diff --git a/README.md b/README.md index ebebc31..9698bfb 100644 --- a/README.md +++ b/README.md @@ -4,7 +4,6 @@ * scout_bringup: launch and configuration files to start ROS nodes * scout_base: a ROS wrapper around Scout SDK to monitor and control the robot -* scout_sdk: Scout SDK customized for ROS * scout_msgs: scout related message definitions * (scout_ros: meta package for the Scout robot ROS packages) diff --git a/readme_zh.md b/readme_zh.md index 9ae64ef..f01c68b 100644 --- a/readme_zh.md +++ b/readme_zh.md @@ -4,13 +4,12 @@ * scout_bringup: launch and configuration files to start ROS nodes * scout_base: a ROS wrapper around Scout SDK to monitor and control the robot -* scout_sdk: Scout SDK customized for ROS * scout_msgs: scout related message definitions * (scout_ros: meta package for the Scout robot ROS packages) 下图是是整个ros package的一个基本框架说明,或许它可以帮助你理解你理解整个ros package内部是如何工作的,他们之间的是相互联系的。 -其中最底层的是移动机器人底盘,它通过can或者usart实现运行在计算平台的sdK进行基本信息的获取,具体可以根据scout_sdk了解更多信息,进而对scout_sdk,仿真部分是基于Webots,构建起的仿真环境。 +其中最底层的是移动机器人底盘,它通过can或者usart实现运行在计算平台的sdk进行基本信息的获取,具体可以根据wrp_sdk了解更多信息。 仿真部分是基于Webots,构建起的仿真环境。 diff --git a/scout_base/CMakeLists.txt b/scout_base/CMakeLists.txt index 8e858e2..c68f608 100644 --- a/scout_base/CMakeLists.txt +++ b/scout_base/CMakeLists.txt @@ -15,7 +15,7 @@ find_package(catkin REQUIRED COMPONENTS std_msgs geometry_msgs scout_msgs - scout_sdk + wrp_sdk tf2 tf2_ros ) @@ -29,7 +29,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_package( INCLUDE_DIRS include LIBRARIES scout_messenger - CATKIN_DEPENDS scout_msgs roscpp sensor_msgs scout_sdk + CATKIN_DEPENDS scout_msgs roscpp sensor_msgs # DEPENDS Boost ) diff --git a/scout_base/include/scout_base/scout_messenger.hpp b/scout_base/include/scout_base/scout_messenger.hpp index aaae791..498e381 100644 --- a/scout_base/include/scout_base/scout_messenger.hpp +++ b/scout_base/include/scout_base/scout_messenger.hpp @@ -18,9 +18,9 @@ #include #include "scout_msgs/ScoutLightCmd.h" -#include "scout_sdk/scout_base.hpp" +#include "wrp_sdk/platforms/scout/scout_base.hpp" -namespace wescore +namespace westonrobot { class ScoutROSMessenger { @@ -68,6 +68,6 @@ private: void LightCmdCallback(const scout_msgs::ScoutLightCmd::ConstPtr &msg); void PublishOdometryToROS(double linear, double angular, double dt); }; -} // namespace wescore +} // namespace westonrobot #endif /* SCOUT_MESSENGER_HPP */ diff --git a/scout_base/package.xml b/scout_base/package.xml index e7a1105..fa76a29 100644 --- a/scout_base/package.xml +++ b/scout_base/package.xml @@ -19,13 +19,13 @@ roslaunch roslint sensor_msgs - scout_sdk + wrp_sdk controller_manager geometry_msgs scout_msgs roscpp sensor_msgs topic_tools - scout_sdk + wrp_sdk diff --git a/scout_base/src/imu_broadcast_node.cpp b/scout_base/src/imu_broadcast_node.cpp deleted file mode 100644 index 93169fa..0000000 --- a/scout_base/src/imu_broadcast_node.cpp +++ /dev/null @@ -1,72 +0,0 @@ -/* - * imu_broadcast_node.cpp - * - * Created on: Oct 02, 2019 19:09 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#include - -#include -#include "lcmtypes/wescore.hpp" - -#include -#include - -ros::Publisher imu_pub; - -struct MessageBroadcaster -{ - void IMULCMCallback(const lcm::ReceiveBuffer *rbuf, const std::string &chan, const wescore_lcm_msgs::IMU *msg) - { - static uint64_t count = 0; - // std::cout << "imu msg received" << std::endl; - sensor_msgs::Imu imu_msg; - imu_msg.header.frame_id = "imu_link"; - imu_msg.header.stamp = ros::Time::now(); - imu_msg.header.seq = count++; - - imu_msg.angular_velocity.x = msg->angular_velocity.x; - imu_msg.angular_velocity.y = msg->angular_velocity.y; - imu_msg.angular_velocity.z = msg->angular_velocity.z; - - imu_msg.linear_acceleration.x = msg->linear_acceleration.x; - imu_msg.linear_acceleration.y = msg->linear_acceleration.y; - imu_msg.linear_acceleration.z = msg->linear_acceleration.z; - - for (int i = 0; i < 9; ++i) - { - imu_msg.orientation_covariance[i] = msg->orientation_covariance[i]; - imu_msg.angular_velocity_covariance[i] = msg->angular_velocity_covariance[i]; - imu_msg.linear_acceleration_covariance[i] = msg->linear_acceleration_covariance[i]; - } - - imu_pub.publish(imu_msg); - } -}; - -int main(int argc, char **argv) -{ - // setup LCM - lcm::LCM lcm; - - if (!lcm.good()) - return 1; - MessageBroadcaster mb; - lcm.subscribe("sensor_hub_raw_imu", &MessageBroadcaster::IMULCMCallback, &mb); - - // setup ROS node - ros::init(argc, argv, "imu_broadcast_node"); - ros::NodeHandle nh; - imu_pub = nh.advertise("imu", 1000); - - ROS_INFO("Started broadcasting"); - while (ros::ok()) - { - lcm.handleTimeout(5); - } - - return 0; -} \ No newline at end of file diff --git a/scout_base/src/scout_base_node.cpp b/scout_base/src/scout_base_node.cpp index a3b7e05..c2cb104 100644 --- a/scout_base/src/scout_base_node.cpp +++ b/scout_base/src/scout_base_node.cpp @@ -5,10 +5,10 @@ #include #include -#include "scout_sdk/scout_base.hpp" +#include "wrp_sdk/platforms/scout/scout_base.hpp" #include "scout_base/scout_messenger.hpp" -using namespace wescore; +using namespace westonrobot; int main(int argc, char **argv) { diff --git a/scout_base/src/scout_messenger.cpp b/scout_base/src/scout_messenger.cpp index 585299b..02870b0 100644 --- a/scout_base/src/scout_messenger.cpp +++ b/scout_base/src/scout_messenger.cpp @@ -13,7 +13,7 @@ #include "scout_msgs/ScoutStatus.h" -namespace wescore +namespace westonrobot { ScoutROSMessenger::ScoutROSMessenger(ros::NodeHandle *nh) : scout_(nullptr), nh_(nh) { @@ -259,4 +259,4 @@ void ScoutROSMessenger::PublishOdometryToROS(double linear, double angular, doub odom_publisher_.publish(odom_msg); } -} // namespace wescore \ No newline at end of file +} // namespace westonrobot \ No newline at end of file diff --git a/scout_sdk/CHANGELOG.md b/scout_sdk/CHANGELOG.md deleted file mode 100644 index 622313a..0000000 --- a/scout_sdk/CHANGELOG.md +++ /dev/null @@ -1,26 +0,0 @@ -# Changelog for scout_sdk - -## 0.4 (2019-09-15) ------------------- -* Unified implementation of UART/CAN for firmware and SDK -* Improvements of code organization -* Contributors: Ruixiang Du - -## 0.3 (2019-08-02) ------------------- -* Added full UART support -* Contributors: Ruixiang Du - -## 0.2 (2019-06-14) ------------------- -* Deprecated initial serial interface support (new one under development) -* Added full CAN support -* Improved multi-threading implementation -* Contributors: Ruixiang Du - -## 0.1 (2019-05-07) ------------------- - -* Added basic serial communication support -* Provided C++ interface, ROS/LCM demo -* Contributors: Ruixiang Du diff --git a/scout_sdk/CMakeLists.txt b/scout_sdk/CMakeLists.txt deleted file mode 100644 index 9074470..0000000 --- a/scout_sdk/CMakeLists.txt +++ /dev/null @@ -1,156 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(scout_sdk) - -## Compile as C++11, supported in ROS Kinetic and newer -add_compile_options(-std=c++11) - -## Find catkin macros and libraries -find_package(catkin REQUIRED COMPONENTS - roscpp - std_msgs -) - -## System dependencies are found with CMake's conventions -# find_package(Boost REQUIRED COMPONENTS system) - -## Uncomment this if the package has a setup.py. This macro ensures -## modules and global scripts declared therein get installed -## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html -# catkin_python_setup() - -################################################ -## Declare ROS messages, services and actions ## -################################################ - -## To declare and build messages, services or actions from within this -## package, follow these steps: -## * Let MSG_DEP_SET be the set of packages whose message types you use in -## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). -## * In the file package.xml: -## * add a build_depend tag for "message_generation" -## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET -## * If MSG_DEP_SET isn't empty the following dependency has been pulled in -## but can be declared for certainty nonetheless: -## * add a exec_depend tag for "message_runtime" -## * In this file (CMakeLists.txt): -## * add "message_generation" and every package in MSG_DEP_SET to -## find_package(catkin REQUIRED COMPONENTS ...) -## * add "message_runtime" and every package in MSG_DEP_SET to -## catkin_package(CATKIN_DEPENDS ...) -## * uncomment the add_*_files sections below as needed -## and list every .msg/.srv/.action file to be processed -## * uncomment the generate_messages entry below -## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) - -## Generate messages in the 'msg' folder -# add_message_files( -# FILES -# Message1.msg -# Message2.msg -# ) - -## Generate services in the 'srv' folder -# add_service_files( -# FILES -# Service1.srv -# Service2.srv -# ) - -## Generate actions in the 'action' folder -# add_action_files( -# FILES -# Action1.action -# Action2.action -# ) - -## Generate added messages and services with any dependencies listed here -# generate_messages( -# DEPENDENCIES -# std_msgs -# ) - -################################################ -## Declare ROS dynamic reconfigure parameters ## -################################################ - -## To declare and build dynamic reconfigure parameters within this -## package, follow these steps: -## * In the file package.xml: -## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" -## * In this file (CMakeLists.txt): -## * add "dynamic_reconfigure" to -## find_package(catkin REQUIRED COMPONENTS ...) -## * uncomment the "generate_dynamic_reconfigure_options" section below -## and list every .cfg file to be processed - -## Generate dynamic reconfigure parameters in the 'cfg' folder -# generate_dynamic_reconfigure_options( -# cfg/DynReconf1.cfg -# cfg/DynReconf2.cfg -# ) - -################################### -## catkin specific configuration ## -################################### -## The catkin_package macro generates cmake config files for your package -## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if your package contains header files -## LIBRARIES: libraries you create in this project that dependent projects also need -## CATKIN_DEPENDS: catkin_packages dependent projects also need -## DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( - INCLUDE_DIRS include - LIBRARIES scout_sdk - CATKIN_DEPENDS roscpp std_msgs -# DEPENDS system_lib -) - -########### -## Build ## -########### - -## Specify additional locations of header files -include_directories( - include - ${catkin_INCLUDE_DIRS} -) - -## Declare a C++ library -set(SCOUT_BASE_SRC - src/scout_base.cpp - src/scout_protocol/scout_can_parser.c - src/scout_protocol/scout_uart_parser.c - src/async_io/async_serial.cpp - src/async_io/async_can.cpp - src/async_io/asyncio_utils.cpp -) -add_library(scout_sdk STATIC ${SCOUT_BASE_SRC}) -set_target_properties(scout_sdk PROPERTIES POSITION_INDEPENDENT_CODE ON) -target_compile_definitions(scout_sdk PUBLIC "-DASIO_ENABLE_OLD_SERVICES -DASIO_HAS_POSIX_STREAM_DESCRIPTOR") -target_link_libraries(scout_sdk pthread ${catkin_LIBRARIES}) -target_include_directories(scout_sdk PUBLIC - $ - $ - $ - PRIVATE src) - -############# -## Install ## -############# - -install(TARGETS scout_sdk - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) - -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) - -install(DIRECTORY asio/asio - DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) - -install(FILES asio/asio.hpp - DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) - -install(DIRECTORY scripts - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) \ No newline at end of file diff --git a/scout_sdk/README.md b/scout_sdk/README.md deleted file mode 100755 index 1e28c5c..0000000 --- a/scout_sdk/README.md +++ /dev/null @@ -1,99 +0,0 @@ -# SDK for AgileX Scout Mobile Base - -Copyright (c) 2019 [WestonRobot](https://www.westonrobot.com/) - -## Introduction - -This software packages provides a C++ interface to communicate with the Scout mobile base, for sending commands to the robot and acquiring the latest robot state. The SDK works on both x86 and ARM platforms. - -Generally, you only need to instantiate an object of "class ScoutBase", then use the object to programmatically control the robot. Internally, class ScoutBase manages two background threads, one to process CAN/UART messages of the robot state and accordingly update state variables in the ScoutState data structure, and the other to maintain a 50Hz loop and send the latest command to the robot base. User can iteratively perform tasks in the main thread and check the robot state or set control commands. - -Refer to "src/apps/scout_demo" for an example. - -## Package Structure - -* apps: demo to illustrate how to use the SDK, scout_monitor is a TUI application to monitor states of Scout -* comm/async_io: manages raw data communication with robot -* comm/scout_protocol: encoding and decoding of Scout UART/CAN protocols -* scout_base: interface to send command to robot and receive robot state -* third_party - - asio: asynchronous IO management (serial and CAN) - - googletest: for unit tests only (not required otherwise) - -## Setup CAN-To-USB adapter - -The instructions work for stm32f0-based adapter with [candleLight](https://github.com/HubertD/candleLight_fw) firmware on a host computer running Linux. (Refer to limitations listed at the bottom for more details.) - -1. Enable gs_usb kernel module - ``` - $ sudo modprobe gs_usb - ``` -2. Bringup can device - ``` - $ sudo ip link set can0 up type can bitrate 500000 - ``` -3. If no error occured during the previous steps, you should be able to see the can device now by using command - ``` - $ ifconfig -a - ``` -4. Install and use can-utils to test the hardware - ``` - $ sudo apt install can-utils - ``` -5. Testing command - ``` - # receiving data from can0 - $ candump can0 - # send data to can0 - $ cansend can0 001#1122334455667788 - ``` - -Two scripts inside the "./scripts" folder are provided for easy setup. You can run "./setup_can2usb.bash" for the first-time setup and run "./bringup_can2usb.bash" to bring up the device each time you unplug and re-plug the adapter. - -## Build SDK - -Install compile tools - -``` -$ sudo apt install build-essential cmake -``` - -If you want to build the TUI monitor tool, install libncurses - -``` -$ sudo apt install libncurses5-dev -``` - -Configure and build - -``` -$ cd scout_sdk -$ mkdir build -$ cd build -$ cmake .. -$ make -``` - -## Known Limitations - -1. The CAN interface requires the hardware to appear as a CAN device in the system. You can use the command "ifconfig" to check the interface status. For example, you may see something like - - ``` - can1: flags=193 mtu 16 - unspec 00-00-00-00-00-00-00-00-00-00-00-00-00-00-00-00 txqueuelen 10 (UNSPEC) - RX packets 4751634 bytes 38013072 (36.2 MiB) - RX errors 0 dropped 0 overruns 0 frame 0 - TX packets 126269 bytes 1010152 (986.4 KiB) - TX errors 0 dropped 0 overruns 0 carrier 0 collisions 0 - device interrupt 43 - ``` - - If you use your own CAN-to-USB adapter, make sure it supports slcan or can be brought up as a native CAN device (for example, CANable https://www.canable.io/). Some adapters may use a custom-defined protocol and appear as a serial device in Linux. In such a case, you will have to translate the byte stream between CAN and UART by yourself. It would be difficult for us to provide support for them since not all manufacturers define this protocol in the same way. - - - -## Reference - -* [CAN command reference in Linux](https://wiki.rdu.im/_pages/Notes/Embedded-System/Linux/can-bus-in-linux.html) \ No newline at end of file diff --git a/scout_sdk/asio/asio.hpp b/scout_sdk/asio/asio.hpp deleted file mode 100644 index 3356df0..0000000 --- a/scout_sdk/asio/asio.hpp +++ /dev/null @@ -1,152 +0,0 @@ -// -// asio.hpp -// ~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_HPP -#define ASIO_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/async_result.hpp" -#include "asio/basic_datagram_socket.hpp" -#include "asio/basic_deadline_timer.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/basic_raw_socket.hpp" -#include "asio/basic_seq_packet_socket.hpp" -#include "asio/basic_serial_port.hpp" -#include "asio/basic_signal_set.hpp" -#include "asio/basic_socket_acceptor.hpp" -#include "asio/basic_socket_iostream.hpp" -#include "asio/basic_socket_streambuf.hpp" -#include "asio/basic_stream_socket.hpp" -#include "asio/basic_streambuf.hpp" -#include "asio/basic_waitable_timer.hpp" -#include "asio/bind_executor.hpp" -#include "asio/buffer.hpp" -#include "asio/buffered_read_stream_fwd.hpp" -#include "asio/buffered_read_stream.hpp" -#include "asio/buffered_stream_fwd.hpp" -#include "asio/buffered_stream.hpp" -#include "asio/buffered_write_stream_fwd.hpp" -#include "asio/buffered_write_stream.hpp" -#include "asio/buffers_iterator.hpp" -#include "asio/completion_condition.hpp" -#include "asio/connect.hpp" -#include "asio/coroutine.hpp" -#include "asio/datagram_socket_service.hpp" -#include "asio/deadline_timer_service.hpp" -#include "asio/deadline_timer.hpp" -#include "asio/defer.hpp" -#include "asio/dispatch.hpp" -#include "asio/error.hpp" -#include "asio/error_code.hpp" -#include "asio/execution_context.hpp" -#include "asio/executor.hpp" -#include "asio/executor_work_guard.hpp" -#include "asio/generic/basic_endpoint.hpp" -#include "asio/generic/datagram_protocol.hpp" -#include "asio/generic/raw_protocol.hpp" -#include "asio/generic/seq_packet_protocol.hpp" -#include "asio/generic/stream_protocol.hpp" -#include "asio/handler_alloc_hook.hpp" -#include "asio/handler_continuation_hook.hpp" -#include "asio/handler_invoke_hook.hpp" -#include "asio/handler_type.hpp" -#include "asio/high_resolution_timer.hpp" -#include "asio/io_context.hpp" -#include "asio/io_context_strand.hpp" -#include "asio/io_service.hpp" -#include "asio/io_service_strand.hpp" -#include "asio/ip/address.hpp" -#include "asio/ip/address_v4.hpp" -#include "asio/ip/address_v4_iterator.hpp" -#include "asio/ip/address_v4_range.hpp" -#include "asio/ip/address_v6.hpp" -#include "asio/ip/address_v6_iterator.hpp" -#include "asio/ip/address_v6_range.hpp" -#include "asio/ip/bad_address_cast.hpp" -#include "asio/ip/basic_endpoint.hpp" -#include "asio/ip/basic_resolver.hpp" -#include "asio/ip/basic_resolver_entry.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" -#include "asio/ip/basic_resolver_query.hpp" -#include "asio/ip/host_name.hpp" -#include "asio/ip/icmp.hpp" -#include "asio/ip/multicast.hpp" -#include "asio/ip/resolver_base.hpp" -#include "asio/ip/resolver_query_base.hpp" -#include "asio/ip/resolver_service.hpp" -#include "asio/ip/tcp.hpp" -#include "asio/ip/udp.hpp" -#include "asio/ip/unicast.hpp" -#include "asio/ip/v6_only.hpp" -#include "asio/is_executor.hpp" -#include "asio/is_read_buffered.hpp" -#include "asio/is_write_buffered.hpp" -#include "asio/local/basic_endpoint.hpp" -#include "asio/local/connect_pair.hpp" -#include "asio/local/datagram_protocol.hpp" -#include "asio/local/stream_protocol.hpp" -#include "asio/packaged_task.hpp" -#include "asio/placeholders.hpp" -#include "asio/posix/basic_descriptor.hpp" -#include "asio/posix/basic_stream_descriptor.hpp" -#include "asio/posix/descriptor.hpp" -#include "asio/posix/descriptor_base.hpp" -#include "asio/posix/stream_descriptor.hpp" -#include "asio/posix/stream_descriptor_service.hpp" -#include "asio/post.hpp" -#include "asio/raw_socket_service.hpp" -#include "asio/read.hpp" -#include "asio/read_at.hpp" -#include "asio/read_until.hpp" -#include "asio/seq_packet_socket_service.hpp" -#include "asio/serial_port.hpp" -#include "asio/serial_port_base.hpp" -#include "asio/serial_port_service.hpp" -#include "asio/signal_set.hpp" -#include "asio/signal_set_service.hpp" -#include "asio/socket_acceptor_service.hpp" -#include "asio/socket_base.hpp" -#include "asio/steady_timer.hpp" -#include "asio/strand.hpp" -#include "asio/stream_socket_service.hpp" -#include "asio/streambuf.hpp" -#include "asio/system_context.hpp" -#include "asio/system_error.hpp" -#include "asio/system_executor.hpp" -#include "asio/system_timer.hpp" -#include "asio/thread.hpp" -#include "asio/thread_pool.hpp" -#include "asio/time_traits.hpp" -#include "asio/use_future.hpp" -#include "asio/uses_executor.hpp" -#include "asio/version.hpp" -#include "asio/wait_traits.hpp" -#include "asio/waitable_timer_service.hpp" -#include "asio/windows/basic_handle.hpp" -#include "asio/windows/basic_object_handle.hpp" -#include "asio/windows/basic_random_access_handle.hpp" -#include "asio/windows/basic_stream_handle.hpp" -#include "asio/windows/object_handle.hpp" -#include "asio/windows/object_handle_service.hpp" -#include "asio/windows/overlapped_handle.hpp" -#include "asio/windows/overlapped_ptr.hpp" -#include "asio/windows/random_access_handle.hpp" -#include "asio/windows/random_access_handle_service.hpp" -#include "asio/windows/stream_handle.hpp" -#include "asio/windows/stream_handle_service.hpp" -#include "asio/write.hpp" -#include "asio/write_at.hpp" - -#endif // ASIO_HPP diff --git a/scout_sdk/asio/asio/associated_allocator.hpp b/scout_sdk/asio/asio/associated_allocator.hpp deleted file mode 100644 index 8b488bb..0000000 --- a/scout_sdk/asio/asio/associated_allocator.hpp +++ /dev/null @@ -1,131 +0,0 @@ -// -// associated_allocator.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_ASSOCIATED_ALLOCATOR_HPP -#define ASIO_ASSOCIATED_ALLOCATOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct associated_allocator_check -{ - typedef void type; -}; - -template -struct associated_allocator_impl -{ - typedef E type; - - static type get(const T&, const E& e) ASIO_NOEXCEPT - { - return e; - } -}; - -template -struct associated_allocator_impl::type> -{ - typedef typename T::allocator_type type; - - static type get(const T& t, const E&) ASIO_NOEXCEPT - { - return t.get_allocator(); - } -}; - -} // namespace detail - -/// Traits type used to obtain the allocator associated with an object. -/** - * A program may specialise this traits type if the @c T template parameter in - * the specialisation is a user-defined type. The template parameter @c - * Allocator shall be a type meeting the Allocator requirements. - * - * Specialisations shall meet the following requirements, where @c t is a const - * reference to an object of type @c T, and @c a is an object of type @c - * Allocator. - * - * @li Provide a nested typedef @c type that identifies a type meeting the - * Allocator requirements. - * - * @li Provide a noexcept static member function named @c get, callable as @c - * get(t) and with return type @c type. - * - * @li Provide a noexcept static member function named @c get, callable as @c - * get(t,a) and with return type @c type. - */ -template > -struct associated_allocator -{ - /// If @c T has a nested type @c allocator_type, T::allocator_type. - /// Otherwise @c Allocator. -#if defined(GENERATING_DOCUMENTATION) - typedef see_below type; -#else // defined(GENERATING_DOCUMENTATION) - typedef typename detail::associated_allocator_impl::type type; -#endif // defined(GENERATING_DOCUMENTATION) - - /// If @c T has a nested type @c allocator_type, returns - /// t.get_allocator(). Otherwise returns @c a. - static type get(const T& t, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return detail::associated_allocator_impl::get(t, a); - } -}; - -/// Helper function to obtain an object's associated allocator. -/** - * @returns associated_allocator::get(t) - */ -template -inline typename associated_allocator::type -get_associated_allocator(const T& t) ASIO_NOEXCEPT -{ - return associated_allocator::get(t); -} - -/// Helper function to obtain an object's associated allocator. -/** - * @returns associated_allocator::get(t, a) - */ -template -inline typename associated_allocator::type -get_associated_allocator(const T& t, const Allocator& a) ASIO_NOEXCEPT -{ - return associated_allocator::get(t, a); -} - -#if defined(ASIO_HAS_ALIAS_TEMPLATES) - -template > -using associated_allocator_t - = typename associated_allocator::type; - -#endif // defined(ASIO_HAS_ALIAS_TEMPLATES) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_ASSOCIATED_ALLOCATOR_HPP diff --git a/scout_sdk/asio/asio/associated_executor.hpp b/scout_sdk/asio/asio/associated_executor.hpp deleted file mode 100644 index 4c5c207..0000000 --- a/scout_sdk/asio/asio/associated_executor.hpp +++ /dev/null @@ -1,149 +0,0 @@ -// -// associated_executor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_ASSOCIATED_EXECUTOR_HPP -#define ASIO_ASSOCIATED_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/is_executor.hpp" -#include "asio/system_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct associated_executor_check -{ - typedef void type; -}; - -template -struct associated_executor_impl -{ - typedef E type; - - static type get(const T&, const E& e) ASIO_NOEXCEPT - { - return e; - } -}; - -template -struct associated_executor_impl::type> -{ - typedef typename T::executor_type type; - - static type get(const T& t, const E&) ASIO_NOEXCEPT - { - return t.get_executor(); - } -}; - -} // namespace detail - -/// Traits type used to obtain the executor associated with an object. -/** - * A program may specialise this traits type if the @c T template parameter in - * the specialisation is a user-defined type. The template parameter @c - * Executor shall be a type meeting the Executor requirements. - * - * Specialisations shall meet the following requirements, where @c t is a const - * reference to an object of type @c T, and @c e is an object of type @c - * Executor. - * - * @li Provide a nested typedef @c type that identifies a type meeting the - * Executor requirements. - * - * @li Provide a noexcept static member function named @c get, callable as @c - * get(t) and with return type @c type. - * - * @li Provide a noexcept static member function named @c get, callable as @c - * get(t,e) and with return type @c type. - */ -template -struct associated_executor -{ - /// If @c T has a nested type @c executor_type, T::executor_type. - /// Otherwise @c Executor. -#if defined(GENERATING_DOCUMENTATION) - typedef see_below type; -#else // defined(GENERATING_DOCUMENTATION) - typedef typename detail::associated_executor_impl::type type; -#endif // defined(GENERATING_DOCUMENTATION) - - /// If @c T has a nested type @c executor_type, returns - /// t.get_executor(). Otherwise returns @c ex. - static type get(const T& t, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return detail::associated_executor_impl::get(t, ex); - } -}; - -/// Helper function to obtain an object's associated executor. -/** - * @returns associated_executor::get(t) - */ -template -inline typename associated_executor::type -get_associated_executor(const T& t) ASIO_NOEXCEPT -{ - return associated_executor::get(t); -} - -/// Helper function to obtain an object's associated executor. -/** - * @returns associated_executor::get(t, ex) - */ -template -inline typename associated_executor::type -get_associated_executor(const T& t, const Executor& ex, - typename enable_if::value>::type* = 0) ASIO_NOEXCEPT -{ - return associated_executor::get(t, ex); -} - -/// Helper function to obtain an object's associated executor. -/** - * @returns associated_executor::get(t, ctx.get_executor()) - */ -template -inline typename associated_executor::type -get_associated_executor(const T& t, ExecutionContext& ctx, - typename enable_if::value>::type* = 0) ASIO_NOEXCEPT -{ - return associated_executor::get(t, ctx.get_executor()); -} - -#if defined(ASIO_HAS_ALIAS_TEMPLATES) - -template -using associated_executor_t = typename associated_executor::type; - -#endif // defined(ASIO_HAS_ALIAS_TEMPLATES) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_ASSOCIATED_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/async_result.hpp b/scout_sdk/asio/asio/async_result.hpp deleted file mode 100644 index 18acdf2..0000000 --- a/scout_sdk/asio/asio/async_result.hpp +++ /dev/null @@ -1,221 +0,0 @@ -// -// async_result.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_ASYNC_RESULT_HPP -#define ASIO_ASYNC_RESULT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/handler_type.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// An interface for customising the behaviour of an initiating function. -/** - * The async_result traits class is used for determining: - * - * @li the concrete completion handler type to be called at the end of the - * asynchronous operation; - * - * @li the initiating function return type; and - * - * @li how the return value of the initiating function is obtained. - * - * The trait allows the handler and return types to be determined at the point - * where the specific completion handler signature is known. - * - * This template may be specialised for user-defined completion token types. - * The primary template assumes that the CompletionToken is the completion - * handler. - */ -#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) -template -#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) -template -#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) -class async_result -{ -public: -#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - /// The concrete completion handler type for the specific signature. - typedef CompletionToken completion_handler_type; - - /// The return type of the initiating function. - typedef void return_type; -#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - // For backward compatibility, determine the concrete completion handler type - // by using the legacy handler_type trait. - typedef typename handler_type::type - completion_handler_type; - - // For backward compatibility, determine the initiating function return type - // using the legacy single-parameter version of async_result. - typedef typename async_result::type return_type; -#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - - /// Construct an async result from a given handler. - /** - * When using a specalised async_result, the constructor has an opportunity - * to initialise some state associated with the completion handler, which is - * then returned from the initiating function. - */ - explicit async_result(completion_handler_type& h) -#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - // No data members to initialise. -#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - : legacy_result_(h) -#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - { - (void)h; - } - - /// Obtain the value to be returned from the initiating function. - return_type get() - { -#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - // Nothing to do. -#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - return legacy_result_.get(); -#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - } - -private: - async_result(const async_result&) ASIO_DELETED; - async_result& operator=(const async_result&) ASIO_DELETED; - -#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - // No data members. -#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - async_result legacy_result_; -#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) -}; - -#if !defined(ASIO_NO_DEPRECATED) - -/// (Deprecated: Use two-parameter version of async_result.) An interface for -/// customising the behaviour of an initiating function. -/** - * This template may be specialised for user-defined handler types. - */ -template -class async_result -{ -public: - /// The return type of the initiating function. - typedef void type; - - /// Construct an async result from a given handler. - /** - * When using a specalised async_result, the constructor has an opportunity - * to initialise some state associated with the handler, which is then - * returned from the initiating function. - */ - explicit async_result(Handler&) - { - } - - /// Obtain the value to be returned from the initiating function. - type get() - { - } -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Helper template to deduce the handler type from a CompletionToken, capture -/// a local copy of the handler, and then create an async_result for the -/// handler. -template -struct async_completion -{ - /// The real handler type to be used for the asynchronous operation. - typedef typename asio::async_result< - typename decay::type, - Signature>::completion_handler_type completion_handler_type; - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Constructor. - /** - * The constructor creates the concrete completion handler and makes the link - * between the handler and the asynchronous result. - */ - explicit async_completion(CompletionToken& token) - : completion_handler(static_cast::value, - completion_handler_type&, CompletionToken&&>::type>(token)), - result(completion_handler) - { - } -#else // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - explicit async_completion(typename decay::type& token) - : completion_handler(token), - result(completion_handler) - { - } - - explicit async_completion(const typename decay::type& token) - : completion_handler(token), - result(completion_handler) - { - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// A copy of, or reference to, a real handler object. -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - typename conditional< - is_same::value, - completion_handler_type&, completion_handler_type>::type completion_handler; -#else // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - completion_handler_type completion_handler; -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// The result of the asynchronous operation's initiating function. - async_result::type, Signature> result; -}; - -namespace detail { - -template -struct async_result_helper - : async_result::type, Signature> -{ -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(GENERATING_DOCUMENTATION) -# define ASIO_INITFN_RESULT_TYPE(ct, sig) \ - void_or_deduced -#elif defined(_MSC_VER) && (_MSC_VER < 1500) -# define ASIO_INITFN_RESULT_TYPE(ct, sig) \ - typename ::asio::detail::async_result_helper< \ - ct, sig>::return_type -#define ASIO_HANDLER_TYPE(ct, sig) \ - typename ::asio::detail::async_result_helper< \ - ct, sig>::completion_handler_type -#else -# define ASIO_INITFN_RESULT_TYPE(ct, sig) \ - typename ::asio::async_result< \ - typename ::asio::decay::type, sig>::return_type -#define ASIO_HANDLER_TYPE(ct, sig) \ - typename ::asio::async_result< \ - typename ::asio::decay::type, sig>::completion_handler_type -#endif - -#endif // ASIO_ASYNC_RESULT_HPP diff --git a/scout_sdk/asio/asio/basic_datagram_socket.hpp b/scout_sdk/asio/asio/basic_datagram_socket.hpp deleted file mode 100644 index 346cc35..0000000 --- a/scout_sdk/asio/asio/basic_datagram_socket.hpp +++ /dev/null @@ -1,1040 +0,0 @@ -// -// basic_datagram_socket.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_DATAGRAM_SOCKET_HPP -#define ASIO_BASIC_DATAGRAM_SOCKET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/basic_socket.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/datagram_socket_service.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides datagram-oriented socket functionality. -/** - * The basic_datagram_socket class template provides asynchronous and blocking - * datagram-oriented socket functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template )> -class basic_datagram_socket - : public basic_socket -{ -public: - /// The native representation of a socket. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename basic_socket< - Protocol ASIO_SVC_TARG>::native_handle_type native_handle_type; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - /// Construct a basic_datagram_socket without opening it. - /** - * This constructor creates a datagram socket without opening it. The open() - * function must be called before data can be sent or received on the socket. - * - * @param io_context The io_context object that the datagram socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - */ - explicit basic_datagram_socket(asio::io_context& io_context) - : basic_socket(io_context) - { - } - - /// Construct and open a basic_datagram_socket. - /** - * This constructor creates and opens a datagram socket. - * - * @param io_context The io_context object that the datagram socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @throws asio::system_error Thrown on failure. - */ - basic_datagram_socket(asio::io_context& io_context, - const protocol_type& protocol) - : basic_socket(io_context, protocol) - { - } - - /// Construct a basic_datagram_socket, opening it and binding it to the given - /// local endpoint. - /** - * This constructor creates a datagram socket and automatically opens it bound - * to the specified endpoint on the local machine. The protocol used is the - * protocol associated with the given endpoint. - * - * @param io_context The io_context object that the datagram socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - * - * @param endpoint An endpoint on the local machine to which the datagram - * socket will be bound. - * - * @throws asio::system_error Thrown on failure. - */ - basic_datagram_socket(asio::io_context& io_context, - const endpoint_type& endpoint) - : basic_socket(io_context, endpoint) - { - } - - /// Construct a basic_datagram_socket on an existing native socket. - /** - * This constructor creates a datagram socket object to hold an existing - * native socket. - * - * @param io_context The io_context object that the datagram socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @param native_socket The new underlying socket implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_datagram_socket(asio::io_context& io_context, - const protocol_type& protocol, const native_handle_type& native_socket) - : basic_socket( - io_context, protocol, native_socket) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_datagram_socket from another. - /** - * This constructor moves a datagram socket from one object to another. - * - * @param other The other basic_datagram_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_datagram_socket(io_context&) constructor. - */ - basic_datagram_socket(basic_datagram_socket&& other) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_datagram_socket from another. - /** - * This assignment operator moves a datagram socket from one object to - * another. - * - * @param other The other basic_datagram_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_datagram_socket(io_context&) constructor. - */ - basic_datagram_socket& operator=(basic_datagram_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } - - /// Move-construct a basic_datagram_socket from a socket of another protocol - /// type. - /** - * This constructor moves a datagram socket from one object to another. - * - * @param other The other basic_datagram_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_datagram_socket(io_context&) constructor. - */ - template - basic_datagram_socket( - basic_datagram_socket&& other, - typename enable_if::value>::type* = 0) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_datagram_socket from a socket of another protocol - /// type. - /** - * This assignment operator moves a datagram socket from one object to - * another. - * - * @param other The other basic_datagram_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_datagram_socket(io_context&) constructor. - */ - template - typename enable_if::value, - basic_datagram_socket>::type& operator=( - basic_datagram_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the socket. - /** - * This function destroys the socket, cancelling any outstanding asynchronous - * operations associated with the socket as if by calling @c cancel. - */ - ~basic_datagram_socket() - { - } - - /// Send some data on a connected socket. - /** - * This function is used to send data on the datagram socket. The function - * call will block until the data has been sent successfully or an error - * occurs. - * - * @param buffers One ore more data buffers to be sent on the socket. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @note The send operation can only be used with a connected socket. Use - * the send_to function to send data on an unconnected datagram socket. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code socket.send(asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t send(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "send"); - return s; - } - - /// Send some data on a connected socket. - /** - * This function is used to send data on the datagram socket. The function - * call will block until the data has been sent successfully or an error - * occurs. - * - * @param buffers One ore more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @note The send operation can only be used with a connected socket. Use - * the send_to function to send data on an unconnected datagram socket. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, flags, ec); - asio::detail::throw_error(ec, "send"); - return s; - } - - /// Send some data on a connected socket. - /** - * This function is used to send data on the datagram socket. The function - * call will block until the data has been sent successfully or an error - * occurs. - * - * @param buffers One or more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes sent. - * - * @note The send operation can only be used with a connected socket. Use - * the send_to function to send data on an unconnected datagram socket. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return this->get_service().send( - this->get_implementation(), buffers, flags, ec); - } - - /// Start an asynchronous send on a connected socket. - /** - * This function is used to asynchronously send data on the datagram socket. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent on the socket. Although - * the buffers object may be copied as necessary, ownership of the underlying - * memory blocks is retained by the caller, which must guarantee that they - * remain valid until the handler is called. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_send operation can only be used with a connected socket. - * Use the async_send_to function to send data on an unconnected datagram - * socket. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.async_send(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send(this->get_implementation(), - buffers, 0, ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send(this->get_implementation(), - buffers, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous send on a connected socket. - /** - * This function is used to asynchronously send data on the datagram socket. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent on the socket. Although - * the buffers object may be copied as necessary, ownership of the underlying - * memory blocks is retained by the caller, which must guarantee that they - * remain valid until the handler is called. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_send operation can only be used with a connected socket. - * Use the async_send_to function to send data on an unconnected datagram - * socket. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send(this->get_implementation(), - buffers, flags, ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send(this->get_implementation(), - buffers, flags, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Send a datagram to the specified endpoint. - /** - * This function is used to send a datagram to the specified remote endpoint. - * The function call will block until the data has been sent successfully or - * an error occurs. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * - * @param destination The remote endpoint to which the data will be sent. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * asio::ip::udp::endpoint destination( - * asio::ip::address::from_string("1.2.3.4"), 12345); - * socket.send_to(asio::buffer(data, size), destination); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination) - { - asio::error_code ec; - std::size_t s = this->get_service().send_to( - this->get_implementation(), buffers, destination, 0, ec); - asio::detail::throw_error(ec, "send_to"); - return s; - } - - /// Send a datagram to the specified endpoint. - /** - * This function is used to send a datagram to the specified remote endpoint. - * The function call will block until the data has been sent successfully or - * an error occurs. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * - * @param destination The remote endpoint to which the data will be sent. - * - * @param flags Flags specifying how the send call is to be made. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - */ - template - std::size_t send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().send_to( - this->get_implementation(), buffers, destination, flags, ec); - asio::detail::throw_error(ec, "send_to"); - return s; - } - - /// Send a datagram to the specified endpoint. - /** - * This function is used to send a datagram to the specified remote endpoint. - * The function call will block until the data has been sent successfully or - * an error occurs. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * - * @param destination The remote endpoint to which the data will be sent. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes sent. - */ - template - std::size_t send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags, - asio::error_code& ec) - { - return this->get_service().send_to(this->get_implementation(), - buffers, destination, flags, ec); - } - - /// Start an asynchronous send. - /** - * This function is used to asynchronously send a datagram to the specified - * remote endpoint. The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param destination The remote endpoint to which the data will be sent. - * Copies will be made of the endpoint as required. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * asio::ip::udp::endpoint destination( - * asio::ip::address::from_string("1.2.3.4"), 12345); - * socket.async_send_to( - * asio::buffer(data, size), destination, handler); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send_to( - this->get_implementation(), buffers, destination, 0, - ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send_to( - this->get_implementation(), buffers, destination, 0, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous send. - /** - * This function is used to asynchronously send a datagram to the specified - * remote endpoint. The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param destination The remote endpoint to which the data will be sent. - * Copies will be made of the endpoint as required. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send_to( - this->get_implementation(), buffers, destination, flags, - ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send_to( - this->get_implementation(), buffers, destination, flags, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the datagram socket. The function - * call will block until data has been received successfully or an error - * occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - * - * @note The receive operation can only be used with a connected socket. Use - * the receive_from function to receive data on an unconnected datagram - * socket. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code socket.receive(asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the datagram socket. The function - * call will block until data has been received successfully or an error - * occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - * - * @note The receive operation can only be used with a connected socket. Use - * the receive_from function to receive data on an unconnected datagram - * socket. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, flags, ec); - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the datagram socket. The function - * call will block until data has been received successfully or an error - * occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes received. - * - * @note The receive operation can only be used with a connected socket. Use - * the receive_from function to receive data on an unconnected datagram - * socket. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return this->get_service().receive( - this->get_implementation(), buffers, flags, ec); - } - - /// Start an asynchronous receive on a connected socket. - /** - * This function is used to asynchronously receive data from the datagram - * socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_receive operation can only be used with a connected socket. - * Use the async_receive_from function to receive data on an unconnected - * datagram socket. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.async_receive(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive(this->get_implementation(), - buffers, 0, ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive(this->get_implementation(), - buffers, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous receive on a connected socket. - /** - * This function is used to asynchronously receive data from the datagram - * socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_receive operation can only be used with a connected socket. - * Use the async_receive_from function to receive data on an unconnected - * datagram socket. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive(this->get_implementation(), - buffers, flags, ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive(this->get_implementation(), - buffers, flags, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Receive a datagram with the endpoint of the sender. - /** - * This function is used to receive a datagram. The function call will block - * until data has been received successfully or an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the datagram. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * asio::ip::udp::endpoint sender_endpoint; - * socket.receive_from( - * asio::buffer(data, size), sender_endpoint); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint) - { - asio::error_code ec; - std::size_t s = this->get_service().receive_from( - this->get_implementation(), buffers, sender_endpoint, 0, ec); - asio::detail::throw_error(ec, "receive_from"); - return s; - } - - /// Receive a datagram with the endpoint of the sender. - /** - * This function is used to receive a datagram. The function call will block - * until data has been received successfully or an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the datagram. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - */ - template - std::size_t receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().receive_from( - this->get_implementation(), buffers, sender_endpoint, flags, ec); - asio::detail::throw_error(ec, "receive_from"); - return s; - } - - /// Receive a datagram with the endpoint of the sender. - /** - * This function is used to receive a datagram. The function call will block - * until data has been received successfully or an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the datagram. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes received. - */ - template - std::size_t receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags, - asio::error_code& ec) - { - return this->get_service().receive_from(this->get_implementation(), - buffers, sender_endpoint, flags, ec); - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive a datagram. The function - * call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the datagram. Ownership of the sender_endpoint object - * is retained by the caller, which must guarantee that it is valid until the - * handler is called. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code socket.async_receive_from( - * asio::buffer(data, size), sender_endpoint, handler); @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, 0, - ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, 0, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive a datagram. The function - * call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the datagram. Ownership of the sender_endpoint object - * is retained by the caller, which must guarantee that it is valid until the - * handler is called. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, flags, - ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, flags, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BASIC_DATAGRAM_SOCKET_HPP diff --git a/scout_sdk/asio/asio/basic_deadline_timer.hpp b/scout_sdk/asio/asio/basic_deadline_timer.hpp deleted file mode 100644 index 5b20066..0000000 --- a/scout_sdk/asio/asio/basic_deadline_timer.hpp +++ /dev/null @@ -1,628 +0,0 @@ -// -// basic_deadline_timer.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_DEADLINE_TIMER_HPP -#define ASIO_BASIC_DEADLINE_TIMER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/time_traits.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/deadline_timer_service.hpp" -#else // defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/detail/deadline_timer_service.hpp" -# define ASIO_SVC_T detail::deadline_timer_service -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides waitable timer functionality. -/** - * The basic_deadline_timer class template provides the ability to perform a - * blocking or asynchronous wait for a timer to expire. - * - * A deadline timer is always in one of two states: "expired" or "not expired". - * If the wait() or async_wait() function is called on an expired timer, the - * wait operation will complete immediately. - * - * Most applications will use the asio::deadline_timer typedef. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Examples - * Performing a blocking wait: - * @code - * // Construct a timer without setting an expiry time. - * asio::deadline_timer timer(io_context); - * - * // Set an expiry time relative to now. - * timer.expires_from_now(boost::posix_time::seconds(5)); - * - * // Wait for the timer to expire. - * timer.wait(); - * @endcode - * - * @par - * Performing an asynchronous wait: - * @code - * void handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Timer expired. - * } - * } - * - * ... - * - * // Construct a timer with an absolute expiry time. - * asio::deadline_timer timer(io_context, - * boost::posix_time::time_from_string("2005-12-07 23:59:59.000")); - * - * // Start an asynchronous wait. - * timer.async_wait(handler); - * @endcode - * - * @par Changing an active deadline_timer's expiry time - * - * Changing the expiry time of a timer while there are pending asynchronous - * waits causes those wait operations to be cancelled. To ensure that the action - * associated with the timer is performed only once, use something like this: - * used: - * - * @code - * void on_some_event() - * { - * if (my_timer.expires_from_now(seconds(5)) > 0) - * { - * // We managed to cancel the timer. Start new asynchronous wait. - * my_timer.async_wait(on_timeout); - * } - * else - * { - * // Too late, timer has already expired! - * } - * } - * - * void on_timeout(const asio::error_code& e) - * { - * if (e != asio::error::operation_aborted) - * { - * // Timer was not cancelled, take necessary action. - * } - * } - * @endcode - * - * @li The asio::basic_deadline_timer::expires_from_now() function - * cancels any pending asynchronous waits, and returns the number of - * asynchronous waits that were cancelled. If it returns 0 then you were too - * late and the wait handler has already been executed, or will soon be - * executed. If it returns 1 then the wait handler was successfully cancelled. - * - * @li If a wait handler is cancelled, the asio::error_code passed to - * it contains the value asio::error::operation_aborted. - */ -template - ASIO_SVC_TPARAM_DEF2(= deadline_timer_service)> -class basic_deadline_timer - : ASIO_SVC_ACCESS basic_io_object -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The time traits type. - typedef TimeTraits traits_type; - - /// The time type. - typedef typename traits_type::time_type time_type; - - /// The duration type. - typedef typename traits_type::duration_type duration_type; - - /// Constructor. - /** - * This constructor creates a timer without setting an expiry time. The - * expires_at() or expires_from_now() functions must be called to set an - * expiry time before the timer can be waited on. - * - * @param io_context The io_context object that the timer will use to dispatch - * handlers for any asynchronous operations performed on the timer. - */ - explicit basic_deadline_timer(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Constructor to set a particular expiry time as an absolute time. - /** - * This constructor creates a timer and sets the expiry time. - * - * @param io_context The io_context object that the timer will use to dispatch - * handlers for any asynchronous operations performed on the timer. - * - * @param expiry_time The expiry time to be used for the timer, expressed - * as an absolute time. - */ - basic_deadline_timer(asio::io_context& io_context, - const time_type& expiry_time) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().expires_at(this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_at"); - } - - /// Constructor to set a particular expiry time relative to now. - /** - * This constructor creates a timer and sets the expiry time. - * - * @param io_context The io_context object that the timer will use to dispatch - * handlers for any asynchronous operations performed on the timer. - * - * @param expiry_time The expiry time to be used for the timer, relative to - * now. - */ - basic_deadline_timer(asio::io_context& io_context, - const duration_type& expiry_time) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().expires_from_now( - this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_from_now"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_deadline_timer from another. - /** - * This constructor moves a timer from one object to another. - * - * @param other The other basic_deadline_timer object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_deadline_timer(io_context&) constructor. - */ - basic_deadline_timer(basic_deadline_timer&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign a basic_deadline_timer from another. - /** - * This assignment operator moves a timer from one object to another. Cancels - * any outstanding asynchronous operations associated with the target object. - * - * @param other The other basic_deadline_timer object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_deadline_timer(io_context&) constructor. - */ - basic_deadline_timer& operator=(basic_deadline_timer&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the timer. - /** - * This function destroys the timer, cancelling any outstanding asynchronous - * wait operations associated with the timer as if by calling @c cancel. - */ - ~basic_deadline_timer() - { - } - -#if defined(ASIO_ENABLE_OLD_SERVICES) - // These functions are provided by basic_io_object<>. -#else // defined(ASIO_ENABLE_OLD_SERVICES) -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - - /// Cancel any asynchronous operations that are waiting on the timer. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the timer. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @return The number of asynchronous operations that were cancelled. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel() - { - asio::error_code ec; - std::size_t s = this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - return s; - } - - /// Cancel any asynchronous operations that are waiting on the timer. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the timer. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. - * - * @note If the timer has already expired when cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel(asio::error_code& ec) - { - return this->get_service().cancel(this->get_implementation(), ec); - } - - /// Cancels one asynchronous operation that is waiting on the timer. - /** - * This function forces the completion of one pending asynchronous wait - * operation against the timer. Handlers are cancelled in FIFO order. The - * handler for the cancelled operation will be invoked with the - * asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @return The number of asynchronous operations that were cancelled. That is, - * either 0 or 1. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when cancel_one() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel_one() - { - asio::error_code ec; - std::size_t s = this->get_service().cancel_one( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel_one"); - return s; - } - - /// Cancels one asynchronous operation that is waiting on the timer. - /** - * This function forces the completion of one pending asynchronous wait - * operation against the timer. Handlers are cancelled in FIFO order. The - * handler for the cancelled operation will be invoked with the - * asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. That is, - * either 0 or 1. - * - * @note If the timer has already expired when cancel_one() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel_one(asio::error_code& ec) - { - return this->get_service().cancel_one(this->get_implementation(), ec); - } - - /// Get the timer's expiry time as an absolute time. - /** - * This function may be used to obtain the timer's current expiry time. - * Whether the timer has expired or not does not affect this value. - */ - time_type expires_at() const - { - return this->get_service().expires_at(this->get_implementation()); - } - - /// Set the timer's expiry time as an absolute time. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @return The number of asynchronous operations that were cancelled. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when expires_at() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_at(const time_type& expiry_time) - { - asio::error_code ec; - std::size_t s = this->get_service().expires_at( - this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_at"); - return s; - } - - /// Set the timer's expiry time as an absolute time. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. - * - * @note If the timer has already expired when expires_at() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_at(const time_type& expiry_time, - asio::error_code& ec) - { - return this->get_service().expires_at( - this->get_implementation(), expiry_time, ec); - } - - /// Get the timer's expiry time relative to now. - /** - * This function may be used to obtain the timer's current expiry time. - * Whether the timer has expired or not does not affect this value. - */ - duration_type expires_from_now() const - { - return this->get_service().expires_from_now(this->get_implementation()); - } - - /// Set the timer's expiry time relative to now. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @return The number of asynchronous operations that were cancelled. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when expires_from_now() is called, - * then the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_from_now(const duration_type& expiry_time) - { - asio::error_code ec; - std::size_t s = this->get_service().expires_from_now( - this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_from_now"); - return s; - } - - /// Set the timer's expiry time relative to now. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. - * - * @note If the timer has already expired when expires_from_now() is called, - * then the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_from_now(const duration_type& expiry_time, - asio::error_code& ec) - { - return this->get_service().expires_from_now( - this->get_implementation(), expiry_time, ec); - } - - /// Perform a blocking wait on the timer. - /** - * This function is used to wait for the timer to expire. This function - * blocks and does not return until the timer has expired. - * - * @throws asio::system_error Thrown on failure. - */ - void wait() - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Perform a blocking wait on the timer. - /** - * This function is used to wait for the timer to expire. This function - * blocks and does not return until the timer has expired. - * - * @param ec Set to indicate what error occurred, if any. - */ - void wait(asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), ec); - } - - /// Start an asynchronous wait on the timer. - /** - * This function may be used to initiate an asynchronous wait against the - * timer. It always returns immediately. - * - * For each call to async_wait(), the supplied handler will be called exactly - * once. The handler will be called when: - * - * @li The timer has expired. - * - * @li The timer was cancelled, in which case the handler is passed the error - * code asio::error::operation_aborted. - * - * @param handler The handler to be called when the timer expires. Copies - * will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(ASIO_MOVE_ARG(WaitHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WaitHandler. - ASIO_WAIT_HANDLER_CHECK(WaitHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_wait(this->get_implementation(), - ASIO_MOVE_CAST(WaitHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_wait(this->get_implementation(), - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# undef ASIO_SVC_T -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_BASIC_DEADLINE_TIMER_HPP diff --git a/scout_sdk/asio/asio/basic_io_object.hpp b/scout_sdk/asio/asio/basic_io_object.hpp deleted file mode 100644 index 442e854..0000000 --- a/scout_sdk/asio/asio/basic_io_object.hpp +++ /dev/null @@ -1,290 +0,0 @@ -// -// basic_io_object.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_IO_OBJECT_HPP -#define ASIO_BASIC_IO_OBJECT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if defined(ASIO_HAS_MOVE) -namespace detail -{ - // Type trait used to determine whether a service supports move. - template - class service_has_move - { - private: - typedef IoObjectService service_type; - typedef typename service_type::implementation_type implementation_type; - - template - static auto asio_service_has_move_eval(T* t, U* u) - -> decltype(t->move_construct(*u, *u), char()); - static char (&asio_service_has_move_eval(...))[2]; - - public: - static const bool value = - sizeof(asio_service_has_move_eval( - static_cast(0), - static_cast(0))) == 1; - }; -} -#endif // defined(ASIO_HAS_MOVE) - -/// Base class for all I/O objects. -/** - * @note All I/O objects are non-copyable. However, when using C++0x, certain - * I/O objects do support move construction and move assignment. - */ -#if !defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) -template -#else -template ::value> -#endif -class basic_io_object -{ -public: - /// The type of the service that will be used to provide I/O operations. - typedef IoObjectService service_type; - - /// The underlying implementation type of I/O object. - typedef typename service_type::implementation_type implementation_type; - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return service_.get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return service_.get_io_context(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// The type of the executor associated with the object. - typedef asio::io_context::executor_type executor_type; - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return service_.get_io_context().get_executor(); - } - -protected: - /// Construct a basic_io_object. - /** - * Performs: - * @code get_service().construct(get_implementation()); @endcode - */ - explicit basic_io_object(asio::io_context& io_context) - : service_(asio::use_service(io_context)) - { - service_.construct(implementation_); - } - -#if defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_io_object. - /** - * Performs: - * @code get_service().move_construct( - * get_implementation(), other.get_implementation()); @endcode - * - * @note Available only for services that support movability, - */ - basic_io_object(basic_io_object&& other); - - /// Move-assign a basic_io_object. - /** - * Performs: - * @code get_service().move_assign(get_implementation(), - * other.get_service(), other.get_implementation()); @endcode - * - * @note Available only for services that support movability, - */ - basic_io_object& operator=(basic_io_object&& other); - - /// Perform a converting move-construction of a basic_io_object. - template - basic_io_object(IoObjectService1& other_service, - typename IoObjectService1::implementation_type& other_implementation); -#endif // defined(GENERATING_DOCUMENTATION) - - /// Protected destructor to prevent deletion through this type. - /** - * Performs: - * @code get_service().destroy(get_implementation()); @endcode - */ - ~basic_io_object() - { - service_.destroy(implementation_); - } - - /// Get the service associated with the I/O object. - service_type& get_service() - { - return service_; - } - - /// Get the service associated with the I/O object. - const service_type& get_service() const - { - return service_; - } - - /// Get the underlying implementation of the I/O object. - implementation_type& get_implementation() - { - return implementation_; - } - - /// Get the underlying implementation of the I/O object. - const implementation_type& get_implementation() const - { - return implementation_; - } - -private: - basic_io_object(const basic_io_object&); - basic_io_object& operator=(const basic_io_object&); - - // The service associated with the I/O object. - service_type& service_; - - /// The underlying implementation of the I/O object. - implementation_type implementation_; -}; - -#if defined(ASIO_HAS_MOVE) -// Specialisation for movable objects. -template -class basic_io_object -{ -public: - typedef IoObjectService service_type; - typedef typename service_type::implementation_type implementation_type; - -#if !defined(ASIO_NO_DEPRECATED) - asio::io_context& get_io_context() - { - return service_->get_io_context(); - } - - asio::io_context& get_io_service() - { - return service_->get_io_context(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - typedef asio::io_context::executor_type executor_type; - - executor_type get_executor() ASIO_NOEXCEPT - { - return service_->get_io_context().get_executor(); - } - -protected: - explicit basic_io_object(asio::io_context& io_context) - : service_(&asio::use_service(io_context)) - { - service_->construct(implementation_); - } - - basic_io_object(basic_io_object&& other) - : service_(&other.get_service()) - { - service_->move_construct(implementation_, other.implementation_); - } - - template - basic_io_object(IoObjectService1& other_service, - typename IoObjectService1::implementation_type& other_implementation) - : service_(&asio::use_service( - other_service.get_io_context())) - { - service_->converting_move_construct(implementation_, - other_service, other_implementation); - } - - ~basic_io_object() - { - service_->destroy(implementation_); - } - - basic_io_object& operator=(basic_io_object&& other) - { - service_->move_assign(implementation_, - *other.service_, other.implementation_); - service_ = other.service_; - return *this; - } - - service_type& get_service() - { - return *service_; - } - - const service_type& get_service() const - { - return *service_; - } - - implementation_type& get_implementation() - { - return implementation_; - } - - const implementation_type& get_implementation() const - { - return implementation_; - } - -private: - basic_io_object(const basic_io_object&); - void operator=(const basic_io_object&); - - IoObjectService* service_; - implementation_type implementation_; -}; -#endif // defined(ASIO_HAS_MOVE) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BASIC_IO_OBJECT_HPP diff --git a/scout_sdk/asio/asio/basic_raw_socket.hpp b/scout_sdk/asio/asio/basic_raw_socket.hpp deleted file mode 100644 index 0de7c77..0000000 --- a/scout_sdk/asio/asio/basic_raw_socket.hpp +++ /dev/null @@ -1,1030 +0,0 @@ -// -// basic_raw_socket.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_RAW_SOCKET_HPP -#define ASIO_BASIC_RAW_SOCKET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/basic_socket.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/raw_socket_service.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides raw-oriented socket functionality. -/** - * The basic_raw_socket class template provides asynchronous and blocking - * raw-oriented socket functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template )> -class basic_raw_socket - : public basic_socket -{ -public: - /// The native representation of a socket. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename basic_socket< - Protocol ASIO_SVC_TARG>::native_handle_type native_handle_type; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - /// Construct a basic_raw_socket without opening it. - /** - * This constructor creates a raw socket without opening it. The open() - * function must be called before data can be sent or received on the socket. - * - * @param io_context The io_context object that the raw socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - */ - explicit basic_raw_socket(asio::io_context& io_context) - : basic_socket(io_context) - { - } - - /// Construct and open a basic_raw_socket. - /** - * This constructor creates and opens a raw socket. - * - * @param io_context The io_context object that the raw socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @throws asio::system_error Thrown on failure. - */ - basic_raw_socket(asio::io_context& io_context, - const protocol_type& protocol) - : basic_socket(io_context, protocol) - { - } - - /// Construct a basic_raw_socket, opening it and binding it to the given - /// local endpoint. - /** - * This constructor creates a raw socket and automatically opens it bound - * to the specified endpoint on the local machine. The protocol used is the - * protocol associated with the given endpoint. - * - * @param io_context The io_context object that the raw socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - * - * @param endpoint An endpoint on the local machine to which the raw - * socket will be bound. - * - * @throws asio::system_error Thrown on failure. - */ - basic_raw_socket(asio::io_context& io_context, - const endpoint_type& endpoint) - : basic_socket(io_context, endpoint) - { - } - - /// Construct a basic_raw_socket on an existing native socket. - /** - * This constructor creates a raw socket object to hold an existing - * native socket. - * - * @param io_context The io_context object that the raw socket will use - * to dispatch handlers for any asynchronous operations performed on the - * socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @param native_socket The new underlying socket implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_raw_socket(asio::io_context& io_context, - const protocol_type& protocol, const native_handle_type& native_socket) - : basic_socket( - io_context, protocol, native_socket) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_raw_socket from another. - /** - * This constructor moves a raw socket from one object to another. - * - * @param other The other basic_raw_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_raw_socket(io_context&) constructor. - */ - basic_raw_socket(basic_raw_socket&& other) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_raw_socket from another. - /** - * This assignment operator moves a raw socket from one object to another. - * - * @param other The other basic_raw_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_raw_socket(io_context&) constructor. - */ - basic_raw_socket& operator=(basic_raw_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } - - /// Move-construct a basic_raw_socket from a socket of another protocol type. - /** - * This constructor moves a raw socket from one object to another. - * - * @param other The other basic_raw_socket object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_raw_socket(io_context&) constructor. - */ - template - basic_raw_socket(basic_raw_socket&& other, - typename enable_if::value>::type* = 0) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_raw_socket from a socket of another protocol type. - /** - * This assignment operator moves a raw socket from one object to another. - * - * @param other The other basic_raw_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_raw_socket(io_context&) constructor. - */ - template - typename enable_if::value, - basic_raw_socket>::type& operator=( - basic_raw_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the socket. - /** - * This function destroys the socket, cancelling any outstanding asynchronous - * operations associated with the socket as if by calling @c cancel. - */ - ~basic_raw_socket() - { - } - - /// Send some data on a connected socket. - /** - * This function is used to send data on the raw socket. The function call - * will block until the data has been sent successfully or an error occurs. - * - * @param buffers One ore more data buffers to be sent on the socket. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @note The send operation can only be used with a connected socket. Use - * the send_to function to send data on an unconnected raw socket. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code socket.send(asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t send(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "send"); - return s; - } - - /// Send some data on a connected socket. - /** - * This function is used to send data on the raw socket. The function call - * will block until the data has been sent successfully or an error occurs. - * - * @param buffers One ore more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @note The send operation can only be used with a connected socket. Use - * the send_to function to send data on an unconnected raw socket. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, flags, ec); - asio::detail::throw_error(ec, "send"); - return s; - } - - /// Send some data on a connected socket. - /** - * This function is used to send data on the raw socket. The function call - * will block until the data has been sent successfully or an error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes sent. - * - * @note The send operation can only be used with a connected socket. Use - * the send_to function to send data on an unconnected raw socket. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return this->get_service().send( - this->get_implementation(), buffers, flags, ec); - } - - /// Start an asynchronous send on a connected socket. - /** - * This function is used to send data on the raw socket. The function call - * will block until the data has been sent successfully or an error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. Although - * the buffers object may be copied as necessary, ownership of the underlying - * memory blocks is retained by the caller, which must guarantee that they - * remain valid until the handler is called. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_send operation can only be used with a connected socket. - * Use the async_send_to function to send data on an unconnected raw - * socket. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.async_send(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send(this->get_implementation(), - buffers, 0, ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send(this->get_implementation(), - buffers, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous send on a connected socket. - /** - * This function is used to send data on the raw socket. The function call - * will block until the data has been sent successfully or an error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. Although - * the buffers object may be copied as necessary, ownership of the underlying - * memory blocks is retained by the caller, which must guarantee that they - * remain valid until the handler is called. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_send operation can only be used with a connected socket. - * Use the async_send_to function to send data on an unconnected raw - * socket. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send(this->get_implementation(), - buffers, flags, ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send(this->get_implementation(), - buffers, flags, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Send raw data to the specified endpoint. - /** - * This function is used to send raw data to the specified remote endpoint. - * The function call will block until the data has been sent successfully or - * an error occurs. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * - * @param destination The remote endpoint to which the data will be sent. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * asio::ip::udp::endpoint destination( - * asio::ip::address::from_string("1.2.3.4"), 12345); - * socket.send_to(asio::buffer(data, size), destination); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination) - { - asio::error_code ec; - std::size_t s = this->get_service().send_to( - this->get_implementation(), buffers, destination, 0, ec); - asio::detail::throw_error(ec, "send_to"); - return s; - } - - /// Send raw data to the specified endpoint. - /** - * This function is used to send raw data to the specified remote endpoint. - * The function call will block until the data has been sent successfully or - * an error occurs. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * - * @param destination The remote endpoint to which the data will be sent. - * - * @param flags Flags specifying how the send call is to be made. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - */ - template - std::size_t send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().send_to( - this->get_implementation(), buffers, destination, flags, ec); - asio::detail::throw_error(ec, "send_to"); - return s; - } - - /// Send raw data to the specified endpoint. - /** - * This function is used to send raw data to the specified remote endpoint. - * The function call will block until the data has been sent successfully or - * an error occurs. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * - * @param destination The remote endpoint to which the data will be sent. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes sent. - */ - template - std::size_t send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags, - asio::error_code& ec) - { - return this->get_service().send_to(this->get_implementation(), - buffers, destination, flags, ec); - } - - /// Start an asynchronous send. - /** - * This function is used to asynchronously send raw data to the specified - * remote endpoint. The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param destination The remote endpoint to which the data will be sent. - * Copies will be made of the endpoint as required. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * asio::ip::udp::endpoint destination( - * asio::ip::address::from_string("1.2.3.4"), 12345); - * socket.async_send_to( - * asio::buffer(data, size), destination, handler); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send_to(this->get_implementation(), - buffers, destination, 0, ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send_to(this->get_implementation(), - buffers, destination, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous send. - /** - * This function is used to asynchronously send raw data to the specified - * remote endpoint. The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent to the remote endpoint. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param destination The remote endpoint to which the data will be sent. - * Copies will be made of the endpoint as required. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send_to(const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send_to( - this->get_implementation(), buffers, destination, flags, - ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send_to( - this->get_implementation(), buffers, destination, flags, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the raw socket. The function - * call will block until data has been received successfully or an error - * occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - * - * @note The receive operation can only be used with a connected socket. Use - * the receive_from function to receive data on an unconnected raw - * socket. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code socket.receive(asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the raw socket. The function - * call will block until data has been received successfully or an error - * occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - * - * @note The receive operation can only be used with a connected socket. Use - * the receive_from function to receive data on an unconnected raw - * socket. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, flags, ec); - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the raw socket. The function - * call will block until data has been received successfully or an error - * occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes received. - * - * @note The receive operation can only be used with a connected socket. Use - * the receive_from function to receive data on an unconnected raw - * socket. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return this->get_service().receive( - this->get_implementation(), buffers, flags, ec); - } - - /// Start an asynchronous receive on a connected socket. - /** - * This function is used to asynchronously receive data from the raw - * socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_receive operation can only be used with a connected socket. - * Use the async_receive_from function to receive data on an unconnected - * raw socket. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.async_receive(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive(this->get_implementation(), - buffers, 0, ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive(this->get_implementation(), - buffers, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous receive on a connected socket. - /** - * This function is used to asynchronously receive data from the raw - * socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The async_receive operation can only be used with a connected socket. - * Use the async_receive_from function to receive data on an unconnected - * raw socket. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive(this->get_implementation(), - buffers, flags, ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive(this->get_implementation(), - buffers, flags, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Receive raw data with the endpoint of the sender. - /** - * This function is used to receive raw data. The function call will block - * until data has been received successfully or an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the data. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * asio::ip::udp::endpoint sender_endpoint; - * socket.receive_from( - * asio::buffer(data, size), sender_endpoint); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint) - { - asio::error_code ec; - std::size_t s = this->get_service().receive_from( - this->get_implementation(), buffers, sender_endpoint, 0, ec); - asio::detail::throw_error(ec, "receive_from"); - return s; - } - - /// Receive raw data with the endpoint of the sender. - /** - * This function is used to receive raw data. The function call will block - * until data has been received successfully or an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the data. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. - */ - template - std::size_t receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().receive_from( - this->get_implementation(), buffers, sender_endpoint, flags, ec); - asio::detail::throw_error(ec, "receive_from"); - return s; - } - - /// Receive raw data with the endpoint of the sender. - /** - * This function is used to receive raw data. The function call will block - * until data has been received successfully or an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the data. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes received. - */ - template - std::size_t receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags, - asio::error_code& ec) - { - return this->get_service().receive_from(this->get_implementation(), - buffers, sender_endpoint, flags, ec); - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive raw data. The function - * call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the data. Ownership of the sender_endpoint object - * is retained by the caller, which must guarantee that it is valid until the - * handler is called. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code socket.async_receive_from( - * asio::buffer(data, size), 0, sender_endpoint, handler); @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, 0, - ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, 0, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive raw data. The function - * call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param sender_endpoint An endpoint object that receives the endpoint of - * the remote sender of the data. Ownership of the sender_endpoint object - * is retained by the caller, which must guarantee that it is valid until the - * handler is called. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive_from(const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, flags, - ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive_from( - this->get_implementation(), buffers, sender_endpoint, flags, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BASIC_RAW_SOCKET_HPP diff --git a/scout_sdk/asio/asio/basic_seq_packet_socket.hpp b/scout_sdk/asio/asio/basic_seq_packet_socket.hpp deleted file mode 100644 index 3655d88..0000000 --- a/scout_sdk/asio/asio/basic_seq_packet_socket.hpp +++ /dev/null @@ -1,618 +0,0 @@ -// -// basic_seq_packet_socket.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_SEQ_PACKET_SOCKET_HPP -#define ASIO_BASIC_SEQ_PACKET_SOCKET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/basic_socket.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/seq_packet_socket_service.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides sequenced packet socket functionality. -/** - * The basic_seq_packet_socket class template provides asynchronous and blocking - * sequenced packet socket functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template )> -class basic_seq_packet_socket - : public basic_socket -{ -public: - /// The native representation of a socket. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename basic_socket< - Protocol ASIO_SVC_TARG>::native_handle_type native_handle_type; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - /// Construct a basic_seq_packet_socket without opening it. - /** - * This constructor creates a sequenced packet socket without opening it. The - * socket needs to be opened and then connected or accepted before data can - * be sent or received on it. - * - * @param io_context The io_context object that the sequenced packet socket - * will use to dispatch handlers for any asynchronous operations performed on - * the socket. - */ - explicit basic_seq_packet_socket(asio::io_context& io_context) - : basic_socket(io_context) - { - } - - /// Construct and open a basic_seq_packet_socket. - /** - * This constructor creates and opens a sequenced_packet socket. The socket - * needs to be connected or accepted before data can be sent or received on - * it. - * - * @param io_context The io_context object that the sequenced packet socket - * will use to dispatch handlers for any asynchronous operations performed on - * the socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @throws asio::system_error Thrown on failure. - */ - basic_seq_packet_socket(asio::io_context& io_context, - const protocol_type& protocol) - : basic_socket(io_context, protocol) - { - } - - /// Construct a basic_seq_packet_socket, opening it and binding it to the - /// given local endpoint. - /** - * This constructor creates a sequenced packet socket and automatically opens - * it bound to the specified endpoint on the local machine. The protocol used - * is the protocol associated with the given endpoint. - * - * @param io_context The io_context object that the sequenced packet socket - * will use to dispatch handlers for any asynchronous operations performed on - * the socket. - * - * @param endpoint An endpoint on the local machine to which the sequenced - * packet socket will be bound. - * - * @throws asio::system_error Thrown on failure. - */ - basic_seq_packet_socket(asio::io_context& io_context, - const endpoint_type& endpoint) - : basic_socket(io_context, endpoint) - { - } - - /// Construct a basic_seq_packet_socket on an existing native socket. - /** - * This constructor creates a sequenced packet socket object to hold an - * existing native socket. - * - * @param io_context The io_context object that the sequenced packet socket - * will use to dispatch handlers for any asynchronous operations performed on - * the socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @param native_socket The new underlying socket implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_seq_packet_socket(asio::io_context& io_context, - const protocol_type& protocol, const native_handle_type& native_socket) - : basic_socket( - io_context, protocol, native_socket) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_seq_packet_socket from another. - /** - * This constructor moves a sequenced packet socket from one object to - * another. - * - * @param other The other basic_seq_packet_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_seq_packet_socket(io_context&) constructor. - */ - basic_seq_packet_socket(basic_seq_packet_socket&& other) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_seq_packet_socket from another. - /** - * This assignment operator moves a sequenced packet socket from one object to - * another. - * - * @param other The other basic_seq_packet_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_seq_packet_socket(io_context&) constructor. - */ - basic_seq_packet_socket& operator=(basic_seq_packet_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } - - /// Move-construct a basic_seq_packet_socket from a socket of another protocol - /// type. - /** - * This constructor moves a sequenced packet socket from one object to - * another. - * - * @param other The other basic_seq_packet_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_seq_packet_socket(io_context&) constructor. - */ - template - basic_seq_packet_socket( - basic_seq_packet_socket&& other, - typename enable_if::value>::type* = 0) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_seq_packet_socket from a socket of another protocol - /// type. - /** - * This assignment operator moves a sequenced packet socket from one object to - * another. - * - * @param other The other basic_seq_packet_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_seq_packet_socket(io_context&) constructor. - */ - template - typename enable_if::value, - basic_seq_packet_socket>::type& operator=( - basic_seq_packet_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the socket. - /** - * This function destroys the socket, cancelling any outstanding asynchronous - * operations associated with the socket as if by calling @c cancel. - */ - ~basic_seq_packet_socket() - { - } - - /// Send some data on the socket. - /** - * This function is used to send data on the sequenced packet socket. The - * function call will block until the data has been sent successfully, or an - * until error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.send(asio::buffer(data, size), 0); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, flags, ec); - asio::detail::throw_error(ec, "send"); - return s; - } - - /// Send some data on the socket. - /** - * This function is used to send data on the sequenced packet socket. The - * function call will block the data has been sent successfully, or an until - * error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes sent. Returns 0 if an error occurred. - * - * @note The send operation may not transmit all of the data to the peer. - * Consider using the @ref write function if you need to ensure that all data - * is written before the blocking operation completes. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return this->get_service().send( - this->get_implementation(), buffers, flags, ec); - } - - /// Start an asynchronous send. - /** - * This function is used to asynchronously send data on the sequenced packet - * socket. The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent on the socket. Although - * the buffers object may be copied as necessary, ownership of the underlying - * memory blocks is retained by the caller, which must guarantee that they - * remain valid until the handler is called. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.async_send(asio::buffer(data, size), 0, handler); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send(this->get_implementation(), - buffers, flags, ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send(this->get_implementation(), - buffers, flags, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Receive some data on the socket. - /** - * This function is used to receive data on the sequenced packet socket. The - * function call will block until data has been received successfully, or - * until an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param out_flags After the receive call completes, contains flags - * associated with the received data. For example, if the - * socket_base::message_end_of_record bit is set then the received data marks - * the end of a record. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.receive(asio::buffer(data, size), out_flags); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags& out_flags) - { - asio::error_code ec; -#if defined(ASIO_ENABLE_OLD_SERVICES) - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, 0, out_flags, ec); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - std::size_t s = this->get_service().receive_with_flags( - this->get_implementation(), buffers, 0, out_flags, ec); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on the socket. - /** - * This function is used to receive data on the sequenced packet socket. The - * function call will block until data has been received successfully, or - * until an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param in_flags Flags specifying how the receive call is to be made. - * - * @param out_flags After the receive call completes, contains flags - * associated with the received data. For example, if the - * socket_base::message_end_of_record bit is set then the received data marks - * the end of a record. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The receive operation may not receive all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that the - * requested amount of data is read before the blocking operation completes. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.receive(asio::buffer(data, size), 0, out_flags); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags in_flags, - socket_base::message_flags& out_flags) - { - asio::error_code ec; -#if defined(ASIO_ENABLE_OLD_SERVICES) - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, in_flags, out_flags, ec); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - std::size_t s = this->get_service().receive_with_flags( - this->get_implementation(), buffers, in_flags, out_flags, ec); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the sequenced packet socket. The - * function call will block until data has been received successfully, or - * until an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param in_flags Flags specifying how the receive call is to be made. - * - * @param out_flags After the receive call completes, contains flags - * associated with the received data. For example, if the - * socket_base::message_end_of_record bit is set then the received data marks - * the end of a record. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes received. Returns 0 if an error occurred. - * - * @note The receive operation may not receive all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that the - * requested amount of data is read before the blocking operation completes. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, asio::error_code& ec) - { -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().receive(this->get_implementation(), - buffers, in_flags, out_flags, ec); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().receive_with_flags(this->get_implementation(), - buffers, in_flags, out_flags, ec); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive data from the sequenced - * packet socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param out_flags Once the asynchronous operation completes, contains flags - * associated with the received data. For example, if the - * socket_base::message_end_of_record bit is set then the received data marks - * the end of a record. The caller must guarantee that the referenced - * variable remains valid until the handler is called. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.async_receive(asio::buffer(data, size), out_flags, handler); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - socket_base::message_flags& out_flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive( - this->get_implementation(), buffers, 0, out_flags, - ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive_with_flags( - this->get_implementation(), buffers, 0, out_flags, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive data from the sequenced - * data socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param in_flags Flags specifying how the receive call is to be made. - * - * @param out_flags Once the asynchronous operation completes, contains flags - * associated with the received data. For example, if the - * socket_base::message_end_of_record bit is set then the received data marks - * the end of a record. The caller must guarantee that the referenced - * variable remains valid until the handler is called. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.async_receive( - * asio::buffer(data, size), - * 0, out_flags, handler); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive( - this->get_implementation(), buffers, in_flags, out_flags, - ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive_with_flags( - this->get_implementation(), buffers, in_flags, out_flags, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BASIC_SEQ_PACKET_SOCKET_HPP diff --git a/scout_sdk/asio/asio/basic_serial_port.hpp b/scout_sdk/asio/asio/basic_serial_port.hpp deleted file mode 100644 index 32262f8..0000000 --- a/scout_sdk/asio/asio/basic_serial_port.hpp +++ /dev/null @@ -1,688 +0,0 @@ -// -// basic_serial_port.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_SERIAL_PORT_HPP -#define ASIO_BASIC_SERIAL_PORT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_SERIAL_PORT) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/serial_port_base.hpp" -#include "asio/serial_port_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides serial port functionality. -/** - * The basic_serial_port class template provides functionality that is common - * to all serial ports. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_serial_port - : public basic_io_object, - public serial_port_base -{ -public: - /// The native representation of a serial port. - typedef typename SerialPortService::native_handle_type native_handle_type; - - /// A basic_serial_port is always the lowest layer. - typedef basic_serial_port lowest_layer_type; - - /// Construct a basic_serial_port without opening it. - /** - * This constructor creates a serial port without opening it. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - */ - explicit basic_serial_port(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct and open a basic_serial_port. - /** - * This constructor creates and opens a serial port for the specified device - * name. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - * - * @param device The platform-specific device name for this serial - * port. - */ - explicit basic_serial_port(asio::io_context& io_context, - const char* device) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), device, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Construct and open a basic_serial_port. - /** - * This constructor creates and opens a serial port for the specified device - * name. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - * - * @param device The platform-specific device name for this serial - * port. - */ - explicit basic_serial_port(asio::io_context& io_context, - const std::string& device) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), device, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Construct a basic_serial_port on an existing native serial port. - /** - * This constructor creates a serial port object to hold an existing native - * serial port. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - * - * @param native_serial_port A native serial port. - * - * @throws asio::system_error Thrown on failure. - */ - basic_serial_port(asio::io_context& io_context, - const native_handle_type& native_serial_port) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_serial_port, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_serial_port from another. - /** - * This constructor moves a serial port from one object to another. - * - * @param other The other basic_serial_port object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_serial_port(io_context&) constructor. - */ - basic_serial_port(basic_serial_port&& other) - : basic_io_object( - ASIO_MOVE_CAST(basic_serial_port)(other)) - { - } - - /// Move-assign a basic_serial_port from another. - /** - * This assignment operator moves a serial port from one object to another. - * - * @param other The other basic_serial_port object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_serial_port(io_context&) constructor. - */ - basic_serial_port& operator=(basic_serial_port&& other) - { - basic_io_object::operator=( - ASIO_MOVE_CAST(basic_serial_port)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since a basic_serial_port cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since a basic_serial_port cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } - - /// Open the serial port using the specified device name. - /** - * This function opens the serial port for the specified device name. - * - * @param device The platform-specific device name. - * - * @throws asio::system_error Thrown on failure. - */ - void open(const std::string& device) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), device, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Open the serial port using the specified device name. - /** - * This function opens the serial port using the given platform-specific - * device name. - * - * @param device The platform-specific device name. - * - * @param ec Set the indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID open(const std::string& device, - asio::error_code& ec) - { - this->get_service().open(this->get_implementation(), device, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native serial port to the serial port. - /* - * This function opens the serial port to hold an existing native serial port. - * - * @param native_serial_port A native serial port. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const native_handle_type& native_serial_port) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_serial_port, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native serial port to the serial port. - /* - * This function opens the serial port to hold an existing native serial port. - * - * @param native_serial_port A native serial port. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const native_handle_type& native_serial_port, - asio::error_code& ec) - { - this->get_service().assign(this->get_implementation(), - native_serial_port, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the serial port is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the serial port. - /** - * This function is used to close the serial port. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the serial port. - /** - * This function is used to close the serial port. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native serial port representation. - /** - * This function may be used to obtain the underlying representation of the - * serial port. This is intended to allow access to native serial port - * functionality that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the serial port. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the serial port. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Send a break sequence to the serial port. - /** - * This function causes a break sequence of platform-specific duration to be - * sent out the serial port. - * - * @throws asio::system_error Thrown on failure. - */ - void send_break() - { - asio::error_code ec; - this->get_service().send_break(this->get_implementation(), ec); - asio::detail::throw_error(ec, "send_break"); - } - - /// Send a break sequence to the serial port. - /** - * This function causes a break sequence of platform-specific duration to be - * sent out the serial port. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID send_break(asio::error_code& ec) - { - this->get_service().send_break(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Set an option on the serial port. - /** - * This function is used to set an option on the serial port. - * - * @param option The option value to be set on the serial port. - * - * @throws asio::system_error Thrown on failure. - * - * @sa SettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - void set_option(const SettableSerialPortOption& option) - { - asio::error_code ec; - this->get_service().set_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "set_option"); - } - - /// Set an option on the serial port. - /** - * This function is used to set an option on the serial port. - * - * @param option The option value to be set on the serial port. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa SettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - ASIO_SYNC_OP_VOID set_option(const SettableSerialPortOption& option, - asio::error_code& ec) - { - this->get_service().set_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get an option from the serial port. - /** - * This function is used to get the current value of an option on the serial - * port. - * - * @param option The option value to be obtained from the serial port. - * - * @throws asio::system_error Thrown on failure. - * - * @sa GettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - void get_option(GettableSerialPortOption& option) - { - asio::error_code ec; - this->get_service().get_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "get_option"); - } - - /// Get an option from the serial port. - /** - * This function is used to get the current value of an option on the serial - * port. - * - * @param option The option value to be obtained from the serial port. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa GettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - ASIO_SYNC_OP_VOID get_option(GettableSerialPortOption& option, - asio::error_code& ec) - { - this->get_service().get_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Write some data to the serial port. - /** - * This function is used to write data to the serial port. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the serial port. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.write_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "write_some"); - return s; - } - - /// Write some data to the serial port. - /** - * This function is used to write data to the serial port. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the serial port. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().write_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write data to the serial port. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be written to the serial port. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.async_write_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - return this->get_service().async_write_some(this->get_implementation(), - buffers, ASIO_MOVE_CAST(WriteHandler)(handler)); - } - - /// Read some data from the serial port. - /** - * This function is used to read data from the serial port. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.read_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "read_some"); - return s; - } - - /// Read some data from the serial port. - /** - * This function is used to read data from the serial port. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().read_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read data from the serial port. - * The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read function if you need to ensure that the - * requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.async_read_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - return this->get_service().async_read_some(this->get_implementation(), - buffers, ASIO_MOVE_CAST(ReadHandler)(handler)); - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_SERIAL_PORT) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_BASIC_SERIAL_PORT_HPP diff --git a/scout_sdk/asio/asio/basic_signal_set.hpp b/scout_sdk/asio/asio/basic_signal_set.hpp deleted file mode 100644 index cf34643..0000000 --- a/scout_sdk/asio/asio/basic_signal_set.hpp +++ /dev/null @@ -1,391 +0,0 @@ -// -// basic_signal_set.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_SIGNAL_SET_HPP -#define ASIO_BASIC_SIGNAL_SET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/signal_set_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides signal functionality. -/** - * The basic_signal_set class template provides the ability to perform an - * asynchronous wait for one or more signals to occur. - * - * Most applications will use the asio::signal_set typedef. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Example - * Performing an asynchronous wait: - * @code - * void handler( - * const asio::error_code& error, - * int signal_number) - * { - * if (!error) - * { - * // A signal occurred. - * } - * } - * - * ... - * - * // Construct a signal set registered for process termination. - * asio::signal_set signals(io_context, SIGINT, SIGTERM); - * - * // Start an asynchronous wait for one of the signals to occur. - * signals.async_wait(handler); - * @endcode - * - * @par Queueing of signal notifications - * - * If a signal is registered with a signal_set, and the signal occurs when - * there are no waiting handlers, then the signal notification is queued. The - * next async_wait operation on that signal_set will dequeue the notification. - * If multiple notifications are queued, subsequent async_wait operations - * dequeue them one at a time. Signal notifications are dequeued in order of - * ascending signal number. - * - * If a signal number is removed from a signal_set (using the @c remove or @c - * erase member functions) then any queued notifications for that signal are - * discarded. - * - * @par Multiple registration of signals - * - * The same signal number may be registered with different signal_set objects. - * When the signal occurs, one handler is called for each signal_set object. - * - * Note that multiple registration only works for signals that are registered - * using Asio. The application must not also register a signal handler using - * functions such as @c signal() or @c sigaction(). - * - * @par Signal masking on POSIX platforms - * - * POSIX allows signals to be blocked using functions such as @c sigprocmask() - * and @c pthread_sigmask(). For signals to be delivered, programs must ensure - * that any signals registered using signal_set objects are unblocked in at - * least one thread. - */ -template -class basic_signal_set - : public basic_io_object -{ -public: - /// Construct a signal set without adding any signals. - /** - * This constructor creates a signal set without registering for any signals. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - */ - explicit basic_signal_set(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct a signal set and add one signal. - /** - * This constructor creates a signal set and registers for one signal. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - * - * @param signal_number_1 The signal number to be added. - * - * @note This constructor is equivalent to performing: - * @code asio::signal_set signals(io_context); - * signals.add(signal_number_1); @endcode - */ - basic_signal_set(asio::io_context& io_context, int signal_number_1) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number_1, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Construct a signal set and add two signals. - /** - * This constructor creates a signal set and registers for two signals. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - * - * @param signal_number_1 The first signal number to be added. - * - * @param signal_number_2 The second signal number to be added. - * - * @note This constructor is equivalent to performing: - * @code asio::signal_set signals(io_context); - * signals.add(signal_number_1); - * signals.add(signal_number_2); @endcode - */ - basic_signal_set(asio::io_context& io_context, int signal_number_1, - int signal_number_2) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number_1, ec); - asio::detail::throw_error(ec, "add"); - this->get_service().add(this->get_implementation(), signal_number_2, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Construct a signal set and add three signals. - /** - * This constructor creates a signal set and registers for three signals. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - * - * @param signal_number_1 The first signal number to be added. - * - * @param signal_number_2 The second signal number to be added. - * - * @param signal_number_3 The third signal number to be added. - * - * @note This constructor is equivalent to performing: - * @code asio::signal_set signals(io_context); - * signals.add(signal_number_1); - * signals.add(signal_number_2); - * signals.add(signal_number_3); @endcode - */ - basic_signal_set(asio::io_context& io_context, int signal_number_1, - int signal_number_2, int signal_number_3) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number_1, ec); - asio::detail::throw_error(ec, "add"); - this->get_service().add(this->get_implementation(), signal_number_2, ec); - asio::detail::throw_error(ec, "add"); - this->get_service().add(this->get_implementation(), signal_number_3, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Add a signal to a signal_set. - /** - * This function adds the specified signal to the set. It has no effect if the - * signal is already in the set. - * - * @param signal_number The signal to be added to the set. - * - * @throws asio::system_error Thrown on failure. - */ - void add(int signal_number) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Add a signal to a signal_set. - /** - * This function adds the specified signal to the set. It has no effect if the - * signal is already in the set. - * - * @param signal_number The signal to be added to the set. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID add(int signal_number, asio::error_code& ec) - { - this->get_service().add(this->get_implementation(), signal_number, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Remove a signal from a signal_set. - /** - * This function removes the specified signal from the set. It has no effect - * if the signal is not in the set. - * - * @param signal_number The signal to be removed from the set. - * - * @throws asio::system_error Thrown on failure. - * - * @note Removes any notifications that have been queued for the specified - * signal number. - */ - void remove(int signal_number) - { - asio::error_code ec; - this->get_service().remove(this->get_implementation(), signal_number, ec); - asio::detail::throw_error(ec, "remove"); - } - - /// Remove a signal from a signal_set. - /** - * This function removes the specified signal from the set. It has no effect - * if the signal is not in the set. - * - * @param signal_number The signal to be removed from the set. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Removes any notifications that have been queued for the specified - * signal number. - */ - ASIO_SYNC_OP_VOID remove(int signal_number, - asio::error_code& ec) - { - this->get_service().remove(this->get_implementation(), signal_number, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Remove all signals from a signal_set. - /** - * This function removes all signals from the set. It has no effect if the set - * is already empty. - * - * @throws asio::system_error Thrown on failure. - * - * @note Removes all queued notifications. - */ - void clear() - { - asio::error_code ec; - this->get_service().clear(this->get_implementation(), ec); - asio::detail::throw_error(ec, "clear"); - } - - /// Remove all signals from a signal_set. - /** - * This function removes all signals from the set. It has no effect if the set - * is already empty. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Removes all queued notifications. - */ - ASIO_SYNC_OP_VOID clear(asio::error_code& ec) - { - this->get_service().clear(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Cancel all operations associated with the signal set. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the signal set. The handler for each cancelled - * operation will be invoked with the asio::error::operation_aborted - * error code. - * - * Cancellation does not alter the set of registered signals. - * - * @throws asio::system_error Thrown on failure. - * - * @note If a registered signal occurred before cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all operations associated with the signal set. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the signal set. The handler for each cancelled - * operation will be invoked with the asio::error::operation_aborted - * error code. - * - * Cancellation does not alter the set of registered signals. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note If a registered signal occurred before cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous operation to wait for a signal to be delivered. - /** - * This function may be used to initiate an asynchronous wait against the - * signal set. It always returns immediately. - * - * For each call to async_wait(), the supplied handler will be called exactly - * once. The handler will be called when: - * - * @li One of the registered signals in the signal set occurs; or - * - * @li The signal set was cancelled, in which case the handler is passed the - * error code asio::error::operation_aborted. - * - * @param handler The handler to be called when the signal occurs. Copies - * will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * int signal_number // Indicates which signal occurred. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(SignalHandler, - void (asio::error_code, int)) - async_wait(ASIO_MOVE_ARG(SignalHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a SignalHandler. - ASIO_SIGNAL_HANDLER_CHECK(SignalHandler, handler) type_check; - - return this->get_service().async_wait(this->get_implementation(), - ASIO_MOVE_CAST(SignalHandler)(handler)); - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_BASIC_SIGNAL_SET_HPP diff --git a/scout_sdk/asio/asio/basic_socket.hpp b/scout_sdk/asio/asio/basic_socket.hpp deleted file mode 100644 index 3dfacb4..0000000 --- a/scout_sdk/asio/asio/basic_socket.hpp +++ /dev/null @@ -1,1757 +0,0 @@ -// -// basic_socket.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_SOCKET_HPP -#define ASIO_BASIC_SOCKET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/async_result.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/post.hpp" -#include "asio/socket_base.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/winrt_ssocket_service.hpp" -# define ASIO_SVC_T detail::winrt_ssocket_service -# elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_socket_service.hpp" -# define ASIO_SVC_T detail::win_iocp_socket_service -# else -# include "asio/detail/reactive_socket_service.hpp" -# define ASIO_SVC_T detail::reactive_socket_service -# endif -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides socket functionality. -/** - * The basic_socket class template provides functionality that is common to both - * stream-oriented and datagram-oriented sockets. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_socket - : ASIO_SVC_ACCESS basic_io_object, - public socket_base -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The native representation of a socket. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename ASIO_SVC_T::native_handle_type native_handle_type; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - -#if !defined(ASIO_NO_EXTENSIONS) - /// A basic_socket is always the lowest layer. - typedef basic_socket lowest_layer_type; -#endif // !defined(ASIO_NO_EXTENSIONS) - - /// Construct a basic_socket without opening it. - /** - * This constructor creates a socket without opening it. - * - * @param io_context The io_context object that the socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - */ - explicit basic_socket(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct and open a basic_socket. - /** - * This constructor creates and opens a socket. - * - * @param io_context The io_context object that the socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @throws asio::system_error Thrown on failure. - */ - basic_socket(asio::io_context& io_context, - const protocol_type& protocol) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), protocol, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Construct a basic_socket, opening it and binding it to the given local - /// endpoint. - /** - * This constructor creates a socket and automatically opens it bound to the - * specified endpoint on the local machine. The protocol used is the protocol - * associated with the given endpoint. - * - * @param io_context The io_context object that the socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - * - * @param endpoint An endpoint on the local machine to which the socket will - * be bound. - * - * @throws asio::system_error Thrown on failure. - */ - basic_socket(asio::io_context& io_context, - const endpoint_type& endpoint) - : basic_io_object(io_context) - { - asio::error_code ec; - const protocol_type protocol = endpoint.protocol(); - this->get_service().open(this->get_implementation(), protocol, ec); - asio::detail::throw_error(ec, "open"); - this->get_service().bind(this->get_implementation(), endpoint, ec); - asio::detail::throw_error(ec, "bind"); - } - - /// Construct a basic_socket on an existing native socket. - /** - * This constructor creates a socket object to hold an existing native socket. - * - * @param io_context The io_context object that the socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @param native_socket A native socket. - * - * @throws asio::system_error Thrown on failure. - */ - basic_socket(asio::io_context& io_context, - const protocol_type& protocol, const native_handle_type& native_socket) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - protocol, native_socket, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_socket from another. - /** - * This constructor moves a socket from one object to another. - * - * @param other The other basic_socket object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket(io_context&) constructor. - */ - basic_socket(basic_socket&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign a basic_socket from another. - /** - * This assignment operator moves a socket from one object to another. - * - * @param other The other basic_socket object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket(io_context&) constructor. - */ - basic_socket& operator=(basic_socket&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } - - // All sockets have access to each other's implementations. - template - friend class basic_socket; - - /// Move-construct a basic_socket from a socket of another protocol type. - /** - * This constructor moves a socket from one object to another. - * - * @param other The other basic_socket object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket(io_context&) constructor. - */ - template - basic_socket(basic_socket&& other, - typename enable_if::value>::type* = 0) - : basic_io_object( - other.get_service(), other.get_implementation()) - { - } - - /// Move-assign a basic_socket from a socket of another protocol type. - /** - * This assignment operator moves a socket from one object to another. - * - * @param other The other basic_socket object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket(io_context&) constructor. - */ - template - typename enable_if::value, - basic_socket>::type& operator=( - basic_socket&& other) - { - basic_socket tmp(std::move(other)); - basic_io_object::operator=(std::move(tmp)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - -#if defined(ASIO_ENABLE_OLD_SERVICES) - // These functions are provided by basic_io_object<>. -#else // defined(ASIO_ENABLE_OLD_SERVICES) -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#if !defined(ASIO_NO_EXTENSIONS) - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since a basic_socket cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since a basic_socket cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } -#endif // !defined(ASIO_NO_EXTENSIONS) - - /// Open the socket using the specified protocol. - /** - * This function opens the socket so that it will use the specified protocol. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * socket.open(asio::ip::tcp::v4()); - * @endcode - */ - void open(const protocol_type& protocol = protocol_type()) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), protocol, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Open the socket using the specified protocol. - /** - * This function opens the socket so that it will use the specified protocol. - * - * @param protocol An object specifying which protocol is to be used. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * asio::error_code ec; - * socket.open(asio::ip::tcp::v4(), ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID open(const protocol_type& protocol, - asio::error_code& ec) - { - this->get_service().open(this->get_implementation(), protocol, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native socket to the socket. - /* - * This function opens the socket to hold an existing native socket. - * - * @param protocol An object specifying which protocol is to be used. - * - * @param native_socket A native socket. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const protocol_type& protocol, - const native_handle_type& native_socket) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - protocol, native_socket, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native socket to the socket. - /* - * This function opens the socket to hold an existing native socket. - * - * @param protocol An object specifying which protocol is to be used. - * - * @param native_socket A native socket. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const protocol_type& protocol, - const native_handle_type& native_socket, asio::error_code& ec) - { - this->get_service().assign(this->get_implementation(), - protocol, native_socket, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the socket. - /** - * This function is used to close the socket. Any asynchronous send, receive - * or connect operations will be cancelled immediately, and will complete - * with the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. Note that, even if - * the function indicates an error, the underlying descriptor is closed. - * - * @note For portable behaviour with respect to graceful closure of a - * connected socket, call shutdown() before closing the socket. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the socket. - /** - * This function is used to close the socket. Any asynchronous send, receive - * or connect operations will be cancelled immediately, and will complete - * with the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. Note that, even if - * the function indicates an error, the underlying descriptor is closed. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::error_code ec; - * socket.close(ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - * - * @note For portable behaviour with respect to graceful closure of a - * connected socket, call shutdown() before closing the socket. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Release ownership of the underlying native socket. - /** - * This function causes all outstanding asynchronous connect, send and receive - * operations to finish immediately, and the handlers for cancelled operations - * will be passed the asio::error::operation_aborted error. Ownership - * of the native socket is then transferred to the caller. - * - * @throws asio::system_error Thrown on failure. - * - * @note This function is unsupported on Windows versions prior to Windows - * 8.1, and will fail with asio::error::operation_not_supported on - * these platforms. - */ -#if defined(ASIO_MSVC) && (ASIO_MSVC >= 1400) \ - && (!defined(_WIN32_WINNT) || _WIN32_WINNT < 0x0603) - __declspec(deprecated("This function always fails with " - "operation_not_supported when used on Windows versions " - "prior to Windows 8.1.")) -#endif - native_handle_type release() - { - asio::error_code ec; - native_handle_type s = this->get_service().release( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "release"); - return s; - } - - /// Release ownership of the underlying native socket. - /** - * This function causes all outstanding asynchronous connect, send and receive - * operations to finish immediately, and the handlers for cancelled operations - * will be passed the asio::error::operation_aborted error. Ownership - * of the native socket is then transferred to the caller. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note This function is unsupported on Windows versions prior to Windows - * 8.1, and will fail with asio::error::operation_not_supported on - * these platforms. - */ -#if defined(ASIO_MSVC) && (ASIO_MSVC >= 1400) \ - && (!defined(_WIN32_WINNT) || _WIN32_WINNT < 0x0603) - __declspec(deprecated("This function always fails with " - "operation_not_supported when used on Windows versions " - "prior to Windows 8.1.")) -#endif - native_handle_type release(asio::error_code& ec) - { - return this->get_service().release(this->get_implementation(), ec); - } - - /// Get the native socket representation. - /** - * This function may be used to obtain the underlying representation of the - * socket. This is intended to allow access to native socket functionality - * that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the socket. - /** - * This function causes all outstanding asynchronous connect, send and receive - * operations to finish immediately, and the handlers for cancelled operations - * will be passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls to cancel() will always fail with - * asio::error::operation_not_supported when run on Windows XP, Windows - * Server 2003, and earlier versions of Windows, unless - * ASIO_ENABLE_CANCELIO is defined. However, the CancelIo function has - * two issues that should be considered before enabling its use: - * - * @li It will only cancel asynchronous operations that were initiated in the - * current thread. - * - * @li It can appear to complete without error, but the request to cancel the - * unfinished operations may be silently ignored by the operating system. - * Whether it works or not seems to depend on the drivers that are installed. - * - * For portable cancellation, consider using one of the following - * alternatives: - * - * @li Disable asio's I/O completion port backend by defining - * ASIO_DISABLE_IOCP. - * - * @li Use the close() function to simultaneously cancel the outstanding - * operations and close the socket. - * - * When running on Windows Vista, Windows Server 2008, and later, the - * CancelIoEx function is always used. This function does not have the - * problems described above. - */ -#if defined(ASIO_MSVC) && (ASIO_MSVC >= 1400) \ - && (!defined(_WIN32_WINNT) || _WIN32_WINNT < 0x0600) \ - && !defined(ASIO_ENABLE_CANCELIO) - __declspec(deprecated("By default, this function always fails with " - "operation_not_supported when used on Windows XP, Windows Server 2003, " - "or earlier. Consult documentation for details.")) -#endif - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the socket. - /** - * This function causes all outstanding asynchronous connect, send and receive - * operations to finish immediately, and the handlers for cancelled operations - * will be passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls to cancel() will always fail with - * asio::error::operation_not_supported when run on Windows XP, Windows - * Server 2003, and earlier versions of Windows, unless - * ASIO_ENABLE_CANCELIO is defined. However, the CancelIo function has - * two issues that should be considered before enabling its use: - * - * @li It will only cancel asynchronous operations that were initiated in the - * current thread. - * - * @li It can appear to complete without error, but the request to cancel the - * unfinished operations may be silently ignored by the operating system. - * Whether it works or not seems to depend on the drivers that are installed. - * - * For portable cancellation, consider using one of the following - * alternatives: - * - * @li Disable asio's I/O completion port backend by defining - * ASIO_DISABLE_IOCP. - * - * @li Use the close() function to simultaneously cancel the outstanding - * operations and close the socket. - * - * When running on Windows Vista, Windows Server 2008, and later, the - * CancelIoEx function is always used. This function does not have the - * problems described above. - */ -#if defined(ASIO_MSVC) && (ASIO_MSVC >= 1400) \ - && (!defined(_WIN32_WINNT) || _WIN32_WINNT < 0x0600) \ - && !defined(ASIO_ENABLE_CANCELIO) - __declspec(deprecated("By default, this function always fails with " - "operation_not_supported when used on Windows XP, Windows Server 2003, " - "or earlier. Consult documentation for details.")) -#endif - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is at the out-of-band data mark. - /** - * This function is used to check whether the socket input is currently - * positioned at the out-of-band data mark. - * - * @return A bool indicating whether the socket is at the out-of-band data - * mark. - * - * @throws asio::system_error Thrown on failure. - */ - bool at_mark() const - { - asio::error_code ec; - bool b = this->get_service().at_mark(this->get_implementation(), ec); - asio::detail::throw_error(ec, "at_mark"); - return b; - } - - /// Determine whether the socket is at the out-of-band data mark. - /** - * This function is used to check whether the socket input is currently - * positioned at the out-of-band data mark. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return A bool indicating whether the socket is at the out-of-band data - * mark. - */ - bool at_mark(asio::error_code& ec) const - { - return this->get_service().at_mark(this->get_implementation(), ec); - } - - /// Determine the number of bytes available for reading. - /** - * This function is used to determine the number of bytes that may be read - * without blocking. - * - * @return The number of bytes that may be read without blocking, or 0 if an - * error occurs. - * - * @throws asio::system_error Thrown on failure. - */ - std::size_t available() const - { - asio::error_code ec; - std::size_t s = this->get_service().available( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "available"); - return s; - } - - /// Determine the number of bytes available for reading. - /** - * This function is used to determine the number of bytes that may be read - * without blocking. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of bytes that may be read without blocking, or 0 if an - * error occurs. - */ - std::size_t available(asio::error_code& ec) const - { - return this->get_service().available(this->get_implementation(), ec); - } - - /// Bind the socket to the given local endpoint. - /** - * This function binds the socket to the specified endpoint on the local - * machine. - * - * @param endpoint An endpoint on the local machine to which the socket will - * be bound. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * socket.open(asio::ip::tcp::v4()); - * socket.bind(asio::ip::tcp::endpoint( - * asio::ip::tcp::v4(), 12345)); - * @endcode - */ - void bind(const endpoint_type& endpoint) - { - asio::error_code ec; - this->get_service().bind(this->get_implementation(), endpoint, ec); - asio::detail::throw_error(ec, "bind"); - } - - /// Bind the socket to the given local endpoint. - /** - * This function binds the socket to the specified endpoint on the local - * machine. - * - * @param endpoint An endpoint on the local machine to which the socket will - * be bound. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * socket.open(asio::ip::tcp::v4()); - * asio::error_code ec; - * socket.bind(asio::ip::tcp::endpoint( - * asio::ip::tcp::v4(), 12345), ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID bind(const endpoint_type& endpoint, - asio::error_code& ec) - { - this->get_service().bind(this->get_implementation(), endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Connect the socket to the specified endpoint. - /** - * This function is used to connect a socket to the specified remote endpoint. - * The function call will block until the connection is successfully made or - * an error occurs. - * - * The socket is automatically opened if it is not already open. If the - * connect fails, and the socket was automatically opened, the socket is - * not returned to the closed state. - * - * @param peer_endpoint The remote endpoint to which the socket will be - * connected. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * asio::ip::tcp::endpoint endpoint( - * asio::ip::address::from_string("1.2.3.4"), 12345); - * socket.connect(endpoint); - * @endcode - */ - void connect(const endpoint_type& peer_endpoint) - { - asio::error_code ec; - if (!is_open()) - { - this->get_service().open(this->get_implementation(), - peer_endpoint.protocol(), ec); - asio::detail::throw_error(ec, "connect"); - } - this->get_service().connect(this->get_implementation(), peer_endpoint, ec); - asio::detail::throw_error(ec, "connect"); - } - - /// Connect the socket to the specified endpoint. - /** - * This function is used to connect a socket to the specified remote endpoint. - * The function call will block until the connection is successfully made or - * an error occurs. - * - * The socket is automatically opened if it is not already open. If the - * connect fails, and the socket was automatically opened, the socket is - * not returned to the closed state. - * - * @param peer_endpoint The remote endpoint to which the socket will be - * connected. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * asio::ip::tcp::endpoint endpoint( - * asio::ip::address::from_string("1.2.3.4"), 12345); - * asio::error_code ec; - * socket.connect(endpoint, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID connect(const endpoint_type& peer_endpoint, - asio::error_code& ec) - { - if (!is_open()) - { - this->get_service().open(this->get_implementation(), - peer_endpoint.protocol(), ec); - if (ec) - { - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - this->get_service().connect(this->get_implementation(), peer_endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous connect. - /** - * This function is used to asynchronously connect a socket to the specified - * remote endpoint. The function call always returns immediately. - * - * The socket is automatically opened if it is not already open. If the - * connect fails, and the socket was automatically opened, the socket is - * not returned to the closed state. - * - * @param peer_endpoint The remote endpoint to which the socket will be - * connected. Copies will be made of the endpoint object as required. - * - * @param handler The handler to be called when the connection operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void connect_handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Connect succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::socket socket(io_context); - * asio::ip::tcp::endpoint endpoint( - * asio::ip::address::from_string("1.2.3.4"), 12345); - * socket.async_connect(endpoint, connect_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(ConnectHandler, - void (asio::error_code)) - async_connect(const endpoint_type& peer_endpoint, - ASIO_MOVE_ARG(ConnectHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ConnectHandler. - ASIO_CONNECT_HANDLER_CHECK(ConnectHandler, handler) type_check; - - if (!is_open()) - { - asio::error_code ec; - const protocol_type protocol = peer_endpoint.protocol(); - this->get_service().open(this->get_implementation(), protocol, ec); - if (ec) - { - async_completion init(handler); - - asio::post(this->get_executor(), - asio::detail::bind_handler( - ASIO_MOVE_CAST(ASIO_HANDLER_TYPE( - ConnectHandler, void (asio::error_code)))( - init.completion_handler), ec)); - - return init.result.get(); - } - } - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_connect(this->get_implementation(), - peer_endpoint, ASIO_MOVE_CAST(ConnectHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_connect( - this->get_implementation(), peer_endpoint, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Set an option on the socket. - /** - * This function is used to set an option on the socket. - * - * @param option The new option value to be set on the socket. - * - * @throws asio::system_error Thrown on failure. - * - * @sa SettableSocketOption @n - * asio::socket_base::broadcast @n - * asio::socket_base::do_not_route @n - * asio::socket_base::keep_alive @n - * asio::socket_base::linger @n - * asio::socket_base::receive_buffer_size @n - * asio::socket_base::receive_low_watermark @n - * asio::socket_base::reuse_address @n - * asio::socket_base::send_buffer_size @n - * asio::socket_base::send_low_watermark @n - * asio::ip::multicast::join_group @n - * asio::ip::multicast::leave_group @n - * asio::ip::multicast::enable_loopback @n - * asio::ip::multicast::outbound_interface @n - * asio::ip::multicast::hops @n - * asio::ip::tcp::no_delay - * - * @par Example - * Setting the IPPROTO_TCP/TCP_NODELAY option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::no_delay option(true); - * socket.set_option(option); - * @endcode - */ - template - void set_option(const SettableSocketOption& option) - { - asio::error_code ec; - this->get_service().set_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "set_option"); - } - - /// Set an option on the socket. - /** - * This function is used to set an option on the socket. - * - * @param option The new option value to be set on the socket. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa SettableSocketOption @n - * asio::socket_base::broadcast @n - * asio::socket_base::do_not_route @n - * asio::socket_base::keep_alive @n - * asio::socket_base::linger @n - * asio::socket_base::receive_buffer_size @n - * asio::socket_base::receive_low_watermark @n - * asio::socket_base::reuse_address @n - * asio::socket_base::send_buffer_size @n - * asio::socket_base::send_low_watermark @n - * asio::ip::multicast::join_group @n - * asio::ip::multicast::leave_group @n - * asio::ip::multicast::enable_loopback @n - * asio::ip::multicast::outbound_interface @n - * asio::ip::multicast::hops @n - * asio::ip::tcp::no_delay - * - * @par Example - * Setting the IPPROTO_TCP/TCP_NODELAY option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::no_delay option(true); - * asio::error_code ec; - * socket.set_option(option, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - template - ASIO_SYNC_OP_VOID set_option(const SettableSocketOption& option, - asio::error_code& ec) - { - this->get_service().set_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get an option from the socket. - /** - * This function is used to get the current value of an option on the socket. - * - * @param option The option value to be obtained from the socket. - * - * @throws asio::system_error Thrown on failure. - * - * @sa GettableSocketOption @n - * asio::socket_base::broadcast @n - * asio::socket_base::do_not_route @n - * asio::socket_base::keep_alive @n - * asio::socket_base::linger @n - * asio::socket_base::receive_buffer_size @n - * asio::socket_base::receive_low_watermark @n - * asio::socket_base::reuse_address @n - * asio::socket_base::send_buffer_size @n - * asio::socket_base::send_low_watermark @n - * asio::ip::multicast::join_group @n - * asio::ip::multicast::leave_group @n - * asio::ip::multicast::enable_loopback @n - * asio::ip::multicast::outbound_interface @n - * asio::ip::multicast::hops @n - * asio::ip::tcp::no_delay - * - * @par Example - * Getting the value of the SOL_SOCKET/SO_KEEPALIVE option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::socket::keep_alive option; - * socket.get_option(option); - * bool is_set = option.value(); - * @endcode - */ - template - void get_option(GettableSocketOption& option) const - { - asio::error_code ec; - this->get_service().get_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "get_option"); - } - - /// Get an option from the socket. - /** - * This function is used to get the current value of an option on the socket. - * - * @param option The option value to be obtained from the socket. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa GettableSocketOption @n - * asio::socket_base::broadcast @n - * asio::socket_base::do_not_route @n - * asio::socket_base::keep_alive @n - * asio::socket_base::linger @n - * asio::socket_base::receive_buffer_size @n - * asio::socket_base::receive_low_watermark @n - * asio::socket_base::reuse_address @n - * asio::socket_base::send_buffer_size @n - * asio::socket_base::send_low_watermark @n - * asio::ip::multicast::join_group @n - * asio::ip::multicast::leave_group @n - * asio::ip::multicast::enable_loopback @n - * asio::ip::multicast::outbound_interface @n - * asio::ip::multicast::hops @n - * asio::ip::tcp::no_delay - * - * @par Example - * Getting the value of the SOL_SOCKET/SO_KEEPALIVE option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::socket::keep_alive option; - * asio::error_code ec; - * socket.get_option(option, ec); - * if (ec) - * { - * // An error occurred. - * } - * bool is_set = option.value(); - * @endcode - */ - template - ASIO_SYNC_OP_VOID get_option(GettableSocketOption& option, - asio::error_code& ec) const - { - this->get_service().get_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the socket. - /** - * This function is used to execute an IO control command on the socket. - * - * @param command The IO control command to be performed on the socket. - * - * @throws asio::system_error Thrown on failure. - * - * @sa IoControlCommand @n - * asio::socket_base::bytes_readable @n - * asio::socket_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::socket::bytes_readable command; - * socket.io_control(command); - * std::size_t bytes_readable = command.get(); - * @endcode - */ - template - void io_control(IoControlCommand& command) - { - asio::error_code ec; - this->get_service().io_control(this->get_implementation(), command, ec); - asio::detail::throw_error(ec, "io_control"); - } - - /// Perform an IO control command on the socket. - /** - * This function is used to execute an IO control command on the socket. - * - * @param command The IO control command to be performed on the socket. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa IoControlCommand @n - * asio::socket_base::bytes_readable @n - * asio::socket_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::socket::bytes_readable command; - * asio::error_code ec; - * socket.io_control(command, ec); - * if (ec) - * { - * // An error occurred. - * } - * std::size_t bytes_readable = command.get(); - * @endcode - */ - template - ASIO_SYNC_OP_VOID io_control(IoControlCommand& command, - asio::error_code& ec) - { - this->get_service().io_control(this->get_implementation(), command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the socket. - /** - * @returns @c true if the socket's synchronous operations will fail with - * asio::error::would_block if they are unable to perform the requested - * operation immediately. If @c false, synchronous operations will block - * until complete. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - bool non_blocking() const - { - return this->get_service().non_blocking(this->get_implementation()); - } - - /// Sets the non-blocking mode of the socket. - /** - * @param mode If @c true, the socket's synchronous operations will fail with - * asio::error::would_block if they are unable to perform the requested - * operation immediately. If @c false, synchronous operations will block - * until complete. - * - * @throws asio::system_error Thrown on failure. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - void non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().non_blocking(this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "non_blocking"); - } - - /// Sets the non-blocking mode of the socket. - /** - * @param mode If @c true, the socket's synchronous operations will fail with - * asio::error::would_block if they are unable to perform the requested - * operation immediately. If @c false, synchronous operations will block - * until complete. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - ASIO_SYNC_OP_VOID non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().non_blocking(this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native socket implementation. - /** - * This function is used to retrieve the non-blocking mode of the underlying - * native socket. This mode has no effect on the behaviour of the socket - * object's synchronous operations. - * - * @returns @c true if the underlying socket is in non-blocking mode and - * direct system calls may fail with asio::error::would_block (or the - * equivalent system error). - * - * @note The current non-blocking mode is cached by the socket object. - * Consequently, the return value may be incorrect if the non-blocking mode - * was set directly on the native socket. - * - * @par Example - * This function is intended to allow the encapsulation of arbitrary - * non-blocking system calls as asynchronous operations, in a way that is - * transparent to the user of the socket object. The following example - * illustrates how Linux's @c sendfile system call might be encapsulated: - * @code template - * struct sendfile_op - * { - * tcp::socket& sock_; - * int fd_; - * Handler handler_; - * off_t offset_; - * std::size_t total_bytes_transferred_; - * - * // Function call operator meeting WriteHandler requirements. - * // Used as the handler for the async_write_some operation. - * void operator()(asio::error_code ec, std::size_t) - * { - * // Put the underlying socket into non-blocking mode. - * if (!ec) - * if (!sock_.native_non_blocking()) - * sock_.native_non_blocking(true, ec); - * - * if (!ec) - * { - * for (;;) - * { - * // Try the system call. - * errno = 0; - * int n = ::sendfile(sock_.native_handle(), fd_, &offset_, 65536); - * ec = asio::error_code(n < 0 ? errno : 0, - * asio::error::get_system_category()); - * total_bytes_transferred_ += ec ? 0 : n; - * - * // Retry operation immediately if interrupted by signal. - * if (ec == asio::error::interrupted) - * continue; - * - * // Check if we need to run the operation again. - * if (ec == asio::error::would_block - * || ec == asio::error::try_again) - * { - * // We have to wait for the socket to become ready again. - * sock_.async_wait(tcp::socket::wait_write, *this); - * return; - * } - * - * if (ec || n == 0) - * { - * // An error occurred, or we have reached the end of the file. - * // Either way we must exit the loop so we can call the handler. - * break; - * } - * - * // Loop around to try calling sendfile again. - * } - * } - * - * // Pass result back to user's handler. - * handler_(ec, total_bytes_transferred_); - * } - * }; - * - * template - * void async_sendfile(tcp::socket& sock, int fd, Handler h) - * { - * sendfile_op op = { sock, fd, h, 0, 0 }; - * sock.async_wait(tcp::socket::wait_write, op); - * } @endcode - */ - bool native_non_blocking() const - { - return this->get_service().native_non_blocking(this->get_implementation()); - } - - /// Sets the non-blocking mode of the native socket implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native socket. It has no effect on the behaviour of the socket object's - * synchronous operations. - * - * @param mode If @c true, the underlying socket is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @throws asio::system_error Thrown on failure. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - * - * @par Example - * This function is intended to allow the encapsulation of arbitrary - * non-blocking system calls as asynchronous operations, in a way that is - * transparent to the user of the socket object. The following example - * illustrates how Linux's @c sendfile system call might be encapsulated: - * @code template - * struct sendfile_op - * { - * tcp::socket& sock_; - * int fd_; - * Handler handler_; - * off_t offset_; - * std::size_t total_bytes_transferred_; - * - * // Function call operator meeting WriteHandler requirements. - * // Used as the handler for the async_write_some operation. - * void operator()(asio::error_code ec, std::size_t) - * { - * // Put the underlying socket into non-blocking mode. - * if (!ec) - * if (!sock_.native_non_blocking()) - * sock_.native_non_blocking(true, ec); - * - * if (!ec) - * { - * for (;;) - * { - * // Try the system call. - * errno = 0; - * int n = ::sendfile(sock_.native_handle(), fd_, &offset_, 65536); - * ec = asio::error_code(n < 0 ? errno : 0, - * asio::error::get_system_category()); - * total_bytes_transferred_ += ec ? 0 : n; - * - * // Retry operation immediately if interrupted by signal. - * if (ec == asio::error::interrupted) - * continue; - * - * // Check if we need to run the operation again. - * if (ec == asio::error::would_block - * || ec == asio::error::try_again) - * { - * // We have to wait for the socket to become ready again. - * sock_.async_wait(tcp::socket::wait_write, *this); - * return; - * } - * - * if (ec || n == 0) - * { - * // An error occurred, or we have reached the end of the file. - * // Either way we must exit the loop so we can call the handler. - * break; - * } - * - * // Loop around to try calling sendfile again. - * } - * } - * - * // Pass result back to user's handler. - * handler_(ec, total_bytes_transferred_); - * } - * }; - * - * template - * void async_sendfile(tcp::socket& sock, int fd, Handler h) - * { - * sendfile_op op = { sock, fd, h, 0, 0 }; - * sock.async_wait(tcp::socket::wait_write, op); - * } @endcode - */ - void native_non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "native_non_blocking"); - } - - /// Sets the non-blocking mode of the native socket implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native socket. It has no effect on the behaviour of the socket object's - * synchronous operations. - * - * @param mode If @c true, the underlying socket is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @param ec Set to indicate what error occurred, if any. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - * - * @par Example - * This function is intended to allow the encapsulation of arbitrary - * non-blocking system calls as asynchronous operations, in a way that is - * transparent to the user of the socket object. The following example - * illustrates how Linux's @c sendfile system call might be encapsulated: - * @code template - * struct sendfile_op - * { - * tcp::socket& sock_; - * int fd_; - * Handler handler_; - * off_t offset_; - * std::size_t total_bytes_transferred_; - * - * // Function call operator meeting WriteHandler requirements. - * // Used as the handler for the async_write_some operation. - * void operator()(asio::error_code ec, std::size_t) - * { - * // Put the underlying socket into non-blocking mode. - * if (!ec) - * if (!sock_.native_non_blocking()) - * sock_.native_non_blocking(true, ec); - * - * if (!ec) - * { - * for (;;) - * { - * // Try the system call. - * errno = 0; - * int n = ::sendfile(sock_.native_handle(), fd_, &offset_, 65536); - * ec = asio::error_code(n < 0 ? errno : 0, - * asio::error::get_system_category()); - * total_bytes_transferred_ += ec ? 0 : n; - * - * // Retry operation immediately if interrupted by signal. - * if (ec == asio::error::interrupted) - * continue; - * - * // Check if we need to run the operation again. - * if (ec == asio::error::would_block - * || ec == asio::error::try_again) - * { - * // We have to wait for the socket to become ready again. - * sock_.async_wait(tcp::socket::wait_write, *this); - * return; - * } - * - * if (ec || n == 0) - * { - * // An error occurred, or we have reached the end of the file. - * // Either way we must exit the loop so we can call the handler. - * break; - * } - * - * // Loop around to try calling sendfile again. - * } - * } - * - * // Pass result back to user's handler. - * handler_(ec, total_bytes_transferred_); - * } - * }; - * - * template - * void async_sendfile(tcp::socket& sock, int fd, Handler h) - * { - * sendfile_op op = { sock, fd, h, 0, 0 }; - * sock.async_wait(tcp::socket::wait_write, op); - * } @endcode - */ - ASIO_SYNC_OP_VOID native_non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the local endpoint of the socket. - /** - * This function is used to obtain the locally bound endpoint of the socket. - * - * @returns An object that represents the local endpoint of the socket. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::endpoint endpoint = socket.local_endpoint(); - * @endcode - */ - endpoint_type local_endpoint() const - { - asio::error_code ec; - endpoint_type ep = this->get_service().local_endpoint( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "local_endpoint"); - return ep; - } - - /// Get the local endpoint of the socket. - /** - * This function is used to obtain the locally bound endpoint of the socket. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns An object that represents the local endpoint of the socket. - * Returns a default-constructed endpoint object if an error occurred. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::error_code ec; - * asio::ip::tcp::endpoint endpoint = socket.local_endpoint(ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - endpoint_type local_endpoint(asio::error_code& ec) const - { - return this->get_service().local_endpoint(this->get_implementation(), ec); - } - - /// Get the remote endpoint of the socket. - /** - * This function is used to obtain the remote endpoint of the socket. - * - * @returns An object that represents the remote endpoint of the socket. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::endpoint endpoint = socket.remote_endpoint(); - * @endcode - */ - endpoint_type remote_endpoint() const - { - asio::error_code ec; - endpoint_type ep = this->get_service().remote_endpoint( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "remote_endpoint"); - return ep; - } - - /// Get the remote endpoint of the socket. - /** - * This function is used to obtain the remote endpoint of the socket. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns An object that represents the remote endpoint of the socket. - * Returns a default-constructed endpoint object if an error occurred. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::error_code ec; - * asio::ip::tcp::endpoint endpoint = socket.remote_endpoint(ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - endpoint_type remote_endpoint(asio::error_code& ec) const - { - return this->get_service().remote_endpoint(this->get_implementation(), ec); - } - - /// Disable sends or receives on the socket. - /** - * This function is used to disable send operations, receive operations, or - * both. - * - * @param what Determines what types of operation will no longer be allowed. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * Shutting down the send side of the socket: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * socket.shutdown(asio::ip::tcp::socket::shutdown_send); - * @endcode - */ - void shutdown(shutdown_type what) - { - asio::error_code ec; - this->get_service().shutdown(this->get_implementation(), what, ec); - asio::detail::throw_error(ec, "shutdown"); - } - - /// Disable sends or receives on the socket. - /** - * This function is used to disable send operations, receive operations, or - * both. - * - * @param what Determines what types of operation will no longer be allowed. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * Shutting down the send side of the socket: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::error_code ec; - * socket.shutdown(asio::ip::tcp::socket::shutdown_send, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID shutdown(shutdown_type what, - asio::error_code& ec) - { - this->get_service().shutdown(this->get_implementation(), what, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the socket to become ready to read, ready to write, or to have - /// pending error conditions. - /** - * This function is used to perform a blocking wait for a socket to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired socket state. - * - * @par Example - * Waiting for a socket to become readable. - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * socket.wait(asio::ip::tcp::socket::wait_read); - * @endcode - */ - void wait(wait_type w) - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), w, ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Wait for the socket to become ready to read, ready to write, or to have - /// pending error conditions. - /** - * This function is used to perform a blocking wait for a socket to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired socket state. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * Waiting for a socket to become readable. - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::error_code ec; - * socket.wait(asio::ip::tcp::socket::wait_read, ec); - * @endcode - */ - ASIO_SYNC_OP_VOID wait(wait_type w, asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the socket to become ready to read, ready to - /// write, or to have pending error conditions. - /** - * This function is used to perform an asynchronous wait for a socket to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired socket state. - * - * @param handler The handler to be called when the wait operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void wait_handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Wait succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::socket socket(io_context); - * ... - * socket.async_wait(asio::ip::tcp::socket::wait_read, wait_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(wait_type w, ASIO_MOVE_ARG(WaitHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WaitHandler. - ASIO_WAIT_HANDLER_CHECK(WaitHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_wait(this->get_implementation(), - w, ASIO_MOVE_CAST(WaitHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_wait(this->get_implementation(), - w, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - -protected: - /// Protected destructor to prevent deletion through this type. - /** - * This function destroys the socket, cancelling any outstanding asynchronous - * operations associated with the socket as if by calling @c cancel. - */ - ~basic_socket() - { - } - -private: - // Disallow copying and assignment. - basic_socket(const basic_socket&) ASIO_DELETED; - basic_socket& operator=(const basic_socket&) ASIO_DELETED; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# undef ASIO_SVC_T -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_BASIC_SOCKET_HPP diff --git a/scout_sdk/asio/asio/basic_socket_acceptor.hpp b/scout_sdk/asio/asio/basic_socket_acceptor.hpp deleted file mode 100644 index ed201bb..0000000 --- a/scout_sdk/asio/asio/basic_socket_acceptor.hpp +++ /dev/null @@ -1,1986 +0,0 @@ -// -// basic_socket_acceptor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_SOCKET_ACCEPTOR_HPP -#define ASIO_BASIC_SOCKET_ACCEPTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/basic_socket.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/socket_base.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/socket_acceptor_service.hpp" -#else // defined(ASIO_ENABLE_OLD_SERVICES) -# if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/null_socket_service.hpp" -# define ASIO_SVC_T detail::null_socket_service -# elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_socket_service.hpp" -# define ASIO_SVC_T detail::win_iocp_socket_service -# else -# include "asio/detail/reactive_socket_service.hpp" -# define ASIO_SVC_T detail::reactive_socket_service -# endif -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides the ability to accept new connections. -/** - * The basic_socket_acceptor class template is used for accepting new socket - * connections. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Example - * Opening a socket acceptor with the SO_REUSEADDR option enabled: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * asio::ip::tcp::endpoint endpoint(asio::ip::tcp::v4(), port); - * acceptor.open(endpoint.protocol()); - * acceptor.set_option(asio::ip::tcp::acceptor::reuse_address(true)); - * acceptor.bind(endpoint); - * acceptor.listen(); - * @endcode - */ -template )> -class basic_socket_acceptor - : ASIO_SVC_ACCESS basic_io_object, - public socket_base -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The native representation of an acceptor. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename ASIO_SVC_T::native_handle_type native_handle_type; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - /// Construct an acceptor without opening it. - /** - * This constructor creates an acceptor without opening it to listen for new - * connections. The open() function must be called before the acceptor can - * accept new socket connections. - * - * @param io_context The io_context object that the acceptor will use to - * dispatch handlers for any asynchronous operations performed on the - * acceptor. - */ - explicit basic_socket_acceptor(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct an open acceptor. - /** - * This constructor creates an acceptor and automatically opens it. - * - * @param io_context The io_context object that the acceptor will use to - * dispatch handlers for any asynchronous operations performed on the - * acceptor. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @throws asio::system_error Thrown on failure. - */ - basic_socket_acceptor(asio::io_context& io_context, - const protocol_type& protocol) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), protocol, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Construct an acceptor opened on the given endpoint. - /** - * This constructor creates an acceptor and automatically opens it to listen - * for new connections on the specified endpoint. - * - * @param io_context The io_context object that the acceptor will use to - * dispatch handlers for any asynchronous operations performed on the - * acceptor. - * - * @param endpoint An endpoint on the local machine on which the acceptor - * will listen for new connections. - * - * @param reuse_addr Whether the constructor should set the socket option - * socket_base::reuse_address. - * - * @throws asio::system_error Thrown on failure. - * - * @note This constructor is equivalent to the following code: - * @code - * basic_socket_acceptor acceptor(io_context); - * acceptor.open(endpoint.protocol()); - * if (reuse_addr) - * acceptor.set_option(socket_base::reuse_address(true)); - * acceptor.bind(endpoint); - * acceptor.listen(listen_backlog); - * @endcode - */ - basic_socket_acceptor(asio::io_context& io_context, - const endpoint_type& endpoint, bool reuse_addr = true) - : basic_io_object(io_context) - { - asio::error_code ec; - const protocol_type protocol = endpoint.protocol(); - this->get_service().open(this->get_implementation(), protocol, ec); - asio::detail::throw_error(ec, "open"); - if (reuse_addr) - { - this->get_service().set_option(this->get_implementation(), - socket_base::reuse_address(true), ec); - asio::detail::throw_error(ec, "set_option"); - } - this->get_service().bind(this->get_implementation(), endpoint, ec); - asio::detail::throw_error(ec, "bind"); - this->get_service().listen(this->get_implementation(), - socket_base::max_listen_connections, ec); - asio::detail::throw_error(ec, "listen"); - } - - /// Construct a basic_socket_acceptor on an existing native acceptor. - /** - * This constructor creates an acceptor object to hold an existing native - * acceptor. - * - * @param io_context The io_context object that the acceptor will use to - * dispatch handlers for any asynchronous operations performed on the - * acceptor. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @param native_acceptor A native acceptor. - * - * @throws asio::system_error Thrown on failure. - */ - basic_socket_acceptor(asio::io_context& io_context, - const protocol_type& protocol, const native_handle_type& native_acceptor) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - protocol, native_acceptor, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_socket_acceptor from another. - /** - * This constructor moves an acceptor from one object to another. - * - * @param other The other basic_socket_acceptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket_acceptor(io_context&) constructor. - */ - basic_socket_acceptor(basic_socket_acceptor&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign a basic_socket_acceptor from another. - /** - * This assignment operator moves an acceptor from one object to another. - * - * @param other The other basic_socket_acceptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket_acceptor(io_context&) constructor. - */ - basic_socket_acceptor& operator=(basic_socket_acceptor&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } - - // All socket acceptors have access to each other's implementations. - template - friend class basic_socket_acceptor; - - /// Move-construct a basic_socket_acceptor from an acceptor of another - /// protocol type. - /** - * This constructor moves an acceptor from one object to another. - * - * @param other The other basic_socket_acceptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket(io_context&) constructor. - */ - template - basic_socket_acceptor( - basic_socket_acceptor&& other, - typename enable_if::value>::type* = 0) - : basic_io_object( - other.get_service(), other.get_implementation()) - { - } - - /// Move-assign a basic_socket_acceptor from an acceptor of another protocol - /// type. - /** - * This assignment operator moves an acceptor from one object to another. - * - * @param other The other basic_socket_acceptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_socket(io_context&) constructor. - */ - template - typename enable_if::value, - basic_socket_acceptor>::type& operator=( - basic_socket_acceptor&& other) - { - basic_socket_acceptor tmp(std::move(other)); - basic_io_object::operator=(std::move(tmp)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the acceptor. - /** - * This function destroys the acceptor, cancelling any outstanding - * asynchronous operations associated with the acceptor as if by calling - * @c cancel. - */ - ~basic_socket_acceptor() - { - } - -#if defined(ASIO_ENABLE_OLD_SERVICES) - // These functions are provided by basic_io_object<>. -#else // defined(ASIO_ENABLE_OLD_SERVICES) -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - - /// Open the acceptor using the specified protocol. - /** - * This function opens the socket acceptor so that it will use the specified - * protocol. - * - * @param protocol An object specifying which protocol is to be used. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * acceptor.open(asio::ip::tcp::v4()); - * @endcode - */ - void open(const protocol_type& protocol = protocol_type()) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), protocol, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Open the acceptor using the specified protocol. - /** - * This function opens the socket acceptor so that it will use the specified - * protocol. - * - * @param protocol An object specifying which protocol is to be used. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * asio::error_code ec; - * acceptor.open(asio::ip::tcp::v4(), ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID open(const protocol_type& protocol, - asio::error_code& ec) - { - this->get_service().open(this->get_implementation(), protocol, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assigns an existing native acceptor to the acceptor. - /* - * This function opens the acceptor to hold an existing native acceptor. - * - * @param protocol An object specifying which protocol is to be used. - * - * @param native_acceptor A native acceptor. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const protocol_type& protocol, - const native_handle_type& native_acceptor) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - protocol, native_acceptor, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assigns an existing native acceptor to the acceptor. - /* - * This function opens the acceptor to hold an existing native acceptor. - * - * @param protocol An object specifying which protocol is to be used. - * - * @param native_acceptor A native acceptor. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const protocol_type& protocol, - const native_handle_type& native_acceptor, asio::error_code& ec) - { - this->get_service().assign(this->get_implementation(), - protocol, native_acceptor, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the acceptor is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Bind the acceptor to the given local endpoint. - /** - * This function binds the socket acceptor to the specified endpoint on the - * local machine. - * - * @param endpoint An endpoint on the local machine to which the socket - * acceptor will be bound. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * asio::ip::tcp::endpoint endpoint(asio::ip::tcp::v4(), 12345); - * acceptor.open(endpoint.protocol()); - * acceptor.bind(endpoint); - * @endcode - */ - void bind(const endpoint_type& endpoint) - { - asio::error_code ec; - this->get_service().bind(this->get_implementation(), endpoint, ec); - asio::detail::throw_error(ec, "bind"); - } - - /// Bind the acceptor to the given local endpoint. - /** - * This function binds the socket acceptor to the specified endpoint on the - * local machine. - * - * @param endpoint An endpoint on the local machine to which the socket - * acceptor will be bound. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * asio::ip::tcp::endpoint endpoint(asio::ip::tcp::v4(), 12345); - * acceptor.open(endpoint.protocol()); - * asio::error_code ec; - * acceptor.bind(endpoint, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID bind(const endpoint_type& endpoint, - asio::error_code& ec) - { - this->get_service().bind(this->get_implementation(), endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Place the acceptor into the state where it will listen for new - /// connections. - /** - * This function puts the socket acceptor into the state where it may accept - * new connections. - * - * @param backlog The maximum length of the queue of pending connections. - * - * @throws asio::system_error Thrown on failure. - */ - void listen(int backlog = socket_base::max_listen_connections) - { - asio::error_code ec; - this->get_service().listen(this->get_implementation(), backlog, ec); - asio::detail::throw_error(ec, "listen"); - } - - /// Place the acceptor into the state where it will listen for new - /// connections. - /** - * This function puts the socket acceptor into the state where it may accept - * new connections. - * - * @param backlog The maximum length of the queue of pending connections. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::error_code ec; - * acceptor.listen(asio::socket_base::max_listen_connections, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID listen(int backlog, asio::error_code& ec) - { - this->get_service().listen(this->get_implementation(), backlog, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Close the acceptor. - /** - * This function is used to close the acceptor. Any asynchronous accept - * operations will be cancelled immediately. - * - * A subsequent call to open() is required before the acceptor can again be - * used to again perform socket accept operations. - * - * @throws asio::system_error Thrown on failure. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the acceptor. - /** - * This function is used to close the acceptor. Any asynchronous accept - * operations will be cancelled immediately. - * - * A subsequent call to open() is required before the acceptor can again be - * used to again perform socket accept operations. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::error_code ec; - * acceptor.close(ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Release ownership of the underlying native acceptor. - /** - * This function causes all outstanding asynchronous accept operations to - * finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. Ownership of the - * native acceptor is then transferred to the caller. - * - * @throws asio::system_error Thrown on failure. - * - * @note This function is unsupported on Windows versions prior to Windows - * 8.1, and will fail with asio::error::operation_not_supported on - * these platforms. - */ -#if defined(ASIO_MSVC) && (ASIO_MSVC >= 1400) \ - && (!defined(_WIN32_WINNT) || _WIN32_WINNT < 0x0603) - __declspec(deprecated("This function always fails with " - "operation_not_supported when used on Windows versions " - "prior to Windows 8.1.")) -#endif - native_handle_type release() - { - asio::error_code ec; - native_handle_type s = this->get_service().release( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "release"); - return s; - } - - /// Release ownership of the underlying native acceptor. - /** - * This function causes all outstanding asynchronous accept operations to - * finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. Ownership of the - * native acceptor is then transferred to the caller. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note This function is unsupported on Windows versions prior to Windows - * 8.1, and will fail with asio::error::operation_not_supported on - * these platforms. - */ -#if defined(ASIO_MSVC) && (ASIO_MSVC >= 1400) \ - && (!defined(_WIN32_WINNT) || _WIN32_WINNT < 0x0603) - __declspec(deprecated("This function always fails with " - "operation_not_supported when used on Windows versions " - "prior to Windows 8.1.")) -#endif - native_handle_type release(asio::error_code& ec) - { - return this->get_service().release(this->get_implementation(), ec); - } - - /// Get the native acceptor representation. - /** - * This function may be used to obtain the underlying representation of the - * acceptor. This is intended to allow access to native acceptor functionality - * that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the acceptor. - /** - * This function causes all outstanding asynchronous connect, send and receive - * operations to finish immediately, and the handlers for cancelled operations - * will be passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the acceptor. - /** - * This function causes all outstanding asynchronous connect, send and receive - * operations to finish immediately, and the handlers for cancelled operations - * will be passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Set an option on the acceptor. - /** - * This function is used to set an option on the acceptor. - * - * @param option The new option value to be set on the acceptor. - * - * @throws asio::system_error Thrown on failure. - * - * @sa SettableSocketOption @n - * asio::socket_base::reuse_address - * asio::socket_base::enable_connection_aborted - * - * @par Example - * Setting the SOL_SOCKET/SO_REUSEADDR option: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::acceptor::reuse_address option(true); - * acceptor.set_option(option); - * @endcode - */ - template - void set_option(const SettableSocketOption& option) - { - asio::error_code ec; - this->get_service().set_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "set_option"); - } - - /// Set an option on the acceptor. - /** - * This function is used to set an option on the acceptor. - * - * @param option The new option value to be set on the acceptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa SettableSocketOption @n - * asio::socket_base::reuse_address - * asio::socket_base::enable_connection_aborted - * - * @par Example - * Setting the SOL_SOCKET/SO_REUSEADDR option: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::acceptor::reuse_address option(true); - * asio::error_code ec; - * acceptor.set_option(option, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - template - ASIO_SYNC_OP_VOID set_option(const SettableSocketOption& option, - asio::error_code& ec) - { - this->get_service().set_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get an option from the acceptor. - /** - * This function is used to get the current value of an option on the - * acceptor. - * - * @param option The option value to be obtained from the acceptor. - * - * @throws asio::system_error Thrown on failure. - * - * @sa GettableSocketOption @n - * asio::socket_base::reuse_address - * - * @par Example - * Getting the value of the SOL_SOCKET/SO_REUSEADDR option: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::acceptor::reuse_address option; - * acceptor.get_option(option); - * bool is_set = option.get(); - * @endcode - */ - template - void get_option(GettableSocketOption& option) const - { - asio::error_code ec; - this->get_service().get_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "get_option"); - } - - /// Get an option from the acceptor. - /** - * This function is used to get the current value of an option on the - * acceptor. - * - * @param option The option value to be obtained from the acceptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa GettableSocketOption @n - * asio::socket_base::reuse_address - * - * @par Example - * Getting the value of the SOL_SOCKET/SO_REUSEADDR option: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::acceptor::reuse_address option; - * asio::error_code ec; - * acceptor.get_option(option, ec); - * if (ec) - * { - * // An error occurred. - * } - * bool is_set = option.get(); - * @endcode - */ - template - ASIO_SYNC_OP_VOID get_option(GettableSocketOption& option, - asio::error_code& ec) const - { - this->get_service().get_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the acceptor. - /** - * This function is used to execute an IO control command on the acceptor. - * - * @param command The IO control command to be performed on the acceptor. - * - * @throws asio::system_error Thrown on failure. - * - * @sa IoControlCommand @n - * asio::socket_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::acceptor::non_blocking_io command(true); - * socket.io_control(command); - * @endcode - */ - template - void io_control(IoControlCommand& command) - { - asio::error_code ec; - this->get_service().io_control(this->get_implementation(), command, ec); - asio::detail::throw_error(ec, "io_control"); - } - - /// Perform an IO control command on the acceptor. - /** - * This function is used to execute an IO control command on the acceptor. - * - * @param command The IO control command to be performed on the acceptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa IoControlCommand @n - * asio::socket_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::acceptor::non_blocking_io command(true); - * asio::error_code ec; - * socket.io_control(command, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - template - ASIO_SYNC_OP_VOID io_control(IoControlCommand& command, - asio::error_code& ec) - { - this->get_service().io_control(this->get_implementation(), command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the acceptor. - /** - * @returns @c true if the acceptor's synchronous operations will fail with - * asio::error::would_block if they are unable to perform the requested - * operation immediately. If @c false, synchronous operations will block - * until complete. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - bool non_blocking() const - { - return this->get_service().non_blocking(this->get_implementation()); - } - - /// Sets the non-blocking mode of the acceptor. - /** - * @param mode If @c true, the acceptor's synchronous operations will fail - * with asio::error::would_block if they are unable to perform the - * requested operation immediately. If @c false, synchronous operations will - * block until complete. - * - * @throws asio::system_error Thrown on failure. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - void non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().non_blocking(this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "non_blocking"); - } - - /// Sets the non-blocking mode of the acceptor. - /** - * @param mode If @c true, the acceptor's synchronous operations will fail - * with asio::error::would_block if they are unable to perform the - * requested operation immediately. If @c false, synchronous operations will - * block until complete. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - ASIO_SYNC_OP_VOID non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().non_blocking(this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native acceptor implementation. - /** - * This function is used to retrieve the non-blocking mode of the underlying - * native acceptor. This mode has no effect on the behaviour of the acceptor - * object's synchronous operations. - * - * @returns @c true if the underlying acceptor is in non-blocking mode and - * direct system calls may fail with asio::error::would_block (or the - * equivalent system error). - * - * @note The current non-blocking mode is cached by the acceptor object. - * Consequently, the return value may be incorrect if the non-blocking mode - * was set directly on the native acceptor. - */ - bool native_non_blocking() const - { - return this->get_service().native_non_blocking(this->get_implementation()); - } - - /// Sets the non-blocking mode of the native acceptor implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native acceptor. It has no effect on the behaviour of the acceptor object's - * synchronous operations. - * - * @param mode If @c true, the underlying acceptor is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @throws asio::system_error Thrown on failure. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - */ - void native_non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "native_non_blocking"); - } - - /// Sets the non-blocking mode of the native acceptor implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native acceptor. It has no effect on the behaviour of the acceptor object's - * synchronous operations. - * - * @param mode If @c true, the underlying acceptor is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @param ec Set to indicate what error occurred, if any. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - */ - ASIO_SYNC_OP_VOID native_non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the local endpoint of the acceptor. - /** - * This function is used to obtain the locally bound endpoint of the acceptor. - * - * @returns An object that represents the local endpoint of the acceptor. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::endpoint endpoint = acceptor.local_endpoint(); - * @endcode - */ - endpoint_type local_endpoint() const - { - asio::error_code ec; - endpoint_type ep = this->get_service().local_endpoint( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "local_endpoint"); - return ep; - } - - /// Get the local endpoint of the acceptor. - /** - * This function is used to obtain the locally bound endpoint of the acceptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns An object that represents the local endpoint of the acceptor. - * Returns a default-constructed endpoint object if an error occurred and the - * error handler did not throw an exception. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::error_code ec; - * asio::ip::tcp::endpoint endpoint = acceptor.local_endpoint(ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - endpoint_type local_endpoint(asio::error_code& ec) const - { - return this->get_service().local_endpoint(this->get_implementation(), ec); - } - - /// Wait for the acceptor to become ready to read, ready to write, or to have - /// pending error conditions. - /** - * This function is used to perform a blocking wait for an acceptor to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired acceptor state. - * - * @par Example - * Waiting for an acceptor to become readable. - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * acceptor.wait(asio::ip::tcp::acceptor::wait_read); - * @endcode - */ - void wait(wait_type w) - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), w, ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Wait for the acceptor to become ready to read, ready to write, or to have - /// pending error conditions. - /** - * This function is used to perform a blocking wait for an acceptor to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired acceptor state. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * Waiting for an acceptor to become readable. - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::error_code ec; - * acceptor.wait(asio::ip::tcp::acceptor::wait_read, ec); - * @endcode - */ - ASIO_SYNC_OP_VOID wait(wait_type w, asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the acceptor to become ready to read, ready to - /// write, or to have pending error conditions. - /** - * This function is used to perform an asynchronous wait for an acceptor to - * enter a ready to read, write or error condition state. - * - * @param w Specifies the desired acceptor state. - * - * @param handler The handler to be called when the wait operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void wait_handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Wait succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * acceptor.async_wait( - * asio::ip::tcp::acceptor::wait_read, - * wait_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(wait_type w, ASIO_MOVE_ARG(WaitHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WaitHandler. - ASIO_WAIT_HANDLER_CHECK(WaitHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_wait(this->get_implementation(), - w, ASIO_MOVE_CAST(WaitHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_wait(this->get_implementation(), - w, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - -#if !defined(ASIO_NO_EXTENSIONS) - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer into the - * given socket. The function call will block until a new connection has been - * accepted successfully or an error occurs. - * - * @param peer The socket into which the new connection will be accepted. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(io_context); - * acceptor.accept(socket); - * @endcode - */ -#if defined(ASIO_ENABLE_OLD_SERVICES) - template - void accept(basic_socket& peer, - typename enable_if::value>::type* = 0) -#else // defined(ASIO_ENABLE_OLD_SERVICES) - template - void accept(basic_socket& peer, - typename enable_if::value>::type* = 0) -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - { - asio::error_code ec; - this->get_service().accept(this->get_implementation(), - peer, static_cast(0), ec); - asio::detail::throw_error(ec, "accept"); - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer into the - * given socket. The function call will block until a new connection has been - * accepted successfully or an error occurs. - * - * @param peer The socket into which the new connection will be accepted. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(io_context); - * asio::error_code ec; - * acceptor.accept(socket, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ -#if defined(ASIO_ENABLE_OLD_SERVICES) - template - ASIO_SYNC_OP_VOID accept( - basic_socket& peer, - asio::error_code& ec, - typename enable_if::value>::type* = 0) -#else // defined(ASIO_ENABLE_OLD_SERVICES) - template - ASIO_SYNC_OP_VOID accept( - basic_socket& peer, asio::error_code& ec, - typename enable_if::value>::type* = 0) -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - { - this->get_service().accept(this->get_implementation(), - peer, static_cast(0), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous accept. - /** - * This function is used to asynchronously accept a new connection into a - * socket. The function call always returns immediately. - * - * @param peer The socket into which the new connection will be accepted. - * Ownership of the peer object is retained by the caller, which must - * guarantee that it is valid until the handler is called. - * - * @param handler The handler to be called when the accept operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void accept_handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Accept succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(io_context); - * acceptor.async_accept(socket, accept_handler); - * @endcode - */ -#if defined(ASIO_ENABLE_OLD_SERVICES) - template - ASIO_INITFN_RESULT_TYPE(AcceptHandler, - void (asio::error_code)) - async_accept(basic_socket& peer, - ASIO_MOVE_ARG(AcceptHandler) handler, - typename enable_if::value>::type* = 0) -#else // defined(ASIO_ENABLE_OLD_SERVICES) - template - ASIO_INITFN_RESULT_TYPE(AcceptHandler, - void (asio::error_code)) - async_accept(basic_socket& peer, - ASIO_MOVE_ARG(AcceptHandler) handler, - typename enable_if::value>::type* = 0) -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a AcceptHandler. - ASIO_ACCEPT_HANDLER_CHECK(AcceptHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_accept(this->get_implementation(), - peer, static_cast(0), - ASIO_MOVE_CAST(AcceptHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_accept(this->get_implementation(), - peer, static_cast(0), init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Accept a new connection and obtain the endpoint of the peer - /** - * This function is used to accept a new connection from a peer into the - * given socket, and additionally provide the endpoint of the remote peer. - * The function call will block until a new connection has been accepted - * successfully or an error occurs. - * - * @param peer The socket into which the new connection will be accepted. - * - * @param peer_endpoint An endpoint object which will receive the endpoint of - * the remote peer. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(io_context); - * asio::ip::tcp::endpoint endpoint; - * acceptor.accept(socket, endpoint); - * @endcode - */ -#if defined(ASIO_ENABLE_OLD_SERVICES) - template - void accept(basic_socket& peer, - endpoint_type& peer_endpoint) -#else // defined(ASIO_ENABLE_OLD_SERVICES) - void accept(basic_socket& peer, endpoint_type& peer_endpoint) -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - { - asio::error_code ec; - this->get_service().accept(this->get_implementation(), - peer, &peer_endpoint, ec); - asio::detail::throw_error(ec, "accept"); - } - - /// Accept a new connection and obtain the endpoint of the peer - /** - * This function is used to accept a new connection from a peer into the - * given socket, and additionally provide the endpoint of the remote peer. - * The function call will block until a new connection has been accepted - * successfully or an error occurs. - * - * @param peer The socket into which the new connection will be accepted. - * - * @param peer_endpoint An endpoint object which will receive the endpoint of - * the remote peer. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(io_context); - * asio::ip::tcp::endpoint endpoint; - * asio::error_code ec; - * acceptor.accept(socket, endpoint, ec); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ -#if defined(ASIO_ENABLE_OLD_SERVICES) - template - ASIO_SYNC_OP_VOID accept( - basic_socket& peer, - endpoint_type& peer_endpoint, asio::error_code& ec) -#else // defined(ASIO_ENABLE_OLD_SERVICES) - ASIO_SYNC_OP_VOID accept(basic_socket& peer, - endpoint_type& peer_endpoint, asio::error_code& ec) -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - { - this->get_service().accept( - this->get_implementation(), peer, &peer_endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous accept. - /** - * This function is used to asynchronously accept a new connection into a - * socket, and additionally obtain the endpoint of the remote peer. The - * function call always returns immediately. - * - * @param peer The socket into which the new connection will be accepted. - * Ownership of the peer object is retained by the caller, which must - * guarantee that it is valid until the handler is called. - * - * @param peer_endpoint An endpoint object into which the endpoint of the - * remote peer will be written. Ownership of the peer_endpoint object is - * retained by the caller, which must guarantee that it is valid until the - * handler is called. - * - * @param handler The handler to be called when the accept operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -#if defined(ASIO_ENABLE_OLD_SERVICES) - template - ASIO_INITFN_RESULT_TYPE(AcceptHandler, - void (asio::error_code)) - async_accept(basic_socket& peer, - endpoint_type& peer_endpoint, ASIO_MOVE_ARG(AcceptHandler) handler) -#else // defined(ASIO_ENABLE_OLD_SERVICES) - template - ASIO_INITFN_RESULT_TYPE(AcceptHandler, - void (asio::error_code)) - async_accept(basic_socket& peer, - endpoint_type& peer_endpoint, ASIO_MOVE_ARG(AcceptHandler) handler) -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a AcceptHandler. - ASIO_ACCEPT_HANDLER_CHECK(AcceptHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_accept(this->get_implementation(), peer, - &peer_endpoint, ASIO_MOVE_CAST(AcceptHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_accept(this->get_implementation(), - peer, &peer_endpoint, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -#endif // !defined(ASIO_NO_EXTENSIONS) - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @returns A socket object representing the newly accepted connection. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(acceptor.accept()); - * @endcode - */ - typename Protocol::socket accept() - { - asio::error_code ec; - typename Protocol::socket peer( - this->get_service().accept( - this->get_implementation(), 0, 0, ec)); - asio::detail::throw_error(ec, "accept"); - return peer; - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns On success, a socket object representing the newly accepted - * connection. On error, a socket object where is_open() is false. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(acceptor.accept(ec)); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - typename Protocol::socket accept(asio::error_code& ec) - { - return this->get_service().accept(this->get_implementation(), 0, 0, ec); - } - - /// Start an asynchronous accept. - /** - * This function is used to asynchronously accept a new connection. The - * function call always returns immediately. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param handler The handler to be called when the accept operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * typename Protocol::socket peer // On success, the newly accepted socket. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void accept_handler(const asio::error_code& error, - * asio::ip::tcp::socket peer) - * { - * if (!error) - * { - * // Accept succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * acceptor.async_accept(accept_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(MoveAcceptHandler, - void (asio::error_code, typename Protocol::socket)) - async_accept(ASIO_MOVE_ARG(MoveAcceptHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a MoveAcceptHandler. - ASIO_MOVE_ACCEPT_HANDLER_CHECK(MoveAcceptHandler, - handler, typename Protocol::socket) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_accept( - this->get_implementation(), static_cast(0), - static_cast(0), - ASIO_MOVE_CAST(MoveAcceptHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_accept( - this->get_implementation(), static_cast(0), - static_cast(0), init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param io_context The io_context object to be used for the newly accepted - * socket. - * - * @returns A socket object representing the newly accepted connection. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(acceptor.accept()); - * @endcode - */ - typename Protocol::socket accept(asio::io_context& io_context) - { - asio::error_code ec; - typename Protocol::socket peer( - this->get_service().accept(this->get_implementation(), - &io_context, static_cast(0), ec)); - asio::detail::throw_error(ec, "accept"); - return peer; - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param io_context The io_context object to be used for the newly accepted - * socket. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns On success, a socket object representing the newly accepted - * connection. On error, a socket object where is_open() is false. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::socket socket(acceptor.accept(io_context2, ec)); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - typename Protocol::socket accept( - asio::io_context& io_context, asio::error_code& ec) - { - return this->get_service().accept(this->get_implementation(), - &io_context, static_cast(0), ec); - } - - /// Start an asynchronous accept. - /** - * This function is used to asynchronously accept a new connection. The - * function call always returns immediately. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param io_context The io_context object to be used for the newly accepted - * socket. - * - * @param handler The handler to be called when the accept operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * typename Protocol::socket peer // On success, the newly accepted socket. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void accept_handler(const asio::error_code& error, - * asio::ip::tcp::socket peer) - * { - * if (!error) - * { - * // Accept succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * acceptor.async_accept(io_context2, accept_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(MoveAcceptHandler, - void (asio::error_code, typename Protocol::socket)) - async_accept(asio::io_context& io_context, - ASIO_MOVE_ARG(MoveAcceptHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a MoveAcceptHandler. - ASIO_MOVE_ACCEPT_HANDLER_CHECK(MoveAcceptHandler, - handler, typename Protocol::socket) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_accept(this->get_implementation(), - &io_context, static_cast(0), - ASIO_MOVE_CAST(MoveAcceptHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_accept(this->get_implementation(), - &io_context, static_cast(0), init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param peer_endpoint An endpoint object into which the endpoint of the - * remote peer will be written. - * - * @returns A socket object representing the newly accepted connection. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::endpoint endpoint; - * asio::ip::tcp::socket socket(acceptor.accept(endpoint)); - * @endcode - */ - typename Protocol::socket accept(endpoint_type& peer_endpoint) - { - asio::error_code ec; - typename Protocol::socket peer( - this->get_service().accept(this->get_implementation(), - static_cast(0), &peer_endpoint, ec)); - asio::detail::throw_error(ec, "accept"); - return peer; - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param peer_endpoint An endpoint object into which the endpoint of the - * remote peer will be written. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns On success, a socket object representing the newly accepted - * connection. On error, a socket object where is_open() is false. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::endpoint endpoint; - * asio::ip::tcp::socket socket(acceptor.accept(endpoint, ec)); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - typename Protocol::socket accept( - endpoint_type& peer_endpoint, asio::error_code& ec) - { - return this->get_service().accept(this->get_implementation(), - static_cast(0), &peer_endpoint, ec); - } - - /// Start an asynchronous accept. - /** - * This function is used to asynchronously accept a new connection. The - * function call always returns immediately. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param peer_endpoint An endpoint object into which the endpoint of the - * remote peer will be written. Ownership of the peer_endpoint object is - * retained by the caller, which must guarantee that it is valid until the - * handler is called. - * - * @param handler The handler to be called when the accept operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * typename Protocol::socket peer // On success, the newly accepted socket. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void accept_handler(const asio::error_code& error, - * asio::ip::tcp::socket peer) - * { - * if (!error) - * { - * // Accept succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::endpoint endpoint; - * acceptor.async_accept(endpoint, accept_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(MoveAcceptHandler, - void (asio::error_code, typename Protocol::socket)) - async_accept(endpoint_type& peer_endpoint, - ASIO_MOVE_ARG(MoveAcceptHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a MoveAcceptHandler. - ASIO_MOVE_ACCEPT_HANDLER_CHECK(MoveAcceptHandler, - handler, typename Protocol::socket) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_accept(this->get_implementation(), - static_cast(0), &peer_endpoint, - ASIO_MOVE_CAST(MoveAcceptHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_accept(this->get_implementation(), - static_cast(0), &peer_endpoint, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param io_context The io_context object to be used for the newly accepted - * socket. - * - * @param peer_endpoint An endpoint object into which the endpoint of the - * remote peer will be written. - * - * @returns A socket object representing the newly accepted connection. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::endpoint endpoint; - * asio::ip::tcp::socket socket( - * acceptor.accept(io_context2, endpoint)); - * @endcode - */ - typename Protocol::socket accept( - asio::io_context& io_context, endpoint_type& peer_endpoint) - { - asio::error_code ec; - typename Protocol::socket peer( - this->get_service().accept(this->get_implementation(), - &io_context, &peer_endpoint, ec)); - asio::detail::throw_error(ec, "accept"); - return peer; - } - - /// Accept a new connection. - /** - * This function is used to accept a new connection from a peer. The function - * call will block until a new connection has been accepted successfully or - * an error occurs. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param io_context The io_context object to be used for the newly accepted - * socket. - * - * @param peer_endpoint An endpoint object into which the endpoint of the - * remote peer will be written. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns On success, a socket object representing the newly accepted - * connection. On error, a socket object where is_open() is false. - * - * @par Example - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::endpoint endpoint; - * asio::ip::tcp::socket socket( - * acceptor.accept(io_context2, endpoint, ec)); - * if (ec) - * { - * // An error occurred. - * } - * @endcode - */ - typename Protocol::socket accept(asio::io_context& io_context, - endpoint_type& peer_endpoint, asio::error_code& ec) - { - return this->get_service().accept(this->get_implementation(), - &io_context, &peer_endpoint, ec); - } - - /// Start an asynchronous accept. - /** - * This function is used to asynchronously accept a new connection. The - * function call always returns immediately. - * - * This overload requires that the Protocol template parameter satisfy the - * AcceptableProtocol type requirements. - * - * @param io_context The io_context object to be used for the newly accepted - * socket. - * - * @param peer_endpoint An endpoint object into which the endpoint of the - * remote peer will be written. Ownership of the peer_endpoint object is - * retained by the caller, which must guarantee that it is valid until the - * handler is called. - * - * @param handler The handler to be called when the accept operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * typename Protocol::socket peer // On success, the newly accepted socket. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void accept_handler(const asio::error_code& error, - * asio::ip::tcp::socket peer) - * { - * if (!error) - * { - * // Accept succeeded. - * } - * } - * - * ... - * - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::ip::tcp::endpoint endpoint; - * acceptor.async_accept(io_context2, endpoint, accept_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(MoveAcceptHandler, - void (asio::error_code, typename Protocol::socket)) - async_accept(asio::io_context& io_context, - endpoint_type& peer_endpoint, - ASIO_MOVE_ARG(MoveAcceptHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a MoveAcceptHandler. - ASIO_MOVE_ACCEPT_HANDLER_CHECK(MoveAcceptHandler, - handler, typename Protocol::socket) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_accept( - this->get_implementation(), &io_context, &peer_endpoint, - ASIO_MOVE_CAST(MoveAcceptHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_accept(this->get_implementation(), - &io_context, &peer_endpoint, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# undef ASIO_SVC_T -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_BASIC_SOCKET_ACCEPTOR_HPP diff --git a/scout_sdk/asio/asio/basic_socket_iostream.hpp b/scout_sdk/asio/asio/basic_socket_iostream.hpp deleted file mode 100644 index 6681367..0000000 --- a/scout_sdk/asio/asio/basic_socket_iostream.hpp +++ /dev/null @@ -1,430 +0,0 @@ -// -// basic_socket_iostream.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_SOCKET_IOSTREAM_HPP -#define ASIO_BASIC_SOCKET_IOSTREAM_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_NO_IOSTREAM) - -#include -#include -#include "asio/basic_socket_streambuf.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/stream_socket_service.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#if !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -# include "asio/detail/variadic_templates.hpp" - -// A macro that should expand to: -// template -// explicit basic_socket_iostream(T1 x1, ..., Tn xn) -// : std::basic_iostream( -// &this->detail::socket_iostream_base< -// Protocol ASIO_SVC_TARG, Clock, -// WaitTraits ASIO_SVC_TARG1>::streambuf_) -// { -// if (rdbuf()->connect(x1, ..., xn) == 0) -// this->setstate(std::ios_base::failbit); -// } -// This macro should only persist within this file. - -# define ASIO_PRIVATE_CTR_DEF(n) \ - template \ - explicit basic_socket_iostream(ASIO_VARIADIC_BYVAL_PARAMS(n)) \ - : std::basic_iostream( \ - &this->detail::socket_iostream_base< \ - Protocol ASIO_SVC_TARG, Clock, \ - WaitTraits ASIO_SVC_TARG1>::streambuf_) \ - { \ - this->setf(std::ios_base::unitbuf); \ - if (rdbuf()->connect(ASIO_VARIADIC_BYVAL_ARGS(n)) == 0) \ - this->setstate(std::ios_base::failbit); \ - } \ - /**/ - -// A macro that should expand to: -// template -// void connect(T1 x1, ..., Tn xn) -// { -// if (rdbuf()->connect(x1, ..., xn) == 0) -// this->setstate(std::ios_base::failbit); -// } -// This macro should only persist within this file. - -# define ASIO_PRIVATE_CONNECT_DEF(n) \ - template \ - void connect(ASIO_VARIADIC_BYVAL_PARAMS(n)) \ - { \ - if (rdbuf()->connect(ASIO_VARIADIC_BYVAL_ARGS(n)) == 0) \ - this->setstate(std::ios_base::failbit); \ - } \ - /**/ - -#endif // !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// A separate base class is used to ensure that the streambuf is initialised -// prior to the basic_socket_iostream's basic_iostream base class. -template -class socket_iostream_base -{ -protected: - socket_iostream_base() - { - } - -#if defined(ASIO_HAS_MOVE) - socket_iostream_base(socket_iostream_base&& other) - : streambuf_(std::move(other.streambuf_)) - { - } - - socket_iostream_base(basic_stream_socket s) - : streambuf_(std::move(s)) - { - } - - socket_iostream_base& operator=(socket_iostream_base&& other) - { - streambuf_ = std::move(other.streambuf_); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - basic_socket_streambuf streambuf_; -}; - -} // namespace detail - -#if !defined(ASIO_BASIC_SOCKET_IOSTREAM_FWD_DECL) -#define ASIO_BASIC_SOCKET_IOSTREAM_FWD_DECL - -// Forward declaration with defaulted arguments. -template ), -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typename Clock = boost::posix_time::ptime, - typename WaitTraits = time_traits - ASIO_SVC_TPARAM1_DEF2(= deadline_timer_service)> -#else // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typename Clock = chrono::steady_clock, - typename WaitTraits = wait_traits - ASIO_SVC_TPARAM1_DEF1(= steady_timer::service_type)> -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) -class basic_socket_iostream; - -#endif // !defined(ASIO_BASIC_SOCKET_IOSTREAM_FWD_DECL) - -/// Iostream interface for a socket. -#if defined(GENERATING_DOCUMENTATION) -template > -#else // defined(GENERATING_DOCUMENTATION) -template -#endif // defined(GENERATING_DOCUMENTATION) -class basic_socket_iostream - : private detail::socket_iostream_base, - public std::basic_iostream -{ -private: - // These typedefs are intended keep this class's implementation independent - // of whether it's using Boost.DateClock, Boost.Chrono or std::chrono. -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typedef WaitTraits traits_helper; -#else // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typedef detail::chrono_time_traits traits_helper; -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - -public: - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - /// The clock type. - typedef Clock clock_type; - -#if defined(GENERATING_DOCUMENTATION) - /// (Deprecated: Use time_point.) The time type. - typedef typename WaitTraits::time_type time_type; - - /// The time type. - typedef typename WaitTraits::time_point time_point; - - /// (Deprecated: Use duration.) The duration type. - typedef typename WaitTraits::duration_type duration_type; - - /// The duration type. - typedef typename WaitTraits::duration duration; -#else -# if !defined(ASIO_NO_DEPRECATED) - typedef typename traits_helper::time_type time_type; - typedef typename traits_helper::duration_type duration_type; -# endif // !defined(ASIO_NO_DEPRECATED) - typedef typename traits_helper::time_type time_point; - typedef typename traits_helper::duration_type duration; -#endif - - /// Construct a basic_socket_iostream without establishing a connection. - basic_socket_iostream() - : std::basic_iostream( - &this->detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>::streambuf_) - { - this->setf(std::ios_base::unitbuf); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Construct a basic_socket_iostream from the supplied socket. - explicit basic_socket_iostream(basic_stream_socket s) - : detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>(std::move(s)), - std::basic_iostream( - &this->detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>::streambuf_) - { - this->setf(std::ios_base::unitbuf); - } - -#if defined(ASIO_HAS_STD_IOSTREAM_MOVE) \ - || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_socket_iostream from another. - basic_socket_iostream(basic_socket_iostream&& other) - : detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>(std::move(other)), - std::basic_iostream(std::move(other)) - { - this->set_rdbuf(&this->detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>::streambuf_); - } - - /// Move-assign a basic_socket_iostream from another. - basic_socket_iostream& operator=(basic_socket_iostream&& other) - { - std::basic_iostream::operator=(std::move(other)); - detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_STD_IOSTREAM_MOVE) - // || defined(GENERATING_DOCUMENTATION) -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - -#if defined(GENERATING_DOCUMENTATION) - /// Establish a connection to an endpoint corresponding to a resolver query. - /** - * This constructor automatically establishes a connection based on the - * supplied resolver query parameters. The arguments are used to construct - * a resolver query object. - */ - template - explicit basic_socket_iostream(T1 t1, ..., TN tn); -#elif defined(ASIO_HAS_VARIADIC_TEMPLATES) - template - explicit basic_socket_iostream(T... x) - : std::basic_iostream( - &this->detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>::streambuf_) - { - this->setf(std::ios_base::unitbuf); - if (rdbuf()->connect(x...) == 0) - this->setstate(std::ios_base::failbit); - } -#else - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_CTR_DEF) -#endif - -#if defined(GENERATING_DOCUMENTATION) - /// Establish a connection to an endpoint corresponding to a resolver query. - /** - * This function automatically establishes a connection based on the supplied - * resolver query parameters. The arguments are used to construct a resolver - * query object. - */ - template - void connect(T1 t1, ..., TN tn); -#elif defined(ASIO_HAS_VARIADIC_TEMPLATES) - template - void connect(T... x) - { - if (rdbuf()->connect(x...) == 0) - this->setstate(std::ios_base::failbit); - } -#else - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_CONNECT_DEF) -#endif - - /// Close the connection. - void close() - { - if (rdbuf()->close() == 0) - this->setstate(std::ios_base::failbit); - } - - /// Return a pointer to the underlying streambuf. - basic_socket_streambuf* rdbuf() const - { - return const_cast*>( - &this->detail::socket_iostream_base< - Protocol ASIO_SVC_TARG, Clock, - WaitTraits ASIO_SVC_TARG1>::streambuf_); - } - - /// Get a reference to the underlying socket. - basic_socket& socket() - { - return rdbuf()->socket(); - } - - /// Get the last error associated with the stream. - /** - * @return An \c error_code corresponding to the last error from the stream. - * - * @par Example - * To print the error associated with a failure to establish a connection: - * @code tcp::iostream s("www.boost.org", "http"); - * if (!s) - * { - * std::cout << "Error: " << s.error().message() << std::endl; - * } @endcode - */ - const asio::error_code& error() const - { - return rdbuf()->error(); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use expiry().) Get the stream's expiry time as an absolute - /// time. - /** - * @return An absolute time value representing the stream's expiry time. - */ - time_point expires_at() const - { - return rdbuf()->expires_at(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the stream's expiry time as an absolute time. - /** - * @return An absolute time value representing the stream's expiry time. - */ - time_point expiry() const - { - return rdbuf()->expiry(); - } - - /// Set the stream's expiry time as an absolute time. - /** - * This function sets the expiry time associated with the stream. Stream - * operations performed after this time (where the operations cannot be - * completed using the internal buffers) will fail with the error - * asio::error::operation_aborted. - * - * @param expiry_time The expiry time to be used for the stream. - */ - void expires_at(const time_point& expiry_time) - { - rdbuf()->expires_at(expiry_time); - } - - /// Set the stream's expiry time relative to now. - /** - * This function sets the expiry time associated with the stream. Stream - * operations performed after this time (where the operations cannot be - * completed using the internal buffers) will fail with the error - * asio::error::operation_aborted. - * - * @param expiry_time The expiry time to be used for the timer. - */ - void expires_after(const duration& expiry_time) - { - rdbuf()->expires_after(expiry_time); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use expiry().) Get the stream's expiry time relative to now. - /** - * @return A relative time value representing the stream's expiry time. - */ - duration expires_from_now() const - { - return rdbuf()->expires_from_now(); - } - - /// (Deprecated: Use expires_after().) Set the stream's expiry time relative - /// to now. - /** - * This function sets the expiry time associated with the stream. Stream - * operations performed after this time (where the operations cannot be - * completed using the internal buffers) will fail with the error - * asio::error::operation_aborted. - * - * @param expiry_time The expiry time to be used for the timer. - */ - void expires_from_now(const duration& expiry_time) - { - rdbuf()->expires_from_now(expiry_time); - } -#endif // !defined(ASIO_NO_DEPRECATED) - -private: - // Disallow copying and assignment. - basic_socket_iostream(const basic_socket_iostream&) ASIO_DELETED; - basic_socket_iostream& operator=( - const basic_socket_iostream&) ASIO_DELETED; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_HAS_VARIADIC_TEMPLATES) -# undef ASIO_PRIVATE_CTR_DEF -# undef ASIO_PRIVATE_CONNECT_DEF -#endif // !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_BASIC_SOCKET_IOSTREAM_HPP diff --git a/scout_sdk/asio/asio/basic_socket_streambuf.hpp b/scout_sdk/asio/asio/basic_socket_streambuf.hpp deleted file mode 100644 index 56a3637..0000000 --- a/scout_sdk/asio/asio/basic_socket_streambuf.hpp +++ /dev/null @@ -1,707 +0,0 @@ -// -// basic_socket_streambuf.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_SOCKET_STREAMBUF_HPP -#define ASIO_BASIC_SOCKET_STREAMBUF_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_NO_IOSTREAM) - -#include -#include -#include "asio/basic_socket.hpp" -#include "asio/basic_stream_socket.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/stream_socket_service.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) -# if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/deadline_timer_service.hpp" -# else // defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/detail/deadline_timer_service.hpp" -# endif // defined(ASIO_ENABLE_OLD_SERVICES) -#else // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) -# include "asio/steady_timer.hpp" -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - -#if !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -# include "asio/detail/variadic_templates.hpp" - -// A macro that should expand to: -// template -// basic_socket_streambuf* connect(T1 x1, ..., Tn xn) -// { -// init_buffers(); -// typedef typename Protocol::resolver resolver_type; -// resolver_type resolver(socket().get_executor().context()); -// connect_to_endpoints( -// resolver.resolve(x1, ..., xn, ec_)); -// return !ec_ ? this : 0; -// } -// This macro should only persist within this file. - -# define ASIO_PRIVATE_CONNECT_DEF(n) \ - template \ - basic_socket_streambuf* connect(ASIO_VARIADIC_BYVAL_PARAMS(n)) \ - { \ - init_buffers(); \ - typedef typename Protocol::resolver resolver_type; \ - resolver_type resolver(socket().get_executor().context()); \ - connect_to_endpoints( \ - resolver.resolve(ASIO_VARIADIC_BYVAL_ARGS(n), ec_)); \ - return !ec_ ? this : 0; \ - } \ - /**/ - -#endif // !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# define ASIO_SVC_T1 detail::deadline_timer_service -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// A separate base class is used to ensure that the io_context member is -// initialised prior to the basic_socket_streambuf's basic_socket base class. -class socket_streambuf_io_context -{ -protected: - socket_streambuf_io_context(io_context* ctx) - : default_io_context_(ctx) - { - } - - shared_ptr default_io_context_; -}; - -// A separate base class is used to ensure that the dynamically allocated -// buffers are constructed prior to the basic_socket_streambuf's basic_socket -// base class. This makes moving the socket is the last potentially throwing -// step in the streambuf's move constructor, giving the constructor a strong -// exception safety guarantee. -class socket_streambuf_buffers -{ -protected: - socket_streambuf_buffers() - : get_buffer_(buffer_size), - put_buffer_(buffer_size) - { - } - - enum { buffer_size = 512 }; - std::vector get_buffer_; - std::vector put_buffer_; -}; - -} // namespace detail - -#if !defined(ASIO_BASIC_SOCKET_STREAMBUF_FWD_DECL) -#define ASIO_BASIC_SOCKET_STREAMBUF_FWD_DECL - -// Forward declaration with defaulted arguments. -template ), -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typename Clock = boost::posix_time::ptime, - typename WaitTraits = time_traits - ASIO_SVC_TPARAM1_DEF2(= deadline_timer_service)> -#else // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typename Clock = chrono::steady_clock, - typename WaitTraits = wait_traits - ASIO_SVC_TPARAM1_DEF1(= steady_timer::service_type)> -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) -class basic_socket_streambuf; - -#endif // !defined(ASIO_BASIC_SOCKET_STREAMBUF_FWD_DECL) - -/// Iostream streambuf for a socket. -#if defined(GENERATING_DOCUMENTATION) -template > -#else // defined(GENERATING_DOCUMENTATION) -template -#endif // defined(GENERATING_DOCUMENTATION) -class basic_socket_streambuf - : public std::streambuf, - private detail::socket_streambuf_io_context, - private detail::socket_streambuf_buffers, -#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - private basic_socket -#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - public basic_socket -#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) -{ -private: - // These typedefs are intended keep this class's implementation independent - // of whether it's using Boost.DateClock, Boost.Chrono or std::chrono. -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typedef WaitTraits traits_helper; -#else // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - typedef detail::chrono_time_traits traits_helper; -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - -public: - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - /// The clock type. - typedef Clock clock_type; - -#if defined(GENERATING_DOCUMENTATION) - /// (Deprecated: Use time_point.) The time type. - typedef typename WaitTraits::time_type time_type; - - /// The time type. - typedef typename WaitTraits::time_point time_point; - - /// (Deprecated: Use duration.) The duration type. - typedef typename WaitTraits::duration_type duration_type; - - /// The duration type. - typedef typename WaitTraits::duration duration; -#else -# if !defined(ASIO_NO_DEPRECATED) - typedef typename traits_helper::time_type time_type; - typedef typename traits_helper::duration_type duration_type; -# endif // !defined(ASIO_NO_DEPRECATED) - typedef typename traits_helper::time_type time_point; - typedef typename traits_helper::duration_type duration; -#endif - - /// Construct a basic_socket_streambuf without establishing a connection. - basic_socket_streambuf() - : detail::socket_streambuf_io_context(new io_context), - basic_socket(*default_io_context_), - expiry_time_(max_expiry_time()) - { - init_buffers(); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Construct a basic_socket_streambuf from the supplied socket. - explicit basic_socket_streambuf(basic_stream_socket s) - : detail::socket_streambuf_io_context(0), - basic_socket(std::move(s)), - expiry_time_(max_expiry_time()) - { - init_buffers(); - } - - /// Move-construct a basic_socket_streambuf from another. - basic_socket_streambuf(basic_socket_streambuf&& other) - : detail::socket_streambuf_io_context(other), - basic_socket(std::move(other.socket())), - ec_(other.ec_), - expiry_time_(other.expiry_time_) - { - get_buffer_.swap(other.get_buffer_); - put_buffer_.swap(other.put_buffer_); - setg(other.eback(), other.gptr(), other.egptr()); - setp(other.pptr(), other.epptr()); - other.ec_ = asio::error_code(); - other.expiry_time_ = max_expiry_time(); - other.init_buffers(); - } - - /// Move-assign a basic_socket_streambuf from another. - basic_socket_streambuf& operator=(basic_socket_streambuf&& other) - { - this->close(); - socket() = std::move(other.socket()); - detail::socket_streambuf_io_context::operator=(other); - ec_ = other.ec_; - expiry_time_ = other.expiry_time_; - get_buffer_.swap(other.get_buffer_); - put_buffer_.swap(other.put_buffer_); - setg(other.eback(), other.gptr(), other.egptr()); - setp(other.pptr(), other.epptr()); - other.ec_ = asio::error_code(); - other.expiry_time_ = max_expiry_time(); - other.put_buffer_.resize(buffer_size); - other.init_buffers(); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destructor flushes buffered data. - virtual ~basic_socket_streambuf() - { - if (pptr() != pbase()) - overflow(traits_type::eof()); - } - - /// Establish a connection. - /** - * This function establishes a connection to the specified endpoint. - * - * @return \c this if a connection was successfully established, a null - * pointer otherwise. - */ - basic_socket_streambuf* connect(const endpoint_type& endpoint) - { - init_buffers(); - ec_ = asio::error_code(); - this->connect_to_endpoints(&endpoint, &endpoint + 1); - return !ec_ ? this : 0; - } - -#if defined(GENERATING_DOCUMENTATION) - /// Establish a connection. - /** - * This function automatically establishes a connection based on the supplied - * resolver query parameters. The arguments are used to construct a resolver - * query object. - * - * @return \c this if a connection was successfully established, a null - * pointer otherwise. - */ - template - basic_socket_streambuf* connect(T1 t1, ..., TN tn); -#elif defined(ASIO_HAS_VARIADIC_TEMPLATES) - template - basic_socket_streambuf* connect(T... x) - { - init_buffers(); - typedef typename Protocol::resolver resolver_type; - resolver_type resolver(socket().get_executor().context()); - connect_to_endpoints(resolver.resolve(x..., ec_)); - return !ec_ ? this : 0; - } -#else - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_CONNECT_DEF) -#endif - - /// Close the connection. - /** - * @return \c this if a connection was successfully established, a null - * pointer otherwise. - */ - basic_socket_streambuf* close() - { - sync(); - socket().close(ec_); - if (!ec_) - init_buffers(); - return !ec_ ? this : 0; - } - - /// Get a reference to the underlying socket. - basic_socket& socket() - { - return *this; - } - - /// Get the last error associated with the stream buffer. - /** - * @return An \c error_code corresponding to the last error from the stream - * buffer. - */ - const asio::error_code& error() const - { - return ec_; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use error().) Get the last error associated with the stream - /// buffer. - /** - * @return An \c error_code corresponding to the last error from the stream - * buffer. - */ - const asio::error_code& puberror() const - { - return error(); - } - - /// (Deprecated: Use expiry().) Get the stream buffer's expiry time as an - /// absolute time. - /** - * @return An absolute time value representing the stream buffer's expiry - * time. - */ - time_point expires_at() const - { - return expiry_time_; - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the stream buffer's expiry time as an absolute time. - /** - * @return An absolute time value representing the stream buffer's expiry - * time. - */ - time_point expiry() const - { - return expiry_time_; - } - - /// Set the stream buffer's expiry time as an absolute time. - /** - * This function sets the expiry time associated with the stream. Stream - * operations performed after this time (where the operations cannot be - * completed using the internal buffers) will fail with the error - * asio::error::operation_aborted. - * - * @param expiry_time The expiry time to be used for the stream. - */ - void expires_at(const time_point& expiry_time) - { - expiry_time_ = expiry_time; - } - - /// Set the stream buffer's expiry time relative to now. - /** - * This function sets the expiry time associated with the stream. Stream - * operations performed after this time (where the operations cannot be - * completed using the internal buffers) will fail with the error - * asio::error::operation_aborted. - * - * @param expiry_time The expiry time to be used for the timer. - */ - void expires_after(const duration& expiry_time) - { - expiry_time_ = traits_helper::add(traits_helper::now(), expiry_time); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use expiry().) Get the stream buffer's expiry time relative - /// to now. - /** - * @return A relative time value representing the stream buffer's expiry time. - */ - duration expires_from_now() const - { - return traits_helper::subtract(expires_at(), traits_helper::now()); - } - - /// (Deprecated: Use expires_after().) Set the stream buffer's expiry time - /// relative to now. - /** - * This function sets the expiry time associated with the stream. Stream - * operations performed after this time (where the operations cannot be - * completed using the internal buffers) will fail with the error - * asio::error::operation_aborted. - * - * @param expiry_time The expiry time to be used for the timer. - */ - void expires_from_now(const duration& expiry_time) - { - expiry_time_ = traits_helper::add(traits_helper::now(), expiry_time); - } -#endif // !defined(ASIO_NO_DEPRECATED) - -protected: - int_type underflow() - { -#if defined(ASIO_WINDOWS_RUNTIME) - ec_ = asio::error::operation_not_supported; - return traits_type::eof(); -#else // defined(ASIO_WINDOWS_RUNTIME) - if (gptr() != egptr()) - return traits_type::eof(); - - for (;;) - { - // Check if we are past the expiry time. - if (traits_helper::less_than(expiry_time_, traits_helper::now())) - { - ec_ = asio::error::timed_out; - return traits_type::eof(); - } - - // Try to complete the operation without blocking. - if (!socket().native_non_blocking()) - socket().native_non_blocking(true, ec_); - detail::buffer_sequence_adapter - bufs(asio::buffer(get_buffer_) + putback_max); - detail::signed_size_type bytes = detail::socket_ops::recv( - socket().native_handle(), bufs.buffers(), bufs.count(), 0, ec_); - - // Check if operation succeeded. - if (bytes > 0) - { - setg(&get_buffer_[0], &get_buffer_[0] + putback_max, - &get_buffer_[0] + putback_max + bytes); - return traits_type::to_int_type(*gptr()); - } - - // Check for EOF. - if (bytes == 0) - { - ec_ = asio::error::eof; - return traits_type::eof(); - } - - // Operation failed. - if (ec_ != asio::error::would_block - && ec_ != asio::error::try_again) - return traits_type::eof(); - - // Wait for socket to become ready. - if (detail::socket_ops::poll_read( - socket().native_handle(), 0, timeout(), ec_) < 0) - return traits_type::eof(); - } -#endif // defined(ASIO_WINDOWS_RUNTIME) - } - - int_type overflow(int_type c) - { -#if defined(ASIO_WINDOWS_RUNTIME) - ec_ = asio::error::operation_not_supported; - return traits_type::eof(); -#else // defined(ASIO_WINDOWS_RUNTIME) - char_type ch = traits_type::to_char_type(c); - - // Determine what needs to be sent. - const_buffer output_buffer; - if (put_buffer_.empty()) - { - if (traits_type::eq_int_type(c, traits_type::eof())) - return traits_type::not_eof(c); // Nothing to do. - output_buffer = asio::buffer(&ch, sizeof(char_type)); - } - else - { - output_buffer = asio::buffer(pbase(), - (pptr() - pbase()) * sizeof(char_type)); - } - - while (output_buffer.size() > 0) - { - // Check if we are past the expiry time. - if (traits_helper::less_than(expiry_time_, traits_helper::now())) - { - ec_ = asio::error::timed_out; - return traits_type::eof(); - } - - // Try to complete the operation without blocking. - if (!socket().native_non_blocking()) - socket().native_non_blocking(true, ec_); - detail::buffer_sequence_adapter< - const_buffer, const_buffer> bufs(output_buffer); - detail::signed_size_type bytes = detail::socket_ops::send( - socket().native_handle(), bufs.buffers(), bufs.count(), 0, ec_); - - // Check if operation succeeded. - if (bytes > 0) - { - output_buffer += static_cast(bytes); - continue; - } - - // Operation failed. - if (ec_ != asio::error::would_block - && ec_ != asio::error::try_again) - return traits_type::eof(); - - // Wait for socket to become ready. - if (detail::socket_ops::poll_write( - socket().native_handle(), 0, timeout(), ec_) < 0) - return traits_type::eof(); - } - - if (!put_buffer_.empty()) - { - setp(&put_buffer_[0], &put_buffer_[0] + put_buffer_.size()); - - // If the new character is eof then our work here is done. - if (traits_type::eq_int_type(c, traits_type::eof())) - return traits_type::not_eof(c); - - // Add the new character to the output buffer. - *pptr() = ch; - pbump(1); - } - - return c; -#endif // defined(ASIO_WINDOWS_RUNTIME) - } - - int sync() - { - return overflow(traits_type::eof()); - } - - std::streambuf* setbuf(char_type* s, std::streamsize n) - { - if (pptr() == pbase() && s == 0 && n == 0) - { - put_buffer_.clear(); - setp(0, 0); - sync(); - return this; - } - - return 0; - } - -private: - // Disallow copying and assignment. - basic_socket_streambuf(const basic_socket_streambuf&) ASIO_DELETED; - basic_socket_streambuf& operator=( - const basic_socket_streambuf&) ASIO_DELETED; - - void init_buffers() - { - setg(&get_buffer_[0], - &get_buffer_[0] + putback_max, - &get_buffer_[0] + putback_max); - - if (put_buffer_.empty()) - setp(0, 0); - else - setp(&put_buffer_[0], &put_buffer_[0] + put_buffer_.size()); - } - - int timeout() const - { - int64_t msec = traits_helper::to_posix_duration( - traits_helper::subtract(expiry_time_, - traits_helper::now())).total_milliseconds(); - if (msec > (std::numeric_limits::max)()) - msec = (std::numeric_limits::max)(); - else if (msec < 0) - msec = 0; - return static_cast(msec); - } - - template - void connect_to_endpoints(const EndpointSequence& endpoints) - { - this->connect_to_endpoints(endpoints.begin(), endpoints.end()); - } - - template - void connect_to_endpoints(EndpointIterator begin, EndpointIterator end) - { -#if defined(ASIO_WINDOWS_RUNTIME) - ec_ = asio::error::operation_not_supported; -#else // defined(ASIO_WINDOWS_RUNTIME) - if (ec_) - return; - - ec_ = asio::error::not_found; - for (EndpointIterator i = begin; i != end; ++i) - { - // Check if we are past the expiry time. - if (traits_helper::less_than(expiry_time_, traits_helper::now())) - { - ec_ = asio::error::timed_out; - return; - } - - // Close and reopen the socket. - typename Protocol::endpoint ep(*i); - socket().close(ec_); - socket().open(ep.protocol(), ec_); - if (ec_) - continue; - - // Try to complete the operation without blocking. - if (!socket().native_non_blocking()) - socket().native_non_blocking(true, ec_); - detail::socket_ops::connect(socket().native_handle(), - ep.data(), ep.size(), ec_); - - // Check if operation succeeded. - if (!ec_) - return; - - // Operation failed. - if (ec_ != asio::error::in_progress - && ec_ != asio::error::would_block) - continue; - - // Wait for socket to become ready. - if (detail::socket_ops::poll_connect( - socket().native_handle(), timeout(), ec_) < 0) - continue; - - // Get the error code from the connect operation. - int connect_error = 0; - size_t connect_error_len = sizeof(connect_error); - if (detail::socket_ops::getsockopt(socket().native_handle(), 0, - SOL_SOCKET, SO_ERROR, &connect_error, &connect_error_len, ec_) - == detail::socket_error_retval) - return; - - // Check the result of the connect operation. - ec_ = asio::error_code(connect_error, - asio::error::get_system_category()); - if (!ec_) - return; - } -#endif // defined(ASIO_WINDOWS_RUNTIME) - } - - // Helper function to get the maximum expiry time. - static time_point max_expiry_time() - { -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - return boost::posix_time::pos_infin; -#else // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - return (time_point::max)(); -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // && defined(ASIO_USE_BOOST_DATE_TIME_FOR_SOCKET_IOSTREAM) - } - - enum { putback_max = 8 }; - asio::error_code ec_; - time_point expiry_time_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# undef ASIO_SVC_T1 -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#if !defined(ASIO_HAS_VARIADIC_TEMPLATES) -# undef ASIO_PRIVATE_CONNECT_DEF -#endif // !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_BASIC_SOCKET_STREAMBUF_HPP diff --git a/scout_sdk/asio/asio/basic_stream_socket.hpp b/scout_sdk/asio/asio/basic_stream_socket.hpp deleted file mode 100644 index eea8862..0000000 --- a/scout_sdk/asio/asio/basic_stream_socket.hpp +++ /dev/null @@ -1,921 +0,0 @@ -// -// basic_stream_socket.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_STREAM_SOCKET_HPP -#define ASIO_BASIC_STREAM_SOCKET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/basic_socket.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/stream_socket_service.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides stream-oriented socket functionality. -/** - * The basic_stream_socket class template provides asynchronous and blocking - * stream-oriented socket functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -template )> -class basic_stream_socket - : public basic_socket -{ -public: - /// The native representation of a socket. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename basic_socket< - Protocol ASIO_SVC_TARG>::native_handle_type native_handle_type; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - /// Construct a basic_stream_socket without opening it. - /** - * This constructor creates a stream socket without opening it. The socket - * needs to be opened and then connected or accepted before data can be sent - * or received on it. - * - * @param io_context The io_context object that the stream socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - */ - explicit basic_stream_socket(asio::io_context& io_context) - : basic_socket(io_context) - { - } - - /// Construct and open a basic_stream_socket. - /** - * This constructor creates and opens a stream socket. The socket needs to be - * connected or accepted before data can be sent or received on it. - * - * @param io_context The io_context object that the stream socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @throws asio::system_error Thrown on failure. - */ - basic_stream_socket(asio::io_context& io_context, - const protocol_type& protocol) - : basic_socket(io_context, protocol) - { - } - - /// Construct a basic_stream_socket, opening it and binding it to the given - /// local endpoint. - /** - * This constructor creates a stream socket and automatically opens it bound - * to the specified endpoint on the local machine. The protocol used is the - * protocol associated with the given endpoint. - * - * @param io_context The io_context object that the stream socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - * - * @param endpoint An endpoint on the local machine to which the stream - * socket will be bound. - * - * @throws asio::system_error Thrown on failure. - */ - basic_stream_socket(asio::io_context& io_context, - const endpoint_type& endpoint) - : basic_socket(io_context, endpoint) - { - } - - /// Construct a basic_stream_socket on an existing native socket. - /** - * This constructor creates a stream socket object to hold an existing native - * socket. - * - * @param io_context The io_context object that the stream socket will use to - * dispatch handlers for any asynchronous operations performed on the socket. - * - * @param protocol An object specifying protocol parameters to be used. - * - * @param native_socket The new underlying socket implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_stream_socket(asio::io_context& io_context, - const protocol_type& protocol, const native_handle_type& native_socket) - : basic_socket( - io_context, protocol, native_socket) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_stream_socket from another. - /** - * This constructor moves a stream socket from one object to another. - * - * @param other The other basic_stream_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_socket(io_context&) constructor. - */ - basic_stream_socket(basic_stream_socket&& other) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_stream_socket from another. - /** - * This assignment operator moves a stream socket from one object to another. - * - * @param other The other basic_stream_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_socket(io_context&) constructor. - */ - basic_stream_socket& operator=(basic_stream_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } - - /// Move-construct a basic_stream_socket from a socket of another protocol - /// type. - /** - * This constructor moves a stream socket from one object to another. - * - * @param other The other basic_stream_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_socket(io_context&) constructor. - */ - template - basic_stream_socket( - basic_stream_socket&& other, - typename enable_if::value>::type* = 0) - : basic_socket(std::move(other)) - { - } - - /// Move-assign a basic_stream_socket from a socket of another protocol type. - /** - * This assignment operator moves a stream socket from one object to another. - * - * @param other The other basic_stream_socket object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_socket(io_context&) constructor. - */ - template - typename enable_if::value, - basic_stream_socket>::type& operator=( - basic_stream_socket&& other) - { - basic_socket::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the socket. - /** - * This function destroys the socket, cancelling any outstanding asynchronous - * operations associated with the socket as if by calling @c cancel. - */ - ~basic_stream_socket() - { - } - - /// Send some data on the socket. - /** - * This function is used to send data on the stream socket. The function - * call will block until one or more bytes of the data has been sent - * successfully, or an until error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @note The send operation may not transmit all of the data to the peer. - * Consider using the @ref write function if you need to ensure that all data - * is written before the blocking operation completes. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.send(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t send(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "send"); - return s; - } - - /// Send some data on the socket. - /** - * This function is used to send data on the stream socket. The function - * call will block until one or more bytes of the data has been sent - * successfully, or an until error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @returns The number of bytes sent. - * - * @throws asio::system_error Thrown on failure. - * - * @note The send operation may not transmit all of the data to the peer. - * Consider using the @ref write function if you need to ensure that all data - * is written before the blocking operation completes. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.send(asio::buffer(data, size), 0); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, flags, ec); - asio::detail::throw_error(ec, "send"); - return s; - } - - /// Send some data on the socket. - /** - * This function is used to send data on the stream socket. The function - * call will block until one or more bytes of the data has been sent - * successfully, or an until error occurs. - * - * @param buffers One or more data buffers to be sent on the socket. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes sent. Returns 0 if an error occurred. - * - * @note The send operation may not transmit all of the data to the peer. - * Consider using the @ref write function if you need to ensure that all data - * is written before the blocking operation completes. - */ - template - std::size_t send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return this->get_service().send( - this->get_implementation(), buffers, flags, ec); - } - - /// Start an asynchronous send. - /** - * This function is used to asynchronously send data on the stream socket. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent on the socket. Although - * the buffers object may be copied as necessary, ownership of the underlying - * memory blocks is retained by the caller, which must guarantee that they - * remain valid until the handler is called. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The send operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.async_send(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send( - this->get_implementation(), buffers, 0, - ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send( - this->get_implementation(), buffers, 0, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous send. - /** - * This function is used to asynchronously send data on the stream socket. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be sent on the socket. Although - * the buffers object may be copied as necessary, ownership of the underlying - * memory blocks is retained by the caller, which must guarantee that they - * remain valid until the handler is called. - * - * @param flags Flags specifying how the send call is to be made. - * - * @param handler The handler to be called when the send operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes sent. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The send operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To send a single data buffer use the @ref buffer function as follows: - * @code - * socket.async_send(asio::buffer(data, size), 0, handler); - * @endcode - * See the @ref buffer documentation for information on sending multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send( - this->get_implementation(), buffers, flags, - ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send( - this->get_implementation(), buffers, flags, - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Receive some data on the socket. - /** - * This function is used to receive data on the stream socket. The function - * call will block until one or more bytes of data has been received - * successfully, or until an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The receive operation may not receive all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that the - * requested amount of data is read before the blocking operation completes. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.receive(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on the socket. - /** - * This function is used to receive data on the stream socket. The function - * call will block until one or more bytes of data has been received - * successfully, or until an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @returns The number of bytes received. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The receive operation may not receive all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that the - * requested amount of data is read before the blocking operation completes. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.receive(asio::buffer(data, size), 0); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags) - { - asio::error_code ec; - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, flags, ec); - asio::detail::throw_error(ec, "receive"); - return s; - } - - /// Receive some data on a connected socket. - /** - * This function is used to receive data on the stream socket. The function - * call will block until one or more bytes of data has been received - * successfully, or until an error occurs. - * - * @param buffers One or more buffers into which the data will be received. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes received. Returns 0 if an error occurred. - * - * @note The receive operation may not receive all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that the - * requested amount of data is read before the blocking operation completes. - */ - template - std::size_t receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return this->get_service().receive( - this->get_implementation(), buffers, flags, ec); - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive data from the stream - * socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The receive operation may not receive all of the requested number of - * bytes. Consider using the @ref async_read function if you need to ensure - * that the requested amount of data is received before the asynchronous - * operation completes. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.async_receive(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive(this->get_implementation(), - buffers, 0, ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive(this->get_implementation(), - buffers, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Start an asynchronous receive. - /** - * This function is used to asynchronously receive data from the stream - * socket. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be received. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param flags Flags specifying how the receive call is to be made. - * - * @param handler The handler to be called when the receive operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes received. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The receive operation may not receive all of the requested number of - * bytes. Consider using the @ref async_read function if you need to ensure - * that the requested amount of data is received before the asynchronous - * operation completes. - * - * @par Example - * To receive into a single data buffer use the @ref buffer function as - * follows: - * @code - * socket.async_receive(asio::buffer(data, size), 0, handler); - * @endcode - * See the @ref buffer documentation for information on receiving into - * multiple buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(const MutableBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive(this->get_implementation(), - buffers, flags, ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive(this->get_implementation(), - buffers, flags, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Write some data to the socket. - /** - * This function is used to write data to the stream socket. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the socket. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * socket.write_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().send( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "write_some"); - return s; - } - - /// Write some data to the socket. - /** - * This function is used to write data to the stream socket. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the socket. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().send(this->get_implementation(), buffers, 0, ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write data to the stream socket. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be written to the socket. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * socket.async_write_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_send(this->get_implementation(), - buffers, 0, ASIO_MOVE_CAST(WriteHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_send(this->get_implementation(), - buffers, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Read some data from the socket. - /** - * This function is used to read data from the stream socket. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * socket.read_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().receive( - this->get_implementation(), buffers, 0, ec); - asio::detail::throw_error(ec, "read_some"); - return s; - } - - /// Read some data from the socket. - /** - * This function is used to read data from the stream socket. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().receive( - this->get_implementation(), buffers, 0, ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read data from the stream socket. - * The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read function if you need to ensure that the - * requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * socket.async_read_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_receive(this->get_implementation(), - buffers, 0, ASIO_MOVE_CAST(ReadHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_receive(this->get_implementation(), - buffers, 0, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BASIC_STREAM_SOCKET_HPP diff --git a/scout_sdk/asio/asio/basic_streambuf.hpp b/scout_sdk/asio/asio/basic_streambuf.hpp deleted file mode 100644 index 14f85d2..0000000 --- a/scout_sdk/asio/asio/basic_streambuf.hpp +++ /dev/null @@ -1,452 +0,0 @@ -// -// basic_streambuf.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_STREAMBUF_HPP -#define ASIO_BASIC_STREAMBUF_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_NO_IOSTREAM) - -#include -#include -#include -#include -#include -#include "asio/basic_streambuf_fwd.hpp" -#include "asio/buffer.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/throw_exception.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Automatically resizable buffer class based on std::streambuf. -/** - * The @c basic_streambuf class is derived from @c std::streambuf to associate - * the streambuf's input and output sequences with one or more character - * arrays. These character arrays are internal to the @c basic_streambuf - * object, but direct access to the array elements is provided to permit them - * to be used efficiently with I/O operations. Characters written to the output - * sequence of a @c basic_streambuf object are appended to the input sequence - * of the same object. - * - * The @c basic_streambuf class's public interface is intended to permit the - * following implementation strategies: - * - * @li A single contiguous character array, which is reallocated as necessary - * to accommodate changes in the size of the character sequence. This is the - * implementation approach currently used in Asio. - * - * @li A sequence of one or more character arrays, where each array is of the - * same size. Additional character array objects are appended to the sequence - * to accommodate changes in the size of the character sequence. - * - * @li A sequence of one or more character arrays of varying sizes. Additional - * character array objects are appended to the sequence to accommodate changes - * in the size of the character sequence. - * - * The constructor for basic_streambuf accepts a @c size_t argument specifying - * the maximum of the sum of the sizes of the input sequence and output - * sequence. During the lifetime of the @c basic_streambuf object, the following - * invariant holds: - * @code size() <= max_size()@endcode - * Any member function that would, if successful, cause the invariant to be - * violated shall throw an exception of class @c std::length_error. - * - * The constructor for @c basic_streambuf takes an Allocator argument. A copy - * of this argument is used for any memory allocation performed, by the - * constructor and by all member functions, during the lifetime of each @c - * basic_streambuf object. - * - * @par Examples - * Writing directly from an streambuf to a socket: - * @code - * asio::streambuf b; - * std::ostream os(&b); - * os << "Hello, World!\n"; - * - * // try sending some data in input sequence - * size_t n = sock.send(b.data()); - * - * b.consume(n); // sent data is removed from input sequence - * @endcode - * - * Reading from a socket directly into a streambuf: - * @code - * asio::streambuf b; - * - * // reserve 512 bytes in output sequence - * asio::streambuf::mutable_buffers_type bufs = b.prepare(512); - * - * size_t n = sock.receive(bufs); - * - * // received data is "committed" from output sequence to input sequence - * b.commit(n); - * - * std::istream is(&b); - * std::string s; - * is >> s; - * @endcode - */ -#if defined(GENERATING_DOCUMENTATION) -template > -#else -template -#endif -class basic_streambuf - : public std::streambuf, - private noncopyable -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The type used to represent the input sequence as a list of buffers. - typedef implementation_defined const_buffers_type; - - /// The type used to represent the output sequence as a list of buffers. - typedef implementation_defined mutable_buffers_type; -#else - typedef ASIO_CONST_BUFFER const_buffers_type; - typedef ASIO_MUTABLE_BUFFER mutable_buffers_type; -#endif - - /// Construct a basic_streambuf object. - /** - * Constructs a streambuf with the specified maximum size. The initial size - * of the streambuf's input sequence is 0. - */ - explicit basic_streambuf( - std::size_t maximum_size = (std::numeric_limits::max)(), - const Allocator& allocator = Allocator()) - : max_size_(maximum_size), - buffer_(allocator) - { - std::size_t pend = (std::min)(max_size_, buffer_delta); - buffer_.resize((std::max)(pend, 1)); - setg(&buffer_[0], &buffer_[0], &buffer_[0]); - setp(&buffer_[0], &buffer_[0] + pend); - } - - /// Get the size of the input sequence. - /** - * @returns The size of the input sequence. The value is equal to that - * calculated for @c s in the following code: - * @code - * size_t s = 0; - * const_buffers_type bufs = data(); - * const_buffers_type::const_iterator i = bufs.begin(); - * while (i != bufs.end()) - * { - * const_buffer buf(*i++); - * s += buf.size(); - * } - * @endcode - */ - std::size_t size() const ASIO_NOEXCEPT - { - return pptr() - gptr(); - } - - /// Get the maximum size of the basic_streambuf. - /** - * @returns The allowed maximum of the sum of the sizes of the input sequence - * and output sequence. - */ - std::size_t max_size() const ASIO_NOEXCEPT - { - return max_size_; - } - - /// Get the current capacity of the basic_streambuf. - /** - * @returns The current total capacity of the streambuf, i.e. for both the - * input sequence and output sequence. - */ - std::size_t capacity() const ASIO_NOEXCEPT - { - return buffer_.capacity(); - } - - /// Get a list of buffers that represents the input sequence. - /** - * @returns An object of type @c const_buffers_type that satisfies - * ConstBufferSequence requirements, representing all character arrays in the - * input sequence. - * - * @note The returned object is invalidated by any @c basic_streambuf member - * function that modifies the input sequence or output sequence. - */ - const_buffers_type data() const ASIO_NOEXCEPT - { - return asio::buffer(asio::const_buffer(gptr(), - (pptr() - gptr()) * sizeof(char_type))); - } - - /// Get a list of buffers that represents the output sequence, with the given - /// size. - /** - * Ensures that the output sequence can accommodate @c n characters, - * reallocating character array objects as necessary. - * - * @returns An object of type @c mutable_buffers_type that satisfies - * MutableBufferSequence requirements, representing character array objects - * at the start of the output sequence such that the sum of the buffer sizes - * is @c n. - * - * @throws std::length_error If size() + n > max_size(). - * - * @note The returned object is invalidated by any @c basic_streambuf member - * function that modifies the input sequence or output sequence. - */ - mutable_buffers_type prepare(std::size_t n) - { - reserve(n); - return asio::buffer(asio::mutable_buffer( - pptr(), n * sizeof(char_type))); - } - - /// Move characters from the output sequence to the input sequence. - /** - * Appends @c n characters from the start of the output sequence to the input - * sequence. The beginning of the output sequence is advanced by @c n - * characters. - * - * Requires a preceding call prepare(x) where x >= n, and - * no intervening operations that modify the input or output sequence. - * - * @note If @c n is greater than the size of the output sequence, the entire - * output sequence is moved to the input sequence and no error is issued. - */ - void commit(std::size_t n) - { - n = std::min(n, epptr() - pptr()); - pbump(static_cast(n)); - setg(eback(), gptr(), pptr()); - } - - /// Remove characters from the input sequence. - /** - * Removes @c n characters from the beginning of the input sequence. - * - * @note If @c n is greater than the size of the input sequence, the entire - * input sequence is consumed and no error is issued. - */ - void consume(std::size_t n) - { - if (egptr() < pptr()) - setg(&buffer_[0], gptr(), pptr()); - if (gptr() + n > pptr()) - n = pptr() - gptr(); - gbump(static_cast(n)); - } - -protected: - enum { buffer_delta = 128 }; - - /// Override std::streambuf behaviour. - /** - * Behaves according to the specification of @c std::streambuf::underflow(). - */ - int_type underflow() - { - if (gptr() < pptr()) - { - setg(&buffer_[0], gptr(), pptr()); - return traits_type::to_int_type(*gptr()); - } - else - { - return traits_type::eof(); - } - } - - /// Override std::streambuf behaviour. - /** - * Behaves according to the specification of @c std::streambuf::overflow(), - * with the specialisation that @c std::length_error is thrown if appending - * the character to the input sequence would require the condition - * size() > max_size() to be true. - */ - int_type overflow(int_type c) - { - if (!traits_type::eq_int_type(c, traits_type::eof())) - { - if (pptr() == epptr()) - { - std::size_t buffer_size = pptr() - gptr(); - if (buffer_size < max_size_ && max_size_ - buffer_size < buffer_delta) - { - reserve(max_size_ - buffer_size); - } - else - { - reserve(buffer_delta); - } - } - - *pptr() = traits_type::to_char_type(c); - pbump(1); - return c; - } - - return traits_type::not_eof(c); - } - - void reserve(std::size_t n) - { - // Get current stream positions as offsets. - std::size_t gnext = gptr() - &buffer_[0]; - std::size_t pnext = pptr() - &buffer_[0]; - std::size_t pend = epptr() - &buffer_[0]; - - // Check if there is already enough space in the put area. - if (n <= pend - pnext) - { - return; - } - - // Shift existing contents of get area to start of buffer. - if (gnext > 0) - { - pnext -= gnext; - std::memmove(&buffer_[0], &buffer_[0] + gnext, pnext); - } - - // Ensure buffer is large enough to hold at least the specified size. - if (n > pend - pnext) - { - if (n <= max_size_ && pnext <= max_size_ - n) - { - pend = pnext + n; - buffer_.resize((std::max)(pend, 1)); - } - else - { - std::length_error ex("asio::streambuf too long"); - asio::detail::throw_exception(ex); - } - } - - // Update stream positions. - setg(&buffer_[0], &buffer_[0], &buffer_[0] + pnext); - setp(&buffer_[0] + pnext, &buffer_[0] + pend); - } - -private: - std::size_t max_size_; - std::vector buffer_; - - // Helper function to get the preferred size for reading data. - friend std::size_t read_size_helper( - basic_streambuf& sb, std::size_t max_size) - { - return std::min( - std::max(512, sb.buffer_.capacity() - sb.size()), - std::min(max_size, sb.max_size() - sb.size())); - } -}; - -/// Adapts basic_streambuf to the dynamic buffer sequence type requirements. -#if defined(GENERATING_DOCUMENTATION) -template > -#else -template -#endif -class basic_streambuf_ref -{ -public: - /// The type used to represent the input sequence as a list of buffers. - typedef typename basic_streambuf::const_buffers_type - const_buffers_type; - - /// The type used to represent the output sequence as a list of buffers. - typedef typename basic_streambuf::mutable_buffers_type - mutable_buffers_type; - - /// Construct a basic_streambuf_ref for the given basic_streambuf object. - explicit basic_streambuf_ref(basic_streambuf& sb) - : sb_(sb) - { - } - - /// Copy construct a basic_streambuf_ref. - basic_streambuf_ref(const basic_streambuf_ref& other) ASIO_NOEXCEPT - : sb_(other.sb_) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move construct a basic_streambuf_ref. - basic_streambuf_ref(basic_streambuf_ref&& other) ASIO_NOEXCEPT - : sb_(other.sb_) - { - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Get the size of the input sequence. - std::size_t size() const ASIO_NOEXCEPT - { - return sb_.size(); - } - - /// Get the maximum size of the dynamic buffer. - std::size_t max_size() const ASIO_NOEXCEPT - { - return sb_.max_size(); - } - - /// Get the current capacity of the dynamic buffer. - std::size_t capacity() const ASIO_NOEXCEPT - { - return sb_.capacity(); - } - - /// Get a list of buffers that represents the input sequence. - const_buffers_type data() const ASIO_NOEXCEPT - { - return sb_.data(); - } - - /// Get a list of buffers that represents the output sequence, with the given - /// size. - mutable_buffers_type prepare(std::size_t n) - { - return sb_.prepare(n); - } - - /// Move bytes from the output sequence to the input sequence. - void commit(std::size_t n) - { - return sb_.commit(n); - } - - /// Remove characters from the input sequence. - void consume(std::size_t n) - { - return sb_.consume(n); - } - -private: - basic_streambuf& sb_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_BASIC_STREAMBUF_HPP diff --git a/scout_sdk/asio/asio/basic_streambuf_fwd.hpp b/scout_sdk/asio/asio/basic_streambuf_fwd.hpp deleted file mode 100644 index ed54fe9..0000000 --- a/scout_sdk/asio/asio/basic_streambuf_fwd.hpp +++ /dev/null @@ -1,36 +0,0 @@ -// -// basic_streambuf_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_STREAMBUF_FWD_HPP -#define ASIO_BASIC_STREAMBUF_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_NO_IOSTREAM) - -#include - -namespace asio { - -template > -class basic_streambuf; - -template > -class basic_streambuf_ref; - -} // namespace asio - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_BASIC_STREAMBUF_FWD_HPP diff --git a/scout_sdk/asio/asio/basic_waitable_timer.hpp b/scout_sdk/asio/asio/basic_waitable_timer.hpp deleted file mode 100644 index 22b85a6..0000000 --- a/scout_sdk/asio/asio/basic_waitable_timer.hpp +++ /dev/null @@ -1,705 +0,0 @@ -// -// basic_waitable_timer.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BASIC_WAITABLE_TIMER_HPP -#define ASIO_BASIC_WAITABLE_TIMER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/wait_traits.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/waitable_timer_service.hpp" -#else // defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/detail/chrono_time_traits.hpp" -# include "asio/detail/deadline_timer_service.hpp" -# define ASIO_SVC_T \ - detail::deadline_timer_service< \ - detail::chrono_time_traits > -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if !defined(ASIO_BASIC_WAITABLE_TIMER_FWD_DECL) -#define ASIO_BASIC_WAITABLE_TIMER_FWD_DECL - -// Forward declaration with defaulted arguments. -template - ASIO_SVC_TPARAM_DEF2(= waitable_timer_service)> -class basic_waitable_timer; - -#endif // !defined(ASIO_BASIC_WAITABLE_TIMER_FWD_DECL) - -/// Provides waitable timer functionality. -/** - * The basic_waitable_timer class template provides the ability to perform a - * blocking or asynchronous wait for a timer to expire. - * - * A waitable timer is always in one of two states: "expired" or "not expired". - * If the wait() or async_wait() function is called on an expired timer, the - * wait operation will complete immediately. - * - * Most applications will use one of the asio::steady_timer, - * asio::system_timer or asio::high_resolution_timer typedefs. - * - * @note This waitable timer functionality is for use with the C++11 standard - * library's @c <chrono> facility, or with the Boost.Chrono library. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Examples - * Performing a blocking wait (C++11): - * @code - * // Construct a timer without setting an expiry time. - * asio::steady_timer timer(io_context); - * - * // Set an expiry time relative to now. - * timer.expires_after(std::chrono::seconds(5)); - * - * // Wait for the timer to expire. - * timer.wait(); - * @endcode - * - * @par - * Performing an asynchronous wait (C++11): - * @code - * void handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Timer expired. - * } - * } - * - * ... - * - * // Construct a timer with an absolute expiry time. - * asio::steady_timer timer(io_context, - * std::chrono::steady_clock::now() + std::chrono::seconds(60)); - * - * // Start an asynchronous wait. - * timer.async_wait(handler); - * @endcode - * - * @par Changing an active waitable timer's expiry time - * - * Changing the expiry time of a timer while there are pending asynchronous - * waits causes those wait operations to be cancelled. To ensure that the action - * associated with the timer is performed only once, use something like this: - * used: - * - * @code - * void on_some_event() - * { - * if (my_timer.expires_after(seconds(5)) > 0) - * { - * // We managed to cancel the timer. Start new asynchronous wait. - * my_timer.async_wait(on_timeout); - * } - * else - * { - * // Too late, timer has already expired! - * } - * } - * - * void on_timeout(const asio::error_code& e) - * { - * if (e != asio::error::operation_aborted) - * { - * // Timer was not cancelled, take necessary action. - * } - * } - * @endcode - * - * @li The asio::basic_waitable_timer::expires_after() function - * cancels any pending asynchronous waits, and returns the number of - * asynchronous waits that were cancelled. If it returns 0 then you were too - * late and the wait handler has already been executed, or will soon be - * executed. If it returns 1 then the wait handler was successfully cancelled. - * - * @li If a wait handler is cancelled, the asio::error_code passed to - * it contains the value asio::error::operation_aborted. - */ -template -class basic_waitable_timer - : ASIO_SVC_ACCESS basic_io_object -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The clock type. - typedef Clock clock_type; - - /// The duration type of the clock. - typedef typename clock_type::duration duration; - - /// The time point type of the clock. - typedef typename clock_type::time_point time_point; - - /// The wait traits type. - typedef WaitTraits traits_type; - - /// Constructor. - /** - * This constructor creates a timer without setting an expiry time. The - * expires_at() or expires_after() functions must be called to set an expiry - * time before the timer can be waited on. - * - * @param io_context The io_context object that the timer will use to dispatch - * handlers for any asynchronous operations performed on the timer. - */ - explicit basic_waitable_timer(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Constructor to set a particular expiry time as an absolute time. - /** - * This constructor creates a timer and sets the expiry time. - * - * @param io_context The io_context object that the timer will use to dispatch - * handlers for any asynchronous operations performed on the timer. - * - * @param expiry_time The expiry time to be used for the timer, expressed - * as an absolute time. - */ - basic_waitable_timer(asio::io_context& io_context, - const time_point& expiry_time) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().expires_at(this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_at"); - } - - /// Constructor to set a particular expiry time relative to now. - /** - * This constructor creates a timer and sets the expiry time. - * - * @param io_context The io_context object that the timer will use to dispatch - * handlers for any asynchronous operations performed on the timer. - * - * @param expiry_time The expiry time to be used for the timer, relative to - * now. - */ - basic_waitable_timer(asio::io_context& io_context, - const duration& expiry_time) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().expires_after( - this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_after"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_waitable_timer from another. - /** - * This constructor moves a timer from one object to another. - * - * @param other The other basic_waitable_timer object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_waitable_timer(io_context&) constructor. - */ - basic_waitable_timer(basic_waitable_timer&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign a basic_waitable_timer from another. - /** - * This assignment operator moves a timer from one object to another. Cancels - * any outstanding asynchronous operations associated with the target object. - * - * @param other The other basic_waitable_timer object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_waitable_timer(io_context&) constructor. - */ - basic_waitable_timer& operator=(basic_waitable_timer&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the timer. - /** - * This function destroys the timer, cancelling any outstanding asynchronous - * wait operations associated with the timer as if by calling @c cancel. - */ - ~basic_waitable_timer() - { - } - -#if defined(ASIO_ENABLE_OLD_SERVICES) - // These functions are provided by basic_io_object<>. -#else // defined(ASIO_ENABLE_OLD_SERVICES) -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - - /// Cancel any asynchronous operations that are waiting on the timer. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the timer. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @return The number of asynchronous operations that were cancelled. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel() - { - asio::error_code ec; - std::size_t s = this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - return s; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use non-error_code overload.) Cancel any asynchronous - /// operations that are waiting on the timer. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the timer. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. - * - * @note If the timer has already expired when cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel(asio::error_code& ec) - { - return this->get_service().cancel(this->get_implementation(), ec); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Cancels one asynchronous operation that is waiting on the timer. - /** - * This function forces the completion of one pending asynchronous wait - * operation against the timer. Handlers are cancelled in FIFO order. The - * handler for the cancelled operation will be invoked with the - * asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @return The number of asynchronous operations that were cancelled. That is, - * either 0 or 1. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when cancel_one() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel_one() - { - asio::error_code ec; - std::size_t s = this->get_service().cancel_one( - this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel_one"); - return s; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use non-error_code overload.) Cancels one asynchronous - /// operation that is waiting on the timer. - /** - * This function forces the completion of one pending asynchronous wait - * operation against the timer. Handlers are cancelled in FIFO order. The - * handler for the cancelled operation will be invoked with the - * asio::error::operation_aborted error code. - * - * Cancelling the timer does not change the expiry time. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. That is, - * either 0 or 1. - * - * @note If the timer has already expired when cancel_one() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t cancel_one(asio::error_code& ec) - { - return this->get_service().cancel_one(this->get_implementation(), ec); - } - - /// (Deprecated: Use expiry().) Get the timer's expiry time as an absolute - /// time. - /** - * This function may be used to obtain the timer's current expiry time. - * Whether the timer has expired or not does not affect this value. - */ - time_point expires_at() const - { - return this->get_service().expires_at(this->get_implementation()); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the timer's expiry time as an absolute time. - /** - * This function may be used to obtain the timer's current expiry time. - * Whether the timer has expired or not does not affect this value. - */ - time_point expiry() const - { - return this->get_service().expiry(this->get_implementation()); - } - - /// Set the timer's expiry time as an absolute time. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @return The number of asynchronous operations that were cancelled. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when expires_at() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_at(const time_point& expiry_time) - { - asio::error_code ec; - std::size_t s = this->get_service().expires_at( - this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_at"); - return s; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use non-error_code overload.) Set the timer's expiry time as - /// an absolute time. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. - * - * @note If the timer has already expired when expires_at() is called, then - * the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_at(const time_point& expiry_time, - asio::error_code& ec) - { - return this->get_service().expires_at( - this->get_implementation(), expiry_time, ec); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Set the timer's expiry time relative to now. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @return The number of asynchronous operations that were cancelled. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when expires_after() is called, - * then the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_after(const duration& expiry_time) - { - asio::error_code ec; - std::size_t s = this->get_service().expires_after( - this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_after"); - return s; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use expiry().) Get the timer's expiry time relative to now. - /** - * This function may be used to obtain the timer's current expiry time. - * Whether the timer has expired or not does not affect this value. - */ - duration expires_from_now() const - { - return this->get_service().expires_from_now(this->get_implementation()); - } - - /// (Deprecated: Use expires_after().) Set the timer's expiry time relative - /// to now. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @return The number of asynchronous operations that were cancelled. - * - * @throws asio::system_error Thrown on failure. - * - * @note If the timer has already expired when expires_from_now() is called, - * then the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_from_now(const duration& expiry_time) - { - asio::error_code ec; - std::size_t s = this->get_service().expires_from_now( - this->get_implementation(), expiry_time, ec); - asio::detail::throw_error(ec, "expires_from_now"); - return s; - } - - /// (Deprecated: Use expires_after().) Set the timer's expiry time relative - /// to now. - /** - * This function sets the expiry time. Any pending asynchronous wait - * operations will be cancelled. The handler for each cancelled operation will - * be invoked with the asio::error::operation_aborted error code. - * - * @param expiry_time The expiry time to be used for the timer. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of asynchronous operations that were cancelled. - * - * @note If the timer has already expired when expires_from_now() is called, - * then the handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - std::size_t expires_from_now(const duration& expiry_time, - asio::error_code& ec) - { - return this->get_service().expires_from_now( - this->get_implementation(), expiry_time, ec); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Perform a blocking wait on the timer. - /** - * This function is used to wait for the timer to expire. This function - * blocks and does not return until the timer has expired. - * - * @throws asio::system_error Thrown on failure. - */ - void wait() - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Perform a blocking wait on the timer. - /** - * This function is used to wait for the timer to expire. This function - * blocks and does not return until the timer has expired. - * - * @param ec Set to indicate what error occurred, if any. - */ - void wait(asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), ec); - } - - /// Start an asynchronous wait on the timer. - /** - * This function may be used to initiate an asynchronous wait against the - * timer. It always returns immediately. - * - * For each call to async_wait(), the supplied handler will be called exactly - * once. The handler will be called when: - * - * @li The timer has expired. - * - * @li The timer was cancelled, in which case the handler is passed the error - * code asio::error::operation_aborted. - * - * @param handler The handler to be called when the timer expires. Copies - * will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(ASIO_MOVE_ARG(WaitHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WaitHandler. - ASIO_WAIT_HANDLER_CHECK(WaitHandler, handler) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_wait(this->get_implementation(), - ASIO_MOVE_CAST(WaitHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - async_completion init(handler); - - this->get_service().async_wait(this->get_implementation(), - init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - -private: - // Disallow copying and assignment. - basic_waitable_timer(const basic_waitable_timer&) ASIO_DELETED; - basic_waitable_timer& operator=( - const basic_waitable_timer&) ASIO_DELETED; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# undef ASIO_SVC_T -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_BASIC_WAITABLE_TIMER_HPP diff --git a/scout_sdk/asio/asio/bind_executor.hpp b/scout_sdk/asio/asio/bind_executor.hpp deleted file mode 100644 index 9e2094b..0000000 --- a/scout_sdk/asio/asio/bind_executor.hpp +++ /dev/null @@ -1,611 +0,0 @@ -// -// bind_executor.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BIND_EXECUTOR_HPP -#define ASIO_BIND_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/detail/variadic_templates.hpp" -#include "asio/associated_executor.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/async_result.hpp" -#include "asio/execution_context.hpp" -#include "asio/is_executor.hpp" -#include "asio/uses_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct executor_binder_check -{ - typedef void type; -}; - -// Helper to automatically define nested typedef result_type. - -template -struct executor_binder_result_type -{ -protected: - typedef void result_type_or_void; -}; - -template -struct executor_binder_result_type::type> -{ - typedef typename T::result_type result_type; -protected: - typedef result_type result_type_or_void; -}; - -template -struct executor_binder_result_type -{ - typedef R result_type; -protected: - typedef result_type result_type_or_void; -}; - -template -struct executor_binder_result_type -{ - typedef R result_type; -protected: - typedef result_type result_type_or_void; -}; - -template -struct executor_binder_result_type -{ - typedef R result_type; -protected: - typedef result_type result_type_or_void; -}; - -template -struct executor_binder_result_type -{ - typedef R result_type; -protected: - typedef result_type result_type_or_void; -}; - -template -struct executor_binder_result_type -{ - typedef R result_type; -protected: - typedef result_type result_type_or_void; -}; - -template -struct executor_binder_result_type -{ - typedef R result_type; -protected: - typedef result_type result_type_or_void; -}; - -// Helper to automatically define nested typedef argument_type. - -template -struct executor_binder_argument_type {}; - -template -struct executor_binder_argument_type::type> -{ - typedef typename T::argument_type argument_type; -}; - -template -struct executor_binder_argument_type -{ - typedef A1 argument_type; -}; - -template -struct executor_binder_argument_type -{ - typedef A1 argument_type; -}; - -// Helper to automatically define nested typedefs first_argument_type and -// second_argument_type. - -template -struct executor_binder_argument_types {}; - -template -struct executor_binder_argument_types::type> -{ - typedef typename T::first_argument_type first_argument_type; - typedef typename T::second_argument_type second_argument_type; -}; - -template -struct executor_binder_argument_type -{ - typedef A1 first_argument_type; - typedef A2 second_argument_type; -}; - -template -struct executor_binder_argument_type -{ - typedef A1 first_argument_type; - typedef A2 second_argument_type; -}; - -// Helper to: -// - Apply the empty base optimisation to the executor. -// - Perform uses_executor construction of the target type, if required. - -template -class executor_binder_base; - -template -class executor_binder_base - : protected Executor -{ -protected: - template - executor_binder_base(ASIO_MOVE_ARG(E) e, ASIO_MOVE_ARG(U) u) - : executor_(ASIO_MOVE_CAST(E)(e)), - target_(executor_arg_t(), executor_, ASIO_MOVE_CAST(U)(u)) - { - } - - Executor executor_; - T target_; -}; - -template -class executor_binder_base -{ -protected: - template - executor_binder_base(ASIO_MOVE_ARG(E) e, ASIO_MOVE_ARG(U) u) - : executor_(ASIO_MOVE_CAST(E)(e)), - target_(ASIO_MOVE_CAST(U)(u)) - { - } - - Executor executor_; - T target_; -}; - -// Helper to enable SFINAE on zero-argument operator() below. - -template -struct executor_binder_result_of0 -{ - typedef void type; -}; - -template -struct executor_binder_result_of0::type>::type> -{ - typedef typename result_of::type type; -}; - -} // namespace detail - -/// A call wrapper type to bind an executor of type @c Executor to an object of -/// type @c T. -template -class executor_binder -#if !defined(GENERATING_DOCUMENTATION) - : public detail::executor_binder_result_type, - public detail::executor_binder_argument_type, - public detail::executor_binder_argument_types, - private detail::executor_binder_base< - T, Executor, uses_executor::value> -#endif // !defined(GENERATING_DOCUMENTATION) -{ -public: - /// The type of the target object. - typedef T target_type; - - /// The type of the associated executor. - typedef Executor executor_type; - -#if defined(GENERATING_DOCUMENTATION) - /// The return type if a function. - /** - * The type of @c result_type is based on the type @c T of the wrapper's - * target object: - * - * @li if @c T is a pointer to function type, @c result_type is a synonym for - * the return type of @c T; - * - * @li if @c T is a class type with a member type @c result_type, then @c - * result_type is a synonym for @c T::result_type; - * - * @li otherwise @c result_type is not defined. - */ - typedef see_below result_type; - - /// The type of the function's argument. - /** - * The type of @c argument_type is based on the type @c T of the wrapper's - * target object: - * - * @li if @c T is a pointer to a function type accepting a single argument, - * @c argument_type is a synonym for the return type of @c T; - * - * @li if @c T is a class type with a member type @c argument_type, then @c - * argument_type is a synonym for @c T::argument_type; - * - * @li otherwise @c argument_type is not defined. - */ - typedef see_below argument_type; - - /// The type of the function's first argument. - /** - * The type of @c first_argument_type is based on the type @c T of the - * wrapper's target object: - * - * @li if @c T is a pointer to a function type accepting two arguments, @c - * first_argument_type is a synonym for the return type of @c T; - * - * @li if @c T is a class type with a member type @c first_argument_type, - * then @c first_argument_type is a synonym for @c T::first_argument_type; - * - * @li otherwise @c first_argument_type is not defined. - */ - typedef see_below first_argument_type; - - /// The type of the function's second argument. - /** - * The type of @c second_argument_type is based on the type @c T of the - * wrapper's target object: - * - * @li if @c T is a pointer to a function type accepting two arguments, @c - * second_argument_type is a synonym for the return type of @c T; - * - * @li if @c T is a class type with a member type @c first_argument_type, - * then @c second_argument_type is a synonym for @c T::second_argument_type; - * - * @li otherwise @c second_argument_type is not defined. - */ - typedef see_below second_argument_type; -#endif // defined(GENERATING_DOCUMENTATION) - - /// Construct an executor wrapper for the specified object. - /** - * This constructor is only valid if the type @c T is constructible from type - * @c U. - */ - template - executor_binder(executor_arg_t, const executor_type& e, - ASIO_MOVE_ARG(U) u) - : base_type(e, ASIO_MOVE_CAST(U)(u)) - { - } - - /// Copy constructor. - executor_binder(const executor_binder& other) - : base_type(other.get_executor(), other.get()) - { - } - - /// Construct a copy, but specify a different executor. - executor_binder(executor_arg_t, const executor_type& e, - const executor_binder& other) - : base_type(e, other.get()) - { - } - - /// Construct a copy of a different executor wrapper type. - /** - * This constructor is only valid if the @c Executor type is constructible - * from type @c OtherExecutor, and the type @c T is constructible from type - * @c U. - */ - template - executor_binder(const executor_binder& other) - : base_type(other.get_executor(), other.get()) - { - } - - /// Construct a copy of a different executor wrapper type, but specify a - /// different executor. - /** - * This constructor is only valid if the type @c T is constructible from type - * @c U. - */ - template - executor_binder(executor_arg_t, const executor_type& e, - const executor_binder& other) - : base_type(e, other.get()) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Move constructor. - executor_binder(executor_binder&& other) - : base_type(ASIO_MOVE_CAST(executor_type)(other.get_executor()), - ASIO_MOVE_CAST(T)(other.get())) - { - } - - /// Move construct the target object, but specify a different executor. - executor_binder(executor_arg_t, const executor_type& e, - executor_binder&& other) - : base_type(e, ASIO_MOVE_CAST(T)(other.get())) - { - } - - /// Move construct from a different executor wrapper type. - template - executor_binder(executor_binder&& other) - : base_type(ASIO_MOVE_CAST(OtherExecutor)(other.get_executor()), - ASIO_MOVE_CAST(U)(other.get())) - { - } - - /// Move construct from a different executor wrapper type, but specify a - /// different executor. - template - executor_binder(executor_arg_t, const executor_type& e, - executor_binder&& other) - : base_type(e, ASIO_MOVE_CAST(U)(other.get())) - { - } - -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destructor. - ~executor_binder() - { - } - - /// Obtain a reference to the target object. - target_type& get() ASIO_NOEXCEPT - { - return this->target_; - } - - /// Obtain a reference to the target object. - const target_type& get() const ASIO_NOEXCEPT - { - return this->target_; - } - - /// Obtain the associated executor. - executor_type get_executor() const ASIO_NOEXCEPT - { - return this->executor_; - } - -#if defined(GENERATING_DOCUMENTATION) - - template auto operator()(Args&& ...); - template auto operator()(Args&& ...) const; - -#elif defined(ASIO_HAS_VARIADIC_TEMPLATES) - - /// Forwarding function call operator. - template - typename result_of::type operator()( - ASIO_MOVE_ARG(Args)... args) - { - return this->target_(ASIO_MOVE_CAST(Args)(args)...); - } - - /// Forwarding function call operator. - template - typename result_of::type operator()( - ASIO_MOVE_ARG(Args)... args) const - { - return this->target_(ASIO_MOVE_CAST(Args)(args)...); - } - -#elif defined(ASIO_HAS_STD_TYPE_TRAITS) && !defined(_MSC_VER) - - typename detail::executor_binder_result_of0::type operator()() - { - return this->target_(); - } - - typename detail::executor_binder_result_of0::type operator()() const - { - return this->target_(); - } - -#define ASIO_PRIVATE_BIND_EXECUTOR_CALL_DEF(n) \ - template \ - typename result_of::type operator()( \ - ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - return this->target_(ASIO_VARIADIC_MOVE_ARGS(n)); \ - } \ - \ - template \ - typename result_of::type operator()( \ - ASIO_VARIADIC_MOVE_PARAMS(n)) const \ - { \ - return this->target_(ASIO_VARIADIC_MOVE_ARGS(n)); \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_BIND_EXECUTOR_CALL_DEF) -#undef ASIO_PRIVATE_BIND_EXECUTOR_CALL_DEF - -#else // defined(ASIO_HAS_STD_TYPE_TRAITS) && !defined(_MSC_VER) - - typedef typename detail::executor_binder_result_type::result_type_or_void - result_type_or_void; - - result_type_or_void operator()() - { - return this->target_(); - } - - result_type_or_void operator()() const - { - return this->target_(); - } - -#define ASIO_PRIVATE_BIND_EXECUTOR_CALL_DEF(n) \ - template \ - result_type_or_void operator()( \ - ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - return this->target_(ASIO_VARIADIC_MOVE_ARGS(n)); \ - } \ - \ - template \ - result_type_or_void operator()( \ - ASIO_VARIADIC_MOVE_PARAMS(n)) const \ - { \ - return this->target_(ASIO_VARIADIC_MOVE_ARGS(n)); \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_BIND_EXECUTOR_CALL_DEF) -#undef ASIO_PRIVATE_BIND_EXECUTOR_CALL_DEF - -#endif // defined(ASIO_HAS_STD_TYPE_TRAITS) && !defined(_MSC_VER) - -private: - typedef detail::executor_binder_base::value> base_type; -}; - -/// Associate an object of type @c T with an executor of type @c Executor. -template -inline executor_binder::type, Executor> -bind_executor(const Executor& ex, ASIO_MOVE_ARG(T) t, - typename enable_if::value>::type* = 0) -{ - return executor_binder::type, Executor>( - executor_arg_t(), ex, ASIO_MOVE_CAST(T)(t)); -} - -/// Associate an object of type @c T with an execution context's executor. -template -inline executor_binder::type, - typename ExecutionContext::executor_type> -bind_executor(ExecutionContext& ctx, ASIO_MOVE_ARG(T) t, - typename enable_if::value>::type* = 0) -{ - return executor_binder::type, - typename ExecutionContext::executor_type>( - executor_arg_t(), ctx.get_executor(), ASIO_MOVE_CAST(T)(t)); -} - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct uses_executor, Executor> - : true_type {}; - -template -class async_result, Signature> -{ -public: - typedef executor_binder< - typename async_result::completion_handler_type, Executor> - completion_handler_type; - - typedef typename async_result::return_type return_type; - - explicit async_result(executor_binder& b) - : target_(b.get()) - { - } - - return_type get() - { - return target_.get(); - } - -private: - async_result(const async_result&) ASIO_DELETED; - async_result& operator=(const async_result&) ASIO_DELETED; - - async_result target_; -}; - -#if !defined(ASIO_NO_DEPRECATED) - -template -struct handler_type, Signature> -{ - typedef executor_binder< - typename handler_type::type, Executor> type; -}; - -template -class async_result > -{ -public: - typedef typename async_result::type type; - - explicit async_result(executor_binder& b) - : target_(b.get()) - { - } - - type get() - { - return target_.get(); - } - -private: - async_result target_; -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -struct associated_allocator, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const executor_binder& b, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(b.get(), a); - } -}; - -template -struct associated_executor, Executor1> -{ - typedef Executor type; - - static type get(const executor_binder& b, - const Executor1& = Executor1()) ASIO_NOEXCEPT - { - return b.get_executor(); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BIND_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/buffer.hpp b/scout_sdk/asio/asio/buffer.hpp deleted file mode 100644 index a9aa8aa..0000000 --- a/scout_sdk/asio/asio/buffer.hpp +++ /dev/null @@ -1,2162 +0,0 @@ -// -// buffer.hpp -// ~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFER_HPP -#define ASIO_BUFFER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include -#include -#include -#include "asio/detail/array_fwd.hpp" -#include "asio/detail/is_buffer_sequence.hpp" -#include "asio/detail/string_view.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/detail/type_traits.hpp" - -#if defined(ASIO_MSVC) && (ASIO_MSVC >= 1700) -# if defined(_HAS_ITERATOR_DEBUGGING) && (_HAS_ITERATOR_DEBUGGING != 0) -# if !defined(ASIO_DISABLE_BUFFER_DEBUGGING) -# define ASIO_ENABLE_BUFFER_DEBUGGING -# endif // !defined(ASIO_DISABLE_BUFFER_DEBUGGING) -# endif // defined(_HAS_ITERATOR_DEBUGGING) -#endif // defined(ASIO_MSVC) && (ASIO_MSVC >= 1700) - -#if defined(__GNUC__) -# if defined(_GLIBCXX_DEBUG) -# if !defined(ASIO_DISABLE_BUFFER_DEBUGGING) -# define ASIO_ENABLE_BUFFER_DEBUGGING -# endif // !defined(ASIO_DISABLE_BUFFER_DEBUGGING) -# endif // defined(_GLIBCXX_DEBUG) -#endif // defined(__GNUC__) - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) -# include "asio/detail/functional.hpp" -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - -#if defined(ASIO_HAS_BOOST_WORKAROUND) -# include -# if BOOST_WORKAROUND(__BORLANDC__, BOOST_TESTED_AT(0x582)) \ - || BOOST_WORKAROUND(__SUNPRO_CC, BOOST_TESTED_AT(0x590)) -# define ASIO_ENABLE_ARRAY_BUFFER_WORKAROUND -# endif // BOOST_WORKAROUND(__BORLANDC__, BOOST_TESTED_AT(0x582)) - // || BOOST_WORKAROUND(__SUNPRO_CC, BOOST_TESTED_AT(0x590)) -#endif // defined(ASIO_HAS_BOOST_WORKAROUND) - -#if defined(ASIO_ENABLE_ARRAY_BUFFER_WORKAROUND) -# include "asio/detail/type_traits.hpp" -#endif // defined(ASIO_ENABLE_ARRAY_BUFFER_WORKAROUND) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -class mutable_buffer; -class const_buffer; - -/// Holds a buffer that can be modified. -/** - * The mutable_buffer class provides a safe representation of a buffer that can - * be modified. It does not own the underlying data, and so is cheap to copy or - * assign. - * - * @par Accessing Buffer Contents - * - * The contents of a buffer may be accessed using the @c data() and @c size() - * member functions: - * - * @code asio::mutable_buffer b1 = ...; - * std::size_t s1 = b1.size(); - * unsigned char* p1 = static_cast(b1.data()); - * @endcode - * - * The @c data() member function permits violations of type safety, so uses of - * it in application code should be carefully considered. - */ -class mutable_buffer -{ -public: - /// Construct an empty buffer. - mutable_buffer() ASIO_NOEXCEPT - : data_(0), - size_(0) - { - } - - /// Construct a buffer to represent a given memory range. - mutable_buffer(void* data, std::size_t size) ASIO_NOEXCEPT - : data_(data), - size_(size) - { - } - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - mutable_buffer(void* data, std::size_t size, - asio::detail::function debug_check) - : data_(data), - size_(size), - debug_check_(debug_check) - { - } - - const asio::detail::function& get_debug_check() const - { - return debug_check_; - } -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - - /// Get a pointer to the beginning of the memory range. - void* data() const ASIO_NOEXCEPT - { -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - if (size_ && debug_check_) - debug_check_(); -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - return data_; - } - - /// Get the size of the memory range. - std::size_t size() const ASIO_NOEXCEPT - { - return size_; - } - - /// Move the start of the buffer by the specified number of bytes. - mutable_buffer& operator+=(std::size_t n) ASIO_NOEXCEPT - { - std::size_t offset = n < size_ ? n : size_; - data_ = static_cast(data_) + offset; - size_ -= offset; - return *this; - } - -private: - void* data_; - std::size_t size_; - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - asio::detail::function debug_check_; -#endif // ASIO_ENABLE_BUFFER_DEBUGGING -}; - -#if !defined(ASIO_NO_DEPRECATED) - -/// (Deprecated: Use mutable_buffer.) Adapts a single modifiable buffer so that -/// it meets the requirements of the MutableBufferSequence concept. -class mutable_buffers_1 - : public mutable_buffer -{ -public: - /// The type for each element in the list of buffers. - typedef mutable_buffer value_type; - - /// A random-access iterator type that may be used to read elements. - typedef const mutable_buffer* const_iterator; - - /// Construct to represent a given memory range. - mutable_buffers_1(void* data, std::size_t size) ASIO_NOEXCEPT - : mutable_buffer(data, size) - { - } - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - mutable_buffers_1(void* data, std::size_t size, - asio::detail::function debug_check) - : mutable_buffer(data, size, debug_check) - { - } -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - - /// Construct to represent a single modifiable buffer. - explicit mutable_buffers_1(const mutable_buffer& b) ASIO_NOEXCEPT - : mutable_buffer(b) - { - } - - /// Get a random-access iterator to the first element. - const_iterator begin() const ASIO_NOEXCEPT - { - return this; - } - - /// Get a random-access iterator for one past the last element. - const_iterator end() const ASIO_NOEXCEPT - { - return begin() + 1; - } -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Holds a buffer that cannot be modified. -/** - * The const_buffer class provides a safe representation of a buffer that cannot - * be modified. It does not own the underlying data, and so is cheap to copy or - * assign. - * - * @par Accessing Buffer Contents - * - * The contents of a buffer may be accessed using the @c data() and @c size() - * member functions: - * - * @code asio::const_buffer b1 = ...; - * std::size_t s1 = b1.size(); - * const unsigned char* p1 = static_cast(b1.data()); - * @endcode - * - * The @c data() member function permits violations of type safety, so uses of - * it in application code should be carefully considered. - */ -class const_buffer -{ -public: - /// Construct an empty buffer. - const_buffer() ASIO_NOEXCEPT - : data_(0), - size_(0) - { - } - - /// Construct a buffer to represent a given memory range. - const_buffer(const void* data, std::size_t size) ASIO_NOEXCEPT - : data_(data), - size_(size) - { - } - - /// Construct a non-modifiable buffer from a modifiable one. - const_buffer(const mutable_buffer& b) ASIO_NOEXCEPT - : data_(b.data()), - size_(b.size()) -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , debug_check_(b.get_debug_check()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - { - } - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - const_buffer(const void* data, std::size_t size, - asio::detail::function debug_check) - : data_(data), - size_(size), - debug_check_(debug_check) - { - } - - const asio::detail::function& get_debug_check() const - { - return debug_check_; - } -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - - /// Get a pointer to the beginning of the memory range. - const void* data() const ASIO_NOEXCEPT - { -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - if (size_ && debug_check_) - debug_check_(); -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - return data_; - } - - /// Get the size of the memory range. - std::size_t size() const ASIO_NOEXCEPT - { - return size_; - } - - /// Move the start of the buffer by the specified number of bytes. - const_buffer& operator+=(std::size_t n) ASIO_NOEXCEPT - { - std::size_t offset = n < size_ ? n : size_; - data_ = static_cast(data_) + offset; - size_ -= offset; - return *this; - } - -private: - const void* data_; - std::size_t size_; - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - asio::detail::function debug_check_; -#endif // ASIO_ENABLE_BUFFER_DEBUGGING -}; - -#if !defined(ASIO_NO_DEPRECATED) - -/// (Deprecated: Use const_buffer.) Adapts a single non-modifiable buffer so -/// that it meets the requirements of the ConstBufferSequence concept. -class const_buffers_1 - : public const_buffer -{ -public: - /// The type for each element in the list of buffers. - typedef const_buffer value_type; - - /// A random-access iterator type that may be used to read elements. - typedef const const_buffer* const_iterator; - - /// Construct to represent a given memory range. - const_buffers_1(const void* data, std::size_t size) ASIO_NOEXCEPT - : const_buffer(data, size) - { - } - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - const_buffers_1(const void* data, std::size_t size, - asio::detail::function debug_check) - : const_buffer(data, size, debug_check) - { - } -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - - /// Construct to represent a single non-modifiable buffer. - explicit const_buffers_1(const const_buffer& b) ASIO_NOEXCEPT - : const_buffer(b) - { - } - - /// Get a random-access iterator to the first element. - const_iterator begin() const ASIO_NOEXCEPT - { - return this; - } - - /// Get a random-access iterator for one past the last element. - const_iterator end() const ASIO_NOEXCEPT - { - return begin() + 1; - } -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Trait to determine whether a type satisfies the MutableBufferSequence -/// requirements. -template -struct is_mutable_buffer_sequence -#if defined(GENERATING_DOCUMENTATION) - : integral_constant -#else // defined(GENERATING_DOCUMENTATION) - : asio::detail::is_buffer_sequence -#endif // defined(GENERATING_DOCUMENTATION) -{ -}; - -/// Trait to determine whether a type satisfies the ConstBufferSequence -/// requirements. -template -struct is_const_buffer_sequence -#if defined(GENERATING_DOCUMENTATION) - : integral_constant -#else // defined(GENERATING_DOCUMENTATION) - : asio::detail::is_buffer_sequence -#endif // defined(GENERATING_DOCUMENTATION) -{ -}; - -/// Trait to determine whether a type satisfies the DynamicBuffer requirements. -template -struct is_dynamic_buffer -#if defined(GENERATING_DOCUMENTATION) - : integral_constant -#else // defined(GENERATING_DOCUMENTATION) - : asio::detail::is_dynamic_buffer -#endif // defined(GENERATING_DOCUMENTATION) -{ -}; - -/// (Deprecated: Use the socket/descriptor wait() and async_wait() member -/// functions.) An implementation of both the ConstBufferSequence and -/// MutableBufferSequence concepts to represent a null buffer sequence. -class null_buffers -{ -public: - /// The type for each element in the list of buffers. - typedef mutable_buffer value_type; - - /// A random-access iterator type that may be used to read elements. - typedef const mutable_buffer* const_iterator; - - /// Get a random-access iterator to the first element. - const_iterator begin() const ASIO_NOEXCEPT - { - return &buf_; - } - - /// Get a random-access iterator for one past the last element. - const_iterator end() const ASIO_NOEXCEPT - { - return &buf_; - } - -private: - mutable_buffer buf_; -}; - -/** @defgroup buffer_sequence_begin asio::buffer_sequence_begin - * - * @brief The asio::buffer_sequence_begin function returns an iterator - * pointing to the first element in a buffer sequence. - */ -/*@{*/ - -/// Get an iterator to the first element in a buffer sequence. -inline const mutable_buffer* buffer_sequence_begin(const mutable_buffer& b) -{ - return &b; -} - -/// Get an iterator to the first element in a buffer sequence. -inline const const_buffer* buffer_sequence_begin(const const_buffer& b) -{ - return &b; -} - -#if defined(ASIO_HAS_DECLTYPE) || defined(GENERATING_DOCUMENTATION) - -/// Get an iterator to the first element in a buffer sequence. -template -inline auto buffer_sequence_begin(C& c) -> decltype(c.begin()) -{ - return c.begin(); -} - -/// Get an iterator to the first element in a buffer sequence. -template -inline auto buffer_sequence_begin(const C& c) -> decltype(c.begin()) -{ - return c.begin(); -} - -#else // defined(ASIO_HAS_DECLTYPE) || defined(GENERATING_DOCUMENTATION) - -template -inline typename C::iterator buffer_sequence_begin(C& c) -{ - return c.begin(); -} - -template -inline typename C::const_iterator buffer_sequence_begin(const C& c) -{ - return c.begin(); -} - -#endif // defined(ASIO_HAS_DECLTYPE) || defined(GENERATING_DOCUMENTATION) - -/*@}*/ - -/** @defgroup buffer_sequence_end asio::buffer_sequence_end - * - * @brief The asio::buffer_sequence_end function returns an iterator - * pointing to one past the end element in a buffer sequence. - */ -/*@{*/ - -/// Get an iterator to one past the end element in a buffer sequence. -inline const mutable_buffer* buffer_sequence_end(const mutable_buffer& b) -{ - return &b + 1; -} - -/// Get an iterator to one past the end element in a buffer sequence. -inline const const_buffer* buffer_sequence_end(const const_buffer& b) -{ - return &b + 1; -} - -#if defined(ASIO_HAS_DECLTYPE) || defined(GENERATING_DOCUMENTATION) - -/// Get an iterator to one past the end element in a buffer sequence. -template -inline auto buffer_sequence_end(C& c) -> decltype(c.end()) -{ - return c.end(); -} - -/// Get an iterator to one past the end element in a buffer sequence. -template -inline auto buffer_sequence_end(const C& c) -> decltype(c.end()) -{ - return c.end(); -} - -#else // defined(ASIO_HAS_DECLTYPE) || defined(GENERATING_DOCUMENTATION) - -template -inline typename C::iterator buffer_sequence_end(C& c) -{ - return c.end(); -} - -template -inline typename C::const_iterator buffer_sequence_end(const C& c) -{ - return c.end(); -} - -#endif // defined(ASIO_HAS_DECLTYPE) || defined(GENERATING_DOCUMENTATION) - -/*@}*/ - -namespace detail { - -// Tag types used to select appropriately optimised overloads. -struct one_buffer {}; -struct multiple_buffers {}; - -// Helper trait to detect single buffers. -template -struct buffer_sequence_cardinality : - conditional< - is_same::value -#if !defined(ASIO_NO_DEPRECATED) - || is_same::value - || is_same::value -#endif // !defined(ASIO_NO_DEPRECATED) - || is_same::value, - one_buffer, multiple_buffers>::type {}; - -template -inline std::size_t buffer_size(one_buffer, - Iterator begin, Iterator) ASIO_NOEXCEPT -{ - return const_buffer(*begin).size(); -} - -template -inline std::size_t buffer_size(multiple_buffers, - Iterator begin, Iterator end) ASIO_NOEXCEPT -{ - std::size_t total_buffer_size = 0; - - Iterator iter = begin; - for (; iter != end; ++iter) - { - const_buffer b(*iter); - total_buffer_size += b.size(); - } - - return total_buffer_size; -} - -} // namespace detail - -/// Get the total number of bytes in a buffer sequence. -/** - * The @c buffer_size function determines the total size of all buffers in the - * buffer sequence, as if computed as follows: - * - * @code size_t total_size = 0; - * auto i = asio::buffer_sequence_begin(buffers); - * auto end = asio::buffer_sequence_end(buffers); - * for (; i != end; ++i) - * { - * const_buffer b(*i); - * total_size += b.size(); - * } - * return total_size; @endcode - * - * The @c BufferSequence template parameter may meet either of the @c - * ConstBufferSequence or @c MutableBufferSequence type requirements. - */ -template -inline std::size_t buffer_size(const BufferSequence& b) ASIO_NOEXCEPT -{ - return detail::buffer_size( - detail::buffer_sequence_cardinality(), - asio::buffer_sequence_begin(b), - asio::buffer_sequence_end(b)); -} - -#if !defined(ASIO_NO_DEPRECATED) - -/** @defgroup buffer_cast asio::buffer_cast - * - * @brief (Deprecated: Use the @c data() member function.) The - * asio::buffer_cast function is used to obtain a pointer to the - * underlying memory region associated with a buffer. - * - * @par Examples: - * - * To access the memory of a non-modifiable buffer, use: - * @code asio::const_buffer b1 = ...; - * const unsigned char* p1 = asio::buffer_cast(b1); - * @endcode - * - * To access the memory of a modifiable buffer, use: - * @code asio::mutable_buffer b2 = ...; - * unsigned char* p2 = asio::buffer_cast(b2); - * @endcode - * - * The asio::buffer_cast function permits violations of type safety, so - * uses of it in application code should be carefully considered. - */ -/*@{*/ - -/// Cast a non-modifiable buffer to a specified pointer to POD type. -template -inline PointerToPodType buffer_cast(const mutable_buffer& b) ASIO_NOEXCEPT -{ - return static_cast(b.data()); -} - -/// Cast a non-modifiable buffer to a specified pointer to POD type. -template -inline PointerToPodType buffer_cast(const const_buffer& b) ASIO_NOEXCEPT -{ - return static_cast(b.data()); -} - -/*@}*/ - -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Create a new modifiable buffer that is offset from the start of another. -/** - * @relates mutable_buffer - */ -inline mutable_buffer operator+(const mutable_buffer& b, - std::size_t n) ASIO_NOEXCEPT -{ - std::size_t offset = n < b.size() ? n : b.size(); - char* new_data = static_cast(b.data()) + offset; - std::size_t new_size = b.size() - offset; - return mutable_buffer(new_data, new_size -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , b.get_debug_check() -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new modifiable buffer that is offset from the start of another. -/** - * @relates mutable_buffer - */ -inline mutable_buffer operator+(std::size_t n, - const mutable_buffer& b) ASIO_NOEXCEPT -{ - return b + n; -} - -/// Create a new non-modifiable buffer that is offset from the start of another. -/** - * @relates const_buffer - */ -inline const_buffer operator+(const const_buffer& b, - std::size_t n) ASIO_NOEXCEPT -{ - std::size_t offset = n < b.size() ? n : b.size(); - const char* new_data = static_cast(b.data()) + offset; - std::size_t new_size = b.size() - offset; - return const_buffer(new_data, new_size -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , b.get_debug_check() -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new non-modifiable buffer that is offset from the start of another. -/** - * @relates const_buffer - */ -inline const_buffer operator+(std::size_t n, - const const_buffer& b) ASIO_NOEXCEPT -{ - return b + n; -} - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) -namespace detail { - -template -class buffer_debug_check -{ -public: - buffer_debug_check(Iterator iter) - : iter_(iter) - { - } - - ~buffer_debug_check() - { -#if defined(ASIO_MSVC) && (ASIO_MSVC == 1400) - // MSVC 8's string iterator checking may crash in a std::string::iterator - // object's destructor when the iterator points to an already-destroyed - // std::string object, unless the iterator is cleared first. - iter_ = Iterator(); -#endif // defined(ASIO_MSVC) && (ASIO_MSVC == 1400) - } - - void operator()() - { - (void)*iter_; - } - -private: - Iterator iter_; -}; - -} // namespace detail -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - -/** @defgroup buffer asio::buffer - * - * @brief The asio::buffer function is used to create a buffer object to - * represent raw memory, an array of POD elements, a vector of POD elements, - * or a std::string. - * - * A buffer object represents a contiguous region of memory as a 2-tuple - * consisting of a pointer and size in bytes. A tuple of the form {void*, - * size_t} specifies a mutable (modifiable) region of memory. Similarly, a - * tuple of the form {const void*, size_t} specifies a const - * (non-modifiable) region of memory. These two forms correspond to the classes - * mutable_buffer and const_buffer, respectively. To mirror C++'s conversion - * rules, a mutable_buffer is implicitly convertible to a const_buffer, and the - * opposite conversion is not permitted. - * - * The simplest use case involves reading or writing a single buffer of a - * specified size: - * - * @code sock.send(asio::buffer(data, size)); @endcode - * - * In the above example, the return value of asio::buffer meets the - * requirements of the ConstBufferSequence concept so that it may be directly - * passed to the socket's write function. A buffer created for modifiable - * memory also meets the requirements of the MutableBufferSequence concept. - * - * An individual buffer may be created from a builtin array, std::vector, - * std::array or boost::array of POD elements. This helps prevent buffer - * overruns by automatically determining the size of the buffer: - * - * @code char d1[128]; - * size_t bytes_transferred = sock.receive(asio::buffer(d1)); - * - * std::vector d2(128); - * bytes_transferred = sock.receive(asio::buffer(d2)); - * - * std::array d3; - * bytes_transferred = sock.receive(asio::buffer(d3)); - * - * boost::array d4; - * bytes_transferred = sock.receive(asio::buffer(d4)); @endcode - * - * In all three cases above, the buffers created are exactly 128 bytes long. - * Note that a vector is @e never automatically resized when creating or using - * a buffer. The buffer size is determined using the vector's size() - * member function, and not its capacity. - * - * @par Accessing Buffer Contents - * - * The contents of a buffer may be accessed using the @c data() and @c size() - * member functions: - * - * @code asio::mutable_buffer b1 = ...; - * std::size_t s1 = b1.size(); - * unsigned char* p1 = static_cast(b1.data()); - * - * asio::const_buffer b2 = ...; - * std::size_t s2 = b2.size(); - * const void* p2 = b2.data(); @endcode - * - * The @c data() member function permits violations of type safety, so - * uses of it in application code should be carefully considered. - * - * For convenience, a @ref buffer_size function is provided that works with - * both buffers and buffer sequences (that is, types meeting the - * ConstBufferSequence or MutableBufferSequence type requirements). In this - * case, the function returns the total size of all buffers in the sequence. - * - * @par Buffer Copying - * - * The @ref buffer_copy function may be used to copy raw bytes between - * individual buffers and buffer sequences. -* - * In particular, when used with the @ref buffer_size function, the @ref - * buffer_copy function can be used to linearise a sequence of buffers. For - * example: - * - * @code vector buffers = ...; - * - * vector data(asio::buffer_size(buffers)); - * asio::buffer_copy(asio::buffer(data), buffers); @endcode - * - * Note that @ref buffer_copy is implemented in terms of @c memcpy, and - * consequently it cannot be used to copy between overlapping memory regions. - * - * @par Buffer Invalidation - * - * A buffer object does not have any ownership of the memory it refers to. It - * is the responsibility of the application to ensure the memory region remains - * valid until it is no longer required for an I/O operation. When the memory - * is no longer available, the buffer is said to have been invalidated. - * - * For the asio::buffer overloads that accept an argument of type - * std::vector, the buffer objects returned are invalidated by any vector - * operation that also invalidates all references, pointers and iterators - * referring to the elements in the sequence (C++ Std, 23.2.4) - * - * For the asio::buffer overloads that accept an argument of type - * std::basic_string, the buffer objects returned are invalidated according to - * the rules defined for invalidation of references, pointers and iterators - * referring to elements of the sequence (C++ Std, 21.3). - * - * @par Buffer Arithmetic - * - * Buffer objects may be manipulated using simple arithmetic in a safe way - * which helps prevent buffer overruns. Consider an array initialised as - * follows: - * - * @code boost::array a = { 'a', 'b', 'c', 'd', 'e' }; @endcode - * - * A buffer object @c b1 created using: - * - * @code b1 = asio::buffer(a); @endcode - * - * represents the entire array, { 'a', 'b', 'c', 'd', 'e' }. An - * optional second argument to the asio::buffer function may be used to - * limit the size, in bytes, of the buffer: - * - * @code b2 = asio::buffer(a, 3); @endcode - * - * such that @c b2 represents the data { 'a', 'b', 'c' }. Even if the - * size argument exceeds the actual size of the array, the size of the buffer - * object created will be limited to the array size. - * - * An offset may be applied to an existing buffer to create a new one: - * - * @code b3 = b1 + 2; @endcode - * - * where @c b3 will set to represent { 'c', 'd', 'e' }. If the offset - * exceeds the size of the existing buffer, the newly created buffer will be - * empty. - * - * Both an offset and size may be specified to create a buffer that corresponds - * to a specific range of bytes within an existing buffer: - * - * @code b4 = asio::buffer(b1 + 1, 3); @endcode - * - * so that @c b4 will refer to the bytes { 'b', 'c', 'd' }. - * - * @par Buffers and Scatter-Gather I/O - * - * To read or write using multiple buffers (i.e. scatter-gather I/O), multiple - * buffer objects may be assigned into a container that supports the - * MutableBufferSequence (for read) or ConstBufferSequence (for write) concepts: - * - * @code - * char d1[128]; - * std::vector d2(128); - * boost::array d3; - * - * boost::array bufs1 = { - * asio::buffer(d1), - * asio::buffer(d2), - * asio::buffer(d3) }; - * bytes_transferred = sock.receive(bufs1); - * - * std::vector bufs2; - * bufs2.push_back(asio::buffer(d1)); - * bufs2.push_back(asio::buffer(d2)); - * bufs2.push_back(asio::buffer(d3)); - * bytes_transferred = sock.send(bufs2); @endcode - */ -/*@{*/ - -#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) -# define ASIO_MUTABLE_BUFFER mutable_buffer -# define ASIO_CONST_BUFFER const_buffer -#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) -# define ASIO_MUTABLE_BUFFER mutable_buffers_1 -# define ASIO_CONST_BUFFER const_buffers_1 -#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION) - -/// Create a new modifiable buffer from an existing buffer. -/** - * @returns mutable_buffer(b). - */ -inline ASIO_MUTABLE_BUFFER buffer( - const mutable_buffer& b) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(b); -} - -/// Create a new modifiable buffer from an existing buffer. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * b.data(), - * min(b.size(), max_size_in_bytes)); @endcode - */ -inline ASIO_MUTABLE_BUFFER buffer(const mutable_buffer& b, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER( - mutable_buffer(b.data(), - b.size() < max_size_in_bytes - ? b.size() : max_size_in_bytes -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , b.get_debug_check() -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - )); -} - -/// Create a new non-modifiable buffer from an existing buffer. -/** - * @returns const_buffer(b). - */ -inline ASIO_CONST_BUFFER buffer( - const const_buffer& b) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(b); -} - -/// Create a new non-modifiable buffer from an existing buffer. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * b.data(), - * min(b.size(), max_size_in_bytes)); @endcode - */ -inline ASIO_CONST_BUFFER buffer(const const_buffer& b, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(b.data(), - b.size() < max_size_in_bytes - ? b.size() : max_size_in_bytes -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , b.get_debug_check() -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new modifiable buffer that represents the given memory range. -/** - * @returns mutable_buffer(data, size_in_bytes). - */ -inline ASIO_MUTABLE_BUFFER buffer(void* data, - std::size_t size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data, size_in_bytes); -} - -/// Create a new non-modifiable buffer that represents the given memory range. -/** - * @returns const_buffer(data, size_in_bytes). - */ -inline ASIO_CONST_BUFFER buffer(const void* data, - std::size_t size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data, size_in_bytes); -} - -/// Create a new modifiable buffer that represents the given POD array. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * static_cast(data), - * N * sizeof(PodType)); @endcode - */ -template -inline ASIO_MUTABLE_BUFFER buffer(PodType (&data)[N]) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data, N * sizeof(PodType)); -} - -/// Create a new modifiable buffer that represents the given POD array. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * static_cast(data), - * min(N * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_MUTABLE_BUFFER buffer(PodType (&data)[N], - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data, - N * sizeof(PodType) < max_size_in_bytes - ? N * sizeof(PodType) : max_size_in_bytes); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * static_cast(data), - * N * sizeof(PodType)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer( - const PodType (&data)[N]) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data, N * sizeof(PodType)); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * static_cast(data), - * min(N * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer(const PodType (&data)[N], - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data, - N * sizeof(PodType) < max_size_in_bytes - ? N * sizeof(PodType) : max_size_in_bytes); -} - -#if defined(ASIO_ENABLE_ARRAY_BUFFER_WORKAROUND) - -// Borland C++ and Sun Studio think the overloads: -// -// unspecified buffer(boost::array& array ...); -// -// and -// -// unspecified buffer(boost::array& array ...); -// -// are ambiguous. This will be worked around by using a buffer_types traits -// class that contains typedefs for the appropriate buffer and container -// classes, based on whether PodType is const or non-const. - -namespace detail { - -template -struct buffer_types_base; - -template <> -struct buffer_types_base -{ - typedef mutable_buffer buffer_type; - typedef ASIO_MUTABLE_BUFFER container_type; -}; - -template <> -struct buffer_types_base -{ - typedef const_buffer buffer_type; - typedef ASIO_CONST_BUFFER container_type; -}; - -template -struct buffer_types - : public buffer_types_base::value> -{ -}; - -} // namespace detail - -template -inline typename detail::buffer_types::container_type -buffer(boost::array& data) ASIO_NOEXCEPT -{ - typedef typename asio::detail::buffer_types::buffer_type - buffer_type; - typedef typename asio::detail::buffer_types::container_type - container_type; - return container_type( - buffer_type(data.c_array(), data.size() * sizeof(PodType))); -} - -template -inline typename detail::buffer_types::container_type -buffer(boost::array& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - typedef typename asio::detail::buffer_types::buffer_type - buffer_type; - typedef typename asio::detail::buffer_types::container_type - container_type; - return container_type( - buffer_type(data.c_array(), - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes)); -} - -#else // defined(ASIO_ENABLE_ARRAY_BUFFER_WORKAROUND) - -/// Create a new modifiable buffer that represents the given POD array. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.data(), - * data.size() * sizeof(PodType)); @endcode - */ -template -inline ASIO_MUTABLE_BUFFER buffer( - boost::array& data) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER( - data.c_array(), data.size() * sizeof(PodType)); -} - -/// Create a new modifiable buffer that represents the given POD array. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.data(), - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_MUTABLE_BUFFER buffer(boost::array& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data.c_array(), - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * data.size() * sizeof(PodType)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer( - boost::array& data) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), data.size() * sizeof(PodType)); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer(boost::array& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes); -} - -#endif // defined(ASIO_ENABLE_ARRAY_BUFFER_WORKAROUND) - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * data.size() * sizeof(PodType)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer( - const boost::array& data) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), data.size() * sizeof(PodType)); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer(const boost::array& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes); -} - -#if defined(ASIO_HAS_STD_ARRAY) || defined(GENERATING_DOCUMENTATION) - -/// Create a new modifiable buffer that represents the given POD array. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.data(), - * data.size() * sizeof(PodType)); @endcode - */ -template -inline ASIO_MUTABLE_BUFFER buffer( - std::array& data) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data.data(), data.size() * sizeof(PodType)); -} - -/// Create a new modifiable buffer that represents the given POD array. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.data(), - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_MUTABLE_BUFFER buffer(std::array& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data.data(), - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * data.size() * sizeof(PodType)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer( - std::array& data) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), data.size() * sizeof(PodType)); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer(std::array& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * data.size() * sizeof(PodType)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer( - const std::array& data) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), data.size() * sizeof(PodType)); -} - -/// Create a new non-modifiable buffer that represents the given POD array. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer(const std::array& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes); -} - -#endif // defined(ASIO_HAS_STD_ARRAY) || defined(GENERATING_DOCUMENTATION) - -/// Create a new modifiable buffer that represents the given POD vector. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.size() ? &data[0] : 0, - * data.size() * sizeof(PodType)); @endcode - * - * @note The buffer is invalidated by any vector operation that would also - * invalidate iterators. - */ -template -inline ASIO_MUTABLE_BUFFER buffer( - std::vector& data) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER( - data.size() ? &data[0] : 0, data.size() * sizeof(PodType) -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::vector::iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new modifiable buffer that represents the given POD vector. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.size() ? &data[0] : 0, - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - * - * @note The buffer is invalidated by any vector operation that would also - * invalidate iterators. - */ -template -inline ASIO_MUTABLE_BUFFER buffer(std::vector& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data.size() ? &data[0] : 0, - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::vector::iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new non-modifiable buffer that represents the given POD vector. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.size() ? &data[0] : 0, - * data.size() * sizeof(PodType)); @endcode - * - * @note The buffer is invalidated by any vector operation that would also - * invalidate iterators. - */ -template -inline ASIO_CONST_BUFFER buffer( - const std::vector& data) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER( - data.size() ? &data[0] : 0, data.size() * sizeof(PodType) -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::vector::const_iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new non-modifiable buffer that represents the given POD vector. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.size() ? &data[0] : 0, - * min(data.size() * sizeof(PodType), max_size_in_bytes)); @endcode - * - * @note The buffer is invalidated by any vector operation that would also - * invalidate iterators. - */ -template -inline ASIO_CONST_BUFFER buffer( - const std::vector& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.size() ? &data[0] : 0, - data.size() * sizeof(PodType) < max_size_in_bytes - ? data.size() * sizeof(PodType) : max_size_in_bytes -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::vector::const_iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new modifiable buffer that represents the given string. -/** - * @returns mutable_buffer(data.size() ? &data[0] : 0, - * data.size() * sizeof(Elem)). - * - * @note The buffer is invalidated by any non-const operation called on the - * given string object. - */ -template -inline ASIO_MUTABLE_BUFFER buffer( - std::basic_string& data) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data.size() ? &data[0] : 0, - data.size() * sizeof(Elem) -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::basic_string::iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new non-modifiable buffer that represents the given string. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.size() ? &data[0] : 0, - * min(data.size() * sizeof(Elem), max_size_in_bytes)); @endcode - * - * @note The buffer is invalidated by any non-const operation called on the - * given string object. - */ -template -inline ASIO_MUTABLE_BUFFER buffer( - std::basic_string& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_MUTABLE_BUFFER(data.size() ? &data[0] : 0, - data.size() * sizeof(Elem) < max_size_in_bytes - ? data.size() * sizeof(Elem) : max_size_in_bytes -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::basic_string::iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new non-modifiable buffer that represents the given string. -/** - * @returns const_buffer(data.data(), data.size() * sizeof(Elem)). - * - * @note The buffer is invalidated by any non-const operation called on the - * given string object. - */ -template -inline ASIO_CONST_BUFFER buffer( - const std::basic_string& data) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), data.size() * sizeof(Elem) -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::basic_string::const_iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new non-modifiable buffer that represents the given string. -/** - * @returns A const_buffer value equivalent to: - * @code const_buffer( - * data.data(), - * min(data.size() * sizeof(Elem), max_size_in_bytes)); @endcode - * - * @note The buffer is invalidated by any non-const operation called on the - * given string object. - */ -template -inline ASIO_CONST_BUFFER buffer( - const std::basic_string& data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.data(), - data.size() * sizeof(Elem) < max_size_in_bytes - ? data.size() * sizeof(Elem) : max_size_in_bytes -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename std::basic_string::const_iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -#if defined(ASIO_HAS_STRING_VIEW) \ - || defined(GENERATING_DOCUMENTATION) - -/// Create a new modifiable buffer that represents the given string_view. -/** - * @returns mutable_buffer(data.size() ? &data[0] : 0, - * data.size() * sizeof(Elem)). - */ -template -inline ASIO_CONST_BUFFER buffer( - basic_string_view data) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.size() ? &data[0] : 0, - data.size() * sizeof(Elem) -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename basic_string_view::iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -/// Create a new non-modifiable buffer that represents the given string. -/** - * @returns A mutable_buffer value equivalent to: - * @code mutable_buffer( - * data.size() ? &data[0] : 0, - * min(data.size() * sizeof(Elem), max_size_in_bytes)); @endcode - */ -template -inline ASIO_CONST_BUFFER buffer( - basic_string_view data, - std::size_t max_size_in_bytes) ASIO_NOEXCEPT -{ - return ASIO_CONST_BUFFER(data.size() ? &data[0] : 0, - data.size() * sizeof(Elem) < max_size_in_bytes - ? data.size() * sizeof(Elem) : max_size_in_bytes -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - , detail::buffer_debug_check< - typename basic_string_view::iterator - >(data.begin()) -#endif // ASIO_ENABLE_BUFFER_DEBUGGING - ); -} - -#endif // defined(ASIO_HAS_STRING_VIEW) - // || defined(GENERATING_DOCUMENTATION) - -/*@}*/ - -/// Adapt a basic_string to the DynamicBuffer requirements. -/** - * Requires that sizeof(Elem) == 1. - */ -template -class dynamic_string_buffer -{ -public: - /// The type used to represent the input sequence as a list of buffers. - typedef ASIO_CONST_BUFFER const_buffers_type; - - /// The type used to represent the output sequence as a list of buffers. - typedef ASIO_MUTABLE_BUFFER mutable_buffers_type; - - /// Construct a dynamic buffer from a string. - /** - * @param s The string to be used as backing storage for the dynamic buffer. - * Any existing data in the string is treated as the dynamic buffer's input - * sequence. The object stores a reference to the string and the user is - * responsible for ensuring that the string object remains valid until the - * dynamic_string_buffer object is destroyed. - * - * @param maximum_size Specifies a maximum size for the buffer, in bytes. - */ - explicit dynamic_string_buffer(std::basic_string& s, - std::size_t maximum_size = - (std::numeric_limits::max)()) ASIO_NOEXCEPT - : string_(s), - size_(string_.size()), - max_size_(maximum_size) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move construct a dynamic buffer. - dynamic_string_buffer(dynamic_string_buffer&& other) ASIO_NOEXCEPT - : string_(other.string_), - size_(other.size_), - max_size_(other.max_size_) - { - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Get the size of the input sequence. - std::size_t size() const ASIO_NOEXCEPT - { - return size_; - } - - /// Get the maximum size of the dynamic buffer. - /** - * @returns The allowed maximum of the sum of the sizes of the input sequence - * and output sequence. - */ - std::size_t max_size() const ASIO_NOEXCEPT - { - return max_size_; - } - - /// Get the current capacity of the dynamic buffer. - /** - * @returns The current total capacity of the buffer, i.e. for both the input - * sequence and output sequence. - */ - std::size_t capacity() const ASIO_NOEXCEPT - { - return string_.capacity(); - } - - /// Get a list of buffers that represents the input sequence. - /** - * @returns An object of type @c const_buffers_type that satisfies - * ConstBufferSequence requirements, representing the basic_string memory in - * input sequence. - * - * @note The returned object is invalidated by any @c dynamic_string_buffer - * or @c basic_string member function that modifies the input sequence or - * output sequence. - */ - const_buffers_type data() const ASIO_NOEXCEPT - { - return const_buffers_type(asio::buffer(string_, size_)); - } - - /// Get a list of buffers that represents the output sequence, with the given - /// size. - /** - * Ensures that the output sequence can accommodate @c n bytes, resizing the - * basic_string object as necessary. - * - * @returns An object of type @c mutable_buffers_type that satisfies - * MutableBufferSequence requirements, representing basic_string memory - * at the start of the output sequence of size @c n. - * - * @throws std::length_error If size() + n > max_size(). - * - * @note The returned object is invalidated by any @c dynamic_string_buffer - * or @c basic_string member function that modifies the input sequence or - * output sequence. - */ - mutable_buffers_type prepare(std::size_t n) - { - if (size () > max_size() || max_size() - size() < n) - { - std::length_error ex("dynamic_string_buffer too long"); - asio::detail::throw_exception(ex); - } - - string_.resize(size_ + n); - - return asio::buffer(asio::buffer(string_) + size_, n); - } - - /// Move bytes from the output sequence to the input sequence. - /** - * @param n The number of bytes to append from the start of the output - * sequence to the end of the input sequence. The remainder of the output - * sequence is discarded. - * - * Requires a preceding call prepare(x) where x >= n, and - * no intervening operations that modify the input or output sequence. - * - * @note If @c n is greater than the size of the output sequence, the entire - * output sequence is moved to the input sequence and no error is issued. - */ - void commit(std::size_t n) - { - size_ += (std::min)(n, string_.size() - size_); - string_.resize(size_); - } - - /// Remove characters from the input sequence. - /** - * Removes @c n characters from the beginning of the input sequence. - * - * @note If @c n is greater than the size of the input sequence, the entire - * input sequence is consumed and no error is issued. - */ - void consume(std::size_t n) - { - std::size_t consume_length = (std::min)(n, size_); - string_.erase(0, consume_length); - size_ -= consume_length; - } - -private: - std::basic_string& string_; - std::size_t size_; - const std::size_t max_size_; -}; - -/// Adapt a vector to the DynamicBuffer requirements. -/** - * Requires that sizeof(Elem) == 1. - */ -template -class dynamic_vector_buffer -{ -public: - /// The type used to represent the input sequence as a list of buffers. - typedef ASIO_CONST_BUFFER const_buffers_type; - - /// The type used to represent the output sequence as a list of buffers. - typedef ASIO_MUTABLE_BUFFER mutable_buffers_type; - - /// Construct a dynamic buffer from a string. - /** - * @param v The vector to be used as backing storage for the dynamic buffer. - * Any existing data in the vector is treated as the dynamic buffer's input - * sequence. The object stores a reference to the vector and the user is - * responsible for ensuring that the vector object remains valid until the - * dynamic_vector_buffer object is destroyed. - * - * @param maximum_size Specifies a maximum size for the buffer, in bytes. - */ - explicit dynamic_vector_buffer(std::vector& v, - std::size_t maximum_size = - (std::numeric_limits::max)()) ASIO_NOEXCEPT - : vector_(v), - size_(vector_.size()), - max_size_(maximum_size) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move construct a dynamic buffer. - dynamic_vector_buffer(dynamic_vector_buffer&& other) ASIO_NOEXCEPT - : vector_(other.vector_), - size_(other.size_), - max_size_(other.max_size_) - { - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Get the size of the input sequence. - std::size_t size() const ASIO_NOEXCEPT - { - return size_; - } - - /// Get the maximum size of the dynamic buffer. - /** - * @returns The allowed maximum of the sum of the sizes of the input sequence - * and output sequence. - */ - std::size_t max_size() const ASIO_NOEXCEPT - { - return max_size_; - } - - /// Get the current capacity of the dynamic buffer. - /** - * @returns The current total capacity of the buffer, i.e. for both the input - * sequence and output sequence. - */ - std::size_t capacity() const ASIO_NOEXCEPT - { - return vector_.capacity(); - } - - /// Get a list of buffers that represents the input sequence. - /** - * @returns An object of type @c const_buffers_type that satisfies - * ConstBufferSequence requirements, representing the basic_string memory in - * input sequence. - * - * @note The returned object is invalidated by any @c dynamic_vector_buffer - * or @c basic_string member function that modifies the input sequence or - * output sequence. - */ - const_buffers_type data() const ASIO_NOEXCEPT - { - return const_buffers_type(asio::buffer(vector_, size_)); - } - - /// Get a list of buffers that represents the output sequence, with the given - /// size. - /** - * Ensures that the output sequence can accommodate @c n bytes, resizing the - * basic_string object as necessary. - * - * @returns An object of type @c mutable_buffers_type that satisfies - * MutableBufferSequence requirements, representing basic_string memory - * at the start of the output sequence of size @c n. - * - * @throws std::length_error If size() + n > max_size(). - * - * @note The returned object is invalidated by any @c dynamic_vector_buffer - * or @c basic_string member function that modifies the input sequence or - * output sequence. - */ - mutable_buffers_type prepare(std::size_t n) - { - if (size () > max_size() || max_size() - size() < n) - { - std::length_error ex("dynamic_vector_buffer too long"); - asio::detail::throw_exception(ex); - } - - vector_.resize(size_ + n); - - return asio::buffer(asio::buffer(vector_) + size_, n); - } - - /// Move bytes from the output sequence to the input sequence. - /** - * @param n The number of bytes to append from the start of the output - * sequence to the end of the input sequence. The remainder of the output - * sequence is discarded. - * - * Requires a preceding call prepare(x) where x >= n, and - * no intervening operations that modify the input or output sequence. - * - * @note If @c n is greater than the size of the output sequence, the entire - * output sequence is moved to the input sequence and no error is issued. - */ - void commit(std::size_t n) - { - size_ += (std::min)(n, vector_.size() - size_); - vector_.resize(size_); - } - - /// Remove characters from the input sequence. - /** - * Removes @c n characters from the beginning of the input sequence. - * - * @note If @c n is greater than the size of the input sequence, the entire - * input sequence is consumed and no error is issued. - */ - void consume(std::size_t n) - { - std::size_t consume_length = (std::min)(n, size_); - vector_.erase(vector_.begin(), vector_.begin() + consume_length); - size_ -= consume_length; - } - -private: - std::vector& vector_; - std::size_t size_; - const std::size_t max_size_; -}; - -/** @defgroup dynamic_buffer asio::dynamic_buffer - * - * @brief The asio::dynamic_buffer function is used to create a - * dynamically resized buffer from a @c std::basic_string or @c std::vector. - */ -/*@{*/ - -/// Create a new dynamic buffer that represents the given string. -/** - * @returns dynamic_string_buffer(data). - */ -template -inline dynamic_string_buffer dynamic_buffer( - std::basic_string& data) ASIO_NOEXCEPT -{ - return dynamic_string_buffer(data); -} - -/// Create a new dynamic buffer that represents the given string. -/** - * @returns dynamic_string_buffer(data, - * max_size). - */ -template -inline dynamic_string_buffer dynamic_buffer( - std::basic_string& data, - std::size_t max_size) ASIO_NOEXCEPT -{ - return dynamic_string_buffer(data, max_size); -} - -/// Create a new dynamic buffer that represents the given vector. -/** - * @returns dynamic_vector_buffer(data). - */ -template -inline dynamic_vector_buffer dynamic_buffer( - std::vector& data) ASIO_NOEXCEPT -{ - return dynamic_vector_buffer(data); -} - -/// Create a new dynamic buffer that represents the given vector. -/** - * @returns dynamic_vector_buffer(data, max_size). - */ -template -inline dynamic_vector_buffer dynamic_buffer( - std::vector& data, - std::size_t max_size) ASIO_NOEXCEPT -{ - return dynamic_vector_buffer(data, max_size); -} - -/*@}*/ - -/** @defgroup buffer_copy asio::buffer_copy - * - * @brief The asio::buffer_copy function is used to copy bytes from a - * source buffer (or buffer sequence) to a target buffer (or buffer sequence). - * - * The @c buffer_copy function is available in two forms: - * - * @li A 2-argument form: @c buffer_copy(target, source) - * - * @li A 3-argument form: @c buffer_copy(target, source, max_bytes_to_copy) - * - * Both forms return the number of bytes actually copied. The number of bytes - * copied is the lesser of: - * - * @li @c buffer_size(target) - * - * @li @c buffer_size(source) - * - * @li @c If specified, @c max_bytes_to_copy. - * - * This prevents buffer overflow, regardless of the buffer sizes used in the - * copy operation. - * - * Note that @ref buffer_copy is implemented in terms of @c memcpy, and - * consequently it cannot be used to copy between overlapping memory regions. - */ -/*@{*/ - -namespace detail { - -inline std::size_t buffer_copy_1(const mutable_buffer& target, - const const_buffer& source) -{ - using namespace std; // For memcpy. - std::size_t target_size = target.size(); - std::size_t source_size = source.size(); - std::size_t n = target_size < source_size ? target_size : source_size; - if (n > 0) - memcpy(target.data(), source.data(), n); - return n; -} - -template -inline std::size_t buffer_copy(one_buffer, one_buffer, - TargetIterator target_begin, TargetIterator, - SourceIterator source_begin, SourceIterator) ASIO_NOEXCEPT -{ - return (buffer_copy_1)(*target_begin, *source_begin); -} - -template -inline std::size_t buffer_copy(one_buffer, one_buffer, - TargetIterator target_begin, TargetIterator, - SourceIterator source_begin, SourceIterator, - std::size_t max_bytes_to_copy) ASIO_NOEXCEPT -{ - return (buffer_copy_1)(*target_begin, - asio::buffer(*source_begin, max_bytes_to_copy)); -} - -template -std::size_t buffer_copy(one_buffer, multiple_buffers, - TargetIterator target_begin, TargetIterator, - SourceIterator source_begin, SourceIterator source_end, - std::size_t max_bytes_to_copy - = (std::numeric_limits::max)()) ASIO_NOEXCEPT -{ - std::size_t total_bytes_copied = 0; - SourceIterator source_iter = source_begin; - - for (mutable_buffer target_buffer( - asio::buffer(*target_begin, max_bytes_to_copy)); - target_buffer.size() && source_iter != source_end; ++source_iter) - { - const_buffer source_buffer(*source_iter); - std::size_t bytes_copied = (buffer_copy_1)(target_buffer, source_buffer); - total_bytes_copied += bytes_copied; - target_buffer += bytes_copied; - } - - return total_bytes_copied; -} - -template -std::size_t buffer_copy(multiple_buffers, one_buffer, - TargetIterator target_begin, TargetIterator target_end, - SourceIterator source_begin, SourceIterator, - std::size_t max_bytes_to_copy - = (std::numeric_limits::max)()) ASIO_NOEXCEPT -{ - std::size_t total_bytes_copied = 0; - TargetIterator target_iter = target_begin; - - for (const_buffer source_buffer( - asio::buffer(*source_begin, max_bytes_to_copy)); - source_buffer.size() && target_iter != target_end; ++target_iter) - { - mutable_buffer target_buffer(*target_iter); - std::size_t bytes_copied = (buffer_copy_1)(target_buffer, source_buffer); - total_bytes_copied += bytes_copied; - source_buffer += bytes_copied; - } - - return total_bytes_copied; -} - -template -std::size_t buffer_copy(multiple_buffers, multiple_buffers, - TargetIterator target_begin, TargetIterator target_end, - SourceIterator source_begin, SourceIterator source_end) ASIO_NOEXCEPT -{ - std::size_t total_bytes_copied = 0; - - TargetIterator target_iter = target_begin; - std::size_t target_buffer_offset = 0; - - SourceIterator source_iter = source_begin; - std::size_t source_buffer_offset = 0; - - while (target_iter != target_end && source_iter != source_end) - { - mutable_buffer target_buffer = - mutable_buffer(*target_iter) + target_buffer_offset; - - const_buffer source_buffer = - const_buffer(*source_iter) + source_buffer_offset; - - std::size_t bytes_copied = (buffer_copy_1)(target_buffer, source_buffer); - total_bytes_copied += bytes_copied; - - if (bytes_copied == target_buffer.size()) - { - ++target_iter; - target_buffer_offset = 0; - } - else - target_buffer_offset += bytes_copied; - - if (bytes_copied == source_buffer.size()) - { - ++source_iter; - source_buffer_offset = 0; - } - else - source_buffer_offset += bytes_copied; - } - - return total_bytes_copied; -} - -template -std::size_t buffer_copy(multiple_buffers, multiple_buffers, - TargetIterator target_begin, TargetIterator target_end, - SourceIterator source_begin, SourceIterator source_end, - std::size_t max_bytes_to_copy) ASIO_NOEXCEPT -{ - std::size_t total_bytes_copied = 0; - - TargetIterator target_iter = target_begin; - std::size_t target_buffer_offset = 0; - - SourceIterator source_iter = source_begin; - std::size_t source_buffer_offset = 0; - - while (total_bytes_copied != max_bytes_to_copy - && target_iter != target_end && source_iter != source_end) - { - mutable_buffer target_buffer = - mutable_buffer(*target_iter) + target_buffer_offset; - - const_buffer source_buffer = - const_buffer(*source_iter) + source_buffer_offset; - - std::size_t bytes_copied = (buffer_copy_1)( - target_buffer, asio::buffer(source_buffer, - max_bytes_to_copy - total_bytes_copied)); - total_bytes_copied += bytes_copied; - - if (bytes_copied == target_buffer.size()) - { - ++target_iter; - target_buffer_offset = 0; - } - else - target_buffer_offset += bytes_copied; - - if (bytes_copied == source_buffer.size()) - { - ++source_iter; - source_buffer_offset = 0; - } - else - source_buffer_offset += bytes_copied; - } - - return total_bytes_copied; -} - -} // namespace detail - -/// Copies bytes from a source buffer sequence to a target buffer sequence. -/** - * @param target A modifiable buffer sequence representing the memory regions to - * which the bytes will be copied. - * - * @param source A non-modifiable buffer sequence representing the memory - * regions from which the bytes will be copied. - * - * @returns The number of bytes copied. - * - * @note The number of bytes copied is the lesser of: - * - * @li @c buffer_size(target) - * - * @li @c buffer_size(source) - * - * This function is implemented in terms of @c memcpy, and consequently it - * cannot be used to copy between overlapping memory regions. - */ -template -inline std::size_t buffer_copy(const MutableBufferSequence& target, - const ConstBufferSequence& source) ASIO_NOEXCEPT -{ - return detail::buffer_copy( - detail::buffer_sequence_cardinality(), - detail::buffer_sequence_cardinality(), - asio::buffer_sequence_begin(target), - asio::buffer_sequence_end(target), - asio::buffer_sequence_begin(source), - asio::buffer_sequence_end(source)); -} - -/// Copies a limited number of bytes from a source buffer sequence to a target -/// buffer sequence. -/** - * @param target A modifiable buffer sequence representing the memory regions to - * which the bytes will be copied. - * - * @param source A non-modifiable buffer sequence representing the memory - * regions from which the bytes will be copied. - * - * @param max_bytes_to_copy The maximum number of bytes to be copied. - * - * @returns The number of bytes copied. - * - * @note The number of bytes copied is the lesser of: - * - * @li @c buffer_size(target) - * - * @li @c buffer_size(source) - * - * @li @c max_bytes_to_copy - * - * This function is implemented in terms of @c memcpy, and consequently it - * cannot be used to copy between overlapping memory regions. - */ -template -inline std::size_t buffer_copy(const MutableBufferSequence& target, - const ConstBufferSequence& source, - std::size_t max_bytes_to_copy) ASIO_NOEXCEPT -{ - return detail::buffer_copy( - detail::buffer_sequence_cardinality(), - detail::buffer_sequence_cardinality(), - asio::buffer_sequence_begin(target), - asio::buffer_sequence_end(target), - asio::buffer_sequence_begin(source), - asio::buffer_sequence_end(source), max_bytes_to_copy); -} - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BUFFER_HPP diff --git a/scout_sdk/asio/asio/buffered_read_stream.hpp b/scout_sdk/asio/asio/buffered_read_stream.hpp deleted file mode 100644 index c3e7f0b..0000000 --- a/scout_sdk/asio/asio/buffered_read_stream.hpp +++ /dev/null @@ -1,257 +0,0 @@ -// -// buffered_read_stream.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFERED_READ_STREAM_HPP -#define ASIO_BUFFERED_READ_STREAM_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/buffered_read_stream_fwd.hpp" -#include "asio/buffer.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_resize_guard.hpp" -#include "asio/detail/buffered_stream_storage.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Adds buffering to the read-related operations of a stream. -/** - * The buffered_read_stream class template can be used to add buffering to the - * synchronous and asynchronous read operations of a stream. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -template -class buffered_read_stream - : private noncopyable -{ -public: - /// The type of the next layer. - typedef typename remove_reference::type next_layer_type; - - /// The type of the lowest layer. - typedef typename next_layer_type::lowest_layer_type lowest_layer_type; - - /// The type of the executor associated with the object. - typedef typename lowest_layer_type::executor_type executor_type; - -#if defined(GENERATING_DOCUMENTATION) - /// The default buffer size. - static const std::size_t default_buffer_size = implementation_defined; -#else - ASIO_STATIC_CONSTANT(std::size_t, default_buffer_size = 1024); -#endif - - /// Construct, passing the specified argument to initialise the next layer. - template - explicit buffered_read_stream(Arg& a) - : next_layer_(a), - storage_(default_buffer_size) - { - } - - /// Construct, passing the specified argument to initialise the next layer. - template - buffered_read_stream(Arg& a, std::size_t buffer_size) - : next_layer_(a), - storage_(buffer_size) - { - } - - /// Get a reference to the next layer. - next_layer_type& next_layer() - { - return next_layer_; - } - - /// Get a reference to the lowest layer. - lowest_layer_type& lowest_layer() - { - return next_layer_.lowest_layer(); - } - - /// Get a const reference to the lowest layer. - const lowest_layer_type& lowest_layer() const - { - return next_layer_.lowest_layer(); - } - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return next_layer_.lowest_layer().get_executor(); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_context() - { - return next_layer_.get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_service() - { - return next_layer_.get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Close the stream. - void close() - { - next_layer_.close(); - } - - /// Close the stream. - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - next_layer_.close(ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Write the given data to the stream. Returns the number of bytes written. - /// Throws an exception on failure. - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - return next_layer_.write_some(buffers); - } - - /// Write the given data to the stream. Returns the number of bytes written, - /// or 0 if an error occurred. - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return next_layer_.write_some(buffers, ec); - } - - /// Start an asynchronous write. The data being written must be valid for the - /// lifetime of the asynchronous operation. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - return next_layer_.async_write_some(buffers, - ASIO_MOVE_CAST(WriteHandler)(handler)); - } - - /// Fill the buffer with some data. Returns the number of bytes placed in the - /// buffer as a result of the operation. Throws an exception on failure. - std::size_t fill(); - - /// Fill the buffer with some data. Returns the number of bytes placed in the - /// buffer as a result of the operation, or 0 if an error occurred. - std::size_t fill(asio::error_code& ec); - - /// Start an asynchronous fill. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_fill(ASIO_MOVE_ARG(ReadHandler) handler); - - /// Read some data from the stream. Returns the number of bytes read. Throws - /// an exception on failure. - template - std::size_t read_some(const MutableBufferSequence& buffers); - - /// Read some data from the stream. Returns the number of bytes read or 0 if - /// an error occurred. - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec); - - /// Start an asynchronous read. The buffer into which the data will be read - /// must be valid for the lifetime of the asynchronous operation. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler); - - /// Peek at the incoming data on the stream. Returns the number of bytes read. - /// Throws an exception on failure. - template - std::size_t peek(const MutableBufferSequence& buffers); - - /// Peek at the incoming data on the stream. Returns the number of bytes read, - /// or 0 if an error occurred. - template - std::size_t peek(const MutableBufferSequence& buffers, - asio::error_code& ec); - - /// Determine the amount of data that may be read without blocking. - std::size_t in_avail() - { - return storage_.size(); - } - - /// Determine the amount of data that may be read without blocking. - std::size_t in_avail(asio::error_code& ec) - { - ec = asio::error_code(); - return storage_.size(); - } - -private: - /// Copy data out of the internal buffer to the specified target buffer. - /// Returns the number of bytes copied. - template - std::size_t copy(const MutableBufferSequence& buffers) - { - std::size_t bytes_copied = asio::buffer_copy( - buffers, storage_.data(), storage_.size()); - storage_.consume(bytes_copied); - return bytes_copied; - } - - /// Copy data from the internal buffer to the specified target buffer, without - /// removing the data from the internal buffer. Returns the number of bytes - /// copied. - template - std::size_t peek_copy(const MutableBufferSequence& buffers) - { - return asio::buffer_copy(buffers, storage_.data(), storage_.size()); - } - - /// The next layer. - Stream next_layer_; - - // The data in the buffer. - detail::buffered_stream_storage storage_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/buffered_read_stream.hpp" - -#endif // ASIO_BUFFERED_READ_STREAM_HPP diff --git a/scout_sdk/asio/asio/buffered_read_stream_fwd.hpp b/scout_sdk/asio/asio/buffered_read_stream_fwd.hpp deleted file mode 100644 index 334b88a..0000000 --- a/scout_sdk/asio/asio/buffered_read_stream_fwd.hpp +++ /dev/null @@ -1,25 +0,0 @@ -// -// buffered_read_stream_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFERED_READ_STREAM_FWD_HPP -#define ASIO_BUFFERED_READ_STREAM_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -namespace asio { - -template -class buffered_read_stream; - -} // namespace asio - -#endif // ASIO_BUFFERED_READ_STREAM_FWD_HPP diff --git a/scout_sdk/asio/asio/buffered_stream.hpp b/scout_sdk/asio/asio/buffered_stream.hpp deleted file mode 100644 index 8014fa4..0000000 --- a/scout_sdk/asio/asio/buffered_stream.hpp +++ /dev/null @@ -1,278 +0,0 @@ -// -// buffered_stream.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFERED_STREAM_HPP -#define ASIO_BUFFERED_STREAM_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/buffered_read_stream.hpp" -#include "asio/buffered_write_stream.hpp" -#include "asio/buffered_stream_fwd.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Adds buffering to the read- and write-related operations of a stream. -/** - * The buffered_stream class template can be used to add buffering to the - * synchronous and asynchronous read and write operations of a stream. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -template -class buffered_stream - : private noncopyable -{ -public: - /// The type of the next layer. - typedef typename remove_reference::type next_layer_type; - - /// The type of the lowest layer. - typedef typename next_layer_type::lowest_layer_type lowest_layer_type; - - /// The type of the executor associated with the object. - typedef typename lowest_layer_type::executor_type executor_type; - - /// Construct, passing the specified argument to initialise the next layer. - template - explicit buffered_stream(Arg& a) - : inner_stream_impl_(a), - stream_impl_(inner_stream_impl_) - { - } - - /// Construct, passing the specified argument to initialise the next layer. - template - explicit buffered_stream(Arg& a, std::size_t read_buffer_size, - std::size_t write_buffer_size) - : inner_stream_impl_(a, write_buffer_size), - stream_impl_(inner_stream_impl_, read_buffer_size) - { - } - - /// Get a reference to the next layer. - next_layer_type& next_layer() - { - return stream_impl_.next_layer().next_layer(); - } - - /// Get a reference to the lowest layer. - lowest_layer_type& lowest_layer() - { - return stream_impl_.lowest_layer(); - } - - /// Get a const reference to the lowest layer. - const lowest_layer_type& lowest_layer() const - { - return stream_impl_.lowest_layer(); - } - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return stream_impl_.lowest_layer().get_executor(); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_context() - { - return stream_impl_.get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_service() - { - return stream_impl_.get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Close the stream. - void close() - { - stream_impl_.close(); - } - - /// Close the stream. - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - stream_impl_.close(ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Flush all data from the buffer to the next layer. Returns the number of - /// bytes written to the next layer on the last write operation. Throws an - /// exception on failure. - std::size_t flush() - { - return stream_impl_.next_layer().flush(); - } - - /// Flush all data from the buffer to the next layer. Returns the number of - /// bytes written to the next layer on the last write operation, or 0 if an - /// error occurred. - std::size_t flush(asio::error_code& ec) - { - return stream_impl_.next_layer().flush(ec); - } - - /// Start an asynchronous flush. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_flush(ASIO_MOVE_ARG(WriteHandler) handler) - { - return stream_impl_.next_layer().async_flush( - ASIO_MOVE_CAST(WriteHandler)(handler)); - } - - /// Write the given data to the stream. Returns the number of bytes written. - /// Throws an exception on failure. - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - return stream_impl_.write_some(buffers); - } - - /// Write the given data to the stream. Returns the number of bytes written, - /// or 0 if an error occurred. - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return stream_impl_.write_some(buffers, ec); - } - - /// Start an asynchronous write. The data being written must be valid for the - /// lifetime of the asynchronous operation. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - return stream_impl_.async_write_some(buffers, - ASIO_MOVE_CAST(WriteHandler)(handler)); - } - - /// Fill the buffer with some data. Returns the number of bytes placed in the - /// buffer as a result of the operation. Throws an exception on failure. - std::size_t fill() - { - return stream_impl_.fill(); - } - - /// Fill the buffer with some data. Returns the number of bytes placed in the - /// buffer as a result of the operation, or 0 if an error occurred. - std::size_t fill(asio::error_code& ec) - { - return stream_impl_.fill(ec); - } - - /// Start an asynchronous fill. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_fill(ASIO_MOVE_ARG(ReadHandler) handler) - { - return stream_impl_.async_fill(ASIO_MOVE_CAST(ReadHandler)(handler)); - } - - /// Read some data from the stream. Returns the number of bytes read. Throws - /// an exception on failure. - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - return stream_impl_.read_some(buffers); - } - - /// Read some data from the stream. Returns the number of bytes read or 0 if - /// an error occurred. - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return stream_impl_.read_some(buffers, ec); - } - - /// Start an asynchronous read. The buffer into which the data will be read - /// must be valid for the lifetime of the asynchronous operation. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - return stream_impl_.async_read_some(buffers, - ASIO_MOVE_CAST(ReadHandler)(handler)); - } - - /// Peek at the incoming data on the stream. Returns the number of bytes read. - /// Throws an exception on failure. - template - std::size_t peek(const MutableBufferSequence& buffers) - { - return stream_impl_.peek(buffers); - } - - /// Peek at the incoming data on the stream. Returns the number of bytes read, - /// or 0 if an error occurred. - template - std::size_t peek(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return stream_impl_.peek(buffers, ec); - } - - /// Determine the amount of data that may be read without blocking. - std::size_t in_avail() - { - return stream_impl_.in_avail(); - } - - /// Determine the amount of data that may be read without blocking. - std::size_t in_avail(asio::error_code& ec) - { - return stream_impl_.in_avail(ec); - } - -private: - // The buffered write stream. - typedef buffered_write_stream write_stream_type; - write_stream_type inner_stream_impl_; - - // The buffered read stream. - typedef buffered_read_stream read_stream_type; - read_stream_type stream_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BUFFERED_STREAM_HPP diff --git a/scout_sdk/asio/asio/buffered_stream_fwd.hpp b/scout_sdk/asio/asio/buffered_stream_fwd.hpp deleted file mode 100644 index 3492979..0000000 --- a/scout_sdk/asio/asio/buffered_stream_fwd.hpp +++ /dev/null @@ -1,25 +0,0 @@ -// -// buffered_stream_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFERED_STREAM_FWD_HPP -#define ASIO_BUFFERED_STREAM_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -namespace asio { - -template -class buffered_stream; - -} // namespace asio - -#endif // ASIO_BUFFERED_STREAM_FWD_HPP diff --git a/scout_sdk/asio/asio/buffered_write_stream.hpp b/scout_sdk/asio/asio/buffered_write_stream.hpp deleted file mode 100644 index aac33d3..0000000 --- a/scout_sdk/asio/asio/buffered_write_stream.hpp +++ /dev/null @@ -1,249 +0,0 @@ -// -// buffered_write_stream.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFERED_WRITE_STREAM_HPP -#define ASIO_BUFFERED_WRITE_STREAM_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/buffered_write_stream_fwd.hpp" -#include "asio/buffer.hpp" -#include "asio/completion_condition.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffered_stream_storage.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/write.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Adds buffering to the write-related operations of a stream. -/** - * The buffered_write_stream class template can be used to add buffering to the - * synchronous and asynchronous write operations of a stream. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -template -class buffered_write_stream - : private noncopyable -{ -public: - /// The type of the next layer. - typedef typename remove_reference::type next_layer_type; - - /// The type of the lowest layer. - typedef typename next_layer_type::lowest_layer_type lowest_layer_type; - - /// The type of the executor associated with the object. - typedef typename lowest_layer_type::executor_type executor_type; - -#if defined(GENERATING_DOCUMENTATION) - /// The default buffer size. - static const std::size_t default_buffer_size = implementation_defined; -#else - ASIO_STATIC_CONSTANT(std::size_t, default_buffer_size = 1024); -#endif - - /// Construct, passing the specified argument to initialise the next layer. - template - explicit buffered_write_stream(Arg& a) - : next_layer_(a), - storage_(default_buffer_size) - { - } - - /// Construct, passing the specified argument to initialise the next layer. - template - buffered_write_stream(Arg& a, std::size_t buffer_size) - : next_layer_(a), - storage_(buffer_size) - { - } - - /// Get a reference to the next layer. - next_layer_type& next_layer() - { - return next_layer_; - } - - /// Get a reference to the lowest layer. - lowest_layer_type& lowest_layer() - { - return next_layer_.lowest_layer(); - } - - /// Get a const reference to the lowest layer. - const lowest_layer_type& lowest_layer() const - { - return next_layer_.lowest_layer(); - } - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return next_layer_.lowest_layer().get_executor(); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_context() - { - return next_layer_.get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_service() - { - return next_layer_.get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Close the stream. - void close() - { - next_layer_.close(); - } - - /// Close the stream. - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - next_layer_.close(ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Flush all data from the buffer to the next layer. Returns the number of - /// bytes written to the next layer on the last write operation. Throws an - /// exception on failure. - std::size_t flush(); - - /// Flush all data from the buffer to the next layer. Returns the number of - /// bytes written to the next layer on the last write operation, or 0 if an - /// error occurred. - std::size_t flush(asio::error_code& ec); - - /// Start an asynchronous flush. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_flush(ASIO_MOVE_ARG(WriteHandler) handler); - - /// Write the given data to the stream. Returns the number of bytes written. - /// Throws an exception on failure. - template - std::size_t write_some(const ConstBufferSequence& buffers); - - /// Write the given data to the stream. Returns the number of bytes written, - /// or 0 if an error occurred and the error handler did not throw. - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec); - - /// Start an asynchronous write. The data being written must be valid for the - /// lifetime of the asynchronous operation. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler); - - /// Read some data from the stream. Returns the number of bytes read. Throws - /// an exception on failure. - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - return next_layer_.read_some(buffers); - } - - /// Read some data from the stream. Returns the number of bytes read or 0 if - /// an error occurred. - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return next_layer_.read_some(buffers, ec); - } - - /// Start an asynchronous read. The buffer into which the data will be read - /// must be valid for the lifetime of the asynchronous operation. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - return next_layer_.async_read_some(buffers, - ASIO_MOVE_CAST(ReadHandler)(handler)); - } - - /// Peek at the incoming data on the stream. Returns the number of bytes read. - /// Throws an exception on failure. - template - std::size_t peek(const MutableBufferSequence& buffers) - { - return next_layer_.peek(buffers); - } - - /// Peek at the incoming data on the stream. Returns the number of bytes read, - /// or 0 if an error occurred. - template - std::size_t peek(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return next_layer_.peek(buffers, ec); - } - - /// Determine the amount of data that may be read without blocking. - std::size_t in_avail() - { - return next_layer_.in_avail(); - } - - /// Determine the amount of data that may be read without blocking. - std::size_t in_avail(asio::error_code& ec) - { - return next_layer_.in_avail(ec); - } - -private: - /// Copy data into the internal buffer from the specified source buffer. - /// Returns the number of bytes copied. - template - std::size_t copy(const ConstBufferSequence& buffers); - - /// The next layer. - Stream next_layer_; - - // The data in the buffer. - detail::buffered_stream_storage storage_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/buffered_write_stream.hpp" - -#endif // ASIO_BUFFERED_WRITE_STREAM_HPP diff --git a/scout_sdk/asio/asio/buffered_write_stream_fwd.hpp b/scout_sdk/asio/asio/buffered_write_stream_fwd.hpp deleted file mode 100644 index 6ef54ba..0000000 --- a/scout_sdk/asio/asio/buffered_write_stream_fwd.hpp +++ /dev/null @@ -1,25 +0,0 @@ -// -// buffered_write_stream_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFERED_WRITE_STREAM_FWD_HPP -#define ASIO_BUFFERED_WRITE_STREAM_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -namespace asio { - -template -class buffered_write_stream; - -} // namespace asio - -#endif // ASIO_BUFFERED_WRITE_STREAM_FWD_HPP diff --git a/scout_sdk/asio/asio/buffers_iterator.hpp b/scout_sdk/asio/asio/buffers_iterator.hpp deleted file mode 100644 index f5c9d4c..0000000 --- a/scout_sdk/asio/asio/buffers_iterator.hpp +++ /dev/null @@ -1,521 +0,0 @@ -// -// buffers_iterator.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_BUFFERS_ITERATOR_HPP -#define ASIO_BUFFERS_ITERATOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include "asio/buffer.hpp" -#include "asio/detail/assert.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - template - struct buffers_iterator_types_helper; - - template <> - struct buffers_iterator_types_helper - { - typedef const_buffer buffer_type; - template - struct byte_type - { - typedef typename add_const::type type; - }; - }; - - template <> - struct buffers_iterator_types_helper - { - typedef mutable_buffer buffer_type; - template - struct byte_type - { - typedef ByteType type; - }; - }; - - template - struct buffers_iterator_types - { - enum - { - is_mutable = is_convertible< - typename BufferSequence::value_type, - mutable_buffer>::value - }; - typedef buffers_iterator_types_helper helper; - typedef typename helper::buffer_type buffer_type; - typedef typename helper::template byte_type::type byte_type; - typedef typename BufferSequence::const_iterator const_iterator; - }; - - template - struct buffers_iterator_types - { - typedef mutable_buffer buffer_type; - typedef ByteType byte_type; - typedef const mutable_buffer* const_iterator; - }; - - template - struct buffers_iterator_types - { - typedef const_buffer buffer_type; - typedef typename add_const::type byte_type; - typedef const const_buffer* const_iterator; - }; - -#if !defined(ASIO_NO_DEPRECATED) - - template - struct buffers_iterator_types - { - typedef mutable_buffer buffer_type; - typedef ByteType byte_type; - typedef const mutable_buffer* const_iterator; - }; - - template - struct buffers_iterator_types - { - typedef const_buffer buffer_type; - typedef typename add_const::type byte_type; - typedef const const_buffer* const_iterator; - }; - -#endif // !defined(ASIO_NO_DEPRECATED) -} - -/// A random access iterator over the bytes in a buffer sequence. -template -class buffers_iterator -{ -private: - typedef typename detail::buffers_iterator_types< - BufferSequence, ByteType>::buffer_type buffer_type; - - typedef typename detail::buffers_iterator_types::const_iterator buffer_sequence_iterator_type; - -public: - /// The type used for the distance between two iterators. - typedef std::ptrdiff_t difference_type; - - /// The type of the value pointed to by the iterator. - typedef ByteType value_type; - -#if defined(GENERATING_DOCUMENTATION) - /// The type of the result of applying operator->() to the iterator. - /** - * If the buffer sequence stores buffer objects that are convertible to - * mutable_buffer, this is a pointer to a non-const ByteType. Otherwise, a - * pointer to a const ByteType. - */ - typedef const_or_non_const_ByteType* pointer; -#else // defined(GENERATING_DOCUMENTATION) - typedef typename detail::buffers_iterator_types< - BufferSequence, ByteType>::byte_type* pointer; -#endif // defined(GENERATING_DOCUMENTATION) - -#if defined(GENERATING_DOCUMENTATION) - /// The type of the result of applying operator*() to the iterator. - /** - * If the buffer sequence stores buffer objects that are convertible to - * mutable_buffer, this is a reference to a non-const ByteType. Otherwise, a - * reference to a const ByteType. - */ - typedef const_or_non_const_ByteType& reference; -#else // defined(GENERATING_DOCUMENTATION) - typedef typename detail::buffers_iterator_types< - BufferSequence, ByteType>::byte_type& reference; -#endif // defined(GENERATING_DOCUMENTATION) - - /// The iterator category. - typedef std::random_access_iterator_tag iterator_category; - - /// Default constructor. Creates an iterator in an undefined state. - buffers_iterator() - : current_buffer_(), - current_buffer_position_(0), - begin_(), - current_(), - end_(), - position_(0) - { - } - - /// Construct an iterator representing the beginning of the buffers' data. - static buffers_iterator begin(const BufferSequence& buffers) -#if defined(__GNUC__) && (__GNUC__ == 4) && (__GNUC_MINOR__ == 3) - __attribute__ ((__noinline__)) -#endif // defined(__GNUC__) && (__GNUC__ == 4) && (__GNUC_MINOR__ == 3) - { - buffers_iterator new_iter; - new_iter.begin_ = asio::buffer_sequence_begin(buffers); - new_iter.current_ = asio::buffer_sequence_begin(buffers); - new_iter.end_ = asio::buffer_sequence_end(buffers); - while (new_iter.current_ != new_iter.end_) - { - new_iter.current_buffer_ = *new_iter.current_; - if (new_iter.current_buffer_.size() > 0) - break; - ++new_iter.current_; - } - return new_iter; - } - - /// Construct an iterator representing the end of the buffers' data. - static buffers_iterator end(const BufferSequence& buffers) -#if defined(__GNUC__) && (__GNUC__ == 4) && (__GNUC_MINOR__ == 3) - __attribute__ ((__noinline__)) -#endif // defined(__GNUC__) && (__GNUC__ == 4) && (__GNUC_MINOR__ == 3) - { - buffers_iterator new_iter; - new_iter.begin_ = asio::buffer_sequence_begin(buffers); - new_iter.current_ = asio::buffer_sequence_begin(buffers); - new_iter.end_ = asio::buffer_sequence_end(buffers); - while (new_iter.current_ != new_iter.end_) - { - buffer_type buffer = *new_iter.current_; - new_iter.position_ += buffer.size(); - ++new_iter.current_; - } - return new_iter; - } - - /// Dereference an iterator. - reference operator*() const - { - return dereference(); - } - - /// Dereference an iterator. - pointer operator->() const - { - return &dereference(); - } - - /// Access an individual element. - reference operator[](std::ptrdiff_t difference) const - { - buffers_iterator tmp(*this); - tmp.advance(difference); - return *tmp; - } - - /// Increment operator (prefix). - buffers_iterator& operator++() - { - increment(); - return *this; - } - - /// Increment operator (postfix). - buffers_iterator operator++(int) - { - buffers_iterator tmp(*this); - ++*this; - return tmp; - } - - /// Decrement operator (prefix). - buffers_iterator& operator--() - { - decrement(); - return *this; - } - - /// Decrement operator (postfix). - buffers_iterator operator--(int) - { - buffers_iterator tmp(*this); - --*this; - return tmp; - } - - /// Addition operator. - buffers_iterator& operator+=(std::ptrdiff_t difference) - { - advance(difference); - return *this; - } - - /// Subtraction operator. - buffers_iterator& operator-=(std::ptrdiff_t difference) - { - advance(-difference); - return *this; - } - - /// Addition operator. - friend buffers_iterator operator+(const buffers_iterator& iter, - std::ptrdiff_t difference) - { - buffers_iterator tmp(iter); - tmp.advance(difference); - return tmp; - } - - /// Addition operator. - friend buffers_iterator operator+(std::ptrdiff_t difference, - const buffers_iterator& iter) - { - buffers_iterator tmp(iter); - tmp.advance(difference); - return tmp; - } - - /// Subtraction operator. - friend buffers_iterator operator-(const buffers_iterator& iter, - std::ptrdiff_t difference) - { - buffers_iterator tmp(iter); - tmp.advance(-difference); - return tmp; - } - - /// Subtraction operator. - friend std::ptrdiff_t operator-(const buffers_iterator& a, - const buffers_iterator& b) - { - return b.distance_to(a); - } - - /// Test two iterators for equality. - friend bool operator==(const buffers_iterator& a, const buffers_iterator& b) - { - return a.equal(b); - } - - /// Test two iterators for inequality. - friend bool operator!=(const buffers_iterator& a, const buffers_iterator& b) - { - return !a.equal(b); - } - - /// Compare two iterators. - friend bool operator<(const buffers_iterator& a, const buffers_iterator& b) - { - return a.distance_to(b) > 0; - } - - /// Compare two iterators. - friend bool operator<=(const buffers_iterator& a, const buffers_iterator& b) - { - return !(b < a); - } - - /// Compare two iterators. - friend bool operator>(const buffers_iterator& a, const buffers_iterator& b) - { - return b < a; - } - - /// Compare two iterators. - friend bool operator>=(const buffers_iterator& a, const buffers_iterator& b) - { - return !(a < b); - } - -private: - // Dereference the iterator. - reference dereference() const - { - return static_cast( - current_buffer_.data())[current_buffer_position_]; - } - - // Compare two iterators for equality. - bool equal(const buffers_iterator& other) const - { - return position_ == other.position_; - } - - // Increment the iterator. - void increment() - { - ASIO_ASSERT(current_ != end_ && "iterator out of bounds"); - ++position_; - - // Check if the increment can be satisfied by the current buffer. - ++current_buffer_position_; - if (current_buffer_position_ != current_buffer_.size()) - return; - - // Find the next non-empty buffer. - ++current_; - current_buffer_position_ = 0; - while (current_ != end_) - { - current_buffer_ = *current_; - if (current_buffer_.size() > 0) - return; - ++current_; - } - } - - // Decrement the iterator. - void decrement() - { - ASIO_ASSERT(position_ > 0 && "iterator out of bounds"); - --position_; - - // Check if the decrement can be satisfied by the current buffer. - if (current_buffer_position_ != 0) - { - --current_buffer_position_; - return; - } - - // Find the previous non-empty buffer. - buffer_sequence_iterator_type iter = current_; - while (iter != begin_) - { - --iter; - buffer_type buffer = *iter; - std::size_t buffer_size = buffer.size(); - if (buffer_size > 0) - { - current_ = iter; - current_buffer_ = buffer; - current_buffer_position_ = buffer_size - 1; - return; - } - } - } - - // Advance the iterator by the specified distance. - void advance(std::ptrdiff_t n) - { - if (n > 0) - { - ASIO_ASSERT(current_ != end_ && "iterator out of bounds"); - for (;;) - { - std::ptrdiff_t current_buffer_balance - = current_buffer_.size() - current_buffer_position_; - - // Check if the advance can be satisfied by the current buffer. - if (current_buffer_balance > n) - { - position_ += n; - current_buffer_position_ += n; - return; - } - - // Update position. - n -= current_buffer_balance; - position_ += current_buffer_balance; - - // Move to next buffer. If it is empty then it will be skipped on the - // next iteration of this loop. - if (++current_ == end_) - { - ASIO_ASSERT(n == 0 && "iterator out of bounds"); - current_buffer_ = buffer_type(); - current_buffer_position_ = 0; - return; - } - current_buffer_ = *current_; - current_buffer_position_ = 0; - } - } - else if (n < 0) - { - std::size_t abs_n = -n; - ASIO_ASSERT(position_ >= abs_n && "iterator out of bounds"); - for (;;) - { - // Check if the advance can be satisfied by the current buffer. - if (current_buffer_position_ >= abs_n) - { - position_ -= abs_n; - current_buffer_position_ -= abs_n; - return; - } - - // Update position. - abs_n -= current_buffer_position_; - position_ -= current_buffer_position_; - - // Check if we've reached the beginning of the buffers. - if (current_ == begin_) - { - ASIO_ASSERT(abs_n == 0 && "iterator out of bounds"); - current_buffer_position_ = 0; - return; - } - - // Find the previous non-empty buffer. - buffer_sequence_iterator_type iter = current_; - while (iter != begin_) - { - --iter; - buffer_type buffer = *iter; - std::size_t buffer_size = buffer.size(); - if (buffer_size > 0) - { - current_ = iter; - current_buffer_ = buffer; - current_buffer_position_ = buffer_size; - break; - } - } - } - } - } - - // Determine the distance between two iterators. - std::ptrdiff_t distance_to(const buffers_iterator& other) const - { - return other.position_ - position_; - } - - buffer_type current_buffer_; - std::size_t current_buffer_position_; - buffer_sequence_iterator_type begin_; - buffer_sequence_iterator_type current_; - buffer_sequence_iterator_type end_; - std::size_t position_; -}; - -/// Construct an iterator representing the beginning of the buffers' data. -template -inline buffers_iterator buffers_begin( - const BufferSequence& buffers) -{ - return buffers_iterator::begin(buffers); -} - -/// Construct an iterator representing the end of the buffers' data. -template -inline buffers_iterator buffers_end( - const BufferSequence& buffers) -{ - return buffers_iterator::end(buffers); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_BUFFERS_ITERATOR_HPP diff --git a/scout_sdk/asio/asio/completion_condition.hpp b/scout_sdk/asio/asio/completion_condition.hpp deleted file mode 100644 index 563f417..0000000 --- a/scout_sdk/asio/asio/completion_condition.hpp +++ /dev/null @@ -1,218 +0,0 @@ -// -// completion_condition.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_COMPLETION_CONDITION_HPP -#define ASIO_COMPLETION_CONDITION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail { - -// The default maximum number of bytes to transfer in a single operation. -enum default_max_transfer_size_t { default_max_transfer_size = 65536 }; - -// Adapt result of old-style completion conditions (which had a bool result -// where true indicated that the operation was complete). -inline std::size_t adapt_completion_condition_result(bool result) -{ - return result ? 0 : default_max_transfer_size; -} - -// Adapt result of current completion conditions (which have a size_t result -// where 0 means the operation is complete, and otherwise the result is the -// maximum number of bytes to transfer on the next underlying operation). -inline std::size_t adapt_completion_condition_result(std::size_t result) -{ - return result; -} - -class transfer_all_t -{ -public: - typedef std::size_t result_type; - - template - std::size_t operator()(const Error& err, std::size_t) - { - return !!err ? 0 : default_max_transfer_size; - } -}; - -class transfer_at_least_t -{ -public: - typedef std::size_t result_type; - - explicit transfer_at_least_t(std::size_t minimum) - : minimum_(minimum) - { - } - - template - std::size_t operator()(const Error& err, std::size_t bytes_transferred) - { - return (!!err || bytes_transferred >= minimum_) - ? 0 : default_max_transfer_size; - } - -private: - std::size_t minimum_; -}; - -class transfer_exactly_t -{ -public: - typedef std::size_t result_type; - - explicit transfer_exactly_t(std::size_t size) - : size_(size) - { - } - - template - std::size_t operator()(const Error& err, std::size_t bytes_transferred) - { - return (!!err || bytes_transferred >= size_) ? 0 : - (size_ - bytes_transferred < default_max_transfer_size - ? size_ - bytes_transferred : std::size_t(default_max_transfer_size)); - } - -private: - std::size_t size_; -}; - -} // namespace detail - -/** - * @defgroup completion_condition Completion Condition Function Objects - * - * Function objects used for determining when a read or write operation should - * complete. - */ -/*@{*/ - -/// Return a completion condition function object that indicates that a read or -/// write operation should continue until all of the data has been transferred, -/// or until an error occurs. -/** - * This function is used to create an object, of unspecified type, that meets - * CompletionCondition requirements. - * - * @par Example - * Reading until a buffer is full: - * @code - * boost::array buf; - * asio::error_code ec; - * std::size_t n = asio::read( - * sock, asio::buffer(buf), - * asio::transfer_all(), ec); - * if (ec) - * { - * // An error occurred. - * } - * else - * { - * // n == 128 - * } - * @endcode - */ -#if defined(GENERATING_DOCUMENTATION) -unspecified transfer_all(); -#else -inline detail::transfer_all_t transfer_all() -{ - return detail::transfer_all_t(); -} -#endif - -/// Return a completion condition function object that indicates that a read or -/// write operation should continue until a minimum number of bytes has been -/// transferred, or until an error occurs. -/** - * This function is used to create an object, of unspecified type, that meets - * CompletionCondition requirements. - * - * @par Example - * Reading until a buffer is full or contains at least 64 bytes: - * @code - * boost::array buf; - * asio::error_code ec; - * std::size_t n = asio::read( - * sock, asio::buffer(buf), - * asio::transfer_at_least(64), ec); - * if (ec) - * { - * // An error occurred. - * } - * else - * { - * // n >= 64 && n <= 128 - * } - * @endcode - */ -#if defined(GENERATING_DOCUMENTATION) -unspecified transfer_at_least(std::size_t minimum); -#else -inline detail::transfer_at_least_t transfer_at_least(std::size_t minimum) -{ - return detail::transfer_at_least_t(minimum); -} -#endif - -/// Return a completion condition function object that indicates that a read or -/// write operation should continue until an exact number of bytes has been -/// transferred, or until an error occurs. -/** - * This function is used to create an object, of unspecified type, that meets - * CompletionCondition requirements. - * - * @par Example - * Reading until a buffer is full or contains exactly 64 bytes: - * @code - * boost::array buf; - * asio::error_code ec; - * std::size_t n = asio::read( - * sock, asio::buffer(buf), - * asio::transfer_exactly(64), ec); - * if (ec) - * { - * // An error occurred. - * } - * else - * { - * // n == 64 - * } - * @endcode - */ -#if defined(GENERATING_DOCUMENTATION) -unspecified transfer_exactly(std::size_t size); -#else -inline detail::transfer_exactly_t transfer_exactly(std::size_t size) -{ - return detail::transfer_exactly_t(size); -} -#endif - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_COMPLETION_CONDITION_HPP diff --git a/scout_sdk/asio/asio/connect.hpp b/scout_sdk/asio/asio/connect.hpp deleted file mode 100644 index 487ce3e..0000000 --- a/scout_sdk/asio/asio/connect.hpp +++ /dev/null @@ -1,1059 +0,0 @@ -// -// connect.hpp -// ~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_CONNECT_HPP -#define ASIO_CONNECT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/async_result.hpp" -#include "asio/basic_socket.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - char (&has_iterator_helper(...))[2]; - - template - char has_iterator_helper(T*, typename T::iterator* = 0); - - template - struct has_iterator_typedef - { - enum { value = (sizeof((has_iterator_helper)((T*)(0))) == 1) }; - }; -} // namespace detail - -/// Type trait used to determine whether a type is an endpoint sequence that can -/// be used with with @c connect and @c async_connect. -template -struct is_endpoint_sequence -{ -#if defined(GENERATING_DOCUMENTATION) - /// The value member is true if the type may be used as an endpoint sequence. - static const bool value; -#else - enum - { - value = detail::has_iterator_typedef::value - }; -#endif -}; - -/** - * @defgroup connect asio::connect - * - * @brief Establishes a socket connection by trying each endpoint in a sequence. - */ -/*@{*/ - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param endpoints A sequence of endpoints. - * - * @returns The successfully connected endpoint. - * - * @throws asio::system_error Thrown on failure. If the sequence is - * empty, the associated @c error_code is asio::error::not_found. - * Otherwise, contains the error from the last connection attempt. - * - * @par Example - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::socket s(io_context); - * asio::connect(s, r.resolve(q)); @endcode - */ -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, - typename enable_if::value>::type* = 0); - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param endpoints A sequence of endpoints. - * - * @param ec Set to indicate what error occurred, if any. If the sequence is - * empty, set to asio::error::not_found. Otherwise, contains the error - * from the last connection attempt. - * - * @returns On success, the successfully connected endpoint. Otherwise, a - * default-constructed endpoint. - * - * @par Example - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::socket s(io_context); - * asio::error_code ec; - * asio::connect(s, r.resolve(q), ec); - * if (ec) - * { - * // An error occurred. - * } @endcode - */ -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, asio::error_code& ec, - typename enable_if::value>::type* = 0); - -#if !defined(ASIO_NO_DEPRECATED) -/// (Deprecated.) Establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @returns On success, an iterator denoting the successfully connected - * endpoint. Otherwise, the end iterator. - * - * @throws asio::system_error Thrown on failure. If the sequence is - * empty, the associated @c error_code is asio::error::not_found. - * Otherwise, contains the error from the last connection attempt. - * - * @note This overload assumes that a default constructed object of type @c - * Iterator represents the end of the sequence. This is a valid assumption for - * iterator types such as @c asio::ip::tcp::resolver::iterator. - */ -template -Iterator connect(basic_socket& s, Iterator begin, - typename enable_if::value>::type* = 0); - -/// (Deprecated.) Establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param ec Set to indicate what error occurred, if any. If the sequence is - * empty, set to asio::error::not_found. Otherwise, contains the error - * from the last connection attempt. - * - * @returns On success, an iterator denoting the successfully connected - * endpoint. Otherwise, the end iterator. - * - * @note This overload assumes that a default constructed object of type @c - * Iterator represents the end of the sequence. This is a valid assumption for - * iterator types such as @c asio::ip::tcp::resolver::iterator. - */ -template -Iterator connect(basic_socket& s, - Iterator begin, asio::error_code& ec, - typename enable_if::value>::type* = 0); -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param end An iterator pointing to the end of a sequence of endpoints. - * - * @returns An iterator denoting the successfully connected endpoint. - * - * @throws asio::system_error Thrown on failure. If the sequence is - * empty, the associated @c error_code is asio::error::not_found. - * Otherwise, contains the error from the last connection attempt. - * - * @par Example - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::resolver::results_type e = r.resolve(q); - * tcp::socket s(io_context); - * asio::connect(s, e.begin(), e.end()); @endcode - */ -template -Iterator connect(basic_socket& s, - Iterator begin, Iterator end); - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param end An iterator pointing to the end of a sequence of endpoints. - * - * @param ec Set to indicate what error occurred, if any. If the sequence is - * empty, set to asio::error::not_found. Otherwise, contains the error - * from the last connection attempt. - * - * @returns On success, an iterator denoting the successfully connected - * endpoint. Otherwise, the end iterator. - * - * @par Example - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::resolver::results_type e = r.resolve(q); - * tcp::socket s(io_context); - * asio::error_code ec; - * asio::connect(s, e.begin(), e.end(), ec); - * if (ec) - * { - * // An error occurred. - * } @endcode - */ -template -Iterator connect(basic_socket& s, - Iterator begin, Iterator end, asio::error_code& ec); - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param endpoints A sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @returns The successfully connected endpoint. - * - * @throws asio::system_error Thrown on failure. If the sequence is - * empty, the associated @c error_code is asio::error::not_found. - * Otherwise, contains the error from the last connection attempt. - * - * @par Example - * The following connect condition function object can be used to output - * information about the individual connection attempts: - * @code struct my_connect_condition - * { - * bool operator()( - * const asio::error_code& ec, - * const::tcp::endpoint& next) - * { - * if (ec) std::cout << "Error: " << ec.message() << std::endl; - * std::cout << "Trying: " << next << std::endl; - * return true; - * } - * }; @endcode - * It would be used with the asio::connect function as follows: - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::socket s(io_context); - * tcp::endpoint e = asio::connect(s, - * r.resolve(q), my_connect_condition()); - * std::cout << "Connected to: " << e << std::endl; @endcode - */ -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, ConnectCondition connect_condition, - typename enable_if::value>::type* = 0); - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param endpoints A sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @param ec Set to indicate what error occurred, if any. If the sequence is - * empty, set to asio::error::not_found. Otherwise, contains the error - * from the last connection attempt. - * - * @returns On success, the successfully connected endpoint. Otherwise, a - * default-constructed endpoint. - * - * @par Example - * The following connect condition function object can be used to output - * information about the individual connection attempts: - * @code struct my_connect_condition - * { - * bool operator()( - * const asio::error_code& ec, - * const::tcp::endpoint& next) - * { - * if (ec) std::cout << "Error: " << ec.message() << std::endl; - * std::cout << "Trying: " << next << std::endl; - * return true; - * } - * }; @endcode - * It would be used with the asio::connect function as follows: - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::socket s(io_context); - * asio::error_code ec; - * tcp::endpoint e = asio::connect(s, - * r.resolve(q), my_connect_condition(), ec); - * if (ec) - * { - * // An error occurred. - * } - * else - * { - * std::cout << "Connected to: " << e << std::endl; - * } @endcode - */ -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, ConnectCondition connect_condition, - asio::error_code& ec, - typename enable_if::value>::type* = 0); - -#if !defined(ASIO_NO_DEPRECATED) -/// (Deprecated.) Establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @returns On success, an iterator denoting the successfully connected - * endpoint. Otherwise, the end iterator. - * - * @throws asio::system_error Thrown on failure. If the sequence is - * empty, the associated @c error_code is asio::error::not_found. - * Otherwise, contains the error from the last connection attempt. - * - * @note This overload assumes that a default constructed object of type @c - * Iterator represents the end of the sequence. This is a valid assumption for - * iterator types such as @c asio::ip::tcp::resolver::iterator. - */ -template -Iterator connect(basic_socket& s, - Iterator begin, ConnectCondition connect_condition, - typename enable_if::value>::type* = 0); - -/// (Deprecated.) Establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @param ec Set to indicate what error occurred, if any. If the sequence is - * empty, set to asio::error::not_found. Otherwise, contains the error - * from the last connection attempt. - * - * @returns On success, an iterator denoting the successfully connected - * endpoint. Otherwise, the end iterator. - * - * @note This overload assumes that a default constructed object of type @c - * Iterator represents the end of the sequence. This is a valid assumption for - * iterator types such as @c asio::ip::tcp::resolver::iterator. - */ -template -Iterator connect(basic_socket& s, Iterator begin, - ConnectCondition connect_condition, asio::error_code& ec, - typename enable_if::value>::type* = 0); -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param end An iterator pointing to the end of a sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @returns An iterator denoting the successfully connected endpoint. - * - * @throws asio::system_error Thrown on failure. If the sequence is - * empty, the associated @c error_code is asio::error::not_found. - * Otherwise, contains the error from the last connection attempt. - * - * @par Example - * The following connect condition function object can be used to output - * information about the individual connection attempts: - * @code struct my_connect_condition - * { - * bool operator()( - * const asio::error_code& ec, - * const::tcp::endpoint& next) - * { - * if (ec) std::cout << "Error: " << ec.message() << std::endl; - * std::cout << "Trying: " << next << std::endl; - * return true; - * } - * }; @endcode - * It would be used with the asio::connect function as follows: - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::resolver::results_type e = r.resolve(q); - * tcp::socket s(io_context); - * tcp::resolver::results_type::iterator i = asio::connect( - * s, e.begin(), e.end(), my_connect_condition()); - * std::cout << "Connected to: " << i->endpoint() << std::endl; @endcode - */ -template -Iterator connect(basic_socket& s, Iterator begin, - Iterator end, ConnectCondition connect_condition); - -/// Establishes a socket connection by trying each endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c connect member - * function, once for each endpoint in the sequence, until a connection is - * successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param end An iterator pointing to the end of a sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @param ec Set to indicate what error occurred, if any. If the sequence is - * empty, set to asio::error::not_found. Otherwise, contains the error - * from the last connection attempt. - * - * @returns On success, an iterator denoting the successfully connected - * endpoint. Otherwise, the end iterator. - * - * @par Example - * The following connect condition function object can be used to output - * information about the individual connection attempts: - * @code struct my_connect_condition - * { - * bool operator()( - * const asio::error_code& ec, - * const::tcp::endpoint& next) - * { - * if (ec) std::cout << "Error: " << ec.message() << std::endl; - * std::cout << "Trying: " << next << std::endl; - * return true; - * } - * }; @endcode - * It would be used with the asio::connect function as follows: - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::resolver::results_type e = r.resolve(q); - * tcp::socket s(io_context); - * asio::error_code ec; - * tcp::resolver::results_type::iterator i = asio::connect( - * s, e.begin(), e.end(), my_connect_condition()); - * if (ec) - * { - * // An error occurred. - * } - * else - * { - * std::cout << "Connected to: " << i->endpoint() << std::endl; - * } @endcode - */ -template -Iterator connect(basic_socket& s, - Iterator begin, Iterator end, ConnectCondition connect_condition, - asio::error_code& ec); - -/*@}*/ - -/** - * @defgroup async_connect asio::async_connect - * - * @brief Asynchronously establishes a socket connection by trying each - * endpoint in a sequence. - */ -/*@{*/ - -/// Asynchronously establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c async_connect - * member function, once for each endpoint in the sequence, until a connection - * is successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param endpoints A sequence of endpoints. - * - * @param handler The handler to be called when the connect operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * // Result of operation. if the sequence is empty, set to - * // asio::error::not_found. Otherwise, contains the - * // error from the last connection attempt. - * const asio::error_code& error, - * - * // On success, the successfully connected endpoint. - * // Otherwise, a default-constructed endpoint. - * const typename Protocol::endpoint& endpoint - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::socket s(io_context); - * - * // ... - * - * r.async_resolve(q, resolve_handler); - * - * // ... - * - * void resolve_handler( - * const asio::error_code& ec, - * tcp::resolver::results_type results) - * { - * if (!ec) - * { - * asio::async_connect(s, results, connect_handler); - * } - * } - * - * // ... - * - * void connect_handler( - * const asio::error_code& ec, - * const tcp::endpoint& endpoint) - * { - * // ... - * } @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(RangeConnectHandler, - void (asio::error_code, typename Protocol::endpoint)) -async_connect(basic_socket& s, - const EndpointSequence& endpoints, - ASIO_MOVE_ARG(RangeConnectHandler) handler, - typename enable_if::value>::type* = 0); - -#if !defined(ASIO_NO_DEPRECATED) -/// (Deprecated.) Asynchronously establishes a socket connection by trying each -/// endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c async_connect - * member function, once for each endpoint in the sequence, until a connection - * is successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param handler The handler to be called when the connect operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * // Result of operation. if the sequence is empty, set to - * // asio::error::not_found. Otherwise, contains the - * // error from the last connection attempt. - * const asio::error_code& error, - * - * // On success, an iterator denoting the successfully - * // connected endpoint. Otherwise, the end iterator. - * Iterator iterator - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note This overload assumes that a default constructed object of type @c - * Iterator represents the end of the sequence. This is a valid assumption for - * iterator types such as @c asio::ip::tcp::resolver::iterator. - */ -template -ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, - Iterator begin, ASIO_MOVE_ARG(IteratorConnectHandler) handler, - typename enable_if::value>::type* = 0); -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Asynchronously establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c async_connect - * member function, once for each endpoint in the sequence, until a connection - * is successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param end An iterator pointing to the end of a sequence of endpoints. - * - * @param handler The handler to be called when the connect operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * // Result of operation. if the sequence is empty, set to - * // asio::error::not_found. Otherwise, contains the - * // error from the last connection attempt. - * const asio::error_code& error, - * - * // On success, an iterator denoting the successfully - * // connected endpoint. Otherwise, the end iterator. - * Iterator iterator - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code std::vector endpoints = ...; - * tcp::socket s(io_context); - * asio::async_connect(s, - * endpoints.begin(), endpoints.end(), - * connect_handler); - * - * // ... - * - * void connect_handler( - * const asio::error_code& ec, - * std::vector::iterator i) - * { - * // ... - * } @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, - Iterator begin, Iterator end, - ASIO_MOVE_ARG(IteratorConnectHandler) handler); - -/// Asynchronously establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c async_connect - * member function, once for each endpoint in the sequence, until a connection - * is successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param endpoints A sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @param handler The handler to be called when the connect operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * // Result of operation. if the sequence is empty, set to - * // asio::error::not_found. Otherwise, contains the - * // error from the last connection attempt. - * const asio::error_code& error, - * - * // On success, an iterator denoting the successfully - * // connected endpoint. Otherwise, the end iterator. - * Iterator iterator - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * The following connect condition function object can be used to output - * information about the individual connection attempts: - * @code struct my_connect_condition - * { - * bool operator()( - * const asio::error_code& ec, - * const::tcp::endpoint& next) - * { - * if (ec) std::cout << "Error: " << ec.message() << std::endl; - * std::cout << "Trying: " << next << std::endl; - * return true; - * } - * }; @endcode - * It would be used with the asio::connect function as follows: - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::socket s(io_context); - * - * // ... - * - * r.async_resolve(q, resolve_handler); - * - * // ... - * - * void resolve_handler( - * const asio::error_code& ec, - * tcp::resolver::results_type results) - * { - * if (!ec) - * { - * asio::async_connect(s, results, - * my_connect_condition(), - * connect_handler); - * } - * } - * - * // ... - * - * void connect_handler( - * const asio::error_code& ec, - * const tcp::endpoint& endpoint) - * { - * if (ec) - * { - * // An error occurred. - * } - * else - * { - * std::cout << "Connected to: " << endpoint << std::endl; - * } - * } @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(RangeConnectHandler, - void (asio::error_code, typename Protocol::endpoint)) -async_connect(basic_socket& s, - const EndpointSequence& endpoints, ConnectCondition connect_condition, - ASIO_MOVE_ARG(RangeConnectHandler) handler, - typename enable_if::value>::type* = 0); - -#if !defined(ASIO_NO_DEPRECATED) -/// (Deprecated.) Asynchronously establishes a socket connection by trying each -/// endpoint in a sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c async_connect - * member function, once for each endpoint in the sequence, until a connection - * is successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @param handler The handler to be called when the connect operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * // Result of operation. if the sequence is empty, set to - * // asio::error::not_found. Otherwise, contains the - * // error from the last connection attempt. - * const asio::error_code& error, - * - * // On success, an iterator denoting the successfully - * // connected endpoint. Otherwise, the end iterator. - * Iterator iterator - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note This overload assumes that a default constructed object of type @c - * Iterator represents the end of the sequence. This is a valid assumption for - * iterator types such as @c asio::ip::tcp::resolver::iterator. - */ -template -ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, Iterator begin, - ConnectCondition connect_condition, - ASIO_MOVE_ARG(IteratorConnectHandler) handler, - typename enable_if::value>::type* = 0); -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Asynchronously establishes a socket connection by trying each endpoint in a -/// sequence. -/** - * This function attempts to connect a socket to one of a sequence of - * endpoints. It does this by repeated calls to the socket's @c async_connect - * member function, once for each endpoint in the sequence, until a connection - * is successfully established. - * - * @param s The socket to be connected. If the socket is already open, it will - * be closed. - * - * @param begin An iterator pointing to the start of a sequence of endpoints. - * - * @param end An iterator pointing to the end of a sequence of endpoints. - * - * @param connect_condition A function object that is called prior to each - * connection attempt. The signature of the function object must be: - * @code bool connect_condition( - * const asio::error_code& ec, - * const typename Protocol::endpoint& next); @endcode - * The @c ec parameter contains the result from the most recent connect - * operation. Before the first connection attempt, @c ec is always set to - * indicate success. The @c next parameter is the next endpoint to be tried. - * The function object should return true if the next endpoint should be tried, - * and false if it should be skipped. - * - * @param handler The handler to be called when the connect operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * // Result of operation. if the sequence is empty, set to - * // asio::error::not_found. Otherwise, contains the - * // error from the last connection attempt. - * const asio::error_code& error, - * - * // On success, an iterator denoting the successfully - * // connected endpoint. Otherwise, the end iterator. - * Iterator iterator - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * The following connect condition function object can be used to output - * information about the individual connection attempts: - * @code struct my_connect_condition - * { - * bool operator()( - * const asio::error_code& ec, - * const::tcp::endpoint& next) - * { - * if (ec) std::cout << "Error: " << ec.message() << std::endl; - * std::cout << "Trying: " << next << std::endl; - * return true; - * } - * }; @endcode - * It would be used with the asio::connect function as follows: - * @code tcp::resolver r(io_context); - * tcp::resolver::query q("host", "service"); - * tcp::socket s(io_context); - * - * // ... - * - * r.async_resolve(q, resolve_handler); - * - * // ... - * - * void resolve_handler( - * const asio::error_code& ec, - * tcp::resolver::iterator i) - * { - * if (!ec) - * { - * tcp::resolver::iterator end; - * asio::async_connect(s, i, end, - * my_connect_condition(), - * connect_handler); - * } - * } - * - * // ... - * - * void connect_handler( - * const asio::error_code& ec, - * tcp::resolver::iterator i) - * { - * if (ec) - * { - * // An error occurred. - * } - * else - * { - * std::cout << "Connected to: " << i->endpoint() << std::endl; - * } - * } @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, - Iterator begin, Iterator end, ConnectCondition connect_condition, - ASIO_MOVE_ARG(IteratorConnectHandler) handler); - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/connect.hpp" - -#endif diff --git a/scout_sdk/asio/asio/coroutine.hpp b/scout_sdk/asio/asio/coroutine.hpp deleted file mode 100644 index cd2d99e..0000000 --- a/scout_sdk/asio/asio/coroutine.hpp +++ /dev/null @@ -1,328 +0,0 @@ -// -// coroutine.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_COROUTINE_HPP -#define ASIO_COROUTINE_HPP - -namespace asio { -namespace detail { - -class coroutine_ref; - -} // namespace detail - -/// Provides support for implementing stackless coroutines. -/** - * The @c coroutine class may be used to implement stackless coroutines. The - * class itself is used to store the current state of the coroutine. - * - * Coroutines are copy-constructible and assignable, and the space overhead is - * a single int. They can be used as a base class: - * - * @code class session : coroutine - * { - * ... - * }; @endcode - * - * or as a data member: - * - * @code class session - * { - * ... - * coroutine coro_; - * }; @endcode - * - * or even bound in as a function argument using lambdas or @c bind(). The - * important thing is that as the application maintains a copy of the object - * for as long as the coroutine must be kept alive. - * - * @par Pseudo-keywords - * - * A coroutine is used in conjunction with certain "pseudo-keywords", which - * are implemented as macros. These macros are defined by a header file: - * - * @code #include @endcode - * - * and may conversely be undefined as follows: - * - * @code #include @endcode - * - * reenter - * - * The @c reenter macro is used to define the body of a coroutine. It takes a - * single argument: a pointer or reference to a coroutine object. For example, - * if the base class is a coroutine object you may write: - * - * @code reenter (this) - * { - * ... coroutine body ... - * } @endcode - * - * and if a data member or other variable you can write: - * - * @code reenter (coro_) - * { - * ... coroutine body ... - * } @endcode - * - * When @c reenter is executed at runtime, control jumps to the location of the - * last @c yield or @c fork. - * - * The coroutine body may also be a single statement, such as: - * - * @code reenter (this) for (;;) - * { - * ... - * } @endcode - * - * @b Limitation: The @c reenter macro is implemented using a switch. This - * means that you must take care when using local variables within the - * coroutine body. The local variable is not allowed in a position where - * reentering the coroutine could bypass the variable definition. - * - * yield statement - * - * This form of the @c yield keyword is often used with asynchronous operations: - * - * @code yield socket_->async_read_some(buffer(*buffer_), *this); @endcode - * - * This divides into four logical steps: - * - * @li @c yield saves the current state of the coroutine. - * @li The statement initiates the asynchronous operation. - * @li The resume point is defined immediately following the statement. - * @li Control is transferred to the end of the coroutine body. - * - * When the asynchronous operation completes, the function object is invoked - * and @c reenter causes control to transfer to the resume point. It is - * important to remember to carry the coroutine state forward with the - * asynchronous operation. In the above snippet, the current class is a - * function object object with a coroutine object as base class or data member. - * - * The statement may also be a compound statement, and this permits us to - * define local variables with limited scope: - * - * @code yield - * { - * mutable_buffers_1 b = buffer(*buffer_); - * socket_->async_read_some(b, *this); - * } @endcode - * - * yield return expression ; - * - * This form of @c yield is often used in generators or coroutine-based parsers. - * For example, the function object: - * - * @code struct interleave : coroutine - * { - * istream& is1; - * istream& is2; - * char operator()(char c) - * { - * reenter (this) for (;;) - * { - * yield return is1.get(); - * yield return is2.get(); - * } - * } - * }; @endcode - * - * defines a trivial coroutine that interleaves the characters from two input - * streams. - * - * This type of @c yield divides into three logical steps: - * - * @li @c yield saves the current state of the coroutine. - * @li The resume point is defined immediately following the semicolon. - * @li The value of the expression is returned from the function. - * - * yield ; - * - * This form of @c yield is equivalent to the following steps: - * - * @li @c yield saves the current state of the coroutine. - * @li The resume point is defined immediately following the semicolon. - * @li Control is transferred to the end of the coroutine body. - * - * This form might be applied when coroutines are used for cooperative - * threading and scheduling is explicitly managed. For example: - * - * @code struct task : coroutine - * { - * ... - * void operator()() - * { - * reenter (this) - * { - * while (... not finished ...) - * { - * ... do something ... - * yield; - * ... do some more ... - * yield; - * } - * } - * } - * ... - * }; - * ... - * task t1, t2; - * for (;;) - * { - * t1(); - * t2(); - * } @endcode - * - * yield break ; - * - * The final form of @c yield is used to explicitly terminate the coroutine. - * This form is comprised of two steps: - * - * @li @c yield sets the coroutine state to indicate termination. - * @li Control is transferred to the end of the coroutine body. - * - * Once terminated, calls to is_complete() return true and the coroutine cannot - * be reentered. - * - * Note that a coroutine may also be implicitly terminated if the coroutine - * body is exited without a yield, e.g. by return, throw or by running to the - * end of the body. - * - * fork statement - * - * The @c fork pseudo-keyword is used when "forking" a coroutine, i.e. splitting - * it into two (or more) copies. One use of @c fork is in a server, where a new - * coroutine is created to handle each client connection: - * - * @code reenter (this) - * { - * do - * { - * socket_.reset(new tcp::socket(io_context_)); - * yield acceptor->async_accept(*socket_, *this); - * fork server(*this)(); - * } while (is_parent()); - * ... client-specific handling follows ... - * } @endcode - * - * The logical steps involved in a @c fork are: - * - * @li @c fork saves the current state of the coroutine. - * @li The statement creates a copy of the coroutine and either executes it - * immediately or schedules it for later execution. - * @li The resume point is defined immediately following the semicolon. - * @li For the "parent", control immediately continues from the next line. - * - * The functions is_parent() and is_child() can be used to differentiate - * between parent and child. You would use these functions to alter subsequent - * control flow. - * - * Note that @c fork doesn't do the actual forking by itself. It is the - * application's responsibility to create a clone of the coroutine and call it. - * The clone can be called immediately, as above, or scheduled for delayed - * execution using something like io_context::post(). - * - * @par Alternate macro names - * - * If preferred, an application can use macro names that follow a more typical - * naming convention, rather than the pseudo-keywords. These are: - * - * @li @c ASIO_CORO_REENTER instead of @c reenter - * @li @c ASIO_CORO_YIELD instead of @c yield - * @li @c ASIO_CORO_FORK instead of @c fork - */ -class coroutine -{ -public: - /// Constructs a coroutine in its initial state. - coroutine() : value_(0) {} - - /// Returns true if the coroutine is the child of a fork. - bool is_child() const { return value_ < 0; } - - /// Returns true if the coroutine is the parent of a fork. - bool is_parent() const { return !is_child(); } - - /// Returns true if the coroutine has reached its terminal state. - bool is_complete() const { return value_ == -1; } - -private: - friend class detail::coroutine_ref; - int value_; -}; - - -namespace detail { - -class coroutine_ref -{ -public: - coroutine_ref(coroutine& c) : value_(c.value_), modified_(false) {} - coroutine_ref(coroutine* c) : value_(c->value_), modified_(false) {} - ~coroutine_ref() { if (!modified_) value_ = -1; } - operator int() const { return value_; } - int& operator=(int v) { modified_ = true; return value_ = v; } -private: - void operator=(const coroutine_ref&); - int& value_; - bool modified_; -}; - -} // namespace detail -} // namespace asio - -#define ASIO_CORO_REENTER(c) \ - switch (::asio::detail::coroutine_ref _coro_value = c) \ - case -1: if (_coro_value) \ - { \ - goto terminate_coroutine; \ - terminate_coroutine: \ - _coro_value = -1; \ - goto bail_out_of_coroutine; \ - bail_out_of_coroutine: \ - break; \ - } \ - else /* fall-through */ case 0: - -#define ASIO_CORO_YIELD_IMPL(n) \ - for (_coro_value = (n);;) \ - if (_coro_value == 0) \ - { \ - case (n): ; \ - break; \ - } \ - else \ - switch (_coro_value ? 0 : 1) \ - for (;;) \ - /* fall-through */ case -1: if (_coro_value) \ - goto terminate_coroutine; \ - else for (;;) \ - /* fall-through */ case 1: if (_coro_value) \ - goto bail_out_of_coroutine; \ - else /* fall-through */ case 0: - -#define ASIO_CORO_FORK_IMPL(n) \ - for (_coro_value = -(n);; _coro_value = (n)) \ - if (_coro_value == (n)) \ - { \ - case -(n): ; \ - break; \ - } \ - else - -#if defined(_MSC_VER) -# define ASIO_CORO_YIELD ASIO_CORO_YIELD_IMPL(__COUNTER__ + 1) -# define ASIO_CORO_FORK ASIO_CORO_FORK_IMPL(__COUNTER__ + 1) -#else // defined(_MSC_VER) -# define ASIO_CORO_YIELD ASIO_CORO_YIELD_IMPL(__LINE__) -# define ASIO_CORO_FORK ASIO_CORO_FORK_IMPL(__LINE__) -#endif // defined(_MSC_VER) - -#endif // ASIO_COROUTINE_HPP diff --git a/scout_sdk/asio/asio/datagram_socket_service.hpp b/scout_sdk/asio/asio/datagram_socket_service.hpp deleted file mode 100644 index 7dc1a3b..0000000 --- a/scout_sdk/asio/asio/datagram_socket_service.hpp +++ /dev/null @@ -1,466 +0,0 @@ -// -// datagram_socket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DATAGRAM_SOCKET_SERVICE_HPP -#define ASIO_DATAGRAM_SOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/null_socket_service.hpp" -#elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_socket_service.hpp" -#else -# include "asio/detail/reactive_socket_service.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a datagram socket. -template -class datagram_socket_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - -private: - // The type of the platform-specific implementation. -#if defined(ASIO_WINDOWS_RUNTIME) - typedef detail::null_socket_service service_impl_type; -#elif defined(ASIO_HAS_IOCP) - typedef detail::win_iocp_socket_service service_impl_type; -#else - typedef detail::reactive_socket_service service_impl_type; -#endif - -public: - /// The type of a datagram socket. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// The native socket type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new datagram socket service for the specified io_context. - explicit datagram_socket_service(asio::io_context& io_context) - : asio::detail::service_base< - datagram_socket_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new datagram socket implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new datagram socket implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another datagram socket implementation. - void move_assign(implementation_type& impl, - datagram_socket_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } - - // All socket services have access to each other's implementations. - template friend class datagram_socket_service; - - /// Move-construct a new datagram socket implementation from another protocol - /// type. - template - void converting_move_construct(implementation_type& impl, - datagram_socket_service& other_service, - typename datagram_socket_service< - Protocol1>::implementation_type& other_impl, - typename enable_if::value>::type* = 0) - { - service_impl_.template converting_move_construct( - impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a datagram socket implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - // Open a new datagram socket implementation. - ASIO_SYNC_OP_VOID open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - if (protocol.type() == ASIO_OS_DEF(SOCK_DGRAM)) - service_impl_.open(impl, protocol, ec); - else - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native socket to a datagram socket. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_socket, - asio::error_code& ec) - { - service_impl_.assign(impl, protocol, native_socket, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a datagram socket implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Release ownership of the underlying socket. - native_handle_type release(implementation_type& impl, - asio::error_code& ec) - { - return service_impl_.release(impl, ec); - } - - /// Get the native socket implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the socket. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is at the out-of-band data mark. - bool at_mark(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.at_mark(impl, ec); - } - - /// Determine the number of bytes available for reading. - std::size_t available(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.available(impl, ec); - } - - // Bind the datagram socket to the specified local endpoint. - ASIO_SYNC_OP_VOID bind(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - service_impl_.bind(impl, endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Connect the datagram socket to the specified endpoint. - ASIO_SYNC_OP_VOID connect(implementation_type& impl, - const endpoint_type& peer_endpoint, asio::error_code& ec) - { - service_impl_.connect(impl, peer_endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous connect. - template - ASIO_INITFN_RESULT_TYPE(ConnectHandler, - void (asio::error_code)) - async_connect(implementation_type& impl, - const endpoint_type& peer_endpoint, - ASIO_MOVE_ARG(ConnectHandler) handler) - { - async_completion init(handler); - - service_impl_.async_connect(impl, peer_endpoint, init.completion_handler); - - return init.result.get(); - } - - /// Set a socket option. - template - ASIO_SYNC_OP_VOID set_option(implementation_type& impl, - const SettableSocketOption& option, asio::error_code& ec) - { - service_impl_.set_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get a socket option. - template - ASIO_SYNC_OP_VOID get_option(const implementation_type& impl, - GettableSocketOption& option, asio::error_code& ec) const - { - service_impl_.get_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the socket. - template - ASIO_SYNC_OP_VOID io_control(implementation_type& impl, - IoControlCommand& command, asio::error_code& ec) - { - service_impl_.io_control(impl, command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the socket. - bool non_blocking(const implementation_type& impl) const - { - return service_impl_.non_blocking(impl); - } - - /// Sets the non-blocking mode of the socket. - ASIO_SYNC_OP_VOID non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const implementation_type& impl) const - { - return service_impl_.native_non_blocking(impl); - } - - /// Sets the non-blocking mode of the native socket implementation. - ASIO_SYNC_OP_VOID native_non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.native_non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.local_endpoint(impl, ec); - } - - /// Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.remote_endpoint(impl, ec); - } - - /// Disable sends or receives on the socket. - ASIO_SYNC_OP_VOID shutdown(implementation_type& impl, - socket_base::shutdown_type what, asio::error_code& ec) - { - service_impl_.shutdown(impl, what, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the socket to become ready to read, ready to write, or to have - /// pending error conditions. - ASIO_SYNC_OP_VOID wait(implementation_type& impl, - socket_base::wait_type w, asio::error_code& ec) - { - service_impl_.wait(impl, w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the socket to become ready to read, ready to - /// write, or to have pending error conditions. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, socket_base::wait_type w, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, w, init.completion_handler); - - return init.result.get(); - } - - /// Send the given data to the peer. - template - std::size_t send(implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.send(impl, buffers, flags, ec); - } - - /// Start an asynchronous send. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(implementation_type& impl, const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - async_completion init(handler); - - service_impl_.async_send(impl, buffers, flags, init.completion_handler); - - return init.result.get(); - } - - /// Send a datagram to the specified endpoint. - template - std::size_t send_to(implementation_type& impl, - const ConstBufferSequence& buffers, const endpoint_type& destination, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.send_to(impl, buffers, destination, flags, ec); - } - - /// Start an asynchronous send. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send_to(implementation_type& impl, - const ConstBufferSequence& buffers, const endpoint_type& destination, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - async_completion init(handler); - - service_impl_.async_send_to(impl, buffers, - destination, flags, init.completion_handler); - - return init.result.get(); - } - - /// Receive some data from the peer. - template - std::size_t receive(implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.receive(impl, buffers, flags, ec); - } - - /// Start an asynchronous receive. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - async_completion init(handler); - - service_impl_.async_receive(impl, buffers, flags, init.completion_handler); - - return init.result.get(); - } - - /// Receive a datagram with the endpoint of the sender. - template - std::size_t receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, endpoint_type& sender_endpoint, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.receive_from(impl, buffers, sender_endpoint, flags, - ec); - } - - /// Start an asynchronous receive that will get the endpoint of the sender. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, endpoint_type& sender_endpoint, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - async_completion init(handler); - - service_impl_.async_receive_from(impl, buffers, - sender_endpoint, flags, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_DATAGRAM_SOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/deadline_timer.hpp b/scout_sdk/asio/asio/deadline_timer.hpp deleted file mode 100644 index 5a21554..0000000 --- a/scout_sdk/asio/asio/deadline_timer.hpp +++ /dev/null @@ -1,38 +0,0 @@ -// -// deadline_timer.hpp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DEADLINE_TIMER_HPP -#define ASIO_DEADLINE_TIMER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/detail/socket_types.hpp" // Must come before posix_time. -#include "asio/basic_deadline_timer.hpp" - -#include - -namespace asio { - -/// Typedef for the typical usage of timer. Uses a UTC clock. -typedef basic_deadline_timer deadline_timer; - -} // namespace asio - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_DEADLINE_TIMER_HPP diff --git a/scout_sdk/asio/asio/deadline_timer_service.hpp b/scout_sdk/asio/asio/deadline_timer_service.hpp deleted file mode 100644 index 2dcc83e..0000000 --- a/scout_sdk/asio/asio/deadline_timer_service.hpp +++ /dev/null @@ -1,173 +0,0 @@ -// -// deadline_timer_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DEADLINE_TIMER_SERVICE_HPP -#define ASIO_DEADLINE_TIMER_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/deadline_timer_service.hpp" -#include "asio/io_context.hpp" -#include "asio/time_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a timer. -template > -class deadline_timer_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base< - deadline_timer_service > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The time traits type. - typedef TimeTraits traits_type; - - /// The time type. - typedef typename traits_type::time_type time_type; - - /// The duration type. - typedef typename traits_type::duration_type duration_type; - -private: - // The type of the platform-specific implementation. - typedef detail::deadline_timer_service service_impl_type; - -public: - /// The implementation type of the deadline timer. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// Construct a new timer service for the specified io_context. - explicit deadline_timer_service(asio::io_context& io_context) - : asio::detail::service_base< - deadline_timer_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new timer implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - - /// Destroy a timer implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Cancel any asynchronous wait operations associated with the timer. - std::size_t cancel(implementation_type& impl, asio::error_code& ec) - { - return service_impl_.cancel(impl, ec); - } - - /// Cancels one asynchronous wait operation associated with the timer. - std::size_t cancel_one(implementation_type& impl, - asio::error_code& ec) - { - return service_impl_.cancel_one(impl, ec); - } - - /// Get the expiry time for the timer as an absolute time. - time_type expires_at(const implementation_type& impl) const - { - return service_impl_.expiry(impl); - } - - /// Set the expiry time for the timer as an absolute time. - std::size_t expires_at(implementation_type& impl, - const time_type& expiry_time, asio::error_code& ec) - { - return service_impl_.expires_at(impl, expiry_time, ec); - } - - /// Get the expiry time for the timer relative to now. - duration_type expires_from_now(const implementation_type& impl) const - { - return TimeTraits::subtract(service_impl_.expiry(impl), TimeTraits::now()); - } - - /// Set the expiry time for the timer relative to now. - std::size_t expires_from_now(implementation_type& impl, - const duration_type& expiry_time, asio::error_code& ec) - { - return service_impl_.expires_after(impl, expiry_time, ec); - } - - // Perform a blocking wait on the timer. - void wait(implementation_type& impl, asio::error_code& ec) - { - service_impl_.wait(impl, ec); - } - - // Start an asynchronous wait on the timer. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_DEADLINE_TIMER_SERVICE_HPP diff --git a/scout_sdk/asio/asio/defer.hpp b/scout_sdk/asio/asio/defer.hpp deleted file mode 100644 index a0897f2..0000000 --- a/scout_sdk/asio/asio/defer.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// -// defer.hpp -// ~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DEFER_HPP -#define ASIO_DEFER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/execution_context.hpp" -#include "asio/is_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Submits a completion token or function object for execution. -/** - * This function submits an object for execution using the object's associated - * executor. The function object is queued for execution, and is never called - * from the current thread prior to returning from defer(). - * - * This function has the following effects: - * - * @li Constructs a function object handler of type @c Handler, initialized - * with handler(forward(token)). - * - * @li Constructs an object @c result of type async_result, - * initializing the object as result(handler). - * - * @li Obtains the handler's associated executor object @c ex by performing - * get_associated_executor(handler). - * - * @li Obtains the handler's associated allocator object @c alloc by performing - * get_associated_allocator(handler). - * - * @li Performs ex.defer(std::move(handler), alloc). - * - * @li Returns result.get(). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) defer( - ASIO_MOVE_ARG(CompletionToken) token); - -/// Submits a completion token or function object for execution. -/** - * This function submits an object for execution using the specified executor. - * The function object is queued for execution, and is never called from the - * current thread prior to returning from defer(). - * - * This function has the following effects: - * - * @li Constructs a function object handler of type @c Handler, initialized - * with handler(forward(token)). - * - * @li Constructs an object @c result of type async_result, - * initializing the object as result(handler). - * - * @li Obtains the handler's associated executor object @c ex1 by performing - * get_associated_executor(handler). - * - * @li Creates a work object @c w by performing make_work(ex1). - * - * @li Obtains the handler's associated allocator object @c alloc by performing - * get_associated_allocator(handler). - * - * @li Constructs a function object @c f with a function call operator that - * performs ex1.dispatch(std::move(handler), alloc) followed by - * w.reset(). - * - * @li Performs Executor(ex).defer(std::move(f), alloc). - * - * @li Returns result.get(). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) defer( - const Executor& ex, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type* = 0); - -/// Submits a completion token or function object for execution. -/** - * @returns defer(ctx.get_executor(), forward(token)). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) defer( - ExecutionContext& ctx, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type* = 0); - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/defer.hpp" - -#endif // ASIO_DEFER_HPP diff --git a/scout_sdk/asio/asio/detail/array.hpp b/scout_sdk/asio/asio/detail/array.hpp deleted file mode 100644 index ba42974..0000000 --- a/scout_sdk/asio/asio/detail/array.hpp +++ /dev/null @@ -1,38 +0,0 @@ -// -// detail/array.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_ARRAY_HPP -#define ASIO_DETAIL_ARRAY_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_ARRAY) -# include -#else // defined(ASIO_HAS_STD_ARRAY) -# include -#endif // defined(ASIO_HAS_STD_ARRAY) - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_STD_ARRAY) -using std::array; -#else // defined(ASIO_HAS_STD_ARRAY) -using boost::array; -#endif // defined(ASIO_HAS_STD_ARRAY) - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_ARRAY_HPP diff --git a/scout_sdk/asio/asio/detail/array_fwd.hpp b/scout_sdk/asio/asio/detail/array_fwd.hpp deleted file mode 100644 index 4161db0..0000000 --- a/scout_sdk/asio/asio/detail/array_fwd.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// -// detail/array_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_ARRAY_FWD_HPP -#define ASIO_DETAIL_ARRAY_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -namespace boost { - -template -class array; - -} // namespace boost - -// Standard library components can't be forward declared, so we'll have to -// include the array header. Fortunately, it's fairly lightweight and doesn't -// add significantly to the compile time. -#if defined(ASIO_HAS_STD_ARRAY) -# include -#endif // defined(ASIO_HAS_STD_ARRAY) - -#endif // ASIO_DETAIL_ARRAY_FWD_HPP diff --git a/scout_sdk/asio/asio/detail/assert.hpp b/scout_sdk/asio/asio/detail/assert.hpp deleted file mode 100644 index a952a44..0000000 --- a/scout_sdk/asio/asio/detail/assert.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// -// detail/assert.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_ASSERT_HPP -#define ASIO_DETAIL_ASSERT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_ASSERT) -# include -#else // defined(ASIO_HAS_BOOST_ASSERT) -# include -#endif // defined(ASIO_HAS_BOOST_ASSERT) - -#if defined(ASIO_HAS_BOOST_ASSERT) -# define ASIO_ASSERT(expr) BOOST_ASSERT(expr) -#else // defined(ASIO_HAS_BOOST_ASSERT) -# define ASIO_ASSERT(expr) assert(expr) -#endif // defined(ASIO_HAS_BOOST_ASSERT) - -#endif // ASIO_DETAIL_ASSERT_HPP diff --git a/scout_sdk/asio/asio/detail/atomic_count.hpp b/scout_sdk/asio/asio/detail/atomic_count.hpp deleted file mode 100644 index 2bf75a5..0000000 --- a/scout_sdk/asio/asio/detail/atomic_count.hpp +++ /dev/null @@ -1,45 +0,0 @@ -// -// detail/atomic_count.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_ATOMIC_COUNT_HPP -#define ASIO_DETAIL_ATOMIC_COUNT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) -// Nothing to include. -#elif defined(ASIO_HAS_STD_ATOMIC) -# include -#else // defined(ASIO_HAS_STD_ATOMIC) -# include -#endif // defined(ASIO_HAS_STD_ATOMIC) - -namespace asio { -namespace detail { - -#if !defined(ASIO_HAS_THREADS) -typedef long atomic_count; -inline void increment(atomic_count& a, long b) { a += b; } -#elif defined(ASIO_HAS_STD_ATOMIC) -typedef std::atomic atomic_count; -inline void increment(atomic_count& a, long b) { a += b; } -#else // defined(ASIO_HAS_STD_ATOMIC) -typedef boost::detail::atomic_count atomic_count; -inline void increment(atomic_count& a, long b) { while (b > 0) ++a, --b; } -#endif // defined(ASIO_HAS_STD_ATOMIC) - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_ATOMIC_COUNT_HPP diff --git a/scout_sdk/asio/asio/detail/base_from_completion_cond.hpp b/scout_sdk/asio/asio/detail/base_from_completion_cond.hpp deleted file mode 100644 index 73b4a95..0000000 --- a/scout_sdk/asio/asio/detail/base_from_completion_cond.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// -// detail/base_from_completion_cond.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_BASE_FROM_COMPLETION_COND_HPP -#define ASIO_DETAIL_BASE_FROM_COMPLETION_COND_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/completion_condition.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class base_from_completion_cond -{ -protected: - explicit base_from_completion_cond(CompletionCondition completion_condition) - : completion_condition_(completion_condition) - { - } - - std::size_t check_for_completion( - const asio::error_code& ec, - std::size_t total_transferred) - { - return detail::adapt_completion_condition_result( - completion_condition_(ec, total_transferred)); - } - -private: - CompletionCondition completion_condition_; -}; - -template <> -class base_from_completion_cond -{ -protected: - explicit base_from_completion_cond(transfer_all_t) - { - } - - static std::size_t check_for_completion( - const asio::error_code& ec, - std::size_t total_transferred) - { - return transfer_all_t()(ec, total_transferred); - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_BASE_FROM_COMPLETION_COND_HPP diff --git a/scout_sdk/asio/asio/detail/bind_handler.hpp b/scout_sdk/asio/asio/detail/bind_handler.hpp deleted file mode 100644 index 0f4f066..0000000 --- a/scout_sdk/asio/asio/detail/bind_handler.hpp +++ /dev/null @@ -1,816 +0,0 @@ -// -// detail/bind_handler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_BIND_HANDLER_HPP -#define ASIO_DETAIL_BIND_HANDLER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class binder1 -{ -public: - template - binder1(int, ASIO_MOVE_ARG(T) handler, const Arg1& arg1) - : handler_(ASIO_MOVE_CAST(T)(handler)), - arg1_(arg1) - { - } - - binder1(Handler& handler, const Arg1& arg1) - : handler_(ASIO_MOVE_CAST(Handler)(handler)), - arg1_(arg1) - { - } - -#if defined(ASIO_HAS_MOVE) - binder1(const binder1& other) - : handler_(other.handler_), - arg1_(other.arg1_) - { - } - - binder1(binder1&& other) - : handler_(ASIO_MOVE_CAST(Handler)(other.handler_)), - arg1_(ASIO_MOVE_CAST(Arg1)(other.arg1_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - handler_(static_cast(arg1_)); - } - - void operator()() const - { - handler_(arg1_); - } - -//private: - Handler handler_; - Arg1 arg1_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - binder1* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - binder1* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - binder1* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - binder1* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void asio_handler_invoke(const Function& function, - binder1* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline binder1::type, Arg1> bind_handler( - ASIO_MOVE_ARG(Handler) handler, const Arg1& arg1) -{ - return binder1::type, Arg1>(0, - ASIO_MOVE_CAST(Handler)(handler), arg1); -} - -template -class binder2 -{ -public: - template - binder2(int, ASIO_MOVE_ARG(T) handler, - const Arg1& arg1, const Arg2& arg2) - : handler_(ASIO_MOVE_CAST(T)(handler)), - arg1_(arg1), - arg2_(arg2) - { - } - - binder2(Handler& handler, const Arg1& arg1, const Arg2& arg2) - : handler_(ASIO_MOVE_CAST(Handler)(handler)), - arg1_(arg1), - arg2_(arg2) - { - } - -#if defined(ASIO_HAS_MOVE) - binder2(const binder2& other) - : handler_(other.handler_), - arg1_(other.arg1_), - arg2_(other.arg2_) - { - } - - binder2(binder2&& other) - : handler_(ASIO_MOVE_CAST(Handler)(other.handler_)), - arg1_(ASIO_MOVE_CAST(Arg1)(other.arg1_)), - arg2_(ASIO_MOVE_CAST(Arg2)(other.arg2_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - handler_(static_cast(arg1_), - static_cast(arg2_)); - } - - void operator()() const - { - handler_(arg1_, arg2_); - } - -//private: - Handler handler_; - Arg1 arg1_; - Arg2 arg2_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - binder2* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - binder2* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - binder2* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - binder2* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void asio_handler_invoke(const Function& function, - binder2* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline binder2::type, Arg1, Arg2> bind_handler( - ASIO_MOVE_ARG(Handler) handler, const Arg1& arg1, const Arg2& arg2) -{ - return binder2::type, Arg1, Arg2>(0, - ASIO_MOVE_CAST(Handler)(handler), arg1, arg2); -} - -template -class binder3 -{ -public: - template - binder3(int, ASIO_MOVE_ARG(T) handler, const Arg1& arg1, - const Arg2& arg2, const Arg3& arg3) - : handler_(ASIO_MOVE_CAST(T)(handler)), - arg1_(arg1), - arg2_(arg2), - arg3_(arg3) - { - } - - binder3(Handler& handler, const Arg1& arg1, - const Arg2& arg2, const Arg3& arg3) - : handler_(ASIO_MOVE_CAST(Handler)(handler)), - arg1_(arg1), - arg2_(arg2), - arg3_(arg3) - { - } - -#if defined(ASIO_HAS_MOVE) - binder3(const binder3& other) - : handler_(other.handler_), - arg1_(other.arg1_), - arg2_(other.arg2_), - arg3_(other.arg3_) - { - } - - binder3(binder3&& other) - : handler_(ASIO_MOVE_CAST(Handler)(other.handler_)), - arg1_(ASIO_MOVE_CAST(Arg1)(other.arg1_)), - arg2_(ASIO_MOVE_CAST(Arg2)(other.arg2_)), - arg3_(ASIO_MOVE_CAST(Arg3)(other.arg3_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - handler_(static_cast(arg1_), - static_cast(arg2_), static_cast(arg3_)); - } - - void operator()() const - { - handler_(arg1_, arg2_, arg3_); - } - -//private: - Handler handler_; - Arg1 arg1_; - Arg2 arg2_; - Arg3 arg3_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - binder3* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - binder3* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - binder3* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - binder3* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void asio_handler_invoke(const Function& function, - binder3* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline binder3::type, Arg1, Arg2, Arg3> bind_handler( - ASIO_MOVE_ARG(Handler) handler, const Arg1& arg1, const Arg2& arg2, - const Arg3& arg3) -{ - return binder3::type, Arg1, Arg2, Arg3>(0, - ASIO_MOVE_CAST(Handler)(handler), arg1, arg2, arg3); -} - -template -class binder4 -{ -public: - template - binder4(int, ASIO_MOVE_ARG(T) handler, const Arg1& arg1, - const Arg2& arg2, const Arg3& arg3, const Arg4& arg4) - : handler_(ASIO_MOVE_CAST(T)(handler)), - arg1_(arg1), - arg2_(arg2), - arg3_(arg3), - arg4_(arg4) - { - } - - binder4(Handler& handler, const Arg1& arg1, - const Arg2& arg2, const Arg3& arg3, const Arg4& arg4) - : handler_(ASIO_MOVE_CAST(Handler)(handler)), - arg1_(arg1), - arg2_(arg2), - arg3_(arg3), - arg4_(arg4) - { - } - -#if defined(ASIO_HAS_MOVE) - binder4(const binder4& other) - : handler_(other.handler_), - arg1_(other.arg1_), - arg2_(other.arg2_), - arg3_(other.arg3_), - arg4_(other.arg4_) - { - } - - binder4(binder4&& other) - : handler_(ASIO_MOVE_CAST(Handler)(other.handler_)), - arg1_(ASIO_MOVE_CAST(Arg1)(other.arg1_)), - arg2_(ASIO_MOVE_CAST(Arg2)(other.arg2_)), - arg3_(ASIO_MOVE_CAST(Arg3)(other.arg3_)), - arg4_(ASIO_MOVE_CAST(Arg4)(other.arg4_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - handler_(static_cast(arg1_), - static_cast(arg2_), static_cast(arg3_), - static_cast(arg4_)); - } - - void operator()() const - { - handler_(arg1_, arg2_, arg3_, arg4_); - } - -//private: - Handler handler_; - Arg1 arg1_; - Arg2 arg2_; - Arg3 arg3_; - Arg4 arg4_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - binder4* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - binder4* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - binder4* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - binder4* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void asio_handler_invoke(const Function& function, - binder4* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline binder4::type, Arg1, Arg2, Arg3, Arg4> -bind_handler(ASIO_MOVE_ARG(Handler) handler, const Arg1& arg1, - const Arg2& arg2, const Arg3& arg3, const Arg4& arg4) -{ - return binder4::type, Arg1, Arg2, Arg3, Arg4>(0, - ASIO_MOVE_CAST(Handler)(handler), arg1, arg2, arg3, arg4); -} - -template -class binder5 -{ -public: - template - binder5(int, ASIO_MOVE_ARG(T) handler, const Arg1& arg1, - const Arg2& arg2, const Arg3& arg3, const Arg4& arg4, const Arg5& arg5) - : handler_(ASIO_MOVE_CAST(T)(handler)), - arg1_(arg1), - arg2_(arg2), - arg3_(arg3), - arg4_(arg4), - arg5_(arg5) - { - } - - binder5(Handler& handler, const Arg1& arg1, const Arg2& arg2, - const Arg3& arg3, const Arg4& arg4, const Arg5& arg5) - : handler_(ASIO_MOVE_CAST(Handler)(handler)), - arg1_(arg1), - arg2_(arg2), - arg3_(arg3), - arg4_(arg4), - arg5_(arg5) - { - } - -#if defined(ASIO_HAS_MOVE) - binder5(const binder5& other) - : handler_(other.handler_), - arg1_(other.arg1_), - arg2_(other.arg2_), - arg3_(other.arg3_), - arg4_(other.arg4_), - arg5_(other.arg5_) - { - } - - binder5(binder5&& other) - : handler_(ASIO_MOVE_CAST(Handler)(other.handler_)), - arg1_(ASIO_MOVE_CAST(Arg1)(other.arg1_)), - arg2_(ASIO_MOVE_CAST(Arg2)(other.arg2_)), - arg3_(ASIO_MOVE_CAST(Arg3)(other.arg3_)), - arg4_(ASIO_MOVE_CAST(Arg4)(other.arg4_)), - arg5_(ASIO_MOVE_CAST(Arg5)(other.arg5_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - handler_(static_cast(arg1_), - static_cast(arg2_), static_cast(arg3_), - static_cast(arg4_), static_cast(arg5_)); - } - - void operator()() const - { - handler_(arg1_, arg2_, arg3_, arg4_, arg5_); - } - -//private: - Handler handler_; - Arg1 arg1_; - Arg2 arg2_; - Arg3 arg3_; - Arg4 arg4_; - Arg5 arg5_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - binder5* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - binder5* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - binder5* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - binder5* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void asio_handler_invoke(const Function& function, - binder5* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline binder5::type, Arg1, Arg2, Arg3, Arg4, Arg5> -bind_handler(ASIO_MOVE_ARG(Handler) handler, const Arg1& arg1, - const Arg2& arg2, const Arg3& arg3, const Arg4& arg4, const Arg5& arg5) -{ - return binder5::type, Arg1, Arg2, Arg3, Arg4, Arg5>(0, - ASIO_MOVE_CAST(Handler)(handler), arg1, arg2, arg3, arg4, arg5); -} - -#if defined(ASIO_HAS_MOVE) - -template -class move_binder1 -{ -public: - move_binder1(int, ASIO_MOVE_ARG(Handler) handler, - ASIO_MOVE_ARG(Arg1) arg1) - : handler_(ASIO_MOVE_CAST(Handler)(handler)), - arg1_(ASIO_MOVE_CAST(Arg1)(arg1)) - { - } - - move_binder1(move_binder1&& other) - : handler_(ASIO_MOVE_CAST(Handler)(other.handler_)), - arg1_(ASIO_MOVE_CAST(Arg1)(other.arg1_)) - { - } - - void operator()() - { - handler_(ASIO_MOVE_CAST(Arg1)(arg1_)); - } - -//private: - Handler handler_; - Arg1 arg1_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - move_binder1* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - move_binder1* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - move_binder1* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(ASIO_MOVE_ARG(Function) function, - move_binder1* this_handler) -{ - asio_handler_invoke_helpers::invoke( - ASIO_MOVE_CAST(Function)(function), this_handler->handler_); -} - -template -class move_binder2 -{ -public: - move_binder2(int, ASIO_MOVE_ARG(Handler) handler, - const Arg1& arg1, ASIO_MOVE_ARG(Arg2) arg2) - : handler_(ASIO_MOVE_CAST(Handler)(handler)), - arg1_(arg1), - arg2_(ASIO_MOVE_CAST(Arg2)(arg2)) - { - } - - move_binder2(move_binder2&& other) - : handler_(ASIO_MOVE_CAST(Handler)(other.handler_)), - arg1_(ASIO_MOVE_CAST(Arg1)(other.arg1_)), - arg2_(ASIO_MOVE_CAST(Arg2)(other.arg2_)) - { - } - - void operator()() - { - handler_(static_cast(arg1_), - ASIO_MOVE_CAST(Arg2)(arg2_)); - } - -//private: - Handler handler_; - Arg1 arg1_; - Arg2 arg2_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - move_binder2* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - move_binder2* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - move_binder2* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(ASIO_MOVE_ARG(Function) function, - move_binder2* this_handler) -{ - asio_handler_invoke_helpers::invoke( - ASIO_MOVE_CAST(Function)(function), this_handler->handler_); -} - -#endif // defined(ASIO_HAS_MOVE) - -} // namespace detail - -template -struct associated_allocator, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const detail::binder1& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_allocator, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const detail::binder2& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const detail::binder1& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -template -struct associated_executor, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const detail::binder2& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#if defined(ASIO_HAS_MOVE) - -template -struct associated_allocator, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const detail::move_binder1& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_allocator< - detail::move_binder2, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const detail::move_binder2& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const detail::move_binder1& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -template -struct associated_executor, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const detail::move_binder2& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // defined(ASIO_HAS_MOVE) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_BIND_HANDLER_HPP diff --git a/scout_sdk/asio/asio/detail/buffer_resize_guard.hpp b/scout_sdk/asio/asio/detail/buffer_resize_guard.hpp deleted file mode 100644 index 58ebc4c..0000000 --- a/scout_sdk/asio/asio/detail/buffer_resize_guard.hpp +++ /dev/null @@ -1,66 +0,0 @@ -// -// detail/buffer_resize_guard.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_BUFFER_RESIZE_GUARD_HPP -#define ASIO_DETAIL_BUFFER_RESIZE_GUARD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/limits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Helper class to manage buffer resizing in an exception safe way. -template -class buffer_resize_guard -{ -public: - // Constructor. - buffer_resize_guard(Buffer& buffer) - : buffer_(buffer), - old_size_(buffer.size()) - { - } - - // Destructor rolls back the buffer resize unless commit was called. - ~buffer_resize_guard() - { - if (old_size_ != (std::numeric_limits::max)()) - { - buffer_.resize(old_size_); - } - } - - // Commit the resize transaction. - void commit() - { - old_size_ = (std::numeric_limits::max)(); - } - -private: - // The buffer being managed. - Buffer& buffer_; - - // The size of the buffer at the time the guard was constructed. - size_t old_size_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_BUFFER_RESIZE_GUARD_HPP diff --git a/scout_sdk/asio/asio/detail/buffer_sequence_adapter.hpp b/scout_sdk/asio/asio/detail/buffer_sequence_adapter.hpp deleted file mode 100644 index 92a8e3d..0000000 --- a/scout_sdk/asio/asio/detail/buffer_sequence_adapter.hpp +++ /dev/null @@ -1,544 +0,0 @@ -// -// detail/buffer_sequence_adapter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_BUFFER_SEQUENCE_ADAPTER_HPP -#define ASIO_DETAIL_BUFFER_SEQUENCE_ADAPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/buffer.hpp" -#include "asio/detail/array_fwd.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class buffer_sequence_adapter_base -{ -#if defined(ASIO_WINDOWS_RUNTIME) -public: - // The maximum number of buffers to support in a single operation. - enum { max_buffers = 1 }; - -protected: - typedef Windows::Storage::Streams::IBuffer^ native_buffer_type; - - ASIO_DECL static void init_native_buffer( - native_buffer_type& buf, - const asio::mutable_buffer& buffer); - - ASIO_DECL static void init_native_buffer( - native_buffer_type& buf, - const asio::const_buffer& buffer); -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) -public: - // The maximum number of buffers to support in a single operation. - enum { max_buffers = 64 < max_iov_len ? 64 : max_iov_len }; - -protected: - typedef WSABUF native_buffer_type; - - static void init_native_buffer(WSABUF& buf, - const asio::mutable_buffer& buffer) - { - buf.buf = static_cast(buffer.data()); - buf.len = static_cast(buffer.size()); - } - - static void init_native_buffer(WSABUF& buf, - const asio::const_buffer& buffer) - { - buf.buf = const_cast(static_cast(buffer.data())); - buf.len = static_cast(buffer.size()); - } -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -public: - // The maximum number of buffers to support in a single operation. - enum { max_buffers = 64 < max_iov_len ? 64 : max_iov_len }; - -protected: - typedef iovec native_buffer_type; - - static void init_iov_base(void*& base, void* addr) - { - base = addr; - } - - template - static void init_iov_base(T& base, void* addr) - { - base = static_cast(addr); - } - - static void init_native_buffer(iovec& iov, - const asio::mutable_buffer& buffer) - { - init_iov_base(iov.iov_base, buffer.data()); - iov.iov_len = buffer.size(); - } - - static void init_native_buffer(iovec& iov, - const asio::const_buffer& buffer) - { - init_iov_base(iov.iov_base, const_cast(buffer.data())); - iov.iov_len = buffer.size(); - } -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -}; - -// Helper class to translate buffers into the native buffer representation. -template -class buffer_sequence_adapter - : buffer_sequence_adapter_base -{ -public: - explicit buffer_sequence_adapter(const Buffers& buffer_sequence) - : count_(0), total_buffer_size_(0) - { - buffer_sequence_adapter::init( - asio::buffer_sequence_begin(buffer_sequence), - asio::buffer_sequence_end(buffer_sequence)); - } - - native_buffer_type* buffers() - { - return buffers_; - } - - std::size_t count() const - { - return count_; - } - - std::size_t total_size() const - { - return total_buffer_size_; - } - - bool all_empty() const - { - return total_buffer_size_ == 0; - } - - static bool all_empty(const Buffers& buffer_sequence) - { - return buffer_sequence_adapter::all_empty( - asio::buffer_sequence_begin(buffer_sequence), - asio::buffer_sequence_end(buffer_sequence)); - } - - static void validate(const Buffers& buffer_sequence) - { - buffer_sequence_adapter::validate( - asio::buffer_sequence_begin(buffer_sequence), - asio::buffer_sequence_end(buffer_sequence)); - } - - static Buffer first(const Buffers& buffer_sequence) - { - return buffer_sequence_adapter::first( - asio::buffer_sequence_begin(buffer_sequence), - asio::buffer_sequence_end(buffer_sequence)); - } - -private: - template - void init(Iterator begin, Iterator end) - { - Iterator iter = begin; - for (; iter != end && count_ < max_buffers; ++iter, ++count_) - { - Buffer buffer(*iter); - init_native_buffer(buffers_[count_], buffer); - total_buffer_size_ += buffer.size(); - } - } - - template - static bool all_empty(Iterator begin, Iterator end) - { - Iterator iter = begin; - std::size_t i = 0; - for (; iter != end && i < max_buffers; ++iter, ++i) - if (Buffer(*iter).size() > 0) - return false; - return true; - } - - template - static void validate(Iterator begin, Iterator end) - { - Iterator iter = begin; - for (; iter != end; ++iter) - { - Buffer buffer(*iter); - buffer.data(); - } - } - - template - static Buffer first(Iterator begin, Iterator end) - { - Iterator iter = begin; - for (; iter != end; ++iter) - { - Buffer buffer(*iter); - if (buffer.size() != 0) - return buffer; - } - return Buffer(); - } - - native_buffer_type buffers_[max_buffers]; - std::size_t count_; - std::size_t total_buffer_size_; -}; - -template -class buffer_sequence_adapter - : buffer_sequence_adapter_base -{ -public: - explicit buffer_sequence_adapter( - const asio::mutable_buffer& buffer_sequence) - { - init_native_buffer(buffer_, Buffer(buffer_sequence)); - total_buffer_size_ = buffer_sequence.size(); - } - - native_buffer_type* buffers() - { - return &buffer_; - } - - std::size_t count() const - { - return 1; - } - - std::size_t total_size() const - { - return total_buffer_size_; - } - - bool all_empty() const - { - return total_buffer_size_ == 0; - } - - static bool all_empty(const asio::mutable_buffer& buffer_sequence) - { - return buffer_sequence.size() == 0; - } - - static void validate(const asio::mutable_buffer& buffer_sequence) - { - buffer_sequence.data(); - } - - static Buffer first(const asio::mutable_buffer& buffer_sequence) - { - return Buffer(buffer_sequence); - } - -private: - native_buffer_type buffer_; - std::size_t total_buffer_size_; -}; - -template -class buffer_sequence_adapter - : buffer_sequence_adapter_base -{ -public: - explicit buffer_sequence_adapter( - const asio::const_buffer& buffer_sequence) - { - init_native_buffer(buffer_, Buffer(buffer_sequence)); - total_buffer_size_ = buffer_sequence.size(); - } - - native_buffer_type* buffers() - { - return &buffer_; - } - - std::size_t count() const - { - return 1; - } - - std::size_t total_size() const - { - return total_buffer_size_; - } - - bool all_empty() const - { - return total_buffer_size_ == 0; - } - - static bool all_empty(const asio::const_buffer& buffer_sequence) - { - return buffer_sequence.size() == 0; - } - - static void validate(const asio::const_buffer& buffer_sequence) - { - buffer_sequence.data(); - } - - static Buffer first(const asio::const_buffer& buffer_sequence) - { - return Buffer(buffer_sequence); - } - -private: - native_buffer_type buffer_; - std::size_t total_buffer_size_; -}; - -#if !defined(ASIO_NO_DEPRECATED) - -template -class buffer_sequence_adapter - : buffer_sequence_adapter_base -{ -public: - explicit buffer_sequence_adapter( - const asio::mutable_buffers_1& buffer_sequence) - { - init_native_buffer(buffer_, Buffer(buffer_sequence)); - total_buffer_size_ = buffer_sequence.size(); - } - - native_buffer_type* buffers() - { - return &buffer_; - } - - std::size_t count() const - { - return 1; - } - - std::size_t total_size() const - { - return total_buffer_size_; - } - - bool all_empty() const - { - return total_buffer_size_ == 0; - } - - static bool all_empty(const asio::mutable_buffers_1& buffer_sequence) - { - return buffer_sequence.size() == 0; - } - - static void validate(const asio::mutable_buffers_1& buffer_sequence) - { - buffer_sequence.data(); - } - - static Buffer first(const asio::mutable_buffers_1& buffer_sequence) - { - return Buffer(buffer_sequence); - } - -private: - native_buffer_type buffer_; - std::size_t total_buffer_size_; -}; - -template -class buffer_sequence_adapter - : buffer_sequence_adapter_base -{ -public: - explicit buffer_sequence_adapter( - const asio::const_buffers_1& buffer_sequence) - { - init_native_buffer(buffer_, Buffer(buffer_sequence)); - total_buffer_size_ = buffer_sequence.size(); - } - - native_buffer_type* buffers() - { - return &buffer_; - } - - std::size_t count() const - { - return 1; - } - - std::size_t total_size() const - { - return total_buffer_size_; - } - - bool all_empty() const - { - return total_buffer_size_ == 0; - } - - static bool all_empty(const asio::const_buffers_1& buffer_sequence) - { - return buffer_sequence.size() == 0; - } - - static void validate(const asio::const_buffers_1& buffer_sequence) - { - buffer_sequence.data(); - } - - static Buffer first(const asio::const_buffers_1& buffer_sequence) - { - return Buffer(buffer_sequence); - } - -private: - native_buffer_type buffer_; - std::size_t total_buffer_size_; -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -class buffer_sequence_adapter > - : buffer_sequence_adapter_base -{ -public: - explicit buffer_sequence_adapter( - const boost::array& buffer_sequence) - { - init_native_buffer(buffers_[0], Buffer(buffer_sequence[0])); - init_native_buffer(buffers_[1], Buffer(buffer_sequence[1])); - total_buffer_size_ = buffer_sequence[0].size() + buffer_sequence[1].size(); - } - - native_buffer_type* buffers() - { - return buffers_; - } - - std::size_t count() const - { - return 2; - } - - std::size_t total_size() const - { - return total_buffer_size_; - } - - bool all_empty() const - { - return total_buffer_size_ == 0; - } - - static bool all_empty(const boost::array& buffer_sequence) - { - return buffer_sequence[0].size() == 0 && buffer_sequence[1].size() == 0; - } - - static void validate(const boost::array& buffer_sequence) - { - buffer_sequence[0].data(); - buffer_sequence[1].data(); - } - - static Buffer first(const boost::array& buffer_sequence) - { - return Buffer(buffer_sequence[0].size() != 0 - ? buffer_sequence[0] : buffer_sequence[1]); - } - -private: - native_buffer_type buffers_[2]; - std::size_t total_buffer_size_; -}; - -#if defined(ASIO_HAS_STD_ARRAY) - -template -class buffer_sequence_adapter > - : buffer_sequence_adapter_base -{ -public: - explicit buffer_sequence_adapter( - const std::array& buffer_sequence) - { - init_native_buffer(buffers_[0], Buffer(buffer_sequence[0])); - init_native_buffer(buffers_[1], Buffer(buffer_sequence[1])); - total_buffer_size_ = buffer_sequence[0].size() + buffer_sequence[1].size(); - } - - native_buffer_type* buffers() - { - return buffers_; - } - - std::size_t count() const - { - return 2; - } - - std::size_t total_size() const - { - return total_buffer_size_; - } - - bool all_empty() const - { - return total_buffer_size_ == 0; - } - - static bool all_empty(const std::array& buffer_sequence) - { - return buffer_sequence[0].size() == 0 && buffer_sequence[1].size() == 0; - } - - static void validate(const std::array& buffer_sequence) - { - buffer_sequence[0].data(); - buffer_sequence[1].data(); - } - - static Buffer first(const std::array& buffer_sequence) - { - return Buffer(buffer_sequence[0].size() != 0 - ? buffer_sequence[0] : buffer_sequence[1]); - } - -private: - native_buffer_type buffers_[2]; - std::size_t total_buffer_size_; -}; - -#endif // defined(ASIO_HAS_STD_ARRAY) - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/buffer_sequence_adapter.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_BUFFER_SEQUENCE_ADAPTER_HPP diff --git a/scout_sdk/asio/asio/detail/buffered_stream_storage.hpp b/scout_sdk/asio/asio/detail/buffered_stream_storage.hpp deleted file mode 100644 index c5eb081..0000000 --- a/scout_sdk/asio/asio/detail/buffered_stream_storage.hpp +++ /dev/null @@ -1,126 +0,0 @@ -// -// detail/buffered_stream_storage.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_BUFFERED_STREAM_STORAGE_HPP -#define ASIO_DETAIL_BUFFERED_STREAM_STORAGE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/buffer.hpp" -#include "asio/detail/assert.hpp" -#include -#include -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class buffered_stream_storage -{ -public: - // The type of the bytes stored in the buffer. - typedef unsigned char byte_type; - - // The type used for offsets into the buffer. - typedef std::size_t size_type; - - // Constructor. - explicit buffered_stream_storage(std::size_t buffer_capacity) - : begin_offset_(0), - end_offset_(0), - buffer_(buffer_capacity) - { - } - - /// Clear the buffer. - void clear() - { - begin_offset_ = 0; - end_offset_ = 0; - } - - // Return a pointer to the beginning of the unread data. - mutable_buffer data() - { - return asio::buffer(buffer_) + begin_offset_; - } - - // Return a pointer to the beginning of the unread data. - const_buffer data() const - { - return asio::buffer(buffer_) + begin_offset_; - } - - // Is there no unread data in the buffer. - bool empty() const - { - return begin_offset_ == end_offset_; - } - - // Return the amount of unread data the is in the buffer. - size_type size() const - { - return end_offset_ - begin_offset_; - } - - // Resize the buffer to the specified length. - void resize(size_type length) - { - ASIO_ASSERT(length <= capacity()); - if (begin_offset_ + length <= capacity()) - { - end_offset_ = begin_offset_ + length; - } - else - { - using namespace std; // For memmove. - memmove(&buffer_[0], &buffer_[0] + begin_offset_, size()); - end_offset_ = length; - begin_offset_ = 0; - } - } - - // Return the maximum size for data in the buffer. - size_type capacity() const - { - return buffer_.size(); - } - - // Consume multiple bytes from the beginning of the buffer. - void consume(size_type count) - { - ASIO_ASSERT(begin_offset_ + count <= end_offset_); - begin_offset_ += count; - if (empty()) - clear(); - } - -private: - // The offset to the beginning of the unread data. - size_type begin_offset_; - - // The offset to the end of the unread data. - size_type end_offset_; - - // The data in the buffer. - std::vector buffer_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_BUFFERED_STREAM_STORAGE_HPP diff --git a/scout_sdk/asio/asio/detail/call_stack.hpp b/scout_sdk/asio/asio/detail/call_stack.hpp deleted file mode 100644 index 5725a10..0000000 --- a/scout_sdk/asio/asio/detail/call_stack.hpp +++ /dev/null @@ -1,125 +0,0 @@ -// -// detail/call_stack.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CALL_STACK_HPP -#define ASIO_DETAIL_CALL_STACK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/tss_ptr.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Helper class to determine whether or not the current thread is inside an -// invocation of io_context::run() for a specified io_context object. -template -class call_stack -{ -public: - // Context class automatically pushes the key/value pair on to the stack. - class context - : private noncopyable - { - public: - // Push the key on to the stack. - explicit context(Key* k) - : key_(k), - next_(call_stack::top_) - { - value_ = reinterpret_cast(this); - call_stack::top_ = this; - } - - // Push the key/value pair on to the stack. - context(Key* k, Value& v) - : key_(k), - value_(&v), - next_(call_stack::top_) - { - call_stack::top_ = this; - } - - // Pop the key/value pair from the stack. - ~context() - { - call_stack::top_ = next_; - } - - // Find the next context with the same key. - Value* next_by_key() const - { - context* elem = next_; - while (elem) - { - if (elem->key_ == key_) - return elem->value_; - elem = elem->next_; - } - return 0; - } - - private: - friend class call_stack; - - // The key associated with the context. - Key* key_; - - // The value associated with the context. - Value* value_; - - // The next element in the stack. - context* next_; - }; - - friend class context; - - // Determine whether the specified owner is on the stack. Returns address of - // key if present, 0 otherwise. - static Value* contains(Key* k) - { - context* elem = top_; - while (elem) - { - if (elem->key_ == k) - return elem->value_; - elem = elem->next_; - } - return 0; - } - - // Obtain the value at the top of the stack. - static Value* top() - { - context* elem = top_; - return elem ? elem->value_ : 0; - } - -private: - // The top of the stack of calls for the current thread. - static tss_ptr top_; -}; - -template -tss_ptr::context> -call_stack::top_; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_CALL_STACK_HPP diff --git a/scout_sdk/asio/asio/detail/chrono.hpp b/scout_sdk/asio/asio/detail/chrono.hpp deleted file mode 100644 index 8f56bee..0000000 --- a/scout_sdk/asio/asio/detail/chrono.hpp +++ /dev/null @@ -1,66 +0,0 @@ -// -// detail/chrono.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CHRONO_HPP -#define ASIO_DETAIL_CHRONO_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_CHRONO) -# include -#elif defined(ASIO_HAS_BOOST_CHRONO) -# include -#endif // defined(ASIO_HAS_BOOST_CHRONO) - -namespace asio { -namespace chrono { - -#if defined(ASIO_HAS_STD_CHRONO) -using std::chrono::duration; -using std::chrono::time_point; -using std::chrono::duration_cast; -using std::chrono::nanoseconds; -using std::chrono::microseconds; -using std::chrono::milliseconds; -using std::chrono::seconds; -using std::chrono::minutes; -using std::chrono::hours; -using std::chrono::time_point_cast; -#if defined(ASIO_HAS_STD_CHRONO_MONOTONIC_CLOCK) -typedef std::chrono::monotonic_clock steady_clock; -#else // defined(ASIO_HAS_STD_CHRONO_MONOTONIC_CLOCK) -using std::chrono::steady_clock; -#endif // defined(ASIO_HAS_STD_CHRONO_MONOTONIC_CLOCK) -using std::chrono::system_clock; -using std::chrono::high_resolution_clock; -#elif defined(ASIO_HAS_BOOST_CHRONO) -using boost::chrono::duration; -using boost::chrono::time_point; -using boost::chrono::duration_cast; -using boost::chrono::nanoseconds; -using boost::chrono::microseconds; -using boost::chrono::milliseconds; -using boost::chrono::seconds; -using boost::chrono::minutes; -using boost::chrono::hours; -using boost::chrono::time_point_cast; -using boost::chrono::system_clock; -using boost::chrono::steady_clock; -using boost::chrono::high_resolution_clock; -#endif // defined(ASIO_HAS_BOOST_CHRONO) - -} // namespace chrono -} // namespace asio - -#endif // ASIO_DETAIL_CHRONO_HPP diff --git a/scout_sdk/asio/asio/detail/chrono_time_traits.hpp b/scout_sdk/asio/asio/detail/chrono_time_traits.hpp deleted file mode 100644 index d1528f7..0000000 --- a/scout_sdk/asio/asio/detail/chrono_time_traits.hpp +++ /dev/null @@ -1,190 +0,0 @@ -// -// detail/chrono_time_traits.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CHRONO_TIME_TRAITS_HPP -#define ASIO_DETAIL_CHRONO_TIME_TRAITS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/cstdint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Helper template to compute the greatest common divisor. -template -struct gcd { enum { value = gcd::value }; }; - -template -struct gcd { enum { value = v1 }; }; - -// Adapts std::chrono clocks for use with a deadline timer. -template -struct chrono_time_traits -{ - // The clock type. - typedef Clock clock_type; - - // The duration type of the clock. - typedef typename clock_type::duration duration_type; - - // The time point type of the clock. - typedef typename clock_type::time_point time_type; - - // The period of the clock. - typedef typename duration_type::period period_type; - - // Get the current time. - static time_type now() - { - return clock_type::now(); - } - - // Add a duration to a time. - static time_type add(const time_type& t, const duration_type& d) - { - const time_type epoch; - if (t >= epoch) - { - if ((time_type::max)() - t < d) - return (time_type::max)(); - } - else // t < epoch - { - if (-(t - (time_type::min)()) > d) - return (time_type::min)(); - } - - return t + d; - } - - // Subtract one time from another. - static duration_type subtract(const time_type& t1, const time_type& t2) - { - const time_type epoch; - if (t1 >= epoch) - { - if (t2 >= epoch) - { - return t1 - t2; - } - else if (t2 == (time_type::min)()) - { - return (duration_type::max)(); - } - else if ((time_type::max)() - t1 < epoch - t2) - { - return (duration_type::max)(); - } - else - { - return t1 - t2; - } - } - else // t1 < epoch - { - if (t2 < epoch) - { - return t1 - t2; - } - else if (t1 == (time_type::min)()) - { - return (duration_type::min)(); - } - else if ((time_type::max)() - t2 < epoch - t1) - { - return (duration_type::min)(); - } - else - { - return -(t2 - t1); - } - } - } - - // Test whether one time is less than another. - static bool less_than(const time_type& t1, const time_type& t2) - { - return t1 < t2; - } - - // Implement just enough of the posix_time::time_duration interface to supply - // what the timer_queue requires. - class posix_time_duration - { - public: - explicit posix_time_duration(const duration_type& d) - : d_(d) - { - } - - int64_t ticks() const - { - return d_.count(); - } - - int64_t total_seconds() const - { - return duration_cast<1, 1>(); - } - - int64_t total_milliseconds() const - { - return duration_cast<1, 1000>(); - } - - int64_t total_microseconds() const - { - return duration_cast<1, 1000000>(); - } - - private: - template - int64_t duration_cast() const - { - const int64_t num1 = period_type::num / gcd::value; - const int64_t num2 = Num / gcd::value; - - const int64_t den1 = period_type::den / gcd::value; - const int64_t den2 = Den / gcd::value; - - const int64_t num = num1 * den2; - const int64_t den = num2 * den1; - - if (num == 1 && den == 1) - return ticks(); - else if (num != 1 && den == 1) - return ticks() * num; - else if (num == 1 && period_type::den != 1) - return ticks() / den; - else - return ticks() * num / den; - } - - duration_type d_; - }; - - // Convert to POSIX duration type. - static posix_time_duration to_posix_duration(const duration_type& d) - { - return posix_time_duration(WaitTraits::to_wait_duration(d)); - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_CHRONO_TIME_TRAITS_HPP diff --git a/scout_sdk/asio/asio/detail/completion_handler.hpp b/scout_sdk/asio/asio/detail/completion_handler.hpp deleted file mode 100644 index 58a2e6d..0000000 --- a/scout_sdk/asio/asio/detail/completion_handler.hpp +++ /dev/null @@ -1,83 +0,0 @@ -// -// detail/completion_handler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_COMPLETION_HANDLER_HPP -#define ASIO_DETAIL_COMPLETION_HANDLER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_work.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class completion_handler : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(completion_handler); - - completion_handler(Handler& h) - : operation(&completion_handler::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(h)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - completion_handler* h(static_cast(base)); - ptr p = { asio::detail::addressof(h->handler_), h, h }; - handler_work w(h->handler_); - - ASIO_HANDLER_COMPLETION((*h)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - Handler handler(ASIO_MOVE_CAST(Handler)(h->handler_)); - p.h = asio::detail::addressof(handler); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN(()); - w.complete(handler, handler); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_COMPLETION_HANDLER_HPP diff --git a/scout_sdk/asio/asio/detail/concurrency_hint.hpp b/scout_sdk/asio/asio/detail/concurrency_hint.hpp deleted file mode 100644 index 229124d..0000000 --- a/scout_sdk/asio/asio/detail/concurrency_hint.hpp +++ /dev/null @@ -1,94 +0,0 @@ -// -// detail/concurrency_hint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CONCURRENCY_HINT_HPP -#define ASIO_DETAIL_CONCURRENCY_HINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/noncopyable.hpp" - -// The concurrency hint ID and mask are used to identify when a "well-known" -// concurrency hint value has been passed to the io_context. -#define ASIO_CONCURRENCY_HINT_ID 0xA5100000u -#define ASIO_CONCURRENCY_HINT_ID_MASK 0xFFFF0000u - -// If set, this bit indicates that the scheduler should perform locking. -#define ASIO_CONCURRENCY_HINT_LOCKING_SCHEDULER 0x1u - -// If set, this bit indicates that the reactor should perform locking when -// managing descriptor registrations. -#define ASIO_CONCURRENCY_HINT_LOCKING_REACTOR_REGISTRATION 0x2u - -// If set, this bit indicates that the reactor should perform locking for I/O. -#define ASIO_CONCURRENCY_HINT_LOCKING_REACTOR_IO 0x4u - -// Helper macro to determine if we have a special concurrency hint. -#define ASIO_CONCURRENCY_HINT_IS_SPECIAL(hint) \ - ((static_cast(hint) \ - & ASIO_CONCURRENCY_HINT_ID_MASK) \ - == ASIO_CONCURRENCY_HINT_ID) - -// Helper macro to determine if locking is enabled for a given facility. -#define ASIO_CONCURRENCY_HINT_IS_LOCKING(facility, hint) \ - (((static_cast(hint) \ - & (ASIO_CONCURRENCY_HINT_ID_MASK \ - | ASIO_CONCURRENCY_HINT_LOCKING_ ## facility)) \ - ^ ASIO_CONCURRENCY_HINT_ID) != 0) - -// This special concurrency hint disables locking in both the scheduler and -// reactor I/O. This hint has the following restrictions: -// -// - Care must be taken to ensure that all operations on the io_context and any -// of its associated I/O objects (such as sockets and timers) occur in only -// one thread at a time. -// -// - Asynchronous resolve operations fail with operation_not_supported. -// -// - If a signal_set is used with the io_context, signal_set objects cannot be -// used with any other io_context in the program. -#define ASIO_CONCURRENCY_HINT_UNSAFE \ - static_cast(ASIO_CONCURRENCY_HINT_ID) - -// This special concurrency hint disables locking in the reactor I/O. This hint -// has the following restrictions: -// -// - Care must be taken to ensure that run functions on the io_context, and all -// operations on the io_context's associated I/O objects (such as sockets and -// timers), occur in only one thread at a time. -#define ASIO_CONCURRENCY_HINT_UNSAFE_IO \ - static_cast(ASIO_CONCURRENCY_HINT_ID \ - | ASIO_CONCURRENCY_HINT_LOCKING_SCHEDULER \ - | ASIO_CONCURRENCY_HINT_LOCKING_REACTOR_REGISTRATION) - -// The special concurrency hint provides full thread safety. -#define ASIO_CONCURRENCY_HINT_SAFE \ - static_cast(ASIO_CONCURRENCY_HINT_ID \ - | ASIO_CONCURRENCY_HINT_LOCKING_SCHEDULER \ - | ASIO_CONCURRENCY_HINT_LOCKING_REACTOR_REGISTRATION \ - | ASIO_CONCURRENCY_HINT_LOCKING_REACTOR_IO) - -// This #define may be overridden at compile time to specify a program-wide -// default concurrency hint, used by the zero-argument io_context constructor. -#if !defined(ASIO_CONCURRENCY_HINT_DEFAULT) -# define ASIO_CONCURRENCY_HINT_DEFAULT -1 -#endif // !defined(ASIO_CONCURRENCY_HINT_DEFAULT) - -// This #define may be overridden at compile time to specify a program-wide -// concurrency hint, used by the one-argument io_context constructor when -// passed a value of 1. -#if !defined(ASIO_CONCURRENCY_HINT_1) -# define ASIO_CONCURRENCY_HINT_1 1 -#endif // !defined(ASIO_CONCURRENCY_HINT_DEFAULT) - -#endif // ASIO_DETAIL_CONCURRENCY_HINT_HPP diff --git a/scout_sdk/asio/asio/detail/conditionally_enabled_event.hpp b/scout_sdk/asio/asio/detail/conditionally_enabled_event.hpp deleted file mode 100644 index 0fda401..0000000 --- a/scout_sdk/asio/asio/detail/conditionally_enabled_event.hpp +++ /dev/null @@ -1,112 +0,0 @@ -// -// detail/conditionally_enabled_event.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CONDITIONALLY_ENABLED_EVENT_HPP -#define ASIO_DETAIL_CONDITIONALLY_ENABLED_EVENT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/conditionally_enabled_mutex.hpp" -#include "asio/detail/event.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/null_event.hpp" -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Mutex adapter used to conditionally enable or disable locking. -class conditionally_enabled_event - : private noncopyable -{ -public: - // Constructor. - conditionally_enabled_event() - { - } - - // Destructor. - ~conditionally_enabled_event() - { - } - - // Signal the event. (Retained for backward compatibility.) - void signal(conditionally_enabled_mutex::scoped_lock& lock) - { - if (lock.mutex_.enabled_) - event_.signal(lock); - } - - // Signal all waiters. - void signal_all(conditionally_enabled_mutex::scoped_lock& lock) - { - if (lock.mutex_.enabled_) - event_.signal_all(lock); - } - - // Unlock the mutex and signal one waiter. - void unlock_and_signal_one( - conditionally_enabled_mutex::scoped_lock& lock) - { - if (lock.mutex_.enabled_) - event_.unlock_and_signal_one(lock); - } - - // If there's a waiter, unlock the mutex and signal it. - bool maybe_unlock_and_signal_one( - conditionally_enabled_mutex::scoped_lock& lock) - { - if (lock.mutex_.enabled_) - return event_.maybe_unlock_and_signal_one(lock); - else - return false; - } - - // Reset the event. - void clear(conditionally_enabled_mutex::scoped_lock& lock) - { - if (lock.mutex_.enabled_) - event_.clear(lock); - } - - // Wait for the event to become signalled. - void wait(conditionally_enabled_mutex::scoped_lock& lock) - { - if (lock.mutex_.enabled_) - event_.wait(lock); - else - null_event().wait(lock); - } - - // Timed wait for the event to become signalled. - bool wait_for_usec( - conditionally_enabled_mutex::scoped_lock& lock, long usec) - { - if (lock.mutex_.enabled_) - return event_.wait_for_usec(lock, usec); - else - return null_event().wait_for_usec(lock, usec); - } - -private: - asio::detail::event event_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_CONDITIONALLY_ENABLED_EVENT_HPP diff --git a/scout_sdk/asio/asio/detail/conditionally_enabled_mutex.hpp b/scout_sdk/asio/asio/detail/conditionally_enabled_mutex.hpp deleted file mode 100644 index 2872db9..0000000 --- a/scout_sdk/asio/asio/detail/conditionally_enabled_mutex.hpp +++ /dev/null @@ -1,149 +0,0 @@ -// -// detail/conditionally_enabled_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CONDITIONALLY_ENABLED_MUTEX_HPP -#define ASIO_DETAIL_CONDITIONALLY_ENABLED_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Mutex adapter used to conditionally enable or disable locking. -class conditionally_enabled_mutex - : private noncopyable -{ -public: - // Helper class to lock and unlock a mutex automatically. - class scoped_lock - : private noncopyable - { - public: - // Tag type used to distinguish constructors. - enum adopt_lock_t { adopt_lock }; - - // Constructor adopts a lock that is already held. - scoped_lock(conditionally_enabled_mutex& m, adopt_lock_t) - : mutex_(m), - locked_(m.enabled_) - { - } - - // Constructor acquires the lock. - explicit scoped_lock(conditionally_enabled_mutex& m) - : mutex_(m) - { - if (m.enabled_) - { - mutex_.mutex_.lock(); - locked_ = true; - } - else - locked_ = false; - } - - // Destructor releases the lock. - ~scoped_lock() - { - if (locked_) - mutex_.mutex_.unlock(); - } - - // Explicitly acquire the lock. - void lock() - { - if (mutex_.enabled_ && !locked_) - { - mutex_.mutex_.lock(); - locked_ = true; - } - } - - // Explicitly release the lock. - void unlock() - { - if (locked_) - { - mutex_.unlock(); - locked_ = false; - } - } - - // Test whether the lock is held. - bool locked() const - { - return locked_; - } - - // Get the underlying mutex. - asio::detail::mutex& mutex() - { - return mutex_.mutex_; - } - - private: - friend class conditionally_enabled_event; - conditionally_enabled_mutex& mutex_; - bool locked_; - }; - - // Constructor. - explicit conditionally_enabled_mutex(bool enabled) - : enabled_(enabled) - { - } - - // Destructor. - ~conditionally_enabled_mutex() - { - } - - // Determine whether locking is enabled. - bool enabled() const - { - return enabled_; - } - - // Lock the mutex. - void lock() - { - if (enabled_) - mutex_.lock(); - } - - // Unlock the mutex. - void unlock() - { - if (enabled_) - mutex_.unlock(); - } - -private: - friend class scoped_lock; - friend class conditionally_enabled_event; - asio::detail::mutex mutex_; - const bool enabled_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_CONDITIONALLY_ENABLED_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/config.hpp b/scout_sdk/asio/asio/detail/config.hpp deleted file mode 100644 index cde334e..0000000 --- a/scout_sdk/asio/asio/detail/config.hpp +++ /dev/null @@ -1,1437 +0,0 @@ -// -// detail/config.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CONFIG_HPP -#define ASIO_DETAIL_CONFIG_HPP - -#if defined(ASIO_STANDALONE) -# define ASIO_DISABLE_BOOST_ARRAY 1 -# define ASIO_DISABLE_BOOST_ASSERT 1 -# define ASIO_DISABLE_BOOST_BIND 1 -# define ASIO_DISABLE_BOOST_CHRONO 1 -# define ASIO_DISABLE_BOOST_DATE_TIME 1 -# define ASIO_DISABLE_BOOST_LIMITS 1 -# define ASIO_DISABLE_BOOST_REGEX 1 -# define ASIO_DISABLE_BOOST_STATIC_CONSTANT 1 -# define ASIO_DISABLE_BOOST_THROW_EXCEPTION 1 -# define ASIO_DISABLE_BOOST_WORKAROUND 1 -#else // defined(ASIO_STANDALONE) -# include -# include -# define ASIO_HAS_BOOST_CONFIG 1 -#endif // defined(ASIO_STANDALONE) - -// Default to a header-only implementation. The user must specifically request -// separate compilation by defining either ASIO_SEPARATE_COMPILATION or -// ASIO_DYN_LINK (as a DLL/shared library implies separate compilation). -#if !defined(ASIO_HEADER_ONLY) -# if !defined(ASIO_SEPARATE_COMPILATION) -# if !defined(ASIO_DYN_LINK) -# define ASIO_HEADER_ONLY 1 -# endif // !defined(ASIO_DYN_LINK) -# endif // !defined(ASIO_SEPARATE_COMPILATION) -#endif // !defined(ASIO_HEADER_ONLY) - -#if defined(ASIO_HEADER_ONLY) -# define ASIO_DECL inline -#else // defined(ASIO_HEADER_ONLY) -# if defined(_MSC_VER) || defined(__BORLANDC__) || defined(__CODEGEARC__) -// We need to import/export our code only if the user has specifically asked -// for it by defining ASIO_DYN_LINK. -# if defined(ASIO_DYN_LINK) -// Export if this is our own source, otherwise import. -# if defined(ASIO_SOURCE) -# define ASIO_DECL __declspec(dllexport) -# else // defined(ASIO_SOURCE) -# define ASIO_DECL __declspec(dllimport) -# endif // defined(ASIO_SOURCE) -# endif // defined(ASIO_DYN_LINK) -# endif // defined(_MSC_VER) || defined(__BORLANDC__) || defined(__CODEGEARC__) -#endif // defined(ASIO_HEADER_ONLY) - -// If ASIO_DECL isn't defined yet define it now. -#if !defined(ASIO_DECL) -# define ASIO_DECL -#endif // !defined(ASIO_DECL) - -// Microsoft Visual C++ detection. -#if !defined(ASIO_MSVC) -# if defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_MSVC) -# define ASIO_MSVC BOOST_MSVC -# elif defined(_MSC_VER) && (defined(__INTELLISENSE__) \ - || (!defined(__MWERKS__) && !defined(__EDG_VERSION__))) -# define ASIO_MSVC _MSC_VER -# endif // defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_MSVC) -#endif // !defined(ASIO_MSVC) -#if defined(ASIO_MSVC) -# include // Needed for _HAS_CXX17. -#endif // defined(ASIO_MSVC) - -// Clang / libc++ detection. -#if defined(__clang__) -# if (__cplusplus >= 201103) -# if __has_include(<__config>) -# include <__config> -# if defined(_LIBCPP_VERSION) -# define ASIO_HAS_CLANG_LIBCXX 1 -# endif // defined(_LIBCPP_VERSION) -# endif // __has_include(<__config>) -# endif // (__cplusplus >= 201103) -#endif // defined(__clang__) - -// Android platform detection. -#if defined(__ANDROID__) -# include -#endif // defined(__ANDROID__) - -// Support move construction and assignment on compilers known to allow it. -#if !defined(ASIO_HAS_MOVE) -# if !defined(ASIO_DISABLE_MOVE) -# if defined(__clang__) -# if __has_feature(__cxx_rvalue_references__) -# define ASIO_HAS_MOVE 1 -# endif // __has_feature(__cxx_rvalue_references__) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_MOVE 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_MOVE 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_MOVE) -#endif // !defined(ASIO_HAS_MOVE) - -// If ASIO_MOVE_CAST isn't defined, and move support is available, define -// ASIO_MOVE_ARG and ASIO_MOVE_CAST to take advantage of rvalue -// references and perfect forwarding. -#if defined(ASIO_HAS_MOVE) && !defined(ASIO_MOVE_CAST) -# define ASIO_MOVE_ARG(type) type&& -# define ASIO_MOVE_ARG2(type1, type2) type1, type2&& -# define ASIO_MOVE_CAST(type) static_cast -# define ASIO_MOVE_CAST2(type1, type2) static_cast -#endif // defined(ASIO_HAS_MOVE) && !defined(ASIO_MOVE_CAST) - -// If ASIO_MOVE_CAST still isn't defined, default to a C++03-compatible -// implementation. Note that older g++ and MSVC versions don't like it when you -// pass a non-member function through a const reference, so for most compilers -// we'll play it safe and stick with the old approach of passing the handler by -// value. -#if !defined(ASIO_MOVE_CAST) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 1)) || (__GNUC__ > 4) -# define ASIO_MOVE_ARG(type) const type& -# else // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 1)) || (__GNUC__ > 4) -# define ASIO_MOVE_ARG(type) type -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 1)) || (__GNUC__ > 4) -# elif defined(ASIO_MSVC) -# if (_MSC_VER >= 1400) -# define ASIO_MOVE_ARG(type) const type& -# else // (_MSC_VER >= 1400) -# define ASIO_MOVE_ARG(type) type -# endif // (_MSC_VER >= 1400) -# else -# define ASIO_MOVE_ARG(type) type -# endif -# define ASIO_MOVE_CAST(type) static_cast -# define ASIO_MOVE_CAST2(type1, type2) static_cast -#endif // !defined(ASIO_MOVE_CAST) - -// Support variadic templates on compilers known to allow it. -#if !defined(ASIO_HAS_VARIADIC_TEMPLATES) -# if !defined(ASIO_DISABLE_VARIADIC_TEMPLATES) -# if defined(__clang__) -# if __has_feature(__cxx_variadic_templates__) -# define ASIO_HAS_VARIADIC_TEMPLATES 1 -# endif // __has_feature(__cxx_variadic_templates__) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_VARIADIC_TEMPLATES 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1900) -# define ASIO_HAS_VARIADIC_TEMPLATES 1 -# endif // (_MSC_VER >= 1900) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_VARIADIC_TEMPLATES) -#endif // !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -// Support deleted functions on compilers known to allow it. -#if !defined(ASIO_DELETED) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_DELETED = delete -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(__clang__) -# if __has_feature(__cxx_deleted_functions__) -# define ASIO_DELETED = delete -# endif // __has_feature(__cxx_deleted_functions__) -# endif // defined(__clang__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1900) -# define ASIO_DELETED = delete -# endif // (_MSC_VER >= 1900) -# endif // defined(ASIO_MSVC) -# if !defined(ASIO_DELETED) -# define ASIO_DELETED -# endif // !defined(ASIO_DELETED) -#endif // !defined(ASIO_DELETED) - -// Support constexpr on compilers known to allow it. -#if !defined(ASIO_HAS_CONSTEXPR) -# if !defined(ASIO_DISABLE_CONSTEXPR) -# if defined(__clang__) -# if __has_feature(__cxx_constexpr__) -# define ASIO_HAS_CONSTEXPR 1 -# endif // __has_feature(__cxx_constexr__) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_CONSTEXPR 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1900) -# define ASIO_HAS_CONSTEXPR 1 -# endif // (_MSC_VER >= 1900) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_CONSTEXPR) -#endif // !defined(ASIO_HAS_CONSTEXPR) -#if !defined(ASIO_CONSTEXPR) -# if defined(ASIO_HAS_CONSTEXPR) -# define ASIO_CONSTEXPR constexpr -# else // defined(ASIO_HAS_CONSTEXPR) -# define ASIO_CONSTEXPR -# endif // defined(ASIO_HAS_CONSTEXPR) -#endif // !defined(ASIO_CONSTEXPR) - -// Support noexcept on compilers known to allow it. -#if !defined(ASIO_NOEXCEPT) -# if !defined(ASIO_DISABLE_NOEXCEPT) -# if (BOOST_VERSION >= 105300) -# define ASIO_NOEXCEPT BOOST_NOEXCEPT -# define ASIO_NOEXCEPT_OR_NOTHROW BOOST_NOEXCEPT_OR_NOTHROW -# elif defined(__clang__) -# if __has_feature(__cxx_noexcept__) -# define ASIO_NOEXCEPT noexcept(true) -# define ASIO_NOEXCEPT_OR_NOTHROW noexcept(true) -# endif // __has_feature(__cxx_noexcept__) -# elif defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_NOEXCEPT noexcept(true) -# define ASIO_NOEXCEPT_OR_NOTHROW noexcept(true) -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# elif defined(ASIO_MSVC) -# if (_MSC_VER >= 1900) -# define ASIO_NOEXCEPT noexcept(true) -# define ASIO_NOEXCEPT_OR_NOTHROW noexcept(true) -# endif // (_MSC_VER >= 1900) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_NOEXCEPT) -# if !defined(ASIO_NOEXCEPT) -# define ASIO_NOEXCEPT -# endif // !defined(ASIO_NOEXCEPT) -# if !defined(ASIO_NOEXCEPT_OR_NOTHROW) -# define ASIO_NOEXCEPT_OR_NOTHROW throw() -# endif // !defined(ASIO_NOEXCEPT_OR_NOTHROW) -#endif // !defined(ASIO_NOEXCEPT) - -// Support automatic type deduction on compilers known to support it. -#if !defined(ASIO_HAS_DECLTYPE) -# if !defined(ASIO_DISABLE_DECLTYPE) -# if defined(__clang__) -# if __has_feature(__cxx_decltype__) -# define ASIO_HAS_DECLTYPE 1 -# endif // __has_feature(__cxx_decltype__) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_DECLTYPE 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_DECLTYPE 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_DECLTYPE) -#endif // !defined(ASIO_HAS_DECLTYPE) - -// Support alias templates on compilers known to allow it. -#if !defined(ASIO_HAS_ALIAS_TEMPLATES) -# if !defined(ASIO_DISABLE_ALIAS_TEMPLATES) -# if defined(__clang__) -# if __has_feature(__cxx_alias_templates__) -# define ASIO_HAS_ALIAS_TEMPLATES 1 -# endif // __has_feature(__cxx_alias_templates__) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_ALIAS_TEMPLATES 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1900) -# define ASIO_HAS_ALIAS_TEMPLATES 1 -# endif // (_MSC_VER >= 1900) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_ALIAS_TEMPLATES) -#endif // !defined(ASIO_HAS_ALIAS_TEMPLATES) - -// Standard library support for system errors. -#if !defined(ASIO_HAS_STD_SYSTEM_ERROR) -# if !defined(ASIO_DISABLE_STD_SYSTEM_ERROR) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_SYSTEM_ERROR 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_SYSTEM_ERROR 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_SYSTEM_ERROR 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_SYSTEM_ERROR 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_SYSTEM_ERROR) -#endif // !defined(ASIO_HAS_STD_SYSTEM_ERROR) - -// Compliant C++11 compilers put noexcept specifiers on error_category members. -#if !defined(ASIO_ERROR_CATEGORY_NOEXCEPT) -# if (BOOST_VERSION >= 105300) -# define ASIO_ERROR_CATEGORY_NOEXCEPT BOOST_NOEXCEPT -# elif defined(__clang__) -# if __has_feature(__cxx_noexcept__) -# define ASIO_ERROR_CATEGORY_NOEXCEPT noexcept(true) -# endif // __has_feature(__cxx_noexcept__) -# elif defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_ERROR_CATEGORY_NOEXCEPT noexcept(true) -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# elif defined(ASIO_MSVC) -# if (_MSC_VER >= 1900) -# define ASIO_ERROR_CATEGORY_NOEXCEPT noexcept(true) -# endif // (_MSC_VER >= 1900) -# endif // defined(ASIO_MSVC) -# if !defined(ASIO_ERROR_CATEGORY_NOEXCEPT) -# define ASIO_ERROR_CATEGORY_NOEXCEPT -# endif // !defined(ASIO_ERROR_CATEGORY_NOEXCEPT) -#endif // !defined(ASIO_ERROR_CATEGORY_NOEXCEPT) - -// Standard library support for arrays. -#if !defined(ASIO_HAS_STD_ARRAY) -# if !defined(ASIO_DISABLE_STD_ARRAY) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_ARRAY 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_ARRAY 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_ARRAY 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1600) -# define ASIO_HAS_STD_ARRAY 1 -# endif // (_MSC_VER >= 1600) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_ARRAY) -#endif // !defined(ASIO_HAS_STD_ARRAY) - -// Standard library support for shared_ptr and weak_ptr. -#if !defined(ASIO_HAS_STD_SHARED_PTR) -# if !defined(ASIO_DISABLE_STD_SHARED_PTR) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_SHARED_PTR 1 -# elif (__cplusplus >= 201103) -# define ASIO_HAS_STD_SHARED_PTR 1 -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_SHARED_PTR 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1600) -# define ASIO_HAS_STD_SHARED_PTR 1 -# endif // (_MSC_VER >= 1600) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_SHARED_PTR) -#endif // !defined(ASIO_HAS_STD_SHARED_PTR) - -// Standard library support for allocator_arg_t. -#if !defined(ASIO_HAS_STD_ALLOCATOR_ARG) -# if !defined(ASIO_DISABLE_STD_ALLOCATOR_ARG) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_ALLOCATOR_ARG 1 -# elif (__cplusplus >= 201103) -# define ASIO_HAS_STD_ALLOCATOR_ARG 1 -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_ALLOCATOR_ARG 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1600) -# define ASIO_HAS_STD_ALLOCATOR_ARG 1 -# endif // (_MSC_VER >= 1600) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_ALLOCATOR_ARG) -#endif // !defined(ASIO_HAS_STD_ALLOCATOR_ARG) - -// Standard library support for atomic operations. -#if !defined(ASIO_HAS_STD_ATOMIC) -# if !defined(ASIO_DISABLE_STD_ATOMIC) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_ATOMIC 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_ATOMIC 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_ATOMIC 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_ATOMIC 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_ATOMIC) -#endif // !defined(ASIO_HAS_STD_ATOMIC) - -// Standard library support for chrono. Some standard libraries (such as the -// libstdc++ shipped with gcc 4.6) provide monotonic_clock as per early C++0x -// drafts, rather than the eventually standardised name of steady_clock. -#if !defined(ASIO_HAS_STD_CHRONO) -# if !defined(ASIO_DISABLE_STD_CHRONO) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_CHRONO 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_CHRONO 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_CHRONO 1 -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ == 6)) -# define ASIO_HAS_STD_CHRONO_MONOTONIC_CLOCK 1 -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ == 6)) -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_CHRONO 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_CHRONO) -#endif // !defined(ASIO_HAS_STD_CHRONO) - -// Boost support for chrono. -#if !defined(ASIO_HAS_BOOST_CHRONO) -# if !defined(ASIO_DISABLE_BOOST_CHRONO) -# if (BOOST_VERSION >= 104700) -# define ASIO_HAS_BOOST_CHRONO 1 -# endif // (BOOST_VERSION >= 104700) -# endif // !defined(ASIO_DISABLE_BOOST_CHRONO) -#endif // !defined(ASIO_HAS_BOOST_CHRONO) - -// Some form of chrono library is available. -#if !defined(ASIO_HAS_CHRONO) -# if defined(ASIO_HAS_STD_CHRONO) \ - || defined(ASIO_HAS_BOOST_CHRONO) -# define ASIO_HAS_CHRONO 1 -# endif // defined(ASIO_HAS_STD_CHRONO) - // || defined(ASIO_HAS_BOOST_CHRONO) -#endif // !defined(ASIO_HAS_CHRONO) - -// Boost support for the DateTime library. -#if !defined(ASIO_HAS_BOOST_DATE_TIME) -# if !defined(ASIO_DISABLE_BOOST_DATE_TIME) -# define ASIO_HAS_BOOST_DATE_TIME 1 -# endif // !defined(ASIO_DISABLE_BOOST_DATE_TIME) -#endif // !defined(ASIO_HAS_BOOST_DATE_TIME) - -// Standard library support for addressof. -#if !defined(ASIO_HAS_STD_ADDRESSOF) -# if !defined(ASIO_DISABLE_STD_ADDRESSOF) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_ADDRESSOF 1 -# elif (__cplusplus >= 201103) -# define ASIO_HAS_STD_ADDRESSOF 1 -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_ADDRESSOF 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_ADDRESSOF 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_ADDRESSOF) -#endif // !defined(ASIO_HAS_STD_ADDRESSOF) - -// Standard library support for the function class. -#if !defined(ASIO_HAS_STD_FUNCTION) -# if !defined(ASIO_DISABLE_STD_FUNCTION) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_FUNCTION 1 -# elif (__cplusplus >= 201103) -# define ASIO_HAS_STD_FUNCTION 1 -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_FUNCTION 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_FUNCTION 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_FUNCTION) -#endif // !defined(ASIO_HAS_STD_FUNCTION) - -// Standard library support for type traits. -#if !defined(ASIO_HAS_STD_TYPE_TRAITS) -# if !defined(ASIO_DISABLE_STD_TYPE_TRAITS) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_TYPE_TRAITS 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_TYPE_TRAITS 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_TYPE_TRAITS 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_TYPE_TRAITS 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_TYPE_TRAITS) -#endif // !defined(ASIO_HAS_STD_TYPE_TRAITS) - -// Standard library support for the nullptr_t type. -#if !defined(ASIO_HAS_NULLPTR) -# if !defined(ASIO_DISABLE_NULLPTR) -# if defined(__clang__) -# if __has_feature(__cxx_nullptr__) -# define ASIO_HAS_NULLPTR 1 -# endif // __has_feature(__cxx_rvalue_references__) -# elif defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_NULLPTR 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 6)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_NULLPTR 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_NULLPTR) -#endif // !defined(ASIO_HAS_NULLPTR) - -// Standard library support for the C++11 allocator additions. -#if !defined(ASIO_HAS_CXX11_ALLOCATORS) -# if !defined(ASIO_DISABLE_CXX11_ALLOCATORS) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_CXX11_ALLOCATORS 1 -# elif (__cplusplus >= 201103) -# define ASIO_HAS_CXX11_ALLOCATORS 1 -# endif // (__cplusplus >= 201103) -# elif defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_CXX11_ALLOCATORS 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1800) -# define ASIO_HAS_CXX11_ALLOCATORS 1 -# endif // (_MSC_VER >= 1800) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_CXX11_ALLOCATORS) -#endif // !defined(ASIO_HAS_CXX11_ALLOCATORS) - -// Standard library support for the cstdint header. -#if !defined(ASIO_HAS_CSTDINT) -# if !defined(ASIO_DISABLE_CSTDINT) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_CSTDINT 1 -# elif (__cplusplus >= 201103) -# define ASIO_HAS_CSTDINT 1 -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_CSTDINT 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_CSTDINT 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_CSTDINT) -#endif // !defined(ASIO_HAS_CSTDINT) - -// Standard library support for the thread class. -#if !defined(ASIO_HAS_STD_THREAD) -# if !defined(ASIO_DISABLE_STD_THREAD) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_THREAD 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_THREAD 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_THREAD 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_THREAD 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_THREAD) -#endif // !defined(ASIO_HAS_STD_THREAD) - -// Standard library support for the mutex and condition variable classes. -#if !defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) -# if !defined(ASIO_DISABLE_STD_MUTEX_AND_CONDVAR) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_MUTEX_AND_CONDVAR 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_MUTEX_AND_CONDVAR 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_MUTEX_AND_CONDVAR 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_MUTEX_AND_CONDVAR 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_MUTEX_AND_CONDVAR) -#endif // !defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) - -// Standard library support for the call_once function. -#if !defined(ASIO_HAS_STD_CALL_ONCE) -# if !defined(ASIO_DISABLE_STD_CALL_ONCE) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_CALL_ONCE 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_CALL_ONCE 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_CALL_ONCE 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_CALL_ONCE 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_CALL_ONCE) -#endif // !defined(ASIO_HAS_STD_CALL_ONCE) - -// Standard library support for futures. -#if !defined(ASIO_HAS_STD_FUTURE) -# if !defined(ASIO_DISABLE_STD_FUTURE) -# if defined(__clang__) -# if defined(ASIO_HAS_CLANG_LIBCXX) -# define ASIO_HAS_STD_FUTURE 1 -# elif (__cplusplus >= 201103) -# if __has_include() -# define ASIO_HAS_STD_FUTURE 1 -# endif // __has_include() -# endif // (__cplusplus >= 201103) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# if defined(_GLIBCXX_HAS_GTHREADS) -# define ASIO_HAS_STD_FUTURE 1 -# endif // defined(_GLIBCXX_HAS_GTHREADS) -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 7)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_FUTURE 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_FUTURE) -#endif // !defined(ASIO_HAS_STD_FUTURE) - -// Standard library support for std::string_view. -#if !defined(ASIO_HAS_STD_STRING_VIEW) -# if !defined(ASIO_DISABLE_STD_STRING_VIEW) -# if defined(__clang__) -# if (__cplusplus >= 201703) -# if __has_include() -# define ASIO_HAS_STD_STRING_VIEW 1 -# endif // __has_include() -# endif // (__cplusplus >= 201703) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if (__GNUC__ >= 7) -# if (__cplusplus >= 201703) -# define ASIO_HAS_STD_STRING_VIEW 1 -# endif // (__cplusplus >= 201703) -# endif // (__GNUC__ >= 7) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1910 && _HAS_CXX17) -# define ASIO_HAS_STD_STRING_VIEW -# endif // (_MSC_VER >= 1910 && _HAS_CXX17) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_STRING_VIEW) -#endif // !defined(ASIO_HAS_STD_STRING_VIEW) - -// Standard library support for std::experimental::string_view. -#if !defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) -# if !defined(ASIO_DISABLE_STD_EXPERIMENTAL_STRING_VIEW) -# if defined(__clang__) -# if (__cplusplus >= 201402) -# if __has_include() -# define ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW 1 -# endif // __has_include() -# endif // (__cplusplus >= 201402) -# endif // defined(__clang__) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 9)) || (__GNUC__ > 4) -# if (__cplusplus >= 201402) -# define ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW 1 -# endif // (__cplusplus >= 201402) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 9)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# endif // !defined(ASIO_DISABLE_STD_EXPERIMENTAL_STRING_VIEW) -#endif // !defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) - -// Standard library has a string_view that we can use. -#if !defined(ASIO_HAS_STRING_VIEW) -# if !defined(ASIO_DISABLE_STRING_VIEW) -# if defined(ASIO_HAS_STD_STRING_VIEW) -# define ASIO_HAS_STRING_VIEW 1 -# elif defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) -# define ASIO_HAS_STRING_VIEW 1 -# endif // defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) -# endif // !defined(ASIO_DISABLE_STRING_VIEW) -#endif // !defined(ASIO_HAS_STRING_VIEW) - -// Standard library support for iostream move construction and assignment. -#if !defined(ASIO_HAS_STD_IOSTREAM_MOVE) -# if !defined(ASIO_DISABLE_STD_IOSTREAM_MOVE) -# if defined(__GNUC__) -# if (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_HAS_STD_IOSTREAM_MOVE 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_STD_IOSTREAM_MOVE 1 -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_IOSTREAM_MOVE) -#endif // !defined(ASIO_HAS_STD_IOSTREAM_MOVE) - -// Standard library has invoke_result (which supersedes result_of). -#if !defined(ASIO_HAS_STD_INVOKE_RESULT) -# if !defined(ASIO_DISABLE_STD_INVOKE_RESULT) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1910 && _HAS_CXX17) -# define ASIO_HAS_STD_INVOKE_RESULT 1 -# endif // (_MSC_VER >= 1910 && _HAS_CXX17) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_STD_INVOKE_RESULT) -#endif // !defined(ASIO_HAS_STD_INVOKE_RESULT) - -// Windows App target. Windows but with a limited API. -#if !defined(ASIO_WINDOWS_APP) -# if defined(_WIN32_WINNT) && (_WIN32_WINNT >= 0x0603) -# include -# if WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_APP) \ - && !WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) -# define ASIO_WINDOWS_APP 1 -# endif // WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_APP) - // && !WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) -# endif // defined(_WIN32_WINNT) && (_WIN32_WINNT >= 0x0603) -#endif // !defined(ASIO_WINDOWS_APP) - -// Legacy WinRT target. Windows App is preferred. -#if !defined(ASIO_WINDOWS_RUNTIME) -# if !defined(ASIO_WINDOWS_APP) -# if defined(__cplusplus_winrt) -# include -# if WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_APP) \ - && !WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) -# define ASIO_WINDOWS_RUNTIME 1 -# endif // WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_APP) - // && !WINAPI_FAMILY_PARTITION(WINAPI_PARTITION_DESKTOP) -# endif // defined(__cplusplus_winrt) -# endif // !defined(ASIO_WINDOWS_APP) -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -// Windows target. Excludes WinRT but includes Windows App targets. -#if !defined(ASIO_WINDOWS) -# if !defined(ASIO_WINDOWS_RUNTIME) -# if defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_WINDOWS) -# define ASIO_WINDOWS 1 -# elif defined(WIN32) || defined(_WIN32) || defined(__WIN32__) -# define ASIO_WINDOWS 1 -# elif defined(ASIO_WINDOWS_APP) -# define ASIO_WINDOWS 1 -# endif // defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_WINDOWS) -# endif // !defined(ASIO_WINDOWS_RUNTIME) -#endif // !defined(ASIO_WINDOWS) - -// Windows: target OS version. -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if !defined(_WIN32_WINNT) && !defined(_WIN32_WINDOWS) -# if defined(_MSC_VER) || defined(__BORLANDC__) -# pragma message( \ - "Please define _WIN32_WINNT or _WIN32_WINDOWS appropriately. For example:\n"\ - "- add -D_WIN32_WINNT=0x0501 to the compiler command line; or\n"\ - "- add _WIN32_WINNT=0x0501 to your project's Preprocessor Definitions.\n"\ - "Assuming _WIN32_WINNT=0x0501 (i.e. Windows XP target).") -# else // defined(_MSC_VER) || defined(__BORLANDC__) -# warning Please define _WIN32_WINNT or _WIN32_WINDOWS appropriately. -# warning For example, add -D_WIN32_WINNT=0x0501 to the compiler command line. -# warning Assuming _WIN32_WINNT=0x0501 (i.e. Windows XP target). -# endif // defined(_MSC_VER) || defined(__BORLANDC__) -# define _WIN32_WINNT 0x0501 -# endif // !defined(_WIN32_WINNT) && !defined(_WIN32_WINDOWS) -# if defined(_MSC_VER) -# if defined(_WIN32) && !defined(WIN32) -# if !defined(_WINSOCK2API_) -# define WIN32 // Needed for correct types in winsock2.h -# else // !defined(_WINSOCK2API_) -# error Please define the macro WIN32 in your compiler options -# endif // !defined(_WINSOCK2API_) -# endif // defined(_WIN32) && !defined(WIN32) -# endif // defined(_MSC_VER) -# if defined(__BORLANDC__) -# if defined(__WIN32__) && !defined(WIN32) -# if !defined(_WINSOCK2API_) -# define WIN32 // Needed for correct types in winsock2.h -# else // !defined(_WINSOCK2API_) -# error Please define the macro WIN32 in your compiler options -# endif // !defined(_WINSOCK2API_) -# endif // defined(__WIN32__) && !defined(WIN32) -# endif // defined(__BORLANDC__) -# if defined(__CYGWIN__) -# if !defined(__USE_W32_SOCKETS) -# error You must add -D__USE_W32_SOCKETS to your compiler options. -# endif // !defined(__USE_W32_SOCKETS) -# endif // defined(__CYGWIN__) -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -// Windows: minimise header inclusion. -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if !defined(ASIO_NO_WIN32_LEAN_AND_MEAN) -# if !defined(WIN32_LEAN_AND_MEAN) -# define WIN32_LEAN_AND_MEAN -# endif // !defined(WIN32_LEAN_AND_MEAN) -# endif // !defined(ASIO_NO_WIN32_LEAN_AND_MEAN) -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -// Windows: suppress definition of "min" and "max" macros. -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if !defined(ASIO_NO_NOMINMAX) -# if !defined(NOMINMAX) -# define NOMINMAX 1 -# endif // !defined(NOMINMAX) -# endif // !defined(ASIO_NO_NOMINMAX) -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -// Windows: IO Completion Ports. -#if !defined(ASIO_HAS_IOCP) -# if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if defined(_WIN32_WINNT) && (_WIN32_WINNT >= 0x0400) -# if !defined(UNDER_CE) && !defined(ASIO_WINDOWS_APP) -# if !defined(ASIO_DISABLE_IOCP) -# define ASIO_HAS_IOCP 1 -# endif // !defined(ASIO_DISABLE_IOCP) -# endif // !defined(UNDER_CE) && !defined(ASIO_WINDOWS_APP) -# endif // defined(_WIN32_WINNT) && (_WIN32_WINNT >= 0x0400) -# endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -#endif // !defined(ASIO_HAS_IOCP) - -// On POSIX (and POSIX-like) platforms we need to include unistd.h in order to -// get access to the various platform feature macros, e.g. to be able to test -// for threads support. -#if !defined(ASIO_HAS_UNISTD_H) -# if !defined(ASIO_HAS_BOOST_CONFIG) -# if defined(unix) \ - || defined(__unix) \ - || defined(_XOPEN_SOURCE) \ - || defined(_POSIX_SOURCE) \ - || (defined(__MACH__) && defined(__APPLE__)) \ - || defined(__FreeBSD__) \ - || defined(__NetBSD__) \ - || defined(__OpenBSD__) \ - || defined(__linux__) -# define ASIO_HAS_UNISTD_H 1 -# endif -# endif // !defined(ASIO_HAS_BOOST_CONFIG) -#endif // !defined(ASIO_HAS_UNISTD_H) -#if defined(ASIO_HAS_UNISTD_H) -# include -#endif // defined(ASIO_HAS_UNISTD_H) - -// Linux: epoll, eventfd and timerfd. -#if defined(__linux__) -# include -# if !defined(ASIO_HAS_EPOLL) -# if !defined(ASIO_DISABLE_EPOLL) -# if LINUX_VERSION_CODE >= KERNEL_VERSION(2,5,45) -# define ASIO_HAS_EPOLL 1 -# endif // LINUX_VERSION_CODE >= KERNEL_VERSION(2,5,45) -# endif // !defined(ASIO_DISABLE_EPOLL) -# endif // !defined(ASIO_HAS_EPOLL) -# if !defined(ASIO_HAS_EVENTFD) -# if !defined(ASIO_DISABLE_EVENTFD) -# if LINUX_VERSION_CODE >= KERNEL_VERSION(2,6,22) -# define ASIO_HAS_EVENTFD 1 -# endif // LINUX_VERSION_CODE >= KERNEL_VERSION(2,6,22) -# endif // !defined(ASIO_DISABLE_EVENTFD) -# endif // !defined(ASIO_HAS_EVENTFD) -# if !defined(ASIO_HAS_TIMERFD) -# if defined(ASIO_HAS_EPOLL) -# if (__GLIBC__ > 2) || (__GLIBC__ == 2 && __GLIBC_MINOR__ >= 8) -# define ASIO_HAS_TIMERFD 1 -# endif // (__GLIBC__ > 2) || (__GLIBC__ == 2 && __GLIBC_MINOR__ >= 8) -# endif // defined(ASIO_HAS_EPOLL) -# endif // !defined(ASIO_HAS_TIMERFD) -#endif // defined(__linux__) - -// Mac OS X, FreeBSD, NetBSD, OpenBSD: kqueue. -#if (defined(__MACH__) && defined(__APPLE__)) \ - || defined(__FreeBSD__) \ - || defined(__NetBSD__) \ - || defined(__OpenBSD__) -# if !defined(ASIO_HAS_KQUEUE) -# if !defined(ASIO_DISABLE_KQUEUE) -# define ASIO_HAS_KQUEUE 1 -# endif // !defined(ASIO_DISABLE_KQUEUE) -# endif // !defined(ASIO_HAS_KQUEUE) -#endif // (defined(__MACH__) && defined(__APPLE__)) - // || defined(__FreeBSD__) - // || defined(__NetBSD__) - // || defined(__OpenBSD__) - -// Solaris: /dev/poll. -#if defined(__sun) -# if !defined(ASIO_HAS_DEV_POLL) -# if !defined(ASIO_DISABLE_DEV_POLL) -# define ASIO_HAS_DEV_POLL 1 -# endif // !defined(ASIO_DISABLE_DEV_POLL) -# endif // !defined(ASIO_HAS_DEV_POLL) -#endif // defined(__sun) - -// Serial ports. -#if !defined(ASIO_HAS_SERIAL_PORT) -# if defined(ASIO_HAS_IOCP) \ - || !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) -# if !defined(__SYMBIAN32__) -# if !defined(ASIO_DISABLE_SERIAL_PORT) -# define ASIO_HAS_SERIAL_PORT 1 -# endif // !defined(ASIO_DISABLE_SERIAL_PORT) -# endif // !defined(__SYMBIAN32__) -# endif // defined(ASIO_HAS_IOCP) - // || !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -#endif // !defined(ASIO_HAS_SERIAL_PORT) - -// Windows: stream handles. -#if !defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) -# if !defined(ASIO_DISABLE_WINDOWS_STREAM_HANDLE) -# if defined(ASIO_HAS_IOCP) -# define ASIO_HAS_WINDOWS_STREAM_HANDLE 1 -# endif // defined(ASIO_HAS_IOCP) -# endif // !defined(ASIO_DISABLE_WINDOWS_STREAM_HANDLE) -#endif // !defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) - -// Windows: random access handles. -#if !defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) -# if !defined(ASIO_DISABLE_WINDOWS_RANDOM_ACCESS_HANDLE) -# if defined(ASIO_HAS_IOCP) -# define ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE 1 -# endif // defined(ASIO_HAS_IOCP) -# endif // !defined(ASIO_DISABLE_WINDOWS_RANDOM_ACCESS_HANDLE) -#endif // !defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) - -// Windows: object handles. -#if !defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) -# if !defined(ASIO_DISABLE_WINDOWS_OBJECT_HANDLE) -# if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if !defined(UNDER_CE) && !defined(ASIO_WINDOWS_APP) -# define ASIO_HAS_WINDOWS_OBJECT_HANDLE 1 -# endif // !defined(UNDER_CE) && !defined(ASIO_WINDOWS_APP) -# endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# endif // !defined(ASIO_DISABLE_WINDOWS_OBJECT_HANDLE) -#endif // !defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - -// Windows: OVERLAPPED wrapper. -#if !defined(ASIO_HAS_WINDOWS_OVERLAPPED_PTR) -# if !defined(ASIO_DISABLE_WINDOWS_OVERLAPPED_PTR) -# if defined(ASIO_HAS_IOCP) -# define ASIO_HAS_WINDOWS_OVERLAPPED_PTR 1 -# endif // defined(ASIO_HAS_IOCP) -# endif // !defined(ASIO_DISABLE_WINDOWS_OVERLAPPED_PTR) -#endif // !defined(ASIO_HAS_WINDOWS_OVERLAPPED_PTR) - -// POSIX: stream-oriented file descriptors. -#if !defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) -# if !defined(ASIO_DISABLE_POSIX_STREAM_DESCRIPTOR) -# if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) -# define ASIO_HAS_POSIX_STREAM_DESCRIPTOR 1 -# endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -# endif // !defined(ASIO_DISABLE_POSIX_STREAM_DESCRIPTOR) -#endif // !defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) - -// UNIX domain sockets. -#if !defined(ASIO_HAS_LOCAL_SOCKETS) -# if !defined(ASIO_DISABLE_LOCAL_SOCKETS) -# if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) -# define ASIO_HAS_LOCAL_SOCKETS 1 -# endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -# endif // !defined(ASIO_DISABLE_LOCAL_SOCKETS) -#endif // !defined(ASIO_HAS_LOCAL_SOCKETS) - -// Can use sigaction() instead of signal(). -#if !defined(ASIO_HAS_SIGACTION) -# if !defined(ASIO_DISABLE_SIGACTION) -# if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) -# define ASIO_HAS_SIGACTION 1 -# endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -# endif // !defined(ASIO_DISABLE_SIGACTION) -#endif // !defined(ASIO_HAS_SIGACTION) - -// Can use signal(). -#if !defined(ASIO_HAS_SIGNAL) -# if !defined(ASIO_DISABLE_SIGNAL) -# if !defined(UNDER_CE) -# define ASIO_HAS_SIGNAL 1 -# endif // !defined(UNDER_CE) -# endif // !defined(ASIO_DISABLE_SIGNAL) -#endif // !defined(ASIO_HAS_SIGNAL) - -// Can use getaddrinfo() and getnameinfo(). -#if !defined(ASIO_HAS_GETADDRINFO) -# if !defined(ASIO_DISABLE_GETADDRINFO) -# if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if defined(_WIN32_WINNT) && (_WIN32_WINNT >= 0x0501) -# define ASIO_HAS_GETADDRINFO 1 -# elif defined(UNDER_CE) -# define ASIO_HAS_GETADDRINFO 1 -# endif // defined(UNDER_CE) -# elif defined(__MACH__) && defined(__APPLE__) -# if defined(__MAC_OS_X_VERSION_MIN_REQUIRED) -# if (__MAC_OS_X_VERSION_MIN_REQUIRED >= 1050) -# define ASIO_HAS_GETADDRINFO 1 -# endif // (__MAC_OS_X_VERSION_MIN_REQUIRED >= 1050) -# else // defined(__MAC_OS_X_VERSION_MIN_REQUIRED) -# define ASIO_HAS_GETADDRINFO 1 -# endif // defined(__MAC_OS_X_VERSION_MIN_REQUIRED) -# else // defined(__MACH__) && defined(__APPLE__) -# define ASIO_HAS_GETADDRINFO 1 -# endif // defined(__MACH__) && defined(__APPLE__) -# endif // !defined(ASIO_DISABLE_GETADDRINFO) -#endif // !defined(ASIO_HAS_GETADDRINFO) - -// Whether standard iostreams are disabled. -#if !defined(ASIO_NO_IOSTREAM) -# if defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_NO_IOSTREAM) -# define ASIO_NO_IOSTREAM 1 -# endif // !defined(BOOST_NO_IOSTREAM) -#endif // !defined(ASIO_NO_IOSTREAM) - -// Whether exception handling is disabled. -#if !defined(ASIO_NO_EXCEPTIONS) -# if defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_NO_EXCEPTIONS) -# define ASIO_NO_EXCEPTIONS 1 -# endif // !defined(BOOST_NO_EXCEPTIONS) -#endif // !defined(ASIO_NO_EXCEPTIONS) - -// Whether the typeid operator is supported. -#if !defined(ASIO_NO_TYPEID) -# if defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_NO_TYPEID) -# define ASIO_NO_TYPEID 1 -# endif // !defined(BOOST_NO_TYPEID) -#endif // !defined(ASIO_NO_TYPEID) - -// Threads. -#if !defined(ASIO_HAS_THREADS) -# if !defined(ASIO_DISABLE_THREADS) -# if defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_HAS_THREADS) -# define ASIO_HAS_THREADS 1 -# elif defined(__GNUC__) && !defined(__MINGW32__) \ - && !defined(linux) && !defined(__linux) && !defined(__linux__) -# define ASIO_HAS_THREADS 1 -# elif defined(_MT) || defined(__MT__) -# define ASIO_HAS_THREADS 1 -# elif defined(_REENTRANT) -# define ASIO_HAS_THREADS 1 -# elif defined(__APPLE__) -# define ASIO_HAS_THREADS 1 -# elif defined(_POSIX_THREADS) && (_POSIX_THREADS + 0 >= 0) -# define ASIO_HAS_THREADS 1 -# elif defined(_PTHREADS) -# define ASIO_HAS_THREADS 1 -# endif // defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_HAS_THREADS) -# endif // !defined(ASIO_DISABLE_THREADS) -#endif // !defined(ASIO_HAS_THREADS) - -// POSIX threads. -#if !defined(ASIO_HAS_PTHREADS) -# if defined(ASIO_HAS_THREADS) -# if defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_HAS_PTHREADS) -# define ASIO_HAS_PTHREADS 1 -# elif defined(_POSIX_THREADS) && (_POSIX_THREADS + 0 >= 0) -# define ASIO_HAS_PTHREADS 1 -# endif // defined(ASIO_HAS_BOOST_CONFIG) && defined(BOOST_HAS_PTHREADS) -# endif // defined(ASIO_HAS_THREADS) -#endif // !defined(ASIO_HAS_PTHREADS) - -// Helper to prevent macro expansion. -#define ASIO_PREVENT_MACRO_SUBSTITUTION - -// Helper to define in-class constants. -#if !defined(ASIO_STATIC_CONSTANT) -# if !defined(ASIO_DISABLE_BOOST_STATIC_CONSTANT) -# define ASIO_STATIC_CONSTANT(type, assignment) \ - BOOST_STATIC_CONSTANT(type, assignment) -# else // !defined(ASIO_DISABLE_BOOST_STATIC_CONSTANT) -# define ASIO_STATIC_CONSTANT(type, assignment) \ - static const type assignment -# endif // !defined(ASIO_DISABLE_BOOST_STATIC_CONSTANT) -#endif // !defined(ASIO_STATIC_CONSTANT) - -// Boost array library. -#if !defined(ASIO_HAS_BOOST_ARRAY) -# if !defined(ASIO_DISABLE_BOOST_ARRAY) -# define ASIO_HAS_BOOST_ARRAY 1 -# endif // !defined(ASIO_DISABLE_BOOST_ARRAY) -#endif // !defined(ASIO_HAS_BOOST_ARRAY) - -// Boost assert macro. -#if !defined(ASIO_HAS_BOOST_ASSERT) -# if !defined(ASIO_DISABLE_BOOST_ASSERT) -# define ASIO_HAS_BOOST_ASSERT 1 -# endif // !defined(ASIO_DISABLE_BOOST_ASSERT) -#endif // !defined(ASIO_HAS_BOOST_ASSERT) - -// Boost limits header. -#if !defined(ASIO_HAS_BOOST_LIMITS) -# if !defined(ASIO_DISABLE_BOOST_LIMITS) -# define ASIO_HAS_BOOST_LIMITS 1 -# endif // !defined(ASIO_DISABLE_BOOST_LIMITS) -#endif // !defined(ASIO_HAS_BOOST_LIMITS) - -// Boost throw_exception function. -#if !defined(ASIO_HAS_BOOST_THROW_EXCEPTION) -# if !defined(ASIO_DISABLE_BOOST_THROW_EXCEPTION) -# define ASIO_HAS_BOOST_THROW_EXCEPTION 1 -# endif // !defined(ASIO_DISABLE_BOOST_THROW_EXCEPTION) -#endif // !defined(ASIO_HAS_BOOST_THROW_EXCEPTION) - -// Boost regex library. -#if !defined(ASIO_HAS_BOOST_REGEX) -# if !defined(ASIO_DISABLE_BOOST_REGEX) -# define ASIO_HAS_BOOST_REGEX 1 -# endif // !defined(ASIO_DISABLE_BOOST_REGEX) -#endif // !defined(ASIO_HAS_BOOST_REGEX) - -// Boost bind function. -#if !defined(ASIO_HAS_BOOST_BIND) -# if !defined(ASIO_DISABLE_BOOST_BIND) -# define ASIO_HAS_BOOST_BIND 1 -# endif // !defined(ASIO_DISABLE_BOOST_BIND) -#endif // !defined(ASIO_HAS_BOOST_BIND) - -// Boost's BOOST_WORKAROUND macro. -#if !defined(ASIO_HAS_BOOST_WORKAROUND) -# if !defined(ASIO_DISABLE_BOOST_WORKAROUND) -# define ASIO_HAS_BOOST_WORKAROUND 1 -# endif // !defined(ASIO_DISABLE_BOOST_WORKAROUND) -#endif // !defined(ASIO_HAS_BOOST_WORKAROUND) - -// Microsoft Visual C++'s secure C runtime library. -#if !defined(ASIO_HAS_SECURE_RTL) -# if !defined(ASIO_DISABLE_SECURE_RTL) -# if defined(ASIO_MSVC) \ - && (ASIO_MSVC >= 1400) \ - && !defined(UNDER_CE) -# define ASIO_HAS_SECURE_RTL 1 -# endif // defined(ASIO_MSVC) - // && (ASIO_MSVC >= 1400) - // && !defined(UNDER_CE) -# endif // !defined(ASIO_DISABLE_SECURE_RTL) -#endif // !defined(ASIO_HAS_SECURE_RTL) - -// Handler hooking. Disabled for ancient Borland C++ and gcc compilers. -#if !defined(ASIO_HAS_HANDLER_HOOKS) -# if !defined(ASIO_DISABLE_HANDLER_HOOKS) -# if defined(__GNUC__) -# if (__GNUC__ >= 3) -# define ASIO_HAS_HANDLER_HOOKS 1 -# endif // (__GNUC__ >= 3) -# elif !defined(__BORLANDC__) -# define ASIO_HAS_HANDLER_HOOKS 1 -# endif // !defined(__BORLANDC__) -# endif // !defined(ASIO_DISABLE_HANDLER_HOOKS) -#endif // !defined(ASIO_HAS_HANDLER_HOOKS) - -// Support for the __thread keyword extension. -#if !defined(ASIO_DISABLE_THREAD_KEYWORD_EXTENSION) -# if defined(__linux__) -# if defined(__GNUC__) && (defined(__i386__) || defined(__x86_64__)) -# if ((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3) -# if !defined(__INTEL_COMPILER) && !defined(__ICL) \ - && !(defined(__clang__) && defined(__ANDROID__)) -# define ASIO_HAS_THREAD_KEYWORD_EXTENSION 1 -# define ASIO_THREAD_KEYWORD __thread -# elif defined(__INTEL_COMPILER) && (__INTEL_COMPILER >= 1100) -# define ASIO_HAS_THREAD_KEYWORD_EXTENSION 1 -# endif // defined(__INTEL_COMPILER) && (__INTEL_COMPILER >= 1100) - // && !(defined(__clang__) && defined(__ANDROID__)) -# endif // ((__GNUC__ == 3) && (__GNUC_MINOR__ >= 3)) || (__GNUC__ > 3) -# endif // defined(__GNUC__) && (defined(__i386__) || defined(__x86_64__)) -# endif // defined(__linux__) -# if defined(ASIO_MSVC) && defined(ASIO_WINDOWS_RUNTIME) -# if (_MSC_VER >= 1700) -# define ASIO_HAS_THREAD_KEYWORD_EXTENSION 1 -# define ASIO_THREAD_KEYWORD __declspec(thread) -# endif // (_MSC_VER >= 1700) -# endif // defined(ASIO_MSVC) && defined(ASIO_WINDOWS_RUNTIME) -#endif // !defined(ASIO_DISABLE_THREAD_KEYWORD_EXTENSION) -#if !defined(ASIO_THREAD_KEYWORD) -# define ASIO_THREAD_KEYWORD __thread -#endif // !defined(ASIO_THREAD_KEYWORD) - -// Support for POSIX ssize_t typedef. -#if !defined(ASIO_DISABLE_SSIZE_T) -# if defined(__linux__) \ - || (defined(__MACH__) && defined(__APPLE__)) -# define ASIO_HAS_SSIZE_T 1 -# endif // defined(__linux__) - // || (defined(__MACH__) && defined(__APPLE__)) -#endif // !defined(ASIO_DISABLE_SSIZE_T) - -// Helper macros to manage the transition away from the old services-based API. -#if defined(ASIO_ENABLE_OLD_SERVICES) -# define ASIO_SVC_TPARAM , typename Service -# define ASIO_SVC_TPARAM_DEF1(d1) , typename Service d1 -# define ASIO_SVC_TPARAM_DEF2(d1, d2) , typename Service d1, d2 -# define ASIO_SVC_TARG , Service -# define ASIO_SVC_T Service -# define ASIO_SVC_TPARAM1 , typename Service1 -# define ASIO_SVC_TPARAM1_DEF1(d1) , typename Service1 d1 -# define ASIO_SVC_TPARAM1_DEF2(d1, d2) , typename Service1 d1, d2 -# define ASIO_SVC_TARG1 , Service1 -# define ASIO_SVC_T1 Service1 -# define ASIO_SVC_ACCESS public -#else // defined(ASIO_ENABLE_OLD_SERVICES) -# define ASIO_SVC_TPARAM -# define ASIO_SVC_TPARAM_DEF1(d1) -# define ASIO_SVC_TPARAM_DEF2(d1, d2) -# define ASIO_SVC_TARG -// ASIO_SVC_T is defined at each point of use. -# define ASIO_SVC_TPARAM1 -# define ASIO_SVC_TPARAM1_DEF1(d1) -# define ASIO_SVC_TPARAM1_DEF2(d1, d2) -# define ASIO_SVC_TARG1 -// ASIO_SVC_T1 is defined at each point of use. -# define ASIO_SVC_ACCESS protected -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -// Helper macros to manage transition away from error_code return values. -#if defined(ASIO_NO_DEPRECATED) -# define ASIO_SYNC_OP_VOID void -# define ASIO_SYNC_OP_VOID_RETURN(e) return -#else // defined(ASIO_NO_DEPRECATED) -# define ASIO_SYNC_OP_VOID asio::error_code -# define ASIO_SYNC_OP_VOID_RETURN(e) return e -#endif // defined(ASIO_NO_DEPRECATED) - -// Newer gcc, clang need special treatment to suppress unused typedef warnings. -#if defined(__clang__) -# if defined(__apple_build_version__) -# if (__clang_major__ >= 7) -# define ASIO_UNUSED_TYPEDEF __attribute__((__unused__)) -# endif // (__clang_major__ >= 7) -# elif ((__clang_major__ == 3) && (__clang_minor__ >= 6)) \ - || (__clang_major__ > 3) -# define ASIO_UNUSED_TYPEDEF __attribute__((__unused__)) -# endif // ((__clang_major__ == 3) && (__clang_minor__ >= 6)) - // || (__clang_major__ > 3) -#elif defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 8)) || (__GNUC__ > 4) -# define ASIO_UNUSED_TYPEDEF __attribute__((__unused__)) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 8)) || (__GNUC__ > 4) -#endif // defined(__GNUC__) -#if !defined(ASIO_UNUSED_TYPEDEF) -# define ASIO_UNUSED_TYPEDEF -#endif // !defined(ASIO_UNUSED_TYPEDEF) - -// Some versions of gcc generate spurious warnings about unused variables. -#if defined(__GNUC__) -# if (__GNUC__ >= 4) -# define ASIO_UNUSED_VARIABLE __attribute__((__unused__)) -# endif // (__GNUC__ >= 4) -#endif // defined(__GNUC__) -#if !defined(ASIO_UNUSED_VARIABLE) -# define ASIO_UNUSED_VARIABLE -#endif // !defined(ASIO_UNUSED_VARIABLE) - -// Support co_await on compilers known to allow it. -#if !defined(ASIO_HAS_CO_AWAIT) -# if !defined(ASIO_DISABLE_CO_AWAIT) -# if defined(ASIO_MSVC) -# if (_MSC_FULL_VER >= 190023506) -# if defined(_RESUMABLE_FUNCTIONS_SUPPORTED) -# define ASIO_HAS_CO_AWAIT 1 -# endif // defined(_RESUMABLE_FUNCTIONS_SUPPORTED) -# endif // (_MSC_FULL_VER >= 190023506) -# endif // defined(ASIO_MSVC) -# endif // !defined(ASIO_DISABLE_CO_AWAIT) -# if defined(__clang__) -# if (__cpp_coroutines >= 201703) -# if __has_include() -# define ASIO_HAS_CO_AWAIT 1 -# endif // __has_include() -# endif // (__cpp_coroutines >= 201703) -# endif // defined(__clang__) -#endif // !defined(ASIO_HAS_CO_AWAIT) - -#endif // ASIO_DETAIL_CONFIG_HPP diff --git a/scout_sdk/asio/asio/detail/consuming_buffers.hpp b/scout_sdk/asio/asio/detail/consuming_buffers.hpp deleted file mode 100644 index 8127ae7..0000000 --- a/scout_sdk/asio/asio/detail/consuming_buffers.hpp +++ /dev/null @@ -1,414 +0,0 @@ -// -// detail/consuming_buffers.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CONSUMING_BUFFERS_HPP -#define ASIO_DETAIL_CONSUMING_BUFFERS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/buffer.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/limits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Helper template to determine the maximum number of prepared buffers. -template -struct prepared_buffers_max -{ - enum { value = buffer_sequence_adapter_base::max_buffers }; -}; - -template -struct prepared_buffers_max > -{ - enum { value = N }; -}; - -#if defined(ASIO_HAS_STD_ARRAY) - -template -struct prepared_buffers_max > -{ - enum { value = N }; -}; - -#endif // defined(ASIO_HAS_STD_ARRAY) - -// A buffer sequence used to represent a subsequence of the buffers. -template -struct prepared_buffers -{ - typedef Buffer value_type; - typedef const Buffer* const_iterator; - - enum { max_buffers = MaxBuffers < 16 ? MaxBuffers : 16 }; - - prepared_buffers() : count(0) {} - const_iterator begin() const { return elems; } - const_iterator end() const { return elems + count; } - - Buffer elems[max_buffers]; - std::size_t count; -}; - -// A proxy for a sub-range in a list of buffers. -template -class consuming_buffers -{ -public: - typedef prepared_buffers::value> - prepared_buffers_type; - - // Construct to represent the entire list of buffers. - explicit consuming_buffers(const Buffers& buffers) - : buffers_(buffers), - total_consumed_(0), - next_elem_(0), - next_elem_offset_(0) - { - using asio::buffer_size; - total_size_ = buffer_size(buffers); - } - - // Determine if we are at the end of the buffers. - bool empty() const - { - return total_consumed_ >= total_size_; - } - - // Get the buffer for a single transfer, with a size. - prepared_buffers_type prepare(std::size_t max_size) - { - prepared_buffers_type result; - - Buffer_Iterator next = asio::buffer_sequence_begin(buffers_); - Buffer_Iterator end = asio::buffer_sequence_end(buffers_); - - std::advance(next, next_elem_); - std::size_t elem_offset = next_elem_offset_; - while (next != end && max_size > 0 && (result.count) < result.max_buffers) - { - Buffer next_buf = Buffer(*next) + elem_offset; - result.elems[result.count] = asio::buffer(next_buf, max_size); - max_size -= result.elems[result.count].size(); - elem_offset = 0; - if (result.elems[result.count].size() > 0) - ++result.count; - ++next; - } - - return result; - } - - // Consume the specified number of bytes from the buffers. - void consume(std::size_t size) - { - total_consumed_ += size; - - Buffer_Iterator next = asio::buffer_sequence_begin(buffers_); - Buffer_Iterator end = asio::buffer_sequence_end(buffers_); - - std::advance(next, next_elem_); - while (next != end && size > 0) - { - Buffer next_buf = Buffer(*next) + next_elem_offset_; - if (size < next_buf.size()) - { - next_elem_offset_ += size; - size = 0; - } - else - { - size -= next_buf.size(); - next_elem_offset_ = 0; - ++next_elem_; - ++next; - } - } - } - - // Get the total number of bytes consumed from the buffers. - std::size_t total_consumed() const - { - return total_consumed_; - } - -private: - Buffers buffers_; - std::size_t total_size_; - std::size_t total_consumed_; - std::size_t next_elem_; - std::size_t next_elem_offset_; -}; - -// Base class of all consuming_buffers specialisations for single buffers. -template -class consuming_single_buffer -{ -public: - // Construct to represent the entire list of buffers. - template - explicit consuming_single_buffer(const Buffer1& buffer) - : buffer_(buffer), - total_consumed_(0) - { - } - - // Determine if we are at the end of the buffers. - bool empty() const - { - return total_consumed_ >= buffer_.size(); - } - - // Get the buffer for a single transfer, with a size. - Buffer prepare(std::size_t max_size) - { - return asio::buffer(buffer_ + total_consumed_, max_size); - } - - // Consume the specified number of bytes from the buffers. - void consume(std::size_t size) - { - total_consumed_ += size; - } - - // Get the total number of bytes consumed from the buffers. - std::size_t total_consumed() const - { - return total_consumed_; - } - -private: - Buffer buffer_; - std::size_t total_consumed_; -}; - -template <> -class consuming_buffers - : public consuming_single_buffer -{ -public: - explicit consuming_buffers(const mutable_buffer& buffer) - : consuming_single_buffer(buffer) - { - } -}; - -template <> -class consuming_buffers - : public consuming_single_buffer -{ -public: - explicit consuming_buffers(const mutable_buffer& buffer) - : consuming_single_buffer(buffer) - { - } -}; - -template <> -class consuming_buffers - : public consuming_single_buffer -{ -public: - explicit consuming_buffers(const const_buffer& buffer) - : consuming_single_buffer(buffer) - { - } -}; - -#if !defined(ASIO_NO_DEPRECATED) - -template <> -class consuming_buffers - : public consuming_single_buffer -{ -public: - explicit consuming_buffers(const mutable_buffers_1& buffer) - : consuming_single_buffer(buffer) - { - } -}; - -template <> -class consuming_buffers - : public consuming_single_buffer -{ -public: - explicit consuming_buffers(const mutable_buffers_1& buffer) - : consuming_single_buffer(buffer) - { - } -}; - -template <> -class consuming_buffers - : public consuming_single_buffer -{ -public: - explicit consuming_buffers(const const_buffers_1& buffer) - : consuming_single_buffer(buffer) - { - } -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -class consuming_buffers, - typename boost::array::const_iterator> -{ -public: - // Construct to represent the entire list of buffers. - explicit consuming_buffers(const boost::array& buffers) - : buffers_(buffers), - total_consumed_(0) - { - } - - // Determine if we are at the end of the buffers. - bool empty() const - { - return total_consumed_ >= - Buffer(buffers_[0]).size() + Buffer(buffers_[1]).size(); - } - - // Get the buffer for a single transfer, with a size. - boost::array prepare(std::size_t max_size) - { - boost::array result = {{ - Buffer(buffers_[0]), Buffer(buffers_[1]) }}; - std::size_t buffer0_size = result[0].size(); - result[0] = asio::buffer(result[0] + total_consumed_, max_size); - result[1] = asio::buffer( - result[1] + (total_consumed_ < buffer0_size - ? 0 : total_consumed_ - buffer0_size), - max_size - result[0].size()); - return result; - } - - // Consume the specified number of bytes from the buffers. - void consume(std::size_t size) - { - total_consumed_ += size; - } - - // Get the total number of bytes consumed from the buffers. - std::size_t total_consumed() const - { - return total_consumed_; - } - -private: - boost::array buffers_; - std::size_t total_consumed_; -}; - -#if defined(ASIO_HAS_STD_ARRAY) - -template -class consuming_buffers, - typename std::array::const_iterator> -{ -public: - // Construct to represent the entire list of buffers. - explicit consuming_buffers(const std::array& buffers) - : buffers_(buffers), - total_consumed_(0) - { - } - - // Determine if we are at the end of the buffers. - bool empty() const - { - return total_consumed_ >= - Buffer(buffers_[0]).size() + Buffer(buffers_[1]).size(); - } - - // Get the buffer for a single transfer, with a size. - std::array prepare(std::size_t max_size) - { - std::array result = {{ - Buffer(buffers_[0]), Buffer(buffers_[1]) }}; - std::size_t buffer0_size = result[0].size(); - result[0] = asio::buffer(result[0] + total_consumed_, max_size); - result[1] = asio::buffer( - result[1] + (total_consumed_ < buffer0_size - ? 0 : total_consumed_ - buffer0_size), - max_size - result[0].size()); - return result; - } - - // Consume the specified number of bytes from the buffers. - void consume(std::size_t size) - { - total_consumed_ += size; - } - - // Get the total number of bytes consumed from the buffers. - std::size_t total_consumed() const - { - return total_consumed_; - } - -private: - std::array buffers_; - std::size_t total_consumed_; -}; - -#endif // defined(ASIO_HAS_STD_ARRAY) - -// Specialisation for null_buffers to ensure that the null_buffers type is -// always passed through to the underlying read or write operation. -template -class consuming_buffers - : public asio::null_buffers -{ -public: - consuming_buffers(const null_buffers&) - { - // No-op. - } - - bool empty() - { - return false; - } - - null_buffers prepare(std::size_t) - { - return null_buffers(); - } - - void consume(std::size_t) - { - // No-op. - } - - std::size_t total_consumed() const - { - return 0; - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_CONSUMING_BUFFERS_HPP diff --git a/scout_sdk/asio/asio/detail/cstddef.hpp b/scout_sdk/asio/asio/detail/cstddef.hpp deleted file mode 100644 index 3912da4..0000000 --- a/scout_sdk/asio/asio/detail/cstddef.hpp +++ /dev/null @@ -1,31 +0,0 @@ -// -// detail/cstddef.hpp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CSTDDEF_HPP -#define ASIO_DETAIL_CSTDDEF_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include - -namespace asio { - -#if defined(ASIO_HAS_NULLPTR) -using std::nullptr_t; -#else // defined(ASIO_HAS_NULLPTR) -struct nullptr_t {}; -#endif // defined(ASIO_HAS_NULLPTR) - -} // namespace asio - -#endif // ASIO_DETAIL_CSTDDEF_HPP diff --git a/scout_sdk/asio/asio/detail/cstdint.hpp b/scout_sdk/asio/asio/detail/cstdint.hpp deleted file mode 100644 index 62342b2..0000000 --- a/scout_sdk/asio/asio/detail/cstdint.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// -// detail/cstdint.hpp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_CSTDINT_HPP -#define ASIO_DETAIL_CSTDINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_CSTDINT) -# include -#else // defined(ASIO_HAS_CSTDINT) -# include -#endif // defined(ASIO_HAS_CSTDINT) - -namespace asio { - -#if defined(ASIO_HAS_CSTDINT) -using std::int16_t; -using std::int_least16_t; -using std::uint16_t; -using std::uint_least16_t; -using std::int32_t; -using std::int_least32_t; -using std::uint32_t; -using std::uint_least32_t; -using std::int64_t; -using std::int_least64_t; -using std::uint64_t; -using std::uint_least64_t; -using std::uintmax_t; -#else // defined(ASIO_HAS_CSTDINT) -using boost::int16_t; -using boost::int_least16_t; -using boost::uint16_t; -using boost::uint_least16_t; -using boost::int32_t; -using boost::int_least32_t; -using boost::uint32_t; -using boost::uint_least32_t; -using boost::int64_t; -using boost::int_least64_t; -using boost::uint64_t; -using boost::uint_least64_t; -using boost::uintmax_t; -#endif // defined(ASIO_HAS_CSTDINT) - -} // namespace asio - -#endif // ASIO_DETAIL_CSTDINT_HPP diff --git a/scout_sdk/asio/asio/detail/date_time_fwd.hpp b/scout_sdk/asio/asio/detail/date_time_fwd.hpp deleted file mode 100644 index a159562..0000000 --- a/scout_sdk/asio/asio/detail/date_time_fwd.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// -// detail/date_time_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_DATE_TIME_FWD_HPP -#define ASIO_DETAIL_DATE_TIME_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -namespace boost { -namespace date_time { - -template -class base_time; - -} // namespace date_time -namespace posix_time { - -class ptime; - -} // namespace posix_time -} // namespace boost - -#endif // ASIO_DETAIL_DATE_TIME_FWD_HPP diff --git a/scout_sdk/asio/asio/detail/deadline_timer_service.hpp b/scout_sdk/asio/asio/detail/deadline_timer_service.hpp deleted file mode 100644 index f58a6e0..0000000 --- a/scout_sdk/asio/asio/detail/deadline_timer_service.hpp +++ /dev/null @@ -1,278 +0,0 @@ -// -// detail/deadline_timer_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_DEADLINE_TIMER_SERVICE_HPP -#define ASIO_DETAIL_DEADLINE_TIMER_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/timer_queue.hpp" -#include "asio/detail/timer_queue_ptime.hpp" -#include "asio/detail/timer_scheduler.hpp" -#include "asio/detail/wait_handler.hpp" -#include "asio/detail/wait_op.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include -# include -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class deadline_timer_service - : public service_base > -{ -public: - // The time type. - typedef typename Time_Traits::time_type time_type; - - // The duration type. - typedef typename Time_Traits::duration_type duration_type; - - // The implementation type of the timer. This type is dependent on the - // underlying implementation of the timer service. - struct implementation_type - : private asio::detail::noncopyable - { - time_type expiry; - bool might_have_pending_waits; - typename timer_queue::per_timer_data timer_data; - }; - - // Constructor. - deadline_timer_service(asio::io_context& io_context) - : service_base >(io_context), - scheduler_(asio::use_service(io_context)) - { - scheduler_.init_task(); - scheduler_.add_timer_queue(timer_queue_); - } - - // Destructor. - ~deadline_timer_service() - { - scheduler_.remove_timer_queue(timer_queue_); - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - } - - // Construct a new timer implementation. - void construct(implementation_type& impl) - { - impl.expiry = time_type(); - impl.might_have_pending_waits = false; - } - - // Destroy a timer implementation. - void destroy(implementation_type& impl) - { - asio::error_code ec; - cancel(impl, ec); - } - - // Move-construct a new serial port implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - scheduler_.move_timer(timer_queue_, impl.timer_data, other_impl.timer_data); - - impl.expiry = other_impl.expiry; - other_impl.expiry = time_type(); - - impl.might_have_pending_waits = other_impl.might_have_pending_waits; - other_impl.might_have_pending_waits = false; - } - - // Move-assign from another serial port implementation. - void move_assign(implementation_type& impl, - deadline_timer_service& other_service, - implementation_type& other_impl) - { - if (this != &other_service) - if (impl.might_have_pending_waits) - scheduler_.cancel_timer(timer_queue_, impl.timer_data); - - other_service.scheduler_.move_timer(other_service.timer_queue_, - impl.timer_data, other_impl.timer_data); - - impl.expiry = other_impl.expiry; - other_impl.expiry = time_type(); - - impl.might_have_pending_waits = other_impl.might_have_pending_waits; - other_impl.might_have_pending_waits = false; - } - - // Cancel any asynchronous wait operations associated with the timer. - std::size_t cancel(implementation_type& impl, asio::error_code& ec) - { - if (!impl.might_have_pending_waits) - { - ec = asio::error_code(); - return 0; - } - - ASIO_HANDLER_OPERATION((scheduler_.context(), - "deadline_timer", &impl, 0, "cancel")); - - std::size_t count = scheduler_.cancel_timer(timer_queue_, impl.timer_data); - impl.might_have_pending_waits = false; - ec = asio::error_code(); - return count; - } - - // Cancels one asynchronous wait operation associated with the timer. - std::size_t cancel_one(implementation_type& impl, - asio::error_code& ec) - { - if (!impl.might_have_pending_waits) - { - ec = asio::error_code(); - return 0; - } - - ASIO_HANDLER_OPERATION((scheduler_.context(), - "deadline_timer", &impl, 0, "cancel_one")); - - std::size_t count = scheduler_.cancel_timer( - timer_queue_, impl.timer_data, 1); - if (count == 0) - impl.might_have_pending_waits = false; - ec = asio::error_code(); - return count; - } - - // Get the expiry time for the timer as an absolute time. - time_type expiry(const implementation_type& impl) const - { - return impl.expiry; - } - - // Get the expiry time for the timer as an absolute time. - time_type expires_at(const implementation_type& impl) const - { - return impl.expiry; - } - - // Get the expiry time for the timer relative to now. - duration_type expires_from_now(const implementation_type& impl) const - { - return Time_Traits::subtract(this->expiry(impl), Time_Traits::now()); - } - - // Set the expiry time for the timer as an absolute time. - std::size_t expires_at(implementation_type& impl, - const time_type& expiry_time, asio::error_code& ec) - { - std::size_t count = cancel(impl, ec); - impl.expiry = expiry_time; - ec = asio::error_code(); - return count; - } - - // Set the expiry time for the timer relative to now. - std::size_t expires_after(implementation_type& impl, - const duration_type& expiry_time, asio::error_code& ec) - { - return expires_at(impl, - Time_Traits::add(Time_Traits::now(), expiry_time), ec); - } - - // Set the expiry time for the timer relative to now. - std::size_t expires_from_now(implementation_type& impl, - const duration_type& expiry_time, asio::error_code& ec) - { - return expires_at(impl, - Time_Traits::add(Time_Traits::now(), expiry_time), ec); - } - - // Perform a blocking wait on the timer. - void wait(implementation_type& impl, asio::error_code& ec) - { - time_type now = Time_Traits::now(); - ec = asio::error_code(); - while (Time_Traits::less_than(now, impl.expiry) && !ec) - { - this->do_wait(Time_Traits::to_posix_duration( - Time_Traits::subtract(impl.expiry, now)), ec); - now = Time_Traits::now(); - } - } - - // Start an asynchronous wait on the timer. - template - void async_wait(implementation_type& impl, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef wait_handler op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - impl.might_have_pending_waits = true; - - ASIO_HANDLER_CREATION((scheduler_.context(), - *p.p, "deadline_timer", &impl, 0, "async_wait")); - - scheduler_.schedule_timer(timer_queue_, impl.expiry, impl.timer_data, p.p); - p.v = p.p = 0; - } - -private: - // Helper function to wait given a duration type. The duration type should - // either be of type boost::posix_time::time_duration, or implement the - // required subset of its interface. - template - void do_wait(const Duration& timeout, asio::error_code& ec) - { -#if defined(ASIO_WINDOWS_RUNTIME) - std::this_thread::sleep_for( - std::chrono::seconds(timeout.total_seconds()) - + std::chrono::microseconds(timeout.total_microseconds())); - ec = asio::error_code(); -#else // defined(ASIO_WINDOWS_RUNTIME) - ::timeval tv; - tv.tv_sec = timeout.total_seconds(); - tv.tv_usec = timeout.total_microseconds() % 1000000; - socket_ops::select(0, 0, 0, 0, &tv, ec); -#endif // defined(ASIO_WINDOWS_RUNTIME) - } - - // The queue of timers. - timer_queue timer_queue_; - - // The object that schedules and executes timers. Usually a reactor. - timer_scheduler& scheduler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_DEADLINE_TIMER_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/dependent_type.hpp b/scout_sdk/asio/asio/detail/dependent_type.hpp deleted file mode 100644 index 85b41c8..0000000 --- a/scout_sdk/asio/asio/detail/dependent_type.hpp +++ /dev/null @@ -1,36 +0,0 @@ -// -// detail/dependent_type.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_DEPENDENT_TYPE_HPP -#define ASIO_DETAIL_DEPENDENT_TYPE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct dependent_type -{ - typedef T type; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_DEPENDENT_TYPE_HPP diff --git a/scout_sdk/asio/asio/detail/descriptor_ops.hpp b/scout_sdk/asio/asio/detail/descriptor_ops.hpp deleted file mode 100644 index 9c0560a..0000000 --- a/scout_sdk/asio/asio/detail/descriptor_ops.hpp +++ /dev/null @@ -1,121 +0,0 @@ -// -// detail/descriptor_ops.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_DESCRIPTOR_OPS_HPP -#define ASIO_DETAIL_DESCRIPTOR_OPS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - -#include -#include "asio/error.hpp" -#include "asio/error_code.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { -namespace descriptor_ops { - -// Descriptor state bits. -enum -{ - // The user wants a non-blocking descriptor. - user_set_non_blocking = 1, - - // The descriptor has been set non-blocking. - internal_non_blocking = 2, - - // Helper "state" used to determine whether the descriptor is non-blocking. - non_blocking = user_set_non_blocking | internal_non_blocking, - - // The descriptor may have been dup()-ed. - possible_dup = 4 -}; - -typedef unsigned char state_type; - -template -inline ReturnType error_wrapper(ReturnType return_value, - asio::error_code& ec) -{ - ec = asio::error_code(errno, - asio::error::get_system_category()); - return return_value; -} - -ASIO_DECL int open(const char* path, int flags, - asio::error_code& ec); - -ASIO_DECL int close(int d, state_type& state, - asio::error_code& ec); - -ASIO_DECL bool set_user_non_blocking(int d, - state_type& state, bool value, asio::error_code& ec); - -ASIO_DECL bool set_internal_non_blocking(int d, - state_type& state, bool value, asio::error_code& ec); - -typedef iovec buf; - -ASIO_DECL std::size_t sync_read(int d, state_type state, buf* bufs, - std::size_t count, bool all_empty, asio::error_code& ec); - -ASIO_DECL bool non_blocking_read(int d, buf* bufs, std::size_t count, - asio::error_code& ec, std::size_t& bytes_transferred); - -ASIO_DECL std::size_t sync_write(int d, state_type state, - const buf* bufs, std::size_t count, bool all_empty, - asio::error_code& ec); - -ASIO_DECL bool non_blocking_write(int d, - const buf* bufs, std::size_t count, - asio::error_code& ec, std::size_t& bytes_transferred); - -ASIO_DECL int ioctl(int d, state_type& state, long cmd, - ioctl_arg_type* arg, asio::error_code& ec); - -ASIO_DECL int fcntl(int d, int cmd, asio::error_code& ec); - -ASIO_DECL int fcntl(int d, int cmd, - long arg, asio::error_code& ec); - -ASIO_DECL int poll_read(int d, - state_type state, asio::error_code& ec); - -ASIO_DECL int poll_write(int d, - state_type state, asio::error_code& ec); - -ASIO_DECL int poll_error(int d, - state_type state, asio::error_code& ec); - -} // namespace descriptor_ops -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/descriptor_ops.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - -#endif // ASIO_DETAIL_DESCRIPTOR_OPS_HPP diff --git a/scout_sdk/asio/asio/detail/descriptor_read_op.hpp b/scout_sdk/asio/asio/detail/descriptor_read_op.hpp deleted file mode 100644 index 6db4bfb..0000000 --- a/scout_sdk/asio/asio/detail/descriptor_read_op.hpp +++ /dev/null @@ -1,128 +0,0 @@ -// -// detail/descriptor_read_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_DESCRIPTOR_READ_OP_HPP -#define ASIO_DETAIL_DESCRIPTOR_READ_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/descriptor_ops.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_work.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class descriptor_read_op_base : public reactor_op -{ -public: - descriptor_read_op_base(int descriptor, - const MutableBufferSequence& buffers, func_type complete_func) - : reactor_op(&descriptor_read_op_base::do_perform, complete_func), - descriptor_(descriptor), - buffers_(buffers) - { - } - - static status do_perform(reactor_op* base) - { - descriptor_read_op_base* o(static_cast(base)); - - buffer_sequence_adapter bufs(o->buffers_); - - status result = descriptor_ops::non_blocking_read(o->descriptor_, - bufs.buffers(), bufs.count(), o->ec_, o->bytes_transferred_) - ? done : not_done; - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_read", - o->ec_, o->bytes_transferred_)); - - return result; - } - -private: - int descriptor_; - MutableBufferSequence buffers_; -}; - -template -class descriptor_read_op - : public descriptor_read_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(descriptor_read_op); - - descriptor_read_op(int descriptor, - const MutableBufferSequence& buffers, Handler& handler) - : descriptor_read_op_base( - descriptor, buffers, &descriptor_read_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - descriptor_read_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#endif // ASIO_DETAIL_DESCRIPTOR_READ_OP_HPP diff --git a/scout_sdk/asio/asio/detail/descriptor_write_op.hpp b/scout_sdk/asio/asio/detail/descriptor_write_op.hpp deleted file mode 100644 index a9ec2a9..0000000 --- a/scout_sdk/asio/asio/detail/descriptor_write_op.hpp +++ /dev/null @@ -1,128 +0,0 @@ -// -// detail/descriptor_write_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_DESCRIPTOR_WRITE_OP_HPP -#define ASIO_DETAIL_DESCRIPTOR_WRITE_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/descriptor_ops.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_work.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class descriptor_write_op_base : public reactor_op -{ -public: - descriptor_write_op_base(int descriptor, - const ConstBufferSequence& buffers, func_type complete_func) - : reactor_op(&descriptor_write_op_base::do_perform, complete_func), - descriptor_(descriptor), - buffers_(buffers) - { - } - - static status do_perform(reactor_op* base) - { - descriptor_write_op_base* o(static_cast(base)); - - buffer_sequence_adapter bufs(o->buffers_); - - status result = descriptor_ops::non_blocking_write(o->descriptor_, - bufs.buffers(), bufs.count(), o->ec_, o->bytes_transferred_) - ? done : not_done; - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_write", - o->ec_, o->bytes_transferred_)); - - return result; - } - -private: - int descriptor_; - ConstBufferSequence buffers_; -}; - -template -class descriptor_write_op - : public descriptor_write_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(descriptor_write_op); - - descriptor_write_op(int descriptor, - const ConstBufferSequence& buffers, Handler& handler) - : descriptor_write_op_base( - descriptor, buffers, &descriptor_write_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - descriptor_write_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#endif // ASIO_DETAIL_DESCRIPTOR_WRITE_OP_HPP diff --git a/scout_sdk/asio/asio/detail/dev_poll_reactor.hpp b/scout_sdk/asio/asio/detail/dev_poll_reactor.hpp deleted file mode 100644 index e9e4e29..0000000 --- a/scout_sdk/asio/asio/detail/dev_poll_reactor.hpp +++ /dev/null @@ -1,218 +0,0 @@ -// -// detail/dev_poll_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_DEV_POLL_REACTOR_HPP -#define ASIO_DETAIL_DEV_POLL_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_DEV_POLL) - -#include -#include -#include -#include "asio/detail/hash_map.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/reactor_op_queue.hpp" -#include "asio/detail/select_interrupter.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/timer_queue_base.hpp" -#include "asio/detail/timer_queue_set.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class dev_poll_reactor - : public execution_context_service_base -{ -public: - enum op_types { read_op = 0, write_op = 1, - connect_op = 1, except_op = 2, max_ops = 3 }; - - // Per-descriptor data. - struct per_descriptor_data - { - }; - - // Constructor. - ASIO_DECL dev_poll_reactor(asio::execution_context& ctx); - - // Destructor. - ASIO_DECL ~dev_poll_reactor(); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Recreate internal descriptors following a fork. - ASIO_DECL void notify_fork( - asio::execution_context::fork_event fork_ev); - - // Initialise the task. - ASIO_DECL void init_task(); - - // Register a socket with the reactor. Returns 0 on success, system error - // code on failure. - ASIO_DECL int register_descriptor(socket_type, per_descriptor_data&); - - // Register a descriptor with an associated single operation. Returns 0 on - // success, system error code on failure. - ASIO_DECL int register_internal_descriptor( - int op_type, socket_type descriptor, - per_descriptor_data& descriptor_data, reactor_op* op); - - // Move descriptor registration from one descriptor_data object to another. - ASIO_DECL void move_descriptor(socket_type descriptor, - per_descriptor_data& target_descriptor_data, - per_descriptor_data& source_descriptor_data); - - // Post a reactor operation for immediate completion. - void post_immediate_completion(reactor_op* op, bool is_continuation) - { - scheduler_.post_immediate_completion(op, is_continuation); - } - - // Start a new operation. The reactor operation will be performed when the - // given descriptor is flagged as ready, or an error has occurred. - ASIO_DECL void start_op(int op_type, socket_type descriptor, - per_descriptor_data&, reactor_op* op, - bool is_continuation, bool allow_speculative); - - // Cancel all operations associated with the given descriptor. The - // handlers associated with the descriptor will be invoked with the - // operation_aborted error. - ASIO_DECL void cancel_ops(socket_type descriptor, per_descriptor_data&); - - // Cancel any operations that are running against the descriptor and remove - // its registration from the reactor. The reactor resources associated with - // the descriptor must be released by calling cleanup_descriptor_data. - ASIO_DECL void deregister_descriptor(socket_type descriptor, - per_descriptor_data&, bool closing); - - // Remove the descriptor's registration from the reactor. The reactor - // resources associated with the descriptor must be released by calling - // cleanup_descriptor_data. - ASIO_DECL void deregister_internal_descriptor( - socket_type descriptor, per_descriptor_data&); - - // Perform any post-deregistration cleanup tasks associated with the - // descriptor data. - ASIO_DECL void cleanup_descriptor_data(per_descriptor_data&); - - // Add a new timer queue to the reactor. - template - void add_timer_queue(timer_queue& queue); - - // Remove a timer queue from the reactor. - template - void remove_timer_queue(timer_queue& queue); - - // Schedule a new operation in the given timer queue to expire at the - // specified absolute time. - template - void schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op); - - // Cancel the timer operations associated with the given token. Returns the - // number of operations that have been posted or dispatched. - template - std::size_t cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled = (std::numeric_limits::max)()); - - // Move the timer operations associated with the given timer. - template - void move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source); - - // Run /dev/poll once until interrupted or events are ready to be dispatched. - ASIO_DECL void run(long usec, op_queue& ops); - - // Interrupt the select loop. - ASIO_DECL void interrupt(); - -private: - // Create the /dev/poll file descriptor. Throws an exception if the descriptor - // cannot be created. - ASIO_DECL static int do_dev_poll_create(); - - // Helper function to add a new timer queue. - ASIO_DECL void do_add_timer_queue(timer_queue_base& queue); - - // Helper function to remove a timer queue. - ASIO_DECL void do_remove_timer_queue(timer_queue_base& queue); - - // Get the timeout value for the /dev/poll DP_POLL operation. The timeout - // value is returned as a number of milliseconds. A return value of -1 - // indicates that the poll should block indefinitely. - ASIO_DECL int get_timeout(int msec); - - // Cancel all operations associated with the given descriptor. The do_cancel - // function of the handler objects will be invoked. This function does not - // acquire the dev_poll_reactor's mutex. - ASIO_DECL void cancel_ops_unlocked(socket_type descriptor, - const asio::error_code& ec); - - // Add a pending event entry for the given descriptor. - ASIO_DECL ::pollfd& add_pending_event_change(int descriptor); - - // The scheduler implementation used to post completions. - scheduler& scheduler_; - - // Mutex to protect access to internal data. - asio::detail::mutex mutex_; - - // The /dev/poll file descriptor. - int dev_poll_fd_; - - // Vector of /dev/poll events waiting to be written to the descriptor. - std::vector< ::pollfd> pending_event_changes_; - - // Hash map to associate a descriptor with a pending event change index. - hash_map pending_event_change_index_; - - // The interrupter is used to break a blocking DP_POLL operation. - select_interrupter interrupter_; - - // The queues of read, write and except operations. - reactor_op_queue op_queue_[max_ops]; - - // The timer queues. - timer_queue_set timer_queues_; - - // Whether the service has been shut down. - bool shutdown_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/dev_poll_reactor.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/dev_poll_reactor.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_DEV_POLL) - -#endif // ASIO_DETAIL_DEV_POLL_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/epoll_reactor.hpp b/scout_sdk/asio/asio/detail/epoll_reactor.hpp deleted file mode 100644 index 5f58109..0000000 --- a/scout_sdk/asio/asio/detail/epoll_reactor.hpp +++ /dev/null @@ -1,266 +0,0 @@ -// -// detail/epoll_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_EPOLL_REACTOR_HPP -#define ASIO_DETAIL_EPOLL_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_EPOLL) - -#include "asio/detail/atomic_count.hpp" -#include "asio/detail/conditionally_enabled_mutex.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/object_pool.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/select_interrupter.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/timer_queue_base.hpp" -#include "asio/detail/timer_queue_set.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/execution_context.hpp" - -#if defined(ASIO_HAS_TIMERFD) -# include -#endif // defined(ASIO_HAS_TIMERFD) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class epoll_reactor - : public execution_context_service_base -{ -private: - // The mutex type used by this reactor. - typedef conditionally_enabled_mutex mutex; - -public: - enum op_types { read_op = 0, write_op = 1, - connect_op = 1, except_op = 2, max_ops = 3 }; - - // Per-descriptor queues. - class descriptor_state : operation - { - friend class epoll_reactor; - friend class object_pool_access; - - descriptor_state* next_; - descriptor_state* prev_; - - mutex mutex_; - epoll_reactor* reactor_; - int descriptor_; - uint32_t registered_events_; - op_queue op_queue_[max_ops]; - bool try_speculative_[max_ops]; - bool shutdown_; - - ASIO_DECL descriptor_state(bool locking); - void set_ready_events(uint32_t events) { task_result_ = events; } - void add_ready_events(uint32_t events) { task_result_ |= events; } - ASIO_DECL operation* perform_io(uint32_t events); - ASIO_DECL static void do_complete( - void* owner, operation* base, - const asio::error_code& ec, std::size_t bytes_transferred); - }; - - // Per-descriptor data. - typedef descriptor_state* per_descriptor_data; - - // Constructor. - ASIO_DECL epoll_reactor(asio::execution_context& ctx); - - // Destructor. - ASIO_DECL ~epoll_reactor(); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Recreate internal descriptors following a fork. - ASIO_DECL void notify_fork( - asio::execution_context::fork_event fork_ev); - - // Initialise the task. - ASIO_DECL void init_task(); - - // Register a socket with the reactor. Returns 0 on success, system error - // code on failure. - ASIO_DECL int register_descriptor(socket_type descriptor, - per_descriptor_data& descriptor_data); - - // Register a descriptor with an associated single operation. Returns 0 on - // success, system error code on failure. - ASIO_DECL int register_internal_descriptor( - int op_type, socket_type descriptor, - per_descriptor_data& descriptor_data, reactor_op* op); - - // Move descriptor registration from one descriptor_data object to another. - ASIO_DECL void move_descriptor(socket_type descriptor, - per_descriptor_data& target_descriptor_data, - per_descriptor_data& source_descriptor_data); - - // Post a reactor operation for immediate completion. - void post_immediate_completion(reactor_op* op, bool is_continuation) - { - scheduler_.post_immediate_completion(op, is_continuation); - } - - // Start a new operation. The reactor operation will be performed when the - // given descriptor is flagged as ready, or an error has occurred. - ASIO_DECL void start_op(int op_type, socket_type descriptor, - per_descriptor_data& descriptor_data, reactor_op* op, - bool is_continuation, bool allow_speculative); - - // Cancel all operations associated with the given descriptor. The - // handlers associated with the descriptor will be invoked with the - // operation_aborted error. - ASIO_DECL void cancel_ops(socket_type descriptor, - per_descriptor_data& descriptor_data); - - // Cancel any operations that are running against the descriptor and remove - // its registration from the reactor. The reactor resources associated with - // the descriptor must be released by calling cleanup_descriptor_data. - ASIO_DECL void deregister_descriptor(socket_type descriptor, - per_descriptor_data& descriptor_data, bool closing); - - // Remove the descriptor's registration from the reactor. The reactor - // resources associated with the descriptor must be released by calling - // cleanup_descriptor_data. - ASIO_DECL void deregister_internal_descriptor( - socket_type descriptor, per_descriptor_data& descriptor_data); - - // Perform any post-deregistration cleanup tasks associated with the - // descriptor data. - ASIO_DECL void cleanup_descriptor_data( - per_descriptor_data& descriptor_data); - - // Add a new timer queue to the reactor. - template - void add_timer_queue(timer_queue& timer_queue); - - // Remove a timer queue from the reactor. - template - void remove_timer_queue(timer_queue& timer_queue); - - // Schedule a new operation in the given timer queue to expire at the - // specified absolute time. - template - void schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op); - - // Cancel the timer operations associated with the given token. Returns the - // number of operations that have been posted or dispatched. - template - std::size_t cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled = (std::numeric_limits::max)()); - - // Move the timer operations associated with the given timer. - template - void move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source); - - // Run epoll once until interrupted or events are ready to be dispatched. - ASIO_DECL void run(long usec, op_queue& ops); - - // Interrupt the select loop. - ASIO_DECL void interrupt(); - -private: - // The hint to pass to epoll_create to size its data structures. - enum { epoll_size = 20000 }; - - // Create the epoll file descriptor. Throws an exception if the descriptor - // cannot be created. - ASIO_DECL static int do_epoll_create(); - - // Create the timerfd file descriptor. Does not throw. - ASIO_DECL static int do_timerfd_create(); - - // Allocate a new descriptor state object. - ASIO_DECL descriptor_state* allocate_descriptor_state(); - - // Free an existing descriptor state object. - ASIO_DECL void free_descriptor_state(descriptor_state* s); - - // Helper function to add a new timer queue. - ASIO_DECL void do_add_timer_queue(timer_queue_base& queue); - - // Helper function to remove a timer queue. - ASIO_DECL void do_remove_timer_queue(timer_queue_base& queue); - - // Called to recalculate and update the timeout. - ASIO_DECL void update_timeout(); - - // Get the timeout value for the epoll_wait call. The timeout value is - // returned as a number of milliseconds. A return value of -1 indicates - // that epoll_wait should block indefinitely. - ASIO_DECL int get_timeout(int msec); - -#if defined(ASIO_HAS_TIMERFD) - // Get the timeout value for the timer descriptor. The return value is the - // flag argument to be used when calling timerfd_settime. - ASIO_DECL int get_timeout(itimerspec& ts); -#endif // defined(ASIO_HAS_TIMERFD) - - // The scheduler implementation used to post completions. - scheduler& scheduler_; - - // Mutex to protect access to internal data. - mutex mutex_; - - // The interrupter is used to break a blocking epoll_wait call. - select_interrupter interrupter_; - - // The epoll file descriptor. - int epoll_fd_; - - // The timer file descriptor. - int timer_fd_; - - // The timer queues. - timer_queue_set timer_queues_; - - // Whether the service has been shut down. - bool shutdown_; - - // Mutex to protect access to the registered descriptors. - mutex registered_descriptors_mutex_; - - // Keep track of all registered descriptors. - object_pool registered_descriptors_; - - // Helper class to do post-perform_io cleanup. - struct perform_io_cleanup_on_block_exit; - friend struct perform_io_cleanup_on_block_exit; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/epoll_reactor.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/epoll_reactor.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_EPOLL) - -#endif // ASIO_DETAIL_EPOLL_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/event.hpp b/scout_sdk/asio/asio/detail/event.hpp deleted file mode 100644 index da8fa77..0000000 --- a/scout_sdk/asio/asio/detail/event.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// -// detail/event.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_EVENT_HPP -#define ASIO_DETAIL_EVENT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) -# include "asio/detail/null_event.hpp" -#elif defined(ASIO_WINDOWS) -# include "asio/detail/win_event.hpp" -#elif defined(ASIO_HAS_PTHREADS) -# include "asio/detail/posix_event.hpp" -#elif defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) -# include "asio/detail/std_event.hpp" -#else -# error Only Windows, POSIX and std::condition_variable are supported! -#endif - -namespace asio { -namespace detail { - -#if !defined(ASIO_HAS_THREADS) -typedef null_event event; -#elif defined(ASIO_WINDOWS) -typedef win_event event; -#elif defined(ASIO_HAS_PTHREADS) -typedef posix_event event; -#elif defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) -typedef std_event event; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_EVENT_HPP diff --git a/scout_sdk/asio/asio/detail/eventfd_select_interrupter.hpp b/scout_sdk/asio/asio/detail/eventfd_select_interrupter.hpp deleted file mode 100644 index f6e594b..0000000 --- a/scout_sdk/asio/asio/detail/eventfd_select_interrupter.hpp +++ /dev/null @@ -1,83 +0,0 @@ -// -// detail/eventfd_select_interrupter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Roelof Naude (roelof.naude at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_EVENTFD_SELECT_INTERRUPTER_HPP -#define ASIO_DETAIL_EVENTFD_SELECT_INTERRUPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_EVENTFD) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class eventfd_select_interrupter -{ -public: - // Constructor. - ASIO_DECL eventfd_select_interrupter(); - - // Destructor. - ASIO_DECL ~eventfd_select_interrupter(); - - // Recreate the interrupter's descriptors. Used after a fork. - ASIO_DECL void recreate(); - - // Interrupt the select call. - ASIO_DECL void interrupt(); - - // Reset the select interrupt. Returns true if the call was interrupted. - ASIO_DECL bool reset(); - - // Get the read descriptor to be passed to select. - int read_descriptor() const - { - return read_descriptor_; - } - -private: - // Open the descriptors. Throws on error. - ASIO_DECL void open_descriptors(); - - // Close the descriptors. - ASIO_DECL void close_descriptors(); - - // The read end of a connection used to interrupt the select call. This file - // descriptor is passed to select such that when it is time to stop, a single - // 64bit value will be written on the other end of the connection and this - // descriptor will become readable. - int read_descriptor_; - - // The write end of a connection used to interrupt the select call. A single - // 64bit non-zero value may be written to this to wake up the select which is - // waiting for the other end to become readable. This descriptor will only - // differ from the read descriptor when a pipe is used. - int write_descriptor_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/eventfd_select_interrupter.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_EVENTFD) - -#endif // ASIO_DETAIL_EVENTFD_SELECT_INTERRUPTER_HPP diff --git a/scout_sdk/asio/asio/detail/executor_op.hpp b/scout_sdk/asio/asio/detail/executor_op.hpp deleted file mode 100644 index 2d5c7e8..0000000 --- a/scout_sdk/asio/asio/detail/executor_op.hpp +++ /dev/null @@ -1,84 +0,0 @@ -// -// detail/executor_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_EXECUTOR_OP_HPP -#define ASIO_DETAIL_EXECUTOR_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/scheduler_operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class executor_op : public Operation -{ -public: - ASIO_DEFINE_HANDLER_ALLOCATOR_PTR(executor_op); - - template - executor_op(ASIO_MOVE_ARG(H) h, const Alloc& allocator) - : Operation(&executor_op::do_complete), - handler_(ASIO_MOVE_CAST(H)(h)), - allocator_(allocator) - { - } - - static void do_complete(void* owner, Operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - executor_op* o(static_cast(base)); - Alloc allocator(o->allocator_); - ptr p = { detail::addressof(allocator), o, o }; - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - Handler handler(ASIO_MOVE_CAST(Handler)(o->handler_)); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN(()); - asio_handler_invoke_helpers::invoke(handler, handler); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; - Alloc allocator_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_EXECUTOR_OP_HPP diff --git a/scout_sdk/asio/asio/detail/fd_set_adapter.hpp b/scout_sdk/asio/asio/detail/fd_set_adapter.hpp deleted file mode 100644 index fd373da..0000000 --- a/scout_sdk/asio/asio/detail/fd_set_adapter.hpp +++ /dev/null @@ -1,39 +0,0 @@ -// -// detail/fd_set_adapter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_FD_SET_ADAPTER_HPP -#define ASIO_DETAIL_FD_SET_ADAPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/posix_fd_set_adapter.hpp" -#include "asio/detail/win_fd_set_adapter.hpp" - -namespace asio { -namespace detail { - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -typedef win_fd_set_adapter fd_set_adapter; -#else -typedef posix_fd_set_adapter fd_set_adapter; -#endif - -} // namespace detail -} // namespace asio - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_FD_SET_ADAPTER_HPP diff --git a/scout_sdk/asio/asio/detail/fenced_block.hpp b/scout_sdk/asio/asio/detail/fenced_block.hpp deleted file mode 100644 index dc34bd9..0000000 --- a/scout_sdk/asio/asio/detail/fenced_block.hpp +++ /dev/null @@ -1,80 +0,0 @@ -// -// detail/fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_FENCED_BLOCK_HPP -#define ASIO_DETAIL_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) \ - || defined(ASIO_DISABLE_FENCED_BLOCK) -# include "asio/detail/null_fenced_block.hpp" -#elif defined(ASIO_HAS_STD_ATOMIC) -# include "asio/detail/std_fenced_block.hpp" -#elif defined(__MACH__) && defined(__APPLE__) -# include "asio/detail/macos_fenced_block.hpp" -#elif defined(__sun) -# include "asio/detail/solaris_fenced_block.hpp" -#elif defined(__GNUC__) && defined(__arm__) \ - && !defined(__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4) -# include "asio/detail/gcc_arm_fenced_block.hpp" -#elif defined(__GNUC__) && (defined(__hppa) || defined(__hppa__)) -# include "asio/detail/gcc_hppa_fenced_block.hpp" -#elif defined(__GNUC__) && (defined(__i386__) || defined(__x86_64__)) -# include "asio/detail/gcc_x86_fenced_block.hpp" -#elif defined(__GNUC__) \ - && ((__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4)) \ - && !defined(__INTEL_COMPILER) && !defined(__ICL) \ - && !defined(__ICC) && !defined(__ECC) && !defined(__PATHSCALE__) -# include "asio/detail/gcc_sync_fenced_block.hpp" -#elif defined(ASIO_WINDOWS) && !defined(UNDER_CE) -# include "asio/detail/win_fenced_block.hpp" -#else -# include "asio/detail/null_fenced_block.hpp" -#endif - -namespace asio { -namespace detail { - -#if !defined(ASIO_HAS_THREADS) \ - || defined(ASIO_DISABLE_FENCED_BLOCK) -typedef null_fenced_block fenced_block; -#elif defined(ASIO_HAS_STD_ATOMIC) -typedef std_fenced_block fenced_block; -#elif defined(__MACH__) && defined(__APPLE__) -typedef macos_fenced_block fenced_block; -#elif defined(__sun) -typedef solaris_fenced_block fenced_block; -#elif defined(__GNUC__) && defined(__arm__) \ - && !defined(__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4) -typedef gcc_arm_fenced_block fenced_block; -#elif defined(__GNUC__) && (defined(__hppa) || defined(__hppa__)) -typedef gcc_hppa_fenced_block fenced_block; -#elif defined(__GNUC__) && (defined(__i386__) || defined(__x86_64__)) -typedef gcc_x86_fenced_block fenced_block; -#elif defined(__GNUC__) \ - && ((__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4)) \ - && !defined(__INTEL_COMPILER) && !defined(__ICL) \ - && !defined(__ICC) && !defined(__ECC) && !defined(__PATHSCALE__) -typedef gcc_sync_fenced_block fenced_block; -#elif defined(ASIO_WINDOWS) && !defined(UNDER_CE) -typedef win_fenced_block fenced_block; -#else -typedef null_fenced_block fenced_block; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/functional.hpp b/scout_sdk/asio/asio/detail/functional.hpp deleted file mode 100644 index a37e9e6..0000000 --- a/scout_sdk/asio/asio/detail/functional.hpp +++ /dev/null @@ -1,38 +0,0 @@ -// -// detail/functional.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_FUNCTIONAL_HPP -#define ASIO_DETAIL_FUNCTIONAL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include - -#if !defined(ASIO_HAS_STD_FUNCTION) -# include -#endif // !defined(ASIO_HAS_STD_FUNCTION) - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_STD_FUNCTION) -using std::function; -#else // defined(ASIO_HAS_STD_FUNCTION) -using boost::function; -#endif // defined(ASIO_HAS_STD_FUNCTION) - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_FUNCTIONAL_HPP diff --git a/scout_sdk/asio/asio/detail/gcc_arm_fenced_block.hpp b/scout_sdk/asio/asio/detail/gcc_arm_fenced_block.hpp deleted file mode 100644 index 7919a55..0000000 --- a/scout_sdk/asio/asio/detail/gcc_arm_fenced_block.hpp +++ /dev/null @@ -1,91 +0,0 @@ -// -// detail/gcc_arm_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_GCC_ARM_FENCED_BLOCK_HPP -#define ASIO_DETAIL_GCC_ARM_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(__GNUC__) && defined(__arm__) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class gcc_arm_fenced_block - : private noncopyable -{ -public: - enum half_t { half }; - enum full_t { full }; - - // Constructor for a half fenced block. - explicit gcc_arm_fenced_block(half_t) - { - } - - // Constructor for a full fenced block. - explicit gcc_arm_fenced_block(full_t) - { - barrier(); - } - - // Destructor. - ~gcc_arm_fenced_block() - { - barrier(); - } - -private: - static void barrier() - { -#if defined(__ARM_ARCH_4__) \ - || defined(__ARM_ARCH_4T__) \ - || defined(__ARM_ARCH_5__) \ - || defined(__ARM_ARCH_5E__) \ - || defined(__ARM_ARCH_5T__) \ - || defined(__ARM_ARCH_5TE__) \ - || defined(__ARM_ARCH_5TEJ__) \ - || defined(__ARM_ARCH_6__) \ - || defined(__ARM_ARCH_6J__) \ - || defined(__ARM_ARCH_6K__) \ - || defined(__ARM_ARCH_6Z__) \ - || defined(__ARM_ARCH_6ZK__) \ - || defined(__ARM_ARCH_6T2__) -# if defined(__thumb__) - // This is just a placeholder and almost certainly not sufficient. - __asm__ __volatile__ ("" : : : "memory"); -# else // defined(__thumb__) - int a = 0, b = 0; - __asm__ __volatile__ ("swp %0, %1, [%2]" - : "=&r"(a) : "r"(1), "r"(&b) : "memory", "cc"); -# endif // defined(__thumb__) -#else - // ARMv7 and later. - __asm__ __volatile__ ("dmb" : : : "memory"); -#endif - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(__GNUC__) && defined(__arm__) - -#endif // ASIO_DETAIL_GCC_ARM_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/gcc_hppa_fenced_block.hpp b/scout_sdk/asio/asio/detail/gcc_hppa_fenced_block.hpp deleted file mode 100644 index d3957ce..0000000 --- a/scout_sdk/asio/asio/detail/gcc_hppa_fenced_block.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// -// detail/gcc_hppa_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_GCC_HPPA_FENCED_BLOCK_HPP -#define ASIO_DETAIL_GCC_HPPA_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(__GNUC__) && (defined(__hppa) || defined(__hppa__)) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class gcc_hppa_fenced_block - : private noncopyable -{ -public: - enum half_t { half }; - enum full_t { full }; - - // Constructor for a half fenced block. - explicit gcc_hppa_fenced_block(half_t) - { - } - - // Constructor for a full fenced block. - explicit gcc_hppa_fenced_block(full_t) - { - barrier(); - } - - // Destructor. - ~gcc_hppa_fenced_block() - { - barrier(); - } - -private: - static void barrier() - { - // This is just a placeholder and almost certainly not sufficient. - __asm__ __volatile__ ("" : : : "memory"); - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(__GNUC__) && (defined(__hppa) || defined(__hppa__)) - -#endif // ASIO_DETAIL_GCC_HPPA_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/gcc_sync_fenced_block.hpp b/scout_sdk/asio/asio/detail/gcc_sync_fenced_block.hpp deleted file mode 100644 index 90d176f..0000000 --- a/scout_sdk/asio/asio/detail/gcc_sync_fenced_block.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// -// detail/gcc_sync_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_GCC_SYNC_FENCED_BLOCK_HPP -#define ASIO_DETAIL_GCC_SYNC_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(__GNUC__) \ - && ((__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4)) \ - && !defined(__INTEL_COMPILER) && !defined(__ICL) \ - && !defined(__ICC) && !defined(__ECC) && !defined(__PATHSCALE__) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class gcc_sync_fenced_block - : private noncopyable -{ -public: - enum half_or_full_t { half, full }; - - // Constructor. - explicit gcc_sync_fenced_block(half_or_full_t) - : value_(0) - { - __sync_lock_test_and_set(&value_, 1); - } - - // Destructor. - ~gcc_sync_fenced_block() - { - __sync_lock_release(&value_); - } - -private: - int value_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(__GNUC__) - // && ((__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4)) - // && !defined(__INTEL_COMPILER) && !defined(__ICL) - // && !defined(__ICC) && !defined(__ECC) && !defined(__PATHSCALE__) - -#endif // ASIO_DETAIL_GCC_SYNC_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/gcc_x86_fenced_block.hpp b/scout_sdk/asio/asio/detail/gcc_x86_fenced_block.hpp deleted file mode 100644 index 1366def..0000000 --- a/scout_sdk/asio/asio/detail/gcc_x86_fenced_block.hpp +++ /dev/null @@ -1,99 +0,0 @@ -// -// detail/gcc_x86_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_GCC_X86_FENCED_BLOCK_HPP -#define ASIO_DETAIL_GCC_X86_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(__GNUC__) && (defined(__i386__) || defined(__x86_64__)) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class gcc_x86_fenced_block - : private noncopyable -{ -public: - enum half_t { half }; - enum full_t { full }; - - // Constructor for a half fenced block. - explicit gcc_x86_fenced_block(half_t) - { - } - - // Constructor for a full fenced block. - explicit gcc_x86_fenced_block(full_t) - { - lbarrier(); - } - - // Destructor. - ~gcc_x86_fenced_block() - { - sbarrier(); - } - -private: - static int barrier() - { - int r = 0, m = 1; - __asm__ __volatile__ ( - "xchgl %0, %1" : - "=r"(r), "=m"(m) : - "0"(1), "m"(m) : - "memory", "cc"); - return r; - } - - static void lbarrier() - { -#if defined(__SSE2__) -# if (__GNUC__ >= 4) && !defined(__INTEL_COMPILER) && !defined(__ICL) - __builtin_ia32_lfence(); -# else // (__GNUC__ >= 4) && !defined(__INTEL_COMPILER) && !defined(__ICL) - __asm__ __volatile__ ("lfence" ::: "memory"); -# endif // (__GNUC__ >= 4) && !defined(__INTEL_COMPILER) && !defined(__ICL) -#else // defined(__SSE2__) - barrier(); -#endif // defined(__SSE2__) - } - - static void sbarrier() - { -#if defined(__SSE2__) -# if (__GNUC__ >= 4) && !defined(__INTEL_COMPILER) && !defined(__ICL) - __builtin_ia32_sfence(); -# else // (__GNUC__ >= 4) && !defined(__INTEL_COMPILER) && !defined(__ICL) - __asm__ __volatile__ ("sfence" ::: "memory"); -# endif // (__GNUC__ >= 4) && !defined(__INTEL_COMPILER) && !defined(__ICL) -#else // defined(__SSE2__) - barrier(); -#endif // defined(__SSE2__) - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(__GNUC__) && (defined(__i386__) || defined(__x86_64__)) - -#endif // ASIO_DETAIL_GCC_X86_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/global.hpp b/scout_sdk/asio/asio/detail/global.hpp deleted file mode 100644 index 085ac64..0000000 --- a/scout_sdk/asio/asio/detail/global.hpp +++ /dev/null @@ -1,52 +0,0 @@ -// -// detail/global.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_GLOBAL_HPP -#define ASIO_DETAIL_GLOBAL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) -# include "asio/detail/null_global.hpp" -#elif defined(ASIO_WINDOWS) -# include "asio/detail/win_global.hpp" -#elif defined(ASIO_HAS_PTHREADS) -# include "asio/detail/posix_global.hpp" -#elif defined(ASIO_HAS_STD_CALL_ONCE) -# include "asio/detail/std_global.hpp" -#else -# error Only Windows, POSIX and std::call_once are supported! -#endif - -namespace asio { -namespace detail { - -template -inline T& global() -{ -#if !defined(ASIO_HAS_THREADS) - return null_global(); -#elif defined(ASIO_WINDOWS) - return win_global(); -#elif defined(ASIO_HAS_PTHREADS) - return posix_global(); -#elif defined(ASIO_HAS_STD_CALL_ONCE) - return std_global(); -#endif -} - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_GLOBAL_HPP diff --git a/scout_sdk/asio/asio/detail/handler_alloc_helpers.hpp b/scout_sdk/asio/asio/detail/handler_alloc_helpers.hpp deleted file mode 100644 index afefb4d..0000000 --- a/scout_sdk/asio/asio/detail/handler_alloc_helpers.hpp +++ /dev/null @@ -1,235 +0,0 @@ -// -// detail/handler_alloc_helpers.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_HANDLER_ALLOC_HELPERS_HPP -#define ASIO_DETAIL_HANDLER_ALLOC_HELPERS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/recycling_allocator.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/handler_alloc_hook.hpp" - -#include "asio/detail/push_options.hpp" - -// Calls to asio_handler_allocate and asio_handler_deallocate must be made from -// a namespace that does not contain any overloads of these functions. The -// asio_handler_alloc_helpers namespace is defined here for that purpose. -namespace asio_handler_alloc_helpers { - -template -inline void* allocate(std::size_t s, Handler& h) -{ -#if !defined(ASIO_HAS_HANDLER_HOOKS) - return ::operator new(s); -#else - using asio::asio_handler_allocate; - return asio_handler_allocate(s, asio::detail::addressof(h)); -#endif -} - -template -inline void deallocate(void* p, std::size_t s, Handler& h) -{ -#if !defined(ASIO_HAS_HANDLER_HOOKS) - ::operator delete(p); -#else - using asio::asio_handler_deallocate; - asio_handler_deallocate(p, s, asio::detail::addressof(h)); -#endif -} - -} // namespace asio_handler_alloc_helpers - -namespace asio { -namespace detail { - -template -class hook_allocator -{ -public: - typedef T value_type; - - template - struct rebind - { - typedef hook_allocator other; - }; - - explicit hook_allocator(Handler& h) - : handler_(h) - { - } - - template - hook_allocator(const hook_allocator& a) - : handler_(a.handler_) - { - } - - T* allocate(std::size_t n) - { - return static_cast( - asio_handler_alloc_helpers::allocate(sizeof(T) * n, handler_)); - } - - void deallocate(T* p, std::size_t n) - { - asio_handler_alloc_helpers::deallocate(p, sizeof(T) * n, handler_); - } - -//private: - Handler& handler_; -}; - -template -class hook_allocator -{ -public: - typedef void value_type; - - template - struct rebind - { - typedef hook_allocator other; - }; - - explicit hook_allocator(Handler& h) - : handler_(h) - { - } - - template - hook_allocator(const hook_allocator& a) - : handler_(a.handler_) - { - } - -//private: - Handler& handler_; -}; - -template -struct get_hook_allocator -{ - typedef Allocator type; - - static type get(Handler&, const Allocator& a) - { - return a; - } -}; - -template -struct get_hook_allocator > -{ - typedef hook_allocator type; - - static type get(Handler& handler, const std::allocator&) - { - return type(handler); - } -}; - -} // namespace detail -} // namespace asio - -#define ASIO_DEFINE_HANDLER_PTR(op) \ - struct ptr \ - { \ - Handler* h; \ - op* v; \ - op* p; \ - ~ptr() \ - { \ - reset(); \ - } \ - static op* allocate(Handler& handler) \ - { \ - typedef typename ::asio::associated_allocator< \ - Handler>::type associated_allocator_type; \ - typedef typename ::asio::detail::get_hook_allocator< \ - Handler, associated_allocator_type>::type hook_allocator_type; \ - ASIO_REBIND_ALLOC(hook_allocator_type, op) a( \ - ::asio::detail::get_hook_allocator< \ - Handler, associated_allocator_type>::get( \ - handler, ::asio::get_associated_allocator(handler))); \ - return a.allocate(1); \ - } \ - void reset() \ - { \ - if (p) \ - { \ - p->~op(); \ - p = 0; \ - } \ - if (v) \ - { \ - typedef typename ::asio::associated_allocator< \ - Handler>::type associated_allocator_type; \ - typedef typename ::asio::detail::get_hook_allocator< \ - Handler, associated_allocator_type>::type hook_allocator_type; \ - ASIO_REBIND_ALLOC(hook_allocator_type, op) a( \ - ::asio::detail::get_hook_allocator< \ - Handler, associated_allocator_type>::get( \ - *h, ::asio::get_associated_allocator(*h))); \ - a.deallocate(static_cast(v), 1); \ - v = 0; \ - } \ - } \ - } \ - /**/ - -#define ASIO_DEFINE_HANDLER_ALLOCATOR_PTR(op) \ - struct ptr \ - { \ - const Alloc* a; \ - void* v; \ - op* p; \ - ~ptr() \ - { \ - reset(); \ - } \ - static op* allocate(const Alloc& a) \ - { \ - typedef typename ::asio::detail::get_recycling_allocator< \ - Alloc>::type recycling_allocator_type; \ - ASIO_REBIND_ALLOC(recycling_allocator_type, op) a1( \ - ::asio::detail::get_recycling_allocator::get(a)); \ - return a1.allocate(1); \ - } \ - void reset() \ - { \ - if (p) \ - { \ - p->~op(); \ - p = 0; \ - } \ - if (v) \ - { \ - typedef typename ::asio::detail::get_recycling_allocator< \ - Alloc>::type recycling_allocator_type; \ - ASIO_REBIND_ALLOC(recycling_allocator_type, op) a1( \ - ::asio::detail::get_recycling_allocator::get(*a)); \ - a1.deallocate(static_cast(v), 1); \ - v = 0; \ - } \ - } \ - } \ - /**/ - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_HANDLER_ALLOC_HELPERS_HPP diff --git a/scout_sdk/asio/asio/detail/handler_cont_helpers.hpp b/scout_sdk/asio/asio/detail/handler_cont_helpers.hpp deleted file mode 100644 index 110ba94..0000000 --- a/scout_sdk/asio/asio/detail/handler_cont_helpers.hpp +++ /dev/null @@ -1,45 +0,0 @@ -// -// detail/handler_cont_helpers.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_HANDLER_CONT_HELPERS_HPP -#define ASIO_DETAIL_HANDLER_CONT_HELPERS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/memory.hpp" -#include "asio/handler_continuation_hook.hpp" - -#include "asio/detail/push_options.hpp" - -// Calls to asio_handler_is_continuation must be made from a namespace that -// does not contain overloads of this function. This namespace is defined here -// for that purpose. -namespace asio_handler_cont_helpers { - -template -inline bool is_continuation(Context& context) -{ -#if !defined(ASIO_HAS_HANDLER_HOOKS) - return false; -#else - using asio::asio_handler_is_continuation; - return asio_handler_is_continuation( - asio::detail::addressof(context)); -#endif -} - -} // namespace asio_handler_cont_helpers - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_HANDLER_CONT_HELPERS_HPP diff --git a/scout_sdk/asio/asio/detail/handler_invoke_helpers.hpp b/scout_sdk/asio/asio/detail/handler_invoke_helpers.hpp deleted file mode 100644 index 4c65c4c..0000000 --- a/scout_sdk/asio/asio/detail/handler_invoke_helpers.hpp +++ /dev/null @@ -1,57 +0,0 @@ -// -// detail/handler_invoke_helpers.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_HANDLER_INVOKE_HELPERS_HPP -#define ASIO_DETAIL_HANDLER_INVOKE_HELPERS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/memory.hpp" -#include "asio/handler_invoke_hook.hpp" - -#include "asio/detail/push_options.hpp" - -// Calls to asio_handler_invoke must be made from a namespace that does not -// contain overloads of this function. The asio_handler_invoke_helpers -// namespace is defined here for that purpose. -namespace asio_handler_invoke_helpers { - -template -inline void invoke(Function& function, Context& context) -{ -#if !defined(ASIO_HAS_HANDLER_HOOKS) - Function tmp(function); - tmp(); -#else - using asio::asio_handler_invoke; - asio_handler_invoke(function, asio::detail::addressof(context)); -#endif -} - -template -inline void invoke(const Function& function, Context& context) -{ -#if !defined(ASIO_HAS_HANDLER_HOOKS) - Function tmp(function); - tmp(); -#else - using asio::asio_handler_invoke; - asio_handler_invoke(function, asio::detail::addressof(context)); -#endif -} - -} // namespace asio_handler_invoke_helpers - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_HANDLER_INVOKE_HELPERS_HPP diff --git a/scout_sdk/asio/asio/detail/handler_tracking.hpp b/scout_sdk/asio/asio/detail/handler_tracking.hpp deleted file mode 100644 index 83f820e..0000000 --- a/scout_sdk/asio/asio/detail/handler_tracking.hpp +++ /dev/null @@ -1,238 +0,0 @@ -// -// detail/handler_tracking.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_HANDLER_TRACKING_HPP -#define ASIO_DETAIL_HANDLER_TRACKING_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -namespace asio { - -class execution_context; - -} // namespace asio - -#if defined(ASIO_CUSTOM_HANDLER_TRACKING) -# include ASIO_CUSTOM_HANDLER_TRACKING -#elif defined(ASIO_ENABLE_HANDLER_TRACKING) -# include "asio/error_code.hpp" -# include "asio/detail/cstdint.hpp" -# include "asio/detail/static_mutex.hpp" -# include "asio/detail/tss_ptr.hpp" -#endif // defined(ASIO_ENABLE_HANDLER_TRACKING) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -#if defined(ASIO_CUSTOM_HANDLER_TRACKING) - -// The user-specified header must define the following macros: -// - ASIO_INHERIT_TRACKED_HANDLER -// - ASIO_ALSO_INHERIT_TRACKED_HANDLER -// - ASIO_HANDLER_TRACKING_INIT -// - ASIO_HANDLER_CREATION(args) -// - ASIO_HANDLER_COMPLETION(args) -// - ASIO_HANDLER_INVOCATION_BEGIN(args) -// - ASIO_HANDLER_INVOCATION_END -// - ASIO_HANDLER_OPERATION(args) -// - ASIO_HANDLER_REACTOR_REGISTRATION(args) -// - ASIO_HANDLER_REACTOR_DEREGISTRATION(args) -// - ASIO_HANDLER_REACTOR_READ_EVENT -// - ASIO_HANDLER_REACTOR_WRITE_EVENT -// - ASIO_HANDLER_REACTOR_ERROR_EVENT -// - ASIO_HANDLER_REACTOR_EVENTS(args) -// - ASIO_HANDLER_REACTOR_OPERATION(args) - -# if !defined(ASIO_ENABLE_HANDLER_TRACKING) -# define ASIO_ENABLE_HANDLER_TRACKING 1 -# endif /// !defined(ASIO_ENABLE_HANDLER_TRACKING) - -#elif defined(ASIO_ENABLE_HANDLER_TRACKING) - -class handler_tracking -{ -public: - class completion; - - // Base class for objects containing tracked handlers. - class tracked_handler - { - private: - // Only the handler_tracking class will have access to the id. - friend class handler_tracking; - friend class completion; - uint64_t id_; - - protected: - // Constructor initialises with no id. - tracked_handler() : id_(0) {} - - // Prevent deletion through this type. - ~tracked_handler() {} - }; - - // Initialise the tracking system. - ASIO_DECL static void init(); - - // Record the creation of a tracked handler. - ASIO_DECL static void creation( - execution_context& context, tracked_handler& h, - const char* object_type, void* object, - uintmax_t native_handle, const char* op_name); - - class completion - { - public: - // Constructor records that handler is to be invoked with no arguments. - ASIO_DECL explicit completion(const tracked_handler& h); - - // Destructor records only when an exception is thrown from the handler, or - // if the memory is being freed without the handler having been invoked. - ASIO_DECL ~completion(); - - // Records that handler is to be invoked with no arguments. - ASIO_DECL void invocation_begin(); - - // Records that handler is to be invoked with one arguments. - ASIO_DECL void invocation_begin(const asio::error_code& ec); - - // Constructor records that handler is to be invoked with two arguments. - ASIO_DECL void invocation_begin( - const asio::error_code& ec, std::size_t bytes_transferred); - - // Constructor records that handler is to be invoked with two arguments. - ASIO_DECL void invocation_begin( - const asio::error_code& ec, int signal_number); - - // Constructor records that handler is to be invoked with two arguments. - ASIO_DECL void invocation_begin( - const asio::error_code& ec, const char* arg); - - // Record that handler invocation has ended. - ASIO_DECL void invocation_end(); - - private: - friend class handler_tracking; - uint64_t id_; - bool invoked_; - completion* next_; - }; - - // Record an operation that is not directly associated with a handler. - ASIO_DECL static void operation(execution_context& context, - const char* object_type, void* object, - uintmax_t native_handle, const char* op_name); - - // Record that a descriptor has been registered with the reactor. - ASIO_DECL static void reactor_registration(execution_context& context, - uintmax_t native_handle, uintmax_t registration); - - // Record that a descriptor has been deregistered from the reactor. - ASIO_DECL static void reactor_deregistration(execution_context& context, - uintmax_t native_handle, uintmax_t registration); - - // Record a reactor-based operation that is associated with a handler. - ASIO_DECL static void reactor_events(execution_context& context, - uintmax_t registration, unsigned events); - - // Record a reactor-based operation that is associated with a handler. - ASIO_DECL static void reactor_operation( - const tracked_handler& h, const char* op_name, - const asio::error_code& ec); - - // Record a reactor-based operation that is associated with a handler. - ASIO_DECL static void reactor_operation( - const tracked_handler& h, const char* op_name, - const asio::error_code& ec, std::size_t bytes_transferred); - - // Write a line of output. - ASIO_DECL static void write_line(const char* format, ...); - -private: - struct tracking_state; - ASIO_DECL static tracking_state* get_state(); -}; - -# define ASIO_INHERIT_TRACKED_HANDLER \ - : public asio::detail::handler_tracking::tracked_handler - -# define ASIO_ALSO_INHERIT_TRACKED_HANDLER \ - , public asio::detail::handler_tracking::tracked_handler - -# define ASIO_HANDLER_TRACKING_INIT \ - asio::detail::handler_tracking::init() - -# define ASIO_HANDLER_CREATION(args) \ - asio::detail::handler_tracking::creation args - -# define ASIO_HANDLER_COMPLETION(args) \ - asio::detail::handler_tracking::completion tracked_completion args - -# define ASIO_HANDLER_INVOCATION_BEGIN(args) \ - tracked_completion.invocation_begin args - -# define ASIO_HANDLER_INVOCATION_END \ - tracked_completion.invocation_end() - -# define ASIO_HANDLER_OPERATION(args) \ - asio::detail::handler_tracking::operation args - -# define ASIO_HANDLER_REACTOR_REGISTRATION(args) \ - asio::detail::handler_tracking::reactor_registration args - -# define ASIO_HANDLER_REACTOR_DEREGISTRATION(args) \ - asio::detail::handler_tracking::reactor_deregistration args - -# define ASIO_HANDLER_REACTOR_READ_EVENT 1 -# define ASIO_HANDLER_REACTOR_WRITE_EVENT 2 -# define ASIO_HANDLER_REACTOR_ERROR_EVENT 4 - -# define ASIO_HANDLER_REACTOR_EVENTS(args) \ - asio::detail::handler_tracking::reactor_events args - -# define ASIO_HANDLER_REACTOR_OPERATION(args) \ - asio::detail::handler_tracking::reactor_operation args - -#else // defined(ASIO_ENABLE_HANDLER_TRACKING) - -# define ASIO_INHERIT_TRACKED_HANDLER -# define ASIO_ALSO_INHERIT_TRACKED_HANDLER -# define ASIO_HANDLER_TRACKING_INIT (void)0 -# define ASIO_HANDLER_CREATION(args) (void)0 -# define ASIO_HANDLER_COMPLETION(args) (void)0 -# define ASIO_HANDLER_INVOCATION_BEGIN(args) (void)0 -# define ASIO_HANDLER_INVOCATION_END (void)0 -# define ASIO_HANDLER_OPERATION(args) (void)0 -# define ASIO_HANDLER_REACTOR_REGISTRATION(args) (void)0 -# define ASIO_HANDLER_REACTOR_DEREGISTRATION(args) (void)0 -# define ASIO_HANDLER_REACTOR_READ_EVENT 0 -# define ASIO_HANDLER_REACTOR_WRITE_EVENT 0 -# define ASIO_HANDLER_REACTOR_ERROR_EVENT 0 -# define ASIO_HANDLER_REACTOR_EVENTS(args) (void)0 -# define ASIO_HANDLER_REACTOR_OPERATION(args) (void)0 - -#endif // defined(ASIO_ENABLE_HANDLER_TRACKING) - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/handler_tracking.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_HANDLER_TRACKING_HPP diff --git a/scout_sdk/asio/asio/detail/handler_type_requirements.hpp b/scout_sdk/asio/asio/detail/handler_type_requirements.hpp deleted file mode 100644 index 9181bc5..0000000 --- a/scout_sdk/asio/asio/detail/handler_type_requirements.hpp +++ /dev/null @@ -1,556 +0,0 @@ -// -// detail/handler_type_requirements.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_HANDLER_TYPE_REQUIREMENTS_HPP -#define ASIO_DETAIL_HANDLER_TYPE_REQUIREMENTS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -// Older versions of gcc have difficulty compiling the sizeof expressions where -// we test the handler type requirements. We'll disable checking of handler type -// requirements for those compilers, but otherwise enable it by default. -#if !defined(ASIO_DISABLE_HANDLER_TYPE_REQUIREMENTS) -# if !defined(__GNUC__) || (__GNUC__ >= 4) -# define ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS 1 -# endif // !defined(__GNUC__) || (__GNUC__ >= 4) -#endif // !defined(ASIO_DISABLE_HANDLER_TYPE_REQUIREMENTS) - -// With C++0x we can use a combination of enhanced SFINAE and static_assert to -// generate better template error messages. As this technique is not yet widely -// portable, we'll only enable it for tested compilers. -#if !defined(ASIO_DISABLE_HANDLER_TYPE_REQUIREMENTS_ASSERT) -# if defined(__GNUC__) -# if ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# if defined(__GXX_EXPERIMENTAL_CXX0X__) -# define ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS_ASSERT 1 -# endif // defined(__GXX_EXPERIMENTAL_CXX0X__) -# endif // ((__GNUC__ == 4) && (__GNUC_MINOR__ >= 5)) || (__GNUC__ > 4) -# endif // defined(__GNUC__) -# if defined(ASIO_MSVC) -# if (_MSC_VER >= 1600) -# define ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS_ASSERT 1 -# endif // (_MSC_VER >= 1600) -# endif // defined(ASIO_MSVC) -# if defined(__clang__) -# if __has_feature(__cxx_static_assert__) -# define ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS_ASSERT 1 -# endif // __has_feature(cxx_static_assert) -# endif // defined(__clang__) -#endif // !defined(ASIO_DISABLE_HANDLER_TYPE_REQUIREMENTS) - -#if defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS) -# include "asio/async_result.hpp" -#endif // defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS) - -namespace asio { -namespace detail { - -#if defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS) - -# if defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS_ASSERT) - -template -auto zero_arg_copyable_handler_test(Handler h, void*) - -> decltype( - sizeof(Handler(static_cast(h))), - ((h)()), - char(0)); - -template -char (&zero_arg_copyable_handler_test(Handler, ...))[2]; - -template -auto one_arg_handler_test(Handler h, Arg1* a1) - -> decltype( - sizeof(Handler(ASIO_MOVE_CAST(Handler)(h))), - ((h)(*a1)), - char(0)); - -template -char (&one_arg_handler_test(Handler h, ...))[2]; - -template -auto two_arg_handler_test(Handler h, Arg1* a1, Arg2* a2) - -> decltype( - sizeof(Handler(ASIO_MOVE_CAST(Handler)(h))), - ((h)(*a1, *a2)), - char(0)); - -template -char (&two_arg_handler_test(Handler, ...))[2]; - -template -auto two_arg_move_handler_test(Handler h, Arg1* a1, Arg2* a2) - -> decltype( - sizeof(Handler(ASIO_MOVE_CAST(Handler)(h))), - ((h)(*a1, ASIO_MOVE_CAST(Arg2)(*a2))), - char(0)); - -template -char (&two_arg_move_handler_test(Handler, ...))[2]; - -# define ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT(expr, msg) \ - static_assert(expr, msg); - -# else // defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS_ASSERT) - -# define ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT(expr, msg) - -# endif // defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS_ASSERT) - -template T& lvref(); -template T& lvref(T); -template const T& clvref(); -template const T& clvref(T); -#if defined(ASIO_HAS_MOVE) -template T rvref(); -template T rvref(T); -#else // defined(ASIO_HAS_MOVE) -template const T& rvref(); -template const T& rvref(T); -#endif // defined(ASIO_HAS_MOVE) -template char argbyv(T); - -template -struct handler_type_requirements -{ -}; - -#define ASIO_LEGACY_COMPLETION_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void()) asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::zero_arg_copyable_handler_test( \ - asio::detail::clvref< \ - asio_true_handler_type>(), 0)) == 1, \ - "CompletionHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::clvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()(), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_READ_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, std::size_t)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "ReadHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_WRITE_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, std::size_t)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "WriteHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_ACCEPT_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::one_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0))) == 1, \ - "AcceptHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_MOVE_ACCEPT_HANDLER_CHECK( \ - handler_type, handler, socket_type) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, socket_type)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_move_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "MoveAcceptHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::rvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_CONNECT_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::one_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0))) == 1, \ - "ConnectHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_RANGE_CONNECT_HANDLER_CHECK( \ - handler_type, handler, endpoint_type) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, endpoint_type)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "RangeConnectHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_ITERATOR_CONNECT_HANDLER_CHECK( \ - handler_type, handler, iter_type) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, iter_type)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "IteratorConnectHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_RESOLVE_HANDLER_CHECK( \ - handler_type, handler, range_type) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, range_type)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "ResolveHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_WAIT_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::one_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0))) == 1, \ - "WaitHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_SIGNAL_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, int)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "SignalHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_HANDSHAKE_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::one_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0))) == 1, \ - "HandshakeHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_BUFFERED_HANDSHAKE_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code, std::size_t)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::two_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0), \ - static_cast(0))) == 1, \ - "BufferedHandshakeHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref(), \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#define ASIO_SHUTDOWN_HANDLER_CHECK( \ - handler_type, handler) \ - \ - typedef ASIO_HANDLER_TYPE(handler_type, \ - void(asio::error_code)) \ - asio_true_handler_type; \ - \ - ASIO_HANDLER_TYPE_REQUIREMENTS_ASSERT( \ - sizeof(asio::detail::one_arg_handler_test( \ - asio::detail::rvref< \ - asio_true_handler_type>(), \ - static_cast(0))) == 1, \ - "ShutdownHandler type requirements not met") \ - \ - typedef asio::detail::handler_type_requirements< \ - sizeof( \ - asio::detail::argbyv( \ - asio::detail::rvref< \ - asio_true_handler_type>())) + \ - sizeof( \ - asio::detail::lvref< \ - asio_true_handler_type>()( \ - asio::detail::lvref()), \ - char(0))> ASIO_UNUSED_TYPEDEF - -#else // !defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS) - -#define ASIO_LEGACY_COMPLETION_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_READ_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_WRITE_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_ACCEPT_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_MOVE_ACCEPT_HANDLER_CHECK( \ - handler_type, handler, socket_type) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_CONNECT_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_RANGE_CONNECT_HANDLER_CHECK( \ - handler_type, handler, iter_type) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_ITERATOR_CONNECT_HANDLER_CHECK( \ - handler_type, handler, iter_type) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_RESOLVE_HANDLER_CHECK( \ - handler_type, handler, iter_type) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_WAIT_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_SIGNAL_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_HANDSHAKE_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_BUFFERED_HANDSHAKE_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#define ASIO_SHUTDOWN_HANDLER_CHECK( \ - handler_type, handler) \ - typedef int ASIO_UNUSED_TYPEDEF - -#endif // !defined(ASIO_ENABLE_HANDLER_TYPE_REQUIREMENTS) - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_HANDLER_TYPE_REQUIREMENTS_HPP diff --git a/scout_sdk/asio/asio/detail/handler_work.hpp b/scout_sdk/asio/asio/detail/handler_work.hpp deleted file mode 100644 index cce5c4b..0000000 --- a/scout_sdk/asio/asio/detail/handler_work.hpp +++ /dev/null @@ -1,95 +0,0 @@ -// -// detail/handler_work.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_HANDLER_WORK_HPP -#define ASIO_DETAIL_HANDLER_WORK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// A helper class template to allow completion handlers to be dispatched -// through either the new executors framework or the old invocaton hook. The -// primary template uses the new executors framework. -template ::type> -class handler_work -{ -public: - explicit handler_work(Handler& handler) ASIO_NOEXCEPT - : executor_(associated_executor::get(handler)) - { - } - - static void start(Handler& handler) ASIO_NOEXCEPT - { - Executor ex(associated_executor::get(handler)); - ex.on_work_started(); - } - - ~handler_work() - { - executor_.on_work_finished(); - } - - template - void complete(Function& function, Handler& handler) - { - executor_.dispatch(ASIO_MOVE_CAST(Function)(function), - associated_allocator::get(handler)); - } - -private: - // Disallow copying and assignment. - handler_work(const handler_work&); - handler_work& operator=(const handler_work&); - - typename associated_executor::type executor_; -}; - -// This specialisation dispatches a handler through the old invocation hook. -// The specialisation is not strictly required for correctness, as the -// system_executor will dispatch through the hook anyway. However, by doing -// this we avoid an extra copy of the handler. -template -class handler_work -{ -public: - explicit handler_work(Handler&) ASIO_NOEXCEPT {} - static void start(Handler&) ASIO_NOEXCEPT {} - ~handler_work() {} - - template - void complete(Function& function, Handler& handler) - { - asio_handler_invoke_helpers::invoke(function, handler); - } - -private: - // Disallow copying and assignment. - handler_work(const handler_work&); - handler_work& operator=(const handler_work&); -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_HANDLER_WORK_HPP diff --git a/scout_sdk/asio/asio/detail/hash_map.hpp b/scout_sdk/asio/asio/detail/hash_map.hpp deleted file mode 100644 index e70970d..0000000 --- a/scout_sdk/asio/asio/detail/hash_map.hpp +++ /dev/null @@ -1,331 +0,0 @@ -// -// detail/hash_map.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_HASH_MAP_HPP -#define ASIO_DETAIL_HASH_MAP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include "asio/detail/assert.hpp" -#include "asio/detail/noncopyable.hpp" - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# include "asio/detail/socket_types.hpp" -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -inline std::size_t calculate_hash_value(int i) -{ - return static_cast(i); -} - -inline std::size_t calculate_hash_value(void* p) -{ - return reinterpret_cast(p) - + (reinterpret_cast(p) >> 3); -} - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -inline std::size_t calculate_hash_value(SOCKET s) -{ - return static_cast(s); -} -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -// Note: assumes K and V are POD types. -template -class hash_map - : private noncopyable -{ -public: - // The type of a value in the map. - typedef std::pair value_type; - - // The type of a non-const iterator over the hash map. - typedef typename std::list::iterator iterator; - - // The type of a const iterator over the hash map. - typedef typename std::list::const_iterator const_iterator; - - // Constructor. - hash_map() - : size_(0), - buckets_(0), - num_buckets_(0) - { - } - - // Destructor. - ~hash_map() - { - delete[] buckets_; - } - - // Get an iterator for the beginning of the map. - iterator begin() - { - return values_.begin(); - } - - // Get an iterator for the beginning of the map. - const_iterator begin() const - { - return values_.begin(); - } - - // Get an iterator for the end of the map. - iterator end() - { - return values_.end(); - } - - // Get an iterator for the end of the map. - const_iterator end() const - { - return values_.end(); - } - - // Check whether the map is empty. - bool empty() const - { - return values_.empty(); - } - - // Find an entry in the map. - iterator find(const K& k) - { - if (num_buckets_) - { - size_t bucket = calculate_hash_value(k) % num_buckets_; - iterator it = buckets_[bucket].first; - if (it == values_.end()) - return values_.end(); - iterator end_it = buckets_[bucket].last; - ++end_it; - while (it != end_it) - { - if (it->first == k) - return it; - ++it; - } - } - return values_.end(); - } - - // Find an entry in the map. - const_iterator find(const K& k) const - { - if (num_buckets_) - { - size_t bucket = calculate_hash_value(k) % num_buckets_; - const_iterator it = buckets_[bucket].first; - if (it == values_.end()) - return it; - const_iterator end_it = buckets_[bucket].last; - ++end_it; - while (it != end_it) - { - if (it->first == k) - return it; - ++it; - } - } - return values_.end(); - } - - // Insert a new entry into the map. - std::pair insert(const value_type& v) - { - if (size_ + 1 >= num_buckets_) - rehash(hash_size(size_ + 1)); - size_t bucket = calculate_hash_value(v.first) % num_buckets_; - iterator it = buckets_[bucket].first; - if (it == values_.end()) - { - buckets_[bucket].first = buckets_[bucket].last = - values_insert(values_.end(), v); - ++size_; - return std::pair(buckets_[bucket].last, true); - } - iterator end_it = buckets_[bucket].last; - ++end_it; - while (it != end_it) - { - if (it->first == v.first) - return std::pair(it, false); - ++it; - } - buckets_[bucket].last = values_insert(end_it, v); - ++size_; - return std::pair(buckets_[bucket].last, true); - } - - // Erase an entry from the map. - void erase(iterator it) - { - ASIO_ASSERT(it != values_.end()); - ASIO_ASSERT(num_buckets_ != 0); - - size_t bucket = calculate_hash_value(it->first) % num_buckets_; - bool is_first = (it == buckets_[bucket].first); - bool is_last = (it == buckets_[bucket].last); - if (is_first && is_last) - buckets_[bucket].first = buckets_[bucket].last = values_.end(); - else if (is_first) - ++buckets_[bucket].first; - else if (is_last) - --buckets_[bucket].last; - - values_erase(it); - --size_; - } - - // Erase a key from the map. - void erase(const K& k) - { - iterator it = find(k); - if (it != values_.end()) - erase(it); - } - - // Remove all entries from the map. - void clear() - { - // Clear the values. - values_.clear(); - size_ = 0; - - // Initialise all buckets to empty. - iterator end_it = values_.end(); - for (size_t i = 0; i < num_buckets_; ++i) - buckets_[i].first = buckets_[i].last = end_it; - } - -private: - // Calculate the hash size for the specified number of elements. - static std::size_t hash_size(std::size_t num_elems) - { - static std::size_t sizes[] = - { -#if defined(ASIO_HASH_MAP_BUCKETS) - ASIO_HASH_MAP_BUCKETS -#else // ASIO_HASH_MAP_BUCKETS - 3, 13, 23, 53, 97, 193, 389, 769, 1543, 3079, 6151, 12289, 24593, - 49157, 98317, 196613, 393241, 786433, 1572869, 3145739, 6291469, - 12582917, 25165843 -#endif // ASIO_HASH_MAP_BUCKETS - }; - const std::size_t nth_size = sizeof(sizes) / sizeof(std::size_t) - 1; - for (std::size_t i = 0; i < nth_size; ++i) - if (num_elems < sizes[i]) - return sizes[i]; - return sizes[nth_size]; - } - - // Re-initialise the hash from the values already contained in the list. - void rehash(std::size_t num_buckets) - { - if (num_buckets == num_buckets_) - return; - ASIO_ASSERT(num_buckets != 0); - - iterator end_iter = values_.end(); - - // Update number of buckets and initialise all buckets to empty. - bucket_type* tmp = new bucket_type[num_buckets]; - delete[] buckets_; - buckets_ = tmp; - num_buckets_ = num_buckets; - for (std::size_t i = 0; i < num_buckets_; ++i) - buckets_[i].first = buckets_[i].last = end_iter; - - // Put all values back into the hash. - iterator iter = values_.begin(); - while (iter != end_iter) - { - std::size_t bucket = calculate_hash_value(iter->first) % num_buckets_; - if (buckets_[bucket].last == end_iter) - { - buckets_[bucket].first = buckets_[bucket].last = iter++; - } - else if (++buckets_[bucket].last == iter) - { - ++iter; - } - else - { - values_.splice(buckets_[bucket].last, values_, iter++); - --buckets_[bucket].last; - } - } - } - - // Insert an element into the values list by splicing from the spares list, - // if a spare is available, and otherwise by inserting a new element. - iterator values_insert(iterator it, const value_type& v) - { - if (spares_.empty()) - { - return values_.insert(it, v); - } - else - { - spares_.front() = v; - values_.splice(it, spares_, spares_.begin()); - return --it; - } - } - - // Erase an element from the values list by splicing it to the spares list. - void values_erase(iterator it) - { - *it = value_type(); - spares_.splice(spares_.begin(), values_, it); - } - - // The number of elements in the hash. - std::size_t size_; - - // The list of all values in the hash map. - std::list values_; - - // The list of spare nodes waiting to be recycled. Assumes that POD types only - // are stored in the hash map. - std::list spares_; - - // The type for a bucket in the hash table. - struct bucket_type - { - iterator first; - iterator last; - }; - - // The buckets in the hash. - bucket_type* buckets_; - - // The number of buckets in the hash. - std::size_t num_buckets_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_HASH_MAP_HPP diff --git a/scout_sdk/asio/asio/detail/impl/buffer_sequence_adapter.ipp b/scout_sdk/asio/asio/detail/impl/buffer_sequence_adapter.ipp deleted file mode 100644 index 323c8ad..0000000 --- a/scout_sdk/asio/asio/detail/impl/buffer_sequence_adapter.ipp +++ /dev/null @@ -1,118 +0,0 @@ -// -// detail/impl/buffer_sequence_adapter.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_BUFFER_SEQUENCE_ADAPTER_IPP -#define ASIO_DETAIL_IMPL_BUFFER_SEQUENCE_ADAPTER_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include -#include -#include -#include "asio/detail/buffer_sequence_adapter.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class winrt_buffer_impl : - public Microsoft::WRL::RuntimeClass< - Microsoft::WRL::RuntimeClassFlags< - Microsoft::WRL::RuntimeClassType::WinRtClassicComMix>, - ABI::Windows::Storage::Streams::IBuffer, - Windows::Storage::Streams::IBufferByteAccess> -{ -public: - explicit winrt_buffer_impl(const asio::const_buffer& b) - { - bytes_ = const_cast(static_cast(b.data())); - length_ = b.size(); - capacity_ = b.size(); - } - - explicit winrt_buffer_impl(const asio::mutable_buffer& b) - { - bytes_ = static_cast(b.data()); - length_ = 0; - capacity_ = b.size(); - } - - ~winrt_buffer_impl() - { - } - - STDMETHODIMP Buffer(byte** value) - { - *value = bytes_; - return S_OK; - } - - STDMETHODIMP get_Capacity(UINT32* value) - { - *value = capacity_; - return S_OK; - } - - STDMETHODIMP get_Length(UINT32 *value) - { - *value = length_; - return S_OK; - } - - STDMETHODIMP put_Length(UINT32 value) - { - if (value > capacity_) - return E_INVALIDARG; - length_ = value; - return S_OK; - } - -private: - byte* bytes_; - UINT32 length_; - UINT32 capacity_; -}; - -void buffer_sequence_adapter_base::init_native_buffer( - buffer_sequence_adapter_base::native_buffer_type& buf, - const asio::mutable_buffer& buffer) -{ - std::memset(&buf, 0, sizeof(native_buffer_type)); - Microsoft::WRL::ComPtr insp - = Microsoft::WRL::Make(buffer); - buf = reinterpret_cast(insp.Get()); -} - -void buffer_sequence_adapter_base::init_native_buffer( - buffer_sequence_adapter_base::native_buffer_type& buf, - const asio::const_buffer& buffer) -{ - std::memset(&buf, 0, sizeof(native_buffer_type)); - Microsoft::WRL::ComPtr insp - = Microsoft::WRL::Make(buffer); - Platform::Object^ buf_obj = reinterpret_cast(insp.Get()); - buf = reinterpret_cast(insp.Get()); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_IMPL_BUFFER_SEQUENCE_ADAPTER_IPP diff --git a/scout_sdk/asio/asio/detail/impl/descriptor_ops.ipp b/scout_sdk/asio/asio/detail/impl/descriptor_ops.ipp deleted file mode 100644 index 1af643f..0000000 --- a/scout_sdk/asio/asio/detail/impl/descriptor_ops.ipp +++ /dev/null @@ -1,474 +0,0 @@ -// -// detail/impl/descriptor_ops.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_DESCRIPTOR_OPS_IPP -#define ASIO_DETAIL_IMPL_DESCRIPTOR_OPS_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/descriptor_ops.hpp" -#include "asio/error.hpp" - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { -namespace descriptor_ops { - -int open(const char* path, int flags, asio::error_code& ec) -{ - errno = 0; - int result = error_wrapper(::open(path, flags), ec); - if (result >= 0) - ec = asio::error_code(); - return result; -} - -int close(int d, state_type& state, asio::error_code& ec) -{ - int result = 0; - if (d != -1) - { - errno = 0; - result = error_wrapper(::close(d), ec); - - if (result != 0 - && (ec == asio::error::would_block - || ec == asio::error::try_again)) - { - // According to UNIX Network Programming Vol. 1, it is possible for - // close() to fail with EWOULDBLOCK under certain circumstances. What - // isn't clear is the state of the descriptor after this error. The one - // current OS where this behaviour is seen, Windows, says that the socket - // remains open. Therefore we'll put the descriptor back into blocking - // mode and have another attempt at closing it. -#if defined(__SYMBIAN32__) - int flags = ::fcntl(d, F_GETFL, 0); - if (flags >= 0) - ::fcntl(d, F_SETFL, flags & ~O_NONBLOCK); -#else // defined(__SYMBIAN32__) - ioctl_arg_type arg = 0; - ::ioctl(d, FIONBIO, &arg); -#endif // defined(__SYMBIAN32__) - state &= ~non_blocking; - - errno = 0; - result = error_wrapper(::close(d), ec); - } - } - - if (result == 0) - ec = asio::error_code(); - return result; -} - -bool set_user_non_blocking(int d, state_type& state, - bool value, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return false; - } - - errno = 0; -#if defined(__SYMBIAN32__) - int result = error_wrapper(::fcntl(d, F_GETFL, 0), ec); - if (result >= 0) - { - errno = 0; - int flag = (value ? (result | O_NONBLOCK) : (result & ~O_NONBLOCK)); - result = error_wrapper(::fcntl(d, F_SETFL, flag), ec); - } -#else // defined(__SYMBIAN32__) - ioctl_arg_type arg = (value ? 1 : 0); - int result = error_wrapper(::ioctl(d, FIONBIO, &arg), ec); -#endif // defined(__SYMBIAN32__) - - if (result >= 0) - { - ec = asio::error_code(); - if (value) - state |= user_set_non_blocking; - else - { - // Clearing the user-set non-blocking mode always overrides any - // internally-set non-blocking flag. Any subsequent asynchronous - // operations will need to re-enable non-blocking I/O. - state &= ~(user_set_non_blocking | internal_non_blocking); - } - return true; - } - - return false; -} - -bool set_internal_non_blocking(int d, state_type& state, - bool value, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return false; - } - - if (!value && (state & user_set_non_blocking)) - { - // It does not make sense to clear the internal non-blocking flag if the - // user still wants non-blocking behaviour. Return an error and let the - // caller figure out whether to update the user-set non-blocking flag. - ec = asio::error::invalid_argument; - return false; - } - - errno = 0; -#if defined(__SYMBIAN32__) - int result = error_wrapper(::fcntl(d, F_GETFL, 0), ec); - if (result >= 0) - { - errno = 0; - int flag = (value ? (result | O_NONBLOCK) : (result & ~O_NONBLOCK)); - result = error_wrapper(::fcntl(d, F_SETFL, flag), ec); - } -#else // defined(__SYMBIAN32__) - ioctl_arg_type arg = (value ? 1 : 0); - int result = error_wrapper(::ioctl(d, FIONBIO, &arg), ec); -#endif // defined(__SYMBIAN32__) - - if (result >= 0) - { - ec = asio::error_code(); - if (value) - state |= internal_non_blocking; - else - state &= ~internal_non_blocking; - return true; - } - - return false; -} - -std::size_t sync_read(int d, state_type state, buf* bufs, - std::size_t count, bool all_empty, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // A request to read 0 bytes on a stream is a no-op. - if (all_empty) - { - ec = asio::error_code(); - return 0; - } - - // Read some data. - for (;;) - { - // Try to complete the operation without blocking. - errno = 0; - signed_size_type bytes = error_wrapper(::readv( - d, bufs, static_cast(count)), ec); - - // Check if operation succeeded. - if (bytes > 0) - return bytes; - - // Check for EOF. - if (bytes == 0) - { - ec = asio::error::eof; - return 0; - } - - // Operation failed. - if ((state & user_set_non_blocking) - || (ec != asio::error::would_block - && ec != asio::error::try_again)) - return 0; - - // Wait for descriptor to become ready. - if (descriptor_ops::poll_read(d, 0, ec) < 0) - return 0; - } -} - -bool non_blocking_read(int d, buf* bufs, std::size_t count, - asio::error_code& ec, std::size_t& bytes_transferred) -{ - for (;;) - { - // Read some data. - errno = 0; - signed_size_type bytes = error_wrapper(::readv( - d, bufs, static_cast(count)), ec); - - // Check for end of stream. - if (bytes == 0) - { - ec = asio::error::eof; - return true; - } - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Check if we need to run the operation again. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - return false; - - // Operation is complete. - if (bytes > 0) - { - ec = asio::error_code(); - bytes_transferred = bytes; - } - else - bytes_transferred = 0; - - return true; - } -} - -std::size_t sync_write(int d, state_type state, const buf* bufs, - std::size_t count, bool all_empty, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // A request to write 0 bytes on a stream is a no-op. - if (all_empty) - { - ec = asio::error_code(); - return 0; - } - - // Write some data. - for (;;) - { - // Try to complete the operation without blocking. - errno = 0; - signed_size_type bytes = error_wrapper(::writev( - d, bufs, static_cast(count)), ec); - - // Check if operation succeeded. - if (bytes > 0) - return bytes; - - // Operation failed. - if ((state & user_set_non_blocking) - || (ec != asio::error::would_block - && ec != asio::error::try_again)) - return 0; - - // Wait for descriptor to become ready. - if (descriptor_ops::poll_write(d, 0, ec) < 0) - return 0; - } -} - -bool non_blocking_write(int d, const buf* bufs, std::size_t count, - asio::error_code& ec, std::size_t& bytes_transferred) -{ - for (;;) - { - // Write some data. - errno = 0; - signed_size_type bytes = error_wrapper(::writev( - d, bufs, static_cast(count)), ec); - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Check if we need to run the operation again. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - return false; - - // Operation is complete. - if (bytes >= 0) - { - ec = asio::error_code(); - bytes_transferred = bytes; - } - else - bytes_transferred = 0; - - return true; - } -} - -int ioctl(int d, state_type& state, long cmd, - ioctl_arg_type* arg, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return -1; - } - - errno = 0; - int result = error_wrapper(::ioctl(d, cmd, arg), ec); - - if (result >= 0) - { - ec = asio::error_code(); - - // When updating the non-blocking mode we always perform the ioctl syscall, - // even if the flags would otherwise indicate that the descriptor is - // already in the correct state. This ensures that the underlying - // descriptor is put into the state that has been requested by the user. If - // the ioctl syscall was successful then we need to update the flags to - // match. - if (cmd == static_cast(FIONBIO)) - { - if (*arg) - { - state |= user_set_non_blocking; - } - else - { - // Clearing the non-blocking mode always overrides any internally-set - // non-blocking flag. Any subsequent asynchronous operations will need - // to re-enable non-blocking I/O. - state &= ~(user_set_non_blocking | internal_non_blocking); - } - } - } - - return result; -} - -int fcntl(int d, int cmd, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return -1; - } - - errno = 0; - int result = error_wrapper(::fcntl(d, cmd), ec); - if (result != -1) - ec = asio::error_code(); - return result; -} - -int fcntl(int d, int cmd, long arg, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return -1; - } - - errno = 0; - int result = error_wrapper(::fcntl(d, cmd, arg), ec); - if (result != -1) - ec = asio::error_code(); - return result; -} - -int poll_read(int d, state_type state, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return -1; - } - - pollfd fds; - fds.fd = d; - fds.events = POLLIN; - fds.revents = 0; - int timeout = (state & user_set_non_blocking) ? 0 : -1; - errno = 0; - int result = error_wrapper(::poll(&fds, 1, timeout), ec); - if (result == 0) - ec = (state & user_set_non_blocking) - ? asio::error::would_block : asio::error_code(); - else if (result > 0) - ec = asio::error_code(); - return result; -} - -int poll_write(int d, state_type state, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return -1; - } - - pollfd fds; - fds.fd = d; - fds.events = POLLOUT; - fds.revents = 0; - int timeout = (state & user_set_non_blocking) ? 0 : -1; - errno = 0; - int result = error_wrapper(::poll(&fds, 1, timeout), ec); - if (result == 0) - ec = (state & user_set_non_blocking) - ? asio::error::would_block : asio::error_code(); - else if (result > 0) - ec = asio::error_code(); - return result; -} - -int poll_error(int d, state_type state, asio::error_code& ec) -{ - if (d == -1) - { - ec = asio::error::bad_descriptor; - return -1; - } - - pollfd fds; - fds.fd = d; - fds.events = POLLPRI | POLLERR | POLLHUP; - fds.revents = 0; - int timeout = (state & user_set_non_blocking) ? 0 : -1; - errno = 0; - int result = error_wrapper(::poll(&fds, 1, timeout), ec); - if (result == 0) - ec = (state & user_set_non_blocking) - ? asio::error::would_block : asio::error_code(); - else if (result > 0) - ec = asio::error_code(); - return result; -} - -} // namespace descriptor_ops -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - -#endif // ASIO_DETAIL_IMPL_DESCRIPTOR_OPS_IPP diff --git a/scout_sdk/asio/asio/detail/impl/dev_poll_reactor.hpp b/scout_sdk/asio/asio/detail/impl/dev_poll_reactor.hpp deleted file mode 100644 index 4cd8aaf..0000000 --- a/scout_sdk/asio/asio/detail/impl/dev_poll_reactor.hpp +++ /dev/null @@ -1,91 +0,0 @@ -// -// detail/impl/dev_poll_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_DEV_POLL_REACTOR_HPP -#define ASIO_DETAIL_IMPL_DEV_POLL_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_DEV_POLL) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -void dev_poll_reactor::add_timer_queue(timer_queue& queue) -{ - do_add_timer_queue(queue); -} - -template -void dev_poll_reactor::remove_timer_queue(timer_queue& queue) -{ - do_remove_timer_queue(queue); -} - -template -void dev_poll_reactor::schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - if (shutdown_) - { - scheduler_.post_immediate_completion(op, false); - return; - } - - bool earliest = queue.enqueue_timer(time, timer, op); - scheduler_.work_started(); - if (earliest) - interrupter_.interrupt(); -} - -template -std::size_t dev_poll_reactor::cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - op_queue ops; - std::size_t n = queue.cancel_timer(timer, ops, max_cancelled); - lock.unlock(); - scheduler_.post_deferred_completions(ops); - return n; -} - -template -void dev_poll_reactor::move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - op_queue ops; - queue.cancel_timer(target, ops); - queue.move_timer(target, source); - lock.unlock(); - scheduler_.post_deferred_completions(ops); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_DEV_POLL) - -#endif // ASIO_DETAIL_IMPL_DEV_POLL_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/impl/dev_poll_reactor.ipp b/scout_sdk/asio/asio/detail/impl/dev_poll_reactor.ipp deleted file mode 100644 index 1ca376c..0000000 --- a/scout_sdk/asio/asio/detail/impl/dev_poll_reactor.ipp +++ /dev/null @@ -1,446 +0,0 @@ -// -// detail/impl/dev_poll_reactor.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_DEV_POLL_REACTOR_IPP -#define ASIO_DETAIL_IMPL_DEV_POLL_REACTOR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_DEV_POLL) - -#include "asio/detail/dev_poll_reactor.hpp" -#include "asio/detail/assert.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -dev_poll_reactor::dev_poll_reactor(asio::execution_context& ctx) - : asio::detail::execution_context_service_base(ctx), - scheduler_(use_service(ctx)), - mutex_(), - dev_poll_fd_(do_dev_poll_create()), - interrupter_(), - shutdown_(false) -{ - // Add the interrupter's descriptor to /dev/poll. - ::pollfd ev = { 0, 0, 0 }; - ev.fd = interrupter_.read_descriptor(); - ev.events = POLLIN | POLLERR; - ev.revents = 0; - ::write(dev_poll_fd_, &ev, sizeof(ev)); -} - -dev_poll_reactor::~dev_poll_reactor() -{ - shutdown(); - ::close(dev_poll_fd_); -} - -void dev_poll_reactor::shutdown() -{ - asio::detail::mutex::scoped_lock lock(mutex_); - shutdown_ = true; - lock.unlock(); - - op_queue ops; - - for (int i = 0; i < max_ops; ++i) - op_queue_[i].get_all_operations(ops); - - timer_queues_.get_all_timers(ops); - - scheduler_.abandon_operations(ops); -} - -void dev_poll_reactor::notify_fork( - asio::execution_context::fork_event fork_ev) -{ - if (fork_ev == asio::execution_context::fork_child) - { - detail::mutex::scoped_lock lock(mutex_); - - if (dev_poll_fd_ != -1) - ::close(dev_poll_fd_); - dev_poll_fd_ = -1; - dev_poll_fd_ = do_dev_poll_create(); - - interrupter_.recreate(); - - // Add the interrupter's descriptor to /dev/poll. - ::pollfd ev = { 0, 0, 0 }; - ev.fd = interrupter_.read_descriptor(); - ev.events = POLLIN | POLLERR; - ev.revents = 0; - ::write(dev_poll_fd_, &ev, sizeof(ev)); - - // Re-register all descriptors with /dev/poll. The changes will be written - // to the /dev/poll descriptor the next time the reactor is run. - for (int i = 0; i < max_ops; ++i) - { - reactor_op_queue::iterator iter = op_queue_[i].begin(); - reactor_op_queue::iterator end = op_queue_[i].end(); - for (; iter != end; ++iter) - { - ::pollfd& pending_ev = add_pending_event_change(iter->first); - pending_ev.events |= POLLERR | POLLHUP; - switch (i) - { - case read_op: pending_ev.events |= POLLIN; break; - case write_op: pending_ev.events |= POLLOUT; break; - case except_op: pending_ev.events |= POLLPRI; break; - default: break; - } - } - } - interrupter_.interrupt(); - } -} - -void dev_poll_reactor::init_task() -{ - scheduler_.init_task(); -} - -int dev_poll_reactor::register_descriptor(socket_type, per_descriptor_data&) -{ - return 0; -} - -int dev_poll_reactor::register_internal_descriptor(int op_type, - socket_type descriptor, per_descriptor_data&, reactor_op* op) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - op_queue_[op_type].enqueue_operation(descriptor, op); - ::pollfd& ev = add_pending_event_change(descriptor); - ev.events = POLLERR | POLLHUP; - switch (op_type) - { - case read_op: ev.events |= POLLIN; break; - case write_op: ev.events |= POLLOUT; break; - case except_op: ev.events |= POLLPRI; break; - default: break; - } - interrupter_.interrupt(); - - return 0; -} - -void dev_poll_reactor::move_descriptor(socket_type, - dev_poll_reactor::per_descriptor_data&, - dev_poll_reactor::per_descriptor_data&) -{ -} - -void dev_poll_reactor::start_op(int op_type, socket_type descriptor, - dev_poll_reactor::per_descriptor_data&, reactor_op* op, - bool is_continuation, bool allow_speculative) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - if (shutdown_) - { - post_immediate_completion(op, is_continuation); - return; - } - - if (allow_speculative) - { - if (op_type != read_op || !op_queue_[except_op].has_operation(descriptor)) - { - if (!op_queue_[op_type].has_operation(descriptor)) - { - if (op->perform()) - { - lock.unlock(); - scheduler_.post_immediate_completion(op, is_continuation); - return; - } - } - } - } - - bool first = op_queue_[op_type].enqueue_operation(descriptor, op); - scheduler_.work_started(); - if (first) - { - ::pollfd& ev = add_pending_event_change(descriptor); - ev.events = POLLERR | POLLHUP; - if (op_type == read_op - || op_queue_[read_op].has_operation(descriptor)) - ev.events |= POLLIN; - if (op_type == write_op - || op_queue_[write_op].has_operation(descriptor)) - ev.events |= POLLOUT; - if (op_type == except_op - || op_queue_[except_op].has_operation(descriptor)) - ev.events |= POLLPRI; - interrupter_.interrupt(); - } -} - -void dev_poll_reactor::cancel_ops(socket_type descriptor, - dev_poll_reactor::per_descriptor_data&) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - cancel_ops_unlocked(descriptor, asio::error::operation_aborted); -} - -void dev_poll_reactor::deregister_descriptor(socket_type descriptor, - dev_poll_reactor::per_descriptor_data&, bool) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - // Remove the descriptor from /dev/poll. - ::pollfd& ev = add_pending_event_change(descriptor); - ev.events = POLLREMOVE; - interrupter_.interrupt(); - - // Cancel any outstanding operations associated with the descriptor. - cancel_ops_unlocked(descriptor, asio::error::operation_aborted); -} - -void dev_poll_reactor::deregister_internal_descriptor( - socket_type descriptor, dev_poll_reactor::per_descriptor_data&) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - // Remove the descriptor from /dev/poll. Since this function is only called - // during a fork, we can apply the change immediately. - ::pollfd ev = { 0, 0, 0 }; - ev.fd = descriptor; - ev.events = POLLREMOVE; - ev.revents = 0; - ::write(dev_poll_fd_, &ev, sizeof(ev)); - - // Destroy all operations associated with the descriptor. - op_queue ops; - asio::error_code ec; - for (int i = 0; i < max_ops; ++i) - op_queue_[i].cancel_operations(descriptor, ops, ec); -} - -void dev_poll_reactor::cleanup_descriptor_data( - dev_poll_reactor::per_descriptor_data&) -{ -} - -void dev_poll_reactor::run(long usec, op_queue& ops) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - // We can return immediately if there's no work to do and the reactor is - // not supposed to block. - if (usec == 0 && op_queue_[read_op].empty() && op_queue_[write_op].empty() - && op_queue_[except_op].empty() && timer_queues_.all_empty()) - return; - - // Write the pending event registration changes to the /dev/poll descriptor. - std::size_t events_size = sizeof(::pollfd) * pending_event_changes_.size(); - if (events_size > 0) - { - errno = 0; - int result = ::write(dev_poll_fd_, - &pending_event_changes_[0], events_size); - if (result != static_cast(events_size)) - { - asio::error_code ec = asio::error_code( - errno, asio::error::get_system_category()); - for (std::size_t i = 0; i < pending_event_changes_.size(); ++i) - { - int descriptor = pending_event_changes_[i].fd; - for (int j = 0; j < max_ops; ++j) - op_queue_[j].cancel_operations(descriptor, ops, ec); - } - } - pending_event_changes_.clear(); - pending_event_change_index_.clear(); - } - - // Calculate timeout. - int timeout; - if (usec == 0) - timeout = 0; - else - { - timeout = (usec < 0) ? -1 : ((usec - 1) / 1000 + 1); - timeout = get_timeout(timeout); - } - lock.unlock(); - - // Block on the /dev/poll descriptor. - ::pollfd events[128] = { { 0, 0, 0 } }; - ::dvpoll dp = { 0, 0, 0 }; - dp.dp_fds = events; - dp.dp_nfds = 128; - dp.dp_timeout = timeout; - int num_events = ::ioctl(dev_poll_fd_, DP_POLL, &dp); - - lock.lock(); - - // Dispatch the waiting events. - for (int i = 0; i < num_events; ++i) - { - int descriptor = events[i].fd; - if (descriptor == interrupter_.read_descriptor()) - { - interrupter_.reset(); - } - else - { - bool more_reads = false; - bool more_writes = false; - bool more_except = false; - - // Exception operations must be processed first to ensure that any - // out-of-band data is read before normal data. - if (events[i].events & (POLLPRI | POLLERR | POLLHUP)) - more_except = - op_queue_[except_op].perform_operations(descriptor, ops); - else - more_except = op_queue_[except_op].has_operation(descriptor); - - if (events[i].events & (POLLIN | POLLERR | POLLHUP)) - more_reads = op_queue_[read_op].perform_operations(descriptor, ops); - else - more_reads = op_queue_[read_op].has_operation(descriptor); - - if (events[i].events & (POLLOUT | POLLERR | POLLHUP)) - more_writes = op_queue_[write_op].perform_operations(descriptor, ops); - else - more_writes = op_queue_[write_op].has_operation(descriptor); - - if ((events[i].events & (POLLERR | POLLHUP)) != 0 - && !more_except && !more_reads && !more_writes) - { - // If we have an event and no operations associated with the - // descriptor then we need to delete the descriptor from /dev/poll. - // The poll operation can produce POLLHUP or POLLERR events when there - // is no operation pending, so if we do not remove the descriptor we - // can end up in a tight polling loop. - ::pollfd ev = { 0, 0, 0 }; - ev.fd = descriptor; - ev.events = POLLREMOVE; - ev.revents = 0; - ::write(dev_poll_fd_, &ev, sizeof(ev)); - } - else - { - ::pollfd ev = { 0, 0, 0 }; - ev.fd = descriptor; - ev.events = POLLERR | POLLHUP; - if (more_reads) - ev.events |= POLLIN; - if (more_writes) - ev.events |= POLLOUT; - if (more_except) - ev.events |= POLLPRI; - ev.revents = 0; - int result = ::write(dev_poll_fd_, &ev, sizeof(ev)); - if (result != sizeof(ev)) - { - asio::error_code ec(errno, - asio::error::get_system_category()); - for (int j = 0; j < max_ops; ++j) - op_queue_[j].cancel_operations(descriptor, ops, ec); - } - } - } - } - timer_queues_.get_ready_timers(ops); -} - -void dev_poll_reactor::interrupt() -{ - interrupter_.interrupt(); -} - -int dev_poll_reactor::do_dev_poll_create() -{ - int fd = ::open("/dev/poll", O_RDWR); - if (fd == -1) - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "/dev/poll"); - } - return fd; -} - -void dev_poll_reactor::do_add_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.insert(&queue); -} - -void dev_poll_reactor::do_remove_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.erase(&queue); -} - -int dev_poll_reactor::get_timeout(int msec) -{ - // By default we will wait no longer than 5 minutes. This will ensure that - // any changes to the system clock are detected after no longer than this. - const int max_msec = 5 * 60 * 1000; - return timer_queues_.wait_duration_msec( - (msec < 0 || max_msec < msec) ? max_msec : msec); -} - -void dev_poll_reactor::cancel_ops_unlocked(socket_type descriptor, - const asio::error_code& ec) -{ - bool need_interrupt = false; - op_queue ops; - for (int i = 0; i < max_ops; ++i) - need_interrupt = op_queue_[i].cancel_operations( - descriptor, ops, ec) || need_interrupt; - scheduler_.post_deferred_completions(ops); - if (need_interrupt) - interrupter_.interrupt(); -} - -::pollfd& dev_poll_reactor::add_pending_event_change(int descriptor) -{ - hash_map::iterator iter - = pending_event_change_index_.find(descriptor); - if (iter == pending_event_change_index_.end()) - { - std::size_t index = pending_event_changes_.size(); - pending_event_changes_.reserve(pending_event_changes_.size() + 1); - pending_event_change_index_.insert(std::make_pair(descriptor, index)); - pending_event_changes_.push_back(::pollfd()); - pending_event_changes_[index].fd = descriptor; - pending_event_changes_[index].revents = 0; - return pending_event_changes_[index]; - } - else - { - return pending_event_changes_[iter->second]; - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_DEV_POLL) - -#endif // ASIO_DETAIL_IMPL_DEV_POLL_REACTOR_IPP diff --git a/scout_sdk/asio/asio/detail/impl/epoll_reactor.hpp b/scout_sdk/asio/asio/detail/impl/epoll_reactor.hpp deleted file mode 100644 index f990059..0000000 --- a/scout_sdk/asio/asio/detail/impl/epoll_reactor.hpp +++ /dev/null @@ -1,89 +0,0 @@ -// -// detail/impl/epoll_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_EPOLL_REACTOR_HPP -#define ASIO_DETAIL_IMPL_EPOLL_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if defined(ASIO_HAS_EPOLL) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -void epoll_reactor::add_timer_queue(timer_queue& queue) -{ - do_add_timer_queue(queue); -} - -template -void epoll_reactor::remove_timer_queue(timer_queue& queue) -{ - do_remove_timer_queue(queue); -} - -template -void epoll_reactor::schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op) -{ - mutex::scoped_lock lock(mutex_); - - if (shutdown_) - { - scheduler_.post_immediate_completion(op, false); - return; - } - - bool earliest = queue.enqueue_timer(time, timer, op); - scheduler_.work_started(); - if (earliest) - update_timeout(); -} - -template -std::size_t epoll_reactor::cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled) -{ - mutex::scoped_lock lock(mutex_); - op_queue ops; - std::size_t n = queue.cancel_timer(timer, ops, max_cancelled); - lock.unlock(); - scheduler_.post_deferred_completions(ops); - return n; -} - -template -void epoll_reactor::move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source) -{ - mutex::scoped_lock lock(mutex_); - op_queue ops; - queue.cancel_timer(target, ops); - queue.move_timer(target, source); - lock.unlock(); - scheduler_.post_deferred_completions(ops); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_EPOLL) - -#endif // ASIO_DETAIL_IMPL_EPOLL_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/impl/epoll_reactor.ipp b/scout_sdk/asio/asio/detail/impl/epoll_reactor.ipp deleted file mode 100644 index 65584a4..0000000 --- a/scout_sdk/asio/asio/detail/impl/epoll_reactor.ipp +++ /dev/null @@ -1,787 +0,0 @@ -// -// detail/impl/epoll_reactor.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_EPOLL_REACTOR_IPP -#define ASIO_DETAIL_IMPL_EPOLL_REACTOR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_EPOLL) - -#include -#include -#include "asio/detail/epoll_reactor.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#if defined(ASIO_HAS_TIMERFD) -# include -#endif // defined(ASIO_HAS_TIMERFD) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -epoll_reactor::epoll_reactor(asio::execution_context& ctx) - : execution_context_service_base(ctx), - scheduler_(use_service(ctx)), - mutex_(ASIO_CONCURRENCY_HINT_IS_LOCKING( - REACTOR_REGISTRATION, scheduler_.concurrency_hint())), - interrupter_(), - epoll_fd_(do_epoll_create()), - timer_fd_(do_timerfd_create()), - shutdown_(false), - registered_descriptors_mutex_(mutex_.enabled()) -{ - // Add the interrupter's descriptor to epoll. - epoll_event ev = { 0, { 0 } }; - ev.events = EPOLLIN | EPOLLERR | EPOLLET; - ev.data.ptr = &interrupter_; - epoll_ctl(epoll_fd_, EPOLL_CTL_ADD, interrupter_.read_descriptor(), &ev); - interrupter_.interrupt(); - - // Add the timer descriptor to epoll. - if (timer_fd_ != -1) - { - ev.events = EPOLLIN | EPOLLERR; - ev.data.ptr = &timer_fd_; - epoll_ctl(epoll_fd_, EPOLL_CTL_ADD, timer_fd_, &ev); - } -} - -epoll_reactor::~epoll_reactor() -{ - if (epoll_fd_ != -1) - close(epoll_fd_); - if (timer_fd_ != -1) - close(timer_fd_); -} - -void epoll_reactor::shutdown() -{ - mutex::scoped_lock lock(mutex_); - shutdown_ = true; - lock.unlock(); - - op_queue ops; - - while (descriptor_state* state = registered_descriptors_.first()) - { - for (int i = 0; i < max_ops; ++i) - ops.push(state->op_queue_[i]); - state->shutdown_ = true; - registered_descriptors_.free(state); - } - - timer_queues_.get_all_timers(ops); - - scheduler_.abandon_operations(ops); -} - -void epoll_reactor::notify_fork( - asio::execution_context::fork_event fork_ev) -{ - if (fork_ev == asio::execution_context::fork_child) - { - if (epoll_fd_ != -1) - ::close(epoll_fd_); - epoll_fd_ = -1; - epoll_fd_ = do_epoll_create(); - - if (timer_fd_ != -1) - ::close(timer_fd_); - timer_fd_ = -1; - timer_fd_ = do_timerfd_create(); - - interrupter_.recreate(); - - // Add the interrupter's descriptor to epoll. - epoll_event ev = { 0, { 0 } }; - ev.events = EPOLLIN | EPOLLERR | EPOLLET; - ev.data.ptr = &interrupter_; - epoll_ctl(epoll_fd_, EPOLL_CTL_ADD, interrupter_.read_descriptor(), &ev); - interrupter_.interrupt(); - - // Add the timer descriptor to epoll. - if (timer_fd_ != -1) - { - ev.events = EPOLLIN | EPOLLERR; - ev.data.ptr = &timer_fd_; - epoll_ctl(epoll_fd_, EPOLL_CTL_ADD, timer_fd_, &ev); - } - - update_timeout(); - - // Re-register all descriptors with epoll. - mutex::scoped_lock descriptors_lock(registered_descriptors_mutex_); - for (descriptor_state* state = registered_descriptors_.first(); - state != 0; state = state->next_) - { - ev.events = state->registered_events_; - ev.data.ptr = state; - int result = epoll_ctl(epoll_fd_, EPOLL_CTL_ADD, state->descriptor_, &ev); - if (result != 0) - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "epoll re-registration"); - } - } - } -} - -void epoll_reactor::init_task() -{ - scheduler_.init_task(); -} - -int epoll_reactor::register_descriptor(socket_type descriptor, - epoll_reactor::per_descriptor_data& descriptor_data) -{ - descriptor_data = allocate_descriptor_state(); - - ASIO_HANDLER_REACTOR_REGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - { - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - descriptor_data->reactor_ = this; - descriptor_data->descriptor_ = descriptor; - descriptor_data->shutdown_ = false; - for (int i = 0; i < max_ops; ++i) - descriptor_data->try_speculative_[i] = true; - } - - epoll_event ev = { 0, { 0 } }; - ev.events = EPOLLIN | EPOLLERR | EPOLLHUP | EPOLLPRI | EPOLLET; - descriptor_data->registered_events_ = ev.events; - ev.data.ptr = descriptor_data; - int result = epoll_ctl(epoll_fd_, EPOLL_CTL_ADD, descriptor, &ev); - if (result != 0) - { - if (errno == EPERM) - { - // This file descriptor type is not supported by epoll. However, if it is - // a regular file then operations on it will not block. We will allow - // this descriptor to be used and fail later if an operation on it would - // otherwise require a trip through the reactor. - descriptor_data->registered_events_ = 0; - return 0; - } - return errno; - } - - return 0; -} - -int epoll_reactor::register_internal_descriptor( - int op_type, socket_type descriptor, - epoll_reactor::per_descriptor_data& descriptor_data, reactor_op* op) -{ - descriptor_data = allocate_descriptor_state(); - - ASIO_HANDLER_REACTOR_REGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - { - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - descriptor_data->reactor_ = this; - descriptor_data->descriptor_ = descriptor; - descriptor_data->shutdown_ = false; - descriptor_data->op_queue_[op_type].push(op); - for (int i = 0; i < max_ops; ++i) - descriptor_data->try_speculative_[i] = true; - } - - epoll_event ev = { 0, { 0 } }; - ev.events = EPOLLIN | EPOLLERR | EPOLLHUP | EPOLLPRI | EPOLLET; - descriptor_data->registered_events_ = ev.events; - ev.data.ptr = descriptor_data; - int result = epoll_ctl(epoll_fd_, EPOLL_CTL_ADD, descriptor, &ev); - if (result != 0) - return errno; - - return 0; -} - -void epoll_reactor::move_descriptor(socket_type, - epoll_reactor::per_descriptor_data& target_descriptor_data, - epoll_reactor::per_descriptor_data& source_descriptor_data) -{ - target_descriptor_data = source_descriptor_data; - source_descriptor_data = 0; -} - -void epoll_reactor::start_op(int op_type, socket_type descriptor, - epoll_reactor::per_descriptor_data& descriptor_data, reactor_op* op, - bool is_continuation, bool allow_speculative) -{ - if (!descriptor_data) - { - op->ec_ = asio::error::bad_descriptor; - post_immediate_completion(op, is_continuation); - return; - } - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - if (descriptor_data->shutdown_) - { - post_immediate_completion(op, is_continuation); - return; - } - - if (descriptor_data->op_queue_[op_type].empty()) - { - if (allow_speculative - && (op_type != read_op - || descriptor_data->op_queue_[except_op].empty())) - { - if (descriptor_data->try_speculative_[op_type]) - { - if (reactor_op::status status = op->perform()) - { - if (status == reactor_op::done_and_exhausted) - if (descriptor_data->registered_events_ != 0) - descriptor_data->try_speculative_[op_type] = false; - descriptor_lock.unlock(); - scheduler_.post_immediate_completion(op, is_continuation); - return; - } - } - - if (descriptor_data->registered_events_ == 0) - { - op->ec_ = asio::error::operation_not_supported; - scheduler_.post_immediate_completion(op, is_continuation); - return; - } - - if (op_type == write_op) - { - if ((descriptor_data->registered_events_ & EPOLLOUT) == 0) - { - epoll_event ev = { 0, { 0 } }; - ev.events = descriptor_data->registered_events_ | EPOLLOUT; - ev.data.ptr = descriptor_data; - if (epoll_ctl(epoll_fd_, EPOLL_CTL_MOD, descriptor, &ev) == 0) - { - descriptor_data->registered_events_ |= ev.events; - } - else - { - op->ec_ = asio::error_code(errno, - asio::error::get_system_category()); - scheduler_.post_immediate_completion(op, is_continuation); - return; - } - } - } - } - else if (descriptor_data->registered_events_ == 0) - { - op->ec_ = asio::error::operation_not_supported; - scheduler_.post_immediate_completion(op, is_continuation); - return; - } - else - { - if (op_type == write_op) - { - descriptor_data->registered_events_ |= EPOLLOUT; - } - - epoll_event ev = { 0, { 0 } }; - ev.events = descriptor_data->registered_events_; - ev.data.ptr = descriptor_data; - epoll_ctl(epoll_fd_, EPOLL_CTL_MOD, descriptor, &ev); - } - } - - descriptor_data->op_queue_[op_type].push(op); - scheduler_.work_started(); -} - -void epoll_reactor::cancel_ops(socket_type, - epoll_reactor::per_descriptor_data& descriptor_data) -{ - if (!descriptor_data) - return; - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - op_queue ops; - for (int i = 0; i < max_ops; ++i) - { - while (reactor_op* op = descriptor_data->op_queue_[i].front()) - { - op->ec_ = asio::error::operation_aborted; - descriptor_data->op_queue_[i].pop(); - ops.push(op); - } - } - - descriptor_lock.unlock(); - - scheduler_.post_deferred_completions(ops); -} - -void epoll_reactor::deregister_descriptor(socket_type descriptor, - epoll_reactor::per_descriptor_data& descriptor_data, bool closing) -{ - if (!descriptor_data) - return; - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - if (!descriptor_data->shutdown_) - { - if (closing) - { - // The descriptor will be automatically removed from the epoll set when - // it is closed. - } - else if (descriptor_data->registered_events_ != 0) - { - epoll_event ev = { 0, { 0 } }; - epoll_ctl(epoll_fd_, EPOLL_CTL_DEL, descriptor, &ev); - } - - op_queue ops; - for (int i = 0; i < max_ops; ++i) - { - while (reactor_op* op = descriptor_data->op_queue_[i].front()) - { - op->ec_ = asio::error::operation_aborted; - descriptor_data->op_queue_[i].pop(); - ops.push(op); - } - } - - descriptor_data->descriptor_ = -1; - descriptor_data->shutdown_ = true; - - descriptor_lock.unlock(); - - ASIO_HANDLER_REACTOR_DEREGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - scheduler_.post_deferred_completions(ops); - - // Leave descriptor_data set so that it will be freed by the subsequent - // call to cleanup_descriptor_data. - } - else - { - // We are shutting down, so prevent cleanup_descriptor_data from freeing - // the descriptor_data object and let the destructor free it instead. - descriptor_data = 0; - } -} - -void epoll_reactor::deregister_internal_descriptor(socket_type descriptor, - epoll_reactor::per_descriptor_data& descriptor_data) -{ - if (!descriptor_data) - return; - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - if (!descriptor_data->shutdown_) - { - epoll_event ev = { 0, { 0 } }; - epoll_ctl(epoll_fd_, EPOLL_CTL_DEL, descriptor, &ev); - - op_queue ops; - for (int i = 0; i < max_ops; ++i) - ops.push(descriptor_data->op_queue_[i]); - - descriptor_data->descriptor_ = -1; - descriptor_data->shutdown_ = true; - - descriptor_lock.unlock(); - - ASIO_HANDLER_REACTOR_DEREGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - // Leave descriptor_data set so that it will be freed by the subsequent - // call to cleanup_descriptor_data. - } - else - { - // We are shutting down, so prevent cleanup_descriptor_data from freeing - // the descriptor_data object and let the destructor free it instead. - descriptor_data = 0; - } -} - -void epoll_reactor::cleanup_descriptor_data( - per_descriptor_data& descriptor_data) -{ - if (descriptor_data) - { - free_descriptor_state(descriptor_data); - descriptor_data = 0; - } -} - -void epoll_reactor::run(long usec, op_queue& ops) -{ - // This code relies on the fact that the scheduler queues the reactor task - // behind all descriptor operations generated by this function. This means, - // that by the time we reach this point, any previously returned descriptor - // operations have already been dequeued. Therefore it is now safe for us to - // reuse and return them for the scheduler to queue again. - - // Calculate timeout. Check the timer queues only if timerfd is not in use. - int timeout; - if (usec == 0) - timeout = 0; - else - { - timeout = (usec < 0) ? -1 : ((usec - 1) / 1000 + 1); - if (timer_fd_ == -1) - { - mutex::scoped_lock lock(mutex_); - timeout = get_timeout(timeout); - } - } - - // Block on the epoll descriptor. - epoll_event events[128]; - int num_events = epoll_wait(epoll_fd_, events, 128, timeout); - -#if defined(ASIO_ENABLE_HANDLER_TRACKING) - // Trace the waiting events. - for (int i = 0; i < num_events; ++i) - { - void* ptr = events[i].data.ptr; - if (ptr == &interrupter_) - { - // Ignore. - } -# if defined(ASIO_HAS_TIMERFD) - else if (ptr == &timer_fd_) - { - // Ignore. - } -# endif // defined(ASIO_HAS_TIMERFD) - else - { - unsigned event_mask = 0; - if ((events[i].events & EPOLLIN) != 0) - event_mask |= ASIO_HANDLER_REACTOR_READ_EVENT; - if ((events[i].events & EPOLLOUT)) - event_mask |= ASIO_HANDLER_REACTOR_WRITE_EVENT; - if ((events[i].events & (EPOLLERR | EPOLLHUP)) != 0) - event_mask |= ASIO_HANDLER_REACTOR_ERROR_EVENT; - ASIO_HANDLER_REACTOR_EVENTS((context(), - reinterpret_cast(ptr), event_mask)); - } - } -#endif // defined(ASIO_ENABLE_HANDLER_TRACKING) - -#if defined(ASIO_HAS_TIMERFD) - bool check_timers = (timer_fd_ == -1); -#else // defined(ASIO_HAS_TIMERFD) - bool check_timers = true; -#endif // defined(ASIO_HAS_TIMERFD) - - // Dispatch the waiting events. - for (int i = 0; i < num_events; ++i) - { - void* ptr = events[i].data.ptr; - if (ptr == &interrupter_) - { - // No need to reset the interrupter since we're leaving the descriptor - // in a ready-to-read state and relying on edge-triggered notifications - // to make it so that we only get woken up when the descriptor's epoll - // registration is updated. - -#if defined(ASIO_HAS_TIMERFD) - if (timer_fd_ == -1) - check_timers = true; -#else // defined(ASIO_HAS_TIMERFD) - check_timers = true; -#endif // defined(ASIO_HAS_TIMERFD) - } -#if defined(ASIO_HAS_TIMERFD) - else if (ptr == &timer_fd_) - { - check_timers = true; - } -#endif // defined(ASIO_HAS_TIMERFD) - else - { - // The descriptor operation doesn't count as work in and of itself, so we - // don't call work_started() here. This still allows the scheduler to - // stop if the only remaining operations are descriptor operations. - descriptor_state* descriptor_data = static_cast(ptr); - if (!ops.is_enqueued(descriptor_data)) - { - descriptor_data->set_ready_events(events[i].events); - ops.push(descriptor_data); - } - else - { - descriptor_data->add_ready_events(events[i].events); - } - } - } - - if (check_timers) - { - mutex::scoped_lock common_lock(mutex_); - timer_queues_.get_ready_timers(ops); - -#if defined(ASIO_HAS_TIMERFD) - if (timer_fd_ != -1) - { - itimerspec new_timeout; - itimerspec old_timeout; - int flags = get_timeout(new_timeout); - timerfd_settime(timer_fd_, flags, &new_timeout, &old_timeout); - } -#endif // defined(ASIO_HAS_TIMERFD) - } -} - -void epoll_reactor::interrupt() -{ - epoll_event ev = { 0, { 0 } }; - ev.events = EPOLLIN | EPOLLERR | EPOLLET; - ev.data.ptr = &interrupter_; - epoll_ctl(epoll_fd_, EPOLL_CTL_MOD, interrupter_.read_descriptor(), &ev); -} - -int epoll_reactor::do_epoll_create() -{ -#if defined(EPOLL_CLOEXEC) - int fd = epoll_create1(EPOLL_CLOEXEC); -#else // defined(EPOLL_CLOEXEC) - int fd = -1; - errno = EINVAL; -#endif // defined(EPOLL_CLOEXEC) - - if (fd == -1 && (errno == EINVAL || errno == ENOSYS)) - { - fd = epoll_create(epoll_size); - if (fd != -1) - ::fcntl(fd, F_SETFD, FD_CLOEXEC); - } - - if (fd == -1) - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "epoll"); - } - - return fd; -} - -int epoll_reactor::do_timerfd_create() -{ -#if defined(ASIO_HAS_TIMERFD) -# if defined(TFD_CLOEXEC) - int fd = timerfd_create(CLOCK_MONOTONIC, TFD_CLOEXEC); -# else // defined(TFD_CLOEXEC) - int fd = -1; - errno = EINVAL; -# endif // defined(TFD_CLOEXEC) - - if (fd == -1 && errno == EINVAL) - { - fd = timerfd_create(CLOCK_MONOTONIC, 0); - if (fd != -1) - ::fcntl(fd, F_SETFD, FD_CLOEXEC); - } - - return fd; -#else // defined(ASIO_HAS_TIMERFD) - return -1; -#endif // defined(ASIO_HAS_TIMERFD) -} - -epoll_reactor::descriptor_state* epoll_reactor::allocate_descriptor_state() -{ - mutex::scoped_lock descriptors_lock(registered_descriptors_mutex_); - return registered_descriptors_.alloc(ASIO_CONCURRENCY_HINT_IS_LOCKING( - REACTOR_IO, scheduler_.concurrency_hint())); -} - -void epoll_reactor::free_descriptor_state(epoll_reactor::descriptor_state* s) -{ - mutex::scoped_lock descriptors_lock(registered_descriptors_mutex_); - registered_descriptors_.free(s); -} - -void epoll_reactor::do_add_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.insert(&queue); -} - -void epoll_reactor::do_remove_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.erase(&queue); -} - -void epoll_reactor::update_timeout() -{ -#if defined(ASIO_HAS_TIMERFD) - if (timer_fd_ != -1) - { - itimerspec new_timeout; - itimerspec old_timeout; - int flags = get_timeout(new_timeout); - timerfd_settime(timer_fd_, flags, &new_timeout, &old_timeout); - return; - } -#endif // defined(ASIO_HAS_TIMERFD) - interrupt(); -} - -int epoll_reactor::get_timeout(int msec) -{ - // By default we will wait no longer than 5 minutes. This will ensure that - // any changes to the system clock are detected after no longer than this. - const int max_msec = 5 * 60 * 1000; - return timer_queues_.wait_duration_msec( - (msec < 0 || max_msec < msec) ? max_msec : msec); -} - -#if defined(ASIO_HAS_TIMERFD) -int epoll_reactor::get_timeout(itimerspec& ts) -{ - ts.it_interval.tv_sec = 0; - ts.it_interval.tv_nsec = 0; - - long usec = timer_queues_.wait_duration_usec(5 * 60 * 1000 * 1000); - ts.it_value.tv_sec = usec / 1000000; - ts.it_value.tv_nsec = usec ? (usec % 1000000) * 1000 : 1; - - return usec ? 0 : TFD_TIMER_ABSTIME; -} -#endif // defined(ASIO_HAS_TIMERFD) - -struct epoll_reactor::perform_io_cleanup_on_block_exit -{ - explicit perform_io_cleanup_on_block_exit(epoll_reactor* r) - : reactor_(r), first_op_(0) - { - } - - ~perform_io_cleanup_on_block_exit() - { - if (first_op_) - { - // Post the remaining completed operations for invocation. - if (!ops_.empty()) - reactor_->scheduler_.post_deferred_completions(ops_); - - // A user-initiated operation has completed, but there's no need to - // explicitly call work_finished() here. Instead, we'll take advantage of - // the fact that the scheduler will call work_finished() once we return. - } - else - { - // No user-initiated operations have completed, so we need to compensate - // for the work_finished() call that the scheduler will make once this - // operation returns. - reactor_->scheduler_.compensating_work_started(); - } - } - - epoll_reactor* reactor_; - op_queue ops_; - operation* first_op_; -}; - -epoll_reactor::descriptor_state::descriptor_state(bool locking) - : operation(&epoll_reactor::descriptor_state::do_complete), - mutex_(locking) -{ -} - -operation* epoll_reactor::descriptor_state::perform_io(uint32_t events) -{ - mutex_.lock(); - perform_io_cleanup_on_block_exit io_cleanup(reactor_); - mutex::scoped_lock descriptor_lock(mutex_, mutex::scoped_lock::adopt_lock); - - // Exception operations must be processed first to ensure that any - // out-of-band data is read before normal data. - static const int flag[max_ops] = { EPOLLIN, EPOLLOUT, EPOLLPRI }; - for (int j = max_ops - 1; j >= 0; --j) - { - if (events & (flag[j] | EPOLLERR | EPOLLHUP)) - { - try_speculative_[j] = true; - while (reactor_op* op = op_queue_[j].front()) - { - if (reactor_op::status status = op->perform()) - { - op_queue_[j].pop(); - io_cleanup.ops_.push(op); - if (status == reactor_op::done_and_exhausted) - { - try_speculative_[j] = false; - break; - } - } - else - break; - } - } - } - - // The first operation will be returned for completion now. The others will - // be posted for later by the io_cleanup object's destructor. - io_cleanup.first_op_ = io_cleanup.ops_.front(); - io_cleanup.ops_.pop(); - return io_cleanup.first_op_; -} - -void epoll_reactor::descriptor_state::do_complete( - void* owner, operation* base, - const asio::error_code& ec, std::size_t bytes_transferred) -{ - if (owner) - { - descriptor_state* descriptor_data = static_cast(base); - uint32_t events = static_cast(bytes_transferred); - if (operation* op = descriptor_data->perform_io(events)) - { - op->complete(owner, ec, 0); - } - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_EPOLL) - -#endif // ASIO_DETAIL_IMPL_EPOLL_REACTOR_IPP diff --git a/scout_sdk/asio/asio/detail/impl/eventfd_select_interrupter.ipp b/scout_sdk/asio/asio/detail/impl/eventfd_select_interrupter.ipp deleted file mode 100644 index c56e89a..0000000 --- a/scout_sdk/asio/asio/detail/impl/eventfd_select_interrupter.ipp +++ /dev/null @@ -1,165 +0,0 @@ -// -// detail/impl/eventfd_select_interrupter.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Roelof Naude (roelof.naude at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_EVENTFD_SELECT_INTERRUPTER_IPP -#define ASIO_DETAIL_IMPL_EVENTFD_SELECT_INTERRUPTER_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_EVENTFD) - -#include -#include -#include -#if __GLIBC__ == 2 && __GLIBC_MINOR__ < 8 -# include -#else // __GLIBC__ == 2 && __GLIBC_MINOR__ < 8 -# include -#endif // __GLIBC__ == 2 && __GLIBC_MINOR__ < 8 -#include "asio/detail/cstdint.hpp" -#include "asio/detail/eventfd_select_interrupter.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -eventfd_select_interrupter::eventfd_select_interrupter() -{ - open_descriptors(); -} - -void eventfd_select_interrupter::open_descriptors() -{ -#if __GLIBC__ == 2 && __GLIBC_MINOR__ < 8 - write_descriptor_ = read_descriptor_ = syscall(__NR_eventfd, 0); - if (read_descriptor_ != -1) - { - ::fcntl(read_descriptor_, F_SETFL, O_NONBLOCK); - ::fcntl(read_descriptor_, F_SETFD, FD_CLOEXEC); - } -#else // __GLIBC__ == 2 && __GLIBC_MINOR__ < 8 -# if defined(EFD_CLOEXEC) && defined(EFD_NONBLOCK) - write_descriptor_ = read_descriptor_ = - ::eventfd(0, EFD_CLOEXEC | EFD_NONBLOCK); -# else // defined(EFD_CLOEXEC) && defined(EFD_NONBLOCK) - errno = EINVAL; - write_descriptor_ = read_descriptor_ = -1; -# endif // defined(EFD_CLOEXEC) && defined(EFD_NONBLOCK) - if (read_descriptor_ == -1 && errno == EINVAL) - { - write_descriptor_ = read_descriptor_ = ::eventfd(0, 0); - if (read_descriptor_ != -1) - { - ::fcntl(read_descriptor_, F_SETFL, O_NONBLOCK); - ::fcntl(read_descriptor_, F_SETFD, FD_CLOEXEC); - } - } -#endif // __GLIBC__ == 2 && __GLIBC_MINOR__ < 8 - - if (read_descriptor_ == -1) - { - int pipe_fds[2]; - if (pipe(pipe_fds) == 0) - { - read_descriptor_ = pipe_fds[0]; - ::fcntl(read_descriptor_, F_SETFL, O_NONBLOCK); - ::fcntl(read_descriptor_, F_SETFD, FD_CLOEXEC); - write_descriptor_ = pipe_fds[1]; - ::fcntl(write_descriptor_, F_SETFL, O_NONBLOCK); - ::fcntl(write_descriptor_, F_SETFD, FD_CLOEXEC); - } - else - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "eventfd_select_interrupter"); - } - } -} - -eventfd_select_interrupter::~eventfd_select_interrupter() -{ - close_descriptors(); -} - -void eventfd_select_interrupter::close_descriptors() -{ - if (write_descriptor_ != -1 && write_descriptor_ != read_descriptor_) - ::close(write_descriptor_); - if (read_descriptor_ != -1) - ::close(read_descriptor_); -} - -void eventfd_select_interrupter::recreate() -{ - close_descriptors(); - - write_descriptor_ = -1; - read_descriptor_ = -1; - - open_descriptors(); -} - -void eventfd_select_interrupter::interrupt() -{ - uint64_t counter(1UL); - int result = ::write(write_descriptor_, &counter, sizeof(uint64_t)); - (void)result; -} - -bool eventfd_select_interrupter::reset() -{ - if (write_descriptor_ == read_descriptor_) - { - for (;;) - { - // Only perform one read. The kernel maintains an atomic counter. - uint64_t counter(0); - errno = 0; - int bytes_read = ::read(read_descriptor_, &counter, sizeof(uint64_t)); - if (bytes_read < 0 && errno == EINTR) - continue; - bool was_interrupted = (bytes_read > 0); - return was_interrupted; - } - } - else - { - for (;;) - { - // Clear all data from the pipe. - char data[1024]; - int bytes_read = ::read(read_descriptor_, data, sizeof(data)); - if (bytes_read < 0 && errno == EINTR) - continue; - bool was_interrupted = (bytes_read > 0); - while (bytes_read == sizeof(data)) - bytes_read = ::read(read_descriptor_, data, sizeof(data)); - return was_interrupted; - } - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_EVENTFD) - -#endif // ASIO_DETAIL_IMPL_EVENTFD_SELECT_INTERRUPTER_IPP diff --git a/scout_sdk/asio/asio/detail/impl/handler_tracking.ipp b/scout_sdk/asio/asio/detail/impl/handler_tracking.ipp deleted file mode 100644 index 5a4ff6f..0000000 --- a/scout_sdk/asio/asio/detail/impl/handler_tracking.ipp +++ /dev/null @@ -1,358 +0,0 @@ -// -// detail/impl/handler_tracking.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_HANDLER_TRACKING_IPP -#define ASIO_DETAIL_IMPL_HANDLER_TRACKING_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_CUSTOM_HANDLER_TRACKING) - -// The handler tracking implementation is provided by the user-specified header. - -#elif defined(ASIO_ENABLE_HANDLER_TRACKING) - -#include -#include -#include "asio/detail/handler_tracking.hpp" - -#if defined(ASIO_HAS_BOOST_DATE_TIME) -# include "asio/time_traits.hpp" -#elif defined(ASIO_HAS_CHRONO) -# include "asio/detail/chrono.hpp" -# include "asio/detail/chrono_time_traits.hpp" -# include "asio/wait_traits.hpp" -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/socket_types.hpp" -#elif !defined(ASIO_WINDOWS) -# include -#endif // !defined(ASIO_WINDOWS) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct handler_tracking_timestamp -{ - uint64_t seconds; - uint64_t microseconds; - - handler_tracking_timestamp() - { -#if defined(ASIO_HAS_BOOST_DATE_TIME) - boost::posix_time::ptime epoch(boost::gregorian::date(1970, 1, 1)); - boost::posix_time::time_duration now = - boost::posix_time::microsec_clock::universal_time() - epoch; -#elif defined(ASIO_HAS_CHRONO) - typedef chrono_time_traits > traits_helper; - traits_helper::posix_time_duration now( - chrono::system_clock::now().time_since_epoch()); -#endif - seconds = static_cast(now.total_seconds()); - microseconds = static_cast(now.total_microseconds() % 1000000); - } -}; - -struct handler_tracking::tracking_state -{ - static_mutex mutex_; - uint64_t next_id_; - tss_ptr* current_completion_; -}; - -handler_tracking::tracking_state* handler_tracking::get_state() -{ - static tracking_state state = { ASIO_STATIC_MUTEX_INIT, 1, 0 }; - return &state; -} - -void handler_tracking::init() -{ - static tracking_state* state = get_state(); - - state->mutex_.init(); - - static_mutex::scoped_lock lock(state->mutex_); - if (state->current_completion_ == 0) - state->current_completion_ = new tss_ptr; -} - -void handler_tracking::creation(execution_context&, - handler_tracking::tracked_handler& h, - const char* object_type, void* object, - uintmax_t /*native_handle*/, const char* op_name) -{ - static tracking_state* state = get_state(); - - static_mutex::scoped_lock lock(state->mutex_); - h.id_ = state->next_id_++; - lock.unlock(); - - handler_tracking_timestamp timestamp; - - uint64_t current_id = 0; - if (completion* current_completion = *state->current_completion_) - current_id = current_completion->id_; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|%I64u*%I64u|%.20s@%p.%.50s\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|%llu*%llu|%.20s@%p.%.50s\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - current_id, h.id_, object_type, object, op_name); -} - -handler_tracking::completion::completion( - const handler_tracking::tracked_handler& h) - : id_(h.id_), - invoked_(false), - next_(*get_state()->current_completion_) -{ - *get_state()->current_completion_ = this; -} - -handler_tracking::completion::~completion() -{ - if (id_) - { - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|%c%I64u|\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|%c%llu|\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - invoked_ ? '!' : '~', id_); - } - - *get_state()->current_completion_ = next_; -} - -void handler_tracking::completion::invocation_begin() -{ - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|>%I64u|\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|>%llu|\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, id_); - - invoked_ = true; -} - -void handler_tracking::completion::invocation_begin( - const asio::error_code& ec) -{ - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|>%I64u|ec=%.20s:%d\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|>%llu|ec=%.20s:%d\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - id_, ec.category().name(), ec.value()); - - invoked_ = true; -} - -void handler_tracking::completion::invocation_begin( - const asio::error_code& ec, std::size_t bytes_transferred) -{ - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|>%I64u|ec=%.20s:%d,bytes_transferred=%I64u\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|>%llu|ec=%.20s:%d,bytes_transferred=%llu\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - id_, ec.category().name(), ec.value(), - static_cast(bytes_transferred)); - - invoked_ = true; -} - -void handler_tracking::completion::invocation_begin( - const asio::error_code& ec, int signal_number) -{ - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|>%I64u|ec=%.20s:%d,signal_number=%d\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|>%llu|ec=%.20s:%d,signal_number=%d\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - id_, ec.category().name(), ec.value(), signal_number); - - invoked_ = true; -} - -void handler_tracking::completion::invocation_begin( - const asio::error_code& ec, const char* arg) -{ - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|>%I64u|ec=%.20s:%d,%.50s\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|>%llu|ec=%.20s:%d,%.50s\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - id_, ec.category().name(), ec.value(), arg); - - invoked_ = true; -} - -void handler_tracking::completion::invocation_end() -{ - if (id_) - { - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|<%I64u|\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|<%llu|\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, id_); - - id_ = 0; - } -} - -void handler_tracking::operation(execution_context&, - const char* object_type, void* object, - uintmax_t /*native_handle*/, const char* op_name) -{ - static tracking_state* state = get_state(); - - handler_tracking_timestamp timestamp; - - unsigned long long current_id = 0; - if (completion* current_completion = *state->current_completion_) - current_id = current_completion->id_; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|%I64u|%.20s@%p.%.50s\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|%llu|%.20s@%p.%.50s\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - current_id, object_type, object, op_name); -} - -void handler_tracking::reactor_registration(execution_context& /*context*/, - uintmax_t /*native_handle*/, uintmax_t /*registration*/) -{ -} - -void handler_tracking::reactor_deregistration(execution_context& /*context*/, - uintmax_t /*native_handle*/, uintmax_t /*registration*/) -{ -} - -void handler_tracking::reactor_events(execution_context& /*context*/, - uintmax_t /*native_handle*/, unsigned /*events*/) -{ -} - -void handler_tracking::reactor_operation( - const tracked_handler& h, const char* op_name, - const asio::error_code& ec) -{ - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|.%I64u|%s,ec=%.20s:%d\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|.%llu|%s,ec=%.20s:%d\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - h.id_, op_name, ec.category().name(), ec.value()); -} - -void handler_tracking::reactor_operation( - const tracked_handler& h, const char* op_name, - const asio::error_code& ec, std::size_t bytes_transferred) -{ - handler_tracking_timestamp timestamp; - - write_line( -#if defined(ASIO_WINDOWS) - "@asio|%I64u.%06I64u|.%I64u|%s,ec=%.20s:%d,bytes_transferred=%I64u\n", -#else // defined(ASIO_WINDOWS) - "@asio|%llu.%06llu|.%llu|%s,ec=%.20s:%d,bytes_transferred=%llu\n", -#endif // defined(ASIO_WINDOWS) - timestamp.seconds, timestamp.microseconds, - h.id_, op_name, ec.category().name(), ec.value(), - static_cast(bytes_transferred)); -} - -void handler_tracking::write_line(const char* format, ...) -{ - using namespace std; // For sprintf (or equivalent). - - va_list args; - va_start(args, format); - - char line[256] = ""; -#if defined(ASIO_HAS_SECURE_RTL) - int length = vsprintf_s(line, sizeof(line), format, args); -#else // defined(ASIO_HAS_SECURE_RTL) - int length = vsprintf(line, format, args); -#endif // defined(ASIO_HAS_SECURE_RTL) - - va_end(args); - -#if defined(ASIO_WINDOWS_RUNTIME) - wchar_t wline[256] = L""; - mbstowcs_s(0, wline, sizeof(wline) / sizeof(wchar_t), line, length); - ::OutputDebugStringW(wline); -#elif defined(ASIO_WINDOWS) - HANDLE stderr_handle = ::GetStdHandle(STD_ERROR_HANDLE); - DWORD bytes_written = 0; - ::WriteFile(stderr_handle, line, length, &bytes_written, 0); -#else // defined(ASIO_WINDOWS) - ::write(STDERR_FILENO, line, length); -#endif // defined(ASIO_WINDOWS) -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_HANDLER_TRACKING) - -#endif // ASIO_DETAIL_IMPL_HANDLER_TRACKING_IPP diff --git a/scout_sdk/asio/asio/detail/impl/kqueue_reactor.hpp b/scout_sdk/asio/asio/detail/impl/kqueue_reactor.hpp deleted file mode 100644 index 136d167..0000000 --- a/scout_sdk/asio/asio/detail/impl/kqueue_reactor.hpp +++ /dev/null @@ -1,93 +0,0 @@ -// -// detail/impl/kqueue_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2005 Stefan Arentz (stefan at soze dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_KQUEUE_REACTOR_HPP -#define ASIO_DETAIL_IMPL_KQUEUE_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_KQUEUE) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -void kqueue_reactor::add_timer_queue(timer_queue& queue) -{ - do_add_timer_queue(queue); -} - -// Remove a timer queue from the reactor. -template -void kqueue_reactor::remove_timer_queue(timer_queue& queue) -{ - do_remove_timer_queue(queue); -} - -template -void kqueue_reactor::schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op) -{ - mutex::scoped_lock lock(mutex_); - - if (shutdown_) - { - scheduler_.post_immediate_completion(op, false); - return; - } - - bool earliest = queue.enqueue_timer(time, timer, op); - scheduler_.work_started(); - if (earliest) - interrupt(); -} - -template -std::size_t kqueue_reactor::cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled) -{ - mutex::scoped_lock lock(mutex_); - op_queue ops; - std::size_t n = queue.cancel_timer(timer, ops, max_cancelled); - lock.unlock(); - scheduler_.post_deferred_completions(ops); - return n; -} - -template -void kqueue_reactor::move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source) -{ - mutex::scoped_lock lock(mutex_); - op_queue ops; - queue.cancel_timer(target, ops); - queue.move_timer(target, source); - lock.unlock(); - scheduler_.post_deferred_completions(ops); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_KQUEUE) - -#endif // ASIO_DETAIL_IMPL_KQUEUE_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/impl/kqueue_reactor.ipp b/scout_sdk/asio/asio/detail/impl/kqueue_reactor.ipp deleted file mode 100644 index 73986e0..0000000 --- a/scout_sdk/asio/asio/detail/impl/kqueue_reactor.ipp +++ /dev/null @@ -1,566 +0,0 @@ -// -// detail/impl/kqueue_reactor.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2005 Stefan Arentz (stefan at soze dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_KQUEUE_REACTOR_IPP -#define ASIO_DETAIL_IMPL_KQUEUE_REACTOR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_KQUEUE) - -#include "asio/detail/kqueue_reactor.hpp" -#include "asio/detail/scheduler.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -#if defined(__NetBSD__) -# define ASIO_KQUEUE_EV_SET(ev, ident, filt, flags, fflags, data, udata) \ - EV_SET(ev, ident, filt, flags, fflags, data, \ - reinterpret_cast(static_cast(udata))) -#else -# define ASIO_KQUEUE_EV_SET(ev, ident, filt, flags, fflags, data, udata) \ - EV_SET(ev, ident, filt, flags, fflags, data, udata) -#endif - -namespace asio { -namespace detail { - -kqueue_reactor::kqueue_reactor(asio::execution_context& ctx) - : execution_context_service_base(ctx), - scheduler_(use_service(ctx)), - mutex_(ASIO_CONCURRENCY_HINT_IS_LOCKING( - REACTOR_REGISTRATION, scheduler_.concurrency_hint())), - kqueue_fd_(do_kqueue_create()), - interrupter_(), - shutdown_(false), - registered_descriptors_mutex_(mutex_.enabled()) -{ - struct kevent events[1]; - ASIO_KQUEUE_EV_SET(&events[0], interrupter_.read_descriptor(), - EVFILT_READ, EV_ADD, 0, 0, &interrupter_); - if (::kevent(kqueue_fd_, events, 1, 0, 0, 0) == -1) - { - asio::error_code error(errno, - asio::error::get_system_category()); - asio::detail::throw_error(error); - } -} - -kqueue_reactor::~kqueue_reactor() -{ - close(kqueue_fd_); -} - -void kqueue_reactor::shutdown() -{ - mutex::scoped_lock lock(mutex_); - shutdown_ = true; - lock.unlock(); - - op_queue ops; - - while (descriptor_state* state = registered_descriptors_.first()) - { - for (int i = 0; i < max_ops; ++i) - ops.push(state->op_queue_[i]); - state->shutdown_ = true; - registered_descriptors_.free(state); - } - - timer_queues_.get_all_timers(ops); - - scheduler_.abandon_operations(ops); -} - -void kqueue_reactor::notify_fork( - asio::execution_context::fork_event fork_ev) -{ - if (fork_ev == asio::execution_context::fork_child) - { - // The kqueue descriptor is automatically closed in the child. - kqueue_fd_ = -1; - kqueue_fd_ = do_kqueue_create(); - - interrupter_.recreate(); - - struct kevent events[2]; - ASIO_KQUEUE_EV_SET(&events[0], interrupter_.read_descriptor(), - EVFILT_READ, EV_ADD, 0, 0, &interrupter_); - if (::kevent(kqueue_fd_, events, 1, 0, 0, 0) == -1) - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "kqueue interrupter registration"); - } - - // Re-register all descriptors with kqueue. - mutex::scoped_lock descriptors_lock(registered_descriptors_mutex_); - for (descriptor_state* state = registered_descriptors_.first(); - state != 0; state = state->next_) - { - if (state->num_kevents_ > 0) - { - ASIO_KQUEUE_EV_SET(&events[0], state->descriptor_, - EVFILT_READ, EV_ADD | EV_CLEAR, 0, 0, state); - ASIO_KQUEUE_EV_SET(&events[1], state->descriptor_, - EVFILT_WRITE, EV_ADD | EV_CLEAR, 0, 0, state); - if (::kevent(kqueue_fd_, events, state->num_kevents_, 0, 0, 0) == -1) - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "kqueue re-registration"); - } - } - } - } -} - -void kqueue_reactor::init_task() -{ - scheduler_.init_task(); -} - -int kqueue_reactor::register_descriptor(socket_type descriptor, - kqueue_reactor::per_descriptor_data& descriptor_data) -{ - descriptor_data = allocate_descriptor_state(); - - ASIO_HANDLER_REACTOR_REGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - mutex::scoped_lock lock(descriptor_data->mutex_); - - descriptor_data->descriptor_ = descriptor; - descriptor_data->num_kevents_ = 0; - descriptor_data->shutdown_ = false; - - return 0; -} - -int kqueue_reactor::register_internal_descriptor( - int op_type, socket_type descriptor, - kqueue_reactor::per_descriptor_data& descriptor_data, reactor_op* op) -{ - descriptor_data = allocate_descriptor_state(); - - ASIO_HANDLER_REACTOR_REGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - mutex::scoped_lock lock(descriptor_data->mutex_); - - descriptor_data->descriptor_ = descriptor; - descriptor_data->num_kevents_ = 1; - descriptor_data->shutdown_ = false; - descriptor_data->op_queue_[op_type].push(op); - - struct kevent events[1]; - ASIO_KQUEUE_EV_SET(&events[0], descriptor, EVFILT_READ, - EV_ADD | EV_CLEAR, 0, 0, descriptor_data); - if (::kevent(kqueue_fd_, events, 1, 0, 0, 0) == -1) - return errno; - - return 0; -} - -void kqueue_reactor::move_descriptor(socket_type, - kqueue_reactor::per_descriptor_data& target_descriptor_data, - kqueue_reactor::per_descriptor_data& source_descriptor_data) -{ - target_descriptor_data = source_descriptor_data; - source_descriptor_data = 0; -} - -void kqueue_reactor::start_op(int op_type, socket_type descriptor, - kqueue_reactor::per_descriptor_data& descriptor_data, reactor_op* op, - bool is_continuation, bool allow_speculative) -{ - if (!descriptor_data) - { - op->ec_ = asio::error::bad_descriptor; - post_immediate_completion(op, is_continuation); - return; - } - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - if (descriptor_data->shutdown_) - { - post_immediate_completion(op, is_continuation); - return; - } - - if (descriptor_data->op_queue_[op_type].empty()) - { - static const int num_kevents[max_ops] = { 1, 2, 1 }; - - if (allow_speculative - && (op_type != read_op - || descriptor_data->op_queue_[except_op].empty())) - { - if (op->perform()) - { - descriptor_lock.unlock(); - scheduler_.post_immediate_completion(op, is_continuation); - return; - } - - if (descriptor_data->num_kevents_ < num_kevents[op_type]) - { - struct kevent events[2]; - ASIO_KQUEUE_EV_SET(&events[0], descriptor, EVFILT_READ, - EV_ADD | EV_CLEAR, 0, 0, descriptor_data); - ASIO_KQUEUE_EV_SET(&events[1], descriptor, EVFILT_WRITE, - EV_ADD | EV_CLEAR, 0, 0, descriptor_data); - if (::kevent(kqueue_fd_, events, num_kevents[op_type], 0, 0, 0) != -1) - { - descriptor_data->num_kevents_ = num_kevents[op_type]; - } - else - { - op->ec_ = asio::error_code(errno, - asio::error::get_system_category()); - scheduler_.post_immediate_completion(op, is_continuation); - return; - } - } - } - else - { - if (descriptor_data->num_kevents_ < num_kevents[op_type]) - descriptor_data->num_kevents_ = num_kevents[op_type]; - - struct kevent events[2]; - ASIO_KQUEUE_EV_SET(&events[0], descriptor, EVFILT_READ, - EV_ADD | EV_CLEAR, 0, 0, descriptor_data); - ASIO_KQUEUE_EV_SET(&events[1], descriptor, EVFILT_WRITE, - EV_ADD | EV_CLEAR, 0, 0, descriptor_data); - ::kevent(kqueue_fd_, events, descriptor_data->num_kevents_, 0, 0, 0); - } - } - - descriptor_data->op_queue_[op_type].push(op); - scheduler_.work_started(); -} - -void kqueue_reactor::cancel_ops(socket_type, - kqueue_reactor::per_descriptor_data& descriptor_data) -{ - if (!descriptor_data) - return; - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - op_queue ops; - for (int i = 0; i < max_ops; ++i) - { - while (reactor_op* op = descriptor_data->op_queue_[i].front()) - { - op->ec_ = asio::error::operation_aborted; - descriptor_data->op_queue_[i].pop(); - ops.push(op); - } - } - - descriptor_lock.unlock(); - - scheduler_.post_deferred_completions(ops); -} - -void kqueue_reactor::deregister_descriptor(socket_type descriptor, - kqueue_reactor::per_descriptor_data& descriptor_data, bool closing) -{ - if (!descriptor_data) - return; - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - if (!descriptor_data->shutdown_) - { - if (closing) - { - // The descriptor will be automatically removed from the kqueue when it - // is closed. - } - else - { - struct kevent events[2]; - ASIO_KQUEUE_EV_SET(&events[0], descriptor, - EVFILT_READ, EV_DELETE, 0, 0, 0); - ASIO_KQUEUE_EV_SET(&events[1], descriptor, - EVFILT_WRITE, EV_DELETE, 0, 0, 0); - ::kevent(kqueue_fd_, events, descriptor_data->num_kevents_, 0, 0, 0); - } - - op_queue ops; - for (int i = 0; i < max_ops; ++i) - { - while (reactor_op* op = descriptor_data->op_queue_[i].front()) - { - op->ec_ = asio::error::operation_aborted; - descriptor_data->op_queue_[i].pop(); - ops.push(op); - } - } - - descriptor_data->descriptor_ = -1; - descriptor_data->shutdown_ = true; - - descriptor_lock.unlock(); - - ASIO_HANDLER_REACTOR_DEREGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - scheduler_.post_deferred_completions(ops); - - // Leave descriptor_data set so that it will be freed by the subsequent - // call to cleanup_descriptor_data. - } - else - { - // We are shutting down, so prevent cleanup_descriptor_data from freeing - // the descriptor_data object and let the destructor free it instead. - descriptor_data = 0; - } -} - -void kqueue_reactor::deregister_internal_descriptor(socket_type descriptor, - kqueue_reactor::per_descriptor_data& descriptor_data) -{ - if (!descriptor_data) - return; - - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - if (!descriptor_data->shutdown_) - { - struct kevent events[2]; - ASIO_KQUEUE_EV_SET(&events[0], descriptor, - EVFILT_READ, EV_DELETE, 0, 0, 0); - ASIO_KQUEUE_EV_SET(&events[1], descriptor, - EVFILT_WRITE, EV_DELETE, 0, 0, 0); - ::kevent(kqueue_fd_, events, descriptor_data->num_kevents_, 0, 0, 0); - - op_queue ops; - for (int i = 0; i < max_ops; ++i) - ops.push(descriptor_data->op_queue_[i]); - - descriptor_data->descriptor_ = -1; - descriptor_data->shutdown_ = true; - - descriptor_lock.unlock(); - - ASIO_HANDLER_REACTOR_DEREGISTRATION(( - context(), static_cast(descriptor), - reinterpret_cast(descriptor_data))); - - // Leave descriptor_data set so that it will be freed by the subsequent - // call to cleanup_descriptor_data. - } - else - { - // We are shutting down, so prevent cleanup_descriptor_data from freeing - // the descriptor_data object and let the destructor free it instead. - descriptor_data = 0; - } -} - -void kqueue_reactor::cleanup_descriptor_data( - per_descriptor_data& descriptor_data) -{ - if (descriptor_data) - { - free_descriptor_state(descriptor_data); - descriptor_data = 0; - } -} - -void kqueue_reactor::run(long usec, op_queue& ops) -{ - mutex::scoped_lock lock(mutex_); - - // Determine how long to block while waiting for events. - timespec timeout_buf = { 0, 0 }; - timespec* timeout = usec ? get_timeout(usec, timeout_buf) : &timeout_buf; - - lock.unlock(); - - // Block on the kqueue descriptor. - struct kevent events[128]; - int num_events = kevent(kqueue_fd_, 0, 0, events, 128, timeout); - -#if defined(ASIO_ENABLE_HANDLER_TRACKING) - // Trace the waiting events. - for (int i = 0; i < num_events; ++i) - { - void* ptr = reinterpret_cast(events[i].udata); - if (ptr != &interrupter_) - { - unsigned event_mask = 0; - switch (events[i].filter) - { - case EVFILT_READ: - event_mask |= ASIO_HANDLER_REACTOR_READ_EVENT; - break; - case EVFILT_WRITE: - event_mask |= ASIO_HANDLER_REACTOR_WRITE_EVENT; - break; - } - if ((events[i].flags & (EV_ERROR | EV_OOBAND)) != 0) - event_mask |= ASIO_HANDLER_REACTOR_ERROR_EVENT; - ASIO_HANDLER_REACTOR_EVENTS((context(), - reinterpret_cast(ptr), event_mask)); - } - } -#endif // defined(ASIO_ENABLE_HANDLER_TRACKING) - - // Dispatch the waiting events. - for (int i = 0; i < num_events; ++i) - { - void* ptr = reinterpret_cast(events[i].udata); - if (ptr == &interrupter_) - { - interrupter_.reset(); - } - else - { - descriptor_state* descriptor_data = static_cast(ptr); - mutex::scoped_lock descriptor_lock(descriptor_data->mutex_); - - if (events[i].filter == EVFILT_WRITE - && descriptor_data->num_kevents_ == 2 - && descriptor_data->op_queue_[write_op].empty()) - { - // Some descriptor types, like serial ports, don't seem to support - // EV_CLEAR with EVFILT_WRITE. Since we have no pending write - // operations we'll remove the EVFILT_WRITE registration here so that - // we don't end up in a tight spin. - struct kevent delete_events[1]; - ASIO_KQUEUE_EV_SET(&delete_events[0], - descriptor_data->descriptor_, EVFILT_WRITE, EV_DELETE, 0, 0, 0); - ::kevent(kqueue_fd_, delete_events, 1, 0, 0, 0); - descriptor_data->num_kevents_ = 1; - } - - // Exception operations must be processed first to ensure that any - // out-of-band data is read before normal data. -#if defined(__NetBSD__) - static const unsigned int filter[max_ops] = -#else - static const int filter[max_ops] = -#endif - { EVFILT_READ, EVFILT_WRITE, EVFILT_READ }; - for (int j = max_ops - 1; j >= 0; --j) - { - if (events[i].filter == filter[j]) - { - if (j != except_op || events[i].flags & EV_OOBAND) - { - while (reactor_op* op = descriptor_data->op_queue_[j].front()) - { - if (events[i].flags & EV_ERROR) - { - op->ec_ = asio::error_code( - static_cast(events[i].data), - asio::error::get_system_category()); - descriptor_data->op_queue_[j].pop(); - ops.push(op); - } - if (op->perform()) - { - descriptor_data->op_queue_[j].pop(); - ops.push(op); - } - else - break; - } - } - } - } - } - } - - lock.lock(); - timer_queues_.get_ready_timers(ops); -} - -void kqueue_reactor::interrupt() -{ - interrupter_.interrupt(); -} - -int kqueue_reactor::do_kqueue_create() -{ - int fd = ::kqueue(); - if (fd == -1) - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "kqueue"); - } - return fd; -} - -kqueue_reactor::descriptor_state* kqueue_reactor::allocate_descriptor_state() -{ - mutex::scoped_lock descriptors_lock(registered_descriptors_mutex_); - return registered_descriptors_.alloc(ASIO_CONCURRENCY_HINT_IS_LOCKING( - REACTOR_IO, scheduler_.concurrency_hint())); -} - -void kqueue_reactor::free_descriptor_state(kqueue_reactor::descriptor_state* s) -{ - mutex::scoped_lock descriptors_lock(registered_descriptors_mutex_); - registered_descriptors_.free(s); -} - -void kqueue_reactor::do_add_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.insert(&queue); -} - -void kqueue_reactor::do_remove_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.erase(&queue); -} - -timespec* kqueue_reactor::get_timeout(long usec, timespec& ts) -{ - // By default we will wait no longer than 5 minutes. This will ensure that - // any changes to the system clock are detected after no longer than this. - const long max_usec = 5 * 60 * 1000 * 1000; - usec = timer_queues_.wait_duration_usec( - (usec < 0 || max_usec < usec) ? max_usec : usec); - ts.tv_sec = usec / 1000000; - ts.tv_nsec = (usec % 1000000) * 1000; - return &ts; -} - -} // namespace detail -} // namespace asio - -#undef ASIO_KQUEUE_EV_SET - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_KQUEUE) - -#endif // ASIO_DETAIL_IMPL_KQUEUE_REACTOR_IPP diff --git a/scout_sdk/asio/asio/detail/impl/null_event.ipp b/scout_sdk/asio/asio/detail/impl/null_event.ipp deleted file mode 100644 index 22ade40..0000000 --- a/scout_sdk/asio/asio/detail/impl/null_event.ipp +++ /dev/null @@ -1,74 +0,0 @@ -// -// detail/impl/null_event.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_NULL_EVENT_IPP -#define ASIO_DETAIL_IMPL_NULL_EVENT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# include "asio/detail/socket_types.hpp" -#else -# include -# if defined(__hpux) -# include -# endif -# if !defined(__hpux) || defined(__SELECT) -# include -# endif -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -void null_event::do_wait() -{ -#if defined(ASIO_WINDOWS_RUNTIME) - std::this_thread::sleep_until((std::chrono::steady_clock::time_point::max)()); -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ::Sleep(INFINITE); -#else - ::pause(); -#endif -} - -void null_event::do_wait_for_usec(long usec) -{ -#if defined(ASIO_WINDOWS_RUNTIME) - std::this_thread::sleep_for(std::chrono::microseconds(usec)); -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ::Sleep(usec / 1000); -#elif defined(__hpux) && defined(__SELECT) - timespec ts; - ts.tv_sec = usec / 1000000; - ts.tv_nsec = (usec % 1000000) * 1000; - ::pselect(0, 0, 0, 0, &ts, 0); -#else - timeval tv; - tv.tv_sec = usec / 1000000; - tv.tv_usec = usec % 1000000; - ::select(0, 0, 0, 0, &tv); -#endif -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_NULL_EVENT_IPP diff --git a/scout_sdk/asio/asio/detail/impl/pipe_select_interrupter.ipp b/scout_sdk/asio/asio/detail/impl/pipe_select_interrupter.ipp deleted file mode 100644 index 13931ab..0000000 --- a/scout_sdk/asio/asio/detail/impl/pipe_select_interrupter.ipp +++ /dev/null @@ -1,124 +0,0 @@ -// -// detail/impl/pipe_select_interrupter.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_PIPE_SELECT_INTERRUPTER_IPP -#define ASIO_DETAIL_IMPL_PIPE_SELECT_INTERRUPTER_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS_RUNTIME) -#if !defined(ASIO_WINDOWS) -#if !defined(__CYGWIN__) -#if !defined(__SYMBIAN32__) -#if !defined(ASIO_HAS_EVENTFD) - -#include -#include -#include -#include -#include "asio/detail/pipe_select_interrupter.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -pipe_select_interrupter::pipe_select_interrupter() -{ - open_descriptors(); -} - -void pipe_select_interrupter::open_descriptors() -{ - int pipe_fds[2]; - if (pipe(pipe_fds) == 0) - { - read_descriptor_ = pipe_fds[0]; - ::fcntl(read_descriptor_, F_SETFL, O_NONBLOCK); - write_descriptor_ = pipe_fds[1]; - ::fcntl(write_descriptor_, F_SETFL, O_NONBLOCK); - -#if defined(FD_CLOEXEC) - ::fcntl(read_descriptor_, F_SETFD, FD_CLOEXEC); - ::fcntl(write_descriptor_, F_SETFD, FD_CLOEXEC); -#endif // defined(FD_CLOEXEC) - } - else - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "pipe_select_interrupter"); - } -} - -pipe_select_interrupter::~pipe_select_interrupter() -{ - close_descriptors(); -} - -void pipe_select_interrupter::close_descriptors() -{ - if (read_descriptor_ != -1) - ::close(read_descriptor_); - if (write_descriptor_ != -1) - ::close(write_descriptor_); -} - -void pipe_select_interrupter::recreate() -{ - close_descriptors(); - - write_descriptor_ = -1; - read_descriptor_ = -1; - - open_descriptors(); -} - -void pipe_select_interrupter::interrupt() -{ - char byte = 0; - signed_size_type result = ::write(write_descriptor_, &byte, 1); - (void)result; -} - -bool pipe_select_interrupter::reset() -{ - for (;;) - { - char data[1024]; - signed_size_type bytes_read = ::read(read_descriptor_, data, sizeof(data)); - if (bytes_read < 0 && errno == EINTR) - continue; - bool was_interrupted = (bytes_read > 0); - while (bytes_read == sizeof(data)) - bytes_read = ::read(read_descriptor_, data, sizeof(data)); - return was_interrupted; - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_EVENTFD) -#endif // !defined(__SYMBIAN32__) -#endif // !defined(__CYGWIN__) -#endif // !defined(ASIO_WINDOWS) -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_IMPL_PIPE_SELECT_INTERRUPTER_IPP diff --git a/scout_sdk/asio/asio/detail/impl/posix_event.ipp b/scout_sdk/asio/asio/detail/impl/posix_event.ipp deleted file mode 100644 index 4b46ab0..0000000 --- a/scout_sdk/asio/asio/detail/impl/posix_event.ipp +++ /dev/null @@ -1,59 +0,0 @@ -// -// detail/impl/posix_event.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_POSIX_EVENT_IPP -#define ASIO_DETAIL_IMPL_POSIX_EVENT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include "asio/detail/posix_event.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -posix_event::posix_event() - : state_(0) -{ -#if (defined(__MACH__) && defined(__APPLE__)) \ - || (defined(__ANDROID__) && (__ANDROID_API__ < 21)) - int error = ::pthread_cond_init(&cond_, 0); -#else // (defined(__MACH__) && defined(__APPLE__)) - // || (defined(__ANDROID__) && (__ANDROID_API__ < 21)) - ::pthread_condattr_t attr; - ::pthread_condattr_init(&attr); - int error = ::pthread_condattr_setclock(&attr, CLOCK_MONOTONIC); - if (error == 0) - error = ::pthread_cond_init(&cond_, &attr); -#endif // (defined(__MACH__) && defined(__APPLE__)) - // || (defined(__ANDROID__) && (__ANDROID_API__ < 21)) - - asio::error_code ec(error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "event"); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_IMPL_POSIX_EVENT_IPP diff --git a/scout_sdk/asio/asio/detail/impl/posix_mutex.ipp b/scout_sdk/asio/asio/detail/impl/posix_mutex.ipp deleted file mode 100644 index 27272b5..0000000 --- a/scout_sdk/asio/asio/detail/impl/posix_mutex.ipp +++ /dev/null @@ -1,46 +0,0 @@ -// -// detail/impl/posix_mutex.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_POSIX_MUTEX_IPP -#define ASIO_DETAIL_IMPL_POSIX_MUTEX_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include "asio/detail/posix_mutex.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -posix_mutex::posix_mutex() -{ - int error = ::pthread_mutex_init(&mutex_, 0); - asio::error_code ec(error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "mutex"); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_IMPL_POSIX_MUTEX_IPP diff --git a/scout_sdk/asio/asio/detail/impl/posix_thread.ipp b/scout_sdk/asio/asio/detail/impl/posix_thread.ipp deleted file mode 100644 index 69bd16f..0000000 --- a/scout_sdk/asio/asio/detail/impl/posix_thread.ipp +++ /dev/null @@ -1,84 +0,0 @@ -// -// detail/impl/posix_thread.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_POSIX_THREAD_IPP -#define ASIO_DETAIL_IMPL_POSIX_THREAD_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include "asio/detail/posix_thread.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -posix_thread::~posix_thread() -{ - if (!joined_) - ::pthread_detach(thread_); -} - -void posix_thread::join() -{ - if (!joined_) - { - ::pthread_join(thread_, 0); - joined_ = true; - } -} - -std::size_t posix_thread::hardware_concurrency() -{ -#if defined(_SC_NPROCESSORS_ONLN) - long result = sysconf(_SC_NPROCESSORS_ONLN); - if (result > 0) - return result; -#endif // defined(_SC_NPROCESSORS_ONLN) - return 0; -} - -void posix_thread::start_thread(func_base* arg) -{ - int error = ::pthread_create(&thread_, 0, - asio_detail_posix_thread_function, arg); - if (error != 0) - { - delete arg; - asio::error_code ec(error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "thread"); - } -} - -void* asio_detail_posix_thread_function(void* arg) -{ - posix_thread::auto_func_base_ptr func = { - static_cast(arg) }; - func.ptr->run(); - return 0; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_IMPL_POSIX_THREAD_IPP diff --git a/scout_sdk/asio/asio/detail/impl/posix_tss_ptr.ipp b/scout_sdk/asio/asio/detail/impl/posix_tss_ptr.ipp deleted file mode 100644 index 54b58bd..0000000 --- a/scout_sdk/asio/asio/detail/impl/posix_tss_ptr.ipp +++ /dev/null @@ -1,46 +0,0 @@ -// -// detail/impl/posix_tss_ptr.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_POSIX_TSS_PTR_IPP -#define ASIO_DETAIL_IMPL_POSIX_TSS_PTR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include "asio/detail/posix_tss_ptr.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -void posix_tss_ptr_create(pthread_key_t& key) -{ - int error = ::pthread_key_create(&key, 0); - asio::error_code ec(error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "tss"); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_IMPL_POSIX_TSS_PTR_IPP diff --git a/scout_sdk/asio/asio/detail/impl/reactive_descriptor_service.ipp b/scout_sdk/asio/asio/detail/impl/reactive_descriptor_service.ipp deleted file mode 100644 index f9505ca..0000000 --- a/scout_sdk/asio/asio/detail/impl/reactive_descriptor_service.ipp +++ /dev/null @@ -1,222 +0,0 @@ -// -// detail/impl/reactive_descriptor_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_REACTIVE_DESCRIPTOR_SERVICE_IPP -#define ASIO_DETAIL_IMPL_REACTIVE_DESCRIPTOR_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - -#include "asio/error.hpp" -#include "asio/detail/reactive_descriptor_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -reactive_descriptor_service::reactive_descriptor_service( - asio::io_context& io_context) - : service_base(io_context), - reactor_(asio::use_service(io_context)) -{ - reactor_.init_task(); -} - -void reactive_descriptor_service::shutdown() -{ -} - -void reactive_descriptor_service::construct( - reactive_descriptor_service::implementation_type& impl) -{ - impl.descriptor_ = -1; - impl.state_ = 0; -} - -void reactive_descriptor_service::move_construct( - reactive_descriptor_service::implementation_type& impl, - reactive_descriptor_service::implementation_type& other_impl) -{ - impl.descriptor_ = other_impl.descriptor_; - other_impl.descriptor_ = -1; - - impl.state_ = other_impl.state_; - other_impl.state_ = 0; - - reactor_.move_descriptor(impl.descriptor_, - impl.reactor_data_, other_impl.reactor_data_); -} - -void reactive_descriptor_service::move_assign( - reactive_descriptor_service::implementation_type& impl, - reactive_descriptor_service& other_service, - reactive_descriptor_service::implementation_type& other_impl) -{ - destroy(impl); - - impl.descriptor_ = other_impl.descriptor_; - other_impl.descriptor_ = -1; - - impl.state_ = other_impl.state_; - other_impl.state_ = 0; - - other_service.reactor_.move_descriptor(impl.descriptor_, - impl.reactor_data_, other_impl.reactor_data_); -} - -void reactive_descriptor_service::destroy( - reactive_descriptor_service::implementation_type& impl) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((reactor_.context(), - "descriptor", &impl, impl.descriptor_, "close")); - - reactor_.deregister_descriptor(impl.descriptor_, impl.reactor_data_, - (impl.state_ & descriptor_ops::possible_dup) == 0); - - asio::error_code ignored_ec; - descriptor_ops::close(impl.descriptor_, impl.state_, ignored_ec); - - reactor_.cleanup_descriptor_data(impl.reactor_data_); - } -} - -asio::error_code reactive_descriptor_service::assign( - reactive_descriptor_service::implementation_type& impl, - const native_handle_type& native_descriptor, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - if (int err = reactor_.register_descriptor( - native_descriptor, impl.reactor_data_)) - { - ec = asio::error_code(err, - asio::error::get_system_category()); - return ec; - } - - impl.descriptor_ = native_descriptor; - impl.state_ = descriptor_ops::possible_dup; - ec = asio::error_code(); - return ec; -} - -asio::error_code reactive_descriptor_service::close( - reactive_descriptor_service::implementation_type& impl, - asio::error_code& ec) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((reactor_.context(), - "descriptor", &impl, impl.descriptor_, "close")); - - reactor_.deregister_descriptor(impl.descriptor_, impl.reactor_data_, - (impl.state_ & descriptor_ops::possible_dup) == 0); - - descriptor_ops::close(impl.descriptor_, impl.state_, ec); - - reactor_.cleanup_descriptor_data(impl.reactor_data_); - } - else - { - ec = asio::error_code(); - } - - // The descriptor is closed by the OS even if close() returns an error. - // - // (Actually, POSIX says the state of the descriptor is unspecified. On - // Linux the descriptor is apparently closed anyway; e.g. see - // http://lkml.org/lkml/2005/9/10/129 - // We'll just have to assume that other OSes follow the same behaviour.) - construct(impl); - - return ec; -} - -reactive_descriptor_service::native_handle_type -reactive_descriptor_service::release( - reactive_descriptor_service::implementation_type& impl) -{ - native_handle_type descriptor = impl.descriptor_; - - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((reactor_.context(), - "descriptor", &impl, impl.descriptor_, "release")); - - reactor_.deregister_descriptor(impl.descriptor_, impl.reactor_data_, false); - reactor_.cleanup_descriptor_data(impl.reactor_data_); - construct(impl); - } - - return descriptor; -} - -asio::error_code reactive_descriptor_service::cancel( - reactive_descriptor_service::implementation_type& impl, - asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return ec; - } - - ASIO_HANDLER_OPERATION((reactor_.context(), - "descriptor", &impl, impl.descriptor_, "cancel")); - - reactor_.cancel_ops(impl.descriptor_, impl.reactor_data_); - ec = asio::error_code(); - return ec; -} - -void reactive_descriptor_service::start_op( - reactive_descriptor_service::implementation_type& impl, - int op_type, reactor_op* op, bool is_continuation, - bool is_non_blocking, bool noop) -{ - if (!noop) - { - if ((impl.state_ & descriptor_ops::non_blocking) || - descriptor_ops::set_internal_non_blocking( - impl.descriptor_, impl.state_, true, op->ec_)) - { - reactor_.start_op(op_type, impl.descriptor_, - impl.reactor_data_, op, is_continuation, is_non_blocking); - return; - } - } - - reactor_.post_immediate_completion(op, is_continuation); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - -#endif // ASIO_DETAIL_IMPL_REACTIVE_DESCRIPTOR_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/reactive_serial_port_service.ipp b/scout_sdk/asio/asio/detail/impl/reactive_serial_port_service.ipp deleted file mode 100644 index c907835..0000000 --- a/scout_sdk/asio/asio/detail/impl/reactive_serial_port_service.ipp +++ /dev/null @@ -1,152 +0,0 @@ -// -// detail/impl/reactive_serial_port_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_REACTIVE_SERIAL_PORT_SERVICE_IPP -#define ASIO_DETAIL_IMPL_REACTIVE_SERIAL_PORT_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_SERIAL_PORT) -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#include -#include "asio/detail/reactive_serial_port_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -reactive_serial_port_service::reactive_serial_port_service( - asio::io_context& io_context) - : service_base(io_context), - descriptor_service_(io_context) -{ -} - -void reactive_serial_port_service::shutdown() -{ - descriptor_service_.shutdown(); -} - -asio::error_code reactive_serial_port_service::open( - reactive_serial_port_service::implementation_type& impl, - const std::string& device, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - descriptor_ops::state_type state = 0; - int fd = descriptor_ops::open(device.c_str(), - O_RDWR | O_NONBLOCK | O_NOCTTY, ec); - if (fd < 0) - return ec; - - int s = descriptor_ops::fcntl(fd, F_GETFL, ec); - if (s >= 0) - s = descriptor_ops::fcntl(fd, F_SETFL, s | O_NONBLOCK, ec); - if (s < 0) - { - asio::error_code ignored_ec; - descriptor_ops::close(fd, state, ignored_ec); - return ec; - } - - // Set up default serial port options. - termios ios; - errno = 0; - s = descriptor_ops::error_wrapper(::tcgetattr(fd, &ios), ec); - if (s >= 0) - { -#if defined(_BSD_SOURCE) || defined(_DEFAULT_SOURCE) - ::cfmakeraw(&ios); -#else - ios.c_iflag &= ~(IGNBRK | BRKINT | PARMRK - | ISTRIP | INLCR | IGNCR | ICRNL | IXON); - ios.c_oflag &= ~OPOST; - ios.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN); - ios.c_cflag &= ~(CSIZE | PARENB); - ios.c_cflag |= CS8; -#endif - ios.c_iflag |= IGNPAR; - ios.c_cflag |= CREAD | CLOCAL; - errno = 0; - s = descriptor_ops::error_wrapper(::tcsetattr(fd, TCSANOW, &ios), ec); - } - if (s < 0) - { - asio::error_code ignored_ec; - descriptor_ops::close(fd, state, ignored_ec); - return ec; - } - - // We're done. Take ownership of the serial port descriptor. - if (descriptor_service_.assign(impl, fd, ec)) - { - asio::error_code ignored_ec; - descriptor_ops::close(fd, state, ignored_ec); - } - - return ec; -} - -asio::error_code reactive_serial_port_service::do_set_option( - reactive_serial_port_service::implementation_type& impl, - reactive_serial_port_service::store_function_type store, - const void* option, asio::error_code& ec) -{ - termios ios; - errno = 0; - descriptor_ops::error_wrapper(::tcgetattr( - descriptor_service_.native_handle(impl), &ios), ec); - if (ec) - return ec; - - if (store(option, ios, ec)) - return ec; - - errno = 0; - descriptor_ops::error_wrapper(::tcsetattr( - descriptor_service_.native_handle(impl), TCSANOW, &ios), ec); - return ec; -} - -asio::error_code reactive_serial_port_service::do_get_option( - const reactive_serial_port_service::implementation_type& impl, - reactive_serial_port_service::load_function_type load, - void* option, asio::error_code& ec) const -{ - termios ios; - errno = 0; - descriptor_ops::error_wrapper(::tcgetattr( - descriptor_service_.native_handle(impl), &ios), ec); - if (ec) - return ec; - - return load(option, ios, ec); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) -#endif // defined(ASIO_HAS_SERIAL_PORT) - -#endif // ASIO_DETAIL_IMPL_REACTIVE_SERIAL_PORT_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/reactive_socket_service_base.ipp b/scout_sdk/asio/asio/detail/impl/reactive_socket_service_base.ipp deleted file mode 100644 index 129b851..0000000 --- a/scout_sdk/asio/asio/detail/impl/reactive_socket_service_base.ipp +++ /dev/null @@ -1,300 +0,0 @@ -// -// detail/reactive_socket_service_base.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_REACTIVE_SOCKET_SERVICE_BASE_IPP -#define ASIO_DETAIL_IMPL_REACTIVE_SOCKET_SERVICE_BASE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_IOCP) \ - && !defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/reactive_socket_service_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -reactive_socket_service_base::reactive_socket_service_base( - asio::io_context& io_context) - : io_context_(io_context), - reactor_(use_service(io_context)) -{ - reactor_.init_task(); -} - -void reactive_socket_service_base::base_shutdown() -{ -} - -void reactive_socket_service_base::construct( - reactive_socket_service_base::base_implementation_type& impl) -{ - impl.socket_ = invalid_socket; - impl.state_ = 0; -} - -void reactive_socket_service_base::base_move_construct( - reactive_socket_service_base::base_implementation_type& impl, - reactive_socket_service_base::base_implementation_type& other_impl) -{ - impl.socket_ = other_impl.socket_; - other_impl.socket_ = invalid_socket; - - impl.state_ = other_impl.state_; - other_impl.state_ = 0; - - reactor_.move_descriptor(impl.socket_, - impl.reactor_data_, other_impl.reactor_data_); -} - -void reactive_socket_service_base::base_move_assign( - reactive_socket_service_base::base_implementation_type& impl, - reactive_socket_service_base& other_service, - reactive_socket_service_base::base_implementation_type& other_impl) -{ - destroy(impl); - - impl.socket_ = other_impl.socket_; - other_impl.socket_ = invalid_socket; - - impl.state_ = other_impl.state_; - other_impl.state_ = 0; - - other_service.reactor_.move_descriptor(impl.socket_, - impl.reactor_data_, other_impl.reactor_data_); -} - -void reactive_socket_service_base::destroy( - reactive_socket_service_base::base_implementation_type& impl) -{ - if (impl.socket_ != invalid_socket) - { - ASIO_HANDLER_OPERATION((reactor_.context(), - "socket", &impl, impl.socket_, "close")); - - reactor_.deregister_descriptor(impl.socket_, impl.reactor_data_, - (impl.state_ & socket_ops::possible_dup) == 0); - - asio::error_code ignored_ec; - socket_ops::close(impl.socket_, impl.state_, true, ignored_ec); - - reactor_.cleanup_descriptor_data(impl.reactor_data_); - } -} - -asio::error_code reactive_socket_service_base::close( - reactive_socket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((reactor_.context(), - "socket", &impl, impl.socket_, "close")); - - reactor_.deregister_descriptor(impl.socket_, impl.reactor_data_, - (impl.state_ & socket_ops::possible_dup) == 0); - - socket_ops::close(impl.socket_, impl.state_, false, ec); - - reactor_.cleanup_descriptor_data(impl.reactor_data_); - } - else - { - ec = asio::error_code(); - } - - // The descriptor is closed by the OS even if close() returns an error. - // - // (Actually, POSIX says the state of the descriptor is unspecified. On - // Linux the descriptor is apparently closed anyway; e.g. see - // http://lkml.org/lkml/2005/9/10/129 - // We'll just have to assume that other OSes follow the same behaviour. The - // known exception is when Windows's closesocket() function fails with - // WSAEWOULDBLOCK, but this case is handled inside socket_ops::close(). - construct(impl); - - return ec; -} - -socket_type reactive_socket_service_base::release( - reactive_socket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return invalid_socket; - } - - ASIO_HANDLER_OPERATION((reactor_.context(), - "socket", &impl, impl.socket_, "release")); - - reactor_.deregister_descriptor(impl.socket_, impl.reactor_data_, false); - reactor_.cleanup_descriptor_data(impl.reactor_data_); - socket_type sock = impl.socket_; - construct(impl); - ec = asio::error_code(); - return sock; -} - -asio::error_code reactive_socket_service_base::cancel( - reactive_socket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return ec; - } - - ASIO_HANDLER_OPERATION((reactor_.context(), - "socket", &impl, impl.socket_, "cancel")); - - reactor_.cancel_ops(impl.socket_, impl.reactor_data_); - ec = asio::error_code(); - return ec; -} - -asio::error_code reactive_socket_service_base::do_open( - reactive_socket_service_base::base_implementation_type& impl, - int af, int type, int protocol, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - socket_holder sock(socket_ops::socket(af, type, protocol, ec)); - if (sock.get() == invalid_socket) - return ec; - - if (int err = reactor_.register_descriptor(sock.get(), impl.reactor_data_)) - { - ec = asio::error_code(err, - asio::error::get_system_category()); - return ec; - } - - impl.socket_ = sock.release(); - switch (type) - { - case SOCK_STREAM: impl.state_ = socket_ops::stream_oriented; break; - case SOCK_DGRAM: impl.state_ = socket_ops::datagram_oriented; break; - default: impl.state_ = 0; break; - } - ec = asio::error_code(); - return ec; -} - -asio::error_code reactive_socket_service_base::do_assign( - reactive_socket_service_base::base_implementation_type& impl, int type, - const reactive_socket_service_base::native_handle_type& native_socket, - asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - if (int err = reactor_.register_descriptor( - native_socket, impl.reactor_data_)) - { - ec = asio::error_code(err, - asio::error::get_system_category()); - return ec; - } - - impl.socket_ = native_socket; - switch (type) - { - case SOCK_STREAM: impl.state_ = socket_ops::stream_oriented; break; - case SOCK_DGRAM: impl.state_ = socket_ops::datagram_oriented; break; - default: impl.state_ = 0; break; - } - impl.state_ |= socket_ops::possible_dup; - ec = asio::error_code(); - return ec; -} - -void reactive_socket_service_base::start_op( - reactive_socket_service_base::base_implementation_type& impl, - int op_type, reactor_op* op, bool is_continuation, - bool is_non_blocking, bool noop) -{ - if (!noop) - { - if ((impl.state_ & socket_ops::non_blocking) - || socket_ops::set_internal_non_blocking( - impl.socket_, impl.state_, true, op->ec_)) - { - reactor_.start_op(op_type, impl.socket_, - impl.reactor_data_, op, is_continuation, is_non_blocking); - return; - } - } - - reactor_.post_immediate_completion(op, is_continuation); -} - -void reactive_socket_service_base::start_accept_op( - reactive_socket_service_base::base_implementation_type& impl, - reactor_op* op, bool is_continuation, bool peer_is_open) -{ - if (!peer_is_open) - start_op(impl, reactor::read_op, op, is_continuation, true, false); - else - { - op->ec_ = asio::error::already_open; - reactor_.post_immediate_completion(op, is_continuation); - } -} - -void reactive_socket_service_base::start_connect_op( - reactive_socket_service_base::base_implementation_type& impl, - reactor_op* op, bool is_continuation, - const socket_addr_type* addr, size_t addrlen) -{ - if ((impl.state_ & socket_ops::non_blocking) - || socket_ops::set_internal_non_blocking( - impl.socket_, impl.state_, true, op->ec_)) - { - if (socket_ops::connect(impl.socket_, addr, addrlen, op->ec_) != 0) - { - if (op->ec_ == asio::error::in_progress - || op->ec_ == asio::error::would_block) - { - op->ec_ = asio::error_code(); - reactor_.start_op(reactor::connect_op, impl.socket_, - impl.reactor_data_, op, is_continuation, false); - return; - } - } - } - - reactor_.post_immediate_completion(op, is_continuation); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_IOCP) - // && !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_IMPL_REACTIVE_SOCKET_SERVICE_BASE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/resolver_service_base.ipp b/scout_sdk/asio/asio/detail/impl/resolver_service_base.ipp deleted file mode 100644 index 540bb66..0000000 --- a/scout_sdk/asio/asio/detail/impl/resolver_service_base.ipp +++ /dev/null @@ -1,154 +0,0 @@ -// -// detail/impl/resolver_service_base.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_RESOLVER_SERVICE_BASE_IPP -#define ASIO_DETAIL_IMPL_RESOLVER_SERVICE_BASE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/resolver_service_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class resolver_service_base::work_io_context_runner -{ -public: - work_io_context_runner(asio::io_context& io_context) - : io_context_(io_context) {} - void operator()() { io_context_.run(); } -private: - asio::io_context& io_context_; -}; - -resolver_service_base::resolver_service_base( - asio::io_context& io_context) - : io_context_impl_(asio::use_service(io_context)), - work_io_context_(new asio::io_context(-1)), - work_io_context_impl_(asio::use_service< - io_context_impl>(*work_io_context_)), - work_(asio::make_work_guard(*work_io_context_)), - work_thread_(0) -{ -} - -resolver_service_base::~resolver_service_base() -{ - base_shutdown(); -} - -void resolver_service_base::base_shutdown() -{ - work_.reset(); - if (work_io_context_.get()) - { - work_io_context_->stop(); - if (work_thread_.get()) - { - work_thread_->join(); - work_thread_.reset(); - } - work_io_context_.reset(); - } -} - -void resolver_service_base::base_notify_fork( - asio::io_context::fork_event fork_ev) -{ - if (work_thread_.get()) - { - if (fork_ev == asio::io_context::fork_prepare) - { - work_io_context_->stop(); - work_thread_->join(); - } - else - { - work_io_context_->restart(); - work_thread_.reset(new asio::detail::thread( - work_io_context_runner(*work_io_context_))); - } - } -} - -void resolver_service_base::construct( - resolver_service_base::implementation_type& impl) -{ - impl.reset(static_cast(0), socket_ops::noop_deleter()); -} - -void resolver_service_base::destroy( - resolver_service_base::implementation_type& impl) -{ - ASIO_HANDLER_OPERATION((io_context_impl_.context(), - "resolver", &impl, 0, "cancel")); - - impl.reset(); -} - -void resolver_service_base::move_construct(implementation_type& impl, - implementation_type& other_impl) -{ - impl = ASIO_MOVE_CAST(implementation_type)(other_impl); -} - -void resolver_service_base::move_assign(implementation_type& impl, - resolver_service_base&, implementation_type& other_impl) -{ - destroy(impl); - impl = ASIO_MOVE_CAST(implementation_type)(other_impl); -} - -void resolver_service_base::cancel( - resolver_service_base::implementation_type& impl) -{ - ASIO_HANDLER_OPERATION((io_context_impl_.context(), - "resolver", &impl, 0, "cancel")); - - impl.reset(static_cast(0), socket_ops::noop_deleter()); -} - -void resolver_service_base::start_resolve_op(resolve_op* op) -{ - if (ASIO_CONCURRENCY_HINT_IS_LOCKING(SCHEDULER, - io_context_impl_.concurrency_hint())) - { - start_work_thread(); - io_context_impl_.work_started(); - work_io_context_impl_.post_immediate_completion(op, false); - } - else - { - op->ec_ = asio::error::operation_not_supported; - io_context_impl_.post_immediate_completion(op, false); - } -} - -void resolver_service_base::start_work_thread() -{ - asio::detail::mutex::scoped_lock lock(mutex_); - if (!work_thread_.get()) - { - work_thread_.reset(new asio::detail::thread( - work_io_context_runner(*work_io_context_))); - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_RESOLVER_SERVICE_BASE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/scheduler.ipp b/scout_sdk/asio/asio/detail/impl/scheduler.ipp deleted file mode 100644 index 35bc678..0000000 --- a/scout_sdk/asio/asio/detail/impl/scheduler.ipp +++ /dev/null @@ -1,571 +0,0 @@ -// -// detail/impl/scheduler.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_SCHEDULER_IPP -#define ASIO_DETAIL_IMPL_SCHEDULER_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/concurrency_hint.hpp" -#include "asio/detail/event.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/reactor.hpp" -#include "asio/detail/scheduler.hpp" -#include "asio/detail/scheduler_thread_info.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct scheduler::task_cleanup -{ - ~task_cleanup() - { - if (this_thread_->private_outstanding_work > 0) - { - asio::detail::increment( - scheduler_->outstanding_work_, - this_thread_->private_outstanding_work); - } - this_thread_->private_outstanding_work = 0; - - // Enqueue the completed operations and reinsert the task at the end of - // the operation queue. - lock_->lock(); - scheduler_->task_interrupted_ = true; - scheduler_->op_queue_.push(this_thread_->private_op_queue); - scheduler_->op_queue_.push(&scheduler_->task_operation_); - } - - scheduler* scheduler_; - mutex::scoped_lock* lock_; - thread_info* this_thread_; -}; - -struct scheduler::work_cleanup -{ - ~work_cleanup() - { - if (this_thread_->private_outstanding_work > 1) - { - asio::detail::increment( - scheduler_->outstanding_work_, - this_thread_->private_outstanding_work - 1); - } - else if (this_thread_->private_outstanding_work < 1) - { - scheduler_->work_finished(); - } - this_thread_->private_outstanding_work = 0; - -#if defined(ASIO_HAS_THREADS) - if (!this_thread_->private_op_queue.empty()) - { - lock_->lock(); - scheduler_->op_queue_.push(this_thread_->private_op_queue); - } -#endif // defined(ASIO_HAS_THREADS) - } - - scheduler* scheduler_; - mutex::scoped_lock* lock_; - thread_info* this_thread_; -}; - -scheduler::scheduler( - asio::execution_context& ctx, int concurrency_hint) - : asio::detail::execution_context_service_base(ctx), - one_thread_(concurrency_hint == 1 - || !ASIO_CONCURRENCY_HINT_IS_LOCKING( - SCHEDULER, concurrency_hint) - || !ASIO_CONCURRENCY_HINT_IS_LOCKING( - REACTOR_IO, concurrency_hint)), - mutex_(ASIO_CONCURRENCY_HINT_IS_LOCKING( - SCHEDULER, concurrency_hint)), - task_(0), - task_interrupted_(true), - outstanding_work_(0), - stopped_(false), - shutdown_(false), - concurrency_hint_(concurrency_hint) -{ - ASIO_HANDLER_TRACKING_INIT; -} - -void scheduler::shutdown() -{ - mutex::scoped_lock lock(mutex_); - shutdown_ = true; - lock.unlock(); - - // Destroy handler objects. - while (!op_queue_.empty()) - { - operation* o = op_queue_.front(); - op_queue_.pop(); - if (o != &task_operation_) - o->destroy(); - } - - // Reset to initial state. - task_ = 0; -} - -void scheduler::init_task() -{ - mutex::scoped_lock lock(mutex_); - if (!shutdown_ && !task_) - { - task_ = &use_service(this->context()); - op_queue_.push(&task_operation_); - wake_one_thread_and_unlock(lock); - } -} - -std::size_t scheduler::run(asio::error_code& ec) -{ - ec = asio::error_code(); - if (outstanding_work_ == 0) - { - stop(); - return 0; - } - - thread_info this_thread; - this_thread.private_outstanding_work = 0; - thread_call_stack::context ctx(this, this_thread); - - mutex::scoped_lock lock(mutex_); - - std::size_t n = 0; - for (; do_run_one(lock, this_thread, ec); lock.lock()) - if (n != (std::numeric_limits::max)()) - ++n; - return n; -} - -std::size_t scheduler::run_one(asio::error_code& ec) -{ - ec = asio::error_code(); - if (outstanding_work_ == 0) - { - stop(); - return 0; - } - - thread_info this_thread; - this_thread.private_outstanding_work = 0; - thread_call_stack::context ctx(this, this_thread); - - mutex::scoped_lock lock(mutex_); - - return do_run_one(lock, this_thread, ec); -} - -std::size_t scheduler::wait_one(long usec, asio::error_code& ec) -{ - ec = asio::error_code(); - if (outstanding_work_ == 0) - { - stop(); - return 0; - } - - thread_info this_thread; - this_thread.private_outstanding_work = 0; - thread_call_stack::context ctx(this, this_thread); - - mutex::scoped_lock lock(mutex_); - - return do_wait_one(lock, this_thread, usec, ec); -} - -std::size_t scheduler::poll(asio::error_code& ec) -{ - ec = asio::error_code(); - if (outstanding_work_ == 0) - { - stop(); - return 0; - } - - thread_info this_thread; - this_thread.private_outstanding_work = 0; - thread_call_stack::context ctx(this, this_thread); - - mutex::scoped_lock lock(mutex_); - -#if defined(ASIO_HAS_THREADS) - // We want to support nested calls to poll() and poll_one(), so any handlers - // that are already on a thread-private queue need to be put on to the main - // queue now. - if (one_thread_) - if (thread_info* outer_info = static_cast(ctx.next_by_key())) - op_queue_.push(outer_info->private_op_queue); -#endif // defined(ASIO_HAS_THREADS) - - std::size_t n = 0; - for (; do_poll_one(lock, this_thread, ec); lock.lock()) - if (n != (std::numeric_limits::max)()) - ++n; - return n; -} - -std::size_t scheduler::poll_one(asio::error_code& ec) -{ - ec = asio::error_code(); - if (outstanding_work_ == 0) - { - stop(); - return 0; - } - - thread_info this_thread; - this_thread.private_outstanding_work = 0; - thread_call_stack::context ctx(this, this_thread); - - mutex::scoped_lock lock(mutex_); - -#if defined(ASIO_HAS_THREADS) - // We want to support nested calls to poll() and poll_one(), so any handlers - // that are already on a thread-private queue need to be put on to the main - // queue now. - if (one_thread_) - if (thread_info* outer_info = static_cast(ctx.next_by_key())) - op_queue_.push(outer_info->private_op_queue); -#endif // defined(ASIO_HAS_THREADS) - - return do_poll_one(lock, this_thread, ec); -} - -void scheduler::stop() -{ - mutex::scoped_lock lock(mutex_); - stop_all_threads(lock); -} - -bool scheduler::stopped() const -{ - mutex::scoped_lock lock(mutex_); - return stopped_; -} - -void scheduler::restart() -{ - mutex::scoped_lock lock(mutex_); - stopped_ = false; -} - -void scheduler::compensating_work_started() -{ - thread_info_base* this_thread = thread_call_stack::contains(this); - ++static_cast(this_thread)->private_outstanding_work; -} - -void scheduler::post_immediate_completion( - scheduler::operation* op, bool is_continuation) -{ -#if defined(ASIO_HAS_THREADS) - if (one_thread_ || is_continuation) - { - if (thread_info_base* this_thread = thread_call_stack::contains(this)) - { - ++static_cast(this_thread)->private_outstanding_work; - static_cast(this_thread)->private_op_queue.push(op); - return; - } - } -#else // defined(ASIO_HAS_THREADS) - (void)is_continuation; -#endif // defined(ASIO_HAS_THREADS) - - work_started(); - mutex::scoped_lock lock(mutex_); - op_queue_.push(op); - wake_one_thread_and_unlock(lock); -} - -void scheduler::post_deferred_completion(scheduler::operation* op) -{ -#if defined(ASIO_HAS_THREADS) - if (one_thread_) - { - if (thread_info_base* this_thread = thread_call_stack::contains(this)) - { - static_cast(this_thread)->private_op_queue.push(op); - return; - } - } -#endif // defined(ASIO_HAS_THREADS) - - mutex::scoped_lock lock(mutex_); - op_queue_.push(op); - wake_one_thread_and_unlock(lock); -} - -void scheduler::post_deferred_completions( - op_queue& ops) -{ - if (!ops.empty()) - { -#if defined(ASIO_HAS_THREADS) - if (one_thread_) - { - if (thread_info_base* this_thread = thread_call_stack::contains(this)) - { - static_cast(this_thread)->private_op_queue.push(ops); - return; - } - } -#endif // defined(ASIO_HAS_THREADS) - - mutex::scoped_lock lock(mutex_); - op_queue_.push(ops); - wake_one_thread_and_unlock(lock); - } -} - -void scheduler::do_dispatch( - scheduler::operation* op) -{ - work_started(); - mutex::scoped_lock lock(mutex_); - op_queue_.push(op); - wake_one_thread_and_unlock(lock); -} - -void scheduler::abandon_operations( - op_queue& ops) -{ - op_queue ops2; - ops2.push(ops); -} - -std::size_t scheduler::do_run_one(mutex::scoped_lock& lock, - scheduler::thread_info& this_thread, - const asio::error_code& ec) -{ - while (!stopped_) - { - if (!op_queue_.empty()) - { - // Prepare to execute first handler from queue. - operation* o = op_queue_.front(); - op_queue_.pop(); - bool more_handlers = (!op_queue_.empty()); - - if (o == &task_operation_) - { - task_interrupted_ = more_handlers; - - if (more_handlers && !one_thread_) - wakeup_event_.unlock_and_signal_one(lock); - else - lock.unlock(); - - task_cleanup on_exit = { this, &lock, &this_thread }; - (void)on_exit; - - // Run the task. May throw an exception. Only block if the operation - // queue is empty and we're not polling, otherwise we want to return - // as soon as possible. - task_->run(more_handlers ? 0 : -1, this_thread.private_op_queue); - } - else - { - std::size_t task_result = o->task_result_; - - if (more_handlers && !one_thread_) - wake_one_thread_and_unlock(lock); - else - lock.unlock(); - - // Ensure the count of outstanding work is decremented on block exit. - work_cleanup on_exit = { this, &lock, &this_thread }; - (void)on_exit; - - // Complete the operation. May throw an exception. Deletes the object. - o->complete(this, ec, task_result); - - return 1; - } - } - else - { - wakeup_event_.clear(lock); - wakeup_event_.wait(lock); - } - } - - return 0; -} - -std::size_t scheduler::do_wait_one(mutex::scoped_lock& lock, - scheduler::thread_info& this_thread, long usec, - const asio::error_code& ec) -{ - if (stopped_) - return 0; - - operation* o = op_queue_.front(); - if (o == 0) - { - wakeup_event_.clear(lock); - wakeup_event_.wait_for_usec(lock, usec); - usec = 0; // Wait at most once. - o = op_queue_.front(); - } - - if (o == &task_operation_) - { - op_queue_.pop(); - bool more_handlers = (!op_queue_.empty()); - - task_interrupted_ = more_handlers; - - if (more_handlers && !one_thread_) - wakeup_event_.unlock_and_signal_one(lock); - else - lock.unlock(); - - { - task_cleanup on_exit = { this, &lock, &this_thread }; - (void)on_exit; - - // Run the task. May throw an exception. Only block if the operation - // queue is empty and we're not polling, otherwise we want to return - // as soon as possible. - task_->run(more_handlers ? 0 : usec, this_thread.private_op_queue); - } - - o = op_queue_.front(); - if (o == &task_operation_) - { - if (!one_thread_) - wakeup_event_.maybe_unlock_and_signal_one(lock); - return 0; - } - } - - if (o == 0) - return 0; - - op_queue_.pop(); - bool more_handlers = (!op_queue_.empty()); - - std::size_t task_result = o->task_result_; - - if (more_handlers && !one_thread_) - wake_one_thread_and_unlock(lock); - else - lock.unlock(); - - // Ensure the count of outstanding work is decremented on block exit. - work_cleanup on_exit = { this, &lock, &this_thread }; - (void)on_exit; - - // Complete the operation. May throw an exception. Deletes the object. - o->complete(this, ec, task_result); - - return 1; -} - -std::size_t scheduler::do_poll_one(mutex::scoped_lock& lock, - scheduler::thread_info& this_thread, - const asio::error_code& ec) -{ - if (stopped_) - return 0; - - operation* o = op_queue_.front(); - if (o == &task_operation_) - { - op_queue_.pop(); - lock.unlock(); - - { - task_cleanup c = { this, &lock, &this_thread }; - (void)c; - - // Run the task. May throw an exception. Only block if the operation - // queue is empty and we're not polling, otherwise we want to return - // as soon as possible. - task_->run(0, this_thread.private_op_queue); - } - - o = op_queue_.front(); - if (o == &task_operation_) - { - wakeup_event_.maybe_unlock_and_signal_one(lock); - return 0; - } - } - - if (o == 0) - return 0; - - op_queue_.pop(); - bool more_handlers = (!op_queue_.empty()); - - std::size_t task_result = o->task_result_; - - if (more_handlers && !one_thread_) - wake_one_thread_and_unlock(lock); - else - lock.unlock(); - - // Ensure the count of outstanding work is decremented on block exit. - work_cleanup on_exit = { this, &lock, &this_thread }; - (void)on_exit; - - // Complete the operation. May throw an exception. Deletes the object. - o->complete(this, ec, task_result); - - return 1; -} - -void scheduler::stop_all_threads( - mutex::scoped_lock& lock) -{ - stopped_ = true; - wakeup_event_.signal_all(lock); - - if (!task_interrupted_ && task_) - { - task_interrupted_ = true; - task_->interrupt(); - } -} - -void scheduler::wake_one_thread_and_unlock( - mutex::scoped_lock& lock) -{ - if (!wakeup_event_.maybe_unlock_and_signal_one(lock)) - { - if (!task_interrupted_ && task_) - { - task_interrupted_ = true; - task_->interrupt(); - } - lock.unlock(); - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_SCHEDULER_IPP diff --git a/scout_sdk/asio/asio/detail/impl/select_reactor.hpp b/scout_sdk/asio/asio/detail/impl/select_reactor.hpp deleted file mode 100644 index 04a04d4..0000000 --- a/scout_sdk/asio/asio/detail/impl/select_reactor.hpp +++ /dev/null @@ -1,100 +0,0 @@ -// -// detail/impl/select_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_SELECT_REACTOR_HPP -#define ASIO_DETAIL_IMPL_SELECT_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) \ - || (!defined(ASIO_HAS_DEV_POLL) \ - && !defined(ASIO_HAS_EPOLL) \ - && !defined(ASIO_HAS_KQUEUE) \ - && !defined(ASIO_WINDOWS_RUNTIME)) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -void select_reactor::add_timer_queue(timer_queue& queue) -{ - do_add_timer_queue(queue); -} - -// Remove a timer queue from the reactor. -template -void select_reactor::remove_timer_queue(timer_queue& queue) -{ - do_remove_timer_queue(queue); -} - -template -void select_reactor::schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - if (shutdown_) - { - scheduler_.post_immediate_completion(op, false); - return; - } - - bool earliest = queue.enqueue_timer(time, timer, op); - scheduler_.work_started(); - if (earliest) - interrupter_.interrupt(); -} - -template -std::size_t select_reactor::cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - op_queue ops; - std::size_t n = queue.cancel_timer(timer, ops, max_cancelled); - lock.unlock(); - scheduler_.post_deferred_completions(ops); - return n; -} - -template -void select_reactor::move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - op_queue ops; - queue.cancel_timer(target, ops); - queue.move_timer(target, source); - lock.unlock(); - scheduler_.post_deferred_completions(ops); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - // || (!defined(ASIO_HAS_DEV_POLL) - // && !defined(ASIO_HAS_EPOLL) - // && !defined(ASIO_HAS_KQUEUE) - // && !defined(ASIO_WINDOWS_RUNTIME)) - -#endif // ASIO_DETAIL_IMPL_SELECT_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/impl/select_reactor.ipp b/scout_sdk/asio/asio/detail/impl/select_reactor.ipp deleted file mode 100644 index 262bc69..0000000 --- a/scout_sdk/asio/asio/detail/impl/select_reactor.ipp +++ /dev/null @@ -1,333 +0,0 @@ -// -// detail/impl/select_reactor.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_SELECT_REACTOR_IPP -#define ASIO_DETAIL_IMPL_SELECT_REACTOR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) \ - || (!defined(ASIO_HAS_DEV_POLL) \ - && !defined(ASIO_HAS_EPOLL) \ - && !defined(ASIO_HAS_KQUEUE) \ - && !defined(ASIO_WINDOWS_RUNTIME)) - -#include "asio/detail/fd_set_adapter.hpp" -#include "asio/detail/select_reactor.hpp" -#include "asio/detail/signal_blocker.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_IOCP) -class select_reactor::thread_function -{ -public: - explicit thread_function(select_reactor* r) - : this_(r) - { - } - - void operator()() - { - this_->run_thread(); - } - -private: - select_reactor* this_; -}; -#endif // defined(ASIO_HAS_IOCP) - -select_reactor::select_reactor(asio::execution_context& ctx) - : execution_context_service_base(ctx), - scheduler_(use_service(ctx)), - mutex_(), - interrupter_(), -#if defined(ASIO_HAS_IOCP) - stop_thread_(false), - thread_(0), -#endif // defined(ASIO_HAS_IOCP) - shutdown_(false) -{ -#if defined(ASIO_HAS_IOCP) - asio::detail::signal_blocker sb; - thread_ = new asio::detail::thread(thread_function(this)); -#endif // defined(ASIO_HAS_IOCP) -} - -select_reactor::~select_reactor() -{ - shutdown(); -} - -void select_reactor::shutdown() -{ - asio::detail::mutex::scoped_lock lock(mutex_); - shutdown_ = true; -#if defined(ASIO_HAS_IOCP) - stop_thread_ = true; -#endif // defined(ASIO_HAS_IOCP) - lock.unlock(); - -#if defined(ASIO_HAS_IOCP) - if (thread_) - { - interrupter_.interrupt(); - thread_->join(); - delete thread_; - thread_ = 0; - } -#endif // defined(ASIO_HAS_IOCP) - - op_queue ops; - - for (int i = 0; i < max_ops; ++i) - op_queue_[i].get_all_operations(ops); - - timer_queues_.get_all_timers(ops); - - scheduler_.abandon_operations(ops); -} - -void select_reactor::notify_fork( - asio::execution_context::fork_event fork_ev) -{ - if (fork_ev == asio::execution_context::fork_child) - interrupter_.recreate(); -} - -void select_reactor::init_task() -{ - scheduler_.init_task(); -} - -int select_reactor::register_descriptor(socket_type, - select_reactor::per_descriptor_data&) -{ - return 0; -} - -int select_reactor::register_internal_descriptor( - int op_type, socket_type descriptor, - select_reactor::per_descriptor_data&, reactor_op* op) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - op_queue_[op_type].enqueue_operation(descriptor, op); - interrupter_.interrupt(); - - return 0; -} - -void select_reactor::move_descriptor(socket_type, - select_reactor::per_descriptor_data&, - select_reactor::per_descriptor_data&) -{ -} - -void select_reactor::start_op(int op_type, socket_type descriptor, - select_reactor::per_descriptor_data&, reactor_op* op, - bool is_continuation, bool) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - if (shutdown_) - { - post_immediate_completion(op, is_continuation); - return; - } - - bool first = op_queue_[op_type].enqueue_operation(descriptor, op); - scheduler_.work_started(); - if (first) - interrupter_.interrupt(); -} - -void select_reactor::cancel_ops(socket_type descriptor, - select_reactor::per_descriptor_data&) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - cancel_ops_unlocked(descriptor, asio::error::operation_aborted); -} - -void select_reactor::deregister_descriptor(socket_type descriptor, - select_reactor::per_descriptor_data&, bool) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - cancel_ops_unlocked(descriptor, asio::error::operation_aborted); -} - -void select_reactor::deregister_internal_descriptor( - socket_type descriptor, select_reactor::per_descriptor_data&) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - op_queue ops; - for (int i = 0; i < max_ops; ++i) - op_queue_[i].cancel_operations(descriptor, ops); -} - -void select_reactor::cleanup_descriptor_data( - select_reactor::per_descriptor_data&) -{ -} - -void select_reactor::run(long usec, op_queue& ops) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - -#if defined(ASIO_HAS_IOCP) - // Check if the thread is supposed to stop. - if (stop_thread_) - return; -#endif // defined(ASIO_HAS_IOCP) - - // Set up the descriptor sets. - for (int i = 0; i < max_select_ops; ++i) - fd_sets_[i].reset(); - fd_sets_[read_op].set(interrupter_.read_descriptor()); - socket_type max_fd = 0; - bool have_work_to_do = !timer_queues_.all_empty(); - for (int i = 0; i < max_select_ops; ++i) - { - have_work_to_do = have_work_to_do || !op_queue_[i].empty(); - fd_sets_[i].set(op_queue_[i], ops); - if (fd_sets_[i].max_descriptor() > max_fd) - max_fd = fd_sets_[i].max_descriptor(); - } - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - // Connection operations on Windows use both except and write fd_sets. - have_work_to_do = have_work_to_do || !op_queue_[connect_op].empty(); - fd_sets_[write_op].set(op_queue_[connect_op], ops); - if (fd_sets_[write_op].max_descriptor() > max_fd) - max_fd = fd_sets_[write_op].max_descriptor(); - fd_sets_[except_op].set(op_queue_[connect_op], ops); - if (fd_sets_[except_op].max_descriptor() > max_fd) - max_fd = fd_sets_[except_op].max_descriptor(); -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - - // We can return immediately if there's no work to do and the reactor is - // not supposed to block. - if (!usec && !have_work_to_do) - return; - - // Determine how long to block while waiting for events. - timeval tv_buf = { 0, 0 }; - timeval* tv = usec ? get_timeout(usec, tv_buf) : &tv_buf; - - lock.unlock(); - - // Block on the select call until descriptors become ready. - asio::error_code ec; - int retval = socket_ops::select(static_cast(max_fd + 1), - fd_sets_[read_op], fd_sets_[write_op], fd_sets_[except_op], tv, ec); - - // Reset the interrupter. - if (retval > 0 && fd_sets_[read_op].is_set(interrupter_.read_descriptor())) - { - interrupter_.reset(); - --retval; - } - - lock.lock(); - - // Dispatch all ready operations. - if (retval > 0) - { -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - // Connection operations on Windows use both except and write fd_sets. - fd_sets_[except_op].perform(op_queue_[connect_op], ops); - fd_sets_[write_op].perform(op_queue_[connect_op], ops); -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - - // Exception operations must be processed first to ensure that any - // out-of-band data is read before normal data. - for (int i = max_select_ops - 1; i >= 0; --i) - fd_sets_[i].perform(op_queue_[i], ops); - } - timer_queues_.get_ready_timers(ops); -} - -void select_reactor::interrupt() -{ - interrupter_.interrupt(); -} - -#if defined(ASIO_HAS_IOCP) -void select_reactor::run_thread() -{ - asio::detail::mutex::scoped_lock lock(mutex_); - while (!stop_thread_) - { - lock.unlock(); - op_queue ops; - run(true, ops); - scheduler_.post_deferred_completions(ops); - lock.lock(); - } -} -#endif // defined(ASIO_HAS_IOCP) - -void select_reactor::do_add_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.insert(&queue); -} - -void select_reactor::do_remove_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.erase(&queue); -} - -timeval* select_reactor::get_timeout(long usec, timeval& tv) -{ - // By default we will wait no longer than 5 minutes. This will ensure that - // any changes to the system clock are detected after no longer than this. - const long max_usec = 5 * 60 * 1000 * 1000; - usec = timer_queues_.wait_duration_usec( - (usec < 0 || max_usec < usec) ? max_usec : usec); - tv.tv_sec = usec / 1000000; - tv.tv_usec = usec % 1000000; - return &tv; -} - -void select_reactor::cancel_ops_unlocked(socket_type descriptor, - const asio::error_code& ec) -{ - bool need_interrupt = false; - op_queue ops; - for (int i = 0; i < max_ops; ++i) - need_interrupt = op_queue_[i].cancel_operations( - descriptor, ops, ec) || need_interrupt; - scheduler_.post_deferred_completions(ops); - if (need_interrupt) - interrupter_.interrupt(); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - // || (!defined(ASIO_HAS_DEV_POLL) - // && !defined(ASIO_HAS_EPOLL) - // && !defined(ASIO_HAS_KQUEUE)) - // && !defined(ASIO_WINDOWS_RUNTIME)) - -#endif // ASIO_DETAIL_IMPL_SELECT_REACTOR_IPP diff --git a/scout_sdk/asio/asio/detail/impl/service_registry.hpp b/scout_sdk/asio/asio/detail/impl/service_registry.hpp deleted file mode 100644 index d4db589..0000000 --- a/scout_sdk/asio/asio/detail/impl/service_registry.hpp +++ /dev/null @@ -1,94 +0,0 @@ -// -// detail/impl/service_registry.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_SERVICE_REGISTRY_HPP -#define ASIO_DETAIL_IMPL_SERVICE_REGISTRY_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -Service& service_registry::use_service() -{ - execution_context::service::key key; - init_key(key, 0); - factory_type factory = &service_registry::create; - return *static_cast(do_use_service(key, factory, &owner_)); -} - -template -Service& service_registry::use_service(io_context& owner) -{ - execution_context::service::key key; - init_key(key, 0); - factory_type factory = &service_registry::create; - return *static_cast(do_use_service(key, factory, &owner)); -} - -template -void service_registry::add_service(Service* new_service) -{ - execution_context::service::key key; - init_key(key, 0); - return do_add_service(key, new_service); -} - -template -bool service_registry::has_service() const -{ - execution_context::service::key key; - init_key(key, 0); - return do_has_service(key); -} - -template -inline void service_registry::init_key( - execution_context::service::key& key, ...) -{ - init_key_from_id(key, Service::id); -} - -#if !defined(ASIO_NO_TYPEID) -template -void service_registry::init_key(execution_context::service::key& key, - typename enable_if< - is_base_of::value>::type*) -{ - key.type_info_ = &typeid(typeid_wrapper); - key.id_ = 0; -} - -template -void service_registry::init_key_from_id(execution_context::service::key& key, - const service_id& /*id*/) -{ - key.type_info_ = &typeid(typeid_wrapper); - key.id_ = 0; -} -#endif // !defined(ASIO_NO_TYPEID) - -template -execution_context::service* service_registry::create(void* owner) -{ - return new Service(*static_cast(owner)); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_SERVICE_REGISTRY_HPP diff --git a/scout_sdk/asio/asio/detail/impl/service_registry.ipp b/scout_sdk/asio/asio/detail/impl/service_registry.ipp deleted file mode 100644 index a465033..0000000 --- a/scout_sdk/asio/asio/detail/impl/service_registry.ipp +++ /dev/null @@ -1,197 +0,0 @@ -// -// detail/impl/service_registry.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_SERVICE_REGISTRY_IPP -#define ASIO_DETAIL_IMPL_SERVICE_REGISTRY_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/service_registry.hpp" -#include "asio/detail/throw_exception.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -service_registry::service_registry(execution_context& owner) - : owner_(owner), - first_service_(0) -{ -} - -service_registry::~service_registry() -{ -} - -void service_registry::shutdown_services() -{ - execution_context::service* service = first_service_; - while (service) - { - service->shutdown(); - service = service->next_; - } -} - -void service_registry::destroy_services() -{ - while (first_service_) - { - execution_context::service* next_service = first_service_->next_; - destroy(first_service_); - first_service_ = next_service; - } -} - -void service_registry::notify_fork(execution_context::fork_event fork_ev) -{ - // Make a copy of all of the services while holding the lock. We don't want - // to hold the lock while calling into each service, as it may try to call - // back into this class. - std::vector services; - { - asio::detail::mutex::scoped_lock lock(mutex_); - execution_context::service* service = first_service_; - while (service) - { - services.push_back(service); - service = service->next_; - } - } - - // If processing the fork_prepare event, we want to go in reverse order of - // service registration, which happens to be the existing order of the - // services in the vector. For the other events we want to go in the other - // direction. - std::size_t num_services = services.size(); - if (fork_ev == execution_context::fork_prepare) - for (std::size_t i = 0; i < num_services; ++i) - services[i]->notify_fork(fork_ev); - else - for (std::size_t i = num_services; i > 0; --i) - services[i - 1]->notify_fork(fork_ev); -} - -void service_registry::init_key_from_id(execution_context::service::key& key, - const execution_context::id& id) -{ - key.type_info_ = 0; - key.id_ = &id; -} - -bool service_registry::keys_match( - const execution_context::service::key& key1, - const execution_context::service::key& key2) -{ - if (key1.id_ && key2.id_) - if (key1.id_ == key2.id_) - return true; - if (key1.type_info_ && key2.type_info_) - if (*key1.type_info_ == *key2.type_info_) - return true; - return false; -} - -void service_registry::destroy(execution_context::service* service) -{ - delete service; -} - -execution_context::service* service_registry::do_use_service( - const execution_context::service::key& key, - factory_type factory, void* owner) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - // First see if there is an existing service object with the given key. - execution_context::service* service = first_service_; - while (service) - { - if (keys_match(service->key_, key)) - return service; - service = service->next_; - } - - // Create a new service object. The service registry's mutex is not locked - // at this time to allow for nested calls into this function from the new - // service's constructor. - lock.unlock(); - auto_service_ptr new_service = { factory(owner) }; - new_service.ptr_->key_ = key; - lock.lock(); - - // Check that nobody else created another service object of the same type - // while the lock was released. - service = first_service_; - while (service) - { - if (keys_match(service->key_, key)) - return service; - service = service->next_; - } - - // Service was successfully initialised, pass ownership to registry. - new_service.ptr_->next_ = first_service_; - first_service_ = new_service.ptr_; - new_service.ptr_ = 0; - return first_service_; -} - -void service_registry::do_add_service( - const execution_context::service::key& key, - execution_context::service* new_service) -{ - if (&owner_ != &new_service->context()) - asio::detail::throw_exception(invalid_service_owner()); - - asio::detail::mutex::scoped_lock lock(mutex_); - - // Check if there is an existing service object with the given key. - execution_context::service* service = first_service_; - while (service) - { - if (keys_match(service->key_, key)) - asio::detail::throw_exception(service_already_exists()); - service = service->next_; - } - - // Take ownership of the service object. - new_service->key_ = key; - new_service->next_ = first_service_; - first_service_ = new_service; -} - -bool service_registry::do_has_service( - const execution_context::service::key& key) const -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - execution_context::service* service = first_service_; - while (service) - { - if (keys_match(service->key_, key)) - return true; - service = service->next_; - } - - return false; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_SERVICE_REGISTRY_IPP diff --git a/scout_sdk/asio/asio/detail/impl/signal_set_service.ipp b/scout_sdk/asio/asio/detail/impl/signal_set_service.ipp deleted file mode 100644 index dd68fc1..0000000 --- a/scout_sdk/asio/asio/detail/impl/signal_set_service.ipp +++ /dev/null @@ -1,669 +0,0 @@ -// -// detail/impl/signal_set_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_SIGNAL_SET_SERVICE_IPP -#define ASIO_DETAIL_IMPL_SIGNAL_SET_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include -#include "asio/detail/reactor.hpp" -#include "asio/detail/signal_blocker.hpp" -#include "asio/detail/signal_set_service.hpp" -#include "asio/detail/static_mutex.hpp" -#include "asio/detail/throw_exception.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct signal_state -{ - // Mutex used for protecting global state. - static_mutex mutex_; - - // The read end of the pipe used for signal notifications. - int read_descriptor_; - - // The write end of the pipe used for signal notifications. - int write_descriptor_; - - // Whether the signal state has been prepared for a fork. - bool fork_prepared_; - - // The head of a linked list of all signal_set_service instances. - class signal_set_service* service_list_; - - // A count of the number of objects that are registered for each signal. - std::size_t registration_count_[max_signal_number]; -}; - -signal_state* get_signal_state() -{ - static signal_state state = { - ASIO_STATIC_MUTEX_INIT, -1, -1, false, 0, { 0 } }; - return &state; -} - -void asio_signal_handler(int signal_number) -{ -#if defined(ASIO_WINDOWS) \ - || defined(ASIO_WINDOWS_RUNTIME) \ - || defined(__CYGWIN__) - signal_set_service::deliver_signal(signal_number); -#else // defined(ASIO_WINDOWS) - // || defined(ASIO_WINDOWS_RUNTIME) - // || defined(__CYGWIN__) - int saved_errno = errno; - signal_state* state = get_signal_state(); - signed_size_type result = ::write(state->write_descriptor_, - &signal_number, sizeof(signal_number)); - (void)result; - errno = saved_errno; -#endif // defined(ASIO_WINDOWS) - // || defined(ASIO_WINDOWS_RUNTIME) - // || defined(__CYGWIN__) - -#if defined(ASIO_HAS_SIGNAL) && !defined(ASIO_HAS_SIGACTION) - ::signal(signal_number, asio_signal_handler); -#endif // defined(ASIO_HAS_SIGNAL) && !defined(ASIO_HAS_SIGACTION) -} - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) -class signal_set_service::pipe_read_op : public reactor_op -{ -public: - pipe_read_op() - : reactor_op(&pipe_read_op::do_perform, pipe_read_op::do_complete) - { - } - - static status do_perform(reactor_op*) - { - signal_state* state = get_signal_state(); - - int fd = state->read_descriptor_; - int signal_number = 0; - while (::read(fd, &signal_number, sizeof(int)) == sizeof(int)) - if (signal_number >= 0 && signal_number < max_signal_number) - signal_set_service::deliver_signal(signal_number); - - return not_done; - } - - static void do_complete(void* /*owner*/, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - pipe_read_op* o(static_cast(base)); - delete o; - } -}; -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - -signal_set_service::signal_set_service( - asio::io_context& io_context) - : service_base(io_context), - io_context_(asio::use_service(io_context)), -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - reactor_(asio::use_service(io_context)), -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - next_(0), - prev_(0) -{ - get_signal_state()->mutex_.init(); - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - reactor_.init_task(); -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - - for (int i = 0; i < max_signal_number; ++i) - registrations_[i] = 0; - - add_service(this); -} - -signal_set_service::~signal_set_service() -{ - remove_service(this); -} - -void signal_set_service::shutdown() -{ - remove_service(this); - - op_queue ops; - - for (int i = 0; i < max_signal_number; ++i) - { - registration* reg = registrations_[i]; - while (reg) - { - ops.push(*reg->queue_); - reg = reg->next_in_table_; - } - } - - io_context_.abandon_operations(ops); -} - -void signal_set_service::notify_fork( - asio::io_context::fork_event fork_ev) -{ -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - switch (fork_ev) - { - case asio::io_context::fork_prepare: - { - int read_descriptor = state->read_descriptor_; - state->fork_prepared_ = true; - lock.unlock(); - reactor_.deregister_internal_descriptor(read_descriptor, reactor_data_); - reactor_.cleanup_descriptor_data(reactor_data_); - } - break; - case asio::io_context::fork_parent: - if (state->fork_prepared_) - { - int read_descriptor = state->read_descriptor_; - state->fork_prepared_ = false; - lock.unlock(); - reactor_.register_internal_descriptor(reactor::read_op, - read_descriptor, reactor_data_, new pipe_read_op); - } - break; - case asio::io_context::fork_child: - if (state->fork_prepared_) - { - asio::detail::signal_blocker blocker; - close_descriptors(); - open_descriptors(); - int read_descriptor = state->read_descriptor_; - state->fork_prepared_ = false; - lock.unlock(); - reactor_.register_internal_descriptor(reactor::read_op, - read_descriptor, reactor_data_, new pipe_read_op); - } - break; - default: - break; - } -#else // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - (void)fork_ev; -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -} - -void signal_set_service::construct( - signal_set_service::implementation_type& impl) -{ - impl.signals_ = 0; -} - -void signal_set_service::destroy( - signal_set_service::implementation_type& impl) -{ - asio::error_code ignored_ec; - clear(impl, ignored_ec); - cancel(impl, ignored_ec); -} - -asio::error_code signal_set_service::add( - signal_set_service::implementation_type& impl, - int signal_number, asio::error_code& ec) -{ - // Check that the signal number is valid. - if (signal_number < 0 || signal_number >= max_signal_number) - { - ec = asio::error::invalid_argument; - return ec; - } - - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - // Find the appropriate place to insert the registration. - registration** insertion_point = &impl.signals_; - registration* next = impl.signals_; - while (next && next->signal_number_ < signal_number) - { - insertion_point = &next->next_in_set_; - next = next->next_in_set_; - } - - // Only do something if the signal is not already registered. - if (next == 0 || next->signal_number_ != signal_number) - { - registration* new_registration = new registration; - -#if defined(ASIO_HAS_SIGNAL) || defined(ASIO_HAS_SIGACTION) - // Register for the signal if we're the first. - if (state->registration_count_[signal_number] == 0) - { -# if defined(ASIO_HAS_SIGACTION) - using namespace std; // For memset. - struct sigaction sa; - memset(&sa, 0, sizeof(sa)); - sa.sa_handler = asio_signal_handler; - sigfillset(&sa.sa_mask); - if (::sigaction(signal_number, &sa, 0) == -1) -# else // defined(ASIO_HAS_SIGACTION) - if (::signal(signal_number, asio_signal_handler) == SIG_ERR) -# endif // defined(ASIO_HAS_SIGACTION) - { -# if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ec = asio::error::invalid_argument; -# else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ec = asio::error_code(errno, - asio::error::get_system_category()); -# endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - delete new_registration; - return ec; - } - } -#endif // defined(ASIO_HAS_SIGNAL) || defined(ASIO_HAS_SIGACTION) - - // Record the new registration in the set. - new_registration->signal_number_ = signal_number; - new_registration->queue_ = &impl.queue_; - new_registration->next_in_set_ = next; - *insertion_point = new_registration; - - // Insert registration into the registration table. - new_registration->next_in_table_ = registrations_[signal_number]; - if (registrations_[signal_number]) - registrations_[signal_number]->prev_in_table_ = new_registration; - registrations_[signal_number] = new_registration; - - ++state->registration_count_[signal_number]; - } - - ec = asio::error_code(); - return ec; -} - -asio::error_code signal_set_service::remove( - signal_set_service::implementation_type& impl, - int signal_number, asio::error_code& ec) -{ - // Check that the signal number is valid. - if (signal_number < 0 || signal_number >= max_signal_number) - { - ec = asio::error::invalid_argument; - return ec; - } - - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - // Find the signal number in the list of registrations. - registration** deletion_point = &impl.signals_; - registration* reg = impl.signals_; - while (reg && reg->signal_number_ < signal_number) - { - deletion_point = ®->next_in_set_; - reg = reg->next_in_set_; - } - - if (reg != 0 && reg->signal_number_ == signal_number) - { -#if defined(ASIO_HAS_SIGNAL) || defined(ASIO_HAS_SIGACTION) - // Set signal handler back to the default if we're the last. - if (state->registration_count_[signal_number] == 1) - { -# if defined(ASIO_HAS_SIGACTION) - using namespace std; // For memset. - struct sigaction sa; - memset(&sa, 0, sizeof(sa)); - sa.sa_handler = SIG_DFL; - if (::sigaction(signal_number, &sa, 0) == -1) -# else // defined(ASIO_HAS_SIGACTION) - if (::signal(signal_number, SIG_DFL) == SIG_ERR) -# endif // defined(ASIO_HAS_SIGACTION) - { -# if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ec = asio::error::invalid_argument; -# else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ec = asio::error_code(errno, - asio::error::get_system_category()); -# endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - return ec; - } - } -#endif // defined(ASIO_HAS_SIGNAL) || defined(ASIO_HAS_SIGACTION) - - // Remove the registration from the set. - *deletion_point = reg->next_in_set_; - - // Remove the registration from the registration table. - if (registrations_[signal_number] == reg) - registrations_[signal_number] = reg->next_in_table_; - if (reg->prev_in_table_) - reg->prev_in_table_->next_in_table_ = reg->next_in_table_; - if (reg->next_in_table_) - reg->next_in_table_->prev_in_table_ = reg->prev_in_table_; - - --state->registration_count_[signal_number]; - - delete reg; - } - - ec = asio::error_code(); - return ec; -} - -asio::error_code signal_set_service::clear( - signal_set_service::implementation_type& impl, - asio::error_code& ec) -{ - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - while (registration* reg = impl.signals_) - { -#if defined(ASIO_HAS_SIGNAL) || defined(ASIO_HAS_SIGACTION) - // Set signal handler back to the default if we're the last. - if (state->registration_count_[reg->signal_number_] == 1) - { -# if defined(ASIO_HAS_SIGACTION) - using namespace std; // For memset. - struct sigaction sa; - memset(&sa, 0, sizeof(sa)); - sa.sa_handler = SIG_DFL; - if (::sigaction(reg->signal_number_, &sa, 0) == -1) -# else // defined(ASIO_HAS_SIGACTION) - if (::signal(reg->signal_number_, SIG_DFL) == SIG_ERR) -# endif // defined(ASIO_HAS_SIGACTION) - { -# if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ec = asio::error::invalid_argument; -# else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ec = asio::error_code(errno, - asio::error::get_system_category()); -# endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - return ec; - } - } -#endif // defined(ASIO_HAS_SIGNAL) || defined(ASIO_HAS_SIGACTION) - - // Remove the registration from the registration table. - if (registrations_[reg->signal_number_] == reg) - registrations_[reg->signal_number_] = reg->next_in_table_; - if (reg->prev_in_table_) - reg->prev_in_table_->next_in_table_ = reg->next_in_table_; - if (reg->next_in_table_) - reg->next_in_table_->prev_in_table_ = reg->prev_in_table_; - - --state->registration_count_[reg->signal_number_]; - - impl.signals_ = reg->next_in_set_; - delete reg; - } - - ec = asio::error_code(); - return ec; -} - -asio::error_code signal_set_service::cancel( - signal_set_service::implementation_type& impl, - asio::error_code& ec) -{ - ASIO_HANDLER_OPERATION((io_context_.context(), - "signal_set", &impl, 0, "cancel")); - - op_queue ops; - { - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - while (signal_op* op = impl.queue_.front()) - { - op->ec_ = asio::error::operation_aborted; - impl.queue_.pop(); - ops.push(op); - } - } - - io_context_.post_deferred_completions(ops); - - ec = asio::error_code(); - return ec; -} - -void signal_set_service::deliver_signal(int signal_number) -{ - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - signal_set_service* service = state->service_list_; - while (service) - { - op_queue ops; - - registration* reg = service->registrations_[signal_number]; - while (reg) - { - if (reg->queue_->empty()) - { - ++reg->undelivered_; - } - else - { - while (signal_op* op = reg->queue_->front()) - { - op->signal_number_ = signal_number; - reg->queue_->pop(); - ops.push(op); - } - } - - reg = reg->next_in_table_; - } - - service->io_context_.post_deferred_completions(ops); - - service = service->next_; - } -} - -void signal_set_service::add_service(signal_set_service* service) -{ - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - // If this is the first service to be created, open a new pipe. - if (state->service_list_ == 0) - open_descriptors(); -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - - // If an io_context object is thread-unsafe then it must be the only - // io_context used to create signal_set objects. - if (state->service_list_ != 0) - { - if (!ASIO_CONCURRENCY_HINT_IS_LOCKING(SCHEDULER, - service->io_context_.concurrency_hint()) - || !ASIO_CONCURRENCY_HINT_IS_LOCKING(SCHEDULER, - state->service_list_->io_context_.concurrency_hint())) - { - std::logic_error ex( - "Thread-unsafe io_context objects require " - "exclusive access to signal handling."); - asio::detail::throw_exception(ex); - } - } - - // Insert service into linked list of all services. - service->next_ = state->service_list_; - service->prev_ = 0; - if (state->service_list_) - state->service_list_->prev_ = service; - state->service_list_ = service; - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - // Register for pipe readiness notifications. - int read_descriptor = state->read_descriptor_; - lock.unlock(); - service->reactor_.register_internal_descriptor(reactor::read_op, - read_descriptor, service->reactor_data_, new pipe_read_op); -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -} - -void signal_set_service::remove_service(signal_set_service* service) -{ - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - if (service->next_ || service->prev_ || state->service_list_ == service) - { -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - // Disable the pipe readiness notifications. - int read_descriptor = state->read_descriptor_; - lock.unlock(); - service->reactor_.deregister_internal_descriptor( - read_descriptor, service->reactor_data_); - service->reactor_.cleanup_descriptor_data(service->reactor_data_); - lock.lock(); -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - - // Remove service from linked list of all services. - if (state->service_list_ == service) - state->service_list_ = service->next_; - if (service->prev_) - service->prev_->next_ = service->next_; - if (service->next_) - service->next_->prev_= service->prev_; - service->next_ = 0; - service->prev_ = 0; - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - // If this is the last service to be removed, close the pipe. - if (state->service_list_ == 0) - close_descriptors(); -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - } -} - -void signal_set_service::open_descriptors() -{ -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - signal_state* state = get_signal_state(); - - int pipe_fds[2]; - if (::pipe(pipe_fds) == 0) - { - state->read_descriptor_ = pipe_fds[0]; - ::fcntl(state->read_descriptor_, F_SETFL, O_NONBLOCK); - - state->write_descriptor_ = pipe_fds[1]; - ::fcntl(state->write_descriptor_, F_SETFL, O_NONBLOCK); - -#if defined(FD_CLOEXEC) - ::fcntl(state->read_descriptor_, F_SETFD, FD_CLOEXEC); - ::fcntl(state->write_descriptor_, F_SETFD, FD_CLOEXEC); -#endif // defined(FD_CLOEXEC) - } - else - { - asio::error_code ec(errno, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "signal_set_service pipe"); - } -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -} - -void signal_set_service::close_descriptors() -{ -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - signal_state* state = get_signal_state(); - - if (state->read_descriptor_ != -1) - ::close(state->read_descriptor_); - state->read_descriptor_ = -1; - - if (state->write_descriptor_ != -1) - ::close(state->write_descriptor_); - state->write_descriptor_ = -1; -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) -} - -void signal_set_service::start_wait_op( - signal_set_service::implementation_type& impl, signal_op* op) -{ - io_context_.work_started(); - - signal_state* state = get_signal_state(); - static_mutex::scoped_lock lock(state->mutex_); - - registration* reg = impl.signals_; - while (reg) - { - if (reg->undelivered_ > 0) - { - --reg->undelivered_; - op->signal_number_ = reg->signal_number_; - io_context_.post_deferred_completion(op); - return; - } - - reg = reg->next_in_set_; - } - - impl.queue_.push(op); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_SIGNAL_SET_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/socket_ops.ipp b/scout_sdk/asio/asio/detail/impl/socket_ops.ipp deleted file mode 100644 index 5e74733..0000000 --- a/scout_sdk/asio/asio/detail/impl/socket_ops.ipp +++ /dev/null @@ -1,3571 +0,0 @@ -// -// detail/impl/socket_ops.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SOCKET_OPS_IPP -#define ASIO_DETAIL_SOCKET_OPS_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include -#include -#include -#include -#include -#include "asio/detail/assert.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include -# include -# include -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) \ - || defined(__MACH__) && defined(__APPLE__) -# if defined(ASIO_HAS_PTHREADS) -# include -# endif // defined(ASIO_HAS_PTHREADS) -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - // || defined(__MACH__) && defined(__APPLE__) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { -namespace socket_ops { - -#if !defined(ASIO_WINDOWS_RUNTIME) - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -struct msghdr { int msg_namelen; }; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#if defined(__hpux) -// HP-UX doesn't declare these functions extern "C", so they are declared again -// here to avoid linker errors about undefined symbols. -extern "C" char* if_indextoname(unsigned int, char*); -extern "C" unsigned int if_nametoindex(const char*); -#endif // defined(__hpux) - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -inline void clear_last_error() -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - WSASetLastError(0); -#else - errno = 0; -#endif -} - -#if !defined(ASIO_WINDOWS_RUNTIME) - -template -inline ReturnType error_wrapper(ReturnType return_value, - asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ec = asio::error_code(WSAGetLastError(), - asio::error::get_system_category()); -#else - ec = asio::error_code(errno, - asio::error::get_system_category()); -#endif - return return_value; -} - -template -inline socket_type call_accept(SockLenType msghdr::*, - socket_type s, socket_addr_type* addr, std::size_t* addrlen) -{ - SockLenType tmp_addrlen = addrlen ? (SockLenType)*addrlen : 0; - socket_type result = ::accept(s, addr, addrlen ? &tmp_addrlen : 0); - if (addrlen) - *addrlen = (std::size_t)tmp_addrlen; - return result; -} - -socket_type accept(socket_type s, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return invalid_socket; - } - - clear_last_error(); - - socket_type new_s = error_wrapper(call_accept( - &msghdr::msg_namelen, s, addr, addrlen), ec); - if (new_s == invalid_socket) - return new_s; - -#if defined(__MACH__) && defined(__APPLE__) || defined(__FreeBSD__) - int optval = 1; - int result = error_wrapper(::setsockopt(new_s, - SOL_SOCKET, SO_NOSIGPIPE, &optval, sizeof(optval)), ec); - if (result != 0) - { - ::close(new_s); - return invalid_socket; - } -#endif - - ec = asio::error_code(); - return new_s; -} - -socket_type sync_accept(socket_type s, state_type state, - socket_addr_type* addr, std::size_t* addrlen, asio::error_code& ec) -{ - // Accept a socket. - for (;;) - { - // Try to complete the operation without blocking. - socket_type new_socket = socket_ops::accept(s, addr, addrlen, ec); - - // Check if operation succeeded. - if (new_socket != invalid_socket) - return new_socket; - - // Operation failed. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - { - if (state & user_set_non_blocking) - return invalid_socket; - // Fall through to retry operation. - } - else if (ec == asio::error::connection_aborted) - { - if (state & enable_connection_aborted) - return invalid_socket; - // Fall through to retry operation. - } -#if defined(EPROTO) - else if (ec.value() == EPROTO) - { - if (state & enable_connection_aborted) - return invalid_socket; - // Fall through to retry operation. - } -#endif // defined(EPROTO) - else - return invalid_socket; - - // Wait for socket to become ready. - if (socket_ops::poll_read(s, 0, -1, ec) < 0) - return invalid_socket; - } -} - -#if defined(ASIO_HAS_IOCP) - -void complete_iocp_accept(socket_type s, - void* output_buffer, DWORD address_length, - socket_addr_type* addr, std::size_t* addrlen, - socket_type new_socket, asio::error_code& ec) -{ - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_NETNAME_DELETED) - ec = asio::error::connection_aborted; - - if (!ec) - { - // Get the address of the peer. - if (addr && addrlen) - { - LPSOCKADDR local_addr = 0; - int local_addr_length = 0; - LPSOCKADDR remote_addr = 0; - int remote_addr_length = 0; - GetAcceptExSockaddrs(output_buffer, 0, address_length, - address_length, &local_addr, &local_addr_length, - &remote_addr, &remote_addr_length); - if (static_cast(remote_addr_length) > *addrlen) - { - ec = asio::error::invalid_argument; - } - else - { - using namespace std; // For memcpy. - memcpy(addr, remote_addr, remote_addr_length); - *addrlen = static_cast(remote_addr_length); - } - } - - // Need to set the SO_UPDATE_ACCEPT_CONTEXT option so that getsockname - // and getpeername will work on the accepted socket. - SOCKET update_ctx_param = s; - socket_ops::state_type state = 0; - socket_ops::setsockopt(new_socket, state, - SOL_SOCKET, SO_UPDATE_ACCEPT_CONTEXT, - &update_ctx_param, sizeof(SOCKET), ec); - } -} - -#else // defined(ASIO_HAS_IOCP) - -bool non_blocking_accept(socket_type s, - state_type state, socket_addr_type* addr, std::size_t* addrlen, - asio::error_code& ec, socket_type& new_socket) -{ - for (;;) - { - // Accept the waiting connection. - new_socket = socket_ops::accept(s, addr, addrlen, ec); - - // Check if operation succeeded. - if (new_socket != invalid_socket) - return true; - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Operation failed. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - { - // Fall through to retry operation. - } - else if (ec == asio::error::connection_aborted) - { - if (state & enable_connection_aborted) - return true; - // Fall through to retry operation. - } -#if defined(EPROTO) - else if (ec.value() == EPROTO) - { - if (state & enable_connection_aborted) - return true; - // Fall through to retry operation. - } -#endif // defined(EPROTO) - else - return true; - - return false; - } -} - -#endif // defined(ASIO_HAS_IOCP) - -template -inline int call_bind(SockLenType msghdr::*, - socket_type s, const socket_addr_type* addr, std::size_t addrlen) -{ - return ::bind(s, addr, (SockLenType)addrlen); -} - -int bind(socket_type s, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - clear_last_error(); - int result = error_wrapper(call_bind( - &msghdr::msg_namelen, s, addr, addrlen), ec); - if (result == 0) - ec = asio::error_code(); - return result; -} - -int close(socket_type s, state_type& state, - bool destruction, asio::error_code& ec) -{ - int result = 0; - if (s != invalid_socket) - { - // We don't want the destructor to block, so set the socket to linger in - // the background. If the user doesn't like this behaviour then they need - // to explicitly close the socket. - if (destruction && (state & user_set_linger)) - { - ::linger opt; - opt.l_onoff = 0; - opt.l_linger = 0; - asio::error_code ignored_ec; - socket_ops::setsockopt(s, state, SOL_SOCKET, - SO_LINGER, &opt, sizeof(opt), ignored_ec); - } - - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - result = error_wrapper(::closesocket(s), ec); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - result = error_wrapper(::close(s), ec); -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - - if (result != 0 - && (ec == asio::error::would_block - || ec == asio::error::try_again)) - { - // According to UNIX Network Programming Vol. 1, it is possible for - // close() to fail with EWOULDBLOCK under certain circumstances. What - // isn't clear is the state of the descriptor after this error. The one - // current OS where this behaviour is seen, Windows, says that the socket - // remains open. Therefore we'll put the descriptor back into blocking - // mode and have another attempt at closing it. -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ioctl_arg_type arg = 0; - ::ioctlsocket(s, FIONBIO, &arg); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if defined(__SYMBIAN32__) - int flags = ::fcntl(s, F_GETFL, 0); - if (flags >= 0) - ::fcntl(s, F_SETFL, flags & ~O_NONBLOCK); -# else // defined(__SYMBIAN32__) - ioctl_arg_type arg = 0; - ::ioctl(s, FIONBIO, &arg); -# endif // defined(__SYMBIAN32__) -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - state &= ~non_blocking; - - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - result = error_wrapper(::closesocket(s), ec); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - result = error_wrapper(::close(s), ec); -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - } - } - - if (result == 0) - ec = asio::error_code(); - return result; -} - -bool set_user_non_blocking(socket_type s, - state_type& state, bool value, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return false; - } - - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ioctl_arg_type arg = (value ? 1 : 0); - int result = error_wrapper(::ioctlsocket(s, FIONBIO, &arg), ec); -#elif defined(__SYMBIAN32__) - int result = error_wrapper(::fcntl(s, F_GETFL, 0), ec); - if (result >= 0) - { - clear_last_error(); - int flag = (value ? (result | O_NONBLOCK) : (result & ~O_NONBLOCK)); - result = error_wrapper(::fcntl(s, F_SETFL, flag), ec); - } -#else - ioctl_arg_type arg = (value ? 1 : 0); - int result = error_wrapper(::ioctl(s, FIONBIO, &arg), ec); -#endif - - if (result >= 0) - { - ec = asio::error_code(); - if (value) - state |= user_set_non_blocking; - else - { - // Clearing the user-set non-blocking mode always overrides any - // internally-set non-blocking flag. Any subsequent asynchronous - // operations will need to re-enable non-blocking I/O. - state &= ~(user_set_non_blocking | internal_non_blocking); - } - return true; - } - - return false; -} - -bool set_internal_non_blocking(socket_type s, - state_type& state, bool value, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return false; - } - - if (!value && (state & user_set_non_blocking)) - { - // It does not make sense to clear the internal non-blocking flag if the - // user still wants non-blocking behaviour. Return an error and let the - // caller figure out whether to update the user-set non-blocking flag. - ec = asio::error::invalid_argument; - return false; - } - - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - ioctl_arg_type arg = (value ? 1 : 0); - int result = error_wrapper(::ioctlsocket(s, FIONBIO, &arg), ec); -#elif defined(__SYMBIAN32__) - int result = error_wrapper(::fcntl(s, F_GETFL, 0), ec); - if (result >= 0) - { - clear_last_error(); - int flag = (value ? (result | O_NONBLOCK) : (result & ~O_NONBLOCK)); - result = error_wrapper(::fcntl(s, F_SETFL, flag), ec); - } -#else - ioctl_arg_type arg = (value ? 1 : 0); - int result = error_wrapper(::ioctl(s, FIONBIO, &arg), ec); -#endif - - if (result >= 0) - { - ec = asio::error_code(); - if (value) - state |= internal_non_blocking; - else - state &= ~internal_non_blocking; - return true; - } - - return false; -} - -int shutdown(socket_type s, int what, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - clear_last_error(); - int result = error_wrapper(::shutdown(s, what), ec); - if (result == 0) - ec = asio::error_code(); - return result; -} - -template -inline int call_connect(SockLenType msghdr::*, - socket_type s, const socket_addr_type* addr, std::size_t addrlen) -{ - return ::connect(s, addr, (SockLenType)addrlen); -} - -int connect(socket_type s, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - clear_last_error(); - int result = error_wrapper(call_connect( - &msghdr::msg_namelen, s, addr, addrlen), ec); - if (result == 0) - ec = asio::error_code(); -#if defined(__linux__) - else if (ec == asio::error::try_again) - ec = asio::error::no_buffer_space; -#endif // defined(__linux__) - return result; -} - -void sync_connect(socket_type s, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec) -{ - // Perform the connect operation. - socket_ops::connect(s, addr, addrlen, ec); - if (ec != asio::error::in_progress - && ec != asio::error::would_block) - { - // The connect operation finished immediately. - return; - } - - // Wait for socket to become ready. - if (socket_ops::poll_connect(s, -1, ec) < 0) - return; - - // Get the error code from the connect operation. - int connect_error = 0; - size_t connect_error_len = sizeof(connect_error); - if (socket_ops::getsockopt(s, 0, SOL_SOCKET, SO_ERROR, - &connect_error, &connect_error_len, ec) == socket_error_retval) - return; - - // Return the result of the connect operation. - ec = asio::error_code(connect_error, - asio::error::get_system_category()); -} - -#if defined(ASIO_HAS_IOCP) - -void complete_iocp_connect(socket_type s, asio::error_code& ec) -{ - // Map non-portable errors to their portable counterparts. - switch (ec.value()) - { - case ERROR_CONNECTION_REFUSED: - ec = asio::error::connection_refused; - break; - case ERROR_NETWORK_UNREACHABLE: - ec = asio::error::network_unreachable; - break; - case ERROR_HOST_UNREACHABLE: - ec = asio::error::host_unreachable; - break; - case ERROR_SEM_TIMEOUT: - ec = asio::error::timed_out; - break; - default: - break; - } - - if (!ec) - { - // Need to set the SO_UPDATE_CONNECT_CONTEXT option so that getsockname - // and getpeername will work on the connected socket. - socket_ops::state_type state = 0; - const int so_update_connect_context = 0x7010; - socket_ops::setsockopt(s, state, SOL_SOCKET, - so_update_connect_context, 0, 0, ec); - } -} - -#endif // defined(ASIO_HAS_IOCP) - -bool non_blocking_connect(socket_type s, asio::error_code& ec) -{ - // Check if the connect operation has finished. This is required since we may - // get spurious readiness notifications from the reactor. -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - fd_set write_fds; - FD_ZERO(&write_fds); - FD_SET(s, &write_fds); - fd_set except_fds; - FD_ZERO(&except_fds); - FD_SET(s, &except_fds); - timeval zero_timeout; - zero_timeout.tv_sec = 0; - zero_timeout.tv_usec = 0; - int ready = ::select(s + 1, 0, &write_fds, &except_fds, &zero_timeout); -#else // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - pollfd fds; - fds.fd = s; - fds.events = POLLOUT; - fds.revents = 0; - int ready = ::poll(&fds, 1, 0); -#endif // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - if (ready == 0) - { - // The asynchronous connect operation is still in progress. - return false; - } - - // Get the error code from the connect operation. - int connect_error = 0; - size_t connect_error_len = sizeof(connect_error); - if (socket_ops::getsockopt(s, 0, SOL_SOCKET, SO_ERROR, - &connect_error, &connect_error_len, ec) == 0) - { - if (connect_error) - { - ec = asio::error_code(connect_error, - asio::error::get_system_category()); - } - else - ec = asio::error_code(); - } - - return true; -} - -int socketpair(int af, int type, int protocol, - socket_type sv[2], asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - (void)(af); - (void)(type); - (void)(protocol); - (void)(sv); - ec = asio::error::operation_not_supported; - return socket_error_retval; -#else - clear_last_error(); - int result = error_wrapper(::socketpair(af, type, protocol, sv), ec); - if (result == 0) - ec = asio::error_code(); - return result; -#endif -} - -bool sockatmark(socket_type s, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return false; - } - -#if defined(SIOCATMARK) - ioctl_arg_type value = 0; -# if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - int result = error_wrapper(::ioctlsocket(s, SIOCATMARK, &value), ec); -# else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - int result = error_wrapper(::ioctl(s, SIOCATMARK, &value), ec); -# endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - if (result == 0) - ec = asio::error_code(); -# if defined(ENOTTY) - if (ec.value() == ENOTTY) - ec = asio::error::not_socket; -# endif // defined(ENOTTY) -#else // defined(SIOCATMARK) - int value = error_wrapper(::sockatmark(s), ec); - if (value != -1) - ec = asio::error_code(); -#endif // defined(SIOCATMARK) - - return ec ? false : value != 0; -} - -size_t available(socket_type s, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return 0; - } - - ioctl_arg_type value = 0; -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - int result = error_wrapper(::ioctlsocket(s, FIONREAD, &value), ec); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - int result = error_wrapper(::ioctl(s, FIONREAD, &value), ec); -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - if (result == 0) - ec = asio::error_code(); -#if defined(ENOTTY) - if (ec.value() == ENOTTY) - ec = asio::error::not_socket; -#endif // defined(ENOTTY) - - return ec ? static_cast(0) : static_cast(value); -} - -int listen(socket_type s, int backlog, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - clear_last_error(); - int result = error_wrapper(::listen(s, backlog), ec); - if (result == 0) - ec = asio::error_code(); - return result; -} - -inline void init_buf_iov_base(void*& base, void* addr) -{ - base = addr; -} - -template -inline void init_buf_iov_base(T& base, void* addr) -{ - base = static_cast(addr); -} - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -typedef WSABUF buf; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -typedef iovec buf; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -void init_buf(buf& b, void* data, size_t size) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - b.buf = static_cast(data); - b.len = static_cast(size); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - init_buf_iov_base(b.iov_base, data); - b.iov_len = size; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -void init_buf(buf& b, const void* data, size_t size) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - b.buf = static_cast(const_cast(data)); - b.len = static_cast(size); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - init_buf_iov_base(b.iov_base, const_cast(data)); - b.iov_len = size; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -inline void init_msghdr_msg_name(void*& name, socket_addr_type* addr) -{ - name = addr; -} - -inline void init_msghdr_msg_name(void*& name, const socket_addr_type* addr) -{ - name = const_cast(addr); -} - -template -inline void init_msghdr_msg_name(T& name, socket_addr_type* addr) -{ - name = reinterpret_cast(addr); -} - -template -inline void init_msghdr_msg_name(T& name, const socket_addr_type* addr) -{ - name = reinterpret_cast(const_cast(addr)); -} - -signed_size_type recv(socket_type s, buf* bufs, size_t count, - int flags, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - // Receive some data. - DWORD recv_buf_count = static_cast(count); - DWORD bytes_transferred = 0; - DWORD recv_flags = flags; - int result = error_wrapper(::WSARecv(s, bufs, - recv_buf_count, &bytes_transferred, &recv_flags, 0, 0), ec); - if (ec.value() == ERROR_NETNAME_DELETED) - ec = asio::error::connection_reset; - else if (ec.value() == ERROR_PORT_UNREACHABLE) - ec = asio::error::connection_refused; - else if (ec.value() == WSAEMSGSIZE || ec.value() == ERROR_MORE_DATA) - ec.assign(0, ec.category()); - if (result != 0) - return socket_error_retval; - ec = asio::error_code(); - return bytes_transferred; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - msghdr msg = msghdr(); - msg.msg_iov = bufs; - msg.msg_iovlen = static_cast(count); - signed_size_type result = error_wrapper(::recvmsg(s, &msg, flags), ec); - if (result >= 0) - ec = asio::error_code(); - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -size_t sync_recv(socket_type s, state_type state, buf* bufs, - size_t count, int flags, bool all_empty, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // A request to read 0 bytes on a stream is a no-op. - if (all_empty && (state & stream_oriented)) - { - ec = asio::error_code(); - return 0; - } - - // Read some data. - for (;;) - { - // Try to complete the operation without blocking. - signed_size_type bytes = socket_ops::recv(s, bufs, count, flags, ec); - - // Check if operation succeeded. - if (bytes > 0) - return bytes; - - // Check for EOF. - if ((state & stream_oriented) && bytes == 0) - { - ec = asio::error::eof; - return 0; - } - - // Operation failed. - if ((state & user_set_non_blocking) - || (ec != asio::error::would_block - && ec != asio::error::try_again)) - return 0; - - // Wait for socket to become ready. - if (socket_ops::poll_read(s, 0, -1, ec) < 0) - return 0; - } -} - -#if defined(ASIO_HAS_IOCP) - -void complete_iocp_recv(state_type state, - const weak_cancel_token_type& cancel_token, bool all_empty, - asio::error_code& ec, size_t bytes_transferred) -{ - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_NETNAME_DELETED) - { - if (cancel_token.expired()) - ec = asio::error::operation_aborted; - else - ec = asio::error::connection_reset; - } - else if (ec.value() == ERROR_PORT_UNREACHABLE) - { - ec = asio::error::connection_refused; - } - else if (ec.value() == WSAEMSGSIZE || ec.value() == ERROR_MORE_DATA) - { - ec.assign(0, ec.category()); - } - - // Check for connection closed. - else if (!ec && bytes_transferred == 0 - && (state & stream_oriented) != 0 - && !all_empty) - { - ec = asio::error::eof; - } -} - -#else // defined(ASIO_HAS_IOCP) - -bool non_blocking_recv(socket_type s, - buf* bufs, size_t count, int flags, bool is_stream, - asio::error_code& ec, size_t& bytes_transferred) -{ - for (;;) - { - // Read some data. - signed_size_type bytes = socket_ops::recv(s, bufs, count, flags, ec); - - // Check for end of stream. - if (is_stream && bytes == 0) - { - ec = asio::error::eof; - return true; - } - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Check if we need to run the operation again. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - return false; - - // Operation is complete. - if (bytes >= 0) - { - ec = asio::error_code(); - bytes_transferred = bytes; - } - else - bytes_transferred = 0; - - return true; - } -} - -#endif // defined(ASIO_HAS_IOCP) - -signed_size_type recvfrom(socket_type s, buf* bufs, size_t count, - int flags, socket_addr_type* addr, std::size_t* addrlen, - asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - // Receive some data. - DWORD recv_buf_count = static_cast(count); - DWORD bytes_transferred = 0; - DWORD recv_flags = flags; - int tmp_addrlen = (int)*addrlen; - int result = error_wrapper(::WSARecvFrom(s, bufs, recv_buf_count, - &bytes_transferred, &recv_flags, addr, &tmp_addrlen, 0, 0), ec); - *addrlen = (std::size_t)tmp_addrlen; - if (ec.value() == ERROR_NETNAME_DELETED) - ec = asio::error::connection_reset; - else if (ec.value() == ERROR_PORT_UNREACHABLE) - ec = asio::error::connection_refused; - else if (ec.value() == WSAEMSGSIZE || ec.value() == ERROR_MORE_DATA) - ec.assign(0, ec.category()); - if (result != 0) - return socket_error_retval; - ec = asio::error_code(); - return bytes_transferred; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - msghdr msg = msghdr(); - init_msghdr_msg_name(msg.msg_name, addr); - msg.msg_namelen = static_cast(*addrlen); - msg.msg_iov = bufs; - msg.msg_iovlen = static_cast(count); - signed_size_type result = error_wrapper(::recvmsg(s, &msg, flags), ec); - *addrlen = msg.msg_namelen; - if (result >= 0) - ec = asio::error_code(); - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -size_t sync_recvfrom(socket_type s, state_type state, buf* bufs, - size_t count, int flags, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // Read some data. - for (;;) - { - // Try to complete the operation without blocking. - signed_size_type bytes = socket_ops::recvfrom( - s, bufs, count, flags, addr, addrlen, ec); - - // Check if operation succeeded. - if (bytes >= 0) - return bytes; - - // Operation failed. - if ((state & user_set_non_blocking) - || (ec != asio::error::would_block - && ec != asio::error::try_again)) - return 0; - - // Wait for socket to become ready. - if (socket_ops::poll_read(s, 0, -1, ec) < 0) - return 0; - } -} - -#if defined(ASIO_HAS_IOCP) - -void complete_iocp_recvfrom( - const weak_cancel_token_type& cancel_token, - asio::error_code& ec) -{ - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_NETNAME_DELETED) - { - if (cancel_token.expired()) - ec = asio::error::operation_aborted; - else - ec = asio::error::connection_reset; - } - else if (ec.value() == ERROR_PORT_UNREACHABLE) - { - ec = asio::error::connection_refused; - } - else if (ec.value() == WSAEMSGSIZE || ec.value() == ERROR_MORE_DATA) - { - ec.assign(0, ec.category()); - } -} - -#else // defined(ASIO_HAS_IOCP) - -bool non_blocking_recvfrom(socket_type s, - buf* bufs, size_t count, int flags, - socket_addr_type* addr, std::size_t* addrlen, - asio::error_code& ec, size_t& bytes_transferred) -{ - for (;;) - { - // Read some data. - signed_size_type bytes = socket_ops::recvfrom( - s, bufs, count, flags, addr, addrlen, ec); - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Check if we need to run the operation again. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - return false; - - // Operation is complete. - if (bytes >= 0) - { - ec = asio::error_code(); - bytes_transferred = bytes; - } - else - bytes_transferred = 0; - - return true; - } -} - -#endif // defined(ASIO_HAS_IOCP) - -signed_size_type recvmsg(socket_type s, buf* bufs, size_t count, - int in_flags, int& out_flags, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - out_flags = 0; - return socket_ops::recv(s, bufs, count, in_flags, ec); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - msghdr msg = msghdr(); - msg.msg_iov = bufs; - msg.msg_iovlen = static_cast(count); - signed_size_type result = error_wrapper(::recvmsg(s, &msg, in_flags), ec); - if (result >= 0) - { - ec = asio::error_code(); - out_flags = msg.msg_flags; - } - else - out_flags = 0; - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -size_t sync_recvmsg(socket_type s, state_type state, - buf* bufs, size_t count, int in_flags, int& out_flags, - asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // Read some data. - for (;;) - { - // Try to complete the operation without blocking. - signed_size_type bytes = socket_ops::recvmsg( - s, bufs, count, in_flags, out_flags, ec); - - // Check if operation succeeded. - if (bytes >= 0) - return bytes; - - // Operation failed. - if ((state & user_set_non_blocking) - || (ec != asio::error::would_block - && ec != asio::error::try_again)) - return 0; - - // Wait for socket to become ready. - if (socket_ops::poll_read(s, 0, -1, ec) < 0) - return 0; - } -} - -#if defined(ASIO_HAS_IOCP) - -void complete_iocp_recvmsg( - const weak_cancel_token_type& cancel_token, - asio::error_code& ec) -{ - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_NETNAME_DELETED) - { - if (cancel_token.expired()) - ec = asio::error::operation_aborted; - else - ec = asio::error::connection_reset; - } - else if (ec.value() == ERROR_PORT_UNREACHABLE) - { - ec = asio::error::connection_refused; - } - else if (ec.value() == WSAEMSGSIZE || ec.value() == ERROR_MORE_DATA) - { - ec.assign(0, ec.category()); - } -} - -#else // defined(ASIO_HAS_IOCP) - -bool non_blocking_recvmsg(socket_type s, - buf* bufs, size_t count, int in_flags, int& out_flags, - asio::error_code& ec, size_t& bytes_transferred) -{ - for (;;) - { - // Read some data. - signed_size_type bytes = socket_ops::recvmsg( - s, bufs, count, in_flags, out_flags, ec); - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Check if we need to run the operation again. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - return false; - - // Operation is complete. - if (bytes >= 0) - { - ec = asio::error_code(); - bytes_transferred = bytes; - } - else - bytes_transferred = 0; - - return true; - } -} - -#endif // defined(ASIO_HAS_IOCP) - -signed_size_type send(socket_type s, const buf* bufs, size_t count, - int flags, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - // Send the data. - DWORD send_buf_count = static_cast(count); - DWORD bytes_transferred = 0; - DWORD send_flags = flags; - int result = error_wrapper(::WSASend(s, const_cast(bufs), - send_buf_count, &bytes_transferred, send_flags, 0, 0), ec); - if (ec.value() == ERROR_NETNAME_DELETED) - ec = asio::error::connection_reset; - else if (ec.value() == ERROR_PORT_UNREACHABLE) - ec = asio::error::connection_refused; - if (result != 0) - return socket_error_retval; - ec = asio::error_code(); - return bytes_transferred; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - msghdr msg = msghdr(); - msg.msg_iov = const_cast(bufs); - msg.msg_iovlen = static_cast(count); -#if defined(__linux__) - flags |= MSG_NOSIGNAL; -#endif // defined(__linux__) - signed_size_type result = error_wrapper(::sendmsg(s, &msg, flags), ec); - if (result >= 0) - ec = asio::error_code(); - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -size_t sync_send(socket_type s, state_type state, const buf* bufs, - size_t count, int flags, bool all_empty, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // A request to write 0 bytes to a stream is a no-op. - if (all_empty && (state & stream_oriented)) - { - ec = asio::error_code(); - return 0; - } - - // Read some data. - for (;;) - { - // Try to complete the operation without blocking. - signed_size_type bytes = socket_ops::send(s, bufs, count, flags, ec); - - // Check if operation succeeded. - if (bytes >= 0) - return bytes; - - // Operation failed. - if ((state & user_set_non_blocking) - || (ec != asio::error::would_block - && ec != asio::error::try_again)) - return 0; - - // Wait for socket to become ready. - if (socket_ops::poll_write(s, 0, -1, ec) < 0) - return 0; - } -} - -#if defined(ASIO_HAS_IOCP) - -void complete_iocp_send( - const weak_cancel_token_type& cancel_token, - asio::error_code& ec) -{ - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_NETNAME_DELETED) - { - if (cancel_token.expired()) - ec = asio::error::operation_aborted; - else - ec = asio::error::connection_reset; - } - else if (ec.value() == ERROR_PORT_UNREACHABLE) - { - ec = asio::error::connection_refused; - } -} - -#else // defined(ASIO_HAS_IOCP) - -bool non_blocking_send(socket_type s, - const buf* bufs, size_t count, int flags, - asio::error_code& ec, size_t& bytes_transferred) -{ - for (;;) - { - // Write some data. - signed_size_type bytes = socket_ops::send(s, bufs, count, flags, ec); - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Check if we need to run the operation again. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - return false; - - // Operation is complete. - if (bytes >= 0) - { - ec = asio::error_code(); - bytes_transferred = bytes; - } - else - bytes_transferred = 0; - - return true; - } -} - -#endif // defined(ASIO_HAS_IOCP) - -signed_size_type sendto(socket_type s, const buf* bufs, size_t count, - int flags, const socket_addr_type* addr, std::size_t addrlen, - asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - // Send the data. - DWORD send_buf_count = static_cast(count); - DWORD bytes_transferred = 0; - int result = error_wrapper(::WSASendTo(s, const_cast(bufs), - send_buf_count, &bytes_transferred, flags, addr, - static_cast(addrlen), 0, 0), ec); - if (ec.value() == ERROR_NETNAME_DELETED) - ec = asio::error::connection_reset; - else if (ec.value() == ERROR_PORT_UNREACHABLE) - ec = asio::error::connection_refused; - if (result != 0) - return socket_error_retval; - ec = asio::error_code(); - return bytes_transferred; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - msghdr msg = msghdr(); - init_msghdr_msg_name(msg.msg_name, addr); - msg.msg_namelen = static_cast(addrlen); - msg.msg_iov = const_cast(bufs); - msg.msg_iovlen = static_cast(count); -#if defined(__linux__) - flags |= MSG_NOSIGNAL; -#endif // defined(__linux__) - signed_size_type result = error_wrapper(::sendmsg(s, &msg, flags), ec); - if (result >= 0) - ec = asio::error_code(); - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -size_t sync_sendto(socket_type s, state_type state, const buf* bufs, - size_t count, int flags, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // Write some data. - for (;;) - { - // Try to complete the operation without blocking. - signed_size_type bytes = socket_ops::sendto( - s, bufs, count, flags, addr, addrlen, ec); - - // Check if operation succeeded. - if (bytes >= 0) - return bytes; - - // Operation failed. - if ((state & user_set_non_blocking) - || (ec != asio::error::would_block - && ec != asio::error::try_again)) - return 0; - - // Wait for socket to become ready. - if (socket_ops::poll_write(s, 0, -1, ec) < 0) - return 0; - } -} - -#if !defined(ASIO_HAS_IOCP) - -bool non_blocking_sendto(socket_type s, - const buf* bufs, size_t count, int flags, - const socket_addr_type* addr, std::size_t addrlen, - asio::error_code& ec, size_t& bytes_transferred) -{ - for (;;) - { - // Write some data. - signed_size_type bytes = socket_ops::sendto( - s, bufs, count, flags, addr, addrlen, ec); - - // Retry operation if interrupted by signal. - if (ec == asio::error::interrupted) - continue; - - // Check if we need to run the operation again. - if (ec == asio::error::would_block - || ec == asio::error::try_again) - return false; - - // Operation is complete. - if (bytes >= 0) - { - ec = asio::error_code(); - bytes_transferred = bytes; - } - else - bytes_transferred = 0; - - return true; - } -} - -#endif // !defined(ASIO_HAS_IOCP) - -socket_type socket(int af, int type, int protocol, - asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - socket_type s = error_wrapper(::WSASocketW(af, type, protocol, 0, 0, - WSA_FLAG_OVERLAPPED), ec); - if (s == invalid_socket) - return s; - - if (af == ASIO_OS_DEF(AF_INET6)) - { - // Try to enable the POSIX default behaviour of having IPV6_V6ONLY set to - // false. This will only succeed on Windows Vista and later versions of - // Windows, where a dual-stack IPv4/v6 implementation is available. - DWORD optval = 0; - ::setsockopt(s, IPPROTO_IPV6, IPV6_V6ONLY, - reinterpret_cast(&optval), sizeof(optval)); - } - - ec = asio::error_code(); - - return s; -#elif defined(__MACH__) && defined(__APPLE__) || defined(__FreeBSD__) - socket_type s = error_wrapper(::socket(af, type, protocol), ec); - if (s == invalid_socket) - return s; - - int optval = 1; - int result = error_wrapper(::setsockopt(s, - SOL_SOCKET, SO_NOSIGPIPE, &optval, sizeof(optval)), ec); - if (result != 0) - { - ::close(s); - return invalid_socket; - } - - return s; -#else - int s = error_wrapper(::socket(af, type, protocol), ec); - if (s >= 0) - ec = asio::error_code(); - return s; -#endif -} - -template -inline int call_setsockopt(SockLenType msghdr::*, - socket_type s, int level, int optname, - const void* optval, std::size_t optlen) -{ - return ::setsockopt(s, level, optname, - (const char*)optval, (SockLenType)optlen); -} - -int setsockopt(socket_type s, state_type& state, int level, int optname, - const void* optval, std::size_t optlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - if (level == custom_socket_option_level && optname == always_fail_option) - { - ec = asio::error::invalid_argument; - return socket_error_retval; - } - - if (level == custom_socket_option_level - && optname == enable_connection_aborted_option) - { - if (optlen != sizeof(int)) - { - ec = asio::error::invalid_argument; - return socket_error_retval; - } - - if (*static_cast(optval)) - state |= enable_connection_aborted; - else - state &= ~enable_connection_aborted; - ec = asio::error_code(); - return 0; - } - - if (level == SOL_SOCKET && optname == SO_LINGER) - state |= user_set_linger; - -#if defined(__BORLANDC__) - // Mysteriously, using the getsockopt and setsockopt functions directly with - // Borland C++ results in incorrect values being set and read. The bug can be - // worked around by using function addresses resolved with GetProcAddress. - if (HMODULE winsock_module = ::GetModuleHandleA("ws2_32")) - { - typedef int (WSAAPI *sso_t)(SOCKET, int, int, const char*, int); - if (sso_t sso = (sso_t)::GetProcAddress(winsock_module, "setsockopt")) - { - clear_last_error(); - return error_wrapper(sso(s, level, optname, - reinterpret_cast(optval), - static_cast(optlen)), ec); - } - } - ec = asio::error::fault; - return socket_error_retval; -#else // defined(__BORLANDC__) - clear_last_error(); - int result = error_wrapper(call_setsockopt(&msghdr::msg_namelen, - s, level, optname, optval, optlen), ec); - if (result == 0) - { - ec = asio::error_code(); - -#if defined(__MACH__) && defined(__APPLE__) \ - || defined(__NetBSD__) || defined(__FreeBSD__) || defined(__OpenBSD__) - // To implement portable behaviour for SO_REUSEADDR with UDP sockets we - // need to also set SO_REUSEPORT on BSD-based platforms. - if ((state & datagram_oriented) - && level == SOL_SOCKET && optname == SO_REUSEADDR) - { - call_setsockopt(&msghdr::msg_namelen, s, - SOL_SOCKET, SO_REUSEPORT, optval, optlen); - } -#endif - } - - return result; -#endif // defined(__BORLANDC__) -} - -template -inline int call_getsockopt(SockLenType msghdr::*, - socket_type s, int level, int optname, - void* optval, std::size_t* optlen) -{ - SockLenType tmp_optlen = (SockLenType)*optlen; - int result = ::getsockopt(s, level, optname, (char*)optval, &tmp_optlen); - *optlen = (std::size_t)tmp_optlen; - return result; -} - -int getsockopt(socket_type s, state_type state, int level, int optname, - void* optval, size_t* optlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - if (level == custom_socket_option_level && optname == always_fail_option) - { - ec = asio::error::invalid_argument; - return socket_error_retval; - } - - if (level == custom_socket_option_level - && optname == enable_connection_aborted_option) - { - if (*optlen != sizeof(int)) - { - ec = asio::error::invalid_argument; - return socket_error_retval; - } - - *static_cast(optval) = (state & enable_connection_aborted) ? 1 : 0; - ec = asio::error_code(); - return 0; - } - -#if defined(__BORLANDC__) - // Mysteriously, using the getsockopt and setsockopt functions directly with - // Borland C++ results in incorrect values being set and read. The bug can be - // worked around by using function addresses resolved with GetProcAddress. - if (HMODULE winsock_module = ::GetModuleHandleA("ws2_32")) - { - typedef int (WSAAPI *gso_t)(SOCKET, int, int, char*, int*); - if (gso_t gso = (gso_t)::GetProcAddress(winsock_module, "getsockopt")) - { - clear_last_error(); - int tmp_optlen = static_cast(*optlen); - int result = error_wrapper(gso(s, level, optname, - reinterpret_cast(optval), &tmp_optlen), ec); - *optlen = static_cast(tmp_optlen); - if (result != 0 && level == IPPROTO_IPV6 && optname == IPV6_V6ONLY - && ec.value() == WSAENOPROTOOPT && *optlen == sizeof(DWORD)) - { - // Dual-stack IPv4/v6 sockets, and the IPV6_V6ONLY socket option, are - // only supported on Windows Vista and later. To simplify program logic - // we will fake success of getting this option and specify that the - // value is non-zero (i.e. true). This corresponds to the behavior of - // IPv6 sockets on Windows platforms pre-Vista. - *static_cast(optval) = 1; - ec = asio::error_code(); - } - return result; - } - } - ec = asio::error::fault; - return socket_error_retval; -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) - clear_last_error(); - int result = error_wrapper(call_getsockopt(&msghdr::msg_namelen, - s, level, optname, optval, optlen), ec); - if (result != 0 && level == IPPROTO_IPV6 && optname == IPV6_V6ONLY - && ec.value() == WSAENOPROTOOPT && *optlen == sizeof(DWORD)) - { - // Dual-stack IPv4/v6 sockets, and the IPV6_V6ONLY socket option, are only - // supported on Windows Vista and later. To simplify program logic we will - // fake success of getting this option and specify that the value is - // non-zero (i.e. true). This corresponds to the behavior of IPv6 sockets - // on Windows platforms pre-Vista. - *static_cast(optval) = 1; - ec = asio::error_code(); - } - if (result == 0) - ec = asio::error_code(); - return result; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - clear_last_error(); - int result = error_wrapper(call_getsockopt(&msghdr::msg_namelen, - s, level, optname, optval, optlen), ec); -#if defined(__linux__) - if (result == 0 && level == SOL_SOCKET && *optlen == sizeof(int) - && (optname == SO_SNDBUF || optname == SO_RCVBUF)) - { - // On Linux, setting SO_SNDBUF or SO_RCVBUF to N actually causes the kernel - // to set the buffer size to N*2. Linux puts additional stuff into the - // buffers so that only about half is actually available to the application. - // The retrieved value is divided by 2 here to make it appear as though the - // correct value has been set. - *static_cast(optval) /= 2; - } -#endif // defined(__linux__) - if (result == 0) - ec = asio::error_code(); - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -template -inline int call_getpeername(SockLenType msghdr::*, - socket_type s, socket_addr_type* addr, std::size_t* addrlen) -{ - SockLenType tmp_addrlen = (SockLenType)*addrlen; - int result = ::getpeername(s, addr, &tmp_addrlen); - *addrlen = (std::size_t)tmp_addrlen; - return result; -} - -int getpeername(socket_type s, socket_addr_type* addr, - std::size_t* addrlen, bool cached, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - -#if defined(ASIO_WINDOWS) && !defined(ASIO_WINDOWS_APP) \ - || defined(__CYGWIN__) - if (cached) - { - // Check if socket is still connected. - DWORD connect_time = 0; - size_t connect_time_len = sizeof(connect_time); - if (socket_ops::getsockopt(s, 0, SOL_SOCKET, SO_CONNECT_TIME, - &connect_time, &connect_time_len, ec) == socket_error_retval) - { - return socket_error_retval; - } - if (connect_time == 0xFFFFFFFF) - { - ec = asio::error::not_connected; - return socket_error_retval; - } - - // The cached value is still valid. - ec = asio::error_code(); - return 0; - } -#else // defined(ASIO_WINDOWS) && !defined(ASIO_WINDOWS_APP) - // || defined(__CYGWIN__) - (void)cached; -#endif // defined(ASIO_WINDOWS) && !defined(ASIO_WINDOWS_APP) - // || defined(__CYGWIN__) - - clear_last_error(); - int result = error_wrapper(call_getpeername( - &msghdr::msg_namelen, s, addr, addrlen), ec); - if (result == 0) - ec = asio::error_code(); - return result; -} - -template -inline int call_getsockname(SockLenType msghdr::*, - socket_type s, socket_addr_type* addr, std::size_t* addrlen) -{ - SockLenType tmp_addrlen = (SockLenType)*addrlen; - int result = ::getsockname(s, addr, &tmp_addrlen); - *addrlen = (std::size_t)tmp_addrlen; - return result; -} - -int getsockname(socket_type s, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - clear_last_error(); - int result = error_wrapper(call_getsockname( - &msghdr::msg_namelen, s, addr, addrlen), ec); - if (result == 0) - ec = asio::error_code(); - return result; -} - -int ioctl(socket_type s, state_type& state, int cmd, - ioctl_arg_type* arg, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - int result = error_wrapper(::ioctlsocket(s, cmd, arg), ec); -#elif defined(__MACH__) && defined(__APPLE__) \ - || defined(__NetBSD__) || defined(__FreeBSD__) || defined(__OpenBSD__) - int result = error_wrapper(::ioctl(s, - static_cast(cmd), arg), ec); -#else - int result = error_wrapper(::ioctl(s, cmd, arg), ec); -#endif - if (result >= 0) - { - ec = asio::error_code(); - - // When updating the non-blocking mode we always perform the ioctl syscall, - // even if the flags would otherwise indicate that the socket is already in - // the correct state. This ensures that the underlying socket is put into - // the state that has been requested by the user. If the ioctl syscall was - // successful then we need to update the flags to match. - if (cmd == static_cast(FIONBIO)) - { - if (*arg) - { - state |= user_set_non_blocking; - } - else - { - // Clearing the non-blocking mode always overrides any internally-set - // non-blocking flag. Any subsequent asynchronous operations will need - // to re-enable non-blocking I/O. - state &= ~(user_set_non_blocking | internal_non_blocking); - } - } - } - - return result; -} - -int select(int nfds, fd_set* readfds, fd_set* writefds, - fd_set* exceptfds, timeval* timeout, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - if (!readfds && !writefds && !exceptfds && timeout) - { - DWORD milliseconds = timeout->tv_sec * 1000 + timeout->tv_usec / 1000; - if (milliseconds == 0) - milliseconds = 1; // Force context switch. - ::Sleep(milliseconds); - ec = asio::error_code(); - return 0; - } - - // The select() call allows timeout values measured in microseconds, but the - // system clock (as wrapped by boost::posix_time::microsec_clock) typically - // has a resolution of 10 milliseconds. This can lead to a spinning select - // reactor, meaning increased CPU usage, when waiting for the earliest - // scheduled timeout if it's less than 10 milliseconds away. To avoid a tight - // spin we'll use a minimum timeout of 1 millisecond. - if (timeout && timeout->tv_sec == 0 - && timeout->tv_usec > 0 && timeout->tv_usec < 1000) - timeout->tv_usec = 1000; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#if defined(__hpux) && defined(__SELECT) - timespec ts; - ts.tv_sec = timeout ? timeout->tv_sec : 0; - ts.tv_nsec = timeout ? timeout->tv_usec * 1000 : 0; - return error_wrapper(::pselect(nfds, readfds, - writefds, exceptfds, timeout ? &ts : 0, 0), ec); -#else - int result = error_wrapper(::select(nfds, readfds, - writefds, exceptfds, timeout), ec); - if (result >= 0) - ec = asio::error_code(); - return result; -#endif -} - -int poll_read(socket_type s, state_type state, - int msec, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - fd_set fds; - FD_ZERO(&fds); - FD_SET(s, &fds); - timeval timeout_obj; - timeval* timeout; - if (state & user_set_non_blocking) - { - timeout_obj.tv_sec = 0; - timeout_obj.tv_usec = 0; - timeout = &timeout_obj; - } - else if (msec >= 0) - { - timeout_obj.tv_sec = msec / 1000; - timeout_obj.tv_usec = (msec % 1000) * 1000; - timeout = &timeout_obj; - } - else - timeout = 0; - clear_last_error(); - int result = error_wrapper(::select(s + 1, &fds, 0, 0, timeout), ec); -#else // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - pollfd fds; - fds.fd = s; - fds.events = POLLIN; - fds.revents = 0; - int timeout = (state & user_set_non_blocking) ? 0 : msec; - clear_last_error(); - int result = error_wrapper(::poll(&fds, 1, timeout), ec); -#endif // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - if (result == 0) - ec = (state & user_set_non_blocking) - ? asio::error::would_block : asio::error_code(); - else if (result > 0) - ec = asio::error_code(); - return result; -} - -int poll_write(socket_type s, state_type state, - int msec, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - fd_set fds; - FD_ZERO(&fds); - FD_SET(s, &fds); - timeval timeout_obj; - timeval* timeout; - if (state & user_set_non_blocking) - { - timeout_obj.tv_sec = 0; - timeout_obj.tv_usec = 0; - timeout = &timeout_obj; - } - else if (msec >= 0) - { - timeout_obj.tv_sec = msec / 1000; - timeout_obj.tv_usec = (msec % 1000) * 1000; - timeout = &timeout_obj; - } - else - timeout = 0; - clear_last_error(); - int result = error_wrapper(::select(s + 1, 0, &fds, 0, timeout), ec); -#else // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - pollfd fds; - fds.fd = s; - fds.events = POLLOUT; - fds.revents = 0; - int timeout = (state & user_set_non_blocking) ? 0 : msec; - clear_last_error(); - int result = error_wrapper(::poll(&fds, 1, timeout), ec); -#endif // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - if (result == 0) - ec = (state & user_set_non_blocking) - ? asio::error::would_block : asio::error_code(); - else if (result > 0) - ec = asio::error_code(); - return result; -} - -int poll_error(socket_type s, state_type state, - int msec, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - fd_set fds; - FD_ZERO(&fds); - FD_SET(s, &fds); - timeval timeout_obj; - timeval* timeout; - if (state & user_set_non_blocking) - { - timeout_obj.tv_sec = 0; - timeout_obj.tv_usec = 0; - timeout = &timeout_obj; - } - else if (msec >= 0) - { - timeout_obj.tv_sec = msec / 1000; - timeout_obj.tv_usec = (msec % 1000) * 1000; - timeout = &timeout_obj; - } - else - timeout = 0; - clear_last_error(); - int result = error_wrapper(::select(s + 1, 0, 0, &fds, timeout), ec); -#else // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - pollfd fds; - fds.fd = s; - fds.events = POLLPRI | POLLERR | POLLHUP; - fds.revents = 0; - int timeout = (state & user_set_non_blocking) ? 0 : msec; - clear_last_error(); - int result = error_wrapper(::poll(&fds, 1, timeout), ec); -#endif // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - if (result == 0) - ec = (state & user_set_non_blocking) - ? asio::error::would_block : asio::error_code(); - else if (result > 0) - ec = asio::error_code(); - return result; -} - -int poll_connect(socket_type s, int msec, asio::error_code& ec) -{ - if (s == invalid_socket) - { - ec = asio::error::bad_descriptor; - return socket_error_retval; - } - -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - fd_set write_fds; - FD_ZERO(&write_fds); - FD_SET(s, &write_fds); - fd_set except_fds; - FD_ZERO(&except_fds); - FD_SET(s, &except_fds); - timeval timeout_obj; - timeval* timeout; - if (msec >= 0) - { - timeout_obj.tv_sec = msec / 1000; - timeout_obj.tv_usec = (msec % 1000) * 1000; - timeout = &timeout_obj; - } - else - timeout = 0; - clear_last_error(); - int result = error_wrapper(::select( - s + 1, 0, &write_fds, &except_fds, timeout), ec); - if (result >= 0) - ec = asio::error_code(); - return result; -#else // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - pollfd fds; - fds.fd = s; - fds.events = POLLOUT; - fds.revents = 0; - clear_last_error(); - int result = error_wrapper(::poll(&fds, 1, msec), ec); - if (result >= 0) - ec = asio::error_code(); - return result; -#endif // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) -} - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -const char* inet_ntop(int af, const void* src, char* dest, size_t length, - unsigned long scope_id, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS_RUNTIME) - using namespace std; // For sprintf. - const unsigned char* bytes = static_cast(src); - if (af == ASIO_OS_DEF(AF_INET)) - { - sprintf_s(dest, length, "%u.%u.%u.%u", - bytes[0], bytes[1], bytes[2], bytes[3]); - return dest; - } - else if (af == ASIO_OS_DEF(AF_INET6)) - { - size_t n = 0, b = 0, z = 0; - while (n < length && b < 16) - { - if (bytes[b] == 0 && bytes[b + 1] == 0 && z == 0) - { - do b += 2; while (b < 16 && bytes[b] == 0 && bytes[b + 1] == 0); - n += sprintf_s(dest + n, length - n, ":%s", b < 16 ? "" : ":"), ++z; - } - else - { - n += sprintf_s(dest + n, length - n, "%s%x", b ? ":" : "", - (static_cast(bytes[b]) << 8) | bytes[b + 1]); - b += 2; - } - } - if (scope_id) - n += sprintf_s(dest + n, length - n, "%%%lu", scope_id); - return dest; - } - else - { - ec = asio::error::address_family_not_supported; - return 0; - } -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) - using namespace std; // For memcpy. - - if (af != ASIO_OS_DEF(AF_INET) && af != ASIO_OS_DEF(AF_INET6)) - { - ec = asio::error::address_family_not_supported; - return 0; - } - - union - { - socket_addr_type base; - sockaddr_storage_type storage; - sockaddr_in4_type v4; - sockaddr_in6_type v6; - } address; - DWORD address_length; - if (af == ASIO_OS_DEF(AF_INET)) - { - address_length = sizeof(sockaddr_in4_type); - address.v4.sin_family = ASIO_OS_DEF(AF_INET); - address.v4.sin_port = 0; - memcpy(&address.v4.sin_addr, src, sizeof(in4_addr_type)); - } - else // AF_INET6 - { - address_length = sizeof(sockaddr_in6_type); - address.v6.sin6_family = ASIO_OS_DEF(AF_INET6); - address.v6.sin6_port = 0; - address.v6.sin6_flowinfo = 0; - address.v6.sin6_scope_id = scope_id; - memcpy(&address.v6.sin6_addr, src, sizeof(in6_addr_type)); - } - - DWORD string_length = static_cast(length); -#if defined(BOOST_NO_ANSI_APIS) || (defined(_MSC_VER) && (_MSC_VER >= 1800)) - LPWSTR string_buffer = (LPWSTR)_alloca(length * sizeof(WCHAR)); - int result = error_wrapper(::WSAAddressToStringW(&address.base, - address_length, 0, string_buffer, &string_length), ec); - ::WideCharToMultiByte(CP_ACP, 0, string_buffer, -1, - dest, static_cast(length), 0, 0); -#else - int result = error_wrapper(::WSAAddressToStringA( - &address.base, address_length, 0, dest, &string_length), ec); -#endif - - // Windows may set error code on success. - if (result != socket_error_retval) - ec = asio::error_code(); - - // Windows may not set an error code on failure. - else if (result == socket_error_retval && !ec) - ec = asio::error::invalid_argument; - - return result == socket_error_retval ? 0 : dest; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - const char* result = error_wrapper(::inet_ntop( - af, src, dest, static_cast(length)), ec); - if (result == 0 && !ec) - ec = asio::error::invalid_argument; - if (result != 0 && af == ASIO_OS_DEF(AF_INET6) && scope_id != 0) - { - using namespace std; // For strcat and sprintf. - char if_name[IF_NAMESIZE + 1] = "%"; - const in6_addr_type* ipv6_address = static_cast(src); - bool is_link_local = ((ipv6_address->s6_addr[0] == 0xfe) - && ((ipv6_address->s6_addr[1] & 0xc0) == 0x80)); - bool is_multicast_link_local = ((ipv6_address->s6_addr[0] == 0xff) - && ((ipv6_address->s6_addr[1] & 0x0f) == 0x02)); - if ((!is_link_local && !is_multicast_link_local) - || if_indextoname(static_cast(scope_id), if_name + 1) == 0) - sprintf(if_name + 1, "%lu", scope_id); - strcat(dest, if_name); - } - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -int inet_pton(int af, const char* src, void* dest, - unsigned long* scope_id, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS_RUNTIME) - using namespace std; // For sscanf. - unsigned char* bytes = static_cast(dest); - if (af == ASIO_OS_DEF(AF_INET)) - { - unsigned int b0, b1, b2, b3; - if (sscanf_s(src, "%u.%u.%u.%u", &b0, &b1, &b2, &b3) != 4) - { - ec = asio::error::invalid_argument; - return -1; - } - if (b0 > 255 || b1 > 255 || b2 > 255 || b3 > 255) - { - ec = asio::error::invalid_argument; - return -1; - } - bytes[0] = static_cast(b0); - bytes[1] = static_cast(b1); - bytes[2] = static_cast(b2); - bytes[3] = static_cast(b3); - ec = asio::error_code(); - return 1; - } - else if (af == ASIO_OS_DEF(AF_INET6)) - { - unsigned char* bytes = static_cast(dest); - std::memset(bytes, 0, 16); - unsigned char back_bytes[16] = { 0 }; - int num_front_bytes = 0, num_back_bytes = 0; - const char* p = src; - - enum { fword, fcolon, bword, scope, done } state = fword; - unsigned long current_word = 0; - while (state != done) - { - if (current_word > 0xFFFF) - { - ec = asio::error::invalid_argument; - return -1; - } - - switch (state) - { - case fword: - if (*p >= '0' && *p <= '9') - current_word = current_word * 16 + *p++ - '0'; - else if (*p >= 'a' && *p <= 'f') - current_word = current_word * 16 + *p++ - 'a' + 10; - else if (*p >= 'A' && *p <= 'F') - current_word = current_word * 16 + *p++ - 'A' + 10; - else - { - if (num_front_bytes == 16) - { - ec = asio::error::invalid_argument; - return -1; - } - - bytes[num_front_bytes++] = (current_word >> 8) & 0xFF; - bytes[num_front_bytes++] = current_word & 0xFF; - current_word = 0; - - if (*p == ':') - state = fcolon, ++p; - else if (*p == '%') - state = scope, ++p; - else if (*p == 0) - state = done; - else - { - ec = asio::error::invalid_argument; - return -1; - } - } - break; - - case fcolon: - if (*p == ':') - state = bword, ++p; - else - state = fword; - break; - - case bword: - if (*p >= '0' && *p <= '9') - current_word = current_word * 16 + *p++ - '0'; - else if (*p >= 'a' && *p <= 'f') - current_word = current_word * 16 + *p++ - 'a' + 10; - else if (*p >= 'A' && *p <= 'F') - current_word = current_word * 16 + *p++ - 'A' + 10; - else - { - if (num_front_bytes + num_back_bytes == 16) - { - ec = asio::error::invalid_argument; - return -1; - } - - back_bytes[num_back_bytes++] = (current_word >> 8) & 0xFF; - back_bytes[num_back_bytes++] = current_word & 0xFF; - current_word = 0; - - if (*p == ':') - state = bword, ++p; - else if (*p == '%') - state = scope, ++p; - else if (*p == 0) - state = done; - else - { - ec = asio::error::invalid_argument; - return -1; - } - } - break; - - case scope: - if (*p >= '0' && *p <= '9') - current_word = current_word * 10 + *p++ - '0'; - else if (*p == 0) - *scope_id = current_word, state = done; - else - { - ec = asio::error::invalid_argument; - return -1; - } - break; - - default: - break; - } - } - - for (int i = 0; i < num_back_bytes; ++i) - bytes[16 - num_back_bytes + i] = back_bytes[i]; - - ec = asio::error_code(); - return 1; - } - else - { - ec = asio::error::address_family_not_supported; - return -1; - } -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) - using namespace std; // For memcpy and strcmp. - - if (af != ASIO_OS_DEF(AF_INET) && af != ASIO_OS_DEF(AF_INET6)) - { - ec = asio::error::address_family_not_supported; - return -1; - } - - union - { - socket_addr_type base; - sockaddr_storage_type storage; - sockaddr_in4_type v4; - sockaddr_in6_type v6; - } address; - int address_length = sizeof(sockaddr_storage_type); -#if defined(BOOST_NO_ANSI_APIS) || (defined(_MSC_VER) && (_MSC_VER >= 1800)) - int num_wide_chars = static_cast(strlen(src)) + 1; - LPWSTR wide_buffer = (LPWSTR)_alloca(num_wide_chars * sizeof(WCHAR)); - ::MultiByteToWideChar(CP_ACP, 0, src, -1, wide_buffer, num_wide_chars); - int result = error_wrapper(::WSAStringToAddressW( - wide_buffer, af, 0, &address.base, &address_length), ec); -#else - int result = error_wrapper(::WSAStringToAddressA( - const_cast(src), af, 0, &address.base, &address_length), ec); -#endif - - if (af == ASIO_OS_DEF(AF_INET)) - { - if (result != socket_error_retval) - { - memcpy(dest, &address.v4.sin_addr, sizeof(in4_addr_type)); - ec = asio::error_code(); - } - else if (strcmp(src, "255.255.255.255") == 0) - { - static_cast(dest)->s_addr = INADDR_NONE; - ec = asio::error_code(); - } - } - else // AF_INET6 - { - if (result != socket_error_retval) - { - memcpy(dest, &address.v6.sin6_addr, sizeof(in6_addr_type)); - if (scope_id) - *scope_id = address.v6.sin6_scope_id; - ec = asio::error_code(); - } - } - - // Windows may not set an error code on failure. - if (result == socket_error_retval && !ec) - ec = asio::error::invalid_argument; - - if (result != socket_error_retval) - ec = asio::error_code(); - - return result == socket_error_retval ? -1 : 1; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - using namespace std; // For strchr, memcpy and atoi. - - // On some platforms, inet_pton fails if an address string contains a scope - // id. Detect and remove the scope id before passing the string to inet_pton. - const bool is_v6 = (af == ASIO_OS_DEF(AF_INET6)); - const char* if_name = is_v6 ? strchr(src, '%') : 0; - char src_buf[max_addr_v6_str_len + 1]; - const char* src_ptr = src; - if (if_name != 0) - { - if (if_name - src > max_addr_v6_str_len) - { - ec = asio::error::invalid_argument; - return 0; - } - memcpy(src_buf, src, if_name - src); - src_buf[if_name - src] = 0; - src_ptr = src_buf; - } - - int result = error_wrapper(::inet_pton(af, src_ptr, dest), ec); - if (result <= 0 && !ec) - ec = asio::error::invalid_argument; - if (result > 0 && is_v6 && scope_id) - { - using namespace std; // For strchr and atoi. - *scope_id = 0; - if (if_name != 0) - { - in6_addr_type* ipv6_address = static_cast(dest); - bool is_link_local = ((ipv6_address->s6_addr[0] == 0xfe) - && ((ipv6_address->s6_addr[1] & 0xc0) == 0x80)); - bool is_multicast_link_local = ((ipv6_address->s6_addr[0] == 0xff) - && ((ipv6_address->s6_addr[1] & 0x0f) == 0x02)); - if (is_link_local || is_multicast_link_local) - *scope_id = if_nametoindex(if_name + 1); - if (*scope_id == 0) - *scope_id = atoi(if_name + 1); - } - } - return result; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -} - -int gethostname(char* name, int namelen, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS_RUNTIME) - try - { - using namespace Windows::Foundation::Collections; - using namespace Windows::Networking; - using namespace Windows::Networking::Connectivity; - IVectorView^ hostnames = NetworkInformation::GetHostNames(); - for (unsigned i = 0; i < hostnames->Size; ++i) - { - HostName^ hostname = hostnames->GetAt(i); - if (hostname->Type == HostNameType::DomainName) - { - std::wstring_convert> converter; - std::string raw_name = converter.to_bytes(hostname->RawName->Data()); - if (namelen > 0 && raw_name.size() < static_cast(namelen)) - { - strcpy_s(name, namelen, raw_name.c_str()); - return 0; - } - } - } - return -1; - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - return -1; - } -#else // defined(ASIO_WINDOWS_RUNTIME) - int result = error_wrapper(::gethostname(name, namelen), ec); -# if defined(ASIO_WINDOWS) - if (result == 0) - ec = asio::error_code(); -# endif // defined(ASIO_WINDOWS) - return result; -#endif // defined(ASIO_WINDOWS_RUNTIME) -} - -#if !defined(ASIO_WINDOWS_RUNTIME) - -#if !defined(ASIO_HAS_GETADDRINFO) - -// The following functions are only needed for emulation of getaddrinfo and -// getnameinfo. - -inline asio::error_code translate_netdb_error(int error) -{ - switch (error) - { - case 0: - return asio::error_code(); - case HOST_NOT_FOUND: - return asio::error::host_not_found; - case TRY_AGAIN: - return asio::error::host_not_found_try_again; - case NO_RECOVERY: - return asio::error::no_recovery; - case NO_DATA: - return asio::error::no_data; - default: - ASIO_ASSERT(false); - return asio::error::invalid_argument; - } -} - -inline hostent* gethostbyaddr(const char* addr, int length, int af, - hostent* result, char* buffer, int buflength, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - (void)(buffer); - (void)(buflength); - hostent* retval = error_wrapper(::gethostbyaddr(addr, length, af), ec); - if (!retval) - return 0; - ec = asio::error_code(); - *result = *retval; - return retval; -#elif defined(__sun) || defined(__QNX__) - int error = 0; - hostent* retval = error_wrapper(::gethostbyaddr_r(addr, length, af, result, - buffer, buflength, &error), ec); - if (error) - ec = translate_netdb_error(error); - return retval; -#elif defined(__MACH__) && defined(__APPLE__) - (void)(buffer); - (void)(buflength); - int error = 0; - hostent* retval = error_wrapper(::getipnodebyaddr( - addr, length, af, &error), ec); - if (error) - ec = translate_netdb_error(error); - if (!retval) - return 0; - *result = *retval; - return retval; -#else - hostent* retval = 0; - int error = 0; - error_wrapper(::gethostbyaddr_r(addr, length, af, result, buffer, - buflength, &retval, &error), ec); - if (error) - ec = translate_netdb_error(error); - return retval; -#endif -} - -inline hostent* gethostbyname(const char* name, int af, struct hostent* result, - char* buffer, int buflength, int ai_flags, asio::error_code& ec) -{ - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - (void)(buffer); - (void)(buflength); - (void)(ai_flags); - if (af != ASIO_OS_DEF(AF_INET)) - { - ec = asio::error::address_family_not_supported; - return 0; - } - hostent* retval = error_wrapper(::gethostbyname(name), ec); - if (!retval) - return 0; - ec = asio::error_code(); - *result = *retval; - return result; -#elif defined(__sun) || defined(__QNX__) - (void)(ai_flags); - if (af != ASIO_OS_DEF(AF_INET)) - { - ec = asio::error::address_family_not_supported; - return 0; - } - int error = 0; - hostent* retval = error_wrapper(::gethostbyname_r(name, result, buffer, - buflength, &error), ec); - if (error) - ec = translate_netdb_error(error); - return retval; -#elif defined(__MACH__) && defined(__APPLE__) - (void)(buffer); - (void)(buflength); - int error = 0; - hostent* retval = error_wrapper(::getipnodebyname( - name, af, ai_flags, &error), ec); - if (error) - ec = translate_netdb_error(error); - if (!retval) - return 0; - *result = *retval; - return retval; -#else - (void)(ai_flags); - if (af != ASIO_OS_DEF(AF_INET)) - { - ec = asio::error::address_family_not_supported; - return 0; - } - hostent* retval = 0; - int error = 0; - error_wrapper(::gethostbyname_r(name, result, - buffer, buflength, &retval, &error), ec); - if (error) - ec = translate_netdb_error(error); - return retval; -#endif -} - -inline void freehostent(hostent* h) -{ -#if defined(__MACH__) && defined(__APPLE__) - if (h) - ::freehostent(h); -#else - (void)(h); -#endif -} - -// Emulation of getaddrinfo based on implementation in: -// Stevens, W. R., UNIX Network Programming Vol. 1, 2nd Ed., Prentice-Hall 1998. - -struct gai_search -{ - const char* host; - int family; -}; - -inline int gai_nsearch(const char* host, - const addrinfo_type* hints, gai_search (&search)[2]) -{ - int search_count = 0; - if (host == 0 || host[0] == '\0') - { - if (hints->ai_flags & AI_PASSIVE) - { - // No host and AI_PASSIVE implies wildcard bind. - switch (hints->ai_family) - { - case ASIO_OS_DEF(AF_INET): - search[search_count].host = "0.0.0.0"; - search[search_count].family = ASIO_OS_DEF(AF_INET); - ++search_count; - break; - case ASIO_OS_DEF(AF_INET6): - search[search_count].host = "0::0"; - search[search_count].family = ASIO_OS_DEF(AF_INET6); - ++search_count; - break; - case ASIO_OS_DEF(AF_UNSPEC): - search[search_count].host = "0::0"; - search[search_count].family = ASIO_OS_DEF(AF_INET6); - ++search_count; - search[search_count].host = "0.0.0.0"; - search[search_count].family = ASIO_OS_DEF(AF_INET); - ++search_count; - break; - default: - break; - } - } - else - { - // No host and not AI_PASSIVE means connect to local host. - switch (hints->ai_family) - { - case ASIO_OS_DEF(AF_INET): - search[search_count].host = "localhost"; - search[search_count].family = ASIO_OS_DEF(AF_INET); - ++search_count; - break; - case ASIO_OS_DEF(AF_INET6): - search[search_count].host = "localhost"; - search[search_count].family = ASIO_OS_DEF(AF_INET6); - ++search_count; - break; - case ASIO_OS_DEF(AF_UNSPEC): - search[search_count].host = "localhost"; - search[search_count].family = ASIO_OS_DEF(AF_INET6); - ++search_count; - search[search_count].host = "localhost"; - search[search_count].family = ASIO_OS_DEF(AF_INET); - ++search_count; - break; - default: - break; - } - } - } - else - { - // Host is specified. - switch (hints->ai_family) - { - case ASIO_OS_DEF(AF_INET): - search[search_count].host = host; - search[search_count].family = ASIO_OS_DEF(AF_INET); - ++search_count; - break; - case ASIO_OS_DEF(AF_INET6): - search[search_count].host = host; - search[search_count].family = ASIO_OS_DEF(AF_INET6); - ++search_count; - break; - case ASIO_OS_DEF(AF_UNSPEC): - search[search_count].host = host; - search[search_count].family = ASIO_OS_DEF(AF_INET6); - ++search_count; - search[search_count].host = host; - search[search_count].family = ASIO_OS_DEF(AF_INET); - ++search_count; - break; - default: - break; - } - } - return search_count; -} - -template -inline T* gai_alloc(std::size_t size = sizeof(T)) -{ - using namespace std; - T* p = static_cast(::operator new(size, std::nothrow)); - if (p) - memset(p, 0, size); - return p; -} - -inline void gai_free(void* p) -{ - ::operator delete(p); -} - -inline void gai_strcpy(char* target, const char* source, std::size_t max_size) -{ - using namespace std; -#if defined(ASIO_HAS_SECURE_RTL) - strcpy_s(target, max_size, source); -#else // defined(ASIO_HAS_SECURE_RTL) - *target = 0; - if (max_size > 0) - strncat(target, source, max_size - 1); -#endif // defined(ASIO_HAS_SECURE_RTL) -} - -enum { gai_clone_flag = 1 << 30 }; - -inline int gai_aistruct(addrinfo_type*** next, const addrinfo_type* hints, - const void* addr, int family) -{ - using namespace std; - - addrinfo_type* ai = gai_alloc(); - if (ai == 0) - return EAI_MEMORY; - - ai->ai_next = 0; - **next = ai; - *next = &ai->ai_next; - - ai->ai_canonname = 0; - ai->ai_socktype = hints->ai_socktype; - if (ai->ai_socktype == 0) - ai->ai_flags |= gai_clone_flag; - ai->ai_protocol = hints->ai_protocol; - ai->ai_family = family; - - switch (ai->ai_family) - { - case ASIO_OS_DEF(AF_INET): - { - sockaddr_in4_type* sinptr = gai_alloc(); - if (sinptr == 0) - return EAI_MEMORY; - sinptr->sin_family = ASIO_OS_DEF(AF_INET); - memcpy(&sinptr->sin_addr, addr, sizeof(in4_addr_type)); - ai->ai_addr = reinterpret_cast(sinptr); - ai->ai_addrlen = sizeof(sockaddr_in4_type); - break; - } - case ASIO_OS_DEF(AF_INET6): - { - sockaddr_in6_type* sin6ptr = gai_alloc(); - if (sin6ptr == 0) - return EAI_MEMORY; - sin6ptr->sin6_family = ASIO_OS_DEF(AF_INET6); - memcpy(&sin6ptr->sin6_addr, addr, sizeof(in6_addr_type)); - ai->ai_addr = reinterpret_cast(sin6ptr); - ai->ai_addrlen = sizeof(sockaddr_in6_type); - break; - } - default: - break; - } - - return 0; -} - -inline addrinfo_type* gai_clone(addrinfo_type* ai) -{ - using namespace std; - - addrinfo_type* new_ai = gai_alloc(); - if (new_ai == 0) - return new_ai; - - new_ai->ai_next = ai->ai_next; - ai->ai_next = new_ai; - - new_ai->ai_flags = 0; - new_ai->ai_family = ai->ai_family; - new_ai->ai_socktype = ai->ai_socktype; - new_ai->ai_protocol = ai->ai_protocol; - new_ai->ai_canonname = 0; - new_ai->ai_addrlen = ai->ai_addrlen; - new_ai->ai_addr = gai_alloc(ai->ai_addrlen); - memcpy(new_ai->ai_addr, ai->ai_addr, ai->ai_addrlen); - - return new_ai; -} - -inline int gai_port(addrinfo_type* aihead, int port, int socktype) -{ - int num_found = 0; - - for (addrinfo_type* ai = aihead; ai; ai = ai->ai_next) - { - if (ai->ai_flags & gai_clone_flag) - { - if (ai->ai_socktype != 0) - { - ai = gai_clone(ai); - if (ai == 0) - return -1; - // ai now points to newly cloned entry. - } - } - else if (ai->ai_socktype != socktype) - { - // Ignore if mismatch on socket type. - continue; - } - - ai->ai_socktype = socktype; - - switch (ai->ai_family) - { - case ASIO_OS_DEF(AF_INET): - { - sockaddr_in4_type* sinptr = - reinterpret_cast(ai->ai_addr); - sinptr->sin_port = port; - ++num_found; - break; - } - case ASIO_OS_DEF(AF_INET6): - { - sockaddr_in6_type* sin6ptr = - reinterpret_cast(ai->ai_addr); - sin6ptr->sin6_port = port; - ++num_found; - break; - } - default: - break; - } - } - - return num_found; -} - -inline int gai_serv(addrinfo_type* aihead, - const addrinfo_type* hints, const char* serv) -{ - using namespace std; - - int num_found = 0; - - if ( -#if defined(AI_NUMERICSERV) - (hints->ai_flags & AI_NUMERICSERV) || -#endif - isdigit(static_cast(serv[0]))) - { - int port = htons(atoi(serv)); - if (hints->ai_socktype) - { - // Caller specifies socket type. - int rc = gai_port(aihead, port, hints->ai_socktype); - if (rc < 0) - return EAI_MEMORY; - num_found += rc; - } - else - { - // Caller does not specify socket type. - int rc = gai_port(aihead, port, SOCK_STREAM); - if (rc < 0) - return EAI_MEMORY; - num_found += rc; - rc = gai_port(aihead, port, SOCK_DGRAM); - if (rc < 0) - return EAI_MEMORY; - num_found += rc; - } - } - else - { - // Try service name with TCP first, then UDP. - if (hints->ai_socktype == 0 || hints->ai_socktype == SOCK_STREAM) - { - servent* sptr = getservbyname(serv, "tcp"); - if (sptr != 0) - { - int rc = gai_port(aihead, sptr->s_port, SOCK_STREAM); - if (rc < 0) - return EAI_MEMORY; - num_found += rc; - } - } - if (hints->ai_socktype == 0 || hints->ai_socktype == SOCK_DGRAM) - { - servent* sptr = getservbyname(serv, "udp"); - if (sptr != 0) - { - int rc = gai_port(aihead, sptr->s_port, SOCK_DGRAM); - if (rc < 0) - return EAI_MEMORY; - num_found += rc; - } - } - } - - if (num_found == 0) - { - if (hints->ai_socktype == 0) - { - // All calls to getservbyname() failed. - return EAI_NONAME; - } - else - { - // Service not supported for socket type. - return EAI_SERVICE; - } - } - - return 0; -} - -inline int gai_echeck(const char* host, const char* service, - int flags, int family, int socktype, int protocol) -{ - (void)(flags); - (void)(protocol); - - // Host or service must be specified. - if (host == 0 || host[0] == '\0') - if (service == 0 || service[0] == '\0') - return EAI_NONAME; - - // Check combination of family and socket type. - switch (family) - { - case ASIO_OS_DEF(AF_UNSPEC): - break; - case ASIO_OS_DEF(AF_INET): - case ASIO_OS_DEF(AF_INET6): - if (service != 0 && service[0] != '\0') - if (socktype != 0 && socktype != SOCK_STREAM && socktype != SOCK_DGRAM) - return EAI_SOCKTYPE; - break; - default: - return EAI_FAMILY; - } - - return 0; -} - -inline void freeaddrinfo_emulation(addrinfo_type* aihead) -{ - addrinfo_type* ai = aihead; - while (ai) - { - gai_free(ai->ai_addr); - gai_free(ai->ai_canonname); - addrinfo_type* ainext = ai->ai_next; - gai_free(ai); - ai = ainext; - } -} - -inline int getaddrinfo_emulation(const char* host, const char* service, - const addrinfo_type* hintsp, addrinfo_type** result) -{ - // Set up linked list of addrinfo structures. - addrinfo_type* aihead = 0; - addrinfo_type** ainext = &aihead; - char* canon = 0; - - // Supply default hints if not specified by caller. - addrinfo_type hints = addrinfo_type(); - hints.ai_family = ASIO_OS_DEF(AF_UNSPEC); - if (hintsp) - hints = *hintsp; - - // If the resolution is not specifically for AF_INET6, remove the AI_V4MAPPED - // and AI_ALL flags. -#if defined(AI_V4MAPPED) - if (hints.ai_family != ASIO_OS_DEF(AF_INET6)) - hints.ai_flags &= ~AI_V4MAPPED; -#endif -#if defined(AI_ALL) - if (hints.ai_family != ASIO_OS_DEF(AF_INET6)) - hints.ai_flags &= ~AI_ALL; -#endif - - // Basic error checking. - int rc = gai_echeck(host, service, hints.ai_flags, hints.ai_family, - hints.ai_socktype, hints.ai_protocol); - if (rc != 0) - { - freeaddrinfo_emulation(aihead); - return rc; - } - - gai_search search[2]; - int search_count = gai_nsearch(host, &hints, search); - for (gai_search* sptr = search; sptr < search + search_count; ++sptr) - { - // Check for IPv4 dotted decimal string. - in4_addr_type inaddr; - asio::error_code ec; - if (socket_ops::inet_pton(ASIO_OS_DEF(AF_INET), - sptr->host, &inaddr, 0, ec) == 1) - { - if (hints.ai_family != ASIO_OS_DEF(AF_UNSPEC) - && hints.ai_family != ASIO_OS_DEF(AF_INET)) - { - freeaddrinfo_emulation(aihead); - gai_free(canon); - return EAI_FAMILY; - } - if (sptr->family == ASIO_OS_DEF(AF_INET)) - { - rc = gai_aistruct(&ainext, &hints, &inaddr, ASIO_OS_DEF(AF_INET)); - if (rc != 0) - { - freeaddrinfo_emulation(aihead); - gai_free(canon); - return rc; - } - } - continue; - } - - // Check for IPv6 hex string. - in6_addr_type in6addr; - if (socket_ops::inet_pton(ASIO_OS_DEF(AF_INET6), - sptr->host, &in6addr, 0, ec) == 1) - { - if (hints.ai_family != ASIO_OS_DEF(AF_UNSPEC) - && hints.ai_family != ASIO_OS_DEF(AF_INET6)) - { - freeaddrinfo_emulation(aihead); - gai_free(canon); - return EAI_FAMILY; - } - if (sptr->family == ASIO_OS_DEF(AF_INET6)) - { - rc = gai_aistruct(&ainext, &hints, &in6addr, - ASIO_OS_DEF(AF_INET6)); - if (rc != 0) - { - freeaddrinfo_emulation(aihead); - gai_free(canon); - return rc; - } - } - continue; - } - - // Look up hostname. - hostent hent; - char hbuf[8192] = ""; - hostent* hptr = socket_ops::gethostbyname(sptr->host, - sptr->family, &hent, hbuf, sizeof(hbuf), hints.ai_flags, ec); - if (hptr == 0) - { - if (search_count == 2) - { - // Failure is OK if there are multiple searches. - continue; - } - freeaddrinfo_emulation(aihead); - gai_free(canon); - if (ec == asio::error::host_not_found) - return EAI_NONAME; - if (ec == asio::error::host_not_found_try_again) - return EAI_AGAIN; - if (ec == asio::error::no_recovery) - return EAI_FAIL; - if (ec == asio::error::no_data) - return EAI_NONAME; - return EAI_NONAME; - } - - // Check for address family mismatch if one was specified. - if (hints.ai_family != ASIO_OS_DEF(AF_UNSPEC) - && hints.ai_family != hptr->h_addrtype) - { - freeaddrinfo_emulation(aihead); - gai_free(canon); - socket_ops::freehostent(hptr); - return EAI_FAMILY; - } - - // Save canonical name first time. - if (host != 0 && host[0] != '\0' && hptr->h_name && hptr->h_name[0] - && (hints.ai_flags & AI_CANONNAME) && canon == 0) - { - std::size_t canon_len = strlen(hptr->h_name) + 1; - canon = gai_alloc(canon_len); - if (canon == 0) - { - freeaddrinfo_emulation(aihead); - socket_ops::freehostent(hptr); - return EAI_MEMORY; - } - gai_strcpy(canon, hptr->h_name, canon_len); - } - - // Create an addrinfo structure for each returned address. - for (char** ap = hptr->h_addr_list; *ap; ++ap) - { - rc = gai_aistruct(&ainext, &hints, *ap, hptr->h_addrtype); - if (rc != 0) - { - freeaddrinfo_emulation(aihead); - gai_free(canon); - socket_ops::freehostent(hptr); - return EAI_FAMILY; - } - } - - socket_ops::freehostent(hptr); - } - - // Check if we found anything. - if (aihead == 0) - { - gai_free(canon); - return EAI_NONAME; - } - - // Return canonical name in first entry. - if (host != 0 && host[0] != '\0' && (hints.ai_flags & AI_CANONNAME)) - { - if (canon) - { - aihead->ai_canonname = canon; - canon = 0; - } - else - { - std::size_t canonname_len = strlen(search[0].host) + 1; - aihead->ai_canonname = gai_alloc(canonname_len); - if (aihead->ai_canonname == 0) - { - freeaddrinfo_emulation(aihead); - return EAI_MEMORY; - } - gai_strcpy(aihead->ai_canonname, search[0].host, canonname_len); - } - } - gai_free(canon); - - // Process the service name. - if (service != 0 && service[0] != '\0') - { - rc = gai_serv(aihead, &hints, service); - if (rc != 0) - { - freeaddrinfo_emulation(aihead); - return rc; - } - } - - // Return result to caller. - *result = aihead; - return 0; -} - -inline asio::error_code getnameinfo_emulation( - const socket_addr_type* sa, std::size_t salen, char* host, - std::size_t hostlen, char* serv, std::size_t servlen, int flags, - asio::error_code& ec) -{ - using namespace std; - - const char* addr; - size_t addr_len; - unsigned short port; - switch (sa->sa_family) - { - case ASIO_OS_DEF(AF_INET): - if (salen != sizeof(sockaddr_in4_type)) - { - return ec = asio::error::invalid_argument; - } - addr = reinterpret_cast( - &reinterpret_cast(sa)->sin_addr); - addr_len = sizeof(in4_addr_type); - port = reinterpret_cast(sa)->sin_port; - break; - case ASIO_OS_DEF(AF_INET6): - if (salen != sizeof(sockaddr_in6_type)) - { - return ec = asio::error::invalid_argument; - } - addr = reinterpret_cast( - &reinterpret_cast(sa)->sin6_addr); - addr_len = sizeof(in6_addr_type); - port = reinterpret_cast(sa)->sin6_port; - break; - default: - return ec = asio::error::address_family_not_supported; - } - - if (host && hostlen > 0) - { - if (flags & NI_NUMERICHOST) - { - if (socket_ops::inet_ntop(sa->sa_family, addr, host, hostlen, 0, ec) == 0) - { - return ec; - } - } - else - { - hostent hent; - char hbuf[8192] = ""; - hostent* hptr = socket_ops::gethostbyaddr(addr, - static_cast(addr_len), sa->sa_family, - &hent, hbuf, sizeof(hbuf), ec); - if (hptr && hptr->h_name && hptr->h_name[0] != '\0') - { - if (flags & NI_NOFQDN) - { - char* dot = strchr(hptr->h_name, '.'); - if (dot) - { - *dot = 0; - } - } - gai_strcpy(host, hptr->h_name, hostlen); - socket_ops::freehostent(hptr); - } - else - { - socket_ops::freehostent(hptr); - if (flags & NI_NAMEREQD) - { - return ec = asio::error::host_not_found; - } - if (socket_ops::inet_ntop(sa->sa_family, - addr, host, hostlen, 0, ec) == 0) - { - return ec; - } - } - } - } - - if (serv && servlen > 0) - { - if (flags & NI_NUMERICSERV) - { - if (servlen < 6) - { - return ec = asio::error::no_buffer_space; - } -#if defined(ASIO_HAS_SECURE_RTL) - sprintf_s(serv, servlen, "%u", ntohs(port)); -#else // defined(ASIO_HAS_SECURE_RTL) - sprintf(serv, "%u", ntohs(port)); -#endif // defined(ASIO_HAS_SECURE_RTL) - } - else - { -#if defined(ASIO_HAS_PTHREADS) - static ::pthread_mutex_t mutex = PTHREAD_MUTEX_INITIALIZER; - ::pthread_mutex_lock(&mutex); -#endif // defined(ASIO_HAS_PTHREADS) - servent* sptr = ::getservbyport(port, (flags & NI_DGRAM) ? "udp" : 0); - if (sptr && sptr->s_name && sptr->s_name[0] != '\0') - { - gai_strcpy(serv, sptr->s_name, servlen); - } - else - { - if (servlen < 6) - { - return ec = asio::error::no_buffer_space; - } -#if defined(ASIO_HAS_SECURE_RTL) - sprintf_s(serv, servlen, "%u", ntohs(port)); -#else // defined(ASIO_HAS_SECURE_RTL) - sprintf(serv, "%u", ntohs(port)); -#endif // defined(ASIO_HAS_SECURE_RTL) - } -#if defined(ASIO_HAS_PTHREADS) - ::pthread_mutex_unlock(&mutex); -#endif // defined(ASIO_HAS_PTHREADS) - } - } - - ec = asio::error_code(); - return ec; -} - -#endif // !defined(ASIO_HAS_GETADDRINFO) - -inline asio::error_code translate_addrinfo_error(int error) -{ - switch (error) - { - case 0: - return asio::error_code(); - case EAI_AGAIN: - return asio::error::host_not_found_try_again; - case EAI_BADFLAGS: - return asio::error::invalid_argument; - case EAI_FAIL: - return asio::error::no_recovery; - case EAI_FAMILY: - return asio::error::address_family_not_supported; - case EAI_MEMORY: - return asio::error::no_memory; - case EAI_NONAME: -#if defined(EAI_ADDRFAMILY) - case EAI_ADDRFAMILY: -#endif -#if defined(EAI_NODATA) && (EAI_NODATA != EAI_NONAME) - case EAI_NODATA: -#endif - return asio::error::host_not_found; - case EAI_SERVICE: - return asio::error::service_not_found; - case EAI_SOCKTYPE: - return asio::error::socket_type_not_supported; - default: // Possibly the non-portable EAI_SYSTEM. -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - return asio::error_code( - WSAGetLastError(), asio::error::get_system_category()); -#else - return asio::error_code( - errno, asio::error::get_system_category()); -#endif - } -} - -asio::error_code getaddrinfo(const char* host, - const char* service, const addrinfo_type& hints, - addrinfo_type** result, asio::error_code& ec) -{ - host = (host && *host) ? host : 0; - service = (service && *service) ? service : 0; - clear_last_error(); -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if defined(ASIO_HAS_GETADDRINFO) - // Building for Windows XP, Windows Server 2003, or later. - int error = ::getaddrinfo(host, service, &hints, result); - return ec = translate_addrinfo_error(error); -# else - // Building for Windows 2000 or earlier. - typedef int (WSAAPI *gai_t)(const char*, - const char*, const addrinfo_type*, addrinfo_type**); - if (HMODULE winsock_module = ::GetModuleHandleA("ws2_32")) - { - if (gai_t gai = (gai_t)::GetProcAddress(winsock_module, "getaddrinfo")) - { - int error = gai(host, service, &hints, result); - return ec = translate_addrinfo_error(error); - } - } - int error = getaddrinfo_emulation(host, service, &hints, result); - return ec = translate_addrinfo_error(error); -# endif -#elif !defined(ASIO_HAS_GETADDRINFO) - int error = getaddrinfo_emulation(host, service, &hints, result); - return ec = translate_addrinfo_error(error); -#else - int error = ::getaddrinfo(host, service, &hints, result); -#if defined(__MACH__) && defined(__APPLE__) - using namespace std; // For isdigit and atoi. - if (error == 0 && service && isdigit(static_cast(service[0]))) - { - u_short_type port = host_to_network_short(atoi(service)); - for (addrinfo_type* ai = *result; ai; ai = ai->ai_next) - { - switch (ai->ai_family) - { - case ASIO_OS_DEF(AF_INET): - { - sockaddr_in4_type* sinptr = - reinterpret_cast(ai->ai_addr); - if (sinptr->sin_port == 0) - sinptr->sin_port = port; - break; - } - case ASIO_OS_DEF(AF_INET6): - { - sockaddr_in6_type* sin6ptr = - reinterpret_cast(ai->ai_addr); - if (sin6ptr->sin6_port == 0) - sin6ptr->sin6_port = port; - break; - } - default: - break; - } - } - } -#endif - return ec = translate_addrinfo_error(error); -#endif -} - -asio::error_code background_getaddrinfo( - const weak_cancel_token_type& cancel_token, const char* host, - const char* service, const addrinfo_type& hints, - addrinfo_type** result, asio::error_code& ec) -{ - if (cancel_token.expired()) - ec = asio::error::operation_aborted; - else - socket_ops::getaddrinfo(host, service, hints, result, ec); - return ec; -} - -void freeaddrinfo(addrinfo_type* ai) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if defined(ASIO_HAS_GETADDRINFO) - // Building for Windows XP, Windows Server 2003, or later. - ::freeaddrinfo(ai); -# else - // Building for Windows 2000 or earlier. - typedef int (WSAAPI *fai_t)(addrinfo_type*); - if (HMODULE winsock_module = ::GetModuleHandleA("ws2_32")) - { - if (fai_t fai = (fai_t)::GetProcAddress(winsock_module, "freeaddrinfo")) - { - fai(ai); - return; - } - } - freeaddrinfo_emulation(ai); -# endif -#elif !defined(ASIO_HAS_GETADDRINFO) - freeaddrinfo_emulation(ai); -#else - ::freeaddrinfo(ai); -#endif -} - -asio::error_code getnameinfo(const socket_addr_type* addr, - std::size_t addrlen, char* host, std::size_t hostlen, - char* serv, std::size_t servlen, int flags, asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if defined(ASIO_HAS_GETADDRINFO) - // Building for Windows XP, Windows Server 2003, or later. - clear_last_error(); - int error = ::getnameinfo(addr, static_cast(addrlen), - host, static_cast(hostlen), - serv, static_cast(servlen), flags); - return ec = translate_addrinfo_error(error); -# else - // Building for Windows 2000 or earlier. - typedef int (WSAAPI *gni_t)(const socket_addr_type*, - int, char*, DWORD, char*, DWORD, int); - if (HMODULE winsock_module = ::GetModuleHandleA("ws2_32")) - { - if (gni_t gni = (gni_t)::GetProcAddress(winsock_module, "getnameinfo")) - { - clear_last_error(); - int error = gni(addr, static_cast(addrlen), - host, static_cast(hostlen), - serv, static_cast(servlen), flags); - return ec = translate_addrinfo_error(error); - } - } - clear_last_error(); - return getnameinfo_emulation(addr, addrlen, - host, hostlen, serv, servlen, flags, ec); -# endif -#elif !defined(ASIO_HAS_GETADDRINFO) - using namespace std; // For memcpy. - sockaddr_storage_type tmp_addr; - memcpy(&tmp_addr, addr, addrlen); - addr = reinterpret_cast(&tmp_addr); - clear_last_error(); - return getnameinfo_emulation(addr, addrlen, - host, hostlen, serv, servlen, flags, ec); -#else - clear_last_error(); - int error = ::getnameinfo(addr, addrlen, host, hostlen, serv, servlen, flags); - return ec = translate_addrinfo_error(error); -#endif -} - -asio::error_code sync_getnameinfo( - const socket_addr_type* addr, std::size_t addrlen, - char* host, std::size_t hostlen, char* serv, - std::size_t servlen, int sock_type, asio::error_code& ec) -{ - // First try resolving with the service name. If that fails try resolving - // but allow the service to be returned as a number. - int flags = (sock_type == SOCK_DGRAM) ? NI_DGRAM : 0; - socket_ops::getnameinfo(addr, addrlen, host, - hostlen, serv, servlen, flags, ec); - if (ec) - { - socket_ops::getnameinfo(addr, addrlen, host, hostlen, - serv, servlen, flags | NI_NUMERICSERV, ec); - } - - return ec; -} - -asio::error_code background_getnameinfo( - const weak_cancel_token_type& cancel_token, - const socket_addr_type* addr, std::size_t addrlen, - char* host, std::size_t hostlen, char* serv, - std::size_t servlen, int sock_type, asio::error_code& ec) -{ - if (cancel_token.expired()) - { - ec = asio::error::operation_aborted; - } - else - { - // First try resolving with the service name. If that fails try resolving - // but allow the service to be returned as a number. - int flags = (sock_type == SOCK_DGRAM) ? NI_DGRAM : 0; - socket_ops::getnameinfo(addr, addrlen, host, - hostlen, serv, servlen, flags, ec); - if (ec) - { - socket_ops::getnameinfo(addr, addrlen, host, hostlen, - serv, servlen, flags | NI_NUMERICSERV, ec); - } - } - - return ec; -} - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -u_long_type network_to_host_long(u_long_type value) -{ -#if defined(ASIO_WINDOWS_RUNTIME) - unsigned char* value_p = reinterpret_cast(&value); - u_long_type result = (static_cast(value_p[0]) << 24) - | (static_cast(value_p[1]) << 16) - | (static_cast(value_p[2]) << 8) - | static_cast(value_p[3]); - return result; -#else // defined(ASIO_WINDOWS_RUNTIME) - return ntohl(value); -#endif // defined(ASIO_WINDOWS_RUNTIME) -} - -u_long_type host_to_network_long(u_long_type value) -{ -#if defined(ASIO_WINDOWS_RUNTIME) - u_long_type result; - unsigned char* result_p = reinterpret_cast(&result); - result_p[0] = static_cast((value >> 24) & 0xFF); - result_p[1] = static_cast((value >> 16) & 0xFF); - result_p[2] = static_cast((value >> 8) & 0xFF); - result_p[3] = static_cast(value & 0xFF); - return result; -#else // defined(ASIO_WINDOWS_RUNTIME) - return htonl(value); -#endif // defined(ASIO_WINDOWS_RUNTIME) -} - -u_short_type network_to_host_short(u_short_type value) -{ -#if defined(ASIO_WINDOWS_RUNTIME) - unsigned char* value_p = reinterpret_cast(&value); - u_short_type result = (static_cast(value_p[0]) << 8) - | static_cast(value_p[1]); - return result; -#else // defined(ASIO_WINDOWS_RUNTIME) - return ntohs(value); -#endif // defined(ASIO_WINDOWS_RUNTIME) -} - -u_short_type host_to_network_short(u_short_type value) -{ -#if defined(ASIO_WINDOWS_RUNTIME) - u_short_type result; - unsigned char* result_p = reinterpret_cast(&result); - result_p[0] = static_cast((value >> 8) & 0xFF); - result_p[1] = static_cast(value & 0xFF); - return result; -#else // defined(ASIO_WINDOWS_RUNTIME) - return htons(value); -#endif // defined(ASIO_WINDOWS_RUNTIME) -} - -} // namespace socket_ops -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SOCKET_OPS_IPP diff --git a/scout_sdk/asio/asio/detail/impl/socket_select_interrupter.ipp b/scout_sdk/asio/asio/detail/impl/socket_select_interrupter.ipp deleted file mode 100644 index 052f2a7..0000000 --- a/scout_sdk/asio/asio/detail/impl/socket_select_interrupter.ipp +++ /dev/null @@ -1,176 +0,0 @@ -// -// detail/impl/socket_select_interrupter.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_SOCKET_SELECT_INTERRUPTER_IPP -#define ASIO_DETAIL_IMPL_SOCKET_SELECT_INTERRUPTER_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS_RUNTIME) - -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - -#include -#include "asio/detail/socket_holder.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_select_interrupter.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -socket_select_interrupter::socket_select_interrupter() -{ - open_descriptors(); -} - -void socket_select_interrupter::open_descriptors() -{ - asio::error_code ec; - socket_holder acceptor(socket_ops::socket( - AF_INET, SOCK_STREAM, IPPROTO_TCP, ec)); - if (acceptor.get() == invalid_socket) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - int opt = 1; - socket_ops::state_type acceptor_state = 0; - socket_ops::setsockopt(acceptor.get(), acceptor_state, - SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt), ec); - - using namespace std; // For memset. - sockaddr_in4_type addr; - std::size_t addr_len = sizeof(addr); - memset(&addr, 0, sizeof(addr)); - addr.sin_family = AF_INET; - addr.sin_addr.s_addr = socket_ops::host_to_network_long(INADDR_LOOPBACK); - addr.sin_port = 0; - if (socket_ops::bind(acceptor.get(), (const socket_addr_type*)&addr, - addr_len, ec) == socket_error_retval) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - if (socket_ops::getsockname(acceptor.get(), (socket_addr_type*)&addr, - &addr_len, ec) == socket_error_retval) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - // Some broken firewalls on Windows will intermittently cause getsockname to - // return 0.0.0.0 when the socket is actually bound to 127.0.0.1. We - // explicitly specify the target address here to work around this problem. - if (addr.sin_addr.s_addr == socket_ops::host_to_network_long(INADDR_ANY)) - addr.sin_addr.s_addr = socket_ops::host_to_network_long(INADDR_LOOPBACK); - - if (socket_ops::listen(acceptor.get(), - SOMAXCONN, ec) == socket_error_retval) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - socket_holder client(socket_ops::socket( - AF_INET, SOCK_STREAM, IPPROTO_TCP, ec)); - if (client.get() == invalid_socket) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - if (socket_ops::connect(client.get(), (const socket_addr_type*)&addr, - addr_len, ec) == socket_error_retval) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - socket_holder server(socket_ops::accept(acceptor.get(), 0, 0, ec)); - if (server.get() == invalid_socket) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - ioctl_arg_type non_blocking = 1; - socket_ops::state_type client_state = 0; - if (socket_ops::ioctl(client.get(), client_state, - FIONBIO, &non_blocking, ec)) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - opt = 1; - socket_ops::setsockopt(client.get(), client_state, - IPPROTO_TCP, TCP_NODELAY, &opt, sizeof(opt), ec); - - non_blocking = 1; - socket_ops::state_type server_state = 0; - if (socket_ops::ioctl(server.get(), server_state, - FIONBIO, &non_blocking, ec)) - asio::detail::throw_error(ec, "socket_select_interrupter"); - - opt = 1; - socket_ops::setsockopt(server.get(), server_state, - IPPROTO_TCP, TCP_NODELAY, &opt, sizeof(opt), ec); - - read_descriptor_ = server.release(); - write_descriptor_ = client.release(); -} - -socket_select_interrupter::~socket_select_interrupter() -{ - close_descriptors(); -} - -void socket_select_interrupter::close_descriptors() -{ - asio::error_code ec; - socket_ops::state_type state = socket_ops::internal_non_blocking; - if (read_descriptor_ != invalid_socket) - socket_ops::close(read_descriptor_, state, true, ec); - if (write_descriptor_ != invalid_socket) - socket_ops::close(write_descriptor_, state, true, ec); -} - -void socket_select_interrupter::recreate() -{ - close_descriptors(); - - write_descriptor_ = invalid_socket; - read_descriptor_ = invalid_socket; - - open_descriptors(); -} - -void socket_select_interrupter::interrupt() -{ - char byte = 0; - socket_ops::buf b; - socket_ops::init_buf(b, &byte, 1); - asio::error_code ec; - socket_ops::send(write_descriptor_, &b, 1, 0, ec); -} - -bool socket_select_interrupter::reset() -{ - char data[1024]; - socket_ops::buf b; - socket_ops::init_buf(b, data, sizeof(data)); - asio::error_code ec; - int bytes_read = socket_ops::recv(read_descriptor_, &b, 1, 0, ec); - bool was_interrupted = (bytes_read > 0); - while (bytes_read == sizeof(data)) - bytes_read = socket_ops::recv(read_descriptor_, &b, 1, 0, ec); - return was_interrupted; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_IMPL_SOCKET_SELECT_INTERRUPTER_IPP diff --git a/scout_sdk/asio/asio/detail/impl/strand_executor_service.hpp b/scout_sdk/asio/asio/detail/impl/strand_executor_service.hpp deleted file mode 100644 index 0e18ca0..0000000 --- a/scout_sdk/asio/asio/detail/impl/strand_executor_service.hpp +++ /dev/null @@ -1,179 +0,0 @@ -// -// detail/impl/strand_executor_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_STRAND_EXECUTOR_SERVICE_HPP -#define ASIO_DETAIL_IMPL_STRAND_EXECUTOR_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/call_stack.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/recycling_allocator.hpp" -#include "asio/executor_work_guard.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class strand_executor_service::invoker -{ -public: - invoker(const implementation_type& impl, Executor& ex) - : impl_(impl), - work_(ex) - { - } - - invoker(const invoker& other) - : impl_(other.impl_), - work_(other.work_) - { - } - -#if defined(ASIO_HAS_MOVE) - invoker(invoker&& other) - : impl_(ASIO_MOVE_CAST(implementation_type)(other.impl_)), - work_(ASIO_MOVE_CAST(executor_work_guard)(other.work_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - struct on_invoker_exit - { - invoker* this_; - - ~on_invoker_exit() - { - this_->impl_->mutex_->lock(); - this_->impl_->ready_queue_.push(this_->impl_->waiting_queue_); - bool more_handlers = this_->impl_->locked_ = - !this_->impl_->ready_queue_.empty(); - this_->impl_->mutex_->unlock(); - - if (more_handlers) - { - Executor ex(this_->work_.get_executor()); - recycling_allocator allocator; - ex.post(ASIO_MOVE_CAST(invoker)(*this_), allocator); - } - } - }; - - void operator()() - { - // Indicate that this strand is executing on the current thread. - call_stack::context ctx(impl_.get()); - - // Ensure the next handler, if any, is scheduled on block exit. - on_invoker_exit on_exit = { this }; - (void)on_exit; - - // Run all ready handlers. No lock is required since the ready queue is - // accessed only within the strand. - asio::error_code ec; - while (scheduler_operation* o = impl_->ready_queue_.front()) - { - impl_->ready_queue_.pop(); - o->complete(impl_.get(), ec, 0); - } - } - -private: - implementation_type impl_; - executor_work_guard work_; -}; - -template -void strand_executor_service::dispatch(const implementation_type& impl, - Executor& ex, ASIO_MOVE_ARG(Function) function, const Allocator& a) -{ - typedef typename decay::type function_type; - - // If we are already in the strand then the function can run immediately. - if (call_stack::contains(impl.get())) - { - // Make a local, non-const copy of the function. - function_type tmp(ASIO_MOVE_CAST(Function)(function)); - - fenced_block b(fenced_block::full); - asio_handler_invoke_helpers::invoke(tmp, tmp); - return; - } - - // Allocate and construct an operation to wrap the function. - typedef executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(function), a); - - ASIO_HANDLER_CREATION((impl->service_->context(), *p.p, - "strand_executor", impl.get(), 0, "dispatch")); - - // Add the function to the strand and schedule the strand if required. - bool first = enqueue(impl, p.p); - p.v = p.p = 0; - if (first) - ex.dispatch(invoker(impl, ex), a); -} - -// Request invocation of the given function and return immediately. -template -void strand_executor_service::post(const implementation_type& impl, - Executor& ex, ASIO_MOVE_ARG(Function) function, const Allocator& a) -{ - typedef typename decay::type function_type; - - // Allocate and construct an operation to wrap the function. - typedef executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(function), a); - - ASIO_HANDLER_CREATION((impl->service_->context(), *p.p, - "strand_executor", impl.get(), 0, "post")); - - // Add the function to the strand and schedule the strand if required. - bool first = enqueue(impl, p.p); - p.v = p.p = 0; - if (first) - ex.post(invoker(impl, ex), a); -} - -// Request invocation of the given function and return immediately. -template -void strand_executor_service::defer(const implementation_type& impl, - Executor& ex, ASIO_MOVE_ARG(Function) function, const Allocator& a) -{ - typedef typename decay::type function_type; - - // Allocate and construct an operation to wrap the function. - typedef executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(function), a); - - ASIO_HANDLER_CREATION((impl->service_->context(), *p.p, - "strand_executor", impl.get(), 0, "defer")); - - // Add the function to the strand and schedule the strand if required. - bool first = enqueue(impl, p.p); - p.v = p.p = 0; - if (first) - ex.defer(invoker(impl, ex), a); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_STRAND_EXECUTOR_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/impl/strand_executor_service.ipp b/scout_sdk/asio/asio/detail/impl/strand_executor_service.ipp deleted file mode 100644 index 365652e..0000000 --- a/scout_sdk/asio/asio/detail/impl/strand_executor_service.ipp +++ /dev/null @@ -1,134 +0,0 @@ -// -// detail/impl/strand_executor_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_STRAND_EXECUTOR_SERVICE_IPP -#define ASIO_DETAIL_IMPL_STRAND_EXECUTOR_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/strand_executor_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -strand_executor_service::strand_executor_service(execution_context& ctx) - : execution_context_service_base(ctx), - mutex_(), - salt_(0), - impl_list_(0) -{ -} - -void strand_executor_service::shutdown() -{ - op_queue ops; - - asio::detail::mutex::scoped_lock lock(mutex_); - - strand_impl* impl = impl_list_; - while (impl) - { - impl->mutex_->lock(); - impl->shutdown_ = true; - ops.push(impl->waiting_queue_); - ops.push(impl->ready_queue_); - impl->mutex_->unlock(); - impl = impl->next_; - } -} - -strand_executor_service::implementation_type -strand_executor_service::create_implementation() -{ - implementation_type new_impl(new strand_impl); - new_impl->locked_ = false; - new_impl->shutdown_ = false; - - asio::detail::mutex::scoped_lock lock(mutex_); - - // Select a mutex from the pool of shared mutexes. - std::size_t salt = salt_++; - std::size_t mutex_index = reinterpret_cast(new_impl.get()); - mutex_index += (reinterpret_cast(new_impl.get()) >> 3); - mutex_index ^= salt + 0x9e3779b9 + (mutex_index << 6) + (mutex_index >> 2); - mutex_index = mutex_index % num_mutexes; - if (!mutexes_[mutex_index].get()) - mutexes_[mutex_index].reset(new mutex); - new_impl->mutex_ = mutexes_[mutex_index].get(); - - // Insert implementation into linked list of all implementations. - new_impl->next_ = impl_list_; - new_impl->prev_ = 0; - if (impl_list_) - impl_list_->prev_ = new_impl.get(); - impl_list_ = new_impl.get(); - new_impl->service_ = this; - - return new_impl; -} - -strand_executor_service::strand_impl::~strand_impl() -{ - asio::detail::mutex::scoped_lock lock(service_->mutex_); - - // Remove implementation from linked list of all implementations. - if (service_->impl_list_ == this) - service_->impl_list_ = next_; - if (prev_) - prev_->next_ = next_; - if (next_) - next_->prev_= prev_; -} - -bool strand_executor_service::enqueue(const implementation_type& impl, - scheduler_operation* op) -{ - impl->mutex_->lock(); - if (impl->shutdown_) - { - impl->mutex_->unlock(); - op->destroy(); - return false; - } - else if (impl->locked_) - { - // Some other function already holds the strand lock. Enqueue for later. - impl->waiting_queue_.push(op); - impl->mutex_->unlock(); - return false; - } - else - { - // The function is acquiring the strand lock and so is responsible for - // scheduling the strand. - impl->locked_ = true; - impl->mutex_->unlock(); - impl->ready_queue_.push(op); - return true; - } -} - -bool strand_executor_service::running_in_this_thread( - const implementation_type& impl) -{ - return !!call_stack::contains(impl.get()); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_STRAND_EXECUTOR_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/strand_service.hpp b/scout_sdk/asio/asio/detail/impl/strand_service.hpp deleted file mode 100644 index da5b716..0000000 --- a/scout_sdk/asio/asio/detail/impl/strand_service.hpp +++ /dev/null @@ -1,118 +0,0 @@ -// -// detail/impl/strand_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_STRAND_SERVICE_HPP -#define ASIO_DETAIL_IMPL_STRAND_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/call_stack.hpp" -#include "asio/detail/completion_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -inline strand_service::strand_impl::strand_impl() - : operation(&strand_service::do_complete), - locked_(false) -{ -} - -struct strand_service::on_dispatch_exit -{ - io_context_impl* io_context_; - strand_impl* impl_; - - ~on_dispatch_exit() - { - impl_->mutex_.lock(); - impl_->ready_queue_.push(impl_->waiting_queue_); - bool more_handlers = impl_->locked_ = !impl_->ready_queue_.empty(); - impl_->mutex_.unlock(); - - if (more_handlers) - io_context_->post_immediate_completion(impl_, false); - } -}; - -template -void strand_service::dispatch(strand_service::implementation_type& impl, - Handler& handler) -{ - // If we are already in the strand then the handler can run immediately. - if (call_stack::contains(impl)) - { - fenced_block b(fenced_block::full); - asio_handler_invoke_helpers::invoke(handler, handler); - return; - } - - // Allocate and construct an operation to wrap the handler. - typedef completion_handler op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((this->context(), - *p.p, "strand", impl, 0, "dispatch")); - - bool dispatch_immediately = do_dispatch(impl, p.p); - operation* o = p.p; - p.v = p.p = 0; - - if (dispatch_immediately) - { - // Indicate that this strand is executing on the current thread. - call_stack::context ctx(impl); - - // Ensure the next handler, if any, is scheduled on block exit. - on_dispatch_exit on_exit = { &io_context_, impl }; - (void)on_exit; - - completion_handler::do_complete( - &io_context_, o, asio::error_code(), 0); - } -} - -// Request the io_context to invoke the given handler and return immediately. -template -void strand_service::post(strand_service::implementation_type& impl, - Handler& handler) -{ - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef completion_handler op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((this->context(), - *p.p, "strand", impl, 0, "post")); - - do_post(impl, p.p, is_continuation); - p.v = p.p = 0; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_STRAND_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/impl/strand_service.ipp b/scout_sdk/asio/asio/detail/impl/strand_service.ipp deleted file mode 100644 index cbaf25b..0000000 --- a/scout_sdk/asio/asio/detail/impl/strand_service.ipp +++ /dev/null @@ -1,177 +0,0 @@ -// -// detail/impl/strand_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_STRAND_SERVICE_IPP -#define ASIO_DETAIL_IMPL_STRAND_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/call_stack.hpp" -#include "asio/detail/strand_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct strand_service::on_do_complete_exit -{ - io_context_impl* owner_; - strand_impl* impl_; - - ~on_do_complete_exit() - { - impl_->mutex_.lock(); - impl_->ready_queue_.push(impl_->waiting_queue_); - bool more_handlers = impl_->locked_ = !impl_->ready_queue_.empty(); - impl_->mutex_.unlock(); - - if (more_handlers) - owner_->post_immediate_completion(impl_, true); - } -}; - -strand_service::strand_service(asio::io_context& io_context) - : asio::detail::service_base(io_context), - io_context_(asio::use_service(io_context)), - mutex_(), - salt_(0) -{ -} - -void strand_service::shutdown() -{ - op_queue ops; - - asio::detail::mutex::scoped_lock lock(mutex_); - - for (std::size_t i = 0; i < num_implementations; ++i) - { - if (strand_impl* impl = implementations_[i].get()) - { - ops.push(impl->waiting_queue_); - ops.push(impl->ready_queue_); - } - } -} - -void strand_service::construct(strand_service::implementation_type& impl) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - std::size_t salt = salt_++; -#if defined(ASIO_ENABLE_SEQUENTIAL_STRAND_ALLOCATION) - std::size_t index = salt; -#else // defined(ASIO_ENABLE_SEQUENTIAL_STRAND_ALLOCATION) - std::size_t index = reinterpret_cast(&impl); - index += (reinterpret_cast(&impl) >> 3); - index ^= salt + 0x9e3779b9 + (index << 6) + (index >> 2); -#endif // defined(ASIO_ENABLE_SEQUENTIAL_STRAND_ALLOCATION) - index = index % num_implementations; - - if (!implementations_[index].get()) - implementations_[index].reset(new strand_impl); - impl = implementations_[index].get(); -} - -bool strand_service::running_in_this_thread( - const implementation_type& impl) const -{ - return call_stack::contains(impl) != 0; -} - -bool strand_service::do_dispatch(implementation_type& impl, operation* op) -{ - // If we are running inside the io_context, and no other handler already - // holds the strand lock, then the handler can run immediately. - bool can_dispatch = io_context_.can_dispatch(); - impl->mutex_.lock(); - if (can_dispatch && !impl->locked_) - { - // Immediate invocation is allowed. - impl->locked_ = true; - impl->mutex_.unlock(); - return true; - } - - if (impl->locked_) - { - // Some other handler already holds the strand lock. Enqueue for later. - impl->waiting_queue_.push(op); - impl->mutex_.unlock(); - } - else - { - // The handler is acquiring the strand lock and so is responsible for - // scheduling the strand. - impl->locked_ = true; - impl->mutex_.unlock(); - impl->ready_queue_.push(op); - io_context_.post_immediate_completion(impl, false); - } - - return false; -} - -void strand_service::do_post(implementation_type& impl, - operation* op, bool is_continuation) -{ - impl->mutex_.lock(); - if (impl->locked_) - { - // Some other handler already holds the strand lock. Enqueue for later. - impl->waiting_queue_.push(op); - impl->mutex_.unlock(); - } - else - { - // The handler is acquiring the strand lock and so is responsible for - // scheduling the strand. - impl->locked_ = true; - impl->mutex_.unlock(); - impl->ready_queue_.push(op); - io_context_.post_immediate_completion(impl, is_continuation); - } -} - -void strand_service::do_complete(void* owner, operation* base, - const asio::error_code& ec, std::size_t /*bytes_transferred*/) -{ - if (owner) - { - strand_impl* impl = static_cast(base); - - // Indicate that this strand is executing on the current thread. - call_stack::context ctx(impl); - - // Ensure the next handler, if any, is scheduled on block exit. - on_do_complete_exit on_exit; - on_exit.owner_ = static_cast(owner); - on_exit.impl_ = impl; - - // Run all ready handlers. No lock is required since the ready queue is - // accessed only within the strand. - while (operation* o = impl->ready_queue_.front()) - { - impl->ready_queue_.pop(); - o->complete(owner, ec, 0); - } - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_STRAND_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/throw_error.ipp b/scout_sdk/asio/asio/detail/impl/throw_error.ipp deleted file mode 100644 index a540cd2..0000000 --- a/scout_sdk/asio/asio/detail/impl/throw_error.ipp +++ /dev/null @@ -1,60 +0,0 @@ -// -// detail/impl/throw_error.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_THROW_ERROR_IPP -#define ASIO_DETAIL_IMPL_THROW_ERROR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/system_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -void do_throw_error(const asio::error_code& err) -{ - asio::system_error e(err); - asio::detail::throw_exception(e); -} - -void do_throw_error(const asio::error_code& err, const char* location) -{ - // boostify: non-boost code starts here -#if defined(ASIO_MSVC) && defined(ASIO_HAS_STD_SYSTEM_ERROR) - // Microsoft's implementation of std::system_error is non-conformant in that - // it ignores the error code's message when a "what" string is supplied. We'll - // work around this by explicitly formatting the "what" string. - std::string what_msg = location; - what_msg += ": "; - what_msg += err.message(); - asio::system_error e(err, what_msg); - asio::detail::throw_exception(e); -#else // defined(ASIO_MSVC) && defined(ASIO_HAS_STD_SYSTEM_ERROR) - // boostify: non-boost code ends here - asio::system_error e(err, location); - asio::detail::throw_exception(e); - // boostify: non-boost code starts here -#endif // defined(ASIO_MSVC) && defined(ASIO_HAS_STD_SYSTEM_ERROR) - // boostify: non-boost code ends here -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_THROW_ERROR_IPP diff --git a/scout_sdk/asio/asio/detail/impl/timer_queue_ptime.ipp b/scout_sdk/asio/asio/detail/impl/timer_queue_ptime.ipp deleted file mode 100644 index 742837f..0000000 --- a/scout_sdk/asio/asio/detail/impl/timer_queue_ptime.ipp +++ /dev/null @@ -1,91 +0,0 @@ -// -// detail/impl/timer_queue_ptime.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_TIMER_QUEUE_PTIME_IPP -#define ASIO_DETAIL_IMPL_TIMER_QUEUE_PTIME_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_DATE_TIME) - -#include "asio/detail/timer_queue_ptime.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -timer_queue >::timer_queue() -{ -} - -timer_queue >::~timer_queue() -{ -} - -bool timer_queue >::enqueue_timer( - const time_type& time, per_timer_data& timer, wait_op* op) -{ - return impl_.enqueue_timer(time, timer, op); -} - -bool timer_queue >::empty() const -{ - return impl_.empty(); -} - -long timer_queue >::wait_duration_msec( - long max_duration) const -{ - return impl_.wait_duration_msec(max_duration); -} - -long timer_queue >::wait_duration_usec( - long max_duration) const -{ - return impl_.wait_duration_usec(max_duration); -} - -void timer_queue >::get_ready_timers( - op_queue& ops) -{ - impl_.get_ready_timers(ops); -} - -void timer_queue >::get_all_timers( - op_queue& ops) -{ - impl_.get_all_timers(ops); -} - -std::size_t timer_queue >::cancel_timer( - per_timer_data& timer, op_queue& ops, std::size_t max_cancelled) -{ - return impl_.cancel_timer(timer, ops, max_cancelled); -} - -void timer_queue >::move_timer( - per_timer_data& target, per_timer_data& source) -{ - impl_.move_timer(target, source); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - -#endif // ASIO_DETAIL_IMPL_TIMER_QUEUE_PTIME_IPP diff --git a/scout_sdk/asio/asio/detail/impl/timer_queue_set.ipp b/scout_sdk/asio/asio/detail/impl/timer_queue_set.ipp deleted file mode 100644 index b516548..0000000 --- a/scout_sdk/asio/asio/detail/impl/timer_queue_set.ipp +++ /dev/null @@ -1,101 +0,0 @@ -// -// detail/impl/timer_queue_set.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_TIMER_QUEUE_SET_IPP -#define ASIO_DETAIL_IMPL_TIMER_QUEUE_SET_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/timer_queue_set.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -timer_queue_set::timer_queue_set() - : first_(0) -{ -} - -void timer_queue_set::insert(timer_queue_base* q) -{ - q->next_ = first_; - first_ = q; -} - -void timer_queue_set::erase(timer_queue_base* q) -{ - if (first_) - { - if (q == first_) - { - first_ = q->next_; - q->next_ = 0; - return; - } - - for (timer_queue_base* p = first_; p->next_; p = p->next_) - { - if (p->next_ == q) - { - p->next_ = q->next_; - q->next_ = 0; - return; - } - } - } -} - -bool timer_queue_set::all_empty() const -{ - for (timer_queue_base* p = first_; p; p = p->next_) - if (!p->empty()) - return false; - return true; -} - -long timer_queue_set::wait_duration_msec(long max_duration) const -{ - long min_duration = max_duration; - for (timer_queue_base* p = first_; p; p = p->next_) - min_duration = p->wait_duration_msec(min_duration); - return min_duration; -} - -long timer_queue_set::wait_duration_usec(long max_duration) const -{ - long min_duration = max_duration; - for (timer_queue_base* p = first_; p; p = p->next_) - min_duration = p->wait_duration_usec(min_duration); - return min_duration; -} - -void timer_queue_set::get_ready_timers(op_queue& ops) -{ - for (timer_queue_base* p = first_; p; p = p->next_) - p->get_ready_timers(ops); -} - -void timer_queue_set::get_all_timers(op_queue& ops) -{ - for (timer_queue_base* p = first_; p; p = p->next_) - p->get_all_timers(ops); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IMPL_TIMER_QUEUE_SET_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_event.ipp b/scout_sdk/asio/asio/detail/impl/win_event.ipp deleted file mode 100644 index 6f74649..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_event.ipp +++ /dev/null @@ -1,76 +0,0 @@ -// -// detail/win_event.ipp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_EVENT_IPP -#define ASIO_DETAIL_IMPL_WIN_EVENT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_event.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -win_event::win_event() - : state_(0) -{ -#if defined(ASIO_WINDOWS_APP) - events_[0] = ::CreateEventExW(0, 0, - CREATE_EVENT_MANUAL_RESET, EVENT_ALL_ACCESS); -#else // defined(ASIO_WINDOWS_APP) - events_[0] = ::CreateEventW(0, true, false, 0); -#endif // defined(ASIO_WINDOWS_APP) - if (!events_[0]) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "event"); - } - -#if defined(ASIO_WINDOWS_APP) - events_[1] = ::CreateEventExW(0, 0, 0, EVENT_ALL_ACCESS); -#else // defined(ASIO_WINDOWS_APP) - events_[1] = ::CreateEventW(0, false, false, 0); -#endif // defined(ASIO_WINDOWS_APP) - if (!events_[1]) - { - DWORD last_error = ::GetLastError(); - ::CloseHandle(events_[0]); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "event"); - } -} - -win_event::~win_event() -{ - ::CloseHandle(events_[0]); - ::CloseHandle(events_[1]); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_IMPL_WIN_EVENT_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_iocp_handle_service.ipp b/scout_sdk/asio/asio/detail/impl/win_iocp_handle_service.ipp deleted file mode 100644 index 9cba2b0..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_iocp_handle_service.ipp +++ /dev/null @@ -1,525 +0,0 @@ -// -// detail/impl/win_iocp_handle_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_IOCP_HANDLE_SERVICE_IPP -#define ASIO_DETAIL_IMPL_WIN_IOCP_HANDLE_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/win_iocp_handle_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_iocp_handle_service::overlapped_wrapper - : public OVERLAPPED -{ -public: - explicit overlapped_wrapper(asio::error_code& ec) - { - Internal = 0; - InternalHigh = 0; - Offset = 0; - OffsetHigh = 0; - - // Create a non-signalled manual-reset event, for GetOverlappedResult. - hEvent = ::CreateEventW(0, TRUE, FALSE, 0); - if (hEvent) - { - // As documented in GetQueuedCompletionStatus, setting the low order - // bit of this event prevents our synchronous writes from being treated - // as completion port events. - DWORD_PTR tmp = reinterpret_cast(hEvent); - hEvent = reinterpret_cast(tmp | 1); - } - else - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - } - - ~overlapped_wrapper() - { - if (hEvent) - { - ::CloseHandle(hEvent); - } - } -}; - -win_iocp_handle_service::win_iocp_handle_service( - asio::io_context& io_context) - : service_base(io_context), - iocp_service_(asio::use_service(io_context)), - mutex_(), - impl_list_(0) -{ -} - -void win_iocp_handle_service::shutdown() -{ - // Close all implementations, causing all operations to complete. - asio::detail::mutex::scoped_lock lock(mutex_); - implementation_type* impl = impl_list_; - while (impl) - { - close_for_destruction(*impl); - impl = impl->next_; - } -} - -void win_iocp_handle_service::construct( - win_iocp_handle_service::implementation_type& impl) -{ - impl.handle_ = INVALID_HANDLE_VALUE; - impl.safe_cancellation_thread_id_ = 0; - - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; -} - -void win_iocp_handle_service::move_construct( - win_iocp_handle_service::implementation_type& impl, - win_iocp_handle_service::implementation_type& other_impl) -{ - impl.handle_ = other_impl.handle_; - other_impl.handle_ = INVALID_HANDLE_VALUE; - - impl.safe_cancellation_thread_id_ = other_impl.safe_cancellation_thread_id_; - other_impl.safe_cancellation_thread_id_ = 0; - - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; -} - -void win_iocp_handle_service::move_assign( - win_iocp_handle_service::implementation_type& impl, - win_iocp_handle_service& other_service, - win_iocp_handle_service::implementation_type& other_impl) -{ - close_for_destruction(impl); - - if (this != &other_service) - { - // Remove implementation from linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; - } - - impl.handle_ = other_impl.handle_; - other_impl.handle_ = INVALID_HANDLE_VALUE; - - impl.safe_cancellation_thread_id_ = other_impl.safe_cancellation_thread_id_; - other_impl.safe_cancellation_thread_id_ = 0; - - if (this != &other_service) - { - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(other_service.mutex_); - impl.next_ = other_service.impl_list_; - impl.prev_ = 0; - if (other_service.impl_list_) - other_service.impl_list_->prev_ = &impl; - other_service.impl_list_ = &impl; - } -} - -void win_iocp_handle_service::destroy( - win_iocp_handle_service::implementation_type& impl) -{ - close_for_destruction(impl); - - // Remove implementation from linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; -} - -asio::error_code win_iocp_handle_service::assign( - win_iocp_handle_service::implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - if (iocp_service_.register_handle(handle, ec)) - return ec; - - impl.handle_ = handle; - ec = asio::error_code(); - return ec; -} - -asio::error_code win_iocp_handle_service::close( - win_iocp_handle_service::implementation_type& impl, - asio::error_code& ec) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((iocp_service_.context(), "handle", - &impl, reinterpret_cast(impl.handle_), "close")); - - if (!::CloseHandle(impl.handle_)) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - else - { - ec = asio::error_code(); - } - - impl.handle_ = INVALID_HANDLE_VALUE; - impl.safe_cancellation_thread_id_ = 0; - } - else - { - ec = asio::error_code(); - } - - return ec; -} - -asio::error_code win_iocp_handle_service::cancel( - win_iocp_handle_service::implementation_type& impl, - asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return ec; - } - - ASIO_HANDLER_OPERATION((iocp_service_.context(), "handle", - &impl, reinterpret_cast(impl.handle_), "cancel")); - - if (FARPROC cancel_io_ex_ptr = ::GetProcAddress( - ::GetModuleHandleA("KERNEL32"), "CancelIoEx")) - { - // The version of Windows supports cancellation from any thread. - typedef BOOL (WINAPI* cancel_io_ex_t)(HANDLE, LPOVERLAPPED); - cancel_io_ex_t cancel_io_ex = (cancel_io_ex_t)cancel_io_ex_ptr; - if (!cancel_io_ex(impl.handle_, 0)) - { - DWORD last_error = ::GetLastError(); - if (last_error == ERROR_NOT_FOUND) - { - // ERROR_NOT_FOUND means that there were no operations to be - // cancelled. We swallow this error to match the behaviour on other - // platforms. - ec = asio::error_code(); - } - else - { - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - } - else - { - ec = asio::error_code(); - } - } - else if (impl.safe_cancellation_thread_id_ == 0) - { - // No operations have been started, so there's nothing to cancel. - ec = asio::error_code(); - } - else if (impl.safe_cancellation_thread_id_ == ::GetCurrentThreadId()) - { - // Asynchronous operations have been started from the current thread only, - // so it is safe to try to cancel them using CancelIo. - if (!::CancelIo(impl.handle_)) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - else - { - ec = asio::error_code(); - } - } - else - { - // Asynchronous operations have been started from more than one thread, - // so cancellation is not safe. - ec = asio::error::operation_not_supported; - } - - return ec; -} - -size_t win_iocp_handle_service::do_write( - win_iocp_handle_service::implementation_type& impl, uint64_t offset, - const asio::const_buffer& buffer, asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // A request to write 0 bytes on a handle is a no-op. - if (buffer.size() == 0) - { - ec = asio::error_code(); - return 0; - } - - overlapped_wrapper overlapped(ec); - if (ec) - { - return 0; - } - - // Write the data. - overlapped.Offset = offset & 0xFFFFFFFF; - overlapped.OffsetHigh = (offset >> 32) & 0xFFFFFFFF; - BOOL ok = ::WriteFile(impl.handle_, buffer.data(), - static_cast(buffer.size()), 0, &overlapped); - if (!ok) - { - DWORD last_error = ::GetLastError(); - if (last_error != ERROR_IO_PENDING) - { - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return 0; - } - } - - // Wait for the operation to complete. - DWORD bytes_transferred = 0; - ok = ::GetOverlappedResult(impl.handle_, - &overlapped, &bytes_transferred, TRUE); - if (!ok) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return 0; - } - - ec = asio::error_code(); - return bytes_transferred; -} - -void win_iocp_handle_service::start_write_op( - win_iocp_handle_service::implementation_type& impl, uint64_t offset, - const asio::const_buffer& buffer, operation* op) -{ - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - if (!is_open(impl)) - { - iocp_service_.on_completion(op, asio::error::bad_descriptor); - } - else if (buffer.size() == 0) - { - // A request to write 0 bytes on a handle is a no-op. - iocp_service_.on_completion(op); - } - else - { - DWORD bytes_transferred = 0; - op->Offset = offset & 0xFFFFFFFF; - op->OffsetHigh = (offset >> 32) & 0xFFFFFFFF; - BOOL ok = ::WriteFile(impl.handle_, buffer.data(), - static_cast(buffer.size()), - &bytes_transferred, op); - DWORD last_error = ::GetLastError(); - if (!ok && last_error != ERROR_IO_PENDING - && last_error != ERROR_MORE_DATA) - { - iocp_service_.on_completion(op, last_error, bytes_transferred); - } - else - { - iocp_service_.on_pending(op); - } - } -} - -size_t win_iocp_handle_service::do_read( - win_iocp_handle_service::implementation_type& impl, uint64_t offset, - const asio::mutable_buffer& buffer, asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return 0; - } - - // A request to read 0 bytes on a stream handle is a no-op. - if (buffer.size() == 0) - { - ec = asio::error_code(); - return 0; - } - - overlapped_wrapper overlapped(ec); - if (ec) - { - return 0; - } - - // Read some data. - overlapped.Offset = offset & 0xFFFFFFFF; - overlapped.OffsetHigh = (offset >> 32) & 0xFFFFFFFF; - BOOL ok = ::ReadFile(impl.handle_, buffer.data(), - static_cast(buffer.size()), 0, &overlapped); - if (!ok) - { - DWORD last_error = ::GetLastError(); - if (last_error != ERROR_IO_PENDING && last_error != ERROR_MORE_DATA) - { - if (last_error == ERROR_HANDLE_EOF) - { - ec = asio::error::eof; - } - else - { - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - return 0; - } - } - - // Wait for the operation to complete. - DWORD bytes_transferred = 0; - ok = ::GetOverlappedResult(impl.handle_, - &overlapped, &bytes_transferred, TRUE); - if (!ok) - { - DWORD last_error = ::GetLastError(); - if (last_error == ERROR_HANDLE_EOF) - { - ec = asio::error::eof; - } - else - { - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - return (last_error == ERROR_MORE_DATA) ? bytes_transferred : 0; - } - - ec = asio::error_code(); - return bytes_transferred; -} - -void win_iocp_handle_service::start_read_op( - win_iocp_handle_service::implementation_type& impl, uint64_t offset, - const asio::mutable_buffer& buffer, operation* op) -{ - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - if (!is_open(impl)) - { - iocp_service_.on_completion(op, asio::error::bad_descriptor); - } - else if (buffer.size() == 0) - { - // A request to read 0 bytes on a handle is a no-op. - iocp_service_.on_completion(op); - } - else - { - DWORD bytes_transferred = 0; - op->Offset = offset & 0xFFFFFFFF; - op->OffsetHigh = (offset >> 32) & 0xFFFFFFFF; - BOOL ok = ::ReadFile(impl.handle_, buffer.data(), - static_cast(buffer.size()), - &bytes_transferred, op); - DWORD last_error = ::GetLastError(); - if (!ok && last_error != ERROR_IO_PENDING - && last_error != ERROR_MORE_DATA) - { - iocp_service_.on_completion(op, last_error, bytes_transferred); - } - else - { - iocp_service_.on_pending(op); - } - } -} - -void win_iocp_handle_service::update_cancellation_thread_id( - win_iocp_handle_service::implementation_type& impl) -{ - if (impl.safe_cancellation_thread_id_ == 0) - impl.safe_cancellation_thread_id_ = ::GetCurrentThreadId(); - else if (impl.safe_cancellation_thread_id_ != ::GetCurrentThreadId()) - impl.safe_cancellation_thread_id_ = ~DWORD(0); -} - -void win_iocp_handle_service::close_for_destruction(implementation_type& impl) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((iocp_service_.context(), "handle", - &impl, reinterpret_cast(impl.handle_), "close")); - - ::CloseHandle(impl.handle_); - impl.handle_ = INVALID_HANDLE_VALUE; - impl.safe_cancellation_thread_id_ = 0; - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_IMPL_WIN_IOCP_HANDLE_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_iocp_io_context.hpp b/scout_sdk/asio/asio/detail/impl/win_iocp_io_context.hpp deleted file mode 100644 index 44887d7..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_iocp_io_context.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// -// detail/impl/win_iocp_io_context.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_IOCP_IO_CONTEXT_HPP -#define ASIO_DETAIL_IMPL_WIN_IOCP_IO_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/completion_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -void win_iocp_io_context::add_timer_queue( - timer_queue& queue) -{ - do_add_timer_queue(queue); -} - -template -void win_iocp_io_context::remove_timer_queue( - timer_queue& queue) -{ - do_remove_timer_queue(queue); -} - -template -void win_iocp_io_context::schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op) -{ - // If the service has been shut down we silently discard the timer. - if (::InterlockedExchangeAdd(&shutdown_, 0) != 0) - { - post_immediate_completion(op, false); - return; - } - - mutex::scoped_lock lock(dispatch_mutex_); - - bool earliest = queue.enqueue_timer(time, timer, op); - work_started(); - if (earliest) - update_timeout(); -} - -template -std::size_t win_iocp_io_context::cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled) -{ - // If the service has been shut down we silently ignore the cancellation. - if (::InterlockedExchangeAdd(&shutdown_, 0) != 0) - return 0; - - mutex::scoped_lock lock(dispatch_mutex_); - op_queue ops; - std::size_t n = queue.cancel_timer(timer, ops, max_cancelled); - post_deferred_completions(ops); - return n; -} - -template -void win_iocp_io_context::move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& to, - typename timer_queue::per_timer_data& from) -{ - asio::detail::mutex::scoped_lock lock(dispatch_mutex_); - op_queue ops; - queue.cancel_timer(to, ops); - queue.move_timer(to, from); - lock.unlock(); - post_deferred_completions(ops); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_IMPL_WIN_IOCP_IO_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/detail/impl/win_iocp_io_context.ipp b/scout_sdk/asio/asio/detail/impl/win_iocp_io_context.ipp deleted file mode 100644 index c371b86..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_iocp_io_context.ipp +++ /dev/null @@ -1,554 +0,0 @@ -// -// detail/impl/win_iocp_io_context.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_IOCP_IO_CONTEXT_IPP -#define ASIO_DETAIL_IMPL_WIN_IOCP_IO_CONTEXT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/error.hpp" -#include "asio/detail/cstdint.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_iocp_io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct win_iocp_io_context::work_finished_on_block_exit -{ - ~work_finished_on_block_exit() - { - io_context_->work_finished(); - } - - win_iocp_io_context* io_context_; -}; - -struct win_iocp_io_context::timer_thread_function -{ - void operator()() - { - while (::InterlockedExchangeAdd(&io_context_->shutdown_, 0) == 0) - { - if (::WaitForSingleObject(io_context_->waitable_timer_.handle, - INFINITE) == WAIT_OBJECT_0) - { - ::InterlockedExchange(&io_context_->dispatch_required_, 1); - ::PostQueuedCompletionStatus(io_context_->iocp_.handle, - 0, wake_for_dispatch, 0); - } - } - } - - win_iocp_io_context* io_context_; -}; - -win_iocp_io_context::win_iocp_io_context( - asio::execution_context& ctx, int concurrency_hint) - : execution_context_service_base(ctx), - iocp_(), - outstanding_work_(0), - stopped_(0), - stop_event_posted_(0), - shutdown_(0), - gqcs_timeout_(get_gqcs_timeout()), - dispatch_required_(0), - concurrency_hint_(concurrency_hint) -{ - ASIO_HANDLER_TRACKING_INIT; - - iocp_.handle = ::CreateIoCompletionPort(INVALID_HANDLE_VALUE, 0, 0, - static_cast(concurrency_hint >= 0 ? concurrency_hint : DWORD(~0))); - if (!iocp_.handle) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "iocp"); - } -} - -void win_iocp_io_context::shutdown() -{ - ::InterlockedExchange(&shutdown_, 1); - - if (timer_thread_.get()) - { - LARGE_INTEGER timeout; - timeout.QuadPart = 1; - ::SetWaitableTimer(waitable_timer_.handle, &timeout, 1, 0, 0, FALSE); - } - - while (::InterlockedExchangeAdd(&outstanding_work_, 0) > 0) - { - op_queue ops; - timer_queues_.get_all_timers(ops); - ops.push(completed_ops_); - if (!ops.empty()) - { - while (win_iocp_operation* op = ops.front()) - { - ops.pop(); - ::InterlockedDecrement(&outstanding_work_); - op->destroy(); - } - } - else - { - DWORD bytes_transferred = 0; - dword_ptr_t completion_key = 0; - LPOVERLAPPED overlapped = 0; - ::GetQueuedCompletionStatus(iocp_.handle, &bytes_transferred, - &completion_key, &overlapped, gqcs_timeout_); - if (overlapped) - { - ::InterlockedDecrement(&outstanding_work_); - static_cast(overlapped)->destroy(); - } - } - } - - if (timer_thread_.get()) - timer_thread_->join(); -} - -asio::error_code win_iocp_io_context::register_handle( - HANDLE handle, asio::error_code& ec) -{ - if (::CreateIoCompletionPort(handle, iocp_.handle, 0, 0) == 0) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - else - { - ec = asio::error_code(); - } - return ec; -} - -size_t win_iocp_io_context::run(asio::error_code& ec) -{ - if (::InterlockedExchangeAdd(&outstanding_work_, 0) == 0) - { - stop(); - ec = asio::error_code(); - return 0; - } - - win_iocp_thread_info this_thread; - thread_call_stack::context ctx(this, this_thread); - - size_t n = 0; - while (do_one(INFINITE, ec)) - if (n != (std::numeric_limits::max)()) - ++n; - return n; -} - -size_t win_iocp_io_context::run_one(asio::error_code& ec) -{ - if (::InterlockedExchangeAdd(&outstanding_work_, 0) == 0) - { - stop(); - ec = asio::error_code(); - return 0; - } - - win_iocp_thread_info this_thread; - thread_call_stack::context ctx(this, this_thread); - - return do_one(INFINITE, ec); -} - -size_t win_iocp_io_context::wait_one(long usec, asio::error_code& ec) -{ - if (::InterlockedExchangeAdd(&outstanding_work_, 0) == 0) - { - stop(); - ec = asio::error_code(); - return 0; - } - - win_iocp_thread_info this_thread; - thread_call_stack::context ctx(this, this_thread); - - return do_one(usec < 0 ? INFINITE : ((usec - 1) / 1000 + 1), ec); -} - -size_t win_iocp_io_context::poll(asio::error_code& ec) -{ - if (::InterlockedExchangeAdd(&outstanding_work_, 0) == 0) - { - stop(); - ec = asio::error_code(); - return 0; - } - - win_iocp_thread_info this_thread; - thread_call_stack::context ctx(this, this_thread); - - size_t n = 0; - while (do_one(0, ec)) - if (n != (std::numeric_limits::max)()) - ++n; - return n; -} - -size_t win_iocp_io_context::poll_one(asio::error_code& ec) -{ - if (::InterlockedExchangeAdd(&outstanding_work_, 0) == 0) - { - stop(); - ec = asio::error_code(); - return 0; - } - - win_iocp_thread_info this_thread; - thread_call_stack::context ctx(this, this_thread); - - return do_one(0, ec); -} - -void win_iocp_io_context::stop() -{ - if (::InterlockedExchange(&stopped_, 1) == 0) - { - if (::InterlockedExchange(&stop_event_posted_, 1) == 0) - { - if (!::PostQueuedCompletionStatus(iocp_.handle, 0, 0, 0)) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "pqcs"); - } - } - } -} - -void win_iocp_io_context::post_deferred_completion(win_iocp_operation* op) -{ - // Flag the operation as ready. - op->ready_ = 1; - - // Enqueue the operation on the I/O completion port. - if (!::PostQueuedCompletionStatus(iocp_.handle, 0, 0, op)) - { - // Out of resources. Put on completed queue instead. - mutex::scoped_lock lock(dispatch_mutex_); - completed_ops_.push(op); - ::InterlockedExchange(&dispatch_required_, 1); - } -} - -void win_iocp_io_context::post_deferred_completions( - op_queue& ops) -{ - while (win_iocp_operation* op = ops.front()) - { - ops.pop(); - - // Flag the operation as ready. - op->ready_ = 1; - - // Enqueue the operation on the I/O completion port. - if (!::PostQueuedCompletionStatus(iocp_.handle, 0, 0, op)) - { - // Out of resources. Put on completed queue instead. - mutex::scoped_lock lock(dispatch_mutex_); - completed_ops_.push(op); - completed_ops_.push(ops); - ::InterlockedExchange(&dispatch_required_, 1); - } - } -} - -void win_iocp_io_context::abandon_operations( - op_queue& ops) -{ - while (win_iocp_operation* op = ops.front()) - { - ops.pop(); - ::InterlockedDecrement(&outstanding_work_); - op->destroy(); - } -} - -void win_iocp_io_context::on_pending(win_iocp_operation* op) -{ - if (::InterlockedCompareExchange(&op->ready_, 1, 0) == 1) - { - // Enqueue the operation on the I/O completion port. - if (!::PostQueuedCompletionStatus(iocp_.handle, - 0, overlapped_contains_result, op)) - { - // Out of resources. Put on completed queue instead. - mutex::scoped_lock lock(dispatch_mutex_); - completed_ops_.push(op); - ::InterlockedExchange(&dispatch_required_, 1); - } - } -} - -void win_iocp_io_context::on_completion(win_iocp_operation* op, - DWORD last_error, DWORD bytes_transferred) -{ - // Flag that the operation is ready for invocation. - op->ready_ = 1; - - // Store results in the OVERLAPPED structure. - op->Internal = reinterpret_cast( - &asio::error::get_system_category()); - op->Offset = last_error; - op->OffsetHigh = bytes_transferred; - - // Enqueue the operation on the I/O completion port. - if (!::PostQueuedCompletionStatus(iocp_.handle, - 0, overlapped_contains_result, op)) - { - // Out of resources. Put on completed queue instead. - mutex::scoped_lock lock(dispatch_mutex_); - completed_ops_.push(op); - ::InterlockedExchange(&dispatch_required_, 1); - } -} - -void win_iocp_io_context::on_completion(win_iocp_operation* op, - const asio::error_code& ec, DWORD bytes_transferred) -{ - // Flag that the operation is ready for invocation. - op->ready_ = 1; - - // Store results in the OVERLAPPED structure. - op->Internal = reinterpret_cast(&ec.category()); - op->Offset = ec.value(); - op->OffsetHigh = bytes_transferred; - - // Enqueue the operation on the I/O completion port. - if (!::PostQueuedCompletionStatus(iocp_.handle, - 0, overlapped_contains_result, op)) - { - // Out of resources. Put on completed queue instead. - mutex::scoped_lock lock(dispatch_mutex_); - completed_ops_.push(op); - ::InterlockedExchange(&dispatch_required_, 1); - } -} - -size_t win_iocp_io_context::do_one(DWORD msec, asio::error_code& ec) -{ - for (;;) - { - // Try to acquire responsibility for dispatching timers and completed ops. - if (::InterlockedCompareExchange(&dispatch_required_, 0, 1) == 1) - { - mutex::scoped_lock lock(dispatch_mutex_); - - // Dispatch pending timers and operations. - op_queue ops; - ops.push(completed_ops_); - timer_queues_.get_ready_timers(ops); - post_deferred_completions(ops); - update_timeout(); - } - - // Get the next operation from the queue. - DWORD bytes_transferred = 0; - dword_ptr_t completion_key = 0; - LPOVERLAPPED overlapped = 0; - ::SetLastError(0); - BOOL ok = ::GetQueuedCompletionStatus(iocp_.handle, - &bytes_transferred, &completion_key, &overlapped, - msec < gqcs_timeout_ ? msec : gqcs_timeout_); - DWORD last_error = ::GetLastError(); - - if (overlapped) - { - win_iocp_operation* op = static_cast(overlapped); - asio::error_code result_ec(last_error, - asio::error::get_system_category()); - - // We may have been passed the last_error and bytes_transferred in the - // OVERLAPPED structure itself. - if (completion_key == overlapped_contains_result) - { - result_ec = asio::error_code(static_cast(op->Offset), - *reinterpret_cast(op->Internal)); - bytes_transferred = op->OffsetHigh; - } - - // Otherwise ensure any result has been saved into the OVERLAPPED - // structure. - else - { - op->Internal = reinterpret_cast(&result_ec.category()); - op->Offset = result_ec.value(); - op->OffsetHigh = bytes_transferred; - } - - // Dispatch the operation only if ready. The operation may not be ready - // if the initiating function (e.g. a call to WSARecv) has not yet - // returned. This is because the initiating function still wants access - // to the operation's OVERLAPPED structure. - if (::InterlockedCompareExchange(&op->ready_, 1, 0) == 1) - { - // Ensure the count of outstanding work is decremented on block exit. - work_finished_on_block_exit on_exit = { this }; - (void)on_exit; - - op->complete(this, result_ec, bytes_transferred); - ec = asio::error_code(); - return 1; - } - } - else if (!ok) - { - if (last_error != WAIT_TIMEOUT) - { - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return 0; - } - - // If we're waiting indefinitely we need to keep going until we get a - // real handler. - if (msec == INFINITE) - continue; - - ec = asio::error_code(); - return 0; - } - else if (completion_key == wake_for_dispatch) - { - // We have been woken up to try to acquire responsibility for dispatching - // timers and completed operations. - } - else - { - // Indicate that there is no longer an in-flight stop event. - ::InterlockedExchange(&stop_event_posted_, 0); - - // The stopped_ flag is always checked to ensure that any leftover - // stop events from a previous run invocation are ignored. - if (::InterlockedExchangeAdd(&stopped_, 0) != 0) - { - // Wake up next thread that is blocked on GetQueuedCompletionStatus. - if (::InterlockedExchange(&stop_event_posted_, 1) == 0) - { - if (!::PostQueuedCompletionStatus(iocp_.handle, 0, 0, 0)) - { - last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return 0; - } - } - - ec = asio::error_code(); - return 0; - } - } - } -} - -DWORD win_iocp_io_context::get_gqcs_timeout() -{ - OSVERSIONINFOEX osvi; - ZeroMemory(&osvi, sizeof(osvi)); - osvi.dwOSVersionInfoSize = sizeof(osvi); - osvi.dwMajorVersion = 6ul; - - const uint64_t condition_mask = ::VerSetConditionMask( - 0, VER_MAJORVERSION, VER_GREATER_EQUAL); - - if (!!::VerifyVersionInfo(&osvi, VER_MAJORVERSION, condition_mask)) - return INFINITE; - - return default_gqcs_timeout; -} - -void win_iocp_io_context::do_add_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(dispatch_mutex_); - - timer_queues_.insert(&queue); - - if (!waitable_timer_.handle) - { - waitable_timer_.handle = ::CreateWaitableTimer(0, FALSE, 0); - if (waitable_timer_.handle == 0) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "timer"); - } - - LARGE_INTEGER timeout; - timeout.QuadPart = -max_timeout_usec; - timeout.QuadPart *= 10; - ::SetWaitableTimer(waitable_timer_.handle, - &timeout, max_timeout_msec, 0, 0, FALSE); - } - - if (!timer_thread_.get()) - { - timer_thread_function thread_function = { this }; - timer_thread_.reset(new thread(thread_function, 65536)); - } -} - -void win_iocp_io_context::do_remove_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(dispatch_mutex_); - - timer_queues_.erase(&queue); -} - -void win_iocp_io_context::update_timeout() -{ - if (timer_thread_.get()) - { - // There's no point updating the waitable timer if the new timeout period - // exceeds the maximum timeout. In that case, we might as well wait for the - // existing period of the timer to expire. - long timeout_usec = timer_queues_.wait_duration_usec(max_timeout_usec); - if (timeout_usec < max_timeout_usec) - { - LARGE_INTEGER timeout; - timeout.QuadPart = -timeout_usec; - timeout.QuadPart *= 10; - ::SetWaitableTimer(waitable_timer_.handle, - &timeout, max_timeout_msec, 0, 0, FALSE); - } - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_IMPL_WIN_IOCP_IO_CONTEXT_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_iocp_serial_port_service.ipp b/scout_sdk/asio/asio/detail/impl/win_iocp_serial_port_service.ipp deleted file mode 100644 index 4a9b8cd..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_iocp_serial_port_service.ipp +++ /dev/null @@ -1,181 +0,0 @@ -// -// detail/impl/win_iocp_serial_port_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_IOCP_SERIAL_PORT_SERVICE_IPP -#define ASIO_DETAIL_IMPL_WIN_IOCP_SERIAL_PORT_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) && defined(ASIO_HAS_SERIAL_PORT) - -#include -#include "asio/detail/win_iocp_serial_port_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -win_iocp_serial_port_service::win_iocp_serial_port_service( - asio::io_context& io_context) - : service_base(io_context), - handle_service_(io_context) -{ -} - -void win_iocp_serial_port_service::shutdown() -{ -} - -asio::error_code win_iocp_serial_port_service::open( - win_iocp_serial_port_service::implementation_type& impl, - const std::string& device, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - // For convenience, add a leading \\.\ sequence if not already present. - std::string name = (device[0] == '\\') ? device : "\\\\.\\" + device; - - // Open a handle to the serial port. - ::HANDLE handle = ::CreateFileA(name.c_str(), - GENERIC_READ | GENERIC_WRITE, 0, 0, - OPEN_EXISTING, FILE_FLAG_OVERLAPPED, 0); - if (handle == INVALID_HANDLE_VALUE) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return ec; - } - - // Determine the initial serial port parameters. - using namespace std; // For memset. - ::DCB dcb; - memset(&dcb, 0, sizeof(DCB)); - dcb.DCBlength = sizeof(DCB); - if (!::GetCommState(handle, &dcb)) - { - DWORD last_error = ::GetLastError(); - ::CloseHandle(handle); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return ec; - } - - // Set some default serial port parameters. This implementation does not - // support changing these, so they might as well be in a known state. - dcb.fBinary = TRUE; // Win32 only supports binary mode. - dcb.fDsrSensitivity = FALSE; - dcb.fNull = FALSE; // Do not ignore NULL characters. - dcb.fAbortOnError = FALSE; // Ignore serial framing errors. - if (!::SetCommState(handle, &dcb)) - { - DWORD last_error = ::GetLastError(); - ::CloseHandle(handle); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return ec; - } - - // Set up timeouts so that the serial port will behave similarly to a - // network socket. Reads wait for at least one byte, then return with - // whatever they have. Writes return once everything is out the door. - ::COMMTIMEOUTS timeouts; - timeouts.ReadIntervalTimeout = 1; - timeouts.ReadTotalTimeoutMultiplier = 0; - timeouts.ReadTotalTimeoutConstant = 0; - timeouts.WriteTotalTimeoutMultiplier = 0; - timeouts.WriteTotalTimeoutConstant = 0; - if (!::SetCommTimeouts(handle, &timeouts)) - { - DWORD last_error = ::GetLastError(); - ::CloseHandle(handle); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return ec; - } - - // We're done. Take ownership of the serial port handle. - if (handle_service_.assign(impl, handle, ec)) - ::CloseHandle(handle); - return ec; -} - -asio::error_code win_iocp_serial_port_service::do_set_option( - win_iocp_serial_port_service::implementation_type& impl, - win_iocp_serial_port_service::store_function_type store, - const void* option, asio::error_code& ec) -{ - using namespace std; // For memcpy. - - ::DCB dcb; - memset(&dcb, 0, sizeof(DCB)); - dcb.DCBlength = sizeof(DCB); - if (!::GetCommState(handle_service_.native_handle(impl), &dcb)) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return ec; - } - - if (store(option, dcb, ec)) - return ec; - - if (!::SetCommState(handle_service_.native_handle(impl), &dcb)) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return ec; - } - - ec = asio::error_code(); - return ec; -} - -asio::error_code win_iocp_serial_port_service::do_get_option( - const win_iocp_serial_port_service::implementation_type& impl, - win_iocp_serial_port_service::load_function_type load, - void* option, asio::error_code& ec) const -{ - using namespace std; // For memset. - - ::DCB dcb; - memset(&dcb, 0, sizeof(DCB)); - dcb.DCBlength = sizeof(DCB); - if (!::GetCommState(handle_service_.native_handle(impl), &dcb)) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - return ec; - } - - return load(option, dcb, ec); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) && defined(ASIO_HAS_SERIAL_PORT) - -#endif // ASIO_DETAIL_IMPL_WIN_IOCP_SERIAL_PORT_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_iocp_socket_service_base.ipp b/scout_sdk/asio/asio/detail/impl/win_iocp_socket_service_base.ipp deleted file mode 100644 index 6c478cd..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_iocp_socket_service_base.ipp +++ /dev/null @@ -1,799 +0,0 @@ -// -// detail/impl/win_iocp_socket_service_base.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_IOCP_SOCKET_SERVICE_BASE_IPP -#define ASIO_DETAIL_IMPL_WIN_IOCP_SOCKET_SERVICE_BASE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/win_iocp_socket_service_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -win_iocp_socket_service_base::win_iocp_socket_service_base( - asio::io_context& io_context) - : io_context_(io_context), - iocp_service_(use_service(io_context)), - reactor_(0), - connect_ex_(0), - nt_set_info_(0), - mutex_(), - impl_list_(0) -{ -} - -void win_iocp_socket_service_base::base_shutdown() -{ - // Close all implementations, causing all operations to complete. - asio::detail::mutex::scoped_lock lock(mutex_); - base_implementation_type* impl = impl_list_; - while (impl) - { - close_for_destruction(*impl); - impl = impl->next_; - } -} - -void win_iocp_socket_service_base::construct( - win_iocp_socket_service_base::base_implementation_type& impl) -{ - impl.socket_ = invalid_socket; - impl.state_ = 0; - impl.cancel_token_.reset(); -#if defined(ASIO_ENABLE_CANCELIO) - impl.safe_cancellation_thread_id_ = 0; -#endif // defined(ASIO_ENABLE_CANCELIO) - - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; -} - -void win_iocp_socket_service_base::base_move_construct( - win_iocp_socket_service_base::base_implementation_type& impl, - win_iocp_socket_service_base::base_implementation_type& other_impl) -{ - impl.socket_ = other_impl.socket_; - other_impl.socket_ = invalid_socket; - - impl.state_ = other_impl.state_; - other_impl.state_ = 0; - - impl.cancel_token_ = other_impl.cancel_token_; - other_impl.cancel_token_.reset(); - -#if defined(ASIO_ENABLE_CANCELIO) - impl.safe_cancellation_thread_id_ = other_impl.safe_cancellation_thread_id_; - other_impl.safe_cancellation_thread_id_ = 0; -#endif // defined(ASIO_ENABLE_CANCELIO) - - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; -} - -void win_iocp_socket_service_base::base_move_assign( - win_iocp_socket_service_base::base_implementation_type& impl, - win_iocp_socket_service_base& other_service, - win_iocp_socket_service_base::base_implementation_type& other_impl) -{ - close_for_destruction(impl); - - if (this != &other_service) - { - // Remove implementation from linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; - } - - impl.socket_ = other_impl.socket_; - other_impl.socket_ = invalid_socket; - - impl.state_ = other_impl.state_; - other_impl.state_ = 0; - - impl.cancel_token_ = other_impl.cancel_token_; - other_impl.cancel_token_.reset(); - -#if defined(ASIO_ENABLE_CANCELIO) - impl.safe_cancellation_thread_id_ = other_impl.safe_cancellation_thread_id_; - other_impl.safe_cancellation_thread_id_ = 0; -#endif // defined(ASIO_ENABLE_CANCELIO) - - if (this != &other_service) - { - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(other_service.mutex_); - impl.next_ = other_service.impl_list_; - impl.prev_ = 0; - if (other_service.impl_list_) - other_service.impl_list_->prev_ = &impl; - other_service.impl_list_ = &impl; - } -} - -void win_iocp_socket_service_base::destroy( - win_iocp_socket_service_base::base_implementation_type& impl) -{ - close_for_destruction(impl); - - // Remove implementation from linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; -} - -asio::error_code win_iocp_socket_service_base::close( - win_iocp_socket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((iocp_service_.context(), - "socket", &impl, impl.socket_, "close")); - - // Check if the reactor was created, in which case we need to close the - // socket on the reactor as well to cancel any operations that might be - // running there. - select_reactor* r = static_cast( - interlocked_compare_exchange_pointer( - reinterpret_cast(&reactor_), 0, 0)); - if (r) - r->deregister_descriptor(impl.socket_, impl.reactor_data_, true); - - socket_ops::close(impl.socket_, impl.state_, false, ec); - - if (r) - r->cleanup_descriptor_data(impl.reactor_data_); - } - else - { - ec = asio::error_code(); - } - - impl.socket_ = invalid_socket; - impl.state_ = 0; - impl.cancel_token_.reset(); -#if defined(ASIO_ENABLE_CANCELIO) - impl.safe_cancellation_thread_id_ = 0; -#endif // defined(ASIO_ENABLE_CANCELIO) - - return ec; -} - -socket_type win_iocp_socket_service_base::release( - win_iocp_socket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (!is_open(impl)) - return invalid_socket; - - cancel(impl, ec); - if (ec) - return invalid_socket; - - nt_set_info_fn fn = get_nt_set_info(); - if (fn == 0) - { - ec = asio::error::operation_not_supported; - return invalid_socket; - } - - HANDLE sock_as_handle = reinterpret_cast(impl.socket_); - ULONG_PTR iosb[2] = { 0, 0 }; - void* info[2] = { 0, 0 }; - if (fn(sock_as_handle, iosb, &info, sizeof(info), - 61 /* FileReplaceCompletionInformation */)) - { - ec = asio::error::operation_not_supported; - return invalid_socket; - } - - socket_type tmp = impl.socket_; - impl.socket_ = invalid_socket; - return tmp; -} - -asio::error_code win_iocp_socket_service_base::cancel( - win_iocp_socket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return ec; - } - - ASIO_HANDLER_OPERATION((iocp_service_.context(), - "socket", &impl, impl.socket_, "cancel")); - - if (FARPROC cancel_io_ex_ptr = ::GetProcAddress( - ::GetModuleHandleA("KERNEL32"), "CancelIoEx")) - { - // The version of Windows supports cancellation from any thread. - typedef BOOL (WINAPI* cancel_io_ex_t)(HANDLE, LPOVERLAPPED); - cancel_io_ex_t cancel_io_ex = (cancel_io_ex_t)cancel_io_ex_ptr; - socket_type sock = impl.socket_; - HANDLE sock_as_handle = reinterpret_cast(sock); - if (!cancel_io_ex(sock_as_handle, 0)) - { - DWORD last_error = ::GetLastError(); - if (last_error == ERROR_NOT_FOUND) - { - // ERROR_NOT_FOUND means that there were no operations to be - // cancelled. We swallow this error to match the behaviour on other - // platforms. - ec = asio::error_code(); - } - else - { - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - } - else - { - ec = asio::error_code(); - } - } -#if defined(ASIO_ENABLE_CANCELIO) - else if (impl.safe_cancellation_thread_id_ == 0) - { - // No operations have been started, so there's nothing to cancel. - ec = asio::error_code(); - } - else if (impl.safe_cancellation_thread_id_ == ::GetCurrentThreadId()) - { - // Asynchronous operations have been started from the current thread only, - // so it is safe to try to cancel them using CancelIo. - socket_type sock = impl.socket_; - HANDLE sock_as_handle = reinterpret_cast(sock); - if (!::CancelIo(sock_as_handle)) - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - else - { - ec = asio::error_code(); - } - } - else - { - // Asynchronous operations have been started from more than one thread, - // so cancellation is not safe. - ec = asio::error::operation_not_supported; - } -#else // defined(ASIO_ENABLE_CANCELIO) - else - { - // Cancellation is not supported as CancelIo may not be used. - ec = asio::error::operation_not_supported; - } -#endif // defined(ASIO_ENABLE_CANCELIO) - - // Cancel any operations started via the reactor. - if (!ec) - { - select_reactor* r = static_cast( - interlocked_compare_exchange_pointer( - reinterpret_cast(&reactor_), 0, 0)); - if (r) - r->cancel_ops(impl.socket_, impl.reactor_data_); - } - - return ec; -} - -asio::error_code win_iocp_socket_service_base::do_open( - win_iocp_socket_service_base::base_implementation_type& impl, - int family, int type, int protocol, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - socket_holder sock(socket_ops::socket(family, type, protocol, ec)); - if (sock.get() == invalid_socket) - return ec; - - HANDLE sock_as_handle = reinterpret_cast(sock.get()); - if (iocp_service_.register_handle(sock_as_handle, ec)) - return ec; - - impl.socket_ = sock.release(); - switch (type) - { - case SOCK_STREAM: impl.state_ = socket_ops::stream_oriented; break; - case SOCK_DGRAM: impl.state_ = socket_ops::datagram_oriented; break; - default: impl.state_ = 0; break; - } - impl.cancel_token_.reset(static_cast(0), socket_ops::noop_deleter()); - ec = asio::error_code(); - return ec; -} - -asio::error_code win_iocp_socket_service_base::do_assign( - win_iocp_socket_service_base::base_implementation_type& impl, - int type, socket_type native_socket, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - HANDLE sock_as_handle = reinterpret_cast(native_socket); - if (iocp_service_.register_handle(sock_as_handle, ec)) - return ec; - - impl.socket_ = native_socket; - switch (type) - { - case SOCK_STREAM: impl.state_ = socket_ops::stream_oriented; break; - case SOCK_DGRAM: impl.state_ = socket_ops::datagram_oriented; break; - default: impl.state_ = 0; break; - } - impl.cancel_token_.reset(static_cast(0), socket_ops::noop_deleter()); - ec = asio::error_code(); - return ec; -} - -void win_iocp_socket_service_base::start_send_op( - win_iocp_socket_service_base::base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, - socket_base::message_flags flags, bool noop, operation* op) -{ - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - if (noop) - iocp_service_.on_completion(op); - else if (!is_open(impl)) - iocp_service_.on_completion(op, asio::error::bad_descriptor); - else - { - DWORD bytes_transferred = 0; - int result = ::WSASend(impl.socket_, buffers, - static_cast(buffer_count), &bytes_transferred, flags, op, 0); - DWORD last_error = ::WSAGetLastError(); - if (last_error == ERROR_PORT_UNREACHABLE) - last_error = WSAECONNREFUSED; - if (result != 0 && last_error != WSA_IO_PENDING) - iocp_service_.on_completion(op, last_error, bytes_transferred); - else - iocp_service_.on_pending(op); - } -} - -void win_iocp_socket_service_base::start_send_to_op( - win_iocp_socket_service_base::base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, - const socket_addr_type* addr, int addrlen, - socket_base::message_flags flags, operation* op) -{ - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - if (!is_open(impl)) - iocp_service_.on_completion(op, asio::error::bad_descriptor); - else - { - DWORD bytes_transferred = 0; - int result = ::WSASendTo(impl.socket_, buffers, - static_cast(buffer_count), - &bytes_transferred, flags, addr, addrlen, op, 0); - DWORD last_error = ::WSAGetLastError(); - if (last_error == ERROR_PORT_UNREACHABLE) - last_error = WSAECONNREFUSED; - if (result != 0 && last_error != WSA_IO_PENDING) - iocp_service_.on_completion(op, last_error, bytes_transferred); - else - iocp_service_.on_pending(op); - } -} - -void win_iocp_socket_service_base::start_receive_op( - win_iocp_socket_service_base::base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, - socket_base::message_flags flags, bool noop, operation* op) -{ - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - if (noop) - iocp_service_.on_completion(op); - else if (!is_open(impl)) - iocp_service_.on_completion(op, asio::error::bad_descriptor); - else - { - DWORD bytes_transferred = 0; - DWORD recv_flags = flags; - int result = ::WSARecv(impl.socket_, buffers, - static_cast(buffer_count), - &bytes_transferred, &recv_flags, op, 0); - DWORD last_error = ::WSAGetLastError(); - if (last_error == ERROR_NETNAME_DELETED) - last_error = WSAECONNRESET; - else if (last_error == ERROR_PORT_UNREACHABLE) - last_error = WSAECONNREFUSED; - if (result != 0 && last_error != WSA_IO_PENDING) - iocp_service_.on_completion(op, last_error, bytes_transferred); - else - iocp_service_.on_pending(op); - } -} - -void win_iocp_socket_service_base::start_null_buffers_receive_op( - win_iocp_socket_service_base::base_implementation_type& impl, - socket_base::message_flags flags, reactor_op* op) -{ - if ((impl.state_ & socket_ops::stream_oriented) != 0) - { - // For stream sockets on Windows, we may issue a 0-byte overlapped - // WSARecv to wait until there is data available on the socket. - ::WSABUF buf = { 0, 0 }; - start_receive_op(impl, &buf, 1, flags, false, op); - } - else - { - start_reactor_op(impl, - (flags & socket_base::message_out_of_band) - ? select_reactor::except_op : select_reactor::read_op, - op); - } -} - -void win_iocp_socket_service_base::start_receive_from_op( - win_iocp_socket_service_base::base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, socket_addr_type* addr, - socket_base::message_flags flags, int* addrlen, operation* op) -{ - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - if (!is_open(impl)) - iocp_service_.on_completion(op, asio::error::bad_descriptor); - else - { - DWORD bytes_transferred = 0; - DWORD recv_flags = flags; - int result = ::WSARecvFrom(impl.socket_, buffers, - static_cast(buffer_count), - &bytes_transferred, &recv_flags, addr, addrlen, op, 0); - DWORD last_error = ::WSAGetLastError(); - if (last_error == ERROR_PORT_UNREACHABLE) - last_error = WSAECONNREFUSED; - if (result != 0 && last_error != WSA_IO_PENDING) - iocp_service_.on_completion(op, last_error, bytes_transferred); - else - iocp_service_.on_pending(op); - } -} - -void win_iocp_socket_service_base::start_accept_op( - win_iocp_socket_service_base::base_implementation_type& impl, - bool peer_is_open, socket_holder& new_socket, int family, int type, - int protocol, void* output_buffer, DWORD address_length, operation* op) -{ - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - if (!is_open(impl)) - iocp_service_.on_completion(op, asio::error::bad_descriptor); - else if (peer_is_open) - iocp_service_.on_completion(op, asio::error::already_open); - else - { - asio::error_code ec; - new_socket.reset(socket_ops::socket(family, type, protocol, ec)); - if (new_socket.get() == invalid_socket) - iocp_service_.on_completion(op, ec); - else - { - DWORD bytes_read = 0; - BOOL result = ::AcceptEx(impl.socket_, new_socket.get(), output_buffer, - 0, address_length, address_length, &bytes_read, op); - DWORD last_error = ::WSAGetLastError(); - if (!result && last_error != WSA_IO_PENDING) - iocp_service_.on_completion(op, last_error); - else - iocp_service_.on_pending(op); - } - } -} - -void win_iocp_socket_service_base::restart_accept_op( - socket_type s, socket_holder& new_socket, int family, int type, - int protocol, void* output_buffer, DWORD address_length, operation* op) -{ - new_socket.reset(); - iocp_service_.work_started(); - - asio::error_code ec; - new_socket.reset(socket_ops::socket(family, type, protocol, ec)); - if (new_socket.get() == invalid_socket) - iocp_service_.on_completion(op, ec); - else - { - DWORD bytes_read = 0; - BOOL result = ::AcceptEx(s, new_socket.get(), output_buffer, - 0, address_length, address_length, &bytes_read, op); - DWORD last_error = ::WSAGetLastError(); - if (!result && last_error != WSA_IO_PENDING) - iocp_service_.on_completion(op, last_error); - else - iocp_service_.on_pending(op); - } -} - -void win_iocp_socket_service_base::start_reactor_op( - win_iocp_socket_service_base::base_implementation_type& impl, - int op_type, reactor_op* op) -{ - select_reactor& r = get_reactor(); - update_cancellation_thread_id(impl); - - if (is_open(impl)) - { - r.start_op(op_type, impl.socket_, impl.reactor_data_, op, false, false); - return; - } - else - op->ec_ = asio::error::bad_descriptor; - - iocp_service_.post_immediate_completion(op, false); -} - -void win_iocp_socket_service_base::start_connect_op( - win_iocp_socket_service_base::base_implementation_type& impl, - int family, int type, const socket_addr_type* addr, - std::size_t addrlen, win_iocp_socket_connect_op_base* op) -{ - // If ConnectEx is available, use that. - if (family == ASIO_OS_DEF(AF_INET) - || family == ASIO_OS_DEF(AF_INET6)) - { - if (connect_ex_fn connect_ex = get_connect_ex(impl, type)) - { - union address_union - { - socket_addr_type base; - sockaddr_in4_type v4; - sockaddr_in6_type v6; - } a; - - using namespace std; // For memset. - memset(&a, 0, sizeof(a)); - a.base.sa_family = family; - - socket_ops::bind(impl.socket_, &a.base, - family == ASIO_OS_DEF(AF_INET) - ? sizeof(a.v4) : sizeof(a.v6), op->ec_); - if (op->ec_ && op->ec_ != asio::error::invalid_argument) - { - iocp_service_.post_immediate_completion(op, false); - return; - } - - op->connect_ex_ = true; - update_cancellation_thread_id(impl); - iocp_service_.work_started(); - - BOOL result = connect_ex(impl.socket_, - addr, static_cast(addrlen), 0, 0, 0, op); - DWORD last_error = ::WSAGetLastError(); - if (!result && last_error != WSA_IO_PENDING) - iocp_service_.on_completion(op, last_error); - else - iocp_service_.on_pending(op); - return; - } - } - - // Otherwise, fall back to a reactor-based implementation. - select_reactor& r = get_reactor(); - update_cancellation_thread_id(impl); - - if ((impl.state_ & socket_ops::non_blocking) != 0 - || socket_ops::set_internal_non_blocking( - impl.socket_, impl.state_, true, op->ec_)) - { - if (socket_ops::connect(impl.socket_, addr, addrlen, op->ec_) != 0) - { - if (op->ec_ == asio::error::in_progress - || op->ec_ == asio::error::would_block) - { - op->ec_ = asio::error_code(); - r.start_op(select_reactor::connect_op, impl.socket_, - impl.reactor_data_, op, false, false); - return; - } - } - } - - r.post_immediate_completion(op, false); -} - -void win_iocp_socket_service_base::close_for_destruction( - win_iocp_socket_service_base::base_implementation_type& impl) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((iocp_service_.context(), - "socket", &impl, impl.socket_, "close")); - - // Check if the reactor was created, in which case we need to close the - // socket on the reactor as well to cancel any operations that might be - // running there. - select_reactor* r = static_cast( - interlocked_compare_exchange_pointer( - reinterpret_cast(&reactor_), 0, 0)); - if (r) - r->deregister_descriptor(impl.socket_, impl.reactor_data_, true); - - asio::error_code ignored_ec; - socket_ops::close(impl.socket_, impl.state_, true, ignored_ec); - - if (r) - r->cleanup_descriptor_data(impl.reactor_data_); - } - - impl.socket_ = invalid_socket; - impl.state_ = 0; - impl.cancel_token_.reset(); -#if defined(ASIO_ENABLE_CANCELIO) - impl.safe_cancellation_thread_id_ = 0; -#endif // defined(ASIO_ENABLE_CANCELIO) -} - -void win_iocp_socket_service_base::update_cancellation_thread_id( - win_iocp_socket_service_base::base_implementation_type& impl) -{ -#if defined(ASIO_ENABLE_CANCELIO) - if (impl.safe_cancellation_thread_id_ == 0) - impl.safe_cancellation_thread_id_ = ::GetCurrentThreadId(); - else if (impl.safe_cancellation_thread_id_ != ::GetCurrentThreadId()) - impl.safe_cancellation_thread_id_ = ~DWORD(0); -#else // defined(ASIO_ENABLE_CANCELIO) - (void)impl; -#endif // defined(ASIO_ENABLE_CANCELIO) -} - -select_reactor& win_iocp_socket_service_base::get_reactor() -{ - select_reactor* r = static_cast( - interlocked_compare_exchange_pointer( - reinterpret_cast(&reactor_), 0, 0)); - if (!r) - { - r = &(use_service(io_context_)); - interlocked_exchange_pointer(reinterpret_cast(&reactor_), r); - } - return *r; -} - -win_iocp_socket_service_base::connect_ex_fn -win_iocp_socket_service_base::get_connect_ex( - win_iocp_socket_service_base::base_implementation_type& impl, int type) -{ -#if defined(ASIO_DISABLE_CONNECTEX) - (void)impl; - (void)type; - return 0; -#else // defined(ASIO_DISABLE_CONNECTEX) - if (type != ASIO_OS_DEF(SOCK_STREAM) - && type != ASIO_OS_DEF(SOCK_SEQPACKET)) - return 0; - - void* ptr = interlocked_compare_exchange_pointer(&connect_ex_, 0, 0); - if (!ptr) - { - GUID guid = { 0x25a207b9, 0xddf3, 0x4660, - { 0x8e, 0xe9, 0x76, 0xe5, 0x8c, 0x74, 0x06, 0x3e } }; - - DWORD bytes = 0; - if (::WSAIoctl(impl.socket_, SIO_GET_EXTENSION_FUNCTION_POINTER, - &guid, sizeof(guid), &ptr, sizeof(ptr), &bytes, 0, 0) != 0) - { - // Set connect_ex_ to a special value to indicate that ConnectEx is - // unavailable. That way we won't bother trying to look it up again. - ptr = this; - } - - interlocked_exchange_pointer(&connect_ex_, ptr); - } - - return reinterpret_cast(ptr == this ? 0 : ptr); -#endif // defined(ASIO_DISABLE_CONNECTEX) -} - -win_iocp_socket_service_base::nt_set_info_fn -win_iocp_socket_service_base::get_nt_set_info() -{ - void* ptr = interlocked_compare_exchange_pointer(&nt_set_info_, 0, 0); - if (!ptr) - { - if (HMODULE h = ::GetModuleHandleA("NTDLL.DLL")) - ptr = reinterpret_cast(GetProcAddress(h, "NtSetInformationFile")); - - // On failure, set nt_set_info_ to a special value to indicate that the - // NtSetInformationFile function is unavailable. That way we won't bother - // trying to look it up again. - interlocked_exchange_pointer(&nt_set_info_, ptr ? ptr : this); - } - - return reinterpret_cast(ptr == this ? 0 : ptr); -} - -void* win_iocp_socket_service_base::interlocked_compare_exchange_pointer( - void** dest, void* exch, void* cmp) -{ -#if defined(_M_IX86) - return reinterpret_cast(InterlockedCompareExchange( - reinterpret_cast(dest), reinterpret_cast(exch), - reinterpret_cast(cmp))); -#else - return InterlockedCompareExchangePointer(dest, exch, cmp); -#endif -} - -void* win_iocp_socket_service_base::interlocked_exchange_pointer( - void** dest, void* val) -{ -#if defined(_M_IX86) - return reinterpret_cast(InterlockedExchange( - reinterpret_cast(dest), reinterpret_cast(val))); -#else - return InterlockedExchangePointer(dest, val); -#endif -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_IMPL_WIN_IOCP_SOCKET_SERVICE_BASE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_mutex.ipp b/scout_sdk/asio/asio/detail/impl/win_mutex.ipp deleted file mode 100644 index dc58a12..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_mutex.ipp +++ /dev/null @@ -1,84 +0,0 @@ -// -// detail/impl/win_mutex.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_MUTEX_IPP -#define ASIO_DETAIL_IMPL_WIN_MUTEX_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_mutex.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -win_mutex::win_mutex() -{ - int error = do_init(); - asio::error_code ec(error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "mutex"); -} - -int win_mutex::do_init() -{ -#if defined(__MINGW32__) - // Not sure if MinGW supports structured exception handling, so for now - // we'll just call the Windows API and hope. -# if defined(UNDER_CE) - ::InitializeCriticalSection(&crit_section_); -# elif defined(ASIO_WINDOWS_APP) - if (!::InitializeCriticalSectionEx(&crit_section_, 0, 0)) - return ::GetLastError(); -# else - if (!::InitializeCriticalSectionAndSpinCount(&crit_section_, 0x80000000)) - return ::GetLastError(); -# endif - return 0; -#else - __try - { -# if defined(UNDER_CE) - ::InitializeCriticalSection(&crit_section_); -# elif defined(ASIO_WINDOWS_APP) - if (!::InitializeCriticalSectionEx(&crit_section_, 0, 0)) - return ::GetLastError(); -# else - if (!::InitializeCriticalSectionAndSpinCount(&crit_section_, 0x80000000)) - return ::GetLastError(); -# endif - } - __except(GetExceptionCode() == STATUS_NO_MEMORY - ? EXCEPTION_EXECUTE_HANDLER : EXCEPTION_CONTINUE_SEARCH) - { - return ERROR_OUTOFMEMORY; - } - - return 0; -#endif -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_IMPL_WIN_MUTEX_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_object_handle_service.ipp b/scout_sdk/asio/asio/detail/impl/win_object_handle_service.ipp deleted file mode 100644 index c5e59d1..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_object_handle_service.ipp +++ /dev/null @@ -1,449 +0,0 @@ -// -// detail/impl/win_object_handle_service.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2011 Boris Schaeling (boris@highscore.de) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_OBJECT_HANDLE_SERVICE_IPP -#define ASIO_DETAIL_IMPL_WIN_OBJECT_HANDLE_SERVICE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - -#include "asio/detail/win_object_handle_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -win_object_handle_service::win_object_handle_service( - asio::io_context& io_context) - : service_base(io_context), - io_context_(asio::use_service(io_context)), - mutex_(), - impl_list_(0), - shutdown_(false) -{ -} - -void win_object_handle_service::shutdown() -{ - mutex::scoped_lock lock(mutex_); - - // Setting this flag to true prevents new objects from being registered, and - // new asynchronous wait operations from being started. We only need to worry - // about cleaning up the operations that are currently in progress. - shutdown_ = true; - - op_queue ops; - for (implementation_type* impl = impl_list_; impl; impl = impl->next_) - ops.push(impl->op_queue_); - - lock.unlock(); - - io_context_.abandon_operations(ops); -} - -void win_object_handle_service::construct( - win_object_handle_service::implementation_type& impl) -{ - impl.handle_ = INVALID_HANDLE_VALUE; - impl.wait_handle_ = INVALID_HANDLE_VALUE; - impl.owner_ = this; - - // Insert implementation into linked list of all implementations. - mutex::scoped_lock lock(mutex_); - if (!shutdown_) - { - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; - } -} - -void win_object_handle_service::move_construct( - win_object_handle_service::implementation_type& impl, - win_object_handle_service::implementation_type& other_impl) -{ - mutex::scoped_lock lock(mutex_); - - // Insert implementation into linked list of all implementations. - if (!shutdown_) - { - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; - } - - impl.handle_ = other_impl.handle_; - other_impl.handle_ = INVALID_HANDLE_VALUE; - impl.wait_handle_ = other_impl.wait_handle_; - other_impl.wait_handle_ = INVALID_HANDLE_VALUE; - impl.op_queue_.push(other_impl.op_queue_); - impl.owner_ = this; - - // We must not hold the lock while calling UnregisterWaitEx. This is because - // the registered callback function might be invoked while we are waiting for - // UnregisterWaitEx to complete. - lock.unlock(); - - if (impl.wait_handle_ != INVALID_HANDLE_VALUE) - ::UnregisterWaitEx(impl.wait_handle_, INVALID_HANDLE_VALUE); - - if (!impl.op_queue_.empty()) - register_wait_callback(impl, lock); -} - -void win_object_handle_service::move_assign( - win_object_handle_service::implementation_type& impl, - win_object_handle_service& other_service, - win_object_handle_service::implementation_type& other_impl) -{ - asio::error_code ignored_ec; - close(impl, ignored_ec); - - mutex::scoped_lock lock(mutex_); - - if (this != &other_service) - { - // Remove implementation from linked list of all implementations. - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; - } - - impl.handle_ = other_impl.handle_; - other_impl.handle_ = INVALID_HANDLE_VALUE; - impl.wait_handle_ = other_impl.wait_handle_; - other_impl.wait_handle_ = INVALID_HANDLE_VALUE; - impl.op_queue_.push(other_impl.op_queue_); - impl.owner_ = this; - - if (this != &other_service) - { - // Insert implementation into linked list of all implementations. - impl.next_ = other_service.impl_list_; - impl.prev_ = 0; - if (other_service.impl_list_) - other_service.impl_list_->prev_ = &impl; - other_service.impl_list_ = &impl; - } - - // We must not hold the lock while calling UnregisterWaitEx. This is because - // the registered callback function might be invoked while we are waiting for - // UnregisterWaitEx to complete. - lock.unlock(); - - if (impl.wait_handle_ != INVALID_HANDLE_VALUE) - ::UnregisterWaitEx(impl.wait_handle_, INVALID_HANDLE_VALUE); - - if (!impl.op_queue_.empty()) - register_wait_callback(impl, lock); -} - -void win_object_handle_service::destroy( - win_object_handle_service::implementation_type& impl) -{ - mutex::scoped_lock lock(mutex_); - - // Remove implementation from linked list of all implementations. - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; - - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((io_context_.context(), "object_handle", - &impl, reinterpret_cast(impl.wait_handle_), "close")); - - HANDLE wait_handle = impl.wait_handle_; - impl.wait_handle_ = INVALID_HANDLE_VALUE; - - op_queue ops; - while (wait_op* op = impl.op_queue_.front()) - { - op->ec_ = asio::error::operation_aborted; - impl.op_queue_.pop(); - ops.push(op); - } - - // We must not hold the lock while calling UnregisterWaitEx. This is - // because the registered callback function might be invoked while we are - // waiting for UnregisterWaitEx to complete. - lock.unlock(); - - if (wait_handle != INVALID_HANDLE_VALUE) - ::UnregisterWaitEx(wait_handle, INVALID_HANDLE_VALUE); - - ::CloseHandle(impl.handle_); - impl.handle_ = INVALID_HANDLE_VALUE; - - io_context_.post_deferred_completions(ops); - } -} - -asio::error_code win_object_handle_service::assign( - win_object_handle_service::implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec) -{ - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - impl.handle_ = handle; - ec = asio::error_code(); - return ec; -} - -asio::error_code win_object_handle_service::close( - win_object_handle_service::implementation_type& impl, - asio::error_code& ec) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((io_context_.context(), "object_handle", - &impl, reinterpret_cast(impl.wait_handle_), "close")); - - mutex::scoped_lock lock(mutex_); - - HANDLE wait_handle = impl.wait_handle_; - impl.wait_handle_ = INVALID_HANDLE_VALUE; - - op_queue completed_ops; - while (wait_op* op = impl.op_queue_.front()) - { - impl.op_queue_.pop(); - op->ec_ = asio::error::operation_aborted; - completed_ops.push(op); - } - - // We must not hold the lock while calling UnregisterWaitEx. This is - // because the registered callback function might be invoked while we are - // waiting for UnregisterWaitEx to complete. - lock.unlock(); - - if (wait_handle != INVALID_HANDLE_VALUE) - ::UnregisterWaitEx(wait_handle, INVALID_HANDLE_VALUE); - - if (::CloseHandle(impl.handle_)) - { - impl.handle_ = INVALID_HANDLE_VALUE; - ec = asio::error_code(); - } - else - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - } - - io_context_.post_deferred_completions(completed_ops); - } - else - { - ec = asio::error_code(); - } - - return ec; -} - -asio::error_code win_object_handle_service::cancel( - win_object_handle_service::implementation_type& impl, - asio::error_code& ec) -{ - if (is_open(impl)) - { - ASIO_HANDLER_OPERATION((io_context_.context(), "object_handle", - &impl, reinterpret_cast(impl.wait_handle_), "cancel")); - - mutex::scoped_lock lock(mutex_); - - HANDLE wait_handle = impl.wait_handle_; - impl.wait_handle_ = INVALID_HANDLE_VALUE; - - op_queue completed_ops; - while (wait_op* op = impl.op_queue_.front()) - { - op->ec_ = asio::error::operation_aborted; - impl.op_queue_.pop(); - completed_ops.push(op); - } - - // We must not hold the lock while calling UnregisterWaitEx. This is - // because the registered callback function might be invoked while we are - // waiting for UnregisterWaitEx to complete. - lock.unlock(); - - if (wait_handle != INVALID_HANDLE_VALUE) - ::UnregisterWaitEx(wait_handle, INVALID_HANDLE_VALUE); - - ec = asio::error_code(); - - io_context_.post_deferred_completions(completed_ops); - } - else - { - ec = asio::error::bad_descriptor; - } - - return ec; -} - -void win_object_handle_service::wait( - win_object_handle_service::implementation_type& impl, - asio::error_code& ec) -{ - switch (::WaitForSingleObject(impl.handle_, INFINITE)) - { - case WAIT_FAILED: - { - DWORD last_error = ::GetLastError(); - ec = asio::error_code(last_error, - asio::error::get_system_category()); - break; - } - case WAIT_OBJECT_0: - case WAIT_ABANDONED: - default: - ec = asio::error_code(); - break; - } -} - -void win_object_handle_service::start_wait_op( - win_object_handle_service::implementation_type& impl, wait_op* op) -{ - io_context_.work_started(); - - if (is_open(impl)) - { - mutex::scoped_lock lock(mutex_); - - if (!shutdown_) - { - impl.op_queue_.push(op); - - // Only the first operation to be queued gets to register a wait callback. - // Subsequent operations have to wait for the first to finish. - if (impl.op_queue_.front() == op) - register_wait_callback(impl, lock); - } - else - { - lock.unlock(); - io_context_.post_deferred_completion(op); - } - } - else - { - op->ec_ = asio::error::bad_descriptor; - io_context_.post_deferred_completion(op); - } -} - -void win_object_handle_service::register_wait_callback( - win_object_handle_service::implementation_type& impl, - mutex::scoped_lock& lock) -{ - lock.lock(); - - if (!RegisterWaitForSingleObject(&impl.wait_handle_, - impl.handle_, &win_object_handle_service::wait_callback, - &impl, INFINITE, WT_EXECUTEONLYONCE)) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - - op_queue completed_ops; - while (wait_op* op = impl.op_queue_.front()) - { - op->ec_ = ec; - impl.op_queue_.pop(); - completed_ops.push(op); - } - - lock.unlock(); - io_context_.post_deferred_completions(completed_ops); - } -} - -void win_object_handle_service::wait_callback(PVOID param, BOOLEAN) -{ - implementation_type* impl = static_cast(param); - mutex::scoped_lock lock(impl->owner_->mutex_); - - if (impl->wait_handle_ != INVALID_HANDLE_VALUE) - { - ::UnregisterWaitEx(impl->wait_handle_, NULL); - impl->wait_handle_ = INVALID_HANDLE_VALUE; - } - - if (wait_op* op = impl->op_queue_.front()) - { - op_queue completed_ops; - - op->ec_ = asio::error_code(); - impl->op_queue_.pop(); - completed_ops.push(op); - - if (!impl->op_queue_.empty()) - { - if (!RegisterWaitForSingleObject(&impl->wait_handle_, - impl->handle_, &win_object_handle_service::wait_callback, - param, INFINITE, WT_EXECUTEONLYONCE)) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - - while ((op = impl->op_queue_.front()) != 0) - { - op->ec_ = ec; - impl->op_queue_.pop(); - completed_ops.push(op); - } - } - } - - io_context_impl& ioc = impl->owner_->io_context_; - lock.unlock(); - ioc.post_deferred_completions(completed_ops); - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - -#endif // ASIO_DETAIL_IMPL_WIN_OBJECT_HANDLE_SERVICE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_static_mutex.ipp b/scout_sdk/asio/asio/detail/impl/win_static_mutex.ipp deleted file mode 100644 index 42089bd..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_static_mutex.ipp +++ /dev/null @@ -1,136 +0,0 @@ -// -// detail/impl/win_static_mutex.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_STATIC_MUTEX_IPP -#define ASIO_DETAIL_IMPL_WIN_STATIC_MUTEX_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_static_mutex.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -void win_static_mutex::init() -{ - int error = do_init(); - asio::error_code ec(error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "static_mutex"); -} - -int win_static_mutex::do_init() -{ - using namespace std; // For sprintf. - wchar_t mutex_name[128]; -#if defined(ASIO_HAS_SECURE_RTL) - swprintf_s( -#else // defined(ASIO_HAS_SECURE_RTL) - _snwprintf( -#endif // defined(ASIO_HAS_SECURE_RTL) - mutex_name, 128, L"asio-58CCDC44-6264-4842-90C2-F3C545CB8AA7-%u-%p", - static_cast(::GetCurrentProcessId()), this); - -#if defined(ASIO_WINDOWS_APP) - HANDLE mutex = ::CreateMutexExW(0, mutex_name, CREATE_MUTEX_INITIAL_OWNER, 0); -#else // defined(ASIO_WINDOWS_APP) - HANDLE mutex = ::CreateMutexW(0, TRUE, mutex_name); -#endif // defined(ASIO_WINDOWS_APP) - DWORD last_error = ::GetLastError(); - if (mutex == 0) - return ::GetLastError(); - - if (last_error == ERROR_ALREADY_EXISTS) - { -#if defined(ASIO_WINDOWS_APP) - ::WaitForSingleObjectEx(mutex, INFINITE, false); -#else // defined(ASIO_WINDOWS_APP) - ::WaitForSingleObject(mutex, INFINITE); -#endif // defined(ASIO_WINDOWS_APP) - } - - if (initialised_) - { - ::ReleaseMutex(mutex); - ::CloseHandle(mutex); - return 0; - } - -#if defined(__MINGW32__) - // Not sure if MinGW supports structured exception handling, so for now - // we'll just call the Windows API and hope. -# if defined(UNDER_CE) - ::InitializeCriticalSection(&crit_section_); -# else - if (!::InitializeCriticalSectionAndSpinCount(&crit_section_, 0x80000000)) - { - last_error = ::GetLastError(); - ::ReleaseMutex(mutex); - ::CloseHandle(mutex); - return last_error; - } -# endif -#else - __try - { -# if defined(UNDER_CE) - ::InitializeCriticalSection(&crit_section_); -# elif defined(ASIO_WINDOWS_APP) - if (!::InitializeCriticalSectionEx(&crit_section_, 0, 0)) - { - last_error = ::GetLastError(); - ::ReleaseMutex(mutex); - ::CloseHandle(mutex); - return last_error; - } -# else - if (!::InitializeCriticalSectionAndSpinCount(&crit_section_, 0x80000000)) - { - last_error = ::GetLastError(); - ::ReleaseMutex(mutex); - ::CloseHandle(mutex); - return last_error; - } -# endif - } - __except(GetExceptionCode() == STATUS_NO_MEMORY - ? EXCEPTION_EXECUTE_HANDLER : EXCEPTION_CONTINUE_SEARCH) - { - ::ReleaseMutex(mutex); - ::CloseHandle(mutex); - return ERROR_OUTOFMEMORY; - } -#endif - - initialised_ = true; - ::ReleaseMutex(mutex); - ::CloseHandle(mutex); - return 0; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_IMPL_WIN_STATIC_MUTEX_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_thread.ipp b/scout_sdk/asio/asio/detail/impl/win_thread.ipp deleted file mode 100644 index ed6dbaf..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_thread.ipp +++ /dev/null @@ -1,150 +0,0 @@ -// -// detail/impl/win_thread.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_THREAD_IPP -#define ASIO_DETAIL_IMPL_WIN_THREAD_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_APP) \ - && !defined(UNDER_CE) - -#include -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_thread.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -win_thread::~win_thread() -{ - ::CloseHandle(thread_); - - // The exit_event_ handle is deliberately allowed to leak here since it - // is an error for the owner of an internal thread not to join() it. -} - -void win_thread::join() -{ - HANDLE handles[2] = { exit_event_, thread_ }; - ::WaitForMultipleObjects(2, handles, FALSE, INFINITE); - ::CloseHandle(exit_event_); - if (terminate_threads()) - { - ::TerminateThread(thread_, 0); - } - else - { - ::QueueUserAPC(apc_function, thread_, 0); - ::WaitForSingleObject(thread_, INFINITE); - } -} - -std::size_t win_thread::hardware_concurrency() -{ - SYSTEM_INFO system_info; - ::GetSystemInfo(&system_info); - return system_info.dwNumberOfProcessors; -} - -void win_thread::start_thread(func_base* arg, unsigned int stack_size) -{ - ::HANDLE entry_event = 0; - arg->entry_event_ = entry_event = ::CreateEventW(0, true, false, 0); - if (!entry_event) - { - DWORD last_error = ::GetLastError(); - delete arg; - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "thread.entry_event"); - } - - arg->exit_event_ = exit_event_ = ::CreateEventW(0, true, false, 0); - if (!exit_event_) - { - DWORD last_error = ::GetLastError(); - delete arg; - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "thread.exit_event"); - } - - unsigned int thread_id = 0; - thread_ = reinterpret_cast(::_beginthreadex(0, - stack_size, win_thread_function, arg, 0, &thread_id)); - if (!thread_) - { - DWORD last_error = ::GetLastError(); - delete arg; - if (entry_event) - ::CloseHandle(entry_event); - if (exit_event_) - ::CloseHandle(exit_event_); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "thread"); - } - - if (entry_event) - { - ::WaitForSingleObject(entry_event, INFINITE); - ::CloseHandle(entry_event); - } -} - -unsigned int __stdcall win_thread_function(void* arg) -{ - win_thread::auto_func_base_ptr func = { - static_cast(arg) }; - - ::SetEvent(func.ptr->entry_event_); - - func.ptr->run(); - - // Signal that the thread has finished its work, but rather than returning go - // to sleep to put the thread into a well known state. If the thread is being - // joined during global object destruction then it may be killed using - // TerminateThread (to avoid a deadlock in DllMain). Otherwise, the SleepEx - // call will be interrupted using QueueUserAPC and the thread will shut down - // cleanly. - HANDLE exit_event = func.ptr->exit_event_; - delete func.ptr; - func.ptr = 0; - ::SetEvent(exit_event); - ::SleepEx(INFINITE, TRUE); - - return 0; -} - -#if defined(WINVER) && (WINVER < 0x0500) -void __stdcall apc_function(ULONG) {} -#else -void __stdcall apc_function(ULONG_PTR) {} -#endif - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_APP) - // && !defined(UNDER_CE) - -#endif // ASIO_DETAIL_IMPL_WIN_THREAD_IPP diff --git a/scout_sdk/asio/asio/detail/impl/win_tss_ptr.ipp b/scout_sdk/asio/asio/detail/impl/win_tss_ptr.ipp deleted file mode 100644 index 61df0ce..0000000 --- a/scout_sdk/asio/asio/detail/impl/win_tss_ptr.ipp +++ /dev/null @@ -1,57 +0,0 @@ -// -// detail/impl/win_tss_ptr.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WIN_TSS_PTR_IPP -#define ASIO_DETAIL_IMPL_WIN_TSS_PTR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_tss_ptr.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -DWORD win_tss_ptr_create() -{ -#if defined(UNDER_CE) - const DWORD out_of_indexes = 0xFFFFFFFF; -#else - const DWORD out_of_indexes = TLS_OUT_OF_INDEXES; -#endif - - DWORD tss_key = ::TlsAlloc(); - if (tss_key == out_of_indexes) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "tss"); - } - return tss_key; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_IMPL_WIN_TSS_PTR_IPP diff --git a/scout_sdk/asio/asio/detail/impl/winrt_ssocket_service_base.ipp b/scout_sdk/asio/asio/detail/impl/winrt_ssocket_service_base.ipp deleted file mode 100644 index 288ca8b..0000000 --- a/scout_sdk/asio/asio/detail/impl/winrt_ssocket_service_base.ipp +++ /dev/null @@ -1,629 +0,0 @@ -// -// detail/impl/winrt_ssocket_service_base.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WINRT_SSOCKET_SERVICE_BASE_IPP -#define ASIO_DETAIL_IMPL_WINRT_SSOCKET_SERVICE_BASE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include -#include "asio/detail/winrt_ssocket_service_base.hpp" -#include "asio/detail/winrt_async_op.hpp" -#include "asio/detail/winrt_utils.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -winrt_ssocket_service_base::winrt_ssocket_service_base( - asio::io_context& io_context) - : io_context_(use_service(io_context)), - async_manager_(use_service(io_context)), - mutex_(), - impl_list_(0) -{ -} - -void winrt_ssocket_service_base::base_shutdown() -{ - // Close all implementations, causing all operations to complete. - asio::detail::mutex::scoped_lock lock(mutex_); - base_implementation_type* impl = impl_list_; - while (impl) - { - asio::error_code ignored_ec; - close(*impl, ignored_ec); - impl = impl->next_; - } -} - -void winrt_ssocket_service_base::construct( - winrt_ssocket_service_base::base_implementation_type& impl) -{ - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; -} - -void winrt_ssocket_service_base::base_move_construct( - winrt_ssocket_service_base::base_implementation_type& impl, - winrt_ssocket_service_base::base_implementation_type& other_impl) -{ - impl.socket_ = other_impl.socket_; - other_impl.socket_ = nullptr; - - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - impl.next_ = impl_list_; - impl.prev_ = 0; - if (impl_list_) - impl_list_->prev_ = &impl; - impl_list_ = &impl; -} - -void winrt_ssocket_service_base::base_move_assign( - winrt_ssocket_service_base::base_implementation_type& impl, - winrt_ssocket_service_base& other_service, - winrt_ssocket_service_base::base_implementation_type& other_impl) -{ - asio::error_code ignored_ec; - close(impl, ignored_ec); - - if (this != &other_service) - { - // Remove implementation from linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; - } - - impl.socket_ = other_impl.socket_; - other_impl.socket_ = nullptr; - - if (this != &other_service) - { - // Insert implementation into linked list of all implementations. - asio::detail::mutex::scoped_lock lock(other_service.mutex_); - impl.next_ = other_service.impl_list_; - impl.prev_ = 0; - if (other_service.impl_list_) - other_service.impl_list_->prev_ = &impl; - other_service.impl_list_ = &impl; - } -} - -void winrt_ssocket_service_base::destroy( - winrt_ssocket_service_base::base_implementation_type& impl) -{ - asio::error_code ignored_ec; - close(impl, ignored_ec); - - // Remove implementation from linked list of all implementations. - asio::detail::mutex::scoped_lock lock(mutex_); - if (impl_list_ == &impl) - impl_list_ = impl.next_; - if (impl.prev_) - impl.prev_->next_ = impl.next_; - if (impl.next_) - impl.next_->prev_= impl.prev_; - impl.next_ = 0; - impl.prev_ = 0; -} - -asio::error_code winrt_ssocket_service_base::close( - winrt_ssocket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (impl.socket_) - { - delete impl.socket_; - impl.socket_ = nullptr; - } - - ec = asio::error_code(); - return ec; -} - -winrt_ssocket_service_base::native_handle_type -winrt_ssocket_service_base::release( - winrt_ssocket_service_base::base_implementation_type& impl, - asio::error_code& ec) -{ - if (!is_open(impl)) - return nullptr; - - cancel(impl, ec); - if (ec) - return nullptr; - - native_handle_type tmp = impl.socket_; - impl.socket_ = nullptr; - return tmp; -} - -std::size_t winrt_ssocket_service_base::do_get_endpoint( - const base_implementation_type& impl, bool local, - void* addr, std::size_t addr_len, asio::error_code& ec) const -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return addr_len; - } - - try - { - std::string addr_string = winrt_utils::string(local - ? impl.socket_->Information->LocalAddress->CanonicalName - : impl.socket_->Information->RemoteAddress->CanonicalName); - unsigned short port = winrt_utils::integer(local - ? impl.socket_->Information->LocalPort - : impl.socket_->Information->RemotePort); - unsigned long scope = 0; - - switch (reinterpret_cast(addr)->sa_family) - { - case ASIO_OS_DEF(AF_INET): - if (addr_len < sizeof(sockaddr_in4_type)) - { - ec = asio::error::invalid_argument; - return addr_len; - } - else - { - socket_ops::inet_pton(ASIO_OS_DEF(AF_INET), addr_string.c_str(), - &reinterpret_cast(addr)->sin_addr, &scope, ec); - reinterpret_cast(addr)->sin_port - = socket_ops::host_to_network_short(port); - ec = asio::error_code(); - return sizeof(sockaddr_in4_type); - } - case ASIO_OS_DEF(AF_INET6): - if (addr_len < sizeof(sockaddr_in6_type)) - { - ec = asio::error::invalid_argument; - return addr_len; - } - else - { - socket_ops::inet_pton(ASIO_OS_DEF(AF_INET6), addr_string.c_str(), - &reinterpret_cast(addr)->sin6_addr, &scope, ec); - reinterpret_cast(addr)->sin6_port - = socket_ops::host_to_network_short(port); - ec = asio::error_code(); - return sizeof(sockaddr_in6_type); - } - default: - ec = asio::error::address_family_not_supported; - return addr_len; - } - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - return addr_len; - } -} - -asio::error_code winrt_ssocket_service_base::do_set_option( - winrt_ssocket_service_base::base_implementation_type& impl, - int level, int optname, const void* optval, - std::size_t optlen, asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return ec; - } - - try - { - if (level == ASIO_OS_DEF(SOL_SOCKET) - && optname == ASIO_OS_DEF(SO_KEEPALIVE)) - { - if (optlen == sizeof(int)) - { - int value = 0; - std::memcpy(&value, optval, optlen); - impl.socket_->Control->KeepAlive = !!value; - ec = asio::error_code(); - } - else - { - ec = asio::error::invalid_argument; - } - } - else if (level == ASIO_OS_DEF(IPPROTO_TCP) - && optname == ASIO_OS_DEF(TCP_NODELAY)) - { - if (optlen == sizeof(int)) - { - int value = 0; - std::memcpy(&value, optval, optlen); - impl.socket_->Control->NoDelay = !!value; - ec = asio::error_code(); - } - else - { - ec = asio::error::invalid_argument; - } - } - else - { - ec = asio::error::invalid_argument; - } - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - } - - return ec; -} - -void winrt_ssocket_service_base::do_get_option( - const winrt_ssocket_service_base::base_implementation_type& impl, - int level, int optname, void* optval, - std::size_t* optlen, asio::error_code& ec) const -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return; - } - - try - { - if (level == ASIO_OS_DEF(SOL_SOCKET) - && optname == ASIO_OS_DEF(SO_KEEPALIVE)) - { - if (*optlen >= sizeof(int)) - { - int value = impl.socket_->Control->KeepAlive ? 1 : 0; - std::memcpy(optval, &value, sizeof(int)); - *optlen = sizeof(int); - ec = asio::error_code(); - } - else - { - ec = asio::error::invalid_argument; - } - } - else if (level == ASIO_OS_DEF(IPPROTO_TCP) - && optname == ASIO_OS_DEF(TCP_NODELAY)) - { - if (*optlen >= sizeof(int)) - { - int value = impl.socket_->Control->NoDelay ? 1 : 0; - std::memcpy(optval, &value, sizeof(int)); - *optlen = sizeof(int); - ec = asio::error_code(); - } - else - { - ec = asio::error::invalid_argument; - } - } - else - { - ec = asio::error::invalid_argument; - } - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - } -} - -asio::error_code winrt_ssocket_service_base::do_connect( - winrt_ssocket_service_base::base_implementation_type& impl, - const void* addr, asio::error_code& ec) -{ - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return ec; - } - - char addr_string[max_addr_v6_str_len]; - unsigned short port; - switch (reinterpret_cast(addr)->sa_family) - { - case ASIO_OS_DEF(AF_INET): - socket_ops::inet_ntop(ASIO_OS_DEF(AF_INET), - &reinterpret_cast(addr)->sin_addr, - addr_string, sizeof(addr_string), 0, ec); - port = socket_ops::network_to_host_short( - reinterpret_cast(addr)->sin_port); - break; - case ASIO_OS_DEF(AF_INET6): - socket_ops::inet_ntop(ASIO_OS_DEF(AF_INET6), - &reinterpret_cast(addr)->sin6_addr, - addr_string, sizeof(addr_string), 0, ec); - port = socket_ops::network_to_host_short( - reinterpret_cast(addr)->sin6_port); - break; - default: - ec = asio::error::address_family_not_supported; - return ec; - } - - if (!ec) try - { - async_manager_.sync(impl.socket_->ConnectAsync( - ref new Windows::Networking::HostName( - winrt_utils::string(addr_string)), - winrt_utils::string(port)), ec); - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - } - - return ec; -} - -void winrt_ssocket_service_base::start_connect_op( - winrt_ssocket_service_base::base_implementation_type& impl, - const void* addr, winrt_async_op* op, bool is_continuation) -{ - if (!is_open(impl)) - { - op->ec_ = asio::error::bad_descriptor; - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - char addr_string[max_addr_v6_str_len]; - unsigned short port = 0; - switch (reinterpret_cast(addr)->sa_family) - { - case ASIO_OS_DEF(AF_INET): - socket_ops::inet_ntop(ASIO_OS_DEF(AF_INET), - &reinterpret_cast(addr)->sin_addr, - addr_string, sizeof(addr_string), 0, op->ec_); - port = socket_ops::network_to_host_short( - reinterpret_cast(addr)->sin_port); - break; - case ASIO_OS_DEF(AF_INET6): - socket_ops::inet_ntop(ASIO_OS_DEF(AF_INET6), - &reinterpret_cast(addr)->sin6_addr, - addr_string, sizeof(addr_string), 0, op->ec_); - port = socket_ops::network_to_host_short( - reinterpret_cast(addr)->sin6_port); - break; - default: - op->ec_ = asio::error::address_family_not_supported; - break; - } - - if (op->ec_) - { - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - try - { - async_manager_.async(impl.socket_->ConnectAsync( - ref new Windows::Networking::HostName( - winrt_utils::string(addr_string)), - winrt_utils::string(port)), op); - } - catch (Platform::Exception^ e) - { - op->ec_ = asio::error_code( - e->HResult, asio::system_category()); - io_context_.post_immediate_completion(op, is_continuation); - } -} - -std::size_t winrt_ssocket_service_base::do_send( - winrt_ssocket_service_base::base_implementation_type& impl, - const asio::const_buffer& data, - socket_base::message_flags flags, asio::error_code& ec) -{ - if (flags) - { - ec = asio::error::operation_not_supported; - return 0; - } - - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return 0; - } - - try - { - buffer_sequence_adapter bufs(asio::buffer(data)); - - if (bufs.all_empty()) - { - ec = asio::error_code(); - return 0; - } - - return async_manager_.sync( - impl.socket_->OutputStream->WriteAsync(bufs.buffers()[0]), ec); - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - return 0; - } -} - -void winrt_ssocket_service_base::start_send_op( - winrt_ssocket_service_base::base_implementation_type& impl, - const asio::const_buffer& data, socket_base::message_flags flags, - winrt_async_op* op, bool is_continuation) -{ - if (flags) - { - op->ec_ = asio::error::operation_not_supported; - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - if (!is_open(impl)) - { - op->ec_ = asio::error::bad_descriptor; - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - try - { - buffer_sequence_adapter bufs(asio::buffer(data)); - - if (bufs.all_empty()) - { - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - async_manager_.async( - impl.socket_->OutputStream->WriteAsync(bufs.buffers()[0]), op); - } - catch (Platform::Exception^ e) - { - op->ec_ = asio::error_code(e->HResult, - asio::system_category()); - io_context_.post_immediate_completion(op, is_continuation); - } -} - -std::size_t winrt_ssocket_service_base::do_receive( - winrt_ssocket_service_base::base_implementation_type& impl, - const asio::mutable_buffer& data, - socket_base::message_flags flags, asio::error_code& ec) -{ - if (flags) - { - ec = asio::error::operation_not_supported; - return 0; - } - - if (!is_open(impl)) - { - ec = asio::error::bad_descriptor; - return 0; - } - - try - { - buffer_sequence_adapter bufs(asio::buffer(data)); - - if (bufs.all_empty()) - { - ec = asio::error_code(); - return 0; - } - - async_manager_.sync( - impl.socket_->InputStream->ReadAsync( - bufs.buffers()[0], bufs.buffers()[0]->Capacity, - Windows::Storage::Streams::InputStreamOptions::Partial), ec); - - std::size_t bytes_transferred = bufs.buffers()[0]->Length; - if (bytes_transferred == 0 && !ec) - { - ec = asio::error::eof; - } - - return bytes_transferred; - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - return 0; - } -} - -void winrt_ssocket_service_base::start_receive_op( - winrt_ssocket_service_base::base_implementation_type& impl, - const asio::mutable_buffer& data, socket_base::message_flags flags, - winrt_async_op* op, - bool is_continuation) -{ - if (flags) - { - op->ec_ = asio::error::operation_not_supported; - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - if (!is_open(impl)) - { - op->ec_ = asio::error::bad_descriptor; - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - try - { - buffer_sequence_adapter bufs(asio::buffer(data)); - - if (bufs.all_empty()) - { - io_context_.post_immediate_completion(op, is_continuation); - return; - } - - async_manager_.async( - impl.socket_->InputStream->ReadAsync( - bufs.buffers()[0], bufs.buffers()[0]->Capacity, - Windows::Storage::Streams::InputStreamOptions::Partial), op); - } - catch (Platform::Exception^ e) - { - op->ec_ = asio::error_code(e->HResult, - asio::system_category()); - io_context_.post_immediate_completion(op, is_continuation); - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_IMPL_WINRT_SSOCKET_SERVICE_BASE_IPP diff --git a/scout_sdk/asio/asio/detail/impl/winrt_timer_scheduler.hpp b/scout_sdk/asio/asio/detail/impl/winrt_timer_scheduler.hpp deleted file mode 100644 index 856378f..0000000 --- a/scout_sdk/asio/asio/detail/impl/winrt_timer_scheduler.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// -// detail/impl/winrt_timer_scheduler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WINRT_TIMER_SCHEDULER_HPP -#define ASIO_DETAIL_IMPL_WINRT_TIMER_SCHEDULER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -void winrt_timer_scheduler::add_timer_queue(timer_queue& queue) -{ - do_add_timer_queue(queue); -} - -// Remove a timer queue from the reactor. -template -void winrt_timer_scheduler::remove_timer_queue(timer_queue& queue) -{ - do_remove_timer_queue(queue); -} - -template -void winrt_timer_scheduler::schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - - if (shutdown_) - { - io_context_.post_immediate_completion(op, false); - return; - } - - bool earliest = queue.enqueue_timer(time, timer, op); - io_context_.work_started(); - if (earliest) - event_.signal(lock); -} - -template -std::size_t winrt_timer_scheduler::cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - op_queue ops; - std::size_t n = queue.cancel_timer(timer, ops, max_cancelled); - lock.unlock(); - io_context_.post_deferred_completions(ops); - return n; -} - -template -void winrt_timer_scheduler::move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& to, - typename timer_queue::per_timer_data& from) -{ - asio::detail::mutex::scoped_lock lock(mutex_); - op_queue ops; - queue.cancel_timer(to, ops); - queue.move_timer(to, from); - lock.unlock(); - scheduler_.post_deferred_completions(ops); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_IMPL_WINRT_TIMER_SCHEDULER_HPP diff --git a/scout_sdk/asio/asio/detail/impl/winrt_timer_scheduler.ipp b/scout_sdk/asio/asio/detail/impl/winrt_timer_scheduler.ipp deleted file mode 100644 index ef21399..0000000 --- a/scout_sdk/asio/asio/detail/impl/winrt_timer_scheduler.ipp +++ /dev/null @@ -1,122 +0,0 @@ -// -// detail/impl/winrt_timer_scheduler.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WINRT_TIMER_SCHEDULER_IPP -#define ASIO_DETAIL_IMPL_WINRT_TIMER_SCHEDULER_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/winrt_timer_scheduler.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -winrt_timer_scheduler::winrt_timer_scheduler( - asio::io_context& io_context) - : asio::detail::service_base(io_context), - io_context_(use_service(io_context)), - mutex_(), - event_(), - timer_queues_(), - thread_(0), - stop_thread_(false), - shutdown_(false) -{ - thread_ = new asio::detail::thread( - bind_handler(&winrt_timer_scheduler::call_run_thread, this)); -} - -winrt_timer_scheduler::~winrt_timer_scheduler() -{ - shutdown(); -} - -void winrt_timer_scheduler::shutdown() -{ - asio::detail::mutex::scoped_lock lock(mutex_); - shutdown_ = true; - stop_thread_ = true; - event_.signal(lock); - lock.unlock(); - - if (thread_) - { - thread_->join(); - delete thread_; - thread_ = 0; - } - - op_queue ops; - timer_queues_.get_all_timers(ops); - io_context_.abandon_operations(ops); -} - -void winrt_timer_scheduler::notify_fork(asio::io_context::fork_event) -{ -} - -void winrt_timer_scheduler::init_task() -{ -} - -void winrt_timer_scheduler::run_thread() -{ - asio::detail::mutex::scoped_lock lock(mutex_); - while (!stop_thread_) - { - const long max_wait_duration = 5 * 60 * 1000000; - long wait_duration = timer_queues_.wait_duration_usec(max_wait_duration); - event_.wait_for_usec(lock, wait_duration); - event_.clear(lock); - op_queue ops; - timer_queues_.get_ready_timers(ops); - if (!ops.empty()) - { - lock.unlock(); - io_context_.post_deferred_completions(ops); - lock.lock(); - } - } -} - -void winrt_timer_scheduler::call_run_thread(winrt_timer_scheduler* scheduler) -{ - scheduler->run_thread(); -} - -void winrt_timer_scheduler::do_add_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.insert(&queue); -} - -void winrt_timer_scheduler::do_remove_timer_queue(timer_queue_base& queue) -{ - mutex::scoped_lock lock(mutex_); - timer_queues_.erase(&queue); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_IMPL_WINRT_TIMER_SCHEDULER_IPP diff --git a/scout_sdk/asio/asio/detail/impl/winsock_init.ipp b/scout_sdk/asio/asio/detail/impl/winsock_init.ipp deleted file mode 100644 index da4b0c0..0000000 --- a/scout_sdk/asio/asio/detail/impl/winsock_init.ipp +++ /dev/null @@ -1,82 +0,0 @@ -// -// detail/impl/winsock_init.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IMPL_WINSOCK_INIT_IPP -#define ASIO_DETAIL_IMPL_WINSOCK_INIT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#include "asio/detail/socket_types.hpp" -#include "asio/detail/winsock_init.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -void winsock_init_base::startup(data& d, - unsigned char major, unsigned char minor) -{ - if (::InterlockedIncrement(&d.init_count_) == 1) - { - WSADATA wsa_data; - long result = ::WSAStartup(MAKEWORD(major, minor), &wsa_data); - ::InterlockedExchange(&d.result_, result); - } -} - -void winsock_init_base::manual_startup(data& d) -{ - if (::InterlockedIncrement(&d.init_count_) == 1) - { - ::InterlockedExchange(&d.result_, 0); - } -} - -void winsock_init_base::cleanup(data& d) -{ - if (::InterlockedDecrement(&d.init_count_) == 0) - { - ::WSACleanup(); - } -} - -void winsock_init_base::manual_cleanup(data& d) -{ - ::InterlockedDecrement(&d.init_count_); -} - -void winsock_init_base::throw_on_error(data& d) -{ - long result = ::InterlockedExchangeAdd(&d.result_, 0); - if (result != 0) - { - asio::error_code ec(result, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "winsock"); - } -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#endif // ASIO_DETAIL_IMPL_WINSOCK_INIT_IPP diff --git a/scout_sdk/asio/asio/detail/io_control.hpp b/scout_sdk/asio/asio/detail/io_control.hpp deleted file mode 100644 index 12f35e0..0000000 --- a/scout_sdk/asio/asio/detail/io_control.hpp +++ /dev/null @@ -1,84 +0,0 @@ -// -// detail/io_control.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IO_CONTROL_HPP -#define ASIO_DETAIL_IO_CONTROL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { -namespace io_control { - -// I/O control command for getting number of bytes available. -class bytes_readable -{ -public: - // Default constructor. - bytes_readable() - : value_(0) - { - } - - // Construct with a specific command value. - bytes_readable(std::size_t value) - : value_(static_cast(value)) - { - } - - // Get the name of the IO control command. - int name() const - { - return static_cast(ASIO_OS_DEF(FIONREAD)); - } - - // Set the value of the I/O control command. - void set(std::size_t value) - { - value_ = static_cast(value); - } - - // Get the current value of the I/O control command. - std::size_t get() const - { - return static_cast(value_); - } - - // Get the address of the command data. - detail::ioctl_arg_type* data() - { - return &value_; - } - - // Get the address of the command data. - const detail::ioctl_arg_type* data() const - { - return &value_; - } - -private: - detail::ioctl_arg_type value_; -}; - -} // namespace io_control -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IO_CONTROL_HPP diff --git a/scout_sdk/asio/asio/detail/is_buffer_sequence.hpp b/scout_sdk/asio/asio/detail/is_buffer_sequence.hpp deleted file mode 100644 index 42ad0eb..0000000 --- a/scout_sdk/asio/asio/detail/is_buffer_sequence.hpp +++ /dev/null @@ -1,239 +0,0 @@ -// -// detail/is_buffer_sequence.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IS_BUFFER_SEQUENCE_HPP -#define ASIO_DETAIL_IS_BUFFER_SEQUENCE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -class mutable_buffer; -class const_buffer; - -namespace detail { - -struct buffer_sequence_memfns_base -{ - void begin(); - void end(); - void size(); - void max_size(); - void capacity(); - void data(); - void prepare(); - void commit(); - void consume(); -}; - -template -struct buffer_sequence_memfns_derived - : T, buffer_sequence_memfns_base -{ -}; - -template -struct buffer_sequence_memfns_check -{ -}; - -template -char (&begin_memfn_helper(...))[2]; - -template -char begin_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::begin>*); - -template -char (&end_memfn_helper(...))[2]; - -template -char end_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::end>*); - -template -char (&size_memfn_helper(...))[2]; - -template -char size_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::size>*); - -template -char (&max_size_memfn_helper(...))[2]; - -template -char max_size_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::max_size>*); - -template -char (&capacity_memfn_helper(...))[2]; - -template -char capacity_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::capacity>*); - -template -char (&data_memfn_helper(...))[2]; - -template -char data_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::data>*); - -template -char (&prepare_memfn_helper(...))[2]; - -template -char prepare_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::prepare>*); - -template -char (&commit_memfn_helper(...))[2]; - -template -char commit_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::commit>*); - -template -char (&consume_memfn_helper(...))[2]; - -template -char consume_memfn_helper( - buffer_sequence_memfns_check< - void (buffer_sequence_memfns_base::*)(), - &buffer_sequence_memfns_derived::consume>*); - -template -char (&buffer_element_type_helper(...))[2]; - -#if defined(ASIO_HAS_DECL_TYPE) - -template -char buffer_element_type_helper(T* t, - typename enable_if::value>::type*); - -#else // defined(ASIO_HAS_DECL_TYPE) - -template -char buffer_element_type_helper( - typename T::const_iterator*, - typename enable_if::value>::type*); - -#endif // defined(ASIO_HAS_DECL_TYPE) - -template -char (&const_buffers_type_typedef_helper(...))[2]; - -template -char const_buffers_type_typedef_helper( - typename T::const_buffers_type*); - -template -char (&mutable_buffers_type_typedef_helper(...))[2]; - -template -char mutable_buffers_type_typedef_helper( - typename T::mutable_buffers_type*); - -template -struct is_buffer_sequence_class - : integral_constant(0)) != 1 && - sizeof(end_memfn_helper(0)) != 1 && - sizeof(buffer_element_type_helper(0, 0)) == 1> -{ -}; - -template -struct is_buffer_sequence - : conditional::value, - is_buffer_sequence_class, - false_type>::type -{ -}; - -template <> -struct is_buffer_sequence - : true_type -{ -}; - -template <> -struct is_buffer_sequence - : true_type -{ -}; - -template <> -struct is_buffer_sequence - : true_type -{ -}; - -template <> -struct is_buffer_sequence - : false_type -{ -}; - -template -struct is_dynamic_buffer_class - : integral_constant(0)) != 1 && - sizeof(max_size_memfn_helper(0)) != 1 && - sizeof(capacity_memfn_helper(0)) != 1 && - sizeof(data_memfn_helper(0)) != 1 && - sizeof(consume_memfn_helper(0)) != 1 && - sizeof(prepare_memfn_helper(0)) != 1 && - sizeof(commit_memfn_helper(0)) != 1 && - sizeof(const_buffers_type_typedef_helper(0)) == 1 && - sizeof(mutable_buffers_type_typedef_helper(0)) == 1> -{ -}; - -template -struct is_dynamic_buffer - : conditional::value, - is_dynamic_buffer_class, - false_type>::type -{ -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IS_BUFFER_SEQUENCE_HPP diff --git a/scout_sdk/asio/asio/detail/is_executor.hpp b/scout_sdk/asio/asio/detail/is_executor.hpp deleted file mode 100644 index 4584dd0..0000000 --- a/scout_sdk/asio/asio/detail/is_executor.hpp +++ /dev/null @@ -1,126 +0,0 @@ -// -// detail/is_executor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_IS_EXECUTOR_HPP -#define ASIO_DETAIL_IS_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct executor_memfns_base -{ - void context(); - void on_work_started(); - void on_work_finished(); - void dispatch(); - void post(); - void defer(); -}; - -template -struct executor_memfns_derived - : T, executor_memfns_base -{ -}; - -template -struct executor_memfns_check -{ -}; - -template -char (&context_memfn_helper(...))[2]; - -template -char context_memfn_helper( - executor_memfns_check< - void (executor_memfns_base::*)(), - &executor_memfns_derived::context>*); - -template -char (&on_work_started_memfn_helper(...))[2]; - -template -char on_work_started_memfn_helper( - executor_memfns_check< - void (executor_memfns_base::*)(), - &executor_memfns_derived::on_work_started>*); - -template -char (&on_work_finished_memfn_helper(...))[2]; - -template -char on_work_finished_memfn_helper( - executor_memfns_check< - void (executor_memfns_base::*)(), - &executor_memfns_derived::on_work_finished>*); - -template -char (&dispatch_memfn_helper(...))[2]; - -template -char dispatch_memfn_helper( - executor_memfns_check< - void (executor_memfns_base::*)(), - &executor_memfns_derived::dispatch>*); - -template -char (&post_memfn_helper(...))[2]; - -template -char post_memfn_helper( - executor_memfns_check< - void (executor_memfns_base::*)(), - &executor_memfns_derived::post>*); - -template -char (&defer_memfn_helper(...))[2]; - -template -char defer_memfn_helper( - executor_memfns_check< - void (executor_memfns_base::*)(), - &executor_memfns_derived::defer>*); - -template -struct is_executor_class - : integral_constant(0)) != 1 && - sizeof(on_work_started_memfn_helper(0)) != 1 && - sizeof(on_work_finished_memfn_helper(0)) != 1 && - sizeof(dispatch_memfn_helper(0)) != 1 && - sizeof(post_memfn_helper(0)) != 1 && - sizeof(defer_memfn_helper(0)) != 1> -{ -}; - -template -struct is_executor - : conditional::value, - is_executor_class, - false_type>::type -{ -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_IS_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/detail/keyword_tss_ptr.hpp b/scout_sdk/asio/asio/detail/keyword_tss_ptr.hpp deleted file mode 100644 index 2ae651a..0000000 --- a/scout_sdk/asio/asio/detail/keyword_tss_ptr.hpp +++ /dev/null @@ -1,70 +0,0 @@ -// -// detail/keyword_tss_ptr.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_KEYWORD_TSS_PTR_HPP -#define ASIO_DETAIL_KEYWORD_TSS_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_THREAD_KEYWORD_EXTENSION) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class keyword_tss_ptr - : private noncopyable -{ -public: - // Constructor. - keyword_tss_ptr() - { - } - - // Destructor. - ~keyword_tss_ptr() - { - } - - // Get the value. - operator T*() const - { - return value_; - } - - // Set the value. - void operator=(T* value) - { - value_ = value; - } - -private: - static ASIO_THREAD_KEYWORD T* value_; -}; - -template -ASIO_THREAD_KEYWORD T* keyword_tss_ptr::value_; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_THREAD_KEYWORD_EXTENSION) - -#endif // ASIO_DETAIL_KEYWORD_TSS_PTR_HPP diff --git a/scout_sdk/asio/asio/detail/kqueue_reactor.hpp b/scout_sdk/asio/asio/detail/kqueue_reactor.hpp deleted file mode 100644 index 43cb9f9..0000000 --- a/scout_sdk/asio/asio/detail/kqueue_reactor.hpp +++ /dev/null @@ -1,242 +0,0 @@ -// -// detail/kqueue_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2005 Stefan Arentz (stefan at soze dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_KQUEUE_REACTOR_HPP -#define ASIO_DETAIL_KQUEUE_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_KQUEUE) - -#include -#include -#include -#include -#include "asio/detail/limits.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/object_pool.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/select_interrupter.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/timer_queue_base.hpp" -#include "asio/detail/timer_queue_set.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/error.hpp" -#include "asio/execution_context.hpp" - -// Older versions of Mac OS X may not define EV_OOBAND. -#if !defined(EV_OOBAND) -# define EV_OOBAND EV_FLAG1 -#endif // !defined(EV_OOBAND) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class scheduler; - -class kqueue_reactor - : public execution_context_service_base -{ -private: - // The mutex type used by this reactor. - typedef conditionally_enabled_mutex mutex; - -public: - enum op_types { read_op = 0, write_op = 1, - connect_op = 1, except_op = 2, max_ops = 3 }; - - // Per-descriptor queues. - struct descriptor_state - { - descriptor_state(bool locking) : mutex_(locking) {} - - friend class kqueue_reactor; - friend class object_pool_access; - - descriptor_state* next_; - descriptor_state* prev_; - - mutex mutex_; - int descriptor_; - int num_kevents_; // 1 == read only, 2 == read and write - op_queue op_queue_[max_ops]; - bool shutdown_; - }; - - // Per-descriptor data. - typedef descriptor_state* per_descriptor_data; - - // Constructor. - ASIO_DECL kqueue_reactor(asio::execution_context& ctx); - - // Destructor. - ASIO_DECL ~kqueue_reactor(); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Recreate internal descriptors following a fork. - ASIO_DECL void notify_fork( - asio::execution_context::fork_event fork_ev); - - // Initialise the task. - ASIO_DECL void init_task(); - - // Register a socket with the reactor. Returns 0 on success, system error - // code on failure. - ASIO_DECL int register_descriptor(socket_type descriptor, - per_descriptor_data& descriptor_data); - - // Register a descriptor with an associated single operation. Returns 0 on - // success, system error code on failure. - ASIO_DECL int register_internal_descriptor( - int op_type, socket_type descriptor, - per_descriptor_data& descriptor_data, reactor_op* op); - - // Move descriptor registration from one descriptor_data object to another. - ASIO_DECL void move_descriptor(socket_type descriptor, - per_descriptor_data& target_descriptor_data, - per_descriptor_data& source_descriptor_data); - - // Post a reactor operation for immediate completion. - void post_immediate_completion(reactor_op* op, bool is_continuation) - { - scheduler_.post_immediate_completion(op, is_continuation); - } - - // Start a new operation. The reactor operation will be performed when the - // given descriptor is flagged as ready, or an error has occurred. - ASIO_DECL void start_op(int op_type, socket_type descriptor, - per_descriptor_data& descriptor_data, reactor_op* op, - bool is_continuation, bool allow_speculative); - - // Cancel all operations associated with the given descriptor. The - // handlers associated with the descriptor will be invoked with the - // operation_aborted error. - ASIO_DECL void cancel_ops(socket_type descriptor, - per_descriptor_data& descriptor_data); - - // Cancel any operations that are running against the descriptor and remove - // its registration from the reactor. The reactor resources associated with - // the descriptor must be released by calling cleanup_descriptor_data. - ASIO_DECL void deregister_descriptor(socket_type descriptor, - per_descriptor_data& descriptor_data, bool closing); - - // Remove the descriptor's registration from the reactor. The reactor - // resources associated with the descriptor must be released by calling - // cleanup_descriptor_data. - ASIO_DECL void deregister_internal_descriptor( - socket_type descriptor, per_descriptor_data& descriptor_data); - - // Perform any post-deregistration cleanup tasks associated with the - // descriptor data. - ASIO_DECL void cleanup_descriptor_data( - per_descriptor_data& descriptor_data); - - // Add a new timer queue to the reactor. - template - void add_timer_queue(timer_queue& queue); - - // Remove a timer queue from the reactor. - template - void remove_timer_queue(timer_queue& queue); - - // Schedule a new operation in the given timer queue to expire at the - // specified absolute time. - template - void schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op); - - // Cancel the timer operations associated with the given token. Returns the - // number of operations that have been posted or dispatched. - template - std::size_t cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled = (std::numeric_limits::max)()); - - // Move the timer operations associated with the given timer. - template - void move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source); - - // Run the kqueue loop. - ASIO_DECL void run(long usec, op_queue& ops); - - // Interrupt the kqueue loop. - ASIO_DECL void interrupt(); - -private: - // Create the kqueue file descriptor. Throws an exception if the descriptor - // cannot be created. - ASIO_DECL static int do_kqueue_create(); - - // Allocate a new descriptor state object. - ASIO_DECL descriptor_state* allocate_descriptor_state(); - - // Free an existing descriptor state object. - ASIO_DECL void free_descriptor_state(descriptor_state* s); - - // Helper function to add a new timer queue. - ASIO_DECL void do_add_timer_queue(timer_queue_base& queue); - - // Helper function to remove a timer queue. - ASIO_DECL void do_remove_timer_queue(timer_queue_base& queue); - - // Get the timeout value for the kevent call. - ASIO_DECL timespec* get_timeout(long usec, timespec& ts); - - // The scheduler used to post completions. - scheduler& scheduler_; - - // Mutex to protect access to internal data. - mutex mutex_; - - // The kqueue file descriptor. - int kqueue_fd_; - - // The interrupter is used to break a blocking kevent call. - select_interrupter interrupter_; - - // The timer queues. - timer_queue_set timer_queues_; - - // Whether the service has been shut down. - bool shutdown_; - - // Mutex to protect access to the registered descriptors. - mutex registered_descriptors_mutex_; - - // Keep track of all registered descriptors. - object_pool registered_descriptors_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/kqueue_reactor.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/kqueue_reactor.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_KQUEUE) - -#endif // ASIO_DETAIL_KQUEUE_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/limits.hpp b/scout_sdk/asio/asio/detail/limits.hpp deleted file mode 100644 index d32470d..0000000 --- a/scout_sdk/asio/asio/detail/limits.hpp +++ /dev/null @@ -1,26 +0,0 @@ -// -// detail/limits.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_LIMITS_HPP -#define ASIO_DETAIL_LIMITS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_LIMITS) -# include -#else // defined(ASIO_HAS_BOOST_LIMITS) -# include -#endif // defined(ASIO_HAS_BOOST_LIMITS) - -#endif // ASIO_DETAIL_LIMITS_HPP diff --git a/scout_sdk/asio/asio/detail/local_free_on_block_exit.hpp b/scout_sdk/asio/asio/detail/local_free_on_block_exit.hpp deleted file mode 100644 index eba6b77..0000000 --- a/scout_sdk/asio/asio/detail/local_free_on_block_exit.hpp +++ /dev/null @@ -1,59 +0,0 @@ -// -// detail/local_free_on_block_exit.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_LOCAL_FREE_ON_BLOCK_EXIT_HPP -#define ASIO_DETAIL_LOCAL_FREE_ON_BLOCK_EXIT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -#if !defined(ASIO_WINDOWS_APP) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class local_free_on_block_exit - : private noncopyable -{ -public: - // Constructor blocks all signals for the calling thread. - explicit local_free_on_block_exit(void* p) - : p_(p) - { - } - - // Destructor restores the previous signal mask. - ~local_free_on_block_exit() - { - ::LocalFree(p_); - } - -private: - void* p_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS_APP) -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#endif // ASIO_DETAIL_LOCAL_FREE_ON_BLOCK_EXIT_HPP diff --git a/scout_sdk/asio/asio/detail/macos_fenced_block.hpp b/scout_sdk/asio/asio/detail/macos_fenced_block.hpp deleted file mode 100644 index bbac270..0000000 --- a/scout_sdk/asio/asio/detail/macos_fenced_block.hpp +++ /dev/null @@ -1,62 +0,0 @@ -// -// detail/macos_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_MACOS_FENCED_BLOCK_HPP -#define ASIO_DETAIL_MACOS_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(__MACH__) && defined(__APPLE__) - -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class macos_fenced_block - : private noncopyable -{ -public: - enum half_t { half }; - enum full_t { full }; - - // Constructor for a half fenced block. - explicit macos_fenced_block(half_t) - { - } - - // Constructor for a full fenced block. - explicit macos_fenced_block(full_t) - { - OSMemoryBarrier(); - } - - // Destructor. - ~macos_fenced_block() - { - OSMemoryBarrier(); - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(__MACH__) && defined(__APPLE__) - -#endif // ASIO_DETAIL_MACOS_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/memory.hpp b/scout_sdk/asio/asio/detail/memory.hpp deleted file mode 100644 index b1ec497..0000000 --- a/scout_sdk/asio/asio/detail/memory.hpp +++ /dev/null @@ -1,70 +0,0 @@ -// -// detail/memory.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_MEMORY_HPP -#define ASIO_DETAIL_MEMORY_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include - -#if !defined(ASIO_HAS_STD_SHARED_PTR) -# include -# include -#endif // !defined(ASIO_HAS_STD_SHARED_PTR) - -#if !defined(ASIO_HAS_STD_ADDRESSOF) -# include -#endif // !defined(ASIO_HAS_STD_ADDRESSOF) - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_STD_SHARED_PTR) -using std::shared_ptr; -using std::weak_ptr; -#else // defined(ASIO_HAS_STD_SHARED_PTR) -using boost::shared_ptr; -using boost::weak_ptr; -#endif // defined(ASIO_HAS_STD_SHARED_PTR) - -#if defined(ASIO_HAS_STD_ADDRESSOF) -using std::addressof; -#else // defined(ASIO_HAS_STD_ADDRESSOF) -using boost::addressof; -#endif // defined(ASIO_HAS_STD_ADDRESSOF) - -} // namespace detail - -#if defined(ASIO_HAS_CXX11_ALLOCATORS) -using std::allocator_arg_t; -# define ASIO_USES_ALLOCATOR(t) \ - namespace std { \ - template \ - struct uses_allocator : true_type {}; \ - } \ - /**/ -# define ASIO_REBIND_ALLOC(alloc, t) \ - typename std::allocator_traits::template rebind_alloc - /**/ -#else // defined(ASIO_HAS_CXX11_ALLOCATORS) -struct allocator_arg_t {}; -# define ASIO_USES_ALLOCATOR(t) -# define ASIO_REBIND_ALLOC(alloc, t) \ - typename alloc::template rebind::other - /**/ -#endif // defined(ASIO_HAS_CXX11_ALLOCATORS) - -} // namespace asio - -#endif // ASIO_DETAIL_MEMORY_HPP diff --git a/scout_sdk/asio/asio/detail/mutex.hpp b/scout_sdk/asio/asio/detail/mutex.hpp deleted file mode 100644 index 2f8f0b1..0000000 --- a/scout_sdk/asio/asio/detail/mutex.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// -// detail/mutex.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_MUTEX_HPP -#define ASIO_DETAIL_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) -# include "asio/detail/null_mutex.hpp" -#elif defined(ASIO_WINDOWS) -# include "asio/detail/win_mutex.hpp" -#elif defined(ASIO_HAS_PTHREADS) -# include "asio/detail/posix_mutex.hpp" -#elif defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) -# include "asio/detail/std_mutex.hpp" -#else -# error Only Windows, POSIX and std::mutex are supported! -#endif - -namespace asio { -namespace detail { - -#if !defined(ASIO_HAS_THREADS) -typedef null_mutex mutex; -#elif defined(ASIO_WINDOWS) -typedef win_mutex mutex; -#elif defined(ASIO_HAS_PTHREADS) -typedef posix_mutex mutex; -#elif defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) -typedef std_mutex mutex; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/noncopyable.hpp b/scout_sdk/asio/asio/detail/noncopyable.hpp deleted file mode 100644 index 0c038e1..0000000 --- a/scout_sdk/asio/asio/detail/noncopyable.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// -// detail/noncopyable.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NONCOPYABLE_HPP -#define ASIO_DETAIL_NONCOPYABLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class noncopyable -{ -protected: - noncopyable() {} - ~noncopyable() {} -private: - noncopyable(const noncopyable&); - const noncopyable& operator=(const noncopyable&); -}; - -} // namespace detail - -using asio::detail::noncopyable; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_NONCOPYABLE_HPP diff --git a/scout_sdk/asio/asio/detail/null_event.hpp b/scout_sdk/asio/asio/detail/null_event.hpp deleted file mode 100644 index 5686a41..0000000 --- a/scout_sdk/asio/asio/detail/null_event.hpp +++ /dev/null @@ -1,100 +0,0 @@ -// -// detail/null_event.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_EVENT_HPP -#define ASIO_DETAIL_NULL_EVENT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class null_event - : private noncopyable -{ -public: - // Constructor. - null_event() - { - } - - // Destructor. - ~null_event() - { - } - - // Signal the event. (Retained for backward compatibility.) - template - void signal(Lock&) - { - } - - // Signal all waiters. - template - void signal_all(Lock&) - { - } - - // Unlock the mutex and signal one waiter. - template - void unlock_and_signal_one(Lock&) - { - } - - // If there's a waiter, unlock the mutex and signal it. - template - bool maybe_unlock_and_signal_one(Lock&) - { - return false; - } - - // Reset the event. - template - void clear(Lock&) - { - } - - // Wait for the event to become signalled. - template - void wait(Lock&) - { - do_wait(); - } - - // Timed wait for the event to become signalled. - template - bool wait_for_usec(Lock&, long usec) - { - do_wait_for_usec(usec); - return true; - } - -private: - ASIO_DECL static void do_wait(); - ASIO_DECL static void do_wait_for_usec(long usec); -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/null_event.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_NULL_EVENT_HPP diff --git a/scout_sdk/asio/asio/detail/null_fenced_block.hpp b/scout_sdk/asio/asio/detail/null_fenced_block.hpp deleted file mode 100644 index 0275326..0000000 --- a/scout_sdk/asio/asio/detail/null_fenced_block.hpp +++ /dev/null @@ -1,47 +0,0 @@ -// -// detail/null_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_FENCED_BLOCK_HPP -#define ASIO_DETAIL_NULL_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class null_fenced_block - : private noncopyable -{ -public: - enum half_or_full_t { half, full }; - - // Constructor. - explicit null_fenced_block(half_or_full_t) - { - } - - // Destructor. - ~null_fenced_block() - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_NULL_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/null_global.hpp b/scout_sdk/asio/asio/detail/null_global.hpp deleted file mode 100644 index 727dd3f..0000000 --- a/scout_sdk/asio/asio/detail/null_global.hpp +++ /dev/null @@ -1,59 +0,0 @@ -// -// detail/null_global.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_GLOBAL_HPP -#define ASIO_DETAIL_NULL_GLOBAL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct null_global_impl -{ - null_global_impl() - : ptr_(0) - { - } - - // Destructor automatically cleans up the global. - ~null_global_impl() - { - delete ptr_; - } - - static null_global_impl instance_; - T* ptr_; -}; - -template -null_global_impl null_global_impl::instance_; - -template -T& null_global() -{ - if (null_global_impl::instance_.ptr_ == 0) - null_global_impl::instance_.ptr_ = new T; - return *null_global_impl::instance_.ptr_; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_NULL_GLOBAL_HPP diff --git a/scout_sdk/asio/asio/detail/null_mutex.hpp b/scout_sdk/asio/asio/detail/null_mutex.hpp deleted file mode 100644 index afe3fc0..0000000 --- a/scout_sdk/asio/asio/detail/null_mutex.hpp +++ /dev/null @@ -1,64 +0,0 @@ -// -// detail/null_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_MUTEX_HPP -#define ASIO_DETAIL_NULL_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class null_mutex - : private noncopyable -{ -public: - typedef asio::detail::scoped_lock scoped_lock; - - // Constructor. - null_mutex() - { - } - - // Destructor. - ~null_mutex() - { - } - - // Lock the mutex. - void lock() - { - } - - // Unlock the mutex. - void unlock() - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_THREADS) - -#endif // ASIO_DETAIL_NULL_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/null_reactor.hpp b/scout_sdk/asio/asio/detail/null_reactor.hpp deleted file mode 100644 index ca3c5fd..0000000 --- a/scout_sdk/asio/asio/detail/null_reactor.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// -// detail/null_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_REACTOR_HPP -#define ASIO_DETAIL_NULL_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) || defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/scheduler_operation.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class null_reactor - : public execution_context_service_base -{ -public: - // Constructor. - null_reactor(asio::execution_context& ctx) - : execution_context_service_base(ctx) - { - } - - // Destructor. - ~null_reactor() - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - } - - // No-op because should never be called. - void run(long /*usec*/, op_queue& /*ops*/) - { - } - - // No-op. - void interrupt() - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) || defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_NULL_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/null_signal_blocker.hpp b/scout_sdk/asio/asio/detail/null_signal_blocker.hpp deleted file mode 100644 index edfe820..0000000 --- a/scout_sdk/asio/asio/detail/null_signal_blocker.hpp +++ /dev/null @@ -1,69 +0,0 @@ -// -// detail/null_signal_blocker.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_SIGNAL_BLOCKER_HPP -#define ASIO_DETAIL_NULL_SIGNAL_BLOCKER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) \ - || defined(ASIO_WINDOWS) \ - || defined(ASIO_WINDOWS_RUNTIME) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class null_signal_blocker - : private noncopyable -{ -public: - // Constructor blocks all signals for the calling thread. - null_signal_blocker() - { - } - - // Destructor restores the previous signal mask. - ~null_signal_blocker() - { - } - - // Block all signals for the calling thread. - void block() - { - } - - // Restore the previous signal mask. - void unblock() - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_THREADS) - // || defined(ASIO_WINDOWS) - // || defined(ASIO_WINDOWS_RUNTIME) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - -#endif // ASIO_DETAIL_NULL_SIGNAL_BLOCKER_HPP diff --git a/scout_sdk/asio/asio/detail/null_socket_service.hpp b/scout_sdk/asio/asio/detail/null_socket_service.hpp deleted file mode 100644 index 109c6c7..0000000 --- a/scout_sdk/asio/asio/detail/null_socket_service.hpp +++ /dev/null @@ -1,508 +0,0 @@ -// -// detail/null_socket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_SOCKET_SERVICE_HPP -#define ASIO_DETAIL_NULL_SOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/buffer.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/socket_base.hpp" -#include "asio/detail/bind_handler.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class null_socket_service : - public service_base > -{ -public: - // The protocol type. - typedef Protocol protocol_type; - - // The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - // The native type of a socket. - typedef int native_handle_type; - - // The implementation type of the socket. - struct implementation_type - { - }; - - // Constructor. - null_socket_service(asio::io_context& io_context) - : service_base >(io_context), - io_context_(io_context) - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - } - - // Construct a new socket implementation. - void construct(implementation_type&) - { - } - - // Move-construct a new socket implementation. - void move_construct(implementation_type&, implementation_type&) - { - } - - // Move-assign from another socket implementation. - void move_assign(implementation_type&, - null_socket_service&, implementation_type&) - { - } - - // Move-construct a new socket implementation from another protocol type. - template - void converting_move_construct(implementation_type&, - null_socket_service&, - typename null_socket_service::implementation_type&) - { - } - - // Destroy a socket implementation. - void destroy(implementation_type&) - { - } - - // Open a new socket implementation. - asio::error_code open(implementation_type&, - const protocol_type&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Assign a native socket to a socket implementation. - asio::error_code assign(implementation_type&, const protocol_type&, - const native_handle_type&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Determine whether the socket is open. - bool is_open(const implementation_type&) const - { - return false; - } - - // Destroy a socket implementation. - asio::error_code close(implementation_type&, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Release ownership of the socket. - native_handle_type release(implementation_type&, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Get the native socket representation. - native_handle_type native_handle(implementation_type&) - { - return 0; - } - - // Cancel all operations associated with the socket. - asio::error_code cancel(implementation_type&, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Determine whether the socket is at the out-of-band data mark. - bool at_mark(const implementation_type&, - asio::error_code& ec) const - { - ec = asio::error::operation_not_supported; - return false; - } - - // Determine the number of bytes available for reading. - std::size_t available(const implementation_type&, - asio::error_code& ec) const - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Place the socket into the state where it will listen for new connections. - asio::error_code listen(implementation_type&, - int, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Perform an IO control command on the socket. - template - asio::error_code io_control(implementation_type&, - IO_Control_Command&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Gets the non-blocking mode of the socket. - bool non_blocking(const implementation_type&) const - { - return false; - } - - // Sets the non-blocking mode of the socket. - asio::error_code non_blocking(implementation_type&, - bool, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const implementation_type&) const - { - return false; - } - - // Sets the non-blocking mode of the native socket implementation. - asio::error_code native_non_blocking(implementation_type&, - bool, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Disable sends or receives on the socket. - asio::error_code shutdown(implementation_type&, - socket_base::shutdown_type, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Bind the socket to the specified local endpoint. - asio::error_code bind(implementation_type&, - const endpoint_type&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Set a socket option. - template - asio::error_code set_option(implementation_type&, - const Option&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Set a socket option. - template - asio::error_code get_option(const implementation_type&, - Option&, asio::error_code& ec) const - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Get the local endpoint. - endpoint_type local_endpoint(const implementation_type&, - asio::error_code& ec) const - { - ec = asio::error::operation_not_supported; - return endpoint_type(); - } - - // Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type&, - asio::error_code& ec) const - { - ec = asio::error::operation_not_supported; - return endpoint_type(); - } - - // Send the given data to the peer. - template - std::size_t send(implementation_type&, const ConstBufferSequence&, - socket_base::message_flags, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Wait until data can be sent without blocking. - std::size_t send(implementation_type&, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Start an asynchronous send. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_send(implementation_type&, const ConstBufferSequence&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Start an asynchronous wait until data can be sent without blocking. - template - void async_send(implementation_type&, const null_buffers&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Receive some data from the peer. Returns the number of bytes received. - template - std::size_t receive(implementation_type&, const MutableBufferSequence&, - socket_base::message_flags, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Wait until data can be received without blocking. - std::size_t receive(implementation_type&, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received - // must be valid for the lifetime of the asynchronous operation. - template - void async_receive(implementation_type&, const MutableBufferSequence&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Wait until data can be received without blocking. - template - void async_receive(implementation_type&, const null_buffers&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Receive some data with associated flags. Returns the number of bytes - // received. - template - std::size_t receive_with_flags(implementation_type&, - const MutableBufferSequence&, socket_base::message_flags, - socket_base::message_flags&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Wait until data can be received without blocking. - std::size_t receive_with_flags(implementation_type&, - const null_buffers&, socket_base::message_flags, - socket_base::message_flags&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received - // must be valid for the lifetime of the asynchronous operation. - template - void async_receive_with_flags(implementation_type&, - const MutableBufferSequence&, socket_base::message_flags, - socket_base::message_flags&, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Wait until data can be received without blocking. - template - void async_receive_with_flags(implementation_type&, - const null_buffers&, socket_base::message_flags, - socket_base::message_flags&, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Send a datagram to the specified endpoint. Returns the number of bytes - // sent. - template - std::size_t send_to(implementation_type&, const ConstBufferSequence&, - const endpoint_type&, socket_base::message_flags, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Wait until data can be sent without blocking. - std::size_t send_to(implementation_type&, const null_buffers&, - const endpoint_type&, socket_base::message_flags, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Start an asynchronous send. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_send_to(implementation_type&, const ConstBufferSequence&, - const endpoint_type&, socket_base::message_flags, - Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Start an asynchronous wait until data can be sent without blocking. - template - void async_send_to(implementation_type&, const null_buffers&, - const endpoint_type&, socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Receive a datagram with the endpoint of the sender. Returns the number of - // bytes received. - template - std::size_t receive_from(implementation_type&, const MutableBufferSequence&, - endpoint_type&, socket_base::message_flags, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Wait until data can be received without blocking. - std::size_t receive_from(implementation_type&, const null_buffers&, - endpoint_type&, socket_base::message_flags, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received and - // the sender_endpoint object must both be valid for the lifetime of the - // asynchronous operation. - template - void async_receive_from(implementation_type&, - const MutableBufferSequence&, endpoint_type&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Wait until data can be received without blocking. - template - void async_receive_from(implementation_type&, - const null_buffers&, endpoint_type&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.post(detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Accept a new connection. - template - asio::error_code accept(implementation_type&, - Socket&, endpoint_type*, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Start an asynchronous accept. The peer and peer_endpoint objects - // must be valid until the accept's handler is invoked. - template - void async_accept(implementation_type&, Socket&, - endpoint_type*, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - io_context_.post(detail::bind_handler(handler, ec)); - } - - // Connect the socket to the specified endpoint. - asio::error_code connect(implementation_type&, - const endpoint_type&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Start an asynchronous connect. - template - void async_connect(implementation_type&, - const endpoint_type&, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - io_context_.post(detail::bind_handler(handler, ec)); - } - -private: - asio::io_context& io_context_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_NULL_SOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/null_static_mutex.hpp b/scout_sdk/asio/asio/detail/null_static_mutex.hpp deleted file mode 100644 index 36ec04f..0000000 --- a/scout_sdk/asio/asio/detail/null_static_mutex.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// -// detail/null_static_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_STATIC_MUTEX_HPP -#define ASIO_DETAIL_NULL_STATIC_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) - -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct null_static_mutex -{ - typedef asio::detail::scoped_lock scoped_lock; - - // Initialise the mutex. - void init() - { - } - - // Lock the mutex. - void lock() - { - } - - // Unlock the mutex. - void unlock() - { - } - - int unused_; -}; - -#define ASIO_NULL_STATIC_MUTEX_INIT { 0 } - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_THREADS) - -#endif // ASIO_DETAIL_NULL_STATIC_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/null_thread.hpp b/scout_sdk/asio/asio/detail/null_thread.hpp deleted file mode 100644 index 7291ba3..0000000 --- a/scout_sdk/asio/asio/detail/null_thread.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// detail/null_thread.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_THREAD_HPP -#define ASIO_DETAIL_NULL_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class null_thread - : private noncopyable -{ -public: - // Constructor. - template - null_thread(Function, unsigned int = 0) - { - asio::detail::throw_error( - asio::error::operation_not_supported, "thread"); - } - - // Destructor. - ~null_thread() - { - } - - // Wait for the thread to exit. - void join() - { - } - - // Get number of CPUs. - static std::size_t hardware_concurrency() - { - return 1; - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_THREADS) - -#endif // ASIO_DETAIL_NULL_THREAD_HPP diff --git a/scout_sdk/asio/asio/detail/null_tss_ptr.hpp b/scout_sdk/asio/asio/detail/null_tss_ptr.hpp deleted file mode 100644 index 323967d..0000000 --- a/scout_sdk/asio/asio/detail/null_tss_ptr.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// -// detail/null_tss_ptr.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_NULL_TSS_PTR_HPP -#define ASIO_DETAIL_NULL_TSS_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class null_tss_ptr - : private noncopyable -{ -public: - // Constructor. - null_tss_ptr() - : value_(0) - { - } - - // Destructor. - ~null_tss_ptr() - { - } - - // Get the value. - operator T*() const - { - return value_; - } - - // Set the value. - void operator=(T* value) - { - value_ = value; - } - -private: - T* value_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_THREADS) - -#endif // ASIO_DETAIL_NULL_TSS_PTR_HPP diff --git a/scout_sdk/asio/asio/detail/object_pool.hpp b/scout_sdk/asio/asio/detail/object_pool.hpp deleted file mode 100644 index e1a3c54..0000000 --- a/scout_sdk/asio/asio/detail/object_pool.hpp +++ /dev/null @@ -1,171 +0,0 @@ -// -// detail/object_pool.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_OBJECT_POOL_HPP -#define ASIO_DETAIL_OBJECT_POOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class object_pool; - -class object_pool_access -{ -public: - template - static Object* create() - { - return new Object; - } - - template - static Object* create(Arg arg) - { - return new Object(arg); - } - - template - static void destroy(Object* o) - { - delete o; - } - - template - static Object*& next(Object* o) - { - return o->next_; - } - - template - static Object*& prev(Object* o) - { - return o->prev_; - } -}; - -template -class object_pool - : private noncopyable -{ -public: - // Constructor. - object_pool() - : live_list_(0), - free_list_(0) - { - } - - // Destructor destroys all objects. - ~object_pool() - { - destroy_list(live_list_); - destroy_list(free_list_); - } - - // Get the object at the start of the live list. - Object* first() - { - return live_list_; - } - - // Allocate a new object. - Object* alloc() - { - Object* o = free_list_; - if (o) - free_list_ = object_pool_access::next(free_list_); - else - o = object_pool_access::create(); - - object_pool_access::next(o) = live_list_; - object_pool_access::prev(o) = 0; - if (live_list_) - object_pool_access::prev(live_list_) = o; - live_list_ = o; - - return o; - } - - // Allocate a new object with an argument. - template - Object* alloc(Arg arg) - { - Object* o = free_list_; - if (o) - free_list_ = object_pool_access::next(free_list_); - else - o = object_pool_access::create(arg); - - object_pool_access::next(o) = live_list_; - object_pool_access::prev(o) = 0; - if (live_list_) - object_pool_access::prev(live_list_) = o; - live_list_ = o; - - return o; - } - - // Free an object. Moves it to the free list. No destructors are run. - void free(Object* o) - { - if (live_list_ == o) - live_list_ = object_pool_access::next(o); - - if (object_pool_access::prev(o)) - { - object_pool_access::next(object_pool_access::prev(o)) - = object_pool_access::next(o); - } - - if (object_pool_access::next(o)) - { - object_pool_access::prev(object_pool_access::next(o)) - = object_pool_access::prev(o); - } - - object_pool_access::next(o) = free_list_; - object_pool_access::prev(o) = 0; - free_list_ = o; - } - -private: - // Helper function to destroy all elements in a list. - void destroy_list(Object* list) - { - while (list) - { - Object* o = list; - list = object_pool_access::next(o); - object_pool_access::destroy(o); - } - } - - // The list of live objects. - Object* live_list_; - - // The free list. - Object* free_list_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_OBJECT_POOL_HPP diff --git a/scout_sdk/asio/asio/detail/old_win_sdk_compat.hpp b/scout_sdk/asio/asio/detail/old_win_sdk_compat.hpp deleted file mode 100644 index bfb109e..0000000 --- a/scout_sdk/asio/asio/detail/old_win_sdk_compat.hpp +++ /dev/null @@ -1,214 +0,0 @@ -// -// detail/old_win_sdk_compat.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_OLD_WIN_SDK_COMPAT_HPP -#define ASIO_DETAIL_OLD_WIN_SDK_COMPAT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -// Guess whether we are building against on old Platform SDK. -#if !defined(IN6ADDR_ANY_INIT) -#define ASIO_HAS_OLD_WIN_SDK 1 -#endif // !defined(IN6ADDR_ANY_INIT) - -#if defined(ASIO_HAS_OLD_WIN_SDK) - -// Emulation of types that are missing from old Platform SDKs. -// -// N.B. this emulation is also used if building for a Windows 2000 target with -// a recent (i.e. Vista or later) SDK, as the SDK does not provide IPv6 support -// in that case. - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -enum -{ - sockaddr_storage_maxsize = 128, // Maximum size. - sockaddr_storage_alignsize = (sizeof(__int64)), // Desired alignment. - sockaddr_storage_pad1size = (sockaddr_storage_alignsize - sizeof(short)), - sockaddr_storage_pad2size = (sockaddr_storage_maxsize - - (sizeof(short) + sockaddr_storage_pad1size + sockaddr_storage_alignsize)) -}; - -struct sockaddr_storage_emulation -{ - short ss_family; - char __ss_pad1[sockaddr_storage_pad1size]; - __int64 __ss_align; - char __ss_pad2[sockaddr_storage_pad2size]; -}; - -struct in6_addr_emulation -{ - union - { - u_char Byte[16]; - u_short Word[8]; - } u; -}; - -#if !defined(s6_addr) -# define _S6_un u -# define _S6_u8 Byte -# define s6_addr _S6_un._S6_u8 -#endif // !defined(s6_addr) - -struct sockaddr_in6_emulation -{ - short sin6_family; - u_short sin6_port; - u_long sin6_flowinfo; - in6_addr_emulation sin6_addr; - u_long sin6_scope_id; -}; - -struct ipv6_mreq_emulation -{ - in6_addr_emulation ipv6mr_multiaddr; - unsigned int ipv6mr_interface; -}; - -struct addrinfo_emulation -{ - int ai_flags; - int ai_family; - int ai_socktype; - int ai_protocol; - size_t ai_addrlen; - char* ai_canonname; - sockaddr* ai_addr; - addrinfo_emulation* ai_next; -}; - -#if !defined(AI_PASSIVE) -# define AI_PASSIVE 0x1 -#endif - -#if !defined(AI_CANONNAME) -# define AI_CANONNAME 0x2 -#endif - -#if !defined(AI_NUMERICHOST) -# define AI_NUMERICHOST 0x4 -#endif - -#if !defined(EAI_AGAIN) -# define EAI_AGAIN WSATRY_AGAIN -#endif - -#if !defined(EAI_BADFLAGS) -# define EAI_BADFLAGS WSAEINVAL -#endif - -#if !defined(EAI_FAIL) -# define EAI_FAIL WSANO_RECOVERY -#endif - -#if !defined(EAI_FAMILY) -# define EAI_FAMILY WSAEAFNOSUPPORT -#endif - -#if !defined(EAI_MEMORY) -# define EAI_MEMORY WSA_NOT_ENOUGH_MEMORY -#endif - -#if !defined(EAI_NODATA) -# define EAI_NODATA WSANO_DATA -#endif - -#if !defined(EAI_NONAME) -# define EAI_NONAME WSAHOST_NOT_FOUND -#endif - -#if !defined(EAI_SERVICE) -# define EAI_SERVICE WSATYPE_NOT_FOUND -#endif - -#if !defined(EAI_SOCKTYPE) -# define EAI_SOCKTYPE WSAESOCKTNOSUPPORT -#endif - -#if !defined(NI_NOFQDN) -# define NI_NOFQDN 0x01 -#endif - -#if !defined(NI_NUMERICHOST) -# define NI_NUMERICHOST 0x02 -#endif - -#if !defined(NI_NAMEREQD) -# define NI_NAMEREQD 0x04 -#endif - -#if !defined(NI_NUMERICSERV) -# define NI_NUMERICSERV 0x08 -#endif - -#if !defined(NI_DGRAM) -# define NI_DGRAM 0x10 -#endif - -#if !defined(IPPROTO_IPV6) -# define IPPROTO_IPV6 41 -#endif - -#if !defined(IPV6_UNICAST_HOPS) -# define IPV6_UNICAST_HOPS 4 -#endif - -#if !defined(IPV6_MULTICAST_IF) -# define IPV6_MULTICAST_IF 9 -#endif - -#if !defined(IPV6_MULTICAST_HOPS) -# define IPV6_MULTICAST_HOPS 10 -#endif - -#if !defined(IPV6_MULTICAST_LOOP) -# define IPV6_MULTICAST_LOOP 11 -#endif - -#if !defined(IPV6_JOIN_GROUP) -# define IPV6_JOIN_GROUP 12 -#endif - -#if !defined(IPV6_LEAVE_GROUP) -# define IPV6_LEAVE_GROUP 13 -#endif - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_OLD_WIN_SDK) - -// Even newer Platform SDKs that support IPv6 may not define IPV6_V6ONLY. -#if !defined(IPV6_V6ONLY) -# define IPV6_V6ONLY 27 -#endif - -// Some SDKs (e.g. Windows CE) don't define IPPROTO_ICMPV6. -#if !defined(IPPROTO_ICMPV6) -# define IPPROTO_ICMPV6 58 -#endif - -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#endif // ASIO_DETAIL_OLD_WIN_SDK_COMPAT_HPP diff --git a/scout_sdk/asio/asio/detail/op_queue.hpp b/scout_sdk/asio/asio/detail/op_queue.hpp deleted file mode 100644 index 6219f79..0000000 --- a/scout_sdk/asio/asio/detail/op_queue.hpp +++ /dev/null @@ -1,162 +0,0 @@ -// -// detail/op_queue.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_OP_QUEUE_HPP -#define ASIO_DETAIL_OP_QUEUE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class op_queue; - -class op_queue_access -{ -public: - template - static Operation* next(Operation* o) - { - return static_cast(o->next_); - } - - template - static void next(Operation1*& o1, Operation2* o2) - { - o1->next_ = o2; - } - - template - static void destroy(Operation* o) - { - o->destroy(); - } - - template - static Operation*& front(op_queue& q) - { - return q.front_; - } - - template - static Operation*& back(op_queue& q) - { - return q.back_; - } -}; - -template -class op_queue - : private noncopyable -{ -public: - // Constructor. - op_queue() - : front_(0), - back_(0) - { - } - - // Destructor destroys all operations. - ~op_queue() - { - while (Operation* op = front_) - { - pop(); - op_queue_access::destroy(op); - } - } - - // Get the operation at the front of the queue. - Operation* front() - { - return front_; - } - - // Pop an operation from the front of the queue. - void pop() - { - if (front_) - { - Operation* tmp = front_; - front_ = op_queue_access::next(front_); - if (front_ == 0) - back_ = 0; - op_queue_access::next(tmp, static_cast(0)); - } - } - - // Push an operation on to the back of the queue. - void push(Operation* h) - { - op_queue_access::next(h, static_cast(0)); - if (back_) - { - op_queue_access::next(back_, h); - back_ = h; - } - else - { - front_ = back_ = h; - } - } - - // Push all operations from another queue on to the back of the queue. The - // source queue may contain operations of a derived type. - template - void push(op_queue& q) - { - if (Operation* other_front = op_queue_access::front(q)) - { - if (back_) - op_queue_access::next(back_, other_front); - else - front_ = other_front; - back_ = op_queue_access::back(q); - op_queue_access::front(q) = 0; - op_queue_access::back(q) = 0; - } - } - - // Whether the queue is empty. - bool empty() const - { - return front_ == 0; - } - - // Test whether an operation is already enqueued. - bool is_enqueued(Operation* o) const - { - return op_queue_access::next(o) != 0 || back_ == o; - } - -private: - friend class op_queue_access; - - // The front of the queue. - Operation* front_; - - // The back of the queue. - Operation* back_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_OP_QUEUE_HPP diff --git a/scout_sdk/asio/asio/detail/operation.hpp b/scout_sdk/asio/asio/detail/operation.hpp deleted file mode 100644 index 811e54d..0000000 --- a/scout_sdk/asio/asio/detail/operation.hpp +++ /dev/null @@ -1,38 +0,0 @@ -// -// detail/operation.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_OPERATION_HPP -#define ASIO_DETAIL_OPERATION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_operation.hpp" -#else -# include "asio/detail/scheduler_operation.hpp" -#endif - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_IOCP) -typedef win_iocp_operation operation; -#else -typedef scheduler_operation operation; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_OPERATION_HPP diff --git a/scout_sdk/asio/asio/detail/pipe_select_interrupter.hpp b/scout_sdk/asio/asio/detail/pipe_select_interrupter.hpp deleted file mode 100644 index 55d7db4..0000000 --- a/scout_sdk/asio/asio/detail/pipe_select_interrupter.hpp +++ /dev/null @@ -1,89 +0,0 @@ -// -// detail/pipe_select_interrupter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_PIPE_SELECT_INTERRUPTER_HPP -#define ASIO_DETAIL_PIPE_SELECT_INTERRUPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) -#if !defined(ASIO_WINDOWS_RUNTIME) -#if !defined(__CYGWIN__) -#if !defined(__SYMBIAN32__) -#if !defined(ASIO_HAS_EVENTFD) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class pipe_select_interrupter -{ -public: - // Constructor. - ASIO_DECL pipe_select_interrupter(); - - // Destructor. - ASIO_DECL ~pipe_select_interrupter(); - - // Recreate the interrupter's descriptors. Used after a fork. - ASIO_DECL void recreate(); - - // Interrupt the select call. - ASIO_DECL void interrupt(); - - // Reset the select interrupt. Returns true if the call was interrupted. - ASIO_DECL bool reset(); - - // Get the read descriptor to be passed to select. - int read_descriptor() const - { - return read_descriptor_; - } - -private: - // Open the descriptors. Throws on error. - ASIO_DECL void open_descriptors(); - - // Close the descriptors. - ASIO_DECL void close_descriptors(); - - // The read end of a connection used to interrupt the select call. This file - // descriptor is passed to select such that when it is time to stop, a single - // byte will be written on the other end of the connection and this - // descriptor will become readable. - int read_descriptor_; - - // The write end of a connection used to interrupt the select call. A single - // byte may be written to this to wake up the select which is waiting for the - // other end to become readable. - int write_descriptor_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/pipe_select_interrupter.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // !defined(ASIO_HAS_EVENTFD) -#endif // !defined(__SYMBIAN32__) -#endif // !defined(__CYGWIN__) -#endif // !defined(ASIO_WINDOWS_RUNTIME) -#endif // !defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_PIPE_SELECT_INTERRUPTER_HPP diff --git a/scout_sdk/asio/asio/detail/pop_options.hpp b/scout_sdk/asio/asio/detail/pop_options.hpp deleted file mode 100644 index 1045612..0000000 --- a/scout_sdk/asio/asio/detail/pop_options.hpp +++ /dev/null @@ -1,135 +0,0 @@ -// -// detail/pop_options.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -// No header guard - -#if defined(__COMO__) - -// Comeau C++ - -#elif defined(__DMC__) - -// Digital Mars C++ - -#elif defined(__INTEL_COMPILER) || defined(__ICL) \ - || defined(__ICC) || defined(__ECC) - -// Intel C++ - -# if (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) -# pragma GCC visibility pop -# endif // (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) - -#elif defined(__clang__) - -// Clang - -# if defined(__OBJC__) -# if !defined(__APPLE_CC__) || (__APPLE_CC__ <= 1) -# if defined(ASIO_OBJC_WORKAROUND) -# undef Protocol -# undef id -# undef ASIO_OBJC_WORKAROUND -# endif -# endif -# endif - -# if !defined(_WIN32) && !defined(__WIN32__) && !defined(WIN32) -# pragma GCC visibility pop -# endif // !defined(_WIN32) && !defined(__WIN32__) && !defined(WIN32) - -#elif defined(__GNUC__) - -// GNU C++ - -# if defined(__MINGW32__) || defined(__CYGWIN__) -# pragma pack (pop) -# endif - -# if defined(__OBJC__) -# if !defined(__APPLE_CC__) || (__APPLE_CC__ <= 1) -# if defined(ASIO_OBJC_WORKAROUND) -# undef Protocol -# undef id -# undef ASIO_OBJC_WORKAROUND -# endif -# endif -# endif - -# if (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) -# pragma GCC visibility pop -# endif // (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) - -# if (__GNUC__ >= 7) -# pragma GCC diagnostic pop -# endif // (__GNUC__ >= 7) - -#elif defined(__KCC) - -// Kai C++ - -#elif defined(__sgi) - -// SGI MIPSpro C++ - -#elif defined(__DECCXX) - -// Compaq Tru64 Unix cxx - -#elif defined(__ghs) - -// Greenhills C++ - -#elif defined(__BORLANDC__) - -// Borland C++ - -# pragma option pop -# pragma nopushoptwarn -# pragma nopackwarning - -#elif defined(__MWERKS__) - -// Metrowerks CodeWarrior - -#elif defined(__SUNPRO_CC) - -// Sun Workshop Compiler C++ - -#elif defined(__HP_aCC) - -// HP aCC - -#elif defined(__MRC__) || defined(__SC__) - -// MPW MrCpp or SCpp - -#elif defined(__IBMCPP__) - -// IBM Visual Age - -#elif defined(_MSC_VER) - -// Microsoft Visual C++ -// -// Must remain the last #elif since some other vendors (Metrowerks, for example) -// also #define _MSC_VER - -# pragma warning (pop) -# pragma pack (pop) - -# if defined(__cplusplus_cli) || defined(__cplusplus_winrt) -# if defined(ASIO_CLR_WORKAROUND) -# undef generic -# undef ASIO_CLR_WORKAROUND -# endif -# endif - -#endif diff --git a/scout_sdk/asio/asio/detail/posix_event.hpp b/scout_sdk/asio/asio/detail/posix_event.hpp deleted file mode 100644 index 121065e..0000000 --- a/scout_sdk/asio/asio/detail/posix_event.hpp +++ /dev/null @@ -1,162 +0,0 @@ -// -// detail/posix_event.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_EVENT_HPP -#define ASIO_DETAIL_POSIX_EVENT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include -#include "asio/detail/assert.hpp" -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class posix_event - : private noncopyable -{ -public: - // Constructor. - ASIO_DECL posix_event(); - - // Destructor. - ~posix_event() - { - ::pthread_cond_destroy(&cond_); - } - - // Signal the event. (Retained for backward compatibility.) - template - void signal(Lock& lock) - { - this->signal_all(lock); - } - - // Signal all waiters. - template - void signal_all(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - (void)lock; - state_ |= 1; - ::pthread_cond_broadcast(&cond_); // Ignore EINVAL. - } - - // Unlock the mutex and signal one waiter. - template - void unlock_and_signal_one(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - state_ |= 1; - bool have_waiters = (state_ > 1); - lock.unlock(); - if (have_waiters) - ::pthread_cond_signal(&cond_); // Ignore EINVAL. - } - - // If there's a waiter, unlock the mutex and signal it. - template - bool maybe_unlock_and_signal_one(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - state_ |= 1; - if (state_ > 1) - { - lock.unlock(); - ::pthread_cond_signal(&cond_); // Ignore EINVAL. - return true; - } - return false; - } - - // Reset the event. - template - void clear(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - (void)lock; - state_ &= ~std::size_t(1); - } - - // Wait for the event to become signalled. - template - void wait(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - while ((state_ & 1) == 0) - { - state_ += 2; - ::pthread_cond_wait(&cond_, &lock.mutex().mutex_); // Ignore EINVAL. - state_ -= 2; - } - } - - // Timed wait for the event to become signalled. - template - bool wait_for_usec(Lock& lock, long usec) - { - ASIO_ASSERT(lock.locked()); - if ((state_ & 1) == 0) - { - state_ += 2; - timespec ts; -#if (defined(__MACH__) && defined(__APPLE__)) \ - || (defined(__ANDROID__) && (__ANDROID_API__ < 21) \ - && defined(HAVE_PTHREAD_COND_TIMEDWAIT_RELATIVE)) - ts.tv_sec = usec / 1000000; - ts.tv_nsec = (usec % 1000000) * 1000; - ::pthread_cond_timedwait_relative_np( - &cond_, &lock.mutex().mutex_, &ts); // Ignore EINVAL. -#else // (defined(__MACH__) && defined(__APPLE__)) - // || (defined(__ANDROID__) && (__ANDROID_API__ < 21) - // && defined(HAVE_PTHREAD_COND_TIMEDWAIT_RELATIVE)) - if (::clock_gettime(CLOCK_MONOTONIC, &ts) == 0) - { - ts.tv_sec += usec / 1000000; - ts.tv_nsec = (usec % 1000000) * 1000; - ts.tv_sec += ts.tv_nsec / 1000000000; - ts.tv_nsec = ts.tv_nsec % 1000000000; - ::pthread_cond_timedwait(&cond_, - &lock.mutex().mutex_, &ts); // Ignore EINVAL. - } -#endif // (defined(__MACH__) && defined(__APPLE__)) - // || (defined(__ANDROID__) && (__ANDROID_API__ < 21) - // && defined(HAVE_PTHREAD_COND_TIMEDWAIT_RELATIVE)) - state_ -= 2; - } - return (state_ & 1) != 0; - } - -private: - ::pthread_cond_t cond_; - std::size_t state_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/posix_event.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_POSIX_EVENT_HPP diff --git a/scout_sdk/asio/asio/detail/posix_fd_set_adapter.hpp b/scout_sdk/asio/asio/detail/posix_fd_set_adapter.hpp deleted file mode 100644 index 95042d6..0000000 --- a/scout_sdk/asio/asio/detail/posix_fd_set_adapter.hpp +++ /dev/null @@ -1,118 +0,0 @@ -// -// detail/posix_fd_set_adapter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_FD_SET_ADAPTER_HPP -#define ASIO_DETAIL_POSIX_FD_SET_ADAPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) \ - && !defined(__CYGWIN__) \ - && !defined(ASIO_WINDOWS_RUNTIME) - -#include -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/reactor_op_queue.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Adapts the FD_SET type to meet the Descriptor_Set concept's requirements. -class posix_fd_set_adapter : noncopyable -{ -public: - posix_fd_set_adapter() - : max_descriptor_(invalid_socket) - { - using namespace std; // Needed for memset on Solaris. - FD_ZERO(&fd_set_); - } - - void reset() - { - using namespace std; // Needed for memset on Solaris. - FD_ZERO(&fd_set_); - } - - bool set(socket_type descriptor) - { - if (descriptor < (socket_type)FD_SETSIZE) - { - if (max_descriptor_ == invalid_socket || descriptor > max_descriptor_) - max_descriptor_ = descriptor; - FD_SET(descriptor, &fd_set_); - return true; - } - return false; - } - - void set(reactor_op_queue& operations, op_queue& ops) - { - reactor_op_queue::iterator i = operations.begin(); - while (i != operations.end()) - { - reactor_op_queue::iterator op_iter = i++; - if (!set(op_iter->first)) - { - asio::error_code ec(error::fd_set_failure); - operations.cancel_operations(op_iter, ops, ec); - } - } - } - - bool is_set(socket_type descriptor) const - { - return FD_ISSET(descriptor, &fd_set_) != 0; - } - - operator fd_set*() - { - return &fd_set_; - } - - socket_type max_descriptor() const - { - return max_descriptor_; - } - - void perform(reactor_op_queue& operations, - op_queue& ops) const - { - reactor_op_queue::iterator i = operations.begin(); - while (i != operations.end()) - { - reactor_op_queue::iterator op_iter = i++; - if (is_set(op_iter->first)) - operations.perform_operations(op_iter, ops); - } - } - -private: - mutable fd_set fd_set_; - socket_type max_descriptor_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS) - // && !defined(__CYGWIN__) - // && !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_POSIX_FD_SET_ADAPTER_HPP diff --git a/scout_sdk/asio/asio/detail/posix_global.hpp b/scout_sdk/asio/asio/detail/posix_global.hpp deleted file mode 100644 index 7ee0a71..0000000 --- a/scout_sdk/asio/asio/detail/posix_global.hpp +++ /dev/null @@ -1,80 +0,0 @@ -// -// detail/posix_global.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_GLOBAL_HPP -#define ASIO_DETAIL_POSIX_GLOBAL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct posix_global_impl -{ - // Helper function to perform initialisation. - static void do_init() - { - instance_.static_ptr_ = instance_.ptr_ = new T; - } - - // Destructor automatically cleans up the global. - ~posix_global_impl() - { - delete static_ptr_; - } - - static ::pthread_once_t init_once_; - static T* static_ptr_; - static posix_global_impl instance_; - T* ptr_; -}; - -template -::pthread_once_t posix_global_impl::init_once_ = PTHREAD_ONCE_INIT; - -template -T* posix_global_impl::static_ptr_ = 0; - -template -posix_global_impl posix_global_impl::instance_; - -template -T& posix_global() -{ - int result = ::pthread_once( - &posix_global_impl::init_once_, - &posix_global_impl::do_init); - - if (result != 0) - std::terminate(); - - return *posix_global_impl::instance_.ptr_; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_POSIX_GLOBAL_HPP diff --git a/scout_sdk/asio/asio/detail/posix_mutex.hpp b/scout_sdk/asio/asio/detail/posix_mutex.hpp deleted file mode 100644 index c0d9fc9..0000000 --- a/scout_sdk/asio/asio/detail/posix_mutex.hpp +++ /dev/null @@ -1,76 +0,0 @@ -// -// detail/posix_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_MUTEX_HPP -#define ASIO_DETAIL_POSIX_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class posix_event; - -class posix_mutex - : private noncopyable -{ -public: - typedef asio::detail::scoped_lock scoped_lock; - - // Constructor. - ASIO_DECL posix_mutex(); - - // Destructor. - ~posix_mutex() - { - ::pthread_mutex_destroy(&mutex_); // Ignore EBUSY. - } - - // Lock the mutex. - void lock() - { - (void)::pthread_mutex_lock(&mutex_); // Ignore EINVAL. - } - - // Unlock the mutex. - void unlock() - { - (void)::pthread_mutex_unlock(&mutex_); // Ignore EINVAL. - } - -private: - friend class posix_event; - ::pthread_mutex_t mutex_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/posix_mutex.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_POSIX_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/posix_signal_blocker.hpp b/scout_sdk/asio/asio/detail/posix_signal_blocker.hpp deleted file mode 100644 index fab5eb1..0000000 --- a/scout_sdk/asio/asio/detail/posix_signal_blocker.hpp +++ /dev/null @@ -1,85 +0,0 @@ -// -// detail/posix_signal_blocker.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_SIGNAL_BLOCKER_HPP -#define ASIO_DETAIL_POSIX_SIGNAL_BLOCKER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include -#include -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class posix_signal_blocker - : private noncopyable -{ -public: - // Constructor blocks all signals for the calling thread. - posix_signal_blocker() - : blocked_(false) - { - sigset_t new_mask; - sigfillset(&new_mask); - blocked_ = (pthread_sigmask(SIG_BLOCK, &new_mask, &old_mask_) == 0); - } - - // Destructor restores the previous signal mask. - ~posix_signal_blocker() - { - if (blocked_) - pthread_sigmask(SIG_SETMASK, &old_mask_, 0); - } - - // Block all signals for the calling thread. - void block() - { - if (!blocked_) - { - sigset_t new_mask; - sigfillset(&new_mask); - blocked_ = (pthread_sigmask(SIG_BLOCK, &new_mask, &old_mask_) == 0); - } - } - - // Restore the previous signal mask. - void unblock() - { - if (blocked_) - blocked_ = (pthread_sigmask(SIG_SETMASK, &old_mask_, 0) != 0); - } - -private: - // Have signals been blocked. - bool blocked_; - - // The previous signal mask. - sigset_t old_mask_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_POSIX_SIGNAL_BLOCKER_HPP diff --git a/scout_sdk/asio/asio/detail/posix_static_mutex.hpp b/scout_sdk/asio/asio/detail/posix_static_mutex.hpp deleted file mode 100644 index 59b86c1..0000000 --- a/scout_sdk/asio/asio/detail/posix_static_mutex.hpp +++ /dev/null @@ -1,64 +0,0 @@ -// -// detail/posix_static_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_STATIC_MUTEX_HPP -#define ASIO_DETAIL_POSIX_STATIC_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct posix_static_mutex -{ - typedef asio::detail::scoped_lock scoped_lock; - - // Initialise the mutex. - void init() - { - // Nothing to do. - } - - // Lock the mutex. - void lock() - { - (void)::pthread_mutex_lock(&mutex_); // Ignore EINVAL. - } - - // Unlock the mutex. - void unlock() - { - (void)::pthread_mutex_unlock(&mutex_); // Ignore EINVAL. - } - - ::pthread_mutex_t mutex_; -}; - -#define ASIO_POSIX_STATIC_MUTEX_INIT { PTHREAD_MUTEX_INITIALIZER } - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_POSIX_STATIC_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/posix_thread.hpp b/scout_sdk/asio/asio/detail/posix_thread.hpp deleted file mode 100644 index 1817af2..0000000 --- a/scout_sdk/asio/asio/detail/posix_thread.hpp +++ /dev/null @@ -1,109 +0,0 @@ -// -// detail/posix_thread.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_THREAD_HPP -#define ASIO_DETAIL_POSIX_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -extern "C" -{ - ASIO_DECL void* asio_detail_posix_thread_function(void* arg); -} - -class posix_thread - : private noncopyable -{ -public: - // Constructor. - template - posix_thread(Function f, unsigned int = 0) - : joined_(false) - { - start_thread(new func(f)); - } - - // Destructor. - ASIO_DECL ~posix_thread(); - - // Wait for the thread to exit. - ASIO_DECL void join(); - - // Get number of CPUs. - ASIO_DECL static std::size_t hardware_concurrency(); - -private: - friend void* asio_detail_posix_thread_function(void* arg); - - class func_base - { - public: - virtual ~func_base() {} - virtual void run() = 0; - }; - - struct auto_func_base_ptr - { - func_base* ptr; - ~auto_func_base_ptr() { delete ptr; } - }; - - template - class func - : public func_base - { - public: - func(Function f) - : f_(f) - { - } - - virtual void run() - { - f_(); - } - - private: - Function f_; - }; - - ASIO_DECL void start_thread(func_base* arg); - - ::pthread_t thread_; - bool joined_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/posix_thread.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_POSIX_THREAD_HPP diff --git a/scout_sdk/asio/asio/detail/posix_tss_ptr.hpp b/scout_sdk/asio/asio/detail/posix_tss_ptr.hpp deleted file mode 100644 index a3096b4..0000000 --- a/scout_sdk/asio/asio/detail/posix_tss_ptr.hpp +++ /dev/null @@ -1,79 +0,0 @@ -// -// detail/posix_tss_ptr.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_POSIX_TSS_PTR_HPP -#define ASIO_DETAIL_POSIX_TSS_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_PTHREADS) - -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Helper function to create thread-specific storage. -ASIO_DECL void posix_tss_ptr_create(pthread_key_t& key); - -template -class posix_tss_ptr - : private noncopyable -{ -public: - // Constructor. - posix_tss_ptr() - { - posix_tss_ptr_create(tss_key_); - } - - // Destructor. - ~posix_tss_ptr() - { - ::pthread_key_delete(tss_key_); - } - - // Get the value. - operator T*() const - { - return static_cast(::pthread_getspecific(tss_key_)); - } - - // Set the value. - void operator=(T* value) - { - ::pthread_setspecific(tss_key_, value); - } - -private: - // Thread-specific storage to allow unlocked access to determine whether a - // thread is a member of the pool. - pthread_key_t tss_key_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/posix_tss_ptr.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_PTHREADS) - -#endif // ASIO_DETAIL_POSIX_TSS_PTR_HPP diff --git a/scout_sdk/asio/asio/detail/push_options.hpp b/scout_sdk/asio/asio/detail/push_options.hpp deleted file mode 100644 index 0a3e979..0000000 --- a/scout_sdk/asio/asio/detail/push_options.hpp +++ /dev/null @@ -1,175 +0,0 @@ -// -// detail/push_options.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -// No header guard - -#if defined(__COMO__) - -// Comeau C++ - -#elif defined(__DMC__) - -// Digital Mars C++ - -#elif defined(__INTEL_COMPILER) || defined(__ICL) \ - || defined(__ICC) || defined(__ECC) - -// Intel C++ - -# if (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) -# pragma GCC visibility push (default) -# endif // (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) - -#elif defined(__clang__) - -// Clang - -# if defined(__OBJC__) -# if !defined(__APPLE_CC__) || (__APPLE_CC__ <= 1) -# if !defined(ASIO_DISABLE_OBJC_WORKAROUND) -# if !defined(Protocol) && !defined(id) -# define Protocol cpp_Protocol -# define id cpp_id -# define ASIO_OBJC_WORKAROUND -# endif -# endif -# endif -# endif - -# if !defined(_WIN32) && !defined(__WIN32__) && !defined(WIN32) -# pragma GCC visibility push (default) -# endif // !defined(_WIN32) && !defined(__WIN32__) && !defined(WIN32) - -#elif defined(__GNUC__) - -// GNU C++ - -# if defined(__MINGW32__) || defined(__CYGWIN__) -# pragma pack (push, 8) -# endif - -# if defined(__OBJC__) -# if !defined(__APPLE_CC__) || (__APPLE_CC__ <= 1) -# if !defined(ASIO_DISABLE_OBJC_WORKAROUND) -# if !defined(Protocol) && !defined(id) -# define Protocol cpp_Protocol -# define id cpp_id -# define ASIO_OBJC_WORKAROUND -# endif -# endif -# endif -# endif - -# if (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) -# pragma GCC visibility push (default) -# endif // (__GNUC__ == 4 && __GNUC_MINOR__ >= 1) || (__GNUC__ > 4) - -# if (__GNUC__ >= 7) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wimplicit-fallthrough" -# endif // (__GNUC__ >= 7) - -#elif defined(__KCC) - -// Kai C++ - -#elif defined(__sgi) - -// SGI MIPSpro C++ - -#elif defined(__DECCXX) - -// Compaq Tru64 Unix cxx - -#elif defined(__ghs) - -// Greenhills C++ - -#elif defined(__BORLANDC__) - -// Borland C++ - -# pragma option push -a8 -b -Ve- -Vx- -w-inl -vi- -# pragma nopushoptwarn -# pragma nopackwarning -# if !defined(__MT__) -# error Multithreaded RTL must be selected. -# endif // !defined(__MT__) - -#elif defined(__MWERKS__) - -// Metrowerks CodeWarrior - -#elif defined(__SUNPRO_CC) - -// Sun Workshop Compiler C++ - -#elif defined(__HP_aCC) - -// HP aCC - -#elif defined(__MRC__) || defined(__SC__) - -// MPW MrCpp or SCpp - -#elif defined(__IBMCPP__) - -// IBM Visual Age - -#elif defined(_MSC_VER) - -// Microsoft Visual C++ -// -// Must remain the last #elif since some other vendors (Metrowerks, for example) -// also #define _MSC_VER - -# pragma warning (disable:4103) -# pragma warning (push) -# pragma warning (disable:4127) -# pragma warning (disable:4180) -# pragma warning (disable:4244) -# pragma warning (disable:4355) -# pragma warning (disable:4510) -# pragma warning (disable:4512) -# pragma warning (disable:4610) -# pragma warning (disable:4675) -# if (_MSC_VER < 1600) -// Visual Studio 2008 generates spurious warnings about unused parameters. -# pragma warning (disable:4100) -# endif // (_MSC_VER < 1600) -# if defined(_M_IX86) && defined(_Wp64) -// The /Wp64 option is broken. If you want to check 64 bit portability, use a -// 64 bit compiler! -# pragma warning (disable:4311) -# pragma warning (disable:4312) -# endif // defined(_M_IX86) && defined(_Wp64) -# pragma pack (push, 8) -// Note that if the /Og optimisation flag is enabled with MSVC6, the compiler -// has a tendency to incorrectly optimise away some calls to member template -// functions, even though those functions contain code that should not be -// optimised away! Therefore we will always disable this optimisation option -// for the MSVC6 compiler. -# if (_MSC_VER < 1300) -# pragma optimize ("g", off) -# endif -# if !defined(_MT) -# error Multithreaded RTL must be selected. -# endif // !defined(_MT) - -# if defined(__cplusplus_cli) || defined(__cplusplus_winrt) -# if !defined(ASIO_DISABLE_CLR_WORKAROUND) -# if !defined(generic) -# define generic cpp_generic -# define ASIO_CLR_WORKAROUND -# endif -# endif -# endif - -#endif diff --git a/scout_sdk/asio/asio/detail/reactive_descriptor_service.hpp b/scout_sdk/asio/asio/detail/reactive_descriptor_service.hpp deleted file mode 100644 index e866863..0000000 --- a/scout_sdk/asio/asio/detail/reactive_descriptor_service.hpp +++ /dev/null @@ -1,388 +0,0 @@ -// -// detail/reactive_descriptor_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_DESCRIPTOR_SERVICE_HPP -#define ASIO_DETAIL_REACTIVE_DESCRIPTOR_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - -#include "asio/buffer.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/descriptor_ops.hpp" -#include "asio/detail/descriptor_read_op.hpp" -#include "asio/detail/descriptor_write_op.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/reactive_null_buffers_op.hpp" -#include "asio/detail/reactive_wait_op.hpp" -#include "asio/detail/reactor.hpp" -#include "asio/posix/descriptor_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class reactive_descriptor_service : - public service_base -{ -public: - // The native type of a descriptor. - typedef int native_handle_type; - - // The implementation type of the descriptor. - class implementation_type - : private asio::detail::noncopyable - { - public: - // Default constructor. - implementation_type() - : descriptor_(-1), - state_(0) - { - } - - private: - // Only this service will have access to the internal values. - friend class reactive_descriptor_service; - - // The native descriptor representation. - int descriptor_; - - // The current state of the descriptor. - descriptor_ops::state_type state_; - - // Per-descriptor data used by the reactor. - reactor::per_descriptor_data reactor_data_; - }; - - // Constructor. - ASIO_DECL reactive_descriptor_service( - asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Construct a new descriptor implementation. - ASIO_DECL void construct(implementation_type& impl); - - // Move-construct a new descriptor implementation. - ASIO_DECL void move_construct(implementation_type& impl, - implementation_type& other_impl); - - // Move-assign from another descriptor implementation. - ASIO_DECL void move_assign(implementation_type& impl, - reactive_descriptor_service& other_service, - implementation_type& other_impl); - - // Destroy a descriptor implementation. - ASIO_DECL void destroy(implementation_type& impl); - - // Assign a native descriptor to a descriptor implementation. - ASIO_DECL asio::error_code assign(implementation_type& impl, - const native_handle_type& native_descriptor, - asio::error_code& ec); - - // Determine whether the descriptor is open. - bool is_open(const implementation_type& impl) const - { - return impl.descriptor_ != -1; - } - - // Destroy a descriptor implementation. - ASIO_DECL asio::error_code close(implementation_type& impl, - asio::error_code& ec); - - // Get the native descriptor representation. - native_handle_type native_handle(const implementation_type& impl) const - { - return impl.descriptor_; - } - - // Release ownership of the native descriptor representation. - ASIO_DECL native_handle_type release(implementation_type& impl); - - // Cancel all operations associated with the descriptor. - ASIO_DECL asio::error_code cancel(implementation_type& impl, - asio::error_code& ec); - - // Perform an IO control command on the descriptor. - template - asio::error_code io_control(implementation_type& impl, - IO_Control_Command& command, asio::error_code& ec) - { - descriptor_ops::ioctl(impl.descriptor_, impl.state_, - command.name(), static_cast(command.data()), ec); - return ec; - } - - // Gets the non-blocking mode of the descriptor. - bool non_blocking(const implementation_type& impl) const - { - return (impl.state_ & descriptor_ops::user_set_non_blocking) != 0; - } - - // Sets the non-blocking mode of the descriptor. - asio::error_code non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - descriptor_ops::set_user_non_blocking( - impl.descriptor_, impl.state_, mode, ec); - return ec; - } - - // Gets the non-blocking mode of the native descriptor implementation. - bool native_non_blocking(const implementation_type& impl) const - { - return (impl.state_ & descriptor_ops::internal_non_blocking) != 0; - } - - // Sets the non-blocking mode of the native descriptor implementation. - asio::error_code native_non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - descriptor_ops::set_internal_non_blocking( - impl.descriptor_, impl.state_, mode, ec); - return ec; - } - - // Wait for the descriptor to become ready to read, ready to write, or to have - // pending error conditions. - asio::error_code wait(implementation_type& impl, - posix::descriptor_base::wait_type w, asio::error_code& ec) - { - switch (w) - { - case posix::descriptor_base::wait_read: - descriptor_ops::poll_read(impl.descriptor_, impl.state_, ec); - break; - case posix::descriptor_base::wait_write: - descriptor_ops::poll_write(impl.descriptor_, impl.state_, ec); - break; - case posix::descriptor_base::wait_error: - descriptor_ops::poll_error(impl.descriptor_, impl.state_, ec); - break; - default: - ec = asio::error::invalid_argument; - break; - } - - return ec; - } - - // Asynchronously wait for the descriptor to become ready to read, ready to - // write, or to have pending error conditions. - template - void async_wait(implementation_type& impl, - posix::descriptor_base::wait_type w, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_wait_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "descriptor", - &impl, impl.descriptor_, "async_wait")); - - int op_type; - switch (w) - { - case posix::descriptor_base::wait_read: - op_type = reactor::read_op; - break; - case posix::descriptor_base::wait_write: - op_type = reactor::write_op; - break; - case posix::descriptor_base::wait_error: - op_type = reactor::except_op; - break; - default: - p.p->ec_ = asio::error::invalid_argument; - reactor_.post_immediate_completion(p.p, is_continuation); - p.v = p.p = 0; - return; - } - - start_op(impl, op_type, p.p, is_continuation, false, false); - p.v = p.p = 0; - } - - // Write some data to the descriptor. - template - size_t write_some(implementation_type& impl, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return descriptor_ops::sync_write(impl.descriptor_, impl.state_, - bufs.buffers(), bufs.count(), bufs.all_empty(), ec); - } - - // Wait until data can be written without blocking. - size_t write_some(implementation_type& impl, - const null_buffers&, asio::error_code& ec) - { - // Wait for descriptor to become ready. - descriptor_ops::poll_write(impl.descriptor_, impl.state_, ec); - - return 0; - } - - // Start an asynchronous write. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_write_some(implementation_type& impl, - const ConstBufferSequence& buffers, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef descriptor_write_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.descriptor_, buffers, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "descriptor", - &impl, impl.descriptor_, "async_write_some")); - - start_op(impl, reactor::write_op, p.p, is_continuation, true, - buffer_sequence_adapter::all_empty(buffers)); - p.v = p.p = 0; - } - - // Start an asynchronous wait until data can be written without blocking. - template - void async_write_some(implementation_type& impl, - const null_buffers&, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "descriptor", - &impl, impl.descriptor_, "async_write_some(null_buffers)")); - - start_op(impl, reactor::write_op, p.p, is_continuation, false, false); - p.v = p.p = 0; - } - - // Read some data from the stream. Returns the number of bytes read. - template - size_t read_some(implementation_type& impl, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return descriptor_ops::sync_read(impl.descriptor_, impl.state_, - bufs.buffers(), bufs.count(), bufs.all_empty(), ec); - } - - // Wait until data can be read without blocking. - size_t read_some(implementation_type& impl, - const null_buffers&, asio::error_code& ec) - { - // Wait for descriptor to become ready. - descriptor_ops::poll_read(impl.descriptor_, impl.state_, ec); - - return 0; - } - - // Start an asynchronous read. The buffer for the data being read must be - // valid for the lifetime of the asynchronous operation. - template - void async_read_some(implementation_type& impl, - const MutableBufferSequence& buffers, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef descriptor_read_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.descriptor_, buffers, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "descriptor", - &impl, impl.descriptor_, "async_read_some")); - - start_op(impl, reactor::read_op, p.p, is_continuation, true, - buffer_sequence_adapter::all_empty(buffers)); - p.v = p.p = 0; - } - - // Wait until data can be read without blocking. - template - void async_read_some(implementation_type& impl, - const null_buffers&, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "descriptor", - &impl, impl.descriptor_, "async_read_some(null_buffers)")); - - start_op(impl, reactor::read_op, p.p, is_continuation, false, false); - p.v = p.p = 0; - } - -private: - // Start the asynchronous operation. - ASIO_DECL void start_op(implementation_type& impl, int op_type, - reactor_op* op, bool is_continuation, bool is_non_blocking, bool noop); - - // The selector that performs event demultiplexing for the service. - reactor& reactor_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/reactive_descriptor_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - -#endif // ASIO_DETAIL_REACTIVE_DESCRIPTOR_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_null_buffers_op.hpp b/scout_sdk/asio/asio/detail/reactive_null_buffers_op.hpp deleted file mode 100644 index 7408269..0000000 --- a/scout_sdk/asio/asio/detail/reactive_null_buffers_op.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// -// detail/reactive_null_buffers_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_NULL_BUFFERS_OP_HPP -#define ASIO_DETAIL_REACTIVE_NULL_BUFFERS_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_null_buffers_op : public reactor_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_null_buffers_op); - - reactive_null_buffers_op(Handler& handler) - : reactor_op(&reactive_null_buffers_op::do_perform, - &reactive_null_buffers_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static status do_perform(reactor_op*) - { - return done; - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_null_buffers_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_NULL_BUFFERS_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_serial_port_service.hpp b/scout_sdk/asio/asio/detail/reactive_serial_port_service.hpp deleted file mode 100644 index 6fddd9f..0000000 --- a/scout_sdk/asio/asio/detail/reactive_serial_port_service.hpp +++ /dev/null @@ -1,236 +0,0 @@ -// -// detail/reactive_serial_port_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SERIAL_PORT_SERVICE_HPP -#define ASIO_DETAIL_REACTIVE_SERIAL_PORT_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_SERIAL_PORT) -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#include -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/serial_port_base.hpp" -#include "asio/detail/descriptor_ops.hpp" -#include "asio/detail/reactive_descriptor_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Extend reactive_descriptor_service to provide serial port support. -class reactive_serial_port_service : - public service_base -{ -public: - // The native type of a serial port. - typedef reactive_descriptor_service::native_handle_type native_handle_type; - - // The implementation type of the serial port. - typedef reactive_descriptor_service::implementation_type implementation_type; - - ASIO_DECL reactive_serial_port_service( - asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Construct a new serial port implementation. - void construct(implementation_type& impl) - { - descriptor_service_.construct(impl); - } - - // Move-construct a new serial port implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - descriptor_service_.move_construct(impl, other_impl); - } - - // Move-assign from another serial port implementation. - void move_assign(implementation_type& impl, - reactive_serial_port_service& other_service, - implementation_type& other_impl) - { - descriptor_service_.move_assign(impl, - other_service.descriptor_service_, other_impl); - } - - // Destroy a serial port implementation. - void destroy(implementation_type& impl) - { - descriptor_service_.destroy(impl); - } - - // Open the serial port using the specified device name. - ASIO_DECL asio::error_code open(implementation_type& impl, - const std::string& device, asio::error_code& ec); - - // Assign a native descriptor to a serial port implementation. - asio::error_code assign(implementation_type& impl, - const native_handle_type& native_descriptor, - asio::error_code& ec) - { - return descriptor_service_.assign(impl, native_descriptor, ec); - } - - // Determine whether the serial port is open. - bool is_open(const implementation_type& impl) const - { - return descriptor_service_.is_open(impl); - } - - // Destroy a serial port implementation. - asio::error_code close(implementation_type& impl, - asio::error_code& ec) - { - return descriptor_service_.close(impl, ec); - } - - // Get the native serial port representation. - native_handle_type native_handle(implementation_type& impl) - { - return descriptor_service_.native_handle(impl); - } - - // Cancel all operations associated with the serial port. - asio::error_code cancel(implementation_type& impl, - asio::error_code& ec) - { - return descriptor_service_.cancel(impl, ec); - } - - // Set an option on the serial port. - template - asio::error_code set_option(implementation_type& impl, - const SettableSerialPortOption& option, asio::error_code& ec) - { - return do_set_option(impl, - &reactive_serial_port_service::store_option, - &option, ec); - } - - // Get an option from the serial port. - template - asio::error_code get_option(const implementation_type& impl, - GettableSerialPortOption& option, asio::error_code& ec) const - { - return do_get_option(impl, - &reactive_serial_port_service::load_option, - &option, ec); - } - - // Send a break sequence to the serial port. - asio::error_code send_break(implementation_type& impl, - asio::error_code& ec) - { - errno = 0; - descriptor_ops::error_wrapper(::tcsendbreak( - descriptor_service_.native_handle(impl), 0), ec); - return ec; - } - - // Write the given data. Returns the number of bytes sent. - template - size_t write_some(implementation_type& impl, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return descriptor_service_.write_some(impl, buffers, ec); - } - - // Start an asynchronous write. The data being written must be valid for the - // lifetime of the asynchronous operation. - template - void async_write_some(implementation_type& impl, - const ConstBufferSequence& buffers, Handler& handler) - { - descriptor_service_.async_write_some(impl, buffers, handler); - } - - // Read some data. Returns the number of bytes received. - template - size_t read_some(implementation_type& impl, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return descriptor_service_.read_some(impl, buffers, ec); - } - - // Start an asynchronous read. The buffer for the data being received must be - // valid for the lifetime of the asynchronous operation. - template - void async_read_some(implementation_type& impl, - const MutableBufferSequence& buffers, Handler& handler) - { - descriptor_service_.async_read_some(impl, buffers, handler); - } - -private: - // Function pointer type for storing a serial port option. - typedef asio::error_code (*store_function_type)( - const void*, termios&, asio::error_code&); - - // Helper function template to store a serial port option. - template - static asio::error_code store_option(const void* option, - termios& storage, asio::error_code& ec) - { - static_cast(option)->store(storage, ec); - return ec; - } - - // Helper function to set a serial port option. - ASIO_DECL asio::error_code do_set_option( - implementation_type& impl, store_function_type store, - const void* option, asio::error_code& ec); - - // Function pointer type for loading a serial port option. - typedef asio::error_code (*load_function_type)( - void*, const termios&, asio::error_code&); - - // Helper function template to load a serial port option. - template - static asio::error_code load_option(void* option, - const termios& storage, asio::error_code& ec) - { - static_cast(option)->load(storage, ec); - return ec; - } - - // Helper function to get a serial port option. - ASIO_DECL asio::error_code do_get_option( - const implementation_type& impl, load_function_type load, - void* option, asio::error_code& ec) const; - - // The implementation used for initiating asynchronous operations. - reactive_descriptor_service descriptor_service_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/reactive_serial_port_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) -#endif // defined(ASIO_HAS_SERIAL_PORT) - -#endif // ASIO_DETAIL_REACTIVE_SERIAL_PORT_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_accept_op.hpp b/scout_sdk/asio/asio/detail/reactive_socket_accept_op.hpp deleted file mode 100644 index 4a98f04..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_accept_op.hpp +++ /dev/null @@ -1,217 +0,0 @@ -// -// detail/reactive_socket_accept_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_ACCEPT_OP_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_ACCEPT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_holder.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_socket_accept_op_base : public reactor_op -{ -public: - reactive_socket_accept_op_base(socket_type socket, - socket_ops::state_type state, Socket& peer, const Protocol& protocol, - typename Protocol::endpoint* peer_endpoint, func_type complete_func) - : reactor_op(&reactive_socket_accept_op_base::do_perform, complete_func), - socket_(socket), - state_(state), - peer_(peer), - protocol_(protocol), - peer_endpoint_(peer_endpoint), - addrlen_(peer_endpoint ? peer_endpoint->capacity() : 0) - { - } - - static status do_perform(reactor_op* base) - { - reactive_socket_accept_op_base* o( - static_cast(base)); - - socket_type new_socket = invalid_socket; - status result = socket_ops::non_blocking_accept(o->socket_, - o->state_, o->peer_endpoint_ ? o->peer_endpoint_->data() : 0, - o->peer_endpoint_ ? &o->addrlen_ : 0, o->ec_, new_socket) - ? done : not_done; - o->new_socket_.reset(new_socket); - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_accept", o->ec_)); - - return result; - } - - void do_assign() - { - if (new_socket_.get() != invalid_socket) - { - if (peer_endpoint_) - peer_endpoint_->resize(addrlen_); - peer_.assign(protocol_, new_socket_.get(), ec_); - if (!ec_) - new_socket_.release(); - } - } - -private: - socket_type socket_; - socket_ops::state_type state_; - socket_holder new_socket_; - Socket& peer_; - Protocol protocol_; - typename Protocol::endpoint* peer_endpoint_; - std::size_t addrlen_; -}; - -template -class reactive_socket_accept_op : - public reactive_socket_accept_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_accept_op); - - reactive_socket_accept_op(socket_type socket, - socket_ops::state_type state, Socket& peer, const Protocol& protocol, - typename Protocol::endpoint* peer_endpoint, Handler& handler) - : reactive_socket_accept_op_base(socket, state, peer, - protocol, peer_endpoint, &reactive_socket_accept_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_accept_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - // On success, assign new connection to peer socket object. - if (owner) - o->do_assign(); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(o->handler_, o->ec_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -#if defined(ASIO_HAS_MOVE) - -template -class reactive_socket_move_accept_op : - private Protocol::socket, - public reactive_socket_accept_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_move_accept_op); - - reactive_socket_move_accept_op(io_context& ioc, socket_type socket, - socket_ops::state_type state, const Protocol& protocol, - typename Protocol::endpoint* peer_endpoint, Handler& handler) - : Protocol::socket(ioc), - reactive_socket_accept_op_base( - socket, state, *this, protocol, peer_endpoint, - &reactive_socket_move_accept_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_move_accept_op* o( - static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - // On success, assign new connection to peer socket object. - if (owner) - o->do_assign(); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::move_binder2 - handler(0, ASIO_MOVE_CAST(Handler)(o->handler_), o->ec_, - ASIO_MOVE_CAST(typename Protocol::socket)(*o)); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, "...")); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -#endif // defined(ASIO_HAS_MOVE) - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_ACCEPT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_connect_op.hpp b/scout_sdk/asio/asio/detail/reactive_socket_connect_op.hpp deleted file mode 100644 index 76164b2..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_connect_op.hpp +++ /dev/null @@ -1,113 +0,0 @@ -// -// detail/reactive_socket_connect_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_CONNECT_OP_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_CONNECT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class reactive_socket_connect_op_base : public reactor_op -{ -public: - reactive_socket_connect_op_base(socket_type socket, func_type complete_func) - : reactor_op(&reactive_socket_connect_op_base::do_perform, complete_func), - socket_(socket) - { - } - - static status do_perform(reactor_op* base) - { - reactive_socket_connect_op_base* o( - static_cast(base)); - - status result = socket_ops::non_blocking_connect( - o->socket_, o->ec_) ? done : not_done; - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_connect", o->ec_)); - - return result; - } - -private: - socket_type socket_; -}; - -template -class reactive_socket_connect_op : public reactive_socket_connect_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_connect_op); - - reactive_socket_connect_op(socket_type socket, Handler& handler) - : reactive_socket_connect_op_base(socket, - &reactive_socket_connect_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_connect_op* o - (static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(o->handler_, o->ec_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_CONNECT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_recv_op.hpp b/scout_sdk/asio/asio/detail/reactive_socket_recv_op.hpp deleted file mode 100644 index 04bd266..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_recv_op.hpp +++ /dev/null @@ -1,135 +0,0 @@ -// -// detail/reactive_socket_recv_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_RECV_OP_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_RECV_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_socket_recv_op_base : public reactor_op -{ -public: - reactive_socket_recv_op_base(socket_type socket, - socket_ops::state_type state, const MutableBufferSequence& buffers, - socket_base::message_flags flags, func_type complete_func) - : reactor_op(&reactive_socket_recv_op_base::do_perform, complete_func), - socket_(socket), - state_(state), - buffers_(buffers), - flags_(flags) - { - } - - static status do_perform(reactor_op* base) - { - reactive_socket_recv_op_base* o( - static_cast(base)); - - buffer_sequence_adapter bufs(o->buffers_); - - status result = socket_ops::non_blocking_recv(o->socket_, - bufs.buffers(), bufs.count(), o->flags_, - (o->state_ & socket_ops::stream_oriented) != 0, - o->ec_, o->bytes_transferred_) ? done : not_done; - - if (result == done) - if ((o->state_ & socket_ops::stream_oriented) != 0) - if (o->bytes_transferred_ == 0) - result = done_and_exhausted; - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_recv", - o->ec_, o->bytes_transferred_)); - - return result; - } - -private: - socket_type socket_; - socket_ops::state_type state_; - MutableBufferSequence buffers_; - socket_base::message_flags flags_; -}; - -template -class reactive_socket_recv_op : - public reactive_socket_recv_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_recv_op); - - reactive_socket_recv_op(socket_type socket, - socket_ops::state_type state, const MutableBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - : reactive_socket_recv_op_base(socket, state, - buffers, flags, &reactive_socket_recv_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_recv_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_RECV_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_recvfrom_op.hpp b/scout_sdk/asio/asio/detail/reactive_socket_recvfrom_op.hpp deleted file mode 100644 index 3d4fa4c..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_recvfrom_op.hpp +++ /dev/null @@ -1,138 +0,0 @@ -// -// detail/reactive_socket_recvfrom_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_RECVFROM_OP_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_RECVFROM_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_socket_recvfrom_op_base : public reactor_op -{ -public: - reactive_socket_recvfrom_op_base(socket_type socket, int protocol_type, - const MutableBufferSequence& buffers, Endpoint& endpoint, - socket_base::message_flags flags, func_type complete_func) - : reactor_op(&reactive_socket_recvfrom_op_base::do_perform, complete_func), - socket_(socket), - protocol_type_(protocol_type), - buffers_(buffers), - sender_endpoint_(endpoint), - flags_(flags) - { - } - - static status do_perform(reactor_op* base) - { - reactive_socket_recvfrom_op_base* o( - static_cast(base)); - - buffer_sequence_adapter bufs(o->buffers_); - - std::size_t addr_len = o->sender_endpoint_.capacity(); - status result = socket_ops::non_blocking_recvfrom(o->socket_, - bufs.buffers(), bufs.count(), o->flags_, - o->sender_endpoint_.data(), &addr_len, - o->ec_, o->bytes_transferred_) ? done : not_done; - - if (result && !o->ec_) - o->sender_endpoint_.resize(addr_len); - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_recvfrom", - o->ec_, o->bytes_transferred_)); - - return result; - } - -private: - socket_type socket_; - int protocol_type_; - MutableBufferSequence buffers_; - Endpoint& sender_endpoint_; - socket_base::message_flags flags_; -}; - -template -class reactive_socket_recvfrom_op : - public reactive_socket_recvfrom_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_recvfrom_op); - - reactive_socket_recvfrom_op(socket_type socket, int protocol_type, - const MutableBufferSequence& buffers, Endpoint& endpoint, - socket_base::message_flags flags, Handler& handler) - : reactive_socket_recvfrom_op_base( - socket, protocol_type, buffers, endpoint, flags, - &reactive_socket_recvfrom_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_recvfrom_op* o( - static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_RECVFROM_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_recvmsg_op.hpp b/scout_sdk/asio/asio/detail/reactive_socket_recvmsg_op.hpp deleted file mode 100644 index f473274..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_recvmsg_op.hpp +++ /dev/null @@ -1,132 +0,0 @@ -// -// detail/reactive_socket_recvmsg_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_RECVMSG_OP_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_RECVMSG_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/socket_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_socket_recvmsg_op_base : public reactor_op -{ -public: - reactive_socket_recvmsg_op_base(socket_type socket, - const MutableBufferSequence& buffers, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, func_type complete_func) - : reactor_op(&reactive_socket_recvmsg_op_base::do_perform, complete_func), - socket_(socket), - buffers_(buffers), - in_flags_(in_flags), - out_flags_(out_flags) - { - } - - static status do_perform(reactor_op* base) - { - reactive_socket_recvmsg_op_base* o( - static_cast(base)); - - buffer_sequence_adapter bufs(o->buffers_); - - status result = socket_ops::non_blocking_recvmsg(o->socket_, - bufs.buffers(), bufs.count(), - o->in_flags_, o->out_flags_, - o->ec_, o->bytes_transferred_) ? done : not_done; - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_recvmsg", - o->ec_, o->bytes_transferred_)); - - return result; - } - -private: - socket_type socket_; - MutableBufferSequence buffers_; - socket_base::message_flags in_flags_; - socket_base::message_flags& out_flags_; -}; - -template -class reactive_socket_recvmsg_op : - public reactive_socket_recvmsg_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_recvmsg_op); - - reactive_socket_recvmsg_op(socket_type socket, - const MutableBufferSequence& buffers, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, Handler& handler) - : reactive_socket_recvmsg_op_base(socket, buffers, - in_flags, out_flags, &reactive_socket_recvmsg_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_recvmsg_op* o( - static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_RECVMSG_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_send_op.hpp b/scout_sdk/asio/asio/detail/reactive_socket_send_op.hpp deleted file mode 100644 index bd550d9..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_send_op.hpp +++ /dev/null @@ -1,134 +0,0 @@ -// -// detail/reactive_socket_send_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_SEND_OP_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_SEND_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_socket_send_op_base : public reactor_op -{ -public: - reactive_socket_send_op_base(socket_type socket, - socket_ops::state_type state, const ConstBufferSequence& buffers, - socket_base::message_flags flags, func_type complete_func) - : reactor_op(&reactive_socket_send_op_base::do_perform, complete_func), - socket_(socket), - state_(state), - buffers_(buffers), - flags_(flags) - { - } - - static status do_perform(reactor_op* base) - { - reactive_socket_send_op_base* o( - static_cast(base)); - - buffer_sequence_adapter bufs(o->buffers_); - - status result = socket_ops::non_blocking_send(o->socket_, - bufs.buffers(), bufs.count(), o->flags_, - o->ec_, o->bytes_transferred_) ? done : not_done; - - if (result == done) - if ((o->state_ & socket_ops::stream_oriented) != 0) - if (o->bytes_transferred_ < bufs.total_size()) - result = done_and_exhausted; - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_send", - o->ec_, o->bytes_transferred_)); - - return result; - } - -private: - socket_type socket_; - socket_ops::state_type state_; - ConstBufferSequence buffers_; - socket_base::message_flags flags_; -}; - -template -class reactive_socket_send_op : - public reactive_socket_send_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_send_op); - - reactive_socket_send_op(socket_type socket, - socket_ops::state_type state, const ConstBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - : reactive_socket_send_op_base(socket, - state, buffers, flags, &reactive_socket_send_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_send_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_SEND_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_sendto_op.hpp b/scout_sdk/asio/asio/detail/reactive_socket_sendto_op.hpp deleted file mode 100644 index c97554d..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_sendto_op.hpp +++ /dev/null @@ -1,130 +0,0 @@ -// -// detail/reactive_socket_sendto_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_SENDTO_OP_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_SENDTO_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_socket_sendto_op_base : public reactor_op -{ -public: - reactive_socket_sendto_op_base(socket_type socket, - const ConstBufferSequence& buffers, const Endpoint& endpoint, - socket_base::message_flags flags, func_type complete_func) - : reactor_op(&reactive_socket_sendto_op_base::do_perform, complete_func), - socket_(socket), - buffers_(buffers), - destination_(endpoint), - flags_(flags) - { - } - - static status do_perform(reactor_op* base) - { - reactive_socket_sendto_op_base* o( - static_cast(base)); - - buffer_sequence_adapter bufs(o->buffers_); - - status result = socket_ops::non_blocking_sendto(o->socket_, - bufs.buffers(), bufs.count(), o->flags_, - o->destination_.data(), o->destination_.size(), - o->ec_, o->bytes_transferred_) ? done : not_done; - - ASIO_HANDLER_REACTOR_OPERATION((*o, "non_blocking_sendto", - o->ec_, o->bytes_transferred_)); - - return result; - } - -private: - socket_type socket_; - ConstBufferSequence buffers_; - Endpoint destination_; - socket_base::message_flags flags_; -}; - -template -class reactive_socket_sendto_op : - public reactive_socket_sendto_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_socket_sendto_op); - - reactive_socket_sendto_op(socket_type socket, - const ConstBufferSequence& buffers, const Endpoint& endpoint, - socket_base::message_flags flags, Handler& handler) - : reactive_socket_sendto_op_base(socket, - buffers, endpoint, flags, &reactive_socket_sendto_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_socket_sendto_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->bytes_transferred_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_SENDTO_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_service.hpp b/scout_sdk/asio/asio/detail/reactive_socket_service.hpp deleted file mode 100644 index 15a4fdb..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_service.hpp +++ /dev/null @@ -1,526 +0,0 @@ -// -// detail/reactive_socket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_SERVICE_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_IOCP) - -#include "asio/buffer.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/socket_base.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/reactive_null_buffers_op.hpp" -#include "asio/detail/reactive_socket_accept_op.hpp" -#include "asio/detail/reactive_socket_connect_op.hpp" -#include "asio/detail/reactive_socket_recvfrom_op.hpp" -#include "asio/detail/reactive_socket_sendto_op.hpp" -#include "asio/detail/reactive_socket_service_base.hpp" -#include "asio/detail/reactor.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_holder.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_socket_service : - public service_base >, - public reactive_socket_service_base -{ -public: - // The protocol type. - typedef Protocol protocol_type; - - // The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - // The native type of a socket. - typedef socket_type native_handle_type; - - // The implementation type of the socket. - struct implementation_type : - reactive_socket_service_base::base_implementation_type - { - // Default constructor. - implementation_type() - : protocol_(endpoint_type().protocol()) - { - } - - // The protocol associated with the socket. - protocol_type protocol_; - }; - - // Constructor. - reactive_socket_service(asio::io_context& io_context) - : service_base >(io_context), - reactive_socket_service_base(io_context) - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - this->base_shutdown(); - } - - // Move-construct a new socket implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - this->base_move_construct(impl, other_impl); - - impl.protocol_ = other_impl.protocol_; - other_impl.protocol_ = endpoint_type().protocol(); - } - - // Move-assign from another socket implementation. - void move_assign(implementation_type& impl, - reactive_socket_service_base& other_service, - implementation_type& other_impl) - { - this->base_move_assign(impl, other_service, other_impl); - - impl.protocol_ = other_impl.protocol_; - other_impl.protocol_ = endpoint_type().protocol(); - } - - // Move-construct a new socket implementation from another protocol type. - template - void converting_move_construct(implementation_type& impl, - reactive_socket_service&, - typename reactive_socket_service< - Protocol1>::implementation_type& other_impl) - { - this->base_move_construct(impl, other_impl); - - impl.protocol_ = protocol_type(other_impl.protocol_); - other_impl.protocol_ = typename Protocol1::endpoint().protocol(); - } - - // Open a new socket implementation. - asio::error_code open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - if (!do_open(impl, protocol.family(), - protocol.type(), protocol.protocol(), ec)) - impl.protocol_ = protocol; - return ec; - } - - // Assign a native socket to a socket implementation. - asio::error_code assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_socket, - asio::error_code& ec) - { - if (!do_assign(impl, protocol.type(), native_socket, ec)) - impl.protocol_ = protocol; - return ec; - } - - // Get the native socket representation. - native_handle_type native_handle(implementation_type& impl) - { - return impl.socket_; - } - - // Bind the socket to the specified local endpoint. - asio::error_code bind(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - socket_ops::bind(impl.socket_, endpoint.data(), endpoint.size(), ec); - return ec; - } - - // Set a socket option. - template - asio::error_code set_option(implementation_type& impl, - const Option& option, asio::error_code& ec) - { - socket_ops::setsockopt(impl.socket_, impl.state_, - option.level(impl.protocol_), option.name(impl.protocol_), - option.data(impl.protocol_), option.size(impl.protocol_), ec); - return ec; - } - - // Set a socket option. - template - asio::error_code get_option(const implementation_type& impl, - Option& option, asio::error_code& ec) const - { - std::size_t size = option.size(impl.protocol_); - socket_ops::getsockopt(impl.socket_, impl.state_, - option.level(impl.protocol_), option.name(impl.protocol_), - option.data(impl.protocol_), &size, ec); - if (!ec) - option.resize(impl.protocol_, size); - return ec; - } - - // Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - endpoint_type endpoint; - std::size_t addr_len = endpoint.capacity(); - if (socket_ops::getsockname(impl.socket_, endpoint.data(), &addr_len, ec)) - return endpoint_type(); - endpoint.resize(addr_len); - return endpoint; - } - - // Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - endpoint_type endpoint; - std::size_t addr_len = endpoint.capacity(); - if (socket_ops::getpeername(impl.socket_, - endpoint.data(), &addr_len, false, ec)) - return endpoint_type(); - endpoint.resize(addr_len); - return endpoint; - } - - // Disable sends or receives on the socket. - asio::error_code shutdown(base_implementation_type& impl, - socket_base::shutdown_type what, asio::error_code& ec) - { - socket_ops::shutdown(impl.socket_, what, ec); - return ec; - } - - // Send a datagram to the specified endpoint. Returns the number of bytes - // sent. - template - size_t send_to(implementation_type& impl, const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags, - asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_sendto(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), flags, - destination.data(), destination.size(), ec); - } - - // Wait until data can be sent without blocking. - size_t send_to(implementation_type& impl, const null_buffers&, - const endpoint_type&, socket_base::message_flags, - asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_write(impl.socket_, impl.state_, -1, ec); - - return 0; - } - - // Start an asynchronous send. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_send_to(implementation_type& impl, - const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags, - Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_sendto_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.socket_, buffers, destination, flags, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_send_to")); - - start_op(impl, reactor::write_op, p.p, is_continuation, true, false); - p.v = p.p = 0; - } - - // Start an asynchronous wait until data can be sent without blocking. - template - void async_send_to(implementation_type& impl, const null_buffers&, - const endpoint_type&, socket_base::message_flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_send_to(null_buffers)")); - - start_op(impl, reactor::write_op, p.p, is_continuation, false, false); - p.v = p.p = 0; - } - - // Receive a datagram with the endpoint of the sender. Returns the number of - // bytes received. - template - size_t receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags, - asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - std::size_t addr_len = sender_endpoint.capacity(); - std::size_t bytes_recvd = socket_ops::sync_recvfrom( - impl.socket_, impl.state_, bufs.buffers(), bufs.count(), - flags, sender_endpoint.data(), &addr_len, ec); - - if (!ec) - sender_endpoint.resize(addr_len); - - return bytes_recvd; - } - - // Wait until data can be received without blocking. - size_t receive_from(implementation_type& impl, const null_buffers&, - endpoint_type& sender_endpoint, socket_base::message_flags, - asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - - // Reset endpoint since it can be given no sensible value at this time. - sender_endpoint = endpoint_type(); - - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received and - // the sender_endpoint object must both be valid for the lifetime of the - // asynchronous operation. - template - void async_receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, endpoint_type& sender_endpoint, - socket_base::message_flags flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_recvfrom_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - int protocol = impl.protocol_.type(); - p.p = new (p.v) op(impl.socket_, protocol, - buffers, sender_endpoint, flags, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_receive_from")); - - start_op(impl, - (flags & socket_base::message_out_of_band) - ? reactor::except_op : reactor::read_op, - p.p, is_continuation, true, false); - p.v = p.p = 0; - } - - // Wait until data can be received without blocking. - template - void async_receive_from(implementation_type& impl, - const null_buffers&, endpoint_type& sender_endpoint, - socket_base::message_flags flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_receive_from(null_buffers)")); - - // Reset endpoint since it can be given no sensible value at this time. - sender_endpoint = endpoint_type(); - - start_op(impl, - (flags & socket_base::message_out_of_band) - ? reactor::except_op : reactor::read_op, - p.p, is_continuation, false, false); - p.v = p.p = 0; - } - - // Accept a new connection. - template - asio::error_code accept(implementation_type& impl, - Socket& peer, endpoint_type* peer_endpoint, asio::error_code& ec) - { - // We cannot accept a socket that is already open. - if (peer.is_open()) - { - ec = asio::error::already_open; - return ec; - } - - std::size_t addr_len = peer_endpoint ? peer_endpoint->capacity() : 0; - socket_holder new_socket(socket_ops::sync_accept(impl.socket_, - impl.state_, peer_endpoint ? peer_endpoint->data() : 0, - peer_endpoint ? &addr_len : 0, ec)); - - // On success, assign new connection to peer socket object. - if (new_socket.get() != invalid_socket) - { - if (peer_endpoint) - peer_endpoint->resize(addr_len); - peer.assign(impl.protocol_, new_socket.get(), ec); - if (!ec) - new_socket.release(); - } - - return ec; - } - -#if defined(ASIO_HAS_MOVE) - // Accept a new connection. - typename Protocol::socket accept(implementation_type& impl, - io_context* peer_io_context, endpoint_type* peer_endpoint, - asio::error_code& ec) - { - typename Protocol::socket peer( - peer_io_context ? *peer_io_context : io_context_); - - std::size_t addr_len = peer_endpoint ? peer_endpoint->capacity() : 0; - socket_holder new_socket(socket_ops::sync_accept(impl.socket_, - impl.state_, peer_endpoint ? peer_endpoint->data() : 0, - peer_endpoint ? &addr_len : 0, ec)); - - // On success, assign new connection to peer socket object. - if (new_socket.get() != invalid_socket) - { - if (peer_endpoint) - peer_endpoint->resize(addr_len); - peer.assign(impl.protocol_, new_socket.get(), ec); - if (!ec) - new_socket.release(); - } - - return peer; - } -#endif // defined(ASIO_HAS_MOVE) - - // Start an asynchronous accept. The peer and peer_endpoint objects must be - // valid until the accept's handler is invoked. - template - void async_accept(implementation_type& impl, Socket& peer, - endpoint_type* peer_endpoint, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_accept_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.socket_, impl.state_, peer, - impl.protocol_, peer_endpoint, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_accept")); - - start_accept_op(impl, p.p, is_continuation, peer.is_open()); - p.v = p.p = 0; - } - -#if defined(ASIO_HAS_MOVE) - // Start an asynchronous accept. The peer_endpoint object must be valid until - // the accept's handler is invoked. - template - void async_accept(implementation_type& impl, - asio::io_context* peer_io_context, - endpoint_type* peer_endpoint, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_move_accept_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(peer_io_context ? *peer_io_context : io_context_, - impl.socket_, impl.state_, impl.protocol_, peer_endpoint, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_accept")); - - start_accept_op(impl, p.p, is_continuation, false); - p.v = p.p = 0; - } -#endif // defined(ASIO_HAS_MOVE) - - // Connect the socket to the specified endpoint. - asio::error_code connect(implementation_type& impl, - const endpoint_type& peer_endpoint, asio::error_code& ec) - { - socket_ops::sync_connect(impl.socket_, - peer_endpoint.data(), peer_endpoint.size(), ec); - return ec; - } - - // Start an asynchronous connect. - template - void async_connect(implementation_type& impl, - const endpoint_type& peer_endpoint, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_connect_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.socket_, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_connect")); - - start_connect_op(impl, p.p, is_continuation, - peer_endpoint.data(), peer_endpoint.size()); - p.v = p.p = 0; - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_socket_service_base.hpp b/scout_sdk/asio/asio/detail/reactive_socket_service_base.hpp deleted file mode 100644 index ccd497e..0000000 --- a/scout_sdk/asio/asio/detail/reactive_socket_service_base.hpp +++ /dev/null @@ -1,511 +0,0 @@ -// -// detail/reactive_socket_service_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_SOCKET_SERVICE_BASE_HPP -#define ASIO_DETAIL_REACTIVE_SOCKET_SERVICE_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_IOCP) \ - && !defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/buffer.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/socket_base.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactive_null_buffers_op.hpp" -#include "asio/detail/reactive_socket_recv_op.hpp" -#include "asio/detail/reactive_socket_recvmsg_op.hpp" -#include "asio/detail/reactive_socket_send_op.hpp" -#include "asio/detail/reactive_wait_op.hpp" -#include "asio/detail/reactor.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_holder.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class reactive_socket_service_base -{ -public: - // The native type of a socket. - typedef socket_type native_handle_type; - - // The implementation type of the socket. - struct base_implementation_type - { - // The native socket representation. - socket_type socket_; - - // The current state of the socket. - socket_ops::state_type state_; - - // Per-descriptor data used by the reactor. - reactor::per_descriptor_data reactor_data_; - }; - - // Constructor. - ASIO_DECL reactive_socket_service_base( - asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void base_shutdown(); - - // Construct a new socket implementation. - ASIO_DECL void construct(base_implementation_type& impl); - - // Move-construct a new socket implementation. - ASIO_DECL void base_move_construct(base_implementation_type& impl, - base_implementation_type& other_impl); - - // Move-assign from another socket implementation. - ASIO_DECL void base_move_assign(base_implementation_type& impl, - reactive_socket_service_base& other_service, - base_implementation_type& other_impl); - - // Destroy a socket implementation. - ASIO_DECL void destroy(base_implementation_type& impl); - - // Determine whether the socket is open. - bool is_open(const base_implementation_type& impl) const - { - return impl.socket_ != invalid_socket; - } - - // Destroy a socket implementation. - ASIO_DECL asio::error_code close( - base_implementation_type& impl, asio::error_code& ec); - - // Release ownership of the socket. - ASIO_DECL socket_type release( - base_implementation_type& impl, asio::error_code& ec); - - // Get the native socket representation. - native_handle_type native_handle(base_implementation_type& impl) - { - return impl.socket_; - } - - // Cancel all operations associated with the socket. - ASIO_DECL asio::error_code cancel( - base_implementation_type& impl, asio::error_code& ec); - - // Determine whether the socket is at the out-of-band data mark. - bool at_mark(const base_implementation_type& impl, - asio::error_code& ec) const - { - return socket_ops::sockatmark(impl.socket_, ec); - } - - // Determine the number of bytes available for reading. - std::size_t available(const base_implementation_type& impl, - asio::error_code& ec) const - { - return socket_ops::available(impl.socket_, ec); - } - - // Place the socket into the state where it will listen for new connections. - asio::error_code listen(base_implementation_type& impl, - int backlog, asio::error_code& ec) - { - socket_ops::listen(impl.socket_, backlog, ec); - return ec; - } - - // Perform an IO control command on the socket. - template - asio::error_code io_control(base_implementation_type& impl, - IO_Control_Command& command, asio::error_code& ec) - { - socket_ops::ioctl(impl.socket_, impl.state_, command.name(), - static_cast(command.data()), ec); - return ec; - } - - // Gets the non-blocking mode of the socket. - bool non_blocking(const base_implementation_type& impl) const - { - return (impl.state_ & socket_ops::user_set_non_blocking) != 0; - } - - // Sets the non-blocking mode of the socket. - asio::error_code non_blocking(base_implementation_type& impl, - bool mode, asio::error_code& ec) - { - socket_ops::set_user_non_blocking(impl.socket_, impl.state_, mode, ec); - return ec; - } - - // Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const base_implementation_type& impl) const - { - return (impl.state_ & socket_ops::internal_non_blocking) != 0; - } - - // Sets the non-blocking mode of the native socket implementation. - asio::error_code native_non_blocking(base_implementation_type& impl, - bool mode, asio::error_code& ec) - { - socket_ops::set_internal_non_blocking(impl.socket_, impl.state_, mode, ec); - return ec; - } - - // Wait for the socket to become ready to read, ready to write, or to have - // pending error conditions. - asio::error_code wait(base_implementation_type& impl, - socket_base::wait_type w, asio::error_code& ec) - { - switch (w) - { - case socket_base::wait_read: - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - break; - case socket_base::wait_write: - socket_ops::poll_write(impl.socket_, impl.state_, -1, ec); - break; - case socket_base::wait_error: - socket_ops::poll_error(impl.socket_, impl.state_, -1, ec); - break; - default: - ec = asio::error::invalid_argument; - break; - } - - return ec; - } - - // Asynchronously wait for the socket to become ready to read, ready to - // write, or to have pending error conditions. - template - void async_wait(base_implementation_type& impl, - socket_base::wait_type w, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_wait_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_wait")); - - int op_type; - switch (w) - { - case socket_base::wait_read: - op_type = reactor::read_op; - break; - case socket_base::wait_write: - op_type = reactor::write_op; - break; - case socket_base::wait_error: - op_type = reactor::except_op; - break; - default: - p.p->ec_ = asio::error::invalid_argument; - reactor_.post_immediate_completion(p.p, is_continuation); - p.v = p.p = 0; - return; - } - - start_op(impl, op_type, p.p, is_continuation, false, false); - p.v = p.p = 0; - } - - // Send the given data to the peer. - template - size_t send(base_implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_send(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), flags, bufs.all_empty(), ec); - } - - // Wait until data can be sent without blocking. - size_t send(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_write(impl.socket_, impl.state_, -1, ec); - - return 0; - } - - // Start an asynchronous send. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_send(base_implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_send_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.socket_, impl.state_, buffers, flags, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_send")); - - start_op(impl, reactor::write_op, p.p, is_continuation, true, - ((impl.state_ & socket_ops::stream_oriented) - && buffer_sequence_adapter::all_empty(buffers))); - p.v = p.p = 0; - } - - // Start an asynchronous wait until data can be sent without blocking. - template - void async_send(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_send(null_buffers)")); - - start_op(impl, reactor::write_op, p.p, is_continuation, false, false); - p.v = p.p = 0; - } - - // Receive some data from the peer. Returns the number of bytes received. - template - size_t receive(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_recv(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), flags, bufs.all_empty(), ec); - } - - // Wait until data can be received without blocking. - size_t receive(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received - // must be valid for the lifetime of the asynchronous operation. - template - void async_receive(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_recv_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.socket_, impl.state_, buffers, flags, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_receive")); - - start_op(impl, - (flags & socket_base::message_out_of_band) - ? reactor::except_op : reactor::read_op, - p.p, is_continuation, - (flags & socket_base::message_out_of_band) == 0, - ((impl.state_ & socket_ops::stream_oriented) - && buffer_sequence_adapter::all_empty(buffers))); - p.v = p.p = 0; - } - - // Wait until data can be received without blocking. - template - void async_receive(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_receive(null_buffers)")); - - start_op(impl, - (flags & socket_base::message_out_of_band) - ? reactor::except_op : reactor::read_op, - p.p, is_continuation, false, false); - p.v = p.p = 0; - } - - // Receive some data with associated flags. Returns the number of bytes - // received. - template - size_t receive_with_flags(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_recvmsg(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), in_flags, out_flags, ec); - } - - // Wait until data can be received without blocking. - size_t receive_with_flags(base_implementation_type& impl, - const null_buffers&, socket_base::message_flags, - socket_base::message_flags& out_flags, asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - - // Clear out_flags, since we cannot give it any other sensible value when - // performing a null_buffers operation. - out_flags = 0; - - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received - // must be valid for the lifetime of the asynchronous operation. - template - void async_receive_with_flags(base_implementation_type& impl, - const MutableBufferSequence& buffers, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_socket_recvmsg_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.socket_, buffers, in_flags, out_flags, handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_receive_with_flags")); - - start_op(impl, - (in_flags & socket_base::message_out_of_band) - ? reactor::except_op : reactor::read_op, - p.p, is_continuation, - (in_flags & socket_base::message_out_of_band) == 0, false); - p.v = p.p = 0; - } - - // Wait until data can be received without blocking. - template - void async_receive_with_flags(base_implementation_type& impl, - const null_buffers&, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef reactive_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((reactor_.context(), *p.p, "socket", - &impl, impl.socket_, "async_receive_with_flags(null_buffers)")); - - // Clear out_flags, since we cannot give it any other sensible value when - // performing a null_buffers operation. - out_flags = 0; - - start_op(impl, - (in_flags & socket_base::message_out_of_band) - ? reactor::except_op : reactor::read_op, - p.p, is_continuation, false, false); - p.v = p.p = 0; - } - -protected: - // Open a new socket implementation. - ASIO_DECL asio::error_code do_open( - base_implementation_type& impl, int af, - int type, int protocol, asio::error_code& ec); - - // Assign a native socket to a socket implementation. - ASIO_DECL asio::error_code do_assign( - base_implementation_type& impl, int type, - const native_handle_type& native_socket, asio::error_code& ec); - - // Start the asynchronous read or write operation. - ASIO_DECL void start_op(base_implementation_type& impl, int op_type, - reactor_op* op, bool is_continuation, bool is_non_blocking, bool noop); - - // Start the asynchronous accept operation. - ASIO_DECL void start_accept_op(base_implementation_type& impl, - reactor_op* op, bool is_continuation, bool peer_is_open); - - // Start the asynchronous connect operation. - ASIO_DECL void start_connect_op(base_implementation_type& impl, - reactor_op* op, bool is_continuation, - const socket_addr_type* addr, size_t addrlen); - - // The io_context that owns this socket service. - io_context& io_context_; - - // The selector that performs event demultiplexing for the service. - reactor& reactor_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/reactive_socket_service_base.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // !defined(ASIO_HAS_IOCP) - // && !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_REACTIVE_SOCKET_SERVICE_BASE_HPP diff --git a/scout_sdk/asio/asio/detail/reactive_wait_op.hpp b/scout_sdk/asio/asio/detail/reactive_wait_op.hpp deleted file mode 100644 index 616d8b1..0000000 --- a/scout_sdk/asio/asio/detail/reactive_wait_op.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// -// detail/reactive_wait_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTIVE_WAIT_OP_HPP -#define ASIO_DETAIL_REACTIVE_WAIT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactive_wait_op : public reactor_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(reactive_wait_op); - - reactive_wait_op(Handler& handler) - : reactor_op(&reactive_wait_op::do_perform, - &reactive_wait_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static status do_perform(reactor_op*) - { - return done; - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - reactive_wait_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(o->handler_, o->ec_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTIVE_WAIT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactor.hpp b/scout_sdk/asio/asio/detail/reactor.hpp deleted file mode 100644 index 4750276..0000000 --- a/scout_sdk/asio/asio/detail/reactor.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// -// detail/reactor.hpp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTOR_HPP -#define ASIO_DETAIL_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/reactor_fwd.hpp" - -#if defined(ASIO_HAS_EPOLL) -# include "asio/detail/epoll_reactor.hpp" -#elif defined(ASIO_HAS_KQUEUE) -# include "asio/detail/kqueue_reactor.hpp" -#elif defined(ASIO_HAS_DEV_POLL) -# include "asio/detail/dev_poll_reactor.hpp" -#elif defined(ASIO_HAS_IOCP) || defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/null_reactor.hpp" -#else -# include "asio/detail/select_reactor.hpp" -#endif - -#endif // ASIO_DETAIL_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/reactor_fwd.hpp b/scout_sdk/asio/asio/detail/reactor_fwd.hpp deleted file mode 100644 index a4555c3..0000000 --- a/scout_sdk/asio/asio/detail/reactor_fwd.hpp +++ /dev/null @@ -1,40 +0,0 @@ -// -// detail/reactor_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTOR_FWD_HPP -#define ASIO_DETAIL_REACTOR_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_IOCP) || defined(ASIO_WINDOWS_RUNTIME) -typedef class null_reactor reactor; -#elif defined(ASIO_HAS_IOCP) -typedef class select_reactor reactor; -#elif defined(ASIO_HAS_EPOLL) -typedef class epoll_reactor reactor; -#elif defined(ASIO_HAS_KQUEUE) -typedef class kqueue_reactor reactor; -#elif defined(ASIO_HAS_DEV_POLL) -typedef class dev_poll_reactor reactor; -#else -typedef class select_reactor reactor; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_REACTOR_FWD_HPP diff --git a/scout_sdk/asio/asio/detail/reactor_op.hpp b/scout_sdk/asio/asio/detail/reactor_op.hpp deleted file mode 100644 index faad1a7..0000000 --- a/scout_sdk/asio/asio/detail/reactor_op.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// -// detail/reactor_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTOR_OP_HPP -#define ASIO_DETAIL_REACTOR_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class reactor_op - : public operation -{ -public: - // The error code to be passed to the completion handler. - asio::error_code ec_; - - // The number of bytes transferred, to be passed to the completion handler. - std::size_t bytes_transferred_; - - // Status returned by perform function. May be used to decide whether it is - // worth performing more operations on the descriptor immediately. - enum status { not_done, done, done_and_exhausted }; - - // Perform the operation. Returns true if it is finished. - status perform() - { - return perform_func_(this); - } - -protected: - typedef status (*perform_func_type)(reactor_op*); - - reactor_op(perform_func_type perform_func, func_type complete_func) - : operation(complete_func), - bytes_transferred_(0), - perform_func_(perform_func) - { - } - -private: - perform_func_type perform_func_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTOR_OP_HPP diff --git a/scout_sdk/asio/asio/detail/reactor_op_queue.hpp b/scout_sdk/asio/asio/detail/reactor_op_queue.hpp deleted file mode 100644 index 898f31d..0000000 --- a/scout_sdk/asio/asio/detail/reactor_op_queue.hpp +++ /dev/null @@ -1,168 +0,0 @@ -// -// detail/reactor_op_queue.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REACTOR_OP_QUEUE_HPP -#define ASIO_DETAIL_REACTOR_OP_QUEUE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/hash_map.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class reactor_op_queue - : private noncopyable -{ -public: - typedef Descriptor key_type; - - struct mapped_type : op_queue - { - mapped_type() {} - mapped_type(const mapped_type&) {} - void operator=(const mapped_type&) {} - }; - - typedef typename hash_map::value_type value_type; - typedef typename hash_map::iterator iterator; - - // Constructor. - reactor_op_queue() - : operations_() - { - } - - // Obtain iterators to all registered descriptors. - iterator begin() { return operations_.begin(); } - iterator end() { return operations_.end(); } - - // Add a new operation to the queue. Returns true if this is the only - // operation for the given descriptor, in which case the reactor's event - // demultiplexing function call may need to be interrupted and restarted. - bool enqueue_operation(Descriptor descriptor, reactor_op* op) - { - std::pair entry = - operations_.insert(value_type(descriptor, mapped_type())); - entry.first->second.push(op); - return entry.second; - } - - // Cancel all operations associated with the descriptor identified by the - // supplied iterator. Any operations pending for the descriptor will be - // cancelled. Returns true if any operations were cancelled, in which case - // the reactor's event demultiplexing function may need to be interrupted and - // restarted. - bool cancel_operations(iterator i, op_queue& ops, - const asio::error_code& ec = - asio::error::operation_aborted) - { - if (i != operations_.end()) - { - while (reactor_op* op = i->second.front()) - { - op->ec_ = ec; - i->second.pop(); - ops.push(op); - } - operations_.erase(i); - return true; - } - - return false; - } - - // Cancel all operations associated with the descriptor. Any operations - // pending for the descriptor will be cancelled. Returns true if any - // operations were cancelled, in which case the reactor's event - // demultiplexing function may need to be interrupted and restarted. - bool cancel_operations(Descriptor descriptor, op_queue& ops, - const asio::error_code& ec = - asio::error::operation_aborted) - { - return this->cancel_operations(operations_.find(descriptor), ops, ec); - } - - // Whether there are no operations in the queue. - bool empty() const - { - return operations_.empty(); - } - - // Determine whether there are any operations associated with the descriptor. - bool has_operation(Descriptor descriptor) const - { - return operations_.find(descriptor) != operations_.end(); - } - - // Perform the operations corresponding to the descriptor identified by the - // supplied iterator. Returns true if there are still unfinished operations - // queued for the descriptor. - bool perform_operations(iterator i, op_queue& ops) - { - if (i != operations_.end()) - { - while (reactor_op* op = i->second.front()) - { - if (op->perform()) - { - i->second.pop(); - ops.push(op); - } - else - { - return true; - } - } - operations_.erase(i); - } - return false; - } - - // Perform the operations corresponding to the descriptor. Returns true if - // there are still unfinished operations queued for the descriptor. - bool perform_operations(Descriptor descriptor, op_queue& ops) - { - return this->perform_operations(operations_.find(descriptor), ops); - } - - // Get all operations owned by the queue. - void get_all_operations(op_queue& ops) - { - iterator i = operations_.begin(); - while (i != operations_.end()) - { - iterator op_iter = i++; - ops.push(op_iter->second); - operations_.erase(op_iter); - } - } - -private: - // The operations that are currently executing asynchronously. - hash_map operations_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_REACTOR_OP_QUEUE_HPP diff --git a/scout_sdk/asio/asio/detail/recycling_allocator.hpp b/scout_sdk/asio/asio/detail/recycling_allocator.hpp deleted file mode 100644 index 964af1d..0000000 --- a/scout_sdk/asio/asio/detail/recycling_allocator.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// -// detail/recycling_allocator.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_RECYCLING_ALLOCATOR_HPP -#define ASIO_DETAIL_RECYCLING_ALLOCATOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/thread_context.hpp" -#include "asio/detail/thread_info_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class recycling_allocator -{ -public: - typedef T value_type; - - template - struct rebind - { - typedef recycling_allocator other; - }; - - recycling_allocator() - { - } - - template - recycling_allocator(const recycling_allocator&) - { - } - - T* allocate(std::size_t n) - { - typedef thread_context::thread_call_stack call_stack; - void* p = thread_info_base::allocate(call_stack::top(), sizeof(T) * n); - return static_cast(p); - } - - void deallocate(T* p, std::size_t n) - { - typedef thread_context::thread_call_stack call_stack; - thread_info_base::deallocate(call_stack::top(), p, sizeof(T) * n); - } -}; - -template <> -class recycling_allocator -{ -public: - typedef void value_type; - - template - struct rebind - { - typedef recycling_allocator other; - }; - - recycling_allocator() - { - } - - template - recycling_allocator(const recycling_allocator&) - { - } -}; - -template -struct get_recycling_allocator -{ - typedef Allocator type; - static type get(const Allocator& a) { return a; } -}; - -template -struct get_recycling_allocator > -{ - typedef recycling_allocator type; - static type get(const std::allocator&) { return type(); } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_RECYCLING_ALLOCATOR_HPP diff --git a/scout_sdk/asio/asio/detail/regex_fwd.hpp b/scout_sdk/asio/asio/detail/regex_fwd.hpp deleted file mode 100644 index dcf7d06..0000000 --- a/scout_sdk/asio/asio/detail/regex_fwd.hpp +++ /dev/null @@ -1,35 +0,0 @@ -// -// detail/regex_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_REGEX_FWD_HPP -#define ASIO_DETAIL_REGEX_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if defined(ASIO_HAS_BOOST_REGEX) - -#include -#include - -namespace boost { - -template -struct sub_match; - -template -class match_results; - -} // namespace boost - -#endif // defined(ASIO_HAS_BOOST_REGEX) - -#endif // ASIO_DETAIL_REGEX_FWD_HPP diff --git a/scout_sdk/asio/asio/detail/resolve_endpoint_op.hpp b/scout_sdk/asio/asio/detail/resolve_endpoint_op.hpp deleted file mode 100644 index 8eee2f9..0000000 --- a/scout_sdk/asio/asio/detail/resolve_endpoint_op.hpp +++ /dev/null @@ -1,122 +0,0 @@ -// -// detail/resolve_endpoint_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_RESOLVER_ENDPOINT_OP_HPP -#define ASIO_DETAIL_RESOLVER_ENDPOINT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/ip/basic_resolver_results.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/resolve_op.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class resolve_endpoint_op : public resolve_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(resolve_endpoint_op); - - typedef typename Protocol::endpoint endpoint_type; - typedef asio::ip::basic_resolver_results results_type; - - resolve_endpoint_op(socket_ops::weak_cancel_token_type cancel_token, - const endpoint_type& endpoint, io_context_impl& ioc, Handler& handler) - : resolve_op(&resolve_endpoint_op::do_complete), - cancel_token_(cancel_token), - endpoint_(endpoint), - io_context_impl_(ioc), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the operation object. - resolve_endpoint_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - if (owner && owner != &o->io_context_impl_) - { - // The operation is being run on the worker io_context. Time to perform - // the resolver operation. - - // Perform the blocking endpoint resolution operation. - char host_name[NI_MAXHOST]; - char service_name[NI_MAXSERV]; - socket_ops::background_getnameinfo(o->cancel_token_, o->endpoint_.data(), - o->endpoint_.size(), host_name, NI_MAXHOST, service_name, NI_MAXSERV, - o->endpoint_.protocol().type(), o->ec_); - o->results_ = results_type::create(o->endpoint_, host_name, service_name); - - // Pass operation back to main io_context for completion. - o->io_context_impl_.post_deferred_completion(o); - p.v = p.p = 0; - } - else - { - // The operation has been returned to the main io_context. The completion - // handler is ready to be delivered. - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated - // before the upcall is made. Even if we're not about to make an upcall, - // a sub-object of the handler may be the true owner of the memory - // associated with the handler. Consequently, a local copy of the handler - // is required to ensure that any owning sub-object remains valid until - // after we have deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->results_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, "...")); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - } - -private: - socket_ops::weak_cancel_token_type cancel_token_; - endpoint_type endpoint_; - io_context_impl& io_context_impl_; - Handler handler_; - results_type results_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_RESOLVER_ENDPOINT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/resolve_op.hpp b/scout_sdk/asio/asio/detail/resolve_op.hpp deleted file mode 100644 index a528aa8..0000000 --- a/scout_sdk/asio/asio/detail/resolve_op.hpp +++ /dev/null @@ -1,45 +0,0 @@ -// -// detail/resolve_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_RESOLVE_OP_HPP -#define ASIO_DETAIL_RESOLVE_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/error.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class resolve_op : public operation -{ -public: - // The error code to be passed to the completion handler. - asio::error_code ec_; - -protected: - resolve_op(func_type complete_func) - : operation(complete_func) - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_RESOLVE_OP_HPP diff --git a/scout_sdk/asio/asio/detail/resolve_query_op.hpp b/scout_sdk/asio/asio/detail/resolve_query_op.hpp deleted file mode 100644 index 0ec5a32..0000000 --- a/scout_sdk/asio/asio/detail/resolve_query_op.hpp +++ /dev/null @@ -1,134 +0,0 @@ -// -// detail/resolve_query_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_RESOLVE_QUERY_OP_HPP -#define ASIO_DETAIL_RESOLVE_QUERY_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/ip/basic_resolver_query.hpp" -#include "asio/ip/basic_resolver_results.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/resolve_op.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class resolve_query_op : public resolve_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(resolve_query_op); - - typedef asio::ip::basic_resolver_query query_type; - typedef asio::ip::basic_resolver_results results_type; - - resolve_query_op(socket_ops::weak_cancel_token_type cancel_token, - const query_type& query, io_context_impl& ioc, Handler& handler) - : resolve_op(&resolve_query_op::do_complete), - cancel_token_(cancel_token), - query_(query), - io_context_impl_(ioc), - handler_(ASIO_MOVE_CAST(Handler)(handler)), - addrinfo_(0) - { - handler_work::start(handler_); - } - - ~resolve_query_op() - { - if (addrinfo_) - socket_ops::freeaddrinfo(addrinfo_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the operation object. - resolve_query_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - - if (owner && owner != &o->io_context_impl_) - { - // The operation is being run on the worker io_context. Time to perform - // the resolver operation. - - // Perform the blocking host resolution operation. - socket_ops::background_getaddrinfo(o->cancel_token_, - o->query_.host_name().c_str(), o->query_.service_name().c_str(), - o->query_.hints(), &o->addrinfo_, o->ec_); - - // Pass operation back to main io_context for completion. - o->io_context_impl_.post_deferred_completion(o); - p.v = p.p = 0; - } - else - { - // The operation has been returned to the main io_context. The completion - // handler is ready to be delivered. - - // Take ownership of the operation's outstanding work. - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated - // before the upcall is made. Even if we're not about to make an upcall, - // a sub-object of the handler may be the true owner of the memory - // associated with the handler. Consequently, a local copy of the handler - // is required to ensure that any owning sub-object remains valid until - // after we have deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, results_type()); - p.h = asio::detail::addressof(handler.handler_); - if (o->addrinfo_) - { - handler.arg2_ = results_type::create(o->addrinfo_, - o->query_.host_name(), o->query_.service_name()); - } - p.reset(); - - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, "...")); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - } - -private: - socket_ops::weak_cancel_token_type cancel_token_; - query_type query_; - io_context_impl& io_context_impl_; - Handler handler_; - asio::detail::addrinfo_type* addrinfo_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_RESOLVE_QUERY_OP_HPP diff --git a/scout_sdk/asio/asio/detail/resolver_service.hpp b/scout_sdk/asio/asio/detail/resolver_service.hpp deleted file mode 100644 index 11a94d1..0000000 --- a/scout_sdk/asio/asio/detail/resolver_service.hpp +++ /dev/null @@ -1,145 +0,0 @@ -// -// detail/resolver_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_RESOLVER_SERVICE_HPP -#define ASIO_DETAIL_RESOLVER_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/ip/basic_resolver_query.hpp" -#include "asio/ip/basic_resolver_results.hpp" -#include "asio/detail/concurrency_hint.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/resolve_endpoint_op.hpp" -#include "asio/detail/resolve_query_op.hpp" -#include "asio/detail/resolver_service_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class resolver_service : - public service_base >, - public resolver_service_base -{ -public: - // The implementation type of the resolver. A cancellation token is used to - // indicate to the background thread that the operation has been cancelled. - typedef socket_ops::shared_cancel_token_type implementation_type; - - // The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - // The query type. - typedef asio::ip::basic_resolver_query query_type; - - // The results type. - typedef asio::ip::basic_resolver_results results_type; - - // Constructor. - resolver_service(asio::io_context& io_context) - : service_base >(io_context), - resolver_service_base(io_context) - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - this->base_shutdown(); - } - - // Perform any fork-related housekeeping. - void notify_fork(asio::io_context::fork_event fork_ev) - { - this->base_notify_fork(fork_ev); - } - - // Resolve a query to a list of entries. - results_type resolve(implementation_type&, const query_type& query, - asio::error_code& ec) - { - asio::detail::addrinfo_type* address_info = 0; - - socket_ops::getaddrinfo(query.host_name().c_str(), - query.service_name().c_str(), query.hints(), &address_info, ec); - auto_addrinfo auto_address_info(address_info); - - return ec ? results_type() : results_type::create( - address_info, query.host_name(), query.service_name()); - } - - // Asynchronously resolve a query to a list of entries. - template - void async_resolve(implementation_type& impl, - const query_type& query, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef resolve_query_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl, query, io_context_impl_, handler); - - ASIO_HANDLER_CREATION((io_context_impl_.context(), - *p.p, "resolver", &impl, 0, "async_resolve")); - - start_resolve_op(p.p); - p.v = p.p = 0; - } - - // Resolve an endpoint to a list of entries. - results_type resolve(implementation_type&, - const endpoint_type& endpoint, asio::error_code& ec) - { - char host_name[NI_MAXHOST]; - char service_name[NI_MAXSERV]; - socket_ops::sync_getnameinfo(endpoint.data(), endpoint.size(), - host_name, NI_MAXHOST, service_name, NI_MAXSERV, - endpoint.protocol().type(), ec); - - return ec ? results_type() : results_type::create( - endpoint, host_name, service_name); - } - - // Asynchronously resolve an endpoint to a list of entries. - template - void async_resolve(implementation_type& impl, - const endpoint_type& endpoint, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef resolve_endpoint_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl, endpoint, io_context_impl_, handler); - - ASIO_HANDLER_CREATION((io_context_impl_.context(), - *p.p, "resolver", &impl, 0, "async_resolve")); - - start_resolve_op(p.p); - p.v = p.p = 0; - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_RESOLVER_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/resolver_service_base.hpp b/scout_sdk/asio/asio/detail/resolver_service_base.hpp deleted file mode 100644 index 10a7922..0000000 --- a/scout_sdk/asio/asio/detail/resolver_service_base.hpp +++ /dev/null @@ -1,140 +0,0 @@ -// -// detail/resolver_service_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_RESOLVER_SERVICE_BASE_HPP -#define ASIO_DETAIL_RESOLVER_SERVICE_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/error.hpp" -#include "asio/executor_work_guard.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/resolve_op.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/detail/thread.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class resolver_service_base -{ -public: - // The implementation type of the resolver. A cancellation token is used to - // indicate to the background thread that the operation has been cancelled. - typedef socket_ops::shared_cancel_token_type implementation_type; - - // Constructor. - ASIO_DECL resolver_service_base(asio::io_context& io_context); - - // Destructor. - ASIO_DECL ~resolver_service_base(); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void base_shutdown(); - - // Perform any fork-related housekeeping. - ASIO_DECL void base_notify_fork( - asio::io_context::fork_event fork_ev); - - // Construct a new resolver implementation. - ASIO_DECL void construct(implementation_type& impl); - - // Destroy a resolver implementation. - ASIO_DECL void destroy(implementation_type&); - - // Move-construct a new resolver implementation. - ASIO_DECL void move_construct(implementation_type& impl, - implementation_type& other_impl); - - // Move-assign from another resolver implementation. - ASIO_DECL void move_assign(implementation_type& impl, - resolver_service_base& other_service, - implementation_type& other_impl); - - // Cancel pending asynchronous operations. - ASIO_DECL void cancel(implementation_type& impl); - -protected: - // Helper function to start an asynchronous resolve operation. - ASIO_DECL void start_resolve_op(resolve_op* op); - -#if !defined(ASIO_WINDOWS_RUNTIME) - // Helper class to perform exception-safe cleanup of addrinfo objects. - class auto_addrinfo - : private asio::detail::noncopyable - { - public: - explicit auto_addrinfo(asio::detail::addrinfo_type* ai) - : ai_(ai) - { - } - - ~auto_addrinfo() - { - if (ai_) - socket_ops::freeaddrinfo(ai_); - } - - operator asio::detail::addrinfo_type*() - { - return ai_; - } - - private: - asio::detail::addrinfo_type* ai_; - }; -#endif // !defined(ASIO_WINDOWS_RUNTIME) - - // Helper class to run the work io_context in a thread. - class work_io_context_runner; - - // Start the work thread if it's not already running. - ASIO_DECL void start_work_thread(); - - // The io_context implementation used to post completions. - io_context_impl& io_context_impl_; - -private: - // Mutex to protect access to internal data. - asio::detail::mutex mutex_; - - // Private io_context used for performing asynchronous host resolution. - asio::detail::scoped_ptr work_io_context_; - - // The work io_context implementation used to post completions. - io_context_impl& work_io_context_impl_; - - // Work for the private io_context to perform. - asio::executor_work_guard< - asio::io_context::executor_type> work_; - - // Thread used for running the work io_context's run loop. - asio::detail::scoped_ptr work_thread_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/resolver_service_base.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_RESOLVER_SERVICE_BASE_HPP diff --git a/scout_sdk/asio/asio/detail/scheduler.hpp b/scout_sdk/asio/asio/detail/scheduler.hpp deleted file mode 100644 index 10c29b7..0000000 --- a/scout_sdk/asio/asio/detail/scheduler.hpp +++ /dev/null @@ -1,213 +0,0 @@ -// -// detail/scheduler.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SCHEDULER_HPP -#define ASIO_DETAIL_SCHEDULER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/error_code.hpp" -#include "asio/execution_context.hpp" -#include "asio/detail/atomic_count.hpp" -#include "asio/detail/conditionally_enabled_event.hpp" -#include "asio/detail/conditionally_enabled_mutex.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/reactor_fwd.hpp" -#include "asio/detail/scheduler_operation.hpp" -#include "asio/detail/thread_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct scheduler_thread_info; - -class scheduler - : public execution_context_service_base, - public thread_context -{ -public: - typedef scheduler_operation operation; - - // Constructor. Specifies the number of concurrent threads that are likely to - // run the scheduler. If set to 1 certain optimisation are performed. - ASIO_DECL scheduler(asio::execution_context& ctx, - int concurrency_hint = 0); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Initialise the task, if required. - ASIO_DECL void init_task(); - - // Run the event loop until interrupted or no more work. - ASIO_DECL std::size_t run(asio::error_code& ec); - - // Run until interrupted or one operation is performed. - ASIO_DECL std::size_t run_one(asio::error_code& ec); - - // Run until timeout, interrupted, or one operation is performed. - ASIO_DECL std::size_t wait_one( - long usec, asio::error_code& ec); - - // Poll for operations without blocking. - ASIO_DECL std::size_t poll(asio::error_code& ec); - - // Poll for one operation without blocking. - ASIO_DECL std::size_t poll_one(asio::error_code& ec); - - // Interrupt the event processing loop. - ASIO_DECL void stop(); - - // Determine whether the scheduler is stopped. - ASIO_DECL bool stopped() const; - - // Restart in preparation for a subsequent run invocation. - ASIO_DECL void restart(); - - // Notify that some work has started. - void work_started() - { - ++outstanding_work_; - } - - // Used to compensate for a forthcoming work_finished call. Must be called - // from within a scheduler-owned thread. - ASIO_DECL void compensating_work_started(); - - // Notify that some work has finished. - void work_finished() - { - if (--outstanding_work_ == 0) - stop(); - } - - // Return whether a handler can be dispatched immediately. - bool can_dispatch() - { - return thread_call_stack::contains(this) != 0; - } - - // Request invocation of the given operation and return immediately. Assumes - // that work_started() has not yet been called for the operation. - ASIO_DECL void post_immediate_completion( - operation* op, bool is_continuation); - - // Request invocation of the given operation and return immediately. Assumes - // that work_started() was previously called for the operation. - ASIO_DECL void post_deferred_completion(operation* op); - - // Request invocation of the given operations and return immediately. Assumes - // that work_started() was previously called for each operation. - ASIO_DECL void post_deferred_completions(op_queue& ops); - - // Enqueue the given operation following a failed attempt to dispatch the - // operation for immediate invocation. - ASIO_DECL void do_dispatch(operation* op); - - // Process unfinished operations as part of a shutdownoperation. Assumes that - // work_started() was previously called for the operations. - ASIO_DECL void abandon_operations(op_queue& ops); - - // Get the concurrency hint that was used to initialise the scheduler. - int concurrency_hint() const - { - return concurrency_hint_; - } - -private: - // The mutex type used by this scheduler. - typedef conditionally_enabled_mutex mutex; - - // The event type used by this scheduler. - typedef conditionally_enabled_event event; - - // Structure containing thread-specific data. - typedef scheduler_thread_info thread_info; - - // Run at most one operation. May block. - ASIO_DECL std::size_t do_run_one(mutex::scoped_lock& lock, - thread_info& this_thread, const asio::error_code& ec); - - // Run at most one operation with a timeout. May block. - ASIO_DECL std::size_t do_wait_one(mutex::scoped_lock& lock, - thread_info& this_thread, long usec, const asio::error_code& ec); - - // Poll for at most one operation. - ASIO_DECL std::size_t do_poll_one(mutex::scoped_lock& lock, - thread_info& this_thread, const asio::error_code& ec); - - // Stop the task and all idle threads. - ASIO_DECL void stop_all_threads(mutex::scoped_lock& lock); - - // Wake a single idle thread, or the task, and always unlock the mutex. - ASIO_DECL void wake_one_thread_and_unlock( - mutex::scoped_lock& lock); - - // Helper class to perform task-related operations on block exit. - struct task_cleanup; - friend struct task_cleanup; - - // Helper class to call work-related operations on block exit. - struct work_cleanup; - friend struct work_cleanup; - - // Whether to optimise for single-threaded use cases. - const bool one_thread_; - - // Mutex to protect access to internal data. - mutable mutex mutex_; - - // Event to wake up blocked threads. - event wakeup_event_; - - // The task to be run by this service. - reactor* task_; - - // Operation object to represent the position of the task in the queue. - struct task_operation : operation - { - task_operation() : operation(0) {} - } task_operation_; - - // Whether the task has been interrupted. - bool task_interrupted_; - - // The count of unfinished work. - atomic_count outstanding_work_; - - // The queue of handlers that are ready to be delivered. - op_queue op_queue_; - - // Flag to indicate that the dispatcher has been stopped. - bool stopped_; - - // Flag to indicate that the dispatcher has been shut down. - bool shutdown_; - - // The concurrency hint used to initialise the scheduler. - const int concurrency_hint_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/scheduler.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_SCHEDULER_HPP diff --git a/scout_sdk/asio/asio/detail/scheduler_operation.hpp b/scout_sdk/asio/asio/detail/scheduler_operation.hpp deleted file mode 100644 index 1c2ce02..0000000 --- a/scout_sdk/asio/asio/detail/scheduler_operation.hpp +++ /dev/null @@ -1,78 +0,0 @@ -// -// detail/scheduler_operation.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SCHEDULER_OPERATION_HPP -#define ASIO_DETAIL_SCHEDULER_OPERATION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/error_code.hpp" -#include "asio/detail/handler_tracking.hpp" -#include "asio/detail/op_queue.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class scheduler; - -// Base class for all operations. A function pointer is used instead of virtual -// functions to avoid the associated overhead. -class scheduler_operation ASIO_INHERIT_TRACKED_HANDLER -{ -public: - typedef scheduler_operation operation_type; - - void complete(void* owner, const asio::error_code& ec, - std::size_t bytes_transferred) - { - func_(owner, this, ec, bytes_transferred); - } - - void destroy() - { - func_(0, this, asio::error_code(), 0); - } - -protected: - typedef void (*func_type)(void*, - scheduler_operation*, - const asio::error_code&, std::size_t); - - scheduler_operation(func_type func) - : next_(0), - func_(func), - task_result_(0) - { - } - - // Prevents deletion through this type. - ~scheduler_operation() - { - } - -private: - friend class op_queue_access; - scheduler_operation* next_; - func_type func_; -protected: - friend class scheduler; - unsigned int task_result_; // Passed into bytes transferred. -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SCHEDULER_OPERATION_HPP diff --git a/scout_sdk/asio/asio/detail/scheduler_thread_info.hpp b/scout_sdk/asio/asio/detail/scheduler_thread_info.hpp deleted file mode 100644 index 2ffe013..0000000 --- a/scout_sdk/asio/asio/detail/scheduler_thread_info.hpp +++ /dev/null @@ -1,40 +0,0 @@ -// -// detail/scheduler_thread_info.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SCHEDULER_THREAD_INFO_HPP -#define ASIO_DETAIL_SCHEDULER_THREAD_INFO_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/op_queue.hpp" -#include "asio/detail/thread_info_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class scheduler; -class scheduler_operation; - -struct scheduler_thread_info : public thread_info_base -{ - op_queue private_op_queue; - long private_outstanding_work; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SCHEDULER_THREAD_INFO_HPP diff --git a/scout_sdk/asio/asio/detail/scoped_lock.hpp b/scout_sdk/asio/asio/detail/scoped_lock.hpp deleted file mode 100644 index 6cbce38..0000000 --- a/scout_sdk/asio/asio/detail/scoped_lock.hpp +++ /dev/null @@ -1,101 +0,0 @@ -// -// detail/scoped_lock.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SCOPED_LOCK_HPP -#define ASIO_DETAIL_SCOPED_LOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Helper class to lock and unlock a mutex automatically. -template -class scoped_lock - : private noncopyable -{ -public: - // Tag type used to distinguish constructors. - enum adopt_lock_t { adopt_lock }; - - // Constructor adopts a lock that is already held. - scoped_lock(Mutex& m, adopt_lock_t) - : mutex_(m), - locked_(true) - { - } - - // Constructor acquires the lock. - explicit scoped_lock(Mutex& m) - : mutex_(m) - { - mutex_.lock(); - locked_ = true; - } - - // Destructor releases the lock. - ~scoped_lock() - { - if (locked_) - mutex_.unlock(); - } - - // Explicitly acquire the lock. - void lock() - { - if (!locked_) - { - mutex_.lock(); - locked_ = true; - } - } - - // Explicitly release the lock. - void unlock() - { - if (locked_) - { - mutex_.unlock(); - locked_ = false; - } - } - - // Test whether the lock is held. - bool locked() const - { - return locked_; - } - - // Get the underlying mutex. - Mutex& mutex() - { - return mutex_; - } - -private: - // The underlying mutex. - Mutex& mutex_; - - // Whether the mutex is currently locked or unlocked. - bool locked_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SCOPED_LOCK_HPP diff --git a/scout_sdk/asio/asio/detail/scoped_ptr.hpp b/scout_sdk/asio/asio/detail/scoped_ptr.hpp deleted file mode 100644 index 3449c53..0000000 --- a/scout_sdk/asio/asio/detail/scoped_ptr.hpp +++ /dev/null @@ -1,87 +0,0 @@ -// -// detail/scoped_ptr.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SCOPED_PTR_HPP -#define ASIO_DETAIL_SCOPED_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class scoped_ptr -{ -public: - // Constructor. - explicit scoped_ptr(T* p = 0) - : p_(p) - { - } - - // Destructor. - ~scoped_ptr() - { - delete p_; - } - - // Access. - T* get() - { - return p_; - } - - // Access. - T* operator->() - { - return p_; - } - - // Dereference. - T& operator*() - { - return *p_; - } - - // Reset pointer. - void reset(T* p = 0) - { - delete p_; - p_ = p; - } - - // Release ownership of the pointer. - T* release() - { - T* tmp = p_; - p_ = 0; - return tmp; - } - -private: - // Disallow copying and assignment. - scoped_ptr(const scoped_ptr&); - scoped_ptr& operator=(const scoped_ptr&); - - T* p_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SCOPED_PTR_HPP diff --git a/scout_sdk/asio/asio/detail/select_interrupter.hpp b/scout_sdk/asio/asio/detail/select_interrupter.hpp deleted file mode 100644 index 1a07599..0000000 --- a/scout_sdk/asio/asio/detail/select_interrupter.hpp +++ /dev/null @@ -1,46 +0,0 @@ -// -// detail/select_interrupter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SELECT_INTERRUPTER_HPP -#define ASIO_DETAIL_SELECT_INTERRUPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS_RUNTIME) - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) || defined(__SYMBIAN32__) -# include "asio/detail/socket_select_interrupter.hpp" -#elif defined(ASIO_HAS_EVENTFD) -# include "asio/detail/eventfd_select_interrupter.hpp" -#else -# include "asio/detail/pipe_select_interrupter.hpp" -#endif - -namespace asio { -namespace detail { - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) || defined(__SYMBIAN32__) -typedef socket_select_interrupter select_interrupter; -#elif defined(ASIO_HAS_EVENTFD) -typedef eventfd_select_interrupter select_interrupter; -#else -typedef pipe_select_interrupter select_interrupter; -#endif - -} // namespace detail -} // namespace asio - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_SELECT_INTERRUPTER_HPP diff --git a/scout_sdk/asio/asio/detail/select_reactor.hpp b/scout_sdk/asio/asio/detail/select_reactor.hpp deleted file mode 100644 index 0996549..0000000 --- a/scout_sdk/asio/asio/detail/select_reactor.hpp +++ /dev/null @@ -1,238 +0,0 @@ -// -// detail/select_reactor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SELECT_REACTOR_HPP -#define ASIO_DETAIL_SELECT_REACTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) \ - || (!defined(ASIO_HAS_DEV_POLL) \ - && !defined(ASIO_HAS_EPOLL) \ - && !defined(ASIO_HAS_KQUEUE) \ - && !defined(ASIO_WINDOWS_RUNTIME)) - -#include -#include "asio/detail/fd_set_adapter.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/reactor_op_queue.hpp" -#include "asio/detail/select_interrupter.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/timer_queue_base.hpp" -#include "asio/detail/timer_queue_set.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/execution_context.hpp" - -#if defined(ASIO_HAS_IOCP) -# include "asio/detail/thread.hpp" -#endif // defined(ASIO_HAS_IOCP) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class select_reactor - : public execution_context_service_base -{ -public: -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - enum op_types { read_op = 0, write_op = 1, except_op = 2, - max_select_ops = 3, connect_op = 3, max_ops = 4 }; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - enum op_types { read_op = 0, write_op = 1, except_op = 2, - max_select_ops = 3, connect_op = 1, max_ops = 3 }; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - - // Per-descriptor data. - struct per_descriptor_data - { - }; - - // Constructor. - ASIO_DECL select_reactor(asio::execution_context& ctx); - - // Destructor. - ASIO_DECL ~select_reactor(); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Recreate internal descriptors following a fork. - ASIO_DECL void notify_fork( - asio::execution_context::fork_event fork_ev); - - // Initialise the task, but only if the reactor is not in its own thread. - ASIO_DECL void init_task(); - - // Register a socket with the reactor. Returns 0 on success, system error - // code on failure. - ASIO_DECL int register_descriptor(socket_type, per_descriptor_data&); - - // Register a descriptor with an associated single operation. Returns 0 on - // success, system error code on failure. - ASIO_DECL int register_internal_descriptor( - int op_type, socket_type descriptor, - per_descriptor_data& descriptor_data, reactor_op* op); - - // Post a reactor operation for immediate completion. - void post_immediate_completion(reactor_op* op, bool is_continuation) - { - scheduler_.post_immediate_completion(op, is_continuation); - } - - // Start a new operation. The reactor operation will be performed when the - // given descriptor is flagged as ready, or an error has occurred. - ASIO_DECL void start_op(int op_type, socket_type descriptor, - per_descriptor_data&, reactor_op* op, bool is_continuation, bool); - - // Cancel all operations associated with the given descriptor. The - // handlers associated with the descriptor will be invoked with the - // operation_aborted error. - ASIO_DECL void cancel_ops(socket_type descriptor, per_descriptor_data&); - - // Cancel any operations that are running against the descriptor and remove - // its registration from the reactor. The reactor resources associated with - // the descriptor must be released by calling cleanup_descriptor_data. - ASIO_DECL void deregister_descriptor(socket_type descriptor, - per_descriptor_data&, bool closing); - - // Remove the descriptor's registration from the reactor. The reactor - // resources associated with the descriptor must be released by calling - // cleanup_descriptor_data. - ASIO_DECL void deregister_internal_descriptor( - socket_type descriptor, per_descriptor_data&); - - // Perform any post-deregistration cleanup tasks associated with the - // descriptor data. - ASIO_DECL void cleanup_descriptor_data(per_descriptor_data&); - - // Move descriptor registration from one descriptor_data object to another. - ASIO_DECL void move_descriptor(socket_type descriptor, - per_descriptor_data& target_descriptor_data, - per_descriptor_data& source_descriptor_data); - - // Add a new timer queue to the reactor. - template - void add_timer_queue(timer_queue& queue); - - // Remove a timer queue from the reactor. - template - void remove_timer_queue(timer_queue& queue); - - // Schedule a new operation in the given timer queue to expire at the - // specified absolute time. - template - void schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op); - - // Cancel the timer operations associated with the given token. Returns the - // number of operations that have been posted or dispatched. - template - std::size_t cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled = (std::numeric_limits::max)()); - - // Move the timer operations associated with the given timer. - template - void move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& target, - typename timer_queue::per_timer_data& source); - - // Run select once until interrupted or events are ready to be dispatched. - ASIO_DECL void run(long usec, op_queue& ops); - - // Interrupt the select loop. - ASIO_DECL void interrupt(); - -private: -#if defined(ASIO_HAS_IOCP) - // Run the select loop in the thread. - ASIO_DECL void run_thread(); -#endif // defined(ASIO_HAS_IOCP) - - // Helper function to add a new timer queue. - ASIO_DECL void do_add_timer_queue(timer_queue_base& queue); - - // Helper function to remove a timer queue. - ASIO_DECL void do_remove_timer_queue(timer_queue_base& queue); - - // Get the timeout value for the select call. - ASIO_DECL timeval* get_timeout(long usec, timeval& tv); - - // Cancel all operations associated with the given descriptor. This function - // does not acquire the select_reactor's mutex. - ASIO_DECL void cancel_ops_unlocked(socket_type descriptor, - const asio::error_code& ec); - - // The scheduler implementation used to post completions. -# if defined(ASIO_HAS_IOCP) - typedef class win_iocp_io_context scheduler_type; -# else // defined(ASIO_HAS_IOCP) - typedef class scheduler scheduler_type; -# endif // defined(ASIO_HAS_IOCP) - scheduler_type& scheduler_; - - // Mutex to protect access to internal data. - asio::detail::mutex mutex_; - - // The interrupter is used to break a blocking select call. - select_interrupter interrupter_; - - // The queues of read, write and except operations. - reactor_op_queue op_queue_[max_ops]; - - // The file descriptor sets to be passed to the select system call. - fd_set_adapter fd_sets_[max_select_ops]; - - // The timer queues. - timer_queue_set timer_queues_; - -#if defined(ASIO_HAS_IOCP) - // Helper class to run the reactor loop in a thread. - class thread_function; - friend class thread_function; - - // Does the reactor loop thread need to stop. - bool stop_thread_; - - // The thread that is running the reactor loop. - asio::detail::thread* thread_; -#endif // defined(ASIO_HAS_IOCP) - - // Whether the service has been shut down. - bool shutdown_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/select_reactor.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/select_reactor.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_IOCP) - // || (!defined(ASIO_HAS_DEV_POLL) - // && !defined(ASIO_HAS_EPOLL) - // && !defined(ASIO_HAS_KQUEUE) - // && !defined(ASIO_WINDOWS_RUNTIME)) - -#endif // ASIO_DETAIL_SELECT_REACTOR_HPP diff --git a/scout_sdk/asio/asio/detail/service_registry.hpp b/scout_sdk/asio/asio/detail/service_registry.hpp deleted file mode 100644 index cda6307..0000000 --- a/scout_sdk/asio/asio/detail/service_registry.hpp +++ /dev/null @@ -1,164 +0,0 @@ -// -// detail/service_registry.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SERVICE_REGISTRY_HPP -#define ASIO_DETAIL_SERVICE_REGISTRY_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/mutex.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -class io_context; - -namespace detail { - -template -class typeid_wrapper {}; - -class service_registry - : private noncopyable -{ -public: - // Constructor. - ASIO_DECL service_registry(execution_context& owner); - - // Destructor. - ASIO_DECL ~service_registry(); - - // Shutdown all services. - ASIO_DECL void shutdown_services(); - - // Destroy all services. - ASIO_DECL void destroy_services(); - - // Notify all services of a fork event. - ASIO_DECL void notify_fork(execution_context::fork_event fork_ev); - - // Get the service object corresponding to the specified service type. Will - // create a new service object automatically if no such object already - // exists. Ownership of the service object is not transferred to the caller. - template - Service& use_service(); - - // Get the service object corresponding to the specified service type. Will - // create a new service object automatically if no such object already - // exists. Ownership of the service object is not transferred to the caller. - // This overload is used for backwards compatibility with services that - // inherit from io_context::service. - template - Service& use_service(io_context& owner); - - // Add a service object. Throws on error, in which case ownership of the - // object is retained by the caller. - template - void add_service(Service* new_service); - - // Check whether a service object of the specified type already exists. - template - bool has_service() const; - -private: - // Initalise a service's key when the key_type typedef is not available. - template - static void init_key(execution_context::service::key& key, ...); - -#if !defined(ASIO_NO_TYPEID) - // Initalise a service's key when the key_type typedef is available. - template - static void init_key(execution_context::service::key& key, - typename enable_if< - is_base_of::value>::type*); -#endif // !defined(ASIO_NO_TYPEID) - - // Initialise a service's key based on its id. - ASIO_DECL static void init_key_from_id( - execution_context::service::key& key, - const execution_context::id& id); - -#if !defined(ASIO_NO_TYPEID) - // Initialise a service's key based on its id. - template - static void init_key_from_id(execution_context::service::key& key, - const service_id& /*id*/); -#endif // !defined(ASIO_NO_TYPEID) - - // Check if a service matches the given id. - ASIO_DECL static bool keys_match( - const execution_context::service::key& key1, - const execution_context::service::key& key2); - - // The type of a factory function used for creating a service instance. - typedef execution_context::service*(*factory_type)(void*); - - // Factory function for creating a service instance. - template - static execution_context::service* create(void* owner); - - // Destroy a service instance. - ASIO_DECL static void destroy(execution_context::service* service); - - // Helper class to manage service pointers. - struct auto_service_ptr; - friend struct auto_service_ptr; - struct auto_service_ptr - { - execution_context::service* ptr_; - ~auto_service_ptr() { destroy(ptr_); } - }; - - // Get the service object corresponding to the specified service key. Will - // create a new service object automatically if no such object already - // exists. Ownership of the service object is not transferred to the caller. - ASIO_DECL execution_context::service* do_use_service( - const execution_context::service::key& key, - factory_type factory, void* owner); - - // Add a service object. Throws on error, in which case ownership of the - // object is retained by the caller. - ASIO_DECL void do_add_service( - const execution_context::service::key& key, - execution_context::service* new_service); - - // Check whether a service object with the specified key already exists. - ASIO_DECL bool do_has_service( - const execution_context::service::key& key) const; - - // Mutex to protect access to internal data. - mutable asio::detail::mutex mutex_; - - // The owner of this service registry and the services it contains. - execution_context& owner_; - - // The first service in the list of contained services. - execution_context::service* first_service_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/service_registry.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/service_registry.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_SERVICE_REGISTRY_HPP diff --git a/scout_sdk/asio/asio/detail/signal_blocker.hpp b/scout_sdk/asio/asio/detail/signal_blocker.hpp deleted file mode 100644 index b684295..0000000 --- a/scout_sdk/asio/asio/detail/signal_blocker.hpp +++ /dev/null @@ -1,44 +0,0 @@ -// -// detail/signal_blocker.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SIGNAL_BLOCKER_HPP -#define ASIO_DETAIL_SIGNAL_BLOCKER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) || defined(ASIO_WINDOWS) \ - || defined(ASIO_WINDOWS_RUNTIME) \ - || defined(__CYGWIN__) || defined(__SYMBIAN32__) -# include "asio/detail/null_signal_blocker.hpp" -#elif defined(ASIO_HAS_PTHREADS) -# include "asio/detail/posix_signal_blocker.hpp" -#else -# error Only Windows and POSIX are supported! -#endif - -namespace asio { -namespace detail { - -#if !defined(ASIO_HAS_THREADS) || defined(ASIO_WINDOWS) \ - || defined(ASIO_WINDOWS_RUNTIME) \ - || defined(__CYGWIN__) || defined(__SYMBIAN32__) -typedef null_signal_blocker signal_blocker; -#elif defined(ASIO_HAS_PTHREADS) -typedef posix_signal_blocker signal_blocker; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_SIGNAL_BLOCKER_HPP diff --git a/scout_sdk/asio/asio/detail/signal_handler.hpp b/scout_sdk/asio/asio/detail/signal_handler.hpp deleted file mode 100644 index d1c9910..0000000 --- a/scout_sdk/asio/asio/detail/signal_handler.hpp +++ /dev/null @@ -1,86 +0,0 @@ -// -// detail/signal_handler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SIGNAL_HANDLER_HPP -#define ASIO_DETAIL_SIGNAL_HANDLER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_work.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/signal_op.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class signal_handler : public signal_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(signal_handler); - - signal_handler(Handler& h) - : signal_op(&signal_handler::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(h)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - signal_handler* h(static_cast(base)); - ptr p = { asio::detail::addressof(h->handler_), h, h }; - handler_work w(h->handler_); - - ASIO_HANDLER_COMPLETION((*h)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(h->handler_, h->ec_, h->signal_number_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SIGNAL_HANDLER_HPP diff --git a/scout_sdk/asio/asio/detail/signal_init.hpp b/scout_sdk/asio/asio/detail/signal_init.hpp deleted file mode 100644 index 814ff51..0000000 --- a/scout_sdk/asio/asio/detail/signal_init.hpp +++ /dev/null @@ -1,47 +0,0 @@ -// -// detail/signal_init.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SIGNAL_INIT_HPP -#define ASIO_DETAIL_SIGNAL_INIT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class signal_init -{ -public: - // Constructor. - signal_init() - { - std::signal(Signal, SIG_IGN); - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#endif // ASIO_DETAIL_SIGNAL_INIT_HPP diff --git a/scout_sdk/asio/asio/detail/signal_op.hpp b/scout_sdk/asio/asio/detail/signal_op.hpp deleted file mode 100644 index c4e364c..0000000 --- a/scout_sdk/asio/asio/detail/signal_op.hpp +++ /dev/null @@ -1,49 +0,0 @@ -// -// detail/signal_op.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SIGNAL_OP_HPP -#define ASIO_DETAIL_SIGNAL_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class signal_op - : public operation -{ -public: - // The error code to be passed to the completion handler. - asio::error_code ec_; - - // The signal number to be passed to the completion handler. - int signal_number_; - -protected: - signal_op(func_type func) - : operation(func), - signal_number_(0) - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SIGNAL_OP_HPP diff --git a/scout_sdk/asio/asio/detail/signal_set_service.hpp b/scout_sdk/asio/asio/detail/signal_set_service.hpp deleted file mode 100644 index a18ab70..0000000 --- a/scout_sdk/asio/asio/detail/signal_set_service.hpp +++ /dev/null @@ -1,217 +0,0 @@ -// -// detail/signal_set_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SIGNAL_SET_SERVICE_HPP -#define ASIO_DETAIL_SIGNAL_SET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/signal_handler.hpp" -#include "asio/detail/signal_op.hpp" -#include "asio/detail/socket_types.hpp" - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) -# include "asio/detail/reactor.hpp" -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -#if defined(NSIG) && (NSIG > 0) -enum { max_signal_number = NSIG }; -#else -enum { max_signal_number = 128 }; -#endif - -extern ASIO_DECL struct signal_state* get_signal_state(); - -extern "C" ASIO_DECL void asio_signal_handler(int signal_number); - -class signal_set_service : - public service_base -{ -public: - // Type used for tracking an individual signal registration. - class registration - { - public: - // Default constructor. - registration() - : signal_number_(0), - queue_(0), - undelivered_(0), - next_in_table_(0), - prev_in_table_(0), - next_in_set_(0) - { - } - - private: - // Only this service will have access to the internal values. - friend class signal_set_service; - - // The signal number that is registered. - int signal_number_; - - // The waiting signal handlers. - op_queue* queue_; - - // The number of undelivered signals. - std::size_t undelivered_; - - // Pointers to adjacent registrations in the registrations_ table. - registration* next_in_table_; - registration* prev_in_table_; - - // Link to next registration in the signal set. - registration* next_in_set_; - }; - - // The implementation type of the signal_set. - class implementation_type - { - public: - // Default constructor. - implementation_type() - : signals_(0) - { - } - - private: - // Only this service will have access to the internal values. - friend class signal_set_service; - - // The pending signal handlers. - op_queue queue_; - - // Linked list of registered signals. - registration* signals_; - }; - - // Constructor. - ASIO_DECL signal_set_service(asio::io_context& io_context); - - // Destructor. - ASIO_DECL ~signal_set_service(); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Perform fork-related housekeeping. - ASIO_DECL void notify_fork( - asio::io_context::fork_event fork_ev); - - // Construct a new signal_set implementation. - ASIO_DECL void construct(implementation_type& impl); - - // Destroy a signal_set implementation. - ASIO_DECL void destroy(implementation_type& impl); - - // Add a signal to a signal_set. - ASIO_DECL asio::error_code add(implementation_type& impl, - int signal_number, asio::error_code& ec); - - // Remove a signal to a signal_set. - ASIO_DECL asio::error_code remove(implementation_type& impl, - int signal_number, asio::error_code& ec); - - // Remove all signals from a signal_set. - ASIO_DECL asio::error_code clear(implementation_type& impl, - asio::error_code& ec); - - // Cancel all operations associated with the signal set. - ASIO_DECL asio::error_code cancel(implementation_type& impl, - asio::error_code& ec); - - // Start an asynchronous operation to wait for a signal to be delivered. - template - void async_wait(implementation_type& impl, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef signal_handler op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((io_context_.context(), - *p.p, "signal_set", &impl, 0, "async_wait")); - - start_wait_op(impl, p.p); - p.v = p.p = 0; - } - - // Deliver notification that a particular signal occurred. - ASIO_DECL static void deliver_signal(int signal_number); - -private: - // Helper function to add a service to the global signal state. - ASIO_DECL static void add_service(signal_set_service* service); - - // Helper function to remove a service from the global signal state. - ASIO_DECL static void remove_service(signal_set_service* service); - - // Helper function to create the pipe descriptors. - ASIO_DECL static void open_descriptors(); - - // Helper function to close the pipe descriptors. - ASIO_DECL static void close_descriptors(); - - // Helper function to start a wait operation. - ASIO_DECL void start_wait_op(implementation_type& impl, signal_op* op); - - // The io_context instance used for dispatching handlers. - io_context_impl& io_context_; - -#if !defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_RUNTIME) \ - && !defined(__CYGWIN__) - // The type used for registering for pipe reactor notifications. - class pipe_read_op; - - // The reactor used for waiting for pipe readiness. - reactor& reactor_; - - // The per-descriptor reactor data used for the pipe. - reactor::per_descriptor_data reactor_data_; -#endif // !defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_RUNTIME) - // && !defined(__CYGWIN__) - - // A mapping from signal number to the registered signal sets. - registration* registrations_[max_signal_number]; - - // Pointers to adjacent services in linked list. - signal_set_service* next_; - signal_set_service* prev_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/signal_set_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_SIGNAL_SET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/socket_holder.hpp b/scout_sdk/asio/asio/detail/socket_holder.hpp deleted file mode 100644 index 99b081f..0000000 --- a/scout_sdk/asio/asio/detail/socket_holder.hpp +++ /dev/null @@ -1,98 +0,0 @@ -// -// detail/socket_holder.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SOCKET_HOLDER_HPP -#define ASIO_DETAIL_SOCKET_HOLDER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Implement the resource acquisition is initialisation idiom for sockets. -class socket_holder - : private noncopyable -{ -public: - // Construct as an uninitialised socket. - socket_holder() - : socket_(invalid_socket) - { - } - - // Construct to take ownership of the specified socket. - explicit socket_holder(socket_type s) - : socket_(s) - { - } - - // Destructor. - ~socket_holder() - { - if (socket_ != invalid_socket) - { - asio::error_code ec; - socket_ops::state_type state = 0; - socket_ops::close(socket_, state, true, ec); - } - } - - // Get the underlying socket. - socket_type get() const - { - return socket_; - } - - // Reset to an uninitialised socket. - void reset() - { - if (socket_ != invalid_socket) - { - asio::error_code ec; - socket_ops::state_type state = 0; - socket_ops::close(socket_, state, true, ec); - socket_ = invalid_socket; - } - } - - // Reset to take ownership of the specified socket. - void reset(socket_type s) - { - reset(); - socket_ = s; - } - - // Release ownership of the socket. - socket_type release() - { - socket_type tmp = socket_; - socket_ = invalid_socket; - return tmp; - } - -private: - // The underlying socket. - socket_type socket_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SOCKET_HOLDER_HPP diff --git a/scout_sdk/asio/asio/detail/socket_ops.hpp b/scout_sdk/asio/asio/detail/socket_ops.hpp deleted file mode 100644 index 815b0d1..0000000 --- a/scout_sdk/asio/asio/detail/socket_ops.hpp +++ /dev/null @@ -1,337 +0,0 @@ -// -// detail/socket_ops.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SOCKET_OPS_HPP -#define ASIO_DETAIL_SOCKET_OPS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/error_code.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { -namespace socket_ops { - -// Socket state bits. -enum -{ - // The user wants a non-blocking socket. - user_set_non_blocking = 1, - - // The socket has been set non-blocking. - internal_non_blocking = 2, - - // Helper "state" used to determine whether the socket is non-blocking. - non_blocking = user_set_non_blocking | internal_non_blocking, - - // User wants connection_aborted errors, which are disabled by default. - enable_connection_aborted = 4, - - // The user set the linger option. Needs to be checked when closing. - user_set_linger = 8, - - // The socket is stream-oriented. - stream_oriented = 16, - - // The socket is datagram-oriented. - datagram_oriented = 32, - - // The socket may have been dup()-ed. - possible_dup = 64 -}; - -typedef unsigned char state_type; - -struct noop_deleter { void operator()(void*) {} }; -typedef shared_ptr shared_cancel_token_type; -typedef weak_ptr weak_cancel_token_type; - -#if !defined(ASIO_WINDOWS_RUNTIME) - -ASIO_DECL socket_type accept(socket_type s, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec); - -ASIO_DECL socket_type sync_accept(socket_type s, - state_type state, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec); - -#if defined(ASIO_HAS_IOCP) - -ASIO_DECL void complete_iocp_accept(socket_type s, - void* output_buffer, DWORD address_length, - socket_addr_type* addr, std::size_t* addrlen, - socket_type new_socket, asio::error_code& ec); - -#else // defined(ASIO_HAS_IOCP) - -ASIO_DECL bool non_blocking_accept(socket_type s, - state_type state, socket_addr_type* addr, std::size_t* addrlen, - asio::error_code& ec, socket_type& new_socket); - -#endif // defined(ASIO_HAS_IOCP) - -ASIO_DECL int bind(socket_type s, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec); - -ASIO_DECL int close(socket_type s, state_type& state, - bool destruction, asio::error_code& ec); - -ASIO_DECL bool set_user_non_blocking(socket_type s, - state_type& state, bool value, asio::error_code& ec); - -ASIO_DECL bool set_internal_non_blocking(socket_type s, - state_type& state, bool value, asio::error_code& ec); - -ASIO_DECL int shutdown(socket_type s, - int what, asio::error_code& ec); - -ASIO_DECL int connect(socket_type s, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec); - -ASIO_DECL void sync_connect(socket_type s, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec); - -#if defined(ASIO_HAS_IOCP) - -ASIO_DECL void complete_iocp_connect(socket_type s, - asio::error_code& ec); - -#endif // defined(ASIO_HAS_IOCP) - -ASIO_DECL bool non_blocking_connect(socket_type s, - asio::error_code& ec); - -ASIO_DECL int socketpair(int af, int type, int protocol, - socket_type sv[2], asio::error_code& ec); - -ASIO_DECL bool sockatmark(socket_type s, asio::error_code& ec); - -ASIO_DECL size_t available(socket_type s, asio::error_code& ec); - -ASIO_DECL int listen(socket_type s, - int backlog, asio::error_code& ec); - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -typedef WSABUF buf; -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) -typedef iovec buf; -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -ASIO_DECL void init_buf(buf& b, void* data, size_t size); - -ASIO_DECL void init_buf(buf& b, const void* data, size_t size); - -ASIO_DECL signed_size_type recv(socket_type s, buf* bufs, - size_t count, int flags, asio::error_code& ec); - -ASIO_DECL size_t sync_recv(socket_type s, state_type state, buf* bufs, - size_t count, int flags, bool all_empty, asio::error_code& ec); - -#if defined(ASIO_HAS_IOCP) - -ASIO_DECL void complete_iocp_recv(state_type state, - const weak_cancel_token_type& cancel_token, bool all_empty, - asio::error_code& ec, size_t bytes_transferred); - -#else // defined(ASIO_HAS_IOCP) - -ASIO_DECL bool non_blocking_recv(socket_type s, - buf* bufs, size_t count, int flags, bool is_stream, - asio::error_code& ec, size_t& bytes_transferred); - -#endif // defined(ASIO_HAS_IOCP) - -ASIO_DECL signed_size_type recvfrom(socket_type s, buf* bufs, - size_t count, int flags, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec); - -ASIO_DECL size_t sync_recvfrom(socket_type s, state_type state, - buf* bufs, size_t count, int flags, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec); - -#if defined(ASIO_HAS_IOCP) - -ASIO_DECL void complete_iocp_recvfrom( - const weak_cancel_token_type& cancel_token, - asio::error_code& ec); - -#else // defined(ASIO_HAS_IOCP) - -ASIO_DECL bool non_blocking_recvfrom(socket_type s, - buf* bufs, size_t count, int flags, - socket_addr_type* addr, std::size_t* addrlen, - asio::error_code& ec, size_t& bytes_transferred); - -#endif // defined(ASIO_HAS_IOCP) - -ASIO_DECL signed_size_type recvmsg(socket_type s, buf* bufs, - size_t count, int in_flags, int& out_flags, - asio::error_code& ec); - -ASIO_DECL size_t sync_recvmsg(socket_type s, state_type state, - buf* bufs, size_t count, int in_flags, int& out_flags, - asio::error_code& ec); - -#if defined(ASIO_HAS_IOCP) - -ASIO_DECL void complete_iocp_recvmsg( - const weak_cancel_token_type& cancel_token, - asio::error_code& ec); - -#else // defined(ASIO_HAS_IOCP) - -ASIO_DECL bool non_blocking_recvmsg(socket_type s, - buf* bufs, size_t count, int in_flags, int& out_flags, - asio::error_code& ec, size_t& bytes_transferred); - -#endif // defined(ASIO_HAS_IOCP) - -ASIO_DECL signed_size_type send(socket_type s, const buf* bufs, - size_t count, int flags, asio::error_code& ec); - -ASIO_DECL size_t sync_send(socket_type s, state_type state, - const buf* bufs, size_t count, int flags, - bool all_empty, asio::error_code& ec); - -#if defined(ASIO_HAS_IOCP) - -ASIO_DECL void complete_iocp_send( - const weak_cancel_token_type& cancel_token, - asio::error_code& ec); - -#else // defined(ASIO_HAS_IOCP) - -ASIO_DECL bool non_blocking_send(socket_type s, - const buf* bufs, size_t count, int flags, - asio::error_code& ec, size_t& bytes_transferred); - -#endif // defined(ASIO_HAS_IOCP) - -ASIO_DECL signed_size_type sendto(socket_type s, const buf* bufs, - size_t count, int flags, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec); - -ASIO_DECL size_t sync_sendto(socket_type s, state_type state, - const buf* bufs, size_t count, int flags, const socket_addr_type* addr, - std::size_t addrlen, asio::error_code& ec); - -#if !defined(ASIO_HAS_IOCP) - -ASIO_DECL bool non_blocking_sendto(socket_type s, - const buf* bufs, size_t count, int flags, - const socket_addr_type* addr, std::size_t addrlen, - asio::error_code& ec, size_t& bytes_transferred); - -#endif // !defined(ASIO_HAS_IOCP) - -ASIO_DECL socket_type socket(int af, int type, int protocol, - asio::error_code& ec); - -ASIO_DECL int setsockopt(socket_type s, state_type& state, - int level, int optname, const void* optval, - std::size_t optlen, asio::error_code& ec); - -ASIO_DECL int getsockopt(socket_type s, state_type state, - int level, int optname, void* optval, - size_t* optlen, asio::error_code& ec); - -ASIO_DECL int getpeername(socket_type s, socket_addr_type* addr, - std::size_t* addrlen, bool cached, asio::error_code& ec); - -ASIO_DECL int getsockname(socket_type s, socket_addr_type* addr, - std::size_t* addrlen, asio::error_code& ec); - -ASIO_DECL int ioctl(socket_type s, state_type& state, - int cmd, ioctl_arg_type* arg, asio::error_code& ec); - -ASIO_DECL int select(int nfds, fd_set* readfds, fd_set* writefds, - fd_set* exceptfds, timeval* timeout, asio::error_code& ec); - -ASIO_DECL int poll_read(socket_type s, - state_type state, int msec, asio::error_code& ec); - -ASIO_DECL int poll_write(socket_type s, - state_type state, int msec, asio::error_code& ec); - -ASIO_DECL int poll_error(socket_type s, - state_type state, int msec, asio::error_code& ec); - -ASIO_DECL int poll_connect(socket_type s, - int msec, asio::error_code& ec); - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -ASIO_DECL const char* inet_ntop(int af, const void* src, char* dest, - size_t length, unsigned long scope_id, asio::error_code& ec); - -ASIO_DECL int inet_pton(int af, const char* src, void* dest, - unsigned long* scope_id, asio::error_code& ec); - -ASIO_DECL int gethostname(char* name, - int namelen, asio::error_code& ec); - -#if !defined(ASIO_WINDOWS_RUNTIME) - -ASIO_DECL asio::error_code getaddrinfo(const char* host, - const char* service, const addrinfo_type& hints, - addrinfo_type** result, asio::error_code& ec); - -ASIO_DECL asio::error_code background_getaddrinfo( - const weak_cancel_token_type& cancel_token, const char* host, - const char* service, const addrinfo_type& hints, - addrinfo_type** result, asio::error_code& ec); - -ASIO_DECL void freeaddrinfo(addrinfo_type* ai); - -ASIO_DECL asio::error_code getnameinfo( - const socket_addr_type* addr, std::size_t addrlen, - char* host, std::size_t hostlen, char* serv, - std::size_t servlen, int flags, asio::error_code& ec); - -ASIO_DECL asio::error_code sync_getnameinfo( - const socket_addr_type* addr, std::size_t addrlen, - char* host, std::size_t hostlen, char* serv, - std::size_t servlen, int sock_type, asio::error_code& ec); - -ASIO_DECL asio::error_code background_getnameinfo( - const weak_cancel_token_type& cancel_token, - const socket_addr_type* addr, std::size_t addrlen, - char* host, std::size_t hostlen, char* serv, - std::size_t servlen, int sock_type, asio::error_code& ec); - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -ASIO_DECL u_long_type network_to_host_long(u_long_type value); - -ASIO_DECL u_long_type host_to_network_long(u_long_type value); - -ASIO_DECL u_short_type network_to_host_short(u_short_type value); - -ASIO_DECL u_short_type host_to_network_short(u_short_type value); - -} // namespace socket_ops -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/socket_ops.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_SOCKET_OPS_HPP diff --git a/scout_sdk/asio/asio/detail/socket_option.hpp b/scout_sdk/asio/asio/detail/socket_option.hpp deleted file mode 100644 index 6852d56..0000000 --- a/scout_sdk/asio/asio/detail/socket_option.hpp +++ /dev/null @@ -1,316 +0,0 @@ -// -// detail/socket_option.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SOCKET_OPTION_HPP -#define ASIO_DETAIL_SOCKET_OPTION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_exception.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { -namespace socket_option { - -// Helper template for implementing boolean-based options. -template -class boolean -{ -public: - // Default constructor. - boolean() - : value_(0) - { - } - - // Construct with a specific option value. - explicit boolean(bool v) - : value_(v ? 1 : 0) - { - } - - // Set the current value of the boolean. - boolean& operator=(bool v) - { - value_ = v ? 1 : 0; - return *this; - } - - // Get the current value of the boolean. - bool value() const - { - return !!value_; - } - - // Convert to bool. - operator bool() const - { - return !!value_; - } - - // Test for false. - bool operator!() const - { - return !value_; - } - - // Get the level of the socket option. - template - int level(const Protocol&) const - { - return Level; - } - - // Get the name of the socket option. - template - int name(const Protocol&) const - { - return Name; - } - - // Get the address of the boolean data. - template - int* data(const Protocol&) - { - return &value_; - } - - // Get the address of the boolean data. - template - const int* data(const Protocol&) const - { - return &value_; - } - - // Get the size of the boolean data. - template - std::size_t size(const Protocol&) const - { - return sizeof(value_); - } - - // Set the size of the boolean data. - template - void resize(const Protocol&, std::size_t s) - { - // On some platforms (e.g. Windows Vista), the getsockopt function will - // return the size of a boolean socket option as one byte, even though a - // four byte integer was passed in. - switch (s) - { - case sizeof(char): - value_ = *reinterpret_cast(&value_) ? 1 : 0; - break; - case sizeof(value_): - break; - default: - { - std::length_error ex("boolean socket option resize"); - asio::detail::throw_exception(ex); - } - } - } - -private: - int value_; -}; - -// Helper template for implementing integer options. -template -class integer -{ -public: - // Default constructor. - integer() - : value_(0) - { - } - - // Construct with a specific option value. - explicit integer(int v) - : value_(v) - { - } - - // Set the value of the int option. - integer& operator=(int v) - { - value_ = v; - return *this; - } - - // Get the current value of the int option. - int value() const - { - return value_; - } - - // Get the level of the socket option. - template - int level(const Protocol&) const - { - return Level; - } - - // Get the name of the socket option. - template - int name(const Protocol&) const - { - return Name; - } - - // Get the address of the int data. - template - int* data(const Protocol&) - { - return &value_; - } - - // Get the address of the int data. - template - const int* data(const Protocol&) const - { - return &value_; - } - - // Get the size of the int data. - template - std::size_t size(const Protocol&) const - { - return sizeof(value_); - } - - // Set the size of the int data. - template - void resize(const Protocol&, std::size_t s) - { - if (s != sizeof(value_)) - { - std::length_error ex("integer socket option resize"); - asio::detail::throw_exception(ex); - } - } - -private: - int value_; -}; - -// Helper template for implementing linger options. -template -class linger -{ -public: - // Default constructor. - linger() - { - value_.l_onoff = 0; - value_.l_linger = 0; - } - - // Construct with specific option values. - linger(bool e, int t) - { - enabled(e); - timeout ASIO_PREVENT_MACRO_SUBSTITUTION(t); - } - - // Set the value for whether linger is enabled. - void enabled(bool value) - { - value_.l_onoff = value ? 1 : 0; - } - - // Get the value for whether linger is enabled. - bool enabled() const - { - return value_.l_onoff != 0; - } - - // Set the value for the linger timeout. - void timeout ASIO_PREVENT_MACRO_SUBSTITUTION(int value) - { -#if defined(WIN32) - value_.l_linger = static_cast(value); -#else - value_.l_linger = value; -#endif - } - - // Get the value for the linger timeout. - int timeout ASIO_PREVENT_MACRO_SUBSTITUTION() const - { - return static_cast(value_.l_linger); - } - - // Get the level of the socket option. - template - int level(const Protocol&) const - { - return Level; - } - - // Get the name of the socket option. - template - int name(const Protocol&) const - { - return Name; - } - - // Get the address of the linger data. - template - detail::linger_type* data(const Protocol&) - { - return &value_; - } - - // Get the address of the linger data. - template - const detail::linger_type* data(const Protocol&) const - { - return &value_; - } - - // Get the size of the linger data. - template - std::size_t size(const Protocol&) const - { - return sizeof(value_); - } - - // Set the size of the int data. - template - void resize(const Protocol&, std::size_t s) - { - if (s != sizeof(value_)) - { - std::length_error ex("linger socket option resize"); - asio::detail::throw_exception(ex); - } - } - -private: - detail::linger_type value_; -}; - -} // namespace socket_option -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SOCKET_OPTION_HPP diff --git a/scout_sdk/asio/asio/detail/socket_select_interrupter.hpp b/scout_sdk/asio/asio/detail/socket_select_interrupter.hpp deleted file mode 100644 index 7351070..0000000 --- a/scout_sdk/asio/asio/detail/socket_select_interrupter.hpp +++ /dev/null @@ -1,91 +0,0 @@ -// -// detail/socket_select_interrupter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SOCKET_SELECT_INTERRUPTER_HPP -#define ASIO_DETAIL_SOCKET_SELECT_INTERRUPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_WINDOWS_RUNTIME) - -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(__SYMBIAN32__) - -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class socket_select_interrupter -{ -public: - // Constructor. - ASIO_DECL socket_select_interrupter(); - - // Destructor. - ASIO_DECL ~socket_select_interrupter(); - - // Recreate the interrupter's descriptors. Used after a fork. - ASIO_DECL void recreate(); - - // Interrupt the select call. - ASIO_DECL void interrupt(); - - // Reset the select interrupt. Returns true if the call was interrupted. - ASIO_DECL bool reset(); - - // Get the read descriptor to be passed to select. - socket_type read_descriptor() const - { - return read_descriptor_; - } - -private: - // Open the descriptors. Throws on error. - ASIO_DECL void open_descriptors(); - - // Close the descriptors. - ASIO_DECL void close_descriptors(); - - // The read end of a connection used to interrupt the select call. This file - // descriptor is passed to select such that when it is time to stop, a single - // byte will be written on the other end of the connection and this - // descriptor will become readable. - socket_type read_descriptor_; - - // The write end of a connection used to interrupt the select call. A single - // byte may be written to this to wake up the select which is waiting for the - // other end to become readable. - socket_type write_descriptor_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/socket_select_interrupter.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS) - // || defined(__CYGWIN__) - // || defined(__SYMBIAN32__) - -#endif // !defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_SOCKET_SELECT_INTERRUPTER_HPP diff --git a/scout_sdk/asio/asio/detail/socket_types.hpp b/scout_sdk/asio/asio/detail/socket_types.hpp deleted file mode 100644 index d354343..0000000 --- a/scout_sdk/asio/asio/detail/socket_types.hpp +++ /dev/null @@ -1,416 +0,0 @@ -// -// detail/socket_types.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SOCKET_TYPES_HPP -#define ASIO_DETAIL_SOCKET_TYPES_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -// Empty. -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# if defined(_WINSOCKAPI_) && !defined(_WINSOCK2API_) -# error WinSock.h has already been included -# endif // defined(_WINSOCKAPI_) && !defined(_WINSOCK2API_) -# if defined(__BORLANDC__) -# include // Needed for __errno -# if !defined(_WSPIAPI_H_) -# define _WSPIAPI_H_ -# define ASIO_WSPIAPI_H_DEFINED -# endif // !defined(_WSPIAPI_H_) -# endif // defined(__BORLANDC__) -# include -# include -# if defined(WINAPI_FAMILY) -# if ((WINAPI_FAMILY & WINAPI_PARTITION_DESKTOP) != 0) -# include -# endif // ((WINAPI_FAMILY & WINAPI_PARTITION_DESKTOP) != 0) -# endif // defined(WINAPI_FAMILY) -# if !defined(ASIO_WINDOWS_APP) -# include -# endif // !defined(ASIO_WINDOWS_APP) -# if defined(ASIO_WSPIAPI_H_DEFINED) -# undef _WSPIAPI_H_ -# undef ASIO_WSPIAPI_H_DEFINED -# endif // defined(ASIO_WSPIAPI_H_DEFINED) -# if !defined(ASIO_NO_DEFAULT_LINKED_LIBS) -# if defined(UNDER_CE) -# pragma comment(lib, "ws2.lib") -# elif defined(_MSC_VER) || defined(__BORLANDC__) -# pragma comment(lib, "ws2_32.lib") -# if !defined(ASIO_WINDOWS_APP) -# pragma comment(lib, "mswsock.lib") -# endif // !defined(ASIO_WINDOWS_APP) -# endif // defined(_MSC_VER) || defined(__BORLANDC__) -# endif // !defined(ASIO_NO_DEFAULT_LINKED_LIBS) -# include "asio/detail/old_win_sdk_compat.hpp" -#else -# include -# if (defined(__MACH__) && defined(__APPLE__)) \ - || defined(__FreeBSD__) || defined(__NetBSD__) \ - || defined(__OpenBSD__) || defined(__linux__) \ - || defined(__EMSCRIPTEN__) -# include -# elif !defined(__SYMBIAN32__) -# include -# endif -# include -# include -# include -# if defined(__hpux) -# include -# endif -# if !defined(__hpux) || defined(__SELECT) -# include -# endif -# include -# include -# include -# include -# if !defined(__SYMBIAN32__) -# include -# endif -# include -# include -# include -# include -# if defined(__sun) -# include -# include -# endif -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -#if defined(ASIO_WINDOWS_RUNTIME) -const int max_addr_v4_str_len = 256; -const int max_addr_v6_str_len = 256; -typedef unsigned __int32 u_long_type; -typedef unsigned __int16 u_short_type; -struct in4_addr_type { u_long_type s_addr; }; -struct in4_mreq_type { in4_addr_type imr_multiaddr, imr_interface; }; -struct in6_addr_type { unsigned char s6_addr[16]; }; -struct in6_mreq_type { in6_addr_type ipv6mr_multiaddr; - unsigned long ipv6mr_interface; }; -struct socket_addr_type { int sa_family; }; -struct sockaddr_in4_type { int sin_family; - in4_addr_type sin_addr; u_short_type sin_port; }; -struct sockaddr_in6_type { int sin6_family; - in6_addr_type sin6_addr; u_short_type sin6_port; - u_long_type sin6_flowinfo; u_long_type sin6_scope_id; }; -struct sockaddr_storage_type { int ss_family; - unsigned char ss_bytes[128 - sizeof(int)]; }; -struct addrinfo_type { int ai_flags; - int ai_family, ai_socktype, ai_protocol; - int ai_addrlen; const void* ai_addr; - const char* ai_canonname; addrinfo_type* ai_next; }; -struct linger_type { u_short_type l_onoff, l_linger; }; -typedef u_long_type ioctl_arg_type; -typedef int signed_size_type; -# define ASIO_OS_DEF(c) ASIO_OS_DEF_##c -# define ASIO_OS_DEF_AF_UNSPEC 0 -# define ASIO_OS_DEF_AF_INET 2 -# define ASIO_OS_DEF_AF_INET6 23 -# define ASIO_OS_DEF_SOCK_STREAM 1 -# define ASIO_OS_DEF_SOCK_DGRAM 2 -# define ASIO_OS_DEF_SOCK_RAW 3 -# define ASIO_OS_DEF_SOCK_SEQPACKET 5 -# define ASIO_OS_DEF_IPPROTO_IP 0 -# define ASIO_OS_DEF_IPPROTO_IPV6 41 -# define ASIO_OS_DEF_IPPROTO_TCP 6 -# define ASIO_OS_DEF_IPPROTO_UDP 17 -# define ASIO_OS_DEF_IPPROTO_ICMP 1 -# define ASIO_OS_DEF_IPPROTO_ICMPV6 58 -# define ASIO_OS_DEF_FIONBIO 1 -# define ASIO_OS_DEF_FIONREAD 2 -# define ASIO_OS_DEF_INADDR_ANY 0 -# define ASIO_OS_DEF_MSG_OOB 0x1 -# define ASIO_OS_DEF_MSG_PEEK 0x2 -# define ASIO_OS_DEF_MSG_DONTROUTE 0x4 -# define ASIO_OS_DEF_MSG_EOR 0 // Not supported. -# define ASIO_OS_DEF_SHUT_RD 0x0 -# define ASIO_OS_DEF_SHUT_WR 0x1 -# define ASIO_OS_DEF_SHUT_RDWR 0x2 -# define ASIO_OS_DEF_SOMAXCONN 0x7fffffff -# define ASIO_OS_DEF_SOL_SOCKET 0xffff -# define ASIO_OS_DEF_SO_BROADCAST 0x20 -# define ASIO_OS_DEF_SO_DEBUG 0x1 -# define ASIO_OS_DEF_SO_DONTROUTE 0x10 -# define ASIO_OS_DEF_SO_KEEPALIVE 0x8 -# define ASIO_OS_DEF_SO_LINGER 0x80 -# define ASIO_OS_DEF_SO_OOBINLINE 0x100 -# define ASIO_OS_DEF_SO_SNDBUF 0x1001 -# define ASIO_OS_DEF_SO_RCVBUF 0x1002 -# define ASIO_OS_DEF_SO_SNDLOWAT 0x1003 -# define ASIO_OS_DEF_SO_RCVLOWAT 0x1004 -# define ASIO_OS_DEF_SO_REUSEADDR 0x4 -# define ASIO_OS_DEF_TCP_NODELAY 0x1 -# define ASIO_OS_DEF_IP_MULTICAST_IF 2 -# define ASIO_OS_DEF_IP_MULTICAST_TTL 3 -# define ASIO_OS_DEF_IP_MULTICAST_LOOP 4 -# define ASIO_OS_DEF_IP_ADD_MEMBERSHIP 5 -# define ASIO_OS_DEF_IP_DROP_MEMBERSHIP 6 -# define ASIO_OS_DEF_IP_TTL 7 -# define ASIO_OS_DEF_IPV6_UNICAST_HOPS 4 -# define ASIO_OS_DEF_IPV6_MULTICAST_IF 9 -# define ASIO_OS_DEF_IPV6_MULTICAST_HOPS 10 -# define ASIO_OS_DEF_IPV6_MULTICAST_LOOP 11 -# define ASIO_OS_DEF_IPV6_JOIN_GROUP 12 -# define ASIO_OS_DEF_IPV6_LEAVE_GROUP 13 -# define ASIO_OS_DEF_AI_CANONNAME 0x2 -# define ASIO_OS_DEF_AI_PASSIVE 0x1 -# define ASIO_OS_DEF_AI_NUMERICHOST 0x4 -# define ASIO_OS_DEF_AI_NUMERICSERV 0x8 -# define ASIO_OS_DEF_AI_V4MAPPED 0x800 -# define ASIO_OS_DEF_AI_ALL 0x100 -# define ASIO_OS_DEF_AI_ADDRCONFIG 0x400 -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) -typedef SOCKET socket_type; -const SOCKET invalid_socket = INVALID_SOCKET; -const int socket_error_retval = SOCKET_ERROR; -const int max_addr_v4_str_len = 256; -const int max_addr_v6_str_len = 256; -typedef sockaddr socket_addr_type; -typedef in_addr in4_addr_type; -typedef ip_mreq in4_mreq_type; -typedef sockaddr_in sockaddr_in4_type; -# if defined(ASIO_HAS_OLD_WIN_SDK) -typedef in6_addr_emulation in6_addr_type; -typedef ipv6_mreq_emulation in6_mreq_type; -typedef sockaddr_in6_emulation sockaddr_in6_type; -typedef sockaddr_storage_emulation sockaddr_storage_type; -typedef addrinfo_emulation addrinfo_type; -# else -typedef in6_addr in6_addr_type; -typedef ipv6_mreq in6_mreq_type; -typedef sockaddr_in6 sockaddr_in6_type; -typedef sockaddr_storage sockaddr_storage_type; -typedef addrinfo addrinfo_type; -# endif -typedef ::linger linger_type; -typedef unsigned long ioctl_arg_type; -typedef u_long u_long_type; -typedef u_short u_short_type; -typedef int signed_size_type; -# define ASIO_OS_DEF(c) ASIO_OS_DEF_##c -# define ASIO_OS_DEF_AF_UNSPEC AF_UNSPEC -# define ASIO_OS_DEF_AF_INET AF_INET -# define ASIO_OS_DEF_AF_INET6 AF_INET6 -# define ASIO_OS_DEF_SOCK_STREAM SOCK_STREAM -# define ASIO_OS_DEF_SOCK_DGRAM SOCK_DGRAM -# define ASIO_OS_DEF_SOCK_RAW SOCK_RAW -# define ASIO_OS_DEF_SOCK_SEQPACKET SOCK_SEQPACKET -# define ASIO_OS_DEF_IPPROTO_IP IPPROTO_IP -# define ASIO_OS_DEF_IPPROTO_IPV6 IPPROTO_IPV6 -# define ASIO_OS_DEF_IPPROTO_TCP IPPROTO_TCP -# define ASIO_OS_DEF_IPPROTO_UDP IPPROTO_UDP -# define ASIO_OS_DEF_IPPROTO_ICMP IPPROTO_ICMP -# define ASIO_OS_DEF_IPPROTO_ICMPV6 IPPROTO_ICMPV6 -# define ASIO_OS_DEF_FIONBIO FIONBIO -# define ASIO_OS_DEF_FIONREAD FIONREAD -# define ASIO_OS_DEF_INADDR_ANY INADDR_ANY -# define ASIO_OS_DEF_MSG_OOB MSG_OOB -# define ASIO_OS_DEF_MSG_PEEK MSG_PEEK -# define ASIO_OS_DEF_MSG_DONTROUTE MSG_DONTROUTE -# define ASIO_OS_DEF_MSG_EOR 0 // Not supported on Windows. -# define ASIO_OS_DEF_SHUT_RD SD_RECEIVE -# define ASIO_OS_DEF_SHUT_WR SD_SEND -# define ASIO_OS_DEF_SHUT_RDWR SD_BOTH -# define ASIO_OS_DEF_SOMAXCONN SOMAXCONN -# define ASIO_OS_DEF_SOL_SOCKET SOL_SOCKET -# define ASIO_OS_DEF_SO_BROADCAST SO_BROADCAST -# define ASIO_OS_DEF_SO_DEBUG SO_DEBUG -# define ASIO_OS_DEF_SO_DONTROUTE SO_DONTROUTE -# define ASIO_OS_DEF_SO_KEEPALIVE SO_KEEPALIVE -# define ASIO_OS_DEF_SO_LINGER SO_LINGER -# define ASIO_OS_DEF_SO_OOBINLINE SO_OOBINLINE -# define ASIO_OS_DEF_SO_SNDBUF SO_SNDBUF -# define ASIO_OS_DEF_SO_RCVBUF SO_RCVBUF -# define ASIO_OS_DEF_SO_SNDLOWAT SO_SNDLOWAT -# define ASIO_OS_DEF_SO_RCVLOWAT SO_RCVLOWAT -# define ASIO_OS_DEF_SO_REUSEADDR SO_REUSEADDR -# define ASIO_OS_DEF_TCP_NODELAY TCP_NODELAY -# define ASIO_OS_DEF_IP_MULTICAST_IF IP_MULTICAST_IF -# define ASIO_OS_DEF_IP_MULTICAST_TTL IP_MULTICAST_TTL -# define ASIO_OS_DEF_IP_MULTICAST_LOOP IP_MULTICAST_LOOP -# define ASIO_OS_DEF_IP_ADD_MEMBERSHIP IP_ADD_MEMBERSHIP -# define ASIO_OS_DEF_IP_DROP_MEMBERSHIP IP_DROP_MEMBERSHIP -# define ASIO_OS_DEF_IP_TTL IP_TTL -# define ASIO_OS_DEF_IPV6_UNICAST_HOPS IPV6_UNICAST_HOPS -# define ASIO_OS_DEF_IPV6_MULTICAST_IF IPV6_MULTICAST_IF -# define ASIO_OS_DEF_IPV6_MULTICAST_HOPS IPV6_MULTICAST_HOPS -# define ASIO_OS_DEF_IPV6_MULTICAST_LOOP IPV6_MULTICAST_LOOP -# define ASIO_OS_DEF_IPV6_JOIN_GROUP IPV6_JOIN_GROUP -# define ASIO_OS_DEF_IPV6_LEAVE_GROUP IPV6_LEAVE_GROUP -# define ASIO_OS_DEF_AI_CANONNAME AI_CANONNAME -# define ASIO_OS_DEF_AI_PASSIVE AI_PASSIVE -# define ASIO_OS_DEF_AI_NUMERICHOST AI_NUMERICHOST -# if defined(AI_NUMERICSERV) -# define ASIO_OS_DEF_AI_NUMERICSERV AI_NUMERICSERV -# else -# define ASIO_OS_DEF_AI_NUMERICSERV 0 -# endif -# if defined(AI_V4MAPPED) -# define ASIO_OS_DEF_AI_V4MAPPED AI_V4MAPPED -# else -# define ASIO_OS_DEF_AI_V4MAPPED 0 -# endif -# if defined(AI_ALL) -# define ASIO_OS_DEF_AI_ALL AI_ALL -# else -# define ASIO_OS_DEF_AI_ALL 0 -# endif -# if defined(AI_ADDRCONFIG) -# define ASIO_OS_DEF_AI_ADDRCONFIG AI_ADDRCONFIG -# else -# define ASIO_OS_DEF_AI_ADDRCONFIG 0 -# endif -# if defined (_WIN32_WINNT) -const int max_iov_len = 64; -# else -const int max_iov_len = 16; -# endif -#else -typedef int socket_type; -const int invalid_socket = -1; -const int socket_error_retval = -1; -const int max_addr_v4_str_len = INET_ADDRSTRLEN; -#if defined(INET6_ADDRSTRLEN) -const int max_addr_v6_str_len = INET6_ADDRSTRLEN + 1 + IF_NAMESIZE; -#else // defined(INET6_ADDRSTRLEN) -const int max_addr_v6_str_len = 256; -#endif // defined(INET6_ADDRSTRLEN) -typedef sockaddr socket_addr_type; -typedef in_addr in4_addr_type; -# if defined(__hpux) -// HP-UX doesn't provide ip_mreq when _XOPEN_SOURCE_EXTENDED is defined. -struct in4_mreq_type -{ - struct in_addr imr_multiaddr; - struct in_addr imr_interface; -}; -# else -typedef ip_mreq in4_mreq_type; -# endif -typedef sockaddr_in sockaddr_in4_type; -typedef in6_addr in6_addr_type; -typedef ipv6_mreq in6_mreq_type; -typedef sockaddr_in6 sockaddr_in6_type; -typedef sockaddr_storage sockaddr_storage_type; -typedef sockaddr_un sockaddr_un_type; -typedef addrinfo addrinfo_type; -typedef ::linger linger_type; -typedef int ioctl_arg_type; -typedef uint32_t u_long_type; -typedef uint16_t u_short_type; -#if defined(ASIO_HAS_SSIZE_T) -typedef ssize_t signed_size_type; -#else // defined(ASIO_HAS_SSIZE_T) -typedef int signed_size_type; -#endif // defined(ASIO_HAS_SSIZE_T) -# define ASIO_OS_DEF(c) ASIO_OS_DEF_##c -# define ASIO_OS_DEF_AF_UNSPEC AF_UNSPEC -# define ASIO_OS_DEF_AF_INET AF_INET -# define ASIO_OS_DEF_AF_INET6 AF_INET6 -# define ASIO_OS_DEF_SOCK_STREAM SOCK_STREAM -# define ASIO_OS_DEF_SOCK_DGRAM SOCK_DGRAM -# define ASIO_OS_DEF_SOCK_RAW SOCK_RAW -# define ASIO_OS_DEF_SOCK_SEQPACKET SOCK_SEQPACKET -# define ASIO_OS_DEF_IPPROTO_IP IPPROTO_IP -# define ASIO_OS_DEF_IPPROTO_IPV6 IPPROTO_IPV6 -# define ASIO_OS_DEF_IPPROTO_TCP IPPROTO_TCP -# define ASIO_OS_DEF_IPPROTO_UDP IPPROTO_UDP -# define ASIO_OS_DEF_IPPROTO_ICMP IPPROTO_ICMP -# define ASIO_OS_DEF_IPPROTO_ICMPV6 IPPROTO_ICMPV6 -# define ASIO_OS_DEF_FIONBIO FIONBIO -# define ASIO_OS_DEF_FIONREAD FIONREAD -# define ASIO_OS_DEF_INADDR_ANY INADDR_ANY -# define ASIO_OS_DEF_MSG_OOB MSG_OOB -# define ASIO_OS_DEF_MSG_PEEK MSG_PEEK -# define ASIO_OS_DEF_MSG_DONTROUTE MSG_DONTROUTE -# define ASIO_OS_DEF_MSG_EOR MSG_EOR -# define ASIO_OS_DEF_SHUT_RD SHUT_RD -# define ASIO_OS_DEF_SHUT_WR SHUT_WR -# define ASIO_OS_DEF_SHUT_RDWR SHUT_RDWR -# define ASIO_OS_DEF_SOMAXCONN SOMAXCONN -# define ASIO_OS_DEF_SOL_SOCKET SOL_SOCKET -# define ASIO_OS_DEF_SO_BROADCAST SO_BROADCAST -# define ASIO_OS_DEF_SO_DEBUG SO_DEBUG -# define ASIO_OS_DEF_SO_DONTROUTE SO_DONTROUTE -# define ASIO_OS_DEF_SO_KEEPALIVE SO_KEEPALIVE -# define ASIO_OS_DEF_SO_LINGER SO_LINGER -# define ASIO_OS_DEF_SO_OOBINLINE SO_OOBINLINE -# define ASIO_OS_DEF_SO_SNDBUF SO_SNDBUF -# define ASIO_OS_DEF_SO_RCVBUF SO_RCVBUF -# define ASIO_OS_DEF_SO_SNDLOWAT SO_SNDLOWAT -# define ASIO_OS_DEF_SO_RCVLOWAT SO_RCVLOWAT -# define ASIO_OS_DEF_SO_REUSEADDR SO_REUSEADDR -# define ASIO_OS_DEF_TCP_NODELAY TCP_NODELAY -# define ASIO_OS_DEF_IP_MULTICAST_IF IP_MULTICAST_IF -# define ASIO_OS_DEF_IP_MULTICAST_TTL IP_MULTICAST_TTL -# define ASIO_OS_DEF_IP_MULTICAST_LOOP IP_MULTICAST_LOOP -# define ASIO_OS_DEF_IP_ADD_MEMBERSHIP IP_ADD_MEMBERSHIP -# define ASIO_OS_DEF_IP_DROP_MEMBERSHIP IP_DROP_MEMBERSHIP -# define ASIO_OS_DEF_IP_TTL IP_TTL -# define ASIO_OS_DEF_IPV6_UNICAST_HOPS IPV6_UNICAST_HOPS -# define ASIO_OS_DEF_IPV6_MULTICAST_IF IPV6_MULTICAST_IF -# define ASIO_OS_DEF_IPV6_MULTICAST_HOPS IPV6_MULTICAST_HOPS -# define ASIO_OS_DEF_IPV6_MULTICAST_LOOP IPV6_MULTICAST_LOOP -# define ASIO_OS_DEF_IPV6_JOIN_GROUP IPV6_JOIN_GROUP -# define ASIO_OS_DEF_IPV6_LEAVE_GROUP IPV6_LEAVE_GROUP -# define ASIO_OS_DEF_AI_CANONNAME AI_CANONNAME -# define ASIO_OS_DEF_AI_PASSIVE AI_PASSIVE -# define ASIO_OS_DEF_AI_NUMERICHOST AI_NUMERICHOST -# if defined(AI_NUMERICSERV) -# define ASIO_OS_DEF_AI_NUMERICSERV AI_NUMERICSERV -# else -# define ASIO_OS_DEF_AI_NUMERICSERV 0 -# endif -// Note: QNX Neutrino 6.3 defines AI_V4MAPPED, AI_ALL and AI_ADDRCONFIG but -// does not implement them. Therefore they are specifically excluded here. -# if defined(AI_V4MAPPED) && !defined(__QNXNTO__) -# define ASIO_OS_DEF_AI_V4MAPPED AI_V4MAPPED -# else -# define ASIO_OS_DEF_AI_V4MAPPED 0 -# endif -# if defined(AI_ALL) && !defined(__QNXNTO__) -# define ASIO_OS_DEF_AI_ALL AI_ALL -# else -# define ASIO_OS_DEF_AI_ALL 0 -# endif -# if defined(AI_ADDRCONFIG) && !defined(__QNXNTO__) -# define ASIO_OS_DEF_AI_ADDRCONFIG AI_ADDRCONFIG -# else -# define ASIO_OS_DEF_AI_ADDRCONFIG 0 -# endif -# if defined(IOV_MAX) -const int max_iov_len = IOV_MAX; -# else -// POSIX platforms are not required to define IOV_MAX. -const int max_iov_len = 16; -# endif -#endif -const int custom_socket_option_level = 0xA5100000; -const int enable_connection_aborted_option = 1; -const int always_fail_option = 2; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_SOCKET_TYPES_HPP diff --git a/scout_sdk/asio/asio/detail/solaris_fenced_block.hpp b/scout_sdk/asio/asio/detail/solaris_fenced_block.hpp deleted file mode 100644 index d48f6a3..0000000 --- a/scout_sdk/asio/asio/detail/solaris_fenced_block.hpp +++ /dev/null @@ -1,62 +0,0 @@ -// -// detail/solaris_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_SOLARIS_FENCED_BLOCK_HPP -#define ASIO_DETAIL_SOLARIS_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(__sun) - -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class solaris_fenced_block - : private noncopyable -{ -public: - enum half_t { half }; - enum full_t { full }; - - // Constructor for a half fenced block. - explicit solaris_fenced_block(half_t) - { - } - - // Constructor for a full fenced block. - explicit solaris_fenced_block(full_t) - { - membar_consumer(); - } - - // Destructor. - ~solaris_fenced_block() - { - membar_producer(); - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(__sun) - -#endif // ASIO_DETAIL_SOLARIS_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/static_mutex.hpp b/scout_sdk/asio/asio/detail/static_mutex.hpp deleted file mode 100644 index 8f2bc02..0000000 --- a/scout_sdk/asio/asio/detail/static_mutex.hpp +++ /dev/null @@ -1,52 +0,0 @@ -// -// detail/static_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STATIC_MUTEX_HPP -#define ASIO_DETAIL_STATIC_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) -# include "asio/detail/null_static_mutex.hpp" -#elif defined(ASIO_WINDOWS) -# include "asio/detail/win_static_mutex.hpp" -#elif defined(ASIO_HAS_PTHREADS) -# include "asio/detail/posix_static_mutex.hpp" -#elif defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) -# include "asio/detail/std_static_mutex.hpp" -#else -# error Only Windows and POSIX are supported! -#endif - -namespace asio { -namespace detail { - -#if !defined(ASIO_HAS_THREADS) -typedef null_static_mutex static_mutex; -# define ASIO_STATIC_MUTEX_INIT ASIO_NULL_STATIC_MUTEX_INIT -#elif defined(ASIO_WINDOWS) -typedef win_static_mutex static_mutex; -# define ASIO_STATIC_MUTEX_INIT ASIO_WIN_STATIC_MUTEX_INIT -#elif defined(ASIO_HAS_PTHREADS) -typedef posix_static_mutex static_mutex; -# define ASIO_STATIC_MUTEX_INIT ASIO_POSIX_STATIC_MUTEX_INIT -#elif defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) -typedef std_static_mutex static_mutex; -# define ASIO_STATIC_MUTEX_INIT ASIO_STD_STATIC_MUTEX_INIT -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_STATIC_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/std_event.hpp b/scout_sdk/asio/asio/detail/std_event.hpp deleted file mode 100644 index 5639ecd..0000000 --- a/scout_sdk/asio/asio/detail/std_event.hpp +++ /dev/null @@ -1,176 +0,0 @@ -// -// detail/std_event.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STD_EVENT_HPP -#define ASIO_DETAIL_STD_EVENT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) - -#include -#include -#include "asio/detail/assert.hpp" -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class std_event - : private noncopyable -{ -public: - // Constructor. - std_event() - : state_(0) - { - } - - // Destructor. - ~std_event() - { - } - - // Signal the event. (Retained for backward compatibility.) - template - void signal(Lock& lock) - { - this->signal_all(lock); - } - - // Signal all waiters. - template - void signal_all(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - (void)lock; - state_ |= 1; - cond_.notify_all(); - } - - // Unlock the mutex and signal one waiter. - template - void unlock_and_signal_one(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - state_ |= 1; - bool have_waiters = (state_ > 1); - lock.unlock(); - if (have_waiters) - cond_.notify_one(); - } - - // If there's a waiter, unlock the mutex and signal it. - template - bool maybe_unlock_and_signal_one(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - state_ |= 1; - if (state_ > 1) - { - lock.unlock(); - cond_.notify_one(); - return true; - } - return false; - } - - // Reset the event. - template - void clear(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - (void)lock; - state_ &= ~std::size_t(1); - } - - // Wait for the event to become signalled. - template - void wait(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - unique_lock_adapter u_lock(lock); - while ((state_ & 1) == 0) - { - waiter w(state_); - cond_.wait(u_lock.unique_lock_); - } - } - - // Timed wait for the event to become signalled. - template - bool wait_for_usec(Lock& lock, long usec) - { - ASIO_ASSERT(lock.locked()); - unique_lock_adapter u_lock(lock); - if ((state_ & 1) == 0) - { - waiter w(state_); - cond_.wait_for(u_lock.unique_lock_, std::chrono::microseconds(usec)); - } - return (state_ & 1) != 0; - } - -private: - // Helper class to temporarily adapt a scoped_lock into a unique_lock so that - // it can be passed to std::condition_variable::wait(). - struct unique_lock_adapter - { - template - explicit unique_lock_adapter(Lock& lock) - : unique_lock_(lock.mutex().mutex_, std::adopt_lock) - { - } - - ~unique_lock_adapter() - { - unique_lock_.release(); - } - - std::unique_lock unique_lock_; - }; - - // Helper to increment and decrement the state to track outstanding waiters. - class waiter - { - public: - explicit waiter(std::size_t& state) - : state_(state) - { - state_ += 2; - } - - ~waiter() - { - state_ -= 2; - } - - private: - std::size_t& state_; - }; - - std::condition_variable cond_; - std::size_t state_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) - -#endif // ASIO_DETAIL_STD_EVENT_HPP diff --git a/scout_sdk/asio/asio/detail/std_fenced_block.hpp b/scout_sdk/asio/asio/detail/std_fenced_block.hpp deleted file mode 100644 index 0d8ade0..0000000 --- a/scout_sdk/asio/asio/detail/std_fenced_block.hpp +++ /dev/null @@ -1,62 +0,0 @@ -// -// detail/std_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STD_FENCED_BLOCK_HPP -#define ASIO_DETAIL_STD_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_ATOMIC) - -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class std_fenced_block - : private noncopyable -{ -public: - enum half_t { half }; - enum full_t { full }; - - // Constructor for a half fenced block. - explicit std_fenced_block(half_t) - { - } - - // Constructor for a full fenced block. - explicit std_fenced_block(full_t) - { - std::atomic_thread_fence(std::memory_order_acquire); - } - - // Destructor. - ~std_fenced_block() - { - std::atomic_thread_fence(std::memory_order_release); - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_STD_ATOMIC) - -#endif // ASIO_DETAIL_STD_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/std_global.hpp b/scout_sdk/asio/asio/detail/std_global.hpp deleted file mode 100644 index 0c5173e..0000000 --- a/scout_sdk/asio/asio/detail/std_global.hpp +++ /dev/null @@ -1,70 +0,0 @@ -// -// detail/std_global.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STD_GLOBAL_HPP -#define ASIO_DETAIL_STD_GLOBAL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_CALL_ONCE) - -#include -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct std_global_impl -{ - // Helper function to perform initialisation. - static void do_init() - { - instance_.ptr_ = new T; - } - - // Destructor automatically cleans up the global. - ~std_global_impl() - { - delete ptr_; - } - - static std::once_flag init_once_; - static std_global_impl instance_; - T* ptr_; -}; - -template -std::once_flag std_global_impl::init_once_; - -template -std_global_impl std_global_impl::instance_; - -template -T& std_global() -{ - std::call_once(std_global_impl::init_once_, &std_global_impl::do_init); - return *std_global_impl::instance_.ptr_; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_STD_CALL_ONCE) - -#endif // ASIO_DETAIL_STD_GLOBAL_HPP diff --git a/scout_sdk/asio/asio/detail/std_mutex.hpp b/scout_sdk/asio/asio/detail/std_mutex.hpp deleted file mode 100644 index 159049e..0000000 --- a/scout_sdk/asio/asio/detail/std_mutex.hpp +++ /dev/null @@ -1,73 +0,0 @@ -// -// detail/std_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STD_MUTEX_HPP -#define ASIO_DETAIL_STD_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) - -#include -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class std_event; - -class std_mutex - : private noncopyable -{ -public: - typedef asio::detail::scoped_lock scoped_lock; - - // Constructor. - std_mutex() - { - } - - // Destructor. - ~std_mutex() - { - } - - // Lock the mutex. - void lock() - { - mutex_.lock(); - } - - // Unlock the mutex. - void unlock() - { - mutex_.unlock(); - } - -private: - friend class std_event; - std::mutex mutex_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) - -#endif // ASIO_DETAIL_STD_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/std_static_mutex.hpp b/scout_sdk/asio/asio/detail/std_static_mutex.hpp deleted file mode 100644 index e9c9dc5..0000000 --- a/scout_sdk/asio/asio/detail/std_static_mutex.hpp +++ /dev/null @@ -1,81 +0,0 @@ -// -// detail/std_static_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STD_STATIC_MUTEX_HPP -#define ASIO_DETAIL_STD_STATIC_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) - -#include -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class std_event; - -class std_static_mutex - : private noncopyable -{ -public: - typedef asio::detail::scoped_lock scoped_lock; - - // Constructor. - std_static_mutex(int) - { - } - - // Destructor. - ~std_static_mutex() - { - } - - // Initialise the mutex. - void init() - { - // Nothing to do. - } - - // Lock the mutex. - void lock() - { - mutex_.lock(); - } - - // Unlock the mutex. - void unlock() - { - mutex_.unlock(); - } - -private: - friend class std_event; - std::mutex mutex_; -}; - -#define ASIO_STD_STATIC_MUTEX_INIT 0 - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_STD_MUTEX_AND_CONDVAR) - -#endif // ASIO_DETAIL_STD_STATIC_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/std_thread.hpp b/scout_sdk/asio/asio/detail/std_thread.hpp deleted file mode 100644 index a240308..0000000 --- a/scout_sdk/asio/asio/detail/std_thread.hpp +++ /dev/null @@ -1,71 +0,0 @@ -// -// detail/std_thread.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STD_THREAD_HPP -#define ASIO_DETAIL_STD_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_THREAD) - -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class std_thread - : private noncopyable -{ -public: - // Constructor. - template - std_thread(Function f, unsigned int = 0) - : thread_(f) - { - } - - // Destructor. - ~std_thread() - { - join(); - } - - // Wait for the thread to exit. - void join() - { - if (thread_.joinable()) - thread_.join(); - } - - // Get number of CPUs. - static std::size_t hardware_concurrency() - { - return std::thread::hardware_concurrency(); - } - -private: - std::thread thread_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_STD_THREAD) - -#endif // ASIO_DETAIL_STD_THREAD_HPP diff --git a/scout_sdk/asio/asio/detail/strand_executor_service.hpp b/scout_sdk/asio/asio/detail/strand_executor_service.hpp deleted file mode 100644 index 67e8427..0000000 --- a/scout_sdk/asio/asio/detail/strand_executor_service.hpp +++ /dev/null @@ -1,142 +0,0 @@ -// -// detail/strand_executor_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STRAND_EXECUTOR_SERVICE_HPP -#define ASIO_DETAIL_STRAND_EXECUTOR_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/atomic_count.hpp" -#include "asio/detail/executor_op.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/scheduler_operation.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Default service implementation for a strand. -class strand_executor_service - : public execution_context_service_base -{ -public: - // The underlying implementation of a strand. - class strand_impl - { - public: - ASIO_DECL ~strand_impl(); - - private: - friend class strand_executor_service; - - // Mutex to protect access to internal data. - mutex* mutex_; - - // Indicates whether the strand is currently "locked" by a handler. This - // means that there is a handler upcall in progress, or that the strand - // itself has been scheduled in order to invoke some pending handlers. - bool locked_; - - // Indicates that the strand has been shut down and will accept no further - // handlers. - bool shutdown_; - - // The handlers that are waiting on the strand but should not be run until - // after the next time the strand is scheduled. This queue must only be - // modified while the mutex is locked. - op_queue waiting_queue_; - - // The handlers that are ready to be run. Logically speaking, these are the - // handlers that hold the strand's lock. The ready queue is only modified - // from within the strand and so may be accessed without locking the mutex. - op_queue ready_queue_; - - // Pointers to adjacent handle implementations in linked list. - strand_impl* next_; - strand_impl* prev_; - - // The strand service in where the implementation is held. - strand_executor_service* service_; - }; - - typedef shared_ptr implementation_type; - - // Construct a new strand service for the specified context. - ASIO_DECL explicit strand_executor_service(execution_context& context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Create a new strand_executor implementation. - ASIO_DECL implementation_type create_implementation(); - - // Request invocation of the given function. - template - static void dispatch(const implementation_type& impl, Executor& ex, - ASIO_MOVE_ARG(Function) function, const Allocator& a); - - // Request invocation of the given function and return immediately. - template - static void post(const implementation_type& impl, Executor& ex, - ASIO_MOVE_ARG(Function) function, const Allocator& a); - - // Request invocation of the given function and return immediately. - template - static void defer(const implementation_type& impl, Executor& ex, - ASIO_MOVE_ARG(Function) function, const Allocator& a); - - // Determine whether the strand is running in the current thread. - ASIO_DECL static bool running_in_this_thread( - const implementation_type& impl); - -private: - friend class strand_impl; - template class invoker; - - // Adds a function to the strand. Returns true if it acquires the lock. - ASIO_DECL static bool enqueue(const implementation_type& impl, - scheduler_operation* op); - - // Mutex to protect access to the service-wide state. - mutex mutex_; - - // Number of mutexes shared between all strand objects. - enum { num_mutexes = 193 }; - - // Pool of mutexes. - scoped_ptr mutexes_[num_mutexes]; - - // Extra value used when hashing to prevent recycled memory locations from - // getting the same mutex. - std::size_t salt_; - - // The head of a linked list of all implementations. - strand_impl* impl_list_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/strand_executor_service.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/strand_executor_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_STRAND_EXECUTOR_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/strand_service.hpp b/scout_sdk/asio/asio/detail/strand_service.hpp deleted file mode 100644 index edc14a0..0000000 --- a/scout_sdk/asio/asio/detail/strand_service.hpp +++ /dev/null @@ -1,142 +0,0 @@ -// -// detail/strand_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STRAND_SERVICE_HPP -#define ASIO_DETAIL_STRAND_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/scoped_ptr.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Default service implementation for a strand. -class strand_service - : public asio::detail::service_base -{ -private: - // Helper class to re-post the strand on exit. - struct on_do_complete_exit; - - // Helper class to re-post the strand on exit. - struct on_dispatch_exit; - -public: - - // The underlying implementation of a strand. - class strand_impl - : public operation - { - public: - strand_impl(); - - private: - // Only this service will have access to the internal values. - friend class strand_service; - friend struct on_do_complete_exit; - friend struct on_dispatch_exit; - - // Mutex to protect access to internal data. - asio::detail::mutex mutex_; - - // Indicates whether the strand is currently "locked" by a handler. This - // means that there is a handler upcall in progress, or that the strand - // itself has been scheduled in order to invoke some pending handlers. - bool locked_; - - // The handlers that are waiting on the strand but should not be run until - // after the next time the strand is scheduled. This queue must only be - // modified while the mutex is locked. - op_queue waiting_queue_; - - // The handlers that are ready to be run. Logically speaking, these are the - // handlers that hold the strand's lock. The ready queue is only modified - // from within the strand and so may be accessed without locking the mutex. - op_queue ready_queue_; - }; - - typedef strand_impl* implementation_type; - - // Construct a new strand service for the specified io_context. - ASIO_DECL explicit strand_service(asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Construct a new strand implementation. - ASIO_DECL void construct(implementation_type& impl); - - // Request the io_context to invoke the given handler. - template - void dispatch(implementation_type& impl, Handler& handler); - - // Request the io_context to invoke the given handler and return immediately. - template - void post(implementation_type& impl, Handler& handler); - - // Determine whether the strand is running in the current thread. - ASIO_DECL bool running_in_this_thread( - const implementation_type& impl) const; - -private: - // Helper function to dispatch a handler. Returns true if the handler should - // be dispatched immediately. - ASIO_DECL bool do_dispatch(implementation_type& impl, operation* op); - - // Helper fiunction to post a handler. - ASIO_DECL void do_post(implementation_type& impl, - operation* op, bool is_continuation); - - ASIO_DECL static void do_complete(void* owner, - operation* base, const asio::error_code& ec, - std::size_t bytes_transferred); - - // The io_context implementation used to post completions. - io_context_impl& io_context_; - - // Mutex to protect access to the array of implementations. - asio::detail::mutex mutex_; - - // Number of implementations shared between all strand objects. -#if defined(ASIO_STRAND_IMPLEMENTATIONS) - enum { num_implementations = ASIO_STRAND_IMPLEMENTATIONS }; -#else // defined(ASIO_STRAND_IMPLEMENTATIONS) - enum { num_implementations = 193 }; -#endif // defined(ASIO_STRAND_IMPLEMENTATIONS) - - // Pool of implementations. - scoped_ptr implementations_[num_implementations]; - - // Extra value used when hashing to prevent recycled memory locations from - // getting the same strand implementation. - std::size_t salt_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/strand_service.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/strand_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_STRAND_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/string_view.hpp b/scout_sdk/asio/asio/detail/string_view.hpp deleted file mode 100644 index f09cebc..0000000 --- a/scout_sdk/asio/asio/detail/string_view.hpp +++ /dev/null @@ -1,47 +0,0 @@ -// -// detail/string_view.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_STRING_VIEW_HPP -#define ASIO_DETAIL_STRING_VIEW_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STRING_VIEW) - -#if defined(ASIO_HAS_STD_STRING_VIEW) -# include -#elif defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) -# include -#else // defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) -# error ASIO_HAS_STRING_VIEW is set but no string_view is available -#endif // defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) - -namespace asio { - -#if defined(ASIO_HAS_STD_STRING_VIEW) -using std::basic_string_view; -using std::string_view; -#elif defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) -using std::experimental::basic_string_view; -using std::experimental::string_view; -#endif // defined(ASIO_HAS_STD_EXPERIMENTAL_STRING_VIEW) - -} // namespace asio - -# define ASIO_STRING_VIEW_PARAM asio::string_view -#else // defined(ASIO_HAS_STRING_VIEW) -# define ASIO_STRING_VIEW_PARAM const std::string& -#endif // defined(ASIO_HAS_STRING_VIEW) - -#endif // ASIO_DETAIL_STRING_VIEW_HPP diff --git a/scout_sdk/asio/asio/detail/thread.hpp b/scout_sdk/asio/asio/detail/thread.hpp deleted file mode 100644 index ea556db..0000000 --- a/scout_sdk/asio/asio/detail/thread.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// -// detail/thread.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_THREAD_HPP -#define ASIO_DETAIL_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) -# include "asio/detail/null_thread.hpp" -#elif defined(ASIO_WINDOWS) -# if defined(UNDER_CE) -# include "asio/detail/wince_thread.hpp" -# elif defined(ASIO_WINDOWS_APP) -# include "asio/detail/winapp_thread.hpp" -# else -# include "asio/detail/win_thread.hpp" -# endif -#elif defined(ASIO_HAS_PTHREADS) -# include "asio/detail/posix_thread.hpp" -#elif defined(ASIO_HAS_STD_THREAD) -# include "asio/detail/std_thread.hpp" -#else -# error Only Windows, POSIX and std::thread are supported! -#endif - -namespace asio { -namespace detail { - -#if !defined(ASIO_HAS_THREADS) -typedef null_thread thread; -#elif defined(ASIO_WINDOWS) -# if defined(UNDER_CE) -typedef wince_thread thread; -# elif defined(ASIO_WINDOWS_APP) -typedef winapp_thread thread; -# else -typedef win_thread thread; -# endif -#elif defined(ASIO_HAS_PTHREADS) -typedef posix_thread thread; -#elif defined(ASIO_HAS_STD_THREAD) -typedef std_thread thread; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_THREAD_HPP diff --git a/scout_sdk/asio/asio/detail/thread_context.hpp b/scout_sdk/asio/asio/detail/thread_context.hpp deleted file mode 100644 index 88b4f31..0000000 --- a/scout_sdk/asio/asio/detail/thread_context.hpp +++ /dev/null @@ -1,42 +0,0 @@ -// -// detail/thread_context.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_THREAD_CONTEXT_HPP -#define ASIO_DETAIL_THREAD_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include -#include -#include "asio/detail/call_stack.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class thread_info_base; - -// Base class for things that manage threads (scheduler, win_iocp_io_context). -class thread_context -{ -public: - // Per-thread call stack to track the state of each thread in the context. - typedef call_stack thread_call_stack; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_THREAD_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/detail/thread_group.hpp b/scout_sdk/asio/asio/detail/thread_group.hpp deleted file mode 100644 index 1e400b0..0000000 --- a/scout_sdk/asio/asio/detail/thread_group.hpp +++ /dev/null @@ -1,89 +0,0 @@ -// -// detail/thread_group.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_THREAD_GROUP_HPP -#define ASIO_DETAIL_THREAD_GROUP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/detail/thread.hpp" - -namespace asio { -namespace detail { - -class thread_group -{ -public: - // Constructor initialises an empty thread group. - thread_group() - : first_(0) - { - } - - // Destructor joins any remaining threads in the group. - ~thread_group() - { - join(); - } - - // Create a new thread in the group. - template - void create_thread(Function f) - { - first_ = new item(f, first_); - } - - // Create new threads in the group. - template - void create_threads(Function f, std::size_t num_threads) - { - for (std::size_t i = 0; i < num_threads; ++i) - create_thread(f); - } - - // Wait for all threads in the group to exit. - void join() - { - while (first_) - { - first_->thread_.join(); - item* tmp = first_; - first_ = first_->next_; - delete tmp; - } - } - -private: - // Structure used to track a single thread in the group. - struct item - { - template - explicit item(Function f, item* next) - : thread_(f), - next_(next) - { - } - - asio::detail::thread thread_; - item* next_; - }; - - // The first thread in the group. - item* first_; -}; - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_THREAD_GROUP_HPP diff --git a/scout_sdk/asio/asio/detail/thread_info_base.hpp b/scout_sdk/asio/asio/detail/thread_info_base.hpp deleted file mode 100644 index 1b22207..0000000 --- a/scout_sdk/asio/asio/detail/thread_info_base.hpp +++ /dev/null @@ -1,121 +0,0 @@ -// -// detail/thread_info_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_THREAD_INFO_BASE_HPP -#define ASIO_DETAIL_THREAD_INFO_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include -#include -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class thread_info_base - : private noncopyable -{ -public: - struct default_tag - { - enum { mem_index = 0 }; - }; - - struct awaitee_tag - { - enum { mem_index = 1 }; - }; - - thread_info_base() - { - for (int i = 0; i < max_mem_index; ++i) - reusable_memory_[i] = 0; - } - - ~thread_info_base() - { - for (int i = 0; i < max_mem_index; ++i) - if (reusable_memory_[i]) - ::operator delete(reusable_memory_[i]); - } - - static void* allocate(thread_info_base* this_thread, std::size_t size) - { - return allocate(default_tag(), this_thread, size); - } - - static void deallocate(thread_info_base* this_thread, - void* pointer, std::size_t size) - { - deallocate(default_tag(), this_thread, pointer, size); - } - - template - static void* allocate(Purpose, thread_info_base* this_thread, - std::size_t size) - { - std::size_t chunks = (size + chunk_size - 1) / chunk_size; - - if (this_thread && this_thread->reusable_memory_[Purpose::mem_index]) - { - void* const pointer = this_thread->reusable_memory_[Purpose::mem_index]; - this_thread->reusable_memory_[Purpose::mem_index] = 0; - - unsigned char* const mem = static_cast(pointer); - if (static_cast(mem[0]) >= chunks) - { - mem[size] = mem[0]; - return pointer; - } - - ::operator delete(pointer); - } - - void* const pointer = ::operator new(chunks * chunk_size + 1); - unsigned char* const mem = static_cast(pointer); - mem[size] = (chunks <= UCHAR_MAX) ? static_cast(chunks) : 0; - return pointer; - } - - template - static void deallocate(Purpose, thread_info_base* this_thread, - void* pointer, std::size_t size) - { - if (size <= chunk_size * UCHAR_MAX) - { - if (this_thread && this_thread->reusable_memory_[Purpose::mem_index] == 0) - { - unsigned char* const mem = static_cast(pointer); - mem[0] = mem[size]; - this_thread->reusable_memory_[Purpose::mem_index] = pointer; - return; - } - } - - ::operator delete(pointer); - } - -private: - enum { chunk_size = 4 }; - enum { max_mem_index = 2 }; - void* reusable_memory_[max_mem_index]; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_THREAD_INFO_BASE_HPP diff --git a/scout_sdk/asio/asio/detail/throw_error.hpp b/scout_sdk/asio/asio/detail/throw_error.hpp deleted file mode 100644 index 5dd8785..0000000 --- a/scout_sdk/asio/asio/detail/throw_error.hpp +++ /dev/null @@ -1,53 +0,0 @@ -// -// detail/throw_error.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_THROW_ERROR_HPP -#define ASIO_DETAIL_THROW_ERROR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/error_code.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -ASIO_DECL void do_throw_error(const asio::error_code& err); - -ASIO_DECL void do_throw_error(const asio::error_code& err, - const char* location); - -inline void throw_error(const asio::error_code& err) -{ - if (err) - do_throw_error(err); -} - -inline void throw_error(const asio::error_code& err, - const char* location) -{ - if (err) - do_throw_error(err, location); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/throw_error.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_THROW_ERROR_HPP diff --git a/scout_sdk/asio/asio/detail/throw_exception.hpp b/scout_sdk/asio/asio/detail/throw_exception.hpp deleted file mode 100644 index f9f7bfb..0000000 --- a/scout_sdk/asio/asio/detail/throw_exception.hpp +++ /dev/null @@ -1,51 +0,0 @@ -// -// detail/throw_exception.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_THROW_EXCEPTION_HPP -#define ASIO_DETAIL_THROW_EXCEPTION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_THROW_EXCEPTION) -# include -#endif // defined(ASIO_BOOST_THROW_EXCEPTION) - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_BOOST_THROW_EXCEPTION) -using boost::throw_exception; -#else // defined(ASIO_HAS_BOOST_THROW_EXCEPTION) - -// Declare the throw_exception function for all targets. -template -void throw_exception(const Exception& e); - -// Only define the throw_exception function when exceptions are enabled. -// Otherwise, it is up to the application to provide a definition of this -// function. -# if !defined(ASIO_NO_EXCEPTIONS) -template -void throw_exception(const Exception& e) -{ - throw e; -} -# endif // !defined(ASIO_NO_EXCEPTIONS) - -#endif // defined(ASIO_HAS_BOOST_THROW_EXCEPTION) - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_THROW_EXCEPTION_HPP diff --git a/scout_sdk/asio/asio/detail/timer_queue.hpp b/scout_sdk/asio/asio/detail/timer_queue.hpp deleted file mode 100644 index 380e779..0000000 --- a/scout_sdk/asio/asio/detail/timer_queue.hpp +++ /dev/null @@ -1,358 +0,0 @@ -// -// detail/timer_queue.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TIMER_QUEUE_HPP -#define ASIO_DETAIL_TIMER_QUEUE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include "asio/detail/cstdint.hpp" -#include "asio/detail/date_time_fwd.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/timer_queue_base.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class timer_queue - : public timer_queue_base -{ -public: - // The time type. - typedef typename Time_Traits::time_type time_type; - - // The duration type. - typedef typename Time_Traits::duration_type duration_type; - - // Per-timer data. - class per_timer_data - { - public: - per_timer_data() : - heap_index_((std::numeric_limits::max)()), - next_(0), prev_(0) - { - } - - private: - friend class timer_queue; - - // The operations waiting on the timer. - op_queue op_queue_; - - // The index of the timer in the heap. - std::size_t heap_index_; - - // Pointers to adjacent timers in a linked list. - per_timer_data* next_; - per_timer_data* prev_; - }; - - // Constructor. - timer_queue() - : timers_(), - heap_() - { - } - - // Add a new timer to the queue. Returns true if this is the timer that is - // earliest in the queue, in which case the reactor's event demultiplexing - // function call may need to be interrupted and restarted. - bool enqueue_timer(const time_type& time, per_timer_data& timer, wait_op* op) - { - // Enqueue the timer object. - if (timer.prev_ == 0 && &timer != timers_) - { - if (this->is_positive_infinity(time)) - { - // No heap entry is required for timers that never expire. - timer.heap_index_ = (std::numeric_limits::max)(); - } - else - { - // Put the new timer at the correct position in the heap. This is done - // first since push_back() can throw due to allocation failure. - timer.heap_index_ = heap_.size(); - heap_entry entry = { time, &timer }; - heap_.push_back(entry); - up_heap(heap_.size() - 1); - } - - // Insert the new timer into the linked list of active timers. - timer.next_ = timers_; - timer.prev_ = 0; - if (timers_) - timers_->prev_ = &timer; - timers_ = &timer; - } - - // Enqueue the individual timer operation. - timer.op_queue_.push(op); - - // Interrupt reactor only if newly added timer is first to expire. - return timer.heap_index_ == 0 && timer.op_queue_.front() == op; - } - - // Whether there are no timers in the queue. - virtual bool empty() const - { - return timers_ == 0; - } - - // Get the time for the timer that is earliest in the queue. - virtual long wait_duration_msec(long max_duration) const - { - if (heap_.empty()) - return max_duration; - - return this->to_msec( - Time_Traits::to_posix_duration( - Time_Traits::subtract(heap_[0].time_, Time_Traits::now())), - max_duration); - } - - // Get the time for the timer that is earliest in the queue. - virtual long wait_duration_usec(long max_duration) const - { - if (heap_.empty()) - return max_duration; - - return this->to_usec( - Time_Traits::to_posix_duration( - Time_Traits::subtract(heap_[0].time_, Time_Traits::now())), - max_duration); - } - - // Dequeue all timers not later than the current time. - virtual void get_ready_timers(op_queue& ops) - { - if (!heap_.empty()) - { - const time_type now = Time_Traits::now(); - while (!heap_.empty() && !Time_Traits::less_than(now, heap_[0].time_)) - { - per_timer_data* timer = heap_[0].timer_; - ops.push(timer->op_queue_); - remove_timer(*timer); - } - } - } - - // Dequeue all timers. - virtual void get_all_timers(op_queue& ops) - { - while (timers_) - { - per_timer_data* timer = timers_; - timers_ = timers_->next_; - ops.push(timer->op_queue_); - timer->next_ = 0; - timer->prev_ = 0; - } - - heap_.clear(); - } - - // Cancel and dequeue operations for the given timer. - std::size_t cancel_timer(per_timer_data& timer, op_queue& ops, - std::size_t max_cancelled = (std::numeric_limits::max)()) - { - std::size_t num_cancelled = 0; - if (timer.prev_ != 0 || &timer == timers_) - { - while (wait_op* op = (num_cancelled != max_cancelled) - ? timer.op_queue_.front() : 0) - { - op->ec_ = asio::error::operation_aborted; - timer.op_queue_.pop(); - ops.push(op); - ++num_cancelled; - } - if (timer.op_queue_.empty()) - remove_timer(timer); - } - return num_cancelled; - } - - // Move operations from one timer to another, empty timer. - void move_timer(per_timer_data& target, per_timer_data& source) - { - target.op_queue_.push(source.op_queue_); - - target.heap_index_ = source.heap_index_; - source.heap_index_ = (std::numeric_limits::max)(); - - if (target.heap_index_ < heap_.size()) - heap_[target.heap_index_].timer_ = ⌖ - - if (timers_ == &source) - timers_ = ⌖ - if (source.prev_) - source.prev_->next_ = ⌖ - if (source.next_) - source.next_->prev_= ⌖ - target.next_ = source.next_; - target.prev_ = source.prev_; - source.next_ = 0; - source.prev_ = 0; - } - -private: - // Move the item at the given index up the heap to its correct position. - void up_heap(std::size_t index) - { - while (index > 0) - { - std::size_t parent = (index - 1) / 2; - if (!Time_Traits::less_than(heap_[index].time_, heap_[parent].time_)) - break; - swap_heap(index, parent); - index = parent; - } - } - - // Move the item at the given index down the heap to its correct position. - void down_heap(std::size_t index) - { - std::size_t child = index * 2 + 1; - while (child < heap_.size()) - { - std::size_t min_child = (child + 1 == heap_.size() - || Time_Traits::less_than( - heap_[child].time_, heap_[child + 1].time_)) - ? child : child + 1; - if (Time_Traits::less_than(heap_[index].time_, heap_[min_child].time_)) - break; - swap_heap(index, min_child); - index = min_child; - child = index * 2 + 1; - } - } - - // Swap two entries in the heap. - void swap_heap(std::size_t index1, std::size_t index2) - { - heap_entry tmp = heap_[index1]; - heap_[index1] = heap_[index2]; - heap_[index2] = tmp; - heap_[index1].timer_->heap_index_ = index1; - heap_[index2].timer_->heap_index_ = index2; - } - - // Remove a timer from the heap and list of timers. - void remove_timer(per_timer_data& timer) - { - // Remove the timer from the heap. - std::size_t index = timer.heap_index_; - if (!heap_.empty() && index < heap_.size()) - { - if (index == heap_.size() - 1) - { - heap_.pop_back(); - } - else - { - swap_heap(index, heap_.size() - 1); - heap_.pop_back(); - if (index > 0 && Time_Traits::less_than( - heap_[index].time_, heap_[(index - 1) / 2].time_)) - up_heap(index); - else - down_heap(index); - } - } - - // Remove the timer from the linked list of active timers. - if (timers_ == &timer) - timers_ = timer.next_; - if (timer.prev_) - timer.prev_->next_ = timer.next_; - if (timer.next_) - timer.next_->prev_= timer.prev_; - timer.next_ = 0; - timer.prev_ = 0; - } - - // Determine if the specified absolute time is positive infinity. - template - static bool is_positive_infinity(const Time_Type&) - { - return false; - } - - // Determine if the specified absolute time is positive infinity. - template - static bool is_positive_infinity( - const boost::date_time::base_time& time) - { - return time.is_pos_infinity(); - } - - // Helper function to convert a duration into milliseconds. - template - long to_msec(const Duration& d, long max_duration) const - { - if (d.ticks() <= 0) - return 0; - int64_t msec = d.total_milliseconds(); - if (msec == 0) - return 1; - if (msec > max_duration) - return max_duration; - return static_cast(msec); - } - - // Helper function to convert a duration into microseconds. - template - long to_usec(const Duration& d, long max_duration) const - { - if (d.ticks() <= 0) - return 0; - int64_t usec = d.total_microseconds(); - if (usec == 0) - return 1; - if (usec > max_duration) - return max_duration; - return static_cast(usec); - } - - // The head of a linked list of all active timers. - per_timer_data* timers_; - - struct heap_entry - { - // The time when the timer should fire. - time_type time_; - - // The associated timer with enqueued operations. - per_timer_data* timer_; - }; - - // The heap of timers, with the earliest timer at the front. - std::vector heap_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_TIMER_QUEUE_HPP diff --git a/scout_sdk/asio/asio/detail/timer_queue_base.hpp b/scout_sdk/asio/asio/detail/timer_queue_base.hpp deleted file mode 100644 index 4af995f..0000000 --- a/scout_sdk/asio/asio/detail/timer_queue_base.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// -// detail/timer_queue_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TIMER_QUEUE_BASE_HPP -#define ASIO_DETAIL_TIMER_QUEUE_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class timer_queue_base - : private noncopyable -{ -public: - // Constructor. - timer_queue_base() : next_(0) {} - - // Destructor. - virtual ~timer_queue_base() {} - - // Whether there are no timers in the queue. - virtual bool empty() const = 0; - - // Get the time to wait until the next timer. - virtual long wait_duration_msec(long max_duration) const = 0; - - // Get the time to wait until the next timer. - virtual long wait_duration_usec(long max_duration) const = 0; - - // Dequeue all ready timers. - virtual void get_ready_timers(op_queue& ops) = 0; - - // Dequeue all timers. - virtual void get_all_timers(op_queue& ops) = 0; - -private: - friend class timer_queue_set; - - // Next timer queue in the set. - timer_queue_base* next_; -}; - -template -class timer_queue; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_TIMER_QUEUE_BASE_HPP diff --git a/scout_sdk/asio/asio/detail/timer_queue_ptime.hpp b/scout_sdk/asio/asio/detail/timer_queue_ptime.hpp deleted file mode 100644 index 84e8338..0000000 --- a/scout_sdk/asio/asio/detail/timer_queue_ptime.hpp +++ /dev/null @@ -1,99 +0,0 @@ -// -// detail/timer_queue_ptime.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TIMER_QUEUE_PTIME_HPP -#define ASIO_DETAIL_TIMER_QUEUE_PTIME_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_DATE_TIME) - -#include "asio/time_traits.hpp" -#include "asio/detail/timer_queue.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct forwarding_posix_time_traits : time_traits {}; - -// Template specialisation for the commonly used instantation. -template <> -class timer_queue > - : public timer_queue_base -{ -public: - // The time type. - typedef boost::posix_time::ptime time_type; - - // The duration type. - typedef boost::posix_time::time_duration duration_type; - - // Per-timer data. - typedef timer_queue::per_timer_data - per_timer_data; - - // Constructor. - ASIO_DECL timer_queue(); - - // Destructor. - ASIO_DECL virtual ~timer_queue(); - - // Add a new timer to the queue. Returns true if this is the timer that is - // earliest in the queue, in which case the reactor's event demultiplexing - // function call may need to be interrupted and restarted. - ASIO_DECL bool enqueue_timer(const time_type& time, - per_timer_data& timer, wait_op* op); - - // Whether there are no timers in the queue. - ASIO_DECL virtual bool empty() const; - - // Get the time for the timer that is earliest in the queue. - ASIO_DECL virtual long wait_duration_msec(long max_duration) const; - - // Get the time for the timer that is earliest in the queue. - ASIO_DECL virtual long wait_duration_usec(long max_duration) const; - - // Dequeue all timers not later than the current time. - ASIO_DECL virtual void get_ready_timers(op_queue& ops); - - // Dequeue all timers. - ASIO_DECL virtual void get_all_timers(op_queue& ops); - - // Cancel and dequeue operations for the given timer. - ASIO_DECL std::size_t cancel_timer( - per_timer_data& timer, op_queue& ops, - std::size_t max_cancelled = (std::numeric_limits::max)()); - - // Move operations from one timer to another, empty timer. - ASIO_DECL void move_timer(per_timer_data& target, - per_timer_data& source); - -private: - timer_queue impl_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/timer_queue_ptime.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - -#endif // ASIO_DETAIL_TIMER_QUEUE_PTIME_HPP diff --git a/scout_sdk/asio/asio/detail/timer_queue_set.hpp b/scout_sdk/asio/asio/detail/timer_queue_set.hpp deleted file mode 100644 index 0ea372a..0000000 --- a/scout_sdk/asio/asio/detail/timer_queue_set.hpp +++ /dev/null @@ -1,66 +0,0 @@ -// -// detail/timer_queue_set.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TIMER_QUEUE_SET_HPP -#define ASIO_DETAIL_TIMER_QUEUE_SET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/timer_queue_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class timer_queue_set -{ -public: - // Constructor. - ASIO_DECL timer_queue_set(); - - // Add a timer queue to the set. - ASIO_DECL void insert(timer_queue_base* q); - - // Remove a timer queue from the set. - ASIO_DECL void erase(timer_queue_base* q); - - // Determine whether all queues are empty. - ASIO_DECL bool all_empty() const; - - // Get the wait duration in milliseconds. - ASIO_DECL long wait_duration_msec(long max_duration) const; - - // Get the wait duration in microseconds. - ASIO_DECL long wait_duration_usec(long max_duration) const; - - // Dequeue all ready timers. - ASIO_DECL void get_ready_timers(op_queue& ops); - - // Dequeue all timers. - ASIO_DECL void get_all_timers(op_queue& ops); - -private: - timer_queue_base* first_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/timer_queue_set.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_DETAIL_TIMER_QUEUE_SET_HPP diff --git a/scout_sdk/asio/asio/detail/timer_scheduler.hpp b/scout_sdk/asio/asio/detail/timer_scheduler.hpp deleted file mode 100644 index b1f8df4..0000000 --- a/scout_sdk/asio/asio/detail/timer_scheduler.hpp +++ /dev/null @@ -1,35 +0,0 @@ -// -// detail/timer_scheduler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TIMER_SCHEDULER_HPP -#define ASIO_DETAIL_TIMER_SCHEDULER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/timer_scheduler_fwd.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/winrt_timer_scheduler.hpp" -#elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_io_context.hpp" -#elif defined(ASIO_HAS_EPOLL) -# include "asio/detail/epoll_reactor.hpp" -#elif defined(ASIO_HAS_KQUEUE) -# include "asio/detail/kqueue_reactor.hpp" -#elif defined(ASIO_HAS_DEV_POLL) -# include "asio/detail/dev_poll_reactor.hpp" -#else -# include "asio/detail/select_reactor.hpp" -#endif - -#endif // ASIO_DETAIL_TIMER_SCHEDULER_HPP diff --git a/scout_sdk/asio/asio/detail/timer_scheduler_fwd.hpp b/scout_sdk/asio/asio/detail/timer_scheduler_fwd.hpp deleted file mode 100644 index 80bae50..0000000 --- a/scout_sdk/asio/asio/detail/timer_scheduler_fwd.hpp +++ /dev/null @@ -1,40 +0,0 @@ -// -// detail/timer_scheduler_fwd.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TIMER_SCHEDULER_FWD_HPP -#define ASIO_DETAIL_TIMER_SCHEDULER_FWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -namespace asio { -namespace detail { - -#if defined(ASIO_WINDOWS_RUNTIME) -typedef class winrt_timer_scheduler timer_scheduler; -#elif defined(ASIO_HAS_IOCP) -typedef class win_iocp_io_context timer_scheduler; -#elif defined(ASIO_HAS_EPOLL) -typedef class epoll_reactor timer_scheduler; -#elif defined(ASIO_HAS_KQUEUE) -typedef class kqueue_reactor timer_scheduler; -#elif defined(ASIO_HAS_DEV_POLL) -typedef class dev_poll_reactor timer_scheduler; -#else -typedef class select_reactor timer_scheduler; -#endif - -} // namespace detail -} // namespace asio - -#endif // ASIO_DETAIL_TIMER_SCHEDULER_FWD_HPP diff --git a/scout_sdk/asio/asio/detail/tss_ptr.hpp b/scout_sdk/asio/asio/detail/tss_ptr.hpp deleted file mode 100644 index e628abe..0000000 --- a/scout_sdk/asio/asio/detail/tss_ptr.hpp +++ /dev/null @@ -1,69 +0,0 @@ -// -// detail/tss_ptr.hpp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TSS_PTR_HPP -#define ASIO_DETAIL_TSS_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_THREADS) -# include "asio/detail/null_tss_ptr.hpp" -#elif defined(ASIO_HAS_THREAD_KEYWORD_EXTENSION) -# include "asio/detail/keyword_tss_ptr.hpp" -#elif defined(ASIO_WINDOWS) -# include "asio/detail/win_tss_ptr.hpp" -#elif defined(ASIO_HAS_PTHREADS) -# include "asio/detail/posix_tss_ptr.hpp" -#else -# error Only Windows and POSIX are supported! -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class tss_ptr -#if !defined(ASIO_HAS_THREADS) - : public null_tss_ptr -#elif defined(ASIO_HAS_THREAD_KEYWORD_EXTENSION) - : public keyword_tss_ptr -#elif defined(ASIO_WINDOWS) - : public win_tss_ptr -#elif defined(ASIO_HAS_PTHREADS) - : public posix_tss_ptr -#endif -{ -public: - void operator=(T* value) - { -#if !defined(ASIO_HAS_THREADS) - null_tss_ptr::operator=(value); -#elif defined(ASIO_HAS_THREAD_KEYWORD_EXTENSION) - keyword_tss_ptr::operator=(value); -#elif defined(ASIO_WINDOWS) - win_tss_ptr::operator=(value); -#elif defined(ASIO_HAS_PTHREADS) - posix_tss_ptr::operator=(value); -#endif - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_TSS_PTR_HPP diff --git a/scout_sdk/asio/asio/detail/type_traits.hpp b/scout_sdk/asio/asio/detail/type_traits.hpp deleted file mode 100644 index edf0928..0000000 --- a/scout_sdk/asio/asio/detail/type_traits.hpp +++ /dev/null @@ -1,86 +0,0 @@ -// -// detail/type_traits.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_TYPE_TRAITS_HPP -#define ASIO_DETAIL_TYPE_TRAITS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_TYPE_TRAITS) -# include -#else // defined(ASIO_HAS_TYPE_TRAITS) -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -#endif // defined(ASIO_HAS_TYPE_TRAITS) - -namespace asio { - -#if defined(ASIO_HAS_STD_TYPE_TRAITS) -using std::add_const; -using std::conditional; -using std::decay; -using std::enable_if; -using std::false_type; -using std::integral_constant; -using std::is_base_of; -using std::is_class; -using std::is_const; -using std::is_convertible; -using std::is_function; -using std::is_same; -using std::remove_pointer; -using std::remove_reference; -#if defined(ASIO_HAS_STD_INVOKE_RESULT) -template struct result_of; -template -struct result_of : std::invoke_result {}; -#else // defined(ASIO_HAS_STD_INVOKE_RESULT) -using std::result_of; -#endif // defined(ASIO_HAS_STD_INVOKE_RESULT) -using std::true_type; -#else // defined(ASIO_HAS_STD_TYPE_TRAITS) -using boost::add_const; -template -struct enable_if : boost::enable_if_c {}; -using boost::conditional; -using boost::decay; -using boost::false_type; -using boost::integral_constant; -using boost::is_base_of; -using boost::is_class; -using boost::is_const; -using boost::is_convertible; -using boost::is_function; -using boost::is_same; -using boost::remove_pointer; -using boost::remove_reference; -using boost::result_of; -using boost::true_type; -#endif // defined(ASIO_HAS_STD_TYPE_TRAITS) - -} // namespace asio - -#endif // ASIO_DETAIL_TYPE_TRAITS_HPP diff --git a/scout_sdk/asio/asio/detail/variadic_templates.hpp b/scout_sdk/asio/asio/detail/variadic_templates.hpp deleted file mode 100644 index d54eb4e..0000000 --- a/scout_sdk/asio/asio/detail/variadic_templates.hpp +++ /dev/null @@ -1,119 +0,0 @@ -// -// detail/variadic_templates.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_VARIADIC_TEMPLATES_HPP -#define ASIO_DETAIL_VARIADIC_TEMPLATES_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -# define ASIO_VARIADIC_TPARAMS(n) ASIO_VARIADIC_TPARAMS_##n - -# define ASIO_VARIADIC_TPARAMS_1 \ - typename T1 -# define ASIO_VARIADIC_TPARAMS_2 \ - typename T1, typename T2 -# define ASIO_VARIADIC_TPARAMS_3 \ - typename T1, typename T2, typename T3 -# define ASIO_VARIADIC_TPARAMS_4 \ - typename T1, typename T2, typename T3, typename T4 -# define ASIO_VARIADIC_TPARAMS_5 \ - typename T1, typename T2, typename T3, typename T4, typename T5 - -# define ASIO_VARIADIC_TARGS(n) ASIO_VARIADIC_TARGS_##n - -# define ASIO_VARIADIC_TARGS_1 T1 -# define ASIO_VARIADIC_TARGS_2 T1, T2 -# define ASIO_VARIADIC_TARGS_3 T1, T2, T3 -# define ASIO_VARIADIC_TARGS_4 T1, T2, T3, T4 -# define ASIO_VARIADIC_TARGS_5 T1, T2, T3, T4, T5 - -# define ASIO_VARIADIC_BYVAL_PARAMS(n) \ - ASIO_VARIADIC_BYVAL_PARAMS_##n - -# define ASIO_VARIADIC_BYVAL_PARAMS_1 T1 x1 -# define ASIO_VARIADIC_BYVAL_PARAMS_2 T1 x1, T2 x2 -# define ASIO_VARIADIC_BYVAL_PARAMS_3 T1 x1, T2 x2, T3 x3 -# define ASIO_VARIADIC_BYVAL_PARAMS_4 T1 x1, T2 x2, T3 x3, T4 x4 -# define ASIO_VARIADIC_BYVAL_PARAMS_5 T1 x1, T2 x2, T3 x3, T4 x4, T5 x5 - -# define ASIO_VARIADIC_BYVAL_ARGS(n) \ - ASIO_VARIADIC_BYVAL_ARGS_##n - -# define ASIO_VARIADIC_BYVAL_ARGS_1 x1 -# define ASIO_VARIADIC_BYVAL_ARGS_2 x1, x2 -# define ASIO_VARIADIC_BYVAL_ARGS_3 x1, x2, x3 -# define ASIO_VARIADIC_BYVAL_ARGS_4 x1, x2, x3, x4 -# define ASIO_VARIADIC_BYVAL_ARGS_5 x1, x2, x3, x4, x5 - -# define ASIO_VARIADIC_MOVE_PARAMS(n) \ - ASIO_VARIADIC_MOVE_PARAMS_##n - -# define ASIO_VARIADIC_MOVE_PARAMS_1 \ - ASIO_MOVE_ARG(T1) x1 -# define ASIO_VARIADIC_MOVE_PARAMS_2 \ - ASIO_MOVE_ARG(T1) x1, ASIO_MOVE_ARG(T2) x2 -# define ASIO_VARIADIC_MOVE_PARAMS_3 \ - ASIO_MOVE_ARG(T1) x1, ASIO_MOVE_ARG(T2) x2, \ - ASIO_MOVE_ARG(T3) x3 -# define ASIO_VARIADIC_MOVE_PARAMS_4 \ - ASIO_MOVE_ARG(T1) x1, ASIO_MOVE_ARG(T2) x2, \ - ASIO_MOVE_ARG(T3) x3, ASIO_MOVE_ARG(T4) x4 -# define ASIO_VARIADIC_MOVE_PARAMS_5 \ - ASIO_MOVE_ARG(T1) x1, ASIO_MOVE_ARG(T2) x2, \ - ASIO_MOVE_ARG(T3) x3, ASIO_MOVE_ARG(T4) x4, \ - ASIO_MOVE_ARG(T5) x5 - -# define ASIO_VARIADIC_MOVE_ARGS(n) \ - ASIO_VARIADIC_MOVE_ARGS_##n - -# define ASIO_VARIADIC_MOVE_ARGS_1 \ - ASIO_MOVE_CAST(T1)(x1) -# define ASIO_VARIADIC_MOVE_ARGS_2 \ - ASIO_MOVE_CAST(T1)(x1), ASIO_MOVE_CAST(T2)(x2) -# define ASIO_VARIADIC_MOVE_ARGS_3 \ - ASIO_MOVE_CAST(T1)(x1), ASIO_MOVE_CAST(T2)(x2), \ - ASIO_MOVE_CAST(T3)(x3) -# define ASIO_VARIADIC_MOVE_ARGS_4 \ - ASIO_MOVE_CAST(T1)(x1), ASIO_MOVE_CAST(T2)(x2), \ - ASIO_MOVE_CAST(T3)(x3), ASIO_MOVE_CAST(T4)(x4) -# define ASIO_VARIADIC_MOVE_ARGS_5 \ - ASIO_MOVE_CAST(T1)(x1), ASIO_MOVE_CAST(T2)(x2), \ - ASIO_MOVE_CAST(T3)(x3), ASIO_MOVE_CAST(T4)(x4), \ - ASIO_MOVE_CAST(T5)(x5) - -# define ASIO_VARIADIC_DECAY(n) \ - ASIO_VARIADIC_DECAY_##n - -# define ASIO_VARIADIC_DECAY_1 \ - typename decay::type -# define ASIO_VARIADIC_DECAY_2 \ - typename decay::type, typename decay::type -# define ASIO_VARIADIC_DECAY_3 \ - typename decay::type, typename decay::type, \ - typename decay::type -# define ASIO_VARIADIC_DECAY_4 \ - typename decay::type, typename decay::type, \ - typename decay::type, typename decay::type -# define ASIO_VARIADIC_DECAY_5 \ - typename decay::type, typename decay::type, \ - typename decay::type, typename decay::type, \ - typename decay::type - -# define ASIO_VARIADIC_GENERATE(m) m(1) m(2) m(3) m(4) m(5) - -#endif // !defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#endif // ASIO_DETAIL_VARIADIC_TEMPLATES_HPP diff --git a/scout_sdk/asio/asio/detail/wait_handler.hpp b/scout_sdk/asio/asio/detail/wait_handler.hpp deleted file mode 100644 index bd3dc24..0000000 --- a/scout_sdk/asio/asio/detail/wait_handler.hpp +++ /dev/null @@ -1,85 +0,0 @@ -// -// detail/wait_handler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WAIT_HANDLER_HPP -#define ASIO_DETAIL_WAIT_HANDLER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class wait_handler : public wait_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(wait_handler); - - wait_handler(Handler& h) - : wait_op(&wait_handler::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(h)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& /*ec*/, - std::size_t /*bytes_transferred*/) - { - // Take ownership of the handler object. - wait_handler* h(static_cast(base)); - ptr p = { asio::detail::addressof(h->handler_), h, h }; - handler_work w(h->handler_); - - ASIO_HANDLER_COMPLETION((*h)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(h->handler_, h->ec_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_WAIT_HANDLER_HPP diff --git a/scout_sdk/asio/asio/detail/wait_op.hpp b/scout_sdk/asio/asio/detail/wait_op.hpp deleted file mode 100644 index 1a3017b..0000000 --- a/scout_sdk/asio/asio/detail/wait_op.hpp +++ /dev/null @@ -1,45 +0,0 @@ -// -// detail/wait_op.hpp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WAIT_OP_HPP -#define ASIO_DETAIL_WAIT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class wait_op - : public operation -{ -public: - // The error code to be passed to the completion handler. - asio::error_code ec_; - -protected: - wait_op(func_type func) - : operation(func) - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_WAIT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_event.hpp b/scout_sdk/asio/asio/detail/win_event.hpp deleted file mode 100644 index 859cdee..0000000 --- a/scout_sdk/asio/asio/detail/win_event.hpp +++ /dev/null @@ -1,151 +0,0 @@ -// -// detail/win_event.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_EVENT_HPP -#define ASIO_DETAIL_WIN_EVENT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include "asio/detail/assert.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_event - : private noncopyable -{ -public: - // Constructor. - ASIO_DECL win_event(); - - // Destructor. - ASIO_DECL ~win_event(); - - // Signal the event. (Retained for backward compatibility.) - template - void signal(Lock& lock) - { - this->signal_all(lock); - } - - // Signal all waiters. - template - void signal_all(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - (void)lock; - state_ |= 1; - ::SetEvent(events_[0]); - } - - // Unlock the mutex and signal one waiter. - template - void unlock_and_signal_one(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - state_ |= 1; - bool have_waiters = (state_ > 1); - lock.unlock(); - if (have_waiters) - ::SetEvent(events_[1]); - } - - // If there's a waiter, unlock the mutex and signal it. - template - bool maybe_unlock_and_signal_one(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - state_ |= 1; - if (state_ > 1) - { - lock.unlock(); - ::SetEvent(events_[1]); - return true; - } - return false; - } - - // Reset the event. - template - void clear(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - (void)lock; - ::ResetEvent(events_[0]); - state_ &= ~std::size_t(1); - } - - // Wait for the event to become signalled. - template - void wait(Lock& lock) - { - ASIO_ASSERT(lock.locked()); - while ((state_ & 1) == 0) - { - state_ += 2; - lock.unlock(); -#if defined(ASIO_WINDOWS_APP) - ::WaitForMultipleObjectsEx(2, events_, false, INFINITE, false); -#else // defined(ASIO_WINDOWS_APP) - ::WaitForMultipleObjects(2, events_, false, INFINITE); -#endif // defined(ASIO_WINDOWS_APP) - lock.lock(); - state_ -= 2; - } - } - - // Timed wait for the event to become signalled. - template - bool wait_for_usec(Lock& lock, long usec) - { - ASIO_ASSERT(lock.locked()); - if ((state_ & 1) == 0) - { - state_ += 2; - lock.unlock(); - DWORD msec = usec > 0 ? (usec < 1000 ? 1 : usec / 1000) : 0; -#if defined(ASIO_WINDOWS_APP) - ::WaitForMultipleObjectsEx(2, events_, false, msec, false); -#else // defined(ASIO_WINDOWS_APP) - ::WaitForMultipleObjects(2, events_, false, msec); -#endif // defined(ASIO_WINDOWS_APP) - lock.lock(); - state_ -= 2; - } - return (state_ & 1) != 0; - } - -private: - HANDLE events_[2]; - std::size_t state_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_event.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_WIN_EVENT_HPP diff --git a/scout_sdk/asio/asio/detail/win_fd_set_adapter.hpp b/scout_sdk/asio/asio/detail/win_fd_set_adapter.hpp deleted file mode 100644 index 8d5e700..0000000 --- a/scout_sdk/asio/asio/detail/win_fd_set_adapter.hpp +++ /dev/null @@ -1,149 +0,0 @@ -// -// detail/win_fd_set_adapter.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_FD_SET_ADAPTER_HPP -#define ASIO_DETAIL_WIN_FD_SET_ADAPTER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/reactor_op_queue.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Adapts the FD_SET type to meet the Descriptor_Set concept's requirements. -class win_fd_set_adapter : noncopyable -{ -public: - enum { default_fd_set_size = 1024 }; - - win_fd_set_adapter() - : capacity_(default_fd_set_size), - max_descriptor_(invalid_socket) - { - fd_set_ = static_cast(::operator new( - sizeof(win_fd_set) - sizeof(SOCKET) - + sizeof(SOCKET) * (capacity_))); - fd_set_->fd_count = 0; - } - - ~win_fd_set_adapter() - { - ::operator delete(fd_set_); - } - - void reset() - { - fd_set_->fd_count = 0; - max_descriptor_ = invalid_socket; - } - - bool set(socket_type descriptor) - { - for (u_int i = 0; i < fd_set_->fd_count; ++i) - if (fd_set_->fd_array[i] == descriptor) - return true; - - reserve(fd_set_->fd_count + 1); - fd_set_->fd_array[fd_set_->fd_count++] = descriptor; - return true; - } - - void set(reactor_op_queue& operations, op_queue&) - { - reactor_op_queue::iterator i = operations.begin(); - while (i != operations.end()) - { - reactor_op_queue::iterator op_iter = i++; - reserve(fd_set_->fd_count + 1); - fd_set_->fd_array[fd_set_->fd_count++] = op_iter->first; - } - } - - bool is_set(socket_type descriptor) const - { - return !!__WSAFDIsSet(descriptor, - const_cast(reinterpret_cast(fd_set_))); - } - - operator fd_set*() - { - return reinterpret_cast(fd_set_); - } - - socket_type max_descriptor() const - { - return max_descriptor_; - } - - void perform(reactor_op_queue& operations, - op_queue& ops) const - { - for (u_int i = 0; i < fd_set_->fd_count; ++i) - operations.perform_operations(fd_set_->fd_array[i], ops); - } - -private: - // This structure is defined to be compatible with the Windows API fd_set - // structure, but without being dependent on the value of FD_SETSIZE. We use - // the "struct hack" to allow the number of descriptors to be varied at - // runtime. - struct win_fd_set - { - u_int fd_count; - SOCKET fd_array[1]; - }; - - // Increase the fd_set_ capacity to at least the specified number of elements. - void reserve(u_int n) - { - if (n <= capacity_) - return; - - u_int new_capacity = capacity_ + capacity_ / 2; - if (new_capacity < n) - new_capacity = n; - - win_fd_set* new_fd_set = static_cast(::operator new( - sizeof(win_fd_set) - sizeof(SOCKET) - + sizeof(SOCKET) * (new_capacity))); - - new_fd_set->fd_count = fd_set_->fd_count; - for (u_int i = 0; i < fd_set_->fd_count; ++i) - new_fd_set->fd_array[i] = fd_set_->fd_array[i]; - - ::operator delete(fd_set_); - fd_set_ = new_fd_set; - capacity_ = new_capacity; - } - - win_fd_set* fd_set_; - u_int capacity_; - socket_type max_descriptor_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#endif // ASIO_DETAIL_WIN_FD_SET_ADAPTER_HPP diff --git a/scout_sdk/asio/asio/detail/win_fenced_block.hpp b/scout_sdk/asio/asio/detail/win_fenced_block.hpp deleted file mode 100644 index 1ce6e13..0000000 --- a/scout_sdk/asio/asio/detail/win_fenced_block.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// -// detail/win_fenced_block.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_FENCED_BLOCK_HPP -#define ASIO_DETAIL_WIN_FENCED_BLOCK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) && !defined(UNDER_CE) - -#include "asio/detail/socket_types.hpp" -#include "asio/detail/noncopyable.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_fenced_block - : private noncopyable -{ -public: - enum half_t { half }; - enum full_t { full }; - - // Constructor for a half fenced block. - explicit win_fenced_block(half_t) - { - } - - // Constructor for a full fenced block. - explicit win_fenced_block(full_t) - { -#if defined(__BORLANDC__) - LONG barrier = 0; - ::InterlockedExchange(&barrier, 1); -#elif defined(ASIO_MSVC) \ - && ((ASIO_MSVC < 1400) || !defined(MemoryBarrier)) -# if defined(_M_IX86) -# pragma warning(push) -# pragma warning(disable:4793) - LONG barrier; - __asm { xchg barrier, eax } -# pragma warning(pop) -# endif // defined(_M_IX86) -#else - MemoryBarrier(); -#endif - } - - // Destructor. - ~win_fenced_block() - { -#if defined(__BORLANDC__) - LONG barrier = 0; - ::InterlockedExchange(&barrier, 1); -#elif defined(ASIO_MSVC) \ - && ((ASIO_MSVC < 1400) || !defined(MemoryBarrier)) -# if defined(_M_IX86) -# pragma warning(push) -# pragma warning(disable:4793) - LONG barrier; - __asm { xchg barrier, eax } -# pragma warning(pop) -# endif // defined(_M_IX86) -#else - MemoryBarrier(); -#endif - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) && !defined(UNDER_CE) - -#endif // ASIO_DETAIL_WIN_FENCED_BLOCK_HPP diff --git a/scout_sdk/asio/asio/detail/win_global.hpp b/scout_sdk/asio/asio/detail/win_global.hpp deleted file mode 100644 index 3b15a32..0000000 --- a/scout_sdk/asio/asio/detail/win_global.hpp +++ /dev/null @@ -1,73 +0,0 @@ -// -// detail/win_global.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_GLOBAL_HPP -#define ASIO_DETAIL_WIN_GLOBAL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/static_mutex.hpp" -#include "asio/detail/tss_ptr.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -struct win_global_impl -{ - // Destructor automatically cleans up the global. - ~win_global_impl() - { - delete ptr_; - } - - static win_global_impl instance_; - static static_mutex mutex_; - static T* ptr_; - static tss_ptr tss_ptr_; -}; - -template -win_global_impl win_global_impl::instance_ = { 0 }; - -template -static_mutex win_global_impl::mutex_ = ASIO_STATIC_MUTEX_INIT; - -template -T* win_global_impl::ptr_ = 0; - -template -tss_ptr win_global_impl::tss_ptr_; - -template -T& win_global() -{ - if (static_cast(win_global_impl::tss_ptr_) == 0) - { - win_global_impl::mutex_.init(); - static_mutex::scoped_lock lock(win_global_impl::mutex_); - win_global_impl::ptr_ = new T; - win_global_impl::tss_ptr_ = win_global_impl::ptr_; - } - - return *win_global_impl::tss_ptr_; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_WIN_GLOBAL_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_handle_read_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_handle_read_op.hpp deleted file mode 100644 index 88e3f6c..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_handle_read_op.hpp +++ /dev/null @@ -1,111 +0,0 @@ -// -// detail/win_iocp_handle_read_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_HANDLE_READ_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_HANDLE_READ_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/error.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_handle_read_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_handle_read_op); - - win_iocp_handle_read_op( - const MutableBufferSequence& buffers, Handler& handler) - : operation(&win_iocp_handle_read_op::do_complete), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t bytes_transferred) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_handle_read_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - if (owner) - { - // Check whether buffers are still valid. - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_HANDLE_EOF) - ec = asio::error::eof; - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - MutableBufferSequence buffers_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_HANDLE_READ_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_handle_service.hpp b/scout_sdk/asio/asio/detail/win_iocp_handle_service.hpp deleted file mode 100644 index 849fe8f..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_handle_service.hpp +++ /dev/null @@ -1,323 +0,0 @@ -// -// detail/win_iocp_handle_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_HANDLE_SERVICE_HPP -#define ASIO_DETAIL_WIN_IOCP_HANDLE_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/cstdint.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/win_iocp_handle_read_op.hpp" -#include "asio/detail/win_iocp_handle_write_op.hpp" -#include "asio/detail/win_iocp_io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_iocp_handle_service : - public service_base -{ -public: - // The native type of a stream handle. - typedef HANDLE native_handle_type; - - // The implementation type of the stream handle. - class implementation_type - { - public: - // Default constructor. - implementation_type() - : handle_(INVALID_HANDLE_VALUE), - safe_cancellation_thread_id_(0), - next_(0), - prev_(0) - { - } - - private: - // Only this service will have access to the internal values. - friend class win_iocp_handle_service; - - // The native stream handle representation. - native_handle_type handle_; - - // The ID of the thread from which it is safe to cancel asynchronous - // operations. 0 means no asynchronous operations have been started yet. - // ~0 means asynchronous operations have been started from more than one - // thread, and cancellation is not supported for the handle. - DWORD safe_cancellation_thread_id_; - - // Pointers to adjacent handle implementations in linked list. - implementation_type* next_; - implementation_type* prev_; - }; - - ASIO_DECL win_iocp_handle_service(asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Construct a new handle implementation. - ASIO_DECL void construct(implementation_type& impl); - - // Move-construct a new handle implementation. - ASIO_DECL void move_construct(implementation_type& impl, - implementation_type& other_impl); - - // Move-assign from another handle implementation. - ASIO_DECL void move_assign(implementation_type& impl, - win_iocp_handle_service& other_service, - implementation_type& other_impl); - - // Destroy a handle implementation. - ASIO_DECL void destroy(implementation_type& impl); - - // Assign a native handle to a handle implementation. - ASIO_DECL asio::error_code assign(implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec); - - // Determine whether the handle is open. - bool is_open(const implementation_type& impl) const - { - return impl.handle_ != INVALID_HANDLE_VALUE; - } - - // Destroy a handle implementation. - ASIO_DECL asio::error_code close(implementation_type& impl, - asio::error_code& ec); - - // Get the native handle representation. - native_handle_type native_handle(const implementation_type& impl) const - { - return impl.handle_; - } - - // Cancel all operations associated with the handle. - ASIO_DECL asio::error_code cancel(implementation_type& impl, - asio::error_code& ec); - - // Write the given data. Returns the number of bytes written. - template - size_t write_some(implementation_type& impl, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return write_some_at(impl, 0, buffers, ec); - } - - // Write the given data at the specified offset. Returns the number of bytes - // written. - template - size_t write_some_at(implementation_type& impl, uint64_t offset, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - asio::const_buffer buffer = - buffer_sequence_adapter::first(buffers); - - return do_write(impl, offset, buffer, ec); - } - - // Start an asynchronous write. The data being written must be valid for the - // lifetime of the asynchronous operation. - template - void async_write_some(implementation_type& impl, - const ConstBufferSequence& buffers, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_handle_write_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(buffers, handler); - - ASIO_HANDLER_CREATION((iocp_service_.context(), *p.p, "handle", &impl, - reinterpret_cast(impl.handle_), "async_write_some")); - - start_write_op(impl, 0, - buffer_sequence_adapter::first(buffers), p.p); - p.v = p.p = 0; - } - - // Start an asynchronous write at a specified offset. The data being written - // must be valid for the lifetime of the asynchronous operation. - template - void async_write_some_at(implementation_type& impl, uint64_t offset, - const ConstBufferSequence& buffers, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_handle_write_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(buffers, handler); - - ASIO_HANDLER_CREATION((iocp_service_.context(), *p.p, "handle", &impl, - reinterpret_cast(impl.handle_), "async_write_some_at")); - - start_write_op(impl, offset, - buffer_sequence_adapter::first(buffers), p.p); - p.v = p.p = 0; - } - - // Read some data. Returns the number of bytes received. - template - size_t read_some(implementation_type& impl, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return read_some_at(impl, 0, buffers, ec); - } - - // Read some data at a specified offset. Returns the number of bytes received. - template - size_t read_some_at(implementation_type& impl, uint64_t offset, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - asio::mutable_buffer buffer = - buffer_sequence_adapter::first(buffers); - - return do_read(impl, offset, buffer, ec); - } - - // Start an asynchronous read. The buffer for the data being received must be - // valid for the lifetime of the asynchronous operation. - template - void async_read_some(implementation_type& impl, - const MutableBufferSequence& buffers, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_handle_read_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(buffers, handler); - - ASIO_HANDLER_CREATION((iocp_service_.context(), *p.p, "handle", &impl, - reinterpret_cast(impl.handle_), "async_read_some")); - - start_read_op(impl, 0, - buffer_sequence_adapter::first(buffers), p.p); - p.v = p.p = 0; - } - - // Start an asynchronous read at a specified offset. The buffer for the data - // being received must be valid for the lifetime of the asynchronous - // operation. - template - void async_read_some_at(implementation_type& impl, uint64_t offset, - const MutableBufferSequence& buffers, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_handle_read_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(buffers, handler); - - ASIO_HANDLER_CREATION((iocp_service_.context(), *p.p, "handle", &impl, - reinterpret_cast(impl.handle_), "async_read_some_at")); - - start_read_op(impl, offset, - buffer_sequence_adapter::first(buffers), p.p); - p.v = p.p = 0; - } - -private: - // Prevent the use of the null_buffers type with this service. - size_t write_some(implementation_type& impl, - const null_buffers& buffers, asio::error_code& ec); - size_t write_some_at(implementation_type& impl, uint64_t offset, - const null_buffers& buffers, asio::error_code& ec); - template - void async_write_some(implementation_type& impl, - const null_buffers& buffers, Handler& handler); - template - void async_write_some_at(implementation_type& impl, uint64_t offset, - const null_buffers& buffers, Handler& handler); - size_t read_some(implementation_type& impl, - const null_buffers& buffers, asio::error_code& ec); - size_t read_some_at(implementation_type& impl, uint64_t offset, - const null_buffers& buffers, asio::error_code& ec); - template - void async_read_some(implementation_type& impl, - const null_buffers& buffers, Handler& handler); - template - void async_read_some_at(implementation_type& impl, uint64_t offset, - const null_buffers& buffers, Handler& handler); - - // Helper class for waiting for synchronous operations to complete. - class overlapped_wrapper; - - // Helper function to perform a synchronous write operation. - ASIO_DECL size_t do_write(implementation_type& impl, - uint64_t offset, const asio::const_buffer& buffer, - asio::error_code& ec); - - // Helper function to start a write operation. - ASIO_DECL void start_write_op(implementation_type& impl, - uint64_t offset, const asio::const_buffer& buffer, - operation* op); - - // Helper function to perform a synchronous write operation. - ASIO_DECL size_t do_read(implementation_type& impl, - uint64_t offset, const asio::mutable_buffer& buffer, - asio::error_code& ec); - - // Helper function to start a read operation. - ASIO_DECL void start_read_op(implementation_type& impl, - uint64_t offset, const asio::mutable_buffer& buffer, - operation* op); - - // Update the ID of the thread from which cancellation is safe. - ASIO_DECL void update_cancellation_thread_id(implementation_type& impl); - - // Helper function to close a handle when the associated object is being - // destroyed. - ASIO_DECL void close_for_destruction(implementation_type& impl); - - // The IOCP service used for running asynchronous operations and dispatching - // handlers. - win_iocp_io_context& iocp_service_; - - // Mutex to protect access to the linked list of implementations. - mutex mutex_; - - // The head of a linked list of all implementations. - implementation_type* impl_list_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_iocp_handle_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_HANDLE_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_handle_write_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_handle_write_op.hpp deleted file mode 100644 index d7bb944..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_handle_write_op.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// -// detail/win_iocp_handle_write_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_HANDLE_WRITE_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_HANDLE_WRITE_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/error.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_handle_write_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_handle_write_op); - - win_iocp_handle_write_op(const ConstBufferSequence& buffers, Handler& handler) - : operation(&win_iocp_handle_write_op::do_complete), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& ec, std::size_t bytes_transferred) - { - // Take ownership of the operation object. - win_iocp_handle_write_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - if (owner) - { - // Check whether buffers are still valid. - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - ConstBufferSequence buffers_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_HANDLE_WRITE_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_io_context.hpp b/scout_sdk/asio/asio/detail/win_iocp_io_context.hpp deleted file mode 100644 index 11bf58b..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_io_context.hpp +++ /dev/null @@ -1,328 +0,0 @@ -// -// detail/win_iocp_io_context.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_IO_CONTEXT_HPP -#define ASIO_DETAIL_WIN_IOCP_IO_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/limits.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/thread.hpp" -#include "asio/detail/thread_context.hpp" -#include "asio/detail/timer_queue_base.hpp" -#include "asio/detail/timer_queue_set.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/detail/win_iocp_operation.hpp" -#include "asio/detail/win_iocp_thread_info.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class wait_op; - -class win_iocp_io_context - : public execution_context_service_base, - public thread_context -{ -public: - // Constructor. Specifies a concurrency hint that is passed through to the - // underlying I/O completion port. - ASIO_DECL win_iocp_io_context(asio::execution_context& ctx, - int concurrency_hint = -1); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Initialise the task. Nothing to do here. - void init_task() - { - } - - // Register a handle with the IO completion port. - ASIO_DECL asio::error_code register_handle( - HANDLE handle, asio::error_code& ec); - - // Run the event loop until stopped or no more work. - ASIO_DECL size_t run(asio::error_code& ec); - - // Run until stopped or one operation is performed. - ASIO_DECL size_t run_one(asio::error_code& ec); - - // Run until timeout, interrupted, or one operation is performed. - ASIO_DECL size_t wait_one(long usec, asio::error_code& ec); - - // Poll for operations without blocking. - ASIO_DECL size_t poll(asio::error_code& ec); - - // Poll for one operation without blocking. - ASIO_DECL size_t poll_one(asio::error_code& ec); - - // Stop the event processing loop. - ASIO_DECL void stop(); - - // Determine whether the io_context is stopped. - bool stopped() const - { - return ::InterlockedExchangeAdd(&stopped_, 0) != 0; - } - - // Restart in preparation for a subsequent run invocation. - void restart() - { - ::InterlockedExchange(&stopped_, 0); - } - - // Notify that some work has started. - void work_started() - { - ::InterlockedIncrement(&outstanding_work_); - } - - // Notify that some work has finished. - void work_finished() - { - if (::InterlockedDecrement(&outstanding_work_) == 0) - stop(); - } - - // Return whether a handler can be dispatched immediately. - bool can_dispatch() - { - return thread_call_stack::contains(this) != 0; - } - - // Request invocation of the given operation and return immediately. Assumes - // that work_started() has not yet been called for the operation. - void post_immediate_completion(win_iocp_operation* op, bool) - { - work_started(); - post_deferred_completion(op); - } - - // Request invocation of the given operation and return immediately. Assumes - // that work_started() was previously called for the operation. - ASIO_DECL void post_deferred_completion(win_iocp_operation* op); - - // Request invocation of the given operation and return immediately. Assumes - // that work_started() was previously called for the operations. - ASIO_DECL void post_deferred_completions( - op_queue& ops); - - // Request invocation of the given operation using the thread-private queue - // and return immediately. Assumes that work_started() has not yet been - // called for the operation. - void post_private_immediate_completion(win_iocp_operation* op) - { - post_immediate_completion(op, false); - } - - // Request invocation of the given operation using the thread-private queue - // and return immediately. Assumes that work_started() was previously called - // for the operation. - void post_private_deferred_completion(win_iocp_operation* op) - { - post_deferred_completion(op); - } - - // Enqueue the given operation following a failed attempt to dispatch the - // operation for immediate invocation. - void do_dispatch(operation* op) - { - post_immediate_completion(op, false); - } - - // Process unfinished operations as part of a shutdown operation. Assumes - // that work_started() was previously called for the operations. - ASIO_DECL void abandon_operations(op_queue& ops); - - // Called after starting an overlapped I/O operation that did not complete - // immediately. The caller must have already called work_started() prior to - // starting the operation. - ASIO_DECL void on_pending(win_iocp_operation* op); - - // Called after starting an overlapped I/O operation that completed - // immediately. The caller must have already called work_started() prior to - // starting the operation. - ASIO_DECL void on_completion(win_iocp_operation* op, - DWORD last_error = 0, DWORD bytes_transferred = 0); - - // Called after starting an overlapped I/O operation that completed - // immediately. The caller must have already called work_started() prior to - // starting the operation. - ASIO_DECL void on_completion(win_iocp_operation* op, - const asio::error_code& ec, DWORD bytes_transferred = 0); - - // Add a new timer queue to the service. - template - void add_timer_queue(timer_queue& timer_queue); - - // Remove a timer queue from the service. - template - void remove_timer_queue(timer_queue& timer_queue); - - // Schedule a new operation in the given timer queue to expire at the - // specified absolute time. - template - void schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op); - - // Cancel the timer associated with the given token. Returns the number of - // handlers that have been posted or dispatched. - template - std::size_t cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled = (std::numeric_limits::max)()); - - // Move the timer operations associated with the given timer. - template - void move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& to, - typename timer_queue::per_timer_data& from); - - // Get the concurrency hint that was used to initialise the io_context. - int concurrency_hint() const - { - return concurrency_hint_; - } - -private: -#if defined(WINVER) && (WINVER < 0x0500) - typedef DWORD dword_ptr_t; - typedef ULONG ulong_ptr_t; -#else // defined(WINVER) && (WINVER < 0x0500) - typedef DWORD_PTR dword_ptr_t; - typedef ULONG_PTR ulong_ptr_t; -#endif // defined(WINVER) && (WINVER < 0x0500) - - // Dequeues at most one operation from the I/O completion port, and then - // executes it. Returns the number of operations that were dequeued (i.e. - // either 0 or 1). - ASIO_DECL size_t do_one(DWORD msec, asio::error_code& ec); - - // Helper to calculate the GetQueuedCompletionStatus timeout. - ASIO_DECL static DWORD get_gqcs_timeout(); - - // Helper function to add a new timer queue. - ASIO_DECL void do_add_timer_queue(timer_queue_base& queue); - - // Helper function to remove a timer queue. - ASIO_DECL void do_remove_timer_queue(timer_queue_base& queue); - - // Called to recalculate and update the timeout. - ASIO_DECL void update_timeout(); - - // Helper class to call work_finished() on block exit. - struct work_finished_on_block_exit; - - // Helper class for managing a HANDLE. - struct auto_handle - { - HANDLE handle; - auto_handle() : handle(0) {} - ~auto_handle() { if (handle) ::CloseHandle(handle); } - }; - - // The IO completion port used for queueing operations. - auto_handle iocp_; - - // The count of unfinished work. - long outstanding_work_; - - // Flag to indicate whether the event loop has been stopped. - mutable long stopped_; - - // Flag to indicate whether there is an in-flight stop event. Every event - // posted using PostQueuedCompletionStatus consumes non-paged pool, so to - // avoid exhausting this resouce we limit the number of outstanding events. - long stop_event_posted_; - - // Flag to indicate whether the service has been shut down. - long shutdown_; - - enum - { - // Timeout to use with GetQueuedCompletionStatus on older versions of - // Windows. Some versions of windows have a "bug" where a call to - // GetQueuedCompletionStatus can appear stuck even though there are events - // waiting on the queue. Using a timeout helps to work around the issue. - default_gqcs_timeout = 500, - - // Maximum waitable timer timeout, in milliseconds. - max_timeout_msec = 5 * 60 * 1000, - - // Maximum waitable timer timeout, in microseconds. - max_timeout_usec = max_timeout_msec * 1000, - - // Completion key value used to wake up a thread to dispatch timers or - // completed operations. - wake_for_dispatch = 1, - - // Completion key value to indicate that an operation has posted with the - // original last_error and bytes_transferred values stored in the fields of - // the OVERLAPPED structure. - overlapped_contains_result = 2 - }; - - // Timeout to use with GetQueuedCompletionStatus. - const DWORD gqcs_timeout_; - - // Function object for processing timeouts in a background thread. - struct timer_thread_function; - friend struct timer_thread_function; - - // Background thread used for processing timeouts. - scoped_ptr timer_thread_; - - // A waitable timer object used for waiting for timeouts. - auto_handle waitable_timer_; - - // Non-zero if timers or completed operations need to be dispatched. - long dispatch_required_; - - // Mutex for protecting access to the timer queues and completed operations. - mutex dispatch_mutex_; - - // The timer queues. - timer_queue_set timer_queues_; - - // The operations that are ready to dispatch. - op_queue completed_ops_; - - // The concurrency hint used to initialise the io_context. - const int concurrency_hint_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/win_iocp_io_context.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_iocp_io_context.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_IO_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_null_buffers_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_null_buffers_op.hpp deleted file mode 100644 index db70cb2..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_null_buffers_op.hpp +++ /dev/null @@ -1,121 +0,0 @@ -// -// detail/win_iocp_null_buffers_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_NULL_BUFFERS_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_NULL_BUFFERS_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_null_buffers_op : public reactor_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_null_buffers_op); - - win_iocp_null_buffers_op(socket_ops::weak_cancel_token_type cancel_token, - Handler& handler) - : reactor_op(&win_iocp_null_buffers_op::do_perform, - &win_iocp_null_buffers_op::do_complete), - cancel_token_(cancel_token), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static status do_perform(reactor_op*) - { - return done; - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t bytes_transferred) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_null_buffers_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // The reactor may have stored a result in the operation object. - if (o->ec_) - ec = o->ec_; - - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_NETNAME_DELETED) - { - if (o->cancel_token_.expired()) - ec = asio::error::operation_aborted; - else - ec = asio::error::connection_reset; - } - else if (ec.value() == ERROR_PORT_UNREACHABLE) - { - ec = asio::error::connection_refused; - } - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - socket_ops::weak_cancel_token_type cancel_token_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_NULL_BUFFERS_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_operation.hpp b/scout_sdk/asio/asio/detail/win_iocp_operation.hpp deleted file mode 100644 index 81d43f0..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_operation.hpp +++ /dev/null @@ -1,96 +0,0 @@ -// -// detail/win_iocp_operation.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_OPERATION_HPP -#define ASIO_DETAIL_WIN_IOCP_OPERATION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/handler_tracking.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/error_code.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_iocp_io_context; - -// Base class for all operations. A function pointer is used instead of virtual -// functions to avoid the associated overhead. -class win_iocp_operation - : public OVERLAPPED - ASIO_ALSO_INHERIT_TRACKED_HANDLER -{ -public: - typedef win_iocp_operation operation_type; - - void complete(void* owner, const asio::error_code& ec, - std::size_t bytes_transferred) - { - func_(owner, this, ec, bytes_transferred); - } - - void destroy() - { - func_(0, this, asio::error_code(), 0); - } - -protected: - typedef void (*func_type)( - void*, win_iocp_operation*, - const asio::error_code&, std::size_t); - - win_iocp_operation(func_type func) - : next_(0), - func_(func) - { - reset(); - } - - // Prevents deletion through this type. - ~win_iocp_operation() - { - } - - void reset() - { - Internal = 0; - InternalHigh = 0; - Offset = 0; - OffsetHigh = 0; - hEvent = 0; - ready_ = 0; - } - -private: - friend class op_queue_access; - friend class win_iocp_io_context; - win_iocp_operation* next_; - func_type func_; - long ready_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_OPERATION_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_overlapped_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_overlapped_op.hpp deleted file mode 100644 index 2b2cc31..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_overlapped_op.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// -// detail/win_iocp_overlapped_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_OVERLAPPED_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_OVERLAPPED_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/error.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_overlapped_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_overlapped_op); - - win_iocp_overlapped_op(Handler& handler) - : operation(&win_iocp_overlapped_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& ec, std::size_t bytes_transferred) - { - // Take ownership of the operation object. - win_iocp_overlapped_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_OVERLAPPED_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_overlapped_ptr.hpp b/scout_sdk/asio/asio/detail/win_iocp_overlapped_ptr.hpp deleted file mode 100644 index 7a19114..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_overlapped_ptr.hpp +++ /dev/null @@ -1,143 +0,0 @@ -// -// detail/win_iocp_overlapped_ptr.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_OVERLAPPED_PTR_HPP -#define ASIO_DETAIL_WIN_IOCP_OVERLAPPED_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/io_context.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/win_iocp_overlapped_op.hpp" -#include "asio/detail/win_iocp_io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Wraps a handler to create an OVERLAPPED object for use with overlapped I/O. -class win_iocp_overlapped_ptr - : private noncopyable -{ -public: - // Construct an empty win_iocp_overlapped_ptr. - win_iocp_overlapped_ptr() - : ptr_(0), - iocp_service_(0) - { - } - - // Construct an win_iocp_overlapped_ptr to contain the specified handler. - template - explicit win_iocp_overlapped_ptr( - asio::io_context& io_context, ASIO_MOVE_ARG(Handler) handler) - : ptr_(0), - iocp_service_(0) - { - this->reset(io_context, ASIO_MOVE_CAST(Handler)(handler)); - } - - // Destructor automatically frees the OVERLAPPED object unless released. - ~win_iocp_overlapped_ptr() - { - reset(); - } - - // Reset to empty. - void reset() - { - if (ptr_) - { - ptr_->destroy(); - ptr_ = 0; - iocp_service_->work_finished(); - iocp_service_ = 0; - } - } - - // Reset to contain the specified handler, freeing any current OVERLAPPED - // object. - template - void reset(asio::io_context& io_context, Handler handler) - { - typedef win_iocp_overlapped_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((io_context, *p.p, - "io_context", &io_context.impl_, 0, "overlapped")); - - io_context.impl_.work_started(); - reset(); - ptr_ = p.p; - p.v = p.p = 0; - iocp_service_ = &io_context.impl_; - } - - // Get the contained OVERLAPPED object. - OVERLAPPED* get() - { - return ptr_; - } - - // Get the contained OVERLAPPED object. - const OVERLAPPED* get() const - { - return ptr_; - } - - // Release ownership of the OVERLAPPED object. - OVERLAPPED* release() - { - if (ptr_) - iocp_service_->on_pending(ptr_); - - OVERLAPPED* tmp = ptr_; - ptr_ = 0; - iocp_service_ = 0; - return tmp; - } - - // Post completion notification for overlapped operation. Releases ownership. - void complete(const asio::error_code& ec, - std::size_t bytes_transferred) - { - if (ptr_) - { - iocp_service_->on_completion(ptr_, ec, - static_cast(bytes_transferred)); - ptr_ = 0; - iocp_service_ = 0; - } - } - -private: - win_iocp_operation* ptr_; - win_iocp_io_context* iocp_service_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_OVERLAPPED_PTR_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_serial_port_service.hpp b/scout_sdk/asio/asio/detail/win_iocp_serial_port_service.hpp deleted file mode 100644 index ac06348..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_serial_port_service.hpp +++ /dev/null @@ -1,230 +0,0 @@ -// -// detail/win_iocp_serial_port_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SERIAL_PORT_SERVICE_HPP -#define ASIO_DETAIL_WIN_IOCP_SERIAL_PORT_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) && defined(ASIO_HAS_SERIAL_PORT) - -#include -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/win_iocp_handle_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Extend win_iocp_handle_service to provide serial port support. -class win_iocp_serial_port_service : - public service_base -{ -public: - // The native type of a serial port. - typedef win_iocp_handle_service::native_handle_type native_handle_type; - - // The implementation type of the serial port. - typedef win_iocp_handle_service::implementation_type implementation_type; - - // Constructor. - ASIO_DECL win_iocp_serial_port_service( - asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Construct a new serial port implementation. - void construct(implementation_type& impl) - { - handle_service_.construct(impl); - } - - // Move-construct a new serial port implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - handle_service_.move_construct(impl, other_impl); - } - - // Move-assign from another serial port implementation. - void move_assign(implementation_type& impl, - win_iocp_serial_port_service& other_service, - implementation_type& other_impl) - { - handle_service_.move_assign(impl, - other_service.handle_service_, other_impl); - } - - // Destroy a serial port implementation. - void destroy(implementation_type& impl) - { - handle_service_.destroy(impl); - } - - // Open the serial port using the specified device name. - ASIO_DECL asio::error_code open(implementation_type& impl, - const std::string& device, asio::error_code& ec); - - // Assign a native handle to a serial port implementation. - asio::error_code assign(implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec) - { - return handle_service_.assign(impl, handle, ec); - } - - // Determine whether the serial port is open. - bool is_open(const implementation_type& impl) const - { - return handle_service_.is_open(impl); - } - - // Destroy a serial port implementation. - asio::error_code close(implementation_type& impl, - asio::error_code& ec) - { - return handle_service_.close(impl, ec); - } - - // Get the native serial port representation. - native_handle_type native_handle(implementation_type& impl) - { - return handle_service_.native_handle(impl); - } - - // Cancel all operations associated with the handle. - asio::error_code cancel(implementation_type& impl, - asio::error_code& ec) - { - return handle_service_.cancel(impl, ec); - } - - // Set an option on the serial port. - template - asio::error_code set_option(implementation_type& impl, - const SettableSerialPortOption& option, asio::error_code& ec) - { - return do_set_option(impl, - &win_iocp_serial_port_service::store_option, - &option, ec); - } - - // Get an option from the serial port. - template - asio::error_code get_option(const implementation_type& impl, - GettableSerialPortOption& option, asio::error_code& ec) const - { - return do_get_option(impl, - &win_iocp_serial_port_service::load_option, - &option, ec); - } - - // Send a break sequence to the serial port. - asio::error_code send_break(implementation_type&, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Write the given data. Returns the number of bytes sent. - template - size_t write_some(implementation_type& impl, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return handle_service_.write_some(impl, buffers, ec); - } - - // Start an asynchronous write. The data being written must be valid for the - // lifetime of the asynchronous operation. - template - void async_write_some(implementation_type& impl, - const ConstBufferSequence& buffers, Handler& handler) - { - handle_service_.async_write_some(impl, buffers, handler); - } - - // Read some data. Returns the number of bytes received. - template - size_t read_some(implementation_type& impl, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return handle_service_.read_some(impl, buffers, ec); - } - - // Start an asynchronous read. The buffer for the data being received must be - // valid for the lifetime of the asynchronous operation. - template - void async_read_some(implementation_type& impl, - const MutableBufferSequence& buffers, Handler& handler) - { - handle_service_.async_read_some(impl, buffers, handler); - } - -private: - // Function pointer type for storing a serial port option. - typedef asio::error_code (*store_function_type)( - const void*, ::DCB&, asio::error_code&); - - // Helper function template to store a serial port option. - template - static asio::error_code store_option(const void* option, - ::DCB& storage, asio::error_code& ec) - { - static_cast(option)->store(storage, ec); - return ec; - } - - // Helper function to set a serial port option. - ASIO_DECL asio::error_code do_set_option( - implementation_type& impl, store_function_type store, - const void* option, asio::error_code& ec); - - // Function pointer type for loading a serial port option. - typedef asio::error_code (*load_function_type)( - void*, const ::DCB&, asio::error_code&); - - // Helper function template to load a serial port option. - template - static asio::error_code load_option(void* option, - const ::DCB& storage, asio::error_code& ec) - { - static_cast(option)->load(storage, ec); - return ec; - } - - // Helper function to get a serial port option. - ASIO_DECL asio::error_code do_get_option( - const implementation_type& impl, load_function_type load, - void* option, asio::error_code& ec) const; - - // The implementation used for initiating asynchronous operations. - win_iocp_handle_service handle_service_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_iocp_serial_port_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_IOCP) && defined(ASIO_HAS_SERIAL_PORT) - -#endif // ASIO_DETAIL_WIN_IOCP_SERIAL_PORT_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_accept_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_accept_op.hpp deleted file mode 100644 index 18e7335..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_accept_op.hpp +++ /dev/null @@ -1,297 +0,0 @@ -// -// detail/win_iocp_socket_accept_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_ACCEPT_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_ACCEPT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/win_iocp_socket_service_base.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_socket_accept_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_socket_accept_op); - - win_iocp_socket_accept_op(win_iocp_socket_service_base& socket_service, - socket_type socket, Socket& peer, const Protocol& protocol, - typename Protocol::endpoint* peer_endpoint, - bool enable_connection_aborted, Handler& handler) - : operation(&win_iocp_socket_accept_op::do_complete), - socket_service_(socket_service), - socket_(socket), - peer_(peer), - protocol_(protocol), - peer_endpoint_(peer_endpoint), - enable_connection_aborted_(enable_connection_aborted), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - socket_holder& new_socket() - { - return new_socket_; - } - - void* output_buffer() - { - return output_buffer_; - } - - DWORD address_length() - { - return sizeof(sockaddr_storage_type) + 16; - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t /*bytes_transferred*/) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_socket_accept_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - if (owner) - { - typename Protocol::endpoint peer_endpoint; - std::size_t addr_len = peer_endpoint.capacity(); - socket_ops::complete_iocp_accept(o->socket_, - o->output_buffer(), o->address_length(), - peer_endpoint.data(), &addr_len, - o->new_socket_.get(), ec); - - // Restart the accept operation if we got the connection_aborted error - // and the enable_connection_aborted socket option is not set. - if (ec == asio::error::connection_aborted - && !o->enable_connection_aborted_) - { - o->reset(); - o->socket_service_.restart_accept_op(o->socket_, - o->new_socket_, o->protocol_.family(), - o->protocol_.type(), o->protocol_.protocol(), - o->output_buffer(), o->address_length(), o); - p.v = p.p = 0; - return; - } - - // If the socket was successfully accepted, transfer ownership of the - // socket to the peer object. - if (!ec) - { - o->peer_.assign(o->protocol_, - typename Socket::native_handle_type( - o->new_socket_.get(), peer_endpoint), ec); - if (!ec) - o->new_socket_.release(); - } - - // Pass endpoint back to caller. - if (o->peer_endpoint_) - *o->peer_endpoint_ = peer_endpoint; - } - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(o->handler_, ec); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - win_iocp_socket_service_base& socket_service_; - socket_type socket_; - socket_holder new_socket_; - Socket& peer_; - Protocol protocol_; - typename Protocol::endpoint* peer_endpoint_; - unsigned char output_buffer_[(sizeof(sockaddr_storage_type) + 16) * 2]; - bool enable_connection_aborted_; - Handler handler_; -}; - -#if defined(ASIO_HAS_MOVE) - -template -class win_iocp_socket_move_accept_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_socket_move_accept_op); - - win_iocp_socket_move_accept_op( - win_iocp_socket_service_base& socket_service, socket_type socket, - const Protocol& protocol, asio::io_context& peer_io_context, - typename Protocol::endpoint* peer_endpoint, - bool enable_connection_aborted, Handler& handler) - : operation(&win_iocp_socket_move_accept_op::do_complete), - socket_service_(socket_service), - socket_(socket), - peer_(peer_io_context), - protocol_(protocol), - peer_endpoint_(peer_endpoint), - enable_connection_aborted_(enable_connection_aborted), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - socket_holder& new_socket() - { - return new_socket_; - } - - void* output_buffer() - { - return output_buffer_; - } - - DWORD address_length() - { - return sizeof(sockaddr_storage_type) + 16; - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t /*bytes_transferred*/) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_socket_move_accept_op* o( - static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - if (owner) - { - typename Protocol::endpoint peer_endpoint; - std::size_t addr_len = peer_endpoint.capacity(); - socket_ops::complete_iocp_accept(o->socket_, - o->output_buffer(), o->address_length(), - peer_endpoint.data(), &addr_len, - o->new_socket_.get(), ec); - - // Restart the accept operation if we got the connection_aborted error - // and the enable_connection_aborted socket option is not set. - if (ec == asio::error::connection_aborted - && !o->enable_connection_aborted_) - { - o->reset(); - o->socket_service_.restart_accept_op(o->socket_, - o->new_socket_, o->protocol_.family(), - o->protocol_.type(), o->protocol_.protocol(), - o->output_buffer(), o->address_length(), o); - p.v = p.p = 0; - return; - } - - // If the socket was successfully accepted, transfer ownership of the - // socket to the peer object. - if (!ec) - { - o->peer_.assign(o->protocol_, - typename Protocol::socket::native_handle_type( - o->new_socket_.get(), peer_endpoint), ec); - if (!ec) - o->new_socket_.release(); - } - - // Pass endpoint back to caller. - if (o->peer_endpoint_) - *o->peer_endpoint_ = peer_endpoint; - } - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::move_binder2 - handler(0, ASIO_MOVE_CAST(Handler)(o->handler_), ec, - ASIO_MOVE_CAST(typename Protocol::socket)(o->peer_)); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, "...")); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - win_iocp_socket_service_base& socket_service_; - socket_type socket_; - socket_holder new_socket_; - typename Protocol::socket peer_; - Protocol protocol_; - typename Protocol::endpoint* peer_endpoint_; - unsigned char output_buffer_[(sizeof(sockaddr_storage_type) + 16) * 2]; - bool enable_connection_aborted_; - Handler handler_; -}; - -#endif // defined(ASIO_HAS_MOVE) - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_ACCEPT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_connect_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_connect_op.hpp deleted file mode 100644 index e0c52dc..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_connect_op.hpp +++ /dev/null @@ -1,127 +0,0 @@ -// -// detail/win_iocp_socket_connect_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_CONNECT_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_CONNECT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_iocp_socket_connect_op_base : public reactor_op -{ -public: - win_iocp_socket_connect_op_base(socket_type socket, func_type complete_func) - : reactor_op(&win_iocp_socket_connect_op_base::do_perform, complete_func), - socket_(socket), - connect_ex_(false) - { - } - - static status do_perform(reactor_op* base) - { - win_iocp_socket_connect_op_base* o( - static_cast(base)); - - return socket_ops::non_blocking_connect( - o->socket_, o->ec_) ? done : not_done; - } - - socket_type socket_; - bool connect_ex_; -}; - -template -class win_iocp_socket_connect_op : public win_iocp_socket_connect_op_base -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_socket_connect_op); - - win_iocp_socket_connect_op(socket_type socket, Handler& handler) - : win_iocp_socket_connect_op_base(socket, - &win_iocp_socket_connect_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t /*bytes_transferred*/) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_socket_connect_op* o( - static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - if (owner) - { - if (o->connect_ex_) - socket_ops::complete_iocp_connect(o->socket_, ec); - else - ec = o->ec_; - } - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(o->handler_, ec); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_CONNECT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_recv_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_recv_op.hpp deleted file mode 100644 index 4159540..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_recv_op.hpp +++ /dev/null @@ -1,117 +0,0 @@ -// -// detail/win_iocp_socket_recv_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_RECV_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_RECV_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_socket_recv_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_socket_recv_op); - - win_iocp_socket_recv_op(socket_ops::state_type state, - socket_ops::weak_cancel_token_type cancel_token, - const MutableBufferSequence& buffers, Handler& handler) - : operation(&win_iocp_socket_recv_op::do_complete), - state_(state), - cancel_token_(cancel_token), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t bytes_transferred) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_socket_recv_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - // Check whether buffers are still valid. - if (owner) - { - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - socket_ops::complete_iocp_recv(o->state_, o->cancel_token_, - buffer_sequence_adapter::all_empty(o->buffers_), - ec, bytes_transferred); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - socket_ops::state_type state_; - socket_ops::weak_cancel_token_type cancel_token_; - MutableBufferSequence buffers_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_RECV_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_recvfrom_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_recvfrom_op.hpp deleted file mode 100644 index 843ce5b..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_recvfrom_op.hpp +++ /dev/null @@ -1,125 +0,0 @@ -// -// detail/win_iocp_socket_recvfrom_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_RECVFROM_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_RECVFROM_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_socket_recvfrom_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_socket_recvfrom_op); - - win_iocp_socket_recvfrom_op(Endpoint& endpoint, - socket_ops::weak_cancel_token_type cancel_token, - const MutableBufferSequence& buffers, Handler& handler) - : operation(&win_iocp_socket_recvfrom_op::do_complete), - endpoint_(endpoint), - endpoint_size_(static_cast(endpoint.capacity())), - cancel_token_(cancel_token), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - int& endpoint_size() - { - return endpoint_size_; - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t bytes_transferred) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_socket_recvfrom_op* o( - static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - // Check whether buffers are still valid. - if (owner) - { - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - socket_ops::complete_iocp_recvfrom(o->cancel_token_, ec); - - // Record the size of the endpoint returned by the operation. - o->endpoint_.resize(o->endpoint_size_); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Endpoint& endpoint_; - int endpoint_size_; - socket_ops::weak_cancel_token_type cancel_token_; - MutableBufferSequence buffers_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_RECVFROM_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_recvmsg_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_recvmsg_op.hpp deleted file mode 100644 index 78f36b7..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_recvmsg_op.hpp +++ /dev/null @@ -1,118 +0,0 @@ -// -// detail/win_iocp_socket_recvmsg_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_RECVMSG_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_RECVMSG_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" -#include "asio/socket_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_socket_recvmsg_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_socket_recvmsg_op); - - win_iocp_socket_recvmsg_op( - socket_ops::weak_cancel_token_type cancel_token, - const MutableBufferSequence& buffers, - socket_base::message_flags& out_flags, Handler& handler) - : operation(&win_iocp_socket_recvmsg_op::do_complete), - cancel_token_(cancel_token), - buffers_(buffers), - out_flags_(out_flags), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t bytes_transferred) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_socket_recvmsg_op* o( - static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - // Check whether buffers are still valid. - if (owner) - { - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - socket_ops::complete_iocp_recvmsg(o->cancel_token_, ec); - o->out_flags_ = 0; - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - socket_ops::weak_cancel_token_type cancel_token_; - MutableBufferSequence buffers_; - socket_base::message_flags& out_flags_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_RECVMSG_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_send_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_send_op.hpp deleted file mode 100644 index e1c7ab9..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_send_op.hpp +++ /dev/null @@ -1,111 +0,0 @@ -// -// detail/win_iocp_socket_send_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_SEND_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_SEND_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_socket_send_op : public operation -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_socket_send_op); - - win_iocp_socket_send_op(socket_ops::weak_cancel_token_type cancel_token, - const ConstBufferSequence& buffers, Handler& handler) - : operation(&win_iocp_socket_send_op::do_complete), - cancel_token_(cancel_token), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t bytes_transferred) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_socket_send_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - // Check whether buffers are still valid. - if (owner) - { - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - socket_ops::complete_iocp_send(o->cancel_token_, ec); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, ec, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - socket_ops::weak_cancel_token_type cancel_token_; - ConstBufferSequence buffers_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_SEND_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_service.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_service.hpp deleted file mode 100644 index 3f01b4d..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_service.hpp +++ /dev/null @@ -1,599 +0,0 @@ -// -// detail/win_iocp_socket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_SERVICE_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/socket_base.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/select_reactor.hpp" -#include "asio/detail/socket_holder.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/win_iocp_io_context.hpp" -#include "asio/detail/win_iocp_null_buffers_op.hpp" -#include "asio/detail/win_iocp_socket_accept_op.hpp" -#include "asio/detail/win_iocp_socket_connect_op.hpp" -#include "asio/detail/win_iocp_socket_recvfrom_op.hpp" -#include "asio/detail/win_iocp_socket_send_op.hpp" -#include "asio/detail/win_iocp_socket_service_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_socket_service : - public service_base >, - public win_iocp_socket_service_base -{ -public: - // The protocol type. - typedef Protocol protocol_type; - - // The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - // The native type of a socket. - class native_handle_type - { - public: - native_handle_type(socket_type s) - : socket_(s), - have_remote_endpoint_(false) - { - } - - native_handle_type(socket_type s, const endpoint_type& ep) - : socket_(s), - have_remote_endpoint_(true), - remote_endpoint_(ep) - { - } - - void operator=(socket_type s) - { - socket_ = s; - have_remote_endpoint_ = false; - remote_endpoint_ = endpoint_type(); - } - - operator socket_type() const - { - return socket_; - } - - bool have_remote_endpoint() const - { - return have_remote_endpoint_; - } - - endpoint_type remote_endpoint() const - { - return remote_endpoint_; - } - - private: - socket_type socket_; - bool have_remote_endpoint_; - endpoint_type remote_endpoint_; - }; - - // The implementation type of the socket. - struct implementation_type : - win_iocp_socket_service_base::base_implementation_type - { - // Default constructor. - implementation_type() - : protocol_(endpoint_type().protocol()), - have_remote_endpoint_(false), - remote_endpoint_() - { - } - - // The protocol associated with the socket. - protocol_type protocol_; - - // Whether we have a cached remote endpoint. - bool have_remote_endpoint_; - - // A cached remote endpoint. - endpoint_type remote_endpoint_; - }; - - // Constructor. - win_iocp_socket_service(asio::io_context& io_context) - : service_base >(io_context), - win_iocp_socket_service_base(io_context) - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - this->base_shutdown(); - } - - // Move-construct a new socket implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - this->base_move_construct(impl, other_impl); - - impl.protocol_ = other_impl.protocol_; - other_impl.protocol_ = endpoint_type().protocol(); - - impl.have_remote_endpoint_ = other_impl.have_remote_endpoint_; - other_impl.have_remote_endpoint_ = false; - - impl.remote_endpoint_ = other_impl.remote_endpoint_; - other_impl.remote_endpoint_ = endpoint_type(); - } - - // Move-assign from another socket implementation. - void move_assign(implementation_type& impl, - win_iocp_socket_service_base& other_service, - implementation_type& other_impl) - { - this->base_move_assign(impl, other_service, other_impl); - - impl.protocol_ = other_impl.protocol_; - other_impl.protocol_ = endpoint_type().protocol(); - - impl.have_remote_endpoint_ = other_impl.have_remote_endpoint_; - other_impl.have_remote_endpoint_ = false; - - impl.remote_endpoint_ = other_impl.remote_endpoint_; - other_impl.remote_endpoint_ = endpoint_type(); - } - - // Move-construct a new socket implementation from another protocol type. - template - void converting_move_construct(implementation_type& impl, - win_iocp_socket_service&, - typename win_iocp_socket_service< - Protocol1>::implementation_type& other_impl) - { - this->base_move_construct(impl, other_impl); - - impl.protocol_ = protocol_type(other_impl.protocol_); - other_impl.protocol_ = typename Protocol1::endpoint().protocol(); - - impl.have_remote_endpoint_ = other_impl.have_remote_endpoint_; - other_impl.have_remote_endpoint_ = false; - - impl.remote_endpoint_ = other_impl.remote_endpoint_; - other_impl.remote_endpoint_ = typename Protocol1::endpoint(); - } - - // Open a new socket implementation. - asio::error_code open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - if (!do_open(impl, protocol.family(), - protocol.type(), protocol.protocol(), ec)) - { - impl.protocol_ = protocol; - impl.have_remote_endpoint_ = false; - impl.remote_endpoint_ = endpoint_type(); - } - return ec; - } - - // Assign a native socket to a socket implementation. - asio::error_code assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_socket, - asio::error_code& ec) - { - if (!do_assign(impl, protocol.type(), native_socket, ec)) - { - impl.protocol_ = protocol; - impl.have_remote_endpoint_ = native_socket.have_remote_endpoint(); - impl.remote_endpoint_ = native_socket.remote_endpoint(); - } - return ec; - } - - // Get the native socket representation. - native_handle_type native_handle(implementation_type& impl) - { - if (impl.have_remote_endpoint_) - return native_handle_type(impl.socket_, impl.remote_endpoint_); - return native_handle_type(impl.socket_); - } - - // Bind the socket to the specified local endpoint. - asio::error_code bind(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - socket_ops::bind(impl.socket_, endpoint.data(), endpoint.size(), ec); - return ec; - } - - // Set a socket option. - template - asio::error_code set_option(implementation_type& impl, - const Option& option, asio::error_code& ec) - { - socket_ops::setsockopt(impl.socket_, impl.state_, - option.level(impl.protocol_), option.name(impl.protocol_), - option.data(impl.protocol_), option.size(impl.protocol_), ec); - return ec; - } - - // Set a socket option. - template - asio::error_code get_option(const implementation_type& impl, - Option& option, asio::error_code& ec) const - { - std::size_t size = option.size(impl.protocol_); - socket_ops::getsockopt(impl.socket_, impl.state_, - option.level(impl.protocol_), option.name(impl.protocol_), - option.data(impl.protocol_), &size, ec); - if (!ec) - option.resize(impl.protocol_, size); - return ec; - } - - // Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - endpoint_type endpoint; - std::size_t addr_len = endpoint.capacity(); - if (socket_ops::getsockname(impl.socket_, endpoint.data(), &addr_len, ec)) - return endpoint_type(); - endpoint.resize(addr_len); - return endpoint; - } - - // Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - endpoint_type endpoint = impl.remote_endpoint_; - std::size_t addr_len = endpoint.capacity(); - if (socket_ops::getpeername(impl.socket_, endpoint.data(), - &addr_len, impl.have_remote_endpoint_, ec)) - return endpoint_type(); - endpoint.resize(addr_len); - return endpoint; - } - - // Disable sends or receives on the socket. - asio::error_code shutdown(base_implementation_type& impl, - socket_base::shutdown_type what, asio::error_code& ec) - { - socket_ops::shutdown(impl.socket_, what, ec); - return ec; - } - - // Send a datagram to the specified endpoint. Returns the number of bytes - // sent. - template - size_t send_to(implementation_type& impl, const ConstBufferSequence& buffers, - const endpoint_type& destination, socket_base::message_flags flags, - asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_sendto(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), flags, - destination.data(), destination.size(), ec); - } - - // Wait until data can be sent without blocking. - size_t send_to(implementation_type& impl, const null_buffers&, - const endpoint_type&, socket_base::message_flags, - asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_write(impl.socket_, impl.state_, -1, ec); - - return 0; - } - - // Start an asynchronous send. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_send_to(implementation_type& impl, - const ConstBufferSequence& buffers, const endpoint_type& destination, - socket_base::message_flags flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_send_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, buffers, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_send_to")); - - buffer_sequence_adapter bufs(buffers); - - start_send_to_op(impl, bufs.buffers(), bufs.count(), - destination.data(), static_cast(destination.size()), - flags, p.p); - p.v = p.p = 0; - } - - // Start an asynchronous wait until data can be sent without blocking. - template - void async_send_to(implementation_type& impl, const null_buffers&, - const endpoint_type&, socket_base::message_flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_send_to(null_buffers)")); - - start_reactor_op(impl, select_reactor::write_op, p.p); - p.v = p.p = 0; - } - - // Receive a datagram with the endpoint of the sender. Returns the number of - // bytes received. - template - size_t receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, - endpoint_type& sender_endpoint, socket_base::message_flags flags, - asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - std::size_t addr_len = sender_endpoint.capacity(); - std::size_t bytes_recvd = socket_ops::sync_recvfrom( - impl.socket_, impl.state_, bufs.buffers(), bufs.count(), - flags, sender_endpoint.data(), &addr_len, ec); - - if (!ec) - sender_endpoint.resize(addr_len); - - return bytes_recvd; - } - - // Wait until data can be received without blocking. - size_t receive_from(implementation_type& impl, - const null_buffers&, endpoint_type& sender_endpoint, - socket_base::message_flags, asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - - // Reset endpoint since it can be given no sensible value at this time. - sender_endpoint = endpoint_type(); - - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received and - // the sender_endpoint object must both be valid for the lifetime of the - // asynchronous operation. - template - void async_receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, endpoint_type& sender_endp, - socket_base::message_flags flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_recvfrom_op< - MutableBufferSequence, endpoint_type, Handler> op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(sender_endp, impl.cancel_token_, buffers, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_receive_from")); - - buffer_sequence_adapter bufs(buffers); - - start_receive_from_op(impl, bufs.buffers(), bufs.count(), - sender_endp.data(), flags, &p.p->endpoint_size(), p.p); - p.v = p.p = 0; - } - - // Wait until data can be received without blocking. - template - void async_receive_from(implementation_type& impl, - const null_buffers&, endpoint_type& sender_endpoint, - socket_base::message_flags flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_receive_from(null_buffers)")); - - // Reset endpoint since it can be given no sensible value at this time. - sender_endpoint = endpoint_type(); - - start_null_buffers_receive_op(impl, flags, p.p); - p.v = p.p = 0; - } - - // Accept a new connection. - template - asio::error_code accept(implementation_type& impl, Socket& peer, - endpoint_type* peer_endpoint, asio::error_code& ec) - { - // We cannot accept a socket that is already open. - if (peer.is_open()) - { - ec = asio::error::already_open; - return ec; - } - - std::size_t addr_len = peer_endpoint ? peer_endpoint->capacity() : 0; - socket_holder new_socket(socket_ops::sync_accept(impl.socket_, - impl.state_, peer_endpoint ? peer_endpoint->data() : 0, - peer_endpoint ? &addr_len : 0, ec)); - - // On success, assign new connection to peer socket object. - if (new_socket.get() != invalid_socket) - { - if (peer_endpoint) - peer_endpoint->resize(addr_len); - peer.assign(impl.protocol_, new_socket.get(), ec); - if (!ec) - new_socket.release(); - } - - return ec; - } - -#if defined(ASIO_HAS_MOVE) - // Accept a new connection. - typename Protocol::socket accept(implementation_type& impl, - io_context* peer_io_context, endpoint_type* peer_endpoint, - asio::error_code& ec) - { - typename Protocol::socket peer( - peer_io_context ? *peer_io_context : io_context_); - - std::size_t addr_len = peer_endpoint ? peer_endpoint->capacity() : 0; - socket_holder new_socket(socket_ops::sync_accept(impl.socket_, - impl.state_, peer_endpoint ? peer_endpoint->data() : 0, - peer_endpoint ? &addr_len : 0, ec)); - - // On success, assign new connection to peer socket object. - if (new_socket.get() != invalid_socket) - { - if (peer_endpoint) - peer_endpoint->resize(addr_len); - peer.assign(impl.protocol_, new_socket.get(), ec); - if (!ec) - new_socket.release(); - } - - return peer; - } -#endif // defined(ASIO_HAS_MOVE) - - // Start an asynchronous accept. The peer and peer_endpoint objects - // must be valid until the accept's handler is invoked. - template - void async_accept(implementation_type& impl, Socket& peer, - endpoint_type* peer_endpoint, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_accept_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - bool enable_connection_aborted = - (impl.state_ & socket_ops::enable_connection_aborted) != 0; - p.p = new (p.v) op(*this, impl.socket_, peer, impl.protocol_, - peer_endpoint, enable_connection_aborted, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_accept")); - - start_accept_op(impl, peer.is_open(), p.p->new_socket(), - impl.protocol_.family(), impl.protocol_.type(), - impl.protocol_.protocol(), p.p->output_buffer(), - p.p->address_length(), p.p); - p.v = p.p = 0; - } - -#if defined(ASIO_HAS_MOVE) - // Start an asynchronous accept. The peer and peer_endpoint objects - // must be valid until the accept's handler is invoked. - template - void async_accept(implementation_type& impl, - asio::io_context* peer_io_context, - endpoint_type* peer_endpoint, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_move_accept_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - bool enable_connection_aborted = - (impl.state_ & socket_ops::enable_connection_aborted) != 0; - p.p = new (p.v) op(*this, impl.socket_, impl.protocol_, - peer_io_context ? *peer_io_context : io_context_, - peer_endpoint, enable_connection_aborted, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_accept")); - - start_accept_op(impl, false, p.p->new_socket(), - impl.protocol_.family(), impl.protocol_.type(), - impl.protocol_.protocol(), p.p->output_buffer(), - p.p->address_length(), p.p); - p.v = p.p = 0; - } -#endif // defined(ASIO_HAS_MOVE) - - // Connect the socket to the specified endpoint. - asio::error_code connect(implementation_type& impl, - const endpoint_type& peer_endpoint, asio::error_code& ec) - { - socket_ops::sync_connect(impl.socket_, - peer_endpoint.data(), peer_endpoint.size(), ec); - return ec; - } - - // Start an asynchronous connect. - template - void async_connect(implementation_type& impl, - const endpoint_type& peer_endpoint, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_connect_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.socket_, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_connect")); - - start_connect_op(impl, impl.protocol_.family(), impl.protocol_.type(), - peer_endpoint.data(), static_cast(peer_endpoint.size()), p.p); - p.v = p.p = 0; - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_socket_service_base.hpp b/scout_sdk/asio/asio/detail/win_iocp_socket_service_base.hpp deleted file mode 100644 index ef1d718..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_socket_service_base.hpp +++ /dev/null @@ -1,591 +0,0 @@ -// -// detail/win_iocp_socket_service_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_SOCKET_SERVICE_BASE_HPP -#define ASIO_DETAIL_WIN_IOCP_SOCKET_SERVICE_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/socket_base.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/operation.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/select_reactor.hpp" -#include "asio/detail/socket_holder.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/win_iocp_io_context.hpp" -#include "asio/detail/win_iocp_null_buffers_op.hpp" -#include "asio/detail/win_iocp_socket_connect_op.hpp" -#include "asio/detail/win_iocp_socket_send_op.hpp" -#include "asio/detail/win_iocp_socket_recv_op.hpp" -#include "asio/detail/win_iocp_socket_recvmsg_op.hpp" -#include "asio/detail/win_iocp_wait_op.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_iocp_socket_service_base -{ -public: - // The implementation type of the socket. - struct base_implementation_type - { - // The native socket representation. - socket_type socket_; - - // The current state of the socket. - socket_ops::state_type state_; - - // We use a shared pointer as a cancellation token here to work around the - // broken Windows support for cancellation. MSDN says that when you call - // closesocket any outstanding WSARecv or WSASend operations will complete - // with the error ERROR_OPERATION_ABORTED. In practice they complete with - // ERROR_NETNAME_DELETED, which means you can't tell the difference between - // a local cancellation and the socket being hard-closed by the peer. - socket_ops::shared_cancel_token_type cancel_token_; - - // Per-descriptor data used by the reactor. - select_reactor::per_descriptor_data reactor_data_; - -#if defined(ASIO_ENABLE_CANCELIO) - // The ID of the thread from which it is safe to cancel asynchronous - // operations. 0 means no asynchronous operations have been started yet. - // ~0 means asynchronous operations have been started from more than one - // thread, and cancellation is not supported for the socket. - DWORD safe_cancellation_thread_id_; -#endif // defined(ASIO_ENABLE_CANCELIO) - - // Pointers to adjacent socket implementations in linked list. - base_implementation_type* next_; - base_implementation_type* prev_; - }; - - // Constructor. - ASIO_DECL win_iocp_socket_service_base( - asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void base_shutdown(); - - // Construct a new socket implementation. - ASIO_DECL void construct(base_implementation_type& impl); - - // Move-construct a new socket implementation. - ASIO_DECL void base_move_construct(base_implementation_type& impl, - base_implementation_type& other_impl); - - // Move-assign from another socket implementation. - ASIO_DECL void base_move_assign(base_implementation_type& impl, - win_iocp_socket_service_base& other_service, - base_implementation_type& other_impl); - - // Destroy a socket implementation. - ASIO_DECL void destroy(base_implementation_type& impl); - - // Determine whether the socket is open. - bool is_open(const base_implementation_type& impl) const - { - return impl.socket_ != invalid_socket; - } - - // Destroy a socket implementation. - ASIO_DECL asio::error_code close( - base_implementation_type& impl, asio::error_code& ec); - - // Release ownership of the socket. - ASIO_DECL socket_type release( - base_implementation_type& impl, asio::error_code& ec); - - // Cancel all operations associated with the socket. - ASIO_DECL asio::error_code cancel( - base_implementation_type& impl, asio::error_code& ec); - - // Determine whether the socket is at the out-of-band data mark. - bool at_mark(const base_implementation_type& impl, - asio::error_code& ec) const - { - return socket_ops::sockatmark(impl.socket_, ec); - } - - // Determine the number of bytes available for reading. - std::size_t available(const base_implementation_type& impl, - asio::error_code& ec) const - { - return socket_ops::available(impl.socket_, ec); - } - - // Place the socket into the state where it will listen for new connections. - asio::error_code listen(base_implementation_type& impl, - int backlog, asio::error_code& ec) - { - socket_ops::listen(impl.socket_, backlog, ec); - return ec; - } - - // Perform an IO control command on the socket. - template - asio::error_code io_control(base_implementation_type& impl, - IO_Control_Command& command, asio::error_code& ec) - { - socket_ops::ioctl(impl.socket_, impl.state_, command.name(), - static_cast(command.data()), ec); - return ec; - } - - // Gets the non-blocking mode of the socket. - bool non_blocking(const base_implementation_type& impl) const - { - return (impl.state_ & socket_ops::user_set_non_blocking) != 0; - } - - // Sets the non-blocking mode of the socket. - asio::error_code non_blocking(base_implementation_type& impl, - bool mode, asio::error_code& ec) - { - socket_ops::set_user_non_blocking(impl.socket_, impl.state_, mode, ec); - return ec; - } - - // Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const base_implementation_type& impl) const - { - return (impl.state_ & socket_ops::internal_non_blocking) != 0; - } - - // Sets the non-blocking mode of the native socket implementation. - asio::error_code native_non_blocking(base_implementation_type& impl, - bool mode, asio::error_code& ec) - { - socket_ops::set_internal_non_blocking(impl.socket_, impl.state_, mode, ec); - return ec; - } - - // Wait for the socket to become ready to read, ready to write, or to have - // pending error conditions. - asio::error_code wait(base_implementation_type& impl, - socket_base::wait_type w, asio::error_code& ec) - { - switch (w) - { - case socket_base::wait_read: - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - break; - case socket_base::wait_write: - socket_ops::poll_write(impl.socket_, impl.state_, -1, ec); - break; - case socket_base::wait_error: - socket_ops::poll_error(impl.socket_, impl.state_, -1, ec); - break; - default: - ec = asio::error::invalid_argument; - break; - } - - return ec; - } - - // Asynchronously wait for the socket to become ready to read, ready to - // write, or to have pending error conditions. - template - void async_wait(base_implementation_type& impl, - socket_base::wait_type w, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_wait_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_wait")); - - switch (w) - { - case socket_base::wait_read: - start_null_buffers_receive_op(impl, 0, p.p); - break; - case socket_base::wait_write: - start_reactor_op(impl, select_reactor::write_op, p.p); - break; - case socket_base::wait_error: - start_reactor_op(impl, select_reactor::except_op, p.p); - break; - default: - p.p->ec_ = asio::error::invalid_argument; - iocp_service_.post_immediate_completion(p.p, is_continuation); - break; - } - - p.v = p.p = 0; - } - - // Send the given data to the peer. Returns the number of bytes sent. - template - size_t send(base_implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_send(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), flags, bufs.all_empty(), ec); - } - - // Wait until data can be sent without blocking. - size_t send(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_write(impl.socket_, impl.state_, -1, ec); - - return 0; - } - - // Start an asynchronous send. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_send(base_implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_send_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, buffers, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_send")); - - buffer_sequence_adapter bufs(buffers); - - start_send_op(impl, bufs.buffers(), bufs.count(), flags, - (impl.state_ & socket_ops::stream_oriented) != 0 && bufs.all_empty(), - p.p); - p.v = p.p = 0; - } - - // Start an asynchronous wait until data can be sent without blocking. - template - void async_send(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_send(null_buffers)")); - - start_reactor_op(impl, select_reactor::write_op, p.p); - p.v = p.p = 0; - } - - // Receive some data from the peer. Returns the number of bytes received. - template - size_t receive(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_recv(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), flags, bufs.all_empty(), ec); - } - - // Wait until data can be received without blocking. - size_t receive(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received - // must be valid for the lifetime of the asynchronous operation. - template - void async_receive(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_recv_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.state_, impl.cancel_token_, buffers, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_receive")); - - buffer_sequence_adapter bufs(buffers); - - start_receive_op(impl, bufs.buffers(), bufs.count(), flags, - (impl.state_ & socket_ops::stream_oriented) != 0 && bufs.all_empty(), - p.p); - p.v = p.p = 0; - } - - // Wait until data can be received without blocking. - template - void async_receive(base_implementation_type& impl, const null_buffers&, - socket_base::message_flags flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_receive(null_buffers)")); - - start_null_buffers_receive_op(impl, flags, p.p); - p.v = p.p = 0; - } - - // Receive some data with associated flags. Returns the number of bytes - // received. - template - size_t receive_with_flags(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, asio::error_code& ec) - { - buffer_sequence_adapter bufs(buffers); - - return socket_ops::sync_recvmsg(impl.socket_, impl.state_, - bufs.buffers(), bufs.count(), in_flags, out_flags, ec); - } - - // Wait until data can be received without blocking. - size_t receive_with_flags(base_implementation_type& impl, - const null_buffers&, socket_base::message_flags, - socket_base::message_flags& out_flags, asio::error_code& ec) - { - // Wait for socket to become ready. - socket_ops::poll_read(impl.socket_, impl.state_, -1, ec); - - // Clear out_flags, since we cannot give it any other sensible value when - // performing a null_buffers operation. - out_flags = 0; - - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received - // must be valid for the lifetime of the asynchronous operation. - template - void async_receive_with_flags(base_implementation_type& impl, - const MutableBufferSequence& buffers, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_socket_recvmsg_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, buffers, out_flags, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_receive_with_flags")); - - buffer_sequence_adapter bufs(buffers); - - start_receive_op(impl, bufs.buffers(), bufs.count(), in_flags, false, p.p); - p.v = p.p = 0; - } - - // Wait until data can be received without blocking. - template - void async_receive_with_flags(base_implementation_type& impl, - const null_buffers&, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef win_iocp_null_buffers_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(impl.cancel_token_, handler); - - ASIO_HANDLER_CREATION((io_context_, *p.p, "socket", - &impl, impl.socket_, "async_receive_with_flags(null_buffers)")); - - // Reset out_flags since it can be given no sensible value at this time. - out_flags = 0; - - start_null_buffers_receive_op(impl, in_flags, p.p); - p.v = p.p = 0; - } - - // Helper function to restart an asynchronous accept operation. - ASIO_DECL void restart_accept_op(socket_type s, - socket_holder& new_socket, int family, int type, int protocol, - void* output_buffer, DWORD address_length, operation* op); - -protected: - // Open a new socket implementation. - ASIO_DECL asio::error_code do_open( - base_implementation_type& impl, int family, int type, - int protocol, asio::error_code& ec); - - // Assign a native socket to a socket implementation. - ASIO_DECL asio::error_code do_assign( - base_implementation_type& impl, int type, - socket_type native_socket, asio::error_code& ec); - - // Helper function to start an asynchronous send operation. - ASIO_DECL void start_send_op(base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, - socket_base::message_flags flags, bool noop, operation* op); - - // Helper function to start an asynchronous send_to operation. - ASIO_DECL void start_send_to_op(base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, - const socket_addr_type* addr, int addrlen, - socket_base::message_flags flags, operation* op); - - // Helper function to start an asynchronous receive operation. - ASIO_DECL void start_receive_op(base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, - socket_base::message_flags flags, bool noop, operation* op); - - // Helper function to start an asynchronous null_buffers receive operation. - ASIO_DECL void start_null_buffers_receive_op( - base_implementation_type& impl, - socket_base::message_flags flags, reactor_op* op); - - // Helper function to start an asynchronous receive_from operation. - ASIO_DECL void start_receive_from_op(base_implementation_type& impl, - WSABUF* buffers, std::size_t buffer_count, socket_addr_type* addr, - socket_base::message_flags flags, int* addrlen, operation* op); - - // Helper function to start an asynchronous accept operation. - ASIO_DECL void start_accept_op(base_implementation_type& impl, - bool peer_is_open, socket_holder& new_socket, int family, int type, - int protocol, void* output_buffer, DWORD address_length, operation* op); - - // Start an asynchronous read or write operation using the reactor. - ASIO_DECL void start_reactor_op(base_implementation_type& impl, - int op_type, reactor_op* op); - - // Start the asynchronous connect operation using the reactor. - ASIO_DECL void start_connect_op(base_implementation_type& impl, - int family, int type, const socket_addr_type* remote_addr, - std::size_t remote_addrlen, win_iocp_socket_connect_op_base* op); - - // Helper function to close a socket when the associated object is being - // destroyed. - ASIO_DECL void close_for_destruction(base_implementation_type& impl); - - // Update the ID of the thread from which cancellation is safe. - ASIO_DECL void update_cancellation_thread_id( - base_implementation_type& impl); - - // Helper function to get the reactor. If no reactor has been created yet, a - // new one is obtained from the io_context and a pointer to it is cached in - // this service. - ASIO_DECL select_reactor& get_reactor(); - - // The type of a ConnectEx function pointer, as old SDKs may not provide it. - typedef BOOL (PASCAL *connect_ex_fn)(SOCKET, - const socket_addr_type*, int, void*, DWORD, DWORD*, OVERLAPPED*); - - // Helper function to get the ConnectEx pointer. If no ConnectEx pointer has - // been obtained yet, one is obtained using WSAIoctl and the pointer is - // cached. Returns a null pointer if ConnectEx is not available. - ASIO_DECL connect_ex_fn get_connect_ex( - base_implementation_type& impl, int type); - - // The type of a NtSetInformationFile function pointer. - typedef LONG (NTAPI *nt_set_info_fn)(HANDLE, ULONG_PTR*, void*, ULONG, ULONG); - - // Helper function to get the NtSetInformationFile function pointer. If no - // NtSetInformationFile pointer has been obtained yet, one is obtained using - // GetProcAddress and the pointer is cached. Returns a null pointer if - // NtSetInformationFile is not available. - ASIO_DECL nt_set_info_fn get_nt_set_info(); - - // Helper function to emulate InterlockedCompareExchangePointer functionality - // for: - // - very old Platform SDKs; and - // - platform SDKs where MSVC's /Wp64 option causes spurious warnings. - ASIO_DECL void* interlocked_compare_exchange_pointer( - void** dest, void* exch, void* cmp); - - // Helper function to emulate InterlockedExchangePointer functionality for: - // - very old Platform SDKs; and - // - platform SDKs where MSVC's /Wp64 option causes spurious warnings. - ASIO_DECL void* interlocked_exchange_pointer(void** dest, void* val); - - // The io_context used to obtain the reactor, if required. - asio::io_context& io_context_; - - // The IOCP service used for running asynchronous operations and dispatching - // handlers. - win_iocp_io_context& iocp_service_; - - // The reactor used for performing connect operations. This object is created - // only if needed. - select_reactor* reactor_; - - // Pointer to ConnectEx implementation. - void* connect_ex_; - - // Pointer to NtSetInformationFile implementation. - void* nt_set_info_; - - // Mutex to protect access to the linked list of implementations. - asio::detail::mutex mutex_; - - // The head of a linked list of all implementations. - base_implementation_type* impl_list_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_iocp_socket_service_base.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_SOCKET_SERVICE_BASE_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_thread_info.hpp b/scout_sdk/asio/asio/detail/win_iocp_thread_info.hpp deleted file mode 100644 index 13181e2..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_thread_info.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// -// detail/win_iocp_thread_info.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_THREAD_INFO_HPP -#define ASIO_DETAIL_WIN_IOCP_THREAD_INFO_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/thread_info_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct win_iocp_thread_info : public thread_info_base -{ -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_WIN_IOCP_THREAD_INFO_HPP diff --git a/scout_sdk/asio/asio/detail/win_iocp_wait_op.hpp b/scout_sdk/asio/asio/detail/win_iocp_wait_op.hpp deleted file mode 100644 index 472eea3..0000000 --- a/scout_sdk/asio/asio/detail/win_iocp_wait_op.hpp +++ /dev/null @@ -1,121 +0,0 @@ -// -// detail/win_iocp_wait_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_IOCP_WAIT_OP_HPP -#define ASIO_DETAIL_WIN_IOCP_WAIT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_IOCP) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/reactor_op.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class win_iocp_wait_op : public reactor_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(win_iocp_wait_op); - - win_iocp_wait_op(socket_ops::weak_cancel_token_type cancel_token, - Handler& handler) - : reactor_op(&win_iocp_wait_op::do_perform, - &win_iocp_wait_op::do_complete), - cancel_token_(cancel_token), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static status do_perform(reactor_op*) - { - return done; - } - - static void do_complete(void* owner, operation* base, - const asio::error_code& result_ec, - std::size_t /*bytes_transferred*/) - { - asio::error_code ec(result_ec); - - // Take ownership of the operation object. - win_iocp_wait_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // The reactor may have stored a result in the operation object. - if (o->ec_) - ec = o->ec_; - - // Map non-portable errors to their portable counterparts. - if (ec.value() == ERROR_NETNAME_DELETED) - { - if (o->cancel_token_.expired()) - ec = asio::error::operation_aborted; - else - ec = asio::error::connection_reset; - } - else if (ec.value() == ERROR_PORT_UNREACHABLE) - { - ec = asio::error::connection_refused; - } - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(o->handler_, ec); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - socket_ops::weak_cancel_token_type cancel_token_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_IOCP) - -#endif // ASIO_DETAIL_WIN_IOCP_WAIT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/win_mutex.hpp b/scout_sdk/asio/asio/detail/win_mutex.hpp deleted file mode 100644 index ce52a2f..0000000 --- a/scout_sdk/asio/asio/detail/win_mutex.hpp +++ /dev/null @@ -1,78 +0,0 @@ -// -// detail/win_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_MUTEX_HPP -#define ASIO_DETAIL_WIN_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_lock.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_mutex - : private noncopyable -{ -public: - typedef asio::detail::scoped_lock scoped_lock; - - // Constructor. - ASIO_DECL win_mutex(); - - // Destructor. - ~win_mutex() - { - ::DeleteCriticalSection(&crit_section_); - } - - // Lock the mutex. - void lock() - { - ::EnterCriticalSection(&crit_section_); - } - - // Unlock the mutex. - void unlock() - { - ::LeaveCriticalSection(&crit_section_); - } - -private: - // Initialisation must be performed in a separate function to the constructor - // since the compiler does not support the use of structured exceptions and - // C++ exceptions in the same function. - ASIO_DECL int do_init(); - - ::CRITICAL_SECTION crit_section_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_mutex.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_WIN_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/win_object_handle_service.hpp b/scout_sdk/asio/asio/detail/win_object_handle_service.hpp deleted file mode 100644 index 1d8abc9..0000000 --- a/scout_sdk/asio/asio/detail/win_object_handle_service.hpp +++ /dev/null @@ -1,184 +0,0 @@ -// -// detail/win_object_handle_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2011 Boris Schaeling (boris@highscore.de) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_OBJECT_HANDLE_SERVICE_HPP -#define ASIO_DETAIL_WIN_OBJECT_HANDLE_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/wait_handler.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class win_object_handle_service : - public service_base -{ -public: - // The native type of an object handle. - typedef HANDLE native_handle_type; - - // The implementation type of the object handle. - class implementation_type - { - public: - // Default constructor. - implementation_type() - : handle_(INVALID_HANDLE_VALUE), - wait_handle_(INVALID_HANDLE_VALUE), - owner_(0), - next_(0), - prev_(0) - { - } - - private: - // Only this service will have access to the internal values. - friend class win_object_handle_service; - - // The native object handle representation. May be accessed or modified - // without locking the mutex. - native_handle_type handle_; - - // The handle used to unregister the wait operation. The mutex must be - // locked when accessing or modifying this member. - HANDLE wait_handle_; - - // The operations waiting on the object handle. If there is a registered - // wait then the mutex must be locked when accessing or modifying this - // member - op_queue op_queue_; - - // The service instance that owns the object handle implementation. - win_object_handle_service* owner_; - - // Pointers to adjacent handle implementations in linked list. The mutex - // must be locked when accessing or modifying these members. - implementation_type* next_; - implementation_type* prev_; - }; - - // Constructor. - ASIO_DECL win_object_handle_service( - asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Construct a new handle implementation. - ASIO_DECL void construct(implementation_type& impl); - - // Move-construct a new handle implementation. - ASIO_DECL void move_construct(implementation_type& impl, - implementation_type& other_impl); - - // Move-assign from another handle implementation. - ASIO_DECL void move_assign(implementation_type& impl, - win_object_handle_service& other_service, - implementation_type& other_impl); - - // Destroy a handle implementation. - ASIO_DECL void destroy(implementation_type& impl); - - // Assign a native handle to a handle implementation. - ASIO_DECL asio::error_code assign(implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec); - - // Determine whether the handle is open. - bool is_open(const implementation_type& impl) const - { - return impl.handle_ != INVALID_HANDLE_VALUE && impl.handle_ != 0; - } - - // Destroy a handle implementation. - ASIO_DECL asio::error_code close(implementation_type& impl, - asio::error_code& ec); - - // Get the native handle representation. - native_handle_type native_handle(const implementation_type& impl) const - { - return impl.handle_; - } - - // Cancel all operations associated with the handle. - ASIO_DECL asio::error_code cancel(implementation_type& impl, - asio::error_code& ec); - - // Perform a synchronous wait for the object to enter a signalled state. - ASIO_DECL void wait(implementation_type& impl, - asio::error_code& ec); - - /// Start an asynchronous wait. - template - void async_wait(implementation_type& impl, Handler& handler) - { - // Allocate and construct an operation to wrap the handler. - typedef wait_handler op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((io_context_.context(), *p.p, "object_handle", - &impl, reinterpret_cast(impl.wait_handle_), "async_wait")); - - start_wait_op(impl, p.p); - p.v = p.p = 0; - } - -private: - // Helper function to start an asynchronous wait operation. - ASIO_DECL void start_wait_op(implementation_type& impl, wait_op* op); - - // Helper function to register a wait operation. - ASIO_DECL void register_wait_callback( - implementation_type& impl, mutex::scoped_lock& lock); - - // Callback function invoked when the registered wait completes. - static ASIO_DECL VOID CALLBACK wait_callback( - PVOID param, BOOLEAN timeout); - - // The io_context implementation used to post completions. - io_context_impl& io_context_; - - // Mutex to protect access to internal state. - mutex mutex_; - - // The head of a linked list of all implementations. - implementation_type* impl_list_; - - // Flag to indicate that the dispatcher has been shut down. - bool shutdown_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_object_handle_service.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - -#endif // ASIO_DETAIL_WIN_OBJECT_HANDLE_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/win_static_mutex.hpp b/scout_sdk/asio/asio/detail/win_static_mutex.hpp deleted file mode 100644 index b169688..0000000 --- a/scout_sdk/asio/asio/detail/win_static_mutex.hpp +++ /dev/null @@ -1,74 +0,0 @@ -// -// detail/win_static_mutex.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_STATIC_MUTEX_HPP -#define ASIO_DETAIL_WIN_STATIC_MUTEX_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include "asio/detail/scoped_lock.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct win_static_mutex -{ - typedef asio::detail::scoped_lock scoped_lock; - - // Initialise the mutex. - ASIO_DECL void init(); - - // Initialisation must be performed in a separate function to the "public" - // init() function since the compiler does not support the use of structured - // exceptions and C++ exceptions in the same function. - ASIO_DECL int do_init(); - - // Lock the mutex. - void lock() - { - ::EnterCriticalSection(&crit_section_); - } - - // Unlock the mutex. - void unlock() - { - ::LeaveCriticalSection(&crit_section_); - } - - bool initialised_; - ::CRITICAL_SECTION crit_section_; -}; - -#if defined(UNDER_CE) -# define ASIO_WIN_STATIC_MUTEX_INIT { false, { 0, 0, 0, 0, 0 } } -#else // defined(UNDER_CE) -# define ASIO_WIN_STATIC_MUTEX_INIT { false, { 0, 0, 0, 0, 0, 0 } } -#endif // defined(UNDER_CE) - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_static_mutex.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_WIN_STATIC_MUTEX_HPP diff --git a/scout_sdk/asio/asio/detail/win_thread.hpp b/scout_sdk/asio/asio/detail/win_thread.hpp deleted file mode 100644 index 8b28a90..0000000 --- a/scout_sdk/asio/asio/detail/win_thread.hpp +++ /dev/null @@ -1,147 +0,0 @@ -// -// detail/win_thread.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_THREAD_HPP -#define ASIO_DETAIL_WIN_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) \ - && !defined(ASIO_WINDOWS_APP) \ - && !defined(UNDER_CE) - -#include -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -ASIO_DECL unsigned int __stdcall win_thread_function(void* arg); - -#if defined(WINVER) && (WINVER < 0x0500) -ASIO_DECL void __stdcall apc_function(ULONG data); -#else -ASIO_DECL void __stdcall apc_function(ULONG_PTR data); -#endif - -template -class win_thread_base -{ -public: - static bool terminate_threads() - { - return ::InterlockedExchangeAdd(&terminate_threads_, 0) != 0; - } - - static void set_terminate_threads(bool b) - { - ::InterlockedExchange(&terminate_threads_, b ? 1 : 0); - } - -private: - static long terminate_threads_; -}; - -template -long win_thread_base::terminate_threads_ = 0; - -class win_thread - : private noncopyable, - public win_thread_base -{ -public: - // Constructor. - template - win_thread(Function f, unsigned int stack_size = 0) - : thread_(0), - exit_event_(0) - { - start_thread(new func(f), stack_size); - } - - // Destructor. - ASIO_DECL ~win_thread(); - - // Wait for the thread to exit. - ASIO_DECL void join(); - - // Get number of CPUs. - ASIO_DECL static std::size_t hardware_concurrency(); - -private: - friend ASIO_DECL unsigned int __stdcall win_thread_function(void* arg); - -#if defined(WINVER) && (WINVER < 0x0500) - friend ASIO_DECL void __stdcall apc_function(ULONG); -#else - friend ASIO_DECL void __stdcall apc_function(ULONG_PTR); -#endif - - class func_base - { - public: - virtual ~func_base() {} - virtual void run() = 0; - ::HANDLE entry_event_; - ::HANDLE exit_event_; - }; - - struct auto_func_base_ptr - { - func_base* ptr; - ~auto_func_base_ptr() { delete ptr; } - }; - - template - class func - : public func_base - { - public: - func(Function f) - : f_(f) - { - } - - virtual void run() - { - f_(); - } - - private: - Function f_; - }; - - ASIO_DECL void start_thread(func_base* arg, unsigned int stack_size); - - ::HANDLE thread_; - ::HANDLE exit_event_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_thread.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS) - // && !defined(ASIO_WINDOWS_APP) - // && !defined(UNDER_CE) - -#endif // ASIO_DETAIL_WIN_THREAD_HPP diff --git a/scout_sdk/asio/asio/detail/win_tss_ptr.hpp b/scout_sdk/asio/asio/detail/win_tss_ptr.hpp deleted file mode 100644 index 4207108..0000000 --- a/scout_sdk/asio/asio/detail/win_tss_ptr.hpp +++ /dev/null @@ -1,79 +0,0 @@ -// -// detail/win_tss_ptr.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WIN_TSS_PTR_HPP -#define ASIO_DETAIL_WIN_TSS_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -// Helper function to create thread-specific storage. -ASIO_DECL DWORD win_tss_ptr_create(); - -template -class win_tss_ptr - : private noncopyable -{ -public: - // Constructor. - win_tss_ptr() - : tss_key_(win_tss_ptr_create()) - { - } - - // Destructor. - ~win_tss_ptr() - { - ::TlsFree(tss_key_); - } - - // Get the value. - operator T*() const - { - return static_cast(::TlsGetValue(tss_key_)); - } - - // Set the value. - void operator=(T* value) - { - ::TlsSetValue(tss_key_, value); - } - -private: - // Thread-specific storage to allow unlocked access to determine whether a - // thread is a member of the pool. - DWORD tss_key_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/win_tss_ptr.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS) - -#endif // ASIO_DETAIL_WIN_TSS_PTR_HPP diff --git a/scout_sdk/asio/asio/detail/winapp_thread.hpp b/scout_sdk/asio/asio/detail/winapp_thread.hpp deleted file mode 100644 index 69dcf08..0000000 --- a/scout_sdk/asio/asio/detail/winapp_thread.hpp +++ /dev/null @@ -1,124 +0,0 @@ -// -// detail/winapp_thread.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINAPP_THREAD_HPP -#define ASIO_DETAIL_WINAPP_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) && defined(ASIO_WINDOWS_APP) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -DWORD WINAPI winapp_thread_function(LPVOID arg); - -class winapp_thread - : private noncopyable -{ -public: - // Constructor. - template - winapp_thread(Function f, unsigned int = 0) - { - scoped_ptr arg(new func(f)); - DWORD thread_id = 0; - thread_ = ::CreateThread(0, 0, winapp_thread_function, - arg.get(), 0, &thread_id); - if (!thread_) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "thread"); - } - arg.release(); - } - - // Destructor. - ~winapp_thread() - { - ::CloseHandle(thread_); - } - - // Wait for the thread to exit. - void join() - { - ::WaitForSingleObjectEx(thread_, INFINITE, false); - } - - // Get number of CPUs. - static std::size_t hardware_concurrency() - { - SYSTEM_INFO system_info; - ::GetNativeSystemInfo(&system_info); - return system_info.dwNumberOfProcessors; - } - -private: - friend DWORD WINAPI winapp_thread_function(LPVOID arg); - - class func_base - { - public: - virtual ~func_base() {} - virtual void run() = 0; - }; - - template - class func - : public func_base - { - public: - func(Function f) - : f_(f) - { - } - - virtual void run() - { - f_(); - } - - private: - Function f_; - }; - - ::HANDLE thread_; -}; - -inline DWORD WINAPI winapp_thread_function(LPVOID arg) -{ - scoped_ptr func( - static_cast(arg)); - func->run(); - return 0; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) && defined(ASIO_WINDOWS_APP) - -#endif // ASIO_DETAIL_WINAPP_THREAD_HPP diff --git a/scout_sdk/asio/asio/detail/wince_thread.hpp b/scout_sdk/asio/asio/detail/wince_thread.hpp deleted file mode 100644 index a2863f6..0000000 --- a/scout_sdk/asio/asio/detail/wince_thread.hpp +++ /dev/null @@ -1,124 +0,0 @@ -// -// detail/wince_thread.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINCE_THREAD_HPP -#define ASIO_DETAIL_WINCE_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) && defined(UNDER_CE) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -DWORD WINAPI wince_thread_function(LPVOID arg); - -class wince_thread - : private noncopyable -{ -public: - // Constructor. - template - wince_thread(Function f, unsigned int = 0) - { - scoped_ptr arg(new func(f)); - DWORD thread_id = 0; - thread_ = ::CreateThread(0, 0, wince_thread_function, - arg.get(), 0, &thread_id); - if (!thread_) - { - DWORD last_error = ::GetLastError(); - asio::error_code ec(last_error, - asio::error::get_system_category()); - asio::detail::throw_error(ec, "thread"); - } - arg.release(); - } - - // Destructor. - ~wince_thread() - { - ::CloseHandle(thread_); - } - - // Wait for the thread to exit. - void join() - { - ::WaitForSingleObject(thread_, INFINITE); - } - - // Get number of CPUs. - static std::size_t hardware_concurrency() - { - SYSTEM_INFO system_info; - ::GetSystemInfo(&system_info); - return system_info.dwNumberOfProcessors; - } - -private: - friend DWORD WINAPI wince_thread_function(LPVOID arg); - - class func_base - { - public: - virtual ~func_base() {} - virtual void run() = 0; - }; - - template - class func - : public func_base - { - public: - func(Function f) - : f_(f) - { - } - - virtual void run() - { - f_(); - } - - private: - Function f_; - }; - - ::HANDLE thread_; -}; - -inline DWORD WINAPI wince_thread_function(LPVOID arg) -{ - scoped_ptr func( - static_cast(arg)); - func->run(); - return 0; -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS) && defined(UNDER_CE) - -#endif // ASIO_DETAIL_WINCE_THREAD_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_async_manager.hpp b/scout_sdk/asio/asio/detail/winrt_async_manager.hpp deleted file mode 100644 index e22ad52..0000000 --- a/scout_sdk/asio/asio/detail/winrt_async_manager.hpp +++ /dev/null @@ -1,294 +0,0 @@ -// -// detail/winrt_async_manager.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_ASYNC_MANAGER_HPP -#define ASIO_DETAIL_WINRT_ASYNC_MANAGER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include -#include "asio/detail/atomic_count.hpp" -#include "asio/detail/winrt_async_op.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class winrt_async_manager - : public asio::detail::service_base -{ -public: - // Constructor. - winrt_async_manager(asio::io_context& io_context) - : asio::detail::service_base(io_context), - io_context_(use_service(io_context)), - outstanding_ops_(1) - { - } - - // Destructor. - ~winrt_async_manager() - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - if (--outstanding_ops_ > 0) - { - // Block until last operation is complete. - std::future f = promise_.get_future(); - f.wait(); - } - } - - void sync(Windows::Foundation::IAsyncAction^ action, - asio::error_code& ec) - { - using namespace Windows::Foundation; - using Windows::Foundation::AsyncStatus; - - auto promise = std::make_shared>(); - auto future = promise->get_future(); - - action->Completed = ref new AsyncActionCompletedHandler( - [promise](IAsyncAction^ action, AsyncStatus status) - { - switch (status) - { - case AsyncStatus::Canceled: - promise->set_value(asio::error::operation_aborted); - break; - case AsyncStatus::Error: - case AsyncStatus::Completed: - default: - asio::error_code ec( - action->ErrorCode.Value, - asio::system_category()); - promise->set_value(ec); - break; - } - }); - - ec = future.get(); - } - - template - TResult sync(Windows::Foundation::IAsyncOperation^ operation, - asio::error_code& ec) - { - using namespace Windows::Foundation; - using Windows::Foundation::AsyncStatus; - - auto promise = std::make_shared>(); - auto future = promise->get_future(); - - operation->Completed = ref new AsyncOperationCompletedHandler( - [promise](IAsyncOperation^ operation, AsyncStatus status) - { - switch (status) - { - case AsyncStatus::Canceled: - promise->set_value(asio::error::operation_aborted); - break; - case AsyncStatus::Error: - case AsyncStatus::Completed: - default: - asio::error_code ec( - operation->ErrorCode.Value, - asio::system_category()); - promise->set_value(ec); - break; - } - }); - - ec = future.get(); - return operation->GetResults(); - } - - template - TResult sync( - Windows::Foundation::IAsyncOperationWithProgress< - TResult, TProgress>^ operation, - asio::error_code& ec) - { - using namespace Windows::Foundation; - using Windows::Foundation::AsyncStatus; - - auto promise = std::make_shared>(); - auto future = promise->get_future(); - - operation->Completed - = ref new AsyncOperationWithProgressCompletedHandler( - [promise](IAsyncOperationWithProgress^ operation, - AsyncStatus status) - { - switch (status) - { - case AsyncStatus::Canceled: - promise->set_value(asio::error::operation_aborted); - break; - case AsyncStatus::Started: - break; - case AsyncStatus::Error: - case AsyncStatus::Completed: - default: - asio::error_code ec( - operation->ErrorCode.Value, - asio::system_category()); - promise->set_value(ec); - break; - } - }); - - ec = future.get(); - return operation->GetResults(); - } - - void async(Windows::Foundation::IAsyncAction^ action, - winrt_async_op* handler) - { - using namespace Windows::Foundation; - using Windows::Foundation::AsyncStatus; - - auto on_completed = ref new AsyncActionCompletedHandler( - [this, handler](IAsyncAction^ action, AsyncStatus status) - { - switch (status) - { - case AsyncStatus::Canceled: - handler->ec_ = asio::error::operation_aborted; - break; - case AsyncStatus::Started: - return; - case AsyncStatus::Completed: - case AsyncStatus::Error: - default: - handler->ec_ = asio::error_code( - action->ErrorCode.Value, - asio::system_category()); - break; - } - io_context_.post_deferred_completion(handler); - if (--outstanding_ops_ == 0) - promise_.set_value(); - }); - - io_context_.work_started(); - ++outstanding_ops_; - action->Completed = on_completed; - } - - template - void async(Windows::Foundation::IAsyncOperation^ operation, - winrt_async_op* handler) - { - using namespace Windows::Foundation; - using Windows::Foundation::AsyncStatus; - - auto on_completed = ref new AsyncOperationCompletedHandler( - [this, handler](IAsyncOperation^ operation, AsyncStatus status) - { - switch (status) - { - case AsyncStatus::Canceled: - handler->ec_ = asio::error::operation_aborted; - break; - case AsyncStatus::Started: - return; - case AsyncStatus::Completed: - handler->result_ = operation->GetResults(); - // Fall through. - case AsyncStatus::Error: - default: - handler->ec_ = asio::error_code( - operation->ErrorCode.Value, - asio::system_category()); - break; - } - io_context_.post_deferred_completion(handler); - if (--outstanding_ops_ == 0) - promise_.set_value(); - }); - - io_context_.work_started(); - ++outstanding_ops_; - operation->Completed = on_completed; - } - - template - void async( - Windows::Foundation::IAsyncOperationWithProgress< - TResult, TProgress>^ operation, - winrt_async_op* handler) - { - using namespace Windows::Foundation; - using Windows::Foundation::AsyncStatus; - - auto on_completed - = ref new AsyncOperationWithProgressCompletedHandler( - [this, handler](IAsyncOperationWithProgress< - TResult, TProgress>^ operation, AsyncStatus status) - { - switch (status) - { - case AsyncStatus::Canceled: - handler->ec_ = asio::error::operation_aborted; - break; - case AsyncStatus::Started: - return; - case AsyncStatus::Completed: - handler->result_ = operation->GetResults(); - // Fall through. - case AsyncStatus::Error: - default: - handler->ec_ = asio::error_code( - operation->ErrorCode.Value, - asio::system_category()); - break; - } - io_context_.post_deferred_completion(handler); - if (--outstanding_ops_ == 0) - promise_.set_value(); - }); - - io_context_.work_started(); - ++outstanding_ops_; - operation->Completed = on_completed; - } - -private: - // The io_context implementation used to post completed handlers. - io_context_impl& io_context_; - - // Count of outstanding operations. - atomic_count outstanding_ops_; - - // Used to keep wait for outstanding operations to complete. - std::promise promise_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_ASYNC_MANAGER_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_async_op.hpp b/scout_sdk/asio/asio/detail/winrt_async_op.hpp deleted file mode 100644 index 75891a4..0000000 --- a/scout_sdk/asio/asio/detail/winrt_async_op.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// -// detail/winrt_async_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_ASYNC_OP_HPP -#define ASIO_DETAIL_WINRT_ASYNC_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/operation.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class winrt_async_op - : public operation -{ -public: - // The error code to be passed to the completion handler. - asio::error_code ec_; - - // The result of the operation, to be passed to the completion handler. - TResult result_; - -protected: - winrt_async_op(func_type complete_func) - : operation(complete_func), - result_() - { - } -}; - -template <> -class winrt_async_op - : public operation -{ -public: - // The error code to be passed to the completion handler. - asio::error_code ec_; - -protected: - winrt_async_op(func_type complete_func) - : operation(complete_func) - { - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_WINRT_ASYNC_OP_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_resolve_op.hpp b/scout_sdk/asio/asio/detail/winrt_resolve_op.hpp deleted file mode 100644 index 07efd29..0000000 --- a/scout_sdk/asio/asio/detail/winrt_resolve_op.hpp +++ /dev/null @@ -1,118 +0,0 @@ -// -// detail/winrt_resolve_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_RESOLVE_OP_HPP -#define ASIO_DETAIL_WINRT_RESOLVE_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/winrt_async_op.hpp" -#include "asio/ip/basic_resolver_results.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class winrt_resolve_op : - public winrt_async_op< - Windows::Foundation::Collections::IVectorView< - Windows::Networking::EndpointPair^>^> -{ -public: - ASIO_DEFINE_HANDLER_PTR(winrt_resolve_op); - - typedef typename Protocol::endpoint endpoint_type; - typedef asio::ip::basic_resolver_query query_type; - typedef asio::ip::basic_resolver_results results_type; - - winrt_resolve_op(const query_type& query, Handler& handler) - : winrt_async_op< - Windows::Foundation::Collections::IVectorView< - Windows::Networking::EndpointPair^>^>( - &winrt_resolve_op::do_complete), - query_(query), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code&, std::size_t) - { - // Take ownership of the operation object. - winrt_resolve_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - results_type results = results_type(); - if (!o->ec_) - { - try - { - results = results_type::create(o->result_, o->query_.hints(), - o->query_.host_name(), o->query_.service_name()); - } - catch (Platform::Exception^ e) - { - o->ec_ = asio::error_code(e->HResult, - asio::system_category()); - } - } - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, results); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, "...")); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - query_type query_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_RESOLVE_OP_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_resolver_service.hpp b/scout_sdk/asio/asio/detail/winrt_resolver_service.hpp deleted file mode 100644 index aeb4448..0000000 --- a/scout_sdk/asio/asio/detail/winrt_resolver_service.hpp +++ /dev/null @@ -1,198 +0,0 @@ -// -// detail/winrt_resolver_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_RESOLVER_SERVICE_HPP -#define ASIO_DETAIL_WINRT_RESOLVER_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/ip/basic_resolver_query.hpp" -#include "asio/ip/basic_resolver_results.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/winrt_async_manager.hpp" -#include "asio/detail/winrt_resolve_op.hpp" -#include "asio/detail/winrt_utils.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class winrt_resolver_service : - public service_base > -{ -public: - // The implementation type of the resolver. A cancellation token is used to - // indicate to the asynchronous operation that the operation has been - // cancelled. - typedef socket_ops::shared_cancel_token_type implementation_type; - - // The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - // The query type. - typedef asio::ip::basic_resolver_query query_type; - - // The results type. - typedef asio::ip::basic_resolver_results results_type; - - // Constructor. - winrt_resolver_service(asio::io_context& io_context) - : service_base >(io_context), - io_context_(use_service(io_context)), - async_manager_(use_service(io_context)) - { - } - - // Destructor. - ~winrt_resolver_service() - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - } - - // Perform any fork-related housekeeping. - void notify_fork(asio::io_context::fork_event) - { - } - - // Construct a new resolver implementation. - void construct(implementation_type&) - { - } - - // Move-construct a new resolver implementation. - void move_construct(implementation_type&, - implementation_type&) - { - } - - // Move-assign from another resolver implementation. - void move_assign(implementation_type&, - winrt_resolver_service&, implementation_type&) - { - } - - // Destroy a resolver implementation. - void destroy(implementation_type&) - { - } - - // Cancel pending asynchronous operations. - void cancel(implementation_type&) - { - } - - // Resolve a query to a list of entries. - results_type resolve(implementation_type&, - const query_type& query, asio::error_code& ec) - { - try - { - using namespace Windows::Networking::Sockets; - auto endpoint_pairs = async_manager_.sync( - DatagramSocket::GetEndpointPairsAsync( - winrt_utils::host_name(query.host_name()), - winrt_utils::string(query.service_name())), ec); - - if (ec) - return results_type(); - - return results_type::create( - endpoint_pairs, query.hints(), - query.host_name(), query.service_name()); - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - return results_type(); - } - } - - // Asynchronously resolve a query to a list of entries. - template - void async_resolve(implementation_type& impl, - const query_type& query, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef winrt_resolve_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(query, handler); - - ASIO_HANDLER_CREATION((io_context_.context(), - *p.p, "resolver", &impl, 0, "async_resolve")); - (void)impl; - - try - { - using namespace Windows::Networking::Sockets; - async_manager_.async(DatagramSocket::GetEndpointPairsAsync( - winrt_utils::host_name(query.host_name()), - winrt_utils::string(query.service_name())), p.p); - p.v = p.p = 0; - } - catch (Platform::Exception^ e) - { - p.p->ec_ = asio::error_code( - e->HResult, asio::system_category()); - io_context_.post_immediate_completion(p.p, is_continuation); - p.v = p.p = 0; - } - } - - // Resolve an endpoint to a list of entries. - results_type resolve(implementation_type&, - const endpoint_type&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return results_type(); - } - - // Asynchronously resolve an endpoint to a list of entries. - template - void async_resolve(implementation_type&, - const endpoint_type&, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const results_type results; - io_context_.get_io_context().post( - detail::bind_handler(handler, ec, results)); - } - -private: - io_context_impl& io_context_; - winrt_async_manager& async_manager_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_RESOLVER_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_socket_connect_op.hpp b/scout_sdk/asio/asio/detail/winrt_socket_connect_op.hpp deleted file mode 100644 index f18b445..0000000 --- a/scout_sdk/asio/asio/detail/winrt_socket_connect_op.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// -// detail/winrt_socket_connect_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_SOCKET_CONNECT_OP_HPP -#define ASIO_DETAIL_WINRT_SOCKET_CONNECT_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/winrt_async_op.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class winrt_socket_connect_op : - public winrt_async_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(winrt_socket_connect_op); - - winrt_socket_connect_op(Handler& handler) - : winrt_async_op(&winrt_socket_connect_op::do_complete), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code&, std::size_t) - { - // Take ownership of the operation object. - winrt_socket_connect_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder1 - handler(o->handler_, o->ec_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_SOCKET_CONNECT_OP_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_socket_recv_op.hpp b/scout_sdk/asio/asio/detail/winrt_socket_recv_op.hpp deleted file mode 100644 index 8f1fcf5..0000000 --- a/scout_sdk/asio/asio/detail/winrt_socket_recv_op.hpp +++ /dev/null @@ -1,112 +0,0 @@ -// -// detail/winrt_socket_recv_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_SOCKET_RECV_OP_HPP -#define ASIO_DETAIL_WINRT_SOCKET_RECV_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/winrt_async_op.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class winrt_socket_recv_op : - public winrt_async_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(winrt_socket_recv_op); - - winrt_socket_recv_op(const MutableBufferSequence& buffers, Handler& handler) - : winrt_async_op( - &winrt_socket_recv_op::do_complete), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code&, std::size_t) - { - // Take ownership of the operation object. - winrt_socket_recv_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - // Check whether buffers are still valid. - if (owner) - { - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - std::size_t bytes_transferred = o->result_ ? o->result_->Length : 0; - if (bytes_transferred == 0 && !o->ec_ && - !buffer_sequence_adapter::all_empty(o->buffers_)) - { - o->ec_ = asio::error::eof; - } - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, bytes_transferred); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - MutableBufferSequence buffers_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_SOCKET_RECV_OP_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_socket_send_op.hpp b/scout_sdk/asio/asio/detail/winrt_socket_send_op.hpp deleted file mode 100644 index 1148c24..0000000 --- a/scout_sdk/asio/asio/detail/winrt_socket_send_op.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// -// detail/winrt_socket_send_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_SOCKET_SEND_OP_HPP -#define ASIO_DETAIL_WINRT_SOCKET_SEND_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/winrt_async_op.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class winrt_socket_send_op : - public winrt_async_op -{ -public: - ASIO_DEFINE_HANDLER_PTR(winrt_socket_send_op); - - winrt_socket_send_op(const ConstBufferSequence& buffers, Handler& handler) - : winrt_async_op(&winrt_socket_send_op::do_complete), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - handler_work::start(handler_); - } - - static void do_complete(void* owner, operation* base, - const asio::error_code&, std::size_t) - { - // Take ownership of the operation object. - winrt_socket_send_op* o(static_cast(base)); - ptr p = { asio::detail::addressof(o->handler_), o, o }; - handler_work w(o->handler_); - - ASIO_HANDLER_COMPLETION((*o)); - -#if defined(ASIO_ENABLE_BUFFER_DEBUGGING) - // Check whether buffers are still valid. - if (owner) - { - buffer_sequence_adapter::validate(o->buffers_); - } -#endif // defined(ASIO_ENABLE_BUFFER_DEBUGGING) - - // Make a copy of the handler so that the memory can be deallocated before - // the upcall is made. Even if we're not about to make an upcall, a - // sub-object of the handler may be the true owner of the memory associated - // with the handler. Consequently, a local copy of the handler is required - // to ensure that any owning sub-object remains valid until after we have - // deallocated the memory here. - detail::binder2 - handler(o->handler_, o->ec_, o->result_); - p.h = asio::detail::addressof(handler.handler_); - p.reset(); - - // Make the upcall if required. - if (owner) - { - fenced_block b(fenced_block::half); - ASIO_HANDLER_INVOCATION_BEGIN((handler.arg1_, handler.arg2_)); - w.complete(handler, handler.handler_); - ASIO_HANDLER_INVOCATION_END; - } - } - -private: - ConstBufferSequence buffers_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_SOCKET_SEND_OP_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_ssocket_service.hpp b/scout_sdk/asio/asio/detail/winrt_ssocket_service.hpp deleted file mode 100644 index 603724a..0000000 --- a/scout_sdk/asio/asio/detail/winrt_ssocket_service.hpp +++ /dev/null @@ -1,241 +0,0 @@ -// -// detail/winrt_ssocket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_SSOCKET_SERVICE_HPP -#define ASIO_DETAIL_WINRT_SSOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/winrt_socket_connect_op.hpp" -#include "asio/detail/winrt_ssocket_service_base.hpp" -#include "asio/detail/winrt_utils.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class winrt_ssocket_service : - public service_base >, - public winrt_ssocket_service_base -{ -public: - // The protocol type. - typedef Protocol protocol_type; - - // The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - - // The native type of a socket. - typedef Windows::Networking::Sockets::StreamSocket^ native_handle_type; - - // The implementation type of the socket. - struct implementation_type : base_implementation_type - { - // Default constructor. - implementation_type() - : base_implementation_type(), - protocol_(endpoint_type().protocol()) - { - } - - // The protocol associated with the socket. - protocol_type protocol_; - }; - - // Constructor. - winrt_ssocket_service(asio::io_context& io_context) - : service_base >(io_context), - winrt_ssocket_service_base(io_context) - { - } - - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - this->base_shutdown(); - } - - // Move-construct a new socket implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - this->base_move_construct(impl, other_impl); - - impl.protocol_ = other_impl.protocol_; - other_impl.protocol_ = endpoint_type().protocol(); - } - - // Move-assign from another socket implementation. - void move_assign(implementation_type& impl, - winrt_ssocket_service& other_service, - implementation_type& other_impl) - { - this->base_move_assign(impl, other_service, other_impl); - - impl.protocol_ = other_impl.protocol_; - other_impl.protocol_ = endpoint_type().protocol(); - } - - // Move-construct a new socket implementation from another protocol type. - template - void converting_move_construct(implementation_type& impl, - winrt_ssocket_service&, - typename winrt_ssocket_service< - Protocol1>::implementation_type& other_impl) - { - this->base_move_construct(impl, other_impl); - - impl.protocol_ = protocol_type(other_impl.protocol_); - other_impl.protocol_ = typename Protocol1::endpoint().protocol(); - } - - // Open a new socket implementation. - asio::error_code open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - try - { - impl.socket_ = ref new Windows::Networking::Sockets::StreamSocket; - impl.protocol_ = protocol; - ec = asio::error_code(); - } - catch (Platform::Exception^ e) - { - ec = asio::error_code(e->HResult, - asio::system_category()); - } - - return ec; - } - - // Assign a native socket to a socket implementation. - asio::error_code assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_socket, - asio::error_code& ec) - { - if (is_open(impl)) - { - ec = asio::error::already_open; - return ec; - } - - impl.socket_ = native_socket; - impl.protocol_ = protocol; - ec = asio::error_code(); - - return ec; - } - - // Bind the socket to the specified local endpoint. - asio::error_code bind(implementation_type&, - const endpoint_type&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - endpoint_type endpoint; - endpoint.resize(do_get_endpoint(impl, true, - endpoint.data(), endpoint.size(), ec)); - return endpoint; - } - - // Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - endpoint_type endpoint; - endpoint.resize(do_get_endpoint(impl, false, - endpoint.data(), endpoint.size(), ec)); - return endpoint; - } - - // Set a socket option. - template - asio::error_code set_option(implementation_type& impl, - const Option& option, asio::error_code& ec) - { - return do_set_option(impl, option.level(impl.protocol_), - option.name(impl.protocol_), option.data(impl.protocol_), - option.size(impl.protocol_), ec); - } - - // Get a socket option. - template - asio::error_code get_option(const implementation_type& impl, - Option& option, asio::error_code& ec) const - { - std::size_t size = option.size(impl.protocol_); - do_get_option(impl, option.level(impl.protocol_), - option.name(impl.protocol_), - option.data(impl.protocol_), &size, ec); - if (!ec) - option.resize(impl.protocol_, size); - return ec; - } - - // Connect the socket to the specified endpoint. - asio::error_code connect(implementation_type& impl, - const endpoint_type& peer_endpoint, asio::error_code& ec) - { - return do_connect(impl, peer_endpoint.data(), ec); - } - - // Start an asynchronous connect. - template - void async_connect(implementation_type& impl, - const endpoint_type& peer_endpoint, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef winrt_socket_connect_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(handler); - - ASIO_HANDLER_CREATION((io_context_.context(), - *p.p, "socket", &impl, 0, "async_connect")); - - start_connect_op(impl, peer_endpoint.data(), p.p, is_continuation); - p.v = p.p = 0; - } -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_SSOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_ssocket_service_base.hpp b/scout_sdk/asio/asio/detail/winrt_ssocket_service_base.hpp deleted file mode 100644 index 61328d0..0000000 --- a/scout_sdk/asio/asio/detail/winrt_ssocket_service_base.hpp +++ /dev/null @@ -1,359 +0,0 @@ -// -// detail/winrt_ssocket_service_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_SSOCKET_SERVICE_BASE_HPP -#define ASIO_DETAIL_WINRT_SSOCKET_SERVICE_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/buffer.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/socket_base.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/winrt_async_manager.hpp" -#include "asio/detail/winrt_socket_recv_op.hpp" -#include "asio/detail/winrt_socket_send_op.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class winrt_ssocket_service_base -{ -public: - // The native type of a socket. - typedef Windows::Networking::Sockets::StreamSocket^ native_handle_type; - - // The implementation type of the socket. - struct base_implementation_type - { - // Default constructor. - base_implementation_type() - : socket_(nullptr), - next_(0), - prev_(0) - { - } - - // The underlying native socket. - native_handle_type socket_; - - // Pointers to adjacent socket implementations in linked list. - base_implementation_type* next_; - base_implementation_type* prev_; - }; - - // Constructor. - ASIO_DECL winrt_ssocket_service_base( - asio::io_context& io_context); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void base_shutdown(); - - // Construct a new socket implementation. - ASIO_DECL void construct(base_implementation_type&); - - // Move-construct a new socket implementation. - ASIO_DECL void base_move_construct(base_implementation_type& impl, - base_implementation_type& other_impl); - - // Move-assign from another socket implementation. - ASIO_DECL void base_move_assign(base_implementation_type& impl, - winrt_ssocket_service_base& other_service, - base_implementation_type& other_impl); - - // Destroy a socket implementation. - ASIO_DECL void destroy(base_implementation_type& impl); - - // Determine whether the socket is open. - bool is_open(const base_implementation_type& impl) const - { - return impl.socket_ != nullptr; - } - - // Destroy a socket implementation. - ASIO_DECL asio::error_code close( - base_implementation_type& impl, asio::error_code& ec); - - // Release ownership of the socket. - ASIO_DECL native_handle_type release( - base_implementation_type& impl, asio::error_code& ec); - - // Get the native socket representation. - native_handle_type native_handle(base_implementation_type& impl) - { - return impl.socket_; - } - - // Cancel all operations associated with the socket. - asio::error_code cancel(base_implementation_type&, - asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Determine whether the socket is at the out-of-band data mark. - bool at_mark(const base_implementation_type&, - asio::error_code& ec) const - { - ec = asio::error::operation_not_supported; - return false; - } - - // Determine the number of bytes available for reading. - std::size_t available(const base_implementation_type&, - asio::error_code& ec) const - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Perform an IO control command on the socket. - template - asio::error_code io_control(base_implementation_type&, - IO_Control_Command&, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Gets the non-blocking mode of the socket. - bool non_blocking(const base_implementation_type&) const - { - return false; - } - - // Sets the non-blocking mode of the socket. - asio::error_code non_blocking(base_implementation_type&, - bool, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const base_implementation_type&) const - { - return false; - } - - // Sets the non-blocking mode of the native socket implementation. - asio::error_code native_non_blocking(base_implementation_type&, - bool, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Disable sends or receives on the socket. - asio::error_code shutdown(base_implementation_type&, - socket_base::shutdown_type, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return ec; - } - - // Send the given data to the peer. - template - std::size_t send(base_implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return do_send(impl, - buffer_sequence_adapter::first(buffers), flags, ec); - } - - // Wait until data can be sent without blocking. - std::size_t send(base_implementation_type&, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Start an asynchronous send. The data being sent must be valid for the - // lifetime of the asynchronous operation. - template - void async_send(base_implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef winrt_socket_send_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(buffers, handler); - - ASIO_HANDLER_CREATION((io_context_.context(), - *p.p, "socket", &impl, 0, "async_send")); - - start_send_op(impl, - buffer_sequence_adapter::first(buffers), - flags, p.p, is_continuation); - p.v = p.p = 0; - } - - // Start an asynchronous wait until data can be sent without blocking. - template - void async_send(base_implementation_type&, const null_buffers&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.get_io_context().post( - detail::bind_handler(handler, ec, bytes_transferred)); - } - - // Receive some data from the peer. Returns the number of bytes received. - template - std::size_t receive(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return do_receive(impl, - buffer_sequence_adapter::first(buffers), flags, ec); - } - - // Wait until data can be received without blocking. - std::size_t receive(base_implementation_type&, const null_buffers&, - socket_base::message_flags, asio::error_code& ec) - { - ec = asio::error::operation_not_supported; - return 0; - } - - // Start an asynchronous receive. The buffer for the data being received - // must be valid for the lifetime of the asynchronous operation. - template - void async_receive(base_implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, Handler& handler) - { - bool is_continuation = - asio_handler_cont_helpers::is_continuation(handler); - - // Allocate and construct an operation to wrap the handler. - typedef winrt_socket_recv_op op; - typename op::ptr p = { asio::detail::addressof(handler), - op::ptr::allocate(handler), 0 }; - p.p = new (p.v) op(buffers, handler); - - ASIO_HANDLER_CREATION((io_context_.context(), - *p.p, "socket", &impl, 0, "async_receive")); - - start_receive_op(impl, - buffer_sequence_adapter::first(buffers), - flags, p.p, is_continuation); - p.v = p.p = 0; - } - - // Wait until data can be received without blocking. - template - void async_receive(base_implementation_type&, const null_buffers&, - socket_base::message_flags, Handler& handler) - { - asio::error_code ec = asio::error::operation_not_supported; - const std::size_t bytes_transferred = 0; - io_context_.get_io_context().post( - detail::bind_handler(handler, ec, bytes_transferred)); - } - -protected: - // Helper function to obtain endpoints associated with the connection. - ASIO_DECL std::size_t do_get_endpoint( - const base_implementation_type& impl, bool local, - void* addr, std::size_t addr_len, asio::error_code& ec) const; - - // Helper function to set a socket option. - ASIO_DECL asio::error_code do_set_option( - base_implementation_type& impl, - int level, int optname, const void* optval, - std::size_t optlen, asio::error_code& ec); - - // Helper function to get a socket option. - ASIO_DECL void do_get_option( - const base_implementation_type& impl, - int level, int optname, void* optval, - std::size_t* optlen, asio::error_code& ec) const; - - // Helper function to perform a synchronous connect. - ASIO_DECL asio::error_code do_connect( - base_implementation_type& impl, - const void* addr, asio::error_code& ec); - - // Helper function to start an asynchronous connect. - ASIO_DECL void start_connect_op( - base_implementation_type& impl, const void* addr, - winrt_async_op* op, bool is_continuation); - - // Helper function to perform a synchronous send. - ASIO_DECL std::size_t do_send( - base_implementation_type& impl, const asio::const_buffer& data, - socket_base::message_flags flags, asio::error_code& ec); - - // Helper function to start an asynchronous send. - ASIO_DECL void start_send_op(base_implementation_type& impl, - const asio::const_buffer& data, socket_base::message_flags flags, - winrt_async_op* op, bool is_continuation); - - // Helper function to perform a synchronous receive. - ASIO_DECL std::size_t do_receive( - base_implementation_type& impl, const asio::mutable_buffer& data, - socket_base::message_flags flags, asio::error_code& ec); - - // Helper function to start an asynchronous receive. - ASIO_DECL void start_receive_op(base_implementation_type& impl, - const asio::mutable_buffer& data, socket_base::message_flags flags, - winrt_async_op* op, - bool is_continuation); - - // The io_context implementation used for delivering completions. - io_context_impl& io_context_; - - // The manager that keeps track of outstanding operations. - winrt_async_manager& async_manager_; - - // Mutex to protect access to the linked list of implementations. - asio::detail::mutex mutex_; - - // The head of a linked list of all implementations. - base_implementation_type* impl_list_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/winrt_ssocket_service_base.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_SSOCKET_SERVICE_BASE_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_timer_scheduler.hpp b/scout_sdk/asio/asio/detail/winrt_timer_scheduler.hpp deleted file mode 100644 index 5dec7c0..0000000 --- a/scout_sdk/asio/asio/detail/winrt_timer_scheduler.hpp +++ /dev/null @@ -1,137 +0,0 @@ -// -// detail/winrt_timer_scheduler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_TIMER_SCHEDULER_HPP -#define ASIO_DETAIL_WINRT_TIMER_SCHEDULER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include -#include "asio/detail/event.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/op_queue.hpp" -#include "asio/detail/thread.hpp" -#include "asio/detail/timer_queue_base.hpp" -#include "asio/detail/timer_queue_set.hpp" -#include "asio/detail/wait_op.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_HAS_IOCP) -# include "asio/detail/thread.hpp" -#endif // defined(ASIO_HAS_IOCP) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class winrt_timer_scheduler - : public asio::detail::service_base -{ -public: - // Constructor. - ASIO_DECL winrt_timer_scheduler(asio::io_context& io_context); - - // Destructor. - ASIO_DECL ~winrt_timer_scheduler(); - - // Destroy all user-defined handler objects owned by the service. - ASIO_DECL void shutdown(); - - // Recreate internal descriptors following a fork. - ASIO_DECL void notify_fork( - asio::io_context::fork_event fork_ev); - - // Initialise the task. No effect as this class uses its own thread. - ASIO_DECL void init_task(); - - // Add a new timer queue to the reactor. - template - void add_timer_queue(timer_queue& queue); - - // Remove a timer queue from the reactor. - template - void remove_timer_queue(timer_queue& queue); - - // Schedule a new operation in the given timer queue to expire at the - // specified absolute time. - template - void schedule_timer(timer_queue& queue, - const typename Time_Traits::time_type& time, - typename timer_queue::per_timer_data& timer, wait_op* op); - - // Cancel the timer operations associated with the given token. Returns the - // number of operations that have been posted or dispatched. - template - std::size_t cancel_timer(timer_queue& queue, - typename timer_queue::per_timer_data& timer, - std::size_t max_cancelled = (std::numeric_limits::max)()); - - // Move the timer operations associated with the given timer. - template - void move_timer(timer_queue& queue, - typename timer_queue::per_timer_data& to, - typename timer_queue::per_timer_data& from); - -private: - // Run the select loop in the thread. - ASIO_DECL void run_thread(); - - // Entry point for the select loop thread. - ASIO_DECL static void call_run_thread(winrt_timer_scheduler* reactor); - - // Helper function to add a new timer queue. - ASIO_DECL void do_add_timer_queue(timer_queue_base& queue); - - // Helper function to remove a timer queue. - ASIO_DECL void do_remove_timer_queue(timer_queue_base& queue); - - // The io_context implementation used to post completions. - io_context_impl& io_context_; - - // Mutex used to protect internal variables. - asio::detail::mutex mutex_; - - // Event used to wake up background thread. - asio::detail::event event_; - - // The timer queues. - timer_queue_set timer_queues_; - - // The background thread that is waiting for timers to expire. - asio::detail::thread* thread_; - - // Does the background thread need to stop. - bool stop_thread_; - - // Whether the service has been shut down. - bool shutdown_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/detail/impl/winrt_timer_scheduler.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/winrt_timer_scheduler.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_TIMER_SCHEDULER_HPP diff --git a/scout_sdk/asio/asio/detail/winrt_utils.hpp b/scout_sdk/asio/asio/detail/winrt_utils.hpp deleted file mode 100644 index 22a2489..0000000 --- a/scout_sdk/asio/asio/detail/winrt_utils.hpp +++ /dev/null @@ -1,106 +0,0 @@ -// -// detail/winrt_utils.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINRT_UTILS_HPP -#define ASIO_DETAIL_WINRT_UTILS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) - -#include -#include -#include -#include -#include -#include -#include -#include "asio/buffer.hpp" -#include "asio/error_code.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/socket_ops.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { -namespace winrt_utils { - -inline Platform::String^ string(const char* from) -{ - std::wstring tmp(from, from + std::strlen(from)); - return ref new Platform::String(tmp.c_str()); -} - -inline Platform::String^ string(const std::string& from) -{ - std::wstring tmp(from.begin(), from.end()); - return ref new Platform::String(tmp.c_str()); -} - -inline std::string string(Platform::String^ from) -{ - std::wstring_convert> converter; - return converter.to_bytes(from->Data()); -} - -inline Platform::String^ string(unsigned short from) -{ - return string(std::to_string(from)); -} - -template -inline Platform::String^ string(const T& from) -{ - return string(from.to_string()); -} - -inline int integer(Platform::String^ from) -{ - return _wtoi(from->Data()); -} - -template -inline Windows::Networking::HostName^ host_name(const T& from) -{ - return ref new Windows::Networking::HostName((string)(from)); -} - -template -inline Windows::Storage::Streams::IBuffer^ buffer_dup( - const ConstBufferSequence& buffers) -{ - using Microsoft::WRL::ComPtr; - using asio::buffer_size; - std::size_t size = buffer_size(buffers); - auto b = ref new Windows::Storage::Streams::Buffer(size); - ComPtr insp = reinterpret_cast(b); - ComPtr bacc; - insp.As(&bacc); - byte* bytes = nullptr; - bacc->Buffer(&bytes); - asio::buffer_copy(asio::buffer(bytes, size), buffers); - b->Length = size; - return b; -} - -} // namespace winrt_utils -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#endif // ASIO_DETAIL_WINRT_UTILS_HPP diff --git a/scout_sdk/asio/asio/detail/winsock_init.hpp b/scout_sdk/asio/asio/detail/winsock_init.hpp deleted file mode 100644 index 9094363..0000000 --- a/scout_sdk/asio/asio/detail/winsock_init.hpp +++ /dev/null @@ -1,128 +0,0 @@ -// -// detail/winsock_init.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WINSOCK_INIT_HPP -#define ASIO_DETAIL_WINSOCK_INIT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class winsock_init_base -{ -protected: - // Structure to track result of initialisation and number of uses. POD is used - // to ensure that the values are zero-initialised prior to any code being run. - struct data - { - long init_count_; - long result_; - }; - - ASIO_DECL static void startup(data& d, - unsigned char major, unsigned char minor); - - ASIO_DECL static void manual_startup(data& d); - - ASIO_DECL static void cleanup(data& d); - - ASIO_DECL static void manual_cleanup(data& d); - - ASIO_DECL static void throw_on_error(data& d); -}; - -template -class winsock_init : private winsock_init_base -{ -public: - winsock_init(bool allow_throw = true) - { - startup(data_, Major, Minor); - if (allow_throw) - throw_on_error(data_); - } - - winsock_init(const winsock_init&) - { - startup(data_, Major, Minor); - throw_on_error(data_); - } - - ~winsock_init() - { - cleanup(data_); - } - - // This class may be used to indicate that user code will manage Winsock - // initialisation and cleanup. This may be required in the case of a DLL, for - // example, where it is not safe to initialise Winsock from global object - // constructors. - // - // To prevent asio from initialising Winsock, the object must be constructed - // before any Asio's own global objects. With MSVC, this may be accomplished - // by adding the following code to the DLL: - // - // #pragma warning(push) - // #pragma warning(disable:4073) - // #pragma init_seg(lib) - // asio::detail::winsock_init<>::manual manual_winsock_init; - // #pragma warning(pop) - class manual - { - public: - manual() - { - manual_startup(data_); - } - - manual(const manual&) - { - manual_startup(data_); - } - - ~manual() - { - manual_cleanup(data_); - } - }; - -private: - friend class manual; - static data data_; -}; - -template -winsock_init_base::data winsock_init::data_; - -// Static variable to ensure that winsock is initialised before main, and -// therefore before any other threads can get started. -static const winsock_init<>& winsock_init_instance = winsock_init<>(false); - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/detail/impl/winsock_init.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - -#endif // ASIO_DETAIL_WINSOCK_INIT_HPP diff --git a/scout_sdk/asio/asio/detail/work_dispatcher.hpp b/scout_sdk/asio/asio/detail/work_dispatcher.hpp deleted file mode 100644 index 7abce49..0000000 --- a/scout_sdk/asio/asio/detail/work_dispatcher.hpp +++ /dev/null @@ -1,72 +0,0 @@ -// -// detail/work_dispatcher.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WORK_DISPATCHER_HPP -#define ASIO_DETAIL_WORK_DISPATCHER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_executor.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/executor_work_guard.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class work_dispatcher -{ -public: - work_dispatcher(Handler& handler) - : work_((get_associated_executor)(handler)), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - work_dispatcher(const work_dispatcher& other) - : work_(other.work_), - handler_(other.handler_) - { - } - - work_dispatcher(work_dispatcher&& other) - : work_(ASIO_MOVE_CAST(executor_work_guard< - typename associated_executor::type>)(other.work_)), - handler_(ASIO_MOVE_CAST(Handler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - typename associated_allocator::type alloc( - (get_associated_allocator)(handler_)); - work_.get_executor().dispatch( - ASIO_MOVE_CAST(Handler)(handler_), alloc); - work_.reset(); - } - -private: - executor_work_guard::type> work_; - Handler handler_; -}; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_WORK_DISPATCHER_HPP diff --git a/scout_sdk/asio/asio/detail/wrapped_handler.hpp b/scout_sdk/asio/asio/detail/wrapped_handler.hpp deleted file mode 100644 index 751f0ea..0000000 --- a/scout_sdk/asio/asio/detail/wrapped_handler.hpp +++ /dev/null @@ -1,291 +0,0 @@ -// -// detail/wrapped_handler.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DETAIL_WRAPPED_HANDLER_HPP -#define ASIO_DETAIL_WRAPPED_HANDLER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -struct is_continuation_delegated -{ - template - bool operator()(Dispatcher&, Handler& handler) const - { - return asio_handler_cont_helpers::is_continuation(handler); - } -}; - -struct is_continuation_if_running -{ - template - bool operator()(Dispatcher& dispatcher, Handler&) const - { - return dispatcher.running_in_this_thread(); - } -}; - -template -class wrapped_handler -{ -public: - typedef void result_type; - - wrapped_handler(Dispatcher dispatcher, Handler& handler) - : dispatcher_(dispatcher), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - wrapped_handler(const wrapped_handler& other) - : dispatcher_(other.dispatcher_), - handler_(other.handler_) - { - } - - wrapped_handler(wrapped_handler&& other) - : dispatcher_(other.dispatcher_), - handler_(ASIO_MOVE_CAST(Handler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - dispatcher_.dispatch(ASIO_MOVE_CAST(Handler)(handler_)); - } - - void operator()() const - { - dispatcher_.dispatch(handler_); - } - - template - void operator()(const Arg1& arg1) - { - dispatcher_.dispatch(detail::bind_handler(handler_, arg1)); - } - - template - void operator()(const Arg1& arg1) const - { - dispatcher_.dispatch(detail::bind_handler(handler_, arg1)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2) - { - dispatcher_.dispatch(detail::bind_handler(handler_, arg1, arg2)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2) const - { - dispatcher_.dispatch(detail::bind_handler(handler_, arg1, arg2)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2, const Arg3& arg3) - { - dispatcher_.dispatch(detail::bind_handler(handler_, arg1, arg2, arg3)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2, const Arg3& arg3) const - { - dispatcher_.dispatch(detail::bind_handler(handler_, arg1, arg2, arg3)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2, const Arg3& arg3, - const Arg4& arg4) - { - dispatcher_.dispatch( - detail::bind_handler(handler_, arg1, arg2, arg3, arg4)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2, const Arg3& arg3, - const Arg4& arg4) const - { - dispatcher_.dispatch( - detail::bind_handler(handler_, arg1, arg2, arg3, arg4)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2, const Arg3& arg3, - const Arg4& arg4, const Arg5& arg5) - { - dispatcher_.dispatch( - detail::bind_handler(handler_, arg1, arg2, arg3, arg4, arg5)); - } - - template - void operator()(const Arg1& arg1, const Arg2& arg2, const Arg3& arg3, - const Arg4& arg4, const Arg5& arg5) const - { - dispatcher_.dispatch( - detail::bind_handler(handler_, arg1, arg2, arg3, arg4, arg5)); - } - -//private: - Dispatcher dispatcher_; - Handler handler_; -}; - -template -class rewrapped_handler -{ -public: - explicit rewrapped_handler(Handler& handler, const Context& context) - : context_(context), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - } - - explicit rewrapped_handler(const Handler& handler, const Context& context) - : context_(context), - handler_(handler) - { - } - -#if defined(ASIO_HAS_MOVE) - rewrapped_handler(const rewrapped_handler& other) - : context_(other.context_), - handler_(other.handler_) - { - } - - rewrapped_handler(rewrapped_handler&& other) - : context_(ASIO_MOVE_CAST(Context)(other.context_)), - handler_(ASIO_MOVE_CAST(Handler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()() - { - handler_(); - } - - void operator()() const - { - handler_(); - } - -//private: - Context context_; - Handler handler_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - wrapped_handler* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - wrapped_handler* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - wrapped_handler* this_handler) -{ - return IsContinuation()(this_handler->dispatcher_, this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - wrapped_handler* this_handler) -{ - this_handler->dispatcher_.dispatch( - rewrapped_handler( - function, this_handler->handler_)); -} - -template -inline void asio_handler_invoke(const Function& function, - wrapped_handler* this_handler) -{ - this_handler->dispatcher_.dispatch( - rewrapped_handler( - function, this_handler->handler_)); -} - -template -inline void* asio_handler_allocate(std::size_t size, - rewrapped_handler* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->context_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - rewrapped_handler* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->context_); -} - -template -inline bool asio_handler_is_continuation( - rewrapped_handler* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->context_); -} - -template -inline void asio_handler_invoke(Function& function, - rewrapped_handler* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->context_); -} - -template -inline void asio_handler_invoke(const Function& function, - rewrapped_handler* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->context_); -} - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_DETAIL_WRAPPED_HANDLER_HPP diff --git a/scout_sdk/asio/asio/dispatch.hpp b/scout_sdk/asio/asio/dispatch.hpp deleted file mode 100644 index b8dfd69..0000000 --- a/scout_sdk/asio/asio/dispatch.hpp +++ /dev/null @@ -1,108 +0,0 @@ -// -// dispatch.hpp -// ~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_DISPATCH_HPP -#define ASIO_DISPATCH_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/execution_context.hpp" -#include "asio/is_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Submits a completion token or function object for execution. -/** - * This function submits an object for execution using the object's associated - * executor. The function object is queued for execution, and is never called - * from the current thread prior to returning from dispatch(). - * - * This function has the following effects: - * - * @li Constructs a function object handler of type @c Handler, initialized - * with handler(forward(token)). - * - * @li Constructs an object @c result of type async_result, - * initializing the object as result(handler). - * - * @li Obtains the handler's associated executor object @c ex by performing - * get_associated_executor(handler). - * - * @li Obtains the handler's associated allocator object @c alloc by performing - * get_associated_allocator(handler). - * - * @li Performs ex.dispatch(std::move(handler), alloc). - * - * @li Returns result.get(). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) dispatch( - ASIO_MOVE_ARG(CompletionToken) token); - -/// Submits a completion token or function object for execution. -/** - * This function submits an object for execution using the specified executor. - * The function object is queued for execution, and is never called from the - * current thread prior to returning from dispatch(). - * - * This function has the following effects: - * - * @li Constructs a function object handler of type @c Handler, initialized - * with handler(forward(token)). - * - * @li Constructs an object @c result of type async_result, - * initializing the object as result(handler). - * - * @li Obtains the handler's associated executor object @c ex1 by performing - * get_associated_executor(handler). - * - * @li Creates a work object @c w by performing make_work(ex1). - * - * @li Obtains the handler's associated allocator object @c alloc by performing - * get_associated_allocator(handler). - * - * @li Constructs a function object @c f with a function call operator that - * performs ex1.dispatch(std::move(handler), alloc) followed by - * w.reset(). - * - * @li Performs Executor(ex).dispatch(std::move(f), alloc). - * - * @li Returns result.get(). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) dispatch( - const Executor& ex, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type* = 0); - -/// Submits a completion token or function object for execution. -/** - * @returns dispatch(ctx.get_executor(), - * forward(token)). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) dispatch( - ExecutionContext& ctx, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type* = 0); - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/dispatch.hpp" - -#endif // ASIO_DISPATCH_HPP diff --git a/scout_sdk/asio/asio/error.hpp b/scout_sdk/asio/asio/error.hpp deleted file mode 100644 index 2be9bde..0000000 --- a/scout_sdk/asio/asio/error.hpp +++ /dev/null @@ -1,356 +0,0 @@ -// -// error.hpp -// ~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_ERROR_HPP -#define ASIO_ERROR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/error_code.hpp" -#include "asio/system_error.hpp" -#if defined(ASIO_WINDOWS) \ - || defined(__CYGWIN__) \ - || defined(ASIO_WINDOWS_RUNTIME) -# include -#else -# include -# include -#endif - -#if defined(GENERATING_DOCUMENTATION) -/// INTERNAL ONLY. -# define ASIO_NATIVE_ERROR(e) implementation_defined -/// INTERNAL ONLY. -# define ASIO_SOCKET_ERROR(e) implementation_defined -/// INTERNAL ONLY. -# define ASIO_NETDB_ERROR(e) implementation_defined -/// INTERNAL ONLY. -# define ASIO_GETADDRINFO_ERROR(e) implementation_defined -/// INTERNAL ONLY. -# define ASIO_WIN_OR_POSIX(e_win, e_posix) implementation_defined -#elif defined(ASIO_WINDOWS_RUNTIME) -# define ASIO_NATIVE_ERROR(e) __HRESULT_FROM_WIN32(e) -# define ASIO_SOCKET_ERROR(e) __HRESULT_FROM_WIN32(WSA ## e) -# define ASIO_NETDB_ERROR(e) __HRESULT_FROM_WIN32(WSA ## e) -# define ASIO_GETADDRINFO_ERROR(e) __HRESULT_FROM_WIN32(WSA ## e) -# define ASIO_WIN_OR_POSIX(e_win, e_posix) e_win -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# define ASIO_NATIVE_ERROR(e) e -# define ASIO_SOCKET_ERROR(e) WSA ## e -# define ASIO_NETDB_ERROR(e) WSA ## e -# define ASIO_GETADDRINFO_ERROR(e) WSA ## e -# define ASIO_WIN_OR_POSIX(e_win, e_posix) e_win -#else -# define ASIO_NATIVE_ERROR(e) e -# define ASIO_SOCKET_ERROR(e) e -# define ASIO_NETDB_ERROR(e) e -# define ASIO_GETADDRINFO_ERROR(e) e -# define ASIO_WIN_OR_POSIX(e_win, e_posix) e_posix -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace error { - -enum basic_errors -{ - /// Permission denied. - access_denied = ASIO_SOCKET_ERROR(EACCES), - - /// Address family not supported by protocol. - address_family_not_supported = ASIO_SOCKET_ERROR(EAFNOSUPPORT), - - /// Address already in use. - address_in_use = ASIO_SOCKET_ERROR(EADDRINUSE), - - /// Transport endpoint is already connected. - already_connected = ASIO_SOCKET_ERROR(EISCONN), - - /// Operation already in progress. - already_started = ASIO_SOCKET_ERROR(EALREADY), - - /// Broken pipe. - broken_pipe = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(ERROR_BROKEN_PIPE), - ASIO_NATIVE_ERROR(EPIPE)), - - /// A connection has been aborted. - connection_aborted = ASIO_SOCKET_ERROR(ECONNABORTED), - - /// Connection refused. - connection_refused = ASIO_SOCKET_ERROR(ECONNREFUSED), - - /// Connection reset by peer. - connection_reset = ASIO_SOCKET_ERROR(ECONNRESET), - - /// Bad file descriptor. - bad_descriptor = ASIO_SOCKET_ERROR(EBADF), - - /// Bad address. - fault = ASIO_SOCKET_ERROR(EFAULT), - - /// No route to host. - host_unreachable = ASIO_SOCKET_ERROR(EHOSTUNREACH), - - /// Operation now in progress. - in_progress = ASIO_SOCKET_ERROR(EINPROGRESS), - - /// Interrupted system call. - interrupted = ASIO_SOCKET_ERROR(EINTR), - - /// Invalid argument. - invalid_argument = ASIO_SOCKET_ERROR(EINVAL), - - /// Message too long. - message_size = ASIO_SOCKET_ERROR(EMSGSIZE), - - /// The name was too long. - name_too_long = ASIO_SOCKET_ERROR(ENAMETOOLONG), - - /// Network is down. - network_down = ASIO_SOCKET_ERROR(ENETDOWN), - - /// Network dropped connection on reset. - network_reset = ASIO_SOCKET_ERROR(ENETRESET), - - /// Network is unreachable. - network_unreachable = ASIO_SOCKET_ERROR(ENETUNREACH), - - /// Too many open files. - no_descriptors = ASIO_SOCKET_ERROR(EMFILE), - - /// No buffer space available. - no_buffer_space = ASIO_SOCKET_ERROR(ENOBUFS), - - /// Cannot allocate memory. - no_memory = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(ERROR_OUTOFMEMORY), - ASIO_NATIVE_ERROR(ENOMEM)), - - /// Operation not permitted. - no_permission = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(ERROR_ACCESS_DENIED), - ASIO_NATIVE_ERROR(EPERM)), - - /// Protocol not available. - no_protocol_option = ASIO_SOCKET_ERROR(ENOPROTOOPT), - - /// No such device. - no_such_device = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(ERROR_BAD_UNIT), - ASIO_NATIVE_ERROR(ENODEV)), - - /// Transport endpoint is not connected. - not_connected = ASIO_SOCKET_ERROR(ENOTCONN), - - /// Socket operation on non-socket. - not_socket = ASIO_SOCKET_ERROR(ENOTSOCK), - - /// Operation cancelled. - operation_aborted = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(ERROR_OPERATION_ABORTED), - ASIO_NATIVE_ERROR(ECANCELED)), - - /// Operation not supported. - operation_not_supported = ASIO_SOCKET_ERROR(EOPNOTSUPP), - - /// Cannot send after transport endpoint shutdown. - shut_down = ASIO_SOCKET_ERROR(ESHUTDOWN), - - /// Connection timed out. - timed_out = ASIO_SOCKET_ERROR(ETIMEDOUT), - - /// Resource temporarily unavailable. - try_again = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(ERROR_RETRY), - ASIO_NATIVE_ERROR(EAGAIN)), - - /// The socket is marked non-blocking and the requested operation would block. - would_block = ASIO_SOCKET_ERROR(EWOULDBLOCK) -}; - -enum netdb_errors -{ - /// Host not found (authoritative). - host_not_found = ASIO_NETDB_ERROR(HOST_NOT_FOUND), - - /// Host not found (non-authoritative). - host_not_found_try_again = ASIO_NETDB_ERROR(TRY_AGAIN), - - /// The query is valid but does not have associated address data. - no_data = ASIO_NETDB_ERROR(NO_DATA), - - /// A non-recoverable error occurred. - no_recovery = ASIO_NETDB_ERROR(NO_RECOVERY) -}; - -enum addrinfo_errors -{ - /// The service is not supported for the given socket type. - service_not_found = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(WSATYPE_NOT_FOUND), - ASIO_GETADDRINFO_ERROR(EAI_SERVICE)), - - /// The socket type is not supported. - socket_type_not_supported = ASIO_WIN_OR_POSIX( - ASIO_NATIVE_ERROR(WSAESOCKTNOSUPPORT), - ASIO_GETADDRINFO_ERROR(EAI_SOCKTYPE)) -}; - -enum misc_errors -{ - /// Already open. - already_open = 1, - - /// End of file or stream. - eof, - - /// Element not found. - not_found, - - /// The descriptor cannot fit into the select system call's fd_set. - fd_set_failure -}; - -inline const asio::error_category& get_system_category() -{ - return asio::system_category(); -} - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -extern ASIO_DECL -const asio::error_category& get_netdb_category(); - -extern ASIO_DECL -const asio::error_category& get_addrinfo_category(); - -#else // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -inline const asio::error_category& get_netdb_category() -{ - return get_system_category(); -} - -inline const asio::error_category& get_addrinfo_category() -{ - return get_system_category(); -} - -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -extern ASIO_DECL -const asio::error_category& get_misc_category(); - -static const asio::error_category& - system_category ASIO_UNUSED_VARIABLE - = asio::error::get_system_category(); -static const asio::error_category& - netdb_category ASIO_UNUSED_VARIABLE - = asio::error::get_netdb_category(); -static const asio::error_category& - addrinfo_category ASIO_UNUSED_VARIABLE - = asio::error::get_addrinfo_category(); -static const asio::error_category& - misc_category ASIO_UNUSED_VARIABLE - = asio::error::get_misc_category(); - -} // namespace error -} // namespace asio - -#if defined(ASIO_HAS_STD_SYSTEM_ERROR) -namespace std { - -template<> struct is_error_code_enum -{ - static const bool value = true; -}; - -template<> struct is_error_code_enum -{ - static const bool value = true; -}; - -template<> struct is_error_code_enum -{ - static const bool value = true; -}; - -template<> struct is_error_code_enum -{ - static const bool value = true; -}; - -} // namespace std -#endif // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -namespace asio { -namespace error { - -inline asio::error_code make_error_code(basic_errors e) -{ - return asio::error_code( - static_cast(e), get_system_category()); -} - -inline asio::error_code make_error_code(netdb_errors e) -{ - return asio::error_code( - static_cast(e), get_netdb_category()); -} - -inline asio::error_code make_error_code(addrinfo_errors e) -{ - return asio::error_code( - static_cast(e), get_addrinfo_category()); -} - -inline asio::error_code make_error_code(misc_errors e) -{ - return asio::error_code( - static_cast(e), get_misc_category()); -} - -} // namespace error -namespace stream_errc { - // Simulates the proposed stream_errc scoped enum. - using error::eof; - using error::not_found; -} // namespace stream_errc -namespace socket_errc { - // Simulates the proposed socket_errc scoped enum. - using error::already_open; - using error::not_found; -} // namespace socket_errc -namespace resolver_errc { - // Simulates the proposed resolver_errc scoped enum. - using error::host_not_found; - const error::netdb_errors try_again = error::host_not_found_try_again; - using error::service_not_found; -} // namespace resolver_errc -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#undef ASIO_NATIVE_ERROR -#undef ASIO_SOCKET_ERROR -#undef ASIO_NETDB_ERROR -#undef ASIO_GETADDRINFO_ERROR -#undef ASIO_WIN_OR_POSIX - -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/error.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_ERROR_HPP diff --git a/scout_sdk/asio/asio/error_code.hpp b/scout_sdk/asio/asio/error_code.hpp deleted file mode 100644 index 7c239e2..0000000 --- a/scout_sdk/asio/asio/error_code.hpp +++ /dev/null @@ -1,202 +0,0 @@ -// -// error_code.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_ERROR_CODE_HPP -#define ASIO_ERROR_CODE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_SYSTEM_ERROR) -# include -#else // defined(ASIO_HAS_STD_SYSTEM_ERROR) -# include -# include "asio/detail/noncopyable.hpp" -# if !defined(ASIO_NO_IOSTREAM) -# include -# endif // !defined(ASIO_NO_IOSTREAM) -#endif // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if defined(ASIO_HAS_STD_SYSTEM_ERROR) - -typedef std::error_category error_category; - -#else // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -/// Base class for all error categories. -class error_category : private noncopyable -{ -public: - /// Destructor. - virtual ~error_category() - { - } - - /// Returns a string naming the error gategory. - virtual const char* name() const = 0; - - /// Returns a string describing the error denoted by @c value. - virtual std::string message(int value) const = 0; - - /// Equality operator to compare two error categories. - bool operator==(const error_category& rhs) const - { - return this == &rhs; - } - - /// Inequality operator to compare two error categories. - bool operator!=(const error_category& rhs) const - { - return !(*this == rhs); - } -}; - -#endif // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -/// Returns the error category used for the system errors produced by asio. -extern ASIO_DECL const error_category& system_category(); - -#if defined(ASIO_HAS_STD_SYSTEM_ERROR) - -typedef std::error_code error_code; - -#else // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -/// Class to represent an error code value. -class error_code -{ -public: - /// Default constructor. - error_code() - : value_(0), - category_(&system_category()) - { - } - - /// Construct with specific error code and category. - error_code(int v, const error_category& c) - : value_(v), - category_(&c) - { - } - - /// Construct from an error code enum. - template - error_code(ErrorEnum e) - { - *this = make_error_code(e); - } - - /// Clear the error value to the default. - void clear() - { - value_ = 0; - category_ = &system_category(); - } - - /// Assign a new error value. - void assign(int v, const error_category& c) - { - value_ = v; - category_ = &c; - } - - /// Get the error value. - int value() const - { - return value_; - } - - /// Get the error category. - const error_category& category() const - { - return *category_; - } - - /// Get the message associated with the error. - std::string message() const - { - return category_->message(value_); - } - - struct unspecified_bool_type_t - { - }; - - typedef void (*unspecified_bool_type)(unspecified_bool_type_t); - - static void unspecified_bool_true(unspecified_bool_type_t) {} - - /// Operator returns non-null if there is a non-success error code. - operator unspecified_bool_type() const - { - if (value_ == 0) - return 0; - else - return &error_code::unspecified_bool_true; - } - - /// Operator to test if the error represents success. - bool operator!() const - { - return value_ == 0; - } - - /// Equality operator to compare two error objects. - friend bool operator==(const error_code& e1, const error_code& e2) - { - return e1.value_ == e2.value_ && e1.category_ == e2.category_; - } - - /// Inequality operator to compare two error objects. - friend bool operator!=(const error_code& e1, const error_code& e2) - { - return e1.value_ != e2.value_ || e1.category_ != e2.category_; - } - -private: - // The value associated with the error code. - int value_; - - // The category associated with the error code. - const error_category* category_; -}; - -# if !defined(ASIO_NO_IOSTREAM) - -/// Output an error code. -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const error_code& ec) -{ - os << ec.category().name() << ':' << ec.value(); - return os; -} - -# endif // !defined(ASIO_NO_IOSTREAM) - -#endif // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/error_code.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_ERROR_CODE_HPP diff --git a/scout_sdk/asio/asio/execution_context.hpp b/scout_sdk/asio/asio/execution_context.hpp deleted file mode 100644 index 1476d19..0000000 --- a/scout_sdk/asio/asio/execution_context.hpp +++ /dev/null @@ -1,411 +0,0 @@ -// -// execution_context.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXECUTION_CONTEXT_HPP -#define ASIO_EXECUTION_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/variadic_templates.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -class execution_context; -class io_context; - -#if !defined(GENERATING_DOCUMENTATION) -template Service& use_service(execution_context&); -template Service& use_service(io_context&); -template void add_service(execution_context&, Service*); -template bool has_service(execution_context&); -#endif // !defined(GENERATING_DOCUMENTATION) - -namespace detail { class service_registry; } - -/// A context for function object execution. -/** - * An execution context represents a place where function objects will be - * executed. An @c io_context is an example of an execution context. - * - * @par The execution_context class and services - * - * Class execution_context implements an extensible, type-safe, polymorphic set - * of services, indexed by service type. - * - * Services exist to manage the resources that are shared across an execution - * context. For example, timers may be implemented in terms of a single timer - * queue, and this queue would be stored in a service. - * - * Access to the services of an execution_context is via three function - * templates, use_service(), add_service() and has_service(). - * - * In a call to @c use_service(), the type argument chooses a service, - * making available all members of the named type. If @c Service is not present - * in an execution_context, an object of type @c Service is created and added - * to the execution_context. A C++ program can check if an execution_context - * implements a particular service with the function template @c - * has_service(). - * - * Service objects may be explicitly added to an execution_context using the - * function template @c add_service(). If the @c Service is already - * present, the service_already_exists exception is thrown. If the owner of the - * service is not the same object as the execution_context parameter, the - * invalid_service_owner exception is thrown. - * - * Once a service reference is obtained from an execution_context object by - * calling use_service(), that reference remains usable as long as the owning - * execution_context object exists. - * - * All service implementations have execution_context::service as a public base - * class. Custom services may be implemented by deriving from this class and - * then added to an execution_context using the facilities described above. - * - * @par The execution_context as a base class - * - * Class execution_context may be used only as a base class for concrete - * execution context types. The @c io_context is an example of such a derived - * type. - * - * On destruction, a class that is derived from execution_context must perform - * execution_context::shutdown() followed by - * execution_context::destroy(). - * - * This destruction sequence permits programs to simplify their resource - * management by using @c shared_ptr<>. Where an object's lifetime is tied to - * the lifetime of a connection (or some other sequence of asynchronous - * operations), a @c shared_ptr to the object would be bound into the handlers - * for all asynchronous operations associated with it. This works as follows: - * - * @li When a single connection ends, all associated asynchronous operations - * complete. The corresponding handler objects are destroyed, and all @c - * shared_ptr references to the objects are destroyed. - * - * @li To shut down the whole program, the io_context function stop() is called - * to terminate any run() calls as soon as possible. The io_context destructor - * calls @c shutdown() and @c destroy() to destroy all pending handlers, - * causing all @c shared_ptr references to all connection objects to be - * destroyed. - */ -class execution_context - : private noncopyable -{ -public: - class id; - class service; - -protected: - /// Constructor. - ASIO_DECL execution_context(); - - /// Destructor. - ASIO_DECL ~execution_context(); - - /// Shuts down all services in the context. - /** - * This function is implemented as follows: - * - * @li For each service object @c svc in the execution_context set, in - * reverse order of the beginning of service object lifetime, performs @c - * svc->shutdown(). - */ - ASIO_DECL void shutdown(); - - /// Destroys all services in the context. - /** - * This function is implemented as follows: - * - * @li For each service object @c svc in the execution_context set, in - * reverse order * of the beginning of service object lifetime, performs - * delete static_cast(svc). - */ - ASIO_DECL void destroy(); - -public: - /// Fork-related event notifications. - enum fork_event - { - /// Notify the context that the process is about to fork. - fork_prepare, - - /// Notify the context that the process has forked and is the parent. - fork_parent, - - /// Notify the context that the process has forked and is the child. - fork_child - }; - - /// Notify the execution_context of a fork-related event. - /** - * This function is used to inform the execution_context that the process is - * about to fork, or has just forked. This allows the execution_context, and - * the services it contains, to perform any necessary housekeeping to ensure - * correct operation following a fork. - * - * This function must not be called while any other execution_context - * function, or any function associated with the execution_context's derived - * class, is being called in another thread. It is, however, safe to call - * this function from within a completion handler, provided no other thread - * is accessing the execution_context or its derived class. - * - * @param event A fork-related event. - * - * @throws asio::system_error Thrown on failure. If the notification - * fails the execution_context object should no longer be used and should be - * destroyed. - * - * @par Example - * The following code illustrates how to incorporate the notify_fork() - * function: - * @code my_execution_context.notify_fork(execution_context::fork_prepare); - * if (fork() == 0) - * { - * // This is the child process. - * my_execution_context.notify_fork(execution_context::fork_child); - * } - * else - * { - * // This is the parent process. - * my_execution_context.notify_fork(execution_context::fork_parent); - * } @endcode - * - * @note For each service object @c svc in the execution_context set, - * performs svc->notify_fork();. When processing the fork_prepare - * event, services are visited in reverse order of the beginning of service - * object lifetime. Otherwise, services are visited in order of the beginning - * of service object lifetime. - */ - ASIO_DECL void notify_fork(fork_event event); - - /// Obtain the service object corresponding to the given type. - /** - * This function is used to locate a service object that corresponds to the - * given service type. If there is no existing implementation of the service, - * then the execution_context will create a new instance of the service. - * - * @param e The execution_context object that owns the service. - * - * @return The service interface implementing the specified service type. - * Ownership of the service interface is not transferred to the caller. - */ - template - friend Service& use_service(execution_context& e); - - /// Obtain the service object corresponding to the given type. - /** - * This function is used to locate a service object that corresponds to the - * given service type. If there is no existing implementation of the service, - * then the io_context will create a new instance of the service. - * - * @param ioc The io_context object that owns the service. - * - * @return The service interface implementing the specified service type. - * Ownership of the service interface is not transferred to the caller. - * - * @note This overload is preserved for backwards compatibility with services - * that inherit from io_context::service. - */ - template - friend Service& use_service(io_context& ioc); - -#if defined(GENERATING_DOCUMENTATION) - - /// Creates a service object and adds it to the execution_context. - /** - * This function is used to add a service to the execution_context. - * - * @param e The execution_context object that owns the service. - * - * @param args Zero or more arguments to be passed to the service - * constructor. - * - * @throws asio::service_already_exists Thrown if a service of the - * given type is already present in the execution_context. - */ - template - friend Service& make_service(execution_context& e, Args&&... args); - -#elif defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - friend Service& make_service(execution_context& e, - ASIO_MOVE_ARG(Args)... args); - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - friend Service& make_service(execution_context& e); - -#define ASIO_PRIVATE_MAKE_SERVICE_DEF(n) \ - template \ - friend Service& make_service(execution_context& e, \ - ASIO_VARIADIC_MOVE_PARAMS(n)); \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_MAKE_SERVICE_DEF) -#undef ASIO_PRIVATE_MAKE_SERVICE_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - - /// (Deprecated: Use make_service().) Add a service object to the - /// execution_context. - /** - * This function is used to add a service to the execution_context. - * - * @param e The execution_context object that owns the service. - * - * @param svc The service object. On success, ownership of the service object - * is transferred to the execution_context. When the execution_context object - * is destroyed, it will destroy the service object by performing: @code - * delete static_cast(svc) @endcode - * - * @throws asio::service_already_exists Thrown if a service of the - * given type is already present in the execution_context. - * - * @throws asio::invalid_service_owner Thrown if the service's owning - * execution_context is not the execution_context object specified by the - * @c e parameter. - */ - template - friend void add_service(execution_context& e, Service* svc); - - /// Determine if an execution_context contains a specified service type. - /** - * This function is used to determine whether the execution_context contains a - * service object corresponding to the given service type. - * - * @param e The execution_context object that owns the service. - * - * @return A boolean indicating whether the execution_context contains the - * service. - */ - template - friend bool has_service(execution_context& e); - -private: - // The service registry. - asio::detail::service_registry* service_registry_; -}; - -/// Class used to uniquely identify a service. -class execution_context::id - : private noncopyable -{ -public: - /// Constructor. - id() {} -}; - -/// Base class for all io_context services. -class execution_context::service - : private noncopyable -{ -public: - /// Get the context object that owns the service. - execution_context& context(); - -protected: - /// Constructor. - /** - * @param owner The execution_context object that owns the service. - */ - ASIO_DECL service(execution_context& owner); - - /// Destructor. - ASIO_DECL virtual ~service(); - -private: - /// Destroy all user-defined handler objects owned by the service. - virtual void shutdown() = 0; - - /// Handle notification of a fork-related event to perform any necessary - /// housekeeping. - /** - * This function is not a pure virtual so that services only have to - * implement it if necessary. The default implementation does nothing. - */ - ASIO_DECL virtual void notify_fork( - execution_context::fork_event event); - - friend class asio::detail::service_registry; - struct key - { - key() : type_info_(0), id_(0) {} - const std::type_info* type_info_; - const execution_context::id* id_; - } key_; - - execution_context& owner_; - service* next_; -}; - -/// Exception thrown when trying to add a duplicate service to an -/// execution_context. -class service_already_exists - : public std::logic_error -{ -public: - ASIO_DECL service_already_exists(); -}; - -/// Exception thrown when trying to add a service object to an -/// execution_context where the service has a different owner. -class invalid_service_owner - : public std::logic_error -{ -public: - ASIO_DECL invalid_service_owner(); -}; - -namespace detail { - -// Special derived service id type to keep classes header-file only. -template -class service_id - : public execution_context::id -{ -}; - -// Special service base class to keep classes header-file only. -template -class execution_context_service_base - : public execution_context::service -{ -public: - static service_id id; - - // Constructor. - execution_context_service_base(execution_context& e) - : execution_context::service(e) - { - } -}; - -template -service_id execution_context_service_base::id; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/execution_context.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/execution_context.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_EXECUTION_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/executor.hpp b/scout_sdk/asio/asio/executor.hpp deleted file mode 100644 index e552cfb..0000000 --- a/scout_sdk/asio/asio/executor.hpp +++ /dev/null @@ -1,341 +0,0 @@ -// -// executor.hpp -// ~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXECUTOR_HPP -#define ASIO_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/cstddef.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Exception thrown when trying to access an empty polymorphic executor. -class bad_executor - : public std::exception -{ -public: - /// Constructor. - ASIO_DECL bad_executor() ASIO_NOEXCEPT; - - /// Obtain message associated with exception. - ASIO_DECL virtual const char* what() const - ASIO_NOEXCEPT_OR_NOTHROW; -}; - -/// Polymorphic wrapper for executors. -class executor -{ -public: - /// Default constructor. - executor() ASIO_NOEXCEPT - : impl_(0) - { - } - - /// Construct from nullptr. - executor(nullptr_t) ASIO_NOEXCEPT - : impl_(0) - { - } - - /// Copy constructor. - executor(const executor& other) ASIO_NOEXCEPT - : impl_(other.clone()) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move constructor. - executor(executor&& other) ASIO_NOEXCEPT - : impl_(other.impl_) - { - other.impl_ = 0; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Construct a polymorphic wrapper for the specified executor. - template - executor(Executor e); - - /// Allocator-aware constructor to create a polymorphic wrapper for the - /// specified executor. - template - executor(allocator_arg_t, const Allocator& a, Executor e); - - /// Destructor. - ~executor() - { - destroy(); - } - - /// Assignment operator. - executor& operator=(const executor& other) ASIO_NOEXCEPT - { - destroy(); - impl_ = other.clone(); - return *this; - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - // Move assignment operator. - executor& operator=(executor&& other) ASIO_NOEXCEPT - { - destroy(); - impl_ = other.impl_; - other.impl_ = 0; - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Assignment operator for nullptr_t. - executor& operator=(nullptr_t) ASIO_NOEXCEPT - { - destroy(); - impl_ = 0; - return *this; - } - - /// Assignment operator to create a polymorphic wrapper for the specified - /// executor. - template - executor& operator=(ASIO_MOVE_ARG(Executor) e) ASIO_NOEXCEPT - { - executor tmp(ASIO_MOVE_CAST(Executor)(e)); - destroy(); - impl_ = tmp.impl_; - tmp.impl_ = 0; - return *this; - } - - /// Obtain the underlying execution context. - execution_context& context() const ASIO_NOEXCEPT - { - return get_impl()->context(); - } - - /// Inform the executor that it has some outstanding work to do. - void on_work_started() const ASIO_NOEXCEPT - { - get_impl()->on_work_started(); - } - - /// Inform the executor that some work is no longer outstanding. - void on_work_finished() const ASIO_NOEXCEPT - { - get_impl()->on_work_finished(); - } - - /// Request the executor to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object is executed according to the rules of the - * target executor object. - * - * @param f The function object to be called. The executor will make a copy - * of the handler object as required. The function signature of the function - * object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void dispatch(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the executor to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object is executed according to the rules of the - * target executor object. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void post(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the executor to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object is executed according to the rules of the - * target executor object. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void defer(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - struct unspecified_bool_type_t {}; - typedef void (*unspecified_bool_type)(unspecified_bool_type_t); - static void unspecified_bool_true(unspecified_bool_type_t) {} - - /// Operator to test if the executor contains a valid target. - operator unspecified_bool_type() const ASIO_NOEXCEPT - { - return impl_ ? &executor::unspecified_bool_true : 0; - } - - /// Obtain type information for the target executor object. - /** - * @returns If @c *this has a target type of type @c T, typeid(T); - * otherwise, typeid(void). - */ -#if !defined(ASIO_NO_TYPEID) || defined(GENERATING_DOCUMENTATION) - const std::type_info& target_type() const ASIO_NOEXCEPT - { - return impl_ ? impl_->target_type() : typeid(void); - } -#else // !defined(ASIO_NO_TYPEID) || defined(GENERATING_DOCUMENTATION) - const void* target_type() const ASIO_NOEXCEPT - { - return impl_ ? impl_->target_type() : 0; - } -#endif // !defined(ASIO_NO_TYPEID) || defined(GENERATING_DOCUMENTATION) - - /// Obtain a pointer to the target executor object. - /** - * @returns If target_type() == typeid(T), a pointer to the stored - * executor target; otherwise, a null pointer. - */ - template - Executor* target() ASIO_NOEXCEPT; - - /// Obtain a pointer to the target executor object. - /** - * @returns If target_type() == typeid(T), a pointer to the stored - * executor target; otherwise, a null pointer. - */ - template - const Executor* target() const ASIO_NOEXCEPT; - - /// Compare two executors for equality. - friend bool operator==(const executor& a, - const executor& b) ASIO_NOEXCEPT - { - if (a.impl_ == b.impl_) - return true; - if (!a.impl_ || !b.impl_) - return false; - return a.impl_->equals(b.impl_); - } - - /// Compare two executors for inequality. - friend bool operator!=(const executor& a, - const executor& b) ASIO_NOEXCEPT - { - return !(a == b); - } - -private: -#if !defined(GENERATING_DOCUMENTATION) - class function; - template class impl; - -#if !defined(ASIO_NO_TYPEID) - typedef const std::type_info& type_id_result_type; -#else // !defined(ASIO_NO_TYPEID) - typedef const void* type_id_result_type; -#endif // !defined(ASIO_NO_TYPEID) - - template - static type_id_result_type type_id() - { -#if !defined(ASIO_NO_TYPEID) - return typeid(T); -#else // !defined(ASIO_NO_TYPEID) - static int unique_id; - return &unique_id; -#endif // !defined(ASIO_NO_TYPEID) - } - - // Base class for all polymorphic executor implementations. - class impl_base - { - public: - virtual impl_base* clone() const ASIO_NOEXCEPT = 0; - virtual void destroy() ASIO_NOEXCEPT = 0; - virtual execution_context& context() ASIO_NOEXCEPT = 0; - virtual void on_work_started() ASIO_NOEXCEPT = 0; - virtual void on_work_finished() ASIO_NOEXCEPT = 0; - virtual void dispatch(ASIO_MOVE_ARG(function)) = 0; - virtual void post(ASIO_MOVE_ARG(function)) = 0; - virtual void defer(ASIO_MOVE_ARG(function)) = 0; - virtual type_id_result_type target_type() const ASIO_NOEXCEPT = 0; - virtual void* target() ASIO_NOEXCEPT = 0; - virtual const void* target() const ASIO_NOEXCEPT = 0; - virtual bool equals(const impl_base* e) const ASIO_NOEXCEPT = 0; - - protected: - impl_base(bool fast_dispatch) : fast_dispatch_(fast_dispatch) {} - virtual ~impl_base() {} - - private: - friend class executor; - const bool fast_dispatch_; - }; - - // Helper function to check and return the implementation pointer. - impl_base* get_impl() const - { - if (!impl_) - { - bad_executor ex; - asio::detail::throw_exception(ex); - } - return impl_; - } - - // Helper function to clone another implementation. - impl_base* clone() const ASIO_NOEXCEPT - { - return impl_ ? impl_->clone() : 0; - } - - // Helper function to destroy an implementation. - void destroy() ASIO_NOEXCEPT - { - if (impl_) - impl_->destroy(); - } - - impl_base* impl_; -#endif // !defined(GENERATING_DOCUMENTATION) -}; - -} // namespace asio - -ASIO_USES_ALLOCATOR(asio::executor) - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/executor.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/executor.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/executor_work_guard.hpp b/scout_sdk/asio/asio/executor_work_guard.hpp deleted file mode 100644 index 1875f54..0000000 --- a/scout_sdk/asio/asio/executor_work_guard.hpp +++ /dev/null @@ -1,170 +0,0 @@ -// -// executor_work_guard.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXECUTOR_WORK_GUARD_HPP -#define ASIO_EXECUTOR_WORK_GUARD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/is_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// An object of type @c executor_work_guard controls ownership of executor work -/// within a scope. -template -class executor_work_guard -{ -public: - /// The underlying executor type. - typedef Executor executor_type; - - /// Constructs a @c executor_work_guard object for the specified executor. - /** - * Stores a copy of @c e and calls on_work_started() on it. - */ - explicit executor_work_guard(const executor_type& e) ASIO_NOEXCEPT - : executor_(e), - owns_(true) - { - executor_.on_work_started(); - } - - /// Copy constructor. - executor_work_guard(const executor_work_guard& other) ASIO_NOEXCEPT - : executor_(other.executor_), - owns_(other.owns_) - { - if (owns_) - executor_.on_work_started(); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move constructor. - executor_work_guard(executor_work_guard&& other) - : executor_(ASIO_MOVE_CAST(Executor)(other.executor_)), - owns_(other.owns_) - { - other.owns_ = false; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destructor. - /** - * Unless the object has already been reset, or is in a moved-from state, - * calls on_work_finished() on the stored executor. - */ - ~executor_work_guard() - { - if (owns_) - executor_.on_work_finished(); - } - - /// Obtain the associated executor. - executor_type get_executor() const ASIO_NOEXCEPT - { - return executor_; - } - - /// Whether the executor_work_guard object owns some outstanding work. - bool owns_work() const ASIO_NOEXCEPT - { - return owns_; - } - - /// Indicate that the work is no longer outstanding. - /* - * Unless the object has already been reset, or is in a moved-from state, - * calls on_work_finished() on the stored executor. - */ - void reset() ASIO_NOEXCEPT - { - if (owns_) - { - executor_.on_work_finished(); - owns_ = false; - } - } - -private: - // Disallow assignment. - executor_work_guard& operator=(const executor_work_guard&); - - executor_type executor_; - bool owns_; -}; - -/// Create an @ref executor_work_guard object. -template -inline executor_work_guard make_work_guard(const Executor& ex, - typename enable_if::value>::type* = 0) -{ - return executor_work_guard(ex); -} - -/// Create an @ref executor_work_guard object. -template -inline executor_work_guard -make_work_guard(ExecutionContext& ctx, - typename enable_if< - is_convertible::value>::type* = 0) -{ - return executor_work_guard( - ctx.get_executor()); -} - -/// Create an @ref executor_work_guard object. -template -inline executor_work_guard::type> -make_work_guard(const T& t, - typename enable_if::value && - !is_convertible::value>::type* = 0) -{ - return executor_work_guard::type>( - associated_executor::get(t)); -} - -/// Create an @ref executor_work_guard object. -template -inline executor_work_guard::type> -make_work_guard(const T& t, const Executor& ex, - typename enable_if::value>::type* = 0) -{ - return executor_work_guard::type>( - associated_executor::get(t, ex)); -} - -/// Create an @ref executor_work_guard object. -template -inline executor_work_guard::type> -make_work_guard(const T& t, ExecutionContext& ctx, - typename enable_if::value && - !is_convertible::value && - is_convertible::value>::type* = 0) -{ - return executor_work_guard::type>( - associated_executor::get( - t, ctx.get_executor())); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_EXECUTOR_WORK_GUARD_HPP diff --git a/scout_sdk/asio/asio/experimental.hpp b/scout_sdk/asio/asio/experimental.hpp deleted file mode 100644 index 5765c37..0000000 --- a/scout_sdk/asio/asio/experimental.hpp +++ /dev/null @@ -1,22 +0,0 @@ -// -// experimental.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2017 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXPERIMENTAL_HPP -#define ASIO_EXPERIMENTAL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/experimental/co_spawn.hpp" -#include "asio/experimental/detached.hpp" -#include "asio/experimental/redirect_error.hpp" - -#endif // ASIO_EXPERIMENTAL_HPP diff --git a/scout_sdk/asio/asio/experimental/co_spawn.hpp b/scout_sdk/asio/asio/experimental/co_spawn.hpp deleted file mode 100644 index cbf5bc5..0000000 --- a/scout_sdk/asio/asio/experimental/co_spawn.hpp +++ /dev/null @@ -1,226 +0,0 @@ -// -// experimental/co_spawn.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXPERIMENTAL_CO_SPAWN_HPP -#define ASIO_EXPERIMENTAL_CO_SPAWN_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_CO_AWAIT) || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/executor.hpp" -#include "asio/strand.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace experimental { -namespace detail { - -using std::experimental::coroutine_handle; - -template class awaiter; -template class awaitee_base; -template class awaitee; -template class await_handler_base; -template -auto co_spawn(const Executor& ex, F&& f, CompletionToken&& token); - -} // namespace detail - -namespace this_coro { - -/// Awaitable type that returns a completion token for the current coroutine. -struct token_t {}; - -/// Awaitable object that returns a completion token for the current coroutine. -constexpr inline token_t token() { return {}; } - -/// Awaitable type that returns the executor of the current coroutine. -struct executor_t {}; - -/// Awaitable object that returns the executor of the current coroutine. -constexpr inline executor_t executor() { return {}; } - -} // namespace this_coro - -/// A completion token that represents the currently executing coroutine. -/** - * The await_token class is used to represent the currently executing - * coroutine. An await_token may be passed as a handler to an asynchronous - * operation. For example: - * - * @code awaitable my_coroutine() - * { - * await_token token = co_await this_coro::token(); - * ... - * std::size_t n = co_await my_socket.async_read_some(buffer, token); - * ... - * } @endcode - * - * The initiating function (async_read_some in the above example) suspends the - * current coroutine. The coroutine is resumed when the asynchronous operation - * completes, and the result of the operation is returned. - */ -template -class await_token -{ -public: - /// The associated executor type. - typedef Executor executor_type; - - /// Copy constructor. - await_token(const await_token& other) noexcept - : awaiter_(other.awaiter_) - { - } - - /// Move constructor. - await_token(await_token&& other) noexcept - : awaiter_(std::exchange(other.awaiter_, nullptr)) - { - } - - /// Get the associated executor. - executor_type get_executor() const noexcept - { - return awaiter_->get_executor(); - } - -private: - // No assignment allowed. - await_token& operator=(const await_token&) = delete; - - template friend class detail::awaitee_base; - template friend class detail::await_handler_base; - - // Private constructor used by awaitee_base. - explicit await_token(detail::awaiter* a) - : awaiter_(a) - { - } - - detail::awaiter* awaiter_; -}; - -/// The return type of a coroutine or asynchronous operation. -template > -class awaitable -{ -public: - /// The type of the awaited value. - typedef T value_type; - - /// The executor type that will be used for the coroutine. - typedef Executor executor_type; - - /// Move constructor. - awaitable(awaitable&& other) noexcept - : awaitee_(std::exchange(other.awaitee_, nullptr)) - { - } - - /// Destructor - ~awaitable() - { - if (awaitee_) - { - detail::coroutine_handle< - detail::awaitee>::from_promise( - *awaitee_).destroy(); - } - } - -#if !defined(GENERATING_DOCUMENTATION) - - // Support for co_await keyword. - bool await_ready() const noexcept - { - return awaitee_->ready(); - } - - // Support for co_await keyword. - void await_suspend(detail::coroutine_handle> h) - { - awaitee_->attach_caller(h); - } - - // Support for co_await keyword. - template - void await_suspend(detail::coroutine_handle> h) - { - awaitee_->attach_caller(h); - } - - // Support for co_await keyword. - T await_resume() - { - return awaitee_->get(); - } - -#endif // !defined(GENERATING_DOCUMENTATION) - -private: - template friend class detail::awaitee; - template friend class detail::await_handler_base; - - // Not copy constructible or copy assignable. - awaitable(const awaitable&) = delete; - awaitable& operator=(const awaitable&) = delete; - - // Construct the awaitable from a coroutine's promise object. - explicit awaitable(detail::awaitee* a) : awaitee_(a) {} - - detail::awaitee* awaitee_; -}; - -/// Spawn a new thread of execution. -template ::value>::type> -inline auto co_spawn(const Executor& ex, F&& f, CompletionToken&& token) -{ - return detail::co_spawn(ex, std::forward(f), - std::forward(token)); -} - -/// Spawn a new thread of execution. -template ::value>::type> -inline auto co_spawn(ExecutionContext& ctx, F&& f, CompletionToken&& token) -{ - return detail::co_spawn(ctx.get_executor(), std::forward(f), - std::forward(token)); -} - -/// Spawn a new thread of execution. -template -inline auto co_spawn(const await_token& parent, - F&& f, CompletionToken&& token) -{ - return detail::co_spawn(parent.get_executor(), std::forward(f), - std::forward(token)); -} - -} // namespace experimental -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/experimental/impl/co_spawn.hpp" - -#endif // defined(ASIO_HAS_CO_AWAIT) || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_EXPERIMENTAL_CO_SPAWN_HPP diff --git a/scout_sdk/asio/asio/experimental/detached.hpp b/scout_sdk/asio/asio/experimental/detached.hpp deleted file mode 100644 index d484f18..0000000 --- a/scout_sdk/asio/asio/experimental/detached.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// -// experimental/detached.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXPERIMENTAL_DETACHED_HPP -#define ASIO_EXPERIMENTAL_DETACHED_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace experimental { - -/// Class used to specify that an asynchronous operation is detached. -/** - - * The detached_t class is used to indicate that an asynchronous operation is - * detached. That is, there is no completion handler waiting for the - * operation's result. A detached_t object may be passed as a handler to an - * asynchronous operation, typically using the special value - * @c asio::experimental::detached. For example: - - * @code my_socket.async_send(my_buffer, asio::experimental::detached); - * @endcode - */ -class detached_t -{ -public: - /// Constructor. - ASIO_CONSTEXPR detached_t() - { - } -}; - -/// A special value, similar to std::nothrow. -/** - * See the documentation for asio::experimental::detached_t for a usage - * example. - */ -#if defined(ASIO_HAS_CONSTEXPR) || defined(GENERATING_DOCUMENTATION) -constexpr detached_t detached; -#elif defined(ASIO_MSVC) -__declspec(selectany) detached_t detached; -#endif - -} // namespace experimental -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/experimental/impl/detached.hpp" - -#endif // ASIO_EXPERIMENTAL_DETACHED_HPP diff --git a/scout_sdk/asio/asio/experimental/impl/co_spawn.hpp b/scout_sdk/asio/asio/experimental/impl/co_spawn.hpp deleted file mode 100644 index 8263eff..0000000 --- a/scout_sdk/asio/asio/experimental/impl/co_spawn.hpp +++ /dev/null @@ -1,876 +0,0 @@ -// -// experimental/impl/co_spawn.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXPERIMENTAL_IMPL_CO_SPAWN_HPP -#define ASIO_EXPERIMENTAL_IMPL_CO_SPAWN_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include -#include -#include -#include "asio/async_result.hpp" -#include "asio/detail/thread_context.hpp" -#include "asio/detail/thread_info_base.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/dispatch.hpp" -#include "asio/post.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace experimental { -namespace detail { - -// Promise object for coroutine at top of thread-of-execution "stack". -template -class awaiter -{ -public: - struct deleter - { - void operator()(awaiter* a) - { - if (a) - a->release(); - } - }; - - typedef std::unique_ptr ptr; - - typedef Executor executor_type; - - ~awaiter() - { - if (has_executor_) - static_cast(static_cast(executor_))->~Executor(); - } - - void set_executor(const Executor& ex) - { - new (&executor_) Executor(ex); - has_executor_ = true; - } - - executor_type get_executor() const noexcept - { - return *static_cast(static_cast(executor_)); - } - - awaiter* get_return_object() - { - return this; - } - - auto initial_suspend() - { - return std::experimental::suspend_always(); - } - - auto final_suspend() - { - return std::experimental::suspend_always(); - } - - void return_void() - { - } - - awaiter* add_ref() - { - ++ref_count_; - return this; - } - - void release() - { - if (--ref_count_ == 0) - coroutine_handle::from_promise(*this).destroy(); - } - - void unhandled_exception() - { - pending_exception_ = std::current_exception(); - } - - void rethrow_unhandled_exception() - { - if (pending_exception_) - { - std::exception_ptr ex = std::exchange(pending_exception_, nullptr); - std::rethrow_exception(ex); - } - } - -private: - std::size_t ref_count_ = 0; - std::exception_ptr pending_exception_ = nullptr; - alignas(Executor) unsigned char executor_[sizeof(Executor)]; - bool has_executor_ = false; -}; - -// Base promise for coroutines further down the thread-of-execution "stack". -template -class awaitee_base -{ -public: -#if !defined(ASIO_DISABLE_AWAITEE_RECYCLING) - void* operator new(std::size_t size) - { - return asio::detail::thread_info_base::allocate( - asio::detail::thread_info_base::awaitee_tag(), - asio::detail::thread_context::thread_call_stack::top(), - size); - } - - void operator delete(void* pointer, std::size_t size) - { - asio::detail::thread_info_base::deallocate( - asio::detail::thread_info_base::awaitee_tag(), - asio::detail::thread_context::thread_call_stack::top(), - pointer, size); - } -#endif // !defined(ASIO_DISABLE_AWAITEE_RECYCLING) - - auto initial_suspend() - { - return std::experimental::suspend_never(); - } - - struct final_suspender - { - awaitee_base* this_; - - bool await_ready() const noexcept - { - return false; - } - - void await_suspend(coroutine_handle) - { - this_->wake_caller(); - } - - void await_resume() const noexcept - { - } - }; - - auto final_suspend() - { - return final_suspender{this}; - } - - void set_except(std::exception_ptr e) - { - pending_exception_ = e; - } - - void unhandled_exception() - { - set_except(std::current_exception()); - } - - void rethrow_exception() - { - if (pending_exception_) - { - std::exception_ptr ex = std::exchange(pending_exception_, nullptr); - std::rethrow_exception(ex); - } - } - - awaiter* top() - { - return awaiter_; - } - - coroutine_handle caller() - { - return caller_; - } - - bool ready() const - { - return ready_; - } - - void wake_caller() - { - if (caller_) - caller_.resume(); - else - ready_ = true; - } - - class awaitable_executor - { - public: - explicit awaitable_executor(awaitee_base* a) - : this_(a) - { - } - - bool await_ready() const noexcept - { - return this_->awaiter_ != nullptr; - } - - template - void await_suspend(coroutine_handle> h) noexcept - { - this_->resume_on_attach_ = h; - } - - Executor await_resume() - { - return this_->awaiter_->get_executor(); - } - - private: - awaitee_base* this_; - }; - - awaitable_executor await_transform(this_coro::executor_t) noexcept - { - return awaitable_executor(this); - } - - class awaitable_token - { - public: - explicit awaitable_token(awaitee_base* a) - : this_(a) - { - } - - bool await_ready() const noexcept - { - return this_->awaiter_ != nullptr; - } - - template - void await_suspend(coroutine_handle> h) noexcept - { - this_->resume_on_attach_ = h; - } - - await_token await_resume() - { - return await_token(this_->awaiter_); - } - - private: - awaitee_base* this_; - }; - - awaitable_token await_transform(this_coro::token_t) noexcept - { - return awaitable_token(this); - } - - template - awaitable await_transform(awaitable& t) const - { - return std::move(t); - } - - template - awaitable await_transform(awaitable&& t) const - { - return std::move(t); - } - - std::experimental::suspend_always await_transform( - std::experimental::suspend_always) const - { - return std::experimental::suspend_always(); - } - - void attach_caller(coroutine_handle> h) - { - this->caller_ = h; - this->attach_callees(&h.promise()); - } - - template - void attach_caller(coroutine_handle> h) - { - this->caller_ = h; - if (h.promise().awaiter_) - this->attach_callees(h.promise().awaiter_); - else - h.promise().unattached_callee_ = this; - } - - void attach_callees(awaiter* a) - { - for (awaitee_base* curr = this; curr != nullptr; - curr = std::exchange(curr->unattached_callee_, nullptr)) - { - curr->awaiter_ = a; - if (curr->resume_on_attach_) - return std::exchange(curr->resume_on_attach_, nullptr).resume(); - } - } - -protected: - awaiter* awaiter_ = nullptr; - coroutine_handle caller_ = nullptr; - awaitee_base* unattached_callee_ = nullptr; - std::exception_ptr pending_exception_ = nullptr; - coroutine_handle resume_on_attach_ = nullptr; - bool ready_ = false; -}; - -// Promise object for coroutines further down the thread-of-execution "stack". -template -class awaitee - : public awaitee_base -{ -public: - awaitee() - { - } - - awaitee(awaitee&& other) noexcept - : awaitee_base(std::move(other)) - { - } - - ~awaitee() - { - if (has_result_) - static_cast(static_cast(result_))->~T(); - } - - awaitable get_return_object() - { - return awaitable(this); - }; - - template - void return_value(U&& u) - { - new (&result_) T(std::forward(u)); - has_result_ = true; - } - - T get() - { - this->caller_ = nullptr; - this->rethrow_exception(); - return std::move(*static_cast(static_cast(result_))); - } - -private: - alignas(T) unsigned char result_[sizeof(T)]; - bool has_result_ = false; -}; - -// Promise object for coroutines further down the thread-of-execution "stack". -template -class awaitee - : public awaitee_base -{ -public: - awaitable get_return_object() - { - return awaitable(this); - }; - - void return_void() - { - } - - void get() - { - this->caller_ = nullptr; - this->rethrow_exception(); - } -}; - -template -class awaiter_task -{ -public: - typedef Executor executor_type; - - awaiter_task(awaiter* a) - : awaiter_(a->add_ref()) - { - } - - awaiter_task(awaiter_task&& other) noexcept - : awaiter_(std::exchange(other.awaiter_, nullptr)) - { - } - - ~awaiter_task() - { - if (awaiter_) - { - // Coroutine "stack unwinding" must be performed through the executor. - executor_type ex(awaiter_->get_executor()); - (post)(ex, - [a = std::move(awaiter_)]() mutable - { - typename awaiter::ptr(std::move(a)); - }); - } - } - - executor_type get_executor() const noexcept - { - return awaiter_->get_executor(); - } - -protected: - typename awaiter::ptr awaiter_; -}; - -template -class co_spawn_handler : public awaiter_task -{ -public: - using awaiter_task::awaiter_task; - - void operator()() - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - coroutine_handle>::from_promise(*ptr.get()).resume(); - } -}; - -template -class await_handler_base : public awaiter_task -{ -public: - typedef awaitable awaitable_type; - - await_handler_base(await_token token) - : awaiter_task(token.awaiter_), - awaitee_(nullptr) - { - } - - await_handler_base(await_handler_base&& other) noexcept - : awaiter_task(std::move(other)), - awaitee_(std::exchange(other.awaitee_, nullptr)) - { - } - - void attach_awaitee(const awaitable& a) - { - awaitee_ = a.awaitee_; - } - -protected: - awaitee* awaitee_; -}; - -template class await_handler; - -template -class await_handler - : public await_handler_base -{ -public: - using await_handler_base::await_handler_base; - - void operator()() - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - this->awaitee_->return_void(); - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base -{ -public: - typedef void return_type; - - using await_handler_base::await_handler_base; - - void operator()(const asio::error_code& ec) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - if (ec) - { - this->awaitee_->set_except( - std::make_exception_ptr(asio::system_error(ec))); - } - else - this->awaitee_->return_void(); - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base -{ -public: - using await_handler_base::await_handler_base; - - void operator()(std::exception_ptr ex) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - if (ex) - this->awaitee_->set_except(ex); - else - this->awaitee_->return_void(); - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base -{ -public: - using await_handler_base::await_handler_base; - - template - void operator()(Arg&& arg) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - this->awaitee_->return_value(std::forward(arg)); - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base -{ -public: - using await_handler_base::await_handler_base; - - template - void operator()(const asio::error_code& ec, Arg&& arg) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - if (ec) - { - this->awaitee_->set_except( - std::make_exception_ptr(asio::system_error(ec))); - } - else - this->awaitee_->return_value(std::forward(arg)); - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base -{ -public: - using await_handler_base::await_handler_base; - - template - void operator()(std::exception_ptr ex, Arg&& arg) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - if (ex) - this->awaitee_->set_except(ex); - else - this->awaitee_->return_value(std::forward(arg)); - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base> -{ -public: - using await_handler_base>::await_handler_base; - - template - void operator()(Args&&... args) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - this->awaitee_->return_value( - std::forward_as_tuple(std::forward(args)...)); - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base> -{ -public: - using await_handler_base>::await_handler_base; - - template - void operator()(const asio::error_code& ec, Args&&... args) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - if (ec) - { - this->awaitee_->set_except( - std::make_exception_ptr(asio::system_error(ec))); - } - else - { - this->awaitee_->return_value( - std::forward_as_tuple(std::forward(args)...)); - } - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -class await_handler - : public await_handler_base> -{ -public: - using await_handler_base>::await_handler_base; - - template - void operator()(std::exception_ptr ex, Args&&... args) - { - typename awaiter::ptr ptr(std::move(this->awaiter_)); - if (ex) - this->awaitee_->set_except(ex); - else - { - this->awaitee_->return_value( - std::forward_as_tuple(std::forward(args)...)); - } - this->awaitee_->wake_caller(); - ptr->rethrow_unhandled_exception(); - } -}; - -template -struct awaitable_signature; - -template -struct awaitable_signature> -{ - typedef void type(std::exception_ptr, T); -}; - -template -struct awaitable_signature> -{ - typedef void type(std::exception_ptr); -}; - -template -awaiter* co_spawn_entry_point(awaitable*, - executor_work_guard work_guard, F f, Handler handler) -{ - bool done = false; - - try - { - T t = co_await f(); - - done = true; - - (dispatch)(work_guard.get_executor(), - [handler = std::move(handler), t = std::move(t)]() mutable - { - handler(std::exception_ptr(), std::move(t)); - }); - } - catch (...) - { - if (done) - throw; - - (dispatch)(work_guard.get_executor(), - [handler = std::move(handler), e = std::current_exception()]() mutable - { - handler(e, T()); - }); - } -} - -template -awaiter* co_spawn_entry_point(awaitable*, - executor_work_guard work_guard, F f, Handler handler) -{ - std::exception_ptr e = nullptr; - - try - { - co_await f(); - } - catch (...) - { - e = std::current_exception(); - } - - (dispatch)(work_guard.get_executor(), - [handler = std::move(handler), e]() mutable - { - handler(e); - }); -} - -template -auto co_spawn(const Executor& ex, F&& f, CompletionToken&& token) -{ - typedef typename result_of::type awaitable_type; - typedef typename awaitable_type::executor_type executor_type; - typedef typename awaitable_signature::type signature_type; - - async_completion completion(token); - - executor_type ex2(ex); - auto work_guard = make_work_guard(completion.completion_handler, ex2); - - auto* a = (co_spawn_entry_point)( - static_cast(nullptr), std::move(work_guard), - std::forward(f), std::move(completion.completion_handler)); - - a->set_executor(ex2); - (post)(co_spawn_handler(a)); - - return completion.result.get(); -} - -#if defined(_MSC_VER) -# pragma warning(push) -# pragma warning(disable:4033) -#endif // defined(_MSC_VER) - -#if defined(_MSC_VER) -template T dummy_return() -{ - return std::move(*static_cast(nullptr)); -} - -template <> -inline void dummy_return() -{ -} -#endif // defined(_MSC_VER) - -template -inline Awaitable make_dummy_awaitable() -{ - for (;;) co_await std::experimental::suspend_always(); -#if defined(_MSC_VER) - co_return dummy_return(); -#endif // defined(_MSC_VER) -} - -#if defined(_MSC_VER) -# pragma warning(pop) -#endif // defined(_MSC_VER) - -} // namespace detail -} // namespace experimental - -template -class async_result, R(Args...)> -{ -public: - typedef experimental::detail::await_handler< - Executor, typename decay::type...> completion_handler_type; - - typedef typename experimental::detail::await_handler< - Executor, Args...>::awaitable_type return_type; - - async_result(completion_handler_type& h) - : awaitable_(experimental::detail::make_dummy_awaitable()) - { - h.attach_awaitee(awaitable_); - } - - return_type get() - { - return std::move(awaitable_); - } - -private: - return_type awaitable_; -}; - -#if !defined(ASIO_NO_DEPRECATED) - -template -struct handler_type, R(Args...)> -{ - typedef experimental::detail::await_handler< - Executor, typename decay::type...> type; -}; - -template -class async_result> -{ -public: - typedef typename experimental::detail::await_handler< - Executor, Args...>::awaitable_type type; - - async_result(experimental::detail::await_handler& h) - : awaitable_(experimental::detail::make_dummy_awaitable()) - { - h.attach_awaitee(awaitable_); - } - - type get() - { - return std::move(awaitable_); - } - -private: - type awaitable_; -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -} // namespace asio - -namespace std { namespace experimental { - -template -struct coroutine_traits< - asio::experimental::detail::awaiter*, Args...> -{ - typedef asio::experimental::detail::awaiter promise_type; -}; - -template -struct coroutine_traits< - asio::experimental::awaitable, Args...> -{ - typedef asio::experimental::detail::awaitee promise_type; -}; - -}} // namespace std::experimental - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_EXPERIMENTAL_IMPL_CO_SPAWN_HPP diff --git a/scout_sdk/asio/asio/experimental/impl/detached.hpp b/scout_sdk/asio/asio/experimental/impl/detached.hpp deleted file mode 100644 index 6ce8887..0000000 --- a/scout_sdk/asio/asio/experimental/impl/detached.hpp +++ /dev/null @@ -1,91 +0,0 @@ -// -// experimental/impl/detached.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXPERIMENTAL_IMPL_DETACHED_HPP -#define ASIO_EXPERIMENTAL_IMPL_DETACHED_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/async_result.hpp" -#include "asio/detail/variadic_templates.hpp" -#include "asio/handler_type.hpp" -#include "asio/system_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace experimental { -namespace detail { - - // Class to adapt a detached_t as a completion handler. - class detached_handler - { - public: - detached_handler(detached_t) - { - } - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - void operator()(Args...) - { - } - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - - void operator()() - { - } - -#define ASIO_PRIVATE_DETACHED_DEF(n) \ - template \ - void operator()(ASIO_VARIADIC_BYVAL_PARAMS(n)) \ - { \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_DETACHED_DEF) -#undef ASIO_PRIVATE_DETACHED_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - }; - -} // namespace detail -} // namespace experimental - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct async_result -{ - typedef asio::experimental::detail::detached_handler - completion_handler_type; - - typedef void return_type; - - explicit async_result(completion_handler_type&) - { - } - - void get() - { - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_EXPERIMENTAL_IMPL_DETACHED_HPP diff --git a/scout_sdk/asio/asio/experimental/impl/redirect_error.hpp b/scout_sdk/asio/asio/experimental/impl/redirect_error.hpp deleted file mode 100644 index d3b97fa..0000000 --- a/scout_sdk/asio/asio/experimental/impl/redirect_error.hpp +++ /dev/null @@ -1,294 +0,0 @@ -// -// experimental/impl/redirect_error.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXPERIMENTAL_IMPL_REDIRECT_ERROR_HPP -#define ASIO_EXPERIMENTAL_IMPL_REDIRECT_ERROR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_executor.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/async_result.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/detail/variadic_templates.hpp" -#include "asio/handler_type.hpp" -#include "asio/system_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace experimental { -namespace detail { - -// Class to adapt a redirect_error_t as a completion handler. -template -class redirect_error_handler -{ -public: - template - redirect_error_handler(redirect_error_t e) - : ec_(e.ec_), - handler_(ASIO_MOVE_CAST(CompletionToken)(e.token_)) - { - } - - void operator()() - { - handler_(); - } - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - typename enable_if< - !is_same::type, asio::error_code>::value - >::type - operator()(ASIO_MOVE_ARG(Arg) arg, ASIO_MOVE_ARG(Args)... args) - { - handler_(ASIO_MOVE_CAST(Arg)(arg), - ASIO_MOVE_CAST(Args)(args)...); - } - - template - void operator()(const asio::error_code& ec, - ASIO_MOVE_ARG(Args)... args) - { - ec_ = ec; - handler_(ASIO_MOVE_CAST(Args)(args)...); - } - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - typename enable_if< - !is_same::type, asio::error_code>::value - >::type - operator()(ASIO_MOVE_ARG(Arg) arg) - { - handler_(ASIO_MOVE_CAST(Arg)(arg)); - } - - void operator()(const asio::error_code& ec) - { - ec_ = ec; - handler_(); - } - -#define ASIO_PRIVATE_REDIRECT_ERROR_DEF(n) \ - template \ - typename enable_if< \ - !is_same::type, asio::error_code>::value \ - >::type \ - operator()(ASIO_MOVE_ARG(Arg) arg, ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - handler_(ASIO_MOVE_CAST(Arg)(arg), \ - ASIO_VARIADIC_MOVE_ARGS(n)); \ - } \ - \ - template \ - void operator()(const asio::error_code& ec, \ - ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - ec_ = ec; \ - handler_(ASIO_VARIADIC_MOVE_ARGS(n)); \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_REDIRECT_ERROR_DEF) -#undef ASIO_PRIVATE_REDIRECT_ERROR_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -//private: - asio::error_code& ec_; - Handler handler_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - redirect_error_handler* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - redirect_error_handler* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - redirect_error_handler* this_handler) -{ - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - redirect_error_handler* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void asio_handler_invoke(const Function& function, - redirect_error_handler* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -struct redirect_error_signature -{ - typedef Signature type; -}; - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -struct redirect_error_signature -{ - typedef R type(Args...); -}; - -template -struct redirect_error_signature -{ - typedef R type(Args...); -}; - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -struct redirect_error_signature -{ - typedef R type(); -}; - -template -struct redirect_error_signature -{ - typedef R type(); -}; - -#define ASIO_PRIVATE_REDIRECT_ERROR_DEF(n) \ - template \ - struct redirect_error_signature< \ - R(asio::error_code, ASIO_VARIADIC_TARGS(n))> \ - { \ - typedef R type(ASIO_VARIADIC_TARGS(n)); \ - }; \ - \ - template \ - struct redirect_error_signature< \ - R(const asio::error_code&, ASIO_VARIADIC_TARGS(n))> \ - { \ - typedef R type(ASIO_VARIADIC_TARGS(n)); \ - }; \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_REDIRECT_ERROR_DEF) -#undef ASIO_PRIVATE_REDIRECT_ERROR_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -} // namespace detail -} // namespace experimental - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct async_result, Signature> - : async_result::type> -{ - typedef experimental::detail::redirect_error_handler< - typename async_result::type> - ::completion_handler_type> completion_handler_type; - - explicit async_result(completion_handler_type& h) - : async_result::type>(h.handler_) - { - } -}; - -#if !defined(ASIO_NO_DEPRECATED) - -template -struct handler_type, Signature> -{ - typedef experimental::detail::redirect_error_handler< - typename async_result::type> - ::completion_handler_type> type; -}; - -template -struct async_result > - : async_result -{ - explicit async_result( - experimental::detail::redirect_error_handler& h) - : async_result(h.handler_) - { - } -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -struct associated_executor< - experimental::detail::redirect_error_handler, Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const experimental::detail::redirect_error_handler& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -template -struct associated_allocator< - experimental::detail::redirect_error_handler, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const experimental::detail::redirect_error_handler& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_EXPERIMENTAL_IMPL_REDIRECT_ERROR_HPP diff --git a/scout_sdk/asio/asio/experimental/redirect_error.hpp b/scout_sdk/asio/asio/experimental/redirect_error.hpp deleted file mode 100644 index 30e81cf..0000000 --- a/scout_sdk/asio/asio/experimental/redirect_error.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// experimental/redirect_error.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_EXPERIMENTAL_REDIRECT_ERROR_HPP -#define ASIO_EXPERIMENTAL_REDIRECT_ERROR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error_code.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace experimental { - -/// Completion token type used to specify that an error produced by an -/// asynchronous operation is captured to an error_code variable. -/** - * The redirect_error_t class is used to indicate that any error_code produced - * by an asynchronous operation is captured to a specified variable. - */ -template -class redirect_error_t -{ -public: - /// Constructor. - template - redirect_error_t(ASIO_MOVE_ARG(T) completion_token, - asio::error_code& ec) - : token_(ASIO_MOVE_CAST(T)(completion_token)), - ec_(ec) - { - } - -//private: - CompletionToken token_; - asio::error_code& ec_; -}; - -/// Create a completion token to capture error_code values to a variable. -template -inline redirect_error_t::type> redirect_error( - CompletionToken&& completion_token, asio::error_code& ec) -{ - return redirect_error_t::type>( - ASIO_MOVE_CAST(CompletionToken)(completion_token), ec); -} - -} // namespace experimental -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/experimental/impl/redirect_error.hpp" - -#endif // ASIO_EXPERIMENTAL_REDIRECT_ERROR_HPP diff --git a/scout_sdk/asio/asio/generic/basic_endpoint.hpp b/scout_sdk/asio/asio/generic/basic_endpoint.hpp deleted file mode 100644 index 73aa151..0000000 --- a/scout_sdk/asio/asio/generic/basic_endpoint.hpp +++ /dev/null @@ -1,193 +0,0 @@ -// -// generic/basic_endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_GENERIC_BASIC_ENDPOINT_HPP -#define ASIO_GENERIC_BASIC_ENDPOINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/generic/detail/endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace generic { - -/// Describes an endpoint for any socket type. -/** - * The asio::generic::basic_endpoint class template describes an endpoint - * that may be associated with any socket type. - * - * @note The socket types sockaddr type must be able to fit into a - * @c sockaddr_storage structure. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * Endpoint. - */ -template -class basic_endpoint -{ -public: - /// The protocol type associated with the endpoint. - typedef Protocol protocol_type; - - /// The type of the endpoint structure. This type is dependent on the - /// underlying implementation of the socket layer. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined data_type; -#else - typedef asio::detail::socket_addr_type data_type; -#endif - - /// Default constructor. - basic_endpoint() - { - } - - /// Construct an endpoint from the specified socket address. - basic_endpoint(const void* socket_address, - std::size_t socket_address_size, int socket_protocol = 0) - : impl_(socket_address, socket_address_size, socket_protocol) - { - } - - /// Construct an endpoint from the specific endpoint type. - template - basic_endpoint(const Endpoint& endpoint) - : impl_(endpoint.data(), endpoint.size(), endpoint.protocol().protocol()) - { - } - - /// Copy constructor. - basic_endpoint(const basic_endpoint& other) - : impl_(other.impl_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - basic_endpoint(basic_endpoint&& other) - : impl_(other.impl_) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from another endpoint. - basic_endpoint& operator=(const basic_endpoint& other) - { - impl_ = other.impl_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move-assign from another endpoint. - basic_endpoint& operator=(basic_endpoint&& other) - { - impl_ = other.impl_; - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// The protocol associated with the endpoint. - protocol_type protocol() const - { - return protocol_type(impl_.family(), impl_.protocol()); - } - - /// Get the underlying endpoint in the native type. - data_type* data() - { - return impl_.data(); - } - - /// Get the underlying endpoint in the native type. - const data_type* data() const - { - return impl_.data(); - } - - /// Get the underlying size of the endpoint in the native type. - std::size_t size() const - { - return impl_.size(); - } - - /// Set the underlying size of the endpoint in the native type. - void resize(std::size_t new_size) - { - impl_.resize(new_size); - } - - /// Get the capacity of the endpoint in the native type. - std::size_t capacity() const - { - return impl_.capacity(); - } - - /// Compare two endpoints for equality. - friend bool operator==(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e1.impl_ == e2.impl_; - } - - /// Compare two endpoints for inequality. - friend bool operator!=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e1.impl_ == e2.impl_); - } - - /// Compare endpoints for ordering. - friend bool operator<(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e1.impl_ < e2.impl_; - } - - /// Compare endpoints for ordering. - friend bool operator>(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e2.impl_ < e1.impl_; - } - - /// Compare endpoints for ordering. - friend bool operator<=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e2 < e1); - } - - /// Compare endpoints for ordering. - friend bool operator>=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e1 < e2); - } - -private: - // The underlying generic endpoint. - asio::generic::detail::endpoint impl_; -}; - -} // namespace generic -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_GENERIC_BASIC_ENDPOINT_HPP diff --git a/scout_sdk/asio/asio/generic/datagram_protocol.hpp b/scout_sdk/asio/asio/generic/datagram_protocol.hpp deleted file mode 100644 index 8678ad8..0000000 --- a/scout_sdk/asio/asio/generic/datagram_protocol.hpp +++ /dev/null @@ -1,123 +0,0 @@ -// -// generic/datagram_protocol.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_GENERIC_DATAGRAM_PROTOCOL_HPP -#define ASIO_GENERIC_DATAGRAM_PROTOCOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/basic_datagram_socket.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/generic/basic_endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace generic { - -/// Encapsulates the flags needed for a generic datagram-oriented socket. -/** - * The asio::generic::datagram_protocol class contains flags necessary - * for datagram-oriented sockets of any address family and protocol. - * - * @par Examples - * Constructing using a native address family and socket protocol: - * @code datagram_protocol p(AF_INET, IPPROTO_UDP); @endcode - * Constructing from a specific protocol type: - * @code datagram_protocol p(asio::ip::udp::v4()); @endcode - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol. - */ -class datagram_protocol -{ -public: - /// Construct a protocol object for a specific address family and protocol. - datagram_protocol(int address_family, int socket_protocol) - : family_(address_family), - protocol_(socket_protocol) - { - } - - /// Construct a generic protocol object from a specific protocol. - /** - * @throws @c bad_cast Thrown if the source protocol is not datagram-oriented. - */ - template - datagram_protocol(const Protocol& source_protocol) - : family_(source_protocol.family()), - protocol_(source_protocol.protocol()) - { - if (source_protocol.type() != type()) - { - std::bad_cast ex; - asio::detail::throw_exception(ex); - } - } - - /// Obtain an identifier for the type of the protocol. - int type() const - { - return ASIO_OS_DEF(SOCK_DGRAM); - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return protocol_; - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return family_; - } - - /// Compare two protocols for equality. - friend bool operator==(const datagram_protocol& p1, - const datagram_protocol& p2) - { - return p1.family_ == p2.family_ && p1.protocol_ == p2.protocol_; - } - - /// Compare two protocols for inequality. - friend bool operator!=(const datagram_protocol& p1, - const datagram_protocol& p2) - { - return !(p1 == p2); - } - - /// The type of an endpoint. - typedef basic_endpoint endpoint; - - /// The generic socket type. - typedef basic_datagram_socket socket; - -private: - int family_; - int protocol_; -}; - -} // namespace generic -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_GENERIC_DATAGRAM_PROTOCOL_HPP diff --git a/scout_sdk/asio/asio/generic/detail/endpoint.hpp b/scout_sdk/asio/asio/generic/detail/endpoint.hpp deleted file mode 100644 index 190beb1..0000000 --- a/scout_sdk/asio/asio/generic/detail/endpoint.hpp +++ /dev/null @@ -1,133 +0,0 @@ -// -// generic/detail/endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_GENERIC_DETAIL_ENDPOINT_HPP -#define ASIO_GENERIC_DETAIL_ENDPOINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace generic { -namespace detail { - -// Helper class for implementing a generic socket endpoint. -class endpoint -{ -public: - // Default constructor. - ASIO_DECL endpoint(); - - // Construct an endpoint from the specified raw bytes. - ASIO_DECL endpoint(const void* sock_addr, - std::size_t sock_addr_size, int sock_protocol); - - // Copy constructor. - endpoint(const endpoint& other) - : data_(other.data_), - size_(other.size_), - protocol_(other.protocol_) - { - } - - // Assign from another endpoint. - endpoint& operator=(const endpoint& other) - { - data_ = other.data_; - size_ = other.size_; - protocol_ = other.protocol_; - return *this; - } - - // Get the address family associated with the endpoint. - int family() const - { - return data_.base.sa_family; - } - - // Get the socket protocol associated with the endpoint. - int protocol() const - { - return protocol_; - } - - // Get the underlying endpoint in the native type. - asio::detail::socket_addr_type* data() - { - return &data_.base; - } - - // Get the underlying endpoint in the native type. - const asio::detail::socket_addr_type* data() const - { - return &data_.base; - } - - // Get the underlying size of the endpoint in the native type. - std::size_t size() const - { - return size_; - } - - // Set the underlying size of the endpoint in the native type. - ASIO_DECL void resize(std::size_t size); - - // Get the capacity of the endpoint in the native type. - std::size_t capacity() const - { - return sizeof(asio::detail::sockaddr_storage_type); - } - - // Compare two endpoints for equality. - ASIO_DECL friend bool operator==( - const endpoint& e1, const endpoint& e2); - - // Compare endpoints for ordering. - ASIO_DECL friend bool operator<( - const endpoint& e1, const endpoint& e2); - -private: - // The underlying socket address. - union data_union - { - asio::detail::socket_addr_type base; - asio::detail::sockaddr_storage_type generic; - } data_; - - // The length of the socket address stored in the endpoint. - std::size_t size_; - - // The socket protocol associated with the endpoint. - int protocol_; - - // Initialise with a specified memory. - ASIO_DECL void init(const void* sock_addr, - std::size_t sock_addr_size, int sock_protocol); -}; - -} // namespace detail -} // namespace generic -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/generic/detail/impl/endpoint.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_GENERIC_DETAIL_ENDPOINT_HPP diff --git a/scout_sdk/asio/asio/generic/detail/impl/endpoint.ipp b/scout_sdk/asio/asio/generic/detail/impl/endpoint.ipp deleted file mode 100644 index 227ffe1..0000000 --- a/scout_sdk/asio/asio/generic/detail/impl/endpoint.ipp +++ /dev/null @@ -1,110 +0,0 @@ -// -// generic/detail/impl/endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_GENERIC_DETAIL_IMPL_ENDPOINT_IPP -#define ASIO_GENERIC_DETAIL_IMPL_ENDPOINT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/error.hpp" -#include "asio/generic/detail/endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace generic { -namespace detail { - -endpoint::endpoint() -{ - init(0, 0, 0); -} - -endpoint::endpoint(const void* sock_addr, - std::size_t sock_addr_size, int sock_protocol) -{ - init(sock_addr, sock_addr_size, sock_protocol); -} - -void endpoint::resize(std::size_t new_size) -{ - if (new_size > sizeof(asio::detail::sockaddr_storage_type)) - { - asio::error_code ec(asio::error::invalid_argument); - asio::detail::throw_error(ec); - } - else - { - size_ = new_size; - protocol_ = 0; - } -} - -bool operator==(const endpoint& e1, const endpoint& e2) -{ - using namespace std; // For memcmp. - return e1.size() == e2.size() && memcmp(e1.data(), e2.data(), e1.size()) == 0; -} - -bool operator<(const endpoint& e1, const endpoint& e2) -{ - if (e1.protocol() < e2.protocol()) - return true; - - if (e1.protocol() > e2.protocol()) - return false; - - using namespace std; // For memcmp. - std::size_t compare_size = e1.size() < e2.size() ? e1.size() : e2.size(); - int compare_result = memcmp(e1.data(), e2.data(), compare_size); - - if (compare_result < 0) - return true; - - if (compare_result > 0) - return false; - - return e1.size() < e2.size(); -} - -void endpoint::init(const void* sock_addr, - std::size_t sock_addr_size, int sock_protocol) -{ - if (sock_addr_size > sizeof(asio::detail::sockaddr_storage_type)) - { - asio::error_code ec(asio::error::invalid_argument); - asio::detail::throw_error(ec); - } - - using namespace std; // For memset and memcpy. - memset(&data_.generic, 0, sizeof(asio::detail::sockaddr_storage_type)); - if (sock_addr_size > 0) - memcpy(&data_.generic, sock_addr, sock_addr_size); - - size_ = sock_addr_size; - protocol_ = sock_protocol; -} - -} // namespace detail -} // namespace generic -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_GENERIC_DETAIL_IMPL_ENDPOINT_IPP diff --git a/scout_sdk/asio/asio/generic/raw_protocol.hpp b/scout_sdk/asio/asio/generic/raw_protocol.hpp deleted file mode 100644 index b83dca6..0000000 --- a/scout_sdk/asio/asio/generic/raw_protocol.hpp +++ /dev/null @@ -1,121 +0,0 @@ -// -// generic/raw_protocol.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_GENERIC_RAW_PROTOCOL_HPP -#define ASIO_GENERIC_RAW_PROTOCOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/basic_raw_socket.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/generic/basic_endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace generic { - -/// Encapsulates the flags needed for a generic raw socket. -/** - * The asio::generic::raw_protocol class contains flags necessary for - * raw sockets of any address family and protocol. - * - * @par Examples - * Constructing using a native address family and socket protocol: - * @code raw_protocol p(AF_INET, IPPROTO_ICMP); @endcode - * Constructing from a specific protocol type: - * @code raw_protocol p(asio::ip::icmp::v4()); @endcode - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol. - */ -class raw_protocol -{ -public: - /// Construct a protocol object for a specific address family and protocol. - raw_protocol(int address_family, int socket_protocol) - : family_(address_family), - protocol_(socket_protocol) - { - } - - /// Construct a generic protocol object from a specific protocol. - /** - * @throws @c bad_cast Thrown if the source protocol is not raw-oriented. - */ - template - raw_protocol(const Protocol& source_protocol) - : family_(source_protocol.family()), - protocol_(source_protocol.protocol()) - { - if (source_protocol.type() != type()) - { - std::bad_cast ex; - asio::detail::throw_exception(ex); - } - } - - /// Obtain an identifier for the type of the protocol. - int type() const - { - return ASIO_OS_DEF(SOCK_RAW); - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return protocol_; - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return family_; - } - - /// Compare two protocols for equality. - friend bool operator==(const raw_protocol& p1, const raw_protocol& p2) - { - return p1.family_ == p2.family_ && p1.protocol_ == p2.protocol_; - } - - /// Compare two protocols for inequality. - friend bool operator!=(const raw_protocol& p1, const raw_protocol& p2) - { - return !(p1 == p2); - } - - /// The type of an endpoint. - typedef basic_endpoint endpoint; - - /// The generic socket type. - typedef basic_raw_socket socket; - -private: - int family_; - int protocol_; -}; - -} // namespace generic -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_GENERIC_RAW_PROTOCOL_HPP diff --git a/scout_sdk/asio/asio/generic/seq_packet_protocol.hpp b/scout_sdk/asio/asio/generic/seq_packet_protocol.hpp deleted file mode 100644 index f92a4c8..0000000 --- a/scout_sdk/asio/asio/generic/seq_packet_protocol.hpp +++ /dev/null @@ -1,122 +0,0 @@ -// -// generic/seq_packet_protocol.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_GENERIC_SEQ_PACKET_PROTOCOL_HPP -#define ASIO_GENERIC_SEQ_PACKET_PROTOCOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/basic_seq_packet_socket.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/generic/basic_endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace generic { - -/// Encapsulates the flags needed for a generic sequenced packet socket. -/** - * The asio::generic::seq_packet_protocol class contains flags necessary - * for seq_packet-oriented sockets of any address family and protocol. - * - * @par Examples - * Constructing using a native address family and socket protocol: - * @code seq_packet_protocol p(AF_INET, IPPROTO_SCTP); @endcode - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol. - */ -class seq_packet_protocol -{ -public: - /// Construct a protocol object for a specific address family and protocol. - seq_packet_protocol(int address_family, int socket_protocol) - : family_(address_family), - protocol_(socket_protocol) - { - } - - /// Construct a generic protocol object from a specific protocol. - /** - * @throws @c bad_cast Thrown if the source protocol is not based around - * sequenced packets. - */ - template - seq_packet_protocol(const Protocol& source_protocol) - : family_(source_protocol.family()), - protocol_(source_protocol.protocol()) - { - if (source_protocol.type() != type()) - { - std::bad_cast ex; - asio::detail::throw_exception(ex); - } - } - - /// Obtain an identifier for the type of the protocol. - int type() const - { - return ASIO_OS_DEF(SOCK_SEQPACKET); - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return protocol_; - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return family_; - } - - /// Compare two protocols for equality. - friend bool operator==(const seq_packet_protocol& p1, - const seq_packet_protocol& p2) - { - return p1.family_ == p2.family_ && p1.protocol_ == p2.protocol_; - } - - /// Compare two protocols for inequality. - friend bool operator!=(const seq_packet_protocol& p1, - const seq_packet_protocol& p2) - { - return !(p1 == p2); - } - - /// The type of an endpoint. - typedef basic_endpoint endpoint; - - /// The generic socket type. - typedef basic_seq_packet_socket socket; - -private: - int family_; - int protocol_; -}; - -} // namespace generic -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_GENERIC_SEQ_PACKET_PROTOCOL_HPP diff --git a/scout_sdk/asio/asio/generic/stream_protocol.hpp b/scout_sdk/asio/asio/generic/stream_protocol.hpp deleted file mode 100644 index 8349f25..0000000 --- a/scout_sdk/asio/asio/generic/stream_protocol.hpp +++ /dev/null @@ -1,127 +0,0 @@ -// -// generic/stream_protocol.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_GENERIC_STREAM_PROTOCOL_HPP -#define ASIO_GENERIC_STREAM_PROTOCOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/basic_socket_iostream.hpp" -#include "asio/basic_stream_socket.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/generic/basic_endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace generic { - -/// Encapsulates the flags needed for a generic stream-oriented socket. -/** - * The asio::generic::stream_protocol class contains flags necessary for - * stream-oriented sockets of any address family and protocol. - * - * @par Examples - * Constructing using a native address family and socket protocol: - * @code stream_protocol p(AF_INET, IPPROTO_TCP); @endcode - * Constructing from a specific protocol type: - * @code stream_protocol p(asio::ip::tcp::v4()); @endcode - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol. - */ -class stream_protocol -{ -public: - /// Construct a protocol object for a specific address family and protocol. - stream_protocol(int address_family, int socket_protocol) - : family_(address_family), - protocol_(socket_protocol) - { - } - - /// Construct a generic protocol object from a specific protocol. - /** - * @throws @c bad_cast Thrown if the source protocol is not stream-oriented. - */ - template - stream_protocol(const Protocol& source_protocol) - : family_(source_protocol.family()), - protocol_(source_protocol.protocol()) - { - if (source_protocol.type() != type()) - { - std::bad_cast ex; - asio::detail::throw_exception(ex); - } - } - - /// Obtain an identifier for the type of the protocol. - int type() const - { - return ASIO_OS_DEF(SOCK_STREAM); - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return protocol_; - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return family_; - } - - /// Compare two protocols for equality. - friend bool operator==(const stream_protocol& p1, const stream_protocol& p2) - { - return p1.family_ == p2.family_ && p1.protocol_ == p2.protocol_; - } - - /// Compare two protocols for inequality. - friend bool operator!=(const stream_protocol& p1, const stream_protocol& p2) - { - return !(p1 == p2); - } - - /// The type of an endpoint. - typedef basic_endpoint endpoint; - - /// The generic socket type. - typedef basic_stream_socket socket; - -#if !defined(ASIO_NO_IOSTREAM) - /// The generic socket iostream type. - typedef basic_socket_iostream iostream; -#endif // !defined(ASIO_NO_IOSTREAM) - -private: - int family_; - int protocol_; -}; - -} // namespace generic -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_GENERIC_STREAM_PROTOCOL_HPP diff --git a/scout_sdk/asio/asio/handler_alloc_hook.hpp b/scout_sdk/asio/asio/handler_alloc_hook.hpp deleted file mode 100644 index d7fe2b0..0000000 --- a/scout_sdk/asio/asio/handler_alloc_hook.hpp +++ /dev/null @@ -1,81 +0,0 @@ -// -// handler_alloc_hook.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_HANDLER_ALLOC_HOOK_HPP -#define ASIO_HANDLER_ALLOC_HOOK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default allocation function for handlers. -/** - * Asynchronous operations may need to allocate temporary objects. Since - * asynchronous operations have a handler function object, these temporary - * objects can be said to be associated with the handler. - * - * Implement asio_handler_allocate and asio_handler_deallocate for your own - * handlers to provide custom allocation for these temporary objects. - * - * The default implementation of these allocation hooks uses ::operator - * new and ::operator delete. - * - * @note All temporary objects associated with a handler will be deallocated - * before the upcall to the handler is performed. This allows the same memory to - * be reused for a subsequent asynchronous operation initiated by the handler. - * - * @par Example - * @code - * class my_handler; - * - * void* asio_handler_allocate(std::size_t size, my_handler* context) - * { - * return ::operator new(size); - * } - * - * void asio_handler_deallocate(void* pointer, std::size_t size, - * my_handler* context) - * { - * ::operator delete(pointer); - * } - * @endcode - */ -ASIO_DECL void* asio_handler_allocate( - std::size_t size, ...); - -/// Default deallocation function for handlers. -/** - * Implement asio_handler_allocate and asio_handler_deallocate for your own - * handlers to provide custom allocation for the associated temporary objects. - * - * The default implementation of these allocation hooks uses ::operator - * new and ::operator delete. - * - * @sa asio_handler_allocate. - */ -ASIO_DECL void asio_handler_deallocate( - void* pointer, std::size_t size, ...); - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/handler_alloc_hook.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_HANDLER_ALLOC_HOOK_HPP diff --git a/scout_sdk/asio/asio/handler_continuation_hook.hpp b/scout_sdk/asio/asio/handler_continuation_hook.hpp deleted file mode 100644 index d41d105..0000000 --- a/scout_sdk/asio/asio/handler_continuation_hook.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// -// handler_continuation_hook.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_HANDLER_CONTINUATION_HOOK_HPP -#define ASIO_HANDLER_CONTINUATION_HOOK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default continuation function for handlers. -/** - * Asynchronous operations may represent a continuation of the asynchronous - * control flow associated with the current handler. The implementation can use - * this knowledge to optimise scheduling of the handler. - * - * Implement asio_handler_is_continuation for your own handlers to indicate - * when a handler represents a continuation. - * - * The default implementation of the continuation hook returns false. - * - * @par Example - * @code - * class my_handler; - * - * bool asio_handler_is_continuation(my_handler* context) - * { - * return true; - * } - * @endcode - */ -inline bool asio_handler_is_continuation(...) -{ - return false; -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_HANDLER_CONTINUATION_HOOK_HPP diff --git a/scout_sdk/asio/asio/handler_invoke_hook.hpp b/scout_sdk/asio/asio/handler_invoke_hook.hpp deleted file mode 100644 index ee618e5..0000000 --- a/scout_sdk/asio/asio/handler_invoke_hook.hpp +++ /dev/null @@ -1,85 +0,0 @@ -// -// handler_invoke_hook.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_HANDLER_INVOKE_HOOK_HPP -#define ASIO_HANDLER_INVOKE_HOOK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/** @defgroup asio_handler_invoke asio::asio_handler_invoke - * - * @brief Default invoke function for handlers. - * - * Completion handlers for asynchronous operations are invoked by the - * io_context associated with the corresponding object (e.g. a socket or - * deadline_timer). Certain guarantees are made on when the handler may be - * invoked, in particular that a handler can only be invoked from a thread that - * is currently calling @c run() on the corresponding io_context object. - * Handlers may subsequently be invoked through other objects (such as - * io_context::strand objects) that provide additional guarantees. - * - * When asynchronous operations are composed from other asynchronous - * operations, all intermediate handlers should be invoked using the same - * method as the final handler. This is required to ensure that user-defined - * objects are not accessed in a way that may violate the guarantees. This - * hooking function ensures that the invoked method used for the final handler - * is accessible at each intermediate step. - * - * Implement asio_handler_invoke for your own handlers to specify a custom - * invocation strategy. - * - * This default implementation invokes the function object like so: - * @code function(); @endcode - * If necessary, the default implementation makes a copy of the function object - * so that the non-const operator() can be used. - * - * @par Example - * @code - * class my_handler; - * - * template - * void asio_handler_invoke(Function function, my_handler* context) - * { - * context->strand_.dispatch(function); - * } - * @endcode - */ -/*@{*/ - -/// Default handler invocation hook used for non-const function objects. -template -inline void asio_handler_invoke(Function& function, ...) -{ - function(); -} - -/// Default handler invocation hook used for const function objects. -template -inline void asio_handler_invoke(const Function& function, ...) -{ - Function tmp(function); - tmp(); -} - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_HANDLER_INVOKE_HOOK_HPP diff --git a/scout_sdk/asio/asio/handler_type.hpp b/scout_sdk/asio/asio/handler_type.hpp deleted file mode 100644 index bc0d305..0000000 --- a/scout_sdk/asio/asio/handler_type.hpp +++ /dev/null @@ -1,50 +0,0 @@ -// -// handler_type.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_HANDLER_TYPE_HPP -#define ASIO_HANDLER_TYPE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// (Deprecated: Use two-parameter version of async_result.) Default handler -/// type traits provided for all completion token types. -/** - * The handler_type traits class is used for determining the concrete handler - * type to be used for an asynchronous operation. It allows the handler type to - * be determined at the point where the specific completion handler signature - * is known. - * - * This template may be specialised for user-defined completion token types. - */ -template -struct handler_type -{ - /// The handler type for the specific signature. - typedef typename conditional< - is_same::type>::value, - decay, - handler_type::type, Signature> - >::type::type type; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_HANDLER_TYPE_HPP diff --git a/scout_sdk/asio/asio/high_resolution_timer.hpp b/scout_sdk/asio/asio/high_resolution_timer.hpp deleted file mode 100644 index 0549cc2..0000000 --- a/scout_sdk/asio/asio/high_resolution_timer.hpp +++ /dev/null @@ -1,44 +0,0 @@ -// -// high_resolution_timer.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_HIGH_RESOLUTION_TIMER_HPP -#define ASIO_HIGH_RESOLUTION_TIMER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_waitable_timer.hpp" -#include "asio/detail/chrono.hpp" - -namespace asio { - -/// Typedef for a timer based on the high resolution clock. -/** - * This typedef uses the C++11 @c <chrono> standard library facility, if - * available. Otherwise, it may use the Boost.Chrono library. To explicitly - * utilise Boost.Chrono, use the basic_waitable_timer template directly: - * @code - * typedef basic_waitable_timer timer; - * @endcode - */ -typedef basic_waitable_timer< - chrono::high_resolution_clock> - high_resolution_timer; - -} // namespace asio - -#endif // defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_HIGH_RESOLUTION_TIMER_HPP diff --git a/scout_sdk/asio/asio/impl/buffered_read_stream.hpp b/scout_sdk/asio/asio/impl/buffered_read_stream.hpp deleted file mode 100644 index e0ed20e..0000000 --- a/scout_sdk/asio/asio/impl/buffered_read_stream.hpp +++ /dev/null @@ -1,429 +0,0 @@ -// -// impl/buffered_read_stream.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_BUFFERED_READ_STREAM_HPP -#define ASIO_IMPL_BUFFERED_READ_STREAM_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -std::size_t buffered_read_stream::fill() -{ - detail::buffer_resize_guard - resize_guard(storage_); - std::size_t previous_size = storage_.size(); - storage_.resize(storage_.capacity()); - storage_.resize(previous_size + next_layer_.read_some(buffer( - storage_.data() + previous_size, - storage_.size() - previous_size))); - resize_guard.commit(); - return storage_.size() - previous_size; -} - -template -std::size_t buffered_read_stream::fill(asio::error_code& ec) -{ - detail::buffer_resize_guard - resize_guard(storage_); - std::size_t previous_size = storage_.size(); - storage_.resize(storage_.capacity()); - storage_.resize(previous_size + next_layer_.read_some(buffer( - storage_.data() + previous_size, - storage_.size() - previous_size), - ec)); - resize_guard.commit(); - return storage_.size() - previous_size; -} - -namespace detail -{ - template - class buffered_fill_handler - { - public: - buffered_fill_handler(detail::buffered_stream_storage& storage, - std::size_t previous_size, ReadHandler& handler) - : storage_(storage), - previous_size_(previous_size), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - buffered_fill_handler(const buffered_fill_handler& other) - : storage_(other.storage_), - previous_size_(other.previous_size_), - handler_(other.handler_) - { - } - - buffered_fill_handler(buffered_fill_handler&& other) - : storage_(other.storage_), - previous_size_(other.previous_size_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - const std::size_t bytes_transferred) - { - storage_.resize(previous_size_ + bytes_transferred); - handler_(ec, bytes_transferred); - } - - //private: - detail::buffered_stream_storage& storage_; - std::size_t previous_size_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - buffered_fill_handler* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - buffered_fill_handler* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - buffered_fill_handler* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - buffered_fill_handler* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - buffered_fill_handler* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::buffered_fill_handler, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const detail::buffered_fill_handler& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::buffered_fill_handler, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const detail::buffered_fill_handler& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -buffered_read_stream::async_fill( - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - std::size_t previous_size = storage_.size(); - storage_.resize(storage_.capacity()); - next_layer_.async_read_some( - buffer( - storage_.data() + previous_size, - storage_.size() - previous_size), - detail::buffered_fill_handler( - storage_, previous_size, init.completion_handler)); - - return init.result.get(); -} - -template -template -std::size_t buffered_read_stream::read_some( - const MutableBufferSequence& buffers) -{ - using asio::buffer_size; - if (buffer_size(buffers) == 0) - return 0; - - if (storage_.empty()) - this->fill(); - - return this->copy(buffers); -} - -template -template -std::size_t buffered_read_stream::read_some( - const MutableBufferSequence& buffers, asio::error_code& ec) -{ - ec = asio::error_code(); - - using asio::buffer_size; - if (buffer_size(buffers) == 0) - return 0; - - if (storage_.empty() && !this->fill(ec)) - return 0; - - return this->copy(buffers); -} - -namespace detail -{ - template - class buffered_read_some_handler - { - public: - buffered_read_some_handler(detail::buffered_stream_storage& storage, - const MutableBufferSequence& buffers, ReadHandler& handler) - : storage_(storage), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - buffered_read_some_handler(const buffered_read_some_handler& other) - : storage_(other.storage_), - buffers_(other.buffers_), - handler_(other.handler_) - { - } - - buffered_read_some_handler(buffered_read_some_handler&& other) - : storage_(other.storage_), - buffers_(other.buffers_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, std::size_t) - { - if (ec || storage_.empty()) - { - const std::size_t length = 0; - handler_(ec, length); - } - else - { - const std::size_t bytes_copied = asio::buffer_copy( - buffers_, storage_.data(), storage_.size()); - storage_.consume(bytes_copied); - handler_(ec, bytes_copied); - } - } - - //private: - detail::buffered_stream_storage& storage_; - MutableBufferSequence buffers_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - buffered_read_some_handler< - MutableBufferSequence, ReadHandler>* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - buffered_read_some_handler< - MutableBufferSequence, ReadHandler>* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - buffered_read_some_handler< - MutableBufferSequence, ReadHandler>* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - buffered_read_some_handler< - MutableBufferSequence, ReadHandler>* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - buffered_read_some_handler< - MutableBufferSequence, ReadHandler>* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::buffered_read_some_handler, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::buffered_read_some_handler< - MutableBufferSequence, ReadHandler>& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::buffered_read_some_handler, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::buffered_read_some_handler< - MutableBufferSequence, ReadHandler>& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -buffered_read_stream::async_read_some( - const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - using asio::buffer_size; - if (buffer_size(buffers) == 0 || !storage_.empty()) - { - next_layer_.async_read_some(ASIO_MUTABLE_BUFFER(0, 0), - detail::buffered_read_some_handler< - MutableBufferSequence, ASIO_HANDLER_TYPE( - ReadHandler, void (asio::error_code, std::size_t))>( - storage_, buffers, init.completion_handler)); - } - else - { - this->async_fill(detail::buffered_read_some_handler< - MutableBufferSequence, ASIO_HANDLER_TYPE( - ReadHandler, void (asio::error_code, std::size_t))>( - storage_, buffers, init.completion_handler)); - } - - return init.result.get(); -} - -template -template -std::size_t buffered_read_stream::peek( - const MutableBufferSequence& buffers) -{ - if (storage_.empty()) - this->fill(); - return this->peek_copy(buffers); -} - -template -template -std::size_t buffered_read_stream::peek( - const MutableBufferSequence& buffers, asio::error_code& ec) -{ - ec = asio::error_code(); - if (storage_.empty() && !this->fill(ec)) - return 0; - return this->peek_copy(buffers); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_BUFFERED_READ_STREAM_HPP diff --git a/scout_sdk/asio/asio/impl/buffered_write_stream.hpp b/scout_sdk/asio/asio/impl/buffered_write_stream.hpp deleted file mode 100644 index bc2d823..0000000 --- a/scout_sdk/asio/asio/impl/buffered_write_stream.hpp +++ /dev/null @@ -1,411 +0,0 @@ -// -// impl/buffered_write_stream.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_BUFFERED_WRITE_STREAM_HPP -#define ASIO_IMPL_BUFFERED_WRITE_STREAM_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -std::size_t buffered_write_stream::flush() -{ - std::size_t bytes_written = write(next_layer_, - buffer(storage_.data(), storage_.size())); - storage_.consume(bytes_written); - return bytes_written; -} - -template -std::size_t buffered_write_stream::flush(asio::error_code& ec) -{ - std::size_t bytes_written = write(next_layer_, - buffer(storage_.data(), storage_.size()), - transfer_all(), ec); - storage_.consume(bytes_written); - return bytes_written; -} - -namespace detail -{ - template - class buffered_flush_handler - { - public: - buffered_flush_handler(detail::buffered_stream_storage& storage, - WriteHandler& handler) - : storage_(storage), - handler_(ASIO_MOVE_CAST(WriteHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - buffered_flush_handler(const buffered_flush_handler& other) - : storage_(other.storage_), - handler_(other.handler_) - { - } - - buffered_flush_handler(buffered_flush_handler&& other) - : storage_(other.storage_), - handler_(ASIO_MOVE_CAST(WriteHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - const std::size_t bytes_written) - { - storage_.consume(bytes_written); - handler_(ec, bytes_written); - } - - //private: - detail::buffered_stream_storage& storage_; - WriteHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - buffered_flush_handler* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - buffered_flush_handler* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - buffered_flush_handler* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - buffered_flush_handler* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - buffered_flush_handler* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::buffered_flush_handler, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const detail::buffered_flush_handler& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::buffered_flush_handler, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const detail::buffered_flush_handler& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -buffered_write_stream::async_flush( - ASIO_MOVE_ARG(WriteHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - async_write(next_layer_, buffer(storage_.data(), storage_.size()), - detail::buffered_flush_handler( - storage_, init.completion_handler)); - - return init.result.get(); -} - -template -template -std::size_t buffered_write_stream::write_some( - const ConstBufferSequence& buffers) -{ - using asio::buffer_size; - if (buffer_size(buffers) == 0) - return 0; - - if (storage_.size() == storage_.capacity()) - this->flush(); - - return this->copy(buffers); -} - -template -template -std::size_t buffered_write_stream::write_some( - const ConstBufferSequence& buffers, asio::error_code& ec) -{ - ec = asio::error_code(); - - using asio::buffer_size; - if (buffer_size(buffers) == 0) - return 0; - - if (storage_.size() == storage_.capacity() && !flush(ec)) - return 0; - - return this->copy(buffers); -} - -namespace detail -{ - template - class buffered_write_some_handler - { - public: - buffered_write_some_handler(detail::buffered_stream_storage& storage, - const ConstBufferSequence& buffers, WriteHandler& handler) - : storage_(storage), - buffers_(buffers), - handler_(ASIO_MOVE_CAST(WriteHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - buffered_write_some_handler(const buffered_write_some_handler& other) - : storage_(other.storage_), - buffers_(other.buffers_), - handler_(other.handler_) - { - } - - buffered_write_some_handler(buffered_write_some_handler&& other) - : storage_(other.storage_), - buffers_(other.buffers_), - handler_(ASIO_MOVE_CAST(WriteHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, std::size_t) - { - if (ec) - { - const std::size_t length = 0; - handler_(ec, length); - } - else - { - using asio::buffer_size; - std::size_t orig_size = storage_.size(); - std::size_t space_avail = storage_.capacity() - orig_size; - std::size_t bytes_avail = buffer_size(buffers_); - std::size_t length = bytes_avail < space_avail - ? bytes_avail : space_avail; - storage_.resize(orig_size + length); - const std::size_t bytes_copied = asio::buffer_copy( - storage_.data() + orig_size, buffers_, length); - handler_(ec, bytes_copied); - } - } - - //private: - detail::buffered_stream_storage& storage_; - ConstBufferSequence buffers_; - WriteHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - buffered_write_some_handler< - ConstBufferSequence, WriteHandler>* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - buffered_write_some_handler< - ConstBufferSequence, WriteHandler>* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - buffered_write_some_handler< - ConstBufferSequence, WriteHandler>* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - buffered_write_some_handler< - ConstBufferSequence, WriteHandler>* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - buffered_write_some_handler< - ConstBufferSequence, WriteHandler>* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::buffered_write_some_handler, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::buffered_write_some_handler< - ConstBufferSequence, WriteHandler>& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::buffered_write_some_handler, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::buffered_write_some_handler< - ConstBufferSequence, WriteHandler>& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -buffered_write_stream::async_write_some( - const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - using asio::buffer_size; - if (buffer_size(buffers) == 0 - || storage_.size() < storage_.capacity()) - { - next_layer_.async_write_some(ASIO_CONST_BUFFER(0, 0), - detail::buffered_write_some_handler< - ConstBufferSequence, ASIO_HANDLER_TYPE( - WriteHandler, void (asio::error_code, std::size_t))>( - storage_, buffers, init.completion_handler)); - } - else - { - this->async_flush(detail::buffered_write_some_handler< - ConstBufferSequence, ASIO_HANDLER_TYPE( - WriteHandler, void (asio::error_code, std::size_t))>( - storage_, buffers, init.completion_handler)); - } - - return init.result.get(); -} - -template -template -std::size_t buffered_write_stream::copy( - const ConstBufferSequence& buffers) -{ - using asio::buffer_size; - std::size_t orig_size = storage_.size(); - std::size_t space_avail = storage_.capacity() - orig_size; - std::size_t bytes_avail = buffer_size(buffers); - std::size_t length = bytes_avail < space_avail ? bytes_avail : space_avail; - storage_.resize(orig_size + length); - return asio::buffer_copy( - storage_.data() + orig_size, buffers, length); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_BUFFERED_WRITE_STREAM_HPP diff --git a/scout_sdk/asio/asio/impl/connect.hpp b/scout_sdk/asio/asio/impl/connect.hpp deleted file mode 100644 index bff1913..0000000 --- a/scout_sdk/asio/asio/impl/connect.hpp +++ /dev/null @@ -1,860 +0,0 @@ -// -// impl/connect.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_CONNECT_HPP -#define ASIO_IMPL_CONNECT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/post.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - struct default_connect_condition - { - template - bool operator()(const asio::error_code&, const Endpoint&) - { - return true; - } - }; - - template - inline typename Protocol::endpoint deref_connect_result( - Iterator iter, asio::error_code& ec) - { - return ec ? typename Protocol::endpoint() : *iter; - } - - template - struct legacy_connect_condition_helper : T - { - typedef char (*fallback_func_type)(...); - operator fallback_func_type() const; - }; - - template - struct legacy_connect_condition_helper - { - R operator()(Arg1, Arg2) const; - char operator()(...) const; - }; - - template - struct is_legacy_connect_condition - { - static char asio_connect_condition_check(char); - static char (&asio_connect_condition_check(Iterator))[2]; - - static const bool value = - sizeof(asio_connect_condition_check( - (*static_cast*>(0))( - *static_cast(0), - *static_cast(0)))) != 1; - }; - - template - inline Iterator call_connect_condition(ConnectCondition& connect_condition, - const asio::error_code& ec, Iterator next, Iterator end, - typename enable_if::value>::type* = 0) - { - if (next != end) - return connect_condition(ec, next); - return end; - } - - template - inline Iterator call_connect_condition(ConnectCondition& connect_condition, - const asio::error_code& ec, Iterator next, Iterator end, - typename enable_if::value>::type* = 0) - { - for (;next != end; ++next) - if (connect_condition(ec, *next)) - return next; - return end; - } -} - -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, - typename enable_if::value>::type*) -{ - asio::error_code ec; - typename Protocol::endpoint result = connect(s, endpoints, ec); - asio::detail::throw_error(ec, "connect"); - return result; -} - -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, asio::error_code& ec, - typename enable_if::value>::type*) -{ - return detail::deref_connect_result( - connect(s, endpoints.begin(), endpoints.end(), - detail::default_connect_condition(), ec), ec); -} - -#if !defined(ASIO_NO_DEPRECATED) -template -Iterator connect(basic_socket& s, Iterator begin, - typename enable_if::value>::type*) -{ - asio::error_code ec; - Iterator result = connect(s, begin, ec); - asio::detail::throw_error(ec, "connect"); - return result; -} - -template -inline Iterator connect(basic_socket& s, - Iterator begin, asio::error_code& ec, - typename enable_if::value>::type*) -{ - return connect(s, begin, Iterator(), detail::default_connect_condition(), ec); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -template -Iterator connect(basic_socket& s, - Iterator begin, Iterator end) -{ - asio::error_code ec; - Iterator result = connect(s, begin, end, ec); - asio::detail::throw_error(ec, "connect"); - return result; -} - -template -inline Iterator connect(basic_socket& s, - Iterator begin, Iterator end, asio::error_code& ec) -{ - return connect(s, begin, end, detail::default_connect_condition(), ec); -} - -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, ConnectCondition connect_condition, - typename enable_if::value>::type*) -{ - asio::error_code ec; - typename Protocol::endpoint result = connect( - s, endpoints, connect_condition, ec); - asio::detail::throw_error(ec, "connect"); - return result; -} - -template -typename Protocol::endpoint connect( - basic_socket& s, - const EndpointSequence& endpoints, ConnectCondition connect_condition, - asio::error_code& ec, - typename enable_if::value>::type*) -{ - return detail::deref_connect_result( - connect(s, endpoints.begin(), endpoints.end(), - connect_condition, ec), ec); -} - -#if !defined(ASIO_NO_DEPRECATED) -template -Iterator connect(basic_socket& s, - Iterator begin, ConnectCondition connect_condition, - typename enable_if::value>::type*) -{ - asio::error_code ec; - Iterator result = connect(s, begin, connect_condition, ec); - asio::detail::throw_error(ec, "connect"); - return result; -} - -template -inline Iterator connect(basic_socket& s, - Iterator begin, ConnectCondition connect_condition, - asio::error_code& ec, - typename enable_if::value>::type*) -{ - return connect(s, begin, Iterator(), connect_condition, ec); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -template -Iterator connect(basic_socket& s, - Iterator begin, Iterator end, ConnectCondition connect_condition) -{ - asio::error_code ec; - Iterator result = connect(s, begin, end, connect_condition, ec); - asio::detail::throw_error(ec, "connect"); - return result; -} - -template -Iterator connect(basic_socket& s, - Iterator begin, Iterator end, ConnectCondition connect_condition, - asio::error_code& ec) -{ - ec = asio::error_code(); - - for (Iterator iter = begin; iter != end; ++iter) - { - iter = (detail::call_connect_condition(connect_condition, ec, iter, end)); - if (iter != end) - { - s.close(ec); - s.connect(*iter, ec); - if (!ec) - return iter; - } - else - break; - } - - if (!ec) - ec = asio::error::not_found; - - return end; -} - -namespace detail -{ - // Enable the empty base class optimisation for the connect condition. - template - class base_from_connect_condition - { - protected: - explicit base_from_connect_condition( - const ConnectCondition& connect_condition) - : connect_condition_(connect_condition) - { - } - - template - void check_condition(const asio::error_code& ec, - Iterator& iter, Iterator& end) - { - iter = detail::call_connect_condition(connect_condition_, ec, iter, end); - } - - private: - ConnectCondition connect_condition_; - }; - - // The default_connect_condition implementation is essentially a no-op. This - // template specialisation lets us eliminate all costs associated with it. - template <> - class base_from_connect_condition - { - protected: - explicit base_from_connect_condition(const default_connect_condition&) - { - } - - template - void check_condition(const asio::error_code&, Iterator&, Iterator&) - { - } - }; - - template - class range_connect_op : base_from_connect_condition - { - public: - range_connect_op(basic_socket& sock, - const EndpointSequence& endpoints, - const ConnectCondition& connect_condition, - RangeConnectHandler& handler) - : base_from_connect_condition(connect_condition), - socket_(sock), - endpoints_(endpoints), - index_(0), - start_(0), - handler_(ASIO_MOVE_CAST(RangeConnectHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - range_connect_op(const range_connect_op& other) - : base_from_connect_condition(other), - socket_(other.socket_), - endpoints_(other.endpoints_), - index_(other.index_), - start_(other.start_), - handler_(other.handler_) - { - } - - range_connect_op(range_connect_op&& other) - : base_from_connect_condition(other), - socket_(other.socket_), - endpoints_(other.endpoints_), - index_(other.index_), - start_(other.start_), - handler_(ASIO_MOVE_CAST(RangeConnectHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(asio::error_code ec, int start = 0) - { - typename EndpointSequence::const_iterator begin = endpoints_.begin(); - typename EndpointSequence::const_iterator iter = begin; - std::advance(iter, index_); - typename EndpointSequence::const_iterator end = endpoints_.end(); - - switch (start_ = start) - { - case 1: - for (;;) - { - this->check_condition(ec, iter, end); - index_ = std::distance(begin, iter); - - if (iter != end) - { - socket_.close(ec); - socket_.async_connect(*iter, - ASIO_MOVE_CAST(range_connect_op)(*this)); - return; - } - - if (start) - { - ec = asio::error::not_found; - asio::post(socket_.get_executor(), - detail::bind_handler( - ASIO_MOVE_CAST(range_connect_op)(*this), ec)); - return; - } - - default: - - if (iter == end) - break; - - if (!socket_.is_open()) - { - ec = asio::error::operation_aborted; - break; - } - - if (!ec) - break; - - ++iter; - ++index_; - } - - handler_(static_cast(ec), - static_cast( - ec || iter == end ? typename Protocol::endpoint() : *iter)); - } - } - - //private: - basic_socket& socket_; - EndpointSequence endpoints_; - std::size_t index_; - int start_; - RangeConnectHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - range_connect_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - range_connect_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - range_connect_op* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - range_connect_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - range_connect_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - class iterator_connect_op : base_from_connect_condition - { - public: - iterator_connect_op(basic_socket& sock, - const Iterator& begin, const Iterator& end, - const ConnectCondition& connect_condition, - IteratorConnectHandler& handler) - : base_from_connect_condition(connect_condition), - socket_(sock), - iter_(begin), - end_(end), - start_(0), - handler_(ASIO_MOVE_CAST(IteratorConnectHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - iterator_connect_op(const iterator_connect_op& other) - : base_from_connect_condition(other), - socket_(other.socket_), - iter_(other.iter_), - end_(other.end_), - start_(other.start_), - handler_(other.handler_) - { - } - - iterator_connect_op(iterator_connect_op&& other) - : base_from_connect_condition(other), - socket_(other.socket_), - iter_(other.iter_), - end_(other.end_), - start_(other.start_), - handler_(ASIO_MOVE_CAST(IteratorConnectHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(asio::error_code ec, int start = 0) - { - switch (start_ = start) - { - case 1: - for (;;) - { - this->check_condition(ec, iter_, end_); - - if (iter_ != end_) - { - socket_.close(ec); - socket_.async_connect(*iter_, - ASIO_MOVE_CAST(iterator_connect_op)(*this)); - return; - } - - if (start) - { - ec = asio::error::not_found; - asio::post(socket_.get_executor(), - detail::bind_handler( - ASIO_MOVE_CAST(iterator_connect_op)(*this), ec)); - return; - } - - default: - - if (iter_ == end_) - break; - - if (!socket_.is_open()) - { - ec = asio::error::operation_aborted; - break; - } - - if (!ec) - break; - - ++iter_; - } - - handler_(static_cast(ec), - static_cast(iter_)); - } - } - - //private: - basic_socket& socket_; - Iterator iter_; - Iterator end_; - int start_; - IteratorConnectHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - iterator_connect_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - iterator_connect_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - iterator_connect_op* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - iterator_connect_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - iterator_connect_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::range_connect_op, - Allocator> -{ - typedef typename associated_allocator< - RangeConnectHandler, Allocator>::type type; - - static type get( - const detail::range_connect_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::range_connect_op, - Executor> -{ - typedef typename associated_executor< - RangeConnectHandler, Executor>::type type; - - static type get( - const detail::range_connect_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -template -struct associated_allocator< - detail::iterator_connect_op, - Allocator> -{ - typedef typename associated_allocator< - IteratorConnectHandler, Allocator>::type type; - - static type get( - const detail::iterator_connect_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::iterator_connect_op, - Executor> -{ - typedef typename associated_executor< - IteratorConnectHandler, Executor>::type type; - - static type get( - const detail::iterator_connect_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(RangeConnectHandler, - void (asio::error_code, typename Protocol::endpoint)) -async_connect(basic_socket& s, - const EndpointSequence& endpoints, - ASIO_MOVE_ARG(RangeConnectHandler) handler, - typename enable_if::value>::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a RangeConnectHandler. - ASIO_RANGE_CONNECT_HANDLER_CHECK( - RangeConnectHandler, handler, typename Protocol::endpoint) type_check; - - async_completion - init(handler); - - detail::range_connect_op(s, - endpoints, detail::default_connect_condition(), - init.completion_handler)(asio::error_code(), 1); - - return init.result.get(); -} - -#if !defined(ASIO_NO_DEPRECATED) -template -inline ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, - Iterator begin, ASIO_MOVE_ARG(IteratorConnectHandler) handler, - typename enable_if::value>::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a IteratorConnectHandler. - ASIO_ITERATOR_CONNECT_HANDLER_CHECK( - IteratorConnectHandler, handler, Iterator) type_check; - - async_completion init(handler); - - detail::iterator_connect_op(s, - begin, Iterator(), detail::default_connect_condition(), - init.completion_handler)(asio::error_code(), 1); - - return init.result.get(); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -template -inline ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, - Iterator begin, Iterator end, - ASIO_MOVE_ARG(IteratorConnectHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a IteratorConnectHandler. - ASIO_ITERATOR_CONNECT_HANDLER_CHECK( - IteratorConnectHandler, handler, Iterator) type_check; - - async_completion init(handler); - - detail::iterator_connect_op(s, - begin, end, detail::default_connect_condition(), - init.completion_handler)(asio::error_code(), 1); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(RangeConnectHandler, - void (asio::error_code, typename Protocol::endpoint)) -async_connect(basic_socket& s, - const EndpointSequence& endpoints, ConnectCondition connect_condition, - ASIO_MOVE_ARG(RangeConnectHandler) handler, - typename enable_if::value>::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a RangeConnectHandler. - ASIO_RANGE_CONNECT_HANDLER_CHECK( - RangeConnectHandler, handler, typename Protocol::endpoint) type_check; - - async_completion - init(handler); - - detail::range_connect_op(s, - endpoints, connect_condition, init.completion_handler)( - asio::error_code(), 1); - - return init.result.get(); -} - -#if !defined(ASIO_NO_DEPRECATED) -template -inline ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, - Iterator begin, ConnectCondition connect_condition, - ASIO_MOVE_ARG(IteratorConnectHandler) handler, - typename enable_if::value>::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a IteratorConnectHandler. - ASIO_ITERATOR_CONNECT_HANDLER_CHECK( - IteratorConnectHandler, handler, Iterator) type_check; - - async_completion init(handler); - - detail::iterator_connect_op(s, - begin, Iterator(), connect_condition, init.completion_handler)( - asio::error_code(), 1); - - return init.result.get(); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -template -inline ASIO_INITFN_RESULT_TYPE(IteratorConnectHandler, - void (asio::error_code, Iterator)) -async_connect(basic_socket& s, - Iterator begin, Iterator end, ConnectCondition connect_condition, - ASIO_MOVE_ARG(IteratorConnectHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a IteratorConnectHandler. - ASIO_ITERATOR_CONNECT_HANDLER_CHECK( - IteratorConnectHandler, handler, Iterator) type_check; - - async_completion init(handler); - - detail::iterator_connect_op(s, - begin, end, connect_condition, init.completion_handler)( - asio::error_code(), 1); - - return init.result.get(); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_CONNECT_HPP diff --git a/scout_sdk/asio/asio/impl/defer.hpp b/scout_sdk/asio/asio/impl/defer.hpp deleted file mode 100644 index a27df0f..0000000 --- a/scout_sdk/asio/asio/impl/defer.hpp +++ /dev/null @@ -1,77 +0,0 @@ -// -// impl/defer.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_DEFER_HPP -#define ASIO_IMPL_DEFER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/work_dispatcher.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) defer( - ASIO_MOVE_ARG(CompletionToken) token) -{ - typedef ASIO_HANDLER_TYPE(CompletionToken, void()) handler; - - async_completion init(token); - - typename associated_executor::type ex( - (get_associated_executor)(init.completion_handler)); - - typename associated_allocator::type alloc( - (get_associated_allocator)(init.completion_handler)); - - ex.defer(ASIO_MOVE_CAST(handler)(init.completion_handler), alloc); - - return init.result.get(); -} - -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) defer( - const Executor& ex, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type*) -{ - typedef ASIO_HANDLER_TYPE(CompletionToken, void()) handler; - - async_completion init(token); - - typename associated_allocator::type alloc( - (get_associated_allocator)(init.completion_handler)); - - ex.defer(detail::work_dispatcher(init.completion_handler), alloc); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) defer( - ExecutionContext& ctx, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type*) -{ - return (defer)(ctx.get_executor(), - ASIO_MOVE_CAST(CompletionToken)(token)); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_DEFER_HPP diff --git a/scout_sdk/asio/asio/impl/dispatch.hpp b/scout_sdk/asio/asio/impl/dispatch.hpp deleted file mode 100644 index 4e11c6b..0000000 --- a/scout_sdk/asio/asio/impl/dispatch.hpp +++ /dev/null @@ -1,78 +0,0 @@ -// -// impl/dispatch.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_DISPATCH_HPP -#define ASIO_IMPL_DISPATCH_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/work_dispatcher.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) dispatch( - ASIO_MOVE_ARG(CompletionToken) token) -{ - typedef ASIO_HANDLER_TYPE(CompletionToken, void()) handler; - - async_completion init(token); - - typename associated_executor::type ex( - (get_associated_executor)(init.completion_handler)); - - typename associated_allocator::type alloc( - (get_associated_allocator)(init.completion_handler)); - - ex.dispatch(ASIO_MOVE_CAST(handler)(init.completion_handler), alloc); - - return init.result.get(); -} - -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) dispatch( - const Executor& ex, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type*) -{ - typedef ASIO_HANDLER_TYPE(CompletionToken, void()) handler; - - async_completion init(token); - - typename associated_allocator::type alloc( - (get_associated_allocator)(init.completion_handler)); - - ex.dispatch(detail::work_dispatcher( - init.completion_handler), alloc); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) dispatch( - ExecutionContext& ctx, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type*) -{ - return (dispatch)(ctx.get_executor(), - ASIO_MOVE_CAST(CompletionToken)(token)); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_DISPATCH_HPP diff --git a/scout_sdk/asio/asio/impl/error.ipp b/scout_sdk/asio/asio/impl/error.ipp deleted file mode 100644 index 6b1f33a..0000000 --- a/scout_sdk/asio/asio/impl/error.ipp +++ /dev/null @@ -1,128 +0,0 @@ -// -// impl/error.ipp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_ERROR_IPP -#define ASIO_IMPL_ERROR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace error { - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -namespace detail { - -class netdb_category : public asio::error_category -{ -public: - const char* name() const ASIO_ERROR_CATEGORY_NOEXCEPT - { - return "asio.netdb"; - } - - std::string message(int value) const - { - if (value == error::host_not_found) - return "Host not found (authoritative)"; - if (value == error::host_not_found_try_again) - return "Host not found (non-authoritative), try again later"; - if (value == error::no_data) - return "The query is valid, but it does not have associated data"; - if (value == error::no_recovery) - return "A non-recoverable error occurred during database lookup"; - return "asio.netdb error"; - } -}; - -} // namespace detail - -const asio::error_category& get_netdb_category() -{ - static detail::netdb_category instance; - return instance; -} - -namespace detail { - -class addrinfo_category : public asio::error_category -{ -public: - const char* name() const ASIO_ERROR_CATEGORY_NOEXCEPT - { - return "asio.addrinfo"; - } - - std::string message(int value) const - { - if (value == error::service_not_found) - return "Service not found"; - if (value == error::socket_type_not_supported) - return "Socket type not supported"; - return "asio.addrinfo error"; - } -}; - -} // namespace detail - -const asio::error_category& get_addrinfo_category() -{ - static detail::addrinfo_category instance; - return instance; -} - -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -namespace detail { - -class misc_category : public asio::error_category -{ -public: - const char* name() const ASIO_ERROR_CATEGORY_NOEXCEPT - { - return "asio.misc"; - } - - std::string message(int value) const - { - if (value == error::already_open) - return "Already open"; - if (value == error::eof) - return "End of file"; - if (value == error::not_found) - return "Element not found"; - if (value == error::fd_set_failure) - return "The descriptor does not fit into the select call's fd_set"; - return "asio.misc error"; - } -}; - -} // namespace detail - -const asio::error_category& get_misc_category() -{ - static detail::misc_category instance; - return instance; -} - -} // namespace error -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_ERROR_IPP diff --git a/scout_sdk/asio/asio/impl/error_code.ipp b/scout_sdk/asio/asio/impl/error_code.ipp deleted file mode 100644 index 0c8a827..0000000 --- a/scout_sdk/asio/asio/impl/error_code.ipp +++ /dev/null @@ -1,206 +0,0 @@ -// -// impl/error_code.ipp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_ERROR_CODE_IPP -#define ASIO_IMPL_ERROR_CODE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# include -#elif defined(ASIO_WINDOWS_RUNTIME) -# include -#else -# include -# include -# include -#endif -#include "asio/detail/local_free_on_block_exit.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/error_code.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -class system_category : public error_category -{ -public: - const char* name() const ASIO_ERROR_CATEGORY_NOEXCEPT - { - return "asio.system"; - } - - std::string message(int value) const - { -#if defined(ASIO_WINDOWS_RUNTIME) || defined(ASIO_WINDOWS_APP) - std::wstring wmsg(128, wchar_t()); - for (;;) - { - DWORD wlength = ::FormatMessageW(FORMAT_MESSAGE_FROM_SYSTEM - | FORMAT_MESSAGE_IGNORE_INSERTS, 0, value, - MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), - &wmsg[0], static_cast(wmsg.size()), 0); - if (wlength == 0 && ::GetLastError() == ERROR_INSUFFICIENT_BUFFER) - { - wmsg.resize(wmsg.size() + wmsg.size() / 2); - continue; - } - if (wlength && wmsg[wlength - 1] == '\n') - --wlength; - if (wlength && wmsg[wlength - 1] == '\r') - --wlength; - if (wlength) - { - std::string msg(wlength * 2, char()); - int length = ::WideCharToMultiByte(CP_ACP, 0, - wmsg.c_str(), static_cast(wlength), - &msg[0], static_cast(wlength * 2), 0, 0); - if (length <= 0) - return "asio.system error"; - msg.resize(static_cast(length)); - return msg; - } - else - return "asio.system error"; - } -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) - char* msg = 0; - DWORD length = ::FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER - | FORMAT_MESSAGE_FROM_SYSTEM - | FORMAT_MESSAGE_IGNORE_INSERTS, 0, value, - MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (char*)&msg, 0, 0); - detail::local_free_on_block_exit local_free_obj(msg); - if (length && msg[length - 1] == '\n') - msg[--length] = '\0'; - if (length && msg[length - 1] == '\r') - msg[--length] = '\0'; - if (length) - return msg; - else - return "asio.system error"; -#else // defined(ASIO_WINDOWS_DESKTOP) || defined(__CYGWIN__) -#if !defined(__sun) - if (value == ECANCELED) - return "Operation aborted."; -#endif // !defined(__sun) -#if defined(__sun) || defined(__QNX__) || defined(__SYMBIAN32__) - using namespace std; - return strerror(value); -#else - char buf[256] = ""; - using namespace std; - return strerror_result(strerror_r(value, buf, sizeof(buf)), buf); -#endif -#endif // defined(ASIO_WINDOWS_DESKTOP) || defined(__CYGWIN__) - } - -#if defined(ASIO_HAS_STD_ERROR_CODE) - std::error_condition default_error_condition( - int ev) const ASIO_ERROR_CATEGORY_NOEXCEPT - { - switch (ev) - { - case access_denied: - return std::errc::permission_denied; - case address_family_not_supported: - return std::errc::address_family_not_supported; - case address_in_use: - return std::errc::address_in_use; - case already_connected: - return std::errc::already_connected; - case already_started: - return std::errc::connection_already_in_progress; - case broken_pipe: - return std::errc::broken_pipe; - case connection_aborted: - return std::errc::connection_aborted; - case connection_refused: - return std::errc::connection_refused; - case connection_reset: - return std::errc::connection_reset; - case bad_descriptor: - return std::errc::bad_file_descriptor; - case fault: - return std::errc::bad_address; - case host_unreachable: - return std::errc::host_unreachable; - case in_progress: - return std::errc::operation_in_progress; - case interrupted: - return std::errc::interrupted; - case invalid_argument: - return std::errc::invalid_argument; - case message_size: - return std::errc::message_size; - case name_too_long: - return std::errc::filename_too_long; - case network_down: - return std::errc::network_down; - case network_reset: - return std::errc::network_reset; - case network_unreachable: - return std::errc::network_unreachable; - case no_descriptors: - return std::errc::too_many_files_open; - case no_buffer_space: - return std::errc::no_buffer_space; - case no_memory: - return std::errc::not_enough_memory; - case no_permission: - return std::errc::operation_not_permitted; - case no_protocol_option: - return std::errc::no_protocol_option; - case no_such_device: - return std::errc::no_such_device; - case not_connected: - return std::errc::not_connected; - case not_socket: - return std::errc::not_a_socket; - case operation_aborted: - return std::errc::operation_canceled; - case operation_not_supported: - return std::errc::operation_not_supported; - case shut_down: - return std::make_error_condition(ev, *this); - case timed_out: - return std::errc::timed_out; - case try_again: - return std::errc::resource_unavailable_try_again; - case would_block: - return std::errc::operation_would_block; - default: - return std::make_error_condition(ev, *this); - } -#endif // defined(ASIO_HAS_STD_ERROR_CODE) - -private: - // Helper function to adapt the result from glibc's variant of strerror_r. - static const char* strerror_result(int, const char* s) { return s; } - static const char* strerror_result(const char* s, const char*) { return s; } -}; - -} // namespace detail - -const error_category& system_category() -{ - static detail::system_category instance; - return instance; -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_ERROR_CODE_IPP diff --git a/scout_sdk/asio/asio/impl/execution_context.hpp b/scout_sdk/asio/asio/impl/execution_context.hpp deleted file mode 100644 index 3d1e457..0000000 --- a/scout_sdk/asio/asio/impl/execution_context.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// -// impl/execution_context.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_EXECUTION_CONTEXT_HPP -#define ASIO_IMPL_EXECUTION_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/detail/service_registry.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -inline Service& use_service(execution_context& e) -{ - // Check that Service meets the necessary type requirements. - (void)static_cast(static_cast(0)); - - return e.service_registry_->template use_service(); -} - -#if !defined(GENERATING_DOCUMENTATION) -# if defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -Service& make_service(execution_context& e, ASIO_MOVE_ARG(Args)... args) -{ - detail::scoped_ptr svc( - new Service(e, ASIO_MOVE_CAST(Args)(args)...)); - e.service_registry_->template add_service(svc.get()); - Service& result = *svc; - svc.release(); - return result; -} - -# else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -Service& make_service(execution_context& e) -{ - detail::scoped_ptr svc(new Service(e)); - e.service_registry_->template add_service(svc.get()); - Service& result = *svc; - svc.release(); - return result; -} - -#define ASIO_PRIVATE_MAKE_SERVICE_DEF(n) \ - template \ - Service& make_service(execution_context& e, \ - ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - detail::scoped_ptr svc( \ - new Service(e, ASIO_VARIADIC_MOVE_ARGS(n))); \ - e.service_registry_->template add_service(svc.get()); \ - Service& result = *svc; \ - svc.release(); \ - return result; \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_MAKE_SERVICE_DEF) -#undef ASIO_PRIVATE_MAKE_SERVICE_DEF - -# endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline void add_service(execution_context& e, Service* svc) -{ - // Check that Service meets the necessary type requirements. - (void)static_cast(static_cast(0)); - - e.service_registry_->template add_service(svc); -} - -template -inline bool has_service(execution_context& e) -{ - // Check that Service meets the necessary type requirements. - (void)static_cast(static_cast(0)); - - return e.service_registry_->template has_service(); -} - -inline execution_context& execution_context::service::context() -{ - return owner_; -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_EXECUTION_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/impl/execution_context.ipp b/scout_sdk/asio/asio/impl/execution_context.ipp deleted file mode 100644 index c2b3b21..0000000 --- a/scout_sdk/asio/asio/impl/execution_context.ipp +++ /dev/null @@ -1,82 +0,0 @@ -// -// impl/execution_context.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_EXECUTION_CONTEXT_IPP -#define ASIO_IMPL_EXECUTION_CONTEXT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/execution_context.hpp" -#include "asio/detail/service_registry.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -execution_context::execution_context() - : service_registry_(new asio::detail::service_registry(*this)) -{ -} - -execution_context::~execution_context() -{ - shutdown(); - destroy(); - delete service_registry_; -} - -void execution_context::shutdown() -{ - service_registry_->shutdown_services(); -} - -void execution_context::destroy() -{ - service_registry_->destroy_services(); -} - -void execution_context::notify_fork( - asio::execution_context::fork_event event) -{ - service_registry_->notify_fork(event); -} - -execution_context::service::service(execution_context& owner) - : owner_(owner), - next_(0) -{ -} - -execution_context::service::~service() -{ -} - -void execution_context::service::notify_fork(execution_context::fork_event) -{ -} - -service_already_exists::service_already_exists() - : std::logic_error("Service already exists.") -{ -} - -invalid_service_owner::invalid_service_owner() - : std::logic_error("Invalid service owner.") -{ -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_EXECUTION_CONTEXT_IPP diff --git a/scout_sdk/asio/asio/impl/executor.hpp b/scout_sdk/asio/asio/impl/executor.hpp deleted file mode 100644 index 0fcf5f5..0000000 --- a/scout_sdk/asio/asio/impl/executor.hpp +++ /dev/null @@ -1,386 +0,0 @@ -// -// impl/executor.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_EXECUTOR_HPP -#define ASIO_IMPL_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/atomic_count.hpp" -#include "asio/detail/executor_op.hpp" -#include "asio/detail/global.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/recycling_allocator.hpp" -#include "asio/executor.hpp" -#include "asio/system_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if !defined(GENERATING_DOCUMENTATION) - -#if defined(ASIO_HAS_MOVE) - -// Lightweight, move-only function object wrapper. -class executor::function -{ -public: - template - explicit function(F f, const Alloc& a) - { - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - op_ = new (p.v) op(ASIO_MOVE_CAST(F)(f), a); - p.v = 0; - } - - function(function&& other) - : op_(other.op_) - { - other.op_ = 0; - } - - ~function() - { - if (op_) - op_->destroy(); - } - - void operator()() - { - if (op_) - { - detail::scheduler_operation* op = op_; - op_ = 0; - op->complete(this, asio::error_code(), 0); - } - } - -private: - detail::scheduler_operation* op_; -}; - -#else // defined(ASIO_HAS_MOVE) - -// Not so lightweight, copyable function object wrapper. -class executor::function -{ -public: - template - explicit function(const F& f, const Alloc&) - : impl_(new impl(f)) - { - } - - void operator()() - { - impl_->invoke_(impl_.get()); - } - -private: - // Base class for polymorphic function implementations. - struct impl_base - { - void (*invoke_)(impl_base*); - }; - - // Polymorphic function implementation. - template - struct impl : impl_base - { - impl(const F& f) - : function_(f) - { - invoke_ = &function::invoke; - } - - F function_; - }; - - // Helper to invoke a function. - template - static void invoke(impl_base* i) - { - static_cast*>(i)->function_(); - } - - detail::shared_ptr impl_; -}; - -#endif // defined(ASIO_HAS_MOVE) - -// Default polymorphic allocator implementation. -template -class executor::impl - : public executor::impl_base -{ -public: - typedef ASIO_REBIND_ALLOC(Allocator, impl) allocator_type; - - static impl_base* create(const Executor& e, Allocator a = Allocator()) - { - raw_mem mem(a); - impl* p = new (mem.ptr_) impl(e, a); - mem.ptr_ = 0; - return p; - } - - impl(const Executor& e, const Allocator& a) ASIO_NOEXCEPT - : impl_base(false), - ref_count_(1), - executor_(e), - allocator_(a) - { - } - - impl_base* clone() const ASIO_NOEXCEPT - { - ++ref_count_; - return const_cast(static_cast(this)); - } - - void destroy() ASIO_NOEXCEPT - { - if (--ref_count_ == 0) - { - allocator_type alloc(allocator_); - impl* p = this; - p->~impl(); - alloc.deallocate(p, 1); - } - } - - void on_work_started() ASIO_NOEXCEPT - { - executor_.on_work_started(); - } - - void on_work_finished() ASIO_NOEXCEPT - { - executor_.on_work_finished(); - } - - execution_context& context() ASIO_NOEXCEPT - { - return executor_.context(); - } - - void dispatch(ASIO_MOVE_ARG(function) f) - { - executor_.dispatch(ASIO_MOVE_CAST(function)(f), allocator_); - } - - void post(ASIO_MOVE_ARG(function) f) - { - executor_.post(ASIO_MOVE_CAST(function)(f), allocator_); - } - - void defer(ASIO_MOVE_ARG(function) f) - { - executor_.defer(ASIO_MOVE_CAST(function)(f), allocator_); - } - - type_id_result_type target_type() const ASIO_NOEXCEPT - { - return type_id(); - } - - void* target() ASIO_NOEXCEPT - { - return &executor_; - } - - const void* target() const ASIO_NOEXCEPT - { - return &executor_; - } - - bool equals(const impl_base* e) const ASIO_NOEXCEPT - { - if (this == e) - return true; - if (target_type() != e->target_type()) - return false; - return executor_ == *static_cast(e->target()); - } - -private: - mutable detail::atomic_count ref_count_; - Executor executor_; - Allocator allocator_; - - struct raw_mem - { - allocator_type allocator_; - impl* ptr_; - - explicit raw_mem(const Allocator& a) - : allocator_(a), - ptr_(allocator_.allocate(1)) - { - } - - ~raw_mem() - { - if (ptr_) - allocator_.deallocate(ptr_, 1); - } - - private: - // Disallow copying and assignment. - raw_mem(const raw_mem&); - raw_mem operator=(const raw_mem&); - }; -}; - -// Polymorphic allocator specialisation for system_executor. -template -class executor::impl - : public executor::impl_base -{ -public: - static impl_base* create(const system_executor&, - const Allocator& = Allocator()) - { - return &detail::global > >(); - } - - impl() - : impl_base(true) - { - } - - impl_base* clone() const ASIO_NOEXCEPT - { - return const_cast(static_cast(this)); - } - - void destroy() ASIO_NOEXCEPT - { - } - - void on_work_started() ASIO_NOEXCEPT - { - executor_.on_work_started(); - } - - void on_work_finished() ASIO_NOEXCEPT - { - executor_.on_work_finished(); - } - - execution_context& context() ASIO_NOEXCEPT - { - return executor_.context(); - } - - void dispatch(ASIO_MOVE_ARG(function) f) - { - executor_.dispatch(ASIO_MOVE_CAST(function)(f), allocator_); - } - - void post(ASIO_MOVE_ARG(function) f) - { - executor_.post(ASIO_MOVE_CAST(function)(f), allocator_); - } - - void defer(ASIO_MOVE_ARG(function) f) - { - executor_.defer(ASIO_MOVE_CAST(function)(f), allocator_); - } - - type_id_result_type target_type() const ASIO_NOEXCEPT - { - return type_id(); - } - - void* target() ASIO_NOEXCEPT - { - return &executor_; - } - - const void* target() const ASIO_NOEXCEPT - { - return &executor_; - } - - bool equals(const impl_base* e) const ASIO_NOEXCEPT - { - return this == e; - } - -private: - system_executor executor_; - Allocator allocator_; -}; - -template -executor::executor(Executor e) - : impl_(impl >::create(e)) -{ -} - -template -executor::executor(allocator_arg_t, const Allocator& a, Executor e) - : impl_(impl::create(e, a)) -{ -} - -template -void executor::dispatch(ASIO_MOVE_ARG(Function) f, - const Allocator& a) const -{ - impl_base* i = get_impl(); - if (i->fast_dispatch_) - system_executor().dispatch(ASIO_MOVE_CAST(Function)(f), a); - else - i->dispatch(function(ASIO_MOVE_CAST(Function)(f), a)); -} - -template -void executor::post(ASIO_MOVE_ARG(Function) f, - const Allocator& a) const -{ - get_impl()->post(function(ASIO_MOVE_CAST(Function)(f), a)); -} - -template -void executor::defer(ASIO_MOVE_ARG(Function) f, - const Allocator& a) const -{ - get_impl()->defer(function(ASIO_MOVE_CAST(Function)(f), a)); -} - -template -Executor* executor::target() ASIO_NOEXCEPT -{ - return impl_ && impl_->target_type() == type_id() - ? static_cast(impl_->target()) : 0; -} - -template -const Executor* executor::target() const ASIO_NOEXCEPT -{ - return impl_ && impl_->target_type() == type_id() - ? static_cast(impl_->target()) : 0; -} - -#endif // !defined(GENERATING_DOCUMENTATION) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/impl/executor.ipp b/scout_sdk/asio/asio/impl/executor.ipp deleted file mode 100644 index 4bd0dc5..0000000 --- a/scout_sdk/asio/asio/impl/executor.ipp +++ /dev/null @@ -1,38 +0,0 @@ -// -// impl/executor.ipp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_EXECUTOR_IPP -#define ASIO_IMPL_EXECUTOR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -bad_executor::bad_executor() ASIO_NOEXCEPT -{ -} - -const char* bad_executor::what() const ASIO_NOEXCEPT_OR_NOTHROW -{ - return "bad executor"; -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_EXECUTOR_IPP diff --git a/scout_sdk/asio/asio/impl/handler_alloc_hook.ipp b/scout_sdk/asio/asio/impl/handler_alloc_hook.ipp deleted file mode 100644 index 909ddac..0000000 --- a/scout_sdk/asio/asio/impl/handler_alloc_hook.ipp +++ /dev/null @@ -1,52 +0,0 @@ -// -// impl/handler_alloc_hook.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_HANDLER_ALLOC_HOOK_IPP -#define ASIO_IMPL_HANDLER_ALLOC_HOOK_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/thread_context.hpp" -#include "asio/detail/thread_info_base.hpp" -#include "asio/handler_alloc_hook.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -void* asio_handler_allocate(std::size_t size, ...) -{ -#if !defined(ASIO_DISABLE_SMALL_BLOCK_RECYCLING) - return detail::thread_info_base::allocate( - detail::thread_context::thread_call_stack::top(), size); -#else // !defined(ASIO_DISABLE_SMALL_BLOCK_RECYCLING) - return ::operator new(size); -#endif // !defined(ASIO_DISABLE_SMALL_BLOCK_RECYCLING) -} - -void asio_handler_deallocate(void* pointer, std::size_t size, ...) -{ -#if !defined(ASIO_DISABLE_SMALL_BLOCK_RECYCLING) - detail::thread_info_base::deallocate( - detail::thread_context::thread_call_stack::top(), pointer, size); -#else // !defined(ASIO_DISABLE_SMALL_BLOCK_RECYCLING) - (void)size; - ::operator delete(pointer); -#endif // !defined(ASIO_DISABLE_SMALL_BLOCK_RECYCLING) -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_HANDLER_ALLOC_HOOK_IPP diff --git a/scout_sdk/asio/asio/impl/io_context.hpp b/scout_sdk/asio/asio/impl/io_context.hpp deleted file mode 100644 index eaf580d..0000000 --- a/scout_sdk/asio/asio/impl/io_context.hpp +++ /dev/null @@ -1,343 +0,0 @@ -// -// impl/io_context.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_IO_CONTEXT_HPP -#define ASIO_IMPL_IO_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/completion_handler.hpp" -#include "asio/detail/executor_op.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/recycling_allocator.hpp" -#include "asio/detail/service_registry.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -inline Service& use_service(io_context& ioc) -{ - // Check that Service meets the necessary type requirements. - (void)static_cast(static_cast(0)); - (void)static_cast(&Service::id); - - return ioc.service_registry_->template use_service(ioc); -} - -template <> -inline detail::io_context_impl& use_service( - io_context& ioc) -{ - return ioc.impl_; -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_io_context.hpp" -#else -# include "asio/detail/scheduler.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -inline io_context::executor_type -io_context::get_executor() ASIO_NOEXCEPT -{ - return executor_type(*this); -} - -#if defined(ASIO_HAS_CHRONO) - -template -std::size_t io_context::run_for( - const chrono::duration& rel_time) -{ - return this->run_until(chrono::steady_clock::now() + rel_time); -} - -template -std::size_t io_context::run_until( - const chrono::time_point& abs_time) -{ - std::size_t n = 0; - while (this->run_one_until(abs_time)) - if (n != (std::numeric_limits::max)()) - ++n; - return n; -} - -template -std::size_t io_context::run_one_for( - const chrono::duration& rel_time) -{ - return this->run_one_until(chrono::steady_clock::now() + rel_time); -} - -template -std::size_t io_context::run_one_until( - const chrono::time_point& abs_time) -{ - typename Clock::time_point now = Clock::now(); - while (now < abs_time) - { - typename Clock::duration rel_time = abs_time - now; - if (rel_time > chrono::seconds(1)) - rel_time = chrono::seconds(1); - - asio::error_code ec; - std::size_t s = impl_.wait_one( - static_cast(chrono::duration_cast< - chrono::microseconds>(rel_time).count()), ec); - asio::detail::throw_error(ec); - - if (s || impl_.stopped()) - return s; - - now = Clock::now(); - } - - return 0; -} - -#endif // defined(ASIO_HAS_CHRONO) - -#if !defined(ASIO_NO_DEPRECATED) - -inline void io_context::reset() -{ - restart(); -} - -template -ASIO_INITFN_RESULT_TYPE(LegacyCompletionHandler, void ()) -io_context::dispatch(ASIO_MOVE_ARG(LegacyCompletionHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a LegacyCompletionHandler. - ASIO_LEGACY_COMPLETION_HANDLER_CHECK( - LegacyCompletionHandler, handler) type_check; - - async_completion init(handler); - - if (impl_.can_dispatch()) - { - detail::fenced_block b(detail::fenced_block::full); - asio_handler_invoke_helpers::invoke( - init.completion_handler, init.completion_handler); - } - else - { - // Allocate and construct an operation to wrap the handler. - typedef detail::completion_handler< - typename handler_type::type> op; - typename op::ptr p = { detail::addressof(init.completion_handler), - op::ptr::allocate(init.completion_handler), 0 }; - p.p = new (p.v) op(init.completion_handler); - - ASIO_HANDLER_CREATION((*this, *p.p, - "io_context", this, 0, "dispatch")); - - impl_.do_dispatch(p.p); - p.v = p.p = 0; - } - - return init.result.get(); -} - -template -ASIO_INITFN_RESULT_TYPE(LegacyCompletionHandler, void ()) -io_context::post(ASIO_MOVE_ARG(LegacyCompletionHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a LegacyCompletionHandler. - ASIO_LEGACY_COMPLETION_HANDLER_CHECK( - LegacyCompletionHandler, handler) type_check; - - async_completion init(handler); - - bool is_continuation = - asio_handler_cont_helpers::is_continuation(init.completion_handler); - - // Allocate and construct an operation to wrap the handler. - typedef detail::completion_handler< - typename handler_type::type> op; - typename op::ptr p = { detail::addressof(init.completion_handler), - op::ptr::allocate(init.completion_handler), 0 }; - p.p = new (p.v) op(init.completion_handler); - - ASIO_HANDLER_CREATION((*this, *p.p, - "io_context", this, 0, "post")); - - impl_.post_immediate_completion(p.p, is_continuation); - p.v = p.p = 0; - - return init.result.get(); -} - -template -#if defined(GENERATING_DOCUMENTATION) -unspecified -#else -inline detail::wrapped_handler -#endif -io_context::wrap(Handler handler) -{ - return detail::wrapped_handler(*this, handler); -} - -#endif // !defined(ASIO_NO_DEPRECATED) - -inline io_context& -io_context::executor_type::context() const ASIO_NOEXCEPT -{ - return io_context_; -} - -inline void -io_context::executor_type::on_work_started() const ASIO_NOEXCEPT -{ - io_context_.impl_.work_started(); -} - -inline void -io_context::executor_type::on_work_finished() const ASIO_NOEXCEPT -{ - io_context_.impl_.work_finished(); -} - -template -void io_context::executor_type::dispatch( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - // Invoke immediately if we are already inside the thread pool. - if (io_context_.impl_.can_dispatch()) - { - // Make a local, non-const copy of the function. - function_type tmp(ASIO_MOVE_CAST(Function)(f)); - - detail::fenced_block b(detail::fenced_block::full); - asio_handler_invoke_helpers::invoke(tmp, tmp); - return; - } - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((this->context(), *p.p, - "io_context", &this->context(), 0, "post")); - - io_context_.impl_.post_immediate_completion(p.p, false); - p.v = p.p = 0; -} - -template -void io_context::executor_type::post( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((this->context(), *p.p, - "io_context", &this->context(), 0, "post")); - - io_context_.impl_.post_immediate_completion(p.p, false); - p.v = p.p = 0; -} - -template -void io_context::executor_type::defer( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((this->context(), *p.p, - "io_context", &this->context(), 0, "defer")); - - io_context_.impl_.post_immediate_completion(p.p, true); - p.v = p.p = 0; -} - -inline bool -io_context::executor_type::running_in_this_thread() const ASIO_NOEXCEPT -{ - return io_context_.impl_.can_dispatch(); -} - -#if !defined(ASIO_NO_DEPRECATED) -inline io_context::work::work(asio::io_context& io_context) - : io_context_impl_(io_context.impl_) -{ - io_context_impl_.work_started(); -} - -inline io_context::work::work(const work& other) - : io_context_impl_(other.io_context_impl_) -{ - io_context_impl_.work_started(); -} - -inline io_context::work::~work() -{ - io_context_impl_.work_finished(); -} - -inline asio::io_context& io_context::work::get_io_context() -{ - return static_cast(io_context_impl_.context()); -} - -inline asio::io_context& io_context::work::get_io_service() -{ - return static_cast(io_context_impl_.context()); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -inline asio::io_context& io_context::service::get_io_context() -{ - return static_cast(context()); -} - -#if !defined(ASIO_NO_DEPRECATED) -inline asio::io_context& io_context::service::get_io_service() -{ - return static_cast(context()); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_IO_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/impl/io_context.ipp b/scout_sdk/asio/asio/impl/io_context.ipp deleted file mode 100644 index 7eb467d..0000000 --- a/scout_sdk/asio/asio/impl/io_context.ipp +++ /dev/null @@ -1,174 +0,0 @@ -// -// impl/io_context.ipp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_IO_CONTEXT_IPP -#define ASIO_IMPL_IO_CONTEXT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/concurrency_hint.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/scoped_ptr.hpp" -#include "asio/detail/service_registry.hpp" -#include "asio/detail/throw_error.hpp" - -#if defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_io_context.hpp" -#else -# include "asio/detail/scheduler.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -io_context::io_context() - : impl_(add_impl(new impl_type(*this, ASIO_CONCURRENCY_HINT_DEFAULT))) -{ -} - -io_context::io_context(int concurrency_hint) - : impl_(add_impl(new impl_type(*this, concurrency_hint == 1 - ? ASIO_CONCURRENCY_HINT_1 : concurrency_hint))) -{ -} - -io_context::impl_type& io_context::add_impl(io_context::impl_type* impl) -{ - asio::detail::scoped_ptr scoped_impl(impl); - asio::add_service(*this, scoped_impl.get()); - return *scoped_impl.release(); -} - -io_context::~io_context() -{ -} - -io_context::count_type io_context::run() -{ - asio::error_code ec; - count_type s = impl_.run(ec); - asio::detail::throw_error(ec); - return s; -} - -#if !defined(ASIO_NO_DEPRECATED) -io_context::count_type io_context::run(asio::error_code& ec) -{ - return impl_.run(ec); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -io_context::count_type io_context::run_one() -{ - asio::error_code ec; - count_type s = impl_.run_one(ec); - asio::detail::throw_error(ec); - return s; -} - -#if !defined(ASIO_NO_DEPRECATED) -io_context::count_type io_context::run_one(asio::error_code& ec) -{ - return impl_.run_one(ec); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -io_context::count_type io_context::poll() -{ - asio::error_code ec; - count_type s = impl_.poll(ec); - asio::detail::throw_error(ec); - return s; -} - -#if !defined(ASIO_NO_DEPRECATED) -io_context::count_type io_context::poll(asio::error_code& ec) -{ - return impl_.poll(ec); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -io_context::count_type io_context::poll_one() -{ - asio::error_code ec; - count_type s = impl_.poll_one(ec); - asio::detail::throw_error(ec); - return s; -} - -#if !defined(ASIO_NO_DEPRECATED) -io_context::count_type io_context::poll_one(asio::error_code& ec) -{ - return impl_.poll_one(ec); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -void io_context::stop() -{ - impl_.stop(); -} - -bool io_context::stopped() const -{ - return impl_.stopped(); -} - -void io_context::restart() -{ - impl_.restart(); -} - -io_context::service::service(asio::io_context& owner) - : execution_context::service(owner) -{ -} - -io_context::service::~service() -{ -} - -void io_context::service::shutdown() -{ -#if !defined(ASIO_NO_DEPRECATED) - shutdown_service(); -#endif // !defined(ASIO_NO_DEPRECATED) -} - -#if !defined(ASIO_NO_DEPRECATED) -void io_context::service::shutdown_service() -{ -} -#endif // !defined(ASIO_NO_DEPRECATED) - -void io_context::service::notify_fork(io_context::fork_event ev) -{ -#if !defined(ASIO_NO_DEPRECATED) - fork_service(ev); -#else // !defined(ASIO_NO_DEPRECATED) - (void)ev; -#endif // !defined(ASIO_NO_DEPRECATED) -} - -#if !defined(ASIO_NO_DEPRECATED) -void io_context::service::fork_service(io_context::fork_event) -{ -} -#endif // !defined(ASIO_NO_DEPRECATED) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_IO_CONTEXT_IPP diff --git a/scout_sdk/asio/asio/impl/post.hpp b/scout_sdk/asio/asio/impl/post.hpp deleted file mode 100644 index 5538953..0000000 --- a/scout_sdk/asio/asio/impl/post.hpp +++ /dev/null @@ -1,77 +0,0 @@ -// -// impl/post.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_POST_HPP -#define ASIO_IMPL_POST_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/detail/work_dispatcher.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) post( - ASIO_MOVE_ARG(CompletionToken) token) -{ - typedef ASIO_HANDLER_TYPE(CompletionToken, void()) handler; - - async_completion init(token); - - typename associated_executor::type ex( - (get_associated_executor)(init.completion_handler)); - - typename associated_allocator::type alloc( - (get_associated_allocator)(init.completion_handler)); - - ex.post(ASIO_MOVE_CAST(handler)(init.completion_handler), alloc); - - return init.result.get(); -} - -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) post( - const Executor& ex, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type*) -{ - typedef ASIO_HANDLER_TYPE(CompletionToken, void()) handler; - - async_completion init(token); - - typename associated_allocator::type alloc( - (get_associated_allocator)(init.completion_handler)); - - ex.post(detail::work_dispatcher(init.completion_handler), alloc); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) post( - ExecutionContext& ctx, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type*) -{ - return (post)(ctx.get_executor(), - ASIO_MOVE_CAST(CompletionToken)(token)); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_POST_HPP diff --git a/scout_sdk/asio/asio/impl/read.hpp b/scout_sdk/asio/asio/impl/read.hpp deleted file mode 100644 index 603a7a9..0000000 --- a/scout_sdk/asio/asio/impl/read.hpp +++ /dev/null @@ -1,715 +0,0 @@ -// -// impl/read.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_READ_HPP -#define ASIO_IMPL_READ_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/buffer.hpp" -#include "asio/completion_condition.hpp" -#include "asio/detail/array_fwd.hpp" -#include "asio/detail/base_from_completion_cond.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/consuming_buffers.hpp" -#include "asio/detail/dependent_type.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - template - std::size_t read_buffer_sequence(SyncReadStream& s, - const MutableBufferSequence& buffers, const MutableBufferIterator&, - CompletionCondition completion_condition, asio::error_code& ec) - { - ec = asio::error_code(); - asio::detail::consuming_buffers tmp(buffers); - while (!tmp.empty()) - { - if (std::size_t max_size = detail::adapt_completion_condition_result( - completion_condition(ec, tmp.total_consumed()))) - tmp.consume(s.read_some(tmp.prepare(max_size), ec)); - else - break; - } - return tmp.total_consumed();; - } -} // namespace detail - -template -std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_mutable_buffer_sequence::value - >::type*) -{ - return detail::read_buffer_sequence(s, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, ec); -} - -template -inline std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - typename enable_if< - is_mutable_buffer_sequence::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = read(s, buffers, transfer_all(), ec); - asio::detail::throw_error(ec, "read"); - return bytes_transferred; -} - -template -inline std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - asio::error_code& ec, - typename enable_if< - is_mutable_buffer_sequence::value - >::type*) -{ - return read(s, buffers, transfer_all(), ec); -} - -template -inline std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, - typename enable_if< - is_mutable_buffer_sequence::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = read(s, buffers, completion_condition, ec); - asio::detail::throw_error(ec, "read"); - return bytes_transferred; -} - -template -std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - typename decay::type b( - ASIO_MOVE_CAST(DynamicBuffer)(buffers)); - - ec = asio::error_code(); - std::size_t total_transferred = 0; - std::size_t max_size = detail::adapt_completion_condition_result( - completion_condition(ec, total_transferred)); - std::size_t bytes_available = std::min( - std::max(512, b.capacity() - b.size()), - std::min(max_size, b.max_size() - b.size())); - while (bytes_available > 0) - { - std::size_t bytes_transferred = s.read_some(b.prepare(bytes_available), ec); - b.commit(bytes_transferred); - total_transferred += bytes_transferred; - max_size = detail::adapt_completion_condition_result( - completion_condition(ec, total_transferred)); - bytes_available = std::min( - std::max(512, b.capacity() - b.size()), - std::min(max_size, b.max_size() - b.size())); - } - return total_transferred; -} - -template -inline std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = read(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), transfer_all(), ec); - asio::detail::throw_error(ec, "read"); - return bytes_transferred; -} - -template -inline std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - return read(s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - transfer_all(), ec); -} - -template -inline std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = read(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), - completion_condition, ec); - asio::detail::throw_error(ec, "read"); - return bytes_transferred; -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -template -inline std::size_t read(SyncReadStream& s, - asio::basic_streambuf& b, - CompletionCondition completion_condition, asio::error_code& ec) -{ - return read(s, basic_streambuf_ref(b), completion_condition, ec); -} - -template -inline std::size_t read(SyncReadStream& s, - asio::basic_streambuf& b) -{ - return read(s, basic_streambuf_ref(b)); -} - -template -inline std::size_t read(SyncReadStream& s, - asio::basic_streambuf& b, - asio::error_code& ec) -{ - return read(s, basic_streambuf_ref(b), ec); -} - -template -inline std::size_t read(SyncReadStream& s, - asio::basic_streambuf& b, - CompletionCondition completion_condition) -{ - return read(s, basic_streambuf_ref(b), completion_condition); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -namespace detail -{ - template - class read_op - : detail::base_from_completion_cond - { - public: - read_op(AsyncReadStream& stream, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, ReadHandler& handler) - : detail::base_from_completion_cond< - CompletionCondition>(completion_condition), - stream_(stream), - buffers_(buffers), - start_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_op(const read_op& other) - : detail::base_from_completion_cond(other), - stream_(other.stream_), - buffers_(other.buffers_), - start_(other.start_), - handler_(other.handler_) - { - } - - read_op(read_op&& other) - : detail::base_from_completion_cond(other), - stream_(other.stream_), - buffers_(other.buffers_), - start_(other.start_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - std::size_t max_size; - switch (start_ = start) - { - case 1: - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - do - { - stream_.async_read_some(buffers_.prepare(max_size), - ASIO_MOVE_CAST(read_op)(*this)); - return; default: - buffers_.consume(bytes_transferred); - if ((!ec && bytes_transferred == 0) || buffers_.empty()) - break; - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - } while (max_size > 0); - - handler_(ec, buffers_.total_consumed()); - } - } - - //private: - AsyncReadStream& stream_; - asio::detail::consuming_buffers buffers_; - int start_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void start_read_buffer_sequence_op(AsyncReadStream& stream, - const MutableBufferSequence& buffers, const MutableBufferIterator&, - CompletionCondition completion_condition, ReadHandler& handler) - { - detail::read_op( - stream, buffers, completion_condition, handler)( - asio::error_code(), 0, 1); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_mutable_buffer_sequence::value - >::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::start_read_buffer_sequence_op(s, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, - init.completion_handler); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_mutable_buffer_sequence::value - >::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::start_read_buffer_sequence_op(s, buffers, - asio::buffer_sequence_begin(buffers), transfer_all(), - init.completion_handler); - - return init.result.get(); -} - -namespace detail -{ - template - class read_dynbuf_op - : detail::base_from_completion_cond - { - public: - template - read_dynbuf_op(AsyncReadStream& stream, - ASIO_MOVE_ARG(BufferSequence) buffers, - CompletionCondition completion_condition, ReadHandler& handler) - : detail::base_from_completion_cond< - CompletionCondition>(completion_condition), - stream_(stream), - buffers_(ASIO_MOVE_CAST(BufferSequence)(buffers)), - start_(0), - total_transferred_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_dynbuf_op(const read_dynbuf_op& other) - : detail::base_from_completion_cond(other), - stream_(other.stream_), - buffers_(other.buffers_), - start_(other.start_), - total_transferred_(other.total_transferred_), - handler_(other.handler_) - { - } - - read_dynbuf_op(read_dynbuf_op&& other) - : detail::base_from_completion_cond(other), - stream_(other.stream_), - buffers_(ASIO_MOVE_CAST(DynamicBuffer)(other.buffers_)), - start_(other.start_), - total_transferred_(other.total_transferred_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - std::size_t max_size, bytes_available; - switch (start_ = start) - { - case 1: - max_size = this->check_for_completion(ec, total_transferred_); - bytes_available = std::min( - std::max(512, - buffers_.capacity() - buffers_.size()), - std::min(max_size, - buffers_.max_size() - buffers_.size())); - for (;;) - { - stream_.async_read_some(buffers_.prepare(bytes_available), - ASIO_MOVE_CAST(read_dynbuf_op)(*this)); - return; default: - total_transferred_ += bytes_transferred; - buffers_.commit(bytes_transferred); - max_size = this->check_for_completion(ec, total_transferred_); - bytes_available = std::min( - std::max(512, - buffers_.capacity() - buffers_.size()), - std::min(max_size, - buffers_.max_size() - buffers_.size())); - if ((!ec && bytes_transferred == 0) || bytes_available == 0) - break; - } - - handler_(ec, static_cast(total_transferred_)); - } - } - - //private: - AsyncReadStream& stream_; - DynamicBuffer buffers_; - int start_; - std::size_t total_transferred_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_dynbuf_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_dynbuf_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_dynbuf_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_dynbuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_dynbuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_dynbuf_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_dynbuf_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_dynbuf_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_dynbuf_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - return async_read(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), - transfer_all(), ASIO_MOVE_CAST(ReadHandler)(handler)); -} - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::read_dynbuf_op::type, - CompletionCondition, ASIO_HANDLER_TYPE( - ReadHandler, void (asio::error_code, std::size_t))>( - s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - completion_condition, init.completion_handler)( - asio::error_code(), 0, 1); - - return init.result.get(); -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, basic_streambuf& b, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - return async_read(s, basic_streambuf_ref(b), - ASIO_MOVE_CAST(ReadHandler)(handler)); -} - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, basic_streambuf& b, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - return async_read(s, basic_streambuf_ref(b), - completion_condition, ASIO_MOVE_CAST(ReadHandler)(handler)); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_READ_HPP diff --git a/scout_sdk/asio/asio/impl/read_at.hpp b/scout_sdk/asio/asio/impl/read_at.hpp deleted file mode 100644 index d736d4d..0000000 --- a/scout_sdk/asio/asio/impl/read_at.hpp +++ /dev/null @@ -1,640 +0,0 @@ -// -// impl/read_at.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_READ_AT_HPP -#define ASIO_IMPL_READ_AT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/buffer.hpp" -#include "asio/completion_condition.hpp" -#include "asio/detail/array_fwd.hpp" -#include "asio/detail/base_from_completion_cond.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/consuming_buffers.hpp" -#include "asio/detail/dependent_type.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - template - std::size_t read_at_buffer_sequence(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - const MutableBufferIterator&, CompletionCondition completion_condition, - asio::error_code& ec) - { - ec = asio::error_code(); - asio::detail::consuming_buffers tmp(buffers); - while (!tmp.empty()) - { - if (std::size_t max_size = detail::adapt_completion_condition_result( - completion_condition(ec, tmp.total_consumed()))) - { - tmp.consume(d.read_some_at(offset + tmp.total_consumed(), - tmp.prepare(max_size), ec)); - } - else - break; - } - return tmp.total_consumed();; - } -} // namespace detail - -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec) -{ - return detail::read_at_buffer_sequence(d, offset, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, ec); -} - -template -inline std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_at( - d, offset, buffers, transfer_all(), ec); - asio::detail::throw_error(ec, "read_at"); - return bytes_transferred; -} - -template -inline std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - asio::error_code& ec) -{ - return read_at(d, offset, buffers, transfer_all(), ec); -} - -template -inline std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - CompletionCondition completion_condition) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_at( - d, offset, buffers, completion_condition, ec); - asio::detail::throw_error(ec, "read_at"); - return bytes_transferred; -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, asio::basic_streambuf& b, - CompletionCondition completion_condition, asio::error_code& ec) -{ - ec = asio::error_code(); - std::size_t total_transferred = 0; - std::size_t max_size = detail::adapt_completion_condition_result( - completion_condition(ec, total_transferred)); - std::size_t bytes_available = read_size_helper(b, max_size); - while (bytes_available > 0) - { - std::size_t bytes_transferred = d.read_some_at( - offset + total_transferred, b.prepare(bytes_available), ec); - b.commit(bytes_transferred); - total_transferred += bytes_transferred; - max_size = detail::adapt_completion_condition_result( - completion_condition(ec, total_transferred)); - bytes_available = read_size_helper(b, max_size); - } - return total_transferred; -} - -template -inline std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, asio::basic_streambuf& b) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_at( - d, offset, b, transfer_all(), ec); - asio::detail::throw_error(ec, "read_at"); - return bytes_transferred; -} - -template -inline std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, asio::basic_streambuf& b, - asio::error_code& ec) -{ - return read_at(d, offset, b, transfer_all(), ec); -} - -template -inline std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, asio::basic_streambuf& b, - CompletionCondition completion_condition) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_at( - d, offset, b, completion_condition, ec); - asio::detail::throw_error(ec, "read_at"); - return bytes_transferred; -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -namespace detail -{ - template - class read_at_op - : detail::base_from_completion_cond - { - public: - read_at_op(AsyncRandomAccessReadDevice& device, - uint64_t offset, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, ReadHandler& handler) - : detail::base_from_completion_cond< - CompletionCondition>(completion_condition), - device_(device), - offset_(offset), - buffers_(buffers), - start_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_at_op(const read_at_op& other) - : detail::base_from_completion_cond(other), - device_(other.device_), - offset_(other.offset_), - buffers_(other.buffers_), - start_(other.start_), - handler_(other.handler_) - { - } - - read_at_op(read_at_op&& other) - : detail::base_from_completion_cond(other), - device_(other.device_), - offset_(other.offset_), - buffers_(other.buffers_), - start_(other.start_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - std::size_t max_size; - switch (start_ = start) - { - case 1: - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - do - { - device_.async_read_some_at( - offset_ + buffers_.total_consumed(), buffers_.prepare(max_size), - ASIO_MOVE_CAST(read_at_op)(*this)); - return; default: - buffers_.consume(bytes_transferred); - if ((!ec && bytes_transferred == 0) || buffers_.empty()) - break; - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - } while (max_size > 0); - - handler_(ec, buffers_.total_consumed()); - } - } - - //private: - AsyncRandomAccessReadDevice& device_; - uint64_t offset_; - asio::detail::consuming_buffers buffers_; - int start_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_at_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_at_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_at_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_at_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_at_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void start_read_at_buffer_sequence_op(AsyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - const MutableBufferIterator&, CompletionCondition completion_condition, - ReadHandler& handler) - { - detail::read_at_op( - d, offset, buffers, completion_condition, handler)( - asio::error_code(), 0, 1); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_at_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_at_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_at_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_at_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::start_read_at_buffer_sequence_op(d, offset, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, - init.completion_handler); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::start_read_at_buffer_sequence_op(d, offset, buffers, - asio::buffer_sequence_begin(buffers), transfer_all(), - init.completion_handler); - - return init.result.get(); -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -namespace detail -{ - template - class read_at_streambuf_op - : detail::base_from_completion_cond - { - public: - read_at_streambuf_op(AsyncRandomAccessReadDevice& device, - uint64_t offset, basic_streambuf& streambuf, - CompletionCondition completion_condition, ReadHandler& handler) - : detail::base_from_completion_cond< - CompletionCondition>(completion_condition), - device_(device), - offset_(offset), - streambuf_(streambuf), - start_(0), - total_transferred_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_at_streambuf_op(const read_at_streambuf_op& other) - : detail::base_from_completion_cond(other), - device_(other.device_), - offset_(other.offset_), - streambuf_(other.streambuf_), - start_(other.start_), - total_transferred_(other.total_transferred_), - handler_(other.handler_) - { - } - - read_at_streambuf_op(read_at_streambuf_op&& other) - : detail::base_from_completion_cond(other), - device_(other.device_), - offset_(other.offset_), - streambuf_(other.streambuf_), - start_(other.start_), - total_transferred_(other.total_transferred_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - std::size_t max_size, bytes_available; - switch (start_ = start) - { - case 1: - max_size = this->check_for_completion(ec, total_transferred_); - bytes_available = read_size_helper(streambuf_, max_size); - for (;;) - { - device_.async_read_some_at(offset_ + total_transferred_, - streambuf_.prepare(bytes_available), - ASIO_MOVE_CAST(read_at_streambuf_op)(*this)); - return; default: - total_transferred_ += bytes_transferred; - streambuf_.commit(bytes_transferred); - max_size = this->check_for_completion(ec, total_transferred_); - bytes_available = read_size_helper(streambuf_, max_size); - if ((!ec && bytes_transferred == 0) || bytes_available == 0) - break; - } - - handler_(ec, static_cast(total_transferred_)); - } - } - - //private: - AsyncRandomAccessReadDevice& device_; - uint64_t offset_; - asio::basic_streambuf& streambuf_; - int start_; - std::size_t total_transferred_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_at_streambuf_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_at_streambuf_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_at_streambuf_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_at_streambuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_at_streambuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_at_streambuf_op, - Allocator1> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_at_streambuf_op& h, - const Allocator1& a = Allocator1()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_at_streambuf_op, - Executor1> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_at_streambuf_op& h, - const Executor1& ex = Executor1()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, - uint64_t offset, asio::basic_streambuf& b, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::read_at_streambuf_op( - d, offset, b, completion_condition, init.completion_handler)( - asio::error_code(), 0, 1); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, - uint64_t offset, asio::basic_streambuf& b, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::read_at_streambuf_op( - d, offset, b, transfer_all(), init.completion_handler)( - asio::error_code(), 0, 1); - - return init.result.get(); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_READ_AT_HPP diff --git a/scout_sdk/asio/asio/impl/read_until.hpp b/scout_sdk/asio/asio/impl/read_until.hpp deleted file mode 100644 index 1f39e19..0000000 --- a/scout_sdk/asio/asio/impl/read_until.hpp +++ /dev/null @@ -1,1500 +0,0 @@ -// -// impl/read_until.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_READ_UNTIL_HPP -#define ASIO_IMPL_READ_UNTIL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include -#include -#include -#include -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/buffer.hpp" -#include "asio/buffers_iterator.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/limits.hpp" -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -template -inline std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, char delim) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_until(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), delim, ec); - asio::detail::throw_error(ec, "read_until"); - return bytes_transferred; -} - -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - char delim, asio::error_code& ec) -{ - typename decay::type b( - ASIO_MOVE_CAST(DynamicBuffer)(buffers)); - - std::size_t search_position = 0; - for (;;) - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = b.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position; - iterator end = iterator::end(data_buffers); - - // Look for a match. - iterator iter = std::find(start_pos, end, delim); - if (iter != end) - { - // Found a match. We're done. - ec = asio::error_code(); - return iter - begin + 1; - } - else - { - // No match. Next search can start with the new data. - search_position = end - begin; - } - - // Check if buffer is full. - if (b.size() == b.max_size()) - { - ec = error::not_found; - return 0; - } - - // Need more data. - std::size_t bytes_to_read = std::min( - std::max(512, b.capacity() - b.size()), - std::min(65536, b.max_size() - b.size())); - b.commit(s.read_some(b.prepare(bytes_to_read), ec)); - if (ec) - return 0; - } -} - -template -inline std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_STRING_VIEW_PARAM delim) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_until(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), delim, ec); - asio::detail::throw_error(ec, "read_until"); - return bytes_transferred; -} - -namespace detail -{ - // Algorithm that finds a subsequence of equal values in a sequence. Returns - // (iterator,true) if a full match was found, in which case the iterator - // points to the beginning of the match. Returns (iterator,false) if a - // partial match was found at the end of the first sequence, in which case - // the iterator points to the beginning of the partial match. Returns - // (last1,false) if no full or partial match was found. - template - std::pair partial_search( - Iterator1 first1, Iterator1 last1, Iterator2 first2, Iterator2 last2) - { - for (Iterator1 iter1 = first1; iter1 != last1; ++iter1) - { - Iterator1 test_iter1 = iter1; - Iterator2 test_iter2 = first2; - for (;; ++test_iter1, ++test_iter2) - { - if (test_iter2 == last2) - return std::make_pair(iter1, true); - if (test_iter1 == last1) - { - if (test_iter2 != first2) - return std::make_pair(iter1, false); - else - break; - } - if (*test_iter1 != *test_iter2) - break; - } - } - return std::make_pair(last1, false); - } -} // namespace detail - -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_STRING_VIEW_PARAM delim, asio::error_code& ec) -{ - typename decay::type b( - ASIO_MOVE_CAST(DynamicBuffer)(buffers)); - - std::size_t search_position = 0; - for (;;) - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = b.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position; - iterator end = iterator::end(data_buffers); - - // Look for a match. - std::pair result = detail::partial_search( - start_pos, end, delim.begin(), delim.end()); - if (result.first != end) - { - if (result.second) - { - // Full match. We're done. - ec = asio::error_code(); - return result.first - begin + delim.length(); - } - else - { - // Partial match. Next search needs to start from beginning of match. - search_position = result.first - begin; - } - } - else - { - // No match. Next search can start with the new data. - search_position = end - begin; - } - - // Check if buffer is full. - if (b.size() == b.max_size()) - { - ec = error::not_found; - return 0; - } - - // Need more data. - std::size_t bytes_to_read = std::min( - std::max(512, b.capacity() - b.size()), - std::min(65536, b.max_size() - b.size())); - b.commit(s.read_some(b.prepare(bytes_to_read), ec)); - if (ec) - return 0; - } -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if defined(ASIO_HAS_BOOST_REGEX) - -template -inline std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - const boost::regex& expr) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_until(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), expr, ec); - asio::detail::throw_error(ec, "read_until"); - return bytes_transferred; -} - -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - const boost::regex& expr, asio::error_code& ec) -{ - typename decay::type b( - ASIO_MOVE_CAST(DynamicBuffer)(buffers)); - - std::size_t search_position = 0; - for (;;) - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = b.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position; - iterator end = iterator::end(data_buffers); - - // Look for a match. - boost::match_results >::allocator_type> - match_results; - if (regex_search(start_pos, end, match_results, expr, - boost::match_default | boost::match_partial)) - { - if (match_results[0].matched) - { - // Full match. We're done. - ec = asio::error_code(); - return match_results[0].second - begin; - } - else - { - // Partial match. Next search needs to start from beginning of match. - search_position = match_results[0].first - begin; - } - } - else - { - // No match. Next search can start with the new data. - search_position = end - begin; - } - - // Check if buffer is full. - if (b.size() == b.max_size()) - { - ec = error::not_found; - return 0; - } - - // Need more data. - std::size_t bytes_to_read = read_size_helper(b, 65536); - b.commit(s.read_some(b.prepare(bytes_to_read), ec)); - if (ec) - return 0; - } -} - -#endif // defined(ASIO_HAS_BOOST_REGEX) - -template -inline std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - MatchCondition match_condition, - typename enable_if::value>::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = read_until(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), - match_condition, ec); - asio::detail::throw_error(ec, "read_until"); - return bytes_transferred; -} - -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - MatchCondition match_condition, asio::error_code& ec, - typename enable_if::value>::type*) -{ - typename decay::type b( - ASIO_MOVE_CAST(DynamicBuffer)(buffers)); - - std::size_t search_position = 0; - for (;;) - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = b.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position; - iterator end = iterator::end(data_buffers); - - // Look for a match. - std::pair result = match_condition(start_pos, end); - if (result.second) - { - // Full match. We're done. - ec = asio::error_code(); - return result.first - begin; - } - else if (result.first != end) - { - // Partial match. Next search needs to start from beginning of match. - search_position = result.first - begin; - } - else - { - // No match. Next search can start with the new data. - search_position = end - begin; - } - - // Check if buffer is full. - if (b.size() == b.max_size()) - { - ec = error::not_found; - return 0; - } - - // Need more data. - std::size_t bytes_to_read = std::min( - std::max(512, b.capacity() - b.size()), - std::min(65536, b.max_size() - b.size())); - b.commit(s.read_some(b.prepare(bytes_to_read), ec)); - if (ec) - return 0; - } -} - -#if !defined(ASIO_NO_IOSTREAM) - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, char delim) -{ - return read_until(s, basic_streambuf_ref(b), delim); -} - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, char delim, - asio::error_code& ec) -{ - return read_until(s, basic_streambuf_ref(b), delim, ec); -} - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, - ASIO_STRING_VIEW_PARAM delim) -{ - return read_until(s, basic_streambuf_ref(b), delim); -} - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, - ASIO_STRING_VIEW_PARAM delim, asio::error_code& ec) -{ - return read_until(s, basic_streambuf_ref(b), delim, ec); -} - -#if defined(ASIO_HAS_BOOST_REGEX) - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, const boost::regex& expr) -{ - return read_until(s, basic_streambuf_ref(b), expr); -} - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, const boost::regex& expr, - asio::error_code& ec) -{ - return read_until(s, basic_streambuf_ref(b), expr, ec); -} - -#endif // defined(ASIO_HAS_BOOST_REGEX) - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, MatchCondition match_condition, - typename enable_if::value>::type*) -{ - return read_until(s, basic_streambuf_ref(b), match_condition); -} - -template -inline std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, - MatchCondition match_condition, asio::error_code& ec, - typename enable_if::value>::type*) -{ - return read_until(s, basic_streambuf_ref(b), match_condition, ec); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -namespace detail -{ - template - class read_until_delim_op - { - public: - template - read_until_delim_op(AsyncReadStream& stream, - ASIO_MOVE_ARG(BufferSequence) buffers, - char delim, ReadHandler& handler) - : stream_(stream), - buffers_(ASIO_MOVE_CAST(BufferSequence)(buffers)), - delim_(delim), - start_(0), - search_position_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_until_delim_op(const read_until_delim_op& other) - : stream_(other.stream_), - buffers_(other.buffers_), - delim_(other.delim_), - start_(other.start_), - search_position_(other.search_position_), - handler_(other.handler_) - { - } - - read_until_delim_op(read_until_delim_op&& other) - : stream_(other.stream_), - buffers_(ASIO_MOVE_CAST(DynamicBuffer)(other.buffers_)), - delim_(other.delim_), - start_(other.start_), - search_position_(other.search_position_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - const std::size_t not_found = (std::numeric_limits::max)(); - std::size_t bytes_to_read; - switch (start_ = start) - { - case 1: - for (;;) - { - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type - buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = buffers_.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position_; - iterator end = iterator::end(data_buffers); - - // Look for a match. - iterator iter = std::find(start_pos, end, delim_); - if (iter != end) - { - // Found a match. We're done. - search_position_ = iter - begin + 1; - bytes_to_read = 0; - } - - // No match yet. Check if buffer is full. - else if (buffers_.size() == buffers_.max_size()) - { - search_position_ = not_found; - bytes_to_read = 0; - } - - // Need to read some more data. - else - { - // Next search can start with the new data. - search_position_ = end - begin; - bytes_to_read = std::min( - std::max(512, - buffers_.capacity() - buffers_.size()), - std::min(65536, - buffers_.max_size() - buffers_.size())); - } - } - - // Check if we're done. - if (!start && bytes_to_read == 0) - break; - - // Start a new asynchronous read operation to obtain more data. - stream_.async_read_some(buffers_.prepare(bytes_to_read), - ASIO_MOVE_CAST(read_until_delim_op)(*this)); - return; default: - buffers_.commit(bytes_transferred); - if (ec || bytes_transferred == 0) - break; - } - - const asio::error_code result_ec = - (search_position_ == not_found) - ? error::not_found : ec; - - const std::size_t result_n = - (ec || search_position_ == not_found) - ? 0 : search_position_; - - handler_(result_ec, result_n); - } - } - - //private: - AsyncReadStream& stream_; - DynamicBuffer buffers_; - char delim_; - int start_; - std::size_t search_position_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_until_delim_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_until_delim_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_until_delim_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_until_delim_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_until_delim_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_until_delim_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_until_delim_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_until_delim_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_until_delim_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - char delim, ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::read_until_delim_op::type, - ASIO_HANDLER_TYPE(ReadHandler, - void (asio::error_code, std::size_t))>( - s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - delim, init.completion_handler)(asio::error_code(), 0, 1); - - return init.result.get(); -} - -namespace detail -{ - template - class read_until_delim_string_op - { - public: - template - read_until_delim_string_op(AsyncReadStream& stream, - ASIO_MOVE_ARG(BufferSequence) buffers, - const std::string& delim, ReadHandler& handler) - : stream_(stream), - buffers_(ASIO_MOVE_CAST(BufferSequence)(buffers)), - delim_(delim), - start_(0), - search_position_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_until_delim_string_op(const read_until_delim_string_op& other) - : stream_(other.stream_), - buffers_(other.buffers_), - delim_(other.delim_), - start_(other.start_), - search_position_(other.search_position_), - handler_(other.handler_) - { - } - - read_until_delim_string_op(read_until_delim_string_op&& other) - : stream_(other.stream_), - buffers_(ASIO_MOVE_CAST(DynamicBuffer)(other.buffers_)), - delim_(ASIO_MOVE_CAST(std::string)(other.delim_)), - start_(other.start_), - search_position_(other.search_position_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - const std::size_t not_found = (std::numeric_limits::max)(); - std::size_t bytes_to_read; - switch (start_ = start) - { - case 1: - for (;;) - { - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type - buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = buffers_.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position_; - iterator end = iterator::end(data_buffers); - - // Look for a match. - std::pair result = detail::partial_search( - start_pos, end, delim_.begin(), delim_.end()); - if (result.first != end && result.second) - { - // Full match. We're done. - search_position_ = result.first - begin + delim_.length(); - bytes_to_read = 0; - } - - // No match yet. Check if buffer is full. - else if (buffers_.size() == buffers_.max_size()) - { - search_position_ = not_found; - bytes_to_read = 0; - } - - // Need to read some more data. - else - { - if (result.first != end) - { - // Partial match. Next search needs to start from beginning of - // match. - search_position_ = result.first - begin; - } - else - { - // Next search can start with the new data. - search_position_ = end - begin; - } - - bytes_to_read = std::min( - std::max(512, - buffers_.capacity() - buffers_.size()), - std::min(65536, - buffers_.max_size() - buffers_.size())); - } - } - - // Check if we're done. - if (!start && bytes_to_read == 0) - break; - - // Start a new asynchronous read operation to obtain more data. - stream_.async_read_some(buffers_.prepare(bytes_to_read), - ASIO_MOVE_CAST(read_until_delim_string_op)(*this)); - return; default: - buffers_.commit(bytes_transferred); - if (ec || bytes_transferred == 0) - break; - } - - const asio::error_code result_ec = - (search_position_ == not_found) - ? error::not_found : ec; - - const std::size_t result_n = - (ec || search_position_ == not_found) - ? 0 : search_position_; - - handler_(result_ec, result_n); - } - } - - //private: - AsyncReadStream& stream_; - DynamicBuffer buffers_; - std::string delim_; - int start_; - std::size_t search_position_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_until_delim_string_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_until_delim_string_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_until_delim_string_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_until_delim_string_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_until_delim_string_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_until_delim_string_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_until_delim_string_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_until_delim_string_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_until_delim_string_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_STRING_VIEW_PARAM delim, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::read_until_delim_string_op::type, - ASIO_HANDLER_TYPE(ReadHandler, - void (asio::error_code, std::size_t))>( - s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - static_cast(delim), - init.completion_handler)(asio::error_code(), 0, 1); - - return init.result.get(); -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if defined(ASIO_HAS_BOOST_REGEX) - -namespace detail -{ - template - class read_until_expr_op - { - public: - template - read_until_expr_op(AsyncReadStream& stream, - ASIO_MOVE_ARG(BufferSequence) buffers, - const boost::regex& expr, ReadHandler& handler) - : stream_(stream), - buffers_(ASIO_MOVE_CAST(BufferSequence)(buffers)), - expr_(expr), - start_(0), - search_position_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_until_expr_op(const read_until_expr_op& other) - : stream_(other.stream_), - buffers_(other.buffers_), - expr_(other.expr_), - start_(other.start_), - search_position_(other.search_position_), - handler_(other.handler_) - { - } - - read_until_expr_op(read_until_expr_op&& other) - : stream_(other.stream_), - buffers_(ASIO_MOVE_CAST(DynamicBuffer)(other.buffers_)), - expr_(other.expr_), - start_(other.start_), - search_position_(other.search_position_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - const std::size_t not_found = (std::numeric_limits::max)(); - std::size_t bytes_to_read; - switch (start_ = start) - { - case 1: - for (;;) - { - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type - buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = buffers_.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position_; - iterator end = iterator::end(data_buffers); - - // Look for a match. - boost::match_results >::allocator_type> - match_results; - bool match = regex_search(start_pos, end, match_results, expr_, - boost::match_default | boost::match_partial); - if (match && match_results[0].matched) - { - // Full match. We're done. - search_position_ = match_results[0].second - begin; - bytes_to_read = 0; - } - - // No match yet. Check if buffer is full. - else if (buffers_.size() == buffers_.max_size()) - { - search_position_ = not_found; - bytes_to_read = 0; - } - - // Need to read some more data. - else - { - if (match) - { - // Partial match. Next search needs to start from beginning of - // match. - search_position_ = match_results[0].first - begin; - } - else - { - // Next search can start with the new data. - search_position_ = end - begin; - } - - bytes_to_read = std::min( - std::max(512, - buffers_.capacity() - buffers_.size()), - std::min(65536, - buffers_.max_size() - buffers_.size())); - } - } - - // Check if we're done. - if (!start && bytes_to_read == 0) - break; - - // Start a new asynchronous read operation to obtain more data. - stream_.async_read_some(buffers_.prepare(bytes_to_read), - ASIO_MOVE_CAST(read_until_expr_op)(*this)); - return; default: - buffers_.commit(bytes_transferred); - if (ec || bytes_transferred == 0) - break; - } - - const asio::error_code result_ec = - (search_position_ == not_found) - ? error::not_found : ec; - - const std::size_t result_n = - (ec || search_position_ == not_found) - ? 0 : search_position_; - - handler_(result_ec, result_n); - } - } - - //private: - AsyncReadStream& stream_; - DynamicBuffer buffers_; - RegEx expr_; - int start_; - std::size_t search_position_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_until_expr_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_until_expr_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_until_expr_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_until_expr_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_until_expr_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_until_expr_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_until_expr_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_until_expr_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_until_expr_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - const boost::regex& expr, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::read_until_expr_op::type, - boost::regex, ASIO_HANDLER_TYPE(ReadHandler, - void (asio::error_code, std::size_t))>( - s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - expr, init.completion_handler)(asio::error_code(), 0, 1); - - return init.result.get(); -} - -#endif // defined(ASIO_HAS_BOOST_REGEX) - -namespace detail -{ - template - class read_until_match_op - { - public: - template - read_until_match_op(AsyncReadStream& stream, - ASIO_MOVE_ARG(BufferSequence) buffers, - MatchCondition match_condition, ReadHandler& handler) - : stream_(stream), - buffers_(ASIO_MOVE_CAST(BufferSequence)(buffers)), - match_condition_(match_condition), - start_(0), - search_position_(0), - handler_(ASIO_MOVE_CAST(ReadHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - read_until_match_op(const read_until_match_op& other) - : stream_(other.stream_), - buffers_(other.buffers_), - match_condition_(other.match_condition_), - start_(other.start_), - search_position_(other.search_position_), - handler_(other.handler_) - { - } - - read_until_match_op(read_until_match_op&& other) - : stream_(other.stream_), - buffers_(ASIO_MOVE_CAST(DynamicBuffer)(other.buffers_)), - match_condition_(other.match_condition_), - start_(other.start_), - search_position_(other.search_position_), - handler_(ASIO_MOVE_CAST(ReadHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - const std::size_t not_found = (std::numeric_limits::max)(); - std::size_t bytes_to_read; - switch (start_ = start) - { - case 1: - for (;;) - { - { - // Determine the range of the data to be searched. - typedef typename DynamicBuffer::const_buffers_type - buffers_type; - typedef buffers_iterator iterator; - buffers_type data_buffers = buffers_.data(); - iterator begin = iterator::begin(data_buffers); - iterator start_pos = begin + search_position_; - iterator end = iterator::end(data_buffers); - - // Look for a match. - std::pair result = match_condition_(start_pos, end); - if (result.second) - { - // Full match. We're done. - search_position_ = result.first - begin; - bytes_to_read = 0; - } - - // No match yet. Check if buffer is full. - else if (buffers_.size() == buffers_.max_size()) - { - search_position_ = not_found; - bytes_to_read = 0; - } - - // Need to read some more data. - else - { - if (result.first != end) - { - // Partial match. Next search needs to start from beginning of - // match. - search_position_ = result.first - begin; - } - else - { - // Next search can start with the new data. - search_position_ = end - begin; - } - - bytes_to_read = std::min( - std::max(512, - buffers_.capacity() - buffers_.size()), - std::min(65536, - buffers_.max_size() - buffers_.size())); - } - } - - // Check if we're done. - if (!start && bytes_to_read == 0) - break; - - // Start a new asynchronous read operation to obtain more data. - stream_.async_read_some(buffers_.prepare(bytes_to_read), - ASIO_MOVE_CAST(read_until_match_op)(*this)); - return; default: - buffers_.commit(bytes_transferred); - if (ec || bytes_transferred == 0) - break; - } - - const asio::error_code result_ec = - (search_position_ == not_found) - ? error::not_found : ec; - - const std::size_t result_n = - (ec || search_position_ == not_found) - ? 0 : search_position_; - - handler_(result_ec, result_n); - } - } - - //private: - AsyncReadStream& stream_; - DynamicBuffer buffers_; - MatchCondition match_condition_; - int start_; - std::size_t search_position_; - ReadHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - read_until_match_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - read_until_match_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - read_until_match_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - read_until_match_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - read_until_match_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::read_until_match_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::read_until_match_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::read_until_match_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::read_until_match_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - MatchCondition match_condition, ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if::value>::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - detail::read_until_match_op::type, - MatchCondition, ASIO_HANDLER_TYPE(ReadHandler, - void (asio::error_code, std::size_t))>( - s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - match_condition, init.completion_handler)( - asio::error_code(), 0, 1); - - return init.result.get(); -} - -#if !defined(ASIO_NO_IOSTREAM) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, - char delim, ASIO_MOVE_ARG(ReadHandler) handler) -{ - return async_read_until(s, basic_streambuf_ref(b), - delim, ASIO_MOVE_CAST(ReadHandler)(handler)); -} - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, - ASIO_STRING_VIEW_PARAM delim, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - return async_read_until(s, basic_streambuf_ref(b), - delim, ASIO_MOVE_CAST(ReadHandler)(handler)); -} - -#if defined(ASIO_HAS_BOOST_REGEX) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, const boost::regex& expr, - ASIO_MOVE_ARG(ReadHandler) handler) -{ - return async_read_until(s, basic_streambuf_ref(b), - expr, ASIO_MOVE_CAST(ReadHandler)(handler)); -} - -#endif // defined(ASIO_HAS_BOOST_REGEX) - -template -inline ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, - MatchCondition match_condition, ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if::value>::type*) -{ - return async_read_until(s, basic_streambuf_ref(b), - match_condition, ASIO_MOVE_CAST(ReadHandler)(handler)); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_READ_UNTIL_HPP diff --git a/scout_sdk/asio/asio/impl/serial_port_base.hpp b/scout_sdk/asio/asio/impl/serial_port_base.hpp deleted file mode 100644 index cdc201d..0000000 --- a/scout_sdk/asio/asio/impl/serial_port_base.hpp +++ /dev/null @@ -1,59 +0,0 @@ -// -// impl/serial_port_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_SERIAL_PORT_BASE_HPP -#define ASIO_IMPL_SERIAL_PORT_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -inline serial_port_base::baud_rate::baud_rate(unsigned int rate) - : value_(rate) -{ -} - -inline unsigned int serial_port_base::baud_rate::value() const -{ - return value_; -} - -inline serial_port_base::flow_control::type -serial_port_base::flow_control::value() const -{ - return value_; -} - -inline serial_port_base::parity::type serial_port_base::parity::value() const -{ - return value_; -} - -inline serial_port_base::stop_bits::type -serial_port_base::stop_bits::value() const -{ - return value_; -} - -inline unsigned int serial_port_base::character_size::value() const -{ - return value_; -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_SERIAL_PORT_BASE_HPP diff --git a/scout_sdk/asio/asio/impl/serial_port_base.ipp b/scout_sdk/asio/asio/impl/serial_port_base.ipp deleted file mode 100644 index 5d52ed5..0000000 --- a/scout_sdk/asio/asio/impl/serial_port_base.ipp +++ /dev/null @@ -1,554 +0,0 @@ -// -// impl/serial_port_base.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_SERIAL_PORT_BASE_IPP -#define ASIO_IMPL_SERIAL_PORT_BASE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_SERIAL_PORT) - -#include -#include "asio/error.hpp" -#include "asio/serial_port_base.hpp" -#include "asio/detail/throw_exception.hpp" - -#if defined(GENERATING_DOCUMENTATION) -# define ASIO_OPTION_STORAGE implementation_defined -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# define ASIO_OPTION_STORAGE DCB -#else -# define ASIO_OPTION_STORAGE termios -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -ASIO_SYNC_OP_VOID serial_port_base::baud_rate::store( - ASIO_OPTION_STORAGE& storage, asio::error_code& ec) const -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - storage.BaudRate = value_; -#else - speed_t baud; - switch (value_) - { - // Do POSIX-specified rates first. - case 0: baud = B0; break; - case 50: baud = B50; break; - case 75: baud = B75; break; - case 110: baud = B110; break; - case 134: baud = B134; break; - case 150: baud = B150; break; - case 200: baud = B200; break; - case 300: baud = B300; break; - case 600: baud = B600; break; - case 1200: baud = B1200; break; - case 1800: baud = B1800; break; - case 2400: baud = B2400; break; - case 4800: baud = B4800; break; - case 9600: baud = B9600; break; - case 19200: baud = B19200; break; - case 38400: baud = B38400; break; - // And now the extended ones conditionally. -# ifdef B7200 - case 7200: baud = B7200; break; -# endif -# ifdef B14400 - case 14400: baud = B14400; break; -# endif -# ifdef B57600 - case 57600: baud = B57600; break; -# endif -# ifdef B115200 - case 115200: baud = B115200; break; -# endif -# ifdef B230400 - case 230400: baud = B230400; break; -# endif -# ifdef B460800 - case 460800: baud = B460800; break; -# endif -# ifdef B500000 - case 500000: baud = B500000; break; -# endif -# ifdef B576000 - case 576000: baud = B576000; break; -# endif -# ifdef B921600 - case 921600: baud = B921600; break; -# endif -# ifdef B1000000 - case 1000000: baud = B1000000; break; -# endif -# ifdef B1152000 - case 1152000: baud = B1152000; break; -# endif -# ifdef B2000000 - case 2000000: baud = B2000000; break; -# endif -# ifdef B3000000 - case 3000000: baud = B3000000; break; -# endif -# ifdef B3500000 - case 3500000: baud = B3500000; break; -# endif -# ifdef B4000000 - case 4000000: baud = B4000000; break; -# endif - default: - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } -# if defined(_BSD_SOURCE) || defined(_DEFAULT_SOURCE) - ::cfsetspeed(&storage, baud); -# else - ::cfsetispeed(&storage, baud); - ::cfsetospeed(&storage, baud); -# endif -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID serial_port_base::baud_rate::load( - const ASIO_OPTION_STORAGE& storage, asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - value_ = storage.BaudRate; -#else - speed_t baud = ::cfgetospeed(&storage); - switch (baud) - { - // First do those specified by POSIX. - case B0: value_ = 0; break; - case B50: value_ = 50; break; - case B75: value_ = 75; break; - case B110: value_ = 110; break; - case B134: value_ = 134; break; - case B150: value_ = 150; break; - case B200: value_ = 200; break; - case B300: value_ = 300; break; - case B600: value_ = 600; break; - case B1200: value_ = 1200; break; - case B1800: value_ = 1800; break; - case B2400: value_ = 2400; break; - case B4800: value_ = 4800; break; - case B9600: value_ = 9600; break; - case B19200: value_ = 19200; break; - case B38400: value_ = 38400; break; - // Now conditionally handle a bunch of extended rates. -# ifdef B7200 - case B7200: value_ = 7200; break; -# endif -# ifdef B14400 - case B14400: value_ = 14400; break; -# endif -# ifdef B57600 - case B57600: value_ = 57600; break; -# endif -# ifdef B115200 - case B115200: value_ = 115200; break; -# endif -# ifdef B230400 - case B230400: value_ = 230400; break; -# endif -# ifdef B460800 - case B460800: value_ = 460800; break; -# endif -# ifdef B500000 - case B500000: value_ = 500000; break; -# endif -# ifdef B576000 - case B576000: value_ = 576000; break; -# endif -# ifdef B921600 - case B921600: value_ = 921600; break; -# endif -# ifdef B1000000 - case B1000000: value_ = 1000000; break; -# endif -# ifdef B1152000 - case B1152000: value_ = 1152000; break; -# endif -# ifdef B2000000 - case B2000000: value_ = 2000000; break; -# endif -# ifdef B3000000 - case B3000000: value_ = 3000000; break; -# endif -# ifdef B3500000 - case B3500000: value_ = 3500000; break; -# endif -# ifdef B4000000 - case B4000000: value_ = 4000000; break; -# endif - default: - value_ = 0; - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -serial_port_base::flow_control::flow_control( - serial_port_base::flow_control::type t) - : value_(t) -{ - if (t != none && t != software && t != hardware) - { - std::out_of_range ex("invalid flow_control value"); - asio::detail::throw_exception(ex); - } -} - -ASIO_SYNC_OP_VOID serial_port_base::flow_control::store( - ASIO_OPTION_STORAGE& storage, asio::error_code& ec) const -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - storage.fOutxCtsFlow = FALSE; - storage.fOutxDsrFlow = FALSE; - storage.fTXContinueOnXoff = TRUE; - storage.fDtrControl = DTR_CONTROL_ENABLE; - storage.fDsrSensitivity = FALSE; - storage.fOutX = FALSE; - storage.fInX = FALSE; - storage.fRtsControl = RTS_CONTROL_ENABLE; - switch (value_) - { - case none: - break; - case software: - storage.fOutX = TRUE; - storage.fInX = TRUE; - break; - case hardware: - storage.fOutxCtsFlow = TRUE; - storage.fRtsControl = RTS_CONTROL_HANDSHAKE; - break; - default: - break; - } -#else - switch (value_) - { - case none: - storage.c_iflag &= ~(IXOFF | IXON); -# if defined(_BSD_SOURCE) || defined(_DEFAULT_SOURCE) - storage.c_cflag &= ~CRTSCTS; -# elif defined(__QNXNTO__) - storage.c_cflag &= ~(IHFLOW | OHFLOW); -# endif - break; - case software: - storage.c_iflag |= IXOFF | IXON; -# if defined(_BSD_SOURCE) || defined(_DEFAULT_SOURCE) - storage.c_cflag &= ~CRTSCTS; -# elif defined(__QNXNTO__) - storage.c_cflag &= ~(IHFLOW | OHFLOW); -# endif - break; - case hardware: -# if defined(_BSD_SOURCE) || defined(_DEFAULT_SOURCE) - storage.c_iflag &= ~(IXOFF | IXON); - storage.c_cflag |= CRTSCTS; - break; -# elif defined(__QNXNTO__) - storage.c_iflag &= ~(IXOFF | IXON); - storage.c_cflag |= (IHFLOW | OHFLOW); - break; -# else - ec = asio::error::operation_not_supported; - ASIO_SYNC_OP_VOID_RETURN(ec); -# endif - default: - break; - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID serial_port_base::flow_control::load( - const ASIO_OPTION_STORAGE& storage, asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - if (storage.fOutX && storage.fInX) - { - value_ = software; - } - else if (storage.fOutxCtsFlow && storage.fRtsControl == RTS_CONTROL_HANDSHAKE) - { - value_ = hardware; - } - else - { - value_ = none; - } -#else - if (storage.c_iflag & (IXOFF | IXON)) - { - value_ = software; - } -# if defined(_BSD_SOURCE) || defined(_DEFAULT_SOURCE) - else if (storage.c_cflag & CRTSCTS) - { - value_ = hardware; - } -# elif defined(__QNXNTO__) - else if (storage.c_cflag & IHFLOW && storage.c_cflag & OHFLOW) - { - value_ = hardware; - } -# endif - else - { - value_ = none; - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -serial_port_base::parity::parity(serial_port_base::parity::type t) - : value_(t) -{ - if (t != none && t != odd && t != even) - { - std::out_of_range ex("invalid parity value"); - asio::detail::throw_exception(ex); - } -} - -ASIO_SYNC_OP_VOID serial_port_base::parity::store( - ASIO_OPTION_STORAGE& storage, asio::error_code& ec) const -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - switch (value_) - { - case none: - storage.fParity = FALSE; - storage.Parity = NOPARITY; - break; - case odd: - storage.fParity = TRUE; - storage.Parity = ODDPARITY; - break; - case even: - storage.fParity = TRUE; - storage.Parity = EVENPARITY; - break; - default: - break; - } -#else - switch (value_) - { - case none: - storage.c_iflag |= IGNPAR; - storage.c_cflag &= ~(PARENB | PARODD); - break; - case even: - storage.c_iflag &= ~(IGNPAR | PARMRK); - storage.c_iflag |= INPCK; - storage.c_cflag |= PARENB; - storage.c_cflag &= ~PARODD; - break; - case odd: - storage.c_iflag &= ~(IGNPAR | PARMRK); - storage.c_iflag |= INPCK; - storage.c_cflag |= (PARENB | PARODD); - break; - default: - break; - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID serial_port_base::parity::load( - const ASIO_OPTION_STORAGE& storage, asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - if (storage.Parity == EVENPARITY) - { - value_ = even; - } - else if (storage.Parity == ODDPARITY) - { - value_ = odd; - } - else - { - value_ = none; - } -#else - if (storage.c_cflag & PARENB) - { - if (storage.c_cflag & PARODD) - { - value_ = odd; - } - else - { - value_ = even; - } - } - else - { - value_ = none; - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -serial_port_base::stop_bits::stop_bits( - serial_port_base::stop_bits::type t) - : value_(t) -{ - if (t != one && t != onepointfive && t != two) - { - std::out_of_range ex("invalid stop_bits value"); - asio::detail::throw_exception(ex); - } -} - -ASIO_SYNC_OP_VOID serial_port_base::stop_bits::store( - ASIO_OPTION_STORAGE& storage, asio::error_code& ec) const -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - switch (value_) - { - case one: - storage.StopBits = ONESTOPBIT; - break; - case onepointfive: - storage.StopBits = ONE5STOPBITS; - break; - case two: - storage.StopBits = TWOSTOPBITS; - break; - default: - break; - } -#else - switch (value_) - { - case one: - storage.c_cflag &= ~CSTOPB; - break; - case two: - storage.c_cflag |= CSTOPB; - break; - default: - ec = asio::error::operation_not_supported; - ASIO_SYNC_OP_VOID_RETURN(ec); - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID serial_port_base::stop_bits::load( - const ASIO_OPTION_STORAGE& storage, asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - if (storage.StopBits == ONESTOPBIT) - { - value_ = one; - } - else if (storage.StopBits == ONE5STOPBITS) - { - value_ = onepointfive; - } - else if (storage.StopBits == TWOSTOPBITS) - { - value_ = two; - } - else - { - value_ = one; - } -#else - value_ = (storage.c_cflag & CSTOPB) ? two : one; -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -serial_port_base::character_size::character_size(unsigned int t) - : value_(t) -{ - if (t < 5 || t > 8) - { - std::out_of_range ex("invalid character_size value"); - asio::detail::throw_exception(ex); - } -} - -ASIO_SYNC_OP_VOID serial_port_base::character_size::store( - ASIO_OPTION_STORAGE& storage, asio::error_code& ec) const -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - storage.ByteSize = value_; -#else - storage.c_cflag &= ~CSIZE; - switch (value_) - { - case 5: storage.c_cflag |= CS5; break; - case 6: storage.c_cflag |= CS6; break; - case 7: storage.c_cflag |= CS7; break; - case 8: storage.c_cflag |= CS8; break; - default: break; - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID serial_port_base::character_size::load( - const ASIO_OPTION_STORAGE& storage, asio::error_code& ec) -{ -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - value_ = storage.ByteSize; -#else - if ((storage.c_cflag & CSIZE) == CS5) { value_ = 5; } - else if ((storage.c_cflag & CSIZE) == CS6) { value_ = 6; } - else if ((storage.c_cflag & CSIZE) == CS7) { value_ = 7; } - else if ((storage.c_cflag & CSIZE) == CS8) { value_ = 8; } - else - { - // Hmmm, use 8 for now. - value_ = 8; - } -#endif - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#undef ASIO_OPTION_STORAGE - -#endif // defined(ASIO_HAS_SERIAL_PORT) - -#endif // ASIO_IMPL_SERIAL_PORT_BASE_IPP diff --git a/scout_sdk/asio/asio/impl/spawn.hpp b/scout_sdk/asio/asio/impl/spawn.hpp deleted file mode 100644 index 5594ad9..0000000 --- a/scout_sdk/asio/asio/impl/spawn.hpp +++ /dev/null @@ -1,535 +0,0 @@ -// -// impl/spawn.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_SPAWN_HPP -#define ASIO_IMPL_SPAWN_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/async_result.hpp" -#include "asio/bind_executor.hpp" -#include "asio/detail/atomic_count.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/system_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - - template - class coro_handler - { - public: - coro_handler(basic_yield_context ctx) - : coro_(ctx.coro_.lock()), - ca_(ctx.ca_), - handler_(ctx.handler_), - ready_(0), - ec_(ctx.ec_), - value_(0) - { - } - - void operator()(T value) - { - *ec_ = asio::error_code(); - *value_ = ASIO_MOVE_CAST(T)(value); - if (--*ready_ == 0) - (*coro_)(); - } - - void operator()(asio::error_code ec, T value) - { - *ec_ = ec; - *value_ = ASIO_MOVE_CAST(T)(value); - if (--*ready_ == 0) - (*coro_)(); - } - - //private: - shared_ptr::callee_type> coro_; - typename basic_yield_context::caller_type& ca_; - Handler handler_; - atomic_count* ready_; - asio::error_code* ec_; - T* value_; - }; - - template - class coro_handler - { - public: - coro_handler(basic_yield_context ctx) - : coro_(ctx.coro_.lock()), - ca_(ctx.ca_), - handler_(ctx.handler_), - ready_(0), - ec_(ctx.ec_) - { - } - - void operator()() - { - *ec_ = asio::error_code(); - if (--*ready_ == 0) - (*coro_)(); - } - - void operator()(asio::error_code ec) - { - *ec_ = ec; - if (--*ready_ == 0) - (*coro_)(); - } - - //private: - shared_ptr::callee_type> coro_; - typename basic_yield_context::caller_type& ca_; - Handler handler_; - atomic_count* ready_; - asio::error_code* ec_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - coro_handler* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - coro_handler* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation(coro_handler*) - { - return true; - } - - template - inline void asio_handler_invoke(Function& function, - coro_handler* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - coro_handler* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - class coro_async_result - { - public: - typedef coro_handler completion_handler_type; - typedef T return_type; - - explicit coro_async_result(completion_handler_type& h) - : handler_(h), - ca_(h.ca_), - ready_(2) - { - h.ready_ = &ready_; - out_ec_ = h.ec_; - if (!out_ec_) h.ec_ = &ec_; - h.value_ = &value_; - } - - return_type get() - { - // Must not hold shared_ptr to coro while suspended. - handler_.coro_.reset(); - - if (--ready_ != 0) - ca_(); - if (!out_ec_ && ec_) throw asio::system_error(ec_); - return ASIO_MOVE_CAST(return_type)(value_); - } - - private: - completion_handler_type& handler_; - typename basic_yield_context::caller_type& ca_; - atomic_count ready_; - asio::error_code* out_ec_; - asio::error_code ec_; - return_type value_; - }; - - template - class coro_async_result - { - public: - typedef coro_handler completion_handler_type; - typedef void return_type; - - explicit coro_async_result(completion_handler_type& h) - : handler_(h), - ca_(h.ca_), - ready_(2) - { - h.ready_ = &ready_; - out_ec_ = h.ec_; - if (!out_ec_) h.ec_ = &ec_; - } - - void get() - { - // Must not hold shared_ptr to coro while suspended. - handler_.coro_.reset(); - - if (--ready_ != 0) - ca_(); - if (!out_ec_ && ec_) throw asio::system_error(ec_); - } - - private: - completion_handler_type& handler_; - typename basic_yield_context::caller_type& ca_; - atomic_count ready_; - asio::error_code* out_ec_; - asio::error_code ec_; - }; - -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -class async_result, ReturnType()> - : public detail::coro_async_result -{ -public: - explicit async_result( - typename detail::coro_async_result::completion_handler_type& h) - : detail::coro_async_result(h) - { - } -}; - -template -class async_result, ReturnType(Arg1)> - : public detail::coro_async_result::type> -{ -public: - explicit async_result( - typename detail::coro_async_result::type>::completion_handler_type& h) - : detail::coro_async_result::type>(h) - { - } -}; - -template -class async_result, - ReturnType(asio::error_code)> - : public detail::coro_async_result -{ -public: - explicit async_result( - typename detail::coro_async_result::completion_handler_type& h) - : detail::coro_async_result(h) - { - } -}; - -template -class async_result, - ReturnType(asio::error_code, Arg2)> - : public detail::coro_async_result::type> -{ -public: - explicit async_result( - typename detail::coro_async_result::type>::completion_handler_type& h) - : detail::coro_async_result::type>(h) - { - } -}; - -#if !defined(ASIO_NO_DEPRECATED) - -template -struct handler_type, ReturnType()> -{ - typedef detail::coro_handler type; -}; - -template -struct handler_type, ReturnType(Arg1)> -{ - typedef detail::coro_handler::type> type; -}; - -template -struct handler_type, - ReturnType(asio::error_code)> -{ - typedef detail::coro_handler type; -}; - -template -struct handler_type, - ReturnType(asio::error_code, Arg2)> -{ - typedef detail::coro_handler::type> type; -}; - -template -class async_result > - : public detail::coro_async_result -{ -public: - typedef typename detail::coro_async_result::return_type type; - - explicit async_result( - typename detail::coro_async_result::completion_handler_type& h) - : detail::coro_async_result(h) - { - } -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -struct associated_allocator, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const detail::coro_handler& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const detail::coro_handler& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -namespace detail { - - template - struct spawn_data : private noncopyable - { - template - spawn_data(ASIO_MOVE_ARG(Hand) handler, - bool call_handler, ASIO_MOVE_ARG(Func) function) - : handler_(ASIO_MOVE_CAST(Hand)(handler)), - call_handler_(call_handler), - function_(ASIO_MOVE_CAST(Func)(function)) - { - } - - weak_ptr::callee_type> coro_; - Handler handler_; - bool call_handler_; - Function function_; - }; - - template - struct coro_entry_point - { - void operator()(typename basic_yield_context::caller_type& ca) - { - shared_ptr > data(data_); -#if !defined(BOOST_COROUTINES_UNIDIRECT) && !defined(BOOST_COROUTINES_V2) - ca(); // Yield until coroutine pointer has been initialised. -#endif // !defined(BOOST_COROUTINES_UNIDIRECT) && !defined(BOOST_COROUTINES_V2) - const basic_yield_context yield( - data->coro_, ca, data->handler_); - - (data->function_)(yield); - if (data->call_handler_) - (data->handler_)(); - } - - shared_ptr > data_; - }; - - template - struct spawn_helper - { - void operator()() - { - typedef typename basic_yield_context::callee_type callee_type; - coro_entry_point entry_point = { data_ }; - shared_ptr coro(new callee_type(entry_point, attributes_)); - data_->coro_ = coro; - (*coro)(); - } - - shared_ptr > data_; - boost::coroutines::attributes attributes_; - }; - - template - inline void asio_handler_invoke(Function& function, - spawn_helper* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->data_->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - spawn_helper* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->data_->handler_); - } - - inline void default_spawn_handler() {} - -} // namespace detail - -template -inline void spawn(ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes) -{ - typedef typename decay::type function_type; - - typename associated_executor::type ex( - (get_associated_executor)(function)); - - asio::spawn(ex, ASIO_MOVE_CAST(Function)(function), attributes); -} - -template -void spawn(ASIO_MOVE_ARG(Handler) handler, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes, - typename enable_if::type>::value && - !is_convertible::value>::type*) -{ - typedef typename decay::type handler_type; - typedef typename decay::type function_type; - - typename associated_executor::type ex( - (get_associated_executor)(handler)); - - typename associated_allocator::type a( - (get_associated_allocator)(handler)); - - detail::spawn_helper helper; - helper.data_.reset( - new detail::spawn_data( - ASIO_MOVE_CAST(Handler)(handler), true, - ASIO_MOVE_CAST(Function)(function))); - helper.attributes_ = attributes; - - ex.dispatch(helper, a); -} - -template -void spawn(basic_yield_context ctx, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes) -{ - typedef typename decay::type function_type; - - Handler handler(ctx.handler_); // Explicit copy that might be moved from. - - typename associated_executor::type ex( - (get_associated_executor)(handler)); - - typename associated_allocator::type a( - (get_associated_allocator)(handler)); - - detail::spawn_helper helper; - helper.data_.reset( - new detail::spawn_data( - ASIO_MOVE_CAST(Handler)(handler), false, - ASIO_MOVE_CAST(Function)(function))); - helper.attributes_ = attributes; - - ex.dispatch(helper, a); -} - -template -inline void spawn(const Executor& ex, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes, - typename enable_if::value>::type*) -{ - asio::spawn(asio::strand(ex), - ASIO_MOVE_CAST(Function)(function), attributes); -} - -template -inline void spawn(const strand& ex, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes) -{ - asio::spawn(asio::bind_executor( - ex, &detail::default_spawn_handler), - ASIO_MOVE_CAST(Function)(function), attributes); -} - -template -inline void spawn(const asio::io_context::strand& s, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes) -{ - asio::spawn(asio::bind_executor( - s, &detail::default_spawn_handler), - ASIO_MOVE_CAST(Function)(function), attributes); -} - -template -inline void spawn(ExecutionContext& ctx, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes, - typename enable_if::value>::type*) -{ - asio::spawn(ctx.get_executor(), - ASIO_MOVE_CAST(Function)(function), attributes); -} - -#endif // !defined(GENERATING_DOCUMENTATION) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_SPAWN_HPP diff --git a/scout_sdk/asio/asio/impl/src.cpp b/scout_sdk/asio/asio/impl/src.cpp deleted file mode 100644 index e8a5953..0000000 --- a/scout_sdk/asio/asio/impl/src.cpp +++ /dev/null @@ -1,25 +0,0 @@ -// -// impl/src.cpp -// ~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#if defined(_MSC_VER) \ - || defined(__BORLANDC__) \ - || defined(__DMC__) -# pragma message ( \ - "This file is deprecated. " \ - "Please #include instead.") -#elif defined(__GNUC__) \ - || defined(__HP_aCC) \ - || defined(__SUNPRO_CC) \ - || defined(__IBMCPP__) -# warning "This file is deprecated." -# warning "Please #include instead." -#endif - -#include "asio/impl/src.hpp" diff --git a/scout_sdk/asio/asio/impl/src.hpp b/scout_sdk/asio/asio/impl/src.hpp deleted file mode 100644 index a72637b..0000000 --- a/scout_sdk/asio/asio/impl/src.hpp +++ /dev/null @@ -1,82 +0,0 @@ -// -// impl/src.hpp -// ~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_SRC_HPP -#define ASIO_IMPL_SRC_HPP - -#define ASIO_SOURCE - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HEADER_ONLY) -# error Do not compile Asio library source with ASIO_HEADER_ONLY defined -#endif - -#include "asio/impl/error.ipp" -#include "asio/impl/error_code.ipp" -#include "asio/impl/execution_context.ipp" -#include "asio/impl/executor.ipp" -#include "asio/impl/handler_alloc_hook.ipp" -#include "asio/impl/io_context.ipp" -#include "asio/impl/serial_port_base.ipp" -#include "asio/impl/system_context.ipp" -#include "asio/impl/thread_pool.ipp" -#include "asio/detail/impl/buffer_sequence_adapter.ipp" -#include "asio/detail/impl/descriptor_ops.ipp" -#include "asio/detail/impl/dev_poll_reactor.ipp" -#include "asio/detail/impl/epoll_reactor.ipp" -#include "asio/detail/impl/eventfd_select_interrupter.ipp" -#include "asio/detail/impl/handler_tracking.ipp" -#include "asio/detail/impl/kqueue_reactor.ipp" -#include "asio/detail/impl/null_event.ipp" -#include "asio/detail/impl/pipe_select_interrupter.ipp" -#include "asio/detail/impl/posix_event.ipp" -#include "asio/detail/impl/posix_mutex.ipp" -#include "asio/detail/impl/posix_thread.ipp" -#include "asio/detail/impl/posix_tss_ptr.ipp" -#include "asio/detail/impl/reactive_descriptor_service.ipp" -#include "asio/detail/impl/reactive_serial_port_service.ipp" -#include "asio/detail/impl/reactive_socket_service_base.ipp" -#include "asio/detail/impl/resolver_service_base.ipp" -#include "asio/detail/impl/scheduler.ipp" -#include "asio/detail/impl/select_reactor.ipp" -#include "asio/detail/impl/service_registry.ipp" -#include "asio/detail/impl/signal_set_service.ipp" -#include "asio/detail/impl/socket_ops.ipp" -#include "asio/detail/impl/socket_select_interrupter.ipp" -#include "asio/detail/impl/strand_executor_service.ipp" -#include "asio/detail/impl/strand_service.ipp" -#include "asio/detail/impl/throw_error.ipp" -#include "asio/detail/impl/timer_queue_ptime.ipp" -#include "asio/detail/impl/timer_queue_set.ipp" -#include "asio/detail/impl/win_iocp_handle_service.ipp" -#include "asio/detail/impl/win_iocp_io_context.ipp" -#include "asio/detail/impl/win_iocp_serial_port_service.ipp" -#include "asio/detail/impl/win_iocp_socket_service_base.ipp" -#include "asio/detail/impl/win_event.ipp" -#include "asio/detail/impl/win_mutex.ipp" -#include "asio/detail/impl/win_object_handle_service.ipp" -#include "asio/detail/impl/win_static_mutex.ipp" -#include "asio/detail/impl/win_thread.ipp" -#include "asio/detail/impl/win_tss_ptr.ipp" -#include "asio/detail/impl/winrt_ssocket_service_base.ipp" -#include "asio/detail/impl/winrt_timer_scheduler.ipp" -#include "asio/detail/impl/winsock_init.ipp" -#include "asio/generic/detail/impl/endpoint.ipp" -#include "asio/ip/impl/address.ipp" -#include "asio/ip/impl/address_v4.ipp" -#include "asio/ip/impl/address_v6.ipp" -#include "asio/ip/impl/host_name.ipp" -#include "asio/ip/impl/network_v4.ipp" -#include "asio/ip/impl/network_v6.ipp" -#include "asio/ip/detail/impl/endpoint.ipp" -#include "asio/local/detail/impl/endpoint.ipp" - -#endif // ASIO_IMPL_SRC_HPP diff --git a/scout_sdk/asio/asio/impl/system_context.hpp b/scout_sdk/asio/asio/impl/system_context.hpp deleted file mode 100644 index 87ffe76..0000000 --- a/scout_sdk/asio/asio/impl/system_context.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// -// impl/system_context.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_SYSTEM_CONTEXT_HPP -#define ASIO_IMPL_SYSTEM_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/system_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -inline system_context::executor_type -system_context::get_executor() ASIO_NOEXCEPT -{ - return system_executor(); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_SYSTEM_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/impl/system_context.ipp b/scout_sdk/asio/asio/impl/system_context.ipp deleted file mode 100644 index 8ad5e41..0000000 --- a/scout_sdk/asio/asio/impl/system_context.ipp +++ /dev/null @@ -1,73 +0,0 @@ -// -// impl/system_context.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_SYSTEM_CONTEXT_IPP -#define ASIO_IMPL_SYSTEM_CONTEXT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/system_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -struct system_context::thread_function -{ - detail::scheduler* scheduler_; - - void operator()() - { - asio::error_code ec; - scheduler_->run(ec); - } -}; - -system_context::system_context() - : scheduler_(use_service(*this)) -{ - scheduler_.work_started(); - - thread_function f = { &scheduler_ }; - std::size_t num_threads = detail::thread::hardware_concurrency() * 2; - threads_.create_threads(f, num_threads ? num_threads : 2); -} - -system_context::~system_context() -{ - scheduler_.work_finished(); - scheduler_.stop(); - threads_.join(); -} - -void system_context::stop() -{ - scheduler_.stop(); -} - -bool system_context::stopped() const ASIO_NOEXCEPT -{ - return scheduler_.stopped(); -} - -void system_context::join() -{ - scheduler_.work_finished(); - threads_.join(); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_SYSTEM_CONTEXT_IPP diff --git a/scout_sdk/asio/asio/impl/system_executor.hpp b/scout_sdk/asio/asio/impl/system_executor.hpp deleted file mode 100644 index ac4861f..0000000 --- a/scout_sdk/asio/asio/impl/system_executor.hpp +++ /dev/null @@ -1,85 +0,0 @@ -// -// impl/system_executor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_SYSTEM_EXECUTOR_HPP -#define ASIO_IMPL_SYSTEM_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/executor_op.hpp" -#include "asio/detail/global.hpp" -#include "asio/detail/recycling_allocator.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/system_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -inline system_context& system_executor::context() const ASIO_NOEXCEPT -{ - return detail::global(); -} - -template -void system_executor::dispatch( - ASIO_MOVE_ARG(Function) f, const Allocator&) const -{ - typename decay::type tmp(ASIO_MOVE_CAST(Function)(f)); - asio_handler_invoke_helpers::invoke(tmp, tmp); -} - -template -void system_executor::post( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - system_context& ctx = detail::global(); - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((ctx, *p.p, - "system_executor", &this->context(), 0, "post")); - - ctx.scheduler_.post_immediate_completion(p.p, false); - p.v = p.p = 0; -} - -template -void system_executor::defer( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - system_context& ctx = detail::global(); - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((ctx, *p.p, - "system_executor", &this->context(), 0, "defer")); - - ctx.scheduler_.post_immediate_completion(p.p, true); - p.v = p.p = 0; -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_SYSTEM_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/impl/thread_pool.hpp b/scout_sdk/asio/asio/impl/thread_pool.hpp deleted file mode 100644 index 058e377..0000000 --- a/scout_sdk/asio/asio/impl/thread_pool.hpp +++ /dev/null @@ -1,127 +0,0 @@ -// -// impl/thread_pool.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_THREAD_POOL_HPP -#define ASIO_IMPL_THREAD_POOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/executor_op.hpp" -#include "asio/detail/fenced_block.hpp" -#include "asio/detail/recycling_allocator.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -inline thread_pool::executor_type -thread_pool::get_executor() ASIO_NOEXCEPT -{ - return executor_type(*this); -} - -inline thread_pool& -thread_pool::executor_type::context() const ASIO_NOEXCEPT -{ - return pool_; -} - -inline void -thread_pool::executor_type::on_work_started() const ASIO_NOEXCEPT -{ - pool_.scheduler_.work_started(); -} - -inline void thread_pool::executor_type::on_work_finished() -const ASIO_NOEXCEPT -{ - pool_.scheduler_.work_finished(); -} - -template -void thread_pool::executor_type::dispatch( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - // Invoke immediately if we are already inside the thread pool. - if (pool_.scheduler_.can_dispatch()) - { - // Make a local, non-const copy of the function. - function_type tmp(ASIO_MOVE_CAST(Function)(f)); - - detail::fenced_block b(detail::fenced_block::full); - asio_handler_invoke_helpers::invoke(tmp, tmp); - return; - } - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((pool_, *p.p, - "thread_pool", &this->context(), 0, "dispatch")); - - pool_.scheduler_.post_immediate_completion(p.p, false); - p.v = p.p = 0; -} - -template -void thread_pool::executor_type::post( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((pool_, *p.p, - "thread_pool", &this->context(), 0, "post")); - - pool_.scheduler_.post_immediate_completion(p.p, false); - p.v = p.p = 0; -} - -template -void thread_pool::executor_type::defer( - ASIO_MOVE_ARG(Function) f, const Allocator& a) const -{ - typedef typename decay::type function_type; - - // Allocate and construct an operation to wrap the function. - typedef detail::executor_op op; - typename op::ptr p = { detail::addressof(a), op::ptr::allocate(a), 0 }; - p.p = new (p.v) op(ASIO_MOVE_CAST(Function)(f), a); - - ASIO_HANDLER_CREATION((pool_, *p.p, - "thread_pool", &this->context(), 0, "defer")); - - pool_.scheduler_.post_immediate_completion(p.p, true); - p.v = p.p = 0; -} - -inline bool -thread_pool::executor_type::running_in_this_thread() const ASIO_NOEXCEPT -{ - return pool_.scheduler_.can_dispatch(); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_THREAD_POOL_HPP diff --git a/scout_sdk/asio/asio/impl/thread_pool.ipp b/scout_sdk/asio/asio/impl/thread_pool.ipp deleted file mode 100644 index 89583c1..0000000 --- a/scout_sdk/asio/asio/impl/thread_pool.ipp +++ /dev/null @@ -1,76 +0,0 @@ -// -// impl/thread_pool.ipp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_THREAD_POOL_IPP -#define ASIO_IMPL_THREAD_POOL_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/thread_pool.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -struct thread_pool::thread_function -{ - detail::scheduler* scheduler_; - - void operator()() - { - asio::error_code ec; - scheduler_->run(ec); - } -}; - -thread_pool::thread_pool() - : scheduler_(use_service(*this)) -{ - scheduler_.work_started(); - - thread_function f = { &scheduler_ }; - std::size_t num_threads = detail::thread::hardware_concurrency() * 2; - threads_.create_threads(f, num_threads ? num_threads : 2); -} - -thread_pool::thread_pool(std::size_t num_threads) - : scheduler_(use_service(*this)) -{ - scheduler_.work_started(); - - thread_function f = { &scheduler_ }; - threads_.create_threads(f, num_threads); -} - -thread_pool::~thread_pool() -{ - stop(); - join(); -} - -void thread_pool::stop() -{ - scheduler_.stop(); -} - -void thread_pool::join() -{ - scheduler_.work_finished(); - threads_.join(); -} - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_THREAD_POOL_IPP diff --git a/scout_sdk/asio/asio/impl/use_future.hpp b/scout_sdk/asio/asio/impl/use_future.hpp deleted file mode 100644 index 51eb7e2..0000000 --- a/scout_sdk/asio/asio/impl/use_future.hpp +++ /dev/null @@ -1,938 +0,0 @@ -// -// impl/use_future.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_USE_FUTURE_HPP -#define ASIO_IMPL_USE_FUTURE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include "asio/async_result.hpp" -#include "asio/detail/memory.hpp" -#include "asio/error_code.hpp" -#include "asio/packaged_task.hpp" -#include "asio/system_error.hpp" -#include "asio/system_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -inline void promise_invoke_and_set(std::promise& p, - F& f, ASIO_MOVE_ARG(Args)... args) -{ -#if !defined(ASIO_NO_EXCEPTIONS) - try -#endif // !defined(ASIO_NO_EXCEPTIONS) - { - p.set_value(f(ASIO_MOVE_CAST(Args)(args)...)); - } -#if !defined(ASIO_NO_EXCEPTIONS) - catch (...) - { - p.set_exception(std::current_exception()); - } -#endif // !defined(ASIO_NO_EXCEPTIONS) -} - -template -inline void promise_invoke_and_set(std::promise& p, - F& f, ASIO_MOVE_ARG(Args)... args) -{ -#if !defined(ASIO_NO_EXCEPTIONS) - try -#endif // !defined(ASIO_NO_EXCEPTIONS) - { - f(ASIO_MOVE_CAST(Args)(args)...); - p.set_value(); - } -#if !defined(ASIO_NO_EXCEPTIONS) - catch (...) - { - p.set_exception(std::current_exception()); - } -#endif // !defined(ASIO_NO_EXCEPTIONS) -} - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -inline void promise_invoke_and_set(std::promise& p, F& f) -{ -#if !defined(ASIO_NO_EXCEPTIONS) - try -#endif // !defined(ASIO_NO_EXCEPTIONS) - { - p.set_value(f()); - } -#if !defined(ASIO_NO_EXCEPTIONS) - catch (...) - { - p.set_exception(std::current_exception()); - } -#endif // !defined(ASIO_NO_EXCEPTIONS) -} - -template -inline void promise_invoke_and_set(std::promise& p, F& f) -{ -#if !defined(ASIO_NO_EXCEPTIONS) - try -#endif // !defined(ASIO_NO_EXCEPTIONS) - { - f(); - p.set_value(); -#if !defined(ASIO_NO_EXCEPTIONS) - } - catch (...) - { - p.set_exception(std::current_exception()); - } -#endif // !defined(ASIO_NO_EXCEPTIONS) -} - -#if defined(ASIO_NO_EXCEPTIONS) - -#define ASIO_PRIVATE_PROMISE_INVOKE_DEF(n) \ - template \ - inline void promise_invoke_and_set(std::promise& p, \ - F& f, ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - p.set_value(f(ASIO_VARIADIC_MOVE_ARGS(n))); \ - } \ - \ - template \ - inline void promise_invoke_and_set(std::promise& p, \ - F& f, ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - f(ASIO_VARIADIC_MOVE_ARGS(n)); \ - p.set_value(); \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_PROMISE_INVOKE_DEF) -#undef ASIO_PRIVATE_PROMISE_INVOKE_DEF - -#else // defined(ASIO_NO_EXCEPTIONS) - -#define ASIO_PRIVATE_PROMISE_INVOKE_DEF(n) \ - template \ - inline void promise_invoke_and_set(std::promise& p, \ - F& f, ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - try \ - { \ - p.set_value(f(ASIO_VARIADIC_MOVE_ARGS(n))); \ - } \ - catch (...) \ - { \ - p.set_exception(std::current_exception()); \ - } \ - } \ - \ - template \ - inline void promise_invoke_and_set(std::promise& p, \ - F& f, ASIO_VARIADIC_MOVE_PARAMS(n)) \ - { \ - try \ - { \ - f(ASIO_VARIADIC_MOVE_ARGS(n)); \ - p.set_value(); \ - } \ - catch (...) \ - { \ - p.set_exception(std::current_exception()); \ - } \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_PROMISE_INVOKE_DEF) -#undef ASIO_PRIVATE_PROMISE_INVOKE_DEF - -#endif // defined(ASIO_NO_EXCEPTIONS) - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -// A function object adapter to invoke a nullary function object and capture -// any exception thrown into a promise. -template -class promise_invoker -{ -public: - promise_invoker(const shared_ptr >& p, - ASIO_MOVE_ARG(F) f) - : p_(p), f_(ASIO_MOVE_CAST(F)(f)) - { - } - - void operator()() - { -#if !defined(ASIO_NO_EXCEPTIONS) - try -#endif // !defined(ASIO_NO_EXCEPTIONS) - { - f_(); - } -#if !defined(ASIO_NO_EXCEPTIONS) - catch (...) - { - p_->set_exception(std::current_exception()); - } -#endif // !defined(ASIO_NO_EXCEPTIONS) - } - -private: - shared_ptr > p_; - typename decay::type f_; -}; - -// An executor that adapts the system_executor to capture any exeption thrown -// by a submitted function object and save it into a promise. -template -class promise_executor -{ -public: - explicit promise_executor(const shared_ptr >& p) - : p_(p) - { - } - - execution_context& context() const ASIO_NOEXCEPT - { - return system_executor().context(); - } - - void on_work_started() const ASIO_NOEXCEPT {} - void on_work_finished() const ASIO_NOEXCEPT {} - - template - void dispatch(ASIO_MOVE_ARG(F) f, const A&) const - { - promise_invoker(p_, ASIO_MOVE_CAST(F)(f))(); - } - - template - void post(ASIO_MOVE_ARG(F) f, const A& a) const - { - system_executor().post( - promise_invoker(p_, ASIO_MOVE_CAST(F)(f)), a); - } - - template - void defer(ASIO_MOVE_ARG(F) f, const A& a) const - { - system_executor().defer( - promise_invoker(p_, ASIO_MOVE_CAST(F)(f)), a); - } - - friend bool operator==(const promise_executor& a, - const promise_executor& b) ASIO_NOEXCEPT - { - return a.p_ == b.p_; - } - - friend bool operator!=(const promise_executor& a, - const promise_executor& b) ASIO_NOEXCEPT - { - return a.p_ != b.p_; - } - -private: - shared_ptr > p_; -}; - -// The base class for all completion handlers that create promises. -template -class promise_creator -{ -public: - typedef promise_executor executor_type; - - executor_type get_executor() const ASIO_NOEXCEPT - { - return executor_type(p_); - } - - typedef std::future future_type; - - future_type get_future() - { - return p_->get_future(); - } - -protected: - template - void create_promise(const Allocator& a) - { - ASIO_REBIND_ALLOC(Allocator, char) b(a); - p_ = std::allocate_shared>(b, std::allocator_arg, b); - } - - shared_ptr > p_; -}; - -// For completion signature void(). -class promise_handler_0 - : public promise_creator -{ -public: - void operator()() - { - this->p_->set_value(); - } -}; - -// For completion signature void(error_code). -class promise_handler_ec_0 - : public promise_creator -{ -public: - void operator()(const asio::error_code& ec) - { - if (ec) - { - this->p_->set_exception( - std::make_exception_ptr( - asio::system_error(ec))); - } - else - { - this->p_->set_value(); - } - } -}; - -// For completion signature void(exception_ptr). -class promise_handler_ex_0 - : public promise_creator -{ -public: - void operator()(const std::exception_ptr& ex) - { - if (ex) - { - this->p_->set_exception(ex); - } - else - { - this->p_->set_value(); - } - } -}; - -// For completion signature void(T). -template -class promise_handler_1 - : public promise_creator -{ -public: - template - void operator()(ASIO_MOVE_ARG(Arg) arg) - { - this->p_->set_value(ASIO_MOVE_CAST(Arg)(arg)); - } -}; - -// For completion signature void(error_code, T). -template -class promise_handler_ec_1 - : public promise_creator -{ -public: - template - void operator()(const asio::error_code& ec, - ASIO_MOVE_ARG(Arg) arg) - { - if (ec) - { - this->p_->set_exception( - std::make_exception_ptr( - asio::system_error(ec))); - } - else - this->p_->set_value(ASIO_MOVE_CAST(Arg)(arg)); - } -}; - -// For completion signature void(exception_ptr, T). -template -class promise_handler_ex_1 - : public promise_creator -{ -public: - template - void operator()(const std::exception_ptr& ex, - ASIO_MOVE_ARG(Arg) arg) - { - if (ex) - this->p_->set_exception(ex); - else - this->p_->set_value(ASIO_MOVE_CAST(Arg)(arg)); - } -}; - -// For completion signature void(T1, ..., Tn); -template -class promise_handler_n - : public promise_creator -{ -public: -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - void operator()(ASIO_MOVE_ARG(Args)... args) - { - this->p_->set_value( - std::forward_as_tuple( - ASIO_MOVE_CAST(Args)(args)...)); - } - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#define ASIO_PRIVATE_CALL_OP_DEF(n) \ - template \ - void operator()(ASIO_VARIADIC_MOVE_PARAMS(n)) \ - {\ - this->p_->set_value( \ - std::forward_as_tuple( \ - ASIO_VARIADIC_MOVE_ARGS(n))); \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_CALL_OP_DEF) -#undef ASIO_PRIVATE_CALL_OP_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) -}; - -// For completion signature void(error_code, T1, ..., Tn); -template -class promise_handler_ec_n - : public promise_creator -{ -public: -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - void operator()(const asio::error_code& ec, - ASIO_MOVE_ARG(Args)... args) - { - if (ec) - { - this->p_->set_exception( - std::make_exception_ptr( - asio::system_error(ec))); - } - else - { - this->p_->set_value( - std::forward_as_tuple( - ASIO_MOVE_CAST(Args)(args)...)); - } - } - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#define ASIO_PRIVATE_CALL_OP_DEF(n) \ - template \ - void operator()(const asio::error_code& ec, \ - ASIO_VARIADIC_MOVE_PARAMS(n)) \ - {\ - if (ec) \ - { \ - this->p_->set_exception( \ - std::make_exception_ptr( \ - asio::system_error(ec))); \ - } \ - else \ - { \ - this->p_->set_value( \ - std::forward_as_tuple( \ - ASIO_VARIADIC_MOVE_ARGS(n))); \ - } \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_CALL_OP_DEF) -#undef ASIO_PRIVATE_CALL_OP_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) -}; - -// For completion signature void(exception_ptr, T1, ..., Tn); -template -class promise_handler_ex_n - : public promise_creator -{ -public: -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - void operator()(const std::exception_ptr& ex, - ASIO_MOVE_ARG(Args)... args) - { - if (ex) - this->p_->set_exception(ex); - else - { - this->p_->set_value( - std::forward_as_tuple( - ASIO_MOVE_CAST(Args)(args)...)); - } - } - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#define ASIO_PRIVATE_CALL_OP_DEF(n) \ - template \ - void operator()(const std::exception_ptr& ex, \ - ASIO_VARIADIC_MOVE_PARAMS(n)) \ - {\ - if (ex) \ - this->p_->set_exception(ex); \ - else \ - { \ - this->p_->set_value( \ - std::forward_as_tuple( \ - ASIO_VARIADIC_MOVE_ARGS(n))); \ - } \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_CALL_OP_DEF) -#undef ASIO_PRIVATE_CALL_OP_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) -}; - -// Helper template to choose the appropriate concrete promise handler -// implementation based on the supplied completion signature. -template class promise_handler_selector; - -template <> -class promise_handler_selector - : public promise_handler_0 {}; - -template <> -class promise_handler_selector - : public promise_handler_ec_0 {}; - -template <> -class promise_handler_selector - : public promise_handler_ex_0 {}; - -template -class promise_handler_selector - : public promise_handler_1 {}; - -template -class promise_handler_selector - : public promise_handler_ec_1 {}; - -template -class promise_handler_selector - : public promise_handler_ex_1 {}; - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -class promise_handler_selector - : public promise_handler_n > {}; - -template -class promise_handler_selector - : public promise_handler_ec_n > {}; - -template -class promise_handler_selector - : public promise_handler_ex_n > {}; - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#define ASIO_PRIVATE_PROMISE_SELECTOR_DEF(n) \ - template \ - class promise_handler_selector< \ - void(Arg, ASIO_VARIADIC_TARGS(n))> \ - : public promise_handler_n< \ - std::tuple > {}; \ - \ - template \ - class promise_handler_selector< \ - void(asio::error_code, Arg, ASIO_VARIADIC_TARGS(n))> \ - : public promise_handler_ec_n< \ - std::tuple > {}; \ - \ - template \ - class promise_handler_selector< \ - void(std::exception_ptr, Arg, ASIO_VARIADIC_TARGS(n))> \ - : public promise_handler_ex_n< \ - std::tuple > {}; \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_PROMISE_SELECTOR_DEF) -#undef ASIO_PRIVATE_PROMISE_SELECTOR_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -// Completion handlers produced from the use_future completion token, when not -// using use_future::operator(). -template -class promise_handler - : public promise_handler_selector -{ -public: - typedef Allocator allocator_type; - typedef void result_type; - - promise_handler(use_future_t u) - : allocator_(u.get_allocator()) - { - this->create_promise(allocator_); - } - - allocator_type get_allocator() const ASIO_NOEXCEPT - { - return allocator_; - } - -private: - Allocator allocator_; -}; - -template -inline void asio_handler_invoke(Function& f, - promise_handler* h) -{ - typename promise_handler::executor_type - ex(h->get_executor()); - ex.dispatch(ASIO_MOVE_CAST(Function)(f), std::allocator()); -} - -template -inline void asio_handler_invoke(const Function& f, - promise_handler* h) -{ - typename promise_handler::executor_type - ex(h->get_executor()); - ex.dispatch(f, std::allocator()); -} - -// Helper base class for async_result specialisation. -template -class promise_async_result -{ -public: - typedef promise_handler completion_handler_type; - typedef typename completion_handler_type::future_type return_type; - - explicit promise_async_result(completion_handler_type& h) - : future_(h.get_future()) - { - } - - return_type get() - { - return ASIO_MOVE_CAST(return_type)(future_); - } - -private: - return_type future_; -}; - -// Return value from use_future::operator(). -template -class packaged_token -{ -public: - packaged_token(Function f, const Allocator& a) - : function_(ASIO_MOVE_CAST(Function)(f)), - allocator_(a) - { - } - -//private: - Function function_; - Allocator allocator_; -}; - -// Completion handlers produced from the use_future completion token, when -// using use_future::operator(). -template -class packaged_handler - : public promise_creator -{ -public: - typedef Allocator allocator_type; - typedef void result_type; - - packaged_handler(packaged_token t) - : function_(ASIO_MOVE_CAST(Function)(t.function_)), - allocator_(t.allocator_) - { - this->create_promise(allocator_); - } - - allocator_type get_allocator() const ASIO_NOEXCEPT - { - return allocator_; - } - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - - template - void operator()(ASIO_MOVE_ARG(Args)... args) - { - (promise_invoke_and_set)(*this->p_, - function_, ASIO_MOVE_CAST(Args)(args)...); - } - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - - void operator()() - { - (promise_invoke_and_set)(*this->p_, function_); - } - -#define ASIO_PRIVATE_CALL_OP_DEF(n) \ - template \ - void operator()(ASIO_VARIADIC_MOVE_PARAMS(n)) \ - {\ - (promise_invoke_and_set)(*this->p_, \ - function_, ASIO_VARIADIC_MOVE_ARGS(n)); \ - } \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_CALL_OP_DEF) -#undef ASIO_PRIVATE_CALL_OP_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -private: - Function function_; - Allocator allocator_; -}; - -template -inline void asio_handler_invoke(Function& f, - packaged_handler* h) -{ - typename packaged_handler::executor_type - ex(h->get_executor()); - ex.dispatch(ASIO_MOVE_CAST(Function)(f), std::allocator()); -} - -template -inline void asio_handler_invoke(const Function& f, - packaged_handler* h) -{ - typename packaged_handler::executor_type - ex(h->get_executor()); - ex.dispatch(f, std::allocator()); -} - -// Helper base class for async_result specialisation. -template -class packaged_async_result -{ -public: - typedef packaged_handler completion_handler_type; - typedef typename completion_handler_type::future_type return_type; - - explicit packaged_async_result(completion_handler_type& h) - : future_(h.get_future()) - { - } - - return_type get() - { - return ASIO_MOVE_CAST(return_type)(future_); - } - -private: - return_type future_; -}; - -} // namespace detail - -template template -inline detail::packaged_token::type, Allocator> -use_future_t::operator()(ASIO_MOVE_ARG(Function) f) const -{ - return detail::packaged_token::type, Allocator>( - ASIO_MOVE_CAST(Function)(f), allocator_); -} - -#if !defined(GENERATING_DOCUMENTATION) - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -class async_result, Result(Args...)> - : public detail::promise_async_result< - void(typename decay::type...), Allocator> -{ -public: - explicit async_result( - typename detail::promise_async_result::type...), - Allocator>::completion_handler_type& h) - : detail::promise_async_result< - void(typename decay::type...), Allocator>(h) - { - } -}; - -template -class async_result, Result(Args...)> - : public detail::packaged_async_result::type> -{ -public: - explicit async_result( - typename detail::packaged_async_result::type>::completion_handler_type& h) - : detail::packaged_async_result::type>(h) - { - } -}; - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -template -class async_result, Result()> - : public detail::promise_async_result -{ -public: - explicit async_result( - typename detail::promise_async_result< - void(), Allocator>::completion_handler_type& h) - : detail::promise_async_result(h) - { - } -}; - -template -class async_result, Result()> - : public detail::packaged_async_result::type> -{ -public: - explicit async_result( - typename detail::packaged_async_result::type>::completion_handler_type& h) - : detail::packaged_async_result::type>(h) - { - } -}; - -#define ASIO_PRIVATE_ASYNC_RESULT_DEF(n) \ - template \ - class async_result, \ - Result(ASIO_VARIADIC_TARGS(n))> \ - : public detail::promise_async_result< \ - void(ASIO_VARIADIC_DECAY(n)), Allocator> \ - { \ - public: \ - explicit async_result( \ - typename detail::promise_async_result< \ - void(ASIO_VARIADIC_DECAY(n)), \ - Allocator>::completion_handler_type& h) \ - : detail::promise_async_result< \ - void(ASIO_VARIADIC_DECAY(n)), Allocator>(h) \ - { \ - } \ - }; \ - \ - template \ - class async_result, \ - Result(ASIO_VARIADIC_TARGS(n))> \ - : public detail::packaged_async_result::type> \ - { \ - public: \ - explicit async_result( \ - typename detail::packaged_async_result::type \ - >::completion_handler_type& h) \ - : detail::packaged_async_result::type>(h) \ - { \ - } \ - }; \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_ASYNC_RESULT_DEF) -#undef ASIO_PRIVATE_ASYNC_RESULT_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - -#if !defined(ASIO_NO_DEPRECATED) - -template -struct handler_type, Signature> -{ - typedef typename async_result, - Signature>::completion_handler_type type; -}; - -template -class async_result > - : public detail::promise_async_result -{ -public: - typedef typename detail::promise_async_result< - Signature, Allocator>::return_type type; - - explicit async_result( - typename detail::promise_async_result< - Signature, Allocator>::completion_handler_type& h) - : detail::promise_async_result(h) - { - } -}; - -template -struct handler_type, Signature> -{ - typedef typename async_result, - Signature>::completion_handler_type type; -}; - -template -class async_result > - : public detail::packaged_async_result -{ -public: - typedef typename detail::packaged_async_result< - Function, Allocator, Result>::return_type type; - - explicit async_result( - typename detail::packaged_async_result< - Function, Allocator, Result>::completion_handler_type& h) - : detail::packaged_async_result(h) - { - } -}; - -#endif // !defined(ASIO_NO_DEPRECATED) - -#endif // !defined(GENERATING_DOCUMENTATION) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_USE_FUTURE_HPP diff --git a/scout_sdk/asio/asio/impl/write.hpp b/scout_sdk/asio/asio/impl/write.hpp deleted file mode 100644 index d07e8d3..0000000 --- a/scout_sdk/asio/asio/impl/write.hpp +++ /dev/null @@ -1,674 +0,0 @@ -// -// impl/write.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_WRITE_HPP -#define ASIO_IMPL_WRITE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/buffer.hpp" -#include "asio/completion_condition.hpp" -#include "asio/detail/array_fwd.hpp" -#include "asio/detail/base_from_completion_cond.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/consuming_buffers.hpp" -#include "asio/detail/dependent_type.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - template - std::size_t write_buffer_sequence(SyncWriteStream& s, - const ConstBufferSequence& buffers, const ConstBufferIterator&, - CompletionCondition completion_condition, asio::error_code& ec) - { - ec = asio::error_code(); - asio::detail::consuming_buffers tmp(buffers); - while (!tmp.empty()) - { - if (std::size_t max_size = detail::adapt_completion_condition_result( - completion_condition(ec, tmp.total_consumed()))) - tmp.consume(s.write_some(tmp.prepare(max_size), ec)); - else - break; - } - return tmp.total_consumed();; - } -} // namespace detail - -template -inline std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_const_buffer_sequence::value - >::type*) -{ - return detail::write_buffer_sequence(s, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, ec); -} - -template -inline std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - typename enable_if< - is_const_buffer_sequence::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = write(s, buffers, transfer_all(), ec); - asio::detail::throw_error(ec, "write"); - return bytes_transferred; -} - -template -inline std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - asio::error_code& ec, - typename enable_if< - is_const_buffer_sequence::value - >::type*) -{ - return write(s, buffers, transfer_all(), ec); -} - -template -inline std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, - typename enable_if< - is_const_buffer_sequence::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = write(s, buffers, completion_condition, ec); - asio::detail::throw_error(ec, "write"); - return bytes_transferred; -} - -template -std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - typename decay::type b( - ASIO_MOVE_CAST(DynamicBuffer)(buffers)); - - std::size_t bytes_transferred = write(s, b.data(), completion_condition, ec); - b.consume(bytes_transferred); - return bytes_transferred; -} - -template -inline std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = write(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), - transfer_all(), ec); - asio::detail::throw_error(ec, "write"); - return bytes_transferred; -} - -template -inline std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - return write(s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - transfer_all(), ec); -} - -template -inline std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - asio::error_code ec; - std::size_t bytes_transferred = write(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), - completion_condition, ec); - asio::detail::throw_error(ec, "write"); - return bytes_transferred; -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -template -inline std::size_t write(SyncWriteStream& s, - asio::basic_streambuf& b, - CompletionCondition completion_condition, asio::error_code& ec) -{ - return write(s, basic_streambuf_ref(b), completion_condition, ec); -} - -template -inline std::size_t write(SyncWriteStream& s, - asio::basic_streambuf& b) -{ - return write(s, basic_streambuf_ref(b)); -} - -template -inline std::size_t write(SyncWriteStream& s, - asio::basic_streambuf& b, - asio::error_code& ec) -{ - return write(s, basic_streambuf_ref(b), ec); -} - -template -inline std::size_t write(SyncWriteStream& s, - asio::basic_streambuf& b, - CompletionCondition completion_condition) -{ - return write(s, basic_streambuf_ref(b), completion_condition); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -namespace detail -{ - template - class write_op - : detail::base_from_completion_cond - { - public: - write_op(AsyncWriteStream& stream, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, WriteHandler& handler) - : detail::base_from_completion_cond< - CompletionCondition>(completion_condition), - stream_(stream), - buffers_(buffers), - start_(0), - handler_(ASIO_MOVE_CAST(WriteHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - write_op(const write_op& other) - : detail::base_from_completion_cond(other), - stream_(other.stream_), - buffers_(other.buffers_), - start_(other.start_), - handler_(other.handler_) - { - } - - write_op(write_op&& other) - : detail::base_from_completion_cond(other), - stream_(other.stream_), - buffers_(other.buffers_), - start_(other.start_), - handler_(ASIO_MOVE_CAST(WriteHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - std::size_t max_size; - switch (start_ = start) - { - case 1: - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - do - { - stream_.async_write_some(buffers_.prepare(max_size), - ASIO_MOVE_CAST(write_op)(*this)); - return; default: - buffers_.consume(bytes_transferred); - if ((!ec && bytes_transferred == 0) || buffers_.empty()) - break; - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - } while (max_size > 0); - - handler_(ec, buffers_.total_consumed()); - } - } - - //private: - AsyncWriteStream& stream_; - asio::detail::consuming_buffers buffers_; - int start_; - WriteHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - write_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - write_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - write_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - write_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - write_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void start_write_buffer_sequence_op(AsyncWriteStream& stream, - const ConstBufferSequence& buffers, const ConstBufferIterator&, - CompletionCondition completion_condition, WriteHandler& handler) - { - detail::write_op( - stream, buffers, completion_condition, handler)( - asio::error_code(), 0, 1); - } - -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::write_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::write_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::write_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::write_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_const_buffer_sequence::value - >::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - detail::start_write_buffer_sequence_op(s, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, - init.completion_handler); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_const_buffer_sequence::value - >::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - detail::start_write_buffer_sequence_op(s, buffers, - asio::buffer_sequence_begin(buffers), transfer_all(), - init.completion_handler); - - return init.result.get(); -} - -namespace detail -{ - template - class write_dynbuf_op - { - public: - template - write_dynbuf_op(AsyncWriteStream& stream, - ASIO_MOVE_ARG(BufferSequence) buffers, - CompletionCondition completion_condition, WriteHandler& handler) - : stream_(stream), - buffers_(ASIO_MOVE_CAST(BufferSequence)(buffers)), - completion_condition_( - ASIO_MOVE_CAST(CompletionCondition)(completion_condition)), - handler_(ASIO_MOVE_CAST(WriteHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - write_dynbuf_op(const write_dynbuf_op& other) - : stream_(other.stream_), - buffers_(other.buffers_), - completion_condition_(other.completion_condition_), - handler_(other.handler_) - { - } - - write_dynbuf_op(write_dynbuf_op&& other) - : stream_(other.stream_), - buffers_(ASIO_MOVE_CAST(DynamicBuffer)(other.buffers_)), - completion_condition_( - ASIO_MOVE_CAST(CompletionCondition)( - other.completion_condition_)), - handler_(ASIO_MOVE_CAST(WriteHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - switch (start) - { - case 1: - async_write(stream_, buffers_.data(), completion_condition_, - ASIO_MOVE_CAST(write_dynbuf_op)(*this)); - return; default: - buffers_.consume(bytes_transferred); - handler_(ec, static_cast(bytes_transferred)); - } - } - - //private: - AsyncWriteStream& stream_; - DynamicBuffer buffers_; - CompletionCondition completion_condition_; - WriteHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - write_dynbuf_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - write_dynbuf_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - write_dynbuf_op* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - write_dynbuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - write_dynbuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::write_dynbuf_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::write_dynbuf_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::write_dynbuf_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::write_dynbuf_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - return async_write(s, - ASIO_MOVE_CAST(DynamicBuffer)(buffers), - transfer_all(), ASIO_MOVE_CAST(WriteHandler)(handler)); -} - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type*) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - detail::write_dynbuf_op::type, - CompletionCondition, ASIO_HANDLER_TYPE( - WriteHandler, void (asio::error_code, std::size_t))>( - s, ASIO_MOVE_CAST(DynamicBuffer)(buffers), - completion_condition, init.completion_handler)( - asio::error_code(), 0, 1); - - return init.result.get(); -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, - asio::basic_streambuf& b, - ASIO_MOVE_ARG(WriteHandler) handler) -{ - return async_write(s, basic_streambuf_ref(b), - ASIO_MOVE_CAST(WriteHandler)(handler)); -} - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, - asio::basic_streambuf& b, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler) -{ - return async_write(s, basic_streambuf_ref(b), - completion_condition, ASIO_MOVE_CAST(WriteHandler)(handler)); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_WRITE_HPP diff --git a/scout_sdk/asio/asio/impl/write_at.hpp b/scout_sdk/asio/asio/impl/write_at.hpp deleted file mode 100644 index cc6f336..0000000 --- a/scout_sdk/asio/asio/impl/write_at.hpp +++ /dev/null @@ -1,572 +0,0 @@ -// -// impl/write_at.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IMPL_WRITE_AT_HPP -#define ASIO_IMPL_WRITE_AT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/associated_allocator.hpp" -#include "asio/associated_executor.hpp" -#include "asio/buffer.hpp" -#include "asio/completion_condition.hpp" -#include "asio/detail/array_fwd.hpp" -#include "asio/detail/base_from_completion_cond.hpp" -#include "asio/detail/bind_handler.hpp" -#include "asio/detail/consuming_buffers.hpp" -#include "asio/detail/dependent_type.hpp" -#include "asio/detail/handler_alloc_helpers.hpp" -#include "asio/detail/handler_cont_helpers.hpp" -#include "asio/detail/handler_invoke_helpers.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - template - std::size_t write_at_buffer_sequence(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - const ConstBufferIterator&, CompletionCondition completion_condition, - asio::error_code& ec) - { - ec = asio::error_code(); - asio::detail::consuming_buffers tmp(buffers); - while (!tmp.empty()) - { - if (std::size_t max_size = detail::adapt_completion_condition_result( - completion_condition(ec, tmp.total_consumed()))) - { - tmp.consume(d.write_some_at(offset + tmp.total_consumed(), - tmp.prepare(max_size), ec)); - } - else - break; - } - return tmp.total_consumed();; - } -} // namespace detail - -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec) -{ - return detail::write_at_buffer_sequence(d, offset, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, ec); -} - -template -inline std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers) -{ - asio::error_code ec; - std::size_t bytes_transferred = write_at( - d, offset, buffers, transfer_all(), ec); - asio::detail::throw_error(ec, "write_at"); - return bytes_transferred; -} - -template -inline std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - asio::error_code& ec) -{ - return write_at(d, offset, buffers, transfer_all(), ec); -} - -template -inline std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - CompletionCondition completion_condition) -{ - asio::error_code ec; - std::size_t bytes_transferred = write_at( - d, offset, buffers, completion_condition, ec); - asio::detail::throw_error(ec, "write_at"); - return bytes_transferred; -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, asio::basic_streambuf& b, - CompletionCondition completion_condition, asio::error_code& ec) -{ - std::size_t bytes_transferred = write_at( - d, offset, b.data(), completion_condition, ec); - b.consume(bytes_transferred); - return bytes_transferred; -} - -template -inline std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, asio::basic_streambuf& b) -{ - asio::error_code ec; - std::size_t bytes_transferred = write_at(d, offset, b, transfer_all(), ec); - asio::detail::throw_error(ec, "write_at"); - return bytes_transferred; -} - -template -inline std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, asio::basic_streambuf& b, - asio::error_code& ec) -{ - return write_at(d, offset, b, transfer_all(), ec); -} - -template -inline std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, asio::basic_streambuf& b, - CompletionCondition completion_condition) -{ - asio::error_code ec; - std::size_t bytes_transferred = write_at( - d, offset, b, completion_condition, ec); - asio::detail::throw_error(ec, "write_at"); - return bytes_transferred; -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -namespace detail -{ - template - class write_at_op - : detail::base_from_completion_cond - { - public: - write_at_op(AsyncRandomAccessWriteDevice& device, - uint64_t offset, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, WriteHandler& handler) - : detail::base_from_completion_cond< - CompletionCondition>(completion_condition), - device_(device), - offset_(offset), - buffers_(buffers), - start_(0), - handler_(ASIO_MOVE_CAST(WriteHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - write_at_op(const write_at_op& other) - : detail::base_from_completion_cond(other), - device_(other.device_), - offset_(other.offset_), - buffers_(other.buffers_), - start_(other.start_), - handler_(other.handler_) - { - } - - write_at_op(write_at_op&& other) - : detail::base_from_completion_cond(other), - device_(other.device_), - offset_(other.offset_), - buffers_(other.buffers_), - start_(other.start_), - handler_(ASIO_MOVE_CAST(WriteHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - std::size_t bytes_transferred, int start = 0) - { - std::size_t max_size; - switch (start_ = start) - { - case 1: - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - do - { - device_.async_write_some_at( - offset_ + buffers_.total_consumed(), buffers_.prepare(max_size), - ASIO_MOVE_CAST(write_at_op)(*this)); - return; default: - buffers_.consume(bytes_transferred); - if ((!ec && bytes_transferred == 0) || buffers_.empty()) - break; - max_size = this->check_for_completion(ec, buffers_.total_consumed()); - } while (max_size > 0); - - handler_(ec, buffers_.total_consumed()); - } - } - - //private: - AsyncRandomAccessWriteDevice& device_; - uint64_t offset_; - asio::detail::consuming_buffers buffers_; - int start_; - WriteHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - write_at_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - write_at_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - write_at_op* this_handler) - { - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - write_at_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - write_at_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void start_write_at_buffer_sequence_op(AsyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - const ConstBufferIterator&, CompletionCondition completion_condition, - WriteHandler& handler) - { - detail::write_at_op( - d, offset, buffers, completion_condition, handler)( - asio::error_code(), 0, 1); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::write_at_op, - Allocator> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::write_at_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::write_at_op, - Executor> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::write_at_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - detail::start_write_at_buffer_sequence_op(d, offset, buffers, - asio::buffer_sequence_begin(buffers), completion_condition, - init.completion_handler); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - detail::start_write_at_buffer_sequence_op(d, offset, buffers, - asio::buffer_sequence_begin(buffers), transfer_all(), - init.completion_handler); - - return init.result.get(); -} - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -namespace detail -{ - template - class write_at_streambuf_op - { - public: - write_at_streambuf_op( - asio::basic_streambuf& streambuf, - WriteHandler& handler) - : streambuf_(streambuf), - handler_(ASIO_MOVE_CAST(WriteHandler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - write_at_streambuf_op(const write_at_streambuf_op& other) - : streambuf_(other.streambuf_), - handler_(other.handler_) - { - } - - write_at_streambuf_op(write_at_streambuf_op&& other) - : streambuf_(other.streambuf_), - handler_(ASIO_MOVE_CAST(WriteHandler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(const asio::error_code& ec, - const std::size_t bytes_transferred) - { - streambuf_.consume(bytes_transferred); - handler_(ec, bytes_transferred); - } - - //private: - asio::basic_streambuf& streambuf_; - WriteHandler handler_; - }; - - template - inline void* asio_handler_allocate(std::size_t size, - write_at_streambuf_op* this_handler) - { - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); - } - - template - inline void asio_handler_deallocate(void* pointer, std::size_t size, - write_at_streambuf_op* this_handler) - { - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); - } - - template - inline bool asio_handler_is_continuation( - write_at_streambuf_op* this_handler) - { - return asio_handler_cont_helpers::is_continuation( - this_handler->handler_); - } - - template - inline void asio_handler_invoke(Function& function, - write_at_streambuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline void asio_handler_invoke(const Function& function, - write_at_streambuf_op* this_handler) - { - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); - } - - template - inline write_at_streambuf_op - make_write_at_streambuf_op( - asio::basic_streambuf& b, WriteHandler handler) - { - return write_at_streambuf_op(b, handler); - } -} // namespace detail - -#if !defined(GENERATING_DOCUMENTATION) - -template -struct associated_allocator< - detail::write_at_streambuf_op, - Allocator1> -{ - typedef typename associated_allocator::type type; - - static type get( - const detail::write_at_streambuf_op& h, - const Allocator1& a = Allocator1()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - detail::write_at_streambuf_op, - Executor1> -{ - typedef typename associated_executor::type type; - - static type get( - const detail::write_at_streambuf_op& h, - const Executor1& ex = Executor1()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -#endif // !defined(GENERATING_DOCUMENTATION) - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, - uint64_t offset, asio::basic_streambuf& b, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - async_write_at(d, offset, b.data(), completion_condition, - detail::write_at_streambuf_op( - b, init.completion_handler)); - - return init.result.get(); -} - -template -inline ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, - uint64_t offset, asio::basic_streambuf& b, - ASIO_MOVE_ARG(WriteHandler) handler) -{ - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - async_write_at(d, offset, b.data(), transfer_all(), - detail::write_at_streambuf_op( - b, init.completion_handler)); - - return init.result.get(); -} - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IMPL_WRITE_AT_HPP diff --git a/scout_sdk/asio/asio/io_context.hpp b/scout_sdk/asio/asio/io_context.hpp deleted file mode 100644 index 4d93be4..0000000 --- a/scout_sdk/asio/asio/io_context.hpp +++ /dev/null @@ -1,876 +0,0 @@ -// -// io_context.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IO_CONTEXT_HPP -#define ASIO_IO_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include "asio/async_result.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/wrapped_handler.hpp" -#include "asio/error_code.hpp" -#include "asio/execution_context.hpp" - -#if defined(ASIO_HAS_CHRONO) -# include "asio/detail/chrono.hpp" -#endif // defined(ASIO_HAS_CHRONO) - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# include "asio/detail/winsock_init.hpp" -#elif defined(__sun) || defined(__QNX__) || defined(__hpux) || defined(_AIX) \ - || defined(__osf__) -# include "asio/detail/signal_init.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail { -#if defined(ASIO_HAS_IOCP) - typedef class win_iocp_io_context io_context_impl; - class win_iocp_overlapped_ptr; -#else - typedef class scheduler io_context_impl; -#endif -} // namespace detail - -/// Provides core I/O functionality. -/** - * The io_context class provides the core I/O functionality for users of the - * asynchronous I/O objects, including: - * - * @li asio::ip::tcp::socket - * @li asio::ip::tcp::acceptor - * @li asio::ip::udp::socket - * @li asio::deadline_timer. - * - * The io_context class also includes facilities intended for developers of - * custom asynchronous services. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe, with the specific exceptions of the restart() - * and notify_fork() functions. Calling restart() while there are unfinished - * run(), run_one(), run_for(), run_until(), poll() or poll_one() calls results - * in undefined behaviour. The notify_fork() function should not be called - * while any io_context function, or any function on an I/O object that is - * associated with the io_context, is being called in another thread. - * - * @par Concepts: - * Dispatcher. - * - * @par Synchronous and asynchronous operations - * - * Synchronous operations on I/O objects implicitly run the io_context object - * for an individual operation. The io_context functions run(), run_one(), - * run_for(), run_until(), poll() or poll_one() must be called for the - * io_context to perform asynchronous operations on behalf of a C++ program. - * Notification that an asynchronous operation has completed is delivered by - * invocation of the associated handler. Handlers are invoked only by a thread - * that is currently calling any overload of run(), run_one(), run_for(), - * run_until(), poll() or poll_one() for the io_context. - * - * @par Effect of exceptions thrown from handlers - * - * If an exception is thrown from a handler, the exception is allowed to - * propagate through the throwing thread's invocation of run(), run_one(), - * run_for(), run_until(), poll() or poll_one(). No other threads that are - * calling any of these functions are affected. It is then the responsibility - * of the application to catch the exception. - * - * After the exception has been caught, the run(), run_one(), run_for(), - * run_until(), poll() or poll_one() call may be restarted @em without the need - * for an intervening call to restart(). This allows the thread to rejoin the - * io_context object's thread pool without impacting any other threads in the - * pool. - * - * For example: - * - * @code - * asio::io_context io_context; - * ... - * for (;;) - * { - * try - * { - * io_context.run(); - * break; // run() exited normally - * } - * catch (my_exception& e) - * { - * // Deal with exception as appropriate. - * } - * } - * @endcode - * - * @par Submitting arbitrary tasks to the io_context - * - * To submit functions to the io_context, use the @ref asio::dispatch, - * @ref asio::post or @ref asio::defer free functions. - * - * For example: - * - * @code void my_task() - * { - * ... - * } - * - * ... - * - * asio::io_context io_context; - * - * // Submit a function to the io_context. - * asio::post(io_context, my_task); - * - * // Submit a lambda object to the io_context. - * asio::post(io_context, - * []() - * { - * ... - * }); - * - * // Run the io_context until it runs out of work. - * io_context.run(); @endcode - * - * @par Stopping the io_context from running out of work - * - * Some applications may need to prevent an io_context object's run() call from - * returning when there is no more work to do. For example, the io_context may - * be being run in a background thread that is launched prior to the - * application's asynchronous operations. The run() call may be kept running by - * creating an object of type - * asio::executor_work_guard: - * - * @code asio::io_context io_context; - * asio::executor_work_guard - * = asio::make_work_guard(io_context); - * ... @endcode - * - * To effect a shutdown, the application will then need to call the io_context - * object's stop() member function. This will cause the io_context run() call - * to return as soon as possible, abandoning unfinished operations and without - * permitting ready handlers to be dispatched. - * - * Alternatively, if the application requires that all operations and handlers - * be allowed to finish normally, the work object may be explicitly reset. - * - * @code asio::io_context io_context; - * asio::executor_work_guard - * = asio::make_work_guard(io_context); - * ... - * work.reset(); // Allow run() to exit. @endcode - */ -class io_context - : public execution_context -{ -private: - typedef detail::io_context_impl impl_type; -#if defined(ASIO_HAS_IOCP) - friend class detail::win_iocp_overlapped_ptr; -#endif - -public: - class executor_type; - friend class executor_type; - -#if !defined(ASIO_NO_DEPRECATED) - class work; - friend class work; -#endif // !defined(ASIO_NO_DEPRECATED) - - class service; - -#if !defined(ASIO_NO_EXTENSIONS) - class strand; -#endif // !defined(ASIO_NO_EXTENSIONS) - - /// The type used to count the number of handlers executed by the context. - typedef std::size_t count_type; - - /// Constructor. - ASIO_DECL io_context(); - - /// Constructor. - /** - * Construct with a hint about the required level of concurrency. - * - * @param concurrency_hint A suggestion to the implementation on how many - * threads it should allow to run simultaneously. - */ - ASIO_DECL explicit io_context(int concurrency_hint); - - /// Destructor. - /** - * On destruction, the io_context performs the following sequence of - * operations: - * - * @li For each service object @c svc in the io_context set, in reverse order - * of the beginning of service object lifetime, performs - * @c svc->shutdown(). - * - * @li Uninvoked handler objects that were scheduled for deferred invocation - * on the io_context, or any associated strand, are destroyed. - * - * @li For each service object @c svc in the io_context set, in reverse order - * of the beginning of service object lifetime, performs - * delete static_cast(svc). - * - * @note The destruction sequence described above permits programs to - * simplify their resource management by using @c shared_ptr<>. Where an - * object's lifetime is tied to the lifetime of a connection (or some other - * sequence of asynchronous operations), a @c shared_ptr to the object would - * be bound into the handlers for all asynchronous operations associated with - * it. This works as follows: - * - * @li When a single connection ends, all associated asynchronous operations - * complete. The corresponding handler objects are destroyed, and all - * @c shared_ptr references to the objects are destroyed. - * - * @li To shut down the whole program, the io_context function stop() is - * called to terminate any run() calls as soon as possible. The io_context - * destructor defined above destroys all handlers, causing all @c shared_ptr - * references to all connection objects to be destroyed. - */ - ASIO_DECL ~io_context(); - - /// Obtains the executor associated with the io_context. - executor_type get_executor() ASIO_NOEXCEPT; - - /// Run the io_context object's event processing loop. - /** - * The run() function blocks until all work has finished and there are no - * more handlers to be dispatched, or until the io_context has been stopped. - * - * Multiple threads may call the run() function to set up a pool of threads - * from which the io_context may execute handlers. All threads that are - * waiting in the pool are equivalent and the io_context may choose any one - * of them to invoke a handler. - * - * A normal exit from the run() function implies that the io_context object - * is stopped (the stopped() function returns @c true). Subsequent calls to - * run(), run_one(), poll() or poll_one() will return immediately unless there - * is a prior call to restart(). - * - * @return The number of handlers that were executed. - * - * @note Calling the run() function from a thread that is currently calling - * one of run(), run_one(), run_for(), run_until(), poll() or poll_one() on - * the same io_context object may introduce the potential for deadlock. It is - * the caller's reponsibility to avoid this. - * - * The poll() function may also be used to dispatch ready handlers, but - * without blocking. - */ - ASIO_DECL count_type run(); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use non-error_code overload.) Run the io_context object's - /// event processing loop. - /** - * The run() function blocks until all work has finished and there are no - * more handlers to be dispatched, or until the io_context has been stopped. - * - * Multiple threads may call the run() function to set up a pool of threads - * from which the io_context may execute handlers. All threads that are - * waiting in the pool are equivalent and the io_context may choose any one - * of them to invoke a handler. - * - * A normal exit from the run() function implies that the io_context object - * is stopped (the stopped() function returns @c true). Subsequent calls to - * run(), run_one(), poll() or poll_one() will return immediately unless there - * is a prior call to restart(). - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of handlers that were executed. - * - * @note Calling the run() function from a thread that is currently calling - * one of run(), run_one(), run_for(), run_until(), poll() or poll_one() on - * the same io_context object may introduce the potential for deadlock. It is - * the caller's reponsibility to avoid this. - * - * The poll() function may also be used to dispatch ready handlers, but - * without blocking. - */ - ASIO_DECL count_type run(asio::error_code& ec); -#endif // !defined(ASIO_NO_DEPRECATED) - -#if defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - /// Run the io_context object's event processing loop for a specified - /// duration. - /** - * The run_for() function blocks until all work has finished and there are no - * more handlers to be dispatched, until the io_context has been stopped, or - * until the specified duration has elapsed. - * - * @param rel_time The duration for which the call may block. - * - * @return The number of handlers that were executed. - */ - template - std::size_t run_for(const chrono::duration& rel_time); - - /// Run the io_context object's event processing loop until a specified time. - /** - * The run_until() function blocks until all work has finished and there are - * no more handlers to be dispatched, until the io_context has been stopped, - * or until the specified time has been reached. - * - * @param abs_time The time point until which the call may block. - * - * @return The number of handlers that were executed. - */ - template - std::size_t run_until(const chrono::time_point& abs_time); -#endif // defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - - /// Run the io_context object's event processing loop to execute at most one - /// handler. - /** - * The run_one() function blocks until one handler has been dispatched, or - * until the io_context has been stopped. - * - * @return The number of handlers that were executed. A zero return value - * implies that the io_context object is stopped (the stopped() function - * returns @c true). Subsequent calls to run(), run_one(), poll() or - * poll_one() will return immediately unless there is a prior call to - * restart(). - * - * @note Calling the run_one() function from a thread that is currently - * calling one of run(), run_one(), run_for(), run_until(), poll() or - * poll_one() on the same io_context object may introduce the potential for - * deadlock. It is the caller's reponsibility to avoid this. - */ - ASIO_DECL count_type run_one(); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use non-error_code overlaod.) Run the io_context object's - /// event processing loop to execute at most one handler. - /** - * The run_one() function blocks until one handler has been dispatched, or - * until the io_context has been stopped. - * - * @return The number of handlers that were executed. A zero return value - * implies that the io_context object is stopped (the stopped() function - * returns @c true). Subsequent calls to run(), run_one(), poll() or - * poll_one() will return immediately unless there is a prior call to - * restart(). - * - * @return The number of handlers that were executed. - * - * @note Calling the run_one() function from a thread that is currently - * calling one of run(), run_one(), run_for(), run_until(), poll() or - * poll_one() on the same io_context object may introduce the potential for - * deadlock. It is the caller's reponsibility to avoid this. - */ - ASIO_DECL count_type run_one(asio::error_code& ec); -#endif // !defined(ASIO_NO_DEPRECATED) - -#if defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - /// Run the io_context object's event processing loop for a specified duration - /// to execute at most one handler. - /** - * The run_one_for() function blocks until one handler has been dispatched, - * until the io_context has been stopped, or until the specified duration has - * elapsed. - * - * @param rel_time The duration for which the call may block. - * - * @return The number of handlers that were executed. - */ - template - std::size_t run_one_for(const chrono::duration& rel_time); - - /// Run the io_context object's event processing loop until a specified time - /// to execute at most one handler. - /** - * The run_one_until() function blocks until one handler has been dispatched, - * until the io_context has been stopped, or until the specified time has - * been reached. - * - * @param abs_time The time point until which the call may block. - * - * @return The number of handlers that were executed. - */ - template - std::size_t run_one_until( - const chrono::time_point& abs_time); -#endif // defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - - /// Run the io_context object's event processing loop to execute ready - /// handlers. - /** - * The poll() function runs handlers that are ready to run, without blocking, - * until the io_context has been stopped or there are no more ready handlers. - * - * @return The number of handlers that were executed. - */ - ASIO_DECL count_type poll(); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use non-error_code overload.) Run the io_context object's - /// event processing loop to execute ready handlers. - /** - * The poll() function runs handlers that are ready to run, without blocking, - * until the io_context has been stopped or there are no more ready handlers. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of handlers that were executed. - */ - ASIO_DECL count_type poll(asio::error_code& ec); -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Run the io_context object's event processing loop to execute one ready - /// handler. - /** - * The poll_one() function runs at most one handler that is ready to run, - * without blocking. - * - * @return The number of handlers that were executed. - */ - ASIO_DECL count_type poll_one(); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use non-error_code overload.) Run the io_context object's - /// event processing loop to execute one ready handler. - /** - * The poll_one() function runs at most one handler that is ready to run, - * without blocking. - * - * @param ec Set to indicate what error occurred, if any. - * - * @return The number of handlers that were executed. - */ - ASIO_DECL count_type poll_one(asio::error_code& ec); -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Stop the io_context object's event processing loop. - /** - * This function does not block, but instead simply signals the io_context to - * stop. All invocations of its run() or run_one() member functions should - * return as soon as possible. Subsequent calls to run(), run_one(), poll() - * or poll_one() will return immediately until restart() is called. - */ - ASIO_DECL void stop(); - - /// Determine whether the io_context object has been stopped. - /** - * This function is used to determine whether an io_context object has been - * stopped, either through an explicit call to stop(), or due to running out - * of work. When an io_context object is stopped, calls to run(), run_one(), - * poll() or poll_one() will return immediately without invoking any - * handlers. - * - * @return @c true if the io_context object is stopped, otherwise @c false. - */ - ASIO_DECL bool stopped() const; - - /// Restart the io_context in preparation for a subsequent run() invocation. - /** - * This function must be called prior to any second or later set of - * invocations of the run(), run_one(), poll() or poll_one() functions when a - * previous invocation of these functions returned due to the io_context - * being stopped or running out of work. After a call to restart(), the - * io_context object's stopped() function will return @c false. - * - * This function must not be called while there are any unfinished calls to - * the run(), run_one(), poll() or poll_one() functions. - */ - ASIO_DECL void restart(); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use restart().) Reset the io_context in preparation for a - /// subsequent run() invocation. - /** - * This function must be called prior to any second or later set of - * invocations of the run(), run_one(), poll() or poll_one() functions when a - * previous invocation of these functions returned due to the io_context - * being stopped or running out of work. After a call to restart(), the - * io_context object's stopped() function will return @c false. - * - * This function must not be called while there are any unfinished calls to - * the run(), run_one(), poll() or poll_one() functions. - */ - void reset(); - - /// (Deprecated: Use asio::dispatch().) Request the io_context to - /// invoke the given handler. - /** - * This function is used to ask the io_context to execute the given handler. - * - * The io_context guarantees that the handler will only be called in a thread - * in which the run(), run_one(), poll() or poll_one() member functions is - * currently being invoked. The handler may be executed inside this function - * if the guarantee can be met. - * - * @param handler The handler to be called. The io_context will make - * a copy of the handler object as required. The function signature of the - * handler must be: @code void handler(); @endcode - * - * @note This function throws an exception only if: - * - * @li the handler's @c asio_handler_allocate function; or - * - * @li the handler's copy constructor - * - * throws an exception. - */ - template - ASIO_INITFN_RESULT_TYPE(LegacyCompletionHandler, void ()) - dispatch(ASIO_MOVE_ARG(LegacyCompletionHandler) handler); - - /// (Deprecated: Use asio::post().) Request the io_context to invoke - /// the given handler and return immediately. - /** - * This function is used to ask the io_context to execute the given handler, - * but without allowing the io_context to call the handler from inside this - * function. - * - * The io_context guarantees that the handler will only be called in a thread - * in which the run(), run_one(), poll() or poll_one() member functions is - * currently being invoked. - * - * @param handler The handler to be called. The io_context will make - * a copy of the handler object as required. The function signature of the - * handler must be: @code void handler(); @endcode - * - * @note This function throws an exception only if: - * - * @li the handler's @c asio_handler_allocate function; or - * - * @li the handler's copy constructor - * - * throws an exception. - */ - template - ASIO_INITFN_RESULT_TYPE(LegacyCompletionHandler, void ()) - post(ASIO_MOVE_ARG(LegacyCompletionHandler) handler); - - /// (Deprecated: Use asio::bind_executor().) Create a new handler that - /// automatically dispatches the wrapped handler on the io_context. - /** - * This function is used to create a new handler function object that, when - * invoked, will automatically pass the wrapped handler to the io_context - * object's dispatch function. - * - * @param handler The handler to be wrapped. The io_context will make a copy - * of the handler object as required. The function signature of the handler - * must be: @code void handler(A1 a1, ... An an); @endcode - * - * @return A function object that, when invoked, passes the wrapped handler to - * the io_context object's dispatch function. Given a function object with the - * signature: - * @code R f(A1 a1, ... An an); @endcode - * If this function object is passed to the wrap function like so: - * @code io_context.wrap(f); @endcode - * then the return value is a function object with the signature - * @code void g(A1 a1, ... An an); @endcode - * that, when invoked, executes code equivalent to: - * @code io_context.dispatch(boost::bind(f, a1, ... an)); @endcode - */ - template -#if defined(GENERATING_DOCUMENTATION) - unspecified -#else - detail::wrapped_handler -#endif - wrap(Handler handler); -#endif // !defined(ASIO_NO_DEPRECATED) - -private: - // Helper function to add the implementation. - ASIO_DECL impl_type& add_impl(impl_type* impl); - - // Backwards compatible overload for use with services derived from - // io_context::service. - template - friend Service& use_service(io_context& ioc); - -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - detail::winsock_init<> init_; -#elif defined(__sun) || defined(__QNX__) || defined(__hpux) || defined(_AIX) \ - || defined(__osf__) - detail::signal_init<> init_; -#endif - - // The implementation. - impl_type& impl_; -}; - -/// Executor used to submit functions to an io_context. -class io_context::executor_type -{ -public: - /// Obtain the underlying execution context. - io_context& context() const ASIO_NOEXCEPT; - - /// Inform the io_context that it has some outstanding work to do. - /** - * This function is used to inform the io_context that some work has begun. - * This ensures that the io_context's run() and run_one() functions do not - * exit while the work is underway. - */ - void on_work_started() const ASIO_NOEXCEPT; - - /// Inform the io_context that some work is no longer outstanding. - /** - * This function is used to inform the io_context that some work has - * finished. Once the count of unfinished work reaches zero, the io_context - * is stopped and the run() and run_one() functions may exit. - */ - void on_work_finished() const ASIO_NOEXCEPT; - - /// Request the io_context to invoke the given function object. - /** - * This function is used to ask the io_context to execute the given function - * object. If the current thread is running the io_context, @c dispatch() - * executes the function before returning. Otherwise, the function will be - * scheduled to run on the io_context. - * - * @param f The function object to be called. The executor will make a copy - * of the handler object as required. The function signature of the function - * object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void dispatch(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the io_context to invoke the given function object. - /** - * This function is used to ask the io_context to execute the given function - * object. The function object will never be executed inside @c post(). - * Instead, it will be scheduled to run on the io_context. - * - * @param f The function object to be called. The executor will make a copy - * of the handler object as required. The function signature of the function - * object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void post(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the io_context to invoke the given function object. - /** - * This function is used to ask the io_context to execute the given function - * object. The function object will never be executed inside @c defer(). - * Instead, it will be scheduled to run on the io_context. - * - * If the current thread belongs to the io_context, @c defer() will delay - * scheduling the function object until the current thread returns control to - * the pool. - * - * @param f The function object to be called. The executor will make a copy - * of the handler object as required. The function signature of the function - * object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void defer(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Determine whether the io_context is running in the current thread. - /** - * @return @c true if the current thread is running the io_context. Otherwise - * returns @c false. - */ - bool running_in_this_thread() const ASIO_NOEXCEPT; - - /// Compare two executors for equality. - /** - * Two executors are equal if they refer to the same underlying io_context. - */ - friend bool operator==(const executor_type& a, - const executor_type& b) ASIO_NOEXCEPT - { - return &a.io_context_ == &b.io_context_; - } - - /// Compare two executors for inequality. - /** - * Two executors are equal if they refer to the same underlying io_context. - */ - friend bool operator!=(const executor_type& a, - const executor_type& b) ASIO_NOEXCEPT - { - return &a.io_context_ != &b.io_context_; - } - -private: - friend class io_context; - - // Constructor. - explicit executor_type(io_context& i) : io_context_(i) {} - - // The underlying io_context. - io_context& io_context_; -}; - -#if !defined(ASIO_NO_DEPRECATED) -/// (Deprecated: Use executor_work_guard.) Class to inform the io_context when -/// it has work to do. -/** - * The work class is used to inform the io_context when work starts and - * finishes. This ensures that the io_context object's run() function will not - * exit while work is underway, and that it does exit when there is no - * unfinished work remaining. - * - * The work class is copy-constructible so that it may be used as a data member - * in a handler class. It is not assignable. - */ -class io_context::work -{ -public: - /// Constructor notifies the io_context that work is starting. - /** - * The constructor is used to inform the io_context that some work has begun. - * This ensures that the io_context object's run() function will not exit - * while the work is underway. - */ - explicit work(asio::io_context& io_context); - - /// Copy constructor notifies the io_context that work is starting. - /** - * The constructor is used to inform the io_context that some work has begun. - * This ensures that the io_context object's run() function will not exit - * while the work is underway. - */ - work(const work& other); - - /// Destructor notifies the io_context that the work is complete. - /** - * The destructor is used to inform the io_context that some work has - * finished. Once the count of unfinished work reaches zero, the io_context - * object's run() function is permitted to exit. - */ - ~work(); - - /// Get the io_context associated with the work. - asio::io_context& get_io_context(); - - /// (Deprecated: Use get_io_context().) Get the io_context associated with the - /// work. - asio::io_context& get_io_service(); - -private: - // Prevent assignment. - void operator=(const work& other); - - // The io_context implementation. - detail::io_context_impl& io_context_impl_; -}; -#endif // !defined(ASIO_NO_DEPRECATED) - -/// Base class for all io_context services. -class io_context::service - : public execution_context::service -{ -public: - /// Get the io_context object that owns the service. - asio::io_context& get_io_context(); - -#if !defined(ASIO_NO_DEPRECATED) - /// Get the io_context object that owns the service. - asio::io_context& get_io_service(); -#endif // !defined(ASIO_NO_DEPRECATED) - -private: - /// Destroy all user-defined handler objects owned by the service. - ASIO_DECL virtual void shutdown(); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use shutdown().) Destroy all user-defined handler objects - /// owned by the service. - ASIO_DECL virtual void shutdown_service(); -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Handle notification of a fork-related event to perform any necessary - /// housekeeping. - /** - * This function is not a pure virtual so that services only have to - * implement it if necessary. The default implementation does nothing. - */ - ASIO_DECL virtual void notify_fork( - execution_context::fork_event event); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use notify_fork().) Handle notification of a fork-related - /// event to perform any necessary housekeeping. - /** - * This function is not a pure virtual so that services only have to - * implement it if necessary. The default implementation does nothing. - */ - ASIO_DECL virtual void fork_service( - execution_context::fork_event event); -#endif // !defined(ASIO_NO_DEPRECATED) - -protected: - /// Constructor. - /** - * @param owner The io_context object that owns the service. - */ - ASIO_DECL service(asio::io_context& owner); - - /// Destructor. - ASIO_DECL virtual ~service(); -}; - -namespace detail { - -// Special service base class to keep classes header-file only. -template -class service_base - : public asio::io_context::service -{ -public: - static asio::detail::service_id id; - - // Constructor. - service_base(asio::io_context& io_context) - : asio::io_context::service(io_context) - { - } -}; - -template -asio::detail::service_id service_base::id; - -} // namespace detail -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/io_context.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/io_context.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -// If both io_context.hpp and strand.hpp have been included, automatically -// include the header file needed for the io_context::strand class. -#if !defined(ASIO_NO_EXTENSIONS) -# if defined(ASIO_STRAND_HPP) -# include "asio/io_context_strand.hpp" -# endif // defined(ASIO_STRAND_HPP) -#endif // !defined(ASIO_NO_EXTENSIONS) - -#endif // ASIO_IO_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/io_context_strand.hpp b/scout_sdk/asio/asio/io_context_strand.hpp deleted file mode 100644 index 3c596f1..0000000 --- a/scout_sdk/asio/asio/io_context_strand.hpp +++ /dev/null @@ -1,384 +0,0 @@ -// -// io_context_strand.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IO_CONTEXT_STRAND_HPP -#define ASIO_IO_CONTEXT_STRAND_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_NO_EXTENSIONS) - -#include "asio/async_result.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/strand_service.hpp" -#include "asio/detail/wrapped_handler.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides serialised handler execution. -/** - * The io_context::strand class provides the ability to post and dispatch - * handlers with the guarantee that none of those handlers will execute - * concurrently. - * - * @par Order of handler invocation - * Given: - * - * @li a strand object @c s - * - * @li an object @c a meeting completion handler requirements - * - * @li an object @c a1 which is an arbitrary copy of @c a made by the - * implementation - * - * @li an object @c b meeting completion handler requirements - * - * @li an object @c b1 which is an arbitrary copy of @c b made by the - * implementation - * - * if any of the following conditions are true: - * - * @li @c s.post(a) happens-before @c s.post(b) - * - * @li @c s.post(a) happens-before @c s.dispatch(b), where the latter is - * performed outside the strand - * - * @li @c s.dispatch(a) happens-before @c s.post(b), where the former is - * performed outside the strand - * - * @li @c s.dispatch(a) happens-before @c s.dispatch(b), where both are - * performed outside the strand - * - * then @c asio_handler_invoke(a1, &a1) happens-before - * @c asio_handler_invoke(b1, &b1). - * - * Note that in the following case: - * @code async_op_1(..., s.wrap(a)); - * async_op_2(..., s.wrap(b)); @endcode - * the completion of the first async operation will perform @c s.dispatch(a), - * and the second will perform @c s.dispatch(b), but the order in which those - * are performed is unspecified. That is, you cannot state whether one - * happens-before the other. Therefore none of the above conditions are met and - * no ordering guarantee is made. - * - * @note The implementation makes no guarantee that handlers posted or - * dispatched through different @c strand objects will be invoked concurrently. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Dispatcher. - */ -class io_context::strand -{ -public: - /// Constructor. - /** - * Constructs the strand. - * - * @param io_context The io_context object that the strand will use to - * dispatch handlers that are ready to be run. - */ - explicit strand(asio::io_context& io_context) - : service_(asio::use_service< - asio::detail::strand_service>(io_context)) - { - service_.construct(impl_); - } - - /// Destructor. - /** - * Destroys a strand. - * - * Handlers posted through the strand that have not yet been invoked will - * still be dispatched in a way that meets the guarantee of non-concurrency. - */ - ~strand() - { - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use context().) Get the io_context associated with the - /// strand. - /** - * This function may be used to obtain the io_context object that the strand - * uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the strand will use to - * dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return service_.get_io_context(); - } - - /// (Deprecated: Use context().) Get the io_context associated with the - /// strand. - /** - * This function may be used to obtain the io_context object that the strand - * uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the strand will use to - * dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return service_.get_io_context(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Obtain the underlying execution context. - asio::io_context& context() const ASIO_NOEXCEPT - { - return service_.get_io_context(); - } - - /// Inform the strand that it has some outstanding work to do. - /** - * The strand delegates this call to its underlying io_context. - */ - void on_work_started() const ASIO_NOEXCEPT - { - context().get_executor().on_work_started(); - } - - /// Inform the strand that some work is no longer outstanding. - /** - * The strand delegates this call to its underlying io_context. - */ - void on_work_finished() const ASIO_NOEXCEPT - { - context().get_executor().on_work_finished(); - } - - /// Request the strand to invoke the given function object. - /** - * This function is used to ask the strand to execute the given function - * object on its underlying io_context. The function object will be executed - * inside this function if the strand is not otherwise busy and if the - * underlying io_context's executor's @c dispatch() function is also able to - * execute the function before returning. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void dispatch(ASIO_MOVE_ARG(Function) f, const Allocator& a) const - { - typename decay::type tmp(ASIO_MOVE_CAST(Function)(f)); - service_.dispatch(impl_, tmp); - (void)a; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use asio::dispatch().) Request the strand to invoke - /// the given handler. - /** - * This function is used to ask the strand to execute the given handler. - * - * The strand object guarantees that handlers posted or dispatched through - * the strand will not be executed concurrently. The handler may be executed - * inside this function if the guarantee can be met. If this function is - * called from within a handler that was posted or dispatched through the same - * strand, then the new handler will be executed immediately. - * - * The strand's guarantee is in addition to the guarantee provided by the - * underlying io_context. The io_context guarantees that the handler will only - * be called in a thread in which the io_context's run member function is - * currently being invoked. - * - * @param handler The handler to be called. The strand will make a copy of the - * handler object as required. The function signature of the handler must be: - * @code void handler(); @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(LegacyCompletionHandler, void ()) - dispatch(ASIO_MOVE_ARG(LegacyCompletionHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a LegacyCompletionHandler. - ASIO_LEGACY_COMPLETION_HANDLER_CHECK( - LegacyCompletionHandler, handler) type_check; - - async_completion init(handler); - - service_.dispatch(impl_, init.completion_handler); - - return init.result.get(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Request the strand to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object will never be executed inside this function. - * Instead, it will be scheduled to run by the underlying io_context. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void post(ASIO_MOVE_ARG(Function) f, const Allocator& a) const - { - typename decay::type tmp(ASIO_MOVE_CAST(Function)(f)); - service_.post(impl_, tmp); - (void)a; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use asio::post().) Request the strand to invoke the - /// given handler and return immediately. - /** - * This function is used to ask the strand to execute the given handler, but - * without allowing the strand to call the handler from inside this function. - * - * The strand object guarantees that handlers posted or dispatched through - * the strand will not be executed concurrently. The strand's guarantee is in - * addition to the guarantee provided by the underlying io_context. The - * io_context guarantees that the handler will only be called in a thread in - * which the io_context's run member function is currently being invoked. - * - * @param handler The handler to be called. The strand will make a copy of the - * handler object as required. The function signature of the handler must be: - * @code void handler(); @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(LegacyCompletionHandler, void ()) - post(ASIO_MOVE_ARG(LegacyCompletionHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a LegacyCompletionHandler. - ASIO_LEGACY_COMPLETION_HANDLER_CHECK( - LegacyCompletionHandler, handler) type_check; - - async_completion init(handler); - - service_.post(impl_, init.completion_handler); - - return init.result.get(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Request the strand to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object will never be executed inside this function. - * Instead, it will be scheduled to run by the underlying io_context. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void defer(ASIO_MOVE_ARG(Function) f, const Allocator& a) const - { - typename decay::type tmp(ASIO_MOVE_CAST(Function)(f)); - service_.post(impl_, tmp); - (void)a; - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use asio::bind_executor().) Create a new handler that - /// automatically dispatches the wrapped handler on the strand. - /** - * This function is used to create a new handler function object that, when - * invoked, will automatically pass the wrapped handler to the strand's - * dispatch function. - * - * @param handler The handler to be wrapped. The strand will make a copy of - * the handler object as required. The function signature of the handler must - * be: @code void handler(A1 a1, ... An an); @endcode - * - * @return A function object that, when invoked, passes the wrapped handler to - * the strand's dispatch function. Given a function object with the signature: - * @code R f(A1 a1, ... An an); @endcode - * If this function object is passed to the wrap function like so: - * @code strand.wrap(f); @endcode - * then the return value is a function object with the signature - * @code void g(A1 a1, ... An an); @endcode - * that, when invoked, executes code equivalent to: - * @code strand.dispatch(boost::bind(f, a1, ... an)); @endcode - */ - template -#if defined(GENERATING_DOCUMENTATION) - unspecified -#else - detail::wrapped_handler -#endif - wrap(Handler handler) - { - return detail::wrapped_handler(*this, handler); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Determine whether the strand is running in the current thread. - /** - * @return @c true if the current thread is executing a handler that was - * submitted to the strand using post(), dispatch() or wrap(). Otherwise - * returns @c false. - */ - bool running_in_this_thread() const ASIO_NOEXCEPT - { - return service_.running_in_this_thread(impl_); - } - - /// Compare two strands for equality. - /** - * Two strands are equal if they refer to the same ordered, non-concurrent - * state. - */ - friend bool operator==(const strand& a, const strand& b) ASIO_NOEXCEPT - { - return a.impl_ == b.impl_; - } - - /// Compare two strands for inequality. - /** - * Two strands are equal if they refer to the same ordered, non-concurrent - * state. - */ - friend bool operator!=(const strand& a, const strand& b) ASIO_NOEXCEPT - { - return a.impl_ != b.impl_; - } - -private: - asio::detail::strand_service& service_; - mutable asio::detail::strand_service::implementation_type impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_EXTENSIONS) - -#endif // ASIO_IO_CONTEXT_STRAND_HPP diff --git a/scout_sdk/asio/asio/io_service.hpp b/scout_sdk/asio/asio/io_service.hpp deleted file mode 100644 index ed05c83..0000000 --- a/scout_sdk/asio/asio/io_service.hpp +++ /dev/null @@ -1,33 +0,0 @@ -// -// io_service.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IO_SERVICE_HPP -#define ASIO_IO_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if !defined(ASIO_NO_DEPRECATED) -/// Typedef for backwards compatibility. -typedef io_context io_service; -#endif // !defined(ASIO_NO_DEPRECATED) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IO_SERVICE_HPP diff --git a/scout_sdk/asio/asio/io_service_strand.hpp b/scout_sdk/asio/asio/io_service_strand.hpp deleted file mode 100644 index 7093f0e..0000000 --- a/scout_sdk/asio/asio/io_service_strand.hpp +++ /dev/null @@ -1,20 +0,0 @@ -// -// io_service_strand.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IO_SERVICE_STRAND_HPP -#define ASIO_IO_SERVICE_STRAND_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/io_context_strand.hpp" - -#endif // ASIO_IO_SERVICE_STRAND_HPP diff --git a/scout_sdk/asio/asio/ip/address.hpp b/scout_sdk/asio/asio/ip/address.hpp deleted file mode 100644 index cf852a6..0000000 --- a/scout_sdk/asio/asio/ip/address.hpp +++ /dev/null @@ -1,260 +0,0 @@ -// -// ip/address.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ADDRESS_HPP -#define ASIO_IP_ADDRESS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/throw_exception.hpp" -#include "asio/detail/string_view.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error_code.hpp" -#include "asio/ip/address_v4.hpp" -#include "asio/ip/address_v6.hpp" -#include "asio/ip/bad_address_cast.hpp" - -#if !defined(ASIO_NO_IOSTREAM) -# include -#endif // !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Implements version-independent IP addresses. -/** - * The asio::ip::address class provides the ability to use either IP - * version 4 or version 6 addresses. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class address -{ -public: - /// Default constructor. - ASIO_DECL address(); - - /// Construct an address from an IPv4 address. - ASIO_DECL address(const asio::ip::address_v4& ipv4_address); - - /// Construct an address from an IPv6 address. - ASIO_DECL address(const asio::ip::address_v6& ipv6_address); - - /// Copy constructor. - ASIO_DECL address(const address& other); - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - ASIO_DECL address(address&& other); -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from another address. - ASIO_DECL address& operator=(const address& other); - -#if defined(ASIO_HAS_MOVE) - /// Move-assign from another address. - ASIO_DECL address& operator=(address&& other); -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from an IPv4 address. - ASIO_DECL address& operator=( - const asio::ip::address_v4& ipv4_address); - - /// Assign from an IPv6 address. - ASIO_DECL address& operator=( - const asio::ip::address_v6& ipv6_address); - - /// Get whether the address is an IP version 4 address. - bool is_v4() const - { - return type_ == ipv4; - } - - /// Get whether the address is an IP version 6 address. - bool is_v6() const - { - return type_ == ipv6; - } - - /// Get the address as an IP version 4 address. - ASIO_DECL asio::ip::address_v4 to_v4() const; - - /// Get the address as an IP version 6 address. - ASIO_DECL asio::ip::address_v6 to_v6() const; - - /// Get the address as a string. - ASIO_DECL std::string to_string() const; - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use other overload.) Get the address as a string. - ASIO_DECL std::string to_string(asio::error_code& ec) const; - - /// (Deprecated: Use make_address().) Create an address from an IPv4 address - /// string in dotted decimal form, or from an IPv6 address in hexadecimal - /// notation. - static address from_string(const char* str); - - /// (Deprecated: Use make_address().) Create an address from an IPv4 address - /// string in dotted decimal form, or from an IPv6 address in hexadecimal - /// notation. - static address from_string(const char* str, asio::error_code& ec); - - /// (Deprecated: Use make_address().) Create an address from an IPv4 address - /// string in dotted decimal form, or from an IPv6 address in hexadecimal - /// notation. - static address from_string(const std::string& str); - - /// (Deprecated: Use make_address().) Create an address from an IPv4 address - /// string in dotted decimal form, or from an IPv6 address in hexadecimal - /// notation. - static address from_string( - const std::string& str, asio::error_code& ec); -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Determine whether the address is a loopback address. - ASIO_DECL bool is_loopback() const; - - /// Determine whether the address is unspecified. - ASIO_DECL bool is_unspecified() const; - - /// Determine whether the address is a multicast address. - ASIO_DECL bool is_multicast() const; - - /// Compare two addresses for equality. - ASIO_DECL friend bool operator==(const address& a1, const address& a2); - - /// Compare two addresses for inequality. - friend bool operator!=(const address& a1, const address& a2) - { - return !(a1 == a2); - } - - /// Compare addresses for ordering. - ASIO_DECL friend bool operator<(const address& a1, const address& a2); - - /// Compare addresses for ordering. - friend bool operator>(const address& a1, const address& a2) - { - return a2 < a1; - } - - /// Compare addresses for ordering. - friend bool operator<=(const address& a1, const address& a2) - { - return !(a2 < a1); - } - - /// Compare addresses for ordering. - friend bool operator>=(const address& a1, const address& a2) - { - return !(a1 < a2); - } - -private: - // The type of the address. - enum { ipv4, ipv6 } type_; - - // The underlying IPv4 address. - asio::ip::address_v4 ipv4_address_; - - // The underlying IPv6 address. - asio::ip::address_v6 ipv6_address_; -}; - -/// Create an address from an IPv4 address string in dotted decimal form, -/// or from an IPv6 address in hexadecimal notation. -/** - * @relates address - */ -ASIO_DECL address make_address(const char* str); - -/// Create an address from an IPv4 address string in dotted decimal form, -/// or from an IPv6 address in hexadecimal notation. -/** - * @relates address - */ -ASIO_DECL address make_address( - const char* str, asio::error_code& ec); - -/// Create an address from an IPv4 address string in dotted decimal form, -/// or from an IPv6 address in hexadecimal notation. -/** - * @relates address - */ -ASIO_DECL address make_address(const std::string& str); - -/// Create an address from an IPv4 address string in dotted decimal form, -/// or from an IPv6 address in hexadecimal notation. -/** - * @relates address - */ -ASIO_DECL address make_address( - const std::string& str, asio::error_code& ec); - -#if defined(ASIO_HAS_STRING_VIEW) \ - || defined(GENERATING_DOCUMENTATION) - -/// Create an address from an IPv4 address string in dotted decimal form, -/// or from an IPv6 address in hexadecimal notation. -/** - * @relates address - */ -ASIO_DECL address make_address(string_view str); - -/// Create an address from an IPv4 address string in dotted decimal form, -/// or from an IPv6 address in hexadecimal notation. -/** - * @relates address - */ -ASIO_DECL address make_address( - string_view str, asio::error_code& ec); - -#endif // defined(ASIO_HAS_STRING_VIEW) - // || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_NO_IOSTREAM) - -/// Output an address as a string. -/** - * Used to output a human-readable string for a specified address. - * - * @param os The output stream to which the string will be written. - * - * @param addr The address to be written. - * - * @return The output stream. - * - * @relates asio::ip::address - */ -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const address& addr); - -#endif // !defined(ASIO_NO_IOSTREAM) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/ip/impl/address.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/ip/impl/address.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_IP_ADDRESS_HPP diff --git a/scout_sdk/asio/asio/ip/address_v4.hpp b/scout_sdk/asio/asio/ip/address_v4.hpp deleted file mode 100644 index 4e1cc9a..0000000 --- a/scout_sdk/asio/asio/ip/address_v4.hpp +++ /dev/null @@ -1,329 +0,0 @@ -// -// ip/address_v4.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ADDRESS_V4_HPP -#define ASIO_IP_ADDRESS_V4_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/array.hpp" -#include "asio/detail/cstdint.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/string_view.hpp" -#include "asio/detail/winsock_init.hpp" -#include "asio/error_code.hpp" - -#if !defined(ASIO_NO_IOSTREAM) -# include -#endif // !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Implements IP version 4 style addresses. -/** - * The asio::ip::address_v4 class provides the ability to use and - * manipulate IP version 4 addresses. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class address_v4 -{ -public: - /// The type used to represent an address as an unsigned integer. - typedef uint_least32_t uint_type; - - /// The type used to represent an address as an array of bytes. - /** - * @note This type is defined in terms of the C++0x template @c std::array - * when it is available. Otherwise, it uses @c boost:array. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef array bytes_type; -#else - typedef asio::detail::array bytes_type; -#endif - - /// Default constructor. - address_v4() - { - addr_.s_addr = 0; - } - - /// Construct an address from raw bytes. - ASIO_DECL explicit address_v4(const bytes_type& bytes); - - /// Construct an address from an unsigned integer in host byte order. - ASIO_DECL explicit address_v4(uint_type addr); - - /// Copy constructor. - address_v4(const address_v4& other) - : addr_(other.addr_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - address_v4(address_v4&& other) - : addr_(other.addr_) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from another address. - address_v4& operator=(const address_v4& other) - { - addr_ = other.addr_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move-assign from another address. - address_v4& operator=(address_v4&& other) - { - addr_ = other.addr_; - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// Get the address in bytes, in network byte order. - ASIO_DECL bytes_type to_bytes() const; - - /// Get the address as an unsigned integer in host byte order - ASIO_DECL uint_type to_uint() const; - -#if !defined(ASIO_NO_DEPRECATED) - /// Get the address as an unsigned long in host byte order - ASIO_DECL unsigned long to_ulong() const; -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the address as a string in dotted decimal format. - ASIO_DECL std::string to_string() const; - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use other overload.) Get the address as a string in dotted - /// decimal format. - ASIO_DECL std::string to_string(asio::error_code& ec) const; - - /// (Deprecated: Use make_address_v4().) Create an address from an IP address - /// string in dotted decimal form. - static address_v4 from_string(const char* str); - - /// (Deprecated: Use make_address_v4().) Create an address from an IP address - /// string in dotted decimal form. - static address_v4 from_string( - const char* str, asio::error_code& ec); - - /// (Deprecated: Use make_address_v4().) Create an address from an IP address - /// string in dotted decimal form. - static address_v4 from_string(const std::string& str); - - /// (Deprecated: Use make_address_v4().) Create an address from an IP address - /// string in dotted decimal form. - static address_v4 from_string( - const std::string& str, asio::error_code& ec); -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Determine whether the address is a loopback address. - ASIO_DECL bool is_loopback() const; - - /// Determine whether the address is unspecified. - ASIO_DECL bool is_unspecified() const; - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use network_v4 class.) Determine whether the address is a - /// class A address. - ASIO_DECL bool is_class_a() const; - - /// (Deprecated: Use network_v4 class.) Determine whether the address is a - /// class B address. - ASIO_DECL bool is_class_b() const; - - /// (Deprecated: Use network_v4 class.) Determine whether the address is a - /// class C address. - ASIO_DECL bool is_class_c() const; -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Determine whether the address is a multicast address. - ASIO_DECL bool is_multicast() const; - - /// Compare two addresses for equality. - friend bool operator==(const address_v4& a1, const address_v4& a2) - { - return a1.addr_.s_addr == a2.addr_.s_addr; - } - - /// Compare two addresses for inequality. - friend bool operator!=(const address_v4& a1, const address_v4& a2) - { - return a1.addr_.s_addr != a2.addr_.s_addr; - } - - /// Compare addresses for ordering. - friend bool operator<(const address_v4& a1, const address_v4& a2) - { - return a1.to_uint() < a2.to_uint(); - } - - /// Compare addresses for ordering. - friend bool operator>(const address_v4& a1, const address_v4& a2) - { - return a1.to_uint() > a2.to_uint(); - } - - /// Compare addresses for ordering. - friend bool operator<=(const address_v4& a1, const address_v4& a2) - { - return a1.to_uint() <= a2.to_uint(); - } - - /// Compare addresses for ordering. - friend bool operator>=(const address_v4& a1, const address_v4& a2) - { - return a1.to_uint() >= a2.to_uint(); - } - - /// Obtain an address object that represents any address. - static address_v4 any() - { - return address_v4(); - } - - /// Obtain an address object that represents the loopback address. - static address_v4 loopback() - { - return address_v4(0x7F000001); - } - - /// Obtain an address object that represents the broadcast address. - static address_v4 broadcast() - { - return address_v4(0xFFFFFFFF); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use network_v4 class.) Obtain an address object that - /// represents the broadcast address that corresponds to the specified - /// address and netmask. - ASIO_DECL static address_v4 broadcast( - const address_v4& addr, const address_v4& mask); - - /// (Deprecated: Use network_v4 class.) Obtain the netmask that corresponds - /// to the address, based on its address class. - ASIO_DECL static address_v4 netmask(const address_v4& addr); -#endif // !defined(ASIO_NO_DEPRECATED) - -private: - // The underlying IPv4 address. - asio::detail::in4_addr_type addr_; -}; - -/// Create an IPv4 address from raw bytes in network order. -/** - * @relates address_v4 - */ -inline address_v4 make_address_v4(const address_v4::bytes_type& bytes) -{ - return address_v4(bytes); -} - -/// Create an IPv4 address from an unsigned integer in host byte order. -/** - * @relates address_v4 - */ -inline address_v4 make_address_v4(address_v4::uint_type addr) -{ - return address_v4(addr); -} - -/// Create an IPv4 address from an IP address string in dotted decimal form. -/** - * @relates address_v4 - */ -ASIO_DECL address_v4 make_address_v4(const char* str); - -/// Create an IPv4 address from an IP address string in dotted decimal form. -/** - * @relates address_v4 - */ -ASIO_DECL address_v4 make_address_v4( - const char* str, asio::error_code& ec); - -/// Create an IPv4 address from an IP address string in dotted decimal form. -/** - * @relates address_v4 - */ -ASIO_DECL address_v4 make_address_v4(const std::string& str); - -/// Create an IPv4 address from an IP address string in dotted decimal form. -/** - * @relates address_v4 - */ -ASIO_DECL address_v4 make_address_v4( - const std::string& str, asio::error_code& ec); - -#if defined(ASIO_HAS_STRING_VIEW) \ - || defined(GENERATING_DOCUMENTATION) - -/// Create an IPv4 address from an IP address string in dotted decimal form. -/** - * @relates address_v4 - */ -ASIO_DECL address_v4 make_address_v4(string_view str); - -/// Create an IPv4 address from an IP address string in dotted decimal form. -/** - * @relates address_v4 - */ -ASIO_DECL address_v4 make_address_v4( - string_view str, asio::error_code& ec); - -#endif // defined(ASIO_HAS_STRING_VIEW) - // || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_NO_IOSTREAM) - -/// Output an address as a string. -/** - * Used to output a human-readable string for a specified address. - * - * @param os The output stream to which the string will be written. - * - * @param addr The address to be written. - * - * @return The output stream. - * - * @relates asio::ip::address_v4 - */ -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const address_v4& addr); - -#endif // !defined(ASIO_NO_IOSTREAM) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/ip/impl/address_v4.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/ip/impl/address_v4.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_IP_ADDRESS_V4_HPP diff --git a/scout_sdk/asio/asio/ip/address_v4_iterator.hpp b/scout_sdk/asio/asio/ip/address_v4_iterator.hpp deleted file mode 100644 index e2ef393..0000000 --- a/scout_sdk/asio/asio/ip/address_v4_iterator.hpp +++ /dev/null @@ -1,162 +0,0 @@ -// -// ip/address_v4_iterator.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ADDRESS_V4_ITERATOR_HPP -#define ASIO_IP_ADDRESS_V4_ITERATOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ip/address_v4.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template class basic_address_iterator; - -/// An input iterator that can be used for traversing IPv4 addresses. -/** - * In addition to satisfying the input iterator requirements, this iterator - * also supports decrement. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template <> class basic_address_iterator -{ -public: - /// The type of the elements pointed to by the iterator. - typedef address_v4 value_type; - - /// Distance between two iterators. - typedef std::ptrdiff_t difference_type; - - /// The type of a pointer to an element pointed to by the iterator. - typedef const address_v4* pointer; - - /// The type of a reference to an element pointed to by the iterator. - typedef const address_v4& reference; - - /// Denotes that the iterator satisfies the input iterator requirements. - typedef std::input_iterator_tag iterator_category; - - /// Construct an iterator that points to the specified address. - basic_address_iterator(const address_v4& addr) ASIO_NOEXCEPT - : address_(addr) - { - } - - /// Copy constructor. - basic_address_iterator( - const basic_address_iterator& other) ASIO_NOEXCEPT - : address_(other.address_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - basic_address_iterator(basic_address_iterator&& other) ASIO_NOEXCEPT - : address_(ASIO_MOVE_CAST(address_v4)(other.address_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assignment operator. - basic_address_iterator& operator=( - const basic_address_iterator& other) ASIO_NOEXCEPT - { - address_ = other.address_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move assignment operator. - basic_address_iterator& operator=( - basic_address_iterator&& other) ASIO_NOEXCEPT - { - address_ = ASIO_MOVE_CAST(address_v4)(other.address_); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// Dereference the iterator. - const address_v4& operator*() const ASIO_NOEXCEPT - { - return address_; - } - - /// Dereference the iterator. - const address_v4* operator->() const ASIO_NOEXCEPT - { - return &address_; - } - - /// Pre-increment operator. - basic_address_iterator& operator++() ASIO_NOEXCEPT - { - address_ = address_v4((address_.to_uint() + 1) & 0xFFFFFFFF); - return *this; - } - - /// Post-increment operator. - basic_address_iterator operator++(int) ASIO_NOEXCEPT - { - basic_address_iterator tmp(*this); - ++*this; - return tmp; - } - - /// Pre-decrement operator. - basic_address_iterator& operator--() ASIO_NOEXCEPT - { - address_ = address_v4((address_.to_uint() - 1) & 0xFFFFFFFF); - return *this; - } - - /// Post-decrement operator. - basic_address_iterator operator--(int) - { - basic_address_iterator tmp(*this); - --*this; - return tmp; - } - - /// Compare two addresses for equality. - friend bool operator==(const basic_address_iterator& a, - const basic_address_iterator& b) - { - return a.address_ == b.address_; - } - - /// Compare two addresses for inequality. - friend bool operator!=(const basic_address_iterator& a, - const basic_address_iterator& b) - { - return a.address_ != b.address_; - } - -private: - address_v4 address_; -}; - -/// An input iterator that can be used for traversing IPv4 addresses. -typedef basic_address_iterator address_v4_iterator; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_ADDRESS_V4_ITERATOR_HPP diff --git a/scout_sdk/asio/asio/ip/address_v4_range.hpp b/scout_sdk/asio/asio/ip/address_v4_range.hpp deleted file mode 100644 index a402842..0000000 --- a/scout_sdk/asio/asio/ip/address_v4_range.hpp +++ /dev/null @@ -1,134 +0,0 @@ -// -// ip/address_v4_range.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ADDRESS_V4_RANGE_HPP -#define ASIO_IP_ADDRESS_V4_RANGE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ip/address_v4_iterator.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template class basic_address_range; - -/// Represents a range of IPv4 addresses. -/** - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template <> class basic_address_range -{ -public: - /// The type of an iterator that points into the range. - typedef basic_address_iterator iterator; - - /// Construct an empty range. - basic_address_range() ASIO_NOEXCEPT - : begin_(address_v4()), - end_(address_v4()) - { - } - - /// Construct an range that represents the given range of addresses. - explicit basic_address_range(const iterator& first, - const iterator& last) ASIO_NOEXCEPT - : begin_(first), - end_(last) - { - } - - /// Copy constructor. - basic_address_range(const basic_address_range& other) ASIO_NOEXCEPT - : begin_(other.begin_), - end_(other.end_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - basic_address_range(basic_address_range&& other) ASIO_NOEXCEPT - : begin_(ASIO_MOVE_CAST(iterator)(other.begin_)), - end_(ASIO_MOVE_CAST(iterator)(other.end_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assignment operator. - basic_address_range& operator=( - const basic_address_range& other) ASIO_NOEXCEPT - { - begin_ = other.begin_; - end_ = other.end_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move assignment operator. - basic_address_range& operator=( - basic_address_range&& other) ASIO_NOEXCEPT - { - begin_ = ASIO_MOVE_CAST(iterator)(other.begin_); - end_ = ASIO_MOVE_CAST(iterator)(other.end_); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// Obtain an iterator that points to the start of the range. - iterator begin() const ASIO_NOEXCEPT - { - return begin_; - } - - /// Obtain an iterator that points to the end of the range. - iterator end() const ASIO_NOEXCEPT - { - return end_; - } - - /// Determine whether the range is empty. - bool empty() const ASIO_NOEXCEPT - { - return size() == 0; - } - - /// Return the size of the range. - std::size_t size() const ASIO_NOEXCEPT - { - return end_->to_uint() - begin_->to_uint(); - } - - /// Find an address in the range. - iterator find(const address_v4& addr) const ASIO_NOEXCEPT - { - return addr >= *begin_ && addr < *end_ ? iterator(addr) : end_; - } - -private: - iterator begin_; - iterator end_; -}; - -/// Represents a range of IPv4 addresses. -typedef basic_address_range address_v4_range; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_ADDRESS_V4_RANGE_HPP diff --git a/scout_sdk/asio/asio/ip/address_v6.hpp b/scout_sdk/asio/asio/ip/address_v6.hpp deleted file mode 100644 index fece332..0000000 --- a/scout_sdk/asio/asio/ip/address_v6.hpp +++ /dev/null @@ -1,336 +0,0 @@ -// -// ip/address_v6.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ADDRESS_V6_HPP -#define ASIO_IP_ADDRESS_V6_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/array.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/string_view.hpp" -#include "asio/detail/winsock_init.hpp" -#include "asio/error_code.hpp" -#include "asio/ip/address_v4.hpp" - -#if !defined(ASIO_NO_IOSTREAM) -# include -#endif // !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template class basic_address_iterator; - -/// Implements IP version 6 style addresses. -/** - * The asio::ip::address_v6 class provides the ability to use and - * manipulate IP version 6 addresses. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class address_v6 -{ -public: - /// The type used to represent an address as an array of bytes. - /** - * @note This type is defined in terms of the C++0x template @c std::array - * when it is available. Otherwise, it uses @c boost:array. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef array bytes_type; -#else - typedef asio::detail::array bytes_type; -#endif - - /// Default constructor. - ASIO_DECL address_v6(); - - /// Construct an address from raw bytes and scope ID. - ASIO_DECL explicit address_v6(const bytes_type& bytes, - unsigned long scope_id = 0); - - /// Copy constructor. - ASIO_DECL address_v6(const address_v6& other); - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - ASIO_DECL address_v6(address_v6&& other); -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from another address. - ASIO_DECL address_v6& operator=(const address_v6& other); - -#if defined(ASIO_HAS_MOVE) - /// Move-assign from another address. - ASIO_DECL address_v6& operator=(address_v6&& other); -#endif // defined(ASIO_HAS_MOVE) - - /// The scope ID of the address. - /** - * Returns the scope ID associated with the IPv6 address. - */ - unsigned long scope_id() const - { - return scope_id_; - } - - /// The scope ID of the address. - /** - * Modifies the scope ID associated with the IPv6 address. - */ - void scope_id(unsigned long id) - { - scope_id_ = id; - } - - /// Get the address in bytes, in network byte order. - ASIO_DECL bytes_type to_bytes() const; - - /// Get the address as a string. - ASIO_DECL std::string to_string() const; - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use other overload.) Get the address as a string. - ASIO_DECL std::string to_string(asio::error_code& ec) const; - - /// (Deprecated: Use make_address_v6().) Create an IPv6 address from an IP - /// address string. - static address_v6 from_string(const char* str); - - /// (Deprecated: Use make_address_v6().) Create an IPv6 address from an IP - /// address string. - static address_v6 from_string( - const char* str, asio::error_code& ec); - - /// (Deprecated: Use make_address_v6().) Create an IPv6 address from an IP - /// address string. - static address_v6 from_string(const std::string& str); - - /// (Deprecated: Use make_address_v6().) Create an IPv6 address from an IP - /// address string. - static address_v6 from_string( - const std::string& str, asio::error_code& ec); - - /// (Deprecated: Use make_address_v4().) Converts an IPv4-mapped or - /// IPv4-compatible address to an IPv4 address. - ASIO_DECL address_v4 to_v4() const; -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Determine whether the address is a loopback address. - ASIO_DECL bool is_loopback() const; - - /// Determine whether the address is unspecified. - ASIO_DECL bool is_unspecified() const; - - /// Determine whether the address is link local. - ASIO_DECL bool is_link_local() const; - - /// Determine whether the address is site local. - ASIO_DECL bool is_site_local() const; - - /// Determine whether the address is a mapped IPv4 address. - ASIO_DECL bool is_v4_mapped() const; - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: No replacement.) Determine whether the address is an - /// IPv4-compatible address. - ASIO_DECL bool is_v4_compatible() const; -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Determine whether the address is a multicast address. - ASIO_DECL bool is_multicast() const; - - /// Determine whether the address is a global multicast address. - ASIO_DECL bool is_multicast_global() const; - - /// Determine whether the address is a link-local multicast address. - ASIO_DECL bool is_multicast_link_local() const; - - /// Determine whether the address is a node-local multicast address. - ASIO_DECL bool is_multicast_node_local() const; - - /// Determine whether the address is a org-local multicast address. - ASIO_DECL bool is_multicast_org_local() const; - - /// Determine whether the address is a site-local multicast address. - ASIO_DECL bool is_multicast_site_local() const; - - /// Compare two addresses for equality. - ASIO_DECL friend bool operator==( - const address_v6& a1, const address_v6& a2); - - /// Compare two addresses for inequality. - friend bool operator!=(const address_v6& a1, const address_v6& a2) - { - return !(a1 == a2); - } - - /// Compare addresses for ordering. - ASIO_DECL friend bool operator<( - const address_v6& a1, const address_v6& a2); - - /// Compare addresses for ordering. - friend bool operator>(const address_v6& a1, const address_v6& a2) - { - return a2 < a1; - } - - /// Compare addresses for ordering. - friend bool operator<=(const address_v6& a1, const address_v6& a2) - { - return !(a2 < a1); - } - - /// Compare addresses for ordering. - friend bool operator>=(const address_v6& a1, const address_v6& a2) - { - return !(a1 < a2); - } - - /// Obtain an address object that represents any address. - static address_v6 any() - { - return address_v6(); - } - - /// Obtain an address object that represents the loopback address. - ASIO_DECL static address_v6 loopback(); - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use make_address_v6().) Create an IPv4-mapped IPv6 address. - ASIO_DECL static address_v6 v4_mapped(const address_v4& addr); - - /// (Deprecated: No replacement.) Create an IPv4-compatible IPv6 address. - ASIO_DECL static address_v6 v4_compatible(const address_v4& addr); -#endif // !defined(ASIO_NO_DEPRECATED) - -private: - friend class basic_address_iterator; - - // The underlying IPv6 address. - asio::detail::in6_addr_type addr_; - - // The scope ID associated with the address. - unsigned long scope_id_; -}; - -/// Create an IPv6 address from raw bytes and scope ID. -/** - * @relates address_v6 - */ -inline address_v6 make_address_v6(const address_v6::bytes_type& bytes, - unsigned long scope_id = 0) -{ - return address_v6(bytes, scope_id); -} - -/// Create an IPv6 address from an IP address string. -/** - * @relates address_v6 - */ -ASIO_DECL address_v6 make_address_v6(const char* str); - -/// Create an IPv6 address from an IP address string. -/** - * @relates address_v6 - */ -ASIO_DECL address_v6 make_address_v6( - const char* str, asio::error_code& ec); - -/// Createan IPv6 address from an IP address string. -/** - * @relates address_v6 - */ -ASIO_DECL address_v6 make_address_v6(const std::string& str); - -/// Create an IPv6 address from an IP address string. -/** - * @relates address_v6 - */ -ASIO_DECL address_v6 make_address_v6( - const std::string& str, asio::error_code& ec); - -#if defined(ASIO_HAS_STRING_VIEW) \ - || defined(GENERATING_DOCUMENTATION) - -/// Create an IPv6 address from an IP address string. -/** - * @relates address_v6 - */ -ASIO_DECL address_v6 make_address_v6(string_view str); - -/// Create an IPv6 address from an IP address string. -/** - * @relates address_v6 - */ -ASIO_DECL address_v6 make_address_v6( - string_view str, asio::error_code& ec); - -#endif // defined(ASIO_HAS_STRING_VIEW) - // || defined(GENERATING_DOCUMENTATION) - -/// Tag type used for distinguishing overloads that deal in IPv4-mapped IPv6 -/// addresses. -enum v4_mapped_t { v4_mapped }; - -/// Create an IPv4 address from a IPv4-mapped IPv6 address. -/** - * @relates address_v4 - */ -ASIO_DECL address_v4 make_address_v4( - v4_mapped_t, const address_v6& v6_addr); - -/// Create an IPv4-mapped IPv6 address from an IPv4 address. -/** - * @relates address_v6 - */ -ASIO_DECL address_v6 make_address_v6( - v4_mapped_t, const address_v4& v4_addr); - -#if !defined(ASIO_NO_IOSTREAM) - -/// Output an address as a string. -/** - * Used to output a human-readable string for a specified address. - * - * @param os The output stream to which the string will be written. - * - * @param addr The address to be written. - * - * @return The output stream. - * - * @relates asio::ip::address_v6 - */ -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const address_v6& addr); - -#endif // !defined(ASIO_NO_IOSTREAM) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/ip/impl/address_v6.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/ip/impl/address_v6.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_IP_ADDRESS_V6_HPP diff --git a/scout_sdk/asio/asio/ip/address_v6_iterator.hpp b/scout_sdk/asio/asio/ip/address_v6_iterator.hpp deleted file mode 100644 index 0a1fb3f..0000000 --- a/scout_sdk/asio/asio/ip/address_v6_iterator.hpp +++ /dev/null @@ -1,183 +0,0 @@ -// -// ip/address_v6_iterator.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Oliver Kowalke (oliver dot kowalke at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ADDRESS_V6_ITERATOR_HPP -#define ASIO_IP_ADDRESS_V6_ITERATOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ip/address_v6.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template class basic_address_iterator; - -/// An input iterator that can be used for traversing IPv6 addresses. -/** - * In addition to satisfying the input iterator requirements, this iterator - * also supports decrement. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template <> class basic_address_iterator -{ -public: - /// The type of the elements pointed to by the iterator. - typedef address_v6 value_type; - - /// Distance between two iterators. - typedef std::ptrdiff_t difference_type; - - /// The type of a pointer to an element pointed to by the iterator. - typedef const address_v6* pointer; - - /// The type of a reference to an element pointed to by the iterator. - typedef const address_v6& reference; - - /// Denotes that the iterator satisfies the input iterator requirements. - typedef std::input_iterator_tag iterator_category; - - /// Construct an iterator that points to the specified address. - basic_address_iterator(const address_v6& addr) ASIO_NOEXCEPT - : address_(addr) - { - } - - /// Copy constructor. - basic_address_iterator( - const basic_address_iterator& other) ASIO_NOEXCEPT - : address_(other.address_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - basic_address_iterator(basic_address_iterator&& other) ASIO_NOEXCEPT - : address_(ASIO_MOVE_CAST(address_v6)(other.address_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assignment operator. - basic_address_iterator& operator=( - const basic_address_iterator& other) ASIO_NOEXCEPT - { - address_ = other.address_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move assignment operator. - basic_address_iterator& operator=( - basic_address_iterator&& other) ASIO_NOEXCEPT - { - address_ = ASIO_MOVE_CAST(address_v6)(other.address_); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// Dereference the iterator. - const address_v6& operator*() const ASIO_NOEXCEPT - { - return address_; - } - - /// Dereference the iterator. - const address_v6* operator->() const ASIO_NOEXCEPT - { - return &address_; - } - - /// Pre-increment operator. - basic_address_iterator& operator++() ASIO_NOEXCEPT - { - for (int i = 15; i >= 0; --i) - { - if (address_.addr_.s6_addr[i] < 0xFF) - { - ++address_.addr_.s6_addr[i]; - break; - } - - address_.addr_.s6_addr[i] = 0; - } - - return *this; - } - - /// Post-increment operator. - basic_address_iterator operator++(int) ASIO_NOEXCEPT - { - basic_address_iterator tmp(*this); - ++*this; - return tmp; - } - - /// Pre-decrement operator. - basic_address_iterator& operator--() ASIO_NOEXCEPT - { - for (int i = 15; i >= 0; --i) - { - if (address_.addr_.s6_addr[i] > 0) - { - --address_.addr_.s6_addr[i]; - break; - } - - address_.addr_.s6_addr[i] = 0xFF; - } - - return *this; - } - - /// Post-decrement operator. - basic_address_iterator operator--(int) - { - basic_address_iterator tmp(*this); - --*this; - return tmp; - } - - /// Compare two addresses for equality. - friend bool operator==(const basic_address_iterator& a, - const basic_address_iterator& b) - { - return a.address_ == b.address_; - } - - /// Compare two addresses for inequality. - friend bool operator!=(const basic_address_iterator& a, - const basic_address_iterator& b) - { - return a.address_ != b.address_; - } - -private: - address_v6 address_; -}; - -/// An input iterator that can be used for traversing IPv6 addresses. -typedef basic_address_iterator address_v6_iterator; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_ADDRESS_V6_ITERATOR_HPP diff --git a/scout_sdk/asio/asio/ip/address_v6_range.hpp b/scout_sdk/asio/asio/ip/address_v6_range.hpp deleted file mode 100644 index 9d7062e..0000000 --- a/scout_sdk/asio/asio/ip/address_v6_range.hpp +++ /dev/null @@ -1,129 +0,0 @@ -// -// ip/address_v6_range.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Oliver Kowalke (oliver dot kowalke at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ADDRESS_V6_RANGE_HPP -#define ASIO_IP_ADDRESS_V6_RANGE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ip/address_v6_iterator.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template class basic_address_range; - -/// Represents a range of IPv6 addresses. -/** - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template <> class basic_address_range -{ -public: - /// The type of an iterator that points into the range. - typedef basic_address_iterator iterator; - - /// Construct an empty range. - basic_address_range() ASIO_NOEXCEPT - : begin_(address_v6()), - end_(address_v6()) - { - } - - /// Construct an range that represents the given range of addresses. - explicit basic_address_range(const iterator& first, - const iterator& last) ASIO_NOEXCEPT - : begin_(first), - end_(last) - { - } - - /// Copy constructor. - basic_address_range(const basic_address_range& other) ASIO_NOEXCEPT - : begin_(other.begin_), - end_(other.end_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - basic_address_range(basic_address_range&& other) ASIO_NOEXCEPT - : begin_(ASIO_MOVE_CAST(iterator)(other.begin_)), - end_(ASIO_MOVE_CAST(iterator)(other.end_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assignment operator. - basic_address_range& operator=( - const basic_address_range& other) ASIO_NOEXCEPT - { - begin_ = other.begin_; - end_ = other.end_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move assignment operator. - basic_address_range& operator=( - basic_address_range&& other) ASIO_NOEXCEPT - { - begin_ = ASIO_MOVE_CAST(iterator)(other.begin_); - end_ = ASIO_MOVE_CAST(iterator)(other.end_); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// Obtain an iterator that points to the start of the range. - iterator begin() const ASIO_NOEXCEPT - { - return begin_; - } - - /// Obtain an iterator that points to the end of the range. - iterator end() const ASIO_NOEXCEPT - { - return end_; - } - - /// Determine whether the range is empty. - bool empty() const ASIO_NOEXCEPT - { - return begin_ == end_; - } - - /// Find an address in the range. - iterator find(const address_v6& addr) const ASIO_NOEXCEPT - { - return addr >= *begin_ && addr < *end_ ? iterator(addr) : end_; - } - -private: - iterator begin_; - iterator end_; -}; - -/// Represents a range of IPv6 addresses. -typedef basic_address_range address_v6_range; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_ADDRESS_V6_RANGE_HPP diff --git a/scout_sdk/asio/asio/ip/bad_address_cast.hpp b/scout_sdk/asio/asio/ip/bad_address_cast.hpp deleted file mode 100644 index 8c71f70..0000000 --- a/scout_sdk/asio/asio/ip/bad_address_cast.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// -// ip/bad_address_cast.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_BAD_ADDRESS_CAST_HPP -#define ASIO_IP_BAD_ADDRESS_CAST_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Thrown to indicate a failed address conversion. -class bad_address_cast : public std::bad_cast -{ -public: - /// Default constructor. - bad_address_cast() {} - - /// Destructor. - virtual ~bad_address_cast() ASIO_NOEXCEPT_OR_NOTHROW {} - - /// Get the message associated with the exception. - virtual const char* what() const ASIO_NOEXCEPT_OR_NOTHROW - { - return "bad address cast"; - } -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_ADDRESS_HPP diff --git a/scout_sdk/asio/asio/ip/basic_endpoint.hpp b/scout_sdk/asio/asio/ip/basic_endpoint.hpp deleted file mode 100644 index 4418ee7..0000000 --- a/scout_sdk/asio/asio/ip/basic_endpoint.hpp +++ /dev/null @@ -1,263 +0,0 @@ -// -// ip/basic_endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_BASIC_ENDPOINT_HPP -#define ASIO_IP_BASIC_ENDPOINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ip/address.hpp" -#include "asio/ip/detail/endpoint.hpp" - -#if !defined(ASIO_NO_IOSTREAM) -# include -#endif // !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Describes an endpoint for a version-independent IP socket. -/** - * The asio::ip::basic_endpoint class template describes an endpoint that - * may be associated with a particular socket. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * Endpoint. - */ -template -class basic_endpoint -{ -public: - /// The protocol type associated with the endpoint. - typedef InternetProtocol protocol_type; - - /// The type of the endpoint structure. This type is dependent on the - /// underlying implementation of the socket layer. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined data_type; -#else - typedef asio::detail::socket_addr_type data_type; -#endif - - /// Default constructor. - basic_endpoint() - : impl_() - { - } - - /// Construct an endpoint using a port number, specified in the host's byte - /// order. The IP address will be the any address (i.e. INADDR_ANY or - /// in6addr_any). This constructor would typically be used for accepting new - /// connections. - /** - * @par Examples - * To initialise an IPv4 TCP endpoint for port 1234, use: - * @code - * asio::ip::tcp::endpoint ep(asio::ip::tcp::v4(), 1234); - * @endcode - * - * To specify an IPv6 UDP endpoint for port 9876, use: - * @code - * asio::ip::udp::endpoint ep(asio::ip::udp::v6(), 9876); - * @endcode - */ - basic_endpoint(const InternetProtocol& internet_protocol, - unsigned short port_num) - : impl_(internet_protocol.family(), port_num) - { - } - - /// Construct an endpoint using a port number and an IP address. This - /// constructor may be used for accepting connections on a specific interface - /// or for making a connection to a remote endpoint. - basic_endpoint(const asio::ip::address& addr, unsigned short port_num) - : impl_(addr, port_num) - { - } - - /// Copy constructor. - basic_endpoint(const basic_endpoint& other) - : impl_(other.impl_) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move constructor. - basic_endpoint(basic_endpoint&& other) - : impl_(other.impl_) - { - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Assign from another endpoint. - basic_endpoint& operator=(const basic_endpoint& other) - { - impl_ = other.impl_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-assign from another endpoint. - basic_endpoint& operator=(basic_endpoint&& other) - { - impl_ = other.impl_; - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// The protocol associated with the endpoint. - protocol_type protocol() const - { - if (impl_.is_v4()) - return InternetProtocol::v4(); - return InternetProtocol::v6(); - } - - /// Get the underlying endpoint in the native type. - data_type* data() - { - return impl_.data(); - } - - /// Get the underlying endpoint in the native type. - const data_type* data() const - { - return impl_.data(); - } - - /// Get the underlying size of the endpoint in the native type. - std::size_t size() const - { - return impl_.size(); - } - - /// Set the underlying size of the endpoint in the native type. - void resize(std::size_t new_size) - { - impl_.resize(new_size); - } - - /// Get the capacity of the endpoint in the native type. - std::size_t capacity() const - { - return impl_.capacity(); - } - - /// Get the port associated with the endpoint. The port number is always in - /// the host's byte order. - unsigned short port() const - { - return impl_.port(); - } - - /// Set the port associated with the endpoint. The port number is always in - /// the host's byte order. - void port(unsigned short port_num) - { - impl_.port(port_num); - } - - /// Get the IP address associated with the endpoint. - asio::ip::address address() const - { - return impl_.address(); - } - - /// Set the IP address associated with the endpoint. - void address(const asio::ip::address& addr) - { - impl_.address(addr); - } - - /// Compare two endpoints for equality. - friend bool operator==(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e1.impl_ == e2.impl_; - } - - /// Compare two endpoints for inequality. - friend bool operator!=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e1 == e2); - } - - /// Compare endpoints for ordering. - friend bool operator<(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e1.impl_ < e2.impl_; - } - - /// Compare endpoints for ordering. - friend bool operator>(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e2.impl_ < e1.impl_; - } - - /// Compare endpoints for ordering. - friend bool operator<=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e2 < e1); - } - - /// Compare endpoints for ordering. - friend bool operator>=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e1 < e2); - } - -private: - // The underlying IP endpoint. - asio::ip::detail::endpoint impl_; -}; - -#if !defined(ASIO_NO_IOSTREAM) - -/// Output an endpoint as a string. -/** - * Used to output a human-readable string for a specified endpoint. - * - * @param os The output stream to which the string will be written. - * - * @param endpoint The endpoint to be written. - * - * @return The output stream. - * - * @relates asio::ip::basic_endpoint - */ -template -std::basic_ostream& operator<<( - std::basic_ostream& os, - const basic_endpoint& endpoint); - -#endif // !defined(ASIO_NO_IOSTREAM) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/ip/impl/basic_endpoint.hpp" - -#endif // ASIO_IP_BASIC_ENDPOINT_HPP diff --git a/scout_sdk/asio/asio/ip/basic_resolver.hpp b/scout_sdk/asio/asio/ip/basic_resolver.hpp deleted file mode 100644 index 812dbec..0000000 --- a/scout_sdk/asio/asio/ip/basic_resolver.hpp +++ /dev/null @@ -1,1018 +0,0 @@ -// -// ip/basic_resolver.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_BASIC_RESOLVER_HPP -#define ASIO_IP_BASIC_RESOLVER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/string_view.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" -#include "asio/ip/basic_resolver_query.hpp" -#include "asio/ip/basic_resolver_results.hpp" -#include "asio/ip/resolver_base.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/ip/resolver_service.hpp" -#else // defined(ASIO_ENABLE_OLD_SERVICES) -# if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/winrt_resolver_service.hpp" -# define ASIO_SVC_T \ - asio::detail::winrt_resolver_service -# else -# include "asio/detail/resolver_service.hpp" -# define ASIO_SVC_T \ - asio::detail::resolver_service -# endif -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Provides endpoint resolution functionality. -/** - * The basic_resolver class template provides the ability to resolve a query - * to a list of endpoints. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template )> -class basic_resolver - : ASIO_SVC_ACCESS basic_io_object, - public resolver_base -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The protocol type. - typedef InternetProtocol protocol_type; - - /// The endpoint type. - typedef typename InternetProtocol::endpoint endpoint_type; - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated.) The query type. - typedef basic_resolver_query query; - - /// (Deprecated.) The iterator type. - typedef basic_resolver_iterator iterator; -#endif // !defined(ASIO_NO_DEPRECATED) - - /// The results type. - typedef basic_resolver_results results_type; - - /// Constructor. - /** - * This constructor creates a basic_resolver. - * - * @param io_context The io_context object that the resolver will use to - * dispatch handlers for any asynchronous operations performed on the - * resolver. - */ - explicit basic_resolver(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_resolver from another. - /** - * This constructor moves a resolver from one object to another. - * - * @param other The other basic_resolver object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_resolver(io_context&) constructor. - */ - basic_resolver(basic_resolver&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign a basic_resolver from another. - /** - * This assignment operator moves a resolver from one object to another. - * Cancels any outstanding asynchronous operations associated with the target - * object. - * - * @param other The other basic_resolver object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_resolver(io_context&) constructor. - */ - basic_resolver& operator=(basic_resolver&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the resolver. - /** - * This function destroys the resolver, cancelling any outstanding - * asynchronous wait operations associated with the resolver as if by calling - * @c cancel. - */ - ~basic_resolver() - { - } - -#if defined(ASIO_ENABLE_OLD_SERVICES) - // These functions are provided by basic_io_object<>. -#else // defined(ASIO_ENABLE_OLD_SERVICES) -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - - /// Cancel any asynchronous operations that are waiting on the resolver. - /** - * This function forces the completion of any pending asynchronous - * operations on the host resolver. The handler for each cancelled operation - * will be invoked with the asio::error::operation_aborted error code. - */ - void cancel() - { - return this->get_service().cancel(this->get_implementation()); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated.) Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve a query into a list of endpoint entries. - * - * @param q A query object that determines what endpoints will be returned. - * - * @returns A range object representing the list of endpoint entries. A - * successful call to this function is guaranteed to return a non-empty - * range. - * - * @throws asio::system_error Thrown on failure. - */ - results_type resolve(const query& q) - { - asio::error_code ec; - results_type r = this->get_service().resolve( - this->get_implementation(), q, ec); - asio::detail::throw_error(ec, "resolve"); - return r; - } - - /// (Deprecated.) Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve a query into a list of endpoint entries. - * - * @param q A query object that determines what endpoints will be returned. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns A range object representing the list of endpoint entries. An - * empty range is returned if an error occurs. A successful call to this - * function is guaranteed to return a non-empty range. - */ - results_type resolve(const query& q, asio::error_code& ec) - { - return this->get_service().resolve(this->get_implementation(), q, ec); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @returns A range object representing the list of endpoint entries. A - * successful call to this function is guaranteed to return a non-empty - * range. - * - * @throws asio::system_error Thrown on failure. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(ASIO_STRING_VIEW_PARAM host, - ASIO_STRING_VIEW_PARAM service) - { - return resolve(host, service, resolver_base::flags()); - } - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns A range object representing the list of endpoint entries. An - * empty range is returned if an error occurs. A successful call to this - * function is guaranteed to return a non-empty range. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(ASIO_STRING_VIEW_PARAM host, - ASIO_STRING_VIEW_PARAM service, asio::error_code& ec) - { - return resolve(host, service, resolver_base::flags(), ec); - } - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @returns A range object representing the list of endpoint entries. A - * successful call to this function is guaranteed to return a non-empty - * range. - * - * @throws asio::system_error Thrown on failure. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(ASIO_STRING_VIEW_PARAM host, - ASIO_STRING_VIEW_PARAM service, resolver_base::flags resolve_flags) - { - asio::error_code ec; - basic_resolver_query q(static_cast(host), - static_cast(service), resolve_flags); - results_type r = this->get_service().resolve( - this->get_implementation(), q, ec); - asio::detail::throw_error(ec, "resolve"); - return r; - } - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns A range object representing the list of endpoint entries. An - * empty range is returned if an error occurs. A successful call to this - * function is guaranteed to return a non-empty range. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(ASIO_STRING_VIEW_PARAM host, - ASIO_STRING_VIEW_PARAM service, resolver_base::flags resolve_flags, - asio::error_code& ec) - { - basic_resolver_query q(static_cast(host), - static_cast(service), resolve_flags); - return this->get_service().resolve(this->get_implementation(), q, ec); - } - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @returns A range object representing the list of endpoint entries. A - * successful call to this function is guaranteed to return a non-empty - * range. - * - * @throws asio::system_error Thrown on failure. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(const protocol_type& protocol, - ASIO_STRING_VIEW_PARAM host, ASIO_STRING_VIEW_PARAM service) - { - return resolve(protocol, host, service, resolver_base::flags()); - } - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns A range object representing the list of endpoint entries. An - * empty range is returned if an error occurs. A successful call to this - * function is guaranteed to return a non-empty range. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(const protocol_type& protocol, - ASIO_STRING_VIEW_PARAM host, ASIO_STRING_VIEW_PARAM service, - asio::error_code& ec) - { - return resolve(protocol, host, service, resolver_base::flags(), ec); - } - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @returns A range object representing the list of endpoint entries. A - * successful call to this function is guaranteed to return a non-empty - * range. - * - * @throws asio::system_error Thrown on failure. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(const protocol_type& protocol, - ASIO_STRING_VIEW_PARAM host, ASIO_STRING_VIEW_PARAM service, - resolver_base::flags resolve_flags) - { - asio::error_code ec; - basic_resolver_query q( - protocol, static_cast(host), - static_cast(service), resolve_flags); - results_type r = this->get_service().resolve( - this->get_implementation(), q, ec); - asio::detail::throw_error(ec, "resolve"); - return r; - } - - /// Perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns A range object representing the list of endpoint entries. An - * empty range is returned if an error occurs. A successful call to this - * function is guaranteed to return a non-empty range. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - results_type resolve(const protocol_type& protocol, - ASIO_STRING_VIEW_PARAM host, ASIO_STRING_VIEW_PARAM service, - resolver_base::flags resolve_flags, asio::error_code& ec) - { - basic_resolver_query q( - protocol, static_cast(host), - static_cast(service), resolve_flags); - return this->get_service().resolve(this->get_implementation(), q, ec); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated.) Asynchronously perform forward resolution of a query to a - /// list of entries. - /** - * This function is used to asynchronously resolve a query into a list of - * endpoint entries. - * - * @param q A query object that determines what endpoints will be returned. - * - * @param handler The handler to be called when the resolve operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * resolver::results_type results // Resolved endpoints as a range. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * A successful resolve operation is guaranteed to pass a non-empty range to - * the handler. - */ - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(const query& q, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ResolveHandler. - ASIO_RESOLVE_HANDLER_CHECK( - ResolveHandler, handler, results_type) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_resolve(this->get_implementation(), q, - ASIO_MOVE_CAST(ResolveHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - asio::async_completion init(handler); - - this->get_service().async_resolve( - this->get_implementation(), q, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Asynchronously perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param handler The handler to be called when the resolve operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * resolver::results_type results // Resolved endpoints as a range. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * A successful resolve operation is guaranteed to pass a non-empty range to - * the handler. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(ASIO_STRING_VIEW_PARAM host, - ASIO_STRING_VIEW_PARAM service, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - return async_resolve(host, service, resolver_base::flags(), - ASIO_MOVE_CAST(ResolveHandler)(handler)); - } - - /// Asynchronously perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @param handler The handler to be called when the resolve operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * resolver::results_type results // Resolved endpoints as a range. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * A successful resolve operation is guaranteed to pass a non-empty range to - * the handler. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(ASIO_STRING_VIEW_PARAM host, - ASIO_STRING_VIEW_PARAM service, - resolver_base::flags resolve_flags, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ResolveHandler. - ASIO_RESOLVE_HANDLER_CHECK( - ResolveHandler, handler, results_type) type_check; - - basic_resolver_query q(static_cast(host), - static_cast(service), resolve_flags); - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_resolve(this->get_implementation(), q, - ASIO_MOVE_CAST(ResolveHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - asio::async_completion init(handler); - - this->get_service().async_resolve( - this->get_implementation(), q, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Asynchronously perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param handler The handler to be called when the resolve operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * resolver::results_type results // Resolved endpoints as a range. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * A successful resolve operation is guaranteed to pass a non-empty range to - * the handler. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(const protocol_type& protocol, - ASIO_STRING_VIEW_PARAM host, ASIO_STRING_VIEW_PARAM service, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - return async_resolve(protocol, host, service, resolver_base::flags(), - ASIO_MOVE_CAST(ResolveHandler)(handler)); - } - - /// Asynchronously perform forward resolution of a query to a list of entries. - /** - * This function is used to resolve host and service names into a list of - * endpoint entries. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @param handler The handler to be called when the resolve operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * resolver::results_type results // Resolved endpoints as a range. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * A successful resolve operation is guaranteed to pass a non-empty range to - * the handler. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(const protocol_type& protocol, - ASIO_STRING_VIEW_PARAM host, ASIO_STRING_VIEW_PARAM service, - resolver_base::flags resolve_flags, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ResolveHandler. - ASIO_RESOLVE_HANDLER_CHECK( - ResolveHandler, handler, results_type) type_check; - - basic_resolver_query q( - protocol, static_cast(host), - static_cast(service), resolve_flags); - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_resolve(this->get_implementation(), q, - ASIO_MOVE_CAST(ResolveHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - asio::async_completion init(handler); - - this->get_service().async_resolve( - this->get_implementation(), q, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } - - /// Perform reverse resolution of an endpoint to a list of entries. - /** - * This function is used to resolve an endpoint into a list of endpoint - * entries. - * - * @param e An endpoint object that determines what endpoints will be - * returned. - * - * @returns A range object representing the list of endpoint entries. A - * successful call to this function is guaranteed to return a non-empty - * range. - * - * @throws asio::system_error Thrown on failure. - */ - results_type resolve(const endpoint_type& e) - { - asio::error_code ec; - results_type i = this->get_service().resolve( - this->get_implementation(), e, ec); - asio::detail::throw_error(ec, "resolve"); - return i; - } - - /// Perform reverse resolution of an endpoint to a list of entries. - /** - * This function is used to resolve an endpoint into a list of endpoint - * entries. - * - * @param e An endpoint object that determines what endpoints will be - * returned. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns A range object representing the list of endpoint entries. An - * empty range is returned if an error occurs. A successful call to this - * function is guaranteed to return a non-empty range. - */ - results_type resolve(const endpoint_type& e, asio::error_code& ec) - { - return this->get_service().resolve(this->get_implementation(), e, ec); - } - - /// Asynchronously perform reverse resolution of an endpoint to a list of - /// entries. - /** - * This function is used to asynchronously resolve an endpoint into a list of - * endpoint entries. - * - * @param e An endpoint object that determines what endpoints will be - * returned. - * - * @param handler The handler to be called when the resolve operation - * completes. Copies will be made of the handler as required. The function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * resolver::results_type results // Resolved endpoints as a range. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * A successful resolve operation is guaranteed to pass a non-empty range to - * the handler. - */ - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(const endpoint_type& e, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ResolveHandler. - ASIO_RESOLVE_HANDLER_CHECK( - ResolveHandler, handler, results_type) type_check; - -#if defined(ASIO_ENABLE_OLD_SERVICES) - return this->get_service().async_resolve(this->get_implementation(), e, - ASIO_MOVE_CAST(ResolveHandler)(handler)); -#else // defined(ASIO_ENABLE_OLD_SERVICES) - asio::async_completion init(handler); - - this->get_service().async_resolve( - this->get_implementation(), e, init.completion_handler); - - return init.result.get(); -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - } -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# undef ASIO_SVC_T -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_IP_BASIC_RESOLVER_HPP diff --git a/scout_sdk/asio/asio/ip/basic_resolver_entry.hpp b/scout_sdk/asio/asio/ip/basic_resolver_entry.hpp deleted file mode 100644 index 99bcbd2..0000000 --- a/scout_sdk/asio/asio/ip/basic_resolver_entry.hpp +++ /dev/null @@ -1,113 +0,0 @@ -// -// ip/basic_resolver_entry.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_BASIC_RESOLVER_ENTRY_HPP -#define ASIO_IP_BASIC_RESOLVER_ENTRY_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/string_view.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// An entry produced by a resolver. -/** - * The asio::ip::basic_resolver_entry class template describes an entry - * as returned by a resolver. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_resolver_entry -{ -public: - /// The protocol type associated with the endpoint entry. - typedef InternetProtocol protocol_type; - - /// The endpoint type associated with the endpoint entry. - typedef typename InternetProtocol::endpoint endpoint_type; - - /// Default constructor. - basic_resolver_entry() - { - } - - /// Construct with specified endpoint, host name and service name. - basic_resolver_entry(const endpoint_type& ep, - ASIO_STRING_VIEW_PARAM host, ASIO_STRING_VIEW_PARAM service) - : endpoint_(ep), - host_name_(static_cast(host)), - service_name_(static_cast(service)) - { - } - - /// Get the endpoint associated with the entry. - endpoint_type endpoint() const - { - return endpoint_; - } - - /// Convert to the endpoint associated with the entry. - operator endpoint_type() const - { - return endpoint_; - } - - /// Get the host name associated with the entry. - std::string host_name() const - { - return host_name_; - } - - /// Get the host name associated with the entry. - template - std::basic_string, Allocator> host_name( - const Allocator& alloc = Allocator()) const - { - return std::basic_string, Allocator>( - host_name_.c_str(), alloc); - } - - /// Get the service name associated with the entry. - std::string service_name() const - { - return service_name_; - } - - /// Get the service name associated with the entry. - template - std::basic_string, Allocator> service_name( - const Allocator& alloc = Allocator()) const - { - return std::basic_string, Allocator>( - service_name_.c_str(), alloc); - } - -private: - endpoint_type endpoint_; - std::string host_name_; - std::string service_name_; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_BASIC_RESOLVER_ENTRY_HPP diff --git a/scout_sdk/asio/asio/ip/basic_resolver_iterator.hpp b/scout_sdk/asio/asio/ip/basic_resolver_iterator.hpp deleted file mode 100644 index ec5412c..0000000 --- a/scout_sdk/asio/asio/ip/basic_resolver_iterator.hpp +++ /dev/null @@ -1,192 +0,0 @@ -// -// ip/basic_resolver_iterator.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_BASIC_RESOLVER_ITERATOR_HPP -#define ASIO_IP_BASIC_RESOLVER_ITERATOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include -#include -#include "asio/detail/memory.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/ip/basic_resolver_entry.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/winrt_utils.hpp" -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// An iterator over the entries produced by a resolver. -/** - * The asio::ip::basic_resolver_iterator class template is used to define - * iterators over the results returned by a resolver. - * - * The iterator's value_type, obtained when the iterator is dereferenced, is: - * @code const basic_resolver_entry @endcode - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_resolver_iterator -{ -public: - /// The type used for the distance between two iterators. - typedef std::ptrdiff_t difference_type; - - /// The type of the value pointed to by the iterator. - typedef basic_resolver_entry value_type; - - /// The type of the result of applying operator->() to the iterator. - typedef const basic_resolver_entry* pointer; - - /// The type of the result of applying operator*() to the iterator. - typedef const basic_resolver_entry& reference; - - /// The iterator category. - typedef std::forward_iterator_tag iterator_category; - - /// Default constructor creates an end iterator. - basic_resolver_iterator() - : index_(0) - { - } - - /// Copy constructor. - basic_resolver_iterator(const basic_resolver_iterator& other) - : values_(other.values_), - index_(other.index_) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move constructor. - basic_resolver_iterator(basic_resolver_iterator&& other) - : values_(ASIO_MOVE_CAST(values_ptr_type)(other.values_)), - index_(other.index_) - { - other.index_ = 0; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Assignment operator. - basic_resolver_iterator& operator=(const basic_resolver_iterator& other) - { - values_ = other.values_; - index_ = other.index_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-assignment operator. - basic_resolver_iterator& operator=(basic_resolver_iterator&& other) - { - if (this != &other) - { - values_ = ASIO_MOVE_CAST(values_ptr_type)(other.values_); - index_ = other.index_; - other.index_ = 0; - } - - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Dereference an iterator. - const basic_resolver_entry& operator*() const - { - return dereference(); - } - - /// Dereference an iterator. - const basic_resolver_entry* operator->() const - { - return &dereference(); - } - - /// Increment operator (prefix). - basic_resolver_iterator& operator++() - { - increment(); - return *this; - } - - /// Increment operator (postfix). - basic_resolver_iterator operator++(int) - { - basic_resolver_iterator tmp(*this); - ++*this; - return tmp; - } - - /// Test two iterators for equality. - friend bool operator==(const basic_resolver_iterator& a, - const basic_resolver_iterator& b) - { - return a.equal(b); - } - - /// Test two iterators for inequality. - friend bool operator!=(const basic_resolver_iterator& a, - const basic_resolver_iterator& b) - { - return !a.equal(b); - } - -protected: - void increment() - { - if (++index_ == values_->size()) - { - // Reset state to match a default constructed end iterator. - values_.reset(); - index_ = 0; - } - } - - bool equal(const basic_resolver_iterator& other) const - { - if (!values_ && !other.values_) - return true; - if (values_ != other.values_) - return false; - return index_ == other.index_; - } - - const basic_resolver_entry& dereference() const - { - return (*values_)[index_]; - } - - typedef std::vector > values_type; - typedef asio::detail::shared_ptr values_ptr_type; - values_ptr_type values_; - std::size_t index_; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_BASIC_RESOLVER_ITERATOR_HPP diff --git a/scout_sdk/asio/asio/ip/basic_resolver_query.hpp b/scout_sdk/asio/asio/ip/basic_resolver_query.hpp deleted file mode 100644 index 84cd98d..0000000 --- a/scout_sdk/asio/asio/ip/basic_resolver_query.hpp +++ /dev/null @@ -1,244 +0,0 @@ -// -// ip/basic_resolver_query.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_BASIC_RESOLVER_QUERY_HPP -#define ASIO_IP_BASIC_RESOLVER_QUERY_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/socket_ops.hpp" -#include "asio/ip/resolver_query_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// An query to be passed to a resolver. -/** - * The asio::ip::basic_resolver_query class template describes a query - * that can be passed to a resolver. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_resolver_query - : public resolver_query_base -{ -public: - /// The protocol type associated with the endpoint query. - typedef InternetProtocol protocol_type; - - /// Construct with specified service name for any protocol. - /** - * This constructor is typically used to perform name resolution for local - * service binding. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for local service - * binding. - * - * @note On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - basic_resolver_query(const std::string& service, - resolver_query_base::flags resolve_flags = passive | address_configured) - : hints_(), - host_name_(), - service_name_(service) - { - typename InternetProtocol::endpoint endpoint; - hints_.ai_flags = static_cast(resolve_flags); - hints_.ai_family = PF_UNSPEC; - hints_.ai_socktype = endpoint.protocol().type(); - hints_.ai_protocol = endpoint.protocol().protocol(); - hints_.ai_addrlen = 0; - hints_.ai_canonname = 0; - hints_.ai_addr = 0; - hints_.ai_next = 0; - } - - /// Construct with specified service name for a given protocol. - /** - * This constructor is typically used to perform name resolution for local - * service binding with a specific protocol version. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for local service - * binding. - * - * @note On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - basic_resolver_query(const protocol_type& protocol, - const std::string& service, - resolver_query_base::flags resolve_flags = passive | address_configured) - : hints_(), - host_name_(), - service_name_(service) - { - hints_.ai_flags = static_cast(resolve_flags); - hints_.ai_family = protocol.family(); - hints_.ai_socktype = protocol.type(); - hints_.ai_protocol = protocol.protocol(); - hints_.ai_addrlen = 0; - hints_.ai_canonname = 0; - hints_.ai_addr = 0; - hints_.ai_next = 0; - } - - /// Construct with specified host name and service name for any protocol. - /** - * This constructor is typically used to perform name resolution for - * communication with remote hosts. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - basic_resolver_query(const std::string& host, const std::string& service, - resolver_query_base::flags resolve_flags = address_configured) - : hints_(), - host_name_(host), - service_name_(service) - { - typename InternetProtocol::endpoint endpoint; - hints_.ai_flags = static_cast(resolve_flags); - hints_.ai_family = ASIO_OS_DEF(AF_UNSPEC); - hints_.ai_socktype = endpoint.protocol().type(); - hints_.ai_protocol = endpoint.protocol().protocol(); - hints_.ai_addrlen = 0; - hints_.ai_canonname = 0; - hints_.ai_addr = 0; - hints_.ai_next = 0; - } - - /// Construct with specified host name and service name for a given protocol. - /** - * This constructor is typically used to perform name resolution for - * communication with remote hosts. - * - * @param protocol A protocol object, normally representing either the IPv4 or - * IPv6 version of an internet protocol. - * - * @param host A string identifying a location. May be a descriptive name or - * a numeric address string. If an empty string and the passive flag has been - * specified, the resolved endpoints are suitable for local service binding. - * If an empty string and passive is not specified, the resolved endpoints - * will use the loopback address. - * - * @param service A string identifying the requested service. This may be a - * descriptive name or a numeric string corresponding to a port number. May - * be an empty string, in which case all resolved endpoints will have a port - * number of 0. - * - * @param resolve_flags A set of flags that determine how name resolution - * should be performed. The default flags are suitable for communication with - * remote hosts. - * - * @note On POSIX systems, host names may be locally defined in the file - * /etc/hosts. On Windows, host names may be defined in the file - * c:\\windows\\system32\\drivers\\etc\\hosts. Remote host name - * resolution is performed using DNS. Operating systems may use additional - * locations when resolving host names (such as NETBIOS names on Windows). - * - * On POSIX systems, service names are typically defined in the file - * /etc/services. On Windows, service names may be found in the file - * c:\\windows\\system32\\drivers\\etc\\services. Operating systems - * may use additional locations when resolving service names. - */ - basic_resolver_query(const protocol_type& protocol, - const std::string& host, const std::string& service, - resolver_query_base::flags resolve_flags = address_configured) - : hints_(), - host_name_(host), - service_name_(service) - { - hints_.ai_flags = static_cast(resolve_flags); - hints_.ai_family = protocol.family(); - hints_.ai_socktype = protocol.type(); - hints_.ai_protocol = protocol.protocol(); - hints_.ai_addrlen = 0; - hints_.ai_canonname = 0; - hints_.ai_addr = 0; - hints_.ai_next = 0; - } - - /// Get the hints associated with the query. - const asio::detail::addrinfo_type& hints() const - { - return hints_; - } - - /// Get the host name associated with the query. - std::string host_name() const - { - return host_name_; - } - - /// Get the service name associated with the query. - std::string service_name() const - { - return service_name_; - } - -private: - asio::detail::addrinfo_type hints_; - std::string host_name_; - std::string service_name_; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_BASIC_RESOLVER_QUERY_HPP diff --git a/scout_sdk/asio/asio/ip/basic_resolver_results.hpp b/scout_sdk/asio/asio/ip/basic_resolver_results.hpp deleted file mode 100644 index 185075f..0000000 --- a/scout_sdk/asio/asio/ip/basic_resolver_results.hpp +++ /dev/null @@ -1,311 +0,0 @@ -// -// ip/basic_resolver_results.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_BASIC_RESOLVER_RESULTS_HPP -#define ASIO_IP_BASIC_RESOLVER_RESULTS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/winrt_utils.hpp" -#endif // defined(ASIO_WINDOWS_RUNTIME) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// A range of entries produced by a resolver. -/** - * The asio::ip::basic_resolver_results class template is used to define - * a range over the results returned by a resolver. - * - * The iterator's value_type, obtained when a results iterator is dereferenced, - * is: @code const basic_resolver_entry @endcode - * - * @note For backward compatibility, basic_resolver_results is derived from - * basic_resolver_iterator. This derivation is deprecated. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_resolver_results -#if !defined(ASIO_NO_DEPRECATED) - : public basic_resolver_iterator -#else // !defined(ASIO_NO_DEPRECATED) - : private basic_resolver_iterator -#endif // !defined(ASIO_NO_DEPRECATED) -{ -public: - /// The protocol type associated with the results. - typedef InternetProtocol protocol_type; - - /// The endpoint type associated with the results. - typedef typename protocol_type::endpoint endpoint_type; - - /// The type of a value in the results range. - typedef basic_resolver_entry value_type; - - /// The type of a const reference to a value in the range. - typedef const value_type& const_reference; - - /// The type of a non-const reference to a value in the range. - typedef value_type& reference; - - /// The type of an iterator into the range. - typedef basic_resolver_iterator const_iterator; - - /// The type of an iterator into the range. - typedef const_iterator iterator; - - /// Type used to represent the distance between two iterators in the range. - typedef std::ptrdiff_t difference_type; - - /// Type used to represent a count of the elements in the range. - typedef std::size_t size_type; - - /// Default constructor creates an empty range. - basic_resolver_results() - { - } - - /// Copy constructor. - basic_resolver_results(const basic_resolver_results& other) - : basic_resolver_iterator(other) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move constructor. - basic_resolver_results(basic_resolver_results&& other) - : basic_resolver_iterator( - ASIO_MOVE_CAST(basic_resolver_results)(other)) - { - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Assignment operator. - basic_resolver_results& operator=(const basic_resolver_results& other) - { - basic_resolver_iterator::operator=(other); - return *this; - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-assignment operator. - basic_resolver_results& operator=(basic_resolver_results&& other) - { - basic_resolver_iterator::operator=( - ASIO_MOVE_CAST(basic_resolver_results)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - -#if !defined(GENERATING_DOCUMENTATION) - // Create results from an addrinfo list returned by getaddrinfo. - static basic_resolver_results create( - asio::detail::addrinfo_type* address_info, - const std::string& host_name, const std::string& service_name) - { - basic_resolver_results results; - if (!address_info) - return results; - - std::string actual_host_name = host_name; - if (address_info->ai_canonname) - actual_host_name = address_info->ai_canonname; - - results.values_.reset(new values_type); - - while (address_info) - { - if (address_info->ai_family == ASIO_OS_DEF(AF_INET) - || address_info->ai_family == ASIO_OS_DEF(AF_INET6)) - { - using namespace std; // For memcpy. - typename InternetProtocol::endpoint endpoint; - endpoint.resize(static_cast(address_info->ai_addrlen)); - memcpy(endpoint.data(), address_info->ai_addr, - address_info->ai_addrlen); - results.values_->push_back( - basic_resolver_entry(endpoint, - actual_host_name, service_name)); - } - address_info = address_info->ai_next; - } - - return results; - } - - // Create results from an endpoint, host name and service name. - static basic_resolver_results create(const endpoint_type& endpoint, - const std::string& host_name, const std::string& service_name) - { - basic_resolver_results results; - results.values_.reset(new values_type); - results.values_->push_back( - basic_resolver_entry( - endpoint, host_name, service_name)); - return results; - } - - // Create results from a sequence of endpoints, host and service name. - template - static basic_resolver_results create( - EndpointIterator begin, EndpointIterator end, - const std::string& host_name, const std::string& service_name) - { - basic_resolver_results results; - if (begin != end) - { - results.values_.reset(new values_type); - for (EndpointIterator ep_iter = begin; ep_iter != end; ++ep_iter) - { - results.values_->push_back( - basic_resolver_entry( - *ep_iter, host_name, service_name)); - } - } - return results; - } - -# if defined(ASIO_WINDOWS_RUNTIME) - // Create results from a Windows Runtime list of EndpointPair objects. - static basic_resolver_results create( - Windows::Foundation::Collections::IVectorView< - Windows::Networking::EndpointPair^>^ endpoints, - const asio::detail::addrinfo_type& hints, - const std::string& host_name, const std::string& service_name) - { - basic_resolver_results results; - if (endpoints->Size) - { - results.values_.reset(new values_type); - for (unsigned int i = 0; i < endpoints->Size; ++i) - { - auto pair = endpoints->GetAt(i); - - if (hints.ai_family == ASIO_OS_DEF(AF_INET) - && pair->RemoteHostName->Type - != Windows::Networking::HostNameType::Ipv4) - continue; - - if (hints.ai_family == ASIO_OS_DEF(AF_INET6) - && pair->RemoteHostName->Type - != Windows::Networking::HostNameType::Ipv6) - continue; - - results.values_->push_back( - basic_resolver_entry( - typename InternetProtocol::endpoint( - ip::make_address( - asio::detail::winrt_utils::string( - pair->RemoteHostName->CanonicalName)), - asio::detail::winrt_utils::integer( - pair->RemoteServiceName)), - host_name, service_name)); - } - } - return results; - } -# endif // defined(ASIO_WINDOWS_RUNTIME) -#endif // !defined(GENERATING_DOCUMENTATION) - - /// Get the number of entries in the results range. - size_type size() const ASIO_NOEXCEPT - { - return this->values_->size(); - } - - /// Get the maximum number of entries permitted in a results range. - size_type max_size() const ASIO_NOEXCEPT - { - return this->values_->max_size(); - } - - /// Determine whether the results range is empty. - bool empty() const ASIO_NOEXCEPT - { - return this->values_->empty(); - } - - /// Obtain a begin iterator for the results range. - const_iterator begin() const - { - basic_resolver_results tmp(*this); - tmp.index_ = 0; - return tmp; - } - - /// Obtain an end iterator for the results range. - const_iterator end() const - { - return const_iterator(); - } - - /// Obtain a begin iterator for the results range. - const_iterator cbegin() const - { - return begin(); - } - - /// Obtain an end iterator for the results range. - const_iterator cend() const - { - return end(); - } - - /// Swap the results range with another. - void swap(basic_resolver_results& that) ASIO_NOEXCEPT - { - if (this != &that) - { - this->values_.swap(that.values_); - std::size_t index = this->index_; - this->index_ = that.index_; - that.index_ = index; - } - } - - /// Test two iterators for equality. - friend bool operator==(const basic_resolver_results& a, - const basic_resolver_results& b) - { - return a.equal(b); - } - - /// Test two iterators for inequality. - friend bool operator!=(const basic_resolver_results& a, - const basic_resolver_results& b) - { - return !a.equal(b); - } - -private: - typedef std::vector > values_type; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_BASIC_RESOLVER_RESULTS_HPP diff --git a/scout_sdk/asio/asio/ip/detail/endpoint.hpp b/scout_sdk/asio/asio/ip/detail/endpoint.hpp deleted file mode 100644 index 9acefe5..0000000 --- a/scout_sdk/asio/asio/ip/detail/endpoint.hpp +++ /dev/null @@ -1,139 +0,0 @@ -// -// ip/detail/endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_DETAIL_ENDPOINT_HPP -#define ASIO_IP_DETAIL_ENDPOINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/socket_types.hpp" -#include "asio/detail/winsock_init.hpp" -#include "asio/error_code.hpp" -#include "asio/ip/address.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { -namespace detail { - -// Helper class for implementating an IP endpoint. -class endpoint -{ -public: - // Default constructor. - ASIO_DECL endpoint(); - - // Construct an endpoint using a family and port number. - ASIO_DECL endpoint(int family, unsigned short port_num); - - // Construct an endpoint using an address and port number. - ASIO_DECL endpoint(const asio::ip::address& addr, - unsigned short port_num); - - // Copy constructor. - endpoint(const endpoint& other) - : data_(other.data_) - { - } - - // Assign from another endpoint. - endpoint& operator=(const endpoint& other) - { - data_ = other.data_; - return *this; - } - - // Get the underlying endpoint in the native type. - asio::detail::socket_addr_type* data() - { - return &data_.base; - } - - // Get the underlying endpoint in the native type. - const asio::detail::socket_addr_type* data() const - { - return &data_.base; - } - - // Get the underlying size of the endpoint in the native type. - std::size_t size() const - { - if (is_v4()) - return sizeof(asio::detail::sockaddr_in4_type); - else - return sizeof(asio::detail::sockaddr_in6_type); - } - - // Set the underlying size of the endpoint in the native type. - ASIO_DECL void resize(std::size_t new_size); - - // Get the capacity of the endpoint in the native type. - std::size_t capacity() const - { - return sizeof(data_); - } - - // Get the port associated with the endpoint. - ASIO_DECL unsigned short port() const; - - // Set the port associated with the endpoint. - ASIO_DECL void port(unsigned short port_num); - - // Get the IP address associated with the endpoint. - ASIO_DECL asio::ip::address address() const; - - // Set the IP address associated with the endpoint. - ASIO_DECL void address(const asio::ip::address& addr); - - // Compare two endpoints for equality. - ASIO_DECL friend bool operator==( - const endpoint& e1, const endpoint& e2); - - // Compare endpoints for ordering. - ASIO_DECL friend bool operator<( - const endpoint& e1, const endpoint& e2); - - // Determine whether the endpoint is IPv4. - bool is_v4() const - { - return data_.base.sa_family == ASIO_OS_DEF(AF_INET); - } - -#if !defined(ASIO_NO_IOSTREAM) - // Convert to a string. - ASIO_DECL std::string to_string() const; -#endif // !defined(ASIO_NO_IOSTREAM) - -private: - // The underlying IP socket address. - union data_union - { - asio::detail::socket_addr_type base; - asio::detail::sockaddr_in4_type v4; - asio::detail::sockaddr_in6_type v6; - } data_; -}; - -} // namespace detail -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/ip/detail/impl/endpoint.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_IP_DETAIL_ENDPOINT_HPP diff --git a/scout_sdk/asio/asio/ip/detail/impl/endpoint.ipp b/scout_sdk/asio/asio/ip/detail/impl/endpoint.ipp deleted file mode 100644 index 304bdf3..0000000 --- a/scout_sdk/asio/asio/ip/detail/impl/endpoint.ipp +++ /dev/null @@ -1,199 +0,0 @@ -// -// ip/detail/impl/endpoint.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_DETAIL_IMPL_ENDPOINT_IPP -#define ASIO_IP_DETAIL_IMPL_ENDPOINT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#if !defined(ASIO_NO_IOSTREAM) -# include -#endif // !defined(ASIO_NO_IOSTREAM) -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/ip/detail/endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { -namespace detail { - -endpoint::endpoint() - : data_() -{ - data_.v4.sin_family = ASIO_OS_DEF(AF_INET); - data_.v4.sin_port = 0; - data_.v4.sin_addr.s_addr = ASIO_OS_DEF(INADDR_ANY); -} - -endpoint::endpoint(int family, unsigned short port_num) - : data_() -{ - using namespace std; // For memcpy. - if (family == ASIO_OS_DEF(AF_INET)) - { - data_.v4.sin_family = ASIO_OS_DEF(AF_INET); - data_.v4.sin_port = - asio::detail::socket_ops::host_to_network_short(port_num); - data_.v4.sin_addr.s_addr = ASIO_OS_DEF(INADDR_ANY); - } - else - { - data_.v6.sin6_family = ASIO_OS_DEF(AF_INET6); - data_.v6.sin6_port = - asio::detail::socket_ops::host_to_network_short(port_num); - data_.v6.sin6_flowinfo = 0; - data_.v6.sin6_addr.s6_addr[0] = 0; data_.v6.sin6_addr.s6_addr[1] = 0; - data_.v6.sin6_addr.s6_addr[2] = 0; data_.v6.sin6_addr.s6_addr[3] = 0; - data_.v6.sin6_addr.s6_addr[4] = 0; data_.v6.sin6_addr.s6_addr[5] = 0; - data_.v6.sin6_addr.s6_addr[6] = 0; data_.v6.sin6_addr.s6_addr[7] = 0; - data_.v6.sin6_addr.s6_addr[8] = 0; data_.v6.sin6_addr.s6_addr[9] = 0; - data_.v6.sin6_addr.s6_addr[10] = 0; data_.v6.sin6_addr.s6_addr[11] = 0; - data_.v6.sin6_addr.s6_addr[12] = 0; data_.v6.sin6_addr.s6_addr[13] = 0; - data_.v6.sin6_addr.s6_addr[14] = 0; data_.v6.sin6_addr.s6_addr[15] = 0; - data_.v6.sin6_scope_id = 0; - } -} - -endpoint::endpoint(const asio::ip::address& addr, - unsigned short port_num) - : data_() -{ - using namespace std; // For memcpy. - if (addr.is_v4()) - { - data_.v4.sin_family = ASIO_OS_DEF(AF_INET); - data_.v4.sin_port = - asio::detail::socket_ops::host_to_network_short(port_num); - data_.v4.sin_addr.s_addr = - asio::detail::socket_ops::host_to_network_long( - addr.to_v4().to_uint()); - } - else - { - data_.v6.sin6_family = ASIO_OS_DEF(AF_INET6); - data_.v6.sin6_port = - asio::detail::socket_ops::host_to_network_short(port_num); - data_.v6.sin6_flowinfo = 0; - asio::ip::address_v6 v6_addr = addr.to_v6(); - asio::ip::address_v6::bytes_type bytes = v6_addr.to_bytes(); - memcpy(data_.v6.sin6_addr.s6_addr, bytes.data(), 16); - data_.v6.sin6_scope_id = - static_cast( - v6_addr.scope_id()); - } -} - -void endpoint::resize(std::size_t new_size) -{ - if (new_size > sizeof(asio::detail::sockaddr_storage_type)) - { - asio::error_code ec(asio::error::invalid_argument); - asio::detail::throw_error(ec); - } -} - -unsigned short endpoint::port() const -{ - if (is_v4()) - { - return asio::detail::socket_ops::network_to_host_short( - data_.v4.sin_port); - } - else - { - return asio::detail::socket_ops::network_to_host_short( - data_.v6.sin6_port); - } -} - -void endpoint::port(unsigned short port_num) -{ - if (is_v4()) - { - data_.v4.sin_port - = asio::detail::socket_ops::host_to_network_short(port_num); - } - else - { - data_.v6.sin6_port - = asio::detail::socket_ops::host_to_network_short(port_num); - } -} - -asio::ip::address endpoint::address() const -{ - using namespace std; // For memcpy. - if (is_v4()) - { - return asio::ip::address_v4( - asio::detail::socket_ops::network_to_host_long( - data_.v4.sin_addr.s_addr)); - } - else - { - asio::ip::address_v6::bytes_type bytes; -#if defined(ASIO_HAS_STD_ARRAY) - memcpy(bytes.data(), data_.v6.sin6_addr.s6_addr, 16); -#else // defined(ASIO_HAS_STD_ARRAY) - memcpy(bytes.elems, data_.v6.sin6_addr.s6_addr, 16); -#endif // defined(ASIO_HAS_STD_ARRAY) - return asio::ip::address_v6(bytes, data_.v6.sin6_scope_id); - } -} - -void endpoint::address(const asio::ip::address& addr) -{ - endpoint tmp_endpoint(addr, port()); - data_ = tmp_endpoint.data_; -} - -bool operator==(const endpoint& e1, const endpoint& e2) -{ - return e1.address() == e2.address() && e1.port() == e2.port(); -} - -bool operator<(const endpoint& e1, const endpoint& e2) -{ - if (e1.address() < e2.address()) - return true; - if (e1.address() != e2.address()) - return false; - return e1.port() < e2.port(); -} - -#if !defined(ASIO_NO_IOSTREAM) -std::string endpoint::to_string() const -{ - std::ostringstream tmp_os; - tmp_os.imbue(std::locale::classic()); - if (is_v4()) - tmp_os << address(); - else - tmp_os << '[' << address() << ']'; - tmp_os << ':' << port(); - - return tmp_os.str(); -} -#endif // !defined(ASIO_NO_IOSTREAM) - -} // namespace detail -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_DETAIL_IMPL_ENDPOINT_IPP diff --git a/scout_sdk/asio/asio/ip/detail/socket_option.hpp b/scout_sdk/asio/asio/ip/detail/socket_option.hpp deleted file mode 100644 index 051ef30..0000000 --- a/scout_sdk/asio/asio/ip/detail/socket_option.hpp +++ /dev/null @@ -1,566 +0,0 @@ -// -// detail/socket_option.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_DETAIL_SOCKET_OPTION_HPP -#define ASIO_IP_DETAIL_SOCKET_OPTION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/ip/address.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { -namespace detail { -namespace socket_option { - -// Helper template for implementing multicast enable loopback options. -template -class multicast_enable_loopback -{ -public: -#if defined(__sun) || defined(__osf__) - typedef unsigned char ipv4_value_type; - typedef unsigned char ipv6_value_type; -#elif defined(_AIX) || defined(__hpux) || defined(__QNXNTO__) - typedef unsigned char ipv4_value_type; - typedef unsigned int ipv6_value_type; -#else - typedef int ipv4_value_type; - typedef int ipv6_value_type; -#endif - - // Default constructor. - multicast_enable_loopback() - : ipv4_value_(0), - ipv6_value_(0) - { - } - - // Construct with a specific option value. - explicit multicast_enable_loopback(bool v) - : ipv4_value_(v ? 1 : 0), - ipv6_value_(v ? 1 : 0) - { - } - - // Set the value of the boolean. - multicast_enable_loopback& operator=(bool v) - { - ipv4_value_ = v ? 1 : 0; - ipv6_value_ = v ? 1 : 0; - return *this; - } - - // Get the current value of the boolean. - bool value() const - { - return !!ipv4_value_; - } - - // Convert to bool. - operator bool() const - { - return !!ipv4_value_; - } - - // Test for false. - bool operator!() const - { - return !ipv4_value_; - } - - // Get the level of the socket option. - template - int level(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Level; - return IPv4_Level; - } - - // Get the name of the socket option. - template - int name(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Name; - return IPv4_Name; - } - - // Get the address of the boolean data. - template - void* data(const Protocol& protocol) - { - if (protocol.family() == PF_INET6) - return &ipv6_value_; - return &ipv4_value_; - } - - // Get the address of the boolean data. - template - const void* data(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return &ipv6_value_; - return &ipv4_value_; - } - - // Get the size of the boolean data. - template - std::size_t size(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return sizeof(ipv6_value_); - return sizeof(ipv4_value_); - } - - // Set the size of the boolean data. - template - void resize(const Protocol& protocol, std::size_t s) - { - if (protocol.family() == PF_INET6) - { - if (s != sizeof(ipv6_value_)) - { - std::length_error ex("multicast_enable_loopback socket option resize"); - asio::detail::throw_exception(ex); - } - ipv4_value_ = ipv6_value_ ? 1 : 0; - } - else - { - if (s != sizeof(ipv4_value_)) - { - std::length_error ex("multicast_enable_loopback socket option resize"); - asio::detail::throw_exception(ex); - } - ipv6_value_ = ipv4_value_ ? 1 : 0; - } - } - -private: - ipv4_value_type ipv4_value_; - ipv6_value_type ipv6_value_; -}; - -// Helper template for implementing unicast hops options. -template -class unicast_hops -{ -public: - // Default constructor. - unicast_hops() - : value_(0) - { - } - - // Construct with a specific option value. - explicit unicast_hops(int v) - : value_(v) - { - } - - // Set the value of the option. - unicast_hops& operator=(int v) - { - value_ = v; - return *this; - } - - // Get the current value of the option. - int value() const - { - return value_; - } - - // Get the level of the socket option. - template - int level(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Level; - return IPv4_Level; - } - - // Get the name of the socket option. - template - int name(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Name; - return IPv4_Name; - } - - // Get the address of the data. - template - int* data(const Protocol&) - { - return &value_; - } - - // Get the address of the data. - template - const int* data(const Protocol&) const - { - return &value_; - } - - // Get the size of the data. - template - std::size_t size(const Protocol&) const - { - return sizeof(value_); - } - - // Set the size of the data. - template - void resize(const Protocol&, std::size_t s) - { - if (s != sizeof(value_)) - { - std::length_error ex("unicast hops socket option resize"); - asio::detail::throw_exception(ex); - } -#if defined(__hpux) - if (value_ < 0) - value_ = value_ & 0xFF; -#endif - } - -private: - int value_; -}; - -// Helper template for implementing multicast hops options. -template -class multicast_hops -{ -public: -#if defined(ASIO_WINDOWS) && defined(UNDER_CE) - typedef int ipv4_value_type; -#else - typedef unsigned char ipv4_value_type; -#endif - typedef int ipv6_value_type; - - // Default constructor. - multicast_hops() - : ipv4_value_(0), - ipv6_value_(0) - { - } - - // Construct with a specific option value. - explicit multicast_hops(int v) - { - if (v < 0 || v > 255) - { - std::out_of_range ex("multicast hops value out of range"); - asio::detail::throw_exception(ex); - } - ipv4_value_ = (ipv4_value_type)v; - ipv6_value_ = v; - } - - // Set the value of the option. - multicast_hops& operator=(int v) - { - if (v < 0 || v > 255) - { - std::out_of_range ex("multicast hops value out of range"); - asio::detail::throw_exception(ex); - } - ipv4_value_ = (ipv4_value_type)v; - ipv6_value_ = v; - return *this; - } - - // Get the current value of the option. - int value() const - { - return ipv6_value_; - } - - // Get the level of the socket option. - template - int level(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Level; - return IPv4_Level; - } - - // Get the name of the socket option. - template - int name(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Name; - return IPv4_Name; - } - - // Get the address of the data. - template - void* data(const Protocol& protocol) - { - if (protocol.family() == PF_INET6) - return &ipv6_value_; - return &ipv4_value_; - } - - // Get the address of the data. - template - const void* data(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return &ipv6_value_; - return &ipv4_value_; - } - - // Get the size of the data. - template - std::size_t size(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return sizeof(ipv6_value_); - return sizeof(ipv4_value_); - } - - // Set the size of the data. - template - void resize(const Protocol& protocol, std::size_t s) - { - if (protocol.family() == PF_INET6) - { - if (s != sizeof(ipv6_value_)) - { - std::length_error ex("multicast hops socket option resize"); - asio::detail::throw_exception(ex); - } - if (ipv6_value_ < 0) - ipv4_value_ = 0; - else if (ipv6_value_ > 255) - ipv4_value_ = 255; - else - ipv4_value_ = (ipv4_value_type)ipv6_value_; - } - else - { - if (s != sizeof(ipv4_value_)) - { - std::length_error ex("multicast hops socket option resize"); - asio::detail::throw_exception(ex); - } - ipv6_value_ = ipv4_value_; - } - } - -private: - ipv4_value_type ipv4_value_; - ipv6_value_type ipv6_value_; -}; - -// Helper template for implementing ip_mreq-based options. -template -class multicast_request -{ -public: - // Default constructor. - multicast_request() - : ipv4_value_(), // Zero-initialisation gives the "any" address. - ipv6_value_() // Zero-initialisation gives the "any" address. - { - } - - // Construct with multicast address only. - explicit multicast_request(const address& multicast_address) - : ipv4_value_(), // Zero-initialisation gives the "any" address. - ipv6_value_() // Zero-initialisation gives the "any" address. - { - if (multicast_address.is_v6()) - { - using namespace std; // For memcpy. - address_v6 ipv6_address = multicast_address.to_v6(); - address_v6::bytes_type bytes = ipv6_address.to_bytes(); - memcpy(ipv6_value_.ipv6mr_multiaddr.s6_addr, bytes.data(), 16); - ipv6_value_.ipv6mr_interface = ipv6_address.scope_id(); - } - else - { - ipv4_value_.imr_multiaddr.s_addr = - asio::detail::socket_ops::host_to_network_long( - multicast_address.to_v4().to_uint()); - ipv4_value_.imr_interface.s_addr = - asio::detail::socket_ops::host_to_network_long( - address_v4::any().to_uint()); - } - } - - // Construct with multicast address and IPv4 address specifying an interface. - explicit multicast_request(const address_v4& multicast_address, - const address_v4& network_interface = address_v4::any()) - : ipv6_value_() // Zero-initialisation gives the "any" address. - { - ipv4_value_.imr_multiaddr.s_addr = - asio::detail::socket_ops::host_to_network_long( - multicast_address.to_uint()); - ipv4_value_.imr_interface.s_addr = - asio::detail::socket_ops::host_to_network_long( - network_interface.to_uint()); - } - - // Construct with multicast address and IPv6 network interface index. - explicit multicast_request( - const address_v6& multicast_address, - unsigned long network_interface = 0) - : ipv4_value_() // Zero-initialisation gives the "any" address. - { - using namespace std; // For memcpy. - address_v6::bytes_type bytes = multicast_address.to_bytes(); - memcpy(ipv6_value_.ipv6mr_multiaddr.s6_addr, bytes.data(), 16); - if (network_interface) - ipv6_value_.ipv6mr_interface = network_interface; - else - ipv6_value_.ipv6mr_interface = multicast_address.scope_id(); - } - - // Get the level of the socket option. - template - int level(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Level; - return IPv4_Level; - } - - // Get the name of the socket option. - template - int name(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Name; - return IPv4_Name; - } - - // Get the address of the option data. - template - const void* data(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return &ipv6_value_; - return &ipv4_value_; - } - - // Get the size of the option data. - template - std::size_t size(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return sizeof(ipv6_value_); - return sizeof(ipv4_value_); - } - -private: - asio::detail::in4_mreq_type ipv4_value_; - asio::detail::in6_mreq_type ipv6_value_; -}; - -// Helper template for implementing options that specify a network interface. -template -class network_interface -{ -public: - // Default constructor. - network_interface() - { - ipv4_value_.s_addr = - asio::detail::socket_ops::host_to_network_long( - address_v4::any().to_uint()); - ipv6_value_ = 0; - } - - // Construct with IPv4 interface. - explicit network_interface(const address_v4& ipv4_interface) - { - ipv4_value_.s_addr = - asio::detail::socket_ops::host_to_network_long( - ipv4_interface.to_uint()); - ipv6_value_ = 0; - } - - // Construct with IPv6 interface. - explicit network_interface(unsigned int ipv6_interface) - { - ipv4_value_.s_addr = - asio::detail::socket_ops::host_to_network_long( - address_v4::any().to_uint()); - ipv6_value_ = ipv6_interface; - } - - // Get the level of the socket option. - template - int level(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Level; - return IPv4_Level; - } - - // Get the name of the socket option. - template - int name(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return IPv6_Name; - return IPv4_Name; - } - - // Get the address of the option data. - template - const void* data(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return &ipv6_value_; - return &ipv4_value_; - } - - // Get the size of the option data. - template - std::size_t size(const Protocol& protocol) const - { - if (protocol.family() == PF_INET6) - return sizeof(ipv6_value_); - return sizeof(ipv4_value_); - } - -private: - asio::detail::in4_addr_type ipv4_value_; - unsigned int ipv6_value_; -}; - -} // namespace socket_option -} // namespace detail -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_DETAIL_SOCKET_OPTION_HPP diff --git a/scout_sdk/asio/asio/ip/host_name.hpp b/scout_sdk/asio/asio/ip/host_name.hpp deleted file mode 100644 index d06de50..0000000 --- a/scout_sdk/asio/asio/ip/host_name.hpp +++ /dev/null @@ -1,42 +0,0 @@ -// -// ip/host_name.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_HOST_NAME_HPP -#define ASIO_IP_HOST_NAME_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/error_code.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Get the current host name. -ASIO_DECL std::string host_name(); - -/// Get the current host name. -ASIO_DECL std::string host_name(asio::error_code& ec); - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/ip/impl/host_name.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_IP_HOST_NAME_HPP diff --git a/scout_sdk/asio/asio/ip/icmp.hpp b/scout_sdk/asio/asio/ip/icmp.hpp deleted file mode 100644 index 92e1953..0000000 --- a/scout_sdk/asio/asio/ip/icmp.hpp +++ /dev/null @@ -1,115 +0,0 @@ -// -// ip/icmp.hpp -// ~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_ICMP_HPP -#define ASIO_IP_ICMP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/basic_raw_socket.hpp" -#include "asio/ip/basic_endpoint.hpp" -#include "asio/ip/basic_resolver.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" -#include "asio/ip/basic_resolver_query.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Encapsulates the flags needed for ICMP. -/** - * The asio::ip::icmp class contains flags necessary for ICMP sockets. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol, InternetProtocol. - */ -class icmp -{ -public: - /// The type of a ICMP endpoint. - typedef basic_endpoint endpoint; - - /// Construct to represent the IPv4 ICMP protocol. - static icmp v4() - { - return icmp(ASIO_OS_DEF(IPPROTO_ICMP), - ASIO_OS_DEF(AF_INET)); - } - - /// Construct to represent the IPv6 ICMP protocol. - static icmp v6() - { - return icmp(ASIO_OS_DEF(IPPROTO_ICMPV6), - ASIO_OS_DEF(AF_INET6)); - } - - /// Obtain an identifier for the type of the protocol. - int type() const - { - return ASIO_OS_DEF(SOCK_RAW); - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return protocol_; - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return family_; - } - - /// The ICMP socket type. - typedef basic_raw_socket socket; - - /// The ICMP resolver type. - typedef basic_resolver resolver; - - /// Compare two protocols for equality. - friend bool operator==(const icmp& p1, const icmp& p2) - { - return p1.protocol_ == p2.protocol_ && p1.family_ == p2.family_; - } - - /// Compare two protocols for inequality. - friend bool operator!=(const icmp& p1, const icmp& p2) - { - return p1.protocol_ != p2.protocol_ || p1.family_ != p2.family_; - } - -private: - // Construct with a specific family. - explicit icmp(int protocol_id, int protocol_family) - : protocol_(protocol_id), - family_(protocol_family) - { - } - - int protocol_; - int family_; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_ICMP_HPP diff --git a/scout_sdk/asio/asio/ip/impl/address.hpp b/scout_sdk/asio/asio/ip/impl/address.hpp deleted file mode 100644 index 085b93f..0000000 --- a/scout_sdk/asio/asio/ip/impl/address.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// ip/impl/address.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_ADDRESS_HPP -#define ASIO_IP_IMPL_ADDRESS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -#if !defined(ASIO_NO_DEPRECATED) - -inline address address::from_string(const char* str) -{ - return asio::ip::make_address(str); -} - -inline address address::from_string( - const char* str, asio::error_code& ec) -{ - return asio::ip::make_address(str, ec); -} - -inline address address::from_string(const std::string& str) -{ - return asio::ip::make_address(str); -} - -inline address address::from_string( - const std::string& str, asio::error_code& ec) -{ - return asio::ip::make_address(str, ec); -} - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const address& addr) -{ - return os << addr.to_string().c_str(); -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_IP_IMPL_ADDRESS_HPP diff --git a/scout_sdk/asio/asio/ip/impl/address.ipp b/scout_sdk/asio/asio/ip/impl/address.ipp deleted file mode 100644 index 0523071..0000000 --- a/scout_sdk/asio/asio/ip/impl/address.ipp +++ /dev/null @@ -1,234 +0,0 @@ -// -// ip/impl/address.ipp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_ADDRESS_IPP -#define ASIO_IP_IMPL_ADDRESS_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/throw_error.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/error.hpp" -#include "asio/ip/address.hpp" -#include "asio/ip/bad_address_cast.hpp" -#include "asio/system_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -address::address() - : type_(ipv4), - ipv4_address_(), - ipv6_address_() -{ -} - -address::address(const asio::ip::address_v4& ipv4_address) - : type_(ipv4), - ipv4_address_(ipv4_address), - ipv6_address_() -{ -} - -address::address(const asio::ip::address_v6& ipv6_address) - : type_(ipv6), - ipv4_address_(), - ipv6_address_(ipv6_address) -{ -} - -address::address(const address& other) - : type_(other.type_), - ipv4_address_(other.ipv4_address_), - ipv6_address_(other.ipv6_address_) -{ -} - -#if defined(ASIO_HAS_MOVE) -address::address(address&& other) - : type_(other.type_), - ipv4_address_(other.ipv4_address_), - ipv6_address_(other.ipv6_address_) -{ -} -#endif // defined(ASIO_HAS_MOVE) - -address& address::operator=(const address& other) -{ - type_ = other.type_; - ipv4_address_ = other.ipv4_address_; - ipv6_address_ = other.ipv6_address_; - return *this; -} - -#if defined(ASIO_HAS_MOVE) -address& address::operator=(address&& other) -{ - type_ = other.type_; - ipv4_address_ = other.ipv4_address_; - ipv6_address_ = other.ipv6_address_; - return *this; -} -#endif // defined(ASIO_HAS_MOVE) - -address& address::operator=(const asio::ip::address_v4& ipv4_address) -{ - type_ = ipv4; - ipv4_address_ = ipv4_address; - ipv6_address_ = asio::ip::address_v6(); - return *this; -} - -address& address::operator=(const asio::ip::address_v6& ipv6_address) -{ - type_ = ipv6; - ipv4_address_ = asio::ip::address_v4(); - ipv6_address_ = ipv6_address; - return *this; -} - -address make_address(const char* str) -{ - asio::error_code ec; - address addr = make_address(str, ec); - asio::detail::throw_error(ec); - return addr; -} - -address make_address(const char* str, asio::error_code& ec) -{ - asio::ip::address_v6 ipv6_address = - asio::ip::make_address_v6(str, ec); - if (!ec) - return address(ipv6_address); - - asio::ip::address_v4 ipv4_address = - asio::ip::make_address_v4(str, ec); - if (!ec) - return address(ipv4_address); - - return address(); -} - -address make_address(const std::string& str) -{ - return make_address(str.c_str()); -} - -address make_address(const std::string& str, - asio::error_code& ec) -{ - return make_address(str.c_str(), ec); -} - -#if defined(ASIO_HAS_STRING_VIEW) - -address make_address(string_view str) -{ - return make_address(static_cast(str)); -} - -address make_address(string_view str, - asio::error_code& ec) -{ - return make_address(static_cast(str), ec); -} - -#endif // defined(ASIO_HAS_STRING_VIEW) - -asio::ip::address_v4 address::to_v4() const -{ - if (type_ != ipv4) - { - bad_address_cast ex; - asio::detail::throw_exception(ex); - } - return ipv4_address_; -} - -asio::ip::address_v6 address::to_v6() const -{ - if (type_ != ipv6) - { - bad_address_cast ex; - asio::detail::throw_exception(ex); - } - return ipv6_address_; -} - -std::string address::to_string() const -{ - if (type_ == ipv6) - return ipv6_address_.to_string(); - return ipv4_address_.to_string(); -} - -#if !defined(ASIO_NO_DEPRECATED) -std::string address::to_string(asio::error_code& ec) const -{ - if (type_ == ipv6) - return ipv6_address_.to_string(ec); - return ipv4_address_.to_string(ec); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -bool address::is_loopback() const -{ - return (type_ == ipv4) - ? ipv4_address_.is_loopback() - : ipv6_address_.is_loopback(); -} - -bool address::is_unspecified() const -{ - return (type_ == ipv4) - ? ipv4_address_.is_unspecified() - : ipv6_address_.is_unspecified(); -} - -bool address::is_multicast() const -{ - return (type_ == ipv4) - ? ipv4_address_.is_multicast() - : ipv6_address_.is_multicast(); -} - -bool operator==(const address& a1, const address& a2) -{ - if (a1.type_ != a2.type_) - return false; - if (a1.type_ == address::ipv6) - return a1.ipv6_address_ == a2.ipv6_address_; - return a1.ipv4_address_ == a2.ipv4_address_; -} - -bool operator<(const address& a1, const address& a2) -{ - if (a1.type_ < a2.type_) - return true; - if (a1.type_ > a2.type_) - return false; - if (a1.type_ == address::ipv6) - return a1.ipv6_address_ < a2.ipv6_address_; - return a1.ipv4_address_ < a2.ipv4_address_; -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_IMPL_ADDRESS_IPP diff --git a/scout_sdk/asio/asio/ip/impl/address_v4.hpp b/scout_sdk/asio/asio/ip/impl/address_v4.hpp deleted file mode 100644 index d1cf407..0000000 --- a/scout_sdk/asio/asio/ip/impl/address_v4.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// ip/impl/address_v4.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_ADDRESS_V4_HPP -#define ASIO_IP_IMPL_ADDRESS_V4_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -#if !defined(ASIO_NO_DEPRECATED) - -inline address_v4 address_v4::from_string(const char* str) -{ - return asio::ip::make_address_v4(str); -} - -inline address_v4 address_v4::from_string( - const char* str, asio::error_code& ec) -{ - return asio::ip::make_address_v4(str, ec); -} - -inline address_v4 address_v4::from_string(const std::string& str) -{ - return asio::ip::make_address_v4(str); -} - -inline address_v4 address_v4::from_string( - const std::string& str, asio::error_code& ec) -{ - return asio::ip::make_address_v4(str, ec); -} - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const address_v4& addr) -{ - return os << addr.to_string().c_str(); -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_IP_IMPL_ADDRESS_V4_HPP diff --git a/scout_sdk/asio/asio/ip/impl/address_v4.ipp b/scout_sdk/asio/asio/ip/impl/address_v4.ipp deleted file mode 100644 index 9559add..0000000 --- a/scout_sdk/asio/asio/ip/impl/address_v4.ipp +++ /dev/null @@ -1,210 +0,0 @@ -// -// ip/impl/address_v4.ipp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_ADDRESS_V4_IPP -#define ASIO_IP_IMPL_ADDRESS_V4_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include "asio/error.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/ip/address_v4.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -address_v4::address_v4(const address_v4::bytes_type& bytes) -{ -#if UCHAR_MAX > 0xFF - if (bytes[0] > 0xFF || bytes[1] > 0xFF - || bytes[2] > 0xFF || bytes[3] > 0xFF) - { - std::out_of_range ex("address_v4 from bytes_type"); - asio::detail::throw_exception(ex); - } -#endif // UCHAR_MAX > 0xFF - - using namespace std; // For memcpy. - memcpy(&addr_.s_addr, bytes.data(), 4); -} - -address_v4::address_v4(address_v4::uint_type addr) -{ - if ((std::numeric_limits::max)() > 0xFFFFFFFF) - { - std::out_of_range ex("address_v4 from unsigned integer"); - asio::detail::throw_exception(ex); - } - - addr_.s_addr = asio::detail::socket_ops::host_to_network_long( - static_cast(addr)); -} - -address_v4::bytes_type address_v4::to_bytes() const -{ - using namespace std; // For memcpy. - bytes_type bytes; -#if defined(ASIO_HAS_STD_ARRAY) - memcpy(bytes.data(), &addr_.s_addr, 4); -#else // defined(ASIO_HAS_STD_ARRAY) - memcpy(bytes.elems, &addr_.s_addr, 4); -#endif // defined(ASIO_HAS_STD_ARRAY) - return bytes; -} - -address_v4::uint_type address_v4::to_uint() const -{ - return asio::detail::socket_ops::network_to_host_long(addr_.s_addr); -} - -#if !defined(ASIO_NO_DEPRECATED) -unsigned long address_v4::to_ulong() const -{ - return asio::detail::socket_ops::network_to_host_long(addr_.s_addr); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -std::string address_v4::to_string() const -{ - asio::error_code ec; - char addr_str[asio::detail::max_addr_v4_str_len]; - const char* addr = - asio::detail::socket_ops::inet_ntop( - ASIO_OS_DEF(AF_INET), &addr_, addr_str, - asio::detail::max_addr_v4_str_len, 0, ec); - if (addr == 0) - asio::detail::throw_error(ec); - return addr; -} - -#if !defined(ASIO_NO_DEPRECATED) -std::string address_v4::to_string(asio::error_code& ec) const -{ - char addr_str[asio::detail::max_addr_v4_str_len]; - const char* addr = - asio::detail::socket_ops::inet_ntop( - ASIO_OS_DEF(AF_INET), &addr_, addr_str, - asio::detail::max_addr_v4_str_len, 0, ec); - if (addr == 0) - return std::string(); - return addr; -} -#endif // !defined(ASIO_NO_DEPRECATED) - -bool address_v4::is_loopback() const -{ - return (to_uint() & 0xFF000000) == 0x7F000000; -} - -bool address_v4::is_unspecified() const -{ - return to_uint() == 0; -} - -#if !defined(ASIO_NO_DEPRECATED) -bool address_v4::is_class_a() const -{ - return (to_uint() & 0x80000000) == 0; -} - -bool address_v4::is_class_b() const -{ - return (to_uint() & 0xC0000000) == 0x80000000; -} - -bool address_v4::is_class_c() const -{ - return (to_uint() & 0xE0000000) == 0xC0000000; -} -#endif // !defined(ASIO_NO_DEPRECATED) - -bool address_v4::is_multicast() const -{ - return (to_uint() & 0xF0000000) == 0xE0000000; -} - -#if !defined(ASIO_NO_DEPRECATED) -address_v4 address_v4::broadcast(const address_v4& addr, const address_v4& mask) -{ - return address_v4(addr.to_uint() | (mask.to_uint() ^ 0xFFFFFFFF)); -} - -address_v4 address_v4::netmask(const address_v4& addr) -{ - if (addr.is_class_a()) - return address_v4(0xFF000000); - if (addr.is_class_b()) - return address_v4(0xFFFF0000); - if (addr.is_class_c()) - return address_v4(0xFFFFFF00); - return address_v4(0xFFFFFFFF); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -address_v4 make_address_v4(const char* str) -{ - asio::error_code ec; - address_v4 addr = make_address_v4(str, ec); - asio::detail::throw_error(ec); - return addr; -} - -address_v4 make_address_v4( - const char* str, asio::error_code& ec) -{ - address_v4::bytes_type bytes; - if (asio::detail::socket_ops::inet_pton( - ASIO_OS_DEF(AF_INET), str, &bytes, 0, ec) <= 0) - return address_v4(); - return address_v4(bytes); -} - -address_v4 make_address_v4(const std::string& str) -{ - return make_address_v4(str.c_str()); -} - -address_v4 make_address_v4( - const std::string& str, asio::error_code& ec) -{ - return make_address_v4(str.c_str(), ec); -} - -#if defined(ASIO_HAS_STRING_VIEW) - -address_v4 make_address_v4(string_view str) -{ - return make_address_v4(static_cast(str)); -} - -address_v4 make_address_v4(string_view str, - asio::error_code& ec) -{ - return make_address_v4(static_cast(str), ec); -} - -#endif // defined(ASIO_HAS_STRING_VIEW) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_IMPL_ADDRESS_V4_IPP diff --git a/scout_sdk/asio/asio/ip/impl/address_v6.hpp b/scout_sdk/asio/asio/ip/impl/address_v6.hpp deleted file mode 100644 index 330eafd..0000000 --- a/scout_sdk/asio/asio/ip/impl/address_v6.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// ip/impl/address_v6.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_ADDRESS_V6_HPP -#define ASIO_IP_IMPL_ADDRESS_V6_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -#if !defined(ASIO_NO_DEPRECATED) - -inline address_v6 address_v6::from_string(const char* str) -{ - return asio::ip::make_address_v6(str); -} - -inline address_v6 address_v6::from_string( - const char* str, asio::error_code& ec) -{ - return asio::ip::make_address_v6(str, ec); -} - -inline address_v6 address_v6::from_string(const std::string& str) -{ - return asio::ip::make_address_v6(str); -} - -inline address_v6 address_v6::from_string( - const std::string& str, asio::error_code& ec) -{ - return asio::ip::make_address_v6(str, ec); -} - -#endif // !defined(ASIO_NO_DEPRECATED) - -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const address_v6& addr) -{ - return os << addr.to_string().c_str(); -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_IP_IMPL_ADDRESS_V6_HPP diff --git a/scout_sdk/asio/asio/ip/impl/address_v6.ipp b/scout_sdk/asio/asio/ip/impl/address_v6.ipp deleted file mode 100644 index 36bd68c..0000000 --- a/scout_sdk/asio/asio/ip/impl/address_v6.ipp +++ /dev/null @@ -1,350 +0,0 @@ -// -// ip/impl/address_v6.ipp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_ADDRESS_V6_IPP -#define ASIO_IP_IMPL_ADDRESS_V6_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/error.hpp" -#include "asio/ip/address_v6.hpp" -#include "asio/ip/bad_address_cast.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -address_v6::address_v6() - : addr_(), - scope_id_(0) -{ -} - -address_v6::address_v6(const address_v6::bytes_type& bytes, - unsigned long scope) - : scope_id_(scope) -{ -#if UCHAR_MAX > 0xFF - for (std::size_t i = 0; i < bytes.size(); ++i) - { - if (bytes[i] > 0xFF) - { - std::out_of_range ex("address_v6 from bytes_type"); - asio::detail::throw_exception(ex); - } - } -#endif // UCHAR_MAX > 0xFF - - using namespace std; // For memcpy. - memcpy(addr_.s6_addr, bytes.data(), 16); -} - -address_v6::address_v6(const address_v6& other) - : addr_(other.addr_), - scope_id_(other.scope_id_) -{ -} - -#if defined(ASIO_HAS_MOVE) -address_v6::address_v6(address_v6&& other) - : addr_(other.addr_), - scope_id_(other.scope_id_) -{ -} -#endif // defined(ASIO_HAS_MOVE) - -address_v6& address_v6::operator=(const address_v6& other) -{ - addr_ = other.addr_; - scope_id_ = other.scope_id_; - return *this; -} - -#if defined(ASIO_HAS_MOVE) -address_v6& address_v6::operator=(address_v6&& other) -{ - addr_ = other.addr_; - scope_id_ = other.scope_id_; - return *this; -} -#endif // defined(ASIO_HAS_MOVE) - -address_v6::bytes_type address_v6::to_bytes() const -{ - using namespace std; // For memcpy. - bytes_type bytes; -#if defined(ASIO_HAS_STD_ARRAY) - memcpy(bytes.data(), addr_.s6_addr, 16); -#else // defined(ASIO_HAS_STD_ARRAY) - memcpy(bytes.elems, addr_.s6_addr, 16); -#endif // defined(ASIO_HAS_STD_ARRAY) - return bytes; -} - -std::string address_v6::to_string() const -{ - asio::error_code ec; - char addr_str[asio::detail::max_addr_v6_str_len]; - const char* addr = - asio::detail::socket_ops::inet_ntop( - ASIO_OS_DEF(AF_INET6), &addr_, addr_str, - asio::detail::max_addr_v6_str_len, scope_id_, ec); - if (addr == 0) - asio::detail::throw_error(ec); - return addr; -} - -#if !defined(ASIO_NO_DEPRECATED) -std::string address_v6::to_string(asio::error_code& ec) const -{ - char addr_str[asio::detail::max_addr_v6_str_len]; - const char* addr = - asio::detail::socket_ops::inet_ntop( - ASIO_OS_DEF(AF_INET6), &addr_, addr_str, - asio::detail::max_addr_v6_str_len, scope_id_, ec); - if (addr == 0) - return std::string(); - return addr; -} - -address_v4 address_v6::to_v4() const -{ - if (!is_v4_mapped() && !is_v4_compatible()) - { - bad_address_cast ex; - asio::detail::throw_exception(ex); - } - - address_v4::bytes_type v4_bytes = { { addr_.s6_addr[12], - addr_.s6_addr[13], addr_.s6_addr[14], addr_.s6_addr[15] } }; - return address_v4(v4_bytes); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -bool address_v6::is_loopback() const -{ - return ((addr_.s6_addr[0] == 0) && (addr_.s6_addr[1] == 0) - && (addr_.s6_addr[2] == 0) && (addr_.s6_addr[3] == 0) - && (addr_.s6_addr[4] == 0) && (addr_.s6_addr[5] == 0) - && (addr_.s6_addr[6] == 0) && (addr_.s6_addr[7] == 0) - && (addr_.s6_addr[8] == 0) && (addr_.s6_addr[9] == 0) - && (addr_.s6_addr[10] == 0) && (addr_.s6_addr[11] == 0) - && (addr_.s6_addr[12] == 0) && (addr_.s6_addr[13] == 0) - && (addr_.s6_addr[14] == 0) && (addr_.s6_addr[15] == 1)); -} - -bool address_v6::is_unspecified() const -{ - return ((addr_.s6_addr[0] == 0) && (addr_.s6_addr[1] == 0) - && (addr_.s6_addr[2] == 0) && (addr_.s6_addr[3] == 0) - && (addr_.s6_addr[4] == 0) && (addr_.s6_addr[5] == 0) - && (addr_.s6_addr[6] == 0) && (addr_.s6_addr[7] == 0) - && (addr_.s6_addr[8] == 0) && (addr_.s6_addr[9] == 0) - && (addr_.s6_addr[10] == 0) && (addr_.s6_addr[11] == 0) - && (addr_.s6_addr[12] == 0) && (addr_.s6_addr[13] == 0) - && (addr_.s6_addr[14] == 0) && (addr_.s6_addr[15] == 0)); -} - -bool address_v6::is_link_local() const -{ - return ((addr_.s6_addr[0] == 0xfe) && ((addr_.s6_addr[1] & 0xc0) == 0x80)); -} - -bool address_v6::is_site_local() const -{ - return ((addr_.s6_addr[0] == 0xfe) && ((addr_.s6_addr[1] & 0xc0) == 0xc0)); -} - -bool address_v6::is_v4_mapped() const -{ - return ((addr_.s6_addr[0] == 0) && (addr_.s6_addr[1] == 0) - && (addr_.s6_addr[2] == 0) && (addr_.s6_addr[3] == 0) - && (addr_.s6_addr[4] == 0) && (addr_.s6_addr[5] == 0) - && (addr_.s6_addr[6] == 0) && (addr_.s6_addr[7] == 0) - && (addr_.s6_addr[8] == 0) && (addr_.s6_addr[9] == 0) - && (addr_.s6_addr[10] == 0xff) && (addr_.s6_addr[11] == 0xff)); -} - -#if !defined(ASIO_NO_DEPRECATED) -bool address_v6::is_v4_compatible() const -{ - return ((addr_.s6_addr[0] == 0) && (addr_.s6_addr[1] == 0) - && (addr_.s6_addr[2] == 0) && (addr_.s6_addr[3] == 0) - && (addr_.s6_addr[4] == 0) && (addr_.s6_addr[5] == 0) - && (addr_.s6_addr[6] == 0) && (addr_.s6_addr[7] == 0) - && (addr_.s6_addr[8] == 0) && (addr_.s6_addr[9] == 0) - && (addr_.s6_addr[10] == 0) && (addr_.s6_addr[11] == 0) - && !((addr_.s6_addr[12] == 0) - && (addr_.s6_addr[13] == 0) - && (addr_.s6_addr[14] == 0) - && ((addr_.s6_addr[15] == 0) || (addr_.s6_addr[15] == 1)))); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -bool address_v6::is_multicast() const -{ - return (addr_.s6_addr[0] == 0xff); -} - -bool address_v6::is_multicast_global() const -{ - return ((addr_.s6_addr[0] == 0xff) && ((addr_.s6_addr[1] & 0x0f) == 0x0e)); -} - -bool address_v6::is_multicast_link_local() const -{ - return ((addr_.s6_addr[0] == 0xff) && ((addr_.s6_addr[1] & 0x0f) == 0x02)); -} - -bool address_v6::is_multicast_node_local() const -{ - return ((addr_.s6_addr[0] == 0xff) && ((addr_.s6_addr[1] & 0x0f) == 0x01)); -} - -bool address_v6::is_multicast_org_local() const -{ - return ((addr_.s6_addr[0] == 0xff) && ((addr_.s6_addr[1] & 0x0f) == 0x08)); -} - -bool address_v6::is_multicast_site_local() const -{ - return ((addr_.s6_addr[0] == 0xff) && ((addr_.s6_addr[1] & 0x0f) == 0x05)); -} - -bool operator==(const address_v6& a1, const address_v6& a2) -{ - using namespace std; // For memcmp. - return memcmp(&a1.addr_, &a2.addr_, - sizeof(asio::detail::in6_addr_type)) == 0 - && a1.scope_id_ == a2.scope_id_; -} - -bool operator<(const address_v6& a1, const address_v6& a2) -{ - using namespace std; // For memcmp. - int memcmp_result = memcmp(&a1.addr_, &a2.addr_, - sizeof(asio::detail::in6_addr_type)); - if (memcmp_result < 0) - return true; - if (memcmp_result > 0) - return false; - return a1.scope_id_ < a2.scope_id_; -} - -address_v6 address_v6::loopback() -{ - address_v6 tmp; - tmp.addr_.s6_addr[15] = 1; - return tmp; -} - -#if !defined(ASIO_NO_DEPRECATED) -address_v6 address_v6::v4_mapped(const address_v4& addr) -{ - address_v4::bytes_type v4_bytes = addr.to_bytes(); - bytes_type v6_bytes = { { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0xFF, 0xFF, - v4_bytes[0], v4_bytes[1], v4_bytes[2], v4_bytes[3] } }; - return address_v6(v6_bytes); -} - -address_v6 address_v6::v4_compatible(const address_v4& addr) -{ - address_v4::bytes_type v4_bytes = addr.to_bytes(); - bytes_type v6_bytes = { { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - v4_bytes[0], v4_bytes[1], v4_bytes[2], v4_bytes[3] } }; - return address_v6(v6_bytes); -} -#endif // !defined(ASIO_NO_DEPRECATED) - -address_v6 make_address_v6(const char* str) -{ - asio::error_code ec; - address_v6 addr = make_address_v6(str, ec); - asio::detail::throw_error(ec); - return addr; -} - -address_v6 make_address_v6( - const char* str, asio::error_code& ec) -{ - address_v6::bytes_type bytes; - unsigned long scope_id = 0; - if (asio::detail::socket_ops::inet_pton( - ASIO_OS_DEF(AF_INET6), str, &bytes[0], &scope_id, ec) <= 0) - return address_v6(); - return address_v6(bytes, scope_id); -} - -address_v6 make_address_v6(const std::string& str) -{ - return make_address_v6(str.c_str()); -} - -address_v6 make_address_v6( - const std::string& str, asio::error_code& ec) -{ - return make_address_v6(str.c_str(), ec); -} - -#if defined(ASIO_HAS_STRING_VIEW) - -address_v6 make_address_v6(string_view str) -{ - return make_address_v6(static_cast(str)); -} - -address_v6 make_address_v6(string_view str, - asio::error_code& ec) -{ - return make_address_v6(static_cast(str), ec); -} - -#endif // defined(ASIO_HAS_STRING_VIEW) - -address_v4 make_address_v4( - v4_mapped_t, const address_v6& v6_addr) -{ - if (!v6_addr.is_v4_mapped()) - { - bad_address_cast ex; - asio::detail::throw_exception(ex); - } - - address_v6::bytes_type v6_bytes = v6_addr.to_bytes(); - address_v4::bytes_type v4_bytes = { { v6_bytes[12], - v6_bytes[13], v6_bytes[14], v6_bytes[15] } }; - return address_v4(v4_bytes); -} - -address_v6 make_address_v6( - v4_mapped_t, const address_v4& v4_addr) -{ - address_v4::bytes_type v4_bytes = v4_addr.to_bytes(); - address_v6::bytes_type v6_bytes = { { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0xFF, 0xFF, v4_bytes[0], v4_bytes[1], v4_bytes[2], v4_bytes[3] } }; - return address_v6(v6_bytes); -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_IMPL_ADDRESS_V6_IPP diff --git a/scout_sdk/asio/asio/ip/impl/basic_endpoint.hpp b/scout_sdk/asio/asio/ip/impl/basic_endpoint.hpp deleted file mode 100644 index 5680a43..0000000 --- a/scout_sdk/asio/asio/ip/impl/basic_endpoint.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// -// ip/impl/basic_endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_BASIC_ENDPOINT_HPP -#define ASIO_IP_IMPL_BASIC_ENDPOINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template -std::basic_ostream& operator<<( - std::basic_ostream& os, - const basic_endpoint& endpoint) -{ - asio::ip::detail::endpoint tmp_ep(endpoint.address(), endpoint.port()); - return os << tmp_ep.to_string().c_str(); -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_IP_IMPL_BASIC_ENDPOINT_HPP diff --git a/scout_sdk/asio/asio/ip/impl/host_name.ipp b/scout_sdk/asio/asio/ip/impl/host_name.ipp deleted file mode 100644 index 932ab1c..0000000 --- a/scout_sdk/asio/asio/ip/impl/host_name.ipp +++ /dev/null @@ -1,54 +0,0 @@ -// -// ip/impl/host_name.ipp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_HOST_NAME_IPP -#define ASIO_IP_IMPL_HOST_NAME_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/winsock_init.hpp" -#include "asio/ip/host_name.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -std::string host_name() -{ - char name[1024]; - asio::error_code ec; - if (asio::detail::socket_ops::gethostname(name, sizeof(name), ec) != 0) - { - asio::detail::throw_error(ec); - return std::string(); - } - return std::string(name); -} - -std::string host_name(asio::error_code& ec) -{ - char name[1024]; - if (asio::detail::socket_ops::gethostname(name, sizeof(name), ec) != 0) - return std::string(); - return std::string(name); -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_IMPL_HOST_NAME_IPP diff --git a/scout_sdk/asio/asio/ip/impl/network_v4.hpp b/scout_sdk/asio/asio/ip/impl/network_v4.hpp deleted file mode 100644 index 911a45c..0000000 --- a/scout_sdk/asio/asio/ip/impl/network_v4.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// -// ip/impl/network_v4.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2014 Oliver Kowalke (oliver dot kowalke at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_NETWORK_V4_HPP -#define ASIO_IP_IMPL_NETWORK_V4_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const network_v4& addr) -{ - asio::error_code ec; - std::string s = addr.to_string(ec); - if (ec) - { - if (os.exceptions() & std::basic_ostream::failbit) - asio::detail::throw_error(ec); - else - os.setstate(std::basic_ostream::failbit); - } - else - for (std::string::iterator i = s.begin(); i != s.end(); ++i) - os << os.widen(*i); - return os; -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_IP_IMPL_NETWORK_V4_HPP diff --git a/scout_sdk/asio/asio/ip/impl/network_v4.ipp b/scout_sdk/asio/asio/ip/impl/network_v4.ipp deleted file mode 100644 index 4b27887..0000000 --- a/scout_sdk/asio/asio/ip/impl/network_v4.ipp +++ /dev/null @@ -1,216 +0,0 @@ -// -// ip/impl/network_v4.ipp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2014 Oliver Kowalke (oliver dot kowalke at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_NETWORK_V4_IPP -#define ASIO_IP_IMPL_NETWORK_V4_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include -#include "asio/error.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/ip/network_v4.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -network_v4::network_v4(const address_v4& addr, unsigned short prefix_len) - : address_(addr), - prefix_length_(prefix_len) -{ - if (prefix_len > 32) - { - std::out_of_range ex("prefix length too large"); - asio::detail::throw_exception(ex); - } -} - -network_v4::network_v4(const address_v4& addr, const address_v4& mask) - : address_(addr), - prefix_length_(0) -{ - address_v4::bytes_type mask_bytes = mask.to_bytes(); - bool finished = false; - for (std::size_t i = 0; i < mask_bytes.size(); ++i) - { - if (finished) - { - if (mask_bytes[i]) - { - std::invalid_argument ex("non-contiguous netmask"); - asio::detail::throw_exception(ex); - } - continue; - } - else - { - switch (mask_bytes[i]) - { - case 255: - prefix_length_ += 8; - break; - case 254: // prefix_length_ += 7 - prefix_length_ += 1; - case 252: // prefix_length_ += 6 - prefix_length_ += 1; - case 248: // prefix_length_ += 5 - prefix_length_ += 1; - case 240: // prefix_length_ += 4 - prefix_length_ += 1; - case 224: // prefix_length_ += 3 - prefix_length_ += 1; - case 192: // prefix_length_ += 2 - prefix_length_ += 1; - case 128: // prefix_length_ += 1 - prefix_length_ += 1; - case 0: // nbits += 0 - finished = true; - break; - default: - std::out_of_range ex("non-contiguous netmask"); - asio::detail::throw_exception(ex); - } - } - } -} - -address_v4 network_v4::netmask() const ASIO_NOEXCEPT -{ - uint32_t nmbits = 0xffffffff; - if (prefix_length_ == 0) - nmbits = 0; - else - nmbits = nmbits << (32 - prefix_length_); - return address_v4(nmbits); -} - -address_v4_range network_v4::hosts() const ASIO_NOEXCEPT -{ - return is_host() - ? address_v4_range(address_, address_v4(address_.to_uint() + 1)) - : address_v4_range(address_v4(network().to_uint() + 1), broadcast()); -} - -bool network_v4::is_subnet_of(const network_v4& other) const -{ - if (other.prefix_length_ >= prefix_length_) - return false; // Only real subsets are allowed. - const network_v4 me(address_, other.prefix_length_); - return other.canonical() == me.canonical(); -} - -std::string network_v4::to_string() const -{ - asio::error_code ec; - std::string addr = to_string(ec); - asio::detail::throw_error(ec); - return addr; -} - -std::string network_v4::to_string(asio::error_code& ec) const -{ - using namespace std; // For sprintf. - ec = asio::error_code(); - char prefix_len[16]; -#if defined(ASIO_HAS_SECURE_RTL) - sprintf_s(prefix_len, sizeof(prefix_len), "/%u", prefix_length_); -#else // defined(ASIO_HAS_SECURE_RTL) - sprintf(prefix_len, "/%u", prefix_length_); -#endif // defined(ASIO_HAS_SECURE_RTL) - return address_.to_string() + prefix_len; -} - -network_v4 make_network_v4(const char* str) -{ - return make_network_v4(std::string(str)); -} - -network_v4 make_network_v4(const char* str, asio::error_code& ec) -{ - return make_network_v4(std::string(str), ec); -} - -network_v4 make_network_v4(const std::string& str) -{ - asio::error_code ec; - network_v4 net = make_network_v4(str, ec); - asio::detail::throw_error(ec); - return net; -} - -network_v4 make_network_v4(const std::string& str, - asio::error_code& ec) -{ - std::string::size_type pos = str.find_first_of("/"); - - if (pos == std::string::npos) - { - ec = asio::error::invalid_argument; - return network_v4(); - } - - if (pos == str.size() - 1) - { - ec = asio::error::invalid_argument; - return network_v4(); - } - - std::string::size_type end = str.find_first_not_of("0123456789", pos + 1); - if (end != std::string::npos) - { - ec = asio::error::invalid_argument; - return network_v4(); - } - - const address_v4 addr = make_address_v4(str.substr(0, pos), ec); - if (ec) - return network_v4(); - - const int prefix_len = std::atoi(str.substr(pos + 1).c_str()); - if (prefix_len < 0 || prefix_len > 32) - { - ec = asio::error::invalid_argument; - return network_v4(); - } - - return network_v4(addr, static_cast(prefix_len)); -} - -#if defined(ASIO_HAS_STRING_VIEW) - -network_v4 make_network_v4(string_view str) -{ - return make_network_v4(static_cast(str)); -} - -network_v4 make_network_v4(string_view str, - asio::error_code& ec) -{ - return make_network_v4(static_cast(str), ec); -} - -#endif // defined(ASIO_HAS_STRING_VIEW) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_IMPL_NETWORK_V4_IPP diff --git a/scout_sdk/asio/asio/ip/impl/network_v6.hpp b/scout_sdk/asio/asio/ip/impl/network_v6.hpp deleted file mode 100644 index b0eedad..0000000 --- a/scout_sdk/asio/asio/ip/impl/network_v6.hpp +++ /dev/null @@ -1,53 +0,0 @@ -// -// ip/impl/network_v6.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_NETWORK_V6_HPP -#define ASIO_IP_IMPL_NETWORK_V6_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#if !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const network_v6& addr) -{ - asio::error_code ec; - std::string s = addr.to_string(ec); - if (ec) - { - if (os.exceptions() & std::basic_ostream::failbit) - asio::detail::throw_error(ec); - else - os.setstate(std::basic_ostream::failbit); - } - else - for (std::string::iterator i = s.begin(); i != s.end(); ++i) - os << os.widen(*i); - return os; -} - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_IP_IMPL_NETWORK_V6_HPP diff --git a/scout_sdk/asio/asio/ip/impl/network_v6.ipp b/scout_sdk/asio/asio/ip/impl/network_v6.ipp deleted file mode 100644 index 2e37a99..0000000 --- a/scout_sdk/asio/asio/ip/impl/network_v6.ipp +++ /dev/null @@ -1,185 +0,0 @@ -// -// ip/impl/network_v6.ipp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2014 Oliver Kowalke (oliver dot kowalke at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_IMPL_NETWORK_V6_IPP -#define ASIO_IP_IMPL_NETWORK_V6_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include -#include -#include "asio/error.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/throw_exception.hpp" -#include "asio/ip/network_v6.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -network_v6::network_v6(const address_v6& addr, unsigned short prefix_len) - : address_(addr), - prefix_length_(prefix_len) -{ - if (prefix_len > 128) - { - std::out_of_range ex("prefix length too large"); - asio::detail::throw_exception(ex); - } -} - -ASIO_DECL address_v6 network_v6::network() const ASIO_NOEXCEPT -{ - address_v6::bytes_type bytes(address_.to_bytes()); - for (std::size_t i = 0; i < 16; ++i) - { - if (prefix_length_ <= i * 8) - bytes[i] = 0; - else if (prefix_length_ < (i + 1) * 8) - bytes[i] &= 0xFF00 >> (prefix_length_ % 8); - } - return address_v6(bytes, address_.scope_id()); -} - -address_v6_range network_v6::hosts() const ASIO_NOEXCEPT -{ - address_v6::bytes_type begin_bytes(address_.to_bytes()); - address_v6::bytes_type end_bytes(address_.to_bytes()); - for (std::size_t i = 0; i < 16; ++i) - { - if (prefix_length_ <= i * 8) - { - begin_bytes[i] = 0; - end_bytes[i] = 0xFF; - } - else if (prefix_length_ < (i + 1) * 8) - { - begin_bytes[i] &= 0xFF00 >> (prefix_length_ % 8); - end_bytes[i] |= 0xFF >> (prefix_length_ % 8); - } - } - return address_v6_range( - address_v6_iterator(address_v6(begin_bytes, address_.scope_id())), - ++address_v6_iterator(address_v6(end_bytes, address_.scope_id()))); -} - -bool network_v6::is_subnet_of(const network_v6& other) const -{ - if (other.prefix_length_ >= prefix_length_) - return false; // Only real subsets are allowed. - const network_v6 me(address_, other.prefix_length_); - return other.canonical() == me.canonical(); -} - -std::string network_v6::to_string() const -{ - asio::error_code ec; - std::string addr = to_string(ec); - asio::detail::throw_error(ec); - return addr; -} - -std::string network_v6::to_string(asio::error_code& ec) const -{ - using namespace std; // For sprintf. - ec = asio::error_code(); - char prefix_len[16]; -#if defined(ASIO_HAS_SECURE_RTL) - sprintf_s(prefix_len, sizeof(prefix_len), "/%u", prefix_length_); -#else // defined(ASIO_HAS_SECURE_RTL) - sprintf(prefix_len, "/%u", prefix_length_); -#endif // defined(ASIO_HAS_SECURE_RTL) - return address_.to_string() + prefix_len; -} - -network_v6 make_network_v6(const char* str) -{ - return make_network_v6(std::string(str)); -} - -network_v6 make_network_v6(const char* str, asio::error_code& ec) -{ - return make_network_v6(std::string(str), ec); -} - -network_v6 make_network_v6(const std::string& str) -{ - asio::error_code ec; - network_v6 net = make_network_v6(str, ec); - asio::detail::throw_error(ec); - return net; -} - -network_v6 make_network_v6(const std::string& str, - asio::error_code& ec) -{ - std::string::size_type pos = str.find_first_of("/"); - - if (pos == std::string::npos) - { - ec = asio::error::invalid_argument; - return network_v6(); - } - - if (pos == str.size() - 1) - { - ec = asio::error::invalid_argument; - return network_v6(); - } - - std::string::size_type end = str.find_first_not_of("0123456789", pos + 1); - if (end != std::string::npos) - { - ec = asio::error::invalid_argument; - return network_v6(); - } - - const address_v6 addr = make_address_v6(str.substr(0, pos), ec); - if (ec) - return network_v6(); - - const int prefix_len = std::atoi(str.substr(pos + 1).c_str()); - if (prefix_len < 0 || prefix_len > 128) - { - ec = asio::error::invalid_argument; - return network_v6(); - } - - return network_v6(addr, static_cast(prefix_len)); -} - -#if defined(ASIO_HAS_STRING_VIEW) - -network_v6 make_network_v6(string_view str) -{ - return make_network_v6(static_cast(str)); -} - -network_v6 make_network_v6(string_view str, - asio::error_code& ec) -{ - return make_network_v6(static_cast(str), ec); -} - -#endif // defined(ASIO_HAS_STRING_VIEW) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_IMPL_NETWORK_V6_IPP diff --git a/scout_sdk/asio/asio/ip/multicast.hpp b/scout_sdk/asio/asio/ip/multicast.hpp deleted file mode 100644 index ea624e1..0000000 --- a/scout_sdk/asio/asio/ip/multicast.hpp +++ /dev/null @@ -1,191 +0,0 @@ -// -// ip/multicast.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_MULTICAST_HPP -#define ASIO_IP_MULTICAST_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/ip/detail/socket_option.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { -namespace multicast { - -/// Socket option to join a multicast group on a specified interface. -/** - * Implements the IPPROTO_IP/IP_ADD_MEMBERSHIP socket option. - * - * @par Examples - * Setting the option to join a multicast group: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::address multicast_address = - * asio::ip::address::from_string("225.0.0.1"); - * asio::ip::multicast::join_group option(multicast_address); - * socket.set_option(option); - * @endcode - * - * @par Concepts: - * SettableSocketOption. - */ -#if defined(GENERATING_DOCUMENTATION) -typedef implementation_defined join_group; -#else -typedef asio::ip::detail::socket_option::multicast_request< - ASIO_OS_DEF(IPPROTO_IP), - ASIO_OS_DEF(IP_ADD_MEMBERSHIP), - ASIO_OS_DEF(IPPROTO_IPV6), - ASIO_OS_DEF(IPV6_JOIN_GROUP)> join_group; -#endif - -/// Socket option to leave a multicast group on a specified interface. -/** - * Implements the IPPROTO_IP/IP_DROP_MEMBERSHIP socket option. - * - * @par Examples - * Setting the option to leave a multicast group: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::address multicast_address = - * asio::ip::address::from_string("225.0.0.1"); - * asio::ip::multicast::leave_group option(multicast_address); - * socket.set_option(option); - * @endcode - * - * @par Concepts: - * SettableSocketOption. - */ -#if defined(GENERATING_DOCUMENTATION) -typedef implementation_defined leave_group; -#else -typedef asio::ip::detail::socket_option::multicast_request< - ASIO_OS_DEF(IPPROTO_IP), - ASIO_OS_DEF(IP_DROP_MEMBERSHIP), - ASIO_OS_DEF(IPPROTO_IPV6), - ASIO_OS_DEF(IPV6_LEAVE_GROUP)> leave_group; -#endif - -/// Socket option for local interface to use for outgoing multicast packets. -/** - * Implements the IPPROTO_IP/IP_MULTICAST_IF socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::address_v4 local_interface = - * asio::ip::address_v4::from_string("1.2.3.4"); - * asio::ip::multicast::outbound_interface option(local_interface); - * socket.set_option(option); - * @endcode - * - * @par Concepts: - * SettableSocketOption. - */ -#if defined(GENERATING_DOCUMENTATION) -typedef implementation_defined outbound_interface; -#else -typedef asio::ip::detail::socket_option::network_interface< - ASIO_OS_DEF(IPPROTO_IP), - ASIO_OS_DEF(IP_MULTICAST_IF), - ASIO_OS_DEF(IPPROTO_IPV6), - ASIO_OS_DEF(IPV6_MULTICAST_IF)> outbound_interface; -#endif - -/// Socket option for time-to-live associated with outgoing multicast packets. -/** - * Implements the IPPROTO_IP/IP_MULTICAST_TTL socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::multicast::hops option(4); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::multicast::hops option; - * socket.get_option(option); - * int ttl = option.value(); - * @endcode - * - * @par Concepts: - * GettableSocketOption, SettableSocketOption. - */ -#if defined(GENERATING_DOCUMENTATION) -typedef implementation_defined hops; -#else -typedef asio::ip::detail::socket_option::multicast_hops< - ASIO_OS_DEF(IPPROTO_IP), - ASIO_OS_DEF(IP_MULTICAST_TTL), - ASIO_OS_DEF(IPPROTO_IPV6), - ASIO_OS_DEF(IPV6_MULTICAST_HOPS)> hops; -#endif - -/// Socket option determining whether outgoing multicast packets will be -/// received on the same socket if it is a member of the multicast group. -/** - * Implements the IPPROTO_IP/IP_MULTICAST_LOOP socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::multicast::enable_loopback option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::multicast::enable_loopback option; - * socket.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * GettableSocketOption, SettableSocketOption. - */ -#if defined(GENERATING_DOCUMENTATION) -typedef implementation_defined enable_loopback; -#else -typedef asio::ip::detail::socket_option::multicast_enable_loopback< - ASIO_OS_DEF(IPPROTO_IP), - ASIO_OS_DEF(IP_MULTICAST_LOOP), - ASIO_OS_DEF(IPPROTO_IPV6), - ASIO_OS_DEF(IPV6_MULTICAST_LOOP)> enable_loopback; -#endif - -} // namespace multicast -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_MULTICAST_HPP diff --git a/scout_sdk/asio/asio/ip/network_v4.hpp b/scout_sdk/asio/asio/ip/network_v4.hpp deleted file mode 100644 index e38f60f..0000000 --- a/scout_sdk/asio/asio/ip/network_v4.hpp +++ /dev/null @@ -1,261 +0,0 @@ -// -// ip/network_v4.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2014 Oliver Kowalke (oliver dot kowalke at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_NETWORK_V4_HPP -#define ASIO_IP_NETWORK_V4_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/string_view.hpp" -#include "asio/error_code.hpp" -#include "asio/ip/address_v4_range.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Represents an IPv4 network. -/** - * The asio::ip::network_v4 class provides the ability to use and - * manipulate IP version 4 networks. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class network_v4 -{ -public: - /// Default constructor. - network_v4() ASIO_NOEXCEPT - : address_(), - prefix_length_(0) - { - } - - /// Construct a network based on the specified address and prefix length. - ASIO_DECL network_v4(const address_v4& addr, - unsigned short prefix_len); - - /// Construct network based on the specified address and netmask. - ASIO_DECL network_v4(const address_v4& addr, - const address_v4& mask); - - /// Copy constructor. - network_v4(const network_v4& other) ASIO_NOEXCEPT - : address_(other.address_), - prefix_length_(other.prefix_length_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - network_v4(network_v4&& other) ASIO_NOEXCEPT - : address_(ASIO_MOVE_CAST(address_v4)(other.address_)), - prefix_length_(other.prefix_length_) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from another network. - network_v4& operator=(const network_v4& other) ASIO_NOEXCEPT - { - address_ = other.address_; - prefix_length_ = other.prefix_length_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move-assign from another network. - network_v4& operator=(network_v4&& other) ASIO_NOEXCEPT - { - address_ = ASIO_MOVE_CAST(address_v4)(other.address_); - prefix_length_ = other.prefix_length_; - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// Obtain the address object specified when the network object was created. - address_v4 address() const ASIO_NOEXCEPT - { - return address_; - } - - /// Obtain the prefix length that was specified when the network object was - /// created. - unsigned short prefix_length() const ASIO_NOEXCEPT - { - return prefix_length_; - } - - /// Obtain the netmask that was specified when the network object was created. - ASIO_DECL address_v4 netmask() const ASIO_NOEXCEPT; - - /// Obtain an address object that represents the network address. - address_v4 network() const ASIO_NOEXCEPT - { - return address_v4(address_.to_uint() & netmask().to_uint()); - } - - /// Obtain an address object that represents the network's broadcast address. - address_v4 broadcast() const ASIO_NOEXCEPT - { - return address_v4(network().to_uint() | (netmask().to_uint() ^ 0xFFFFFFFF)); - } - - /// Obtain an address range corresponding to the hosts in the network. - ASIO_DECL address_v4_range hosts() const ASIO_NOEXCEPT; - - /// Obtain the true network address, omitting any host bits. - network_v4 canonical() const ASIO_NOEXCEPT - { - return network_v4(network(), netmask()); - } - - /// Test if network is a valid host address. - bool is_host() const ASIO_NOEXCEPT - { - return prefix_length_ == 32; - } - - /// Test if a network is a real subnet of another network. - ASIO_DECL bool is_subnet_of(const network_v4& other) const; - - /// Get the network as an address in dotted decimal format. - ASIO_DECL std::string to_string() const; - - /// Get the network as an address in dotted decimal format. - ASIO_DECL std::string to_string(asio::error_code& ec) const; - - /// Compare two networks for equality. - friend bool operator==(const network_v4& a, const network_v4& b) - { - return a.address_ == b.address_ && a.prefix_length_ == b.prefix_length_; - } - - /// Compare two networks for inequality. - friend bool operator!=(const network_v4& a, const network_v4& b) - { - return !(a == b); - } - -private: - address_v4 address_; - unsigned short prefix_length_; -}; - -/// Create an IPv4 network from an address and prefix length. -/** - * @relates address_v4 - */ -inline network_v4 make_network_v4( - const address_v4& addr, unsigned short prefix_len) -{ - return network_v4(addr, prefix_len); -} - -/// Create an IPv4 network from an address and netmask. -/** - * @relates address_v4 - */ -inline network_v4 make_network_v4( - const address_v4& addr, const address_v4& mask) -{ - return network_v4(addr, mask); -} - -/// Create an IPv4 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v4 - */ -ASIO_DECL network_v4 make_network_v4(const char* str); - -/// Create an IPv4 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v4 - */ -ASIO_DECL network_v4 make_network_v4( - const char* str, asio::error_code& ec); - -/// Create an IPv4 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v4 - */ -ASIO_DECL network_v4 make_network_v4(const std::string& str); - -/// Create an IPv4 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v4 - */ -ASIO_DECL network_v4 make_network_v4( - const std::string& str, asio::error_code& ec); - -#if defined(ASIO_HAS_STRING_VIEW) \ - || defined(GENERATING_DOCUMENTATION) - -/// Create an IPv4 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v4 - */ -ASIO_DECL network_v4 make_network_v4(string_view str); - -/// Create an IPv4 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v4 - */ -ASIO_DECL network_v4 make_network_v4( - string_view str, asio::error_code& ec); - -#endif // defined(ASIO_HAS_STRING_VIEW) - // || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_NO_IOSTREAM) - -/// Output a network as a string. -/** - * Used to output a human-readable string for a specified network. - * - * @param os The output stream to which the string will be written. - * - * @param net The network to be written. - * - * @return The output stream. - * - * @relates asio::ip::address_v4 - */ -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const network_v4& net); - -#endif // !defined(ASIO_NO_IOSTREAM) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/ip/impl/network_v4.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/ip/impl/network_v4.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_IP_NETWORK_V4_HPP diff --git a/scout_sdk/asio/asio/ip/network_v6.hpp b/scout_sdk/asio/asio/ip/network_v6.hpp deleted file mode 100644 index 7b6b7e6..0000000 --- a/scout_sdk/asio/asio/ip/network_v6.hpp +++ /dev/null @@ -1,235 +0,0 @@ -// -// ip/network_v6.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2014 Oliver Kowalke (oliver dot kowalke at gmail dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_NETWORK_V6_HPP -#define ASIO_IP_NETWORK_V6_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/string_view.hpp" -#include "asio/error_code.hpp" -#include "asio/ip/address_v6_range.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Represents an IPv6 network. -/** - * The asio::ip::network_v6 class provides the ability to use and - * manipulate IP version 6 networks. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class network_v6 -{ -public: - /// Default constructor. - network_v6() ASIO_NOEXCEPT - : address_(), - prefix_length_(0) - { - } - - /// Construct a network based on the specified address and prefix length. - ASIO_DECL network_v6(const address_v6& addr, - unsigned short prefix_len); - - /// Copy constructor. - network_v6(const network_v6& other) ASIO_NOEXCEPT - : address_(other.address_), - prefix_length_(other.prefix_length_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - network_v6(network_v6&& other) ASIO_NOEXCEPT - : address_(ASIO_MOVE_CAST(address_v6)(other.address_)), - prefix_length_(other.prefix_length_) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from another network. - network_v6& operator=(const network_v6& other) ASIO_NOEXCEPT - { - address_ = other.address_; - prefix_length_ = other.prefix_length_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move-assign from another network. - network_v6& operator=(network_v6&& other) ASIO_NOEXCEPT - { - address_ = ASIO_MOVE_CAST(address_v6)(other.address_); - prefix_length_ = other.prefix_length_; - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// Obtain the address object specified when the network object was created. - address_v6 address() const ASIO_NOEXCEPT - { - return address_; - } - - /// Obtain the prefix length that was specified when the network object was - /// created. - unsigned short prefix_length() const ASIO_NOEXCEPT - { - return prefix_length_; - } - - /// Obtain an address object that represents the network address. - ASIO_DECL address_v6 network() const ASIO_NOEXCEPT; - - /// Obtain an address range corresponding to the hosts in the network. - ASIO_DECL address_v6_range hosts() const ASIO_NOEXCEPT; - - /// Obtain the true network address, omitting any host bits. - network_v6 canonical() const ASIO_NOEXCEPT - { - return network_v6(network(), prefix_length()); - } - - /// Test if network is a valid host address. - bool is_host() const ASIO_NOEXCEPT - { - return prefix_length_ == 128; - } - - /// Test if a network is a real subnet of another network. - ASIO_DECL bool is_subnet_of(const network_v6& other) const; - - /// Get the network as an address in dotted decimal format. - ASIO_DECL std::string to_string() const; - - /// Get the network as an address in dotted decimal format. - ASIO_DECL std::string to_string(asio::error_code& ec) const; - - /// Compare two networks for equality. - friend bool operator==(const network_v6& a, const network_v6& b) - { - return a.address_ == b.address_ && a.prefix_length_ == b.prefix_length_; - } - - /// Compare two networks for inequality. - friend bool operator!=(const network_v6& a, const network_v6& b) - { - return !(a == b); - } - -private: - address_v6 address_; - unsigned short prefix_length_; -}; - -/// Create an IPv6 network from an address and prefix length. -/** - * @relates address_v6 - */ -inline network_v6 make_network_v6( - const address_v6& addr, unsigned short prefix_len) -{ - return network_v6(addr, prefix_len); -} - -/// Create an IPv6 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v6 - */ -ASIO_DECL network_v6 make_network_v6(const char* str); - -/// Create an IPv6 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v6 - */ -ASIO_DECL network_v6 make_network_v6( - const char* str, asio::error_code& ec); - -/// Create an IPv6 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v6 - */ -ASIO_DECL network_v6 make_network_v6(const std::string& str); - -/// Create an IPv6 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v6 - */ -ASIO_DECL network_v6 make_network_v6( - const std::string& str, asio::error_code& ec); - -#if defined(ASIO_HAS_STRING_VIEW) \ - || defined(GENERATING_DOCUMENTATION) - -/// Create an IPv6 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v6 - */ -ASIO_DECL network_v6 make_network_v6(string_view str); - -/// Create an IPv6 network from a string containing IP address and prefix -/// length. -/** - * @relates network_v6 - */ -ASIO_DECL network_v6 make_network_v6( - string_view str, asio::error_code& ec); - -#endif // defined(ASIO_HAS_STRING_VIEW) - // || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_NO_IOSTREAM) - -/// Output a network as a string. -/** - * Used to output a human-readable string for a specified network. - * - * @param os The output stream to which the string will be written. - * - * @param net The network to be written. - * - * @return The output stream. - * - * @relates asio::ip::address_v6 - */ -template -std::basic_ostream& operator<<( - std::basic_ostream& os, const network_v6& net); - -#endif // !defined(ASIO_NO_IOSTREAM) - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/ip/impl/network_v6.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/ip/impl/network_v6.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_IP_NETWORK_V6_HPP diff --git a/scout_sdk/asio/asio/ip/resolver_base.hpp b/scout_sdk/asio/asio/ip/resolver_base.hpp deleted file mode 100644 index d32c911..0000000 --- a/scout_sdk/asio/asio/ip/resolver_base.hpp +++ /dev/null @@ -1,129 +0,0 @@ -// -// ip/resolver_base.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_RESOLVER_BASE_HPP -#define ASIO_IP_RESOLVER_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// The resolver_base class is used as a base for the basic_resolver class -/// templates to provide a common place to define the flag constants. -class resolver_base -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// A bitmask type (C++ Std [lib.bitmask.types]). - typedef unspecified flags; - - /// Determine the canonical name of the host specified in the query. - static const flags canonical_name = implementation_defined; - - /// Indicate that returned endpoint is intended for use as a locally bound - /// socket endpoint. - static const flags passive = implementation_defined; - - /// Host name should be treated as a numeric string defining an IPv4 or IPv6 - /// address and no name resolution should be attempted. - static const flags numeric_host = implementation_defined; - - /// Service name should be treated as a numeric string defining a port number - /// and no name resolution should be attempted. - static const flags numeric_service = implementation_defined; - - /// If the query protocol family is specified as IPv6, return IPv4-mapped - /// IPv6 addresses on finding no IPv6 addresses. - static const flags v4_mapped = implementation_defined; - - /// If used with v4_mapped, return all matching IPv6 and IPv4 addresses. - static const flags all_matching = implementation_defined; - - /// Only return IPv4 addresses if a non-loopback IPv4 address is configured - /// for the system. Only return IPv6 addresses if a non-loopback IPv6 address - /// is configured for the system. - static const flags address_configured = implementation_defined; -#else - enum flags - { - canonical_name = ASIO_OS_DEF(AI_CANONNAME), - passive = ASIO_OS_DEF(AI_PASSIVE), - numeric_host = ASIO_OS_DEF(AI_NUMERICHOST), - numeric_service = ASIO_OS_DEF(AI_NUMERICSERV), - v4_mapped = ASIO_OS_DEF(AI_V4MAPPED), - all_matching = ASIO_OS_DEF(AI_ALL), - address_configured = ASIO_OS_DEF(AI_ADDRCONFIG) - }; - - // Implement bitmask operations as shown in C++ Std [lib.bitmask.types]. - - friend flags operator&(flags x, flags y) - { - return static_cast( - static_cast(x) & static_cast(y)); - } - - friend flags operator|(flags x, flags y) - { - return static_cast( - static_cast(x) | static_cast(y)); - } - - friend flags operator^(flags x, flags y) - { - return static_cast( - static_cast(x) ^ static_cast(y)); - } - - friend flags operator~(flags x) - { - return static_cast(~static_cast(x)); - } - - friend flags& operator&=(flags& x, flags y) - { - x = x & y; - return x; - } - - friend flags& operator|=(flags& x, flags y) - { - x = x | y; - return x; - } - - friend flags& operator^=(flags& x, flags y) - { - x = x ^ y; - return x; - } -#endif - -protected: - /// Protected destructor to prevent deletion through this type. - ~resolver_base() - { - } -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_RESOLVER_BASE_HPP diff --git a/scout_sdk/asio/asio/ip/resolver_query_base.hpp b/scout_sdk/asio/asio/ip/resolver_query_base.hpp deleted file mode 100644 index be36858..0000000 --- a/scout_sdk/asio/asio/ip/resolver_query_base.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// -// ip/resolver_query_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_RESOLVER_QUERY_BASE_HPP -#define ASIO_IP_RESOLVER_QUERY_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ip/resolver_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// The resolver_query_base class is used as a base for the -/// basic_resolver_query class templates to provide a common place to define -/// the flag constants. -class resolver_query_base : public resolver_base -{ -protected: - /// Protected destructor to prevent deletion through this type. - ~resolver_query_base() - { - } -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_RESOLVER_QUERY_BASE_HPP diff --git a/scout_sdk/asio/asio/ip/resolver_service.hpp b/scout_sdk/asio/asio/ip/resolver_service.hpp deleted file mode 100644 index 519d72d..0000000 --- a/scout_sdk/asio/asio/ip/resolver_service.hpp +++ /dev/null @@ -1,200 +0,0 @@ -// -// ip/resolver_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_RESOLVER_SERVICE_HPP -#define ASIO_IP_RESOLVER_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/async_result.hpp" -#include "asio/error_code.hpp" -#include "asio/io_context.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" -#include "asio/ip/basic_resolver_query.hpp" -#include "asio/ip/basic_resolver_results.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/winrt_resolver_service.hpp" -#else -# include "asio/detail/resolver_service.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Default service implementation for a resolver. -template -class resolver_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base< - resolver_service > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The protocol type. - typedef InternetProtocol protocol_type; - - /// The endpoint type. - typedef typename InternetProtocol::endpoint endpoint_type; - - /// The query type. - typedef basic_resolver_query query_type; - - /// The iterator type. - typedef basic_resolver_iterator iterator_type; - - /// The results type. - typedef basic_resolver_results results_type; - -private: - // The type of the platform-specific implementation. -#if defined(ASIO_WINDOWS_RUNTIME) - typedef asio::detail::winrt_resolver_service - service_impl_type; -#else - typedef asio::detail::resolver_service - service_impl_type; -#endif - -public: - /// The type of a resolver implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// Construct a new resolver service for the specified io_context. - explicit resolver_service(asio::io_context& io_context) - : asio::detail::service_base< - resolver_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new resolver implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new resolver implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another resolver implementation. - void move_assign(implementation_type& impl, - resolver_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a resolver implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Cancel pending asynchronous operations. - void cancel(implementation_type& impl) - { - service_impl_.cancel(impl); - } - - /// Resolve a query to a list of entries. - results_type resolve(implementation_type& impl, const query_type& query, - asio::error_code& ec) - { - return service_impl_.resolve(impl, query, ec); - } - - /// Asynchronously resolve a query to a list of entries. - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(implementation_type& impl, const query_type& query, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_resolve(impl, query, init.completion_handler); - - return init.result.get(); - } - - /// Resolve an endpoint to a list of entries. - results_type resolve(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - return service_impl_.resolve(impl, endpoint, ec); - } - - /// Asynchronously resolve an endpoint to a list of entries. - template - ASIO_INITFN_RESULT_TYPE(ResolveHandler, - void (asio::error_code, results_type)) - async_resolve(implementation_type& impl, const endpoint_type& endpoint, - ASIO_MOVE_ARG(ResolveHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_resolve(impl, endpoint, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // Perform any fork-related housekeeping. - void notify_fork(asio::io_context::fork_event event) - { - service_impl_.notify_fork(event); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_IP_RESOLVER_SERVICE_HPP diff --git a/scout_sdk/asio/asio/ip/tcp.hpp b/scout_sdk/asio/asio/ip/tcp.hpp deleted file mode 100644 index f1adeb0..0000000 --- a/scout_sdk/asio/asio/ip/tcp.hpp +++ /dev/null @@ -1,155 +0,0 @@ -// -// ip/tcp.hpp -// ~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_TCP_HPP -#define ASIO_IP_TCP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/basic_socket_acceptor.hpp" -#include "asio/basic_socket_iostream.hpp" -#include "asio/basic_stream_socket.hpp" -#include "asio/detail/socket_option.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/ip/basic_endpoint.hpp" -#include "asio/ip/basic_resolver.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" -#include "asio/ip/basic_resolver_query.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Encapsulates the flags needed for TCP. -/** - * The asio::ip::tcp class contains flags necessary for TCP sockets. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol, InternetProtocol. - */ -class tcp -{ -public: - /// The type of a TCP endpoint. - typedef basic_endpoint endpoint; - - /// Construct to represent the IPv4 TCP protocol. - static tcp v4() - { - return tcp(ASIO_OS_DEF(AF_INET)); - } - - /// Construct to represent the IPv6 TCP protocol. - static tcp v6() - { - return tcp(ASIO_OS_DEF(AF_INET6)); - } - - /// Obtain an identifier for the type of the protocol. - int type() const - { - return ASIO_OS_DEF(SOCK_STREAM); - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return ASIO_OS_DEF(IPPROTO_TCP); - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return family_; - } - - /// The TCP socket type. - typedef basic_stream_socket socket; - - /// The TCP acceptor type. - typedef basic_socket_acceptor acceptor; - - /// The TCP resolver type. - typedef basic_resolver resolver; - -#if !defined(ASIO_NO_IOSTREAM) - /// The TCP iostream type. - typedef basic_socket_iostream iostream; -#endif // !defined(ASIO_NO_IOSTREAM) - - /// Socket option for disabling the Nagle algorithm. - /** - * Implements the IPPROTO_TCP/TCP_NODELAY socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::no_delay option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::tcp::no_delay option; - * socket.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined no_delay; -#else - typedef asio::detail::socket_option::boolean< - ASIO_OS_DEF(IPPROTO_TCP), ASIO_OS_DEF(TCP_NODELAY)> no_delay; -#endif - - /// Compare two protocols for equality. - friend bool operator==(const tcp& p1, const tcp& p2) - { - return p1.family_ == p2.family_; - } - - /// Compare two protocols for inequality. - friend bool operator!=(const tcp& p1, const tcp& p2) - { - return p1.family_ != p2.family_; - } - -private: - // Construct with a specific family. - explicit tcp(int protocol_family) - : family_(protocol_family) - { - } - - int family_; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_TCP_HPP diff --git a/scout_sdk/asio/asio/ip/udp.hpp b/scout_sdk/asio/asio/ip/udp.hpp deleted file mode 100644 index 1c93f9b..0000000 --- a/scout_sdk/asio/asio/ip/udp.hpp +++ /dev/null @@ -1,111 +0,0 @@ -// -// ip/udp.hpp -// ~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_UDP_HPP -#define ASIO_IP_UDP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/basic_datagram_socket.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/ip/basic_endpoint.hpp" -#include "asio/ip/basic_resolver.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" -#include "asio/ip/basic_resolver_query.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Encapsulates the flags needed for UDP. -/** - * The asio::ip::udp class contains flags necessary for UDP sockets. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol, InternetProtocol. - */ -class udp -{ -public: - /// The type of a UDP endpoint. - typedef basic_endpoint endpoint; - - /// Construct to represent the IPv4 UDP protocol. - static udp v4() - { - return udp(ASIO_OS_DEF(AF_INET)); - } - - /// Construct to represent the IPv6 UDP protocol. - static udp v6() - { - return udp(ASIO_OS_DEF(AF_INET6)); - } - - /// Obtain an identifier for the type of the protocol. - int type() const - { - return ASIO_OS_DEF(SOCK_DGRAM); - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return ASIO_OS_DEF(IPPROTO_UDP); - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return family_; - } - - /// The UDP socket type. - typedef basic_datagram_socket socket; - - /// The UDP resolver type. - typedef basic_resolver resolver; - - /// Compare two protocols for equality. - friend bool operator==(const udp& p1, const udp& p2) - { - return p1.family_ == p2.family_; - } - - /// Compare two protocols for inequality. - friend bool operator!=(const udp& p1, const udp& p2) - { - return p1.family_ != p2.family_; - } - -private: - // Construct with a specific family. - explicit udp(int protocol_family) - : family_(protocol_family) - { - } - - int family_; -}; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_UDP_HPP diff --git a/scout_sdk/asio/asio/ip/unicast.hpp b/scout_sdk/asio/asio/ip/unicast.hpp deleted file mode 100644 index 14e3e48..0000000 --- a/scout_sdk/asio/asio/ip/unicast.hpp +++ /dev/null @@ -1,70 +0,0 @@ -// -// ip/unicast.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_UNICAST_HPP -#define ASIO_IP_UNICAST_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/ip/detail/socket_option.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { -namespace unicast { - -/// Socket option for time-to-live associated with outgoing unicast packets. -/** - * Implements the IPPROTO_IP/IP_UNICAST_TTL socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::unicast::hops option(4); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::ip::unicast::hops option; - * socket.get_option(option); - * int ttl = option.value(); - * @endcode - * - * @par Concepts: - * GettableSocketOption, SettableSocketOption. - */ -#if defined(GENERATING_DOCUMENTATION) -typedef implementation_defined hops; -#else -typedef asio::ip::detail::socket_option::unicast_hops< - ASIO_OS_DEF(IPPROTO_IP), - ASIO_OS_DEF(IP_TTL), - ASIO_OS_DEF(IPPROTO_IPV6), - ASIO_OS_DEF(IPV6_UNICAST_HOPS)> hops; -#endif - -} // namespace unicast -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_UNICAST_HPP diff --git a/scout_sdk/asio/asio/ip/v6_only.hpp b/scout_sdk/asio/asio/ip/v6_only.hpp deleted file mode 100644 index ac7234e..0000000 --- a/scout_sdk/asio/asio/ip/v6_only.hpp +++ /dev/null @@ -1,69 +0,0 @@ -// -// ip/v6_only.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IP_V6_ONLY_HPP -#define ASIO_IP_V6_ONLY_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/socket_option.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ip { - -/// Socket option for determining whether an IPv6 socket supports IPv6 -/// communication only. -/** - * Implements the IPPROTO_IPV6/IP_V6ONLY socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::v6_only option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::ip::v6_only option; - * socket.get_option(option); - * bool v6_only = option.value(); - * @endcode - * - * @par Concepts: - * GettableSocketOption, SettableSocketOption. - */ -#if defined(GENERATING_DOCUMENTATION) -typedef implementation_defined v6_only; -#elif defined(IPV6_V6ONLY) -typedef asio::detail::socket_option::boolean< - IPPROTO_IPV6, IPV6_V6ONLY> v6_only; -#else -typedef asio::detail::socket_option::boolean< - asio::detail::custom_socket_option_level, - asio::detail::always_fail_option> v6_only; -#endif - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IP_V6_ONLY_HPP diff --git a/scout_sdk/asio/asio/is_executor.hpp b/scout_sdk/asio/asio/is_executor.hpp deleted file mode 100644 index a1661ec..0000000 --- a/scout_sdk/asio/asio/is_executor.hpp +++ /dev/null @@ -1,46 +0,0 @@ -// -// is_executor.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IS_EXECUTOR_HPP -#define ASIO_IS_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/is_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// The is_executor trait detects whether a type T meets the Executor type -/// requirements. -/** - * Class template @c is_executor is a UnaryTypeTrait that is derived from @c - * true_type if the type @c T meets the syntactic requirements for Executor, - * otherwise @c false_type. - */ -template -struct is_executor -#if defined(GENERATING_DOCUMENTATION) - : integral_constant -#else // defined(GENERATING_DOCUMENTATION) - : asio::detail::is_executor -#endif // defined(GENERATING_DOCUMENTATION) -{ -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IS_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/is_read_buffered.hpp b/scout_sdk/asio/asio/is_read_buffered.hpp deleted file mode 100644 index c5a67b2..0000000 --- a/scout_sdk/asio/asio/is_read_buffered.hpp +++ /dev/null @@ -1,59 +0,0 @@ -// -// is_read_buffered.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IS_READ_BUFFERED_HPP -#define ASIO_IS_READ_BUFFERED_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/buffered_read_stream_fwd.hpp" -#include "asio/buffered_stream_fwd.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail { - -template -char is_read_buffered_helper(buffered_stream* s); - -template -char is_read_buffered_helper(buffered_read_stream* s); - -struct is_read_buffered_big_type { char data[10]; }; -is_read_buffered_big_type is_read_buffered_helper(...); - -} // namespace detail - -/// The is_read_buffered class is a traits class that may be used to determine -/// whether a stream type supports buffering of read data. -template -class is_read_buffered -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The value member is true only if the Stream type supports buffering of - /// read data. - static const bool value; -#else - ASIO_STATIC_CONSTANT(bool, - value = sizeof(detail::is_read_buffered_helper((Stream*)0)) == 1); -#endif -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IS_READ_BUFFERED_HPP diff --git a/scout_sdk/asio/asio/is_write_buffered.hpp b/scout_sdk/asio/asio/is_write_buffered.hpp deleted file mode 100644 index e237dd6..0000000 --- a/scout_sdk/asio/asio/is_write_buffered.hpp +++ /dev/null @@ -1,59 +0,0 @@ -// -// is_write_buffered.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_IS_WRITE_BUFFERED_HPP -#define ASIO_IS_WRITE_BUFFERED_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/buffered_stream_fwd.hpp" -#include "asio/buffered_write_stream_fwd.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail { - -template -char is_write_buffered_helper(buffered_stream* s); - -template -char is_write_buffered_helper(buffered_write_stream* s); - -struct is_write_buffered_big_type { char data[10]; }; -is_write_buffered_big_type is_write_buffered_helper(...); - -} // namespace detail - -/// The is_write_buffered class is a traits class that may be used to determine -/// whether a stream type supports buffering of written data. -template -class is_write_buffered -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The value member is true only if the Stream type supports buffering of - /// written data. - static const bool value; -#else - ASIO_STATIC_CONSTANT(bool, - value = sizeof(detail::is_write_buffered_helper((Stream*)0)) == 1); -#endif -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_IS_WRITE_BUFFERED_HPP diff --git a/scout_sdk/asio/asio/local/basic_endpoint.hpp b/scout_sdk/asio/asio/local/basic_endpoint.hpp deleted file mode 100644 index 94e470a..0000000 --- a/scout_sdk/asio/asio/local/basic_endpoint.hpp +++ /dev/null @@ -1,239 +0,0 @@ -// -// local/basic_endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Derived from a public domain implementation written by Daniel Casimiro. -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_LOCAL_BASIC_ENDPOINT_HPP -#define ASIO_LOCAL_BASIC_ENDPOINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_LOCAL_SOCKETS) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/local/detail/endpoint.hpp" - -#if !defined(ASIO_NO_IOSTREAM) -# include -#endif // !defined(ASIO_NO_IOSTREAM) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace local { - -/// Describes an endpoint for a UNIX socket. -/** - * The asio::local::basic_endpoint class template describes an endpoint - * that may be associated with a particular UNIX socket. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * Endpoint. - */ -template -class basic_endpoint -{ -public: - /// The protocol type associated with the endpoint. - typedef Protocol protocol_type; - - /// The type of the endpoint structure. This type is dependent on the - /// underlying implementation of the socket layer. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined data_type; -#else - typedef asio::detail::socket_addr_type data_type; -#endif - - /// Default constructor. - basic_endpoint() - { - } - - /// Construct an endpoint using the specified path name. - basic_endpoint(const char* path_name) - : impl_(path_name) - { - } - - /// Construct an endpoint using the specified path name. - basic_endpoint(const std::string& path_name) - : impl_(path_name) - { - } - - /// Copy constructor. - basic_endpoint(const basic_endpoint& other) - : impl_(other.impl_) - { - } - -#if defined(ASIO_HAS_MOVE) - /// Move constructor. - basic_endpoint(basic_endpoint&& other) - : impl_(other.impl_) - { - } -#endif // defined(ASIO_HAS_MOVE) - - /// Assign from another endpoint. - basic_endpoint& operator=(const basic_endpoint& other) - { - impl_ = other.impl_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) - /// Move-assign from another endpoint. - basic_endpoint& operator=(basic_endpoint&& other) - { - impl_ = other.impl_; - return *this; - } -#endif // defined(ASIO_HAS_MOVE) - - /// The protocol associated with the endpoint. - protocol_type protocol() const - { - return protocol_type(); - } - - /// Get the underlying endpoint in the native type. - data_type* data() - { - return impl_.data(); - } - - /// Get the underlying endpoint in the native type. - const data_type* data() const - { - return impl_.data(); - } - - /// Get the underlying size of the endpoint in the native type. - std::size_t size() const - { - return impl_.size(); - } - - /// Set the underlying size of the endpoint in the native type. - void resize(std::size_t new_size) - { - impl_.resize(new_size); - } - - /// Get the capacity of the endpoint in the native type. - std::size_t capacity() const - { - return impl_.capacity(); - } - - /// Get the path associated with the endpoint. - std::string path() const - { - return impl_.path(); - } - - /// Set the path associated with the endpoint. - void path(const char* p) - { - impl_.path(p); - } - - /// Set the path associated with the endpoint. - void path(const std::string& p) - { - impl_.path(p); - } - - /// Compare two endpoints for equality. - friend bool operator==(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e1.impl_ == e2.impl_; - } - - /// Compare two endpoints for inequality. - friend bool operator!=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e1.impl_ == e2.impl_); - } - - /// Compare endpoints for ordering. - friend bool operator<(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e1.impl_ < e2.impl_; - } - - /// Compare endpoints for ordering. - friend bool operator>(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return e2.impl_ < e1.impl_; - } - - /// Compare endpoints for ordering. - friend bool operator<=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e2 < e1); - } - - /// Compare endpoints for ordering. - friend bool operator>=(const basic_endpoint& e1, - const basic_endpoint& e2) - { - return !(e1 < e2); - } - -private: - // The underlying UNIX domain endpoint. - asio::local::detail::endpoint impl_; -}; - -/// Output an endpoint as a string. -/** - * Used to output a human-readable string for a specified endpoint. - * - * @param os The output stream to which the string will be written. - * - * @param endpoint The endpoint to be written. - * - * @return The output stream. - * - * @relates asio::local::basic_endpoint - */ -template -std::basic_ostream& operator<<( - std::basic_ostream& os, - const basic_endpoint& endpoint) -{ - os << endpoint.path(); - return os; -} - -} // namespace local -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_LOCAL_SOCKETS) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_LOCAL_BASIC_ENDPOINT_HPP diff --git a/scout_sdk/asio/asio/local/connect_pair.hpp b/scout_sdk/asio/asio/local/connect_pair.hpp deleted file mode 100644 index 2f7c090..0000000 --- a/scout_sdk/asio/asio/local/connect_pair.hpp +++ /dev/null @@ -1,106 +0,0 @@ -// -// local/connect_pair.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_LOCAL_CONNECT_PAIR_HPP -#define ASIO_LOCAL_CONNECT_PAIR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_LOCAL_SOCKETS) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_socket.hpp" -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/local/basic_endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace local { - -/// Create a pair of connected sockets. -template -void connect_pair( - basic_socket& socket1, - basic_socket& socket2); - -/// Create a pair of connected sockets. -template -ASIO_SYNC_OP_VOID connect_pair( - basic_socket& socket1, - basic_socket& socket2, - asio::error_code& ec); - -template -inline void connect_pair( - basic_socket& socket1, - basic_socket& socket2) -{ - asio::error_code ec; - connect_pair(socket1, socket2, ec); - asio::detail::throw_error(ec, "connect_pair"); -} - -template -inline ASIO_SYNC_OP_VOID connect_pair( - basic_socket& socket1, - basic_socket& socket2, - asio::error_code& ec) -{ - // Check that this function is only being used with a UNIX domain socket. - asio::local::basic_endpoint* tmp - = static_cast(0); - (void)tmp; - - Protocol protocol; - asio::detail::socket_type sv[2]; - if (asio::detail::socket_ops::socketpair(protocol.family(), - protocol.type(), protocol.protocol(), sv, ec) - == asio::detail::socket_error_retval) - ASIO_SYNC_OP_VOID_RETURN(ec); - - socket1.assign(protocol, sv[0], ec); - if (ec) - { - asio::error_code temp_ec; - asio::detail::socket_ops::state_type state[2] = { 0, 0 }; - asio::detail::socket_ops::close(sv[0], state[0], true, temp_ec); - asio::detail::socket_ops::close(sv[1], state[1], true, temp_ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - socket2.assign(protocol, sv[1], ec); - if (ec) - { - asio::error_code temp_ec; - socket1.close(temp_ec); - asio::detail::socket_ops::state_type state = 0; - asio::detail::socket_ops::close(sv[1], state, true, temp_ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -} // namespace local -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_LOCAL_SOCKETS) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_LOCAL_CONNECT_PAIR_HPP diff --git a/scout_sdk/asio/asio/local/datagram_protocol.hpp b/scout_sdk/asio/asio/local/datagram_protocol.hpp deleted file mode 100644 index b87df2e..0000000 --- a/scout_sdk/asio/asio/local/datagram_protocol.hpp +++ /dev/null @@ -1,80 +0,0 @@ -// -// local/datagram_protocol.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_LOCAL_DATAGRAM_PROTOCOL_HPP -#define ASIO_LOCAL_DATAGRAM_PROTOCOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_LOCAL_SOCKETS) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_datagram_socket.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/local/basic_endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace local { - -/// Encapsulates the flags needed for datagram-oriented UNIX sockets. -/** - * The asio::local::datagram_protocol class contains flags necessary for - * datagram-oriented UNIX domain sockets. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol. - */ -class datagram_protocol -{ -public: - /// Obtain an identifier for the type of the protocol. - int type() const - { - return SOCK_DGRAM; - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return 0; - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return AF_UNIX; - } - - /// The type of a UNIX domain endpoint. - typedef basic_endpoint endpoint; - - /// The UNIX domain socket type. - typedef basic_datagram_socket socket; -}; - -} // namespace local -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_LOCAL_SOCKETS) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_LOCAL_DATAGRAM_PROTOCOL_HPP diff --git a/scout_sdk/asio/asio/local/detail/endpoint.hpp b/scout_sdk/asio/asio/local/detail/endpoint.hpp deleted file mode 100644 index 4870f3b..0000000 --- a/scout_sdk/asio/asio/local/detail/endpoint.hpp +++ /dev/null @@ -1,133 +0,0 @@ -// -// local/detail/endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Derived from a public domain implementation written by Daniel Casimiro. -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_LOCAL_DETAIL_ENDPOINT_HPP -#define ASIO_LOCAL_DETAIL_ENDPOINT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_LOCAL_SOCKETS) - -#include -#include -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace local { -namespace detail { - -// Helper class for implementing a UNIX domain endpoint. -class endpoint -{ -public: - // Default constructor. - ASIO_DECL endpoint(); - - // Construct an endpoint using the specified path name. - ASIO_DECL endpoint(const char* path_name); - - // Construct an endpoint using the specified path name. - ASIO_DECL endpoint(const std::string& path_name); - - // Copy constructor. - endpoint(const endpoint& other) - : data_(other.data_), - path_length_(other.path_length_) - { - } - - // Assign from another endpoint. - endpoint& operator=(const endpoint& other) - { - data_ = other.data_; - path_length_ = other.path_length_; - return *this; - } - - // Get the underlying endpoint in the native type. - asio::detail::socket_addr_type* data() - { - return &data_.base; - } - - // Get the underlying endpoint in the native type. - const asio::detail::socket_addr_type* data() const - { - return &data_.base; - } - - // Get the underlying size of the endpoint in the native type. - std::size_t size() const - { - return path_length_ - + offsetof(asio::detail::sockaddr_un_type, sun_path); - } - - // Set the underlying size of the endpoint in the native type. - ASIO_DECL void resize(std::size_t size); - - // Get the capacity of the endpoint in the native type. - std::size_t capacity() const - { - return sizeof(asio::detail::sockaddr_un_type); - } - - // Get the path associated with the endpoint. - ASIO_DECL std::string path() const; - - // Set the path associated with the endpoint. - ASIO_DECL void path(const char* p); - - // Set the path associated with the endpoint. - ASIO_DECL void path(const std::string& p); - - // Compare two endpoints for equality. - ASIO_DECL friend bool operator==( - const endpoint& e1, const endpoint& e2); - - // Compare endpoints for ordering. - ASIO_DECL friend bool operator<( - const endpoint& e1, const endpoint& e2); - -private: - // The underlying UNIX socket address. - union data_union - { - asio::detail::socket_addr_type base; - asio::detail::sockaddr_un_type local; - } data_; - - // The length of the path associated with the endpoint. - std::size_t path_length_; - - // Initialise with a specified path. - ASIO_DECL void init(const char* path, std::size_t path_length); -}; - -} // namespace detail -} // namespace local -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/local/detail/impl/endpoint.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_LOCAL_SOCKETS) - -#endif // ASIO_LOCAL_DETAIL_ENDPOINT_HPP diff --git a/scout_sdk/asio/asio/local/detail/impl/endpoint.ipp b/scout_sdk/asio/asio/local/detail/impl/endpoint.ipp deleted file mode 100644 index d5bbf50..0000000 --- a/scout_sdk/asio/asio/local/detail/impl/endpoint.ipp +++ /dev/null @@ -1,129 +0,0 @@ -// -// local/detail/impl/endpoint.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Derived from a public domain implementation written by Daniel Casimiro. -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_LOCAL_DETAIL_IMPL_ENDPOINT_IPP -#define ASIO_LOCAL_DETAIL_IMPL_ENDPOINT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_LOCAL_SOCKETS) - -#include -#include "asio/detail/socket_ops.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/local/detail/endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace local { -namespace detail { - -endpoint::endpoint() -{ - init("", 0); -} - -endpoint::endpoint(const char* path_name) -{ - using namespace std; // For strlen. - init(path_name, strlen(path_name)); -} - -endpoint::endpoint(const std::string& path_name) -{ - init(path_name.data(), path_name.length()); -} - -void endpoint::resize(std::size_t new_size) -{ - if (new_size > sizeof(asio::detail::sockaddr_un_type)) - { - asio::error_code ec(asio::error::invalid_argument); - asio::detail::throw_error(ec); - } - else if (new_size == 0) - { - path_length_ = 0; - } - else - { - path_length_ = new_size - - offsetof(asio::detail::sockaddr_un_type, sun_path); - - // The path returned by the operating system may be NUL-terminated. - if (path_length_ > 0 && data_.local.sun_path[path_length_ - 1] == 0) - --path_length_; - } -} - -std::string endpoint::path() const -{ - return std::string(data_.local.sun_path, path_length_); -} - -void endpoint::path(const char* p) -{ - using namespace std; // For strlen. - init(p, strlen(p)); -} - -void endpoint::path(const std::string& p) -{ - init(p.data(), p.length()); -} - -bool operator==(const endpoint& e1, const endpoint& e2) -{ - return e1.path() == e2.path(); -} - -bool operator<(const endpoint& e1, const endpoint& e2) -{ - return e1.path() < e2.path(); -} - -void endpoint::init(const char* path_name, std::size_t path_length) -{ - if (path_length > sizeof(data_.local.sun_path) - 1) - { - // The buffer is not large enough to store this address. - asio::error_code ec(asio::error::name_too_long); - asio::detail::throw_error(ec); - } - - using namespace std; // For memcpy. - data_.local = asio::detail::sockaddr_un_type(); - data_.local.sun_family = AF_UNIX; - if (path_length > 0) - memcpy(data_.local.sun_path, path_name, path_length); - path_length_ = path_length; - - // NUL-terminate normal path names. Names that start with a NUL are in the - // UNIX domain protocol's "abstract namespace" and are not NUL-terminated. - if (path_length > 0 && data_.local.sun_path[0] == 0) - data_.local.sun_path[path_length] = 0; -} - -} // namespace detail -} // namespace local -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_LOCAL_SOCKETS) - -#endif // ASIO_LOCAL_DETAIL_IMPL_ENDPOINT_IPP diff --git a/scout_sdk/asio/asio/local/stream_protocol.hpp b/scout_sdk/asio/asio/local/stream_protocol.hpp deleted file mode 100644 index e2ef5f3..0000000 --- a/scout_sdk/asio/asio/local/stream_protocol.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// -// local/stream_protocol.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_LOCAL_STREAM_PROTOCOL_HPP -#define ASIO_LOCAL_STREAM_PROTOCOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_LOCAL_SOCKETS) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_socket_acceptor.hpp" -#include "asio/basic_socket_iostream.hpp" -#include "asio/basic_stream_socket.hpp" -#include "asio/detail/socket_types.hpp" -#include "asio/local/basic_endpoint.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace local { - -/// Encapsulates the flags needed for stream-oriented UNIX sockets. -/** - * The asio::local::stream_protocol class contains flags necessary for - * stream-oriented UNIX domain sockets. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Safe. - * - * @par Concepts: - * Protocol. - */ -class stream_protocol -{ -public: - /// Obtain an identifier for the type of the protocol. - int type() const - { - return SOCK_STREAM; - } - - /// Obtain an identifier for the protocol. - int protocol() const - { - return 0; - } - - /// Obtain an identifier for the protocol family. - int family() const - { - return AF_UNIX; - } - - /// The type of a UNIX domain endpoint. - typedef basic_endpoint endpoint; - - /// The UNIX domain socket type. - typedef basic_stream_socket socket; - - /// The UNIX domain acceptor type. - typedef basic_socket_acceptor acceptor; - -#if !defined(ASIO_NO_IOSTREAM) - /// The UNIX domain iostream type. - typedef basic_socket_iostream iostream; -#endif // !defined(ASIO_NO_IOSTREAM) -}; - -} // namespace local -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_LOCAL_SOCKETS) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_LOCAL_STREAM_PROTOCOL_HPP diff --git a/scout_sdk/asio/asio/packaged_task.hpp b/scout_sdk/asio/asio/packaged_task.hpp deleted file mode 100644 index 1e20b42..0000000 --- a/scout_sdk/asio/asio/packaged_task.hpp +++ /dev/null @@ -1,126 +0,0 @@ -// -// packaged_task.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_PACKAGED_TASK_HPP -#define ASIO_PACKAGED_TASK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_FUTURE) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/detail/variadic_templates.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if defined(ASIO_HAS_VARIADIC_TEMPLATES) \ - || defined(GENERATING_DOCUMENTATION) - -/// Partial specialisation of @c async_result for @c std::packaged_task. -template -class async_result, Signature> -{ -public: - /// The packaged task is the concrete completion handler type. - typedef std::packaged_task completion_handler_type; - - /// The return type of the initiating function is the future obtained from - /// the packaged task. - typedef std::future return_type; - - /// The constructor extracts the future from the packaged task. - explicit async_result(completion_handler_type& h) - : future_(h.get_future()) - { - } - - /// Returns the packaged task's future. - return_type get() - { - return std::move(future_); - } - -private: - return_type future_; -}; - -#else // defined(ASIO_HAS_VARIADIC_TEMPLATES) - // || defined(GENERATING_DOCUMENTATION) - -template -struct async_result, Signature> -{ - typedef std::packaged_task completion_handler_type; - typedef std::future return_type; - - explicit async_result(completion_handler_type& h) - : future_(h.get_future()) - { - } - - return_type get() - { - return std::move(future_); - } - -private: - return_type future_; -}; - -#define ASIO_PRIVATE_ASYNC_RESULT_DEF(n) \ - template \ - class async_result< \ - std::packaged_task, Signature> \ - { \ - public: \ - typedef std::packaged_task< \ - Result(ASIO_VARIADIC_TARGS(n))> \ - completion_handler_type; \ - \ - typedef std::future return_type; \ - \ - explicit async_result(completion_handler_type& h) \ - : future_(h.get_future()) \ - { \ - } \ - \ - return_type get() \ - { \ - return std::move(future_); \ - } \ - \ - private: \ - return_type future_; \ - }; \ - /**/ - ASIO_VARIADIC_GENERATE(ASIO_PRIVATE_ASYNC_RESULT_DEF) -#undef ASIO_PRIVATE_ASYNC_RESULT_DEF - -#endif // defined(ASIO_HAS_VARIADIC_TEMPLATES) - // || defined(GENERATING_DOCUMENTATION) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_STD_FUTURE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_PACKAGED_TASK_HPP diff --git a/scout_sdk/asio/asio/placeholders.hpp b/scout_sdk/asio/asio/placeholders.hpp deleted file mode 100644 index e71a21e..0000000 --- a/scout_sdk/asio/asio/placeholders.hpp +++ /dev/null @@ -1,151 +0,0 @@ -// -// placeholders.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_PLACEHOLDERS_HPP -#define ASIO_PLACEHOLDERS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_BIND) -# include -#endif // defined(ASIO_HAS_BOOST_BIND) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace placeholders { - -#if defined(GENERATING_DOCUMENTATION) - -/// An argument placeholder, for use with boost::bind(), that corresponds to -/// the error argument of a handler for any of the asynchronous functions. -unspecified error; - -/// An argument placeholder, for use with boost::bind(), that corresponds to -/// the bytes_transferred argument of a handler for asynchronous functions such -/// as asio::basic_stream_socket::async_write_some or -/// asio::async_write. -unspecified bytes_transferred; - -/// An argument placeholder, for use with boost::bind(), that corresponds to -/// the iterator argument of a handler for asynchronous functions such as -/// asio::async_connect. -unspecified iterator; - -/// An argument placeholder, for use with boost::bind(), that corresponds to -/// the results argument of a handler for asynchronous functions such as -/// asio::basic_resolver::async_resolve. -unspecified results; - -/// An argument placeholder, for use with boost::bind(), that corresponds to -/// the results argument of a handler for asynchronous functions such as -/// asio::async_connect. -unspecified endpoint; - -/// An argument placeholder, for use with boost::bind(), that corresponds to -/// the signal_number argument of a handler for asynchronous functions such as -/// asio::signal_set::async_wait. -unspecified signal_number; - -#elif defined(ASIO_HAS_BOOST_BIND) -# if defined(__BORLANDC__) || defined(__GNUC__) - -inline boost::arg<1> error() -{ - return boost::arg<1>(); -} - -inline boost::arg<2> bytes_transferred() -{ - return boost::arg<2>(); -} - -inline boost::arg<2> iterator() -{ - return boost::arg<2>(); -} - -inline boost::arg<2> results() -{ - return boost::arg<2>(); -} - -inline boost::arg<2> endpoint() -{ - return boost::arg<2>(); -} - -inline boost::arg<2> signal_number() -{ - return boost::arg<2>(); -} - -# else - -namespace detail -{ - template - struct placeholder - { - static boost::arg& get() - { - static boost::arg result; - return result; - } - }; -} - -# if defined(ASIO_MSVC) && (ASIO_MSVC < 1400) - -static boost::arg<1>& error - = asio::placeholders::detail::placeholder<1>::get(); -static boost::arg<2>& bytes_transferred - = asio::placeholders::detail::placeholder<2>::get(); -static boost::arg<2>& iterator - = asio::placeholders::detail::placeholder<2>::get(); -static boost::arg<2>& results - = asio::placeholders::detail::placeholder<2>::get(); -static boost::arg<2>& endpoint - = asio::placeholders::detail::placeholder<2>::get(); -static boost::arg<2>& signal_number - = asio::placeholders::detail::placeholder<2>::get(); - -# else - -namespace -{ - boost::arg<1>& error - = asio::placeholders::detail::placeholder<1>::get(); - boost::arg<2>& bytes_transferred - = asio::placeholders::detail::placeholder<2>::get(); - boost::arg<2>& iterator - = asio::placeholders::detail::placeholder<2>::get(); - boost::arg<2>& results - = asio::placeholders::detail::placeholder<2>::get(); - boost::arg<2>& endpoint - = asio::placeholders::detail::placeholder<2>::get(); - boost::arg<2>& signal_number - = asio::placeholders::detail::placeholder<2>::get(); -} // namespace - -# endif -# endif -#endif - -} // namespace placeholders -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_PLACEHOLDERS_HPP diff --git a/scout_sdk/asio/asio/posix/basic_descriptor.hpp b/scout_sdk/asio/asio/posix/basic_descriptor.hpp deleted file mode 100644 index c15da63..0000000 --- a/scout_sdk/asio/asio/posix/basic_descriptor.hpp +++ /dev/null @@ -1,582 +0,0 @@ -// -// posix/basic_descriptor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_POSIX_BASIC_DESCRIPTOR_HPP -#define ASIO_POSIX_BASIC_DESCRIPTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_io_object.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/posix/descriptor_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace posix { - -/// Provides POSIX descriptor functionality. -/** - * The posix::basic_descriptor class template provides the ability to wrap a - * POSIX descriptor. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_descriptor - : public basic_io_object, - public descriptor_base -{ -public: - /// The native representation of a descriptor. - typedef typename DescriptorService::native_handle_type native_handle_type; - - /// A basic_descriptor is always the lowest layer. - typedef basic_descriptor lowest_layer_type; - - /// Construct a basic_descriptor without opening it. - /** - * This constructor creates a descriptor without opening it. - * - * @param io_context The io_context object that the descriptor will use to - * dispatch handlers for any asynchronous operations performed on the - * descriptor. - */ - explicit basic_descriptor(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct a basic_descriptor on an existing native descriptor. - /** - * This constructor creates a descriptor object to hold an existing native - * descriptor. - * - * @param io_context The io_context object that the descriptor will use to - * dispatch handlers for any asynchronous operations performed on the - * descriptor. - * - * @param native_descriptor A native descriptor. - * - * @throws asio::system_error Thrown on failure. - */ - basic_descriptor(asio::io_context& io_context, - const native_handle_type& native_descriptor) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_descriptor, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_descriptor from another. - /** - * This constructor moves a descriptor from one object to another. - * - * @param other The other basic_descriptor object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_descriptor(io_context&) constructor. - */ - basic_descriptor(basic_descriptor&& other) - : basic_io_object( - ASIO_MOVE_CAST(basic_descriptor)(other)) - { - } - - /// Move-assign a basic_descriptor from another. - /** - * This assignment operator moves a descriptor from one object to another. - * - * @param other The other basic_descriptor object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_descriptor(io_context&) constructor. - */ - basic_descriptor& operator=(basic_descriptor&& other) - { - basic_io_object::operator=( - ASIO_MOVE_CAST(basic_descriptor)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since a basic_descriptor cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since a basic_descriptor cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } - - /// Assign an existing native descriptor to the descriptor. - /* - * This function opens the descriptor to hold an existing native descriptor. - * - * @param native_descriptor A native descriptor. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const native_handle_type& native_descriptor) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_descriptor, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native descriptor to the descriptor. - /* - * This function opens the descriptor to hold an existing native descriptor. - * - * @param native_descriptor A native descriptor. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const native_handle_type& native_descriptor, - asio::error_code& ec) - { - this->get_service().assign( - this->get_implementation(), native_descriptor, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the descriptor is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the descriptor. - /** - * This function is used to close the descriptor. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. Note that, even if - * the function indicates an error, the underlying descriptor is closed. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the descriptor. - /** - * This function is used to close the descriptor. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. Note that, even if - * the function indicates an error, the underlying descriptor is closed. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native descriptor representation. - /** - * This function may be used to obtain the underlying representation of the - * descriptor. This is intended to allow access to native descriptor - * functionality that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Release ownership of the native descriptor implementation. - /** - * This function may be used to obtain the underlying representation of the - * descriptor. After calling this function, @c is_open() returns false. The - * caller is responsible for closing the descriptor. - * - * All outstanding asynchronous read or write operations will finish - * immediately, and the handlers for cancelled operations will be passed the - * asio::error::operation_aborted error. - */ - native_handle_type release() - { - return this->get_service().release(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the descriptor. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the descriptor. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the descriptor. - /** - * This function is used to execute an IO control command on the descriptor. - * - * @param command The IO control command to be performed on the descriptor. - * - * @throws asio::system_error Thrown on failure. - * - * @sa IoControlCommand @n - * asio::posix::descriptor_base::bytes_readable @n - * asio::posix::descriptor_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * asio::posix::stream_descriptor::bytes_readable command; - * descriptor.io_control(command); - * std::size_t bytes_readable = command.get(); - * @endcode - */ - template - void io_control(IoControlCommand& command) - { - asio::error_code ec; - this->get_service().io_control(this->get_implementation(), command, ec); - asio::detail::throw_error(ec, "io_control"); - } - - /// Perform an IO control command on the descriptor. - /** - * This function is used to execute an IO control command on the descriptor. - * - * @param command The IO control command to be performed on the descriptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa IoControlCommand @n - * asio::posix::descriptor_base::bytes_readable @n - * asio::posix::descriptor_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * asio::posix::stream_descriptor::bytes_readable command; - * asio::error_code ec; - * descriptor.io_control(command, ec); - * if (ec) - * { - * // An error occurred. - * } - * std::size_t bytes_readable = command.get(); - * @endcode - */ - template - ASIO_SYNC_OP_VOID io_control(IoControlCommand& command, - asio::error_code& ec) - { - this->get_service().io_control(this->get_implementation(), command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the descriptor. - /** - * @returns @c true if the descriptor's synchronous operations will fail with - * asio::error::would_block if they are unable to perform the requested - * operation immediately. If @c false, synchronous operations will block - * until complete. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - bool non_blocking() const - { - return this->get_service().non_blocking(this->get_implementation()); - } - - /// Sets the non-blocking mode of the descriptor. - /** - * @param mode If @c true, the descriptor's synchronous operations will fail - * with asio::error::would_block if they are unable to perform the - * requested operation immediately. If @c false, synchronous operations will - * block until complete. - * - * @throws asio::system_error Thrown on failure. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - void non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().non_blocking(this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "non_blocking"); - } - - /// Sets the non-blocking mode of the descriptor. - /** - * @param mode If @c true, the descriptor's synchronous operations will fail - * with asio::error::would_block if they are unable to perform the - * requested operation immediately. If @c false, synchronous operations will - * block until complete. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - ASIO_SYNC_OP_VOID non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().non_blocking(this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native descriptor implementation. - /** - * This function is used to retrieve the non-blocking mode of the underlying - * native descriptor. This mode has no effect on the behaviour of the - * descriptor object's synchronous operations. - * - * @returns @c true if the underlying descriptor is in non-blocking mode and - * direct system calls may fail with asio::error::would_block (or the - * equivalent system error). - * - * @note The current non-blocking mode is cached by the descriptor object. - * Consequently, the return value may be incorrect if the non-blocking mode - * was set directly on the native descriptor. - */ - bool native_non_blocking() const - { - return this->get_service().native_non_blocking( - this->get_implementation()); - } - - /// Sets the non-blocking mode of the native descriptor implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native descriptor. It has no effect on the behaviour of the descriptor - * object's synchronous operations. - * - * @param mode If @c true, the underlying descriptor is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @throws asio::system_error Thrown on failure. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - */ - void native_non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "native_non_blocking"); - } - - /// Sets the non-blocking mode of the native descriptor implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native descriptor. It has no effect on the behaviour of the descriptor - * object's synchronous operations. - * - * @param mode If @c true, the underlying descriptor is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @param ec Set to indicate what error occurred, if any. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - */ - ASIO_SYNC_OP_VOID native_non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the descriptor to become ready to read, ready to write, or to - /// have pending error conditions. - /** - * This function is used to perform a blocking wait for a descriptor to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired descriptor state. - * - * @par Example - * Waiting for a descriptor to become readable. - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * descriptor.wait(asio::posix::stream_descriptor::wait_read); - * @endcode - */ - void wait(wait_type w) - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), w, ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Wait for the descriptor to become ready to read, ready to write, or to - /// have pending error conditions. - /** - * This function is used to perform a blocking wait for a descriptor to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired descriptor state. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * Waiting for a descriptor to become readable. - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * asio::error_code ec; - * descriptor.wait(asio::posix::stream_descriptor::wait_read, ec); - * @endcode - */ - ASIO_SYNC_OP_VOID wait(wait_type w, asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the descriptor to become ready to read, ready to - /// write, or to have pending error conditions. - /** - * This function is used to perform an asynchronous wait for a descriptor to - * enter a ready to read, write or error condition state. - * - * @param w Specifies the desired descriptor state. - * - * @param handler The handler to be called when the wait operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void wait_handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Wait succeeded. - * } - * } - * - * ... - * - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * descriptor.async_wait( - * asio::posix::stream_descriptor::wait_read, - * wait_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(wait_type w, ASIO_MOVE_ARG(WaitHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WaitHandler. - ASIO_WAIT_HANDLER_CHECK(WaitHandler, handler) type_check; - - return this->get_service().async_wait(this->get_implementation(), - w, ASIO_MOVE_CAST(WaitHandler)(handler)); - } - -protected: - /// Protected destructor to prevent deletion through this type. - ~basic_descriptor() - { - } -}; - -} // namespace posix -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_POSIX_BASIC_DESCRIPTOR_HPP diff --git a/scout_sdk/asio/asio/posix/basic_stream_descriptor.hpp b/scout_sdk/asio/asio/posix/basic_stream_descriptor.hpp deleted file mode 100644 index acd5cb6..0000000 --- a/scout_sdk/asio/asio/posix/basic_stream_descriptor.hpp +++ /dev/null @@ -1,362 +0,0 @@ -// -// posix/basic_stream_descriptor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_POSIX_BASIC_STREAM_DESCRIPTOR_HPP -#define ASIO_POSIX_BASIC_STREAM_DESCRIPTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/posix/basic_descriptor.hpp" -#include "asio/posix/stream_descriptor_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace posix { - -/// Provides stream-oriented descriptor functionality. -/** - * The posix::basic_stream_descriptor class template provides asynchronous and - * blocking stream-oriented descriptor functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -template -class basic_stream_descriptor - : public basic_descriptor -{ -public: - /// The native representation of a descriptor. - typedef typename StreamDescriptorService::native_handle_type - native_handle_type; - - /// Construct a basic_stream_descriptor without opening it. - /** - * This constructor creates a stream descriptor without opening it. The - * descriptor needs to be opened and then connected or accepted before data - * can be sent or received on it. - * - * @param io_context The io_context object that the stream descriptor will - * use to dispatch handlers for any asynchronous operations performed on the - * descriptor. - */ - explicit basic_stream_descriptor(asio::io_context& io_context) - : basic_descriptor(io_context) - { - } - - /// Construct a basic_stream_descriptor on an existing native descriptor. - /** - * This constructor creates a stream descriptor object to hold an existing - * native descriptor. - * - * @param io_context The io_context object that the stream descriptor will - * use to dispatch handlers for any asynchronous operations performed on the - * descriptor. - * - * @param native_descriptor The new underlying descriptor implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_stream_descriptor(asio::io_context& io_context, - const native_handle_type& native_descriptor) - : basic_descriptor(io_context, native_descriptor) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_stream_descriptor from another. - /** - * This constructor moves a stream descriptor from one object to another. - * - * @param other The other basic_stream_descriptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_descriptor(io_context&) constructor. - */ - basic_stream_descriptor(basic_stream_descriptor&& other) - : basic_descriptor( - ASIO_MOVE_CAST(basic_stream_descriptor)(other)) - { - } - - /// Move-assign a basic_stream_descriptor from another. - /** - * This assignment operator moves a stream descriptor from one object to - * another. - * - * @param other The other basic_stream_descriptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_descriptor(io_context&) constructor. - */ - basic_stream_descriptor& operator=(basic_stream_descriptor&& other) - { - basic_descriptor::operator=( - ASIO_MOVE_CAST(basic_stream_descriptor)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Write some data to the descriptor. - /** - * This function is used to write data to the stream descriptor. The function - * call will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the descriptor. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.write_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "write_some"); - return s; - } - - /// Write some data to the descriptor. - /** - * This function is used to write data to the stream descriptor. The function - * call will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the descriptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().write_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write data to the stream - * descriptor. The function call always returns immediately. - * - * @param buffers One or more data buffers to be written to the descriptor. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.async_write_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - return this->get_service().async_write_some(this->get_implementation(), - buffers, ASIO_MOVE_CAST(WriteHandler)(handler)); - } - - /// Read some data from the descriptor. - /** - * This function is used to read data from the stream descriptor. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.read_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "read_some"); - return s; - } - - /// Read some data from the descriptor. - /** - * This function is used to read data from the stream descriptor. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().read_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read data from the stream - * descriptor. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read function if you need to ensure that the - * requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.async_read_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - return this->get_service().async_read_some(this->get_implementation(), - buffers, ASIO_MOVE_CAST(ReadHandler)(handler)); - } -}; - -} // namespace posix -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_POSIX_BASIC_STREAM_DESCRIPTOR_HPP diff --git a/scout_sdk/asio/asio/posix/descriptor.hpp b/scout_sdk/asio/asio/posix/descriptor.hpp deleted file mode 100644 index d0cee1a..0000000 --- a/scout_sdk/asio/asio/posix/descriptor.hpp +++ /dev/null @@ -1,644 +0,0 @@ -// -// posix/descriptor.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_POSIX_DESCRIPTOR_HPP -#define ASIO_POSIX_DESCRIPTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/async_result.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/reactive_descriptor_service.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/posix/descriptor_base.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#define ASIO_SVC_T asio::detail::reactive_descriptor_service - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace posix { - -/// Provides POSIX descriptor functionality. -/** - * The posix::descriptor class template provides the ability to wrap a - * POSIX descriptor. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class descriptor - : ASIO_SVC_ACCESS basic_io_object, - public descriptor_base -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The native representation of a descriptor. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef ASIO_SVC_T::native_handle_type native_handle_type; -#endif - - /// A descriptor is always the lowest layer. - typedef descriptor lowest_layer_type; - - /// Construct a descriptor without opening it. - /** - * This constructor creates a descriptor without opening it. - * - * @param io_context The io_context object that the descriptor will use to - * dispatch handlers for any asynchronous operations performed on the - * descriptor. - */ - explicit descriptor(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct a descriptor on an existing native descriptor. - /** - * This constructor creates a descriptor object to hold an existing native - * descriptor. - * - * @param io_context The io_context object that the descriptor will use to - * dispatch handlers for any asynchronous operations performed on the - * descriptor. - * - * @param native_descriptor A native descriptor. - * - * @throws asio::system_error Thrown on failure. - */ - descriptor(asio::io_context& io_context, - const native_handle_type& native_descriptor) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_descriptor, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a descriptor from another. - /** - * This constructor moves a descriptor from one object to another. - * - * @param other The other descriptor object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c descriptor(io_context&) constructor. - */ - descriptor(descriptor&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign a descriptor from another. - /** - * This assignment operator moves a descriptor from one object to another. - * - * @param other The other descriptor object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c descriptor(io_context&) constructor. - */ - descriptor& operator=(descriptor&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since a descriptor cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since a descriptor cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } - - /// Assign an existing native descriptor to the descriptor. - /* - * This function opens the descriptor to hold an existing native descriptor. - * - * @param native_descriptor A native descriptor. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const native_handle_type& native_descriptor) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_descriptor, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native descriptor to the descriptor. - /* - * This function opens the descriptor to hold an existing native descriptor. - * - * @param native_descriptor A native descriptor. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const native_handle_type& native_descriptor, - asio::error_code& ec) - { - this->get_service().assign( - this->get_implementation(), native_descriptor, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the descriptor is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the descriptor. - /** - * This function is used to close the descriptor. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. Note that, even if - * the function indicates an error, the underlying descriptor is closed. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the descriptor. - /** - * This function is used to close the descriptor. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. Note that, even if - * the function indicates an error, the underlying descriptor is closed. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native descriptor representation. - /** - * This function may be used to obtain the underlying representation of the - * descriptor. This is intended to allow access to native descriptor - * functionality that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Release ownership of the native descriptor implementation. - /** - * This function may be used to obtain the underlying representation of the - * descriptor. After calling this function, @c is_open() returns false. The - * caller is responsible for closing the descriptor. - * - * All outstanding asynchronous read or write operations will finish - * immediately, and the handlers for cancelled operations will be passed the - * asio::error::operation_aborted error. - */ - native_handle_type release() - { - return this->get_service().release(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the descriptor. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the descriptor. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the descriptor. - /** - * This function is used to execute an IO control command on the descriptor. - * - * @param command The IO control command to be performed on the descriptor. - * - * @throws asio::system_error Thrown on failure. - * - * @sa IoControlCommand @n - * asio::posix::descriptor_base::bytes_readable @n - * asio::posix::descriptor_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * asio::posix::stream_descriptor::bytes_readable command; - * descriptor.io_control(command); - * std::size_t bytes_readable = command.get(); - * @endcode - */ - template - void io_control(IoControlCommand& command) - { - asio::error_code ec; - this->get_service().io_control(this->get_implementation(), command, ec); - asio::detail::throw_error(ec, "io_control"); - } - - /// Perform an IO control command on the descriptor. - /** - * This function is used to execute an IO control command on the descriptor. - * - * @param command The IO control command to be performed on the descriptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa IoControlCommand @n - * asio::posix::descriptor_base::bytes_readable @n - * asio::posix::descriptor_base::non_blocking_io - * - * @par Example - * Getting the number of bytes ready to read: - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * asio::posix::stream_descriptor::bytes_readable command; - * asio::error_code ec; - * descriptor.io_control(command, ec); - * if (ec) - * { - * // An error occurred. - * } - * std::size_t bytes_readable = command.get(); - * @endcode - */ - template - ASIO_SYNC_OP_VOID io_control(IoControlCommand& command, - asio::error_code& ec) - { - this->get_service().io_control(this->get_implementation(), command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the descriptor. - /** - * @returns @c true if the descriptor's synchronous operations will fail with - * asio::error::would_block if they are unable to perform the requested - * operation immediately. If @c false, synchronous operations will block - * until complete. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - bool non_blocking() const - { - return this->get_service().non_blocking(this->get_implementation()); - } - - /// Sets the non-blocking mode of the descriptor. - /** - * @param mode If @c true, the descriptor's synchronous operations will fail - * with asio::error::would_block if they are unable to perform the - * requested operation immediately. If @c false, synchronous operations will - * block until complete. - * - * @throws asio::system_error Thrown on failure. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - void non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().non_blocking(this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "non_blocking"); - } - - /// Sets the non-blocking mode of the descriptor. - /** - * @param mode If @c true, the descriptor's synchronous operations will fail - * with asio::error::would_block if they are unable to perform the - * requested operation immediately. If @c false, synchronous operations will - * block until complete. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note The non-blocking mode has no effect on the behaviour of asynchronous - * operations. Asynchronous operations will never fail with the error - * asio::error::would_block. - */ - ASIO_SYNC_OP_VOID non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().non_blocking(this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native descriptor implementation. - /** - * This function is used to retrieve the non-blocking mode of the underlying - * native descriptor. This mode has no effect on the behaviour of the - * descriptor object's synchronous operations. - * - * @returns @c true if the underlying descriptor is in non-blocking mode and - * direct system calls may fail with asio::error::would_block (or the - * equivalent system error). - * - * @note The current non-blocking mode is cached by the descriptor object. - * Consequently, the return value may be incorrect if the non-blocking mode - * was set directly on the native descriptor. - */ - bool native_non_blocking() const - { - return this->get_service().native_non_blocking( - this->get_implementation()); - } - - /// Sets the non-blocking mode of the native descriptor implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native descriptor. It has no effect on the behaviour of the descriptor - * object's synchronous operations. - * - * @param mode If @c true, the underlying descriptor is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @throws asio::system_error Thrown on failure. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - */ - void native_non_blocking(bool mode) - { - asio::error_code ec; - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - asio::detail::throw_error(ec, "native_non_blocking"); - } - - /// Sets the non-blocking mode of the native descriptor implementation. - /** - * This function is used to modify the non-blocking mode of the underlying - * native descriptor. It has no effect on the behaviour of the descriptor - * object's synchronous operations. - * - * @param mode If @c true, the underlying descriptor is put into non-blocking - * mode and direct system calls may fail with asio::error::would_block - * (or the equivalent system error). - * - * @param ec Set to indicate what error occurred, if any. If the @c mode is - * @c false, but the current value of @c non_blocking() is @c true, this - * function fails with asio::error::invalid_argument, as the - * combination does not make sense. - */ - ASIO_SYNC_OP_VOID native_non_blocking( - bool mode, asio::error_code& ec) - { - this->get_service().native_non_blocking( - this->get_implementation(), mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the descriptor to become ready to read, ready to write, or to - /// have pending error conditions. - /** - * This function is used to perform a blocking wait for a descriptor to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired descriptor state. - * - * @par Example - * Waiting for a descriptor to become readable. - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * descriptor.wait(asio::posix::stream_descriptor::wait_read); - * @endcode - */ - void wait(wait_type w) - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), w, ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Wait for the descriptor to become ready to read, ready to write, or to - /// have pending error conditions. - /** - * This function is used to perform a blocking wait for a descriptor to enter - * a ready to read, write or error condition state. - * - * @param w Specifies the desired descriptor state. - * - * @param ec Set to indicate what error occurred, if any. - * - * @par Example - * Waiting for a descriptor to become readable. - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * asio::error_code ec; - * descriptor.wait(asio::posix::stream_descriptor::wait_read, ec); - * @endcode - */ - ASIO_SYNC_OP_VOID wait(wait_type w, asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the descriptor to become ready to read, ready to - /// write, or to have pending error conditions. - /** - * This function is used to perform an asynchronous wait for a descriptor to - * enter a ready to read, write or error condition state. - * - * @param w Specifies the desired descriptor state. - * - * @param handler The handler to be called when the wait operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * @code - * void wait_handler(const asio::error_code& error) - * { - * if (!error) - * { - * // Wait succeeded. - * } - * } - * - * ... - * - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * descriptor.async_wait( - * asio::posix::stream_descriptor::wait_read, - * wait_handler); - * @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(wait_type w, ASIO_MOVE_ARG(WaitHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WaitHandler. - ASIO_WAIT_HANDLER_CHECK(WaitHandler, handler) type_check; - - async_completion init(handler); - - this->get_service().async_wait( - this->get_implementation(), w, init.completion_handler); - - return init.result.get(); - } - -protected: - /// Protected destructor to prevent deletion through this type. - /** - * This function destroys the descriptor, cancelling any outstanding - * asynchronous wait operations associated with the descriptor as if by - * calling @c cancel. - */ - ~descriptor() - { - } -}; - -} // namespace posix -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#undef ASIO_SVC_T - -#endif // defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) - // || defined(GENERATING_DOCUMENTATION) - -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_POSIX_DESCRIPTOR_HPP diff --git a/scout_sdk/asio/asio/posix/descriptor_base.hpp b/scout_sdk/asio/asio/posix/descriptor_base.hpp deleted file mode 100644 index 4aac04f..0000000 --- a/scout_sdk/asio/asio/posix/descriptor_base.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// -// posix/descriptor_base.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_POSIX_DESCRIPTOR_BASE_HPP -#define ASIO_POSIX_DESCRIPTOR_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/detail/io_control.hpp" -#include "asio/detail/socket_option.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace posix { - -/// The descriptor_base class is used as a base for the descriptor class as a -/// place to define the associated IO control commands. -class descriptor_base -{ -public: - /// Wait types. - /** - * For use with descriptor::wait() and descriptor::async_wait(). - */ - enum wait_type - { - /// Wait for a descriptor to become ready to read. - wait_read, - - /// Wait for a descriptor to become ready to write. - wait_write, - - /// Wait for a descriptor to have error conditions pending. - wait_error - }; - - /// IO control command to get the amount of data that can be read without - /// blocking. - /** - * Implements the FIONREAD IO control command. - * - * @par Example - * @code - * asio::posix::stream_descriptor descriptor(io_context); - * ... - * asio::descriptor_base::bytes_readable command(true); - * descriptor.io_control(command); - * std::size_t bytes_readable = command.get(); - * @endcode - * - * @par Concepts: - * IoControlCommand. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined bytes_readable; -#else - typedef asio::detail::io_control::bytes_readable bytes_readable; -#endif - -protected: - /// Protected destructor to prevent deletion through this type. - ~descriptor_base() - { - } -}; - -} // namespace posix -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_POSIX_DESCRIPTOR_BASE_HPP diff --git a/scout_sdk/asio/asio/posix/stream_descriptor.hpp b/scout_sdk/asio/asio/posix/stream_descriptor.hpp deleted file mode 100644 index abb426a..0000000 --- a/scout_sdk/asio/asio/posix/stream_descriptor.hpp +++ /dev/null @@ -1,360 +0,0 @@ -// -// posix/stream_descriptor.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_POSIX_STREAM_DESCRIPTOR_HPP -#define ASIO_POSIX_STREAM_DESCRIPTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/posix/descriptor.hpp" - -#if defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) \ - || defined(GENERATING_DOCUMENTATION) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/posix/basic_stream_descriptor.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -namespace asio { -namespace posix { - -#if defined(ASIO_ENABLE_OLD_SERVICES) -// Typedef for the typical usage of a stream-oriented descriptor. -typedef basic_stream_descriptor<> stream_descriptor; -#else // defined(ASIO_ENABLE_OLD_SERVICES) -/// Provides stream-oriented descriptor functionality. -/** - * The posix::stream_descriptor class template provides asynchronous and - * blocking stream-oriented descriptor functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -class stream_descriptor - : public descriptor -{ -public: - /// Construct a stream_descriptor without opening it. - /** - * This constructor creates a stream descriptor without opening it. The - * descriptor needs to be opened and then connected or accepted before data - * can be sent or received on it. - * - * @param io_context The io_context object that the stream descriptor will - * use to dispatch handlers for any asynchronous operations performed on the - * descriptor. - */ - explicit stream_descriptor(asio::io_context& io_context) - : descriptor(io_context) - { - } - - /// Construct a stream_descriptor on an existing native descriptor. - /** - * This constructor creates a stream descriptor object to hold an existing - * native descriptor. - * - * @param io_context The io_context object that the stream descriptor will - * use to dispatch handlers for any asynchronous operations performed on the - * descriptor. - * - * @param native_descriptor The new underlying descriptor implementation. - * - * @throws asio::system_error Thrown on failure. - */ - stream_descriptor(asio::io_context& io_context, - const native_handle_type& native_descriptor) - : descriptor(io_context, native_descriptor) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a stream_descriptor from another. - /** - * This constructor moves a stream descriptor from one object to another. - * - * @param other The other stream_descriptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c stream_descriptor(io_context&) constructor. - */ - stream_descriptor(stream_descriptor&& other) - : descriptor(std::move(other)) - { - } - - /// Move-assign a stream_descriptor from another. - /** - * This assignment operator moves a stream descriptor from one object to - * another. - * - * @param other The other stream_descriptor object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c stream_descriptor(io_context&) constructor. - */ - stream_descriptor& operator=(stream_descriptor&& other) - { - descriptor::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Write some data to the descriptor. - /** - * This function is used to write data to the stream descriptor. The function - * call will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the descriptor. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.write_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "write_some"); - return s; - } - - /// Write some data to the descriptor. - /** - * This function is used to write data to the stream descriptor. The function - * call will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the descriptor. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().write_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write data to the stream - * descriptor. The function call always returns immediately. - * - * @param buffers One or more data buffers to be written to the descriptor. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.async_write_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - asio::async_completion init(handler); - - this->get_service().async_write_some( - this->get_implementation(), buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the descriptor. - /** - * This function is used to read data from the stream descriptor. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.read_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "read_some"); - return s; - } - - /// Read some data from the descriptor. - /** - * This function is used to read data from the stream descriptor. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().read_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read data from the stream - * descriptor. The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read function if you need to ensure that the - * requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * descriptor.async_read_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - asio::async_completion init(handler); - - this->get_service().async_read_some( - this->get_implementation(), buffers, init.completion_handler); - - return init.result.get(); - } -}; -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -} // namespace posix -} // namespace asio - -#endif // defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_POSIX_STREAM_DESCRIPTOR_HPP diff --git a/scout_sdk/asio/asio/posix/stream_descriptor_service.hpp b/scout_sdk/asio/asio/posix/stream_descriptor_service.hpp deleted file mode 100644 index 4ffbb96..0000000 --- a/scout_sdk/asio/asio/posix/stream_descriptor_service.hpp +++ /dev/null @@ -1,279 +0,0 @@ -// -// posix/stream_descriptor_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_POSIX_STREAM_DESCRIPTOR_SERVICE_HPP -#define ASIO_POSIX_STREAM_DESCRIPTOR_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/async_result.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/detail/reactive_descriptor_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace posix { - -/// Default service implementation for a stream descriptor. -class stream_descriptor_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - -private: - // The type of the platform-specific implementation. - typedef detail::reactive_descriptor_service service_impl_type; - -public: - /// The type of a stream descriptor implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef service_impl_type::implementation_type implementation_type; -#endif - - /// The native descriptor type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new stream descriptor service for the specified io_context. - explicit stream_descriptor_service(asio::io_context& io_context) - : asio::detail::service_base(io_context), - service_impl_(io_context) - { - } - - /// Construct a new stream descriptor implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new stream descriptor implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another stream descriptor implementation. - void move_assign(implementation_type& impl, - stream_descriptor_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a stream descriptor implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Assign an existing native descriptor to a stream descriptor. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const native_handle_type& native_descriptor, - asio::error_code& ec) - { - service_impl_.assign(impl, native_descriptor, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the descriptor is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a stream descriptor implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native descriptor implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Release ownership of the native descriptor implementation. - native_handle_type release(implementation_type& impl) - { - return service_impl_.release(impl); - } - - /// Cancel all asynchronous operations associated with the descriptor. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the descriptor. - template - ASIO_SYNC_OP_VOID io_control(implementation_type& impl, - IoControlCommand& command, asio::error_code& ec) - { - service_impl_.io_control(impl, command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the descriptor. - bool non_blocking(const implementation_type& impl) const - { - return service_impl_.non_blocking(impl); - } - - /// Sets the non-blocking mode of the descriptor. - ASIO_SYNC_OP_VOID non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native descriptor implementation. - bool native_non_blocking(const implementation_type& impl) const - { - return service_impl_.native_non_blocking(impl); - } - - /// Sets the non-blocking mode of the native descriptor implementation. - ASIO_SYNC_OP_VOID native_non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.native_non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the descriptor to become ready to read, ready to write, or to - /// have pending error conditions. - ASIO_SYNC_OP_VOID wait(implementation_type& impl, - descriptor_base::wait_type w, asio::error_code& ec) - { - service_impl_.wait(impl, w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the descriptor to become ready to read, ready to - /// write, or to have pending error conditions. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, descriptor_base::wait_type w, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, w, init.completion_handler); - - return init.result.get(); - } - - /// Write the given data to the stream. - template - std::size_t write_some(implementation_type& impl, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.write_some(impl, buffers, ec); - } - - /// Start an asynchronous write. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(implementation_type& impl, - const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_write_some(impl, buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the stream. - template - std::size_t read_some(implementation_type& impl, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.read_some(impl, buffers, ec); - } - - /// Start an asynchronous read. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(implementation_type& impl, - const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_read_some(impl, buffers, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace posix -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_POSIX_STREAM_DESCRIPTOR) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_POSIX_STREAM_DESCRIPTOR_SERVICE_HPP diff --git a/scout_sdk/asio/asio/post.hpp b/scout_sdk/asio/asio/post.hpp deleted file mode 100644 index 87d7b96..0000000 --- a/scout_sdk/asio/asio/post.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// -// post.hpp -// ~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_POST_HPP -#define ASIO_POST_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/execution_context.hpp" -#include "asio/is_executor.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Submits a completion token or function object for execution. -/** - * This function submits an object for execution using the object's associated - * executor. The function object is queued for execution, and is never called - * from the current thread prior to returning from post(). - * - * This function has the following effects: - * - * @li Constructs a function object handler of type @c Handler, initialized - * with handler(forward(token)). - * - * @li Constructs an object @c result of type async_result, - * initializing the object as result(handler). - * - * @li Obtains the handler's associated executor object @c ex by performing - * get_associated_executor(handler). - * - * @li Obtains the handler's associated allocator object @c alloc by performing - * get_associated_allocator(handler). - * - * @li Performs ex.post(std::move(handler), alloc). - * - * @li Returns result.get(). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) post( - ASIO_MOVE_ARG(CompletionToken) token); - -/// Submits a completion token or function object for execution. -/** - * This function submits an object for execution using the specified executor. - * The function object is queued for execution, and is never called from the - * current thread prior to returning from post(). - * - * This function has the following effects: - * - * @li Constructs a function object handler of type @c Handler, initialized - * with handler(forward(token)). - * - * @li Constructs an object @c result of type async_result, - * initializing the object as result(handler). - * - * @li Obtains the handler's associated executor object @c ex1 by performing - * get_associated_executor(handler). - * - * @li Creates a work object @c w by performing make_work(ex1). - * - * @li Obtains the handler's associated allocator object @c alloc by performing - * get_associated_allocator(handler). - * - * @li Constructs a function object @c f with a function call operator that - * performs ex1.dispatch(std::move(handler), alloc) followed by - * w.reset(). - * - * @li Performs Executor(ex).post(std::move(f), alloc). - * - * @li Returns result.get(). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) post( - const Executor& ex, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type* = 0); - -/// Submits a completion token or function object for execution. -/** - * @returns post(ctx.get_executor(), forward(token)). - */ -template -ASIO_INITFN_RESULT_TYPE(CompletionToken, void()) post( - ExecutionContext& ctx, ASIO_MOVE_ARG(CompletionToken) token, - typename enable_if::value>::type* = 0); - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/post.hpp" - -#endif // ASIO_POST_HPP diff --git a/scout_sdk/asio/asio/raw_socket_service.hpp b/scout_sdk/asio/asio/raw_socket_service.hpp deleted file mode 100644 index 2bccf03..0000000 --- a/scout_sdk/asio/asio/raw_socket_service.hpp +++ /dev/null @@ -1,466 +0,0 @@ -// -// raw_socket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_RAW_SOCKET_SERVICE_HPP -#define ASIO_RAW_SOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/null_socket_service.hpp" -#elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_socket_service.hpp" -#else -# include "asio/detail/reactive_socket_service.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a raw socket. -template -class raw_socket_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - -private: - // The type of the platform-specific implementation. -#if defined(ASIO_WINDOWS_RUNTIME) - typedef detail::null_socket_service service_impl_type; -#elif defined(ASIO_HAS_IOCP) - typedef detail::win_iocp_socket_service service_impl_type; -#else - typedef detail::reactive_socket_service service_impl_type; -#endif - -public: - /// The type of a raw socket. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// The native socket type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new raw socket service for the specified io_context. - explicit raw_socket_service(asio::io_context& io_context) - : asio::detail::service_base< - raw_socket_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new raw socket implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new raw socket implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another raw socket implementation. - void move_assign(implementation_type& impl, - raw_socket_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } - - // All socket services have access to each other's implementations. - template friend class raw_socket_service; - - /// Move-construct a new raw socket implementation from another protocol - /// type. - template - void converting_move_construct(implementation_type& impl, - raw_socket_service& other_service, - typename raw_socket_service< - Protocol1>::implementation_type& other_impl, - typename enable_if::value>::type* = 0) - { - service_impl_.template converting_move_construct( - impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a raw socket implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - // Open a new raw socket implementation. - ASIO_SYNC_OP_VOID open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - if (protocol.type() == ASIO_OS_DEF(SOCK_RAW)) - service_impl_.open(impl, protocol, ec); - else - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native socket to a raw socket. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_socket, - asio::error_code& ec) - { - service_impl_.assign(impl, protocol, native_socket, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a raw socket implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Release ownership of the underlying socket. - native_handle_type release(implementation_type& impl, - asio::error_code& ec) - { - return service_impl_.release(impl, ec); - } - - /// Get the native socket implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the socket. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is at the out-of-band data mark. - bool at_mark(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.at_mark(impl, ec); - } - - /// Determine the number of bytes available for reading. - std::size_t available(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.available(impl, ec); - } - - // Bind the raw socket to the specified local endpoint. - ASIO_SYNC_OP_VOID bind(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - service_impl_.bind(impl, endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Connect the raw socket to the specified endpoint. - ASIO_SYNC_OP_VOID connect(implementation_type& impl, - const endpoint_type& peer_endpoint, asio::error_code& ec) - { - service_impl_.connect(impl, peer_endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous connect. - template - ASIO_INITFN_RESULT_TYPE(ConnectHandler, - void (asio::error_code)) - async_connect(implementation_type& impl, - const endpoint_type& peer_endpoint, - ASIO_MOVE_ARG(ConnectHandler) handler) - { - async_completion init(handler); - - service_impl_.async_connect(impl, peer_endpoint, init.completion_handler); - - return init.result.get(); - } - - /// Set a socket option. - template - ASIO_SYNC_OP_VOID set_option(implementation_type& impl, - const SettableSocketOption& option, asio::error_code& ec) - { - service_impl_.set_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get a socket option. - template - ASIO_SYNC_OP_VOID get_option(const implementation_type& impl, - GettableSocketOption& option, asio::error_code& ec) const - { - service_impl_.get_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the socket. - template - ASIO_SYNC_OP_VOID io_control(implementation_type& impl, - IoControlCommand& command, asio::error_code& ec) - { - service_impl_.io_control(impl, command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the socket. - bool non_blocking(const implementation_type& impl) const - { - return service_impl_.non_blocking(impl); - } - - /// Sets the non-blocking mode of the socket. - ASIO_SYNC_OP_VOID non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const implementation_type& impl) const - { - return service_impl_.native_non_blocking(impl); - } - - /// Sets the non-blocking mode of the native socket implementation. - ASIO_SYNC_OP_VOID native_non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.native_non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.local_endpoint(impl, ec); - } - - /// Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.remote_endpoint(impl, ec); - } - - /// Disable sends or receives on the socket. - ASIO_SYNC_OP_VOID shutdown(implementation_type& impl, - socket_base::shutdown_type what, asio::error_code& ec) - { - service_impl_.shutdown(impl, what, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the socket to become ready to read, ready to write, or to have - /// pending error conditions. - ASIO_SYNC_OP_VOID wait(implementation_type& impl, - socket_base::wait_type w, asio::error_code& ec) - { - service_impl_.wait(impl, w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the socket to become ready to read, ready to - /// write, or to have pending error conditions. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, socket_base::wait_type w, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, w, init.completion_handler); - - return init.result.get(); - } - - /// Send the given data to the peer. - template - std::size_t send(implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.send(impl, buffers, flags, ec); - } - - /// Start an asynchronous send. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(implementation_type& impl, const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - async_completion init(handler); - - service_impl_.async_send(impl, buffers, flags, init.completion_handler); - - return init.result.get(); - } - - /// Send raw data to the specified endpoint. - template - std::size_t send_to(implementation_type& impl, - const ConstBufferSequence& buffers, const endpoint_type& destination, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.send_to(impl, buffers, destination, flags, ec); - } - - /// Start an asynchronous send. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send_to(implementation_type& impl, - const ConstBufferSequence& buffers, const endpoint_type& destination, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - async_completion init(handler); - - service_impl_.async_send_to(impl, buffers, - destination, flags, init.completion_handler); - - return init.result.get(); - } - - /// Receive some data from the peer. - template - std::size_t receive(implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.receive(impl, buffers, flags, ec); - } - - /// Start an asynchronous receive. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - async_completion init(handler); - - service_impl_.async_receive(impl, buffers, flags, init.completion_handler); - - return init.result.get(); - } - - /// Receive raw data with the endpoint of the sender. - template - std::size_t receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, endpoint_type& sender_endpoint, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.receive_from(impl, buffers, sender_endpoint, flags, - ec); - } - - /// Start an asynchronous receive that will get the endpoint of the sender. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive_from(implementation_type& impl, - const MutableBufferSequence& buffers, endpoint_type& sender_endpoint, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - async_completion init(handler); - - service_impl_.async_receive_from(impl, buffers, - sender_endpoint, flags, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_RAW_SOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/read.hpp b/scout_sdk/asio/asio/read.hpp deleted file mode 100644 index e77206a..0000000 --- a/scout_sdk/asio/asio/read.hpp +++ /dev/null @@ -1,947 +0,0 @@ -// -// read.hpp -// ~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_READ_HPP -#define ASIO_READ_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/buffer.hpp" -#include "asio/error.hpp" - -#if !defined(ASIO_NO_EXTENSIONS) -# include "asio/basic_streambuf_fwd.hpp" -#endif // !defined(ASIO_NO_EXTENSIONS) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/** - * @defgroup read asio::read - * - * @brief Attempt to read a certain amount of data from a stream before - * returning. - */ -/*@{*/ - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * stream. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::read(s, asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::read( - * s, buffers, - * asio::transfer_all()); @endcode - */ -template -std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - typename enable_if< - is_mutable_buffer_sequence::value - >::type* = 0); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * stream. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::read(s, asio::buffer(data, size), ec); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::read( - * s, buffers, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - asio::error_code& ec, - typename enable_if< - is_mutable_buffer_sequence::value - >::type* = 0); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * stream. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's read_some function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::read(s, asio::buffer(data, size), - * asio::transfer_at_least(32)); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, - typename enable_if< - is_mutable_buffer_sequence::value - >::type* = 0); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * stream. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's read_some function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t read(SyncReadStream& s, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_mutable_buffer_sequence::value - >::type* = 0); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The specified dynamic buffer sequence is full (that is, it has reached - * maximum size). - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @note This overload is equivalent to calling: - * @code asio::read( - * s, buffers, - * asio::transfer_all()); @endcode - */ -template -std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffer is full (that is, it has reached maximum size). - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @note This overload is equivalent to calling: - * @code asio::read( - * s, buffers, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The specified dynamic buffer sequence is full (that is, it has reached - * maximum size). - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's read_some function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - */ -template -std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The specified dynamic buffer sequence is full (that is, it has reached - * maximum size). - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's read_some function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t read(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffer is full (that is, it has reached maximum size). - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @note This overload is equivalent to calling: - * @code asio::read( - * s, b, - * asio::transfer_all()); @endcode - */ -template -std::size_t read(SyncReadStream& s, basic_streambuf& b); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffer is full (that is, it has reached maximum size). - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @note This overload is equivalent to calling: - * @code asio::read( - * s, b, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t read(SyncReadStream& s, basic_streambuf& b, - asio::error_code& ec); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffer is full (that is, it has reached maximum size). - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's read_some function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - */ -template -std::size_t read(SyncReadStream& s, basic_streambuf& b, - CompletionCondition completion_condition); - -/// Attempt to read a certain amount of data from a stream before returning. -/** - * This function is used to read a certain number of bytes of data from a - * stream. The call will block until one of the following conditions is true: - * - * @li The supplied buffer is full (that is, it has reached maximum size). - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's read_some function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t read(SyncReadStream& s, basic_streambuf& b, - CompletionCondition completion_condition, asio::error_code& ec); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ -/** - * @defgroup async_read asio::async_read - * - * @brief Start an asynchronous operation to read a certain amount of data from - * a stream. - */ -/*@{*/ - -/// Start an asynchronous operation to read a certain amount of data from a -/// stream. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions is - * true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other read operations (such - * as async_read, the stream's async_read_some function, or any other composed - * operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * stream. Although the buffers object may be copied as necessary, ownership of - * the underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes copied into the - * // buffers. If an error occurred, - * // this will be the number of - * // bytes successfully transferred - * // prior to the error. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * asio::async_read(s, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::async_read( - * s, buffers, - * asio::transfer_all(), - * handler); @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_mutable_buffer_sequence::value - >::type* = 0); - -/// Start an asynchronous operation to read a certain amount of data from a -/// stream. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions is - * true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * stream. Although the buffers object may be copied as necessary, ownership of - * the underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's async_read_some function. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes copied into the - * // buffers. If an error occurred, - * // this will be the number of - * // bytes successfully transferred - * // prior to the error. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::async_read(s, - * asio::buffer(data, size), - * asio::transfer_at_least(32), - * handler); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_mutable_buffer_sequence::value - >::type* = 0); - -/// Start an asynchronous operation to read a certain amount of data from a -/// stream. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions is - * true: - * - * @li The specified dynamic buffer sequence is full (that is, it has reached - * maximum size). - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other read operations (such - * as async_read, the stream's async_read_some function, or any other composed - * operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes copied into the - * // buffers. If an error occurred, - * // this will be the number of - * // bytes successfully transferred - * // prior to the error. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note This overload is equivalent to calling: - * @code asio::async_read( - * s, buffers, - * asio::transfer_all(), - * handler); @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Start an asynchronous operation to read a certain amount of data from a -/// stream. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions is - * true: - * - * @li The specified dynamic buffer sequence is full (that is, it has reached - * maximum size). - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other read operations (such - * as async_read, the stream's async_read_some function, or any other composed - * operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's async_read_some function. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes copied into the - * // buffers. If an error occurred, - * // this will be the number of - * // bytes successfully transferred - * // prior to the error. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Start an asynchronous operation to read a certain amount of data from a -/// stream. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions is - * true: - * - * @li The supplied buffer is full (that is, it has reached maximum size). - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other read operations (such - * as async_read, the stream's async_read_some function, or any other composed - * operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param b A basic_streambuf object into which the data will be read. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes copied into the - * // buffers. If an error occurred, - * // this will be the number of - * // bytes successfully transferred - * // prior to the error. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note This overload is equivalent to calling: - * @code asio::async_read( - * s, b, - * asio::transfer_all(), - * handler); @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, basic_streambuf& b, - ASIO_MOVE_ARG(ReadHandler) handler); - -/// Start an asynchronous operation to read a certain amount of data from a -/// stream. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions is - * true: - * - * @li The supplied buffer is full (that is, it has reached maximum size). - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other read operations (such - * as async_read, the stream's async_read_some function, or any other composed - * operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param b A basic_streambuf object into which the data will be read. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_read_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the stream's async_read_some function. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes copied into the - * // buffers. If an error occurred, - * // this will be the number of - * // bytes successfully transferred - * // prior to the error. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read(AsyncReadStream& s, basic_streambuf& b, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/read.hpp" - -#endif // ASIO_READ_HPP diff --git a/scout_sdk/asio/asio/read_at.hpp b/scout_sdk/asio/asio/read_at.hpp deleted file mode 100644 index df2c628..0000000 --- a/scout_sdk/asio/asio/read_at.hpp +++ /dev/null @@ -1,671 +0,0 @@ -// -// read_at.hpp -// ~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_READ_AT_HPP -#define ASIO_READ_AT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/detail/cstdint.hpp" -#include "asio/error.hpp" - -#if !defined(ASIO_NO_EXTENSIONS) -# include "asio/basic_streambuf_fwd.hpp" -#endif // !defined(ASIO_NO_EXTENSIONS) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/** - * @defgroup read_at asio::read_at - * - * @brief Attempt to read a certain amount of data at the specified offset - * before returning. - */ -/*@{*/ - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * device. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::read_at(d, 42, asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::read_at( - * d, 42, buffers, - * asio::transfer_all()); @endcode - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers); - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * device. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::read_at(d, 42, - * asio::buffer(data, size), ec); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::read_at( - * d, 42, buffers, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - asio::error_code& ec); - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * device. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the device's read_some_at function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::read_at(d, 42, asio::buffer(data, size), - * asio::transfer_at_least(32)); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - CompletionCondition completion_condition); - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * device. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the device's read_some_at function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @note This overload is equivalent to calling: - * @code asio::read_at( - * d, 42, b, - * asio::transfer_all()); @endcode - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, basic_streambuf& b); - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @note This overload is equivalent to calling: - * @code asio::read_at( - * d, 42, b, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, basic_streambuf& b, - asio::error_code& ec); - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the device's read_some_at function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, basic_streambuf& b, - CompletionCondition completion_condition); - -/// Attempt to read a certain amount of data at the specified offset before -/// returning. -/** - * This function is used to read a certain number of bytes of data from a - * random access device at the specified offset. The call will block until one - * of the following conditions is true: - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the SyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param b The basic_streambuf object into which the data will be read. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest read_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the device's read_some_at function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t read_at(SyncRandomAccessReadDevice& d, - uint64_t offset, basic_streambuf& b, - CompletionCondition completion_condition, asio::error_code& ec); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ -/** - * @defgroup async_read_at asio::async_read_at - * - * @brief Start an asynchronous operation to read a certain amount of data at - * the specified offset. - */ -/*@{*/ - -/// Start an asynchronous operation to read a certain amount of data at the -/// specified offset. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a random access device at the specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * async_read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the AsyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * device. Although the buffers object may be copied as necessary, ownership of - * the underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes copied into the buffers. If an error - * // occurred, this will be the number of bytes successfully - * // transferred prior to the error. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * asio::async_read_at(d, 42, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::async_read_at( - * d, 42, buffers, - * asio::transfer_all(), - * handler); @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, uint64_t offset, - const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler); - -/// Start an asynchronous operation to read a certain amount of data at the -/// specified offset. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a random access device at the specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li The supplied buffers are full. That is, the bytes transferred is equal to - * the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * @param d The device from which the data is to be read. The type must support - * the AsyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. The sum - * of the buffer sizes indicates the maximum number of bytes to read from the - * device. Although the buffers object may be copied as necessary, ownership of - * the underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_read_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the device's async_read_some_at function. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes copied into the buffers. If an error - * // occurred, this will be the number of bytes successfully - * // transferred prior to the error. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code asio::async_read_at(d, 42, - * asio::buffer(data, size), - * asio::transfer_at_least(32), - * handler); @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, - uint64_t offset, const MutableBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Start an asynchronous operation to read a certain amount of data at the -/// specified offset. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a random access device at the specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * async_read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the AsyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param b A basic_streambuf object into which the data will be read. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes copied into the buffers. If an error - * // occurred, this will be the number of bytes successfully - * // transferred prior to the error. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note This overload is equivalent to calling: - * @code asio::async_read_at( - * d, 42, b, - * asio::transfer_all(), - * handler); @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, uint64_t offset, - basic_streambuf& b, ASIO_MOVE_ARG(ReadHandler) handler); - -/// Start an asynchronous operation to read a certain amount of data at the -/// specified offset. -/** - * This function is used to asynchronously read a certain number of bytes of - * data from a random access device at the specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * async_read_some_at function. - * - * @param d The device from which the data is to be read. The type must support - * the AsyncRandomAccessReadDevice concept. - * - * @param offset The offset at which the data will be read. - * - * @param b A basic_streambuf object into which the data will be read. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the read operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_read_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the read operation is complete. A non-zero - * return value indicates the maximum number of bytes to be read on the next - * call to the device's async_read_some_at function. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes copied into the buffers. If an error - * // occurred, this will be the number of bytes successfully - * // transferred prior to the error. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_at(AsyncRandomAccessReadDevice& d, - uint64_t offset, basic_streambuf& b, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(ReadHandler) handler); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/read_at.hpp" - -#endif // ASIO_READ_AT_HPP diff --git a/scout_sdk/asio/asio/read_until.hpp b/scout_sdk/asio/asio/read_until.hpp deleted file mode 100644 index f413d98..0000000 --- a/scout_sdk/asio/asio/read_until.hpp +++ /dev/null @@ -1,1824 +0,0 @@ -// -// read_until.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_READ_UNTIL_HPP -#define ASIO_READ_UNTIL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include -#include "asio/async_result.hpp" -#include "asio/detail/regex_fwd.hpp" -#include "asio/detail/string_view.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" - -#if !defined(ASIO_NO_EXTENSIONS) -# include "asio/basic_streambuf_fwd.hpp" -#endif // !defined(ASIO_NO_EXTENSIONS) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -namespace detail -{ - char (&has_result_type_helper(...))[2]; - - template - char has_result_type_helper(T*, typename T::result_type* = 0); - - template - struct has_result_type - { - enum { value = (sizeof((has_result_type_helper)((T*)(0))) == 1) }; - }; -} // namespace detail - -/// Type trait used to determine whether a type can be used as a match condition -/// function with read_until and async_read_until. -template -struct is_match_condition -{ -#if defined(GENERATING_DOCUMENTATION) - /// The value member is true if the type may be used as a match condition. - static const bool value; -#else - enum - { - value = asio::is_function< - typename asio::remove_pointer::type>::value - || detail::has_result_type::value - }; -#endif -}; - -/** - * @defgroup read_until asio::read_until - * - * @brief Read data into a dynamic buffer sequence, or into a streambuf, until - * it contains a delimiter, matches a regular expression, or a function object - * indicates a match. - */ -/*@{*/ - -/// Read data into a dynamic buffer sequence until it contains a specified -/// delimiter. -/** - * This function is used to read data into the specified dynamic buffer - * sequence until the dynamic buffer sequence's get area contains the specified - * delimiter. The call will block until one of the following conditions is - * true: - * - * @li The get area of the dynamic buffer sequence contains the specified - * delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the dynamic buffer sequence's get area already - * contains the delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @param delim The delimiter character. - * - * @returns The number of bytes in the dynamic buffer sequence's get area up to - * and including the delimiter. - * - * @throws asio::system_error Thrown on failure. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond the delimiter. An application will - * typically leave that data in the dynamic buffer sequence for a subsequent - * read_until operation to examine. - * - * @par Example - * To read data into a @c std::string until a newline is encountered: - * @code std::string data; - * std::string n = asio::read_until(s, - * asio::dynamic_buffer(data), '\n'); - * std::string line = data.substr(0, n); - * data.erase(0, n); @endcode - * After the @c read_until operation completes successfully, the string @c data - * contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\n', 'd', 'e', ... } @endcode - * The call to @c substr then extracts the data up to and including the - * delimiter, so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\n' } @endcode - * After the call to @c erase, the remaining data is left in the buffer @c b as - * follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c read_until operation. - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, char delim); - -/// Read data into a dynamic buffer sequence until it contains a specified -/// delimiter. -/** - * This function is used to read data into the specified dynamic buffer - * sequence until the dynamic buffer sequence's get area contains the specified - * delimiter. The call will block until one of the following conditions is - * true: - * - * @li The get area of the dynamic buffer sequence contains the specified - * delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the dynamic buffer sequence's get area already - * contains the delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @param delim The delimiter character. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the dynamic buffer sequence's get area up to - * and including the delimiter. Returns 0 if an error occurred. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond the delimiter. An application will - * typically leave that data in the dynamic buffer sequence for a subsequent - * read_until operation to examine. - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - char delim, asio::error_code& ec); - -/// Read data into a dynamic buffer sequence until it contains a specified -/// delimiter. -/** - * This function is used to read data into the specified dynamic buffer - * sequence until the dynamic buffer sequence's get area contains the specified - * delimiter. The call will block until one of the following conditions is - * true: - * - * @li The get area of the dynamic buffer sequence contains the specified - * delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the dynamic buffer sequence's get area already - * contains the delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @param delim The delimiter string. - * - * @returns The number of bytes in the dynamic buffer sequence's get area up to - * and including the delimiter. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond the delimiter. An application will - * typically leave that data in the dynamic buffer sequence for a subsequent - * read_until operation to examine. - * - * @par Example - * To read data into a @c std::string until a CR-LF sequence is encountered: - * @code std::string data; - * std::string n = asio::read_until(s, - * asio::dynamic_buffer(data), "\r\n"); - * std::string line = data.substr(0, n); - * data.erase(0, n); @endcode - * After the @c read_until operation completes successfully, the string @c data - * contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c substr then extracts the data up to and including the - * delimiter, so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r', '\n' } @endcode - * After the call to @c erase, the remaining data is left in the buffer @c b as - * follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c read_until operation. - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_STRING_VIEW_PARAM delim); - -/// Read data into a dynamic buffer sequence until it contains a specified -/// delimiter. -/** - * This function is used to read data into the specified dynamic buffer - * sequence until the dynamic buffer sequence's get area contains the specified - * delimiter. The call will block until one of the following conditions is - * true: - * - * @li The get area of the dynamic buffer sequence contains the specified - * delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the dynamic buffer sequence's get area already - * contains the delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * - * @param delim The delimiter string. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the dynamic buffer sequence's get area up to - * and including the delimiter. Returns 0 if an error occurred. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond the delimiter. An application will - * typically leave that data in the dynamic buffer sequence for a subsequent - * read_until operation to examine. - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_STRING_VIEW_PARAM delim, - asio::error_code& ec); - -#if !defined(ASIO_NO_EXTENSIONS) -#if defined(ASIO_HAS_BOOST_REGEX) \ - || defined(GENERATING_DOCUMENTATION) - -/// Read data into a dynamic buffer sequence until some part of the data it -/// contains matches a regular expression. -/** - * This function is used to read data into the specified dynamic buffer - * sequence until the dynamic buffer sequence's get area contains some data - * that matches a regular expression. The call will block until one of the - * following conditions is true: - * - * @li A substring of the dynamic buffer sequence's get area matches the - * regular expression. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the dynamic buffer sequence's get area already - * contains data that matches the regular expression, the function returns - * immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers A dynamic buffer sequence into which the data will be read. - * - * @param expr The regular expression. - * - * @returns The number of bytes in the dynamic buffer sequence's get area up to - * and including the substring that matches the regular expression. - * - * @throws asio::system_error Thrown on failure. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond that which matched the regular - * expression. An application will typically leave that data in the dynamic - * buffer sequence for a subsequent read_until operation to examine. - * - * @par Example - * To read data into a @c std::string until a CR-LF sequence is encountered: - * @code std::string data; - * std::string n = asio::read_until(s, - * asio::dynamic_buffer(data), boost::regex("\r\n")); - * std::string line = data.substr(0, n); - * data.erase(0, n); @endcode - * After the @c read_until operation completes successfully, the string @c data - * contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c substr then extracts the data up to and including the - * delimiter, so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r', '\n' } @endcode - * After the call to @c erase, the remaining data is left in the buffer @c b as - * follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c read_until operation. - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - const boost::regex& expr); - -/// Read data into a dynamic buffer sequence until some part of the data it -/// contains matches a regular expression. -/** - * This function is used to read data into the specified dynamic buffer - * sequence until the dynamic buffer sequence's get area contains some data - * that matches a regular expression. The call will block until one of the - * following conditions is true: - * - * @li A substring of the dynamic buffer sequence's get area matches the - * regular expression. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the dynamic buffer sequence's get area already - * contains data that matches the regular expression, the function returns - * immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers A dynamic buffer sequence into which the data will be read. - * - * @param expr The regular expression. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the dynamic buffer sequence's get area up to - * and including the substring that matches the regular expression. Returns 0 - * if an error occurred. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond that which matched the regular - * expression. An application will typically leave that data in the dynamic - * buffer sequence for a subsequent read_until operation to examine. - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - const boost::regex& expr, asio::error_code& ec); - -#endif // defined(ASIO_HAS_BOOST_REGEX) - // || defined(GENERATING_DOCUMENTATION) - -/// Read data into a dynamic buffer sequence until a function object indicates a -/// match. - -/** - * This function is used to read data into the specified dynamic buffer - * sequence until a user-defined match condition function object, when applied - * to the data contained in the dynamic buffer sequence, indicates a successful - * match. The call will block until one of the following conditions is true: - * - * @li The match condition function object returns a std::pair where the second - * element evaluates to true. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the match condition function object already indicates - * a match, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers A dynamic buffer sequence into which the data will be read. - * - * @param match_condition The function object to be called to determine whether - * a match exists. The signature of the function object must be: - * @code pair match_condition(iterator begin, iterator end); - * @endcode - * where @c iterator represents the type: - * @code buffers_iterator - * @endcode - * The iterator parameters @c begin and @c end define the range of bytes to be - * scanned to determine whether there is a match. The @c first member of the - * return value is an iterator marking one-past-the-end of the bytes that have - * been consumed by the match function. This iterator is used to calculate the - * @c begin parameter for any subsequent invocation of the match condition. The - * @c second member of the return value is true if a match has been found, false - * otherwise. - * - * @returns The number of bytes in the dynamic_buffer's get area that - * have been fully consumed by the match function. - * - * @throws asio::system_error Thrown on failure. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond that which matched the function object. - * An application will typically leave that data in the dynamic buffer sequence - * for a subsequent read_until operation to examine. - - * @note The default implementation of the @c is_match_condition type trait - * evaluates to true for function pointers and function objects with a - * @c result_type typedef. It must be specialised for other user-defined - * function objects. - * - * @par Examples - * To read data into a dynamic buffer sequence until whitespace is encountered: - * @code typedef asio::buffers_iterator< - * asio::const_buffers_1> iterator; - * - * std::pair - * match_whitespace(iterator begin, iterator end) - * { - * iterator i = begin; - * while (i != end) - * if (std::isspace(*i++)) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * ... - * std::string data; - * asio::read_until(s, data, match_whitespace); - * @endcode - * - * To read data into a @c std::string until a matching character is found: - * @code class match_char - * { - * public: - * explicit match_char(char c) : c_(c) {} - * - * template - * std::pair operator()( - * Iterator begin, Iterator end) const - * { - * Iterator i = begin; - * while (i != end) - * if (c_ == *i++) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * - * private: - * char c_; - * }; - * - * namespace asio { - * template <> struct is_match_condition - * : public boost::true_type {}; - * } // namespace asio - * ... - * std::string data; - * asio::read_until(s, data, match_char('a')); - * @endcode - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - MatchCondition match_condition, - typename enable_if::value>::type* = 0); - -/// Read data into a dynamic buffer sequence until a function object indicates a -/// match. -/** - * This function is used to read data into the specified dynamic buffer - * sequence until a user-defined match condition function object, when applied - * to the data contained in the dynamic buffer sequence, indicates a successful - * match. The call will block until one of the following conditions is true: - * - * @li The match condition function object returns a std::pair where the second - * element evaluates to true. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the match condition function object already indicates - * a match, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param buffers A dynamic buffer sequence into which the data will be read. - * - * @param match_condition The function object to be called to determine whether - * a match exists. The signature of the function object must be: - * @code pair match_condition(iterator begin, iterator end); - * @endcode - * where @c iterator represents the type: - * @code buffers_iterator - * @endcode - * The iterator parameters @c begin and @c end define the range of bytes to be - * scanned to determine whether there is a match. The @c first member of the - * return value is an iterator marking one-past-the-end of the bytes that have - * been consumed by the match function. This iterator is used to calculate the - * @c begin parameter for any subsequent invocation of the match condition. The - * @c second member of the return value is true if a match has been found, false - * otherwise. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the dynamic buffer sequence's get area that - * have been fully consumed by the match function. Returns 0 if an error - * occurred. - * - * @note After a successful read_until operation, the dynamic buffer sequence - * may contain additional data beyond that which matched the function object. - * An application will typically leave that data in the dynamic buffer sequence - * for a subsequent read_until operation to examine. - * - * @note The default implementation of the @c is_match_condition type trait - * evaluates to true for function pointers and function objects with a - * @c result_type typedef. It must be specialised for other user-defined - * function objects. - */ -template -std::size_t read_until(SyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - MatchCondition match_condition, asio::error_code& ec, - typename enable_if::value>::type* = 0); - -#if !defined(ASIO_NO_IOSTREAM) - -/// Read data into a streambuf until it contains a specified delimiter. -/** - * This function is used to read data into the specified streambuf until the - * streambuf's get area contains the specified delimiter. The call will block - * until one of the following conditions is true: - * - * @li The get area of the streambuf contains the specified delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the streambuf's get area already contains the - * delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param delim The delimiter character. - * - * @returns The number of bytes in the streambuf's get area up to and including - * the delimiter. - * - * @throws asio::system_error Thrown on failure. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond the delimiter. An application will typically leave - * that data in the streambuf for a subsequent read_until operation to examine. - * - * @par Example - * To read data into a streambuf until a newline is encountered: - * @code asio::streambuf b; - * asio::read_until(s, b, '\n'); - * std::istream is(&b); - * std::string line; - * std::getline(is, line); @endcode - * After the @c read_until operation completes successfully, the buffer @c b - * contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\n', 'd', 'e', ... } @endcode - * The call to @c std::getline then extracts the data up to and including the - * newline (which is discarded), so that the string @c line contains: - * @code { 'a', 'b', ..., 'c' } @endcode - * The remaining data is left in the buffer @c b as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c read_until operation. - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, char delim); - -/// Read data into a streambuf until it contains a specified delimiter. -/** - * This function is used to read data into the specified streambuf until the - * streambuf's get area contains the specified delimiter. The call will block - * until one of the following conditions is true: - * - * @li The get area of the streambuf contains the specified delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the streambuf's get area already contains the - * delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param delim The delimiter character. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the streambuf's get area up to and including - * the delimiter. Returns 0 if an error occurred. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond the delimiter. An application will typically leave - * that data in the streambuf for a subsequent read_until operation to examine. - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, char delim, - asio::error_code& ec); - -/// Read data into a streambuf until it contains a specified delimiter. -/** - * This function is used to read data into the specified streambuf until the - * streambuf's get area contains the specified delimiter. The call will block - * until one of the following conditions is true: - * - * @li The get area of the streambuf contains the specified delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the streambuf's get area already contains the - * delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param delim The delimiter string. - * - * @returns The number of bytes in the streambuf's get area up to and including - * the delimiter. - * - * @throws asio::system_error Thrown on failure. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond the delimiter. An application will typically leave - * that data in the streambuf for a subsequent read_until operation to examine. - * - * @par Example - * To read data into a streambuf until a newline is encountered: - * @code asio::streambuf b; - * asio::read_until(s, b, "\r\n"); - * std::istream is(&b); - * std::string line; - * std::getline(is, line); @endcode - * After the @c read_until operation completes successfully, the buffer @c b - * contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c std::getline then extracts the data up to and including the - * newline (which is discarded), so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r' } @endcode - * The remaining data is left in the buffer @c b as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c read_until operation. - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, - ASIO_STRING_VIEW_PARAM delim); - -/// Read data into a streambuf until it contains a specified delimiter. -/** - * This function is used to read data into the specified streambuf until the - * streambuf's get area contains the specified delimiter. The call will block - * until one of the following conditions is true: - * - * @li The get area of the streambuf contains the specified delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the streambuf's get area already contains the - * delimiter, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param delim The delimiter string. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the streambuf's get area up to and including - * the delimiter. Returns 0 if an error occurred. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond the delimiter. An application will typically leave - * that data in the streambuf for a subsequent read_until operation to examine. - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, - ASIO_STRING_VIEW_PARAM delim, asio::error_code& ec); - -#if defined(ASIO_HAS_BOOST_REGEX) \ - || defined(GENERATING_DOCUMENTATION) - -/// Read data into a streambuf until some part of the data it contains matches -/// a regular expression. -/** - * This function is used to read data into the specified streambuf until the - * streambuf's get area contains some data that matches a regular expression. - * The call will block until one of the following conditions is true: - * - * @li A substring of the streambuf's get area matches the regular expression. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the streambuf's get area already contains data that - * matches the regular expression, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param expr The regular expression. - * - * @returns The number of bytes in the streambuf's get area up to and including - * the substring that matches the regular expression. - * - * @throws asio::system_error Thrown on failure. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond that which matched the regular expression. An - * application will typically leave that data in the streambuf for a subsequent - * read_until operation to examine. - * - * @par Example - * To read data into a streambuf until a CR-LF sequence is encountered: - * @code asio::streambuf b; - * asio::read_until(s, b, boost::regex("\r\n")); - * std::istream is(&b); - * std::string line; - * std::getline(is, line); @endcode - * After the @c read_until operation completes successfully, the buffer @c b - * contains the data which matched the regular expression: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c std::getline then extracts the data up to and including the - * newline (which is discarded), so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r' } @endcode - * The remaining data is left in the buffer @c b as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c read_until operation. - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, const boost::regex& expr); - -/// Read data into a streambuf until some part of the data it contains matches -/// a regular expression. -/** - * This function is used to read data into the specified streambuf until the - * streambuf's get area contains some data that matches a regular expression. - * The call will block until one of the following conditions is true: - * - * @li A substring of the streambuf's get area matches the regular expression. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the streambuf's get area already contains data that - * matches the regular expression, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param expr The regular expression. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the streambuf's get area up to and including - * the substring that matches the regular expression. Returns 0 if an error - * occurred. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond that which matched the regular expression. An - * application will typically leave that data in the streambuf for a subsequent - * read_until operation to examine. - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, const boost::regex& expr, - asio::error_code& ec); - -#endif // defined(ASIO_HAS_BOOST_REGEX) - // || defined(GENERATING_DOCUMENTATION) - -/// Read data into a streambuf until a function object indicates a match. -/** - * This function is used to read data into the specified streambuf until a - * user-defined match condition function object, when applied to the data - * contained in the streambuf, indicates a successful match. The call will - * block until one of the following conditions is true: - * - * @li The match condition function object returns a std::pair where the second - * element evaluates to true. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the match condition function object already indicates - * a match, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param match_condition The function object to be called to determine whether - * a match exists. The signature of the function object must be: - * @code pair match_condition(iterator begin, iterator end); - * @endcode - * where @c iterator represents the type: - * @code buffers_iterator::const_buffers_type> - * @endcode - * The iterator parameters @c begin and @c end define the range of bytes to be - * scanned to determine whether there is a match. The @c first member of the - * return value is an iterator marking one-past-the-end of the bytes that have - * been consumed by the match function. This iterator is used to calculate the - * @c begin parameter for any subsequent invocation of the match condition. The - * @c second member of the return value is true if a match has been found, false - * otherwise. - * - * @returns The number of bytes in the streambuf's get area that have been fully - * consumed by the match function. - * - * @throws asio::system_error Thrown on failure. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond that which matched the function object. An application - * will typically leave that data in the streambuf for a subsequent read_until - * operation to examine. - * - * @note The default implementation of the @c is_match_condition type trait - * evaluates to true for function pointers and function objects with a - * @c result_type typedef. It must be specialised for other user-defined - * function objects. - * - * @par Examples - * To read data into a streambuf until whitespace is encountered: - * @code typedef asio::buffers_iterator< - * asio::streambuf::const_buffers_type> iterator; - * - * std::pair - * match_whitespace(iterator begin, iterator end) - * { - * iterator i = begin; - * while (i != end) - * if (std::isspace(*i++)) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * ... - * asio::streambuf b; - * asio::read_until(s, b, match_whitespace); - * @endcode - * - * To read data into a streambuf until a matching character is found: - * @code class match_char - * { - * public: - * explicit match_char(char c) : c_(c) {} - * - * template - * std::pair operator()( - * Iterator begin, Iterator end) const - * { - * Iterator i = begin; - * while (i != end) - * if (c_ == *i++) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * - * private: - * char c_; - * }; - * - * namespace asio { - * template <> struct is_match_condition - * : public boost::true_type {}; - * } // namespace asio - * ... - * asio::streambuf b; - * asio::read_until(s, b, match_char('a')); - * @endcode - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, MatchCondition match_condition, - typename enable_if::value>::type* = 0); - -/// Read data into a streambuf until a function object indicates a match. -/** - * This function is used to read data into the specified streambuf until a - * user-defined match condition function object, when applied to the data - * contained in the streambuf, indicates a successful match. The call will - * block until one of the following conditions is true: - * - * @li The match condition function object returns a std::pair where the second - * element evaluates to true. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * read_some function. If the match condition function object already indicates - * a match, the function returns immediately. - * - * @param s The stream from which the data is to be read. The type must support - * the SyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param match_condition The function object to be called to determine whether - * a match exists. The signature of the function object must be: - * @code pair match_condition(iterator begin, iterator end); - * @endcode - * where @c iterator represents the type: - * @code buffers_iterator::const_buffers_type> - * @endcode - * The iterator parameters @c begin and @c end define the range of bytes to be - * scanned to determine whether there is a match. The @c first member of the - * return value is an iterator marking one-past-the-end of the bytes that have - * been consumed by the match function. This iterator is used to calculate the - * @c begin parameter for any subsequent invocation of the match condition. The - * @c second member of the return value is true if a match has been found, false - * otherwise. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes in the streambuf's get area that have been fully - * consumed by the match function. Returns 0 if an error occurred. - * - * @note After a successful read_until operation, the streambuf may contain - * additional data beyond that which matched the function object. An application - * will typically leave that data in the streambuf for a subsequent read_until - * operation to examine. - * - * @note The default implementation of the @c is_match_condition type trait - * evaluates to true for function pointers and function objects with a - * @c result_type typedef. It must be specialised for other user-defined - * function objects. - */ -template -std::size_t read_until(SyncReadStream& s, - asio::basic_streambuf& b, - MatchCondition match_condition, asio::error_code& ec, - typename enable_if::value>::type* = 0); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ -/** - * @defgroup async_read_until asio::async_read_until - * - * @brief Start an asynchronous operation to read data into a dynamic buffer - * sequence, or into a streambuf, until it contains a delimiter, matches a - * regular expression, or a function object indicates a match. - */ -/*@{*/ - -/// Start an asynchronous operation to read data into a dynamic buffer sequence -/// until it contains a specified delimiter. -/** - * This function is used to asynchronously read data into the specified dynamic - * buffer sequence until the dynamic buffer sequence's get area contains the - * specified delimiter. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li The get area of the dynamic buffer sequence contains the specified - * delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the dynamic buffer sequence's get area already contains the delimiter, this - * asynchronous operation completes immediately. The program must ensure that - * the stream performs no other read operations (such as async_read, - * async_read_until, the stream's async_read_some function, or any other - * composed operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param delim The delimiter character. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the dynamic buffer sequence's - * // get area up to and including the delimiter. - * // 0 if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the dynamic buffer - * sequence may contain additional data beyond the delimiter. An application - * will typically leave that data in the dynamic buffer sequence for a - * subsequent async_read_until operation to examine. - * - * @par Example - * To asynchronously read data into a @c std::string until a newline is - * encountered: - * @code std::string data; - * ... - * void handler(const asio::error_code& e, std::size_t size) - * { - * if (!e) - * { - * std::string line = data.substr(0, n); - * data.erase(0, n); - * ... - * } - * } - * ... - * asio::async_read_until(s, data, '\n', handler); @endcode - * After the @c async_read_until operation completes successfully, the buffer - * @c data contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\n', 'd', 'e', ... } @endcode - * The call to @c substr then extracts the data up to and including the - * delimiter, so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\n' } @endcode - * After the call to @c erase, the remaining data is left in the buffer @c data - * as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c async_read_until operation. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - char delim, ASIO_MOVE_ARG(ReadHandler) handler); - -/// Start an asynchronous operation to read data into a dynamic buffer sequence -/// until it contains a specified delimiter. -/** - * This function is used to asynchronously read data into the specified dynamic - * buffer sequence until the dynamic buffer sequence's get area contains the - * specified delimiter. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li The get area of the dynamic buffer sequence contains the specified - * delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the dynamic buffer sequence's get area already contains the delimiter, this - * asynchronous operation completes immediately. The program must ensure that - * the stream performs no other read operations (such as async_read, - * async_read_until, the stream's async_read_some function, or any other - * composed operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param delim The delimiter string. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the dynamic buffer sequence's - * // get area up to and including the delimiter. - * // 0 if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the dynamic buffer - * sequence may contain additional data beyond the delimiter. An application - * will typically leave that data in the dynamic buffer sequence for a - * subsequent async_read_until operation to examine. - * - * @par Example - * To asynchronously read data into a @c std::string until a CR-LF sequence is - * encountered: - * @code std::string data; - * ... - * void handler(const asio::error_code& e, std::size_t size) - * { - * if (!e) - * { - * std::string line = data.substr(0, n); - * data.erase(0, n); - * ... - * } - * } - * ... - * asio::async_read_until(s, data, "\r\n", handler); @endcode - * After the @c async_read_until operation completes successfully, the string - * @c data contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c substr then extracts the data up to and including the - * delimiter, so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r', '\n' } @endcode - * After the call to @c erase, the remaining data is left in the string @c data - * as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c async_read_until operation. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_STRING_VIEW_PARAM delim, - ASIO_MOVE_ARG(ReadHandler) handler); - -#if !defined(ASIO_NO_EXTENSIONS) -#if defined(ASIO_HAS_BOOST_REGEX) \ - || defined(GENERATING_DOCUMENTATION) - -/// Start an asynchronous operation to read data into a dynamic buffer sequence -/// until some part of its data matches a regular expression. -/** - * This function is used to asynchronously read data into the specified dynamic - * buffer sequence until the dynamic buffer sequence's get area contains some - * data that matches a regular expression. The function call always returns - * immediately. The asynchronous operation will continue until one of the - * following conditions is true: - * - * @li A substring of the dynamic buffer sequence's get area matches the regular - * expression. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the dynamic buffer sequence's get area already contains data that matches - * the regular expression, this asynchronous operation completes immediately. - * The program must ensure that the stream performs no other read operations - * (such as async_read, async_read_until, the stream's async_read_some - * function, or any other composed operations that perform reads) until this - * operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param expr The regular expression. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the dynamic buffer - * // sequence's get area up to and including the - * // substring that matches the regular expression. - * // 0 if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the dynamic buffer - * sequence may contain additional data beyond that which matched the regular - * expression. An application will typically leave that data in the dynamic - * buffer sequence for a subsequent async_read_until operation to examine. - * - * @par Example - * To asynchronously read data into a @c std::string until a CR-LF sequence is - * encountered: - * @code std::string data; - * ... - * void handler(const asio::error_code& e, std::size_t size) - * { - * if (!e) - * { - * std::string line = data.substr(0, n); - * data.erase(0, n); - * ... - * } - * } - * ... - * asio::async_read_until(s, data, - * boost::regex("\r\n"), handler); @endcode - * After the @c async_read_until operation completes successfully, the string - * @c data contains the data which matched the regular expression: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c substr then extracts the data up to and including the match, - * so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r', '\n' } @endcode - * After the call to @c erase, the remaining data is left in the string @c data - * as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c async_read_until operation. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - const boost::regex& expr, - ASIO_MOVE_ARG(ReadHandler) handler); - -#endif // defined(ASIO_HAS_BOOST_REGEX) - // || defined(GENERATING_DOCUMENTATION) - -/// Start an asynchronous operation to read data into a dynamic buffer sequence -/// until a function object indicates a match. -/** - * This function is used to asynchronously read data into the specified dynamic - * buffer sequence until a user-defined match condition function object, when - * applied to the data contained in the dynamic buffer sequence, indicates a - * successful match. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li The match condition function object returns a std::pair where the second - * element evaluates to true. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the match condition function object already indicates a match, this - * asynchronous operation completes immediately. The program must ensure that - * the stream performs no other read operations (such as async_read, - * async_read_until, the stream's async_read_some function, or any other - * composed operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param buffers The dynamic buffer sequence into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param match_condition The function object to be called to determine whether - * a match exists. The signature of the function object must be: - * @code pair match_condition(iterator begin, iterator end); - * @endcode - * where @c iterator represents the type: - * @code buffers_iterator - * @endcode - * The iterator parameters @c begin and @c end define the range of bytes to be - * scanned to determine whether there is a match. The @c first member of the - * return value is an iterator marking one-past-the-end of the bytes that have - * been consumed by the match function. This iterator is used to calculate the - * @c begin parameter for any subsequent invocation of the match condition. The - * @c second member of the return value is true if a match has been found, false - * otherwise. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the dynamic buffer sequence's - * // get area that have been fully consumed by the match - * // function. O if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the dynamic buffer - * sequence may contain additional data beyond that which matched the function - * object. An application will typically leave that data in the dynamic buffer - * sequence for a subsequent async_read_until operation to examine. - * - * @note The default implementation of the @c is_match_condition type trait - * evaluates to true for function pointers and function objects with a - * @c result_type typedef. It must be specialised for other user-defined - * function objects. - * - * @par Examples - * To asynchronously read data into a @c std::string until whitespace is - * encountered: - * @code typedef asio::buffers_iterator< - * asio::const_buffers_1> iterator; - * - * std::pair - * match_whitespace(iterator begin, iterator end) - * { - * iterator i = begin; - * while (i != end) - * if (std::isspace(*i++)) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * ... - * void handler(const asio::error_code& e, std::size_t size); - * ... - * std::string data; - * asio::async_read_until(s, data, match_whitespace, handler); - * @endcode - * - * To asynchronously read data into a @c std::string until a matching character - * is found: - * @code class match_char - * { - * public: - * explicit match_char(char c) : c_(c) {} - * - * template - * std::pair operator()( - * Iterator begin, Iterator end) const - * { - * Iterator i = begin; - * while (i != end) - * if (c_ == *i++) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * - * private: - * char c_; - * }; - * - * namespace asio { - * template <> struct is_match_condition - * : public boost::true_type {}; - * } // namespace asio - * ... - * void handler(const asio::error_code& e, std::size_t size); - * ... - * std::string data; - * asio::async_read_until(s, data, match_char('a'), handler); - * @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - MatchCondition match_condition, ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if::value>::type* = 0); - -#if !defined(ASIO_NO_IOSTREAM) - -/// Start an asynchronous operation to read data into a streambuf until it -/// contains a specified delimiter. -/** - * This function is used to asynchronously read data into the specified - * streambuf until the streambuf's get area contains the specified delimiter. - * The function call always returns immediately. The asynchronous operation - * will continue until one of the following conditions is true: - * - * @li The get area of the streambuf contains the specified delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the streambuf's get area already contains the delimiter, this asynchronous - * operation completes immediately. The program must ensure that the stream - * performs no other read operations (such as async_read, async_read_until, the - * stream's async_read_some function, or any other composed operations that - * perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. Ownership of - * the streambuf is retained by the caller, which must guarantee that it remains - * valid until the handler is called. - * - * @param delim The delimiter character. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the streambuf's get - * // area up to and including the delimiter. - * // 0 if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the streambuf may - * contain additional data beyond the delimiter. An application will typically - * leave that data in the streambuf for a subsequent async_read_until operation - * to examine. - * - * @par Example - * To asynchronously read data into a streambuf until a newline is encountered: - * @code asio::streambuf b; - * ... - * void handler(const asio::error_code& e, std::size_t size) - * { - * if (!e) - * { - * std::istream is(&b); - * std::string line; - * std::getline(is, line); - * ... - * } - * } - * ... - * asio::async_read_until(s, b, '\n', handler); @endcode - * After the @c async_read_until operation completes successfully, the buffer - * @c b contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\n', 'd', 'e', ... } @endcode - * The call to @c std::getline then extracts the data up to and including the - * newline (which is discarded), so that the string @c line contains: - * @code { 'a', 'b', ..., 'c' } @endcode - * The remaining data is left in the buffer @c b as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c async_read_until operation. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, - char delim, ASIO_MOVE_ARG(ReadHandler) handler); - -/// Start an asynchronous operation to read data into a streambuf until it -/// contains a specified delimiter. -/** - * This function is used to asynchronously read data into the specified - * streambuf until the streambuf's get area contains the specified delimiter. - * The function call always returns immediately. The asynchronous operation - * will continue until one of the following conditions is true: - * - * @li The get area of the streambuf contains the specified delimiter. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the streambuf's get area already contains the delimiter, this asynchronous - * operation completes immediately. The program must ensure that the stream - * performs no other read operations (such as async_read, async_read_until, the - * stream's async_read_some function, or any other composed operations that - * perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. Ownership of - * the streambuf is retained by the caller, which must guarantee that it remains - * valid until the handler is called. - * - * @param delim The delimiter string. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the streambuf's get - * // area up to and including the delimiter. - * // 0 if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the streambuf may - * contain additional data beyond the delimiter. An application will typically - * leave that data in the streambuf for a subsequent async_read_until operation - * to examine. - * - * @par Example - * To asynchronously read data into a streambuf until a newline is encountered: - * @code asio::streambuf b; - * ... - * void handler(const asio::error_code& e, std::size_t size) - * { - * if (!e) - * { - * std::istream is(&b); - * std::string line; - * std::getline(is, line); - * ... - * } - * } - * ... - * asio::async_read_until(s, b, "\r\n", handler); @endcode - * After the @c async_read_until operation completes successfully, the buffer - * @c b contains the delimiter: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c std::getline then extracts the data up to and including the - * newline (which is discarded), so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r' } @endcode - * The remaining data is left in the buffer @c b as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c async_read_until operation. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, - ASIO_STRING_VIEW_PARAM delim, - ASIO_MOVE_ARG(ReadHandler) handler); - -#if defined(ASIO_HAS_BOOST_REGEX) \ - || defined(GENERATING_DOCUMENTATION) - -/// Start an asynchronous operation to read data into a streambuf until some -/// part of its data matches a regular expression. -/** - * This function is used to asynchronously read data into the specified - * streambuf until the streambuf's get area contains some data that matches a - * regular expression. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li A substring of the streambuf's get area matches the regular expression. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the streambuf's get area already contains data that matches the regular - * expression, this asynchronous operation completes immediately. The program - * must ensure that the stream performs no other read operations (such as - * async_read, async_read_until, the stream's async_read_some function, or any - * other composed operations that perform reads) until this operation - * completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. Ownership of - * the streambuf is retained by the caller, which must guarantee that it remains - * valid until the handler is called. - * - * @param expr The regular expression. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the streambuf's get - * // area up to and including the substring - * // that matches the regular. expression. - * // 0 if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the streambuf may - * contain additional data beyond that which matched the regular expression. An - * application will typically leave that data in the streambuf for a subsequent - * async_read_until operation to examine. - * - * @par Example - * To asynchronously read data into a streambuf until a CR-LF sequence is - * encountered: - * @code asio::streambuf b; - * ... - * void handler(const asio::error_code& e, std::size_t size) - * { - * if (!e) - * { - * std::istream is(&b); - * std::string line; - * std::getline(is, line); - * ... - * } - * } - * ... - * asio::async_read_until(s, b, boost::regex("\r\n"), handler); @endcode - * After the @c async_read_until operation completes successfully, the buffer - * @c b contains the data which matched the regular expression: - * @code { 'a', 'b', ..., 'c', '\r', '\n', 'd', 'e', ... } @endcode - * The call to @c std::getline then extracts the data up to and including the - * newline (which is discarded), so that the string @c line contains: - * @code { 'a', 'b', ..., 'c', '\r' } @endcode - * The remaining data is left in the buffer @c b as follows: - * @code { 'd', 'e', ... } @endcode - * This data may be the start of a new line, to be extracted by a subsequent - * @c async_read_until operation. - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, const boost::regex& expr, - ASIO_MOVE_ARG(ReadHandler) handler); - -#endif // defined(ASIO_HAS_BOOST_REGEX) - // || defined(GENERATING_DOCUMENTATION) - -/// Start an asynchronous operation to read data into a streambuf until a -/// function object indicates a match. -/** - * This function is used to asynchronously read data into the specified - * streambuf until a user-defined match condition function object, when applied - * to the data contained in the streambuf, indicates a successful match. The - * function call always returns immediately. The asynchronous operation will - * continue until one of the following conditions is true: - * - * @li The match condition function object returns a std::pair where the second - * element evaluates to true. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_read_some function, and is known as a composed operation. If - * the match condition function object already indicates a match, this - * asynchronous operation completes immediately. The program must ensure that - * the stream performs no other read operations (such as async_read, - * async_read_until, the stream's async_read_some function, or any other - * composed operations that perform reads) until this operation completes. - * - * @param s The stream from which the data is to be read. The type must support - * the AsyncReadStream concept. - * - * @param b A streambuf object into which the data will be read. - * - * @param match_condition The function object to be called to determine whether - * a match exists. The signature of the function object must be: - * @code pair match_condition(iterator begin, iterator end); - * @endcode - * where @c iterator represents the type: - * @code buffers_iterator::const_buffers_type> - * @endcode - * The iterator parameters @c begin and @c end define the range of bytes to be - * scanned to determine whether there is a match. The @c first member of the - * return value is an iterator marking one-past-the-end of the bytes that have - * been consumed by the match function. This iterator is used to calculate the - * @c begin parameter for any subsequent invocation of the match condition. The - * @c second member of the return value is true if a match has been found, false - * otherwise. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // The number of bytes in the streambuf's get - * // area that have been fully consumed by the - * // match function. O if an error occurred. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note After a successful async_read_until operation, the streambuf may - * contain additional data beyond that which matched the function object. An - * application will typically leave that data in the streambuf for a subsequent - * async_read_until operation to examine. - * - * @note The default implementation of the @c is_match_condition type trait - * evaluates to true for function pointers and function objects with a - * @c result_type typedef. It must be specialised for other user-defined - * function objects. - * - * @par Examples - * To asynchronously read data into a streambuf until whitespace is encountered: - * @code typedef asio::buffers_iterator< - * asio::streambuf::const_buffers_type> iterator; - * - * std::pair - * match_whitespace(iterator begin, iterator end) - * { - * iterator i = begin; - * while (i != end) - * if (std::isspace(*i++)) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * ... - * void handler(const asio::error_code& e, std::size_t size); - * ... - * asio::streambuf b; - * asio::async_read_until(s, b, match_whitespace, handler); - * @endcode - * - * To asynchronously read data into a streambuf until a matching character is - * found: - * @code class match_char - * { - * public: - * explicit match_char(char c) : c_(c) {} - * - * template - * std::pair operator()( - * Iterator begin, Iterator end) const - * { - * Iterator i = begin; - * while (i != end) - * if (c_ == *i++) - * return std::make_pair(i, true); - * return std::make_pair(i, false); - * } - * - * private: - * char c_; - * }; - * - * namespace asio { - * template <> struct is_match_condition - * : public boost::true_type {}; - * } // namespace asio - * ... - * void handler(const asio::error_code& e, std::size_t size); - * ... - * asio::streambuf b; - * asio::async_read_until(s, b, match_char('a'), handler); - * @endcode - */ -template -ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) -async_read_until(AsyncReadStream& s, - asio::basic_streambuf& b, - MatchCondition match_condition, ASIO_MOVE_ARG(ReadHandler) handler, - typename enable_if::value>::type* = 0); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/read_until.hpp" - -#endif // ASIO_READ_UNTIL_HPP diff --git a/scout_sdk/asio/asio/seq_packet_socket_service.hpp b/scout_sdk/asio/asio/seq_packet_socket_service.hpp deleted file mode 100644 index 7e6824d..0000000 --- a/scout_sdk/asio/asio/seq_packet_socket_service.hpp +++ /dev/null @@ -1,416 +0,0 @@ -// -// seq_packet_socket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SEQ_PACKET_SOCKET_SERVICE_HPP -#define ASIO_SEQ_PACKET_SOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/null_socket_service.hpp" -#elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_socket_service.hpp" -#else -# include "asio/detail/reactive_socket_service.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a sequenced packet socket. -template -class seq_packet_socket_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base< - seq_packet_socket_service > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - -private: - // The type of the platform-specific implementation. -#if defined(ASIO_WINDOWS_RUNTIME) - typedef detail::null_socket_service service_impl_type; -#elif defined(ASIO_HAS_IOCP) - typedef detail::win_iocp_socket_service service_impl_type; -#else - typedef detail::reactive_socket_service service_impl_type; -#endif - -public: - /// The type of a sequenced packet socket implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// The native socket type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new sequenced packet socket service for the specified - /// io_context. - explicit seq_packet_socket_service(asio::io_context& io_context) - : asio::detail::service_base< - seq_packet_socket_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new sequenced packet socket implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new sequenced packet socket implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another sequenced packet socket implementation. - void move_assign(implementation_type& impl, - seq_packet_socket_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } - - // All socket services have access to each other's implementations. - template friend class seq_packet_socket_service; - - /// Move-construct a new sequenced packet socket implementation from another - /// protocol type. - template - void converting_move_construct(implementation_type& impl, - seq_packet_socket_service& other_service, - typename seq_packet_socket_service< - Protocol1>::implementation_type& other_impl, - typename enable_if::value>::type* = 0) - { - service_impl_.template converting_move_construct( - impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a sequenced packet socket implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Open a sequenced packet socket. - ASIO_SYNC_OP_VOID open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - if (protocol.type() == ASIO_OS_DEF(SOCK_SEQPACKET)) - service_impl_.open(impl, protocol, ec); - else - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native socket to a sequenced packet socket. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_socket, - asio::error_code& ec) - { - service_impl_.assign(impl, protocol, native_socket, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a sequenced packet socket implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Release ownership of the underlying socket. - native_handle_type release(implementation_type& impl, - asio::error_code& ec) - { - return service_impl_.release(impl, ec); - } - - /// Get the native socket implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the socket. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is at the out-of-band data mark. - bool at_mark(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.at_mark(impl, ec); - } - - /// Determine the number of bytes available for reading. - std::size_t available(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.available(impl, ec); - } - - /// Bind the sequenced packet socket to the specified local endpoint. - ASIO_SYNC_OP_VOID bind(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - service_impl_.bind(impl, endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Connect the sequenced packet socket to the specified endpoint. - ASIO_SYNC_OP_VOID connect(implementation_type& impl, - const endpoint_type& peer_endpoint, asio::error_code& ec) - { - service_impl_.connect(impl, peer_endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous connect. - template - ASIO_INITFN_RESULT_TYPE(ConnectHandler, - void (asio::error_code)) - async_connect(implementation_type& impl, - const endpoint_type& peer_endpoint, - ASIO_MOVE_ARG(ConnectHandler) handler) - { - async_completion init(handler); - - service_impl_.async_connect(impl, peer_endpoint, init.completion_handler); - - return init.result.get(); - } - - /// Set a socket option. - template - ASIO_SYNC_OP_VOID set_option(implementation_type& impl, - const SettableSocketOption& option, asio::error_code& ec) - { - service_impl_.set_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get a socket option. - template - ASIO_SYNC_OP_VOID get_option(const implementation_type& impl, - GettableSocketOption& option, asio::error_code& ec) const - { - service_impl_.get_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the socket. - template - ASIO_SYNC_OP_VOID io_control(implementation_type& impl, - IoControlCommand& command, asio::error_code& ec) - { - service_impl_.io_control(impl, command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the socket. - bool non_blocking(const implementation_type& impl) const - { - return service_impl_.non_blocking(impl); - } - - /// Sets the non-blocking mode of the socket. - ASIO_SYNC_OP_VOID non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const implementation_type& impl) const - { - return service_impl_.native_non_blocking(impl); - } - - /// Sets the non-blocking mode of the native socket implementation. - ASIO_SYNC_OP_VOID native_non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.native_non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.local_endpoint(impl, ec); - } - - /// Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.remote_endpoint(impl, ec); - } - - /// Disable sends or receives on the socket. - ASIO_SYNC_OP_VOID shutdown(implementation_type& impl, - socket_base::shutdown_type what, asio::error_code& ec) - { - service_impl_.shutdown(impl, what, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the socket to become ready to read, ready to write, or to have - /// pending error conditions. - ASIO_SYNC_OP_VOID wait(implementation_type& impl, - socket_base::wait_type w, asio::error_code& ec) - { - service_impl_.wait(impl, w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the socket to become ready to read, ready to - /// write, or to have pending error conditions. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, socket_base::wait_type w, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, w, init.completion_handler); - - return init.result.get(); - } - - /// Send the given data to the peer. - template - std::size_t send(implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.send(impl, buffers, flags, ec); - } - - /// Start an asynchronous send. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - async_completion init(handler); - - service_impl_.async_send(impl, buffers, flags, init.completion_handler); - - return init.result.get(); - } - - /// Receive some data from the peer. - template - std::size_t receive(implementation_type& impl, - const MutableBufferSequence& buffers, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, asio::error_code& ec) - { - return service_impl_.receive_with_flags(impl, - buffers, in_flags, out_flags, ec); - } - - /// Start an asynchronous receive. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(implementation_type& impl, - const MutableBufferSequence& buffers, socket_base::message_flags in_flags, - socket_base::message_flags& out_flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - async_completion init(handler); - - service_impl_.async_receive_with_flags(impl, - buffers, in_flags, out_flags, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_SEQ_PACKET_SOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/serial_port.hpp b/scout_sdk/asio/asio/serial_port.hpp deleted file mode 100644 index 27bb63e..0000000 --- a/scout_sdk/asio/asio/serial_port.hpp +++ /dev/null @@ -1,769 +0,0 @@ -// -// serial_port.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SERIAL_PORT_HPP -#define ASIO_SERIAL_PORT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_SERIAL_PORT) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/async_result.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/serial_port_base.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/basic_serial_port.hpp" -#else // defined(ASIO_ENABLE_OLD_SERVICES) -# if defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_serial_port_service.hpp" -# define ASIO_SVC_T detail::win_iocp_serial_port_service -# else -# include "asio/detail/reactive_serial_port_service.hpp" -# define ASIO_SVC_T detail::reactive_serial_port_service -# endif -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if defined(ASIO_ENABLE_OLD_SERVICES) -// Typedef for the typical usage of a serial port. -typedef basic_serial_port<> serial_port; -#else // defined(ASIO_ENABLE_OLD_SERVICES) -/// Provides serial port functionality. -/** - * The serial_port class provides a wrapper over serial port functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class serial_port - : ASIO_SVC_ACCESS basic_io_object, - public serial_port_base -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The native representation of a serial port. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef ASIO_SVC_T::native_handle_type native_handle_type; -#endif - - /// A basic_serial_port is always the lowest layer. - typedef serial_port lowest_layer_type; - - /// Construct a serial_port without opening it. - /** - * This constructor creates a serial port without opening it. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - */ - explicit serial_port(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct and open a serial_port. - /** - * This constructor creates and opens a serial port for the specified device - * name. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - * - * @param device The platform-specific device name for this serial - * port. - */ - explicit serial_port(asio::io_context& io_context, - const char* device) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), device, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Construct and open a serial_port. - /** - * This constructor creates and opens a serial port for the specified device - * name. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - * - * @param device The platform-specific device name for this serial - * port. - */ - explicit serial_port(asio::io_context& io_context, - const std::string& device) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), device, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Construct a serial_port on an existing native serial port. - /** - * This constructor creates a serial port object to hold an existing native - * serial port. - * - * @param io_context The io_context object that the serial port will use to - * dispatch handlers for any asynchronous operations performed on the port. - * - * @param native_serial_port A native serial port. - * - * @throws asio::system_error Thrown on failure. - */ - serial_port(asio::io_context& io_context, - const native_handle_type& native_serial_port) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_serial_port, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a serial_port from another. - /** - * This constructor moves a serial port from one object to another. - * - * @param other The other serial_port object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c serial_port(io_context&) constructor. - */ - serial_port(serial_port&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign a serial_port from another. - /** - * This assignment operator moves a serial port from one object to another. - * - * @param other The other serial_port object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c serial_port(io_context&) constructor. - */ - serial_port& operator=(serial_port&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroys the serial port. - /** - * This function destroys the serial port, cancelling any outstanding - * asynchronous wait operations associated with the serial port as if by - * calling @c cancel. - */ - ~serial_port() - { - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since a serial_port cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since a serial_port cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } - - /// Open the serial port using the specified device name. - /** - * This function opens the serial port for the specified device name. - * - * @param device The platform-specific device name. - * - * @throws asio::system_error Thrown on failure. - */ - void open(const std::string& device) - { - asio::error_code ec; - this->get_service().open(this->get_implementation(), device, ec); - asio::detail::throw_error(ec, "open"); - } - - /// Open the serial port using the specified device name. - /** - * This function opens the serial port using the given platform-specific - * device name. - * - * @param device The platform-specific device name. - * - * @param ec Set the indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID open(const std::string& device, - asio::error_code& ec) - { - this->get_service().open(this->get_implementation(), device, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native serial port to the serial port. - /* - * This function opens the serial port to hold an existing native serial port. - * - * @param native_serial_port A native serial port. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const native_handle_type& native_serial_port) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), - native_serial_port, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native serial port to the serial port. - /* - * This function opens the serial port to hold an existing native serial port. - * - * @param native_serial_port A native serial port. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const native_handle_type& native_serial_port, - asio::error_code& ec) - { - this->get_service().assign(this->get_implementation(), - native_serial_port, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the serial port is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the serial port. - /** - * This function is used to close the serial port. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the serial port. - /** - * This function is used to close the serial port. Any asynchronous read or - * write operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native serial port representation. - /** - * This function may be used to obtain the underlying representation of the - * serial port. This is intended to allow access to native serial port - * functionality that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the serial port. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the serial port. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Send a break sequence to the serial port. - /** - * This function causes a break sequence of platform-specific duration to be - * sent out the serial port. - * - * @throws asio::system_error Thrown on failure. - */ - void send_break() - { - asio::error_code ec; - this->get_service().send_break(this->get_implementation(), ec); - asio::detail::throw_error(ec, "send_break"); - } - - /// Send a break sequence to the serial port. - /** - * This function causes a break sequence of platform-specific duration to be - * sent out the serial port. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID send_break(asio::error_code& ec) - { - this->get_service().send_break(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Set an option on the serial port. - /** - * This function is used to set an option on the serial port. - * - * @param option The option value to be set on the serial port. - * - * @throws asio::system_error Thrown on failure. - * - * @sa SettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - void set_option(const SettableSerialPortOption& option) - { - asio::error_code ec; - this->get_service().set_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "set_option"); - } - - /// Set an option on the serial port. - /** - * This function is used to set an option on the serial port. - * - * @param option The option value to be set on the serial port. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa SettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - ASIO_SYNC_OP_VOID set_option(const SettableSerialPortOption& option, - asio::error_code& ec) - { - this->get_service().set_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get an option from the serial port. - /** - * This function is used to get the current value of an option on the serial - * port. - * - * @param option The option value to be obtained from the serial port. - * - * @throws asio::system_error Thrown on failure. - * - * @sa GettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - void get_option(GettableSerialPortOption& option) - { - asio::error_code ec; - this->get_service().get_option(this->get_implementation(), option, ec); - asio::detail::throw_error(ec, "get_option"); - } - - /// Get an option from the serial port. - /** - * This function is used to get the current value of an option on the serial - * port. - * - * @param option The option value to be obtained from the serial port. - * - * @param ec Set to indicate what error occurred, if any. - * - * @sa GettableSerialPortOption @n - * asio::serial_port_base::baud_rate @n - * asio::serial_port_base::flow_control @n - * asio::serial_port_base::parity @n - * asio::serial_port_base::stop_bits @n - * asio::serial_port_base::character_size - */ - template - ASIO_SYNC_OP_VOID get_option(GettableSerialPortOption& option, - asio::error_code& ec) - { - this->get_service().get_option(this->get_implementation(), option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Write some data to the serial port. - /** - * This function is used to write data to the serial port. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the serial port. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.write_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "write_some"); - return s; - } - - /// Write some data to the serial port. - /** - * This function is used to write data to the serial port. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the serial port. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().write_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write data to the serial port. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be written to the serial port. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.async_write_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - async_completion init(handler); - - this->get_service().async_write_some( - this->get_implementation(), buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the serial port. - /** - * This function is used to read data from the serial port. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.read_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "read_some"); - return s; - } - - /// Read some data from the serial port. - /** - * This function is used to read data from the serial port. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().read_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read data from the serial port. - * The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read function if you need to ensure that the - * requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * serial_port.async_read_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - async_completion init(handler); - - this->get_service().async_read_some( - this->get_implementation(), buffers, init.completion_handler); - - return init.result.get(); - } -}; -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) -# undef ASIO_SVC_T -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // defined(ASIO_HAS_SERIAL_PORT) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_SERIAL_PORT_HPP diff --git a/scout_sdk/asio/asio/serial_port_base.hpp b/scout_sdk/asio/asio/serial_port_base.hpp deleted file mode 100644 index feb5b9d..0000000 --- a/scout_sdk/asio/asio/serial_port_base.hpp +++ /dev/null @@ -1,167 +0,0 @@ -// -// serial_port_base.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2008 Rep Invariant Systems, Inc. (info@repinvariant.com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SERIAL_PORT_BASE_HPP -#define ASIO_SERIAL_PORT_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_SERIAL_PORT) \ - || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) -# include -#endif // !defined(ASIO_WINDOWS) && !defined(__CYGWIN__) - -#include "asio/detail/socket_types.hpp" -#include "asio/error_code.hpp" - -#if defined(GENERATING_DOCUMENTATION) -# define ASIO_OPTION_STORAGE implementation_defined -#elif defined(ASIO_WINDOWS) || defined(__CYGWIN__) -# define ASIO_OPTION_STORAGE DCB -#else -# define ASIO_OPTION_STORAGE termios -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// The serial_port_base class is used as a base for the basic_serial_port class -/// template so that we have a common place to define the serial port options. -class serial_port_base -{ -public: - /// Serial port option to permit changing the baud rate. - /** - * Implements changing the baud rate for a given serial port. - */ - class baud_rate - { - public: - explicit baud_rate(unsigned int rate = 0); - unsigned int value() const; - ASIO_DECL ASIO_SYNC_OP_VOID store( - ASIO_OPTION_STORAGE& storage, - asio::error_code& ec) const; - ASIO_DECL ASIO_SYNC_OP_VOID load( - const ASIO_OPTION_STORAGE& storage, - asio::error_code& ec); - private: - unsigned int value_; - }; - - /// Serial port option to permit changing the flow control. - /** - * Implements changing the flow control for a given serial port. - */ - class flow_control - { - public: - enum type { none, software, hardware }; - ASIO_DECL explicit flow_control(type t = none); - type value() const; - ASIO_DECL ASIO_SYNC_OP_VOID store( - ASIO_OPTION_STORAGE& storage, - asio::error_code& ec) const; - ASIO_DECL ASIO_SYNC_OP_VOID load( - const ASIO_OPTION_STORAGE& storage, - asio::error_code& ec); - private: - type value_; - }; - - /// Serial port option to permit changing the parity. - /** - * Implements changing the parity for a given serial port. - */ - class parity - { - public: - enum type { none, odd, even }; - ASIO_DECL explicit parity(type t = none); - type value() const; - ASIO_DECL ASIO_SYNC_OP_VOID store( - ASIO_OPTION_STORAGE& storage, - asio::error_code& ec) const; - ASIO_DECL ASIO_SYNC_OP_VOID load( - const ASIO_OPTION_STORAGE& storage, - asio::error_code& ec); - private: - type value_; - }; - - /// Serial port option to permit changing the number of stop bits. - /** - * Implements changing the number of stop bits for a given serial port. - */ - class stop_bits - { - public: - enum type { one, onepointfive, two }; - ASIO_DECL explicit stop_bits(type t = one); - type value() const; - ASIO_DECL ASIO_SYNC_OP_VOID store( - ASIO_OPTION_STORAGE& storage, - asio::error_code& ec) const; - ASIO_DECL ASIO_SYNC_OP_VOID load( - const ASIO_OPTION_STORAGE& storage, - asio::error_code& ec); - private: - type value_; - }; - - /// Serial port option to permit changing the character size. - /** - * Implements changing the character size for a given serial port. - */ - class character_size - { - public: - ASIO_DECL explicit character_size(unsigned int t = 8); - unsigned int value() const; - ASIO_DECL ASIO_SYNC_OP_VOID store( - ASIO_OPTION_STORAGE& storage, - asio::error_code& ec) const; - ASIO_DECL ASIO_SYNC_OP_VOID load( - const ASIO_OPTION_STORAGE& storage, - asio::error_code& ec); - private: - unsigned int value_; - }; - -protected: - /// Protected destructor to prevent deletion through this type. - ~serial_port_base() - { - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#undef ASIO_OPTION_STORAGE - -#include "asio/impl/serial_port_base.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/serial_port_base.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // defined(ASIO_HAS_SERIAL_PORT) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_SERIAL_PORT_BASE_HPP diff --git a/scout_sdk/asio/asio/serial_port_service.hpp b/scout_sdk/asio/asio/serial_port_service.hpp deleted file mode 100644 index 0e20d96..0000000 --- a/scout_sdk/asio/asio/serial_port_service.hpp +++ /dev/null @@ -1,249 +0,0 @@ -// -// serial_port_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SERIAL_PORT_SERVICE_HPP -#define ASIO_SERIAL_PORT_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_SERIAL_PORT) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include -#include "asio/async_result.hpp" -#include "asio/detail/reactive_serial_port_service.hpp" -#include "asio/detail/win_iocp_serial_port_service.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" -#include "asio/serial_port_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a serial port. -class serial_port_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - -private: - // The type of the platform-specific implementation. -#if defined(ASIO_HAS_IOCP) - typedef detail::win_iocp_serial_port_service service_impl_type; -#else - typedef detail::reactive_serial_port_service service_impl_type; -#endif - -public: - /// The type of a serial port implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef service_impl_type::implementation_type implementation_type; -#endif - - /// The native handle type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new serial port service for the specified io_context. - explicit serial_port_service(asio::io_context& io_context) - : asio::detail::service_base(io_context), - service_impl_(io_context) - { - } - - /// Construct a new serial port implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new serial port implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another serial port implementation. - void move_assign(implementation_type& impl, - serial_port_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a serial port implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Open a serial port. - ASIO_SYNC_OP_VOID open(implementation_type& impl, - const std::string& device, asio::error_code& ec) - { - service_impl_.open(impl, device, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native handle to a serial port. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec) - { - service_impl_.assign(impl, handle, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the handle is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a serial port implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native handle implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the handle. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Set a serial port option. - template - ASIO_SYNC_OP_VOID set_option(implementation_type& impl, - const SettableSerialPortOption& option, asio::error_code& ec) - { - service_impl_.set_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get a serial port option. - template - ASIO_SYNC_OP_VOID get_option(const implementation_type& impl, - GettableSerialPortOption& option, asio::error_code& ec) const - { - service_impl_.get_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Send a break sequence to the serial port. - ASIO_SYNC_OP_VOID send_break(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.send_break(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Write the given data to the stream. - template - std::size_t write_some(implementation_type& impl, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.write_some(impl, buffers, ec); - } - - /// Start an asynchronous write. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(implementation_type& impl, - const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - async_completion init(handler); - - service_impl_.async_write_some(impl, buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the stream. - template - std::size_t read_some(implementation_type& impl, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.read_some(impl, buffers, ec); - } - - /// Start an asynchronous read. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(implementation_type& impl, - const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - async_completion init(handler); - - service_impl_.async_read_some(impl, buffers, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_SERIAL_PORT) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_SERIAL_PORT_SERVICE_HPP diff --git a/scout_sdk/asio/asio/signal_set.hpp b/scout_sdk/asio/asio/signal_set.hpp deleted file mode 100644 index 30e5c4e..0000000 --- a/scout_sdk/asio/asio/signal_set.hpp +++ /dev/null @@ -1,447 +0,0 @@ -// -// signal_set.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SIGNAL_SET_HPP -#define ASIO_SIGNAL_SET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/async_result.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/basic_signal_set.hpp" -#else // defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/detail/signal_set_service.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -namespace asio { - -#if defined(ASIO_ENABLE_OLD_SERVICES) -// Typedef for the typical usage of a signal set. -typedef basic_signal_set<> signal_set; -#else // defined(ASIO_ENABLE_OLD_SERVICES) -/// Provides signal functionality. -/** - * The signal_set class provides the ability to perform an asynchronous wait - * for one or more signals to occur. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Example - * Performing an asynchronous wait: - * @code - * void handler( - * const asio::error_code& error, - * int signal_number) - * { - * if (!error) - * { - * // A signal occurred. - * } - * } - * - * ... - * - * // Construct a signal set registered for process termination. - * asio::signal_set signals(io_context, SIGINT, SIGTERM); - * - * // Start an asynchronous wait for one of the signals to occur. - * signals.async_wait(handler); - * @endcode - * - * @par Queueing of signal notifications - * - * If a signal is registered with a signal_set, and the signal occurs when - * there are no waiting handlers, then the signal notification is queued. The - * next async_wait operation on that signal_set will dequeue the notification. - * If multiple notifications are queued, subsequent async_wait operations - * dequeue them one at a time. Signal notifications are dequeued in order of - * ascending signal number. - * - * If a signal number is removed from a signal_set (using the @c remove or @c - * erase member functions) then any queued notifications for that signal are - * discarded. - * - * @par Multiple registration of signals - * - * The same signal number may be registered with different signal_set objects. - * When the signal occurs, one handler is called for each signal_set object. - * - * Note that multiple registration only works for signals that are registered - * using Asio. The application must not also register a signal handler using - * functions such as @c signal() or @c sigaction(). - * - * @par Signal masking on POSIX platforms - * - * POSIX allows signals to be blocked using functions such as @c sigprocmask() - * and @c pthread_sigmask(). For signals to be delivered, programs must ensure - * that any signals registered using signal_set objects are unblocked in at - * least one thread. - */ -class signal_set - : ASIO_SVC_ACCESS basic_io_object -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// Construct a signal set without adding any signals. - /** - * This constructor creates a signal set without registering for any signals. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - */ - explicit signal_set(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct a signal set and add one signal. - /** - * This constructor creates a signal set and registers for one signal. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - * - * @param signal_number_1 The signal number to be added. - * - * @note This constructor is equivalent to performing: - * @code asio::signal_set signals(io_context); - * signals.add(signal_number_1); @endcode - */ - signal_set(asio::io_context& io_context, int signal_number_1) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number_1, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Construct a signal set and add two signals. - /** - * This constructor creates a signal set and registers for two signals. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - * - * @param signal_number_1 The first signal number to be added. - * - * @param signal_number_2 The second signal number to be added. - * - * @note This constructor is equivalent to performing: - * @code asio::signal_set signals(io_context); - * signals.add(signal_number_1); - * signals.add(signal_number_2); @endcode - */ - signal_set(asio::io_context& io_context, int signal_number_1, - int signal_number_2) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number_1, ec); - asio::detail::throw_error(ec, "add"); - this->get_service().add(this->get_implementation(), signal_number_2, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Construct a signal set and add three signals. - /** - * This constructor creates a signal set and registers for three signals. - * - * @param io_context The io_context object that the signal set will use to - * dispatch handlers for any asynchronous operations performed on the set. - * - * @param signal_number_1 The first signal number to be added. - * - * @param signal_number_2 The second signal number to be added. - * - * @param signal_number_3 The third signal number to be added. - * - * @note This constructor is equivalent to performing: - * @code asio::signal_set signals(io_context); - * signals.add(signal_number_1); - * signals.add(signal_number_2); - * signals.add(signal_number_3); @endcode - */ - signal_set(asio::io_context& io_context, int signal_number_1, - int signal_number_2, int signal_number_3) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number_1, ec); - asio::detail::throw_error(ec, "add"); - this->get_service().add(this->get_implementation(), signal_number_2, ec); - asio::detail::throw_error(ec, "add"); - this->get_service().add(this->get_implementation(), signal_number_3, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Destroys the signal set. - /** - * This function destroys the signal set, cancelling any outstanding - * asynchronous wait operations associated with the signal set as if by - * calling @c cancel. - */ - ~signal_set() - { - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } - - /// Add a signal to a signal_set. - /** - * This function adds the specified signal to the set. It has no effect if the - * signal is already in the set. - * - * @param signal_number The signal to be added to the set. - * - * @throws asio::system_error Thrown on failure. - */ - void add(int signal_number) - { - asio::error_code ec; - this->get_service().add(this->get_implementation(), signal_number, ec); - asio::detail::throw_error(ec, "add"); - } - - /// Add a signal to a signal_set. - /** - * This function adds the specified signal to the set. It has no effect if the - * signal is already in the set. - * - * @param signal_number The signal to be added to the set. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID add(int signal_number, - asio::error_code& ec) - { - this->get_service().add(this->get_implementation(), signal_number, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Remove a signal from a signal_set. - /** - * This function removes the specified signal from the set. It has no effect - * if the signal is not in the set. - * - * @param signal_number The signal to be removed from the set. - * - * @throws asio::system_error Thrown on failure. - * - * @note Removes any notifications that have been queued for the specified - * signal number. - */ - void remove(int signal_number) - { - asio::error_code ec; - this->get_service().remove(this->get_implementation(), signal_number, ec); - asio::detail::throw_error(ec, "remove"); - } - - /// Remove a signal from a signal_set. - /** - * This function removes the specified signal from the set. It has no effect - * if the signal is not in the set. - * - * @param signal_number The signal to be removed from the set. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Removes any notifications that have been queued for the specified - * signal number. - */ - ASIO_SYNC_OP_VOID remove(int signal_number, - asio::error_code& ec) - { - this->get_service().remove(this->get_implementation(), signal_number, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Remove all signals from a signal_set. - /** - * This function removes all signals from the set. It has no effect if the set - * is already empty. - * - * @throws asio::system_error Thrown on failure. - * - * @note Removes all queued notifications. - */ - void clear() - { - asio::error_code ec; - this->get_service().clear(this->get_implementation(), ec); - asio::detail::throw_error(ec, "clear"); - } - - /// Remove all signals from a signal_set. - /** - * This function removes all signals from the set. It has no effect if the set - * is already empty. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Removes all queued notifications. - */ - ASIO_SYNC_OP_VOID clear(asio::error_code& ec) - { - this->get_service().clear(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Cancel all operations associated with the signal set. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the signal set. The handler for each cancelled - * operation will be invoked with the asio::error::operation_aborted - * error code. - * - * Cancellation does not alter the set of registered signals. - * - * @throws asio::system_error Thrown on failure. - * - * @note If a registered signal occurred before cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all operations associated with the signal set. - /** - * This function forces the completion of any pending asynchronous wait - * operations against the signal set. The handler for each cancelled - * operation will be invoked with the asio::error::operation_aborted - * error code. - * - * Cancellation does not alter the set of registered signals. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note If a registered signal occurred before cancel() is called, then the - * handlers for asynchronous wait operations will: - * - * @li have already been invoked; or - * - * @li have been queued for invocation in the near future. - * - * These handlers can no longer be cancelled, and therefore are passed an - * error code that indicates the successful completion of the wait operation. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous operation to wait for a signal to be delivered. - /** - * This function may be used to initiate an asynchronous wait against the - * signal set. It always returns immediately. - * - * For each call to async_wait(), the supplied handler will be called exactly - * once. The handler will be called when: - * - * @li One of the registered signals in the signal set occurs; or - * - * @li The signal set was cancelled, in which case the handler is passed the - * error code asio::error::operation_aborted. - * - * @param handler The handler to be called when the signal occurs. Copies - * will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * int signal_number // Indicates which signal occurred. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(SignalHandler, - void (asio::error_code, int)) - async_wait(ASIO_MOVE_ARG(SignalHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a SignalHandler. - ASIO_SIGNAL_HANDLER_CHECK(SignalHandler, handler) type_check; - - async_completion init(handler); - - this->get_service().async_wait(this->get_implementation(), - init.completion_handler); - - return init.result.get(); - } -}; -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -} // namespace asio - -#endif // ASIO_SIGNAL_SET_HPP diff --git a/scout_sdk/asio/asio/signal_set_service.hpp b/scout_sdk/asio/asio/signal_set_service.hpp deleted file mode 100644 index 3285beb..0000000 --- a/scout_sdk/asio/asio/signal_set_service.hpp +++ /dev/null @@ -1,142 +0,0 @@ -// -// signal_set_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SIGNAL_SET_SERVICE_HPP -#define ASIO_SIGNAL_SET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/async_result.hpp" -#include "asio/detail/signal_set_service.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a signal set. -class signal_set_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - -public: - /// The type of a signal set implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef detail::signal_set_service::implementation_type implementation_type; -#endif - - /// Construct a new signal set service for the specified io_context. - explicit signal_set_service(asio::io_context& io_context) - : asio::detail::service_base(io_context), - service_impl_(io_context) - { - } - - /// Construct a new signal set implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - - /// Destroy a signal set implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Add a signal to a signal_set. - ASIO_SYNC_OP_VOID add(implementation_type& impl, - int signal_number, asio::error_code& ec) - { - service_impl_.add(impl, signal_number, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Remove a signal to a signal_set. - ASIO_SYNC_OP_VOID remove(implementation_type& impl, - int signal_number, asio::error_code& ec) - { - service_impl_.remove(impl, signal_number, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Remove all signals from a signal_set. - ASIO_SYNC_OP_VOID clear(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.clear(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Cancel all operations associated with the signal set. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - // Start an asynchronous operation to wait for a signal to be delivered. - template - ASIO_INITFN_RESULT_TYPE(SignalHandler, - void (asio::error_code, int)) - async_wait(implementation_type& impl, - ASIO_MOVE_ARG(SignalHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // Perform any fork-related housekeeping. - void notify_fork(asio::io_context::fork_event event) - { - service_impl_.notify_fork(event); - } - - // The platform-specific implementation. - detail::signal_set_service service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_SIGNAL_SET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/socket_acceptor_service.hpp b/scout_sdk/asio/asio/socket_acceptor_service.hpp deleted file mode 100644 index cd40fe1..0000000 --- a/scout_sdk/asio/asio/socket_acceptor_service.hpp +++ /dev/null @@ -1,372 +0,0 @@ -// -// socket_acceptor_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SOCKET_ACCEPTOR_SERVICE_HPP -#define ASIO_SOCKET_ACCEPTOR_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/basic_socket.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/null_socket_service.hpp" -#elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_socket_service.hpp" -#else -# include "asio/detail/reactive_socket_service.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a socket acceptor. -template -class socket_acceptor_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename protocol_type::endpoint endpoint_type; - -private: - // The type of the platform-specific implementation. -#if defined(ASIO_WINDOWS_RUNTIME) - typedef detail::null_socket_service service_impl_type; -#elif defined(ASIO_HAS_IOCP) - typedef detail::win_iocp_socket_service service_impl_type; -#else - typedef detail::reactive_socket_service service_impl_type; -#endif - -public: - /// The native type of the socket acceptor. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// The native acceptor type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new socket acceptor service for the specified io_context. - explicit socket_acceptor_service(asio::io_context& io_context) - : asio::detail::service_base< - socket_acceptor_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new socket acceptor implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new socket acceptor implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another socket acceptor implementation. - void move_assign(implementation_type& impl, - socket_acceptor_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } - - // All acceptor services have access to each other's implementations. - template friend class socket_acceptor_service; - - /// Move-construct a new socket acceptor implementation from another protocol - /// type. - template - void converting_move_construct(implementation_type& impl, - socket_acceptor_service& other_service, - typename socket_acceptor_service< - Protocol1>::implementation_type& other_impl, - typename enable_if::value>::type* = 0) - { - service_impl_.template converting_move_construct( - impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a socket acceptor implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Open a new socket acceptor implementation. - ASIO_SYNC_OP_VOID open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - service_impl_.open(impl, protocol, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native acceptor to a socket acceptor. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_acceptor, - asio::error_code& ec) - { - service_impl_.assign(impl, protocol, native_acceptor, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the acceptor is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Cancel all asynchronous operations associated with the acceptor. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Bind the socket acceptor to the specified local endpoint. - ASIO_SYNC_OP_VOID bind(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - service_impl_.bind(impl, endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Place the socket acceptor into the state where it will listen for new - /// connections. - ASIO_SYNC_OP_VOID listen(implementation_type& impl, int backlog, - asio::error_code& ec) - { - service_impl_.listen(impl, backlog, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Close a socket acceptor implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Release ownership of the underlying acceptor. - native_handle_type release(implementation_type& impl, - asio::error_code& ec) - { - return service_impl_.release(impl, ec); - } - - /// Get the native acceptor implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Set a socket option. - template - ASIO_SYNC_OP_VOID set_option(implementation_type& impl, - const SettableSocketOption& option, asio::error_code& ec) - { - service_impl_.set_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get a socket option. - template - ASIO_SYNC_OP_VOID get_option(const implementation_type& impl, - GettableSocketOption& option, asio::error_code& ec) const - { - service_impl_.get_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the socket. - template - ASIO_SYNC_OP_VOID io_control(implementation_type& impl, - IoControlCommand& command, asio::error_code& ec) - { - service_impl_.io_control(impl, command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the acceptor. - bool non_blocking(const implementation_type& impl) const - { - return service_impl_.non_blocking(impl); - } - - /// Sets the non-blocking mode of the acceptor. - ASIO_SYNC_OP_VOID non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native acceptor implementation. - bool native_non_blocking(const implementation_type& impl) const - { - return service_impl_.native_non_blocking(impl); - } - - /// Sets the non-blocking mode of the native acceptor implementation. - ASIO_SYNC_OP_VOID native_non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.native_non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.local_endpoint(impl, ec); - } - - /// Wait for the acceptor to become ready to read, ready to write, or to have - /// pending error conditions. - ASIO_SYNC_OP_VOID wait(implementation_type& impl, - socket_base::wait_type w, asio::error_code& ec) - { - service_impl_.wait(impl, w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the acceptor to become ready to read, ready to - /// write, or to have pending error conditions. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, socket_base::wait_type w, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, w, init.completion_handler); - - return init.result.get(); - } - - /// Accept a new connection. - template - ASIO_SYNC_OP_VOID accept(implementation_type& impl, - basic_socket& peer, - endpoint_type* peer_endpoint, asio::error_code& ec, - typename enable_if::value>::type* = 0) - { - service_impl_.accept(impl, peer, peer_endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - -#if defined(ASIO_HAS_MOVE) - /// Accept a new connection. - typename Protocol::socket accept(implementation_type& impl, - io_context* peer_io_context, endpoint_type* peer_endpoint, - asio::error_code& ec) - { - return service_impl_.accept(impl, peer_io_context, peer_endpoint, ec); - } -#endif // defined(ASIO_HAS_MOVE) - - /// Start an asynchronous accept. - template - ASIO_INITFN_RESULT_TYPE(AcceptHandler, - void (asio::error_code)) - async_accept(implementation_type& impl, - basic_socket& peer, - endpoint_type* peer_endpoint, - ASIO_MOVE_ARG(AcceptHandler) handler, - typename enable_if::value>::type* = 0) - { - async_completion init(handler); - - service_impl_.async_accept(impl, - peer, peer_endpoint, init.completion_handler); - - return init.result.get(); - } - -#if defined(ASIO_HAS_MOVE) - /// Start an asynchronous accept. - template - ASIO_INITFN_RESULT_TYPE(MoveAcceptHandler, - void (asio::error_code, typename Protocol::socket)) - async_accept(implementation_type& impl, - asio::io_context* peer_io_context, endpoint_type* peer_endpoint, - ASIO_MOVE_ARG(MoveAcceptHandler) handler) - { - async_completion init(handler); - - service_impl_.async_accept(impl, - peer_io_context, peer_endpoint, init.completion_handler); - - return init.result.get(); - } -#endif // defined(ASIO_HAS_MOVE) - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_SOCKET_ACCEPTOR_SERVICE_HPP diff --git a/scout_sdk/asio/asio/socket_base.hpp b/scout_sdk/asio/asio/socket_base.hpp deleted file mode 100644 index 87ed840..0000000 --- a/scout_sdk/asio/asio/socket_base.hpp +++ /dev/null @@ -1,559 +0,0 @@ -// -// socket_base.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SOCKET_BASE_HPP -#define ASIO_SOCKET_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/io_control.hpp" -#include "asio/detail/socket_option.hpp" -#include "asio/detail/socket_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// The socket_base class is used as a base for the basic_stream_socket and -/// basic_datagram_socket class templates so that we have a common place to -/// define the shutdown_type and enum. -class socket_base -{ -public: - /// Different ways a socket may be shutdown. - enum shutdown_type - { -#if defined(GENERATING_DOCUMENTATION) - /// Shutdown the receive side of the socket. - shutdown_receive = implementation_defined, - - /// Shutdown the send side of the socket. - shutdown_send = implementation_defined, - - /// Shutdown both send and receive on the socket. - shutdown_both = implementation_defined -#else - shutdown_receive = ASIO_OS_DEF(SHUT_RD), - shutdown_send = ASIO_OS_DEF(SHUT_WR), - shutdown_both = ASIO_OS_DEF(SHUT_RDWR) -#endif - }; - - /// Bitmask type for flags that can be passed to send and receive operations. - typedef int message_flags; - -#if defined(GENERATING_DOCUMENTATION) - /// Peek at incoming data without removing it from the input queue. - static const int message_peek = implementation_defined; - - /// Process out-of-band data. - static const int message_out_of_band = implementation_defined; - - /// Specify that the data should not be subject to routing. - static const int message_do_not_route = implementation_defined; - - /// Specifies that the data marks the end of a record. - static const int message_end_of_record = implementation_defined; -#else - ASIO_STATIC_CONSTANT(int, - message_peek = ASIO_OS_DEF(MSG_PEEK)); - ASIO_STATIC_CONSTANT(int, - message_out_of_band = ASIO_OS_DEF(MSG_OOB)); - ASIO_STATIC_CONSTANT(int, - message_do_not_route = ASIO_OS_DEF(MSG_DONTROUTE)); - ASIO_STATIC_CONSTANT(int, - message_end_of_record = ASIO_OS_DEF(MSG_EOR)); -#endif - - /// Wait types. - /** - * For use with basic_socket::wait() and basic_socket::async_wait(). - */ - enum wait_type - { - /// Wait for a socket to become ready to read. - wait_read, - - /// Wait for a socket to become ready to write. - wait_write, - - /// Wait for a socket to have error conditions pending. - wait_error - }; - - /// Socket option to permit sending of broadcast messages. - /** - * Implements the SOL_SOCKET/SO_BROADCAST socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::socket_base::broadcast option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::socket_base::broadcast option; - * socket.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined broadcast; -#else - typedef asio::detail::socket_option::boolean< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_BROADCAST)> - broadcast; -#endif - - /// Socket option to enable socket-level debugging. - /** - * Implements the SOL_SOCKET/SO_DEBUG socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::debug option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::debug option; - * socket.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined debug; -#else - typedef asio::detail::socket_option::boolean< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_DEBUG)> debug; -#endif - - /// Socket option to prevent routing, use local interfaces only. - /** - * Implements the SOL_SOCKET/SO_DONTROUTE socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::socket_base::do_not_route option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::udp::socket socket(io_context); - * ... - * asio::socket_base::do_not_route option; - * socket.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined do_not_route; -#else - typedef asio::detail::socket_option::boolean< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_DONTROUTE)> - do_not_route; -#endif - - /// Socket option to send keep-alives. - /** - * Implements the SOL_SOCKET/SO_KEEPALIVE socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::keep_alive option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::keep_alive option; - * socket.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined keep_alive; -#else - typedef asio::detail::socket_option::boolean< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_KEEPALIVE)> keep_alive; -#endif - - /// Socket option for the send buffer size of a socket. - /** - * Implements the SOL_SOCKET/SO_SNDBUF socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::send_buffer_size option(8192); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::send_buffer_size option; - * socket.get_option(option); - * int size = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Integer_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined send_buffer_size; -#else - typedef asio::detail::socket_option::integer< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_SNDBUF)> - send_buffer_size; -#endif - - /// Socket option for the send low watermark. - /** - * Implements the SOL_SOCKET/SO_SNDLOWAT socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::send_low_watermark option(1024); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::send_low_watermark option; - * socket.get_option(option); - * int size = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Integer_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined send_low_watermark; -#else - typedef asio::detail::socket_option::integer< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_SNDLOWAT)> - send_low_watermark; -#endif - - /// Socket option for the receive buffer size of a socket. - /** - * Implements the SOL_SOCKET/SO_RCVBUF socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::receive_buffer_size option(8192); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::receive_buffer_size option; - * socket.get_option(option); - * int size = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Integer_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined receive_buffer_size; -#else - typedef asio::detail::socket_option::integer< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_RCVBUF)> - receive_buffer_size; -#endif - - /// Socket option for the receive low watermark. - /** - * Implements the SOL_SOCKET/SO_RCVLOWAT socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::receive_low_watermark option(1024); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::receive_low_watermark option; - * socket.get_option(option); - * int size = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Integer_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined receive_low_watermark; -#else - typedef asio::detail::socket_option::integer< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_RCVLOWAT)> - receive_low_watermark; -#endif - - /// Socket option to allow the socket to be bound to an address that is - /// already in use. - /** - * Implements the SOL_SOCKET/SO_REUSEADDR socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::socket_base::reuse_address option(true); - * acceptor.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::socket_base::reuse_address option; - * acceptor.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined reuse_address; -#else - typedef asio::detail::socket_option::boolean< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_REUSEADDR)> - reuse_address; -#endif - - /// Socket option to specify whether the socket lingers on close if unsent - /// data is present. - /** - * Implements the SOL_SOCKET/SO_LINGER socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::linger option(true, 30); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::linger option; - * socket.get_option(option); - * bool is_set = option.enabled(); - * unsigned short timeout = option.timeout(); - * @endcode - * - * @par Concepts: - * Socket_Option, Linger_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined linger; -#else - typedef asio::detail::socket_option::linger< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_LINGER)> - linger; -#endif - - /// Socket option for putting received out-of-band data inline. - /** - * Implements the SOL_SOCKET/SO_OOBINLINE socket option. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::out_of_band_inline option(true); - * socket.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::out_of_band_inline option; - * socket.get_option(option); - * bool value = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined out_of_band_inline; -#else - typedef asio::detail::socket_option::boolean< - ASIO_OS_DEF(SOL_SOCKET), ASIO_OS_DEF(SO_OOBINLINE)> - out_of_band_inline; -#endif - - /// Socket option to report aborted connections on accept. - /** - * Implements a custom socket option that determines whether or not an accept - * operation is permitted to fail with asio::error::connection_aborted. - * By default the option is false. - * - * @par Examples - * Setting the option: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::socket_base::enable_connection_aborted option(true); - * acceptor.set_option(option); - * @endcode - * - * @par - * Getting the current option value: - * @code - * asio::ip::tcp::acceptor acceptor(io_context); - * ... - * asio::socket_base::enable_connection_aborted option; - * acceptor.get_option(option); - * bool is_set = option.value(); - * @endcode - * - * @par Concepts: - * Socket_Option, Boolean_Socket_Option. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined enable_connection_aborted; -#else - typedef asio::detail::socket_option::boolean< - asio::detail::custom_socket_option_level, - asio::detail::enable_connection_aborted_option> - enable_connection_aborted; -#endif - - /// IO control command to get the amount of data that can be read without - /// blocking. - /** - * Implements the FIONREAD IO control command. - * - * @par Example - * @code - * asio::ip::tcp::socket socket(io_context); - * ... - * asio::socket_base::bytes_readable command(true); - * socket.io_control(command); - * std::size_t bytes_readable = command.get(); - * @endcode - * - * @par Concepts: - * IO_Control_Command, Size_IO_Control_Command. - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined bytes_readable; -#else - typedef asio::detail::io_control::bytes_readable bytes_readable; -#endif - - /// The maximum length of the queue of pending incoming connections. -#if defined(GENERATING_DOCUMENTATION) - static const int max_listen_connections = implementation_defined; -#else - ASIO_STATIC_CONSTANT(int, max_listen_connections - = ASIO_OS_DEF(SOMAXCONN)); -#endif - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use max_listen_connections.) The maximum length of the queue - /// of pending incoming connections. -#if defined(GENERATING_DOCUMENTATION) - static const int max_connections = implementation_defined; -#else - ASIO_STATIC_CONSTANT(int, max_connections - = ASIO_OS_DEF(SOMAXCONN)); -#endif -#endif // !defined(ASIO_NO_DEPRECATED) - -protected: - /// Protected destructor to prevent deletion through this type. - ~socket_base() - { - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SOCKET_BASE_HPP diff --git a/scout_sdk/asio/asio/spawn.hpp b/scout_sdk/asio/asio/spawn.hpp deleted file mode 100644 index a91c581..0000000 --- a/scout_sdk/asio/asio/spawn.hpp +++ /dev/null @@ -1,336 +0,0 @@ -// -// spawn.hpp -// ~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SPAWN_HPP -#define ASIO_SPAWN_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/bind_executor.hpp" -#include "asio/detail/memory.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/detail/wrapped_handler.hpp" -#include "asio/executor.hpp" -#include "asio/io_context.hpp" -#include "asio/is_executor.hpp" -#include "asio/strand.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Context object the represents the currently executing coroutine. -/** - * The basic_yield_context class is used to represent the currently executing - * stackful coroutine. A basic_yield_context may be passed as a handler to an - * asynchronous operation. For example: - * - * @code template - * void my_coroutine(basic_yield_context yield) - * { - * ... - * std::size_t n = my_socket.async_read_some(buffer, yield); - * ... - * } @endcode - * - * The initiating function (async_read_some in the above example) suspends the - * current coroutine. The coroutine is resumed when the asynchronous operation - * completes, and the result of the operation is returned. - */ -template -class basic_yield_context -{ -public: - /// The coroutine callee type, used by the implementation. - /** - * When using Boost.Coroutine v1, this type is: - * @code typename coroutine @endcode - * When using Boost.Coroutine v2 (unidirectional coroutines), this type is: - * @code push_coroutine @endcode - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined callee_type; -#elif defined(BOOST_COROUTINES_UNIDIRECT) || defined(BOOST_COROUTINES_V2) - typedef boost::coroutines::push_coroutine callee_type; -#else - typedef boost::coroutines::coroutine callee_type; -#endif - - /// The coroutine caller type, used by the implementation. - /** - * When using Boost.Coroutine v1, this type is: - * @code typename coroutine::caller_type @endcode - * When using Boost.Coroutine v2 (unidirectional coroutines), this type is: - * @code pull_coroutine @endcode - */ -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined caller_type; -#elif defined(BOOST_COROUTINES_UNIDIRECT) || defined(BOOST_COROUTINES_V2) - typedef boost::coroutines::pull_coroutine caller_type; -#else - typedef boost::coroutines::coroutine::caller_type caller_type; -#endif - - /// Construct a yield context to represent the specified coroutine. - /** - * Most applications do not need to use this constructor. Instead, the - * spawn() function passes a yield context as an argument to the coroutine - * function. - */ - basic_yield_context( - const detail::weak_ptr& coro, - caller_type& ca, Handler& handler) - : coro_(coro), - ca_(ca), - handler_(handler), - ec_(0) - { - } - - /// Construct a yield context from another yield context type. - /** - * Requires that OtherHandler be convertible to Handler. - */ - template - basic_yield_context(const basic_yield_context& other) - : coro_(other.coro_), - ca_(other.ca_), - handler_(other.handler_), - ec_(other.ec_) - { - } - - /// Return a yield context that sets the specified error_code. - /** - * By default, when a yield context is used with an asynchronous operation, a - * non-success error_code is converted to system_error and thrown. This - * operator may be used to specify an error_code object that should instead be - * set with the asynchronous operation's result. For example: - * - * @code template - * void my_coroutine(basic_yield_context yield) - * { - * ... - * std::size_t n = my_socket.async_read_some(buffer, yield[ec]); - * if (ec) - * { - * // An error occurred. - * } - * ... - * } @endcode - */ - basic_yield_context operator[](asio::error_code& ec) const - { - basic_yield_context tmp(*this); - tmp.ec_ = &ec; - return tmp; - } - -#if defined(GENERATING_DOCUMENTATION) -private: -#endif // defined(GENERATING_DOCUMENTATION) - detail::weak_ptr coro_; - caller_type& ca_; - Handler handler_; - asio::error_code* ec_; -}; - -#if defined(GENERATING_DOCUMENTATION) -/// Context object that represents the currently executing coroutine. -typedef basic_yield_context yield_context; -#else // defined(GENERATING_DOCUMENTATION) -typedef basic_yield_context< - executor_binder > yield_context; -#endif // defined(GENERATING_DOCUMENTATION) - -/** - * @defgroup spawn asio::spawn - * - * @brief Start a new stackful coroutine. - * - * The spawn() function is a high-level wrapper over the Boost.Coroutine - * library. This function enables programs to implement asynchronous logic in a - * synchronous manner, as illustrated by the following example: - * - * @code asio::spawn(my_strand, do_echo); - * - * // ... - * - * void do_echo(asio::yield_context yield) - * { - * try - * { - * char data[128]; - * for (;;) - * { - * std::size_t length = - * my_socket.async_read_some( - * asio::buffer(data), yield); - * - * asio::async_write(my_socket, - * asio::buffer(data, length), yield); - * } - * } - * catch (std::exception& e) - * { - * // ... - * } - * } @endcode - */ -/*@{*/ - -/// Start a new stackful coroutine, calling the specified handler when it -/// completes. -/** - * This function is used to launch a new coroutine. - * - * @param function The coroutine function. The function must have the signature: - * @code void function(basic_yield_context yield); @endcode - * - * @param attributes Boost.Coroutine attributes used to customise the coroutine. - */ -template -void spawn(ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes - = boost::coroutines::attributes()); - -/// Start a new stackful coroutine, calling the specified handler when it -/// completes. -/** - * This function is used to launch a new coroutine. - * - * @param handler A handler to be called when the coroutine exits. More - * importantly, the handler provides an execution context (via the the handler - * invocation hook) for the coroutine. The handler must have the signature: - * @code void handler(); @endcode - * - * @param function The coroutine function. The function must have the signature: - * @code void function(basic_yield_context yield); @endcode - * - * @param attributes Boost.Coroutine attributes used to customise the coroutine. - */ -template -void spawn(ASIO_MOVE_ARG(Handler) handler, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes - = boost::coroutines::attributes(), - typename enable_if::type>::value && - !is_convertible::value>::type* = 0); - -/// Start a new stackful coroutine, inheriting the execution context of another. -/** - * This function is used to launch a new coroutine. - * - * @param ctx Identifies the current coroutine as a parent of the new - * coroutine. This specifies that the new coroutine should inherit the - * execution context of the parent. For example, if the parent coroutine is - * executing in a particular strand, then the new coroutine will execute in the - * same strand. - * - * @param function The coroutine function. The function must have the signature: - * @code void function(basic_yield_context yield); @endcode - * - * @param attributes Boost.Coroutine attributes used to customise the coroutine. - */ -template -void spawn(basic_yield_context ctx, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes - = boost::coroutines::attributes()); - -/// Start a new stackful coroutine that executes on a given executor. -/** - * This function is used to launch a new coroutine. - * - * @param ex Identifies the executor that will run the coroutine. The new - * coroutine is implicitly given its own strand within this executor. - * - * @param function The coroutine function. The function must have the signature: - * @code void function(yield_context yield); @endcode - * - * @param attributes Boost.Coroutine attributes used to customise the coroutine. - */ -template -void spawn(const Executor& ex, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes - = boost::coroutines::attributes(), - typename enable_if::value>::type* = 0); - -/// Start a new stackful coroutine that executes on a given strand. -/** - * This function is used to launch a new coroutine. - * - * @param ex Identifies the strand that will run the coroutine. - * - * @param function The coroutine function. The function must have the signature: - * @code void function(yield_context yield); @endcode - * - * @param attributes Boost.Coroutine attributes used to customise the coroutine. - */ -template -void spawn(const strand& ex, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes - = boost::coroutines::attributes()); - -/// Start a new stackful coroutine that executes in the context of a strand. -/** - * This function is used to launch a new coroutine. - * - * @param s Identifies a strand. By starting multiple coroutines on the same - * strand, the implementation ensures that none of those coroutines can execute - * simultaneously. - * - * @param function The coroutine function. The function must have the signature: - * @code void function(yield_context yield); @endcode - * - * @param attributes Boost.Coroutine attributes used to customise the coroutine. - */ -template -void spawn(const asio::io_context::strand& s, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes - = boost::coroutines::attributes()); - -/// Start a new stackful coroutine that executes on a given execution context. -/** - * This function is used to launch a new coroutine. - * - * @param ctx Identifies the execution context that will run the coroutine. The - * new coroutine is implicitly given its own strand within this execution - * context. - * - * @param function The coroutine function. The function must have the signature: - * @code void function(yield_context yield); @endcode - * - * @param attributes Boost.Coroutine attributes used to customise the coroutine. - */ -template -void spawn(ExecutionContext& ctx, - ASIO_MOVE_ARG(Function) function, - const boost::coroutines::attributes& attributes - = boost::coroutines::attributes(), - typename enable_if::value>::type* = 0); - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/spawn.hpp" - -#endif // ASIO_SPAWN_HPP diff --git a/scout_sdk/asio/asio/ssl.hpp b/scout_sdk/asio/asio/ssl.hpp deleted file mode 100644 index cbad19d..0000000 --- a/scout_sdk/asio/asio/ssl.hpp +++ /dev/null @@ -1,27 +0,0 @@ -// -// ssl.hpp -// ~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_HPP -#define ASIO_SSL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/ssl/context.hpp" -#include "asio/ssl/context_base.hpp" -#include "asio/ssl/error.hpp" -#include "asio/ssl/rfc2818_verification.hpp" -#include "asio/ssl/stream.hpp" -#include "asio/ssl/stream_base.hpp" -#include "asio/ssl/verify_context.hpp" -#include "asio/ssl/verify_mode.hpp" - -#endif // ASIO_SSL_HPP diff --git a/scout_sdk/asio/asio/ssl/context.hpp b/scout_sdk/asio/asio/ssl/context.hpp deleted file mode 100644 index 9543aab..0000000 --- a/scout_sdk/asio/asio/ssl/context.hpp +++ /dev/null @@ -1,758 +0,0 @@ -// -// ssl/context.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_CONTEXT_HPP -#define ASIO_SSL_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/buffer.hpp" -#include "asio/io_context.hpp" -#include "asio/ssl/context_base.hpp" -#include "asio/ssl/detail/openssl_types.hpp" -#include "asio/ssl/detail/openssl_init.hpp" -#include "asio/ssl/detail/password_callback.hpp" -#include "asio/ssl/detail/verify_callback.hpp" -#include "asio/ssl/verify_mode.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -class context - : public context_base, - private noncopyable -{ -public: - /// The native handle type of the SSL context. - typedef SSL_CTX* native_handle_type; - - /// Constructor. - ASIO_DECL explicit context(method m); - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a context from another. - /** - * This constructor moves an SSL context from one object to another. - * - * @param other The other context object from which the move will occur. - * - * @note Following the move, the following operations only are valid for the - * moved-from object: - * @li Destruction. - * @li As a target for move-assignment. - */ - ASIO_DECL context(context&& other); - - /// Move-assign a context from another. - /** - * This assignment operator moves an SSL context from one object to another. - * - * @param other The other context object from which the move will occur. - * - * @note Following the move, the following operations only are valid for the - * moved-from object: - * @li Destruction. - * @li As a target for move-assignment. - */ - ASIO_DECL context& operator=(context&& other); -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destructor. - ASIO_DECL ~context(); - - /// Get the underlying implementation in the native type. - /** - * This function may be used to obtain the underlying implementation of the - * context. This is intended to allow access to context functionality that is - * not otherwise provided. - */ - ASIO_DECL native_handle_type native_handle(); - - /// Clear options on the context. - /** - * This function may be used to configure the SSL options used by the context. - * - * @param o A bitmask of options. The available option values are defined in - * the context_base class. The specified options, if currently enabled on the - * context, are cleared. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_clear_options. - */ - ASIO_DECL void clear_options(options o); - - /// Clear options on the context. - /** - * This function may be used to configure the SSL options used by the context. - * - * @param o A bitmask of options. The available option values are defined in - * the context_base class. The specified options, if currently enabled on the - * context, are cleared. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_clear_options. - */ - ASIO_DECL ASIO_SYNC_OP_VOID clear_options(options o, - asio::error_code& ec); - - /// Set options on the context. - /** - * This function may be used to configure the SSL options used by the context. - * - * @param o A bitmask of options. The available option values are defined in - * the context_base class. The options are bitwise-ored with any existing - * value for the options. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_options. - */ - ASIO_DECL void set_options(options o); - - /// Set options on the context. - /** - * This function may be used to configure the SSL options used by the context. - * - * @param o A bitmask of options. The available option values are defined in - * the context_base class. The options are bitwise-ored with any existing - * value for the options. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_options. - */ - ASIO_DECL ASIO_SYNC_OP_VOID set_options(options o, - asio::error_code& ec); - - /// Set the peer verification mode. - /** - * This function may be used to configure the peer verification mode used by - * the context. - * - * @param v A bitmask of peer verification modes. See @ref verify_mode for - * available values. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_verify. - */ - ASIO_DECL void set_verify_mode(verify_mode v); - - /// Set the peer verification mode. - /** - * This function may be used to configure the peer verification mode used by - * the context. - * - * @param v A bitmask of peer verification modes. See @ref verify_mode for - * available values. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_verify. - */ - ASIO_DECL ASIO_SYNC_OP_VOID set_verify_mode( - verify_mode v, asio::error_code& ec); - - /// Set the peer verification depth. - /** - * This function may be used to configure the maximum verification depth - * allowed by the context. - * - * @param depth Maximum depth for the certificate chain verification that - * shall be allowed. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_verify_depth. - */ - ASIO_DECL void set_verify_depth(int depth); - - /// Set the peer verification depth. - /** - * This function may be used to configure the maximum verification depth - * allowed by the context. - * - * @param depth Maximum depth for the certificate chain verification that - * shall be allowed. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_verify_depth. - */ - ASIO_DECL ASIO_SYNC_OP_VOID set_verify_depth( - int depth, asio::error_code& ec); - - /// Set the callback used to verify peer certificates. - /** - * This function is used to specify a callback function that will be called - * by the implementation when it needs to verify a peer certificate. - * - * @param callback The function object to be used for verifying a certificate. - * The function signature of the handler must be: - * @code bool verify_callback( - * bool preverified, // True if the certificate passed pre-verification. - * verify_context& ctx // The peer certificate and other context. - * ); @endcode - * The return value of the callback is true if the certificate has passed - * verification, false otherwise. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_verify. - */ - template - void set_verify_callback(VerifyCallback callback); - - /// Set the callback used to verify peer certificates. - /** - * This function is used to specify a callback function that will be called - * by the implementation when it needs to verify a peer certificate. - * - * @param callback The function object to be used for verifying a certificate. - * The function signature of the handler must be: - * @code bool verify_callback( - * bool preverified, // True if the certificate passed pre-verification. - * verify_context& ctx // The peer certificate and other context. - * ); @endcode - * The return value of the callback is true if the certificate has passed - * verification, false otherwise. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_verify. - */ - template - ASIO_SYNC_OP_VOID set_verify_callback(VerifyCallback callback, - asio::error_code& ec); - - /// Load a certification authority file for performing verification. - /** - * This function is used to load one or more trusted certification authorities - * from a file. - * - * @param filename The name of a file containing certification authority - * certificates in PEM format. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_load_verify_locations. - */ - ASIO_DECL void load_verify_file(const std::string& filename); - - /// Load a certification authority file for performing verification. - /** - * This function is used to load the certificates for one or more trusted - * certification authorities from a file. - * - * @param filename The name of a file containing certification authority - * certificates in PEM format. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_load_verify_locations. - */ - ASIO_DECL ASIO_SYNC_OP_VOID load_verify_file( - const std::string& filename, asio::error_code& ec); - - /// Add certification authority for performing verification. - /** - * This function is used to add one trusted certification authority - * from a memory buffer. - * - * @param ca The buffer containing the certification authority certificate. - * The certificate must use the PEM format. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_get_cert_store and @c X509_STORE_add_cert. - */ - ASIO_DECL void add_certificate_authority(const const_buffer& ca); - - /// Add certification authority for performing verification. - /** - * This function is used to add one trusted certification authority - * from a memory buffer. - * - * @param ca The buffer containing the certification authority certificate. - * The certificate must use the PEM format. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_get_cert_store and @c X509_STORE_add_cert. - */ - ASIO_DECL ASIO_SYNC_OP_VOID add_certificate_authority( - const const_buffer& ca, asio::error_code& ec); - - /// Configures the context to use the default directories for finding - /// certification authority certificates. - /** - * This function specifies that the context should use the default, - * system-dependent directories for locating certification authority - * certificates. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_default_verify_paths. - */ - ASIO_DECL void set_default_verify_paths(); - - /// Configures the context to use the default directories for finding - /// certification authority certificates. - /** - * This function specifies that the context should use the default, - * system-dependent directories for locating certification authority - * certificates. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_default_verify_paths. - */ - ASIO_DECL ASIO_SYNC_OP_VOID set_default_verify_paths( - asio::error_code& ec); - - /// Add a directory containing certificate authority files to be used for - /// performing verification. - /** - * This function is used to specify the name of a directory containing - * certification authority certificates. Each file in the directory must - * contain a single certificate. The files must be named using the subject - * name's hash and an extension of ".0". - * - * @param path The name of a directory containing the certificates. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_load_verify_locations. - */ - ASIO_DECL void add_verify_path(const std::string& path); - - /// Add a directory containing certificate authority files to be used for - /// performing verification. - /** - * This function is used to specify the name of a directory containing - * certification authority certificates. Each file in the directory must - * contain a single certificate. The files must be named using the subject - * name's hash and an extension of ".0". - * - * @param path The name of a directory containing the certificates. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_load_verify_locations. - */ - ASIO_DECL ASIO_SYNC_OP_VOID add_verify_path( - const std::string& path, asio::error_code& ec); - - /// Use a certificate from a memory buffer. - /** - * This function is used to load a certificate into the context from a buffer. - * - * @param certificate The buffer containing the certificate. - * - * @param format The certificate format (ASN.1 or PEM). - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_certificate or SSL_CTX_use_certificate_ASN1. - */ - ASIO_DECL void use_certificate( - const const_buffer& certificate, file_format format); - - /// Use a certificate from a memory buffer. - /** - * This function is used to load a certificate into the context from a buffer. - * - * @param certificate The buffer containing the certificate. - * - * @param format The certificate format (ASN.1 or PEM). - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_certificate or SSL_CTX_use_certificate_ASN1. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_certificate( - const const_buffer& certificate, file_format format, - asio::error_code& ec); - - /// Use a certificate from a file. - /** - * This function is used to load a certificate into the context from a file. - * - * @param filename The name of the file containing the certificate. - * - * @param format The file format (ASN.1 or PEM). - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_certificate_file. - */ - ASIO_DECL void use_certificate_file( - const std::string& filename, file_format format); - - /// Use a certificate from a file. - /** - * This function is used to load a certificate into the context from a file. - * - * @param filename The name of the file containing the certificate. - * - * @param format The file format (ASN.1 or PEM). - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_certificate_file. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_certificate_file( - const std::string& filename, file_format format, - asio::error_code& ec); - - /// Use a certificate chain from a memory buffer. - /** - * This function is used to load a certificate chain into the context from a - * buffer. - * - * @param chain The buffer containing the certificate chain. The certificate - * chain must use the PEM format. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_certificate and SSL_CTX_add_extra_chain_cert. - */ - ASIO_DECL void use_certificate_chain(const const_buffer& chain); - - /// Use a certificate chain from a memory buffer. - /** - * This function is used to load a certificate chain into the context from a - * buffer. - * - * @param chain The buffer containing the certificate chain. The certificate - * chain must use the PEM format. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_certificate and SSL_CTX_add_extra_chain_cert. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_certificate_chain( - const const_buffer& chain, asio::error_code& ec); - - /// Use a certificate chain from a file. - /** - * This function is used to load a certificate chain into the context from a - * file. - * - * @param filename The name of the file containing the certificate. The file - * must use the PEM format. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_certificate_chain_file. - */ - ASIO_DECL void use_certificate_chain_file(const std::string& filename); - - /// Use a certificate chain from a file. - /** - * This function is used to load a certificate chain into the context from a - * file. - * - * @param filename The name of the file containing the certificate. The file - * must use the PEM format. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_certificate_chain_file. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_certificate_chain_file( - const std::string& filename, asio::error_code& ec); - - /// Use a private key from a memory buffer. - /** - * This function is used to load a private key into the context from a buffer. - * - * @param private_key The buffer containing the private key. - * - * @param format The private key format (ASN.1 or PEM). - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_PrivateKey or SSL_CTX_use_PrivateKey_ASN1. - */ - ASIO_DECL void use_private_key( - const const_buffer& private_key, file_format format); - - /// Use a private key from a memory buffer. - /** - * This function is used to load a private key into the context from a buffer. - * - * @param private_key The buffer containing the private key. - * - * @param format The private key format (ASN.1 or PEM). - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_PrivateKey or SSL_CTX_use_PrivateKey_ASN1. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_private_key( - const const_buffer& private_key, file_format format, - asio::error_code& ec); - - /// Use a private key from a file. - /** - * This function is used to load a private key into the context from a file. - * - * @param filename The name of the file containing the private key. - * - * @param format The file format (ASN.1 or PEM). - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_PrivateKey_file. - */ - ASIO_DECL void use_private_key_file( - const std::string& filename, file_format format); - - /// Use a private key from a file. - /** - * This function is used to load a private key into the context from a file. - * - * @param filename The name of the file containing the private key. - * - * @param format The file format (ASN.1 or PEM). - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_PrivateKey_file. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_private_key_file( - const std::string& filename, file_format format, - asio::error_code& ec); - - /// Use an RSA private key from a memory buffer. - /** - * This function is used to load an RSA private key into the context from a - * buffer. - * - * @param private_key The buffer containing the RSA private key. - * - * @param format The private key format (ASN.1 or PEM). - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_RSAPrivateKey or SSL_CTX_use_RSAPrivateKey_ASN1. - */ - ASIO_DECL void use_rsa_private_key( - const const_buffer& private_key, file_format format); - - /// Use an RSA private key from a memory buffer. - /** - * This function is used to load an RSA private key into the context from a - * buffer. - * - * @param private_key The buffer containing the RSA private key. - * - * @param format The private key format (ASN.1 or PEM). - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_RSAPrivateKey or SSL_CTX_use_RSAPrivateKey_ASN1. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_rsa_private_key( - const const_buffer& private_key, file_format format, - asio::error_code& ec); - - /// Use an RSA private key from a file. - /** - * This function is used to load an RSA private key into the context from a - * file. - * - * @param filename The name of the file containing the RSA private key. - * - * @param format The file format (ASN.1 or PEM). - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_use_RSAPrivateKey_file. - */ - ASIO_DECL void use_rsa_private_key_file( - const std::string& filename, file_format format); - - /// Use an RSA private key from a file. - /** - * This function is used to load an RSA private key into the context from a - * file. - * - * @param filename The name of the file containing the RSA private key. - * - * @param format The file format (ASN.1 or PEM). - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_use_RSAPrivateKey_file. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_rsa_private_key_file( - const std::string& filename, file_format format, - asio::error_code& ec); - - /// Use the specified memory buffer to obtain the temporary Diffie-Hellman - /// parameters. - /** - * This function is used to load Diffie-Hellman parameters into the context - * from a buffer. - * - * @param dh The memory buffer containing the Diffie-Hellman parameters. The - * buffer must use the PEM format. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_tmp_dh. - */ - ASIO_DECL void use_tmp_dh(const const_buffer& dh); - - /// Use the specified memory buffer to obtain the temporary Diffie-Hellman - /// parameters. - /** - * This function is used to load Diffie-Hellman parameters into the context - * from a buffer. - * - * @param dh The memory buffer containing the Diffie-Hellman parameters. The - * buffer must use the PEM format. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_tmp_dh. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_tmp_dh( - const const_buffer& dh, asio::error_code& ec); - - /// Use the specified file to obtain the temporary Diffie-Hellman parameters. - /** - * This function is used to load Diffie-Hellman parameters into the context - * from a file. - * - * @param filename The name of the file containing the Diffie-Hellman - * parameters. The file must use the PEM format. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_tmp_dh. - */ - ASIO_DECL void use_tmp_dh_file(const std::string& filename); - - /// Use the specified file to obtain the temporary Diffie-Hellman parameters. - /** - * This function is used to load Diffie-Hellman parameters into the context - * from a file. - * - * @param filename The name of the file containing the Diffie-Hellman - * parameters. The file must use the PEM format. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_tmp_dh. - */ - ASIO_DECL ASIO_SYNC_OP_VOID use_tmp_dh_file( - const std::string& filename, asio::error_code& ec); - - /// Set the password callback. - /** - * This function is used to specify a callback function to obtain password - * information about an encrypted key in PEM format. - * - * @param callback The function object to be used for obtaining the password. - * The function signature of the handler must be: - * @code std::string password_callback( - * std::size_t max_length, // The maximum size for a password. - * password_purpose purpose // Whether password is for reading or writing. - * ); @endcode - * The return value of the callback is a string containing the password. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_CTX_set_default_passwd_cb. - */ - template - void set_password_callback(PasswordCallback callback); - - /// Set the password callback. - /** - * This function is used to specify a callback function to obtain password - * information about an encrypted key in PEM format. - * - * @param callback The function object to be used for obtaining the password. - * The function signature of the handler must be: - * @code std::string password_callback( - * std::size_t max_length, // The maximum size for a password. - * password_purpose purpose // Whether password is for reading or writing. - * ); @endcode - * The return value of the callback is a string containing the password. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_CTX_set_default_passwd_cb. - */ - template - ASIO_SYNC_OP_VOID set_password_callback(PasswordCallback callback, - asio::error_code& ec); - -private: - struct bio_cleanup; - struct x509_cleanup; - struct evp_pkey_cleanup; - struct rsa_cleanup; - struct dh_cleanup; - - // Helper function used to set a peer certificate verification callback. - ASIO_DECL ASIO_SYNC_OP_VOID do_set_verify_callback( - detail::verify_callback_base* callback, asio::error_code& ec); - - // Callback used when the SSL implementation wants to verify a certificate. - ASIO_DECL static int verify_callback_function( - int preverified, X509_STORE_CTX* ctx); - - // Helper function used to set a password callback. - ASIO_DECL ASIO_SYNC_OP_VOID do_set_password_callback( - detail::password_callback_base* callback, asio::error_code& ec); - - // Callback used when the SSL implementation wants a password. - ASIO_DECL static int password_callback_function( - char* buf, int size, int purpose, void* data); - - // Helper function to set the temporary Diffie-Hellman parameters from a BIO. - ASIO_DECL ASIO_SYNC_OP_VOID do_use_tmp_dh( - BIO* bio, asio::error_code& ec); - - // Helper function to make a BIO from a memory buffer. - ASIO_DECL BIO* make_buffer_bio(const const_buffer& b); - - // The underlying native implementation. - native_handle_type handle_; - - // Ensure openssl is initialised. - asio::ssl::detail::openssl_init<> init_; -}; - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/ssl/impl/context.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/ssl/impl/context.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_SSL_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/ssl/context_base.hpp b/scout_sdk/asio/asio/ssl/context_base.hpp deleted file mode 100644 index 56c7693..0000000 --- a/scout_sdk/asio/asio/ssl/context_base.hpp +++ /dev/null @@ -1,192 +0,0 @@ -// -// ssl/context_base.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_CONTEXT_BASE_HPP -#define ASIO_SSL_CONTEXT_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ssl/detail/openssl_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -/// The context_base class is used as a base for the basic_context class -/// template so that we have a common place to define various enums. -class context_base -{ -public: - /// Different methods supported by a context. - enum method - { - /// Generic SSL version 2. - sslv2, - - /// SSL version 2 client. - sslv2_client, - - /// SSL version 2 server. - sslv2_server, - - /// Generic SSL version 3. - sslv3, - - /// SSL version 3 client. - sslv3_client, - - /// SSL version 3 server. - sslv3_server, - - /// Generic TLS version 1. - tlsv1, - - /// TLS version 1 client. - tlsv1_client, - - /// TLS version 1 server. - tlsv1_server, - - /// Generic SSL/TLS. - sslv23, - - /// SSL/TLS client. - sslv23_client, - - /// SSL/TLS server. - sslv23_server, - - /// Generic TLS version 1.1. - tlsv11, - - /// TLS version 1.1 client. - tlsv11_client, - - /// TLS version 1.1 server. - tlsv11_server, - - /// Generic TLS version 1.2. - tlsv12, - - /// TLS version 1.2 client. - tlsv12_client, - - /// TLS version 1.2 server. - tlsv12_server, - - /// Generic TLS. - tls, - - /// TLS client. - tls_client, - - /// TLS server. - tls_server - }; - - /// Bitmask type for SSL options. - typedef long options; - -#if defined(GENERATING_DOCUMENTATION) - /// Implement various bug workarounds. - static const long default_workarounds = implementation_defined; - - /// Always create a new key when using tmp_dh parameters. - static const long single_dh_use = implementation_defined; - - /// Disable SSL v2. - static const long no_sslv2 = implementation_defined; - - /// Disable SSL v3. - static const long no_sslv3 = implementation_defined; - - /// Disable TLS v1. - static const long no_tlsv1 = implementation_defined; - - /// Disable TLS v1.1. - static const long no_tlsv1_1 = implementation_defined; - - /// Disable TLS v1.2. - static const long no_tlsv1_2 = implementation_defined; - - /// Disable compression. Compression is disabled by default. - static const long no_compression = implementation_defined; -#else - ASIO_STATIC_CONSTANT(long, default_workarounds = SSL_OP_ALL); - ASIO_STATIC_CONSTANT(long, single_dh_use = SSL_OP_SINGLE_DH_USE); - ASIO_STATIC_CONSTANT(long, no_sslv2 = SSL_OP_NO_SSLv2); - ASIO_STATIC_CONSTANT(long, no_sslv3 = SSL_OP_NO_SSLv3); - ASIO_STATIC_CONSTANT(long, no_tlsv1 = SSL_OP_NO_TLSv1); -# if defined(SSL_OP_NO_TLSv1_1) - ASIO_STATIC_CONSTANT(long, no_tlsv1_1 = SSL_OP_NO_TLSv1_1); -# else // defined(SSL_OP_NO_TLSv1_1) - ASIO_STATIC_CONSTANT(long, no_tlsv1_1 = 0x10000000L); -# endif // defined(SSL_OP_NO_TLSv1_1) -# if defined(SSL_OP_NO_TLSv1_2) - ASIO_STATIC_CONSTANT(long, no_tlsv1_2 = SSL_OP_NO_TLSv1_2); -# else // defined(SSL_OP_NO_TLSv1_2) - ASIO_STATIC_CONSTANT(long, no_tlsv1_2 = 0x08000000L); -# endif // defined(SSL_OP_NO_TLSv1_2) -# if defined(SSL_OP_NO_COMPRESSION) - ASIO_STATIC_CONSTANT(long, no_compression = SSL_OP_NO_COMPRESSION); -# else // defined(SSL_OP_NO_COMPRESSION) - ASIO_STATIC_CONSTANT(long, no_compression = 0x20000L); -# endif // defined(SSL_OP_NO_COMPRESSION) -#endif - - /// File format types. - enum file_format - { - /// ASN.1 file. - asn1, - - /// PEM file. - pem - }; - -#if !defined(GENERATING_DOCUMENTATION) - // The following types and constants are preserved for backward compatibility. - // New programs should use the equivalents of the same names that are defined - // in the asio::ssl namespace. - typedef int verify_mode; - ASIO_STATIC_CONSTANT(int, verify_none = SSL_VERIFY_NONE); - ASIO_STATIC_CONSTANT(int, verify_peer = SSL_VERIFY_PEER); - ASIO_STATIC_CONSTANT(int, - verify_fail_if_no_peer_cert = SSL_VERIFY_FAIL_IF_NO_PEER_CERT); - ASIO_STATIC_CONSTANT(int, verify_client_once = SSL_VERIFY_CLIENT_ONCE); -#endif - - /// Purpose of PEM password. - enum password_purpose - { - /// The password is needed for reading/decryption. - for_reading, - - /// The password is needed for writing/encryption. - for_writing - }; - -protected: - /// Protected destructor to prevent deletion through this type. - ~context_base() - { - } -}; - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_CONTEXT_BASE_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/buffered_handshake_op.hpp b/scout_sdk/asio/asio/ssl/detail/buffered_handshake_op.hpp deleted file mode 100644 index 38a03fc..0000000 --- a/scout_sdk/asio/asio/ssl/detail/buffered_handshake_op.hpp +++ /dev/null @@ -1,114 +0,0 @@ -// -// ssl/detail/buffered_handshake_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_BUFFERED_HANDSHAKE_OP_HPP -#define ASIO_SSL_DETAIL_BUFFERED_HANDSHAKE_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/ssl/detail/engine.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -template -class buffered_handshake_op -{ -public: - buffered_handshake_op(stream_base::handshake_type type, - const ConstBufferSequence& buffers) - : type_(type), - buffers_(buffers), - total_buffer_size_(asio::buffer_size(buffers_)) - { - } - - engine::want operator()(engine& eng, - asio::error_code& ec, - std::size_t& bytes_transferred) const - { - return this->process(eng, ec, bytes_transferred, - asio::buffer_sequence_begin(buffers_), - asio::buffer_sequence_end(buffers_)); - } - - template - void call_handler(Handler& handler, - const asio::error_code& ec, - const std::size_t& bytes_transferred) const - { - handler(ec, bytes_transferred); - } - -private: - template - engine::want process(engine& eng, - asio::error_code& ec, - std::size_t& bytes_transferred, - Iterator begin, Iterator end) const - { - Iterator iter = begin; - std::size_t accumulated_size = 0; - - for (;;) - { - engine::want want = eng.handshake(type_, ec); - if (want != engine::want_input_and_retry - || bytes_transferred == total_buffer_size_) - return want; - - // Find the next buffer piece to be fed to the engine. - while (iter != end) - { - const_buffer buffer(*iter); - - // Skip over any buffers which have already been consumed by the engine. - if (bytes_transferred >= accumulated_size + buffer.size()) - { - accumulated_size += buffer.size(); - ++iter; - continue; - } - - // The current buffer may have been partially consumed by the engine on - // a previous iteration. If so, adjust the buffer to point to the - // unused portion. - if (bytes_transferred > accumulated_size) - buffer = buffer + (bytes_transferred - accumulated_size); - - // Pass the buffer to the engine, and update the bytes transferred to - // reflect the total number of bytes consumed so far. - bytes_transferred += buffer.size(); - buffer = eng.put_input(buffer); - bytes_transferred -= buffer.size(); - break; - } - } - } - - stream_base::handshake_type type_; - ConstBufferSequence buffers_; - std::size_t total_buffer_size_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_BUFFERED_HANDSHAKE_OP_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/engine.hpp b/scout_sdk/asio/asio/ssl/detail/engine.hpp deleted file mode 100644 index 2f033d6..0000000 --- a/scout_sdk/asio/asio/ssl/detail/engine.hpp +++ /dev/null @@ -1,160 +0,0 @@ -// -// ssl/detail/engine.hpp -// ~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_ENGINE_HPP -#define ASIO_SSL_DETAIL_ENGINE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/buffer.hpp" -#include "asio/detail/static_mutex.hpp" -#include "asio/ssl/detail/openssl_types.hpp" -#include "asio/ssl/detail/verify_callback.hpp" -#include "asio/ssl/stream_base.hpp" -#include "asio/ssl/verify_mode.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -class engine -{ -public: - enum want - { - // Returned by functions to indicate that the engine wants input. The input - // buffer should be updated to point to the data. The engine then needs to - // be called again to retry the operation. - want_input_and_retry = -2, - - // Returned by functions to indicate that the engine wants to write output. - // The output buffer points to the data to be written. The engine then - // needs to be called again to retry the operation. - want_output_and_retry = -1, - - // Returned by functions to indicate that the engine doesn't need input or - // output. - want_nothing = 0, - - // Returned by functions to indicate that the engine wants to write output. - // The output buffer points to the data to be written. After that the - // operation is complete, and the engine does not need to be called again. - want_output = 1 - }; - - // Construct a new engine for the specified context. - ASIO_DECL explicit engine(SSL_CTX* context); - - // Destructor. - ASIO_DECL ~engine(); - - // Get the underlying implementation in the native type. - ASIO_DECL SSL* native_handle(); - - // Set the peer verification mode. - ASIO_DECL asio::error_code set_verify_mode( - verify_mode v, asio::error_code& ec); - - // Set the peer verification depth. - ASIO_DECL asio::error_code set_verify_depth( - int depth, asio::error_code& ec); - - // Set a peer certificate verification callback. - ASIO_DECL asio::error_code set_verify_callback( - verify_callback_base* callback, asio::error_code& ec); - - // Perform an SSL handshake using either SSL_connect (client-side) or - // SSL_accept (server-side). - ASIO_DECL want handshake( - stream_base::handshake_type type, asio::error_code& ec); - - // Perform a graceful shutdown of the SSL session. - ASIO_DECL want shutdown(asio::error_code& ec); - - // Write bytes to the SSL session. - ASIO_DECL want write(const asio::const_buffer& data, - asio::error_code& ec, std::size_t& bytes_transferred); - - // Read bytes from the SSL session. - ASIO_DECL want read(const asio::mutable_buffer& data, - asio::error_code& ec, std::size_t& bytes_transferred); - - // Get output data to be written to the transport. - ASIO_DECL asio::mutable_buffer get_output( - const asio::mutable_buffer& data); - - // Put input data that was read from the transport. - ASIO_DECL asio::const_buffer put_input( - const asio::const_buffer& data); - - // Map an error::eof code returned by the underlying transport according to - // the type and state of the SSL session. Returns a const reference to the - // error code object, suitable for passing to a completion handler. - ASIO_DECL const asio::error_code& map_error_code( - asio::error_code& ec) const; - -private: - // Disallow copying and assignment. - engine(const engine&); - engine& operator=(const engine&); - - // Callback used when the SSL implementation wants to verify a certificate. - ASIO_DECL static int verify_callback_function( - int preverified, X509_STORE_CTX* ctx); - -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) - // The SSL_accept function may not be thread safe. This mutex is used to - // protect all calls to the SSL_accept function. - ASIO_DECL static asio::detail::static_mutex& accept_mutex(); -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) - - // Perform one operation. Returns >= 0 on success or error, want_read if the - // operation needs more input, or want_write if it needs to write some output - // before the operation can complete. - ASIO_DECL want perform(int (engine::* op)(void*, std::size_t), - void* data, std::size_t length, asio::error_code& ec, - std::size_t* bytes_transferred); - - // Adapt the SSL_accept function to the signature needed for perform(). - ASIO_DECL int do_accept(void*, std::size_t); - - // Adapt the SSL_connect function to the signature needed for perform(). - ASIO_DECL int do_connect(void*, std::size_t); - - // Adapt the SSL_shutdown function to the signature needed for perform(). - ASIO_DECL int do_shutdown(void*, std::size_t); - - // Adapt the SSL_read function to the signature needed for perform(). - ASIO_DECL int do_read(void* data, std::size_t length); - - // Adapt the SSL_write function to the signature needed for perform(). - ASIO_DECL int do_write(void* data, std::size_t length); - - SSL* ssl_; - BIO* ext_bio_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/ssl/detail/impl/engine.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_SSL_DETAIL_ENGINE_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/handshake_op.hpp b/scout_sdk/asio/asio/ssl/detail/handshake_op.hpp deleted file mode 100644 index f782023..0000000 --- a/scout_sdk/asio/asio/ssl/detail/handshake_op.hpp +++ /dev/null @@ -1,62 +0,0 @@ -// -// ssl/detail/handshake_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_HANDSHAKE_OP_HPP -#define ASIO_SSL_DETAIL_HANDSHAKE_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/ssl/detail/engine.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -class handshake_op -{ -public: - handshake_op(stream_base::handshake_type type) - : type_(type) - { - } - - engine::want operator()(engine& eng, - asio::error_code& ec, - std::size_t& bytes_transferred) const - { - bytes_transferred = 0; - return eng.handshake(type_, ec); - } - - template - void call_handler(Handler& handler, - const asio::error_code& ec, - const std::size_t&) const - { - handler(ec); - } - -private: - stream_base::handshake_type type_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_HANDSHAKE_OP_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/impl/engine.ipp b/scout_sdk/asio/asio/ssl/detail/impl/engine.ipp deleted file mode 100644 index e60e8d6..0000000 --- a/scout_sdk/asio/asio/ssl/detail/impl/engine.ipp +++ /dev/null @@ -1,322 +0,0 @@ -// -// ssl/detail/impl/engine.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_IMPL_ENGINE_IPP -#define ASIO_SSL_DETAIL_IMPL_ENGINE_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/ssl/detail/engine.hpp" -#include "asio/ssl/error.hpp" -#include "asio/ssl/verify_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -engine::engine(SSL_CTX* context) - : ssl_(::SSL_new(context)) -{ - if (!ssl_) - { - asio::error_code ec( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - asio::detail::throw_error(ec, "engine"); - } - -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) - accept_mutex().init(); -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) - - ::SSL_set_mode(ssl_, SSL_MODE_ENABLE_PARTIAL_WRITE); - ::SSL_set_mode(ssl_, SSL_MODE_ACCEPT_MOVING_WRITE_BUFFER); -#if defined(SSL_MODE_RELEASE_BUFFERS) - ::SSL_set_mode(ssl_, SSL_MODE_RELEASE_BUFFERS); -#endif // defined(SSL_MODE_RELEASE_BUFFERS) - - ::BIO* int_bio = 0; - ::BIO_new_bio_pair(&int_bio, 0, &ext_bio_, 0); - ::SSL_set_bio(ssl_, int_bio, int_bio); -} - -engine::~engine() -{ - if (SSL_get_app_data(ssl_)) - { - delete static_cast(SSL_get_app_data(ssl_)); - SSL_set_app_data(ssl_, 0); - } - - ::BIO_free(ext_bio_); - ::SSL_free(ssl_); -} - -SSL* engine::native_handle() -{ - return ssl_; -} - -asio::error_code engine::set_verify_mode( - verify_mode v, asio::error_code& ec) -{ - ::SSL_set_verify(ssl_, v, ::SSL_get_verify_callback(ssl_)); - - ec = asio::error_code(); - return ec; -} - -asio::error_code engine::set_verify_depth( - int depth, asio::error_code& ec) -{ - ::SSL_set_verify_depth(ssl_, depth); - - ec = asio::error_code(); - return ec; -} - -asio::error_code engine::set_verify_callback( - verify_callback_base* callback, asio::error_code& ec) -{ - if (SSL_get_app_data(ssl_)) - delete static_cast(SSL_get_app_data(ssl_)); - - SSL_set_app_data(ssl_, callback); - - ::SSL_set_verify(ssl_, ::SSL_get_verify_mode(ssl_), - &engine::verify_callback_function); - - ec = asio::error_code(); - return ec; -} - -int engine::verify_callback_function(int preverified, X509_STORE_CTX* ctx) -{ - if (ctx) - { - if (SSL* ssl = static_cast( - ::X509_STORE_CTX_get_ex_data( - ctx, ::SSL_get_ex_data_X509_STORE_CTX_idx()))) - { - if (SSL_get_app_data(ssl)) - { - verify_callback_base* callback = - static_cast( - SSL_get_app_data(ssl)); - - verify_context verify_ctx(ctx); - return callback->call(preverified != 0, verify_ctx) ? 1 : 0; - } - } - } - - return 0; -} - -engine::want engine::handshake( - stream_base::handshake_type type, asio::error_code& ec) -{ - return perform((type == asio::ssl::stream_base::client) - ? &engine::do_connect : &engine::do_accept, 0, 0, ec, 0); -} - -engine::want engine::shutdown(asio::error_code& ec) -{ - return perform(&engine::do_shutdown, 0, 0, ec, 0); -} - -engine::want engine::write(const asio::const_buffer& data, - asio::error_code& ec, std::size_t& bytes_transferred) -{ - if (data.size() == 0) - { - ec = asio::error_code(); - return engine::want_nothing; - } - - return perform(&engine::do_write, - const_cast(data.data()), - data.size(), ec, &bytes_transferred); -} - -engine::want engine::read(const asio::mutable_buffer& data, - asio::error_code& ec, std::size_t& bytes_transferred) -{ - if (data.size() == 0) - { - ec = asio::error_code(); - return engine::want_nothing; - } - - return perform(&engine::do_read, data.data(), - data.size(), ec, &bytes_transferred); -} - -asio::mutable_buffer engine::get_output( - const asio::mutable_buffer& data) -{ - int length = ::BIO_read(ext_bio_, - data.data(), static_cast(data.size())); - - return asio::buffer(data, - length > 0 ? static_cast(length) : 0); -} - -asio::const_buffer engine::put_input( - const asio::const_buffer& data) -{ - int length = ::BIO_write(ext_bio_, - data.data(), static_cast(data.size())); - - return asio::buffer(data + - (length > 0 ? static_cast(length) : 0)); -} - -const asio::error_code& engine::map_error_code( - asio::error_code& ec) const -{ - // We only want to map the error::eof code. - if (ec != asio::error::eof) - return ec; - - // If there's data yet to be read, it's an error. - if (BIO_wpending(ext_bio_)) - { - ec = asio::ssl::error::stream_truncated; - return ec; - } - - // SSL v2 doesn't provide a protocol-level shutdown, so an eof on the - // underlying transport is passed through. -#if (OPENSSL_VERSION_NUMBER < 0x10100000L) - if (SSL_version(ssl_) == SSL2_VERSION) - return ec; -#endif // (OPENSSL_VERSION_NUMBER < 0x10100000L) - - // Otherwise, the peer should have negotiated a proper shutdown. - if ((::SSL_get_shutdown(ssl_) & SSL_RECEIVED_SHUTDOWN) == 0) - { - ec = asio::ssl::error::stream_truncated; - } - - return ec; -} - -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) -asio::detail::static_mutex& engine::accept_mutex() -{ - static asio::detail::static_mutex mutex = ASIO_STATIC_MUTEX_INIT; - return mutex; -} -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) - -engine::want engine::perform(int (engine::* op)(void*, std::size_t), - void* data, std::size_t length, asio::error_code& ec, - std::size_t* bytes_transferred) -{ - std::size_t pending_output_before = ::BIO_ctrl_pending(ext_bio_); - ::ERR_clear_error(); - int result = (this->*op)(data, length); - int ssl_error = ::SSL_get_error(ssl_, result); - int sys_error = static_cast(::ERR_get_error()); - std::size_t pending_output_after = ::BIO_ctrl_pending(ext_bio_); - - if (ssl_error == SSL_ERROR_SSL) - { - ec = asio::error_code(sys_error, - asio::error::get_ssl_category()); - return want_nothing; - } - - if (ssl_error == SSL_ERROR_SYSCALL) - { - ec = asio::error_code(sys_error, - asio::error::get_system_category()); - return want_nothing; - } - - if (result > 0 && bytes_transferred) - *bytes_transferred = static_cast(result); - - if (ssl_error == SSL_ERROR_WANT_WRITE) - { - ec = asio::error_code(); - return want_output_and_retry; - } - else if (pending_output_after > pending_output_before) - { - ec = asio::error_code(); - return result > 0 ? want_output : want_output_and_retry; - } - else if (ssl_error == SSL_ERROR_WANT_READ) - { - ec = asio::error_code(); - return want_input_and_retry; - } - else if (::SSL_get_shutdown(ssl_) & SSL_RECEIVED_SHUTDOWN) - { - ec = asio::error::eof; - return want_nothing; - } - else - { - ec = asio::error_code(); - return want_nothing; - } -} - -int engine::do_accept(void*, std::size_t) -{ -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) - asio::detail::static_mutex::scoped_lock lock(accept_mutex()); -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) - return ::SSL_accept(ssl_); -} - -int engine::do_connect(void*, std::size_t) -{ - return ::SSL_connect(ssl_); -} - -int engine::do_shutdown(void*, std::size_t) -{ - int result = ::SSL_shutdown(ssl_); - if (result == 0) - result = ::SSL_shutdown(ssl_); - return result; -} - -int engine::do_read(void* data, std::size_t length) -{ - return ::SSL_read(ssl_, data, - length < INT_MAX ? static_cast(length) : INT_MAX); -} - -int engine::do_write(void* data, std::size_t length) -{ - return ::SSL_write(ssl_, data, - length < INT_MAX ? static_cast(length) : INT_MAX); -} - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_IMPL_ENGINE_IPP diff --git a/scout_sdk/asio/asio/ssl/detail/impl/openssl_init.ipp b/scout_sdk/asio/asio/ssl/detail/impl/openssl_init.ipp deleted file mode 100644 index fb0fff9..0000000 --- a/scout_sdk/asio/asio/ssl/detail/impl/openssl_init.ipp +++ /dev/null @@ -1,165 +0,0 @@ -// -// ssl/detail/impl/openssl_init.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2005 Voipster / Indrek dot Juhani at voipster dot com -// Copyright (c) 2005-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_IMPL_OPENSSL_INIT_IPP -#define ASIO_SSL_DETAIL_IMPL_OPENSSL_INIT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/assert.hpp" -#include "asio/detail/mutex.hpp" -#include "asio/detail/tss_ptr.hpp" -#include "asio/ssl/detail/openssl_init.hpp" -#include "asio/ssl/detail/openssl_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -class openssl_init_base::do_init -{ -public: - do_init() - { -#if (OPENSSL_VERSION_NUMBER < 0x10100000L) - ::SSL_library_init(); - ::SSL_load_error_strings(); - ::OpenSSL_add_all_algorithms(); - - mutexes_.resize(::CRYPTO_num_locks()); - for (size_t i = 0; i < mutexes_.size(); ++i) - mutexes_[i].reset(new asio::detail::mutex); - ::CRYPTO_set_locking_callback(&do_init::openssl_locking_func); -#endif // (OPENSSL_VERSION_NUMBER < 0x10100000L) -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) - ::CRYPTO_set_id_callback(&do_init::openssl_id_func); -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) - -#if !defined(SSL_OP_NO_COMPRESSION) \ - && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - null_compression_methods_ = sk_SSL_COMP_new_null(); -#endif // !defined(SSL_OP_NO_COMPRESSION) - // && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - } - - ~do_init() - { -#if !defined(SSL_OP_NO_COMPRESSION) \ - && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - sk_SSL_COMP_free(null_compression_methods_); -#endif // !defined(SSL_OP_NO_COMPRESSION) - // && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) - ::CRYPTO_set_id_callback(0); -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) -#if (OPENSSL_VERSION_NUMBER < 0x10100000L) - ::CRYPTO_set_locking_callback(0); - ::ERR_free_strings(); - ::EVP_cleanup(); - ::CRYPTO_cleanup_all_ex_data(); -#endif // (OPENSSL_VERSION_NUMBER < 0x10100000L) -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) - ::ERR_remove_state(0); -#elif (OPENSSL_VERSION_NUMBER < 0x10100000L) - ::ERR_remove_thread_state(NULL); -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) -#if (OPENSSL_VERSION_NUMBER >= 0x10002000L) \ - && (OPENSSL_VERSION_NUMBER < 0x10100000L) \ - && !defined(SSL_OP_NO_COMPRESSION) - ::SSL_COMP_free_compression_methods(); -#endif // (OPENSSL_VERSION_NUMBER >= 0x10002000L) - // && (OPENSSL_VERSION_NUMBER < 0x10100000L) - // && !defined(SSL_OP_NO_COMPRESSION) -#if !defined(OPENSSL_IS_BORINGSSL) - ::CONF_modules_unload(1); -#endif // !defined(OPENSSL_IS_BORINGSSL) -#if !defined(OPENSSL_NO_ENGINE) \ - && (OPENSSL_VERSION_NUMBER < 0x10100000L) - ::ENGINE_cleanup(); -#endif // !defined(OPENSSL_NO_ENGINE) - // && (OPENSSL_VERSION_NUMBER < 0x10100000L) - } - -#if !defined(SSL_OP_NO_COMPRESSION) \ - && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - STACK_OF(SSL_COMP)* get_null_compression_methods() const - { - return null_compression_methods_; - } -#endif // !defined(SSL_OP_NO_COMPRESSION) - // && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - -private: -#if (OPENSSL_VERSION_NUMBER < 0x10000000L) - static unsigned long openssl_id_func() - { -#if defined(ASIO_WINDOWS) || defined(__CYGWIN__) - return ::GetCurrentThreadId(); -#else // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - void* id = &errno; - ASIO_ASSERT(sizeof(unsigned long) >= sizeof(void*)); - return reinterpret_cast(id); -#endif // defined(ASIO_WINDOWS) || defined(__CYGWIN__) - } -#endif // (OPENSSL_VERSION_NUMBER < 0x10000000L) - -#if (OPENSSL_VERSION_NUMBER < 0x10100000L) - static void openssl_locking_func(int mode, int n, - const char* /*file*/, int /*line*/) - { - if (mode & CRYPTO_LOCK) - instance()->mutexes_[n]->lock(); - else - instance()->mutexes_[n]->unlock(); - } - - // Mutexes to be used in locking callbacks. - std::vector > mutexes_; -#endif // (OPENSSL_VERSION_NUMBER < 0x10100000L) - -#if !defined(SSL_OP_NO_COMPRESSION) \ - && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - STACK_OF(SSL_COMP)* null_compression_methods_; -#endif // !defined(SSL_OP_NO_COMPRESSION) - // && (OPENSSL_VERSION_NUMBER >= 0x00908000L) -}; - -asio::detail::shared_ptr -openssl_init_base::instance() -{ - static asio::detail::shared_ptr init(new do_init); - return init; -} - -#if !defined(SSL_OP_NO_COMPRESSION) \ - && (OPENSSL_VERSION_NUMBER >= 0x00908000L) -STACK_OF(SSL_COMP)* openssl_init_base::get_null_compression_methods() -{ - return instance()->get_null_compression_methods(); -} -#endif // !defined(SSL_OP_NO_COMPRESSION) - // && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_IMPL_OPENSSL_INIT_IPP diff --git a/scout_sdk/asio/asio/ssl/detail/io.hpp b/scout_sdk/asio/asio/ssl/detail/io.hpp deleted file mode 100644 index 0b0e51a..0000000 --- a/scout_sdk/asio/asio/ssl/detail/io.hpp +++ /dev/null @@ -1,372 +0,0 @@ -// -// ssl/detail/io.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_IO_HPP -#define ASIO_SSL_DETAIL_IO_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/ssl/detail/engine.hpp" -#include "asio/ssl/detail/stream_core.hpp" -#include "asio/write.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -template -std::size_t io(Stream& next_layer, stream_core& core, - const Operation& op, asio::error_code& ec) -{ - std::size_t bytes_transferred = 0; - do switch (op(core.engine_, ec, bytes_transferred)) - { - case engine::want_input_and_retry: - - // If the input buffer is empty then we need to read some more data from - // the underlying transport. - if (core.input_.size() == 0) - core.input_ = asio::buffer(core.input_buffer_, - next_layer.read_some(core.input_buffer_, ec)); - - // Pass the new input data to the engine. - core.input_ = core.engine_.put_input(core.input_); - - // Try the operation again. - continue; - - case engine::want_output_and_retry: - - // Get output data from the engine and write it to the underlying - // transport. - asio::write(next_layer, - core.engine_.get_output(core.output_buffer_), ec); - - // Try the operation again. - continue; - - case engine::want_output: - - // Get output data from the engine and write it to the underlying - // transport. - asio::write(next_layer, - core.engine_.get_output(core.output_buffer_), ec); - - // Operation is complete. Return result to caller. - core.engine_.map_error_code(ec); - return bytes_transferred; - - default: - - // Operation is complete. Return result to caller. - core.engine_.map_error_code(ec); - return bytes_transferred; - - } while (!ec); - - // Operation failed. Return result to caller. - core.engine_.map_error_code(ec); - return 0; -} - -template -class io_op -{ -public: - io_op(Stream& next_layer, stream_core& core, - const Operation& op, Handler& handler) - : next_layer_(next_layer), - core_(core), - op_(op), - start_(0), - want_(engine::want_nothing), - bytes_transferred_(0), - handler_(ASIO_MOVE_CAST(Handler)(handler)) - { - } - -#if defined(ASIO_HAS_MOVE) - io_op(const io_op& other) - : next_layer_(other.next_layer_), - core_(other.core_), - op_(other.op_), - start_(other.start_), - want_(other.want_), - ec_(other.ec_), - bytes_transferred_(other.bytes_transferred_), - handler_(other.handler_) - { - } - - io_op(io_op&& other) - : next_layer_(other.next_layer_), - core_(other.core_), - op_(ASIO_MOVE_CAST(Operation)(other.op_)), - start_(other.start_), - want_(other.want_), - ec_(other.ec_), - bytes_transferred_(other.bytes_transferred_), - handler_(ASIO_MOVE_CAST(Handler)(other.handler_)) - { - } -#endif // defined(ASIO_HAS_MOVE) - - void operator()(asio::error_code ec, - std::size_t bytes_transferred = ~std::size_t(0), int start = 0) - { - switch (start_ = start) - { - case 1: // Called after at least one async operation. - do - { - switch (want_ = op_(core_.engine_, ec_, bytes_transferred_)) - { - case engine::want_input_and_retry: - - // If the input buffer already has data in it we can pass it to the - // engine and then retry the operation immediately. - if (core_.input_.size() != 0) - { - core_.input_ = core_.engine_.put_input(core_.input_); - continue; - } - - // The engine wants more data to be read from input. However, we - // cannot allow more than one read operation at a time on the - // underlying transport. The pending_read_ timer's expiry is set to - // pos_infin if a read is in progress, and neg_infin otherwise. - if (core_.expiry(core_.pending_read_) == core_.neg_infin()) - { - // Prevent other read operations from being started. - core_.pending_read_.expires_at(core_.pos_infin()); - - // Start reading some data from the underlying transport. - next_layer_.async_read_some( - asio::buffer(core_.input_buffer_), - ASIO_MOVE_CAST(io_op)(*this)); - } - else - { - // Wait until the current read operation completes. - core_.pending_read_.async_wait(ASIO_MOVE_CAST(io_op)(*this)); - } - - // Yield control until asynchronous operation completes. Control - // resumes at the "default:" label below. - return; - - case engine::want_output_and_retry: - case engine::want_output: - - // The engine wants some data to be written to the output. However, we - // cannot allow more than one write operation at a time on the - // underlying transport. The pending_write_ timer's expiry is set to - // pos_infin if a write is in progress, and neg_infin otherwise. - if (core_.expiry(core_.pending_write_) == core_.neg_infin()) - { - // Prevent other write operations from being started. - core_.pending_write_.expires_at(core_.pos_infin()); - - // Start writing all the data to the underlying transport. - asio::async_write(next_layer_, - core_.engine_.get_output(core_.output_buffer_), - ASIO_MOVE_CAST(io_op)(*this)); - } - else - { - // Wait until the current write operation completes. - core_.pending_write_.async_wait(ASIO_MOVE_CAST(io_op)(*this)); - } - - // Yield control until asynchronous operation completes. Control - // resumes at the "default:" label below. - return; - - default: - - // The SSL operation is done and we can invoke the handler, but we - // have to keep in mind that this function might be being called from - // the async operation's initiating function. In this case we're not - // allowed to call the handler directly. Instead, issue a zero-sized - // read so the handler runs "as-if" posted using io_context::post(). - if (start) - { - next_layer_.async_read_some( - asio::buffer(core_.input_buffer_, 0), - ASIO_MOVE_CAST(io_op)(*this)); - - // Yield control until asynchronous operation completes. Control - // resumes at the "default:" label below. - return; - } - else - { - // Continue on to run handler directly. - break; - } - } - - default: - if (bytes_transferred == ~std::size_t(0)) - bytes_transferred = 0; // Timer cancellation, no data transferred. - else if (!ec_) - ec_ = ec; - - switch (want_) - { - case engine::want_input_and_retry: - - // Add received data to the engine's input. - core_.input_ = asio::buffer( - core_.input_buffer_, bytes_transferred); - core_.input_ = core_.engine_.put_input(core_.input_); - - // Release any waiting read operations. - core_.pending_read_.expires_at(core_.neg_infin()); - - // Try the operation again. - continue; - - case engine::want_output_and_retry: - - // Release any waiting write operations. - core_.pending_write_.expires_at(core_.neg_infin()); - - // Try the operation again. - continue; - - case engine::want_output: - - // Release any waiting write operations. - core_.pending_write_.expires_at(core_.neg_infin()); - - // Fall through to call handler. - - default: - - // Pass the result to the handler. - op_.call_handler(handler_, - core_.engine_.map_error_code(ec_), - ec_ ? 0 : bytes_transferred_); - - // Our work here is done. - return; - } - } while (!ec_); - - // Operation failed. Pass the result to the handler. - op_.call_handler(handler_, core_.engine_.map_error_code(ec_), 0); - } - } - -//private: - Stream& next_layer_; - stream_core& core_; - Operation op_; - int start_; - engine::want want_; - asio::error_code ec_; - std::size_t bytes_transferred_; - Handler handler_; -}; - -template -inline void* asio_handler_allocate(std::size_t size, - io_op* this_handler) -{ - return asio_handler_alloc_helpers::allocate( - size, this_handler->handler_); -} - -template -inline void asio_handler_deallocate(void* pointer, std::size_t size, - io_op* this_handler) -{ - asio_handler_alloc_helpers::deallocate( - pointer, size, this_handler->handler_); -} - -template -inline bool asio_handler_is_continuation( - io_op* this_handler) -{ - return this_handler->start_ == 0 ? true - : asio_handler_cont_helpers::is_continuation(this_handler->handler_); -} - -template -inline void asio_handler_invoke(Function& function, - io_op* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void asio_handler_invoke(const Function& function, - io_op* this_handler) -{ - asio_handler_invoke_helpers::invoke( - function, this_handler->handler_); -} - -template -inline void async_io(Stream& next_layer, stream_core& core, - const Operation& op, Handler& handler) -{ - io_op( - next_layer, core, op, handler)( - asio::error_code(), 0, 1); -} - -} // namespace detail -} // namespace ssl - -template -struct associated_allocator< - ssl::detail::io_op, Allocator> -{ - typedef typename associated_allocator::type type; - - static type get(const ssl::detail::io_op& h, - const Allocator& a = Allocator()) ASIO_NOEXCEPT - { - return associated_allocator::get(h.handler_, a); - } -}; - -template -struct associated_executor< - ssl::detail::io_op, Executor> -{ - typedef typename associated_executor::type type; - - static type get(const ssl::detail::io_op& h, - const Executor& ex = Executor()) ASIO_NOEXCEPT - { - return associated_executor::get(h.handler_, ex); - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_IO_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/openssl_init.hpp b/scout_sdk/asio/asio/ssl/detail/openssl_init.hpp deleted file mode 100644 index c3e4727..0000000 --- a/scout_sdk/asio/asio/ssl/detail/openssl_init.hpp +++ /dev/null @@ -1,101 +0,0 @@ -// -// ssl/detail/openssl_init.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_OPENSSL_INIT_HPP -#define ASIO_SSL_DETAIL_OPENSSL_INIT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/detail/memory.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/ssl/detail/openssl_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -class openssl_init_base - : private noncopyable -{ -protected: - // Class that performs the actual initialisation. - class do_init; - - // Helper function to manage a do_init singleton. The static instance of the - // openssl_init object ensures that this function is always called before - // main, and therefore before any other threads can get started. The do_init - // instance must be static in this function to ensure that it gets - // initialised before any other global objects try to use it. - ASIO_DECL static asio::detail::shared_ptr instance(); - -#if !defined(SSL_OP_NO_COMPRESSION) \ - && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - // Get an empty stack of compression methods, to be used when disabling - // compression. - ASIO_DECL static STACK_OF(SSL_COMP)* get_null_compression_methods(); -#endif // !defined(SSL_OP_NO_COMPRESSION) - // && (OPENSSL_VERSION_NUMBER >= 0x00908000L) -}; - -template -class openssl_init : private openssl_init_base -{ -public: - // Constructor. - openssl_init() - : ref_(instance()) - { - using namespace std; // For memmove. - - // Ensure openssl_init::instance_ is linked in. - openssl_init* tmp = &instance_; - memmove(&tmp, &tmp, sizeof(openssl_init*)); - } - - // Destructor. - ~openssl_init() - { - } - -#if !defined(SSL_OP_NO_COMPRESSION) \ - && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - using openssl_init_base::get_null_compression_methods; -#endif // !defined(SSL_OP_NO_COMPRESSION) - // && (OPENSSL_VERSION_NUMBER >= 0x00908000L) - -private: - // Instance to force initialisation of openssl at global scope. - static openssl_init instance_; - - // Reference to singleton do_init object to ensure that openssl does not get - // cleaned up until the last user has finished with it. - asio::detail::shared_ptr ref_; -}; - -template -openssl_init openssl_init::instance_; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/ssl/detail/impl/openssl_init.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_SSL_DETAIL_OPENSSL_INIT_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/openssl_types.hpp b/scout_sdk/asio/asio/ssl/detail/openssl_types.hpp deleted file mode 100644 index a044af3..0000000 --- a/scout_sdk/asio/asio/ssl/detail/openssl_types.hpp +++ /dev/null @@ -1,30 +0,0 @@ -// -// ssl/detail/openssl_types.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_OPENSSL_TYPES_HPP -#define ASIO_SSL_DETAIL_OPENSSL_TYPES_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/socket_types.hpp" -#include -#include -#if !defined(OPENSSL_NO_ENGINE) -# include -#endif // !defined(OPENSSL_NO_ENGINE) -#include -#include -#include -#include - -#endif // ASIO_SSL_DETAIL_OPENSSL_TYPES_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/password_callback.hpp b/scout_sdk/asio/asio/ssl/detail/password_callback.hpp deleted file mode 100644 index 9b1dbee..0000000 --- a/scout_sdk/asio/asio/ssl/detail/password_callback.hpp +++ /dev/null @@ -1,66 +0,0 @@ -// -// ssl/detail/password_callback.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_PASSWORD_CALLBACK_HPP -#define ASIO_SSL_DETAIL_PASSWORD_CALLBACK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include -#include "asio/ssl/context_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -class password_callback_base -{ -public: - virtual ~password_callback_base() - { - } - - virtual std::string call(std::size_t size, - context_base::password_purpose purpose) = 0; -}; - -template -class password_callback : public password_callback_base -{ -public: - explicit password_callback(PasswordCallback callback) - : callback_(callback) - { - } - - virtual std::string call(std::size_t size, - context_base::password_purpose purpose) - { - return callback_(size, purpose); - } - -private: - PasswordCallback callback_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_PASSWORD_CALLBACK_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/read_op.hpp b/scout_sdk/asio/asio/ssl/detail/read_op.hpp deleted file mode 100644 index b0d6de2..0000000 --- a/scout_sdk/asio/asio/ssl/detail/read_op.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// ssl/detail/read_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_READ_OP_HPP -#define ASIO_SSL_DETAIL_READ_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/ssl/detail/engine.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -template -class read_op -{ -public: - read_op(const MutableBufferSequence& buffers) - : buffers_(buffers) - { - } - - engine::want operator()(engine& eng, - asio::error_code& ec, - std::size_t& bytes_transferred) const - { - asio::mutable_buffer buffer = - asio::detail::buffer_sequence_adapter::first(buffers_); - - return eng.read(buffer, ec, bytes_transferred); - } - - template - void call_handler(Handler& handler, - const asio::error_code& ec, - const std::size_t& bytes_transferred) const - { - handler(ec, bytes_transferred); - } - -private: - MutableBufferSequence buffers_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_READ_OP_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/shutdown_op.hpp b/scout_sdk/asio/asio/ssl/detail/shutdown_op.hpp deleted file mode 100644 index d20b430..0000000 --- a/scout_sdk/asio/asio/ssl/detail/shutdown_op.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// -// ssl/detail/shutdown_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_SHUTDOWN_OP_HPP -#define ASIO_SSL_DETAIL_SHUTDOWN_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/ssl/detail/engine.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -class shutdown_op -{ -public: - engine::want operator()(engine& eng, - asio::error_code& ec, - std::size_t& bytes_transferred) const - { - bytes_transferred = 0; - return eng.shutdown(ec); - } - - template - void call_handler(Handler& handler, - const asio::error_code& ec, - const std::size_t&) const - { - handler(ec); - } -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_SHUTDOWN_OP_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/stream_core.hpp b/scout_sdk/asio/asio/ssl/detail/stream_core.hpp deleted file mode 100644 index 13fde74..0000000 --- a/scout_sdk/asio/asio/ssl/detail/stream_core.hpp +++ /dev/null @@ -1,134 +0,0 @@ -// -// ssl/detail/stream_core.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_STREAM_CORE_HPP -#define ASIO_SSL_DETAIL_STREAM_CORE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_BOOST_DATE_TIME) -# include "asio/deadline_timer.hpp" -#else // defined(ASIO_HAS_BOOST_DATE_TIME) -# include "asio/steady_timer.hpp" -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) -#include "asio/ssl/detail/engine.hpp" -#include "asio/buffer.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -struct stream_core -{ - // According to the OpenSSL documentation, this is the buffer size that is - // sufficient to hold the largest possible TLS record. - enum { max_tls_record_size = 17 * 1024 }; - - stream_core(SSL_CTX* context, asio::io_context& io_context) - : engine_(context), - pending_read_(io_context), - pending_write_(io_context), - output_buffer_space_(max_tls_record_size), - output_buffer_(asio::buffer(output_buffer_space_)), - input_buffer_space_(max_tls_record_size), - input_buffer_(asio::buffer(input_buffer_space_)) - { - pending_read_.expires_at(neg_infin()); - pending_write_.expires_at(neg_infin()); - } - - ~stream_core() - { - } - - // The SSL engine. - engine engine_; - -#if defined(ASIO_HAS_BOOST_DATE_TIME) - // Timer used for storing queued read operations. - asio::deadline_timer pending_read_; - - // Timer used for storing queued write operations. - asio::deadline_timer pending_write_; - - // Helper function for obtaining a time value that always fires. - static asio::deadline_timer::time_type neg_infin() - { - return boost::posix_time::neg_infin; - } - - // Helper function for obtaining a time value that never fires. - static asio::deadline_timer::time_type pos_infin() - { - return boost::posix_time::pos_infin; - } - - // Helper function to get a timer's expiry time. - static asio::deadline_timer::time_type expiry( - const asio::deadline_timer& timer) - { - return timer.expires_at(); - } -#else // defined(ASIO_HAS_BOOST_DATE_TIME) - // Timer used for storing queued read operations. - asio::steady_timer pending_read_; - - // Timer used for storing queued write operations. - asio::steady_timer pending_write_; - - // Helper function for obtaining a time value that always fires. - static asio::steady_timer::time_point neg_infin() - { - return (asio::steady_timer::time_point::min)(); - } - - // Helper function for obtaining a time value that never fires. - static asio::steady_timer::time_point pos_infin() - { - return (asio::steady_timer::time_point::max)(); - } - - // Helper function to get a timer's expiry time. - static asio::steady_timer::time_point expiry( - const asio::steady_timer& timer) - { - return timer.expiry(); - } -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - - // Buffer space used to prepare output intended for the transport. - std::vector output_buffer_space_; - - // A buffer that may be used to prepare output intended for the transport. - const asio::mutable_buffer output_buffer_; - - // Buffer space used to read input intended for the engine. - std::vector input_buffer_space_; - - // A buffer that may be used to read input intended for the engine. - const asio::mutable_buffer input_buffer_; - - // The buffer pointing to the engine's unconsumed input. - asio::const_buffer input_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_STREAM_CORE_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/verify_callback.hpp b/scout_sdk/asio/asio/ssl/detail/verify_callback.hpp deleted file mode 100644 index 1c56a27..0000000 --- a/scout_sdk/asio/asio/ssl/detail/verify_callback.hpp +++ /dev/null @@ -1,62 +0,0 @@ -// -// ssl/detail/verify_callback.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_VERIFY_CALLBACK_HPP -#define ASIO_SSL_DETAIL_VERIFY_CALLBACK_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/ssl/verify_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -class verify_callback_base -{ -public: - virtual ~verify_callback_base() - { - } - - virtual bool call(bool preverified, verify_context& ctx) = 0; -}; - -template -class verify_callback : public verify_callback_base -{ -public: - explicit verify_callback(VerifyCallback callback) - : callback_(callback) - { - } - - virtual bool call(bool preverified, verify_context& ctx) - { - return callback_(preverified, ctx); - } - -private: - VerifyCallback callback_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_VERIFY_CALLBACK_HPP diff --git a/scout_sdk/asio/asio/ssl/detail/write_op.hpp b/scout_sdk/asio/asio/ssl/detail/write_op.hpp deleted file mode 100644 index 1d341c0..0000000 --- a/scout_sdk/asio/asio/ssl/detail/write_op.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// ssl/detail/write_op.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_DETAIL_WRITE_OP_HPP -#define ASIO_SSL_DETAIL_WRITE_OP_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/ssl/detail/engine.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { -namespace detail { - -template -class write_op -{ -public: - write_op(const ConstBufferSequence& buffers) - : buffers_(buffers) - { - } - - engine::want operator()(engine& eng, - asio::error_code& ec, - std::size_t& bytes_transferred) const - { - asio::const_buffer buffer = - asio::detail::buffer_sequence_adapter::first(buffers_); - - return eng.write(buffer, ec, bytes_transferred); - } - - template - void call_handler(Handler& handler, - const asio::error_code& ec, - const std::size_t& bytes_transferred) const - { - handler(ec, bytes_transferred); - } - -private: - ConstBufferSequence buffers_; -}; - -} // namespace detail -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_DETAIL_WRITE_OP_HPP diff --git a/scout_sdk/asio/asio/ssl/error.hpp b/scout_sdk/asio/asio/ssl/error.hpp deleted file mode 100644 index 6165c5c..0000000 --- a/scout_sdk/asio/asio/ssl/error.hpp +++ /dev/null @@ -1,111 +0,0 @@ -// -// ssl/error.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_ERROR_HPP -#define ASIO_SSL_ERROR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/error_code.hpp" -#include "asio/ssl/detail/openssl_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace error { - -enum ssl_errors -{ - // Error numbers are those produced by openssl. -}; - -extern ASIO_DECL -const asio::error_category& get_ssl_category(); - -static const asio::error_category& - ssl_category ASIO_UNUSED_VARIABLE - = asio::error::get_ssl_category(); - -} // namespace error -namespace ssl { -namespace error { - -enum stream_errors -{ -#if defined(GENERATING_DOCUMENTATION) - /// The underlying stream closed before the ssl stream gracefully shut down. - stream_truncated -#elif (OPENSSL_VERSION_NUMBER < 0x10100000L) && !defined(OPENSSL_IS_BORINGSSL) - stream_truncated = ERR_PACK(ERR_LIB_SSL, 0, SSL_R_SHORT_READ) -#else - stream_truncated = 1 -#endif -}; - -extern ASIO_DECL -const asio::error_category& get_stream_category(); - -static const asio::error_category& - stream_category ASIO_UNUSED_VARIABLE - = asio::ssl::error::get_stream_category(); - -} // namespace error -} // namespace ssl -} // namespace asio - -#if defined(ASIO_HAS_STD_SYSTEM_ERROR) -namespace std { - -template<> struct is_error_code_enum -{ - static const bool value = true; -}; - -template<> struct is_error_code_enum -{ - static const bool value = true; -}; - -} // namespace std -#endif // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -namespace asio { -namespace error { - -inline asio::error_code make_error_code(ssl_errors e) -{ - return asio::error_code( - static_cast(e), get_ssl_category()); -} - -} // namespace error -namespace ssl { -namespace error { - -inline asio::error_code make_error_code(stream_errors e) -{ - return asio::error_code( - static_cast(e), get_stream_category()); -} - -} // namespace error -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/ssl/impl/error.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_SSL_ERROR_HPP diff --git a/scout_sdk/asio/asio/ssl/impl/context.hpp b/scout_sdk/asio/asio/ssl/impl/context.hpp deleted file mode 100644 index 40199c1..0000000 --- a/scout_sdk/asio/asio/ssl/impl/context.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// ssl/impl/context.hpp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2005 Voipster / Indrek dot Juhani at voipster dot com -// Copyright (c) 2005-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_IMPL_CONTEXT_HPP -#define ASIO_SSL_IMPL_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/throw_error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -template -void context::set_verify_callback(VerifyCallback callback) -{ - asio::error_code ec; - this->set_verify_callback(callback, ec); - asio::detail::throw_error(ec, "set_verify_callback"); -} - -template -ASIO_SYNC_OP_VOID context::set_verify_callback( - VerifyCallback callback, asio::error_code& ec) -{ - do_set_verify_callback( - new detail::verify_callback(callback), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -template -void context::set_password_callback(PasswordCallback callback) -{ - asio::error_code ec; - this->set_password_callback(callback, ec); - asio::detail::throw_error(ec, "set_password_callback"); -} - -template -ASIO_SYNC_OP_VOID context::set_password_callback( - PasswordCallback callback, asio::error_code& ec) -{ - do_set_password_callback( - new detail::password_callback(callback), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_IMPL_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/ssl/impl/context.ipp b/scout_sdk/asio/asio/ssl/impl/context.ipp deleted file mode 100644 index b756fd2..0000000 --- a/scout_sdk/asio/asio/ssl/impl/context.ipp +++ /dev/null @@ -1,1159 +0,0 @@ -// -// ssl/impl/context.ipp -// ~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2005 Voipster / Indrek dot Juhani at voipster dot com -// Copyright (c) 2005-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_IMPL_CONTEXT_IPP -#define ASIO_SSL_IMPL_CONTEXT_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/ssl/context.hpp" -#include "asio/ssl/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -struct context::bio_cleanup -{ - BIO* p; - ~bio_cleanup() { if (p) ::BIO_free(p); } -}; - -struct context::x509_cleanup -{ - X509* p; - ~x509_cleanup() { if (p) ::X509_free(p); } -}; - -struct context::evp_pkey_cleanup -{ - EVP_PKEY* p; - ~evp_pkey_cleanup() { if (p) ::EVP_PKEY_free(p); } -}; - -struct context::rsa_cleanup -{ - RSA* p; - ~rsa_cleanup() { if (p) ::RSA_free(p); } -}; - -struct context::dh_cleanup -{ - DH* p; - ~dh_cleanup() { if (p) ::DH_free(p); } -}; - -context::context(context::method m) - : handle_(0) -{ - ::ERR_clear_error(); - - switch (m) - { - // SSL v2. -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) || defined(OPENSSL_NO_SSL2) - case context::sslv2: - case context::sslv2_client: - case context::sslv2_server: - asio::detail::throw_error( - asio::error::invalid_argument, "context"); - break; -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) || defined(OPENSSL_NO_SSL2) - case context::sslv2: - handle_ = ::SSL_CTX_new(::SSLv2_method()); - break; - case context::sslv2_client: - handle_ = ::SSL_CTX_new(::SSLv2_client_method()); - break; - case context::sslv2_server: - handle_ = ::SSL_CTX_new(::SSLv2_server_method()); - break; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) || defined(OPENSSL_NO_SSL2) - - // SSL v3. -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - case context::sslv3: - handle_ = ::SSL_CTX_new(::TLS_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, SSL3_VERSION); - SSL_CTX_set_max_proto_version(handle_, SSL3_VERSION); - } - break; - case context::sslv3_client: - handle_ = ::SSL_CTX_new(::TLS_client_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, SSL3_VERSION); - SSL_CTX_set_max_proto_version(handle_, SSL3_VERSION); - } - break; - case context::sslv3_server: - handle_ = ::SSL_CTX_new(::TLS_server_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, SSL3_VERSION); - SSL_CTX_set_max_proto_version(handle_, SSL3_VERSION); - } - break; -#elif defined(OPENSSL_NO_SSL3) - case context::sslv3: - case context::sslv3_client: - case context::sslv3_server: - asio::detail::throw_error( - asio::error::invalid_argument, "context"); - break; -#else // defined(OPENSSL_NO_SSL3) - case context::sslv3: - handle_ = ::SSL_CTX_new(::SSLv3_method()); - break; - case context::sslv3_client: - handle_ = ::SSL_CTX_new(::SSLv3_client_method()); - break; - case context::sslv3_server: - handle_ = ::SSL_CTX_new(::SSLv3_server_method()); - break; -#endif // defined(OPENSSL_NO_SSL3) - - // TLS v1.0. -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - case context::tlsv1: - handle_ = ::SSL_CTX_new(::TLS_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_VERSION); - } - break; - case context::tlsv1_client: - handle_ = ::SSL_CTX_new(::TLS_client_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_VERSION); - } - break; - case context::tlsv1_server: - handle_ = ::SSL_CTX_new(::TLS_server_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_VERSION); - } - break; -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - case context::tlsv1: - handle_ = ::SSL_CTX_new(::TLSv1_method()); - break; - case context::tlsv1_client: - handle_ = ::SSL_CTX_new(::TLSv1_client_method()); - break; - case context::tlsv1_server: - handle_ = ::SSL_CTX_new(::TLSv1_server_method()); - break; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - - // TLS v1.1. -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - case context::tlsv11: - handle_ = ::SSL_CTX_new(::TLS_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_1_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_1_VERSION); - } - break; - case context::tlsv11_client: - handle_ = ::SSL_CTX_new(::TLS_client_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_1_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_1_VERSION); - } - break; - case context::tlsv11_server: - handle_ = ::SSL_CTX_new(::TLS_server_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_1_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_1_VERSION); - } - break; -#elif defined(SSL_TXT_TLSV1_1) - case context::tlsv11: - handle_ = ::SSL_CTX_new(::TLSv1_1_method()); - break; - case context::tlsv11_client: - handle_ = ::SSL_CTX_new(::TLSv1_1_client_method()); - break; - case context::tlsv11_server: - handle_ = ::SSL_CTX_new(::TLSv1_1_server_method()); - break; -#else // defined(SSL_TXT_TLSV1_1) - case context::tlsv11: - case context::tlsv11_client: - case context::tlsv11_server: - asio::detail::throw_error( - asio::error::invalid_argument, "context"); - break; -#endif // defined(SSL_TXT_TLSV1_1) - - // TLS v1.2. -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - case context::tlsv12: - handle_ = ::SSL_CTX_new(::TLS_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_2_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_2_VERSION); - } - break; - case context::tlsv12_client: - handle_ = ::SSL_CTX_new(::TLS_client_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_2_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_2_VERSION); - } - break; - case context::tlsv12_server: - handle_ = ::SSL_CTX_new(::TLS_server_method()); - if (handle_) - { - SSL_CTX_set_min_proto_version(handle_, TLS1_2_VERSION); - SSL_CTX_set_max_proto_version(handle_, TLS1_2_VERSION); - } - break; -#elif defined(SSL_TXT_TLSV1_1) - case context::tlsv12: - handle_ = ::SSL_CTX_new(::TLSv1_2_method()); - break; - case context::tlsv12_client: - handle_ = ::SSL_CTX_new(::TLSv1_2_client_method()); - break; - case context::tlsv12_server: - handle_ = ::SSL_CTX_new(::TLSv1_2_server_method()); - break; -#else // defined(SSL_TXT_TLSV1_1) - case context::tlsv12: - case context::tlsv12_client: - case context::tlsv12_server: - asio::detail::throw_error( - asio::error::invalid_argument, "context"); - break; -#endif // defined(SSL_TXT_TLSV1_1) - - // Any supported SSL/TLS version. - case context::sslv23: - handle_ = ::SSL_CTX_new(::SSLv23_method()); - break; - case context::sslv23_client: - handle_ = ::SSL_CTX_new(::SSLv23_client_method()); - break; - case context::sslv23_server: - handle_ = ::SSL_CTX_new(::SSLv23_server_method()); - break; - - // Any supported TLS version. -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - case context::tls: - handle_ = ::SSL_CTX_new(::TLS_method()); - if (handle_) - SSL_CTX_set_min_proto_version(handle_, TLS1_VERSION); - break; - case context::tls_client: - handle_ = ::SSL_CTX_new(::TLS_client_method()); - if (handle_) - SSL_CTX_set_min_proto_version(handle_, TLS1_VERSION); - break; - case context::tls_server: - handle_ = ::SSL_CTX_new(::TLS_server_method()); - if (handle_) - SSL_CTX_set_min_proto_version(handle_, TLS1_VERSION); - break; -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - case context::tls: - handle_ = ::SSL_CTX_new(::SSLv23_method()); - if (handle_) - SSL_CTX_set_options(handle_, SSL_OP_NO_SSLv2 | SSL_OP_NO_SSLv3); - break; - case context::tls_client: - handle_ = ::SSL_CTX_new(::SSLv23_client_method()); - if (handle_) - SSL_CTX_set_options(handle_, SSL_OP_NO_SSLv2 | SSL_OP_NO_SSLv3); - break; - case context::tls_server: - handle_ = ::SSL_CTX_new(::SSLv23_server_method()); - if (handle_) - SSL_CTX_set_options(handle_, SSL_OP_NO_SSLv2 | SSL_OP_NO_SSLv3); - break; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - - default: - handle_ = ::SSL_CTX_new(0); - break; - } - - if (handle_ == 0) - { - asio::error_code ec( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - asio::detail::throw_error(ec, "context"); - } - - set_options(no_compression); -} - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) -context::context(context&& other) -{ - handle_ = other.handle_; - other.handle_ = 0; -} - -context& context::operator=(context&& other) -{ - context tmp(ASIO_MOVE_CAST(context)(*this)); - handle_ = other.handle_; - other.handle_ = 0; - return *this; -} -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - -context::~context() -{ - if (handle_) - { -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - void* cb_userdata = ::SSL_CTX_get_default_passwd_cb_userdata(handle_); -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - void* cb_userdata = handle_->default_passwd_callback_userdata; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - if (cb_userdata) - { - detail::password_callback_base* callback = - static_cast( - cb_userdata); - delete callback; -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - ::SSL_CTX_set_default_passwd_cb_userdata(handle_, 0); -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - handle_->default_passwd_callback_userdata = 0; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - } - - if (SSL_CTX_get_app_data(handle_)) - { - detail::verify_callback_base* callback = - static_cast( - SSL_CTX_get_app_data(handle_)); - delete callback; - SSL_CTX_set_app_data(handle_, 0); - } - - ::SSL_CTX_free(handle_); - } -} - -context::native_handle_type context::native_handle() -{ - return handle_; -} - -void context::clear_options(context::options o) -{ - asio::error_code ec; - clear_options(o, ec); - asio::detail::throw_error(ec, "clear_options"); -} - -ASIO_SYNC_OP_VOID context::clear_options( - context::options o, asio::error_code& ec) -{ -#if (OPENSSL_VERSION_NUMBER >= 0x009080DFL) \ - && (OPENSSL_VERSION_NUMBER != 0x00909000L) -# if !defined(SSL_OP_NO_COMPRESSION) - if ((o & context::no_compression) != 0) - { -# if (OPENSSL_VERSION_NUMBER >= 0x00908000L) - handle_->comp_methods = SSL_COMP_get_compression_methods(); -# endif // (OPENSSL_VERSION_NUMBER >= 0x00908000L) - o ^= context::no_compression; - } -# endif // !defined(SSL_OP_NO_COMPRESSION) - - ::SSL_CTX_clear_options(handle_, o); - - ec = asio::error_code(); -#else // (OPENSSL_VERSION_NUMBER >= 0x009080DFL) - // && (OPENSSL_VERSION_NUMBER != 0x00909000L) - (void)o; - ec = asio::error::operation_not_supported; -#endif // (OPENSSL_VERSION_NUMBER >= 0x009080DFL) - // && (OPENSSL_VERSION_NUMBER != 0x00909000L) - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::set_options(context::options o) -{ - asio::error_code ec; - set_options(o, ec); - asio::detail::throw_error(ec, "set_options"); -} - -ASIO_SYNC_OP_VOID context::set_options( - context::options o, asio::error_code& ec) -{ -#if !defined(SSL_OP_NO_COMPRESSION) - if ((o & context::no_compression) != 0) - { -#if (OPENSSL_VERSION_NUMBER >= 0x00908000L) - handle_->comp_methods = - asio::ssl::detail::openssl_init<>::get_null_compression_methods(); -#endif // (OPENSSL_VERSION_NUMBER >= 0x00908000L) - o ^= context::no_compression; - } -#endif // !defined(SSL_OP_NO_COMPRESSION) - - ::SSL_CTX_set_options(handle_, o); - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::set_verify_mode(verify_mode v) -{ - asio::error_code ec; - set_verify_mode(v, ec); - asio::detail::throw_error(ec, "set_verify_mode"); -} - -ASIO_SYNC_OP_VOID context::set_verify_mode( - verify_mode v, asio::error_code& ec) -{ - ::SSL_CTX_set_verify(handle_, v, ::SSL_CTX_get_verify_callback(handle_)); - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::set_verify_depth(int depth) -{ - asio::error_code ec; - set_verify_depth(depth, ec); - asio::detail::throw_error(ec, "set_verify_depth"); -} - -ASIO_SYNC_OP_VOID context::set_verify_depth( - int depth, asio::error_code& ec) -{ - ::SSL_CTX_set_verify_depth(handle_, depth); - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::load_verify_file(const std::string& filename) -{ - asio::error_code ec; - load_verify_file(filename, ec); - asio::detail::throw_error(ec, "load_verify_file"); -} - -ASIO_SYNC_OP_VOID context::load_verify_file( - const std::string& filename, asio::error_code& ec) -{ - ::ERR_clear_error(); - - if (::SSL_CTX_load_verify_locations(handle_, filename.c_str(), 0) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::add_certificate_authority(const const_buffer& ca) -{ - asio::error_code ec; - add_certificate_authority(ca, ec); - asio::detail::throw_error(ec, "add_certificate_authority"); -} - -ASIO_SYNC_OP_VOID context::add_certificate_authority( - const const_buffer& ca, asio::error_code& ec) -{ - ::ERR_clear_error(); - - bio_cleanup bio = { make_buffer_bio(ca) }; - if (bio.p) - { - if (X509_STORE* store = ::SSL_CTX_get_cert_store(handle_)) - { - for (;;) - { - x509_cleanup cert = { ::PEM_read_bio_X509(bio.p, 0, 0, 0) }; - if (!cert.p) - break; - - if (::X509_STORE_add_cert(store, cert.p) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - } - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::set_default_verify_paths() -{ - asio::error_code ec; - set_default_verify_paths(ec); - asio::detail::throw_error(ec, "set_default_verify_paths"); -} - -ASIO_SYNC_OP_VOID context::set_default_verify_paths( - asio::error_code& ec) -{ - ::ERR_clear_error(); - - if (::SSL_CTX_set_default_verify_paths(handle_) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::add_verify_path(const std::string& path) -{ - asio::error_code ec; - add_verify_path(path, ec); - asio::detail::throw_error(ec, "add_verify_path"); -} - -ASIO_SYNC_OP_VOID context::add_verify_path( - const std::string& path, asio::error_code& ec) -{ - ::ERR_clear_error(); - - if (::SSL_CTX_load_verify_locations(handle_, 0, path.c_str()) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_certificate( - const const_buffer& certificate, file_format format) -{ - asio::error_code ec; - use_certificate(certificate, format, ec); - asio::detail::throw_error(ec, "use_certificate"); -} - -ASIO_SYNC_OP_VOID context::use_certificate( - const const_buffer& certificate, file_format format, - asio::error_code& ec) -{ - ::ERR_clear_error(); - - if (format == context_base::asn1) - { - if (::SSL_CTX_use_certificate_ASN1(handle_, - static_cast(certificate.size()), - static_cast(certificate.data())) == 1) - { - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - else if (format == context_base::pem) - { - bio_cleanup bio = { make_buffer_bio(certificate) }; - if (bio.p) - { - x509_cleanup cert = { ::PEM_read_bio_X509(bio.p, 0, 0, 0) }; - if (cert.p) - { - if (::SSL_CTX_use_certificate(handle_, cert.p) == 1) - { - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - } - } - else - { - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_certificate_file( - const std::string& filename, file_format format) -{ - asio::error_code ec; - use_certificate_file(filename, format, ec); - asio::detail::throw_error(ec, "use_certificate_file"); -} - -ASIO_SYNC_OP_VOID context::use_certificate_file( - const std::string& filename, file_format format, - asio::error_code& ec) -{ - int file_type; - switch (format) - { - case context_base::asn1: - file_type = SSL_FILETYPE_ASN1; - break; - case context_base::pem: - file_type = SSL_FILETYPE_PEM; - break; - default: - { - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - ::ERR_clear_error(); - - if (::SSL_CTX_use_certificate_file(handle_, filename.c_str(), file_type) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_certificate_chain(const const_buffer& chain) -{ - asio::error_code ec; - use_certificate_chain(chain, ec); - asio::detail::throw_error(ec, "use_certificate_chain"); -} - -ASIO_SYNC_OP_VOID context::use_certificate_chain( - const const_buffer& chain, asio::error_code& ec) -{ - ::ERR_clear_error(); - - bio_cleanup bio = { make_buffer_bio(chain) }; - if (bio.p) - { -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - pem_password_cb* callback = ::SSL_CTX_get_default_passwd_cb(handle_); - void* cb_userdata = ::SSL_CTX_get_default_passwd_cb_userdata(handle_); -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - pem_password_cb* callback = handle_->default_passwd_callback; - void* cb_userdata = handle_->default_passwd_callback_userdata; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - x509_cleanup cert = { - ::PEM_read_bio_X509_AUX(bio.p, 0, - callback, - cb_userdata) }; - if (!cert.p) - { - ec = asio::error_code(ERR_R_PEM_LIB, - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - int result = ::SSL_CTX_use_certificate(handle_, cert.p); - if (result == 0 || ::ERR_peek_error() != 0) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - -#if (OPENSSL_VERSION_NUMBER >= 0x10002000L) && !defined(LIBRESSL_VERSION_NUMBER) - ::SSL_CTX_clear_chain_certs(handle_); -#else - if (handle_->extra_certs) - { - ::sk_X509_pop_free(handle_->extra_certs, X509_free); - handle_->extra_certs = 0; - } -#endif // (OPENSSL_VERSION_NUMBER >= 0x10002000L) - - while (X509* cacert = ::PEM_read_bio_X509(bio.p, 0, - callback, - cb_userdata)) - { - if (!::SSL_CTX_add_extra_chain_cert(handle_, cacert)) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - result = ::ERR_peek_last_error(); - if ((ERR_GET_LIB(result) == ERR_LIB_PEM) - && (ERR_GET_REASON(result) == PEM_R_NO_START_LINE)) - { - ::ERR_clear_error(); - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_certificate_chain_file(const std::string& filename) -{ - asio::error_code ec; - use_certificate_chain_file(filename, ec); - asio::detail::throw_error(ec, "use_certificate_chain_file"); -} - -ASIO_SYNC_OP_VOID context::use_certificate_chain_file( - const std::string& filename, asio::error_code& ec) -{ - ::ERR_clear_error(); - - if (::SSL_CTX_use_certificate_chain_file(handle_, filename.c_str()) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_private_key( - const const_buffer& private_key, context::file_format format) -{ - asio::error_code ec; - use_private_key(private_key, format, ec); - asio::detail::throw_error(ec, "use_private_key"); -} - -ASIO_SYNC_OP_VOID context::use_private_key( - const const_buffer& private_key, context::file_format format, - asio::error_code& ec) -{ - ::ERR_clear_error(); - -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - pem_password_cb* callback = ::SSL_CTX_get_default_passwd_cb(handle_); - void* cb_userdata = ::SSL_CTX_get_default_passwd_cb_userdata(handle_); -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - pem_password_cb* callback = handle_->default_passwd_callback; - void* cb_userdata = handle_->default_passwd_callback_userdata; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - - bio_cleanup bio = { make_buffer_bio(private_key) }; - if (bio.p) - { - evp_pkey_cleanup evp_private_key = { 0 }; - switch (format) - { - case context_base::asn1: - evp_private_key.p = ::d2i_PrivateKey_bio(bio.p, 0); - break; - case context_base::pem: - evp_private_key.p = ::PEM_read_bio_PrivateKey( - bio.p, 0, callback, - cb_userdata); - break; - default: - { - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - if (evp_private_key.p) - { - if (::SSL_CTX_use_PrivateKey(handle_, evp_private_key.p) == 1) - { - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - } - - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_private_key_file( - const std::string& filename, context::file_format format) -{ - asio::error_code ec; - use_private_key_file(filename, format, ec); - asio::detail::throw_error(ec, "use_private_key_file"); -} - -void context::use_rsa_private_key( - const const_buffer& private_key, context::file_format format) -{ - asio::error_code ec; - use_rsa_private_key(private_key, format, ec); - asio::detail::throw_error(ec, "use_rsa_private_key"); -} - -ASIO_SYNC_OP_VOID context::use_rsa_private_key( - const const_buffer& private_key, context::file_format format, - asio::error_code& ec) -{ - ::ERR_clear_error(); - -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - pem_password_cb* callback = ::SSL_CTX_get_default_passwd_cb(handle_); - void* cb_userdata = ::SSL_CTX_get_default_passwd_cb_userdata(handle_); -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - pem_password_cb* callback = handle_->default_passwd_callback; - void* cb_userdata = handle_->default_passwd_callback_userdata; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - - bio_cleanup bio = { make_buffer_bio(private_key) }; - if (bio.p) - { - rsa_cleanup rsa_private_key = { 0 }; - switch (format) - { - case context_base::asn1: - rsa_private_key.p = ::d2i_RSAPrivateKey_bio(bio.p, 0); - break; - case context_base::pem: - rsa_private_key.p = ::PEM_read_bio_RSAPrivateKey( - bio.p, 0, callback, - cb_userdata); - break; - default: - { - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - if (rsa_private_key.p) - { - if (::SSL_CTX_use_RSAPrivateKey(handle_, rsa_private_key.p) == 1) - { - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - } - - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID context::use_private_key_file( - const std::string& filename, context::file_format format, - asio::error_code& ec) -{ - int file_type; - switch (format) - { - case context_base::asn1: - file_type = SSL_FILETYPE_ASN1; - break; - case context_base::pem: - file_type = SSL_FILETYPE_PEM; - break; - default: - { - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - ::ERR_clear_error(); - - if (::SSL_CTX_use_PrivateKey_file(handle_, filename.c_str(), file_type) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_rsa_private_key_file( - const std::string& filename, context::file_format format) -{ - asio::error_code ec; - use_rsa_private_key_file(filename, format, ec); - asio::detail::throw_error(ec, "use_rsa_private_key_file"); -} - -ASIO_SYNC_OP_VOID context::use_rsa_private_key_file( - const std::string& filename, context::file_format format, - asio::error_code& ec) -{ - int file_type; - switch (format) - { - case context_base::asn1: - file_type = SSL_FILETYPE_ASN1; - break; - case context_base::pem: - file_type = SSL_FILETYPE_PEM; - break; - default: - { - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - ::ERR_clear_error(); - - if (::SSL_CTX_use_RSAPrivateKey_file( - handle_, filename.c_str(), file_type) != 1) - { - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_tmp_dh(const const_buffer& dh) -{ - asio::error_code ec; - use_tmp_dh(dh, ec); - asio::detail::throw_error(ec, "use_tmp_dh"); -} - -ASIO_SYNC_OP_VOID context::use_tmp_dh( - const const_buffer& dh, asio::error_code& ec) -{ - ::ERR_clear_error(); - - bio_cleanup bio = { make_buffer_bio(dh) }; - if (bio.p) - { - return do_use_tmp_dh(bio.p, ec); - } - - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -void context::use_tmp_dh_file(const std::string& filename) -{ - asio::error_code ec; - use_tmp_dh_file(filename, ec); - asio::detail::throw_error(ec, "use_tmp_dh_file"); -} - -ASIO_SYNC_OP_VOID context::use_tmp_dh_file( - const std::string& filename, asio::error_code& ec) -{ - ::ERR_clear_error(); - - bio_cleanup bio = { ::BIO_new_file(filename.c_str(), "r") }; - if (bio.p) - { - return do_use_tmp_dh(bio.p, ec); - } - - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID context::do_use_tmp_dh( - BIO* bio, asio::error_code& ec) -{ - ::ERR_clear_error(); - - dh_cleanup dh = { ::PEM_read_bio_DHparams(bio, 0, 0, 0) }; - if (dh.p) - { - if (::SSL_CTX_set_tmp_dh(handle_, dh.p) == 1) - { - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - } - - ec = asio::error_code( - static_cast(::ERR_get_error()), - asio::error::get_ssl_category()); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -ASIO_SYNC_OP_VOID context::do_set_verify_callback( - detail::verify_callback_base* callback, asio::error_code& ec) -{ - if (SSL_CTX_get_app_data(handle_)) - { - delete static_cast( - SSL_CTX_get_app_data(handle_)); - } - - SSL_CTX_set_app_data(handle_, callback); - - ::SSL_CTX_set_verify(handle_, - ::SSL_CTX_get_verify_mode(handle_), - &context::verify_callback_function); - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -int context::verify_callback_function(int preverified, X509_STORE_CTX* ctx) -{ - if (ctx) - { - if (SSL* ssl = static_cast( - ::X509_STORE_CTX_get_ex_data( - ctx, ::SSL_get_ex_data_X509_STORE_CTX_idx()))) - { - if (SSL_CTX* handle = ::SSL_get_SSL_CTX(ssl)) - { - if (SSL_CTX_get_app_data(handle)) - { - detail::verify_callback_base* callback = - static_cast( - SSL_CTX_get_app_data(handle)); - - verify_context verify_ctx(ctx); - return callback->call(preverified != 0, verify_ctx) ? 1 : 0; - } - } - } - } - - return 0; -} - -ASIO_SYNC_OP_VOID context::do_set_password_callback( - detail::password_callback_base* callback, asio::error_code& ec) -{ -#if (OPENSSL_VERSION_NUMBER >= 0x10100000L) && !defined(LIBRESSL_VERSION_NUMBER) - void* old_callback = ::SSL_CTX_get_default_passwd_cb_userdata(handle_); - ::SSL_CTX_set_default_passwd_cb_userdata(handle_, callback); -#else // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - void* old_callback = handle_->default_passwd_callback_userdata; - handle_->default_passwd_callback_userdata = callback; -#endif // (OPENSSL_VERSION_NUMBER >= 0x10100000L) - - if (old_callback) - delete static_cast( - old_callback); - - SSL_CTX_set_default_passwd_cb(handle_, &context::password_callback_function); - - ec = asio::error_code(); - ASIO_SYNC_OP_VOID_RETURN(ec); -} - -int context::password_callback_function( - char* buf, int size, int purpose, void* data) -{ - using namespace std; // For strncat and strlen. - - if (data) - { - detail::password_callback_base* callback = - static_cast(data); - - std::string passwd = callback->call(static_cast(size), - purpose ? context_base::for_writing : context_base::for_reading); - -#if defined(ASIO_HAS_SECURE_RTL) - strcpy_s(buf, size, passwd.c_str()); -#else // defined(ASIO_HAS_SECURE_RTL) - *buf = '\0'; - if (size > 0) - strncat(buf, passwd.c_str(), size - 1); -#endif // defined(ASIO_HAS_SECURE_RTL) - - return static_cast(strlen(buf)); - } - - return 0; -} - -BIO* context::make_buffer_bio(const const_buffer& b) -{ - return ::BIO_new_mem_buf( - const_cast(b.data()), - static_cast(b.size())); -} - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_IMPL_CONTEXT_IPP diff --git a/scout_sdk/asio/asio/ssl/impl/error.ipp b/scout_sdk/asio/asio/ssl/impl/error.ipp deleted file mode 100644 index 98e8c91..0000000 --- a/scout_sdk/asio/asio/ssl/impl/error.ipp +++ /dev/null @@ -1,100 +0,0 @@ -// -// ssl/impl/error.ipp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_IMPL_ERROR_IPP -#define ASIO_SSL_IMPL_ERROR_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ssl/error.hpp" -#include "asio/ssl/detail/openssl_init.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace error { -namespace detail { - -class ssl_category : public asio::error_category -{ -public: - const char* name() const ASIO_ERROR_CATEGORY_NOEXCEPT - { - return "asio.ssl"; - } - - std::string message(int value) const - { - const char* s = ::ERR_reason_error_string(value); - return s ? s : "asio.ssl error"; - } -}; - -} // namespace detail - -const asio::error_category& get_ssl_category() -{ - static detail::ssl_category instance; - return instance; -} - -} // namespace error -namespace ssl { -namespace error { - -#if (OPENSSL_VERSION_NUMBER < 0x10100000L) && !defined(OPENSSL_IS_BORINGSSL) - -const asio::error_category& get_stream_category() -{ - return asio::error::get_ssl_category(); -} - -#else - -namespace detail { - -class stream_category : public asio::error_category -{ -public: - const char* name() const ASIO_ERROR_CATEGORY_NOEXCEPT - { - return "asio.ssl.stream"; - } - - std::string message(int value) const - { - switch (value) - { - case stream_truncated: return "stream truncated"; - default: return "asio.ssl.stream error"; - } - } -}; - -} // namespace detail - -const asio::error_category& get_stream_category() -{ - static detail::stream_category instance; - return instance; -} - -#endif - -} // namespace error -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_IMPL_ERROR_IPP diff --git a/scout_sdk/asio/asio/ssl/impl/rfc2818_verification.ipp b/scout_sdk/asio/asio/ssl/impl/rfc2818_verification.ipp deleted file mode 100644 index 577e4a1..0000000 --- a/scout_sdk/asio/asio/ssl/impl/rfc2818_verification.ipp +++ /dev/null @@ -1,160 +0,0 @@ -// -// ssl/impl/rfc2818_verification.ipp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_IMPL_RFC2818_VERIFICATION_IPP -#define ASIO_SSL_IMPL_RFC2818_VERIFICATION_IPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include -#include "asio/ip/address.hpp" -#include "asio/ssl/rfc2818_verification.hpp" -#include "asio/ssl/detail/openssl_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -bool rfc2818_verification::operator()( - bool preverified, verify_context& ctx) const -{ - using namespace std; // For memcmp. - - // Don't bother looking at certificates that have failed pre-verification. - if (!preverified) - return false; - - // We're only interested in checking the certificate at the end of the chain. - int depth = X509_STORE_CTX_get_error_depth(ctx.native_handle()); - if (depth > 0) - return true; - - // Try converting the host name to an address. If it is an address then we - // need to look for an IP address in the certificate rather than a host name. - asio::error_code ec; - ip::address address = ip::make_address(host_, ec); - bool is_address = !ec; - - X509* cert = X509_STORE_CTX_get_current_cert(ctx.native_handle()); - - // Go through the alternate names in the certificate looking for matching DNS - // or IP address entries. - GENERAL_NAMES* gens = static_cast( - X509_get_ext_d2i(cert, NID_subject_alt_name, 0, 0)); - for (int i = 0; i < sk_GENERAL_NAME_num(gens); ++i) - { - GENERAL_NAME* gen = sk_GENERAL_NAME_value(gens, i); - if (gen->type == GEN_DNS && !is_address) - { - ASN1_IA5STRING* domain = gen->d.dNSName; - if (domain->type == V_ASN1_IA5STRING && domain->data && domain->length) - { - const char* pattern = reinterpret_cast(domain->data); - std::size_t pattern_length = domain->length; - if (match_pattern(pattern, pattern_length, host_.c_str())) - { - GENERAL_NAMES_free(gens); - return true; - } - } - } - else if (gen->type == GEN_IPADD && is_address) - { - ASN1_OCTET_STRING* ip_address = gen->d.iPAddress; - if (ip_address->type == V_ASN1_OCTET_STRING && ip_address->data) - { - if (address.is_v4() && ip_address->length == 4) - { - ip::address_v4::bytes_type bytes = address.to_v4().to_bytes(); - if (memcmp(bytes.data(), ip_address->data, 4) == 0) - { - GENERAL_NAMES_free(gens); - return true; - } - } - else if (address.is_v6() && ip_address->length == 16) - { - ip::address_v6::bytes_type bytes = address.to_v6().to_bytes(); - if (memcmp(bytes.data(), ip_address->data, 16) == 0) - { - GENERAL_NAMES_free(gens); - return true; - } - } - } - } - } - GENERAL_NAMES_free(gens); - - // No match in the alternate names, so try the common names. We should only - // use the "most specific" common name, which is the last one in the list. - X509_NAME* name = X509_get_subject_name(cert); - int i = -1; - ASN1_STRING* common_name = 0; - while ((i = X509_NAME_get_index_by_NID(name, NID_commonName, i)) >= 0) - { - X509_NAME_ENTRY* name_entry = X509_NAME_get_entry(name, i); - common_name = X509_NAME_ENTRY_get_data(name_entry); - } - if (common_name && common_name->data && common_name->length) - { - const char* pattern = reinterpret_cast(common_name->data); - std::size_t pattern_length = common_name->length; - if (match_pattern(pattern, pattern_length, host_.c_str())) - return true; - } - - return false; -} - -bool rfc2818_verification::match_pattern(const char* pattern, - std::size_t pattern_length, const char* host) -{ - using namespace std; // For tolower. - - const char* p = pattern; - const char* p_end = p + pattern_length; - const char* h = host; - - while (p != p_end && *h) - { - if (*p == '*') - { - ++p; - while (*h && *h != '.') - if (match_pattern(p, p_end - p, h++)) - return true; - } - else if (tolower(*p) == tolower(*h)) - { - ++p; - ++h; - } - else - { - return false; - } - } - - return p == p_end && !*h; -} - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_IMPL_RFC2818_VERIFICATION_IPP diff --git a/scout_sdk/asio/asio/ssl/impl/src.hpp b/scout_sdk/asio/asio/ssl/impl/src.hpp deleted file mode 100644 index 9a1b038..0000000 --- a/scout_sdk/asio/asio/ssl/impl/src.hpp +++ /dev/null @@ -1,28 +0,0 @@ -// -// impl/ssl/src.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_IMPL_SRC_HPP -#define ASIO_SSL_IMPL_SRC_HPP - -#define ASIO_SOURCE - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HEADER_ONLY) -# error Do not compile Asio library source with ASIO_HEADER_ONLY defined -#endif - -#include "asio/ssl/impl/context.ipp" -#include "asio/ssl/impl/error.ipp" -#include "asio/ssl/detail/impl/engine.ipp" -#include "asio/ssl/detail/impl/openssl_init.ipp" -#include "asio/ssl/impl/rfc2818_verification.ipp" - -#endif // ASIO_SSL_IMPL_SRC_HPP diff --git a/scout_sdk/asio/asio/ssl/rfc2818_verification.hpp b/scout_sdk/asio/asio/ssl/rfc2818_verification.hpp deleted file mode 100644 index 3589f53..0000000 --- a/scout_sdk/asio/asio/ssl/rfc2818_verification.hpp +++ /dev/null @@ -1,94 +0,0 @@ -// -// ssl/rfc2818_verification.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_RFC2818_VERIFICATION_HPP -#define ASIO_SSL_RFC2818_VERIFICATION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include -#include "asio/ssl/detail/openssl_types.hpp" -#include "asio/ssl/verify_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -/// Verifies a certificate against a hostname according to the rules described -/// in RFC 2818. -/** - * @par Example - * The following example shows how to synchronously open a secure connection to - * a given host name: - * @code - * using asio::ip::tcp; - * namespace ssl = asio::ssl; - * typedef ssl::stream ssl_socket; - * - * // Create a context that uses the default paths for finding CA certificates. - * ssl::context ctx(ssl::context::sslv23); - * ctx.set_default_verify_paths(); - * - * // Open a socket and connect it to the remote host. - * asio::io_context io_context; - * ssl_socket sock(io_context, ctx); - * tcp::resolver resolver(io_context); - * tcp::resolver::query query("host.name", "https"); - * asio::connect(sock.lowest_layer(), resolver.resolve(query)); - * sock.lowest_layer().set_option(tcp::no_delay(true)); - * - * // Perform SSL handshake and verify the remote host's certificate. - * sock.set_verify_mode(ssl::verify_peer); - * sock.set_verify_callback(ssl::rfc2818_verification("host.name")); - * sock.handshake(ssl_socket::client); - * - * // ... read and write as normal ... - * @endcode - */ -class rfc2818_verification -{ -public: - /// The type of the function object's result. - typedef bool result_type; - - /// Constructor. - explicit rfc2818_verification(const std::string& host) - : host_(host) - { - } - - /// Perform certificate verification. - ASIO_DECL bool operator()(bool preverified, verify_context& ctx) const; - -private: - // Helper function to check a host name against a pattern. - ASIO_DECL static bool match_pattern(const char* pattern, - std::size_t pattern_length, const char* host); - - // Helper function to check a host name against an IPv4 address - // The host name to be checked. - std::string host_; -}; - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#if defined(ASIO_HEADER_ONLY) -# include "asio/ssl/impl/rfc2818_verification.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_SSL_RFC2818_VERIFICATION_HPP diff --git a/scout_sdk/asio/asio/ssl/stream.hpp b/scout_sdk/asio/asio/ssl/stream.hpp deleted file mode 100644 index 2b221ed..0000000 --- a/scout_sdk/asio/asio/ssl/stream.hpp +++ /dev/null @@ -1,761 +0,0 @@ -// -// ssl/stream.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_STREAM_HPP -#define ASIO_SSL_STREAM_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/async_result.hpp" -#include "asio/detail/buffer_sequence_adapter.hpp" -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/ssl/context.hpp" -#include "asio/ssl/detail/buffered_handshake_op.hpp" -#include "asio/ssl/detail/handshake_op.hpp" -#include "asio/ssl/detail/io.hpp" -#include "asio/ssl/detail/read_op.hpp" -#include "asio/ssl/detail/shutdown_op.hpp" -#include "asio/ssl/detail/stream_core.hpp" -#include "asio/ssl/detail/write_op.hpp" -#include "asio/ssl/stream_base.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -/// Provides stream-oriented functionality using SSL. -/** - * The stream class template provides asynchronous and blocking stream-oriented - * functionality using SSL. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. The application must also ensure that all - * asynchronous operations are performed within the same implicit or explicit - * strand. - * - * @par Example - * To use the SSL stream template with an ip::tcp::socket, you would write: - * @code - * asio::io_context io_context; - * asio::ssl::context ctx(asio::ssl::context::sslv23); - * asio::ssl::stream sock(io_context, ctx); - * @endcode - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -template -class stream : - public stream_base, - private noncopyable -{ -public: - /// The native handle type of the SSL stream. - typedef SSL* native_handle_type; - - /// Structure for use with deprecated impl_type. - struct impl_struct - { - SSL* ssl; - }; - - /// The type of the next layer. - typedef typename remove_reference::type next_layer_type; - - /// The type of the lowest layer. - typedef typename next_layer_type::lowest_layer_type lowest_layer_type; - - /// The type of the executor associated with the object. - typedef typename lowest_layer_type::executor_type executor_type; - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Construct a stream. - /** - * This constructor creates a stream and initialises the underlying stream - * object. - * - * @param arg The argument to be passed to initialise the underlying stream. - * - * @param ctx The SSL context to be used for the stream. - */ - template - stream(Arg&& arg, context& ctx) - : next_layer_(ASIO_MOVE_CAST(Arg)(arg)), - core_(ctx.native_handle(), - next_layer_.lowest_layer().get_executor().context()) - { - } -#else // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - template - stream(Arg& arg, context& ctx) - : next_layer_(arg), - core_(ctx.native_handle(), - next_layer_.lowest_layer().get_executor().context()) - { - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destructor. - /** - * @note A @c stream object must not be destroyed while there are pending - * asynchronous operations associated with it. - */ - ~stream() - { - } - - /// Get the executor associated with the object. - /** - * This function may be used to obtain the executor object that the stream - * uses to dispatch handlers for asynchronous operations. - * - * @return A copy of the executor that stream will use to dispatch handlers. - */ - executor_type get_executor() ASIO_NOEXCEPT - { - return next_layer_.lowest_layer().get_executor(); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_context() - { - return next_layer_.lowest_layer().get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - asio::io_context& get_io_service() - { - return next_layer_.lowest_layer().get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the underlying implementation in the native type. - /** - * This function may be used to obtain the underlying implementation of the - * context. This is intended to allow access to context functionality that is - * not otherwise provided. - * - * @par Example - * The native_handle() function returns a pointer of type @c SSL* that is - * suitable for passing to functions such as @c SSL_get_verify_result and - * @c SSL_get_peer_certificate: - * @code - * asio::ssl::stream sock(io_context, ctx); - * - * // ... establish connection and perform handshake ... - * - * if (X509* cert = SSL_get_peer_certificate(sock.native_handle())) - * { - * if (SSL_get_verify_result(sock.native_handle()) == X509_V_OK) - * { - * // ... - * } - * } - * @endcode - */ - native_handle_type native_handle() - { - return core_.engine_.native_handle(); - } - - /// Get a reference to the next layer. - /** - * This function returns a reference to the next layer in a stack of stream - * layers. - * - * @return A reference to the next layer in the stack of stream layers. - * Ownership is not transferred to the caller. - */ - const next_layer_type& next_layer() const - { - return next_layer_; - } - - /// Get a reference to the next layer. - /** - * This function returns a reference to the next layer in a stack of stream - * layers. - * - * @return A reference to the next layer in the stack of stream layers. - * Ownership is not transferred to the caller. - */ - next_layer_type& next_layer() - { - return next_layer_; - } - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * stream layers. - * - * @return A reference to the lowest layer in the stack of stream layers. - * Ownership is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return next_layer_.lowest_layer(); - } - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * stream layers. - * - * @return A reference to the lowest layer in the stack of stream layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return next_layer_.lowest_layer(); - } - - /// Set the peer verification mode. - /** - * This function may be used to configure the peer verification mode used by - * the stream. The new mode will override the mode inherited from the context. - * - * @param v A bitmask of peer verification modes. See @ref verify_mode for - * available values. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_set_verify. - */ - void set_verify_mode(verify_mode v) - { - asio::error_code ec; - set_verify_mode(v, ec); - asio::detail::throw_error(ec, "set_verify_mode"); - } - - /// Set the peer verification mode. - /** - * This function may be used to configure the peer verification mode used by - * the stream. The new mode will override the mode inherited from the context. - * - * @param v A bitmask of peer verification modes. See @ref verify_mode for - * available values. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_set_verify. - */ - ASIO_SYNC_OP_VOID set_verify_mode( - verify_mode v, asio::error_code& ec) - { - core_.engine_.set_verify_mode(v, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Set the peer verification depth. - /** - * This function may be used to configure the maximum verification depth - * allowed by the stream. - * - * @param depth Maximum depth for the certificate chain verification that - * shall be allowed. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_set_verify_depth. - */ - void set_verify_depth(int depth) - { - asio::error_code ec; - set_verify_depth(depth, ec); - asio::detail::throw_error(ec, "set_verify_depth"); - } - - /// Set the peer verification depth. - /** - * This function may be used to configure the maximum verification depth - * allowed by the stream. - * - * @param depth Maximum depth for the certificate chain verification that - * shall be allowed. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_set_verify_depth. - */ - ASIO_SYNC_OP_VOID set_verify_depth( - int depth, asio::error_code& ec) - { - core_.engine_.set_verify_depth(depth, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Set the callback used to verify peer certificates. - /** - * This function is used to specify a callback function that will be called - * by the implementation when it needs to verify a peer certificate. - * - * @param callback The function object to be used for verifying a certificate. - * The function signature of the handler must be: - * @code bool verify_callback( - * bool preverified, // True if the certificate passed pre-verification. - * verify_context& ctx // The peer certificate and other context. - * ); @endcode - * The return value of the callback is true if the certificate has passed - * verification, false otherwise. - * - * @throws asio::system_error Thrown on failure. - * - * @note Calls @c SSL_set_verify. - */ - template - void set_verify_callback(VerifyCallback callback) - { - asio::error_code ec; - this->set_verify_callback(callback, ec); - asio::detail::throw_error(ec, "set_verify_callback"); - } - - /// Set the callback used to verify peer certificates. - /** - * This function is used to specify a callback function that will be called - * by the implementation when it needs to verify a peer certificate. - * - * @param callback The function object to be used for verifying a certificate. - * The function signature of the handler must be: - * @code bool verify_callback( - * bool preverified, // True if the certificate passed pre-verification. - * verify_context& ctx // The peer certificate and other context. - * ); @endcode - * The return value of the callback is true if the certificate has passed - * verification, false otherwise. - * - * @param ec Set to indicate what error occurred, if any. - * - * @note Calls @c SSL_set_verify. - */ - template - ASIO_SYNC_OP_VOID set_verify_callback(VerifyCallback callback, - asio::error_code& ec) - { - core_.engine_.set_verify_callback( - new detail::verify_callback(callback), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform SSL handshaking. - /** - * This function is used to perform SSL handshaking on the stream. The - * function call will block until handshaking is complete or an error occurs. - * - * @param type The type of handshaking to be performed, i.e. as a client or as - * a server. - * - * @throws asio::system_error Thrown on failure. - */ - void handshake(handshake_type type) - { - asio::error_code ec; - handshake(type, ec); - asio::detail::throw_error(ec, "handshake"); - } - - /// Perform SSL handshaking. - /** - * This function is used to perform SSL handshaking on the stream. The - * function call will block until handshaking is complete or an error occurs. - * - * @param type The type of handshaking to be performed, i.e. as a client or as - * a server. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID handshake(handshake_type type, - asio::error_code& ec) - { - detail::io(next_layer_, core_, detail::handshake_op(type), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform SSL handshaking. - /** - * This function is used to perform SSL handshaking on the stream. The - * function call will block until handshaking is complete or an error occurs. - * - * @param type The type of handshaking to be performed, i.e. as a client or as - * a server. - * - * @param buffers The buffered data to be reused for the handshake. - * - * @throws asio::system_error Thrown on failure. - */ - template - void handshake(handshake_type type, const ConstBufferSequence& buffers) - { - asio::error_code ec; - handshake(type, buffers, ec); - asio::detail::throw_error(ec, "handshake"); - } - - /// Perform SSL handshaking. - /** - * This function is used to perform SSL handshaking on the stream. The - * function call will block until handshaking is complete or an error occurs. - * - * @param type The type of handshaking to be performed, i.e. as a client or as - * a server. - * - * @param buffers The buffered data to be reused for the handshake. - * - * @param ec Set to indicate what error occurred, if any. - */ - template - ASIO_SYNC_OP_VOID handshake(handshake_type type, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - detail::io(next_layer_, core_, - detail::buffered_handshake_op(type, buffers), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous SSL handshake. - /** - * This function is used to asynchronously perform an SSL handshake on the - * stream. This function call always returns immediately. - * - * @param type The type of handshaking to be performed, i.e. as a client or as - * a server. - * - * @param handler The handler to be called when the handshake operation - * completes. Copies will be made of the handler as required. The equivalent - * function signature of the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(HandshakeHandler, - void (asio::error_code)) - async_handshake(handshake_type type, - ASIO_MOVE_ARG(HandshakeHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a HandshakeHandler. - ASIO_HANDSHAKE_HANDLER_CHECK(HandshakeHandler, handler) type_check; - - asio::async_completion init(handler); - - detail::async_io(next_layer_, core_, - detail::handshake_op(type), init.completion_handler); - - return init.result.get(); - } - - /// Start an asynchronous SSL handshake. - /** - * This function is used to asynchronously perform an SSL handshake on the - * stream. This function call always returns immediately. - * - * @param type The type of handshaking to be performed, i.e. as a client or as - * a server. - * - * @param buffers The buffered data to be reused for the handshake. Although - * the buffers object may be copied as necessary, ownership of the underlying - * buffers is retained by the caller, which must guarantee that they remain - * valid until the handler is called. - * - * @param handler The handler to be called when the handshake operation - * completes. Copies will be made of the handler as required. The equivalent - * function signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Amount of buffers used in handshake. - * ); @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(BufferedHandshakeHandler, - void (asio::error_code, std::size_t)) - async_handshake(handshake_type type, const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(BufferedHandshakeHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a BufferedHandshakeHandler. - ASIO_BUFFERED_HANDSHAKE_HANDLER_CHECK( - BufferedHandshakeHandler, handler) type_check; - - asio::async_completion init(handler); - - detail::async_io(next_layer_, core_, - detail::buffered_handshake_op(type, buffers), - init.completion_handler); - - return init.result.get(); - } - - /// Shut down SSL on the stream. - /** - * This function is used to shut down SSL on the stream. The function call - * will block until SSL has been shut down or an error occurs. - * - * @throws asio::system_error Thrown on failure. - */ - void shutdown() - { - asio::error_code ec; - shutdown(ec); - asio::detail::throw_error(ec, "shutdown"); - } - - /// Shut down SSL on the stream. - /** - * This function is used to shut down SSL on the stream. The function call - * will block until SSL has been shut down or an error occurs. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID shutdown(asio::error_code& ec) - { - detail::io(next_layer_, core_, detail::shutdown_op(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously shut down SSL on the stream. - /** - * This function is used to asynchronously shut down SSL on the stream. This - * function call always returns immediately. - * - * @param handler The handler to be called when the handshake operation - * completes. Copies will be made of the handler as required. The equivalent - * function signature of the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - */ - template - ASIO_INITFN_RESULT_TYPE(ShutdownHandler, - void (asio::error_code)) - async_shutdown(ASIO_MOVE_ARG(ShutdownHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ShutdownHandler. - ASIO_SHUTDOWN_HANDLER_CHECK(ShutdownHandler, handler) type_check; - - asio::async_completion init(handler); - - detail::async_io(next_layer_, core_, detail::shutdown_op(), - init.completion_handler); - - return init.result.get(); - } - - /// Write some data to the stream. - /** - * This function is used to write data on the stream. The function call will - * block until one or more bytes of data has been written successfully, or - * until an error occurs. - * - * @param buffers The data to be written. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that all - * data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t n = write_some(buffers, ec); - asio::detail::throw_error(ec, "write_some"); - return n; - } - - /// Write some data to the stream. - /** - * This function is used to write data on the stream. The function call will - * block until one or more bytes of data has been written successfully, or - * until an error occurs. - * - * @param buffers The data to be written to the stream. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that all - * data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return detail::io(next_layer_, core_, - detail::write_op(buffers), ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write one or more bytes of data to - * the stream. The function call always returns immediately. - * - * @param buffers The data to be written to the stream. Although the buffers - * object may be copied as necessary, ownership of the underlying buffers is - * retained by the caller, which must guarantee that they remain valid until - * the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The equivalent function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * - * @note The async_write_some operation may not transmit all of the data to - * the peer. Consider using the @ref async_write function if you need to - * ensure that all data is written before the blocking operation completes. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - asio::async_completion init(handler); - - detail::async_io(next_layer_, core_, - detail::write_op(buffers), - init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the stream. - /** - * This function is used to read data from the stream. The function call will - * block until one or more bytes of data has been read successfully, or until - * an error occurs. - * - * @param buffers The buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that the - * requested amount of data is read before the blocking operation completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t n = read_some(buffers, ec); - asio::detail::throw_error(ec, "read_some"); - return n; - } - - /// Read some data from the stream. - /** - * This function is used to read data from the stream. The function call will - * block until one or more bytes of data has been read successfully, or until - * an error occurs. - * - * @param buffers The buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that the - * requested amount of data is read before the blocking operation completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return detail::io(next_layer_, core_, - detail::read_op(buffers), ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read one or more bytes of data from - * the stream. The function call always returns immediately. - * - * @param buffers The buffers into which the data will be read. Although the - * buffers object may be copied as necessary, ownership of the underlying - * buffers is retained by the caller, which must guarantee that they remain - * valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The equivalent function - * signature of the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * - * @note The async_read_some operation may not read all of the requested - * number of bytes. Consider using the @ref async_read function if you need to - * ensure that the requested amount of data is read before the asynchronous - * operation completes. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - asio::async_completion init(handler); - - detail::async_io(next_layer_, core_, - detail::read_op(buffers), - init.completion_handler); - - return init.result.get(); - } - -private: - Stream next_layer_; - detail::stream_core core_; -}; - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_STREAM_HPP diff --git a/scout_sdk/asio/asio/ssl/stream_base.hpp b/scout_sdk/asio/asio/ssl/stream_base.hpp deleted file mode 100644 index 56873e4..0000000 --- a/scout_sdk/asio/asio/ssl/stream_base.hpp +++ /dev/null @@ -1,52 +0,0 @@ -// -// ssl/stream_base.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_STREAM_BASE_HPP -#define ASIO_SSL_STREAM_BASE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -/// The stream_base class is used as a base for the asio::ssl::stream -/// class template so that we have a common place to define various enums. -class stream_base -{ -public: - /// Different handshake types. - enum handshake_type - { - /// Perform handshaking as a client. - client, - - /// Perform handshaking as a server. - server - }; - -protected: - /// Protected destructor to prevent deletion through this type. - ~stream_base() - { - } -}; - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_STREAM_BASE_HPP diff --git a/scout_sdk/asio/asio/ssl/verify_context.hpp b/scout_sdk/asio/asio/ssl/verify_context.hpp deleted file mode 100644 index e172697..0000000 --- a/scout_sdk/asio/asio/ssl/verify_context.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// -// ssl/verify_context.hpp -// ~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_VERIFY_CONTEXT_HPP -#define ASIO_SSL_VERIFY_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/noncopyable.hpp" -#include "asio/ssl/detail/openssl_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -/// A simple wrapper around the X509_STORE_CTX type, used during verification of -/// a peer certificate. -/** - * @note The verify_context does not own the underlying X509_STORE_CTX object. - */ -class verify_context - : private noncopyable -{ -public: - /// The native handle type of the verification context. - typedef X509_STORE_CTX* native_handle_type; - - /// Constructor. - explicit verify_context(native_handle_type handle) - : handle_(handle) - { - } - - /// Get the underlying implementation in the native type. - /** - * This function may be used to obtain the underlying implementation of the - * context. This is intended to allow access to context functionality that is - * not otherwise provided. - */ - native_handle_type native_handle() - { - return handle_; - } - -private: - // The underlying native implementation. - native_handle_type handle_; -}; - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_VERIFY_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/ssl/verify_mode.hpp b/scout_sdk/asio/asio/ssl/verify_mode.hpp deleted file mode 100644 index 8c4b394..0000000 --- a/scout_sdk/asio/asio/ssl/verify_mode.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// -// ssl/verify_mode.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SSL_VERIFY_MODE_HPP -#define ASIO_SSL_VERIFY_MODE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/ssl/detail/openssl_types.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace ssl { - -/// Bitmask type for peer verification. -/** - * Possible values are: - * - * @li @ref verify_none - * @li @ref verify_peer - * @li @ref verify_fail_if_no_peer_cert - * @li @ref verify_client_once - */ -typedef int verify_mode; - -#if defined(GENERATING_DOCUMENTATION) -/// No verification. -const int verify_none = implementation_defined; - -/// Verify the peer. -const int verify_peer = implementation_defined; - -/// Fail verification if the peer has no certificate. Ignored unless -/// @ref verify_peer is set. -const int verify_fail_if_no_peer_cert = implementation_defined; - -/// Do not request client certificate on renegotiation. Ignored unless -/// @ref verify_peer is set. -const int verify_client_once = implementation_defined; -#else -const int verify_none = SSL_VERIFY_NONE; -const int verify_peer = SSL_VERIFY_PEER; -const int verify_fail_if_no_peer_cert = SSL_VERIFY_FAIL_IF_NO_PEER_CERT; -const int verify_client_once = SSL_VERIFY_CLIENT_ONCE; -#endif - -} // namespace ssl -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SSL_VERIFY_MODE_HPP diff --git a/scout_sdk/asio/asio/steady_timer.hpp b/scout_sdk/asio/asio/steady_timer.hpp deleted file mode 100644 index 3ede208..0000000 --- a/scout_sdk/asio/asio/steady_timer.hpp +++ /dev/null @@ -1,42 +0,0 @@ -// -// steady_timer.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_STEADY_TIMER_HPP -#define ASIO_STEADY_TIMER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_waitable_timer.hpp" -#include "asio/detail/chrono.hpp" - -namespace asio { - -/// Typedef for a timer based on the steady clock. -/** - * This typedef uses the C++11 @c <chrono> standard library facility, if - * available. Otherwise, it may use the Boost.Chrono library. To explicitly - * utilise Boost.Chrono, use the basic_waitable_timer template directly: - * @code - * typedef basic_waitable_timer timer; - * @endcode - */ -typedef basic_waitable_timer steady_timer; - -} // namespace asio - -#endif // defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_STEADY_TIMER_HPP diff --git a/scout_sdk/asio/asio/strand.hpp b/scout_sdk/asio/asio/strand.hpp deleted file mode 100644 index ea78ef0..0000000 --- a/scout_sdk/asio/asio/strand.hpp +++ /dev/null @@ -1,286 +0,0 @@ -// -// strand.hpp -// ~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_STRAND_HPP -#define ASIO_STRAND_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/strand_executor_service.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Provides serialised function invocation for any executor type. -template -class strand -{ -public: - /// The type of the underlying executor. - typedef Executor inner_executor_type; - - /// Default constructor. - /** - * This constructor is only valid if the underlying executor type is default - * constructible. - */ - strand() - : executor_(), - impl_(use_service( - executor_.context()).create_implementation()) - { - } - - /// Construct a strand for the specified executor. - explicit strand(const Executor& e) - : executor_(e), - impl_(use_service( - executor_.context()).create_implementation()) - { - } - - /// Copy constructor. - strand(const strand& other) ASIO_NOEXCEPT - : executor_(other.executor_), - impl_(other.impl_) - { - } - - /// Converting constructor. - /** - * This constructor is only valid if the @c OtherExecutor type is convertible - * to @c Executor. - */ - template - strand( - const strand& other) ASIO_NOEXCEPT - : executor_(other.executor_), - impl_(other.impl_) - { - } - - /// Assignment operator. - strand& operator=(const strand& other) ASIO_NOEXCEPT - { - executor_ = other.executor_; - impl_ = other.impl_; - return *this; - } - - /// Converting assignment operator. - /** - * This assignment operator is only valid if the @c OtherExecutor type is - * convertible to @c Executor. - */ - template - strand& operator=( - const strand& other) ASIO_NOEXCEPT - { - executor_ = other.executor_; - impl_ = other.impl_; - return *this; - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move constructor. - strand(strand&& other) ASIO_NOEXCEPT - : executor_(ASIO_MOVE_CAST(Executor)(other.executor_)), - impl_(ASIO_MOVE_CAST(implementation_type)(other.impl_)) - { - } - - /// Converting move constructor. - /** - * This constructor is only valid if the @c OtherExecutor type is convertible - * to @c Executor. - */ - template - strand(strand&& other) ASIO_NOEXCEPT - : executor_(ASIO_MOVE_CAST(OtherExecutor)(other)), - impl_(ASIO_MOVE_CAST(implementation_type)(other.impl_)) - { - } - - /// Move assignment operator. - strand& operator=(strand&& other) ASIO_NOEXCEPT - { - executor_ = ASIO_MOVE_CAST(Executor)(other); - impl_ = ASIO_MOVE_CAST(implementation_type)(other.impl_); - return *this; - } - - /// Converting move assignment operator. - /** - * This assignment operator is only valid if the @c OtherExecutor type is - * convertible to @c Executor. - */ - template - strand& operator=( - const strand&& other) ASIO_NOEXCEPT - { - executor_ = ASIO_MOVE_CAST(OtherExecutor)(other); - impl_ = ASIO_MOVE_CAST(implementation_type)(other.impl_); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destructor. - ~strand() - { - } - - /// Obtain the underlying executor. - inner_executor_type get_inner_executor() const ASIO_NOEXCEPT - { - return executor_; - } - - /// Obtain the underlying execution context. - execution_context& context() const ASIO_NOEXCEPT - { - return executor_.context(); - } - - /// Inform the strand that it has some outstanding work to do. - /** - * The strand delegates this call to its underlying executor. - */ - void on_work_started() const ASIO_NOEXCEPT - { - executor_.on_work_started(); - } - - /// Inform the strand that some work is no longer outstanding. - /** - * The strand delegates this call to its underlying executor. - */ - void on_work_finished() const ASIO_NOEXCEPT - { - executor_.on_work_finished(); - } - - /// Request the strand to invoke the given function object. - /** - * This function is used to ask the strand to execute the given function - * object on its underlying executor. The function object will be executed - * inside this function if the strand is not otherwise busy and if the - * underlying executor's @c dispatch() function is also able to execute the - * function before returning. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void dispatch(ASIO_MOVE_ARG(Function) f, const Allocator& a) const - { - detail::strand_executor_service::dispatch(impl_, - executor_, ASIO_MOVE_CAST(Function)(f), a); - } - - /// Request the strand to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object will never be executed inside this function. - * Instead, it will be scheduled by the underlying executor's defer function. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void post(ASIO_MOVE_ARG(Function) f, const Allocator& a) const - { - detail::strand_executor_service::post(impl_, - executor_, ASIO_MOVE_CAST(Function)(f), a); - } - - /// Request the strand to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object will never be executed inside this function. - * Instead, it will be scheduled by the underlying executor's defer function. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void defer(ASIO_MOVE_ARG(Function) f, const Allocator& a) const - { - detail::strand_executor_service::defer(impl_, - executor_, ASIO_MOVE_CAST(Function)(f), a); - } - - /// Determine whether the strand is running in the current thread. - /** - * @return @c true if the current thread is executing a function that was - * submitted to the strand using post(), dispatch() or defer(). Otherwise - * returns @c false. - */ - bool running_in_this_thread() const ASIO_NOEXCEPT - { - return detail::strand_executor_service::running_in_this_thread(impl_); - } - - /// Compare two strands for equality. - /** - * Two strands are equal if they refer to the same ordered, non-concurrent - * state. - */ - friend bool operator==(const strand& a, const strand& b) ASIO_NOEXCEPT - { - return a.impl_ == b.impl_; - } - - /// Compare two strands for inequality. - /** - * Two strands are equal if they refer to the same ordered, non-concurrent - * state. - */ - friend bool operator!=(const strand& a, const strand& b) ASIO_NOEXCEPT - { - return a.impl_ != b.impl_; - } - -private: - Executor executor_; - typedef detail::strand_executor_service::implementation_type - implementation_type; - implementation_type impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -// If both io_context.hpp and strand.hpp have been included, automatically -// include the header file needed for the io_context::strand class. -#if !defined(ASIO_NO_EXTENSIONS) -# if defined(ASIO_IO_CONTEXT_HPP) -# include "asio/io_context_strand.hpp" -# endif // defined(ASIO_IO_CONTEXT_HPP) -#endif // !defined(ASIO_NO_EXTENSIONS) - -#endif // ASIO_STRAND_HPP diff --git a/scout_sdk/asio/asio/stream_socket_service.hpp b/scout_sdk/asio/asio/stream_socket_service.hpp deleted file mode 100644 index 91b0a71..0000000 --- a/scout_sdk/asio/asio/stream_socket_service.hpp +++ /dev/null @@ -1,412 +0,0 @@ -// -// stream_socket_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_STREAM_SOCKET_SERVICE_HPP -#define ASIO_STREAM_SOCKET_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/type_traits.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_WINDOWS_RUNTIME) -# include "asio/detail/winrt_ssocket_service.hpp" -#elif defined(ASIO_HAS_IOCP) -# include "asio/detail/win_iocp_socket_service.hpp" -#else -# include "asio/detail/reactive_socket_service.hpp" -#endif - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a stream socket. -template -class stream_socket_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The protocol type. - typedef Protocol protocol_type; - - /// The endpoint type. - typedef typename Protocol::endpoint endpoint_type; - -private: - // The type of the platform-specific implementation. -#if defined(ASIO_WINDOWS_RUNTIME) - typedef detail::winrt_ssocket_service service_impl_type; -#elif defined(ASIO_HAS_IOCP) - typedef detail::win_iocp_socket_service service_impl_type; -#else - typedef detail::reactive_socket_service service_impl_type; -#endif - -public: - /// The type of a stream socket implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// The native socket type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef typename service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new stream socket service for the specified io_context. - explicit stream_socket_service(asio::io_context& io_context) - : asio::detail::service_base< - stream_socket_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new stream socket implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new stream socket implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another stream socket implementation. - void move_assign(implementation_type& impl, - stream_socket_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } - - // All socket services have access to each other's implementations. - template friend class stream_socket_service; - - /// Move-construct a new stream socket implementation from another protocol - /// type. - template - void converting_move_construct(implementation_type& impl, - stream_socket_service& other_service, - typename stream_socket_service< - Protocol1>::implementation_type& other_impl, - typename enable_if::value>::type* = 0) - { - service_impl_.template converting_move_construct( - impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a stream socket implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Open a stream socket. - ASIO_SYNC_OP_VOID open(implementation_type& impl, - const protocol_type& protocol, asio::error_code& ec) - { - if (protocol.type() == ASIO_OS_DEF(SOCK_STREAM)) - service_impl_.open(impl, protocol, ec); - else - ec = asio::error::invalid_argument; - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Assign an existing native socket to a stream socket. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const protocol_type& protocol, const native_handle_type& native_socket, - asio::error_code& ec) - { - service_impl_.assign(impl, protocol, native_socket, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a stream socket implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Release ownership of the underlying socket. - native_handle_type release(implementation_type& impl, - asio::error_code& ec) - { - return service_impl_.release(impl, ec); - } - - /// Get the native socket implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the socket. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the socket is at the out-of-band data mark. - bool at_mark(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.at_mark(impl, ec); - } - - /// Determine the number of bytes available for reading. - std::size_t available(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.available(impl, ec); - } - - /// Bind the stream socket to the specified local endpoint. - ASIO_SYNC_OP_VOID bind(implementation_type& impl, - const endpoint_type& endpoint, asio::error_code& ec) - { - service_impl_.bind(impl, endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Connect the stream socket to the specified endpoint. - ASIO_SYNC_OP_VOID connect(implementation_type& impl, - const endpoint_type& peer_endpoint, asio::error_code& ec) - { - service_impl_.connect(impl, peer_endpoint, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Start an asynchronous connect. - template - ASIO_INITFN_RESULT_TYPE(ConnectHandler, - void (asio::error_code)) - async_connect(implementation_type& impl, - const endpoint_type& peer_endpoint, - ASIO_MOVE_ARG(ConnectHandler) handler) - { - async_completion init(handler); - - service_impl_.async_connect(impl, peer_endpoint, init.completion_handler); - - return init.result.get(); - } - - /// Set a socket option. - template - ASIO_SYNC_OP_VOID set_option(implementation_type& impl, - const SettableSocketOption& option, asio::error_code& ec) - { - service_impl_.set_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get a socket option. - template - ASIO_SYNC_OP_VOID get_option(const implementation_type& impl, - GettableSocketOption& option, asio::error_code& ec) const - { - service_impl_.get_option(impl, option, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform an IO control command on the socket. - template - ASIO_SYNC_OP_VOID io_control(implementation_type& impl, - IoControlCommand& command, asio::error_code& ec) - { - service_impl_.io_control(impl, command, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the socket. - bool non_blocking(const implementation_type& impl) const - { - return service_impl_.non_blocking(impl); - } - - /// Sets the non-blocking mode of the socket. - ASIO_SYNC_OP_VOID non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Gets the non-blocking mode of the native socket implementation. - bool native_non_blocking(const implementation_type& impl) const - { - return service_impl_.native_non_blocking(impl); - } - - /// Sets the non-blocking mode of the native socket implementation. - ASIO_SYNC_OP_VOID native_non_blocking(implementation_type& impl, - bool mode, asio::error_code& ec) - { - service_impl_.native_non_blocking(impl, mode, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the local endpoint. - endpoint_type local_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.local_endpoint(impl, ec); - } - - /// Get the remote endpoint. - endpoint_type remote_endpoint(const implementation_type& impl, - asio::error_code& ec) const - { - return service_impl_.remote_endpoint(impl, ec); - } - - /// Disable sends or receives on the socket. - ASIO_SYNC_OP_VOID shutdown(implementation_type& impl, - socket_base::shutdown_type what, asio::error_code& ec) - { - service_impl_.shutdown(impl, what, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Wait for the socket to become ready to read, ready to write, or to have - /// pending error conditions. - ASIO_SYNC_OP_VOID wait(implementation_type& impl, - socket_base::wait_type w, asio::error_code& ec) - { - service_impl_.wait(impl, w, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Asynchronously wait for the socket to become ready to read, ready to - /// write, or to have pending error conditions. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, socket_base::wait_type w, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, w, init.completion_handler); - - return init.result.get(); - } - - /// Send the given data to the peer. - template - std::size_t send(implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.send(impl, buffers, flags, ec); - } - - /// Start an asynchronous send. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_send(implementation_type& impl, - const ConstBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(WriteHandler) handler) - { - async_completion init(handler); - - service_impl_.async_send(impl, buffers, flags, init.completion_handler); - - return init.result.get(); - } - - /// Receive some data from the peer. - template - std::size_t receive(implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, asio::error_code& ec) - { - return service_impl_.receive(impl, buffers, flags, ec); - } - - /// Start an asynchronous receive. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_receive(implementation_type& impl, - const MutableBufferSequence& buffers, - socket_base::message_flags flags, - ASIO_MOVE_ARG(ReadHandler) handler) - { - async_completion init(handler); - - service_impl_.async_receive(impl, buffers, flags, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_STREAM_SOCKET_SERVICE_HPP diff --git a/scout_sdk/asio/asio/streambuf.hpp b/scout_sdk/asio/asio/streambuf.hpp deleted file mode 100644 index cb3f35f..0000000 --- a/scout_sdk/asio/asio/streambuf.hpp +++ /dev/null @@ -1,33 +0,0 @@ -// -// streambuf.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_STREAMBUF_HPP -#define ASIO_STREAMBUF_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_NO_IOSTREAM) - -#include "asio/basic_streambuf.hpp" - -namespace asio { - -/// Typedef for the typical usage of basic_streambuf. -typedef basic_streambuf<> streambuf; - -} // namespace asio - -#endif // !defined(ASIO_NO_IOSTREAM) - -#endif // ASIO_STREAMBUF_HPP diff --git a/scout_sdk/asio/asio/system_context.hpp b/scout_sdk/asio/asio/system_context.hpp deleted file mode 100644 index ccd1113..0000000 --- a/scout_sdk/asio/asio/system_context.hpp +++ /dev/null @@ -1,78 +0,0 @@ -// -// system_context.hpp -// ~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SYSTEM_CONTEXT_HPP -#define ASIO_SYSTEM_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/scheduler.hpp" -#include "asio/detail/thread_group.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -class system_executor; - -/// The executor context for the system executor. -class system_context : public execution_context -{ -public: - /// The executor type associated with the context. - typedef system_executor executor_type; - - /// Destructor shuts down all threads in the system thread pool. - ASIO_DECL ~system_context(); - - /// Obtain an executor for the context. - executor_type get_executor() ASIO_NOEXCEPT; - - /// Signal all threads in the system thread pool to stop. - ASIO_DECL void stop(); - - /// Determine whether the system thread pool has been stopped. - ASIO_DECL bool stopped() const ASIO_NOEXCEPT; - - /// Join all threads in the system thread pool. - ASIO_DECL void join(); - -#if defined(GENERATING_DOCUMENTATION) -private: -#endif // defined(GENERATING_DOCUMENTATION) - // Constructor creates all threads in the system thread pool. - ASIO_DECL system_context(); - -private: - friend class system_executor; - - struct thread_function; - - // The underlying scheduler. - detail::scheduler& scheduler_; - - // The threads in the system thread pool. - detail::thread_group threads_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/system_context.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/system_context.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_SYSTEM_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/system_error.hpp b/scout_sdk/asio/asio/system_error.hpp deleted file mode 100644 index 6390894..0000000 --- a/scout_sdk/asio/asio/system_error.hpp +++ /dev/null @@ -1,131 +0,0 @@ -// -// system_error.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SYSTEM_ERROR_HPP -#define ASIO_SYSTEM_ERROR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_SYSTEM_ERROR) -# include -#else // defined(ASIO_HAS_STD_SYSTEM_ERROR) -# include -# include -# include -# include "asio/error_code.hpp" -# include "asio/detail/scoped_ptr.hpp" -#endif // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -#if defined(ASIO_HAS_STD_SYSTEM_ERROR) - -typedef std::system_error system_error; - -#else // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -/// The system_error class is used to represent system conditions that -/// prevent the library from operating correctly. -class system_error - : public std::exception -{ -public: - /// Construct with an error code. - system_error(const error_code& ec) - : code_(ec), - context_() - { - } - - /// Construct with an error code and context. - system_error(const error_code& ec, const std::string& context) - : code_(ec), - context_(context) - { - } - - /// Copy constructor. - system_error(const system_error& other) - : std::exception(other), - code_(other.code_), - context_(other.context_), - what_() - { - } - - /// Destructor. - virtual ~system_error() throw () - { - } - - /// Assignment operator. - system_error& operator=(const system_error& e) - { - context_ = e.context_; - code_ = e.code_; - what_.reset(); - return *this; - } - - /// Get a string representation of the exception. - virtual const char* what() const throw () - { -#if !defined(ASIO_NO_EXCEPTIONS) - try -#endif // !defined(ASIO_NO_EXCEPTIONS) - { - if (!what_.get()) - { - std::string tmp(context_); - if (tmp.length()) - tmp += ": "; - tmp += code_.message(); - what_.reset(new std::string(tmp)); - } - return what_->c_str(); - } -#if !defined(ASIO_NO_EXCEPTIONS) - catch (std::exception&) - { - return "system_error"; - } -#endif // !defined(ASIO_NO_EXCEPTIONS) - } - - /// Get the error code associated with the exception. - error_code code() const - { - return code_; - } - -private: - // The code associated with the error. - error_code code_; - - // The context associated with the error. - std::string context_; - - // The string representation of the error. - mutable asio::detail::scoped_ptr what_; -}; - -#endif // defined(ASIO_HAS_STD_SYSTEM_ERROR) - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_SYSTEM_ERROR_HPP diff --git a/scout_sdk/asio/asio/system_executor.hpp b/scout_sdk/asio/asio/system_executor.hpp deleted file mode 100644 index b588a21..0000000 --- a/scout_sdk/asio/asio/system_executor.hpp +++ /dev/null @@ -1,129 +0,0 @@ -// -// system_executor.hpp -// ~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SYSTEM_EXECUTOR_HPP -#define ASIO_SYSTEM_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -class system_context; - -/// An executor that uses arbitrary threads. -/** - * The system executor represents an execution context where functions are - * permitted to run on arbitrary threads. The post() and defer() functions - * schedule the function to run on an unspecified system thread pool, and - * dispatch() invokes the function immediately. - */ -class system_executor -{ -public: - /// Obtain the underlying execution context. - system_context& context() const ASIO_NOEXCEPT; - - /// Inform the executor that it has some outstanding work to do. - /** - * For the system executor, this is a no-op. - */ - void on_work_started() const ASIO_NOEXCEPT - { - } - - /// Inform the executor that some work is no longer outstanding. - /** - * For the system executor, this is a no-op. - */ - void on_work_finished() const ASIO_NOEXCEPT - { - } - - /// Request the system executor to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object will always be executed inside this function. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void dispatch(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the system executor to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object will never be executed inside this function. - * Instead, it will be scheduled to run on an unspecified system thread pool. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void post(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the system executor to invoke the given function object. - /** - * This function is used to ask the executor to execute the given function - * object. The function object will never be executed inside this function. - * Instead, it will be scheduled to run on an unspecified system thread pool. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void defer(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Compare two executors for equality. - /** - * System executors always compare equal. - */ - friend bool operator==(const system_executor&, - const system_executor&) ASIO_NOEXCEPT - { - return true; - } - - /// Compare two executors for inequality. - /** - * System executors always compare equal. - */ - friend bool operator!=(const system_executor&, - const system_executor&) ASIO_NOEXCEPT - { - return false; - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/system_executor.hpp" - -#endif // ASIO_SYSTEM_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/system_timer.hpp b/scout_sdk/asio/asio/system_timer.hpp deleted file mode 100644 index e75e7d4..0000000 --- a/scout_sdk/asio/asio/system_timer.hpp +++ /dev/null @@ -1,42 +0,0 @@ -// -// system_timer.hpp -// ~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_SYSTEM_TIMER_HPP -#define ASIO_SYSTEM_TIMER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_waitable_timer.hpp" -#include "asio/detail/chrono.hpp" - -namespace asio { - -/// Typedef for a timer based on the system clock. -/** - * This typedef uses the C++11 @c <chrono> standard library facility, if - * available. Otherwise, it may use the Boost.Chrono library. To explicitly - * utilise Boost.Chrono, use the basic_waitable_timer template directly: - * @code - * typedef basic_waitable_timer timer; - * @endcode - */ -typedef basic_waitable_timer system_timer; - -} // namespace asio - -#endif // defined(ASIO_HAS_CHRONO) || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_SYSTEM_TIMER_HPP diff --git a/scout_sdk/asio/asio/thread.hpp b/scout_sdk/asio/asio/thread.hpp deleted file mode 100644 index eeeef7b..0000000 --- a/scout_sdk/asio/asio/thread.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// -// thread.hpp -// ~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_THREAD_HPP -#define ASIO_THREAD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/thread.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// A simple abstraction for starting threads. -/** - * The asio::thread class implements the smallest possible subset of the - * functionality of boost::thread. It is intended to be used only for starting - * a thread and waiting for it to exit. If more extensive threading - * capabilities are required, you are strongly advised to use something else. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Example - * A typical use of asio::thread would be to launch a thread to run an - * io_context's event processing loop: - * - * @par - * @code asio::io_context io_context; - * // ... - * asio::thread t(boost::bind(&asio::io_context::run, &io_context)); - * // ... - * t.join(); @endcode - */ -class thread - : private noncopyable -{ -public: - /// Start a new thread that executes the supplied function. - /** - * This constructor creates a new thread that will execute the given function - * or function object. - * - * @param f The function or function object to be run in the thread. The - * function signature must be: @code void f(); @endcode - */ - template - explicit thread(Function f) - : impl_(f) - { - } - - /// Destructor. - ~thread() - { - } - - /// Wait for the thread to exit. - /** - * This function will block until the thread has exited. - * - * If this function is not called before the thread object is destroyed, the - * thread itself will continue to run until completion. You will, however, - * no longer have the ability to wait for it to exit. - */ - void join() - { - impl_.join(); - } - -private: - detail::thread impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_THREAD_HPP diff --git a/scout_sdk/asio/asio/thread_pool.hpp b/scout_sdk/asio/asio/thread_pool.hpp deleted file mode 100644 index f22f18d..0000000 --- a/scout_sdk/asio/asio/thread_pool.hpp +++ /dev/null @@ -1,232 +0,0 @@ -// -// thread_pool.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_THREAD_POOL_HPP -#define ASIO_THREAD_POOL_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/scheduler.hpp" -#include "asio/detail/thread_group.hpp" -#include "asio/execution_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// A simple fixed-size thread pool. -/** - * The thread pool class is an execution context where functions are permitted - * to run on one of a fixed number of threads. - * - * @par Submitting tasks to the pool - * - * To submit functions to the io_context, use the @ref asio::dispatch, - * @ref asio::post or @ref asio::defer free functions. - * - * For example: - * - * @code void my_task() - * { - * ... - * } - * - * ... - * - * // Launch the pool with four threads. - * asio::thread_pool pool(4); - * - * // Submit a function to the pool. - * asio::post(pool, my_task); - * - * // Submit a lambda object to the pool. - * asio::post(pool, - * []() - * { - * ... - * }); - * - * // Wait for all tasks in the pool to complete. - * pool.join(); @endcode - */ -class thread_pool - : public execution_context -{ -public: - class executor_type; - - /// Constructs a pool with an automatically determined number of threads. - ASIO_DECL thread_pool(); - - /// Constructs a pool with a specified number of threads. - ASIO_DECL thread_pool(std::size_t num_threads); - - /// Destructor. - /** - * Automatically stops and joins the pool, if not explicitly done beforehand. - */ - ASIO_DECL ~thread_pool(); - - /// Obtains the executor associated with the pool. - executor_type get_executor() ASIO_NOEXCEPT; - - /// Stops the threads. - /** - * This function stops the threads as soon as possible. As a result of calling - * @c stop(), pending function objects may be never be invoked. - */ - ASIO_DECL void stop(); - - /// Joins the threads. - /** - * This function blocks until the threads in the pool have completed. If @c - * stop() is not called prior to @c join(), the @c join() call will wait - * until the pool has no more outstanding work. - */ - ASIO_DECL void join(); - -private: - friend class executor_type; - struct thread_function; - - // The underlying scheduler. - detail::scheduler& scheduler_; - - // The threads in the pool. - detail::thread_group threads_; -}; - -/// Executor used to submit functions to a thread pool. -class thread_pool::executor_type -{ -public: - /// Obtain the underlying execution context. - thread_pool& context() const ASIO_NOEXCEPT; - - /// Inform the thread pool that it has some outstanding work to do. - /** - * This function is used to inform the thread pool that some work has begun. - * This ensures that the thread pool's join() function will not return while - * the work is underway. - */ - void on_work_started() const ASIO_NOEXCEPT; - - /// Inform the thread pool that some work is no longer outstanding. - /** - * This function is used to inform the thread pool that some work has - * finished. Once the count of unfinished work reaches zero, the thread - * pool's join() function is permitted to exit. - */ - void on_work_finished() const ASIO_NOEXCEPT; - - /// Request the thread pool to invoke the given function object. - /** - * This function is used to ask the thread pool to execute the given function - * object. If the current thread belongs to the pool, @c dispatch() executes - * the function before returning. Otherwise, the function will be scheduled - * to run on the thread pool. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void dispatch(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the thread pool to invoke the given function object. - /** - * This function is used to ask the thread pool to execute the given function - * object. The function object will never be executed inside @c post(). - * Instead, it will be scheduled to run on the thread pool. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void post(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Request the thread pool to invoke the given function object. - /** - * This function is used to ask the thread pool to execute the given function - * object. The function object will never be executed inside @c defer(). - * Instead, it will be scheduled to run on the thread pool. - * - * If the current thread belongs to the thread pool, @c defer() will delay - * scheduling the function object until the current thread returns control to - * the pool. - * - * @param f The function object to be called. The executor will make - * a copy of the handler object as required. The function signature of the - * function object must be: @code void function(); @endcode - * - * @param a An allocator that may be used by the executor to allocate the - * internal storage needed for function invocation. - */ - template - void defer(ASIO_MOVE_ARG(Function) f, const Allocator& a) const; - - /// Determine whether the thread pool is running in the current thread. - /** - * @return @c true if the current thread belongs to the pool. Otherwise - * returns @c false. - */ - bool running_in_this_thread() const ASIO_NOEXCEPT; - - /// Compare two executors for equality. - /** - * Two executors are equal if they refer to the same underlying thread pool. - */ - friend bool operator==(const executor_type& a, - const executor_type& b) ASIO_NOEXCEPT - { - return &a.pool_ == &b.pool_; - } - - /// Compare two executors for inequality. - /** - * Two executors are equal if they refer to the same underlying thread pool. - */ - friend bool operator!=(const executor_type& a, - const executor_type& b) ASIO_NOEXCEPT - { - return &a.pool_ != &b.pool_; - } - -private: - friend class thread_pool; - - // Constructor. - explicit executor_type(thread_pool& p) : pool_(p) {} - - // The underlying thread pool. - thread_pool& pool_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/thread_pool.hpp" -#if defined(ASIO_HEADER_ONLY) -# include "asio/impl/thread_pool.ipp" -#endif // defined(ASIO_HEADER_ONLY) - -#endif // ASIO_THREAD_POOL_HPP diff --git a/scout_sdk/asio/asio/time_traits.hpp b/scout_sdk/asio/asio/time_traits.hpp deleted file mode 100644 index 72f4aab..0000000 --- a/scout_sdk/asio/asio/time_traits.hpp +++ /dev/null @@ -1,86 +0,0 @@ -// -// time_traits.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TIME_TRAITS_HPP -#define ASIO_TIME_TRAITS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/socket_types.hpp" // Must come before posix_time. - -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - || defined(GENERATING_DOCUMENTATION) - -#include - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Time traits suitable for use with the deadline timer. -template -struct time_traits; - -/// Time traits specialised for posix_time. -template <> -struct time_traits -{ - /// The time type. - typedef boost::posix_time::ptime time_type; - - /// The duration type. - typedef boost::posix_time::time_duration duration_type; - - /// Get the current time. - static time_type now() - { -#if defined(BOOST_DATE_TIME_HAS_HIGH_PRECISION_CLOCK) - return boost::posix_time::microsec_clock::universal_time(); -#else // defined(BOOST_DATE_TIME_HAS_HIGH_PRECISION_CLOCK) - return boost::posix_time::second_clock::universal_time(); -#endif // defined(BOOST_DATE_TIME_HAS_HIGH_PRECISION_CLOCK) - } - - /// Add a duration to a time. - static time_type add(const time_type& t, const duration_type& d) - { - return t + d; - } - - /// Subtract one time from another. - static duration_type subtract(const time_type& t1, const time_type& t2) - { - return t1 - t2; - } - - /// Test whether one time is less than another. - static bool less_than(const time_type& t1, const time_type& t2) - { - return t1 < t2; - } - - /// Convert to POSIX duration type. - static boost::posix_time::time_duration to_posix_duration( - const duration_type& d) - { - return d; - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_TIME_TRAITS_HPP diff --git a/scout_sdk/asio/asio/ts/buffer.hpp b/scout_sdk/asio/asio/ts/buffer.hpp deleted file mode 100644 index faf08a4..0000000 --- a/scout_sdk/asio/asio/ts/buffer.hpp +++ /dev/null @@ -1,24 +0,0 @@ -// -// ts/buffer.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_BUFFER_HPP -#define ASIO_TS_BUFFER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/buffer.hpp" -#include "asio/completion_condition.hpp" -#include "asio/read.hpp" -#include "asio/write.hpp" -#include "asio/read_until.hpp" - -#endif // ASIO_TS_BUFFER_HPP diff --git a/scout_sdk/asio/asio/ts/executor.hpp b/scout_sdk/asio/asio/ts/executor.hpp deleted file mode 100644 index 8669cb6..0000000 --- a/scout_sdk/asio/asio/ts/executor.hpp +++ /dev/null @@ -1,35 +0,0 @@ -// -// ts/executor.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_EXECUTOR_HPP -#define ASIO_TS_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/handler_type.hpp" -#include "asio/async_result.hpp" -#include "asio/associated_allocator.hpp" -#include "asio/execution_context.hpp" -#include "asio/is_executor.hpp" -#include "asio/associated_executor.hpp" -#include "asio/bind_executor.hpp" -#include "asio/executor_work_guard.hpp" -#include "asio/system_executor.hpp" -#include "asio/executor.hpp" -#include "asio/dispatch.hpp" -#include "asio/post.hpp" -#include "asio/defer.hpp" -#include "asio/strand.hpp" -#include "asio/packaged_task.hpp" -#include "asio/use_future.hpp" - -#endif // ASIO_TS_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/ts/internet.hpp b/scout_sdk/asio/asio/ts/internet.hpp deleted file mode 100644 index 6282e90..0000000 --- a/scout_sdk/asio/asio/ts/internet.hpp +++ /dev/null @@ -1,40 +0,0 @@ -// -// ts/internet.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_INTERNET_HPP -#define ASIO_TS_INTERNET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/ip/address.hpp" -#include "asio/ip/address_v4.hpp" -#include "asio/ip/address_v4_iterator.hpp" -#include "asio/ip/address_v4_range.hpp" -#include "asio/ip/address_v6.hpp" -#include "asio/ip/address_v6_iterator.hpp" -#include "asio/ip/address_v6_range.hpp" -#include "asio/ip/bad_address_cast.hpp" -#include "asio/ip/basic_endpoint.hpp" -#include "asio/ip/basic_resolver_query.hpp" -#include "asio/ip/basic_resolver_entry.hpp" -#include "asio/ip/basic_resolver_iterator.hpp" -#include "asio/ip/basic_resolver.hpp" -#include "asio/ip/host_name.hpp" -#include "asio/ip/network_v4.hpp" -#include "asio/ip/network_v6.hpp" -#include "asio/ip/tcp.hpp" -#include "asio/ip/udp.hpp" -#include "asio/ip/v6_only.hpp" -#include "asio/ip/unicast.hpp" -#include "asio/ip/multicast.hpp" - -#endif // ASIO_TS_INTERNET_HPP diff --git a/scout_sdk/asio/asio/ts/io_context.hpp b/scout_sdk/asio/asio/ts/io_context.hpp deleted file mode 100644 index b967cd6..0000000 --- a/scout_sdk/asio/asio/ts/io_context.hpp +++ /dev/null @@ -1,20 +0,0 @@ -// -// ts/io_context.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_IO_CONTEXT_HPP -#define ASIO_TS_IO_CONTEXT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/io_context.hpp" - -#endif // ASIO_TS_IO_CONTEXT_HPP diff --git a/scout_sdk/asio/asio/ts/net.hpp b/scout_sdk/asio/asio/ts/net.hpp deleted file mode 100644 index f96075d..0000000 --- a/scout_sdk/asio/asio/ts/net.hpp +++ /dev/null @@ -1,26 +0,0 @@ -// -// ts/net.hpp -// ~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_NET_HPP -#define ASIO_TS_NET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/ts/netfwd.hpp" -#include "asio/ts/executor.hpp" -#include "asio/ts/io_context.hpp" -#include "asio/ts/timer.hpp" -#include "asio/ts/buffer.hpp" -#include "asio/ts/socket.hpp" -#include "asio/ts/internet.hpp" - -#endif // ASIO_TS_NET_HPP diff --git a/scout_sdk/asio/asio/ts/netfwd.hpp b/scout_sdk/asio/asio/ts/netfwd.hpp deleted file mode 100644 index 657a21d..0000000 --- a/scout_sdk/asio/asio/ts/netfwd.hpp +++ /dev/null @@ -1,197 +0,0 @@ -// -// ts/netfwd.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_NETFWD_HPP -#define ASIO_TS_NETFWD_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_CHRONO) -# include "asio/detail/chrono.hpp" -#endif // defined(ASIO_HAS_CHRONO) - -#if defined(ASIO_HAS_BOOST_DATE_TIME) -# include "asio/detail/date_time_fwd.hpp" -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - -#if !defined(GENERATING_DOCUMENTATION) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -class execution_context; - -template -class executor_binder; - -template -class executor_work_guard; - -class system_executor; - -class executor; - -template -class strand; - -class io_context; - -template -struct wait_traits; - -#if defined(ASIO_HAS_BOOST_DATE_TIME) - -template -struct time_traits; - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -template -class waitable_timer_service; - -#if defined(ASIO_HAS_BOOST_DATE_TIME) - -template -class deadline_timer_service; - -#endif // defined(ASIO_HAS_BOOST_DATE_TIME) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#if !defined(ASIO_BASIC_WAITABLE_TIMER_FWD_DECL) -#define ASIO_BASIC_WAITABLE_TIMER_FWD_DECL - -template - ASIO_SVC_TPARAM_DEF2(= waitable_timer_service)> -class basic_waitable_timer; - -#endif // !defined(ASIO_BASIC_WAITABLE_TIMER_FWD_DECL) - -#if defined(ASIO_HAS_CHRONO) - -typedef basic_waitable_timer system_timer; - -typedef basic_waitable_timer steady_timer; - -typedef basic_waitable_timer - high_resolution_timer; - -#endif // defined(ASIO_HAS_CHRONO) - -template -class basic_socket; - -template -class basic_datagram_socket; - -template -class basic_stream_socket; - -template -class basic_socket_acceptor; - -#if !defined(ASIO_BASIC_SOCKET_STREAMBUF_FWD_DECL) -#define ASIO_BASIC_SOCKET_STREAMBUF_FWD_DECL - -// Forward declaration with defaulted arguments. -template ), -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - || defined(GENERATING_DOCUMENTATION) - typename Clock = boost::posix_time::ptime, - typename WaitTraits = time_traits - ASIO_SVC_TPARAM1_DEF2(= deadline_timer_service)> -#else - typename Clock = chrono::steady_clock, - typename WaitTraits = wait_traits - ASIO_SVC_TPARAM1_DEF1(= steady_timer::service_type)> -#endif -class basic_socket_streambuf; - -#endif // !defined(ASIO_BASIC_SOCKET_STREAMBUF_FWD_DECL) - -#if !defined(ASIO_BASIC_SOCKET_IOSTREAM_FWD_DECL) -#define ASIO_BASIC_SOCKET_IOSTREAM_FWD_DECL - -// Forward declaration with defaulted arguments. -template ), -#if defined(ASIO_HAS_BOOST_DATE_TIME) \ - || defined(GENERATING_DOCUMENTATION) - typename Clock = boost::posix_time::ptime, - typename WaitTraits = time_traits - ASIO_SVC_TPARAM1_DEF2(= deadline_timer_service)> -#else - typename Clock = chrono::steady_clock, - typename WaitTraits = wait_traits - ASIO_SVC_TPARAM1_DEF1(= steady_timer::service_type)> -#endif -class basic_socket_iostream; - -#endif // !defined(ASIO_BASIC_SOCKET_IOSTREAM_FWD_DECL) - -namespace ip { - -class address; - -class address_v4; - -class address_v6; - -template -class basic_address_iterator; - -typedef basic_address_iterator address_v4_iterator; - -typedef basic_address_iterator address_v6_iterator; - -template -class basic_address_range; - -typedef basic_address_range address_v4_range; - -typedef basic_address_range address_v6_range; - -class network_v4; - -class network_v6; - -template -class basic_endpoint; - -template -class basic_resolver_entry; - -template -class basic_resolver_results; - -template -class basic_resolver; - -class tcp; - -class udp; - -} // namespace ip -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // !defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_TS_NETFWD_HPP diff --git a/scout_sdk/asio/asio/ts/socket.hpp b/scout_sdk/asio/asio/ts/socket.hpp deleted file mode 100644 index a542734..0000000 --- a/scout_sdk/asio/asio/ts/socket.hpp +++ /dev/null @@ -1,27 +0,0 @@ -// -// ts/socket.hpp -// ~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_SOCKET_HPP -#define ASIO_TS_SOCKET_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/socket_base.hpp" -#include "asio/basic_socket.hpp" -#include "asio/basic_datagram_socket.hpp" -#include "asio/basic_stream_socket.hpp" -#include "asio/basic_socket_acceptor.hpp" -#include "asio/basic_socket_streambuf.hpp" -#include "asio/basic_socket_iostream.hpp" -#include "asio/connect.hpp" - -#endif // ASIO_TS_SOCKET_HPP diff --git a/scout_sdk/asio/asio/ts/timer.hpp b/scout_sdk/asio/asio/ts/timer.hpp deleted file mode 100644 index 872be8b..0000000 --- a/scout_sdk/asio/asio/ts/timer.hpp +++ /dev/null @@ -1,26 +0,0 @@ -// -// ts/timer.hpp -// ~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_TS_TIMER_HPP -#define ASIO_TS_TIMER_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/chrono.hpp" - -#include "asio/wait_traits.hpp" -#include "asio/basic_waitable_timer.hpp" -#include "asio/system_timer.hpp" -#include "asio/steady_timer.hpp" -#include "asio/high_resolution_timer.hpp" - -#endif // ASIO_TS_TIMER_HPP diff --git a/scout_sdk/asio/asio/unyield.hpp b/scout_sdk/asio/asio/unyield.hpp deleted file mode 100644 index de3ed02..0000000 --- a/scout_sdk/asio/asio/unyield.hpp +++ /dev/null @@ -1,21 +0,0 @@ -// -// unyield.hpp -// ~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifdef reenter -# undef reenter -#endif - -#ifdef yield -# undef yield -#endif - -#ifdef fork -# undef fork -#endif diff --git a/scout_sdk/asio/asio/use_future.hpp b/scout_sdk/asio/asio/use_future.hpp deleted file mode 100644 index 3f9c696..0000000 --- a/scout_sdk/asio/asio/use_future.hpp +++ /dev/null @@ -1,159 +0,0 @@ -// -// use_future.hpp -// ~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_USE_FUTURE_HPP -#define ASIO_USE_FUTURE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_STD_FUTURE) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace detail { - -template -class packaged_token; - -template -class packaged_handler; - -} // namespace detail - -/// Class used to specify that an asynchronous operation should return a future. -/** - * The use_future_t class is used to indicate that an asynchronous operation - * should return a std::future object. A use_future_t object may be passed as a - * handler to an asynchronous operation, typically using the special value @c - * asio::use_future. For example: - * - * @code std::future my_future - * = my_socket.async_read_some(my_buffer, asio::use_future); @endcode - * - * The initiating function (async_read_some in the above example) returns a - * future that will receive the result of the operation. If the operation - * completes with an error_code indicating failure, it is converted into a - * system_error and passed back to the caller via the future. - */ -template > -class use_future_t -{ -public: - /// The allocator type. The allocator is used when constructing the - /// @c std::promise object for a given asynchronous operation. - typedef Allocator allocator_type; - - /// Construct using default-constructed allocator. - ASIO_CONSTEXPR use_future_t() - { - } - - /// Construct using specified allocator. - explicit use_future_t(const Allocator& allocator) - : allocator_(allocator) - { - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use rebind().) Specify an alternate allocator. - template - use_future_t operator[](const OtherAllocator& allocator) const - { - return use_future_t(allocator); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Specify an alternate allocator. - template - use_future_t rebind(const OtherAllocator& allocator) const - { - return use_future_t(allocator); - } - - /// Obtain allocator. - allocator_type get_allocator() const - { - return allocator_; - } - - /// Wrap a function object in a packaged task. - /** - * The @c package function is used to adapt a function object as a packaged - * task. When this adapter is passed as a completion token to an asynchronous - * operation, the result of the function object is retuned via a std::future. - * - * @par Example - * - * @code std::future fut = - * my_socket.async_read_some(buffer, - * use_future([](asio::error_code ec, std::size_t n) - * { - * return ec ? 0 : n; - * })); - * ... - * std::size_t n = fut.get(); @endcode - */ - template -#if defined(GENERATING_DOCUMENTATION) - unspecified -#else // defined(GENERATING_DOCUMENTATION) - detail::packaged_token::type, Allocator> -#endif // defined(GENERATING_DOCUMENTATION) - operator()(ASIO_MOVE_ARG(Function) f) const; - -private: - // Helper type to ensure that use_future can be constexpr default-constructed - // even when std::allocator can't be. - struct std_allocator_void - { - ASIO_CONSTEXPR std_allocator_void() - { - } - - operator std::allocator() const - { - return std::allocator(); - } - }; - - typename conditional< - is_same, Allocator>::value, - std_allocator_void, Allocator>::type allocator_; -}; - -/// A special value, similar to std::nothrow. -/** - * See the documentation for asio::use_future_t for a usage example. - */ -#if defined(ASIO_HAS_CONSTEXPR) || defined(GENERATING_DOCUMENTATION) -constexpr use_future_t<> use_future; -#elif defined(ASIO_MSVC) -__declspec(selectany) use_future_t<> use_future; -#endif - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/use_future.hpp" - -#endif // defined(ASIO_HAS_STD_FUTURE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_USE_FUTURE_HPP diff --git a/scout_sdk/asio/asio/uses_executor.hpp b/scout_sdk/asio/asio/uses_executor.hpp deleted file mode 100644 index e985c28..0000000 --- a/scout_sdk/asio/asio/uses_executor.hpp +++ /dev/null @@ -1,71 +0,0 @@ -// -// uses_executor.hpp -// ~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_USES_EXECUTOR_HPP -#define ASIO_USES_EXECUTOR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/detail/type_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// A special type, similar to std::nothrow_t, used to disambiguate -/// constructors that accept executor arguments. -/** - * The executor_arg_t struct is an empty structure type used as a unique type - * to disambiguate constructor and function overloading. Specifically, some - * types have constructors with executor_arg_t as the first argument, - * immediately followed by an argument of a type that satisfies the Executor - * type requirements. - */ -struct executor_arg_t -{ - /// Constructor. - ASIO_CONSTEXPR executor_arg_t() ASIO_NOEXCEPT - { - } -}; - -/// A special value, similar to std::nothrow, used to disambiguate constructors -/// that accept executor arguments. -/** - * See asio::executor_arg_t and asio::uses_executor - * for more information. - */ -#if defined(ASIO_HAS_CONSTEXPR) || defined(GENERATING_DOCUMENTATION) -constexpr executor_arg_t executor_arg; -#elif defined(ASIO_MSVC) -__declspec(selectany) executor_arg_t executor_arg; -#endif - -/// The uses_executor trait detects whether a type T has an associated executor -/// that is convertible from type Executor. -/** - * Meets the BinaryTypeTrait requirements. The Asio library provides a - * definition that is derived from false_type. A program may specialize this - * template to derive from true_type for a user-defined type T that can be - * constructed with an executor, where the first argument of a constructor has - * type executor_arg_t and the second argument is convertible from type - * Executor. - */ -template -struct uses_executor : false_type {}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_USES_EXECUTOR_HPP diff --git a/scout_sdk/asio/asio/version.hpp b/scout_sdk/asio/asio/version.hpp deleted file mode 100644 index 099ffdb..0000000 --- a/scout_sdk/asio/asio/version.hpp +++ /dev/null @@ -1,23 +0,0 @@ -// -// version.hpp -// ~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_VERSION_HPP -#define ASIO_VERSION_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -// ASIO_VERSION % 100 is the sub-minor version -// ASIO_VERSION / 100 % 1000 is the minor version -// ASIO_VERSION / 100000 is the major version -#define ASIO_VERSION 101201 // 1.12.1 - -#endif // ASIO_VERSION_HPP diff --git a/scout_sdk/asio/asio/wait_traits.hpp b/scout_sdk/asio/asio/wait_traits.hpp deleted file mode 100644 index a6016f7..0000000 --- a/scout_sdk/asio/asio/wait_traits.hpp +++ /dev/null @@ -1,56 +0,0 @@ -// -// wait_traits.hpp -// ~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WAIT_TRAITS_HPP -#define ASIO_WAIT_TRAITS_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Wait traits suitable for use with the basic_waitable_timer class template. -template -struct wait_traits -{ - /// Convert a clock duration into a duration used for waiting. - /** - * @returns @c d. - */ - static typename Clock::duration to_wait_duration( - const typename Clock::duration& d) - { - return d; - } - - /// Convert a clock duration into a duration used for waiting. - /** - * @returns @c d. - */ - static typename Clock::duration to_wait_duration( - const typename Clock::time_point& t) - { - typename Clock::time_point now = Clock::now(); - if (now + (Clock::duration::max)() < t) - return (Clock::duration::max)(); - if (now + (Clock::duration::min)() > t) - return (Clock::duration::min)(); - return t - now; - } -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // ASIO_WAIT_TRAITS_HPP diff --git a/scout_sdk/asio/asio/waitable_timer_service.hpp b/scout_sdk/asio/asio/waitable_timer_service.hpp deleted file mode 100644 index 75e496f..0000000 --- a/scout_sdk/asio/asio/waitable_timer_service.hpp +++ /dev/null @@ -1,210 +0,0 @@ -// -// waitable_timer_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WAITABLE_TIMER_SERVICE_HPP -#define ASIO_WAITABLE_TIMER_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/chrono_time_traits.hpp" -#include "asio/detail/deadline_timer_service.hpp" -#include "asio/io_context.hpp" -#include "asio/wait_traits.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/// Default service implementation for a timer. -template > -class waitable_timer_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base< - waitable_timer_service > -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - - /// The clock type. - typedef Clock clock_type; - - /// The duration type of the clock. - typedef typename clock_type::duration duration; - - /// The time point type of the clock. - typedef typename clock_type::time_point time_point; - - /// The wait traits type. - typedef WaitTraits traits_type; - -private: - // The type of the platform-specific implementation. - typedef detail::deadline_timer_service< - detail::chrono_time_traits > service_impl_type; - -public: - /// The implementation type of the waitable timer. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef typename service_impl_type::implementation_type implementation_type; -#endif - - /// Construct a new timer service for the specified io_context. - explicit waitable_timer_service(asio::io_context& io_context) - : asio::detail::service_base< - waitable_timer_service >(io_context), - service_impl_(io_context) - { - } - - /// Construct a new timer implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - - /// Destroy a timer implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new timer implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another timer implementation. - void move_assign(implementation_type& impl, - waitable_timer_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Cancel any asynchronous wait operations associated with the timer. - std::size_t cancel(implementation_type& impl, asio::error_code& ec) - { - return service_impl_.cancel(impl, ec); - } - - /// Cancels one asynchronous wait operation associated with the timer. - std::size_t cancel_one(implementation_type& impl, - asio::error_code& ec) - { - return service_impl_.cancel_one(impl, ec); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use expiry().) Get the expiry time for the timer as an - /// absolute time. - time_point expires_at(const implementation_type& impl) const - { - return service_impl_.expiry(impl); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the expiry time for the timer as an absolute time. - time_point expiry(const implementation_type& impl) const - { - return service_impl_.expiry(impl); - } - - /// Set the expiry time for the timer as an absolute time. - std::size_t expires_at(implementation_type& impl, - const time_point& expiry_time, asio::error_code& ec) - { - return service_impl_.expires_at(impl, expiry_time, ec); - } - - /// Set the expiry time for the timer relative to now. - std::size_t expires_after(implementation_type& impl, - const duration& expiry_time, asio::error_code& ec) - { - return service_impl_.expires_after(impl, expiry_time, ec); - } - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use expiry().) Get the expiry time for the timer relative to - /// now. - duration expires_from_now(const implementation_type& impl) const - { - typedef detail::chrono_time_traits traits; - return traits::subtract(service_impl_.expiry(impl), traits::now()); - } - - /// (Deprecated: Use expires_after().) Set the expiry time for the timer - /// relative to now. - std::size_t expires_from_now(implementation_type& impl, - const duration& expiry_time, asio::error_code& ec) - { - return service_impl_.expires_after(impl, expiry_time, ec); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - // Perform a blocking wait on the timer. - void wait(implementation_type& impl, asio::error_code& ec) - { - service_impl_.wait(impl, ec); - } - - // Start an asynchronous wait on the timer. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, - ASIO_MOVE_ARG(WaitHandler) handler) - { - async_completion init(handler); - - service_impl_.async_wait(impl, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WAITABLE_TIMER_SERVICE_HPP diff --git a/scout_sdk/asio/asio/windows/basic_handle.hpp b/scout_sdk/asio/asio/windows/basic_handle.hpp deleted file mode 100644 index f7c9d0d..0000000 --- a/scout_sdk/asio/asio/windows/basic_handle.hpp +++ /dev/null @@ -1,273 +0,0 @@ -// -// windows/basic_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_BASIC_HANDLE_HPP -#define ASIO_WINDOWS_BASIC_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) \ - || defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) \ - || defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/basic_io_object.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Provides Windows handle functionality. -/** - * The windows::basic_handle class template provides the ability to wrap a - * Windows handle. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_handle - : public basic_io_object -{ -public: - /// The native representation of a handle. - typedef typename HandleService::native_handle_type native_handle_type; - - /// A basic_handle is always the lowest layer. - typedef basic_handle lowest_layer_type; - - /// Construct a basic_handle without opening it. - /** - * This constructor creates a handle without opening it. - * - * @param io_context The io_context object that the handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - */ - explicit basic_handle(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct a basic_handle on an existing native handle. - /** - * This constructor creates a handle object to hold an existing native handle. - * - * @param io_context The io_context object that the handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - * - * @param handle A native handle. - * - * @throws asio::system_error Thrown on failure. - */ - basic_handle(asio::io_context& io_context, - const native_handle_type& handle) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), handle, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_handle from another. - /** - * This constructor moves a handle from one object to another. - * - * @param other The other basic_handle object from which the move will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_handle(io_context&) constructor. - */ - basic_handle(basic_handle&& other) - : basic_io_object( - ASIO_MOVE_CAST(basic_handle)(other)) - { - } - - /// Move-assign a basic_handle from another. - /** - * This assignment operator moves a handle from one object to another. - * - * @param other The other basic_handle object from which the move will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_handle(io_context&) constructor. - */ - basic_handle& operator=(basic_handle&& other) - { - basic_io_object::operator=( - ASIO_MOVE_CAST(basic_handle)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since a basic_handle cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since a basic_handle cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } - - /// Assign an existing native handle to the handle. - /* - * This function opens the handle to hold an existing native handle. - * - * @param handle A native handle. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const native_handle_type& handle) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), handle, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native handle to the handle. - /* - * This function opens the handle to hold an existing native handle. - * - * @param handle A native handle. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const native_handle_type& handle, - asio::error_code& ec) - { - this->get_service().assign(this->get_implementation(), handle, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the handle is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the handle. - /** - * This function is used to close the handle. Any asynchronous read or write - * operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the handle. - /** - * This function is used to close the handle. Any asynchronous read or write - * operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native handle representation. - /** - * This function may be used to obtain the underlying representation of the - * handle. This is intended to allow access to native handle functionality - * that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the handle. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the handle. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - -protected: - /// Protected destructor to prevent deletion through this type. - ~basic_handle() - { - } -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) - // || defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) - // || defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_BASIC_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/basic_object_handle.hpp b/scout_sdk/asio/asio/windows/basic_object_handle.hpp deleted file mode 100644 index 4b29684..0000000 --- a/scout_sdk/asio/asio/windows/basic_object_handle.hpp +++ /dev/null @@ -1,182 +0,0 @@ -// -// windows/basic_object_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2011 Boris Schaeling (boris@highscore.de) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_BASIC_OBJECT_HANDLE_HPP -#define ASIO_WINDOWS_BASIC_OBJECT_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/windows/basic_handle.hpp" -#include "asio/windows/object_handle_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Provides object-oriented handle functionality. -/** - * The windows::basic_object_handle class template provides asynchronous and - * blocking object-oriented handle functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_object_handle - : public basic_handle -{ -public: - /// The native representation of a handle. - typedef typename ObjectHandleService::native_handle_type native_handle_type; - - /// Construct a basic_object_handle without opening it. - /** - * This constructor creates an object handle without opening it. - * - * @param io_context The io_context object that the object handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - */ - explicit basic_object_handle(asio::io_context& io_context) - : basic_handle(io_context) - { - } - - /// Construct a basic_object_handle on an existing native handle. - /** - * This constructor creates an object handle object to hold an existing native - * handle. - * - * @param io_context The io_context object that the object handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - * - * @param native_handle The new underlying handle implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_object_handle(asio::io_context& io_context, - const native_handle_type& native_handle) - : basic_handle(io_context, native_handle) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_object_handle from another. - /** - * This constructor moves an object handle from one object to another. - * - * @param other The other basic_object_handle object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_object_handle(io_context&) constructor. - */ - basic_object_handle(basic_object_handle&& other) - : basic_handle( - ASIO_MOVE_CAST(basic_object_handle)(other)) - { - } - - /// Move-assign a basic_object_handle from another. - /** - * This assignment operator moves an object handle from one object to another. - * - * @param other The other basic_object_handle object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_object_handle(io_context&) constructor. - */ - basic_object_handle& operator=(basic_object_handle&& other) - { - basic_handle::operator=( - ASIO_MOVE_CAST(basic_object_handle)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Perform a blocking wait on the object handle. - /** - * This function is used to wait for the object handle to be set to the - * signalled state. This function blocks and does not return until the object - * handle has been set to the signalled state. - * - * @throws asio::system_error Thrown on failure. - */ - void wait() - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Perform a blocking wait on the object handle. - /** - * This function is used to wait for the object handle to be set to the - * signalled state. This function blocks and does not return until the object - * handle has been set to the signalled state. - * - * @param ec Set to indicate what error occurred, if any. - */ - void wait(asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), ec); - } - - /// Start an asynchronous wait on the object handle. - /** - * This function is be used to initiate an asynchronous wait against the - * object handle. It always returns immediately. - * - * @param handler The handler to be called when the object handle is set to - * the signalled state. Copies will be made of the handler as required. The - * function signature of the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(ASIO_MOVE_ARG(WaitHandler) handler) - { - return this->get_service().async_wait(this->get_implementation(), - ASIO_MOVE_CAST(WaitHandler)(handler)); - } -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_BASIC_OBJECT_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/basic_random_access_handle.hpp b/scout_sdk/asio/asio/windows/basic_random_access_handle.hpp deleted file mode 100644 index 4226977..0000000 --- a/scout_sdk/asio/asio/windows/basic_random_access_handle.hpp +++ /dev/null @@ -1,376 +0,0 @@ -// -// windows/basic_random_access_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_BASIC_RANDOM_ACCESS_HANDLE_HPP -#define ASIO_WINDOWS_BASIC_RANDOM_ACCESS_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/windows/basic_handle.hpp" -#include "asio/windows/random_access_handle_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Provides random-access handle functionality. -/** - * The windows::basic_random_access_handle class template provides asynchronous - * and blocking random-access handle functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -template -class basic_random_access_handle - : public basic_handle -{ -public: - /// The native representation of a handle. - typedef typename RandomAccessHandleService::native_handle_type - native_handle_type; - - /// Construct a basic_random_access_handle without opening it. - /** - * This constructor creates a random-access handle without opening it. The - * handle needs to be opened before data can be written to or read from it. - * - * @param io_context The io_context object that the random-access handle will - * use to dispatch handlers for any asynchronous operations performed on the - * handle. - */ - explicit basic_random_access_handle(asio::io_context& io_context) - : basic_handle(io_context) - { - } - - /// Construct a basic_random_access_handle on an existing native handle. - /** - * This constructor creates a random-access handle object to hold an existing - * native handle. - * - * @param io_context The io_context object that the random-access handle will - * use to dispatch handlers for any asynchronous operations performed on the - * handle. - * - * @param handle The new underlying handle implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_random_access_handle(asio::io_context& io_context, - const native_handle_type& handle) - : basic_handle(io_context, handle) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_random_access_handle from another. - /** - * This constructor moves a random-access handle from one object to another. - * - * @param other The other basic_random_access_handle object from which the - * move will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_random_access_handle(io_context&) - * constructor. - */ - basic_random_access_handle(basic_random_access_handle&& other) - : basic_handle( - ASIO_MOVE_CAST(basic_random_access_handle)(other)) - { - } - - /// Move-assign a basic_random_access_handle from another. - /** - * This assignment operator moves a random-access handle from one object to - * another. - * - * @param other The other basic_random_access_handle object from which the - * move will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_random_access_handle(io_context&) - * constructor. - */ - basic_random_access_handle& operator=(basic_random_access_handle&& other) - { - basic_handle::operator=( - ASIO_MOVE_CAST(basic_random_access_handle)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Write some data to the handle at the specified offset. - /** - * This function is used to write data to the random-access handle. The - * function call will block until one or more bytes of the data has been - * written successfully, or until an error occurs. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some_at operation may not write all of the data. Consider - * using the @ref write_at function if you need to ensure that all data is - * written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.write_some_at(42, asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some_at(uint64_t offset, - const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some_at( - this->get_implementation(), offset, buffers, ec); - asio::detail::throw_error(ec, "write_some_at"); - return s; - } - - /// Write some data to the handle at the specified offset. - /** - * This function is used to write data to the random-access handle. The - * function call will block until one or more bytes of the data has been - * written successfully, or until an error occurs. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write_at function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some_at(uint64_t offset, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return this->get_service().write_some_at( - this->get_implementation(), offset, buffers, ec); - } - - /// Start an asynchronous write at the specified offset. - /** - * This function is used to asynchronously write data to the random-access - * handle. The function call always returns immediately. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more data buffers to be written to the handle. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write_at function if you need to ensure that - * all data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_write_some_at(42, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some_at(uint64_t offset, - const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - return this->get_service().async_write_some_at(this->get_implementation(), - offset, buffers, ASIO_MOVE_CAST(WriteHandler)(handler)); - } - - /// Read some data from the handle at the specified offset. - /** - * This function is used to read data from the random-access handle. The - * function call will block until one or more bytes of data has been read - * successfully, or until an error occurs. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read_at function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.read_some_at(42, asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some_at(uint64_t offset, - const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some_at( - this->get_implementation(), offset, buffers, ec); - asio::detail::throw_error(ec, "read_some_at"); - return s; - } - - /// Read some data from the handle at the specified offset. - /** - * This function is used to read data from the random-access handle. The - * function call will block until one or more bytes of data has been read - * successfully, or until an error occurs. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read_at function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some_at(uint64_t offset, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return this->get_service().read_some_at( - this->get_implementation(), offset, buffers, ec); - } - - /// Start an asynchronous read at the specified offset. - /** - * This function is used to asynchronously read data from the random-access - * handle. The function call always returns immediately. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read_at function if you need to ensure that - * the requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_read_some_at(42, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some_at(uint64_t offset, - const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - return this->get_service().async_read_some_at(this->get_implementation(), - offset, buffers, ASIO_MOVE_CAST(ReadHandler)(handler)); - } -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_BASIC_RANDOM_ACCESS_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/basic_stream_handle.hpp b/scout_sdk/asio/asio/windows/basic_stream_handle.hpp deleted file mode 100644 index 3bfce68..0000000 --- a/scout_sdk/asio/asio/windows/basic_stream_handle.hpp +++ /dev/null @@ -1,359 +0,0 @@ -// -// windows/basic_stream_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_BASIC_STREAM_HANDLE_HPP -#define ASIO_WINDOWS_BASIC_STREAM_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/detail/handler_type_requirements.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/error.hpp" -#include "asio/windows/basic_handle.hpp" -#include "asio/windows/stream_handle_service.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Provides stream-oriented handle functionality. -/** - * The windows::basic_stream_handle class template provides asynchronous and - * blocking stream-oriented handle functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -template -class basic_stream_handle - : public basic_handle -{ -public: - /// The native representation of a handle. - typedef typename StreamHandleService::native_handle_type native_handle_type; - - /// Construct a basic_stream_handle without opening it. - /** - * This constructor creates a stream handle without opening it. The handle - * needs to be opened and then connected or accepted before data can be sent - * or received on it. - * - * @param io_context The io_context object that the stream handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - */ - explicit basic_stream_handle(asio::io_context& io_context) - : basic_handle(io_context) - { - } - - /// Construct a basic_stream_handle on an existing native handle. - /** - * This constructor creates a stream handle object to hold an existing native - * handle. - * - * @param io_context The io_context object that the stream handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - * - * @param handle The new underlying handle implementation. - * - * @throws asio::system_error Thrown on failure. - */ - basic_stream_handle(asio::io_context& io_context, - const native_handle_type& handle) - : basic_handle(io_context, handle) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a basic_stream_handle from another. - /** - * This constructor moves a stream handle from one object to another. - * - * @param other The other basic_stream_handle object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_handle(io_context&) constructor. - */ - basic_stream_handle(basic_stream_handle&& other) - : basic_handle( - ASIO_MOVE_CAST(basic_stream_handle)(other)) - { - } - - /// Move-assign a basic_stream_handle from another. - /** - * This assignment operator moves a stream handle from one object to - * another. - * - * @param other The other basic_stream_handle object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c basic_stream_handle(io_context&) constructor. - */ - basic_stream_handle& operator=(basic_stream_handle&& other) - { - basic_handle::operator=( - ASIO_MOVE_CAST(basic_stream_handle)(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Write some data to the handle. - /** - * This function is used to write data to the stream handle. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.write_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "write_some"); - return s; - } - - /// Write some data to the handle. - /** - * This function is used to write data to the stream handle. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().write_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write data to the stream handle. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be written to the handle. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_write_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - return this->get_service().async_write_some(this->get_implementation(), - buffers, ASIO_MOVE_CAST(WriteHandler)(handler)); - } - - /// Read some data from the handle. - /** - * This function is used to read data from the stream handle. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.read_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "read_some"); - return s; - } - - /// Read some data from the handle. - /** - * This function is used to read data from the stream handle. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().read_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read data from the stream handle. - * The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read function if you need to ensure that the - * requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_read_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - return this->get_service().async_read_some(this->get_implementation(), - buffers, ASIO_MOVE_CAST(ReadHandler)(handler)); - } -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_BASIC_STREAM_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/object_handle.hpp b/scout_sdk/asio/asio/windows/object_handle.hpp deleted file mode 100644 index 581b568..0000000 --- a/scout_sdk/asio/asio/windows/object_handle.hpp +++ /dev/null @@ -1,381 +0,0 @@ -// -// windows/object_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2011 Boris Schaeling (boris@highscore.de) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_OBJECT_HANDLE_HPP -#define ASIO_WINDOWS_OBJECT_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/async_result.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_object_handle_service.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/windows/basic_object_handle.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#define ASIO_SVC_T asio::detail::win_object_handle_service - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -#if defined(ASIO_ENABLE_OLD_SERVICES) -// Typedef for the typical usage of an object handle. -typedef basic_object_handle<> object_handle; -#else // defined(ASIO_ENABLE_OLD_SERVICES) -/// Provides object-oriented handle functionality. -/** - * The windows::object_handle class provides asynchronous and blocking - * object-oriented handle functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class object_handle - : ASIO_SVC_ACCESS basic_io_object -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The native representation of a handle. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef ASIO_SVC_T::native_handle_type native_handle_type; -#endif - - /// An object_handle is always the lowest layer. - typedef object_handle lowest_layer_type; - - /// Construct an object_handle without opening it. - /** - * This constructor creates an object handle without opening it. - * - * @param io_context The io_context object that the object handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - */ - explicit object_handle(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct an object_handle on an existing native handle. - /** - * This constructor creates an object handle object to hold an existing native - * handle. - * - * @param io_context The io_context object that the object handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - * - * @param native_handle The new underlying handle implementation. - * - * @throws asio::system_error Thrown on failure. - */ - object_handle(asio::io_context& io_context, - const native_handle_type& native_handle) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), native_handle, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct an object_handle from another. - /** - * This constructor moves an object handle from one object to another. - * - * @param other The other object_handle object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c object_handle(io_context&) constructor. - */ - object_handle(object_handle&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign an object_handle from another. - /** - * This assignment operator moves an object handle from one object to another. - * - * @param other The other object_handle object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c object_handle(io_context&) constructor. - */ - object_handle& operator=(object_handle&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since an object_handle cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since an object_handle cannot contain any further layers, it simply - * returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } - - /// Assign an existing native handle to the handle. - /* - * This function opens the handle to hold an existing native handle. - * - * @param handle A native handle. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const native_handle_type& handle) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), handle, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native handle to the handle. - /* - * This function opens the handle to hold an existing native handle. - * - * @param handle A native handle. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const native_handle_type& handle, - asio::error_code& ec) - { - this->get_service().assign(this->get_implementation(), handle, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the handle is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the handle. - /** - * This function is used to close the handle. Any asynchronous read or write - * operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the handle. - /** - * This function is used to close the handle. Any asynchronous read or write - * operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native handle representation. - /** - * This function may be used to obtain the underlying representation of the - * handle. This is intended to allow access to native handle functionality - * that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the handle. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the handle. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Perform a blocking wait on the object handle. - /** - * This function is used to wait for the object handle to be set to the - * signalled state. This function blocks and does not return until the object - * handle has been set to the signalled state. - * - * @throws asio::system_error Thrown on failure. - */ - void wait() - { - asio::error_code ec; - this->get_service().wait(this->get_implementation(), ec); - asio::detail::throw_error(ec, "wait"); - } - - /// Perform a blocking wait on the object handle. - /** - * This function is used to wait for the object handle to be set to the - * signalled state. This function blocks and does not return until the object - * handle has been set to the signalled state. - * - * @param ec Set to indicate what error occurred, if any. - */ - void wait(asio::error_code& ec) - { - this->get_service().wait(this->get_implementation(), ec); - } - - /// Start an asynchronous wait on the object handle. - /** - * This function is be used to initiate an asynchronous wait against the - * object handle. It always returns immediately. - * - * @param handler The handler to be called when the object handle is set to - * the signalled state. Copies will be made of the handler as required. The - * function signature of the handler must be: - * @code void handler( - * const asio::error_code& error // Result of operation. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(ASIO_MOVE_ARG(WaitHandler) handler) - { - asio::async_completion init(handler); - - this->get_service().async_wait(this->get_implementation(), - init.completion_handler); - - return init.result.get(); - } -}; -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#undef ASIO_SVC_T - -#endif // defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_WINDOWS_OBJECT_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/object_handle_service.hpp b/scout_sdk/asio/asio/windows/object_handle_service.hpp deleted file mode 100644 index 95436d7..0000000 --- a/scout_sdk/asio/asio/windows/object_handle_service.hpp +++ /dev/null @@ -1,183 +0,0 @@ -// -// windows/object_handle_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// Copyright (c) 2011 Boris Schaeling (boris@highscore.de) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_OBJECT_HANDLE_SERVICE_HPP -#define ASIO_WINDOWS_OBJECT_HANDLE_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/async_result.hpp" -#include "asio/detail/win_object_handle_service.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Default service implementation for an object handle. -class object_handle_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - -private: - // The type of the platform-specific implementation. - typedef detail::win_object_handle_service service_impl_type; - -public: - /// The type of an object handle implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef service_impl_type::implementation_type implementation_type; -#endif - - /// The native handle type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new object handle service for the specified io_context. - explicit object_handle_service(asio::io_context& io_context) - : asio::detail::service_base(io_context), - service_impl_(io_context) - { - } - - /// Construct a new object handle implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new object handle implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another object handle implementation. - void move_assign(implementation_type& impl, - object_handle_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy an object handle implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Assign an existing native handle to an object handle. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec) - { - service_impl_.assign(impl, handle, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the handle is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close an object handle implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native handle implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the handle. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - // Wait for a signaled state. - void wait(implementation_type& impl, asio::error_code& ec) - { - service_impl_.wait(impl, ec); - } - - /// Start an asynchronous wait. - template - ASIO_INITFN_RESULT_TYPE(WaitHandler, - void (asio::error_code)) - async_wait(implementation_type& impl, - ASIO_MOVE_ARG(WaitHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_wait(impl, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_OBJECT_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_OBJECT_HANDLE_SERVICE_HPP diff --git a/scout_sdk/asio/asio/windows/overlapped_handle.hpp b/scout_sdk/asio/asio/windows/overlapped_handle.hpp deleted file mode 100644 index 3d479ba..0000000 --- a/scout_sdk/asio/asio/windows/overlapped_handle.hpp +++ /dev/null @@ -1,331 +0,0 @@ -// -// windows/overlapped_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_OVERLAPPED_HANDLE_HPP -#define ASIO_WINDOWS_OVERLAPPED_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if !defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) \ - || defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/async_result.hpp" -#include "asio/basic_io_object.hpp" -#include "asio/detail/throw_error.hpp" -#include "asio/detail/win_iocp_handle_service.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#if defined(ASIO_HAS_MOVE) -# include -#endif // defined(ASIO_HAS_MOVE) - -#define ASIO_SVC_T asio::detail::win_iocp_handle_service - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Provides Windows handle functionality for objects that support -/// overlapped I/O. -/** - * The windows::overlapped_handle class provides the ability to wrap a Windows - * handle. The underlying object referred to by the handle must support - * overlapped I/O. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class overlapped_handle - : ASIO_SVC_ACCESS basic_io_object -{ -public: - /// The type of the executor associated with the object. - typedef io_context::executor_type executor_type; - - /// The native representation of a handle. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef ASIO_SVC_T::native_handle_type native_handle_type; -#endif - - /// An overlapped_handle is always the lowest layer. - typedef overlapped_handle lowest_layer_type; - - /// Construct an overlapped_handle without opening it. - /** - * This constructor creates a handle without opening it. - * - * @param io_context The io_context object that the handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - */ - explicit overlapped_handle(asio::io_context& io_context) - : basic_io_object(io_context) - { - } - - /// Construct an overlapped_handle on an existing native handle. - /** - * This constructor creates a handle object to hold an existing native handle. - * - * @param io_context The io_context object that the handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - * - * @param handle A native handle. - * - * @throws asio::system_error Thrown on failure. - */ - overlapped_handle(asio::io_context& io_context, - const native_handle_type& handle) - : basic_io_object(io_context) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), handle, ec); - asio::detail::throw_error(ec, "assign"); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct an overlapped_handle from another. - /** - * This constructor moves a handle from one object to another. - * - * @param other The other overlapped_handle object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c overlapped_handle(io_context&) constructor. - */ - overlapped_handle(overlapped_handle&& other) - : basic_io_object(std::move(other)) - { - } - - /// Move-assign an overlapped_handle from another. - /** - * This assignment operator moves a handle from one object to another. - * - * @param other The other overlapped_handle object from which the move will - * occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c overlapped_handle(io_context&) constructor. - */ - overlapped_handle& operator=(overlapped_handle&& other) - { - basic_io_object::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - -#if !defined(ASIO_NO_DEPRECATED) - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_context() - { - return basic_io_object::get_io_context(); - } - - /// (Deprecated: Use get_executor().) Get the io_context associated with the - /// object. - /** - * This function may be used to obtain the io_context object that the I/O - * object uses to dispatch handlers for asynchronous operations. - * - * @return A reference to the io_context object that the I/O object will use - * to dispatch handlers. Ownership is not transferred to the caller. - */ - asio::io_context& get_io_service() - { - return basic_io_object::get_io_service(); - } -#endif // !defined(ASIO_NO_DEPRECATED) - - /// Get the executor associated with the object. - executor_type get_executor() ASIO_NOEXCEPT - { - return basic_io_object::get_executor(); - } - - /// Get a reference to the lowest layer. - /** - * This function returns a reference to the lowest layer in a stack of - * layers. Since an overlapped_handle cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A reference to the lowest layer in the stack of layers. Ownership - * is not transferred to the caller. - */ - lowest_layer_type& lowest_layer() - { - return *this; - } - - /// Get a const reference to the lowest layer. - /** - * This function returns a const reference to the lowest layer in a stack of - * layers. Since an overlapped_handle cannot contain any further layers, it - * simply returns a reference to itself. - * - * @return A const reference to the lowest layer in the stack of layers. - * Ownership is not transferred to the caller. - */ - const lowest_layer_type& lowest_layer() const - { - return *this; - } - - /// Assign an existing native handle to the handle. - /* - * This function opens the handle to hold an existing native handle. - * - * @param handle A native handle. - * - * @throws asio::system_error Thrown on failure. - */ - void assign(const native_handle_type& handle) - { - asio::error_code ec; - this->get_service().assign(this->get_implementation(), handle, ec); - asio::detail::throw_error(ec, "assign"); - } - - /// Assign an existing native handle to the handle. - /* - * This function opens the handle to hold an existing native handle. - * - * @param handle A native handle. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID assign(const native_handle_type& handle, - asio::error_code& ec) - { - this->get_service().assign(this->get_implementation(), handle, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the handle is open. - bool is_open() const - { - return this->get_service().is_open(this->get_implementation()); - } - - /// Close the handle. - /** - * This function is used to close the handle. Any asynchronous read or write - * operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void close() - { - asio::error_code ec; - this->get_service().close(this->get_implementation(), ec); - asio::detail::throw_error(ec, "close"); - } - - /// Close the handle. - /** - * This function is used to close the handle. Any asynchronous read or write - * operations will be cancelled immediately, and will complete with the - * asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID close(asio::error_code& ec) - { - this->get_service().close(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native handle representation. - /** - * This function may be used to obtain the underlying representation of the - * handle. This is intended to allow access to native handle functionality - * that is not otherwise provided. - */ - native_handle_type native_handle() - { - return this->get_service().native_handle(this->get_implementation()); - } - - /// Cancel all asynchronous operations associated with the handle. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @throws asio::system_error Thrown on failure. - */ - void cancel() - { - asio::error_code ec; - this->get_service().cancel(this->get_implementation(), ec); - asio::detail::throw_error(ec, "cancel"); - } - - /// Cancel all asynchronous operations associated with the handle. - /** - * This function causes all outstanding asynchronous read or write operations - * to finish immediately, and the handlers for cancelled operations will be - * passed the asio::error::operation_aborted error. - * - * @param ec Set to indicate what error occurred, if any. - */ - ASIO_SYNC_OP_VOID cancel(asio::error_code& ec) - { - this->get_service().cancel(this->get_implementation(), ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - -protected: - /// Protected destructor to prevent deletion through this type. - /** - * This function destroys the handle, cancelling any outstanding asynchronous - * wait operations associated with the handle as if by calling @c cancel. - */ - ~overlapped_handle() - { - } -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#undef ASIO_SVC_T - -#endif // defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) - // || defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // !defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_OVERLAPPED_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/overlapped_ptr.hpp b/scout_sdk/asio/asio/windows/overlapped_ptr.hpp deleted file mode 100644 index ce0b2a4..0000000 --- a/scout_sdk/asio/asio/windows/overlapped_ptr.hpp +++ /dev/null @@ -1,116 +0,0 @@ -// -// windows/overlapped_ptr.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_OVERLAPPED_PTR_HPP -#define ASIO_WINDOWS_OVERLAPPED_PTR_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_HAS_WINDOWS_OVERLAPPED_PTR) \ - || defined(GENERATING_DOCUMENTATION) - -#include "asio/detail/noncopyable.hpp" -#include "asio/detail/win_iocp_overlapped_ptr.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Wraps a handler to create an OVERLAPPED object for use with overlapped I/O. -/** - * A special-purpose smart pointer used to wrap an application handler so that - * it can be passed as the LPOVERLAPPED argument to overlapped I/O functions. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class overlapped_ptr - : private noncopyable -{ -public: - /// Construct an empty overlapped_ptr. - overlapped_ptr() - : impl_() - { - } - - /// Construct an overlapped_ptr to contain the specified handler. - template - explicit overlapped_ptr(asio::io_context& io_context, - ASIO_MOVE_ARG(Handler) handler) - : impl_(io_context, ASIO_MOVE_CAST(Handler)(handler)) - { - } - - /// Destructor automatically frees the OVERLAPPED object unless released. - ~overlapped_ptr() - { - } - - /// Reset to empty. - void reset() - { - impl_.reset(); - } - - /// Reset to contain the specified handler, freeing any current OVERLAPPED - /// object. - template - void reset(asio::io_context& io_context, - ASIO_MOVE_ARG(Handler) handler) - { - impl_.reset(io_context, ASIO_MOVE_CAST(Handler)(handler)); - } - - /// Get the contained OVERLAPPED object. - OVERLAPPED* get() - { - return impl_.get(); - } - - /// Get the contained OVERLAPPED object. - const OVERLAPPED* get() const - { - return impl_.get(); - } - - /// Release ownership of the OVERLAPPED object. - OVERLAPPED* release() - { - return impl_.release(); - } - - /// Post completion notification for overlapped operation. Releases ownership. - void complete(const asio::error_code& ec, - std::size_t bytes_transferred) - { - impl_.complete(ec, bytes_transferred); - } - -private: - detail::win_iocp_overlapped_ptr impl_; -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_OVERLAPPED_PTR) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_WINDOWS_OVERLAPPED_PTR_HPP diff --git a/scout_sdk/asio/asio/windows/random_access_handle.hpp b/scout_sdk/asio/asio/windows/random_access_handle.hpp deleted file mode 100644 index 301d5f8..0000000 --- a/scout_sdk/asio/asio/windows/random_access_handle.hpp +++ /dev/null @@ -1,378 +0,0 @@ -// -// windows/random_access_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_RANDOM_ACCESS_HANDLE_HPP -#define ASIO_WINDOWS_RANDOM_ACCESS_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/windows/overlapped_handle.hpp" - -#if defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/windows/basic_random_access_handle.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -#if defined(ASIO_ENABLE_OLD_SERVICES) -// Typedef for the typical usage of a random-access handle. -typedef basic_random_access_handle<> random_access_handle; -#else // defined(ASIO_ENABLE_OLD_SERVICES) -/// Provides random-access handle functionality. -/** - * The windows::random_access_handle class provides asynchronous and - * blocking random-access handle functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - */ -class random_access_handle - : public overlapped_handle -{ -public: - /// Construct a random_access_handle without opening it. - /** - * This constructor creates a random-access handle without opening it. The - * handle needs to be opened before data can be written to or read from it. - * - * @param io_context The io_context object that the random-access handle will - * use to dispatch handlers for any asynchronous operations performed on the - * handle. - */ - explicit random_access_handle(asio::io_context& io_context) - : overlapped_handle(io_context) - { - } - - /// Construct a random_access_handle on an existing native handle. - /** - * This constructor creates a random-access handle object to hold an existing - * native handle. - * - * @param io_context The io_context object that the random-access handle will - * use to dispatch handlers for any asynchronous operations performed on the - * handle. - * - * @param handle The new underlying handle implementation. - * - * @throws asio::system_error Thrown on failure. - */ - random_access_handle(asio::io_context& io_context, - const native_handle_type& handle) - : overlapped_handle(io_context, handle) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a random_access_handle from another. - /** - * This constructor moves a random-access handle from one object to another. - * - * @param other The other random_access_handle object from which the - * move will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c random_access_handle(io_context&) - * constructor. - */ - random_access_handle(random_access_handle&& other) - : overlapped_handle(std::move(other)) - { - } - - /// Move-assign a random_access_handle from another. - /** - * This assignment operator moves a random-access handle from one object to - * another. - * - * @param other The other random_access_handle object from which the - * move will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c random_access_handle(io_context&) - * constructor. - */ - random_access_handle& operator=(random_access_handle&& other) - { - overlapped_handle::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Write some data to the handle at the specified offset. - /** - * This function is used to write data to the random-access handle. The - * function call will block until one or more bytes of the data has been - * written successfully, or until an error occurs. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some_at operation may not write all of the data. Consider - * using the @ref write_at function if you need to ensure that all data is - * written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.write_some_at(42, asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some_at(uint64_t offset, - const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some_at( - this->get_implementation(), offset, buffers, ec); - asio::detail::throw_error(ec, "write_some_at"); - return s; - } - - /// Write some data to the handle at the specified offset. - /** - * This function is used to write data to the random-access handle. The - * function call will block until one or more bytes of the data has been - * written successfully, or until an error occurs. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write_at function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some_at(uint64_t offset, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return this->get_service().write_some_at( - this->get_implementation(), offset, buffers, ec); - } - - /// Start an asynchronous write at the specified offset. - /** - * This function is used to asynchronously write data to the random-access - * handle. The function call always returns immediately. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more data buffers to be written to the handle. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write_at function if you need to ensure that - * all data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_write_some_at(42, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some_at(uint64_t offset, - const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - asio::async_completion init(handler); - - this->get_service().async_write_some_at(this->get_implementation(), - offset, buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the handle at the specified offset. - /** - * This function is used to read data from the random-access handle. The - * function call will block until one or more bytes of data has been read - * successfully, or until an error occurs. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read_at function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.read_some_at(42, asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some_at(uint64_t offset, - const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some_at( - this->get_implementation(), offset, buffers, ec); - asio::detail::throw_error(ec, "read_some_at"); - return s; - } - - /// Read some data from the handle at the specified offset. - /** - * This function is used to read data from the random-access handle. The - * function call will block until one or more bytes of data has been read - * successfully, or until an error occurs. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read_at function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some_at(uint64_t offset, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return this->get_service().read_some_at( - this->get_implementation(), offset, buffers, ec); - } - - /// Start an asynchronous read at the specified offset. - /** - * This function is used to asynchronously read data from the random-access - * handle. The function call always returns immediately. - * - * @param offset The offset at which the data will be read. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read_at function if you need to ensure that - * the requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_read_some_at(42, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some_at(uint64_t offset, - const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - asio::async_completion init(handler); - - this->get_service().async_read_some_at(this->get_implementation(), - offset, buffers, init.completion_handler); - - return init.result.get(); - } -}; -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_WINDOWS_RANDOM_ACCESS_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/random_access_handle_service.hpp b/scout_sdk/asio/asio/windows/random_access_handle_service.hpp deleted file mode 100644 index ebccf3e..0000000 --- a/scout_sdk/asio/asio/windows/random_access_handle_service.hpp +++ /dev/null @@ -1,214 +0,0 @@ -// -// windows/random_access_handle_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_RANDOM_ACCESS_HANDLE_SERVICE_HPP -#define ASIO_WINDOWS_RANDOM_ACCESS_HANDLE_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/cstdint.hpp" -#include "asio/detail/win_iocp_handle_service.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Default service implementation for a random-access handle. -class random_access_handle_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - -private: - // The type of the platform-specific implementation. - typedef detail::win_iocp_handle_service service_impl_type; - -public: - /// The type of a random-access handle implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef service_impl_type::implementation_type implementation_type; -#endif - - /// The native handle type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new random-access handle service for the specified io_context. - explicit random_access_handle_service(asio::io_context& io_context) - : asio::detail::service_base< - random_access_handle_service>(io_context), - service_impl_(io_context) - { - } - - /// Construct a new random-access handle implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new random-access handle implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another random-access handle implementation. - void move_assign(implementation_type& impl, - random_access_handle_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a random-access handle implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Assign an existing native handle to a random-access handle. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec) - { - service_impl_.assign(impl, handle, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the handle is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a random-access handle implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native handle implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the handle. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Write the given data at the specified offset. - template - std::size_t write_some_at(implementation_type& impl, uint64_t offset, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.write_some_at(impl, offset, buffers, ec); - } - - /// Start an asynchronous write at the specified offset. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some_at(implementation_type& impl, - uint64_t offset, const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_write_some_at(impl, - offset, buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the specified offset. - template - std::size_t read_some_at(implementation_type& impl, uint64_t offset, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.read_some_at(impl, offset, buffers, ec); - } - - /// Start an asynchronous read at the specified offset. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some_at(implementation_type& impl, - uint64_t offset, const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_read_some_at(impl, - offset, buffers, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_RANDOM_ACCESS_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_RANDOM_ACCESS_HANDLE_SERVICE_HPP diff --git a/scout_sdk/asio/asio/windows/stream_handle.hpp b/scout_sdk/asio/asio/windows/stream_handle.hpp deleted file mode 100644 index 8f0a21b..0000000 --- a/scout_sdk/asio/asio/windows/stream_handle.hpp +++ /dev/null @@ -1,362 +0,0 @@ -// -// windows/stream_handle.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_STREAM_HANDLE_HPP -#define ASIO_WINDOWS_STREAM_HANDLE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include "asio/windows/overlapped_handle.hpp" - -#if defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#if defined(ASIO_ENABLE_OLD_SERVICES) -# include "asio/windows/basic_stream_handle.hpp" -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -#if defined(ASIO_ENABLE_OLD_SERVICES) -// Typedef for the typical usage of a stream-oriented handle. -typedef basic_stream_handle<> stream_handle; -#else // defined(ASIO_ENABLE_OLD_SERVICES) -/// Provides stream-oriented handle functionality. -/** - * The windows::stream_handle class provides asynchronous and blocking - * stream-oriented handle functionality. - * - * @par Thread Safety - * @e Distinct @e objects: Safe.@n - * @e Shared @e objects: Unsafe. - * - * @par Concepts: - * AsyncReadStream, AsyncWriteStream, Stream, SyncReadStream, SyncWriteStream. - */ -class stream_handle - : public overlapped_handle -{ -public: - /// Construct a stream_handle without opening it. - /** - * This constructor creates a stream handle without opening it. The handle - * needs to be opened and then connected or accepted before data can be sent - * or received on it. - * - * @param io_context The io_context object that the stream handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - */ - explicit stream_handle(asio::io_context& io_context) - : overlapped_handle(io_context) - { - } - - /// Construct a stream_handle on an existing native handle. - /** - * This constructor creates a stream handle object to hold an existing native - * handle. - * - * @param io_context The io_context object that the stream handle will use to - * dispatch handlers for any asynchronous operations performed on the handle. - * - * @param handle The new underlying handle implementation. - * - * @throws asio::system_error Thrown on failure. - */ - stream_handle(asio::io_context& io_context, - const native_handle_type& handle) - : overlapped_handle(io_context, handle) - { - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a stream_handle from another. - /** - * This constructor moves a stream handle from one object to another. - * - * @param other The other stream_handle object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c stream_handle(io_context&) constructor. - */ - stream_handle(stream_handle&& other) - : overlapped_handle(std::move(other)) - { - } - - /// Move-assign a stream_handle from another. - /** - * This assignment operator moves a stream handle from one object to - * another. - * - * @param other The other stream_handle object from which the move - * will occur. - * - * @note Following the move, the moved-from object is in the same state as if - * constructed using the @c stream_handle(io_context&) constructor. - */ - stream_handle& operator=(stream_handle&& other) - { - overlapped_handle::operator=(std::move(other)); - return *this; - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Write some data to the handle. - /** - * This function is used to write data to the stream handle. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @returns The number of bytes written. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.write_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().write_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "write_some"); - return s; - } - - /// Write some data to the handle. - /** - * This function is used to write data to the stream handle. The function call - * will block until one or more bytes of the data has been written - * successfully, or until an error occurs. - * - * @param buffers One or more data buffers to be written to the handle. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. Returns 0 if an error occurred. - * - * @note The write_some operation may not transmit all of the data to the - * peer. Consider using the @ref write function if you need to ensure that - * all data is written before the blocking operation completes. - */ - template - std::size_t write_some(const ConstBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().write_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous write. - /** - * This function is used to asynchronously write data to the stream handle. - * The function call always returns immediately. - * - * @param buffers One or more data buffers to be written to the handle. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes written. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The write operation may not transmit all of the data to the peer. - * Consider using the @ref async_write function if you need to ensure that all - * data is written before the asynchronous operation completes. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_write_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a WriteHandler. - ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check; - - asio::async_completion init(handler); - - this->get_service().async_write_some( - this->get_implementation(), buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the handle. - /** - * This function is used to read data from the stream handle. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @returns The number of bytes read. - * - * @throws asio::system_error Thrown on failure. An error code of - * asio::error::eof indicates that the connection was closed by the - * peer. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.read_some(asio::buffer(data, size)); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers) - { - asio::error_code ec; - std::size_t s = this->get_service().read_some( - this->get_implementation(), buffers, ec); - asio::detail::throw_error(ec, "read_some"); - return s; - } - - /// Read some data from the handle. - /** - * This function is used to read data from the stream handle. The function - * call will block until one or more bytes of data has been read successfully, - * or until an error occurs. - * - * @param buffers One or more buffers into which the data will be read. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes read. Returns 0 if an error occurred. - * - * @note The read_some operation may not read all of the requested number of - * bytes. Consider using the @ref read function if you need to ensure that - * the requested amount of data is read before the blocking operation - * completes. - */ - template - std::size_t read_some(const MutableBufferSequence& buffers, - asio::error_code& ec) - { - return this->get_service().read_some( - this->get_implementation(), buffers, ec); - } - - /// Start an asynchronous read. - /** - * This function is used to asynchronously read data from the stream handle. - * The function call always returns immediately. - * - * @param buffers One or more buffers into which the data will be read. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the read operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * std::size_t bytes_transferred // Number of bytes read. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation - * of the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @note The read operation may not read all of the requested number of bytes. - * Consider using the @ref async_read function if you need to ensure that the - * requested amount of data is read before the asynchronous operation - * completes. - * - * @par Example - * To read into a single data buffer use the @ref buffer function as follows: - * @code - * handle.async_read_some(asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on reading into multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - // If you get an error on the following line it means that your handler does - // not meet the documented type requirements for a ReadHandler. - ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check; - - asio::async_completion init(handler); - - this->get_service().async_read_some( - this->get_implementation(), buffers, init.completion_handler); - - return init.result.get(); - } -}; -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // ASIO_WINDOWS_STREAM_HANDLE_HPP diff --git a/scout_sdk/asio/asio/windows/stream_handle_service.hpp b/scout_sdk/asio/asio/windows/stream_handle_service.hpp deleted file mode 100644 index 1c665d5..0000000 --- a/scout_sdk/asio/asio/windows/stream_handle_service.hpp +++ /dev/null @@ -1,210 +0,0 @@ -// -// windows/stream_handle_service.hpp -// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WINDOWS_STREAM_HANDLE_SERVICE_HPP -#define ASIO_WINDOWS_STREAM_HANDLE_SERVICE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" - -#if defined(ASIO_ENABLE_OLD_SERVICES) - -#if defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) \ - || defined(GENERATING_DOCUMENTATION) - -#include -#include "asio/async_result.hpp" -#include "asio/detail/win_iocp_handle_service.hpp" -#include "asio/error.hpp" -#include "asio/io_context.hpp" - -#include "asio/detail/push_options.hpp" - -namespace asio { -namespace windows { - -/// Default service implementation for a stream handle. -class stream_handle_service -#if defined(GENERATING_DOCUMENTATION) - : public asio::io_context::service -#else - : public asio::detail::service_base -#endif -{ -public: -#if defined(GENERATING_DOCUMENTATION) - /// The unique service identifier. - static asio::io_context::id id; -#endif - -private: - // The type of the platform-specific implementation. - typedef detail::win_iocp_handle_service service_impl_type; - -public: - /// The type of a stream handle implementation. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined implementation_type; -#else - typedef service_impl_type::implementation_type implementation_type; -#endif - - /// The native handle type. -#if defined(GENERATING_DOCUMENTATION) - typedef implementation_defined native_handle_type; -#else - typedef service_impl_type::native_handle_type native_handle_type; -#endif - - /// Construct a new stream handle service for the specified io_context. - explicit stream_handle_service(asio::io_context& io_context) - : asio::detail::service_base(io_context), - service_impl_(io_context) - { - } - - /// Construct a new stream handle implementation. - void construct(implementation_type& impl) - { - service_impl_.construct(impl); - } - -#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - /// Move-construct a new stream handle implementation. - void move_construct(implementation_type& impl, - implementation_type& other_impl) - { - service_impl_.move_construct(impl, other_impl); - } - - /// Move-assign from another stream handle implementation. - void move_assign(implementation_type& impl, - stream_handle_service& other_service, - implementation_type& other_impl) - { - service_impl_.move_assign(impl, other_service.service_impl_, other_impl); - } -#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION) - - /// Destroy a stream handle implementation. - void destroy(implementation_type& impl) - { - service_impl_.destroy(impl); - } - - /// Assign an existing native handle to a stream handle. - ASIO_SYNC_OP_VOID assign(implementation_type& impl, - const native_handle_type& handle, asio::error_code& ec) - { - service_impl_.assign(impl, handle, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Determine whether the handle is open. - bool is_open(const implementation_type& impl) const - { - return service_impl_.is_open(impl); - } - - /// Close a stream handle implementation. - ASIO_SYNC_OP_VOID close(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.close(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Get the native handle implementation. - native_handle_type native_handle(implementation_type& impl) - { - return service_impl_.native_handle(impl); - } - - /// Cancel all asynchronous operations associated with the handle. - ASIO_SYNC_OP_VOID cancel(implementation_type& impl, - asio::error_code& ec) - { - service_impl_.cancel(impl, ec); - ASIO_SYNC_OP_VOID_RETURN(ec); - } - - /// Write the given data to the stream. - template - std::size_t write_some(implementation_type& impl, - const ConstBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.write_some(impl, buffers, ec); - } - - /// Start an asynchronous write. - template - ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) - async_write_some(implementation_type& impl, - const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_write_some(impl, buffers, init.completion_handler); - - return init.result.get(); - } - - /// Read some data from the stream. - template - std::size_t read_some(implementation_type& impl, - const MutableBufferSequence& buffers, asio::error_code& ec) - { - return service_impl_.read_some(impl, buffers, ec); - } - - /// Start an asynchronous read. - template - ASIO_INITFN_RESULT_TYPE(ReadHandler, - void (asio::error_code, std::size_t)) - async_read_some(implementation_type& impl, - const MutableBufferSequence& buffers, - ASIO_MOVE_ARG(ReadHandler) handler) - { - asio::async_completion init(handler); - - service_impl_.async_read_some(impl, buffers, init.completion_handler); - - return init.result.get(); - } - -private: - // Destroy all user-defined handler objects owned by the service. - void shutdown() - { - service_impl_.shutdown(); - } - - // The platform-specific implementation. - service_impl_type service_impl_; -}; - -} // namespace windows -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#endif // defined(ASIO_HAS_WINDOWS_STREAM_HANDLE) - // || defined(GENERATING_DOCUMENTATION) - -#endif // defined(ASIO_ENABLE_OLD_SERVICES) - -#endif // ASIO_WINDOWS_STREAM_HANDLE_SERVICE_HPP diff --git a/scout_sdk/asio/asio/write.hpp b/scout_sdk/asio/asio/write.hpp deleted file mode 100644 index 517a842..0000000 --- a/scout_sdk/asio/asio/write.hpp +++ /dev/null @@ -1,927 +0,0 @@ -// -// write.hpp -// ~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WRITE_HPP -#define ASIO_WRITE_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/buffer.hpp" -#include "asio/error.hpp" - -#if !defined(ASIO_NO_EXTENSIONS) -# include "asio/basic_streambuf_fwd.hpp" -#endif // !defined(ASIO_NO_EXTENSIONS) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/** - * @defgroup write asio::write - * - * @brief Write a certain amount of data to a stream before returning. - */ -/*@{*/ - -/// Write all of the supplied data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * stream. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::write(s, asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::write( - * s, buffers, - * asio::transfer_all()); @endcode - */ -template -std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - typename enable_if< - is_const_buffer_sequence::value - >::type* = 0); - -/// Write all of the supplied data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * stream. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::write(s, asio::buffer(data, size), ec); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::write( - * s, buffers, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - asio::error_code& ec, - typename enable_if< - is_const_buffer_sequence::value - >::type* = 0); - -/// Write a certain amount of data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * stream. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's write_some function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::write(s, asio::buffer(data, size), - * asio::transfer_at_least(32)); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, - typename enable_if< - is_const_buffer_sequence::value - >::type* = 0); - -/// Write a certain amount of data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * stream. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's write_some function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t write(SyncWriteStream& s, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_const_buffer_sequence::value - >::type* = 0); - -/// Write all of the supplied data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied dynamic buffer sequence has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers The dynamic buffer sequence from which data will be written. - * Successfully written data is automatically consumed from the buffers. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @note This overload is equivalent to calling: - * @code asio::write( - * s, buffers, - * asio::transfer_all()); @endcode - */ -template -std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Write all of the supplied data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied dynamic buffer sequence has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers The dynamic buffer sequence from which data will be written. - * Successfully written data is automatically consumed from the buffers. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @note This overload is equivalent to calling: - * @code asio::write( - * s, buffers, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Write a certain amount of data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied dynamic buffer sequence has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers The dynamic buffer sequence from which data will be written. - * Successfully written data is automatically consumed from the buffers. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's write_some function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - */ -template -std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Write a certain amount of data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied dynamic buffer sequence has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param buffers The dynamic buffer sequence from which data will be written. - * Successfully written data is automatically consumed from the buffers. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's write_some function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t write(SyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, asio::error_code& ec, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Write all of the supplied data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param b The basic_streambuf object from which data will be written. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @note This overload is equivalent to calling: - * @code asio::write( - * s, b, - * asio::transfer_all()); @endcode - */ -template -std::size_t write(SyncWriteStream& s, basic_streambuf& b); - -/// Write all of the supplied data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param b The basic_streambuf object from which data will be written. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @note This overload is equivalent to calling: - * @code asio::write( - * s, b, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t write(SyncWriteStream& s, basic_streambuf& b, - asio::error_code& ec); - -/// Write a certain amount of data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param b The basic_streambuf object from which data will be written. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's write_some function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - */ -template -std::size_t write(SyncWriteStream& s, basic_streambuf& b, - CompletionCondition completion_condition); - -/// Write a certain amount of data to a stream before returning. -/** - * This function is used to write a certain number of bytes of data to a stream. - * The call will block until one of the following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * write_some function. - * - * @param s The stream to which the data is to be written. The type must support - * the SyncWriteStream concept. - * - * @param b The basic_streambuf object from which data will be written. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's write_some function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t write(SyncWriteStream& s, basic_streambuf& b, - CompletionCondition completion_condition, asio::error_code& ec); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ -/** - * @defgroup async_write asio::async_write - * - * @brief Start an asynchronous operation to write a certain amount of data to a - * stream. - */ -/*@{*/ - -/// Start an asynchronous operation to write all of the supplied data to a -/// stream. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_write_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other write operations (such - * as async_write, the stream's async_write_some function, or any other composed - * operations that perform writes) until this operation completes. - * - * @param s The stream to which the data is to be written. The type must support - * the AsyncWriteStream concept. - * - * @param buffers One or more buffers containing the data to be written. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes written from the - * // buffers. If an error occurred, - * // this will be less than the sum - * // of the buffer sizes. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * asio::async_write(s, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_const_buffer_sequence::value - >::type* = 0); - -/// Start an asynchronous operation to write a certain amount of data to a -/// stream. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_write_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other write operations (such - * as async_write, the stream's async_write_some function, or any other composed - * operations that perform writes) until this operation completes. - * - * @param s The stream to which the data is to be written. The type must support - * the AsyncWriteStream concept. - * - * @param buffers One or more buffers containing the data to be written. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's async_write_some function. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes written from the - * // buffers. If an error occurred, - * // this will be less than the sum - * // of the buffer sizes. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::async_write(s, - * asio::buffer(data, size), - * asio::transfer_at_least(32), - * handler); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_const_buffer_sequence::value - >::type* = 0); - -/// Start an asynchronous operation to write all of the supplied data to a -/// stream. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li All of the data in the supplied dynamic buffer sequence has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_write_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other write operations (such - * as async_write, the stream's async_write_some function, or any other composed - * operations that perform writes) until this operation completes. - * - * @param s The stream to which the data is to be written. The type must support - * the AsyncWriteStream concept. - * - * @param buffers The dynamic buffer sequence from which data will be written. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. Successfully written - * data is automatically consumed from the buffers. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes written from the - * // buffers. If an error occurred, - * // this will be less than the sum - * // of the buffer sizes. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -/// Start an asynchronous operation to write a certain amount of data to a -/// stream. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li All of the data in the supplied dynamic buffer sequence has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_write_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other write operations (such - * as async_write, the stream's async_write_some function, or any other composed - * operations that perform writes) until this operation completes. - * - * @param s The stream to which the data is to be written. The type must support - * the AsyncWriteStream concept. - * - * @param buffers The dynamic buffer sequence from which data will be written. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. Successfully written - * data is automatically consumed from the buffers. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's async_write_some function. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes written from the - * // buffers. If an error occurred, - * // this will be less than the sum - * // of the buffer sizes. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, - ASIO_MOVE_ARG(DynamicBuffer) buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler, - typename enable_if< - is_dynamic_buffer::type>::value - >::type* = 0); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Start an asynchronous operation to write all of the supplied data to a -/// stream. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_write_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other write operations (such - * as async_write, the stream's async_write_some function, or any other composed - * operations that perform writes) until this operation completes. - * - * @param s The stream to which the data is to be written. The type must support - * the AsyncWriteStream concept. - * - * @param b A basic_streambuf object from which data will be written. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes written from the - * // buffers. If an error occurred, - * // this will be less than the sum - * // of the buffer sizes. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, basic_streambuf& b, - ASIO_MOVE_ARG(WriteHandler) handler); - -/// Start an asynchronous operation to write a certain amount of data to a -/// stream. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a stream. The function call always returns immediately. The - * asynchronous operation will continue until one of the following conditions - * is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the stream's - * async_write_some function, and is known as a composed operation. The - * program must ensure that the stream performs no other write operations (such - * as async_write, the stream's async_write_some function, or any other composed - * operations that perform writes) until this operation completes. - * - * @param s The stream to which the data is to be written. The type must support - * the AsyncWriteStream concept. - * - * @param b A basic_streambuf object from which data will be written. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_write_some operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the stream's async_write_some function. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * const asio::error_code& error, // Result of operation. - * - * std::size_t bytes_transferred // Number of bytes written from the - * // buffers. If an error occurred, - * // this will be less than the sum - * // of the buffer sizes. - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write(AsyncWriteStream& s, basic_streambuf& b, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/write.hpp" - -#endif // ASIO_WRITE_HPP diff --git a/scout_sdk/asio/asio/write_at.hpp b/scout_sdk/asio/asio/write_at.hpp deleted file mode 100644 index 5018d21..0000000 --- a/scout_sdk/asio/asio/write_at.hpp +++ /dev/null @@ -1,677 +0,0 @@ -// -// write_at.hpp -// ~~~~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#ifndef ASIO_WRITE_AT_HPP -#define ASIO_WRITE_AT_HPP - -#if defined(_MSC_VER) && (_MSC_VER >= 1200) -# pragma once -#endif // defined(_MSC_VER) && (_MSC_VER >= 1200) - -#include "asio/detail/config.hpp" -#include -#include "asio/async_result.hpp" -#include "asio/detail/cstdint.hpp" -#include "asio/error.hpp" - -#if !defined(ASIO_NO_EXTENSIONS) -# include "asio/basic_streambuf_fwd.hpp" -#endif // !defined(ASIO_NO_EXTENSIONS) - -#include "asio/detail/push_options.hpp" - -namespace asio { - -/** - * @defgroup write_at asio::write_at - * - * @brief Write a certain amount of data at a specified offset before returning. - */ -/*@{*/ - -/// Write all of the supplied data at the specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * device. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::write_at(d, 42, asio::buffer(data, size)); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::write_at( - * d, offset, buffers, - * asio::transfer_all()); @endcode - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers); - -/// Write all of the supplied data at the specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * device. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::write_at(d, 42, - * asio::buffer(data, size), ec); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - * - * @note This overload is equivalent to calling: - * @code asio::write_at( - * d, offset, buffers, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - asio::error_code& ec); - -/// Write a certain amount of data at a specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * device. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the device's write_some_at function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::write_at(d, 42, asio::buffer(data, size), - * asio::transfer_at_least(32)); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - CompletionCondition completion_condition); - -/// Write a certain amount of data at a specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more buffers containing the data to be written. The sum - * of the buffer sizes indicates the maximum number of bytes to write to the - * device. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the device's write_some_at function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, asio::error_code& ec); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Write all of the supplied data at the specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param b The basic_streambuf object from which data will be written. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - * - * @note This overload is equivalent to calling: - * @code asio::write_at( - * d, 42, b, - * asio::transfer_all()); @endcode - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, basic_streambuf& b); - -/// Write all of the supplied data at the specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param b The basic_streambuf object from which data will be written. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes transferred. - * - * @note This overload is equivalent to calling: - * @code asio::write_at( - * d, 42, b, - * asio::transfer_all(), ec); @endcode - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, - uint64_t offset, basic_streambuf& b, - asio::error_code& ec); - -/// Write a certain amount of data at a specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param b The basic_streambuf object from which data will be written. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the device's write_some_at function. - * - * @returns The number of bytes transferred. - * - * @throws asio::system_error Thrown on failure. - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, uint64_t offset, - basic_streambuf& b, CompletionCondition completion_condition); - -/// Write a certain amount of data at a specified offset before returning. -/** - * This function is used to write a certain number of bytes of data to a random - * access device at a specified offset. The call will block until one of the - * following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * write_some_at function. - * - * @param d The device to which the data is to be written. The type must support - * the SyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param b The basic_streambuf object from which data will be written. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest write_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the device's write_some_at function. - * - * @param ec Set to indicate what error occurred, if any. - * - * @returns The number of bytes written. If an error occurs, returns the total - * number of bytes successfully transferred prior to the error. - */ -template -std::size_t write_at(SyncRandomAccessWriteDevice& d, uint64_t offset, - basic_streambuf& b, CompletionCondition completion_condition, - asio::error_code& ec); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ -/** - * @defgroup async_write_at asio::async_write_at - * - * @brief Start an asynchronous operation to write a certain amount of data at - * the specified offset. - */ -/*@{*/ - -/// Start an asynchronous operation to write all of the supplied data at the -/// specified offset. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a random access device at a specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * async_write_some_at function, and is known as a composed operation. - * The program must ensure that the device performs no overlapping - * write operations (such as async_write_at, the device's async_write_some_at - * function, or any other composed operations that perform writes) until this - * operation completes. Operations are overlapping if the regions defined by - * their offsets, and the numbers of bytes to write, intersect. - * - * @param d The device to which the data is to be written. The type must support - * the AsyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more buffers containing the data to be written. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of - * the handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes written from the buffers. If an error - * // occurred, this will be less than the sum of the buffer sizes. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code - * asio::async_write_at(d, 42, asio::buffer(data, size), handler); - * @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, uint64_t offset, - const ConstBufferSequence& buffers, - ASIO_MOVE_ARG(WriteHandler) handler); - -/// Start an asynchronous operation to write a certain amount of data at the -/// specified offset. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a random access device at a specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li All of the data in the supplied buffers has been written. That is, the - * bytes transferred is equal to the sum of the buffer sizes. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * async_write_some_at function, and is known as a composed operation. - * The program must ensure that the device performs no overlapping - * write operations (such as async_write_at, the device's async_write_some_at - * function, or any other composed operations that perform writes) until this - * operation completes. Operations are overlapping if the regions defined by - * their offsets, and the numbers of bytes to write, intersect. - * - * @param d The device to which the data is to be written. The type must support - * the AsyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param buffers One or more buffers containing the data to be written. - * Although the buffers object may be copied as necessary, ownership of the - * underlying memory blocks is retained by the caller, which must guarantee - * that they remain valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_write_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the device's async_write_some_at function. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes written from the buffers. If an error - * // occurred, this will be less than the sum of the buffer sizes. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - * - * @par Example - * To write a single data buffer use the @ref buffer function as follows: - * @code asio::async_write_at(d, 42, - * asio::buffer(data, size), - * asio::transfer_at_least(32), - * handler); @endcode - * See the @ref buffer documentation for information on writing multiple - * buffers in one go, and how to use it with arrays, boost::array or - * std::vector. - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, - uint64_t offset, const ConstBufferSequence& buffers, - CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler); - -#if !defined(ASIO_NO_EXTENSIONS) -#if !defined(ASIO_NO_IOSTREAM) - -/// Start an asynchronous operation to write all of the supplied data at the -/// specified offset. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a random access device at a specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li An error occurred. - * - * This operation is implemented in terms of zero or more calls to the device's - * async_write_some_at function, and is known as a composed operation. - * The program must ensure that the device performs no overlapping - * write operations (such as async_write_at, the device's async_write_some_at - * function, or any other composed operations that perform writes) until this - * operation completes. Operations are overlapping if the regions defined by - * their offsets, and the numbers of bytes to write, intersect. - * - * @param d The device to which the data is to be written. The type must support - * the AsyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param b A basic_streambuf object from which data will be written. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes written from the buffers. If an error - * // occurred, this will be less than the sum of the buffer sizes. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, uint64_t offset, - basic_streambuf& b, ASIO_MOVE_ARG(WriteHandler) handler); - -/// Start an asynchronous operation to write a certain amount of data at the -/// specified offset. -/** - * This function is used to asynchronously write a certain number of bytes of - * data to a random access device at a specified offset. The function call - * always returns immediately. The asynchronous operation will continue until - * one of the following conditions is true: - * - * @li All of the data in the supplied basic_streambuf has been written. - * - * @li The completion_condition function object returns 0. - * - * This operation is implemented in terms of zero or more calls to the device's - * async_write_some_at function, and is known as a composed operation. - * The program must ensure that the device performs no overlapping - * write operations (such as async_write_at, the device's async_write_some_at - * function, or any other composed operations that perform writes) until this - * operation completes. Operations are overlapping if the regions defined by - * their offsets, and the numbers of bytes to write, intersect. - * - * @param d The device to which the data is to be written. The type must support - * the AsyncRandomAccessWriteDevice concept. - * - * @param offset The offset at which the data will be written. - * - * @param b A basic_streambuf object from which data will be written. Ownership - * of the streambuf is retained by the caller, which must guarantee that it - * remains valid until the handler is called. - * - * @param completion_condition The function object to be called to determine - * whether the write operation is complete. The signature of the function object - * must be: - * @code std::size_t completion_condition( - * // Result of latest async_write_some_at operation. - * const asio::error_code& error, - * - * // Number of bytes transferred so far. - * std::size_t bytes_transferred - * ); @endcode - * A return value of 0 indicates that the write operation is complete. A - * non-zero return value indicates the maximum number of bytes to be written on - * the next call to the device's async_write_some_at function. - * - * @param handler The handler to be called when the write operation completes. - * Copies will be made of the handler as required. The function signature of the - * handler must be: - * @code void handler( - * // Result of operation. - * const asio::error_code& error, - * - * // Number of bytes written from the buffers. If an error - * // occurred, this will be less than the sum of the buffer sizes. - * std::size_t bytes_transferred - * ); @endcode - * Regardless of whether the asynchronous operation completes immediately or - * not, the handler will not be invoked from within this function. Invocation of - * the handler will be performed in a manner equivalent to using - * asio::io_context::post(). - */ -template -ASIO_INITFN_RESULT_TYPE(WriteHandler, - void (asio::error_code, std::size_t)) -async_write_at(AsyncRandomAccessWriteDevice& d, uint64_t offset, - basic_streambuf& b, CompletionCondition completion_condition, - ASIO_MOVE_ARG(WriteHandler) handler); - -#endif // !defined(ASIO_NO_IOSTREAM) -#endif // !defined(ASIO_NO_EXTENSIONS) - -/*@}*/ - -} // namespace asio - -#include "asio/detail/pop_options.hpp" - -#include "asio/impl/write_at.hpp" - -#endif // ASIO_WRITE_AT_HPP diff --git a/scout_sdk/asio/asio/yield.hpp b/scout_sdk/asio/asio/yield.hpp deleted file mode 100644 index b527ac9..0000000 --- a/scout_sdk/asio/asio/yield.hpp +++ /dev/null @@ -1,23 +0,0 @@ -// -// yield.hpp -// ~~~~~~~~~ -// -// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com) -// -// Distributed under the Boost Software License, Version 1.0. (See accompanying -// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) -// - -#include "coroutine.hpp" - -#ifndef reenter -# define reenter(c) ASIO_CORO_REENTER(c) -#endif - -#ifndef yield -# define yield ASIO_CORO_YIELD -#endif - -#ifndef fork -# define fork ASIO_CORO_FORK -#endif diff --git a/scout_sdk/docs/SCOUT_UserManual_v1.2.10_S.pdf b/scout_sdk/docs/SCOUT_UserManual_v1.2.10_S.pdf deleted file mode 100644 index 95df6c2..0000000 Binary files a/scout_sdk/docs/SCOUT_UserManual_v1.2.10_S.pdf and /dev/null differ diff --git a/scout_sdk/docs/misc/SCOUT_UserManual_v1.2.8_CN.pdf b/scout_sdk/docs/misc/SCOUT_UserManual_v1.2.8_CN.pdf deleted file mode 100644 index 4f34c71..0000000 Binary files a/scout_sdk/docs/misc/SCOUT_UserManual_v1.2.8_CN.pdf and /dev/null differ diff --git a/scout_sdk/docs/misc/beaglebone_black_can_cape.md b/scout_sdk/docs/misc/beaglebone_black_can_cape.md deleted file mode 100644 index 22a6265..0000000 --- a/scout_sdk/docs/misc/beaglebone_black_can_cape.md +++ /dev/null @@ -1,23 +0,0 @@ -# Setup CAN on Beaglebone Black - -CAN/RS485 Cape: https://item.taobao.com/item.htm?spm=a1z09.2.0.0.68b02e8d02l2uT&id=42637485181&_u=a4mg52ma183 - -* Install latest Debian image from offical site -* Build and install overlays -``` -$ sudo apt install device-tree-compiler -$ git clone https://github.com/beagleboard/bb.org-overlays -$ cd ./bb.org-overlays/ -$ ./install.sh -``` -* Edit /boot/uEnv.txt -``` -# 1. Add the following overlay -###Custom Cape -dtb_overlay=/lib/firmware/BB-CAN1-00A0.dtbo - -# 2. Disable auto loading of virutal capes (uncomment the two lines) -disable_uboot_overlay_video=1 -disable_uboot_overlay_audio=1 -``` -* Reboot the system \ No newline at end of file diff --git a/scout_sdk/docs/misc/beaglebone_ros_install.md b/scout_sdk/docs/misc/beaglebone_ros_install.md deleted file mode 100644 index cb63e7a..0000000 --- a/scout_sdk/docs/misc/beaglebone_ros_install.md +++ /dev/null @@ -1,51 +0,0 @@ -``` -$ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu stretch main" > /etc/apt/sources.list.d/ros-latest.list' -$ wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -O - | sudo apt-key add - -$ sudo apt-get update -``` - -``` -$ sudo apt-get install -y python-pip python-setuptools python-yaml python-distribute python-docutils python-dateutil python-six -$ sudo pip install rosdep rosinstall_generator wstool rosinstall -$ sudo apt-get install -y \ - libconsole-bridge-dev liblz4-dev checkinstall cmake \ - python-empy python-nose libbz2-dev \ - libboost-test-dev libboost-dev libboost-program-options-dev \ - libboost-regex-dev libboost-signals-dev \ - libtinyxml-dev libboost-filesystem-dev libxml2-dev \ - libgtest-dev libpoco-dev -``` - -``` -$ sudo rosdep init -$ rosdep update -``` - -``` -$ rosinstall_generator ros_comm --rosdistro melodic --deps --tar > melodic-ros_comm.rosinstall -$ wstool init -j1 src melodic-ros_comm.rosinstall -``` - -``` -$ # rosdep install --from-paths src --ignore-src --rosdistro melodic -y -$ sudo ./src/catkin/bin/catkin_make_isolated --install --install-space /opt/ros/melodic -DCMAKE_BUILD_TYPE=Release -``` - -``` -$ source /opt/ros/melodic/setup.bash -``` - -Additional runtime dependencies: - -``` -$ sudo apt install -y python-defusedxml python-netifaces -``` - -``` -$ sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys F42ED6FBAB17C654 -``` - -Reference: - -* [1] https://machinekoder.com/ros-with-debian-stretch-on-the-beaglebone-black-green-blue/ -* [2] http://wiki.ros.org/melodic/Installation/Source \ No newline at end of file diff --git a/scout_sdk/docs/misc/can_msg.txt b/scout_sdk/docs/misc/can_msg.txt deleted file mode 100644 index 80b9832..0000000 --- a/scout_sdk/docs/misc/can_msg.txt +++ /dev/null @@ -1,2248 +0,0 @@ - can1 203 [8] 00 00 00 00 00 00 E2 EF - can1 141 [8] 00 00 00 02 0F 00 E2 3D - can1 131 [8] 00 00 00 00 00 00 E4 1E - can1 200 [8] 00 00 00 00 00 00 E3 ED - can1 201 [8] 00 00 00 00 00 00 E3 EE - can1 202 [8] 00 00 00 00 00 00 E3 EF - can1 203 [8] 00 00 00 00 00 00 E3 F0 - can1 141 [8] 00 00 00 02 0E 00 E3 3D - can1 151 [8] 01 00 00 EF 00 3C E4 6A - can1 131 [8] 00 00 00 00 00 00 E5 1F - can1 200 [8] 00 00 00 00 00 00 E4 EE - can1 201 [8] 00 00 00 00 00 00 E4 EF - can1 202 [8] 00 00 00 00 00 00 E4 F0 - can1 203 [8] 00 00 00 00 00 00 E4 F1 - can1 141 [8] 00 00 00 02 0E 00 E4 3E - can1 151 [8] 01 00 00 EF 00 3C E5 6B - can1 131 [8] 00 00 00 00 00 00 E6 20 - can1 200 [8] 00 00 00 00 00 00 E5 EF - can1 201 [8] 00 00 00 00 00 00 E5 F0 - can1 202 [8] 00 00 00 00 00 00 E5 F1 - can1 203 [8] 00 00 00 00 00 00 E5 F2 - can1 141 [8] 00 00 00 02 0D 00 E5 3E - can1 151 [8] 01 00 00 EF 00 3C E6 6C - can1 131 [8] 00 00 00 00 00 00 E7 21 - can1 200 [8] 00 00 00 00 00 00 E6 F0 - can1 201 [8] 00 00 00 00 00 00 E6 F1 - can1 202 [8] 00 00 00 00 00 00 E6 F2 - can1 203 [8] 00 00 00 00 00 00 E6 F3 - can1 141 [8] 00 00 00 02 0C 00 E6 3E - can1 151 [8] 01 00 00 EF 00 3C E7 6D - can1 151 [8] 01 00 00 EF 00 3C E8 6E - can1 131 [8] 00 00 00 00 00 00 E8 22 - can1 200 [8] 00 00 00 00 00 00 E7 F1 - can1 201 [8] 00 00 00 00 00 00 E7 F2 - can1 202 [8] 00 00 00 00 00 00 E7 F3 - can1 203 [8] 00 00 00 00 00 00 E7 F4 - can1 141 [8] 00 00 00 02 0B 00 E7 3E - can1 131 [8] 00 00 00 00 00 00 E9 23 - can1 200 [8] 00 00 00 00 00 00 E8 F2 - can1 201 [8] 00 00 00 00 00 00 E8 F3 - can1 202 [8] 00 00 00 00 00 00 E8 F4 - can1 203 [8] 00 00 00 00 00 00 E8 F5 - can1 141 [8] 00 00 00 02 0A 00 E8 3E - can1 151 [8] 01 00 00 EF 00 3C E9 6F - can1 131 [8] 00 00 00 00 00 00 EA 24 - can1 200 [8] 00 00 00 00 00 00 E9 F3 - can1 201 [8] 00 00 00 00 00 00 E9 F4 - can1 202 [8] 00 00 00 00 00 00 E9 F5 - can1 203 [8] 00 00 00 00 00 00 E9 F6 - can1 141 [8] 00 00 00 02 0A 00 E9 3F - can1 151 [8] 01 00 00 EF 00 3C EA 70 - can1 131 [8] 00 00 00 00 00 00 EB 25 - can1 200 [8] 00 00 00 00 00 00 EA F4 - can1 201 [8] 00 00 00 00 00 00 EA F5 - can1 202 [8] 00 00 00 00 00 00 EA F6 - can1 203 [8] 00 00 00 00 00 00 EA F7 - can1 141 [8] 00 00 00 02 09 00 EA 3F - can1 151 [8] 01 00 00 EF 00 3C EB 71 - can1 131 [8] 00 00 00 00 00 00 EC 26 - can1 200 [8] 00 00 00 00 00 00 EB F5 - can1 201 [8] 00 00 00 00 00 00 EB F6 - can1 202 [8] 00 00 00 00 00 00 EB F7 - can1 203 [8] 00 00 00 00 00 00 EB F8 - can1 141 [8] 00 00 00 02 08 00 EB 3F - can1 151 [8] 01 00 00 EF 00 3C EC 72 - can1 131 [8] 00 00 00 00 00 00 ED 27 - can1 200 [8] 00 00 00 00 00 00 EC F6 - can1 201 [8] 00 00 00 00 00 00 EC F7 - can1 202 [8] 00 00 00 00 00 00 EC F8 - can1 203 [8] 00 00 00 00 00 00 EC F9 - can1 141 [8] 00 00 00 02 07 00 EC 3F - can1 151 [8] 01 00 00 EF 00 3C ED 73 - can1 131 [8] 00 00 00 00 00 00 EE 28 - can1 200 [8] 00 00 00 00 00 00 ED F7 - can1 201 [8] 00 00 00 00 00 00 ED F8 - can1 202 [8] 00 00 00 00 00 00 ED F9 - can1 203 [8] 00 00 00 00 00 00 ED FA - can1 141 [8] 00 00 00 02 06 00 ED 3F - can1 151 [8] 01 00 00 EF 00 3C EE 74 - can1 131 [8] 00 00 00 00 00 00 EF 29 - can1 200 [8] 00 00 00 00 00 00 EE F8 - can1 201 [8] 00 00 00 00 00 00 EE F9 - can1 202 [8] 00 00 00 00 00 00 EE FA - can1 203 [8] 00 00 00 00 00 00 EE FB - can1 141 [8] 00 00 00 02 06 00 EE 40 - can1 151 [8] 01 00 00 EF 00 3C EF 75 - can1 131 [8] 00 00 00 00 00 00 F0 2A - can1 200 [8] 00 00 00 00 00 00 EF F9 - can1 201 [8] 00 00 00 00 00 00 EF FA - can1 202 [8] 00 00 00 00 00 00 EF FB - can1 203 [8] 00 00 00 00 00 00 EF FC - can1 141 [8] 00 00 00 02 05 00 EF 40 - can1 151 [8] 01 00 00 EF 00 3C F0 76 - can1 131 [8] 00 00 00 00 00 00 F1 2B - can1 200 [8] 00 00 00 00 00 00 F0 FA - can1 201 [8] 00 00 00 00 00 00 F0 FB - can1 202 [8] 00 00 00 00 00 00 F0 FC - can1 203 [8] 00 00 00 00 00 00 F0 FD - can1 141 [8] 00 00 00 02 04 00 F0 40 - can1 151 [8] 01 00 00 EF 00 3C F1 77 - can1 131 [8] 00 00 00 00 00 00 F2 2C - can1 200 [8] 00 00 00 00 00 00 F1 FB - can1 201 [8] 00 00 00 00 00 00 F1 FC - can1 202 [8] 00 00 00 00 00 00 F1 FD - can1 203 [8] 00 00 00 00 00 00 F1 FE - can1 141 [8] 00 00 00 02 03 00 F1 40 - can1 151 [8] 01 00 00 EF 00 3C F2 78 - can1 131 [8] 00 00 00 00 00 00 F3 2D - can1 200 [8] 00 00 00 00 00 00 F2 FC - can1 201 [8] 00 00 00 00 00 00 F2 FD - can1 202 [8] 00 00 00 00 00 00 F2 FE - can1 203 [8] 00 00 00 00 00 00 F2 FF - can1 141 [8] 00 00 00 02 02 00 F2 40 - can1 151 [8] 01 00 00 EF 00 3C F3 79 - can1 131 [8] 00 00 00 00 00 00 F4 2E - can1 200 [8] 00 00 00 00 00 00 F3 FD - can1 201 [8] 00 00 00 00 00 00 F3 FE - can1 202 [8] 00 00 00 00 00 00 F3 FF - can1 203 [8] 00 00 00 00 00 00 F3 00 - can1 141 [8] 00 00 00 02 02 00 F3 41 - can1 151 [8] 01 00 00 EF 00 3C F4 7A - can1 131 [8] 00 00 00 00 00 00 F5 2F - can1 200 [8] 00 00 00 00 00 00 F4 FE - can1 201 [8] 00 00 00 00 00 00 F4 FF - can1 202 [8] 00 00 00 00 00 00 F4 00 - can1 203 [8] 00 00 00 00 00 00 F4 01 - can1 141 [8] 00 00 00 02 01 00 F4 41 - can1 151 [8] 01 00 00 EF 00 3C F5 7B - can1 151 [8] 01 00 00 EF 00 3C F6 7C - can1 131 [8] 00 00 00 00 00 00 F6 30 - can1 200 [8] 00 00 00 00 00 00 F5 FF - can1 201 [8] 00 00 00 00 00 00 F5 00 - can1 202 [8] 00 00 00 00 00 00 F5 01 - can1 203 [8] 00 00 00 00 00 00 F5 02 - can1 141 [8] 00 00 00 02 00 00 F5 41 - can1 131 [8] 00 00 00 00 00 00 F7 31 - can1 200 [8] 00 00 00 00 00 00 F6 00 - can1 201 [8] 00 00 00 00 00 00 F6 01 - can1 202 [8] 00 00 00 00 00 00 F6 02 - can1 203 [8] 00 00 00 00 00 00 F6 03 - can1 141 [8] 00 00 00 02 01 00 F6 43 - can1 151 [8] 01 00 00 EF 00 3C F7 7D - can1 131 [8] 00 00 00 00 00 00 F8 32 - can1 200 [8] 00 00 00 00 00 00 F7 01 - can1 201 [8] 00 00 00 00 00 00 F7 02 - can1 202 [8] 00 00 00 00 00 00 F7 03 - can1 203 [8] 00 00 00 00 00 00 F7 04 - can1 141 [8] 00 00 00 02 02 00 F7 45 - can1 151 [8] 01 00 00 EF 00 3C F8 7E - can1 131 [8] 00 00 00 00 00 00 F9 33 - can1 200 [8] 00 00 00 00 00 00 F8 02 - can1 201 [8] 00 00 00 00 00 00 F8 03 - can1 202 [8] 00 00 00 00 00 00 F8 04 - can1 203 [8] 00 00 00 00 00 00 F8 05 - can1 141 [8] 00 00 00 02 02 00 F8 46 - can1 151 [8] 01 00 00 EF 00 3C F9 7F - can1 131 [8] 00 00 00 00 00 00 FA 34 - can1 200 [8] 00 00 00 00 00 00 F9 03 - can1 201 [8] 00 00 00 00 00 00 F9 04 - can1 202 [8] 00 00 00 00 00 00 F9 05 - can1 203 [8] 00 00 00 00 00 00 F9 06 - can1 141 [8] 00 00 00 02 03 00 F9 48 - can1 151 [8] 01 00 00 EF 00 3C FA 80 - can1 131 [8] 00 00 00 00 00 00 FB 35 - can1 200 [8] 00 00 00 00 00 00 FA 04 - can1 201 [8] 00 00 00 00 00 00 FA 05 - can1 202 [8] 00 00 00 00 00 00 FA 06 - can1 203 [8] 00 00 00 00 00 00 FA 07 - can1 141 [8] 00 00 00 02 04 00 FA 4A - can1 151 [8] 01 00 00 EF 00 3C FB 81 - can1 131 [8] 00 00 00 00 00 00 FC 36 - can1 200 [8] 00 00 00 00 00 00 FB 05 - can1 201 [8] 00 00 00 00 00 00 FB 06 - can1 202 [8] 00 00 00 00 00 00 FB 07 - can1 203 [8] 00 00 00 00 00 00 FB 08 - can1 141 [8] 00 00 00 02 05 00 FB 4C - can1 151 [8] 01 00 00 EF 00 3C FC 82 - can1 131 [8] 00 00 00 00 00 00 FD 37 - can1 200 [8] 00 00 00 00 00 00 FC 06 - can1 201 [8] 00 00 00 00 00 00 FC 07 - can1 202 [8] 00 00 00 00 00 00 FC 08 - can1 203 [8] 00 00 00 00 00 00 FC 09 - can1 141 [8] 00 00 00 02 06 00 FC 4E - can1 151 [8] 01 00 00 EF 00 3C FD 83 - can1 131 [8] 00 00 00 00 00 00 FE 38 - can1 200 [8] 00 00 00 00 00 00 FD 07 - can1 201 [8] 00 00 00 00 00 00 FD 08 - can1 202 [8] 00 00 00 00 00 00 FD 09 - can1 203 [8] 00 00 00 00 00 00 FD 0A - can1 141 [8] 00 00 00 02 07 00 FD 50 - can1 151 [8] 01 00 00 EF 00 3C FE 84 - can1 131 [8] 00 00 00 00 00 00 FF 39 - can1 200 [8] 00 00 00 00 00 00 FE 08 - can1 201 [8] 00 00 00 00 00 00 FE 09 - can1 202 [8] 00 00 00 00 00 00 FE 0A - can1 203 [8] 00 00 00 00 00 00 FE 0B - can1 141 [8] 00 00 00 02 07 00 FE 51 - can1 151 [8] 01 00 00 EF 00 3C FF 85 - can1 131 [8] 00 00 00 00 00 00 00 3A - can1 200 [8] 00 00 00 00 00 00 FF 09 - can1 201 [8] 00 00 00 00 00 00 FF 0A - can1 202 [8] 00 00 00 00 00 00 FF 0B - can1 203 [8] 00 00 00 00 00 00 FF 0C - can1 141 [8] 00 00 00 02 08 00 FF 53 - can1 151 [8] 01 00 00 EF 00 3C 00 86 - can1 131 [8] 00 00 00 00 00 00 01 3B - can1 200 [8] 00 00 00 00 00 00 00 0A - can1 201 [8] 00 00 00 00 00 00 00 0B - can1 202 [8] 00 00 00 00 00 00 00 0C - can1 203 [8] 00 00 00 00 00 00 00 0D - can1 141 [8] 00 00 00 02 09 00 00 55 - can1 151 [8] 01 00 00 EF 00 3C 01 87 - can1 131 [8] 00 00 00 00 00 00 02 3C - can1 200 [8] 00 00 00 00 00 00 01 0B - can1 201 [8] 00 00 00 00 00 00 01 0C - can1 202 [8] 00 00 00 00 00 00 01 0D - can1 203 [8] 00 00 00 00 00 00 01 0E - can1 141 [8] 00 00 00 02 0A 00 01 57 - can1 151 [8] 01 00 00 EF 00 3C 02 88 - can1 131 [8] 00 00 00 00 00 00 03 3D - can1 200 [8] 00 00 00 00 00 00 02 0C - can1 201 [8] 00 00 00 00 00 00 02 0D - can1 202 [8] 00 00 00 00 00 00 02 0E - can1 203 [8] 00 00 00 00 00 00 02 0F - can1 141 [8] 00 00 00 02 0B 00 02 59 - can1 151 [8] 01 00 00 EF 00 3C 03 89 - can1 131 [8] 00 00 00 00 00 00 04 3E - can1 200 [8] 00 00 00 00 00 00 03 0D - can1 201 [8] 00 00 00 00 00 00 03 0E - can1 202 [8] 00 00 00 00 00 00 03 0F - can1 203 [8] 00 00 00 00 00 00 03 10 - can1 141 [8] 00 00 00 02 0B 00 03 5A - can1 151 [8] 01 00 00 EF 00 3C 04 8A - can1 131 [8] 00 00 00 00 00 00 05 3F - can1 200 [8] 00 00 00 00 00 00 04 0E - can1 201 [8] 00 00 00 00 00 00 04 0F - can1 202 [8] 00 00 00 00 00 00 04 10 - can1 203 [8] 00 00 00 00 00 00 04 11 - can1 141 [8] 00 00 00 02 0C 00 04 5C - can1 151 [8] 01 00 00 EF 00 3C 05 8B - can1 131 [8] 00 00 00 00 00 00 06 40 - can1 200 [8] 00 00 00 00 00 00 05 0F - can1 201 [8] 00 00 00 00 00 00 05 10 - can1 202 [8] 00 00 00 00 00 00 05 11 - can1 203 [8] 00 00 00 00 00 00 05 12 - can1 141 [8] 00 00 00 02 0D 00 05 5E - can1 151 [8] 01 00 00 EF 00 3C 06 8C - can1 131 [8] 00 00 00 00 00 00 07 41 - can1 200 [8] 00 00 00 00 00 00 06 10 - can1 201 [8] 00 00 00 00 00 00 06 11 - can1 202 [8] 00 00 00 00 00 00 06 12 - can1 203 [8] 00 00 00 00 00 00 06 13 - can1 141 [8] 00 00 00 02 0E 00 06 60 - can1 151 [8] 01 00 00 EF 00 3C 07 8D - can1 131 [8] 00 00 00 00 00 00 08 42 - can1 200 [8] 00 00 00 00 00 00 07 11 - can1 201 [8] 00 00 00 00 00 00 07 12 - can1 202 [8] 00 00 00 00 00 00 07 13 - can1 203 [8] 00 00 00 00 00 00 07 14 - can1 141 [8] 00 00 00 02 0F 00 07 62 - can1 151 [8] 01 00 00 EF 00 3C 08 8E - can1 131 [8] 00 00 00 00 00 00 09 43 - can1 200 [8] 00 00 00 00 00 00 08 12 - can1 201 [8] 00 00 00 00 00 00 08 13 - can1 202 [8] 00 00 00 00 00 00 08 14 - can1 203 [8] 00 00 00 00 00 00 08 15 - can1 141 [8] 00 00 00 02 0F 00 08 63 - can1 151 [8] 01 00 00 EF 00 3C 09 8F - can1 151 [8] 01 00 00 EF 00 3C 0A 90 - can1 131 [8] 00 00 00 00 00 00 0A 44 - can1 200 [8] 00 00 00 00 00 00 09 13 - can1 201 [8] 00 00 00 00 00 00 09 14 - can1 202 [8] 00 00 00 00 00 00 09 15 - can1 203 [8] 00 00 00 00 00 00 09 16 - can1 141 [8] 00 00 00 02 10 00 09 65 - can1 131 [8] 00 00 00 00 00 00 0B 45 - can1 200 [8] 00 00 00 00 00 00 0A 14 - can1 201 [8] 00 00 00 00 00 00 0A 15 - can1 202 [8] 00 00 00 00 00 00 0A 16 - can1 203 [8] 00 00 00 00 00 00 0A 17 - can1 141 [8] 00 00 00 02 11 00 0A 67 - can1 151 [8] 01 00 00 EF 00 3C 0B 91 - can1 131 [8] 00 00 00 00 00 00 0C 46 - can1 200 [8] 00 00 00 00 00 00 0B 15 - can1 201 [8] 00 00 00 00 00 00 0B 16 - can1 202 [8] 00 00 00 00 00 00 0B 17 - can1 203 [8] 00 00 00 00 00 00 0B 18 - can1 141 [8] 00 00 00 02 12 00 0B 69 - can1 151 [8] 01 00 00 EF 00 3C 0C 92 - can1 131 [8] 00 00 00 00 00 00 0D 47 - can1 200 [8] 00 00 00 00 00 00 0C 16 - can1 201 [8] 00 00 00 00 00 00 0C 17 - can1 202 [8] 00 00 00 00 00 00 0C 18 - can1 203 [8] 00 00 00 00 00 00 0C 19 - can1 141 [8] 00 00 00 02 13 00 0C 6B - can1 151 [8] 01 00 00 EF 00 3C 0D 93 - can1 131 [8] 00 00 00 00 00 00 0E 48 - can1 200 [8] 00 00 00 00 00 00 0D 17 - can1 201 [8] 00 00 00 00 00 00 0D 18 - can1 202 [8] 00 00 00 00 00 00 0D 19 - can1 203 [8] 00 00 00 00 00 00 0D 1A - can1 141 [8] 00 00 00 02 13 00 0D 6C - can1 151 [8] 01 00 00 EF 00 3C 0E 94 - can1 131 [8] 00 00 00 00 00 00 0F 49 - can1 200 [8] 00 00 00 00 00 00 0E 18 - can1 201 [8] 00 00 00 00 00 00 0E 19 - can1 202 [8] 00 00 00 00 00 00 0E 1A - can1 203 [8] 00 00 00 00 00 00 0E 1B - can1 141 [8] 00 00 00 02 14 00 0E 6E - can1 151 [8] 01 00 00 EF 00 3C 0F 95 - can1 131 [8] 00 00 00 00 00 00 10 4A - can1 200 [8] 00 00 00 00 00 00 0F 19 - can1 201 [8] 00 00 00 00 00 00 0F 1A - can1 202 [8] 00 00 00 00 00 00 0F 1B - can1 203 [8] 00 00 00 00 00 00 0F 1C - can1 141 [8] 00 00 00 02 15 00 0F 70 - can1 151 [8] 01 00 00 EF 00 3C 10 96 - can1 131 [8] 00 00 00 00 00 00 11 4B - can1 200 [8] 00 00 00 00 00 00 10 1A - can1 201 [8] 00 00 00 00 00 00 10 1B - can1 202 [8] 00 00 00 00 00 00 10 1C - can1 203 [8] 00 00 00 00 00 00 10 1D - can1 141 [8] 00 00 00 02 16 00 10 72 - can1 151 [8] 01 00 00 EF 00 3C 11 97 - can1 131 [8] 00 00 00 00 00 00 12 4C - can1 200 [8] 00 00 00 00 00 00 11 1B - can1 201 [8] 00 00 00 00 00 00 11 1C - can1 202 [8] 00 00 00 00 00 00 11 1D - can1 203 [8] 00 00 00 00 00 00 11 1E - can1 141 [8] 00 00 00 02 17 00 11 74 - can1 151 [8] 01 00 00 EF 00 3C 12 98 - can1 131 [8] 00 00 00 00 00 00 13 4D - can1 200 [8] 00 00 00 00 00 00 12 1C - can1 201 [8] 00 00 00 00 00 00 12 1D - can1 202 [8] 00 00 00 00 00 00 12 1E - can1 203 [8] 00 00 00 00 00 00 12 1F - can1 141 [8] 00 00 00 02 17 00 12 75 - can1 151 [8] 01 00 00 EF 00 3C 13 99 - can1 131 [8] 00 00 00 00 00 00 14 4E - can1 200 [8] 00 00 00 00 00 00 13 1D - can1 201 [8] 00 00 00 00 00 00 13 1E - can1 202 [8] 00 00 00 00 00 00 13 1F - can1 203 [8] 00 00 00 00 00 00 13 20 - can1 141 [8] 00 00 00 02 18 00 13 77 - can1 151 [8] 01 00 00 EF 00 3C 14 9A - can1 131 [8] 00 00 00 00 00 00 15 4F - can1 200 [8] 00 00 00 00 00 00 14 1E - can1 201 [8] 00 00 00 00 00 00 14 1F - can1 202 [8] 00 00 00 00 00 00 14 20 - can1 203 [8] 00 00 00 00 00 00 14 21 - can1 141 [8] 00 00 00 02 19 00 14 79 - can1 151 [8] 01 00 00 EF 00 3C 15 9B - can1 131 [8] 00 00 00 00 00 00 16 50 - can1 200 [8] 00 00 00 00 00 00 15 1F - can1 201 [8] 00 00 00 00 00 00 15 20 - can1 202 [8] 00 00 00 00 00 00 15 21 - can1 203 [8] 00 00 00 00 00 00 15 22 - can1 141 [8] 00 00 00 02 1A 00 15 7B - can1 151 [8] 01 00 00 EF 00 3C 16 9C - can1 131 [8] 00 00 00 00 00 00 17 51 - can1 200 [8] 00 00 00 00 00 00 16 20 - can1 201 [8] 00 00 00 00 00 00 16 21 - can1 202 [8] 00 00 00 00 00 00 16 22 - can1 203 [8] 00 00 00 00 00 00 16 23 - can1 141 [8] 00 00 00 02 1B 00 16 7D - can1 151 [8] 01 00 00 EF 00 3C 17 9D - can1 131 [8] 00 00 00 00 00 00 18 52 - can1 200 [8] 00 00 00 00 00 00 17 21 - can1 201 [8] 00 00 00 00 00 00 17 22 - can1 202 [8] 00 00 00 00 00 00 17 23 - can1 203 [8] 00 00 00 00 00 00 17 24 - can1 141 [8] 00 00 00 02 1C 00 17 7F - can1 151 [8] 01 00 00 EF 00 3C 18 9E - can1 131 [8] 00 00 00 00 00 00 19 53 - can1 200 [8] 00 00 00 00 00 00 18 22 - can1 201 [8] 00 00 00 00 00 00 18 23 - can1 202 [8] 00 00 00 00 00 00 18 24 - can1 203 [8] 00 00 00 00 00 00 18 25 - can1 141 [8] 00 00 00 02 1C 00 18 80 - can1 151 [8] 01 00 00 EF 00 3C 19 9F - can1 131 [8] 00 00 00 00 00 00 1A 54 - can1 200 [8] 00 00 00 00 00 00 19 23 - can1 201 [8] 00 00 00 00 00 00 19 24 - can1 202 [8] 00 00 00 00 00 00 19 25 - can1 203 [8] 00 00 00 00 00 00 19 26 - can1 141 [8] 00 00 00 02 1D 00 19 82 - can1 151 [8] 01 00 00 EF 00 3C 1A A0 - can1 131 [8] 00 00 00 00 00 00 1B 55 - can1 200 [8] 00 00 00 00 00 00 1A 24 - can1 201 [8] 00 00 00 00 00 00 1A 25 - can1 202 [8] 00 00 00 00 00 00 1A 26 - can1 203 [8] 00 00 00 00 00 00 1A 27 - can1 141 [8] 00 00 00 02 1E 00 1A 84 - can1 151 [8] 01 00 00 EF 00 3C 1B A1 - can1 131 [8] 00 00 00 00 00 00 1C 56 - can1 200 [8] 00 00 00 00 00 00 1B 25 - can1 201 [8] 00 00 00 00 00 00 1B 26 - can1 202 [8] 00 00 00 00 00 00 1B 27 - can1 203 [8] 00 00 00 00 00 00 1B 28 - can1 141 [8] 00 00 00 02 1F 00 1B 86 - can1 151 [8] 01 00 00 EF 00 3C 1C A2 - can1 131 [8] 00 00 00 00 00 00 1D 57 - can1 200 [8] 00 00 00 00 00 00 1C 26 - can1 201 [8] 00 00 00 00 00 00 1C 27 - can1 202 [8] 00 00 00 00 00 00 1C 28 - can1 203 [8] 00 00 00 00 00 00 1C 29 - can1 141 [8] 00 00 00 02 20 00 1C 88 - can1 151 [8] 01 00 00 EF 00 3C 1D A3 - can1 151 [8] 01 00 00 EF 00 3C 1E A4 - can1 131 [8] 00 00 00 00 00 00 1E 58 - can1 200 [8] 00 00 00 00 00 00 1D 27 - can1 201 [8] 00 00 00 00 00 00 1D 28 - can1 202 [8] 00 00 00 00 00 00 1D 29 - can1 203 [8] 00 00 00 00 00 00 1D 2A - can1 141 [8] 00 00 00 02 20 00 1D 89 - can1 131 [8] 00 00 00 00 00 00 1F 59 - can1 200 [8] 00 00 00 00 00 00 1E 28 - can1 201 [8] 00 00 00 00 00 00 1E 29 - can1 202 [8] 00 00 00 00 00 00 1E 2A - can1 203 [8] 00 00 00 00 00 00 1E 2B - can1 141 [8] 00 00 00 02 21 00 1E 8B - can1 151 [8] 01 00 00 EF 00 3C 1F A5 - can1 131 [8] 00 00 00 00 00 00 20 5A - can1 200 [8] 00 00 00 00 00 00 1F 29 - can1 201 [8] 00 00 00 00 00 00 1F 2A - can1 202 [8] 00 00 00 00 00 00 1F 2B - can1 203 [8] 00 00 00 00 00 00 1F 2C - can1 141 [8] 00 00 00 02 22 00 1F 8D - can1 151 [8] 01 00 00 EF 00 3C 20 A6 - can1 131 [8] 00 00 00 00 00 00 21 5B - can1 200 [8] 00 00 00 00 00 00 20 2A - can1 201 [8] 00 00 00 00 00 00 20 2B - can1 202 [8] 00 00 00 00 00 00 20 2C - can1 203 [8] 00 00 00 00 00 00 20 2D - can1 141 [8] 00 00 00 02 23 00 20 8F - can1 151 [8] 01 00 00 EF 00 3C 21 A7 - can1 131 [8] 00 00 00 00 00 00 22 5C - can1 200 [8] 00 00 00 00 00 00 21 2B - can1 201 [8] 00 00 00 00 00 00 21 2C - can1 202 [8] 00 00 00 00 00 00 21 2D - can1 203 [8] 00 00 00 00 00 00 21 2E - can1 141 [8] 00 00 00 02 24 00 21 91 - can1 151 [8] 01 00 00 EF 00 3C 22 A8 - can1 131 [8] 00 00 00 00 00 00 23 5D - can1 200 [8] 00 00 00 00 00 00 22 2C - can1 201 [8] 00 00 00 00 00 00 22 2D - can1 202 [8] 00 00 00 00 00 00 22 2E - can1 203 [8] 00 00 00 00 00 00 22 2F - can1 141 [8] 00 00 00 02 24 00 22 92 - can1 151 [8] 01 00 00 EF 00 3C 23 A9 - can1 131 [8] 00 00 00 00 00 00 24 5E - can1 200 [8] 00 00 00 00 00 00 23 2D - can1 201 [8] 00 00 00 00 00 00 23 2E - can1 202 [8] 00 00 00 00 00 00 23 2F - can1 203 [8] 00 00 00 00 00 00 23 30 - can1 141 [8] 00 00 00 02 25 00 23 94 - can1 151 [8] 01 00 00 EF 00 3C 24 AA - can1 131 [8] 00 00 00 00 00 00 25 5F - can1 200 [8] 00 00 00 00 00 00 24 2E - can1 201 [8] 00 00 00 00 00 00 24 2F - can1 202 [8] 00 00 00 00 00 00 24 30 - can1 203 [8] 00 00 00 00 00 00 24 31 - can1 141 [8] 00 00 00 02 26 00 24 96 - can1 151 [8] 01 00 00 EF 00 3C 25 AB - can1 131 [8] 00 00 00 00 00 00 26 60 - can1 200 [8] 00 00 00 00 00 00 25 2F - can1 201 [8] 00 00 00 00 00 00 25 30 - can1 202 [8] 00 00 00 00 00 00 25 31 - can1 203 [8] 00 00 00 00 00 00 25 32 - can1 141 [8] 00 00 00 02 27 00 25 98 - can1 151 [8] 01 00 00 EF 00 3C 26 AC - can1 131 [8] 00 00 00 00 00 00 27 61 - can1 200 [8] 00 00 00 00 00 00 26 30 - can1 201 [8] 00 00 00 00 00 00 26 31 - can1 202 [8] 00 00 00 00 00 00 26 32 - can1 203 [8] 00 00 00 00 00 00 26 33 - can1 141 [8] 00 00 00 02 28 00 26 9A - can1 151 [8] 01 00 00 EF 00 3C 27 AD - can1 151 [8] 01 00 00 EF 00 3C 28 AE - can1 131 [8] 00 00 00 00 00 00 28 62 - can1 200 [8] 00 00 00 00 00 00 27 31 - can1 201 [8] 00 00 00 00 00 00 27 32 - can1 202 [8] 00 00 00 00 00 00 27 33 - can1 203 [8] 00 00 00 00 00 00 27 34 - can1 141 [8] 00 00 00 02 28 00 27 9B - can1 131 [8] 00 00 00 00 00 00 29 63 - can1 200 [8] 00 00 00 00 00 00 28 32 - can1 201 [8] 00 00 00 00 00 00 28 33 - can1 202 [8] 00 00 00 00 00 00 28 34 - can1 203 [8] 00 00 00 00 00 00 28 35 - can1 141 [8] 00 00 00 02 29 00 28 9D - can1 151 [8] 01 00 00 EF 00 3C 29 AF - can1 131 [8] 00 00 00 00 00 00 2A 64 - can1 200 [8] 00 00 00 00 00 00 29 33 - can1 201 [8] 00 00 00 00 00 00 29 34 - can1 202 [8] 00 00 00 00 00 00 29 35 - can1 203 [8] 00 00 00 00 00 00 29 36 - can1 141 [8] 00 00 00 02 2A 00 29 9F - can1 151 [8] 01 00 00 EF 00 3C 2A B0 - can1 131 [8] 00 00 00 00 00 00 2B 65 - can1 200 [8] 00 00 00 00 00 00 2A 34 - can1 201 [8] 00 00 00 00 00 00 2A 35 - can1 202 [8] 00 00 00 00 00 00 2A 36 - can1 203 [8] 00 00 00 00 00 00 2A 37 - can1 141 [8] 00 00 00 02 2B 00 2A A1 - can1 151 [8] 01 00 00 EF 00 3C 2B B1 - can1 131 [8] 00 00 00 00 00 00 2C 66 - can1 200 [8] 00 00 00 00 00 00 2B 35 - can1 201 [8] 00 00 00 00 00 00 2B 36 - can1 202 [8] 00 00 00 00 00 00 2B 37 - can1 203 [8] 00 00 00 00 00 00 2B 38 - can1 141 [8] 00 00 00 02 2C 00 2B A3 - can1 151 [8] 01 00 00 EF 00 3C 2C B2 - can1 131 [8] 00 00 00 00 00 00 2D 67 - can1 200 [8] 00 00 00 00 00 00 2C 36 - can1 201 [8] 00 00 00 00 00 00 2C 37 - can1 202 [8] 00 00 00 00 00 00 2C 38 - can1 203 [8] 00 00 00 00 00 00 2C 39 - can1 141 [8] 00 00 00 02 2C 00 2C A4 - can1 151 [8] 01 00 00 EF 00 3C 2D B3 - can1 131 [8] 00 00 00 00 00 00 2E 68 - can1 200 [8] 00 00 00 00 00 00 2D 37 - can1 201 [8] 00 00 00 00 00 00 2D 38 - can1 202 [8] 00 00 00 00 00 00 2D 39 - can1 203 [8] 00 00 00 00 00 00 2D 3A - can1 141 [8] 00 00 00 02 2D 00 2D A6 - can1 151 [8] 01 00 00 EF 00 3C 2E B4 - can1 131 [8] 00 00 00 00 00 00 2F 69 - can1 200 [8] 00 00 00 00 00 00 2E 38 - can1 201 [8] 00 00 00 00 00 00 2E 39 - can1 202 [8] 00 00 00 00 00 00 2E 3A - can1 203 [8] 00 00 00 00 00 00 2E 3B - can1 141 [8] 00 00 00 02 2E 00 2E A8 - can1 151 [8] 01 00 00 EF 00 3C 2F B5 - can1 131 [8] 00 00 00 00 00 00 30 6A - can1 200 [8] 00 00 00 00 00 00 2F 39 - can1 201 [8] 00 00 00 00 00 00 2F 3A - can1 202 [8] 00 00 00 00 00 00 2F 3B - can1 203 [8] 00 00 00 00 00 00 2F 3C - can1 141 [8] 00 00 00 02 2F 00 2F AA - can1 151 [8] 01 00 00 EF 00 3C 30 B6 - can1 131 [8] 00 00 00 00 00 00 31 6B - can1 200 [8] 00 00 00 00 00 00 30 3A - can1 201 [8] 00 00 00 00 00 00 30 3B - can1 202 [8] 00 00 00 00 00 00 30 3C - can1 203 [8] 00 00 00 00 00 00 30 3D - can1 141 [8] 00 00 00 02 30 00 30 AC - can1 151 [8] 01 00 00 EF 00 3C 31 B7 - can1 131 [8] 00 00 00 00 00 00 32 6C - can1 200 [8] 00 00 00 00 00 00 31 3B - can1 201 [8] 00 00 00 00 00 00 31 3C - can1 202 [8] 00 00 00 00 00 00 31 3D - can1 203 [8] 00 00 00 00 00 00 31 3E - can1 141 [8] 00 00 00 02 31 00 31 AE - can1 151 [8] 01 00 00 EF 00 3C 32 B8 - can1 131 [8] 00 00 00 00 00 00 33 6D - can1 200 [8] 00 00 00 00 00 00 32 3C - can1 201 [8] 00 00 00 00 00 00 32 3D - can1 202 [8] 00 00 00 00 00 00 32 3E - can1 203 [8] 00 00 00 00 00 00 32 3F - can1 141 [8] 00 00 00 02 31 00 32 AF - can1 151 [8] 01 00 00 EF 00 3C 33 B9 - can1 131 [8] 00 00 00 00 00 00 34 6E - can1 200 [8] 00 00 00 00 00 00 33 3D - can1 201 [8] 00 00 00 00 00 00 33 3E - can1 202 [8] 00 00 00 00 00 00 33 3F - can1 203 [8] 00 00 00 00 00 00 33 40 - can1 141 [8] 00 00 00 02 32 00 33 B1 - can1 151 [8] 01 00 00 EF 00 3C 34 BA - can1 131 [8] 00 00 00 00 00 00 35 6F - can1 200 [8] 00 00 00 00 00 00 34 3E - can1 201 [8] 00 00 00 00 00 00 34 3F - can1 202 [8] 00 00 00 00 00 00 34 40 - can1 203 [8] 00 00 00 00 00 00 34 41 - can1 141 [8] 00 00 00 02 33 00 34 B3 - can1 151 [8] 01 00 00 EF 00 3C 35 BB - can1 131 [8] 00 00 00 00 00 00 36 70 - can1 200 [8] 00 00 00 00 00 00 35 3F - can1 201 [8] 00 00 00 00 00 00 35 40 - can1 202 [8] 00 00 00 00 00 00 35 41 - can1 203 [8] 00 00 00 00 00 00 35 42 - can1 141 [8] 00 00 00 02 34 00 35 B5 - can1 151 [8] 01 00 00 EF 00 3C 36 BC - can1 131 [8] 00 00 00 00 00 00 37 71 - can1 200 [8] 00 00 00 00 00 00 36 40 - can1 201 [8] 00 00 00 00 00 00 36 41 - can1 202 [8] 00 00 00 00 00 00 36 42 - can1 203 [8] 00 00 00 00 00 00 36 43 - can1 141 [8] 00 00 00 02 35 00 36 B7 - can1 151 [8] 01 00 00 EF 00 3C 37 BD - can1 131 [8] 00 00 00 00 00 00 38 72 - can1 200 [8] 00 00 00 00 00 00 37 41 - can1 201 [8] 00 00 00 00 00 00 37 42 - can1 202 [8] 00 00 00 00 00 00 37 43 - can1 203 [8] 00 00 00 00 00 00 37 44 - can1 141 [8] 00 00 00 02 35 00 37 B8 - can1 151 [8] 01 00 00 EF 00 3C 38 BE - can1 131 [8] 00 00 00 00 00 00 39 73 - can1 200 [8] 00 00 00 00 00 00 38 42 - can1 201 [8] 00 00 00 00 00 00 38 43 - can1 202 [8] 00 00 00 00 00 00 38 44 - can1 203 [8] 00 00 00 00 00 00 38 45 - can1 141 [8] 00 00 00 02 36 00 38 BA - can1 151 [8] 01 00 00 EF 00 3C 39 BF - can1 131 [8] 00 00 00 00 00 00 3A 74 - can1 200 [8] 00 00 00 00 00 00 39 43 - can1 201 [8] 00 00 00 00 00 00 39 44 - can1 202 [8] 00 00 00 00 00 00 39 45 - can1 203 [8] 00 00 00 00 00 00 39 46 - can1 141 [8] 00 00 00 02 37 00 39 BC - can1 151 [8] 01 00 00 EF 00 3C 3A C0 - can1 131 [8] 00 00 00 00 00 00 3B 75 - can1 200 [8] 00 00 00 00 00 00 3A 44 - can1 201 [8] 00 00 00 00 00 00 3A 45 - can1 202 [8] 00 00 00 00 00 00 3A 46 - can1 203 [8] 00 00 00 00 00 00 3A 47 - can1 141 [8] 00 00 00 02 38 00 3A BE - can1 151 [8] 01 00 00 EF 00 3C 3B C1 - can1 131 [8] 00 00 00 00 00 00 3C 76 - can1 200 [8] 00 00 00 00 00 00 3B 45 - can1 201 [8] 00 00 00 00 00 00 3B 46 - can1 202 [8] 00 00 00 00 00 00 3B 47 - can1 203 [8] 00 00 00 00 00 00 3B 48 - can1 141 [8] 00 00 00 02 39 00 3B C0 - can1 151 [8] 01 00 00 EF 00 3C 3C C2 - can1 131 [8] 00 00 00 00 00 00 3D 77 - can1 200 [8] 00 00 00 00 00 00 3C 46 - can1 201 [8] 00 00 00 00 00 00 3C 47 - can1 202 [8] 00 00 00 00 00 00 3C 48 - can1 203 [8] 00 00 00 00 00 00 3C 49 - can1 141 [8] 00 00 00 02 39 00 3C C1 - can1 151 [8] 01 00 00 EF 00 3C 3D C3 - can1 131 [8] 00 00 00 00 00 00 3E 78 - can1 200 [8] 00 00 00 00 00 00 3D 47 - can1 201 [8] 00 00 00 00 00 00 3D 48 - can1 202 [8] 00 00 00 00 00 00 3D 49 - can1 203 [8] 00 00 00 00 00 00 3D 4A - can1 141 [8] 00 00 00 02 3A 00 3D C3 - can1 151 [8] 01 00 00 EF 00 3C 3E C4 - can1 131 [8] 00 00 00 00 00 00 3F 79 - can1 200 [8] 00 00 00 00 00 00 3E 48 - can1 201 [8] 00 00 00 00 00 00 3E 49 - can1 202 [8] 00 00 00 00 00 00 3E 4A - can1 203 [8] 00 00 00 00 00 00 3E 4B - can1 141 [8] 00 00 00 02 3B 00 3E C5 - can1 151 [8] 01 00 00 EF 00 3C 3F C5 - can1 131 [8] 00 00 00 00 00 00 40 7A - can1 200 [8] 00 00 00 00 00 00 3F 49 - can1 201 [8] 00 00 00 00 00 00 3F 4A - can1 202 [8] 00 00 00 00 00 00 3F 4B - can1 203 [8] 00 00 00 00 00 00 3F 4C - can1 141 [8] 00 00 00 02 3C 00 3F C7 - can1 151 [8] 01 00 00 EF 00 3C 40 C6 - can1 131 [8] 00 00 00 00 00 00 41 7B - can1 200 [8] 00 00 00 00 00 00 40 4A - can1 201 [8] 00 00 00 00 00 00 40 4B - can1 202 [8] 00 00 00 00 00 00 40 4C - can1 203 [8] 00 00 00 00 00 00 40 4D - can1 141 [8] 00 00 00 02 3D 00 40 C9 - can1 151 [8] 01 00 00 EF 00 3C 41 C7 - can1 131 [8] 00 00 00 00 00 00 42 7C - can1 200 [8] 00 00 00 00 00 00 41 4B - can1 201 [8] 00 00 00 00 00 00 41 4C - can1 202 [8] 00 00 00 00 00 00 41 4D - can1 203 [8] 00 00 00 00 00 00 41 4E - can1 141 [8] 00 00 00 02 3D 00 41 CA - can1 151 [8] 01 00 00 EF 00 3C 42 C8 - can1 131 [8] 00 00 00 00 00 00 43 7D - can1 200 [8] 00 00 00 00 00 00 42 4C - can1 201 [8] 00 00 00 00 00 00 42 4D - can1 202 [8] 00 00 00 00 00 00 42 4E - can1 203 [8] 00 00 00 00 00 00 42 4F - can1 141 [8] 00 00 00 02 3E 00 42 CC - can1 151 [8] 01 00 00 EF 00 3C 43 C9 - can1 131 [8] 00 00 00 00 00 00 44 7E - can1 200 [8] 00 00 00 00 00 00 43 4D - can1 201 [8] 00 00 00 00 00 00 43 4E - can1 202 [8] 00 00 00 00 00 00 43 4F - can1 203 [8] 00 00 00 00 00 00 43 50 - can1 141 [8] 00 00 00 02 3F 00 43 CE - can1 151 [8] 01 00 00 EF 00 3C 44 CA - can1 131 [8] 00 00 00 00 00 00 45 7F - can1 200 [8] 00 00 00 00 00 00 44 4E - can1 201 [8] 00 00 00 00 00 00 44 4F - can1 202 [8] 00 00 00 00 00 00 44 50 - can1 203 [8] 00 00 00 00 00 00 44 51 - can1 141 [8] 00 00 00 02 40 00 44 D0 - can1 151 [8] 01 00 00 EF 00 3C 45 CB - can1 151 [8] 01 00 00 EF 00 3C 46 CC - can1 131 [8] 00 00 00 00 00 00 46 80 - can1 200 [8] 00 00 00 00 00 00 45 4F - can1 201 [8] 00 00 00 00 00 00 45 50 - can1 202 [8] 00 00 00 00 00 00 45 51 - can1 203 [8] 00 00 00 00 00 00 45 52 - can1 141 [8] 00 00 00 02 41 00 45 D2 - can1 131 [8] 00 00 00 00 00 00 47 81 - can1 200 [8] 00 00 00 00 00 00 46 50 - can1 201 [8] 00 00 00 00 00 00 46 51 - can1 202 [8] 00 00 00 00 00 00 46 52 - can1 203 [8] 00 00 00 00 00 00 46 53 - can1 141 [8] 00 00 00 02 41 00 46 D3 - can1 151 [8] 01 00 00 EF 00 3C 47 CD - can1 131 [8] 00 00 00 00 00 00 48 82 - can1 200 [8] 00 00 00 00 00 00 47 51 - can1 201 [8] 00 00 00 00 00 00 47 52 - can1 202 [8] 00 00 00 00 00 00 47 53 - can1 203 [8] 00 00 00 00 00 00 47 54 - can1 141 [8] 00 00 00 02 42 00 47 D5 - can1 151 [8] 01 00 00 EF 00 3C 48 CE - can1 131 [8] 00 00 00 00 00 00 49 83 - can1 200 [8] 00 00 00 00 00 00 48 52 - can1 201 [8] 00 00 00 00 00 00 48 53 - can1 202 [8] 00 00 00 00 00 00 48 54 - can1 203 [8] 00 00 00 00 00 00 48 55 - can1 141 [8] 00 00 00 02 43 00 48 D7 - can1 151 [8] 01 00 00 EF 00 3C 49 CF - can1 131 [8] 00 00 00 00 00 00 4A 84 - can1 200 [8] 00 00 00 00 00 00 49 53 - can1 201 [8] 00 00 00 00 00 00 49 54 - can1 202 [8] 00 00 00 00 00 00 49 55 - can1 203 [8] 00 00 00 00 00 00 49 56 - can1 141 [8] 00 00 00 02 44 00 49 D9 - can1 151 [8] 01 00 00 EF 00 3C 4A D0 - can1 131 [8] 00 00 00 00 00 00 4B 85 - can1 200 [8] 00 00 00 00 00 00 4A 54 - can1 201 [8] 00 00 00 00 00 00 4A 55 - can1 202 [8] 00 00 00 00 00 00 4A 56 - can1 203 [8] 00 00 00 00 00 00 4A 57 - can1 141 [8] 00 00 00 02 45 00 4A DB - can1 151 [8] 01 00 00 EF 00 3C 4B D1 - can1 131 [8] 00 00 00 00 00 00 4C 86 - can1 200 [8] 00 00 00 00 00 00 4B 55 - can1 201 [8] 00 00 00 00 00 00 4B 56 - can1 202 [8] 00 00 00 00 00 00 4B 57 - can1 203 [8] 00 00 00 00 00 00 4B 58 - can1 141 [8] 00 00 00 02 46 00 4B DD - can1 151 [8] 01 00 00 EF 00 3C 4C D2 - can1 131 [8] 00 00 00 00 00 00 4D 87 - can1 200 [8] 00 00 00 00 00 00 4C 56 - can1 201 [8] 00 00 00 00 00 00 4C 57 - can1 202 [8] 00 00 00 00 00 00 4C 58 - can1 203 [8] 00 00 00 00 00 00 4C 59 - can1 141 [8] 00 00 00 02 46 00 4C DE - can1 151 [8] 01 00 00 EF 00 3C 4D D3 - can1 131 [8] 00 00 00 00 00 00 4E 88 - can1 200 [8] 00 00 00 00 00 00 4D 57 - can1 201 [8] 00 00 00 00 00 00 4D 58 - can1 202 [8] 00 00 00 00 00 00 4D 59 - can1 203 [8] 00 00 00 00 00 00 4D 5A - can1 141 [8] 00 00 00 02 47 00 4D E0 - can1 151 [8] 01 00 00 EF 00 3C 4E D4 - can1 131 [8] 00 00 00 00 00 00 4F 89 - can1 200 [8] 00 00 00 00 00 00 4E 58 - can1 201 [8] 00 00 00 00 00 00 4E 59 - can1 202 [8] 00 00 00 00 00 00 4E 5A - can1 203 [8] 00 00 00 00 00 00 4E 5B - can1 141 [8] 00 00 00 02 48 00 4E E2 - can1 151 [8] 01 00 00 EF 00 3C 4F D5 - can1 131 [8] 00 00 00 00 00 00 50 8A - can1 200 [8] 00 00 00 00 00 00 4F 59 - can1 201 [8] 00 00 00 00 00 00 4F 5A - can1 202 [8] 00 00 00 00 00 00 4F 5B - can1 203 [8] 00 00 00 00 00 00 4F 5C - can1 141 [8] 00 00 00 02 49 00 4F E4 - can1 151 [8] 01 00 00 EF 00 3C 50 D6 - can1 131 [8] 00 00 00 00 00 00 51 8B - can1 200 [8] 00 00 00 00 00 00 50 5A - can1 201 [8] 00 00 00 00 00 00 50 5B - can1 202 [8] 00 00 00 00 00 00 50 5C - can1 203 [8] 00 00 00 00 00 00 50 5D - can1 141 [8] 00 00 00 02 4A 00 50 E6 - can1 151 [8] 01 00 00 EF 00 3C 51 D7 - can1 131 [8] 00 00 00 00 00 00 52 8C - can1 200 [8] 00 00 00 00 00 00 51 5B - can1 201 [8] 00 00 00 00 00 00 51 5C - can1 202 [8] 00 00 00 00 00 00 51 5D - can1 203 [8] 00 00 00 00 00 00 51 5E - can1 141 [8] 00 00 00 02 4A 00 51 E7 - can1 151 [8] 01 00 00 EF 00 3C 52 D8 - can1 131 [8] 00 00 00 00 00 00 53 8D - can1 200 [8] 00 00 00 00 00 00 52 5C - can1 201 [8] 00 00 00 00 00 00 52 5D - can1 202 [8] 00 00 00 00 00 00 52 5E - can1 203 [8] 00 00 00 00 00 00 52 5F - can1 141 [8] 00 00 00 02 4B 00 52 E9 - can1 151 [8] 01 00 00 EF 00 3C 53 D9 - can1 131 [8] 00 00 00 00 00 00 54 8E - can1 200 [8] 00 00 00 00 00 00 53 5D - can1 201 [8] 00 00 00 00 00 00 53 5E - can1 202 [8] 00 00 00 00 00 00 53 5F - can1 203 [8] 00 00 00 00 00 00 53 60 - can1 141 [8] 00 00 00 02 4C 00 53 EB - can1 151 [8] 01 00 00 EF 00 3C 54 DA - can1 131 [8] 00 00 00 00 00 00 55 8F - can1 200 [8] 00 00 00 00 00 00 54 5E - can1 201 [8] 00 00 00 00 00 00 54 5F - can1 202 [8] 00 00 00 00 00 00 54 60 - can1 203 [8] 00 00 00 00 00 00 54 61 - can1 141 [8] 00 00 00 02 4D 00 54 ED - can1 151 [8] 01 00 00 EF 00 3C 55 DB - can1 151 [8] 01 00 00 EF 00 3C 56 DC - can1 131 [8] 00 00 00 00 00 00 56 90 - can1 200 [8] 00 00 00 00 00 00 55 5F - can1 201 [8] 00 00 00 00 00 00 55 60 - can1 202 [8] 00 00 00 00 00 00 55 61 - can1 203 [8] 00 00 00 00 00 00 55 62 - can1 141 [8] 00 00 00 02 4E 00 55 EF - can1 131 [8] 00 00 00 00 00 00 57 91 - can1 200 [8] 00 00 00 00 00 00 56 60 - can1 201 [8] 00 00 00 00 00 00 56 61 - can1 202 [8] 00 00 00 00 00 00 56 62 - can1 203 [8] 00 00 00 00 00 00 56 63 - can1 141 [8] 00 00 00 02 4E 00 56 F0 - can1 151 [8] 01 00 00 EF 00 3C 57 DD - can1 131 [8] 00 00 00 00 00 00 58 92 - can1 200 [8] 00 00 00 00 00 00 57 61 - can1 201 [8] 00 00 00 00 00 00 57 62 - can1 202 [8] 00 00 00 00 00 00 57 63 - can1 203 [8] 00 00 00 00 00 00 57 64 - can1 141 [8] 00 00 00 02 4F 00 57 F2 - can1 151 [8] 01 00 00 EF 00 3C 58 DE - can1 131 [8] 00 00 00 00 00 00 59 93 - can1 200 [8] 00 00 00 00 00 00 58 62 - can1 201 [8] 00 00 00 00 00 00 58 63 - can1 202 [8] 00 00 00 00 00 00 58 64 - can1 203 [8] 00 00 00 00 00 00 58 65 - can1 141 [8] 00 00 00 02 50 00 58 F4 - can1 151 [8] 01 00 00 EF 00 3C 59 DF - can1 131 [8] 00 00 00 00 00 00 5A 94 - can1 200 [8] 00 00 00 00 00 00 59 63 - can1 201 [8] 00 00 00 00 00 00 59 64 - can1 202 [8] 00 00 00 00 00 00 59 65 - can1 203 [8] 00 00 00 00 00 00 59 66 - can1 141 [8] 00 00 00 02 51 00 59 F6 - can1 151 [8] 01 00 00 EF 00 3C 5A E0 - can1 131 [8] 00 00 00 00 00 00 5B 95 - can1 200 [8] 00 00 00 00 00 00 5A 64 - can1 201 [8] 00 00 00 00 00 00 5A 65 - can1 202 [8] 00 00 00 00 00 00 5A 66 - can1 203 [8] 00 00 00 00 00 00 5A 67 - can1 141 [8] 00 00 00 02 52 00 5A F8 - can1 151 [8] 01 00 00 EF 00 3C 5B E1 - can1 131 [8] 00 00 00 00 00 00 5C 96 - can1 200 [8] 00 00 00 00 00 00 5B 65 - can1 201 [8] 00 00 00 00 00 00 5B 66 - can1 202 [8] 00 00 00 00 00 00 5B 67 - can1 203 [8] 00 00 00 00 00 00 5B 68 - can1 141 [8] 00 00 00 02 52 00 5B F9 - can1 151 [8] 01 00 00 EF 00 3C 5C E2 - can1 131 [8] 00 00 00 00 00 00 5D 97 - can1 200 [8] 00 00 00 00 00 00 5C 66 - can1 201 [8] 00 00 00 00 00 00 5C 67 - can1 202 [8] 00 00 00 00 00 00 5C 68 - can1 203 [8] 00 00 00 00 00 00 5C 69 - can1 141 [8] 00 00 00 02 53 00 5C FB - can1 151 [8] 01 00 00 EF 00 3C 5D E3 - can1 131 [8] 00 00 00 00 00 00 5E 98 - can1 200 [8] 00 00 00 00 00 00 5D 67 - can1 201 [8] 00 00 00 00 00 00 5D 68 - can1 202 [8] 00 00 00 00 00 00 5D 69 - can1 203 [8] 00 00 00 00 00 00 5D 6A - can1 141 [8] 00 00 00 02 54 00 5D FD - can1 151 [8] 01 00 00 EF 00 3C 5E E4 - can1 131 [8] 00 00 00 00 00 00 5F 99 - can1 200 [8] 00 00 00 00 00 00 5E 68 - can1 201 [8] 00 00 00 00 00 00 5E 69 - can1 202 [8] 00 00 00 00 00 00 5E 6A - can1 203 [8] 00 00 00 00 00 00 5E 6B - can1 141 [8] 00 00 00 02 55 00 5E FF - can1 151 [8] 01 00 00 EF 00 3C 5F E5 - can1 131 [8] 00 00 00 00 00 00 60 9A - can1 200 [8] 00 00 00 00 00 00 5F 69 - can1 201 [8] 00 00 00 00 00 00 5F 6A - can1 202 [8] 00 00 00 00 00 00 5F 6B - can1 203 [8] 00 00 00 00 00 00 5F 6C - can1 141 [8] 00 00 00 02 56 00 5F 01 - can1 151 [8] 01 00 00 EF 00 3C 60 E6 - can1 131 [8] 00 00 00 00 00 00 61 9B - can1 200 [8] 00 00 00 00 00 00 60 6A - can1 201 [8] 00 00 00 00 00 00 60 6B - can1 202 [8] 00 00 00 00 00 00 60 6C - can1 203 [8] 00 00 00 00 00 00 60 6D - can1 141 [8] 00 00 00 02 56 00 60 02 - can1 151 [8] 01 00 00 EF 00 3C 61 E7 - can1 131 [8] 00 00 00 00 00 00 62 9C - can1 200 [8] 00 00 00 00 00 00 61 6B - can1 201 [8] 00 00 00 00 00 00 61 6C - can1 202 [8] 00 00 00 00 00 00 61 6D - can1 203 [8] 00 00 00 00 00 00 61 6E - can1 141 [8] 00 00 00 02 57 00 61 04 - can1 151 [8] 01 00 00 EF 00 3C 62 E8 - can1 151 [8] 01 00 00 EF 00 3C 63 E9 - can1 131 [8] 00 00 00 00 00 00 63 9D - can1 200 [8] 00 00 00 00 00 00 62 6C - can1 201 [8] 00 00 00 00 00 00 62 6D - can1 202 [8] 00 00 00 00 00 00 62 6E - can1 203 [8] 00 00 00 00 00 00 62 6F - can1 141 [8] 00 00 00 02 58 00 62 06 - can1 131 [8] 00 00 00 00 00 00 64 9E - can1 200 [8] 00 00 00 00 00 00 63 6D - can1 201 [8] 00 00 00 00 00 00 63 6E - can1 202 [8] 00 00 00 00 00 00 63 6F - can1 203 [8] 00 00 00 00 00 00 63 70 - can1 141 [8] 00 00 00 02 59 00 63 08 - can1 151 [8] 01 00 00 EF 00 3C 64 EA - can1 131 [8] 00 00 00 00 00 00 65 9F - can1 200 [8] 00 00 00 00 00 00 64 6E - can1 201 [8] 00 00 00 00 00 00 64 6F - can1 202 [8] 00 00 00 00 00 00 64 70 - can1 203 [8] 00 00 00 00 00 00 64 71 - can1 141 [8] 00 00 00 02 5A 00 64 0A - can1 151 [8] 01 00 00 EF 00 3C 65 EB - can1 131 [8] 00 00 00 00 00 00 66 A0 - can1 200 [8] 00 00 00 00 00 00 65 6F - can1 201 [8] 00 00 00 00 00 00 65 70 - can1 202 [8] 00 00 00 00 00 00 65 71 - can1 203 [8] 00 00 00 00 00 00 65 72 - can1 141 [8] 00 00 00 02 5B 00 65 0C - can1 151 [8] 01 00 00 EF 00 3C 66 EC - can1 131 [8] 00 00 00 00 00 00 67 A1 - can1 200 [8] 00 00 00 00 00 00 66 70 - can1 201 [8] 00 00 00 00 00 00 66 71 - can1 202 [8] 00 00 00 00 00 00 66 72 - can1 203 [8] 00 00 00 00 00 00 66 73 - can1 141 [8] 00 00 00 02 5B 00 66 0D - can1 151 [8] 01 00 00 EF 00 3C 67 ED - can1 131 [8] 00 00 00 00 00 00 68 A2 - can1 200 [8] 00 00 00 00 00 00 67 71 - can1 201 [8] 00 00 00 00 00 00 67 72 - can1 202 [8] 00 00 00 00 00 00 67 73 - can1 203 [8] 00 00 00 00 00 00 67 74 - can1 141 [8] 00 00 00 02 5C 00 67 0F - can1 151 [8] 01 00 00 EF 00 3C 68 EE - can1 131 [8] 00 00 00 00 00 00 69 A3 - can1 200 [8] 00 00 00 00 00 00 68 72 - can1 201 [8] 00 00 00 00 00 00 68 73 - can1 202 [8] 00 00 00 00 00 00 68 74 - can1 203 [8] 00 00 00 00 00 00 68 75 - can1 141 [8] 00 00 00 02 5D 00 68 11 - can1 151 [8] 01 00 00 EF 00 3C 69 EF - can1 131 [8] 00 00 00 00 00 00 6A A4 - can1 200 [8] 00 00 00 00 00 00 69 73 - can1 201 [8] 00 00 00 00 00 00 69 74 - can1 202 [8] 00 00 00 00 00 00 69 75 - can1 203 [8] 00 00 00 00 00 00 69 76 - can1 141 [8] 00 00 00 02 5E 00 69 13 - can1 151 [8] 01 00 00 EF 00 3C 6A F0 - can1 131 [8] 00 00 00 00 00 00 6B A5 - can1 200 [8] 00 00 00 00 00 00 6A 74 - can1 201 [8] 00 00 00 00 00 00 6A 75 - can1 202 [8] 00 00 00 00 00 00 6A 76 - can1 203 [8] 00 00 00 00 00 00 6A 77 - can1 141 [8] 00 00 00 02 5F 00 6A 15 - can1 151 [8] 01 00 00 EF 00 3C 6B F1 - can1 131 [8] 00 00 00 00 00 00 6C A6 - can1 200 [8] 00 00 00 00 00 00 6B 75 - can1 201 [8] 00 00 00 00 00 00 6B 76 - can1 202 [8] 00 00 00 00 00 00 6B 77 - can1 203 [8] 00 00 00 00 00 00 6B 78 - can1 141 [8] 00 00 00 02 5F 00 6B 16 - can1 151 [8] 01 00 00 EF 00 3C 6C F2 - can1 151 [8] 01 00 00 EF 00 3C 6D F3 - can1 131 [8] 00 00 00 00 00 00 6D A7 - can1 200 [8] 00 00 00 00 00 00 6C 76 - can1 201 [8] 00 00 00 00 00 00 6C 77 - can1 202 [8] 00 00 00 00 00 00 6C 78 - can1 203 [8] 00 00 00 00 00 00 6C 79 - can1 141 [8] 00 00 00 02 60 00 6C 18 - can1 131 [8] 00 00 00 00 00 00 6E A8 - can1 200 [8] 00 00 00 00 00 00 6D 77 - can1 201 [8] 00 00 00 00 00 00 6D 78 - can1 202 [8] 00 00 00 00 00 00 6D 79 - can1 203 [8] 00 00 00 00 00 00 6D 7A - can1 141 [8] 00 00 00 02 61 00 6D 1A - can1 151 [8] 01 00 00 EF 00 3C 6E F4 - can1 131 [8] 00 00 00 00 00 00 6F A9 - can1 200 [8] 00 00 00 00 00 00 6E 78 - can1 201 [8] 00 00 00 00 00 00 6E 79 - can1 202 [8] 00 00 00 00 00 00 6E 7A - can1 203 [8] 00 00 00 00 00 00 6E 7B - can1 141 [8] 00 00 00 02 62 00 6E 1C - can1 151 [8] 01 00 00 EF 00 3C 6F F5 - can1 131 [8] 00 00 00 00 00 00 70 AA - can1 200 [8] 00 00 00 00 00 00 6F 79 - can1 201 [8] 00 00 00 00 00 00 6F 7A - can1 202 [8] 00 00 00 00 00 00 6F 7B - can1 203 [8] 00 00 00 00 00 00 6F 7C - can1 141 [8] 00 00 00 02 63 00 6F 1E - can1 151 [8] 01 00 00 EF 00 3C 70 F6 - can1 131 [8] 00 00 00 00 00 00 71 AB - can1 200 [8] 00 00 00 00 00 00 70 7A - can1 201 [8] 00 00 00 00 00 00 70 7B - can1 202 [8] 00 00 00 00 00 00 70 7C - can1 203 [8] 00 00 00 00 00 00 70 7D - can1 141 [8] 00 00 00 02 63 00 70 1F - can1 151 [8] 01 00 00 EF 00 3C 71 F7 - can1 131 [8] 00 00 00 00 00 00 72 AC - can1 200 [8] 00 00 00 00 00 00 71 7B - can1 201 [8] 00 00 00 00 00 00 71 7C - can1 202 [8] 00 00 00 00 00 00 71 7D - can1 203 [8] 00 00 00 00 00 00 71 7E - can1 141 [8] 00 00 00 02 64 00 71 21 - can1 151 [8] 01 00 00 EF 00 3C 72 F8 - can1 131 [8] 00 00 00 00 00 00 73 AD - can1 200 [8] 00 00 00 00 00 00 72 7C - can1 201 [8] 00 00 00 00 00 00 72 7D - can1 202 [8] 00 00 00 00 00 00 72 7E - can1 203 [8] 00 00 00 00 00 00 72 7F - can1 141 [8] 00 00 00 02 64 00 72 22 - can1 151 [8] 01 00 00 EF 00 3C 73 F9 - can1 131 [8] 00 00 00 00 00 00 74 AE - can1 200 [8] 00 00 00 00 00 00 73 7D - can1 201 [8] 00 00 00 00 00 00 73 7E - can1 202 [8] 00 00 00 00 00 00 73 7F - can1 203 [8] 00 00 00 00 00 00 73 80 - can1 141 [8] 00 00 00 02 63 00 73 22 - can1 151 [8] 01 00 00 EF 00 3C 74 FA - can1 131 [8] 00 00 00 00 00 00 75 AF - can1 200 [8] 00 00 00 00 00 00 74 7E - can1 201 [8] 00 00 00 00 00 00 74 7F - can1 202 [8] 00 00 00 00 00 00 74 80 - can1 203 [8] 00 00 00 00 00 00 74 81 - can1 141 [8] 00 00 00 02 62 00 74 22 - can1 151 [8] 01 00 00 EF 00 3C 75 FB - can1 131 [8] 00 00 00 00 00 00 76 B0 - can1 200 [8] 00 00 00 00 00 00 75 7F - can1 201 [8] 00 00 00 00 00 00 75 80 - can1 202 [8] 00 00 00 00 00 00 75 81 - can1 203 [8] 00 00 00 00 00 00 75 82 - can1 141 [8] 00 00 00 02 62 00 75 23 - can1 151 [8] 01 00 00 EF 00 3C 76 FC - can1 131 [8] 00 00 00 00 00 00 77 B1 - can1 200 [8] 00 00 00 00 00 00 76 80 - can1 201 [8] 00 00 00 00 00 00 76 81 - can1 202 [8] 00 00 00 00 00 00 76 82 - can1 203 [8] 00 00 00 00 00 00 76 83 - can1 141 [8] 00 00 00 02 61 00 76 23 - can1 151 [8] 01 00 00 EF 00 3C 77 FD - can1 151 [8] 01 00 00 EF 00 3C 78 FE - can1 131 [8] 00 00 00 00 00 00 78 B2 - can1 200 [8] 00 00 00 00 00 00 77 81 - can1 201 [8] 00 00 00 00 00 00 77 82 - can1 202 [8] 00 00 00 00 00 00 77 83 - can1 203 [8] 00 00 00 00 00 00 77 84 - can1 141 [8] 00 00 00 02 60 00 77 23 - can1 131 [8] 00 00 00 00 00 00 79 B3 - can1 200 [8] 00 00 00 00 00 00 78 82 - can1 201 [8] 00 00 00 00 00 00 78 83 - can1 202 [8] 00 00 00 00 00 00 78 84 - can1 203 [8] 00 00 00 00 00 00 78 85 - can1 141 [8] 00 00 00 02 5F 00 78 23 - can1 151 [8] 01 00 00 EF 00 3C 79 FF - can1 131 [8] 00 00 00 00 00 00 7A B4 - can1 200 [8] 00 00 00 00 00 00 79 83 - can1 201 [8] 00 00 00 00 00 00 79 84 - can1 202 [8] 00 00 00 00 00 00 79 85 - can1 203 [8] 00 00 00 00 00 00 79 86 - can1 141 [8] 00 00 00 02 5E 00 79 23 - can1 151 [8] 01 00 00 EF 00 3C 7A 00 - can1 131 [8] 00 00 00 00 00 00 7B B5 - can1 200 [8] 00 00 00 00 00 00 7A 84 - can1 201 [8] 00 00 00 00 00 00 7A 85 - can1 202 [8] 00 00 00 00 00 00 7A 86 - can1 203 [8] 00 00 00 00 00 00 7A 87 - can1 141 [8] 00 00 00 02 5E 00 7A 24 - can1 151 [8] 01 00 00 EF 00 3C 7B 01 - can1 131 [8] 00 00 00 00 00 00 7C B6 - can1 200 [8] 00 00 00 00 00 00 7B 85 - can1 201 [8] 00 00 00 00 00 00 7B 86 - can1 202 [8] 00 00 00 00 00 00 7B 87 - can1 203 [8] 00 00 00 00 00 00 7B 88 - can1 141 [8] 00 00 00 02 5D 00 7B 24 - can1 151 [8] 01 00 00 EF 00 3C 7C 02 - can1 131 [8] 00 00 00 00 00 00 7D B7 - can1 200 [8] 00 00 00 00 00 00 7C 86 - can1 201 [8] 00 00 00 00 00 00 7C 87 - can1 202 [8] 00 00 00 00 00 00 7C 88 - can1 203 [8] 00 00 00 00 00 00 7C 89 - can1 141 [8] 00 00 00 02 5C 00 7C 24 - can1 151 [8] 01 00 00 EF 00 3C 7D 03 - can1 131 [8] 00 00 00 00 00 00 7E B8 - can1 200 [8] 00 00 00 00 00 00 7D 87 - can1 201 [8] 00 00 00 00 00 00 7D 88 - can1 202 [8] 00 00 00 00 00 00 7D 89 - can1 203 [8] 00 00 00 00 00 00 7D 8A - can1 141 [8] 00 00 00 02 5B 00 7D 24 - can1 151 [8] 01 00 00 EF 00 3C 7E 04 - can1 131 [8] 00 00 00 00 00 00 7F B9 - can1 200 [8] 00 00 00 00 00 00 7E 88 - can1 201 [8] 00 00 00 00 00 00 7E 89 - can1 202 [8] 00 00 00 00 00 00 7E 8A - can1 203 [8] 00 00 00 00 00 00 7E 8B - can1 141 [8] 00 00 00 02 5A 00 7E 24 - can1 151 [8] 01 00 00 EF 00 3C 7F 05 - can1 131 [8] 00 00 00 00 00 00 80 BA - can1 200 [8] 00 00 00 00 00 00 7F 89 - can1 201 [8] 00 00 00 00 00 00 7F 8A - can1 202 [8] 00 00 00 00 00 00 7F 8B - can1 203 [8] 00 00 00 00 00 00 7F 8C - can1 141 [8] 00 00 00 02 59 00 7F 24 - can1 151 [8] 01 00 00 EF 00 3C 80 06 - can1 131 [8] 00 00 00 00 00 00 81 BB - can1 200 [8] 00 00 00 00 00 00 80 8A - can1 201 [8] 00 00 00 00 00 00 80 8B - can1 202 [8] 00 00 00 00 00 00 80 8C - can1 203 [8] 00 00 00 00 00 00 80 8D - can1 141 [8] 00 00 00 02 59 00 80 25 - can1 151 [8] 01 00 00 EF 00 3C 81 07 - can1 131 [8] 00 00 00 00 00 00 82 BC - can1 200 [8] 00 00 00 00 00 00 81 8B - can1 201 [8] 00 00 00 00 00 00 81 8C - can1 202 [8] 00 00 00 00 00 00 81 8D - can1 203 [8] 00 00 00 00 00 00 81 8E - can1 141 [8] 00 00 00 02 58 00 81 25 - can1 151 [8] 01 00 00 EF 00 3C 82 08 - can1 131 [8] 00 00 00 00 00 00 83 BD - can1 200 [8] 00 00 00 00 00 00 82 8C - can1 201 [8] 00 00 00 00 00 00 82 8D - can1 202 [8] 00 00 00 00 00 00 82 8E - can1 203 [8] 00 00 00 00 00 00 82 8F - can1 141 [8] 00 00 00 02 57 00 82 25 - can1 151 [8] 01 00 00 EF 00 3C 83 09 - can1 131 [8] 00 00 00 00 00 00 84 BE - can1 200 [8] 00 00 00 00 00 00 83 8D - can1 201 [8] 00 00 00 00 00 00 83 8E - can1 202 [8] 00 00 00 00 00 00 83 8F - can1 203 [8] 00 00 00 00 00 00 83 90 - can1 141 [8] 00 00 00 02 56 00 83 25 - can1 151 [8] 01 00 00 EF 00 3C 84 0A - can1 131 [8] 00 00 00 00 00 00 85 BF - can1 200 [8] 00 00 00 00 00 00 84 8E - can1 201 [8] 00 00 00 00 00 00 84 8F - can1 202 [8] 00 00 00 00 00 00 84 90 - can1 203 [8] 00 00 00 00 00 00 84 91 - can1 141 [8] 00 00 00 02 55 00 84 25 - can1 151 [8] 01 00 00 EF 00 3C 85 0B - can1 131 [8] 00 00 00 00 00 00 86 C0 - can1 200 [8] 00 00 00 00 00 00 85 8F - can1 201 [8] 00 00 00 00 00 00 85 90 - can1 202 [8] 00 00 00 00 00 00 85 91 - can1 203 [8] 00 00 00 00 00 00 85 92 - can1 141 [8] 00 00 00 02 55 00 85 26 - can1 151 [8] 01 00 00 EF 00 3C 86 0C - can1 131 [8] 00 00 00 00 00 00 87 C1 - can1 200 [8] 00 00 00 00 00 00 86 90 - can1 201 [8] 00 00 00 00 00 00 86 91 - can1 202 [8] 00 00 00 00 00 00 86 92 - can1 203 [8] 00 00 00 00 00 00 86 93 - can1 141 [8] 00 00 00 02 54 00 86 26 - can1 151 [8] 01 00 00 EF 00 3C 87 0D - can1 131 [8] 00 00 00 00 00 00 88 C2 - can1 200 [8] 00 00 00 00 00 00 87 91 - can1 201 [8] 00 00 00 00 00 00 87 92 - can1 202 [8] 00 00 00 00 00 00 87 93 - can1 203 [8] 00 00 00 00 00 00 87 94 - can1 141 [8] 00 00 00 02 53 00 87 26 - can1 151 [8] 01 00 00 EF 00 3C 88 0E - can1 131 [8] 00 00 00 00 00 00 89 C3 - can1 200 [8] 00 00 00 00 00 00 88 92 - can1 201 [8] 00 00 00 00 00 00 88 93 - can1 202 [8] 00 00 00 00 00 00 88 94 - can1 203 [8] 00 00 00 00 00 00 88 95 - can1 141 [8] 00 00 00 02 52 00 88 26 - can1 151 [8] 01 00 00 EF 00 3C 89 0F - can1 131 [8] 00 00 00 00 00 00 8A C4 - can1 200 [8] 00 00 00 00 00 00 89 93 - can1 201 [8] 00 00 00 00 00 00 89 94 - can1 202 [8] 00 00 00 00 00 00 89 95 - can1 203 [8] 00 00 00 00 00 00 89 96 - can1 141 [8] 00 00 00 02 51 00 89 26 - can1 151 [8] 01 00 00 EF 00 3C 8A 10 - can1 131 [8] 00 00 00 00 00 00 8B C5 - can1 200 [8] 00 00 00 00 00 00 8A 94 - can1 201 [8] 00 00 00 00 00 00 8A 95 - can1 202 [8] 00 00 00 00 00 00 8A 96 - can1 203 [8] 00 00 00 00 00 00 8A 97 - can1 141 [8] 00 00 00 02 51 00 8A 27 - can1 151 [8] 01 00 00 EF 00 3C 8B 11 - can1 151 [8] 01 00 00 EF 00 3C 8C 12 - can1 131 [8] 00 00 00 00 00 00 8C C6 - can1 200 [8] 00 00 00 00 00 00 8B 95 - can1 201 [8] 00 00 00 00 00 00 8B 96 - can1 202 [8] 00 00 00 00 00 00 8B 97 - can1 203 [8] 00 00 00 00 00 00 8B 98 - can1 141 [8] 00 00 00 02 50 00 8B 27 - can1 151 [8] 01 00 00 EF 00 3C 8D 13 - can1 131 [8] 00 00 00 00 00 00 8D C7 - can1 200 [8] 00 00 00 00 00 00 8C 96 - can1 201 [8] 00 00 00 00 00 00 8C 97 - can1 202 [8] 00 00 00 00 00 00 8C 98 - can1 203 [8] 00 00 00 00 00 00 8C 99 - can1 141 [8] 00 00 00 02 4F 00 8C 27 - can1 131 [8] 00 00 00 00 00 00 8E C8 - can1 200 [8] 00 00 00 00 00 00 8D 97 - can1 201 [8] 00 00 00 00 00 00 8D 98 - can1 202 [8] 00 00 00 00 00 00 8D 99 - can1 203 [8] 00 00 00 00 00 00 8D 9A - can1 141 [8] 00 00 00 02 4E 00 8D 27 - can1 151 [8] 01 00 00 EF 00 3C 8E 14 - can1 131 [8] 00 00 00 00 00 00 8F C9 - can1 200 [8] 00 00 00 00 00 00 8E 98 - can1 201 [8] 00 00 00 00 00 00 8E 99 - can1 202 [8] 00 00 00 00 00 00 8E 9A - can1 203 [8] 00 00 00 00 00 00 8E 9B - can1 141 [8] 00 00 00 02 4D 00 8E 27 - can1 151 [8] 01 00 00 EF 00 3C 8F 15 - can1 131 [8] 00 00 00 00 00 00 90 CA - can1 200 [8] 00 00 00 00 00 00 8F 99 - can1 201 [8] 00 00 00 00 00 00 8F 9A - can1 202 [8] 00 00 00 00 00 00 8F 9B - can1 203 [8] 00 00 00 00 00 00 8F 9C - can1 141 [8] 00 00 00 02 4D 00 8F 28 - can1 151 [8] 01 00 00 EF 00 3C 90 16 - can1 131 [8] 00 00 00 00 00 00 91 CB - can1 200 [8] 00 00 00 00 00 00 90 9A - can1 201 [8] 00 00 00 00 00 00 90 9B - can1 202 [8] 00 00 00 00 00 00 90 9C - can1 203 [8] 00 00 00 00 00 00 90 9D - can1 141 [8] 00 00 00 02 4C 00 90 28 - can1 151 [8] 01 00 00 EF 00 3C 91 17 - can1 131 [8] 00 00 00 00 00 00 92 CC - can1 200 [8] 00 00 00 00 00 00 91 9B - can1 201 [8] 00 00 00 00 00 00 91 9C - can1 202 [8] 00 00 00 00 00 00 91 9D - can1 203 [8] 00 00 00 00 00 00 91 9E - can1 141 [8] 00 00 00 02 4B 00 91 28 - can1 151 [8] 01 00 00 EF 00 3C 92 18 - can1 131 [8] 00 00 00 00 00 00 93 CD - can1 200 [8] 00 00 00 00 00 00 92 9C - can1 201 [8] 00 00 00 00 00 00 92 9D - can1 202 [8] 00 00 00 00 00 00 92 9E - can1 203 [8] 00 00 00 00 00 00 92 9F - can1 141 [8] 00 00 00 02 4A 00 92 28 - can1 151 [8] 01 00 00 EF 00 3C 93 19 - can1 131 [8] 00 00 00 00 00 00 94 CE - can1 200 [8] 00 00 00 00 00 00 93 9D - can1 201 [8] 00 00 00 00 00 00 93 9E - can1 202 [8] 00 00 00 00 00 00 93 9F - can1 203 [8] 00 00 00 00 00 00 93 A0 - can1 141 [8] 00 00 00 02 49 00 93 28 - can1 151 [8] 01 00 00 EF 00 3C 94 1A - can1 131 [8] 00 00 00 00 00 00 95 CF - can1 200 [8] 00 00 00 00 00 00 94 9E - can1 201 [8] 00 00 00 00 00 00 94 9F - can1 202 [8] 00 00 00 00 00 00 94 A0 - can1 203 [8] 00 00 00 00 00 00 94 A1 - can1 141 [8] 00 00 00 02 49 00 94 29 - can1 151 [8] 01 00 00 EF 00 3C 95 1B - can1 151 [8] 01 00 00 EF 00 3C 96 1C - can1 131 [8] 00 00 00 00 00 00 96 D0 - can1 200 [8] 00 00 00 00 00 00 95 9F - can1 201 [8] 00 00 00 00 00 00 95 A0 - can1 202 [8] 00 00 00 00 00 00 95 A1 - can1 203 [8] 00 00 00 00 00 00 95 A2 - can1 141 [8] 00 00 00 02 48 00 95 29 - can1 131 [8] 00 00 00 00 00 00 97 D1 - can1 200 [8] 00 00 00 00 00 00 96 A0 - can1 201 [8] 00 00 00 00 00 00 96 A1 - can1 202 [8] 00 00 00 00 00 00 96 A2 - can1 203 [8] 00 00 00 00 00 00 96 A3 - can1 141 [8] 00 00 00 02 47 00 96 29 - can1 151 [8] 01 00 00 EF 00 3C 97 1D - can1 131 [8] 00 00 00 00 00 00 98 D2 - can1 200 [8] 00 00 00 00 00 00 97 A1 - can1 201 [8] 00 00 00 00 00 00 97 A2 - can1 202 [8] 00 00 00 00 00 00 97 A3 - can1 203 [8] 00 00 00 00 00 00 97 A4 - can1 141 [8] 00 00 00 02 46 00 97 29 - can1 151 [8] 01 00 00 EF 00 3C 98 1E - can1 131 [8] 00 00 00 00 00 00 99 D3 - can1 200 [8] 00 00 00 00 00 00 98 A2 - can1 201 [8] 00 00 00 00 00 00 98 A3 - can1 202 [8] 00 00 00 00 00 00 98 A4 - can1 203 [8] 00 00 00 00 00 00 98 A5 - can1 141 [8] 00 00 00 02 45 00 98 29 - can1 151 [8] 01 00 00 EF 00 3C 99 1F - can1 131 [8] 00 00 00 00 00 00 9A D4 - can1 200 [8] 00 00 00 00 00 00 99 A3 - can1 201 [8] 00 00 00 00 00 00 99 A4 - can1 202 [8] 00 00 00 00 00 00 99 A5 - can1 203 [8] 00 00 00 00 00 00 99 A6 - can1 141 [8] 00 00 00 02 44 00 99 29 - can1 151 [8] 01 00 00 EF 00 3C 9A 20 - can1 131 [8] 00 00 00 00 00 00 9B D5 - can1 200 [8] 00 00 00 00 00 00 9A A4 - can1 201 [8] 00 00 00 00 00 00 9A A5 - can1 202 [8] 00 00 00 00 00 00 9A A6 - can1 203 [8] 00 00 00 00 00 00 9A A7 - can1 141 [8] 00 00 00 02 44 00 9A 2A - can1 151 [8] 01 00 00 EF 00 3C 9B 21 - can1 131 [8] 00 00 00 00 00 00 9C D6 - can1 200 [8] 00 00 00 00 00 00 9B A5 - can1 201 [8] 00 00 00 00 00 00 9B A6 - can1 202 [8] 00 00 00 00 00 00 9B A7 - can1 203 [8] 00 00 00 00 00 00 9B A8 - can1 141 [8] 00 00 00 02 43 00 9B 2A - can1 151 [8] 01 00 00 EF 00 3C 9C 22 - can1 131 [8] 00 00 00 00 00 00 9D D7 - can1 200 [8] 00 00 00 00 00 00 9C A6 - can1 201 [8] 00 00 00 00 00 00 9C A7 - can1 202 [8] 00 00 00 00 00 00 9C A8 - can1 203 [8] 00 00 00 00 00 00 9C A9 - can1 141 [8] 00 00 00 02 42 00 9C 2A - can1 151 [8] 01 00 00 EF 00 3C 9D 23 - can1 131 [8] 00 00 00 00 00 00 9E D8 - can1 200 [8] 00 00 00 00 00 00 9D A7 - can1 201 [8] 00 00 00 00 00 00 9D A8 - can1 202 [8] 00 00 00 00 00 00 9D A9 - can1 203 [8] 00 00 00 00 00 00 9D AA - can1 141 [8] 00 00 00 02 41 00 9D 2A - can1 151 [8] 01 00 00 EF 00 3C 9E 24 - can1 131 [8] 00 00 00 00 00 00 9F D9 - can1 200 [8] 00 00 00 00 00 00 9E A8 - can1 201 [8] 00 00 00 00 00 00 9E A9 - can1 202 [8] 00 00 00 00 00 00 9E AA - can1 203 [8] 00 00 00 00 00 00 9E AB - can1 141 [8] 00 00 00 02 40 00 9E 2A - can1 151 [8] 01 00 00 EF 00 3C 9F 25 - can1 151 [8] 01 00 00 EF 00 3C A0 26 - can1 131 [8] 00 00 00 00 00 00 A0 DA - can1 200 [8] 00 00 00 00 00 00 9F A9 - can1 201 [8] 00 00 00 00 00 00 9F AA - can1 202 [8] 00 00 00 00 00 00 9F AB - can1 203 [8] 00 00 00 00 00 00 9F AC - can1 141 [8] 00 00 00 02 40 00 9F 2B - can1 131 [8] 00 00 00 00 00 00 A1 DB - can1 200 [8] 00 00 00 00 00 00 A0 AA - can1 201 [8] 00 00 00 00 00 00 A0 AB - can1 202 [8] 00 00 00 00 00 00 A0 AC - can1 203 [8] 00 00 00 00 00 00 A0 AD - can1 141 [8] 00 00 00 02 3F 00 A0 2B - can1 151 [8] 01 00 00 EF 00 3C A1 27 - can1 131 [8] 00 00 00 00 00 00 A2 DC - can1 200 [8] 00 00 00 00 00 00 A1 AB - can1 201 [8] 00 00 00 00 00 00 A1 AC - can1 202 [8] 00 00 00 00 00 00 A1 AD - can1 203 [8] 00 00 00 00 00 00 A1 AE - can1 141 [8] 00 00 00 02 3E 00 A1 2B - can1 151 [8] 01 00 00 EF 00 3C A2 28 - can1 131 [8] 00 00 00 00 00 00 A3 DD - can1 200 [8] 00 00 00 00 00 00 A2 AC - can1 201 [8] 00 00 00 00 00 00 A2 AD - can1 202 [8] 00 00 00 00 00 00 A2 AE - can1 203 [8] 00 00 00 00 00 00 A2 AF - can1 141 [8] 00 00 00 02 3D 00 A2 2B - can1 151 [8] 01 00 00 EF 00 3C A3 29 - can1 131 [8] 00 00 00 00 00 00 A4 DE - can1 200 [8] 00 00 00 00 00 00 A3 AD - can1 201 [8] 00 00 00 00 00 00 A3 AE - can1 202 [8] 00 00 00 00 00 00 A3 AF - can1 203 [8] 00 00 00 00 00 00 A3 B0 - can1 141 [8] 00 00 00 02 3C 00 A3 2B - can1 151 [8] 01 00 00 EF 00 3C A4 2A - can1 131 [8] 00 00 00 00 00 00 A5 DF - can1 200 [8] 00 00 00 00 00 00 A4 AE - can1 201 [8] 00 00 00 00 00 00 A4 AF - can1 202 [8] 00 00 00 00 00 00 A4 B0 - can1 203 [8] 00 00 00 00 00 00 A4 B1 - can1 141 [8] 00 00 00 02 3C 00 A4 2C - can1 151 [8] 01 00 00 EF 00 3C A5 2B - can1 131 [8] 00 00 00 00 00 00 A6 E0 - can1 200 [8] 00 00 00 00 00 00 A5 AF - can1 201 [8] 00 00 00 00 00 00 A5 B0 - can1 202 [8] 00 00 00 00 00 00 A5 B1 - can1 203 [8] 00 00 00 00 00 00 A5 B2 - can1 141 [8] 00 00 00 02 3B 00 A5 2C - can1 151 [8] 01 00 00 EF 00 3C A6 2C - can1 131 [8] 00 00 00 00 00 00 A7 E1 - can1 200 [8] 00 00 00 00 00 00 A6 B0 - can1 201 [8] 00 00 00 00 00 00 A6 B1 - can1 202 [8] 00 00 00 00 00 00 A6 B2 - can1 203 [8] 00 00 00 00 00 00 A6 B3 - can1 141 [8] 00 00 00 02 3A 00 A6 2C - can1 151 [8] 01 00 00 EF 00 3C A7 2D - can1 131 [8] 00 00 00 00 00 00 A8 E2 - can1 200 [8] 00 00 00 00 00 00 A7 B1 - can1 201 [8] 00 00 00 00 00 00 A7 B2 - can1 202 [8] 00 00 00 00 00 00 A7 B3 - can1 203 [8] 00 00 00 00 00 00 A7 B4 - can1 141 [8] 00 00 00 02 39 00 A7 2C - can1 151 [8] 01 00 00 EF 00 3C A8 2E - can1 151 [8] 01 00 00 EF 00 3C A9 2F - can1 131 [8] 00 00 00 00 00 00 A9 E3 - can1 200 [8] 00 00 00 00 00 00 A8 B2 - can1 201 [8] 00 00 00 00 00 00 A8 B3 - can1 202 [8] 00 00 00 00 00 00 A8 B4 - can1 203 [8] 00 00 00 00 00 00 A8 B5 - can1 141 [8] 00 00 00 02 38 00 A8 2C - can1 151 [8] 01 00 00 EF 00 3C AA 30 - can1 131 [8] 00 00 00 00 00 00 AA E4 - can1 200 [8] 00 00 00 00 00 00 A9 B3 - can1 201 [8] 00 00 00 00 00 00 A9 B4 - can1 202 [8] 00 00 00 00 00 00 A9 B5 - can1 203 [8] 00 00 00 00 00 00 A9 B6 - can1 141 [8] 00 00 00 02 38 00 A9 2D - can1 131 [8] 00 00 00 00 00 00 AB E5 - can1 200 [8] 00 00 00 00 00 00 AA B4 - can1 201 [8] 00 00 00 00 00 00 AA B5 - can1 202 [8] 00 00 00 00 00 00 AA B6 - can1 203 [8] 00 00 00 00 00 00 AA B7 - can1 141 [8] 00 00 00 02 37 00 AA 2D - can1 151 [8] 01 00 00 EF 00 3C AB 31 - can1 131 [8] 00 00 00 00 00 00 AC E6 - can1 200 [8] 00 00 00 00 00 00 AB B5 - can1 201 [8] 00 00 00 00 00 00 AB B6 - can1 202 [8] 00 00 00 00 00 00 AB B7 - can1 203 [8] 00 00 00 00 00 00 AB B8 - can1 141 [8] 00 00 00 02 36 00 AB 2D - can1 151 [8] 01 00 00 EF 00 3C AC 32 - can1 131 [8] 00 00 00 00 00 00 AD E7 - can1 200 [8] 00 00 00 00 00 00 AC B6 - can1 201 [8] 00 00 00 00 00 00 AC B7 - can1 202 [8] 00 00 00 00 00 00 AC B8 - can1 203 [8] 00 00 00 00 00 00 AC B9 - can1 141 [8] 00 00 00 02 35 00 AC 2D - can1 151 [8] 01 00 00 EF 00 3C AD 33 - can1 131 [8] 00 00 00 00 00 00 AE E8 - can1 200 [8] 00 00 00 00 00 00 AD B7 - can1 201 [8] 00 00 00 00 00 00 AD B8 - can1 202 [8] 00 00 00 00 00 00 AD B9 - can1 203 [8] 00 00 00 00 00 00 AD BA - can1 141 [8] 00 00 00 02 34 00 AD 2D - can1 151 [8] 01 00 00 EF 00 3C AE 34 - can1 131 [8] 00 00 00 00 00 00 AF E9 - can1 200 [8] 00 00 00 00 00 00 AE B8 - can1 201 [8] 00 00 00 00 00 00 AE B9 - can1 202 [8] 00 00 00 00 00 00 AE BA - can1 203 [8] 00 00 00 00 00 00 AE BB - can1 141 [8] 00 00 00 02 33 00 AE 2D - can1 151 [8] 01 00 00 EF 00 3C AF 35 - can1 131 [8] 00 00 00 00 00 00 B0 EA - can1 200 [8] 00 00 00 00 00 00 AF B9 - can1 201 [8] 00 00 00 00 00 00 AF BA - can1 202 [8] 00 00 00 00 00 00 AF BB - can1 203 [8] 00 00 00 00 00 00 AF BC - can1 141 [8] 00 00 00 02 33 00 AF 2E - can1 151 [8] 01 00 00 EF 00 3C B0 36 - can1 131 [8] 00 00 00 00 00 00 B1 EB - can1 200 [8] 00 00 00 00 00 00 B0 BA - can1 201 [8] 00 00 00 00 00 00 B0 BB - can1 202 [8] 00 00 00 00 00 00 B0 BC - can1 203 [8] 00 00 00 00 00 00 B0 BD - can1 141 [8] 00 00 00 02 32 00 B0 2E - can1 151 [8] 01 00 00 EF 00 3C B1 37 - can1 131 [8] 00 00 00 00 00 00 B2 EC - can1 200 [8] 00 00 00 00 00 00 B1 BB - can1 201 [8] 00 00 00 00 00 00 B1 BC - can1 202 [8] 00 00 00 00 00 00 B1 BD - can1 203 [8] 00 00 00 00 00 00 B1 BE - can1 141 [8] 00 00 00 02 31 00 B1 2E - can1 151 [8] 01 00 00 EF 00 3C B2 38 - can1 131 [8] 00 00 00 00 00 00 B3 ED - can1 200 [8] 00 00 00 00 00 00 B2 BC - can1 201 [8] 00 00 00 00 00 00 B2 BD - can1 202 [8] 00 00 00 00 00 00 B2 BE - can1 203 [8] 00 00 00 00 00 00 B2 BF - can1 141 [8] 00 00 00 02 30 00 B2 2E - can1 151 [8] 01 00 00 EF 00 3C B3 39 - can1 131 [8] 00 00 00 00 00 00 B4 EE - can1 200 [8] 00 00 00 00 00 00 B3 BD - can1 201 [8] 00 00 00 00 00 00 B3 BE - can1 202 [8] 00 00 00 00 00 00 B3 BF - can1 203 [8] 00 00 00 00 00 00 B3 C0 - can1 141 [8] 00 00 00 02 2F 00 B3 2E - can1 151 [8] 01 00 00 EF 00 3C B4 3A - can1 131 [8] 00 00 00 00 00 00 B5 EF - can1 200 [8] 00 00 00 00 00 00 B4 BE - can1 201 [8] 00 00 00 00 00 00 B4 BF - can1 202 [8] 00 00 00 00 00 00 B4 C0 - can1 203 [8] 00 00 00 00 00 00 B4 C1 - can1 141 [8] 00 00 00 02 2F 00 B4 2F - can1 151 [8] 01 00 00 EF 00 3C B5 3B - can1 131 [8] 00 00 00 00 00 00 B6 F0 - can1 200 [8] 00 00 00 00 00 00 B5 BF - can1 201 [8] 00 00 00 00 00 00 B5 C0 - can1 202 [8] 00 00 00 00 00 00 B5 C1 - can1 203 [8] 00 00 00 00 00 00 B5 C2 - can1 141 [8] 00 00 00 02 2E 00 B5 2F - can1 151 [8] 01 00 00 EF 00 3C B6 3C - can1 131 [8] 00 00 00 00 00 00 B7 F1 - can1 200 [8] 00 00 00 00 00 00 B6 C0 - can1 201 [8] 00 00 00 00 00 00 B6 C1 - can1 202 [8] 00 00 00 00 00 00 B6 C2 - can1 203 [8] 00 00 00 00 00 00 B6 C3 - can1 141 [8] 00 00 00 02 2D 00 B6 2F - can1 151 [8] 01 00 00 EF 00 3C B7 3D - can1 131 [8] 00 00 00 00 00 00 B8 F2 - can1 200 [8] 00 00 00 00 00 00 B7 C1 - can1 201 [8] 00 00 00 00 00 00 B7 C2 - can1 202 [8] 00 00 00 00 00 00 B7 C3 - can1 203 [8] 00 00 00 00 00 00 B7 C4 - can1 141 [8] 00 00 00 02 2C 00 B7 2F - can1 151 [8] 01 00 00 EF 00 3C B8 3E - can1 131 [8] 00 00 00 00 00 00 B9 F3 - can1 200 [8] 00 00 00 00 00 00 B8 C2 - can1 201 [8] 00 00 00 00 00 00 B8 C3 - can1 202 [8] 00 00 00 00 00 00 B8 C4 - can1 203 [8] 00 00 00 00 00 00 B8 C5 - can1 141 [8] 00 00 00 02 2B 00 B8 2F - can1 151 [8] 01 00 00 EF 00 3C B9 3F - can1 131 [8] 00 00 00 00 00 00 BA F4 - can1 200 [8] 00 00 00 00 00 00 B9 C3 - can1 201 [8] 00 00 00 00 00 00 B9 C4 - can1 202 [8] 00 00 00 00 00 00 B9 C5 - can1 203 [8] 00 00 00 00 00 00 B9 C6 - can1 141 [8] 00 00 00 02 2B 00 B9 30 - can1 151 [8] 01 00 00 EF 00 3C BA 40 - can1 131 [8] 00 00 00 00 00 00 BB F5 - can1 200 [8] 00 00 00 00 00 00 BA C4 - can1 201 [8] 00 00 00 00 00 00 BA C5 - can1 202 [8] 00 00 00 00 00 00 BA C6 - can1 203 [8] 00 00 00 00 00 00 BA C7 - can1 141 [8] 00 00 00 02 2A 00 BA 30 - can1 151 [8] 01 00 00 EF 00 3C BB 41 - can1 131 [8] 00 00 00 00 00 00 BC F6 - can1 200 [8] 00 00 00 00 00 00 BB C5 - can1 201 [8] 00 00 00 00 00 00 BB C6 - can1 202 [8] 00 00 00 00 00 00 BB C7 - can1 203 [8] 00 00 00 00 00 00 BB C8 - can1 141 [8] 00 00 00 02 29 00 BB 30 - can1 151 [8] 01 00 00 EF 00 3C BC 42 - can1 131 [8] 00 00 00 00 00 00 BD F7 - can1 200 [8] 00 00 00 00 00 00 BC C6 - can1 201 [8] 00 00 00 00 00 00 BC C7 - can1 202 [8] 00 00 00 00 00 00 BC C8 - can1 203 [8] 00 00 00 00 00 00 BC C9 - can1 141 [8] 00 00 00 02 28 00 BC 30 - can1 151 [8] 01 00 00 EF 00 3C BD 43 - can1 131 [8] 00 00 00 00 00 00 BE F8 - can1 200 [8] 00 00 00 00 00 00 BD C7 - can1 201 [8] 00 00 00 00 00 00 BD C8 - can1 202 [8] 00 00 00 00 00 00 BD C9 - can1 203 [8] 00 00 00 00 00 00 BD CA - can1 141 [8] 00 00 00 02 27 00 BD 30 - can1 151 [8] 01 00 00 EF 00 3C BE 44 - can1 131 [8] 00 00 00 00 00 00 BF F9 - can1 200 [8] 00 00 00 00 00 00 BE C8 - can1 201 [8] 00 00 00 00 00 00 BE C9 - can1 202 [8] 00 00 00 00 00 00 BE CA - can1 203 [8] 00 00 00 00 00 00 BE CB - can1 141 [8] 00 00 00 02 27 00 BE 31 - can1 151 [8] 01 00 00 EF 00 3C BF 45 - can1 131 [8] 00 00 00 00 00 00 C0 FA - can1 200 [8] 00 00 00 00 00 00 BF C9 - can1 201 [8] 00 00 00 00 00 00 BF CA - can1 202 [8] 00 00 00 00 00 00 BF CB - can1 203 [8] 00 00 00 00 00 00 BF CC - can1 141 [8] 00 00 00 02 26 00 BF 31 - can1 151 [8] 01 00 00 EF 00 3C C0 46 - can1 131 [8] 00 00 00 00 00 00 C1 FB - can1 200 [8] 00 00 00 00 00 00 C0 CA - can1 201 [8] 00 00 00 00 00 00 C0 CB - can1 202 [8] 00 00 00 00 00 00 C0 CC - can1 203 [8] 00 00 00 00 00 00 C0 CD - can1 141 [8] 00 00 00 02 25 00 C0 31 - can1 151 [8] 01 00 00 EF 00 3C C1 47 - can1 131 [8] 00 00 00 00 00 00 C2 FC - can1 200 [8] 00 00 00 00 00 00 C1 CB - can1 201 [8] 00 00 00 00 00 00 C1 CC - can1 202 [8] 00 00 00 00 00 00 C1 CD - can1 203 [8] 00 00 00 00 00 00 C1 CE - can1 141 [8] 00 00 00 02 24 00 C1 31 - can1 151 [8] 01 00 00 EF 00 3C C2 48 - can1 131 [8] 00 00 00 00 00 00 C3 FD - can1 200 [8] 00 00 00 00 00 00 C2 CC - can1 201 [8] 00 00 00 00 00 00 C2 CD - can1 202 [8] 00 00 00 00 00 00 C2 CE - can1 203 [8] 00 00 00 00 00 00 C2 CF - can1 141 [8] 00 00 00 02 23 00 C2 31 - can1 151 [8] 01 00 00 EF 00 3C C3 49 - can1 131 [8] 00 00 00 00 00 00 C4 FE - can1 200 [8] 00 00 00 00 00 00 C3 CD - can1 201 [8] 00 00 00 00 00 00 C3 CE - can1 202 [8] 00 00 00 00 00 00 C3 CF - can1 203 [8] 00 00 00 00 00 00 C3 D0 - can1 141 [8] 00 00 00 02 23 00 C3 32 - can1 151 [8] 01 00 00 EF 00 3C C4 4A - can1 131 [8] 00 00 00 00 00 00 C5 FF - can1 200 [8] 00 00 00 00 00 00 C4 CE - can1 201 [8] 00 00 00 00 00 00 C4 CF - can1 202 [8] 00 00 00 00 00 00 C4 D0 - can1 203 [8] 00 00 00 00 00 00 C4 D1 - can1 141 [8] 00 00 00 02 22 00 C4 32 - can1 151 [8] 01 00 00 EF 00 3C C5 4B - can1 131 [8] 00 00 00 00 00 00 C6 00 - can1 200 [8] 00 00 00 00 00 00 C5 CF - can1 201 [8] 00 00 00 00 00 00 C5 D0 - can1 202 [8] 00 00 00 00 00 00 C5 D1 - can1 203 [8] 00 00 00 00 00 00 C5 D2 - can1 141 [8] 00 00 00 02 21 00 C5 32 - can1 151 [8] 01 00 00 EF 00 3C C6 4C - can1 131 [8] 00 00 00 00 00 00 C7 01 - can1 200 [8] 00 00 00 00 00 00 C6 D0 - can1 201 [8] 00 00 00 00 00 00 C6 D1 - can1 202 [8] 00 00 00 00 00 00 C6 D2 - can1 203 [8] 00 00 00 00 00 00 C6 D3 - can1 141 [8] 00 00 00 02 20 00 C6 32 - can1 151 [8] 01 00 00 EF 00 3C C7 4D - can1 131 [8] 00 00 00 00 00 00 C8 02 - can1 200 [8] 00 00 00 00 00 00 C7 D1 - can1 201 [8] 00 00 00 00 00 00 C7 D2 - can1 202 [8] 00 00 00 00 00 00 C7 D3 - can1 203 [8] 00 00 00 00 00 00 C7 D4 - can1 141 [8] 00 00 00 02 1F 00 C7 32 - can1 151 [8] 01 00 00 EF 00 3C C8 4E - can1 131 [8] 00 00 00 00 00 00 C9 03 - can1 200 [8] 00 00 00 00 00 00 C8 D2 - can1 201 [8] 00 00 00 00 00 00 C8 D3 - can1 202 [8] 00 00 00 00 00 00 C8 D4 - can1 203 [8] 00 00 00 00 00 00 C8 D5 - can1 141 [8] 00 00 00 02 1F 00 C8 33 - can1 151 [8] 01 00 00 EF 00 3C C9 4F - can1 131 [8] 00 00 00 00 00 00 CA 04 - can1 200 [8] 00 00 00 00 00 00 C9 D3 - can1 201 [8] 00 00 00 00 00 00 C9 D4 - can1 202 [8] 00 00 00 00 00 00 C9 D5 - can1 203 [8] 00 00 00 00 00 00 C9 D6 - can1 141 [8] 00 00 00 02 1E 00 C9 33 - can1 151 [8] 01 00 00 EF 00 3C CA 50 - can1 131 [8] 00 00 00 00 00 00 CB 05 - can1 200 [8] 00 00 00 00 00 00 CA D4 - can1 201 [8] 00 00 00 00 00 00 CA D5 - can1 202 [8] 00 00 00 00 00 00 CA D6 - can1 203 [8] 00 00 00 00 00 00 CA D7 - can1 141 [8] 00 00 00 02 1D 00 CA 33 - can1 151 [8] 01 00 00 EF 00 3C CB 51 - can1 131 [8] 00 00 00 00 00 00 CC 06 - can1 200 [8] 00 00 00 00 00 00 CB D5 - can1 201 [8] 00 00 00 00 00 00 CB D6 - can1 202 [8] 00 00 00 00 00 00 CB D7 - can1 203 [8] 00 00 00 00 00 00 CB D8 - can1 141 [8] 00 00 00 02 1C 00 CB 33 - can1 151 [8] 01 00 00 EF 00 3C CC 52 - can1 131 [8] 00 00 00 00 00 00 CD 07 - can1 200 [8] 00 00 00 00 00 00 CC D6 - can1 201 [8] 00 00 00 00 00 00 CC D7 - can1 202 [8] 00 00 00 00 00 00 CC D8 - can1 203 [8] 00 00 00 00 00 00 CC D9 - can1 141 [8] 00 00 00 02 1B 00 CC 33 - can1 151 [8] 01 00 00 EF 00 3C CD 53 - can1 131 [8] 00 00 00 00 00 00 CE 08 - can1 200 [8] 00 00 00 00 00 00 CD D7 - can1 201 [8] 00 00 00 00 00 00 CD D8 - can1 202 [8] 00 00 00 00 00 00 CD D9 - can1 203 [8] 00 00 00 00 00 00 CD DA - can1 141 [8] 00 00 00 02 1A 00 CD 33 - can1 151 [8] 01 00 00 EF 00 3C CE 54 - can1 131 [8] 00 00 00 00 00 00 CF 09 - can1 200 [8] 00 00 00 00 00 00 CE D8 - can1 201 [8] 00 00 00 00 00 00 CE D9 - can1 202 [8] 00 00 00 00 00 00 CE DA - can1 203 [8] 00 00 00 00 00 00 CE DB - can1 141 [8] 00 00 00 02 1A 00 CE 34 - can1 151 [8] 01 00 00 EF 00 3C CF 55 - can1 131 [8] 00 00 00 00 00 00 D0 0A - can1 200 [8] 00 00 00 00 00 00 CF D9 - can1 201 [8] 00 00 00 00 00 00 CF DA - can1 202 [8] 00 00 00 00 00 00 CF DB - can1 203 [8] 00 00 00 00 00 00 CF DC - can1 141 [8] 00 00 00 02 19 00 CF 34 - can1 151 [8] 01 00 00 EF 00 3C D0 56 - can1 151 [8] 01 00 00 EF 00 3C D1 57 - can1 131 [8] 00 00 00 00 00 00 D1 0B - can1 200 [8] 00 00 00 00 00 00 D0 DA - can1 201 [8] 00 00 00 00 00 00 D0 DB - can1 202 [8] 00 00 00 00 00 00 D0 DC - can1 203 [8] 00 00 00 00 00 00 D0 DD - can1 141 [8] 00 00 00 02 18 00 D0 34 - can1 131 [8] 00 00 00 00 00 00 D2 0C - can1 200 [8] 00 00 00 00 00 00 D1 DB - can1 201 [8] 00 00 00 00 00 00 D1 DC - can1 202 [8] 00 00 00 00 00 00 D1 DD - can1 203 [8] 00 00 00 00 00 00 D1 DE - can1 141 [8] 00 00 00 02 17 00 D1 34 - can1 151 [8] 01 00 00 EF 00 3C D2 58 - can1 131 [8] 00 00 00 00 00 00 D3 0D - can1 200 [8] 00 00 00 00 00 00 D2 DC - can1 201 [8] 00 00 00 00 00 00 D2 DD - can1 202 [8] 00 00 00 00 00 00 D2 DE - can1 203 [8] 00 00 00 00 00 00 D2 DF - can1 141 [8] 00 00 00 02 16 00 D2 34 - can1 151 [8] 01 00 00 EF 00 3C D3 59 - can1 131 [8] 00 00 00 00 00 00 D4 0E - can1 200 [8] 00 00 00 00 00 00 D3 DD - can1 201 [8] 00 00 00 00 00 00 D3 DE - can1 202 [8] 00 00 00 00 00 00 D3 DF - can1 203 [8] 00 00 00 00 00 00 D3 E0 - can1 141 [8] 00 00 00 02 16 00 D3 35 - can1 151 [8] 01 00 00 EF 00 3C D4 5A - can1 131 [8] 00 00 00 00 00 00 D5 0F - can1 200 [8] 00 00 00 00 00 00 D4 DE - can1 201 [8] 00 00 00 00 00 00 D4 DF - can1 202 [8] 00 00 00 00 00 00 D4 E0 - can1 203 [8] 00 00 00 00 00 00 D4 E1 - can1 141 [8] 00 00 00 02 15 00 D4 35 - can1 151 [8] 01 00 00 EF 00 3C D5 5B - can1 131 [8] 00 00 00 00 00 00 D6 10 - can1 200 [8] 00 00 00 00 00 00 D5 DF - can1 201 [8] 00 00 00 00 00 00 D5 E0 - can1 202 [8] 00 00 00 00 00 00 D5 E1 - can1 203 [8] 00 00 00 00 00 00 D5 E2 - can1 141 [8] 00 00 00 02 14 00 D5 35 - can1 151 [8] 01 00 00 EF 00 3C D6 5C - can1 131 [8] 00 00 00 00 00 00 D7 11 - can1 200 [8] 00 00 00 00 00 00 D6 E0 - can1 201 [8] 00 00 00 00 00 00 D6 E1 - can1 202 [8] 00 00 00 00 00 00 D6 E2 - can1 203 [8] 00 00 00 00 00 00 D6 E3 - can1 141 [8] 00 00 00 02 13 00 D6 35 - can1 151 [8] 01 00 00 EF 00 3C D7 5D - can1 131 [8] 00 00 00 00 00 00 D8 12 - can1 200 [8] 00 00 00 00 00 00 D7 E1 - can1 201 [8] 00 00 00 00 00 00 D7 E2 - can1 202 [8] 00 00 00 00 00 00 D7 E3 - can1 203 [8] 00 00 00 00 00 00 D7 E4 - can1 141 [8] 00 00 00 02 12 00 D7 35 - can1 151 [8] 01 00 00 EF 00 3C D8 5E - can1 131 [8] 00 00 00 00 00 00 D9 13 - can1 200 [8] 00 00 00 00 00 00 D8 E2 - can1 201 [8] 00 00 00 00 00 00 D8 E3 - can1 202 [8] 00 00 00 00 00 00 D8 E4 - can1 203 [8] 00 00 00 00 00 00 D8 E5 - can1 141 [8] 00 00 00 02 12 00 D8 36 - can1 151 [8] 01 00 00 EF 00 3C D9 5F - can1 131 [8] 00 00 00 00 00 00 DA 14 - can1 200 [8] 00 00 00 00 00 00 D9 E3 - can1 201 [8] 00 00 00 00 00 00 D9 E4 - can1 202 [8] 00 00 00 00 00 00 D9 E5 - can1 203 [8] 00 00 00 00 00 00 D9 E6 - can1 141 [8] 00 00 00 02 11 00 D9 36 - can1 151 [8] 01 00 00 EF 00 3C DA 60 - can1 151 [8] 01 00 00 EF 00 3C DB 61 - can1 131 [8] 00 00 00 00 00 00 DB 15 - can1 200 [8] 00 00 00 00 00 00 DA E4 - can1 201 [8] 00 00 00 00 00 00 DA E5 - can1 202 [8] 00 00 00 00 00 00 DA E6 - can1 203 [8] 00 00 00 00 00 00 DA E7 - can1 141 [8] 00 00 00 02 10 00 DA 36 - can1 131 [8] 00 00 00 00 00 00 DC 16 - can1 200 [8] 00 00 00 00 00 00 DB E5 - can1 201 [8] 00 00 00 00 00 00 DB E6 - can1 202 [8] 00 00 00 00 00 00 DB E7 - can1 203 [8] 00 00 00 00 00 00 DB E8 - can1 141 [8] 00 00 00 02 0F 00 DB 36 - can1 151 [8] 01 00 00 EF 00 3C DC 62 - can1 131 [8] 00 00 00 00 00 00 DD 17 - can1 200 [8] 00 00 00 00 00 00 DC E6 - can1 201 [8] 00 00 00 00 00 00 DC E7 - can1 202 [8] 00 00 00 00 00 00 DC E8 - can1 203 [8] 00 00 00 00 00 00 DC E9 - can1 141 [8] 00 00 00 02 0E 00 DC 36 - can1 151 [8] 01 00 00 EF 00 3C DD 63 - can1 131 [8] 00 00 00 00 00 00 DE 18 - can1 200 [8] 00 00 00 00 00 00 DD E7 - can1 201 [8] 00 00 00 00 00 00 DD E8 - can1 202 [8] 00 00 00 00 00 00 DD E9 - can1 203 [8] 00 00 00 00 00 00 DD EA - can1 141 [8] 00 00 00 02 0E 00 DD 37 - can1 151 [8] 01 00 00 EF 00 3C DE 64 - can1 131 [8] 00 00 00 00 00 00 DF 19 - can1 200 [8] 00 00 00 00 00 00 DE E8 - can1 201 [8] 00 00 00 00 00 00 DE E9 - can1 202 [8] 00 00 00 00 00 00 DE EA - can1 203 [8] 00 00 00 00 00 00 DE EB - can1 141 [8] 00 00 00 02 0D 00 DE 37 - can1 151 [8] 01 00 00 EF 00 3C DF 65 - can1 131 [8] 00 00 00 00 00 00 E0 1A - can1 200 [8] 00 00 00 00 00 00 DF E9 - can1 201 [8] 00 00 00 00 00 00 DF EA - can1 202 [8] 00 00 00 00 00 00 DF EB - can1 203 [8] 00 00 00 00 00 00 DF EC - can1 141 [8] 00 00 00 02 0C 00 DF 37 - can1 151 [8] 01 00 00 EF 00 3C E0 66 - can1 131 [8] 00 00 00 00 00 00 E1 1B - can1 200 [8] 00 00 00 00 00 00 E0 EA - can1 201 [8] 00 00 00 00 00 00 E0 EB - can1 202 [8] 00 00 00 00 00 00 E0 EC - can1 203 [8] 00 00 00 00 00 00 E0 ED - can1 141 [8] 00 00 00 02 0B 00 E0 37 - can1 151 [8] 01 00 00 EF 00 3C E1 67 - can1 151 [8] 01 00 00 EF 00 3C E2 68 - can1 131 [8] 00 00 00 00 00 00 E2 1C - can1 200 [8] 00 00 00 00 00 00 E1 EB - can1 201 [8] 00 00 00 00 00 00 E1 EC - can1 202 [8] 00 00 00 00 00 00 E1 ED - can1 203 [8] 00 00 00 00 00 00 E1 EE - can1 141 [8] 00 00 00 02 0A 00 E1 37 - can1 131 [8] 00 00 00 00 00 00 E3 1D - can1 200 [8] 00 00 00 00 00 00 E2 EC - can1 201 [8] 00 00 00 00 00 00 E2 ED - can1 202 [8] 00 00 00 00 00 00 E2 EE - can1 203 [8] 00 00 00 00 00 00 E2 EF - can1 141 [8] 00 00 00 02 0A 00 E2 38 - can1 151 [8] 01 00 00 EF 00 3C E3 69 - can1 131 [8] 00 00 00 00 00 00 E4 1E - can1 200 [8] 00 00 00 00 00 00 E3 ED - can1 201 [8] 00 00 00 00 00 00 E3 EE - can1 202 [8] 00 00 00 00 00 00 E3 EF - can1 203 [8] 00 00 00 00 00 00 E3 F0 - can1 141 [8] 00 00 00 02 09 00 E3 38 - can1 151 [8] 01 00 00 EF 00 3C E4 6A - can1 131 [8] 00 00 00 00 00 00 E5 1F - can1 200 [8] 00 00 00 00 00 00 E4 EE - can1 201 [8] 00 00 00 00 00 00 E4 EF - can1 202 [8] 00 00 00 00 00 00 E4 F0 - can1 203 [8] 00 00 00 00 00 00 E4 F1 - can1 141 [8] 00 00 00 02 08 00 E4 38 - can1 151 [8] 01 00 00 EF 00 3C E5 6B - can1 151 [8] 01 00 00 EF 00 3C E6 6C - can1 131 [8] 00 00 00 00 00 00 E6 20 - can1 200 [8] 00 00 00 00 00 00 E5 EF - can1 201 [8] 00 00 00 00 00 00 E5 F0 - can1 202 [8] 00 00 00 00 00 00 E5 F1 - can1 203 [8] 00 00 00 00 00 00 E5 F2 - can1 141 [8] 00 00 00 02 07 00 E5 38 - can1 151 [8] 01 00 00 EF 00 3C E7 6D - can1 131 [8] 00 00 00 00 00 00 E7 21 - can1 200 [8] 00 00 00 00 00 00 E6 F0 - can1 201 [8] 00 00 00 00 00 00 E6 F1 - can1 202 [8] 00 00 00 00 00 00 E6 F2 - can1 203 [8] 00 00 00 00 00 00 E6 F3 - can1 141 [8] 00 00 00 02 06 00 E6 38 - can1 131 [8] 00 00 00 00 00 00 E8 22 - can1 200 [8] 00 00 00 00 00 00 E7 F1 - can1 201 [8] 00 00 00 00 00 00 E7 F2 - can1 202 [8] 00 00 00 00 00 00 E7 F3 - can1 203 [8] 00 00 00 00 00 00 E7 F4 - can1 141 [8] 00 00 00 02 05 00 E7 38 - can1 151 [8] 01 00 00 EF 00 3C E8 6E - can1 131 [8] 00 00 00 00 00 00 E9 23 - can1 200 [8] 00 00 00 00 00 00 E8 F2 - can1 201 [8] 00 00 00 00 00 00 E8 F3 - can1 202 [8] 00 00 00 00 00 00 E8 F4 - can1 203 [8] 00 00 00 00 00 00 E8 F5 - can1 141 [8] 00 00 00 02 05 00 E8 39 - can1 151 [8] 01 00 00 EF 00 3C E9 6F - can1 131 [8] 00 00 00 00 00 00 EA 24 - can1 200 [8] 00 00 00 00 00 00 E9 F3 - can1 201 [8] 00 00 00 00 00 00 E9 F4 - can1 202 [8] 00 00 00 00 00 00 E9 F5 - can1 203 [8] 00 00 00 00 00 00 E9 F6 - can1 141 [8] 00 00 00 02 04 00 E9 39 - can1 151 [8] 01 00 00 EF 00 3C EA 70 - can1 131 [8] 00 00 00 00 00 00 EB 25 - can1 200 [8] 00 00 00 00 00 00 EA F4 - can1 201 [8] 00 00 00 00 00 00 EA F5 - can1 202 [8] 00 00 00 00 00 00 EA F6 - can1 203 [8] 00 00 00 00 00 00 EA F7 - can1 141 [8] 00 00 00 02 03 00 EA 39 - can1 151 [8] 01 00 00 EF 00 3C EB 71 - can1 131 [8] 00 00 00 00 00 00 EC 26 - can1 200 [8] 00 00 00 00 00 00 EB F5 - can1 201 [8] 00 00 00 00 00 00 EB F6 - can1 202 [8] 00 00 00 00 00 00 EB F7 - can1 203 [8] 00 00 00 00 00 00 EB F8 - can1 141 [8] 00 00 00 02 02 00 EB 39 - can1 151 [8] 01 00 00 EF 00 3C EC 72 - can1 131 [8] 00 00 00 00 00 00 ED 27 - can1 200 [8] 00 00 00 00 00 00 EC F6 - can1 201 [8] 00 00 00 00 00 00 EC F7 - can1 202 [8] 00 00 00 00 00 00 EC F8 - can1 203 [8] 00 00 00 00 00 00 EC F9 - can1 141 [8] 00 00 00 02 01 00 EC 39 - can1 151 [8] 01 00 00 EF 00 3C ED 73 - can1 131 [8] 00 00 00 00 00 00 EE 28 - can1 200 [8] 00 00 00 00 00 00 ED F7 - can1 201 [8] 00 00 00 00 00 00 ED F8 - can1 202 [8] 00 00 00 00 00 00 ED F9 - can1 203 [8] 00 00 00 00 00 00 ED FA - can1 141 [8] 00 00 00 02 01 00 ED 3A - can1 151 [8] 01 00 00 EF 00 3C EE 74 - can1 131 [8] 00 00 00 00 00 00 EF 29 - can1 200 [8] 00 00 00 00 00 00 EE F8 - can1 201 [8] 00 00 00 00 00 00 EE F9 - can1 202 [8] 00 00 00 00 00 00 EE FA - can1 203 [8] 00 00 00 00 00 00 EE FB - can1 141 [8] 00 00 00 02 00 00 EE 3A - can1 151 [8] 01 00 00 EF 00 3C EF 75 - can1 131 [8] 00 00 00 00 00 00 F0 2A - can1 200 [8] 00 00 00 00 00 00 EF F9 - can1 201 [8] 00 00 00 00 00 00 EF FA - can1 202 [8] 00 00 00 00 00 00 EF FB - can1 203 [8] 00 00 00 00 00 00 EF FC - can1 141 [8] 00 00 00 02 01 00 EF 3C - can1 151 [8] 01 00 00 EF 00 3C F0 76 - can1 131 [8] 00 00 00 00 00 00 F1 2B - can1 200 [8] 00 00 00 00 00 00 F0 FA - can1 201 [8] 00 00 00 00 00 00 F0 FB - can1 202 [8] 00 00 00 00 00 00 F0 FC - can1 203 [8] 00 00 00 00 00 00 F0 FD - can1 141 [8] 00 00 00 02 02 00 F0 3E - can1 151 [8] 01 00 00 EF 00 3C F1 77 - can1 131 [8] 00 00 00 00 00 00 F2 2C - can1 200 [8] 00 00 00 00 00 00 F1 FB - can1 201 [8] 00 00 00 00 00 00 F1 FC - can1 202 [8] 00 00 00 00 00 00 F1 FD - can1 203 [8] 00 00 00 00 00 00 F1 FE - can1 141 [8] 00 00 00 02 03 00 F1 40 - can1 151 [8] 01 00 00 EF 00 3C F2 78 - can1 131 [8] 00 00 00 00 00 00 F3 2D - can1 200 [8] 00 00 00 00 00 00 F2 FC - can1 201 [8] 00 00 00 00 00 00 F2 FD - can1 202 [8] 00 00 00 00 00 00 F2 FE - can1 203 [8] 00 00 00 00 00 00 F2 FF - can1 141 [8] 00 00 00 02 03 00 F2 41 - can1 151 [8] 01 00 00 EF 00 3C F3 79 - can1 131 [8] 00 00 00 00 00 00 F4 2E - can1 200 [8] 00 00 00 00 00 00 F3 FD - can1 201 [8] 00 00 00 00 00 00 F3 FE - can1 202 [8] 00 00 00 00 00 00 F3 FF - can1 203 [8] 00 00 00 00 00 00 F3 00 - can1 141 [8] 00 00 00 02 04 00 F3 43 - can1 151 [8] 01 00 00 EF 00 3C F4 7A - can1 131 [8] 00 00 00 00 00 00 F5 2F - can1 200 [8] 00 00 00 00 00 00 F4 FE - can1 201 [8] 00 00 00 00 00 00 F4 FF - can1 202 [8] 00 00 00 00 00 00 F4 00 - can1 203 [8] 00 00 00 00 00 00 F4 01 - can1 141 [8] 00 00 00 02 05 00 F4 45 - can1 151 [8] 01 00 00 EF 00 3C F5 7B - can1 131 [8] 00 00 00 00 00 00 F6 30 - can1 200 [8] 00 00 00 00 00 00 F5 FF - can1 201 [8] 00 00 00 00 00 00 F5 00 - can1 202 [8] 00 00 00 00 00 00 F5 01 - can1 203 [8] 00 00 00 00 00 00 F5 02 - can1 141 [8] 00 00 00 02 06 00 F5 47 - can1 151 [8] 01 00 00 EF 00 3C F6 7C - can1 131 [8] 00 00 00 00 00 00 F7 31 - can1 200 [8] 00 00 00 00 00 00 F6 00 - can1 201 [8] 00 00 00 00 00 00 F6 01 - can1 202 [8] 00 00 00 00 00 00 F6 02 - can1 203 [8] 00 00 00 00 00 00 F6 03 - can1 141 [8] 00 00 00 02 07 00 F6 49 - can1 151 [8] 01 00 00 EF 00 3C F7 7D - can1 131 [8] 00 00 00 00 00 00 F8 32 - can1 200 [8] 00 00 00 00 00 00 F7 01 - can1 201 [8] 00 00 00 00 00 00 F7 02 - can1 202 [8] 00 00 00 00 00 00 F7 03 - can1 203 [8] 00 00 00 00 00 00 F7 04 - can1 141 [8] 00 00 00 02 07 00 F7 4A - can1 151 [8] 01 00 00 EF 00 3C F8 7E - can1 131 [8] 00 00 00 00 00 00 F9 33 - can1 200 [8] 00 00 00 00 00 00 F8 02 - can1 201 [8] 00 00 00 00 00 00 F8 03 - can1 202 [8] 00 00 00 00 00 00 F8 04 - can1 203 [8] 00 00 00 00 00 00 F8 05 - can1 141 [8] 00 00 00 02 08 00 F8 4C - can1 151 [8] 01 00 00 EF 00 3C F9 7F - can1 131 [8] 00 00 00 00 00 00 FA 34 - can1 200 [8] 00 00 00 00 00 00 F9 03 - can1 201 [8] 00 00 00 00 00 00 F9 04 - can1 202 [8] 00 00 00 00 00 00 F9 05 - can1 203 [8] 00 00 00 00 00 00 F9 06 - can1 141 [8] 00 00 00 02 09 00 F9 4E - can1 151 [8] 01 00 00 EF 00 3C FA 80 - can1 131 [8] 00 00 00 00 00 00 FB 35 - can1 200 [8] 00 00 00 00 00 00 FA 04 - can1 201 [8] 00 00 00 00 00 00 FA 05 - can1 202 [8] 00 00 00 00 00 00 FA 06 - can1 203 [8] 00 00 00 00 00 00 FA 07 - can1 141 [8] 00 00 00 02 0A 00 FA 50 - can1 151 [8] 01 00 00 EF 00 3C FB 81 - can1 131 [8] 00 00 00 00 00 00 FC 36 - can1 200 [8] 00 00 00 00 00 00 FB 05 - can1 201 [8] 00 00 00 00 00 00 FB 06 - can1 202 [8] 00 00 00 00 00 00 FB 07 - can1 203 [8] 00 00 00 00 00 00 FB 08 - can1 141 [8] 00 00 00 02 0B 00 FB 52 - can1 151 [8] 01 00 00 EF 00 3C FC 82 - can1 131 [8] 00 00 00 00 00 00 FD 37 - can1 200 [8] 00 00 00 00 00 00 FC 06 - can1 201 [8] 00 00 00 00 00 00 FC 07 - can1 202 [8] 00 00 00 00 00 00 FC 08 - can1 203 [8] 00 00 00 00 00 00 FC 09 - can1 141 [8] 00 00 00 02 0B 00 FC 53 - can1 151 [8] 01 00 00 EF 00 3C FD 83 - can1 131 [8] 00 00 00 00 00 00 FE 38 - can1 200 [8] 00 00 00 00 00 00 FD 07 - can1 201 [8] 00 00 00 00 00 00 FD 08 - can1 202 [8] 00 00 00 00 00 00 FD 09 - can1 203 [8] 00 00 00 00 00 00 FD 0A - can1 141 [8] 00 00 00 02 0C 00 FD 55 - can1 151 [8] 01 00 00 EF 00 3C FE 84 - can1 131 [8] 00 00 00 00 00 00 FF 39 - can1 200 [8] 00 00 00 00 00 00 FE 08 - can1 201 [8] 00 00 00 00 00 00 FE 09 - can1 202 [8] 00 00 00 00 00 00 FE 0A - can1 203 [8] 00 00 00 00 00 00 FE 0B - can1 141 [8] 00 00 00 02 0D 00 FE 57 - can1 151 [8] 01 00 00 EF 00 3C FF 85 - can1 131 [8] 00 00 00 00 00 00 00 3A - can1 200 [8] 00 00 00 00 00 00 FF 09 - can1 201 [8] 00 00 00 00 00 00 FF 0A - can1 202 [8] 00 00 00 00 00 00 FF 0B - can1 203 [8] 00 00 00 00 00 00 FF 0C - can1 141 [8] 00 00 00 02 0E 00 FF 59 - can1 151 [8] 01 00 00 EF 00 3C 00 86 - can1 131 [8] 00 00 00 00 00 00 01 3B - can1 200 [8] 00 00 00 00 00 00 00 0A - can1 201 [8] 00 00 00 00 00 00 00 0B - can1 202 [8] 00 00 00 00 00 00 00 0C - can1 203 [8] 00 00 00 00 00 00 00 0D - can1 141 [8] 00 00 00 02 0F 00 00 5B - can1 151 [8] 01 00 00 EF 00 3C 01 87 - can1 131 [8] 00 00 00 00 00 00 02 3C - can1 200 [8] 00 00 00 00 00 00 01 0B - can1 201 [8] 00 00 00 00 00 00 01 0C - can1 202 [8] 00 00 00 00 00 00 01 0D - can1 203 [8] 00 00 00 00 00 00 01 0E - can1 141 [8] 00 00 00 02 10 00 01 5D - can1 151 [8] 01 00 00 EF 00 3C 02 88 - can1 131 [8] 00 00 00 00 00 00 03 3D - can1 200 [8] 00 00 00 00 00 00 02 0C - can1 201 [8] 00 00 00 00 00 00 02 0D - can1 202 [8] 00 00 00 00 00 00 02 0E - can1 203 [8] 00 00 00 00 00 00 02 0F - can1 141 [8] 00 00 00 02 10 00 02 5E - can1 151 [8] 01 00 00 EF 00 3C 03 89 - can1 131 [8] 00 00 00 00 00 00 04 3E - can1 200 [8] 00 00 00 00 00 00 03 0D - can1 201 [8] 00 00 00 00 00 00 03 0E - can1 202 [8] 00 00 00 00 00 00 03 0F - can1 203 [8] 00 00 00 00 00 00 03 10 - can1 141 [8] 00 00 00 02 11 00 03 60 - can1 151 [8] 01 00 00 EF 00 3C 04 8A - can1 131 [8] 00 00 00 00 00 00 05 3F - can1 200 [8] 00 00 00 00 00 00 04 0E - can1 201 [8] 00 00 00 00 00 00 04 0F - can1 202 [8] 00 00 00 00 00 00 04 10 - can1 203 [8] 00 00 00 00 00 00 04 11 - can1 141 [8] 00 00 00 02 12 00 04 62 - can1 151 [8] 01 00 00 EF 00 3C 05 8B - can1 131 [8] 00 00 00 00 00 00 06 40 - can1 200 [8] 00 00 00 00 00 00 05 0F - can1 201 [8] 00 00 00 00 00 00 05 10 - can1 202 [8] 00 00 00 00 00 00 05 11 - can1 203 [8] 00 00 00 00 00 00 05 12 - can1 141 [8] 00 00 00 02 13 00 05 64 - can1 151 [8] 01 00 00 EF 00 3C 06 8C - can1 131 [8] 00 00 00 00 00 00 07 41 - can1 200 [8] 00 00 00 00 00 00 06 10 - can1 201 [8] 00 00 00 00 00 00 06 11 - can1 202 [8] 00 00 00 00 00 00 06 12 - can1 203 [8] 00 00 00 00 00 00 06 13 - can1 141 [8] 00 00 00 02 14 00 06 66 - can1 151 [8] 01 00 00 EF 00 3C 07 8D - can1 131 [8] 00 00 00 00 00 00 08 42 - can1 200 [8] 00 00 00 00 00 00 07 11 - can1 201 [8] 00 00 00 00 00 00 07 12 - can1 202 [8] 00 00 00 00 00 00 07 13 - can1 203 [8] 00 00 00 00 00 00 07 14 - can1 141 [8] 00 00 00 02 14 00 07 67 - can1 151 [8] 01 00 00 EF 00 3C 08 8E - can1 131 [8] 00 00 00 00 00 00 09 43 - can1 200 [8] 00 00 00 00 00 00 08 12 - can1 201 [8] 00 00 00 00 00 00 08 13 - can1 202 [8] 00 00 00 00 00 00 08 14 - can1 203 [8] 00 00 00 00 00 00 08 15 - can1 141 [8] 00 00 00 02 15 00 08 69 - can1 151 [8] 01 00 00 EF 00 3C 09 8F - can1 131 [8] 00 00 00 00 00 00 0A 44 - can1 200 [8] 00 00 00 00 00 00 09 13 - can1 201 [8] 00 00 00 00 00 00 09 14 - can1 202 [8] 00 00 00 00 00 00 09 15 - can1 203 [8] 00 00 00 00 00 00 09 16 - can1 141 [8] 00 00 00 02 16 00 09 6B - can1 151 [8] 01 00 00 EF 00 3C 0A 90 - can1 131 [8] 00 00 00 00 00 00 0B 45 - can1 200 [8] 00 00 00 00 00 00 0A 14 - can1 201 [8] 00 00 00 00 00 00 0A 15 - can1 202 [8] 00 00 00 00 00 00 0A 16 - can1 203 [8] 00 00 00 00 00 00 0A 17 - can1 141 [8] 00 00 00 02 17 00 0A 6D - can1 151 [8] 01 00 00 EF 00 3C 0B 91 - can1 131 [8] 00 00 00 00 00 00 0C 46 - can1 200 [8] 00 00 00 00 00 00 0B 15 - can1 201 [8] 00 00 00 00 00 00 0B 16 - can1 202 [8] 00 00 00 00 00 00 0B 17 - can1 203 [8] 00 00 00 00 00 00 0B 18 - can1 141 [8] 00 00 00 02 18 00 0B 6F - can1 151 [8] 01 00 00 EF 00 3C 0C 92 - can1 131 [8] 00 00 00 00 00 00 0D 47 - can1 200 [8] 00 00 00 00 00 00 0C 16 - can1 201 [8] 00 00 00 00 00 00 0C 17 - can1 202 [8] 00 00 00 00 00 00 0C 18 - can1 203 [8] 00 00 00 00 00 00 0C 19 - can1 141 [8] 00 00 00 02 18 00 0C 70 - can1 151 [8] 01 00 00 EF 00 3C 0D 93 - can1 151 [8] 01 00 00 EF 00 3C 0E 94 - can1 131 [8] 00 00 00 00 00 00 0E 48 - can1 200 [8] 00 00 00 00 00 00 0D 17 - can1 201 [8] 00 00 00 00 00 00 0D 18 - can1 202 [8] 00 00 00 00 00 00 0D 19 - can1 203 [8] 00 00 00 00 00 00 0D 1A - can1 141 [8] 00 00 00 02 19 00 0D 72 - can1 131 [8] 00 00 00 00 00 00 0F 49 - can1 200 [8] 00 00 00 00 00 00 0E 18 - can1 201 [8] 00 00 00 00 00 00 0E 19 - can1 202 [8] 00 00 00 00 00 00 0E 1A - can1 203 [8] 00 00 00 00 00 00 0E 1B - can1 141 [8] 00 00 00 02 1A 00 0E 74 - can1 151 [8] 01 00 00 EF 00 3C 0F 95 - can1 131 [8] 00 00 00 00 00 00 10 4A - can1 200 [8] 00 00 00 00 00 00 0F 19 - can1 201 [8] 00 00 00 00 00 00 0F 1A - can1 202 [8] 00 00 00 00 00 00 0F 1B - can1 203 [8] 00 00 00 00 00 00 0F 1C - can1 141 [8] 00 00 00 02 1B 00 0F 76 - can1 151 [8] 01 00 00 EF 00 3C 10 96 - can1 131 [8] 00 00 00 00 00 00 11 4B - can1 200 [8] 00 00 00 00 00 00 10 1A - can1 201 [8] 00 00 00 00 00 00 10 1B - can1 202 [8] 00 00 00 00 00 00 10 1C - can1 203 [8] 00 00 00 00 00 00 10 1D - can1 141 [8] 00 00 00 02 1C 00 10 78 - can1 151 [8] 01 00 00 EF 00 3C 11 97 - can1 131 [8] 00 00 00 00 00 00 12 4C - can1 200 [8] 00 00 00 00 00 00 11 1B - can1 201 [8] 00 00 00 00 00 00 11 1C - can1 202 [8] 00 00 00 00 00 00 11 1D - can1 203 [8] 00 00 00 00 00 00 11 1E - can1 141 [8] 00 00 00 02 1C 00 11 79 - can1 151 [8] 01 00 00 EF 00 3C 12 98 - can1 131 [8] 00 00 00 00 00 00 13 4D - can1 200 [8] 00 00 00 00 00 00 12 1C - can1 201 [8] 00 00 00 00 00 00 12 1D - can1 202 [8] 00 00 00 00 00 00 12 1E - can1 203 [8] 00 00 00 00 00 00 12 1F - can1 141 [8] 00 00 00 02 1D 00 12 7B - can1 151 [8] 01 00 00 EF 00 3C 13 99 - can1 131 [8] 00 00 00 00 00 00 14 4E - can1 200 [8] 00 00 00 00 00 00 13 1D - can1 201 [8] 00 00 00 00 00 00 13 1E - can1 202 [8] 00 00 00 00 00 00 13 1F - can1 203 [8] 00 00 00 00 00 00 13 20 - can1 141 [8] 00 00 00 02 1E 00 13 7D - can1 151 [8] 01 00 00 EF 00 3C 14 9A - can1 131 [8] 00 00 00 00 00 00 15 4F - can1 200 [8] 00 00 00 00 00 00 14 1E - can1 201 [8] 00 00 00 00 00 00 14 1F - can1 202 [8] 00 00 00 00 00 00 14 20 - can1 203 [8] 00 00 00 00 00 00 14 21 - can1 141 [8] 00 00 00 02 1F 00 14 7F - can1 151 [8] 01 00 00 EF 00 3C 15 9B - can1 131 [8] 00 00 00 00 00 00 16 50 - can1 200 [8] 00 00 00 00 00 00 15 1F - can1 201 [8] 00 00 00 00 00 00 15 20 - can1 202 [8] 00 00 00 00 00 00 15 21 - can1 203 [8] 00 00 00 00 00 00 15 22 - can1 141 [8] 00 00 00 02 20 00 15 81 - can1 151 [8] 01 00 00 EF 00 3C 16 9C - can1 131 [8] 00 00 00 00 00 00 17 51 - can1 200 [8] 00 00 00 00 00 00 16 20 - can1 201 [8] 00 00 00 00 00 00 16 21 - can1 202 [8] 00 00 00 00 00 00 16 22 - can1 203 [8] 00 00 00 00 00 00 16 23 - can1 141 [8] 00 00 00 02 21 00 16 83 - can1 151 [8] 01 00 00 EF 00 3C 17 9D - can1 151 [8] 01 00 00 EF 00 3C 18 9E - can1 131 [8] 00 00 00 00 00 00 18 52 - can1 200 [8] 00 00 00 00 00 00 17 21 - can1 201 [8] 00 00 00 00 00 00 17 22 - can1 202 [8] 00 00 00 00 00 00 17 23 - can1 203 [8] 00 00 00 00 00 00 17 24 - can1 141 [8] 00 00 00 02 21 00 17 84 - can1 131 [8] 00 00 00 00 00 00 19 53 - can1 200 [8] 00 00 00 00 00 00 18 22 - can1 201 [8] 00 00 00 00 00 00 18 23 - can1 202 [8] 00 00 00 00 00 00 18 24 - can1 203 [8] 00 00 00 00 00 00 18 25 - can1 141 [8] 00 00 00 02 22 00 18 86 - can1 151 [8] 01 00 00 EF 00 3C 19 9F - can1 131 [8] 00 00 00 00 00 00 1A 54 - can1 200 [8] 00 00 00 00 00 00 19 23 - can1 201 [8] 00 00 00 00 00 00 19 24 - can1 202 [8] 00 00 00 00 00 00 19 25 - can1 203 [8] 00 00 00 00 00 00 19 26 - can1 141 [8] 00 00 00 02 23 00 19 88 - can1 151 [8] 01 00 00 EF 00 3C 1A A0 - can1 131 [8] 00 00 00 00 00 00 1B 55 - can1 200 [8] 00 00 00 00 00 00 1A 24 - can1 201 [8] 00 00 00 00 00 00 1A 25 - can1 202 [8] 00 00 00 00 00 00 1A 26 - can1 203 [8] 00 00 00 00 00 00 1A 27 - can1 141 [8] 00 00 00 02 24 00 1A 8A - can1 151 [8] 01 00 00 EF 00 3C 1B A1 - can1 131 [8] 00 00 00 00 00 00 1C 56 - can1 200 [8] 00 00 00 00 00 00 1B 25 - can1 201 [8] 00 00 00 00 00 00 1B 26 - can1 202 [8] 00 00 00 00 00 00 1B 27 - can1 203 [8] 00 00 00 00 00 00 1B 28 - can1 141 [8] 00 00 00 02 25 00 1B 8C - can1 151 [8] 01 00 00 EF 00 3C 1C A2 - can1 131 [8] 00 00 00 00 00 00 1D 57 - can1 200 [8] 00 00 00 00 00 00 1C 26 - can1 201 [8] 00 00 00 00 00 00 1C 27 - can1 202 [8] 00 00 00 00 00 00 1C 28 - can1 203 [8] 00 00 00 00 00 00 1C 29 - can1 141 [8] 00 00 00 02 25 00 1C 8D - can1 151 [8] 01 00 00 EF 00 3C 1D A3 - can1 131 [8] 00 00 00 00 00 00 1E 58 - can1 200 [8] 00 00 00 00 00 00 1D 27 - can1 201 [8] 00 00 00 00 00 00 1D 28 - can1 202 [8] 00 00 00 00 00 00 1D 29 - can1 203 [8] 00 00 00 00 00 00 1D 2A - can1 141 [8] 00 00 00 02 26 00 1D 8F - can1 151 [8] 01 00 00 EF 00 3C 1E A4 - can1 131 [8] 00 00 00 00 00 00 1F 59 - can1 200 [8] 00 00 00 00 00 00 1E 28 - can1 201 [8] 00 00 00 00 00 00 1E 29 - can1 202 [8] 00 00 00 00 00 00 1E 2A - can1 203 [8] 00 00 00 00 00 00 1E 2B - can1 141 [8] 00 00 00 02 27 00 1E 91 - can1 151 [8] 01 00 00 EF 00 3C 1F A5 - can1 131 [8] 00 00 00 00 00 00 20 5A - can1 200 [8] 00 00 00 00 00 00 1F 29 - can1 201 [8] 00 00 00 00 00 00 1F 2A - can1 202 [8] 00 00 00 00 00 00 1F 2B - can1 203 [8] 00 00 00 00 00 00 1F 2C - can1 141 [8] 00 00 00 02 28 00 1F 93 - can1 151 [8] 01 00 00 EF 00 3C 20 A6 - can1 131 [8] 00 00 00 00 00 00 21 5B - can1 200 [8] 00 00 00 00 00 00 20 2A - can1 201 [8] 00 00 00 00 00 00 20 2B - can1 202 [8] 00 00 00 00 00 00 20 2C - can1 203 [8] 00 00 00 00 00 00 20 2D - can1 141 [8] 00 00 00 02 29 00 20 95 - can1 151 [8] 01 00 00 EF 00 3C 21 A7 - can1 151 [8] 01 00 00 EF 00 3C 22 A8 - can1 131 [8] 00 00 00 00 00 00 22 5C - can1 200 [8] 00 00 00 00 00 00 21 2B - can1 201 [8] 00 00 00 00 00 00 21 2C - can1 202 [8] 00 00 00 00 00 00 21 2D - can1 203 [8] 00 00 00 00 00 00 21 2E - can1 141 [8] 00 00 00 02 29 00 21 96 - can1 131 [8] 00 00 00 00 00 00 23 5D - can1 200 [8] 00 00 00 00 00 00 22 2C - can1 201 [8] 00 00 00 00 00 00 22 2D - can1 202 [8] 00 00 00 00 00 00 22 2E - can1 203 [8] 00 00 00 00 00 00 22 2F - can1 141 [8] 00 00 00 02 2A 00 22 98 - can1 151 [8] 01 00 00 EF 00 3C 23 A9 - can1 131 [8] 00 00 00 00 00 00 24 5E - can1 200 [8] 00 00 00 00 00 00 23 2D - can1 201 [8] 00 00 00 00 00 00 23 2E - can1 202 [8] 00 00 00 00 00 00 23 2F - can1 203 [8] 00 00 00 00 00 00 23 30 - can1 141 [8] 00 00 00 02 2B 00 23 9A diff --git a/scout_sdk/docs/misc/check_endianness.md b/scout_sdk/docs/misc/check_endianness.md deleted file mode 100644 index 7f8545b..0000000 --- a/scout_sdk/docs/misc/check_endianness.md +++ /dev/null @@ -1,36 +0,0 @@ -On a Big Endian-System (Solaris on SPARC) - -``` -$ echo -n I | od -to2 | head -n1 | cut -f2 -d" " | cut -c6 -0 -``` -On a little endian system (Linux on x86) -``` -$ echo -n I | od -to2 | head -n1 | cut -f2 -d" " | cut -c6 -1 -``` -The solution above is clever and works great for Linux *86 and Solaris Sparc. - -I needed a shell-only (no Perl) solution that also worked on AIX/Power and HPUX/Itanium. Unfortunately the last two don't play nice: AIX reports "6" and HPUX gives an empty line. - -Using your solution, I was able to craft something that worked on all these Unix systems: -``` -$ echo I | tr -d [:space:] | od -to2 | head -n1 | awk '{print $2}' | cut -c6 -``` -Regarding the Python solution someone posted, it does not work in Jython because the JVM treats everything as Big. If anyone can get it to work in Jython, please post! - -Also, I found this, which explains the endianness of various platforms. Some hardware can operate in either mode depending on what the O/S selects: http://labs.hoffmanlabs.com/node/544 - -If you're going to use awk this line can be simplified to: -``` -echo -n I | od -to2 | awk '{ print substr($2,6,1); exit}' -``` -For small Linux boxes that don't have 'od' (say OpenWrt) then try 'hexdump': -``` -echo -n I | hexdump -o | awk '{ print substr($2,6,1); exit}' -``` - -Reference: - -* [1] https://serverfault.com/questions/163487/how-to-tell-if-a-linux-system-is-big-endian-or-little-endian -* [2] https://wiki.rdu.im/_pages/Knowledge-Base/Computing/Computing.html \ No newline at end of file diff --git a/scout_sdk/docs/misc/commands.md b/scout_sdk/docs/misc/commands.md deleted file mode 100644 index 42620c3..0000000 --- a/scout_sdk/docs/misc/commands.md +++ /dev/null @@ -1,55 +0,0 @@ -# Commands - -## Create gif animation using "imagemagick" - -``` -$ convert -delay 120 -loop 0 *.png animated.gif -``` - -## Get statistics of the code base - -``` -$ sudo apt install cloc -$ cd ~/Workspace/librav/src -$ cloc --exclude-dir=cmake,lcmtypes,third_party . -``` - -## Create a pair of VSP’s - -``` -$ socat -d -d pty,raw,echo=0 pty,raw,echo=0 -``` - -``` -$ cat nmea_test.txt > /dev/pts/6 -``` - -## git subtree - -Adding the sub-project as a remote -``` -$ git remote add -f [remote-name] [remote-url] -$ git subtree add --prefix [sub-project-name] [remote-name] [branch-name] --squash -``` - -Update the sub-project -``` -$ git fetch [remote-name] [branch-name] -$ git subtree pull --prefix [sub-project-name] [remote-name] [branch-name] --squash -``` - -Push to remote -``` -$ git subtree push --prefix=[sub-project-name] [remote-name] [branch-name] -``` - -Firmware branch update -``` -$ git fetch fw_origin pios_pixcar -$ git subtree pull --prefix firmware fw_origin pios_pixcar --squash -``` - -## Reference - -* [Git subtree: the alternative to Git submodule](https://www.atlassian.com/blog/git/alternatives-to-git-submodule-git-subtree) -* [Virtual serial port: socat](https://justcheckingonall.wordpress.com/2009/06/09/howto-vsp-socat/) \ No newline at end of file diff --git a/scout_sdk/docs/misc/jetson_tx2_can.md b/scout_sdk/docs/misc/jetson_tx2_can.md deleted file mode 100644 index 96b9c1d..0000000 --- a/scout_sdk/docs/misc/jetson_tx2_can.md +++ /dev/null @@ -1,12 +0,0 @@ -# Enable CAN on Jetson TX2 - -``` -$ sudo modprobe can -$ sudo modprobe mttcan -$ sudo ip link set can0 type can bitrate 500000 -$ sudo ip link set up can0 -``` - -Reference: - -* https://devtalk.nvidia.com/default/topic/1006762/jetson-tx2/how-can-i-use-can-bus-in-tx2-/post/5166583/#5166583 diff --git a/scout_sdk/docs/misc/release_checklist.md b/scout_sdk/docs/misc/release_checklist.md deleted file mode 100644 index eb1f841..0000000 --- a/scout_sdk/docs/misc/release_checklist.md +++ /dev/null @@ -1 +0,0 @@ -* Disable tests to keep minimal dependency by default \ No newline at end of file diff --git a/scout_sdk/docs/misc/scout_interface.png b/scout_sdk/docs/misc/scout_interface.png deleted file mode 100755 index 4c23fc4..0000000 Binary files a/scout_sdk/docs/misc/scout_interface.png and /dev/null differ diff --git a/scout_sdk/docs/misc/scout_monitor_tool.gif b/scout_sdk/docs/misc/scout_monitor_tool.gif deleted file mode 100644 index 886aab3..0000000 Binary files a/scout_sdk/docs/misc/scout_monitor_tool.gif and /dev/null differ diff --git a/scout_sdk/docs/misc/test_can_msg.txt b/scout_sdk/docs/misc/test_can_msg.txt deleted file mode 100644 index 1287944..0000000 --- a/scout_sdk/docs/misc/test_can_msg.txt +++ /dev/null @@ -1,7 +0,0 @@ - can1 131 [8] 00 00 00 00 00 00 E4 1E - can1 141 [8] 00 00 00 02 0E 00 E3 3D - can1 151 [8] 01 00 00 EF 00 3C E5 6B - can1 200 [8] 00 00 00 00 00 00 EA F4 - can1 201 [8] 00 00 00 00 00 00 EA F5 - can1 202 [8] 00 00 00 00 00 00 EA F6 - can1 203 [8] 00 00 00 00 00 00 EA F7 \ No newline at end of file diff --git a/scout_sdk/include/scout_sdk/async_io/async_can.hpp b/scout_sdk/include/scout_sdk/async_io/async_can.hpp deleted file mode 100644 index 6a6de15..0000000 --- a/scout_sdk/include/scout_sdk/async_io/async_can.hpp +++ /dev/null @@ -1,138 +0,0 @@ -/* - * async_can.hpp - * - * Created on: Jun 10, 2019 02:16 - * Description: code based on uavcan and libmavconn - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -/* - * Copyright (c) 2016 UAVCAN Team - * - * Distributed under the MIT License, available in the file LICENSE. - * - */ - -/* - * libmavconn - * Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved. - * - * This file is part of the mavros package and subject to the license terms - * in the top-level LICENSE file of the mavros repository. - * https://github.com/mavlink/mavros/tree/master/LICENSE.md - */ - -#ifndef ASYNC_CAN_HPP -#define ASYNC_CAN_HPP - -#include - -#include -#include -#include -#include -#include -#include -#include - -#ifndef ASIO_ENABLE_OLD_SERVICES -#define ASIO_ENABLE_OLD_SERVICES -#endif - -#ifndef ASIO_HAS_POSIX_STREAM_DESCRIPTOR -#define ASIO_HAS_POSIX_STREAM_DESCRIPTOR -#endif - -#include "asio.hpp" -#include "asio/posix/basic_stream_descriptor.hpp" - -// #include "async_io/device_error.hpp" -// #include "async_io/msg_buffer.hpp" - -namespace wescore -{ -using steady_clock = std::chrono::steady_clock; -using lock_guard = std::lock_guard; - -class ASyncCAN : public std::enable_shared_from_this -{ -public: - static constexpr auto DEFAULT_DEVICE = "can1"; - static constexpr std::size_t MAX_TXQ_SIZE = 1000; - - using ReceiveCallback = std::function; - using ClosedCallback = std::function; - - using Ptr = std::shared_ptr; - using ConstPtr = std::shared_ptr; - using WeakPtr = std::weak_ptr; - - struct IOStat - { - std::size_t tx_total_frames; // total bytes transferred - std::size_t rx_total_frames; // total bytes received - float tx_speed; // current transfer speed [Frames/s] - float rx_speed; // current receive speed [Frames/s] - }; - -public: - ASyncCAN(std::string device = DEFAULT_DEVICE); - ~ASyncCAN(); - - // do not allow copy - ASyncCAN(const ASyncCAN &other) = delete; - ASyncCAN &operator=(const ASyncCAN &other) = delete; - - std::size_t conn_id; - int can_fd_; - - static Ptr open_url(std::string url); - void open(std::string device); - void close(); - - void set_receive_callback(ReceiveCallback cb) { receive_cb = cb; } - void set_closed_callback(ClosedCallback cb) { port_closed_cb = cb; } - - inline bool is_open() { return true; } - IOStat get_iostat(); - - void send_frame(const can_frame &tx_frame); - -private: - // monotonic counter (increment only) - bool can_interface_opened_ = false; - static std::atomic conn_id_counter; - - struct can_frame rcv_frame; - - // port statistics - std::atomic tx_total_frames; - std::atomic rx_total_frames; - std::size_t last_tx_total_frames; - std::size_t last_rx_total_frames; - std::chrono::time_point last_iostat; - std::recursive_mutex iostat_mutex; - - // io service - asio::io_service io_service; - asio::posix::basic_stream_descriptor<> stream; - std::thread io_thread; - - // callback objects - ClosedCallback port_closed_cb; - ReceiveCallback receive_cb; - - // internal processing - void do_read(struct can_frame &rec_frame, asio::posix::basic_stream_descriptor<> &stream); - void do_write(bool check_tx_state); - - void call_receive_callback(can_frame *rx_frame); - void default_receive_callback(can_frame *rx_frame); - - void iostat_tx_add(std::size_t bytes); - void iostat_rx_add(std::size_t bytes); -}; -} // namespace wescore - -#endif /* ASYNC_CAN_HPP */ diff --git a/scout_sdk/include/scout_sdk/async_io/async_serial.hpp b/scout_sdk/include/scout_sdk/async_io/async_serial.hpp deleted file mode 100644 index 3433bb7..0000000 --- a/scout_sdk/include/scout_sdk/async_io/async_serial.hpp +++ /dev/null @@ -1,153 +0,0 @@ -/* - * async_serial.hpp - * - * Created on: Nov 23, 2018 22:18 - * Description: asynchronous serial communication using asio - * adapted from code in libmavconn - * - * Main changes: 1. Removed dependency on Boost (asio standalone - * and C++ STL only) - * 2. Removed dependency on console-bridge - * 3. Removed mavlink related code - * 4. Removed UDP/TCP related code - * - * Author: Vladimir Ermakov - * Ruixiang Du - * - * Additioanl reference: - * [1] http://www.webalice.it/fede.tft/serial_port/serial_port.html - * - */ - -/* - * libmavconn - * Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved. - * - * This file is part of the mavros package and subject to the license terms - * in the top-level LICENSE file of the mavros repository. - * https://github.com/mavlink/mavros/tree/master/LICENSE.md - */ - -#ifndef ASYNC_SERIAL_HPP -#define ASYNC_SERIAL_HPP - -#include -#include -#include -#include -#include -#include - -#ifndef ASIO_ENABLE_OLD_SERVICES -#define ASIO_ENABLE_OLD_SERVICES -#endif - -#ifndef ASIO_HAS_POSIX_STREAM_DESCRIPTOR -#define ASIO_HAS_POSIX_STREAM_DESCRIPTOR -#endif - -#include "asio.hpp" - -#include "scout_sdk/async_io/device_error.hpp" -#include "scout_sdk/async_io/msg_buffer.hpp" - -namespace wescore -{ -using steady_clock = std::chrono::steady_clock; -using lock_guard = std::lock_guard; - -/// Note: instance of ASyncSerial MUST be managed by a std::shared_ptr -class ASyncSerial : public std::enable_shared_from_this -{ -public: - static constexpr auto DEFAULT_DEVICE = "/dev/ttyUSB0"; - static constexpr auto DEFAULT_BAUDRATE = 115200; - static constexpr std::size_t MAX_TXQ_SIZE = 1000; - - /** - * @param buf: pointer to a buffer - * @param bufsize: size of the buffer (the value should be constant in most cases) - * @param bytes_received: number of bytes received inside the buffer - */ - using ReceiveCallback = std::function; - using ClosedCallback = std::function; - - using Ptr = std::shared_ptr; - using ConstPtr = std::shared_ptr; - using WeakPtr = std::weak_ptr; - - struct IOStat - { - std::size_t tx_total_bytes; //!< total bytes transferred - std::size_t rx_total_bytes; //!< total bytes received - float tx_speed; //!< current transfer speed [B/s] - float rx_speed; //!< current receive speed [B/s] - }; - -public: - ASyncSerial(std::string device = DEFAULT_DEVICE, unsigned baudrate = DEFAULT_BAUDRATE, bool hwflow = false); - ~ASyncSerial(); - - // do not allow copy - ASyncSerial(const ASyncSerial &other) = delete; - ASyncSerial &operator=(const ASyncSerial &other) = delete; - - std::size_t conn_id; - - static Ptr open_url(std::string url); - void open(std::string device = "", unsigned baudrate = 0, bool hwflow = false); - void close(); - - void set_baud(unsigned baudrate) { serial_dev_.set_option(asio::serial_port_base::baud_rate(baudrate)); } - - void send_bytes(const uint8_t *bytes, size_t length); - void set_receive_callback(ReceiveCallback cb) { receive_cb = cb; } - void set_closed_callback(ClosedCallback cb) { port_closed_cb = cb; } - - inline bool is_open() { return serial_dev_.is_open(); } - IOStat get_iostat(); - -private: - // monotonic counter (increment only) - static std::atomic conn_id_counter; - - // port properties - std::string device_ = DEFAULT_DEVICE; - unsigned baudrate_ = DEFAULT_BAUDRATE; - bool hwflow_ = false; - - // port statistics - std::atomic tx_total_bytes; - std::atomic rx_total_bytes; - std::size_t last_tx_total_bytes; - std::size_t last_rx_total_bytes; - std::chrono::time_point last_iostat; - std::recursive_mutex iostat_mutex; - - // io service - asio::io_service io_service; - std::thread io_thread; - asio::serial_port serial_dev_; - - std::atomic tx_in_progress; - std::deque tx_q; - std::array rx_buf; - std::recursive_mutex mutex; - - // callback objects - ClosedCallback port_closed_cb; - ReceiveCallback receive_cb; - - // internal processing - void do_read(); - void do_write(bool check_tx_state); - - void call_receive_callback(uint8_t *buf, const std::size_t bufsize, std::size_t bytes_received); - void default_receive_callback(uint8_t *buf, const std::size_t bufsize, std::size_t bytes_received); - - void iostat_tx_add(std::size_t bytes); - void iostat_rx_add(std::size_t bytes); -}; -} // namespace wescore - -#endif /* ASYNC_SERIAL_HPP */ diff --git a/scout_sdk/include/scout_sdk/async_io/device_error.hpp b/scout_sdk/include/scout_sdk/async_io/device_error.hpp deleted file mode 100644 index 4362a96..0000000 --- a/scout_sdk/include/scout_sdk/async_io/device_error.hpp +++ /dev/null @@ -1,57 +0,0 @@ -/** - * @brief MAVConn device error class - * @file device_error.hpp - * @author Vladimir Ermakov - */ -/* - * libmavconn - * Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved. - * - * This file is part of the mavros package and subject to the license terms - * in the top-level LICENSE file of the mavros repository. - * https://github.com/mavlink/mavros/tree/master/LICENSE.md - */ - -#ifndef DEVICE_ERROR_HPP -#define DEVICE_ERROR_HPP - -#include -#include -#include - -namespace wescore -{ -class DeviceError : public std::runtime_error -{ - public: - template - DeviceError(const char *module, T msg) : std::runtime_error(make_message(module, msg)) - { - } - - template - static std::string make_message(const char *module, T msg) - { - std::ostringstream ss; - ss << "DeviceError:" << module << ":" << msg_to_string(msg); - return ss.str(); - } - - static std::string msg_to_string(const char *description) - { - return description; - } - - static std::string msg_to_string(int errnum) - { - return std::strerror(errnum); - } - - static std::string msg_to_string(std::system_error &err) - { - return err.what(); - } -}; -} // namespace mavconn - -#endif /* DEVICE_ERROR_HPP */ diff --git a/scout_sdk/include/scout_sdk/async_io/msg_buffer.hpp b/scout_sdk/include/scout_sdk/async_io/msg_buffer.hpp deleted file mode 100644 index 4caab51..0000000 --- a/scout_sdk/include/scout_sdk/async_io/msg_buffer.hpp +++ /dev/null @@ -1,69 +0,0 @@ -/** - * @brief MAVConn message buffer class (internal) - * @file msgbuffer.hpp - * @author Vladimir Ermakov - */ -/* - * libmavconn - * Copyright 2014,2015,2016 Vladimir Ermakov, All rights reserved. - * - * This file is part of the mavros package and subject to the license terms - * in the top-level LICENSE file of the mavros repository. - * https://github.com/mavlink/mavros/tree/master/LICENSE.md - */ - -#pragma once - -#include -#include -#include -#include - -namespace wescore -{ - -/** - * @brief Message buffer for internal use in libmavconn - */ -struct MsgBuffer -{ - //! Maximum buffer size with padding for CRC bytes (280 + padding) - static constexpr ssize_t MAX_PACKET_LEN = 255; - static constexpr ssize_t MAX_SIZE = MAX_PACKET_LEN + 16; - uint8_t data[MAX_SIZE]; - ssize_t len; - ssize_t pos; - - MsgBuffer() : pos(0), - len(0) - { - } - - /** - * @brief Buffer constructor for send_bytes() - * @param[in] nbytes should be less than MAX_SIZE - */ - MsgBuffer(const uint8_t *bytes, ssize_t nbytes) : pos(0), - len(nbytes) - { - assert(0 < nbytes && nbytes < MAX_SIZE); - std::memcpy(data, bytes, nbytes); - } - - virtual ~MsgBuffer() - { - pos = 0; - len = 0; - } - - uint8_t *dpos() - { - return data + pos; - } - - ssize_t nbytes() - { - return len - pos; - } -}; -} // namespace wescore diff --git a/scout_sdk/include/scout_sdk/scout_base.hpp b/scout_sdk/include/scout_sdk/scout_base.hpp deleted file mode 100644 index 528eca2..0000000 --- a/scout_sdk/include/scout_sdk/scout_base.hpp +++ /dev/null @@ -1,110 +0,0 @@ -/* - * scout_base.hpp - * - * Created on: Jun 04, 2019 01:22 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#ifndef SCOUT_BASE_HPP -#define SCOUT_BASE_HPP - -#include -#include -#include -#include -#include - -#include "scout_sdk/async_io/async_can.hpp" -#include "scout_sdk/async_io/async_serial.hpp" - -#include "scout_sdk/scout_protocol/scout_protocol.h" -#include "scout_sdk/scout_protocol/scout_can_parser.h" -#include "scout_sdk/scout_protocol/scout_uart_parser.h" - -#include "scout_sdk/scout_types.hpp" - -namespace wescore -{ -class ScoutBase -{ -public: - ScoutBase() = default; - ~ScoutBase(); - - // do not allow copy - ScoutBase(const ScoutBase &scout) = delete; - ScoutBase &operator=(const ScoutBase &scout) = delete; - -public: - // connect to roboot from CAN or serial - void Connect(std::string dev_name, int32_t baud_rate = 0); - - // disconnect from roboot, only valid for serial port - void Disconnect(); - - // cmd thread runs at 100Hz (10ms) by default - void SetCmdThreadPeriodMs(int32_t period_ms) { cmd_thread_period_ms_ = period_ms; }; - - // motion control - void SetMotionCommand(double linear_vel, double angular_vel, - ScoutMotionCmd::FaultClearFlag fault_clr_flag = ScoutMotionCmd::FaultClearFlag::NO_FAULT); - - // light control - void SetLightCommand(ScoutLightCmd cmd); - void DisableLightCmdControl(); - - // get robot state - ScoutState GetScoutState(); - -private: - // hardware communication interface - std::shared_ptr can_if_; - std::shared_ptr serial_if_; - - // CAN priority higher than serial if both connected - bool can_connected_ = false; - bool serial_connected_ = false; - - // serial port related variables - uint8_t tx_cmd_len_; - uint8_t tx_buffer_[SCOUT_CMD_BUF_LEN]; - - // cmd/status update related variables - std::thread cmd_thread_; - std::mutex scout_state_mutex_; - std::mutex motion_cmd_mutex_; - std::mutex light_cmd_mutex_; - - ScoutState scout_state_; - ScoutMotionCmd current_motion_cmd_; - ScoutLightCmd current_light_cmd_; - - int32_t cmd_thread_period_ms_ = 10; - bool cmd_thread_started_ = false; - - bool light_ctrl_enabled_ = false; - bool light_ctrl_requested_ = false; - - // internal functions - void ConfigureCANBus(const std::string &can_if_name = "can1"); - void ConfigureSerial(const std::string uart_name = "/dev/ttyUSB0", int32_t baud_rate = 115200); - - void StartCmdThread(); - void ControlLoop(int32_t period_ms); - - void SendMotionCmd(uint8_t count); - void SendLightCmd(uint8_t count); - - void ParseCANFrame(can_frame *rx_frame); - void ParseUARTBuffer(uint8_t *buf, const size_t bufsize, size_t bytes_received); - - void NewStatusMsgReceivedCallback(const ScoutStatusMessage &msg); - -public: - static void UpdateScoutState(const ScoutStatusMessage &status_msg, ScoutState &state); -}; -} // namespace wescore - -#endif /* SCOUT_BASE_HPP */ diff --git a/scout_sdk/include/scout_sdk/scout_protocol/scout_can_parser.h b/scout_sdk/include/scout_sdk/scout_protocol/scout_can_parser.h deleted file mode 100644 index 962cc1e..0000000 --- a/scout_sdk/include/scout_sdk/scout_protocol/scout_can_parser.h +++ /dev/null @@ -1,48 +0,0 @@ -/* - * scout_can_parser.h - * - * Created on: Aug 31, 2019 04:23 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#ifndef SCOUT_CAN_PARSER_H -#define SCOUT_CAN_PARSER_H - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -#include "scout_sdk/scout_protocol/scout_protocol.h" - -#ifdef __linux__ -#include -#else -struct can_frame -{ - uint32_t can_id; - uint8_t can_dlc; - uint8_t data[8]__attribute__((aligned(8))); -}; -#endif - -bool DecodeScoutStatusMsgFromCAN(const struct can_frame *rx_frame, ScoutStatusMessage *msg); -bool DecodeScoutControlMsgFromCAN(const struct can_frame *rx_frame, ScoutControlMessage *msg); - -void EncodeScoutStatusMsgToCAN(const ScoutStatusMessage *msg, struct can_frame *tx_frame); -void EncodeScoutControlMsgToCAN(const ScoutControlMessage *msg, struct can_frame *tx_frame); - -void EncodeScoutMotionControlMsgToCAN(const MotionControlMessage *msg, struct can_frame *tx_frame); -void EncodeScoutLightControlMsgToCAN(const LightControlMessage *msg, struct can_frame *tx_frame); - -uint8_t CalcScoutCANChecksum(uint16_t id, uint8_t *data, uint8_t dlc); - -#ifdef __cplusplus -} -#endif - -#endif /* SCOUT_CAN_PARSER_H */ diff --git a/scout_sdk/include/scout_sdk/scout_protocol/scout_protocol.h b/scout_sdk/include/scout_sdk/scout_protocol/scout_protocol.h deleted file mode 100644 index fca7228..0000000 --- a/scout_sdk/include/scout_sdk/scout_protocol/scout_protocol.h +++ /dev/null @@ -1,283 +0,0 @@ -/* - * scout_protocol.h - * - * Created on: Aug 07, 2019 21:49 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#ifndef SCOUT_PROTOCOL_H -#define SCOUT_PROTOCOL_H - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#define SCOUT_CMD_BUF_LEN 32 -#define SCOUT_STATUS_BUF_LEN 32 -#define SCOUT_FRAME_SIZE 13 - -#define SCOUT_MOTOR1_ID ((uint8_t)0x00) -#define SCOUT_MOTOR2_ID ((uint8_t)0x01) -#define SCOUT_MOTOR3_ID ((uint8_t)0x02) -#define SCOUT_MOTOR4_ID ((uint8_t)0x03) - -// UART Definitions -#define UART_FRAME_SYSTEM_STATUS_ID ((uint8_t)0x01) -#define UART_FRAME_MOTION_STATUS_ID ((uint8_t)0x02) -#define UART_FRAME_MOTOR1_DRIVER_STATUS_ID ((uint8_t)0x03) -#define UART_FRAME_MOTOR2_DRIVER_STATUS_ID ((uint8_t)0x04) -#define UART_FRAME_MOTOR3_DRIVER_STATUS_ID ((uint8_t)0x05) -#define UART_FRAME_MOTOR4_DRIVER_STATUS_ID ((uint8_t)0x06) -#define UART_FRAME_LIGHT_STATUS_ID ((uint8_t)0x07) - -#define UART_FRAME_MOTION_CONTROL_ID ((uint8_t)0x01) -#define UART_FRAME_LIGHT_CONTROL_ID ((uint8_t)0x02) - -// CAN Definitions -#define CAN_MSG_MOTION_CONTROL_CMD_ID ((uint32_t)0x130) -#define CAN_MSG_MOTION_CONTROL_STATUS_ID ((uint32_t)0x131) -#define CAN_MSG_LIGHT_CONTROL_CMD_ID ((uint32_t)0x140) -#define CAN_MSG_LIGHT_CONTROL_STATUS_ID ((uint32_t)0x141) -#define CAN_MSG_SYSTEM_STATUS_STATUS_ID ((uint32_t)0x151) -#define CAN_MSG_MOTOR1_DRIVER_STATUS_ID ((uint32_t)0x200) -#define CAN_MSG_MOTOR2_DRIVER_STATUS_ID ((uint32_t)0x201) -#define CAN_MSG_MOTOR3_DRIVER_STATUS_ID ((uint32_t)0x202) -#define CAN_MSG_MOTOR4_DRIVER_STATUS_ID ((uint32_t)0x203) - -/*--------------------- Control/State Constants ------------------------*/ - -// Motion Control -#define CTRL_MODE_REMOTE ((uint8_t)0x00) -#define CTRL_MODE_CMD_CAN ((uint8_t)0x01) -#define CTRL_MODE_CMD_UART ((uint8_t)0x02) -#define CTRL_MODE_COMMANDED ((uint8_t)0x03) - -#define FAULT_CLR_NONE ((uint8_t)0x00) -#define FAULT_CLR_BAT_UNDER_VOL ((uint8_t)0x01) -#define FAULT_CLR_BAT_OVER_VOL ((uint8_t)0x02) -#define FAULT_CLR_MOTOR1_COMM ((uint8_t)0x03) -#define FAULT_CLR_MOTOR2_COMM ((uint8_t)0x04) -#define FAULT_CLR_MOTOR3_COMM ((uint8_t)0x05) -#define FAULT_CLR_MOTOR4_COMM ((uint8_t)0x06) -#define FAULT_CLR_MOTOR_DRV_OVERHEAT ((uint8_t)0x07) -#define FAULT_CLR_MOTOR_OVERCURRENT ((uint8_t)0x08) - -// Light Control -#define LIGHT_DISABLE_CTRL ((uint8_t)0x00) -#define LIGHT_ENABLE_CTRL ((uint8_t)0x01) - -#define LIGHT_MODE_CONST_OFF ((uint8_t)0x00) -#define LIGHT_MODE_CONST_ON ((uint8_t)0x01) -#define LIGHT_MODE_BREATH ((uint8_t)0x02) -#define LIGHT_MODE_CUSTOM ((uint8_t)0x03) - -// System Status Feedback -#define BASE_STATE_NORMAL ((uint8_t)0x00) -#define BASE_STATE_ESTOP ((uint8_t)0x01) -#define BASE_STATE_EXCEPTION ((uint8_t)0x02) - -#define FAULT_CAN_CHECKSUM_ERROR ((uint16_t)0x0100) -#define FAULT_MOTOR_DRV_OVERHEAT_W ((uint16_t)0x0200) -#define FAULT_MOTOR_OVERCURRENT_W ((uint16_t)0x0400) -#define FAULT_BAT_UNDER_VOL_W ((uint16_t)0x0800) -#define FAULT_HIGH_BYTE_RESERVED1 ((uint16_t)0x1000) -#define FAULT_HIGH_BYTE_RESERVED2 ((uint16_t)0x2000) -#define FAULT_HIGH_BYTE_RESERVED3 ((uint16_t)0x4000) -#define FAULT_HIGH_BYTE_RESERVED4 ((uint16_t)0x8000) - -#define FAULT_BAT_UNDER_VOL_F ((uint16_t)0x0001) -#define FAULT_BAT_OVER_VOL_F ((uint16_t)0x0002) -#define FAULT_MOTOR1_COMM_F ((uint16_t)0x0004) -#define FAULT_MOTOR2_COMM_F ((uint16_t)0x0008) -#define FAULT_MOTOR3_COMM_F ((uint16_t)0x0010) -#define FAULT_MOTOR4_COMM_F ((uint16_t)0x0020) -#define FAULT_MOTOR_DRV_OVERHEAT_F ((uint16_t)0x0040) -#define FAULT_MOTOR_OVERCURRENT_F ((uint16_t)0x0080) - -/*-------------------- Control/Feedback Messages -----------------------*/ - -/* No padding in the struct */ -// reference: https://stackoverflow.com/questions/3318410/pragma-pack-effect -#pragma pack(push, 1) - -// Note: id could be different for UART and CAN protocol - -// Motion Control -typedef struct { - union - { - struct - { - uint8_t control_mode; - uint8_t fault_clear_flag; - int8_t linear_velocity_cmd; - int8_t angular_velocity_cmd; - uint8_t reserved0; - uint8_t reserved1; - uint8_t count; - uint8_t checksum; - } cmd; - uint8_t raw[8]; - } data; -} MotionControlMessage; - -typedef struct { - union - { - struct - { - struct - { - uint8_t high_byte; - uint8_t low_byte; - } linear_velocity; - struct - { - uint8_t high_byte; - uint8_t low_byte; - } angular_velocity; - uint8_t reserved0; - uint8_t reserved1; - uint8_t count; - uint8_t checksum; - } status; - uint8_t raw[8]; - } data; -} MotionStatusMessage; - -// System Status Feedback -typedef struct { - union - { - struct - { - uint8_t base_state; - uint8_t control_mode; - struct - { - uint8_t high_byte; - uint8_t low_byte; - } battery_voltage; - struct - { - uint8_t high_byte; - uint8_t low_byte; - } fault_code; - uint8_t count; - uint8_t checksum; - } status; - uint8_t raw[8]; - } data; -} SystemStatusMessage; - -// Light Control -typedef struct { - union - { - struct - { - uint8_t light_ctrl_enable; - uint8_t front_light_mode; - uint8_t front_light_custom; - uint8_t rear_light_mode; - uint8_t rear_light_custom; - uint8_t reserved0; - uint8_t count; - uint8_t checksum; - } cmd; - uint8_t raw[8]; - } data; -} LightControlMessage; - -typedef struct { - union - { - struct - { - uint8_t light_ctrl_enable; - uint8_t front_light_mode; - uint8_t front_light_custom; - uint8_t rear_light_mode; - uint8_t rear_light_custom; - uint8_t reserved0; - uint8_t count; - uint8_t checksum; - } status; - uint8_t raw[8]; - } data; -} LightStatusMessage; - -// Motor Driver Feedback -typedef struct -{ - uint8_t motor_id; - union { - struct - { - struct - { - uint8_t high_byte; - uint8_t low_byte; - } current; - struct - { - uint8_t high_byte; - uint8_t low_byte; - } rpm; - int8_t temperature; - uint8_t reserved0; - uint8_t count; - uint8_t checksum; - } status; - uint8_t raw[8]; - } data; -} MotorDriverStatusMessage; - -// For convenience to access status/control message -typedef enum -{ - ScoutStatusNone = 0x00, - ScoutMotionStatusMsg = 0x01, - ScoutLightStatusMsg = 0x02, - ScoutSystemStatusMsg = 0x03, - ScoutMotorDriverStatusMsg = 0x04 -} ScoutStatusMsgType; - -typedef struct -{ - ScoutStatusMsgType msg_type; - - // only one of the following fields is updated, as specified by msg_type - MotionStatusMessage motion_status_msg; - LightStatusMessage light_status_msg; - SystemStatusMessage system_status_msg; - MotorDriverStatusMessage motor_driver_status_msg; -} ScoutStatusMessage; - -typedef enum -{ - ScoutControlNone = 0x20, - ScoutMotionControlMsg = 0x21, - ScoutLightControlMsg = 0x22 -} ScoutControlMsgType; - -typedef struct -{ - ScoutControlMsgType msg_type; - - // only one of the following fields is updated, as specified by msg_type - MotionControlMessage motion_control_msg; - LightControlMessage light_control_msg; -} ScoutControlMessage; - -#pragma pack(pop) - -#ifdef __cplusplus -} -#endif - -#endif /* SCOUT_PROTOCOL_H */ diff --git a/scout_sdk/include/scout_sdk/scout_protocol/scout_uart_parser.h b/scout_sdk/include/scout_sdk/scout_protocol/scout_uart_parser.h deleted file mode 100644 index 017273d..0000000 --- a/scout_sdk/include/scout_sdk/scout_protocol/scout_uart_parser.h +++ /dev/null @@ -1,38 +0,0 @@ -/* - * scout_uart_parser.h - * - * Created on: Aug 14, 2019 12:01 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#ifndef SCOUT_UART_PARSER_H -#define SCOUT_UART_PARSER_H - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include -#include - -#include "scout_sdk/scout_protocol/scout_protocol.h" - -bool DecodeScoutStatusMsgFromUART(uint8_t c, ScoutStatusMessage *msg); -bool DecodeScoutControlMsgFromUART(uint8_t c, ScoutControlMessage *msg); - -void EncodeScoutStatusMsgToUART(const ScoutStatusMessage *msg, uint8_t *buf, uint8_t *len); -void EncodeScoutControlMsgToUART(const ScoutControlMessage *msg, uint8_t *buf, uint8_t *len); - -void EncodeMotionControlMsgToUART(const MotionControlMessage *msg, uint8_t *buf, uint8_t *len); -void EncodeLightControlMsgToUART(const LightControlMessage *msg, uint8_t *buf, uint8_t *len); - -uint8_t CalcScoutUARTChecksum(uint8_t *buf, uint8_t len); - -#ifdef __cplusplus -} -#endif - -#endif /* SCOUT_UART_PARSER_H */ diff --git a/scout_sdk/include/scout_sdk/scout_types.hpp b/scout_sdk/include/scout_sdk/scout_types.hpp deleted file mode 100644 index 6767a0e..0000000 --- a/scout_sdk/include/scout_sdk/scout_types.hpp +++ /dev/null @@ -1,111 +0,0 @@ -/* - * scout_state.hpp - * - * Created on: Jun 11, 2019 08:48 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#ifndef SCOUT_STATE_HPP -#define SCOUT_STATE_HPP - -#include -#include - -namespace wescore -{ -struct ScoutState -{ - enum MotorID - { - FRONT_RIGHT = 0, - FRONT_LEFT = 1, - REAR_LEFT = 2, - REAR_RIGHT = 3 - }; - - struct MotorState - { - double current = 0; // in A - double rpm = 0; - double temperature = 0; - }; - - struct LightState - { - uint8_t mode = 0; - uint8_t custom_value = 0; - }; - - // base state - uint8_t base_state = 0; - uint8_t control_mode = 0; - uint16_t fault_code = 0; - double battery_voltage = 0.0; - - // motor state - MotorState motor_states[4]; - - // light state - bool light_control_enabled = false; - LightState front_light_state; - LightState rear_light_state; - - // motion state - double linear_velocity = 0; - double angular_velocity = 0; -}; - -struct ScoutMotionCmd -{ - enum class FaultClearFlag - { - NO_FAULT = 0x00, - BAT_UNDER_VOL = 0x01, - BAT_OVER_VOL = 0x02, - MOTOR1_COMM = 0x03, - MOTOR2_COMM = 0x04, - MOTOR3_COMM = 0x05, - MOTOR4_COMM = 0x06, - MOTOR_DRV_OVERHEAT = 0x07, - MOTOR_OVERCURRENT = 0x08 - }; - - ScoutMotionCmd(int8_t linear = 0, int8_t angular = 0, - FaultClearFlag fault_clr_flag = FaultClearFlag::NO_FAULT) - : linear_velocity(linear), angular_velocity(angular), - fault_clear_flag(fault_clr_flag) {} - - int8_t linear_velocity; - int8_t angular_velocity; - FaultClearFlag fault_clear_flag; - - static constexpr double max_linear_velocity = 1.5; // 1.5 m/s - static constexpr double min_linear_velocity = -1.5; // -1.5 m/s - static constexpr double max_angular_velocity = 0.5235; // 0.5235 rad/s - static constexpr double min_angular_velocity = -0.5235; // -0.5235 rad/s -}; - -struct ScoutLightCmd -{ - enum class LightMode - { - CONST_OFF = 0x00, - CONST_ON = 0x01, - BREATH = 0x02, - CUSTOM = 0x03 - }; - - ScoutLightCmd() = default; - ScoutLightCmd(LightMode f_mode, uint8_t f_value, LightMode r_mode, uint8_t r_value) : front_mode(f_mode), front_custom_value(f_value), - rear_mode(r_mode), rear_custom_value(r_value) {} - - LightMode front_mode; - uint8_t front_custom_value; - LightMode rear_mode; - uint8_t rear_custom_value; -}; -} // namespace wescore - -#endif /* SCOUT_STATE_HPP */ diff --git a/scout_sdk/package.xml b/scout_sdk/package.xml deleted file mode 100644 index e88a1aa..0000000 --- a/scout_sdk/package.xml +++ /dev/null @@ -1,65 +0,0 @@ - - - scout_sdk - 0.0.0 - The scout_sdk package - - - - - rdu - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - roscpp - std_msgs - roscpp - std_msgs - roscpp - std_msgs - - - - - - - - diff --git a/scout_sdk/scripts/bringup_can2usb.bash b/scout_sdk/scripts/bringup_can2usb.bash deleted file mode 100755 index e638f6a..0000000 --- a/scout_sdk/scripts/bringup_can2usb.bash +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/bash - -# bring up can interface -sudo ip link set can0 up type can bitrate 500000 \ No newline at end of file diff --git a/scout_sdk/scripts/setup_can2usb.bash b/scout_sdk/scripts/setup_can2usb.bash deleted file mode 100755 index 6a8d891..0000000 --- a/scout_sdk/scripts/setup_can2usb.bash +++ /dev/null @@ -1,10 +0,0 @@ -#!/bin/bash - -# enable kernel module: gs_usb -sudo modprobe gs_usb - -# bring up can interface -sudo ip link set can0 up type can bitrate 500000 - -# install can utils -sudo apt install -y can-utils \ No newline at end of file diff --git a/scout_sdk/src/async_io/async_can.cpp b/scout_sdk/src/async_io/async_can.cpp deleted file mode 100644 index dc36de8..0000000 --- a/scout_sdk/src/async_io/async_can.cpp +++ /dev/null @@ -1,202 +0,0 @@ -/* - * async_can.cpp - * - * Created on: Jun 10, 2019 02:25 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - * Copyright (c) 2016 UAVCAN Team - */ - -// This is needed to enable necessary declarations in sys/ -#ifndef _GNU_SOURCE -#define _GNU_SOURCE -#endif - -#include "scout_sdk/async_io/async_can.hpp" - -#include -#include -#include -#include -#include - -#include -#include - -#include "asyncio_utils.hpp" - -using namespace wescore; - -using asio::buffer; -using asio::io_service; -using std::error_code; - -std::atomic ASyncCAN::conn_id_counter{0}; - -ASyncCAN::ASyncCAN(std::string device) : tx_total_frames(0), - rx_total_frames(0), - last_tx_total_frames(0), - last_rx_total_frames(0), - last_iostat(steady_clock::now()), - io_service(), - stream(io_service) -{ - conn_id = conn_id_counter.fetch_add(1); - open(device); -} - -ASyncCAN::~ASyncCAN() -{ - close(); -} - -void ASyncCAN::open(std::string device) -{ - const size_t iface_name_size = strlen(device.c_str()) + 1; - if (iface_name_size > IFNAMSIZ) - return; - - can_fd_ = socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW); - if (can_fd_ < 0) - return; - - struct ifreq ifr; - memset(&ifr, 0, sizeof(ifr)); - memcpy(ifr.ifr_name, device.c_str(), iface_name_size); - - const int ioctl_result = ioctl(can_fd_, SIOCGIFINDEX, &ifr); - if (ioctl_result < 0) - close(); - - struct sockaddr_can addr; - memset(&addr, 0, sizeof(addr)); - addr.can_family = AF_CAN; - addr.can_ifindex = ifr.ifr_ifindex; - - const int bind_result = bind(can_fd_, (struct sockaddr *)&addr, sizeof(addr)); - if (bind_result < 0) - close(); - ; - - can_interface_opened_ = true; - - // NOTE: shared_from_this() should not be used in constructors - - // give some work to io_service before start - stream.assign(can_fd_); - io_service.post(std::bind(&ASyncCAN::do_read, this, std::ref(rcv_frame), std::ref(stream))); - - // run io_service for async io - io_thread = std::thread([this]() { - set_this_thread_name("mcan%zu", conn_id); - io_service.run(); - }); -} - -void ASyncCAN::close() -{ - // lock_guard lock(mutex); - // if (!is_open()) - // return; - - const int close_result = ::close(can_fd_); - can_fd_ = -1; - - io_service.stop(); - - if (io_thread.joinable()) - io_thread.join(); - - io_service.reset(); - - can_interface_opened_ = false; - - if (port_closed_cb) - port_closed_cb(); -} - -ASyncCAN::IOStat ASyncCAN::get_iostat() -{ - std::lock_guard lock(iostat_mutex); - IOStat stat; - - stat.tx_total_frames = tx_total_frames; - stat.rx_total_frames = rx_total_frames; - - auto d_tx = stat.tx_total_frames - last_tx_total_frames; - auto d_rx = stat.rx_total_frames - last_rx_total_frames; - last_tx_total_frames = stat.tx_total_frames; - last_rx_total_frames = stat.rx_total_frames; - - auto now = steady_clock::now(); - auto dt = now - last_iostat; - last_iostat = now; - - float dt_s = std::chrono::duration_cast(dt).count(); - - stat.tx_speed = d_tx / dt_s; - stat.rx_speed = d_rx / dt_s; - - return stat; -} - -void ASyncCAN::iostat_tx_add(size_t frame) -{ - tx_total_frames += frame; -} - -void ASyncCAN::iostat_rx_add(size_t frame) -{ - rx_total_frames += frame; -} - -void ASyncCAN::send_frame(const can_frame &tx_frame) -{ - iostat_tx_add(1); - stream.async_write_some(asio::buffer(&tx_frame, sizeof(tx_frame)), - [](error_code error, size_t bytes_transferred) { - // std::cout << "frame sent" << std::endl; - }); -} - -void ASyncCAN::call_receive_callback(can_frame *rx_frame) -{ - // keep track of statistics - iostat_rx_add(1); - - // call the actual parser - if (receive_cb) - receive_cb(rx_frame); - else - default_receive_callback(rx_frame); -} - -void ASyncCAN::default_receive_callback(can_frame *rx_frame) -{ - // do nothing - // std::cerr << "no callback function set" << std::endl; - std::cout << std::hex << rx_frame->can_id << " "; - for (int i = 0; i < rx_frame->can_dlc; i++) - std::cout << std::hex << int(rx_frame->data[i]) << " "; - std::cout << std::dec << std::endl; -} - -void ASyncCAN::do_read(struct can_frame &rec_frame, asio::posix::basic_stream_descriptor<> &stream) -{ - auto sthis = shared_from_this(); - stream.async_read_some( - asio::buffer(&rcv_frame, sizeof(rcv_frame)), - [sthis](error_code error, size_t bytes_transferred) { - if (error) - { - std::cerr << "read error in connection " << sthis->conn_id << " : " - << error.message().c_str() << std::endl; - sthis->close(); - return; - } - - sthis->call_receive_callback(&sthis->rcv_frame); - sthis->do_read(std::ref(sthis->rcv_frame), std::ref(sthis->stream)); - }); -} diff --git a/scout_sdk/src/async_io/async_serial.cpp b/scout_sdk/src/async_io/async_serial.cpp deleted file mode 100644 index 00c36ae..0000000 --- a/scout_sdk/src/async_io/async_serial.cpp +++ /dev/null @@ -1,342 +0,0 @@ -/* - * async_serial.cpp - * - * Created on: Nov 23, 2018 22:24 - * Description: asynchronous serial communication using asio - * adapted from code in libmavconn - * - * Main changes: 1. Removed dependency on Boost (asio standalone - * and C++ STL only) - * 2. Removed dependency on console-bridge - * 3. Removed mavlink related code - * 4. Removed UDP/TCP related code - * - * Author: Vladimir Ermakov - * Ruixiang Du - */ -/* - * libmavconn - * Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved. - * - * This file is part of the mavros package and subject to the license terms - * in the top-level LICENSE file of the mavros repository. - * https://github.com/mavlink/mavros/tree/master/LICENSE.md - */ - -#include -#include - -#include "scout_sdk/async_io/async_serial.hpp" -#include "asyncio_utils.hpp" - -#if defined(__linux__) -#include -#endif - -using namespace wescore; - -using asio::buffer; -using asio::io_service; -using std::error_code; - -std::atomic ASyncSerial::conn_id_counter{0}; - -ASyncSerial::ASyncSerial(std::string device, unsigned baudrate, bool hwflow) : device_(device), - baudrate_(baudrate), - hwflow_(hwflow), tx_total_bytes(0), - rx_total_bytes(0), - last_tx_total_bytes(0), - last_rx_total_bytes(0), - last_iostat(steady_clock::now()), - tx_in_progress(false), - tx_q{}, - rx_buf{}, - io_service(), - serial_dev_(io_service) -{ - conn_id = conn_id_counter.fetch_add(1); -} - -ASyncSerial::~ASyncSerial() -{ - close(); -} - -void ASyncSerial::open(std::string device, unsigned baudrate, bool hwflow) -{ - using SPB = asio::serial_port_base; - - if (device != "") - { - device_ = device; - baudrate_ = baudrate; - hwflow_ = hwflow; - } - - std::cout << "connection: " << conn_id << " , device: " << device_ << " @ " << baudrate_ << "bps" << std::endl; - - try - { - serial_dev_.open(device_); - - // Set baudrate and 8N1 mode - serial_dev_.set_option(SPB::baud_rate(baudrate_)); - serial_dev_.set_option(SPB::character_size(8)); - serial_dev_.set_option(SPB::parity(SPB::parity::none)); - serial_dev_.set_option(SPB::stop_bits(SPB::stop_bits::one)); - serial_dev_.set_option(SPB::flow_control((hwflow_) ? SPB::flow_control::hardware : SPB::flow_control::none)); - -#if defined(__linux__) - // Enable low latency mode on Linux - { - int fd = serial_dev_.native_handle(); - - struct serial_struct ser_info; - ioctl(fd, TIOCGSERIAL, &ser_info); - - ser_info.flags |= ASYNC_LOW_LATENCY; - - ioctl(fd, TIOCSSERIAL, &ser_info); - } -#endif - } - catch (std::system_error &err) - { - throw DeviceError("serial", err); - } - - // NOTE: shared_from_this() should not be used in constructors - - // TODO is the following step necessary? - // give some work to io_service before start - io_service.post(std::bind(&ASyncSerial::do_read, this)); - - // run io_service for async io - io_thread = std::thread([this]() { - set_this_thread_name("mserial%zu", conn_id); - io_service.run(); - }); -} - -void ASyncSerial::close() -{ - lock_guard lock(mutex); - if (!is_open()) - return; - - serial_dev_.cancel(); - serial_dev_.close(); - - io_service.stop(); - - if (io_thread.joinable()) - io_thread.join(); - - io_service.reset(); - - if (port_closed_cb) - port_closed_cb(); -} - -ASyncSerial::IOStat ASyncSerial::get_iostat() -{ - std::lock_guard lock(iostat_mutex); - IOStat stat; - - stat.tx_total_bytes = tx_total_bytes; - stat.rx_total_bytes = rx_total_bytes; - - auto d_tx = stat.tx_total_bytes - last_tx_total_bytes; - auto d_rx = stat.rx_total_bytes - last_rx_total_bytes; - last_tx_total_bytes = stat.tx_total_bytes; - last_rx_total_bytes = stat.rx_total_bytes; - - auto now = steady_clock::now(); - auto dt = now - last_iostat; - last_iostat = now; - - float dt_s = std::chrono::duration_cast(dt).count(); - - stat.tx_speed = d_tx / dt_s; - stat.rx_speed = d_rx / dt_s; - - return stat; -} - -void ASyncSerial::iostat_tx_add(size_t bytes) -{ - tx_total_bytes += bytes; -} - -void ASyncSerial::iostat_rx_add(size_t bytes) -{ - rx_total_bytes += bytes; -} - -void ASyncSerial::send_bytes(const uint8_t *bytes, size_t length) -{ - if (!is_open()) - { - std::cerr << "send: channel closed! connection id: " << conn_id << std::endl; - return; - } - - lock_guard lock(mutex); - if (tx_q.size() >= MAX_TXQ_SIZE) - throw std::length_error("ASyncSerial::send_bytes: TX queue overflow"); - tx_q.emplace_back(bytes, length); - io_service.post(std::bind(&ASyncSerial::do_write, shared_from_this(), true)); -} - -void ASyncSerial::call_receive_callback(uint8_t *buf, const std::size_t bufsize, std::size_t bytes_received) -{ - assert(bufsize >= bytes_received); - - // keep track of statistics - iostat_rx_add(bytes_received); - - // call the actual parser - if (receive_cb) - receive_cb(buf, bufsize, bytes_received); - else - default_receive_callback(buf, bufsize, bytes_received); -} - -void ASyncSerial::default_receive_callback(uint8_t *buf, const size_t bufsize, size_t bytes_received) -{ - // do nothing - std::cerr << "no callback function set" << std::endl; -} - -void ASyncSerial::do_read(void) -{ - auto sthis = shared_from_this(); - serial_dev_.async_read_some( - buffer(rx_buf), - [sthis](error_code error, size_t bytes_transferred) { - if (error) - { - std::cerr << "read error in connection " << sthis->conn_id << " : " - << error.message().c_str() << std::endl; - sthis->close(); - return; - } - - sthis->call_receive_callback(sthis->rx_buf.data(), sthis->rx_buf.size(), bytes_transferred); - sthis->do_read(); - }); - - // std::cout << rx_buf.data() << std::endl; -} - -void ASyncSerial::do_write(bool check_tx_state) -{ - if (check_tx_state && tx_in_progress) - return; - - lock_guard lock(mutex); - if (tx_q.empty()) - return; - - tx_in_progress = true; - auto sthis = shared_from_this(); - auto &buf_ref = tx_q.front(); - serial_dev_.async_write_some( - buffer(buf_ref.dpos(), buf_ref.nbytes()), - [sthis, &buf_ref](error_code error, size_t bytes_transferred) { - assert(bytes_transferred <= buf_ref.len); - - if (error) - { - std::cerr << "write error in connection " << sthis->conn_id << " : " - << error.message().c_str() << std::endl; - sthis->close(); - return; - } - - sthis->iostat_tx_add(bytes_transferred); - lock_guard lock(sthis->mutex); - - if (sthis->tx_q.empty()) - { - sthis->tx_in_progress = false; - return; - } - - buf_ref.pos += bytes_transferred; - if (buf_ref.nbytes() == 0) - sthis->tx_q.pop_front(); - - if (!sthis->tx_q.empty()) - sthis->do_write(false); - else - sthis->tx_in_progress = false; - }); -} - -//---------------------------------------------------------------------------------------// - -namespace -{ -ASyncSerial::Ptr url_parse_serial( - std::string path, std::string query, bool hwflow) -{ - std::string file_path; - int baudrate; - - url_parse_host(path, file_path, baudrate, ASyncSerial::DEFAULT_DEVICE, ASyncSerial::DEFAULT_BAUDRATE); - url_parse_query(query); - - return std::make_shared(file_path, baudrate, hwflow); -} -} // namespace - -ASyncSerial::Ptr ASyncSerial::open_url(std::string url) -{ - /* Based on code found here: - * http://stackoverflow.com/questions/2616011/easy-way-to-parse-a-url-in-c-cross-platform - */ - - const std::string proto_end("://"); - std::string proto; - std::string host; - std::string path; - std::string query; - - auto proto_it = std::search( - url.begin(), url.end(), - proto_end.begin(), proto_end.end()); - if (proto_it == url.end()) - { - // looks like file path - std::cout << "URL: " << url.c_str() << " looks like file path" << std::endl; - return url_parse_serial(url, "", false); - } - - // copy protocol - proto.reserve(std::distance(url.begin(), proto_it)); - std::transform(url.begin(), proto_it, - std::back_inserter(proto), - std::ref(tolower)); - - // copy host - std::advance(proto_it, proto_end.length()); - auto path_it = std::find(proto_it, url.end(), '/'); - std::transform(proto_it, path_it, - std::back_inserter(host), - std::ref(tolower)); - - // copy path, and query if exists - auto query_it = std::find(path_it, url.end(), '?'); - path.assign(path_it, query_it); - if (query_it != url.end()) - ++query_it; - query.assign(query_it, url.end()); - - if (proto == "serial") - return url_parse_serial(path, query, false); - else if (proto == "serial-hwfc") - return url_parse_serial(path, query, true); - else - throw DeviceError("url", "Unknown URL type"); -} diff --git a/scout_sdk/src/async_io/asyncio_utils.cpp b/scout_sdk/src/async_io/asyncio_utils.cpp deleted file mode 100644 index d01a608..0000000 --- a/scout_sdk/src/async_io/asyncio_utils.cpp +++ /dev/null @@ -1,82 +0,0 @@ -/* - * asyncio_utils.cpp - * - * Created on: Jul 24, 2019 01:46 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#include "asyncio_utils.hpp" - -namespace wescore -{ -void url_parse_host(std::string host, - std::string &host_out, int &port_out, - const std::string def_host, const int def_port) -{ - std::string port; - - auto sep_it = std::find(host.begin(), host.end(), ':'); - if (sep_it == host.end()) - { - // host - if (!host.empty()) - { - host_out = host; - port_out = def_port; - } - else - { - host_out = def_host; - port_out = def_port; - } - return; - } - - if (sep_it == host.begin()) - { - // :port - host_out = def_host; - } - else - { - // host:port - host_out.assign(host.begin(), sep_it); - } - - port.assign(sep_it + 1, host.end()); - port_out = std::stoi(port); -} - -/** - * Parse ?ids=sid,cid - */ -void url_parse_query(std::string query) -{ - const std::string ids_end("ids="); - std::string sys, comp; - - if (query.empty()) - return; - - auto ids_it = std::search(query.begin(), query.end(), - ids_end.begin(), ids_end.end()); - if (ids_it == query.end()) - { - std::cerr << "URL: unknown query arguments" << std::endl; - return; - } - - std::advance(ids_it, ids_end.length()); - auto comma_it = std::find(ids_it, query.end(), ','); - if (comma_it == query.end()) - { - std::cerr << "URL: no comma in ids= query" << std::endl; - return; - } - - sys.assign(ids_it, comma_it); - comp.assign(comma_it + 1, query.end()); -} -} // namespace wescore \ No newline at end of file diff --git a/scout_sdk/src/async_io/asyncio_utils.hpp b/scout_sdk/src/async_io/asyncio_utils.hpp deleted file mode 100644 index 7083081..0000000 --- a/scout_sdk/src/async_io/asyncio_utils.hpp +++ /dev/null @@ -1,63 +0,0 @@ -/** - * @brief MAVConn async serial utility class - * @file async_utils.hpp - * @author Vladimir Ermakov - */ -/* - * libmavconn - * Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved. - * - * This file is part of the mavros package and subject to the license terms - * in the top-level LICENSE file of the mavros repository. - * https://github.com/mavlink/mavros/tree/master/LICENSE.md - */ - -#ifndef ASYNCIO_UTILS_HPP -#define ASYNCIO_UTILS_HPP - -#include -#include -#include - -namespace wescore -{ -template -std::string format(const std::string &fmt, Args... args) -{ - // C++11 specify that string store elements continously - std::string ret; - - auto sz = std::snprintf(nullptr, 0, fmt.c_str(), args...); - ret.reserve(sz + 1); - ret.resize(sz); // to be sure there have room for \0 - std::snprintf(&ret.front(), ret.capacity() + 1, fmt.c_str(), args...); - return ret; -} - -template -bool set_this_thread_name(const std::string &name, Args &&... args) -{ - auto new_name = format(name, std::forward(args)...); - -#ifdef __APPLE__ - return pthread_setname_np(new_name.c_str()) == 0; -#else - pthread_t pth = pthread_self(); - return pthread_setname_np(pth, new_name.c_str()) == 0; -#endif -} - -/** - * Parse host:port pairs - */ -void url_parse_host(std::string host, - std::string &host_out, int &port_out, - const std::string def_host, const int def_port); - -/** - * Parse ?ids=sid,cid - */ -void url_parse_query(std::string query); -} // namespace wescore - -#endif /* ASYNCIO_UTILS_HPP */ diff --git a/scout_sdk/src/scout_base.cpp b/scout_sdk/src/scout_base.cpp deleted file mode 100644 index b603cb8..0000000 --- a/scout_sdk/src/scout_base.cpp +++ /dev/null @@ -1,391 +0,0 @@ -#include "scout_sdk/scout_base.hpp" - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace -{ -// source: https://github.com/rxdu/stopwatch -struct StopWatch -{ - using Clock = std::chrono::high_resolution_clock; - using time_point = typename Clock::time_point; - using duration = typename Clock::duration; - - StopWatch() { tic_point = Clock::now(); }; - - time_point tic_point; - - void tic() - { - tic_point = Clock::now(); - }; - - double toc() - { - return std::chrono::duration_cast(Clock::now() - tic_point).count() / 1000000.0; - }; - - // for different precisions - double stoc() - { - return std::chrono::duration_cast(Clock::now() - tic_point).count(); - }; - - double mtoc() - { - return std::chrono::duration_cast(Clock::now() - tic_point).count(); - }; - - double utoc() - { - return std::chrono::duration_cast(Clock::now() - tic_point).count(); - }; - - double ntoc() - { - return std::chrono::duration_cast(Clock::now() - tic_point).count(); - }; - - // you have to call tic() before calling this function - void sleep_until_ms(int64_t period_ms) - { - int64_t duration = period_ms - std::chrono::duration_cast(Clock::now() - tic_point).count(); - - if (duration > 0) - std::this_thread::sleep_for(std::chrono::milliseconds(duration)); - }; - - void sleep_until_us(int64_t period_us) - { - int64_t duration = period_us - std::chrono::duration_cast(Clock::now() - tic_point).count(); - - if (duration > 0) - std::this_thread::sleep_for(std::chrono::microseconds(duration)); - }; -}; -} // namespace - -namespace wescore -{ -ScoutBase::~ScoutBase() -{ - if (serial_connected_) - serial_if_->close(); - - if (cmd_thread_.joinable()) - cmd_thread_.join(); -} - -void ScoutBase::Connect(std::string dev_name, int32_t baud_rate) -{ - if (baud_rate == 0) - { - ConfigureCANBus(dev_name); - } - else - { - ConfigureSerial(dev_name, baud_rate); - - if (!serial_connected_) - std::cerr << "ERROR: Failed to connect to serial port" << std::endl; - } -} - -void ScoutBase::Disconnect() -{ - if (serial_connected_) - { - if (serial_if_->is_open()) - serial_if_->close(); - } -} - -void ScoutBase::ConfigureCANBus(const std::string &can_if_name) -{ - can_if_ = std::make_shared(can_if_name); - - can_if_->set_receive_callback(std::bind(&ScoutBase::ParseCANFrame, this, std::placeholders::_1)); - - can_connected_ = true; -} - -void ScoutBase::ConfigureSerial(const std::string uart_name, int32_t baud_rate) -{ - serial_if_ = std::make_shared(uart_name, baud_rate); - serial_if_->open(); - - if (serial_if_->is_open()) - serial_connected_ = true; - - serial_if_->set_receive_callback(std::bind(&ScoutBase::ParseUARTBuffer, this, - std::placeholders::_1, - std::placeholders::_2, - std::placeholders::_3)); -} - -void ScoutBase::StartCmdThread() -{ - current_motion_cmd_.linear_velocity = 0; - current_motion_cmd_.angular_velocity = 0; - current_motion_cmd_.fault_clear_flag = ScoutMotionCmd::FaultClearFlag::NO_FAULT; - - cmd_thread_ = std::thread(std::bind(&ScoutBase::ControlLoop, this, cmd_thread_period_ms_)); - cmd_thread_started_ = true; -} - -void ScoutBase::SendMotionCmd(uint8_t count) -{ - // motion control message - MotionControlMessage m_msg; - - if (can_connected_) - m_msg.data.cmd.control_mode = CTRL_MODE_CMD_CAN; - else if (serial_connected_) - m_msg.data.cmd.control_mode = CTRL_MODE_CMD_UART; - - motion_cmd_mutex_.lock(); - m_msg.data.cmd.fault_clear_flag = static_cast(current_motion_cmd_.fault_clear_flag); - m_msg.data.cmd.linear_velocity_cmd = current_motion_cmd_.linear_velocity; - m_msg.data.cmd.angular_velocity_cmd = current_motion_cmd_.angular_velocity; - motion_cmd_mutex_.unlock(); - - m_msg.data.cmd.reserved0 = 0; - m_msg.data.cmd.reserved1 = 0; - m_msg.data.cmd.count = count; - - if (can_connected_) - m_msg.data.cmd.checksum = CalcScoutCANChecksum(CAN_MSG_MOTION_CONTROL_CMD_ID, m_msg.data.raw, 8); - // serial_connected_: checksum will be calculated later when packed into a complete serial frame - - if (can_connected_) - { - // send to can bus - can_frame m_frame; - EncodeScoutMotionControlMsgToCAN(&m_msg, &m_frame); - can_if_->send_frame(m_frame); - } - else - { - // send to serial port - EncodeMotionControlMsgToUART(&m_msg, tx_buffer_, &tx_cmd_len_); - serial_if_->send_bytes(tx_buffer_, tx_cmd_len_); - } -} - -void ScoutBase::SendLightCmd(uint8_t count) -{ - LightControlMessage l_msg; - - light_cmd_mutex_.lock(); - if (light_ctrl_enabled_) - { - l_msg.data.cmd.light_ctrl_enable = LIGHT_ENABLE_CTRL; - - l_msg.data.cmd.front_light_mode = static_cast(current_light_cmd_.front_mode); - l_msg.data.cmd.front_light_custom = current_light_cmd_.front_custom_value; - l_msg.data.cmd.rear_light_mode = static_cast(current_light_cmd_.rear_mode); - l_msg.data.cmd.rear_light_custom = current_light_cmd_.rear_custom_value; - } - else - { - l_msg.data.cmd.light_ctrl_enable = LIGHT_DISABLE_CTRL; - - l_msg.data.cmd.front_light_mode = LIGHT_MODE_CONST_OFF; - l_msg.data.cmd.front_light_custom = 0; - l_msg.data.cmd.rear_light_mode = LIGHT_MODE_CONST_OFF; - l_msg.data.cmd.rear_light_custom = 0; - } - light_ctrl_requested_ = false; - light_cmd_mutex_.unlock(); - - l_msg.data.cmd.reserved0 = 0; - l_msg.data.cmd.count = count; - - if (can_connected_) - l_msg.data.cmd.checksum = CalcScoutCANChecksum(CAN_MSG_LIGHT_CONTROL_CMD_ID, l_msg.data.raw, 8); - // serial_connected_: checksum will be calculated later when packed into a complete serial frame - - if (can_connected_) - { - // send to can bus - can_frame l_frame; - EncodeScoutLightControlMsgToCAN(&l_msg, &l_frame); - - can_if_->send_frame(l_frame); - } - else - { - // send to serial port - EncodeLightControlMsgToUART(&l_msg, tx_buffer_, &tx_cmd_len_); - serial_if_->send_bytes(tx_buffer_, tx_cmd_len_); - } - - // std::cout << "cmd: " << static_cast(l_msg.data.cmd.front_light_mode) << " , " << static_cast(l_msg.data.cmd.front_light_custom) << " , " - // << static_cast(l_msg.data.cmd.rear_light_mode) << " , " << static_cast(l_msg.data.cmd.rear_light_custom) << std::endl; - // std::cout << "can: "; - // for (int i = 0; i < 8; ++i) - // std::cout << static_cast(l_frame.data[i]) << " "; - // std::cout << "uart: "; - // for (int i = 0; i < tx_cmd_len_; ++i) - // std::cout << static_cast(tx_buffer_[i]) << " "; - // std::cout << std::endl; -} - -void ScoutBase::ControlLoop(int32_t period_ms) -{ - StopWatch ctrl_sw; - uint8_t cmd_count = 0; - uint8_t light_cmd_count = 0; - while (true) - { - ctrl_sw.tic(); - - // motion control message - SendMotionCmd(cmd_count++); - - // check if there is request for light control - if (light_ctrl_requested_) - SendLightCmd(light_cmd_count++); - - ctrl_sw.sleep_until_ms(period_ms); - // std::cout << "control loop update frequency: " << 1.0 / ctrl_sw.toc() << std::endl; - } -} - -ScoutState ScoutBase::GetScoutState() -{ - std::lock_guard guard(scout_state_mutex_); - return scout_state_; -} - -void ScoutBase::SetMotionCommand(double linear_vel, double angular_vel, ScoutMotionCmd::FaultClearFlag fault_clr_flag) -{ - // make sure cmd thread is started before attempting to send commands - if (!cmd_thread_started_) - StartCmdThread(); - - if (linear_vel < ScoutMotionCmd::min_linear_velocity) - linear_vel = ScoutMotionCmd::min_linear_velocity; - if (linear_vel > ScoutMotionCmd::max_linear_velocity) - linear_vel = ScoutMotionCmd::max_linear_velocity; - if (angular_vel < ScoutMotionCmd::min_angular_velocity) - angular_vel = ScoutMotionCmd::min_angular_velocity; - if (angular_vel > ScoutMotionCmd::max_angular_velocity) - angular_vel = ScoutMotionCmd::max_angular_velocity; - - std::lock_guard guard(motion_cmd_mutex_); - current_motion_cmd_.linear_velocity = static_cast(linear_vel / ScoutMotionCmd::max_linear_velocity * 100.0); - current_motion_cmd_.angular_velocity = static_cast(angular_vel / ScoutMotionCmd::max_angular_velocity * 100.0); - current_motion_cmd_.fault_clear_flag = fault_clr_flag; -} - -void ScoutBase::SetLightCommand(ScoutLightCmd cmd) -{ - if (!cmd_thread_started_) - StartCmdThread(); - - std::lock_guard guard(light_cmd_mutex_); - current_light_cmd_ = cmd; - light_ctrl_enabled_ = true; - light_ctrl_requested_ = true; -} - -void ScoutBase::DisableLightCmdControl() -{ - std::lock_guard guard(light_cmd_mutex_); - light_ctrl_enabled_ = false; - light_ctrl_requested_ = true; -} - -void ScoutBase::ParseCANFrame(can_frame *rx_frame) -{ - // validate checksum, discard frame if fails - if (!rx_frame->data[7] == CalcScoutCANChecksum(rx_frame->can_id, rx_frame->data, rx_frame->can_dlc)) - { - std::cerr << "ERROR: checksum mismatch, discard frame with id " << rx_frame->can_id << std::endl; - return; - } - - // otherwise, update robot state with new frame - ScoutStatusMessage status_msg; - DecodeScoutStatusMsgFromCAN(rx_frame, &status_msg); - NewStatusMsgReceivedCallback(status_msg); -} - -void ScoutBase::ParseUARTBuffer(uint8_t *buf, const size_t bufsize, size_t bytes_received) -{ - // std::cout << "bytes received from serial: " << bytes_received << std::endl; - ScoutStatusMessage status_msg; - for (int i = 0; i < bytes_received; ++i) - { - if (DecodeScoutStatusMsgFromUART(buf[i], &status_msg)) - NewStatusMsgReceivedCallback(status_msg); - } -} - -void ScoutBase::NewStatusMsgReceivedCallback(const ScoutStatusMessage &msg) -{ - // std::cout << "new status msg received" << std::endl; - std::lock_guard guard(scout_state_mutex_); - UpdateScoutState(msg, scout_state_); -} - -void ScoutBase::UpdateScoutState(const ScoutStatusMessage &status_msg, ScoutState &state) -{ - switch (status_msg.msg_type) - { - case ScoutMotionStatusMsg: - { - // std::cout << "motion control feedback received" << std::endl; - const MotionStatusMessage &msg = status_msg.motion_status_msg; - state.linear_velocity = static_cast(static_cast(msg.data.status.linear_velocity.low_byte) | static_cast(msg.data.status.linear_velocity.high_byte) << 8) / 1000.0; - state.angular_velocity = static_cast(static_cast(msg.data.status.angular_velocity.low_byte) | static_cast(msg.data.status.angular_velocity.high_byte) << 8) / 1000.0; - break; - } - case ScoutLightStatusMsg: - { - // std::cout << "light control feedback received" << std::endl; - const LightStatusMessage &msg = status_msg.light_status_msg; - if (msg.data.status.light_ctrl_enable == LIGHT_DISABLE_CTRL) - state.light_control_enabled = false; - else - state.light_control_enabled = true; - state.front_light_state.mode = msg.data.status.front_light_mode; - state.front_light_state.custom_value = msg.data.status.front_light_custom; - state.rear_light_state.mode = msg.data.status.rear_light_mode; - state.rear_light_state.custom_value = msg.data.status.rear_light_custom; - break; - } - case ScoutSystemStatusMsg: - { - // std::cout << "system status feedback received" << std::endl; - const SystemStatusMessage &msg = status_msg.system_status_msg; - state.control_mode = msg.data.status.control_mode; - state.base_state = msg.data.status.base_state; - state.battery_voltage = (static_cast(msg.data.status.battery_voltage.low_byte) | static_cast(msg.data.status.battery_voltage.high_byte) << 8) / 10.0; - state.fault_code = (static_cast(msg.data.status.fault_code.low_byte) | static_cast(msg.data.status.fault_code.high_byte) << 8); - break; - } - case ScoutMotorDriverStatusMsg: - { - // std::cout << "motor 1 driver feedback received" << std::endl; - const MotorDriverStatusMessage &msg = status_msg.motor_driver_status_msg; - for (int i = 0; i < 4; ++i) - { - state.motor_states[status_msg.motor_driver_status_msg.motor_id].current = (static_cast(msg.data.status.current.low_byte) | static_cast(msg.data.status.current.high_byte) << 8) / 10.0; - state.motor_states[status_msg.motor_driver_status_msg.motor_id].rpm = static_cast(static_cast(msg.data.status.rpm.low_byte) | static_cast(msg.data.status.rpm.high_byte) << 8); - state.motor_states[status_msg.motor_driver_status_msg.motor_id].temperature = msg.data.status.temperature; - } - break; - } - } -} -} // namespace wescore diff --git a/scout_sdk/src/scout_protocol/scout_can_parser.c b/scout_sdk/src/scout_protocol/scout_can_parser.c deleted file mode 100644 index 91d80b8..0000000 --- a/scout_sdk/src/scout_protocol/scout_can_parser.c +++ /dev/null @@ -1,197 +0,0 @@ -/* - * scout_can_parser.c - * - * Created on: Aug 31, 2019 04:25 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#include "scout_sdk/scout_protocol/scout_can_parser.h" - -#include "string.h" - -bool DecodeScoutStatusMsgFromCAN(const struct can_frame *rx_frame, ScoutStatusMessage *msg) -{ - msg->msg_type = ScoutStatusNone; - - switch (rx_frame->can_id) - { - // in the current implementation, both MsgType and can_frame include 8 * uint8_t - case CAN_MSG_MOTION_CONTROL_STATUS_ID: - { - msg->msg_type = ScoutMotionStatusMsg; - // msg->motion_status_msg.id = CAN_MSG_MOTION_CONTROL_STATUS_ID; - memcpy(msg->motion_status_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - case CAN_MSG_LIGHT_CONTROL_STATUS_ID: - { - msg->msg_type = ScoutLightStatusMsg; - // msg->light_status_msg.id = CAN_MSG_LIGHT_CONTROL_STATUS_ID; - memcpy(msg->light_status_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - case CAN_MSG_SYSTEM_STATUS_STATUS_ID: - { - msg->msg_type = ScoutSystemStatusMsg; - // msg->system_status_msg.id = CAN_MSG_SYSTEM_STATUS_STATUS_ID; - memcpy(msg->system_status_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - case CAN_MSG_MOTOR1_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - // msg->motor_driver_status_msg.id = CAN_MSG_MOTOR1_DRIVER_STATUS_ID; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR1_ID; - memcpy(msg->motor_driver_status_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - case CAN_MSG_MOTOR2_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - // msg->motor_driver_status_msg.id = CAN_MSG_MOTOR2_DRIVER_STATUS_ID; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR2_ID; - memcpy(msg->motor_driver_status_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - case CAN_MSG_MOTOR3_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - // msg->motor_driver_status_msg.id = CAN_MSG_MOTOR3_DRIVER_STATUS_ID; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR3_ID; - memcpy(msg->motor_driver_status_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - case CAN_MSG_MOTOR4_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - // msg->motor_driver_status_msg.id = CAN_MSG_MOTOR4_DRIVER_STATUS_ID; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR4_ID; - memcpy(msg->motor_driver_status_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - default: - break; - } - - return true; -} - -bool DecodeScoutControlMsgFromCAN(const struct can_frame *rx_frame, ScoutControlMessage *msg) -{ - msg->msg_type = ScoutControlNone; - - switch (rx_frame->can_id) - { - // in the current implementation, both MsgType and can_frame include 8 * uint8_t - case CAN_MSG_MOTION_CONTROL_CMD_ID: - { - msg->msg_type = ScoutMotionControlMsg; - // msg->motion_control_msg.id = CAN_MSG_MOTION_CONTROL_CMD_ID; - memcpy(msg->motion_control_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - case CAN_MSG_LIGHT_CONTROL_CMD_ID: - { - msg->msg_type = ScoutLightControlMsg; - // msg->light_control_msg.id = CAN_MSG_LIGHT_CONTROL_STATUS_ID; - memcpy(msg->light_control_msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t)); - break; - } - default: - break; - } - - return true; -} - -void EncodeScoutStatusMsgToCAN(const ScoutStatusMessage *msg, struct can_frame *tx_frame) -{ - switch (msg->msg_type) - { - // in the current implementation, both MsgType and can_frame include 8 * uint8_t - case ScoutMotionStatusMsg: - { - tx_frame->can_id = CAN_MSG_MOTION_CONTROL_STATUS_ID; - tx_frame->can_dlc = 8; - memcpy(tx_frame->data, msg->motion_status_msg.data.raw, tx_frame->can_dlc); - break; - } - case ScoutLightStatusMsg: - { - tx_frame->can_id = CAN_MSG_LIGHT_CONTROL_STATUS_ID; - tx_frame->can_dlc = 8; - memcpy(tx_frame->data, msg->light_status_msg.data.raw, tx_frame->can_dlc); - break; - } - case ScoutSystemStatusMsg: - { - tx_frame->can_id = CAN_MSG_SYSTEM_STATUS_STATUS_ID; - tx_frame->can_dlc = 8; - memcpy(tx_frame->data, msg->system_status_msg.data.raw, tx_frame->can_dlc); - break; - } - case ScoutMotorDriverStatusMsg: - { - if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR1_ID) - tx_frame->can_id = CAN_MSG_MOTOR1_DRIVER_STATUS_ID; - else if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR2_ID) - tx_frame->can_id = CAN_MSG_MOTOR2_DRIVER_STATUS_ID; - else if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR3_ID) - tx_frame->can_id = CAN_MSG_MOTOR3_DRIVER_STATUS_ID; - else if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR4_ID) - tx_frame->can_id = CAN_MSG_MOTOR4_DRIVER_STATUS_ID; - tx_frame->can_dlc = 8; - memcpy(tx_frame->data, msg->motor_driver_status_msg.data.raw, tx_frame->can_dlc); - break; - } - default: - break; - } - tx_frame->data[7] = CalcScoutCANChecksum(tx_frame->can_id, tx_frame->data, tx_frame->can_dlc); -} - -void EncodeScoutControlMsgToCAN(const ScoutControlMessage *msg, struct can_frame *tx_frame) -{ - switch (msg->msg_type) - { - case ScoutMotionControlMsg: - { - EncodeScoutMotionControlMsgToCAN(&(msg->motion_control_msg), tx_frame); - break; - } - case ScoutLightControlMsg: - { - EncodeScoutLightControlMsgToCAN(&(msg->light_control_msg), tx_frame); - break; - } - default: - break; - } -} - -void EncodeScoutMotionControlMsgToCAN(const MotionControlMessage *msg, struct can_frame *tx_frame) -{ - tx_frame->can_id = CAN_MSG_MOTION_CONTROL_CMD_ID; - tx_frame->can_dlc = 8; - memcpy(tx_frame->data, msg->data.raw, tx_frame->can_dlc); - tx_frame->data[7] = CalcScoutCANChecksum(tx_frame->can_id, tx_frame->data, tx_frame->can_dlc); -} - -void EncodeScoutLightControlMsgToCAN(const LightControlMessage *msg, struct can_frame *tx_frame) -{ - tx_frame->can_id = CAN_MSG_LIGHT_CONTROL_CMD_ID; - tx_frame->can_dlc = 8; - memcpy(tx_frame->data, msg->data.raw, tx_frame->can_dlc); - tx_frame->data[7] = CalcScoutCANChecksum(tx_frame->can_id, tx_frame->data, tx_frame->can_dlc); -} - -uint8_t CalcScoutCANChecksum(uint16_t id, uint8_t *data, uint8_t dlc) -{ - uint8_t checksum = 0x00; - checksum = (uint8_t)(id & 0x00ff) + (uint8_t)(id >> 8) + dlc; - for (int i = 0; i < (dlc - 1); ++i) - checksum += data[i]; - return checksum; -} \ No newline at end of file diff --git a/scout_sdk/src/scout_protocol/scout_uart_parser.c b/scout_sdk/src/scout_protocol/scout_uart_parser.c deleted file mode 100644 index c084535..0000000 --- a/scout_sdk/src/scout_protocol/scout_uart_parser.c +++ /dev/null @@ -1,640 +0,0 @@ -/* - * scout_uart_parser.c - * - * Created on: Aug 14, 2019 12:02 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#include "scout_sdk/scout_protocol/scout_uart_parser.h" - -// #define PRINT_CPP_DEBUG_INFO -// #define PRINT_JLINK_DEBUG_INFO -// #define USE_XOR_CHECKSUM - -#ifdef PRINT_CPP_DEBUG_INFO -#undef PRINT_JLINK_DEBUG_INFO -#endif - -#ifdef PRINT_CPP_DEBUG_INFO -#define < iostream > -#elif (defined(PRINT_JLINK_DEBUG_INFO)) -#include "segger/jlink_rtt.h" -#endif - -typedef enum -{ - WAIT_FOR_SOF1 = 0, - WAIT_FOR_SOF2, - WAIT_FOR_FRAME_LEN, - WAIT_FOR_FRAME_TYPE, - WAIT_FOR_FRAME_ID, - WAIT_FOR_PAYLOAD, - WAIT_FOR_FRAME_COUNT, - WAIT_FOR_CHECKSUM -} ScoutSerialDecodeState; - -#define PAYLOAD_BUFFER_SIZE (SCOUT_FRAME_SIZE * 2) - -#define FRAME_SOF_LEN ((uint8_t)2) -#define FRAME_FIXED_FIELD_LEN ((uint8_t)4) - -#define FRAME_SOF1 ((uint8_t)0x5a) -#define FRAME_SOF2 ((uint8_t)0xa5) - -#define FRAME_TYPE_CONTROL ((uint8_t)0x55) -#define FRAME_TYPE_STATUS ((uint8_t)0xaa) - -#define FRAME_NONE_ID ((uint8_t)0x00) - -typedef union { - ScoutStatusMessage status_msg; - ScoutControlMessage control_msg; -} ScoutDecodedMessage; - -// frame buffer -static uint8_t frame_id = 0; -static uint8_t frame_type = 0; -static uint8_t frame_len = 0; -static uint8_t frame_cnt = 0; -static uint8_t frame_checksum = 0; -static uint8_t internal_checksum = 0; -static uint8_t payload_buffer[PAYLOAD_BUFFER_SIZE]; -static size_t payload_data_pos = 0; - -// statisctics -static uint32_t frame_parsed = 0; -static uint32_t frame_with_wrong_checksum = 0; - -static bool ParseChar(uint8_t c, ScoutDecodedMessage *msg); -static uint8_t CalcBufferedFrameChecksum(); -static bool ConstructStatusMessage(ScoutStatusMessage *msg); -static bool ConstructControlMessage(ScoutControlMessage *msg); - -void EncodeScoutStatusMsgToUART(const ScoutStatusMessage *msg, uint8_t *buf, uint8_t *len) -{ - // SOF - buf[0] = FRAME_SOF1; - buf[1] = FRAME_SOF2; - - // frame len, type, ID - buf[2] = 0x0a; - buf[3] = FRAME_TYPE_STATUS; - - switch (msg->msg_type) - { - // in the current implementation, both MsgType and can_frame include 8 * uint8_t - case ScoutMotionStatusMsg: - { - buf[4] = UART_FRAME_MOTION_STATUS_ID; - buf[5] = msg->motion_status_msg.data.status.linear_velocity.high_byte; - buf[6] = msg->motion_status_msg.data.status.linear_velocity.low_byte; - buf[7] = msg->motion_status_msg.data.status.angular_velocity.high_byte; - buf[8] = msg->motion_status_msg.data.status.angular_velocity.low_byte; - buf[9] = 0; - buf[10] = 0; - buf[11] = msg->motion_status_msg.data.status.count; - break; - } - case ScoutLightStatusMsg: - { - buf[4] = UART_FRAME_LIGHT_STATUS_ID; - buf[5] = msg->light_status_msg.data.status.light_ctrl_enable; - buf[6] = msg->light_status_msg.data.status.front_light_mode; - buf[7] = msg->light_status_msg.data.status.front_light_custom; - buf[8] = msg->light_status_msg.data.status.rear_light_mode; - buf[9] = msg->light_status_msg.data.status.rear_light_custom; - buf[10] = 0; - buf[11] = msg->light_status_msg.data.status.count; - break; - } - case ScoutSystemStatusMsg: - { - buf[4] = UART_FRAME_SYSTEM_STATUS_ID; - buf[5] = msg->system_status_msg.data.status.base_state; - buf[6] = msg->system_status_msg.data.status.control_mode; - buf[7] = msg->system_status_msg.data.status.battery_voltage.high_byte; - buf[8] = msg->system_status_msg.data.status.battery_voltage.low_byte; - buf[9] = msg->system_status_msg.data.status.fault_code.high_byte; - buf[10] = msg->system_status_msg.data.status.fault_code.low_byte; - buf[11] = msg->system_status_msg.data.status.count; - break; - } - case ScoutMotorDriverStatusMsg: - { - if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR1_ID) - buf[4] = UART_FRAME_MOTOR1_DRIVER_STATUS_ID; - else if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR2_ID) - buf[4] = UART_FRAME_MOTOR2_DRIVER_STATUS_ID; - else if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR3_ID) - buf[4] = UART_FRAME_MOTOR3_DRIVER_STATUS_ID; - else if (msg->motor_driver_status_msg.motor_id == SCOUT_MOTOR4_ID) - buf[4] = UART_FRAME_MOTOR4_DRIVER_STATUS_ID; - buf[5] = msg->motor_driver_status_msg.data.status.current.high_byte; - buf[6] = msg->motor_driver_status_msg.data.status.current.low_byte; - buf[7] = msg->motor_driver_status_msg.data.status.rpm.high_byte; - buf[8] = msg->motor_driver_status_msg.data.status.rpm.low_byte; - buf[9] = msg->motor_driver_status_msg.data.status.temperature; - buf[10] = 0; - buf[11] = msg->motor_driver_status_msg.data.status.count; - break; - } - default: - break; - } - - buf[12] = CalcScoutUARTChecksum(buf, buf[2] + FRAME_SOF_LEN); - - // length: SOF + Frame + Checksum - *len = buf[2] + FRAME_SOF_LEN + 1; -} - -void EncodeScoutControlMsgToUART(const ScoutControlMessage *msg, uint8_t *buf, uint8_t *len) -{ - switch (msg->msg_type) - { - case ScoutMotionControlMsg: - { - EncodeMotionControlMsgToUART(&(msg->motion_control_msg), buf, len); - break; - } - case ScoutLightControlMsg: - { - EncodeLightControlMsgToUART(&(msg->light_control_msg), buf, len); - break; - } - default: - break; - } -} - -void EncodeMotionControlMsgToUART(const MotionControlMessage *msg, uint8_t *buf, uint8_t *len) -{ - // SOF - buf[0] = FRAME_SOF1; - buf[1] = FRAME_SOF2; - - // frame len, type, ID - buf[2] = 0x0a; - buf[3] = FRAME_TYPE_CONTROL; - buf[4] = UART_FRAME_MOTION_CONTROL_ID; - - // frame payload - buf[5] = msg->data.cmd.control_mode; - buf[6] = msg->data.cmd.fault_clear_flag; - buf[7] = msg->data.cmd.linear_velocity_cmd; - buf[8] = msg->data.cmd.angular_velocity_cmd; - buf[9] = 0x00; - buf[10] = 0x00; - - // frame count, checksum - buf[11] = msg->data.cmd.count; - buf[12] = CalcScoutUARTChecksum(buf, buf[2] + FRAME_SOF_LEN); - - // length: SOF + Frame + Checksum - *len = buf[2] + FRAME_SOF_LEN + 1; -} - -void EncodeLightControlMsgToUART(const LightControlMessage *msg, uint8_t *buf, uint8_t *len) -{ - // SOF - buf[0] = FRAME_SOF1; - buf[1] = FRAME_SOF2; - - // frame len, type, ID - buf[2] = 0x0a; - buf[3] = FRAME_TYPE_CONTROL; - buf[4] = UART_FRAME_LIGHT_CONTROL_ID; - - // frame payload - buf[5] = msg->data.cmd.light_ctrl_enable; - buf[6] = msg->data.cmd.front_light_mode; - buf[7] = msg->data.cmd.front_light_custom; - buf[8] = msg->data.cmd.rear_light_mode; - buf[9] = msg->data.cmd.rear_light_custom; - buf[10] = 0x00; - - // frame count, checksum - buf[11] = msg->data.cmd.count; - buf[12] = CalcScoutUARTChecksum(buf, buf[2] + FRAME_SOF_LEN); - - // length: SOF + Frame + Checksum - *len = buf[2] + FRAME_SOF_LEN + 1; -} - -bool DecodeScoutStatusMsgFromUART(uint8_t c, ScoutStatusMessage *msg) -{ - static ScoutDecodedMessage decoded_msg; - - bool result = ParseChar(c, &decoded_msg); - if (result) - *msg = decoded_msg.status_msg; - return result; -} - -bool DecodeScoutControlMsgFromUART(uint8_t c, ScoutControlMessage *msg) -{ - static ScoutDecodedMessage decoded_msg; - - bool result = ParseChar(c, &decoded_msg); - if (result) - *msg = decoded_msg.control_msg; - return result; -} - -uint8_t CalcScoutUARTChecksum(uint8_t *buf, uint8_t len) -{ - uint8_t checksum = 0; - -#ifdef USE_XOR_CHECKSUM - for (int i = 0; i < len; ++i) - checksum ^= buf[i]; -#else - for (int i = 0; i < len; ++i) - checksum += buf[i]; -#endif - - return checksum; -} - -uint8_t CalcBufferedFrameChecksum() -{ - uint8_t checksum = 0x00; - -#ifdef USE_XOR_CHECKSUM - checksum ^= FRAME_SOF1; - checksum ^= FRAME_SOF2; - checksum ^= frame_len; - checksum ^= frame_type; - checksum ^= frame_id; - for (size_t i = 0; i < payload_data_pos; ++i) - checksum ^= payload_buffer[i]; - checksum ^= frame_cnt; -#else - checksum += FRAME_SOF1; - checksum += FRAME_SOF2; - checksum += frame_len; - checksum += frame_type; - checksum += frame_id; - for (size_t i = 0; i < payload_data_pos; ++i) - checksum += payload_buffer[i]; - checksum += frame_cnt; -#endif - - return checksum; -} - -bool ParseChar(uint8_t c, ScoutDecodedMessage *msg) -{ - static ScoutSerialDecodeState decode_state = WAIT_FOR_SOF1; - - bool new_frame_parsed = false; - switch (decode_state) - { - case WAIT_FOR_SOF1: - { - if (c == FRAME_SOF1) - { - frame_id = FRAME_NONE_ID; - frame_type = 0; - frame_len = 0; - frame_cnt = 0; - frame_checksum = 0; - internal_checksum = 0; - payload_data_pos = 0; - memset(payload_buffer, 0, PAYLOAD_BUFFER_SIZE); - - decode_state = WAIT_FOR_SOF2; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "found sof1" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "found sof1\n"); -#endif - } - break; - } - case WAIT_FOR_SOF2: - { - if (c == FRAME_SOF2) - { - decode_state = WAIT_FOR_FRAME_LEN; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "found sof2" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "found sof2\n"); -#endif - } - else - { - decode_state = WAIT_FOR_SOF1; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "failed to find sof2" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "failed to find sof2\n"); -#endif - } - break; - } - case WAIT_FOR_FRAME_LEN: - { - frame_len = c; - decode_state = WAIT_FOR_FRAME_TYPE; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "frame len: " << std::hex << static_cast(frame_len) << std::dec << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkRTTPrintf(0, "frame len: %d\n", frame_len); -#endif - break; - } - case WAIT_FOR_FRAME_TYPE: - { - switch (c) - { - case FRAME_TYPE_CONTROL: - { - frame_type = FRAME_TYPE_CONTROL; - decode_state = WAIT_FOR_FRAME_ID; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "control type frame received" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "control type frame received\n"); -#endif - break; - } - case FRAME_TYPE_STATUS: - { - frame_type = FRAME_TYPE_STATUS; - decode_state = WAIT_FOR_FRAME_ID; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "status type frame received" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "status type frame received\n"); -#endif - break; - } - default: - { -#ifdef PRINT_CPP_DEBUG_INFO - std::cerr << "ERROR: Not expecting frame of a type other than FRAME_TYPE_STATUS" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "ERROR: Not expecting frame of a type other than FRAME_TYPE_STATUS\n"); -#endif - decode_state = WAIT_FOR_SOF1; - } - } - break; - } - case WAIT_FOR_FRAME_ID: - { - switch (c) - { - case UART_FRAME_SYSTEM_STATUS_ID: - case UART_FRAME_MOTION_STATUS_ID: - case UART_FRAME_MOTOR1_DRIVER_STATUS_ID: - case UART_FRAME_MOTOR2_DRIVER_STATUS_ID: - case UART_FRAME_MOTOR3_DRIVER_STATUS_ID: - case UART_FRAME_MOTOR4_DRIVER_STATUS_ID: - case UART_FRAME_LIGHT_STATUS_ID: - { - frame_id = c; - decode_state = WAIT_FOR_PAYLOAD; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "frame id: " << std::hex << static_cast(frame_id) << std::dec << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkRTTPrintf(0, "frame id: %d\n", frame_id); -#endif - break; - } - default: - { -#ifdef PRINT_CPP_DEBUG_INFO - std::cerr << "ERROR: Unknown frame id" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "ERROR: Unknown frame id\n"); -#endif - decode_state = WAIT_FOR_SOF1; - } - } - break; - } - case WAIT_FOR_PAYLOAD: - { - payload_buffer[payload_data_pos++] = c; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "1 byte added: " << std::hex << static_cast(c) << std::dec << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkRTTPrintf(0, "1 byte added: %d\n", c); -#endif - if (payload_data_pos == (frame_len - FRAME_FIXED_FIELD_LEN)) - decode_state = WAIT_FOR_FRAME_COUNT; - break; - } - case WAIT_FOR_FRAME_COUNT: - { - frame_cnt = c; - decode_state = WAIT_FOR_CHECKSUM; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "frame count: " << std::hex << static_cast(frame_cnt) << std::dec << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkRTTPrintf(0, "frame count: %d\n", frame_cnt); -#endif - break; - } - case WAIT_FOR_CHECKSUM: - { - frame_checksum = c; - internal_checksum = CalcBufferedFrameChecksum(); - new_frame_parsed = true; - decode_state = WAIT_FOR_SOF1; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "--- frame checksum: " << std::hex << static_cast(frame_checksum) << std::dec << std::endl; - std::cout << "--- internal frame checksum: " << std::hex << static_cast(internal_checksum) << std::dec << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkRTTPrintf(0, "--- frame checksum: : %d\n", frame_checksum); - JLinkRTTPrintf(0, "--- internal frame checksum: : %d\n", internal_checksum); -#endif - break; - } - default: - break; - } - - if (new_frame_parsed) - { - if (frame_checksum == internal_checksum) - { -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "checksum correct" << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "checksum correct\n"); -#endif - if (frame_type == FRAME_TYPE_STATUS) - ConstructStatusMessage(&(msg->status_msg)); - else if (frame_type == FRAME_TYPE_CONTROL) - ConstructControlMessage(&(msg->control_msg)); - ++frame_parsed; - } - else - { - ++frame_with_wrong_checksum; -#ifdef PRINT_CPP_DEBUG_INFO - std::cout << "checksum is NOT correct" << std::endl; - std::cout << std::hex << static_cast(frame_id) << " , " << static_cast(frame_len) << " , " << static_cast(frame_cnt) << " , " << static_cast(frame_checksum) << " : " << std::dec << std::endl; - std::cout << "payload: "; - for (int i = 0; i < payload_data_pos; ++i) - std::cout << std::hex << static_cast(payload_buffer[i]) << std::dec << " "; - std::cout << std::endl; - std::cout << "--- frame checksum: " << std::hex << static_cast(frame_checksum) << std::dec << std::endl; - std::cout << "--- internal frame checksum: " << std::hex << static_cast(internal_checksum) << std::dec << std::endl; -#elif (defined(PRINT_JLINK_DEBUG_INFO)) - JLinkWriteString(0, "checksum is NOT correct\n"); -#endif - } - } - - return new_frame_parsed; -} - -bool ConstructControlMessage(ScoutControlMessage *msg) -{ - if (msg == NULL) - return false; - - switch (frame_id) - { - case UART_FRAME_MOTION_CONTROL_ID: - { - msg->msg_type = ScoutMotionControlMsg; - msg->motion_control_msg.data.cmd.control_mode = payload_buffer[0]; - msg->motion_control_msg.data.cmd.fault_clear_flag = payload_buffer[1]; - msg->motion_control_msg.data.cmd.linear_velocity_cmd = payload_buffer[2]; - msg->motion_control_msg.data.cmd.angular_velocity_cmd = payload_buffer[3]; - msg->motion_control_msg.data.cmd.reserved0 = payload_buffer[4]; - msg->motion_control_msg.data.cmd.reserved1 = payload_buffer[5]; - msg->motion_control_msg.data.cmd.count = frame_cnt; - msg->motion_control_msg.data.cmd.checksum = frame_checksum; - break; - } - case UART_FRAME_LIGHT_CONTROL_ID: - { - msg->msg_type = ScoutLightControlMsg; - msg->light_control_msg.data.cmd.light_ctrl_enable = payload_buffer[0]; - msg->light_control_msg.data.cmd.front_light_mode = payload_buffer[1]; - msg->light_control_msg.data.cmd.front_light_custom = payload_buffer[2]; - msg->light_control_msg.data.cmd.rear_light_mode = payload_buffer[3]; - msg->light_control_msg.data.cmd.rear_light_custom = payload_buffer[4]; - msg->light_control_msg.data.cmd.reserved0 = payload_buffer[5]; - msg->light_control_msg.data.cmd.count = frame_cnt; - msg->light_control_msg.data.cmd.checksum = frame_checksum; - break; - } - } - return true; -} - -bool ConstructStatusMessage(ScoutStatusMessage *msg) -{ - if (msg == NULL) - return false; - - switch (frame_id) - { - case UART_FRAME_SYSTEM_STATUS_ID: - { - msg->msg_type = ScoutSystemStatusMsg; - msg->system_status_msg.data.status.base_state = payload_buffer[0]; - msg->system_status_msg.data.status.control_mode = payload_buffer[1]; - msg->system_status_msg.data.status.battery_voltage.high_byte = payload_buffer[2]; - msg->system_status_msg.data.status.battery_voltage.low_byte = payload_buffer[3]; - msg->system_status_msg.data.status.fault_code.high_byte = payload_buffer[4]; - msg->system_status_msg.data.status.fault_code.low_byte = payload_buffer[5]; - msg->system_status_msg.data.status.count = frame_cnt; - msg->system_status_msg.data.status.checksum = frame_checksum; - break; - } - case UART_FRAME_MOTION_STATUS_ID: - { - msg->msg_type = ScoutMotionStatusMsg; - msg->motion_status_msg.data.status.linear_velocity.high_byte = payload_buffer[0]; - msg->motion_status_msg.data.status.linear_velocity.low_byte = payload_buffer[1]; - msg->motion_status_msg.data.status.angular_velocity.high_byte = payload_buffer[2]; - msg->motion_status_msg.data.status.angular_velocity.low_byte = payload_buffer[3]; - msg->motion_status_msg.data.status.reserved0 = 0x00; - msg->motion_status_msg.data.status.reserved0 = 0x00; - msg->motion_status_msg.data.status.count = frame_cnt; - msg->motion_status_msg.data.status.checksum = frame_checksum; - break; - } - case UART_FRAME_MOTOR1_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR1_ID; - msg->motor_driver_status_msg.data.status.current.high_byte = payload_buffer[0]; - msg->motor_driver_status_msg.data.status.current.low_byte = payload_buffer[1]; - msg->motor_driver_status_msg.data.status.rpm.high_byte = payload_buffer[2]; - msg->motor_driver_status_msg.data.status.rpm.low_byte = payload_buffer[3]; - msg->motor_driver_status_msg.data.status.temperature = payload_buffer[4]; - msg->motor_driver_status_msg.data.status.reserved0 = 0x00; - msg->motor_driver_status_msg.data.status.count = frame_cnt; - msg->motor_driver_status_msg.data.status.checksum = frame_checksum; - break; - } - case UART_FRAME_MOTOR2_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR2_ID; - msg->motor_driver_status_msg.data.status.current.high_byte = payload_buffer[0]; - msg->motor_driver_status_msg.data.status.current.low_byte = payload_buffer[1]; - msg->motor_driver_status_msg.data.status.rpm.high_byte = payload_buffer[2]; - msg->motor_driver_status_msg.data.status.rpm.low_byte = payload_buffer[3]; - msg->motor_driver_status_msg.data.status.temperature = payload_buffer[4]; - msg->motor_driver_status_msg.data.status.reserved0 = 0x00; - msg->motor_driver_status_msg.data.status.count = frame_cnt; - msg->motor_driver_status_msg.data.status.checksum = frame_checksum; - break; - } - case UART_FRAME_MOTOR3_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR3_ID; - msg->motor_driver_status_msg.data.status.current.high_byte = payload_buffer[0]; - msg->motor_driver_status_msg.data.status.current.low_byte = payload_buffer[1]; - msg->motor_driver_status_msg.data.status.rpm.high_byte = payload_buffer[2]; - msg->motor_driver_status_msg.data.status.rpm.low_byte = payload_buffer[3]; - msg->motor_driver_status_msg.data.status.temperature = payload_buffer[4]; - msg->motor_driver_status_msg.data.status.reserved0 = 0x00; - msg->motor_driver_status_msg.data.status.count = frame_cnt; - msg->motor_driver_status_msg.data.status.checksum = frame_checksum; - break; - } - case UART_FRAME_MOTOR4_DRIVER_STATUS_ID: - { - msg->msg_type = ScoutMotorDriverStatusMsg; - msg->motor_driver_status_msg.motor_id = SCOUT_MOTOR4_ID; - msg->motor_driver_status_msg.data.status.current.high_byte = payload_buffer[0]; - msg->motor_driver_status_msg.data.status.current.low_byte = payload_buffer[1]; - msg->motor_driver_status_msg.data.status.rpm.high_byte = payload_buffer[2]; - msg->motor_driver_status_msg.data.status.rpm.low_byte = payload_buffer[3]; - msg->motor_driver_status_msg.data.status.temperature = payload_buffer[4]; - msg->motor_driver_status_msg.data.status.reserved0 = 0x00; - msg->motor_driver_status_msg.data.status.count = frame_cnt; - msg->motor_driver_status_msg.data.status.checksum = frame_checksum; - break; - } - case UART_FRAME_LIGHT_STATUS_ID: - { - msg->msg_type = ScoutLightStatusMsg; - msg->light_status_msg.data.status.light_ctrl_enable = payload_buffer[0]; - msg->light_status_msg.data.status.front_light_mode = payload_buffer[1]; - msg->light_status_msg.data.status.front_light_custom = payload_buffer[2]; - msg->light_status_msg.data.status.rear_light_mode = payload_buffer[3]; - msg->light_status_msg.data.status.rear_light_custom = payload_buffer[4]; - msg->light_status_msg.data.status.reserved0 = 0x00; - msg->light_status_msg.data.status.count = frame_cnt; - msg->light_status_msg.data.status.checksum = frame_checksum; - break; - } - } - return true; -} diff --git a/scout_webots_sim/CMakeLists.txt b/scout_webots_sim/CMakeLists.txt deleted file mode 100644 index 5fce193..0000000 --- a/scout_webots_sim/CMakeLists.txt +++ /dev/null @@ -1,219 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(scout_webots_sim) - -## Compile as C++11, supported in ROS Kinetic and newer -add_compile_options(-std=c++11) - -## Find catkin macros and libraries -## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) -## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS - roslaunch - geometry_msgs - roscpp - rospy - scout_base - sensor_msgs - std_msgs - message_generation - tf - webots_ros - pcl_ros -) - -## System dependencies are found with CMake's conventions -# find_package(Boost REQUIRED COMPONENTS system) - - -## Uncomment this if the package has a setup.py. This macro ensures -## modules and global scripts declared therein get installed -## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html -# catkin_python_setup() - -################################################ -## Declare ROS messages, services and actions ## -################################################ - -## To declare and build messages, services or actions from within this -## package, follow these steps: -## * Let MSG_DEP_SET be the set of packages whose message types you use in -## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). -## * In the file package.xml: -## * add a build_depend tag for "message_generation" -## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET -## * If MSG_DEP_SET isn't empty the following dependency has been pulled in -## but can be declared for certainty nonetheless: -## * add a exec_depend tag for "message_runtime" -## * In this file (CMakeLists.txt): -## * add "message_generation" and every package in MSG_DEP_SET to -## find_package(catkin REQUIRED COMPONENTS ...) -## * add "message_runtime" and every package in MSG_DEP_SET to -## catkin_package(CATKIN_DEPENDS ...) -## * uncomment the add_*_files sections below as needed -## and list every .msg/.srv/.action file to be processed -## * uncomment the generate_messages entry below -## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) - -## Generate messages in the 'msg' folder -# add_message_files( -# FILES -# BoolStamped.msg -# Float64Stamped.msg -# Int32Stamped.msg -# ) - -## Generate services in the 'srv' folder -# add_service_files( -# FILES -# camera_get_focus_info.srv -# camera_get_info.srv -# ) - -## Generate actions in the 'action' folder -# add_action_files( -# FILES -# Action1.action -# Action2.action -# ) - -## Generate added messages and services with any dependencies listed here -# generate_messages( -# DEPENDENCIES -# std_msgs -# sensor_msgs -# ) - -################################################ -## Declare ROS dynamic reconfigure parameters ## -################################################ - -## To declare and build dynamic reconfigure parameters within this -## package, follow these steps: -## * In the file package.xml: -## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" -## * In this file (CMakeLists.txt): -## * add "dynamic_reconfigure" to -## find_package(catkin REQUIRED COMPONENTS ...) -## * uncomment the "generate_dynamic_reconfigure_options" section below -## and list every .cfg file to be processed - -## Generate dynamic reconfigure parameters in the 'cfg' folder -# generate_dynamic_reconfigure_options( -# cfg/DynReconf1.cfg -# cfg/DynReconf2.cfg -# ) - -################################### -## catkin specific configuration ## -################################### -## The catkin_package macro generates cmake config files for your package -## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if your package contains header files -## LIBRARIES: libraries you create in this project that dependent projects also need -## CATKIN_DEPENDS: catkin_packages dependent projects also need -## DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( -# INCLUDE_DIRS include -# LIBRARIES scout_webots_sim - CATKIN_DEPENDS geometry_msgs roscpp rospy scout_base sensor_msgs std_msgs message_runtime tf webots_ros pcl_ros -# DEPENDS system_lib -) - -########### -## Build ## -########### - -## Specify additional locations of header files -## Your package locations should be listed before other locations -include_directories( - include - ${catkin_INCLUDE_DIRS} -) - -## Declare a C++ library -# set(SCOUT_WEBOTS_SRC -# src/scout_webots_interface.cpp -# ) -# add_library(scout_webots_sim STATIC ${SCOUT_WEBOTS_SRC}) -# target_link_libraries(scout_webots_sim ${catkin_LIBRARIES}) -# target_include_directories(scout_webots_sim PUBLIC -# $ -# $ -# PRIVATE src) -## Specify libraries to link a library or executable target against -# target_link_libraries(${PROJECT_NAME}_node -# ${catkin_LIBRARIES} -# ) - -## Declare a C++ executable -add_executable(scout_webots_node src/scout_webots_node.cpp src/scout_webots_interface.cpp) -add_dependencies(scout_webots_node webots_ros_generate_messages_cpp) -target_link_libraries(scout_webots_node ${catkin_LIBRARIES}) - -############# -## Install ## -############# - -roslaunch_add_file_check(launch) - -install(TARGETS scout_webots_node - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) - -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) - -install(DIRECTORY launch urdf worlds - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) - -# all install targets should use catkin DESTINATION variables -# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html - -## Mark executable scripts (Python etc.) for installation -## in contrast to setup.py, you can choose the destination -# install(PROGRAMS -# scripts/my_python_script -# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark executables for installation -## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html -# install(TARGETS ${PROJECT_NAME}_node -# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark libraries for installation -## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html -# install(TARGETS ${PROJECT_NAME} -# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} -# ) - -## Mark cpp header files for installation -# install(DIRECTORY include/${PROJECT_NAME}/ -# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} -# FILES_MATCHING PATTERN "*.h" -# PATTERN ".svn" EXCLUDE -# ) - -## Mark other files for installation (e.g. launch and bag files, etc.) -# install(FILES -# # myfile1 -# # myfile2 -# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -# ) - -############# -## Testing ## -############# - -## Add gtest based cpp test target and link libraries -# catkin_add_gtest(${PROJECT_NAME}-test test/test_scout_webots_sim.cpp) -# if(TARGET ${PROJECT_NAME}-test) -# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) -# endif() - -## Add folders to be run by python nosetests -# catkin_add_nosetests(test) diff --git a/scout_webots_sim/README.md b/scout_webots_sim/README.md deleted file mode 100644 index a5bb1ec..0000000 --- a/scout_webots_sim/README.md +++ /dev/null @@ -1,15 +0,0 @@ -## scout_webots_sim - -* Install dependencies - -``` -$ sudo apt install ros-melodic-webots-ros -``` - -* Set WEBOTS_HOME variable - -Add the following line to your "~/.bashrc" - -``` -export WEBOTS_HOME=/usr/local/webots -``` diff --git a/scout_webots_sim/include/scout_webots_sim/scout_sim_params.hpp b/scout_webots_sim/include/scout_webots_sim/scout_sim_params.hpp deleted file mode 100644 index 544d9c6..0000000 --- a/scout_webots_sim/include/scout_webots_sim/scout_sim_params.hpp +++ /dev/null @@ -1,36 +0,0 @@ -/* - * scout_sim_params.hpp - * - * Created on: Sep 27, 2019 15:08 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#ifndef SCOUT_SIM_PARAMS_HPP -#define SCOUT_SIM_PARAMS_HPP - -#include - -namespace wescore -{ -struct ScoutSimParams -{ - /* Scout Parameters */ - static constexpr double max_steer_angle = 30.0; // in degree - - static constexpr double track = 0.576; // in meter (left & right wheel distance) - static constexpr double wheelbase = 0.648; // in meter (front & rear wheel distance) - static constexpr double wheel_radius = 0.165; // in meter - - // from user manual v1.2.8 P18 - // max linear velocity: 1.5 m/s - // max angular velocity: 0.7853 rad/s - static constexpr double max_linear_speed = 1.5; // in m/s - static constexpr double max_angular_speed = 0.7853; // in rad/s - static constexpr double max_speed_cmd = 10.0; // in rad/s -}; -} // namespace wescore - - -#endif /* SCOUT_SIM_PARAMS_HPP */ diff --git a/scout_webots_sim/include/scout_webots_sim/scout_webots_interface.hpp b/scout_webots_sim/include/scout_webots_sim/scout_webots_interface.hpp deleted file mode 100644 index 8c98c21..0000000 --- a/scout_webots_sim/include/scout_webots_sim/scout_webots_interface.hpp +++ /dev/null @@ -1,41 +0,0 @@ -/* - * scout_webots_interface.hpp - * - * Created on: Sep 26, 2019 23:04 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#ifndef SCOUT_WEBOTS_INTERFACE_HPP -#define SCOUT_WEBOTS_INTERFACE_HPP - -#include - -#include -#include -#include - -#include "scout_base/scout_messenger.hpp" - -namespace wescore -{ -class ScoutWebotsInterface -{ -public: - ScoutWebotsInterface(ros::NodeHandle *nh, ScoutROSMessenger* msger, uint32_t time_step); - - void InitComponents(std::string controller_name); - void UpdateSimState(); - -private: - ros::NodeHandle *nh_; - ScoutROSMessenger* messenger_; - uint32_t time_step_; - - std::string robot_name_ = "agilex_scout"; - const std::vector motor_names_{"motor_fr", "motor_fl", "motor_rl", "motor_rr"}; -}; -} // namespace wescore - -#endif /* SCOUT_WEBOTS_INTERFACE_HPP */ diff --git a/scout_webots_sim/launch/scout_base.launch b/scout_webots_sim/launch/scout_base.launch deleted file mode 100644 index 54672cd..0000000 --- a/scout_webots_sim/launch/scout_base.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/scout_webots_sim/launch/webots.launch b/scout_webots_sim/launch/webots.launch deleted file mode 100644 index 59a285a..0000000 --- a/scout_webots_sim/launch/webots.launch +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/scout_webots_sim/package.xml b/scout_webots_sim/package.xml deleted file mode 100644 index 60bbcb0..0000000 --- a/scout_webots_sim/package.xml +++ /dev/null @@ -1,85 +0,0 @@ - - - scout_webots_sim - 0.0.0 - The scout_webots_sim package - - - - - rdu - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - geometry_msgs - roscpp - rospy - scout_base - sensor_msgs - std_msgs - tf - message_runtime - webots_ros - pcl_ros - roslaunch - geometry_msgs - roscpp - rospy - scout_base - sensor_msgs - std_msgs - geometry_msgs - roscpp - rospy - scout_base - sensor_msgs - std_msgs - tf - message_runtime - webots_ros - pcl_ros - - - - - - - diff --git a/scout_webots_sim/src/scout_webots_interface.cpp b/scout_webots_sim/src/scout_webots_interface.cpp deleted file mode 100644 index 5cfd2de..0000000 --- a/scout_webots_sim/src/scout_webots_interface.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/* - * scout_webots_interface.cpp - * - * Created on: Sep 26, 2019 23:19 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#include "scout_webots_sim/scout_webots_interface.hpp" - -#include -#include -#include - -#include -#include -#include -#include - -#include "scout_webots_sim/scout_sim_params.hpp" - -namespace wescore -{ -ScoutWebotsInterface::ScoutWebotsInterface(ros::NodeHandle *nh, ScoutROSMessenger *msger, uint32_t time_step) - : nh_(nh), messenger_(msger), time_step_(time_step) -{ -} - -void ScoutWebotsInterface::InitComponents(std::string controller_name) -{ - // reset controller name - robot_name_ = controller_name; - - // init motors - for (int i = 0; i < 4; ++i) - { - // position - webots_ros::set_float set_position_srv; - ros::ServiceClient set_position_client = nh_->serviceClient(robot_name_ + "/" + std::string(motor_names_[i]) + - std::string("/set_position")); - - set_position_srv.request.value = INFINITY; - if (set_position_client.call(set_position_srv) && set_position_srv.response.success) - ROS_INFO("Position set to INFINITY for motor %s.", motor_names_[i].c_str()); - else - ROS_ERROR("Failed to call service set_position on motor %s.", motor_names_[i].c_str()); - - // speed - ros::ServiceClient set_velocity_client; - webots_ros::set_float set_velocity_srv; - set_velocity_client = nh_->serviceClient(robot_name_ + "/" + std::string(motor_names_[i]) + - std::string("/set_velocity")); - - set_velocity_srv.request.value = 0.0; - if (set_velocity_client.call(set_velocity_srv) && set_velocity_srv.response.success == 1) - ROS_INFO("Velocity set to 0.0 for motor %s.", motor_names_[i].c_str()); - else - ROS_ERROR("Failed to call service set_velocity on motor %s.", motor_names_[i].c_str()); - } -} - -void ScoutWebotsInterface::UpdateSimState() -{ - // constants for calculation - constexpr double rotation_radius = std::hypot(ScoutSimParams::wheelbase / 2.0, ScoutSimParams::track / 2.0) * 2.0; - constexpr double rotation_theta = std::atan2(ScoutSimParams::wheelbase, ScoutSimParams::track); - - // update robot state - double wheel_speeds[4]; - for (int i = 0; i < 4; ++i) - { - webots_ros::get_float get_velocity_srv; - ros::ServiceClient get_velocity_client = nh_->serviceClient(robot_name_ + "/" + std::string(motor_names_[i]) + - std::string("/get_velocity")); - - if (get_velocity_client.call(get_velocity_srv)) - { - wheel_speeds[i] = get_velocity_srv.response.value; - ROS_INFO("Velocity set to 0.0 for motor %s.", motor_names_[i].c_str()); - } - else - ROS_ERROR("Failed to call service set_velocity on motor %s.", motor_names_[i].c_str()); - } - float left_speed = (wheel_speeds[1] + wheel_speeds[2]) / 2.0 * ScoutSimParams::wheel_radius; - float right_speed = (wheel_speeds[0] + wheel_speeds[3]) / 2.0 * ScoutSimParams::wheel_radius; - double linear_speed = (right_speed + left_speed) / 2.0; - double angular_speed = (right_speed - left_speed) * std::cos(rotation_theta) / rotation_radius; - - messenger_->PublishSimStateToROS(linear_speed, angular_speed); - - // send robot command - double linear, angular; - messenger_->GetCurrentMotionCmdForSim(linear, angular); - - if (linear > ScoutSimParams::max_linear_speed) - linear = ScoutSimParams::max_linear_speed; - if (linear < -ScoutSimParams::max_linear_speed) - linear = -ScoutSimParams::max_linear_speed; - - if (angular > ScoutSimParams::max_angular_speed) - angular = ScoutSimParams::max_angular_speed; - if (angular < -ScoutSimParams::max_angular_speed) - angular = -ScoutSimParams::max_angular_speed; - - double vel_left_cmd = (linear - angular * rotation_radius / std::cos(rotation_theta)) / ScoutSimParams::wheel_radius; - double vel_right_cmd = (linear + angular * rotation_radius / std::cos(rotation_theta)) / ScoutSimParams::wheel_radius; - - double wheel_cmds[4]; - wheel_cmds[0] = vel_right_cmd; - wheel_cmds[1] = vel_left_cmd; - wheel_cmds[2] = vel_left_cmd; - wheel_cmds[3] = vel_right_cmd; - for (int i = 0; i < 4; ++i) - { - ros::ServiceClient set_velocity_client; - webots_ros::set_float set_velocity_srv; - set_velocity_client = nh_->serviceClient(robot_name_ + "/" + std::string(motor_names_[i]) + - std::string("/set_velocity")); - - set_velocity_srv.request.value = wheel_cmds[i]; - if (set_velocity_client.call(set_velocity_srv) && set_velocity_srv.response.success == 1) - ROS_INFO("Velocity set to 0.0 for motor %s.", motor_names_[i].c_str()); - else - ROS_ERROR("Failed to call service set_velocity on motor %s.", motor_names_[i].c_str()); - } -} - -} // namespace wescore \ No newline at end of file diff --git a/scout_webots_sim/src/scout_webots_node.cpp b/scout_webots_sim/src/scout_webots_node.cpp deleted file mode 100644 index e6a96b6..0000000 --- a/scout_webots_sim/src/scout_webots_node.cpp +++ /dev/null @@ -1,119 +0,0 @@ -/* - * scout_webots_node.cpp - * - * Created on: Sep 26, 2019 23:03 - * Description: - * - * Copyright (c) 2019 Ruixiang Du (rdu) - */ - -#include - -#include - -#include -#include - -#include -#include - -#include "scout_webots_sim/scout_webots_interface.hpp" - -using namespace wescore; - -ros::ServiceClient timeStepClient; -webots_ros::set_int timeStepSrv; - -static int controllerCount; -static std::vector controllerList; - -void quit(int sig) -{ - ROS_INFO("User stopped the 'agilex_scout' node."); - timeStepSrv.request.value = 0; - timeStepClient.call(timeStepSrv); - ros::shutdown(); - exit(0); -} - -// catch names of the controllers availables on ROS network -void controllerNameCallback(const std_msgs::String::ConstPtr &name) -{ - controllerCount++; - controllerList.push_back(name->data); - ROS_INFO("Controller #%d: %s.", controllerCount, controllerList.back().c_str()); -} - -int main(int argc, char *argv[]) -{ - ros::init(argc, argv, "scout_webots_node", ros::init_options::AnonymousName); - ros::NodeHandle nh, private_node("~"); - - ScoutROSMessenger messenger(&nh); - private_node.param("odom_frame", messenger.odom_frame_, std::string("odom")); - private_node.param("base_frame", messenger.base_frame_, std::string("base_link")); - private_node.param("sim_control_rate", messenger.sim_control_rate_, 50); - private_node.param("simulated_robot", messenger.simulated_robot_, true); - messenger.SetupSubscription(); - - const uint32_t time_step = 1000 / messenger.sim_control_rate_; - ScoutWebotsInterface scout_webots(&nh, &messenger, time_step); - - signal(SIGINT, quit); - - // subscribe to the topic model_name to get the list of availables controllers - std::string controllerName; - ros::Subscriber nameSub = nh.subscribe("model_name", 100, controllerNameCallback); - while (controllerCount == 0 || controllerCount < nameSub.getNumPublishers()) - { - ros::spinOnce(); - ros::spinOnce(); - ros::spinOnce(); - } - ros::spinOnce(); - - // if there is more than one controller available, it let the user choose - if (controllerCount == 1) - controllerName = controllerList[0]; - else - { - int wantedController = 0; - std::cout << "Choose the # of the controller you want to use:\n"; - std::cin >> wantedController; - if (1 <= wantedController && wantedController <= controllerCount) - controllerName = controllerList[wantedController - 1]; - else - { - ROS_ERROR("Invalid number for controller choice."); - return 1; - } - } - ROS_INFO("Using controller: '%s'", controllerName.c_str()); - - // leave topic once it is not necessary anymore - nameSub.shutdown(); - - // init robot components - scout_webots.InitComponents(controllerName); - - ROS_INFO("Entering ROS main loop..."); - - // main loop - timeStepClient = nh.serviceClient(controllerName + "/robot/time_step"); - timeStepSrv.request.value = time_step; - while (ros::ok()) - { - if (!timeStepClient.call(timeStepSrv) || !timeStepSrv.response.success) - { - ROS_ERROR("Failed to call service time_step for next step."); - break; - } - scout_webots.UpdateSimState(); - ros::spinOnce(); - } - timeStepSrv.request.value = 0; - timeStepClient.call(timeStepSrv); - - ros::shutdown(); - return 0; -} \ No newline at end of file diff --git a/scout_webots_sim/urdf/agilex_scout_webots.urdf b/scout_webots_sim/urdf/agilex_scout_webots.urdf deleted file mode 100644 index 8048cce..0000000 --- a/scout_webots_sim/urdf/agilex_scout_webots.urdf +++ /dev/null @@ -1,72 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/scout_webots_sim/worlds/scout_base.wbt b/scout_webots_sim/worlds/scout_base.wbt deleted file mode 100644 index 73b717c..0000000 --- a/scout_webots_sim/worlds/scout_base.wbt +++ /dev/null @@ -1,541 +0,0 @@ -#VRML_SIM R2020a utf8 -WorldInfo { - basicTimeStep 10 - contactProperties [ - ContactProperties { - coulombFriction [ - 0.71 - ] - } - DEF WHEEL_FLOOR_CONTACT ContactProperties { - material1 "wheel" - softCFM 0 - } - ] -} -Viewpoint { - orientation -0.05993534606055326 0.9810557224110815 0.18422112749918998 2.49878299826534 - position 4.153041811133038 2.8682136668592655 -5.57878305843104 -} -TexturedBackground { -} -TexturedBackgroundLight { -} -Floor { -} -Robot { - translation 0 0.18 0 - children [ - DEF TR_JOINT_FR Transform { - translation -0.324 0 -0.292 - rotation 1 0 0 0 - children [ - DEF JOINT_FR HingeJoint { - jointParameters HingeJointParameters { - axis 0 0 1 - suspensionSpringConstant 6000 - suspensionDampingConstant 150 - suspensionAxis 0 1 0 - } - device [ - RotationalMotor { - name "motor_fr" - controlPID 20 5 0 - maxTorque 500 - } - ] - endPoint DEF WHEEL_FR Solid { - rotation 0 0 1 0 - children [ - DEF RIGHT_WHEEL_SHAPE Group { - children [ - DEF fr_wheel Shape { - appearance Appearance { - material Material { - } - texture ImageTexture { - url [ - "textures/asphalt.jpg" - ] - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.13554038 0.042892516 -0.069771796, -0.13278328 0.042059064 -0.0744977, -0.13335426 0.04021135 -0.074497633, -0.13218653 0.043898493 -0.074497685, -0.13925226 0.039888471 -0.064937085, -0.13869464 0.041784614 -0.064938538, -0.13666777 0.039148629 -0.069773041, -0.14164937 0.040574849 -0.059997797, -0.13611099 0.041042209 -0.069772899, -0.13389969 0.038355947 -0.074497998, -0.14817569 0.060243756 -0.016996644, -0.14594689 0.064170331 -0.02079767, -0.14825675 0.058705896 -0.02062875, 0.13666779 -0.039140731 -0.069777355, 0.13393641 -0.038219482 -0.074502155, 0.13395466 -0.038155407 -0.074502185, 0.13391806 -0.038283616 -0.0745022, 0.13389972 -0.038347602 -0.07450217, -0.14909345 0.042705894 -0.040051579, -0.14819232 0.046369195 -0.039422251, -0.14756079 0.042267114 -0.044997647, 0.13771954 -0.036958784 -0.069033667, 0.13925239 -0.039881438 -0.064941525, -0.14345324 0.073058307 0.0020041466, -0.14103125 0.077660829 4.4107437e-06, -0.14345321 0.073058426 -0.0019958392, 0.020898819 0.15135732 -0.046991453, 0.024799228 0.15215826 -0.042991385, 0.0245713 0.15080476 -0.046991527, 0.13993706 -0.036142468 -0.065544918, 0.14164947 -0.040568203 -0.060002312, -0.13753256 0.081669539 0.017004497, -0.13583025 0.085292041 0.013004802, -0.13791394 0.081879884 0.013004676, -0.13545704 0.085067809 0.017004654, 0.13861468 -0.027829945 -0.071102127, 0.13627006 -0.028813958 -0.074501589, 0.13666986 -0.026853889 -0.074501559, -0.14959303 0.045271158 -0.03581953, -0.14523301 0.069453448 -0.0019962415, 0.087965637 0.11697868 0.062006548, 0.090716958 0.11485827 0.062006429, 0.089132383 0.11850441 0.058006659, 0.14205047 -0.03527385 -0.062001973, -0.14220911 0.075014412 0.0077890009, -0.13944799 0.080090702 0.0072358027, -0.14028603 0.078902543 0.0036229417, 0.14389774 -0.035803169 -0.058002025, 0.14380696 -0.041186452 -0.055083513, 0.086273536 0.12060153 0.058006823, 0.034714505 0.15428767 -0.02799125, 0.038522288 0.15338135 -0.027991265, 0.038278103 0.1525287 -0.031991526, 0.034502357 0.15342695 -0.031991392, 0.044107348 0.15399489 -0.014991373, 0.049138978 0.152677 -0.012991399, 0.049019024 0.15225863 -0.016991407, 0.14571026 -0.038699061 -0.052290842, 0.14577836 -0.041751325 -0.050081149, 0.1466932 -0.040488392 -0.048667327, 0.047844753 0.15339348 -0.0093875527, 0.14471269 -0.032352567 -0.058001861, 0.14284757 -0.031892866 -0.06200178, 0.081380501 0.12931186 0.047007263, 0.084499538 0.12729564 0.047007218, 0.085249677 0.12844563 0.043007165, -0.14857814 0.060409546 -0.012996599, -0.14742209 0.064167172 -0.0077834204, -0.14660832 0.065393418 -0.01139266, 0.082087338 0.13048914 0.043007284, 0.14756081 -0.042262197 -0.045002401, 0.071686596 0.14096045 0.02800788, 0.076076552 0.13815236 0.03000778, 0.073297679 0.14090925 0.024417803, 0.14544478 -0.028883696 -0.058001578, 0.14356428 -0.028494 -0.062001705, -0.15044656 0.043092966 -0.035049163, -0.14523295 0.06945309 0.0020038411, 0.14345646 -0.020061105 -0.064938977, 0.14420012 -0.025079131 -0.062001407, 0.14052582 -0.021528125 -0.069772422, 0.14993548 -0.040556282 -0.039266765, 0.14909345 -0.042701393 -0.040056333, 0.021075875 0.15271842 -0.042991519, 0.14609392 -0.025398135 -0.058001474, 0.15044674 -0.0430893 -0.035054103, 0.059181899 0.14938486 0.0094029456, 0.064662308 0.14710778 0.0092397481, 0.063410416 0.14786276 0.0056267977, 0.017213792 0.15182066 -0.046991408, -0.14692208 0.065805048 -0.0019963309, 0.085164785 0.11903328 0.062006637, 0.06040895 0.14857736 0.013008386, 0.15128353 -0.039436698 -0.035647735, 0.15161888 -0.043425381 -0.030002549, 0.14168575 -0.011648893 -0.069774851, 0.13881767 -0.011382818 -0.07450065, 0.1389669 -0.0093879402 -0.074500531, 0.13863978 -0.013375401 -0.074500799, 0.030885562 0.15509951 -0.02799125, 0.030705735 0.15423158 -0.031991333, 0.1390875 -0.0073910356 -0.074500471, 0.071258754 0.14018321 0.032007843, 0.14617679 -0.018516332 -0.06000106, -0.15161885 0.04342854 -0.029997513, -0.15099028 0.052794635 -0.016997039, -0.15003766 0.056687355 -0.01299686, -0.14962938 0.056536913 -0.016996786, 0.14842109 -0.021210819 -0.054290578, 0.14740074 -0.027062058 -0.054442465, 0.15252696 -0.038276255 -0.032002181, 0.078213438 0.13125163 0.047007382, -0.14692204 0.06580472 0.0020037293, 0.078875929 0.13245496 0.043007538, 0.14967051 -0.022891074 -0.050667107, 0.15337981 -0.038520783 -0.028002232, 0.15258616 -0.043702632 -0.025033653, 0.022819951 0.15422142 -0.037255481, 0.026890427 0.15494227 -0.031991258, 0.028930724 0.15303296 -0.037813857, 0.068176061 0.14269155 0.028008074, -0.1498227 0.058425486 -0.0072259009, 0.1424915 -0.0053864717 -0.06903179, -0.0037085861 0.14133692 -0.071092628, -0.0022273213 0.13927025 -0.074492224, -0.0042273551 0.13922378 -0.074492231, 0.15382227 -0.041041136 -0.022250324, 0.15337838 -0.043929875 -0.020031407, -0.0062264204 0.13914874 -0.074492209, -0.10143233 0.095449746 0.074505381, -0.10005096 0.096896857 0.07450553, -0.10350897 0.097446144 0.069779679, 0.017339975 0.15318763 -0.042991534, -0.11634291 0.091936707 0.058005154, -0.11267667 0.093413472 0.062005162, -0.11411151 0.094691962 0.058005191, 0.15135485 -0.020896256 -0.047001094, 0.15215585 -0.024796724 -0.043001354, 0.1508022 -0.024568737 -0.047001347, 0.072596133 0.13778561 0.03782779, -0.15140411 0.052929908 -0.012996972, 0.07693629 0.13668913 0.03365463, 0.15396115 -0.042585671 -0.018634424, 0.15428622 -0.034713 -0.028001949, 0.15342516 -0.034500748 -0.032001898, -0.15258628 0.043705404 -0.02502881, -0.15214375 0.046573788 -0.022798799, -0.15193456 0.045013368 -0.026405543, 0.060242951 0.14817473 0.0170082, 0.063553289 0.14596736 0.02225402, 0.065082535 0.14588243 0.018638402, 0.15399414 -0.044106513 -0.015002444, 0.013518721 0.1521942 -0.046991393, 0.15271616 -0.02107349 -0.043001235, -0.14851961 0.062115282 0.0020034835, -0.14851952 0.062115401 -0.0019965991, 0.1518182 -0.017211229 -0.047000974, 0.027037635 0.15581644 -0.02799125, -0.10279288 0.093983084 0.074505247, 0.1550981 -0.030884087 -0.02800186, 0.15422986 -0.030704051 -0.032001808, 0.067777663 0.14189908 0.032008097, -0.10659813 0.092871875 0.071103841, -0.10683144 0.097817123 0.064946435, -0.1089929 0.093154103 0.067647904, 0.15421945 -0.02281788 -0.03726545, 0.15494055 -0.026888609 -0.032001466, 0.15303092 -0.028928697 -0.037824109, -0.11486173 0.090713292 0.062005054, 0.064623743 0.14433497 0.028008014, 0.14133301 0.0037125051 -0.071100354, 0.13926607 0.0022315085 -0.074499965, 0.13921976 0.0042313635 -0.074499786, -0.11850777 0.089129001 0.058005031, 0.13914469 0.0062306225 -0.074499682, 0.15318535 -0.01733762 -0.043001041, 0.021545485 0.15537104 -0.033636332, 0.15510061 -0.042022675 -0.0092314184, 0.15442854 -0.044231325 -0.010013402, -0.15337837 0.043932021 -0.020026579, -0.15225761 0.049019992 -0.016997293, -0.10413215 0.092497021 0.074505262, 0.15219167 -0.013516098 -0.047000736, -0.12729836 0.084496796 0.047004856, -0.12632774 0.08835876 0.04300493, -0.12844795 0.085247159 0.043004774, 0.013593644 0.15356538 -0.04299131, 0.15468951 -0.044306278 -0.0050111711, -0.12520681 0.087565929 0.047005013, 0.15581495 -0.027036101 -0.028001472, 0.083497062 0.11147779 0.074506223, 0.085089624 0.11026701 0.074506223, 0.085258022 0.11429191 0.069040477, 0.15536916 -0.021543622 -0.033646271, 0.15356311 -0.0135912 -0.043000743, -0.11698225 0.087961942 0.062005043, 0.15565851 -0.040679544 -0.0056189448, 0.064255267 0.14352849 0.032008007, 0.15477639 -0.044331431 -2.5480986e-06, -0.12060478 0.086270243 0.05800477, -0.15399402 0.044107974 -0.014997572, -0.15267639 0.049139649 -0.012997091, -0.15339288 0.047845066 -0.0093935952, -0.12931457 0.081377864 0.047004625, -0.13049164 0.082084805 0.04300455, 0.08188723 0.11266541 0.074506357, 0.1482843 0.00066009164 -0.058000013, 0.14825761 -0.0028851926 -0.058000222, 0.14633887 -0.0027801394 -0.062000111, 0.14636377 0.00069329143 -0.061999962, -0.14096215 0.071684897 0.028004117, -0.13815415 0.076074839 0.030004352, -0.14091067 0.073296189 0.024413936, 0.15641123 -0.020240635 -0.030001119, 0.061031848 0.14589018 0.028008267, 0.057764977 0.14825469 0.022812158, 0.15326589 -0.0083670616 -0.045000494, 0.15012822 -0.011062533 -0.052843124, 0.15202546 -0.0068309307 -0.048665404, -0.0006569773 0.1482875 -0.057991669, 0.002888456 0.14826068 -0.057991758, 0.0027836263 0.14634222 -0.061991729, 0.15479448 -0.012226582 -0.039425462, -0.00068992376 0.1463671 -0.061991811, 0.020242393 0.15641269 -0.02999115, -0.14938551 0.059181243 0.0093978867, -0.1471083 0.064661771 0.0092350841, -0.147863 0.063410014 0.0056220666, -0.11903676 0.08516115 0.062004916, 0.15611362 -0.03930518 -0.0020022094, -0.14857812 0.060408056 0.013003282, 0.15723118 -0.022712141 -0.02424933, 0.15624468 -0.028565526 -0.024409652, -0.15442854 0.04423219 -0.010008395, -0.14018519 0.071256816 0.032004043, 0.15760282 -0.024241567 -0.020633489, 0.0083696693 0.15326843 -0.044991389, 0.011065558 0.1501312 -0.052834228, 0.006833747 0.15202799 -0.048656553, 0.012228593 0.15479672 -0.039416164, 0.1482262 0.0042050481 -0.05799982, 0.14630619 0.0041663647 -0.061999887, -0.13125435 0.078210711 0.047004469, -0.13245746 0.078873456 0.043004401, 0.052793831 0.15098932 0.017008469, 0.05653587 0.14962846 0.01700829, 0.056686729 0.15003696 0.013008401, 0.052929297 0.15140334 0.01300852, 0.15611359 -0.039305389 0.0019978583, 0.15468949 -0.044306815 0.0050061792, -0.15400696 0.046519101 -0.00578437, -0.1426931 0.068174362 0.028003715, 0.022713467 0.15723261 -0.024239182, 0.028566986 0.15624607 -0.024399102, 0.15704656 -0.03539452 -0.0020019561, -0.13778767 0.072593778 0.037824251, -0.13669106 0.076934427 0.033651404, 0.15533608 -0.041489899 0.007782504, 0.15442854 -0.044232398 0.010008395, 0.060693711 0.14507031 0.032008216, -0.14817569 0.060241908 0.017003313, -0.14596856 0.063551843 0.022249289, -0.14588366 0.065081447 0.018633798, 0.024242759 0.15760377 -0.020623147, -0.0042018741 0.14822936 -0.057991728, -0.0041630268 0.14630958 -0.061991774, 0.14808339 0.0077476203 -0.057999551, -0.15468948 0.044306606 -0.0050062686, 0.14616615 0.0076372027 -0.061999708, 0.1547166 -0.042814761 0.011392176, -0.14190093 0.067775846 0.032003827, 0.15704657 -0.035394788 0.0019981265, 0.039305255 0.15611351 0.0020086616, 0.044331431 0.15477639 8.6128712e-06, 0.039305344 0.1561138 -0.0019913316, -0.14433675 0.064622134 0.028003633, 0.1539941 -0.044108152 0.014997616, 0.15788141 -0.031461656 -0.0020018071, -0.11148202 0.083492875 0.074504755, -0.11027131 0.085085273 0.0745048, -0.11429583 0.085253835 0.069038875, -0.15477642 0.044331312 2.5257468e-06, 0.14072637 0.020171314 -0.069773048, 0.13814111 0.017810285 -0.0744991, 0.13787107 0.019792408 -0.074498832, -0.14353029 0.064253509 0.032003667, -0.11266986 0.081882954 0.074504673, 0.15788141 -0.031461865 0.0019981563, -0.14589176 0.06103 0.028003432, -0.14825614 0.057763517 0.022806909, -0.0077444613 0.14808655 -0.057991572, -0.0076338649 0.1461696 -0.061991766, 0.15861788 -0.027509302 -0.0020014942, -0.15099031 0.052792907 0.017002981, -0.14962927 0.056534857 0.017003134, -0.15003777 0.056686044 0.013003096, -0.15140408 0.052928567 0.013002902, 0.15906724 -0.02362138 -0.0072304606, 0.15800434 -0.029753119 -0.0077885836, -0.15468946 0.044306099 0.0050112829, -0.15377358 0.047052443 0.0072340518, -0.15432629 0.045707881 0.0036210567, 0.035394669 0.1570462 0.0020088404, 0.035394564 0.15704665 -0.0019913465, 0.15389058 -0.041664094 0.020801112, 0.1533784 -0.04393217 0.020026639, -0.14507221 0.060691923 0.03200344, 0.044107273 0.15399322 0.015008599, 0.049018994 0.1522567 0.017008454, 0.049138963 0.15267563 0.013008624, 0.15258622 -0.043705523 0.02502878, 0.047497347 0.15221724 0.020638824, 0.15861781 -0.027509511 0.001998499, -0.15442848 0.044231176 0.010013528, -0.15267628 0.049138129 0.013002727, 0.15941256 -0.022214383 -0.0036179274, -0.15399395 0.044106394 0.0150024, -0.15225762 0.049018055 0.017002683, 0.057131827 0.14438269 0.039431006, 0.062627792 0.14213553 0.039274752, 0.061687231 0.14365268 0.035655528, 0.15368804 -0.04010582 0.02440767, -0.1522184 0.04749611 0.020632885, 0.1516189 -0.043428779 0.029997498, -0.02016747 0.1407302 -0.069766313, -0.017806128 0.13814515 -0.074492246, -0.019788429 0.13787517 -0.074492231, -0.1443848 0.057129502 0.039426129, -0.142138 0.062625438 0.039270446, -0.14365456 0.061685145 0.035650883, 0.031461746 0.15788132 0.0020088255, 0.031461701 0.1578815 -0.0019911379, 0.058035374 0.14282012 0.043008, -0.1533784 0.043929696 0.02003146, 0.062185824 0.1388914 0.048670933, 0.064022601 0.1395022 0.045007631, 0.15221049 0.013307452 -0.046999171, 0.15385938 0.0096827447 -0.042999461, 0.15248884 0.0096040368 -0.046999529, -0.14282259 0.05803284 0.043003231, -0.13889404 0.062182993 0.048666604, -0.13950489 0.064019978 0.045003559, -0.15207291 0.045949757 0.024248537, 0.15965241 -0.020787954 -1.0877848e-06, 0.15814258 0.00048935413 -0.027999833, 0.15722048 -0.0033760369 -0.032000199, 0.15725596 0.00050473213 -0.031999886, 0.15810624 -0.0034246743 -0.028000206, -0.12012978 0.070485771 0.074503928, -0.11910497 0.072203875 0.074504167, -0.12259858 0.071969926 0.069778293, 0.027509376 0.15861782 -0.0019910038, 0.15994798 -0.0087336898 -0.015000537, 0.15869272 -0.011548519 -0.02280204, 0.15957749 -0.007258296 -0.018632457, -0.13388462 0.063742846 0.058003582, -0.13063885 0.065998405 0.06200362, -0.13232212 0.066925615 0.058003835, 0.15934791 -0.013908595 -0.01700075, 0.023621678 0.15906751 -0.0072201937, 0.029753476 0.15800455 -0.0077781528, 0.1601935 -0.012511581 -0.0093970448, 0.15978292 -0.013932586 -0.013000816, -0.14155366 0.057509214 0.047003184, -0.13817064 0.060316861 0.052289523, -0.15258625 0.043702602 0.025033694, 0.1533798 -0.038523912 0.027997822, 0.070489988 0.12012553 0.07450667, 0.072208077 0.11910069 0.074506789, 0.07197383 0.12259457 0.069781125, 0.15921801 -0.023061484 0.0057834238, 0.15826601 -0.028918266 0.0056169778, -0.12698987 0.066565335 0.067646474, -0.12592025 0.071592331 0.064945027, -0.12907001 0.07107082 0.06000391, 0.063746244 0.13388121 0.058007553, 0.066001981 0.13063553 0.062007353, 0.066929013 0.13231888 0.058007434, 0.14176209 0.028153628 -0.065541297, 0.14308767 0.022537649 -0.064939559, 0.14011838 0.026456118 -0.069030076, -0.12112986 0.068753153 0.074503735, 0.14522506 0.024909019 -0.059998602, 0.15357704 0.01343745 -0.042999357, -0.13216837 0.062879622 0.06200368, 0.15880938 -0.024457186 0.0093931705, -0.13537037 0.060523868 0.058003347, 0.057511985 0.14155081 0.047007963, 0.15184219 0.01700303 -0.046999067, 0.060319856 0.13816762 0.052293912, -0.14290972 0.054051667 0.047003027, -0.14419737 0.054527462 0.043002915, -0.15161882 0.043425232 0.030002389, 0.15808208 0.0044030249 -0.027999669, 0.15719564 0.0043852329 -0.031999752, -0.13362353 0.059725583 0.062003341, 0.027509332 0.15861765 0.0020088404, 0.15252696 -0.038279772 0.031997904, 0.15044679 -0.043093294 0.03504926, 0.066569135 0.12698609 0.067649812, 0.071595907 0.12591654 0.064948007, 0.071074292 0.12906653 0.060007259, -0.13677874 0.057270139 0.05800315, 0.068757311 0.12112549 0.074506819, -0.14033066 0.054475576 0.052848209, -0.14418121 0.050562143 0.047002893, -0.14548607 0.050989389 0.043002903, -0.15044665 0.043089241 0.035054155, -0.14904515 0.0457111 0.037269108, -0.15038386 0.044588894 0.033649508, 0.022214472 0.15941277 -0.0036077797, 0.15428616 -0.034716129 0.027998075, -0.13500327 0.056537688 0.062003165, 0.062883273 0.1321649 0.062007457, 0.13696426 0.035069019 -0.071098536, 0.13527885 0.033165187 -0.074498117, 0.13478853 0.035104752 -0.074498147, 0.1342705 0.037036985 -0.074497998, 0.15320317 0.017184168 -0.042999089, -0.14536762 0.047042876 0.047002777, 0.15048723 -0.040117502 0.037817895, 0.14909339 -0.042705894 0.040051505, -0.14668809 0.047421396 0.043002639, -0.14909334 0.042701185 0.040056426, 0.060527176 0.13536686 0.058007643, 0.16056284 -0.0064557791 -0.0092293769, 0.16049717 -0.01108253 -0.005787462, -0.14756072 0.042262107 0.045002282, 0.054054424 0.14290684 0.047007963, 0.15138416 0.020688593 -0.046998918, -0.14448647 0.045265824 0.050666369, 0.054529965 0.14419493 0.043008164, 0.14907645 -0.041212976 0.041420981, -0.12726673 0.056592196 0.074503198, -0.12644072 0.05841428 0.074503213, -0.13040183 0.057683229 0.069037333, 0.15792476 0.0083139241 -0.027999476, 0.15703954 0.0082631111 -0.031999514, -0.12806654 0.054758519 0.074503116, 0.15342513 -0.034504235 0.031998098, -0.14577831 0.041751325 0.050081015, -0.13221131 0.052258164 0.069774315, -0.1327513 0.057142675 0.065548271, 0.14756075 -0.042267203 0.044997647, -0.14348865 0.043472201 0.054289479, 0.15509802 -0.030887216 0.027998313, -0.12883982 0.052913487 0.074502997, -0.14380683 0.041186333 0.055083562, -0.14164953 0.040568113 0.060002349, 0.13900131 -0.025829554 -0.071101993, 0.14085019 -0.026804686 -0.067646623, 0.13704148 -0.024888158 -0.074501455, 0.13738495 -0.0229173 -0.074501395, 0.14096481 -0.026194572 -0.067646474, 0.14879405 -0.027650595 -0.050843254, 0.14859107 -0.028722525 -0.050843284, 0.15021864 -0.027915567 -0.047001615, 0.15025353 -0.03137213 -0.04500173, -0.013304874 0.15221313 -0.046991445, -0.0096803606 0.15386164 -0.042991303, -0.0096013248 0.15249145 -0.046991453, 0.1515682 -0.028166682 -0.043001622, 0.15273787 0.020920604 -0.042998865, 0.15169656 -0.030165225 -0.041426763, 0.15270925 -0.028378993 -0.03926602, 0.14325848 -0.0058665574 -0.067645267, 0.14451447 -0.0098674297 -0.064941451, 0.1385335 0.036962718 -0.067642882, 0.14447176 -0.0040972531 -0.06554313, 0.14624256 -0.0059891641 -0.062000364, 0.02078788 0.15965235 8.970499e-06, 0.14712603 -0.0080309808 -0.060000479, 0.14816141 -0.0060680807 -0.058000311, 0.14868593 -0.0095419586 -0.056442052, 0.1497391 -0.0061328709 -0.054441184, 0.15066895 -0.0053051114 -0.052288979, 0.059729129 0.13361993 0.062007546, 0.1411736 0.0076694787 -0.071100086, 0.14328429 0.0052095056 -0.0676447, 0.13904086 0.0082283914 -0.074499518, 0.14179385 0.010281652 -0.069770634, 0.15685976 -0.029151469 -0.020030692, 0.15786594 -0.025759399 -0.01700148, 0.15685752 -0.032485366 -0.015001923, 0.1565668 -0.030082971 -0.020803019, 0.14807248 0.028354913 -0.052287087, 0.14882655 0.022621542 -0.052841306, 0.14708203 0.023783088 -0.056440189, 0.14316781 0.0077776015 -0.067644641, 0.057273433 0.13677537 0.058007628, 0.14432454 0.01236397 -0.064937219, 0.15748951 -0.029268712 -0.015001699, 0.15748371 -0.031129211 -0.011398003, 0.15829521 -0.025831789 -0.013001472, 0.14614996 0.0079392791 -0.06199953, 0.14663279 0.014475375 -0.059999183, -0.00048772991 0.15814415 -0.027991191, 0.0034261793 0.15810782 -0.027991176, 0.003377825 0.15722221 -0.031991184, -0.00050291419 0.15725768 -0.031991169, 0.1579338 -0.029351652 -0.010012478, 0.1542298 -0.030707538 0.031998321, 0.054478556 0.14032775 0.052852899, 0.15519404 -0.006357342 -0.039264739, 0.15591589 -0.010844678 -0.035822704, 0.15520139 -0.0061756074 -0.039264888, 0.0087345392 0.15994874 -0.014991164, 0.011549816 0.15869376 -0.022792369, 0.0072593391 0.15957847 -0.018623099, 0.14806764 0.0080431104 -0.057999581, 0.14942029 0.012347847 -0.054288775, 0.013909489 0.15934891 -0.016991124, 0.012512118 0.16019383 -0.0093872547, 0.013933316 0.15978348 -0.012991056, 0.15620863 -0.0063990951 -0.035645813, 0.15626648 -0.0047841072 -0.035645857, 0.15870368 -0.021741837 -0.015001237, 0.15895244 -0.017870814 -0.017001003, 0.15938599 -0.017910987 -0.013001069, 0.15889001 -0.021878183 -0.013001114, 0.15845835 -0.021821767 -0.017001197, 0.050564945 0.14417845 0.047008097, 0.14964433 0.0081284642 -0.054440349, 0.15101235 0.01098761 -0.050665051, 0.050992176 0.14548364 0.043008283, 0.14972757 0.0064163208 -0.054440409, 0.13980563 0.021054178 -0.071099326, 0.13757266 0.021770656 -0.074498802, 0.1372458 0.023744375 -0.074498743, 0.14973451 0.027169228 -0.048663542, 0.15712488 -0.0064367652 -0.032000348, 0.15748091 -0.0085980892 -0.030000508, 0.15111941 0.0082083046 -0.050841242, 0.15125749 0.0050623715 -0.05084151, 0.15581489 -0.02703923 0.027998492, 0.15801075 -0.0064733922 -0.028000444, 0.1581414 -0.010073394 -0.026408687, 0.023061156 0.15921754 0.0057937056, 0.028917804 0.15826574 0.0056274086, 0.15739289 -0.023327917 0.022802427, 0.15645087 -0.02947998 0.022244051, 0.15256616 0.0082867444 -0.046999589, 0.15346789 0.0028489232 -0.044999912, 0.14442036 0.033639997 -0.057998002, 0.14328927 0.029853165 -0.061998352, 0.14254056 0.033245057 -0.061998144, 0.14518319 0.030177683 -0.057998255, 0.15955856 -0.014165819 -0.015000835, 0.15872996 -0.0065030754 -0.024248451, 0.15909842 -0.0057834089 -0.022248223, -0.028149821 0.14176577 -0.06553492, -0.022534013 0.14309135 -0.064932808, -0.026452176 0.14012226 -0.069023676, 0.1539368 0.0083609223 -0.042999491, 0.15460603 0.0043468475 -0.041424841, -0.024905801 0.14522842 -0.059991755, 0.15793377 -0.029352725 0.010009214, 0.15685754 -0.032487094 0.014998123, 0.15780878 -0.030306965 0.0092297345, 0.15829524 -0.025833309 0.012998655, -0.013435096 0.15357935 -0.042991333, 0.15509565 0.0084235668 -0.039263904, 0.15563178 0.0058493316 -0.037822142, 0.15543067 0.012071371 -0.037263379, 0.15748946 -0.029270411 0.014998347, 0.15670818 -0.030989647 0.018628567, 0.15786588 -0.025761187 0.016998515, 0.15610966 0.0084785819 -0.035644978, 0.15626809 0.013569474 -0.033644393, 0.024456605 0.15880877 0.0094034076, 0.14353304 0.028657734 -0.061998382, 0.15685967 -0.029153645 0.020027444, -0.017000392 0.15184474 -0.0469914, 0.13595174 0.041576028 -0.069768861, 0.13372481 0.038961738 -0.074497998, 0.15702544 0.008528024 -0.031999484, 0.1454163 0.029033512 -0.057998419, 0.056541294 0.13499975 0.062007636, 0.15791076 0.0085757971 -0.02799949, 0.15699397 0.015071541 -0.029999241, 0.15834329 0.012844563 -0.024247319, 0.1510879 0.02275151 -0.046998709, 0.15128565 0.025947481 -0.044998556, 0.1587038 -0.021743476 0.014998719, 0.15889004 -0.021879703 0.012998864, 0.15938592 -0.017912388 0.012999028, 0.15895241 -0.017872721 0.016998932, 0.15845826 -0.021823734 0.016998857, 0.16074428 -0.0065866411 -0.0057872087, 0.160808 -0.005022347 -0.005617097, 0.15862957 0.0086146891 -0.024247646, 0.15868415 0.0069182515 -0.024407625, 0.14611731 -0.039422423 0.050842121, 0.14577833 -0.041756928 0.050076365, 0.15904589 0.011436105 -0.020631373, -0.0044014007 0.15808353 -0.027991116, 0.16085063 -0.006591171 -0.0020003319, 0.16076061 -0.0087790489 -4.4703484e-07, 0.16094579 -0.0035811961 -0.0020001531, -0.0043834001 0.15719724 -0.031991079, 0.15244523 0.022955686 -0.042998612, 0.15494055 -0.026892126 0.031998575, 0.15363459 0.022525162 -0.039423555, 0.038278073 0.15252519 0.032008529, 0.04342702 0.15161714 0.03000851, 0.038522243 0.15337813 0.028008625, 0.15931101 0.0086514056 -0.020028532, 0.15933561 0.0055106282 -0.020801038, 0.15964007 0.010014981 -0.016999528, 0.16085064 -0.0065913796 0.0019996762, 0.16062805 -0.010221511 0.0036180615, 0.16094574 -0.0035813749 0.0019999295, 0.15359291 0.023128241 -0.039263129, 0.15268481 0.028514922 -0.039262846, 0.15442033 0.02412191 -0.035820723, 0.14380692 -0.041192532 0.055079028, 0.1372994 0.041311532 -0.067642689, 0.14080277 0.039970785 -0.061997861, 0.1379555 0.044169247 -0.06493549, 0.15955856 -0.014167517 0.0149993, 0.15978295 -0.013934016 0.012999222, 0.047045603 0.14536503 0.047008246, 0.15994796 -0.0087353587 0.014999464, 0.15934804 -0.013910532 0.0169992, 0.14357479 0.037083298 -0.057997897, 0.14171153 0.036618263 -0.06199789, 0.16074447 -0.0065872967 0.0057843626, 0.1603885 -0.011655957 0.0072308183, 0.04742381 0.14668557 0.043008283, 0.16036446 -0.0073136091 0.011394113, 0.16067374 -0.0058842897 0.0077843964, 0.1599506 0.0086859465 -0.014999464, 0.16046229 0.0046946406 -0.011396095, 0.16015367 0.0032331944 -0.014999822, 0.16007473 0.010039806 -0.012999415, 0.15270853 -0.028383255 0.0392652, 0.15347788 -0.023573011 0.039421737, 0.15215591 -0.024801672 0.042998597, 0.15251017 -0.029431283 0.03926523, 0.1537796 -0.028176457 0.035645798, 0.15695624 -0.021791846 0.026408747, 0.14015934 0.042171657 -0.061997488, 0.13973607 0.046741396 -0.05999741, 0.1426473 0.040505081 -0.057997823, 0.16040191 0.0087099969 -0.010010377, 0.16066359 0.0061522126 -0.0077865422, 0.16033548 0.012366593 -0.007228449, 0.1515682 -0.028171599 0.042998388, 0.1502535 -0.031377256 0.044998229, 0.14199828 0.042724729 -0.057997584, 0.14292704 0.04528749 -0.054287031, 0.16064262 0.0087229609 -0.0057862997, 0.034714565 0.15428451 0.028008595, 0.16076235 0.0084761381 -0.0019994527, 0.16035904 0.013815135 -0.003615886, 0.15935621 0.01628685 -0.014999077, 0.15977481 0.014026761 -0.012999266, 0.15934137 0.013985574 -0.016999155, 0.15894398 0.017947555 -0.016999081, 0.15937559 0.018004805 -0.012999013, 0.15021858 -0.027920932 0.046998456, 0.15080222 -0.024574071 0.046998709, 0.14924943 -0.029722571 0.048661515, -0.035065159 0.13696811 -0.071092807, -0.033161066 0.13528293 -0.074492432, -0.035100587 0.1347926 -0.074492462, 0.14351039 0.043179423 -0.054438397, 0.14478177 0.044315726 -0.050663337, 0.14454646 0.039573014 -0.054438666, 0.1607489 0.0087285042 -0.001999557, -0.037032783 0.13427454 -0.074492522, -0.017181858 0.15320545 -0.042991452, 0.13090204 0.053421229 -0.071097434, 0.12927991 0.051837653 -0.074497119, 0.12852205 0.053689212 -0.074496984, 0.13001101 0.049975544 -0.074497238, 0.13071921 0.056972086 -0.069028348, 0.13271035 0.05098021 -0.06977129, 0.15421367 0.030788332 -0.031998277, 0.15544619 0.026660234 -0.029998451, 0.15341353 0.030108452 -0.035643801, 0.15403023 0.031693518 -0.031998113, 0.15490456 0.031843275 -0.027998209, 0.14886296 -0.027669042 0.05066219, 0.14893498 -0.02188918 0.05284375, 0.14812881 -0.028064609 0.052284718, 0.14492509 0.043604821 -0.05083926, 0.14652924 0.043295264 -0.046997666, 0.14633934 0.038593531 -0.050839603, 0.1607489 0.0087281168 0.0020003766, 0.1607624 0.0084759593 0.0020005256, 0.16027531 0.015259415 9.0897083e-07, 0.1603577 0.01294598 0.0057854652, 0.13275105 0.054175615 -0.067641914, 0.13448589 0.053812653 -0.064937919, 0.13194393 0.058992743 -0.065539673, 0.15508312 0.030961633 -0.02799806, 0.15641831 0.025369018 -0.026406631, 0.1450651 -0.037623882 0.054440781, 0.15639666 0.029764324 -0.022246182, 0.15873049 -0.0065057576 0.024245426, 0.15930305 -0.0063757002 0.020803168, 0.15875889 -0.0049014986 0.024409592, 0.15848529 -0.010961235 0.024245203, 0.16064268 0.0087222457 0.0057852864, 0.16073288 0.0070242882 0.0056189597, 0.16026977 0.011494309 0.0093952119, 0.0064563304 0.16056341 -0.0092202276, 0.011082724 0.16049746 -0.0057777911, 0.14164945 -0.040574968 0.059997737, 0.1584008 0.023850918 -0.014998734, 0.15719189 0.028433055 -0.01863046, 0.15788136 0.027077019 -0.014998496, -0.020686001 0.15138668 -0.046991557, 0.15844794 0.021898389 -0.016998723, 0.15728398 0.024053454 -0.022800013, 0.15887728 0.021971822 -0.012998775, 0.15801078 -0.0064764917 0.027999654, 0.15748087 -0.0086014569 0.029999614, 0.15810622 -0.0034278035 0.027999684, 0.16040191 0.0087089539 0.010011464, 0.16059604 0.0055685639 0.0092317462, 0.1600747 0.010038495 0.013000667, 0.15884762 0.023917824 -0.010009468, 0.15797392 0.029434592 -0.0092274696, 0.15893927 0.024909437 -0.0057854354, 0.1589613 0.023448557 -0.0093950331, 0.15712489 -0.0064404607 0.031999752, 0.1565358 -0.010011137 0.033646509, 0.1572205 -0.0033797026 0.031999782, 0.15995064 0.0086842775 0.015000537, 0.15967481 0.0046581626 0.01863043, 0.16015357 0.0032316446 0.015000135, 0.1596401 0.010013044 0.017000511, 0.15620811 -0.0064030886 0.035647094, 0.15548055 -0.01140359 0.037265942, 0.15450901 -0.0070070624 0.041422784, -0.0083123446 0.1579262 -0.027991056, 0.15564069 -0.0056252182 0.037819684, 0.14971079 0.045043766 -0.035642818, 0.15042865 0.040333956 -0.037820116, 0.14784768 0.043677062 -0.042997569, -0.0082612932 0.15704137 -0.031991214, 0.14884809 0.046355277 -0.037261426, 0.034502313 0.15342337 0.032008648, 0.14933099 0.048002243 -0.033642456, 0.15126394 0.043000549 -0.031997576, 0.13875644 0.056625456 -0.054437563, 0.13604186 0.056600213 -0.059996799, 0.13805115 0.060593396 -0.052285284, 0.14006203 0.05517152 -0.052839488, 0.13810278 0.055915684 -0.056438431, 0.12523161 0.06562236 -0.071096718, 0.12683597 0.066862702 -0.067641333, 0.12572746 0.064667404 -0.071096897, 0.12266353 0.065986514 -0.074496314, 0.12170315 0.067741454 -0.074496284, 0.15641113 -0.020244092 0.029998869, 0.12359852 0.064217955 -0.074496418, 0.12329243 0.07078591 -0.069767177, 0.1401913 -0.026058495 0.069032624, 0.14213911 -0.026177317 0.065543592, 0.14052583 -0.021535903 0.069770053, 0.13666987 -0.026862144 0.074498489, 0.13996918 -0.0272277 0.06903249, 0.13738495 -0.022925735 0.074498743, 0.13704146 -0.024896532 0.074498639, 0.04226467 0.14755818 0.045008287, 0.159311 0.00864923 0.020029485, 0.15908796 0.0060727298 0.022246107, 0.15863734 0.012280196 0.022804409, 0.15058894 0.045307934 -0.031997532, 0.14970438 0.049628258 -0.029997244, 0.030885443 0.15509653 0.028008878, 0.16098505 0.0004388392 0.0019999295, 0.16098505 0.00043907762 -0.0020000637, 0.15211555 0.043247104 -0.027997598, 0.14012414 0.057183415 -0.050838411, 0.13993514 0.059807211 -0.048661664, 0.14298548 0.053856075 -0.046997041, 0.15143795 0.045563132 -0.027997479, 0.15151536 0.047757328 -0.024245456, 0.045268893 0.14448363 0.05067195, 0.15863001 0.0086119771 0.024246261, 0.15792482 0.0083106756 0.028000399, 0.1578698 0.013680547 0.026410729, 0.14146562 0.057730705 -0.046996713, 0.14171928 0.058961302 -0.044996679, 0.1442537 0.054383457 -0.042997092, 0.15935622 0.016285121 0.015000865, 0.15934141 0.013983667 0.017000705, 0.15977472 0.014025301 0.01300092, 0.15937561 0.018003374 0.013001114, 0.15894392 0.017945677 0.017000973, 0.15541643 0.038799852 -0.01499787, 0.15539475 0.040283173 -0.011394009, 0.15541901 0.03878963 -0.014997885, 0.1541148 0.040828079 -0.020798951, 0.1589711 -0.012435853 0.020629585, 0.15340929 0.045287192 -0.016997516, 0.15212743 0.045770198 -0.024245501, 0.15316638 0.042055488 -0.024405569, 0.15251374 0.046540439 -0.020629406, 0.15791076 0.0085726678 0.028000534, 0.15787046 0.031516552 -0.0019982308, 0.1578937 0.03088671 -0.0056149811, 0.15770742 0.032322437 -0.0019982457, 0.15469229 -0.022315711 0.035818443, 0.15868342 0.027213722 1.4603138e-06, 0.14273661 0.058248967 -0.042996764, 0.14477085 0.056147367 -0.039421648, 0.14251208 0.061775446 -0.039261043, 0.15128507 -0.0062021911 0.050663397, 0.15326589 -0.0083722174 0.044999495, 0.15122552 -0.0059199929 0.050844058, -0.020918146 0.15274015 -0.042991482, 0.14956544 -0.010459363 0.054286525, 0.1509372 -0.011985391 0.050663203, 0.1570254 0.0085244179 0.032000586, 0.15703952 0.0082595646 0.032000512, 0.056596488 0.12726265 0.074507043, 0.058418497 0.12643662 0.074506983, 0.057687104 0.13039804 0.069041327, 0.15699387 0.015068233 0.03000088, 0.15577905 0.012666076 0.035820439, 0.1578705 0.031516373 0.0020017028, 0.15795459 0.030016571 0.0077863485, 0.15887517 0.025777966 0.0036200583, 0.15770739 0.032322198 0.0020017773, 0.14389783 -0.035809726 0.057997897, 0.14381117 0.058687299 -0.039261177, 0.14518158 0.057878822 -0.035818651, 0.14980459 -0.0061416924 0.054286659, 0.14979941 -0.0044006407 0.054442793, 0.15840085 0.023849249 0.015001372, 0.15844791 0.021896511 0.017001182, 0.15887724 0.021970421 0.013001263, -0.036958933 0.1385372 -0.06763728, 0.15797108 0.028554171 0.01139614, 0.15788133 0.02707544 0.01500158, 0.15896083 0.024326086 0.0072327852, 0.15610923 0.0084744692 0.035647914, 0.15619341 0.0067491233 0.035647884, 0.15487486 0.01117 0.039423674, 0.14475149 0.059070796 -0.035641998, 0.14561674 0.060581863 -0.029996589, 0.14286782 0.063491195 -0.035641983, 0.15339439 0.046150923 -0.014997423, 0.15382744 0.04540813 -0.012997448, 0.15264782 0.049228251 -0.01299718, 0.15223448 0.049091816 -0.016997278, 0.14816141 -0.0060745776 0.057999656, 0.14825763 -0.0028917491 0.05799982, 0.14712606 -0.0080378056 0.05999954, 0.15509506 0.0084191263 0.039267361, 0.15523487 0.0052434504 0.039267272, 0.15385944 0.0096778274 0.043000549, 0.12626705 0.074026793 -0.061995819, 0.12837902 0.070300281 -0.061996102, 0.12466881 0.073760003 -0.064933777, -0.02835203 0.14807537 -0.052280277, -0.022618562 0.14882943 -0.052834205, -0.023779988 0.14708513 -0.056433335, 0.12583241 0.076663792 -0.059995607, 0.13071533 0.048103064 -0.074497402, 0.13005832 0.071231604 -0.057995975, 0.15776743 0.023753494 0.020030305, 0.15695047 0.024579883 0.024247259, 0.15775241 0.023250282 0.020631686, 0.15672742 0.029232532 0.02080515, 0.13405433 0.070244193 -0.05083774, 0.13211727 0.070745558 -0.054436922, 0.13129121 0.075421661 -0.050661534, 0.13408306 0.070189625 -0.0508378, 0.13322188 0.074815601 -0.046995848, 0.14624259 -0.0059961677 0.061999723, 0.14633889 -0.0027871728 0.061999872, 0.1445145 -0.0098747611 0.064940393, 0.15393677 0.0083560348 0.043000519, 0.15346788 0.0028439164 0.045000121, 0.16092387 0.0044586957 0.0020001829, 0.16092388 0.0044591129 -0.0019997805, 0.030705795 0.15422803 0.032008633, 0.12792367 0.074997783 -0.057995886, 0.12926677 0.075956315 -0.054285318, 0.13533761 0.070916325 -0.046996042, 0.13703474 0.069154263 -0.044996172, 0.13442236 0.075481147 -0.042995811, 0.15405789 0.046349972 -0.0057842135, 0.15526655 0.041748822 -0.0077845454, 0.15484558 0.044036686 -0.0019975603, 0.15356369 0.047734648 -0.0072263926, 0.15326425 0.049152046 -0.003613919, 0.14440767 -0.0059211552 0.065544561, 0.14329728 -0.0048817694 0.067642421, 0.15102459 0.053397387 -0.01499702, 0.15096539 0.052865982 -0.016997069, 0.1496028 0.056607276 -0.016996801, 0.15000489 0.056774378 -0.012996867, 0.15137337 0.053017795 -0.012996957, 0.054762766 0.12806222 0.074507222, 0.15256608 0.0082814097 0.047000483, 0.15248883 0.009598583 0.047000542, -0.027166486 0.14973712 -0.048656695, 0.15212065 0.0042338371 0.048663408, 0.12928583 0.075796187 -0.054436505, 0.052261949 0.13220724 0.069778711, 0.057146311 0.13274744 0.065552443, 0.14708792 0.060023576 -0.024244711, 0.14798838 0.058449358 -0.022798195, 0.14685179 0.059539318 -0.026404724, 0.14585257 0.063819677 -0.022244453, 0.15415981 0.046380579 -0.0019974858, 0.15286136 0.050541401 2.771616e-06, 0.13655363 0.0715532 -0.042996019, 0.13768242 0.072796345 -0.037818238, 0.13741018 0.070997655 -0.041421071, 0.027037606 0.15581328 0.028008744, 0.14247233 -0.00584203 0.069033578, 0.14124902 -0.0061545074 0.071098268, 0.14168571 -0.011656672 0.069773555, 0.023326591 0.1573914 0.022812545, 0.029478759 0.15644962 0.022254542, 0.15118928 0.0082065165 0.050664246, 0.150071 0.011800706 0.052845776, -0.033636838 0.1444236 -0.057991974, -0.029849656 0.1432927 -0.061991915, -0.03324154 0.14254394 -0.061992079, 0.15065916 0.0056008399 0.052286595, 0.14771985 0.060281157 -0.020025566, -0.030174412 0.14518642 -0.057991944, 0.14692408 0.062698603 -0.018628553, 0.14789793 0.061529964 -0.014996648, 0.15415977 0.046380252 0.0020025223, 0.15484564 0.044036418 0.0020025223, 0.15345633 0.048304319 0.0057874173, 0.14205047 -0.035280824 0.06199795, 0.13925242 -0.03988871 0.064937145, 0.11623757 0.083945781 -0.067640305, 0.11803973 0.079232901 -0.069769725, 0.11450455 0.079305619 -0.074495614, 0.11914046 0.082389444 -0.064936265, 0.11335371 0.080941975 -0.074495524, 0.11476518 0.084631532 -0.069026768, 0.11550941 0.086874187 -0.065538093, 0.14471269 -0.032359213 0.057998136, 0.14970982 0.0081258714 0.054287508, 0.14840959 0.01314652 0.056444317, 0.1480834 0.0077410638 0.05800049, 0.15541647 0.038798183 0.015002176, 0.1538274 0.045406759 0.013002589, 0.15463464 0.040072352 0.018632457, 0.15541898 0.038787991 0.015002191, 0.15533021 0.041164875 0.0092338026, 0.15405799 0.046349347 0.0057872981, 0.15513983 0.042614549 0.005621016, 0.15369369 0.046869636 0.0093972087, 0.14831285 0.060523033 -0.014996588, 0.1550831 0.030958563 0.02800186, 0.1558689 0.030548573 0.024411514, 0.15490451 0.031840056 0.02800183, 0.15544613 0.026656896 0.030001476, 0.14806762 0.0080365539 0.058000475, 0.11865887 0.085694045 -0.061995238, 0.11614789 0.089067817 -0.061995029, 0.11771339 0.090182006 -0.057994962, 0.12003714 0.085453361 -0.059995219, 0.14873129 0.060693413 -0.01000759, -0.041572183 0.13595569 -0.069763444, -0.038957544 0.13372898 -0.074492544, 0.14941154 0.05965203 -0.0057834685, 0.1497582 0.058232754 -0.0093930513, 0.14746352 0.063849151 -0.0092254579, 0.15421367 0.030784756 0.032001764, 0.15403023 0.031689852 0.032001957, 0.15298975 0.029149085 0.037821725, 0.15483841 0.025072396 0.033648536, 0.14615007 0.0079322159 0.062000453, 0.14663275 0.01446864 0.060000956, 0.14432445 0.012356788 0.064938605, 0.14616609 0.0076302588 0.062000453, 0.052917793 0.12883565 0.0745074, 0.15244523 0.022950888 0.043001339, 0.15411946 0.023479819 0.037267864, 0.1521938 0.027550042 0.041424796, 0.15128565 0.025942475 0.045001581, 0.1527378 0.020915687 0.04300122, 0.12021571 0.086818129 -0.057995185, 0.12219857 0.085244656 -0.056436792, 0.15339433 0.046149194 0.015002653, 0.15264782 0.04922685 0.013002902, 0.15223451 0.049089938 0.017002732, 0.15340929 0.045285314 0.017002508, 0.14895453 0.060784161 -0.0057833642, 0.14864925 0.061841816 3.5613775e-06, 0.14706211 0.06524694 -0.005613029, 0.14431626 0.0078324378 0.065545395, 0.14179386 0.010273784 0.069771871, 0.14439963 0.0061078072 0.065545216, 0.15108785 0.022746146 0.047001198, 0.15138409 0.020683378 0.047001183, 0.1498192 0.021901816 0.050665051, 0.12149592 0.087742418 -0.054435804, 0.12110725 0.089793354 -0.05228366, 0.12427424 0.084954828 -0.052837819, 0.026890382 0.15493873 0.032008663, 0.10623142 0.093297154 -0.071095183, 0.10818638 0.091023117 -0.071095482, 0.10621071 0.090111196 -0.074494958, 0.10877849 0.093409926 -0.067639738, 0.10490559 0.09162733 -0.074494869, 0.10357884 0.093124688 -0.074494809, 0.10445082 0.096446395 -0.069765776, 0.14238222 0.0077272058 0.069034383, 0.1391446 0.0062221587 0.074500412, 0.14251769 0.0046010017 0.069034413, 0.13861892 -0.036645949 0.067640617, 0.13666779 -0.039148599 0.069773182, 0.13904092 0.0082198381 0.074500501, 0.13566287 0.079533517 -0.03199549, 0.1379033 0.075581968 -0.031995729, 0.13480157 0.07831493 -0.037259802, 0.1349059 0.080028087 -0.033640638, 0.13490804 0.081696302 -0.029995441, 0.13867868 0.076011717 -0.02799584, 0.14972429 0.022540867 0.050664961, 0.14875056 0.027879298 0.050845876, 0.14814226 0.023084223 0.054288372, 0.12269358 0.088607043 -0.050836757, -0.037079968 0.14357793 -0.057991959, -0.036614828 0.1417149 -0.061992057, 0.12504654 0.089018613 -0.04499501, 0.12311907 0.089446217 -0.048660144, 0.10773197 0.094614774 -0.067639619, 0.10513085 0.099652112 -0.064932361, 0.10951769 0.097104937 -0.061994612, 0.13642772 0.079981536 -0.027995557, 0.13708989 0.080275327 -0.024243429, 0.15212777 0.045767576 0.024248496, 0.15211557 0.043243915 0.028002501, 0.15374771 0.041320831 0.022248089, 0.149763 0.038641006 -0.041422948, 0.14898668 0.036927402 -0.04499796, 0.15192705 0.047272384 0.022806317, 0.15086718 0.048466772 0.02641277, 0.13633898 -0.03743118 0.071096539, 0.15102465 0.053395659 0.015003011, 0.15137333 0.053016424 0.013003051, 0.15000486 0.056772918 0.013003305, 0.021790206 0.15695477 0.02641882, 0.15096538 0.052864075 0.01700297, 0.14960276 0.056605369 0.017003268, 0.14895456 0.060783565 0.0057881922, 0.14956214 0.059088409 0.0072346926, 0.14915566 0.060484648 0.0036218464, 0.1428476 -0.031899899 0.061998263, 0.14731494 0.064412057 0.0077884197, 0.14188826 0.07434693 -0.014995888, 0.14116602 0.07409811 -0.020797089, 0.13948591 0.078288555 -0.016995654, 0.14253494 0.073851734 -0.011392191, 0.14289102 0.072401136 -0.014995992, 0.13986653 0.078499466 -0.012995541, 0.15143797 0.045559824 0.028002575, 0.14970437 0.04962483 0.030002773, 0.14873129 0.060692251 0.010014325, 0.14765631 0.062990099 0.011398152, 0.1478979 0.061528385 0.015003398, 0.15058894 0.045304179 0.032002628, 0.14905442 0.047012627 0.035822257, 0.15126397 0.042996943 0.032002375, 0.12592182 0.090937793 -0.039259255, 0.1286476 0.086954236 -0.039419889, 0.14544488 -0.028890371 0.057998359, 0.12519296 0.091938794 -0.03925927, 0.12866271 0.088733643 -0.035817057, 0.14831284 0.060521305 0.015003353, 0.14971031 0.045039594 0.035649955, 0.15077507 0.04133606 0.035649747, 0.14850579 0.045352846 0.039425597, 0.12674512 0.091532141 -0.035640195, 0.12515807 0.093690544 -0.03564021, 0.13389966 -0.038355947 0.074497864, 0.13819014 0.081014067 -0.014995515, 0.13786645 0.081961364 -0.012995407, 0.13749391 0.081736356 -0.016995385, 0.11260556 0.09889394 -0.054435223, 0.11306298 0.098370701 -0.054435357, 0.11094764 0.098386496 -0.057994545, 0.10912454 0.10281658 -0.054283708, 0.11121719 0.1027458 -0.050659999, 0.14541636 0.029026836 0.058001578, 0.14702219 0.029043049 0.054444522, 0.14518322 0.030171067 0.058001727, 0.13391806 -0.038291991 0.074497908, 0.14522494 0.024902463 0.060001567, 0.14873768 0.044746786 0.039269418, 0.15017562 0.039654851 0.039269164, 0.1478477 0.043672174 0.043002412, 0.13393643 -0.038227916 0.074497849, 0.096882269 0.10297266 -0.071094736, 0.097450107 0.10351279 -0.06976828, 0.096901044 0.10005498 -0.074494317, 0.093987405 0.10279691 -0.074494213, 0.092501372 0.10413632 -0.074494168, 0.095454082 0.1014365 -0.074494436, 0.13395467 -0.038163751 0.074497879, 0.093056336 0.10804743 -0.069025367, 0.15135482 -0.020901471 0.046998769, 0.15271614 -0.021078318 0.042998821, 0.14771977 0.060278952 0.020032465, 0.14754555 0.058888286 0.024249211, 0.14862324 0.05777055 0.020633534, 0.1462929 0.063374698 0.020807043, 0.12748857 0.092068821 -0.031994924, 0.12502593 0.095386207 -0.031994551, 0.12848543 0.091465801 -0.02999483, 0.1257486 0.095900446 -0.027994752, 0.11371554 0.099868625 -0.050836042, 0.11510335 0.098266035 -0.05083622, 0.11323428 0.10258457 -0.046994194, 0.14353305 0.028650761 0.062001556, 0.1432893 0.029846042 0.062001631, 0.14078988 0.027127147 0.067644179, 0.14308773 0.022530228 0.064942181, 0.12820737 0.092587709 -0.027994797, 0.12992147 0.09072414 -0.02640298, 0.14708835 0.060020924 0.024249375, 0.1456167 0.060578555 0.030003339, 0.1451629 0.064466625 0.024413541, 0.11480418 0.10082448 -0.046994299, 0.11425649 0.10350052 -0.042994142, 0.11821131 0.097913593 -0.044994473, 0.13417877 0.087497562 -0.014995188, 0.13361043 0.088730335 -0.01299493, 0.13578069 0.085372418 -0.012995258, 0.13325574 0.088477939 -0.016995013, 0.13541684 0.085133553 -0.016995281, 0.12879096 0.093008846 -0.024242729, 0.13127208 0.089914531 -0.022796348, 0.12799485 0.094674736 -0.022242621, 0.13887976 0.08141759 -0.0019954294, 0.13909175 0.080708981 -0.0072246194, 0.13848428 0.082024276 -0.003612116, 0.13778232 0.083289057 4.7087669e-06, 0.14116432 0.077389032 -0.0019956529, 0.11583565 0.10173002 -0.042994335, 0.11816703 0.099794269 -0.041419476, 0.12934427 0.093408227 -0.020023748, 0.13049829 0.092897773 -0.0149948, 0.12928882 0.093820244 -0.018626869, -0.040501885 0.14265049 -0.057991914, -0.039967462 0.14080626 -0.061992243, 0.13887975 0.081417352 0.0020046681, 0.13886003 0.081240445 0.005789265, 0.14116429 0.077388644 0.0020043105, 0.11670761 0.10249576 -0.039258718, 0.11399557 0.10634768 -0.037258074, 0.11803226 0.1016084 -0.037816718, 0.14357328 0.043192118 0.05428946, 0.14652926 0.043289781 0.047002524, 0.14368179 0.044898719 0.052847594, 0.1417627 0.045840979 0.056446269, 0.14563492 0.038985252 0.052288383, 0.020242259 0.15640929 0.030008808, 0.14264733 0.040498614 0.058002293, 0.14188823 0.074345231 0.015004233, 0.13986658 0.078498065 0.013004556, 0.13948591 0.078286588 0.017004386, 0.14184041 0.073477089 0.01863429, 0.14289102 0.072399497 0.015004113, 0.1422756 0.074697018 0.0092355013, 0.14475088 0.059066594 0.035650656, 0.14266722 0.062461585 0.037823588, 0.14503004 0.057185948 0.037269786, 0.14537662 0.058898538 0.033650473, 0.11747058 0.10316563 -0.035639599, 0.11762777 0.10437319 -0.031994179, 0.14543365 0.046843857 -0.046997279, 0.14199826 0.042718142 0.058002323, 0.13973607 0.046734571 0.060002595, -0.013984606 0.15934229 -0.01699096, -0.010039061 0.16007537 -0.012991086, -0.010014057 0.15964097 -0.016991034, 0.14381057 0.058682621 0.039270118, 0.1442537 0.054378599 0.043003082, -0.0004389286 0.1609849 0.0020091981, 0.0035813302 0.16094589 -0.0019909889, -0.00043897331 0.16098505 -0.0019909143, 0.14224701 0.06072551 0.041426733, 0.0035813004 0.16094565 0.002009064, 0.095111713 0.11125347 -0.061993793, 0.093282938 0.11039937 -0.065536678, 0.093417108 0.11268023 -0.061993659, 0.097820759 0.10683495 -0.064934805, 0.09469533 0.11411482 -0.057993621, 0.098013073 0.11002174 -0.059993804, 0.13022995 0.094047159 -0.010005549, 0.13304552 0.0900971 -0.0093912929, 0.12955864 0.095061958 -0.0092238039, 0.13239171 0.091403753 -0.00578174, 0.14015937 0.042164624 0.062002391, 0.13795541 0.044162184 0.064940393, 0.14356431 -0.028501123 0.061998427, 0.14080277 0.039963871 0.062002227, 0.1427366 0.058244139 0.043003306, 0.0087346435 0.15994707 0.015009061, 0.011655435 0.16038805 0.0072404593, 0.007313028 0.16036367 0.01140359, 0.14171936 0.058956116 0.04500331, 0.013933271 0.15978214 0.013008982, 0.096359581 0.11271295 -0.05799374, 0.1001668 0.11029923 -0.056435332, 0.10470061 0.11128074 -0.046993673, 0.10012904 0.11460036 -0.048658654, 0.10210335 0.11461228 -0.044993624, 0.14609395 -0.025404662 0.057998538, 0.10637291 0.11158729 -0.042993769, 0.10545938 0.110562 -0.046993822, 0.10225488 0.1104787 -0.052836373, 0.13819009 0.081012368 0.015004516, 0.13786647 0.081959963 0.013004646, 0.13749389 0.081734449 0.017004639, 0.13042542 0.094188243 -0.0057817698, 0.012434646 0.15897003 0.020639196, 0.013909504 0.15934709 0.017008901, 0.15406916 0.035667092 -0.027998015, 0.12885621 0.09633553 -0.0056112409, 0.15320124 0.03548485 -0.031997979, 0.13840075 0.041635334 0.065547436, 0.13941926 0.038086534 0.065547228, -0.0044589341 0.16092396 -0.0019909441, 0.14146566 0.057725191 0.047003224, 0.14118883 0.054690272 0.050666869, 0.14298557 0.05385077 0.047002986, 0.13881677 0.060280234 0.050847605, 0.02231361 0.15469018 0.035828426, 0.0281744 0.15377751 0.03565602, 0.097385734 0.11391285 -0.054434389, 0.098090574 0.11449099 -0.052282229, 0.11936688 0.10483012 -0.024242163, 0.11828783 0.10496491 -0.027994126, 0.11579017 0.10876808 -0.024241835, 0.11721753 0.1081048 -0.020625934, 0.11975154 0.10434717 -0.024402127, 0.13051158 0.094250321 -0.0019945651, 0.12806535 0.097548217 -0.0019945651, 0.13116127 0.093368828 5.2750111e-06, 0.15181811 -0.017216593 0.046999052, 0.15318532 -0.017342359 0.04299897, 0.10564126 0.11228034 -0.042993769, 0.10607353 0.11340094 -0.039418593, 0.081242219 0.11571231 -0.071093962, 0.085266322 0.11527377 -0.067638636, 0.085220113 0.11281472 -0.071094275, 0.081887245 0.11267388 -0.074493766, 0.0802605 0.11383855 -0.074493662, 0.080371499 0.11727083 -0.069764569, 0.13654594 0.041077226 0.06903629, 0.13595168 0.041568279 0.069773585, 0.13372478 0.038953245 0.074502155, 0.13427049 0.03702867 0.07450214, 0.13791969 0.036198765 0.069036067, 0.14018898 0.057204217 0.050667003, 0.13929056 0.055470169 0.054290205, 0.11987965 0.10528031 -0.020023063, 0.118568 0.1073643 -0.016993999, 0.12113847 0.10365281 -0.02079545, 0.1305116 0.094249964 0.0020052344, 0.12806541 0.097547948 0.0020054877, -0.014026001 0.15977541 -0.012991071, 0.13195689 0.092158467 0.0036237538, 0.082389787 0.11734676 -0.067638427, 0.085164785 0.11904025 -0.061993361, 0.080321044 0.12054759 -0.064931139, 0.13881713 0.056644082 0.05429019, 0.13604197 0.056593508 0.06000334, 0.023570865 0.15347567 0.039431602, 0.13687272 0.061030298 0.05444631, 0.13417879 0.087495983 0.015004933, 0.13325566 0.088476062 0.017004997, 0.13541679 0.085131556 0.017004654, 0.13361053 0.088728815 0.013005018, 0.13578068 0.085370958 0.013004795, 0.13042541 0.094187617 0.005790025, 0.12928827 0.095577806 0.0077901185, -0.030106328 0.15341544 -0.035636783, -0.024119884 0.15442231 -0.035813317, -0.028512686 0.15268692 -0.039255977, 0.13266383 0.090887517 0.0072364062, 0.12036087 0.10570279 -0.01499401, 0.11889206 0.10765463 -0.012993887, 0.12252791 0.10371703 -0.011390552, 0.12319779 0.10238212 -0.014994219, -0.026658565 0.15544781 -0.029991381, 0.14673693 0.047274768 -0.042997435, 0.1364277 0.079978317 0.028004438, 0.13759854 0.079894096 0.022808164, 0.13629939 0.080822736 0.026414558, 0.13490807 0.081692904 0.030004576, 0.13867866 0.076008588 0.028004169, -0.050976381 0.13271421 -0.069766752, -0.048098855 0.13071933 -0.074492626, -0.049971394 0.13001505 -0.074492618, 0.13758105 0.072086841 0.039270818, 0.13468999 0.07726118 0.039427221, 0.13442229 0.075476319 0.0430042, 0.13779618 0.073850363 0.035651654, 0.13758597 0.072077662 0.039270818, 0.084106073 0.11979058 -0.061993361, 0.080109283 0.12366864 -0.059993014, 0.086273566 0.120608 -0.057993248, 0.13022994 0.094046116 0.010016173, 0.12993756 0.094267398 0.011399806, 0.13049823 0.092896074 0.015005291, 0.14425215 0.050364912 -0.0469971, 0.12070051 0.10600063 -0.010004953, 0.11764489 0.10963628 -0.0072230697, 0.12177619 0.10498217 -0.0077810884, 0.13566281 0.079529911 0.03200455, 0.13790323 0.075578362 0.032004446, 0.13485558 0.079001576 0.035824239, 0.14420013 -0.025086015 0.061998531, 0.13655363 0.071548313 0.043003976, 0.13703474 0.069149166 0.045003921, 0.085209668 0.12136203 -0.057993084, -0.0044590235 0.16092387 0.0020090491, 0.083510458 0.12452129 -0.054282486, 0.12088163 0.10615942 -0.0057808459, 0.12040432 0.10686055 -0.0019941926, 0.13381602 0.054602593 0.065548033, 0.1344859 0.053805262 0.064943984, 0.13122278 0.057775706 0.067645967, 0.10159327 0.11883348 -0.035638765, 0.10159636 0.11749172 -0.039257869, 0.10117242 0.11919194 -0.035638765, 0.10491134 0.11776331 -0.02999337, 0.10569221 0.11513913 -0.035815552, 0.11519507 0.11130998 -0.014993772, 0.11585884 0.11028242 -0.016993716, 0.11307788 0.11313203 -0.016993612, 0.11617187 0.11058456 -0.012993842, 0.11337939 0.113446 -0.012993559, 0.15313914 0.039469242 -0.027997807, 0.13533764 0.07091102 0.047003984, 0.13322189 0.074810237 0.047004193, 0.1333079 0.070414484 0.052290171, 0.13521792 0.069816768 0.048667014, 0.15227896 0.039254695 -0.031997845, 0.086116895 0.12265423 -0.054433867, 0.088339448 0.12106335 -0.054434091, 0.085566401 0.12491792 -0.050658718, 0.069875464 0.12291116 -0.071093515, 0.068757415 0.12113386 -0.074493155, 0.067010552 0.12210909 -0.074493304, 0.070489943 0.12013391 -0.074493244, 0.066681236 0.12604547 -0.069024414, 0.071973875 0.12260228 -0.069767252, 0.1320226 0.053870708 0.069036901, 0.12992957 0.055740088 0.07110174, 0.12852202 0.053680807 0.07450299, 0.12927988 0.051829338 0.074503019, 0.13271031 0.050972432 0.069777176, 0.1293442 0.093406081 0.020034224, 0.12852259 0.094338864 0.020808876, 0.13074198 0.090243846 0.024250925, 0.13204154 0.089393824 0.020635471, 0.14761478 -0.020207524 0.056442484, 0.10218929 0.11953014 -0.031993255, 0.10066627 0.12081572 -0.03199321, -0.008476153 0.1607624 -0.0019909739, 0.10125633 0.12147781 -0.027993158, 0.086965814 0.12386301 -0.050834775, 0.15219158 -0.013521463 0.046999305, 0.15356305 -0.013596058 0.042999312, 0.09035179 0.12141535 -0.050834879, 0.087568641 0.12520957 -0.046992972, 0.070862621 0.12464699 -0.067637905, 0.071595982 0.12592369 -0.064933747, 0.10276541 0.12020382 -0.027993307, 0.10647631 0.11735988 -0.026401505, 0.12879129 0.093006372 0.024251133, 0.12717785 0.09515211 0.02441518, 0.035277307 0.14204675 0.062007993, 0.040571541 0.14164606 0.060008079, 0.035806403 0.1438944 0.058008045, 0.087798297 0.12504852 -0.046993017, 0.088361368 0.12633002 -0.042992964, 0.09299852 0.12358698 -0.041418061, 0.093460143 0.1217632 -0.044993177, 0.12088174 0.10615882 0.005790621, 0.12040427 0.10686046 0.0020059496, 0.11730073 0.11010286 0.0057907552, 0.041991279 0.13279909 0.07450743, 0.04389444 0.13218221 0.074507415, 0.042888567 0.13553646 0.06978181, 0.11813693 0.10891318 0.0094006658, 0.1212862 0.10570699 0.0056245774, 0.1097683 0.11666512 -0.014993504, 0.10655491 0.11960718 -0.014993235, 0.10966136 0.1174435 -0.0093896687, 0.032355875 0.14470926 0.058008149, 0.11051646 0.11623669 -0.012993529, 0.11022681 0.11591175 -0.016993448, 0.10323311 0.12075081 -0.024241328, 0.10371889 0.12078261 -0.022241071, 0.12820734 0.09258455 0.028005183, 0.12574869 0.095897138 0.028005376, 0.12848549 0.091462433 0.030005023, 0.15814263 0.00048610568 0.028000057, 0.088587165 0.12617171 -0.042992979, 0.12070054 0.10599947 0.010016948, 0.11889218 0.10765323 0.013006002, 0.0063745081 0.15930176 0.020812541, 0.010959879 0.15848371 0.024254873, 0.12208672 0.10448349 0.0092372, 0.12748854 0.092065364 0.032005206, 0.12862527 0.089771062 0.033652186, 0.12502599 0.095382601 0.032005414, 0.12450807 0.062436163 -0.074496567, 0.089254111 0.12712133 -0.039257288, 0.0924633 0.12532556 -0.037815288, 0.087473363 0.12904781 -0.037256941, 0.12036085 0.10570109 0.015005872, 0.14553875 0.050844252 -0.042997211, 0.12193382 0.10319716 0.018636078, 0.12319785 0.10238034 0.015005797, 0.11856803 0.10736236 0.017006084, 0.12674469 0.091527849 0.035652518, 0.12866829 0.088024408 0.03727147, 0.12519078 0.092642009 0.037825346, 0.089837551 0.12795225 -0.035638213, 0.091453731 0.12793109 -0.031992868, 0.086823881 0.13063648 -0.033637851, 0.13305458 0.060989439 -0.061996609, 0.12792365 0.074991316 0.0580042, 0.13005826 0.071225286 0.058004126, 0.13008782 0.075745165 0.052849367, 0.12800708 0.076236695 0.056447908, 0.12583235 0.076656967 0.060004398, -0.02189742 0.15844887 -0.016990989, -0.018004119 0.1593762 -0.012991086, -0.017946586 0.15894467 -0.016991138, 0.12592126 0.090933025 0.0392721, 0.12516722 0.090855986 0.041428417, 0.066202492 0.13054085 -0.06199266, 0.066002056 0.13064241 -0.06199266, 0.066928953 0.13232547 -0.057992667, 0.066378787 0.12838885 -0.065535739, 0.071074292 0.12907329 -0.05999276, 0.057876095 0.12899652 -0.071093202, 0.054762766 0.12807059 -0.074492812, 0.057478592 0.13135713 -0.067637607, 0.057980776 0.12894964 -0.071093202, 0.056596458 0.127271 -0.074492946, 0.12630369 0.066176385 0.069037616, 0.12266347 0.06597808 0.074503615, 0.12359846 0.06420964 0.07450363, 0.12170312 0.06773302 0.074503824, 0.12640584 0.06598109 0.069037855, 0.1274479 0.068155259 0.065548867, 0.12329243 0.070778072 0.069775164, 0.11987962 0.10527802 0.020035028, 0.11637019 0.10850963 0.022809938, 0.12059303 0.10393727 0.022251502, 0.09036459 0.12870264 -0.031992793, -0.0084762275 0.16076225 0.0020090342, 0.086101845 0.13214046 -0.02999267, 0.09196566 0.12865463 -0.02799274, 0.074798375 0.13156885 -0.050834328, 0.070155293 0.13344777 -0.052281111, 0.072118327 0.13400784 -0.048657492, 0.078213483 0.13125694 -0.046992585, 0.075107872 0.1304628 -0.052835211, 0.07311216 0.129823 -0.056434333, 0.12626696 0.074019849 0.062004015, 0.12466885 0.073752612 0.064942077, 0.12837894 0.070293337 0.062004015, 0.067071125 0.13225338 -0.057992563, 0.040079549 0.13338861 0.074507415, 0.090874135 0.12942791 -0.027992696, 0.088684306 0.13180673 -0.024240568, 0.11936711 0.1048277 0.024251759, 0.11828789 0.10496163 0.028005928, 0.075514391 0.13282815 -0.046992585, 0.074040279 0.13445899 -0.044992417, 0.078875944 0.13245982 -0.042992562, 0.11519516 0.11130825 0.015006348, 0.1133794 0.11344445 0.013006493, 0.11307782 0.11313018 0.017006308, 0.11585881 0.11028039 0.017006218, 0.11617188 0.11058307 0.013006225, 0.10454333 0.122282 -0.0057800263, 0.10873315 0.11857197 -0.0057801753, 0.10515706 0.12150815 -0.0092222244, 0.1041889 0.1225934 -0.0056098551, -0.043292671 0.14653173 -0.046991855, -0.038638704 0.14976519 -0.041416623, -0.036924966 0.14898914 -0.044991545, -0.038590677 0.14634213 -0.050833561, 0.10709617 0.12021402 6.8247318e-06, 0.15725602 0.00050109625 0.032000124, 0.091287747 0.13001701 -0.024240732, 0.093530044 0.12837821 -0.024400711, 0.090223238 0.13147774 -0.020624697, 0.10461229 0.12236279 -0.0019931793, 0.10314803 0.12359953 -0.0019929856, 0.076192886 0.13402134 -0.042992547, 0.072905332 0.13715339 -0.039256826, 0.031896323 0.1428442 0.062008053, 0.078180447 0.13416132 -0.039417222, 0.12275022 0.088642389 0.050668657, 0.12504646 0.089013577 0.045004994, 0.12192203 0.089658618 0.050849319, 0.12547843 0.084736615 0.050668627, 0.14617668 -0.018523037 0.059998959, 0.12345423 0.085074425 0.054291934, 0.09167996 0.1305753 -0.020021543, 0.0950367 0.12800989 -0.020794109, 0.091704756 0.13105625 -0.016992599, 0.10461232 0.12236258 0.0020068735, 0.10314798 0.12359944 0.0020070374, 0.15808217 0.0043997169 0.02800028, 0.10814117 0.11921096 0.0036252737, 0.076766565 0.13502997 -0.039256811, 0.077421859 0.13577104 -0.03581433, 0.12154904 0.087774754 0.054291859, 0.11985968 0.089957148 0.054447934, 0.1097683 0.11666346 0.015006602, 0.10655488 0.11960554 0.01500684, 0.10883874 0.1165345 0.020636871, 0.028886899 0.1454415 0.058008105, 0.1105164 0.11623538 0.013006613, 0.11022682 0.11590976 0.017006427, 0.11747026 0.10316131 0.035653174, 0.11790769 0.10266122 0.035653129, 0.11762768 0.10436976 0.032005832, 0.11389454 0.10702893 0.035825804, 0.11412024 0.10529557 0.039428964, 0.10454327 0.12228155 0.0057915747, 0.10477854 0.12195083 0.0077915639, 0.0920479 0.1310994 -0.014992684, 0.096376717 0.1283817 -0.011389107, 0.097327039 0.12722936 -0.014992833, 0.088413998 0.13329834 -0.016992584, 0.088651985 0.13366282 -0.012992501, 0.091956034 0.1314114 -0.012992561, -0.021971166 0.158878 -0.012991101, 0.12021573 0.086811721 0.058004931, 0.11771335 0.09017548 0.05800502, 0.1348287 0.061727345 -0.057996556, 0.12003706 0.085446656 0.06000486, 0.11670715 0.10249072 0.039272562, 0.11809699 0.10088637 0.039272487, 0.0208987 0.15135223 0.047008485, 0.024799123 0.15215343 0.043008551, 0.02107586 0.15271369 0.043008581, 0.11425649 0.10349566 0.043005779, 0.053494304 0.13624266 -0.061992377, 0.057273388 0.13678193 -0.057992399, 0.056541279 0.13500673 -0.061992526, 0.024571374 0.15079942 0.04700847, 0.051483765 0.13539836 -0.06493032, 0.050582707 0.13839412 -0.059992135, 0.092307597 0.13146889 -0.010003537, 0.09536238 0.12944791 -0.0077796578, 0.090299055 0.13306591 -0.0072216243, 0.11865889 0.085687011 0.062004849, 0.11614783 0.089060932 0.062004983, 0.11914043 0.082382083 0.064945653, 0.13626999 -0.028822422 0.07449846, 0.11583568 0.10172507 0.043005764, 0.11821119 0.097908765 0.045005485, 0.054196209 0.13802999 -0.057992294, 0.053708732 0.13998219 -0.054281682, 0.092446119 0.13166589 -0.0057794303, 0.09360674 0.13097391 -0.0019926876, 0.089181095 0.13398743 -0.0036091655, 0.11716993 0.084611773 0.065549716, 0.11507563 0.085526705 0.067647517, 0.085705817 0.13533068 -0.014992476, 0.085068643 0.1354579 -0.01699248, 0.085292861 0.13583091 -0.012992382, 0.11480415 0.1008192 0.047005638, 0.11629139 0.098155081 0.048668653, 0.11323425 0.10257909 0.047005847, 0.05477342 0.13949952 -0.054433048, 0.055624709 0.1408264 -0.050657898, 0.059186205 0.13768551 -0.054433033, -0.02976308 0.15639788 -0.022239223, -0.024052322 0.15728515 -0.022792548, -0.025367528 0.15641966 -0.026399359, 0.092507303 0.13175276 -0.0019925684, 0.14345641 -0.020068347 0.064936846, 0.087999836 0.13482222 7.5697899e-06, 0.038929462 0.1359202 -0.071092784, 0.042888641 0.13554433 -0.069766626, 0.040079638 0.13339683 -0.074492484, 0.038159624 0.13395876 -0.074492559, 0.036962509 0.13772333 -0.069023818, 0.11559968 0.083477497 0.069038689, 0.11450455 0.079297185 0.074504554, 0.1180397 0.079225153 0.069778711, 0.11426774 0.083254516 0.07110329, 0.11376819 0.099909037 0.050669327, 0.11429627 0.098312706 0.052291751, 0.10997069 0.10279328 0.052850991, -0.043674737 0.14785016 -0.042991623, -0.040331952 0.15043071 -0.037813991, 0.078852952 0.13869888 -0.02002117, 0.074241996 0.140834 -0.022239968, 0.075778455 0.14062566 -0.018624172, 0.077268392 0.14031923 -0.014992148, 0.079260096 0.13796711 -0.022793606, 0.081670567 0.1375334 -0.016992286, 0.092507273 0.13175243 0.0020074397, 0.089859426 0.13344428 0.0057922155, 0.093606755 0.13097373 0.0020072907, 0.039479345 0.13783997 -0.067637339, 0.041781083 0.13869822 -0.064933032, 0.036146164 0.13994065 -0.065535009, 0.15719563 0.0043816566 0.032000229, 0.11265488 0.098931164 0.054292515, 0.11094762 0.098380029 0.058005646, 0.10323337 0.12074846 0.024252698, 0.10738255 0.1170741 0.024252459, 0.10430759 0.12057254 0.020810381, -0.046841145 0.14543614 -0.046991788, 0.10281551 0.12106618 0.024416581, 0.10491133 0.11775982 0.030006617, 0.092446268 0.13166526 0.0057921708, -0.028431863 0.15719265 -0.018623203, 0.09472321 0.13004544 0.0056259036, 0.090939358 0.1324704 0.0094019324, 0.079169482 0.13925529 -0.014992192, 0.081880584 0.13791475 -0.012992382, 0.10276532 0.12020075 0.028006852, 0.10125636 0.12147456 0.028006852, 0.040301725 0.14071089 -0.061992154, 0.035277262 0.14205381 -0.061992005, 0.040571615 0.14165264 -0.059992149, 0.092307687 0.13146773 0.010018274, 0.091956094 0.13141 0.013007432, 0.095775828 0.12903076 0.0092385411, 0.028497532 0.14356071 0.062008083, 0.079392776 0.13964793 -0.010003075, 0.075482577 0.14186138 -0.0092211962, 0.079622358 0.13979459 -0.0057789832, 0.08077839 0.13890105 -0.0093885362, 0.10218927 0.11952662 0.032006651, 0.10066625 0.12081203 0.0320068, 0.025401279 0.14609066 0.058008239, 0.105424 0.11614197 0.033653572, 0.10564128 0.11227548 0.043006361, 0.10181119 0.11643028 0.041429937, 0.10210329 0.11460719 0.045006439, -0.035665482 0.15407065 -0.027991273, -0.031691745 0.15403208 -0.03199137, -0.03548307 0.15320307 -0.03199143, 0.10637294 0.11158255 0.043006271, 0.1058546 0.11444867 0.03727296, -0.031841569 0.15490609 -0.027991302, 0.040830433 0.14255688 -0.057992071, 0.042391419 0.14283726 -0.056433499, 0.035806403 0.14390093 -0.057991952, 0.038701937 0.14571309 -0.052280411, 0.092047989 0.13109756 0.015007436, 0.095912889 0.12774265 0.018637374, 0.097327039 0.12722766 0.015007153, 0.091704801 0.13105422 0.017007396, 0.088651985 0.13366133 0.013007537, 0.088414103 0.13329631 0.01700744, 0.13331449 0.064933151 -0.057996377, 0.021886185 0.14893186 0.05285348, 0.028061599 0.14812568 0.052294686, 0.10159297 0.11882889 0.035653979, 0.1014367 0.11817676 0.037826568, 0.13156977 0.064129859 -0.06199643, 0.079511955 0.13985729 -0.0057789832, 0.07429716 0.14270386 -0.0056086183, 0.077660993 0.14103115 7.8827143e-06, 0.10859613 0.095366448 0.065550268, 0.10951774 0.097097844 0.06200546, 0.10513085 0.09964481 0.064943612, 0.10445075 0.096438587 0.069776654, 0.10908562 0.094806224 0.065550283, 0.057139829 0.14552552 -0.035637259, 0.06225796 0.14275849 -0.037814334, 0.056564853 0.14527687 -0.037255973, 0.060693696 0.14507395 -0.031991825, 0.055578202 0.14668128 -0.033636883, 0.10470064 0.11127552 0.047006249, 0.1054593 0.11055672 0.047006205, 0.1034762 0.11053357 0.050670028, 0.017213717 0.15181535 0.047008693, 0.0173399 0.15318266 0.043008521, 0.041265294 0.14407453 -0.054432705, 0.044194832 0.14390475 -0.052834377, 0.025833458 0.1390053 -0.07109274, 0.027833909 0.13861868 -0.071092695, 0.026858002 0.1366739 -0.074492395, 0.026808649 0.14085397 -0.067637175, 0.024892285 0.13704562 -0.074492306, 0.022921458 0.13738894 -0.074492246, 0.021531925 0.1405296 -0.069763206, 0.1071409 0.094087988 0.069039315, 0.10490561 0.091618925 0.07450518, 0.10855368 0.092454642 0.069039285, 0.10357884 0.093116254 0.074505255, 0.091679916 0.13057309 0.020036414, 0.094440952 0.12816575 0.022252962, 0.089306682 0.13168368 0.022811219, 0.057475001 0.14637905 -0.03199175, 0.061031803 0.14589337 -0.027991742, 0.054539531 0.14798692 -0.029991612, 0.041672066 0.14549452 -0.050833449, 0.040491208 0.14669579 -0.048656851, 0.026198462 0.14096865 -0.067637056, 0.025082633 0.14420351 -0.061992034, 0.057799041 0.14720407 -0.027991802, 0.057131261 0.14823622 -0.024239779, 0.091287985 0.13001457 0.024253175, 0.09196569 0.12865153 0.028007194, 0.087733179 0.1319567 0.02641739, 0.042071015 0.14688715 -0.046991676, 0.047045633 0.14537033 -0.04699181, 0.042264685 0.14756331 -0.044991732, -0.056596927 0.13604525 -0.059992433, -0.05380895 0.13448933 -0.064933352, -0.058989175 0.13194752 -0.065535523, 0.085705906 0.13532883 0.01500766, 0.085292846 0.13582939 0.013007686, 0.085068539 0.13545603 0.017007589, 0.065574005 0.14615047 -0.014991805, 0.065392882 0.14660877 -0.011388168, 0.0665759 0.14569661 -0.014991969, 0.064169258 0.1459482 -0.020793229, 0.060242951 0.14817661 -0.016991705, -0.047272317 0.14673939 -0.04299175, 0.06040886 0.14857885 -0.012991622, 0.058062091 0.14787394 -0.024239704, 0.062618464 0.1459718 -0.024399698, 0.058704883 0.14825794 -0.020623758, 0.090874061 0.12942484 0.028007329, 0.086101964 0.13213691 0.030007467, 0.07939285 0.13964677 0.010018751, 0.075014815 0.14220878 0.0077927262, 0.076168269 0.14130971 0.011402383, 0.077268347 0.14031753 0.015007883, 0.081880599 0.13791323 0.013007745, 0.080091178 0.13944739 0.0072391778, 0.090364635 0.12869906 0.032007232, 0.091453686 0.12792745 0.032007143, -0.050362319 0.14425471 -0.046991825, 0.087222293 0.12968943 0.03582707, 0.042768478 0.14932215 -0.039256021, 0.046367079 0.14819458 -0.039416566, 0.040558398 0.14993757 -0.039256066, 0.045269191 0.14959508 -0.035813615, 0.097428367 0.1139566 0.054293439, 0.10142745 0.11041254 0.054293275, 0.098913595 0.11454076 0.050850779, 0.098013118 0.11001489 0.060006201, 0.025082588 0.14419651 0.062008113, 0.096836597 0.11437291 0.05444923, 0.079169482 0.13925374 0.015007809, 0.081670612 0.1375314 0.017007679, 0.089837298 0.1279479 0.035654575, 0.092106789 0.12632421 0.03565459, 0.087828115 0.12804955 0.039430186, 0.043048158 0.15029818 -0.035637036, 0.03943865 0.15128547 -0.035637036, 0.13172403 0.068101943 -0.057996213, 0.13001102 0.06723398 -0.061996296, 0.058545709 0.14910495 -0.014991716, 0.056535855 0.14963022 -0.016991615, 0.056686714 0.15003845 -0.012991503, 0.096359655 0.11270633 0.058006376, 0.094695359 0.11410818 0.058006376, -0.039467596 0.1531406 -0.027991474, -0.039252922 0.15228093 -0.031991348, 0.089253739 0.12711635 0.039273873, 0.092686325 0.12463588 0.039273858, 0.088361248 0.12632531 0.043007046, 0.078852922 0.13869652 0.020036861, 0.078638569 0.13803354 0.024253637, 0.080178291 0.13783148 0.020638019, 0.074862212 0.14076009 0.020811498, 0.043300599 0.15117958 -0.031991556, 0.04342702 0.15162045 -0.029991508, 0.027653515 0.14879692 -0.0508333, 0.028725237 0.14859384 -0.050833464, 0.027065024 0.14740372 -0.054432616, 0.022893861 0.14967343 -0.050657377, 0.095111698 0.11124644 0.06200628, 0.093417168 0.11267313 0.062006295, 0.097820833 0.10682768 0.06494692, 0.08858718 0.12616694 0.04300718, 0.091533601 0.12157127 0.048670009, 0.093460128 0.12175819 0.045006931, 0.020204261 0.14761159 0.056451827, 0.043544888 0.1520316 -0.027991503, 0.041042358 0.15382341 -0.022239313, 0.045011953 0.15193608 -0.026399493, 0.078515783 0.13810337 0.024253651, 0.013518766 0.15218878 0.047008559, 0.013593614 0.15356058 0.043008655, 0.027918205 0.15022117 -0.046991587, 0.031374663 0.15025598 -0.044991612, 0.058798894 0.14974943 -0.0057784021, 0.062115446 0.14851955 -0.00199157, 0.064166725 0.14742243 -0.0077786446, 0.058425128 0.14982307 -0.00722076, 0.057130247 0.15047267 -0.0036082417, 0.093918368 0.10985035 0.065551132, 0.093158096 0.10898903 0.067648932, 0.051384732 0.15172172 -0.014991567, 0.052929297 0.15140477 -0.012991473, 0.052793816 0.15099126 -0.016991585, 0.087798387 0.12504324 0.047007009, 0.087568551 0.12520427 0.047007024, 0.043742999 0.15272355 -0.02423957, 0.046572551 0.15214515 -0.022792891, 0.15685116 0.036250591 -0.0019978732, 0.058837876 0.14984834 -0.0019916296, 0.055792615 0.15102386 8.6128712e-06, 0.028169096 0.15157062 -0.042991564, 0.030167431 0.15169874 -0.041416436, -0.00048781931 0.15814102 0.028008908, 0.0033777505 0.15721869 0.032008812, 0.003426224 0.15810448 0.028008893, 0.087006077 0.12391457 0.050670683, 0.084339201 0.12468672 0.052852124, 0.089553267 0.12128106 0.052293062, 0.043930948 0.15337947 -0.020020336, 0.042586669 0.15396222 -0.018623412, 0.05883792 0.14984789 0.0020083487, 0.062115401 0.14851937 0.0020083487, 0.057912305 0.15009415 0.0057931393, 0.028381094 0.15271142 -0.039255828, -0.064663522 0.1257315 -0.071093507, -0.062431976 0.12451211 -0.074493095, -0.064213686 0.12360245 -0.074493155, 0.0058703125 0.1432623 -0.067636959, 0.011652857 0.14168957 -0.069766231, 0.0053903759 0.1424953 -0.069023632, 0.0098711252 0.14451793 -0.064932778, 0.0041010082 0.1444754 -0.0655348, -0.050842062 0.14554125 -0.042991892, 0.086154595 0.12270182 0.054293931, 0.082251102 0.12422675 0.05645059, 0.06557411 0.14614859 0.015008211, 0.06657584 0.14569509 0.015008122, 0.058799028 0.14974889 0.0057931542, 0.085209563 0.12135565 0.058006838, 0.080109254 0.12366188 0.060006872, 0.076766133 0.13502485 0.039274395, 0.073350012 0.13616607 0.041430905, -0.060986027 0.13305786 -0.061992608, 0.077732787 0.13513407 0.037274167, 0.005992651 0.14624599 -0.061991736, 0.0080344081 0.14712924 -0.05999168, 0.044231668 0.15442911 -0.01000227, 0.042023122 0.155101 -0.0092204064, 0.046518907 0.15400717 -0.0057781339, 0.084106073 0.11978364 0.062006786, 0.080321118 0.12054023 0.064944774, 0.076192856 0.13401645 0.043007419, 0.074040428 0.13445371 0.045007586, 0.0060713142 0.14816457 -0.05799178, 0.0095450133 0.148689 -0.056433141, -0.053853519 0.142988 -0.046991937, 0.058545619 0.14910322 0.015008524, 0.044298097 0.15466046 -0.0057781339, 0.040679827 0.15565878 -0.005608052, 0.083050653 0.11828053 0.065551728, 0.080371529 0.11726302 0.069777876, 0.085253581 0.11670285 0.065551549, 0.075514361 0.13282281 0.04700765, 0.076285154 0.13078776 0.05067119, 0.070945382 0.13367921 0.050851732, 0.0061359257 0.14974198 -0.054432318, 0.15685111 0.036250412 0.0020020157, 0.0053080171 0.1506719 -0.052280173, 0.044327438 0.15476272 -0.0019913316, -0.043245532 0.1521171 -0.027991518, -0.042998865 0.15126592 -0.031991407, -0.0076655447 0.14117762 -0.071092568, -0.0052057356 0.14328811 -0.067636922, -0.008224234 0.13904491 -0.074492171, -0.010277703 0.14179757 -0.069763146, 0.081937745 0.11669505 0.069040537, -0.00050291419 0.15725413 0.032008916, 0.080260515 0.11383003 0.074506432, 0.07483305 0.13162392 0.050671071, 0.074314639 0.13021395 0.054294422, 0.029152438 0.15686107 -0.020020112, 0.025760323 0.15786684 -0.016991153, 0.032486171 0.15685841 -0.014991269, 0.030084133 0.15656784 -0.020792469, 0.0083696097 0.15326339 0.045008689, 0.011401445 0.15547836 0.03727521, 0.044327453 0.15476239 0.0020087212, 0.041489482 0.15533552 0.0077934712, 0.045708194 0.15432584 0.0036272854, -0.0077738017 0.14317146 -0.067637034, 0.0070046633 0.1545065 0.041431934, -0.012360364 0.14432809 -0.064929761, 0.074100688 0.1303356 0.054294303, 0.068957597 0.13305348 0.054450318, 0.018519714 0.14617315 0.060008228, 0.05806227 0.14787158 0.024254352, 0.056169882 0.14817077 0.026418343, -0.0044014454 0.1580804 0.028008878, 0.15589701 0.040156096 -0.0019977838, 0.051384687 0.15171999 0.01500845, 0.044298083 0.15466002 0.0057934374, 0.047053054 0.1537731 0.007240057, 0.01198256 0.15093434 0.050672367, 0.029269502 0.1574904 -0.014991149, 0.025832519 0.15829587 -0.01299113, 0.031129733 0.15748444 -0.011387333, 0.057798952 0.14720103 0.028008372, 0.054539442 0.14798358 0.030008286, -0.0079357624 0.14615354 -0.061991751, -0.014472067 0.14663616 -0.059991822, 0.044231728 0.15442795 0.0100196, 0.042813987 0.15471587 0.011403203, 0.029352024 0.15793434 -0.010001898, -0.061724201 0.13483179 -0.05799254, 0.057474986 0.14637548 0.032008246, 0.056176409 0.14584669 0.03582792, 0.0063593984 0.15519616 -0.039255634, 0.010846585 0.15591791 -0.035813302, 0.0061776638 0.15520346 -0.039255664, -0.0080398619 0.14807078 -0.057991698, -0.012344956 0.14942333 -0.054281108, 0.057139695 0.14552107 0.035655662, -0.054381028 0.14425591 -0.042991988, 0.026858032 0.13666564 0.074507609, 0.02881816 0.13626578 0.074507639, 0.027223632 0.13996512 0.069041982, 0.0064010024 0.15621054 -0.035636634, 0.0047861189 0.15626836 -0.035636604, 0.021742731 0.15870464 -0.014991134, 0.021822751 0.15845919 -0.016991109, 0.017871752 0.15895319 -0.016991109, 0.017911687 0.15938661 -0.012991041, 0.021878943 0.15889066 -0.012991071, -0.0081254542 0.14964721 -0.054432437, -0.010984853 0.15101525 -0.05065725, -0.0064132959 0.14973053 -0.054432526, 0.067071155 0.13224688 0.058007419, -0.021050245 0.13980958 -0.071092628, -0.013984635 0.15934038 0.01700893, -0.010014072 0.15963906 0.017008975, -0.010039106 0.16007403 0.013008997, -0.021766558 0.13757676 -0.074492365, -0.023740217 0.13724998 -0.074492358, 0.070473701 0.12395528 0.069040954, 0.066827074 0.1245884 0.071105614, -0.014026046 0.15977409 0.013008982, 0.067010567 0.12210053 0.074506834, 0.11563164 0.077652842 -0.074495673, 0.11673494 0.07598412 -0.074495777, -0.030886352 0.1578939 -0.0056079477, -0.024909154 0.15893951 -0.0057779253, -0.029434219 0.15797451 -0.0092201531, 0.043931007 0.15337712 0.020037651, 0.041662917 0.1538893 0.020812169, 0.045951277 0.15207148 0.024254501, 0.0064386278 0.15712649 -0.031991214, 0.0085998625 0.15748256 -0.029991284, 0.020064756 0.14345264 0.064945832, 0.026173666 0.14213541 0.065553054, -0.008205533 0.15112224 -0.050833173, -0.0050595552 0.15126029 -0.05083333, 0.066202477 0.13053393 0.062007308, -0.027213752 0.15868333 9.0450048e-06, 0.0064748824 0.1580123 -0.027991116, 0.010074839 0.15814281 -0.026399121, 0.15589704 0.040155888 0.0020021796, 0.043743163 0.15272117 0.024254471, 0.040104404 0.15368655 0.024418518, -0.060590409 0.13805389 -0.052280925, -0.008284077 0.15256867 -0.0469914, -0.0028465688 0.1534704 -0.044991329, 0.014166623 0.15955949 -0.014991134, 0.0065042526 0.1587314 -0.024239182, 0.0057846904 0.15909958 -0.02223891, -0.0043834895 0.15719381 0.032008931, 0.043544769 0.15202859 0.028008595, -0.0083585531 0.1539391 -0.042991325, -0.0043444484 0.15460825 -0.041416436, 0.029352114 0.15793315 0.010019794, 0.03248623 0.15685663 0.015008807, 0.030306444 0.15780821 0.0092401952, 0.025832593 0.15829453 0.013008863, 0.043300673 0.15117598 0.032008573, 0.044590771 0.15038189 0.033655614, -0.0084214211 0.1550979 -0.039255708, -0.0120693 0.15543291 -0.037255362, -0.0058472306 0.15563387 -0.037813619, 0.054797336 0.13955459 0.05429475, 0.0525451 0.13941461 0.05645138, 0.029269576 0.15748847 0.015008792, 0.025760293 0.15786496 0.017008841, 0.030988589 0.15670708 0.018638998, 0.021532133 0.14052168 0.069779187, 0.043048054 0.15029365 0.035655826, 0.040115386 0.15048507 0.03782846, 0.045713291 0.14904308 0.037275016, -0.0084765702 0.15611169 -0.035636604, -0.013567597 0.15627 -0.033636287, 0.054196224 0.13802353 0.058007777, 0.050582722 0.1383872 0.060007825, -0.0083124042 0.15792295 0.028008863, 0.042768344 0.14931697 0.039275214, 0.041210517 0.14907402 0.041431665, -0.028654248 0.14353648 -0.061992064, 0.13881765 -0.011391193 0.074499324, 0.13863982 -0.013383836 0.074499309, -0.064929947 0.13331762 -0.057992548, 0.029152468 0.15685871 0.020037904, -0.06412638 0.13157323 -0.061992623, 0.1482842 0.00065368414 0.058000058, -0.0085262209 0.15702716 -0.031991154, 0.05349426 0.13623583 0.06200771, 0.051483691 0.13539109 0.064945474, 0.042448908 0.14820188 0.043008283, -0.029030263 0.14541948 -0.057991803, -0.0085742623 0.15791216 -0.027991205, -0.015070021 0.15699559 -0.02999115, -0.012843326 0.15834463 -0.024239168, -0.022748888 0.15109038 -0.046991594, -0.025945008 0.15128806 -0.044991583, 0.021742642 0.15870303 0.015008822, 0.02182278 0.15845737 0.01700893, 0.021878958 0.1588892 0.013008848, 0.017911673 0.15938514 0.013008952, 0.017871737 0.15895137 0.017008945, 0.0065869093 0.16074458 -0.0057778805, 0.0050226003 0.16080818 -0.0056076795, 0.052823126 0.13452619 0.065552577, -0.0086133629 0.15863091 -0.024239138, -0.0069169849 0.15868536 -0.024399042, 0.14311638 0.065173745 -0.03199628, -0.011434913 0.15904692 -0.020623103, 0.0065912455 0.1608507 -0.0019908547, 0.0087790042 0.16076046 8.9854002e-06, -0.022953361 0.15244761 -0.042991541, -0.022522986 0.1536369 -0.039416172, 0.041691378 0.14555609 0.05067195, 0.039419562 0.14611432 0.050852478, 0.043475375 0.14348575 0.054295078, -0.0086503327 0.15931219 -0.020020112, -0.0055095702 0.15933684 -0.02079235, 0.0065912008 0.1608505 0.0020091087, 0.010221317 0.16062772 0.0036275536, -0.023126185 0.15359506 -0.039255805, -0.04130774 0.13730308 -0.067637287, -0.044165842 0.13795906 -0.064930163, 0.041283369 0.14413145 0.054295063, 0.037620857 0.14506194 0.054451019, 0.014166608 0.15955785 0.015008941, 0.0065869391 0.16074407 0.0057936758, 0.0058836937 0.16067335 0.0077936798, 0.13896686 -0.0093961358 0.074499533, -0.0086851269 0.15995148 -0.014991, -0.0046940297 0.16046292 -0.011387274, -0.0032323003 0.16015434 -0.014990985, -0.0082612485 0.15703782 0.032008901, 0.040830493 0.14255026 0.05800803, 0.028380975 0.15270621 0.039275438, 0.029428929 0.15250805 0.039275467, -0.046539314 0.15251487 -0.02062349, -0.040826969 0.15411592 -0.020792589, -0.042054117 0.15316769 -0.024399318, -0.042168275 0.14016277 -0.061992176, -0.046738043 0.13973925 -0.059992149, -0.0087095797 0.16040245 -0.010002002, -0.068098642 0.13172725 -0.057992652, -0.0061517358 0.1606639 -0.0077779889, -0.067230545 0.13001445 -0.061992735, -0.01236631 0.16033569 -0.0072201639, 0.040301681 0.14070398 0.062007859, 0.14636372 0.00068625808 0.062000096, 0.041781068 0.13869101 0.064948738, 0.028169125 0.1515657 0.043008521, 0.031374633 0.15025097 0.045008481, -0.042721458 0.14200157 -0.057992078, -0.045284517 0.14292997 -0.054281451, -0.0087226778 0.16064289 -0.005777806, -0.013815016 0.16035905 -0.0036077648, 0.039796114 0.13893816 0.065552711, 0.036642253 0.13861516 0.067650467, -0.07029698 0.12838235 -0.061992854, -0.066858828 0.12683979 -0.067637943, -0.070782036 0.12329629 -0.069764286, 0.1439354 0.065514356 -0.027996331, -0.016286016 0.15935701 -0.014991075, 0.02791819 0.15021583 0.047008485, 0.14822616 0.0041986406 0.058000281, 0.029719785 0.14924669 0.048671588, -0.045286253 0.15341011 -0.01699134, -0.043176427 0.14351338 -0.054432742, -0.039570019 0.14454934 -0.054432698, -0.044312812 0.14478436 -0.050657623, -0.0087284893 0.16074905 -0.0019908845, -0.053417251 0.13090596 -0.071093053, -0.051833592 0.12928391 -0.07449282, -0.053685047 0.12852621 -0.07449279, -0.056968324 0.13072303 -0.069024183, 0.039262697 0.13707584 0.069041654, 0.037427112 0.13633496 0.07110621, -0.02189745 0.15844697 0.017009094, -0.017946646 0.15894282 0.017008841, -0.018004075 0.15937462 0.013008997, 0.038159564 0.13395029 0.074507535, 0.13908751 -0.00739941 0.074499637, -0.030786492 0.1542154 -0.031991445, -0.021971151 0.15887648 0.013008997, 0.15221052 0.013302088 0.047000781, 0.027666286 0.1488601 0.050672114, 0.15357712 0.013432592 0.043000728, -0.04360202 0.14492792 -0.050833508, -0.0087284148 0.16074863 0.002009064, -0.036250442 0.15685117 -0.0019912124, -0.032322317 0.15770721 0.0020088702, -0.032322325 0.15770748 -0.0019911379, -0.01525934 0.16027516 9.1344118e-06, -0.012946367 0.16035739 0.0057937354, -0.054171763 0.13275471 -0.067637533, -0.030960053 0.15508464 -0.027991243, 0.0065043569 0.15872902 0.024254724, 0.0049000829 0.15875745 0.024418786, -0.030017011 0.1579541 0.0077935755, -0.024326578 0.15896031 0.0072403699, -0.025778159 0.15887502 0.0036274642, -0.0087227672 0.16064245 0.0057937354, -0.0070246309 0.16073239 0.0056276321, -0.011494964 0.1602692 0.0094036162, -0.023849994 0.15840155 -0.014991149, -0.027076289 0.15788224 -0.014991134, 0.006474793 0.15800914 0.028008908, 0.008599773 0.1574792 0.030008793, -0.0087096095 0.16040128 0.010019809, -0.0055691898 0.1605953 0.0092404187, -0.023917332 0.15884811 -0.010001808, -0.02344802 0.15896168 -0.0093874484, 0.0064385682 0.15712306 0.032008931, 0.010009214 0.1565339 0.033655852, -0.073756419 0.12467241 -0.064930931, -0.0086850822 0.15994969 0.015009061, -0.0046592355 0.15967369 0.018639252, -0.0032323897 0.16015279 0.015008941, 0.0064009726 0.15620598 0.035656124, 0.0056230575 0.15563861 0.037828863, -0.045407429 0.1538282 -0.012991413, -0.041748568 0.15526676 -0.0077780932, -0.040282562 0.15539521 -0.011387691, -0.045041874 0.14971277 -0.035636865, -0.046353266 0.14885017 -0.037255727, -0.048000269 0.14933285 -0.033636771, -0.056622349 0.13875934 -0.05443304, -0.055168428 0.1400649 -0.052834749, -0.055912502 0.13810581 -0.056433909, -0.065618463 0.12523562 -0.071093529, 0.13136414 0.07803157 -0.046995491, -0.071228407 0.13006148 -0.057992786, -0.065982342 0.1226674 -0.074493118, -0.067737371 0.12170729 -0.074493125, 0.026054651 0.14018738 0.069041818, 0.022921428 0.13738066 0.074507728, 0.024892226 0.13703731 0.074507803, -0.028554872 0.15797034 0.011403441, -0.0086504668 0.15930998 0.020037949, -0.0060740113 0.15908673 0.022254571, -0.012281537 0.15863591 0.02281262, -0.045305938 0.15059063 -0.031991549, -0.049626596 0.14970595 -0.029991612, 0.14630614 0.0041593909 0.0620002, -0.057180487 0.14012688 -0.050833866, -0.059804469 0.13993785 -0.048657171, -0.045561478 0.15143952 -0.027991571, -0.047755949 0.15151674 -0.024239533, -0.0086133629 0.15862858 0.024254784, -0.013682067 0.15786821 0.02641888, -0.057727978 0.14146829 -0.046992011, -0.058958702 0.14172181 -0.044991955, -0.016286045 0.15935537 0.015008971, -0.036250539 0.15685096 0.0020087212, 0.14226994 0.069056481 -0.027996048, 0.14146443 0.068685859 -0.031996056, -0.038798966 0.15541726 -0.014991403, -0.038788818 0.15541977 -0.014991313, -0.045768909 0.15212864 -0.024239488, -0.0085743368 0.15790901 0.028008908, -0.031516515 0.15787047 -0.0019911379, -0.058246642 0.14273894 -0.042992048, -0.056145109 0.14477295 -0.039416783, -0.061773323 0.14251411 -0.039256416, 0.0061992556 0.15128225 0.050672174, 0.0059170276 0.15122259 0.05085285, 0.010456204 0.14956227 0.05429548, -0.0085262209 0.15702367 0.032009065, 0.15184216 0.016997755 0.047000915, -0.015070051 0.15699226 0.030008748, 0.15320311 0.017179281 0.043001026, -0.012668118 0.15577698 0.035828456, -0.040156014 0.15589696 -0.0019912422, -0.031516515 0.15787017 0.0020088106, -0.058685131 0.14381328 -0.039256416, -0.057876945 0.14518365 -0.035813756, 0.0061386973 0.14980137 0.054295376, 0.0043975413 0.14979631 0.054451376, -0.023849964 0.15839976 0.015008882, -0.027076125 0.15788046 0.015008852, -0.0084765851 0.15610713 0.035656229, -0.01117219 0.15487251 0.039431632, -0.0067510754 0.15619135 0.035656199, -0.059068874 0.14475328 -0.035637274, -0.060580261 0.14561844 -0.029991828, -0.063489348 0.14286971 -0.03563749, -0.046150044 0.15339506 -0.014991418, -0.049090862 0.15223542 -0.016991436, -0.049227521 0.15264842 -0.012991346, 0.0060712844 0.14815798 0.058008388, 0.0028884113 0.14825431 0.058008373, 0.0080343336 0.14712256 0.060008347, -0.0084214509 0.15509281 0.039275616, -0.0096803755 0.15385684 0.043008626, -0.005245626 0.15523273 0.039275587, -0.074023306 0.12627032 -0.061992966, -0.076660402 0.12583581 -0.059993014, -0.023754671 0.15776625 0.020037934, -0.024581313 0.15694895 0.024254739, -0.023251519 0.15775117 0.020639151, 0.13253886 0.078741461 -0.042995617, -0.029233605 0.15672609 0.020812407, -0.07024134 0.1340571 -0.050834276, -0.070742473 0.13212013 -0.054433495, -0.075418733 0.13129389 -0.050658338, -0.070186637 0.13408577 -0.050834276, -0.074812874 0.13322449 -0.046992548, 0.0059926659 0.14623904 0.062008217, 0.0027836412 0.14633527 0.062008195, 0.0098709613 0.14451072 0.064949125, -0.0083584785 0.15393418 0.043008626, 0.12942879 0.081201345 -0.046995506, -0.0028464794 0.15346512 0.045008689, -0.074994631 0.12792683 -0.057992816, -0.075953431 0.12926978 -0.05428233, -0.070913799 0.13534024 -0.046992406, -0.075478867 0.13442463 -0.042992555, -0.069151744 0.13703707 -0.044992365, -0.046349682 0.15405801 -0.0057781786, -0.04773429 0.15356407 -0.007220611, -0.049151808 0.15326437 -0.0036080778, -0.044036597 0.1548456 -0.0019913316, 0.0059174299 0.1444039 0.065553077, 0.0048780292 0.14329326 0.067650743, -0.079229094 0.11804366 -0.069767565, -0.077648811 0.1156359 -0.074493602, -0.079301536 0.11450872 -0.074493594, -0.07598 0.11673909 -0.074493416, -0.053396538 0.15102556 -0.014991537, -0.052865192 0.15096635 -0.016991548, -0.056606412 0.14960361 -0.016991578, -0.056773871 0.15000555 -0.012991458, -0.05301699 0.15137404 -0.012991488, -0.0082841218 0.15256333 0.047008559, -0.0096013844 0.15248623 0.047008649, -0.0042364597 0.152118 0.048671767, -0.075793229 0.12928879 -0.054433562, -0.060022198 0.14708918 -0.024239719, -0.058448173 0.14798951 -0.022793055, -0.059537806 0.14685318 -0.026399814, -0.06381844 0.14585376 -0.022239901, -0.046380341 0.15415984 -0.0019913465, -0.050541438 0.15286142 8.59797e-06, 0.14051734 0.072556376 -0.027995914, 0.13972647 0.072155803 -0.031995878, -0.071550779 0.13655588 -0.042992353, -0.040155992 0.15589675 0.0020087063, -0.072794348 0.1376844 -0.03781458, -0.070995398 0.1374124 -0.041417331, 0.0058381855 0.14246827 0.06904199, 0.0061505735 0.14124492 0.071106553, 0.011652857 0.14168158 0.069782175, -0.0082092732 0.15118638 0.050672211, -0.011803672 0.15006787 0.052853495, -0.0056037158 0.15065619 0.052294642, -0.060280144 0.1477209 -0.020020671, -0.062697582 0.14692491 -0.018623903, -0.061529242 0.1478987 -0.014991768, -0.046380259 0.15415952 0.0020086169, -0.048304699 0.15345606 0.0057933927, -0.044036619 0.15484548 0.0020086467, -0.083942071 0.11624125 -0.067638464, -0.082385801 0.11914408 -0.064934127, -0.080937877 0.11335787 -0.074493587, -0.084627733 0.11476889 -0.069024988, -0.086870581 0.11551318 -0.065536469, -0.0081290007 0.14970666 0.054295368, -0.013149679 0.14840642 0.056451946, -0.0077444166 0.14807996 0.058008336, -0.038799047 0.15541562 0.015008718, -0.041165531 0.1553297 0.009240225, -0.045407407 0.15382674 0.013008609, -0.04007341 0.15463364 0.018638998, -0.038788818 0.1554181 0.015008703, -0.046349697 0.15405756 0.0057933033, -0.046870232 0.15369302 0.0094030946, -0.042614974 0.15513939 0.005627349, -0.060521998 0.14831358 -0.014991745, -0.030960061 0.15508139 0.028008655, -0.030550003 0.1558674 0.024418607, -0.031841546 0.15490282 0.028008766, -0.026658639 0.15544438 0.030008689, -0.0080398023 0.1480642 0.058008492, -0.085690625 0.11866224 -0.061993316, -0.089064457 0.11615139 -0.06199339, -0.090178959 0.11771646 -0.057993397, -0.085450068 0.1200403 -0.059993349, 0.15406907 0.035663903 0.028002083, -0.060692854 0.14873165 -0.010002531, -0.059651792 0.14941171 -0.0057785213, -0.058232419 0.14975849 -0.0093878657, -0.063848659 0.14746401 -0.0092209056, -0.030786484 0.15421188 0.032008693, -0.029151231 0.15298757 0.037828483, -0.025074244 0.15483648 0.033655763, -0.031691685 0.15402842 0.032008648, -0.0079357475 0.14614642 0.062008291, -0.0076337159 0.14616248 0.062008306, 0.011386931 0.13881338 0.074507765, 0.013379589 0.13863555 0.074507743, -0.014472112 0.1466293 0.060008302, -0.012360498 0.14432076 0.064945981, -0.00065694749 0.14828092 0.05800838, -0.022953317 0.15244278 0.043008626, -0.020918176 0.15273523 0.043008618, -0.02348198 0.15411711 0.037275091, 0.107494 0.088576436 -0.074495047, -0.027552366 0.15219137 0.041431852, -0.025944978 0.15128297 0.045008428, -0.086815 0.12021899 -0.057993293, -0.085241497 0.12220165 -0.056434728, 0.13057636 0.081954956 -0.042995408, -0.046150088 0.15339354 0.015008621, -0.049227543 0.15264702 0.013008662, -0.045286261 0.15340829 0.017008595, -0.049090847 0.1522336 0.017008446, -0.06078402 0.14895472 -0.0057785437, -0.061841808 0.14864919 8.3893538e-06, -0.065246798 0.14706236 -0.005608432, -0.0078362077 0.14431256 0.065553121, -0.010277778 0.14178982 0.069779173, -0.0061114728 0.14439586 0.065553144, -0.022748947 0.15108508 0.047008507, -0.02068609 0.15138149 0.047008537, -0.021904558 0.14981639 0.050672174, -0.087739259 0.1214987 -0.054433927, -0.089790635 0.12110996 -0.052281931, -0.08495193 0.12427703 -0.052835561, -0.093293138 0.10623533 -0.07109452, -0.091019109 0.10819012 -0.071094476, -0.090107031 0.10621479 -0.074493952, -0.093406275 0.10878226 -0.067638971, -0.091623217 0.1049096 -0.074494086, -0.093120523 0.10358292 -0.074494205, -0.096442506 0.10445461 -0.069765352, -0.0077311397 0.14237821 0.069041863, -0.0082243383 0.13903663 0.074507765, -0.0062263608 0.13914031 0.074507862, -0.0046050251 0.14251366 0.069042154, -0.079531662 0.13566458 -0.031992361, -0.075580165 0.13790506 -0.031992272, -0.078312993 0.13480362 -0.037256569, -0.080026105 0.13490775 -0.033637434, -0.081694759 0.13490963 -0.029992543, -0.076010182 0.13868019 -0.027992189, -0.065172009 0.14311808 -0.031991966, -0.022543609 0.14972141 0.050672144, -0.023087397 0.14813918 0.054295383, -0.027882114 0.14874771 0.050852552, 0.127417 0.084323168 -0.046995297, -0.088604145 0.12269622 -0.050834768, -0.089443386 0.12312159 -0.048658118, -0.089015983 0.12504888 -0.044992983, -0.094610967 0.10773572 -0.067638941, -0.09964852 0.10513434 -0.064931974, -0.097101547 0.10952109 -0.061993942, -0.079979941 0.13642916 -0.027992308, -0.080273867 0.13709113 -0.02424036, -0.045769051 0.15212634 0.024254486, -0.041322134 0.15374646 0.022254363, -0.047273763 0.15192577 0.022812329, -0.048468448 0.15086558 0.026418559, -0.043245465 0.15211391 0.028008573, -0.053396545 0.15102383 0.015008524, -0.052865021 0.15096435 0.017008454, -0.053017072 0.15137261 0.013008617, -0.056773834 0.15000418 0.013008505, -0.05660636 0.14960158 0.017008498, -0.060783975 0.14895406 0.0057930201, -0.060484879 0.14915544 0.0036269799, -0.064412661 0.1473144 0.007792972, -0.059088655 0.14956161 0.0072397217, -0.07434608 0.14188907 -0.014992133, -0.078287661 0.13948685 -0.016992144, -0.078498729 0.13986713 -0.012992084, -0.074097097 0.14116704 -0.020793341, -0.073851198 0.14253554 -0.011388399, -0.072400376 0.14289182 -0.014991924, -0.04556144 0.15143636 0.028008498, -0.049626626 0.14970267 0.030008376, -0.060692869 0.14873055 0.010019392, -0.062990703 0.14765555 0.011402726, -0.061529234 0.14789701 0.015008241, 0.15320125 0.035481334 0.032002032, -0.045306027 0.15058717 0.03200841, -0.04299885 0.15126222 0.032008469, -0.047014587 0.14905241 0.035828143, 0.0093920082 0.13896257 0.074507691, -0.090935677 0.12592399 -0.039257258, -0.091936678 0.12519532 -0.039257497, -0.088731647 0.12866461 -0.035814859, -0.086952068 0.12864977 -0.03941761, -0.060522027 0.148312 0.015008315, -0.045041725 0.14970836 0.035655692, -0.045354933 0.14850345 0.039431266, -0.041338131 0.15077296 0.035655878, -0.091530189 0.12674704 -0.035638414, -0.093688592 0.12515998 -0.035638563, 0.15313923 0.039466023 0.028002188, -0.081013247 0.1381909 -0.014992356, -0.081735432 0.13749486 -0.016992263, -0.081960633 0.13786712 -0.012992203, -0.098891042 0.11260849 -0.054434419, -0.098367698 0.11306599 -0.05443453, -0.098383322 0.11095083 -0.057993792, -0.10281368 0.10912755 -0.054283366, -0.10274301 0.11121997 -0.050659373, -0.029030219 0.14541298 0.058008112, -0.024905697 0.14522162 0.06000822, -0.029046133 0.14701912 0.05445113, -0.030174434 0.14517978 0.058008127, -0.044749036 0.1487354 0.039275281, -0.043674722 0.14784524 0.043008402, -0.039657198 0.15017352 0.039275348, -0.00068990886 0.14636004 0.062008217, -0.10296881 0.096886218 -0.071095102, -0.10350893 0.097453952 -0.069768734, -0.10005098 0.096905202 -0.07449463, -0.10279285 0.093991399 -0.074494645, -0.104132 0.092505395 -0.074494794, -0.10143232 0.09545809 -0.074494667, -0.10804339 0.093060076 -0.069026321, -0.060280219 0.14771867 0.020037316, -0.063375846 0.1462917 0.020811766, -0.05888968 0.14754412 0.024254151, -0.057771727 0.14862198 0.020638637, -0.092067078 0.12749019 -0.031992868, -0.095384434 0.12502763 -0.031992994, -0.091464102 0.12848699 -0.029992811, -0.095898911 0.12575012 -0.027992927, -0.099865921 0.11371839 -0.050835222, -0.10258202 0.11323705 -0.046993643, -0.065512702 0.14393678 -0.027991883, -0.098263219 0.11510611 -0.050835334, -0.028654233 0.14352953 0.062008083, -0.029849634 0.14328566 0.06200809, -0.027130991 0.14078599 0.067650549, -0.022533998 0.14308408 0.064949065, -0.0042018741 0.14822286 0.058008388, 0.12853599 0.085119337 -0.042995185, -0.09258616 0.12820891 -0.027992822, -0.090722673 0.1299229 -0.026400827, -0.060022302 0.14708677 0.024254128, -0.064468086 0.14516133 0.024418049, -0.060580246 0.14561495 0.030008219, 0.13921969 0.0042231083 0.074500293, 0.13926609 0.002222985 0.074500144, -0.10082185 0.1148068 -0.046993621, -0.097911164 0.11821371 -0.044993415, -0.10349823 0.11425883 -0.042993583, -0.087496758 0.13417947 -0.014992595, -0.085371479 0.13578129 -0.01299233, -0.085132547 0.1354177 -0.016992472, -0.088476941 0.13325655 -0.016992562, -0.088729531 0.1336112 -0.012992479, 0.0073951036 0.13908312 0.074507862, -0.093007639 0.12879226 -0.02424071, -0.094673663 0.12799597 -0.022240743, -0.013304844 0.1522077 0.047008485, -0.013435036 0.15357456 0.043008596, -0.089913361 0.1312733 -0.022794008, -0.081417456 0.13887978 -0.0019921958, -0.077388927 0.14116421 -0.0019920468, -0.080708615 0.139092 -0.0072214231, -0.077388942 0.14116406 0.0020078495, -0.082024142 0.13848442 -0.0036088675, -0.083289042 0.13778237 7.6666474e-06, -0.10172767 0.11583793 -0.042993531, -0.099792019 0.11816919 -0.041418448, -0.093407221 0.12934542 -0.020021752, -0.092896938 0.13049912 -0.014992803, -0.093819275 0.12928975 -0.018624865, -0.081417464 0.13887951 0.0020078942, -0.081240982 0.13885969 0.0057924688, -0.10249352 0.11670974 -0.039257847, -0.10634565 0.11399758 -0.037257664, -0.10160625 0.11803427 -0.037815839, -0.043195188 0.14356992 0.054295011, -0.043292597 0.14652655 0.047008283, -0.044901744 0.14367878 0.052853115, -0.045844242 0.14175951 0.056451499, -0.038988099 0.14563191 0.052294284, -0.040501989 0.14264402 0.058007993, -0.074346155 0.14188749 0.015008032, -0.078498729 0.13986579 0.013007991, -0.078287616 0.13948482 0.017007902, -0.073478028 0.14183927 0.018638082, -0.074697576 0.14227486 0.0092393532, -0.072400413 0.14289019 0.015008062, -0.05906862 0.14474878 0.035655588, -0.05718796 0.14502788 0.037274629, -0.058900297 0.14537475 0.033655249, -0.062463656 0.14266512 0.037828118, -0.10316359 0.11747262 -0.035638846, -0.10437137 0.11762932 -0.031993374, -0.042721488 0.14199498 0.05800797, -0.046738014 0.1397326 0.060007833, -0.058684848 0.14380816 0.039274938, -0.060727865 0.14224449 0.041431226, -0.05438108 0.14425102 0.043008186, -0.11125002 0.095115215 -0.061994664, -0.11001834 0.098016351 -0.059994482, -0.10683142 0.097824246 -0.064935461, 0.15227894 0.039251149 0.032002226, -0.11039566 0.093286544 -0.065537684, -0.11267672 0.093420506 -0.061994851, -0.11411151 0.094698519 -0.05799485, -0.09404669 0.13023034 -0.010003492, -0.095061481 0.12955904 -0.0092217475, -0.090096585 0.13304585 -0.0093887523, -0.091403462 0.13239196 -0.0057792813, -0.042168275 0.14015588 0.062007926, -0.044165723 0.13795179 0.06494575, -0.039967448 0.14079934 0.062007956, -0.058246501 0.14273399 0.043008015, -0.058958687 0.14171663 0.045007862, -0.1127096 0.096362859 -0.057994537, -0.11029599 0.10016987 -0.056435905, -0.11127813 0.1047031 -0.046994045, -0.11055937 0.10546172 -0.046994135, -0.11047564 0.10225767 -0.052836865, -0.11459745 0.10013166 -0.048659407, -0.11460976 0.10210592 -0.044994228, -0.11158496 0.10637525 -0.042994171, -0.081013232 0.13818926 0.015007772, -0.081960678 0.13786563 0.013007849, -0.081735313 0.13749281 0.017007738, -0.094187975 0.13042554 -0.0057795718, -0.07802894 0.13136679 -0.046992682, -0.096335292 0.12885633 -0.0056095347, -0.041639142 0.13839698 0.065552749, -0.038090207 0.13941553 0.065552942, -0.057728097 0.14146286 0.047007881, -0.054693274 0.14118585 0.050671637, -0.053853586 0.14298281 0.047008105, -0.060283132 0.13881376 0.050852068, -0.11390986 0.097388715 -0.054435357, -0.11448817 0.09809339 -0.052283131, -0.10482875 0.11936805 -0.024241365, -0.10876672 0.1157915 -0.024241596, -0.10810384 0.11721864 -0.020625487, -0.10496334 0.11828941 -0.027993388, -0.10434579 0.11975276 -0.024401113, -0.094250202 0.13051167 -0.0019927695, -0.097548038 0.12806547 -0.001992777, 0.11552374 0.09297052 -0.057994708, -0.093368836 0.13116118 7.4356794e-06, 0.11400163 0.09179911 -0.061994866, -0.11227789 0.10564369 -0.042994037, -0.11339878 0.1060757 -0.039418928, -0.0041630417 0.14630252 0.062008277, -0.11570837 0.081246078 -0.071095966, -0.11526999 0.085270137 -0.067640133, -0.11281087 0.085224122 -0.07109578, -0.11266967 0.081891447 -0.074495479, -0.11383423 0.080264628 -0.074495591, -0.11726692 0.080375344 -0.0697667, -0.041081138 0.13654202 0.069041744, -0.041572206 0.13594764 0.069778882, -0.038957596 0.1337204 0.074507505, -0.037032902 0.13426617 0.074507505, -0.036202602 0.13791567 0.069041766, -0.057207055 0.14018616 0.050671577, -0.055473343 0.13928747 0.054294869, -0.10527908 0.11988071 -0.020022377, -0.1073632 0.11856881 -0.016993396, -0.069054969 0.14227158 -0.027992062, -0.10365167 0.12113953 -0.020794511, -0.068684034 0.14146632 -0.031992063, -0.094250113 0.1305114 0.002007328, -0.092158645 0.13195661 0.003625907, -0.097547933 0.12806505 0.002007097, -0.11734281 0.082393497 -0.067640372, -0.11903683 0.085168242 -0.061995253, -0.12054409 0.08032468 -0.064933509, -0.056647137 0.13881409 0.054294802, -0.05659689 0.13603848 0.060007639, -0.061033517 0.13686964 0.054450564, -0.087496892 0.13417798 0.015007541, -0.088729501 0.1336098 0.013007566, -0.088477015 0.13325474 0.017007492, -0.085132532 0.13541582 0.017007522, -0.085371606 0.13577992 0.013007767, -0.094188049 0.13042507 0.0057919919, -0.095578335 0.12928757 0.0077920631, -0.090887941 0.13266331 0.0072388947, -0.017000422 0.15183932 0.047008529, -0.017181829 0.15320051 0.043008633, -0.10570174 0.12036178 -0.014993265, -0.10371652 0.12252825 -0.01138936, -0.10238124 0.12319857 -0.014993154, -0.10765389 0.118893 -0.012993366, -0.079980031 0.13642609 0.028007746, -0.076010101 0.13867679 0.028007828, -0.079895444 0.13759717 0.02281145, -0.080824234 0.1362977 0.026417643, -0.08169473 0.13490626 0.030007645, -0.072089083 0.13757861 0.039274625, -0.072080016 0.13758355 0.039274581, -0.07385236 0.1377942 0.035655111, -0.077263512 0.13468772 0.039430574, -0.075478807 0.13441986 0.043007657, -0.11978728 0.084109575 -0.06199526, -0.12060478 0.086276859 -0.057995126, -0.12366521 0.080112606 -0.059995517, -0.094046816 0.13022935 0.010018259, 0.14656107 0.06660524 -0.0019962341, -0.092896909 0.13049728 0.01500728, -0.094268046 0.12993675 0.011401825, -0.10600007 0.12070096 -0.010004126, -0.10963599 0.1176455 -0.0072224066, -0.10498182 0.1217767 -0.0077800825, 0.13996826 0.075083911 -0.024403781, -0.079531699 0.13566086 0.032007672, -0.079003498 0.13485357 0.035827324, -0.07558009 0.1379016 0.032007724, -0.071550868 0.13655114 0.043007672, -0.069151767 0.13703206 0.045007624, -0.12135889 0.085212767 -0.057995245, -0.12451845 0.083513409 -0.054284893, -0.10615918 0.12088186 -0.0057801455, -0.10686052 0.12040436 -0.0019932538, -0.054606423 0.13381237 0.065552518, -0.053808898 0.13448215 0.064948499, -0.057779558 0.13121897 0.067650013, -0.078739151 0.13254124 -0.042992607, -0.11883126 0.10159519 -0.035639711, -0.1177616 0.10491285 -0.029994234, -0.11513728 0.10569403 -0.035816006, -0.11748956 0.10159847 -0.03925883, -0.11918995 0.10117447 -0.03563983, -0.11130916 0.11519578 -0.014993533, -0.11028136 0.11585972 -0.016993612, -0.11313116 0.11307868 -0.016993642, -0.1134451 0.1133801 -0.012993589, -0.11058383 0.11617255 -0.012993358, 0.13833387 0.079311192 -0.020627588, -0.070913792 0.13533491 0.04700771, -0.070417367 0.13330483 0.05229383, -0.069819547 0.13521516 0.048670717, -0.074812971 0.1332193 0.047007456, 0.11326805 0.095705926 -0.057994694, -0.12265123 0.08611992 -0.054435953, -0.1249152 0.085569263 -0.05066096, -0.12106035 0.088342369 -0.054435991, 0.11179115 0.094478607 -0.061994612, -0.12290708 0.069879383 -0.071096554, -0.12112981 0.068761587 -0.074496225, -0.12210486 0.067014694 -0.074496269, -0.1201298 0.070494264 -0.074496023, -0.12604168 0.06668511 -0.069027849, -0.1225985 0.071977764 -0.069770075, -0.053874604 0.13201869 0.069041431, -0.055744305 0.12992552 0.071105883, -0.053685032 0.12851766 0.074507385, -0.05183363 0.12927559 0.074507274, -0.050976276 0.13270625 0.069781713, -0.081198707 0.12943143 -0.04699266, -0.093407281 0.12934306 0.020036221, -0.090245366 0.13074076 0.024253309, -0.089395031 0.13204029 0.020637706, -0.094340056 0.12852129 0.020810716, -0.11952845 0.102191 -0.031994201, -0.12081384 0.10066792 -0.031994328, -0.12147626 0.10125786 -0.027994357, -0.12386017 0.08696869 -0.050836794, -0.12520695 0.087571263 -0.046995141, -0.12141238 0.090354592 -0.050836787, -0.12464319 0.070866436 -0.06764102, -0.12592013 0.071599513 -0.064936906, -0.12020235 0.10276678 -0.027994215, -0.11735845 0.10647759 -0.026402071, -0.093007781 0.12878972 0.024253152, 0.14656103 0.066604972 0.0020038635, -0.095153518 0.12717643 0.024416924, -0.12504593 0.08780092 -0.046995044, -0.12358446 0.09300074 -0.041419908, -0.12176076 0.093462646 -0.04499463, -0.12632768 0.088363588 -0.042995043, -0.072554804 0.14051881 -0.027992137, -0.072153948 0.13972816 -0.031992026, -0.1061592 0.12088135 0.0057915226, -0.10686067 0.12040406 0.0020068362, -0.11010321 0.11730048 0.0057912394, -0.10891369 0.11813635 0.0094011649, -0.10570735 0.1212858 0.0056255683, -0.11666425 0.10976902 -0.014993794, -0.11744316 0.10966173 -0.0093901381, -0.11623599 0.11051714 -0.012993842, -0.11591084 0.11022773 -0.01699385, -0.11960648 0.10655567 -0.014994033, -0.12074938 0.1032345 -0.024242274, -0.12078144 0.10372004 -0.022242144, -0.092586182 0.12820572 0.028007194, -0.09146414 0.12848359 0.030007191, -0.0958988 0.12574697 0.028007075, -0.12616941 0.088589489 -0.042995073, -0.10600013 0.12069985 0.010017693, -0.10765385 0.11889142 0.013006806, -0.10448413 0.12208593 0.0092382357, -0.092067085 0.12748665 0.032007135, -0.089772902 0.12862325 0.033654213, -0.095384426 0.12502405 0.032007001, -0.12711927 0.089256287 -0.039259471, -0.12532362 0.092465311 -0.037817128, -0.12904578 0.08747533 -0.037259184, -0.10570168 0.12036005 0.015006788, -0.10319826 0.12193272 0.018637106, -0.10238125 0.12319684 0.015007004, -0.10736322 0.11856705 0.01700668, -0.091529913 0.1267426 0.035654478, -0.092644207 0.12518862 0.037827089, -0.088026553 0.12866625 0.037273765, -0.12795028 0.089839518 -0.035640366, -0.12792942 0.091455489 -0.031994902, -0.13063452 0.086825848 -0.033640325, -0.074994504 0.12792024 0.058007136, -0.071228474 0.13005498 0.05800724, -0.075748049 0.13008484 0.052852482, -0.076239958 0.12800378 0.056450807, -0.076660417 0.12582895 0.060007133, -0.090935193 0.12591892 0.039273977, -0.090858147 0.12516484 0.041430317, -0.13053736 0.066205859 -0.061996348, -0.13063881 0.066005439 -0.061996415, -0.13232225 0.066932142 -0.05799628, -0.12838529 0.066382498 -0.065539174, -0.12906995 0.071077555 -0.059996039, -0.12899263 0.057879925 -0.071097307, -0.12894569 0.05798462 -0.071097329, -0.12726676 0.0566006 -0.074496806, -0.13135338 0.057482302 -0.06764181, -0.12806648 0.054766864 -0.074496984, -0.035665534 0.15406752 0.028008617, -0.066180117 0.12629977 0.069040932, -0.064213805 0.12359422 0.074506931, -0.065985024 0.12640199 0.069041274, -0.068158895 0.12744418 0.065552123, -0.070781991 0.12328845 0.069778241, -0.067737408 0.12169883 0.074506789, -0.065982379 0.12265918 0.074506834, -0.10527927 0.11987856 0.020035654, -0.10851089 0.11636892 0.022810377, -0.10393857 0.12059164 0.022252485, 0.14208376 0.075252205 -0.007782653, -0.12870094 0.090366304 -0.031995021, -0.13213879 0.086103588 -0.029995263, -0.12865314 0.091967136 -0.027994819, -0.13156591 0.074801117 -0.05083748, -0.13344502 0.070158064 -0.052284703, -0.13400513 0.072120935 -0.048660971, -0.12981993 0.073115259 -0.056437418, -0.088572361 0.10749805 -0.074494101, -0.13125445 0.078215986 -0.04699567, -0.13045964 0.075110793 -0.052838415, -0.074023411 0.12626335 0.062007152, -0.073756412 0.12466508 0.064944893, -0.070296913 0.12837541 0.062007234, -0.13225019 0.067074239 -0.057996288, -0.081952684 0.13057879 -0.042992599, -0.12942646 0.090875536 -0.027994856, -0.13180545 0.088685483 -0.024243116, -0.10482907 0.1193656 0.024252601, -0.10496341 0.11828616 0.028006569, -0.13282561 0.075516999 -0.046995677, -0.13245749 0.078878343 -0.042995691, -0.13445632 0.074042797 -0.0449958, -0.11130924 0.11519429 0.015006468, -0.11028137 0.11585784 0.017006427, -0.11058389 0.11617118 0.013006561, -0.11344517 0.11337855 0.013006404, -0.11313114 0.11307675 0.017006263, -0.12228183 0.10454336 -0.0057810917, -0.12021407 0.10709605 6.0126185e-06, -0.11857183 0.10873345 -0.0057807788, -0.12150759 0.10515752 -0.0092232674, -0.12259311 0.1041891 -0.0056108683, -0.1300157 0.091289014 -0.024242945, -0.12837683 0.093531191 -0.024402723, -0.13147661 0.090224355 -0.020626977, -0.12236266 0.10461232 -0.0019941926, -0.12359948 0.10314804 -0.0019942001, 0.14485198 0.070244133 0.0020039678, 0.14485206 0.070244372 -0.0019960999, -0.13401893 0.07619524 -0.042995758, -0.13715127 0.072907418 -0.039260507, -0.13415918 0.078182608 -0.039420404, -0.088645376 0.12274733 0.05067075, -0.085077614 0.12345114 0.05429408, -0.084739476 0.12547553 0.050670855, -0.089016058 0.12504396 0.04500708, -0.08966133 0.12191918 0.050851069, -0.13057421 0.091680825 -0.020023905, -0.12800874 0.095037758 -0.020795867, -0.13105533 0.091705561 -0.016994812, -0.084320553 0.12741956 -0.046992816, -0.12236265 0.10461211 0.0020057559, -0.11921119 0.10814098 0.0036246628, -0.1235996 0.1031478 0.0020057932, -0.1350278 0.076768667 -0.039260104, -0.13576928 0.077423781 -0.035817645, -0.087777786 0.12154588 0.054293811, -0.089960366 0.11985666 0.05444961, -0.11666425 0.10976744 0.015006259, -0.11653581 0.10883746 0.020636402, -0.11591084 0.11022583 0.017006181, -0.11960643 0.106554 0.015006013, -0.11623595 0.11051574 0.013006218, -0.10316323 0.11746812 0.035654001, -0.10437141 0.1176258 0.032006629, -0.10703087 0.11389235 0.035826229, -0.10529774 0.11411798 0.039429344, -0.10266317 0.11790556 0.035654016, -0.12228183 0.10454276 0.0057905763, -0.12195131 0.10477805 0.0077905208, -0.13109839 0.092048854 -0.014994845, -0.12838128 0.096377313 -0.011390895, -0.12722853 0.097327679 -0.014994517, -0.13329746 0.088415027 -0.01699502, -0.1336621 0.088652641 -0.012994982, -0.13141072 0.091956675 -0.012994789, -0.086814947 0.12021241 0.058006853, -0.085450105 0.12003362 0.060006812, -0.090178862 0.11770999 0.058006592, -0.035483018 0.15319937 0.032008536, -0.10249306 0.11670488 0.039273404, -0.10349815 0.11425394 0.043006279, -0.10088862 0.11809471 0.039273508, -0.13623938 0.053497702 -0.061997004, -0.13500315 0.056544662 -0.061996862, -0.13539475 0.051487267 -0.064935014, -0.13839072 0.050586134 -0.059997261, -0.13677877 0.057276696 -0.057996869, -0.13146824 0.092308015 -0.01000575, -0.12944746 0.095362753 -0.0077815875, -0.13306552 0.090299338 -0.0072240904, -0.085690759 0.11865535 0.062006794, -0.082385615 0.11913663 0.06494765, -0.089064419 0.11614433 0.062006652, -0.10172771 0.11583304 0.043006435, -0.097911149 0.11820874 0.045006655, -0.13802692 0.054199398 -0.057996951, -0.13997915 0.053711563 -0.05428642, -0.039467663 0.15313765 0.028008573, -0.13166556 0.092446476 -0.0057817772, -0.1309738 0.09360683 -0.001994662, -0.13398729 0.089181334 -0.0036116466, -0.084615506 0.11716637 0.065551586, -0.085530654 0.11507171 0.067649186, -0.13532975 0.085706592 -0.014995188, -0.13545701 0.085069597 -0.016995102, -0.13583021 0.085293531 -0.012995221, -0.10082183 0.11480129 0.047006391, -0.10258196 0.11323157 0.047006398, -0.09815789 0.11628851 0.048669621, -0.13949651 0.054776132 -0.054437749, -0.13768245 0.0591892 -0.05443754, -0.14082357 0.055627614 -0.050662547, -0.13175268 0.092507333 -0.0019947812, -0.13482217 0.087999612 5.0365925e-06, -0.083481528 0.11559582 0.069040559, -0.083258592 0.11426371 0.071105078, -0.079229154 0.11803573 0.069780894, -0.079301469 0.11450011 0.074506402, -0.099912062 0.11376521 0.05067011, -0.10279615 0.10996768 0.052851267, -0.09831553 0.11429313 0.052292608, -0.13869765 0.078853935 -0.02002456, -0.14083275 0.074243098 -0.022243828, -0.14062458 0.075779289 -0.0186278, -0.14031816 0.077269137 -0.014995687, -0.13796592 0.079261363 -0.022797003, -0.13753252 0.081671417 -0.016995423, -0.1317527 0.092507213 0.0020052493, -0.085117072 0.12853828 -0.042992763, -0.13097374 0.093606621 0.002005294, -0.13344461 0.089859128 0.0057897791, -0.098934144 0.11265162 0.054293446, -0.098383315 0.1109443 0.058006227, -0.0042272806 0.13921538 0.074507803, -0.0022273064 0.13926178 0.074507855, -0.12074976 0.10323188 0.024251729, -0.11776168 0.10490957 0.03000579, -0.11707544 0.10738111 0.024251908, -0.12057371 0.10430637 0.020809323, -0.12106742 0.10281417 0.024415582, -0.13166562 0.09244585 0.0057898089, -0.1300458 0.094722778 0.0056238696, -0.132471 0.090938896 0.0093996674, -0.13925445 0.079170227 -0.014995649, -0.13791385 0.081881225 -0.012995444, -0.12020234 0.10276359 0.028005891, -0.1214762 0.10125473 0.028005734, 0.14305271 0.073839486 0.0020041913, 0.14305277 0.073839724 -0.0019958168, -0.13146824 0.092306882 0.010016128, -0.12903121 0.095775127 0.009236753, -0.13141081 0.091955364 0.013005197, -0.13964741 0.079393268 -0.01000642, -0.13979428 0.079622597 -0.0057824701, -0.13890055 0.080778807 -0.0093917623, -0.14186083 0.075483054 -0.0092248842, 0.14736407 0.037977457 0.048665375, 0.1489867 0.036922306 0.045002028, -0.11952849 0.10218734 0.032005861, -0.12081386 0.10066438 0.032005638, -0.11614399 0.10542205 0.033653043, -0.11227793 0.1056388 0.043005943, -0.11445073 0.10585228 0.037272461, -0.11643254 0.10180882 0.041428916, -0.11158498 0.10637039 0.043005906, -0.11460976 0.10210079 0.045005575, -0.13109848 0.092047155 0.015005156, -0.13105536 0.091703713 0.017005101, -0.12774375 0.09591189 0.018635534, -0.13329756 0.088413149 0.017004944, -0.13366199 0.088651389 0.013005003, 0.10561897 0.10274211 -0.059994161, -0.12722841 0.09732613 0.015005425, -0.11883094 0.1015909 0.035653099, -0.11817887 0.10143456 0.037825719, -0.13985689 0.079512239 -0.0057824552, -0.14270377 0.074297369 -0.0056125373, -0.095370017 0.10859236 0.065551095, -0.099648483 0.1051271 0.064943835, -0.096442498 0.10444671 0.069777198, -0.0948098 0.10908189 0.065551125, -0.097101405 0.10951412 0.062006123, -0.14552355 0.057141632 -0.035642214, -0.14507219 0.06069544 -0.031996496, -0.14275634 0.062260002 -0.037818804, -0.14527479 0.056566715 -0.03726095, -0.14667943 0.055580139 -0.033642016, -0.11127808 0.10469785 0.047005787, -0.11053653 0.10347316 0.05066973, -0.11055937 0.1054565 0.047005773, -0.094091818 0.10713699 0.069039911, -0.091623224 0.10490134 0.074505992, -0.092458576 0.10854974 0.069040194, -0.0931205 0.10357451 0.074505828, -0.13057423 0.09167859 0.020034172, -0.039252773 0.15227705 0.032008529, -0.13168502 0.089305401 0.022808738, -0.12816715 0.094439656 0.022251055, -0.14637719 0.05747667 -0.031996876, -0.1458919 0.061033398 -0.027996585, -0.14798516 0.054541022 -0.029996969, -0.14720252 0.057800442 -0.027996674, -0.1482348 0.057132453 -0.024244852, -0.13001592 0.091286451 0.024250895, -0.13195828 0.08773154 0.026414864, -0.1286532 0.091963917 0.028005242, 0.13787104 0.019784063 0.074501142, 0.13814108 0.017801881 0.074500963, 0.14072636 0.020163447 0.069775283, -0.13532975 0.085704923 0.015004739, 0.14442031 0.0336335 0.058001906, -0.14614952 0.065574765 -0.014996387, -0.14569584 0.06657666 -0.014996305, -0.14787264 0.058063418 -0.024244785, -0.14597058 0.062619716 -0.024404518, -0.12942633 0.090872318 0.028005145, -0.13213867 0.086100161 0.030004799, -0.13964747 0.079392195 0.010015428, -0.14131039 0.076167613 0.011398725, -0.14031827 0.077267557 0.015004314, -0.12870096 0.090362698 0.032005079, -0.12969139 0.087220192 0.035824597, -0.12792921 0.091451734 0.032005236, -0.11395969 0.097425312 0.054292545, -0.11001834 0.098009676 0.060005568, -0.11041563 0.10142437 0.054292642, -0.11454352 0.098910809 0.050849773, -0.114376 0.096833408 0.054448284, -0.13925451 0.079168558 0.015004359, -0.12795001 0.089835376 0.03565231, -0.12805203 0.087825924 0.039427795, -0.092967272 0.11552694 -0.057993531, -0.12632608 0.092104673 0.035652608, -0.14910406 0.058546513 -0.0149967, -0.09179569 0.11400509 -0.061993688, -0.11270972 0.096356273 0.058005422, -0.12711875 0.089251459 0.039271891, -0.12463806 0.092683911 0.0392721, -0.13869774 0.078851789 0.020033374, -0.13803509 0.078637123 0.024250358, -0.13783291 0.080176979 0.020634808, -0.14076133 0.07486093 0.020807654, -0.11125003 0.095108181 0.062005378, -0.12616929 0.088584572 0.04300493, -0.12157411 0.09153071 0.048668243, -0.12176085 0.09345758 0.045005277, -0.13810483 0.078514427 0.024250373, -0.1497491 0.058799148 -0.0057836473, -0.15047255 0.057130456 -0.0036135092, -0.10985413 0.093914598 0.065550223, -0.1517209 0.051385462 -0.014997214, -0.12504593 0.087795526 0.047004998, -0.14984819 0.058837891 -0.0019966885, -0.15102383 0.05579263 3.1590462e-06, -0.12391749 0.087003142 0.050668597, -0.12468977 0.084336311 0.052849937, 0.13757257 0.021762341 0.074501067, -0.12128405 0.089550257 0.052291207, -0.14984822 0.058837652 0.0020032525, -0.15009457 0.057911843 0.0057879165, -0.12270478 0.086151421 0.054291904, -0.12422994 0.082247794 0.056448247, -0.14614955 0.065573156 0.015003748, -0.14569591 0.066574991 0.015003748, -0.14974914 0.058798522 0.0057879314, -0.066605024 0.14656115 -0.0019919202, -0.12135892 0.085206211 0.058004748, -0.12366521 0.080105811 0.060004421, -0.075082511 0.13996968 -0.0244001, 0.13907619 0.025430471 0.071100056, -0.13502717 0.076763868 0.039271314, -0.13513617 0.077730626 0.037270911, -0.13616849 0.073347479 0.041427448, 0.14254059 0.033237964 0.062001884, -0.11978722 0.084102362 0.062004872, -0.12054409 0.080317348 0.064942494, -0.1340189 0.076190382 0.043004371, -0.13445637 0.07403779 0.045004167, -0.14910412 0.058544785 0.015003264, -0.11828414 0.083047032 0.065549672, -0.11726688 0.080367386 0.069775812, -0.11670655 0.085249692 0.065549821, -0.13282558 0.075511664 0.04700416, -0.13079062 0.076282173 0.050668094, 0.14357485 0.037076622 0.058002129, -0.13368218 0.070942402 0.050848205, -0.116699 0.081933767 0.06903854, -0.11383423 0.080256432 0.074504569, -0.07930997 0.13833496 -0.020624377, -0.13162683 0.074830174 0.050668046, -0.1302169 0.074311525 0.054291382, -0.095702656 0.1132713 -0.057993636, -0.13033876 0.074097455 0.054291207, -0.13305648 0.068954527 0.054446775, -0.14787297 0.058060765 0.024249099, -0.094475113 0.11179459 -0.06199383, -0.14817211 0.056168407 0.026413191, -0.15172093 0.051383823 0.015002776, 0.13724591 0.023735851 0.074501306, -0.14720251 0.057797343 0.028003294, -0.14798521 0.054537654 0.030003045, -0.14637715 0.057473153 0.032003243, 0.14543369 0.046838611 0.047002614, 0.14673701 0.047269762 0.043002769, -0.14584856 0.056174248 0.035822868, -0.14552321 0.057137638 0.035650678, -0.13225019 0.067067742 0.058003798, -0.12395926 0.070469826 0.069037944, -0.12459233 0.066823006 0.071102276, -0.12210482 0.06700629 0.074503735, -0.13053742 0.066198796 0.062003847, -0.066605084 0.14656082 0.0020082816, -0.13955766 0.054794192 0.054289974, -0.1394178 0.052541763 0.056446556, -0.13802692 0.054192901 0.058003109, -0.1383907 0.05057925 0.060002971, -0.13623939 0.053490698 0.062003054, -0.13539483 0.051479965 0.064940885, -0.13452989 0.052819371 0.065548062, -0.070244282 0.1448521 -0.0019919723, 0.11070746 0.10530642 -0.046994045, 0.14171149 0.036611348 0.062002108, -0.075251877 0.14208397 -0.0077789277, 0.12333675 0.098983198 -0.027994424, 0.1226341 0.098442405 -0.031994388, 0.14425224 0.050359607 0.047002971, 0.14553869 0.050839424 0.043002918, -0.070244305 0.14485192 0.0020080879, 0.14393538 0.065511227 0.028003573, 0.14176731 0.076068044 0.0056228042, -0.073839635 0.14305279 -0.0019919425, 0.11169478 0.10626003 -0.042994007, 0.1394106 0.079894483 0.009398967, 0.10811532 0.10796613 -0.046993822, 0.1208494 0.10200515 -0.027994201, 0.12016745 0.1014387 -0.031994283, 0.14311634 0.065170288 0.032003805, -0.073839597 0.1430524 0.0020080507, -0.037980326 0.14736122 0.048671417, -0.036924921 0.14898401 0.045008294, 0.14226989 0.069053262 0.028003901, -0.10273864 0.1056222 -0.059994042, 0.085089669 0.11027536 -0.074493945, 0.083497092 0.11148617 -0.074493796, 0.10906635 0.10895628 -0.042994037, 0.14069796 0.074496806 0.022249877, -0.01978837 0.13786677 0.074507751, -0.017806202 0.13813683 0.074507773, -0.020167425 0.14072236 0.069782063, -0.033636808 0.14441705 0.058008075, 0.14146444 0.068682134 0.032003835, 0.14051731 0.072553188 0.028004214, 0.11371608 0.10804093 -0.033639014, -0.021766528 0.13756827 0.074507795, 0.13478848 0.035096258 0.074501947, 0.13527873 0.033156812 0.074501991, -0.025434524 0.139072 0.071106352, -0.033241555 0.14253691 0.062007956, -0.037080005 0.1435715 0.058007993, -0.023740172 0.1372416 0.074507639, 0.13972646 0.072152197 0.032004103, -0.046841182 0.14543086 0.047008187, -0.047272362 0.14673442 0.043008283, 0.091940075 0.11634612 -0.057993531, 0.090716869 0.1148653 -0.061993584, 0.11334677 0.10966793 -0.029993832, -0.10530385 0.11071011 -0.0469938, -0.036614843 0.14170808 0.062007904, -0.098981619 0.12333819 -0.02799312, -0.098440744 0.12263578 -0.031992979, -0.050362326 0.14424953 0.047008209, -0.050841846 0.14553615 0.043008275, 0.089132309 0.11851093 -0.057993367, 0.087965548 0.1169858 -0.061993539, -0.065512709 0.14393371 0.028008126, -0.076068319 0.14176691 0.0056265891, -0.10625766 0.11169717 -0.042993717, -0.079895191 0.13941014 0.0094024539, -0.10796349 0.10811788 -0.046993941, 0.12558948 0.10071582 -0.0019944459, -0.10200378 0.12085071 -0.02799318, -0.10143689 0.12016922 -0.031993218, -0.065172039 0.14311448 0.032008126, -0.069054887 0.14226815 0.028008096, 0.12558952 0.10071561 0.0020056516, -0.11027128 0.085093707 -0.074495167, -0.11148208 0.08350116 -0.074495338, -0.10895381 0.10906863 -0.042993836, 0.12303524 0.10382062 -0.0019941628, -0.074498191 0.14069661 0.02225367, 0.13482869 0.061720967 0.058003351, -0.0686839 0.14146262 0.032008044, 0.072208077 0.11910912 -0.074493378, -0.072554745 0.14051566 0.028007925, 0.12303525 0.10382038 0.00200589, -0.10803915 0.11371785 -0.033638835, -0.035100572 0.13478425 0.074507542, -0.033160985 0.13527444 0.074507669, 0.13305454 0.060982496 0.062003434, 0.13001095 0.04996711 0.07450299, 0.13071533 0.04809466 0.074502677, 0.13331448 0.064926594 0.058003709, -0.07215403 0.13972455 0.032007977, -0.11634286 0.091943264 -0.057994805, -0.11486182 0.090720266 -0.061995029, 0.1167601 0.11078334 -0.0036104769, -0.10966627 0.11334845 -0.02999378, 0.13156976 0.064122915 0.062003642, 0.13172399 0.068095356 0.058003858, 0.13136417 0.078026205 0.047004431, 0.13253888 0.078736663 0.043004394, 0.10797328 0.11687091 -0.022794798, -0.11850768 0.089135349 -0.057994917, -0.11698227 0.087969005 -0.061995022, 0.084499657 0.1273008 -0.046992779, 0.10517049 0.1202375 -0.01862523, 0.11579429 0.11186019 6.2435865e-06, 0.13001102 0.067227006 0.062003776, 0.098218992 0.12394649 -0.027992934, 0.097654238 0.12326288 -0.031992972, 0.12942883 0.08119601 0.04700461, 0.13057637 0.081950158 0.043004557, 0.085249722 0.12845033 -0.042992905, 0.081380457 0.12931719 -0.046992719, -0.10071573 0.12558937 0.00200703, -0.10071567 0.12558964 -0.001992844, 0.095121428 0.12633938 -0.027992919, 0.094582796 0.12563527 -0.031992987, 0.12741701 0.084317803 0.047004789, 0.12853594 0.085114509 0.043004841, -0.061724238 0.13482532 0.058007516, 0.12333681 0.098979801 0.02800554, 0.058418587 0.12644491 -0.074492931, -0.11910491 0.072212249 -0.074495986, 0.082087398 0.13049394 -0.042992651, -0.10382053 0.12303519 0.0020068288, -0.10382051 0.12303537 -0.0019930229, 0.1226341 0.09843874 0.032005623, -0.060986035 0.13305098 0.062007412, -0.049971446 0.13000691 0.074507423, -0.048099011 0.13071108 0.074507415, -0.064929955 0.13331112 0.058007397, 0.12084921 0.10200217 0.028005794, 0.12450805 0.06242767 0.074503526, -0.11078323 0.11676022 -0.0036100298, 0.12016745 0.10143515 0.032005861, -0.064126365 0.13156629 0.06200736, -0.068098664 0.13172072 0.058007404, 0.063746408 0.1338875 -0.057992533, 0.062883213 0.13217187 -0.06199263, -0.078028917 0.13136145 0.047007486, -0.078739189 0.13253635 0.043007456, 0.052261963 0.13221517 -0.06976372, 0.052917793 0.12884405 -0.074492842, -0.11686981 0.10797447 -0.02279529, -0.12729841 0.08450219 -0.04699523, -0.12023658 0.1051715 -0.018626034, -0.11186017 0.11579424 6.4224005e-06, 0.060527191 0.13537353 -0.057992399, 0.059729099 0.133627 -0.061992511, -0.067230545 0.13000745 0.062007241, 0.11489698 0.10912582 0.026416212, -0.1239449 0.098220557 -0.027994432, -0.12326108 0.097655892 -0.031994544, -0.081198648 0.12942606 0.047007352, -0.081952654 0.13057393 0.043007374, 0.10911319 0.11812925 0.0072379261, -0.12844804 0.085252047 -0.042995334, -0.12931454 0.081383079 -0.046995483, 0.10570307 0.12081778 0.011401325, 0.11334674 0.10966456 0.030006066, -0.12633774 0.095122844 -0.027994707, -0.12563349 0.094584495 -0.031994663, 0.10002938 0.1261366 0.0020072013, 0.10002938 0.12613696 -0.0019930154, -0.084320508 0.12741423 0.04700724, -0.085117064 0.12853339 0.043007262, -0.098981611 0.12333494 0.028006934, -0.12644088 0.058422655 -0.074496821, -0.13049164 0.082089752 -0.042995416, 0.072113678 0.13871649 -0.035637766, 0.076076508 0.13815561 -0.029992312, 0.041991308 0.13280755 -0.074492633, 0.04389444 0.1321907 -0.074492589, 0.096848249 0.12859529 0.0020071864, 0.096848235 0.12859559 -0.0019927621, -0.098440729 0.12263224 0.032007024, -0.10200371 0.12084758 0.028006852, 0.11563168 0.077644438 0.074504346, 0.11673489 0.075975686 0.074504226, 0.11552361 0.092964143 0.058005184, -0.062432088 0.12450376 0.074507013, 0.071258724 0.14018694 -0.031992063, 0.061069712 0.13847637 -0.050834104, -0.10143702 0.12016571 0.032006644, 0.057511955 0.14155626 -0.046992034, 0.063166872 0.14118251 -0.041417211, 0.064022526 0.13950735 -0.044992253, 0.11400169 0.091792017 0.062005207, 0.071686625 0.14096373 -0.027992085, 0.113268 0.095699281 0.058005393, -0.13388443 0.063749343 -0.057996511, -0.1321685 0.062886626 -0.061996542, 0.11335365 0.08093366 0.074504539, 0.11070752 0.10530105 0.047005966, 0.11169475 0.10625529 0.043005958, -0.13221115 0.052265793 -0.069768161, -0.12883988 0.052921891 -0.074496917, 0.077691972 0.13811061 -0.026400298, 0.058035314 0.14282501 -0.042991951, 0.054054469 0.14291218 -0.046992064, 0.11179121 0.094471544 0.062005341, -0.1353703 0.060530305 -0.057996564, -0.13362344 0.059732467 -0.061996691, -0.10912737 0.11489543 0.026416585, 0.068176091 0.14269477 -0.027991936, 0.067777529 0.14190277 -0.031992003, 0.1081153 0.10796082 0.047006071, 0.10906641 0.1089513 0.043006212, -0.11812989 0.10911277 0.0072373971, 0.054529935 0.14419976 -0.042991862, 0.050564975 0.14418378 -0.046991929, -0.12081853 0.10570243 0.011400409, 0.064623639 0.14433831 -0.027991876, 0.064255193 0.14353201 -0.031992003, -0.10966626 0.11334509 0.030006342, 0.10783269 0.10280934 0.056449354, -0.1261369 0.10002923 0.0020055845, -0.12613684 0.10002947 -0.0019944534, 0.098218963 0.12394333 0.028007001, 0.028818175 0.13627413 -0.074492387, 0.050992042 0.14548859 -0.042991966, -0.13871463 0.072115481 -0.035641387, -0.13815412 0.076078266 -0.029995628, -0.12859555 0.096848071 0.0020054728, -0.12859535 0.096848279 -0.00199458, 0.097654238 0.12325934 0.032006979, 0.10561895 0.10273528 0.060005873, 0.095121384 0.12633619 0.028007075, -0.077648818 0.11562738 0.074506424, -0.075979859 0.11673069 0.074506588, -0.092967279 0.11552033 0.058006562, 0.04742378 0.14669043 -0.042991862, 0.10621059 0.090102851 0.074505046, 0.10749392 0.088567972 0.074505031, -0.14018519 0.071260512 -0.031995967, -0.13847351 0.061072469 -0.050838366, 0.094582811 0.12563163 0.032007098, -0.14155367 0.057514518 -0.046996787, -0.1411802 0.063168883 -0.0414216, -0.13950473 0.064024955 -0.044996455, -0.091795646 0.11399797 0.062006377, 0.032355905 0.14471576 -0.057991847, -0.14096215 0.071688175 -0.027996041, 0.031896368 0.14285102 -0.06199199, -0.095702671 0.11326477 0.058006413, -0.080937885 0.11334953 0.074506328, -0.10530387 0.11070487 0.047006145, -0.10625763 0.11169219 0.043006256, 0.073058337 0.14345339 -0.0019919574, -0.13810912 0.077693492 -0.0264038, -0.14282277 0.058037698 -0.042996742, -0.14290956 0.054056913 -0.046996862, 0.02888687 0.14544809 -0.057991952, 0.028497621 0.14356762 -0.061992005, -0.094475113 0.11178753 0.062006243, 0.073058411 0.14345306 0.0020080209, -0.14269313 0.068177611 -0.027996175, -0.14190096 0.067779422 -0.031996205, -0.1079635 0.10811254 0.047006026, -0.10895382 0.10906383 0.043006167, 0.07890293 0.14028573 0.0036264807, -0.14419731 0.05453217 -0.04299701, 0.020064712 0.14345998 -0.064929932, 0.025401413 0.14609697 -0.057991698, -0.14418112 0.050567389 -0.0469971, -0.14433655 0.064625114 -0.027996361, -0.14353026 0.064256936 -0.031996503, 0.069453329 0.1452328 0.0020081103, 0.069453344 0.14523298 -0.0019917786, -0.1028127 0.10782945 0.056449674, -0.1239449 0.098217249 0.028005548, -0.1438068 0.041192502 -0.055078857, -0.14390188 0.044197708 -0.052840061, -0.14283398 0.042394519 -0.056439191, -0.14548606 0.050994456 -0.042997241, 0.011387035 0.13882175 -0.074492194, 0.009392038 0.138971 -0.074492186, 0.013379559 0.13864386 -0.074492298, -0.14536762 0.047048271 -0.046997435, 0.065804943 0.14692184 0.0020082444, 0.065804899 0.14692208 -0.001991719, 0.0073951036 0.13909152 -0.074492209, -0.12326113 0.097652286 0.032005481, 0.018519685 0.14618 -0.059991792, -0.10273866 0.10561538 0.060005829, -0.12633792 0.095119804 0.028005369, -0.1457783 0.041756928 -0.050076336, 0.095454007 0.10142815 0.074505776, 0.096901119 0.10004658 0.074505463, 0.097450033 0.10350499 0.069780186, -0.14668807 0.047426134 -0.042997435, 0.091940209 0.1163395 0.05800657, -0.090107046 0.1062063 0.074506, -0.088572316 0.10748962 0.07450597, 0.021213815 0.148424 -0.054281101, -0.1256336 0.094580859 0.032005407, 0.093987346 0.1027886 0.074505836, 0.092875943 0.10659403 0.071104512, 0.092501283 0.10412806 0.07450588, -0.13278329 0.04205054 0.074502394, -0.13218653 0.043890119 0.074502528, -0.13554025 0.042884588 0.069776759, -0.13925226 0.0398812 0.064941585, -0.13869466 0.041777343 0.064943388, -0.13335432 0.040202916 0.074502297, -0.13666782 0.039140671 0.069777451, -0.13389973 0.038347453 0.074502125, -0.13611169 0.041034579 0.069776461, 0.13554041 -0.042884737 -0.069776624, 0.1327832 -0.04205066 -0.074502289, 0.13335437 -0.040203005 -0.074502274, 0.13218653 -0.043890208 -0.074502513, 0.1386947 -0.041777432 -0.064943239, 0.13611113 -0.04103446 -0.069777578, 0.13278326 -0.042059213 0.07449767, 0.13218665 -0.043898761 0.074497625, 0.1355404 -0.042892665 0.069771856, 0.13869464 -0.041784763 0.06493862, 0.13335434 -0.040211409 0.074497774, 0.13611168 -0.041042417 0.069771692, -0.042691655 -0.075808913 0.064206511, -0.037533008 -0.078491122 0.064206414, -0.037533037 -0.07848385 -0.064215183, 0.07433638 -0.04520455 0.064208195, 0.077189505 -0.040138483 0.064208552, 0.077189483 -0.04013136 -0.064212993, 0.079697803 -0.034885913 -0.064212784, -0.032206818 -0.080815643 -0.064215325, -0.032206923 -0.080822647 0.064206295, -0.026736699 -0.082786232 -0.064215429, 0.079697728 -0.034893125 0.064208835, -0.083636962 0.023958951 -0.064209469, -0.083636925 0.023951828 0.064212129, -0.085050158 0.01831916 -0.064209789, 0.081850141 -0.029484749 -0.064212501, -0.026736803 -0.082793534 0.064206131, -0.021147385 -0.084387153 -0.064215526, 0.081850141 -0.029491961 0.064209208, -0.085050218 0.018311977 0.064211898, 0.083636932 -0.023951799 -0.064212114, -0.086083673 0.012597471 -0.064210169, 0.083636954 -0.0239591 0.064209551, -0.021147393 -0.084394336 0.064205945, -0.015463389 -0.085611224 -0.064215623, -0.08608368 0.012590289 0.064211458, -0.086732633 0.0068196058 -0.064210407, -0.015463442 -0.085618377 0.064205959, -0.0097105131 -0.086452842 -0.0642156, -0.086732544 0.0068123937 0.06421116, -0.086994216 0.0010113716 -0.06421075, -0.0097104833 -0.086460114 0.064205974, -0.0039141104 -0.08690846 -0.064215697, -0.086994223 0.0010041595 0.064210862, -0.086867258 -0.0048015118 -0.064211063, -0.0039141476 -0.086915672 0.064205952, 0.0018996075 -0.086975783 -0.064215645, -0.086867303 -0.0048087239 0.064210653, -0.086352155 -0.010592908 -0.064211369, 0.0018996373 -0.086983025 0.064205855, 0.007705085 -0.086654574 -0.064215615, -0.086352222 -0.01060009 0.06421034, -0.085451677 -0.016336918 -0.064211719, 0.007705003 -0.086661875 0.064205967, 0.013475925 -0.085946441 -0.064215608, -0.085451677 -0.01634413 0.064209923, -0.084169388 -0.022007972 -0.064212099, 0.013475969 -0.085953772 0.064205952, 0.019186713 -0.084854424 -0.064215511, -0.084169477 -0.022015095 0.064209551, -0.082511306 -0.027580649 -0.064212427, 0.019186683 -0.084861636 0.064206071, 0.024811745 -0.083383381 -0.064215437, -0.082511306 -0.027587831 0.064209148, -0.080484711 -0.033030212 -0.064212576, 0.02481167 -0.083390683 0.064206198, 0.030325964 -0.081539989 -0.06421528, -0.080484599 -0.033037484 0.064208895, -0.078098491 -0.038332254 -0.064212814, 0.030325957 -0.081547171 0.064206317, 0.035704702 -0.079332262 -0.064215295, -0.078098491 -0.038339466 0.064208582, -0.075363532 -0.043463022 -0.064213105, 0.035704814 -0.079339594 0.06420631, 0.04092402 -0.076770365 -0.064215146, -0.075363517 -0.043470263 0.064208329, -0.072291985 -0.048399717 -0.064213425, 0.040924057 -0.076777577 0.064206526, 0.045960538 -0.073865414 -0.064214855, -0.072291948 -0.048406899 0.06420809, -0.068897523 -0.053120255 -0.064213663, 0.045960598 -0.073872775 0.064206719, 0.050791785 -0.07063067 -0.064214647, -0.06889756 -0.053127408 0.064207897, -0.065195456 -0.057603389 -0.064213976, 0.05079186 -0.070637941 0.064206935, 0.055396311 -0.067080438 -0.06421455, -0.065195486 -0.057610601 0.064207509, -0.061202191 -0.061829329 -0.064214289, 0.055396259 -0.06708765 0.064207032, 0.059753306 -0.063230604 -0.064214401, -0.061202139 -0.06183663 0.064207308, -0.056935616 -0.06577903 -0.06421449, 0.059753329 -0.063237846 0.064207315, 0.063843451 -0.059098393 -0.064214058, -0.056935534 -0.065786302 0.064207189, -0.052414469 -0.06943512 -0.064214706, 0.063843384 -0.059105515 0.064207412, 0.067648411 -0.054702073 -0.064213812, -0.052414492 -0.069442242 0.064206883, -0.047659487 -0.072780848 -0.064214848, 0.067648426 -0.054709196 0.064207703, 0.071151219 -0.050061435 -0.064213581, -0.047659419 -0.072788119 0.064206652, -0.042691611 -0.075801641 -0.06421499, 0.071151331 -0.050068855 0.064208031, 0.074336417 -0.045197308 -0.064213395, 0.056863129 0.071534306 -0.066574931, 0.0607844 0.06823343 -0.066575184, 0.056935444 0.065786153 -0.064206913, -0.077284209 0.071548402 -0.071878374, -0.074584603 0.074358404 -0.071878046, -0.071213983 0.070998102 -0.070419155, -0.082435332 0.087241709 -0.074330449, -0.088524908 0.088255942 -0.074495099, -0.083437346 0.09308064 -0.074494921, -0.080116227 0.089375973 -0.074330434, -0.076809898 0.085687548 -0.073837698, 0.081241861 0.081497401 -0.07383804, 0.086231291 0.076198339 -0.073838398, 0.082551822 0.072947145 -0.073019579, -0.079033107 0.083641142 -0.073837951, 0.07777524 0.078019977 -0.073019356, -0.081493273 0.081245929 -0.073838048, -0.075660691 0.080072224 -0.073019281, -0.07801602 0.077779353 -0.073019363, 0.07005547 0.078640282 -0.071877971, 0.070994303 0.071217895 -0.070419103, 0.066889554 0.075086534 -0.070418864, 0.07435438 0.074588597 -0.071878016, -0.074571982 0.060308218 -0.068649344, -0.06822975 0.060788125 -0.066575497, -0.071053006 0.057462454 -0.066575721, -0.071608767 0.063798487 -0.068649255, 0.059679225 0.075076967 -0.068648681, -0.078636371 0.070059419 -0.071878307, -0.073791541 0.068315119 -0.070419192, -0.07508269 0.066893429 -0.070419356, 0.063794717 0.071612537 -0.0686488, -0.080839708 0.074839979 -0.073019475, 0.055052549 0.072936982 -0.066574872, 0.052414566 0.069442093 -0.064206749, 0.084739029 0.08500573 -0.074330658, 0.089943349 0.079478294 -0.074330911, -0.085001349 0.084743202 -0.074330688, 0.088251606 0.08852911 -0.074495092, 0.093076438 0.083441526 -0.074495405, -0.078189515 0.063233733 -0.070419654, 0.073278517 0.082258105 -0.073018983, 0.062574446 0.07871899 -0.070418626, -0.082254164 0.07328257 -0.073019624, -0.084442995 0.078175426 -0.073838338, 0.12190894 -0.027622581 -0.074501485, 0.12016807 -0.034414709 -0.074501976, 0.11538511 -0.033044696 -0.074337363, 0.057778865 0.076549053 -0.068648502, -0.074606508 0.052766711 -0.06657593, -0.067648284 0.054709077 -0.064207695, 0.052762955 0.074610025 -0.066574782, -0.071151309 0.050068527 -0.064207911, 0.047659546 0.072787881 -0.064206675, -0.081890248 0.066226661 -0.071878448, 0.076544702 0.085924476 -0.073837727, -0.085920431 0.076548755 -0.073838353, 0.065536067 0.082444608 -0.071877584, -0.088078052 0.081540614 -0.074330896, -0.093333855 0.083153188 -0.07449542, 0.060581952 0.080262542 -0.070418611, -0.078301176 0.055379838 -0.068649724, 0.055376068 0.078305006 -0.068648487, -0.085657768 0.069273412 -0.073019691, 0.079839751 0.089623123 -0.074330389, -0.089619085 0.07984373 -0.074330881, 0.083149165 0.093338013 -0.074494645, 0.050058261 0.076451242 -0.066574723, -0.082099825 0.058066249 -0.070419848, 0.068551168 0.08623758 -0.073018759, -0.077447526 0.048500299 -0.066576272, -0.074336305 0.045204252 -0.064208306, 0.063449249 0.084061325 -0.071877584, -0.089475721 0.072360873 -0.073838644, 0.05806236 0.082103789 -0.070418477, -0.085985526 0.060814559 -0.071878821, 0.048496738 0.077451229 -0.066574648, 0.042691633 0.075808704 -0.064206421, 0.052537248 0.080237299 -0.068648338, -0.081282899 0.050902188 -0.068650007, -0.0933275 0.075475782 -0.074331157, -0.097849227 0.077789247 -0.074495673, 0.071606666 0.090081245 -0.073837548, 0.066368416 0.087928563 -0.073018789, -0.089941539 0.063612193 -0.073020197, 0.060810477 0.085989535 -0.071877331, -0.085226253 0.053371489 -0.070420235, 0.050898492 0.081286728 -0.068648174, -0.080044851 0.044081599 -0.066576481, -0.077189319 0.040138185 -0.064208508, 0.055085957 0.084129691 -0.070418432, 0.07468918 0.093958765 -0.074330211, 0.077785149 0.097853333 -0.074494585, -0.089259923 0.055897564 -0.071879119, 0.069326565 0.091847569 -0.073837608, 0.06360814 0.089945644 -0.073018536, -0.08107426 0.042158425 -0.066576533, -0.084008977 0.046264589 -0.068650246, 0.044840232 0.079623997 -0.066574574, 0.053367645 0.085230112 -0.070418403, 0.057693094 0.088111579 -0.071877256, -0.093366496 0.058469057 -0.073020428, -0.085089378 0.044246167 -0.068650343, 0.07231082 0.095801353 -0.074330166, 0.072176337 0.10206091 -0.074494213, 0.066443354 0.093954474 -0.073837399, -0.088084437 0.048508883 -0.070420422, 0.047060832 0.083567411 -0.068648085, -0.082390383 0.039524019 -0.066576727, -0.079697698 0.034892917 -0.064208828, -0.097528182 0.061074942 -0.073839203, 0.055893585 0.089263916 -0.071877196, -0.093950406 0.066447318 -0.073838964, -0.089217119 0.04639256 -0.070420563, 0.060347453 0.092165142 -0.073018566, 0.069303557 0.097998887 -0.074329928, -0.092253484 0.050804764 -0.071879365, -0.086470678 0.041481405 -0.068650626, 0.049343884 0.087621361 -0.070418328, 0.058465004 0.093370676 -0.073018432, -0.083708733 0.036649019 -0.06657692, 0.063037306 0.096273005 -0.07383731, -0.10172641 0.063704014 -0.074331746, -0.10594325 0.066344529 -0.074496269, -0.10205682 0.07218039 -0.074496001, -0.097994685 0.069307774 -0.074331716, -0.093439803 0.048588157 -0.071879447, 0.051679417 0.091768205 -0.071877107, -0.096497826 0.053142011 -0.073020816, 0.061070979 0.097532272 -0.073837161, -0.090665534 0.043493688 -0.07042069, 0.065750912 0.10041705 -0.074329898, 0.066340297 0.10594735 -0.074494079, -0.084476694 0.034842283 -0.066576943, -0.081850052 0.029491812 -0.064209051, -0.087854274 0.03846392 -0.06865067, 0.054057121 0.095990032 -0.073018283, 0.063699886 0.10173073 -0.074329704, -0.097738743 0.05082339 -0.073020756, -0.10079911 0.055510461 -0.073839523, 0.034838572 0.084480494 -0.066574194, 0.037533149 0.078490853 -0.064206377, 0.032206863 0.080822587 -0.064206205, -0.0949568 0.045552045 -0.071879804, 0.039520368 0.082394212 -0.066574365, 0.05646652 0.10026836 -0.073837057, -0.088660367 0.036567718 -0.06865079, -0.092116296 0.040329814 -0.070420906, 0.036563858 0.088664174 -0.068647824, 0.041477576 0.086474478 -0.068647921, -0.10209522 0.053088635 -0.07383956, -0.10513809 0.057899892 -0.074332193, -0.10949622 0.060299814 -0.074496642, 0.058897227 0.1045846 -0.074329615, 0.060295835 0.10950044 -0.074493945, -0.099325456 0.047647715 -0.073021054, 0.038337663 0.092965364 -0.070417911, 0.043489769 0.090669543 -0.070418164, -0.085969493 0.030976057 -0.066577256, 0.030047104 0.08630079 -0.066574186, 0.026736796 0.082793355 -0.064206094, -0.092961535 0.038341612 -0.070420943, -0.096476167 0.042238563 -0.071879968, -0.10649008 0.055373669 -0.074332304, -0.11270483 0.054065555 -0.074496925, 0.040152267 0.097365409 -0.071876757, 0.04554823 0.09496063 -0.071876809, -0.10375261 0.049771279 -0.073839813, 0.028082371 0.086960286 -0.066574074, -0.090226941 0.032510012 -0.068651035, 0.031535208 0.090574861 -0.068647832, -0.09736146 0.040156126 -0.071879968, 0.041999608 0.10184467 -0.07301794, 0.047643736 0.099329561 -0.073018119, -0.10091479 0.044181615 -0.073021159, -0.10821899 0.051913798 -0.074332587, 0.0294732 0.091266662 -0.068647735, -0.094604097 0.034087181 -0.070421256, 0.033065036 0.094968855 -0.070417874, 0.025161073 0.087849855 -0.066573948, 0.021147341 0.084394276 -0.064206064, -0.10184067 0.042003602 -0.073021218, 0.043871492 0.10638398 -0.073836669, 0.049767271 0.10375679 -0.073836744, -0.1054129 0.046150923 -0.073840082, 0.030903101 0.095694035 -0.070417769, -0.099081792 0.035700321 -0.071880184, 0.034629956 0.099463463 -0.071876705, -0.10637983 0.043875575 -0.073840208, -0.10995057 0.048137516 -0.074332759, -0.11555876 0.047661066 -0.07449732, 0.026407093 0.092200607 -0.068647623, -0.10364031 0.037342757 -0.07302165, 0.022211686 0.088641673 -0.06657391, 0.04576014 0.1109634 -0.074329227, 0.051909566 0.10822317 -0.074329525, 0.047656968 0.11556289 -0.074493468, 0.054061368 0.11270902 -0.074493766, -0.11095935 0.045764267 -0.074332744, 0.03236559 0.10022315 -0.07187663, -0.10825963 0.039006948 -0.073840491, -0.11291992 0.040685892 -0.074333236, -0.1180491 0.041106701 -0.074497692, 0.036223188 0.10403946 -0.073017873, 0.02768822 0.09667334 -0.07041771, 0.11751598 0.0025707185 -0.074129879, 0.11258253 0.0024629235 -0.073473677, 0.1148957 0.0063594282 -0.073842317, 0.020196065 0.089122474 -0.06657403, 0.015463457 0.085618258 -0.064205892, 0.11506365 -0.0013290644 -0.073842749, 0.12499999 0.00019726157 -0.074499935, 0.12001671 -0.0013862252 -0.074335456, 0.02331166 0.093031377 -0.068647571, 0.033854738 0.10483414 -0.073017828, 0.037837863 0.10867637 -0.07383661, 0.017015457 0.11631009 -0.074123614, 0.020452857 0.11324307 -0.073836297, 0.01630111 0.11142749 -0.073467404, 0.021333247 0.11811787 -0.074328773, 0.012843758 0.11435625 -0.07383617, 0.028998688 0.10124886 -0.07187666, 0.021196261 0.093536079 -0.068647519, -0.022077143 0.11545616 -0.074123576, -0.02537737 0.1122421 -0.073836349, -0.026469857 0.11707386 -0.074328884, -0.021128699 0.12320551 -0.074493147, -0.018591285 0.11858025 -0.07432881, -0.017823979 0.11368653 -0.073836334, -0.02115047 0.1106095 -0.073467568, 0.024442613 0.097544521 -0.070417643, -0.093732573 0.070932299 -0.074126132, 0.035363659 0.10950658 -0.07383658, 0.03946659 0.11335459 -0.074329078, 0.041102469 0.11805326 -0.074493229, -0.11185559 0.036127716 -0.074127853, -0.10715989 0.034611136 -0.07347174, 0.030332908 0.1059069 -0.073017657, -0.11062303 0.031688988 -0.073840976, 0.10894156 0.00056245923 -0.072768286, 0.016241685 0.089927346 -0.066573821, 0.11015379 -0.0012720525 -0.073023766, 0.10530882 -0.0012159348 -0.071882293, 0.10886203 0.0042024553 -0.072768167, 0.08911889 -0.020192236 -0.066580102, 0.085050233 -0.018312067 -0.064211816, 0.10999301 0.0060881376 -0.073023275, 0.022224396 0.09807384 -0.070417657, 0.087846309 -0.025157422 -0.066580415, 0.10515514 0.0058205426 -0.07188192, 0.12117168 0.0048221052 -0.074407145, 0.11984161 0.0066330731 -0.074335068, 0.093532428 -0.021192402 -0.068653941, 0.092196718 -0.026403308 -0.068654418, 0.025599554 0.10216117 -0.071876504, 0.12479247 0.0072057545 -0.074499652, 0.054226309 0.10009804 -0.073662817, 0.036885977 0.11422041 -0.074329011, 0.054287523 0.10426074 -0.074124247, 0.098069876 -0.022220492 -0.070424393, 0.096669495 -0.027684391 -0.070424616, 0.034418866 0.12017205 -0.074493244, 0.050912127 0.10182366 -0.073662654, 0.031684965 0.11062714 -0.073836423, 0.057255104 0.1069043 -0.074401572, 0.090111077 -0.015163451 -0.066579923, 0.086083688 -0.012590438 -0.064211577, 0.017046079 0.094380766 -0.068647504, 0.05423443 0.10846797 -0.074401394, 0.10271151 -0.023272306 -0.071883455, 0.10124484 -0.028994739 -0.071883872, 0.023276314 0.10271558 -0.071876459, 0.017569453 0.10752091 -0.072762378, 0.019580156 0.1084111 -0.073017627, 0.018719003 0.10364306 -0.071876481, 0.026777104 0.10686138 -0.073017634, 0.013967067 0.10804787 -0.072762258, 0.011754796 0.10466185 -0.071876466, 0.012295693 0.10947683 -0.073017538, 0.090416051 -0.013224065 -0.066579744, 0.033048779 0.11538926 -0.074328959, 0.018842503 0.11979872 -0.07440073, 0.020747826 0.12327027 -0.074493051, 0.015475288 0.12028009 -0.074400753, 0.013396576 0.11927888 -0.074328914, 0.094573773 -0.015914619 -0.068653673, 0.017873019 0.098959297 -0.070417419, 0.013803661 0.12423962 -0.074493065, 0.10743701 -0.024343103 -0.073025033, 0.10590278 -0.03032884 -0.07302548, -0.018670768 0.10733491 -0.07276237, -0.017063439 0.10883564 -0.073017545, -0.016313016 0.10404882 -0.071876511, 0.024347141 0.10744092 -0.073017672, 0.094893932 -0.01387915 -0.068653524, 0.027970746 0.11162406 -0.073836289, -0.022246823 0.10665131 -0.072762363, -0.023225941 0.10272685 -0.071876466, -0.0242946 0.10745302 -0.073017597, -0.089659289 0.070150286 -0.073664539, 0.099161759 -0.016686827 -0.07042408, -0.091873117 0.067224979 -0.073664643, 0.090819731 -0.010087103 -0.066579565, 0.086732596 -0.0068125725 -0.064211085, -0.095821291 0.074328065 -0.074403241, 0.11222579 -0.025428325 -0.07384406, 0.11062316 -0.031680852 -0.073844448, -0.097868241 0.071611404 -0.074403577, 0.025432453 0.11222962 -0.073836297, 0.099497445 -0.014552563 -0.070424005, -0.10309685 0.035211951 -0.072766423, 0.029174909 0.11642906 -0.074328914, 0.027626842 0.12191284 -0.074493207, -0.10421562 0.031747371 -0.072766632, 0.10385506 -0.017476618 -0.071883172, -0.1012447 0.029002786 -0.071880683, -0.10590269 0.030336946 -0.073021963, -0.11496887 0.038577974 -0.07440532, -0.11600544 0.035338461 -0.074405611, -0.12016802 0.034422874 -0.07449808, -0.11538507 0.033052921 -0.074333645, 0.095317461 -0.010586709 -0.06865342, 0.10471532 -0.00033411384 -0.071717128, 0.10054976 -0.0011608899 -0.070423156, 0.091097668 -0.0071554482 -0.066579312, 0.026527077 0.11706078 -0.074328847, 0.11705668 -0.026523054 -0.074336961, 0.10420657 -0.015241414 -0.071883097, 0.10611196 0.001139015 -0.072094649, 0.10470627 0.0014156401 -0.071717009, 0.10863321 -0.018280804 -0.07302472, 0.10328232 0.002835393 -0.071312398, 0.0049826801 0.091246396 -0.066573791, 0.0097105801 0.086460024 -0.064205982, 0.0039141923 0.086915463 -0.064205855, 0.099941544 -0.011100411 -0.070423618, 0.010199219 0.090811282 -0.066573784, 0.10460062 0.0049136877 -0.071716845, 0.10040306 0.0055575967 -0.070422739, 0.052972794 0.095896661 -0.072893083, 0.091242656 -0.0049788952 -0.066579312, 0.086994141 -0.0010042191 -0.064210862, 0.095609263 -0.0075100064 -0.068653226, 0.052327797 0.097868174 -0.073177278, 0.051391929 0.09675324 -0.072893098, 0.0052293837 0.095765054 -0.068647392, 0.1090009 -0.015942782 -0.073024422, 0.049415678 0.096185505 -0.072581664, 0.010704339 0.095308512 -0.068647444, 0.048188969 0.098387688 -0.072892964, 0.11347521 -0.019095838 -0.073843688, 0.017750695 0.10320425 -0.071711257, 0.0054831505 0.10041079 -0.070417605, 0.011223525 0.099932224 -0.070417412, 0.10467172 -0.011625856 -0.071882844, 0.095761389 -0.0052256286 -0.068653077, 0.016530231 0.10482651 -0.072088823, 0.016023681 0.10348654 -0.071711175, -0.0001411885 0.091382056 -0.066573799, -0.0018995553 0.086982727 -0.0642059, 0.10024755 -0.0078743398 -0.070423663, 0.014386952 0.10231861 -0.07130678, 0.012556881 0.10396424 -0.071711317, 0.11385924 -0.016653508 -0.073843569, 0.0057426244 0.1051631 -0.071876273, -0.017083853 0.10331684 -0.071711212, -0.015575692 0.099346876 -0.070417479, 0.11835994 -0.019917846 -0.074336484, 0.12326609 -0.020743549 -0.074501142, 0.10948741 -0.012160897 -0.073024347, -0.0019952953 0.091360509 -0.066573747, -0.018768802 0.10444909 -0.072088823, -0.00014819205 0.095907658 -0.068647385, -0.018807799 0.10301697 -0.071711279, -0.019970909 0.1013768 -0.071306907, 0.09137249 -0.0010547936 -0.066579103, 0.1004069 -0.0054791272 -0.070423454, -0.022239387 0.10233092 -0.071711391, -0.022176333 0.098084629 -0.070417635, -0.098810405 0.034672648 -0.071715117, 0.0060068071 0.1100013 -0.07301753, 0.10499212 -0.0082471371 -0.071882665, 0.11876059 -0.017370433 -0.074336305, -0.00209409 0.095885009 -0.068647429, -0.098142631 0.03230378 -0.071310773, 0.12423554 -0.013799399 -0.074500859, 0.11436749 -0.012703061 -0.073843494, -0.00015544891 0.10056043 -0.070417441, -0.10133953 0.031489134 -0.072093025, 0.0958976 -0.0011071265 -0.068652779, -0.099913664 0.031351417 -0.071715295, -0.10042349 0.0296776 -0.071715429, -0.096669443 0.027692229 -0.070421584, -0.0052647144 0.091230541 -0.066573843, -0.0077049732 0.086661786 -0.064205892, 0.099574715 0.00079166889 -0.070079669, 0.10515925 -0.005738616 -0.071882591, 0.0062745959 0.11490402 -0.073836222, 0.10982248 -0.0086265504 -0.073024258, -0.0021956712 0.10053656 -0.070417456, 0.099492818 0.0041185021 -0.07007955, 0.11929076 -0.013250113 -0.074336246, 0.095757663 0.0053005815 -0.068652511, 0.0494394 0.091860771 -0.071598992, -0.00016279519 0.10531974 -0.071876258, 0.046398073 0.093434006 -0.071599022, -0.0055253059 0.095748425 -0.068647452, 0.10999724 -0.0060027242 -0.073024049, 0.015785441 0.098322481 -0.070074223, 0.11471761 -0.0090112686 -0.073843181, -0.008092761 0.091023177 -0.06657394, 0.012491211 0.098795176 -0.070074238, 0.00654459 0.11985046 -0.074328721, 0.0068158954 0.12481818 -0.07449311, -0.0022995472 0.10529476 -0.071876451, -0.017339021 0.098060459 -0.07007429, -0.014855012 0.094750375 -0.068647482, -0.020605825 0.097426355 -0.07007426, -0.021150231 0.09354651 -0.068647474, 0.11490016 -0.0062705278 -0.073842943, -0.00017020106 0.11016506 -0.073017441, -0.094144315 0.032447606 -0.070077866, 0.11965586 -0.0093994141 -0.074336022, -0.0057934225 0.1003935 -0.070417494, -0.095175765 0.029283494 -0.070078127, 0.12481406 -0.0068117678 -0.074500397, -0.092196815 0.026410967 -0.06865143, -0.0084934682 0.095530957 -0.068647511, 0.095426261 -0.00017154217 -0.068450809, -0.010371447 0.090791643 -0.066573881, -0.013475955 0.085953474 -0.064205885, -0.0024054199 0.11013886 -0.073017403, 0.11984631 -0.0065405071 -0.074335784, 0.094051018 0.0016212165 -0.067853436, 0.095378801 0.0030173659 -0.068450615, -0.00017781556 0.11507517 -0.073836252, 0.091239125 0.00505054 -0.066578671, 0.048266575 0.087660462 -0.070248246, -0.0060676187 0.10514489 -0.071876414, 0.045968473 0.087310135 -0.069742173, 0.090788051 0.010375261 -0.066578344, 0.086867258 0.0048086345 -0.064210519, 0.086352333 0.010599941 -0.064210236, -0.0089056045 0.10016528 -0.070417471, 0.045363724 0.089197278 -0.070248097, 0.016044989 0.094071537 -0.068445504, -0.010885015 0.095287979 -0.068647496, -0.0025125593 0.11504793 -0.073836222, 0.014048591 0.093013614 -0.067848235, 0.012892678 0.094555169 -0.068445414, -0.00018547475 0.12002873 -0.074328743, -0.00019314885 0.12500393 -0.07449308, 0.095284209 0.010888994 -0.068652287, -0.015699342 0.094129801 -0.068445437, -0.014154151 0.09027943 -0.066573948, -0.0063468069 0.10998213 -0.0730175, -0.017238259 0.092475593 -0.067848444, -0.018835872 0.093552738 -0.068445586, -0.020152338 0.089132458 -0.06657403, 0.099906787 0.01141715 -0.070422485, -0.0093270987 0.10490608 -0.071876302, -0.090518162 0.030213952 -0.06844908, -0.011413112 0.099910557 -0.070417613, 0.090063781 0.015449375 -0.06657812, 0.085451722 0.016343981 -0.064209819, -0.0026207864 0.1200003 -0.07432875, -0.089645915 0.028495938 -0.067851894, -0.091477007 0.027172416 -0.068449341, -0.0072017312 0.12479663 -0.074492961, -0.087846324 0.025164813 -0.066577494, 0.090484083 0.00025749207 -0.066125363, 0.10463542 0.011957318 -0.071881622, 0.090424985 0.0032809079 -0.066125214, -0.0066296756 0.11488429 -0.0738362, -0.0097562671 0.1097323 -0.073017612, 0.045434132 0.083414048 -0.06825456, 0.042672247 0.084860265 -0.06825456, 0.089752406 0.017166466 -0.066577986, -0.011953324 0.10463917 -0.071876287, 0.094524071 0.016214311 -0.06865184, 0.014799789 0.089269608 -0.06612052, 0.011808828 0.08971411 -0.066120356, -0.0069150627 0.11982968 -0.07432878, 0.10944927 0.012507409 -0.073023036, -0.015300438 0.08918497 -0.066120483, -0.010191038 0.11462319 -0.073836215, -0.018271826 0.088623911 -0.066120408, -0.019186668 0.084861457 -0.064206108, 0.094197258 0.018016577 -0.068651885, -0.012503237 0.10945335 -0.073017575, -0.08569631 0.02904737 -0.066123784, 0.099109679 0.017000914 -0.070422202, -0.086619027 0.026167631 -0.06612394, 0.042748094 0.080259413 -0.066349298, 0.08905609 0.020474881 -0.066577911, 0.084169462 0.022015005 -0.064209491, 0.1143277 0.013064712 -0.073841974, -0.010629699 0.11955738 -0.074328765, 0.098766983 0.01889056 -0.070422158, -0.014187425 0.12419629 -0.074493065, -0.013060451 0.11433163 -0.073836222, 0.10380046 0.017805457 -0.071881369, 0.093466371 0.021488965 -0.068651676, 0.088405505 0.023122966 -0.066577822, -0.013622835 0.11925337 -0.074328743, 0.11924919 0.013626963 -0.074334607, 0.12419234 0.014191687 -0.074499145, 0.10344158 0.019784629 -0.071881115, 0.1085761 0.018624455 -0.073022649, -0.025432542 0.087771624 -0.066574022, -0.02481173 0.083390653 -0.064206049, 0.098000675 0.02253136 -0.070421845, 0.092783779 0.024267912 -0.068651542, 0.087768003 0.025436342 -0.066577569, 0.082511425 0.027587742 -0.064209193, 0.10820064 0.020694673 -0.073022515, -0.026692025 0.092118531 -0.068647593, 0.11341555 0.019454539 -0.073841646, 0.102639 0.023597717 -0.071880877, -0.027986854 0.09658727 -0.070417732, 0.097284913 0.025445223 -0.07042177, -0.030313678 0.086207688 -0.066574194, -0.030325994 0.081547171 -0.064206198, 0.092114717 0.026695788 -0.068651229, 0.11302342 0.021616876 -0.073841348, 0.11829777 0.020291865 -0.074334204, -0.029311515 0.10115865 -0.071876571, 0.12320146 0.021132857 -0.074498847, 0.086664036 0.028976113 -0.06657742, -0.031852148 0.085651129 -0.066574194, 0.10736115 0.024683058 -0.073022336, -0.031814903 0.09047696 -0.06864772, 0.10188943 0.026649475 -0.071880743, -0.028003372 0.12182701 -0.074493304, 0.096583351 0.027990878 -0.070421547, -0.030660018 0.1058124 -0.073017813, 0.11788882 0.022547215 -0.074334279, 0.12182289 0.028007627 -0.074498445, -0.033429667 0.089892894 -0.06864775, 0.086203977 0.030317396 -0.0665773, 0.080484658 0.033037215 -0.06420894, 0.090955898 0.030411154 -0.068651006, -0.033358328 0.094865978 -0.070417821, -0.035099506 0.084372371 -0.066574186, 0.11214653 0.025783211 -0.073841199, -0.035704821 0.079339564 -0.064206354, -0.032026686 0.11052874 -0.073836416, 0.10657714 0.027875394 -0.073022142, -0.035051368 0.094253629 -0.070417836, 0.1011547 0.029315472 -0.071880594, 0.09047322 0.031818777 -0.06865111, -0.034937233 0.099356055 -0.071876593, 0.095368415 0.031886339 -0.070421323, -0.036837757 0.088550717 -0.068647802, -0.037501596 0.0833323 -0.066574305, 0.11697412 0.02689296 -0.074333861, -0.033405378 0.11528641 -0.074328996, 0.11132745 0.029117793 -0.073840991, -0.034790076 0.12006521 -0.074493289, -0.03671027 0.09871453 -0.071876712, 0.10580847 0.030664176 -0.073021844, -0.036544599 0.10392711 -0.073017828, 0.094862282 0.03336224 -0.070421219, -0.038624808 0.092846453 -0.070417978, 0.084535256 0.034700006 -0.066576958, -0.039358869 0.087459266 -0.068647951, 0.099882185 0.03339541 -0.071880355, -0.039774843 0.082271516 -0.06657429, -0.040923908 0.076777309 -0.064206429, 0.11611976 0.03037101 -0.074333712, -0.038399279 0.10325617 -0.073017813, 0.12006108 0.034794182 -0.074497998, 0.11052471 0.032030672 -0.073840782, -0.038173378 0.1085591 -0.073836654, 0.099352077 0.034941167 -0.071880311, -0.040452875 0.097240746 -0.071876779, 0.088721842 0.036418289 -0.068650633, -0.041268267 0.091702014 -0.070417874, 0.10447748 0.03493169 -0.073021725, -0.041744627 0.086345911 -0.068647906, 0.11528245 0.033409536 -0.074333638, -0.040110864 0.10785827 -0.073836625, 0.1039229 0.036548674 -0.073021561, -0.039816633 0.11323211 -0.074329168, 0.093025848 0.03818509 -0.07042101, -0.041467205 0.11792558 -0.074493535, -0.042983636 0.08064127 -0.066574499, 0.10913423 0.036488593 -0.073840618, -0.04231406 0.1017144 -0.07301794, 0.08226791 0.03977859 -0.066576645, 0.078098536 0.038339287 -0.064208642, -0.043221496 0.096042186 -0.071876936, 0.10855512 0.038177401 -0.073840469, -0.043769851 0.090534776 -0.07041803, 0.097428739 0.039992303 -0.071880013, -0.041837566 0.1125012 -0.074329101, 0.11383219 0.038059175 -0.074333295, -0.048013724 0.11541492 -0.074493557, -0.044325076 0.079911977 -0.066574618, -0.045960478 0.073872507 -0.064206697, 0.11792159 0.041471243 -0.074497715, 0.086342141 0.041748405 -0.068650499, -0.045112297 0.084635109 -0.068648152, 0.11322802 0.03982085 -0.074333221, -0.044200145 0.10624793 -0.07383661, 0.10191122 0.041832089 -0.073021248, -0.045210026 0.10046065 -0.073017962, 0.090530857 0.043773681 -0.070420697, -0.045841463 0.094819605 -0.07187701, 0.079908237 0.044328809 -0.066576466, 0.075363606 0.043470144 -0.064208329, -0.046520136 0.083869368 -0.0686481, 0.10645364 0.043696463 -0.073840201, -0.047300868 0.088740826 -0.070418231, -0.046102837 0.11082157 -0.07432925, 0.079156458 0.045657784 -0.066576496, 0.094815597 0.045845449 -0.071879581, -0.047225043 0.1049383 -0.073836774, -0.047950409 0.099181861 -0.073018171, 0.083865702 0.046524048 -0.068650216, -0.048777014 0.087937981 -0.070418172, 0.1110363 0.045577228 -0.074332923, 0.11541095 0.048017949 -0.074497446, 0.083076566 0.047918916 -0.068650097, -0.048273601 0.077590346 -0.066574685, -0.049539566 0.092940807 -0.071876943, 0.099177778 0.04795453 -0.073020995, -0.049258068 0.10945559 -0.074329354, -0.054409347 0.11254132 -0.074493758, 0.087934136 0.048780888 -0.070420459, -0.050087675 0.10360238 -0.073836766, -0.051085554 0.092100054 -0.071877114, 0.077297315 0.048739493 -0.066576228, 0.07229194 0.04840681 -0.064208105, -0.050664283 0.08143276 -0.068648189, 0.087106779 0.050243527 -0.070420355, -0.051818773 0.097216666 -0.073018238, 0.10359842 0.050091743 -0.073839799, 0.092096046 0.051089734 -0.071879447, -0.052243948 0.10806218 -0.074329369, -0.053435966 0.096337169 -0.073018245, 0.081125289 0.051153183 -0.068649992, -0.053122208 0.085383296 -0.07041835, 0.075930327 0.050842971 -0.066576108, -0.054128557 0.10154969 -0.073837005, 0.091229543 0.052621484 -0.071879327, -0.052993342 0.074446559 -0.06657476, 0.10805799 0.052248091 -0.074332446, -0.050791778 0.070637792 -0.064206772, 0.11253712 0.054413646 -0.07449697, -0.055817641 0.10063094 -0.073837034, 0.09633325 0.053440034 -0.073020637, -0.055636324 0.089424402 -0.071877323, 0.085060939 0.053634644 -0.070420176, -0.056458496 0.10592094 -0.07432951, -0.060633883 0.10931361 -0.074493773, 0.079690754 0.05336085 -0.068649828, -0.05561769 0.078133494 -0.068648487, 0.074442983 0.052997053 -0.066575944, 0.06889759 0.053127289 -0.064207762, -0.058220513 0.10496283 -0.074329555, 0.095426813 0.055042237 -0.073020592, -0.058196031 0.093538344 -0.073018394, 0.10062699 0.055821806 -0.07383956, 0.089086846 0.056173176 -0.071879119, -0.058315769 0.081923813 -0.070418417, -0.057083867 0.071358085 -0.066574953, 0.083556622 0.055949479 -0.070420012, -0.055396236 0.067087561 -0.064206943, -0.060790151 0.097707659 -0.073837161, 0.078129739 0.055621445 -0.06864965, 0.099680215 0.057495385 -0.073839381, -0.058184221 0.070463866 -0.066575073, 0.10495868 0.058224648 -0.074332073, -0.061075985 0.085801214 -0.071877457, 0.10930939 0.0606381 -0.074496627, 0.072365135 0.055800885 -0.066575855, 0.09318544 0.058757454 -0.073020458, -0.059910998 0.074892104 -0.068648659, -0.063406929 0.10191351 -0.074329711, 0.08751142 0.058597416 -0.071879014, -0.06666749 0.10574171 -0.074494071, 0.081919953 0.058319658 -0.070419863, -0.061065733 0.07395336 -0.068648763, 0.10397126 0.059970349 -0.074332073, -0.063885882 0.089748591 -0.073018648, 0.10573772 0.06667161 -0.074496239, 0.071354523 0.0570876 -0.066575751, 0.065195426 0.057610512 -0.064207494, -0.062817462 0.078525186 -0.070418671, 0.075948894 0.058564425 -0.068649471, -0.060994998 0.068045259 -0.066575199, -0.059753314 0.063237727 -0.064207226, 0.097338989 0.061376184 -0.073839322, -0.064028114 0.077540964 -0.070418805, 0.09153755 0.061293274 -0.073020294, -0.066733286 0.093748659 -0.07383731, 0.08579731 0.06107983 -0.071878761, -0.065790571 0.082241774 -0.071877562, -0.064015701 0.071414948 -0.06864883, 0.074888378 0.059914738 -0.068649545, 0.07963337 0.06140551 -0.070419639, -0.06276051 0.066420168 -0.066575229, 0.10152912 0.06401813 -0.074331969, -0.0670586 0.081211001 -0.071877763, 0.095617592 0.064025074 -0.073839143, -0.069606021 0.097784042 -0.074330062, -0.0724914 0.10183737 -0.07449422, 0.089744508 0.063889921 -0.073020175, -0.068817414 0.086025327 -0.073018797, 0.068476677 0.060509801 -0.066575482, 0.078521267 0.062821358 -0.070419669, -0.067121215 0.074879467 -0.070418842, 0.083402365 0.064311653 -0.071878612, -0.065868795 0.069709629 -0.068648927, 0.09973368 0.066781044 -0.07433176, -0.064714238 0.064518183 -0.066575401, -0.063843317 0.059105217 -0.06420739, 0.10183321 0.07249555 -0.074496001, 0.093744621 0.066737473 -0.073838934, -0.070143804 0.08494705 -0.073018976, 0.071867883 0.063506514 -0.068649217, -0.071884699 0.089859366 -0.07383763, 0.082237661 0.065794557 -0.071878538, -0.070298068 0.07842347 -0.071877912, 0.087239578 0.067270368 -0.073019817, -0.069064111 0.073091328 -0.070418902, 0.097780034 0.069610268 -0.074331596, -0.06791912 0.067713201 -0.068649024, 0.075354308 0.066587299 -0.070419282, -0.073270291 0.088733256 -0.073837623, 0.086021259 0.068821311 -0.073019832, -0.074979134 0.09372744 -0.074330218, -0.078087188 0.097612649 -0.0744946, 0.091127902 0.070268571 -0.073838636, -0.067056566 0.062079966 -0.066575482, 0.064514473 0.064717919 -0.066575378, 0.061202168 0.061836421 -0.064207196, -0.073532365 0.08203125 -0.07301911, 0.078920797 0.069738865 -0.071878433, -0.072332799 0.076550543 -0.071877934, 0.089855462 0.071888775 -0.073838681, 0.095050737 0.073293328 -0.074331328, -0.076424465 0.0925529 -0.074330136, 0.097608417 0.078091323 -0.074495688, 0.067709446 0.06792289 -0.068649068, -0.070377424 0.065154314 -0.068649262, 0.093723461 0.074983329 -0.074331209, -0.071608759 0.063790798 0.068656385, -0.07379169 0.068307281 0.07042706, -0.075082697 0.066885531 0.070426852, -0.070377365 0.065146625 0.068656482, 0.071606696 0.09007284 0.073847726, 0.076544672 0.085916221 0.073847622, 0.079839721 0.089614809 0.074340537, -0.067056477 0.062072515 0.066582486, -0.06471438 0.064510792 0.066582747, -0.067919098 0.067705601 0.068656594, 0.074689105 0.09395048 0.074340776, -0.063843325 0.059098065 0.064214058, 0.072310835 0.095793009 0.074340984, 0.07778509 0.097845078 0.074505419, 0.072176367 0.10205248 0.074505731, 0.064514503 0.064710379 0.066582739, 0.068476617 0.06050247 0.066582471, 0.071867883 0.063498825 0.06865637, 0.065195471 0.05760327 0.064214051, 0.067709491 0.067915171 0.068656489, 0.061202168 0.06182918 0.064214244, -0.078189507 0.063225925 0.070426717, -0.078636326 0.070051283 0.071886145, -0.081890181 0.066218555 0.071885876, 0.066889465 0.075078666 0.070427239, 0.070994318 0.071209967 0.070426986, 0.07435438 0.07458055 0.071886376, 0.07005547 0.078632146 0.071886569, -0.06822978 0.060780644 0.066582516, 0.068551242 0.086229235 0.073028654, -0.067648396 0.054701984 0.064213902, 0.073278472 0.08224988 0.07302846, 0.069326609 0.091839343 0.07384792, -0.10172634 0.063695699 0.074339166, -0.097994775 0.06929934 0.07433942, -0.10205671 0.072171867 0.074503973, 0.069303527 0.097990572 0.074341044, -0.10594317 0.066336095 0.074503608, -0.074571952 0.060300589 0.068656296, 0.063794717 0.071604908 0.068656862, 0.065536082 0.082436502 0.071886882, -0.085985564 0.060806483 0.071885727, -0.08565788 0.069265217 0.073027633, -0.089941539 0.063603878 0.07302735, -0.097528093 0.061066747 0.073846117, 0.066368341 0.087920427 0.073028639, -0.093950406 0.066439092 0.073846467, 0.066443339 0.093946159 0.073848069, -0.071053006 0.057454973 0.066582263, -0.082099751 0.058058351 0.070426382, 0.060784459 0.06822589 0.066582859, 0.056935519 0.065778941 0.064214498, 0.065750822 0.1004087 0.074341223, -0.093366615 0.058460861 0.073027067, 0.066340402 0.105939 0.074505955, 0.062574387 0.078711092 0.070427582, -0.10513815 0.057891607 0.074338779, -0.10949637 0.060291499 0.074503511, 0.063449189 0.084053129 0.071886927, -0.078301147 0.05537203 0.068655923, 0.063608155 0.089937419 0.073028892, -0.089259975 0.055889398 0.071885422, 0.063699856 0.10172245 0.074341401, -0.10649013 0.055365533 0.074338615, -0.11270487 0.054057121 0.074503154, 0.063037321 0.096264601 0.073848158, 0.059679136 0.075069308 0.06865707, -0.10079905 0.055502295 0.073845848, -0.074606448 0.052759111 0.066582017, -0.071151294 0.050061345 0.064213686, 0.060581848 0.080254644 0.070427641, 0.060810491 0.085981458 0.071887106, -0.085226133 0.053363621 0.070426024, -0.10209519 0.05308035 0.073845707, 0.061070949 0.097523987 0.073848277, 0.060347512 0.092157096 0.073028937, -0.096497715 0.053133696 0.073026747, 0.056863144 0.071526796 0.066583067, -0.10821895 0.051905364 0.074338503, 0.052414611 0.069434792 0.064214766, -0.081282988 0.050894529 0.068655774, 0.057778925 0.076541334 0.068657175, -0.097738758 0.050815225 0.07302656, 0.058062375 0.082095653 0.070427716, 0.058897167 0.10457644 0.074341372, 0.06029588 0.10949197 0.074506059, -0.092253491 0.050796688 0.071885116, 0.058465049 0.093362302 0.073029056, -0.10375267 0.049763113 0.073845498, 0.057693109 0.088103414 0.071887195, -0.10995062 0.048129201 0.074338242, -0.11555874 0.047652543 0.074502587, 0.055052474 0.072929591 0.066583171, -0.077447556 0.048492879 0.066581793, -0.074336253 0.04519707 0.064213336, 0.055376038 0.078297228 0.06865719, -0.093439862 0.04858011 0.071885124, 0.056466475 0.10026017 0.073848352, -0.088084526 0.048501015 0.070425808, 0.055893615 0.089255959 0.071887314, -0.099325433 0.0476394 0.073026359, 0.055086002 0.084121764 0.070427701, -0.11095919 0.045755833 0.074338123, 0.052762985 0.074602574 0.066583306, 0.047659501 0.072780818 0.064214915, -0.10541288 0.046142638 0.073845297, 0.054057032 0.095981836 0.073029205, -0.089217186 0.046384543 0.070425771, 0.053367555 0.085222185 0.07042785, 0.052537188 0.080229729 0.068657368, -0.084008954 0.04625681 0.068655297, -0.094956808 0.045544058 0.071884662, -0.10637996 0.043867379 0.073845208, 0.051679343 0.091760248 0.071887285, 0.050898433 0.081279159 0.068657383, -0.10091478 0.04417339 0.07302627, 0.050058112 0.076443791 0.066583291, -0.085089162 0.044238329 0.068655327, -0.080044828 0.044074088 0.066581585, -0.077189475 0.040131032 0.064213075, 0.049343944 0.087613225 0.070428044, -0.090665586 0.043485731 0.070425548, 0.048496753 0.077443779 0.06658341, -0.11292004 0.040677756 0.074337713, 0.042691693 0.075801551 0.064215064, -0.11804919 0.041098207 0.074502245, -0.10184073 0.041995287 0.073026121, 0.045760095 0.11095518 0.074341834, 0.0519097 0.10821465 0.074341565, 0.054061487 0.1127004 0.074506283, 0.047656953 0.11555451 0.074506462, -0.096476123 0.042230487 0.071884513, 0.047060877 0.083559513 0.068657592, -0.081074253 0.042150855 0.066581421, -0.086470775 0.041473687 0.068655141, 0.043871433 0.10637584 0.073848784, 0.049767226 0.10374865 0.07384868, -0.10825962 0.038998634 0.073844895, 0.044840217 0.079616576 0.06658347, -0.097361282 0.040148228 0.071884483, -0.092116453 0.040321887 0.070425346, 0.041999623 0.1018365 0.073029563, 0.047643736 0.099321306 0.073029369, -0.082390338 0.039516479 0.066581413, -0.079697669 0.034885824 0.064212739, 0.039466605 0.11334628 0.074341908, -0.10364027 0.037334472 0.07302589, 0.041102454 0.11804488 0.07450667, -0.09296149 0.038333714 0.070425197, 0.040152222 0.097357243 0.071887776, 0.045548126 0.094952643 0.071887553, -0.08785437 0.038456291 0.068655036, 0.036885977 0.11421221 0.074341968, 0.034418747 0.12016392 0.074506789, -0.099081822 0.035692364 0.071884349, 0.037837729 0.10866827 0.073848814, -0.088660322 0.03655988 0.068654805, -0.083708815 0.036641598 0.066581219, 0.038337722 0.092957407 0.070428178, 0.043489709 0.090661585 0.070428208, -0.094604209 0.034079134 0.070425019, -0.084476799 0.034834713 0.066581041, 0.035363749 0.10949835 0.073848858, -0.081850275 0.029484689 0.064212486, -0.090227023 0.032502294 0.068654656, 0.036223218 0.10403112 0.073029563, -0.085969478 0.030968577 0.066580802, 0.033048898 0.11538079 0.074342027, 0.036563963 0.088656366 0.06865795, 0.041477576 0.086466789 0.068657771, 0.11751591 0.0025624037 0.074130252, 0.12001681 -0.0013946295 0.074335545, 0.12499991 0.00018891692 0.07449992, 0.11506364 -0.0013372898 0.073842645, 0.033854663 0.10482594 0.073029593, 0.11258264 0.0024546087 0.073473901, 0.11489575 0.0063511133 0.073843151, 0.034629896 0.099455446 0.07188791, 0.031684935 0.11061895 0.073848844, 0.017015457 0.11630169 0.074136667, 0.020452872 0.11323494 0.073849134, 0.021333322 0.11810938 0.074342199, 0.02917482 0.11642084 0.074341953, 0.027626768 0.12190464 0.074506834, 0.01630123 0.11141908 0.07348004, 0.012843668 0.1143482 0.073849149, 0.034838587 0.084472924 0.066583768, 0.039520442 0.082386553 0.066583842, 0.037533179 0.078483641 0.064215228, -0.022077203 0.11544791 0.074136615, -0.018591225 0.11857188 0.074342236, -0.021128654 0.12319708 0.074506924, 0.032206878 0.080815405 0.064215332, -0.017824024 0.11367831 0.073849112, -0.026469797 0.11706543 0.074342199, -0.025377393 0.11223394 0.073849082, 0.03236562 0.10021505 0.07188791, -0.021150485 0.11060134 0.073480062, 0.033065036 0.094960868 0.070428401, -0.093732558 0.070924014 0.074134059, -0.089475751 0.072352618 0.073846929, -0.093327366 0.075467259 0.074339867, 0.030332863 0.10589865 0.073029786, -0.11185559 0.036119401 0.074132137, 0.026527286 0.11705232 0.074342057, 0.027970761 0.11161581 0.073849112, -0.10715979 0.034602851 0.073475741, -0.11062307 0.031680644 0.073844492, 0.030902997 0.095686227 0.070428461, 0.12117171 0.0048137605 0.074407756, 0.12479246 0.0071974397 0.074500337, 0.11984168 0.0066247284 0.074336007, 0.1089415 0.0005543828 0.07276845, 0.1101537 -0.0012801588 0.073023736, 0.031535178 0.090567052 0.068657801, 0.10530879 -0.001224041 0.071882114, 0.10886209 0.0041942894 0.072768643, 0.028998733 0.10124072 0.071887895, 0.10999304 0.0060800016 0.073024139, 0.10515513 0.0058124959 0.071882561, 0.057255104 0.10689589 0.074413434, 0.025432408 0.11222136 0.07384906, 0.054287508 0.10425255 0.074135959, 0.054234385 0.10845968 0.074413598, 0.026777163 0.10685304 0.073029801, 0.054226294 0.10008985 0.073673993, 0.029473186 0.091258883 0.068658084, 0.050912112 0.10181549 0.073674247, 0.030047074 0.086293519 0.066583902, 0.018842459 0.11979046 0.074414171, 0.02074784 0.12326187 0.074506842, 0.026736885 0.082786024 0.064215347, 0.027688205 0.096665502 0.070428535, 0.015475258 0.12027174 0.074414283, 0.013803586 0.12423131 0.074506953, 0.013396561 0.11927074 0.074342296, 0.017569497 0.10751268 0.072774462, 0.018718943 0.10363486 0.071887977, 0.019580066 0.10840297 0.073029801, 0.024347231 0.10743278 0.073029816, 0.013967022 0.1080398 0.072774395, 0.012295693 0.10946864 0.073029958, 0.01175487 0.10465372 0.071888164, 0.02559948 0.10215303 0.071887985, -0.018670753 0.10732681 0.07277447, -0.017063498 0.1088275 0.073029943, -0.016313016 0.10404086 0.071888126, -0.022246897 0.10664314 0.072774425, 0.028082445 0.086952657 0.066583917, -0.024294585 0.10744467 0.073029816, -0.023225889 0.1027188 0.071888, 0.026407197 0.092192799 0.068658024, -0.095821351 0.07431969 0.074411534, -0.097849213 0.077780873 0.074504383, -0.097868159 0.07160306 0.074411437, -0.089659281 0.070141912 0.073672369, 0.023276299 0.10270742 0.071887903, -0.09187308 0.067216575 0.073672235, 0.024442628 0.097536534 0.070428647, -0.11496884 0.038569689 0.074409679, -0.11600552 0.035330176 0.074409433, 0.025161162 0.087842375 0.066584051, -0.12016806 0.03441453 0.074501872, -0.11538509 0.033044547 0.074337512, 0.11705668 -0.026531428 0.074334115, 0.12016806 -0.034423083 0.074498072, 0.12190887 -0.027630925 0.074498504, 0.021147341 0.084386975 0.064215519, -0.10309675 0.035203725 0.072770327, 0.11538509 -0.033053011 0.074333772, -0.10421564 0.031739086 0.072770312, -0.10590276 0.030328691 0.073025547, 0.022224545 0.098065674 0.07042864, -0.10124473 0.028994679 0.071883917, 0.11222571 -0.02543655 0.073841378, 0.1106232 -0.031689167 0.073840931, 0.10471529 -0.00034219027 0.071717113, 0.023311749 0.093023717 0.068658121, 0.1005498 -0.0011688769 0.070423082, 0.10743695 -0.024351299 0.073022306, 0.10590284 -0.030337065 0.073022038, 0.1033075 0.0016765893 0.071312606, 0.1060603 0.0034947693 0.072094947, 0.11835995 -0.019926131 0.074334428, 0.12326613 -0.020752072 0.074498683, 0.10466813 0.0031570494 0.071717218, 0.10460058 0.0049056411 0.071717352, 0.10271151 -0.023280442 0.071880981, 0.10124481 -0.029002815 0.071880519, 0.021196127 0.093528479 0.068658151, 0.10040306 0.0055496693 0.070423335, 0.052972704 0.095888734 0.072904065, 0.022211745 0.088634163 0.066584013, 0.11876057 -0.017378837 0.074334547, 0.1242356 -0.013807833 0.074499309, 0.052327767 0.097859979 0.07318826, 0.1134751 -0.019103885 0.073841602, 0.051391825 0.096745163 0.072903991, 0.01787293 0.098951459 0.070428669, 0.098069847 -0.02222839 0.07042186, 0.09666948 -0.027692318 0.070421532, 0.020195872 0.089115053 0.066584043, 0.049415693 0.09617731 0.072592437, 0.015463412 0.085611135 0.0642156, 0.048189014 0.098379493 0.072904259, 0.11385931 -0.016661763 0.07384178, 0.01775068 0.1031962 0.07172291, 0.10863318 -0.01828897 0.073022708, 0.016530201 0.10481858 0.072100572, 0.017046183 0.094372988 0.068658195, 0.11929072 -0.013258308 0.074334785, 0.0065445602 0.11984214 0.074342228, 0.0068159252 0.12480989 0.074507013, 0.01602374 0.10347849 0.071722925, 0.093532398 -0.021200001 0.068651706, 0.092196748 -0.026411057 0.068651274, 0.014386967 0.10231054 0.071318232, 0.10900088 -0.015950888 0.073022932, 0.012556925 0.1039561 0.071722895, 0.016241699 0.089919657 0.066584192, 0.01122351 0.099924296 0.070428781, -0.017083868 0.1033088 0.071722895, -0.015575796 0.09933877 0.070428699, 0.10385498 -0.017484635 0.071881235, 0.0062745214 0.11489582 0.073849149, -0.018840283 0.10158485 0.071318209, 0.1143675 -0.012711316 0.073842004, 0.11965582 -0.0094076693 0.074335024, 0.12481408 -0.0068200827 0.074499667, -0.021090969 0.10399678 0.07210058, 0.0060068071 0.1099931 0.073029988, -0.020526558 0.10268036 0.07172288, 0.089118868 -0.020199716 0.066577971, 0.08505033 -0.018319428 0.064209849, -0.022239491 0.10232297 0.071722955, 0.087846249 -0.025164872 0.066577762, -0.02217631 0.098076552 0.070428647, 0.10420661 -0.015249461 0.071881354, -0.098810375 0.034664571 0.071719117, -0.00018548965 0.12002045 0.074342288, -0.00019313395 0.12499556 0.074507028, 0.099161774 -0.016694695 0.070422143, 0.1094874 -0.012169063 0.07302314, -0.098142639 0.032295674 0.07131438, 0.0057425797 0.10515508 0.071888112, -0.10133968 0.031481057 0.072096527, 0.11984624 -0.0065488219 0.074335143, -0.099913672 0.03134346 0.071718916, -0.0026207864 0.11999196 0.074342437, -0.10042337 0.029669523 0.071718737, -0.0072016269 0.12478802 0.074506983, 0.11471757 -0.0090195835 0.073842227, -0.096669443 0.027684271 0.070424631, 0.099577636 0.00022909045 0.070079744, 0.099497423 -0.014560491 0.070422292, 0.095897615 -0.0011148751 0.068652719, -0.00017778575 0.11506683 0.073849231, 0.099514097 0.0035564303 0.070079863, 0.094573662 -0.015922159 0.068652004, 0.0054831505 0.10040277 0.070428669, 0.095757648 0.0052929223 0.068653122, 0.10467175 -0.011633933 0.071881518, 0.049439415 0.091852784 0.071609393, -0.0025125891 0.11503971 0.073849119, 0.11490011 -0.0062786043 0.073842362, 0.046398208 0.09342581 0.071609378, 0.015785396 0.098314762 0.070085138, -0.00017014146 0.1101568 0.073030002, 0.10982254 -0.0086349249 0.07302326, 0.012491301 0.098787248 0.070085362, 0.094893858 -0.013886839 0.068652183, -0.0069150031 0.11982119 0.074342348, 0.010704353 0.095300794 0.068658203, 0.090111062 -0.015171081 0.066578224, 0.08608368 -0.01259774 0.064210087, -0.016792491 0.098147631 0.070085242, -0.014855027 0.094742477 0.068658069, 0.0052294135 0.095757425 0.068658173, 0.099941552 -0.011108369 0.070422485, -0.020062968 0.097531915 0.070085108, -0.021150321 0.09353894 0.068658195, -0.0024054497 0.11013082 0.07302998, -0.00016272068 0.10531157 0.071888186, -0.094144255 0.032439709 0.070081517, -0.095175773 0.029275805 0.070081361, 0.10999723 -0.006011039 0.073023483, -0.0066296905 0.11487594 0.073849186, -0.092196718 0.026403248 0.068654358, 0.10499211 -0.0082551837 0.071881682, -0.010629758 0.11954895 0.07434231, -0.014187485 0.12418795 0.074506968, 0.095419392 0.0011496842 0.068450958, 0.090416178 -0.013231784 0.066578299, 0.09137243 -0.0010623038 0.066579074, 0.0049826503 0.091238767 0.066584162, 0.010199234 0.090803802 0.066584289, 0.009710446 0.086452782 0.06421563, 0.09403187 0.002486676 0.067853704, 0.095317483 -0.010594487 0.068652168, 0.0039141774 0.086908251 0.064215727, -0.0022995919 0.10528663 0.071888097, 0.095327511 0.0043374598 0.068451226, 0.091239139 0.0050429702 0.066579372, -0.00015544891 0.10055244 0.070428684, 0.048266485 0.087652445 0.070258066, -0.0063467473 0.10997397 0.07303001, 0.045968398 0.087302357 0.069751933, 0.10515927 -0.0057468116 0.07188195, 0.045363739 0.08918938 0.07025823, 0.10024752 -0.0078822672 0.070422694, -0.010190994 0.11461493 0.073849231, 0.090819672 -0.010094494 0.066578552, 0.086732656 -0.0068198442 0.064210519, 0.016045034 0.094063848 0.068456247, -0.013622805 0.11924487 0.074342206, 0.014048576 0.093005985 0.067858845, -0.0021956414 0.10052857 0.070428774, 0.012892753 0.094547391 0.068456069, 0.10040696 -0.0054872036 0.070422798, -0.00014820695 0.095899969 0.0686583, -0.017008588 0.093894303 0.068456091, -0.014154091 0.090271831 0.066584066, 0.095609248 -0.0075177252 0.068652451, -0.0060675889 0.10513681 0.071888156, -0.01809594 0.092303932 0.067858785, -0.009756133 0.1097241 0.073029973, -0.02013661 0.09327355 0.068456121, -0.020152271 0.089124948 0.066584051, -0.090518057 0.030206263 0.068452589, -0.01306051 0.11432344 0.073849156, 0.095761299 -0.0052333176 0.068652451, -0.089645907 0.028488219 0.067855306, -0.0020940602 0.0958772 0.068658337, -0.091477022 0.027164727 0.068452388, 0.091097727 -0.007163018 0.066578701, -0.087846279 0.025157332 0.066580459, -0.0001412183 0.091374576 0.066584259, 0.090481892 0.00067001581 0.066125438, 0.086867198 0.004801333 0.064211085, 0.086994186 -0.0010114312 0.064210728, -0.0018996596 0.086975634 0.064215638, 0.090408787 0.0036930442 0.066125721, 0.045434088 0.083406389 0.068263963, -0.0057934225 0.10038549 0.070428841, 0.042672232 0.084852487 0.068263963, 0.091242641 -0.0049864352 0.066578865, -0.009327054 0.10489801 0.071888171, 0.014799818 0.089262009 0.06613043, -0.012503296 0.10944501 0.073029824, 0.011808753 0.089706659 0.066130482, -0.0019952804 0.091352999 0.06658417, -0.015714332 0.089105666 0.066130437, -0.019186661 0.084854275 0.064215586, -0.01347588 0.085946262 0.064215675, 0.11924931 0.013618499 0.074336395, 0.12419234 0.014183313 0.074500814, -0.018683031 0.088530689 0.066130467, -0.0055253506 0.095740795 0.068658173, -0.085696325 0.029039919 0.066127017, -0.086619146 0.02616021 0.066126995, -0.0089055896 0.10015735 0.070428699, 0.042748109 0.080252022 0.066358149, -0.011953324 0.10463119 0.071888164, 0.11432773 0.013056427 0.073843449, -0.0052645504 0.091222912 0.066584311, -0.0077049732 0.086654454 0.064215682, 0.10944925 0.012499273 0.073024482, -0.0084935129 0.095523238 0.068658173, 0.11829774 0.02028355 0.074336648, 0.12320139 0.021124512 0.074501112, -0.011413082 0.0999026 0.070428677, -0.028003313 0.12181854 0.074506827, 0.10463537 0.011949241 0.071882963, -0.008092761 0.091015756 0.066584274, 0.11788875 0.02253899 0.074336842, 0.12182291 0.027999133 0.074501589, -0.010885179 0.095280468 0.068658143, 0.11341563 0.019446224 0.073843777, 0.099906772 0.011409163 0.070423767, -0.010371417 0.090784222 0.066584185, 0.11302343 0.021608591 0.073843911, 0.108576 0.018616378 0.073024794, 0.116974 0.026884675 0.074337095, -0.033405319 0.11527812 0.074342072, -0.034790099 0.12005684 0.074506797, 0.095284283 0.010881245 0.068653509, 0.10820065 0.020686418 0.073024899, 0.10380051 0.017797351 0.071883112, -0.032026686 0.11052048 0.073848896, 0.11214656 0.025774866 0.073844239, 0.11611974 0.030362695 0.074337274, 0.12006116 0.034785628 0.074501991, 0.090788141 0.010367692 0.066579789, 0.086352393 0.010592669 0.064211398, -0.030660003 0.10580423 0.073029689, 0.10344163 0.019776464 0.071883261, -0.039816655 0.11322379 0.074341975, -0.041467115 0.11791715 0.074506581, 0.099109665 0.016992956 0.070424005, 0.10736115 0.024674892 0.073025152, -0.029311575 0.10115063 0.071887977, 0.1113275 0.029109508 0.073844284, -0.041837476 0.1124928 0.074341796, -0.048013918 0.1154066 0.074506477, 0.11528242 0.033401161 0.074337453, -0.038173325 0.1085507 0.073848747, 0.098766983 0.018882573 0.070424169, 0.094523996 0.016206801 0.068653747, 0.10263905 0.023589581 0.071883529, -0.027986921 0.096579343 0.070428424, 0.10657707 0.027867287 0.073025331, -0.040110908 0.10785007 0.073848769, 0.11052467 0.032022446 0.073844597, -0.036544569 0.10391882 0.073029682, 0.094197288 0.018008739 0.068653896, 0.090063751 0.015441865 0.066579863, 0.085451797 0.016336739 0.064211786, -0.046102755 0.11081305 0.074341863, -0.026692003 0.092110842 0.06865795, 0.11383215 0.03805083 0.07433778, 0.11792161 0.041462868 0.074502289, -0.038399182 0.10324782 0.073029563, 0.09800069 0.022523433 0.070424408, -0.034937233 0.099347949 0.071887866, 0.10188942 0.026641309 0.071883723, -0.044200078 0.10623965 0.073848747, 0.10580848 0.03065598 0.07302551, -0.049257994 0.10944703 0.074341714, -0.05440931 0.11253282 0.07450632, 0.089752331 0.017159045 0.066580147, -0.025432594 0.087764263 0.066583984, 0.11322804 0.039812475 0.074337751, -0.024811648 0.083383232 0.064215489, -0.036710285 0.098706454 0.071887799, 0.10913427 0.036480278 0.073844686, -0.03335835 0.09485814 0.070428468, 0.093466446 0.021481216 0.06865412, -0.042313993 0.10170618 0.073029526, 0.097284988 0.025437295 0.070424527, -0.047225058 0.10493016 0.07384862, 0.10115463 0.029307544 0.071883872, -0.052243911 0.10805371 0.074341603, 0.10855506 0.038169265 0.07384482, -0.035051279 0.094245672 0.070428394, 0.10447748 0.034923434 0.073025793, -0.031814955 0.090469211 0.06865795, 0.089056045 0.02046746 0.066580236, 0.084169567 0.022007644 0.064212009, -0.04045298 0.097232789 0.071887642, 0.092783749 0.024260402 0.06865415, -0.045209996 0.10045236 0.073029369, 0.096583351 0.02798298 0.07042475, -0.050087713 0.10359421 0.07384859, 0.1039229 0.036540478 0.073025778, -0.033429623 0.089885086 0.068657942, 0.11103621 0.045569003 0.074338138, 0.11541089 0.048009634 0.074502647, -0.030313663 0.086200237 0.066584021, -0.030325882 0.08153984 0.06421525, 0.099882126 0.033387303 0.071884081, -0.05645857 0.10591272 0.074341528, -0.06063389 0.10930511 0.074506186, 0.088405535 0.023115516 0.066580355, -0.038624816 0.092838496 0.070428252, 0.092114672 0.026688129 0.068654507, -0.043221474 0.09603405 0.07188753, 0.099352047 0.03493312 0.071884125, -0.047950536 0.099173695 0.073029362, -0.031852111 0.085643589 0.066583902, 0.10645376 0.043688059 0.073845208, -0.058220573 0.10495454 0.074341454, 0.09536837 0.031878412 0.070424959, -0.05412855 0.1015414 0.073848397, 0.087768093 0.025428653 0.06658043, 0.082511336 0.027580529 0.064212278, -0.036837794 0.088542998 0.068657771, 0.094862178 0.033354282 0.070424989, -0.041268356 0.091694087 0.070428193, 0.10191123 0.041823894 0.073026106, -0.045841418 0.094811529 0.071887553, 0.090955839 0.030403405 0.068654642, 0.10805805 0.052239567 0.074338511, 0.11253719 0.054405212 0.074503034, -0.055817693 0.10062268 0.073848322, -0.05181881 0.097208411 0.07302919, 0.09047316 0.031810939 0.068654582, -0.035099506 0.084364831 0.066583842, -0.035704717 0.079332173 0.064215228, 0.097428799 0.039984196 0.071884498, -0.039358936 0.087451637 0.068657659, 0.086663991 0.028968662 0.066580713, -0.043769807 0.090526789 0.070428163, 0.10359846 0.050083548 0.073845431, -0.053435922 0.096328944 0.073029175, 0.086204067 0.030309826 0.066580802, 0.080484688 0.033029974 0.064212605, 0.093025923 0.038177162 0.070425197, -0.063406996 0.10190508 0.074341349, -0.066667512 0.10573334 0.074505955, -0.049539551 0.092932791 0.071887411, 0.099177733 0.047946423 0.073026419, -0.037501663 0.08332485 0.066583775, 0.10495874 0.058216244 0.074338838, 0.10930946 0.060629666 0.074503362, -0.041744679 0.086338222 0.068657584, -0.051085554 0.092092007 0.071887292, 0.088721797 0.036410719 0.06865491, 0.10397127 0.059961975 0.074338853, 0.1057377 0.066663235 0.074503615, -0.060790025 0.097699195 0.073848337, 0.094815612 0.045837313 0.071884856, -0.047301002 0.088732958 0.070428215, 0.10062701 0.055813521 0.073845819, -0.039774768 0.082263947 0.066583641, -0.040923908 0.076770186 0.064215042, -0.048777051 0.087930173 0.070428029, 0.084535167 0.034692615 0.066581041, -0.058196053 0.093530267 0.073028989, 0.09968023 0.05748713 0.073846027, -0.045112334 0.08462733 0.068657532, 0.090530783 0.043765783 0.0704256, -0.069606028 0.097775787 0.074340984, 0.096333236 0.053431779 0.073026851, -0.072491407 0.10182887 0.074505776, -0.046520159 0.083861709 0.068657547, -0.055636413 0.089416325 0.071887121, 0.10152914 0.064009786 0.074339211, 0.095426738 0.05503419 0.07302694, -0.042983614 0.080634028 0.066583544, 0.086342126 0.041740716 0.068655163, -0.06673333 0.093740374 0.073848054, 0.092096061 0.051081687 0.071885139, -0.044325091 0.079904497 0.066583551, 0.097339004 0.06136781 0.073846117, -0.045960508 0.073865384 0.064214915, -0.0531222 0.085375369 0.07042782, 0.099733576 0.06677261 0.07433939, 0.10183324 0.072487116 0.074503973, -0.063885882 0.089740366 0.073028781, 0.091229528 0.052613378 0.071885183, 0.08226791 0.03977108 0.066581309, 0.078098431 0.038332134 0.064212859, -0.074979171 0.093719155 0.074340738, -0.078087211 0.097604185 0.074505493, 0.087934211 0.048772871 0.070425779, -0.050664298 0.08142516 0.06865745, 0.093185529 0.05874911 0.073027074, -0.07642439 0.092544615 0.074340746, -0.083437264 0.093072176 0.074505307, -0.061075963 0.085793197 0.071887001, 0.095617592 0.064016789 0.07384631, 0.097780123 0.069601923 0.074339479, -0.071884736 0.089851201 0.073847733, 0.087106809 0.050235629 0.070425943, 0.083865657 0.046516269 0.068655565, -0.048273541 0.077582836 0.06658347, 0.08908689 0.05616498 0.071885303, -0.073270418 0.08872509 0.073847689, 0.091537535 0.061284989 0.073027208, -0.058315814 0.081915885 0.070427768, 0.093744606 0.066729128 0.073846504, -0.068817392 0.086017072 0.073028632, 0.083076581 0.047911197 0.068655506, -0.08011622 0.089367628 0.074340545, 0.079908267 0.044321388 0.066581547, -0.070143826 0.084938884 0.073028497, 0.075363621 0.043462843 0.064213187, 0.095050707 0.073284984 0.074339539, 0.097608447 0.078082949 0.074504405, -0.055617698 0.078125805 0.06865719, 0.085060924 0.053626716 0.070426151, -0.065790497 0.082233548 0.071886837, 0.087511435 0.05858928 0.071885437, -0.076809868 0.085679173 0.07384751, 0.089744583 0.063881725 0.073027417, 0.079156369 0.045650423 0.066581681, -0.082435474 0.087233275 0.074340545, -0.088524781 0.088247359 0.074505009, -0.067058533 0.081202835 0.071886845, 0.093723401 0.074975044 0.074339762, -0.052993402 0.074439228 0.066583343, -0.05079183 0.070630491 0.064214773, 0.091127947 0.070260316 0.073846698, -0.062817395 0.078517139 0.070427455, 0.081125379 0.051145434 0.06865567, 0.083556697 0.055941433 0.070426121, -0.073532388 0.082022995 0.073028371, 0.08579725 0.061071813 0.071885541, -0.079033166 0.083632976 0.073847495, -0.085001387 0.084734887 0.074340329, 0.089855462 0.071880519 0.073846713, -0.064028241 0.077533066 0.07042747, -0.059911154 0.074884504 0.068657137, 0.087239489 0.067262173 0.073027596, 0.077297211 0.048732042 0.066581905, -0.070298001 0.078415275 0.071886562, 0.07229197 0.048399568 0.06421347, 0.07969062 0.053353101 0.068655789, -0.075660743 0.080064118 0.07302814, 0.081920013 0.05831179 0.070426404, -0.081493229 0.081237704 0.073847353, 0.089943349 0.079469979 0.074339941, 0.093076438 0.083433062 0.074504673, -0.06106586 0.073945701 0.068657123, 0.086021215 0.068813264 0.073027745, -0.057084009 0.071350694 0.066583134, 0.083402395 0.064303577 0.071885899, -0.055396348 0.067080379 0.064214602, -0.088078067 0.081532419 0.074340127, -0.0933339 0.083144903 0.074504711, 0.075930312 0.050835401 0.066581905, -0.067121238 0.07487154 0.070427179, 0.078129664 0.055613816 0.068656027, -0.072332859 0.076542497 0.071886495, 0.086231321 0.076190025 0.073847011, -0.07801602 0.077771127 0.073028162, 0.08223772 0.065786451 0.071885914, -0.058184236 0.070456326 0.066582948, 0.079633325 0.061397493 0.070426539, 0.074443012 0.052989483 0.066582039, -0.089619033 0.079835504 0.074339889, 0.068897605 0.053119987 0.064213827, -0.084442995 0.078167349 0.073847257, 0.082551777 0.072938949 0.073027924, -0.064015806 0.071407378 0.068656951, 0.078521281 0.062813431 0.070426717, -0.0690642 0.073083401 0.070427224, 0.075948805 0.058556736 0.068656176, -0.074584588 0.074350268 0.071886346, 0.084739059 0.084997267 0.074340343, 0.088251621 0.088520616 0.074505016, 0.078920916 0.06973058 0.071886107, -0.085920423 0.07654044 0.073847145, -0.080839738 0.074831843 0.073027954, 0.074888289 0.059907109 0.068656161, -0.060994975 0.068037689 0.066582851, -0.059753351 0.063230544 0.064214297, 0.072365016 0.055793554 0.066582277, -0.065868825 0.06970188 0.068656728, 0.081241861 0.081489205 0.073847368, -0.07121402 0.070990235 0.070427001, 0.075354353 0.066579223 0.070426837, 0.071354449 0.057080209 0.066582233, -0.082254127 0.073274344 0.073027909, 0.077775285 0.078011781 0.073028117, -0.077284172 0.071540266 0.071886271, 0.083149165 0.093329698 0.07450515, -0.06276048 0.066412807 0.066582732, 0.04286401 -0.15911555 0.007777527, 0.041125141 -0.15977848 0.0019910187, 0.045150034 -0.1586881 0.0019909889, 0.043184325 -0.15706962 0.024398156, 0.040456362 -0.15710118 0.027991235, 0.041952282 -0.15800205 0.020791203, 0.044381596 -0.15603766 0.027991198, 0.03364677 -0.16131625 0.0077772364, 0.030111894 -0.16192585 0.0092197955, 0.031563446 -0.1618408 0.0056074187, 0.032998875 -0.16165239 0.0019909889, 0.037073798 -0.16076678 0.0019910187, 0.033528693 -0.16075066 0.014990963, 0.027756266 -0.1618472 0.014990859, 0.029113702 -0.16117084 0.018621743, 0.039396442 -0.16000921 0.0077773929, 0.041400112 -0.15925157 0.011386953, 0.033378795 -0.16003269 0.020791024, 0.036505617 -0.15806594 0.027991109, 0.032531969 -0.15893134 0.027991071, 0.030447394 -0.16039169 0.022237539, 0.039258234 -0.15944818 0.014991038, 0.039909266 -0.15928656 0.014991149, 0.039082833 -0.15873611 0.020791151, 0.041489273 -0.154421 0.037811011, 0.040247962 -0.15626642 0.031991325, 0.044142105 -0.15521136 0.031991422, 0.038143426 -0.14783832 0.057991624, 0.03978397 -0.15046597 0.050829217, 0.040776648 -0.14871845 0.054429226, 0.041723989 -0.14686802 0.057991862, 0.032642193 -0.15653002 0.037811033, 0.029218026 -0.15679374 0.039253205, 0.030806564 -0.15749267 0.035634696, 0.032386355 -0.15808281 0.031991184, 0.036328532 -0.15722373 0.031991236, 0.032197312 -0.15439734 0.044991314, 0.026658721 -0.15544948 0.044991225, 0.027886108 -0.15394086 0.048652984, 0.038215525 -0.15526339 0.037811033, 0.039805204 -0.15378791 0.04141441, 0.031772196 -0.15235889 0.050829098, 0.034540474 -0.14872149 0.057991594, 0.030917071 -0.14951676 0.057991542, 0.029079139 -0.15232509 0.052276023, 0.037694804 -0.153148 0.044991404, 0.038100973 -0.15304756 0.044991463, 0.037197024 -0.15112609 0.050829098, 0.029141843 -0.14253724 0.072016582, 0.025762998 -0.14318657 0.072016537, 0.028182551 -0.14555347 0.067054838, 0.038540006 -0.14315891 0.067056507, 0.037694283 -0.14603901 0.061991885, 0.041207731 -0.14508665 0.061991893, 0.031039856 -0.14497098 0.06705492, 0.030603379 -0.14768779 0.061991811, 0.034158796 -0.14690629 0.061991639, 0.03250435 -0.14180827 0.072016574, 0.035792239 -0.14387131 0.067054942, 0.035848558 -0.14099991 0.07201656, 0.042449348 -0.15763855 -0.022253327, 0.04045628 -0.15709808 -0.028008796, 0.044381522 -0.15603441 -0.028008737, 0.043729313 -0.15898496 -0.0056270957, 0.041125081 -0.1597783 -0.0020089746, 0.042281769 -0.15918097 -0.0092398524, 0.045149982 -0.15868783 -0.0020088851, 0.033333838 -0.15981451 -0.022253327, 0.029916875 -0.16071343 -0.020811096, 0.031236254 -0.15987214 -0.024417549, 0.032531925 -0.15892816 -0.028008848, 0.036505654 -0.15806276 -0.028008841, 0.033528745 -0.16074902 -0.015009098, 0.029233366 -0.16192615 -0.011403352, 0.027756266 -0.16184565 -0.015009008, 0.039030097 -0.15851963 -0.022253349, 0.041196592 -0.15851158 -0.018638067, 0.033629104 -0.16123089 -0.0092399418, 0.037073828 -0.16076657 -0.0020090789, 0.032998808 -0.16165221 -0.0020090118, 0.030694485 -0.16190329 -0.0077934116, 0.039258189 -0.15944657 -0.015008993, 0.039909378 -0.15928489 -0.015008882, 0.039375804 -0.15992454 -0.0092398822, 0.040186465 -0.14977348 -0.052290618, 0.038143501 -0.14783177 -0.058008373, 0.041724019 -0.14686149 -0.058008276, 0.042490065 -0.1547454 -0.035654001, 0.04024785 -0.15626276 -0.032008864, 0.040817976 -0.15417615 -0.039272957, 0.044142127 -0.15520772 -0.032008648, 0.031657904 -0.15180516 -0.052290566, 0.028606072 -0.1529786 -0.050848536, 0.029778697 -0.15129808 -0.054447971, 0.030917123 -0.14951023 -0.058008395, 0.034540556 -0.14871487 -0.058008395, 0.032197326 -0.15439233 -0.045008644, 0.028260887 -0.15631753 -0.041429922, 0.026658759 -0.15544432 -0.045008831, 0.037063286 -0.15057665 -0.052290522, 0.039166465 -0.15145952 -0.048668377, 0.032559447 -0.15612888 -0.039273001, 0.036328524 -0.15722016 -0.032008864, 0.03238637 -0.1580793 -0.032008819, 0.029854514 -0.15708223 -0.037826337, 0.03769473 -0.15314299 -0.04500857, 0.038100913 -0.15304241 -0.045008622, 0.038118795 -0.15486562 -0.039272919, 0.050489239 -0.15646127 -0.013008758, 0.047986172 -0.15754405 -0.0094030648, 0.046525538 -0.15768525 -0.013008788, 0.050489247 -0.15646264 0.012991175, 0.046525538 -0.15768671 0.01299113, 0.048849449 -0.15741184 0.0072199702, 0.052266315 -0.15630955 -0.0072396398, 0.051655464 -0.15670595 -8.7469816e-06, 0.049419358 -0.1573022 -0.0057931691, 0.054420672 -0.15513745 -0.013008758, 0.052324384 -0.15648383 -8.7618828e-06, 0.05026608 -0.15710917 0.0036075562, 0.05782406 -0.15433985 -0.0072394758, 0.058317699 -0.15371513 -0.01300852, 0.060627714 -0.15326041 -0.0072394758, 0.052287184 -0.1563729 0.0057776719, 0.054420635 -0.15513894 0.012991384, 0.057888478 -0.15451193 -8.6426735e-06, 0.062022068 -0.15285009 -0.0036266595, 0.063378401 -0.15234241 -8.6277723e-06, 0.061189987 -0.15310851 0.005777806, 0.057847187 -0.15440229 0.005777806, 0.059772871 -0.15346113 0.009387359, 0.058317736 -0.15371668 0.012991413, 0.047825933 -0.15161446 -0.041008517, 0.046515867 -0.15250677 -0.039429508, 0.044844024 -0.15188056 -0.043008573, 0.04859186 -0.15072328 -0.043008476, 0.050217807 -0.15083924 -0.041008502, 0.048167348 -0.15302682 -0.035825752, 0.052309811 -0.14947373 -0.043008402, 0.052597046 -0.15002608 -0.04100839, 0.050346263 -0.15240887 -0.035512738, 0.054963142 -0.14917552 -0.041008331, 0.055995815 -0.14813232 -0.043008395, 0.05076693 -0.15363795 -0.030008636, 0.051040523 -0.15467584 -0.024505749, 0.048401713 -0.15582052 -0.022810906, 0.049601912 -0.1547792 -0.026417352, 0.058783077 -0.14885899 -0.03727226, 0.057598136 -0.14981216 -0.035537206, 0.049181707 -0.15616673 -0.019008681, 0.0464077 -0.15727872 -0.017008826, 0.050356373 -0.15605935 -0.017008826, 0.051731393 -0.15534061 -0.019008741, 0.060483798 -0.14917868 -0.033653371, 0.060158595 -0.15020943 -0.030008376, 0.054272905 -0.1547409 -0.017008588, 0.054267198 -0.15447319 -0.019008711, 0.062153004 -0.14939535 -0.030008376, 0.056788459 -0.15356424 -0.019008741, 0.060449332 -0.15129435 -0.024252877, 0.05852706 -0.15199754 -0.024525881, 0.059325092 -0.15235698 -0.020637691, 0.05815509 -0.15332413 -0.017008707, 0.051314063 -0.15345621 -0.030008607, 0.052814968 -0.15295625 -0.029963762, 0.057443134 -0.1533204 -0.019008666, 0.04817418 -0.1494658 0.046991549, 0.045505449 -0.14890534 0.050653905, 0.044473812 -0.15060836 0.046991535, 0.044917189 -0.13837823 0.072016768, 0.041632399 -0.13940173 0.072016776, 0.044466563 -0.14160436 0.066743925, 0.049129121 -0.14685628 0.052830145, 0.047969967 -0.1439909 0.059991911, 0.04649055 -0.14709836 0.054276995, 0.051845148 -0.14823246 0.046991743, 0.048150241 -0.1439307 0.059991941, 0.046223782 -0.14284861 0.063390143, 0.054339573 -0.14500904 0.052830197, 0.055484578 -0.14690885 0.046991758, 0.056825891 -0.14405307 0.052830413, 0.047308706 -0.14141566 0.065409854, 0.048176989 -0.13727742 0.072016932, 0.053256921 -0.14212033 0.059992038, 0.057589449 -0.14214018 0.056430198, 0.058295719 -0.14012885 0.059992157, 0.055270039 -0.1384981 0.065410092, 0.052326232 -0.13963696 0.065409958, 0.053350776 -0.13734901 0.068736531, 0.051409714 -0.13609961 0.072016902, 0.04918164 -0.15616888 0.018991247, 0.047664538 -0.15639952 0.020622112, 0.046407759 -0.15728065 0.016991265, 0.05035641 -0.15606135 0.016991228, 0.051731348 -0.15534285 0.018991217, 0.048886053 -0.15541872 0.024237983, 0.054272883 -0.15474269 0.016991362, 0.054267228 -0.15447539 0.018991247, 0.051040493 -0.15467858 0.024488404, 0.056788407 -0.15356636 0.018991396, 0.05815509 -0.15332612 0.016991347, 0.050766893 -0.1536414 0.029991411, 0.050346203 -0.1524128 0.035495721, 0.047509171 -0.15283573 0.037253164, 0.049148373 -0.1532917 0.033634506, 0.060005158 -0.15173352 0.022791564, 0.058527038 -0.15200028 0.024508789, 0.047825985 -0.15161905 0.040991515, 0.044844024 -0.15188539 0.042991489, 0.048591852 -0.15072826 0.042991579, 0.050217852 -0.15084365 0.040991493, 0.061101906 -0.15061375 0.026398584, 0.060158551 -0.15021282 0.029991612, 0.052309886 -0.14947852 0.042991571, 0.052596934 -0.15003064 0.040991575, 0.062152863 -0.1493986 0.029991567, 0.054963104 -0.14918011 0.040991619, 0.059467189 -0.14900339 0.035811163, 0.057598211 -0.14981604 0.035520524, 0.057747304 -0.14862183 0.039414331, 0.055995815 -0.14813724 0.042991601, 0.051317103 -0.15346855 0.02994664, 0.052814953 -0.1529595 0.029946789, 0.055777326 -0.14887765 0.040991731, 0.0058504939 -0.15496066 -0.052290939, 0.0042907894 -0.15261304 -0.058008604, 0.0079974309 -0.15246379 -0.058008656, 0.0069903135 -0.1603207 -0.035654247, 0.0044666007 -0.1613009 -0.032009065, 0.0054867789 -0.15939349 -0.039273046, 0.008498013 -0.16113871 -0.03200908, -0.0029162765 -0.15504345 -0.05229073, -0.0061527342 -0.15550849 -0.050848685, -0.0046355873 -0.15413091 -0.05444809, -0.0031279176 -0.1526413 -0.058008589, 0.00058162957 -0.15267223 -0.058008581, -0.0029660091 -0.15768588 -0.045008883, -0.0085998327 -0.15747926 -0.045008875, -0.0072321147 -0.15868703 -0.041430056, 0.0026269108 -0.15504864 -0.052290745, 0.0044809803 -0.15637738 -0.048668563, -0.0029994026 -0.15945959 -0.03927324, 0.00043257326 -0.16136223 -0.032009013, -0.0036019087 -0.1613225 -0.03200905, -0.0058485046 -0.15978694 -0.037826538, 0.0026716664 -0.15769124 -0.045008823, 0.0030899867 -0.15768343 -0.045008846, 0.0027016997 -0.15946484 -0.039273217, 0.0063069984 -0.16313201 -0.022253528, 0.0044840947 -0.16216147 -0.028009154, 0.0085477158 -0.16199827 -0.02800899, 0.0072554871 -0.16472951 -0.0056273118, 0.0045399517 -0.16492343 -0.002009213, 0.005800426 -0.16459852 -0.0092400908, 0.0087066367 -0.16475612 -0.0020092279, -0.0030642748 -0.16322505 -0.02225361, -0.0065955743 -0.16334099 -0.020811282, -0.0051220506 -0.16281447 -0.024417721, -0.0036489069 -0.16218257 -0.028009005, 0.00041769445 -0.16222298 -0.028009132, -0.0030821785 -0.16417944 -0.015009202, -0.0089538693 -0.16396418 -0.01500921, -0.0075315833 -0.16437122 -0.011403412, 0.0027774051 -0.16323021 -0.022253588, 0.0048913658 -0.16370437 -0.018638358, -0.0030913725 -0.1646716 -0.0092400834, 0.00037033856 -0.16498554 -0.00200928, -0.0037995204 -0.16494223 -0.0020092279, -0.0061020032 -0.16467422 -0.007793583, 0.0027935207 -0.16418463 -0.015009224, 0.0034643784 -0.16417184 -0.015009172, 0.0028018951 -0.16467676 -0.0092400908, 0.0063829944 -0.16466433 0.0077771693, 0.0045398921 -0.1649237 0.0019906238, 0.0087066069 -0.16475621 0.0019907728, 0.0071506947 -0.16274109 0.02439785, 0.0044840127 -0.16216475 0.027990848, 0.005742155 -0.16337588 0.020790882, 0.0085475966 -0.16200146 0.027990863, -0.0030929446 -0.16475883 0.0077771544, -0.0066748783 -0.16456652 0.0092196241, -0.0052408203 -0.16480646 0.0056072176, -0.0037994981 -0.16494238 0.0019907728, 0.00037032366 -0.16498575 0.0019906014, -0.003082186 -0.16418111 0.014990859, -0.0089538395 -0.16396582 0.014990732, -0.0074796975 -0.16360846 0.018621631, 0.0028034225 -0.16476402 0.0077771693, 0.0049256012 -0.16447115 0.011386707, -0.0030683056 -0.16344792 0.020790882, 0.0004177615 -0.1622262 0.027990855, -0.0036488622 -0.16218576 0.027990907, -0.0060061067 -0.16314557 0.022237487, 0.0027935579 -0.16418636 0.014990769, 0.0034644678 -0.16417363 0.014990762, 0.0027811229 -0.1634531 0.020790882, -0.0033054575 -0.14544833 0.072016537, -0.0067440942 -0.14532945 0.072016336, -0.0049118176 -0.14817548 0.067054637, 0.0057187602 -0.14814568 0.067056209, 0.0042532384 -0.15076539 0.061991654, 0.0078905746 -0.15061879 0.061991587, -0.0019966885 -0.14824331 0.067054607, -0.0030267537 -0.15079501 0.061991513, 0.000613451 -0.15082404 0.061991572, 0.00013504922 -0.145486 0.072016433, 0.002881363 -0.14822879 0.067054607, 0.0035752803 -0.14544201 0.072016448, 0.0060876384 -0.15978161 0.037810788, 0.0044666305 -0.16130453 0.031990975, 0.0084979609 -0.16114232 0.031990968, 0.0042908564 -0.1526196 0.057991341, 0.0053052679 -0.15554625 0.050828904, 0.0066620708 -0.15406346 0.054428995, 0.007997483 -0.15247032 0.057991453, -0.0030069575 -0.15986925 0.037810802, -0.0064038485 -0.15936437 0.039253041, -0.0050108954 -0.16039905 0.035634346, -0.0036019087 -0.16132617 0.031991057, 0.00043255836 -0.16136581 0.031990983, -0.0029659569 -0.157691 0.044991098, -0.0070676431 -0.15628651 0.048652872, -0.0085997805 -0.15748435 0.044991225, 0.0027084574 -0.15987444 0.03781078, 0.0045867264 -0.15878966 0.041414082, -0.0029267445 -0.15560919 0.050828911, 0.00058163702 -0.15267879 0.057991333, -0.0031278953 -0.15264776 0.057991318, -0.0055447072 -0.15497679 0.052275762, 0.0026716813 -0.15769622 0.044991218, 0.0030900165 -0.15768856 0.044991158, 0.0026364103 -0.15561426 0.050828904, 0.014407314 -0.1637733 -0.013009243, 0.011726141 -0.16427201 -0.0094033927, 0.010270566 -0.1640847 -0.01300925, 0.014407232 -0.16377479 0.012990795, 0.010270581 -0.16408613 0.012990795, 0.012597337 -0.16433525 0.0072195232, 0.016173661 -0.16402084 -0.0072400868, 0.015489921 -0.16427135 -9.0897083e-06, 0.013177276 -0.16435525 -0.0057935268, 0.018534817 -0.1633577 -0.013009191, 0.016191661 -0.16420376 -9.2163682e-06, 0.014045723 -0.16435537 0.0036072135, 0.022030443 -0.16333738 -0.0072399676, 0.022650532 -0.16283807 -0.013009183, 0.025003977 -0.16290879 -0.0072399452, 0.01618015 -0.16408721 0.0057771653, 0.018534862 -0.16335911 0.012990832, 0.022054888 -0.16351947 -9.2536211e-06, 0.026454709 -0.16281891 -0.0036271065, 0.027889945 -0.16262597 -9.0524554e-06, 0.025586002 -0.16288584 0.0057771951, 0.022039153 -0.16340342 0.0057771578, 0.024126031 -0.16291425 0.0093867257, 0.022650592 -0.1628395 0.012990832, 0.013197899 -0.16319728 0.018990844, 0.011667617 -0.16308475 0.020621829, 0.010246225 -0.16366407 0.016990751, 0.014367133 -0.16335383 0.01699087, 0.015867479 -0.16295946 0.018990807, 0.013076723 -0.16240016 0.024237446, 0.018478893 -0.16293997 0.016990811, 0.018532872 -0.16267791 0.018990844, 0.015341885 -0.16215804 0.024488039, 0.021193206 -0.16235277 0.018990822, 0.022578955 -0.16242251 0.016990803, 0.015306115 -0.16108611 0.029991023, 0.01516939 -0.15979472 0.035495348, 0.012309365 -0.15957579 0.037252866, 0.013805911 -0.16038495 0.033634119, 0.024737135 -0.16128153 0.022791125, 0.023236804 -0.16121274 0.02450832, 0.012888998 -0.15846008 0.040991135, 0.0099225491 -0.1580562 0.042991161, 0.013833813 -0.1577619 0.042991102, 0.015393272 -0.15823632 0.040991172, 0.026055649 -0.16043416 0.026398011, 0.025225222 -0.15983334 0.029990949, 0.01773677 -0.15737087 0.042991161, 0.017893836 -0.15797311 0.04099115, 0.027350754 -0.15948334 0.029990979, 0.02038987 -0.15767038 0.04099112, 0.02482035 -0.15850022 0.035810508, 0.022817291 -0.15887672 0.035520002, 0.023228444 -0.15774566 0.039413899, 0.021628723 -0.15688333 0.042991228, 0.015880838 -0.16104007 0.029946201, 0.017454527 -0.16087705 0.029946253, 0.021251 -0.15755668 0.04099115, 0.01370763 -0.15643817 0.046991222, 0.011230677 -0.15529794 0.050653636, 0.0098458603 -0.15672854 0.046991199, 0.012999952 -0.14490393 0.072016388, 0.0095696971 -0.14517084 0.072016552, 0.011842594 -0.14794898 0.066743374, 0.015219353 -0.1541065 0.05282969, 0.014727168 -0.15105516 0.059991576, 0.012593269 -0.15375555 0.054276623, 0.017561026 -0.15605256 0.046991214, 0.014916219 -0.15103656 0.05999168, 0.013278842 -0.14955282 0.06338989, 0.020710319 -0.15346512 0.05282969, 0.021403886 -0.15557209 0.046991274, 0.023346946 -0.15308625 0.052829698, 0.014655545 -0.14839745 0.065409638, 0.016422972 -0.14455602 0.072016485, 0.020297669 -0.15040794 0.059991568, 0.024517164 -0.15139145 0.056429699, 0.025653273 -0.14958754 0.05999165, 0.023066513 -0.14732468 0.065409645, 0.019943066 -0.14777979 0.065409593, 0.021451026 -0.1457772 0.068736084, 0.019836657 -0.1441271 0.07201653, 0.01288902 -0.15845549 -0.041008875, 0.011413224 -0.15903386 -0.03942997, 0.009922497 -0.15805125 -0.043008998, 0.01383391 -0.1577571 -0.043008871, 0.015393361 -0.15823165 -0.041008875, 0.01290758 -0.15990835 -0.035826236, 0.017736763 -0.15736601 -0.043008812, 0.017893933 -0.15796864 -0.041008867, 0.015169375 -0.15979069 -0.03551311, 0.020389885 -0.15766576 -0.041008927, 0.02162876 -0.15687838 -0.043008871, 0.015306115 -0.16108257 -0.030009031, 0.015341967 -0.16215539 -0.024506316, 0.012514554 -0.16268411 -0.022811331, 0.013916425 -0.16193596 -0.026417799, 0.024184562 -0.15820715 -0.037272766, 0.022817232 -0.15887266 -0.03553775, 0.013197958 -0.16319516 -0.019009158, 0.010246277 -0.16366214 -0.017009214, 0.014367223 -0.16335189 -0.017009206, 0.015867591 -0.16295731 -0.019009285, 0.025771536 -0.15889752 -0.033653773, 0.0252252 -0.15982988 -0.030008987, 0.018478952 -0.16293803 -0.01700905, 0.018532827 -0.16267574 -0.019009061, 0.027350686 -0.15947977 -0.030009039, 0.021193177 -0.16235062 -0.019009031, 0.025267303 -0.16095224 -0.024253517, 0.023236796 -0.16120991 -0.024526417, 0.023934834 -0.16173822 -0.020638295, 0.022579022 -0.16242063 -0.017009087, 0.015879981 -0.1610271 -0.030009113, 0.017454438 -0.1608738 -0.029964328, 0.021885701 -0.16225871 -0.019009069, 0.088098705 -0.11577788 0.072018065, 0.085336223 -0.11782888 0.072017983, 0.088543236 -0.11891147 0.067056328, 0.096836001 -0.11226028 0.067058206, 0.09732376 -0.11522198 0.06199348, 0.10007618 -0.11283964 0.061993644, 0.09086477 -0.11714715 0.067056447, 0.091650546 -0.11978424 0.061993286, 0.094514683 -0.11753732 0.06199342, 0.090811923 -0.11366212 0.072018191, 0.094669588 -0.11409444 0.067056522, 0.093474358 -0.11148277 0.072018385, 0.10438041 -0.12112719 0.037812963, 0.10406269 -0.12332842 0.031992987, 0.10711354 -0.12068829 0.031993225, 0.098509192 -0.11664817 0.057993412, 0.10112761 -0.11830381 0.050831035, 0.1012637 -0.11629874 0.054431006, 0.10131422 -0.11422044 0.057993606, 0.097324453 -0.12686604 0.037812635, 0.094353803 -0.12858918 0.039254829, 0.096088283 -0.12852979 0.035636306, 0.097767942 -0.12837604 0.031992823, 0.10094691 -0.12589163 0.031992853, 0.095998161 -0.12513754 0.044992998, 0.091915727 -0.12659696 0.048654497, 0.091464482 -0.12848857 0.044992745, 0.10179634 -0.1233066 0.037812814, 0.10258821 -0.12128744 0.041416243, 0.094730623 -0.12348551 0.050830811, 0.095646329 -0.1190072 0.057993367, 0.092726827 -0.12129593 0.057993233, 0.092289582 -0.12462369 0.05227752, 0.10040917 -0.12162668 0.044993162, 0.10073145 -0.12135994 0.044993192, 0.099083349 -0.12002102 0.050830901, 0.10765661 -0.12476024 0.0077794492, 0.10637761 -0.12611198 0.0019930303, 0.10953096 -0.12338319 0.0019930154, 0.10705713 -0.12277806 0.024400055, 0.1046128 -0.12399012 0.027993128, 0.10635182 -0.12415254 0.020793036, 0.10768795 -0.1213288 0.027993202, 0.10030694 -0.13074222 0.0077790767, 0.097386606 -0.13282505 0.0092213899, 0.098657519 -0.13211861 0.0056089908, 0.099869184 -0.13132614 0.0019926578, 0.10315643 -0.12876022 0.0019927621, 0.099954993 -0.1302838 0.014992639, 0.096159585 -0.13257807 0.018623456, 0.095229968 -0.13377649 0.014992446, 0.10492017 -0.12706983 0.0077793151, 0.10639665 -0.1255179 0.011388928, 0.099508412 -0.12970206 0.020792678, 0.10147192 -0.12657341 0.0279928, 0.098267354 -0.12907743 0.02799274, 0.09702304 -0.13129741 0.022239164, 0.10455198 -0.12662449 0.014992997, 0.10506848 -0.12619624 0.014993012, 0.10408489 -0.12605894 0.020792872, 0.10664283 -0.12360924 -0.022251368, 0.10461278 -0.1239869 -0.028006941, 0.10768797 -0.1213257 -0.028006777, 0.10837986 -0.12426683 -0.005625084, 0.10637762 -0.12611172 -0.0020071566, 0.10716078 -0.12507176 -0.0092379302, 0.10953084 -0.12338281 -0.0020069927, 0.099374235 -0.12952486 -0.022251725, 0.096685551 -0.13181722 -0.020809427, 0.097509407 -0.13048673 -0.024416029, 0.098267317 -0.12907407 -0.028007388, 0.10147195 -0.12657028 -0.028007135, 0.099955067 -0.13028228 -0.015007317, 0.096595757 -0.13320643 -0.011401683, 0.095230006 -0.13377473 -0.0150076, 0.1039445 -0.12588668 -0.022251457, 0.1058929 -0.12493932 -0.018636107, 0.10025448 -0.13067278 -0.009238258, 0.1031564 -0.12875992 -0.0020072609, 0.099869348 -0.13132599 -0.002007395, 0.097902067 -0.13255182 -0.0077918172, 0.10455205 -0.12662277 -0.015007153, 0.10506853 -0.1261946 -0.015007228, 0.10486522 -0.12700242 -0.0092379302, 0.10119229 -0.11750457 -0.052288726, 0.098509304 -0.11664167 -0.0580066, 0.10131419 -0.11421388 -0.058006465, 0.10542468 -0.12098491 -0.035651997, 0.10406273 -0.12332481 -0.032006964, 0.10367128 -0.1211974 -0.039271012, 0.1071135 -0.12068468 -0.03200677, 0.094389789 -0.12303555 -0.05228892, 0.092149273 -0.12541687 -0.050846949, 0.092476673 -0.12339413 -0.05444625, 0.092726804 -0.12128943 -0.058006763, 0.095646299 -0.11900067 -0.058006719, 0.095998205 -0.12513244 -0.045006931, 0.093286842 -0.12857521 -0.041428372, 0.091464579 -0.12848359 -0.045007184, 0.098726749 -0.11958331 -0.052288741, 0.10100477 -0.11946625 -0.048666567, 0.097077727 -0.12654009 -0.03927128, 0.10094689 -0.12588802 -0.032007053, 0.097767964 -0.12837243 -0.032007203, 0.09505415 -0.12857246 -0.037824795, 0.10040911 -0.12162155 -0.045006827, 0.10073145 -0.12135485 -0.045006827, 0.10153837 -0.12298974 -0.039271072, 0.10825297 -0.11376238 0.046993583, 0.10560536 -0.11441517 0.050655887, 0.10541488 -0.1163972 0.046993434, 0.10050733 -0.10518605 0.072018653, 0.097991832 -0.10753348 0.072018579, 0.10150118 -0.10828817 0.066745654, 0.10798099 -0.11099687 0.05283235, 0.10569329 -0.10891819 0.059993908, 0.10570884 -0.11235976 0.05427891, 0.1110253 -0.11105821 0.046993732, 0.10582957 -0.10878584 0.059993848, 0.10362431 -0.10864675 0.063392252, 0.11187403 -0.10707179 0.052832425, 0.11373011 -0.10828668 0.046993896, 0.11369928 -0.10513186 0.052832544, 0.10398009 -0.10688511 0.065411776, 0.10296661 -0.10277992 0.072018847, 0.109645 -0.10493907 0.059994161, 0.11355729 -0.10307702 0.056432322, 0.11332074 -0.10095844 0.059994444, 0.1098871 -0.10080215 0.065412119, 0.10772882 -0.10310546 0.06541191, 0.10765921 -0.10059947 0.06873852, 0.10536828 -0.10031599 0.072018936, 0.10887371 -0.11584866 -0.041006535, 0.10808051 -0.11722121 -0.039427504, 0.10630263 -0.11738241 -0.043006584, 0.10917715 -0.11471364 -0.043006495, 0.1106923 -0.11411247 -0.041006431, 0.10979391 -0.11697316 -0.035823703, 0.11198477 -0.11197454 -0.043006405, 0.11248312 -0.11234769 -0.041006327, 0.11148901 -0.11547109 -0.035510689, 0.11424585 -0.1105547 -0.041006207, 0.11472359 -0.10916668 -0.043006122, 0.11240119 -0.11639595 -0.030006573, 0.11309788 -0.11721241 -0.024503767, 0.11121693 -0.11938861 -0.022808895, 0.11184654 -0.11792958 -0.026415259, 0.11755002 -0.10861215 -0.037270024, 0.11689597 -0.10998496 -0.035535067, 0.11206982 -0.11936218 -0.019006699, 0.11005308 -0.12156758 -0.017006814, 0.11308147 -0.11875567 -0.017006651, 0.11400856 -0.11751169 -0.019006535, 0.11922106 -0.10816225 -0.033650905, 0.11937515 -0.10923207 -0.030006036, 0.1160382 -0.11586839 -0.017006621, 0.11591683 -0.11562976 -0.019006431, 0.12081866 -0.10763305 -0.030006006, 0.11779404 -0.11371684 -0.019006416, 0.12010767 -0.11008337 -0.024250701, 0.11868086 -0.11155099 -0.024523571, 0.11955574 -0.11152864 -0.020635486, 0.11892113 -0.11290762 -0.017006338, 0.11281518 -0.11599466 -0.030006617, 0.11395062 -0.11489314 -0.029961631, 0.11827818 -0.11321324 -0.019006297, 0.11206982 -0.11936426 0.018993244, 0.1108029 -0.12023038 0.02062425, 0.11005305 -0.12156948 0.016993046, 0.11308154 -0.11875767 0.016993403, 0.11400856 -0.11751378 0.018993452, 0.11147777 -0.1188167 0.024239987, 0.11603812 -0.11587042 0.016993448, 0.11591689 -0.11563194 0.018993556, 0.11309787 -0.11721516 0.024490505, 0.11779405 -0.11371911 0.018993661, 0.11892121 -0.11290953 0.016993567, 0.1124012 -0.11639932 0.0299934, 0.11148894 -0.11547503 0.035497829, 0.10911632 -0.11708692 0.037255257, 0.11079097 -0.11678642 0.033636615, 0.11989684 -0.110672 0.022793859, 0.11868083 -0.11155367 0.024511069, 0.1088737 -0.11585334 0.040993422, 0.10630257 -0.11738712 0.042993367, 0.10917722 -0.11471859 0.04299362, 0.11069226 -0.11411709 0.040993541, 0.12039921 -0.10918742 0.026400834, 0.11937512 -0.10923541 0.029993966, 0.1119848 -0.11197954 0.04299365, 0.1124832 -0.11235231 0.040993601, 0.12081868 -0.1076366 0.029993981, 0.11424588 -0.11055931 0.040993899, 0.11822732 -0.10844582 0.035813391, 0.11689595 -0.10998896 0.035522684, 0.11651218 -0.10884836 0.039416641, 0.11472367 -0.1091716 0.042993933, 0.11282193 -0.11600497 0.029948771, 0.1139506 -0.11489636 0.029948875, 0.11484825 -0.10993358 0.040993884, 0.11337543 -0.11906016 -0.013006598, 0.11159 -0.12112173 -0.0094009042, 0.11033541 -0.12188277 -0.013006851, 0.11337546 -0.11906156 0.012993336, 0.11033539 -0.12188423 0.012993157, 0.11231003 -0.1206283 0.0072220266, 0.11491063 -0.1181525 -0.0072374493, 0.11453208 -0.11877474 -6.6161156e-06, 0.11277623 -0.12028205 -0.0057910085, 0.11634333 -0.11616179 -0.013006508, 0.11503843 -0.11828423 -6.6459179e-06, 0.11345529 -0.11974096 0.003609851, 0.11906345 -0.11396649 -0.0072372705, 0.11923712 -0.11318934 -0.01300627, 0.121121 -0.1117774 -0.0072371066, 0.11495665 -0.11820054 0.005779773, 0.11634337 -0.11616319 0.012993529, 0.11919593 -0.11409366 -6.3478947e-06, 0.12320086 -0.10975695 -6.1094761e-06, 0.12156142 -0.1113967 0.0057801753, 0.12219919 -0.11080286 -0.0036242604, 0.11911111 -0.11401278 0.0057800412, 0.12043742 -0.11232919 0.0093896538, 0.11923712 -0.1131908 0.012993783, 0.074810505 -0.14131713 0.037811801, 0.074010931 -0.14339247 0.031991988, 0.077572681 -0.14149734 0.031992048, 0.070083611 -0.13564414 0.057992384, 0.072267666 -0.13784066 0.050829925, 0.072846547 -0.13591635 0.054429963, 0.073358387 -0.13390127 0.057992451, 0.066654511 -0.14534202 0.037811577, 0.063374981 -0.14636108 0.039253801, 0.06507916 -0.14668894 0.035635203, 0.06675078 -0.14691275 0.03199178, 0.070402861 -0.14519802 0.03199181, 0.065746218 -0.14336187 0.044992045, 0.060580589 -0.14561999 0.044991784, 0.061441399 -0.14387619 0.048653662, 0.071806334 -0.142867 0.037811726, 0.073027678 -0.14107472 0.041415021, 0.064877965 -0.14146912 0.050829716, 0.066767424 -0.13730675 0.057992138, 0.063411802 -0.13888851 0.057992198, 0.062245004 -0.14203534 0.052276425, 0.070827827 -0.14092043 0.044992119, 0.071201324 -0.14073205 0.044992149, 0.069892511 -0.13906005 0.050829895, 0.077195764 -0.14558801 0.007778272, 0.075648025 -0.14662138 0.0019918084, 0.079329453 -0.14466274 0.0019918233, 0.077052608 -0.1435222 0.024398848, 0.074399985 -0.14416006 0.027991951, 0.07605911 -0.14470533 0.020791844, 0.077990085 -0.14224967 0.02799198, 0.068699345 -0.14978459 0.0077780038, 0.065388799 -0.15116557 0.009220466, 0.066784948 -0.15075952 0.0056080669, 0.06814263 -0.15025654 0.0019915998, 0.071918227 -0.14848635 0.0019916743, 0.068458311 -0.14925954 0.01499173, 0.064247407 -0.15065151 0.018622473, 0.063074581 -0.15161306 0.014991432, 0.074013963 -0.14723104 0.007778272, 0.075798817 -0.14604622 0.011387751, 0.068152308 -0.1485928 0.020791709, 0.070762999 -0.1459797 0.027991712, 0.067081451 -0.14770755 0.027991757, 0.06537433 -0.14959523 0.022238076, 0.073754296 -0.14671484 0.014991745, 0.074353136 -0.14641222 0.01499182, 0.073424734 -0.14605963 0.020791799, 0.060127817 -0.13247904 0.0720172, 0.056978151 -0.13386387 0.072017051, 0.059863836 -0.13563317 0.067055337, 0.069428764 -0.13099381 0.067057267, 0.069245175 -0.13398984 0.061992593, 0.072458722 -0.1322796 0.061992608, 0.062519796 -0.13442934 0.067055479, 0.062698953 -0.13717514 0.061992228, 0.065991342 -0.13562205 0.061992422, 0.063243754 -0.13102004 0.072017163, 0.066908374 -0.13229978 0.067055598, 0.066324487 -0.1294879 0.072017275, 0.072507314 -0.13707605 -0.052289762, 0.070083596 -0.13563773 -0.05800768, 0.073358417 -0.13389483 -0.058007538, 0.075859383 -0.14141077 -0.035653144, 0.074010909 -0.1433889 -0.032008022, 0.074102528 -0.14122769 -0.039272085, 0.077572688 -0.14149374 -0.032008022, 0.064644657 -0.14095435 -0.052289985, 0.061930396 -0.14277768 -0.050847948, 0.062699609 -0.14087835 -0.054447323, 0.063411891 -0.13888198 -0.058007762, 0.066767402 -0.13730028 -0.058007769, 0.065746263 -0.1433568 -0.045008019, 0.060580611 -0.14561492 -0.045008145, 0.062336765 -0.14610976 -0.041429326, 0.069641054 -0.13855401 -0.052289799, 0.071887955 -0.13894662 -0.04866752, 0.066485524 -0.14496914 -0.039272405, 0.070402853 -0.14519444 -0.032008082, 0.066750765 -0.14690924 -0.032008216, 0.064060427 -0.1465005 -0.037825756, 0.070827805 -0.14091536 -0.04500787, 0.071201324 -0.14072704 -0.045007922, 0.071624242 -0.14250046 -0.039272115, 0.076463237 -0.14424032 -0.02225247, 0.074399941 -0.14415684 -0.028008148, 0.077990152 -0.14224648 -0.028007925, 0.078010462 -0.14526808 -0.005626142, 0.075647965 -0.14662123 -0.0020082444, 0.076642841 -0.1457814 -0.0092390627, 0.079329386 -0.14466238 -0.0020081103, 0.068060458 -0.14839008 -0.022252709, 0.06492918 -0.1500268 -0.020810455, 0.066028289 -0.14891297 -0.024416983, 0.067081474 -0.14770448 -0.028008386, 0.070762977 -0.14597654 -0.028008163, 0.068458222 -0.14925781 -0.015008375, 0.064532518 -0.15136129 -0.011402741, 0.063074566 -0.15161142 -0.015008584, 0.073325746 -0.1458602 -0.02225247, 0.075436108 -0.14537027 -0.018637344, 0.068663374 -0.14970526 -0.0092392713, 0.071918257 -0.1484862 -0.0020083785, 0.068142541 -0.1502564 -0.0020083636, 0.065951921 -0.15101382 -0.0077928305, 0.073754266 -0.14671302 -0.015008375, 0.074353114 -0.14641052 -0.015008256, 0.073975213 -0.1471529 -0.0092391074, 0.080224968 -0.13499874 0.046992496, 0.077498481 -0.13504612 0.050654799, 0.076871663 -0.13693592 0.046992242, 0.074582212 -0.12491393 0.072017469, 0.071607456 -0.1266427 0.072017573, 0.074860707 -0.12815937 0.066744663, 0.08057522 -0.13224202 0.052831009, 0.078807503 -0.1297065 0.05999276, 0.078056812 -0.13306528 0.054277882, 0.083529539 -0.13297939 0.0469926, 0.078969896 -0.12960777 0.059992641, 0.076850787 -0.12898132 0.063390896, 0.085244022 -0.12928167 0.052831128, 0.08678323 -0.1308791 0.046992734, 0.087455198 -0.12779641 0.052831277, 0.077589817 -0.12734297 0.065410659, 0.077515237 -0.12311521 0.072017618, 0.083545662 -0.12670648 0.059993014, 0.087774038 -0.12576166 0.05643101, 0.08801499 -0.1236437 0.059993103, 0.084702276 -0.12272704 0.065411061, 0.08208558 -0.12449229 0.065410703, 0.082575262 -0.12203372 0.068737358, 0.080404915 -0.12124765 0.072017796, 0.082699127 -0.14130938 0.018992051, 0.081271343 -0.14187208 0.020623073, 0.080242239 -0.14301065 0.016992033, 0.083820514 -0.14094323 0.016992092, 0.085001171 -0.13993689 0.018992081, 0.082243964 -0.14064389 0.024238795, 0.087345496 -0.13878623 0.016992271, 0.087280333 -0.13852674 0.01899223, 0.084179856 -0.13944298 0.024489373, 0.089536101 -0.13707951 0.018992275, 0.090815015 -0.13654107 0.01699239, 0.083682053 -0.13849264 0.029992163, 0.082998507 -0.13738847 0.035496578, 0.080326729 -0.13843209 0.037254065, 0.082026213 -0.13851175 0.033635333, 0.092264257 -0.13457674 0.022792518, 0.09088251 -0.13516572 0.024509802, 0.080364868 -0.13717553 0.040992349, 0.077516712 -0.13809866 0.042992383, 0.080913119 -0.13613638 0.042992428, 0.082524039 -0.13588727 0.040992469, 0.093084365 -0.13324115 0.026399612, 0.092075445 -0.13306025 0.029992566, 0.084259845 -0.13409078 0.042992532, 0.084662728 -0.13456526 0.040992558, 0.09383858 -0.13182265 0.029992595, 0.08678022 -0.13320938 0.040992528, 0.091132097 -0.13203487 0.03581208, 0.089490779 -0.13324317 0.035521343, 0.089370437 -0.13204584 0.039415315, 0.08755485 -0.13196287 0.042992502, 0.084180094 -0.13820171 0.029947549, 0.085527092 -0.13737223 0.029947609, 0.087506711 -0.13273335 0.040992543, 0.084039345 -0.14130348 -0.013007894, 0.081840016 -0.14291611 -0.0094022155, 0.080447488 -0.14337882 -0.013008207, 0.084039375 -0.14130491 0.012992099, 0.080447473 -0.14338028 0.01299198, 0.082651988 -0.14259523 0.00722076, 0.085738055 -0.14076012 -0.0072386712, 0.085230589 -0.14128253 -7.8976154e-06, 0.083183408 -0.14236149 -0.00579229, 0.087577805 -0.13913819 -0.013007745, 0.085833505 -0.14091712 -7.9423189e-06, 0.08396586 -0.14198482 0.0036085397, 0.090718254 -0.13760325 -0.0072386712, 0.091060497 -0.13688427 -0.013007671, 0.09321139 -0.13592693 -0.0072384328, 0.08577235 -0.14081722 0.005778566, 0.087577812 -0.13913962 0.012992233, 0.090819225 -0.13775679 -7.6889992e-06, 0.095688656 -0.13441986 -7.4952841e-06, 0.093725652 -0.13565376 0.0057788342, 0.094479389 -0.13521653 -0.0036257058, 0.090754606 -0.1376591 0.0057786256, 0.092422381 -0.13631284 0.0093883127, 0.09106046 -0.1368857 0.012992308, 0.080364779 -0.13717079 -0.041007727, 0.079286091 -0.13833231 -0.039428666, 0.077516794 -0.13809377 -0.043007851, 0.080913097 -0.13613164 -0.043007642, 0.082524061 -0.13588268 -0.041007549, 0.081011802 -0.13847181 -0.035824984, 0.084259912 -0.13408598 -0.043007523, 0.084662721 -0.13456056 -0.041007534, 0.082998469 -0.13738447 -0.035511941, 0.086780295 -0.13320479 -0.041007563, 0.087554805 -0.1319581 -0.043007404, 0.083682105 -0.13848925 -0.030007705, 0.084179834 -0.1394403 -0.024505064, 0.081861742 -0.14114335 -0.022810191, 0.082800262 -0.13986114 -0.026416644, 0.090433881 -0.13204625 -0.037271351, 0.089490823 -0.13323918 -0.035536304, 0.082699172 -0.14130723 -0.01900807, 0.080242224 -0.14300862 -0.017008036, 0.083820567 -0.14094135 -0.017007992, 0.0850012 -0.13993478 -0.019007832, 0.092163168 -0.1319797 -0.033652291, 0.092075333 -0.13305667 -0.030007541, 0.087345473 -0.13878429 -0.017007813, 0.087280348 -0.13852468 -0.019007742, 0.093838617 -0.13181928 -0.030007407, 0.089536101 -0.13707736 -0.019007698, 0.092600189 -0.13404974 -0.024252117, 0.090882577 -0.13516304 -0.024524882, 0.091740526 -0.13533598 -0.020636752, 0.090815 -0.13653913 -0.017007619, 0.084175035 -0.13819018 -0.03000775, 0.085527167 -0.1373688 -0.029962838, 0.090120219 -0.1366941 -0.019007623, -0.022694312 -0.1573506 -0.041008785, -0.024261788 -0.1575861 -0.039429657, -0.025496401 -0.15629658 -0.043008827, -0.021617703 -0.15687999 -0.043008856, -0.02020295 -0.15768981 -0.041008852, -0.022999436 -0.15877122 -0.035826162, -0.017725714 -0.15736723 -0.043008864, -0.017706513 -0.15798968 -0.041008912, -0.020768173 -0.15915987 -0.035513133, -0.015205748 -0.15824983 -0.041008964, -0.013822913 -0.15775806 -0.043009013, -0.020922378 -0.16044983 -0.030009039, -0.021125942 -0.16150379 -0.024506114, -0.024000071 -0.16138992 -0.022811323, -0.022467107 -0.16097254 -0.026417673, -0.01162672 -0.15962207 -0.037272863, -0.013107739 -0.15996677 -0.035537802, -0.023447536 -0.16204032 -0.019009046, -0.026429117 -0.16183877 -0.017009094, -0.022342563 -0.16245326 -0.017009072, -0.020791858 -0.1624026 -0.019009061, -0.010232896 -0.16064808 -0.033653878, -0.010973111 -0.16143563 -0.030009076, -0.018241741 -0.16296473 -0.017009214, -0.018130757 -0.16272107 -0.019009098, -0.0088231042 -0.16156745 -0.030009069, -0.015464909 -0.16299605 -0.019009173, -0.011181645 -0.16253933 -0.024253562, -0.013218768 -0.16233879 -0.024526536, -0.012655713 -0.1630089 -0.020638384, -0.014129281 -0.16337278 -0.017009258, -0.020350449 -0.1605233 -0.030009031, -0.018781327 -0.1607241 -0.029964142, -0.014769226 -0.16306055 -0.019009069, -0.023447558 -0.16204241 0.018990956, -0.024914443 -0.16159222 0.020621851, -0.026429109 -0.16184068 0.016990826, -0.022342443 -0.16245538 0.016990818, -0.020791873 -0.1624046 0.018991016, -0.023388244 -0.16123834 0.024237603, -0.018241823 -0.16296655 0.016990826, -0.018130839 -0.16272318 0.018990859, -0.021125861 -0.16150644 0.024488017, -0.01546488 -0.1629982 0.018990785, -0.01412937 -0.16337466 0.016990818, -0.020922296 -0.16045326 0.029990986, -0.020768225 -0.1591638 0.035495348, -0.023507647 -0.15831399 0.037252806, -0.0222288 -0.15943581 0.033634245, -0.011771359 -0.16274247 0.022791013, -0.01321876 -0.16234159 0.024508193, -0.022694305 -0.15735525 0.040991157, -0.025496475 -0.15630141 0.042991139, -0.021617636 -0.15688485 0.042991139, -0.020202979 -0.15769446 0.04099115, -0.010297351 -0.16220954 0.026397899, -0.010973148 -0.161439 0.029991008, -0.017725714 -0.15737206 0.042991266, -0.017706543 -0.15799421 0.04099115, -0.0088230148 -0.16157079 0.029990956, -0.015205696 -0.15825456 0.04099118, -0.01107116 -0.16004941 0.035810567, -0.013107777 -0.15997073 0.035519928, -0.012455054 -0.15895957 0.03941378, -0.013822787 -0.15776289 0.042991124, -0.020351507 -0.1605362 0.02994623, -0.018781267 -0.1607275 0.029946253, -0.014340945 -0.15833515 0.040991142, -0.022397004 -0.16287312 -0.013009138, -0.025121942 -0.16276267 -0.0094032511, -0.026499391 -0.16225609 -0.013009027, -0.022397071 -0.16287452 0.012990922, -0.026499368 -0.16225752 0.012991004, -0.024286397 -0.1630182 0.0072195902, -0.020729996 -0.16350743 -0.0072401389, -0.021452256 -0.16359955 -9.2312694e-06, -0.023725621 -0.16316667 -0.0057934448, -0.01828061 -0.16338634 -0.013009258, -0.020753108 -0.16368976 -9.1791153e-06, -0.022878811 -0.16336012 0.0036072433, -0.014867984 -0.1641444 -0.0072401091, -0.014152437 -0.16379553 -0.013009258, -0.011873677 -0.16438818 -0.0072402507, -0.020738296 -0.16357359 0.005777292, -0.018280543 -0.16338781 0.012990795, -0.014884613 -0.16432747 -9.2387199e-06, -0.0089970082 -0.16475463 -9.2685223e-06, -0.011300787 -0.16449544 0.0057771355, -0.010439262 -0.16462347 -0.0036273748, -0.014874004 -0.16421077 0.0057772398, -0.012730524 -0.16419822 0.0093867779, -0.014152497 -0.16379705 0.012990795, -0.021446243 -0.15556622 0.046991147, -0.023607351 -0.15390334 0.050653644, -0.025275834 -0.15499011 0.04699146, -0.019569278 -0.14416376 0.072016545, -0.022972934 -0.14366058 0.072016537, -0.021375209 -0.14687485 0.066743456, -0.019453473 -0.15362948 0.05282969, -0.019254312 -0.15054506 0.059991643, -0.021935686 -0.15270287 0.054276735, -0.017603591 -0.15604782 0.046991184, -0.01906582 -0.15056908 0.059991658, -0.020331837 -0.14875826 0.06338992, -0.013957515 -0.15422592 0.052829809, -0.013750255 -0.15643439 0.046991207, -0.011302672 -0.15444338 0.05282969, -0.018732674 -0.14793798 0.065409526, -0.016154669 -0.14458624 0.0720165, -0.013679385 -0.15115365 0.059991516, -0.009784624 -0.15305132 0.056429595, -0.0082753822 -0.15154564 0.059991531, -0.010293946 -0.14876372 0.065409645, -0.013440341 -0.14851242 0.065409623, -0.011524461 -0.14689547 0.06873592, -0.012731016 -0.14492789 0.072016336, -0.03558699 -0.14106622 0.072016641, -0.03891287 -0.14018527 0.072016649, -0.037760042 -0.14336753 0.06705492, -0.027389325 -0.14570403 0.067056365, -0.029401079 -0.14793187 0.061991863, -0.025822312 -0.14859837 0.061991654, -0.034933075 -0.14408225 0.067054823, -0.036505096 -0.14634085 0.06199196, -0.032962658 -0.14717919 0.061991766, -0.032241166 -0.14186835 0.072016612, -0.030174069 -0.14515358 0.067054838, -0.028877266 -0.14259109 0.07201656, -0.029619217 -0.15713027 0.037810966, -0.031538598 -0.15825424 0.031991154, -0.02757217 -0.15899321 0.031991005, -0.029777147 -0.14974797 0.057991587, -0.029439397 -0.15282702 0.05082909, -0.02778665 -0.15168345 0.054429047, -0.02613014 -0.15042719 0.057991579, -0.038505338 -0.15519178 0.037811115, -0.041704677 -0.15394378 0.039253458, -0.04057689 -0.15526253 0.035634674, -0.039409697 -0.1564799 0.031991288, -0.035485223 -0.15741622 0.031991169, -0.037980624 -0.15307733 0.044991389, -0.04166685 -0.15079552 0.048653215, -0.043427162 -0.15162215 0.044991478, -0.032934271 -0.15646884 0.037810981, -0.030861706 -0.15582913 0.041414365, -0.037478954 -0.15105653 0.050829098, -0.033406459 -0.14898026 0.057991661, -0.037016116 -0.14812464 0.057991661, -0.039890639 -0.14985752 0.05227612, -0.032485455 -0.15433699 0.044991344, -0.032075956 -0.15442261 0.044991381, -0.032056518 -0.15229937 0.050829068, -0.028778702 -0.15237719 -0.052290641, -0.029777117 -0.14974147 -0.05800838, -0.026130222 -0.15042064 -0.05800844, -0.028860122 -0.15785629 -0.035654128, -0.031538494 -0.15825069 -0.032008894, -0.030119717 -0.15661791 -0.039272971, -0.027572207 -0.15898955 -0.032008916, -0.037344247 -0.15050733 -0.052290544, -0.0406029 -0.15024036 -0.050848439, -0.038817346 -0.14923516 -0.054447897, -0.037016131 -0.14811808 -0.05800835, -0.033406474 -0.1489737 -0.058008373, -0.037980564 -0.1530723 -0.045008659, -0.043427154 -0.15161708 -0.045008741, -0.042362414 -0.15309906 -0.041429691, -0.031941161 -0.15174568 -0.052290551, -0.030429214 -0.15345371 -0.048668444, -0.038407736 -0.15479407 -0.039272867, -0.035485208 -0.15741265 -0.032008894, -0.039409652 -0.15647626 -0.032008827, -0.041258357 -0.15447921 -0.037826225, -0.03248544 -0.15433192 -0.045008607, -0.032075904 -0.15441751 -0.0450086, -0.032850794 -0.15606788 -0.039272904, -0.030151755 -0.16044545 -0.022253335, -0.031713076 -0.15909365 -0.028009012, -0.02771502 -0.15983862 -0.028009012, -0.029582195 -0.16221386 -0.0056272149, -0.032272816 -0.16179872 -0.0020090565, -0.030971721 -0.16176251 -0.0092398822, -0.028173327 -0.16256264 -0.0020090938, -0.03930869 -0.15845075 -0.022253118, -0.042777151 -0.15777811 -0.020810857, -0.04122369 -0.15759251 -0.024417602, -0.03964673 -0.1573042 -0.028008841, -0.035691157 -0.15824866 -0.028008878, -0.039538391 -0.15937731 -0.015008986, -0.045214914 -0.15786073 -0.015008867, -0.043919064 -0.15857416 -0.011403121, -0.033614792 -0.15975565 -0.022253357, -0.031659141 -0.16068849 -0.018638067, -0.039656758 -0.15985501 -0.0092399046, -0.036351629 -0.16093135 -0.0020090342, -0.040407307 -0.15996119 -0.0020090342, -0.042592697 -0.15918767 -0.0077932328, -0.033811137 -0.16068974 -0.015008993, -0.033154428 -0.16082656 -0.015009046, -0.033912495 -0.16117144 -0.0092398524, -0.030418195 -0.16195622 0.0077772588, -0.032272764 -0.16179889 0.0019910038, -0.02817332 -0.16256291 0.001990959, -0.029241696 -0.16025198 0.024397939, -0.031713061 -0.15909678 0.027991138, -0.030756131 -0.16055754 0.020791017, -0.027714998 -0.15984175 0.027991109, -0.039677612 -0.15993974 0.007777378, -0.043126747 -0.15895537 0.0092198327, -0.041782133 -0.15950838 0.005607456, -0.040407389 -0.15996149 0.0019910559, -0.036351629 -0.16093168 0.001990959, -0.039538354 -0.15937895 0.014991, -0.043698296 -0.15784204 0.018622003, -0.045214944 -0.15786242 0.014991149, -0.033930324 -0.16125682 0.007777296, -0.031796016 -0.16144368 0.011386916, -0.039361715 -0.15866718 0.020791098, -0.035691082 -0.15825182 0.027991123, -0.039646745 -0.15730745 0.027991183, -0.042158626 -0.15771881 0.022237718, -0.033811197 -0.16069141 0.014990978, -0.03315445 -0.16082826 0.01499097, -0.033660047 -0.15997383 0.020791076, -0.055524737 -0.14689371 0.04699178, -0.057261564 -0.14479154 0.05065427, -0.059129924 -0.14547995 0.046991892, -0.051157296 -0.13619477 0.07201694, -0.054363593 -0.13494694 0.072017029, -0.053521134 -0.13843602 0.066744044, -0.05315093 -0.14544892 0.052830316, -0.052270181 -0.14248618 0.059992038, -0.055364657 -0.14399317 0.054277126, -0.051885553 -0.14821824 0.046991795, -0.052091904 -0.14255151 0.059992064, -0.052923217 -0.14050424 0.0633903, -0.047925457 -0.14725348 0.052830189, -0.048214719 -0.14945272 0.04699152, -0.045385554 -0.148056 0.052830175, -0.051181406 -0.14006066 0.065409988, -0.047922246 -0.13736644 0.072016791, -0.046970412 -0.14432007 0.059991911, -0.043595694 -0.14703679 0.056429885, -0.041789271 -0.1459046 0.059991911, -0.043138064 -0.14274335 0.065409839, -0.046149433 -0.14179829 0.065409914, -0.043921873 -0.14064837 0.0687363, -0.044660419 -0.13846141 0.072016805, -0.058917135 -0.15276232 0.018991418, -0.060247175 -0.15199673 0.020622417, -0.061779186 -0.15190187 0.016991429, -0.057931773 -0.15341055 0.016991392, -0.056408793 -0.15370613 0.018991396, -0.058680378 -0.15199149 0.024238154, -0.054047562 -0.15482154 0.016991228, -0.053885318 -0.15460896 0.018991277, -0.056534529 -0.15275609 0.024488501, -0.051347315 -0.15547022 0.018991314, -0.050129004 -0.15613452 0.016991235, -0.056101538 -0.15177464 0.029991403, -0.055664293 -0.15055189 0.035495803, -0.058146015 -0.14911383 0.037253328, -0.057148859 -0.1504921 0.033634722, -0.047689527 -0.15604275 0.022791326, -0.049011461 -0.15532994 0.024508625, -0.05713971 -0.14835998 0.040991776, -0.059637092 -0.14670902 0.042991795, -0.055985354 -0.14814112 0.042991571, -0.054786168 -0.14924523 0.040991567, -0.046133801 -0.1558513 0.026398256, -0.046621151 -0.15494961 0.029991291, -0.052299351 -0.14948225 0.042991616, -0.052419126 -0.15009296 0.04099156, -0.044554338 -0.15555656 0.029991262, -0.050038971 -0.15090308 0.040991612, -0.046407416 -0.15357322 0.035810977, -0.048375465 -0.15304324 0.035520144, -0.047514215 -0.1522027 0.039414257, -0.048581295 -0.15073159 0.042991579, -0.055563688 -0.15198269 0.029946789, -0.054075241 -0.15251857 0.02994667, -0.049213648 -0.15117434 0.04099156, -0.057139635 -0.14835531 -0.04100839, -0.058720112 -0.14823633 -0.039429285, -0.059637018 -0.1467042 -0.043008178, -0.055985257 -0.14813626 -0.04300832, -0.054786317 -0.14924064 -0.041008338, -0.05775322 -0.14967251 -0.035825677, -0.052299298 -0.14947733 -0.043008409, -0.052419119 -0.15008831 -0.041008428, -0.055664361 -0.15054795 -0.035512619, -0.050038949 -0.15089852 -0.041008398, -0.048581257 -0.1507268 -0.043008506, -0.056101613 -0.15177131 -0.030008622, -0.056534491 -0.15275329 -0.024505593, -0.059311286 -0.15200308 -0.02281072, -0.057723731 -0.15193731 -0.026417211, -0.046854831 -0.15303281 -0.037272498, -0.04837548 -0.15303919 -0.035537414, -0.058917195 -0.15276006 -0.019008532, -0.061779194 -0.15189996 -0.017008618, -0.057931922 -0.15340865 -0.017008595, -0.056408793 -0.15370393 -0.019008532, -0.045724429 -0.15434334 -0.033653557, -0.046621174 -0.15494639 -0.030008644, -0.054047585 -0.15481961 -0.01700867, -0.053885311 -0.15460682 -0.019008704, -0.044554293 -0.15555325 -0.030008703, -0.051347375 -0.15546808 -0.019008704, -0.047070056 -0.15597603 -0.024253212, -0.049011305 -0.15532723 -0.024526007, -0.048611484 -0.15610591 -0.020638019, -0.050129116 -0.15613258 -0.017008834, -0.055560336 -0.15197021 -0.030008569, -0.054075263 -0.15251517 -0.029963747, -0.050683483 -0.15568569 -0.01900886, -0.058078364 -0.15380564 -0.013008602, -0.060710333 -0.15309164 -0.0094027817, -0.061940476 -0.15229142 -0.013008542, -0.058078393 -0.1538071 0.012991354, -0.061940402 -0.15229279 0.012991346, -0.059952393 -0.15352672 0.0072200671, -0.056594104 -0.15479517 -0.0072395355, -0.05731868 -0.15472424 -8.6128712e-06, -0.059438802 -0.15379629 -0.0057929456, -0.054179206 -0.15522212 -0.013008736, -0.056657143 -0.1549677 -8.6277723e-06, -0.058656208 -0.15417343 0.0036078617, -0.051020801 -0.15672049 -0.0072396398, -0.05024568 -0.15653947 -0.013008758, -0.048155881 -0.15762445 -0.0072397366, -0.056616843 -0.15485778 0.0057777464, -0.054179139 -0.15522352 0.012991384, -0.051077738 -0.15689513 -8.7767839e-06, -0.045432776 -0.15862179 -9.0375543e-06, -0.047621116 -0.15785652 0.0057776198, -0.04680974 -0.15817288 -0.003627114, -0.051041357 -0.15678385 0.0057776123, -0.048948742 -0.15724862 0.0093871281, -0.050245643 -0.15654099 0.01299122, -0.066084072 -0.12961072 0.072017156, -0.069130599 -0.12801164 0.072017431, -0.068714678 -0.13137066 0.067055643, -0.059124038 -0.13595635 0.067056872, -0.061581019 -0.13768062 0.06199234, -0.058240294 -0.1391269 0.061992098, -0.066117778 -0.13269663 0.067055538, -0.068152919 -0.13454863 0.061992411, -0.064885877 -0.13615438 0.061992221, -0.06300056 -0.13113707 0.072017163, -0.061716516 -0.13480008 0.067055434, -0.059881933 -0.13259035 0.072017103, -0.061965071 -0.14215279 -0.052290156, -0.062351823 -0.13936099 -0.058007903, -0.058947511 -0.14083466 -0.058007888, -0.063263312 -0.14747661 -0.035653494, -0.065962397 -0.14726484 -0.032008231, -0.06421572 -0.14598897 -0.039272346, -0.062259845 -0.14886805 -0.03200832, -0.069899529 -0.13842377 -0.052289821, -0.073017314 -0.13743842 -0.050847754, -0.071052715 -0.13685557 -0.054447137, -0.069048099 -0.1361675 -0.058007725, -0.065719344 -0.13780501 -0.058007754, -0.071090542 -0.14078301 -0.045007974, -0.076076858 -0.13815218 -0.045007832, -0.075368576 -0.13983396 -0.041428998, -0.0649077 -0.14083341 -0.052289963, -0.063813537 -0.14283505 -0.048667811, -0.071890183 -0.14236653 -0.03927213, -0.069623485 -0.14556974 -0.032008201, -0.073241182 -0.14378363 -0.032008111, -0.074599132 -0.14142534 -0.037825398, -0.066013634 -0.14323387 -0.045008093, -0.065633468 -0.14340845 -0.045008048, -0.066755965 -0.14484486 -0.039272279, -0.065098576 -0.14971328 -0.02225291, -0.066320032 -0.14804786 -0.028008267, -0.062587909 -0.14966378 -0.028008364, -0.06493663 -0.15156412 -0.0056266636, -0.067467354 -0.15056056 -0.0020083934, -0.066190839 -0.15081477 -0.0092392638, -0.063640647 -0.15221775 -0.0020086244, -0.073581889 -0.145731 -0.022252515, -0.076813839 -0.14430347 -0.020810127, -0.075258002 -0.14446822 -0.024416782, -0.073656477 -0.14453807 -0.028008163, -0.070010208 -0.14633897 -0.028008103, -0.074012004 -0.14658323 -0.015008211, -0.079208903 -0.14384151 -0.015008129, -0.078104094 -0.14482546 -0.011402391, -0.068321183 -0.14827022 -0.022252738, -0.066622049 -0.1496149 -0.018637523, -0.074233718 -0.14702266 -0.0092391297, -0.071250804 -0.14880756 -0.0020084381, -0.074988954 -0.14695922 -0.0020082518, -0.076947369 -0.14571863 -0.0077925473, -0.068720527 -0.14913717 -0.015008353, -0.068110734 -0.14941674 -0.015008375, -0.068926357 -0.14958435 -0.009239234, -0.063840881 -0.14659965 0.037811644, -0.065962315 -0.1472685 0.031991616, -0.062259853 -0.14887154 0.031991653, -0.062351804 -0.13936755 0.05799219, -0.062707871 -0.14244449 0.050829709, -0.060841888 -0.14169738 0.054429494, -0.05894744 -0.14084128 0.057992171, -0.072072819 -0.14273265 0.037811756, -0.074914359 -0.14080381 0.039254032, -0.07410834 -0.14234057 0.035635449, -0.073241271 -0.14378721 0.031991944, -0.069623545 -0.14557335 0.031991862, -0.071090519 -0.14078817 0.044992097, -0.07417658 -0.13774323 0.048654035, -0.07607682 -0.1381574 0.044992164, -0.06692566 -0.14521736 0.037811704, -0.064762704 -0.14505479 0.041414909, -0.07015188 -0.13892937 0.050829735, -0.065719351 -0.13781151 0.057992313, -0.069048181 -0.13617414 0.057992388, -0.072236203 -0.13722378 0.052276779, -0.066013575 -0.14323881 0.044991761, -0.065633439 -0.14341336 0.044991963, -0.065142006 -0.14134777 0.050829671, -0.065694064 -0.15112692 0.0077778399, -0.067467362 -0.15056083 0.0019915402, -0.063640565 -0.15221801 0.0019913986, -0.064167552 -0.14972726 0.024398468, -0.066319957 -0.14805105 0.027991734, -0.065712094 -0.14968818 0.02079159, -0.062587902 -0.14966694 0.027991585, -0.074272662 -0.14710075 0.0077781007, -0.077416264 -0.14537331 0.0092206001, -0.076228574 -0.14621177 0.0056082979, -0.074989021 -0.14695957 0.0019918233, -0.071250834 -0.14880776 0.0019916594, -0.074012071 -0.14658481 0.01499176, -0.077725582 -0.1441609 0.018622823, -0.07920891 -0.14384323 0.01499182, -0.068962492 -0.14966363 0.0077780187, -0.066923335 -0.15032062 0.011387534, -0.073681228 -0.14593035 0.020791635, -0.070010267 -0.14634216 0.027991839, -0.073656432 -0.14454123 0.027991809, -0.076197013 -0.14438322 0.022238463, -0.06872046 -0.14913893 0.014991641, -0.068110771 -0.14941841 0.014991604, -0.068413489 -0.14847282 0.02079168, -0.11375961 -0.10825551 0.046993885, -0.11441225 -0.10560817 0.050656319, -0.11639447 -0.10541752 0.046994172, -0.10518199 -0.10051137 0.072018862, -0.10752945 -0.097995967 0.072019085, -0.10828449 -0.10150513 0.066746078, -0.11099382 -0.10798413 0.05283235, -0.10891485 -0.10569668 0.059994012, -0.11235672 -0.10571188 0.054279219, -0.11105543 -0.11102802 0.046993777, -0.10878236 -0.10583302 0.059994053, -0.10864319 -0.10362777 0.063392356, -0.10706884 -0.11187708 0.052832283, -0.10828391 -0.11373281 0.046993606, -0.10512878 -0.11370233 0.052832037, -0.10688135 -0.1039837 0.06541194, -0.10277571 -0.10297066 0.072018638, -0.10493559 -0.10964835 0.059993979, -0.10307373 -0.11356047 0.056431718, -0.1009549 -0.11332425 0.059993643, -0.10079838 -0.10989094 0.065411709, -0.1031017 -0.10773253 0.065411761, -0.10059559 -0.10766304 0.068738163, -0.10031196 -0.10537234 0.072018608, -0.11585107 -0.10887143 -0.041006118, -0.11722323 -0.10807848 -0.03942693, -0.11738466 -0.10630026 -0.043006003, -0.11471597 -0.10917479 -0.043006107, -0.11411471 -0.11069003 -0.041006297, -0.11697515 -0.10979193 -0.035823449, -0.11197682 -0.11198232 -0.043006346, -0.11234977 -0.11248088 -0.041006364, -0.11547298 -0.11148703 -0.035510533, -0.1105568 -0.11424363 -0.041006461, -0.10916898 -0.11472127 -0.04300651, -0.11639753 -0.11239952 -0.030006453, -0.11721364 -0.11309657 -0.024503589, -0.11938969 -0.11121574 -0.022808433, -0.11793113 -0.11184511 -0.026414908, -0.10861404 -0.1175482 -0.037270516, -0.10998692 -0.11689404 -0.035535417, -0.11936308 -0.11206874 -0.019006304, -0.12156847 -0.11005214 -0.017006122, -0.1187566 -0.11308065 -0.017006382, -0.11751276 -0.11400741 -0.019006424, -0.10816419 -0.11921921 -0.033651538, -0.1092336 -0.11937344 -0.030006751, -0.11586935 -0.11603722 -0.017006561, -0.11563076 -0.11591589 -0.019006468, -0.10763473 -0.12081707 -0.030006707, -0.1137178 -0.11779305 -0.019006632, -0.11008468 -0.12010634 -0.024251267, -0.11155226 -0.11867949 -0.024524108, -0.11152967 -0.11955458 -0.020635895, -0.11290845 -0.11892024 -0.017006621, -0.11599623 -0.1128135 -0.030006386, -0.11489467 -0.11394891 -0.029961661, -0.11321408 -0.11827728 -0.019006692, -0.11906094 -0.11337465 -0.013006382, -0.12112232 -0.11158958 -0.0094004348, -0.12188355 -0.11033478 -0.01300627, -0.11906084 -0.11337617 0.012993619, -0.12188347 -0.11033618 0.012993794, -0.12062782 -0.11231044 0.0072224289, -0.11815272 -0.11491033 -0.0072372779, -0.1187747 -0.11453217 -6.3925982e-06, -0.12028237 -0.11277613 -0.0057907626, -0.11616249 -0.11634269 -0.013006605, -0.11828426 -0.11503845 -6.4447522e-06, -0.11974065 -0.11345544 0.003610108, -0.11396687 -0.11906305 -0.0072374344, -0.11319022 -0.11923644 -0.013006732, -0.11177777 -0.12112069 -0.0072377175, -0.11820017 -0.114957 0.0057799742, -0.1161624 -0.11634418 0.012993354, -0.11409369 -0.11919594 -6.6310167e-06, -0.11080273 -0.12219903 -0.0036249608, -0.10975689 -0.12320083 -6.9364905e-06, -0.11139631 -0.12156183 0.0057795681, -0.11401252 -0.11911148 0.005779814, -0.11232863 -0.12043795 0.0093891285, -0.1131902 -0.11923784 0.012993399, -0.11936317 -0.11207074 0.018993694, -0.1202292 -0.11080417 0.020624775, -0.12156844 -0.11005402 0.016993839, -0.1187567 -0.1130825 0.016993646, -0.11751271 -0.11400962 0.018993631, -0.1188152 -0.11147928 0.024240285, -0.11586931 -0.11603922 0.016993482, -0.11563078 -0.11591795 0.01899353, -0.11721368 -0.1130994 0.024490796, -0.11371782 -0.11779517 0.018993322, -0.1129085 -0.11892226 0.01699343, -0.11639755 -0.11240289 0.029993728, -0.1154729 -0.11149096 0.035498109, -0.1170848 -0.10911846 0.03725569, -0.11678458 -0.11079288 0.033636928, -0.11067051 -0.11989814 0.022793349, -0.11155224 -0.11868221 0.024510644, -0.115851 -0.10887605 0.040993914, -0.11738464 -0.10630512 0.042994078, -0.11471599 -0.10917968 0.042994022, -0.11411469 -0.11069465 0.040993787, -0.10918598 -0.12040055 0.026400369, -0.10923365 -0.1193769 0.029993374, -0.1119768 -0.11198717 0.042993743, -0.11234979 -0.11248547 0.040993605, -0.10763478 -0.12082043 0.029993247, -0.11055686 -0.11424839 0.040993594, -0.10844358 -0.11822939 0.03581287, -0.10998688 -0.11689794 0.035522271, -0.10884596 -0.11651447 0.039416131, -0.10916901 -0.11472622 0.042993646, -0.11600335 -0.11282355 0.029948987, -0.11489465 -0.11395225 0.029948831, -0.10993101 -0.11485064 0.040993597, -0.12475966 -0.10765716 0.0077802688, -0.12611187 -0.10637778 0.0019940063, -0.12338296 -0.10953107 0.0019938052, -0.12277653 -0.1070585 0.024400942, -0.12398852 -0.1046145 0.027994081, -0.12415136 -0.10635296 0.020794053, -0.12132715 -0.10768953 0.027993947, -0.13074173 -0.1003074 0.0077808723, -0.13282445 -0.097387284 0.0092233904, -0.13211815 -0.098657846 0.0056109354, -0.13132595 -0.099869311 0.0019944385, -0.12875998 -0.10315651 0.0019942001, -0.130283 -0.099955976 0.014994472, -0.1337755 -0.095230907 0.014994729, -0.13257702 -0.096160591 0.018625416, -0.12706944 -0.10492072 0.0077806748, -0.12551722 -0.10639733 0.011390019, -0.12970078 -0.099509597 0.020794395, -0.12657171 -0.1014736 0.027994387, -0.12907557 -0.098268867 0.027994465, -0.13129605 -0.097024232 0.022241168, -0.12662348 -0.10455295 0.014994211, -0.12619528 -0.10506937 0.014994107, -0.12605768 -0.10408604 0.02079422, -0.12361034 -0.10664171 -0.022250354, -0.12398851 -0.10461131 -0.028005935, -0.12132712 -0.10768643 -0.028005935, -0.12426715 -0.1083796 -0.0056242719, -0.12611184 -0.1063776 -0.0020060092, -0.12507224 -0.1071603 -0.0092368647, -0.123383 -0.1095309 -0.0020061024, -0.12952605 -0.099372983 -0.022249974, -0.13181832 -0.096684426 -0.02080749, -0.1304881 -0.097508073 -0.024414152, -0.12907557 -0.098265767 -0.028005511, -0.12657174 -0.10147035 -0.02800563, -0.13028297 -0.099954128 -0.015005626, -0.13320714 -0.096595049 -0.01139953, -0.1337755 -0.095229298 -0.01500538, -0.12588784 -0.10394323 -0.022250235, -0.1249403 -0.105892 -0.018635072, -0.13067338 -0.10025385 -0.0092363954, -0.12876001 -0.10315627 -0.002005823, -0.13132598 -0.099869102 -0.0020056292, -0.1325523 -0.097901762 -0.0077897534, -0.12662362 -0.10455123 -0.015005954, -0.12619545 -0.10506764 -0.015005983, -0.12700292 -0.10486481 -0.0092366561, -0.1175076 -0.10118949 -0.052287936, -0.11664481 -0.098506093 -0.058005549, -0.11421709 -0.10131103 -0.05800584, -0.1209868 -0.10542271 -0.035651177, -0.12332657 -0.1040611 -0.032005809, -0.1211995 -0.10366905 -0.039269924, -0.12068632 -0.10711178 -0.032006018, -0.12303846 -0.094386816 -0.05228734, -0.1254198 -0.092146426 -0.050845243, -0.12339706 -0.092473656 -0.054444477, -0.12129252 -0.092723399 -0.058005184, -0.1190038 -0.095642984 -0.058005415, -0.12513497 -0.095995724 -0.045005523, -0.12857738 -0.093284637 -0.041426398, -0.12848602 -0.091462106 -0.045005135, -0.11958621 -0.098724067 -0.052287661, -0.11946896 -0.1010021 -0.048665442, -0.1265423 -0.097075641 -0.039269656, -0.12588981 -0.10094506 -0.032005675, -0.12837413 -0.097766131 -0.032005504, -0.12857461 -0.095052153 -0.037822902, -0.12162413 -0.10040665 -0.045005716, -0.1213573 -0.10072884 -0.045005694, -0.1229919 -0.10153604 -0.039269902, -0.1157738 -0.088102698 0.072019622, -0.11782495 -0.085340291 0.072019786, -0.11890773 -0.08854714 0.067058079, -0.11225642 -0.096839786 0.067058958, -0.11521859 -0.097327381 0.061994616, -0.11283608 -0.10007966 0.061994437, -0.11714316 -0.090868652 0.067057803, -0.1197806 -0.091654092 0.061994851, -0.11753388 -0.094518155 0.061994608, -0.11365812 -0.09081611 0.072019413, -0.11409047 -0.094673336 0.067057669, -0.11147873 -0.093478352 0.072019249, -0.12112489 -0.10438246 0.037814043, -0.12332658 -0.10406461 0.031994183, -0.12068625 -0.10711545 0.031993959, -0.11664491 -0.09851259 0.057994373, -0.11830094 -0.10113034 0.050831936, -0.11629556 -0.10126683 0.054431889, -0.114217 -0.10131761 0.05799441, -0.1268639 -0.097326756 0.037814319, -0.12858695 -0.09435609 0.039256588, -0.12852755 -0.096090287 0.035637885, -0.12837416 -0.097769707 0.031994626, -0.12588979 -0.10094866 0.031994395, -0.12513502 -0.09600082 0.044994544, -0.12659416 -0.091918498 0.048656382, -0.12848596 -0.091467202 0.044994842, -0.12330445 -0.10179853 0.037814073, -0.12128498 -0.10259065 0.041417267, -0.1234826 -0.094733477 0.050832391, -0.11900381 -0.09564963 0.057994574, -0.12129244 -0.092730135 0.057994753, -0.12462048 -0.092292398 0.052279249, -0.12162411 -0.1004118 0.044994287, -0.12135735 -0.100734 0.044994287, -0.12001804 -0.099086165 0.050832123, -0.093267381 -0.11165613 0.072018251, -0.095881611 -0.10941926 0.072018452, -0.096223727 -0.1127865 0.067056626, -0.08789397 -0.11939132 0.067057788, -0.090673238 -0.12052578 0.06199329, -0.087737985 -0.12267891 0.061993148, -0.093986981 -0.11465728 0.067056552, -0.096383378 -0.11600992 0.061993562, -0.09355545 -0.11830229 0.061993409, -0.090600915 -0.11383051 0.072018161, -0.090164021 -0.1176872 0.067056328, -0.087883763 -0.1159412 0.072018027, -0.096780829 -0.13147387 -0.022251792, -0.097601205 -0.12957835 -0.028007366, -0.094322436 -0.13198423 -0.02800741, -0.097034819 -0.13331437 -0.0056255832, -0.099278547 -0.13177294 -0.0020073652, -0.098090783 -0.13230473 -0.0092383325, -0.095916733 -0.13423988 -0.0020074248, -0.10416558 -0.12570372 -0.022251517, -0.10699883 -0.12359259 -0.020808995, -0.1055187 -0.12409961 -0.02441556, -0.10397294 -0.12452397 -0.028006822, -0.10081875 -0.12709111 -0.028006993, -0.10477447 -0.1264388 -0.015007168, -0.10923086 -0.12260935 -0.015006788, -0.10837262 -0.12381467 -0.011401109, -0.099601664 -0.12934989 -0.022251733, -0.098244339 -0.13103881 -0.01863651, -0.10508818 -0.126818 -0.0092379525, -0.10257725 -0.1292218 -0.0020073056, -0.10581028 -0.12658802 -0.0020070449, -0.10744367 -0.12494287 -0.0077913031, -0.10018387 -0.13010633 -0.015007287, -0.099651389 -0.13051462 -0.015007369, -0.10048383 -0.13049641 -0.0092381984, -0.092043869 -0.12480029 -0.05228924, -0.091799945 -0.1219922 -0.05800692, -0.088808954 -0.12418658 -0.058007002, -0.094494157 -0.12970164 -0.035652526, -0.097078346 -0.12889472 -0.03200718, -0.095091753 -0.12803936 -0.039271288, -0.093825601 -0.13128132 -0.032007404, -0.098949902 -0.11939901 -0.052288733, -0.10177014 -0.11774457 -0.050846592, -0.09972512 -0.11761352 -0.054446004, -0.097617805 -0.1173889 -0.058006607, -0.094736822 -0.11972591 -0.058006726, -0.10063593 -0.12143391 -0.045006923, -0.10459529 -0.11955684 -0.041427776, -0.1049118 -0.11775962 -0.045006536, -0.0946192 -0.12285921 -0.052288935, -0.093997963 -0.12505385 -0.04866679, -0.10176773 -0.12279996 -0.039271116, -0.10027072 -0.12642714 -0.032007061, -0.10340011 -0.12388089 -0.032006934, -0.10419928 -0.12127948 -0.037824422, -0.096231565 -0.12495312 -0.045006908, -0.095899776 -0.12520802 -0.045006983, -0.097313851 -0.1263586 -0.03927128, -0.097675949 -0.13271946 0.0077789649, -0.099278577 -0.13177317 0.0019926503, -0.095916659 -0.13424024 0.0019924492, -0.095875926 -0.13169479 0.024399571, -0.097601101 -0.12958157 0.027992707, -0.097373024 -0.13131285 0.020792663, -0.094322443 -0.13198733 0.027992647, -0.1051433 -0.12688529 0.0077792481, -0.10782366 -0.12450185 0.0092218742, -0.10685236 -0.12558344 0.0056094825, -0.10581033 -0.12658817 0.0019928738, -0.1025774 -0.12922198 0.0019926578, -0.10477436 -0.12644047 0.014992848, -0.10923097 -0.12261119 0.014993005, -0.10785543 -0.1232509 0.018624067, -0.10053661 -0.13056585 0.007779032, -0.098694667 -0.13166001 0.011388592, -0.10430621 -0.12587574 0.020792868, -0.10081872 -0.1270943 0.027992871, -0.10397294 -0.12452719 0.027993046, -0.10641451 -0.12380791 0.022239517, -0.10018378 -0.13010812 0.014992751, -0.099651515 -0.13051626 0.014992643, -0.099736117 -0.12952691 0.02079263, -0.094861194 -0.12871838 0.037812516, -0.097078398 -0.12889826 0.03199276, -0.093825318 -0.13128513 0.031992681, -0.09179993 -0.12199873 0.057993293, -0.09283188 -0.12491935 0.050830673, -0.090846449 -0.12460625 0.054430474, -0.088809006 -0.1241931 0.057992984, -0.10202635 -0.12311637 0.037812829, -0.10436737 -0.12060377 0.039255306, -0.1039235 -0.12228128 0.035636522, -0.10340007 -0.12388444 0.031993125, -0.10027059 -0.12643087 0.03199289, -0.10063592 -0.12143916 0.044993158, -0.10296702 -0.11778387 0.048655052, -0.10491182 -0.11776477 0.044993456, -0.097561225 -0.12668419 0.037812632, -0.095416248 -0.12700698 0.041415911, -0.099307194 -0.11983576 0.050830927, -0.094736792 -0.11973235 0.057993177, -0.097617805 -0.1173954 0.057993442, -0.10095975 -0.1177091 0.052277762, -0.096231699 -0.12495813 0.044992965, -0.095899768 -0.12521303 0.044992998, -0.094960853 -0.12330854 0.050830744, -0.086818814 -0.13085541 0.046992719, -0.088044375 -0.12841958 0.0506551, -0.090019196 -0.12867472 0.046992827, -0.080179825 -0.12139669 0.072017878, -0.083028212 -0.11946651 0.072017841, -0.082983375 -0.1230557 0.066744961, -0.084183 -0.12997523 0.05283111, -0.082665168 -0.12728253 0.059992805, -0.086017296 -0.12806332 0.054278042, -0.083565682 -0.13295659 0.046992585, -0.082505643 -0.127386 0.059992887, -0.082860664 -0.12520528 0.063391268, -0.079490095 -0.13289714 0.052830897, -0.080261908 -0.13497677 0.046992335, -0.07719259 -0.13424483 0.05283092, -0.081063718 -0.12516013 0.065410718, -0.077286676 -0.12325883 0.072017625, -0.077906281 -0.13024986 0.059992645, -0.075220719 -0.13364941 0.056430634, -0.073207587 -0.13294756 0.059992652, -0.073818937 -0.12956554 0.065410599, -0.076544762 -0.12797391 0.065410599, -0.07411699 -0.12734842 0.06873706, -0.074350268 -0.12505206 0.072017536, -0.091432586 -0.13582191 0.018992379, -0.092558734 -0.13477975 0.020623431, -0.094031349 -0.13434637 0.01699242, -0.090616167 -0.13667315 0.016992219, -0.089197151 -0.13730037 0.018992387, -0.091030091 -0.13512316 0.024239138, -0.087143354 -0.13891315 0.016992129, -0.086937882 -0.13874194 0.018992193, -0.089108132 -0.13634628 0.024489488, -0.084655195 -0.14014646 0.018992148, -0.083615273 -0.141065 0.016992092, -0.088467471 -0.13548577 0.02999239, -0.087769359 -0.1343908 0.035496738, -0.08986856 -0.1324366 0.037254453, -0.089203276 -0.13400221 0.033635747, -0.081216335 -0.14151859 0.022792034, -0.082346551 -0.14052927 0.024509408, -0.088719651 -0.1319257 0.040992558, -0.090787143 -0.12976035 0.042992782, -0.087545648 -0.13196898 0.042992655, -0.086622253 -0.13331228 0.040992588, -0.079656899 -0.1416783 0.026399001, -0.079931498 -0.14069077 0.029992193, -0.084250495 -0.13409665 0.042992529, -0.084503189 -0.13466543 0.040992483, -0.078051522 -0.14174211 0.029991999, -0.082362913 -0.13598508 0.040992383, -0.079416744 -0.13939607 0.035811722, -0.081217423 -0.13844168 0.035521097, -0.080190629 -0.13781369 0.039414965, -0.080903575 -0.13614208 0.042992529, -0.087989546 -0.13580799 0.029947609, -0.086657636 -0.1366618 0.02994762, -0.081618682 -0.13643309 0.040992331, -0.090847313 -0.13702586 -0.013007738, -0.093254335 -0.13574407 -0.0094018206, -0.094275624 -0.13469002 -0.013007581, -0.09084738 -0.13702717 0.012992308, -0.094275609 -0.13469142 0.012992539, -0.092612021 -0.13633674 0.0072211847, -0.089620449 -0.13832062 -0.0072387233, -0.090310931 -0.1380904 -7.6815486e-06, -0.092171535 -0.13671392 -0.005791977, -0.087361194 -0.13927427 -0.013007775, -0.089720175 -0.13847503 -7.6666474e-06, -0.091492362 -0.1372557 0.003608793, -0.084615327 -0.14143783 -0.0072388202, -0.083819337 -0.14143401 -0.013007939, -0.08202333 -0.14295679 -0.0072388127, -0.089656375 -0.13837686 0.0057786256, -0.087361075 -0.13927573 0.012992218, -0.084709518 -0.14159563 -7.8976154e-06, -0.079590283 -0.14453533 -8.046627e-06, -0.081553429 -0.14330193 0.0057783648, -0.080832928 -0.14379114 -0.0036262497, -0.08464922 -0.14149523 0.0057784319, -0.082712464 -0.14241397 0.0093879253, -0.083819345 -0.14143556 0.012992121, -0.088719644 -0.13192105 -0.041007303, -0.090234093 -0.13145325 -0.039428294, -0.090787098 -0.1297555 -0.043007292, -0.087545671 -0.13196421 -0.043007456, -0.086622283 -0.13330764 -0.041007459, -0.08961083 -0.13306859 -0.035824761, -0.084250502 -0.13409182 -0.043007486, -0.084503166 -0.1346609 -0.041007541, -0.087769337 -0.13438684 -0.035511829, -0.082362883 -0.1359804 -0.041007757, -0.080903508 -0.13613728 -0.043007627, -0.08846771 -0.13548222 -0.030007534, -0.089108244 -0.13634342 -0.024504676, -0.091648385 -0.13499397 -0.022809803, -0.090086065 -0.13528311 -0.026416332, -0.079733647 -0.13876975 -0.037271619, -0.081217423 -0.13843766 -0.035536617, -0.091432564 -0.1358197 -0.01900766, -0.094031386 -0.13434428 -0.017007492, -0.090616114 -0.13667125 -0.017007634, -0.089197114 -0.13729823 -0.019007713, -0.078923084 -0.14029893 -0.033652879, -0.079931393 -0.14068726 -0.030008048, -0.087143391 -0.13891131 -0.017007783, -0.0869378 -0.13873985 -0.019007832, -0.078051485 -0.14173895 -0.030008011, -0.084655188 -0.14014426 -0.019007877, -0.080598101 -0.14159104 -0.024252385, -0.082346424 -0.14052665 -0.024525195, -0.082129702 -0.14137489 -0.020637065, -0.08361531 -0.14106297 -0.017007902, -0.087984316 -0.13579673 -0.030007645, -0.086657636 -0.13665846 -0.029962972, -0.084056407 -0.14050421 -0.019007809, 0.1442416 0.076464385 -0.022240132, 0.14415835 0.074401468 -0.027995795, 0.14224805 0.077991605 -0.027995661, 0.14526835 0.078010827 -0.0056136549, 0.1466212 0.07564804 -0.0019957572, 0.14578184 0.076643258 -0.0092265308, 0.14466245 0.07932958 -0.001995489, 0.14839129 0.06806156 -0.022240579, 0.15002798 0.06493023 -0.02079843, 0.14891438 0.066029578 -0.024404898, 0.14770596 0.067082942 -0.027996168, 0.14597805 0.070764393 -0.027996048, 0.14925858 0.068459064 -0.014996231, 0.15136185 0.064532965 -0.011390552, 0.15161224 0.063075364 -0.014996454, 0.14586139 0.073326886 -0.022240281, 0.1453712 0.075437069 -0.018624842, 0.14970574 0.068663776 -0.0092269778, 0.14848621 0.071918339 -0.0019960254, 0.15025644 0.068142653 -0.0019962043, 0.15101431 0.065952152 -0.0077806115, 0.14671388 0.073755115 -0.014995888, 0.14641137 0.074353874 -0.014995843, 0.14715336 0.073975682 -0.0092266351, 0.14558753 0.077195257 0.0077908337, 0.14662117 0.075647771 0.0020042062, 0.14466254 0.079329193 0.0020044595, 0.14352074 0.077051193 0.024411321, 0.1441583 0.074398428 0.028004199, 0.14470416 0.076057792 0.020804256, 0.14224802 0.077988535 0.028004348, 0.14978416 0.068698734 0.0077903718, 0.1511649 0.065388173 0.0092324466, 0.15075913 0.066784561 0.0056201816, 0.15025645 0.068142354 0.0020038188, 0.14848629 0.071918041 0.0020039529, 0.14925864 0.068457514 0.015003815, 0.15161224 0.063073605 0.015003577, 0.15065055 0.064246327 0.018634424, 0.14723054 0.074013352 0.0077906549, 0.1460457 0.075798005 0.011400208, 0.14859174 0.068151057 0.020803839, 0.145978 0.070761204 0.028004035, 0.14770593 0.067079693 0.028003782, 0.14959385 0.065372944 0.022250324, 0.14671387 0.073753446 0.015004203, 0.14641137 0.074352145 0.015004203, 0.14605837 0.073423445 0.020804077, 0.14131492 0.074808329 0.03782396, 0.14339074 0.074009061 0.032004148, 0.14149562 0.077570707 0.032004416, 0.13564084 0.07008028 0.058003813, 0.13783793 0.072264701 0.050841853, 0.13591315 0.072843522 0.054441601, 0.13389803 0.073355079 0.058004051, 0.14533983 0.066652447 0.037823528, 0.14635882 0.063372582 0.039265603, 0.14668684 0.065076977 0.035647079, 0.146911 0.066748947 0.032003835, 0.14519623 0.070401013 0.032004088, 0.14335924 0.065743536 0.045003593, 0.14561744 0.060577869 0.045003369, 0.14387338 0.06143859 0.048665076, 0.14286478 0.071804166 0.037823722, 0.14107218 0.073025227 0.041427165, 0.14146625 0.064875156 0.050841376, 0.13730346 0.066764027 0.058003858, 0.13888513 0.063408494 0.05800347, 0.14203234 0.062242031 0.052288026, 0.1409179 0.070825189 0.045003921, 0.14072941 0.071198672 0.045004055, 0.13905714 0.069889635 0.05084151, 0.1370789 0.072510034 -0.052278116, 0.13564083 0.070086807 -0.057996154, 0.133898 0.073361546 -0.05799596, 0.14141263 0.075861275 -0.03564097, 0.14339074 0.074012578 -0.031995878, 0.14122985 0.074104667 -0.03925997, 0.14149551 0.077574492 -0.031995609, 0.14095728 0.064647466 -0.05227834, 0.14278041 0.061933219 -0.050836504, 0.14088126 0.062702596 -0.054435953, 0.13888511 0.063415021 -0.057996586, 0.13730349 0.066770583 -0.057996288, 0.14335923 0.065748632 -0.044996366, 0.14611195 0.062339067 -0.041417569, 0.14561743 0.060582966 -0.044996664, 0.13855687 0.069643945 -0.052278116, 0.13894939 0.071890593 -0.048655689, 0.14497137 0.066487581 -0.039260432, 0.14519617 0.070404589 -0.031996012, 0.14691101 0.066752523 -0.031996265, 0.14650245 0.064062536 -0.037813857, 0.1409179 0.070830226 -0.044996008, 0.14072953 0.071203798 -0.044996023, 0.14250255 0.071626395 -0.039260119, 0.13562928 0.059867442 -0.067059562, 0.13385983 0.056982189 -0.072021455, 0.13247502 0.060131848 -0.072021216, 0.13227616 0.072462082 -0.061995924, 0.13398635 0.069248557 -0.061996073, 0.13099006 0.069432288 -0.06706053, 0.13442475 0.062523246 -0.067060888, 0.13561851 0.06599468 -0.06199646, 0.13717158 0.062702358 -0.061996505, 0.13101606 0.06324777 -0.072021112, 0.13229515 0.066911757 -0.067060664, 0.12948383 0.066328406 -0.072020888, 0.13717313 0.080367029 -0.040995553, 0.1383345 0.079288125 -0.039416388, 0.13809621 0.077519119 -0.042995736, 0.13613403 0.080915451 -0.042995423, 0.13588493 0.082526356 -0.040995389, 0.13847384 0.081013799 -0.035812572, 0.13408834 0.084262252 -0.042995363, 0.13456289 0.08466503 -0.040995285, 0.13738649 0.083000451 -0.035499528, 0.13320711 0.086782485 -0.040995106, 0.13196036 0.087557256 -0.042995155, 0.13849084 0.08368367 -0.029995248, 0.13944158 0.08418107 -0.024492502, 0.14114456 0.081862867 -0.02279754, 0.13986246 0.08280167 -0.026404098, 0.13204835 0.090435982 -0.037258774, 0.1332411 0.089492708 -0.035523757, 0.14130826 0.082700223 -0.018995225, 0.14300969 0.08024314 -0.016995519, 0.14094213 0.083821386 -0.016995281, 0.13993569 0.085002214 -0.018995121, 0.13198143 0.092165023 -0.033639714, 0.13305835 0.092077017 -0.029994786, 0.13878526 0.087346435 -0.016995177, 0.13852566 0.087281346 -0.018994987, 0.13182086 0.093840271 -0.029994816, 0.13707843 0.089536995 -0.018995017, 0.13405102 0.092601478 -0.024239138, 0.13516435 0.090883821 -0.024512276, 0.13533707 0.091741592 -0.020623982, 0.13654013 0.090815902 -0.016994938, 0.13819183 0.084176689 -0.029995233, 0.13737045 0.085528731 -0.02995044, 0.13669515 0.09012115 -0.018994853, 0.12490988 0.074586213 -0.072020382, 0.12761594 0.073654473 -0.068738282, 0.12663871 0.071611375 -0.07202062, 0.13499603 0.080227554 -0.046995491, 0.13693322 0.076874286 -0.04699567, 0.13386549 0.07784465 -0.052836314, 0.12674296 0.077229857 -0.066749498, 0.129703 0.07881099 -0.059995636, 0.1284962 0.07566449 -0.065411419, 0.12311117 0.077519208 -0.072020262, 0.12960429 0.078973144 -0.059995621, 0.13182992 0.078361809 -0.05643554, 0.12390554 0.081704736 -0.066749245, 0.12124367 0.08040902 -0.072020054, 0.1224571 0.083860397 -0.066749215, 0.13173942 0.080273688 -0.054278225, 0.13297664 0.083532035 -0.046995267, 0.12670296 0.083548933 -0.059995383, 0.12364016 0.088018209 -0.05999516, 0.12698945 0.087595046 -0.054277882, 0.12309502 0.085961014 -0.063395128, 0.12879018 0.084924936 -0.054278016, 0.12897453 0.087229311 -0.05065541, 0.13087638 0.086785823 -0.046995133, 0.14130828 0.082697988 0.019004807, 0.14187086 0.081270158 0.02063553, 0.14300977 0.080241174 0.01700443, 0.14094214 0.083819509 0.017004639, 0.13993575 0.084999949 0.019004866, 0.14064243 0.082242459 0.024251267, 0.13878532 0.087344438 0.017004877, 0.13852561 0.087279201 0.019004866, 0.13944164 0.084178239 0.024501875, 0.13707837 0.089534909 0.019005209, 0.13654017 0.090814114 0.017005071, 0.13849083 0.083680332 0.03000465, 0.13738655 0.082996458 0.035509095, 0.13842995 0.08032462 0.03726621, 0.13850991 0.082024246 0.03364785, 0.13457538 0.092262983 0.022805259, 0.13516434 0.090881139 0.024522454, 0.13717316 0.08036238 0.041004568, 0.1380962 0.077514291 0.043004349, 0.13613404 0.080910683 0.043004587, 0.13588502 0.082521647 0.041004702, 0.13323967 0.093082696 0.026412204, 0.13305841 0.09207359 0.030005157, 0.13408829 0.084257483 0.043004662, 0.13456282 0.084660441 0.041004807, 0.13182083 0.093836784 0.030005261, 0.13320714 0.086777866 0.041004911, 0.13203286 0.091129929 0.035824597, 0.13324106 0.089488775 0.035533786, 0.13204344 0.089368194 0.039427787, 0.13196035 0.087552398 0.04300496, 0.1382 0.084178329 0.029960006, 0.13737047 0.085525393 0.029960036, 0.13273105 0.087504357 0.041004956, 0.14130415 0.084040016 -0.012995213, 0.14291658 0.081840456 -0.0093895942, 0.14337951 0.080448091 -0.012995541, 0.14130408 0.084038734 0.013004825, 0.14337958 0.080446661 0.013004556, 0.14259471 0.082651436 0.007233426, 0.14076054 0.085738391 -0.0072260946, 0.14128257 0.085230559 4.8279762e-06, 0.14236169 0.083183765 -0.0057796091, 0.13913886 0.087578535 -0.012994975, 0.14091708 0.08583346 4.7981739e-06, 0.14198464 0.083965659 0.0036212802, 0.13760355 0.090718627 -0.0072258711, 0.13688485 0.091061205 -0.012994975, 0.13592722 0.09321171 -0.0072257072, 0.14081678 0.085772097 0.0057912618, 0.13913892 0.087576926 0.013004914, 0.1377566 0.09081915 5.2154064e-06, 0.13521665 0.094479531 -0.0036127269, 0.1344199 0.095688522 5.3495169e-06, 0.13565339 0.093725264 0.0057917237, 0.13765858 0.0907543 0.0057916641, 0.13631223 0.0924218 0.0094011277, 0.1368849 0.091059744 0.013005182, 0.15441881 0.041487157 0.037822187, 0.15626462 0.04024592 0.03200227, 0.15520957 0.04414016 0.032002494, 0.14783503 0.038140178 0.058002204, 0.15046303 0.039781034 0.050839841, 0.14871542 0.040773541 0.054439858, 0.1468647 0.041720659 0.058002323, 0.15652789 0.03264004 0.037821531, 0.15679146 0.029215753 0.039263651, 0.15749054 0.030804455 0.035645172, 0.15808108 0.032384485 0.032001793, 0.15722196 0.036326617 0.032002166, 0.15439481 0.032194763 0.045001775, 0.15393816 0.027883291 0.048663244, 0.15544693 0.026656032 0.045001462, 0.15526125 0.038213462 0.037821949, 0.1537853 0.039802849 0.041425347, 0.15235613 0.031769246 0.050839588, 0.14871809 0.034537077 0.058001906, 0.14951344 0.030913681 0.058001801, 0.1523221 0.029076248 0.052285969, 0.1531454 0.037692219 0.045002013, 0.15304489 0.038098335 0.045002162, 0.15112323 0.037194163 0.050839856, 0.15911508 0.042863488 0.007788837, 0.15977833 0.04112494 0.0020022988, 0.15868807 0.045149744 0.0020025223, 0.15706822 0.043182939 0.024409324, 0.15709955 0.040454626 0.028002292, 0.15800074 0.04195118 0.020802423, 0.15603609 0.04437986 0.02800253, 0.16131578 0.033646256 0.0077882111, 0.16192532 0.030111462 0.0092305541, 0.16184047 0.031563014 0.0056181848, 0.1616523 0.032998711 0.0020017922, 0.16076674 0.037073672 0.0020020157, 0.16074982 0.033527792 0.015001908, 0.16116983 0.029112667 0.018632472, 0.16184634 0.02775535 0.01500161, 0.16000876 0.039395839 0.0077885836, 0.1592508 0.041399509 0.011398375, 0.16003154 0.033377588 0.020801947, 0.15806423 0.03650403 0.028002083, 0.15892965 0.032530278 0.02800189, 0.16039038 0.030446142 0.022248268, 0.15944745 0.039257228 0.015002191, 0.15928566 0.039908409 0.01500231, 0.1587349 0.039081514 0.02080217, 0.14554965 0.028186202 -0.06706135, 0.14318255 0.025766969 -0.072023153, 0.14253327 0.029145807 -0.072023019, 0.14508319 0.041211158 -0.061997712, 0.14603543 0.037697762 -0.06199795, 0.14315514 0.038543791 -0.067062214, 0.14496653 0.031043142 -0.067062676, 0.1469027 0.034162164 -0.061998084, 0.14768429 0.030606806 -0.061998397, 0.14180431 0.032508373 -0.072022751, 0.14386675 0.035795748 -0.067062274, 0.14099598 0.035852581 -0.072022513, 0.14977637 0.040189415 -0.052279949, 0.14783512 0.038146704 -0.057997897, 0.14686461 0.041727245 -0.057997659, 0.15474743 0.042491972 -0.035642788, 0.15626459 0.040249616 -0.031997755, 0.15417829 0.040820211 -0.039261907, 0.1552095 0.044143915 -0.031997472, 0.1518079 0.031660676 -0.052280247, 0.15298136 0.028608769 -0.050838381, 0.15130101 0.02978158 -0.054437846, 0.14951342 0.030920327 -0.057998285, 0.1487181 0.034543663 -0.05799818, 0.15439481 0.03219977 -0.044998229, 0.15544693 0.026661187 -0.044998497, 0.15631984 0.028263181 -0.041419461, 0.15057956 0.037066102 -0.052280009, 0.15146224 0.039169043 -0.048657626, 0.1561311 0.032561541 -0.039262354, 0.157222 0.036330253 -0.031997979, 0.15808108 0.032388151 -0.031998277, 0.1570842 0.029856533 -0.037815884, 0.1531454 0.037697345 -0.044997886, 0.15304491 0.038103431 -0.044997826, 0.15486766 0.038120866 -0.039261997, 0.15763976 0.042450607 -0.022241965, 0.15709952 0.040457815 -0.027997777, 0.15603612 0.044383109 -0.027997389, 0.15898514 0.043729544 -0.0056156814, 0.15977833 0.041125178 -0.0019976497, 0.15918148 0.042282104 -0.0092285126, 0.15868796 0.045150161 -0.0019975454, 0.15981565 0.03333509 -0.022242531, 0.16071451 0.029917806 -0.020800397, 0.15987343 0.031237572 -0.024406865, 0.15892977 0.032533377 -0.027998164, 0.15806426 0.036507159 -0.027997956, 0.16074975 0.03352952 -0.014998138, 0.1618464 0.027756989 -0.014998496, 0.1619267 0.029233873 -0.011392444, 0.15852082 0.039031237 -0.022242144, 0.15851249 0.041197628 -0.018626884, 0.16123131 0.033629596 -0.0092290491, 0.16076675 0.037073821 -0.0019979179, 0.1616523 0.032998979 -0.0019982159, 0.16190374 0.030694723 -0.007782504, 0.15944739 0.039258897 -0.01499778, 0.15928566 0.039910048 -0.014997676, 0.15992497 0.039376289 -0.0092286766, 0.15161668 0.047828317 -0.040997356, 0.15250891 0.046518028 -0.03941828, 0.15188296 0.044846237 -0.042997539, 0.15072575 0.048594117 -0.042997479, 0.15084143 0.050220042 -0.040997207, 0.15302879 0.048169255 -0.035814494, 0.14947599 0.052312195 -0.042997167, 0.15002841 0.052599192 -0.040996939, 0.15241088 0.050348073 -0.035501376, 0.1491778 0.054965317 -0.040996864, 0.14813471 0.055998117 -0.042996839, 0.1536396 0.050768614 -0.029997215, 0.15467723 0.051041871 -0.024494275, 0.15582168 0.048402935 -0.022799522, 0.15478066 0.049603343 -0.026406005, 0.14886099 0.058785021 -0.037260622, 0.14981398 0.057600141 -0.03552562, 0.15616785 0.049182624 -0.018997252, 0.15727964 0.046408743 -0.016997457, 0.15606038 0.050357252 -0.016997278, 0.15534182 0.051732242 -0.018997133, 0.1491807 0.060485572 -0.033641517, 0.15021098 0.06016016 -0.029996574, 0.15474181 0.054273814 -0.016997069, 0.15447423 0.054268152 -0.018996894, 0.14939691 0.062154502 -0.02999647, 0.15356524 0.056789517 -0.01899679, 0.15129556 0.060450673 -0.024241179, 0.15199876 0.058528304 -0.024514019, 0.1523581 0.059326112 -0.020625845, 0.15332502 0.058155894 -0.016996711, 0.15345767 0.051315725 -0.029997036, 0.15295783 0.05281657 -0.029952228, 0.15332144 0.057444185 -0.018996671, 0.15646188 0.050489902 -0.01299724, 0.15754449 0.047986746 -0.0093913823, 0.15768601 0.046526164 -0.012997344, 0.15646192 0.050488502 0.013002887, 0.15768597 0.046524763 0.013002694, 0.15741143 0.048848808 0.0072315484, 0.15630992 0.052266628 -0.0072279572, 0.15670598 0.051655322 2.9057264e-06, 0.15730251 0.049419612 -0.005781576, 0.15513822 0.054421395 -0.012996942, 0.15648375 0.052324355 2.9653311e-06, 0.15710898 0.050265938 0.0036192238, 0.15434021 0.057824552 -0.0072276294, 0.15371583 0.058318138 -0.012996614, 0.15326075 0.060628086 -0.0072273612, 0.15637244 0.052286863 0.0057893097, 0.15513828 0.054419905 0.013003111, 0.15451202 0.057888389 3.2633543e-06, 0.15285009 0.06202215 -0.0036145896, 0.15234239 0.063378304 3.5315752e-06, 0.15310812 0.061189562 0.0057898015, 0.15440202 0.057846904 0.0057896823, 0.15346052 0.059772223 0.0093993247, 0.1537158 0.058316767 0.013003305, 0.15616781 0.049180537 0.019002825, 0.15639846 0.047663271 0.020633712, 0.15727966 0.046406746 0.017002553, 0.15606035 0.050355226 0.017002806, 0.15534183 0.051730245 0.01900284, 0.15541728 0.048884511 0.024249345, 0.15474179 0.054271877 0.017003015, 0.15447418 0.054266036 0.019003078, 0.1546772 0.05103907 0.024500087, 0.15356527 0.056787223 0.019003332, 0.15332496 0.058154106 0.017003238, 0.15363961 0.050765097 0.030002907, 0.15241081 0.050344169 0.035507202, 0.15283361 0.047507048 0.037264377, 0.15328968 0.049146414 0.033646047, 0.15173197 0.060003847 0.0228035, 0.15199883 0.058525503 0.024520561, 0.15161672 0.047823578 0.041002661, 0.15188301 0.044841468 0.043002546, 0.15072577 0.048589289 0.043002784, 0.1508414 0.050215364 0.04100278, 0.15061226 0.061100364 0.026410535, 0.15021098 0.060156912 0.030003354, 0.14947608 0.052307308 0.043002903, 0.15002835 0.052594632 0.041003048, 0.14939684 0.062151104 0.030003533, 0.14917779 0.054960638 0.041003168, 0.14900129 0.05946517 0.035822913, 0.1498141 0.057596028 0.035532087, 0.14861971 0.05774492 0.039425939, 0.14813462 0.055993348 0.043003112, 0.15346693 0.051315248 0.029958218, 0.15295777 0.052813262 0.029958233, 0.14887524 0.055774987 0.041003153, 0.13837418 0.04492116 -0.07202208, 0.1408051 0.043410838 -0.068739966, 0.13939776 0.041636407 -0.072022289, 0.14946316 0.048176676 -0.046997219, 0.15060556 0.04447636 -0.046997458, 0.14783067 0.046104938 -0.052838027, 0.14074957 0.047090828 -0.066751257, 0.14398745 0.047973394 -0.059997171, 0.14211062 0.04517436 -0.065413058, 0.1372733 0.048180878 -0.072021753, 0.14392735 0.04815346 -0.059997335, 0.14596111 0.047062397 -0.056437373, 0.13897914 0.052084684 -0.066750899, 0.13609563 0.051413625 -0.072021514, 0.1380467 0.054508656 -0.066750705, 0.14629835 0.04894647 -0.054280028, 0.1482297 0.051847726 -0.046997145, 0.14211692 0.053260148 -0.059997037, 0.14012538 0.058299065 -0.059996784, 0.1432966 0.057141185 -0.054279491, 0.13913606 0.056414723 -0.063396826, 0.14445814 0.05413726 -0.054279789, 0.14515062 0.05634287 -0.050657228, 0.14690621 0.055487245 -0.046996891, 0.080179945 0.12139663 -0.072017714, 0.083022028 0.12173137 -0.068735555, 0.083028227 0.11946642 -0.072017878, 0.086818844 0.13085535 -0.04699263, 0.090019226 0.12867469 -0.046992779, 0.086834431 0.12821788 -0.052833483, 0.08068426 0.12457374 -0.066746771, 0.08266513 0.12728253 -0.05999285, 0.082943067 0.12392402 -0.065408826, 0.07728672 0.12325865 -0.072017595, 0.082505733 0.12738585 -0.059992835, 0.084776014 0.1278007 -0.056432739, 0.076186359 0.12737441 -0.066746697, 0.074350446 0.12505195 -0.07201764, 0.073945999 0.12868807 -0.066746697, 0.083864868 0.12948403 -0.054275542, 0.083565801 0.13295639 -0.046992496, 0.077906311 0.13024962 -0.05999276, 0.073207632 0.1329475 -0.059992567, 0.076408789 0.13401937 -0.054275215, 0.073609173 0.1308575 -0.063392475, 0.079189718 0.13239497 -0.054275349, 0.078355908 0.13455117 -0.050652832, 0.080261692 0.13497686 -0.046992421, 0.090847313 0.13702717 -0.012992412, 0.093254462 0.13574502 -0.0093865097, 0.094275668 0.13469127 -0.012992382, 0.090847284 0.13702565 0.01300779, 0.094275743 0.13468993 0.013007626, 0.092612103 0.13633594 0.0072363913, 0.089620531 0.13832134 -0.0072230846, 0.090311065 0.13809025 7.7784061e-06, 0.092171624 0.13671428 -0.0057765841, 0.087361231 0.13927555 -0.012992218, 0.08972016 0.13847491 7.7784061e-06, 0.09149231 0.13725528 0.0036241412, 0.084615335 0.1414386 -0.0072228462, 0.083819479 0.14143538 -0.012992084, 0.082023352 0.14295736 -0.0072228462, 0.089656353 0.13837597 0.0057942122, 0.087361142 0.13927421 0.01300779, 0.08470948 0.1415956 8.046627e-06, 0.079590395 0.14453506 8.1211329e-06, 0.081553459 0.14330125 0.0057944953, 0.080832914 0.14379141 -0.0036100745, 0.08464931 0.14149448 0.0057944655, 0.082712576 0.14241272 0.0094038397, 0.083819464 0.14143395 0.013008028, 0.088719755 0.13192561 -0.040992588, 0.090234131 0.13145751 -0.039413497, 0.090787157 0.12976021 -0.042992681, 0.087545589 0.13196895 -0.042992622, 0.086622357 0.1333122 -0.040992469, 0.089610875 0.13307267 -0.035809696, 0.084250525 0.13409653 -0.042992562, 0.084503189 0.13466546 -0.040992483, 0.087769255 0.1343908 -0.035496697, 0.08236295 0.13598496 -0.04099226, 0.080903649 0.13614202 -0.042992324, 0.088467717 0.13548541 -0.029992536, 0.089108184 0.13634607 -0.024489477, 0.09164834 0.13499644 -0.02279453, 0.090085968 0.13528594 -0.026401103, 0.07973364 0.13877374 -0.037255988, 0.081217557 0.13844138 -0.03552112, 0.091432601 0.13582182 -0.018992394, 0.094031483 0.1343461 -0.016992554, 0.090616286 0.13667303 -0.016992405, 0.089197174 0.13730022 -0.01899223, 0.078923106 0.14030251 -0.033637017, 0.079931438 0.14069057 -0.029992089, 0.087143376 0.13891318 -0.016992182, 0.086937785 0.13874188 -0.018992275, 0.078051552 0.14174199 -0.029992044, 0.084655091 0.14014629 -0.018992066, 0.080598146 0.14159372 -0.024236456, 0.082346454 0.1405293 -0.0245094, 0.082129762 0.14137703 -0.02062127, 0.083615288 0.14106494 -0.016992033, 0.087984279 0.13579991 -0.029992431, 0.086657688 0.13666162 -0.029947475, 0.084056392 0.14050633 -0.018992037, 0.091432691 0.13581961 0.019007683, 0.092558891 0.13477716 0.020638511, 0.094031453 0.13434428 0.017007515, 0.090616286 0.1366711 0.017007679, 0.089197204 0.13729808 0.019007713, 0.09103018 0.13512036 0.024254307, 0.087143376 0.13891122 0.017007768, 0.086937845 0.13873971 0.019007862, 0.089108169 0.1363433 0.02450487, 0.084655151 0.1401442 0.019007847, 0.083615229 0.14106309 0.017007902, 0.088467672 0.13548213 0.030007482, 0.087769225 0.13438675 0.035511792, 0.089868546 0.13243225 0.037269264, 0.089203343 0.13399836 0.033650786, 0.08121638 0.141516 0.022808135, 0.082346454 0.14052653 0.02452521, 0.088719741 0.13192096 0.041007459, 0.090787187 0.12975532 0.043007284, 0.087545648 0.13196403 0.043007433, 0.086622298 0.13330749 0.041007668, 0.079656973 0.14167517 0.026415005, 0.079931498 0.14068717 0.030007944, 0.084250495 0.13409173 0.043007523, 0.084503204 0.13466081 0.041007578, 0.078051463 0.14173871 0.030008003, 0.082362935 0.13598028 0.041007683, 0.079416797 0.13939199 0.035827383, 0.081217498 0.13843757 0.035536572, 0.080190614 0.13780922 0.039430544, 0.080903634 0.13613716 0.043007657, 0.087989494 0.13580474 0.029962838, 0.086657703 0.13665837 0.029963076, 0.081618845 0.13642827 0.041007638, 0.096223786 0.11278647 -0.067056671, 0.09588176 0.10941908 -0.072018474, 0.093267351 0.1116561 -0.072018206, 0.087738052 0.12267885 -0.061993241, 0.090673104 0.12052563 -0.061993256, 0.087893933 0.11939111 -0.067057684, 0.093986481 0.11465636 -0.067057952, 0.093555525 0.1183022 -0.061993286, 0.096383318 0.11600983 -0.06199351, 0.090600982 0.11383042 -0.072018161, 0.090163589 0.11768651 -0.067057833, 0.0878838 0.11594114 -0.072017998, 0.094861373 0.12871397 0.037826926, 0.097078368 0.12889454 0.032007232, 0.093825534 0.13128132 0.032007262, 0.091800004 0.12199217 0.058006808, 0.092831925 0.12491363 0.050844684, 0.090846553 0.12459999 0.054444626, 0.088808909 0.1241864 0.058006957, 0.10202648 0.1231119 0.037826627, 0.10436738 0.12059918 0.039268926, 0.10392362 0.12227714 0.035650343, 0.10340014 0.12388089 0.032007009, 0.10027066 0.12642717 0.032007173, 0.10063602 0.12143379 0.045006782, 0.1029671 0.11777827 0.048668295, 0.10491183 0.1177595 0.045006663, 0.097561151 0.12667981 0.037826896, 0.095416129 0.12700227 0.041430205, 0.099307224 0.11982998 0.050844446, 0.094736919 0.1197257 0.058006808, 0.097617775 0.11738867 0.0580066, 0.10095969 0.11770332 0.052291095, 0.096231639 0.12495294 0.04500702, 0.095899701 0.12520787 0.04500702, 0.094960988 0.12330264 0.050844595, 0.09767589 0.1327185 0.0077938288, 0.099278718 0.13177282 0.0020072907, 0.095916674 0.13423985 0.0020075291, 0.095875889 0.13169181 0.024414346, 0.097601295 0.12957817 0.028007179, 0.097373083 0.13131034 0.020807475, 0.094322428 0.13198417 0.028007478, 0.10514331 0.12688437 0.0077936798, 0.10782374 0.12450069 0.0092358887, 0.10685247 0.12558258 0.0056235194, 0.10581039 0.1265879 0.0020072013, 0.1025773 0.12922168 0.0020072758, 0.10477452 0.12643877 0.015007079, 0.10785551 0.12324864 0.018637821, 0.10923091 0.12260938 0.015006945, 0.10053664 0.13056472 0.0077937394, 0.098694831 0.13165849 0.011403397, 0.10430637 0.12587336 0.020807087, 0.10081881 0.12709096 0.028007209, 0.10397294 0.12452388 0.02800706, 0.10641463 0.1238052 0.022253528, 0.10018396 0.13010621 0.015007436, 0.099651426 0.13051447 0.015007406, 0.099736273 0.12952447 0.020807207, 0.096781 0.1314761 -0.022237107, 0.09760128 0.12958142 -0.02799274, 0.094322458 0.13198739 -0.027992502, 0.097034812 0.13331482 -0.0056106448, 0.099278703 0.13177323 -0.0019925535, 0.098090872 0.13230571 -0.0092234462, 0.095916688 0.13424009 -0.0019924194, 0.10416558 0.12570605 -0.022237197, 0.10699883 0.1235947 -0.020795092, 0.10551859 0.12410221 -0.02440156, 0.10397285 0.12452707 -0.027993038, 0.10081871 0.1270943 -0.027992904, 0.10477453 0.12644044 -0.014992952, 0.10837267 0.12381586 -0.011387154, 0.10923086 0.12261111 -0.014993131, 0.099601731 0.12935224 -0.022237122, 0.098244399 0.13104084 -0.018621787, 0.10508829 0.12681881 -0.0092236251, 0.10257736 0.1292218 -0.0019927472, 0.10581042 0.12658814 -0.0019928217, 0.10744375 0.12494352 -0.0077774227, 0.10018398 0.13010785 -0.014992803, 0.099651456 0.13051611 -0.014992684, 0.10048409 0.13049719 -0.0092234313, 0.092044041 0.12480584 -0.052275181, 0.091800004 0.12199861 -0.057993129, 0.088809088 0.12419283 -0.057993129, 0.094494209 0.12970543 -0.03563796, 0.097078398 0.12889814 -0.031992644, 0.09509185 0.1280435 -0.03925702, 0.093825489 0.13128501 -0.03199254, 0.098949939 0.11940467 -0.0522753, 0.10177015 0.11775017 -0.05083333, 0.099725276 0.11761943 -0.054432899, 0.097617909 0.11739504 -0.057993352, 0.094736859 0.11973232 -0.057993248, 0.10063595 0.12143892 -0.044993192, 0.10491182 0.11776462 -0.044993371, 0.10459544 0.11956143 -0.041414395, 0.094619274 0.1228649 -0.052275121, 0.09399806 0.12505937 -0.048652828, 0.10176773 0.12280431 -0.039257258, 0.10027067 0.12643078 -0.031992868, 0.10340013 0.12388444 -0.031992942, 0.10419944 0.12128356 -0.037810758, 0.096231535 0.12495816 -0.044993013, 0.095899746 0.12521294 -0.044992983, 0.097313851 0.12636295 -0.039257154, 0.12475967 0.10765615 0.0077924132, 0.12611179 0.10637754 0.0020060241, 0.12338306 0.10953072 0.0020061582, 0.12277655 0.10705572 0.02441296, 0.1239884 0.10461131 0.028005868, 0.1241513 0.10635066 0.020806, 0.12132718 0.10768628 0.028006151, 0.13074182 0.10030636 0.0077920407, 0.13282454 0.097386122 0.0092343837, 0.13211833 0.098657221 0.0056218803, 0.13132605 0.099869072 0.0020056367, 0.12876005 0.10315636 0.002005741, 0.130283 0.099954188 0.015005603, 0.13257706 0.096158177 0.018636227, 0.13377567 0.095229119 0.01500541, 0.12706947 0.10491955 0.0077922791, 0.12551716 0.10639578 0.011401802, 0.12970088 0.099507183 0.020805538, 0.12657179 0.10147026 0.028005809, 0.12907566 0.098265499 0.028005466, 0.13129604 0.097021729 0.022252142, 0.12662362 0.10455123 0.015005812, 0.12619539 0.10506755 0.01500605, 0.12605785 0.10408363 0.020805851, 0.12361048 0.10664406 -0.022238493, 0.12398843 0.10461432 -0.027993977, 0.12132712 0.10768941 -0.027993917, 0.12426718 0.10838011 -0.0056119561, 0.12611185 0.10637763 -0.0019939691, 0.12507215 0.10716125 -0.0092248321, 0.12338306 0.10953099 -0.0019938797, 0.12952602 0.099375248 -0.022238687, 0.13181834 0.096686542 -0.020796612, 0.13048816 0.097510666 -0.024403125, 0.1290756 0.098268807 -0.027994454, 0.12657182 0.10147339 -0.027994186, 0.13028301 0.099955827 -0.014994368, 0.13320711 0.096596152 -0.011388749, 0.13377561 0.095230699 -0.014994785, 0.12588784 0.1039457 -0.022238597, 0.12494037 0.10589382 -0.018623114, 0.13067326 0.10025483 -0.0092250854, 0.12876004 0.10315654 -0.0019942075, 0.13132606 0.099869221 -0.001994431, 0.13255231 0.097902507 -0.0077787489, 0.12662363 0.10455284 -0.0149941, 0.12619545 0.10506928 -0.014994115, 0.12700295 0.10486561 -0.0092249364, 0.12112504 0.10437813 0.037825689, 0.1233267 0.10406083 0.032005787, 0.12068635 0.10711172 0.032005936, 0.1166449 0.098505974 0.058005527, 0.11830093 0.10112464 0.050843313, 0.11629568 0.10126051 0.054443285, 0.11421719 0.10131094 0.058005705, 0.12686391 0.097322285 0.037825227, 0.12858708 0.0943515 0.039267242, 0.12852772 0.096086293 0.035648763, 0.12837414 0.097766191 0.032005474, 0.12588973 0.10094503 0.032005697, 0.12513499 0.095995545 0.045005366, 0.12848596 0.091461986 0.045005143, 0.12659422 0.091912955 0.04866682, 0.12330447 0.10179421 0.03782551, 0.12128507 0.10258582 0.0414287, 0.12348264 0.094727695 0.05084306, 0.11900377 0.095643073 0.058005393, 0.12129256 0.092723399 0.058005139, 0.12462062 0.092286527 0.052289665, 0.12162408 0.10040656 0.04500556, 0.12135716 0.10072896 0.045005575, 0.1200182 0.099080414 0.050843194, 0.11890784 0.088546783 -0.067058012, 0.11782484 0.085340202 -0.072019801, 0.11577389 0.088102639 -0.072019681, 0.11283609 0.1000796 -0.061994433, 0.11521845 0.097327262 -0.061994508, 0.11225642 0.096839726 -0.067058951, 0.11714262 0.090867996 -0.067059293, 0.11753379 0.094518125 -0.061994657, 0.1197806 0.091653913 -0.061994806, 0.11365815 0.090815961 -0.072019443, 0.11408985 0.09467274 -0.067059159, 0.11147879 0.093478292 -0.072019368, 0.11750756 0.10119519 -0.052276358, 0.11664496 0.09851253 -0.05799447, 0.11421713 0.10131747 -0.057994366, 0.1209868 0.10542667 -0.035639375, 0.12332661 0.10406449 -0.031994224, 0.12119961 0.1036734 -0.039258301, 0.12068637 0.10711524 -0.03199403, 0.12303835 0.094392568 -0.052276716, 0.12541984 0.092151999 -0.050834775, 0.12339707 0.092479736 -0.05443424, 0.12129258 0.092729956 -0.057994798, 0.11900379 0.095649421 -0.057994664, 0.12513502 0.096000671 -0.044994682, 0.12848601 0.091466963 -0.044994757, 0.12857744 0.093289047 -0.041415915, 0.11958636 0.098729581 -0.052276567, 0.11946902 0.10100746 -0.048654214, 0.12654229 0.097079873 -0.039258674, 0.12588973 0.10094857 -0.031994313, 0.12837423 0.097769648 -0.031994566, 0.12857462 0.095056206 -0.037812203, 0.12162411 0.10041159 -0.044994324, 0.12135734 0.10073394 -0.044994339, 0.12299186 0.10154042 -0.039258435, 0.11936322 0.11206862 0.019006312, 0.12022929 0.1108017 0.020637289, 0.12156844 0.11005205 0.017006218, 0.11875671 0.1130805 0.017006308, 0.11751275 0.11400756 0.019006401, 0.1188152 0.11147642 0.024252921, 0.11586946 0.11603707 0.017006412, 0.11563085 0.11591566 0.019006684, 0.11721376 0.11309645 0.02450341, 0.11371785 0.11779302 0.019006655, 0.11290856 0.11892024 0.017006695, 0.11639757 0.11239934 0.030006155, 0.115473 0.11148697 0.035510555, 0.11708489 0.10911414 0.037267864, 0.11678474 0.110789 0.033649519, 0.11067063 0.11989552 0.022806808, 0.11155234 0.11867937 0.024523869, 0.11585097 0.10887149 0.041006148, 0.11738482 0.10629997 0.043005988, 0.11471599 0.1091747 0.043006122, 0.11411472 0.11068985 0.041006267, 0.10918579 0.12039769 0.026413813, 0.10923366 0.11937341 0.030006677, 0.11197695 0.11198217 0.043006271, 0.11234984 0.11248079 0.041006342, 0.10763484 0.12081677 0.030006796, 0.11055695 0.11424345 0.041006535, 0.10844371 0.11822528 0.035826132, 0.1099869 0.11689401 0.035535425, 0.10884608 0.11650982 0.039429218, 0.1091691 0.11472121 0.04300645, 0.11600322 0.11282012 0.029961646, 0.11489473 0.11394879 0.029961661, 0.10993111 0.11484584 0.041006535, 0.11906095 0.11337617 -0.012993544, 0.1211223 0.11159053 -0.0093878359, 0.12188348 0.11033601 -0.012993887, 0.1190609 0.11337474 0.013006389, 0.12188345 0.11033466 0.01300621, 0.12062766 0.11230966 0.0072349608, 0.1181528 0.11491087 -0.0072244108, 0.11877462 0.11453217 6.4522028e-06, 0.12028246 0.11277661 -0.0057779402, 0.11616249 0.116344 -0.012993351, 0.11828436 0.11503831 6.4522028e-06, 0.11974072 0.11345497 0.0036228299, 0.11396684 0.11906376 -0.007224068, 0.11319011 0.11923769 -0.012993321, 0.11177786 0.12112126 -0.0072240531, 0.1182002 0.1149562 0.0057928711, 0.11616249 0.11634248 0.013006598, 0.11409363 0.11919585 6.6906214e-06, 0.10975699 0.12320068 6.8098307e-06, 0.11139633 0.12156096 0.0057932734, 0.11080281 0.12219936 -0.0036112219, 0.11401248 0.11911061 0.0057931691, 0.11232874 0.12043691 0.0094025582, 0.11319007 0.11923635 0.013006836, 0.11585109 0.10887596 -0.040993974, 0.1172234 0.10808262 -0.039414749, 0.11738473 0.10630494 -0.042994127, 0.11471607 0.10917944 -0.042993844, 0.11411472 0.11069447 -0.04099378, 0.11697526 0.1097959 -0.035811186, 0.11197695 0.11198705 -0.042993724, 0.11234987 0.1124855 -0.040993646, 0.11547302 0.11149085 -0.035497963, 0.11055692 0.11424807 -0.040993512, 0.10916911 0.11472598 -0.042993531, 0.11639751 0.1124028 -0.029993743, 0.11721373 0.1130991 -0.024490818, 0.11938991 0.11121798 -0.02279602, 0.11793098 0.11184803 -0.026402444, 0.10861424 0.11755204 -0.037257269, 0.10998696 0.11689785 -0.035522178, 0.1193631 0.11207092 -0.018993601, 0.12156855 0.11005399 -0.016993821, 0.11875676 0.11308241 -0.016993612, 0.11751282 0.11400953 -0.018993601, 0.10816424 0.11922297 -0.033638224, 0.10923366 0.11937678 -0.02999337, 0.11586951 0.11603898 -0.016993567, 0.11563082 0.11591792 -0.018993407, 0.10763478 0.12082031 -0.029993236, 0.11371796 0.11779502 -0.018993333, 0.11008462 0.12010902 -0.024237692, 0.11155228 0.11868218 -0.024510652, 0.11152977 0.11955684 -0.020622522, 0.11290857 0.11892205 -0.01699321, 0.11599633 0.1128169 -0.029993653, 0.11489476 0.1139521 -0.029948786, 0.11321425 0.11827928 -0.018993214, 0.10518196 0.10051137 -0.072018906, 0.10802741 0.10020524 -0.068736851, 0.10752943 0.097995788 -0.072019041, 0.11375964 0.10825559 -0.046993807, 0.11639439 0.10541746 -0.04699406, 0.11318782 0.10568079 -0.052834809, 0.10638072 0.10349667 -0.066748023, 0.10891482 0.10569659 -0.059993923, 0.10843839 0.10236046 -0.065409973, 0.10277583 0.10297051 -0.072018862, 0.1087824 0.1058329 -0.059994012, 0.11108808 0.10573229 -0.056434125, 0.10261874 0.10722789 -0.066747859, 0.10031202 0.10537228 -0.072018579, 0.10072699 0.10900718 -0.066747829, 0.11057453 0.10757595 -0.054276675, 0.11105554 0.11102784 -0.046993673, 0.1049356 0.10964835 -0.059993818, 0.1009551 0.11332402 -0.059993595, 0.10431449 0.11365682 -0.054276392, 0.10088134 0.11119717 -0.063393697, 0.10666429 0.11145431 -0.054276526, 0.10633118 0.11374202 -0.050654039, 0.10828397 0.11373273 -0.046993554, 0.14106217 -0.035591155 0.072022527, 0.14018115 -0.038916975 0.072022423, 0.14336374 -0.037763894 0.067060858, 0.14570022 -0.027393222 0.067062929, 0.14792839 -0.02940464 0.061998338, 0.1485949 -0.025825948 0.061998472, 0.14407854 -0.034936845 0.067061067, 0.14633724 -0.03650865 0.061997995, 0.14717568 -0.032966316 0.061998159, 0.14186426 -0.032245219 0.072022885, 0.1451498 -0.030177951 0.067061365, 0.14258705 -0.028881371 0.072022989, 0.15238011 -0.02877596 -0.052283779, 0.14974464 -0.029773891 -0.058001742, 0.15042382 -0.026127011 -0.058001474, 0.1578583 -0.028858125 -0.035646841, 0.15825242 -0.031536818 -0.032001808, 0.15662017 -0.030117601 -0.039266005, 0.15899141 -0.027570456 -0.03200157, 0.1505101 -0.037341416 -0.052284181, 0.15024328 -0.040600359 -0.05084227, 0.14923792 -0.038814455 -0.054441631, 0.14812136 -0.037013024 -0.058002204, 0.14897701 -0.033403277 -0.058001906, 0.1530748 -0.037978202 -0.045002148, 0.15161958 -0.043424785 -0.045002401, 0.15310127 -0.042360157 -0.041423589, 0.15174857 -0.031938285 -0.052283794, 0.15345645 -0.030426621 -0.04866159, 0.15479633 -0.038405597 -0.039266288, 0.15741444 -0.035483509 -0.032002017, 0.15647799 -0.03940782 -0.032002181, 0.15448132 -0.041256309 -0.037819862, 0.15433443 -0.032483071 -0.045001805, 0.15442002 -0.032073468 -0.04500182, 0.15606999 -0.032848716 -0.03926608, 0.16044664 -0.030150592 -0.022246033, 0.15909514 -0.031711578 -0.028001696, 0.15984002 -0.027713567 -0.028001487, 0.16221413 -0.029582024 -0.0056198537, 0.16179885 -0.032272756 -0.002001822, 0.16176283 -0.030971289 -0.0092325807, 0.16256283 -0.028173238 -0.0020015836, 0.15845197 -0.039307445 -0.02224654, 0.15777911 -0.042776227 -0.020804361, 0.15759397 -0.041222304 -0.024410903, 0.15730578 -0.039645225 -0.028002232, 0.15825012 -0.035689503 -0.028002098, 0.15937811 -0.039537549 -0.015002295, 0.15786156 -0.045214206 -0.015002534, 0.15857479 -0.043918431 -0.011396632, 0.1597569 -0.033613622 -0.022246301, 0.1606894 -0.031658113 -0.018630892, 0.15985551 -0.039656401 -0.0092330873, 0.16093162 -0.036351711 -0.0020020902, 0.15996143 -0.04040724 -0.0020023137, 0.15918797 -0.042592227 -0.0077866912, 0.16069061 -0.033810377 -0.015001938, 0.16082743 -0.033153564 -0.015001878, 0.16117194 -0.033912003 -0.0092328489, 0.15712804 -0.029621422 0.037818104, 0.15825243 -0.031540483 0.031998336, 0.15899146 -0.027574092 0.03199856, 0.14974463 -0.029780507 0.05799827, 0.15282424 -0.02944234 0.050836131, 0.1516802 -0.027789742 0.054436013, 0.15042384 -0.026133537 0.057998464, 0.15518963 -0.038507462 0.037817657, 0.15394154 -0.041707039 0.039259717, 0.15526055 -0.040578961 0.035641268, 0.15647811 -0.039411604 0.031997889, 0.15741441 -0.035487175 0.031998098, 0.15307474 -0.037983298 0.044997796, 0.15079281 -0.041669667 0.048659369, 0.15161958 -0.043429852 0.044997483, 0.15646669 -0.032936394 0.037817851, 0.15582661 -0.03086406 0.041421354, 0.15105356 -0.037481993 0.05083558, 0.14897698 -0.033409774 0.057998121, 0.14812133 -0.037019491 0.057997912, 0.1498545 -0.039893687 0.052282259, 0.15433444 -0.032488078 0.044998094, 0.15442002 -0.032078534 0.044998124, 0.15229651 -0.032059461 0.050835818, 0.16195562 -0.030418754 0.0077847093, 0.16179885 -0.032273054 0.0019981265, 0.16256276 -0.028173417 0.0019984692, 0.16025057 -0.029243052 0.024405271, 0.15909508 -0.031714708 0.027998269, 0.16055635 -0.030757368 0.020798251, 0.15984003 -0.027716756 0.027998492, 0.15993932 -0.039678216 0.0077841431, 0.15895471 -0.043127358 0.0092263669, 0.15950808 -0.041782618 0.0056141019, 0.15996137 -0.040407479 0.0019977242, 0.16093159 -0.036351979 0.001997903, 0.15937814 -0.039539307 0.014997751, 0.15784092 -0.043699384 0.018628359, 0.15786156 -0.045215875 0.014997512, 0.16125637 -0.033930779 0.0077845305, 0.16144288 -0.031796783 0.011394233, 0.15866596 -0.039363027 0.020797804, 0.15825015 -0.035692722 0.027998045, 0.15730579 -0.039648354 0.027997896, 0.15771741 -0.042159885 0.02224429, 0.16069067 -0.033812225 0.014998108, 0.16082744 -0.033155262 0.014998168, 0.15997267 -0.033661366 0.020798117, 0.14415975 -0.019565344 -0.072025597, 0.14569461 -0.021980911 -0.068743676, 0.14365664 -0.022969097 -0.07202588, 0.15556356 -0.021443605 -0.047001183, 0.15498742 -0.025273174 -0.047001451, 0.1531937 -0.022601753 -0.052841976, 0.14724144 -0.018641293 -0.066754788, 0.15054163 -0.019251049 -0.06000112, 0.14763609 -0.020958364 -0.065416783, 0.14458218 -0.016150773 -0.072025493, 0.15056568 -0.019062638 -0.060001075, 0.15192467 -0.020927966 -0.056441188, 0.14781307 -0.013373733 -0.066754565, 0.14492378 -0.012726992 -0.072025284, 0.14802453 -0.010785282 -0.066754535, 0.15304601 -0.019376963 -0.054283917, 0.15604505 -0.017600983 -0.047000989, 0.15115017 -0.013676018 -0.060000747, 0.15154219 -0.0082721114 -0.060000464, 0.15389706 -0.010691375 -0.054283276, 0.1498332 -0.0095406473 -0.063400388, 0.15364026 -0.01390177 -0.054283544, 0.15522119 -0.012215018 -0.050660908, 0.15643172 -0.013747692 -0.047000706, 0.15735282 -0.022691995 -0.04100126, 0.15758829 -0.024259567 -0.039422229, 0.15629891 -0.025494188 -0.043001428, 0.15688232 -0.021615446 -0.043001294, 0.15769207 -0.0202007 -0.041001141, 0.15877309 -0.022997439 -0.035818368, 0.15736964 -0.017723352 -0.043001056, 0.15799192 -0.017704427 -0.041001007, 0.15916175 -0.020766288 -0.035505384, 0.15825209 -0.015203416 -0.041000903, 0.15776034 -0.01382044 -0.043000728, 0.16045146 -0.020920783 -0.030001119, 0.16150504 -0.02112475 -0.02449818, 0.16139109 -0.023998886 -0.02280362, 0.16097403 -0.022465587 -0.026409999, 0.15962417 -0.011624664 -0.037264585, 0.15996867 -0.01310575 -0.035529584, 0.16204143 -0.023446321 -0.019001335, 0.16183966 -0.026428223 -0.017001495, 0.16245422 -0.022341579 -0.017001331, 0.16240355 -0.020790964 -0.019001082, 0.16065004 -0.010231107 -0.033645436, 0.16143724 -0.010971427 -0.030000582, 0.16296566 -0.018240809 -0.017001078, 0.16272211 -0.018129796 -0.019000962, 0.16156904 -0.008821398 -0.030000523, 0.16299704 -0.015463859 -0.019000828, 0.16254061 -0.011180401 -0.024245054, 0.1623401 -0.013217509 -0.024518117, 0.16301009 -0.012654513 -0.020629957, 0.16337357 -0.014128357 -0.01700075, 0.16052501 -0.020348787 -0.030001178, 0.16072579 -0.018779635 -0.029956162, 0.1630616 -0.014768213 -0.019000813, 0.16204143 -0.023448586 0.018998712, 0.16159105 -0.024915695 0.020629585, 0.16183963 -0.02643007 0.01699844, 0.16245425 -0.022343487 0.016998842, 0.16240358 -0.02079308 0.018998876, 0.16123702 -0.023389757 0.024245292, 0.16296576 -0.018242747 0.016998962, 0.16272208 -0.018131942 0.018998936, 0.16150501 -0.021127433 0.024495929, 0.16299704 -0.015466034 0.018999085, 0.16337365 -0.014130354 0.016999155, 0.16045147 -0.020924121 0.029998884, 0.15916181 -0.020770282 0.035503209, 0.15831178 -0.02350992 0.037260488, 0.1594339 -0.022230774 0.033641994, 0.16274114 -0.011772662 0.022799417, 0.16234016 -0.01322028 0.024516642, 0.15735281 -0.022696674 0.040998772, 0.15629885 -0.025498927 0.042998612, 0.15688236 -0.021620303 0.04299885, 0.15769213 -0.020205379 0.040998876, 0.1622081 -0.010298878 0.026406482, 0.16143729 -0.010974854 0.029999316, 0.15736963 -0.01772818 0.042998955, 0.1579919 -0.017709017 0.040998951, 0.16156904 -0.0088247955 0.029999599, 0.15825209 -0.015208006 0.040999264, 0.16004729 -0.011073291 0.03581889, 0.15996864 -0.013109773 0.035528094, 0.15895724 -0.012457371 0.039422095, 0.15776034 -0.013825268 0.042999342, 0.16053459 -0.020353317 0.029954121, 0.16072577 -0.018782884 0.02995427, 0.15833288 -0.014343321 0.040999219, 0.16287377 -0.022396475 -0.013001248, 0.16276316 -0.02512148 -0.0093955696, 0.16225678 -0.026498556 -0.013001516, 0.1628738 -0.022397935 0.012998775, 0.16225681 -0.026500076 0.012998506, 0.16301769 -0.024286866 0.0072273612, 0.16350791 -0.020729661 -0.0072321445, 0.16359957 -0.021452218 -1.1622906e-06, 0.163167 -0.023725539 -0.005785659, 0.16338697 -0.018279821 -0.01300104, 0.16368979 -0.020753056 -1.1473894e-06, 0.16335994 -0.022879034 0.0036151707, 0.16414467 -0.014867604 -0.0072316527, 0.1637962 -0.014151782 -0.013000801, 0.16438851 -0.011873364 -0.0072315037, 0.16357329 -0.020738751 0.0057852864, 0.16338696 -0.018281281 0.012999028, 0.16432726 -0.014884621 -8.7916851e-07, 0.16462359 -0.010439217 -0.0036186278, 0.1647546 -0.0089971125 -5.0663948e-07, 0.16449498 -0.011301219 0.0057857335, 0.16421041 -0.014874339 0.0057855546, 0.16419758 -0.012731194 0.0093950629, 0.1637962 -0.014153153 0.012999266, 0.16377398 0.014408052 -0.012999237, 0.16427241 0.011726588 -0.0093934685, 0.16408536 0.010271281 -0.01299943, 0.16377398 0.014406443 0.013000891, 0.16408537 0.01026988 0.013000503, 0.1643347 0.012596965 0.0072294921, 0.16402118 0.016173989 -0.0072300285, 0.16427125 0.015489906 9.5367432e-07, 0.16435546 0.013177484 -0.0057836026, 0.16335833 0.018535495 -0.012998998, 0.16420366 0.016191632 8.9406967e-07, 0.16435519 0.014045537 0.0036172569, 0.16333763 0.022030771 -0.0072296858, 0.16283867 0.022651225 -0.012998804, 0.16290905 0.025004357 -0.0072294921, 0.16408689 0.016179711 0.005787313, 0.16335832 0.018534005 0.013001129, 0.16351938 0.022054881 1.2069941e-06, 0.16262586 0.027889937 1.475215e-06, 0.16288541 0.025585741 0.005787909, 0.16281903 0.026454777 -0.0036166459, 0.16340309 0.022038788 0.0057877451, 0.16291367 0.024125427 0.009397313, 0.16283871 0.022649676 0.013001233, 0.15845765 0.012891173 -0.040999293, 0.15903594 0.011415452 -0.039420202, 0.15805373 0.0099247992 -0.042999491, 0.15775932 0.013836324 -0.042999238, 0.15823399 0.015395612 -0.040999249, 0.15991025 0.012909591 -0.035816506, 0.15736838 0.017739147 -0.042999029, 0.15797067 0.017896086 -0.040998995, 0.15979263 0.015171289 -0.035503358, 0.15766801 0.02039209 -0.040998772, 0.15688084 0.021631122 -0.042998865, 0.16108423 0.015307724 -0.029999033, 0.1621567 0.015343308 -0.024496287, 0.16268532 0.012515694 -0.022801459, 0.16193734 0.013917834 -0.026407883, 0.15820922 0.024186552 -0.037262559, 0.15887466 0.022819221 -0.035527647, 0.16319627 0.013199031 -0.018999144, 0.163663 0.010247141 -0.016999438, 0.16335289 0.014367968 -0.016999185, 0.1629584 0.015868574 -0.01899913, 0.15889934 0.025773376 -0.03364341, 0.15983152 0.025226712 -0.029998496, 0.16293898 0.018479794 -0.016999051, 0.16267675 0.018533885 -0.018998921, 0.1594815 0.027352363 -0.029998496, 0.16235164 0.02119416 -0.018998712, 0.1609536 0.025268584 -0.024243057, 0.16121137 0.023238033 -0.024516076, 0.16173917 0.023935854 -0.020627901, 0.16242157 0.022579879 -0.016998708, 0.16102867 0.015881598 -0.029999107, 0.16087526 0.017456114 -0.029954091, 0.1622598 0.021886647 -0.018998727, 0.16319631 0.013196796 0.019000813, 0.16308351 0.011666268 0.020631626, 0.16366304 0.010245204 0.017000601, 0.16335288 0.01436615 0.01700078, 0.16295843 0.015866458 0.019000813, 0.1623988 0.013075322 0.024247319, 0.16293903 0.018477947 0.017000973, 0.16267672 0.01853177 0.019001067, 0.16215672 0.015340477 0.024497956, 0.16235164 0.021192044 0.019001186, 0.16242161 0.022577882 0.017001286, 0.16108425 0.015304297 0.030000851, 0.15979263 0.015167296 0.035505131, 0.1595735 0.012307286 0.037262529, 0.16038302 0.013803959 0.033644021, 0.16128017 0.024735719 0.022801593, 0.16121137 0.023235261 0.024518698, 0.15845765 0.012886494 0.041000679, 0.15805365 0.009920001 0.043000534, 0.1577594 0.013831407 0.043000713, 0.15823399 0.015390962 0.041000903, 0.16043264 0.026053876 0.026408523, 0.15983143 0.025223404 0.030001342, 0.15736841 0.01773417 0.04300113, 0.15797074 0.017891526 0.041001022, 0.1594815 0.027348906 0.030001611, 0.15766799 0.02038756 0.041001111, 0.15849815 0.024818301 0.035820872, 0.15887462 0.022815287 0.03553015, 0.15774339 0.023226261 0.039424151, 0.15688084 0.021626234 0.043001279, 0.16103825 0.015879124 0.029956192, 0.16087526 0.017452747 0.029956281, 0.15755431 0.021248519 0.04100129, 0.1448999 0.013003945 -0.072023794, 0.14693387 0.010990381 -0.068741754, 0.14516677 0.0095736682 -0.072024018, 0.15643555 0.013710201 -0.046999186, 0.15672596 0.0098484159 -0.046999305, 0.15438284 0.012053847 -0.052840099, 0.14769857 0.014590532 -0.066753075, 0.15105163 0.014730483 -0.059999198, 0.14859907 0.012419343 -0.06541498, 0.1445519 0.016426921 -0.072023764, 0.15103322 0.01491943 -0.059999183, 0.1527732 0.013403177 -0.056439191, 0.14708388 0.019853145 -0.066752627, 0.14412308 0.019840747 -0.072023451, 0.14671409 0.022423834 -0.066752642, 0.15352127 0.015164882 -0.05428198, 0.15604986 0.017563641 -0.046999022, 0.15040454 0.020300865 -0.059998825, 0.14958416 0.025656581 -0.059998468, 0.15241835 0.023822099 -0.054281443, 0.14820033 0.024039656 -0.063398555, 0.15288228 0.020635009 -0.054281697, 0.15404826 0.022631288 -0.050659031, 0.15556939 0.021406412 -0.046998709, 0.14817169 -0.0049083233 -0.067063302, 0.14532551 -0.0067400932 -0.072024897, 0.1454443 -0.0033013821 -0.072024792, 0.1506153 0.0078939795 -0.061999634, 0.15076181 0.0042566657 -0.061999768, 0.14814189 0.0057224333 -0.067064136, 0.14823872 -0.0019930005 -0.067064509, 0.15082058 0.00061687827 -0.062000066, 0.15079141 -0.0030233264 -0.062000126, 0.14548177 0.00013899803 -0.072024465, 0.1482242 0.0028849542 -0.067064241, 0.14543796 0.0035792589 -0.07202433, 0.15496351 0.0058533847 -0.052281812, 0.1526162 0.0042939782 -0.0579997, 0.15246695 0.0080006421 -0.057999581, 0.16032256 0.0069921315 -0.035644844, 0.16130264 0.004468441 -0.031999782, 0.15939558 0.0054889023 -0.039263904, 0.16114061 0.0084996819 -0.031999543, 0.15504634 -0.0029134154 -0.05228214, 0.15551135 -0.0061499178 -0.050840437, 0.15413398 -0.004632622 -0.054439589, 0.15264449 -0.0031247437 -0.058000162, 0.15267548 0.00058481097 -0.058000043, 0.15768836 -0.0029634833 -0.045000255, 0.15748167 -0.0085974634 -0.045000523, 0.1586892 -0.0072298348 -0.041421533, 0.1550515 0.0026297271 -0.052281827, 0.15637997 0.0044836998 -0.048659489, 0.15946172 -0.0029972792 -0.039264336, 0.16136393 0.00043430924 -0.032000005, 0.16132432 -0.0036001205 -0.032000244, 0.15978894 -0.0058465898 -0.037817806, 0.15769358 0.0026741922 -0.044999912, 0.157686 0.003092438 -0.044999927, 0.15946697 0.0027039051 -0.039264128, 0.16313323 0.006308049 -0.022243977, 0.16216311 0.0044856071 -0.027999699, 0.16199973 0.0085490942 -0.027999505, 0.16472974 0.0072556436 -0.0056176633, 0.16492355 0.0045400262 -0.0019997954, 0.16459906 0.005800873 -0.0092305392, 0.16475619 0.0087067187 -0.0019995868, 0.16322626 -0.0030630529 -0.022244647, 0.16334221 -0.0065945387 -0.020802438, 0.16281581 -0.005120784 -0.024408847, 0.162184 -0.0036473274 -0.028000191, 0.16222456 0.00041916966 -0.027999908, 0.16418028 -0.0030813217 -0.01500015, 0.16396499 -0.0089531541 -0.015000477, 0.16437185 -0.0075311065 -0.01139459, 0.16323143 0.0027784109 -0.022244185, 0.16370542 0.004892379 -0.018628925, 0.16467206 -0.0030908585 -0.0092309117, 0.16498563 0.00037041306 -0.0020000488, 0.16494222 -0.0037993491 -0.0020002723, 0.16467459 -0.0061016381 -0.0077846646, 0.16418548 0.0027943254 -0.014999896, 0.16417269 0.0034650862 -0.014999896, 0.16467728 0.0028023124 -0.0092308074, 0.15977946 0.0060854852 0.037820145, 0.16130267 0.0044648051 0.032000199, 0.16114055 0.0084961951 0.032000497, 0.15261622 0.0042874515 0.058000267, 0.15554337 0.0053024292 0.050838068, 0.15406044 0.0066588223 0.054438069, 0.15246694 0.0079940557 0.058000505, 0.15986694 -0.0030091405 0.037819549, 0.159362 -0.0064061582 0.039261729, 0.16039705 -0.00501284 0.035643175, 0.16132431 -0.0036037266 0.031999812, 0.16136393 0.00043061376 0.032000124, 0.15768835 -0.0029685199 0.044999778, 0.15628386 -0.0070702732 0.048661128, 0.1574817 -0.0086025 0.04499954, 0.15987235 0.0027063489 0.037819922, 0.15878718 0.0045842826 0.04142338, 0.15560621 -0.0029297769 0.050837472, 0.15267546 0.00057822466 0.058000013, 0.15264452 -0.0031312406 0.057999909, 0.15497376 -0.0055476725 0.052284151, 0.15769362 0.0026690364 0.045000181, 0.15768601 0.003087312 0.045000166, 0.15561146 0.002633363 0.05083786, 0.16466381 0.0063824058 0.0077867508, 0.16492364 0.0045396686 0.0020002872, 0.16475616 0.0087064505 0.0020004064, 0.1627396 0.0071491301 0.024407312, 0.16216306 0.0044824481 0.028000265, 0.16337466 0.0057408214 0.020800427, 0.16199969 0.008545965 0.028000504, 0.16475832 -0.0030935407 0.0077861995, 0.16456595 -0.006675303 0.0092284083, 0.16480622 -0.0052412152 0.0056161582, 0.16494228 -0.0037996769 0.0019997805, 0.16498564 0.00037017465 0.0019999743, 0.16418035 -0.0030830503 0.014999896, 0.16396494 -0.0089548528 0.014999449, 0.16360743 -0.0074810088 0.018630445, 0.16476354 0.0028029084 0.0077865422, 0.16447048 0.0049247742 0.011396229, 0.16344669 -0.00306952 0.020799935, 0.16222455 0.00041598082 0.028000012, 0.162184 -0.0036504567 0.027999699, 0.16314428 -0.0060075223 0.022246286, 0.16418542 0.0027926862 0.01500015, 0.16417265 0.0034635067 0.015000179, 0.1634519 0.002779752 0.020800158, 0.15276112 -0.058918357 0.01899676, 0.15199551 -0.060248375 0.020627543, 0.15190101 -0.061780185 0.016996443, 0.15340954 -0.057932824 0.016996682, 0.15370506 -0.056409955 0.018996775, 0.15199003 -0.058681816 0.024243429, 0.15482065 -0.054048568 0.016996905, 0.15460777 -0.053886414 0.018996984, 0.15275477 -0.056535959 0.024493948, 0.15546913 -0.051348567 0.018997118, 0.15613338 -0.050130129 0.016997278, 0.15177295 -0.056103259 0.029996902, 0.15054987 -0.055666387 0.035501197, 0.14911157 -0.058148086 0.037258461, 0.15049018 -0.057150781 0.033639953, 0.15604138 -0.04769069 0.022797406, 0.15532842 -0.04901287 0.024514496, 0.14835778 -0.057142049 0.04099682, 0.14670673 -0.059639543 0.04299669, 0.14813867 -0.055987865 0.042996868, 0.14924283 -0.054788649 0.040997013, 0.15584981 -0.046135366 0.026404455, 0.154948 -0.046622932 0.029997319, 0.14947969 -0.052301884 0.042997047, 0.15009055 -0.05242151 0.040997088, 0.15555489 -0.044556111 0.029997483, 0.15090081 -0.050041318 0.040997267, 0.15357108 -0.046409607 0.035816908, 0.15304118 -0.048377514 0.035526171, 0.15220037 -0.047516525 0.039420083, 0.15072921 -0.048583776 0.042997211, 0.15198091 -0.055565417 0.029952109, 0.15251678 -0.05407685 0.029952258, 0.151172 -0.049216151 0.040997207, 0.15380636 -0.058077574 -0.01300329, 0.15309212 -0.060709804 -0.0093975514, 0.15229201 -0.061939776 -0.013003543, 0.15380636 -0.058079153 0.012996718, 0.15229207 -0.061941266 0.012996599, 0.15352637 -0.059952974 0.0072253495, 0.15479541 -0.056593776 -0.0072339326, 0.15472424 -0.057318747 -3.144145e-06, 0.15379655 -0.059438676 -0.0057876706, 0.1552227 -0.054178596 -0.013003081, 0.15496777 -0.056657195 -3.1590462e-06, 0.15417317 -0.058656454 0.0036132038, 0.15672085 -0.051020533 -0.0072338432, 0.15654033 -0.050244987 -0.013002843, 0.15762484 -0.048155546 -0.007233575, 0.15485737 -0.056617111 0.0057832748, 0.15522271 -0.054179966 0.012996972, 0.15689512 -0.051077724 -2.8759241e-06, 0.15862182 -0.045432806 -2.5331974e-06, 0.15785605 -0.047621399 0.0057837367, 0.15817317 -0.046809673 -0.0036208183, 0.15678354 -0.051041663 0.0057834983, 0.15724793 -0.048949331 0.0093931854, 0.15654023 -0.050246418 0.01299724, 0.14835781 -0.0571374 -0.041003272, 0.14823842 -0.058718055 -0.039424255, 0.14670664 -0.059634775 -0.043003306, 0.14813861 -0.055983007 -0.043003172, 0.14924279 -0.054783881 -0.041003108, 0.14967453 -0.057751149 -0.035820454, 0.14947963 -0.052296907 -0.043002963, 0.15009055 -0.052416891 -0.041002929, 0.15054998 -0.055662543 -0.035507277, 0.15090087 -0.050036788 -0.041002735, 0.15072921 -0.048579007 -0.043002754, 0.15177298 -0.056099892 -0.030003086, 0.15275472 -0.056533277 -0.024500296, 0.15200426 -0.059310049 -0.022805482, 0.15193868 -0.05772227 -0.026411936, 0.1530349 -0.046852976 -0.037266433, 0.15304115 -0.04837361 -0.035531461, 0.15276107 -0.058916152 -0.019003153, 0.15190096 -0.061778247 -0.017003492, 0.1534096 -0.057930946 -0.017003343, 0.15370503 -0.056407809 -0.019003242, 0.15434521 -0.045722604 -0.033647478, 0.15494801 -0.046619654 -0.030002594, 0.15482067 -0.05404681 -0.017003179, 0.15460783 -0.053884387 -0.019002974, 0.15555483 -0.044552743 -0.030002564, 0.15546912 -0.051346302 -0.01900287, 0.15597722 -0.047068864 -0.02424711, 0.15532847 -0.049010128 -0.024520099, 0.15610692 -0.048610449 -0.020631984, 0.15613343 -0.050128251 -0.017002895, 0.15197188 -0.05555883 -0.030003101, 0.15251684 -0.054073602 -0.029958203, 0.15568674 -0.050682455 -0.019002751, 0.13619068 -0.051153123 -0.072027355, 0.13714972 -0.053849816 -0.068745479, 0.13494286 -0.054359585 -0.072027668, 0.14689106 -0.055522114 -0.04700312, 0.14547713 -0.05912739 -0.047003403, 0.14432287 -0.056123912 -0.052843928, 0.13940087 -0.05093807 -0.066756576, 0.14248279 -0.052266985 -0.060003012, 0.13927004 -0.053284913 -0.065418705, 0.13736245 -0.04791823 -0.072027266, 0.14254807 -0.052088499 -0.060002923, 0.14345801 -0.054209709 -0.05644308, 0.14113036 -0.04592976 -0.066756442, 0.13845727 -0.044656396 -0.072027132, 0.14191253 -0.043453336 -0.066756308, 0.14489642 -0.052947044 -0.05428566, 0.1482155 -0.051882952 -0.047003016, 0.14431661 -0.046967149 -0.060002625, 0.14590129 -0.041785985 -0.060002401, 0.14765884 -0.044668555 -0.054285243, 0.14395279 -0.042642444 -0.06340225, 0.14669406 -0.047741324 -0.054285333, 0.14861086 -0.046448827 -0.050662935, 0.14944997 -0.048212349 -0.047002748, 0.1497145 -0.065097332 -0.022247955, 0.14804947 -0.066318423 -0.028003767, 0.1496653 -0.062586397 -0.028003469, 0.15156442 -0.064936459 -0.0056217313, 0.15056089 -0.067467213 -0.002003774, 0.15081525 -0.066190362 -0.0092344582, 0.15221785 -0.063640535 -0.002003625, 0.14573225 -0.073580801 -0.022248581, 0.14430451 -0.076812834 -0.020806268, 0.14446965 -0.075256705 -0.024412826, 0.14453964 -0.073655009 -0.028004095, 0.1463405 -0.070008695 -0.028003752, 0.14658403 -0.074011296 -0.015004143, 0.14384234 -0.079208106 -0.015004516, 0.14482611 -0.078103483 -0.011398584, 0.14827137 -0.068319947 -0.022248223, 0.14961573 -0.066621125 -0.018632829, 0.14702313 -0.074233353 -0.0092350245, 0.14880759 -0.071250856 -0.0020039529, 0.1469593 -0.074988872 -0.0020041764, 0.14571914 -0.076947033 -0.0077886134, 0.14913814 -0.068719804 -0.01500389, 0.14941765 -0.0681099 -0.01500386, 0.14958474 -0.068925858 -0.0092346221, 0.14215574 -0.061962098 -0.052285656, 0.13936415 -0.062348604 -0.058003485, 0.140838 -0.058944315 -0.058003277, 0.14747855 -0.06326133 -0.035648748, 0.14726669 -0.065960586 -0.032003775, 0.14599106 -0.064213634 -0.039267808, 0.14886978 -0.062258124 -0.032003462, 0.13842654 -0.069896668 -0.052285939, 0.13744134 -0.073014498 -0.050844043, 0.13685861 -0.071049839 -0.054443419, 0.13617082 -0.069045007 -0.058003932, 0.13780819 -0.065716177 -0.058003679, 0.14078544 -0.071088225 -0.04500398, 0.13983613 -0.075366348 -0.041425377, 0.1381547 -0.076074481 -0.045004293, 0.1408364 -0.064904749 -0.052285686, 0.14283779 -0.063810915 -0.048663333, 0.14236873 -0.071888 -0.039268196, 0.1455715 -0.069621712 -0.032003969, 0.14378534 -0.073239416 -0.032004043, 0.14142731 -0.07459721 -0.037821725, 0.14323619 -0.066011161 -0.045003772, 0.14341088 -0.065631002 -0.045003742, 0.14484701 -0.066753745 -0.039267853, 0.15112643 -0.06569472 0.007782653, 0.15056095 -0.06746769 0.0019961596, 0.15221784 -0.063640743 0.0019964576, 0.14972591 -0.06416899 0.024403334, 0.14804947 -0.066321641 0.027996257, 0.1496869 -0.065713376 0.020796239, 0.14966536 -0.062589556 0.027996436, 0.14710014 -0.074273169 0.0077822357, 0.14537284 -0.077416927 0.0092245042, 0.14621139 -0.076228946 0.0056121647, 0.1469593 -0.07498914 0.0019958168, 0.14880759 -0.071251154 0.0019961149, 0.146584 -0.074012935 0.014995888, 0.14384237 -0.079209656 0.0149955, 0.14415979 -0.077726841 0.018626541, 0.14966318 -0.068963021 0.0077825189, 0.15031987 -0.066924065 0.011392176, 0.14592905 -0.073682576 0.020795926, 0.14634049 -0.070011914 0.027996078, 0.14453956 -0.073658258 0.02799584, 0.14438194 -0.076198339 0.022242248, 0.14913809 -0.068721414 0.014996246, 0.14941765 -0.068111479 0.014996082, 0.14847171 -0.068414718 0.020796135, 0.14659759 -0.063843071 0.037816212, 0.14726672 -0.065964162 0.03199634, 0.14886978 -0.06226176 0.031996548, 0.1393642 -0.062355131 0.057996601, 0.14244159 -0.062710762 0.050834224, 0.14169425 -0.060845077 0.054434121, 0.14083797 -0.058950871 0.057996795, 0.1427305 -0.072075069 0.037815765, 0.1408017 -0.074916542 0.039257854, 0.14233863 -0.07411027 0.035639226, 0.1437854 -0.073243082 0.031995848, 0.14557153 -0.069625258 0.031996101, 0.14078541 -0.07109338 0.044996038, 0.13815472 -0.076079518 0.04499568, 0.13774031 -0.0741795 0.048657551, 0.14521518 -0.06692788 0.037816048, 0.14505237 -0.064765036 0.041419417, 0.13892645 -0.070154965 0.050833791, 0.13780819 -0.065722615 0.057996362, 0.13617083 -0.069051564 0.057996079, 0.13722086 -0.07223928 0.052280262, 0.14323619 -0.066016197 0.044996247, 0.14341083 -0.065636039 0.044996306, 0.14134493 -0.065144986 0.050833985, 0.12960657 -0.066088021 0.072020799, 0.12800761 -0.069134623 0.07202059, 0.13136685 -0.068718433 0.067059115, 0.13595256 -0.059127867 0.067061141, 0.13767713 -0.061584651 0.06199649, 0.13912328 -0.05824393 0.061996669, 0.13269293 -0.066121489 0.067059234, 0.13454506 -0.06815654 0.061996251, 0.13615075 -0.064889401 0.061996415, 0.13113308 -0.063004553 0.072021082, 0.13479628 -0.061720312 0.067059487, 0.1325863 -0.059885979 0.07202132, 0.13192327 -0.088717461 -0.04100509, 0.13145542 -0.090232074 -0.039425895, 0.1297579 -0.090784788 -0.043005139, 0.1319665 -0.087543339 -0.04300487, 0.1333099 -0.086620063 -0.041004822, 0.13307059 -0.089608908 -0.035822093, 0.13409433 -0.084248126 -0.043004707, 0.13466316 -0.084500939 -0.041004717, 0.13438886 -0.087767422 -0.035509169, 0.13598274 -0.082360625 -0.041004702, 0.13613965 -0.080901116 -0.043004572, 0.13548395 -0.088466018 -0.030005038, 0.13634488 -0.089106977 -0.024502099, 0.1349951 -0.091647148 -0.022807315, 0.13528451 -0.090084612 -0.026413694, 0.13877179 -0.079731613 -0.03726846, 0.13843958 -0.08121568 -0.035533294, 0.13582081 -0.091431618 -0.019005165, 0.13434529 -0.09403044 -0.017005354, 0.13667223 -0.090615332 -0.017005026, 0.13729927 -0.089196146 -0.019004986, 0.14030083 -0.078921229 -0.033649385, 0.1406889 -0.079929858 -0.030004546, 0.13891225 -0.087142438 -0.017004952, 0.1387409 -0.086936712 -0.019004881, 0.14174056 -0.078049928 -0.030004337, 0.14014536 -0.084654063 -0.019004717, 0.14159252 -0.080596834 -0.024249017, 0.14052799 -0.082345188 -0.024522007, 0.1413759 -0.082128644 -0.020633876, 0.14106408 -0.08361432 -0.017004699, 0.13579834 -0.087982655 -0.030004904, 0.13666002 -0.086655945 -0.029960185, 0.14050531 -0.084055364 -0.019004628, 0.13702649 -0.090846688 -0.013005093, 0.13574454 -0.09325397 -0.0093994588, 0.13469073 -0.094274938 -0.013005331, 0.1370265 -0.090848088 0.01299499, 0.13469075 -0.094276398 0.012994841, 0.13633636 -0.092612565 0.0072235167, 0.13832107 -0.089620113 -0.0072358549, 0.13809042 -0.09031108 -5.0663948e-06, 0.13671416 -0.092171311 -0.0057895035, 0.13927501 -0.087360531 -0.013004944, 0.13847497 -0.089720219 -5.081296e-06, 0.13725549 -0.091492504 0.0036112964, 0.14143828 -0.084615082 -0.0072356164, 0.14143483 -0.083818763 -0.01300469, 0.14295721 -0.082022965 -0.0072354227, 0.13837644 -0.089656651 0.0057814568, 0.13927501 -0.087361932 0.012995139, 0.14159568 -0.084709555 -4.7236681e-06, 0.14379133 -0.080832899 -0.0036226213, 0.14453512 -0.07959041 -4.4703484e-06, 0.1433017 -0.081553757 0.0057818741, 0.1414949 -0.084649652 0.0057817101, 0.14241333 -0.082713127 0.0093912184, 0.14143474 -0.083820105 0.012995288, 0.13582079 -0.091433644 0.018994868, 0.1347784 -0.092559993 0.0206258, 0.13434535 -0.094032466 0.016994685, 0.13667223 -0.09061715 0.016994894, 0.13729922 -0.089198351 0.018994957, 0.13512172 -0.091031641 0.024241418, 0.13891223 -0.087144315 0.016995102, 0.13874096 -0.086938918 0.018995076, 0.13634481 -0.089109629 0.024492189, 0.14014536 -0.084656209 0.01899533, 0.14106405 -0.083616287 0.016995296, 0.13548395 -0.088469416 0.029994994, 0.13438886 -0.087771297 0.035499394, 0.13243437 -0.089870781 0.037256703, 0.13400027 -0.089205205 0.033638209, 0.14151722 -0.081217587 0.022795528, 0.14052796 -0.08234778 0.024512857, 0.13192332 -0.088722199 0.040995061, 0.12975788 -0.090789527 0.042994902, 0.13196653 -0.087548137 0.042995006, 0.13330996 -0.086624801 0.04099521, 0.1416766 -0.079658538 0.026402563, 0.14068887 -0.079933286 0.029995486, 0.13409427 -0.084252805 0.042995378, 0.13466316 -0.084505677 0.040995315, 0.14174056 -0.078053236 0.02999562, 0.13598272 -0.082365423 0.040995449, 0.13939399 -0.079418778 0.035815075, 0.13843957 -0.081219524 0.035524294, 0.13781154 -0.080193043 0.039418176, 0.13613971 -0.080906063 0.042995423, 0.13580632 -0.087991208 0.029950306, 0.13666004 -0.086659372 0.029950455, 0.13643068 -0.0816212 0.040995404, 0.13085277 -0.086821586 0.046995059, 0.1284167 -0.088047206 0.050657317, 0.12867205 -0.090021849 0.046994865, 0.12139265 -0.080183983 0.072020009, 0.11946258 -0.083032221 0.07201986, 0.1230519 -0.082987189 0.066747114, 0.12997216 -0.084186047 0.052833766, 0.12727919 -0.082668543 0.059995502, 0.12806025 -0.086020499 0.054280475, 0.13295391 -0.083568394 0.046995312, 0.12738252 -0.08250913 0.059995502, 0.12520158 -0.082864195 0.063393548, 0.13289422 -0.079493105 0.052833974, 0.13497409 -0.080264479 0.046995625, 0.13424197 -0.077195615 0.052834108, 0.12515637 -0.081067473 0.065413147, 0.12325478 -0.077290803 0.072020084, 0.13024642 -0.077909797 0.059995666, 0.13364625 -0.075223982 0.056433991, 0.13294411 -0.073211104 0.059995979, 0.12956168 -0.073822796 0.065413684, 0.1279701 -0.076548487 0.065413579, 0.12734461 -0.074120998 0.068739966, 0.12504788 -0.074354291 0.072020382, 0.13271901 -0.097676367 0.0077808946, 0.13177308 -0.099278837 0.0019944012, 0.13424003 -0.095916867 0.0019946843, 0.1316933 -0.09587726 0.024401605, 0.12957998 -0.097602874 0.027994588, 0.13131157 -0.09737435 0.0207946, 0.13198574 -0.094324112 0.027994812, 0.12688485 -0.1051439 0.0077806264, 0.12450124 -0.10782436 0.0092226565, 0.12558305 -0.10685274 0.0056104809, 0.12658808 -0.10581046 0.0019940138, 0.12922192 -0.10257757 0.0019941926, 0.12643972 -0.10477534 0.014994055, 0.12261032 -0.10923183 0.014993817, 0.12324972 -0.10785663 0.018624842, 0.13056523 -0.10053715 0.0077808052, 0.13165918 -0.098695368 0.011390418, 0.12587461 -0.10430741 0.020794123, 0.12709266 -0.1008203 0.027994454, 0.12452551 -0.10397455 0.02799426, 0.12380655 -0.10641593 0.022240549, 0.13010713 -0.1001848 0.014994472, 0.13051534 -0.09965238 0.014994472, 0.12952571 -0.099737465 0.020794481, 0.13147497 -0.096779764 -0.022249743, 0.12957999 -0.097599745 -0.028005525, 0.13198578 -0.094320893 -0.028005272, 0.13331459 -0.097034603 -0.0056234747, 0.13177299 -0.099278659 -0.0020056069, 0.1323052 -0.098090351 -0.0092364103, 0.13424002 -0.095916569 -0.0020054132, 0.12570485 -0.10416436 -0.022250235, 0.12359375 -0.1069977 -0.020808011, 0.12410094 -0.10551721 -0.024414524, 0.12452555 -0.1039713 -0.028005749, 0.12709263 -0.1008172 -0.02800566, 0.12643966 -0.10477361 -0.015005901, 0.12381525 -0.10837203 -0.011400267, 0.12261033 -0.10923022 -0.01500614, 0.12935102 -0.099600494 -0.022249997, 0.13103983 -0.098243445 -0.018634662, 0.12681836 -0.10508779 -0.009236753, 0.12922193 -0.10257727 -0.0020057708, 0.12658808 -0.10581028 -0.0020059496, 0.12494323 -0.10744339 -0.0077903569, 0.1301071 -0.10018307 -0.015005648, 0.13051531 -0.099650592 -0.015005648, 0.13049683 -0.10048363 -0.009236455, 0.12480316 -0.092041165 -0.052287295, 0.12199544 -0.091796815 -0.058005169, 0.12418977 -0.088805765 -0.058005065, 0.12970361 -0.094492257 -0.035650581, 0.12889647 -0.097076625 -0.03200537, 0.12804145 -0.095089674 -0.039269626, 0.13128316 -0.093823731 -0.03200525, 0.11940187 -0.098947048 -0.052287549, 0.1177474 -0.10176733 -0.050845683, 0.11761653 -0.099722177 -0.054444969, 0.11739207 -0.097614765 -0.058005497, 0.11972911 -0.094733685 -0.058005422, 0.1214365 -0.10063347 -0.045005605, 0.11955906 -0.10459322 -0.041427121, 0.11776223 -0.10490936 -0.045005962, 0.12286205 -0.094616413 -0.05228737, 0.12505668 -0.093995333 -0.048665047, 0.12280212 -0.10176551 -0.039270014, 0.12642914 -0.1002689 -0.032005623, 0.12388261 -0.10339838 -0.032005772, 0.1212815 -0.10419729 -0.037823424, 0.12495559 -0.096229076 -0.045005411, 0.12521046 -0.095897287 -0.045005366, 0.1263608 -0.097311676 -0.039269611, 0.11165197 -0.093271464 0.072019249, 0.10941518 -0.095885724 0.07201916, 0.11278277 -0.096227586 0.06705755, 0.11938751 -0.087897718 0.067059502, 0.12052213 -0.090676576 0.061995, 0.1226755 -0.087741584 0.061995119, 0.11465348 -0.093990773 0.067057639, 0.11600639 -0.096386909 0.061994508, 0.11829874 -0.093559116 0.061994731, 0.11382635 -0.090604931 0.072019428, 0.11768345 -0.090167791 0.067057908, 0.11593709 -0.087887824 0.072019681, 0.12871625 -0.094863564 0.037814468, 0.12889642 -0.097080261 0.031994522, 0.13128316 -0.093827367 0.03199476, 0.12199547 -0.091803312 0.057994902, 0.1249165 -0.092834741 0.050832585, 0.12460309 -0.090849668 0.054432496, 0.12418973 -0.088812232 0.057995021, 0.1231143 -0.10202855 0.037814051, 0.1206015 -0.10436964 0.03925623, 0.12227933 -0.10392562 0.035637543, 0.12388261 -0.10340199 0.031994224, 0.12642911 -0.10027242 0.031994402, 0.12143647 -0.10063866 0.044994295, 0.11778107 -0.10296988 0.048655868, 0.11776217 -0.1049144 0.044994146, 0.12668198 -0.097563297 0.037814304, 0.12700459 -0.095418572 0.041417673, 0.11983302 -0.099310189 0.050832137, 0.11972913 -0.094740212 0.057994679, 0.11739204 -0.097621202 0.057994559, 0.11770631 -0.10096264 0.052278802, 0.12495556 -0.096234202 0.044994548, 0.12521046 -0.095902354 0.044994578, 0.12330569 -0.094963819 0.050832316, -0.013198018 0.16319516 0.019009188, -0.011667594 0.16308239 0.020640165, -0.010246217 0.16366211 0.017009199, -0.014367059 0.16335174 0.01700905, -0.015867472 0.16295722 0.019009158, -0.013076708 0.16239741 0.024255767, -0.01847887 0.16293794 0.01700905, -0.018532783 0.16267565 0.019009158, -0.015341997 0.16215524 0.024506137, -0.021193087 0.16235051 0.019009143, -0.02257891 0.16242045 0.01700902, -0.015305981 0.16108239 0.030009046, -0.015169173 0.15979046 0.035513192, -0.012309387 0.15957135 0.037270725, -0.013805911 0.16038102 0.033652201, -0.024737045 0.1612789 0.022809073, -0.023236692 0.16120991 0.024526313, -0.012888998 0.15845522 0.041008979, -0.0099224895 0.1580511 0.043008789, -0.01383391 0.15775689 0.043008834, -0.015393272 0.15823159 0.041008964, -0.026055634 0.160431 0.026416034, -0.025225103 0.15982968 0.030009046, -0.017736703 0.15736586 0.043008842, -0.017893851 0.1579684 0.041008994, -0.027350605 0.15947968 0.030008882, -0.020389944 0.15766567 0.041008972, -0.024820223 0.15849608 0.035828389, -0.022817299 0.15887269 0.035537884, -0.023228422 0.15774095 0.039431594, -0.021628737 0.15687841 0.043008737, -0.015880808 0.16103649 0.029964343, -0.017454475 0.16087356 0.029964358, -0.021251053 0.15755194 0.041008823, -0.014407247 0.16377458 -0.012990788, -0.011726081 0.16427287 -0.0093848854, -0.010270551 0.16408607 -0.012990907, -0.014407337 0.1637733 0.01300922, -0.010270596 0.16408452 0.013009265, -0.012597322 0.16433418 0.0072380155, -0.016173601 0.16402155 -0.0072216839, -0.015489995 0.16427138 9.2238188e-06, -0.013177186 0.16435555 -0.0057751536, -0.018534809 0.16335902 -0.012990892, -0.016191632 0.16420364 9.2238188e-06, -0.01404576 0.16435492 0.0036256462, -0.022030488 0.16333818 -0.007221818, -0.02265045 0.16283932 -0.012990907, -0.025003865 0.16290939 -0.007221669, -0.016180143 0.16408652 0.0057956725, -0.018534839 0.16335756 0.01300922, -0.022054836 0.16351929 9.2089176e-06, -0.027889878 0.16262576 9.2238188e-06, -0.025586054 0.1628851 0.0057954788, -0.026454702 0.16281921 -0.0036090016, -0.022039086 0.16340268 0.0057956129, -0.024126083 0.16291311 0.0094050318, -0.02265045 0.16283777 0.01300925, -0.012888953 0.1584599 -0.040991083, -0.011413157 0.15903807 -0.039411932, -0.0099224895 0.15805593 -0.042991146, -0.01383397 0.15776178 -0.042991295, -0.015393302 0.15823624 -0.040991075, -0.01290752 0.15991232 -0.035808295, -0.017736733 0.15737081 -0.042991176, -0.017893806 0.15797296 -0.040991046, -0.015169278 0.15979451 -0.035495117, -0.020389885 0.15767023 -0.04099112, -0.021628708 0.15688324 -0.042991303, -0.015305981 0.1610859 -0.029990882, -0.015342012 0.16215807 -0.024488077, -0.012514532 0.16268644 -0.022793129, -0.013916418 0.16193888 -0.026399672, -0.02418448 0.15821123 -0.037255004, -0.022817135 0.15887648 -0.03551992, -0.013198018 0.16319728 -0.018990725, -0.010246113 0.16366383 -0.01699087, -0.014366999 0.1633538 -0.016990796, -0.015867412 0.16295928 -0.018990874, -0.025771484 0.15890104 -0.033636071, -0.025225058 0.15983316 -0.02999115, -0.0184789 0.16293985 -0.016990766, -0.018532842 0.16267791 -0.018990844, -0.027350575 0.15948302 -0.029991128, -0.021193102 0.16235277 -0.018990844, -0.025267407 0.16095495 -0.024235487, -0.023236766 0.16121271 -0.024508208, -0.023934737 0.16174024 -0.020620078, -0.02257891 0.16242242 -0.016990885, -0.015879884 0.16103032 -0.029990897, -0.017454401 0.16087687 -0.029946044, -0.021885619 0.16226077 -0.018990874, -0.012999952 0.14490396 -0.07201644, -0.010986641 0.14693755 -0.068734273, -0.0095696449 0.14517084 -0.072016455, -0.013707593 0.15643805 -0.046991229, -0.0098457932 0.15672851 -0.046991199, -0.012050733 0.15438572 -0.052831948, -0.014586806 0.14770219 -0.066745467, -0.014727026 0.15105498 -0.059991613, -0.012415588 0.14860263 -0.065407254, -0.016422898 0.14455593 -0.072016373, -0.014916122 0.15103647 -0.059991531, -0.013400063 0.15277627 -0.056431524, -0.019849479 0.14708751 -0.066745639, -0.019836694 0.1441271 -0.072016507, -0.022420079 0.1467177 -0.066745706, -0.015161857 0.15352413 -0.054274164, -0.017561093 0.15605253 -0.046991222, -0.020297647 0.15040779 -0.059991576, -0.025653243 0.14958739 -0.059991576, -0.023819 0.15242118 -0.054274194, -0.024036109 0.14820382 -0.063391618, -0.020632058 0.15288538 -0.054274194, -0.022628456 0.15405101 -0.050651759, -0.021403715 0.15557197 -0.046991184, 0.0049118996 0.14817539 -0.067054689, 0.0067440569 0.14532942 -0.072016455, 0.0033054948 0.1454483 -0.072016314, -0.0078905821 0.15061867 -0.061991557, -0.0042531788 0.15076518 -0.06199161, -0.0057186931 0.14814562 -0.067056015, 0.0019966662 0.14824244 -0.067056, -0.0006134063 0.15082401 -0.061991595, 0.0030267686 0.15079477 -0.061991654, -0.00013493001 0.14548588 -0.072016366, -0.0028813332 0.14822784 -0.067056, -0.0035753101 0.14544207 -0.072016373, -0.0058505237 0.15496624 -0.05227349, -0.0042907298 0.15261945 -0.057991482, -0.0079974085 0.15247011 -0.057991527, -0.0069903135 0.16032442 -0.035636172, -0.0044666082 0.16130453 -0.031990841, -0.0054867566 0.15939769 -0.039255232, -0.0084980875 0.16114247 -0.031990811, 0.0029162914 0.15504929 -0.052273303, 0.0061528534 0.15551403 -0.050831154, 0.0046356171 0.15413693 -0.054430842, 0.0031279773 0.15264764 -0.057991378, -0.00058162212 0.15267873 -0.0579914, 0.0029659867 0.15769082 -0.04499121, 0.0085999221 0.15748399 -0.04499115, 0.0072320849 0.15869159 -0.041412324, -0.0026268512 0.15505439 -0.052273244, -0.0044808835 0.15638268 -0.048650905, 0.00299941 0.15946367 -0.039255247, -0.0004324168 0.16136554 -0.031990811, 0.0036019385 0.16132605 -0.03199102, 0.0058486015 0.15979108 -0.037808493, -0.0026715845 0.15769616 -0.04499121, -0.003090024 0.15768859 -0.04499115, -0.0027016997 0.15946919 -0.039255232, -0.0063829124 0.16466331 0.0077957511, -0.0045399219 0.16492331 0.0020093024, -0.0087066144 0.164756 0.0020093173, -0.0071506053 0.16273823 0.02441597, -0.0044840425 0.16216147 0.028009057, -0.0057419538 0.16337338 0.020809129, -0.0085474551 0.16199803 0.028009117, 0.0030929744 0.16475779 0.0077956021, 0.0066747814 0.16456538 0.0092381388, 0.0052408278 0.16480583 0.0056257397, 0.0037995726 0.16494209 0.0020093024, -0.00037041306 0.16498542 0.0020093173, 0.003082186 0.16417938 0.015009314, 0.0074799061 0.16360632 0.018640086, 0.0089538991 0.163964 0.01500921, -0.0028033704 0.16476294 0.0077957809, -0.0049255043 0.16446978 0.011405259, 0.0030684173 0.16344544 0.020809203, -0.00041770935 0.16222289 0.028009236, 0.0036488324 0.16218233 0.028009057, 0.0060060918 0.16314298 0.022255689, -0.002793476 0.16418451 0.015009239, -0.0034642518 0.16417179 0.015009269, -0.002781108 0.16345066 0.020809218, -0.0063068569 0.16313446 -0.022235274, -0.0044840574 0.16216457 -0.027990937, -0.0085475147 0.16200104 -0.027990937, -0.0072554499 0.16472995 -0.0056087375, -0.0045399964 0.16492367 -0.0019907951, -0.0058004409 0.16459945 -0.009221524, -0.0087066889 0.16475636 -0.001990661, 0.0030643046 0.16322741 -0.022235215, 0.0065956265 0.16334322 -0.020793006, 0.00512214 0.16281703 -0.024399504, 0.0036489218 0.16218543 -0.027990907, -0.00041775405 0.16222605 -0.027990848, 0.003082186 0.16418102 -0.014990777, 0.0089539438 0.16396564 -0.014990911, 0.007531628 0.16437259 -0.011385038, -0.0027772933 0.16323245 -0.022235245, -0.0048913658 0.16370639 -0.018619969, 0.0030913651 0.16467252 -0.0092216283, -0.00037023425 0.16498563 -0.0019907653, 0.0037995428 0.16494247 -0.0019907653, 0.0061021447 0.16467482 -0.0077750236, -0.0027934909 0.16418618 -0.014990762, -0.0034642816 0.16417345 -0.014990762, -0.0028018057 0.16467768 -0.0092216283, -0.0060876459 0.15977722 0.037828654, -0.0044665635 0.16130072 0.032009125, -0.0084980428 0.16113874 0.032009184, -0.0042907447 0.15261289 0.058008634, -0.0053052455 0.15554053 0.050846487, -0.006662026 0.15405723 0.054446146, -0.0079973936 0.15246359 0.058008574, 0.0030070096 0.15986466 0.037828743, 0.0064039677 0.15935963 0.039270863, 0.005010888 0.16039488 0.035652548, 0.0036020428 0.1613223 0.032009006, -0.0004324764 0.16136208 0.03200911, 0.0029659718 0.15768573 0.045008928, 0.0085998625 0.15747896 0.045008838, 0.0070676208 0.15628099 0.048670575, -0.0027084649 0.15987003 0.037828803, -0.0045866221 0.15878481 0.041431919, 0.0029267818 0.15560341 0.050846472, -0.00058159232 0.15267205 0.058008537, 0.0031280816 0.15264118 0.058008611, 0.0055447817 0.15497085 0.052293062, -0.0026715994 0.15769103 0.045008823, -0.0030900538 0.15768352 0.045008868, -0.002636373 0.15560851 0.050846487, -0.049181603 0.15616655 0.019008763, -0.047664486 0.15639713 0.020639732, -0.0464077 0.1572786 0.017008699, -0.050356306 0.15605938 0.017008841, -0.051731408 0.15534073 0.019008674, -0.048886076 0.15541577 0.024255455, -0.054273009 0.15474075 0.017008767, -0.054267071 0.15447307 0.019008674, -0.05104062 0.15467572 0.024505779, -0.056788519 0.15356418 0.019008689, -0.05815509 0.15332407 0.017008588, -0.050766937 0.1536378 0.030008659, -0.050346203 0.15240884 0.035512902, -0.047509246 0.15283158 0.037270285, -0.049148329 0.15328789 0.033651762, -0.060005195 0.15173081 0.022808701, -0.05852703 0.15199733 0.024525881, -0.047825947 0.15161425 0.041008651, -0.044843882 0.15188047 0.043008462, -0.04859177 0.15072313 0.043008462, -0.050217733 0.150839 0.041008569, -0.061101861 0.15061063 0.026415415, -0.060158625 0.15020925 0.030008495, -0.052309848 0.14947358 0.04300838, -0.052596956 0.15002599 0.041008435, -0.06215284 0.14939511 0.030008428, -0.054963209 0.14917547 0.041008361, -0.059467167 0.14899924 0.035827816, -0.05759804 0.14981198 0.035537094, -0.0577472 0.14861733 0.039431058, -0.055995651 0.14813221 0.043008268, -0.051317029 0.15346512 0.029963911, -0.052814901 0.15295622 0.029963858, -0.055777363 0.14887297 0.041008398, -0.044917233 0.13837823 -0.072016992, -0.043406971 0.140809 -0.068734497, -0.041632302 0.13940173 -0.072016723, -0.048174091 0.14946559 -0.046991587, -0.04447373 0.15060821 -0.046991557, -0.046102129 0.1478335 -0.052832268, -0.047087111 0.14075333 -0.066745788, -0.047969908 0.14399078 -0.059991911, -0.045170717 0.14211431 -0.06540776, -0.048176892 0.13727719 -0.072016887, -0.048150226 0.14393058 -0.059991956, -0.047059357 0.14596415 -0.05643186, -0.052080996 0.13898283 -0.066745989, -0.051409714 0.13609952 -0.072016977, -0.054504886 0.13805038 -0.066746056, -0.0489434 0.14630133 -0.054274641, -0.051845118 0.14823228 -0.046991564, -0.053256892 0.14212012 -0.059992053, -0.058295585 0.14012861 -0.059992142, -0.0571381 0.14329952 -0.054274745, -0.05641108 0.13913962 -0.063392095, -0.05413425 0.14446107 -0.054274596, -0.056340046 0.14515328 -0.050652206, -0.055484623 0.14690864 -0.046991803, -0.050489232 0.15646264 -0.012991153, -0.04798609 0.15754494 -0.0093854517, -0.046525382 0.15768662 -0.01299113, -0.050489217 0.15646115 0.013008878, -0.046525516 0.15768522 0.013008982, -0.048849501 0.15741089 0.007237643, -0.052266262 0.15631023 -0.0072221756, -0.0516553 0.15670574 8.8661909e-06, -0.049419411 0.15730274 -0.0057755411, -0.054420628 0.15513885 -0.012991369, -0.052324302 0.15648371 8.7469816e-06, -0.050266147 0.15710866 0.0036252886, -0.057824157 0.15434057 -0.0072221458, -0.058317527 0.15371647 -0.012991361, -0.060627706 0.15326107 -0.0072222129, -0.052287154 0.15637201 0.0057952553, -0.054420657 0.15513745 0.01300884, -0.057888418 0.15451202 8.6128712e-06, -0.063378222 0.15234226 8.6054206e-06, -0.061189882 0.1531077 0.0057950541, -0.062021978 0.15285024 -0.0036094487, -0.057847135 0.15440151 0.0057950169, -0.0597727 0.15345985 0.0094045624, -0.058317527 0.15371495 0.013008691, -0.047825865 0.15161902 -0.040991515, -0.046515845 0.15251124 -0.039412305, -0.044843912 0.1518853 -0.042991504, -0.048591755 0.15072823 -0.042991571, -0.050217777 0.15084374 -0.04099153, -0.048167236 0.15303075 -0.035808615, -0.052309774 0.14947838 -0.042991593, -0.052597068 0.15003064 -0.040991649, -0.050346121 0.15241268 -0.035495706, -0.054963082 0.14917982 -0.040991664, -0.055995688 0.14813715 -0.042991713, -0.050766923 0.15364131 -0.029991433, -0.05104053 0.1546784 -0.024488382, -0.048401639 0.15582296 -0.022793502, -0.049601875 0.15478194 -0.02640003, -0.05878301 0.14886305 -0.037255391, -0.057598054 0.14981583 -0.035520531, -0.049181618 0.15616867 -0.018991187, -0.046407767 0.15728056 -0.016991243, -0.050356284 0.15606117 -0.016991109, -0.0517314 0.15534291 -0.018991165, -0.060483836 0.14918256 -0.033636414, -0.060158603 0.15021259 -0.029991552, -0.054272898 0.15474266 -0.016991392, -0.054267064 0.15447518 -0.018991195, -0.062152818 0.14939845 -0.029991575, -0.056788288 0.15356621 -0.018991396, -0.060449235 0.15129694 -0.024236053, -0.058527075 0.15200019 -0.024508834, -0.05932498 0.15235904 -0.020620674, -0.058155067 0.15332597 -0.016991459, -0.051314086 0.1534594 -0.029991336, -0.052814901 0.15295947 -0.02994667, -0.057443053 0.15332243 -0.018991418, -0.041489288 0.15441671 0.037828408, -0.040247917 0.15626279 0.032008886, -0.044142134 0.15520775 0.032008789, -0.03814353 0.14783177 0.058008246, -0.03978391 0.15046009 0.050846159, -0.040776655 0.14871225 0.05444584, -0.041724004 0.14686137 0.058008097, -0.032642163 0.15652582 0.037828527, -0.029217958 0.15678924 0.039270796, -0.030806512 0.15748852 0.035652302, -0.032386363 0.15807918 0.032009035, -0.03632836 0.15722004 0.032008827, -0.032197282 0.15439215 0.045008823, -0.027886093 0.15393552 0.048670329, -0.026658729 0.15544423 0.045008793, -0.038215511 0.15525913 0.037828475, -0.039805211 0.15378305 0.04143168, -0.031772204 0.15235332 0.050846294, -0.034540363 0.14871475 0.058008417, -0.030917071 0.14951017 0.058008373, -0.029079065 0.1523191 0.05229307, -0.037694715 0.15314281 0.045008473, -0.038100883 0.15304229 0.04500857, -0.037197076 0.15112039 0.050846145, -0.042863987 0.15911454 0.0077953637, -0.041125029 0.15977815 0.0020088404, -0.045149975 0.15868777 0.0020090044, -0.043184355 0.15706688 0.024415761, -0.040456243 0.15709785 0.028008834, -0.041952386 0.15799955 0.02080889, -0.044381626 0.15603441 0.028008841, -0.033646688 0.16131526 0.0077954531, -0.030111954 0.16192469 0.0092379153, -0.031563409 0.16183999 0.0056255609, -0.032998875 0.16165209 0.0020090789, -0.037073769 0.16076648 0.0020090789, -0.033528641 0.16074884 0.015009135, -0.029113725 0.16116861 0.018639937, -0.027756214 0.16184539 0.01500912, -0.039396338 0.16000825 0.0077952743, -0.041400172 0.15925011 0.011404857, -0.03337878 0.16003025 0.020809084, -0.036505632 0.15806264 0.028009102, -0.032531895 0.1589281 0.028008863, -0.030447446 0.16038901 0.022255614, -0.039258249 0.15944651 0.015009031, -0.039909251 0.15928477 0.015009001, -0.039082721 0.15873373 0.020808905, -0.042449296 0.1576409 -0.022235498, -0.04045631 0.15710112 -0.027991176, -0.044381507 0.15603748 -0.02799128, -0.043729253 0.15898541 -0.0056091398, -0.041124947 0.15977842 -0.0019909739, -0.042281598 0.1591818 -0.0092218369, -0.045149989 0.15868807 -0.0019911379, -0.033333786 0.15981695 -0.022235498, -0.029916815 0.16071567 -0.020793065, -0.031236179 0.15987465 -0.024399579, -0.032531835 0.15893114 -0.027991146, -0.036505595 0.15806583 -0.027991064, -0.033528693 0.16075066 -0.014991015, -0.029233485 0.16192728 -0.011385083, -0.027756155 0.16184703 -0.01499106, -0.03903003 0.15852198 -0.022235349, -0.041196577 0.15851355 -0.01862023, -0.03362897 0.16123167 -0.0092219114, -0.037073821 0.16076672 -0.0019909889, -0.032998838 0.16165233 -0.0019908696, -0.03069441 0.16190401 -0.0077752769, -0.039258175 0.15944815 -0.014990985, -0.039909236 0.15928641 -0.014991149, -0.039375737 0.15992546 -0.0092219114, -0.040186457 0.14977926 -0.052273721, -0.038143441 0.14783821 -0.057991758, -0.041723877 0.14686784 -0.057991691, -0.042490117 0.15474933 -0.035636567, -0.040247813 0.15626633 -0.031991169, -0.040817924 0.15418026 -0.039255582, -0.04414206 0.15521121 -0.031991176, -0.031657897 0.15181088 -0.052273504, -0.028605968 0.15298411 -0.050831415, -0.0297786 0.15130398 -0.054430909, -0.030917026 0.14951649 -0.057991743, -0.034540452 0.14872125 -0.057991624, -0.032197274 0.15439719 -0.044991314, -0.028260827 0.15632206 -0.041412421, -0.026658714 0.15544939 -0.044991247, -0.037063234 0.15058249 -0.052273475, -0.039166503 0.15146476 -0.0486513, -0.032559343 0.1561332 -0.039255433, -0.036328405 0.15722358 -0.031991191, -0.032386363 0.15808278 -0.031991117, -0.029854566 0.15708631 -0.037808731, -0.037694745 0.15314782 -0.044991493, -0.038100868 0.15304735 -0.044991337, -0.038118631 0.15486977 -0.039255567, -0.028182559 0.14555335 -0.067054763, -0.025762908 0.1431866 -0.072016478, -0.029141724 0.14253724 -0.072016604, -0.041207805 0.14508656 -0.061991833, -0.037694141 0.14603874 -0.061991833, -0.038539954 0.14315882 -0.067056365, -0.031039603 0.14497009 -0.067056194, -0.034158751 0.14690608 -0.061991803, -0.030603401 0.14768776 -0.061991766, -0.032504283 0.14180815 -0.072016716, -0.035792045 0.14387044 -0.067056298, -0.035848588 0.14099985 -0.072016731, 0.02269429 0.15735513 -0.040991157, 0.024261802 0.15759036 -0.039412096, 0.025496602 0.15630111 -0.042991281, 0.021617785 0.15688479 -0.042991161, 0.020202965 0.15769425 -0.040991098, 0.022999406 0.1587753 -0.035808176, 0.017725781 0.15737203 -0.042991161, 0.017706543 0.15799403 -0.040991127, 0.020768195 0.15916377 -0.035495266, 0.015205756 0.15825438 -0.040991127, 0.013822824 0.1577628 -0.042991146, 0.020922363 0.16045317 -0.029991135, 0.021125957 0.1615063 -0.024488002, 0.024000093 0.1613923 -0.022793159, 0.022467136 0.16097543 -0.026399747, 0.011626676 0.15962625 -0.037255019, 0.013107792 0.1599707 -0.035519958, 0.023447469 0.16204247 -0.018990934, 0.026429147 0.16184062 -0.016990975, 0.022342548 0.16245514 -0.01699087, 0.020792007 0.16240442 -0.018990725, 0.010232955 0.16065204 -0.03363584, 0.010973155 0.16143885 -0.029991001, 0.018241718 0.16296667 -0.016990796, 0.018130824 0.16272315 -0.018990815, 0.0088231415 0.16157067 -0.029990897, 0.015464872 0.16299817 -0.018990815, 0.011181667 0.16254193 -0.024235308, 0.013218746 0.16234139 -0.024508223, 0.012655675 0.16301119 -0.020619988, 0.01412937 0.16337445 -0.016990736, 0.020350516 0.16052678 -0.029991135, 0.018781304 0.16072729 -0.029946223, 0.014769301 0.16306257 -0.018990815, 0.019569308 0.14416361 -0.072016589, 0.021984696 0.14569843 -0.068734273, 0.022972882 0.14366063 -0.0720165, 0.021446198 0.15556625 -0.046991199, 0.025275752 0.15499008 -0.046991214, 0.022604749 0.15319663 -0.052832127, 0.018644959 0.14724505 -0.06674552, 0.019254312 0.15054506 -0.059991643, 0.020962 0.14763972 -0.065407366, 0.016154706 0.14458603 -0.07201653, 0.019065961 0.15056878 -0.059991643, 0.020931169 0.15192771 -0.056431517, 0.013377383 0.14781678 -0.066745505, 0.01273112 0.14492765 -0.072016507, 0.010789126 0.14802825 -0.066745669, 0.019379988 0.15304887 -0.054274216, 0.01760368 0.15604764 -0.046991259, 0.01367943 0.15115353 -0.059991613, 0.0082754791 0.15154552 -0.059991583, 0.010694355 0.15390006 -0.054274097, 0.0095442086 0.14983672 -0.063391477, 0.013904855 0.15364316 -0.054274186, 0.012217805 0.15522408 -0.05065158, 0.013750166 0.15643439 -0.046991184, 0.023447514 0.16204029 0.019009158, 0.024914369 0.1615898 0.020640001, 0.026429117 0.16183868 0.017009079, 0.022342563 0.16245329 0.017009139, 0.020791963 0.16240224 0.019009173, 0.023388252 0.16123542 0.024255663, 0.018241704 0.1629647 0.017009109, 0.018130854 0.16272098 0.019009173, 0.021125987 0.16150364 0.024506286, 0.015464917 0.1629959 0.019009158, 0.014129356 0.16337258 0.017009154, 0.020922348 0.16044953 0.030008912, 0.02076824 0.15915969 0.035513192, 0.023507789 0.15830967 0.03727065, 0.022228822 0.1594319 0.033652142, 0.011771336 0.16273972 0.022809163, 0.013218775 0.16233864 0.024526507, 0.022694349 0.15735042 0.041008845, 0.025496542 0.15629616 0.043008834, 0.02161774 0.15687981 0.043008879, 0.02020292 0.15768975 0.041008845, 0.010297269 0.16220656 0.026416197, 0.010973185 0.16143546 0.030009046, 0.017725781 0.15736708 0.043008834, 0.017706648 0.15798941 0.041008845, 0.0088231713 0.1615673 0.030009046, 0.015205756 0.15824974 0.041008949, 0.011071205 0.16004521 0.035828501, 0.013107851 0.15996668 0.035537824, 0.012455195 0.15895498 0.039431632, 0.013822824 0.15775785 0.043008819, 0.020351663 0.16053289 0.029964253, 0.018781319 0.16072392 0.029964358, 0.014340922 0.15833053 0.041009068, 0.022397131 0.16287434 -0.012990907, 0.025122017 0.16276354 -0.0093850493, 0.026499435 0.16225752 -0.012990892, 0.022397131 0.16287306 0.013009086, 0.026499361 0.16225618 0.013009086, 0.024286509 0.16301709 0.007237941, 0.020729959 0.16350818 -0.0072216541, 0.021452308 0.16359946 9.1344118e-06, 0.023725703 0.16316706 -0.0057751685, 0.01828061 0.1633876 -0.012990788, 0.02075316 0.16368967 9.1046095e-06, 0.022878751 0.16335964 0.0036257356, 0.014867976 0.16414499 -0.0072215497, 0.014152482 0.1637969 -0.012990773, 0.011873692 0.16438884 -0.0072216243, 0.020738348 0.16357291 0.0057956725, 0.018280566 0.1633862 0.01300922, 0.014884651 0.16432723 9.2089176e-06, 0.010439336 0.16462368 -0.0036087632, 0.0089970678 0.16475451 9.2536211e-06, 0.011300817 0.16449469 0.005795747, 0.014874086 0.16420996 0.0057956874, 0.012730643 0.16419691 0.0094050169, 0.014152497 0.16379541 0.01300922, -0.15380636 0.058078974 -0.012996629, -0.15309213 0.060710728 -0.0093907192, -0.15229204 0.061941236 -0.012996495, -0.15380628 0.058077544 0.013003282, -0.152292 0.061939716 0.013003387, -0.15352617 0.059951931 0.0072319955, -0.15479553 0.056594551 -0.0072277188, -0.15472418 0.057318628 3.1366944e-06, -0.15379649 0.059439093 -0.0057808459, -0.15522277 0.054179966 -0.012996972, -0.15496764 0.056657016 3.1515956e-06, -0.15417318 0.058655977 0.0036197901, -0.15672065 0.051021188 -0.0072279349, -0.1565402 0.050246418 -0.012997262, -0.15762475 0.048156112 -0.0072282031, -0.1548574 0.056616485 0.0057895929, -0.1552227 0.054178476 0.013003167, -0.15689507 0.051077545 2.9280782e-06, -0.15862185 0.045432776 2.5108457e-06, -0.15785612 0.047620684 0.0057891011, -0.15817305 0.046809822 -0.0036154911, -0.15678349 0.051040977 0.0057892874, -0.15724793 0.048948169 0.0093986392, -0.15654019 0.050244898 0.013002783, -0.14835769 0.057141811 -0.04099679, -0.14823836 0.058722258 -0.039417543, -0.14670657 0.059639394 -0.042996578, -0.14813851 0.055987686 -0.042996898, -0.14924279 0.0547885 -0.040996857, -0.14967437 0.057755113 -0.035813913, -0.14947964 0.052301586 -0.042997137, -0.15009062 0.05242148 -0.040997148, -0.15054998 0.055666238 -0.035501055, -0.1509008 0.050041169 -0.040997252, -0.15072897 0.048583567 -0.042997323, -0.15177283 0.05610311 -0.029996857, -0.15275474 0.05653584 -0.024493933, -0.15200415 0.059312403 -0.022798836, -0.1519385 0.057725191 -0.026405402, -0.15303487 0.04685697 -0.037261225, -0.15304118 0.048377424 -0.035526156, -0.15276116 0.058918387 -0.018996634, -0.15190092 0.061780185 -0.016996637, -0.15340954 0.057932675 -0.016996823, -0.15370491 0.056409776 -0.018996656, -0.15434507 0.045726299 -0.033642314, -0.15494797 0.046622753 -0.029997408, -0.15482062 0.054048568 -0.016997106, -0.15460771 0.053886265 -0.018996917, -0.15555489 0.044556022 -0.029997505, -0.15546909 0.051348448 -0.018997081, -0.15597722 0.047071546 -0.02424185, -0.15532845 0.04901278 -0.024514705, -0.15610686 0.048612595 -0.020626396, -0.1561334 0.050130069 -0.016997144, -0.15197188 0.055562079 -0.029996932, -0.15251675 0.05407685 -0.029952116, -0.15568693 0.050684601 -0.018997125, -0.15276112 0.058916181 0.019003343, -0.15199542 0.060245901 0.020634349, -0.15190089 0.061778188 0.017003298, -0.1534095 0.057930857 0.017003212, -0.15370497 0.05640772 0.019003168, -0.15199 0.058678985 0.024249956, -0.15482059 0.05404675 0.017002996, -0.15460779 0.053884238 0.019002955, -0.15275478 0.056533068 0.024500348, -0.15546915 0.051346332 0.019002959, -0.15613337 0.050128132 0.017002832, -0.15177277 0.056099653 0.030003145, -0.15054984 0.055662364 0.035507455, -0.14911161 0.058143795 0.037265059, -0.15049008 0.057146877 0.033646509, -0.1560414 0.047688127 0.022802759, -0.1553285 0.049010068 0.024520084, -0.14835769 0.057137311 0.041003227, -0.14670651 0.059634507 0.043003373, -0.14813849 0.055982858 0.043003127, -0.14924282 0.054783911 0.041003134, -0.15584986 0.046132296 0.026409652, -0.15494788 0.046619356 0.03000262, -0.14947978 0.052297026 0.043002889, -0.15009053 0.052416712 0.041002877, -0.15555492 0.044552535 0.030002512, -0.15090089 0.050036699 0.041002937, -0.15357095 0.046405435 0.035822079, -0.15304121 0.048373461 0.035531629, -0.15220031 0.047511935 0.039425302, -0.15072897 0.04857868 0.04300274, -0.15198088 0.055562049 0.029958367, -0.15251693 0.054073572 0.02995839, -0.1511718 0.049211323 0.041002773, -0.13619068 0.05116111 -0.07202173, -0.1371495 0.053857297 -0.068739414, -0.13494295 0.054367602 -0.072021469, -0.14689094 0.05552721 -0.046996817, -0.14547716 0.059132606 -0.04699669, -0.14432271 0.056129724 -0.05283758, -0.1394009 0.050945461 -0.066750899, -0.14248274 0.052273512 -0.059997052, -0.13926998 0.053292155 -0.065412797, -0.13736236 0.047926247 -0.072021812, -0.14254802 0.052095175 -0.059997037, -0.14345801 0.054215997 -0.056436919, -0.14113036 0.04593721 -0.06675119, -0.13845731 0.044664353 -0.072022073, -0.14191245 0.043460727 -0.066751443, -0.14489649 0.052953124 -0.054279797, -0.14821547 0.051888198 -0.046997152, -0.14431672 0.046973825 -0.059997261, -0.1459012 0.041792631 -0.059997655, -0.14765882 0.044674367 -0.054280289, -0.14395267 0.042649269 -0.063397452, -0.14669392 0.047747284 -0.054280102, -0.14861068 0.046454281 -0.050657898, -0.14944988 0.048217416 -0.046997219, -0.1313668 0.068718433 -0.067059085, -0.12800759 0.069134593 -0.072020635, -0.12960649 0.06608814 -0.072020933, -0.13912316 0.058243781 -0.06199681, -0.13767713 0.061584473 -0.061996706, -0.13595256 0.059127718 -0.067061096, -0.13269213 0.066120923 -0.067060724, -0.13615078 0.064889371 -0.061996415, -0.13454513 0.068156362 -0.061996207, -0.13113314 0.063004673 -0.07202106, -0.13479547 0.061719775 -0.067060828, -0.13258633 0.059885919 -0.072021253, -0.14215568 0.06196788 -0.05227863, -0.13936418 0.062355012 -0.057996593, -0.14083791 0.058950782 -0.057996728, -0.14747846 0.063265204 -0.035641655, -0.14726667 0.065964013 -0.031996332, -0.14599109 0.064217776 -0.039260581, -0.14886975 0.062261641 -0.031996623, -0.13842654 0.06990248 -0.052278049, -0.13744125 0.07302016 -0.050835952, -0.13685854 0.071055919 -0.054435521, -0.13617074 0.069051325 -0.057996117, -0.13780808 0.065722585 -0.057996385, -0.1407854 0.071093142 -0.044996038, -0.13815473 0.076079339 -0.044995748, -0.13983622 0.075370938 -0.041416854, -0.14083631 0.064910531 -0.052278489, -0.14283776 0.063816339 -0.048656225, -0.14236873 0.071892291 -0.039260119, -0.14557159 0.069625348 -0.031996034, -0.14378542 0.073242992 -0.0319959, -0.14142728 0.074601322 -0.037813343, -0.14323618 0.066016167 -0.044996388, -0.14341089 0.06563586 -0.044996239, -0.14484702 0.066758156 -0.039260492, -0.14971438 0.065099716 -0.022240728, -0.14804937 0.066321492 -0.027996272, -0.14966542 0.062589467 -0.027996421, -0.15156421 0.064936846 -0.0056143999, -0.15056071 0.067467362 -0.0019962713, -0.15081522 0.066191256 -0.0092271417, -0.15221769 0.063640624 -0.0019963458, -0.14573225 0.073583156 -0.022240229, -0.14430447 0.076815069 -0.020797826, -0.14446965 0.075259358 -0.024404332, -0.14453954 0.07365796 -0.027995817, -0.14634044 0.070011824 -0.027996071, -0.14658403 0.074012876 -0.014995903, -0.14384235 0.079209596 -0.014995575, -0.14482619 0.078104734 -0.011389785, -0.14827129 0.068322301 -0.022240587, -0.14961573 0.066622913 -0.018625312, -0.14702305 0.074234247 -0.0092266947, -0.14880748 0.071250886 -0.0019960105, -0.14695928 0.074989021 -0.0019957647, -0.14571902 0.076947719 -0.0077798739, -0.14913803 0.068721354 -0.014996126, -0.14941755 0.06811139 -0.014996283, -0.1495847 0.068926752 -0.0092271492, -0.1465975 0.063838691 0.037823323, -0.14726669 0.065960556 0.032003649, -0.14886972 0.062258035 0.032003373, -0.13936418 0.062348545 0.058003481, -0.14244163 0.0627051 0.050841209, -0.1416941 0.060838819 0.054440979, -0.14083785 0.058944136 0.058003273, -0.14273056 0.072070748 0.037823807, -0.14080167 0.074912041 0.039266184, -0.14233872 0.074106276 0.035647608, -0.14378531 0.073239356 0.032004271, -0.1455715 0.069621772 0.032003939, -0.14078528 0.071088046 0.045003995, -0.13774043 0.074173898 0.048665822, -0.1381547 0.076074362 0.045004286, -0.14521517 0.066923559 0.037823558, -0.14505228 0.064760268 0.041426711, -0.13892628 0.070149034 0.050841589, -0.13780804 0.065716028 0.05800372, -0.1361706 0.069044828 0.05800385, -0.13722074 0.07223326 0.052288447, -0.14323625 0.066011071 0.045003612, -0.14341089 0.065630883 0.045003533, -0.14134488 0.065139025 0.050841324, -0.15112635 0.065693706 0.0077901259, -0.15056083 0.067467213 0.0020038411, -0.15221778 0.063640445 0.0020036176, -0.14972594 0.064166278 0.024410542, -0.14804941 0.066318363 0.028003722, -0.14968684 0.065710962 0.020803642, -0.14966528 0.062586188 0.028003484, -0.14710018 0.074272245 0.0077906251, -0.14537275 0.077415645 0.0092331097, -0.14621136 0.076228112 0.0056207553, -0.14695928 0.074988842 0.0020041838, -0.14880762 0.071250916 0.002003938, -0.14658403 0.074011147 0.015004203, -0.14384231 0.079208046 0.015004426, -0.14415964 0.077724457 0.018635355, -0.149663 0.068962008 0.0077902302, -0.15031986 0.066922665 0.011399657, -0.14592907 0.073680162 0.020804211, -0.14634041 0.070008606 0.028003946, -0.14453954 0.07365483 0.028004125, -0.14438188 0.076195598 0.022250824, -0.14913806 0.068719506 0.015003972, -0.14941756 0.068109781 0.0150038, -0.14847173 0.068412215 0.020803757, -0.1213925 0.080183804 -0.072019987, -0.1217275 0.083025932 -0.068737827, -0.11946238 0.083032161 -0.072019942, -0.13085279 0.086821526 -0.046995163, -0.12867209 0.090021938 -0.046994776, -0.1282149 0.086837381 -0.052835763, -0.12456997 0.080687612 -0.066749237, -0.12727919 0.082668424 -0.059995435, -0.12392046 0.082946628 -0.065411068, -0.12325476 0.077290773 -0.07202027, -0.12738258 0.082509011 -0.059995361, -0.12779763 0.084779084 -0.056435168, -0.12737069 0.076189935 -0.066749617, -0.12504798 0.074354261 -0.072020479, -0.12868437 0.073949635 -0.066749737, -0.129481 0.083867818 -0.054278076, -0.13295391 0.083568245 -0.04699529, -0.13024631 0.077909648 -0.059995599, -0.13294421 0.073211044 -0.059995897, -0.13401639 0.076411784 -0.054278411, -0.13085398 0.07361266 -0.063395761, -0.13239202 0.079192668 -0.054278299, -0.13454831 0.07835868 -0.050656028, -0.13497412 0.08026436 -0.046995468, -0.13192338 0.088721931 -0.040995054, -0.13145527 0.090236217 -0.039415807, -0.12975787 0.090789437 -0.042995058, -0.13196646 0.087547958 -0.042995155, -0.13330987 0.086624503 -0.040995128, -0.13307059 0.089612961 -0.035812221, -0.13409424 0.084252745 -0.042995326, -0.13466313 0.084505349 -0.040995322, -0.13438889 0.087771058 -0.035499312, -0.13598254 0.082365066 -0.040995397, -0.13613978 0.080906093 -0.042995438, -0.13548388 0.088469326 -0.029995032, -0.13634473 0.08910948 -0.02449213, -0.13499501 0.091649532 -0.022797123, -0.13528445 0.090087473 -0.026403598, -0.13877165 0.079735637 -0.03725931, -0.13843957 0.081219345 -0.035524212, -0.13582072 0.091433585 -0.018994853, -0.13434532 0.094032347 -0.016994804, -0.13667221 0.090616971 -0.016995035, -0.13729914 0.089198053 -0.018995024, -0.14030077 0.078924984 -0.033640459, -0.14068876 0.079932988 -0.029995523, -0.13891222 0.087144345 -0.016995035, -0.13874072 0.086938649 -0.018995106, -0.14174044 0.078053057 -0.029995658, -0.14014536 0.084656239 -0.018995114, -0.14159247 0.080599397 -0.024239846, -0.14052802 0.08234778 -0.024512775, -0.14137596 0.08213079 -0.02062469, -0.14106396 0.083616138 -0.016995393, -0.13579825 0.087986082 -0.029995099, -0.13666002 0.086659312 -0.029950313, -0.14050522 0.08405742 -0.018995196, -0.13582084 0.091431528 0.019005172, -0.13477835 0.092557549 0.020636201, -0.13434541 0.094030499 0.017005272, -0.13667223 0.090615273 0.017004989, -0.1372993 0.089196056 0.01900503, -0.13512166 0.091028661 0.02425193, -0.13891214 0.087142348 0.017004907, -0.13874082 0.086936623 0.019004889, -0.13634467 0.089106768 0.024502084, -0.14014515 0.084653974 0.019004881, -0.14106411 0.08361429 0.017004639, -0.13548379 0.08846572 0.030005068, -0.13438874 0.087767124 0.035509117, -0.13243447 0.089866489 0.037266962, -0.13400012 0.089201212 0.033648156, -0.14151725 0.081214905 0.022804588, -0.14052801 0.082345068 0.024521947, -0.13192329 0.088717371 0.041005053, -0.12975785 0.090784609 0.043005019, -0.13196656 0.08754319 0.043004811, -0.13330993 0.086619914 0.041004933, -0.14167653 0.079655349 0.026411615, -0.14068887 0.079929709 0.030004553, -0.13409421 0.084247798 0.043004785, -0.13466319 0.08450076 0.041004851, -0.14174044 0.0780496 0.030004315, -0.13598266 0.082360625 0.04100452, -0.13939407 0.079414755 0.035823964, -0.13843952 0.081215382 0.035533395, -0.13781142 0.080188304 0.039427236, -0.13613969 0.080901116 0.043004632, -0.1358064 0.08798787 0.029960237, -0.13666013 0.086655885 0.029960081, -0.13643061 0.081616342 0.04100458, -0.1370264 0.090848029 -0.012994818, -0.13574451 0.093254864 -0.0093890205, -0.13469058 0.09427622 -0.012994729, -0.13702643 0.090846539 0.013005204, -0.13469058 0.094274938 0.013005354, -0.13633639 0.092611521 0.0072339848, -0.13832104 0.089620769 -0.0072258711, -0.13809025 0.090310961 5.0291419e-06, -0.13671404 0.092171788 -0.005779162, -0.13927504 0.087361902 -0.012995213, -0.13847491 0.08972019 5.1632524e-06, -0.13725537 0.091492057 0.0036216006, -0.14143831 0.084615737 -0.0072260648, -0.14143473 0.083820015 -0.012995332, -0.14295706 0.082023561 -0.0072262734, -0.13837644 0.089655936 0.005791463, -0.1392749 0.087360322 0.013004966, -0.14159556 0.084709436 4.8205256e-06, -0.14379123 0.080833107 -0.0036136433, -0.14453509 0.079590261 4.4554472e-06, -0.14330167 0.081553102 0.0057909787, -0.14149481 0.084648818 0.0057911873, -0.14241329 0.082711816 0.009400554, -0.1414347 0.083818763 0.013004683, -0.12871611 0.094859272 0.037825055, -0.12889636 0.097076565 0.032005467, -0.13128324 0.093823612 0.032005355, -0.12199542 0.091796666 0.058005173, -0.12491649 0.09282887 0.050842918, -0.12460309 0.090843379 0.054442782, -0.12418969 0.088805616 0.058004912, -0.1231143 0.10202438 0.037825465, -0.12060142 0.10436511 0.03926786, -0.12227921 0.10392147 0.035649166, -0.12388257 0.10339841 0.032005787, -0.12642896 0.10026875 0.032005616, -0.12143656 0.10063344 0.04500559, -0.11778107 0.10296428 0.048667468, -0.11776222 0.10490924 0.04500594, -0.12668192 0.097558916 0.037825234, -0.12700441 0.095413744 0.041428395, -0.11983302 0.099304348 0.050843254, -0.11972901 0.094733596 0.058005244, -0.11739206 0.097614557 0.058005422, -0.11770622 0.10095674 0.052289985, -0.12495548 0.096228898 0.045005336, -0.12521036 0.095897168 0.045005374, -0.12330568 0.094957978 0.050842933, -0.11278273 0.096227407 -0.067057565, -0.1094152 0.095885694 -0.072019234, -0.11165198 0.093271285 -0.072019324, -0.12267538 0.087741315 -0.061995074, -0.1205221 0.090676516 -0.061994947, -0.11938746 0.087897599 -0.067059495, -0.11465271 0.093990117 -0.067059122, -0.11829872 0.093558937 -0.061994851, -0.11600625 0.09638676 -0.061994642, -0.11382634 0.090604842 -0.072019443, -0.11768273 0.090167224 -0.067059249, -0.11593701 0.087887734 -0.072019674, -0.12480309 0.092046767 -0.052276947, -0.12199536 0.091803223 -0.05799479, -0.12418967 0.088812113 -0.057995006, -0.12970352 0.094496161 -0.035639822, -0.12889636 0.097080112 -0.031994537, -0.12804131 0.095093846 -0.039258823, -0.13128313 0.093827248 -0.031994693, -0.11940182 0.098952681 -0.052276447, -0.11774745 0.10177299 -0.050834231, -0.11761662 0.099728197 -0.054433808, -0.11739196 0.097621024 -0.0579945, -0.119729 0.094740033 -0.057994783, -0.12143649 0.10063851 -0.044994324, -0.11776218 0.10491443 -0.044994093, -0.11955896 0.10459766 -0.0414152, -0.12286191 0.094622016 -0.052276738, -0.12505659 0.094000667 -0.048654631, -0.12280201 0.10176983 -0.03925842, -0.12642893 0.10027239 -0.031994395, -0.1238827 0.10340196 -0.031994201, -0.12128156 0.10420144 -0.037811734, -0.12495553 0.096234173 -0.044994548, -0.12521033 0.095902264 -0.044994697, -0.12636076 0.097316116 -0.039258741, -0.13271904 0.097675443 0.0077918544, -0.13177301 0.099278569 0.0020056218, -0.13424009 0.09591639 0.0020052418, -0.13169318 0.095874399 0.024412364, -0.12957993 0.097599685 0.028005518, -0.13131168 0.097371876 0.020805523, -0.13198587 0.094320953 0.028005309, -0.12688464 0.10514283 0.0077923462, -0.12450114 0.10782316 0.0092348158, -0.12558319 0.10685214 0.005622454, -0.12658806 0.1058104 0.0020059645, -0.12922174 0.10257712 0.0020057186, -0.1264396 0.10477355 0.015005887, -0.12324975 0.10785437 0.018636994, -0.12261026 0.10923004 0.015006095, -0.13056512 0.10053614 0.0077920333, -0.13165925 0.098693997 0.011401467, -0.12587467 0.10430503 0.020805895, -0.12709263 0.10081702 0.028005503, -0.12452555 0.10397121 0.028005928, -0.12380651 0.10641325 0.022252537, -0.13010705 0.10018307 0.015005574, -0.13051537 0.099650592 0.015005648, -0.12952554 0.099734902 0.020805627, -0.13147499 0.096782118 -0.022238918, -0.12957993 0.097602785 -0.027994566, -0.13198578 0.094323963 -0.02799473, -0.13331448 0.09703505 -0.0056127161, -0.13177297 0.099278659 -0.0019944832, -0.13230519 0.098091245 -0.0092252716, -0.13424 0.095916867 -0.0019945726, -0.12570477 0.10416675 -0.022238605, -0.12359378 0.1069999 -0.020796053, -0.12410084 0.10552001 -0.024402738, -0.12452554 0.10397452 -0.027994148, -0.12709273 0.10082021 -0.027994305, -0.12643954 0.10477516 -0.014994167, -0.12261032 0.10923177 -0.014993928, -0.12381512 0.10837322 -0.01138816, -0.12935103 0.099602908 -0.022238851, -0.13103984 0.098245412 -0.01862368, -0.12681833 0.10508871 -0.009224847, -0.12922186 0.10257757 -0.0019944012, -0.12658817 0.10581043 -0.0019940585, -0.12494306 0.10744414 -0.0077782348, -0.13010702 0.10018459 -0.014994338, -0.13051525 0.099652261 -0.014994465, -0.13049681 0.10048446 -0.0092252344, -0.07458213 0.12491378 -0.072017595, -0.0736508 0.12761968 -0.068735227, -0.071607366 0.12664273 -0.072017536, -0.080224894 0.13499856 -0.046992391, -0.076871678 0.13693586 -0.046992391, -0.077841558 0.13386837 -0.05283317, -0.077226311 0.12674648 -0.066746593, -0.07880754 0.12970641 -0.059992746, -0.075660855 0.12849966 -0.065408461, -0.077515297 0.12311521 -0.072017647, -0.078969844 0.12960762 -0.059992626, -0.078358918 0.13183311 -0.056432731, -0.081701003 0.12390926 -0.066746823, -0.08040493 0.12124762 -0.072017774, -0.083856575 0.12246066 -0.066746987, -0.080270767 0.13174245 -0.054275356, -0.083529569 0.13297918 -0.046992548, -0.083545566 0.12670621 -0.059992813, -0.088015005 0.12364346 -0.059992969, -0.087592065 0.12699246 -0.054275639, -0.085957542 0.12309858 -0.063392997, -0.084921971 0.12879315 -0.054275624, -0.087226637 0.12897727 -0.050653242, -0.086783282 0.13087896 -0.046992645, -0.080364749 0.13717538 -0.040992334, -0.079286143 0.13833669 -0.039413057, -0.077516824 0.13809842 -0.042992301, -0.080913149 0.13613641 -0.042992286, -0.082524225 0.1358873 -0.040992342, -0.081011832 0.13847587 -0.035809472, -0.084259883 0.13409057 -0.042992577, -0.084662735 0.13456509 -0.040992469, -0.082998522 0.13738844 -0.035496466, -0.086780243 0.13320944 -0.040992521, -0.087554961 0.13196272 -0.042992659, -0.083682053 0.13849244 -0.029992118, -0.084179804 0.13944289 -0.024489261, -0.081861593 0.14114559 -0.022794314, -0.08280015 0.13986397 -0.026400894, -0.090433843 0.13205037 -0.037256449, -0.08949066 0.13324299 -0.03552141, -0.082699254 0.14130944 -0.018992051, -0.080242194 0.14301062 -0.016991965, -0.08382038 0.14094305 -0.016992033, -0.085001193 0.1399368 -0.018992059, -0.09216316 0.13198322 -0.033637457, -0.092075281 0.13305998 -0.029992566, -0.087345377 0.13878608 -0.016992167, -0.087280251 0.13852656 -0.018992215, -0.093838565 0.13182247 -0.02999261, -0.089536086 0.13707942 -0.018992297, -0.092600204 0.13405237 -0.024236932, -0.090882562 0.13516557 -0.024509735, -0.091740519 0.13533819 -0.020621523, -0.090815 0.13654101 -0.016992398, -0.084175006 0.13819334 -0.029992327, -0.085527107 0.13737211 -0.029947624, -0.090120174 0.13669619 -0.018992268, -0.084039398 0.14130482 -0.012992136, -0.081839971 0.1429171 -0.0093862116, -0.08044742 0.14338025 -0.01299189, -0.08403936 0.14130345 0.013008073, -0.08044751 0.14337888 0.013008021, -0.08265204 0.14259437 0.0072368085, -0.085738003 0.14076084 -0.0072229877, -0.085230716 0.1412825 7.8603625e-06, -0.08318343 0.14236194 -0.0057763159, -0.087577753 0.13913956 -0.012992136, -0.085833445 0.14091715 8.0391765e-06, -0.083965868 0.14198443 0.0036243498, -0.090718284 0.13760388 -0.0072231963, -0.091060437 0.13688564 -0.012992278, -0.093211412 0.13592756 -0.0072232038, -0.085772462 0.14081654 0.0057943091, -0.087577745 0.13913816 0.013007775, -0.090819292 0.13775662 7.7933073e-06, -0.094479181 0.13521668 -0.003610447, -0.095688537 0.13441971 7.5772405e-06, -0.09372557 0.13565293 0.0057940707, -0.090754561 0.13765824 0.0057942122, -0.092422366 0.1363115 0.0094034672, -0.091060407 0.13688412 0.013007782, -0.082699254 0.14130729 0.019007944, -0.081271335 0.14186957 0.020638995, -0.080242172 0.14300868 0.017008081, -0.083820418 0.14094111 0.017007902, -0.085001208 0.13993466 0.019007854, -0.082243994 0.14064106 0.024254419, -0.087345444 0.1387842 0.017007738, -0.087280326 0.13852444 0.019007683, -0.084179662 0.13944009 0.024504922, -0.08953616 0.1370773 0.01900769, -0.09081506 0.13653913 0.017007597, -0.08368212 0.1384891 0.030007757, -0.082998559 0.13738444 0.035511948, -0.080326699 0.13842779 0.037269473, -0.082026266 0.13850805 0.033651039, -0.092264198 0.134574 0.022807658, -0.090882517 0.13516313 0.024524935, -0.080364726 0.13717076 0.041007802, -0.077516817 0.13809365 0.043007828, -0.080913067 0.13613153 0.043007642, -0.082524106 0.13588262 0.041007675, -0.093084209 0.13323802 0.026414432, -0.092075258 0.13305655 0.030007429, -0.08425989 0.13408592 0.043007508, -0.084662676 0.13456044 0.041007608, -0.093838558 0.13181916 0.030007362, -0.086780205 0.13320482 0.041007571, -0.09113194 0.13203081 0.035826914, -0.089490652 0.13323903 0.035536356, -0.089370504 0.13204119 0.039430246, -0.087554865 0.13195801 0.043007404, -0.084180064 0.13819835 0.029963039, -0.085527129 0.13736871 0.029963106, -0.087506741 0.13272873 0.041007422, -0.076463223 0.14424279 -0.022236265, -0.074399821 0.14415985 -0.027991898, -0.077990122 0.14224949 -0.027991951, -0.078010552 0.14526859 -0.0056099817, -0.07564804 0.14662126 -0.001991719, -0.076642819 0.14578235 -0.0092227235, -0.079329446 0.14466265 -0.0019919649, -0.068060532 0.14839262 -0.022236101, -0.064929128 0.15002897 -0.020793632, -0.066028275 0.14891568 -0.024400182, -0.067081518 0.14770752 -0.027991742, -0.070762858 0.14597946 -0.027991764, -0.068458296 0.14925939 -0.014991708, -0.064532518 0.1513623 -0.011385679, -0.063074455 0.151613 -0.014991581, -0.073325738 0.14586261 -0.022236064, -0.0754361 0.14537215 -0.018620975, -0.068663225 0.14970616 -0.0092224404, -0.071918242 0.14848632 -0.0019916147, -0.068142489 0.15025643 -0.0019916072, -0.065951847 0.15101454 -0.007775791, -0.073754176 0.14671475 -0.014991835, -0.074353069 0.14641216 -0.014991775, -0.073975265 0.14715376 -0.0092225969, -0.072507292 0.13708168 -0.052274458, -0.070083529 0.13564396 -0.057992421, -0.07335829 0.13390115 -0.057992533, -0.07585936 0.14141452 -0.035637319, -0.074010901 0.14339241 -0.031991966, -0.074102551 0.14123195 -0.03925629, -0.077572666 0.14149722 -0.031992197, -0.064644672 0.14096022 -0.052274138, -0.061930478 0.14278331 -0.050831899, -0.062699601 0.14088416 -0.054431565, -0.063411765 0.13888815 -0.057992294, -0.066767327 0.13730663 -0.057992317, -0.065746032 0.14336169 -0.044991963, -0.062336795 0.14611429 -0.041413024, -0.060580619 0.1456199 -0.044991814, -0.069641002 0.13855979 -0.052274197, -0.071887821 0.13895199 -0.048652023, -0.066485509 0.14497355 -0.039256088, -0.070402808 0.14519784 -0.031991802, -0.066750698 0.14691269 -0.031991735, -0.064060263 0.14650443 -0.03780935, -0.070827797 0.14092031 -0.044992097, -0.07120128 0.14073199 -0.044992119, -0.071624309 0.14250478 -0.039256185, -0.059863783 0.13563284 -0.067055315, -0.056978084 0.13386381 -0.072017163, -0.060127623 0.13247895 -0.072017156, -0.07245867 0.1322796 -0.061992683, -0.0692451 0.13398972 -0.061992481, -0.06942869 0.13099363 -0.067057036, -0.062519394 0.13442859 -0.067056865, -0.065991201 0.13562179 -0.061992414, -0.062698871 0.13717499 -0.061992273, -0.063243724 0.13101992 -0.072017163, -0.06690795 0.13229901 -0.067057014, -0.066324323 0.1294876 -0.072017245, -0.074810468 0.14131269 0.037827641, -0.074010909 0.14338881 0.032008104, -0.077572674 0.14149359 0.032007828, -0.070083581 0.13563752 0.058007605, -0.072267637 0.13783491 0.050845444, -0.072846554 0.13590989 0.054445095, -0.073358305 0.13389462 0.058007486, -0.066654399 0.14533764 0.037828006, -0.063374862 0.14635646 0.039270222, -0.065079138 0.14668483 0.035651617, -0.066750787 0.14690924 0.032008342, -0.070402816 0.14519441 0.032008216, -0.065746143 0.14335659 0.045007899, -0.061441235 0.1438705 0.048669748, -0.060580462 0.14561474 0.045008235, -0.071806297 0.14286265 0.037827827, -0.073027678 0.14106983 0.04143092, -0.064877875 0.14146334 0.05084569, -0.066767335 0.13729998 0.058007695, -0.063411683 0.13888159 0.058007762, -0.062244833 0.14202926 0.052292533, -0.070827655 0.1409153 0.045007907, -0.071201332 0.14072692 0.045007862, -0.06989257 0.13905433 0.050845504, -0.077195592 0.14558718 0.007794477, -0.075648047 0.14662108 0.0020082518, -0.079329282 0.14466217 0.0020079985, -0.077052549 0.14351937 0.024414949, -0.074399896 0.14415661 0.028008141, -0.076059088 0.14470294 0.02080822, -0.077990085 0.14224631 0.028008021, -0.068699233 0.14978367 0.0077947453, -0.065388724 0.15116429 0.0092373118, -0.066784896 0.15075871 0.0056248978, -0.068142526 0.15025622 0.0020083711, -0.071918085 0.1484859 0.0020083487, -0.068458274 0.14925772 0.015008397, -0.063074604 0.15161133 0.015008487, -0.064247467 0.15064943 0.018639326, -0.074013911 0.14723 0.007794641, -0.075798847 0.14604497 0.011404239, -0.068152286 0.14859053 0.020808391, -0.070762962 0.14597639 0.02800823, -0.067081444 0.14770433 0.028008208, -0.065374345 0.14959252 0.022254959, -0.073754214 0.14671302 0.015008233, -0.074353054 0.14641052 0.015008271, -0.073424675 0.1460571 0.020808227, -0.11206974 0.11936194 0.019006729, -0.11080291 0.12022793 0.020637751, -0.11005297 0.12156764 0.017006867, -0.11308151 0.11875564 0.017006658, -0.1140086 0.11751157 0.019006714, -0.11147773 0.11881387 0.024253115, -0.11603821 0.11586839 0.01700639, -0.11591668 0.11562961 0.019006483, -0.11309793 0.11721221 0.024503581, -0.11779404 0.11371678 0.019006431, -0.11892104 0.11290753 0.017006248, -0.11240111 0.1163958 0.030006453, -0.11148895 0.11547095 0.035510711, -0.10911637 0.11708277 0.037268363, -0.11079095 0.11678272 0.033649676, -0.11989686 0.11066937 0.022806279, -0.11868092 0.11155081 0.024523713, -0.10887361 0.11584857 0.041006707, -0.10630264 0.11738223 0.043006591, -0.10917705 0.11471334 0.04300645, -0.11069226 0.11411241 0.041006505, -0.12039912 0.10918429 0.026413128, -0.11937511 0.10923183 0.030006073, -0.11198474 0.11197439 0.043006293, -0.11248301 0.11234745 0.041006356, -0.1208187 0.10763308 0.030006081, -0.11424573 0.11055461 0.041006267, -0.11822732 0.10844162 0.035825647, -0.116896 0.10998484 0.035535052, -0.11651205 0.10884365 0.039428957, -0.1147235 0.10916653 0.043006249, -0.11282194 0.11600164 0.029961877, -0.1139505 0.11489281 0.029961683, -0.11484813 0.1099287 0.041006275, -0.11337541 0.1190615 -0.012993403, -0.11158998 0.12112269 -0.0093873069, -0.11033539 0.12188426 -0.012993142, -0.11337545 0.11906013 0.013006844, -0.11033541 0.12188268 0.013006806, -0.11231002 0.1206274 0.007235609, -0.11491051 0.11815318 -0.0072241724, -0.114532 0.1187745 6.6161156e-06, -0.11277628 0.12028256 -0.0057775676, -0.11634329 0.11616307 -0.01299341, -0.11503838 0.11828417 6.6459179e-06, -0.11345522 0.1197404 0.0036231577, -0.11906337 0.11396703 -0.007224381, -0.11923715 0.1131908 -0.012993641, -0.12112098 0.11177811 -0.0072246641, -0.11495666 0.1181998 0.0057929382, -0.11634324 0.11616164 0.01300665, -0.11919595 0.1140936 6.4224005e-06, -0.1232006 0.10975686 6.1541796e-06, -0.12156138 0.11139581 0.0057926625, -0.12219901 0.11080304 -0.0036119223, -0.11911111 0.11401209 0.0057928711, -0.12043749 0.11232805 0.0094023198, -0.11923716 0.11318943 0.013006367, -0.10887376 0.11585328 -0.04099343, -0.1080805 0.11722547 -0.039414398, -0.10630248 0.11738706 -0.042993434, -0.10917699 0.11471835 -0.042993523, -0.11069219 0.11411694 -0.040993564, -0.10979397 0.11697713 -0.035810605, -0.11198477 0.11197922 -0.042993777, -0.11248301 0.1123521 -0.040993735, -0.11148878 0.11547479 -0.035497777, -0.11424585 0.11055914 -0.040993795, -0.11472353 0.10917136 -0.042994, -0.11240096 0.11639914 -0.029993564, -0.11309791 0.11721489 -0.024490505, -0.11121678 0.11939099 -0.022795491, -0.11184666 0.11793256 -0.026402183, -0.11754996 0.10861611 -0.037257783, -0.11689598 0.10998881 -0.035522722, -0.11206989 0.11936423 -0.018993244, -0.11005299 0.12156942 -0.016993172, -0.11308151 0.11875755 -0.016993254, -0.11400855 0.11751375 -0.018993393, -0.11922092 0.10816604 -0.033638984, -0.11937509 0.1092352 -0.029993884, -0.11603804 0.11587021 -0.016993508, -0.11591686 0.11563191 -0.018993519, -0.12081869 0.10763642 -0.029993974, -0.11779401 0.11371893 -0.018993653, -0.12010756 0.11008593 -0.024238169, -0.11868077 0.11155349 -0.024511039, -0.11955564 0.11153078 -0.020623013, -0.11892103 0.11290929 -0.016993575, -0.11281513 0.11599791 -0.029993527, -0.11395044 0.11489627 -0.029948786, -0.1182782 0.11321545 -0.018993661, -0.10050735 0.10518602 -0.072018616, -0.10020143 0.10803103 -0.068736434, -0.097991854 0.10753331 -0.072018623, -0.10825292 0.11376223 -0.046993546, -0.10541487 0.11639708 -0.046993412, -0.10567788 0.11319059 -0.052834384, -0.10349286 0.10638425 -0.066747934, -0.10569319 0.10891819 -0.059993848, -0.10235684 0.10844198 -0.06540966, -0.10296655 0.10277984 -0.072018936, -0.10582955 0.10878572 -0.059993863, -0.10572907 0.11109123 -0.056433804, -0.10722423 0.10262239 -0.066748008, -0.10536819 0.10031593 -0.072018914, -0.10900345 0.10073063 -0.066748187, -0.10757296 0.11057743 -0.0542766, -0.11102527 0.11105824 -0.046993688, -0.10964496 0.10493886 -0.059994042, -0.11332073 0.10095838 -0.059994496, -0.11365375 0.10431737 -0.054276928, -0.11119361 0.10088497 -0.063394189, -0.11145126 0.10666728 -0.054276809, -0.11373916 0.10633385 -0.050654382, -0.11373005 0.10828653 -0.046993963, -0.10119222 0.11751047 -0.052275628, -0.098509297 0.11664802 -0.057993434, -0.10131422 0.11422029 -0.057993554, -0.10542453 0.12098867 -0.035638377, -0.10406273 0.12332839 -0.031993158, -0.10367122 0.12120172 -0.039257415, -0.10711352 0.1206882 -0.031993255, -0.094389684 0.12304124 -0.052275077, -0.092149198 0.12542269 -0.050832875, -0.092476644 0.12340009 -0.054432482, -0.092726693 0.12129563 -0.057993121, -0.095646322 0.11900717 -0.057993263, -0.095998079 0.12513736 -0.044993065, -0.093286686 0.12857968 -0.041414, -0.091464564 0.12848854 -0.044992737, -0.098726764 0.11958918 -0.052275322, -0.1010046 0.11947173 -0.048653111, -0.097077638 0.12654424 -0.039257139, -0.10094684 0.1258916 -0.031992927, -0.097767927 0.12837607 -0.03199292, -0.095054276 0.12857667 -0.037810303, -0.10040907 0.1216265 -0.044993229, -0.10073137 0.12135977 -0.044993192, -0.10153823 0.12299398 -0.039257437, -0.088543229 0.1189115 -0.067056231, -0.085336246 0.11782876 -0.072017938, -0.088098601 0.11577785 -0.072018012, -0.10007615 0.11283946 -0.061993681, -0.097323716 0.11522183 -0.061993524, -0.096835904 0.1122601 -0.067058139, -0.090864278 0.11714634 -0.067057826, -0.094514668 0.11753732 -0.061993428, -0.091650479 0.11978409 -0.061993271, -0.090811945 0.11366209 -0.072018243, -0.094668992 0.11409357 -0.067058086, -0.093474261 0.11148277 -0.072018325, -0.1066428 0.1236116 -0.022237405, -0.10461275 0.12399 -0.027992949, -0.10768785 0.12132859 -0.027993187, -0.10837992 0.12426743 -0.0056110322, -0.1063776 0.12611189 -0.0019930229, -0.10716078 0.12507263 -0.0092237741, -0.10953086 0.1233831 -0.0019930378, -0.099373996 0.129527 -0.022237122, -0.096685484 0.13181931 -0.020794705, -0.097509407 0.13048935 -0.024401255, -0.098267205 0.12907708 -0.02799277, -0.10147179 0.12657323 -0.027992822, -0.099954918 0.13028374 -0.014992796, -0.095230058 0.13377637 -0.014992446, -0.096595749 0.13320759 -0.01138676, -0.10394447 0.12588894 -0.022237286, -0.10589293 0.12494117 -0.018622234, -0.10025448 0.13067368 -0.0092235282, -0.10315639 0.12876022 -0.0019927919, -0.099869184 0.13132605 -0.001992628, -0.097901948 0.13255265 -0.0077769458, -0.10455193 0.12662441 -0.01499293, -0.10506842 0.12619621 -0.01499296, -0.10486495 0.12700328 -0.0092236549, -0.10765654 0.1247592 0.0077934414, -0.10637756 0.12611157 0.0020071641, -0.10953081 0.1233829 0.0020068362, -0.10705701 0.12277526 0.024413705, -0.10461278 0.12398681 0.028007075, -0.10635178 0.12415025 0.020806976, -0.10768797 0.12132543 0.02800677, -0.10030695 0.13074133 0.0077937692, -0.097386651 0.132824 0.0092362985, -0.098657489 0.13211784 0.005623877, -0.099869221 0.13132599 0.0020074248, -0.10315645 0.12875995 0.0020071492, -0.099955037 0.13028219 0.015007272, -0.095229968 0.1337747 0.015007637, -0.096159481 0.1325759 0.018638268, -0.10492005 0.12706876 0.0077934712, -0.10639661 0.12551653 0.011403032, -0.09950836 0.12969953 0.020807378, -0.10147185 0.12657022 0.028007098, -0.098267287 0.12907395 0.028007343, -0.097023018 0.13129473 0.02225402, -0.104552 0.12662262 0.015007116, -0.1050684 0.1261946 0.015007049, -0.10408493 0.12605667 0.02080705, -0.10438041 0.12112293 0.037826613, -0.1040627 0.12332478 0.032006986, -0.10711355 0.12068465 0.032006867, -0.0985092 0.11664155 0.05800657, -0.10112754 0.11829802 0.050844453, -0.10126366 0.11629248 0.054444149, -0.10131419 0.11421373 0.058006421, -0.097324505 0.12686169 0.037826993, -0.09435375 0.12858468 0.039269254, -0.096088305 0.12852567 0.035650663, -0.097767934 0.12837237 0.032007247, -0.10094686 0.1258879 0.032007165, -0.095998146 0.12513244 0.045007028, -0.091464601 0.12848341 0.045007281, -0.091915555 0.12659138 0.04866869, -0.10179634 0.12330222 0.037826553, -0.10258822 0.1212827 0.041429818, -0.094730578 0.12347984 0.050844617, -0.095646255 0.11900049 0.058006667, -0.092726745 0.12128934 0.058006816, -0.092289485 0.12461752 0.052291416, -0.10040913 0.12162143 0.045006849, -0.10073145 0.12135464 0.045006923, -0.099083319 0.12001517 0.050844446, -0.14946303 -0.048176855 0.046997298, -0.14890245 -0.045508325 0.05065966, -0.15060556 -0.044476569 0.046997502, -0.13837408 -0.044921309 0.072022036, -0.13939762 -0.041636437 0.07202211, -0.14160065 -0.04447037 0.066749267, -0.14685316 -0.049132019 0.052835658, -0.14398742 -0.047973454 0.059997384, -0.14709523 -0.046493679 0.05428274, -0.14822955 -0.051847905 0.046997115, -0.14392737 -0.048153698 0.059997384, -0.14284495 -0.046227336 0.063395612, -0.14500612 -0.054342628 0.052835405, -0.14690609 -0.055487394 0.046996899, -0.14404991 -0.056828886 0.052835282, -0.14141205 -0.047312438 0.065415122, -0.13727334 -0.048180968 0.072021872, -0.1421169 -0.053260326 0.059997063, -0.14213696 -0.05759275 0.056434929, -0.14012535 -0.058299094 0.059996657, -0.13849443 -0.055273682 0.065414734, -0.13963316 -0.052329808 0.065414816, -0.13734503 -0.053354621 0.068741202, -0.13609551 -0.051413804 0.072021738, -0.15616778 -0.049182773 0.018997476, -0.1563983 -0.047665834 0.020628233, -0.15727971 -0.046408772 0.016997397, -0.15606037 -0.050357372 0.016997159, -0.15534167 -0.051732481 0.01899711, -0.15541716 -0.048887372 0.024243999, -0.15474175 -0.054273903 0.016996924, -0.1544742 -0.054268241 0.018996857, -0.15467712 -0.05104211 0.024494171, -0.15356523 -0.056789577 0.018996757, -0.15332502 -0.058156103 0.016996719, -0.15363961 -0.050768733 0.029997069, -0.15241088 -0.050348282 0.035501558, -0.15283357 -0.047511309 0.037259117, -0.15328965 -0.049150318 0.033640537, -0.15173207 -0.06000641 0.022796739, -0.1519988 -0.058528543 0.024513986, -0.15161672 -0.047828317 0.040997449, -0.15188277 -0.044846475 0.042997517, -0.15072571 -0.048594266 0.042997297, -0.15084131 -0.050220191 0.040997192, -0.15061221 -0.061103582 0.026403617, -0.15021099 -0.060160339 0.029996622, -0.14947602 -0.052312225 0.042997044, -0.15002833 -0.05259937 0.040997062, -0.14939693 -0.06215471 0.029996429, -0.14917774 -0.054965466 0.04099685, -0.14900124 -0.059469223 0.035816126, -0.14981405 -0.057600141 0.03552565, -0.14861959 -0.057749629 0.039419457, -0.14813465 -0.055998176 0.042996895, -0.15346679 -0.051318824 0.02995247, -0.1529578 -0.052816749 0.029952485, -0.14887521 -0.055779755 0.040996827, -0.15646204 -0.050488442 -0.013002828, -0.15754449 -0.047985792 -0.0093968548, -0.15768592 -0.046524823 -0.013002668, -0.15646195 -0.050489962 0.012997221, -0.15768583 -0.046526402 0.012997322, -0.15741128 -0.04885 0.0072260387, -0.15630981 -0.052266002 -0.0072338097, -0.15670584 -0.051655561 -2.8871e-06, -0.15730236 -0.049419224 -0.0057870857, -0.15513818 -0.054419994 -0.01300307, -0.15648362 -0.052324533 -2.9057264e-06, -0.15710883 -0.050266415 0.0036135055, -0.15434013 -0.057823718 -0.0072340183, -0.1537158 -0.058316767 -0.013003323, -0.15326081 -0.060627311 -0.0072342567, -0.15637235 -0.052287668 0.0057834014, -0.15513818 -0.054421514 0.012996972, -0.15451182 -0.057888508 -3.1292439e-06, -0.15234233 -0.063378364 -3.5203993e-06, -0.15310808 -0.061190426 0.0057830364, -0.15285006 -0.062021971 -0.0036215708, -0.15440211 -0.057847559 0.0057832785, -0.15346047 -0.059773386 0.0093925893, -0.15371577 -0.058318406 0.012996659, -0.15161669 -0.047823727 -0.041002616, -0.15250899 -0.046513706 -0.03942354, -0.15188289 -0.044841588 -0.043002523, -0.15072575 -0.048589379 -0.043002702, -0.15084133 -0.050215453 -0.041002929, -0.15302885 -0.048165292 -0.03581997, -0.14947599 -0.052307487 -0.043002985, -0.15002835 -0.052594841 -0.04100287, -0.15241091 -0.050344288 -0.035507038, -0.14917772 -0.054960966 -0.041003086, -0.14813462 -0.055993348 -0.043003157, -0.15363953 -0.050765306 -0.030002899, -0.15467715 -0.051039308 -0.024500005, -0.15582171 -0.048400462 -0.022804998, -0.15478046 -0.049600542 -0.026411533, -0.14886096 -0.058781028 -0.037267148, -0.14981404 -0.057596147 -0.035532095, -0.15616767 -0.049180657 -0.019002769, -0.15727969 -0.046406835 -0.017002687, -0.15606034 -0.050355613 -0.017002754, -0.15534179 -0.051730335 -0.019002974, -0.14918058 -0.060481995 -0.033648379, -0.15021113 -0.060156971 -0.030003384, -0.15474182 -0.054271936 -0.017003138, -0.1544742 -0.054266125 -0.019002963, -0.14939694 -0.062151194 -0.030003563, -0.15356526 -0.056787401 -0.019003186, -0.15129557 -0.06044811 -0.024247959, -0.15199882 -0.058525711 -0.024520598, -0.15235808 -0.059323967 -0.020632498, -0.15332501 -0.058154196 -0.017003264, -0.15345767 -0.051312447 -0.030002914, -0.15295777 -0.052813441 -0.029958181, -0.15332162 -0.057442069 -0.019003224, -0.15441871 -0.041491449 0.037817441, -0.15626451 -0.040249705 0.031997759, -0.15520942 -0.044143885 0.031997595, -0.14783499 -0.038146794 0.05799792, -0.15046301 -0.039786816 0.050835423, -0.14871538 -0.040779859 0.054435167, -0.14686459 -0.041727364 0.057997663, -0.15652791 -0.032644331 0.037817884, -0.15679131 -0.029220313 0.039260261, -0.15749055 -0.030808508 0.0356417, -0.15808092 -0.03238821 0.031998258, -0.15722188 -0.036330223 0.031997994, -0.15439469 -0.032200009 0.044998087, -0.15544681 -0.026661336 0.044998452, -0.15393808 -0.027888775 0.0486601, -0.15526107 -0.038217783 0.037817661, -0.15378527 -0.039807618 0.041420694, -0.15235603 -0.031775028 0.050835878, -0.14871812 -0.034543902 0.057998132, -0.14951351 -0.030920386 0.057998206, -0.15232208 -0.029082119 0.052282859, -0.15314542 -0.037697434 0.04499789, -0.15304482 -0.038103551 0.044997875, -0.15112323 -0.037199944 0.050835531, -0.15911499 -0.042864501 0.0077840649, -0.15977846 -0.041125149 0.0019977614, -0.1586881 -0.045150101 0.0019974001, -0.15706819 -0.0431858 0.02440447, -0.15709938 -0.040457934 0.027997687, -0.15800089 -0.041953623 0.020797666, -0.15603606 -0.044383258 0.027997576, -0.16131575 -0.03364718 0.0077845119, -0.16192518 -0.030112535 0.009227138, -0.16184029 -0.031563699 0.0056146905, -0.16165224 -0.032998979 0.0019981377, -0.16076656 -0.03707397 0.0019978955, -0.16074969 -0.03352958 0.014998138, -0.16116977 -0.029114783 0.018629313, -0.16184622 -0.027757198 0.014998429, -0.16000871 -0.039396852 0.007784158, -0.15925069 -0.041400939 0.011393592, -0.16003141 -0.033380032 0.020798098, -0.15806416 -0.03650713 0.027997922, -0.15892966 -0.032533526 0.027998079, -0.16039054 -0.030448616 0.022244904, -0.15944719 -0.039258957 0.014997736, -0.15928559 -0.039910167 0.014997777, -0.15873489 -0.039084047 0.02079777, -0.14253335 -0.029145837 0.072022893, -0.14318253 -0.025767058 0.072023153, -0.14554968 -0.0281865 0.06706135, -0.14315505 -0.03854385 0.067062318, -0.14603554 -0.037697822 0.061997831, -0.14508311 -0.041211277 0.06199779, -0.14496714 -0.031043649 0.067061238, -0.14768429 -0.030606896 0.061998304, -0.14690259 -0.034162343 0.061998114, -0.1418042 -0.032508552 0.07202284, -0.14386746 -0.035796106 0.067060895, -0.1409958 -0.03585279 0.072022572, -0.14977624 -0.040183634 -0.052284457, -0.14783496 -0.038140267 -0.058002219, -0.14686462 -0.041720778 -0.05800242, -0.15474741 -0.042488128 -0.035647579, -0.15626448 -0.04024598 -0.032002307, -0.15417817 -0.040816009 -0.039266475, -0.15520948 -0.044140279 -0.032002375, -0.15180793 -0.031654984 -0.052283868, -0.15298143 -0.028603166 -0.050841451, -0.15130107 -0.02977562 -0.054441124, -0.14951339 -0.03091386 -0.058001816, -0.1487181 -0.034537345 -0.058001913, -0.15439478 -0.032194823 -0.04500176, -0.1554468 -0.0266563 -0.045001574, -0.15631974 -0.028258711 -0.041422777, -0.15057939 -0.03706041 -0.052284099, -0.1514622 -0.039163798 -0.048661999, -0.15613104 -0.032557219 -0.03926599, -0.15722185 -0.036326706 -0.032002032, -0.15808102 -0.032384783 -0.032001853, -0.15708417 -0.029852271 -0.037819192, -0.15314537 -0.037692398 -0.04500217, -0.15304494 -0.038098544 -0.045002192, -0.15486759 -0.038116604 -0.039266437, -0.15763974 -0.042448103 -0.022246793, -0.15709943 -0.040454805 -0.028002232, -0.15603603 -0.044380188 -0.028002538, -0.15898517 -0.043729186 -0.0056205653, -0.15977848 -0.04112497 -0.0020023212, -0.15918155 -0.042281121 -0.009233173, -0.15868801 -0.045149893 -0.0020025298, -0.15981564 -0.033332765 -0.022246256, -0.16071448 -0.029915839 -0.02080372, -0.15987331 -0.031235099 -0.024410315, -0.15892962 -0.032530457 -0.02800183, -0.15806428 -0.03650403 -0.028002046, -0.16074979 -0.033527941 -0.01500186, -0.16192661 -0.029232889 -0.011395838, -0.16184649 -0.02775532 -0.015001427, -0.15852085 -0.039028972 -0.022246517, -0.15851238 -0.041195661 -0.018631395, -0.16123132 -0.033628613 -0.0092327371, -0.16076656 -0.037073731 -0.0020020679, -0.16165213 -0.032998681 -0.0020019561, -0.16190366 -0.030694008 -0.0077859759, -0.15944719 -0.039257348 -0.015002172, -0.15928555 -0.039908558 -0.015002295, -0.15992492 -0.039375335 -0.0092331171, -0.13717297 -0.080362439 -0.041004546, -0.13833439 -0.079284012 -0.039425306, -0.13809612 -0.07751438 -0.043004341, -0.13613391 -0.080910742 -0.04300458, -0.13588493 -0.082521856 -0.041004658, -0.13847376 -0.081009805 -0.035821676, -0.13408841 -0.084257424 -0.043004669, -0.13456297 -0.084660441 -0.041004896, -0.13738647 -0.082996607 -0.035508849, -0.1332072 -0.086777925 -0.041004866, -0.1319605 -0.087552428 -0.043004915, -0.13849092 -0.083680362 -0.030004747, -0.13944143 -0.084178478 -0.024501875, -0.14114448 -0.081860512 -0.022806808, -0.13986246 -0.082798779 -0.026413284, -0.13204834 -0.090431869 -0.03726881, -0.133241 -0.089488834 -0.03553386, -0.14130847 -0.082698137 -0.019004494, -0.14300957 -0.080241352 -0.017004587, -0.14094222 -0.083819509 -0.01700478, -0.13993564 -0.085000128 -0.019004643, -0.13198157 -0.092161268 -0.033649966, -0.13305843 -0.092073679 -0.030005187, -0.13878509 -0.087344646 -0.017005019, -0.13852572 -0.08727929 -0.019004911, -0.1318208 -0.093836874 -0.030005299, -0.13707839 -0.089535058 -0.019004852, -0.13405107 -0.092598796 -0.024249583, -0.13516432 -0.090881228 -0.024522528, -0.13533708 -0.091739446 -0.020634353, -0.13654014 -0.090814143 -0.017005056, -0.13819185 -0.084173411 -0.030004859, -0.13737029 -0.085525483 -0.029959977, -0.13669512 -0.090119094 -0.019004978, -0.14130828 -0.082700312 0.01899527, -0.14187084 -0.081272662 0.020626508, -0.14300948 -0.080243319 0.016995434, -0.14094225 -0.083821446 0.016995288, -0.13993575 -0.085002184 0.018995211, -0.14064243 -0.08224532 0.024242006, -0.13878509 -0.087346584 0.016995028, -0.13852561 -0.087281406 0.018995151, -0.13944148 -0.084181339 0.024492338, -0.13707837 -0.089537174 0.018995013, -0.13654001 -0.090816051 0.016994912, -0.13849083 -0.083683848 0.029995378, -0.1373865 -0.0830006 0.035499737, -0.13842991 -0.080328882 0.037257243, -0.13850988 -0.082028151 0.03363869, -0.13457544 -0.092265576 0.022794914, -0.13516447 -0.09088397 0.024512254, -0.13717309 -0.080367088 0.040995531, -0.13809617 -0.077519298 0.042995572, -0.13613391 -0.0809156 0.042995505, -0.13588488 -0.082526445 0.040995378, -0.13323954 -0.093085885 0.026401833, -0.13305837 -0.092077196 0.029994778, -0.13408835 -0.084262282 0.042995211, -0.13456285 -0.08466509 0.04099521, -0.13182093 -0.093840152 0.029994678, -0.1332071 -0.086782575 0.04099521, -0.13203289 -0.091134161 0.035814349, -0.13324086 -0.089492947 0.035523858, -0.13204344 -0.089372694 0.039417699, -0.13196041 -0.087557316 0.042995207, -0.1381999 -0.084181696 0.029950526, -0.13737042 -0.085528821 0.029950414, -0.13273092 -0.087509125 0.040995084, -0.14130414 -0.084038675 -0.013004672, -0.14291655 -0.081839442 -0.0093986839, -0.14337943 -0.08044678 -0.013004508, -0.14130399 -0.084040105 0.012995269, -0.14337948 -0.08044821 0.012995567, -0.14259467 -0.082652509 0.0072240718, -0.14076036 -0.085737765 -0.0072356537, -0.14128245 -0.085230738 -4.7832727e-06, -0.14236161 -0.083183229 -0.0057889223, -0.13913879 -0.087577134 -0.013004985, -0.14091708 -0.08583346 -4.8354268e-06, -0.14198455 -0.083966136 0.0036118254, -0.13760349 -0.090717912 -0.0072359666, -0.13688487 -0.091059804 -0.013005078, -0.13592726 -0.093210995 -0.007236205, -0.14081685 -0.085772634 0.0057815351, -0.13913876 -0.087578654 0.012995061, -0.13775656 -0.090819329 -5.0961971e-06, -0.13441986 -0.095688701 -5.3793192e-06, -0.13565332 -0.093726039 0.0057812743, -0.13521662 -0.094479263 -0.0036234707, -0.1376586 -0.090754896 0.00578136, -0.1363122 -0.092422932 0.0093907155, -0.13688503 -0.091061175 0.012994993, -0.13499594 -0.080227613 0.046995483, -0.135043 -0.077501327 0.050657902, -0.13693328 -0.076874435 0.046995733, -0.12490972 -0.074586272 0.072020397, -0.12663865 -0.071611643 0.072020516, -0.12815571 -0.074864566 0.066747651, -0.1322391 -0.080578148 0.052833937, -0.12970303 -0.07881096 0.059995595, -0.13306208 -0.078059763 0.054280821, -0.13297659 -0.083532244 0.046995319, -0.12960435 -0.078973204 0.0599957, -0.12897775 -0.076854408 0.063393936, -0.12927884 -0.085247099 0.052833624, -0.13087632 -0.086785942 0.046995074, -0.12779343 -0.087458193 0.052833371, -0.12733932 -0.077593416 0.065413475, -0.12311118 -0.077519298 0.072020158, -0.12670302 -0.083549023 0.059995327, -0.12575848 -0.087777168 0.056433264, -0.1236401 -0.088018388 0.059995022, -0.12272329 -0.084705979 0.065412998, -0.12448864 -0.082089216 0.06541314, -0.12202986 -0.082579195 0.068739556, -0.12124351 -0.08040908 0.072020032, -0.13247496 -0.060131907 0.072021075, -0.13385987 -0.056982249 0.072021395, -0.13562912 -0.05986768 0.067059591, -0.13098989 -0.069432586 0.067060485, -0.13398634 -0.069248557 0.061996125, -0.1322761 -0.072462201 0.061996028, -0.13442557 -0.062523603 0.067059457, -0.13717163 -0.062702358 0.061996493, -0.13561846 -0.065994829 0.061996296, -0.13101606 -0.063247859 0.072020978, -0.13229597 -0.066912264 0.067059249, -0.12948373 -0.066328466 0.072020851, -0.14131501 -0.074812621 0.037815683, -0.14339074 -0.074012786 0.031995833, -0.14149535 -0.077574521 0.031995695, -0.13564068 -0.070087045 0.057996094, -0.13783787 -0.072270572 0.050833743, -0.13591318 -0.072849631 0.054433409, -0.13389795 -0.073361725 0.057995822, -0.1453397 -0.06665656 0.037815891, -0.1463588 -0.063377321 0.03925851, -0.14668681 -0.065081149 0.035639845, -0.14691095 -0.066752642 0.031996325, -0.14519617 -0.070404649 0.031996079, -0.14335918 -0.065748751 0.044996321, -0.1438733 -0.061444134 0.048658323, -0.14561731 -0.060583115 0.044996686, -0.14286479 -0.071808398 0.037815724, -0.14107211 -0.073030114 0.041418936, -0.14146626 -0.064880878 0.050833944, -0.13730352 -0.066770673 0.057996232, -0.13888499 -0.063415229 0.057996433, -0.14203241 -0.062247872 0.052281078, -0.14091778 -0.070830345 0.044996046, -0.14072937 -0.071203917 0.044996046, -0.13905716 -0.069895416 0.050833758, -0.1455875 -0.07719624 0.0077821426, -0.14662112 -0.07564801 0.0019956715, -0.14466247 -0.079329491 0.0019954965, -0.14352073 -0.077053994 0.024402689, -0.1441583 -0.074401587 0.027995769, -0.144704 -0.076060176 0.020795893, -0.14224803 -0.077991784 0.027995646, -0.14978416 -0.068699718 0.0077826604, -0.15116502 -0.065389395 0.0092250779, -0.15075916 -0.066785246 0.0056127273, -0.15025645 -0.068142742 0.0019960627, -0.14848623 -0.071918428 0.0019959994, -0.14925855 -0.068459064 0.01499626, -0.15065032 -0.064248621 0.018627379, -0.15161222 -0.063075364 0.014996473, -0.14723052 -0.074014425 0.0077822395, -0.14604563 -0.075799555 0.011391673, -0.14859162 -0.06815356 0.020796064, -0.14597809 -0.070764571 0.027996045, -0.14770603 -0.067083061 0.027996272, -0.14959385 -0.065375626 0.022242989, -0.1467139 -0.073755115 0.014995817, -0.14641137 -0.074353933 0.014995843, -0.1460584 -0.073425829 0.020795919, -0.14424139 -0.07646206 -0.022248641, -0.14415851 -0.074398339 -0.028004102, -0.14224803 -0.077988684 -0.028004333, -0.14526828 -0.078010321 -0.0056224167, -0.14662117 -0.07564792 -0.0020042546, -0.14578193 -0.076642334 -0.0092351958, -0.14466242 -0.079329431 -0.0020044483, -0.14839125 -0.068059206 -0.022248223, -0.15002778 -0.064927995 -0.020805664, -0.14891443 -0.066026986 -0.024412356, -0.147706 -0.067080021 -0.028003886, -0.14597794 -0.070761383 -0.028003879, -0.14925866 -0.068457395 -0.015003871, -0.1513617 -0.064531833 -0.011397872, -0.15161216 -0.063073695 -0.015003528, -0.14586131 -0.073324502 -0.022248439, -0.1453712 -0.075435102 -0.01863347, -0.1497056 -0.068662852 -0.0092347302, -0.14848623 -0.07191813 -0.0020040423, -0.15025637 -0.068142474 -0.0020037815, -0.15101433 -0.065951377 -0.0077879839, -0.14671391 -0.073753506 -0.015004184, -0.14641139 -0.074352324 -0.015004173, -0.14715335 -0.073974729 -0.0092350319, -0.13707888 -0.072504431 -0.052286245, -0.13564071 -0.07008028 -0.058003947, -0.13389799 -0.073355198 -0.058004208, -0.14141253 -0.075857431 -0.035649508, -0.14339066 -0.07400921 -0.032004192, -0.14122981 -0.074100435 -0.039268307, -0.14149535 -0.077570975 -0.032004304, -0.14095728 -0.064641804 -0.052285574, -0.14278045 -0.061927438 -0.050843492, -0.14088118 -0.062696666 -0.054442823, -0.13888508 -0.063408613 -0.058003575, -0.13730329 -0.066764265 -0.058003739, -0.14335918 -0.065743625 -0.045003571, -0.14611199 -0.062334508 -0.041424632, -0.14561722 -0.060578197 -0.045003325, -0.13855679 -0.069638163 -0.052285917, -0.1389493 -0.071885258 -0.048663929, -0.14497134 -0.066483289 -0.039267831, -0.14519629 -0.070400983 -0.032003976, -0.14691105 -0.066748947 -0.032003805, -0.14650238 -0.064058512 -0.037821166, -0.14091784 -0.070825368 -0.045003973, -0.14072928 -0.071198881 -0.045003951, -0.1425027 -0.071622133 -0.039268248, -0.1410621 0.03558296 0.072026528, -0.14018101 0.03890878 0.072026774, -0.14336365 0.037756145 0.067065164, -0.14570019 0.027385622 0.067066044, -0.14792825 0.029397398 0.062001709, -0.14859477 0.025818855 0.062001437, -0.14407854 0.034929156 0.06706474, -0.14633726 0.036501557 0.062002022, -0.1471757 0.032959104 0.062001921, -0.14186424 0.032237113 0.072026327, -0.14514972 0.030170202 0.067064688, -0.1425871 0.028873235 0.072026163, -0.15712786 0.029616982 0.037821397, -0.15825239 0.031536788 0.032001745, -0.15899146 0.027570397 0.032001555, -0.14974464 0.029773831 0.058001719, -0.15282407 0.029436469 0.050839435, -0.15168016 0.027783543 0.054438971, -0.15042385 0.026126891 0.058001477, -0.15518959 0.03850314 0.037821896, -0.15394154 0.04170242 0.039264519, -0.15526059 0.040574938 0.035645757, -0.15647805 0.03940779 0.032002237, -0.15741441 0.035483479 0.032001968, -0.15307467 0.037977934 0.045002073, -0.15079275 0.041664034 0.048664123, -0.15161957 0.043424517 0.045002427, -0.15646662 0.032932192 0.037821569, -0.15582675 0.030859381 0.041424803, -0.15105349 0.037476212 0.050839808, -0.14897686 0.033403188 0.058001939, -0.14812133 0.037012756 0.058002166, -0.14985454 0.039887637 0.052286707, -0.15433428 0.032482684 0.045001782, -0.15442 0.032073349 0.045001779, -0.15229644 0.03205356 0.050839577, -0.15238005 0.028781652 -0.052280605, -0.14974453 0.029780358 -0.057998322, -0.15042382 0.026133448 -0.057998508, -0.15785837 0.028862 -0.035643719, -0.15825239 0.031540334 -0.031998299, -0.15662023 0.030121773 -0.039262563, -0.15899134 0.027573913 -0.031998336, -0.15050995 0.037347168 -0.052280016, -0.15024316 0.040605783 -0.050837733, -0.14923802 0.038820356 -0.054437265, -0.14812142 0.037019342 -0.05799786, -0.14897683 0.033409625 -0.057998165, -0.15307471 0.03798309 -0.044997819, -0.15161957 0.043429613 -0.044997573, -0.1531013 0.042364776 -0.041418903, -0.1517486 0.031944126 -0.052280217, -0.15345642 0.030431926 -0.048658036, -0.15479624 0.038409829 -0.039262094, -0.15741436 0.035487086 -0.031998113, -0.15647802 0.039411277 -0.031997763, -0.15448132 0.041260391 -0.037815191, -0.15433437 0.032487899 -0.044998184, -0.15441993 0.032078356 -0.044998221, -0.15606992 0.032852948 -0.039262354, -0.16044655 0.030152977 -0.022242717, -0.15909514 0.031714648 -0.027998216, -0.15984002 0.027716547 -0.027998462, -0.1622141 0.0295825 -0.0056164041, -0.16179876 0.032272905 -0.0019981973, -0.16176286 0.030972123 -0.0092291012, -0.16256273 0.028173298 -0.0019983239, -0.15845203 0.039309889 -0.022242151, -0.15777907 0.042778313 -0.020799711, -0.15759383 0.041224808 -0.024406381, -0.15730581 0.039648354 -0.027997822, -0.15825018 0.035692722 -0.027997933, -0.15937796 0.039539158 -0.014997788, -0.15786155 0.045215875 -0.014997587, -0.1585747 0.043919533 -0.011391632, -0.15975684 0.033615917 -0.022242531, -0.16068934 0.03166005 -0.018627398, -0.15985546 0.039657265 -0.0092285722, -0.16093144 0.03635177 -0.0019980446, -0.15996122 0.040407479 -0.0019978061, -0.15918796 0.042593032 -0.007781826, -0.16069058 0.033812106 -0.014998123, -0.16082729 0.033155292 -0.014998287, -0.16117182 0.033912867 -0.0092289969, -0.16195565 0.030417711 0.0077882037, -0.16179886 0.032272726 0.0020017773, -0.16256276 0.028173208 0.0020016581, -0.16025043 0.029240131 0.024408579, -0.15909514 0.0317114 0.028001737, -0.16055626 0.030754894 0.020801827, -0.15983999 0.027713418 0.02800151, -0.15993927 0.039677113 0.007788565, -0.15895474 0.043126285 0.0092312954, -0.15950787 0.041781813 0.005618725, -0.15996134 0.0404073 0.0020023435, -0.16093142 0.036351502 0.002002012, -0.15937795 0.039537489 0.015002206, -0.15784082 0.043697208 0.018633328, -0.15786155 0.045214176 0.015002519, -0.16125637 0.033929735 0.0077883378, -0.16144285 0.031795353 0.011397664, -0.15866585 0.039360523 0.020802155, -0.15825018 0.035689473 0.028001986, -0.15730567 0.039645076 0.028002273, -0.15771729 0.042157263 0.022248898, -0.16069067 0.033810318 0.015001949, -0.16082731 0.033153564 0.015001792, -0.15997249 0.033658862 0.020801984, -0.15735278 0.022696614 -0.040998831, -0.15758824 0.024263889 -0.039419428, -0.15629876 0.025498867 -0.042998672, -0.15688241 0.021620065 -0.042998925, -0.15769204 0.020205319 -0.040998891, -0.15877318 0.023001403 -0.035815902, -0.1573696 0.017728001 -0.042998984, -0.1579919 0.017708778 -0.040999018, -0.15916182 0.020770162 -0.035502955, -0.158252 0.015207857 -0.040999204, -0.15776043 0.013825178 -0.04299935, -0.16045147 0.020924002 -0.029998802, -0.16150479 0.021127194 -0.024495937, -0.16139118 0.02400133 -0.022800952, -0.16097397 0.022468388 -0.026407368, -0.15962416 0.011628717 -0.037263237, -0.15996861 0.013109744 -0.035528094, -0.16204132 0.023448437 -0.018998682, -0.16183975 0.02643016 -0.016998529, -0.16245443 0.022343606 -0.016998716, -0.16240346 0.020792872 -0.018998712, -0.16065001 0.010234922 -0.033644401, -0.16143733 0.010974824 -0.029999316, -0.16296566 0.018242598 -0.016998909, -0.16272201 0.018131852 -0.018998899, -0.16156903 0.0088246167 -0.029999517, -0.16299713 0.015465885 -0.01899904, -0.16254058 0.011182994 -0.024243802, -0.16234002 0.013220161 -0.02451656, -0.16301003 0.012656659 -0.020628594, -0.16337353 0.014130235 -0.016999178, -0.16052493 0.020352185 -0.029998861, -0.16072577 0.018782914 -0.029954128, -0.16306157 0.014770389 -0.018999174, -0.16287366 0.022397786 -0.012998767, -0.16276318 0.025122494 -0.0093926489, -0.1622567 0.026500076 -0.012998529, -0.16287358 0.022396237 0.013001252, -0.16225678 0.026498526 0.013001479, -0.16301769 0.024285913 0.007230211, -0.16350782 0.020730317 -0.007229656, -0.16359961 0.021452099 1.2405217e-06, -0.16316697 0.023725897 -0.0057829767, -0.16338688 0.018281221 -0.012999035, -0.16368976 0.020753056 1.2032688e-06, -0.16335987 0.022878379 0.0036177859, -0.16414461 0.014868379 -0.0072301142, -0.1637961 0.014153063 -0.012999229, -0.16438858 0.01187399 -0.0072302222, -0.16357329 0.020737797 0.0057875253, -0.16338703 0.01827994 0.013001133, -0.16432738 0.014884621 9.0524554e-07, -0.16462344 0.010439306 -0.0036175326, -0.1647545 0.0089969933 5.6251884e-07, -0.16449496 0.011300504 0.0057870597, -0.16421026 0.014873624 0.0057872906, -0.1641975 0.012729943 0.0093964785, -0.16379614 0.014151663 0.013000898, -0.16204146 0.023446441 0.019001313, -0.16159084 0.024913371 0.020632297, -0.16183963 0.026428044 0.017001465, -0.16245434 0.022341579 0.017001353, -0.16240343 0.020790786 0.01900116, -0.16123702 0.023386925 0.024247937, -0.16296566 0.01824078 0.017001059, -0.16272205 0.018129677 0.019000925, -0.16150498 0.021124482 0.024498269, -0.16299704 0.01546365 0.019000836, -0.16337362 0.014128357 0.01700082, -0.1604515 0.020920485 0.030001093, -0.15916166 0.020766109 0.035505481, -0.15831175 0.023505598 0.037262939, -0.15943399 0.0222269 0.033644471, -0.16274111 0.01176995 0.022800751, -0.16234013 0.01321736 0.024518073, -0.15735278 0.022691905 0.041001253, -0.15629882 0.025494039 0.043001324, -0.15688226 0.021615297 0.043001056, -0.15769209 0.0202007 0.041001059, -0.16220814 0.010295719 0.026407663, -0.16143729 0.010971367 0.030000541, -0.15736957 0.017723322 0.043000959, -0.15799187 0.017704278 0.041000966, -0.16156904 0.0088213086 0.030000474, -0.15825203 0.015203327 0.041000891, -0.16004732 0.011069119 0.035820179, -0.15996864 0.01310569 0.035529666, -0.15895732 0.012452871 0.039423279, -0.15776029 0.01382032 0.043000791, -0.1605345 0.020350099 0.029956572, -0.16072564 0.018779576 0.029956277, -0.15833279 0.014338672 0.041000813, -0.15556353 0.021443665 0.047001299, -0.15390055 0.023604512 0.050663624, -0.15498728 0.025273114 0.047001492, -0.14415969 0.019565195 0.072025597, -0.14365667 0.022968978 0.072025836, -0.14687102 0.021371305 0.06675297, -0.15362644 0.019450396 0.052839484, -0.15054166 0.019250929 0.060001198, -0.1526998 0.021932513 0.054286506, -0.15604518 0.017600954 0.047000915, -0.15056559 0.019062459 0.060001235, -0.14875454 0.020328373 0.063399397, -0.15422302 0.01395452 0.052839201, -0.15643169 0.013747483 0.047000803, -0.1544403 0.01129961 0.052839067, -0.1479342 0.018728942 0.065418877, -0.14458205 0.016150564 0.072025456, -0.15115014 0.013675869 0.060000751, -0.1530481 0.00978145 0.056438714, -0.15154214 0.0082721114 0.060000487, -0.14876001 0.010290205 0.065418437, -0.14850858 0.013436586 0.065418556, -0.14689164 0.011520505 0.068744808, -0.14492369 0.012726992 0.072025239, -0.16377395 -0.014406502 -0.013000812, -0.16427246 -0.011725664 -0.0093947724, -0.16408533 -0.01026994 -0.013000507, -0.16377401 -0.014407903 0.012999192, -0.16408533 -0.010271341 0.012999453, -0.16433461 -0.012597829 0.0072279759, -0.16402113 -0.016173214 -0.0072318166, -0.16427135 -0.015490025 -9.7230077e-07, -0.16435534 -0.013176978 -0.0057852045, -0.16335827 -0.018534154 -0.013000894, -0.16420366 -0.016191661 -8.9779496e-07, -0.16435513 -0.014046073 0.0036155954, -0.16333762 -0.022030085 -0.0072321072, -0.16283867 -0.022649825 -0.013001367, -0.16290906 -0.025003612 -0.0072322823, -0.16408683 -0.016180485 0.0057855137, -0.16335832 -0.018535703 0.01299898, -0.16351947 -0.02205494 -1.1660159e-06, -0.16281909 -0.026454568 -0.003619615, -0.16262592 -0.027889937 -1.4528632e-06, -0.16288546 -0.025586396 0.0057848841, -0.16340311 -0.022039652 0.0057852343, -0.16291344 -0.024126738 0.0093946271, -0.16283859 -0.022651166 0.01299879, -0.15845755 -0.012886733 -0.041000694, -0.15903594 -0.011411071 -0.039421678, -0.15805355 -0.0099201798 -0.043000631, -0.15775943 -0.013831526 -0.043000907, -0.15823397 -0.015391022 -0.041000895, -0.1599102 -0.012905657 -0.035818122, -0.1573683 -0.017734408 -0.043000989, -0.15797071 -0.017891616 -0.041001029, -0.15979268 -0.015167326 -0.035505086, -0.15766802 -0.020387709 -0.041001022, -0.15688083 -0.021626383 -0.043001309, -0.16108429 -0.015304416 -0.030000821, -0.16215667 -0.015340567 -0.024497963, -0.16268536 -0.012513429 -0.022802889, -0.16193728 -0.013915062 -0.026409611, -0.1582092 -0.024182409 -0.037265137, -0.15887463 -0.022815287 -0.035530135, -0.16319619 -0.013196856 -0.019000687, -0.16366303 -0.010245264 -0.017000668, -0.16335295 -0.01436615 -0.017000765, -0.16295846 -0.015866399 -0.019001, -0.15889932 -0.025769681 -0.033646256, -0.15983146 -0.025223523 -0.030001342, -0.16293898 -0.018477947 -0.017001063, -0.16267677 -0.018531829 -0.019001, -0.15948153 -0.027348995 -0.030001573, -0.16235149 -0.021192133 -0.019001126, -0.16095355 -0.025265932 -0.024245918, -0.16121128 -0.023235291 -0.024518594, -0.16173917 -0.023933649 -0.020630613, -0.16242152 -0.022578031 -0.01700132, -0.16102867 -0.015878171 -0.030000888, -0.16087519 -0.017452747 -0.029956229, -0.16225964 -0.02188468 -0.019001149, -0.15643555 -0.01371029 0.046999376, -0.15529504 -0.011233509 0.050661746, -0.15672591 -0.0098485649 0.046999477, -0.14489986 -0.013004065 0.07202372, -0.14516674 -0.0095737875 0.072023965, -0.14794515 -0.011846453 0.066751182, -0.15410346 -0.015222311 0.052837491, -0.15105173 -0.014730543 0.059999175, -0.15375237 -0.012596369 0.054284561, -0.15605001 -0.01756376 0.04699906, -0.15103325 -0.014919549 0.059999179, -0.14954923 -0.013282508 0.063397408, -0.1534621 -0.020713419 0.052837264, -0.15556936 -0.021406651 0.046998862, -0.15308329 -0.023349851 0.052837178, -0.1483936 -0.014659196 0.065416947, -0.14455189 -0.01642701 0.072023645, -0.15040451 -0.020301163 0.059998963, -0.15138805 -0.024520397 0.056436833, -0.14958411 -0.02565679 0.059998542, -0.14732076 -0.023070127 0.065416485, -0.14777598 -0.019946635 0.065416627, -0.14577322 -0.02145496 0.068743013, -0.14412311 -0.019840777 0.072023451, -0.16319621 -0.013199061 0.018999282, -0.1630834 -0.011668772 0.020630352, -0.16366298 -0.010247171 0.016999289, -0.16335283 -0.014368057 0.016999166, -0.16295835 -0.015868634 0.018999148, -0.16239868 -0.013078183 0.024245974, -0.16293886 -0.018479973 0.016998902, -0.16267662 -0.018533945 0.01899901, -0.16215678 -0.015343368 0.024496265, -0.16235153 -0.021194249 0.018998783, -0.16242163 -0.022579908 0.016998794, -0.16108432 -0.015307695 0.029999223, -0.15979259 -0.015171379 0.035503484, -0.15957342 -0.012311548 0.037261087, -0.16038285 -0.013807952 0.033642504, -0.16128016 -0.024738431 0.022798754, -0.16121149 -0.023238063 0.024516042, -0.15845764 -0.012891233 0.040999226, -0.15805356 -0.0099250674 0.042999458, -0.1577594 -0.013836354 0.042999201, -0.15823391 -0.015395731 0.040999267, -0.16043243 -0.026057184 0.026405543, -0.15983152 -0.025226861 0.029998608, -0.15736844 -0.017739177 0.042998929, -0.15797058 -0.017896265 0.040999111, -0.15948138 -0.027352393 0.029998489, -0.15766804 -0.020392329 0.040998884, -0.15849806 -0.024822295 0.035818025, -0.15887454 -0.02281937 0.03552752, -0.15774339 -0.023230702 0.039421368, -0.15688077 -0.0216313 0.042998724, -0.16103821 -0.015882581 0.029954333, -0.16087514 -0.017456174 0.029954251, -0.15755436 -0.021253347 0.040998906, -0.16313319 -0.0063057542 -0.022244774, -0.16216305 -0.0044826269 -0.028000198, -0.16199976 -0.0085460246 -0.028000399, -0.16472974 -0.0072552562 -0.0056185797, -0.16492365 -0.0045397282 -0.0020002872, -0.16459894 -0.0057999194 -0.0092311688, -0.16475618 -0.0087065101 -0.0020005703, -0.1632261 0.0030653775 -0.02224417, -0.163342 0.0065965354 -0.02080173, -0.16281587 0.0051234663 -0.024408422, -0.16218391 0.0036503673 -0.027999803, -0.16222441 -0.00041633844 -0.028000072, -0.16418032 0.0030829608 -0.014999859, -0.1639649 0.0089547634 -0.014999427, -0.16437188 0.0075322986 -0.011393808, -0.16323122 -0.0027761757 -0.022244528, -0.16370541 -0.0048904419 -0.01862938, -0.16467196 0.0030917525 -0.0092307255, -0.16498566 -0.00037020445 -0.0020000339, -0.16494222 0.0037995875 -0.0019999295, -0.16467446 0.0061023533 -0.0077839531, -0.16418533 -0.0027927458 -0.015000165, -0.16417271 -0.0034634471 -0.015000314, -0.16467732 -0.0028014183 -0.0092310533, -0.15496346 -0.0058476329 -0.052282445, -0.15261619 -0.0042876303 -0.058000199, -0.15246691 -0.0079942346 -0.058000505, -0.16032247 -0.0069883168 -0.035645701, -0.16130266 -0.0044648349 -0.032000266, -0.15939558 -0.0054845512 -0.039264515, -0.16114059 -0.0084962547 -0.032000393, -0.15504631 0.0029191673 -0.052281812, -0.15551126 0.0061555803 -0.050839655, -0.15413393 0.0046386123 -0.054439187, -0.1526444 0.0031310618 -0.057999827, -0.15267543 -0.00057828426 -0.058000103, -0.15768835 0.0029684901 -0.04499986, -0.15868917 0.0072344542 -0.041420847, -0.15748151 0.0086022019 -0.044999518, -0.15505147 -0.0026238859 -0.052282199, -0.15638007 -0.0044781268 -0.048660129, -0.15946171 0.0030016005 -0.039264016, -0.16136397 -0.00043073297 -0.032000147, -0.16132432 0.0036037266 -0.03199973, -0.15978894 0.0058505833 -0.037817284, -0.15769359 -0.0026691556 -0.045000136, -0.15768592 -0.003087461 -0.045000292, -0.15946704 -0.0026994646 -0.039264359, -0.16466375 -0.0063833892 0.00778611, -0.16492362 -0.0045399964 0.0019996837, -0.1647561 -0.0087067187 0.0019995309, -0.16273963 -0.0071520507 0.024406567, -0.162163 -0.0044857264 0.027999699, -0.16337469 -0.0057433248 0.020799693, -0.1619997 -0.0085493326 0.027999483, -0.16475825 0.0030925274 0.0077865347, -0.16456592 0.0066741407 0.0092293434, -0.16480626 0.0052403808 0.0056167543, -0.16494229 0.0037992597 0.0020001605, -0.1649856 -0.00037044287 0.0019999743, -0.16418032 0.0030812621 0.015000097, -0.16396491 0.0089531243 0.015000351, -0.1636073 0.0074787736 0.018631272, -0.16476354 -0.0028038919 0.0077863187, -0.16447048 -0.0049262345 0.011395652, -0.16344666 0.0030672252 0.02080014, -0.16222453 -0.00041931868 0.028000053, -0.16218397 0.0036471188 0.028000169, -0.16314428 0.0060047507 0.022246849, -0.16418535 -0.0027944148 0.014999732, -0.16417255 -0.003465116 0.014999762, -0.16345176 -0.0027822554 0.020799916, -0.15977933 -0.0060898066 0.037819311, -0.16130264 -0.0044684708 0.03199992, -0.16114053 -0.0084997714 0.031999532, -0.1526162 -0.0042940676 0.057999842, -0.15554333 -0.005308181 0.050837412, -0.15406044 -0.0066651404 0.054437231, -0.15246703 -0.0080007613 0.057999641, -0.15986687 0.0030047297 0.037819874, -0.15936208 0.0064016879 0.039262541, -0.16039702 0.0050087571 0.035643701, -0.1613242 0.0036000907 0.032000348, -0.16136402 -0.00043424964 0.03199999, -0.15768841 0.0029634237 0.045000274, -0.15748161 0.0085972548 0.045000516, -0.15628375 0.0070648491 0.048662048, -0.15987235 -0.0027107298 0.037819557, -0.15878718 -0.0045890212 0.041422732, -0.15560614 0.0029239058 0.050837845, -0.15267548 -0.00058493018 0.05799986, -0.15264441 0.0031245947 0.058000091, -0.15497388 0.0055418909 0.05228477, -0.1576937 -0.0026742816 0.044999942, -0.15768591 -0.0030926764 0.044999678, -0.15561132 -0.0026392639 0.050837435, -0.14544429 0.0033013225 0.072024718, -0.14532544 0.0067399144 0.072024971, -0.14817162 0.0049081445 0.067063279, -0.14814192 -0.0057224333 0.067064203, -0.15076178 -0.0042567551 0.061999708, -0.15061529 -0.0078940392 0.061999492, -0.1482396 0.0019928813 0.067063153, -0.15079136 0.0030230582 0.062000163, -0.15082063 -0.00061705709 0.062000014, -0.1454818 -0.00013902783 0.072024554, -0.14822499 -0.0028851628 0.067062661, -0.14543791 -0.0035793483 0.07202439, 0.065098614 0.14971548 -0.02223587, 0.066319972 0.14805096 -0.027991742, 0.062588021 0.14966685 -0.027991712, 0.064936697 0.15156457 -0.0056094825, 0.067467317 0.15056089 -0.0019916296, 0.066190913 0.15081576 -0.0092224777, 0.063640639 0.15221795 -0.0019915849, 0.073582023 0.14573342 -0.022236213, 0.076813981 0.1443055 -0.020793959, 0.075258061 0.14447078 -0.024400532, 0.073656574 0.14454103 -0.027991876, 0.070010155 0.14634213 -0.027991757, 0.074012071 0.1465849 -0.01499182, 0.078104049 0.14482656 -0.011386022, 0.079208836 0.14384308 -0.014991954, 0.068321213 0.14827266 -0.022236094, 0.066622198 0.14961666 -0.018620655, 0.074233815 0.14702353 -0.0092225969, 0.071250945 0.14880759 -0.0019915551, 0.07498908 0.14695939 -0.0019917339, 0.076947376 0.14571947 -0.0077761114, 0.068720564 0.14913878 -0.01499173, 0.068110645 0.14941832 -0.014991611, 0.068926439 0.14958522 -0.0092224926, 0.061964944 0.14215845 -0.052274153, 0.062351912 0.13936728 -0.057992294, 0.058947504 0.14084113 -0.057992086, 0.063263401 0.14748034 -0.035636991, 0.065962285 0.14726841 -0.031991705, 0.064215794 0.14599329 -0.039256066, 0.062259883 0.1488716 -0.031991586, 0.069899559 0.13842946 -0.052274302, 0.073017374 0.13744402 -0.050832286, 0.071052849 0.13686147 -0.054431647, 0.069048181 0.13617399 -0.057992399, 0.065719455 0.13781136 -0.057992339, 0.071090713 0.14078784 -0.044992119, 0.075368628 0.1398384 -0.041413397, 0.07607697 0.13815698 -0.044992313, 0.064907581 0.14083916 -0.052274093, 0.063813671 0.14284042 -0.048651814, 0.07189019 0.14237076 -0.039256215, 0.069623604 0.14557314 -0.031991795, 0.073241293 0.14378706 -0.031992003, 0.074599296 0.14142919 -0.037809446, 0.066013694 0.14323869 -0.04499191, 0.065633461 0.14341336 -0.044992059, 0.06675604 0.14484924 -0.039256066, 0.068714723 0.1313706 -0.067055553, 0.06913051 0.12801158 -0.072017357, 0.066084057 0.1296106 -0.072017342, 0.058240443 0.13912666 -0.061992168, 0.06158106 0.13768059 -0.061992273, 0.059124053 0.1359562 -0.067056879, 0.066117212 0.13269597 -0.067056939, 0.064885885 0.13615423 -0.061992392, 0.068152934 0.13454852 -0.061992377, 0.063000619 0.13113701 -0.072017208, 0.06171611 0.13479912 -0.06705682, 0.059881866 0.13259047 -0.072017193, 0.063840985 0.14659536 0.037828103, 0.065962315 0.14726484 0.03200835, 0.062259793 0.14886814 0.032008454, 0.062351868 0.13936082 0.058007807, 0.062707886 0.14243868 0.050845787, 0.060842067 0.14169103 0.05444552, 0.058947578 0.14083454 0.05800797, 0.072072908 0.14272833 0.037827805, 0.074914306 0.1407994 0.039269865, 0.074108303 0.14233658 0.035651535, 0.073241174 0.1437836 0.032008097, 0.06962356 0.14556959 0.032008111, 0.071090713 0.14078271 0.045007914, 0.074176714 0.13773754 0.048669502, 0.076076895 0.13815212 0.045007735, 0.066925704 0.14521304 0.037827983, 0.064762697 0.14505005 0.041431323, 0.070151925 0.13892362 0.050845534, 0.06571947 0.13780484 0.058007777, 0.069048181 0.13616738 0.058007658, 0.072236329 0.13721776 0.052292004, 0.066013724 0.1432336 0.045007974, 0.065633476 0.1434083 0.045008078, 0.065141916 0.14134204 0.050845549, 0.065694228 0.15112591 0.007794857, 0.067467332 0.15056062 0.0020084977, 0.063640594 0.15221772 0.0020084828, 0.064167589 0.14972442 0.024415419, 0.066320032 0.14804772 0.028008372, 0.065712288 0.14968559 0.020808369, 0.062587932 0.14966366 0.028008386, 0.074272618 0.14709973 0.0077946186, 0.077416286 0.14537221 0.009237051, 0.076228574 0.14621103 0.0056246668, 0.074989051 0.14695916 0.0020082891, 0.071250945 0.14880753 0.0020084977, 0.074012071 0.14658326 0.015008211, 0.079208851 0.14384151 0.015008122, 0.077725649 0.14415872 0.018638894, 0.06896247 0.14966264 0.0077949315, 0.066923276 0.15031916 0.011404425, 0.073681414 0.14592782 0.020808116, 0.070010275 0.14633879 0.028008223, 0.073656589 0.14453781 0.028008148, 0.076196969 0.14438057 0.02225475, 0.068720549 0.1491372 0.015008345, 0.06811069 0.14941663 0.015008479, 0.068413377 0.14847049 0.020808399, 0.030418396 0.16195521 0.0077954382, 0.032272756 0.16179872 0.002009064, 0.028173313 0.16256267 0.0020090044, 0.029241651 0.16024902 0.024416, 0.031713039 0.15909347 0.028008997, 0.030756176 0.16055512 0.020809054, 0.027715102 0.15983844 0.028008997, 0.039677635 0.15993887 0.0077954829, 0.043126851 0.15895414 0.0092377663, 0.041782305 0.15950754 0.005625397, 0.040407375 0.15996128 0.0020090491, 0.036351681 0.16093132 0.0020090491, 0.039538383 0.15937722 0.015008867, 0.043698356 0.15783992 0.018639699, 0.04521504 0.15786076 0.015008822, 0.033930257 0.16125581 0.0077954382, 0.031796128 0.16144204 0.011405066, 0.039361775 0.15866464 0.020808965, 0.035691008 0.15824866 0.028008923, 0.039646775 0.15730408 0.028008908, 0.042158589 0.15771604 0.022255555, 0.033811182 0.16068962 0.015009075, 0.033154353 0.16082656 0.015009075, 0.033660099 0.15997136 0.020809084, 0.029619321 0.15712577 0.03782849, 0.031538591 0.15825054 0.03200902, 0.027572215 0.15898961 0.032009065, 0.02977711 0.14974132 0.058008388, 0.029439479 0.15282112 0.050846279, 0.027786672 0.1516771 0.054446116, 0.026130334 0.15042043 0.058008462, 0.038505375 0.15518752 0.03782849, 0.041704774 0.15393916 0.039270625, 0.040576845 0.15525857 0.035652161, 0.039409772 0.15647608 0.032008782, 0.035485178 0.15741256 0.032008842, 0.037980601 0.1530723 0.0450086, 0.043427184 0.15161696 0.045008436, 0.04166688 0.15078986 0.048670128, 0.032934293 0.15646446 0.037828475, 0.030861825 0.15582421 0.041431829, 0.037479132 0.15105057 0.050846145, 0.033406496 0.14897361 0.058008343, 0.037016109 0.14811796 0.058008224, 0.039890632 0.14985153 0.052292854, 0.03248544 0.15433174 0.045008823, 0.032076016 0.15441743 0.045008674, 0.032056451 0.15229383 0.050846115, 0.037759915 0.14336744 -0.067054972, 0.038912952 0.14018503 -0.072016731, 0.035586998 0.14106613 -0.072016597, 0.025822312 0.14859834 -0.061991766, 0.029401079 0.14793184 -0.061991766, 0.027389377 0.14570391 -0.067056283, 0.034932807 0.14408156 -0.067056313, 0.03296259 0.14717922 -0.061991796, 0.036505103 0.1463407 -0.061991796, 0.032241285 0.1418682 -0.072016567, 0.030173972 0.14515266 -0.067056239, 0.028877318 0.142591 -0.072016627, 0.028778777 0.15238294 -0.052273616, 0.029777169 0.14974785 -0.057991609, 0.026130289 0.15042695 -0.057991624, 0.028860077 0.15786025 -0.0356365, 0.03153865 0.15825418 -0.031991124, 0.030119672 0.15662238 -0.039255425, 0.027572155 0.15899321 -0.03199099, 0.037344232 0.15051299 -0.052273512, 0.040602908 0.15024614 -0.050831556, 0.03881748 0.14924091 -0.054431066, 0.037016213 0.14812446 -0.057991728, 0.033406436 0.14898026 -0.057991609, 0.037980631 0.15307724 -0.044991314, 0.04342714 0.15162215 -0.044991449, 0.042362556 0.15310341 -0.041412517, 0.03194119 0.15175149 -0.052273482, 0.03042917 0.15345916 -0.048651204, 0.038407683 0.15479845 -0.03925547, 0.035485193 0.15741622 -0.031991079, 0.039409786 0.15647966 -0.031991214, 0.041258305 0.15448341 -0.037808895, 0.03248544 0.15433681 -0.044991344, 0.032075942 0.15442246 -0.044991329, 0.032850787 0.15607211 -0.03925544, 0.030151829 0.16044772 -0.022235379, 0.031713083 0.15909663 -0.027991116, 0.027715117 0.1598416 -0.027991027, 0.029582217 0.16221446 -0.0056089908, 0.032272801 0.16179892 -0.0019909143, 0.030971721 0.16176331 -0.009221673, 0.028173357 0.16256276 -0.0019908994, 0.039308786 0.1584532 -0.022235513, 0.04277724 0.15778032 -0.02079317, 0.041223586 0.15759507 -0.024399713, 0.0396467 0.15730724 -0.027991116, 0.035691068 0.15825173 -0.027991191, 0.039538443 0.15937889 -0.014990985, 0.045215026 0.15786242 -0.014991164, 0.043918908 0.15857539 -0.011385292, 0.033614799 0.15975797 -0.022235364, 0.031659141 0.16069046 -0.018620044, 0.039656818 0.15985602 -0.0092218518, 0.036351711 0.16093156 -0.0019908547, 0.040407315 0.15996146 -0.0019909739, 0.042592615 0.15918836 -0.0077753663, 0.033811197 0.16069147 -0.014991, 0.033154413 0.16082814 -0.01499103, 0.03391248 0.16117236 -0.0092218071, 0.057139605 0.14835998 -0.040991619, 0.058720097 0.14824063 -0.039412603, 0.059637055 0.14670908 -0.042991698, 0.055985391 0.14814091 -0.042991757, 0.054786265 0.14924502 -0.040991634, 0.05775322 0.14967653 -0.035808757, 0.052299395 0.1494821 -0.042991668, 0.052419141 0.15009293 -0.040991545, 0.055664346 0.15055186 -0.035495728, 0.050038919 0.15090311 -0.04099156, 0.048581317 0.15073133 -0.042991623, 0.056101561 0.15177462 -0.029991537, 0.056534529 0.15275607 -0.024488598, 0.059311271 0.1520054 -0.022793636, 0.057723761 0.15194014 -0.026400194, 0.046854958 0.15303692 -0.037255406, 0.048375532 0.15304306 -0.035520315, 0.058917254 0.15276214 -0.018991441, 0.06177938 0.15190169 -0.016991436, 0.05793184 0.1534104 -0.016991377, 0.056408837 0.15370613 -0.018991336, 0.045724541 0.15434697 -0.033636242, 0.046621218 0.15494952 -0.029991314, 0.054047689 0.1548216 -0.016991407, 0.053885415 0.15460882 -0.018991336, 0.044554427 0.15555644 -0.029991329, 0.05134739 0.15547001 -0.018991351, 0.047070131 0.15597847 -0.02423577, 0.049011499 0.15532976 -0.024508595, 0.048611581 0.15610778 -0.020620331, 0.050129205 0.15613428 -0.016991124, 0.055560455 0.15197352 -0.029991522, 0.054075301 0.15251845 -0.029946595, 0.050683603 0.15568781 -0.018991217, 0.058078304 0.15380698 -0.012991339, 0.060710296 0.15309265 -0.0093855113, 0.061940521 0.15229264 -0.012991413, 0.058078334 0.15380561 0.013008639, 0.061940491 0.15229121 0.013008624, 0.059952334 0.15352586 0.0072374493, 0.056594178 0.15479586 -0.0072221458, 0.057318777 0.15472418 8.7171793e-06, 0.059438899 0.1537967 -0.0057756752, 0.054179251 0.15522343 -0.012991309, 0.05665721 0.15496752 8.7469816e-06, 0.058656231 0.15417278 0.0036251694, 0.051020861 0.1567212 -0.0072220713, 0.050245747 0.15654093 -0.012991309, 0.048155904 0.15762511 -0.0072220564, 0.056616858 0.15485707 0.0057952255, 0.054179296 0.15522194 0.013008788, 0.051077694 0.15689516 8.8661909e-06, 0.046809748 0.15817317 -0.0036092848, 0.045432836 0.15862173 8.9108944e-06, 0.047621161 0.15785575 0.0057952851, 0.051041305 0.15678316 0.0057952851, 0.048948735 0.15724745 0.0094047189, 0.050245732 0.15653938 0.013008788, 0.051157221 0.13619474 -0.07201694, 0.053853631 0.1371533 -0.06873472, 0.054363593 0.13494691 -0.072017044, 0.055524707 0.14689359 -0.04699184, 0.059130073 0.14547962 -0.04699178, 0.056126818 0.1443257 -0.052832574, 0.05094178 0.13940457 -0.066745996, 0.052270278 0.14248607 -0.059992045, 0.053288668 0.13927367 -0.065407887, 0.047922209 0.13736641 -0.072016954, 0.052091807 0.14255136 -0.059991971, 0.054212704 0.14346114 -0.056431964, 0.045933515 0.14113405 -0.066745862, 0.044660553 0.1384612 -0.07201688, 0.043457046 0.14191625 -0.066745847, 0.05295001 0.14489919 -0.054274559, 0.051885545 0.1482181 -0.046991676, 0.046970621 0.14431986 -0.059991941, 0.041789323 0.14590448 -0.059991807, 0.044671625 0.14766175 -0.054274514, 0.042645916 0.14395627 -0.063391894, 0.047744364 0.14669695 -0.054274529, 0.046451479 0.1486136 -0.050652117, 0.048214898 0.14945254 -0.046991572, 0.058917239 0.15276009 0.019008636, 0.060247183 0.15199438 0.020639569, 0.061779276 0.15189987 0.017008498, 0.05793184 0.15340859 0.017008662, 0.056408808 0.15370402 0.019008666, 0.05868037 0.15198857 0.024255246, 0.054047689 0.1548197 0.017008677, 0.053885296 0.1546067 0.019008726, 0.056534529 0.15275329 0.024505734, 0.051347449 0.15546793 0.019008771, 0.05012916 0.1561324 0.017008692, 0.056101516 0.15177113 0.030008495, 0.055664361 0.15054777 0.03551285, 0.058146 0.14910945 0.037270114, 0.057148933 0.15048817 0.033651754, 0.047689632 0.15603998 0.02280885, 0.049011409 0.15532705 0.02452606, 0.05713959 0.14835536 0.041008383, 0.0596371 0.14670411 0.043008238, 0.055985346 0.14813608 0.043008298, 0.054786235 0.14924046 0.041008368, 0.046133757 0.15584826 0.026415765, 0.046621263 0.15494615 0.030008733, 0.052299351 0.14947715 0.043008491, 0.052419126 0.15008822 0.041008413, 0.044554383 0.15555307 0.030008718, 0.050038904 0.15089852 0.041008502, 0.046407536 0.15356901 0.035828039, 0.048375577 0.15303898 0.035537541, 0.047514096 0.15219814 0.039431214, 0.048581198 0.1507265 0.043008491, 0.055563614 0.15197927 0.029963791, 0.054075271 0.15251493 0.029963747, 0.049213693 0.15116951 0.041008502, -0.12450807 -0.062436223 0.074496642, -0.12896091 -0.057423055 0.07449685, -0.12759256 -0.060402811 0.074496605, -0.11253721 -0.054413736 0.074496903, -0.12852199 -0.053689301 0.074497111, -0.11541091 -0.048018187 0.074497253, -0.13025986 -0.054412186 0.074497029, -0.12927984 -0.051837772 0.074497126, 0.114887 0.082025141 0.074504584, 0.11295086 0.084671289 0.074504763, -0.13001104 -0.049975693 0.074497283, 0.071496762 -0.12172547 0.07449314, 0.067737371 -0.12170735 0.074493155, 0.06865038 -0.12335327 0.07449314, -0.11792153 -0.041471422 0.074497744, -0.1307153 -0.048103273 0.074497275, -0.13355279 -0.045737118 0.074497424, -0.13245453 -0.048826844 0.074497223, 0.060398512 -0.12759671 0.074492872, 0.062432051 -0.12451226 0.074493043, 0.057418726 -0.12896517 0.074492782, 0.063345708 -0.1261594 0.074492998, 0.11095354 0.087272018 0.074504927, 0.10889652 0.089825451 0.074505016, 0.074304573 -0.12003198 0.074493207, 0.075979955 -0.1167393 0.074493483, 0.077072352 -0.11827388 0.074493363, -0.13457885 -0.042622894 0.074497625, -0.13372473 -0.038961828 0.074497707, -0.12006104 -0.034794331 0.074497998, 0.053685032 -0.12852624 0.074492753, 0.054408014 -0.13026401 0.074492775, -0.13553244 -0.039485693 0.074497744, 0.084675662 -0.11295497 0.074493639, 0.080937937 -0.11335793 0.074493632, 0.082029425 -0.11489132 0.074493647, -0.13427056 -0.037037194 0.074497968, -0.13478851 -0.035104871 0.074498095, -0.12182282 -0.028007776 0.074498355, 0.10498023 0.094372571 0.074505374, 0.10275987 0.096785367 0.074505404, 0.045732997 -0.13355702 0.074492544, 0.048099019 -0.1307196 0.074492782, 0.042618655 -0.13458318 0.07449244, 0.048822552 -0.13245884 0.074492641, -0.13527875 -0.033165365 0.074498065, 0.08727625 -0.1109578 0.074493766, 0.088572346 -0.10749817 0.074493945, 0.089829713 -0.10890085 0.07449396, -0.13783348 -0.030496389 0.07449834, -0.13708803 -0.033689439 0.074498087, 0.1004841 0.099146038 0.074505627, 0.098154083 0.10145316 0.074505627, 0.038957641 -0.13372901 0.07449241, 0.039481461 -0.13553685 0.07449241, -0.13850442 -0.027286857 0.074498422, 0.096789747 -0.10276428 0.074494198, 0.09312056 -0.1035831 0.074494198, 0.094376869 -0.1049844 0.074494198, -0.13724582 -0.023744375 0.074498631, -0.1232014 -0.021132916 0.074498713, -0.13910072 -0.024062663 0.074498683, -0.1375725 -0.021770775 0.074498728, 0.033685379 -0.13709241 0.074492216, 0.033161081 -0.13528308 0.074492402, 0.030492209 -0.13783768 0.074492224, 0.027282633 -0.13850877 0.074492209, -0.13787103 -0.019792587 0.074498869, 0.10005093 -0.096905291 0.074494526, -0.12419232 -0.014191777 0.07449913, 0.099150352 -0.10048836 0.074494287, 0.10145748 -0.09815833 0.074494585, 0.093753234 0.10553318 0.074506029, 0.091276839 0.10768217 0.074506015, -0.13814096 -0.017810345 0.074498907, 0.023740232 -0.13725001 0.074492246, 0.024058327 -0.13910511 0.074492179, 0.1076865 -0.091280937 0.074494898, 0.10413221 -0.092505574 0.074494675, 0.1055375 -0.09375748 0.074494839, -0.14038084 -0.014872313 0.074499145, -0.13999772 -0.018128753 0.074499026, 0.088751048 0.10977322 0.074506238, 0.086177334 0.11180499 0.074506313, -0.14068829 -0.011607677 0.074499339, 0.01812461 -0.14000189 0.074492149, 0.017806172 -0.13814524 0.074492209, 0.014868088 -0.14038509 0.074492171, -0.13904083 -0.0082286 0.074499711, -0.12479239 -0.0072059929 0.074499674, 0.011603519 -0.14069259 0.074492149, 0.11027142 -0.085094035 0.074495241, 0.1097775 -0.088755161 0.074495032, 0.11180925 -0.086181551 0.074495047, -0.14091985 -0.0083369911 0.074499637, -0.1391446 -0.0062307417 0.074499726, 0.0082242936 -0.13904512 0.074492216, 0.0083326921 -0.1409241 0.074492037, -0.12499987 -0.00019747019 0.074500032, -0.1392197 -0.0042315423 0.074499756, 0.081347376 0.11536661 0.074506491, 0.078645706 0.11722499 0.074506581, 0.11722922 -0.078650028 0.074495673, 0.11383434 -0.080264926 0.074495494, 0.11537091 -0.081351638 0.07449539, -0.13926607 -0.0022315979 0.074499756, 0.065982409 -0.12266779 0.07449308, 0.060633883 -0.10931364 0.074493788, 0.064213879 -0.12360281 0.074493043, 0.075901672 0.1190201 0.074506655, 0.077648789 -0.1156359 0.074493475, 0.066667534 -0.10574192 0.074494049, -0.14116286 0.00093883276 0.074500158, -0.14114663 -0.0023401678 0.074499801, 0.073116764 0.12075076 0.074506894, 0.054409504 -0.11254147 0.074493766, -0.14110284 0.0042173564 0.074500255, -0.13908747 0.0073908567 0.074500397, -0.12481406 0.0068116188 0.074500397, 0.079301469 -0.11450875 0.07449346, 0.072491445 -0.10183743 0.074494272, -0.14096662 0.0074934661 0.074500516, -0.13896681 0.0093877614 0.07450065, 0.051833659 -0.12928414 0.07449279, 0.048013963 -0.11541528 0.074493445, 0.049971461 -0.13001519 0.074492753, -0.13881761 0.011382639 0.074500754, -0.12423569 0.013799429 0.074500769, 0.078087233 -0.097612709 0.074494474, 0.06791836 0.12374929 0.074506998, 0.065025702 0.12529334 0.074507043, -0.13863972 0.013375252 0.07450068, 0.090107158 -0.10621491 0.074493989, 0.041467182 -0.11792585 0.07449346, 0.062097907 0.12676999 0.074507058, -0.14016962 0.016738147 0.074500933, -0.14052063 0.013477951 0.074500762, 0.0023357421 -0.14115086 0.074492186, 0.0022273585 -0.13927034 0.074492149, -0.00094304979 -0.14116722 0.074492119, 0.059136763 0.12817806 0.074507266, 0.083437271 -0.093080759 0.074494667, 0.091623321 -0.10490987 0.074494183, -0.13974285 0.019989192 0.074501112, 0.034790039 -0.12006539 0.074493214, 0.037032977 -0.13427478 0.074492395, 0.035100624 -0.13479275 0.074492387, -0.13738491 0.022917122 0.074501321, -0.12326612 0.020743549 0.074501172, -0.13924082 0.02322945 0.074501194, -0.0042214766 -0.14110714 0.074492015, 0.11902425 -0.075905979 0.074495822, 0.11910492 -0.072212338 0.074495897, -0.13704139 0.024888009 0.074501351, 0.12075505 -0.073121011 0.074495852, 0.088524804 -0.088255882 0.074495032, 0.10143238 -0.095458329 0.07449469, -0.1219089 0.027622461 0.074501589, -0.13666978 0.026853651 0.074501455, 0.028003454 -0.12182719 0.074493244, 0.053635359 0.1305756 0.074507371, 0.050587997 0.13178602 0.07450743, -0.13626996 0.028813779 0.074501589, -0.0073950216 -0.13909173 0.074492224, -0.007497713 -0.14097103 0.074492007, 0.047513291 0.13292557 0.074507505, -0.13741368 0.032326937 0.074501738, -0.13812765 0.029126525 0.074501656, 0.10279289 -0.093991578 0.07449466, 0.093333982 -0.083153427 0.074495241, 0.04441303 0.13399327 0.074507505, 0.021766551 -0.13757688 0.074492238, 0.021128744 -0.12320563 0.074493118, 0.019788399 -0.13787535 0.074492209, -0.13662568 0.035509706 0.074501947, 0.12375345 -0.067922652 0.07449618, 0.12529762 -0.065029979 0.074496433, 0.12210491 -0.067014813 0.074496239, -0.13395466 0.038155228 0.074502103, -0.13393635 0.038219422 0.074502073, -0.13391811 0.038283497 0.074502103, 0.097849339 -0.077789426 0.074495599, 0.11148205 -0.083501279 0.074495211, 0.014187545 -0.12419662 0.074493058, -0.13576394 0.03867349 0.07450211, -0.013379589 -0.13864401 0.074492209, -0.016742393 -0.14017397 0.074492231, -0.013482228 -0.14052501 0.074492127, 0.10205676 -0.07218051 0.074495986, 0.11266979 -0.081891537 0.07449539, 0.038677812 0.13575977 0.074507788, 0.035514086 0.13662142 0.074507624, 0.0062264651 -0.13914892 0.074492171, 0.0072017163 -0.12479675 0.074492872, 0.0042272881 -0.13922393 0.074492194, -0.019993462 -0.13974738 0.074492157, 0.12644082 -0.058422804 0.074496672, 0.12677415 -0.062102199 0.074496597, 0.12818222 -0.059141099 0.074496686, 0.032331228 0.13740936 0.074507624, 0.10594325 -0.066344678 0.07449621, 0.1201297 -0.070494175 0.074496031, -0.13292968 0.047509074 0.074502617, -0.13399735 0.044408649 0.074502498, 0.0001931563 -0.1250042 0.074492857, 0.029130861 0.13812333 0.074507788, -0.022921391 -0.13738921 0.074492246, -0.023233816 -0.13924515 0.074492171, -0.13179034 0.05058372 0.074502856, 0.13057987 -0.053639501 0.074497014, 0.13179037 -0.050592214 0.074497178, 0.12883988 -0.05292201 0.074497074, 0.10949632 -0.060299993 0.074496552, 0.1211298 -0.068761557 0.07449609, -0.13057986 0.053631037 0.074503019, -0.0068159774 -0.12481827 0.074493013, -0.0093919262 -0.13897115 0.074492186, -0.011386923 -0.13882193 0.074492209, -0.028818108 -0.13627428 0.074492231, -0.032331213 -0.137418 0.074492276, -0.029130884 -0.13813189 0.074492194, 0.023233846 0.1392366 0.074507803, 0.019993454 0.13973868 0.074507892, 0.1329298 -0.047517657 0.074497283, 0.13399751 -0.044417292 0.07449764, -0.035514072 -0.13662994 0.074492306, 0.11270482 -0.054065645 0.074497059, 0.12726673 -0.056600839 0.074496925, -0.013803564 -0.12423995 0.074493073, 0.016742468 0.14016542 0.07450781, -0.12677409 0.062093735 0.074503474, -0.12818219 0.059132546 0.074503377, -0.038159564 -0.13395897 0.074492574, -0.03867767 -0.13576835 0.074492425, 0.013482377 0.14051637 0.07450784, 0.11555886 -0.047661185 0.074497283, -0.12529771 0.065021515 0.074503824, 0.1280666 -0.054767132 0.074496865, -0.024892189 -0.13704583 0.074492268, -0.020747803 -0.12327027 0.074493006, -0.026857972 -0.13667417 0.074492298, 0.13576397 -0.038682044 0.074497893, 0.13662574 -0.035518229 0.074498117, -0.12375352 0.067914158 0.074503854, 0.11804913 -0.04110682 0.074497744, -0.027626723 -0.12191316 0.074493222, -0.043894328 -0.13219082 0.074492753, -0.047513254 -0.13293406 0.074492417, -0.04441312 -0.1340017 0.074492417, 0.0074977577 0.14096251 0.074507847, 0.0042215139 0.14109871 0.074507877, 0.13741374 -0.032335401 0.074498087, 0.1381276 -0.029135108 0.074498251, -0.050587945 -0.13179463 0.074492574, -0.034418762 -0.12017226 0.074493274, -0.040079586 -0.13339698 0.074492514, -0.041991301 -0.13280764 0.074492529, 0.0009431392 0.14115852 0.074508019, -0.052917726 -0.12884411 0.074492753, -0.053635292 -0.13058397 0.074492738, -0.11902427 0.075897574 0.074504301, -0.120755 0.073112398 0.074504063, 0.13924089 -0.023238003 0.074498728, 0.13974296 -0.019997865 0.074498937, -0.0023356974 0.14114219 0.074507996, -0.041102529 -0.11805344 0.074493453, -0.058418512 -0.12644508 0.074492894, -0.062098 -0.12677845 0.074492782, -0.059136614 -0.12818658 0.074492797, 0.14016968 -0.01674673 0.074499041, 0.14052075 -0.013486534 0.074499264, -0.11722919 0.078641444 0.074504465, -0.065025628 -0.12530196 0.074492976, -0.054762743 -0.12807083 0.074492767, -0.047656924 -0.11556298 0.074493468, -0.056596391 -0.12727109 0.074492864, -0.11537092 0.081343114 0.074504539, -0.067010477 -0.12210909 0.074493214, -0.067918405 -0.12375772 0.074493058, -0.0083326548 0.14091557 0.074508011, -0.011603519 0.14068395 0.07450778, -0.054061435 -0.11270905 0.074493676, 0.14096673 -0.0075018704 0.074499652, 0.1411029 -0.0042257905 0.074499771, -0.014868021 0.14037663 0.074507847, -0.072207995 -0.11910924 0.074493356, -0.075901613 -0.1190286 0.074493229, -0.07311672 -0.12075922 0.07449311, -0.10977751 0.088746727 0.074504972, -0.11180929 0.086173058 0.0745048, -0.068757258 -0.12113404 0.074493229, -0.060295735 -0.10950056 0.074493796, -0.070490003 -0.12013394 0.074493252, -0.018124402 0.13999328 0.07450787, 0.14116283 -0.00094735622 0.074499935, 0.14114664 0.0023315251 0.074500114, -0.078645624 -0.1172334 0.074493438, -0.10768647 0.091272354 0.074505106, -0.08026056 -0.11383849 0.074493706, -0.081347309 -0.11537504 0.074493654, -0.10553752 0.093748987 0.074505374, -0.066340387 -0.10594741 0.074494079, 0.14091985 0.0083284676 0.074500501, 0.14068836 0.011599332 0.074500591, -0.024058372 0.1390965 0.074507862, -0.027282625 0.13850018 0.074507765, -0.081887305 -0.112674 0.074493669, -0.072176337 -0.10206109 0.074494302, -0.08349701 -0.11148629 0.074493751, -0.030492194 0.13782927 0.074507631, -0.085089654 -0.1102756 0.074493825, -0.088750839 -0.1097818 0.074493855, -0.086177289 -0.11181352 0.074493706, 0.14038086 0.014863789 0.074500799, 0.13999772 0.018120199 0.074500978, -0.091276743 -0.10769075 0.074493855, -0.099150307 0.10047978 0.074505612, -0.10145749 0.098149866 0.0745055, -0.07778506 -0.097853601 0.074494451, -0.033685371 0.13708383 0.074507602, -0.096789651 0.10275549 0.074505709, -0.092501178 -0.10413647 0.074494213, -0.093753338 -0.10554177 0.074494094, -0.094376847 0.10497585 0.074506007, 0.13910079 0.02405411 0.074501351, 0.13850455 0.027278423 0.074501619, -0.093987361 -0.10279706 0.074494213, -0.083149254 -0.093338192 0.074494913, -0.095454022 -0.10143664 0.074494168, -0.042618647 0.13457471 0.074507639, -0.039481401 0.13552827 0.074507631, -0.096900925 -0.10005531 0.074494459, -0.10048413 -0.099154532 0.074494466, -0.098154061 -0.10146171 0.074494272, 0.13783348 0.030487865 0.074501619, 0.13708808 0.033681095 0.074501902, -0.10275987 -0.09679395 0.074494652, -0.088251695 -0.08852911 0.074495025, -0.045732975 0.13354844 0.07450752, -0.10357876 -0.093124837 0.074494645, -0.10498011 -0.094381154 0.0744946, 0.13553248 0.03947714 0.0745022, 0.13457896 0.042614371 0.074502394, -0.087276198 0.11094937 0.074506246, -0.089829646 0.10889223 0.074506208, -0.048822515 0.13245028 0.074507371, -0.093076505 -0.083441556 0.074495256, -0.084675662 0.11294648 0.074506246, -0.10490546 -0.091627598 0.074494943, -0.082029298 0.11488262 0.074506335, -0.10621067 -0.090111375 0.074494943, -0.057418771 0.12895665 0.074507214, -0.054407924 0.13025543 0.074507378, -0.10749394 -0.088576674 0.074495025, -0.11095351 -0.087280571 0.074495003, -0.10889658 -0.089833945 0.074494913, 0.1335528 0.045728683 0.074502558, 0.13245448 0.048818231 0.074502811, -0.060398482 0.12758827 0.074506983, -0.097608328 -0.078091383 0.074495606, -0.07430464 0.12002337 0.074506827, -0.077072412 0.11826536 0.074506648, -0.06334573 0.12615097 0.074507043, -0.11295061 -0.084679931 0.074495248, -0.071496695 0.12171689 0.074506819, -0.068650298 0.12334472 0.074506924, -0.11335361 -0.080942243 0.074495465, -0.11488697 -0.082033813 0.074495301, -0.10183316 -0.07249561 0.074495986, -0.11450449 -0.079305708 0.074495621, 0.13025974 0.054403663 0.074503019, 0.128961 0.057414383 0.074503154, -0.11563163 -0.077652931 0.074495703, -0.10573765 -0.066671818 0.07449618, -0.11673494 -0.07598421 0.074495599, -0.12002775 -0.074308842 0.074495673, -0.11826961 -0.077076524 0.074495628, 0.12759252 0.060394287 0.074503481, 0.12615532 0.063341349 0.074503615, -0.12172119 -0.071501046 0.074496128, -0.12170313 -0.067741692 0.07449609, -0.12334892 -0.068654627 0.074496195, -0.10930932 -0.060638249 0.074496582, -0.12266334 -0.065986782 0.074496202, 0.12334897 0.068646163 0.074503899, 0.12172127 0.071492463 0.074503958, -0.12359849 -0.064218074 0.074496493, -0.12615526 -0.063350022 0.074496418, 0.12002768 0.074300319 0.074504182, 0.11826952 0.07706818 0.074504375, -0.057418711 0.12896502 -0.074492753, -0.054407842 0.13026375 -0.074492775, 0.072491378 -0.10182911 -0.074505739, 0.080937982 -0.11334959 -0.074506424, 0.079301558 -0.11450034 -0.074506618, 0.084675707 -0.1129466 -0.074506387, 0.082029395 -0.11488289 -0.074506432, 0.078087233 -0.097604245 -0.074505545, -0.048822515 0.1324586 -0.074492522, -0.045732878 0.13355672 -0.074492522, 0.088572353 -0.10748982 -0.074505985, 0.08727625 -0.11094943 -0.074506335, -0.12334885 -0.068646282 -0.074503854, -0.12170316 -0.067733258 -0.074503928, -0.12172124 -0.071492612 -0.07450413, 0.089829706 -0.10889238 -0.074506178, 0.090107225 -0.1062066 -0.074506044, 0.083437376 -0.093072385 -0.074505262, -0.042618588 0.13458297 -0.07449244, -0.12759241 -0.060394466 -0.074503504, -0.12450798 -0.062428027 -0.074503519, -0.12615532 -0.063341558 -0.074503683, -0.12896088 -0.057414711 -0.074503325, 0.091623321 -0.10490143 -0.074505895, 0.093120575 -0.1035746 -0.074505903, -0.12002781 -0.074300408 -0.074504286, -0.11673488 -0.075975746 -0.074504301, -0.11826961 -0.07706809 -0.074504338, -0.039481372 0.13553658 -0.074492447, 0.0885249 -0.088247567 -0.074504934, -0.13025969 -0.054403901 -0.074503146, -0.12852201 -0.053680867 -0.074503034, 0.096789792 -0.10275576 -0.074505903, 0.094376877 -0.10497606 -0.074505873, -0.114887 -0.0820252 -0.074504599, -0.11335371 -0.08093369 -0.074504599, -0.11295065 -0.084671527 -0.074504867, -0.033685304 0.13709217 -0.074492291, -0.030492209 0.13783756 -0.074492179, 0.10005089 -0.096896887 -0.074505419, 0.099150285 -0.10047993 -0.074505731, 0.10145751 -0.098149985 -0.074505553, -0.13355269 -0.045728803 -0.074502587, -0.13071525 -0.048094898 -0.074502863, -0.13245447 -0.04881835 -0.074502841, -0.13457887 -0.04261452 -0.074502528, -0.10749389 -0.0885683 -0.074505091, -0.11095356 -0.087272108 -0.074504979, -0.10889652 -0.0898256 -0.074505039, 0.093333915 -0.083145112 -0.074504703, 0.10143237 -0.095449924 -0.074505359, -0.027282633 0.13850859 -0.074492171, 0.10279287 -0.093983173 -0.074505284, 0.10413225 -0.092497051 -0.074505314, -0.024058364 0.13910493 -0.074492209, -0.13372466 -0.038953453 -0.074502304, -0.13553238 -0.039477348 -0.074502312, 0.097849391 -0.077781022 -0.074504316, -0.10498016 -0.094372809 -0.074505255, -0.10357861 -0.093116492 -0.074505284, -0.10275982 -0.096785694 -0.074505441, 0.10768655 -0.091272533 -0.074505135, 0.1055376 -0.093749225 -0.07450521, -0.13783345 -0.030488044 -0.074501812, -0.13527873 -0.033156961 -0.074502006, -0.137088 -0.033681303 -0.074501954, -0.13850439 -0.027278602 -0.074501619, -0.09690094 -0.10004669 -0.07450562, -0.018124506 0.14000189 -0.074492112, -0.014867991 0.140385 -0.07449206, -0.10048398 -0.099146187 -0.074505553, -0.098153971 -0.10145336 -0.074505776, 0.11027138 -0.085085511 -0.074504882, 0.1097775 -0.088746816 -0.074505016, 0.11180928 -0.086173117 -0.074504927, 0.10205676 -0.072172135 -0.074504003, 0.11148207 -0.083492965 -0.074504703, -0.011603519 0.14069244 -0.074492075, -0.13910085 -0.024054229 -0.074501373, -0.13724583 -0.023736 -0.074501388, 0.11266984 -0.081883162 -0.074504748, -0.093753308 -0.10553333 -0.074506007, -0.092501253 -0.104128 -0.074506, -0.091276713 -0.10768244 -0.074506164, 0.10594327 -0.066336215 -0.07450369, 0.11383438 -0.080256522 -0.074504584, -0.0083327442 0.14092401 -0.074492082, -0.1403808 -0.014863908 -0.074500807, -0.13814089 -0.01780203 -0.074501172, -0.13999757 -0.018120378 -0.074500978, 0.11722922 -0.078641593 -0.07450445, 0.11537097 -0.081343144 -0.074504539, -0.14068814 -0.011599422 -0.074500814, -0.085089631 -0.11026713 -0.07450629, -0.088750869 -0.10977337 -0.074506238, -0.086177215 -0.11180517 -0.074506402, 0.11910495 -0.072203934 -0.074504003, 0.11902428 -0.075897634 -0.074504167, -0.0023357868 0.14115086 -0.074492067, 0.00094310939 0.14116699 -0.074492082, 0.12075506 -0.073112696 -0.074504241, 0.12012976 -0.070485771 -0.074503973, -0.14091986 -0.0083286166 -0.074500486, -0.13904074 -0.0082201064 -0.074500524, 0.10949633 -0.060291678 -0.074503377, 0.0042215586 0.14110696 -0.074492104, -0.081347331 -0.1153667 -0.074506432, -0.080260538 -0.11383021 -0.07450638, -0.078645714 -0.11722511 -0.074506588, -0.12266345 -0.065978169 -0.074503697, -0.10930932 -0.060629755 -0.074503399, -0.12359848 -0.064209759 -0.074503615, 0.1211298 -0.068753213 -0.074503854, 0.11270484 -0.054057211 -0.074503049, 0.12210485 -0.06700635 -0.074503779, 0.0074977279 0.14097086 -0.074492179, -0.10573763 -0.066663295 -0.07450375, -0.11563163 -0.077644557 -0.074504353, -0.11253722 -0.054405332 -0.074503019, 0.12529764 -0.065021515 -0.074503586, 0.12375347 -0.067914158 -0.074503914, 0.12644072 -0.05841434 -0.074503422, 0.1267741 -0.062093884 -0.074503526, -0.10183322 -0.072487265 -0.074504122, -0.11450435 -0.079297394 -0.074504554, 0.013482288 0.14052489 -0.074492075, 0.016742423 0.14017379 -0.074492067, 0.12818219 -0.059132606 -0.074503332, -0.1292797 -0.051829547 -0.074503064, -0.11541089 -0.048009723 -0.074502714, -0.13001096 -0.049967259 -0.074502848, 0.11555877 -0.047652692 -0.074502677, 0.12726679 -0.056592345 -0.074503168, 0.019993484 0.1397472 -0.074492082, 0.12806657 -0.054758608 -0.074503139, -0.097608373 -0.078082979 -0.074504361, 0.11804913 -0.041098356 -0.074502364, 0.1288399 -0.052913606 -0.074503019, 0.023233861 0.13924506 -0.074492328, -0.10621077 -0.090102881 -0.074505039, -0.11792148 -0.041463077 -0.074502312, -0.14116286 0.00094726682 -0.074500106, -0.13926616 -0.002223134 -0.074500039, -0.1411466 -0.0023316741 -0.074500173, 0.13179037 -0.05058381 -0.07450287, 0.1305799 -0.053631186 -0.07450299, -0.093076363 -0.083433241 -0.074504703, -0.10490556 -0.091619194 -0.074505076, -0.13427049 -0.037028849 -0.074502088, -0.12006096 -0.034785956 -0.074501991, -0.13478856 -0.035096496 -0.074502014, 0.13292973 -0.047509164 -0.074502632, 0.029130816 0.13813183 -0.074492313, 0.032331169 0.13741785 -0.074492335, -0.14110282 0.0042256415 -0.074499682, 0.13399751 -0.044408828 -0.074502528, -0.075901799 -0.11902007 -0.074506722, -0.072208136 -0.11910081 -0.074506707, -0.073116802 -0.1207509 -0.074506678, -0.088251673 -0.088520736 -0.074505016, -0.095453963 -0.10142821 -0.074505799, 0.035514012 0.13662991 -0.07449232, -0.12182285 -0.027999371 -0.0745015, -0.1390875 0.0073992312 -0.074499562, -0.14096665 0.0075019598 -0.074499682, -0.08314912 -0.093329787 -0.074505284, 0.038677901 0.13576806 -0.074492425, -0.093987301 -0.1027886 -0.074505828, -0.13757244 -0.021762431 -0.074501313, -0.12320136 -0.021124601 -0.074501164, -0.13787106 -0.019784153 -0.074501134, -0.06701044 -0.12210065 -0.074506819, -0.065025717 -0.12529343 -0.07450702, -0.067918368 -0.12374943 -0.074506998, 0.13662577 -0.035510004 -0.074501991, 0.13576394 -0.03867352 -0.074502185, -0.077785105 -0.097845167 -0.07450553, -0.083496988 -0.11147788 -0.074506283, -0.12419234 -0.014183313 -0.074500918, 0.13741376 -0.032327056 -0.074501857, -0.14052063 0.013486266 -0.07449916, -0.14016959 0.016746521 -0.074499071, -0.13863972 0.013383806 -0.074499346, 0.044413105 0.13400149 -0.07449241, 0.047513366 0.1329338 -0.074492499, -0.07217633 -0.10205263 -0.074505731, 0.13812765 -0.029126704 -0.074501693, -0.081887223 -0.11266556 -0.07450632, -0.12479242 -0.0071975589 -0.074500434, -0.13914469 -0.0062222779 -0.074500285, -0.13921982 -0.0042230487 -0.074500293, 0.050587937 0.13179445 -0.074492604, -0.13974294 0.019997656 -0.074498825, -0.058418587 -0.12643662 -0.074507155, -0.062097959 -0.12677005 -0.074507117, -0.059136696 -0.12817815 -0.07450714, 0.053635404 0.13058385 -0.074492753, -0.06634026 -0.10593912 -0.074505985, -0.070489995 -0.12012559 -0.074506707, -0.12499981 -0.00018891692 -0.074500062, -0.13924095 0.023237884 -0.074498691, -0.13738489 0.022925645 -0.07449875, 0.13974293 -0.019989341 -0.074501112, 0.13924089 -0.023229688 -0.074501276, -0.052917816 -0.12883574 -0.074507222, -0.050587907 -0.13178617 -0.07450746, -0.053635232 -0.13057575 -0.0745074, 0.1401697 -0.016738296 -0.074500993, -0.068757266 -0.12112567 -0.074506879, -0.060295746 -0.10949203 -0.074506156, -0.13896683 0.0093961358 -0.074499436, -0.12481403 0.0068199635 -0.074499734, -0.13881773 0.011391073 -0.074499406, 0.059136853 0.12818632 -0.074492782, 0.062097937 0.1267783 -0.074492946, -0.13812765 0.029134989 -0.07449843, -0.13741365 0.03233543 -0.07449811, -0.13627012 0.028822362 -0.0744984, 0.14052072 -0.013478041 -0.074500799, -0.047513299 -0.13292557 -0.07450743, -0.043894261 -0.1321823 -0.0745074, -0.044413067 -0.13399321 -0.074507572, -0.13662557 0.03551811 -0.074498154, 0.065025657 0.12530175 -0.074492827, -0.054061338 -0.1127007 -0.074506335, -0.056596525 -0.12726268 -0.074507184, -0.12423563 0.013807714 -0.074499257, 0.06791842 0.1237576 -0.07449314, -0.13395464 0.038163692 -0.074497998, -0.13576393 0.038681775 -0.074497961, -0.054762758 -0.12806246 -0.074507251, -0.047656953 -0.1155546 -0.074506596, -0.13704145 0.024896383 -0.074498616, -0.12326612 0.020751953 -0.07449884, 0.14110288 -0.0042174459 -0.074500293, 0.14096674 -0.0074935555 -0.074500427, -0.13666973 0.026862115 -0.074498542, -0.038159557 -0.13395044 -0.074507564, -0.035514042 -0.13662159 -0.074507751, -0.038677715 -0.13575995 -0.074507788, 0.14116284 -0.00093898177 -0.074500054, -0.041102476 -0.11804497 -0.074506566, -0.041991189 -0.1327993 -0.074507572, -0.12190894 0.027630866 -0.07449846, -0.13399738 0.044417083 -0.074497499, -0.13292971 0.047517538 -0.074497312, 0.073116735 0.12075925 -0.074493259, 0.075901747 0.11902827 -0.074493244, -0.028818093 -0.13626587 -0.074507736, -0.032331184 -0.13740951 -0.074507743, -0.029130861 -0.13812339 -0.074507765, -0.13179028 0.050592035 -0.074497245, 0.14114669 0.0023399591 -0.074499816, -0.040079512 -0.13338861 -0.074507579, -0.034418777 -0.12016398 -0.074506737, -0.13393638 0.038227737 -0.074498072, -0.13391799 0.038291812 -0.074497961, -0.13057977 0.053639323 -0.074497066, 0.078645721 0.11723334 -0.074493438, -0.022921354 -0.13738087 -0.074507795, -0.01999341 -0.13973895 -0.074507929, -0.023233742 -0.13923687 -0.074507788, -0.02762676 -0.12190464 -0.074506834, -0.026857994 -0.13666564 -0.074507758, 0.081347391 0.11537507 -0.074493513, -0.12818217 0.059140861 -0.074496679, -0.12677401 0.062102139 -0.074496612, -0.016742438 -0.14016557 -0.074507885, -0.013379499 -0.13863564 -0.074507855, -0.013482265 -0.14051655 -0.074507937, 0.14068836 0.011607677 -0.074499458, 0.14091991 0.0083368123 -0.074499533, -0.12529759 0.06502983 -0.074496299, -0.020747773 -0.12326196 -0.074506946, -0.024892159 -0.13703746 -0.074507751, 0.14038089 0.014872193 -0.07449922, 0.086177319 0.1118134 -0.074493751, 0.088750914 0.10978171 -0.07449384, -0.12375344 0.067922384 -0.074496262, -0.013803497 -0.12423143 -0.074506976, -0.011386879 -0.13881356 -0.074507765, 0.13999771 0.018128663 -0.074499056, -0.007395044 -0.13908327 -0.074507914, -0.0042214468 -0.14109886 -0.074507847, -0.0074977651 -0.14096257 -0.074508011, 0.09127678 0.10769069 -0.07449393, -0.12075502 0.073120862 -0.074495971, -0.11902415 0.075905859 -0.07449571, -0.0093919635 -0.13896272 -0.07450781, -0.0068159252 -0.12480986 -0.07450702, 0.093753278 0.1055415 -0.074494094, -0.00094300508 -0.1411587 -0.074507974, 0.0022272766 -0.13926196 -0.074507885, 0.0023357794 -0.14114237 -0.074507914, -0.11722924 0.078649819 -0.074495606, 0.13850452 0.027286738 -0.074498519, 0.1391008 0.024062455 -0.074498624, -0.11537086 0.081351399 -0.074495502, 0.00019317865 -0.12499568 -0.074507013, 0.0042272881 -0.13921565 -0.074507713, 0.13783354 0.03049621 -0.074498311, 0.0082242265 -0.13903672 -0.074507855, 0.011603549 -0.14068413 -0.0745079, 0.008332774 -0.14091578 -0.074507892, 0.098154068 0.10146153 -0.074494228, 0.1004841 0.099154472 -0.074494481, 0.0072017163 -0.12478834 -0.074507087, 0.0062264949 -0.13914055 -0.074507736, 0.13708811 0.033689439 -0.074498162, 0.10275987 0.09679383 -0.074494526, -0.11180927 0.086181402 -0.07449507, -0.10977755 0.088755101 -0.074495062, 0.014868058 -0.14037663 -0.074507877, 0.017806247 -0.13813704 -0.074507818, 0.01812461 -0.13999349 -0.0745079, 0.10498025 0.094380945 -0.07449472, -0.1076866 0.091280907 -0.074494839, 0.014187552 -0.12418813 -0.074506953, 0.019788399 -0.13786691 -0.07450778, 0.13457893 0.042622834 -0.0744977, -0.10553742 0.093757451 -0.074494831, 0.13553248 0.039485604 -0.074497834, 0.02374021 -0.13724157 -0.074507825, 0.027282685 -0.13850039 -0.074507758, 0.024058282 -0.13909668 -0.074507907, 0.021766566 -0.13756841 -0.07450778, 0.021128744 -0.12319735 -0.074506857, 0.13355279 0.045737088 -0.074497402, -0.10145747 0.09815824 -0.07449457, -0.099150248 0.10048822 -0.074494444, 0.033161066 -0.13527459 -0.074507728, 0.030492179 -0.1378293 -0.074507765, 0.033685364 -0.13708404 -0.074507684, -0.096789636 0.10276401 -0.07449425, 0.10889649 0.089833915 -0.074495092, 0.11095352 0.087280422 -0.074495167, 0.028003424 -0.12181878 -0.074506886, 0.035100669 -0.13478437 -0.074507609, 0.13245454 0.048826665 -0.074497327, 0.11295083 0.084679872 -0.074495271, 0.11488701 0.082033604 -0.07449545, -0.094376817 0.10498437 -0.074494109, 0.12896098 0.057422876 -0.074496806, 0.13025981 0.054412127 -0.074496984, 0.038957626 -0.13372073 -0.07450752, 0.042618692 -0.13457468 -0.074507557, 0.039481468 -0.13552833 -0.074507773, 0.037032939 -0.13426641 -0.074507602, 0.034790039 -0.12005702 -0.074506715, 0.1275925 0.060402721 -0.074496567, 0.11826952 0.077076435 -0.074495628, 0.12002778 0.074308753 -0.074495792, 0.12615527 0.063349843 -0.074496552, 0.12172118 0.071500987 -0.074496001, 0.123349 0.068654537 -0.074496105, -0.08982975 0.10890076 -0.074493796, -0.087276228 0.11095768 -0.07449387, 0.048098937 -0.13071108 -0.074507333, 0.045732968 -0.13354865 -0.074507579, 0.048822597 -0.1324504 -0.07450743, 0.041467153 -0.11791733 -0.0745067, 0.049971417 -0.13000685 -0.074507371, -0.084675618 0.11295477 -0.074493624, -0.082029358 0.11489114 -0.074493557, 0.051833652 -0.12927568 -0.074507274, 0.048013948 -0.11540678 -0.074506558, 0.053685024 -0.12851799 -0.074507184, 0.057418711 -0.12895676 -0.074507304, 0.054407991 -0.1302557 -0.07450743, 0.054409593 -0.11253309 -0.074506342, -0.077072397 0.11827376 -0.074493356, -0.074304648 0.12003198 -0.074493341, 0.062432006 -0.12450385 -0.074507065, 0.060398616 -0.12758839 -0.074507177, 0.063345708 -0.12615106 -0.07450705, 0.064213894 -0.12359437 -0.074506976, -0.071496703 0.12172538 -0.074493267, -0.068650246 0.12335321 -0.074493133, 0.060633972 -0.10930526 -0.074506164, 0.065982468 -0.1226593 -0.074506998, 0.067737348 -0.12169886 -0.074506857, 0.07149677 -0.12171707 -0.074506871, 0.068650365 -0.12334481 -0.074506983, 0.066667601 -0.10573348 -0.074505962, -0.063345715 0.12615946 -0.074492909, -0.060398422 0.12759653 -0.074492842, 0.075979911 -0.11673081 -0.074506558, 0.074304603 -0.12002358 -0.074506834, 0.077072345 -0.11826527 -0.074506767, 0.077648759 -0.11562744 -0.074506558, 0.027211167 -0.13986304 0.074316107, 0.027116083 -0.14112678 0.073800012, 0.028269656 -0.14084879 0.073829383, 0.027782537 -0.13972202 0.074323706, 0.02996435 -0.14144728 0.073142938, 0.030786902 -0.14104855 0.07333453, 0.029903591 -0.14051107 0.07382936, 0.029126883 -0.14140084 0.073334552, 0.029550739 -0.14164084 0.073042721, 0.028727815 -0.14180997 0.073042654, 0.028146416 -0.14194748 0.073022112, 0.026981868 -0.1422151 0.07298062, 0.032474406 -0.13850737 0.074371316, 0.034039259 -0.13813776 0.074369833, 0.034465589 -0.13909748 0.07401403, 0.034002431 -0.1403822 0.073273472, 0.034941085 -0.13992855 0.073450491, 0.035393253 -0.14054006 0.072790124, 0.032534122 -0.13980573 0.073894076, 0.033530615 -0.14060304 0.073180363, 0.031562962 -0.14014769 0.073829368, 0.029031076 -0.1398907 0.074193917, 0.026066437 -0.14013776 0.074300475, 0.025531821 -0.14034334 0.074269101, 0.024458393 -0.14074567 0.074199602, 0.024800561 -0.14165297 0.07374002, 0.024232723 -0.13994592 0.074417949, 0.026401088 -0.14231169 0.072993018, 0.025238551 -0.14249766 0.073017672, 0.031515554 -0.13886148 0.074340455, 0.03103473 -0.1390357 0.074323736, 0.030212119 -0.13921675 0.074323736, 0.030663639 -0.13954201 0.074193925, 0.029819854 -0.13944376 0.074284501, 0.028198354 -0.13978067 0.074284397, 0.042699195 -0.13593683 0.074316382, 0.043251269 -0.13573289 0.074323967, 0.04386159 -0.13679805 0.073829643, 0.045612529 -0.13720301 0.073143214, 0.046385296 -0.1367147 0.073334657, 0.04544729 -0.13627937 0.073829636, 0.044775091 -0.13725054 0.073334798, 0.045223258 -0.13744152 0.07304287, 0.0444244 -0.13770187 0.07304284, 0.043862097 -0.13790366 0.073022284, 0.042746305 -0.13720325 0.073800303, 0.04273475 -0.13829976 0.072980836, 0.04777766 -0.13400045 0.074371517, 0.04929135 -0.13345805 0.074370116, 0.049822375 -0.13436392 0.074014373, 0.049506046 -0.13569257 0.073273614, 0.050387904 -0.1351366 0.073450856, 0.050905727 -0.13569364 0.07279034, 0.047982372 -0.13528413 0.073894367, 0.049061783 -0.13596484 0.073180601, 0.047055595 -0.1357325 0.073829629, 0.044510901 -0.13576066 0.074194103, 0.041592509 -0.13633811 0.074300699, 0.041084215 -0.13660225 0.074269384, 0.040062778 -0.13712233 0.074199803, 0.040504262 -0.13798544 0.073740087, 0.039748847 -0.13635281 0.07441818, 0.042168468 -0.13846093 0.072993338, 0.041034073 -0.13877591 0.073017888, 0.046864495 -0.13445976 0.074340686, 0.046406247 -0.13468674 0.07432393, 0.045609064 -0.13495874 0.074323975, 0.04609409 -0.13523132 0.074194126, 0.045244634 -0.13522831 0.074284621, 0.043671101 -0.13574451 0.074284628, -0.0045925826 -0.14241144 0.074316002, -0.00576967 -0.14242464 0.074300364, -0.0049665496 -0.14362234 0.073800042, -0.003779985 -0.14360815 0.073829181, -0.0040041655 -0.14240125 0.07432349, -0.0022609457 -0.1445688 0.073142819, -0.0013703331 -0.14436302 0.073334299, -0.0021118745 -0.14364243 0.073829025, -0.0030671507 -0.14433682 0.073334329, -0.0027072579 -0.1446653 0.073042504, -0.0035472512 -0.14464724 0.07304243, -0.0041446164 -0.14465174 0.073021963, -0.0053395331 -0.14465353 0.072980538, 0.00084035099 -0.142261 0.074371062, 0.0024482757 -0.14224896 0.07436952, 0.0026502684 -0.14327934 0.074013688, 0.0019129887 -0.14442894 0.073273033, 0.0029289126 -0.1441955 0.073450349, 0.003233701 -0.14489233 0.072789855, 0.00060966611 -0.1435402 0.073893897, 0.0014036819 -0.14453927 0.073180288, -0.00041324645 -0.14365721 0.073829263, -0.0028242841 -0.14284357 0.074193634, -0.0063366592 -0.14250606 0.074269138, -0.0074726939 -0.14265957 0.074199528, -0.00734099 -0.14362025 0.073739856, -0.0075149387 -0.14182952 0.07441777, -0.0059271455 -0.14461851 0.072992958, -0.0071019977 -0.14454108 0.073017634, -0.00017327815 -0.1423929 0.074340209, -0.0006807819 -0.14245579 0.074323505, -0.0015229955 -0.14244926 0.07432349, -0.0011552721 -0.14286673 0.074193649, -0.0019560456 -0.14258331 0.074284397, -0.003611818 -0.14255089 0.074284397, 0.011380889 -0.14203027 0.074315943, 0.012322366 -0.14312842 0.073829174, 0.011964336 -0.14195409 0.074323587, 0.013939366 -0.14391279 0.073142931, 0.014801353 -0.14360875 0.073334418, 0.013983697 -0.14297575 0.073829241, 0.013112374 -0.14377287 0.073334321, 0.013506658 -0.14405873 0.073042579, 0.012669966 -0.14413476 0.07304249, 0.012076899 -0.1442064 0.073021978, 0.011144929 -0.14327535 0.07380005, 0.010889664 -0.14434174 0.072980538, 0.016762801 -0.14127254 0.074371085, 0.018359236 -0.14108029 0.074369669, 0.018675283 -0.14208171 0.074013941, 0.018071398 -0.14330673 0.073273391, 0.01905477 -0.14296094 0.073450424, 0.019435607 -0.14361915 0.072789848, 0.016676664 -0.14256942 0.073893994, 0.017577708 -0.14347327 0.073180303, 0.015673421 -0.14280036 0.073829241, 0.013186254 -0.14226162 0.074193671, 0.010212496 -0.14217514 0.074300364, 0.0096582472 -0.14231944 0.074268967, 0.0085466579 -0.14259923 0.074199528, 0.008784987 -0.14353898 0.073739722, 0.0084117949 -0.14177918 0.07441777, 0.010301724 -0.14437291 0.072992988, 0.0091256276 -0.14442754 0.073017634, 0.015770294 -0.14151695 0.074340366, 0.015272997 -0.14163625 0.074323513, 0.014435358 -0.14172408 0.074323528, 0.014847532 -0.1420978 0.074193843, 0.014020085 -0.14190573 0.074284367, 0.012371197 -0.14205909 0.074284412, 0.085198924 -0.11420611 0.074317575, 0.084286742 -0.11495048 0.074301921, 0.085661478 -0.11538598 0.073801495, 0.086580306 -0.11463499 0.073830821, 0.085652485 -0.11383119 0.07432504, 0.088366844 -0.11443898 0.073144622, 0.088935003 -0.11372289 0.073336057, 0.087905832 -0.11362189 0.073830783, 0.087592095 -0.1147604 0.073335916, 0.088078104 -0.11479279 0.07304401, 0.087410048 -0.11530226 0.073044173, 0.086945981 -0.11567837 0.07302352, 0.08601281 -0.11642474 0.072982199, 0.089352705 -0.11070108 0.07437285, 0.090602323 -0.10968912 0.074371442, 0.091402598 -0.11036885 0.074015588, 0.091543011 -0.11172736 0.07327503, 0.092191733 -0.11091128 0.073452175, 0.092864551 -0.11126614 0.072791889, 0.089969911 -0.11184517 0.073895521, 0.091213644 -0.11213109 0.073182061, 0.089243159 -0.11257434 0.073830955, 0.086850636 -0.11344141 0.07419531, 0.083894119 -0.11536747 0.074270666, 0.083101824 -0.1161958 0.074200973, 0.083803669 -0.1168648 0.073741235, 0.082551248 -0.11557326 0.074419364, 0.085531436 -0.11676377 0.072994478, 0.08456476 -0.11743581 0.073019072, 0.088642456 -0.11143613 0.074341945, 0.088284902 -0.1118018 0.074325264, 0.08762233 -0.11232179 0.074325152, 0.088170111 -0.11241895 0.074195452, 0.087367356 -0.11269659 0.074286059, 0.086052559 -0.11370352 0.074285828, 0.097449675 -0.10394874 0.074318007, 0.098870546 -0.10422039 0.073831409, 0.097858481 -0.10352546 0.07432577, 0.10062382 -0.10382554 0.073145181, 0.10110817 -0.10305032 0.073336691, 0.10007422 -0.10306513 0.073831484, 0.099889942 -0.10423163 0.073336631, 0.10037653 -0.10420939 0.073044777, 0.099769704 -0.10479051 0.073044732, 0.099350788 -0.10521632 0.073024109, 0.09804146 -0.1050694 0.073802114, 0.098506927 -0.10606235 0.072982863, 0.10118501 -0.10000089 0.074373409, 0.10231341 -0.098855287 0.074372128, 0.10318485 -0.099441081 0.074016184, 0.10347639 -0.1007753 0.073275641, 0.10402964 -0.099891871 0.073452771, 0.10473794 -0.10016894 0.072792351, 0.10192641 -0.10106835 0.073896229, 0.10319431 -0.10121331 0.073182657, 0.10128584 -0.1018745 0.073831499, 0.099005453 -0.10300401 0.074196041, 0.096626706 -0.10479048 0.074302375, 0.096283309 -0.10524893 0.074271217, 0.095588557 -0.10616082 0.074201599, 0.096360922 -0.10674688 0.073741853, 0.09497188 -0.10560378 0.074419945, 0.098066546 -0.10645312 0.072995126, 0.097181238 -0.10722917 0.073019788, 0.10056151 -0.1008108 0.074342564, 0.10024717 -0.10121411 0.0743258, 0.099647 -0.10180497 0.07432574, 0.10020219 -0.10184014 0.07419607, 0.099435516 -0.10220587 0.074286535, 0.098241851 -0.1033538 0.074286491, 0.057650439 -0.13030148 0.074316598, 0.056595519 -0.13082412 0.074301101, 0.057838842 -0.13155451 0.073800698, 0.058901861 -0.13102698 0.073829897, 0.05817613 -0.13003674 0.07432422, 0.060687132 -0.13123336 0.073143654, 0.061400466 -0.13066152 0.073335201, 0.060419515 -0.13033399 0.073829912, 0.059860364 -0.13137445 0.073335208, 0.060326949 -0.13151389 0.073043287, 0.059562266 -0.13186216 0.073043175, 0.059026115 -0.13212544 0.073022619, 0.057950243 -0.13264546 0.072981223, 0.06248007 -0.12780851 0.074371919, 0.063923523 -0.12710011 0.074370332, 0.064552605 -0.12794083 0.074014574, 0.064386979 -0.12929633 0.073273934, 0.065201148 -0.12864533 0.073451251, 0.065777965 -0.12914079 0.072790824, 0.062827267 -0.12906116 0.07389468, 0.063976102 -0.1296168 0.073181003, 0.061956428 -0.12961045 0.073829986, 0.059430949 -0.12992346 0.074194483, 0.056120001 -0.13114327 0.074269749, 0.055163115 -0.13177463 0.074200146, 0.055698641 -0.13258299 0.073740475, 0.054765031 -0.13104507 0.074418493, 0.057405598 -0.13286892 0.072993606, 0.056313545 -0.13330892 0.07301829, 0.061624028 -0.12836719 0.074340999, 0.061194032 -0.12864405 0.074324213, 0.060432427 -0.12900349 0.074324235, 0.060944848 -0.12922019 0.074194506, 0.060100459 -0.12931216 0.074285008, 0.058594562 -0.13000146 0.074285023, 0.071876496 -0.12302729 0.074317008, 0.070886798 -0.12366471 0.074301347, 0.072204217 -0.12425154 0.073801041, 0.072369315 -0.12270552 0.074324667, 0.073201396 -0.12360829 0.073830329, 0.074998498 -0.12361342 0.073144011, 0.075643368 -0.1229654 0.073335506, 0.074631885 -0.12274969 0.073830336, 0.074192762 -0.12384602 0.073335528, 0.074672103 -0.12393254 0.073043644, 0.073951133 -0.12436417 0.073043577, 0.073447816 -0.12468588 0.073023058, 0.072436996 -0.12532312 0.072981566, 0.076396734 -0.12000942 0.074372344, 0.077751763 -0.11914372 0.074370816, 0.07847102 -0.11990872 0.074015237, 0.078458391 -0.12127438 0.073274449, 0.079194337 -0.120536 0.073451661, 0.079823136 -0.12096396 0.072791189, 0.07688202 -0.12121531 0.073895171, 0.078085914 -0.1216388 0.073181517, 0.076078206 -0.12185857 0.07383047, 0.073603578 -0.1224525 0.074194893, 0.07045003 -0.12403521 0.074270077, 0.069569901 -0.12476978 0.074200466, 0.070192456 -0.12551293 0.073740855, 0.069092706 -0.12408936 0.07441885, 0.071920745 -0.12560609 0.072994091, 0.070884891 -0.12616575 0.07301861, 0.075608671 -0.12066031 0.074341446, 0.075212419 -0.12098354 0.074324712, 0.074495867 -0.12142628 0.074324712, 0.075029291 -0.12158397 0.074194998, 0.074200414 -0.12176999 0.074285455, 0.072781198 -0.12262347 0.074285455, -0.020508207 -0.14100188 0.074315973, -0.021679483 -0.14088333 0.074300461, -0.021015331 -0.14216337 0.073800042, -0.01983469 -0.14228198 0.073829383, -0.019922346 -0.14105755 0.074323624, -0.018432885 -0.14340666 0.073142827, -0.017524779 -0.14330193 0.073334306, -0.018181048 -0.14250275 0.073829234, -0.019208014 -0.14308605 0.073334426, -0.01888714 -0.14345255 0.073042601, -0.019719832 -0.14334056 0.073042512, -0.020313919 -0.1432783 0.073021919, -0.021501534 -0.14314616 0.072980605, -0.015092686 -0.1414606 0.074371092, -0.013493419 -0.14162874 0.074369527, -0.013408102 -0.14267525 0.074013837, -0.014269583 -0.14373505 0.073273242, -0.013233729 -0.14361683 0.073450305, -0.013009012 -0.14434326 0.072789878, -0.015465081 -0.14270607 0.073893875, -0.014787823 -0.14378771 0.073180273, -0.016494736 -0.14270768 0.073829241, -0.018799514 -0.14162907 0.074193768, -0.022252016 -0.14090052 0.074269079, -0.023398094 -0.14092594 0.07419949, -0.023374811 -0.14189515 0.073739856, -0.02334702 -0.14009649 0.074418016, -0.022081636 -0.1430456 0.072993018, -0.023240343 -0.1428372 0.073017627, -0.01611457 -0.14147821 0.074340314, -0.016625933 -0.14148396 0.074323483, -0.017462246 -0.14138308 0.07432352, -0.017143518 -0.14183915 0.074193604, -0.017907508 -0.14146775 0.074284352, -0.019549161 -0.14125025 0.074284397, -0.03616605 -0.13781908 0.074316114, -0.03731662 -0.13756996 0.074300572, -0.036800161 -0.13891631 0.073800273, -0.035639994 -0.13916656 0.073829502, -0.03559012 -0.13793993 0.074323751, -0.034373023 -0.140441 0.073142968, -0.033458956 -0.14043874 0.073334515, -0.0340214 -0.13957116 0.073829465, -0.035107225 -0.14003587 0.073334634, -0.03482949 -0.14043587 0.073042735, -0.0356443 -0.14023131 0.073042676, -0.036227748 -0.14010295 0.073022112, -0.037393123 -0.1398387 0.072980851, -0.030835778 -0.13888133 0.074371174, -0.029265553 -0.13922742 0.074369863, -0.02929794 -0.14027691 0.074014001, -0.030272558 -0.1412335 0.073273405, -0.029229999 -0.1412321 0.073450424, -0.029087931 -0.14197928 0.072789945, -0.03134539 -0.14007714 0.073894046, -0.030793488 -0.14122772 0.073180385, -0.032368764 -0.13996366 0.073829494, -0.034538336 -0.13863379 0.074193962, -0.037887447 -0.13752317 0.074269392, -0.039029129 -0.13742018 0.074199736, -0.03911458 -0.13838592 0.073740095, -0.038885556 -0.13660154 0.074418187, -0.037958376 -0.1396738 0.072993323, -0.039086469 -0.13933691 0.073017918, -0.03185343 -0.13878435 0.074340507, -0.0323622 -0.13873273 0.074323609, -0.033181779 -0.13853902 0.074323758, -0.032916196 -0.1390278 0.074193999, -0.033633776 -0.13857326 0.074284501, -0.035240814 -0.13817334 0.074284516, -0.051369146 -0.13290319 0.074316397, -0.052121863 -0.13392255 0.073800482, -0.050997153 -0.13430116 0.073829748, -0.050810233 -0.13308775 0.074323975, -0.049880721 -0.13570952 0.07314343, -0.048972063 -0.13580966 0.073334754, -0.049434103 -0.13488442 0.073829651, -0.050564975 -0.13522455 0.073334873, -0.050333887 -0.1356532 0.073042929, -0.05112084 -0.1353586 0.073043093, -0.051686101 -0.13516584 0.073022403, -0.052814506 -0.13477266 0.072981171, -0.046191156 -0.13455564 0.074371539, -0.044669531 -0.1350753 0.074369945, -0.044819303 -0.1361146 0.074014232, -0.045894809 -0.13695607 0.073273465, -0.044858783 -0.13707134 0.073450632, -0.04480122 -0.13782972 0.072790243, -0.046831496 -0.1356869 0.073894352, -0.046411939 -0.13689208 0.073180601, -0.047835715 -0.13545936 0.073829547, -0.049842767 -0.13389498 0.074194267, -0.052484438 -0.13252687 0.074301139, -0.053046517 -0.13241649 0.074269719, -0.054169446 -0.1321862 0.074200153, -0.054362454 -0.13313633 0.07374046, -0.053935044 -0.13138902 0.074418426, -0.053357609 -0.13454556 0.072993398, -0.054441012 -0.13408464 0.073018156, -0.047191471 -0.13434526 0.074340753, -0.047691233 -0.13423714 0.074323982, -0.048484117 -0.13395277 0.0743239, -0.048274852 -0.1344682 0.074194238, -0.048937179 -0.13393623 0.074284777, -0.050489299 -0.13335875 0.074284598, -0.06592603 -0.12631607 0.074316785, -0.066992342 -0.12581718 0.074301176, -0.066788279 -0.12724468 0.073800921, -0.065713003 -0.12774694 0.07383009, -0.065391302 -0.12656209 0.074324332, -0.06476149 -0.12927118 0.073143639, -0.063869521 -0.12947249 0.07333523, -0.064225093 -0.12850136 0.073830068, -0.065387085 -0.12871277 0.07333523, -0.065205351 -0.12916458 0.073043436, -0.065954298 -0.12878379 0.073043406, -0.066494435 -0.12852886 0.073022768, -0.067571849 -0.12801206 0.072981574, -0.060965732 -0.1285378 0.074371845, -0.059511799 -0.12922466 0.074370362, -0.059776913 -0.13024071 0.074014626, -0.060940012 -0.13095647 0.073273838, -0.059923451 -0.13118678 0.073450983, -0.059951127 -0.13194695 0.072790459, -0.061728589 -0.12959018 0.07389465, -0.061446596 -0.13083482 0.073180959, -0.062701084 -0.12925178 0.073829964, -0.064520292 -0.12747252 0.074194476, -0.06753844 -0.12564448 0.074269958, -0.068628483 -0.12529004 0.074200436, -0.068926677 -0.12621251 0.07374084, -0.068306416 -0.12452385 0.074418783, -0.068085968 -0.12772554 0.07299383, -0.069110908 -0.12714607 0.073018491, -0.061936311 -0.12821674 0.074340977, -0.062420748 -0.12805328 0.074324355, -0.063176841 -0.12768194 0.07432434, -0.063026607 -0.12821767 0.074194476, -0.063625008 -0.12761471 0.074285068, -0.065102771 -0.12686718 0.074285209, -0.10394458 -0.097453773 0.074318349, -0.10506518 -0.098045647 0.073802412, -0.1042162 -0.098874688 0.073831841, -0.10352129 -0.097862631 0.074325956, -0.10382144 -0.10062793 0.073145315, -0.10304604 -0.10111243 0.073336691, -0.10306083 -0.1000784 0.07383164, -0.10422742 -0.099894106 0.073336713, -0.10420515 -0.10038066 0.073044844, -0.10478631 -0.099773824 0.073044889, -0.10521185 -0.099354953 0.073024467, -0.10605812 -0.09851104 0.072983176, -0.099996597 -0.10118911 0.074373469, -0.09885098 -0.10231763 0.07437183, -0.099436857 -0.10318905 0.074016169, -0.10077105 -0.10348046 0.073275521, -0.099887609 -0.10403377 0.073452547, -0.10016474 -0.10474208 0.072792083, -0.10106422 -0.10193062 0.073896095, -0.10120901 -0.10319856 0.073182479, -0.10187027 -0.10128999 0.073831677, -0.10299976 -0.099009752 0.074196212, -0.1047863 -0.096630901 0.074302882, -0.10524467 -0.096287429 0.074271575, -0.10615656 -0.095592856 0.074202135, -0.10674262 -0.096365184 0.073742315, -0.10559942 -0.094976187 0.074420393, -0.10644892 -0.098070621 0.072995543, -0.10722497 -0.097185254 0.073020235, -0.10080649 -0.10056564 0.074342579, -0.10120979 -0.10025126 0.074325785, -0.10180081 -0.099651277 0.074325889, -0.10183598 -0.1002064 0.074196145, -0.10220176 -0.09943974 0.074286677, -0.10334957 -0.098246187 0.07428664, -0.11420192 -0.085202962 0.074319087, -0.11538179 -0.085665584 0.073803172, -0.11463082 -0.086584508 0.073832445, -0.11382711 -0.085656583 0.074326769, -0.11443479 -0.088370949 0.07314603, -0.11371872 -0.088939279 0.073337384, -0.11361756 -0.087909877 0.073832318, -0.1147562 -0.087596238 0.073337376, -0.11478845 -0.088082284 0.073045731, -0.115298 -0.087414294 0.073045664, -0.11567423 -0.086950153 0.073025167, -0.11642067 -0.086016834 0.072983921, -0.11069688 -0.089357018 0.07437402, -0.10968491 -0.09060657 0.07437247, -0.11036464 -0.091406882 0.07401675, -0.11172324 -0.091547072 0.073276207, -0.11090721 -0.092195779 0.073453173, -0.1112619 -0.092868567 0.072792739, -0.11184098 -0.089974076 0.073896877, -0.1121269 -0.091217816 0.073183276, -0.11257017 -0.089247406 0.073832303, -0.11343728 -0.086854905 0.074196763, -0.11494609 -0.084290892 0.074303627, -0.11536324 -0.083898455 0.074272215, -0.11619172 -0.083106041 0.074202836, -0.11686053 -0.083807826 0.073743284, -0.11556901 -0.082555562 0.074421197, -0.11675961 -0.085535616 0.072996274, -0.11743164 -0.084568888 0.07302098, -0.11143194 -0.088646621 0.074343339, -0.11179753 -0.088289052 0.074326664, -0.11231753 -0.087626636 0.074326694, -0.11241469 -0.088174313 0.074196704, -0.11269239 -0.087371498 0.074287474, -0.11369945 -0.086056739 0.074287355, -0.092380002 -0.1084792 0.07431785, -0.09191367 -0.1088379 0.074325345, -0.092490867 -0.10992146 0.073831141, -0.091902159 -0.11161971 0.073144689, -0.09107773 -0.11201409 0.073336221, -0.091208026 -0.11098832 0.073831081, -0.092387982 -0.11093578 0.073336273, -0.092311285 -0.11141688 0.073044382, -0.092956752 -0.11087888 0.073044404, -0.09342663 -0.11051005 0.073023856, -0.093427353 -0.10919279 0.073801719, -0.094361976 -0.10976636 0.072982632, -0.088038631 -0.11174899 0.074372813, -0.086773947 -0.11274204 0.074371308, -0.087258607 -0.11367369 0.074015588, -0.088551827 -0.11411265 0.073274828, -0.087611839 -0.11456358 0.073451951, -0.08780808 -0.11529839 0.072791532, -0.089016572 -0.1126053 0.073895544, -0.089018598 -0.11388138 0.073182017, -0.089889303 -0.11205906 0.073830791, -0.09126702 -0.10991946 0.074195564, -0.093308769 -0.10775569 0.074302241, -0.09380272 -0.10746562 0.074270979, -0.094786629 -0.10687757 0.074201502, -0.095282629 -0.1077106 0.073741853, -0.094302058 -0.1062023 0.074419774, -0.094799623 -0.10937268 0.072994776, -0.095669843 -0.10857967 0.073019594, -0.088913396 -0.11122006 0.074341998, -0.089349285 -0.11095294 0.074325264, -0.090003714 -0.11042279 0.074325293, -0.089976497 -0.11097831 0.074195445, -0.090425804 -0.11025742 0.074286066, -0.091700301 -0.10919982 0.07428617, -0.079653867 -0.11814043 0.074317247, -0.079602458 -0.11958602 0.073830456, -0.079150245 -0.11844471 0.074324846, -0.078827441 -0.12120759 0.073144153, -0.077963829 -0.12150732 0.073335707, -0.078208327 -0.12050241 0.073830456, -0.079386607 -0.12058243 0.073335633, -0.079256624 -0.12105185 0.073043905, -0.07995823 -0.12058961 0.073043704, -0.080466494 -0.12027574 0.073023319, -0.080614656 -0.11896673 0.073801234, -0.081479162 -0.11964142 0.072981954, -0.074973568 -0.12090343 0.074372321, -0.073605776 -0.12174878 0.074370697, -0.073982924 -0.12272877 0.074014798, -0.075218856 -0.12330985 0.073274352, -0.074234478 -0.1236527 0.073451303, -0.074346952 -0.124405 0.072790921, -0.075849645 -0.12186387 0.073895261, -0.075708747 -0.12313226 0.073181435, -0.076777965 -0.12141892 0.073830463, -0.07838653 -0.11944693 0.074194983, -0.080657735 -0.1175254 0.074301712, -0.081180975 -0.11729255 0.074270517, -0.082224481 -0.11681825 0.074201033, -0.082624078 -0.11770171 0.073741257, -0.081818715 -0.11609304 0.074419364, -0.081958175 -0.11929899 0.072994269, -0.082911871 -0.11860865 0.073019117, -0.075902015 -0.12047598 0.074341543, -0.076365262 -0.12025908 0.074324816, -0.07707493 -0.11980551 0.074324816, -0.076985635 -0.12035474 0.074195087, -0.07751286 -0.11968863 0.074285507, -0.078897566 -0.11878037 0.074285641, 0.13029717 0.057646245 0.074327126, 0.13155037 0.057834595 0.073811263, 0.13102271 0.058897704 0.073840573, 0.13003254 0.058171898 0.074334815, 0.13122921 0.060682982 0.073154405, 0.13247496 0.060123712 0.072027996, 0.13101608 0.063239694 0.07202816, 0.13065743 0.061396182 0.073345989, 0.13032983 0.060415328 0.073840678, 0.13137005 0.059856206 0.07334581, 0.1315098 0.060322791 0.073054031, 0.13185789 0.059558123 0.073054001, 0.13212138 0.05902189 0.073033303, 0.13264133 0.057946056 0.072991922, 0.12780432 0.06247586 0.074382618, 0.12709582 0.063919365 0.074381173, 0.12793656 0.064548343 0.074025527, 0.1292922 0.064382821 0.073284805, 0.12864101 0.065196961 0.073462054, 0.12913664 0.065773845 0.07280162, 0.12905705 0.062823057 0.073905393, 0.12961258 0.063971877 0.073191956, 0.12948377 0.066320419 0.072028294, 0.12960628 0.061952233 0.073840752, 0.12991922 0.059426725 0.074205101, 0.1308199 0.056591243 0.074311554, 0.13113907 0.056115776 0.074280187, 0.13177042 0.055158973 0.074210674, 0.13257872 0.055694461 0.073751032, 0.1310408 0.054760873 0.074428901, 0.13385987 0.056974024 0.072027758, 0.13286471 0.057401299 0.073004276, 0.13330482 0.056309342 0.073028997, 0.12836291 0.061619818 0.074351728, 0.12863982 0.06118989 0.074335024, 0.12899952 0.060428262 0.074334905, 0.12921594 0.060940653 0.074205235, 0.12930803 0.060096204 0.074295685, 0.12999734 0.058590293 0.074295565, 0.12302311 0.071872443 0.074327931, 0.12366059 0.070882559 0.074312329, 0.12424734 0.07219997 0.073812038, 0.123604 0.073197067 0.073841363, 0.12270136 0.072365165 0.07433553, 0.12360926 0.074994445 0.073155135, 0.12490991 0.074578077 0.072028726, 0.12311111 0.077511251 0.07202886, 0.12296121 0.075639129 0.07334666, 0.12274554 0.074627697 0.073841408, 0.12384199 0.07418853 0.07334666, 0.12392838 0.074667931 0.073054716, 0.12435997 0.073946983 0.073054701, 0.12468176 0.073443711 0.073034078, 0.12531893 0.072432727 0.072992787, 0.12000528 0.076392531 0.074383274, 0.11913952 0.077747583 0.074381918, 0.1199045 0.078466833 0.074026302, 0.12127033 0.078453988 0.073285624, 0.12053199 0.079190165 0.073462814, 0.12095986 0.079818994 0.07280232, 0.12121113 0.076877832 0.073906228, 0.12163453 0.078081727 0.073192775, 0.12124363 0.080400884 0.072029084, 0.12185438 0.076074034 0.073841587, 0.12244812 0.073599339 0.074205846, 0.12403105 0.070445806 0.074281126, 0.12476556 0.069565713 0.074211493, 0.1255088 0.070188254 0.073751763, 0.12408514 0.069088429 0.074429691, 0.12663862 0.071603328 0.072028562, 0.12560195 0.07191664 0.07300514, 0.12616149 0.070880711 0.073029727, 0.12065612 0.075604439 0.074352548, 0.12097944 0.075208247 0.074335873, 0.12142201 0.074491501 0.074335709, 0.1215798 0.075025082 0.074206054, 0.12176581 0.074196249 0.0742964, 0.12261929 0.072777003 0.074296415, 0.13985878 0.027206957 0.074325532, 0.14112249 0.027111739 0.073809609, 0.1408446 0.028265476 0.073838919, 0.13971782 0.027778268 0.074333042, 0.14144316 0.029960126 0.073152706, 0.14253324 0.02913779 0.072026178, 0.14180426 0.032500297 0.072026327, 0.14104444 0.030782759 0.073344082, 0.14050679 0.029899269 0.073839054, 0.14139664 0.02912268 0.073344037, 0.14163657 0.029546529 0.073052377, 0.14180584 0.028723598 0.073052242, 0.14194329 0.028142393 0.073031604, 0.14221081 0.026977569 0.072990179, 0.13850316 0.032470107 0.074380919, 0.13813362 0.034035176 0.074379489, 0.13909328 0.034461319 0.074023768, 0.14037803 0.033998311 0.073283255, 0.13992442 0.034936696 0.073460415, 0.14053594 0.035389096 0.072799861, 0.13980165 0.03252992 0.073903665, 0.14059885 0.03352648 0.073190317, 0.14099595 0.035844535 0.072026476, 0.14014339 0.031558812 0.073838994, 0.13988656 0.029026777 0.074203432, 0.14013362 0.026062161 0.074309886, 0.140339 0.025527596 0.074278578, 0.14074154 0.024454266 0.07420893, 0.14164875 0.024796426 0.0737492, 0.13994169 0.024228483 0.074427113, 0.14318262 0.025758892 0.072025955, 0.14230751 0.026396841 0.073002502, 0.14249353 0.025234282 0.073027223, 0.13885726 0.031511337 0.074349985, 0.13903148 0.031030655 0.074333251, 0.13921259 0.030208051 0.074333236, 0.13953783 0.030659318 0.074203447, 0.13943957 0.029815704 0.074294001, 0.13977644 0.028194278 0.074293807, 0.1359327 0.042695045 0.074326307, 0.13633399 0.041588277 0.074310645, 0.13719912 0.042742014 0.073810428, 0.13679379 0.043857366 0.073839709, 0.1357287 0.043246925 0.074333832, 0.13719888 0.045608312 0.07315357, 0.13837418 0.044913113 0.072027192, 0.13727319 0.048172891 0.072027251, 0.13671054 0.046381176 0.073345006, 0.13627525 0.045443088 0.073839739, 0.13724634 0.044770896 0.073344991, 0.13743739 0.045218974 0.073053136, 0.13769764 0.044420183 0.073053166, 0.13789944 0.043857902 0.073032573, 0.1382957 0.042730391 0.072991073, 0.13399634 0.047773451 0.074381739, 0.13345379 0.04928723 0.074380308, 0.13435969 0.049818099 0.074024603, 0.13568833 0.049501896 0.07328409, 0.1351324 0.050383717 0.073461249, 0.13568954 0.050901532 0.07280083, 0.13528007 0.047978073 0.073904648, 0.13596065 0.049057662 0.073191091, 0.1360956 0.051405638 0.072027504, 0.13572827 0.04705137 0.073839977, 0.1357564 0.044506758 0.074204296, 0.13659796 0.041079998 0.074279487, 0.13711819 0.040058464 0.074209765, 0.13798128 0.040500134 0.073750064, 0.13634859 0.039744735 0.074428067, 0.13939776 0.041628242 0.072026789, 0.13845679 0.042164117 0.073003337, 0.13877173 0.04102996 0.073027998, 0.13445561 0.046860248 0.074350908, 0.13468258 0.046401918 0.074334234, 0.1349546 0.045604885 0.074334055, 0.1352271 0.046089888 0.0742044, 0.13522395 0.045240462 0.074294776, 0.13574032 0.043666899 0.074294746, 0.079653934 0.11813214 0.074330598, 0.080657706 0.11751691 0.074314922, 0.080614716 0.11895853 0.07381478, 0.079602569 0.11957768 0.07384406, 0.079150319 0.11843625 0.074338123, 0.078827471 0.12119922 0.073157728, 0.0801799 0.12138849 0.072031483, 0.07728669 0.12325069 0.072031453, 0.077963904 0.12149897 0.073349103, 0.078208253 0.12049419 0.073844001, 0.079386696 0.12057406 0.073349267, 0.079256773 0.1210435 0.073057458, 0.07995832 0.12058121 0.073057383, 0.080466598 0.12026736 0.07303676, 0.081479222 0.11963308 0.072995469, 0.074973702 0.12089512 0.074385792, 0.073605806 0.12174037 0.074384421, 0.073982984 0.12272033 0.074028835, 0.075218976 0.12330139 0.073288277, 0.074234426 0.12364435 0.073465452, 0.074347109 0.12439653 0.072805002, 0.075849533 0.12185559 0.073908731, 0.075708792 0.12312379 0.073195308, 0.074350357 0.12504399 0.072031558, 0.076777935 0.12141052 0.073844165, 0.078386664 0.1194385 0.074208453, 0.08118102 0.11728418 0.074283615, 0.082224503 0.11680993 0.07421416, 0.082624108 0.11769328 0.073754445, 0.08181861 0.11608469 0.074432373, 0.083028182 0.11945844 0.072031304, 0.081958205 0.11929071 0.073007762, 0.082911819 0.11860022 0.073032454, 0.075902104 0.12046748 0.074354962, 0.076365232 0.12025079 0.074338406, 0.077074945 0.11979714 0.074338123, 0.076985568 0.12034631 0.074208543, 0.07751289 0.11968014 0.074299008, 0.078897581 0.11877194 0.074299008, 0.092380166 0.1084708 0.074330032, 0.093308821 0.10774714 0.074314311, 0.093427405 0.1091845 0.073814064, 0.092490867 0.10991308 0.07384342, 0.091913611 0.10882968 0.074337542, 0.091902256 0.11161125 0.073157385, 0.093267336 0.1116479 0.072030768, 0.090600893 0.11382234 0.072030976, 0.091077641 0.11200589 0.073348731, 0.091208115 0.11098 0.07384336, 0.092388019 0.11092746 0.073348716, 0.092311382 0.11140853 0.073056862, 0.092956826 0.11087054 0.073056906, 0.093426734 0.11050189 0.073036283, 0.09436208 0.10975802 0.072994873, 0.088038743 0.11174056 0.074385285, 0.086773947 0.11273372 0.074383944, 0.087258592 0.11366522 0.074028164, 0.088551819 0.11410433 0.073287636, 0.087611929 0.11455527 0.073464826, 0.087808117 0.11529011 0.072804525, 0.089016631 0.11259699 0.07390821, 0.089018747 0.11387306 0.073194712, 0.087883845 0.11593294 0.072031081, 0.089889482 0.11205062 0.073843583, 0.091267079 0.10991108 0.074207857, 0.093802616 0.10745722 0.074283168, 0.094786629 0.10686913 0.074213579, 0.095282584 0.10770223 0.073753923, 0.094302028 0.10619393 0.074431717, 0.095881671 0.10941115 0.072030738, 0.094799697 0.10936433 0.073007256, 0.09566991 0.10857132 0.073031858, 0.088913396 0.11121175 0.074354425, 0.089349404 0.11094451 0.074337676, 0.090003744 0.11041442 0.074337766, 0.089976579 0.11096987 0.074208066, 0.090425834 0.11024901 0.074298456, 0.091700196 0.10919142 0.074298456, 0.11420196 0.085194618 0.07432881, 0.11494625 0.084282547 0.074313, 0.11538169 0.085657239 0.073812783, 0.11382705 0.085648179 0.074336469, 0.11463082 0.086576194 0.073842227, 0.11443488 0.088362604 0.07315594, 0.1157739 0.088094532 0.072029561, 0.11365813 0.090807825 0.072029635, 0.11371875 0.088930696 0.073347479, 0.11361769 0.087901592 0.073842198, 0.11475627 0.087587893 0.073347405, 0.11478861 0.08807382 0.07305558, 0.11529817 0.087405831 0.073055461, 0.11567421 0.086941659 0.073034942, 0.11642051 0.086008638 0.072993428, 0.1106969 0.089348406 0.074384168, 0.10968496 0.090597928 0.074382707, 0.11036463 0.091398478 0.074026987, 0.1117231 0.091538787 0.073286474, 0.11090718 0.092187464 0.07346347, 0.11126198 0.092860222 0.072803199, 0.11184093 0.089965641 0.073907048, 0.11212687 0.091209441 0.073193461, 0.11147888 0.093470216 0.072029814, 0.11257014 0.089238971 0.073842242, 0.11343728 0.086846381 0.07420668, 0.11536336 0.083889961 0.074281722, 0.11619154 0.083097667 0.074212149, 0.11686057 0.083799452 0.073752582, 0.11556897 0.082547247 0.074430376, 0.11782482 0.085332185 0.072029412, 0.11675963 0.085527301 0.07300584, 0.11743169 0.084560454 0.073030397, 0.11143196 0.088638186 0.074353263, 0.11179754 0.088280737 0.074336559, 0.11231764 0.087618232 0.074336439, 0.11241475 0.088165909 0.074206769, 0.11269228 0.087363154 0.07429716, 0.11369945 0.086048365 0.07429716, 0.1039446 0.097445577 0.074329391, 0.10421617 0.098866343 0.073842734, 0.10352126 0.097854137 0.074336931, 0.10382137 0.10061973 0.073156625, 0.10518196 0.10050327 0.072030216, 0.1027758 0.10296243 0.072030395, 0.10304618 0.10110387 0.073348165, 0.10306096 0.10006991 0.073842838, 0.10422741 0.099885881 0.07334815, 0.10420516 0.10037246 0.073056266, 0.10478632 0.099765509 0.073056266, 0.10521202 0.099346489 0.073035583, 0.10506524 0.098037243 0.073813513, 0.10605818 0.098502785 0.072994277, 0.099996507 0.10118079 0.074384779, 0.098850995 0.10230932 0.074383318, 0.09943679 0.10318071 0.074027762, 0.100771 0.10347223 0.073287115, 0.099887595 0.10402551 0.073464215, 0.10016482 0.10473371 0.072803885, 0.10106428 0.10192218 0.073907584, 0.10120924 0.10319012 0.073194087, 0.10031195 0.10536423 0.072030425, 0.10187031 0.1012817 0.073842898, 0.10299982 0.099001259 0.074207276, 0.10478634 0.096622437 0.07431373, 0.1052447 0.096278995 0.074282497, 0.10615665 0.095584273 0.074212924, 0.10674269 0.096356809 0.073753282, 0.10559957 0.094967604 0.074431136, 0.1075294 0.097987801 0.072030157, 0.10644892 0.098062396 0.07300663, 0.10722505 0.097176999 0.073031247, 0.10080652 0.10055721 0.074353859, 0.10120989 0.10024285 0.074337065, 0.10180081 0.099642783 0.074337065, 0.10183598 0.100198 0.074207455, 0.1022017 0.099431306 0.074297801, 0.10334972 0.098237485 0.074297696, 0.13781491 -0.036170334 0.074321911, 0.13793576 -0.035594344 0.07432954, 0.13916242 -0.035644323 0.073835298, 0.14043696 -0.034377158 0.07314904, 0.14043459 -0.033462942 0.07334052, 0.139567 -0.034025669 0.073835388, 0.14003165 -0.035111487 0.073340505, 0.14043176 -0.034833729 0.073048636, 0.14022712 -0.035648584 0.073048532, 0.14009884 -0.036232084 0.073027998, 0.13891226 -0.036804289 0.073805973, 0.13983452 -0.037397444 0.072986528, 0.13887723 -0.030840129 0.074377373, 0.13922317 -0.029269695 0.074375927, 0.14027272 -0.02930212 0.074020237, 0.14122936 -0.030276805 0.073279575, 0.1412278 -0.029234201 0.073456809, 0.141975 -0.029092193 0.072796389, 0.14007303 -0.031349599 0.073900163, 0.14122358 -0.03079775 0.073186591, 0.13995951 -0.032372802 0.073835477, 0.13862953 -0.034542561 0.0741999, 0.13756591 -0.037320912 0.074306235, 0.13751891 -0.037891626 0.074274987, 0.13741589 -0.039033294 0.074205369, 0.13838175 -0.039118856 0.073745668, 0.13659731 -0.038889676 0.074423581, 0.13966961 -0.037962556 0.072998941, 0.13933286 -0.039090723 0.073023632, 0.13878021 -0.031857669 0.074346513, 0.1387286 -0.032366395 0.074329674, 0.13853475 -0.033186018 0.0743296, 0.13902362 -0.03292039 0.074199826, 0.13856903 -0.033638 0.074290335, 0.13816907 -0.035245031 0.074290335, 0.14099774 -0.020512581 0.074322745, 0.14087899 -0.021683753 0.074307054, 0.14215897 -0.021019638 0.073806927, 0.14227773 -0.019838929 0.073836133, 0.14105329 -0.019926667 0.074330389, 0.14340237 -0.018437058 0.073150009, 0.14415969 -0.01957345 0.072023481, 0.14458221 -0.016158849 0.072023734, 0.14329773 -0.017528862 0.073341429, 0.14249851 -0.018185169 0.073836297, 0.14308193 -0.019212216 0.07334134, 0.14344838 -0.018891275 0.073049501, 0.14333631 -0.019724101 0.073049366, 0.14327408 -0.020318151 0.073028833, 0.14314196 -0.021505684 0.072987542, 0.14145638 -0.015096754 0.074378222, 0.14162453 -0.01349774 0.074376866, 0.14267106 -0.013412416 0.074021161, 0.14373082 -0.014273703 0.073280513, 0.14361264 -0.013238043 0.073457763, 0.14433917 -0.013013124 0.072797224, 0.14270188 -0.015469402 0.073901013, 0.14378338 -0.014791995 0.07318756, 0.14492376 -0.012735069 0.072023913, 0.1427035 -0.016498834 0.073836386, 0.14162487 -0.018803895 0.074200705, 0.14089631 -0.022256285 0.074275896, 0.14092171 -0.023402274 0.074206188, 0.14189105 -0.023378938 0.073746637, 0.14009224 -0.023351252 0.07442449, 0.1436566 -0.022977054 0.072023273, 0.14304143 -0.022085905 0.07299988, 0.14283301 -0.02324453 0.073024586, 0.14147402 -0.016118854 0.074347347, 0.14147973 -0.016630262 0.074330524, 0.14137897 -0.017466426 0.074330524, 0.1418349 -0.01714769 0.074200794, 0.14146355 -0.017911673 0.074291319, 0.14124593 -0.019553423 0.074291289, 0.14202607 0.011376649 0.074324667, 0.14194997 0.011960149 0.074332193, 0.14312433 0.012318134 0.073837936, 0.1439088 0.013935059 0.073151752, 0.14489985 0.012995839 0.072025344, 0.14455196 0.016418785 0.072025478, 0.1436047 0.014797211 0.073343232, 0.14297152 0.013979524 0.07383807, 0.14376871 0.013108104 0.073343262, 0.14405464 0.013502508 0.073051259, 0.14413065 0.012665689 0.073051304, 0.14420216 0.012072653 0.07303068, 0.14327109 0.011140645 0.073808655, 0.14433768 0.010885298 0.07298927, 0.1412683 0.016758502 0.074379981, 0.14107625 0.018355012 0.074378669, 0.14207754 0.018671125 0.074022919, 0.14330254 0.018067032 0.073282212, 0.14295669 0.019050628 0.073459432, 0.14361505 0.019431531 0.072799042, 0.14256522 0.016672552 0.073902771, 0.14346905 0.017573446 0.073189333, 0.14412309 0.019832611 0.072025731, 0.14279617 0.015669167 0.073838249, 0.14225736 0.013181984 0.074202478, 0.142171 0.010208368 0.074308813, 0.1423153 0.0096540153 0.074277565, 0.14259507 0.0085423589 0.074207947, 0.14353494 0.0087807477 0.073748335, 0.14177504 0.0084076524 0.074426219, 0.1451668 0.0095655322 0.07202512, 0.14436863 0.010297447 0.073001534, 0.14442341 0.0091213584 0.07302621, 0.14151277 0.015766084 0.074349105, 0.14163211 0.015268832 0.074332267, 0.14171997 0.014431208 0.074332193, 0.14209358 0.014843374 0.074202597, 0.14190157 0.014015883 0.074292958, 0.14205477 0.012366891 0.074292973, 0.14240728 -0.0045967698 0.074323624, 0.14360401 -0.0037841499 0.073836952, 0.14239696 -0.004008323 0.074331224, 0.14456457 -0.0022651851 0.073150843, 0.14544427 -0.0033095181 0.07202442, 0.14548182 0.000130862 0.072024539, 0.1443589 -0.0013743341 0.073342398, 0.14363818 -0.0021160841 0.07383728, 0.14433286 -0.0030713975 0.073342249, 0.14466107 -0.0027114451 0.073050424, 0.14464292 -0.0035513639 0.073050305, 0.14464773 -0.0041488409 0.073029697, 0.14361821 -0.0049707592 0.073807761, 0.1446493 -0.0053436756 0.072988346, 0.14225675 0.00083619356 0.074379042, 0.14224479 0.0024440587 0.074377716, 0.14327514 0.0026460588 0.07402198, 0.14442475 0.0019086897 0.073281363, 0.14419131 0.0029246509 0.073458612, 0.14488813 0.0032295883 0.072798029, 0.14353602 0.00060546398 0.073901981, 0.14453509 0.0013995171 0.073188335, 0.1454379 0.0035712421 0.072024778, 0.14365308 -0.00041741133 0.073837221, 0.1428393 -0.0028288066 0.074201539, 0.14242047 -0.0057739615 0.074307963, 0.14250179 -0.0063409507 0.074276775, 0.1426554 -0.0074769557 0.074207157, 0.14361598 -0.0073452294 0.073747382, 0.14182539 -0.0075190067 0.07442537, 0.1453255 -0.0067480505 0.072024301, 0.14461426 -0.0059313774 0.073000714, 0.14453709 -0.0071062148 0.073025331, 0.14238872 -0.00017747283 0.074348271, 0.14245157 -0.00068491697 0.074331433, 0.142445 -0.0015271306 0.074331582, 0.14286253 -0.001159519 0.074201748, 0.14257903 -0.0019601882 0.074292257, 0.14254671 -0.0036161244 0.074292108, 0.13289899 -0.051373124 0.074321136, 0.1339184 -0.052126139 0.073805019, 0.13429686 -0.05100137 0.073834389, 0.13308366 -0.050814509 0.074328646, 0.13570538 -0.049885064 0.073148236, 0.13619068 -0.05116117 0.072021678, 0.13736248 -0.047926337 0.072021887, 0.13580543 -0.048976302 0.073339641, 0.13488019 -0.049438179 0.073834479, 0.1352203 -0.050569296 0.073339537, 0.1356491 -0.05033794 0.073047757, 0.13535446 -0.051124901 0.073047757, 0.13516164 -0.05169034 0.073027223, 0.13476861 -0.052818775 0.072985709, 0.13455141 -0.046195447 0.074376374, 0.13507113 -0.04467383 0.074375093, 0.13611037 -0.044823438 0.074019283, 0.13695195 -0.045899183 0.07327871, 0.13706715 -0.044863045 0.0734559, 0.13782552 -0.044805408 0.072795451, 0.1356826 -0.046835691 0.073899254, 0.13688788 -0.046416163 0.073185861, 0.13845724 -0.044664502 0.072022066, 0.13545533 -0.04783988 0.073834628, 0.13389078 -0.049847037 0.074198917, 0.1325227 -0.052488625 0.07430537, 0.13241211 -0.053050578 0.074274182, 0.13218199 -0.054173678 0.074204475, 0.13313216 -0.054366708 0.073744848, 0.13138458 -0.053939313 0.074422777, 0.13494286 -0.054367632 0.072021559, 0.13454133 -0.053361893 0.072998106, 0.13408041 -0.054445207 0.073022634, 0.13434106 -0.047195673 0.074345648, 0.13423288 -0.047695577 0.074328855, 0.13394855 -0.048488379 0.074328825, 0.13446403 -0.048279166 0.074199036, 0.13393196 -0.048941314 0.074289531, 0.13335457 -0.050493419 0.074289501, 0.1263119 -0.065930188 0.074320167, 0.12581307 -0.066996634 0.074304655, 0.12724055 -0.066792369 0.073804215, 0.12774268 -0.06571728 0.07383351, 0.12655789 -0.065395623 0.074327767, 0.12926716 -0.064765483 0.073147282, 0.12946829 -0.063873827 0.073338777, 0.1284972 -0.064229339 0.073833629, 0.1287086 -0.065391183 0.073338687, 0.12916052 -0.065209478 0.073046863, 0.12877971 -0.065958411 0.073046878, 0.12852485 -0.066498667 0.07302627, 0.1280078 -0.067575842 0.072984889, 0.12853359 -0.060969949 0.074375585, 0.12922043 -0.059516191 0.074374288, 0.13023639 -0.059781194 0.074018568, 0.13095218 -0.0609442 0.073277876, 0.13118269 -0.059927613 0.07345508, 0.13194272 -0.059955359 0.072794721, 0.12958598 -0.061732888 0.073898375, 0.13083053 -0.061450869 0.073184907, 0.1292477 -0.062705189 0.073833674, 0.12746833 -0.06452471 0.074198127, 0.1256402 -0.067542613 0.074273199, 0.12528576 -0.068632841 0.074203804, 0.12620839 -0.068930894 0.073744044, 0.12451969 -0.068310618 0.074421972, 0.12772132 -0.06809032 0.072997242, 0.1271418 -0.069115132 0.073021844, 0.12821263 -0.061940491 0.074344829, 0.12804905 -0.062424958 0.074328005, 0.12767781 -0.063180953 0.07432799, 0.12821345 -0.063030869 0.074198171, 0.12761059 -0.06362915 0.074288666, 0.12686311 -0.065106988 0.074288532, 0.11813632 -0.079658121 0.074319392, 0.11844051 -0.079154402 0.074327067, 0.11958192 -0.079606682 0.07383284, 0.12120333 -0.078831524 0.073146582, 0.12150312 -0.077968121 0.073337957, 0.12049829 -0.07821247 0.07383281, 0.12057833 -0.079390883 0.073337972, 0.12104768 -0.079260826 0.073046133, 0.12058537 -0.079962432 0.073046148, 0.12027156 -0.080470681 0.073025525, 0.11896264 -0.080619037 0.073803365, 0.11963725 -0.081483454 0.072984055, 0.12089941 -0.074977815 0.074374825, 0.1217446 -0.073610038 0.074373409, 0.12272456 -0.073987186 0.074017659, 0.12330566 -0.075223088 0.073277056, 0.12364852 -0.074238628 0.07345432, 0.12440073 -0.074351281 0.072793812, 0.12185978 -0.075853765 0.07389769, 0.12312812 -0.075712919 0.073184133, 0.12141469 -0.076782107 0.073832974, 0.11944284 -0.078390896 0.074197277, 0.11752121 -0.080661893 0.074303806, 0.11728834 -0.081185162 0.074272558, 0.11681407 -0.08222881 0.07420288, 0.11769746 -0.08262834 0.073743254, 0.11608884 -0.081822842 0.074421167, 0.11929496 -0.081962317 0.072996482, 0.11860454 -0.082915962 0.073021114, 0.12047175 -0.075906247 0.074344039, 0.1202551 -0.076369584 0.074327186, 0.1198015 -0.077079266 0.074327216, 0.12035058 -0.076989889 0.074197337, 0.11968446 -0.077517033 0.074287936, 0.11877619 -0.078901887 0.074287876, 0.10847508 -0.092384309 0.074318722, 0.10883386 -0.091917872 0.074326336, 0.10991737 -0.092495143 0.073832095, 0.11161545 -0.091906488 0.073145822, 0.11201008 -0.091081887 0.073337376, 0.11098412 -0.091212362 0.07383202, 0.11093172 -0.092392206 0.073337242, 0.11141267 -0.092315555 0.073045447, 0.11087471 -0.092960894 0.073045373, 0.11050596 -0.093430787 0.073024824, 0.10918862 -0.093431681 0.073802918, 0.10976227 -0.094366223 0.072983459, 0.11174487 -0.088042885 0.07437411, 0.11273787 -0.086778164 0.074372754, 0.11366948 -0.087262869 0.074016899, 0.11410847 -0.088555902 0.073276326, 0.11455944 -0.087616146 0.073453546, 0.11529431 -0.087812215 0.072793007, 0.11260112 -0.089020878 0.073896974, 0.11387723 -0.089022815 0.073183283, 0.1120548 -0.08989343 0.073832199, 0.10991521 -0.091271281 0.074196547, 0.10775141 -0.093312889 0.074303135, 0.10746155 -0.093806982 0.074271828, 0.10687329 -0.094790906 0.07420224, 0.10770644 -0.095286757 0.073742509, 0.10619815 -0.09430626 0.074420527, 0.10936841 -0.09480384 0.072995886, 0.10857554 -0.095674127 0.073020414, 0.11121596 -0.088917673 0.074343354, 0.11094876 -0.089353681 0.074326456, 0.11041849 -0.090007961 0.074326366, 0.11097421 -0.089980811 0.074196652, 0.11025327 -0.090430081 0.074287191, 0.10919567 -0.091704398 0.074287102, -0.011380821 0.14202183 0.07433182, -0.010212556 0.14216673 0.074316293, -0.011144757 0.14326695 0.073815949, -0.012322351 0.14311999 0.073845245, -0.011964396 0.14194584 0.074339561, -0.013939217 0.14390448 0.073159054, -0.012999877 0.14489582 0.072032638, -0.016422912 0.14454788 0.072032616, -0.014801264 0.14360034 0.073350482, -0.013983697 0.14296719 0.073845305, -0.013112336 0.14376462 0.073350415, -0.013506725 0.14405042 0.07305871, -0.012669936 0.14412647 0.073058665, -0.012076825 0.14419803 0.073038146, -0.01088953 0.14433339 0.072996818, -0.016762793 0.14126405 0.074387074, -0.018359184 0.14107195 0.074385636, -0.018675283 0.14207327 0.074029975, -0.018071294 0.14329818 0.073289327, -0.019054785 0.14295259 0.073466286, -0.019435659 0.14361086 0.07280606, -0.016676679 0.14256108 0.073909931, -0.017577678 0.14346495 0.073196284, -0.019836679 0.14411911 0.072032616, -0.015673369 0.14279193 0.07384526, -0.013186201 0.1422531 0.074209601, -0.0096582472 0.14231098 0.074285045, -0.0085465759 0.14259088 0.074215539, -0.0087849498 0.14353073 0.073755965, -0.0084118098 0.14177078 0.074433744, -0.0095695406 0.14516267 0.072032742, -0.01030162 0.14436439 0.073009096, -0.0091255903 0.14441916 0.073033817, -0.015770271 0.14150852 0.07435628, -0.015273049 0.14162782 0.074339569, -0.014435455 0.14171576 0.074339479, -0.014847428 0.14208937 0.07420972, -0.01402013 0.14189738 0.074300133, -0.012371168 0.14205065 0.074300222, 0.0045926273 0.14240301 0.074331976, 0.0057697743 0.14241633 0.074316375, 0.0049666166 0.1436139 0.073816076, 0.0037799925 0.14359975 0.07384529, 0.0040042251 0.14239281 0.074339449, 0.0022611022 0.14456028 0.073159017, 0.0033054948 0.14544019 0.072032854, -0.00013493001 0.14547765 0.072032839, 0.0013703108 0.14435476 0.073350504, 0.0021119565 0.14363384 0.073845267, 0.0030671805 0.14432856 0.073350489, 0.0027073324 0.1446569 0.07305862, 0.0035473406 0.14463872 0.07305862, 0.0041445643 0.14464355 0.073038124, 0.005339548 0.14464524 0.072996624, -0.00084032118 0.14225259 0.074387103, -0.0024483204 0.14224064 0.074385591, -0.002650246 0.14327097 0.074029952, -0.0019128174 0.14442036 0.073289327, -0.0029288679 0.14418712 0.073466443, -0.0032337457 0.14488399 0.07280612, -0.0006096065 0.14353168 0.073910072, -0.0014036596 0.14453086 0.073196441, -0.0035753548 0.14543387 0.072032623, 0.0004132092 0.14364889 0.073845401, 0.0028244555 0.14283505 0.07420972, 0.0063367486 0.14249751 0.074285015, 0.0074727237 0.14265129 0.074215554, 0.007341072 0.14361179 0.073755927, 0.007514894 0.14182109 0.074433759, 0.0067440569 0.1453214 0.072032772, 0.0059272647 0.14461005 0.073009074, 0.0071020871 0.14453277 0.073033795, 0.00017333031 0.14238447 0.074356228, 0.00068078935 0.14244735 0.074339591, 0.0015229583 0.14244097 0.074339621, 0.0011552721 0.14285839 0.074209765, 0.0019560456 0.14257482 0.074300341, 0.0036118478 0.1425426 0.074300207, -0.04269927 0.13592854 0.074331567, -0.042746246 0.13719499 0.073815763, -0.043861568 0.13678959 0.073844962, -0.043251172 0.13572434 0.074339099, -0.045612566 0.13719478 0.073158681, -0.044917189 0.1383701 0.072032273, -0.048176907 0.13726908 0.072032273, -0.046385288 0.13670632 0.073350146, -0.04544735 0.136271 0.073844858, -0.044775203 0.13724229 0.073350117, -0.045223132 0.13743308 0.073058307, -0.044424355 0.13769349 0.0730583, -0.043862075 0.13789529 0.073037796, -0.042734765 0.13829142 0.072996445, -0.047777593 0.13399199 0.074386656, -0.049291231 0.13344955 0.074385121, -0.049822219 0.13435549 0.074029393, -0.049505956 0.13568413 0.073289007, -0.05038783 0.13512814 0.073465958, -0.050905719 0.13568524 0.072805591, -0.04798235 0.13527572 0.073909558, -0.049061775 0.13595647 0.073195994, -0.051409736 0.13609144 0.072032288, -0.047055446 0.13572392 0.073844992, -0.044510856 0.13575232 0.07420931, -0.041592486 0.13632974 0.074315958, -0.0410842 0.13659385 0.074284814, -0.040062726 0.13711408 0.074215218, -0.040504284 0.13797709 0.073755547, -0.039748698 0.13634434 0.074433364, -0.041632295 0.13939366 0.07203237, -0.042168461 0.1384525 0.073008828, -0.04103402 0.13876754 0.073033594, -0.046864562 0.13445145 0.074355811, -0.046406291 0.13467845 0.074338943, -0.045609213 0.13495049 0.074339226, -0.046094023 0.13522285 0.07420931, -0.045244589 0.13521978 0.074299864, -0.043671012 0.13573608 0.074299864, -0.027211145 0.13985476 0.074331805, -0.026066363 0.14012939 0.074316181, -0.027115986 0.1411182 0.073815882, -0.028269649 0.14084035 0.073845215, -0.027782425 0.13971353 0.074339323, -0.029964261 0.14143899 0.073158883, -0.029141814 0.14252904 0.072032601, -0.032504335 0.14180025 0.072032467, -0.030786812 0.14104009 0.073350243, -0.029903434 0.14050272 0.073845208, -0.029126912 0.14139247 0.073350422, -0.029550761 0.14163235 0.073058523, -0.028727785 0.14180151 0.073058628, -0.028146386 0.14193913 0.0730379, -0.026981801 0.14220664 0.072996661, -0.032474436 0.13849893 0.07438691, -0.034039311 0.13812932 0.074385338, -0.034465544 0.13908908 0.074029617, -0.034002438 0.14037383 0.073289238, -0.034940936 0.13992006 0.073466353, -0.035393201 0.14053166 0.072805941, -0.032534093 0.13979745 0.073909804, -0.033530548 0.14059463 0.073196225, -0.035848625 0.1409919 0.072032437, -0.031562977 0.14013925 0.073845178, -0.029031143 0.13988239 0.074209623, -0.02553165 0.1403347 0.074284963, -0.024458334 0.14073738 0.074215546, -0.024800539 0.14164454 0.073755823, -0.02423276 0.13993749 0.074433722, -0.025762916 0.14317843 0.072032616, -0.026401073 0.14230335 0.073009066, -0.025238439 0.14248922 0.073033728, -0.031515576 0.13885313 0.074355997, -0.031034745 0.13902733 0.074339315, -0.03021232 0.13920856 0.074339435, -0.030663572 0.13953358 0.074209638, -0.029819846 0.13943535 0.074300103, -0.028198406 0.1397723 0.07430023, 0.02050814 0.14099351 0.074331835, 0.021015495 0.14215472 0.073815987, 0.019834712 0.1422736 0.073845282, 0.019922465 0.14104897 0.074339285, 0.01843293 0.1433982 0.073159024, 0.019569322 0.14415565 0.07203266, 0.016154721 0.1445781 0.07203263, 0.017524838 0.14329356 0.073350489, 0.018180996 0.14249429 0.073845282, 0.01920794 0.14307767 0.073350504, 0.018887207 0.14344415 0.073058665, 0.019719869 0.14333221 0.073058635, 0.020313889 0.14326999 0.073037997, 0.021501541 0.14313784 0.072996706, 0.015092656 0.14145213 0.074386969, 0.013493389 0.14162034 0.074385531, 0.013408169 0.14266691 0.07402993, 0.01426959 0.14372668 0.073289298, 0.013233855 0.14360839 0.073466383, 0.013009012 0.14433494 0.072806172, 0.01546514 0.14269757 0.073909931, 0.014787957 0.14377919 0.073196299, 0.01273109 0.1449196 0.072032616, 0.016494691 0.14269936 0.073845252, 0.018799648 0.14162067 0.074209765, 0.021679536 0.14087483 0.074316218, 0.022252023 0.14089212 0.074284971, 0.023397997 0.14091745 0.074215531, 0.023374826 0.1418868 0.073755771, 0.023346975 0.14008799 0.074433759, 0.022972897 0.1436525 0.072032645, 0.022081599 0.14303723 0.073009118, 0.023240432 0.1428287 0.073033735, 0.016114727 0.14146972 0.074356243, 0.016626015 0.14147547 0.074339435, 0.017462209 0.14137468 0.074339479, 0.017143592 0.14183071 0.074209742, 0.01790756 0.14145923 0.074300304, 0.019549176 0.14124179 0.074300289, 0.036166072 0.13781071 0.074331671, 0.036800101 0.13890803 0.073815718, 0.035640165 0.13915822 0.073845074, 0.035590157 0.13793162 0.074339136, 0.034372985 0.14043278 0.07315883, 0.035586983 0.14105809 0.072032496, 0.032241195 0.14186016 0.072032616, 0.033458874 0.14043042 0.073350325, 0.034021378 0.1395627 0.073845178, 0.035107225 0.14002746 0.073350236, 0.034829482 0.14042756 0.073058486, 0.035644352 0.14022303 0.073058471, 0.036227837 0.14009452 0.073037937, 0.037393168 0.13983032 0.072996467, 0.030835882 0.13887301 0.074386746, 0.029265478 0.13921902 0.074385345, 0.029297933 0.1402685 0.074029714, 0.030272529 0.14122522 0.073289335, 0.029230133 0.14122364 0.073466346, 0.029087991 0.14197093 0.072805956, 0.031345427 0.14006871 0.073909834, 0.030793622 0.14121941 0.073196217, 0.028877348 0.14258289 0.072032586, 0.032368675 0.13995525 0.073845223, 0.034538358 0.13862529 0.074209511, 0.037316784 0.13756156 0.074315965, 0.037887529 0.13751465 0.074284837, 0.039029181 0.13741171 0.074215204, 0.039114609 0.13837746 0.073755637, 0.038885608 0.13659307 0.074433386, 0.038912997 0.14017698 0.072032452, 0.037958369 0.13966545 0.07300894, 0.039086521 0.13932866 0.073033661, 0.031853348 0.138776 0.074356139, 0.032362178 0.13872442 0.074339345, 0.033181757 0.13853064 0.074339315, 0.032916248 0.13901937 0.074209601, 0.033633798 0.1385648 0.07430011, 0.035240874 0.13816491 0.07430011, -0.13289905 0.051364779 0.074326754, -0.13252264 0.052480191 0.074311242, -0.13391834 0.052117735 0.073810861, -0.13429698 0.050993025 0.073840179, -0.13308358 0.050805986 0.074334443, -0.13570525 0.049876571 0.073153749, -0.1361907 0.051152974 0.072027385, -0.13736239 0.047918081 0.072027281, -0.1358054 0.048967957 0.073345207, -0.13488011 0.049429864 0.073840067, -0.13522033 0.050560921 0.073345274, -0.13564901 0.050329685 0.073053449, -0.13535443 0.051116496 0.073053405, -0.13516159 0.051682025 0.073032886, -0.13476841 0.052810341 0.072991639, -0.13455126 0.046186984 0.074381612, -0.13507104 0.044665396 0.0743801, -0.13611031 0.044815034 0.074024305, -0.1369518 0.045890629 0.073283851, -0.13706708 0.044854611 0.073460907, -0.13782546 0.044797003 0.072800457, -0.1356826 0.046827167 0.073904581, -0.13688773 0.046407729 0.073191069, -0.13845733 0.044656366 0.07202699, -0.1354551 0.047831386 0.07383994, -0.13389072 0.049838632 0.074204445, -0.13241209 0.053042144 0.074280143, -0.13218197 0.054165393 0.074210629, -0.13313195 0.054358125 0.073750898, -0.13138467 0.053930759 0.074428841, -0.13494284 0.054359466 0.072027624, -0.13454139 0.053353608 0.073004045, -0.1340804 0.054436862 0.073028848, -0.13434118 0.047187388 0.074350901, -0.1342328 0.047686994 0.074334182, -0.13394849 0.048479885 0.074334279, -0.13446386 0.048270673 0.074204385, -0.13393177 0.04893294 0.074294925, -0.1333545 0.050485075 0.074295163, -0.12631182 0.065921783 0.074327692, -0.12581295 0.066988111 0.074312061, -0.12724063 0.066784233 0.073811829, -0.12774259 0.065708816 0.073840991, -0.12655789 0.06538713 0.074335128, -0.12926725 0.064757109 0.073154613, -0.12960657 0.066080004 0.072028257, -0.13113311 0.062996507 0.072028123, -0.12946832 0.063865393 0.073346034, -0.12849717 0.064220786 0.073840782, -0.12870857 0.065382808 0.073346078, -0.12916054 0.065201104 0.073054291, -0.12877958 0.065949976 0.073054299, -0.12852472 0.066490293 0.073033698, -0.12800777 0.067567527 0.072992474, -0.12853363 0.060961723 0.074382499, -0.12922035 0.059507757 0.074380919, -0.13023645 0.059772849 0.074025154, -0.1309521 0.060935855 0.07328473, -0.13118266 0.059919238 0.073461801, -0.13194267 0.059946984 0.072801441, -0.12958598 0.061724424 0.073905423, -0.13083057 0.061442554 0.073191807, -0.13258636 0.059877783 0.072027966, -0.12924752 0.062696785 0.073840663, -0.12746823 0.064516127 0.074205339, -0.12564024 0.067534238 0.074280947, -0.12528571 0.068624347 0.074211285, -0.12620822 0.0689224 0.073751777, -0.12451965 0.068302125 0.074429676, -0.12800768 0.069126487 0.072028458, -0.12772122 0.068081886 0.07300476, -0.12714191 0.069106847 0.073029682, -0.12821259 0.061931968 0.074351728, -0.12804899 0.062416524 0.074335001, -0.1276778 0.063172609 0.074335061, -0.12821345 0.063022375 0.074205317, -0.12761047 0.063620836 0.074295774, -0.12686297 0.065098554 0.074296102, -0.11813628 0.079649568 0.074328393, -0.11844049 0.079145968 0.074335895, -0.11958193 0.079598367 0.073841721, -0.12120336 0.078823149 0.073155418, -0.12139253 0.080175817 0.072029144, -0.12325478 0.077282697 0.072028831, -0.12150322 0.077959716 0.073346868, -0.12049842 0.078204185 0.073841579, -0.12057831 0.079382598 0.073346943, -0.12104776 0.079252481 0.07305523, -0.12058545 0.079953998 0.073055178, -0.12027159 0.080462337 0.073034599, -0.11896249 0.080610484 0.073812507, -0.11963718 0.08147496 0.072993346, -0.1208993 0.074969441 0.074383169, -0.12174457 0.073601454 0.074381761, -0.1227245 0.073978722 0.074026048, -0.12330578 0.075214684 0.07328555, -0.12364852 0.074230343 0.073462673, -0.12440061 0.074342906 0.072802074, -0.12185975 0.075845301 0.073906176, -0.12312821 0.075704545 0.073192425, -0.12504798 0.074346334 0.072028682, -0.12141475 0.076773733 0.073841631, -0.11944282 0.078382224 0.074206173, -0.11752118 0.080653548 0.074312828, -0.11728841 0.081176966 0.074281618, -0.11681402 0.082220435 0.074212134, -0.11769738 0.082619905 0.073752493, -0.1160889 0.081814498 0.074430309, -0.11946238 0.083024025 0.072029293, -0.11929487 0.081953973 0.073005557, -0.11860441 0.082907617 0.073030517, -0.12047163 0.075897783 0.0743526, -0.12025499 0.07636115 0.074335858, -0.11980134 0.077070653 0.074335881, -0.12035052 0.076981515 0.07420601, -0.11968461 0.077508658 0.074296646, -0.1187762 0.078893393 0.074296646, -0.10847501 0.092375845 0.074329168, -0.10775135 0.093304455 0.074313529, -0.10918853 0.093423158 0.0738132, -0.10991725 0.092486709 0.073842451, -0.10883372 0.091909379 0.074336693, -0.11161539 0.091898024 0.073156148, -0.111652 0.093263298 0.072029732, -0.11382633 0.090596795 0.07202971, -0.11200993 0.091073394 0.073347531, -0.11098401 0.091203839 0.073842481, -0.11093158 0.092383862 0.073347434, -0.1114126 0.092307091 0.073055759, -0.11087479 0.092952669 0.073055789, -0.11050605 0.093422532 0.07303524, -0.10976213 0.094357878 0.072994024, -0.11174477 0.0880346 0.074384034, -0.11273783 0.0867697 0.074382409, -0.11366937 0.087254375 0.074026778, -0.11410849 0.088547617 0.073286295, -0.11455937 0.087607652 0.073463447, -0.11529414 0.0878039 0.072802931, -0.11260106 0.089012355 0.073906884, -0.11387727 0.08901453 0.073193364, -0.11593705 0.087879598 0.072029382, -0.11205478 0.089885056 0.073842227, -0.10991521 0.091262788 0.074206881, -0.10746141 0.093798488 0.074282371, -0.10687328 0.094782382 0.074212804, -0.10770641 0.095278323 0.073753148, -0.10619812 0.094297647 0.074431136, -0.10941519 0.095877558 0.072029963, -0.10936845 0.094795585 0.073006451, -0.10857546 0.095665872 0.073031113, -0.11121593 0.08890906 0.074353188, -0.11094864 0.089345187 0.074336514, -0.11041836 0.089999467 0.074336573, -0.11097413 0.089972317 0.074206755, -0.11025317 0.090421557 0.074297354, -0.10919555 0.091696024 0.074297436, -0.071876697 0.12301889 0.074330844, -0.072204135 0.12424314 0.073814899, -0.073201314 0.12359965 0.073844239, -0.072369337 0.12269714 0.074338473, -0.074998505 0.12360501 0.073157765, -0.074582107 0.12490571 0.07203158, -0.077515297 0.12310702 0.072031423, -0.075643398 0.12295711 0.073349312, -0.07463184 0.12274134 0.073844202, -0.074192718 0.12383783 0.073349409, -0.074671954 0.12392429 0.073057599, -0.073951215 0.12435585 0.073057629, -0.073447861 0.12467757 0.073037006, -0.07243707 0.12531483 0.07299573, -0.076396868 0.12000105 0.074385896, -0.0777518 0.11913535 0.074384265, -0.078471109 0.11990052 0.074028514, -0.078458376 0.1212661 0.073288105, -0.079194225 0.12052777 0.07346525, -0.079823121 0.12095568 0.072804779, -0.076881915 0.12120694 0.073908716, -0.078085832 0.12163031 0.07319513, -0.080404915 0.12123954 0.072031476, -0.076078057 0.12185025 0.073843993, -0.073603556 0.12244394 0.074208729, -0.070886888 0.12365639 0.074315317, -0.070450105 0.12402683 0.07428398, -0.069570012 0.12476134 0.074214637, -0.070192523 0.12550461 0.073754832, -0.069092661 0.12408093 0.074432805, -0.071607418 0.12663454 0.072031632, -0.071920671 0.12559772 0.073008165, -0.070884906 0.12615728 0.073032878, -0.075608671 0.12065199 0.074354917, -0.075212389 0.12097517 0.074338257, -0.074495852 0.12141785 0.074338354, -0.075029097 0.12157556 0.074208453, -0.074200414 0.12176162 0.074299179, -0.072781228 0.12261507 0.074299157, -0.057650439 0.13029295 0.074331202, -0.058175988 0.13002837 0.074338749, -0.058901727 0.13101843 0.073844582, -0.06068708 0.13122496 0.073158294, -0.060127705 0.13247091 0.072032019, -0.063243747 0.13101187 0.072031915, -0.061400421 0.13065326 0.073349863, -0.060419425 0.13032559 0.073844559, -0.059860379 0.13136604 0.073349729, -0.060326874 0.13150561 0.073058061, -0.059562325 0.13185376 0.073058017, -0.05902613 0.13211721 0.073037453, -0.057838865 0.13154614 0.073815338, -0.057950228 0.13263702 0.072996184, -0.062480099 0.1278002 0.074386172, -0.063923433 0.12709156 0.074384682, -0.064552523 0.1279324 0.074029081, -0.064387046 0.12928808 0.073288567, -0.065201089 0.12863687 0.073465645, -0.065778121 0.12913251 0.07280533, -0.062827222 0.12905282 0.073909186, -0.063975975 0.12960836 0.073195748, -0.066324294 0.12947962 0.072031759, -0.061956391 0.1296021 0.073844597, -0.05943089 0.12991494 0.074208885, -0.056595527 0.13081571 0.074315563, -0.056120045 0.13113493 0.074284472, -0.05516313 0.1317662 0.074214973, -0.055698641 0.13257456 0.073755279, -0.054764956 0.13103655 0.074433155, -0.056978121 0.13385573 0.072032019, -0.057405494 0.13286054 0.0730085, -0.056313634 0.13330069 0.073033273, -0.061623983 0.12835875 0.074355423, -0.061194144 0.12863573 0.074338771, -0.060432389 0.12899509 0.074338771, -0.060944848 0.12921187 0.074208923, -0.060100392 0.12930366 0.074299507, -0.058594711 0.12999314 0.074299589, -0.09744963 0.10394028 0.074329823, -0.096626602 0.1047821 0.074314214, -0.098041378 0.10506091 0.073813878, -0.098870456 0.10421199 0.073843166, -0.097858399 0.10351706 0.074337214, -0.10062383 0.10381734 0.073156789, -0.10050733 0.10517782 0.0720305, -0.10296658 0.10277176 0.072030328, -0.10110825 0.1030421 0.073348217, -0.10007417 0.1030567 0.073843077, -0.099889949 0.10422325 0.073348254, -0.10037653 0.10420108 0.073056392, -0.099769801 0.10478219 0.073056482, -0.099350639 0.10520786 0.073035881, -0.098506734 0.10605392 0.072994657, -0.10118491 0.099992216 0.074384674, -0.10231341 0.098846823 0.07438302, -0.10318483 0.099432588 0.074027389, -0.10347613 0.10076681 0.073286839, -0.10402966 0.099883497 0.073463932, -0.1047378 0.1001606 0.072803661, -0.10192642 0.10106009 0.073907666, -0.10319414 0.10120487 0.073194072, -0.10536817 0.10030791 0.072030075, -0.10128582 0.10186598 0.073843062, -0.099005371 0.1029956 0.07420747, -0.096283317 0.10524064 0.074283049, -0.095588617 0.10615242 0.07421343, -0.096360989 0.10673866 0.073753878, -0.094971806 0.10559529 0.074431725, -0.097991839 0.1075252 0.072030596, -0.098066539 0.10644487 0.07300704, -0.097181141 0.10722074 0.073031798, -0.10056144 0.10080236 0.074353963, -0.10024707 0.10120562 0.074337229, -0.099646956 0.1017966 0.074337199, -0.10020223 0.10183176 0.074207477, -0.099435531 0.10219753 0.074298181, -0.098241776 0.10334545 0.074298017, -0.085198857 0.11419773 0.07433036, -0.086580321 0.11462671 0.073843755, -0.085652336 0.11382276 0.074337855, -0.088366717 0.11443064 0.073157415, -0.088098668 0.11576974 0.072031029, -0.090811893 0.11365402 0.072030991, -0.088934869 0.11371449 0.073348917, -0.087905765 0.11361343 0.073843792, -0.087592028 0.11475199 0.073348895, -0.088078134 0.11478445 0.073057026, -0.087409988 0.11529389 0.073057093, -0.086945876 0.11566994 0.073036522, -0.085661374 0.11537746 0.073814653, -0.086012766 0.11641642 0.072995253, -0.08935269 0.11069271 0.07438533, -0.090602256 0.10968083 0.074383743, -0.091402635 0.1103605 0.074028037, -0.091542967 0.11171904 0.073287547, -0.092191637 0.11090294 0.073464669, -0.092864417 0.11125779 0.072804287, -0.089969873 0.11183655 0.073908165, -0.091213547 0.11212263 0.073194653, -0.093474232 0.11147469 0.07203079, -0.089243174 0.11256596 0.073843651, -0.086850613 0.11343306 0.074208058, -0.084286645 0.11494192 0.07431487, -0.083894044 0.11535901 0.074283667, -0.083101787 0.11618742 0.074213989, -0.083803639 0.11685637 0.073754467, -0.082551353 0.11556482 0.074432246, -0.085336208 0.1178208 0.072031341, -0.085531354 0.1167554 0.073007591, -0.084564723 0.11742753 0.073032267, -0.088642426 0.11142781 0.074354589, -0.08828482 0.11179331 0.074337758, -0.087622188 0.11231333 0.074337773, -0.088170156 0.11241046 0.074208088, -0.087367296 0.11268815 0.074298672, -0.086052641 0.11369517 0.074298672, -0.13593256 -0.04270345 0.074321561, -0.13719909 -0.042750418 0.073805541, -0.13679391 -0.04386571 0.073834874, -0.13572854 -0.043255508 0.074329033, -0.13719891 -0.045616537 0.073148429, -0.13671039 -0.04638961 0.073339723, -0.13627519 -0.045451492 0.073834702, -0.13724642 -0.04477936 0.07333988, -0.13743742 -0.045227289 0.073048025, -0.13769759 -0.044428587 0.073048145, -0.13789944 -0.043866158 0.073027611, -0.13829564 -0.042738855 0.072986387, -0.13399641 -0.047781855 0.074376374, -0.13345382 -0.049295545 0.074374795, -0.13435973 -0.049826473 0.074019164, -0.13568829 -0.049510151 0.073278427, -0.1351323 -0.050392091 0.073455505, -0.13568933 -0.050909996 0.072795093, -0.13527979 -0.047986567 0.073899232, -0.13596056 -0.049065977 0.073185518, -0.13572839 -0.047059596 0.073834628, -0.1357564 -0.044514984 0.074199215, -0.13633399 -0.04159674 0.074305981, -0.13659787 -0.041088551 0.074274682, -0.13711806 -0.040066838 0.074205212, -0.13798134 -0.040508568 0.073745549, -0.13634865 -0.03975293 0.074423656, -0.13845673 -0.042172641 0.072998717, -0.13877173 -0.041038215 0.073023513, -0.13445564 -0.046868682 0.074345633, -0.13468267 -0.046410382 0.074328922, -0.13495459 -0.045613408 0.074328929, -0.13522707 -0.046098292 0.07419914, -0.13522384 -0.045248866 0.074289709, -0.13574028 -0.043675274 0.074289724, -0.13985877 -0.027215362 0.074322231, -0.14013368 -0.026070654 0.074306905, -0.14112253 -0.027120113 0.07380645, -0.14084473 -0.028273851 0.073835701, -0.13971771 -0.027786672 0.074329913, -0.14144318 -0.02996847 0.073149338, -0.1410445 -0.030791074 0.073340602, -0.14050679 -0.029907733 0.073835537, -0.1413966 -0.029131085 0.073340744, -0.14163658 -0.029554933 0.073048919, -0.14180578 -0.028731912 0.073048934, -0.14194337 -0.028150558 0.07302843, -0.14221089 -0.026986063 0.072987124, -0.13850321 -0.032478482 0.074377224, -0.13813359 -0.03404358 0.074375696, -0.13909331 -0.034469664 0.074019969, -0.14037798 -0.034006655 0.073279276, -0.13992439 -0.03494525 0.073456511, -0.14053594 -0.035397351 0.072795987, -0.13980161 -0.032538265 0.073900148, -0.14059889 -0.033534676 0.073186494, -0.14014338 -0.031567276 0.073835425, -0.13988647 -0.0290353 0.074200146, -0.14033905 -0.025535971 0.074275628, -0.14074147 -0.0244627 0.074206024, -0.14164871 -0.024804831 0.073746383, -0.13994178 -0.024236947 0.074424468, -0.1423074 -0.026405275 0.072999671, -0.14249352 -0.025242716 0.073024303, -0.13885719 -0.03151986 0.074346535, -0.13903156 -0.031039089 0.074329659, -0.1392125 -0.030216396 0.074329853, -0.13953768 -0.030667782 0.074200012, -0.13943943 -0.029824048 0.074290663, -0.13977653 -0.028202593 0.074290723, -0.12302315 -0.071880698 0.074319884, -0.12366061 -0.070891023 0.07430426, -0.12424725 -0.072208345 0.073803842, -0.12360402 -0.07320556 0.073833205, -0.12270121 -0.072373569 0.074327402, -0.12360913 -0.0750027 0.073146701, -0.12296126 -0.075647503 0.073338188, -0.12274539 -0.074636191 0.073833019, -0.12384197 -0.074196845 0.073338166, -0.12392842 -0.074676245 0.073046505, -0.12435989 -0.073955357 0.073046483, -0.12468168 -0.073451966 0.073025934, -0.12531894 -0.072441101 0.072984666, -0.12000519 -0.076400995 0.074374706, -0.11913951 -0.077755958 0.074373126, -0.11990462 -0.078475147 0.074017614, -0.12127022 -0.078462392 0.073276848, -0.12053192 -0.079198509 0.073454097, -0.12095992 -0.079827279 0.072793581, -0.12121111 -0.076886147 0.073897541, -0.1216345 -0.078090012 0.07318382, -0.12185436 -0.076082289 0.073833011, -0.12244806 -0.073607773 0.074197635, -0.12403093 -0.070454389 0.074272998, -0.12476553 -0.069574118 0.074203804, -0.12550864 -0.070196748 0.073743992, -0.12408519 -0.069096714 0.074422099, -0.12560198 -0.071924806 0.072997004, -0.12616149 -0.070888907 0.073021851, -0.12065616 -0.075612783 0.074343979, -0.12097938 -0.075216591 0.07432732, -0.12142192 -0.074500054 0.074327409, -0.12157972 -0.075033486 0.07419762, -0.1217658 -0.074204594 0.074288249, -0.12261922 -0.072785437 0.074288115, -0.13029709 -0.057654768 0.074320748, -0.13102277 -0.058905989 0.073833898, -0.13003261 -0.058180273 0.074328251, -0.13122919 -0.060691297 0.073147617, -0.13065746 -0.061404437 0.073338948, -0.13032988 -0.060423642 0.073833935, -0.13137011 -0.059864521 0.073339075, -0.13150975 -0.060331106 0.073047228, -0.13185789 -0.059566468 0.073047221, -0.13212131 -0.059030235 0.073026761, -0.13155025 -0.057843119 0.073804818, -0.13264123 -0.057954431 0.07298544, -0.12780428 -0.062484205 0.07437557, -0.1270957 -0.06392777 0.074374013, -0.12793665 -0.064556658 0.074018218, -0.12929219 -0.064391136 0.073277667, -0.12864113 -0.065205246 0.073454663, -0.12913667 -0.065782249 0.072794303, -0.12905701 -0.062831432 0.073898405, -0.12961258 -0.063980341 0.073184788, -0.12960623 -0.061960638 0.073833704, -0.12991922 -0.05943504 0.074198335, -0.13081977 -0.056599826 0.074305147, -0.13113898 -0.05612424 0.074274041, -0.13177033 -0.055167347 0.074204393, -0.13257867 -0.055702776 0.073744744, -0.13104074 -0.054769337 0.074422643, -0.13286474 -0.057409644 0.072997861, -0.13330477 -0.056317717 0.073022589, -0.12836292 -0.061628342 0.074344821, -0.12863986 -0.061198354 0.074328013, -0.12899938 -0.060436577 0.074328199, -0.12921593 -0.060948968 0.074198298, -0.12930796 -0.060104519 0.074288934, -0.12999727 -0.058598727 0.074288912, -0.13781486 0.03616181 0.074325904, -0.13916227 0.035635799 0.073839299, -0.1379357 0.035585821 0.074333534, -0.14043684 0.034368724 0.073152944, -0.14043456 0.033454627 0.073344231, -0.13956681 0.034017265 0.073839143, -0.14003152 0.035102963 0.073344395, -0.14043172 0.034825295 0.073052578, -0.14022715 0.03564024 0.073052615, -0.14009866 0.03622371 0.073032036, -0.13891207 0.036795825 0.073810063, -0.13983445 0.0373891 0.072990775, -0.13887709 0.030831695 0.074380815, -0.13922314 0.029261321 0.074379295, -0.14027268 0.029293776 0.07402356, -0.14122944 0.030268282 0.073282868, -0.14122772 0.029225945 0.073460087, -0.14197502 0.029083788 0.072799653, -0.14007296 0.031341076 0.073903613, -0.14122358 0.030789405 0.073190019, -0.13995939 0.032364488 0.073839054, -0.13862956 0.034534276 0.074203655, -0.13756573 0.037312448 0.074310392, -0.13751888 0.037883192 0.074279308, -0.1374158 0.039025038 0.07420972, -0.1383817 0.039110333 0.073750041, -0.13659734 0.038881361 0.074427918, -0.13966946 0.037954152 0.073003218, -0.13933274 0.039082259 0.073027939, -0.13878018 0.031849235 0.074350029, -0.13872842 0.032357901 0.074333251, -0.13853483 0.033177704 0.07433337, -0.13902357 0.032911956 0.074203581, -0.13856906 0.033629507 0.074294165, -0.13816901 0.035236597 0.074294239, -0.14099775 0.020504147 0.074325129, -0.14087892 0.021675378 0.074309498, -0.14215901 0.021011293 0.073809236, -0.14227793 0.019830525 0.073838443, -0.14105317 0.019918203 0.074332654, -0.14340243 0.018428713 0.073151976, -0.14329776 0.017520607 0.073343441, -0.1424986 0.018176854 0.073838249, -0.14308186 0.019203663 0.073343426, -0.14344837 0.01888296 0.073051587, -0.14333622 0.019715607 0.073051631, -0.14327407 0.020309716 0.073031232, -0.14314203 0.021497458 0.072989829, -0.14145631 0.01508829 0.074379846, -0.14162451 0.013489246 0.074378312, -0.14267108 0.013404071 0.074022502, -0.14373064 0.014265269 0.073282063, -0.14361253 0.013229728 0.073459119, -0.14433911 0.01300481 0.072798796, -0.1427018 0.015460879 0.073902637, -0.14378341 0.014783651 0.073189184, -0.14270352 0.016490519 0.073838279, -0.14162496 0.018795431 0.074202716, -0.14089629 0.022247791 0.07427834, -0.1409217 0.02339378 0.074208811, -0.14189114 0.023370534 0.073749132, -0.14009225 0.023342729 0.074427113, -0.1430414 0.022077531 0.073002309, -0.14283305 0.023236185 0.073027, -0.14147395 0.016110331 0.074349225, -0.14147963 0.016621798 0.074332416, -0.14137903 0.017457992 0.074332535, -0.14183493 0.017139375 0.074202567, -0.14146343 0.017903328 0.074293345, -0.14124593 0.019544959 0.074293301, -0.14202614 -0.011384934 0.074323244, -0.14327106 -0.011149108 0.073807359, -0.14312425 -0.012326449 0.073836528, -0.14194997 -0.011968493 0.074330844, -0.14390875 -0.013943464 0.073150247, -0.14360464 -0.014805466 0.073341563, -0.14297137 -0.013987958 0.073836356, -0.14376862 -0.013116568 0.073341578, -0.14405465 -0.013510823 0.073049799, -0.14413063 -0.012674004 0.073049806, -0.14420225 -0.012080997 0.07302916, -0.14433767 -0.010893822 0.072988093, -0.14126822 -0.016767025 0.074377999, -0.14107615 -0.018363416 0.074376531, -0.14207746 -0.018679678 0.074020825, -0.1433024 -0.018075496 0.07328032, -0.14295658 -0.019059002 0.07345739, -0.14361495 -0.019439816 0.072796948, -0.14256525 -0.016680926 0.073901013, -0.14346905 -0.01758188 0.073187292, -0.1427961 -0.015677631 0.073836386, -0.14225732 -0.013190478 0.074200973, -0.14217094 -0.010216832 0.074307762, -0.14231516 -0.0096623898 0.074276574, -0.1425951 -0.0085507631 0.074207067, -0.14353479 -0.0087892413 0.073747307, -0.14177491 -0.008415997 0.074425362, -0.14436868 -0.010305852 0.073000535, -0.14442334 -0.0091298521 0.073025316, -0.14151272 -0.015774578 0.074347325, -0.14163211 -0.015277237 0.074330524, -0.14171994 -0.014439613 0.07433065, -0.14209366 -0.014851689 0.074200988, -0.14190157 -0.014024228 0.074291527, -0.1420548 -0.012375325 0.074291646, -0.14240728 0.0045883656 0.074324057, -0.14360392 0.003775835 0.073837437, -0.14239696 0.0039998889 0.074331693, -0.14456455 0.0022568107 0.073151082, -0.14435899 0.0013661385 0.073342517, -0.14363812 0.0021077096 0.07383728, -0.14433277 0.0030628741 0.073342592, -0.14466117 0.00270316 0.073050797, -0.14464293 0.0035430789 0.073050812, -0.14464761 0.0041405261 0.073030204, -0.14361808 0.0049623251 0.073808342, -0.14464928 0.0053352714 0.07298895, -0.14225672 -0.00084456801 0.074379019, -0.14224477 -0.0024525225 0.074377477, -0.14327511 -0.0026544929 0.074021742, -0.14442471 -0.001917094 0.073281072, -0.14419122 -0.0029332042 0.073458225, -0.14488797 -0.0032377839 0.072797872, -0.14353594 -0.00061395764 0.073901892, -0.14453506 -0.0014078915 0.07318835, -0.14365299 0.00040897727 0.073837236, -0.14283928 0.0028201938 0.074201912, -0.14242041 0.0057655275 0.074308768, -0.14250173 0.0063324869 0.074277461, -0.14265537 0.0074685812 0.074207976, -0.14361601 0.0073367953 0.073748313, -0.14182532 0.0075106919 0.074426249, -0.14461434 0.0059230328 0.073001504, -0.144537 0.0070978403 0.073026232, -0.14238861 0.00016897917 0.074348226, -0.14245167 0.00067657232 0.074331522, -0.14244518 0.0015187562 0.074331671, -0.14286248 0.0011510253 0.074201882, -0.14257897 0.0019518137 0.074292377, -0.14254668 0.0036075711 0.074292481, 0.065925971 0.12630767 0.07433103, 0.066992357 0.12580881 0.074315369, 0.06678836 0.12723625 0.073815152, 0.065713033 0.12773845 0.073844478, 0.065391332 0.12655365 0.074338615, 0.064761326 0.12926298 0.073158339, 0.066084072 0.12960261 0.072031766, 0.06300056 0.13112903 0.07203199, 0.063869655 0.12946421 0.073349684, 0.064225048 0.12849286 0.073844612, 0.065386951 0.12870449 0.07334964, 0.065205336 0.12915638 0.073057726, 0.065954223 0.12877548 0.073057845, 0.06649445 0.12852058 0.073037148, 0.067571774 0.12800357 0.072995797, 0.060965776 0.12852937 0.074386299, 0.059511811 0.12921622 0.074384883, 0.059777007 0.13023216 0.074029148, 0.060940146 0.13094792 0.073288471, 0.059923485 0.13117838 0.073465869, 0.059951141 0.13193858 0.072805315, 0.061728701 0.12958193 0.073909163, 0.061446786 0.13082635 0.073195621, 0.05988194 0.13258219 0.072032034, 0.062701106 0.12924352 0.073844552, 0.064520344 0.12746406 0.074208871, 0.067538545 0.1256358 0.074284121, 0.06862855 0.1252816 0.074214593, 0.068926737 0.12620413 0.073754981, 0.068306446 0.12451541 0.07443279, 0.069130659 0.12800339 0.072031811, 0.068086118 0.12771714 0.073008239, 0.069111004 0.12713772 0.07303299, 0.061936229 0.12820831 0.074355438, 0.062420771 0.12804484 0.074338749, 0.0631769 0.12767348 0.074338704, 0.063026726 0.12820908 0.074208945, 0.063625082 0.1276063 0.074299529, 0.065102786 0.12685889 0.074299261, 0.028182544 -0.14554593 -0.067071147, 0.025762938 -0.14317855 -0.072032548, 0.029141806 -0.14252925 -0.072032548, 0.041207783 -0.14507976 -0.062008254, 0.03769438 -0.14603209 -0.062008187, 0.038540028 -0.14315149 -0.067072488, 0.031039618 -0.14496273 -0.067072563, 0.034158804 -0.14689931 -0.062008306, 0.030603372 -0.14768079 -0.062008284, 0.032504335 -0.14180019 -0.072032541, 0.035792023 -0.14386299 -0.067072436, 0.03584861 -0.14099196 -0.072032556, 0.044917248 -0.13837007 -0.072032377, 0.043407023 -0.14080128 -0.068750344, 0.041632436 -0.13939372 -0.072032504, 0.048174135 -0.14946058 -0.047008462, 0.044473864 -0.15060303 -0.04700841, 0.046102129 -0.14782763 -0.05284898, 0.047087096 -0.14074579 -0.066761695, 0.047969975 -0.1439842 -0.060008205, 0.045170777 -0.14210695 -0.06542366, 0.048177019 -0.13726929 -0.072032258, 0.048150308 -0.14392397 -0.060008071, 0.04705935 -0.14595804 -0.056448191, 0.052081108 -0.13897556 -0.066761658, 0.051409744 -0.13609153 -0.072032236, 0.054504938 -0.13804308 -0.066761568, 0.048943438 -0.14629537 -0.054290965, 0.051845126 -0.1482271 -0.047008269, 0.053256914 -0.14211351 -0.060007997, 0.058295771 -0.14012206 -0.060007863, 0.057138234 -0.14329374 -0.054290816, 0.056411147 -0.13913256 -0.063407727, 0.054134235 -0.14445499 -0.054290846, 0.056340054 -0.14514774 -0.05066856, 0.055484615 -0.14690357 -0.047008097, -0.0049118921 -0.14816797 -0.067071229, -0.0067441091 -0.14532143 -0.072032623, -0.0033053979 -0.14544031 -0.072032794, 0.007890664 -0.15061194 -0.062008508, 0.0042531714 -0.15075827 -0.06200844, 0.0057186931 -0.14813814 -0.067072667, -0.0019966438 -0.14823493 -0.067072831, 0.00061357766 -0.15081716 -0.062008582, -0.0030267537 -0.15078801 -0.062008508, 0.00013501942 -0.1454778 -0.072032794, 0.0028813258 -0.1482206 -0.067072771, 0.0035753176 -0.14543393 -0.072032757, 0.012999952 -0.14489591 -0.072032712, 0.010986656 -0.14692998 -0.068750836, 0.0095696077 -0.14516282 -0.072032787, 0.013707615 -0.15643287 -0.04700882, 0.0098458901 -0.15672326 -0.047008835, 0.01205086 -0.15437996 -0.052849367, 0.014586903 -0.14769489 -0.066762179, 0.014727071 -0.15104836 -0.060008593, 0.01241561 -0.14859524 -0.065423988, 0.016422957 -0.144548 -0.072032675, 0.014916167 -0.15102983 -0.060008407, 0.013400041 -0.1527701 -0.056448542, 0.019849531 -0.14708012 -0.066762045, 0.019836716 -0.14411914 -0.072032668, 0.022420198 -0.1467104 -0.066762, 0.015161887 -0.15351826 -0.054291353, 0.017561145 -0.1560474 -0.04700876, 0.020297676 -0.15040115 -0.060008489, 0.025653355 -0.1495809 -0.060008399, 0.023819074 -0.15241539 -0.054291271, 0.024036147 -0.1481967 -0.063408263, 0.020632088 -0.15287918 -0.054291457, 0.022628434 -0.15404543 -0.050669, 0.021403849 -0.15556669 -0.047008589, 0.088543214 -0.11890405 -0.067069612, 0.085336246 -0.1178208 -0.072031245, 0.08809869 -0.11576986 -0.072031125, 0.10007616 -0.11283255 -0.062006444, 0.097323768 -0.11521515 -0.062006474, 0.096835971 -0.11225265 -0.067070782, 0.090864249 -0.11713889 -0.067070931, 0.094514705 -0.11753035 -0.062006608, 0.09165056 -0.11977726 -0.062006801, 0.090811893 -0.11365402 -0.072030984, 0.094668947 -0.11408621 -0.067070797, 0.093474425 -0.11147475 -0.072030865, 0.10050736 -0.105178 -0.07203044, 0.10020133 -0.10802352 -0.068748474, 0.097991832 -0.10752529 -0.072030753, 0.10825304 -0.11375698 -0.047006458, 0.1054149 -0.11639193 -0.047006577, 0.10567784 -0.11318484 -0.052847117, 0.10349307 -0.10637701 -0.066759795, 0.10569333 -0.10891148 -0.060006127, 0.10235693 -0.10843468 -0.065421879, 0.10296659 -0.1027717 -0.072030425, 0.10582966 -0.10877916 -0.060006082, 0.10572909 -0.111085 -0.056446075, 0.10722415 -0.102615 -0.066759631, 0.10536825 -0.10030791 -0.072030231, 0.10900344 -0.10072327 -0.066759542, 0.10757295 -0.11057147 -0.054289028, 0.11102536 -0.11105299 -0.047006309, 0.10964504 -0.10493225 -0.060005978, 0.11332073 -0.10095173 -0.060005635, 0.1136538 -0.10431147 -0.054288715, 0.1111936 -0.10087782 -0.063405529, 0.11145124 -0.10666129 -0.0542887, 0.11373921 -0.1063284 -0.050666362, 0.1137301 -0.10828134 -0.047006086, 0.059863873 -0.1356256 -0.067070611, 0.056978136 -0.13385585 -0.072032027, 0.060127795 -0.13247094 -0.072031982, 0.072458625 -0.1322726 -0.062007338, 0.06924513 -0.13398284 -0.062007584, 0.069428675 -0.13098624 -0.067071736, 0.062519424 -0.13442105 -0.067071885, 0.065991335 -0.13561511 -0.062007569, 0.062698968 -0.13716829 -0.062007762, 0.063243799 -0.13101196 -0.072031796, 0.066908143 -0.13229159 -0.067071967, 0.06632439 -0.12947971 -0.072031803, 0.074582219 -0.12490574 -0.072031647, 0.0736508 -0.12761202 -0.068749458, 0.071607515 -0.12663466 -0.072031677, 0.080225006 -0.13499331 -0.047007635, 0.076871701 -0.13693058 -0.047007605, 0.077841617 -0.13386256 -0.052848212, 0.077226348 -0.1267392 -0.066760927, 0.07880754 -0.12969983 -0.060007304, 0.075660825 -0.12849253 -0.065422811, 0.077515282 -0.12310711 -0.072031595, 0.078969911 -0.12960106 -0.060007393, 0.078358889 -0.13182682 -0.056447357, 0.081701137 -0.12390193 -0.066760845, 0.08040493 -0.1212396 -0.072031327, 0.083856665 -0.12245345 -0.066760838, 0.080270708 -0.13173637 -0.054290168, 0.083529465 -0.132974 -0.047007382, 0.083545662 -0.12669963 -0.060007043, 0.088014998 -0.12363693 -0.060006976, 0.087592073 -0.12698641 -0.054289982, 0.085957468 -0.12309146 -0.063406788, 0.084921882 -0.12878716 -0.054289967, 0.087226532 -0.12897176 -0.050667614, 0.086783178 -0.1308738 -0.047007218, -0.019569308 -0.14415562 -0.072032809, -0.021984644 -0.14569083 -0.068750575, -0.022972919 -0.14365256 -0.072032601, -0.021446161 -0.15556091 -0.047008723, -0.025275767 -0.15498483 -0.047008589, -0.022604704 -0.15319073 -0.052849345, -0.018644921 -0.14723754 -0.066762194, -0.019254319 -0.15053838 -0.060008429, -0.020962022 -0.14763251 -0.06542398, -0.016154625 -0.14457822 -0.072032653, -0.019065805 -0.15056241 -0.060008481, -0.020931147 -0.15192154 -0.056448549, -0.013377376 -0.14780942 -0.06676203, -0.012731053 -0.14491969 -0.072032787, -0.01078888 -0.14802092 -0.066762127, -0.019379824 -0.15304297 -0.054291487, -0.017603546 -0.15604252 -0.047008775, -0.01367937 -0.15114683 -0.060008474, -0.0082755014 -0.15153879 -0.060008392, -0.010694273 -0.15389404 -0.054291457, -0.0095441341 -0.14982966 -0.06340839, -0.013904713 -0.15363726 -0.054291457, -0.01221779 -0.15521839 -0.050669141, -0.013750292 -0.15642914 -0.047008663, -0.037760004 -0.14335996 -0.06707105, -0.038912892 -0.14017725 -0.072032541, -0.035586983 -0.14105821 -0.072032571, -0.025822289 -0.14859134 -0.062008314, -0.029401049 -0.14792496 -0.062008269, -0.027389258 -0.14569661 -0.067072704, -0.034932718 -0.14407408 -0.067072384, -0.03296271 -0.14717218 -0.062008321, -0.036505066 -0.14633384 -0.062008299, -0.032241069 -0.14186031 -0.072032541, -0.030173942 -0.14514539 -0.06707257, -0.028877303 -0.14258304 -0.072032511, -0.051157147 -0.13618672 -0.072032213, -0.053853653 -0.13714579 -0.068750158, -0.054363653 -0.13493878 -0.072032124, -0.055524632 -0.14688835 -0.047008105, -0.059129976 -0.14547449 -0.047008231, -0.056126758 -0.14431986 -0.052848764, -0.050941721 -0.13939711 -0.066761717, -0.052270278 -0.14247945 -0.060008012, -0.053288504 -0.13926649 -0.065423578, -0.047922216 -0.13735846 -0.072032258, -0.05209177 -0.14254481 -0.060008049, -0.054212756 -0.14345491 -0.056448087, -0.045933433 -0.14112675 -0.066761829, -0.044660456 -0.13845319 -0.072032444, -0.043457069 -0.14190888 -0.066761814, -0.05294992 -0.14489344 -0.054290988, -0.051885433 -0.14821297 -0.047008283, -0.046970397 -0.14431325 -0.060008109, -0.041789226 -0.14589801 -0.060008243, -0.04467158 -0.14765584 -0.05429104, -0.042645887 -0.14394921 -0.063408017, -0.047744296 -0.14669105 -0.054291002, -0.046451502 -0.14860797 -0.050668769, -0.048214808 -0.14944738 -0.047008395, -0.068714678 -0.1313633 -0.067070343, -0.069130518 -0.12800357 -0.072031803, -0.06608399 -0.12960252 -0.07203187, -0.058240347 -0.13911968 -0.062007882, -0.061581053 -0.13767374 -0.062007695, -0.059124023 -0.13594878 -0.067072012, -0.066117294 -0.13268849 -0.067071877, -0.064885885 -0.13614738 -0.062007673, -0.06815289 -0.13454172 -0.062007591, -0.063000634 -0.13112915 -0.072031878, -0.061716102 -0.13479176 -0.067071982, -0.059881933 -0.13258228 -0.072032005, -0.10518187 -0.10050336 -0.072030187, -0.10802745 -0.10019749 -0.068748049, -0.10752939 -0.097987831 -0.072030045, -0.1137596 -0.10825041 -0.047006108, -0.11639448 -0.10541219 -0.047005832, -0.11318775 -0.10567501 -0.052846633, -0.1063806 -0.10348931 -0.066759646, -0.10891481 -0.10569 -0.060005933, -0.10843845 -0.10235307 -0.065421447, -0.10277569 -0.1029627 -0.07203038, -0.10878235 -0.10582638 -0.060005963, -0.1110881 -0.10572606 -0.056445912, -0.10261876 -0.10722056 -0.066760033, -0.10031192 -0.10536429 -0.072030537, -0.10072706 -0.1089997 -0.066759981, -0.11057443 -0.10756987 -0.054288827, -0.11105557 -0.11102274 -0.047006182, -0.10493551 -0.10964185 -0.060006276, -0.10095491 -0.11331746 -0.060006306, -0.10431443 -0.1136508 -0.054289125, -0.10088141 -0.11119005 -0.063406169, -0.10666408 -0.11144832 -0.05428905, -0.10633107 -0.11373627 -0.050666831, -0.10828391 -0.11372745 -0.047006428, -0.11890773 -0.08853963 -0.067067869, -0.11782493 -0.085332245 -0.072029322, -0.11577376 -0.088094682 -0.072029576, -0.11283604 -0.10007289 -0.062005639, -0.11521842 -0.097320318 -0.06200546, -0.11225642 -0.096832275 -0.067069888, -0.11714261 -0.090860635 -0.067069568, -0.11753384 -0.094511241 -0.062005356, -0.11978064 -0.091647059 -0.062005252, -0.11365816 -0.090807766 -0.072029695, -0.11408981 -0.094665229 -0.067069679, -0.11147877 -0.093470395 -0.072029889, -0.09622369 -0.11277908 -0.067069374, -0.095881753 -0.10941109 -0.072030708, -0.093267381 -0.11164793 -0.072030827, -0.087737888 -0.12267196 -0.062006831, -0.090673171 -0.12051871 -0.062006749, -0.087893978 -0.11938393 -0.06707117, -0.093986414 -0.11464897 -0.067070849, -0.093555458 -0.11829525 -0.06200669, -0.096383348 -0.11600283 -0.062006548, -0.090600833 -0.11382234 -0.072031036, -0.090163589 -0.11767906 -0.067071043, -0.087883681 -0.11593309 -0.072031029, -0.080179825 -0.12138867 -0.072031319, -0.083021939 -0.12172365 -0.068749279, -0.083028086 -0.11945856 -0.07203117, -0.086818874 -0.13085017 -0.047007255, -0.090019137 -0.12866941 -0.04700724, -0.086834379 -0.12821203 -0.052847937, -0.080684222 -0.12456632 -0.066760696, -0.082665086 -0.12727585 -0.060007095, -0.082942992 -0.12391672 -0.065422744, -0.077286631 -0.12325087 -0.072031543, -0.082505681 -0.1273793 -0.06000717, -0.084775962 -0.12779468 -0.056447133, -0.076186247 -0.12736699 -0.066760994, -0.07435032 -0.12504399 -0.072031528, -0.073945925 -0.12868068 -0.066761062, -0.08386483 -0.12947804 -0.054290012, -0.083565757 -0.13295129 -0.047007404, -0.077906273 -0.130243 -0.060007423, -0.073207624 -0.1329408 -0.060007468, -0.076408833 -0.13401341 -0.054290354, -0.073609158 -0.13085049 -0.063407242, -0.079189725 -0.13238901 -0.05429028, -0.078355789 -0.13454548 -0.050667956, -0.080261767 -0.1349715 -0.047007509, 0.13562925 0.059859991 0.067066252, 0.13099 0.069424868 0.067068428, 0.13398631 0.069241583 0.062003866, 0.13227612 0.072455078 0.06200403, 0.13442563 0.062515944 0.067066476, 0.13717164 0.062695324 0.062003553, 0.13561857 0.065987587 0.062003672, 0.13229591 0.066904515 0.067066684, 0.13499598 0.080222219 0.047004536, 0.13504317 0.077495486 0.05066663, 0.13693324 0.076868922 0.047004402, 0.12815566 0.074856907 0.066756085, 0.13223907 0.080572248 0.052842915, 0.12970309 0.078803986 0.060004428, 0.13306215 0.078053683 0.054289609, 0.13297664 0.08352676 0.04700467, 0.12960428 0.078966349 0.060004443, 0.12897786 0.076847136 0.063402489, 0.12927864 0.085241139 0.052843153, 0.13087645 0.086780488 0.047004968, 0.12779337 0.087452203 0.052843422, 0.12733927 0.077585936 0.065422222, 0.12670295 0.083542258 0.060004726, 0.12575842 0.08777079 0.05644314, 0.12364013 0.088011444 0.060005024, 0.12272331 0.084698498 0.065422595, 0.12448862 0.082081854 0.065422371, 0.12202986 0.082571387 0.068748891, 0.14554961 0.028178811 0.067064539, 0.1431552 0.038536131 0.067066729, 0.14603543 0.037690669 0.062002108, 0.14508314 0.041204274 0.062002376, 0.1449672 0.03103587 0.067064717, 0.14768437 0.030599743 0.06200178, 0.14690268 0.03415519 0.062001899, 0.14386752 0.035788387 0.067064926, 0.14946318 0.048171282 0.047002643, 0.14890236 0.045502633 0.050664842, 0.15060548 0.044471145 0.047002554, 0.14160068 0.04446283 0.066754296, 0.14685321 0.049126118 0.052841261, 0.14398751 0.04796648 0.060002774, 0.14709526 0.046487451 0.054287985, 0.1482297 0.051842391 0.047002971, 0.14392735 0.048146695 0.060002595, 0.14284503 0.046220183 0.063400805, 0.14500605 0.054336607 0.052841499, 0.14690618 0.055481941 0.04700321, 0.14405009 0.056822747 0.052841589, 0.141412 0.047305018 0.065420464, 0.14211686 0.053253531 0.060002998, 0.14213695 0.057586253 0.056441382, 0.14012532 0.058292329 0.06000334, 0.13849448 0.055266351 0.065420821, 0.13963333 0.052322388 0.065420762, 0.13734506 0.053346783 0.068747133, 0.086818829 0.13085017 0.047007367, 0.088044509 0.12841374 0.050669461, 0.090019226 0.12866932 0.047007114, 0.08298333 0.12304807 0.066758722, 0.084182963 0.12996918 0.052845791, 0.082665056 0.12727582 0.060007289, 0.086017311 0.128057 0.0542925, 0.083565712 0.13295114 0.047007486, 0.082505748 0.12737909 0.060007274, 0.082860708 0.12519798 0.063405186, 0.07949014 0.13289112 0.052845925, 0.080261707 0.13497138 0.047007635, 0.07719259 0.1342389 0.052845985, 0.081063852 0.12515262 0.065424904, 0.077906445 0.13024285 0.060007289, 0.075220719 0.13364291 0.056445733, 0.073207647 0.13294068 0.060007453, 0.073818997 0.12955806 0.065425232, 0.076544851 0.12796643 0.065424934, 0.07411705 0.12734053 0.068751454, 0.096223757 0.11277893 0.067069262, 0.087893918 0.11938378 0.067071244, 0.090673149 0.12051854 0.062006786, 0.087738052 0.12267187 0.06200701, 0.093987018 0.11464953 0.067069381, 0.096383363 0.11600283 0.062006578, 0.09355557 0.11829504 0.062006757, 0.09016411 0.11767966 0.067069605, 0.11890778 0.088539362 0.067067921, 0.11225647 0.096832126 0.067069948, 0.11521852 0.097320199 0.062005401, 0.11283609 0.10007268 0.062005594, 0.11714332 0.090860933 0.067068011, 0.11978059 0.091647029 0.062005207, 0.1175338 0.094511062 0.062005341, 0.11409049 0.094665796 0.067068279, 0.11375967 0.10825026 0.047006056, 0.11441234 0.10560238 0.050668254, 0.11639442 0.1054121 0.047006056, 0.10828443 0.10149741 0.06675747, 0.11099391 0.10797802 0.05284436, 0.10891484 0.10568982 0.060006052, 0.11235671 0.10570577 0.054291219, 0.11105558 0.11102253 0.047006309, 0.10878243 0.10582602 0.060006022, 0.1086432 0.10362071 0.063404024, 0.10706891 0.11187094 0.052844614, 0.10828395 0.11372742 0.047006384, 0.10512879 0.11369619 0.052844957, 0.10688131 0.10397646 0.065423638, 0.10493562 0.10964143 0.060006246, 0.10307382 0.11355397 0.056444481, 0.10095511 0.11331722 0.060006425, 0.10079844 0.10988331 0.06542404, 0.10310176 0.10772511 0.065423861, 0.10059558 0.10765523 0.068750203, 0.14336374 -0.037756383 -0.067065075, 0.14018115 -0.038908929 -0.072026819, 0.14106223 -0.035583079 -0.072026581, 0.14859486 -0.025818914 -0.062001556, 0.14792839 -0.029397726 -0.06200175, 0.14570026 -0.027385741 -0.067065924, 0.14407772 -0.034929067 -0.067066297, 0.1471757 -0.032959312 -0.062001899, 0.14633715 -0.036501586 -0.062002003, 0.1418643 -0.032237083 -0.072026402, 0.14514908 -0.030170321 -0.067066178, 0.14258698 -0.028873354 -0.072026193, 0.15556361 -0.02144894 0.046998784, 0.15390053 -0.023610234 0.050661013, 0.15498737 -0.025278509 0.046998575, 0.14687113 -0.021379054 0.06675069, 0.15362653 -0.019456446 0.052837268, 0.15054165 -0.019257784 0.059998915, 0.15269978 -0.021938771 0.054284081, 0.15604512 -0.017606407 0.046999082, 0.15056568 -0.019069284 0.0599989, 0.14875455 -0.020335555 0.063397154, 0.15422297 -0.013960421 0.052837655, 0.1564317 -0.013752997 0.046999156, 0.15444036 -0.01130566 0.052837789, 0.14793433 -0.018736333 0.065416753, 0.15115018 -0.013682842 0.059999302, 0.1530481 -0.0097878575 0.056437671, 0.15154217 -0.0082788467 0.059999526, 0.14875998 -0.010297626 0.065417215, 0.14850859 -0.013443947 0.065416992, 0.1468917 -0.011528343 0.068743616, 0.1564355 0.013704926 0.047000736, 0.15529498 0.011227667 0.050662965, 0.15672591 0.0098430812 0.047000602, 0.1479452 0.011838734 0.066752493, 0.15410353 0.01521641 0.052839249, 0.15105169 0.014723599 0.060000986, 0.15375242 0.01259008 0.054285914, 0.15604991 0.017558306 0.04700096, 0.15103316 0.014912724 0.060000986, 0.14954935 0.013275236 0.063399017, 0.15346216 0.02070722 0.052839592, 0.15556939 0.021401048 0.047001168, 0.15308329 0.023343921 0.052839831, 0.14839368 0.014651775 0.065418646, 0.15040459 0.020294189 0.060001284, 0.15138812 0.02451396 0.056439593, 0.14958413 0.025649816 0.060001522, 0.14732087 0.023062617 0.065419152, 0.14777598 0.019939244 0.065418929, 0.14577319 0.021447092 0.068745419, 0.14817169 -0.0049157739 0.067062706, 0.14814191 0.0057148039 0.067064732, 0.15076183 0.0042496622 0.0620002, 0.15061526 0.0078869462 0.062000409, 0.14823949 -0.0020004511 0.067062899, 0.15079142 -0.0030303597 0.061999902, 0.15082055 0.00060981512 0.062000021, 0.14822498 0.002877444 0.067063153, 0.14689112 -0.055527329 0.046996891, 0.14478877 -0.057264328 0.05065912, 0.14547715 -0.059132725 0.046996623, 0.13843217 -0.053524941 0.066748798, 0.14544594 -0.053153872 0.052835435, 0.14248279 -0.05227375 0.059997126, 0.1439901 -0.055367649 0.054282099, 0.1482155 -0.051888198 0.04699713, 0.14254808 -0.052095294 0.059997067, 0.14050072 -0.052926868 0.063395262, 0.14725046 -0.047928393 0.052835748, 0.14944991 -0.048217624 0.046997264, 0.1480532 -0.04538846 0.052835897, 0.14005685 -0.05118522 0.065414935, 0.14431661 -0.046973944 0.059997395, 0.14703363 -0.04359895 0.056435645, 0.14590117 -0.04179275 0.059997708, 0.14273967 -0.043141693 0.065415472, 0.14179447 -0.046153307 0.065415204, 0.1406444 -0.043925941 0.068741664, 0.13136685 -0.068710983 -0.067066774, 0.12800759 -0.069126546 -0.072028369, 0.12960663 -0.066080034 -0.072028369, 0.13912328 -0.058236986 -0.062003389, 0.13767713 -0.061577708 -0.062003583, 0.1359525 -0.059120208 -0.067067698, 0.13269213 -0.066113651 -0.06706813, 0.13615078 -0.064882368 -0.062003702, 0.13454509 -0.068149447 -0.062003836, 0.13113314 -0.062996596 -0.072028115, 0.13479555 -0.061712354 -0.067067936, 0.13258629 -0.059877872 -0.072027981, 0.1213926 -0.080175817 -0.072029114, 0.12172747 -0.083018184 -0.068747088, 0.11946255 -0.083024085 -0.072029188, 0.13085274 -0.086816251 -0.047004893, 0.12867203 -0.090016544 -0.047004998, 0.1282149 -0.086831391 -0.052845553, 0.12457012 -0.080680519 -0.066758409, 0.12727922 -0.082661808 -0.060004532, 0.12392047 -0.082939416 -0.065420404, 0.12325478 -0.077282727 -0.072028905, 0.12738261 -0.082502395 -0.060004517, 0.12779775 -0.084772944 -0.056444749, 0.12737072 -0.076182574 -0.066758126, 0.12504795 -0.074346364 -0.072028697, 0.12868439 -0.073942244 -0.066757962, 0.12948099 -0.083861887 -0.054287508, 0.1329539 -0.083563089 -0.047004625, 0.13024634 -0.077903003 -0.060004383, 0.13294409 -0.07320416 -0.060004205, 0.13401639 -0.076405734 -0.054287136, 0.13085395 -0.073605627 -0.063404009, 0.13239206 -0.079186767 -0.054287165, 0.13454835 -0.078353018 -0.050664738, 0.13497415 -0.080259174 -0.047004431, 0.11278269 -0.096219987 -0.067068279, 0.10941515 -0.095877618 -0.072029904, 0.11165202 -0.093263268 -0.072029769, 0.12267544 -0.087734491 -0.062004998, 0.12052214 -0.090669662 -0.062005028, 0.11938756 -0.087890267 -0.067069396, 0.11465287 -0.093982756 -0.067069724, 0.11829874 -0.093552083 -0.062005222, 0.11600635 -0.096379906 -0.062005475, 0.11382633 -0.090596825 -0.07202968, 0.11768282 -0.090159863 -0.067069516, 0.11593717 -0.087879777 -0.072029516, -0.013707638 0.15643266 0.047008894, -0.011230633 0.15529209 0.05067119, -0.0098457485 0.1567232 0.047008678, -0.011842623 0.14794138 0.066760048, -0.015219331 0.15410057 0.052847072, -0.014726967 0.15104812 0.060008422, -0.012593165 0.15374938 0.054293878, -0.017561063 0.15604714 0.047008812, -0.014916167 0.15102971 0.060008541, -0.013278797 0.14954573 0.063406616, -0.020710215 0.15345913 0.05284708, -0.02140376 0.15556651 0.047008775, -0.023346871 0.15308025 0.052847102, -0.014655516 0.14839 0.065426245, -0.020297602 0.15040097 0.060008481, -0.024517074 0.15138498 0.056446746, -0.025653273 0.14958072 0.060008422, -0.023066297 0.14731708 0.065426268, -0.019942909 0.14777231 0.06542626, -0.021450907 0.14576921 0.068752363, 0.0049119294 0.14816779 0.067071214, -0.0057186931 0.14813805 0.067072831, -0.0042532682 0.1507583 0.062008448, -0.0078905523 0.15061167 0.06200844, 0.001996696 0.14823577 0.067071237, 0.0030268431 0.15078789 0.062008433, -0.0006134361 0.15081695 0.06200844, -0.0028812885 0.14822119 0.067071252, -0.048174158 0.14946038 0.047008395, -0.045505412 0.14889944 0.050670557, -0.04447379 0.15060285 0.047008425, -0.044466496 0.1415967 0.066759698, -0.049128927 0.14685008 0.052846588, -0.047969967 0.14398417 0.060008198, -0.046490498 0.14709195 0.054293491, -0.051845133 0.14822683 0.047008418, -0.048150256 0.14392385 0.060008213, -0.046223752 0.1428414 0.063406132, -0.054339625 0.14500305 0.052846603, -0.055484645 0.14690337 0.04700844, -0.056825817 0.14404696 0.052846469, -0.047308631 0.14140826 0.065425761, -0.053256929 0.14211354 0.060008004, -0.05758933 0.14213371 0.056446247, -0.058295682 0.14012185 0.060007825, -0.055269964 0.1384908 0.065425627, -0.052326173 0.13962954 0.065425731, -0.053350717 0.1373412 0.068751946, -0.028182521 0.14554578 0.067071155, -0.038539894 0.14315134 0.067072541, -0.037694171 0.1460318 0.062008068, -0.041207738 0.14507958 0.062008172, -0.031039812 0.14496335 0.067071199, -0.030603342 0.14768064 0.062008321, -0.034158684 0.14689904 0.062008269, -0.035792276 0.14386371 0.067070991, 0.021446183 0.15556082 0.047008812, 0.023607388 0.15389752 0.050670952, 0.025275826 0.15498465 0.047008723, 0.021375179 0.14686733 0.066760078, 0.019453466 0.15362352 0.052846938, 0.019254342 0.15053827 0.060008466, 0.021935612 0.15269667 0.054293841, 0.017603621 0.15604237 0.047008798, 0.019066006 0.15056217 0.060008466, 0.020331889 0.14875108 0.063406482, 0.013957426 0.15422001 0.052847072, 0.013750255 0.15642899 0.047008857, 0.011302665 0.15443742 0.052847117, 0.018732667 0.14793056 0.065426275, 0.013679504 0.15114671 0.060008422, 0.0097846389 0.153045 0.056446686, 0.0082754493 0.15153873 0.060008556, 0.010293931 0.14875621 0.06542626, 0.013440371 0.14850497 0.065426186, 0.011524379 0.14688778 0.068752438, 0.037760049 0.14335978 0.067071021, 0.027389437 0.14569637 0.06707269, 0.029401138 0.14792466 0.062008455, 0.025822192 0.14859137 0.062008321, 0.034933016 0.14407471 0.067070976, 0.036505163 0.14633361 0.062008351, 0.032962725 0.14717215 0.062008366, 0.030174226 0.14514598 0.06707117, -0.14689095 0.055521995 0.047003176, -0.14478871 0.057258695 0.050665542, -0.14547719 0.059127331 0.047003426, -0.13843232 0.053517282 0.066754855, -0.14544596 0.053147823 0.052841492, -0.14248271 0.052266836 0.060002919, -0.14399008 0.05536139 0.05428838, -0.1482155 0.051882803 0.047002859, -0.14254802 0.05208841 0.060002901, -0.14050072 0.052919626 0.063401252, -0.14725041 0.047922313 0.052841123, -0.14944987 0.0482122 0.047002744, -0.14805302 0.0453825 0.05284084, -0.14005682 0.05117771 0.065420687, -0.14431666 0.046967059 0.060002703, -0.14703356 0.043592423 0.056440622, -0.14590108 0.041785866 0.060002413, -0.14273967 0.043134362 0.06542027, -0.14179447 0.046145976 0.065420404, -0.14064451 0.043918163 0.068746723, -0.13136682 0.068710864 0.067066789, -0.13595241 0.059120089 0.067067787, -0.1376771 0.061577469 0.06200343, -0.13912319 0.058236748 0.06200321, -0.13269292 0.066113889 0.067066729, -0.13454513 0.068149418 0.062003836, -0.13615067 0.064882189 0.062003653, -0.13479625 0.061712652 0.067066386, -0.13085264 0.086816132 0.047004815, -0.12841661 0.088041455 0.050667293, -0.12867191 0.090016305 0.047005087, -0.12305198 0.08297959 0.066756457, -0.12997212 0.084179968 0.05284315, -0.12727907 0.082661659 0.060004659, -0.12806015 0.086014241 0.054290093, -0.13295388 0.08356303 0.047004711, -0.12738256 0.082502335 0.060004655, -0.12520152 0.082857072 0.063402846, -0.13289419 0.079487115 0.052842908, -0.13497403 0.080259055 0.047004446, -0.13424192 0.077189565 0.052842688, -0.12515631 0.081060112 0.065422334, -0.1302464 0.077902824 0.060004357, -0.1336461 0.075217515 0.056442399, -0.13294412 0.07320419 0.060004156, -0.12956174 0.073815227 0.065421909, -0.12797022 0.076541245 0.065422058, -0.12734456 0.07411319 0.068748415, -0.11278265 0.096219808 0.067068398, -0.11938743 0.087889969 0.067069367, -0.12052214 0.090669602 0.06200508, -0.12267545 0.087734431 0.062004879, -0.11465333 0.093983084 0.067068249, -0.11600626 0.096379757 0.06200543, -0.11829865 0.093551993 0.062005319, -0.11768337 0.090160191 0.067067936, -0.080224991 0.13499326 0.047007598, -0.077498384 0.13504031 0.050669812, -0.076871485 0.1369305 0.047007732, -0.074860767 0.12815186 0.066759028, -0.080575235 0.13223612 0.052845895, -0.078807406 0.12969953 0.060007289, -0.078056671 0.13305894 0.054292694, -0.083529525 0.13297394 0.047007471, -0.078969896 0.12960088 0.060007244, -0.076850675 0.1289742 0.063405298, -0.085244022 0.12927571 0.05284562, -0.086783119 0.13087353 0.047007427, -0.08745525 0.12779048 0.052845508, -0.077589706 0.12733561 0.065424919, -0.083545662 0.12669951 0.060007185, -0.087774128 0.12575528 0.056445271, -0.088014893 0.12363669 0.060006887, -0.084702238 0.12271973 0.065424688, -0.082085572 0.12448499 0.065424748, -0.082575247 0.12202594 0.068751156, -0.059863858 0.13562542 0.067070536, -0.069428682 0.13098618 0.067071848, -0.06924513 0.13398272 0.062007576, -0.07245861 0.13227248 0.062007457, -0.06251993 0.13442186 0.067070521, -0.06269899 0.13716805 0.062007695, -0.065991327 0.13561496 0.062007494, -0.066908322 0.13229203 0.067070425, -0.10825298 0.11375692 0.047006488, -0.10560536 0.11440951 0.050668724, -0.10541473 0.11639175 0.047006458, -0.1015012 0.10828048 0.06675785, -0.10798103 0.11099085 0.052844524, -0.10569325 0.1089114 0.060006157, -0.10570887 0.11235377 0.054291509, -0.11102532 0.1110529 0.047006294, -0.10582956 0.10877892 0.060006186, -0.10362419 0.10863957 0.063404314, -0.11187392 0.10706577 0.052844323, -0.11372998 0.10828117 0.047006056, -0.11369924 0.10512587 0.052844323, -0.10397986 0.1068776 0.065423742, -0.10964496 0.10493216 0.06000594, -0.11355712 0.10307062 0.056443952, -0.11332072 0.10095164 0.060005747, -0.10988702 0.1007947 0.065423511, -0.10772891 0.10309801 0.06542363, -0.10765915 0.1005916 0.06874986, -0.088543169 0.11890391 0.067069694, -0.096835941 0.11225259 0.067070872, -0.09732382 0.11521491 0.062006414, -0.10007609 0.11283249 0.062006332, -0.090864785 0.11713946 0.067069568, -0.091650516 0.11977696 0.062006749, -0.094514631 0.11753032 0.06200663, -0.094669431 0.11408666 0.067069344, -0.13837406 -0.044913262 -0.072027087, -0.14080504 -0.043403178 -0.068744883, -0.13939762 -0.041628391 -0.072027035, -0.14946303 -0.04817155 -0.047002681, -0.1506056 -0.044471204 -0.047002554, -0.14783069 -0.046099126 -0.052843332, -0.14074951 -0.047083467 -0.066756614, -0.14398728 -0.047966719 -0.060002729, -0.14211053 -0.045167148 -0.065418191, -0.13727319 -0.048172802 -0.072027333, -0.14392728 -0.048146993 -0.060002781, -0.14596112 -0.047056258 -0.056442723, -0.13897917 -0.052077442 -0.066756628, -0.13609549 -0.051405728 -0.072027527, -0.13804662 -0.054501355 -0.066756971, -0.14629826 -0.04894051 -0.054285504, -0.1482296 -0.051842719 -0.047002994, -0.14211687 -0.053253651 -0.060003005, -0.14012536 -0.05829224 -0.060003236, -0.14329669 -0.057135105 -0.054285981, -0.13913602 -0.05640763 -0.063403144, -0.144458 -0.054131359 -0.054285899, -0.1451506 -0.056337148 -0.050663523, -0.14690617 -0.05548209 -0.047003098, -0.14554964 -0.028178871 -0.067064643, -0.14318259 -0.025758982 -0.072025947, -0.14253333 -0.02913779 -0.072026238, -0.1450832 -0.041204304 -0.062002376, -0.14603539 -0.037690848 -0.06200213, -0.14315517 -0.03853631 -0.067066513, -0.14496621 -0.031036019 -0.067066245, -0.14690274 -0.034155309 -0.062001988, -0.14768414 -0.030599982 -0.062001765, -0.14180423 -0.032500386 -0.072026387, -0.14386672 -0.035788327 -0.067066371, -0.14099592 -0.035844654 -0.072026655, -0.12490968 -0.074578226 -0.072028801, -0.1276159 -0.073646963 -0.068746559, -0.12663877 -0.071603417 -0.072028674, -0.13499598 -0.080222398 -0.047004543, -0.13693322 -0.076869041 -0.047004335, -0.13386545 -0.077838719 -0.052844971, -0.12674287 -0.077222645 -0.066758096, -0.1297031 -0.078804135 -0.06000445, -0.12849613 -0.075657129 -0.065419957, -0.12311111 -0.077511311 -0.072029009, -0.12960419 -0.078966558 -0.060004421, -0.13182977 -0.078355789 -0.056444481, -0.12390561 -0.081697345 -0.066758454, -0.12124363 -0.080400944 -0.072029091, -0.12245704 -0.083853036 -0.066758558, -0.13173926 -0.080267727 -0.054287285, -0.1329767 -0.08352679 -0.047004677, -0.12670305 -0.083542287 -0.060004652, -0.12364023 -0.088011593 -0.060005054, -0.12698942 -0.087589025 -0.054287657, -0.12309494 -0.085953981 -0.063404731, -0.12879017 -0.084918916 -0.054287553, -0.12897453 -0.087223679 -0.050665297, -0.13087636 -0.086780638 -0.047004856, -0.13562927 -0.05986008 -0.067066334, -0.13385984 -0.056974173 -0.072027773, -0.13247491 -0.060123891 -0.072027966, -0.13227613 -0.072455198 -0.062004007, -0.13398638 -0.069241703 -0.062003963, -0.13098988 -0.069425046 -0.067068309, -0.13442485 -0.062515765 -0.067067914, -0.13561843 -0.065987825 -0.062003821, -0.1371716 -0.062695444 -0.062003553, -0.13101602 -0.063239813 -0.072028123, -0.13229525 -0.066904306 -0.06706816, -0.12948373 -0.06632033 -0.072028369, -0.14336368 0.037763655 -0.067060836, -0.14018103 0.038916886 -0.072022408, -0.14106205 0.035590857 -0.072022557, -0.14859474 0.025825769 -0.061998576, -0.14792824 0.029404521 -0.061998352, -0.14570026 0.027392983 -0.067062922, -0.14407787 0.034936756 -0.067062512, -0.14717564 0.032966197 -0.061998256, -0.14633721 0.036508381 -0.061997883, -0.14186442 0.032245219 -0.07202293, -0.14514902 0.030177683 -0.067062691, -0.14258714 0.028881311 -0.072022922, -0.14415973 0.019573301 -0.072023511, -0.14569467 0.021988541 -0.06874124, -0.14365652 0.022976965 -0.072023332, -0.15556343 0.021448821 -0.046998858, -0.15498739 0.025278419 -0.046998553, -0.15319359 0.022607714 -0.052839391, -0.14724129 0.018648565 -0.066752777, -0.15054148 0.019257635 -0.059998915, -0.14763612 0.020965725 -0.065414555, -0.14458212 0.01615864 -0.072023585, -0.15056556 0.019069135 -0.0599989, -0.15192458 0.020934165 -0.056438893, -0.14781307 0.013381153 -0.066753082, -0.14492372 0.012735039 -0.072023958, -0.14802462 0.010792732 -0.066753186, -0.15304598 0.019383043 -0.054281741, -0.15604502 0.017606139 -0.046999015, -0.15115018 0.013682753 -0.059999287, -0.15154201 0.0082786977 -0.059999526, -0.15389711 0.010697365 -0.054282166, -0.1498332 0.0095477402 -0.063399427, -0.15364018 0.013907731 -0.054281913, -0.15522116 0.012220621 -0.050659709, -0.15643172 0.013752788 -0.046999149, -0.14489986 -0.012995899 -0.072025374, -0.14693376 -0.010982871 -0.068743117, -0.14516684 -0.0095655024 -0.07202509, -0.15643542 -0.013705015 -0.047000758, -0.15672587 -0.0098432302 -0.047000587, -0.15438277 -0.012047946 -0.052841343, -0.14769861 -0.014583141 -0.066754617, -0.15105176 -0.014723718 -0.060000882, -0.14859892 -0.012412071 -0.065416358, -0.14455181 -0.016418844 -0.072025523, -0.15103315 -0.014912844 -0.060000889, -0.15277311 -0.013397008 -0.0564408, -0.14708373 -0.019845903 -0.066755041, -0.14412314 -0.01983276 -0.072025783, -0.146714 -0.022416383 -0.066755116, -0.15352118 -0.015158862 -0.054283522, -0.15604994 -0.017558515 -0.047000982, -0.15040439 -0.020294398 -0.060001083, -0.14958401 -0.025650024 -0.060001388, -0.15241845 -0.023816049 -0.054284111, -0.1482003 -0.024032593 -0.063401274, -0.15288216 -0.020628959 -0.05428388, -0.15404812 -0.022625685 -0.050661676, -0.15556934 -0.021401316 -0.047001205, -0.14817163 0.0049155653 -0.067062713, -0.14532542 0.0067479908 -0.072024204, -0.14544426 0.0033094287 -0.07202448, -0.15061527 -0.0078870058 -0.062000521, -0.15076178 -0.0042497814 -0.062000342, -0.14814192 -0.0057149529 -0.067064732, -0.14823881 0.0020004213 -0.067064263, -0.15082049 -0.00060993433 -0.062000126, -0.15079138 0.0030301511 -0.061999895, -0.14548174 -0.00013098121 -0.072024539, -0.14822406 -0.0028776526 -0.06706465, -0.14543787 -0.0035713017 -0.07202474, 0.068714753 0.13136306 0.067070395, 0.059123963 0.13594869 0.067072198, 0.06158103 0.13767362 0.062007859, 0.058240294 0.1391198 0.062007815, 0.066117719 0.132689 0.06707041, 0.068152919 0.13454154 0.062007532, 0.064885944 0.13614714 0.06200771, 0.061716452 0.13479239 0.067070529, 0.028727777 -0.1418018 -0.073058523, 0.028177664 -0.14199516 -0.072975673, 0.029126853 -0.1413925 -0.07335031, 0.028269581 -0.14084062 -0.073845118, 0.029903553 -0.14050269 -0.073845103, 0.030663624 -0.13953364 -0.074209519, 0.031562954 -0.14013934 -0.073845059, 0.029819824 -0.13943535 -0.074299969, 0.030212194 -0.13920856 -0.07433933, 0.031034797 -0.1390273 -0.074339263, 0.031482913 -0.13877881 -0.074375354, 0.033952087 -0.13789877 -0.074434109, 0.032470837 -0.13966274 -0.073985204, 0.031513661 -0.13924819 -0.074242301, 0.029550701 -0.14163259 -0.073058538, 0.029964305 -0.14143908 -0.073158838, 0.030786984 -0.14104041 -0.073350199, 0.025964148 -0.13986927 -0.074385963, 0.024292983 -0.14017397 -0.074384972, 0.025651805 -0.14063832 -0.074174091, 0.024609782 -0.14117312 -0.074026816, 0.024990655 -0.14204696 -0.073457301, 0.026169367 -0.14036402 -0.074237868, 0.027182505 -0.14125693 -0.073724762, 0.027072988 -0.1423701 -0.072804645, 0.025367066 -0.1426875 -0.072800562, 0.02903109 -0.13988239 -0.074209511, 0.034265876 -0.13867 -0.074217416, 0.033441812 -0.14042526 -0.073357761, 0.033867709 -0.14013857 -0.073499613, 0.034710519 -0.1395438 -0.073757842, 0.035244562 -0.14034814 -0.07303524, 0.033640936 -0.14077872 -0.072998039, 0.034176022 -0.14063737 -0.073010482, 0.027246311 -0.13993332 -0.074308008, 0.027782485 -0.13971364 -0.074339308, 0.028198354 -0.13977233 -0.074299991, 0.044424258 -0.13769358 -0.073058397, 0.04389932 -0.13794747 -0.072975472, 0.044775143 -0.13724223 -0.073350064, 0.043861575 -0.13678977 -0.073844895, 0.045447297 -0.1362713 -0.073844828, 0.046094075 -0.13522291 -0.074209288, 0.045244619 -0.1352199 -0.07429976, 0.047055662 -0.13572425 -0.073844865, 0.045609057 -0.1349504 -0.074339107, 0.046406284 -0.13467842 -0.07433901, 0.046823658 -0.13438123 -0.074375041, 0.049178876 -0.1332303 -0.074433878, 0.047904387 -0.13514885 -0.073984928, 0.046906792 -0.13484427 -0.074242085, 0.045223132 -0.13743326 -0.073058344, 0.045612521 -0.13719481 -0.073158585, 0.046385363 -0.13670647 -0.073350191, 0.041461729 -0.13608262 -0.074385881, 0.0398352 -0.13657266 -0.074384741, 0.041237377 -0.13688171 -0.074173704, 0.040261835 -0.13752997 -0.074026547, 0.040738218 -0.1383557 -0.073457196, 0.041721076 -0.13655132 -0.074237652, 0.0428278 -0.13732517 -0.073724702, 0.042843737 -0.13844374 -0.072804421, 0.041183986 -0.13895011 -0.072800472, 0.044510961 -0.13575244 -0.074209295, 0.04957708 -0.13396159 -0.0742172, 0.048954658 -0.13579804 -0.073357582, 0.049345836 -0.13546559 -0.073499188, 0.050116673 -0.13478002 -0.073757596, 0.050737321 -0.13551947 -0.073035046, 0.049192026 -0.13612711 -0.072997801, 0.049708009 -0.13592651 -0.073010154, 0.04274299 -0.13600275 -0.074307859, 0.043251202 -0.13572451 -0.074338943, 0.043671139 -0.13573626 -0.074299842, -0.0035472214 -0.1446389 -0.073058799, -0.0041265935 -0.14470503 -0.072975926, -0.0037799627 -0.14359999 -0.073845275, -0.003067039 -0.14432883 -0.073350534, -0.0021119341 -0.1436342 -0.073845252, -0.0011552274 -0.14285839 -0.07420966, -0.0004132092 -0.14364898 -0.073845215, -0.0019560382 -0.14257488 -0.074300088, -0.0015230328 -0.14244092 -0.074339531, -0.0006807223 -0.1424475 -0.074339554, -0.00018852949 -0.14230487 -0.074375585, 0.0024145544 -0.14199632 -0.074434325, 0.00057791173 -0.1433863 -0.073985294, -0.00026301295 -0.14276931 -0.074242413, -0.002707161 -0.14465711 -0.073058687, -0.0022609979 -0.14456058 -0.073159009, -0.0013702661 -0.14435488 -0.073350467, -0.0058115348 -0.14213997 -0.074386194, -0.0075087249 -0.14206511 -0.074385129, -0.006287232 -0.14282 -0.074174128, -0.0074222311 -0.14310959 -0.074026868, -0.0072452277 -0.14404634 -0.073457554, -0.0057215765 -0.14266795 -0.074238002, -0.0049325228 -0.14376393 -0.073724911, -0.0052869171 -0.1448248 -0.072804756, -0.0070208013 -0.14475465 -0.072800718, -0.0028244779 -0.14283511 -0.074209698, 0.0025488585 -0.14281797 -0.074217707, 0.0013549402 -0.14434597 -0.073358119, 0.0018339232 -0.14416128 -0.07349968, 0.0027879104 -0.14376885 -0.073758051, 0.0031294897 -0.1446718 -0.073035412, 0.0014703199 -0.14473474 -0.072998241, 0.0020235702 -0.14471608 -0.073010683, -0.0045757964 -0.14248753 -0.074308358, -0.0040041879 -0.14239281 -0.074339442, -0.003611736 -0.14254257 -0.074300215, 0.012669988 -0.1441265 -0.073058695, 0.012101591 -0.14425725 -0.072975799, 0.012322351 -0.14312011 -0.073845193, 0.013112411 -0.14376464 -0.073350549, 0.013983749 -0.14296737 -0.073845208, 0.014847435 -0.14208934 -0.074209735, 0.014020167 -0.1418975 -0.074300148, 0.015673481 -0.14279217 -0.073845252, 0.014435425 -0.14171582 -0.074339353, 0.015273109 -0.14162791 -0.074339338, 0.015746176 -0.14143118 -0.074375615, 0.01829844 -0.14083311 -0.07443431, 0.016629003 -0.14242008 -0.073985286, 0.015724115 -0.14190099 -0.074242428, 0.013506696 -0.14405048 -0.073058695, 0.013939388 -0.14390469 -0.073159024, 0.014801323 -0.14360061 -0.073350474, 0.010139942 -0.14189672 -0.074386172, 0.0084453523 -0.14201254 -0.074385069, 0.0097434372 -0.14262584 -0.074174121, 0.0086481646 -0.14304084 -0.074026875, 0.0089288726 -0.14395183 -0.073457398, 0.010288604 -0.14241153 -0.07423801, 0.011195369 -0.14341217 -0.073724911, 0.01096198 -0.14450604 -0.072804779, 0.0092312023 -0.14463052 -0.072800733, 0.013186172 -0.14225319 -0.074209608, 0.018523842 -0.14163458 -0.074217662, 0.017508395 -0.14328662 -0.073357992, 0.01796367 -0.14304945 -0.07349965, 0.018867888 -0.14255267 -0.073758021, 0.01930847 -0.14341161 -0.073035426, 0.017666653 -0.14366016 -0.072998226, 0.018214308 -0.14357951 -0.073010638, 0.011406921 -0.14210406 -0.074308172, 0.011964373 -0.14194584 -0.074339502, 0.012371138 -0.1420505 -0.074300222, 0.087409966 -0.11529401 -0.073057093, 0.086998358 -0.11570698 -0.072974257, 0.086580381 -0.11462682 -0.073843628, 0.087592117 -0.1147522 -0.07334885, 0.087905839 -0.11361358 -0.073843516, 0.088170096 -0.11241063 -0.074208103, 0.089243159 -0.11256608 -0.073843539, 0.087367363 -0.11268827 -0.074298576, 0.087622292 -0.11231345 -0.074337825, 0.088284843 -0.11179349 -0.074337661, 0.08858081 -0.11137509 -0.074373789, 0.090423763 -0.10951087 -0.074432515, 0.089854389 -0.11174276 -0.073983692, 0.088812262 -0.11178473 -0.074240744, 0.088078089 -0.11478445 -0.073057018, 0.088366851 -0.11443081 -0.073157251, 0.088934951 -0.11371464 -0.073348731, 0.084081724 -0.11475199 -0.07438463, 0.082708187 -0.11575165 -0.074383676, 0.084133811 -0.11558032 -0.074172564, 0.083427094 -0.11651433 -0.074025393, 0.08414942 -0.11713642 -0.073455989, 0.084481187 -0.11510873 -0.07423652, 0.085781559 -0.11547369 -0.073723331, 0.08616583 -0.11652401 -0.072803192, 0.084766455 -0.11755028 -0.07279925, 0.086850636 -0.11343303 -0.074207924, 0.091040991 -0.11006954 -0.07421577, 0.091060005 -0.11200845 -0.073356248, 0.091319405 -0.11156547 -0.073497988, 0.091820575 -0.11066398 -0.073756143, 0.092650682 -0.11115688 -0.073033564, 0.091392815 -0.11224058 -0.072996527, 0.091813557 -0.11188099 -0.073008843, 0.085264534 -0.11425334 -0.0743066, 0.085652448 -0.11382282 -0.074337922, 0.086052552 -0.1136952 -0.074298546, 0.099769719 -0.10478234 -0.073056415, 0.099406816 -0.10523868 -0.072973669, 0.099890053 -0.10422352 -0.073348239, 0.098870464 -0.10421199 -0.073843077, 0.10007416 -0.10305679 -0.073842928, 0.10020214 -0.10183176 -0.07420741, 0.099435538 -0.10219765 -0.074298047, 0.10128587 -0.10186619 -0.073842928, 0.099647015 -0.10179675 -0.074337214, 0.10024718 -0.10120571 -0.074337035, 0.10049427 -0.10075685 -0.074373335, 0.10211698 -0.098698169 -0.07443203, 0.10180106 -0.10097963 -0.073982924, 0.1007701 -0.101138 -0.074240118, 0.10037656 -0.1042012 -0.073056445, 0.10062386 -0.1038174 -0.073156774, 0.10110816 -0.10304213 -0.073348254, 0.096401617 -0.10461634 -0.074384212, 0.095148765 -0.10576338 -0.07438311, 0.096546084 -0.10543361 -0.07417202, 0.09594848 -0.10644078 -0.074024864, 0.096735902 -0.10697803 -0.073455408, 0.096838601 -0.10492596 -0.074235842, 0.098171555 -0.10514313 -0.073722832, 0.098671012 -0.10614374 -0.072802633, 0.097395435 -0.10732037 -0.072798647, 0.099005468 -0.10299575 -0.0742075, 0.10279281 -0.099184006 -0.074215218, 0.10302892 -0.1011087 -0.073355675, 0.10323707 -0.10063952 -0.07349737, 0.10363413 -0.099687457 -0.073755622, 0.1045142 -0.1000843 -0.07303308, 0.10338562 -0.10130221 -0.072995856, 0.10376329 -0.10089755 -0.073008299, 0.097521245 -0.10398835 -0.074306145, 0.097858503 -0.10351714 -0.074337341, 0.098241858 -0.10334563 -0.07429792, 0.059562236 -0.13185385 -0.07305783, 0.059069067 -0.13216498 -0.072975233, 0.058901817 -0.13101867 -0.073844515, 0.059860311 -0.13136607 -0.073349647, 0.060419522 -0.13032568 -0.073844515, 0.060944788 -0.12921187 -0.074208975, 0.060100399 -0.12930375 -0.074299581, 0.06195651 -0.12960219 -0.073844478, 0.060432389 -0.12899524 -0.074338786, 0.061194085 -0.12863579 -0.074338652, 0.061575711 -0.12829357 -0.07437478, 0.063787162 -0.12688631 -0.074433491, 0.062735587 -0.12893552 -0.073984548, 0.061710089 -0.12874445 -0.074241683, 0.060326979 -0.13150585 -0.073057905, 0.060687125 -0.13122514 -0.073158205, 0.061400369 -0.13065338 -0.073349632, 0.056437954 -0.13058481 -0.074385539, 0.054876499 -0.13125375 -0.074384488, 0.056304425 -0.13140389 -0.07417348, 0.055407591 -0.13215727 -0.074026272, 0.055973448 -0.13292438 -0.073456801, 0.056748167 -0.13102147 -0.074237488, 0.05793456 -0.13166654 -0.073724248, 0.058075517 -0.13277605 -0.072804086, 0.056482933 -0.13346529 -0.072800115, 0.059430934 -0.12991509 -0.07420902, 0.0642647 -0.12756827 -0.074216813, 0.063851818 -0.12946293 -0.073357157, 0.064203374 -0.12908876 -0.073498979, 0.064892508 -0.12832117 -0.073757321, 0.065592103 -0.12898648 -0.073034599, 0.064124554 -0.12976322 -0.072997406, 0.064614773 -0.12950626 -0.073009871, 0.057702072 -0.13036177 -0.074307546, 0.058176138 -0.13002858 -0.074338801, 0.058594666 -0.12999323 -0.074299537, 0.073951118 -0.12435576 -0.07305745, 0.073495857 -0.12472031 -0.072974779, 0.07419277 -0.12383789 -0.073349327, 0.073201373 -0.12359992 -0.07384406, 0.074631989 -0.12274152 -0.073844038, 0.075029321 -0.12157571 -0.074208401, 0.074200474 -0.12176174 -0.074299067, 0.076078258 -0.1218504 -0.073844075, 0.074495807 -0.12141773 -0.074338228, 0.075212412 -0.12097529 -0.07433825, 0.075553343 -0.12059271 -0.074374378, 0.077593386 -0.11894652 -0.074433014, 0.076777712 -0.12110052 -0.073984221, 0.07573732 -0.12102565 -0.074241251, 0.074672036 -0.12392434 -0.073057458, 0.074998423 -0.12360513 -0.073157795, 0.075643308 -0.1229572 -0.073349215, 0.070704386 -0.12344462 -0.074385099, 0.069227718 -0.12428427 -0.074384011, 0.070663385 -0.12427363 -0.074173078, 0.069856644 -0.12512267 -0.074025847, 0.070504807 -0.12582168 -0.073456593, 0.071061455 -0.12384379 -0.074236996, 0.072312653 -0.12435204 -0.073723875, 0.072577059 -0.12543887 -0.072803728, 0.071071602 -0.12630203 -0.07279966, 0.073603615 -0.12244412 -0.07420864, 0.078144133 -0.11957076 -0.074216388, 0.077946082 -0.12149969 -0.07335683, 0.078253426 -0.1210885 -0.07349845, 0.078852341 -0.12024879 -0.073756732, 0.079622053 -0.12083149 -0.0730341, 0.078250676 -0.12176758 -0.072996974, 0.078709103 -0.1214574 -0.073009469, 0.071935683 -0.12308159 -0.074307151, 0.072369315 -0.12269717 -0.074338391, 0.072781257 -0.12261513 -0.074299097, -0.019719847 -0.14333227 -0.07305868, -0.020302959 -0.14333326 -0.072975926, -0.019208066 -0.14307773 -0.07335037, -0.019834734 -0.14227372 -0.073845208, -0.018180922 -0.14249462 -0.073845208, -0.01714348 -0.14183089 -0.074209586, -0.017907538 -0.14145935 -0.074300133, -0.017462201 -0.14137483 -0.074339353, -0.016494744 -0.14269957 -0.073845237, -0.016625993 -0.14147562 -0.074339405, -0.016121 -0.14138898 -0.074375562, -0.013499595 -0.14137381 -0.074434355, -0.015480354 -0.1425494 -0.073985405, -0.01624693 -0.14184216 -0.074242413, -0.01888708 -0.14344433 -0.073058672, -0.018432848 -0.1433984 -0.073158957, -0.017524704 -0.14329374 -0.073350467, -0.021690093 -0.14059541 -0.074386075, -0.02336815 -0.14033112 -0.074385084, -0.022239015 -0.14121789 -0.074174091, -0.023399189 -0.14137876 -0.074026786, -0.02332817 -0.14232937 -0.073457435, -0.021659821 -0.14113009 -0.07423798, -0.020998359 -0.14230767 -0.073724836, -0.021469206 -0.14332226 -0.072804712, -0.023184471 -0.14305842 -0.072800696, -0.018799588 -0.1416207 -0.074209608, -0.013458125 -0.14220548 -0.074217625, -0.014815621 -0.14358997 -0.073357992, -0.014319003 -0.14346015 -0.073499732, -0.01332701 -0.143177 -0.073758066, -0.013088681 -0.14411244 -0.073035412, -0.01474452 -0.14398941 -0.072998233, -0.014192641 -0.1440326 -0.073010638, -0.020501085 -0.14107931 -0.074308291, -0.019922435 -0.1410493 -0.074339345, -0.019549258 -0.14124188 -0.074300207, -0.03564439 -0.14022315 -0.073058389, -0.036223978 -0.14015877 -0.072975613, -0.035107292 -0.14002761 -0.073350228, -0.035640016 -0.13915831 -0.073844992, -0.034021452 -0.13956282 -0.073844969, -0.032916181 -0.13901946 -0.074209556, -0.032368682 -0.13995537 -0.073845021, -0.033633858 -0.13856483 -0.074299976, -0.033181831 -0.13853055 -0.074339226, -0.032362156 -0.13872436 -0.074339271, -0.031850465 -0.13869497 -0.074375391, -0.029244073 -0.13897347 -0.074434198, -0.031343959 -0.13991985 -0.073985182, -0.032026432 -0.1391311 -0.074242294, -0.034829505 -0.14042774 -0.073058397, -0.034372993 -0.14043292 -0.073158741, -0.033458762 -0.14043057 -0.073350281, -0.037295878 -0.13728291 -0.074385867, -0.038933799 -0.1368323 -0.074384749, -0.037911035 -0.13784006 -0.074173853, -0.039081901 -0.13786992 -0.074026495, -0.039117798 -0.13882259 -0.073457167, -0.037325725 -0.13781768 -0.074237764, -0.036800183 -0.13906172 -0.07372468, -0.037381776 -0.14001712 -0.072804533, -0.039056562 -0.13956296 -0.072800472, -0.034538321 -0.13862535 -0.074209563, -0.029295884 -0.13980439 -0.074217461, -0.03080003 -0.14102834 -0.073357865, -0.03029184 -0.14095482 -0.073499598, -0.029274434 -0.14078456 -0.073758028, -0.029142387 -0.14174074 -0.073035359, -0.03077393 -0.14143312 -0.072998032, -0.030230425 -0.1415379 -0.073010489, -0.036168545 -0.13789684 -0.074308001, -0.035590053 -0.13793147 -0.074339233, -0.03524074 -0.13816506 -0.074299999, -0.051120773 -0.13535044 -0.073058076, -0.051689468 -0.13522157 -0.072975397, -0.050997131 -0.13429281 -0.073844783, -0.050565034 -0.13521618 -0.073349997, -0.049434096 -0.13487613 -0.073844723, -0.048274867 -0.13446 -0.074209288, -0.048937231 -0.13392779 -0.074299611, -0.048484042 -0.13394445 -0.074339025, -0.047835648 -0.13545111 -0.073844768, -0.047691338 -0.1342288 -0.074338973, -0.047179602 -0.13425669 -0.074375205, -0.0446207 -0.13482535 -0.074434079, -0.046813421 -0.13553059 -0.073984966, -0.04740335 -0.13467047 -0.074242011, -0.050333843 -0.13564512 -0.073058233, -0.049880728 -0.13570127 -0.073158592, -0.048972152 -0.1358014 -0.07335005, -0.052432679 -0.13224378 -0.074385695, -0.054009818 -0.13161278 -0.074384563, -0.05310636 -0.13272852 -0.07417345, -0.054273166 -0.13262731 -0.074026264, -0.054415531 -0.13356981 -0.073456869, -0.052522093 -0.13277188 -0.074237488, -0.052139297 -0.13406706 -0.073724337, -0.052824147 -0.13495129 -0.072804265, -0.054437555 -0.13431251 -0.072800122, -0.049842671 -0.13388664 -0.07420934, -0.044765294 -0.13564512 -0.074217334, -0.046396852 -0.13669291 -0.073357522, -0.045883812 -0.13667694 -0.073499389, -0.044853762 -0.13662153 -0.073757671, -0.044829473 -0.13758665 -0.073035128, -0.046416439 -0.13709825 -0.072997794, -0.045888029 -0.13726303 -0.07301034, -0.051381178 -0.13298014 -0.074307591, -0.05081021 -0.1330795 -0.074338935, -0.050489344 -0.1333504 -0.074299619, -0.065954164 -0.12877557 -0.073057845, -0.066504896 -0.12858394 -0.072974972, -0.065386839 -0.12870461 -0.073349647, -0.065712929 -0.12773862 -0.073844396, -0.064225025 -0.1284931 -0.073844396, -0.063026622 -0.12820935 -0.074209012, -0.062701002 -0.12924358 -0.073844537, -0.063624986 -0.12760648 -0.07429935, -0.063176773 -0.12767363 -0.074338518, -0.062420815 -0.1280449 -0.07433866, -0.06191545 -0.12812999 -0.07437475, -0.059436217 -0.12898159 -0.074433707, -0.061694145 -0.12943697 -0.073984556, -0.062183991 -0.12851626 -0.074241854, -0.065205142 -0.12915653 -0.07305783, -0.064761378 -0.12926319 -0.073158108, -0.063869476 -0.12946433 -0.073349677, -0.066910118 -0.12554154 -0.074385278, -0.068406649 -0.12473804 -0.07438416, -0.067633703 -0.12594783 -0.074173212, -0.068781853 -0.12571654 -0.074025944, -0.069028921 -0.12663737 -0.073456496, -0.067058019 -0.12605652 -0.074237175, -0.066822678 -0.12738621 -0.073724113, -0.06760221 -0.1281884 -0.072803825, -0.0691339 -0.12737286 -0.072799966, -0.064520441 -0.12746406 -0.074208818, -0.059671782 -0.12978017 -0.074216969, -0.06141036 -0.13063857 -0.073357247, -0.060898654 -0.13068014 -0.073499009, -0.059868917 -0.13074052 -0.073757462, -0.059952892 -0.13170215 -0.073034853, -0.061475068 -0.13103908 -0.072997443, -0.060968503 -0.13126215 -0.073009908, -0.065947443 -0.12639117 -0.074307404, -0.065391347 -0.12655371 -0.074338548, -0.065102935 -0.12685892 -0.07429941, -0.10478628 -0.099765658 -0.073056161, -0.1052428 -0.099402696 -0.072973363, -0.10422748 -0.099885911 -0.073348053, -0.10421621 -0.098866463 -0.073842786, -0.10306083 -0.10007015 -0.073842831, -0.101836 -0.10019788 -0.074207321, -0.10220171 -0.099431336 -0.074297808, -0.10180081 -0.099642843 -0.074337117, -0.10187031 -0.10128176 -0.073842831, -0.10120992 -0.10024294 -0.074337117, -0.10076094 -0.10049003 -0.074373193, -0.098702125 -0.1021128 -0.07443203, -0.10098374 -0.10179687 -0.073983118, -0.10114209 -0.10076591 -0.07424026, -0.10420509 -0.10037252 -0.073056281, -0.10382144 -0.10061982 -0.073156528, -0.10304604 -0.10110426 -0.073348172, -0.1046204 -0.09639746 -0.074383669, -0.10576758 -0.095144629 -0.074382372, -0.10543772 -0.096541971 -0.074171446, -0.10644498 -0.095944345 -0.074024282, -0.10698212 -0.096731812 -0.073454849, -0.10493023 -0.096834391 -0.074235551, -0.10514708 -0.09816736 -0.073722303, -0.1061478 -0.098666996 -0.072802179, -0.10732425 -0.097391367 -0.072798058, -0.10299987 -0.099001259 -0.074207246, -0.099188186 -0.10278866 -0.07421533, -0.10111284 -0.10302478 -0.073355734, -0.10064351 -0.10323304 -0.073497482, -0.099691503 -0.10362998 -0.073755831, -0.10008837 -0.1045101 -0.07303331, -0.10130616 -0.10338151 -0.072995991, -0.10090159 -0.10375935 -0.073008433, -0.10399245 -0.097517043 -0.074305713, -0.10352127 -0.097854316 -0.074336961, -0.10334965 -0.098237664 -0.074297726, -0.11529803 -0.087406039 -0.073055461, -0.11571104 -0.08699435 -0.072972611, -0.1147562 -0.087588012 -0.073347405, -0.11463088 -0.086576223 -0.073842041, -0.11361764 -0.087901771 -0.073842108, -0.11241468 -0.088165939 -0.074206673, -0.11257009 -0.089238971 -0.073842175, -0.11269229 -0.087363154 -0.074297078, -0.11231753 -0.087618172 -0.07433635, -0.11179754 -0.088280767 -0.074336462, -0.11137918 -0.088576645 -0.074372604, -0.10951505 -0.09041959 -0.074431524, -0.11174686 -0.089850187 -0.07398247, -0.11178865 -0.08880803 -0.074239552, -0.11478849 -0.088074118 -0.07305558, -0.11443479 -0.088362813 -0.073155813, -0.11371861 -0.088930964 -0.07334733, -0.11475613 -0.084077507 -0.074382991, -0.11575581 -0.082704067 -0.074381776, -0.11558452 -0.084129483 -0.074170873, -0.11651842 -0.083423018 -0.074023589, -0.11714051 -0.084145427 -0.073454037, -0.11511284 -0.084477097 -0.074234776, -0.11547768 -0.085777462 -0.073721714, -0.116528 -0.086161673 -0.072801478, -0.11755433 -0.084762514 -0.072797403, -0.11343718 -0.08684656 -0.074206553, -0.1100736 -0.091036946 -0.074214764, -0.11201256 -0.091055959 -0.073354997, -0.1115696 -0.091315359 -0.073496819, -0.1106679 -0.091816485 -0.073755234, -0.11116092 -0.092646539 -0.073032603, -0.11224467 -0.091388702 -0.07299526, -0.11188499 -0.091809481 -0.073007673, -0.11425751 -0.085260421 -0.074304983, -0.11382711 -0.085648358 -0.074336253, -0.11369935 -0.086048633 -0.074297011, -0.092956729 -0.11087057 -0.073056743, -0.093450986 -0.11056122 -0.072974093, -0.092388004 -0.11092761 -0.073348589, -0.092490859 -0.10991323 -0.073843278, -0.091208138 -0.11098 -0.073843479, -0.089976616 -0.11096993 -0.074207857, -0.090425842 -0.11024916 -0.074298389, -0.089889206 -0.11205074 -0.073843509, -0.090003774 -0.11041439 -0.074337676, -0.089349285 -0.11094454 -0.074337669, -0.088875718 -0.11113995 -0.074373938, -0.086648032 -0.11252183 -0.074432716, -0.088950627 -0.11246338 -0.073983654, -0.089223422 -0.11145666 -0.074240766, -0.0923113 -0.11140853 -0.07305678, -0.091902345 -0.11161137 -0.073157184, -0.091077596 -0.11200586 -0.073348671, -0.093169034 -0.10750508 -0.074384294, -0.094449192 -0.10638854 -0.074383095, -0.093964972 -0.10774019 -0.074172206, -0.095032722 -0.10725906 -0.074024878, -0.095478557 -0.10810181 -0.073455535, -0.093427859 -0.10797396 -0.074236132, -0.093494251 -0.10932294 -0.073723048, -0.094432749 -0.10993132 -0.07280279, -0.09574464 -0.10879543 -0.072798803, -0.091267087 -0.10991114 -0.074207842, -0.087055385 -0.11324784 -0.074215956, -0.088941388 -0.11369798 -0.073356368, -0.088451788 -0.11385238 -0.0734981, -0.087461285 -0.11414033 -0.073756434, -0.087757148 -0.11505926 -0.07303381, -0.089093626 -0.11407408 -0.072996639, -0.088649474 -0.11440423 -0.073009044, -0.092419684 -0.10854739 -0.074306302, -0.091913618 -0.10882971 -0.074337713, -0.091700226 -0.10919142 -0.074298389, -0.079958186 -0.12058139 -0.073057421, -0.080484062 -0.12032923 -0.072974533, -0.079386607 -0.12057421 -0.073349126, -0.079602495 -0.11957783 -0.073843792, -0.078208312 -0.12049422 -0.073843949, -0.076985568 -0.12034634 -0.074208476, -0.077512816 -0.11968026 -0.074298874, -0.076777875 -0.12141061 -0.073844016, -0.077074923 -0.11979717 -0.074338108, -0.076365285 -0.12025094 -0.074338257, -0.075872622 -0.12039196 -0.074374281, -0.073504262 -0.12151584 -0.074433327, -0.075798981 -0.12171543 -0.073984228, -0.076182842 -0.12074566 -0.074241281, -0.079256624 -0.12104374 -0.073057406, -0.078827433 -0.1211994 -0.07315775, -0.077963799 -0.12149909 -0.07334917, -0.080545887 -0.11726069 -0.074384719, -0.081943199 -0.11629441 -0.074383713, -0.081310682 -0.11758348 -0.07417281, -0.082425587 -0.1172249 -0.074025378, -0.082774125 -0.11811227 -0.073456079, -0.080750816 -0.11775568 -0.074236557, -0.080665611 -0.11910346 -0.073723696, -0.081530221 -0.11981317 -0.072803378, -0.082960926 -0.11883131 -0.072799414, -0.078386538 -0.11943865 -0.074208453, -0.073827766 -0.12228301 -0.074216515, -0.075651519 -0.12294152 -0.07335683, -0.075147785 -0.12303984 -0.073498569, -0.074131213 -0.1232152 -0.073756881, -0.074322298 -0.12416151 -0.073034428, -0.075760745 -0.12333208 -0.072996996, -0.075282358 -0.12361047 -0.073009536, -0.079684742 -0.11821255 -0.074306875, -0.079150185 -0.11843655 -0.074338168, -0.07889761 -0.11877197 -0.074298821, 0.13185795 0.0595662 -0.073047265, 0.13216901 0.059072912 -0.07296443, 0.13102277 0.0589059 -0.073833913, 0.13137011 0.059864402 -0.073338971, 0.13032997 0.060423523 -0.073833808, 0.12921597 0.060949028 -0.074198246, 0.12960625 0.061960489 -0.073833704, 0.12930804 0.06010443 -0.074288845, 0.12899947 0.060436547 -0.07432805, 0.12863989 0.061198175 -0.074328005, 0.12829775 0.061579734 -0.074364126, 0.12689045 0.063791215 -0.074422836, 0.12893963 0.062739521 -0.073973715, 0.12874852 0.061714321 -0.074230999, 0.1315098 0.060331017 -0.073047087, 0.13122922 0.060691088 -0.073147416, 0.13065749 0.061404318 -0.073338926, 0.13058899 0.056442052 -0.074375108, 0.13125791 0.054880559 -0.07437405, 0.13140807 0.056308448 -0.074162945, 0.13216141 0.055411696 -0.074015707, 0.13292867 0.055977494 -0.073446229, 0.13102563 0.056752175 -0.074226826, 0.13167061 0.057938576 -0.07371369, 0.13278021 0.058079541 -0.072793335, 0.13346927 0.056486934 -0.07278955, 0.12991922 0.05943504 -0.074198201, 0.12757243 0.064268768 -0.07420598, 0.12946695 0.063855886 -0.073346347, 0.12909277 0.064207375 -0.073488131, 0.12832528 0.064896554 -0.073746338, 0.12899061 0.065596104 -0.073023736, 0.12976733 0.064128578 -0.072986469, 0.12951027 0.064618826 -0.072998896, 0.130366 0.057706207 -0.074296996, 0.13003261 0.058180094 -0.074328139, 0.12999727 0.058598667 -0.074288905, 0.12435998 0.073955238 -0.073046461, 0.12472437 0.073499829 -0.072963715, 0.12360398 0.073205411 -0.073833108, 0.1238419 0.074196786 -0.073338136, 0.1227455 0.074636042 -0.073832855, 0.12157983 0.075033367 -0.074197575, 0.1217657 0.074204624 -0.074287966, 0.12185441 0.07608223 -0.07383287, 0.12142207 0.074499935 -0.074327335, 0.12097944 0.075216621 -0.07432735, 0.12059683 0.075557381 -0.074363351, 0.11895069 0.077597409 -0.074421987, 0.12110481 0.076781809 -0.073973015, 0.12102976 0.075741351 -0.074230328, 0.12392847 0.074676037 -0.073046252, 0.12360933 0.075002432 -0.073146671, 0.12296127 0.075647265 -0.073338166, 0.12344871 0.070708483 -0.074374169, 0.12428837 0.069231749 -0.074373245, 0.12427773 0.070667505 -0.074162081, 0.12512667 0.069860727 -0.074014917, 0.12582576 0.070508748 -0.07344541, 0.12384795 0.071065634 -0.074225977, 0.12435606 0.072316825 -0.073712826, 0.12544286 0.072581023 -0.072792545, 0.126306 0.071075618 -0.0727887, 0.12244819 0.073607653 -0.074197516, 0.11957495 0.078148365 -0.074205264, 0.12150382 0.077950001 -0.073345631, 0.12109271 0.078257501 -0.073487312, 0.12025267 0.078856498 -0.073745593, 0.12083554 0.079626054 -0.073022828, 0.12177174 0.0782547 -0.072985679, 0.12146141 0.078713179 -0.072998255, 0.12308566 0.071939826 -0.074296266, 0.12270142 0.07237348 -0.074327394, 0.12261935 0.072785288 -0.074288115, 0.14180584 0.028731853 -0.073048905, 0.14199932 0.028181583 -0.072966203, 0.14084467 0.028273702 -0.073835596, 0.14139664 0.029130876 -0.073340759, 0.14050673 0.029907614 -0.073835433, 0.13953775 0.030667692 -0.074199945, 0.13943955 0.029823929 -0.074290559, 0.13921258 0.030216336 -0.074329734, 0.14014338 0.031566978 -0.073835313, 0.1390315 0.031038851 -0.074329719, 0.13878299 0.031487018 -0.074365839, 0.13790299 0.033956319 -0.074424535, 0.1396668 0.032474965 -0.073975503, 0.13925242 0.031517804 -0.074232653, 0.14163664 0.029554725 -0.07304889, 0.14144321 0.029968381 -0.073149279, 0.14104453 0.030791044 -0.073340729, 0.13987336 0.025968283 -0.074376836, 0.1401782 0.024297029 -0.074375674, 0.1406423 0.025655836 -0.074164703, 0.14117727 0.024613857 -0.074017555, 0.14205109 0.024994731 -0.073448062, 0.14036809 0.026173472 -0.074228585, 0.14126098 0.027186602 -0.073715359, 0.1423741 0.027077109 -0.072795108, 0.14269161 0.025371045 -0.072791144, 0.13988651 0.02903524 -0.074200094, 0.13867418 0.034270018 -0.074207783, 0.14042932 0.033445895 -0.073348135, 0.14014281 0.03387177 -0.073489845, 0.13954782 0.03471446 -0.073748097, 0.1403521 0.035248458 -0.073025316, 0.1407828 0.033644885 -0.072988272, 0.1406413 0.034180135 -0.073000744, 0.1399374 0.027250409 -0.074298695, 0.13971782 0.027786642 -0.074329898, 0.13977659 0.028202415 -0.074290618, 0.13769767 0.044428408 -0.07304804, 0.13795158 0.043903321 -0.072965309, 0.13679375 0.043865651 -0.073834762, 0.13724636 0.044779122 -0.07333982, 0.13627525 0.045451343 -0.073834568, 0.1352271 0.046098143 -0.07419908, 0.135224 0.045248806 -0.074289635, 0.13572823 0.047059774 -0.073834479, 0.13495457 0.045613289 -0.074328884, 0.1346826 0.046410263 -0.074328884, 0.13438529 0.046827883 -0.074364975, 0.1332345 0.049183011 -0.07442373, 0.13515308 0.047908425 -0.073974594, 0.13484836 0.046910942 -0.074231863, 0.1374374 0.0452272 -0.07304807, 0.13719887 0.045616537 -0.073148236, 0.13671055 0.046389341 -0.07333976, 0.13608681 0.041465849 -0.074375927, 0.13657682 0.039839357 -0.074374899, 0.13688596 0.041241407 -0.074163884, 0.13753414 0.040265858 -0.074016616, 0.13835983 0.040742278 -0.073447183, 0.13655549 0.041725159 -0.074227735, 0.13732934 0.042831868 -0.073714569, 0.13844773 0.042847693 -0.072794169, 0.13895404 0.041187942 -0.07279031, 0.13575654 0.044514894 -0.074199215, 0.13396566 0.049581051 -0.074206799, 0.13580209 0.048958629 -0.073347166, 0.13546957 0.049349815 -0.073488921, 0.13478406 0.050120622 -0.073747247, 0.13552351 0.050741285 -0.073024586, 0.13613111 0.049195975 -0.072987348, 0.13593054 0.049711913 -0.07299979, 0.13600689 0.04274711 -0.074297816, 0.13572869 0.043255299 -0.074329004, 0.13574041 0.043675244 -0.074289739, 0.079958245 0.12058952 -0.073043838, 0.080484033 0.12033731 -0.072961122, 0.07960254 0.11958602 -0.07383053, 0.079386666 0.12058237 -0.073335543, 0.078208342 0.12050235 -0.073830336, 0.076985717 0.12035444 -0.074194878, 0.077512756 0.11968857 -0.074285448, 0.07707493 0.11980551 -0.074324697, 0.07677795 0.12141874 -0.073830247, 0.076365262 0.12025914 -0.074324682, 0.07587266 0.12040019 -0.074360877, 0.073504373 0.12152416 -0.074419588, 0.075798929 0.12172392 -0.073970437, 0.076182753 0.12075391 -0.074227706, 0.079256803 0.12105164 -0.073043808, 0.078827515 0.1212073 -0.073144034, 0.077963918 0.12150717 -0.073335543, 0.080546021 0.11726898 -0.074371666, 0.08194311 0.11630288 -0.074370652, 0.081310734 0.11759177 -0.074159577, 0.082425639 0.11723307 -0.074012101, 0.082774237 0.11812037 -0.073442802, 0.080750778 0.117764 -0.074223399, 0.080665708 0.1191116 -0.073710129, 0.081530213 0.11982122 -0.072790027, 0.082961053 0.11883932 -0.072785988, 0.07838656 0.11944696 -0.074194983, 0.073827773 0.12229115 -0.074202776, 0.075651526 0.1229496 -0.073343009, 0.075147688 0.12304801 -0.073484778, 0.07413128 0.12322319 -0.073743135, 0.074322358 0.12416953 -0.073020414, 0.075760752 0.12334031 -0.072983176, 0.075282335 0.12361848 -0.072995678, 0.079684705 0.11822081 -0.074293613, 0.079150245 0.11844471 -0.074324816, 0.078897595 0.11878049 -0.074285582, 0.092956841 0.11087868 -0.073044285, 0.093451098 0.11056936 -0.072961643, 0.092490897 0.10992131 -0.073830947, 0.092388049 0.11093569 -0.07333611, 0.09120816 0.11098814 -0.073830947, 0.089976624 0.11097816 -0.0741954, 0.090425834 0.11025736 -0.074285939, 0.090003759 0.11042264 -0.074325293, 0.089889422 0.11205894 -0.073830977, 0.089349449 0.11095276 -0.074325278, 0.088875607 0.11114821 -0.074361414, 0.086648151 0.11252999 -0.07442008, 0.088950664 0.11247158 -0.073971018, 0.089223549 0.11146486 -0.074228212, 0.092311338 0.11141673 -0.0730443, 0.091902256 0.11161941 -0.073144525, 0.091077611 0.11201411 -0.073336124, 0.093169004 0.10751337 -0.074372217, 0.094449252 0.10639676 -0.07437104, 0.093965039 0.10774845 -0.074160114, 0.095032841 0.10726729 -0.074012771, 0.095478565 0.10810986 -0.073443323, 0.093427971 0.10798213 -0.07422398, 0.093494207 0.10933113 -0.073710874, 0.094432771 0.10993937 -0.072790474, 0.09574464 0.10880345 -0.072786599, 0.091267124 0.10991937 -0.074195489, 0.087055475 0.11325604 -0.074203223, 0.0889415 0.11370614 -0.073343635, 0.088451877 0.11386043 -0.073485255, 0.087461352 0.11414838 -0.073743552, 0.0877572 0.11506739 -0.073021039, 0.089093789 0.11408222 -0.072983697, 0.088649392 0.11441237 -0.07299611, 0.092419654 0.10855573 -0.074294135, 0.091913655 0.1088379 -0.074325264, 0.091700271 0.10919964 -0.074286118, 0.11529817 0.087414026 -0.073045731, 0.11571114 0.087002337 -0.072962865, 0.11463092 0.086584389 -0.073832259, 0.11475624 0.087596089 -0.073337436, 0.11361758 0.087909847 -0.073832229, 0.1124147 0.088174194 -0.074196711, 0.11269237 0.087371379 -0.074287266, 0.11257021 0.089247137 -0.073832124, 0.11231767 0.087626427 -0.07432647, 0.11179757 0.088289022 -0.0743265, 0.1113793 0.08858484 -0.074362591, 0.10951497 0.090427846 -0.074421272, 0.11174691 0.089858443 -0.073972166, 0.11178881 0.088816255 -0.074229449, 0.11478858 0.088082135 -0.073045596, 0.11443484 0.08837083 -0.073145926, 0.11371878 0.088939041 -0.073337451, 0.11475609 0.084085733 -0.074373454, 0.11575583 0.082712352 -0.07437253, 0.11558451 0.084137827 -0.074161395, 0.11651845 0.083431304 -0.074014097, 0.11714055 0.084153503 -0.073444694, 0.11511293 0.084485352 -0.074225351, 0.11547767 0.085785449 -0.073711976, 0.11652799 0.086169899 -0.072791755, 0.11755432 0.084770441 -0.072787881, 0.11343731 0.086854786 -0.074196801, 0.11007375 0.091044962 -0.074204549, 0.11201259 0.091064066 -0.073344812, 0.11156963 0.091323406 -0.073486522, 0.11066796 0.091824532 -0.073744848, 0.11116096 0.092654645 -0.073022246, 0.11224471 0.091396749 -0.072984979, 0.11188507 0.091817379 -0.072997391, 0.11425756 0.085268617 -0.074295461, 0.11382701 0.085656524 -0.074326694, 0.11369951 0.086056709 -0.074287415, 0.10478629 0.099773735 -0.073044986, 0.10524288 0.099410832 -0.072962284, 0.10421623 0.098874539 -0.073831722, 0.10422757 0.099893868 -0.073336691, 0.10306092 0.10007831 -0.073831618, 0.10183604 0.10020626 -0.074196085, 0.10220173 0.099439561 -0.07428655, 0.10187037 0.10128981 -0.073831394, 0.10180089 0.099651098 -0.074325874, 0.10120983 0.10025126 -0.074325755, 0.10076109 0.10049838 -0.074361876, 0.098702177 0.10212106 -0.074420527, 0.10098371 0.10180521 -0.073971584, 0.10114209 0.10077435 -0.074228734, 0.10420519 0.10038069 -0.073044926, 0.10382152 0.10062775 -0.07314527, 0.1030461 0.10111231 -0.07333675, 0.1046204 0.096405715 -0.074372768, 0.10576762 0.095152766 -0.074371651, 0.10543773 0.096550256 -0.07416068, 0.10644503 0.09595257 -0.074013412, 0.10698229 0.096739918 -0.073444009, 0.10493018 0.096842647 -0.074224576, 0.10514712 0.098175555 -0.073711261, 0.10614786 0.098675013 -0.07279107, 0.10732444 0.097399354 -0.072787151, 0.10299978 0.099009544 -0.074196219, 0.099188283 0.10279688 -0.074203834, 0.10111281 0.10303289 -0.073344156, 0.1006435 0.10324112 -0.073485762, 0.099691421 0.10363817 -0.073744237, 0.10008836 0.10451826 -0.073021531, 0.10130621 0.10338953 -0.072984293, 0.10090168 0.1037674 -0.07299681, 0.10399248 0.097525418 -0.074294746, 0.10352124 0.097862512 -0.074325979, 0.10334958 0.098246068 -0.074286774, 0.14022711 -0.035640389 -0.073052481, 0.14016277 -0.036219925 -0.072969764, 0.14003159 -0.035103202 -0.073344305, 0.13916239 -0.035636038 -0.073839158, 0.13956699 -0.034017324 -0.073839128, 0.1390236 -0.032912076 -0.074203581, 0.13995945 -0.032364547 -0.07383889, 0.13856903 -0.033629596 -0.07429415, 0.1385348 -0.033177614 -0.074333355, 0.13872862 -0.032358021 -0.074333385, 0.13869901 -0.031846434 -0.074369416, 0.13897762 -0.029239953 -0.074428022, 0.13992405 -0.031339854 -0.07397908, 0.13913533 -0.032022506 -0.074236304, 0.1404317 -0.034825474 -0.073052451, 0.14043698 -0.034368962 -0.07315281, 0.14043459 -0.033454806 -0.07334438, 0.13728702 -0.037291735 -0.074380249, 0.13683648 -0.03892979 -0.07437925, 0.13784423 -0.037906885 -0.07416825, 0.13787405 -0.039077848 -0.074021056, 0.13882658 -0.03911373 -0.073451608, 0.13782182 -0.037321538 -0.074232072, 0.13906586 -0.036796123 -0.073718876, 0.14002126 -0.037377775 -0.072798833, 0.13956702 -0.039052516 -0.072794899, 0.1386295 -0.034534186 -0.074203655, 0.13980848 -0.029291779 -0.074211285, 0.14103231 -0.030795902 -0.073351681, 0.14095896 -0.030287862 -0.073493406, 0.1407886 -0.02927044 -0.073751658, 0.14174488 -0.029138237 -0.073029026, 0.14143716 -0.030769974 -0.072991773, 0.14154197 -0.030226499 -0.07300429, 0.13790095 -0.036164343 -0.074302271, 0.13793576 -0.03558597 -0.074333504, 0.13816908 -0.035236746 -0.074294105, 0.14333633 -0.019715816 -0.073051617, 0.14333725 -0.020298898 -0.07296893, 0.14227778 -0.019830644 -0.073838323, 0.14308193 -0.019203931 -0.073343471, 0.14249852 -0.018176973 -0.073838174, 0.14183494 -0.017139435 -0.074202731, 0.14146349 -0.017903298 -0.074293211, 0.14270356 -0.016490668 -0.073838055, 0.14137903 -0.017458141 -0.074332461, 0.14147973 -0.016621947 -0.074332386, 0.14139307 -0.016116858 -0.074368462, 0.14137806 -0.013495505 -0.074427187, 0.14255361 -0.015476316 -0.073978186, 0.14184636 -0.016242802 -0.074235409, 0.14344829 -0.01888299 -0.073051617, 0.14340243 -0.018428862 -0.073151886, 0.14329782 -0.017520756 -0.073343381, 0.14059964 -0.021686018 -0.074379414, 0.14033525 -0.023363948 -0.074378416, 0.14122219 -0.022234917 -0.074167296, 0.14138287 -0.023394942 -0.074020132, 0.14233361 -0.023324281 -0.073450819, 0.14113438 -0.021655768 -0.074231252, 0.14231175 -0.020994306 -0.073718056, 0.14332625 -0.021465361 -0.072798014, 0.14306238 -0.023180485 -0.07279405, 0.14162487 -0.01879549 -0.074202716, 0.14220947 -0.01345402 -0.074210346, 0.14359409 -0.014811695 -0.073350787, 0.14346421 -0.014315009 -0.073492527, 0.14318094 -0.013323039 -0.073750824, 0.14411661 -0.013084739 -0.073028117, 0.14399344 -0.014740497 -0.072990924, 0.14403668 -0.014188647 -0.073003486, 0.14108345 -0.020496935 -0.074301451, 0.14105329 -0.019918263 -0.07433258, 0.14124599 -0.019544989 -0.074293211, 0.14413063 0.012673914 -0.073049858, 0.14426138 0.012105554 -0.072967038, 0.14312422 0.012326419 -0.073836476, 0.14376865 0.013116539 -0.073341548, 0.14297149 0.013987839 -0.073836386, 0.14209358 0.01485166 -0.074200809, 0.14279608 0.015677452 -0.073836282, 0.14190151 0.014024228 -0.074291319, 0.14171997 0.014439553 -0.074330658, 0.14163211 0.015277207 -0.074330613, 0.14143528 0.015750259 -0.074366674, 0.14083736 0.01830247 -0.074425399, 0.14242417 0.016633034 -0.073976338, 0.14190519 0.015728295 -0.074233592, 0.14405459 0.013510734 -0.073049739, 0.14390877 0.013943374 -0.073150098, 0.14360471 0.014805406 -0.073341593, 0.14190096 0.010144174 -0.074377641, 0.14201674 0.0084494352 -0.074376598, 0.1426301 0.009747535 -0.074165568, 0.14304487 0.0086522996 -0.074018285, 0.14395595 0.0089329183 -0.073448971, 0.14241558 0.010292679 -0.074229419, 0.14341632 0.011199504 -0.073716313, 0.14451015 0.010965973 -0.072796091, 0.14463454 0.0092352033 -0.072792202, 0.14225744 0.01319024 -0.074201018, 0.14163882 0.018527836 -0.074208587, 0.14329065 0.01751247 -0.073348954, 0.14305356 0.017967761 -0.073490724, 0.14255674 0.018871933 -0.073748931, 0.14341578 0.019312441 -0.07302627, 0.14366424 0.017670691 -0.072989061, 0.14358352 0.018218279 -0.073001459, 0.14210816 0.011411041 -0.074299619, 0.14194997 0.011968344 -0.074330747, 0.14205478 0.012375176 -0.074291468, 0.14464298 -0.0035431683 -0.073050797, 0.14470921 -0.0041227043 -0.072968066, 0.14360395 -0.0037758648 -0.073837474, 0.14433283 -0.0030630231 -0.073342502, 0.14363816 -0.0021078885 -0.073837221, 0.14286259 -0.0011511743 -0.074201733, 0.14257911 -0.0019519627 -0.074292347, 0.14365312 -0.00040918589 -0.073837265, 0.14244509 -0.0015188456 -0.074331477, 0.14245157 -0.00067654252 -0.074331492, 0.14230895 -0.00018444657 -0.074367598, 0.14200057 0.0024187267 -0.074426278, 0.14339057 0.00058200955 -0.073977217, 0.14277351 -0.00025892258 -0.074234441, 0.14466113 -0.0027032793 -0.073050663, 0.14456463 -0.0022569597 -0.073151052, 0.14435899 -0.0013663173 -0.073342487, 0.14214399 -0.0058073997 -0.074378565, 0.14206931 -0.0075044632 -0.074377581, 0.14282414 -0.006283164 -0.074166492, 0.14311382 -0.0074180663 -0.074019194, 0.14405045 -0.0072411299 -0.073449805, 0.14267209 -0.0057174861 -0.074230298, 0.14376791 -0.0049284101 -0.073717177, 0.14482883 -0.0052828789 -0.072796941, 0.14475869 -0.0070167482 -0.072792977, 0.14283934 -0.0028203428 -0.074201807, 0.14282215 0.0025530159 -0.074209496, 0.14434999 0.0013589859 -0.073349878, 0.14416534 0.001837939 -0.073491678, 0.14377287 0.002791971 -0.073749825, 0.14467588 0.0031335354 -0.073027045, 0.14473891 0.0014744103 -0.072989926, 0.14472008 0.0020274818 -0.073002443, 0.14249179 -0.0045717657 -0.074300528, 0.14239699 -0.0040000379 -0.074331746, 0.14254671 -0.0036076903 -0.074292332, 0.13535452 -0.051116675 -0.073053509, 0.13522568 -0.051685482 -0.072970748, 0.13522036 -0.050561041 -0.07334514, 0.13429697 -0.050993174 -0.073840007, 0.13488024 -0.049430072 -0.073839903, 0.134464 -0.048270762 -0.074204415, 0.13393193 -0.04893297 -0.074294925, 0.13394853 -0.048480093 -0.0743341, 0.13545527 -0.047831625 -0.073839858, 0.13423288 -0.047687203 -0.074334085, 0.13426074 -0.047175527 -0.074370235, 0.13482943 -0.04461664 -0.074428871, 0.13553473 -0.046809226 -0.073979899, 0.13467464 -0.047399282 -0.074237138, 0.13564906 -0.050329804 -0.073053464, 0.13570534 -0.04987675 -0.07315369, 0.1358054 -0.048967987 -0.07334505, 0.13224792 -0.052428544 -0.074381232, 0.13161689 -0.054005682 -0.074380115, 0.13273281 -0.053102225 -0.07416907, 0.13263127 -0.054268867 -0.074021921, 0.13357398 -0.054411501 -0.073452562, 0.13277602 -0.05251798 -0.074232996, 0.13407116 -0.052135229 -0.073719859, 0.13495535 -0.052820146 -0.072799698, 0.13431646 -0.054433495 -0.072795719, 0.13389082 -0.049838722 -0.074204385, 0.13564938 -0.04476124 -0.074212193, 0.13669702 -0.046392828 -0.073352575, 0.13668102 -0.045879841 -0.073494226, 0.13662554 -0.044849694 -0.073752552, 0.13759074 -0.044825435 -0.073029965, 0.13710228 -0.046412438 -0.072992742, 0.13726711 -0.045884013 -0.073005185, 0.13298428 -0.051377088 -0.074303046, 0.13308367 -0.050806224 -0.074334264, 0.13335465 -0.050485164 -0.074294999, 0.12877971 -0.065950096 -0.073054388, 0.12858801 -0.066500902 -0.072971478, 0.12870863 -0.065382957 -0.073346108, 0.12774268 -0.065709025 -0.073840797, 0.12849724 -0.064220995 -0.073840812, 0.12821347 -0.063022494 -0.074205235, 0.12761059 -0.063620925 -0.074295744, 0.12767784 -0.063172728 -0.074334905, 0.12924773 -0.062697023 -0.073840708, 0.12804911 -0.062416583 -0.074334964, 0.12813415 -0.061911374 -0.074371025, 0.12898566 -0.05943206 -0.07442975, 0.12944111 -0.061690032 -0.073980808, 0.12852032 -0.062179953 -0.074237898, 0.12916054 -0.065201133 -0.073054209, 0.12926722 -0.064757258 -0.073154464, 0.12946835 -0.063865542 -0.073345974, 0.12554584 -0.066905916 -0.074381948, 0.12474213 -0.068402499 -0.074380964, 0.12595215 -0.067629665 -0.074169993, 0.12572072 -0.06877774 -0.074022681, 0.12664136 -0.069024861 -0.073453233, 0.12606061 -0.067053974 -0.074233904, 0.12739038 -0.066818625 -0.073720619, 0.12819234 -0.067598343 -0.072800413, 0.12737688 -0.069129944 -0.072796509, 0.12746832 -0.064516276 -0.07420525, 0.12978426 -0.059667587 -0.074213043, 0.13064271 -0.061406285 -0.07335332, 0.13068417 -0.060894608 -0.073495105, 0.13074446 -0.059864879 -0.073753312, 0.13170622 -0.059948772 -0.07303077, 0.1310432 -0.061471075 -0.072993621, 0.13126624 -0.060964495 -0.073005989, 0.12639526 -0.06594342 -0.07430391, 0.12655789 -0.065387309 -0.074335098, 0.12686309 -0.065098673 -0.074295834, 0.12058543 -0.079954207 -0.073054999, 0.1203333 -0.080480069 -0.072972327, 0.11958192 -0.079598427 -0.073841646, 0.12057837 -0.079382688 -0.073346794, 0.12049829 -0.078204215 -0.073841631, 0.12035055 -0.076981455 -0.074206159, 0.11968442 -0.077508658 -0.074296534, 0.11980145 -0.077070802 -0.074335739, 0.12141472 -0.076773852 -0.073841527, 0.12025504 -0.07636115 -0.074335739, 0.12039614 -0.075868547 -0.074371874, 0.12151991 -0.073500186 -0.074430585, 0.12171961 -0.075794786 -0.073981613, 0.12074982 -0.07617873 -0.074238732, 0.12104772 -0.07925263 -0.073054954, 0.12120338 -0.078823417 -0.073155358, 0.12150314 -0.077959776 -0.073346823, 0.11726487 -0.080541819 -0.074382782, 0.11629868 -0.081939012 -0.074381664, 0.11758757 -0.081306458 -0.074170724, 0.1172291 -0.082421511 -0.074023366, 0.11811642 -0.082770199 -0.073454097, 0.11775985 -0.080746621 -0.074234664, 0.11910764 -0.080661565 -0.073721498, 0.11981723 -0.081526041 -0.072801217, 0.11883539 -0.082956851 -0.072797239, 0.11944276 -0.078382462 -0.074206188, 0.12228706 -0.07382369 -0.074213803, 0.12294541 -0.075647444 -0.073354185, 0.12304396 -0.075143635 -0.073495805, 0.12321923 -0.074127138 -0.073754162, 0.12416554 -0.074318349 -0.073031545, 0.12333617 -0.075756729 -0.072994307, 0.12361456 -0.075278372 -0.073006913, 0.11821668 -0.079680562 -0.07430476, 0.11844055 -0.079146057 -0.074335888, 0.11877618 -0.078893483 -0.074296609, 0.11087471 -0.092952728 -0.073055804, 0.1105653 -0.093447119 -0.072973043, 0.1099174 -0.092486829 -0.073842332, 0.11093163 -0.092383891 -0.073347449, 0.11098413 -0.091203988 -0.073842362, 0.11097416 -0.089972407 -0.07420668, 0.1102533 -0.090421826 -0.074297249, 0.11205482 -0.089885235 -0.073842213, 0.11041854 -0.089999646 -0.074336499, 0.11094873 -0.089345217 -0.074336469, 0.1111441 -0.088871539 -0.074372515, 0.11252598 -0.086644053 -0.07443133, 0.11246758 -0.088946581 -0.073982358, 0.11146085 -0.089219362 -0.074239567, 0.11141272 -0.092307419 -0.073055759, 0.11161542 -0.091898233 -0.073156059, 0.11200994 -0.091073602 -0.073347509, 0.10750923 -0.09316498 -0.074383497, 0.10639266 -0.094445109 -0.074382484, 0.10774439 -0.093960911 -0.074171439, 0.10726319 -0.095028639 -0.074024156, 0.10810591 -0.095474541 -0.073454797, 0.10797815 -0.093423784 -0.074235201, 0.10932698 -0.093490183 -0.073722228, 0.1099354 -0.094428748 -0.072801962, 0.10879952 -0.095740676 -0.072798073, 0.10991524 -0.091262996 -0.074206784, 0.11325207 -0.087051243 -0.074214593, 0.11370202 -0.088937342 -0.073355004, 0.11385643 -0.08844772 -0.073496789, 0.11414437 -0.08745718 -0.073754862, 0.11506332 -0.087753087 -0.073032334, 0.1140781 -0.089089513 -0.072995111, 0.11440829 -0.088645399 -0.073007539, 0.10855153 -0.092415631 -0.0743054, 0.10883392 -0.091909558 -0.074336603, 0.10919559 -0.091696054 -0.074297383, -0.012669876 0.14413476 -0.073042393, -0.012101531 0.14426535 -0.072959751, -0.013112292 0.14377266 -0.073334314, -0.012322307 0.14312837 -0.073829122, -0.013983697 0.14297551 -0.073829174, -0.014847502 0.14209774 -0.074193701, -0.014020041 0.14190558 -0.074284174, -0.014435396 0.14172417 -0.074323513, -0.015673384 0.14280018 -0.073829152, -0.015273094 0.14163622 -0.07432346, -0.015746072 0.1414395 -0.074359484, -0.018298462 0.14084142 -0.074418522, -0.016628891 0.14242828 -0.073969297, -0.015724227 0.14190945 -0.074226551, -0.013506651 0.14405861 -0.073042467, -0.013939261 0.14391285 -0.073142789, -0.014801338 0.14360872 -0.073334403, -0.010140121 0.14190507 -0.074370198, -0.0084452182 0.1420207 -0.074369192, -0.0097433478 0.142634 -0.07415811, -0.0086481124 0.14304891 -0.074010938, -0.0089287907 0.14395997 -0.073441282, -0.010288596 0.14241958 -0.074221946, -0.011195391 0.1434204 -0.073708862, -0.010962009 0.14451408 -0.072788484, -0.0092311054 0.14463863 -0.072784565, -0.013186276 0.14226145 -0.074193805, -0.018523768 0.14164284 -0.074201591, -0.017508313 0.14329454 -0.073341928, -0.017963767 0.14305755 -0.073483594, -0.018867776 0.14256066 -0.073742047, -0.019308418 0.14341977 -0.073019288, -0.017666623 0.14366826 -0.072981983, -0.018214285 0.14358753 -0.072994582, -0.011406898 0.1421122 -0.074292168, -0.011964336 0.14195403 -0.074323438, -0.012371033 0.14205894 -0.074284121, 0.0035472214 0.14464697 -0.073042393, 0.0041266233 0.14471322 -0.072959743, 0.0037799925 0.14360797 -0.073829144, 0.0030671209 0.14433694 -0.073334374, 0.0021119565 0.14364225 -0.073829137, 0.0011552572 0.1428667 -0.074193709, 0.0019560307 0.14258328 -0.074284166, 0.001523003 0.1424492 -0.074323468, 0.0004132539 0.14365718 -0.073829174, 0.00068071485 0.14245579 -0.074323528, 0.000188604 0.14231315 -0.074359499, -0.0024145544 0.1420047 -0.074418396, -0.00057789683 0.14339459 -0.073969178, 0.0002630353 0.14277774 -0.074226461, 0.0027071983 0.14466527 -0.073042475, 0.0022609681 0.14456874 -0.073142737, 0.001370281 0.14436296 -0.07333418, 0.0058116168 0.14214811 -0.074370205, 0.00750871 0.1420733 -0.0743692, 0.0062873363 0.14282823 -0.074158028, 0.0074221939 0.1431179 -0.074010693, 0.0072452426 0.14405459 -0.073441319, 0.0057215691 0.14267614 -0.074221984, 0.0049325675 0.14377213 -0.073708832, 0.0052869916 0.14483282 -0.072788469, 0.0070208907 0.14476261 -0.072784521, 0.002824381 0.14284348 -0.074193664, -0.0025487691 0.14282617 -0.074201591, -0.0013548285 0.14435402 -0.073341846, -0.001833871 0.14416933 -0.073483638, -0.0027877688 0.14377683 -0.073741876, -0.0031294823 0.14467981 -0.073019244, -0.0014703125 0.14474303 -0.07298205, -0.002023533 0.14472404 -0.072994336, 0.0045758933 0.14249578 -0.074292153, 0.00400424 0.14240113 -0.074323483, 0.0036117733 0.14255074 -0.074284159, -0.044424355 0.13770175 -0.073042862, -0.043899275 0.13795555 -0.072960004, -0.043861553 0.13679793 -0.07382942, -0.044775106 0.13725033 -0.073334716, -0.04544732 0.13627926 -0.073829405, -0.046093985 0.1352312 -0.074194081, -0.047055602 0.13573238 -0.073829561, -0.045244582 0.13522807 -0.074284777, -0.045609079 0.13495874 -0.074323848, -0.046406262 0.13468665 -0.074324004, -0.046823584 0.13438952 -0.074360155, -0.049178794 0.13323861 -0.074418858, -0.047904432 0.13515717 -0.073969677, -0.046906769 0.13485247 -0.074226931, -0.045223258 0.13744146 -0.073042743, -0.045612566 0.13720295 -0.073143169, -0.04638537 0.13671467 -0.073334664, -0.041461766 0.13609096 -0.074370459, -0.039835133 0.1365808 -0.074369483, -0.041237302 0.13688996 -0.074158445, -0.040261842 0.13753822 -0.074011065, -0.040738262 0.1383639 -0.073441625, -0.041721024 0.13655955 -0.074222267, -0.042827785 0.13733333 -0.073709138, -0.042843692 0.13845178 -0.072788924, -0.041183941 0.13895804 -0.072784826, -0.044510864 0.13576061 -0.074194059, -0.049576983 0.13396972 -0.074202158, -0.048954546 0.13580593 -0.073342457, -0.049345747 0.13547358 -0.073484063, -0.050116532 0.1347881 -0.073742397, -0.050737254 0.13552743 -0.073019698, -0.049191929 0.13613501 -0.072982423, -0.049707949 0.13593456 -0.072994821, -0.042742841 0.13601097 -0.074292667, -0.043251202 0.13573265 -0.0743239, -0.043670937 0.13574433 -0.074284472, -0.0287278 0.14180994 -0.073042624, -0.028177619 0.14200336 -0.072959729, -0.02912689 0.14140067 -0.073334426, -0.028269701 0.14084867 -0.073829181, -0.029903457 0.14051086 -0.073829249, -0.030663595 0.13954201 -0.074193805, -0.029819854 0.1394437 -0.074284397, -0.031562865 0.14014748 -0.073829189, -0.030212291 0.13921678 -0.074323595, -0.031034701 0.13903564 -0.074323572, -0.031482831 0.13878712 -0.074359722, -0.033952087 0.13790715 -0.074418679, -0.03247077 0.13967103 -0.073969409, -0.031513594 0.13925645 -0.074226715, -0.029550694 0.14164063 -0.073042795, -0.029964231 0.14144716 -0.073142871, -0.030786864 0.1410484 -0.073334552, -0.025964163 0.13987747 -0.074370347, -0.024292983 0.14018223 -0.074369289, -0.025651641 0.14064646 -0.074158214, -0.024609737 0.14118135 -0.074010953, -0.024990685 0.14205503 -0.073441401, -0.026169345 0.14037222 -0.074222215, -0.02718249 0.14126506 -0.073708944, -0.027073018 0.14237821 -0.072788686, -0.025367066 0.14269546 -0.072784618, -0.029031053 0.13989073 -0.07419388, -0.034265913 0.13867831 -0.074201852, -0.033441864 0.14043337 -0.073342189, -0.033867709 0.14014682 -0.073483773, -0.0347104 0.13955185 -0.073742233, -0.035244472 0.14035612 -0.07301946, -0.033640787 0.14078686 -0.072982319, -0.034175947 0.14064544 -0.072994664, -0.027246237 0.13994145 -0.074292406, -0.027782492 0.13972193 -0.074323572, -0.028198406 0.13978058 -0.074284293, 0.019719884 0.14334038 -0.073042534, 0.020302981 0.14334124 -0.072959729, 0.01920791 0.14308599 -0.073334388, 0.019834667 0.14228198 -0.073829174, 0.018181056 0.14250261 -0.073829122, 0.017143562 0.14183915 -0.074193783, 0.016494721 0.14270765 -0.073829114, 0.017907456 0.14146772 -0.074284241, 0.017462209 0.14138311 -0.074323609, 0.016625941 0.14148396 -0.074323513, 0.016121 0.14139718 -0.074359655, 0.013499707 0.14138219 -0.074418403, 0.015480414 0.14255765 -0.073969297, 0.016247019 0.14185035 -0.074226461, 0.018887177 0.14345247 -0.073042609, 0.018432915 0.1434066 -0.073142901, 0.017524749 0.14330181 -0.073334388, 0.021690086 0.14060375 -0.074370198, 0.023368105 0.14033934 -0.074369214, 0.022239044 0.1412262 -0.074158214, 0.023399115 0.14138705 -0.074010968, 0.023328274 0.14233753 -0.073441342, 0.021659866 0.14113837 -0.074222088, 0.020998359 0.14231578 -0.073708907, 0.021469399 0.14333025 -0.072788596, 0.023184538 0.14306632 -0.072784528, 0.018799603 0.14162901 -0.074193679, 0.013458222 0.14221364 -0.074201629, 0.014815763 0.14359799 -0.073341876, 0.014319152 0.14346817 -0.073483594, 0.013327137 0.14318505 -0.073741935, 0.013088748 0.14412051 -0.073019363, 0.01474458 0.14399749 -0.072982006, 0.01419282 0.14404055 -0.072994545, 0.020501122 0.14108759 -0.074292295, 0.019922435 0.14105737 -0.074323617, 0.019549251 0.14125013 -0.074284285, 0.035644472 0.14023113 -0.073042721, 0.036224097 0.14016682 -0.0729599, 0.035640135 0.13916638 -0.073829368, 0.03510724 0.14003569 -0.073334575, 0.034021467 0.13957098 -0.073829263, 0.032916218 0.13902768 -0.07419391, 0.032368645 0.13996348 -0.073829293, 0.033633798 0.1385732 -0.074284434, 0.033181876 0.13853887 -0.07432358, 0.032362133 0.13873264 -0.074323639, 0.031850606 0.1387032 -0.074359685, 0.029244021 0.13898182 -0.074418522, 0.031343982 0.1399281 -0.073969439, 0.032026604 0.13913932 -0.074226722, 0.034829542 0.14043579 -0.073042706, 0.03437297 0.140441 -0.073143005, 0.033458903 0.14043868 -0.073334545, 0.037295908 0.1372911 -0.074370518, 0.038933769 0.13684052 -0.07436952, 0.037911057 0.13784832 -0.074158415, 0.039081797 0.13787827 -0.074011043, 0.039117828 0.13883069 -0.073441729, 0.037325665 0.13782588 -0.074222282, 0.036800295 0.13906994 -0.0737091, 0.037381887 0.14002523 -0.072788805, 0.039056689 0.13957098 -0.072784737, 0.034538358 0.1386337 -0.07419394, 0.029295981 0.13981265 -0.074201703, 0.030800015 0.14103633 -0.073342025, 0.03029193 0.14096293 -0.07348378, 0.029274479 0.14079267 -0.073742151, 0.029142395 0.14174891 -0.07301949, 0.030774042 0.14144117 -0.072982147, 0.030230433 0.14154598 -0.072994664, 0.03616856 0.13790506 -0.074292451, 0.035590187 0.13793993 -0.074323744, 0.035240829 0.13817325 -0.074284375, -0.13535446 0.051124722 -0.073047765, -0.13522558 0.051693499 -0.072964847, -0.13522035 0.050569147 -0.073339455, -0.13429695 0.05100134 -0.073834352, -0.13488021 0.049438208 -0.073834389, -0.13446397 0.048279107 -0.074198984, -0.13393191 0.048941195 -0.074289441, -0.13394849 0.048488289 -0.074328832, -0.13545527 0.047839701 -0.073834538, -0.13423294 0.047695488 -0.074328758, -0.13426065 0.047183752 -0.074364953, -0.13482946 0.044624805 -0.074423835, -0.13553464 0.046817571 -0.073974773, -0.1346747 0.047407508 -0.074231721, -0.135649 0.050338 -0.073047623, -0.1357051 0.049884826 -0.073148079, -0.13580543 0.048976272 -0.073339589, -0.13224791 0.052436799 -0.074375227, -0.13161682 0.054013968 -0.074374087, -0.13273272 0.05311054 -0.074163154, -0.13263132 0.054277301 -0.074015781, -0.13357383 0.054419577 -0.073446326, -0.13277601 0.052526325 -0.074227087, -0.13407114 0.052143306 -0.073713869, -0.13495532 0.052828282 -0.072793685, -0.1343165 0.054441541 -0.072789513, -0.13389069 0.049846888 -0.074198954, -0.13564917 0.044769436 -0.07420712, -0.13669699 0.046401024 -0.073347405, -0.13668096 0.045887858 -0.073489167, -0.13662553 0.04485786 -0.073747508, -0.13759078 0.044833511 -0.073024847, -0.13710229 0.046420515 -0.072987482, -0.13726716 0.04589197 -0.073000036, -0.13298419 0.051385224 -0.074297443, -0.13308367 0.05081442 -0.074328601, -0.13335449 0.050493449 -0.074289292, -0.12877953 0.065958172 -0.073046885, -0.12858795 0.066508949 -0.07296399, -0.12870851 0.065391034 -0.073338695, -0.12774265 0.065717041 -0.073833458, -0.12849709 0.064228952 -0.073833749, -0.12821335 0.06303063 -0.074198194, -0.12761059 0.06362927 -0.074288636, -0.1276778 0.063180864 -0.074327841, -0.12924774 0.062705219 -0.073833771, -0.12804896 0.062424868 -0.074327931, -0.12813404 0.06191957 -0.074363962, -0.12898561 0.059440404 -0.074423119, -0.12944108 0.061698169 -0.073973909, -0.12852019 0.062188208 -0.074231014, -0.12916037 0.06520918 -0.073046893, -0.12926711 0.064765334 -0.073147334, -0.12946841 0.063873649 -0.073338829, -0.12554577 0.066914082 -0.0743744, -0.12474207 0.068410575 -0.074373372, -0.12595204 0.06763792 -0.074162453, -0.12572065 0.068786055 -0.074014992, -0.1266413 0.069032937 -0.073445544, -0.12606055 0.067062289 -0.07422632, -0.1273903 0.066826671 -0.073713243, -0.12819235 0.06760627 -0.072792895, -0.12737691 0.06913802 -0.072788782, -0.12746829 0.064524531 -0.074198082, -0.12978417 0.059675932 -0.0742063, -0.13064277 0.06141448 -0.073346473, -0.13068414 0.060902834 -0.073488288, -0.13074443 0.059873044 -0.073746666, -0.13170621 0.059956998 -0.073024072, -0.1310432 0.061479241 -0.072986796, -0.13126624 0.060972512 -0.072999239, -0.12639529 0.065951705 -0.074296556, -0.12655783 0.065395594 -0.074327767, -0.12686306 0.065107048 -0.074288458, -0.12058546 0.079962343 -0.073046148, -0.12033332 0.080488145 -0.072963215, -0.12057832 0.079390854 -0.073337965, -0.11958198 0.079606593 -0.07383278, -0.12049821 0.078212291 -0.073832735, -0.12035049 0.07698974 -0.074197344, -0.12141463 0.076782078 -0.07383287, -0.11968446 0.077516973 -0.074287854, -0.11980134 0.077078938 -0.074327022, -0.12025508 0.076369315 -0.074327223, -0.12039612 0.075876623 -0.074363239, -0.12151983 0.073508471 -0.074422345, -0.12171956 0.075803131 -0.073973037, -0.12074981 0.076186895 -0.074230172, -0.12104768 0.079260677 -0.073046148, -0.12120346 0.078831524 -0.0731465, -0.12150312 0.077967882 -0.073338069, -0.11726476 0.080550104 -0.074373633, -0.11629856 0.081947327 -0.074372508, -0.11758762 0.081314802 -0.074161537, -0.11722898 0.082429647 -0.074014187, -0.11811625 0.082778305 -0.073444739, -0.11775985 0.080754846 -0.074225403, -0.11910746 0.080669641 -0.073712274, -0.11981732 0.081534177 -0.072792023, -0.1188353 0.082965016 -0.072788, -0.11944284 0.078390688 -0.0741973, -0.122287 0.073831916 -0.074205443, -0.12294542 0.07565558 -0.073345669, -0.12304404 0.075151861 -0.073487483, -0.1232191 0.074135274 -0.073745869, -0.12416549 0.074326366 -0.07302314, -0.1233362 0.075764775 -0.07298591, -0.12361445 0.075286359 -0.072998352, -0.11821663 0.079688758 -0.074295789, -0.11844048 0.079154283 -0.074327111, -0.11877611 0.078901738 -0.074287854, -0.11087475 0.092960924 -0.073045284, -0.11056513 0.093455046 -0.072962433, -0.10991727 0.092494935 -0.073831998, -0.11093159 0.092392087 -0.073337093, -0.11098403 0.091212213 -0.073832028, -0.11097418 0.089980662 -0.074196637, -0.11205488 0.089893311 -0.073832139, -0.11025314 0.090429932 -0.074287109, -0.11041837 0.090007871 -0.074326411, -0.1109487 0.089353442 -0.074326448, -0.11114398 0.088879794 -0.074362583, -0.11252601 0.08665216 -0.074421629, -0.11246748 0.088954687 -0.073972382, -0.11146072 0.089227617 -0.074229538, -0.11141253 0.092315257 -0.073045373, -0.11161544 0.091906458 -0.073145613, -0.11200994 0.091081619 -0.073337287, -0.10750916 0.093173206 -0.074372984, -0.10639262 0.094453484 -0.07437177, -0.1077443 0.093969017 -0.074161008, -0.10726302 0.095036834 -0.074013606, -0.10810575 0.095482647 -0.073443957, -0.10797817 0.093431979 -0.074224815, -0.10932682 0.09349817 -0.073711686, -0.1099354 0.094436616 -0.072791338, -0.10879943 0.095748693 -0.072787143, -0.10991522 0.091271162 -0.074196652, -0.11325195 0.087059557 -0.07420481, -0.11370197 0.088945359 -0.073344983, -0.11385634 0.088455796 -0.073486835, -0.11414438 0.087465376 -0.073745102, -0.11506328 0.087761074 -0.073022455, -0.11407816 0.089097857 -0.072985053, -0.11440824 0.088653564 -0.072997637, -0.1085515 0.092423826 -0.074294962, -0.1088338 0.091917753 -0.07432624, -0.10919554 0.091704309 -0.074287057, -0.073951192 0.12436396 -0.07304354, -0.073495798 0.1247282 -0.072960787, -0.073201381 0.12360814 -0.073830262, -0.07419271 0.12384588 -0.073335387, -0.074632019 0.12274963 -0.073830344, -0.075029194 0.12158388 -0.074194878, -0.076078005 0.12185842 -0.073830344, -0.074200347 0.12176991 -0.074285366, -0.074495874 0.12142619 -0.074324712, -0.075212337 0.12098351 -0.074324638, -0.075553201 0.12060097 -0.07436081, -0.077593356 0.11895478 -0.074419729, -0.076777644 0.12110889 -0.073970601, -0.075737275 0.12103382 -0.074227743, -0.074672088 0.12393251 -0.073043548, -0.074998565 0.12361339 -0.073143966, -0.075643383 0.12296525 -0.073335372, -0.070704401 0.12345287 -0.074371189, -0.069227606 0.12429252 -0.074370198, -0.070663415 0.12428185 -0.074159138, -0.069856614 0.12513092 -0.074011773, -0.070504636 0.12582979 -0.073442332, -0.071061432 0.12385207 -0.074223019, -0.072312601 0.12436002 -0.073709793, -0.072577089 0.12544706 -0.072789595, -0.071071528 0.12631002 -0.072785571, -0.073603414 0.12245238 -0.074194901, -0.078144051 0.11957896 -0.074202843, -0.077946112 0.12150779 -0.073343217, -0.078253478 0.1210967 -0.073485002, -0.078852326 0.12025681 -0.073743239, -0.079621918 0.12083954 -0.073020555, -0.078250639 0.1217756 -0.072983302, -0.078709073 0.12146547 -0.072995842, -0.071935579 0.12308976 -0.074293278, -0.07236927 0.1227054 -0.074324518, -0.072781295 0.12262344 -0.074285291, -0.059562266 0.13186184 -0.073043168, -0.059069023 0.13217303 -0.072960354, -0.059860311 0.13137424 -0.07333497, -0.058901764 0.13102674 -0.073829852, -0.060419485 0.13033387 -0.073829845, -0.060944915 0.12922016 -0.074194349, -0.060100369 0.12931207 -0.074284874, -0.061956406 0.12961042 -0.073829845, -0.060432404 0.12900349 -0.074324213, -0.061194092 0.12864396 -0.07432428, -0.061575606 0.12830204 -0.074360408, -0.063787296 0.12689456 -0.074419253, -0.062735446 0.12894374 -0.073970169, -0.061710119 0.12875283 -0.074227259, -0.060326897 0.13151374 -0.073043182, -0.060687125 0.13123319 -0.073143408, -0.061400376 0.13066143 -0.07333497, -0.056437805 0.13059294 -0.074370854, -0.054876544 0.13126203 -0.074369788, -0.056304291 0.13141209 -0.074158698, -0.055407584 0.13216549 -0.074011371, -0.055973455 0.1329326 -0.073441975, -0.056747973 0.1310297 -0.074222557, -0.057934508 0.13167459 -0.073709451, -0.058075517 0.13278413 -0.072789282, -0.056482859 0.13347328 -0.072785176, -0.059431016 0.12992349 -0.074194357, -0.064264618 0.12757659 -0.074202456, -0.063851729 0.12947097 -0.073342755, -0.064203203 0.12909684 -0.073484451, -0.064892612 0.1283294 -0.073742822, -0.065591969 0.12899446 -0.07302022, -0.064124539 0.12977126 -0.072982743, -0.06461475 0.12951434 -0.072995178, -0.057702161 0.13037017 -0.074292913, -0.058175996 0.13003671 -0.074324101, -0.058594532 0.13000137 -0.074284889, -0.099769674 0.10479033 -0.07304462, -0.099406928 0.10524696 -0.07296183, -0.098870374 0.10422009 -0.073831268, -0.099889979 0.10423151 -0.073336549, -0.10007419 0.10306486 -0.07383129, -0.10020211 0.10184005 -0.074196056, -0.10128583 0.10187432 -0.073831446, -0.099435464 0.10220596 -0.074286439, -0.099647008 0.10180503 -0.07432574, -0.10024717 0.10121396 -0.074325733, -0.10049414 0.10076511 -0.074361935, -0.10211691 0.098706454 -0.074420869, -0.10180107 0.10098797 -0.073971555, -0.10076999 0.10114625 -0.07422895, -0.10037648 0.10420918 -0.073044598, -0.10062376 0.10382551 -0.073144987, -0.1011082 0.10305014 -0.07333672, -0.09640155 0.10462448 -0.074372306, -0.095148735 0.10577178 -0.074371204, -0.096546099 0.10544187 -0.074160255, -0.09594842 0.10644907 -0.074012965, -0.096735924 0.10698617 -0.07344345, -0.096838489 0.10493433 -0.074224181, -0.098171353 0.10515124 -0.073711, -0.098670982 0.10615182 -0.072790675, -0.097395346 0.10732839 -0.072786659, -0.099005349 0.10300389 -0.074195825, -0.1027929 0.099192232 -0.074204147, -0.10302886 0.10111687 -0.073344342, -0.103237 0.1006476 -0.073486052, -0.10363407 0.099695563 -0.073744379, -0.10451405 0.10009235 -0.073021725, -0.10338543 0.10131025 -0.072984464, -0.1037633 0.10090575 -0.072996847, -0.097521298 0.10399657 -0.074294478, -0.097858332 0.10352546 -0.074325711, -0.098241821 0.10335386 -0.074286439, -0.087409951 0.11530209 -0.073044062, -0.086998262 0.11571524 -0.072961159, -0.087592036 0.11476025 -0.07333602, -0.086580448 0.11463508 -0.073830739, -0.08790575 0.11362162 -0.073830716, -0.088170148 0.11241889 -0.074195363, -0.087367408 0.11269665 -0.074285872, -0.089243233 0.11257422 -0.073830858, -0.0876223 0.11232179 -0.074325159, -0.08828494 0.11180171 -0.074325107, -0.08858072 0.11138335 -0.074361295, -0.090423755 0.10951915 -0.074420273, -0.089854307 0.11175099 -0.073971055, -0.088812105 0.11179292 -0.074228197, -0.088078156 0.11479262 -0.073044047, -0.08836671 0.11443889 -0.073144451, -0.088934891 0.11372271 -0.073335975, -0.084081627 0.11476019 -0.0743718, -0.082708225 0.11575988 -0.07437063, -0.084133714 0.11558861 -0.0741596, -0.083427221 0.11652267 -0.07401228, -0.084149465 0.11714458 -0.073442854, -0.084481247 0.11511707 -0.074223541, -0.085781395 0.1154817 -0.073710427, -0.086165771 0.11653206 -0.072790034, -0.08476638 0.11755821 -0.0727861, -0.086850584 0.11344141 -0.07419531, -0.091041103 0.11007783 -0.074203461, -0.091060013 0.1120165 -0.073343627, -0.091319218 0.11157364 -0.073485471, -0.091820568 0.11067203 -0.073743962, -0.092650674 0.11116484 -0.073021173, -0.091392711 0.1122486 -0.072983854, -0.091813497 0.111889 -0.072996289, -0.085264497 0.11426154 -0.0742938, -0.085652441 0.11383107 -0.074325077, -0.086052619 0.11370349 -0.074285716, -0.13769752 -0.044420332 -0.073053084, -0.13795146 -0.043895245 -0.072970204, -0.13679382 -0.043857485 -0.073839657, -0.13724637 -0.044771165 -0.073344909, -0.13627517 -0.045443207 -0.073839776, -0.13522717 -0.046089888 -0.074204363, -0.13572827 -0.04705143 -0.073839754, -0.13522395 -0.045240402 -0.074294761, -0.13495451 -0.045604974 -0.074333996, -0.13468257 -0.046402216 -0.074334085, -0.13438536 -0.046819538 -0.074370228, -0.13323455 -0.049174696 -0.074429207, -0.13515288 -0.047900319 -0.073979907, -0.13484836 -0.046902686 -0.074237168, -0.13743722 -0.045219123 -0.073053062, -0.13719881 -0.045608521 -0.073153488, -0.13671052 -0.046381325 -0.073345013, -0.13608673 -0.041457683 -0.074380562, -0.13657671 -0.039831012 -0.07437937, -0.13688597 -0.041233122 -0.074168421, -0.13753405 -0.040257722 -0.074021161, -0.13835976 -0.040734231 -0.073451743, -0.13655543 -0.041716993 -0.074232332, -0.13732937 -0.042823792 -0.073719144, -0.13844776 -0.042839706 -0.07279893, -0.13895416 -0.041179925 -0.072795004, -0.13575642 -0.044506699 -0.074204281, -0.13396561 -0.049572825 -0.074212499, -0.13580197 -0.048950642 -0.073352762, -0.13546953 -0.049341798 -0.073494405, -0.13478407 -0.050112367 -0.073752731, -0.13552341 -0.050733268 -0.073030353, -0.13613106 -0.049187988 -0.072992906, -0.13593048 -0.049703866 -0.073005378, -0.13600673 -0.042738885 -0.074302711, -0.13572866 -0.043247104 -0.074334003, -0.13574028 -0.043666959 -0.074294686, -0.1418058 -0.028723776 -0.073052198, -0.14199924 -0.028173596 -0.072969414, -0.14139667 -0.029122919 -0.073344022, -0.14084458 -0.028265595 -0.073838688, -0.14050677 -0.029899418 -0.073838778, -0.13953781 -0.030659407 -0.074203476, -0.14014339 -0.031558901 -0.073838912, -0.13943952 -0.029815584 -0.074293949, -0.13921259 -0.030208051 -0.074333161, -0.1390315 -0.031030685 -0.074333258, -0.13878286 -0.031478822 -0.074369431, -0.13790293 -0.033948183 -0.074428409, -0.13966665 -0.03246668 -0.073979221, -0.13925245 -0.031509519 -0.074236356, -0.14163646 -0.029546708 -0.07305222, -0.14144325 -0.029960275 -0.07315255, -0.14104436 -0.030782938 -0.073343992, -0.13987345 -0.025959939 -0.074379645, -0.14017811 -0.024288774 -0.074378572, -0.14064232 -0.025647491 -0.074167624, -0.14117718 -0.024605662 -0.074020244, -0.14205107 -0.024986595 -0.073450923, -0.14036807 -0.026165217 -0.074231483, -0.141261 -0.027178466 -0.073718406, -0.14237407 -0.027069092 -0.072798207, -0.14269155 -0.025363117 -0.072794095, -0.13988647 -0.029027045 -0.074203171, -0.13867423 -0.034261703 -0.074211575, -0.1404293 -0.033437848 -0.073351964, -0.14014277 -0.033863604 -0.073493585, -0.13954782 -0.034706324 -0.073751986, -0.14035216 -0.035240471 -0.073029324, -0.14078285 -0.033636779 -0.072992086, -0.14064121 -0.034171999 -0.073004611, -0.1399373 -0.027242154 -0.074301772, -0.13971773 -0.027778268 -0.074333064, -0.13977638 -0.028194219 -0.0742938, -0.12435994 -0.073947161 -0.073054746, -0.12472418 -0.073491812 -0.072971739, -0.12384193 -0.07418859 -0.073346548, -0.12360399 -0.073197275 -0.073841199, -0.12274551 -0.074627876 -0.073841378, -0.12157968 -0.075025141 -0.074205883, -0.12176584 -0.074196339 -0.07429634, -0.12142198 -0.07449159 -0.074335702, -0.12185438 -0.076074094 -0.073841386, -0.12097932 -0.075208277 -0.07433565, -0.12059685 -0.075549066 -0.0743718, -0.11895075 -0.077589184 -0.074430741, -0.12110467 -0.076773584 -0.07398165, -0.12102975 -0.075733304 -0.07423874, -0.12392844 -0.07466796 -0.073054753, -0.12360917 -0.074994475 -0.073155098, -0.12296122 -0.075639188 -0.073346697, -0.12344868 -0.070700377 -0.074382201, -0.12428822 -0.069223523 -0.074381068, -0.12427755 -0.07065931 -0.074170098, -0.1251267 -0.069852442 -0.07402274, -0.12582573 -0.070500672 -0.073453397, -0.12384787 -0.071057469 -0.074234039, -0.12435607 -0.072308689 -0.073720947, -0.12544292 -0.072572976 -0.072800569, -0.12630606 -0.071067572 -0.072796635, -0.12244819 -0.073599428 -0.074205838, -0.1195749 -0.078139931 -0.074214064, -0.12150374 -0.077942044 -0.073354252, -0.12109262 -0.078249276 -0.073496081, -0.12025275 -0.078848243 -0.073754475, -0.12083552 -0.079617977 -0.073031932, -0.12177165 -0.078246653 -0.0729945, -0.12146129 -0.078705072 -0.073006898, -0.12308573 -0.071931541 -0.074304245, -0.12270119 -0.072365165 -0.074335679, -0.12261935 -0.072777092 -0.074296363, -0.13185795 -0.059558123 -0.073053993, -0.13216895 -0.059064895 -0.072971188, -0.13102269 -0.058897763 -0.073840544, -0.1313701 -0.059856355 -0.073345877, -0.13032994 -0.060415328 -0.073840477, -0.12921587 -0.060940742 -0.074205153, -0.12930781 -0.060096353 -0.07429561, -0.12960631 -0.061952382 -0.07384076, -0.12899938 -0.060428262 -0.074334837, -0.12863982 -0.06118989 -0.074334927, -0.12829772 -0.061571419 -0.074371129, -0.12689042 -0.063783169 -0.074429847, -0.12893954 -0.062731385 -0.073980816, -0.12874857 -0.061705917 -0.074237965, -0.13150971 -0.06032294 -0.073053949, -0.13122922 -0.060683101 -0.073154345, -0.1306574 -0.06139645 -0.073345855, -0.1305888 -0.056433827 -0.074381433, -0.13125782 -0.054872394 -0.074380301, -0.13140804 -0.056300253 -0.074169278, -0.13216135 -0.055403501 -0.074021854, -0.13292859 -0.055969387 -0.073452599, -0.13102561 -0.056744009 -0.074233219, -0.13167053 -0.05793044 -0.073720157, -0.13278021 -0.058071434 -0.072799951, -0.13346934 -0.056478888 -0.072795883, -0.12991926 -0.059426755 -0.074205108, -0.12757239 -0.064260602 -0.074213155, -0.12946689 -0.06384784 -0.073353603, -0.12909278 -0.06419915 -0.073495299, -0.12832515 -0.064888448 -0.073753692, -0.12899041 -0.065588117 -0.073031157, -0.12976727 -0.064120591 -0.072993718, -0.12951028 -0.06461063 -0.073006302, -0.13036607 -0.057697952 -0.074303411, -0.1300326 -0.058171898 -0.074334823, -0.12999716 -0.058590472 -0.074295536, -0.14022715 0.035648584 -0.073048696, -0.14016277 0.03622818 -0.072965689, -0.13916236 0.035644084 -0.073835246, -0.14003164 0.035111278 -0.073340446, -0.13956687 0.03402558 -0.073835224, -0.13902363 0.032920361 -0.074199766, -0.13856904 0.033637941 -0.074290283, -0.13995939 0.032372713 -0.073835343, -0.13853467 0.033185959 -0.074329652, -0.1387284 0.032366246 -0.074329704, -0.13869902 0.03185463 -0.074365772, -0.13897762 0.029248327 -0.074424878, -0.13992393 0.031348109 -0.073975481, -0.13913529 0.032030523 -0.074232645, -0.1404317 0.03483364 -0.073048659, -0.14043686 0.034377038 -0.073148981, -0.14043461 0.033462822 -0.073340476, -0.1372869 0.03730008 -0.074376106, -0.13683641 0.038937896 -0.074374862, -0.13784418 0.03791517 -0.074163981, -0.13787401 0.039085984 -0.074016631, -0.13882658 0.039121836 -0.073447227, -0.13782173 0.037329674 -0.074228026, -0.13906582 0.036804259 -0.07371486, -0.14002123 0.037385851 -0.072794512, -0.13956694 0.039060563 -0.072790481, -0.13862947 0.034542471 -0.074199788, -0.13980839 0.029300153 -0.074208014, -0.14103222 0.030803978 -0.073348284, -0.14095882 0.030295938 -0.073489964, -0.14078847 0.029278576 -0.073748335, -0.14174476 0.029146343 -0.073025651, -0.14143708 0.03077808 -0.072988346, -0.14154184 0.030234456 -0.073000878, -0.13790089 0.036172688 -0.07429821, -0.13793576 0.035594225 -0.074329466, -0.13816911 0.035244882 -0.074290231, -0.14333624 0.019723892 -0.073049493, -0.14333723 0.020307094 -0.072966598, -0.1422779 0.01983884 -0.073835894, -0.14308187 0.019212037 -0.073341295, -0.14249855 0.018185109 -0.073836081, -0.14183491 0.01714763 -0.074200816, -0.14146358 0.017911702 -0.074291132, -0.1427035 0.016498774 -0.073836252, -0.14137889 0.017466277 -0.074330546, -0.14147966 0.016630083 -0.074330613, -0.14139301 0.016125113 -0.074366756, -0.14137794 0.0135037 -0.074425675, -0.14255372 0.015484571 -0.073976487, -0.14184624 0.016251057 -0.074233644, -0.14344838 0.018891186 -0.073049478, -0.14340241 0.018436849 -0.073149785, -0.14329772 0.017528743 -0.073341317, -0.14059947 0.021694332 -0.074376978, -0.1403352 0.023372203 -0.074375823, -0.14122197 0.022243053 -0.074164815, -0.14138298 0.023403406 -0.074017502, -0.14233354 0.023332268 -0.073448144, -0.14113428 0.021663994 -0.074228711, -0.14231166 0.021002412 -0.073715828, -0.14332613 0.021473378 -0.072795525, -0.14306235 0.023188442 -0.072791316, -0.14162494 0.018803805 -0.074200578, -0.14220962 0.013462216 -0.074208833, -0.14359406 0.014819741 -0.073349096, -0.14346413 0.014323175 -0.073490836, -0.14318106 0.013331294 -0.073749326, -0.14411645 0.013092726 -0.07302662, -0.14399341 0.014748514 -0.072989307, -0.14403668 0.014196664 -0.073001839, -0.14108334 0.02050516 -0.074299067, -0.14105317 0.019926548 -0.074330315, -0.14124596 0.019553483 -0.074291021, -0.14413068 -0.012665808 -0.073051184, -0.14426124 -0.012097508 -0.072968483, -0.14376867 -0.013108194 -0.073343188, -0.14312427 -0.012318224 -0.073837884, -0.14297137 -0.013979763 -0.073837973, -0.14209348 -0.014843464 -0.074202485, -0.14279601 -0.015669495 -0.073838025, -0.14190143 -0.014015973 -0.074292868, -0.14171988 -0.014431387 -0.074332386, -0.14163208 -0.015268862 -0.074332453, -0.14143522 -0.015742064 -0.074368589, -0.14083725 -0.018294305 -0.074427485, -0.14242421 -0.016624808 -0.07397835, -0.14190516 -0.01572001 -0.074235372, -0.14405456 -0.013502598 -0.073051304, -0.14390856 -0.013935357 -0.073151655, -0.14360464 -0.01479733 -0.073343277, -0.14190093 -0.010135859 -0.074378736, -0.14201656 -0.0084409714 -0.074377716, -0.14262997 -0.0097393692 -0.07416679, -0.14304492 -0.0086441338 -0.074019387, -0.14395586 -0.0089247525 -0.073449947, -0.14241552 -0.010284334 -0.074230619, -0.14341626 -0.011191338 -0.073717572, -0.14451018 -0.010957986 -0.072797239, -0.14463452 -0.009227246 -0.072793059, -0.14225733 -0.013182163 -0.0742025, -0.14163871 -0.018519759 -0.074210763, -0.14329058 -0.017504334 -0.073350973, -0.14305356 -0.017959654 -0.073492713, -0.14255679 -0.018863648 -0.073751159, -0.14341575 -0.019304365 -0.073028445, -0.14366423 -0.017662644 -0.072991103, -0.14358354 -0.018210202 -0.073003612, -0.14210816 -0.011402696 -0.074300833, -0.14194986 -0.011960268 -0.074331999, -0.1420548 -0.01236704 -0.074292921, -0.14464279 0.0035513341 -0.073050514, -0.14470908 0.0041306317 -0.072967485, -0.14360379 0.0037839413 -0.073836975, -0.14433272 0.0030711591 -0.073342256, -0.14363819 0.0021159947 -0.073837079, -0.14286235 0.0011593699 -0.074201614, -0.14257897 0.0019601285 -0.074292012, -0.14365296 0.00041720271 -0.073837131, -0.14244512 0.0015271604 -0.07433144, -0.14245158 0.00068482757 -0.074331492, -0.14230892 0.00019279122 -0.074367642, -0.14200056 -0.0024104118 -0.074426591, -0.14339043 -0.00057390332 -0.073977277, -0.14277345 0.00026723742 -0.074234471, -0.14466104 0.0027113557 -0.07305038, -0.14456445 0.0022649765 -0.073150828, -0.14435887 0.0013743639 -0.073342301, -0.14214395 0.0058157146 -0.074377812, -0.14206919 0.0075128973 -0.074376777, -0.1428242 0.0062914193 -0.074165925, -0.14311375 0.0074262619 -0.074018516, -0.14405052 0.0072493255 -0.073449098, -0.14267202 0.0057257414 -0.074229755, -0.14376788 0.0049366355 -0.073716559, -0.14482886 0.0052910745 -0.072796479, -0.14475873 0.0070248544 -0.072792269, -0.14283925 0.0028286278 -0.074201509, -0.14282224 -0.0025447905 -0.07420972, -0.1443499 -0.0013508797 -0.073350042, -0.14416538 -0.0018298924 -0.073491715, -0.1437729 -0.0027837753 -0.073750302, -0.14467576 -0.003125459 -0.073027566, -0.14473885 -0.0014663935 -0.072990149, -0.14471999 -0.0020195544 -0.07300254, -0.14249158 0.0045799911 -0.074300006, -0.14239687 0.0040082037 -0.074331194, -0.14254665 0.0036158264 -0.074291989, 0.065954208 0.12878382 -0.073043346, 0.066505 0.12859201 -0.072960541, 0.06538713 0.12871259 -0.073335245, 0.065713033 0.12774676 -0.073830023, 0.064225003 0.1285013 -0.073829979, 0.063026652 0.12821755 -0.074194476, 0.063624963 0.12761468 -0.074284986, 0.062701091 0.12925178 -0.073829889, 0.063176855 0.12768179 -0.07432428, 0.062420771 0.12805325 -0.074324369, 0.061915502 0.12813818 -0.074360475, 0.059436291 0.12898982 -0.074419066, 0.06169416 0.12944517 -0.07397005, 0.062184095 0.12852445 -0.074227333, 0.065205336 0.12916461 -0.073043302, 0.06476137 0.12927121 -0.073143572, 0.063869625 0.12947229 -0.073335156, 0.066909954 0.12554994 -0.074371234, 0.068406641 0.12474626 -0.074370205, 0.067633778 0.12595624 -0.074159116, 0.068781838 0.12572491 -0.074011743, 0.069028869 0.12664542 -0.07344231, 0.067057997 0.12606478 -0.074222893, 0.066822737 0.12739435 -0.073709875, 0.067602158 0.12819636 -0.072789401, 0.069134012 0.12738091 -0.072785601, 0.064520434 0.12747234 -0.07419458, 0.059671834 0.12978837 -0.074202389, 0.061410353 0.13064671 -0.073342636, 0.060898721 0.13068822 -0.073484391, 0.059869006 0.13074851 -0.073742673, 0.0599529 0.13171032 -0.073019981, 0.061475173 0.13104725 -0.072982818, 0.060968578 0.1312702 -0.072995186, 0.065947667 0.12639925 -0.074293122, 0.065391466 0.12656179 -0.074324325, 0.065102816 0.12686715 -0.074285001, 0.051368997 0.13289481 0.074331567, 0.052484468 0.13251841 0.074315757, 0.052121952 0.13391408 0.073815525, 0.050997332 0.13429266 0.073844835, 0.050810248 0.13307935 0.074338973, 0.049880847 0.13570121 0.073158547, 0.051157236 0.1361866 0.072032154, 0.047922269 0.13735831 0.072032303, 0.048972115 0.13580117 0.073350102, 0.049434036 0.13487598 0.07384479, 0.050565153 0.13521618 0.073349983, 0.050333917 0.13564485 0.073058203, 0.051120773 0.13535032 0.073058218, 0.051686123 0.13515753 0.07303758, 0.052814588 0.13476434 0.072996274, 0.046191141 0.13454729 0.074386641, 0.044669598 0.1350669 0.074385077, 0.044819295 0.13610619 0.074029431, 0.045895055 0.13694766 0.073288932, 0.044858888 0.13706288 0.073466137, 0.044801205 0.13782138 0.072805747, 0.046831459 0.13567853 0.073909581, 0.046412006 0.13688371 0.073196009, 0.044660553 0.13845307 0.072032288, 0.047835678 0.13545108 0.073844865, 0.04984279 0.13388649 0.074209303, 0.053046554 0.13240787 0.074284479, 0.054169476 0.13217777 0.074215025, 0.054362401 0.13312796 0.073755309, 0.053935081 0.13138047 0.074433178, 0.054363579 0.13493878 0.072032124, 0.053357661 0.13453722 0.073008612, 0.05444105 0.13407621 0.073033229, 0.04719156 0.13433686 0.074355826, 0.047691345 0.13422871 0.074338943, 0.048484147 0.13394433 0.074338958, 0.048275054 0.13445967 0.074209243, 0.048937157 0.13392767 0.074299708, 0.050489336 0.13335031 0.074299708, 0.071608767 -0.063798666 0.068649247, 0.070377409 -0.065154344 0.068649128, 0.073791668 -0.068315208 0.070419289, -0.071606576 -0.090081304 0.073837705, -0.079839632 -0.089623332 0.074330471, -0.074689075 -0.093958944 0.074330248, -0.076544613 -0.085924625 0.073837928, 0.067056544 -0.062080085 0.066575721, 0.064714178 -0.064518273 0.066575475, 0.067918979 -0.06771335 0.068649143, -0.07231082 -0.095801324 0.074330226, -0.064514361 -0.064718127 0.066575475, -0.068476602 -0.06051001 0.066575781, -0.071867809 -0.063506544 0.068649292, -0.067709543 -0.067923039 0.068649031, 0.078189515 -0.063233942 0.07041952, 0.075082652 -0.066893578 0.070419371, 0.078636318 -0.070059508 0.071878225, 0.081890255 -0.066226721 0.071878508, -0.06688948 -0.075086713 0.070418909, -0.07435438 -0.074588686 0.071878046, -0.070055246 -0.078640491 0.071877778, -0.07099425 -0.071217984 0.070419118, 0.068229809 -0.060788214 0.066575572, -0.068551168 -0.086237729 0.073018879, -0.073278531 -0.082258344 0.073019065, -0.069326572 -0.091847658 0.073837563, 0.10172647 -0.063704044 0.074332058, 0.097994722 -0.069307774 0.074331716, -0.069303572 -0.097998977 0.074330054, 0.074571744 -0.060308337 0.068649471, -0.063794672 -0.071612656 0.06864877, 0.085985646 -0.06081453 0.07187885, 0.085657761 -0.069273412 0.073019922, -0.065535925 -0.082444757 0.071877606, 0.089941584 -0.063612372 0.073020265, 0.097528152 -0.061075091 0.073839366, 0.093950465 -0.066447526 0.073838905, -0.066368304 -0.087928712 0.073018864, -0.066443369 -0.093954593 0.073837355, 0.071053028 -0.057462633 0.06657584, 0.082099825 -0.058066338 0.070419863, -0.060784571 -0.06823352 0.066575252, -0.065750763 -0.10041741 0.074329898, 0.093366623 -0.058469236 0.073020443, -0.062574394 -0.078719079 0.070418656, 0.1051382 -0.057900041 0.074332297, 0.078301348 -0.055379897 0.068649575, -0.063449264 -0.084061325 0.071877383, -0.06360808 -0.089945763 0.07301873, 0.089259997 -0.055897564 0.071879059, -0.063699827 -0.1017307 0.074329853, 0.10649022 -0.055373937 0.074332446, -0.063037261 -0.096273124 0.073837325, 0.10079897 -0.055510551 0.073839635, -0.05967927 -0.075076967 0.068648629, 0.074606411 -0.052766711 0.066576123, -0.060581945 -0.080262601 0.070418648, 0.085226245 -0.053371698 0.070420071, -0.060810417 -0.085989624 0.07187742, 0.10209525 -0.053088814 0.073839709, -0.061070934 -0.097532421 0.073837385, -0.060347363 -0.092165262 0.07301864, 0.096497856 -0.05314219 0.073020831, -0.056863114 -0.071534485 0.06657508, 0.10821904 -0.051913887 0.07433264, -0.057778984 -0.076549202 0.068648659, 0.081283107 -0.050902396 0.068649963, 0.097738817 -0.050823539 0.07302089, -0.05806233 -0.082103848 0.070418537, -0.058897108 -0.10458469 0.074329659, 0.092253558 -0.050804824 0.071879372, -0.058465019 -0.093370825 0.073018529, 0.10375272 -0.049771518 0.073839933, -0.057693087 -0.088111609 0.071877211, 0.10995065 -0.048137486 0.074332803, -0.055052437 -0.072937191 0.066574998, 0.077447519 -0.048500419 0.066576332, -0.055375859 -0.078305155 0.068648413, 0.093439832 -0.048588216 0.071879476, 0.088084504 -0.048509091 0.070420325, -0.056466334 -0.10026866 0.073837109, -0.055893481 -0.089263976 0.071877249, 0.099325575 -0.047647893 0.073021129, -0.055085883 -0.08412984 0.070418403, 0.11095933 -0.045764267 0.074333012, -0.052762829 -0.074610144 0.066574894, 0.10541289 -0.046151012 0.073840246, -0.054056928 -0.0959903 0.073018372, 0.089217246 -0.046392679 0.070420578, -0.053367563 -0.08523044 0.070418276, 0.084009036 -0.046264708 0.06865032, -0.052537173 -0.080237478 0.068648271, 0.09495683 -0.045552224 0.07187967, 0.10637997 -0.043875754 0.07384032, -0.051679276 -0.091768235 0.0718771, -0.050898395 -0.081286937 0.068648309, 0.10091488 -0.044181883 0.073021367, -0.050058194 -0.076451331 0.066574723, 0.085089415 -0.044246376 0.068650305, 0.080044881 -0.044081688 0.06657654, -0.049344033 -0.087621331 0.070418075, 0.090665668 -0.043493778 0.070420682, -0.048496701 -0.077451259 0.066574723, 0.11292015 -0.04068619 0.07433331, 0.10184076 -0.042003751 0.073021501, -0.045760028 -0.11096358 0.074329212, -0.051909603 -0.10822314 0.074329555, 0.096476272 -0.042238712 0.071879849, -0.047060825 -0.08356753 0.068648197, 0.081074268 -0.042158544 0.066576779, 0.086470768 -0.041481525 0.068650588, -0.043871514 -0.10638413 0.073836863, -0.049767226 -0.10375684 0.073836893, 0.1082598 -0.039007187 0.073840573, -0.044840217 -0.079624146 0.066574566, 0.097361416 -0.040156394 0.071880072, 0.092116386 -0.040329933 0.070420921, -0.0419994 -0.10184488 0.073018044, -0.047643676 -0.09932974 0.073018119, 0.082390502 -0.039524317 0.066576913, 0.10364024 -0.037342787 0.073021814, -0.039466523 -0.11335474 0.074329168, 0.092961565 -0.03834179 0.070420906, -0.040152222 -0.097365469 0.071876809, -0.045548119 -0.094960898 0.071876928, 0.087854385 -0.038464159 0.068650618, -0.036885925 -0.11422062 0.074329175, -0.037837647 -0.10867664 0.073836595, 0.099081844 -0.03570053 0.071880266, 0.088660404 -0.036567807 0.068650782, 0.083708838 -0.036649197 0.066577032, -0.03833764 -0.092965662 0.07041797, -0.043489814 -0.090669602 0.070418067, 0.094604194 -0.034087211 0.070421144, 0.084476799 -0.034842461 0.066577017, -0.035363615 -0.10950667 0.073836505, 0.090227082 -0.032510221 0.06865117, -0.036223091 -0.10403955 0.073017888, 0.085969508 -0.030976176 0.06657739, -0.033048794 -0.11538938 0.074329004, -0.036563851 -0.088664204 0.068647765, -0.041477486 -0.086474806 0.068647981, -0.11751581 -0.0025708973 0.074130088, -0.11506356 0.0013287365 0.073842809, -0.12001676 0.0013861656 0.074335709, -0.033854678 -0.10483417 0.073017888, -0.11258256 -0.0024631619 0.073473603, -0.1148956 -0.0063596666 0.073842391, -0.034629963 -0.099463642 0.071876585, -0.031684831 -0.11062735 0.07383652, -0.01701548 -0.11631009 0.074123457, -0.020452827 -0.1132434 0.073836356, -0.021333262 -0.11811796 0.074328795, -0.029174767 -0.11642921 0.074329019, -0.016301118 -0.11142752 0.073467553, -0.012843624 -0.11435652 0.073836289, -0.034838475 -0.084480554 0.066574298, -0.039520368 -0.082394302 0.066574514, 0.022077262 -0.11545631 0.074123651, 0.018591315 -0.11858037 0.074328944, 0.026469819 -0.11707377 0.074328989, 0.017823979 -0.11368656 0.073836245, 0.025377408 -0.11224234 0.073836558, -0.032365561 -0.10022327 0.071876578, 0.021150455 -0.1106095 0.07346756, -0.033065058 -0.094968766 0.070417799, 0.093732528 -0.070932329 0.074126095, 0.089475676 -0.072360963 0.07383877, 0.093327388 -0.075475752 0.074331373, -0.030332863 -0.10590696 0.073017798, 0.11185555 -0.036127716 0.074128121, -0.026527092 -0.11706087 0.074328937, -0.027970716 -0.1116243 0.073836401, 0.10715987 -0.034611285 0.073471844, -0.030902982 -0.095694244 0.070417702, -0.12117176 -0.0048222244 0.074407235, -0.11984155 -0.0066332221 0.074335024, -0.1089415 -0.00056257844 0.072768345, -0.10530873 0.0012158155 0.07188224, -0.11015378 0.0012719631 0.073023781, -0.031535208 -0.09057495 0.068647847, -0.10886206 -0.0042025745 0.072768196, -0.028998651 -0.10124886 0.071876481, -0.10999297 -0.0060884655 0.073023528, -0.10515517 -0.0058207214 0.071881853, -0.025432207 -0.11223 0.073836394, -0.057254978 -0.10690436 0.074401468, -0.054287493 -0.10426092 0.074124284, -0.054234296 -0.10846815 0.074401304, -0.026777245 -0.10686135 0.073017627, -0.054226302 -0.10009813 0.073662937, -0.029473141 -0.091266781 0.068647809, -0.050912112 -0.10182393 0.073662713, -0.030047148 -0.086301029 0.066574305, -0.018842459 -0.11979878 0.074400775, -0.027688242 -0.096673429 0.070417613, -0.015475214 -0.12028021 0.074400783, -0.013396516 -0.119279 0.074328795, -0.017569467 -0.10752106 0.07276234, -0.019580163 -0.10841119 0.073017664, -0.018718891 -0.10364309 0.071876377, -0.024347126 -0.10744119 0.073017776, -0.013966933 -0.10804805 0.072762333, -0.012295626 -0.10947695 0.073017642, -0.011754632 -0.10466197 0.071876384, 0.018670827 -0.10733536 0.07276243, 0.017063469 -0.1088357 0.073017627, -0.02559945 -0.10216129 0.071876526, 0.016313031 -0.10404906 0.071876392, 0.022246875 -0.10665148 0.072762474, -0.028082475 -0.086960196 0.066574149, 0.024294548 -0.10745308 0.073017634, 0.023225978 -0.10272691 0.071876436, 0.095821403 -0.074328184 0.074403256, -0.026407115 -0.092200845 0.068647623, 0.097868122 -0.071611524 0.074403524, 0.089659356 -0.070150465 0.073664516, -0.023276292 -0.10271555 0.071876362, 0.09187305 -0.067224979 0.073664606, -0.024442531 -0.09754476 0.070417613, 0.11496888 -0.038578242 0.074405357, 0.11600547 -0.035338551 0.074405506, -0.025161177 -0.087850094 0.066574313, 0.10309699 -0.035212129 0.072766453, -0.11705677 0.026522994 0.074337125, 0.10421577 -0.03174746 0.072766736, -0.022224411 -0.0980739 0.070417635, -0.11222567 0.025428087 0.073844269, -0.10471531 0.00033405423 0.071717188, -0.023311652 -0.093031585 0.068647563, -0.1005498 0.0011608303 0.070423208, -0.10743691 0.024342954 0.073025092, -0.10611196 -0.001139164 0.072094634, -0.1047063 -0.0014157891 0.071717069, -0.11835986 0.019917846 0.074336633, -0.10328224 -0.0028354526 0.071312405, -0.021196023 -0.093536258 0.068647511, -0.10271147 0.023272216 0.0718835, -0.10460057 -0.0049137771 0.071716875, -0.022211663 -0.088641763 0.066574045, -0.10040296 -0.0055578053 0.070422776, -0.11876051 0.017370492 0.074336439, -0.052972674 -0.095897138 0.072893351, -0.0523277 -0.097868323 0.07317733, -0.11347503 0.019095659 0.073843695, -0.017873034 -0.098959446 0.070417471, -0.051391795 -0.096753418 0.072893254, -0.098069891 0.022220284 0.070424385, -0.020195901 -0.089122683 0.066574059, -0.049415633 -0.096185625 0.072581612, -0.11385928 0.016653448 0.073843628, -0.048188955 -0.098387867 0.07289312, -0.10863312 0.018280745 0.073024787, -0.017750554 -0.10320446 0.071711384, -0.017046049 -0.094380945 0.068647571, -0.015525796 -0.10215205 0.07130678, -0.006544672 -0.11985052 0.074328847, -0.11929075 0.013249993 0.074336439, -0.09353222 0.021192163 0.068654016, -0.014190808 -0.10516897 0.072088793, -0.014292203 -0.10373995 0.07171125, -0.10900096 0.015942693 0.07302472, -0.012556873 -0.10396421 0.071711406, -0.011223547 -0.099932224 0.070417419, -0.016241729 -0.089927316 0.066574052, -0.10385495 0.017476499 0.071883142, 0.017083853 -0.1033169 0.071711265, 0.015575811 -0.099346995 0.070417434, -0.0062745735 -0.11490431 0.073836342, 0.018768817 -0.10444906 0.072088853, -0.11436742 0.012702882 0.07384342, 0.018807761 -0.10301691 0.071711376, -0.11965586 0.0093993247 0.074336104, -0.0060067251 -0.1100015 0.073017709, -0.089118816 0.020192116 0.066580139, 0.01997079 -0.10137677 0.071306765, -0.10420658 0.015241206 0.071883187, 0.022239476 -0.10233101 0.071711384, 0.00018550456 -0.12002885 0.074328862, 0.022176355 -0.098084748 0.070417494, 0.09881036 -0.034672707 0.071715161, -0.099161744 0.016686618 0.070424005, 0.10061303 -0.033739269 0.072092712, -0.10948744 0.012160748 0.073024459, -0.0057426393 -0.10516328 0.071876347, -0.11984621 0.0065403283 0.074335843, 0.099375889 -0.033016801 0.071715295, 0.0026208013 -0.1200003 0.074328773, -0.11471759 0.009011209 0.073843278, 0.098496377 -0.031208426 0.071310818, 0.00017777085 -0.11507535 0.073836267, 0.10042354 -0.029677689 0.071715415, -0.099497348 0.014552444 0.070423931, -0.099574618 -0.0007918179 0.07007961, -0.094573684 0.01591444 0.068653718, -0.095897585 0.0011069775 0.068652928, -0.0054830685 -0.10041097 0.070417501, -0.099492669 -0.0041185915 0.070079446, -0.10467187 0.011625797 0.071882844, -0.095757648 -0.0053007901 0.068652458, -0.049439207 -0.09186101 0.071599059, 0.0025125965 -0.11504808 0.073836319, -0.1149001 0.006270349 0.073843174, -0.04639814 -0.093433976 0.071599051, 0.00017026067 -0.11016527 0.073017552, -0.10982266 0.0086266398 0.073024362, -0.016332738 -0.098233193 0.070074148, -0.094893828 0.01387912 0.068653509, 0.0069150478 -0.1198296 0.074328803, -0.013041332 -0.098724157 0.070074178, -0.010704286 -0.095308632 0.068647549, -0.090110913 0.015163302 0.066579975, -0.005229339 -0.095765263 0.068647578, 0.017339066 -0.098060638 0.070074297, 0.014855042 -0.094750345 0.068647586, 0.0024053901 -0.11013907 0.073017687, -0.099941492 0.011100203 0.070423767, 0.00016267598 -0.10531962 0.071876228, 0.020605981 -0.097426474 0.070074268, 0.021150328 -0.093546718 0.068647541, 0.094323561 -0.031922698 0.070078015, -0.10999722 0.0060024858 0.073024124, 0.0066296533 -0.11488438 0.073836282, 0.095337495 -0.028753191 0.070078105, -0.10499218 0.0082470477 0.071882688, 0.010629818 -0.11955732 0.074328825, -0.095426053 0.00017127395 0.068450898, -0.090416051 0.013223976 0.066579744, -0.0049825683 -0.091246426 0.066573918, -0.010199167 -0.090811491 0.066573977, -0.091372415 0.0010547042 0.066579163, -0.095317364 0.01058656 0.068653479, 0.0022996143 -0.10529482 0.071876369, -0.094050959 -0.0016212463 0.067853384, 0.00015542656 -0.10056043 0.070417486, -0.095378697 -0.0030174553 0.068450712, -0.091239095 -0.0050506592 0.066578761, -0.048266418 -0.087660462 0.070248149, 0.0063467696 -0.1099824 0.073017694, -0.10515903 0.0057384074 0.071882531, -0.045968346 -0.087310404 0.069742262, 0.010191135 -0.1146234 0.073836282, -0.10024744 0.0078742504 0.070423588, -0.045363754 -0.089197338 0.070248082, -0.090819642 0.010086894 0.06657967, 0.013622828 -0.11925334 0.074328721, -0.014733464 -0.094285965 0.068445526, 0.002195619 -0.10053647 0.070417486, -0.013184473 -0.093140185 0.067848429, 0.00014831126 -0.095907807 0.068647355, -0.10040696 0.0054790676 0.070423305, -0.01157479 -0.094725668 0.068445519, 0.0060676783 -0.10514501 0.071876377, -0.095609158 0.0075097084 0.068653293, 0.015699372 -0.09412998 0.068445481, 0.014154166 -0.09027949 0.066574067, 0.009756282 -0.10973251 0.073017664, 0.017238334 -0.092475682 0.067848384, 0.018835828 -0.093552768 0.068445705, 0.020152308 -0.089132488 0.066574067, 0.013060674 -0.11433199 0.073836416, 0.09008868 -0.03147164 0.068449125, -0.095761403 0.0052254498 0.068653122, 0.00209409 -0.095885098 0.068647482, 0.089377567 -0.029327005 0.067851946, -0.091097735 0.0071554482 0.066579431, 0.00014127791 -0.091382265 0.06657391, 0.09108983 -0.028443694 0.068449184, -0.090483971 -0.00025761127 0.066125438, 0.005793348 -0.1003935 0.070417516, -0.09042488 -0.0032810569 0.066125199, -0.091242649 0.004978776 0.066579282, -0.045434088 -0.083414257 0.068254568, 0.0093271211 -0.10490611 0.071876362, 0.012503371 -0.10945353 0.073017672, -0.042672217 -0.084860325 0.068254419, 0.0019953176 -0.091360658 0.06657397, -0.014385395 -0.089337319 0.066120453, -0.011392228 -0.089768052 0.066120416, -0.11924918 -0.013627082 0.074334815, 0.01530046 -0.089185148 0.066120461, 0.0055253282 -0.095748633 0.068647437, 0.018271878 -0.088624209 0.066120461, 0.0089056343 -0.10016543 0.070417449, 0.085560828 -0.029445052 0.066123903, 0.011953384 -0.10463938 0.071876347, 0.086496696 -0.026569545 0.066123903, -0.11432762 -0.013064831 0.073842026, -0.042748079 -0.080259681 0.066349179, 0.0052647069 -0.091230631 0.066573948, 0.0084936619 -0.095531195 0.068647482, -0.10944945 -0.012507409 0.073023133, -0.11829777 -0.020291954 0.074334502, 0.011413179 -0.099910855 0.070417434, -0.10463525 -0.011957437 0.071881548, 0.0080927312 -0.091023356 0.066573977, -0.11788885 -0.022547275 0.074334264, 0.010885142 -0.095288068 0.068647571, -0.11341549 -0.019454688 0.073841639, -0.099906795 -0.01141724 0.070422515, 0.010371506 -0.090791941 0.066573955, -0.11302328 -0.021617115 0.073841557, -0.10857598 -0.018624663 0.073022738, -0.1169741 -0.02689302 0.074334025, 0.033405416 -0.11528662 0.074328981, -0.095284209 -0.010889083 0.068652228, -0.10820058 -0.020694733 0.073022693, -0.10380054 -0.017805487 0.071881264, 0.032026656 -0.11052883 0.07383655, -0.11214647 -0.025783151 0.073841259, -0.11611969 -0.030371159 0.074333861, -0.090788022 -0.010375381 0.066578448, 0.030660123 -0.10581273 0.073017895, 0.039816789 -0.1132322 0.07432919, -0.10344157 -0.0197846 0.071881115, -0.099109747 -0.017001033 0.070422113, -0.10736109 -0.024683326 0.073022306, 0.029311493 -0.10115859 0.071876474, -0.11132738 -0.029117793 0.073841229, 0.041837558 -0.11250129 0.07432922, -0.1152824 -0.033409536 0.074333668, 0.038173497 -0.10855925 0.073836662, -0.09876702 -0.018890589 0.070421994, -0.0945241 -0.016214579 0.068652019, 0.027986944 -0.096587509 0.070417613, -0.10263901 -0.023597777 0.071881056, -0.10657702 -0.027875334 0.073022194, 0.040110804 -0.10785836 0.073836632, -0.11052469 -0.032030791 0.073840946, 0.036544599 -0.10392717 0.073018014, 0.046102837 -0.11082166 0.074329346, -0.094197229 -0.018016666 0.068651862, -0.090063758 -0.015449584 0.066578187, 0.026692033 -0.092118651 0.068647727, -0.11383215 -0.038059264 0.074333459, 0.038399257 -0.10325614 0.073017977, -0.098000675 -0.02253136 0.07042183, 0.034937166 -0.099355996 0.071876615, -0.10188936 -0.026649535 0.071880668, 0.044200137 -0.10624802 0.073836677, -0.10580849 -0.030664235 0.073022053, 0.049258001 -0.10945559 0.074329592, -0.089752205 -0.017166615 0.06657818, 0.025432549 -0.087771863 0.066574201, -0.11322799 -0.039820999 0.074333265, 0.036710434 -0.098714769 0.07187672, -0.10913421 -0.036488712 0.073840775, 0.033358358 -0.094866276 0.070417739, -0.093466431 -0.021489143 0.068651631, 0.042314149 -0.10171455 0.073018022, -0.097284943 -0.025445372 0.070421755, 0.047225058 -0.10493839 0.073836893, -0.10115473 -0.029315501 0.071880579, 0.052243896 -0.10806215 0.074329577, -0.108555 -0.038177639 0.073840566, 0.035051383 -0.094253868 0.070417829, -0.10447732 -0.034931898 0.073021807, 0.031814925 -0.09047702 0.068647586, -0.089055926 -0.020475298 0.066577911, 0.040453024 -0.097240835 0.071876816, -0.092783742 -0.024268121 0.068651408, 0.045210004 -0.10046077 0.073018163, -0.09658324 -0.027991027 0.070421487, 0.050087683 -0.10360247 0.07383699, -0.1039229 -0.036548704 0.073021814, 0.033429645 -0.089892983 0.068647824, 0.030313708 -0.086207777 0.066574275, -0.11103611 -0.045577496 0.074333027, 0.056458518 -0.10592106 0.074329644, -0.099882111 -0.033395529 0.07188043, -0.08840555 -0.023123085 0.066577889, 0.03862489 -0.092846483 0.07041797, 0.043221436 -0.096042126 0.071876816, -0.09211465 -0.026695997 0.068651274, 0.047950462 -0.09918189 0.07301823, -0.099352062 -0.034941256 0.071880303, -0.10645351 -0.043696642 0.073840335, 0.031852253 -0.085651338 0.06657429, 0.058220603 -0.10496289 0.074329704, -0.09536837 -0.031886458 0.070421301, -0.087768108 -0.025436282 0.066577651, 0.054128543 -0.1015498 0.073837005, 0.036837846 -0.088550955 0.068647906, -0.094862223 -0.033362418 0.070421278, -0.10191129 -0.041832149 0.073021494, 0.041268289 -0.091702253 0.070417911, 0.045841485 -0.094819665 0.071876973, -0.090955839 -0.030411214 0.068651229, 0.055817746 -0.10063103 0.073837072, -0.10805797 -0.05224821 0.07433264, 0.05181881 -0.097216755 0.073018275, -0.090473205 -0.031818897 0.068651028, 0.035099529 -0.08437252 0.06657429, -0.097428843 -0.039992362 0.071880087, 0.039358892 -0.087459356 0.068647951, -0.086663947 -0.028976351 0.06657736, 0.043769754 -0.090534776 0.070418082, -0.10359837 -0.050091952 0.073839858, 0.053435974 -0.096337289 0.073018275, -0.086203948 -0.030317456 0.066577345, 0.063406967 -0.10191351 0.074329846, -0.093025826 -0.038185269 0.070420906, 0.049539581 -0.092940748 0.071877137, -0.099177748 -0.047954679 0.073021077, 0.037501678 -0.083332539 0.066574425, -0.10495867 -0.058224797 0.074332282, 0.041744731 -0.08634603 0.068648003, -0.088721678 -0.036418557 0.068650812, 0.051085643 -0.092100084 0.0718771, -0.103971 -0.059970587 0.074332073, 0.060790189 -0.097707659 0.073837355, 0.04730092 -0.088740975 0.070418105, -0.094815508 -0.045845479 0.071879588, 0.039774917 -0.082271725 0.066574506, -0.10062698 -0.055821925 0.07383959, 0.048777051 -0.08793819 0.070418216, -0.08453536 -0.034700006 0.066577122, 0.05819618 -0.093538612 0.073018506, -0.099680111 -0.057495505 0.07383956, 0.045112289 -0.084635109 0.06864801, -0.090530723 -0.04377389 0.070420697, 0.069606178 -0.097784281 0.07433001, 0.046520233 -0.083869517 0.06864813, -0.096333094 -0.053440183 0.073020846, 0.05563651 -0.089424461 0.071877196, -0.10152902 -0.06401825 0.074332006, -0.095426887 -0.055042356 0.073020786, 0.042983681 -0.080641657 0.066574499, 0.066733502 -0.093748808 0.073837481, -0.086342037 -0.041748583 0.068650499, -0.092095941 -0.051089704 0.071879372, 0.044325031 -0.079912066 0.066574618, -0.097338915 -0.061376333 0.073839381, 0.053122252 -0.085383415 0.070418261, -0.099733695 -0.066781044 0.07433185, 0.063885882 -0.089748621 0.073018886, -0.091229536 -0.052621603 0.07187923, -0.08226794 -0.03977856 0.066576853, 0.074979216 -0.093727559 0.074330285, 0.05066435 -0.081432998 0.068648249, -0.087934285 -0.048781127 0.07042034, 0.076424465 -0.092552871 0.074330278, -0.09318535 -0.058757544 0.073020384, 0.061075941 -0.085801154 0.071877405, -0.095617473 -0.064025223 0.073839128, 0.071884722 -0.089859545 0.07383772, -0.09777993 -0.069610357 0.074331559, -0.087106854 -0.050243735 0.07042031, 0.048273645 -0.077590466 0.066574723, -0.083865628 -0.046524167 0.068650216, -0.08908686 -0.056173235 0.071879104, 0.073270336 -0.088733435 0.073837742, -0.09153749 -0.061293334 0.073020294, 0.058315925 -0.081923932 0.07041844, 0.068817481 -0.086025357 0.073018856, -0.09374468 -0.066737622 0.073838979, 0.080116309 -0.089376003 0.074330613, -0.083076507 -0.047919095 0.068650186, -0.079908229 -0.044328958 0.066576533, 0.070143878 -0.084947258 0.073018886, 0.05561772 -0.078133613 0.068648443, -0.095050588 -0.073293507 0.074331313, -0.08506085 -0.053634942 0.070420116, 0.065790571 -0.082241744 0.071877688, -0.08751148 -0.058597356 0.071878999, 0.076809905 -0.085687637 0.073837943, 0.082435258 -0.08724162 0.074330658, -0.089744508 -0.0638901 0.073020056, -0.079156354 -0.045657963 0.06657654, 0.067058727 -0.08121106 0.071877673, 0.052993275 -0.074446797 0.066574924, -0.093723319 -0.074983358 0.074331351, -0.091127887 -0.070268661 0.073838711, 0.062817372 -0.078525335 0.070418671, -0.08112523 -0.051153362 0.068649963, 0.073532335 -0.08203128 0.073019072, -0.083556712 -0.055949509 0.070419915, 0.079033181 -0.083641291 0.0738381, -0.085797146 -0.061080009 0.071878985, 0.085001372 -0.084743202 0.074330866, 0.064028099 -0.077541143 0.070418783, -0.089855358 -0.071888924 0.073838666, 0.059910968 -0.074892104 0.068648614, -0.087239452 -0.067270547 0.073020048, -0.07729727 -0.048739582 0.066576332, 0.07029812 -0.078423381 0.071877755, -0.079690605 -0.053360969 0.068649836, 0.07566081 -0.080072433 0.073019378, -0.081919909 -0.058319867 0.070419893, 0.08149343 -0.081246018 0.073838308, -0.08994329 -0.079478413 0.074330986, 0.061065838 -0.073953509 0.068648607, -0.086021125 -0.068821609 0.073019907, 0.057083957 -0.071358383 0.066575065, -0.08340238 -0.064311713 0.071878567, 0.088078022 -0.081540763 0.07433103, -0.075930238 -0.05084309 0.066576332, 0.067121334 -0.074879706 0.070418924, -0.078129724 -0.055621654 0.068649784, 0.072332911 -0.076550692 0.071877927, -0.086231261 -0.076198459 0.073838413, 0.078016043 -0.077779442 0.073019363, -0.082237743 -0.065794677 0.071878582, 0.058184378 -0.070464075 0.066575117, -0.079633228 -0.061405718 0.070419639, 0.08961907 -0.079843998 0.074331015, -0.074442908 -0.052997112 0.066576093, 0.084442981 -0.078175724 0.073838413, -0.082551733 -0.072947264 0.073019803, 0.064015843 -0.071415246 0.068648756, 0.069064185 -0.073091388 0.070419051, -0.078521259 -0.062821418 0.070419669, -0.075948887 -0.058564663 0.068649456, 0.074584551 -0.074358433 0.071878068, -0.084739104 -0.085005581 0.074330807, 0.08592049 -0.076548904 0.073838398, 0.080839835 -0.074840039 0.073019609, -0.078920811 -0.069738775 0.071878344, 0.060995057 -0.068045408 0.066575266, -0.074888252 -0.059914887 0.068649486, -0.072364964 -0.055801064 0.066575907, 0.065868706 -0.069709629 0.06864889, -0.081241861 -0.08149749 0.073838301, 0.071214058 -0.070998341 0.070419148, -0.075354308 -0.066587478 0.070419356, -0.071354568 -0.057087749 0.066575885, 0.082254179 -0.073282748 0.073019698, -0.07777527 -0.078020155 0.0730194, 0.07728409 -0.071548462 0.071878254, 0.062760532 -0.066420376 0.066575274, 0.055524662 0.1468882 0.047008425, 0.057261571 0.14478582 0.050670534, 0.059130028 0.14547437 0.047008231, 0.053521141 0.13842842 0.066759601, 0.053150892 0.14544293 0.052846596, 0.052270234 0.14247936 0.060008034, 0.055364549 0.14398697 0.054293439, 0.051885501 0.14821276 0.047008455, 0.052091852 0.1425446 0.060007975, 0.052923203 0.14049703 0.063406065, 0.047925338 0.14724755 0.052846745, 0.048214868 0.14944723 0.047008485, 0.04538545 0.14805028 0.052846774, 0.051181406 0.14005327 0.065425679, 0.046970472 0.14431319 0.060008168, 0.043595731 0.14703038 0.056446314, 0.041789293 0.14589775 0.060008332, 0.043138117 0.14273584 0.065425888, 0.046149641 0.14179072 0.065425754, 0.043921977 0.14064029 0.068752185, 0.051120818 0.13535845 -0.073042944, 0.05168961 0.13522959 -0.072960243, 0.050997213 0.13430095 -0.073829636, 0.050565153 0.1352244 -0.073334858, 0.049434111 0.13488418 -0.073829547, 0.048274934 0.13446817 -0.074194208, 0.048937201 0.13393605 -0.074284524, 0.047835618 0.13545933 -0.073829547, 0.048484251 0.1339525 -0.074324012, 0.047691375 0.13423696 -0.074324027, 0.047179714 0.1342648 -0.074359998, 0.044620767 0.13483357 -0.074418828, 0.046813324 0.13553888 -0.073969662, 0.047403425 0.13467875 -0.074226871, 0.050333887 0.13565311 -0.073042944, 0.049880862 0.13570935 -0.073143154, 0.048972145 0.13580936 -0.073334828, 0.052432701 0.13225207 -0.074370876, 0.054009855 0.13162088 -0.074369699, 0.053106382 0.13273677 -0.074158609, 0.054273143 0.1326355 -0.074011296, 0.054415494 0.13357791 -0.073441952, 0.052522138 0.1327801 -0.074222505, 0.052139282 0.13407534 -0.073709339, 0.052824169 0.13495934 -0.072789013, 0.054437593 0.13432053 -0.072784975, 0.049842745 0.13389489 -0.074194178, 0.044765487 0.13565344 -0.074202046, 0.046396926 0.13670099 -0.073342323, 0.045883834 0.13668498 -0.073484093, 0.044853732 0.13662961 -0.073742375, 0.044829562 0.13759464 -0.073019534, 0.046416432 0.13710621 -0.072982535, 0.045888096 0.13727123 -0.072994858, 0.051381111 0.13298839 -0.074292764, 0.050810203 0.13308775 -0.074323967, 0.050489277 0.13335869 -0.074284732, 0.075082615 -0.06688562 -0.070426844, 0.070377432 -0.065146714 -0.068656407, 0.071608737 -0.063790947 -0.068656415, 0.077284165 -0.071540326 -0.071886234, 0.07121405 -0.070990354 -0.070427112, 0.073791623 -0.068307281 -0.070427097, -0.056862988 -0.071526915 -0.066583097, 0.074584559 -0.074350387 -0.071886428, -0.060784347 -0.068226159 -0.066582851, 0.082435258 -0.087233305 -0.074340269, 0.080116361 -0.089367688 -0.074340567, 0.07680995 -0.085679322 -0.07384748, -0.081241854 -0.081489265 -0.073847272, -0.086231254 -0.076190323 -0.073846869, -0.082551822 -0.072938919 -0.07302773, 0.079033166 -0.083633125 -0.073847346, -0.077775314 -0.07801196 -0.07302808, 0.08149346 -0.081237823 -0.073847279, 0.075660802 -0.080064237 -0.07302811, -0.070055254 -0.078632295 -0.071886778, -0.074354313 -0.07458052 -0.071886458, -0.070994191 -0.071210116 -0.070427105, 0.078016035 -0.077771157 -0.073028013, 0.074571811 -0.060300529 -0.068656124, 0.068229683 -0.060780734 -0.066582412, 0.071053118 -0.057455212 -0.066582225, -0.06688945 -0.075078666 -0.070427403, 0.078636348 -0.070051432 -0.071886197, -0.059679218 -0.075069338 -0.068656944, -0.063794665 -0.071604937 -0.068656877, 0.080839835 -0.074831903 -0.07302776, -0.055052586 -0.07292968 -0.066582933, -0.084739052 -0.084997267 -0.074340232, -0.089943275 -0.079470098 -0.074339934, 0.085001439 -0.084734917 -0.074340187, 0.078189507 -0.063226014 -0.070426628, -0.073278554 -0.082250118 -0.073028281, 0.082254216 -0.073274463 -0.073027745, -0.062574416 -0.078711122 -0.070427611, 0.084443077 -0.078167468 -0.073847011, 0.074606501 -0.05275923 -0.066581964, -0.057779014 -0.076541454 -0.068657137, -0.052762918 -0.074602783 -0.066583127, 0.081890255 -0.066218585 -0.07188601, -0.07654465 -0.08591634 -0.073847532, 0.08592049 -0.076540679 -0.073846973, -0.065536037 -0.08243677 -0.071886882, 0.088078052 -0.081532478 -0.074339956, -0.06058187 -0.080254823 -0.070427686, 0.078301311 -0.055372179 -0.068655916, -0.055375874 -0.078297436 -0.068657234, 0.085657761 -0.069265306 -0.073027574, -0.079839632 -0.089614928 -0.074340545, 0.089619078 -0.079835624 -0.074339963, -0.050058164 -0.076443821 -0.066583298, 0.08209984 -0.0580585 -0.070426404, -0.068551116 -0.086229622 -0.07302849, 0.077447571 -0.048492998 -0.066581637, -0.063449278 -0.084053308 -0.071886986, 0.089475773 -0.072352797 -0.073846675, -0.058062278 -0.082095951 -0.070427567, 0.085985579 -0.060806423 -0.07188563, -0.048496619 -0.077443719 -0.066583246, -0.052537292 -0.080229729 -0.068657458, 0.0812831 -0.050894707 -0.068655655, -0.071606569 -0.090073109 -0.073847704, 0.093327351 -0.075467348 -0.074339762, -0.066368327 -0.087920427 -0.073028512, 0.089941628 -0.063604206 -0.073027238, -0.060810432 -0.085981637 -0.071887039, 0.08522626 -0.05336377 -0.070426121, -0.05089841 -0.081279188 -0.068657465, 0.080044918 -0.044074178 -0.066581398, -0.055085875 -0.084121943 -0.070427775, -0.074689135 -0.09395057 -0.074340701, 0.089259982 -0.055889487 -0.071885303, -0.06932658 -0.091839552 -0.0738478, 0.081074283 -0.042151093 -0.066581309, -0.063608103 -0.089937538 -0.073028773, 0.084009059 -0.046256959 -0.068655387, -0.044840217 -0.079616755 -0.066583499, -0.053367503 -0.085222334 -0.070427991, -0.057693079 -0.088103443 -0.07188718, 0.093366638 -0.05846107 -0.07302703, 0.085089423 -0.044238508 -0.068655208, -0.072310872 -0.095792979 -0.074340783, 0.088084519 -0.048501134 -0.070425823, -0.066443354 -0.093946338 -0.073847964, -0.047060847 -0.083559602 -0.068657443, 0.082390457 -0.039516777 -0.066581264, 0.097528182 -0.061066896 -0.073846027, -0.055893511 -0.089255989 -0.071887337, 0.093950465 -0.066439271 -0.0738464, 0.089217201 -0.046384752 -0.070425615, -0.060347393 -0.092157066 -0.073028855, 0.092253558 -0.050796807 -0.071885198, -0.069303535 -0.097990632 -0.074341066, -0.049343914 -0.087613523 -0.070428051, 0.086470775 -0.041473836 -0.068655148, -0.058465116 -0.09336251 -0.07302893, 0.083708778 -0.036641657 -0.066581145, -0.063037306 -0.096264839 -0.073848099, 0.10172648 -0.063695759 -0.074338958, 0.097994775 -0.06929937 -0.074339271, 0.093439855 -0.04858017 -0.071885064, -0.051679268 -0.091760308 -0.071887307, 0.096497923 -0.053133905 -0.073026776, -0.061070919 -0.097524136 -0.073848084, 0.090665661 -0.04348591 -0.070425496, -0.065750889 -0.10040888 -0.074341089, 0.084476739 -0.034834921 -0.066580951, -0.054056928 -0.095981956 -0.073029071, 0.087854415 -0.03845644 -0.06865494, -0.063699841 -0.10172227 -0.074341118, 0.097738817 -0.050815463 -0.073026419, 0.10079903 -0.055502355 -0.073845699, -0.034838594 -0.084472984 -0.0665837, 0.094956808 -0.045544118 -0.071884885, -0.039520361 -0.082386762 -0.066583574, 0.088660426 -0.036560237 -0.068654805, -0.056466326 -0.10026038 -0.073848225, 0.092116401 -0.040322036 -0.070425317, -0.036563843 -0.088656634 -0.068657845, -0.041477568 -0.086466908 -0.068657696, 0.10209532 -0.053080589 -0.07384558, 0.10513817 -0.057891697 -0.074338824, -0.058897115 -0.10457641 -0.074341387, 0.099325553 -0.047639638 -0.073026299, 0.085969508 -0.030968755 -0.066580772, -0.03833773 -0.092957616 -0.070428327, -0.043489724 -0.090661734 -0.07042826, -0.030047052 -0.086293727 -0.066583849, 0.092961542 -0.038333744 -0.070425227, 0.096476339 -0.042230606 -0.071884587, 0.10649018 -0.055365622 -0.074338526, -0.040152162 -0.097357392 -0.071887679, -0.045548104 -0.094952792 -0.071887553, 0.10375275 -0.049763232 -0.073845595, -0.028082423 -0.086952686 -0.066583864, 0.090227127 -0.032502472 -0.068654716, -0.031535104 -0.090567142 -0.068657875, 0.097361334 -0.040148139 -0.071884498, -0.041999444 -0.10183671 -0.073029414, -0.047643654 -0.099321514 -0.073029175, 0.10091488 -0.044173628 -0.073026106, -0.029473156 -0.091259092 -0.068657987, 0.10821906 -0.051905572 -0.074338406, 0.094604276 -0.034079432 -0.070425078, -0.033065051 -0.094960958 -0.070428431, 0.10184074 -0.041995436 -0.073026046, -0.02516108 -0.087842554 -0.066583946, -0.043871529 -0.10637587 -0.073848709, -0.049767219 -0.10374865 -0.073848352, 0.10541287 -0.046142727 -0.073845252, -0.030903041 -0.095686257 -0.070428446, 0.099081792 -0.035692364 -0.07188426, -0.034629948 -0.099455506 -0.071887784, 0.10637998 -0.043867499 -0.073845074, 0.10995069 -0.048129231 -0.074338272, -0.026407167 -0.092193007 -0.068658061, 0.10364032 -0.037334621 -0.073025733, -0.022211723 -0.088634253 -0.066583939, -0.045759998 -0.11095512 -0.074341662, -0.051909454 -0.108215 -0.074341491, 0.11095934 -0.045755923 -0.074338064, 0.10825975 -0.038998812 -0.073844895, -0.032365538 -0.1002152 -0.071887918, 0.11292007 -0.040677756 -0.07433781, -0.036223143 -0.10403126 -0.073029593, -0.027688272 -0.096665502 -0.070428558, -0.11751591 -0.0025624335 -0.074130192, -0.11258262 -0.0024548769 -0.073473789, -0.11489555 -0.0063514411 -0.073843107, -0.020195939 -0.089115262 -0.066584125, -0.11506359 0.001337111 -0.07384263, -0.12001672 0.0013943613 -0.074335434, -0.023311652 -0.093023807 -0.068658091, -0.033854723 -0.10482606 -0.073029459, -0.037837625 -0.10866839 -0.073848724, -0.01701542 -0.1163018 -0.074136436, -0.021333359 -0.11810952 -0.074342109, -0.020452864 -0.11323506 -0.07384903, -0.016301051 -0.11141938 -0.073480032, -0.012843646 -0.11434832 -0.073849156, -0.028998695 -0.10124081 -0.07188794, -0.021196105 -0.093528628 -0.068658061, 0.02207721 -0.11544794 -0.074136429, 0.025377356 -0.11223403 -0.07384894, 0.026469789 -0.11706543 -0.074341953, 0.018591322 -0.11857212 -0.074342124, 0.017824091 -0.1136784 -0.073848985, 0.021150447 -0.1106014 -0.073480025, -0.024442516 -0.097536683 -0.070428558, 0.093732603 -0.070924073 -0.074133977, -0.035363615 -0.1094985 -0.073848814, -0.039466485 -0.11334646 -0.074341856, 0.11185561 -0.036119491 -0.074132025, 0.1071599 -0.034603029 -0.073475674, -0.030332953 -0.10589865 -0.073029585, -0.10894148 -0.000554353 -0.07276839, -0.016241714 -0.089919865 -0.066584103, -0.11015372 0.0012800395 -0.07302352, -0.10530887 0.001224041 -0.071882144, -0.089118913 0.020199686 -0.066577919, -0.10886198 -0.0041944087 -0.072768681, -0.022224315 -0.098065913 -0.070428692, -0.10515511 -0.0058125854 -0.071882658, -0.10999306 -0.0060801506 -0.073023982, -0.093532279 0.021199882 -0.068651602, -0.12117168 -0.0048138201 -0.074407756, -0.11984149 -0.0066249073 -0.074335814, -0.025599405 -0.10215318 -0.071887977, -0.054226324 -0.10008988 -0.073673904, -0.098069921 0.022228301 -0.070421837, -0.036885902 -0.11421224 -0.074341893, -0.054287545 -0.10425258 -0.074135877, -0.031684771 -0.1106191 -0.073848784, -0.050912134 -0.10181555 -0.073674038, -0.090111144 0.015170932 -0.066578113, -0.057255134 -0.10689604 -0.074413478, -0.017046034 -0.094373047 -0.068658069, -0.054234423 -0.10845989 -0.074413605, -0.10271136 0.023280323 -0.071880892, -0.023276277 -0.10270748 -0.071888082, -0.017569467 -0.10751283 -0.072774448, -0.019580096 -0.10840306 -0.07302992, -0.018718891 -0.10363498 -0.071888119, -0.090416051 0.013231516 -0.066578224, -0.026777156 -0.10685316 -0.073029719, -0.013966963 -0.10803989 -0.072774515, -0.011754721 -0.10465384 -0.071888119, -0.012295686 -0.10946879 -0.073029868, -0.018842489 -0.11979046 -0.074414209, -0.094573736 0.015922159 -0.068652004, -0.033048838 -0.11538097 -0.074341945, -0.015475206 -0.12027183 -0.074414194, -0.013396479 -0.11927071 -0.074342139, -0.017872997 -0.098951519 -0.070428662, -0.10743695 0.024351299 -0.073022269, 0.018670827 -0.10732704 -0.072774328, 0.017063498 -0.10882753 -0.073029749, -0.024347074 -0.10743296 -0.073029734, 0.016312897 -0.10404074 -0.071888089, -0.094893858 0.01388678 -0.068652049, 0.022246838 -0.10664308 -0.072774425, 0.024294555 -0.10744491 -0.073029719, -0.027970731 -0.11161596 -0.073848926, 0.023226 -0.10271889 -0.071888044, -0.099161677 0.016694427 -0.070422202, 0.089659393 -0.070142299 -0.073672414, 0.091873035 -0.067216843 -0.073672086, -0.090819716 0.010094494 -0.0665785, 0.095821366 -0.07431975 -0.074411586, -0.11222547 0.025436342 -0.073841184, 0.097868145 -0.071603119 -0.074411467, -0.025432318 -0.11222166 -0.073848963, -0.099497378 0.014560491 -0.070422411, 0.1030969 -0.035203964 -0.072770327, -0.02917482 -0.11642087 -0.074341983, -0.10385507 0.017484665 -0.071881317, 0.10421582 -0.031739205 -0.072770119, 0.11496893 -0.038569927 -0.074409574, -0.095317446 0.010594279 -0.068652295, 0.11600542 -0.035330176 -0.07440947, -0.1047153 0.00034213066 -0.071717113, -0.10054976 0.0011687875 -0.070423096, -0.091097675 0.007162869 -0.066578597, -0.026527166 -0.11705258 -0.074341968, -0.11705671 0.026531249 -0.074334018, -0.10420657 0.015249342 -0.071881369, -0.10611201 -0.0011309385 -0.072094761, -0.10470637 -0.0014077127 -0.071717106, -0.10328227 -0.0028274357 -0.071312621, -0.10863299 0.018288851 -0.073022529, -0.004982613 -0.091238916 -0.066584192, -0.10460061 -0.0049058199 -0.071717411, -0.099941552 0.011108249 -0.070422493, -0.010199212 -0.090803891 -0.066584155, -0.10040297 -0.0055498183 -0.070423432, -0.052972719 -0.095888853 -0.072903939, -0.091242664 0.0049862862 -0.066578701, -0.09560933 0.0075175464 -0.068652384, -0.052327707 -0.097860038 -0.073188297, -0.05139184 -0.096745193 -0.072903939, -0.0052292719 -0.095757484 -0.06865821, -0.10900095 0.015951067 -0.073022842, -0.049415596 -0.096177489 -0.072592549, -0.010704204 -0.095301032 -0.068658166, -0.048188932 -0.098379672 -0.072904125, -0.11347502 0.019103885 -0.073841512, -0.017750658 -0.1031965 -0.071722865, -0.005483076 -0.10040301 -0.070428789, -0.011223592 -0.099924415 -0.070428766, -0.10467185 0.011633903 -0.071881481, -0.015525848 -0.102144 -0.071318254, -0.095761403 0.005233258 -0.068652444, 0.00014129281 -0.091374785 -0.0665842, -0.014292248 -0.10373205 -0.07172282, -0.10024738 0.0078821182 -0.070422679, -0.014190845 -0.10516089 -0.072100624, -0.012556873 -0.10395628 -0.071722843, -0.11385912 0.016661555 -0.073841833, 0.017083861 -0.10330889 -0.071722887, 0.015575834 -0.099338979 -0.070428684, -0.0057425722 -0.10515511 -0.071888164, -0.11835984 0.019926101 -0.074334376, 0.0019952729 -0.091353089 -0.066584148, -0.10948747 0.012168974 -0.073023014, 0.018768862 -0.10444102 -0.072100624, 0.018807769 -0.1030091 -0.071723022, 0.00014822185 -0.095900148 -0.068658143, -0.091372445 0.001062274 -0.066578954, 0.019970931 -0.10136884 -0.071318232, 0.022239476 -0.10232306 -0.071722694, 0.02217634 -0.09807685 -0.07042861, -0.100407 0.0054870546 -0.070422858, 0.098810315 -0.034664661 -0.071719021, -0.006006822 -0.10999319 -0.073029898, -0.10499221 0.0082549751 -0.071881719, -0.1187605 0.017378688 -0.074334495, 0.098142713 -0.032295913 -0.071314439, 0.0020940676 -0.09587729 -0.068658151, 0.099913649 -0.031343609 -0.071718812, -0.1143674 0.012711048 -0.073841959, 0.10133968 -0.031481206 -0.072096437, 0.00015542656 -0.10055247 -0.070428737, 0.10042354 -0.029669642 -0.071718767, -0.09589766 0.0011146963 -0.068652712, 0.0052646548 -0.091223061 -0.06658417, -0.099574521 -0.00078386068 -0.070079781, -0.10515918 0.005746603 -0.071881868, -0.0062745735 -0.11489603 -0.073849037, -0.099492751 -0.0041107535 -0.070080005, -0.10982254 0.0086347759 -0.073023126, 0.0021956116 -0.10052866 -0.070428744, -0.095757641 -0.0052930415 -0.06865304, -0.049439229 -0.091853052 -0.071609348, -0.11929079 0.013258278 -0.074334756, 0.00016277283 -0.10531184 -0.071888179, -0.046398088 -0.093426079 -0.071609497, 0.0055253804 -0.095740944 -0.068658136, -0.01633282 -0.098225325 -0.070085295, -0.10999724 0.0060108304 -0.073023483, -0.013041355 -0.098716229 -0.070085287, -0.11471761 0.0090194046 -0.073842108, 0.0080927685 -0.091015905 -0.066584118, -0.0065446496 -0.11984217 -0.074342228, 0.017338976 -0.098052651 -0.07008525, 0.014855176 -0.094742715 -0.068658173, 0.0022996366 -0.10528669 -0.071888201, 0.020605907 -0.097418487 -0.070085272, 0.021150351 -0.093538851 -0.068658143, 0.00017038733 -0.11015707 -0.073029943, -0.11490013 0.0062785447 -0.073842317, 0.09414424 -0.032439768 -0.070081577, -0.11965587 0.0094076991 -0.074334994, 0.0057934672 -0.10038549 -0.070428729, 0.095175847 -0.029275835 -0.070081294, 0.0084935799 -0.095523328 -0.068658158, -0.095426112 0.00017902255 -0.068450801, 0.010371424 -0.090784401 -0.066584148, 0.0024053901 -0.11013082 -0.073029883, -0.11984635 0.0065488517 -0.074335195, -0.094050959 -0.0016137064 -0.067853555, -0.095378704 -0.0030096173 -0.068450883, 0.00017783791 -0.11506712 -0.073849104, -0.09123911 -0.0050432086 -0.066579238, -0.048266426 -0.087652624 -0.070258044, 0.0060675591 -0.10513684 -0.071888164, -0.04596851 -0.087302357 -0.069752045, -0.045363665 -0.08918947 -0.070258029, -0.090788007 -0.01036787 -0.066579595, 0.0089056492 -0.10015756 -0.070428796, -0.01473362 -0.094278276 -0.068455979, 0.010885179 -0.095280468 -0.068658166, -0.013184406 -0.093132466 -0.06785877, 0.0025125891 -0.11503986 -0.073849119, -0.011574857 -0.09471786 -0.068456031, 0.00018558651 -0.12002066 -0.074342161, 0.015699379 -0.09412235 -0.068456091, 0.014154211 -0.090272069 -0.06658414, -0.095284283 -0.010881305 -0.068653464, 0.017238379 -0.092468113 -0.067858748, 0.0063468367 -0.10997418 -0.073029861, 0.018835895 -0.093545109 -0.068455942, 0.020152263 -0.089125067 -0.066583969, -0.099906817 -0.011409163 -0.070423663, 0.090518169 -0.030206442 -0.068452448, 0.0093271509 -0.10489798 -0.071888171, 0.011413172 -0.099902838 -0.070428781, -0.090063743 -0.015441954 -0.066579834, 0.089645952 -0.028488457 -0.06785503, 0.0026207343 -0.11999196 -0.074342214, 0.091477104 -0.027164966 -0.068452328, -0.090484008 -0.00025013089 -0.06612549, -0.090424873 -0.0032736361 -0.066125624, -0.10463522 -0.01194942 -0.071882911, 0.0066296682 -0.11487615 -0.073849067, -0.04543408 -0.083406597 -0.068263948, 0.0097562596 -0.10972428 -0.073029883, -0.042672165 -0.084852606 -0.068264104, -0.089752272 -0.017159134 -0.06657993, 0.011953376 -0.10463139 -0.071888044, -0.01438535 -0.089329869 -0.066130407, -0.094524108 -0.016206771 -0.068653785, -0.011392199 -0.089760542 -0.066130571, -0.10944927 -0.012499303 -0.073024295, 0.006915018 -0.11982128 -0.074342132, 0.01530049 -0.089177668 -0.066130415, 0.018271871 -0.08861658 -0.066130385, 0.01019115 -0.11461508 -0.073849104, -0.094197266 -0.018008947 -0.068653896, 0.085696481 -0.029040068 -0.066127092, 0.012503266 -0.1094453 -0.073029906, 0.086619079 -0.026160389 -0.066126943, -0.042748131 -0.0802522 -0.066358142, -0.099109627 -0.016993105 -0.07042402, -0.089055933 -0.020467669 -0.066580027, -0.11432768 -0.013056546 -0.07384333, 0.010629781 -0.11954904 -0.074342243, -0.098766975 -0.018882722 -0.070424177, 0.013060622 -0.11432359 -0.073849052, -0.10380036 -0.01779753 -0.071883321, -0.093466312 -0.021481365 -0.068654016, -0.088405557 -0.023115635 -0.066580355, 0.01362288 -0.11924523 -0.074342109, -0.11924922 -0.013618767 -0.074336223, -0.10344151 -0.019776523 -0.071883291, -0.10857601 -0.018616378 -0.073024713, 0.025432527 -0.087764382 -0.066583849, -0.098000735 -0.022523463 -0.070424393, -0.092783801 -0.024260402 -0.068654113, -0.087768093 -0.025428951 -0.0665804, -0.10820056 -0.020686537 -0.073024794, 0.02669204 -0.092110872 -0.068657935, -0.1134154 -0.019446492 -0.073843747, -0.10263896 -0.023589611 -0.071883544, 0.027986966 -0.096579552 -0.070428565, -0.097284943 -0.025437385 -0.070424475, 0.030313663 -0.086200237 -0.066583835, -0.092114657 -0.026688188 -0.068654276, -0.11302346 -0.02160871 -0.073844001, -0.11829776 -0.020283669 -0.074336648, 0.029311612 -0.10115069 -0.07188794, -0.086663961 -0.028968722 -0.066580556, 0.03185223 -0.085643798 -0.066583805, -0.10736111 -0.024674982 -0.073024958, 0.031814963 -0.090469271 -0.068657912, -0.10188936 -0.026641428 -0.071883693, -0.096583232 -0.027983069 -0.070424773, 0.030660108 -0.10580447 -0.073029608, -0.11788877 -0.0225389 -0.074336775, -0.086203918 -0.030310065 -0.066580713, 0.033429667 -0.089885235 -0.068657853, -0.090955943 -0.030403376 -0.06865456, 0.033358447 -0.094858408 -0.070428453, -0.11214653 -0.025775105 -0.073844075, 0.035099469 -0.084364951 -0.066583619, 0.032026671 -0.11052054 -0.073848933, -0.10657702 -0.027867287 -0.073025197, 0.035051331 -0.094245881 -0.070428409, -0.1011547 -0.029307574 -0.071883887, 0.034937248 -0.099348068 -0.071887881, -0.090473145 -0.031811178 -0.068654612, -0.09536849 -0.031878501 -0.070424892, 0.036837816 -0.088543147 -0.068657786, 0.037501685 -0.083325058 -0.066583596, -0.11697413 -0.026884824 -0.074336916, 0.033405386 -0.11527824 -0.074341968, -0.11132749 -0.029109508 -0.073844284, -0.10580845 -0.030656189 -0.073025435, 0.036710404 -0.098706663 -0.071887799, -0.094862171 -0.033354461 -0.070425071, 0.036544599 -0.10391894 -0.073029637, 0.03862489 -0.092838615 -0.07042826, -0.08453536 -0.034692526 -0.066580914, -0.099882126 -0.033387512 -0.071884163, 0.039358921 -0.087451756 -0.068657711, 0.039774932 -0.082264274 -0.066583581, -0.11611976 -0.030362844 -0.074337073, 0.038399309 -0.10324794 -0.073029444, -0.11052451 -0.032022655 -0.073844388, 0.038173504 -0.10855091 -0.073848739, -0.099351957 -0.034933239 -0.071884193, 0.040453009 -0.097232729 -0.07188762, -0.088721782 -0.036410779 -0.068654895, 0.041268334 -0.091694236 -0.07042823, -0.10447733 -0.034923673 -0.073025569, 0.041744724 -0.086338311 -0.068657666, -0.11528238 -0.03340131 -0.074337214, -0.10392292 -0.036540538 -0.073025681, 0.040110804 -0.10785013 -0.073848642, 0.039816782 -0.11322397 -0.074341781, -0.093025841 -0.038177222 -0.070425361, 0.042983666 -0.080634117 -0.066583395, -0.10913428 -0.036480367 -0.073844768, 0.042314157 -0.10170633 -0.073029362, -0.082267903 -0.039771169 -0.066581354, 0.043221571 -0.096034229 -0.071887702, -0.10855493 -0.038169354 -0.073844746, 0.043769807 -0.090526938 -0.070428245, -0.097428858 -0.039984286 -0.071884461, 0.041837543 -0.1124928 -0.074341655, -0.11383224 -0.038050801 -0.074337609, 0.044325076 -0.079904616 -0.066583373, -0.086341992 -0.041740954 -0.068655282, 0.045112297 -0.08462742 -0.068657562, -0.11322801 -0.039812565 -0.074337773, 0.044200242 -0.10623991 -0.073848531, -0.10191114 -0.041824013 -0.073026069, 0.045210056 -0.10045257 -0.073029362, -0.090530723 -0.043765903 -0.070425637, 0.045841523 -0.094811618 -0.071887635, -0.079908185 -0.044321418 -0.066581413, 0.046520226 -0.083861828 -0.06865745, -0.10645355 -0.043688357 -0.073845081, 0.047300868 -0.088733077 -0.070428185, 0.046102837 -0.11081314 -0.074341744, -0.079156362 -0.045650482 -0.066581592, -0.094815485 -0.045837492 -0.071884915, 0.047225192 -0.10493025 -0.073848531, 0.047950454 -0.099173695 -0.07302922, -0.083865695 -0.046516538 -0.068655476, 0.048777059 -0.087930292 -0.070428036, -0.11103615 -0.045569003 -0.074337907, -0.083076589 -0.047911316 -0.068655439, 0.048273697 -0.077583015 -0.066583216, 0.049539611 -0.092932791 -0.071887471, -0.099177815 -0.047946513 -0.073026285, 0.049258031 -0.10944712 -0.074341655, 0.05008778 -0.10359433 -0.073848434, -0.087934151 -0.048773289 -0.070425808, -0.07729727 -0.048732221 -0.066581644, 0.051085725 -0.092092127 -0.071887366, -0.087106921 -0.050235748 -0.070425943, 0.050664403 -0.081425369 -0.068657465, 0.051818825 -0.09720856 -0.07302925, -0.10359834 -0.050083786 -0.073845483, -0.092096016 -0.051081717 -0.071885124, 0.052243911 -0.10805386 -0.074341521, -0.081125215 -0.051145643 -0.068655662, 0.053435959 -0.096329093 -0.073029168, 0.053122252 -0.085375547 -0.070427991, -0.07593026 -0.050835669 -0.066581957, 0.054128505 -0.10154149 -0.073848441, -0.091229513 -0.052613497 -0.071885213, -0.10805807 -0.052239776 -0.074338414, 0.05299335 -0.074439287 -0.066583179, 0.055817701 -0.1006228 -0.073848411, -0.096333131 -0.053431928 -0.073026642, 0.05563651 -0.089416355 -0.071887381, -0.085060939 -0.053626925 -0.070426032, 0.05645854 -0.1059128 -0.074341364, -0.079690799 -0.053353131 -0.068655834, -0.074442945 -0.052989632 -0.06658192, 0.055617779 -0.078125954 -0.068657249, 0.058220685 -0.10495451 -0.074341387, -0.095426835 -0.05503425 -0.073026799, 0.058196232 -0.093530416 -0.0730289, -0.10062684 -0.0558137 -0.073845774, 0.058315925 -0.081916094 -0.070427649, -0.089086719 -0.056165189 -0.071885385, -0.083556697 -0.055941641 -0.070426241, 0.057083942 -0.071350753 -0.066582955, -0.078129672 -0.055613965 -0.068655841, 0.060790062 -0.097699314 -0.073848084, -0.099680126 -0.057487369 -0.073845744, 0.058184326 -0.070456535 -0.066582881, -0.10495868 -0.058216393 -0.074338771, 0.061075933 -0.085793227 -0.071887039, -0.072365135 -0.055793703 -0.066582143, -0.09318544 -0.058749229 -0.073027067, 0.05991096 -0.074884385 -0.068656966, 0.063406989 -0.1019052 -0.074341178, -0.087511346 -0.058589429 -0.071885556, -0.081919931 -0.058312029 -0.07042636, 0.061065793 -0.073945969 -0.068656981, -0.10397101 -0.059962153 -0.074338831, 0.063885823 -0.089740425 -0.07302881, -0.071354583 -0.05708015 -0.066582143, 0.062817469 -0.078517377 -0.070427552, -0.075948872 -0.058556974 -0.068656094, 0.06099499 -0.068037808 -0.066582859, -0.09733893 -0.061368048 -0.073846117, 0.064028211 -0.077533185 -0.07042747, -0.09153755 -0.061285168 -0.073027246, 0.066733479 -0.093740553 -0.073847868, -0.08579725 -0.061071992 -0.071885668, 0.065790571 -0.082233608 -0.071886875, -0.074888207 -0.059907228 -0.068656169, 0.064015836 -0.071407437 -0.068656825, -0.079633303 -0.061397672 -0.070426539, 0.062760614 -0.066412926 -0.066582769, -0.10152899 -0.064009964 -0.074339114, 0.067058682 -0.081203014 -0.07188683, -0.095617525 -0.06401673 -0.073846325, 0.069606178 -0.097775996 -0.074340999, 0.068817399 -0.086017132 -0.073028572, -0.089744508 -0.063881844 -0.073027298, -0.068476453 -0.06050247 -0.066582389, 0.067121357 -0.074871629 -0.070427366, -0.078521274 -0.062813491 -0.070426688, -0.08340238 -0.064303547 -0.071885765, 0.06586872 -0.06970197 -0.068656787, -0.09973377 -0.066772699 -0.074339211, 0.064714126 -0.064510733 -0.066582598, -0.093744621 -0.066729397 -0.073846355, 0.070143923 -0.084939003 -0.07302852, -0.071867809 -0.063498944 -0.068656474, 0.071884751 -0.08985135 -0.073847689, -0.082237653 -0.0657866 -0.071885936, 0.070298105 -0.078415364 -0.071886741, -0.087239489 -0.067262292 -0.073027477, 0.069064133 -0.073083341 -0.070427254, -0.097780086 -0.069602042 -0.07433939, 0.067919068 -0.067705572 -0.068656661, -0.075354323 -0.066579491 -0.070426948, 0.073270418 -0.08872515 -0.073847719, 0.074979223 -0.093719214 -0.074340783, -0.086021267 -0.068813324 -0.073027439, -0.091127917 -0.070260346 -0.073846489, 0.067056574 -0.062072635 -0.066582561, -0.064514406 -0.064710528 -0.066582605, 0.07353244 -0.082023263 -0.073028304, -0.0789207 -0.069730699 -0.071886227, 0.072332941 -0.076542586 -0.071886525, -0.089855239 -0.071880788 -0.073846653, -0.09505076 -0.073284984 -0.074339591, 0.076424442 -0.092544556 -0.074340694, -0.06770955 -0.067915291 -0.068656728, -0.093723334 -0.074975073 -0.074339703, 0.14817573 -0.060242087 -0.017003357, 0.14594698 -0.064168155 -0.020804927, 0.14825691 -0.058703721 -0.020635337, 0.14819227 -0.046364814 -0.039427355, -0.13771945 0.036966264 -0.06902945, 0.14345329 -0.073058456 0.0019958913, 0.14103124 -0.077660918 -4.4107437e-06, 0.1434533 -0.073058248 -0.0020041615, -0.020898744 -0.1513522 -0.047008447, -0.024799183 -0.15215352 -0.043008506, -0.024571322 -0.15079957 -0.047008455, -0.13993692 0.03614977 -0.06554085, 0.13753247 -0.081671536 0.0169954, 0.13583025 -0.085293591 0.012995198, 0.13791408 -0.081881464 0.012995437, 0.13545692 -0.085069686 0.016995281, -0.13861464 0.027837843 -0.071098939, 0.1495931 -0.045267195 -0.035824552, 0.14523302 -0.069453239 -0.0020039827, -0.087965608 -0.11698586 0.061993428, -0.090716913 -0.11486545 0.061993573, -0.089132339 -0.11851108 0.057993364, -0.14205034 0.035280734 -0.061998136, 0.1422092 -0.075015277 0.0077805668, 0.13944797 -0.080091625 0.0072268546, 0.14028603 -0.078903139 0.0036141723, -0.1438978 0.035809577 -0.057998024, -0.086273581 -0.12060815 0.057993222, -0.03471455 -0.15428457 -0.02800858, -0.038277991 -0.15252522 -0.032008626, -0.034502365 -0.15342334 -0.032008611, -0.038522258 -0.15337825 -0.028008573, -0.14571021 0.038704753 -0.052286446, -0.044107273 -0.15399331 -0.015008621, -0.049138859 -0.15267566 -0.013008557, -0.049018942 -0.15225667 -0.017008618, -0.14669311 0.040493846 -0.048662782, -0.04784482 -0.15339237 -0.0094049573, -0.14471263 0.032359153 -0.057998292, -0.14284754 0.031899571 -0.061998203, 0.14857817 -0.060408205 -0.013003394, 0.14742209 -0.064166397 -0.0077905208, 0.14660826 -0.065392226 -0.011400089, -0.081380546 -0.12931725 0.046992708, -0.084499463 -0.12730107 0.046992909, -0.085249737 -0.12845057 0.042992759, -0.082087249 -0.13049415 0.04299267, -0.0716867 -0.14096388 0.027992092, -0.076076522 -0.13815579 0.029992215, -0.073297702 -0.1409122 0.024401918, -0.14544475 0.028890043 -0.057998426, -0.14356436 0.028500885 -0.061998501, 0.14523295 -0.069453448 0.001996085, -0.14345631 0.020068198 -0.064936765, -0.14420006 0.025085956 -0.061998539, -0.14052564 0.021535784 -0.069769934, -0.14993551 0.040560573 -0.039262243, -0.021075755 -0.15271381 -0.043008551, -0.14609386 0.025404483 -0.057998531, -0.059181921 -0.14938608 0.0093861148, -0.064662389 -0.14710891 0.0092232302, -0.063410349 -0.14786354 0.0056102648, 0.14692214 -0.065804869 -0.0020037144, -0.017213792 -0.15181556 -0.047008432, -0.0851648 -0.11904052 0.06199332, -0.15128349 0.039440572 -0.035643324, -0.060408711 -0.148579 0.012991734, -0.14168562 0.011656672 -0.069773495, -0.030885532 -0.1550965 -0.028008558, -0.030705743 -0.154228 -0.032008544, -0.071258701 -0.140187 0.03199216, -0.14617668 0.018523037 -0.059998922, -0.14842111 0.021216691 -0.054288328, 0.15099031 -0.052792877 -0.017002985, 0.15003783 -0.056686044 -0.013003156, 0.14962937 -0.056535006 -0.017003134, -0.1474006 0.027067989 -0.054439403, -0.078213416 -0.13125712 0.046992723, -0.15252694 0.038279712 -0.031997852, -0.078875907 -0.13246 0.042992588, 0.14692213 -0.065805137 0.0019963384, -0.14967048 0.022896618 -0.050664373, -0.022819847 -0.15421742 -0.037272766, -0.026890352 -0.15493888 -0.032008715, -0.028930709 -0.15302885 -0.037831038, -0.15337965 0.038523644 -0.027997822, 0.14851958 -0.062115282 -0.0020035356, -0.068176024 -0.14269477 0.02799198, 0.14982273 -0.05842492 -0.007232368, -0.14249143 0.0053939819 -0.069031209, -0.15382218 0.04104346 -0.022245653, 0.0037085935 -0.14132896 -0.071108386, 0.10350897 -0.097453982 0.069768712, -0.017339855 -0.15318289 -0.043008566, -0.072596088 -0.13778991 0.037812375, -0.15135489 0.020901322 -0.046998858, -0.15215588 0.024801552 -0.042998642, -0.15080225 0.024573952 -0.046998598, 0.11634293 -0.091943473 0.057994798, 0.11267684 -0.093420595 0.061994642, 0.11411161 -0.094698638 0.057994679, -0.076936238 -0.13669303 0.033639386, 0.15140414 -0.052928597 -0.013002902, -0.15396127 0.042587668 -0.018629573, -0.15428616 0.03471595 -0.027997971, -0.15342505 0.034503996 -0.031998105, 0.1521439 -0.046571434 -0.022804007, 0.15193459 -0.045010567 -0.026410669, -0.060242824 -0.14817673 0.016991585, -0.06355311 -0.14597023 0.022237509, -0.065082476 -0.1458846 0.018622138, -0.013518713 -0.15218902 -0.047008559, -0.15271607 0.02107814 -0.042998873, 0.14851958 -0.06211552 0.0019965321, -0.15181799 0.017216414 -0.04699903, -0.027037539 -0.15581349 -0.028008699, -0.15509798 0.030886948 -0.027998246, -0.15422988 0.030707419 -0.031998217, -0.067777738 -0.14190277 0.031991981, 0.10659812 -0.092880011 0.071093321, 0.10683151 -0.097824544 0.064935476, 0.1089929 -0.093161762 0.067637414, -0.064623713 -0.14433837 0.02799198, -0.15421948 0.022821963 -0.037262842, -0.15494063 0.026892275 -0.031998448, -0.15303077 0.028932691 -0.03782095, 0.11486193 -0.090720326 0.06199497, -0.14133294 -0.0037046373 -0.071100779, 0.1185078 -0.089135736 0.057995036, -0.15318537 0.017342269 -0.042999044, -0.02154547 -0.15536726 -0.033653773, 0.15225771 -0.049018085 -0.017002761, -0.15510049 0.042023569 -0.0092267841, 0.12729847 -0.08450228 0.046995252, 0.12632778 -0.088363796 0.042995036, 0.12844798 -0.085252166 0.042995155, -0.15219171 0.013521403 -0.046999283, -0.013593562 -0.15356076 -0.043008626, 0.12520686 -0.087571293 0.046995118, -0.15581483 0.027039081 -0.027998388, -0.085257962 -0.11429989 0.069027558, -0.15536913 0.021547288 -0.033643946, -0.15356308 0.013596088 -0.042999268, 0.11698236 -0.087969184 0.061995119, 0.12060476 -0.086276889 0.057995126, -0.15565845 0.040679991 -0.0056143627, -0.064255342 -0.1435321 0.031991914, 0.15267637 -0.049138278 -0.013002664, 0.15339288 -0.047844231 -0.0093989968, 0.12931457 -0.081383258 0.046995506, 0.13049173 -0.082089841 0.042995438, -0.14828426 -0.00065374374 -0.058000058, -0.14825761 0.0028916001 -0.057999901, -0.14633884 0.0027870536 -0.06199988, -0.14636369 -0.00068643689 -0.062000029, 0.14096229 -0.071688354 0.027996019, 0.13815415 -0.076078326 0.02999571, 0.14091077 -0.07329917 0.024405777, -0.15641102 0.020243853 -0.029998884, -0.061031677 -0.14589366 0.027991839, -0.15326594 0.0083720684 -0.04499945, -0.15012813 0.011068463 -0.052841902, -0.15202537 0.0068363845 -0.048664659, -0.05776488 -0.14825732 0.022795349, 0.000657022 -0.14828104 -0.058008373, -0.0028883293 -0.14825428 -0.058008336, -0.002783604 -0.14633548 -0.062008254, 0.00068995357 -0.1463604 -0.062008277, -0.15479451 0.012230724 -0.039424144, -0.020242244 -0.15640956 -0.03000883, 0.14938557 -0.059182435 0.0093911588, 0.14710844 -0.064662993 0.0092277676, 0.14786315 -0.063410819 0.0056149811, 0.11903684 -0.085168153 0.061995253, -0.15611345 0.039305359 -0.0019978955, 0.14857814 -0.060409576 0.012996614, -0.15723117 0.022714704 -0.024246804, -0.15624478 0.028568298 -0.024406329, 0.14018518 -0.071260512 0.031996056, -0.0083696172 -0.15326339 -0.045008652, -0.011065505 -0.15012518 -0.052851044, -0.0068336278 -0.15202275 -0.04867357, -0.15760282 0.024243832 -0.020630792, -0.1482262 -0.0041986704 -0.058000304, -0.012228608 -0.15479246 -0.039433487, -0.14630596 -0.0041595995 -0.062000282, 0.13125443 -0.078216195 0.04699561, 0.13245758 -0.078878522 0.042995647, -0.052793734 -0.15099138 0.016991481, -0.05668667 -0.15003857 0.012991615, -0.05292929 -0.1514048 0.012991525, -0.05653581 -0.14963046 0.016991571, 0.15400708 -0.046518594 -0.0057894886, -0.15611365 0.039305121 0.0020022839, 0.14269313 -0.06817764 0.027996257, -0.0227134 -0.15722987 -0.024256974, -0.028566957 -0.15624344 -0.024416767, -0.15704641 0.035394788 -0.0019979998, 0.13778771 -0.072598368 0.037815988, 0.13669102 -0.076938212 0.033642814, -0.15533607 0.041488916 0.0077869855, -0.060693651 -0.14507395 0.031991772, 0.14817572 -0.060243905 0.016996548, 0.14596877 -0.063554436 0.022242233, 0.14588362 -0.065083534 0.018626526, -0.024242677 -0.15760165 -0.020640947, 0.0042019486 -0.14822283 -0.058008261, 0.0041630417 -0.14630279 -0.062008262, -0.14808336 -0.0077412724 -0.058000512, -0.14616609 -0.0076303482 -0.062000528, -0.15471649 0.042813361 0.0113969, 0.14190096 -0.067779481 0.031996205, -0.15704632 0.035394341 0.0020019338, -0.039305389 -0.1561138 0.0019911975, -0.044331402 -0.15477651 -8.6277723e-06, -0.0393053 -0.15611354 -0.0020086989, 0.14433683 -0.064625442 0.02799648, -0.15788142 0.031461865 -0.0019982383, 0.11429602 -0.085261881 0.069029287, -0.035394542 -0.15704641 -0.0020088777, 0.14353034 -0.064257026 0.031996459, -0.14072627 -0.020163566 -0.069775343, 0.14589185 -0.061033368 0.0279966, -0.15788129 0.031461596 0.0020017289, 0.14825603 -0.05776614 0.02280049, 0.0077445433 -0.1480802 -0.05800838, 0.0076338351 -0.14616263 -0.062008232, -0.15861782 0.027509421 -0.001998499, 0.15099032 -0.052794844 0.01699695, 0.1500378 -0.056687385 0.012996837, 0.15140405 -0.052929878 0.012997016, 0.14962938 -0.056536913 0.016996875, -0.15906708 0.023621976 -0.007227838, -0.15800419 0.029753804 -0.007785134, 0.15377367 -0.047053576 0.0072287917, 0.15432625 -0.045708358 0.0036160052, -0.035394646 -0.1570465 0.0019911826, 0.14507231 -0.060695678 0.031996667, -0.15389046 0.041661531 0.020805854, -0.044107266 -0.15399495 0.014991358, -0.049018979 -0.15225863 0.016991422, -0.049138889 -0.15267715 0.012991384, -0.047497295 -0.15221956 0.020621754, -0.031461813 -0.15788126 -0.0020088553, 0.1526764 -0.049139708 0.012997285, -0.15861796 0.027509302 0.0020015389, -0.15941262 0.022214711 -0.0036154985, -0.057131834 -0.14438719 0.03941492, -0.0626278 -0.14214021 0.039258905, -0.061687171 -0.14365661 0.035639375, 0.15225762 -0.049020022 0.016997263, -0.1536881 0.040102959 0.024412174, 0.1522184 -0.047498524 0.020627603, 0.020167403 -0.14072239 -0.069782116, 0.14438495 -0.057134122 0.039419845, 0.1421378 -0.062630057 0.039263442, 0.14365463 -0.061689258 0.035643891, -0.031461798 -0.1578815 0.0019912347, -0.058035173 -0.14282522 0.042991951, -0.062185764 -0.13889688 0.048655324, -0.064022541 -0.13950753 0.044992141, -0.15221044 -0.013302267 -0.047000736, -0.15385929 -0.0096780658 -0.043000586, -0.15248886 -0.0095987916 -0.04700049, 0.14282262 -0.058037728 0.042996675, 0.13889414 -0.062188447 0.048659742, 0.13950482 -0.064025164 0.04499644, 0.15207291 -0.045952708 0.024243295, -0.1596522 0.020787805 1.0952353e-06, -0.1581426 -0.00048622489 -0.027999952, -0.15810615 0.0034276545 -0.027999707, -0.15722045 0.0033796728 -0.031999722, -0.15725598 -0.00050115585 -0.032000065, 0.1225985 -0.071977794 0.069770142, -0.15994793 0.0087353587 -0.014999606, -0.15934786 0.013910472 -0.016999207, -0.1586926 0.011550814 -0.022800751, 0.13388455 -0.063749611 0.057996422, 0.13063903 -0.066005468 0.061996281, 0.13232219 -0.066932201 0.057996243, -0.027509384 -0.15861771 -0.0020089895, -0.15957734 0.0072602928 -0.018631652, -0.16019332 0.012512386 -0.0093955472, -0.15978293 0.013934076 -0.012999266, -0.023621678 -0.15906689 -0.0072380751, -0.02975335 -0.15800393 -0.0077958554, 0.14155363 -0.057514668 0.046996877, 0.13817063 -0.060322672 0.052282885, -0.15337968 0.038520664 0.028002184, -0.071973957 -0.12260237 0.069767416, -0.15921795 0.023060739 0.0057859905, -0.063746199 -0.13388783 0.057992507, -0.066001862 -0.13064265 0.061992664, -0.066928834 -0.13232553 0.057992507, -0.15826599 0.028917491 0.0056201518, 0.12698993 -0.066573054 0.067638949, 0.12592009 -0.071599573 0.064936996, 0.12906989 -0.071077675 0.059996098, -0.14176206 -0.028146118 -0.065544434, -0.14308777 -0.022530496 -0.064942114, -0.14011836 -0.026448488 -0.069033042, -0.14522514 -0.024902314 -0.060001507, -0.15357697 -0.013432711 -0.043000765, 0.13216849 -0.062886745 0.061996475, 0.13537033 -0.060530573 0.057996556, -0.057511859 -0.14155635 0.046992034, -0.060319643 -0.13817367 0.052278489, -0.15880933 0.024456084 0.0093958676, -0.15184204 -0.016997963 -0.047000974, 0.14290965 -0.054057091 0.046996936, 0.1441974 -0.054532439 0.042996958, -0.15808205 -0.0043999851 -0.028000154, -0.15719551 -0.0043817163 -0.032000296, -0.027509354 -0.15861791 0.0019910857, 0.1336236 -0.059732705 0.061996639, -0.15252694 0.038276136 0.032002226, 0.13677873 -0.057276785 0.057996839, -0.06656912 -0.12699375 0.067635521, -0.071595937 -0.12592396 0.064934015, -0.071074307 -0.12907338 0.059992857, 0.14033073 -0.054481596 0.052842081, 0.14418131 -0.050567627 0.046997264, 0.14548612 -0.050994605 0.042997211, -0.022214487 -0.1594125 -0.0036256909, 0.14904526 -0.045715362 0.03726396, 0.15038392 -0.044592589 0.033644617, 0.13500336 -0.05654484 0.061996862, -0.15428615 0.034712821 0.02800199, -0.062883109 -0.13217202 0.06199256, -0.13696414 -0.035061359 -0.071102485, 0.14536768 -0.04704839 0.046997458, -0.15320307 -0.01717931 -0.043000996, 0.14668813 -0.047426373 0.042997256, -0.15048712 0.040113211 0.037822306, -0.060527101 -0.13537368 0.057992399, -0.16056284 0.0064567626 -0.0092287958, -0.054054305 -0.14291251 0.046991907, -0.054529808 -0.14420003 0.042991929, -0.16049707 0.011082917 -0.005786214, -0.15138412 -0.020683467 -0.047001235, 0.14448659 -0.045271844 0.050661251, -0.1490763 0.041207999 0.041425634, 0.13040189 -0.057690948 0.069030881, -0.15792465 -0.0083108246 -0.028000481, -0.15703951 -0.008259505 -0.032000519, -0.15342505 0.034500539 0.032001853, 0.13221115 -0.052265972 0.069768369, 0.13275123 -0.057150066 0.065541819, 0.14348879 -0.043478549 0.054284722, -0.15509805 0.030883789 0.028001893, -0.13900143 0.025837481 -0.071099073, -0.14085025 0.026812375 -0.067643493, -0.1409649 0.026202261 -0.067643531, -0.14879404 0.027656287 -0.050840221, -0.14859095 0.028728008 -0.050840177, -0.15021862 0.027920812 -0.046998352, 0.0133048 -0.15220776 -0.047008626, 0.0096804798 -0.15385702 -0.043008603, 0.0096014068 -0.15248626 -0.047008604, -0.1502535 0.031377077 -0.044998258, -0.15156823 0.02817142 -0.042998455, -0.15169646 0.030169755 -0.041423418, -0.15273765 -0.020915836 -0.043001175, -0.15270916 0.028383166 -0.039262936, -0.14325842 0.0058740675 -0.067644678, -0.14451426 0.0098746121 -0.06494043, -0.14447182 0.0041045547 -0.065542676, -0.14624262 0.0059960783 -0.061999686, -0.14712593 0.0080375671 -0.059999496, -0.13853344 -0.036955178 -0.067647278, -0.14816143 0.0060744286 -0.057999767, -0.020787887 -0.15965247 -9.0003014e-06, -0.14868584 0.0095481575 -0.056441076, -0.14973904 0.0061389208 -0.054440401, -0.059729066 -0.13362718 0.061992571, -0.15066901 0.0053107738 -0.052288361, -0.1411735 -0.0076616704 -0.071100965, -0.14328423 -0.0052020252 -0.067645326, -0.14179379 -0.010273933 -0.06977164, -0.15685964 0.029153496 -0.020027198, -0.15656672 0.030085176 -0.020799562, -0.15786597 0.025761217 -0.016998492, -0.057273395 -0.13678199 0.057992332, -0.15685764 0.032487124 -0.014998093, -0.14316773 -0.0077700615 -0.06764549, -0.14432444 -0.012356788 -0.064938463, -0.15748945 0.029270262 -0.014998414, -0.1582953 0.025833309 -0.012998596, -0.1480726 -0.028349191 -0.052290261, -0.14882647 -0.022615582 -0.052843727, -0.14708206 -0.023776948 -0.056442872, 0.00048783422 -0.15814108 -0.028008834, -0.003377758 -0.15721878 -0.032008842, 0.0005030036 -0.15725416 -0.032008804, -0.15748373 0.031130522 -0.01139456, -0.14615016 -0.0079323351 -0.062000558, -0.0034262612 -0.15810457 -0.028008908, -0.14663276 -0.014468819 -0.060000889, -0.15793371 0.029352576 -0.010009192, -0.054478459 -0.14033365 0.052837282, -0.15422985 0.030703992 0.032001741, -0.15519381 0.0063615143 -0.039264046, -0.15591587 0.010848612 -0.035821356, -0.15520129 0.0061797798 -0.039264031, -0.0087344423 -0.15994719 -0.015009008, -0.011549689 -0.15869141 -0.022810332, -0.0072593465 -0.15957648 -0.018640891, -0.013909586 -0.15934703 -0.017008938, -0.14806753 -0.0080367327 -0.05800049, -0.012512162 -0.16019294 -0.0094052851, -0.013933256 -0.15978217 -0.013009042, -0.1494202 -0.012342155 -0.054290116, -0.15620852 0.0064028203 -0.03564512, -0.15626648 0.0047879815 -0.035645254, -0.15870374 0.021743566 -0.014998816, -0.15938601 0.017912447 -0.012998931, -0.15888995 0.021879524 -0.01299879, -0.050564967 -0.14418402 0.046991922, -0.050992057 -0.14548862 0.042991728, -0.1584581 0.021823615 -0.01699876, -0.15895227 0.017872453 -0.016999096, -0.14964426 -0.0081225634 -0.054441303, -0.14972749 -0.0064103603 -0.054441132, -0.15101232 -0.010982096 -0.05066628, -0.13980567 -0.021046311 -0.071101628, -0.15712491 0.0064403713 -0.031999514, -0.15748093 0.0086015165 -0.029999696, -0.14973459 -0.027163655 -0.048666567, -0.15111932 -0.008202821 -0.050842248, -0.023061074 -0.15921843 0.0057757646, -0.15125749 -0.0050567091 -0.050842091, -0.15581484 0.027035832 0.02800145, -0.15801072 0.0064764023 -0.027999602, -0.15814149 0.010076284 -0.026407592, -0.028917983 -0.15826628 0.0056097358, -0.15256613 -0.0082815886 -0.047000505, -0.15739289 0.023325205 0.022805024, -0.15645094 0.029477417 0.0222474, -0.15346786 -0.0028440058 -0.045000136, -0.15955843 0.014167339 -0.014999218, -0.14442027 -0.03363356 -0.058001891, -0.14518318 -0.030171186 -0.058001764, -0.14328933 -0.029846191 -0.062001705, -0.15873 0.0065055192 -0.024247728, -0.14254043 -0.033238232 -0.062001906, -0.15909833 0.0057857633 -0.022247635, 0.02814994 -0.14175856 -0.065550879, 0.022533961 -0.14308417 -0.064948991, 0.026452236 -0.14011461 -0.069039471, -0.15393676 -0.0083560646 -0.043000586, -0.15460604 -0.0043423176 -0.04142534, 0.024905764 -0.14522171 -0.06000822, -0.15793377 0.029351562 0.010012604, -0.15829514 0.025831729 0.013001479, -0.15685762 0.032485247 0.015001748, -0.15780872 0.030305684 0.0092329606, -0.15509564 -0.0084193349 -0.039265014, 0.0134352 -0.15357471 -0.043008603, -0.15543067 -0.012067288 -0.037264764, -0.15563181 -0.0058451295 -0.037822768, -0.15748946 0.029268622 0.015001636, -0.15670809 0.030987442 0.018631876, -0.15786603 0.02575928 0.017001439, -0.15610968 -0.008474648 -0.035645999, -0.15626803 -0.013565719 -0.033645943, -0.024456516 -0.15880996 0.0093855113, -0.14353305 -0.02865088 -0.062001579, 0.017000496 -0.15183949 -0.047008611, -0.15685961 0.029151201 0.020030715, -0.13595182 -0.041568279 -0.069773518, -0.15702537 -0.0085245669 -0.03200049, -0.1454162 -0.029027075 -0.058001697, -0.056541272 -0.13500679 0.061992455, -0.15791059 -0.0085729659 -0.028000429, -0.1569939 -0.015068352 -0.030000903, -0.15834311 -0.012842059 -0.024248756, -0.15108782 -0.022746235 -0.04700128, -0.15128557 -0.025942534 -0.045001432, -0.15870379 0.021741837 0.015001193, -0.15938593 0.017910898 0.013001043, -0.15895233 0.017870635 0.017000988, -0.15845826 0.021821737 0.017001171, -0.15888992 0.021878093 0.013001293, -0.16074429 0.0065871477 -0.0057866089, -0.16080779 0.005022794 -0.0056163929, -0.15862952 -0.0086120963 -0.024248585, -0.15904588 -0.011433899 -0.020632789, 0.0044015497 -0.15808058 -0.028008878, 0.0043834671 -0.15719381 -0.032008827, -0.15868415 -0.0069157481 -0.02440837, -0.16085063 0.00659132 -0.0019996911, -0.16094579 0.0035814643 -0.0019997098, -0.16076057 0.0087788403 4.7683716e-07, -0.15244521 -0.022950977 -0.043001354, -0.1461173 0.039416701 0.050846513, -0.15363458 -0.02252087 -0.03942617, -0.038278066 -0.15252873 0.031991482, -0.043426931 -0.15162081 0.029991418, -0.038522266 -0.15338153 0.027991392, -0.15494065 0.026888698 0.032001663, -0.15931092 -0.0086494088 -0.020029403, -0.15964019 -0.010013044 -0.017000668, -0.15933558 -0.0055085719 -0.020801589, -0.16085067 0.0065911114 0.0020004064, -0.16094577 0.0035811067 0.0020001903, -0.16062802 0.010221004 0.0036191568, -0.15359288 -0.023124039 -0.039265752, -0.15268484 -0.02851063 -0.039266177, -0.15442023 -0.024117857 -0.035823464, -0.13729939 -0.041303933 -0.067647412, -0.14080274 -0.039963961 -0.062002353, -0.13795543 -0.044162244 -0.064940363, -0.15955848 0.014165729 0.015000753, -0.15994795 0.0087336302 0.015000515, -0.1593478 0.013908476 0.017000686, -0.047045618 -0.14537042 0.046991855, -0.047423758 -0.14669058 0.04299178, -0.15978286 0.013932556 0.013000727, -0.16074428 0.0065864623 0.0057850145, -0.16067368 0.0058831871 0.0077851824, -0.14357477 -0.037076741 -0.058002189, -0.16036451 0.0073122382 0.011394814, -0.16038856 0.011654973 0.0072319955, -0.14171158 -0.036611438 -0.062002063, -0.15995067 -0.0086843371 -0.01500053, -0.16046235 -0.0046935081 -0.011396684, -0.16015363 -0.0032315552 -0.015000306, -0.16007473 -0.010038406 -0.013000607, -0.15270858 0.028378785 0.039268542, -0.15251011 0.029426754 0.039268415, -0.1537796 0.028172493 0.035649013, -0.15347791 0.023568511 0.039424371, -0.15215592 0.024796635 0.043001384, -0.14015931 -0.042164803 -0.06200245, -0.139736 -0.04673478 -0.060002662, -0.15695626 0.021788687 0.026411202, -0.14264718 -0.040498763 -0.058002338, -0.16040188 -0.0087090731 -0.010011356, -0.16066352 -0.0061516166 -0.0077873208, -0.16033541 -0.012365997 -0.0072297119, -0.15156817 0.028166533 0.043001562, -0.15025344 0.031372011 0.045001671, -0.034714505 -0.15428776 0.027991399, -0.1419982 -0.042718291 -0.058002442, -0.14292696 -0.04528144 -0.054292172, -0.16064249 -0.0087224841 -0.0057873465, -0.16076232 -0.0084761083 -0.0020005591, -0.16035903 -0.013814986 -0.0036174953, -0.15935628 -0.016285181 -0.01500091, -0.15894383 -0.017945707 -0.01700101, -0.15937547 -0.018003464 -0.013001088, -0.15934145 -0.013983786 -0.017000742, -0.15977478 -0.014025331 -0.013000648, -0.15021853 0.027915418 0.047001671, -0.15080215 0.024568617 0.047001552, 0.035065249 -0.13696024 -0.071108274, -0.14924929 0.029716998 0.048664771, -0.14351036 -0.043173403 -0.054443054, -0.14454645 -0.039567024 -0.054443054, -0.14478175 -0.044309974 -0.050668158, -0.16074875 -0.008728385 -0.0020005554, 0.017181814 -0.15320081 -0.043008626, -0.13090207 -0.053413302 -0.071103513, -0.13271029 -0.050972492 -0.069777131, -0.13071913 -0.056964397 -0.069034733, -0.15421377 -0.030784696 -0.032001801, -0.15403017 -0.031690031 -0.032001823, -0.15490451 -0.031840175 -0.02800183, -0.15341353 -0.030104518 -0.035647154, -0.15544604 -0.026656896 -0.030001521, -0.14886302 0.02766341 0.050665308, -0.14893484 0.021883041 0.052846227, -0.14812893 0.028058529 0.052287783, -0.14492501 -0.043599099 -0.050844178, -0.14652908 -0.043289989 -0.04700239, -0.14633927 -0.038587958 -0.050843909, -0.16098493 -0.00043877959 -0.0020000711, -0.16074884 -0.0087284148 0.0019995719, -0.16027533 -0.015259415 -8.8661909e-07, -0.16035762 -0.012946665 0.0057839416, -0.16076232 -0.0084761381 0.0019995905, -0.13275105 -0.054168135 -0.067648023, -0.13448584 -0.053805381 -0.064943857, -0.13194385 -0.058985531 -0.065546185, -0.15508305 -0.030958682 -0.028001718, -0.15641817 -0.025366247 -0.026409432, -0.15639658 -0.029761881 -0.022249654, -0.15873039 0.0065028965 0.02424632, -0.15848517 0.010958225 0.024246365, -0.1593031 0.0063731968 0.020804003, -0.14506505 0.037617594 0.054444931, -0.15875889 0.0048986971 0.024410073, -0.16064271 -0.0087230206 0.0057843104, -0.16026972 -0.01149562 0.0093939863, -0.0064563155 -0.16056246 -0.0092381313, -0.011082776 -0.16049695 -0.0057958737, -0.16073284 -0.0070248842 0.0056181736, -0.15840085 -0.023849159 -0.015001364, -0.15844786 -0.021896571 -0.017001174, -0.1572839 -0.02405104 -0.02280274, -0.15719199 -0.028431058 -0.018633708, -0.15788133 -0.02707544 -0.01500155, -0.15887712 -0.02197051 -0.013001274, 0.02068603 -0.15138149 -0.047008477, -0.15801078 0.0064732134 0.028000273, -0.15810618 0.0034244657 0.028000221, -0.1574809 0.0085980892 0.03000031, -0.16040182 -0.008710295 0.010010377, -0.16007468 -0.010040045 0.012999482, -0.16059583 -0.0055698156 0.0092310235, -0.15884759 -0.02391687 -0.010012161, -0.15893941 -0.02490887 -0.0057883225, -0.15896125 -0.023447514 -0.009397611, -0.15797393 -0.029433757 -0.0092307776, -0.15712488 0.0064367354 0.032000385, -0.15722047 0.0033760667 0.03200027, -0.15653589 0.010007292 0.033647653, -0.15995057 -0.0086859167 0.01499955, -0.15967469 -0.0046604574 0.018629976, -0.16015355 -0.0032333732 0.014999896, -0.15964027 -0.010014921 0.016999453, -0.15620807 0.0063988566 0.035647795, 0.0083124042 -0.15792319 -0.028008804, 0.0082613453 -0.15703779 -0.032008819, -0.15564072 0.0056207776 0.037820403, -0.15450895 0.0070023239 0.041423723, -0.15548052 0.011399329 0.03726716, -0.14971077 -0.045039922 -0.035647906, -0.15042864 -0.040329933 -0.03782472, -0.1478478 -0.043672234 -0.043002568, -0.14884809 -0.046351314 -0.037266634, -0.14933103 -0.047998488 -0.03364782, -0.15126395 -0.042997092 -0.032002397, -0.1387565 -0.056619495 -0.054443918, -0.14006206 -0.055165589 -0.052845538, -0.13810286 -0.055909514 -0.056444764, -0.03450238 -0.15342689 0.031991377, -0.13604191 -0.056593597 -0.060003124, -0.13805109 -0.060587555 -0.052292086, -0.15641102 0.020240456 0.030001104, -0.12523162 -0.065614611 -0.071104094, -0.12683594 -0.066855162 -0.067648828, -0.12572755 -0.064659446 -0.071104147, -0.12329237 -0.070778161 -0.069775201, -0.1401913 0.026050597 0.069035426, -0.14213917 0.026169926 0.065546431, -0.14052573 0.021527976 0.069772467, -0.13996913 0.027219713 0.069035605, -0.042264648 -0.14756343 0.044991791, -0.15931109 -0.0086516738 0.020028498, -0.15908794 -0.0060753822 0.022245456, -0.15863724 -0.012282938 0.022803064, -0.1505889 -0.045304358 -0.032002531, -0.15211551 -0.043244034 -0.028002493, -0.14970422 -0.049625099 -0.030002706, -0.030885465 -0.15509975 0.027991347, -0.14012426 -0.057177752 -0.05084493, -0.14298543 -0.053850919 -0.047003046, -0.13993515 -0.059801728 -0.048668347, -0.045268819 -0.14448941 0.050655834, -0.15143795 -0.045560002 -0.02800259, -0.15151536 -0.047754765 -0.024250805, -0.16098511 -0.00043907762 0.0019999295, -0.15862988 -0.0086148977 0.024245478, -0.15792477 -0.0083140731 0.027999472, -0.15786982 -0.013683677 0.026409276, -0.1414656 -0.05772537 -0.047003135, -0.1417191 -0.058956414 -0.045003399, -0.1442536 -0.054378718 -0.043003, -0.15935621 -0.016286939 0.014999017, -0.15977475 -0.014026821 0.0129993, -0.15937559 -0.018004775 0.012999095, -0.15894388 -0.017947644 0.016998988, -0.15934142 -0.013985664 0.016999178, -0.15541643 -0.038798153 -0.015002191, -0.15411489 -0.040825784 -0.020803548, -0.15340923 -0.045285344 -0.017002545, -0.15897103 0.01243335 0.020631023, -0.15539464 -0.04028216 -0.011398505, -0.15541892 -0.03878805 -0.015002355, -0.15212733 -0.045767605 -0.024250701, -0.15251364 -0.046538264 -0.020634763, -0.15316632 -0.042052925 -0.024410293, -0.15791072 -0.0085759461 0.027999513, -0.16092381 -0.0044589043 -0.0020002723, -0.15787038 -0.031516403 -0.0020016655, -0.15868339 -0.027213931 -1.5199184e-06, -0.15789378 -0.030886263 -0.0056184828, -0.15469235 0.022311658 0.03582089, -0.15770754 -0.032322168 -0.0020018369, -0.14273663 -0.058244318 -0.043003276, -0.14251202 -0.061771244 -0.039267957, -0.1447708 -0.056142986 -0.039427951, -0.15128502 0.0061964095 0.050664164, -0.15093727 0.011979699 0.050664466, -0.15326585 0.0083669722 0.045000501, -0.15122536 0.0059140623 0.050844591, 0.020918325 -0.15273541 -0.043008648, -0.1495654 0.010453045 0.054287635, -0.15702535 -0.0085280836 0.031999685, -0.15699381 -0.015071839 0.029999219, -0.15703952 -0.0082631111 0.031999547, -0.057687037 -0.13040596 0.069026738, -0.15577909 -0.012670219 0.035819013, -0.15787052 -0.031516582 0.0019981079, -0.15770739 -0.032322526 0.0019982085, -0.15887518 -0.025778383 0.0036171451, -0.15795454 -0.030017525 0.007782992, -0.14389774 0.03580308 0.058002051, -0.1438112 -0.058682978 -0.039267726, -0.14518146 -0.057874918 -0.035825357, -0.14980458 0.0061354339 0.05428743, -0.14979941 0.0043945014 0.054443084, -0.15840071 -0.023851037 0.014998704, -0.15887716 -0.021971911 0.012998734, -0.15896074 -0.02432704 0.007229995, 0.036958948 -0.13852969 -0.067652762, -0.15797108 -0.028555542 0.011392869, -0.15788127 -0.027077109 0.014998503, -0.15844791 -0.021898568 0.016998637, -0.15610918 -0.0084785521 0.035646901, -0.15619329 -0.0067532063 0.035646904, -0.15487477 -0.01117456 0.039422296, -0.14475137 -0.059066892 -0.035648748, -0.14286792 -0.063487381 -0.035649016, -0.14561673 -0.060578555 -0.030003399, -0.15339433 -0.046149254 -0.015002757, -0.15382735 -0.045406699 -0.013002586, -0.15264787 -0.04922685 -0.013002723, -0.15223449 -0.049090058 -0.017002806, -0.1481614 0.006067872 0.058000188, -0.14825758 0.0028851032 0.058000121, -0.14712583 0.0080307722 0.060000531, -0.15509492 -0.0084237456 0.039266348, -0.15523486 -0.0052479804 0.039266638, -0.15385941 -0.0096829534 0.042999551, -0.12626708 -0.074019969 -0.062004186, -0.12837887 -0.070293516 -0.062003948, -0.12466886 -0.073752761 -0.064941965, -0.12583238 -0.076657146 -0.060004339, -0.13005838 -0.071225315 -0.058004037, -0.15776743 -0.023755878 0.020027712, -0.15672748 -0.029234916 0.02080198, -0.15695052 -0.024582744 0.02424448, 0.028352089 -0.14806968 -0.052297071, 0.022618592 -0.14882356 -0.052850872, 0.023780018 -0.14707884 -0.056449808, -0.15775234 -0.023252845 0.020629026, -0.1340543 -0.070238441 -0.05084569, -0.13211721 -0.070739537 -0.054444797, -0.13129124 -0.075415999 -0.050670005, -0.13322182 -0.074810416 -0.047004141, -0.134083 -0.070183903 -0.050845705, -0.14624268 0.0059890151 0.06200039, -0.14451432 0.0098672509 0.06494157, -0.030705713 -0.15423167 0.031991474, -0.14633878 0.0027801096 0.062000155, -0.15393683 -0.0083611012 0.042999517, -0.1534678 -0.0028491616 0.044999771, -0.16092393 -0.0044590533 0.0019997172, -0.12792367 -0.074991465 -0.0580042, -0.1292668 -0.075950414 -0.054293849, -0.13533762 -0.070911229 -0.047003955, -0.13703464 -0.069149375 -0.045003995, -0.13442218 -0.075476497 -0.043004334, -0.15405786 -0.046349406 -0.0057894774, -0.15356362 -0.047733992 -0.0072317459, -0.15326425 -0.049151838 -0.0036195517, -0.15484554 -0.044036597 -0.0020025708, -0.15526649 -0.041748136 -0.0077891536, -0.14440753 0.0059137344 0.06554535, -0.1432972 0.0048740506 0.067643017, -0.15102465 -0.053395838 -0.015003089, -0.15000486 -0.056773037 -0.013003182, -0.15137331 -0.053016394 -0.013002954, -0.14960274 -0.056605518 -0.017003223, -0.15096527 -0.052864164 -0.017003022, -0.15256613 -0.0082868636 0.046999618, -0.15212062 -0.0042392015 0.048662834, -0.15248886 -0.0096041262 0.046999477, 0.027166456 -0.1497317 -0.048673555, -0.12928587 -0.075790197 -0.054445118, -0.14708778 -0.060021013 -0.024251349, -0.14685184 -0.059536487 -0.026411474, -0.14585255 -0.063817292 -0.022251561, -0.052261993 -0.13221511 0.069763884, -0.14798841 -0.058447003 -0.0228047, -0.057146322 -0.13275498 0.06553752, -0.15415977 -0.046380341 -0.0020026006, -0.15286134 -0.050541401 -2.8051436e-06, -0.027037621 -0.1558165 0.027991362, -0.1365535 -0.071548551 -0.043004185, -0.13768236 -0.072792202 -0.037826523, -0.13741027 -0.070992947 -0.041429065, -0.14247231 0.005834192 0.069034398, -0.14124881 0.0061464012 0.071098827, -0.14168561 0.011648744 0.069774948, -0.02332662 -0.15739417 0.02279494, -0.029478662 -0.15645224 0.022236891, 0.033636875 -0.14441717 -0.058008052, 0.029849738 -0.14328584 -0.062008098, 0.033241533 -0.14253709 -0.062007986, -0.15118924 -0.0082122386 0.050663188, -0.15065911 -0.0056068003 0.05228598, -0.15007091 -0.011806816 0.052844372, -0.1477198 -0.060279131 -0.020032525, -0.14692399 -0.062696785 -0.018635668, 0.030174412 -0.14518005 -0.058008134, -0.14789788 -0.061528474 -0.015003428, -0.15415978 -0.04638049 0.0019974224, -0.15484549 -0.044036776 0.0019975752, -0.15345635 -0.048305035 0.0057819225, -0.14205036 0.035273671 0.062001988, -0.11623751 -0.08393839 -0.067649812, -0.11914039 -0.082382232 -0.064945512, -0.11803962 -0.079225302 -0.069778658, -0.11476512 -0.084623873 -0.069036245, -0.11550946 -0.086866885 -0.065547764, -0.14471266 0.032352626 0.058001749, -0.14970969 -0.0081321597 0.054286581, -0.14808322 -0.0077478886 0.057999521, -0.14840963 -0.013152808 0.056442883, -0.15541641 -0.038799882 0.014997877, -0.15533021 -0.041166097 0.0092290901, -0.15382743 -0.045408279 0.012997583, -0.15463461 -0.040074557 0.01862805, -0.1554189 -0.038789809 0.014997859, -0.15405779 -0.046350151 0.005782228, -0.15369359 -0.046870708 0.0093919523, -0.15513971 -0.042615324 0.0056161173, -0.14831273 -0.060521454 -0.01500345, -0.1550831 -0.030961692 0.027998254, -0.15586872 -0.030551344 0.024408061, -0.15490451 -0.031843334 0.027998265, -0.15544622 -0.026660293 0.0299986, -0.14806758 -0.0080431402 0.057999618, -0.11865889 -0.08568716 -0.062004842, -0.11614779 -0.089061111 -0.062005177, -0.11771329 -0.090175718 -0.058005176, -0.12003703 -0.085446715 -0.060004815, 0.041572273 -0.13594782 -0.069778927, -0.14873137 -0.060692549 -0.010014225, -0.14746346 -0.063848197 -0.0092326179, -0.14941144 -0.059651703 -0.0057901926, -0.14975798 -0.05823192 -0.0093996264, -0.15421379 -0.030788451 0.031998314, -0.1540302 -0.031693548 0.031998243, -0.15298975 -0.029153436 0.037818313, -0.15483828 -0.02507627 0.033645686, -0.14615005 -0.0079393089 0.061999582, -0.14663292 -0.014475465 0.059999302, -0.14432445 -0.012364209 0.064937308, -0.14616615 -0.0076373816 0.061999492, -0.15244517 -0.022955924 0.042998739, -0.15411942 -0.0234842 0.037265286, -0.1521937 -0.027554959 0.0414217, -0.15128568 -0.02594769 0.044998482, -0.1527378 -0.020920694 0.042998724, -0.1202158 -0.086811632 -0.058004946, -0.12219849 -0.085238427 -0.056446366, -0.1533943 -0.046150953 0.014997449, -0.15223445 -0.049091756 0.016997103, -0.1534093 -0.045287162 0.016997326, -0.1526479 -0.04922834 0.012997221, -0.14895445 -0.060783714 -0.0057903193, -0.14706217 -0.065246433 -0.0056203194, -0.14864936 -0.061841935 -3.4198165e-06, -0.14431626 -0.0078398883 0.065544546, -0.14179373 -0.010281801 0.069770619, -0.14439958 -0.0061151683 0.065544546, -0.15108782 -0.022751659 0.046998732, -0.14981933 -0.021907508 0.050662521, -0.15138409 -0.020688832 0.046998758, -0.12149584 -0.087736368 -0.054445699, -0.12427425 -0.084949106 -0.052847318, -0.12110719 -0.089787483 -0.052293666, -0.02689039 -0.15494233 0.031991288, -0.1062314 -0.093289316 -0.071105652, -0.10818634 -0.09101519 -0.071105659, -0.10877842 -0.093402535 -0.067650288, -0.10445077 -0.096438646 -0.069776639, -0.14238206 -0.0077351332 0.069033444, -0.14251751 -0.0046088994 0.069033787, -0.13861902 0.036638439 0.067644745, -0.13566285 -0.079529911 -0.032004349, -0.13480151 -0.078310966 -0.037268482, -0.13490593 -0.080024391 -0.033649683, -0.13490801 -0.081693083 -0.030004576, -0.13790324 -0.075578421 -0.032004237, -0.1386786 -0.076008558 -0.028004333, -0.14972427 -0.022546619 0.050662376, -0.1481421 -0.023090541 0.05428572, -0.14875048 -0.02788502 0.050842758, 0.03707996 -0.14357165 -0.058008052, 0.03661485 -0.1417082 -0.062007912, -0.12269349 -0.08860147 -0.050846674, -0.12504655 -0.089013577 -0.045005031, -0.12311894 -0.089440852 -0.048670016, -0.10773212 -0.094607234 -0.067650326, -0.10951762 -0.097097903 -0.062005579, -0.10513085 -0.099644899 -0.064943515, -0.13642763 -0.079978615 -0.02800452, -0.13708988 -0.080272615 -0.024252459, -0.15212776 -0.045770526 0.024243295, -0.15192716 -0.047274977 0.022801135, -0.15086719 -0.048469931 0.026407253, -0.15374771 -0.041323483 0.022243306, -0.14976281 -0.038636357 -0.041427344, -0.14898667 -0.036922544 -0.045002021, -0.15211555 -0.043247193 0.027997591, -0.021790259 -0.15695781 0.026401192, -0.15102467 -0.053397417 0.014996994, -0.14960268 -0.056607306 0.016996801, -0.15096529 -0.052866071 0.016997036, -0.15137336 -0.053017795 0.012997068, -0.13633892 0.037423074 0.071100712, -0.15000482 -0.056774616 0.012996919, -0.14895448 -0.06078434 0.0057812668, -0.14915568 -0.060485065 0.0036152266, -0.14731492 -0.064413071 0.0077811144, -0.14284757 0.031892776 0.062001821, -0.14956215 -0.059089243 0.0072280206, -0.14188832 -0.074345261 -0.015004195, -0.13986664 -0.078498036 -0.013004325, -0.14253497 -0.073850542 -0.011400551, -0.13948569 -0.078286648 -0.017004438, -0.14289093 -0.072399497 -0.015004188, -0.14116594 -0.074096084 -0.020805456, -0.15143797 -0.045563161 0.027997449, -0.14970426 -0.049628496 0.029997218, -0.14873128 -0.060693502 0.01000753, -0.14765623 -0.06299156 0.011391014, -0.14789788 -0.061530143 0.01499654, -0.15058899 -0.045307785 0.03199733, -0.14905429 -0.04701677 0.03581712, -0.15126397 -0.043000609 0.031997487, -0.1259218 -0.090933591 -0.039269522, -0.12866268 -0.088729799 -0.035827026, -0.12864752 -0.086949915 -0.039429598, -0.14544477 0.028883398 0.058001556, -0.1251929 -0.091934472 -0.039269656, -0.14831284 -0.060523033 0.014996458, -0.14971024 -0.045043856 0.035644859, -0.14850566 -0.045357376 0.039420445, -0.15077502 -0.041340232 0.035645105, -0.12674519 -0.091528267 -0.035650551, -0.12515807 -0.09368664 -0.035650738, -0.13818996 -0.081012487 -0.01500456, -0.13749386 -0.081734568 -0.017004713, -0.13786651 -0.081959963 -0.013004564, -0.1126055 -0.098888099 -0.054446429, -0.10912459 -0.10281068 -0.054295242, -0.11121721 -0.1027402 -0.050671533, -0.11094764 -0.098380089 -0.058005534, -0.11306304 -0.098364741 -0.054446355, -0.14541629 -0.029033571 0.057998464, -0.14702214 -0.029049367 0.054441258, -0.14518324 -0.030177802 0.057998337, -0.14522496 -0.024909168 0.059998628, -0.14873764 -0.044751436 0.039264213, -0.14784768 -0.043677211 0.042997506, -0.15017563 -0.039659381 0.039264578, -0.096882313 -0.10296491 -0.071106277, -0.093056254 -0.10803971 -0.069037661, -0.097450003 -0.10350507 -0.069779955, -0.14771982 -0.060281366 0.020025574, -0.14629284 -0.063377053 0.02079995, -0.14754546 -0.058891356 0.024242572, -0.14862329 -0.057772875 0.02062713, -0.15135492 0.020896047 0.047001213, -0.1274884 -0.092065424 -0.032005154, -0.12848537 -0.091462553 -0.030005239, -0.15271619 0.021073431 0.043001227, -0.12502587 -0.09538269 -0.032005355, -0.12574866 -0.095897317 -0.028005362, -0.11371544 -0.099863052 -0.050847404, -0.11323427 -0.10257927 -0.047005728, -0.11510329 -0.098260373 -0.05084727, -0.14353304 -0.028657973 0.061998323, -0.14078996 -0.027134925 0.067641124, -0.14308782 -0.022537619 0.064939663, -0.14328915 -0.029853225 0.061998289, -0.12820724 -0.09258467 -0.028005183, -0.12992136 -0.090721339 -0.026413225, -0.1470882 -0.060023874 0.024242543, -0.14516282 -0.064469606 0.024406236, -0.14561668 -0.060581952 0.029996529, -0.1148041 -0.10081938 -0.047005616, -0.11425652 -0.10349581 -0.043005832, -0.11821125 -0.097908765 -0.045005545, -0.13417873 -0.087496042 -0.015004933, -0.13325563 -0.088476092 -0.017004915, -0.13361056 -0.088728875 -0.01300507, -0.13541675 -0.085131586 -0.017004766, -0.13578063 -0.085371017 -0.013004728, -0.12879097 -0.093006432 -0.024253219, -0.13127208 -0.089912146 -0.02280654, -0.12799487 -0.094672322 -0.022253223, -0.13887969 -0.081417501 -0.0020045377, -0.14116415 -0.077388883 -0.002004344, -0.13909157 -0.080708236 -0.0072336197, -0.13848424 -0.082024097 -0.003621269, -0.13778223 -0.083289057 -4.61936e-06, -0.11583557 -0.10172534 -0.043005638, -0.11816709 -0.099789768 -0.041430719, -0.12934425 -0.093406141 -0.020034254, -0.13049823 -0.092896253 -0.015005298, -0.12928888 -0.093818307 -0.018637352, 0.040501893 -0.14264405 -0.058008015, 0.039967462 -0.14079931 -0.062008016, -0.13887963 -0.08141768 0.0019953959, -0.14116411 -0.077389002 0.0019956119, -0.13885991 -0.081241369 0.0057800636, -0.11670767 -0.10249141 -0.039270237, -0.11399549 -0.10634357 -0.037270099, -0.11803221 -0.1016044 -0.03782814, -0.14357321 -0.043198436 0.054284535, -0.14652908 -0.043295264 0.046997622, -0.1436817 -0.044904768 0.05284252, -0.14176261 -0.045847535 0.056440983, -0.14264719 -0.04050526 0.057997692, -0.14563495 -0.038991123 0.052284084, -0.14188829 -0.074347019 0.014995791, -0.13948573 -0.078288704 0.016995698, -0.14184035 -0.073479265 0.018626168, -0.1428909 -0.072401196 0.014995791, -0.14227553 -0.07469818 0.0092272162, -0.1398665 -0.078499556 0.012995668, -0.14475092 -0.059070706 0.035643987, -0.14266714 -0.062465906 0.037816595, -0.020242237 -0.1564129 0.02999121, -0.14502996 -0.057190269 0.037263397, -0.14537671 -0.058902264 0.033643808, -0.11747059 -0.10316163 -0.03565111, -0.1176276 -0.10436985 -0.032005876, 0.01398471 -0.15934059 -0.01700899, 0.010039158 -0.16007403 -0.013009027, 0.010014042 -0.15963927 -0.017008938, -0.14199832 -0.042724788 0.057997607, -0.13973609 -0.046741575 0.059997354, -0.14543366 -0.046838641 -0.047002554, -0.14381042 -0.05868718 0.039263505, -0.14224699 -0.060730249 0.041419897, 0.0004388988 -0.16098508 0.0019909739, -0.0035812333 -0.16094601 0.0019909889, -0.0035811886 -0.16094571 -0.0020090789, -0.14425358 -0.054383606 0.042997111, 0.00043889135 -0.16098484 -0.0020089895, -0.095111705 -0.11124656 -0.062006295, -0.097820714 -0.10682803 -0.064946957, -0.093282968 -0.11039197 -0.065549053, -0.098013096 -0.11001521 -0.060006224, -0.093417078 -0.11267319 -0.062006332, -0.094695248 -0.11410841 -0.05800654, -0.13022989 -0.094046324 -0.01001624, -0.13239163 -0.091403216 -0.0057919994, -0.13304538 -0.090096205 -0.0094013959, -0.12955864 -0.095061004 -0.0092343912, -0.14015934 -0.042171717 0.061997697, -0.1379555 -0.044169426 0.064935401, -0.14080267 -0.039971054 0.061997704, -0.1435643 0.028493941 0.062001616, -0.14273663 -0.058249086 0.042996675, -0.14171928 -0.058961421 0.044996705, -0.0087345243 -0.15994883 0.01499097, -0.011655487 -0.16038901 0.0072223768, -0.0073129162 -0.16036519 0.011385545, -0.013933234 -0.15978357 0.012991033, -0.096359491 -0.11270651 -0.058006339, -0.10016679 -0.11029303 -0.056447826, -0.10470062 -0.11127558 -0.04700622, -0.10012908 -0.11459482 -0.048671469, -0.10210342 -0.11460724 -0.045006461, -0.1063729 -0.11158264 -0.043006256, -0.10545926 -0.11055678 -0.047006115, -0.10225475 -0.11047286 -0.052848749, -0.14609388 0.025398105 0.058001358, -0.13819002 -0.081014156 0.014995452, -0.13786653 -0.081961393 0.012995396, -0.13749386 -0.081736386 0.016995449, -0.012434639 -0.15897235 0.02062133, -0.013909474 -0.15934902 0.016991012, -0.13042524 -0.094187677 -0.005792167, -0.12885621 -0.096335053 -0.0056222081, -0.15406907 -0.035664052 -0.028001942, -0.1384007 -0.041642845 0.065542549, -0.13941929 -0.038093835 0.065542877, -0.15320128 -0.035481364 -0.032001905, -0.14146551 -0.057730734 0.046996836, -0.1388166 -0.060286194 0.050840996, 0.0044589639 -0.16092378 -0.0020090342, -0.14298542 -0.053856015 0.046997048, -0.1411887 -0.054696143 0.05066067, -0.097385682 -0.11390692 -0.054447129, -0.022313595 -0.15469432 0.035811141, -0.09809041 -0.11448538 -0.052294999, -0.028174475 -0.15378153 0.035638779, -0.1193667 -0.10482749 -0.024253987, -0.11828776 -0.10496184 -0.028005771, -0.11579014 -0.10876551 -0.024254143, -0.11975155 -0.10434455 -0.024413936, -0.11721742 -0.10810262 -0.020638153, -0.13051163 -0.094250172 -0.0020052455, -0.13116114 -0.093369067 -5.1856041e-06, -0.1280652 -0.097548008 -0.0020055175, -0.10564124 -0.11227563 -0.043006361, -0.10607351 -0.1133967 -0.039431237, -0.1518181 0.01721102 0.04700106, -0.15318534 0.017337471 0.043000914, -0.081242099 -0.11570454 -0.07110697, -0.085219994 -0.11280701 -0.071106963, -0.085266255 -0.11526611 -0.067651577, -0.08037138 -0.11726305 -0.069777772, -0.13654584 -0.041084975 0.069031633, -0.1359517 -0.041576147 0.069768861, -0.1379196 -0.036206543 0.069031976, -0.14018895 -0.057209969 0.050660562, -0.13929051 -0.055476516 0.054283962, -0.11987956 -0.10527822 -0.020035006, -0.12113843 -0.1036506 -0.020807102, -0.11856791 -0.10736227 -0.017005987, 0.014026009 -0.15977407 -0.013009027, -0.13051161 -0.09425047 0.0019947104, -0.13195691 -0.092158854 0.0036134198, -0.12806541 -0.097548246 0.0019944571, -0.08238972 -0.11733916 -0.067651719, -0.085164651 -0.11903352 -0.06200663, -0.080321051 -0.12054041 -0.064944573, -0.13881715 -0.056650341 0.054283783, -0.13687256 -0.061036617 0.054439355, -0.023570769 -0.15348017 0.039414346, -0.13604192 -0.056600332 0.059996918, -0.13417871 -0.087497771 0.014995046, -0.13578057 -0.085372418 0.012995213, -0.13361052 -0.088730246 0.012995046, -0.13325571 -0.08847791 0.016995136, -0.13541672 -0.085133612 0.016995121, -0.13042539 -0.094188362 0.0057793297, -0.13266385 -0.09088856 0.0072263144, 0.030106485 -0.15341163 -0.035654172, 0.024119958 -0.15441838 -0.035830684, 0.028512701 -0.15268257 -0.039272957, -0.12928826 -0.09557882 0.0077792779, -0.12036096 -0.10570112 -0.015005998, -0.11889219 -0.10765317 -0.013005979, 0.026658624 -0.15544447 -0.030008733, -0.12252766 -0.10371596 -0.011402197, -0.12319776 -0.1023806 -0.015005767, -0.14673683 -0.047270149 -0.043002665, -0.13642767 -0.079981685 0.027995467, -0.13867855 -0.076011956 0.027995661, -0.13759851 -0.079896808 0.022799168, -0.13629928 -0.080825984 0.026405439, 0.050976396 -0.13270646 -0.069781661, -0.13490795 -0.081696421 0.029995371, -0.13758078 -0.07209152 0.039262854, -0.13758585 -0.072082371 0.039262813, -0.13779622 -0.073854387 0.035643242, -0.13469 -0.077265918 0.039418608, -0.13442224 -0.075481325 0.042995788, -0.084105931 -0.11978391 -0.062006824, -0.086273693 -0.12060165 -0.058006763, -0.080109335 -0.12366194 -0.060007088, -0.13022976 -0.094047457 0.010005556, -0.12993762 -0.094268769 0.011389371, -0.13049822 -0.092897832 0.014994785, -0.12070046 -0.10599968 -0.010016836, -0.11764491 -0.10963553 -0.0072353631, -0.14425212 -0.050359726 -0.047002897, -0.12177624 -0.10498148 -0.0077928826, -0.13566285 -0.079533577 0.031995542, -0.13485551 -0.079005688 0.035815284, -0.13790333 -0.075581998 0.031995755, -0.13655347 -0.071553439 0.042995941, -0.14420012 0.025079131 0.062001366, -0.13703474 -0.069154561 0.044996083, -0.085209467 -0.12135568 -0.058006763, 0.0044589117 -0.16092396 0.0019910038, -0.083510339 -0.12451547 -0.054296561, -0.12088168 -0.10615891 -0.0057928637, -0.12040425 -0.10686043 -0.0020059496, -0.13381594 -0.054610044 0.065541923, -0.13122271 -0.057783395 0.067639366, -0.13448599 -0.053812712 0.06493789, -0.10159325 -0.11882946 -0.035652049, -0.10159631 -0.11748746 -0.039271064, -0.10117243 -0.11918807 -0.035652198, -0.10569218 -0.11513525 -0.035828575, -0.10491133 -0.11776 -0.030006573, -0.11519507 -0.11130831 -0.015006252, -0.11307786 -0.11313018 -0.017006472, -0.11337923 -0.11344469 -0.013006419, -0.1161719 -0.11058331 -0.013006181, -0.11585882 -0.11028054 -0.017006271, -0.15313929 -0.039466083 -0.02800221, -0.13533768 -0.070916474 0.046996113, -0.13322181 -0.07481581 0.04699586, -0.13330787 -0.070420384 0.052282292, -0.13521793 -0.069822311 0.048659321, -0.086116895 -0.12264815 -0.054447703, -0.088339441 -0.12105733 -0.05444774, -0.15227889 -0.039251238 -0.032002166, -0.085566223 -0.12491232 -0.050672673, -0.069875486 -0.12290317 -0.071107402, -0.066681258 -0.12603787 -0.069038674, -0.071973875 -0.12259457 -0.069780938, -0.13202254 -0.053878576 0.069031, -0.13271032 -0.05098021 0.069771364, -0.12992956 -0.055748254 0.071095556, 0.0084761754 -0.16076219 -0.0020090267, -0.12934431 -0.093408376 0.020023819, -0.12852244 -0.094341367 0.020798281, -0.14761476 0.020201027 0.056444708, -0.13204148 -0.089396209 0.020625345, -0.13074206 -0.090246648 0.024240825, -0.1021892 -0.1195268 -0.03200677, -0.10066628 -0.12081218 -0.032006763, -0.10125621 -0.12147468 -0.02800677, -0.086965702 -0.12385738 -0.050848529, -0.087568551 -0.12520438 -0.047007076, -0.1521917 0.013516068 0.047000766, -0.090351865 -0.1214096 -0.050848521, -0.070862494 -0.12463954 -0.067652151, -0.071595915 -0.12591657 -0.064947896, -0.15356314 0.013591081 0.04300081, -0.10276531 -0.12020072 -0.028006703, -0.10647634 -0.1173569 -0.026414603, -0.12879127 -0.093009263 0.024240557, -0.12717783 -0.095154971 0.02440444, -0.035277285 -0.1420539 0.061992042, -0.040571555 -0.14165276 0.059991956, -0.035806365 -0.14390093 0.057991952, -0.08779835 -0.12504339 -0.047007017, -0.088361204 -0.12632534 -0.04300721, -0.092998564 -0.12358248 -0.041432112, -0.093460068 -0.12175831 -0.045006998, -0.04288853 -0.13554436 0.069766626, -0.12088162 -0.10615972 0.0057787523, -0.12040426 -0.1068607 0.0019939803, -0.11730069 -0.11010364 0.0057785586, -0.12128627 -0.10570776 0.00561269, -0.11813708 -0.10891417 0.0093883798, -0.1097683 -0.11666355 -0.015006475, -0.1102266 -0.11590999 -0.017006442, -0.10655471 -0.11960572 -0.015006743, -0.10966135 -0.11744267 -0.0094029382, -0.032355823 -0.14471611 0.057991922, -0.1105165 -0.11623523 -0.013006575, -0.10323314 -0.12074828 -0.024254866, -0.10371877 -0.12078029 -0.02225484, -0.12820721 -0.092587769 0.027994759, -0.15814261 -0.00048935413 0.027999971, -0.12574866 -0.095900565 0.027994633, -0.12848544 -0.09146598 0.029994905, -0.088587135 -0.12616721 -0.043007076, -0.12070049 -0.10600057 0.010004949, -0.0063743666 -0.15930441 0.020794578, -0.010959834 -0.15848655 0.024236977, -0.1220866 -0.10448483 0.0092255287, -0.1188923 -0.10765463 0.012994029, -0.12748846 -0.09206894 0.031994745, -0.12502588 -0.095386326 0.031994734, -0.12862527 -0.089774907 0.03364215, -0.089254044 -0.12711704 -0.039271533, -0.087473311 -0.12904382 -0.037271313, -0.092463218 -0.12532151 -0.037829466, -0.14553869 -0.050839573 -0.043002941, -0.12036081 -0.10570288 0.014994055, -0.12193379 -0.10319945 0.018624503, -0.12319778 -0.1023823 0.014994334, -0.11856798 -0.10736436 0.016994055, -0.12674454 -0.091531903 0.035642236, -0.12519068 -0.092646301 0.037814893, -0.12866826 -0.08802852 0.037261631, -0.089837626 -0.12794852 -0.035652585, -0.086823918 -0.1306327 -0.033652551, -0.091453478 -0.1279276 -0.03200718, 0.021897413 -0.15844697 -0.017008774, 0.018004164 -0.15937483 -0.013008997, 0.017946698 -0.15894297 -0.017008997, -0.12792368 -0.074997872 0.057995845, -0.13005835 -0.071231693 0.057996113, -0.1300879 -0.075751066 0.052840918, -0.12800702 -0.076243192 0.056439329, -0.13305449 -0.060982645 -0.062003441, -0.12583241 -0.076663911 0.059995696, -0.12592122 -0.090937585 0.039261669, -0.1251674 -0.090860605 0.04141815, -0.066202402 -0.13053405 -0.062007368, -0.066378728 -0.12838158 -0.065550141, -0.0660019 -0.13063556 -0.062007338, -0.066928886 -0.13231909 -0.058007434, -0.071074173 -0.12906665 -0.060007267, -0.057876028 -0.12898877 -0.071107715, -0.057478569 -0.13134944 -0.067652471, -0.057980672 -0.12894186 -0.071107768, -0.12630369 -0.066184223 0.069030195, -0.12744781 -0.06816262 0.065541103, -0.1232924 -0.070785969 0.069767311, -0.12640589 -0.065989017 0.06903033, -0.11987956 -0.10528046 0.020023022, -0.11637025 -0.10851222 0.022797752, -0.12059291 -0.10393986 0.022239871, -0.090364523 -0.12869918 -0.032007217, -0.086101823 -0.13213715 -0.030007467, 0.0084761828 -0.16076243 0.0019910112, -0.091965511 -0.12865183 -0.028007187, -0.074798442 -0.13156316 -0.050849095, -0.078213491 -0.13125172 -0.047007434, -0.075107902 -0.13045678 -0.052849866, -0.073112175 -0.12981683 -0.056448922, -0.070155181 -0.13344198 -0.052296087, -0.072118156 -0.13400248 -0.048672706, -0.12626708 -0.074026972 0.061995905, -0.12466877 -0.073760003 0.064933702, -0.12837896 -0.07030049 0.061996061, -0.067071036 -0.13224712 -0.058007516, -0.090874031 -0.12942493 -0.028007306, -0.088684216 -0.13180405 -0.02425544, -0.11936715 -0.10483056 0.024239961, -0.11828782 -0.104965 0.027994089, -0.075514376 -0.13282284 -0.047007397, -0.078875922 -0.13245517 -0.043007463, -0.07404042 -0.13445392 -0.045007557, -0.11519504 -0.11131012 0.014993876, -0.11585884 -0.11028242 0.016993806, -0.11617188 -0.11058456 0.012993779, -0.11307783 -0.113132 0.01699362, -0.11337927 -0.11344609 0.012993619, -0.10454302 -0.12228176 -0.0057937503, -0.10515714 -0.12150717 -0.0092358962, -0.10418889 -0.1225929 -0.0056236982, -0.10873323 -0.11857152 -0.0057936609, -0.10709616 -0.1202141 -6.5788627e-06, 0.043292604 -0.14652652 -0.047008172, 0.038638704 -0.14976057 -0.041433491, 0.036925003 -0.14898422 -0.045008346, -0.091287628 -0.13001442 -0.024255313, -0.093529999 -0.12837556 -0.024415217, 0.038590692 -0.14633656 -0.050849803, -0.09022326 -0.13147551 -0.020639442, -0.15725596 -0.00050482154 0.03200011, -0.10461219 -0.12236267 -0.0020068362, -0.10314792 -0.12359956 -0.0020069703, -0.076192856 -0.13401657 -0.043007456, -0.078180358 -0.13415712 -0.039432392, -0.031896293 -0.1428512 0.061992019, -0.072905198 -0.13714913 -0.039272152, -0.12275022 -0.088648081 0.05065877, -0.12504661 -0.089018673 0.044995051, -0.12192196 -0.08966431 0.050839253, -0.1254784 -0.084742367 0.050658971, -0.12345423 -0.085080683 0.054282267, -0.091679886 -0.13057315 -0.020036399, -0.14617664 0.018516093 0.060001105, -0.095036551 -0.12800768 -0.020808406, -0.091704629 -0.13105446 -0.017007388, -0.10461237 -0.1223627 0.0019931719, -0.15808207 -0.0044031739 0.02799977, -0.10314789 -0.12359977 0.0019929856, -0.10814122 -0.11921138 0.0036118627, -0.07676632 -0.13502568 -0.0392721, -0.077421725 -0.13576722 -0.035829701, -0.12154893 -0.087781042 0.054282133, -0.11985976 -0.089963347 0.054437861, -0.10976828 -0.11666518 0.014993444, -0.11051641 -0.11623678 0.012993421, -0.10655472 -0.11960727 0.014993411, -0.02888687 -0.14544815 0.05799181, -0.10883866 -0.11653695 0.020623725, -0.1102266 -0.11591196 0.016993444, -0.1174702 -0.10316545 0.035641614, -0.11762758 -0.10437346 0.031994198, -0.11389456 -0.10703301 0.035813604, -0.11790764 -0.10266531 0.035641599, -0.11412027 -0.10530007 0.039417099, -0.10454334 -0.12228227 0.0057777762, -0.1047785 -0.12195185 0.0077778324, -0.092047974 -0.13109764 -0.015007347, -0.08841411 -0.13329649 -0.017007492, -0.096376628 -0.12838066 -0.011403516, -0.097327061 -0.12722769 -0.015007205, -0.088652045 -0.13366124 -0.013007559, 0.021971144 -0.1588766 -0.013008952, -0.091956019 -0.13141006 -0.013007328, -0.12021564 -0.086818248 0.057995018, -0.11771331 -0.090182245 0.057994861, -0.12003708 -0.085453421 0.059995268, -0.13482872 -0.061720997 -0.058003552, -0.11670701 -0.10249531 0.039261147, -0.11809697 -0.10089082 0.039261151, -0.11425637 -0.10350063 0.042994168, -0.053494252 -0.13623601 -0.062007718, -0.057273351 -0.13677549 -0.058007754, -0.056541316 -0.13499999 -0.062007584, -0.020898663 -0.15135759 0.046991415, -0.024571255 -0.15080494 0.046991542, -0.024799168 -0.15215847 0.042991512, -0.051483609 -0.13539127 -0.064945549, -0.050582573 -0.13838753 -0.060007796, -0.021075785 -0.15271869 0.042991348, -0.092307568 -0.13146785 -0.010018319, -0.09536235 -0.12944701 -0.0077942535, -0.090298958 -0.13306522 -0.0072366744, -0.11865889 -0.085694224 0.061995108, -0.11614786 -0.089068115 0.061994962, -0.1191406 -0.082389444 0.06493634, -0.11583557 -0.10173008 0.042994302, -0.11821119 -0.097913772 0.044994548, -0.054196224 -0.13802379 -0.058007821, -0.053708628 -0.13997626 -0.054297358, -0.092446119 -0.13166541 -0.0057943538, -0.093606807 -0.13097376 -0.0020073056, -0.089181021 -0.13398713 -0.0036241114, -0.11717 -0.084619164 0.065540314, -0.11507563 -0.085534543 0.067637846, -0.08570575 -0.13532898 -0.015007682, -0.085068777 -0.13545606 -0.017007664, -0.085292771 -0.13582957 -0.013007611, -0.11480416 -0.10082459 0.046994388, -0.1132343 -0.1025846 0.046994269, 0.029763207 -0.15639549 -0.022256754, 0.024052292 -0.15728271 -0.022810251, 0.025367618 -0.15641686 -0.026416875, -0.11629137 -0.098160744 0.048657637, -0.054773174 -0.13949373 -0.054448619, -0.055624753 -0.14082062 -0.050673552, -0.059186056 -0.13767943 -0.054448605, -0.092507392 -0.13175255 -0.0020074397, -0.087999724 -0.13482243 -7.5697899e-06, -0.1434563 0.020060927 0.064939119, -0.038929336 -0.13591227 -0.071108051, -0.042888522 -0.13553646 -0.069781855, -0.036962464 -0.1377157 -0.069039278, -0.11559975 -0.083485305 0.069029301, -0.11803965 -0.079232961 0.069769688, -0.11426764 -0.083262742 0.071093887, -0.11376796 -0.099915028 0.050658096, -0.11429623 -0.098318577 0.052280623, -0.10997073 -0.10279921 0.052839343, 0.043674737 -0.14784542 -0.043008365, -0.078852862 -0.13869661 -0.020036682, -0.081670545 -0.13753149 -0.017007798, -0.079260074 -0.1379647 -0.022809051, -0.074241973 -0.14083177 -0.022255808, -0.075778425 -0.14062381 -0.018639989, -0.077268459 -0.14031753 -0.015007935, 0.040332057 -0.15042672 -0.037830837, -0.092507266 -0.13175273 0.0019926354, -0.089859486 -0.13344499 0.005777128, -0.093606703 -0.13097394 0.0019927397, -0.0394793 -0.13783246 -0.067652777, -0.041781016 -0.13869113 -0.06494873, 0.046841227 -0.14543101 -0.047008179, -0.036146067 -0.13993341 -0.065550737, -0.11265483 -0.098937273 0.054281436, -0.11094765 -0.098386645 0.057994422, -0.15719566 -0.0043853819 0.031999737, -0.10323331 -0.12075123 0.024238966, -0.10430754 -0.12057495 0.020796776, -0.10281554 -0.12106904 0.024402991, 0.028432064 -0.15719089 -0.018640898, -0.10491128 -0.11776337 0.029993389, -0.10738254 -0.11707687 0.024239372, -0.092446201 -0.13166606 0.0057773218, -0.09093947 -0.1324715 0.0093870983, -0.094723158 -0.13004619 0.0056113452, -0.079169534 -0.13925362 -0.015007727, -0.081880666 -0.13791332 -0.013007723, -0.10276518 -0.12020397 0.027993277, -0.10125637 -0.12147787 0.027993247, -0.040301748 -0.14070386 -0.062007971, -0.035277218 -0.14204699 -0.062007964, -0.040571466 -0.14164621 -0.060008027, -0.02849751 -0.14356777 0.061992034, -0.092307605 -0.13146907 0.010003522, -0.091955967 -0.13141161 0.012992688, -0.095775768 -0.1290319 0.0092241168, -0.079392761 -0.13964695 -0.010018654, -0.075482555 -0.14186034 -0.0092369989, -0.079622395 -0.13979402 -0.0057947934, -0.080778338 -0.1389001 -0.0094040856, -0.10218918 -0.11953032 0.03199327, -0.10066621 -0.12081575 0.031993199, -0.025401235 -0.14609727 0.057991855, -0.10542395 -0.11614594 0.033640567, -0.10564116 -0.11228055 0.042993698, -0.10585452 -0.11445296 0.037260156, -0.10181129 -0.1164349 0.041416701, -0.10637285 -0.11158746 0.042993739, -0.10210337 -0.1146124 0.044993639, -0.040830433 -0.14255038 -0.058008045, -0.035806328 -0.14389452 -0.058008149, -0.038701937 -0.14570734 -0.052296869, -0.042391375 -0.14283103 -0.0564496, 0.035665609 -0.15406752 -0.028008692, 0.031691708 -0.15402839 -0.032008551, 0.035483129 -0.15319952 -0.032008611, -0.092047974 -0.13109922 0.01499261, -0.091704518 -0.13105652 0.016992629, -0.095912747 -0.12774494 0.01862305, -0.08865203 -0.13366276 0.012992539, -0.088414051 -0.13329834 0.016992494, 0.031841598 -0.15490305 -0.028008722, -0.097326927 -0.12722939 0.0149929, -0.021886125 -0.14893791 0.052836753, -0.028061606 -0.14813176 0.052277967, -0.10159288 -0.11883295 0.035640739, -0.13331434 -0.064926803 -0.058003739, -0.10143657 -0.11818117 0.037813447, -0.13156977 -0.064123034 -0.062003501, -0.079511933 -0.13985667 -0.0057947785, -0.074297152 -0.14270341 -0.0056248084, -0.077660777 -0.1410313 -7.9572201e-06, -0.10859616 -0.095373869 0.065539703, -0.10951763 -0.097105026 0.061994579, -0.10513086 -0.09965232 0.064932369, -0.10445073 -0.096446395 0.069765829, -0.10908574 -0.094813615 0.06553968, -0.057139739 -0.14552179 -0.035653464, -0.056564756 -0.14527285 -0.037272282, -0.055578299 -0.14667749 -0.03365346, -0.06225799 -0.14275438 -0.03783039, -0.060693696 -0.14507043 -0.032008074, -0.10470064 -0.11128083 0.046993818, -0.10347612 -0.11053938 0.050657548, -0.10545932 -0.11056218 0.046993826, -0.017213777 -0.15182081 0.046991415, -0.0173399 -0.15318793 0.042991377, -0.041265301 -0.14406857 -0.054448858, -0.044194706 -0.14389893 -0.052850604, -0.02583342 -0.13899741 -0.071108297, -0.026808538 -0.1408464 -0.067652993, -0.027833834 -0.13861081 -0.071108297, -0.02153194 -0.14052185 -0.069778912, -0.1071407 -0.094095856 0.069028638, -0.10855361 -0.09246251 0.069028884, -0.091679946 -0.13057551 0.020021714, -0.089306645 -0.13168642 0.022796296, -0.094440892 -0.1281684 0.022238567, -0.057475016 -0.14637557 -0.032008208, -0.054539487 -0.1479837 -0.030008242, -0.061031625 -0.14589036 -0.028008163, -0.041671969 -0.14548901 -0.050849892, -0.040491141 -0.14669046 -0.048673391, -0.02619838 -0.1409612 -0.067652978, -0.025082558 -0.14419675 -0.062008172, -0.057799049 -0.14720115 -0.028008133, -0.057131112 -0.14823356 -0.024256401, -0.091287822 -0.13001761 0.024238557, -0.087733045 -0.13195992 0.026402622, -0.091965482 -0.12865502 0.027992796, 0.056596898 -0.13603851 -0.060007647, 0.053809084 -0.13448235 -0.064948477, 0.058989182 -0.13194039 -0.065550379, -0.042070918 -0.14688209 -0.047008187, -0.04226464 -0.14755836 -0.045008384, -0.047045626 -0.14536497 -0.047008261, -0.085705757 -0.1353305 0.014992416, -0.085292727 -0.13583097 0.012992375, -0.08506874 -0.13545787 0.016992249, -0.065573975 -0.1461488 -0.015008181, -0.064169213 -0.14594588 -0.020809494, -0.060242832 -0.14817488 -0.017008372, 0.047272429 -0.14673463 -0.04300826, -0.065392815 -0.14660761 -0.011404589, -0.066575825 -0.14569503 -0.015008301, -0.060408749 -0.1485776 -0.013008423, -0.058062151 -0.14787138 -0.024256274, -0.058704786 -0.14825583 -0.020640343, -0.062618479 -0.14596939 -0.024416186, -0.090874076 -0.12942818 0.02799277, -0.086101949 -0.13214052 0.029992513, -0.079392783 -0.13964808 0.010003097, -0.075014822 -0.14220959 0.007776767, -0.076168291 -0.14131117 0.01138667, -0.07726831 -0.14031923 0.014992192, -0.08009126 -0.1394484 0.0072235391, -0.081880696 -0.13791475 0.012992233, -0.090364501 -0.12870288 0.031992834, -0.091453515 -0.12793124 0.031992868, -0.087222382 -0.12969348 0.03581249, -0.042768545 -0.1493178 -0.039272852, -0.04055842 -0.14993328 -0.039272979, 0.050362363 -0.14424959 -0.047008224, -0.046367027 -0.14819017 -0.039433271, -0.045269199 -0.14959112 -0.035830431, -0.025082521 -0.14420375 0.061991856, -0.097428344 -0.1139628 0.054280639, -0.10142736 -0.11041877 0.054280829, -0.098913729 -0.11454633 0.050837833, -0.098012954 -0.11002189 0.059993837, -0.096836515 -0.11437917 0.054436527, -0.079169452 -0.13925537 0.014992207, -0.081670523 -0.13753343 0.016992204, -0.089837283 -0.12795204 0.035640161, -0.092106782 -0.12632814 0.035640284, -0.087828122 -0.12805396 0.039415792, -0.043048017 -0.15029433 -0.035653867, -0.03943865 -0.15128168 -0.035654031, -0.13172412 -0.068095535 -0.058003731, -0.13001096 -0.067227274 -0.062003888, -0.058545612 -0.14910328 -0.015008442, -0.056686722 -0.15003705 -0.013008371, -0.056535751 -0.14962843 -0.017008364, -0.096359491 -0.1127131 0.057993528, -0.094695173 -0.11411503 0.057993542, -0.089253724 -0.12712088 0.039259754, -0.092686273 -0.12464049 0.039259892, -0.088361204 -0.1263302 0.042992998, -0.078852832 -0.13869905 0.020021297, -0.074862219 -0.14076251 0.02079571, 0.03946773 -0.15313765 -0.028008617, 0.039252959 -0.15227726 -0.032008521, -0.078638569 -0.13803631 0.024238169, -0.080178276 -0.13783398 0.020622626, -0.043300577 -0.15117604 -0.032008506, -0.043426998 -0.15161726 -0.030008636, -0.027653456 -0.14879119 -0.050849974, -0.028725185 -0.14858833 -0.050850108, -0.027065046 -0.14739752 -0.054449148, -0.022893846 -0.14966768 -0.050674111, -0.095111638 -0.11125365 0.061993748, -0.097820699 -0.10683522 0.064935029, -0.093417063 -0.11268032 0.061993651, -0.08858718 -0.12617183 0.042992931, -0.020204224 -0.14761803 0.056435317, -0.091533527 -0.12157688 0.048656341, -0.093460143 -0.12176326 0.044993114, -0.043544807 -0.15202868 -0.028008468, -0.045011945 -0.15193313 -0.026416659, -0.041042291 -0.15382105 -0.022256672, -0.013518691 -0.15219435 0.046991415, -0.07851582 -0.1381062 0.024238147, -0.013593577 -0.15356556 0.042991348, -0.027918212 -0.15021595 -0.047008477, -0.031374566 -0.15025097 -0.04500851, -0.058798887 -0.14974901 -0.0057952628, -0.058425233 -0.14982247 -0.0072376281, -0.057130061 -0.15047249 -0.0036251023, -0.064166568 -0.14742172 -0.0077952594, -0.062115312 -0.1485194 -0.0020084158, -0.093918294 -0.10985789 0.065538779, -0.093158066 -0.10899669 0.067636535, -0.051384732 -0.15172017 -0.015008651, -0.052929245 -0.15140343 -0.013008468, -0.052793786 -0.15098935 -0.017008476, -0.087798268 -0.1250487 0.046992868, -0.087568671 -0.12520966 0.046993025, -0.15685117 -0.036250412 -0.0020021237, -0.043742947 -0.15272087 -0.024256587, -0.046572559 -0.15214267 -0.022809908, -0.058837682 -0.14984819 -0.0020084232, -0.055792771 -0.15102381 -8.5011125e-06, 0.00048780441 -0.15814427 0.027991116, -0.0033777356 -0.15722236 0.031991214, -0.0034261346 -0.15810785 0.027991146, -0.028168991 -0.15156579 -0.043008529, -0.030167438 -0.15169406 -0.041433692, -0.087006003 -0.12392044 0.050656851, -0.084339201 -0.12469268 0.052838136, -0.089553237 -0.12128699 0.052279409, -0.04393097 -0.15337732 -0.020037636, -0.042586595 -0.15396038 -0.018640675, -0.058837838 -0.14984831 0.0019915998, -0.057912245 -0.1500949 0.0057762191, -0.062115312 -0.14851967 0.0019916669, 0.06466347 -0.1257236 -0.071107671, -0.028381035 -0.1527071 -0.039273031, -0.0058703199 -0.14325467 -0.067653015, -0.011652783 -0.14168176 -0.069782205, -0.0053902939 -0.14248767 -0.069039628, -0.0098710656 -0.14451081 -0.064948976, 0.050841942 -0.1455363 -0.043008201, -0.0041009337 -0.14446816 -0.065550983, -0.086154595 -0.12270796 0.054280147, -0.082251027 -0.12423313 0.056436572, -0.065573886 -0.14615041 0.014991894, -0.066575691 -0.14569688 0.014991768, -0.058798954 -0.14974964 0.0057762191, -0.085209429 -0.1213623 0.057993192, -0.080109403 -0.12366867 0.059993025, 0.060986124 -0.13305122 -0.062007599, -0.076766089 -0.13502944 0.039259307, -0.073349968 -0.13617089 0.041415673, -0.077732839 -0.13513821 0.037258919, -0.0059925839 -0.14623925 -0.062008232, -0.0080343485 -0.14712256 -0.060008183, -0.044231661 -0.15442806 -0.010019511, -0.046518788 -0.15400672 -0.0057955384, -0.04202304 -0.15510008 -0.009237729, -0.084105976 -0.11979076 0.06199332, -0.080321074 -0.12054765 0.06493111, -0.076192826 -0.13402149 0.042992551, -0.074040428 -0.13445905 0.044992413, -0.006071128 -0.14815822 -0.058008395, -0.0095450282 -0.14868286 -0.056449927, 0.053853616 -0.1429829 -0.047008015, -0.058545612 -0.14910489 0.014991663, -0.04429806 -0.15466002 -0.0057955384, -0.040679798 -0.15565822 -0.0056254119, -0.083050638 -0.11828792 0.065538362, -0.08037135 -0.11727101 0.069764681, -0.085253447 -0.11671042 0.065538459, -0.075514466 -0.13282827 0.0469926, -0.076285094 -0.13079357 0.050656471, -0.070945293 -0.13368505 0.05083663, -0.0061359182 -0.14973605 -0.054449156, -0.0053079948 -0.15066603 -0.052297175, -0.044327296 -0.15476254 -0.0020086169, 0.043245547 -0.152114 -0.028008573, -0.15685099 -0.036250651 0.0019979663, 0.0076656044 -0.14116964 -0.071108401, 0.0052057058 -0.14328054 -0.067653172, 0.042998768 -0.15126222 -0.032008506, 0.010277852 -0.14178988 -0.069779225, 0.00050295144 -0.15725774 0.031991214, -0.081937626 -0.11670291 0.069027409, -0.074832819 -0.13162979 0.050656389, -0.074314646 -0.13022009 0.054279629, -0.029152483 -0.15685865 -0.0200378, -0.025760353 -0.15786505 -0.017008819, -0.032486126 -0.15685675 -0.015008785, -0.030084118 -0.15656567 -0.020810075, -0.0083695725 -0.15326846 0.044991352, -0.01140137 -0.15548277 0.037257686, -0.0070047081 -0.15451133 0.041414574, -0.044327304 -0.15476283 0.00199119, -0.04570803 -0.15432656 0.003609851, -0.041489452 -0.15533662 0.00777594, 0.0077738017 -0.14316389 -0.067652993, -0.018519677 -0.14618012 0.059991799, 0.012360372 -0.14432076 -0.064945966, -0.074100584 -0.13034189 0.054279648, -0.068957746 -0.13305962 0.054435458, -0.15589687 -0.040156215 -0.0020022057, -0.058062203 -0.14787441 0.024237655, -0.056169868 -0.14817378 0.026401706, 0.0044014826 -0.15808368 0.027991131, -0.051384643 -0.15172181 0.014991365, -0.04429809 -0.15466076 0.005776003, -0.047052979 -0.15377414 0.0072228387, -0.02926939 -0.15748876 -0.015008867, -0.011982493 -0.15094006 0.05065529, -0.025832564 -0.15829462 -0.0130089, -0.031129822 -0.15748316 -0.011405192, -0.057799034 -0.14720422 0.027991749, -0.054539494 -0.14798716 0.029991761, 0.0079357699 -0.14614663 -0.062008217, 0.014472067 -0.14662948 -0.060008213, -0.044231758 -0.15442905 0.010002278, -0.042814046 -0.15471721 0.011385806, 0.061724268 -0.13482553 -0.05800759, -0.029351979 -0.15793335 -0.010019794, -0.057474889 -0.14637914 0.031991795, -0.056176402 -0.14585066 0.035811469, -0.0063593462 -0.15519181 -0.039273076, -0.0061777085 -0.15519926 -0.03927324, -0.010846674 -0.15591386 -0.035830848, 0.0080398023 -0.14806437 -0.058008358, 0.054381117 -0.14425123 -0.043008156, 0.012344971 -0.14941722 -0.054297924, -0.05713959 -0.14552516 0.035639234, -0.027223639 -0.13997304 0.06902615, -0.0064009577 -0.15620673 -0.035654172, -0.0047861263 -0.1562646 -0.035654239, -0.021742634 -0.15870306 -0.015009023, -0.017871685 -0.15895149 -0.017008997, -0.017911606 -0.15938532 -0.013008907, -0.021878898 -0.15888923 -0.013008937, -0.021822728 -0.15845734 -0.017009005, 0.0081255063 -0.14964131 -0.054449134, 0.0064134225 -0.14972466 -0.054449327, 0.010984913 -0.1510095 -0.050674252, -0.06707117 -0.13225347 0.057992544, 0.021050267 -0.1398018 -0.071108252, 0.01398474 -0.15934247 0.016990975, 0.010014065 -0.15964103 0.016991086, 0.010039128 -0.1600754 0.012990996, 0.014026001 -0.1597755 0.012991004, -0.070473708 -0.12396339 0.069026887, -0.066827014 -0.12459651 0.071091592, -0.043930978 -0.15337944 0.020020589, -0.045951225 -0.15207431 0.024237357, -0.041662857 -0.15389192 0.020794772, 0.030886456 -0.15789342 -0.0056255534, 0.024909109 -0.15893897 -0.0057958141, 0.029434182 -0.1579735 -0.0092379972, -0.0064384937 -0.15712309 -0.032008834, -0.02006463 -0.14346012 0.064929843, -0.026173599 -0.14214286 0.065536879, -0.0085997432 -0.15747929 -0.030008845, 0.0082056373 -0.15111652 -0.050850116, 0.005059652 -0.15125465 -0.050850235, 0.027213812 -0.15868345 -9.0077519e-06, -0.066202439 -0.13054115 0.061992608, -0.0064748302 -0.15800923 -0.028008878, 0.060590446 -0.1380482 -0.052296311, -0.010074824 -0.15813997 -0.026416972, -0.15589695 -0.040156305 0.0019977242, -0.043743059 -0.15272409 0.024237357, -0.040104419 -0.15368953 0.024401285, 0.0082842857 -0.15256351 -0.047008581, 0.0028465614 -0.15346533 -0.045008637, -0.014166534 -0.15955782 -0.015009053, 0.0043834373 -0.15719751 0.031991154, -0.006504342 -0.15872872 -0.024257012, -0.0057846159 -0.15909716 -0.022256918, -0.04354468 -0.15203181 0.027991511, 0.0083586127 -0.15393451 -0.043008767, 0.0043446124 -0.15460378 -0.041433871, -0.029352106 -0.15793437 0.010002069, -0.025832511 -0.15829605 0.01299113, -0.032486148 -0.15685844 0.014991187, -0.030306384 -0.15780938 0.0092225969, -0.043300591 -0.1511797 0.03199143, -0.044590712 -0.15038574 0.033638701, 0.0084215328 -0.15509358 -0.039273053, 0.012069307 -0.15542871 -0.037272893, 0.0058472753 -0.15562975 -0.037831098, -0.054797284 -0.13956085 0.054279149, -0.052545078 -0.13942119 0.056435801, -0.029269494 -0.15749034 0.014991209, -0.030988514 -0.15670934 0.018621542, -0.025760293 -0.1578669 0.016991101, -0.043047912 -0.15029788 0.035638988, -0.045713335 -0.1490474 0.037258096, -0.021531977 -0.14052966 0.069763511, -0.040115356 -0.15048948 0.0378116, 0.0084765628 -0.15610769 -0.035654195, 0.013567597 -0.15626618 -0.0336539, 0.0083123371 -0.15792632 0.027991131, -0.054196209 -0.13803023 0.057992212, -0.050582662 -0.13839427 0.059992142, -0.042768307 -0.14932153 0.039258547, -0.04121045 -0.14907879 0.041414797, 0.028654285 -0.14352965 -0.062008083, 0.064930007 -0.13331127 -0.058007583, 0.064126447 -0.13156635 -0.062007412, -0.029152498 -0.15686104 0.020020314, 0.008526206 -0.15702361 -0.032008789, -0.14828423 -0.00066033006 0.058000017, -0.053494319 -0.13624293 0.061992265, -0.051483601 -0.13539857 0.064930245, -0.042448893 -0.14820677 0.042991601, 0.029030249 -0.1454131 -0.058008261, 0.0085743591 -0.15790915 -0.028008774, 0.015069962 -0.15699217 -0.030008875, 0.012843244 -0.158342 -0.024256989, 0.022749066 -0.15108532 -0.047008447, 0.025945157 -0.15128309 -0.045008488, -0.021742716 -0.1587047 0.01499112, -0.017871685 -0.15895325 0.016991109, -0.021822743 -0.15845919 0.016991124, -0.021878853 -0.15889075 0.012991086, -0.017911598 -0.15938672 0.012991115, -0.0065868124 -0.1607441 -0.0057958737, -0.0050226301 -0.16080767 -0.0056257844, -0.052823097 -0.13453361 0.065537408, 0.0086134076 -0.15862834 -0.024256989, 0.011435062 -0.1590448 -0.02064091, -0.14311635 -0.065170318 -0.032003619, 0.0069170967 -0.15868285 -0.024416864, -0.0065912232 -0.16085061 -0.0020090416, -0.0087788925 -0.16076049 -9.0152025e-06, 0.022953309 -0.15244284 -0.043008603, 0.022523083 -0.15363252 -0.039433405, -0.041691266 -0.14556193 0.050655536, -0.039419457 -0.14612016 0.050836168, -0.043475352 -0.14349189 0.054278903, 0.0086504295 -0.15930995 -0.020038009, 0.0055096 -0.1593346 -0.020810336, -0.0065911189 -0.1608507 0.0019910187, -0.010221153 -0.16062835 0.0036095008, 0.0231262 -0.15359077 -0.039273113, 0.041307732 -0.13729542 -0.067652754, 0.044165701 -0.13795191 -0.064945653, -0.041283287 -0.14413774 0.054278828, -0.037620813 -0.14506811 0.054434739, -0.014166646 -0.15955949 0.014991015, -0.0065868199 -0.16074485 0.0057757646, -0.0058837533 -0.16067415 0.0077757388, 0.0082613006 -0.1570414 0.031991221, 0.0086851195 -0.15994984 -0.015008949, 0.0046941191 -0.16046178 -0.011405334, 0.0032323748 -0.16015291 -0.015009046, -0.040830486 -0.14255702 0.057992093, -0.028380916 -0.1527108 0.039258294, -0.029428929 -0.15251246 0.039258316, 0.0421682 -0.14015588 -0.062007897, 0.046539411 -0.15251264 -0.020640582, 0.040827006 -0.1541138 -0.020809911, 0.042054087 -0.15316513 -0.024416506, 0.046738081 -0.13973266 -0.060007848, 0.068098694 -0.13172081 -0.058007419, 0.067230612 -0.13000751 -0.062007412, 0.0087096542 -0.16040143 -0.010019921, 0.0061518028 -0.16066325 -0.0077958554, 0.01236634 -0.16033506 -0.007238172, -0.040301628 -0.14071095 0.061992243, -0.041781053 -0.13869834 0.064933196, -0.028169006 -0.15157074 0.042991556, -0.031374536 -0.15025616 0.044991501, -0.14636365 -0.00069352984 0.061999995, 0.042721562 -0.14199525 -0.058008075, 0.045284525 -0.14292401 -0.054297507, 0.0087226555 -0.16064233 -0.0057958141, -0.14393526 -0.065511316 -0.028003782, 0.01381512 -0.16035879 -0.0036257133, -0.039795958 -0.13894561 0.065537147, -0.036642194 -0.13862282 0.067634791, 0.070296966 -0.12837553 -0.062007219, 0.066858932 -0.12683222 -0.067652196, 0.070782043 -0.12328848 -0.069778197, 0.016286023 -0.1593554 -0.015009008, -0.02791822 -0.15022132 0.046991631, 0.045286305 -0.15340841 -0.01700861, -0.029719755 -0.14925227 0.048654877, -0.14822623 -0.0042052269 0.057999678, 0.043176465 -0.14350748 -0.054448761, 0.044312857 -0.14477882 -0.05067388, 0.039570048 -0.14454347 -0.054448932, 0.0087284297 -0.16074866 -0.0020090863, 0.053417332 -0.13089818 -0.07110782, 0.056968257 -0.13071534 -0.069038853, -0.03926257 -0.13708383 0.069026344, -0.037427112 -0.13634306 0.071090981, 0.021897472 -0.15844893 0.016991079, 0.018004134 -0.15937623 0.012991093, 0.021971107 -0.15887803 0.01299113, 0.030786544 -0.15421206 -0.03200867, -0.15221041 -0.013307631 0.046999142, 0.017946668 -0.15894496 0.016991057, -0.027666308 -0.14886576 0.05065529, -0.15357701 -0.013437539 0.042999193, 0.043602072 -0.14492229 -0.050849862, 0.0087283924 -0.16074899 0.0019910187, 0.015259415 -0.1602754 -8.9854002e-06, 0.012946419 -0.16035804 0.0057757199, 0.05417192 -0.13274726 -0.067652561, 0.030960158 -0.15508169 -0.028008632, -0.0065043196 -0.15873179 0.02423697, -0.0048999265 -0.15876034 0.024400979, 0.030017056 -0.15795514 0.007775858, 0.024326615 -0.15896127 0.0072223842, 0.025778174 -0.15887544 0.0036096051, 0.0087227002 -0.16064316 0.0057757348, 0.011494972 -0.16027036 0.009385474, 0.0070247054 -0.16073322 0.0056094602, 0.023850106 -0.1584 -0.015008911, 0.027076326 -0.15788054 -0.015009031, -0.0064748526 -0.15801242 0.027991138, -0.008599788 -0.15748274 0.029991098, 0.0087096542 -0.16040248 0.010001928, 0.0055692345 -0.16059658 0.0092224255, 0.023917325 -0.15884718 -0.010019787, 0.02344802 -0.15896079 -0.0094050989, -0.006438449 -0.15712681 0.031991206, -0.010009162 -0.15653777 0.033638313, 0.0086851195 -0.15995154 0.014990993, 0.0046592057 -0.15967602 0.018621258, 0.0032324716 -0.16015452 0.014990978, 0.073756367 -0.12466523 -0.064944811, 0.045407437 -0.15382683 -0.013008669, 0.040282644 -0.15539417 -0.011404946, -0.0064009428 -0.15621001 0.035638541, -0.0056231469 -0.15564287 0.037811376, 0.041748568 -0.15526611 -0.0077956319, 0.045041874 -0.14970884 -0.035653882, 0.04635334 -0.14884612 -0.037272379, 0.048000373 -0.14932913 -0.033653557, 0.056622446 -0.13875338 -0.054448582, 0.055168539 -0.14005905 -0.052850477, 0.055912666 -0.13809979 -0.056449339, -0.1313642 -0.078026295 -0.047004409, 0.06561847 -0.12522763 -0.071107477, 0.071228534 -0.13005507 -0.058007352, -0.026054598 -0.14019525 0.069026053, 0.028554909 -0.15797174 0.011385635, 0.0086503476 -0.15931228 0.02002009, 0.0060740784 -0.15908927 0.022236772, 0.012281537 -0.15863869 0.022794776, 0.045306005 -0.15058723 -0.032008506, 0.049626596 -0.14970267 -0.030008413, -0.14630607 -0.0041666329 0.061999738, 0.057180554 -0.14012128 -0.05084946, 0.059804477 -0.13993245 -0.0486729, 0.045561552 -0.15143648 -0.028008521, 0.047756031 -0.15151417 -0.024256565, 0.0086133704 -0.15863144 0.024236985, 0.013682134 -0.1578714 0.026401073, 0.057727948 -0.14146295 -0.047007993, 0.058958814 -0.14171684 -0.045008019, 0.016286045 -0.15935707 0.014991097, 0.036250509 -0.15685132 0.0019912273, 0.032322317 -0.15770763 0.001991123, 0.032322332 -0.15770742 -0.0020089149, 0.03625048 -0.15685099 -0.0020088255, -0.14226976 -0.06905362 -0.028003864, 0.038799025 -0.15541565 -0.015008807, 0.038788937 -0.15541822 -0.015008792, -0.1414645 -0.068682134 -0.03200382, 0.045768946 -0.15212604 -0.024256565, 0.0085743591 -0.15791231 0.027991168, 0.031516604 -0.15787035 -0.0020088106, 0.05824665 -0.14273417 -0.043008037, 0.056145206 -0.14476871 -0.039432816, 0.06177339 -0.14250979 -0.03927248, -0.0061992407 -0.15128797 0.050655298, -0.010456212 -0.1495685 0.054278709, -0.0059169903 -0.15122834 0.050835796, 0.0085262582 -0.15702724 0.031991236, -0.15184201 -0.017003298 0.046998989, 0.015069954 -0.15699559 0.029991172, 0.012668118 -0.15578109 0.035811022, -0.15320309 -0.017184228 0.042999029, 0.031516612 -0.15787065 0.0019912496, 0.058685087 -0.14380896 -0.039272465, 0.05787693 -0.14517951 -0.035830185, -0.0061385706 -0.14980769 0.054278508, -0.0043975711 -0.14980257 0.054434478, 0.023850068 -0.15840173 0.014991112, 0.027076289 -0.15788227 0.014991112, 0.0084765255 -0.1561113 0.035638638, 0.011172183 -0.15487707 0.039414234, 0.0067511797 -0.15619543 0.035638638, 0.059068829 -0.14474958 -0.035653584, 0.060580157 -0.14561495 -0.03000813, 0.063489333 -0.1428659 -0.035653502, 0.046150051 -0.15339342 -0.015008643, 0.04922758 -0.1526472 -0.01300855, 0.049090855 -0.15223357 -0.017008469, -0.0060711801 -0.14816481 0.057991706, -0.0080343112 -0.14712945 0.059991769, -0.0028884038 -0.14826095 0.057991572, 0.0084214956 -0.15509722 0.039258108, 0.0096804872 -0.15386185 0.042991348, 0.0052456185 -0.15523723 0.0392581, 0.074023388 -0.1262635 -0.06200704, 0.076660417 -0.12582898 -0.060007006, 0.023754716 -0.15776855 0.02002015, 0.029233657 -0.15672874 0.020794697, 0.024581254 -0.15695179 0.024237171, -0.13253886 -0.078736901 -0.043004476, 0.023251496 -0.1577535 0.020621456, 0.07024134 -0.13405162 -0.050849169, 0.075418875 -0.13128844 -0.05067315, 0.07481306 -0.13321924 -0.047007419, 0.070186771 -0.1340802 -0.050849281, 0.070742503 -0.1321142 -0.054448292, -0.0059926063 -0.14624622 0.061991699, -0.0027836636 -0.14634246 0.061991662, -0.009871088 -0.14451814 0.064932913, 0.0083585829 -0.15393931 0.04299137, 0.0028465092 -0.15347046 0.044991404, 0.074994639 -0.1279206 -0.058007203, 0.075953484 -0.12926376 -0.054296792, -0.12942886 -0.08119607 -0.047004513, 0.070913814 -0.13533515 -0.047007613, 0.075478874 -0.13441995 -0.043007582, 0.069151901 -0.13703227 -0.045007668, 0.046349756 -0.15405774 -0.0057955086, 0.047734298 -0.15356329 -0.0072376877, 0.049151987 -0.15326414 -0.0036251992, 0.044036657 -0.15484554 -0.002008602, -0.0059174821 -0.14441136 0.065536834, -0.0048778728 -0.14330095 0.06763462, 0.079229206 -0.11803597 -0.069780797, 0.05339665 -0.15102392 -0.015008509, 0.056606457 -0.14960173 -0.017008469, 0.056773826 -0.15000412 -0.013008416, 0.053017192 -0.15137273 -0.01300855, 0.052865043 -0.15096447 -0.017008483, 0.0082841888 -0.15256888 0.046991408, 0.0042365342 -0.15212339 0.048654601, 0.009601377 -0.15249169 0.046991445, 0.075793177 -0.12928292 -0.054448076, 0.060022332 -0.14708668 -0.024256289, 0.058448225 -0.14798716 -0.022809699, 0.059537999 -0.14685038 -0.026416346, 0.063818499 -0.14585143 -0.02225624, -0.14051732 -0.072553277 -0.028003998, 0.046380453 -0.15415967 -0.0020087063, 0.050541431 -0.15286145 -8.6724758e-06, -0.13972652 -0.072152257 -0.032004058, 0.040156133 -0.15589708 0.0019912571, 0.071550921 -0.13655123 -0.043007761, 0.072794318 -0.13768035 -0.037830204, 0.070995398 -0.13740796 -0.041432805, -0.005838044 -0.14247632 0.069025815, -0.0061505064 -0.14125299 0.071090639, -0.011652835 -0.1416896 0.069766365, 0.040156156 -0.1558969 -0.0020089, 0.0082093626 -0.15119219 0.05065529, 0.011803694 -0.15007395 0.052836634, 0.0056038052 -0.15066218 0.052277744, 0.060280181 -0.14771885 -0.020037353, 0.062697731 -0.14692307 -0.018640175, 0.061529331 -0.14789709 -0.01500833, 0.046380423 -0.15415987 0.0019913763, 0.048304826 -0.15345681 0.0057761073, 0.044036597 -0.1548456 0.0019913912, 0.083942093 -0.11623377 -0.067651585, 0.082385883 -0.1191369 -0.064947598, 0.08462771 -0.11476141 -0.069038056, 0.086870365 -0.11550578 -0.065549284, 0.0081290901 -0.14971283 0.054278597, 0.013149716 -0.14841297 0.05643522, 0.0077444687 -0.14808667 0.057991706, 0.038799092 -0.15541741 0.014991336, 0.04007341 -0.1546357 0.018621519, 0.038788959 -0.15541992 0.014991298, 0.04116556 -0.15533075 0.0092227012, 0.045407392 -0.15382823 0.012991458, 0.046349756 -0.15405837 0.0057761371, 0.04687012 -0.15369409 0.0093859136, 0.042614952 -0.15514022 0.0056098402, 0.060522228 -0.14831206 -0.01500839, 0.030960068 -0.15508479 0.027991243, 0.02665861 -0.15544781 0.029991247, 0.030550048 -0.15587032 0.024400994, 0.031841621 -0.15490615 0.027991407, 0.008039847 -0.1480709 0.057991706, 0.085690729 -0.11865541 -0.062006645, 0.089064509 -0.11614436 -0.062006555, 0.09017884 -0.11771002 -0.058006674, 0.08545012 -0.1200338 -0.060006775, 0.060693011 -0.14873093 -0.010019198, 0.059651904 -0.14941135 -0.0057952255, 0.058232419 -0.14975774 -0.0094047636, 0.063848644 -0.14746305 -0.0092374235, -0.15406898 -0.0356673 0.027998053, 0.030786514 -0.15421563 0.031991437, 0.029151306 -0.15299198 0.037811451, 0.025074214 -0.15484035 0.033638425, 0.031691745 -0.15403199 0.031991445, 0.007935755 -0.14615351 0.061991885, 0.0076338202 -0.14616966 0.061991908, 0.014472097 -0.14663619 0.059991814, 0.012360379 -0.14432812 0.064929835, 0.0006569922 -0.14828762 0.057991683, 0.022953384 -0.15244767 0.042991325, 0.027552433 -0.15219608 0.041414805, 0.025945112 -0.15128827 0.044991389, 0.02348192 -0.15412143 0.037257873, 0.02091831 -0.1527403 0.042991363, 0.086815007 -0.12021255 -0.058006704, 0.085241519 -0.12219539 -0.056448281, 0.046150059 -0.15339503 0.014991432, 0.0490909 -0.15223542 0.016991451, 0.045286328 -0.15341029 0.016991347, 0.04922758 -0.15264863 0.012991533, -0.13057627 -0.081950158 -0.043004639, 0.060784012 -0.14895427 -0.0057952106, 0.061841898 -0.14864928 -8.3893538e-06, 0.065246738 -0.14706188 -0.0056249201, 0.0078361258 -0.14431989 0.065536834, 0.010277785 -0.14179769 0.0697634, 0.0061115623 -0.1444034 0.065536916, 0.022749037 -0.15109062 0.046991631, 0.020686127 -0.15138683 0.046991542, 0.02190455 -0.14982206 0.050655432, 0.087739326 -0.12149274 -0.054447591, 0.089790538 -0.1211043 -0.052295461, 0.084952079 -0.12427136 -0.052849576, 0.093293257 -0.10622752 -0.071106479, 0.091019168 -0.10818237 -0.071106508, 0.093406342 -0.10877472 -0.067651108, 0.096442558 -0.10444692 -0.069777027, 0.0077311695 -0.14238602 0.069025949, 0.0046050102 -0.14252153 0.069026046, 0.079531685 -0.13566095 -0.032007605, 0.075580172 -0.13790157 -0.032007799, 0.078312866 -0.1347996 -0.037271664, 0.076010227 -0.13867718 -0.028007805, 0.080026135 -0.13490412 -0.033652693, 0.081694633 -0.13490632 -0.030007541, 0.022543669 -0.14972726 0.050655298, 0.023087434 -0.14814529 0.054278702, 0.065172054 -0.1431146 -0.032008052, 0.027882114 -0.14875335 0.050835945, 0.088604309 -0.12269062 -0.050848499, 0.089443587 -0.12311628 -0.048671871, 0.08901602 -0.12504396 -0.045006931, -0.127417 -0.084318012 -0.047004782, 0.094611131 -0.1077283 -0.067651123, 0.097101398 -0.10951418 -0.06200622, 0.099648558 -0.10512722 -0.064943686, 0.079980068 -0.13642615 -0.028007686, 0.080273993 -0.13708854 -0.024255678, 0.045768984 -0.15212926 0.024237327, 0.047273755 -0.1519284 0.022795178, 0.048468426 -0.15086862 0.026401587, 0.041322142 -0.15374911 0.022237137, 0.043245576 -0.15211719 0.027991399, 0.05339656 -0.15102556 0.014991596, 0.056606442 -0.14960375 0.016991615, 0.052865043 -0.15096635 0.016991451, 0.053017147 -0.15137413 0.012991488, 0.056773782 -0.15000555 0.012991622, 0.060784079 -0.14895493 0.0057763308, 0.059088789 -0.14956263 0.0072229654, 0.060484871 -0.14915591 0.0036101341, 0.064412661 -0.14731538 0.0077765286, 0.074346088 -0.14188746 -0.015008032, 0.074097171 -0.14116487 -0.020809278, 0.078287601 -0.13948482 -0.017007932, 0.073851228 -0.14253435 -0.011404365, 0.072400361 -0.14289016 -0.015007958, 0.078498855 -0.13986593 -0.013007835, 0.045561552 -0.15143973 0.027991541, 0.049626648 -0.14970613 0.029991589, 0.060692936 -0.14873189 0.010002553, 0.062990852 -0.14765713 0.011386365, 0.061529413 -0.14789867 0.014991626, 0.045306027 -0.15059087 0.031991549, 0.047014713 -0.14905658 0.035811342, -0.15320125 -0.03548494 0.031998023, 0.042998783 -0.15126565 0.031991467, 0.090935744 -0.12591964 -0.039271519, 0.091936566 -0.12519088 -0.039271474, 0.086951993 -0.12864554 -0.039432123, 0.088731758 -0.1286608 -0.035829231, 0.060522191 -0.14831373 0.014991567, 0.04504174 -0.14971238 0.035638876, 0.045355082 -0.14850813 0.039414585, 0.041338176 -0.15077713 0.035638958, 0.091530249 -0.12674314 -0.035652593, 0.093688682 -0.12515613 -0.035652563, 0.081013285 -0.13818923 -0.015007764, 0.081735522 -0.13749307 -0.017007813, 0.0819607 -0.13786575 -0.01300773, -0.15313925 -0.039469302 0.027997874, 0.098891102 -0.11260253 -0.054447144, 0.09836781 -0.11306024 -0.054447234, 0.098383367 -0.11094448 -0.058006346, 0.10281368 -0.1091215 -0.054295689, 0.10274295 -0.11121434 -0.050671995, 0.029030293 -0.14541963 0.057991967, 0.024905719 -0.14522862 0.059991948, 0.029046178 -0.14702529 0.054434747, 0.030174449 -0.14518654 0.057991944, 0.044749133 -0.14873999 0.039258473, 0.04367467 -0.14785016 0.042991608, 0.039657101 -0.15017802 0.039258368, 0.00068990141 -0.14636734 0.061991766, 0.10296877 -0.09687838 -0.071105987, 0.10804357 -0.093052506 -0.069036797, 0.10350897 -0.097446233 -0.069779724, 0.060280122 -0.14772102 0.020020649, 0.057771727 -0.14862442 0.020622104, 0.063375793 -0.14629406 0.020795256, 0.058889732 -0.14754695 0.024237692, 0.09206716 -0.12748671 -0.032007143, 0.095384464 -0.12502411 -0.032007009, 0.095898919 -0.12574705 -0.02800715, 0.091464251 -0.12848386 -0.030007213, 0.099865869 -0.11371267 -0.050848082, 0.098263249 -0.11510047 -0.05084835, 0.065512866 -0.14393395 -0.028008103, 0.10258192 -0.11323163 -0.047006324, 0.028654277 -0.14353672 0.06199199, 0.029849693 -0.14329284 0.061991848, 0.027131066 -0.14079362 0.067634746, 0.022533931 -0.14309147 0.064932987, 0.0042019561 -0.14822948 0.057991751, 0.092586234 -0.12820587 -0.028007135, -0.128536 -0.085114688 -0.043004788, 0.09072274 -0.12992004 -0.026415318, 0.060022421 -0.14708963 0.024237677, 0.064468093 -0.14516428 0.024401695, 0.060580269 -0.1456185 0.02999182, 0.10082193 -0.11480159 -0.047006413, 0.097911187 -0.11820877 -0.045006633, 0.10349829 -0.11425406 -0.043006524, 0.087496877 -0.13417807 -0.01500757, 0.088476986 -0.13325477 -0.017007425, 0.088729531 -0.13360989 -0.013007417, 0.085371614 -0.13577998 -0.013007715, 0.085132517 -0.13541588 -0.017007649, 0.093007617 -0.12878963 -0.024255171, 0.089913443 -0.13127095 -0.022808701, 0.094673768 -0.12799373 -0.022255123, 0.081417546 -0.1388796 -0.0020078123, 0.077388912 -0.14116415 -0.0020080209, 0.080708697 -0.13909119 -0.0072368532, 0.082024105 -0.13848421 -0.0036244094, 0.083289042 -0.13778234 -7.6591969e-06, 0.077388927 -0.14116433 0.0019920319, 0.013304889 -0.15221325 0.04699146, 0.013435163 -0.15357953 0.042991363, 0.10172763 -0.1158331 -0.043006539, 0.099792011 -0.1181649 -0.04143174, 0.093407258 -0.12934327 -0.020036265, 0.092896968 -0.13049743 -0.015007302, 0.093819387 -0.1292879 -0.018639371, 0.081417486 -0.13887972 0.0019923002, 0.0812409 -0.13886046 0.0057769716, 0.10249356 -0.11670548 -0.039270937, 0.10160641 -0.11803016 -0.037829027, 0.10634566 -0.11399359 -0.037270606, 0.043195322 -0.14357632 0.054278903, 0.038988128 -0.14563796 0.052278131, 0.043292634 -0.14653182 0.04699181, 0.040501915 -0.14265072 0.057991982, 0.044901744 -0.1436848 0.052837051, 0.045844249 -0.14176592 0.056435637, 0.074346177 -0.14188924 0.014991954, 0.078287542 -0.13948673 0.016992152, 0.073478095 -0.1418415 0.018622383, 0.078498803 -0.13986731 0.012992233, 0.072400294 -0.14289182 0.014991984, 0.074697763 -0.14227626 0.009223491, 0.05906862 -0.14475292 0.035639249, 0.062463813 -0.14266932 0.037812062, 0.057188071 -0.14503217 0.037258461, 0.058900356 -0.14537868 0.033638924, 0.10316373 -0.11746883 -0.035651997, 0.10437162 -0.11762598 -0.032006577, 0.042721525 -0.14200172 0.057992063, 0.04673811 -0.13973948 0.059992135, 0.058684893 -0.14381281 0.039258786, 0.060727902 -0.14224935 0.041415282, 0.054381162 -0.14425614 0.042991899, 0.11125006 -0.0951083 -0.062005445, 0.11267681 -0.093413562 -0.062005356, 0.11411157 -0.094692051 -0.058005318, 0.10683145 -0.097817123 -0.064946368, 0.11039565 -0.093279302 -0.065548182, -0.1522789 -0.039254725 0.031997744, 0.11001844 -0.098009765 -0.06000562, 0.094046816 -0.13022935 -0.010018289, 0.09009669 -0.13304496 -0.0094037354, 0.091403469 -0.13239139 -0.0057942569, 0.09506157 -0.12955806 -0.0092364103, 0.042168245 -0.14016289 0.061992094, 0.039967537 -0.14080632 0.061992086, 0.044165745 -0.13795921 0.064930134, 0.05824668 -0.14273906 0.042991936, 0.058958836 -0.14172187 0.044992059, 0.11270968 -0.096356332 -0.058005512, 0.11029609 -0.1001637 -0.056447163, 0.11127818 -0.104698 -0.047005832, 0.11158508 -0.10637057 -0.043006063, 0.11055942 -0.10545665 -0.047005877, 0.11459753 -0.10012642 -0.048670664, 0.11460978 -0.10210097 -0.045005754, 0.11047567 -0.10225177 -0.052848279, 0.081013277 -0.13819081 0.014992148, 0.081960738 -0.13786724 0.012992352, 0.081735454 -0.13749489 0.016992256, 0.094187945 -0.13042504 -0.0057942867, 0.078028902 -0.13136151 -0.047007397, 0.096335292 -0.12885603 -0.0056238472, 0.041639179 -0.13840452 0.065537237, 0.038090266 -0.13942295 0.065537177, 0.057728022 -0.14146832 0.046992138, 0.060283221 -0.13881972 0.050836399, 0.053853497 -0.1429882 0.046992026, 0.054693334 -0.14119166 0.050655782, 0.1139099 -0.097382694 -0.054446295, 0.11448828 -0.098087698 -0.05229421, 0.10482882 -0.11936545 -0.024254769, 0.10876676 -0.11578891 -0.024254501, 0.10810383 -0.11721644 -0.020638764, 0.1049633 -0.11828625 -0.028006569, 0.10434593 -0.11975023 -0.024414703, -0.11552363 -0.092964232 -0.058005325, 0.094250239 -0.13051155 -0.0020072609, 0.093368977 -0.13116133 -7.3313713e-06, 0.09754809 -0.12806523 -0.0020071566, -0.11400155 -0.091792256 -0.062005222, 0.112278 -0.10563886 -0.043005899, 0.11339876 -0.10607135 -0.039430812, 0.004163079 -0.14630973 0.061991856, 0.11570834 -0.08123821 -0.071104959, 0.11726697 -0.080367565 -0.06977576, 0.11281083 -0.085216224 -0.071105421, 0.11526988 -0.085262567 -0.067649826, 0.041081123 -0.1365498 0.069026276, 0.036202684 -0.13792357 0.069026299, 0.04157228 -0.1359556 0.069763638, 0.057206996 -0.14019188 0.050655954, 0.05547332 -0.13929361 0.054279126, 0.069055058 -0.14226842 -0.028007939, 0.10527916 -0.11987856 -0.020035669, 0.10736325 -0.11856708 -0.01700668, 0.10365169 -0.12113741 -0.020808175, 0.094250225 -0.1305117 0.0019926727, 0.097548142 -0.12806553 0.0019928962, 0.068683922 -0.14146268 -0.032007888, 0.092158712 -0.13195717 0.0036111474, 0.11734292 -0.082385987 -0.067649588, 0.12054402 -0.080317527 -0.064942405, 0.11903687 -0.085161239 -0.06200476, 0.056647241 -0.13882023 0.054279156, 0.061033443 -0.13687581 0.054435186, 0.056596853 -0.13604537 0.05999241, 0.087496869 -0.13417962 0.014992431, 0.08872956 -0.13361123 0.012992531, 0.088476971 -0.1332567 0.01699248, 0.085132629 -0.1354177 0.016992405, 0.085371651 -0.13578144 0.012992308, 0.09418796 -0.13042587 0.0057774037, 0.09088809 -0.13266426 0.0072239339, 0.095578365 -0.12928876 0.0077774227, 0.10570192 -0.1203602 -0.015006796, 0.10765395 -0.11889145 -0.013006628, 0.017000489 -0.15184483 0.046991415, 0.10371653 -0.12252718 -0.011403158, 0.10238139 -0.12319708 -0.015006959, 0.017181836 -0.15320557 0.042991355, 0.079980038 -0.13642934 0.027992427, 0.076010227 -0.1386804 0.027992189, 0.079895444 -0.13759989 0.022795945, 0.080824316 -0.13630083 0.026402473, 0.081694715 -0.13490975 0.029992431, 0.072089225 -0.1375832 0.039259106, 0.072080001 -0.13758802 0.039259106, 0.073852263 -0.13779831 0.035639718, 0.077263579 -0.13469225 0.039415419, 0.075478777 -0.13442478 0.042992502, 0.1197872 -0.084102541 -0.062004715, 0.12366524 -0.08010602 -0.060004368, -0.14656101 -0.066605061 -0.0020037964, 0.12060478 -0.086270273 -0.058004901, 0.094046786 -0.13023049 0.010003746, 0.092896961 -0.13049912 0.014992625, 0.094268136 -0.12993824 0.011387214, 0.10600012 -0.12069994 -0.010017544, 0.10963594 -0.11764458 -0.0072358251, -0.13996825 -0.07508117 -0.024412088, 0.10498179 -0.12177587 -0.0077936947, 0.07953161 -0.13566464 0.031992435, 0.079003684 -0.13485774 0.035812274, 0.075580142 -0.13790512 0.031992361, 0.071550868 -0.13655609 0.042992517, 0.069151938 -0.13703734 0.044992402, 0.12135886 -0.08520633 -0.058004782, 0.12451842 -0.083507359 -0.054294214, 0.10615914 -0.12088138 -0.0057936013, 0.10686058 -0.12040421 -0.0020066649, 0.054606371 -0.13381967 0.065537512, 0.053808913 -0.13448966 0.064933509, 0.057779461 -0.13122645 0.067635223, 0.11883146 -0.10159135 -0.035651103, 0.11776163 -0.10490972 -0.030005947, 0.11513723 -0.10569024 -0.035828009, 0.11748966 -0.10159436 -0.039270192, 0.11918994 -0.10117051 -0.035651043, 0.0787393 -0.13253659 -0.043007568, 0.11130926 -0.11519435 -0.015006602, 0.11313114 -0.11307684 -0.017006338, 0.11344524 -0.11337876 -0.013006449, 0.11058391 -0.1161713 -0.013006523, 0.11028141 -0.11585793 -0.017006621, 0.070913769 -0.13534033 0.046992347, 0.070417471 -0.13331088 0.052278861, 0.069819584 -0.13522056 0.048655622, -0.13833383 -0.079308927 -0.020636469, 0.074813001 -0.13322464 0.046992585, 0.12265117 -0.08611384 -0.054445699, 0.12491512 -0.08556354 -0.05067046, -0.11326794 -0.095699549 -0.05800546, 0.12106033 -0.088336527 -0.054445818, -0.11179109 -0.094471693 -0.062005393, 0.12290712 -0.069871724 -0.071104527, 0.12604173 -0.066677511 -0.069035366, 0.12259851 -0.071970046 -0.069778278, 0.053874575 -0.13202655 0.069026574, 0.050976455 -0.13271433 0.069766738, 0.055744246 -0.1299336 0.071091235, 0.081198812 -0.12942621 -0.047007263, 0.093407303 -0.12934545 0.020021752, 0.089395106 -0.13204277 0.020623013, 0.090245292 -0.13074341 0.024238542, 0.094340019 -0.12852371 0.020796344, 0.11952852 -0.10218745 -0.032005772, 0.12081389 -0.10066453 -0.032005638, 0.12147617 -0.10125479 -0.02800563, 0.12386028 -0.086962998 -0.050846517, 0.12520696 -0.087566048 -0.047004879, 0.12141246 -0.090349019 -0.050846875, 0.12464324 -0.070858836 -0.067648932, 0.12592018 -0.071592301 -0.064944819, 0.12020233 -0.10276371 -0.028005764, 0.11735835 -0.10647485 -0.026413947, 0.093007863 -0.12879261 0.024238646, 0.095153511 -0.12717927 0.024402782, 0.12504593 -0.087795675 -0.047004849, 0.1263278 -0.088358968 -0.04300496, 0.1235847 -0.092996329 -0.041430235, 0.12176079 -0.093457639 -0.045005292, -0.14656106 -0.06660527 0.0019963011, 0.072554819 -0.14051574 -0.028007925, 0.1061592 -0.12088209 0.0057779402, 0.10686058 -0.12040433 0.0019932091, 0.11010326 -0.11730108 0.0057781637, 0.10891376 -0.11813763 0.0093879253, 0.072154105 -0.13972467 -0.032007843, 0.10570743 -0.1212866 0.0056117475, 0.11666428 -0.10976738 -0.015006244, 0.11744318 -0.10966089 -0.0094024837, 0.11623601 -0.11051574 -0.013006106, 0.11591076 -0.11022571 -0.017006233, 0.11960652 -0.10655406 -0.015005991, 0.12074953 -0.10323185 -0.024253756, 0.12078154 -0.10371771 -0.022253841, 0.092586249 -0.12820902 0.02799277, 0.091464147 -0.12848714 0.029992804, 0.095898934 -0.1257503 0.027992949, 0.1261694 -0.08858484 -0.04300493, 0.10600012 -0.12070107 0.010004133, 0.10765392 -0.11889297 0.01299338, 0.10448411 -0.12208721 0.0092245936, 0.092067152 -0.12749046 0.031992868, 0.089773022 -0.1286273 0.033639848, 0.095384441 -0.12502769 0.031993002, 0.1271193 -0.089251995 -0.039269507, 0.12904578 -0.087471306 -0.037268996, 0.12532356 -0.092461169 -0.037827685, 0.10570196 -0.12036189 0.01499325, 0.10736328 -0.11856902 0.016993359, 0.10319836 -0.12193489 0.018623307, 0.10238139 -0.12319875 0.014993042, 0.091529846 -0.12674662 0.03564021, 0.088026501 -0.12867048 0.03725931, 0.092644155 -0.12519294 0.037813038, 0.12795037 -0.089835793 -0.035650596, 0.13063452 -0.086822033 -0.033650085, 0.1279293 -0.091451794 -0.032005146, 0.074994668 -0.12792704 0.057992786, 0.071228541 -0.13006169 0.057992749, 0.075748123 -0.13009077 0.052837715, 0.07624004 -0.1280103 0.056436516, 0.076660477 -0.12583581 0.059992813, 0.0909352 -0.12592342 0.039259762, 0.090858363 -0.12516969 0.041416183, 0.13053747 -0.066199005 -0.062003821, 0.13063908 -0.065998644 -0.062003702, 0.13232225 -0.066925734 -0.058003888, 0.12838525 -0.066375077 -0.065546587, 0.12907 -0.071070939 -0.060003921, 0.12899268 -0.057872176 -0.071103677, 0.13135338 -0.057474703 -0.067648247, 0.12894574 -0.057976782 -0.071103781, 0.066180252 -0.12630767 0.069026805, 0.065985039 -0.12640989 0.069026925, 0.070782013 -0.12329635 0.069764197, 0.068158939 -0.12745166 0.06553787, 0.10527919 -0.11988094 0.020022333, 0.035665624 -0.15407076 0.027991377, 0.10851084 -0.1163716 0.022797182, 0.10393857 -0.12059438 0.022238925, 0.12870097 -0.090362966 -0.032005027, 0.13213879 -0.08610028 -0.030004904, -0.14208366 -0.07525149 -0.0077911653, 0.12865323 -0.091964036 -0.028005168, 0.13156596 -0.074795485 -0.050845802, 0.13344507 -0.070152283 -0.052292645, 0.13400522 -0.07211557 -0.048669174, 0.13125436 -0.078210801 -0.047004387, 0.13045979 -0.075104952 -0.052846745, 0.12981993 -0.07310915 -0.056445673, 0.074023418 -0.12627047 0.061992966, 0.070296854 -0.12838244 0.061992794, 0.073756389 -0.12467253 0.064930871, 0.13225034 -0.067067862 -0.058003739, 0.12942648 -0.090872467 -0.028005034, 0.13180552 -0.08868295 -0.024253085, 0.081952602 -0.13057396 -0.043007329, 0.1048291 -0.11936852 0.024239153, 0.10496334 -0.11828947 0.027993396, 0.13282557 -0.075511932 -0.047004178, 0.13445637 -0.07403785 -0.045004129, 0.13245755 -0.078873634 -0.043004379, 0.11130925 -0.11519602 0.014993504, 0.11313114 -0.11307874 0.016993612, 0.11028145 -0.11585993 0.016993463, 0.11344519 -0.11338016 0.012993619, 0.11058392 -0.11617258 0.012993544, 0.12228186 -0.10454285 -0.005792737, 0.12021412 -0.1070962 -6.0349703e-06, 0.11857173 -0.10873294 -0.0057929903, 0.12150764 -0.10515663 -0.0092350096, 0.12259316 -0.10418871 -0.0056226552, 0.1300157 -0.091286421 -0.024253234, 0.13147672 -0.090222061 -0.02063714, 0.12837687 -0.093528628 -0.024413258, 0.12236276 -0.10461211 -0.00200589, 0.12359964 -0.10314795 -0.0020057857, 0.13401879 -0.076190382 -0.043004304, 0.13715123 -0.072903156 -0.039268598, -0.14485201 -0.070244491 0.0019959845, -0.14485201 -0.070244253 -0.0020040013, 0.13415918 -0.078178346 -0.039429232, 0.08864525 -0.12275302 0.05065684, 0.08901608 -0.12504905 0.044993013, 0.089661375 -0.12192509 0.050837472, 0.085077576 -0.12345734 0.054280043, 0.084739454 -0.12548134 0.05065681, 0.13057429 -0.091678917 -0.020034313, 0.13105536 -0.091703743 -0.017005131, 0.12800878 -0.095035493 -0.020806685, 0.12236276 -0.10461244 0.0019940734, 0.11921121 -0.10814151 0.0036124587, 0.084320568 -0.12741438 -0.047007158, 0.1235996 -0.10314822 0.0019943118, 0.13502783 -0.076764375 -0.039268792, 0.13576919 -0.077419817 -0.0358264, 0.087777883 -0.12155217 0.054280102, 0.089960232 -0.11986285 0.054436162, 0.11666433 -0.1097692 0.014993861, 0.11623608 -0.11051717 0.012993902, 0.11960654 -0.10655576 0.014993995, 0.11653575 -0.10883984 0.020624176, 0.11591082 -0.11022773 0.016993821, 0.10316329 -0.11747238 0.035640806, 0.10703107 -0.11389667 0.035813391, 0.10529775 -0.11412257 0.039416581, 0.10266324 -0.1179097 0.035640821, 0.10437155 -0.11762947 0.031993464, 0.12228194 -0.10454366 0.0057787448, 0.12195142 -0.10477906 0.0077788532, 0.13109851 -0.092047185 -0.015005246, 0.13366203 -0.08865124 -0.013004944, 0.13141079 -0.091955394 -0.013005152, 0.12838127 -0.096376091 -0.011401698, 0.1272285 -0.097326189 -0.015005365, 0.13329741 -0.088413149 -0.017005041, 0.08681497 -0.12021905 0.057993203, 0.090178885 -0.11771667 0.057993397, 0.085450105 -0.12004054 0.059993267, 0.10249303 -0.11670938 0.039260298, 0.10349831 -0.11425906 0.042993635, 0.035483152 -0.15320313 0.031991452, 0.10088865 -0.11809933 0.039260104, 0.13623936 -0.053490967 -0.062003076, 0.13500331 -0.056537837 -0.06200321, 0.13539481 -0.051479995 -0.064940766, 0.13677868 -0.057270199 -0.058003291, 0.13839075 -0.050579399 -0.060002878, 0.13146836 -0.09230718 -0.010016158, 0.13306561 -0.090298682 -0.0072342604, 0.12944752 -0.095362097 -0.0077922046, 0.085690677 -0.11866245 0.061993331, 0.089064524 -0.11615139 0.061993465, 0.082385838 -0.11914414 0.064934239, 0.10172761 -0.11583805 0.042993531, 0.097911172 -0.11821386 0.044993326, 0.13802697 -0.05419296 -0.058003083, 0.13997932 -0.053705603 -0.05429247, 0.13166556 -0.09244591 -0.0057920516, 0.13398728 -0.089180887 -0.0036215931, 0.13097386 -0.093606651 -0.002005294, 0.039467655 -0.1531409 0.027991511, 0.084615454 -0.11717364 0.065538332, 0.085530646 -0.11507946 0.067636102, 0.13532972 -0.085705012 -0.015004784, 0.13583016 -0.085292131 -0.013004839, 0.13545693 -0.085067749 -0.017004758, 0.10082188 -0.11480689 0.046993673, 0.098157957 -0.11629415 0.048656613, 0.10258196 -0.11323711 0.046993703, 0.13949665 -0.054770321 -0.054443806, 0.13768238 -0.059183121 -0.05444409, 0.14082351 -0.055621833 -0.050668791, 0.1317527 -0.092507273 -0.0020051301, 0.13482237 -0.087999851 -4.9471855e-06, 0.083481453 -0.11560357 0.069027498, 0.083258688 -0.11427173 0.071092241, 0.079229116 -0.11804369 0.069767699, 0.09991201 -0.11377093 0.050657347, 0.10279622 -0.10997373 0.052838877, 0.098315775 -0.11429924 0.05227986, 0.13869767 -0.078851819 -0.020033419, 0.13796601 -0.079258889 -0.02280584, 0.14083287 -0.074240804 -0.022252157, 0.13753247 -0.081669539 -0.017004564, 0.1406246 -0.07577759 -0.018636316, 0.14031833 -0.077267587 -0.015004307, 0.13175267 -0.092507511 0.0019948035, 0.13344462 -0.089859813 0.0057796687, 0.13097388 -0.093606949 0.001994729, 0.098934315 -0.1126579 0.054280698, 0.085117146 -0.12853354 -0.043007195, 0.098383345 -0.11095098 0.05799374, 0.12074983 -0.10323495 0.024240106, 0.11776162 -0.10491312 0.029994056, 0.11707544 -0.10738409 0.024239928, 0.12057382 -0.10430869 0.020797551, 0.12106751 -0.10281688 0.024404168, 0.13166571 -0.092446715 0.0057794303, 0.132471 -0.090940058 0.0093894899, 0.13004585 -0.094723582 0.0056133121, 0.1392546 -0.079168737 -0.015004486, 0.13791409 -0.081880003 -0.013004571, 0.12020238 -0.10276693 0.02799423, 0.1214762 -0.10125795 0.027994335, -0.14305267 -0.073839784 0.0019958988, -0.14305268 -0.073839575 -0.0020042434, 0.13146836 -0.092308253 0.010005787, 0.13141084 -0.091956913 0.012994871, 0.12903136 -0.095776379 0.0092261434, 0.13964742 -0.079392314 -0.010015309, 0.1397943 -0.079621971 -0.0057913363, 0.13890053 -0.080777884 -0.0094007701, -0.14736393 -0.03798306 0.048661061, -0.14898665 -0.03692767 0.044997901, 0.14186086 -0.075482011 -0.0092332959, 0.11952849 -0.10219109 0.031994313, 0.11614402 -0.1054258 0.033641145, 0.12081388 -0.10066816 0.031994417, 0.11227793 -0.10564369 0.042994097, 0.11643264 -0.10181361 0.041417539, 0.11460979 -0.10210606 0.044994205, 0.11445089 -0.10585672 0.037260503, 0.11158503 -0.1063754 0.042993963, 0.13109849 -0.092048883 0.01499486, 0.13366205 -0.08865273 0.012995064, 0.13329744 -0.088414997 0.016995057, 0.12774372 -0.095913917 0.018624887, 0.12722853 -0.097327918 0.014994472, 0.13105536 -0.09170562 0.016994879, 0.11883103 -0.10159498 0.035641775, 0.11817893 -0.10143894 0.037814334, -0.10561885 -0.10273537 -0.060005784, 0.13985699 -0.079511672 -0.0057913214, 0.14270362 -0.074296772 -0.0056210309, 0.09537001 -0.1085999 0.065538824, 0.097101398 -0.10952124 0.061993867, 0.099648573 -0.10513446 0.064932078, 0.096442483 -0.1044547 0.069765419, 0.094809905 -0.10908937 0.065538853, 0.14552361 -0.057137907 -0.035648674, 0.14275643 -0.062255889 -0.037825987, 0.145275 -0.056562781 -0.037267238, 0.14667949 -0.055576444 -0.033648223, 0.14507219 -0.060691893 -0.032003403, 0.11127821 -0.10470331 0.046994075, 0.11055939 -0.10546196 0.04699412, 0.11053649 -0.10347903 0.050658062, 0.094091915 -0.10714483 0.069027856, 0.092458636 -0.10855758 0.069027945, 0.039252989 -0.15228093 0.031991445, 0.13057427 -0.091681153 0.020023853, 0.12816709 -0.094442189 0.022240326, 0.13168511 -0.089308023 0.022798762, 0.14637733 -0.057473183 -0.032003179, 0.14798531 -0.054537892 -0.030002996, 0.14589185 -0.061030209 -0.02800338, 0.14720258 -0.057797521 -0.02800326, 0.14823492 -0.05712989 -0.024251282, 0.13001607 -0.091289401 0.024240822, 0.12865324 -0.091967225 0.027994752, -0.14072627 -0.020171463 0.069773123, 0.13195834 -0.087734789 0.026405007, 0.13532975 -0.085706621 0.014995292, 0.14614955 -0.065573156 -0.015003562, 0.145696 -0.06657505 -0.015003741, -0.14442033 -0.033640116 0.057998128, 0.14787266 -0.058060825 -0.024251357, 0.14597064 -0.062617093 -0.0244115, 0.12942645 -0.090875536 0.027994841, 0.13213885 -0.086103737 0.029995188, 0.1396475 -0.079393446 0.010006502, 0.14131056 -0.076169044 0.011390239, 0.14031848 -0.077269256 0.014995649, 0.12870097 -0.090366453 0.031994909, 0.12969144 -0.087224364 0.035814807, 0.1279293 -0.09145543 0.031994879, 0.11395972 -0.097431362 0.054281697, 0.11454357 -0.098916501 0.050838664, 0.11437606 -0.096839666 0.054437563, 0.1100184 -0.09801656 0.059994549, 0.11041571 -0.10143059 0.054281309, 0.13925469 -0.079170376 0.0149955, 0.12794998 -0.089839339 0.035642341, 0.12805179 -0.087830365 0.039418057, 0.12632617 -0.092108786 0.035642236, 0.14910413 -0.058544904 -0.015003294, 0.092967413 -0.11552063 -0.05800651, 0.09179572 -0.1139982 -0.062006459, 0.11270972 -0.096362978 0.057994574, 0.12711871 -0.089255959 0.039261788, 0.12463818 -0.09268856 0.039261594, 0.13869776 -0.078854084 0.020024598, 0.138035 -0.078639925 0.024241433, 0.13783282 -0.080179423 0.02062577, 0.14076138 -0.074863434 0.020799339, 0.11125007 -0.095115274 0.061994657, 0.12616944 -0.088589638 0.042995065, 0.12157415 -0.091536254 0.048658103, 0.12176081 -0.093462706 0.044994727, 0.13810475 -0.078517258 0.024241507, 0.14974919 -0.058798701 -0.0057901442, 0.15047261 -0.057129979 -0.0036198944, 0.10985421 -0.093922079 0.065539703, 0.15172096 -0.051383823 -0.015002891, 0.12504597 -0.087801069 0.046995059, 0.14984822 -0.058837712 -0.0020033717, 0.15102383 -0.055792689 -3.0696392e-06, 0.1239175 -0.087008893 0.050658762, 0.12128405 -0.089556336 0.052281216, 0.12468974 -0.084342182 0.052840292, 0.14984822 -0.05883795 0.001996696, 0.15009449 -0.057912618 0.0057815164, 0.12270495 -0.086157769 0.054282144, 0.12423005 -0.082254261 0.056438968, 0.14614956 -0.065574795 0.014996335, 0.145696 -0.06657666 0.014996275, 0.14974922 -0.058799267 0.0057814866, 0.066605203 -0.14656103 -0.0020082742, 0.12135885 -0.085212797 0.05799517, 0.12366531 -0.080112815 0.059995502, -0.13907617 -0.025438607 0.071097173, 0.13502714 -0.076768398 0.039262593, 0.13513619 -0.077735007 0.037262172, 0.075082548 -0.13996705 -0.024415791, 0.1361686 -0.073352277 0.041419119, 0.1197872 -0.084109515 0.061995223, 0.12054395 -0.08032468 0.064933389, -0.1425404 -0.033245206 0.061998077, 0.1340189 -0.076195389 0.042995766, 0.1344564 -0.074042946 0.044995829, 0.14910409 -0.058546543 0.014996693, 0.11828418 -0.083054483 0.065540358, 0.11726701 -0.080375493 0.069766685, 0.11670657 -0.085257113 0.065540135, 0.13282557 -0.075517148 0.046995729, 0.13079074 -0.076288015 0.050659597, 0.1336821 -0.070948243 0.050840348, 0.11669905 -0.081941605 0.069029376, -0.14357485 -0.037083358 0.057997882, 0.079310037 -0.13833284 -0.020639822, 0.13162683 -0.074835867 0.050659612, 0.13021696 -0.074317783 0.054282904, 0.13033876 -0.074103713 0.054282844, 0.13305664 -0.068960726 0.054439038, 0.14787307 -0.058063835 0.024242714, 0.14817226 -0.056171536 0.02640681, 0.095702678 -0.11326486 -0.058006361, 0.094475158 -0.11178753 -0.062006265, 0.15172097 -0.051385552 0.014997065, 0.1472026 -0.057800651 0.027996868, 0.14798522 -0.054541171 0.029996902, 0.14637734 -0.057476759 0.031996772, 0.14584857 -0.05617851 0.035816655, -0.14543355 -0.046843916 0.046997372, 0.14552322 -0.057141572 0.035644114, -0.14673695 -0.047274888 0.042997293, 0.13225031 -0.067074448 0.057996228, 0.12395931 -0.070477754 0.069029987, 0.12459229 -0.066831082 0.071094871, 0.13053747 -0.066205978 0.061996296, 0.13955775 -0.054800421 0.054283947, 0.13941795 -0.052548468 0.056440696, 0.13802695 -0.054199457 0.057996914, 0.13839081 -0.050586194 0.059997112, 0.066605248 -0.14656121 0.0019917041, 0.13623935 -0.053497821 0.061997071, 0.13539475 -0.051487327 0.064935043, 0.13452989 -0.052826703 0.065542161, -0.11070756 -0.10530117 -0.047005966, -0.14171144 -0.036618382 0.06199798, 0.075251952 -0.14208341 -0.0077948421, -0.12333667 -0.098980069 -0.028005525, -0.12263408 -0.098438978 -0.032005608, -0.14425214 -0.05036509 0.046997156, -0.14553858 -0.050844401 0.04299717, 0.070244364 -0.14485219 0.0019918531, 0.07024435 -0.14485195 -0.0020082295, -0.14393534 -0.065514535 0.027996279, -0.14176732 -0.076068759 0.0056143291, -0.11169481 -0.10625532 -0.043006025, -0.13941067 -0.079895645 0.0093899518, -0.10811527 -0.10796097 -0.047006056, -0.12084918 -0.10200223 -0.028005794, -0.12016739 -0.10143536 -0.032005847, -0.14311637 -0.065173894 0.031996414, 0.073839627 -0.14305297 0.0019919425, 0.073839664 -0.14305264 -0.0020080358, 0.037980273 -0.14736667 0.048654854, 0.036925018 -0.14898929 0.044991598, -0.14226982 -0.06905666 0.027996104, 0.10273878 -0.10561559 -0.060005948, -0.10906628 -0.10895151 -0.043006144, -0.14069793 -0.074499458 0.022241466, 0.02016747 -0.14073026 0.06976635, 0.03363692 -0.14442366 0.057991944, -0.14146443 -0.06868583 0.031996228, -0.14051737 -0.072556376 0.027996037, -0.11371597 -0.10803723 -0.033651121, 0.025434658 -0.13908026 0.071090877, 0.033241533 -0.14254415 0.061992094, 0.037079982 -0.1435782 0.057991967, -0.13972645 -0.072155833 0.031996008, 0.046841286 -0.14543641 0.046991915, 0.047272444 -0.14673957 0.042991742, -0.091940098 -0.11633971 -0.058006629, -0.090716876 -0.11485845 -0.062006444, -0.11334676 -0.10966456 -0.0300062, 0.10530385 -0.11070478 -0.047006309, 0.03661485 -0.1417152 0.061992042, 0.098981649 -0.12333521 -0.028006971, 0.098440677 -0.12263218 -0.032006964, 0.050362341 -0.14425495 0.046991877, 0.05084195 -0.1455411 0.04299178, -0.089132316 -0.11850446 -0.058006696, -0.087965667 -0.11697885 -0.062006667, 0.06551294 -0.14393705 0.027991951, 0.076068349 -0.14176777 0.0056105703, 0.10625772 -0.11169228 -0.043006405, 0.079895094 -0.13941121 0.0093867779, 0.10796349 -0.10811281 -0.047006041, 0.10200377 -0.12084782 -0.028006867, 0.10143703 -0.12016571 -0.032006666, 0.065172128 -0.14311814 0.031991974, -0.12558934 -0.10071585 0.0019943975, 0.069054954 -0.14227161 0.027991936, -0.12558934 -0.10071564 -0.0020056255, 0.10895389 -0.10906395 -0.043006256, 0.074498154 -0.14069921 0.022237882, -0.13482872 -0.061727583 0.057996575, 0.068684049 -0.14146632 0.031992048, 0.072554789 -0.14051896 0.027992219, -0.12303516 -0.10382068 0.0019942261, -0.12303519 -0.10382032 -0.0020059012, 0.10803912 -0.11371407 -0.033651516, -0.13305449 -0.060989648 0.061996516, -0.13331448 -0.064933389 0.057996362, 0.072154097 -0.13972828 0.031992361, 0.11634295 -0.091936916 -0.058005184, 0.11486199 -0.090713501 -0.062005237, -0.11675994 -0.11078313 -0.0036229342, 0.10966629 -0.11334515 -0.030006379, -0.13156971 -0.064130127 0.061996441, -0.13172403 -0.068102121 0.057996247, -0.13136411 -0.07803157 0.046995673, -0.13253886 -0.078741759 0.042995606, -0.10797315 -0.11686862 -0.022807874, 0.11850777 -0.08912912 -0.05800502, 0.11698233 -0.087962151 -0.062004939, -0.084499471 -0.12729567 -0.047007129, -0.1051705 -0.12023556 -0.01863876, -0.11579433 -0.11186036 -6.2584877e-06, -0.13001099 -0.067234248 0.061996281, -0.098218851 -0.12394345 -0.02800703, -0.097654261 -0.12325934 -0.032006957, -0.12942882 -0.081201404 0.046995468, -0.1305764 -0.081955075 0.04299546, -0.085249662 -0.12844568 -0.043007292, 0.10071582 -0.1255897 0.0019930154, -0.081380568 -0.12931201 -0.04700727, 0.10071579 -0.1255894 -0.0020070374, -0.095121264 -0.12633637 -0.028007112, -0.094582625 -0.12563187 -0.032007083, 0.10382062 -0.12303531 -0.0020068139, -0.12741692 -0.084323317 0.046995293, -0.128536 -0.085119486 0.042995166, 0.061724238 -0.13483196 0.057992406, -0.12333673 -0.098983288 0.027994443, -0.082087219 -0.13048932 -0.043007329, 0.10382053 -0.1230354 0.0019931197, -0.12263407 -0.098442525 0.031994544, 0.060986146 -0.13305807 0.061992452, -0.12084918 -0.10200554 0.027994324, 0.064930007 -0.13331777 0.057992548, 0.11078332 -0.11675999 -0.0036232769, -0.12016733 -0.10143888 0.03199425, 0.064126357 -0.13157335 0.061992593, 0.068098776 -0.13172734 0.057992533, -0.063746072 -0.13388145 -0.058007628, -0.062883139 -0.13216504 -0.062007397, 0.078028977 -0.13136682 0.046992764, 0.078739241 -0.13254136 0.042992532, -0.052261993 -0.13220733 -0.069778636, 0.11686978 -0.10797197 -0.022807509, 0.12729841 -0.084497005 -0.047004759, 0.12023658 -0.10516953 -0.018637896, 0.11186029 -0.11579433 -6.5267086e-06, -0.060527198 -0.1353671 -0.05800762, -0.059729114 -0.13362005 -0.062007509, 0.067230649 -0.13001457 0.06199269, -0.114897 -0.10912892 0.026403815, 0.12394502 -0.098217338 -0.028005555, 0.12326121 -0.097652406 -0.032005489, 0.081198759 -0.12943155 0.04699266, 0.081952684 -0.13057888 0.042992786, -0.10002927 -0.12613684 -0.0020071641, -0.10911307 -0.11813021 0.0072247237, 0.12844805 -0.085247397 -0.043004826, 0.12931466 -0.081378043 -0.047004566, -0.10570309 -0.12081918 0.011387754, -0.1133468 -0.10966805 0.02999384, 0.12633781 -0.095119864 -0.028005362, 0.12563354 -0.094581008 -0.032005236, -0.10002931 -0.12613696 0.0019928589, 0.08432062 -0.12741977 0.046992838, 0.08511702 -0.12853831 0.042992771, -0.096848205 -0.12859544 -0.0020072907, 0.098981664 -0.1233384 0.027993113, 0.13049173 -0.082084954 -0.043004572, -0.072113603 -0.13871267 -0.035653226, -0.076076448 -0.13815239 -0.03000775, -0.096848197 -0.12859565 0.0019927546, 0.098440699 -0.12263578 0.031993046, 0.10200378 -0.12085101 0.027993292, -0.11552367 -0.092970759 0.057994783, -0.071258664 -0.14018336 -0.032007866, -0.061069578 -0.13847077 -0.05084946, 0.10143707 -0.12016928 0.031993315, -0.057511851 -0.14155105 -0.047008008, -0.063166752 -0.14117789 -0.041433007, -0.064022481 -0.13950238 -0.045007803, -0.11400156 -0.09179917 0.061994877, -0.071686544 -0.14096063 -0.028007932, -0.11326805 -0.095705956 0.057994567, 0.13388449 -0.063743025 -0.058003619, 0.13216853 -0.062879711 -0.062003553, -0.11070749 -0.10530663 0.046994034, -0.11169466 -0.10626015 0.042994004, 0.13221118 -0.052258134 -0.069774076, -0.077691957 -0.13810763 -0.026415884, -0.058035374 -0.1428203 -0.043008141, -0.054054506 -0.14290699 -0.047008082, -0.11179108 -0.094478786 0.06199462, 0.13537031 -0.060523897 -0.058003411, 0.13362354 -0.059725702 -0.062003419, -0.068176024 -0.14269161 -0.028007917, 0.10912729 -0.11489856 0.026403636, -0.067777589 -0.14189914 -0.03200797, -0.10811527 -0.10796621 0.046993889, -0.10906631 -0.1089564 0.042993855, 0.11812975 -0.10911372 0.0072252005, -0.054529965 -0.14419502 -0.043008238, -0.050564922 -0.14417863 -0.047008112, 0.12081847 -0.10570383 0.011388585, -0.064623721 -0.14433527 -0.028008059, -0.064255245 -0.14352855 -0.032008059, 0.10966633 -0.11334851 0.029993623, -0.10783257 -0.10281599 0.056437794, 0.12613687 -0.10002947 0.0019944012, 0.12613688 -0.10002917 -0.0020056218, -0.098218858 -0.1239467 0.027993165, -0.050991967 -0.14548391 -0.043008238, 0.13871463 -0.072111696 -0.035649523, 0.13815407 -0.076074868 -0.030004352, 0.12859547 -0.096848398 0.0019945502, 0.12859553 -0.09684822 -0.0020054579, -0.097654171 -0.12326306 0.031993121, -0.10561895 -0.10274225 0.059994277, -0.095121317 -0.1263395 0.027992893, 0.092967406 -0.11552709 0.057993606, -0.047423758 -0.14668572 -0.043008246, 0.14018521 -0.071256965 -0.032003909, 0.13847354 -0.061066836 -0.050845176, -0.094582766 -0.12563533 0.031992819, 0.14155364 -0.057509333 -0.047003224, 0.14118025 -0.063164473 -0.041428626, 0.13950482 -0.064020067 -0.045003608, 0.091795683 -0.11400509 0.061993644, 0.14096224 -0.071685076 -0.028003916, -0.032355793 -0.14470953 -0.058008127, -0.031896323 -0.14284417 -0.062007926, 0.09570273 -0.11327145 0.057993576, 0.10530386 -0.11071026 0.046993822, 0.10625779 -0.11169726 0.042993754, -0.073058322 -0.14345315 -0.0020081401, 0.13810912 -0.077690512 -0.026412532, 0.14282265 -0.0580329 -0.043003261, 0.14290968 -0.054051816 -0.047002986, -0.028886877 -0.14544168 -0.058008194, -0.028497443 -0.14356071 -0.062008083, 0.094475277 -0.11179468 0.061993793, -0.073058359 -0.14345348 0.0019917712, 0.14269316 -0.068174392 -0.028003886, 0.14190099 -0.067776024 -0.03200379, 0.10796352 -0.10811812 0.046994016, 0.10895388 -0.10906893 0.042993829, -0.078902982 -0.14028621 0.0036106855, 0.14419742 -0.054527581 -0.043003127, -0.020064726 -0.14345288 -0.064946011, -0.025401346 -0.14609069 -0.058008209, 0.14418131 -0.050562322 -0.047002748, 0.14433679 -0.064622164 -0.028003514, 0.14353032 -0.064253449 -0.032003641, -0.069453306 -0.14523312 0.001991801, -0.069453321 -0.14523286 -0.0020083264, 0.10281279 -0.10783589 0.056437448, 0.12394498 -0.098220527 0.027994543, 0.14390194 -0.044191837 -0.052845001, 0.14283413 -0.04238838 -0.056443915, 0.14548615 -0.050989777 -0.043002933, 0.14536774 -0.047042996 -0.047002748, -0.065804876 -0.14692223 0.0019918382, -0.065804899 -0.14692187 -0.0020082369, 0.12326123 -0.097656012 0.031994522, -0.018519618 -0.14617333 -0.060008243, 0.10273873 -0.10562229 0.059993997, 0.12633784 -0.095123082 0.027994707, -0.097449943 -0.10351291 0.069768451, 0.14668804 -0.047421366 -0.04300268, -0.091940247 -0.11634615 0.05799346, -0.021213725 -0.14841807 -0.054297835, 0.12563354 -0.094584584 0.031994641, -0.092875883 -0.10660219 0.071092576, 0.056254029 0.15177464 0.024505883, 0.053793013 0.15152976 0.029963881, 0.058638245 0.15178609 0.019008532, 0.05613023 0.15273139 0.019008696, 0.053607076 0.15363517 0.019008666, 0.0510692 0.1544973 0.019008681, 0.048731729 0.1543507 0.024526253, 0.046339601 0.15396255 0.030008718, 0.048091128 0.1520457 0.035537824, 0.049751133 0.14989364 0.041008383, 0.052131146 0.14908254 0.041008383, 0.054497913 0.1482338 0.041008368, 0.056851 0.14734733 0.041008249, 0.055379361 0.14955205 0.035513192, 0.054471433 0.1524235 0.024505973, 0.050577298 0.1537596 0.024506018, 0.053668037 0.15017459 0.035513252, 0.050243169 0.15274361 0.029963881, 0.049831241 0.15149102 0.035513222, 0.048091114 0.15204978 -0.035520777, 0.049751163 0.14989811 -0.040991634, 0.046339557 0.15396604 -0.029991493, 0.054498017 0.14823824 -0.040991619, 0.05685094 0.14735192 -0.040991753, 0.052131131 0.14908719 -0.040991515, 0.053793028 0.15153307 -0.029946744, 0.055379286 0.14955598 -0.035496309, 0.058638334 0.1517882 -0.01899156, 0.056254074 0.15177742 -0.024488673, 0.051069304 0.15449926 -0.018991366, 0.053607106 0.15363708 -0.018991351, 0.05613029 0.15273347 -0.018991455, 0.04873167 0.15435344 -0.024508893, 0.053665951 0.15017259 -0.035520792, 0.049829349 0.15148899 -0.035520762, 0.054470241 0.1524229 -0.024508953, 0.050240293 0.15273762 -0.029991463, 0.050576165 0.15375882 -0.024508789, -0.16115323 -0.015171409 0.024496503, -0.15986501 -0.017282933 0.029954433, -0.16219769 -0.013027787 0.018999312, -0.16196117 -0.015697628 0.018999174, -0.1616807 -0.018362969 0.018998921, -0.1613563 -0.021023601 0.018998779, -0.15882309 -0.025054038 0.029998753, -0.16021028 -0.0230667 0.024516322, -0.15663771 -0.020215482 0.040998872, -0.15785626 -0.022644401 0.035527971, -0.15693961 -0.017719388 0.040998973, -0.15720177 -0.015218794 0.040999081, -0.15742423 -0.012714088 0.040999305, -0.15877181 -0.014996052 0.035503887, -0.16096434 -0.017059177 0.024496369, -0.16047841 -0.021147221 0.024496168, -0.1585902 -0.016807944 0.035503831, -0.15941834 -0.021007746 0.029954188, -0.15811139 -0.020835906 0.035503536, -0.15882304 -0.025050581 -0.030001365, -0.15785629 -0.022640467 -0.035530418, -0.15663774 -0.020211101 -0.041001, -0.15720172 -0.015214056 -0.041001014, -0.15742427 -0.012709439 -0.04100062, -0.15693972 -0.017714769 -0.04100094, -0.15986498 -0.017279565 -0.029956132, -0.1587719 -0.014992088 -0.035505436, -0.16219771 -0.013025671 -0.019000784, -0.16115321 -0.015168756 -0.02449812, -0.16135627 -0.021021485 -0.019001134, -0.16168058 -0.018360943 -0.019001074, -0.16196117 -0.015695482 -0.019000784, -0.16021019 -0.023063868 -0.024518922, -0.1585838 -0.016803443 -0.03553012, -0.15810519 -0.020831168 -0.0355305, -0.16096079 -0.017055929 -0.024518542, -0.15940875 -0.021003127 -0.030001216, -0.16047496 -0.021144032 -0.024518736, -0.16048838 0.021068871 0.024498601, -0.15970242 0.018723637 0.029956304, -0.16102986 0.023391277 0.019001305, -0.16139311 0.020735681 0.019001201, -0.16171287 0.018074691 0.019001033, -0.16198877 0.015408754 0.019000825, -0.16132605 0.013161868 0.024518389, -0.16041571 0.010915667 0.030000523, -0.15893678 0.013049513 0.03552996, -0.15720835 0.015146494 0.041000888, -0.15694731 0.017647207 0.041001078, -0.15664646 0.020143569 0.041001119, -0.15630576 0.022634774 0.041001227, -0.15812743 0.020709753 0.03550604, -0.16072437 0.019186616 0.024498332, -0.16116028 0.01509279 0.024498206, -0.15835364 0.018902898 0.03550588, -0.16009577 0.014992684 0.02995614, -0.15878323 0.014869601 0.035505582, -0.15893689 0.013053566 -0.035528652, -0.15720837 0.015151083 -0.040999122, -0.16041568 0.010919005 -0.029999308, -0.15664645 0.020148188 -0.040998869, -0.15630582 0.022639483 -0.04099869, -0.15694737 0.017651856 -0.040998995, -0.15970226 0.018726975 -0.029954232, -0.1581274 0.020713806 -0.035503507, -0.16102976 0.023393184 -0.018998668, -0.16048837 0.021071732 -0.024496153, -0.16198871 0.015410841 -0.018999189, -0.16171288 0.018076807 -0.01899901, -0.16139312 0.020737857 -0.018998735, -0.16132605 0.013164669 -0.024516784, -0.15834734 0.018906087 -0.03552831, -0.15877703 0.014872909 -0.035528399, -0.16072063 0.019188732 -0.024516553, -0.16008608 0.014995217 -0.029999182, -0.16115665 0.015095025 -0.024516769, -0.13861188 -0.083590835 0.024492685, -0.13653542 -0.084934443 0.029950447, -0.14048305 -0.08211267 0.018995307, -0.13625567 -0.088951558 0.018994965, -0.1377022 -0.086695343 0.018995214, -0.13911147 -0.084415466 0.018995214, -0.13222492 -0.091483891 0.02999489, -0.13433704 -0.090295017 0.024512425, -0.13235554 -0.086176366 0.040995292, -0.13239928 -0.088893443 0.035524301, -0.13631882 -0.079758972 0.040995549, -0.13503197 -0.081919134 0.040995426, -0.13371071 -0.084058553 0.040995311, -0.13654272 -0.082399696 0.03550012, -0.13762294 -0.085209578 0.024492487, -0.1354112 -0.088682204 0.024492297, -0.13559294 -0.0839535 0.035499983, -0.13451679 -0.088096589 0.029950351, -0.13341412 -0.087374687 0.035499886, -0.13222477 -0.091480494 -0.030005217, -0.13239941 -0.08888948 -0.035534143, -0.13235551 -0.086171865 -0.041004881, -0.13371074 -0.084053695 -0.041004755, -0.13503185 -0.081914544 -0.041004583, -0.13631883 -0.079754442 -0.041004479, -0.13653539 -0.084931135 -0.029960029, -0.13654268 -0.082395762 -0.035509326, -0.1404829 -0.082110584 -0.019004658, -0.13861209 -0.083588034 -0.024502024, -0.13911149 -0.08441326 -0.019004717, -0.1377022 -0.086693257 -0.019004874, -0.13625556 -0.088949412 -0.019004993, -0.13433693 -0.090292335 -0.024522588, -0.13558762 -0.083946079 -0.035534024, -0.13340862 -0.087367296 -0.035534106, -0.13761973 -0.085205048 -0.024522349, -0.13450873 -0.088087946 -0.030004941, -0.13540828 -0.088677466 -0.02452261, -0.14926633 -0.059763968 -0.030003361, -0.14885995 -0.057199061 -0.035532564, -0.14821261 -0.05455932 -0.041003101, -0.15064856 -0.047421038 -0.041002683, -0.14987455 -0.049813211 -0.041002743, -0.14906235 -0.052192897 -0.041002974, -0.15201151 -0.052419573 -0.029958203, -0.15145469 -0.049946189 -0.03550753, -0.15523231 -0.048791438 -0.019002676, -0.15373704 -0.050648302 -0.024500124, -0.15263286 -0.056399375 -0.019003175, -0.15354106 -0.053877801 -0.019002959, -0.15440768 -0.051341593 -0.019002952, -0.15106103 -0.058135748 -0.0245208, -0.15086827 -0.051670372 -0.035532139, -0.14950548 -0.055490553 -0.035532244, -0.15312955 -0.052445412 -0.024520554, -0.15073803 -0.055948347 -0.030003153, -0.15174617 -0.056322992 -0.024520703, -0.15373701 -0.050650984 0.024494469, -0.15201147 -0.052423 0.02995247, -0.15523244 -0.048793554 0.018997196, -0.15440769 -0.051343828 0.018997163, -0.15354103 -0.053880006 0.018996865, -0.1526328 -0.05640173 0.018996779, -0.14926636 -0.059767306 0.029996619, -0.15106106 -0.0581384 0.024514314, -0.14821264 -0.054564059 0.040996905, -0.14886001 -0.057203054 0.035525985, -0.14906237 -0.052197546 0.040997107, -0.14987451 -0.04981789 0.040997211, -0.15064858 -0.047425538 0.040997371, -0.15145457 -0.049950153 0.035501894, -0.15313298 -0.052449197 0.024494343, -0.15174952 -0.056326926 0.024494182, -0.15087423 -0.051676333 0.035501793, -0.15074712 -0.055955023 0.029952094, -0.14951129 -0.055496722 0.035501584, -0.11861105 0.10855472 -0.029993922, -0.11612433 0.1093016 -0.035523184, -0.11346544 0.10986388 -0.04099375, -0.10991019 0.11342034 -0.040993571, -0.10809074 0.11515585 -0.040993549, -0.11170208 0.11165631 -0.040993758, -0.1131853 0.11421451 -0.029948652, -0.1107154 0.11478597 -0.035498172, -0.11131334 0.11869019 -0.018993378, -0.11233775 0.11653766 -0.024490818, -0.11704005 0.11304724 -0.018993631, -0.11516213 0.11495948 -0.018993482, -0.11325309 0.11684066 -0.01899343, -0.11792253 0.11087781 -0.02451136, -0.11201432 0.11350989 -0.035522901, -0.11486487 0.11062428 -0.03552305, -0.11369331 0.11521059 -0.024511307, -0.11581206 0.11153618 -0.029993609, -0.11658648 0.1122818 -0.024511382, -0.11233774 0.11653498 0.024503872, -0.11318526 0.11421126 0.029961735, -0.11131335 0.11868799 0.019006647, -0.11325308 0.11683851 0.019006647, -0.1151621 0.11495736 0.019006543, -0.11704005 0.11304513 0.019006312, -0.11861103 0.10855129 0.030006073, -0.11792248 0.1108751 0.024523847, -0.11346541 0.10985917 0.04100614, -0.11612435 0.10929775 0.035535522, -0.11170207 0.11165172 0.041006252, -0.10991041 0.11341572 0.041006379, -0.1080909 0.11515126 0.041006602, -0.11071547 0.11478215 0.035511188, -0.11369578 0.11521032 0.024503857, -0.11658917 0.11228141 0.024503581, -0.11201873 0.11351034 0.035511181, -0.11581896 0.11153957 0.02996172, -0.11486956 0.11062479 0.035510972, -0.083589487 0.13861069 0.024505176, -0.0849327 0.13653368 0.029962882, -0.082111552 0.14048183 0.019007862, -0.084414274 0.13911045 0.019007735, -0.086694017 0.13770121 0.019007735, -0.088950373 0.13625449 0.019007638, -0.091481984 0.13222307 0.030007429, -0.090293594 0.13433552 0.024525061, -0.086174048 0.13235316 0.041007444, -0.088891327 0.13239738 0.035536833, -0.084056042 0.13370833 0.041007601, -0.081916682 0.13502938 0.041007705, -0.079756685 0.13631654 0.041007794, -0.082397752 0.13654077 0.035512425, -0.085208222 0.13762146 0.024505079, -0.08868058 0.13540977 0.02450493, -0.083951361 0.13559094 0.035512388, -0.088095002 0.13451514 0.029962838, -0.087372631 0.13341212 0.03551235, -0.091482036 0.13222653 -0.029992528, -0.088891402 0.13240132 -0.035521865, -0.086174019 0.13235784 -0.04099258, -0.08191672 0.13503417 -0.040992402, -0.079756603 0.13632116 -0.040992357, -0.08405599 0.13371286 -0.040992573, -0.084932655 0.13653705 -0.029947512, -0.082397588 0.13654462 -0.035497047, -0.082111605 0.14048409 -0.018992156, -0.08358933 0.13861322 -0.024489522, -0.08895047 0.13625678 -0.018992402, -0.086694039 0.13770321 -0.01899226, -0.084414355 0.13911253 -0.018992223, -0.090293616 0.13433826 -0.024509996, -0.083948016 0.13558945 -0.035521537, -0.087369233 0.13341066 -0.035521753, -0.085206315 0.1376211 -0.024509862, -0.088089623 0.1345104 -0.029992379, -0.088678688 0.13540968 -0.024509996, -0.13545291 0.088615596 0.024502367, -0.13576223 0.086161584 0.029960208, -0.13493326 0.09094286 0.019005068, -0.13641295 0.088708043 0.01900503, -0.13785544 0.086449206 0.019004881, -0.13926068 0.084166944 0.019004717, -0.13963835 0.081855029 0.02452223, -0.13979274 0.079436213 0.030004524, -0.13753426 0.080717176 0.035533816, -0.13506702 0.081856281 0.041004747, -0.13374674 0.083996207 0.041004799, -0.13239259 0.086114645 0.041004956, -0.13100472 0.088211566 0.041004911, -0.13348141 0.087267578 0.03550975, -0.13648221 0.087021887 0.02450221, -0.13865128 0.083522767 0.024502069, -0.1344692 0.085737973 0.03550946, -0.1377354 0.082970709 0.029959969, -0.13660619 0.082290173 0.035509333, -0.13753428 0.080721259 -0.035524689, -0.13506706 0.08186093 -0.040995419, -0.13979262 0.07943967 -0.029995576, -0.13239254 0.086119443 -0.040995225, -0.13100475 0.088216245 -0.040995188, -0.13374665 0.084000766 -0.040995337, -0.13576229 0.086164892 -0.029950358, -0.13348147 0.087271512 -0.035499759, -0.13493322 0.090944886 -0.018994883, -0.13545293 0.088618338 -0.024492428, -0.13926065 0.08416906 -0.018995143, -0.13785541 0.086451352 -0.018995076, -0.13641289 0.088710099 -0.018994935, -0.13963833 0.08185783 -0.024513036, -0.13446382 0.085738361 -0.035524406, -0.13660088 0.082290918 -0.035524569, -0.13647917 0.087022781 -0.024512835, -0.13772699 0.082969189 -0.029995389, -0.13864827 0.083523661 -0.02451285, -0.15177593 0.056252569 0.024500489, -0.15153152 0.053791285 0.029958434, -0.15178715 0.058637202 0.019003376, -0.15273242 0.056129187 0.019003212, -0.15363619 0.053605974 0.019003075, -0.15449823 0.051068217 0.019002836, -0.15435216 0.048730105 0.024520341, -0.15396428 0.046337754 0.03000265, -0.15204772 0.048089027 0.035531864, -0.14989588 0.049748778 0.041002877, -0.14908485 0.052128792 0.041002955, -0.14823613 0.054495424 0.041003179, -0.14734963 0.056848466 0.041003153, -0.149554 0.055377156 0.035507929, -0.15242484 0.054470032 0.024500463, -0.15376085 0.050575912 0.024500176, -0.1501767 0.053665847 0.035507895, -0.1527452 0.05024147 0.0299582, -0.15149303 0.049829245 0.035507552, -0.15204766 0.048092991 -0.035526633, -0.14989579 0.049753308 -0.040997237, -0.15396437 0.046341091 -0.029997386, -0.14823619 0.054500282 -0.040996961, -0.14734957 0.056853175 -0.040996782, -0.14908487 0.052133501 -0.040997148, -0.1515315 0.053794593 -0.029952139, -0.14955416 0.055381268 -0.035501651, -0.15178715 0.058639258 -0.018996663, -0.15177597 0.0562554 -0.024494171, -0.15449834 0.051070452 -0.018997274, -0.15363622 0.053608179 -0.018996917, -0.15273237 0.056131333 -0.018996842, -0.15435216 0.048733026 -0.024514876, -0.15017074 0.053667873 -0.035526291, -0.15148695 0.049831241 -0.035526395, -0.15242156 0.054471642 -0.024514534, -0.15273599 0.050241828 -0.029997215, -0.15375751 0.050577551 -0.024514854, 0.021070421 0.16048685 0.024506375, 0.018725395 0.15970063 0.029964268, 0.02339229 0.16102868 0.019009158, 0.020736888 0.16139212 0.019009113, 0.018075719 0.16171196 0.019009143, 0.015409857 0.16198754 0.019009188, 0.013163298 0.16132453 0.02452673, 0.010917351 0.16041386 0.030008942, 0.013051584 0.15893486 0.035538241, 0.015148804 0.15720594 0.04100886, 0.01764968 0.15694478 0.04100883, 0.020145968 0.15664393 0.041008875, 0.022637039 0.15630358 0.041008845, 0.020711929 0.15812549 0.035513565, 0.019188046 0.16072291 0.024506375, 0.015094206 0.16115895 0.024506345, 0.018905029 0.15835166 0.035513684, 0.014994457 0.16009408 0.029964298, 0.014871553 0.15878129 0.035513654, 0.013051629 0.1589388 -0.035520345, 0.015148714 0.15721068 -0.040991291, 0.01091738 0.1604172 -0.029990971, 0.020145878 0.15664867 -0.040991247, 0.022637174 0.15630811 -0.040991306, 0.017649665 0.15694955 -0.040991098, 0.01872535 0.15970409 -0.029946253, 0.020711899 0.15812945 -0.035495847, 0.02339229 0.16103077 -0.018990934, 0.021070465 0.16048971 -0.024488255, 0.015409797 0.16198984 -0.018990979, 0.01807569 0.16171405 -0.018990979, 0.020736888 0.16139421 -0.018990815, 0.013163269 0.1613273 -0.024508581, 0.018904239 0.15834936 -0.035520315, 0.014871001 0.15877891 -0.035520241, 0.019187659 0.16072211 -0.024508595, 0.014993578 0.16008779 -0.029991046, 0.015093833 0.16115808 -0.024508551, -0.059765518 0.149268 -0.029991619, -0.057201125 0.14886215 -0.035520896, -0.054561608 0.14821503 -0.040991738, -0.047423214 0.15065095 -0.040991507, -0.049815476 0.14987677 -0.040991679, -0.052195162 0.14906469 -0.040991656, -0.052421317 0.15201315 -0.029946625, -0.049948141 0.15145639 -0.03549616, -0.048792623 0.15523344 -0.018991224, -0.050649546 0.1537385 -0.02448874, -0.056400508 0.15263385 -0.018991411, -0.053878896 0.1535421 -0.018991396, -0.051342718 0.15440875 -0.01899121, -0.058136888 0.1510624 -0.024509013, -0.05167219 0.15087023 -0.03552074, -0.055492476 0.1495074 -0.035520896, -0.052446738 0.15313092 -0.024508961, -0.055950031 0.15073958 -0.029991508, -0.056324214 0.15174749 -0.024509035, -0.050649516 0.15373573 0.024506032, -0.052421212 0.1520097 0.029963784, -0.048792534 0.1552313 0.019008674, -0.051342525 0.15440655 0.019008696, -0.053878903 0.15353999 0.019008532, -0.056400485 0.15263176 0.019008525, -0.059765585 0.14926463 0.030008189, -0.05813688 0.15105951 0.024526082, -0.0545616 0.14821038 0.041008368, -0.057200998 0.14885804 0.035537645, -0.052195013 0.14906004 0.041008353, -0.049815476 0.14987212 0.04100839, -0.047423206 0.15064618 0.041008532, -0.049948238 0.15145254 0.035513312, -0.052447945 0.15313157 0.024505913, -0.056325465 0.15174812 0.024505913, -0.051674239 0.15087232 0.035513245, -0.055953361 0.15074548 0.029963762, -0.055494666 0.14950922 0.03551317, -0.02505222 0.15882456 -0.029991165, -0.022642359 0.15785819 -0.035520509, -0.020213231 0.15664005 -0.040991135, -0.015216321 0.15720406 -0.040991127, -0.012711748 0.15742642 -0.040991157, -0.017716959 0.15694195 -0.040991299, -0.017281175 0.15986681 -0.029946223, -0.014993936 0.15877363 -0.035495728, -0.013026699 0.16219869 -0.018990964, -0.015169904 0.16115454 -0.024488196, -0.021022409 0.16135728 -0.0189908, -0.018361926 0.16168162 -0.018990934, -0.015696511 0.16196218 -0.018990949, -0.02306509 0.16021159 -0.024508521, -0.016805276 0.15858573 -0.035520405, -0.02083309 0.15810716 -0.035520405, -0.01705721 0.16096213 -0.024508581, -0.021004871 0.15941045 -0.02999106, -0.021145284 0.16047624 -0.024508566, -0.015169814 0.16115171 0.02450636, -0.01728119 0.15986338 0.029964238, -0.013026729 0.16219667 0.019009054, -0.015696511 0.16196004 0.019009128, -0.018361956 0.16167951 0.019009039, -0.021022424 0.1613552 0.019009128, -0.0250521 0.15882114 0.030008897, -0.023065105 0.16020888 0.024526656, -0.020213202 0.15663546 0.041008823, -0.022642389 0.15785414 0.035538048, -0.017717019 0.1569373 0.04100886, -0.015216276 0.15719947 0.041008875, -0.012711644 0.15742177 0.0410088, -0.01499413 0.15876979 0.035513788, -0.017057613 0.16096288 0.02450642, -0.021145672 0.16047707 0.02450633, -0.016806051 0.15858817 0.035513759, -0.021006048 0.15941674 0.029964283, -0.020833924 0.15810949 0.035513639, 0.13545287 -0.088618428 0.024492502, 0.13576226 -0.086165041 0.029950455, 0.1349334 -0.090945035 0.018994898, 0.13926072 -0.08416912 0.018995315, 0.13785553 -0.086451352 0.018995136, 0.13641298 -0.088710189 0.018995002, 0.13979265 -0.079439759 0.029995516, 0.13963842 -0.081857949 0.024513051, 0.13506714 -0.081861079 0.040995374, 0.13753435 -0.080721259 0.035524786, 0.13100487 -0.088216364 0.040995225, 0.13239253 -0.086119473 0.040995255, 0.13374683 -0.084001034 0.040995315, 0.13348141 -0.08727172 0.035499886, 0.13648219 -0.087024868 0.024492547, 0.13865134 -0.083525747 0.024492696, 0.13446921 -0.085741937 0.03549999, 0.1377355 -0.082974285 0.029950708, 0.13660626 -0.082294315 0.035500228, 0.13979265 -0.079436243 -0.030004397, 0.13753441 -0.080717444 -0.035533637, 0.13506716 -0.081856549 -0.041004524, 0.1337468 -0.083996385 -0.041004747, 0.13239259 -0.086114883 -0.041004851, 0.13100484 -0.088211745 -0.041004986, 0.1357623 -0.086161733 -0.029960111, 0.13348141 -0.087267846 -0.035509542, 0.13493338 -0.090942949 -0.019004971, 0.13545293 -0.088615656 -0.024502233, 0.13641289 -0.088708103 -0.019005001, 0.13785562 -0.086449325 -0.019004911, 0.13926074 -0.084166974 -0.019004688, 0.13963839 -0.081855237 -0.024522185, 0.13446382 -0.085734576 -0.035533935, 0.13660085 -0.082287133 -0.03553386, 0.13647926 -0.087020278 -0.024522394, 0.13772717 -0.08296591 -0.030004665, 0.13864826 -0.083521128 -0.0245222, 0.1539644 -0.046337813 -0.030002594, 0.15204778 -0.048089206 -0.035531983, 0.14989594 -0.049748868 -0.04100284, 0.1490849 -0.052128881 -0.041002885, 0.14823608 -0.054495662 -0.041003093, 0.14734969 -0.056848675 -0.041003063, 0.15153158 -0.053791434 -0.029958159, 0.14955413 -0.055377364 -0.035507843, 0.15178721 -0.058637232 -0.019003212, 0.15177602 -0.056252837 -0.0245004, 0.1527324 -0.056129217 -0.019003123, 0.15363616 -0.053606033 -0.019002989, 0.15449834 -0.051068276 -0.01900284, 0.15435214 -0.048730463 -0.024520308, 0.15017073 -0.053663969 -0.035532266, 0.15148699 -0.049827397 -0.035532072, 0.15242159 -0.05446896 -0.024520561, 0.15273601 -0.05023855 -0.030002907, 0.15375751 -0.050574839 -0.024520338, 0.15177605 -0.056255639 0.024494231, 0.15153153 -0.053794742 0.029952273, 0.15178725 -0.058639407 0.018996701, 0.15449835 -0.051070452 0.018997118, 0.15363622 -0.053608149 0.018996894, 0.1527324 -0.056131303 0.018996865, 0.15396431 -0.046341091 0.029997423, 0.1543521 -0.048733145 0.024514765, 0.14989601 -0.049753547 0.040997252, 0.15204778 -0.04809323 0.035526663, 0.1473497 -0.056853384 0.04099685, 0.14823613 -0.054500282 0.040996984, 0.14908499 -0.05213356 0.040997207, 0.1495541 -0.055381358 0.035501644, 0.15242486 -0.054472893 0.02449435, 0.15376094 -0.050578743 0.024494469, 0.15017667 -0.053670049 0.035501704, 0.15274528 -0.050244898 0.029952496, 0.15149301 -0.049833328 0.035502046, 0.16115324 0.015168428 0.024498269, 0.15986519 0.017279446 0.029956281, 0.16219769 0.013025612 0.019000828, 0.16135632 0.021021396 0.019001186, 0.16168068 0.018360764 0.019000962, 0.16196123 0.015695304 0.019000843, 0.15882301 0.025050431 0.030001357, 0.1602103 0.023063779 0.024518892, 0.15663774 0.020210832 0.041001156, 0.15785626 0.022640437 0.035530567, 0.15742421 0.012709349 0.041000664, 0.15720186 0.015213847 0.041000932, 0.15693972 0.01771462 0.041000932, 0.15877168 0.014992118 0.035505697, 0.1609644 0.017056167 0.024498254, 0.16047841 0.02114442 0.024498627, 0.15859024 0.01680389 0.035505697, 0.15941848 0.021004379 0.0299564, 0.1581115 0.020831853 0.035505921, 0.15882309 0.025053918 -0.029998645, 0.15785629 0.022644401 -0.035528094, 0.15663777 0.020215511 -0.040998891, 0.15693973 0.017719179 -0.04099901, 0.15720187 0.015218526 -0.040999144, 0.15742421 0.012713969 -0.040999323, 0.15986516 0.017282873 -0.029954106, 0.15877175 0.014996022 -0.03550379, 0.16219774 0.013027698 -0.018999293, 0.1611532 0.0151712 -0.024496511, 0.16196121 0.015697509 -0.01899907, 0.16168067 0.018362999 -0.018998951, 0.16135626 0.021023542 -0.018998832, 0.16021033 0.023066461 -0.024516255, 0.15858389 0.016807169 -0.035528377, 0.15810531 0.020834953 -0.035528004, 0.1609609 0.017058551 -0.024516672, 0.15940881 0.021006495 -0.029998854, 0.16047494 0.021146625 -0.024516299, 0.16048835 -0.021071792 0.024496257, 0.15970236 -0.018727094 0.029954314, 0.16102988 -0.023393393 0.018998697, 0.16198874 -0.01541093 0.018999144, 0.16171291 -0.018076897 0.018999025, 0.16139325 -0.020737976 0.018998936, 0.16041563 -0.010919183 0.029999495, 0.16132602 -0.013164729 0.024516732, 0.15720841 -0.015151113 0.040999234, 0.15893692 -0.013053656 0.035528526, 0.15630588 -0.022639573 0.040998757, 0.15664645 -0.020148247 0.040998891, 0.15694734 -0.017651945 0.040999085, 0.15812753 -0.020713955 0.0355037, 0.16072431 -0.019189477 0.024496391, 0.16116033 -0.015095592 0.02449654, 0.15835375 -0.01890707 0.0355037, 0.16009563 -0.014996052 0.029954419, 0.15878332 -0.014873624 0.035503924, 0.16041565 -0.010915697 -0.030000612, 0.15893692 -0.013049662 -0.035529941, 0.15720838 -0.015146434 -0.041000828, 0.1569473 -0.017647326 -0.041001007, 0.15664645 -0.020143688 -0.041001126, 0.15630588 -0.022634894 -0.04100123, 0.15970239 -0.018723696 -0.029956192, 0.15812752 -0.020709962 -0.035505831, 0.16102991 -0.023391277 -0.019001231, 0.16048837 -0.02106905 -0.024498358, 0.16139327 -0.020735741 -0.019001067, 0.16171293 -0.018074661 -0.019000992, 0.16198874 -0.015408814 -0.019000798, 0.16132602 -0.013162076 -0.024518296, 0.15834752 -0.018902481 -0.035530269, 0.15877688 -0.014868915 -0.035530046, 0.1607208 -0.019186288 -0.024518713, 0.16008615 -0.014991909 -0.030000851, 0.16115682 -0.015092582 -0.024518564, 0.10855304 0.1186128 -0.02999334, 0.10929969 0.11612627 -0.035522744, 0.10986166 0.11346757 -0.040993571, 0.11341816 0.10991254 -0.04099381, 0.11515357 0.10809311 -0.04099381, 0.11165403 0.11170429 -0.04099378, 0.11421297 0.11318693 -0.029948816, 0.11478423 0.11071727 -0.035498336, 0.11868925 0.1113143 -0.01899375, 0.11653641 0.11233893 -0.024491027, 0.11304612 0.11704105 -0.018993348, 0.11495861 0.11516324 -0.018993482, 0.11683983 0.1132541 -0.018993631, 0.1108766 0.11792386 -0.024511009, 0.113508 0.11201617 -0.035522923, 0.1106225 0.11486682 -0.035522804, 0.11520924 0.1136947 -0.024511188, 0.1115346 0.11581367 -0.029993623, 0.11228046 0.11658785 -0.024511039, 0.11653645 0.11233622 0.024503648, 0.11421295 0.11318359 0.029961661, 0.11868922 0.11131227 0.019006312, 0.11683975 0.11325198 0.019006461, 0.11495858 0.11516112 0.019006521, 0.11304618 0.11703894 0.019006535, 0.10855302 0.11860943 0.030006677, 0.11087659 0.11792123 0.024524242, 0.10986167 0.11346307 0.04100652, 0.10929966 0.11612222 0.035535857, 0.11165409 0.11169964 0.041006342, 0.11341816 0.10990793 0.041006356, 0.11515348 0.10808846 0.041006163, 0.11478421 0.1107133 0.035511032, 0.11521176 0.11369425 0.024503753, 0.11228302 0.11658764 0.024503991, 0.11351243 0.11201674 0.035511047, 0.11154126 0.11581728 0.029961854, 0.11062683 0.11486751 0.03551127, 0.088617072 0.13545141 0.024504945, 0.086163297 0.13576046 0.029962897, 0.090943903 0.13493207 0.019007713, 0.088709235 0.13641173 0.019007728, 0.086450279 0.13785434 0.019007862, 0.084168047 0.13925964 0.019007877, 0.081856474 0.13963684 0.024525359, 0.079437956 0.13979083 0.030007958, 0.080719203 0.13753232 0.035537004, 0.081858665 0.13506469 0.041007698, 0.083998576 0.13374442 0.041007578, 0.086117327 0.13239014 0.0410074, 0.088213906 0.13100243 0.041007414, 0.087269723 0.13347945 0.035512403, 0.087023571 0.13648072 0.02450496, 0.083524346 0.13864979 0.024505094, 0.085739896 0.13446721 0.035512358, 0.082972527 0.13773367 0.029963061, 0.082292318 0.13660419 0.035512462, 0.080719143 0.13753629 -0.035521492, 0.081858769 0.13506925 -0.040992334, 0.079437912 0.13979438 -0.029992118, 0.086117253 0.13239479 -0.040992543, 0.08821395 0.13100713 -0.040992633, 0.083998531 0.1337491 -0.040992483, 0.086163357 0.13576382 -0.029947609, 0.087269872 0.13348311 -0.035497099, 0.090943977 0.13493428 -0.018992424, 0.088617146 0.13545424 -0.024489731, 0.084168136 0.13926169 -0.018992171, 0.086450368 0.13785639 -0.018992275, 0.088709131 0.13641399 -0.01899226, 0.081856415 0.13963977 -0.024509847, 0.085736588 0.13446569 -0.035521701, 0.082288995 0.13660279 -0.035521686, 0.087021574 0.13648051 -0.024509951, 0.082967594 0.13772875 -0.029992357, 0.083522394 0.13864958 -0.024509743, 0.15373711 0.050648183 0.024500161, 0.15201148 0.052419543 0.029958323, 0.15523231 0.048791528 0.01900281, 0.15263285 0.056399286 0.019003168, 0.15354113 0.053877711 0.019003063, 0.15440769 0.051341593 0.01900284, 0.14926638 0.059763849 0.030003324, 0.15106109 0.058135539 0.02452077, 0.14821275 0.054559112 0.041003138, 0.14886011 0.057198972 0.035532534, 0.15064867 0.04742077 0.041002691, 0.14987457 0.049813181 0.041002929, 0.14906251 0.052192777 0.041003078, 0.15145448 0.049946129 0.035507545, 0.15313302 0.052446306 0.024500266, 0.15174961 0.056323916 0.024500504, 0.15087432 0.05167228 0.035507798, 0.15074718 0.055951715 0.029958576, 0.14951126 0.05549258 0.035507977, 0.14926638 0.059767157 -0.029996634, 0.1488601 0.057202965 -0.035526007, 0.14821272 0.05456394 -0.040996954, 0.14906251 0.052197397 -0.040997118, 0.14987458 0.04981783 -0.040997222, 0.15064862 0.047425419 -0.040997326, 0.15201157 0.052422941 -0.029952198, 0.15145448 0.049950123 -0.035501927, 0.15523235 0.048793525 -0.018997267, 0.15373716 0.050650924 -0.024494514, 0.15440774 0.05134365 -0.018997133, 0.1535411 0.053879887 -0.018996879, 0.1526328 0.056401581 -0.01899679, 0.15106103 0.058138311 -0.024514288, 0.15086836 0.051674128 -0.03552635, 0.14950538 0.055494398 -0.035526082, 0.15312959 0.052448004 -0.02451463, 0.15073809 0.055951595 -0.029996917, 0.15174626 0.056325465 -0.024514437, 0.13861205 0.083587885 0.024502054, 0.13653544 0.084930986 0.029960096, 0.14048304 0.082110554 0.019004613, 0.13911155 0.08441326 0.019004747, 0.13770223 0.086693197 0.019004881, 0.13625571 0.088949293 0.019005015, 0.13222486 0.091480225 0.030005038, 0.13433698 0.090292066 0.024522722, 0.13235568 0.086171687 0.041004792, 0.13239941 0.08888939 0.035534233, 0.13371065 0.084053665 0.041004762, 0.13503192 0.081914335 0.041004568, 0.13631891 0.079754204 0.041004345, 0.13654277 0.082395583 0.035509378, 0.13762291 0.085206687 0.024502069, 0.13541128 0.088679314 0.024502277, 0.13559294 0.083949447 0.035509437, 0.13451684 0.088093191 0.02996026, 0.13341415 0.087370604 0.035509735, 0.13222487 0.091483682 -0.029994816, 0.1323995 0.088893205 -0.035524189, 0.13235562 0.086176246 -0.040995166, 0.13503197 0.081919044 -0.040995568, 0.13631886 0.079758942 -0.040995494, 0.1337107 0.084058285 -0.04099527, 0.13653551 0.084934264 -0.029950485, 0.13654277 0.082399637 -0.035500184, 0.14048296 0.08211267 -0.01899536, 0.13861205 0.083590657 -0.024492592, 0.13625567 0.088951588 -0.018995121, 0.13770229 0.086695224 -0.018995151, 0.13911147 0.084415436 -0.018995225, 0.13433693 0.090294927 -0.024512485, 0.13558753 0.083949894 -0.035524517, 0.13340868 0.0873712 -0.035524383, 0.13761979 0.085207611 -0.024512842, 0.13450873 0.088091254 -0.029995129, 0.13540831 0.088680148 -0.024512663, -0.079437979 -0.13979095 -0.030007869, -0.080719218 -0.13753244 -0.035536975, -0.081858799 -0.13506487 -0.041007563, -0.083998516 -0.1337446 -0.041007556, -0.086117238 -0.13239029 -0.041007496, -0.088213965 -0.13100255 -0.041007482, -0.086163275 -0.13576061 -0.02996283, -0.087269664 -0.13347942 -0.035512149, -0.090943754 -0.13493234 -0.01900769, -0.08861693 -0.13545173 -0.02450493, -0.088709094 -0.13641179 -0.019007728, -0.086450286 -0.13785446 -0.019007631, -0.084167995 -0.13925961 -0.019007847, -0.081856467 -0.13963705 -0.024525478, -0.085736394 -0.13446191 -0.035536848, -0.082288966 -0.13659891 -0.035536975, -0.087021612 -0.13647798 -0.024525166, -0.08296752 -0.13772559 -0.030007735, -0.083522417 -0.13864705 -0.024525404, -0.088616922 -0.13545445 0.024489742, -0.086163312 -0.13576379 0.029947691, -0.090943858 -0.13493451 0.018992364, -0.084167928 -0.1392619 0.018992208, -0.086450353 -0.13785651 0.01899226, -0.088709004 -0.13641408 0.018992275, -0.079437993 -0.13979444 0.029992171, -0.08185643 -0.13963977 0.024509825, -0.081858665 -0.13506949 0.040992491, -0.08071927 -0.13753635 0.035521597, -0.088213935 -0.13100731 0.0409927, -0.086117163 -0.13239497 0.040992662, -0.083998643 -0.13374907 0.040992569, -0.087269664 -0.13348347 0.035497259, -0.0870234 -0.1364837 0.024489745, -0.083524205 -0.1386528 0.024489447, -0.085739858 -0.13447133 0.035497267, -0.082972482 -0.13773721 0.029947568, -0.082292363 -0.13660824 0.035496943, -0.11653615 -0.11233932 0.024491087, -0.1142129 -0.11318704 0.029948924, -0.11868925 -0.11131445 0.018993713, -0.1130462 -0.1170412 0.018993448, -0.11495872 -0.11516318 0.018993545, -0.11683984 -0.11325422 0.01899372, -0.10855305 -0.11861292 0.029993322, -0.11087662 -0.11792397 0.024510887, -0.10986148 -0.11346778 0.040993582, -0.10929973 -0.11612636 0.035522822, -0.11515349 -0.10809326 0.040993955, -0.11341803 -0.10991275 0.040993869, -0.11165415 -0.11170435 0.040993799, -0.11478412 -0.11071748 0.0354986, -0.11521187 -0.11369717 0.024490885, -0.11228296 -0.11659062 0.024490751, -0.1135124 -0.11202094 0.035498414, -0.11154127 -0.11582074 0.029948749, -0.1106268 -0.1148715 0.035498369, -0.1085531 -0.11860949 -0.03000655, -0.1092997 -0.11612236 -0.035535768, -0.10986167 -0.11346322 -0.041006364, -0.11165407 -0.11169976 -0.041006245, -0.11341821 -0.10990807 -0.041006118, -0.11515345 -0.10808849 -0.041006148, -0.1142128 -0.11318368 -0.029961519, -0.11478405 -0.11071357 -0.035510935, -0.11868925 -0.11131233 -0.019006215, -0.11653633 -0.1123364 -0.024503686, -0.11683983 -0.1132521 -0.019006282, -0.11495861 -0.11516115 -0.019006409, -0.11304615 -0.117039 -0.019006513, -0.1108766 -0.11792126 -0.02452419, -0.11350794 -0.11201254 -0.035535574, -0.11062241 -0.11486307 -0.035535626, -0.11520914 -0.11369202 -0.024524018, -0.11153454 -0.11581042 -0.030006506, -0.11228046 -0.11658525 -0.024524018, -0.046339422 -0.15396276 -0.030008651, -0.04809121 -0.15204591 -0.035537735, -0.049751088 -0.14989367 -0.041008428, -0.052131087 -0.1490826 -0.041008294, -0.054497898 -0.14823389 -0.041008331, -0.056850962 -0.14734748 -0.041008294, -0.053792998 -0.15152985 -0.029963821, -0.055379316 -0.1495522 -0.035513096, -0.058638237 -0.15178621 -0.019008473, -0.056254044 -0.15177476 -0.024505913, -0.056130327 -0.15273136 -0.019008562, -0.053607062 -0.15363511 -0.019008555, -0.05106926 -0.1544973 -0.019008666, -0.04873164 -0.15435085 -0.024526238, -0.053665884 -0.15016872 -0.035537802, -0.049829237 -0.15148506 -0.035537824, -0.054470271 -0.15242025 -0.024526082, -0.050240181 -0.15273437 -0.030008584, -0.050576262 -0.15375626 -0.024526291, -0.056254059 -0.15177745 0.024488829, -0.053792961 -0.15153328 0.029946767, -0.05863817 -0.15178835 0.018991508, -0.05106926 -0.15449941 0.018991418, -0.053607017 -0.15363732 0.018991388, -0.056130283 -0.15273362 0.018991411, -0.046339422 -0.15396616 0.029991336, -0.04873158 -0.15435365 0.024508886, -0.049751043 -0.14989841 0.040991604, -0.048091166 -0.1520499 0.035520799, -0.056850962 -0.14735216 0.040991731, -0.054497927 -0.14823851 0.040991761, -0.052131034 -0.14908728 0.040991671, -0.055379346 -0.14955601 0.035496436, -0.054471582 -0.15242618 0.024488732, -0.050577313 -0.15376237 0.024488702, -0.053668059 -0.15017879 0.035496347, -0.050243132 -0.15274698 0.029946797, -0.049831226 -0.15149507 0.035496324, -0.021070406 -0.16048986 0.02448833, -0.018725373 -0.15970406 0.02994629, -0.02339226 -0.1610308 0.018990979, -0.015409797 -0.16198978 0.018990867, -0.018075764 -0.1617139 0.018990867, -0.020736806 -0.16139439 0.018991075, -0.010917336 -0.16041747 0.029990986, -0.013163261 -0.16132739 0.024508581, -0.015148722 -0.1572108 0.040991187, -0.013051569 -0.15893897 0.035520427, -0.022637144 -0.15630814 0.040991329, -0.020145893 -0.15664884 0.04099115, -0.017649569 -0.1569497 0.040991239, -0.020711876 -0.15812954 0.035495937, -0.019188084 -0.16072577 0.024488322, -0.015094139 -0.16116172 0.024488285, -0.018904947 -0.15835577 0.035495967, -0.014994487 -0.16009757 0.029946275, -0.014871538 -0.15878531 0.035495885, -0.01091738 -0.16041401 -0.030009054, -0.013051614 -0.15893513 -0.035538211, -0.015148692 -0.15720618 -0.041008934, -0.017649569 -0.15694514 -0.041008823, -0.020145871 -0.1566442 -0.0410088, -0.022637196 -0.15630364 -0.0410088, -0.018725328 -0.15970072 -0.029964276, -0.020711862 -0.15812567 -0.03551358, -0.023392208 -0.16102877 -0.019009113, -0.021070398 -0.16048709 -0.024506353, -0.020736732 -0.16139224 -0.019009136, -0.018075757 -0.16171184 -0.019009054, -0.015409768 -0.16198769 -0.019009143, -0.013163224 -0.16132468 -0.024526618, -0.018904261 -0.15834543 -0.035538189, -0.014870971 -0.15877497 -0.035538167, -0.019187592 -0.16071934 -0.024526678, -0.014993578 -0.16008446 -0.030009016, -0.01509387 -0.16115546 -0.024526626, 0.09148211 -0.13222334 -0.030007422, 0.08889138 -0.13239753 -0.035536736, 0.086174101 -0.13235331 -0.041007504, 0.084056132 -0.13370854 -0.041007593, 0.081916757 -0.13502964 -0.041007549, 0.079756744 -0.13631666 -0.041007698, 0.084932692 -0.1365338 -0.029962853, 0.08239764 -0.13654077 -0.035512328, 0.082111672 -0.14048195 -0.019007817, 0.083589442 -0.13861069 -0.024505109, 0.08441437 -0.13911051 -0.019007742, 0.086694196 -0.13770127 -0.019007653, 0.08895041 -0.13625467 -0.019007638, 0.090293646 -0.13433579 -0.024525076, 0.083948061 -0.13558564 -0.035536915, 0.087369308 -0.13340682 -0.035536721, 0.085206337 -0.13761854 -0.024525329, 0.088089563 -0.13450712 -0.030007556, 0.088678755 -0.13540703 -0.024525225, 0.083589405 -0.13861352 0.024489596, 0.084932737 -0.13653713 0.029947698, 0.082111657 -0.14048415 0.01899226, 0.08895041 -0.13625681 0.018992409, 0.086694203 -0.13770345 0.01899229, 0.084414341 -0.13911268 0.01899223, 0.091482088 -0.13222674 0.029992431, 0.090293705 -0.13433838 0.024510041, 0.086174086 -0.13235804 0.040992573, 0.088891424 -0.13240147 0.035521865, 0.079756737 -0.13632128 0.040992334, 0.081916779 -0.13503432 0.040992483, 0.084056109 -0.1337131 0.040992513, 0.08239767 -0.13654476 0.035497129, 0.085208185 -0.13762432 0.024489626, 0.088680625 -0.13541278 0.024489671, 0.083951414 -0.13559508 0.035497129, 0.088094898 -0.13451856 0.029947713, 0.087372705 -0.133416 0.035497278, 0.11233775 -0.11653784 0.024490759, 0.11318531 -0.11421469 0.029948875, 0.11131334 -0.11869025 0.018993288, 0.11703999 -0.11304727 0.018993691, 0.11516223 -0.11495963 0.018993512, 0.11325312 -0.11684084 0.018993422, 0.11861113 -0.1085549 0.029993877, 0.11792263 -0.11087802 0.024511293, 0.1134654 -0.10986397 0.040994018, 0.11612432 -0.10930172 0.035523161, 0.10809086 -0.11515599 0.040993541, 0.10991039 -0.11342061 0.040993631, 0.11170196 -0.11165628 0.040993795, 0.11071538 -0.11478609 0.035498351, 0.11369575 -0.11521319 0.024490789, 0.11658908 -0.11228436 0.024491072, 0.11201885 -0.11351445 0.03549844, 0.11581902 -0.11154297 0.029949084, 0.11486948 -0.11062887 0.035498619, 0.11861113 -0.10855141 -0.03000614, 0.11612434 -0.10929775 -0.035535365, 0.11346541 -0.10985935 -0.041006163, 0.11170201 -0.11165178 -0.041006312, 0.10991034 -0.11341596 -0.041006356, 0.10809078 -0.11515126 -0.041006535, 0.11318527 -0.11421126 -0.029961616, 0.11071537 -0.11478215 -0.035511091, 0.11131339 -0.11868814 -0.019006684, 0.11233773 -0.11653504 -0.024503902, 0.11325316 -0.11683866 -0.01900658, 0.11516223 -0.11495745 -0.019006461, 0.11704 -0.1130451 -0.019006297, 0.11792264 -0.11087528 -0.024523795, 0.11201437 -0.11350608 -0.035535648, 0.11486492 -0.11062047 -0.035535395, 0.11369332 -0.11520785 -0.024524093, 0.11581204 -0.11153293 -0.0300062, 0.11658661 -0.11227912 -0.024523899, 0.02505222 -0.15882131 -0.030009001, 0.022642419 -0.15785438 -0.035538115, 0.020213164 -0.15663552 -0.0410088, 0.017717004 -0.15693742 -0.041008763, 0.01521638 -0.15719971 -0.041008949, 0.012711711 -0.15742189 -0.041008748, 0.017281227 -0.15986344 -0.029964149, 0.01499413 -0.15876979 -0.035513572, 0.013026834 -0.16219679 -0.019009143, 0.015169933 -0.16115189 -0.024506509, 0.015696488 -0.1619601 -0.019009046, 0.018362023 -0.16167957 -0.019009061, 0.021022454 -0.16135532 -0.019009024, 0.023065209 -0.16020906 -0.024526492, 0.016805366 -0.15858203 -0.035538167, 0.020833112 -0.15810329 -0.035538144, 0.017057255 -0.16095948 -0.024526618, 0.021004841 -0.15940714 -0.030008987, 0.021145366 -0.16047364 -0.024526633, 0.015169933 -0.16115469 0.024488263, 0.017281286 -0.15986678 0.029946253, 0.013026766 -0.16219887 0.018990904, 0.021022514 -0.16135746 0.018991023, 0.018362045 -0.16168177 0.018990807, 0.015696488 -0.16196221 0.018990993, 0.025052242 -0.15882477 0.029991135, 0.023065202 -0.16021177 0.024508573, 0.020213127 -0.15664017 0.040991187, 0.022642486 -0.15785828 0.03552039, 0.012711793 -0.15742663 0.040991135, 0.015216306 -0.15720424 0.04099118, 0.017717011 -0.15694213 0.040991098, 0.014994092 -0.15877375 0.035495929, 0.017057605 -0.16096574 0.024488352, 0.021145798 -0.16047993 0.024488278, 0.016806081 -0.15859225 0.035495922, 0.021006107 -0.15942013 0.029946439, 0.020833939 -0.15811351 0.035495944, 0.050649606 -0.15373853 0.024488762, 0.052421272 -0.15201321 0.029946782, 0.048792578 -0.15523356 0.018991277, 0.056400493 -0.15263397 0.018991426, 0.053878993 -0.15354225 0.018991366, 0.051342726 -0.15440866 0.018991277, 0.059765615 -0.14926821 0.029991612, 0.058136947 -0.15106249 0.024509236, 0.054561637 -0.14821517 0.040991679, 0.057201073 -0.14886218 0.035520986, 0.047423147 -0.15065104 0.040991567, 0.049815513 -0.14987701 0.040991582, 0.052195169 -0.14906484 0.040991619, 0.049948171 -0.15145656 0.035496302, 0.052447923 -0.15313452 0.024488762, 0.056325406 -0.15175095 0.024488822, 0.051674291 -0.15087637 0.035496391, 0.055953406 -0.15074882 0.029946826, 0.055494778 -0.14951339 0.035496414, 0.059765562 -0.14926478 -0.030008368, 0.057201155 -0.14885816 -0.035537593, 0.054561585 -0.14821035 -0.041008361, 0.052195229 -0.14906031 -0.041008562, 0.049815536 -0.1498723 -0.041008428, 0.047423147 -0.15064624 -0.04100839, 0.052421272 -0.1520099 -0.029963709, 0.049948201 -0.15145257 -0.035513222, 0.048792563 -0.15523133 -0.019008689, 0.050649509 -0.15373582 -0.024505921, 0.05134277 -0.15440655 -0.019008666, 0.053878888 -0.15354013 -0.019008651, 0.05640056 -0.15263173 -0.019008577, 0.05813697 -0.15105969 -0.024526119, 0.051672205 -0.15086633 -0.035537742, 0.05549252 -0.14950347 -0.035537593, 0.052446708 -0.15312833 -0.024526238, 0.055950031 -0.15073651 -0.030008428, 0.056324176 -0.15174493 -0.024526201 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 0, 3, 1, -1, 4, 5, 6, -1, 7, 5, 4, -1, 8, 2, 9, -1, 8, 9, 6, -1, 8, 5, 0, -1, 8, 0, 2, -1, 8, 6, 5, -1, 10, 11, 12, -1, 13, 14, 15, -1, 13, 16, 14, -1, 13, 17, 16, -1, 18, 19, 20, -1, 21, 13, 15, -1, 22, 13, 21, -1, 23, 24, 25, -1, 26, 27, 28, -1, 29, 22, 21, -1, 30, 22, 29, -1, 31, 32, 33, -1, 31, 34, 32, -1, 35, 36, 37, -1, 38, 19, 18, -1, 39, 23, 25, -1, 40, 41, 42, -1, 43, 30, 29, -1, 44, 45, 46, -1, 44, 46, 24, -1, 44, 24, 23, -1, 47, 48, 30, -1, 49, 40, 42, -1, 47, 30, 43, -1, 50, 51, 52, -1, 50, 52, 53, -1, 54, 55, 56, -1, 57, 58, 48, -1, 57, 48, 47, -1, 59, 58, 57, -1, 60, 55, 54, -1, 61, 43, 62, -1, 61, 47, 43, -1, 63, 64, 65, -1, 66, 67, 68, -1, 63, 65, 69, -1, 70, 58, 59, -1, 71, 72, 73, -1, 74, 62, 75, -1, 74, 61, 62, -1, 76, 38, 18, -1, 77, 23, 39, -1, 78, 79, 80, -1, 81, 82, 70, -1, 83, 27, 26, -1, 84, 75, 79, -1, 84, 74, 75, -1, 85, 82, 81, -1, 86, 87, 88, -1, 89, 83, 26, -1, 90, 77, 39, -1, 91, 40, 49, -1, 92, 87, 86, -1, 93, 85, 81, -1, 94, 85, 93, -1, 95, 96, 97, -1, 95, 98, 96, -1, 99, 50, 53, -1, 99, 53, 100, -1, 101, 95, 97, -1, 102, 72, 71, -1, 103, 79, 78, -1, 103, 84, 79, -1, 104, 38, 76, -1, 105, 106, 107, -1, 108, 84, 103, -1, 108, 109, 84, -1, 110, 94, 93, -1, 111, 63, 69, -1, 112, 77, 90, -1, 111, 69, 113, -1, 114, 109, 108, -1, 115, 94, 110, -1, 115, 116, 94, -1, 117, 118, 119, -1, 120, 102, 71, -1, 121, 67, 66, -1, 122, 95, 101, -1, 123, 124, 125, -1, 126, 127, 116, -1, 126, 116, 115, -1, 128, 123, 125, -1, 129, 130, 131, -1, 132, 83, 89, -1, 133, 134, 135, -1, 136, 137, 138, -1, 139, 72, 102, -1, 140, 106, 105, -1, 139, 141, 72, -1, 142, 127, 126, -1, 143, 110, 144, -1, 143, 115, 110, -1, 145, 146, 147, -1, 145, 147, 104, -1, 148, 149, 150, -1, 151, 127, 142, -1, 152, 132, 89, -1, 153, 137, 136, -1, 154, 90, 155, -1, 154, 112, 90, -1, 156, 153, 136, -1, 157, 100, 118, -1, 158, 129, 131, -1, 157, 99, 100, -1, 159, 144, 160, -1, 159, 143, 144, -1, 161, 102, 120, -1, 162, 158, 131, -1, 162, 131, 163, -1, 162, 163, 164, -1, 165, 166, 167, -1, 168, 134, 133, -1, 169, 161, 120, -1, 170, 171, 172, -1, 173, 168, 133, -1, 174, 170, 172, -1, 175, 153, 156, -1, 176, 118, 117, -1, 176, 157, 118, -1, 177, 178, 151, -1, 179, 180, 146, -1, 179, 146, 145, -1, 181, 158, 162, -1, 182, 175, 156, -1, 183, 184, 185, -1, 186, 132, 152, -1, 187, 178, 177, -1, 183, 188, 184, -1, 189, 160, 166, -1, 189, 159, 160, -1, 190, 191, 192, -1, 193, 166, 165, -1, 193, 189, 166, -1, 194, 175, 182, -1, 195, 168, 173, -1, 196, 187, 177, -1, 197, 161, 169, -1, 198, 187, 196, -1, 199, 195, 173, -1, 200, 180, 179, -1, 200, 201, 180, -1, 202, 201, 200, -1, 203, 183, 185, -1, 203, 185, 204, -1, 205, 190, 192, -1, 206, 207, 208, -1, 206, 208, 209, -1, 210, 211, 212, -1, 213, 189, 193, -1, 214, 197, 169, -1, 215, 149, 148, -1, 216, 217, 218, -1, 216, 182, 217, -1, 219, 220, 221, -1, 216, 194, 182, -1, 222, 194, 216, -1, 219, 221, 223, -1, 224, 157, 176, -1, 225, 226, 227, -1, 228, 195, 199, -1, 229, 198, 196, -1, 230, 226, 225, -1, 231, 232, 189, -1, 233, 202, 200, -1, 231, 189, 213, -1, 234, 211, 210, -1, 235, 232, 231, -1, 236, 186, 152, -1, 236, 152, 237, -1, 236, 237, 238, -1, 239, 186, 236, -1, 240, 209, 241, -1, 240, 206, 209, -1, 242, 204, 243, -1, 244, 245, 246, -1, 244, 246, 247, -1, 242, 203, 204, -1, 248, 249, 198, -1, 248, 198, 229, -1, 250, 202, 233, -1, 251, 234, 210, -1, 252, 253, 157, -1, 252, 157, 224, -1, 254, 248, 229, -1, 255, 256, 211, -1, 255, 211, 234, -1, 257, 258, 249, -1, 257, 249, 248, -1, 259, 197, 214, -1, 260, 261, 262, -1, 263, 253, 252, -1, 264, 219, 223, -1, 264, 223, 265, -1, 266, 240, 241, -1, 267, 250, 233, -1, 266, 241, 268, -1, 269, 258, 257, -1, 270, 234, 251, -1, 271, 248, 254, -1, 272, 273, 274, -1, 275, 270, 251, -1, 276, 258, 269, -1, 277, 271, 254, -1, 278, 279, 280, -1, 281, 250, 267, -1, 282, 283, 284, -1, 285, 270, 275, -1, 286, 278, 280, -1, 287, 271, 277, -1, 288, 285, 275, -1, 289, 261, 260, -1, 290, 264, 265, -1, 290, 265, 291, -1, 292, 287, 277, -1, 293, 294, 295, -1, 293, 295, 296, -1, 297, 292, 298, -1, 299, 300, 301, -1, 299, 301, 281, -1, 302, 272, 274, -1, 302, 274, 303, -1, 304, 305, 276, -1, 306, 285, 288, -1, 307, 308, 309, -1, 310, 305, 304, -1, 311, 308, 307, -1, 312, 287, 292, -1, 313, 314, 300, -1, 313, 300, 299, -1, 315, 292, 297, -1, 315, 312, 292, -1, 316, 317, 314, -1, 316, 314, 313, -1, 318, 319, 320, -1, 321, 310, 304, -1, 322, 317, 316, -1, 323, 310, 321, -1, 324, 325, 326, -1, 327, 328, 329, -1, 330, 302, 303, -1, 330, 303, 331, -1, 332, 319, 318, -1, 333, 322, 316, -1, 332, 334, 335, -1, 332, 335, 319, -1, 336, 337, 338, -1, 339, 340, 341, -1, 339, 328, 327, -1, 339, 341, 328, -1, 342, 322, 333, -1, 343, 312, 315, -1, 344, 345, 346, -1, 344, 347, 345, -1, 348, 349, 350, -1, 351, 330, 331, -1, 352, 353, 354, -1, 355, 356, 357, -1, 352, 358, 353, -1, 359, 351, 360, -1, 361, 362, 352, -1, 363, 364, 340, -1, 363, 340, 339, -1, 365, 342, 333, -1, 366, 323, 321, -1, 367, 368, 369, -1, 370, 371, 312, -1, 370, 312, 343, -1, 372, 373, 374, -1, 375, 376, 377, -1, 378, 379, 380, -1, 381, 348, 350, -1, 382, 379, 378, -1, 383, 337, 336, -1, 384, 356, 355, -1, 385, 371, 370, -1, 386, 384, 355, -1, 387, 334, 332, -1, 388, 383, 336, -1, 387, 389, 334, -1, 390, 339, 391, -1, 390, 363, 339, -1, 392, 342, 365, -1, 393, 346, 394, -1, 395, 384, 386, -1, 393, 344, 346, -1, 396, 330, 351, -1, 397, 398, 323, -1, 397, 323, 366, -1, 399, 400, 401, -1, 402, 395, 386, -1, 403, 367, 369, -1, 404, 364, 363, -1, 405, 391, 406, -1, 405, 390, 391, -1, 407, 408, 409, -1, 407, 409, 392, -1, 410, 396, 351, -1, 410, 351, 359, -1, 411, 397, 366, -1, 412, 395, 402, -1, 413, 376, 375, -1, 414, 415, 416, -1, 417, 414, 416, -1, 418, 383, 388, -1, 419, 405, 406, -1, 420, 421, 398, -1, 419, 406, 422, -1, 420, 398, 397, -1, 423, 408, 407, -1, 423, 422, 408, -1, 424, 413, 375, -1, 425, 426, 361, -1, 427, 419, 422, -1, 427, 422, 423, -1, 425, 361, 352, -1, 428, 387, 332, -1, 429, 418, 388, -1, 430, 419, 427, -1, 428, 332, 431, -1, 432, 421, 420, -1, 433, 434, 435, -1, 436, 394, 437, -1, 436, 393, 394, -1, 438, 433, 435, -1, 439, 397, 411, -1, 440, 430, 427, -1, 441, 435, 442, -1, 441, 438, 435, -1, 443, 421, 432, -1, 444, 430, 440, -1, 445, 439, 411, -1, 446, 438, 441, -1, 447, 444, 440, -1, 448, 444, 447, -1, 449, 35, 37, -1, 449, 450, 35, -1, 449, 451, 452, -1, 449, 37, 451, -1, 449, 452, 80, -1, 453, 450, 449, -1, 453, 449, 80, -1, 453, 79, 450, -1, 453, 80, 79, -1, 454, 455, 109, -1, 454, 114, 138, -1, 454, 109, 114, -1, 456, 454, 138, -1, 456, 457, 455, -1, 458, 459, 460, -1, 456, 138, 137, -1, 456, 455, 454, -1, 461, 456, 137, -1, 462, 418, 429, -1, 461, 463, 457, -1, 461, 457, 456, -1, 464, 137, 165, -1, 464, 165, 167, -1, 464, 167, 463, -1, 464, 463, 461, -1, 464, 461, 137, -1, 465, 95, 122, -1, 465, 466, 95, -1, 467, 414, 417, -1, 465, 122, 468, -1, 469, 466, 465, -1, 469, 465, 468, -1, 469, 208, 207, -1, 470, 396, 410, -1, 469, 471, 466, -1, 469, 468, 208, -1, 472, 471, 469, -1, 472, 469, 207, -1, 472, 473, 471, -1, 474, 207, 475, -1, 474, 475, 218, -1, 474, 218, 217, -1, 474, 472, 207, -1, 474, 217, 473, -1, 476, 413, 424, -1, 474, 473, 472, -1, 477, 170, 174, -1, 477, 478, 170, -1, 477, 174, 479, -1, 477, 479, 480, -1, 481, 235, 482, -1, 481, 483, 484, -1, 481, 484, 232, -1, 481, 232, 235, -1, 485, 486, 487, -1, 488, 477, 480, -1, 488, 478, 477, -1, 489, 476, 424, -1, 488, 268, 478, -1, 488, 480, 490, -1, 491, 492, 483, -1, 491, 482, 493, -1, 491, 481, 482, -1, 491, 483, 481, -1, 494, 490, 495, -1, 494, 266, 268, -1, 496, 497, 498, -1, 494, 488, 490, -1, 494, 268, 488, -1, 496, 498, 499, -1, 500, 491, 493, -1, 500, 297, 298, -1, 500, 298, 492, -1, 500, 493, 297, -1, 501, 439, 445, -1, 500, 492, 491, -1, 502, 389, 387, -1, 503, 504, 222, -1, 503, 216, 505, -1, 503, 222, 216, -1, 506, 507, 508, -1, 509, 495, 510, -1, 506, 511, 507, -1, 509, 266, 494, -1, 509, 494, 495, -1, 512, 513, 506, -1, 514, 505, 515, -1, 514, 503, 505, -1, 514, 504, 503, -1, 516, 517, 518, -1, 516, 518, 519, -1, 516, 519, 493, -1, 516, 493, 482, -1, 516, 482, 520, -1, 516, 520, 517, -1, 521, 428, 431, -1, 522, 510, 523, -1, 521, 431, 524, -1, 522, 525, 266, -1, 522, 266, 509, -1, 522, 509, 510, -1, 526, 379, 282, -1, 526, 527, 528, -1, 526, 284, 527, -1, 529, 486, 485, -1, 526, 528, 380, -1, 526, 380, 379, -1, 526, 282, 284, -1, 530, 531, 504, -1, 530, 515, 345, -1, 530, 504, 514, -1, 530, 345, 347, -1, 530, 514, 515, -1, 532, 523, 338, -1, 532, 533, 525, -1, 534, 501, 445, -1, 532, 525, 522, -1, 532, 522, 523, -1, 535, 536, 531, -1, 535, 530, 347, -1, 537, 538, 396, -1, 539, 534, 540, -1, 537, 396, 470, -1, 535, 531, 530, -1, 541, 532, 338, -1, 541, 542, 533, -1, 543, 544, 545, -1, 541, 338, 337, -1, 541, 533, 532, -1, 543, 546, 544, -1, 547, 518, 517, -1, 547, 362, 518, -1, 547, 352, 362, -1, 547, 358, 352, -1, 547, 517, 358, -1, 548, 353, 536, -1, 548, 535, 347, -1, 548, 536, 535, -1, 548, 347, 549, -1, 548, 549, 354, -1, 548, 354, 353, -1, 550, 551, 552, -1, 553, 554, 542, -1, 555, 551, 550, -1, 553, 542, 541, -1, 553, 541, 337, -1, 556, 557, 558, -1, 556, 558, 371, -1, 556, 385, 559, -1, 556, 371, 385, -1, 560, 459, 458, -1, 561, 562, 554, -1, 561, 337, 563, -1, 561, 553, 337, -1, 561, 554, 553, -1, 564, 565, 557, -1, 564, 556, 559, -1, 564, 559, 566, -1, 564, 557, 556, -1, 567, 437, 562, -1, 567, 562, 561, -1, 567, 563, 568, -1, 569, 538, 537, -1, 567, 561, 563, -1, 570, 378, 544, -1, 570, 544, 546, -1, 570, 382, 378, -1, 571, 540, 565, -1, 572, 560, 458, -1, 571, 565, 564, -1, 571, 539, 540, -1, 571, 566, 539, -1, 573, 417, 574, -1, 571, 564, 566, -1, 575, 437, 567, -1, 575, 436, 437, -1, 573, 467, 417, -1, 575, 567, 568, -1, 576, 487, 382, -1, 577, 476, 489, -1, 576, 570, 546, -1, 576, 382, 570, -1, 576, 485, 487, -1, 576, 546, 485, -1, 578, 436, 575, -1, 578, 568, 579, -1, 578, 579, 580, -1, 578, 575, 568, -1, 581, 429, 486, -1, 581, 486, 529, -1, 581, 462, 429, -1, 581, 529, 582, -1, 583, 559, 584, -1, 583, 584, 585, -1, 583, 566, 559, -1, 583, 586, 587, -1, 583, 587, 566, -1, 583, 585, 586, -1, 588, 425, 589, -1, 588, 426, 425, -1, 590, 591, 436, -1, 590, 436, 578, -1, 590, 578, 580, -1, 592, 593, 443, -1, 590, 580, 594, -1, 595, 496, 499, -1, 596, 597, 426, -1, 596, 426, 588, -1, 596, 589, 598, -1, 596, 588, 589, -1, 595, 499, 599, -1, 600, 462, 581, -1, 600, 581, 582, -1, 601, 501, 534, -1, 600, 602, 462, -1, 603, 604, 605, -1, 606, 607, 591, -1, 606, 594, 608, -1, 606, 591, 590, -1, 606, 590, 594, -1, 609, 610, 597, -1, 609, 597, 596, -1, 609, 598, 611, -1, 609, 596, 598, -1, 612, 613, 614, -1, 612, 600, 582, -1, 612, 614, 602, -1, 612, 602, 600, -1, 612, 582, 613, -1, 615, 593, 592, -1, 616, 467, 573, -1, 616, 617, 467, -1, 616, 573, 618, -1, 619, 585, 620, -1, 621, 521, 524, -1, 619, 620, 622, -1, 619, 623, 586, -1, 619, 622, 623, -1, 619, 586, 585, -1, 624, 545, 625, -1, 626, 627, 610, -1, 621, 524, 628, -1, 624, 543, 545, -1, 626, 610, 609, -1, 626, 609, 611, -1, 626, 629, 627, -1, 626, 611, 630, -1, 626, 630, 629, -1, 631, 607, 606, -1, 631, 632, 633, -1, 631, 633, 607, -1, 631, 608, 634, -1, 631, 606, 608, -1, 635, 636, 637, -1, 635, 638, 639, -1, 635, 639, 636, -1, 640, 601, 534, -1, 641, 618, 642, -1, 641, 643, 617, -1, 641, 617, 616, -1, 640, 534, 539, -1, 641, 616, 618, -1, 644, 632, 631, -1, 644, 645, 632, -1, 644, 634, 646, -1, 644, 631, 634, -1, 647, 635, 637, -1, 647, 638, 635, -1, 647, 648, 638, -1, 649, 641, 642, -1, 649, 642, 650, -1, 649, 643, 641, -1, 651, 645, 644, -1, 652, 603, 605, -1, 651, 653, 645, -1, 651, 646, 654, -1, 651, 644, 646, -1, 655, 656, 657, -1, 655, 658, 659, -1, 655, 657, 658, -1, 655, 659, 656, -1, 660, 648, 647, -1, 660, 637, 661, -1, 660, 647, 637, -1, 660, 662, 648, -1, 663, 664, 665, -1, 666, 643, 649, -1, 666, 649, 650, -1, 666, 650, 667, -1, 666, 668, 643, -1, 669, 653, 651, -1, 670, 663, 665, -1, 669, 651, 654, -1, 671, 560, 572, -1, 672, 673, 674, -1, 672, 675, 673, -1, 672, 674, 676, -1, 672, 677, 675, -1, 678, 679, 680, -1, 678, 681, 682, -1, 678, 680, 681, -1, 683, 684, 685, -1, 683, 662, 660, -1, 683, 660, 661, -1, 683, 661, 684, -1, 683, 685, 662, -1, 686, 668, 666, -1, 686, 687, 688, -1, 686, 667, 687, -1, 686, 666, 667, -1, 686, 688, 668, -1, 689, 669, 654, -1, 689, 653, 669, -1, 689, 690, 653, -1, 689, 654, 691, -1, 689, 691, 692, -1, 693, 672, 676, -1, 693, 694, 677, -1, 693, 676, 695, -1, 693, 695, 694, -1, 693, 677, 672, -1, 696, 697, 679, -1, 696, 678, 682, -1, 696, 679, 678, -1, 698, 615, 592, -1, 696, 699, 697, -1, 696, 682, 699, -1, 700, 701, 702, -1, 700, 703, 701, -1, 704, 705, 690, -1, 704, 692, 706, -1, 707, 708, 512, -1, 704, 690, 689, -1, 704, 689, 692, -1, 707, 512, 506, -1, 709, 615, 698, -1, 710, 711, 712, -1, 713, 671, 572, -1, 710, 714, 715, -1, 710, 716, 714, -1, 710, 715, 711, -1, 717, 718, 703, -1, 717, 702, 719, -1, 717, 700, 702, -1, 717, 703, 700, -1, 720, 721, 705, -1, 720, 704, 706, -1, 720, 706, 722, -1, 720, 705, 704, -1, 723, 712, 724, -1, 723, 710, 712, -1, 723, 716, 710, -1, 723, 725, 726, -1, 723, 726, 716, -1, 723, 724, 725, -1, 727, 718, 717, -1, 727, 717, 719, -1, 727, 728, 718, -1, 727, 719, 729, -1, 730, 720, 722, -1, 730, 731, 732, -1, 730, 732, 721, -1, 730, 721, 720, -1, 730, 722, 733, -1, 643, 625, 617, -1, 734, 728, 727, -1, 734, 735, 728, -1, 643, 624, 625, -1, 734, 736, 735, -1, 737, 595, 599, -1, 734, 729, 738, -1, 734, 738, 736, -1, 734, 727, 729, -1, 739, 740, 741, -1, 737, 599, 742, -1, 739, 741, 743, -1, 744, 603, 652, -1, 739, 743, 745, -1, 739, 746, 740, -1, 747, 748, 749, -1, 747, 750, 751, -1, 747, 751, 748, -1, 752, 753, 754, -1, 752, 755, 756, -1, 757, 601, 640, -1, 752, 758, 755, -1, 752, 756, 759, -1, 752, 759, 753, -1, 752, 754, 758, -1, 760, 761, 762, -1, 760, 763, 764, -1, 760, 762, 765, -1, 760, 766, 763, -1, 760, 765, 766, -1, 767, 621, 628, -1, 760, 764, 761, -1, 768, 769, 731, -1, 768, 731, 730, -1, 768, 730, 733, -1, 768, 733, 770, -1, 771, 745, 772, -1, 657, 634, 608, -1, 771, 746, 739, -1, 773, 744, 652, -1, 771, 739, 745, -1, 774, 598, 775, -1, 771, 776, 746, -1, 777, 749, 778, -1, 777, 779, 750, -1, 777, 750, 747, -1, 777, 747, 749, -1, 774, 611, 598, -1, 780, 772, 781, -1, 782, 621, 767, -1, 780, 771, 772, -1, 780, 776, 771, -1, 783, 784, 769, -1, 783, 769, 768, -1, 783, 768, 770, -1, 783, 770, 785, -1, 786, 777, 778, -1, 786, 779, 777, -1, 622, 620, 627, -1, 786, 778, 787, -1, 786, 788, 779, -1, 622, 627, 629, -1, 789, 790, 791, -1, 789, 792, 793, -1, 789, 791, 792, -1, 789, 793, 790, -1, 794, 795, 796, -1, 794, 796, 797, -1, 798, 623, 622, -1, 794, 797, 799, -1, 794, 799, 795, -1, 800, 801, 776, -1, 800, 781, 802, -1, 800, 780, 781, -1, 800, 776, 780, -1, 800, 802, 801, -1, 803, 784, 783, -1, 803, 783, 785, -1, 804, 805, 806, -1, 807, 601, 757, -1, 804, 808, 805, -1, 809, 810, 788, -1, 809, 786, 787, -1, 807, 639, 601, -1, 809, 788, 786, -1, 809, 787, 811, -1, 812, 813, 814, -1, 815, 671, 713, -1, 812, 816, 817, -1, 812, 817, 813, -1, 818, 819, 784, -1, 818, 803, 785, -1, 820, 821, 822, -1, 818, 784, 803, -1, 818, 785, 823, -1, 818, 823, 824, -1, 825, 826, 827, -1, 825, 808, 804, -1, 825, 828, 826, -1, 825, 804, 806, -1, 829, 709, 698, -1, 825, 827, 808, -1, 825, 806, 828, -1, 830, 831, 810, -1, 830, 809, 811, -1, 830, 810, 809, -1, 832, 812, 814, -1, 832, 814, 833, -1, 656, 634, 657, -1, 832, 816, 812, -1, 834, 835, 836, -1, 837, 663, 670, -1, 834, 838, 839, -1, 834, 840, 838, -1, 834, 836, 840, -1, 841, 819, 818, -1, 841, 842, 819, -1, 636, 639, 807, -1, 841, 818, 824, -1, 841, 824, 843, -1, 844, 845, 831, -1, 844, 831, 830, -1, 844, 811, 846, -1, 844, 846, 845, -1, 844, 830, 811, -1, 847, 848, 799, -1, 847, 849, 848, -1, 847, 850, 849, -1, 847, 799, 850, -1, 851, 816, 832, -1, 851, 832, 833, -1, 680, 614, 613, -1, 851, 833, 852, -1, 851, 853, 816, -1, 854, 855, 842, -1, 854, 842, 841, -1, 854, 841, 843, -1, 854, 843, 856, -1, 679, 614, 680, -1, 857, 858, 859, -1, 860, 861, 862, -1, 857, 859, 863, -1, 677, 864, 675, -1, 857, 865, 858, -1, 866, 867, 868, -1, 866, 868, 835, -1, 866, 839, 869, -1, 866, 834, 839, -1, 866, 869, 867, -1, 866, 835, 834, -1, 870, 871, 872, -1, 870, 873, 871, -1, 870, 872, 874, -1, 875, 851, 852, -1, 875, 853, 851, -1, 875, 852, 876, -1, 875, 877, 853, -1, 878, 879, 855, -1, 878, 855, 854, -1, 880, 775, 881, -1, 878, 854, 856, -1, 880, 774, 775, -1, 882, 744, 773, -1, 883, 865, 857, -1, 883, 857, 863, -1, 883, 863, 884, -1, 885, 873, 870, -1, 885, 886, 873, -1, 885, 874, 887, -1, 885, 870, 874, -1, 888, 889, 848, -1, 888, 890, 889, -1, 888, 848, 891, -1, 888, 891, 892, -1, 893, 875, 876, -1, 893, 876, 894, -1, 893, 877, 875, -1, 895, 896, 897, -1, 895, 898, 899, -1, 900, 820, 822, -1, 895, 899, 849, -1, 895, 897, 898, -1, 895, 849, 896, -1, 901, 856, 902, -1, 901, 878, 856, -1, 901, 879, 878, -1, 903, 861, 860, -1, 901, 904, 879, -1, 905, 872, 871, -1, 905, 865, 883, -1, 905, 871, 865, -1, 905, 884, 872, -1, 906, 822, 907, -1, 905, 883, 884, -1, 908, 909, 910, -1, 906, 900, 822, -1, 908, 910, 911, -1, 912, 890, 888, -1, 912, 892, 913, -1, 912, 888, 892, -1, 914, 886, 885, -1, 914, 915, 916, -1, 914, 916, 886, -1, 914, 887, 915, -1, 917, 882, 773, -1, 653, 880, 881, -1, 914, 885, 887, -1, 918, 893, 894, -1, 918, 919, 920, -1, 921, 917, 922, -1, 918, 894, 919, -1, 918, 920, 877, -1, 918, 877, 893, -1, 923, 901, 902, -1, 923, 902, 924, -1, 923, 904, 901, -1, 925, 926, 927, -1, 923, 928, 904, -1, 929, 897, 909, -1, 925, 930, 926, -1, 929, 909, 908, -1, 929, 911, 931, -1, 929, 931, 932, -1, 929, 908, 911, -1, 933, 934, 890, -1, 933, 913, 935, -1, 933, 890, 912, -1, 936, 937, 709, -1, 933, 912, 913, -1, 938, 939, 940, -1, 936, 709, 829, -1, 938, 941, 939, -1, 938, 940, 942, -1, 938, 942, 943, -1, 938, 943, 944, -1, 945, 936, 829, -1, 946, 923, 924, -1, 946, 928, 923, -1, 946, 924, 947, -1, 946, 948, 928, -1, 949, 950, 951, -1, 949, 951, 952, -1, 949, 952, 953, -1, 949, 953, 950, -1, 954, 955, 934, -1, 954, 935, 956, -1, 954, 933, 935, -1, 954, 934, 933, -1, 954, 956, 955, -1, 957, 897, 929, -1, 957, 898, 897, -1, 957, 929, 932, -1, 958, 959, 960, -1, 958, 961, 959, -1, 962, 948, 946, -1, 962, 946, 947, -1, 963, 938, 944, -1, 963, 964, 965, -1, 701, 703, 798, -1, 963, 966, 941, -1, 963, 944, 964, -1, 963, 941, 938, -1, 967, 957, 932, -1, 968, 670, 969, -1, 701, 798, 622, -1, 967, 970, 971, -1, 968, 837, 670, -1, 967, 971, 898, -1, 967, 932, 972, -1, 967, 898, 957, -1, 973, 960, 974, -1, 973, 974, 975, -1, 973, 961, 958, -1, 973, 975, 976, -1, 973, 958, 960, -1, 973, 976, 961, -1, 977, 948, 962, -1, 977, 962, 947, -1, 977, 947, 978, -1, 977, 978, 979, -1, 977, 980, 948, -1, 981, 900, 906, -1, 982, 983, 984, -1, 982, 984, 985, -1, 982, 986, 983, -1, 987, 966, 963, -1, 987, 963, 965, -1, 987, 988, 966, -1, 989, 990, 991, -1, 989, 950, 990, -1, 989, 992, 950, -1, 989, 991, 992, -1, 714, 659, 658, -1, 993, 970, 967, -1, 993, 967, 972, -1, 993, 994, 970, -1, 993, 972, 995, -1, 993, 995, 994, -1, 996, 977, 979, -1, 996, 979, 997, -1, 996, 998, 980, -1, 996, 980, 977, -1, 999, 986, 982, -1, 999, 1000, 986, -1, 999, 982, 985, -1, 999, 1001, 1000, -1, 1002, 988, 987, -1, 1002, 987, 965, -1, 1002, 965, 1003, -1, 1002, 1004, 988, -1, 1005, 882, 917, -1, 1006, 1007, 1008, -1, 690, 880, 653, -1, 1006, 1009, 1007, -1, 1006, 1010, 1011, -1, 1006, 1008, 1010, -1, 1006, 1011, 1012, -1, 1013, 996, 997, -1, 1013, 1014, 1015, -1, 1016, 1017, 937, -1, 1013, 998, 996, -1, 1013, 997, 1018, -1, 1013, 1018, 1014, -1, 1013, 1015, 998, -1, 1016, 937, 936, -1, 1019, 1020, 1021, -1, 1019, 1021, 1022, -1, 1019, 1022, 1023, -1, 1019, 1024, 1020, -1, 1025, 1001, 999, -1, 1025, 999, 985, -1, 1025, 985, 1026, -1, 1025, 1027, 1001, -1, 1025, 1026, 1027, -1, 1028, 1004, 1002, -1, 1029, 927, 1030, -1, 1028, 1002, 1003, -1, 1028, 1031, 1004, -1, 1028, 1003, 1032, -1, 1028, 1032, 1031, -1, 1033, 1034, 1035, -1, 1033, 1009, 1006, -1, 1033, 1006, 1012, -1, 1029, 925, 927, -1, 1033, 1035, 1009, -1, 1033, 1012, 1034, -1, 1036, 1037, 1024, -1, 1036, 1019, 1023, -1, 1036, 1023, 1037, -1, 1036, 1024, 1019, -1, 1038, 1039, 1040, -1, 1038, 1040, 992, -1, 687, 1041, 1042, -1, 1038, 992, 1043, -1, 687, 1042, 688, -1, 1038, 1043, 1044, -1, 1045, 1017, 1016, -1, 1046, 990, 1047, -1, 1046, 1047, 1048, -1, 1049, 917, 921, -1, 1046, 1050, 990, -1, 1046, 1051, 1050, -1, 1046, 1048, 1051, -1, 1052, 1053, 1054, -1, 1049, 1005, 917, -1, 1055, 936, 945, -1, 1052, 1054, 1056, -1, 1057, 1058, 1059, -1, 1057, 1060, 1061, -1, 1057, 1061, 1058, -1, 1057, 1059, 1062, -1, 1057, 1062, 1060, -1, 1063, 1038, 1044, -1, 1063, 1044, 1064, -1, 1063, 1039, 1038, -1, 1065, 1048, 1053, -1, 1065, 1052, 1056, -1, 1065, 1053, 1052, -1, 1065, 1056, 1066, -1, 1065, 1066, 1067, -1, 1068, 1063, 1064, -1, 1068, 1064, 1069, -1, 1068, 1039, 1063, -1, 1068, 1070, 1039, -1, 1071, 1072, 1031, -1, 1073, 1055, 945, -1, 1071, 1031, 1074, -1, 1071, 1075, 1072, -1, 1076, 1065, 1067, -1, 1076, 1048, 1065, -1, 1076, 1051, 1048, -1, 1077, 1070, 1068, -1, 1077, 1068, 1069, -1, 1077, 1078, 1070, -1, 1077, 1069, 1079, -1, 1080, 1071, 1074, -1, 1080, 1074, 1081, -1, 1082, 1017, 1045, -1, 1080, 1075, 1071, -1, 1083, 1084, 1062, -1, 1083, 1085, 1084, -1, 716, 659, 714, -1, 1083, 1059, 1085, -1, 1083, 1062, 1059, -1, 1086, 1087, 1088, -1, 1086, 1088, 1089, -1, 1086, 1089, 1090, -1, 1091, 1092, 1093, -1, 1094, 1082, 1045, -1, 1091, 1095, 1092, -1, 1096, 1097, 1078, -1, 1096, 1079, 1098, -1, 1096, 1098, 1097, -1, 1099, 1094, 1045, -1, 1096, 1078, 1077, -1, 1096, 1077, 1079, -1, 1100, 1101, 1102, -1, 1100, 1103, 1104, -1, 1100, 1105, 1103, -1, 1106, 1099, 1045, -1, 1100, 1102, 1105, -1, 1100, 1104, 1107, -1, 1108, 637, 1109, -1, 1100, 1107, 1101, -1, 1108, 661, 637, -1, 1110, 1111, 1112, -1, 1110, 1112, 1051, -1, 1110, 1076, 1067, -1, 1110, 1067, 1113, -1, 1110, 1051, 1076, -1, 1114, 1080, 1081, -1, 1114, 1075, 1080, -1, 1114, 1081, 1115, -1, 1114, 1116, 1075, -1, 1114, 1115, 1117, -1, 1118, 1087, 1086, -1, 1118, 1086, 1090, -1, 1118, 1119, 1087, -1, 1118, 1090, 1120, -1, 1121, 1093, 1122, -1, 1121, 1095, 1091, -1, 1121, 1122, 1123, -1, 1121, 1124, 1095, -1, 1121, 1091, 1093, -1, 1121, 1123, 1124, -1, 1125, 1116, 1114, -1, 1125, 1114, 1117, -1, 1125, 1126, 1116, -1, 1127, 1110, 1113, -1, 1127, 1128, 1111, -1, 1127, 1111, 1110, -1, 1127, 1113, 1129, -1, 1127, 1129, 1128, -1, 1130, 1120, 1131, -1, 1130, 1119, 1118, -1, 1130, 1132, 1119, -1, 1130, 1118, 1120, -1, 1133, 1134, 1135, -1, 1133, 1136, 1134, -1, 1133, 1135, 1137, -1, 1133, 1137, 1136, -1, 1138, 1125, 1117, -1, 1138, 1139, 1126, -1, 1138, 1126, 1125, -1, 1138, 1117, 1140, -1, 699, 715, 697, -1, 1141, 1142, 1143, -1, 1141, 1143, 1144, -1, 1141, 1145, 1142, -1, 1146, 1130, 1131, -1, 1146, 1132, 1130, -1, 1146, 1147, 1132, -1, 1148, 1139, 1138, -1, 1148, 1149, 1139, -1, 1148, 1138, 1140, -1, 1148, 1140, 1150, -1, 1151, 1030, 1152, -1, 1148, 1150, 1149, -1, 1153, 1144, 1154, -1, 1151, 1029, 1030, -1, 1153, 1141, 1144, -1, 1153, 1154, 1155, -1, 1153, 1145, 1141, -1, 1153, 1155, 1145, -1, 1156, 1131, 1157, -1, 1156, 1158, 1147, -1, 1156, 1147, 1146, -1, 1156, 1146, 1131, -1, 741, 1041, 687, -1, 1159, 1160, 1161, -1, 741, 740, 1041, -1, 1159, 1161, 1162, -1, 1159, 1163, 1160, -1, 1164, 1005, 1049, -1, 1159, 1165, 1163, -1, 1166, 1167, 1168, -1, 1166, 1168, 1169, -1, 1166, 1169, 1170, -1, 1166, 1170, 1171, -1, 1166, 1171, 1167, -1, 1172, 1128, 1173, -1, 1172, 1174, 1175, -1, 1172, 1175, 1128, -1, 1176, 1157, 1177, -1, 1176, 1177, 1158, -1, 1176, 1156, 1157, -1, 1178, 741, 687, -1, 1176, 1158, 1156, -1, 1179, 1162, 1180, -1, 1181, 1182, 1183, -1, 1179, 1165, 1159, -1, 1179, 1159, 1162, -1, 711, 715, 699, -1, 1184, 1174, 1172, -1, 1184, 1185, 1174, -1, 1184, 1172, 1173, -1, 1186, 1187, 1188, -1, 1184, 1173, 1189, -1, 1186, 1190, 1187, -1, 1191, 1192, 1193, -1, 1191, 1194, 1192, -1, 1191, 1193, 1195, -1, 1191, 1196, 1194, -1, 1197, 1198, 1149, -1, 1197, 1149, 1199, -1, 1197, 1200, 1198, -1, 1201, 1180, 1202, -1, 1203, 1055, 1073, -1, 1201, 1165, 1179, -1, 1201, 1179, 1180, -1, 1201, 1204, 1165, -1, 1205, 1185, 1184, -1, 1206, 1207, 1208, -1, 1205, 1184, 1189, -1, 1205, 1189, 1209, -1, 1206, 1210, 1207, -1, 1211, 1196, 1191, -1, 1211, 1191, 1195, -1, 1211, 1212, 1196, -1, 1213, 1214, 1215, -1, 1216, 1203, 1073, -1, 1213, 1217, 1218, -1, 1213, 1219, 1214, -1, 1213, 1218, 1219, -1, 1220, 1221, 1222, -1, 1220, 1222, 1168, -1, 1220, 1168, 1167, -1, 1220, 1167, 1221, -1, 1223, 1200, 1197, -1, 1224, 1225, 1206, -1, 1226, 682, 681, -1, 1223, 1197, 1199, -1, 1223, 1199, 1227, -1, 1226, 681, 1228, -1, 1229, 1230, 1204, -1, 1229, 1201, 1202, -1, 1231, 1186, 1188, -1, 1229, 1204, 1201, -1, 1232, 1233, 1234, -1, 1232, 1185, 1205, -1, 684, 1216, 685, -1, 1232, 1205, 1209, -1, 1232, 1209, 1235, -1, 1232, 1234, 1185, -1, 1236, 1237, 1005, -1, 1238, 1195, 1239, -1, 1238, 1211, 1195, -1, 1238, 1212, 1211, -1, 1238, 1239, 1212, -1, 1240, 1241, 1242, -1, 1236, 1005, 1164, -1, 1240, 1242, 1243, -1, 1240, 1244, 1241, -1, 1245, 1200, 1223, -1, 1245, 1223, 1227, -1, 1245, 1227, 1246, -1, 1245, 1247, 1200, -1, 1248, 1109, 1249, -1, 1250, 1213, 1215, -1, 1250, 1217, 1213, -1, 1248, 1108, 1109, -1, 1250, 1251, 1217, -1, 1250, 1215, 1251, -1, 1252, 1253, 1254, -1, 1252, 1255, 1256, -1, 1252, 1254, 1255, -1, 1252, 1256, 1257, -1, 1258, 1229, 1202, -1, 1258, 1202, 1259, -1, 1258, 1259, 1260, -1, 1258, 1260, 1261, -1, 1258, 1262, 1230, -1, 1258, 1261, 1262, -1, 1258, 1230, 1229, -1, 1263, 1232, 1235, -1, 1263, 1233, 1232, -1, 1263, 1264, 1233, -1, 1265, 1240, 1243, -1, 1265, 1244, 1240, -1, 1265, 1243, 1266, -1, 1265, 1267, 1244, -1, 1268, 1246, 1269, -1, 1268, 1245, 1246, -1, 1270, 1182, 1181, -1, 1268, 1247, 1245, -1, 1268, 1271, 1247, -1, 1272, 1273, 1253, -1, 1272, 1257, 1274, -1, 1272, 1252, 1257, -1, 1272, 1253, 1252, -1, 1275, 1276, 1264, -1, 1277, 1237, 1236, -1, 1275, 1278, 1276, -1, 1275, 1263, 1235, -1, 1275, 1264, 1263, -1, 1275, 1235, 1278, -1, 1279, 1280, 1281, -1, 1279, 1282, 1280, -1, 1279, 1281, 1283, -1, 1279, 1283, 1282, -1, 1284, 1269, 1285, -1, 1284, 1271, 1268, -1, 1286, 1287, 1288, -1, 1284, 1268, 1269, -1, 1284, 1289, 1271, -1, 1290, 1266, 1291, -1, 748, 694, 695, -1, 1290, 1292, 1293, -1, 1294, 1287, 1286, -1, 1290, 1293, 1267, -1, 1290, 1265, 1266, -1, 1290, 1267, 1265, -1, 1295, 741, 1178, -1, 1296, 1297, 1298, -1, 1296, 1298, 1299, -1, 1296, 1300, 1297, -1, 1301, 1302, 1303, -1, 1304, 1305, 1306, -1, 1304, 1307, 1305, -1, 1304, 1308, 1307, -1, 1309, 1274, 1310, -1, 1309, 1273, 1272, -1, 1309, 1272, 1274, -1, 1309, 1311, 1273, -1, 1312, 1285, 1313, -1, 1312, 1313, 1314, -1, 1312, 1314, 1289, -1, 1312, 1284, 1285, -1, 1312, 1289, 1284, -1, 1315, 1295, 1178, -1, 1316, 1290, 1291, -1, 1316, 1291, 1317, -1, 1316, 1292, 1290, -1, 1316, 1318, 1292, -1, 1319, 1320, 1300, -1, 1319, 1299, 1321, -1, 1319, 1321, 1320, -1, 1319, 1300, 1296, -1, 1319, 1296, 1299, -1, 1322, 1203, 1216, -1, 1323, 1304, 1306, -1, 1323, 1308, 1304, -1, 1323, 1324, 1308, -1, 1325, 1311, 1309, -1, 1326, 1186, 1231, -1, 1325, 1310, 1327, -1, 1325, 1309, 1310, -1, 1328, 1316, 1317, -1, 1328, 1318, 1316, -1, 1328, 1317, 1329, -1, 1328, 1329, 1318, -1, 1330, 1331, 1276, -1, 1330, 1276, 1332, -1, 1333, 1334, 1335, -1, 1333, 1336, 1337, -1, 1333, 1337, 1334, -1, 1338, 1339, 1340, -1, 1338, 1341, 1339, -1, 1338, 1342, 1341, -1, 1338, 1340, 1342, -1, 1343, 1226, 1228, -1, 1344, 1323, 1306, -1, 1344, 1306, 1345, -1, 1344, 1324, 1323, -1, 1344, 1345, 1346, -1, 1344, 1346, 1347, -1, 1344, 1347, 1324, -1, 1343, 1228, 1348, -1, 1349, 1350, 1311, -1, 1349, 1327, 1351, -1, 1349, 1311, 1325, -1, 1349, 1325, 1327, -1, 1352, 1353, 1354, -1, 1352, 1355, 1353, -1, 1352, 1354, 1356, -1, 1352, 1357, 1355, -1, 1358, 1332, 1359, -1, 1358, 1359, 1360, -1, 1358, 1360, 1361, -1, 1358, 1362, 1331, -1, 1358, 1330, 1332, -1, 1358, 1361, 1362, -1, 1358, 1331, 1330, -1, 1363, 1314, 1364, -1, 1363, 1365, 1366, -1, 1367, 1216, 684, -1, 1363, 1366, 1314, -1, 1368, 1335, 1369, -1, 1370, 1326, 1231, -1, 1368, 1336, 1333, -1, 1368, 1369, 1371, -1, 1367, 1322, 1216, -1, 1368, 1333, 1335, -1, 1372, 1349, 1351, -1, 1373, 1249, 1374, -1, 1372, 1375, 1350, -1, 1372, 1351, 1376, -1, 1372, 1350, 1349, -1, 1377, 1357, 1352, -1, 1373, 1248, 1249, -1, 1377, 1352, 1356, -1, 1377, 1378, 1357, -1, 1377, 1356, 1378, -1, 1379, 1380, 1336, -1, 1379, 1336, 1368, -1, 1379, 1368, 1371, -1, 1381, 1364, 1382, -1, 1381, 1363, 1364, -1, 1383, 1384, 1385, -1, 1381, 1365, 1363, -1, 1386, 1376, 1387, -1, 1386, 1388, 1389, -1, 1386, 1389, 1375, -1, 1386, 1372, 1376, -1, 1386, 1375, 1372, -1, 1390, 1391, 1392, -1, 1393, 1394, 1395, -1, 1390, 1392, 1396, -1, 1390, 1397, 1391, -1, 1398, 1399, 1400, -1, 1401, 1383, 1385, -1, 1398, 1402, 1403, -1, 1398, 1400, 1402, -1, 1398, 1403, 1399, -1, 1404, 1371, 1405, -1, 1404, 1379, 1371, -1, 1404, 1405, 1380, -1, 1404, 1380, 1379, -1, 1406, 1382, 1407, -1, 1406, 1408, 1365, -1, 1406, 1381, 1382, -1, 1409, 729, 719, -1, 1406, 1365, 1381, -1, 1410, 1386, 1387, -1, 1410, 1388, 1386, -1, 1411, 1390, 1396, -1, 1411, 1397, 1390, -1, 1411, 1396, 1412, -1, 1413, 1414, 1224, -1, 1411, 1415, 1397, -1, 1416, 1417, 1408, -1, 1416, 1406, 1407, -1, 1416, 1408, 1406, -1, 1413, 1224, 1206, -1, 1416, 1407, 1418, -1, 754, 1419, 758, -1, 1420, 1421, 1388, -1, 1420, 1410, 1387, -1, 1420, 1387, 1422, -1, 1420, 1388, 1410, -1, 1423, 1415, 1411, -1, 1423, 1411, 1412, -1, 1424, 1295, 1315, -1, 1423, 1425, 1426, -1, 1423, 1412, 1427, -1, 1423, 1426, 1415, -1, 1428, 1429, 1417, -1, 1428, 1418, 1430, -1, 1428, 1416, 1418, -1, 1428, 1417, 1416, -1, 1431, 1420, 1422, -1, 1431, 1432, 1421, -1, 1431, 1422, 1433, -1, 1431, 1421, 1420, -1, 1434, 748, 695, -1, 1435, 1436, 1437, -1, 1435, 1437, 1438, -1, 1435, 1438, 1439, -1, 1440, 1441, 1442, -1, 1443, 1429, 1428, -1, 1443, 1428, 1430, -1, 1443, 1430, 1444, -1, 1443, 1444, 1429, -1, 1445, 1446, 1447, -1, 1445, 1448, 1446, -1, 1445, 1449, 1448, -1, 1450, 1451, 1452, -1, 1450, 1452, 1453, -1, 1450, 1454, 1451, -1, 1450, 1453, 1454, -1, 1455, 1456, 1457, -1, 1455, 1458, 1456, -1, 1455, 1459, 1460, -1, 1455, 1460, 1461, -1, 1455, 1457, 1459, -1, 1455, 1461, 1458, -1, 1462, 1427, 1463, -1, 1462, 1425, 1423, -1, 1462, 1464, 1425, -1, 1462, 1423, 1427, -1, 1465, 1432, 1431, -1, 1466, 1326, 1370, -1, 1465, 1431, 1433, -1, 1465, 1433, 1467, -1, 779, 1424, 1315, -1, 1465, 1468, 1432, -1, 1469, 1470, 1471, -1, 1469, 1472, 1473, -1, 1469, 1473, 1474, -1, 1469, 1474, 1470, -1, 1475, 1476, 1477, -1, 1475, 1436, 1435, -1, 1475, 1435, 1439, -1, 1475, 1477, 1436, -1, 1475, 1439, 1476, -1, 1478, 1445, 1447, -1, 1478, 1449, 1445, -1, 1479, 1393, 1395, -1, 1478, 1470, 1449, -1, 1478, 1447, 1470, -1, 1480, 1467, 1481, -1, 1480, 1465, 1467, -1, 1480, 1468, 1465, -1, 1482, 1463, 1483, -1, 1482, 1462, 1463, -1, 1482, 1464, 1462, -1, 1482, 1483, 1464, -1, 1484, 1471, 1485, -1, 1484, 1486, 1472, -1, 1484, 1472, 1469, -1, 1484, 1469, 1471, -1, 776, 1343, 1348, -1, 1487, 1488, 1489, -1, 1487, 1490, 1491, -1, 1487, 1491, 1488, -1, 1487, 1489, 1490, -1, 1492, 1493, 1494, -1, 1492, 1494, 1495, -1, 1496, 1497, 1498, -1, 776, 1348, 746, -1, 1496, 1498, 1499, -1, 1492, 1500, 1493, -1, 1501, 729, 1409, -1, 1502, 1480, 1481, -1, 1502, 1503, 1468, -1, 1502, 1468, 1480, -1, 1502, 1481, 1504, -1, 1505, 1495, 1506, -1, 1505, 1500, 1492, -1, 1505, 1492, 1495, -1, 1507, 1485, 1508, -1, 1507, 1486, 1484, -1, 1509, 1383, 1401, -1, 813, 1373, 1374, -1, 1507, 1484, 1485, -1, 813, 1374, 735, -1, 1507, 1510, 1486, -1, 1511, 1512, 1513, -1, 813, 735, 736, -1, 1511, 1514, 1512, -1, 1515, 1322, 1367, -1, 1511, 1516, 1514, -1, 1517, 1502, 1504, -1, 1517, 1518, 1503, -1, 1517, 1504, 1519, -1, 1517, 1503, 1502, -1, 1517, 1519, 1518, -1, 1520, 1506, 1521, -1, 1520, 1500, 1505, -1, 1522, 1501, 1409, -1, 1520, 1523, 1500, -1, 1520, 1505, 1506, -1, 1524, 1510, 1507, -1, 1524, 1507, 1508, -1, 1524, 1508, 1525, -1, 1524, 1525, 1510, -1, 1526, 1511, 1513, -1, 1526, 1513, 1527, -1, 1526, 1516, 1511, -1, 817, 1373, 813, -1, 1528, 1529, 1530, -1, 1531, 1509, 1401, -1, 1528, 1532, 1529, -1, 1528, 1530, 1533, -1, 1528, 1533, 1532, -1, 1534, 1535, 1536, -1, 1534, 1537, 1538, -1, 1534, 1536, 1537, -1, 1539, 1523, 1520, -1, 1539, 1540, 1523, -1, 1539, 1520, 1521, -1, 1539, 1521, 1540, -1, 1541, 1542, 1543, -1, 1541, 1543, 1518, -1, 1541, 1544, 1545, -1, 1541, 1519, 1544, -1, 1541, 1545, 1546, -1, 1541, 1546, 1542, -1, 1547, 1441, 1440, -1, 1541, 1518, 1519, -1, 1548, 1527, 1549, -1, 1548, 1516, 1526, -1, 1548, 1526, 1527, -1, 1550, 748, 1434, -1, 1548, 1551, 1516, -1, 1552, 1553, 1535, -1, 1552, 1535, 1534, -1, 1552, 1534, 1538, -1, 1554, 1555, 1556, -1, 1552, 1538, 1557, -1, 1558, 1559, 1560, -1, 1554, 1561, 1555, -1, 1558, 1560, 1562, -1, 1558, 1562, 1563, -1, 1564, 1565, 1542, -1, 1564, 1546, 1566, -1, 1564, 1542, 1546, -1, 788, 1424, 779, -1, 1567, 1548, 1549, -1, 1567, 1549, 1568, -1, 1567, 1551, 1548, -1, 1567, 1569, 1551, -1, 763, 1570, 764, -1, 1571, 1572, 1553, -1, 1571, 1553, 1552, -1, 1571, 1552, 1557, -1, 1573, 1563, 1574, -1, 1573, 1558, 1563, -1, 1573, 1559, 1558, -1, 1575, 1564, 1566, -1, 1575, 1565, 1564, -1, 1575, 1576, 1565, -1, 1575, 1566, 1577, -1, 1578, 1569, 1567, -1, 1578, 1567, 1568, -1, 1578, 1568, 1579, -1, 1580, 1545, 1544, -1, 1580, 1544, 1581, -1, 1580, 1582, 1545, -1, 1580, 1581, 1582, -1, 1583, 1584, 1572, -1, 790, 722, 791, -1, 790, 733, 722, -1, 1583, 1557, 1585, -1, 1583, 1571, 1557, -1, 1583, 1572, 1571, -1, 1586, 1587, 1588, -1, 1586, 1559, 1573, -1, 1586, 1573, 1574, -1, 1586, 1574, 1587, -1, 1586, 1588, 1559, -1, 1589, 1590, 1591, -1, 805, 725, 724, -1, 1592, 1575, 1577, -1, 1593, 1322, 1515, -1, 1592, 1576, 1575, -1, 1592, 1577, 1594, -1, 1595, 1596, 1597, -1, 1593, 761, 1322, -1, 1595, 1597, 1598, -1, 1595, 1598, 1599, -1, 1600, 1569, 1578, -1, 808, 725, 805, -1, 1600, 1601, 1602, -1, 1600, 1578, 1579, -1, 1600, 1603, 1601, -1, 1600, 1579, 1603, -1, 1600, 1602, 1569, -1, 749, 748, 1550, -1, 1604, 1605, 1584, -1, 1604, 1583, 1585, -1, 1604, 1585, 1606, -1, 1604, 1584, 1583, -1, 1607, 1608, 1497, -1, 1609, 1610, 1611, -1, 1609, 1611, 1612, -1, 1607, 1497, 1496, -1, 1609, 1613, 1610, -1, 1609, 1614, 1613, -1, 1615, 1576, 1592, -1, 1615, 1592, 1594, -1, 1615, 1594, 1616, -1, 1615, 1617, 1576, -1, 1618, 1619, 1596, -1, 1618, 1599, 1620, -1, 1618, 1596, 1595, -1, 1621, 1501, 1522, -1, 1618, 1595, 1599, -1, 1622, 1623, 1605, -1, 1622, 1605, 1604, -1, 1622, 1604, 1606, -1, 1622, 1606, 1623, -1, 1624, 1625, 1626, -1, 1627, 1607, 1496, -1, 1624, 1626, 1628, -1, 1624, 1629, 1625, -1, 1630, 1615, 1616, -1, 1630, 1617, 1615, -1, 1631, 1590, 1589, -1, 1630, 1632, 1617, -1, 1630, 1616, 1633, -1, 1634, 1609, 1612, -1, 1634, 1635, 1614, -1, 1634, 1614, 1609, -1, 1636, 1624, 1628, -1, 1636, 1629, 1624, -1, 1636, 1628, 1637, -1, 1638, 1618, 1620, -1, 1638, 1639, 1640, -1, 1638, 1640, 1619, -1, 1638, 1620, 1639, -1, 1638, 1619, 1618, -1, 1641, 1632, 1630, -1, 1641, 1642, 1643, -1, 1641, 1630, 1633, -1, 1644, 1509, 1531, -1, 1641, 1643, 1632, -1, 1641, 1633, 1642, -1, 1645, 1612, 1646, -1, 1645, 1634, 1612, -1, 1645, 1635, 1634, -1, 1645, 1647, 1648, -1, 762, 761, 1593, -1, 1645, 1648, 1635, -1, 1649, 1637, 1650, -1, 1649, 1629, 1636, -1, 1649, 1636, 1637, -1, 1651, 1644, 1531, -1, 1649, 1652, 1629, -1, 1653, 1654, 1655, -1, 1656, 1657, 1658, -1, 1653, 1659, 1660, -1, 1653, 1660, 1654, -1, 1656, 1661, 1657, -1, 784, 1621, 1522, -1, 1662, 1663, 1640, -1, 1662, 1664, 1665, -1, 1662, 1640, 1664, -1, 1666, 1643, 1642, -1, 1666, 1667, 1668, -1, 1666, 1668, 1643, -1, 1666, 1669, 1667, -1, 1666, 1642, 1670, -1, 1666, 1671, 1669, -1, 1672, 1550, 1434, -1, 1666, 1670, 1671, -1, 1673, 1651, 1674, -1, 1675, 1676, 1652, -1, 1675, 1650, 1676, -1, 1675, 1649, 1650, -1, 1672, 1434, 1677, -1, 1675, 1652, 1649, -1, 1678, 1679, 1680, -1, 1678, 1646, 1679, -1, 1678, 1645, 1646, -1, 1678, 1680, 1647, -1, 1678, 1647, 1645, -1, 1681, 1682, 1683, -1, 1681, 1683, 1684, -1, 1681, 1685, 1682, -1, 1686, 1687, 1688, -1, 1686, 1689, 1687, -1, 1686, 1688, 1690, -1, 1691, 1659, 1653, -1, 1691, 1692, 1659, -1, 1691, 1693, 1692, -1, 1694, 1556, 1695, -1, 1691, 1655, 1693, -1, 1691, 1653, 1655, -1, 1694, 1554, 1556, -1, 1696, 1662, 1665, -1, 1696, 1697, 1663, -1, 1696, 1663, 1662, -1, 1698, 1699, 1700, -1, 1698, 1701, 1699, -1, 1698, 1702, 1703, -1, 1698, 1700, 1702, -1, 1698, 1703, 1704, -1, 1705, 1681, 1684, -1, 1705, 1706, 1707, -1, 1705, 1685, 1681, -1, 1705, 1684, 1708, -1, 1705, 1708, 1706, -1, 1705, 1707, 1685, -1, 1709, 1710, 1667, -1, 1709, 1667, 1669, -1, 1709, 1669, 1711, -1, 1712, 1713, 1689, -1, 1712, 1686, 1690, -1, 1712, 1689, 1686, -1, 1712, 1690, 1714, -1, 1715, 1696, 1665, -1, 1715, 1697, 1696, -1, 1715, 1665, 1716, -1, 1717, 1704, 1718, -1, 1717, 1701, 1698, -1, 1717, 1698, 1704, -1, 1717, 1718, 1701, -1, 1719, 1712, 1714, -1, 1719, 1713, 1712, -1, 1719, 1714, 1720, -1, 1721, 1722, 1710, -1, 1721, 1710, 1709, -1, 1721, 1709, 1711, -1, 1721, 1711, 1723, -1, 1724, 1725, 1697, -1, 1724, 1697, 1715, -1, 1724, 1716, 1726, -1, 1727, 1728, 1729, -1, 1724, 1715, 1716, -1, 1724, 1726, 1725, -1, 1730, 1731, 1732, -1, 1730, 1670, 1731, -1, 1730, 1732, 1671, -1, 1730, 1671, 1670, -1, 1733, 1734, 1735, -1, 1733, 1735, 1736, -1, 1733, 1736, 1737, -1, 1738, 1607, 1627, -1, 1733, 1739, 1734, -1, 1733, 1737, 1739, -1, 1740, 1713, 1719, -1, 1740, 1741, 1713, -1, 1740, 1742, 1741, -1, 1740, 1719, 1720, -1, 1740, 1720, 1742, -1, 1743, 1723, 1744, -1, 1743, 1722, 1721, -1, 1743, 1721, 1723, -1, 1745, 1746, 1747, -1, 1745, 1747, 1748, -1, 1745, 1749, 1750, -1, 1745, 1750, 1746, -1, 1751, 1752, 1722, -1, 1751, 1722, 1743, -1, 1751, 1743, 1744, -1, 1753, 1738, 1627, -1, 1751, 1744, 1754, -1, 1755, 1756, 1726, -1, 1755, 1726, 1757, -1, 819, 1621, 784, -1, 1755, 1758, 1756, -1, 1759, 1760, 1761, -1, 1759, 1762, 1760, -1, 1763, 1644, 1651, -1, 1759, 1761, 1764, -1, 1765, 1745, 1748, -1, 1765, 1749, 1745, -1, 1765, 1766, 1749, -1, 802, 797, 801, -1, 1767, 1752, 1751, -1, 1767, 1751, 1754, -1, 1767, 1768, 1752, -1, 1767, 1754, 1769, -1, 1770, 1758, 1755, -1, 1770, 1757, 1771, -1, 1770, 1755, 1757, -1, 1772, 1677, 1773, -1, 1772, 1672, 1677, -1, 1774, 1775, 1776, -1, 1774, 1737, 1775, -1, 1774, 1776, 1739, -1, 1774, 1739, 1737, -1, 1777, 1762, 1759, -1, 1777, 1759, 1764, -1, 1777, 1764, 1778, -1, 1779, 1658, 1780, -1, 1781, 1768, 1767, -1, 1781, 1782, 1768, -1, 1781, 1767, 1769, -1, 1781, 1769, 1783, -1, 1784, 1785, 1786, -1, 1784, 1786, 1766, -1, 1779, 1656, 1658, -1, 1784, 1748, 1787, -1, 1784, 1766, 1765, -1, 1784, 1765, 1748, -1, 1788, 1771, 52, -1, 1788, 1770, 1771, -1, 1788, 1789, 1758, -1, 1788, 52, 1789, -1, 1788, 1758, 1770, -1, 858, 753, 759, -1, 1790, 1791, 1792, -1, 1790, 1793, 28, -1, 1790, 1792, 1793, -1, 1794, 1778, 1795, -1, 1794, 1796, 1762, -1, 1794, 1777, 1778, -1, 1794, 1762, 1777, -1, 799, 797, 802, -1, 1797, 1798, 1799, -1, 1797, 1799, 1782, -1, 1797, 1781, 1783, -1, 1797, 1782, 1781, -1, 1800, 1763, 1651, -1, 1801, 1789, 51, -1, 1801, 51, 1802, -1, 1800, 1651, 1673, -1, 1801, 1803, 1789, -1, 1804, 72, 1785, -1, 1805, 1694, 1695, -1, 1804, 1787, 73, -1, 1805, 1695, 1806, -1, 1804, 73, 72, -1, 1804, 1785, 1784, -1, 1804, 1784, 1787, -1, 1807, 1791, 1790, -1, 1807, 1790, 28, -1, 1807, 28, 27, -1, 1807, 1808, 1791, -1, 1809, 1810, 1811, -1, 1809, 1811, 1812, -1, 1809, 1812, 1813, -1, 835, 793, 792, -1, 1814, 1794, 1795, -1, 835, 792, 836, -1, 1814, 1796, 1794, -1, 1814, 1795, 1815, -1, 1814, 1815, 1796, -1, 1816, 56, 55, -1, 1816, 1817, 1818, -1, 1816, 55, 1817, -1, 1816, 1818, 56, -1, 1819, 1797, 1783, -1, 1819, 1798, 1797, -1, 1819, 1783, 1820, -1, 1821, 1801, 1802, -1, 1821, 1803, 1801, -1, 1821, 1822, 1803, -1, 1823, 828, 806, -1, 1824, 1809, 1813, -1, 1824, 1810, 1809, -1, 1824, 1813, 1825, -1, 1826, 1808, 1807, -1, 1826, 1807, 27, -1, 1826, 1827, 1808, -1, 1828, 1829, 1830, -1, 1831, 1820, 1832, -1, 1831, 1819, 1820, -1, 826, 840, 827, -1, 1831, 1833, 1798, -1, 1831, 1798, 1819, -1, 1834, 1822, 1821, -1, 1834, 1802, 1835, -1, 1834, 1835, 54, -1, 1834, 54, 56, -1, 1834, 56, 1822, -1, 1834, 1821, 1802, -1, 1836, 1837, 1810, -1, 1836, 1810, 1824, -1, 1836, 1824, 1825, -1, 1836, 1825, 1838, -1, 1839, 1827, 1826, -1, 1839, 27, 117, -1, 1840, 1841, 1842, -1, 1839, 119, 1827, -1, 1839, 1826, 27, -1, 1839, 117, 119, -1, 1843, 1844, 1845, -1, 1843, 1846, 1844, -1, 1843, 1845, 1847, -1, 1848, 1738, 1753, -1, 1849, 1831, 1832, -1, 1849, 1832, 1850, -1, 1849, 49, 1833, -1, 1849, 1833, 1831, -1, 1851, 148, 150, -1, 1851, 92, 148, -1, 1851, 150, 1852, -1, 1851, 1852, 87, -1, 1851, 87, 92, -1, 1853, 1837, 1836, -1, 1853, 1836, 1838, -1, 1853, 88, 1837, -1, 1853, 1838, 86, -1, 1853, 86, 88, -1, 1854, 1850, 1855, -1, 859, 858, 759, -1, 1854, 1849, 1850, -1, 1854, 49, 1849, -1, 848, 889, 795, -1, 1856, 141, 139, -1, 1856, 139, 1857, -1, 1858, 1727, 1729, -1, 1856, 113, 1859, -1, 1856, 1859, 141, -1, 848, 795, 799, -1, 1860, 221, 220, -1, 1860, 1846, 1843, -1, 1860, 1843, 1847, -1, 1860, 1861, 1846, -1, 1860, 1847, 221, -1, 1862, 60, 54, -1, 1862, 54, 1863, -1, 1862, 1864, 60, -1, 1865, 1855, 1866, -1, 1865, 1854, 1855, -1, 865, 1773, 858, -1, 865, 1772, 1773, -1, 1865, 91, 49, -1, 1865, 49, 1854, -1, 1867, 113, 1856, -1, 1867, 1856, 1857, -1, 838, 840, 826, -1, 1867, 1857, 1868, -1, 1869, 1860, 220, -1, 1869, 1861, 1860, -1, 1869, 1870, 1861, -1, 1871, 1848, 1753, -1, 1872, 245, 148, -1, 1872, 148, 92, -1, 1872, 246, 245, -1, 1872, 92, 246, -1, 1873, 1864, 1862, -1, 1873, 1863, 1874, -1, 1873, 1862, 1863, -1, 1875, 91, 1865, -1, 1875, 1866, 1876, -1, 1875, 1877, 91, -1, 1875, 1865, 1866, -1, 1878, 113, 1867, -1, 1878, 111, 113, -1, 1878, 1867, 1868, -1, 1878, 1879, 111, -1, 1878, 1868, 1880, -1, 1881, 1869, 220, -1, 1881, 1870, 1869, -1, 1882, 828, 1823, -1, 1881, 220, 1883, -1, 1881, 1883, 238, -1, 1881, 237, 1870, -1, 1881, 238, 237, -1, 1884, 1873, 1874, -1, 1884, 1864, 1873, -1, 1885, 1780, 1886, -1, 1884, 1874, 274, -1, 1884, 273, 1864, -1, 1885, 1779, 1780, -1, 1884, 274, 273, -1, 1887, 1888, 123, -1, 1887, 128, 1889, -1, 1887, 1889, 1890, -1, 1887, 123, 128, -1, 1891, 1875, 1876, -1, 1892, 1829, 1828, -1, 1891, 1877, 1875, -1, 1891, 1876, 1893, -1, 1891, 205, 192, -1, 1891, 1893, 205, -1, 1891, 192, 1877, -1, 1894, 1895, 1879, -1, 1894, 1878, 1880, -1, 1894, 1879, 1878, -1, 1896, 263, 1897, -1, 1896, 1898, 1899, -1, 1896, 1899, 253, -1, 1900, 1806, 1901, -1, 1896, 253, 263, -1, 1902, 272, 1903, -1, 1902, 273, 272, -1, 1900, 1805, 1806, -1, 1902, 1904, 273, -1, 1905, 291, 1888, -1, 1900, 1901, 1906, -1, 1905, 1890, 1907, -1, 1905, 1888, 1887, -1, 1905, 1887, 1890, -1, 1908, 401, 1895, -1, 1908, 1895, 1894, -1, 1908, 1909, 401, -1, 1908, 1880, 1909, -1, 1908, 1894, 1880, -1, 1910, 1763, 1800, -1, 1911, 215, 1912, -1, 1911, 214, 149, -1, 1913, 1892, 1828, -1, 1914, 1882, 1823, -1, 1911, 149, 215, -1, 1915, 308, 244, -1, 1915, 309, 308, -1, 1915, 244, 247, -1, 1915, 247, 309, -1, 1916, 1917, 1904, -1, 1916, 1904, 1902, -1, 1916, 1902, 1903, -1, 1918, 1805, 1900, -1, 1919, 1898, 1896, -1, 1919, 1897, 1920, -1, 1919, 1921, 1898, -1, 1919, 1896, 1897, -1, 1922, 1912, 1923, -1, 1922, 1911, 1912, -1, 1922, 214, 1911, -1, 1924, 290, 291, -1, 1924, 1907, 1925, -1, 1924, 291, 1905, -1, 1924, 1905, 1907, -1, 1926, 1903, 1927, -1, 1926, 1916, 1903, -1, 1926, 1927, 307, -1, 1926, 1917, 1916, -1, 1926, 307, 309, -1, 1926, 309, 1917, -1, 1928, 1921, 1919, -1, 1929, 1727, 1858, -1, 1928, 359, 360, -1, 1928, 1920, 359, -1, 1928, 1919, 1920, -1, 1928, 360, 1921, -1, 1930, 1923, 1931, -1, 1930, 1922, 1923, -1, 1930, 259, 214, -1, 1930, 214, 1922, -1, 1932, 239, 236, -1, 1932, 1933, 239, -1, 1932, 236, 1934, -1, 1935, 1925, 1936, -1, 1935, 290, 1924, -1, 1935, 1924, 1925, -1, 1937, 1931, 318, -1, 1938, 1848, 1871, -1, 1937, 1930, 1931, -1, 1937, 259, 1930, -1, 1937, 320, 259, -1, 1937, 318, 320, -1, 1939, 1940, 1941, -1, 1942, 1933, 1932, -1, 1942, 1932, 1934, -1, 1942, 1934, 1943, -1, 1944, 1897, 1945, -1, 1944, 1945, 1946, -1, 1944, 1947, 1948, -1, 1944, 1948, 1920, -1, 1944, 1946, 1947, -1, 1944, 1920, 1897, -1, 1949, 1936, 1950, -1, 1949, 290, 1935, -1, 1949, 1935, 1936, -1, 1949, 1951, 290, -1, 1952, 401, 1909, -1, 1952, 1909, 377, -1, 1953, 551, 324, -1, 1954, 1955, 1956, -1, 1953, 1957, 1958, -1, 1953, 326, 1957, -1, 1953, 1958, 552, -1, 1953, 324, 326, -1, 1953, 552, 551, -1, 1959, 399, 1960, -1, 1954, 1956, 1961, -1, 1959, 1960, 1962, -1, 939, 1963, 940, -1, 1959, 1962, 403, -1, 939, 1964, 1963, -1, 1959, 369, 400, -1, 1959, 400, 399, -1, 1959, 403, 369, -1, 1965, 1966, 1967, -1, 1968, 307, 1969, -1, 1968, 311, 307, -1, 1968, 1970, 311, -1, 1971, 1972, 1933, -1, 1971, 498, 497, -1, 1971, 1933, 1942, -1, 1971, 1943, 498, -1, 896, 849, 850, -1, 1971, 1942, 1943, -1, 1973, 1974, 1763, -1, 1975, 1951, 1949, -1, 1973, 1763, 1910, -1, 1975, 1950, 460, -1, 1975, 1949, 1950, -1, 1975, 1976, 1951, -1, 1977, 401, 1952, -1, 1978, 1966, 1965, -1, 1977, 1952, 377, -1, 1977, 376, 399, -1, 1977, 377, 376, -1, 1977, 399, 401, -1, 1979, 1972, 1971, -1, 1979, 1980, 1972, -1, 1979, 1971, 497, -1, 1981, 1882, 1914, -1, 1982, 1969, 1983, -1, 1984, 1727, 1929, -1, 1982, 1968, 1969, -1, 1982, 1970, 1968, -1, 1985, 460, 459, -1, 1985, 1975, 460, -1, 1985, 1976, 1975, -1, 1985, 1986, 1976, -1, 1987, 506, 513, -1, 1987, 1946, 511, -1, 1987, 511, 506, -1, 1987, 513, 1947, -1, 1987, 1947, 1946, -1, 1988, 497, 1989, -1, 1988, 1989, 508, -1, 1988, 508, 507, -1, 1988, 507, 1980, -1, 1988, 1979, 497, -1, 1990, 1892, 1913, -1, 1988, 1980, 1979, -1, 1991, 1983, 605, -1, 1991, 605, 604, -1, 1991, 1982, 1983, -1, 1991, 1970, 1982, -1, 1991, 604, 1970, -1, 1992, 1985, 459, -1, 1992, 1986, 1985, -1, 1992, 1993, 1986, -1, 1994, 538, 569, -1, 1994, 1995, 1996, -1, 1994, 569, 1997, -1, 1994, 1996, 538, -1, 1998, 604, 603, -1, 1998, 1999, 604, -1, 2000, 1993, 1992, -1, 2000, 459, 2001, -1, 2000, 1992, 459, -1, 2000, 2002, 1993, -1, 2003, 502, 2004, -1, 2003, 389, 502, -1, 2003, 489, 389, -1, 2005, 1994, 1997, -1, 2005, 1997, 2006, -1, 890, 1981, 1914, -1, 2005, 1995, 1994, -1, 2005, 2007, 1995, -1, 2008, 1974, 1973, -1, 2009, 603, 2010, -1, 2009, 1998, 603, -1, 2009, 1999, 1998, -1, 2009, 2011, 1999, -1, 2012, 2000, 2001, -1, 2012, 2002, 2000, -1, 2012, 2001, 2013, -1, 2012, 742, 2002, -1, 2014, 2004, 2015, -1, 2016, 1990, 1913, -1, 2014, 2003, 2004, -1, 2014, 489, 2003, -1, 2017, 2010, 2018, -1, 2017, 2011, 2009, -1, 2017, 2009, 2010, -1, 2019, 550, 926, -1, 2019, 926, 930, -1, 2020, 2021, 920, -1, 2019, 555, 550, -1, 2022, 1929, 1858, -1, 2023, 2006, 921, -1, 2022, 1858, 2024, -1, 2023, 921, 922, -1, 2023, 2007, 2005, -1, 2023, 922, 2007, -1, 2025, 876, 852, -1, 2023, 2005, 2006, -1, 2026, 737, 742, -1, 2026, 2012, 2013, -1, 2026, 742, 2012, -1, 2027, 2015, 2028, -1, 2027, 2014, 2015, -1, 2027, 577, 489, -1, 2027, 489, 2014, -1, 2029, 2018, 767, -1, 2029, 767, 628, -1, 2029, 2017, 2018, -1, 2029, 2011, 2017, -1, 2029, 628, 2011, -1, 2030, 862, 555, -1, 2030, 930, 860, -1, 2030, 860, 862, -1, 2030, 2019, 930, -1, 2030, 555, 2019, -1, 2031, 737, 2026, -1, 2031, 2026, 2013, -1, 2031, 2013, 2032, -1, 2031, 2032, 2033, -1, 2034, 713, 861, -1, 2034, 903, 2035, -1, 2034, 815, 713, -1, 2034, 861, 903, -1, 2036, 2037, 2006, -1, 2036, 2006, 1997, -1, 2036, 1997, 2038, -1, 2036, 2038, 2039, -1, 2036, 2039, 2040, -1, 2036, 2040, 2037, -1, 2041, 707, 2042, -1, 2041, 708, 707, -1, 2043, 2028, 906, -1, 2043, 577, 2027, -1, 2043, 907, 577, -1, 2043, 906, 907, -1, 2043, 2027, 2028, -1, 2044, 737, 2031, -1, 2044, 2045, 737, -1, 2044, 2031, 2033, -1, 2046, 845, 846, -1, 2044, 2033, 2047, -1, 2048, 2042, 1187, -1, 2048, 2041, 2042, -1, 2048, 2049, 708, -1, 2048, 708, 2041, -1, 2050, 815, 2034, -1, 2050, 2034, 2035, -1, 2050, 2051, 815, -1, 2052, 767, 2053, -1, 2052, 782, 767, -1, 2052, 2054, 782, -1, 2055, 2056, 2045, -1, 2055, 2044, 2047, -1, 2055, 2047, 1183, -1, 2055, 2045, 2044, -1, 2057, 1187, 1190, -1, 2057, 2048, 1187, -1, 2057, 2058, 2049, -1, 2057, 2049, 2048, -1, 2059, 2035, 1288, -1, 2059, 1288, 1287, -1, 2059, 2050, 2035, -1, 2059, 2051, 2050, -1, 2059, 1287, 2051, -1, 2060, 1152, 837, -1, 934, 1981, 890, -1, 2060, 968, 2061, -1, 2060, 837, 968, -1, 2062, 2053, 2063, -1, 2062, 2052, 2053, -1, 2062, 2054, 2052, -1, 2064, 1210, 1206, -1, 2064, 2039, 1210, -1, 2064, 1206, 1225, -1, 2064, 2040, 2039, -1, 2064, 1225, 2040, -1, 2065, 1190, 2066, -1, 2065, 2066, 1208, -1, 2067, 2020, 920, -1, 2065, 1208, 1207, -1, 2065, 1207, 2058, -1, 2065, 2058, 2057, -1, 2065, 2057, 1190, -1, 2068, 2069, 2070, -1, 2068, 2070, 2056, -1, 2071, 1990, 2016, -1, 2068, 1183, 1182, -1, 2068, 2055, 1183, -1, 2068, 2056, 2055, -1, 2072, 2062, 2063, -1, 2072, 2063, 1385, -1, 2072, 1385, 1384, -1, 2072, 2054, 2062, -1, 2072, 1384, 2054, -1, 2073, 1277, 1555, -1, 2073, 2074, 1237, -1, 2075, 2076, 2077, -1, 2073, 1237, 1277, -1, 2078, 1151, 1152, -1, 2078, 2061, 2079, -1, 2078, 1152, 2060, -1, 2078, 2060, 2061, -1, 2080, 2068, 1182, -1, 2081, 2022, 2024, -1, 2080, 2082, 2069, -1, 2080, 2069, 2068, -1, 2081, 2024, 2083, -1, 919, 2067, 920, -1, 2080, 1182, 2084, -1, 2085, 1384, 1383, -1, 2086, 876, 2025, -1, 2085, 2087, 1384, -1, 2088, 2089, 2074, -1, 2088, 2073, 1555, -1, 2088, 2074, 2073, -1, 2090, 2079, 2091, -1, 2090, 1151, 2078, -1, 2090, 2078, 2079, -1, 2092, 1370, 2082, -1, 2092, 2080, 2084, -1, 2092, 2084, 2093, -1, 2092, 2082, 2080, -1, 2094, 1383, 2095, -1, 2096, 2097, 2098, -1, 2094, 2087, 2085, -1, 2099, 845, 2046, -1, 2094, 2085, 1383, -1, 2100, 1181, 1442, -1, 2100, 1270, 1181, -1, 2100, 1441, 1270, -1, 2100, 1442, 1441, -1, 2101, 1555, 1561, -1, 2102, 2086, 2025, -1, 2101, 2103, 2089, -1, 2101, 2088, 1555, -1, 2101, 2089, 2088, -1, 2104, 2076, 2075, -1, 2105, 1151, 2090, -1, 2105, 2106, 1151, -1, 2105, 2090, 2091, -1, 2105, 2091, 2107, -1, 2108, 1370, 2092, -1, 2108, 2092, 2093, -1, 2109, 2110, 2111, -1, 2109, 1303, 2110, -1, 2109, 2111, 2112, -1, 2109, 1301, 1303, -1, 2113, 2094, 2095, -1, 2113, 1479, 1395, -1, 2113, 2087, 2094, -1, 2113, 2095, 2114, -1, 2115, 2116, 2117, -1, 2113, 2114, 2118, -1, 2119, 2067, 919, -1, 2113, 2118, 1479, -1, 2113, 1395, 2087, -1, 2120, 1286, 1657, -1, 2115, 2117, 2121, -1, 2120, 1657, 1661, -1, 2122, 902, 856, -1, 2120, 1294, 1286, -1, 2123, 1674, 2103, -1, 2123, 2101, 1561, -1, 2123, 2103, 2101, -1, 2122, 856, 2124, -1, 2123, 1561, 1673, -1, 2123, 1673, 1674, -1, 2125, 1499, 2106, -1, 2125, 1496, 1499, -1, 959, 867, 869, -1, 2125, 2107, 1496, -1, 2125, 2106, 2105, -1, 2125, 2105, 2107, -1, 2126, 1466, 1370, -1, 2126, 2108, 2093, -1, 2126, 1370, 2108, -1, 2127, 2128, 2129, -1, 2126, 2093, 2130, -1, 2126, 2130, 2131, -1, 2132, 1301, 2109, -1, 2132, 1729, 1728, -1, 2132, 2109, 2112, -1, 961, 867, 959, -1, 2132, 1728, 1301, -1, 2132, 2112, 1729, -1, 2133, 2120, 1661, -1, 2133, 1661, 1589, -1, 2133, 1591, 1294, -1, 2133, 1589, 1591, -1, 2133, 1294, 2120, -1, 2134, 1413, 2135, -1, 2134, 1414, 1413, -1, 2136, 2137, 2138, -1, 2139, 2126, 2131, -1, 2139, 2140, 1466, -1, 2139, 1466, 2126, -1, 2139, 2131, 2141, -1, 2142, 1547, 1440, -1, 2142, 1631, 2143, -1, 2142, 1440, 1590, -1, 911, 910, 845, -1, 2142, 1590, 1631, -1, 2144, 2145, 1414, -1, 2144, 2134, 2135, -1, 2144, 2135, 1830, -1, 911, 845, 2099, -1, 2144, 1414, 2134, -1, 2146, 2140, 2139, -1, 2146, 2147, 2140, -1, 2146, 2139, 2141, -1, 2146, 2141, 1956, -1, 2148, 1967, 1966, -1, 2148, 2143, 1967, -1, 2148, 2142, 2143, -1, 2148, 1547, 2142, -1, 2148, 1966, 2149, -1, 2148, 2149, 1547, -1, 2150, 2145, 2144, -1, 2150, 2151, 2145, -1, 2150, 1830, 1829, -1, 2150, 2144, 1830, -1, 2152, 2096, 2098, -1, 2153, 1956, 1955, -1, 2153, 2146, 1956, -1, 2153, 2154, 2155, -1, 2153, 2155, 2147, -1, 2153, 2147, 2146, -1, 2156, 2151, 2150, -1, 2156, 1901, 2151, -1, 2156, 1829, 2157, -1, 2158, 2159, 2160, -1, 2156, 2157, 1906, -1, 2156, 1906, 1901, -1, 2158, 2160, 2104, -1, 2156, 2150, 1829, -1, 2161, 1607, 2162, -1, 2161, 2162, 2163, -1, 2161, 1608, 1607, -1, 2161, 1886, 1608, -1, 2164, 2165, 2166, -1, 2164, 2166, 1727, -1, 2164, 1727, 1984, -1, 2167, 1840, 1842, -1, 2168, 887, 874, -1, 2167, 2098, 2097, -1, 2169, 2083, 2096, -1, 2167, 2097, 1840, -1, 2167, 2170, 2171, -1, 2167, 1842, 2170, -1, 2169, 2081, 2083, -1, 2167, 2171, 2098, -1, 2172, 1939, 1941, -1, 2172, 1974, 2008, -1, 2172, 2008, 2173, -1, 2172, 2174, 1939, -1, 2172, 2173, 2174, -1, 2172, 1941, 1974, -1, 2175, 2137, 2136, -1, 2176, 2177, 2154, -1, 2176, 2153, 1955, -1, 2176, 2154, 2153, -1, 2176, 1955, 2178, -1, 2179, 1886, 2161, -1, 2179, 2163, 2180, -1, 2179, 2161, 2163, -1, 2179, 1885, 1886, -1, 2181, 2086, 2102, -1, 2182, 2165, 2164, -1, 2182, 1871, 2165, -1, 2182, 2164, 1984, -1, 2182, 1984, 2183, -1, 2184, 2180, 2185, -1, 2184, 1885, 2179, -1, 2184, 2179, 2180, -1, 2186, 2177, 2176, -1, 2186, 2016, 2177, -1, 2186, 2176, 2178, -1, 2186, 2178, 2187, -1, 2188, 2182, 2183, -1, 948, 2181, 2102, -1, 2188, 1871, 2182, -1, 2188, 1938, 1871, -1, 2188, 2183, 2189, -1, 2190, 1954, 1961, -1, 2190, 2117, 2116, -1, 2191, 2128, 2127, -1, 2192, 2046, 2193, -1, 2190, 1961, 2117, -1, 2190, 2116, 1954, -1, 2194, 2160, 2195, -1, 2194, 2195, 2076, -1, 2194, 2104, 2160, -1, 2194, 2076, 2104, -1, 2196, 2075, 2077, -1, 2196, 2185, 2075, -1, 2196, 1885, 2184, -1, 2192, 2099, 2046, -1, 2196, 2184, 2185, -1, 2196, 2077, 1885, -1, 2197, 2186, 2187, -1, 2197, 2016, 2186, -1, 2198, 1978, 1965, -1, 2198, 1965, 2129, -1, 2199, 2200, 1938, -1, 2199, 2188, 2189, -1, 2199, 2189, 2201, -1, 2199, 1938, 2188, -1, 2202, 1900, 2203, -1, 2202, 2204, 1918, -1, 2202, 1918, 1900, -1, 2205, 2016, 2197, -1, 2205, 2071, 2016, -1, 2206, 2122, 2124, -1, 2205, 2197, 2187, -1, 2205, 2187, 2207, -1, 2206, 2124, 2208, -1, 2205, 2207, 2209, -1, 2210, 2191, 2127, -1, 2211, 1978, 2198, -1, 2211, 2198, 2129, -1, 2211, 2128, 2136, -1, 2211, 2129, 2128, -1, 2211, 2138, 1978, -1, 2211, 2136, 2138, -1, 2212, 2213, 2200, -1, 2212, 2199, 2201, -1, 2212, 2200, 2199, -1, 2214, 2202, 2203, -1, 2214, 2203, 2215, -1, 2214, 2204, 2202, -1, 2216, 2137, 2175, -1, 2216, 2175, 2217, -1, 2216, 2115, 2121, -1, 2216, 2121, 2137, -1, 2218, 2209, 2219, -1, 2218, 2205, 2209, -1, 2218, 2220, 2071, -1, 2218, 2071, 2205, -1, 2221, 2222, 2213, -1, 2221, 2212, 2201, -1, 2221, 2223, 2222, -1, 2221, 2213, 2212, -1, 2221, 2201, 2223, -1, 2224, 2158, 2104, -1, 2224, 2104, 2225, -1, 2224, 2226, 2158, -1, 2224, 2225, 2226, -1, 2227, 2204, 2214, -1, 2227, 2215, 2228, -1, 2227, 2214, 2215, -1, 2227, 2229, 2204, -1, 2230, 2219, 2231, -1, 2230, 2232, 2220, -1, 2230, 2218, 2219, -1, 2230, 2220, 2218, -1, 2233, 2096, 2152, -1, 2233, 2152, 2234, -1, 2233, 2169, 2096, -1, 2235, 2216, 2217, -1, 2235, 2236, 2237, -1, 2238, 887, 2168, -1, 2235, 2237, 2115, -1, 2235, 2115, 2216, -1, 2235, 2217, 2239, -1, 2235, 2239, 2236, -1, 2240, 2241, 2242, -1, 2240, 2243, 2241, -1, 2240, 2242, 2244, -1, 2245, 2229, 2227, -1, 2245, 2228, 2246, -1, 956, 953, 955, -1, 2245, 2247, 2229, -1, 2245, 2227, 2228, -1, 2248, 2230, 2231, -1, 2248, 2232, 2230, -1, 2249, 2238, 2168, -1, 2248, 2250, 2232, -1, 2251, 2234, 2252, -1, 2251, 2169, 2233, -1, 2251, 2233, 2234, -1, 2253, 2243, 2240, -1, 2253, 2244, 2254, -1, 980, 2181, 948, -1, 2253, 2255, 2243, -1, 2253, 2240, 2244, -1, 2256, 2158, 2257, -1, 2256, 2257, 2258, -1, 2256, 2259, 2159, -1, 2256, 2159, 2158, -1, 2260, 2245, 2246, -1, 2260, 2247, 2245, -1, 2260, 2246, 2261, -1, 2262, 2263, 2264, -1, 2262, 2265, 2263, -1, 2266, 2226, 2267, -1, 2266, 2267, 2268, -1, 2266, 2269, 2270, -1, 2266, 2270, 2226, -1, 2266, 2268, 2269, -1, 2271, 2231, 2272, -1, 2271, 2250, 2248, -1, 950, 953, 956, -1, 2271, 2273, 2250, -1, 2267, 2226, 2225, -1, 2271, 2248, 2231, -1, 2274, 2242, 2241, -1, 2274, 2169, 2251, -1, 2274, 2241, 2169, -1, 2274, 2252, 2242, -1, 2274, 2251, 2252, -1, 2275, 2276, 2277, -1, 2275, 2277, 2278, -1, 2279, 2258, 2280, -1, 2281, 2193, 2282, -1, 2279, 2256, 2258, -1, 2281, 2192, 2193, -1, 2279, 2259, 2256, -1, 2283, 2253, 2254, -1, 2283, 2255, 2253, -1, 2284, 2191, 2210, -1, 2283, 2285, 2286, -1, 2283, 2286, 2255, -1, 2283, 2254, 2285, -1, 2287, 2288, 2289, -1, 2287, 2261, 2288, -1, 2287, 2289, 2247, -1, 2287, 2260, 2261, -1, 2287, 2247, 2260, -1, 2290, 2271, 2272, -1, 2290, 2272, 2291, -1, 2290, 2292, 2273, -1, 2290, 2273, 2271, -1, 2293, 2268, 2276, -1, 2293, 2276, 2275, -1, 2293, 2275, 2278, -1, 2293, 2278, 2294, -1, 2293, 2294, 2295, -1, 2296, 2279, 2280, -1, 2296, 2280, 2297, -1, 2296, 2259, 2279, -1, 2296, 2298, 2259, -1, 2299, 2262, 2264, -1, 1000, 2206, 2208, -1, 2299, 2300, 2262, -1, 1000, 2208, 986, -1, 2299, 2264, 2301, -1, 2299, 2301, 2302, -1, 2299, 2302, 2303, -1, 2304, 2291, 2305, -1, 2304, 2306, 2292, -1, 2304, 2292, 2290, -1, 2304, 2290, 2291, -1, 2307, 2308, 2309, -1, 2307, 2310, 2311, -1, 2307, 2311, 2308, -1, 2307, 2309, 2310, -1, 2312, 2296, 2297, -1, 2312, 2297, 2313, -1, 2312, 2314, 2298, -1, 2312, 2298, 2296, -1, 2312, 2313, 2314, -1, 2259, 2284, 2210, -1, 2315, 2269, 2268, -1, 2315, 2268, 2293, -1, 2315, 2293, 2295, -1, 2316, 2317, 2318, -1, 2316, 2319, 2317, -1, 2320, 2306, 2304, -1, 1021, 1020, 915, -1, 2320, 2304, 2305, -1, 1021, 915, 887, -1, 2321, 2322, 2323, -1, 2321, 2299, 2303, -1, 2321, 2324, 2300, -1, 2321, 2303, 2322, -1, 2321, 2300, 2299, -1, 2325, 974, 960, -1, 2326, 2315, 2295, -1, 2326, 2269, 2315, -1, 2326, 2327, 2328, -1, 2326, 2328, 2269, -1, 2326, 2295, 2329, -1, 2330, 2331, 2332, -1, 2330, 2332, 2319, -1, 2330, 2318, 2333, -1, 2330, 2316, 2318, -1, 2330, 2319, 2316, -1, 2330, 2333, 2331, -1, 2334, 2335, 2306, -1, 2336, 2337, 2289, -1, 2334, 2305, 2338, -1, 2334, 2306, 2320, -1, 2334, 2338, 2339, -1, 2334, 2320, 2305, -1, 2340, 2246, 2228, -1, 2341, 2342, 2343, -1, 1007, 2344, 1008, -1, 2341, 2343, 2345, -1, 2341, 2345, 2346, -1, 2347, 2321, 2323, -1, 2347, 2348, 2324, -1, 2347, 2324, 2321, -1, 2349, 2238, 2249, -1, 2350, 2309, 2351, -1, 2350, 2352, 2309, -1, 2350, 2353, 2352, -1, 2350, 2351, 2353, -1, 2354, 2355, 2327, -1, 2354, 2327, 2326, -1, 2354, 2326, 2329, -1, 2354, 2356, 2355, -1, 2354, 2329, 2356, -1, 2357, 2335, 2334, -1, 2357, 2334, 2339, -1, 2357, 2339, 2358, -1, 2357, 2359, 2335, -1, 975, 983, 976, -1, 2360, 2361, 2342, -1, 2360, 2362, 2361, -1, 2360, 2341, 2346, -1, 2360, 2342, 2341, -1, 2363, 2347, 2323, -1, 2363, 2323, 2364, -1, 2363, 2365, 2348, -1, 2363, 2348, 2347, -1, 2366, 2367, 2368, -1, 2366, 2369, 2367, -1, 992, 951, 950, -1, 2366, 2370, 2371, -1, 992, 1040, 951, -1, 2366, 2368, 2370, -1, 2366, 2371, 2372, -1, 2373, 2357, 2358, -1, 2373, 2359, 2357, -1, 2373, 2358, 2374, -1, 2373, 2374, 2375, -1, 2373, 2376, 2359, -1, 2373, 2375, 2376, -1, 2377, 2378, 2379, -1, 2377, 2379, 2380, -1, 2377, 2380, 2381, -1, 2377, 2382, 2378, -1, 2383, 2222, 2223, -1, 2384, 2360, 2346, -1, 2384, 2385, 2362, -1, 2384, 2362, 2360, -1, 2384, 2346, 2386, -1, 2387, 2349, 2249, -1, 2384, 2386, 2385, -1, 2388, 2364, 2389, -1, 2388, 2389, 2390, -1, 2388, 2363, 2364, -1, 2388, 2365, 2363, -1, 2388, 2390, 2365, -1, 984, 983, 975, -1, 2391, 2392, 2393, -1, 2391, 2366, 2372, -1, 2391, 2369, 2366, -1, 2391, 2393, 2369, -1, 2391, 2372, 2392, -1, 2394, 2382, 2377, -1, 2394, 2395, 2382, -1, 2394, 2377, 2381, -1, 2394, 2381, 2395, -1, 2396, 2397, 2352, -1, 2396, 2352, 2398, -1, 2396, 2398, 2399, -1, 2396, 2400, 2397, -1, 2401, 2402, 2351, -1, 2401, 2351, 2403, -1, 2401, 2403, 2404, -1, 2401, 2405, 2402, -1, 2401, 2404, 2405, -1, 2406, 2407, 2408, -1, 2406, 2409, 2407, -1, 2410, 2411, 2412, -1, 2298, 2284, 2259, -1, 2410, 2413, 2411, -1, 2410, 2412, 2414, -1, 1024, 2282, 1020, -1, 2410, 2414, 2415, -1, 2410, 2415, 2413, -1, 2416, 2399, 2417, -1, 2416, 2400, 2396, -1, 1024, 2281, 2282, -1, 2416, 2396, 2399, -1, 2418, 2408, 2419, -1, 2418, 2419, 2420, -1, 2418, 2406, 2408, -1, 2421, 974, 2325, -1, 2418, 2404, 2409, -1, 2418, 2409, 2406, -1, 2422, 2423, 2400, -1, 2422, 2417, 2424, -1, 2422, 2400, 2416, -1, 2425, 2336, 2289, -1, 2422, 2416, 2417, -1, 2426, 2390, 2427, -1, 2426, 2428, 2429, -1, 2426, 2429, 2390, -1, 2430, 2404, 2418, -1, 2430, 2405, 2404, -1, 2430, 2418, 2420, -1, 2431, 2422, 2424, -1, 2431, 2423, 2422, -1, 2431, 2424, 2432, -1, 2431, 2433, 2423, -1, 2434, 2427, 2435, -1, 2434, 2428, 2426, -1, 2434, 2426, 2427, -1, 2436, 2421, 2325, -1, 2437, 2412, 2411, -1, 2437, 2438, 2439, -1, 2437, 2411, 2438, -1, 2437, 2439, 2412, -1, 2440, 2441, 2442, -1, 2288, 2425, 2289, -1, 2440, 2442, 2443, -1, 2440, 2443, 2444, -1, 2445, 2446, 2447, -1, 2445, 2447, 2448, -1, 2449, 2450, 2451, -1, 2449, 2432, 2450, -1, 2449, 2451, 2433, -1, 2452, 2246, 2340, -1, 2449, 2431, 2432, -1, 2449, 2433, 2431, -1, 2453, 2454, 2455, -1, 2453, 2456, 2457, -1, 2453, 2458, 2456, -1, 2453, 2455, 2458, -1, 2453, 2457, 2459, -1, 2453, 2459, 2454, -1, 2460, 2420, 2461, -1, 2460, 2405, 2430, -1, 2460, 2462, 2463, -1, 2460, 2463, 2405, -1, 2460, 2430, 2420, -1, 2464, 2434, 2435, -1, 2464, 2428, 2434, -1, 2464, 2435, 2465, -1, 2464, 2466, 2428, -1, 2464, 2465, 2467, -1, 2468, 2444, 2469, -1, 2470, 2222, 2383, -1, 2468, 2440, 2444, -1, 2468, 2471, 2441, -1, 2468, 2441, 2440, -1, 2472, 2448, 2473, -1, 2472, 2473, 2474, -1, 2472, 2475, 2446, -1, 2472, 2474, 2475, -1, 2472, 2445, 2448, -1, 2476, 2452, 2340, -1, 2472, 2446, 2445, -1, 2477, 2349, 2387, -1, 2478, 2479, 2466, -1, 2478, 2466, 2464, -1, 2478, 2464, 2467, -1, 2480, 2481, 2482, -1, 2480, 2461, 2481, -1, 2483, 2484, 1015, -1, 2480, 2460, 2461, -1, 2480, 2482, 2462, -1, 2480, 2462, 2460, -1, 2485, 2471, 2468, -1, 2485, 2486, 2471, -1, 2485, 2468, 2469, -1, 2485, 2469, 2487, -1, 2488, 2489, 2490, -1, 2488, 2490, 2491, -1, 2488, 2492, 2489, -1, 2493, 2425, 2288, -1, 2488, 2491, 2492, -1, 2494, 2479, 2478, -1, 2494, 2467, 2495, -1, 2494, 2478, 2467, -1, 2496, 2231, 2497, -1, 2494, 2498, 2479, -1, 2499, 2500, 2501, -1, 2496, 2272, 2231, -1, 2499, 2502, 2500, -1, 2499, 2501, 2503, -1, 2499, 2503, 2504, -1, 2505, 2486, 2485, -1, 2505, 2506, 2486, -1, 2505, 2485, 2487, -1, 2507, 2508, 2498, -1, 2317, 2236, 2239, -1, 2507, 2498, 2494, -1, 2507, 2495, 2509, -1, 2507, 2509, 2508, -1, 2507, 2494, 2495, -1, 2510, 2511, 2502, -1, 2510, 2499, 2504, -1, 2510, 2504, 2511, -1, 2510, 2502, 2499, -1, 2512, 2487, 2513, -1, 2512, 2506, 2505, -1, 2512, 2514, 2506, -1, 2512, 2505, 2487, -1, 2319, 2236, 2317, -1, 2515, 2516, 2517, -1, 2515, 2517, 2518, -1, 2515, 2519, 2516, -1, 2515, 2520, 2519, -1, 2521, 2522, 2523, -1, 2521, 2523, 2524, -1, 2521, 2525, 2522, -1, 2521, 2524, 2526, -1, 2521, 2526, 2525, -1, 2527, 2528, 2529, -1, 2527, 2529, 2482, -1, 2527, 2482, 2530, -1, 2531, 2512, 2513, -1, 2531, 2532, 2514, -1, 2531, 2514, 2512, -1, 2531, 2513, 2532, -1, 2533, 2520, 2515, -1, 2533, 2518, 2534, -1, 2278, 2277, 2222, -1, 2278, 2222, 2470, -1, 2533, 2515, 2518, -1, 2535, 2530, 2536, -1, 2535, 2537, 2528, -1, 2535, 2528, 2527, -1, 2535, 2527, 2530, -1, 2538, 2539, 2540, -1, 2541, 2421, 2436, -1, 2538, 2542, 2543, -1, 2538, 2540, 2542, -1, 2538, 2543, 2544, -1, 2545, 2508, 2546, -1, 2545, 2547, 2508, -1, 2545, 2548, 2547, -1, 2549, 2533, 2534, -1, 2549, 2534, 2550, -1, 2549, 2551, 2520, -1, 2549, 2520, 2533, -1, 2552, 2536, 2553, -1, 2552, 2537, 2535, -1, 2552, 2535, 2536, -1, 2554, 2555, 2539, -1, 2554, 2538, 2544, -1, 2554, 2539, 2538, -1, 2556, 2557, 2558, -1, 1014, 2483, 1015, -1, 2556, 2559, 2560, -1, 2556, 2561, 2557, -1, 2556, 2558, 2559, -1, 2562, 2523, 2522, -1, 2562, 2563, 2564, -1, 2562, 2522, 2563, -1, 2562, 2564, 2523, -1, 2565, 2548, 2545, -1, 2566, 2254, 2244, -1, 2565, 2545, 2546, -1, 2565, 2546, 2567, -1, 2568, 2551, 2549, -1, 2568, 2549, 2550, -1, 2568, 2569, 2551, -1, 2570, 2571, 2572, -1, 1039, 2541, 2436, -1, 2570, 2553, 2573, -1, 2570, 2537, 2552, -1, 2570, 2572, 2537, -1, 2570, 2552, 2553, -1, 2574, 2544, 2575, -1, 2574, 2555, 2554, -1, 2574, 2575, 2555, -1, 2574, 2554, 2544, -1, 2576, 2577, 2578, -1, 2576, 2579, 2577, -1, 2576, 2580, 2579, -1, 2581, 2548, 2565, -1, 2581, 2567, 2582, -1, 2583, 965, 964, -1, 2581, 2584, 2548, -1, 2581, 2565, 2567, -1, 2583, 964, 2585, -1, 2586, 2587, 2561, -1, 2588, 2452, 2476, -1, 2586, 2556, 2560, -1, 2586, 2560, 2587, -1, 2586, 2561, 2556, -1, 2589, 2590, 2591, -1, 2589, 2592, 2593, -1, 2589, 2593, 2594, -1, 2589, 2591, 2592, -1, 2595, 2569, 2568, -1, 2595, 2550, 2596, -1, 2595, 2596, 2597, -1, 2595, 2597, 2598, -1, 2306, 2588, 2476, -1, 2595, 2599, 2569, -1, 2595, 2568, 2550, -1, 2595, 2598, 2599, -1, 2600, 2601, 2571, -1, 2600, 2571, 2570, -1, 2600, 2570, 2573, -1, 2602, 2578, 2603, -1, 2604, 2470, 2383, -1, 2602, 2576, 2578, -1, 2602, 2605, 2580, -1, 2604, 2383, 2606, -1, 2602, 2580, 2576, -1, 2607, 2584, 2581, -1, 2607, 2581, 2582, -1, 2607, 2608, 2584, -1, 2607, 2582, 2609, -1, 2610, 2611, 2590, -1, 2610, 2594, 2612, -1, 2610, 2589, 2594, -1, 2610, 2590, 2589, -1, 2613, 2614, 2601, -1, 2613, 2573, 2615, -1, 1031, 2387, 1004, -1, 2613, 2600, 2573, -1, 1031, 2477, 2387, -1, 2613, 2615, 2614, -1, 2613, 2601, 2600, -1, 2616, 2617, 2618, -1, 2616, 2619, 2620, -1, 1072, 2477, 1031, -1, 2616, 2620, 2617, -1, 2616, 2618, 2619, -1, 2621, 2607, 2609, -1, 2621, 2609, 2622, -1, 2621, 2623, 2608, -1, 2621, 2608, 2607, -1, 2624, 2497, 2625, -1, 2626, 2605, 2602, -1, 2624, 2496, 2497, -1, 2626, 2627, 2628, -1, 2626, 2628, 2605, -1, 2626, 2602, 2603, -1, 2626, 2603, 2629, -1, 1050, 991, 990, -1, 2630, 2631, 2632, -1, 2630, 2632, 2633, -1, 2630, 2633, 2634, -1, 2635, 2636, 2637, -1, 2635, 2637, 2638, -1, 2635, 2638, 2639, -1, 2640, 2641, 2611, -1, 2640, 2612, 2642, -1, 2640, 2610, 2612, -1, 2640, 2611, 2610, -1, 2643, 2621, 2622, -1, 2644, 994, 995, -1, 2643, 2623, 2621, -1, 2643, 2645, 2623, -1, 2643, 2622, 2646, -1, 2643, 2646, 2645, -1, 2647, 2629, 2648, -1, 2647, 2649, 2627, -1, 1037, 2650, 1024, -1, 2647, 2627, 2626, -1, 2647, 2626, 2629, -1, 2651, 2631, 2630, -1, 2651, 2652, 2653, -1, 2651, 2630, 2634, -1, 2651, 2634, 2652, -1, 2651, 2653, 2631, -1, 2654, 2636, 2635, -1, 2654, 2655, 2636, -1, 2654, 2635, 2639, -1, 2656, 2642, 2657, -1, 2656, 2641, 2640, -1, 2656, 2640, 2642, -1, 2658, 2659, 2649, -1, 1070, 2541, 1039, -1, 2658, 2647, 2648, -1, 2658, 2649, 2647, -1, 2658, 2648, 2659, -1, 2660, 2661, 2614, -1, 2660, 2614, 2662, -1, 2663, 2254, 2566, -1, 2664, 2665, 2666, -1, 2664, 2667, 2668, -1, 2664, 2666, 2667, -1, 2669, 2670, 2671, -1, 2669, 2672, 2673, -1, 2669, 2671, 2672, -1, 2674, 2650, 1037, -1, 2669, 2673, 2670, -1, 2675, 2655, 2654, -1, 2674, 1058, 2650, -1, 2675, 2676, 2677, -1, 2675, 2677, 2655, -1, 2675, 2678, 2676, -1, 2675, 2639, 2678, -1, 2675, 2654, 2639, -1, 2679, 2583, 2585, -1, 2680, 2657, 2681, -1, 2680, 2641, 2656, -1, 2680, 2682, 2641, -1, 2313, 2308, 2314, -1, 2680, 2656, 2657, -1, 2679, 2585, 2683, -1, 2684, 2685, 2686, -1, 2684, 2687, 2685, -1, 2684, 2686, 2688, -1, 2684, 2689, 2687, -1, 2690, 2662, 2691, -1, 2690, 2691, 2692, -1, 2690, 2692, 2693, -1, 2690, 2694, 2661, -1, 2690, 2661, 2660, -1, 2690, 2693, 2694, -1, 2695, 2663, 2566, -1, 2690, 2660, 2662, -1, 2696, 2697, 2698, -1, 2335, 2588, 2306, -1, 2696, 2698, 2645, -1, 2696, 2645, 2699, -1, 2700, 2665, 2664, -1, 2700, 2701, 2702, -1, 2700, 2668, 2701, -1, 2700, 2664, 2668, -1, 2703, 2681, 2704, -1, 2703, 2705, 2682, -1, 2703, 2680, 2681, -1, 2703, 2682, 2680, -1, 2706, 2684, 2688, -1, 2706, 2707, 2689, -1, 1059, 1058, 2674, -1, 2706, 2689, 2684, -1, 2706, 2688, 2707, -1, 2708, 2709, 2665, -1, 2708, 2665, 2700, -1, 2708, 2700, 2702, -1, 2309, 2308, 2313, -1, 2710, 2697, 2696, -1, 2711, 994, 2644, -1, 2710, 2696, 2699, -1, 2710, 2699, 2712, -1, 2713, 2714, 2715, -1, 2713, 2715, 2705, -1, 2713, 2705, 2703, -1, 2713, 2704, 2716, -1, 2713, 2703, 2704, -1, 2717, 2606, 2718, -1, 2719, 2720, 2721, -1, 2719, 2721, 2722, -1, 2719, 2723, 2720, -1, 2717, 2604, 2606, -1, 2724, 2725, 2726, -1, 2724, 2727, 2728, -1, 2724, 2728, 2725, -1, 2724, 2726, 2727, -1, 2729, 2708, 2702, -1, 2729, 2709, 2708, -1, 2729, 2702, 2730, -1, 2729, 2730, 2709, -1, 2731, 2732, 2697, -1, 2731, 2710, 2712, -1, 2731, 2697, 2710, -1, 2731, 2712, 2733, -1, 2734, 2714, 2713, -1, 2734, 2713, 2716, -1, 2735, 2719, 2722, -1, 2735, 2722, 2736, -1, 2735, 2723, 2719, -1, 2735, 2737, 2723, -1, 2738, 2739, 2732, -1, 2738, 2733, 2740, -1, 2738, 2732, 2731, -1, 2738, 2731, 2733, -1, 2361, 2625, 2342, -1, 2741, 2734, 2716, -1, 1056, 994, 2711, -1, 2741, 2742, 2714, -1, 2741, 2714, 2734, -1, 2361, 2624, 2625, -1, 2741, 2716, 2743, -1, 1056, 1054, 994, -1, 2744, 2735, 2736, -1, 2744, 2737, 2735, -1, 2744, 2745, 2746, -1, 2744, 2746, 2737, -1, 1092, 1027, 1026, -1, 2744, 2736, 2747, -1, 2748, 2739, 2738, -1, 2748, 2738, 2740, -1, 2748, 2740, 2749, -1, 2748, 2750, 2739, -1, 2751, 2752, 2742, -1, 2751, 2741, 2743, -1, 2751, 2742, 2741, -1, 2751, 2743, 2753, -1, 2754, 2755, 2756, -1, 2754, 2756, 2757, -1, 2754, 2757, 2758, -1, 2759, 2748, 2749, -1, 2759, 2760, 2750, -1, 2759, 2750, 2748, -1, 1095, 1027, 1092, -1, 2759, 2749, 2760, -1, 2761, 2762, 2763, -1, 2761, 2764, 2762, -1, 2379, 2378, 2285, -1, 2379, 2285, 2254, -1, 2761, 2765, 2764, -1, 2766, 2767, 2768, -1, 2766, 2769, 2767, -1, 2766, 2768, 2770, -1, 2771, 2333, 2318, -1, 2766, 2770, 2769, -1, 2772, 2773, 2774, -1, 2772, 2775, 2776, -1, 2772, 2776, 2777, -1, 2772, 2778, 2773, -1, 2772, 2777, 2778, -1, 2772, 2774, 2775, -1, 2779, 2747, 2780, -1, 2779, 2781, 2745, -1, 1062, 2782, 1060, -1, 2779, 2745, 2744, -1, 2779, 2744, 2747, -1, 2783, 2752, 2751, -1, 2783, 2753, 2784, -1, 2783, 2785, 2752, -1, 2783, 2751, 2753, -1, 2786, 2787, 2788, -1, 2786, 2789, 2787, -1, 2367, 2790, 2368, -1, 2786, 2791, 2792, -1, 2786, 2792, 2789, -1, 2793, 2794, 2795, -1, 2793, 2795, 2755, -1, 1088, 2679, 2683, -1, 2793, 2754, 2758, -1, 2793, 2755, 2754, -1, 1088, 2683, 1035, -1, 2793, 2758, 2794, -1, 2796, 2763, 2787, -1, 2797, 2663, 2695, -1, 2796, 2787, 2765, -1, 2796, 2765, 2761, -1, 2796, 2761, 2763, -1, 2798, 2785, 2783, -1, 2798, 2783, 2784, -1, 2331, 2343, 2332, -1, 2798, 2784, 2799, -1, 2800, 2779, 2780, -1, 2800, 2781, 2779, -1, 2800, 2780, 2801, -1, 2800, 2801, 2781, -1, 2802, 2803, 2791, -1, 2802, 2788, 2804, -1, 2802, 2786, 2788, -1, 2802, 2791, 2786, -1, 2805, 2806, 2807, -1, 2805, 2807, 2808, -1, 2805, 2809, 2806, -1, 2805, 2808, 2809, -1, 2810, 2811, 2812, -1, 2810, 2813, 2814, -1, 2810, 2812, 2813, -1, 2815, 2798, 2799, -1, 2815, 2785, 2798, -1, 2815, 2816, 2785, -1, 2815, 2799, 2817, -1, 2818, 2811, 2810, -1, 2818, 2814, 2819, -1, 2820, 2711, 2644, -1, 2818, 2810, 2814, -1, 2352, 2397, 2310, -1, 2352, 2310, 2309, -1, 2820, 2644, 2821, -1, 2822, 2804, 2823, -1, 2822, 2803, 2802, -1, 2822, 2802, 2804, -1, 2822, 2824, 2803, -1, 2825, 2826, 2827, -1, 2825, 2827, 2828, -1, 2825, 2828, 2829, -1, 2830, 2815, 2817, -1, 2830, 2816, 2815, -1, 2830, 2831, 2816, -1, 2830, 2817, 2832, -1, 2833, 2797, 2695, -1, 2830, 2832, 2831, -1, 2834, 2835, 2811, -1, 2834, 2818, 2819, -1, 2834, 2819, 2836, -1, 2834, 2811, 2818, -1, 2837, 2822, 2823, -1, 2837, 2823, 2838, -1, 2345, 2343, 2331, -1, 2837, 2824, 2822, -1, 2837, 2838, 2824, -1, 2839, 2826, 2825, -1, 2839, 2829, 2840, -1, 2839, 2825, 2829, -1, 2841, 2842, 2843, -1, 2841, 2844, 2842, -1, 2841, 2843, 2845, -1, 2841, 2845, 2844, -1, 2846, 2847, 2848, -1, 2846, 2848, 2849, -1, 2846, 2850, 2847, -1, 2851, 2835, 2834, -1, 2851, 2836, 2852, -1, 2851, 2834, 2836, -1, 2851, 2852, 2835, -1, 2853, 2854, 2855, -1, 2853, 2855, 2831, -1, 2853, 2856, 2857, -1, 2853, 2831, 2832, -1, 2853, 2832, 2856, -1, 2853, 2858, 2854, -1, 2853, 2857, 2858, -1, 2859, 2826, 2839, -1, 2859, 2839, 2840, -1, 2859, 2860, 2826, -1, 2382, 2718, 2378, -1, 2382, 2717, 2718, -1, 2859, 2840, 2861, -1, 2862, 2333, 2771, -1, 2863, 2850, 2846, -1, 2863, 2849, 2864, -1, 2863, 2846, 2849, -1, 2863, 2865, 2850, -1, 2866, 2867, 2868, -1, 2866, 2868, 2869, -1, 2866, 2870, 2867, -1, 2871, 2872, 2854, -1, 2871, 2854, 2858, -1, 2871, 2858, 2873, -1, 2874, 2860, 2859, -1, 2874, 2875, 2860, -1, 2874, 2859, 2861, -1, 2874, 2861, 2876, -1, 2877, 2863, 2864, -1, 2877, 2865, 2863, -1, 2877, 2878, 2865, -1, 2879, 2866, 2869, -1, 2879, 2869, 2880, -1, 2879, 2870, 2866, -1, 2881, 2862, 2771, -1, 2882, 2883, 2872, -1, 2882, 2871, 2873, -1, 2882, 2872, 2871, -1, 2882, 2873, 2884, -1, 2885, 2875, 2874, -1, 2885, 2876, 2886, -1, 2885, 2874, 2876, -1, 2887, 2857, 2856, -1, 2887, 2888, 2889, -1, 2887, 2856, 2888, -1, 2887, 2889, 2857, -1, 2890, 2877, 2864, -1, 2890, 2878, 2877, -1, 2890, 2864, 2891, -1, 2890, 2892, 2878, -1, 2893, 2894, 2870, -1, 2893, 2895, 2894, -1, 2893, 2880, 2895, -1, 2893, 2879, 2880, -1, 2893, 2870, 2879, -1, 2896, 2882, 2884, -1, 2896, 2883, 2882, -1, 2896, 2884, 2897, -1, 2898, 2875, 2885, -1, 2898, 2886, 2899, -1, 2898, 2900, 2875, -1, 2898, 2901, 2900, -1, 2898, 2885, 2886, -1, 2898, 2899, 2901, -1, 2902, 2890, 2891, -1, 2902, 2891, 2903, -1, 2902, 2892, 2890, -1, 2902, 2904, 2892, -1, 2905, 2906, 2907, -1, 2905, 2907, 2908, -1, 2905, 2909, 2906, -1, 2905, 2910, 2909, -1, 2911, 2896, 2897, -1, 2912, 2797, 2833, -1, 2911, 2883, 2896, -1, 2911, 2913, 2883, -1, 2911, 2897, 2914, -1, 2915, 2902, 2903, -1, 2915, 2903, 2916, -1, 2915, 2904, 2902, -1, 1137, 1084, 1085, -1, 2915, 2916, 2904, -1, 2917, 2918, 2376, -1, 2919, 2920, 2921, -1, 2919, 2921, 2922, -1, 2919, 2922, 2923, -1, 2924, 2911, 2914, -1, 2924, 2913, 2911, -1, 2924, 2925, 2913, -1, 2924, 2914, 2926, -1, 2927, 2928, 2910, -1, 2927, 2910, 2905, -1, 2927, 2905, 2908, -1, 2929, 2920, 2919, -1, 2929, 2923, 2930, -1, 2931, 2821, 2932, -1, 2929, 2919, 2923, -1, 2933, 2924, 2926, -1, 2931, 2820, 2821, -1, 2933, 2925, 2924, -1, 2933, 2934, 2925, -1, 2933, 2935, 2934, -1, 2933, 2926, 2935, -1, 2936, 2937, 2938, -1, 2936, 2938, 2928, -1, 2936, 2927, 2908, -1, 2936, 2908, 2939, -1, 1098, 2940, 2941, -1, 1098, 2941, 1097, -1, 2936, 2928, 2927, -1, 2942, 2930, 2943, -1, 2942, 2929, 2930, -1, 2942, 2944, 2920, -1, 2942, 2920, 2929, -1, 2945, 2946, 2947, -1, 2945, 2948, 2946, -1, 2945, 2947, 2949, -1, 2950, 2951, 2952, -1, 2950, 2953, 2951, -1, 2950, 2954, 2953, -1, 2955, 1035, 1034, -1, 2950, 2952, 2956, -1, 2950, 2956, 2934, -1, 2950, 2934, 2935, -1, 2950, 2935, 2954, -1, 2955, 1088, 1035, -1, 2957, 2944, 2942, -1, 2957, 2958, 2944, -1, 2957, 2943, 2958, -1, 2957, 2942, 2943, -1, 2959, 2936, 2939, -1, 2959, 24, 2937, -1, 2959, 2939, 2960, -1, 2959, 2960, 24, -1, 2959, 2937, 2936, -1, 2961, 2962, 2963, -1, 2961, 2964, 2965, -1, 2961, 2965, 2962, -1, 2966, 2967, 2968, -1, 2966, 2969, 2970, -1, 2966, 2968, 2969, -1, 2971, 2948, 2945, -1, 2971, 2949, 2972, -1, 2971, 2972, 2973, -1, 2971, 2945, 2949, -1, 2971, 2973, 2948, -1, 2974, 2964, 2961, -1, 2974, 2961, 2963, -1, 2974, 2975, 2976, -1, 2974, 2963, 2977, -1, 1142, 2782, 1062, -1, 2974, 2977, 2975, -1, 2974, 2976, 2964, -1, 1142, 1145, 2782, -1, 2978, 2952, 2951, -1, 2979, 2862, 2881, -1, 2978, 2951, 2980, -1, 2978, 2981, 2952, -1, 2982, 2966, 2970, -1, 2982, 2983, 2967, -1, 2982, 2970, 2984, -1, 2982, 2967, 2966, -1, 2985, 2984, 2986, -1, 2985, 2983, 2982, -1, 2985, 2982, 2984, -1, 2987, 2980, 2988, -1, 2987, 2978, 2980, -1, 2987, 2981, 2978, -1, 2987, 2989, 2981, -1, 2990, 2991, 2992, -1, 2993, 2954, 32, -1, 2993, 34, 2953, -1, 2993, 2953, 2954, -1, 2993, 32, 34, -1, 2994, 1122, 1093, -1, 2995, 66, 68, -1, 2995, 10, 66, -1, 2375, 2917, 2376, -1, 2995, 68, 2996, -1, 2995, 2996, 11, -1, 2995, 11, 10, -1, 2997, 2985, 2986, -1, 2997, 2986, 12, -1, 2997, 2998, 2983, -1, 2997, 2983, 2985, -1, 1135, 1084, 1137, -1, 2997, 12, 2998, -1, 2999, 2988, 3000, -1, 2999, 2989, 2987, -1, 2999, 2987, 2988, -1, 3001, 33, 45, -1, 3001, 44, 3002, -1, 3001, 3002, 3003, -1, 3001, 45, 44, -1, 3004, 2999, 3000, -1, 3004, 3000, 3005, -1, 1089, 1088, 2955, -1, 3004, 2989, 2999, -1, 3004, 3006, 2989, -1, 3007, 3008, 3009, -1, 3007, 3009, 3010, -1, 2400, 2979, 2881, -1, 3007, 3010, 3011, -1, 3012, 3001, 3003, -1, 3012, 33, 3001, -1, 3012, 31, 33, -1, 3013, 3005, 3014, -1, 3013, 3004, 3005, -1, 3013, 3006, 3004, -1, 3015, 2323, 2322, -1, 3013, 3016, 3006, -1, 3017, 107, 106, -1, 3017, 66, 10, -1, 3017, 10, 107, -1, 1160, 1163, 2940, -1, 3017, 106, 66, -1, 3015, 2322, 3018, -1, 1160, 2940, 1098, -1, 3019, 3008, 3007, -1, 3019, 3007, 3011, -1, 3019, 3011, 135, -1, 3020, 3016, 3013, -1, 3020, 3014, 184, -1, 3020, 3013, 3014, -1, 3020, 3021, 3016, -1, 3022, 3012, 3003, -1, 3022, 3023, 3024, -1, 3022, 3024, 31, -1, 3022, 3003, 3025, -1, 3022, 31, 3012, -1, 3026, 3019, 135, -1, 3026, 135, 134, -1, 3026, 163, 3008, -1, 3026, 3008, 3019, -1, 3027, 3021, 3020, -1, 3027, 3020, 184, -1, 3027, 3028, 3029, -1, 3027, 3029, 3021, -1, 3030, 3022, 3025, -1, 3030, 211, 3023, -1, 3030, 3025, 212, -1, 3030, 3023, 3022, -1, 3030, 212, 211, -1, 3031, 155, 67, -1, 3031, 121, 3032, -1, 3031, 67, 121, -1, 3033, 3026, 134, -1, 2390, 2912, 2833, -1, 3033, 134, 164, -1, 3033, 163, 3026, -1, 2390, 2833, 2365, -1, 3033, 164, 163, -1, 3034, 105, 180, -1, 1155, 2931, 2932, -1, 3034, 201, 140, -1, 3034, 140, 105, -1, 1155, 2932, 1145, -1, 3034, 180, 201, -1, 2429, 2912, 2390, -1, 3035, 3027, 184, -1, 3035, 3028, 3027, -1, 3035, 184, 188, -1, 3036, 3032, 3037, -1, 3036, 3031, 3032, -1, 3036, 155, 3031, -1, 3038, 3035, 188, -1, 3038, 188, 3039, -1, 3040, 2990, 2992, -1, 3038, 3028, 3035, -1, 3038, 3041, 3028, -1, 3042, 3036, 3037, -1, 3042, 3037, 3043, -1, 3042, 154, 155, -1, 2402, 2353, 2351, -1, 3042, 155, 3036, -1, 3044, 3038, 3039, -1, 3044, 3041, 3038, -1, 3044, 3039, 3045, -1, 3044, 199, 3041, -1, 3046, 262, 3047, -1, 3046, 3047, 226, -1, 3046, 230, 260, -1, 3046, 226, 230, -1, 3046, 260, 262, -1, 3048, 154, 3042, -1, 3049, 2355, 2356, -1, 3048, 3043, 225, -1, 3048, 227, 154, -1, 3048, 225, 227, -1, 3048, 3042, 3043, -1, 3050, 3044, 3045, -1, 3050, 3045, 3051, -1, 2395, 3052, 2382, -1, 3053, 2992, 1124, -1, 3050, 199, 3044, -1, 3054, 256, 255, -1, 3053, 1124, 1123, -1, 3054, 243, 3055, -1, 3054, 3055, 256, -1, 3054, 255, 3056, -1, 3053, 3040, 2992, -1, 3057, 1122, 2994, -1, 3058, 199, 3050, -1, 3058, 3051, 3059, -1, 3058, 228, 199, -1, 3058, 3050, 3051, -1, 3060, 3056, 3061, -1, 3060, 3054, 3056, -1, 3060, 243, 3054, -1, 3062, 295, 294, -1, 3062, 230, 295, -1, 3062, 260, 230, -1, 3062, 294, 260, -1, 2423, 2979, 2400, -1, 3063, 3058, 3059, -1, 3063, 3059, 3064, -1, 3063, 3065, 228, -1, 3063, 228, 3058, -1, 3066, 3067, 242, -1, 3066, 243, 3060, -1, 3068, 3057, 2994, -1, 3066, 242, 243, -1, 3066, 3061, 3069, -1, 3066, 3060, 3061, -1, 3070, 3063, 3064, -1, 3070, 286, 280, -1, 3070, 3064, 3071, -1, 3072, 3052, 2395, -1, 3070, 3071, 286, -1, 3070, 280, 3065, -1, 3070, 3065, 3063, -1, 3072, 2413, 3052, -1, 3073, 3074, 3067, -1, 3075, 3015, 3018, -1, 3073, 3066, 3069, -1, 3073, 3067, 3066, -1, 3076, 3073, 3069, -1, 3076, 374, 3074, -1, 3076, 3077, 374, -1, 3076, 3074, 3073, -1, 3076, 3069, 3077, -1, 3078, 261, 289, -1, 3078, 288, 261, -1, 3075, 3018, 3079, -1, 3078, 289, 3080, -1, 3081, 293, 296, -1, 3081, 314, 317, -1, 3081, 296, 314, -1, 3081, 317, 293, -1, 3082, 3040, 3053, -1, 3083, 288, 3078, -1, 3083, 3078, 3080, -1, 3083, 3080, 3084, -1, 3085, 288, 3083, -1, 3085, 306, 288, -1, 3086, 1098, 3087, -1, 3085, 3083, 3084, -1, 3085, 3084, 3088, -1, 3089, 3085, 3088, -1, 3086, 1160, 1098, -1, 3089, 306, 3085, -1, 3089, 327, 329, -1, 3089, 3088, 327, -1, 3089, 329, 306, -1, 3090, 374, 3077, -1, 3090, 3077, 357, -1, 3091, 372, 3092, -1, 3091, 3092, 3093, -1, 2411, 2413, 3072, -1, 3091, 3093, 381, -1, 3091, 350, 373, -1, 3091, 381, 350, -1, 3091, 373, 372, -1, 3094, 356, 372, -1, 3094, 3090, 357, -1, 3094, 374, 3090, -1, 3094, 357, 356, -1, 3095, 2355, 3049, -1, 3094, 372, 374, -1, 3096, 364, 404, -1, 3096, 402, 364, -1, 3096, 404, 3097, -1, 1107, 1194, 1101, -1, 3098, 3096, 3097, -1, 3098, 402, 3096, -1, 3098, 3097, 3099, -1, 3100, 412, 402, -1, 3100, 3098, 3099, -1, 3100, 402, 3098, -1, 3100, 3099, 3101, -1, 3102, 3101, 441, -1, 3102, 412, 3100, -1, 3102, 442, 412, -1, 3102, 441, 442, -1, 3102, 3100, 3101, -1, 3103, 3095, 3049, -1, 2408, 2355, 3095, -1, 2408, 2407, 2355, -1, 2447, 2385, 2386, -1, 3104, 1131, 1120, -1, 2446, 2385, 2447, -1, 3105, 3057, 3068, -1, 2412, 3106, 2414, -1, 1165, 3105, 3068, -1, 2442, 3075, 3079, -1, 3107, 1115, 3108, -1, 3107, 1117, 1115, -1, 2442, 3079, 2393, -1, 1149, 1134, 1136, -1, 1149, 1136, 1139, -1, 1198, 1134, 1149, -1, 3109, 3087, 3110, -1, 3109, 3086, 3087, -1, 3111, 3095, 3103, -1, 3112, 1128, 1129, -1, 1154, 3113, 1155, -1, 1192, 1194, 1107, -1, 3114, 3111, 3103, -1, 3115, 1131, 3104, -1, 3116, 3113, 1154, -1, 3116, 1171, 3113, -1, 3117, 3115, 3104, -1, 1204, 3105, 1165, -1, 1167, 1171, 3116, -1, 3118, 3107, 3108, -1, 3118, 3108, 3119, -1, 3120, 1128, 3112, -1, 1234, 3109, 3110, -1, 1234, 3110, 1185, -1, 2490, 2439, 2438, -1, 3121, 3111, 3114, -1, 2450, 3122, 3123, -1, 2450, 3123, 2451, -1, 3124, 3120, 3112, -1, 3125, 2393, 2392, -1, 1254, 3126, 3127, -1, 3125, 2442, 2393, -1, 1255, 1254, 3127, -1, 3128, 3115, 3117, -1, 1173, 1128, 3120, -1, 2501, 3106, 2412, -1, 2501, 2500, 3106, -1, 1168, 3129, 1169, -1, 3130, 3131, 3132, -1, 3133, 2473, 2448, -1, 1218, 3128, 3117, -1, 2489, 2439, 2490, -1, 2443, 2442, 3125, -1, 1241, 3119, 1177, -1, 2516, 3122, 2450, -1, 1241, 3118, 3119, -1, 3134, 3120, 3124, -1, 2516, 2519, 3122, -1, 3135, 3134, 3124, -1, 2502, 3121, 3114, -1, 2502, 3114, 2500, -1, 3136, 1177, 1157, -1, 3136, 1241, 1177, -1, 3137, 3130, 3132, -1, 1217, 3128, 1218, -1, 3138, 3139, 1262, -1, 3140, 3132, 2475, -1, 3140, 2475, 2474, -1, 3140, 3137, 3132, -1, 3141, 2473, 3133, -1, 3142, 3141, 3133, -1, 1239, 1219, 1212, -1, 3143, 3137, 3140, -1, 3144, 3134, 3135, -1, 3145, 2450, 3146, -1, 3145, 2516, 2450, -1, 1261, 3138, 1262, -1, 2459, 2540, 2454, -1, 1214, 1219, 1239, -1, 1300, 3144, 3135, -1, 1297, 3129, 1168, -1, 1297, 1300, 3129, -1, 3147, 1193, 3148, -1, 3147, 1195, 1193, -1, 3149, 1241, 3136, -1, 3150, 2487, 2469, -1, 3151, 3141, 3142, -1, 1281, 1222, 1221, -1, 1281, 1221, 1283, -1, 2520, 3151, 3142, -1, 1242, 1241, 3149, -1, 3152, 2465, 3153, -1, 3152, 2467, 2465, -1, 2508, 2491, 2498, -1, 2508, 2492, 2491, -1, 1320, 3144, 1300, -1, 2547, 2492, 2508, -1, 3154, 3146, 3155, -1, 3154, 3145, 3146, -1, 3156, 3148, 3157, -1, 3158, 2482, 2481, -1, 3156, 3147, 3148, -1, 2511, 3159, 2502, -1, 2542, 2540, 2459, -1, 3160, 2487, 3150, -1, 3161, 3159, 2511, -1, 3161, 2525, 3159, -1, 3162, 3160, 3150, -1, 3163, 1269, 1246, -1, 2551, 3151, 2520, -1, 2522, 2525, 3161, -1, 3164, 3153, 3165, -1, 3164, 3152, 3153, -1, 3166, 2482, 3158, -1, 2572, 3154, 3155, -1, 1334, 1337, 1251, -1, 2572, 3155, 2537, -1, 1334, 1251, 1215, -1, 1311, 3157, 1273, -1, 1311, 3156, 3157, -1, 1339, 1291, 1266, -1, 3167, 3166, 3158, -1, 3168, 1269, 3163, -1, 2591, 3169, 3170, -1, 1314, 1280, 1282, -1, 2592, 2591, 3170, -1, 1314, 1282, 1289, -1, 3171, 3160, 3162, -1, 2530, 2482, 3166, -1, 1366, 1280, 1314, -1, 3172, 3168, 3163, -1, 1321, 1307, 1320, -1, 2523, 3173, 2524, -1, 2557, 3171, 3162, -1, 3174, 1276, 1278, -1, 1341, 1291, 1339, -1, 1305, 1307, 1321, -1, 2579, 3165, 2532, -1, 2579, 3164, 3165, -1, 3175, 3166, 3167, -1, 1357, 3176, 1355, -1, 3177, 3175, 3167, -1, 3178, 3168, 3172, -1, 3179, 2579, 2532, -1, 3179, 2532, 2513, -1, 2561, 3171, 2557, -1, 3180, 3181, 2599, -1, 1329, 3178, 3172, -1, 3182, 1276, 3174, -1, 3183, 3184, 1362, -1, 3185, 3182, 3174, -1, 2575, 2558, 2555, -1, 3186, 3175, 3177, -1, 1403, 1342, 1340, -1, 2598, 3180, 2599, -1, 2559, 2558, 2575, -1, 1391, 3178, 1329, -1, 2631, 3186, 3177, -1, 2632, 3173, 2523, -1, 1332, 1276, 3182, -1, 2632, 2631, 3173, -1, 3187, 2543, 3188, -1, 1361, 3183, 1362, -1, 3187, 2544, 2543, -1, 3189, 1329, 1317, -1, 3189, 1391, 1329, -1, 3190, 2579, 3179, -1, 3191, 3182, 3185, -1, 3192, 3191, 3185, -1, 2619, 2564, 2563, -1, 2619, 2563, 2620, -1, 1402, 1342, 1403, -1, 3193, 1306, 3194, -1, 3193, 1345, 1306, -1, 2577, 2579, 3190, -1, 2653, 3186, 2631, -1, 1405, 3195, 1380, -1, 3196, 3188, 3197, -1, 3196, 3187, 3188, -1, 3198, 1387, 1376, -1, 3199, 3195, 1405, -1, 3200, 1391, 3189, -1, 3201, 3191, 3192, -1, 1436, 3201, 3192, -1, 3202, 1369, 3203, -1, 3202, 1371, 1369, -1, 1437, 1346, 1345, -1, 1437, 1436, 1346, -1, 1399, 1403, 3195, -1, 1399, 3195, 3199, -1, 3204, 3194, 3205, -1, 3204, 3193, 3194, -1, 1392, 1391, 3200, -1, 2667, 2666, 2587, -1, 2667, 2587, 2560, -1, 2641, 3197, 2611, -1, 2641, 3196, 3197, -1, 1448, 1378, 1356, -1, 1449, 1378, 1448, -1, 3206, 1387, 3198, -1, 2670, 2629, 2603, -1, 3207, 3206, 3198, -1, 3208, 2582, 3209, -1, 3208, 2609, 2582, -1, 1477, 3201, 1436, -1, 2645, 2618, 2617, -1, 2645, 2617, 2623, -1, 3210, 3203, 3211, -1, 2698, 2618, 2645, -1, 3210, 3202, 3203, -1, 2652, 2637, 2653, -1, 3212, 3205, 3213, -1, 3212, 3204, 3205, -1, 3214, 2614, 2615, -1, 2673, 2629, 2670, -1, 2638, 2637, 2652, -1, 3215, 1418, 1407, -1, 1453, 3216, 1454, -1, 2689, 3217, 2687, -1, 3218, 3206, 3207, -1, 3219, 3208, 3209, -1, 3219, 3209, 3220, -1, 1494, 1400, 1399, -1, 1494, 1493, 1400, -1, 1472, 3218, 3207, -1, 1468, 3211, 1432, -1, 1468, 3210, 3211, -1, 3221, 1418, 3215, -1, 1512, 3213, 1429, -1, 1512, 3212, 3213, -1, 3222, 2614, 3214, -1, 1512, 1429, 1444, -1, 3223, 3224, 2694, -1, 3225, 3222, 3214, -1, 3226, 3221, 3215, -1, 1514, 3212, 1512, -1, 1486, 3218, 1472, -1, 1457, 3227, 1459, -1, 2727, 2672, 2671, -1, 1490, 1412, 1491, -1, 1490, 1427, 1412, -1, 2720, 3219, 3220, -1, 2720, 3220, 2659, -1, 1476, 1460, 1477, -1, 2662, 2614, 3222, -1, 2693, 3223, 2694, -1, 1470, 1474, 1449, -1, 3228, 2720, 2659, -1, 3228, 2659, 2648, -1, 3229, 3221, 3226, -1, 3230, 3222, 3225, -1, 1461, 1460, 1476, -1, 3231, 3230, 3225, -1, 1483, 3229, 3226, -1, 3232, 1447, 1446, -1, 3232, 1446, 3233, -1, 2726, 2672, 2727, -1, 3234, 2678, 2639, -1, 3234, 2639, 3235, -1, 3236, 1452, 1451, -1, 3236, 1451, 3237, -1, 2730, 3238, 2709, -1, 1536, 3229, 1483, -1, 3239, 2716, 2704, -1, 3240, 3238, 2730, -1, 3241, 2720, 3228, -1, 3242, 3233, 3243, -1, 3242, 3232, 3233, -1, 3244, 3230, 3231, -1, 3245, 1483, 1463, -1, 3245, 1536, 1483, -1, 2755, 3244, 3231, -1, 1560, 1452, 3236, -1, 3246, 2702, 2701, -1, 3246, 2701, 3247, -1, 2756, 2755, 2676, -1, 2756, 2676, 2678, -1, 2728, 2727, 3238, -1, 2728, 3238, 3240, -1, 1533, 1489, 1488, -1, 1533, 1488, 1532, -1, 3248, 3234, 3235, -1, 3248, 3235, 3249, -1, 2721, 2720, 3241, -1, 1540, 3250, 1523, -1, 2764, 2707, 2688, -1, 2765, 2707, 2764, -1, 3251, 2716, 3239, -1, 1562, 1560, 3236, -1, 3252, 3251, 3239, -1, 1559, 3242, 3243, -1, 1559, 3243, 1560, -1, 2795, 3244, 2755, -1, 3253, 3250, 1540, -1, 3254, 1536, 3245, -1, 3255, 3247, 3256, -1, 3257, 1521, 1506, -1, 3255, 3246, 3247, -1, 3257, 1506, 3258, -1, 1529, 3250, 3253, -1, 1529, 1532, 3250, -1, 3259, 3248, 3249, -1, 3259, 3249, 3260, -1, 1537, 1536, 3254, -1, 3261, 2740, 2733, -1, 2767, 3262, 2768, -1, 3263, 3251, 3252, -1, 3264, 1525, 1508, -1, 3265, 1525, 3264, -1, 1596, 3266, 1597, -1, 1596, 3267, 3266, -1, 2813, 2812, 2725, -1, 2813, 2725, 2728, -1, 2791, 3263, 3252, -1, 3268, 3258, 3269, -1, 3268, 3257, 3258, -1, 2785, 3255, 3256, -1, 2785, 3256, 2752, -1, 3270, 2740, 3261, -1, 2828, 2750, 2760, -1, 2828, 3259, 3260, -1, 2828, 3260, 2750, -1, 3271, 3270, 3261, -1, 2827, 3259, 2828, -1, 3272, 3273, 1602, -1, 3274, 1568, 1549, -1, 1626, 1530, 1529, -1, 2803, 3263, 2791, -1, 1626, 1625, 1530, -1, 2773, 3275, 2774, -1, 3276, 3265, 3264, -1, 2806, 2736, 2807, -1, 1614, 1582, 1581, -1, 2806, 2747, 2736, -1, 2794, 2775, 2795, -1, 1587, 3277, 1588, -1, 1617, 3269, 1576, -1, 1617, 3268, 3269, -1, 2787, 2789, 2765, -1, 1601, 3272, 1602, -1, 3278, 3270, 3271, -1, 3279, 3277, 1587, -1, 3279, 3280, 3281, -1, 3279, 3281, 3277, -1, 3282, 1568, 3274, -1, 2776, 2775, 2794, -1, 3283, 3265, 3276, -1, 2801, 3278, 3271, -1, 3284, 3282, 3274, -1, 3285, 2763, 2762, -1, 3285, 2762, 3286, -1, 1635, 1582, 1614, -1, 3287, 1601, 1603, -1, 3288, 1585, 1557, -1, 3288, 1557, 3289, -1, 3290, 2770, 3291, -1, 3290, 2769, 2770, -1, 1610, 1613, 3292, -1, 1610, 3292, 3265, -1, 1610, 3265, 3283, -1, 3293, 3280, 3279, -1, 3293, 1687, 3280, -1, 3294, 3293, 3279, -1, 2847, 3278, 2801, -1, 3295, 3282, 3284, -1, 3296, 3286, 3297, -1, 3296, 3285, 3286, -1, 1623, 3295, 3284, -1, 3298, 2801, 2780, -1, 3299, 3283, 3276, -1, 3298, 2847, 2801, -1, 3299, 3276, 3300, -1, 2867, 2769, 3290, -1, 3301, 3288, 3289, -1, 3301, 3289, 3302, -1, 2843, 2808, 2845, -1, 2843, 2809, 2808, -1, 2852, 3303, 2835, -1, 3304, 3293, 3294, -1, 3305, 3304, 3294, -1, 2868, 2867, 3290, -1, 1682, 3295, 1623, -1, 2870, 3297, 2867, -1, 2870, 3296, 3297, -1, 3306, 3303, 2852, -1, 3307, 3299, 3300, -1, 3307, 3300, 3308, -1, 3309, 2847, 3298, -1, 3310, 1682, 1623, -1, 3311, 2819, 3312, -1, 3310, 1623, 1606, -1, 3311, 2836, 2819, -1, 1692, 3301, 3302, -1, 1692, 3302, 1659, -1, 2844, 2845, 3303, -1, 2844, 3303, 3306, -1, 1688, 1687, 3293, -1, 3313, 1650, 1637, -1, 2848, 2847, 3309, -1, 1699, 3314, 1700, -1, 3315, 3304, 3305, -1, 1676, 1660, 1652, -1, 3316, 2838, 2823, -1, 3317, 2838, 3316, -1, 1725, 3315, 3305, -1, 1654, 1660, 1676, -1, 3318, 3312, 3319, -1, 3318, 3311, 3312, -1, 1713, 3307, 3308, -1, 1713, 3308, 1689, -1, 3320, 1650, 3313, -1, 3321, 1682, 3310, -1, 3322, 3320, 3313, -1, 1664, 1640, 1639, -1, 3323, 3324, 2900, -1, 3325, 2876, 2861, -1, 3326, 3315, 1725, -1, 3327, 3328, 1707, -1, 2922, 2921, 2842, -1, 2922, 2842, 2844, -1, 3329, 3317, 3316, -1, 1683, 1682, 3321, -1, 2910, 2889, 2888, -1, 2895, 3330, 2894, -1, 2913, 3318, 3319, -1, 2913, 3319, 2883, -1, 3331, 3320, 3322, -1, 2901, 3323, 2900, -1, 1706, 3327, 1707, -1, 3332, 3333, 3334, -1, 3332, 3334, 3330, -1, 3332, 3330, 2895, -1, 1722, 3331, 3322, -1, 3335, 2876, 3325, -1, 3336, 1664, 1639, -1, 3337, 3317, 3329, -1, 3336, 1639, 3338, -1, 3339, 3335, 3325, -1, 2928, 2889, 2910, -1, 3340, 2901, 2899, -1, 3341, 2864, 3342, -1, 3341, 2891, 2864, -1, 1726, 3326, 1725, -1, 1756, 3326, 1726, -1, 3343, 1680, 1679, -1, 2906, 3317, 3337, -1, 2906, 2909, 3344, -1, 2906, 3344, 3317, -1, 1761, 1760, 1693, -1, 1761, 1693, 1655, -1, 3345, 2968, 3333, -1, 3345, 3333, 3332, -1, 1752, 3331, 1722, -1, 1742, 1736, 1741, -1, 3346, 3345, 3332, -1, 3347, 3336, 3338, -1, 3347, 3338, 3348, -1, 3349, 3335, 3339, -1, 2916, 3349, 3339, -1, 1737, 1736, 1742, -1, 3350, 1680, 3343, -1, 3351, 3329, 3352, -1, 3351, 3337, 3329, -1, 1766, 1732, 1731, -1, 1766, 1731, 1749, -1, 3353, 3342, 3354, -1, 3353, 3341, 3342, -1, 1746, 1680, 3350, -1, 1746, 1750, 3355, -1, 1746, 3355, 1680, -1, 3356, 3345, 3346, -1, 3357, 1718, 1704, -1, 1739, 1811, 1734, -1, 3358, 3347, 3348, -1, 3359, 3356, 3346, -1, 3358, 3348, 1718, -1, 2965, 3349, 2916, -1, 3360, 3352, 3361, -1, 3360, 3351, 3352, -1, 3362, 3343, 3363, -1, 3362, 3350, 3343, -1, 3364, 2916, 2903, -1, 3364, 2965, 2916, -1, 2973, 3354, 2948, -1, 2973, 3353, 3354, -1, 2969, 2968, 3345, -1, 3365, 2943, 2930, -1, 3366, 3367, 3368, -1, 3366, 3368, 7, -1, 3369, 3356, 3359, -1, 2958, 2946, 2944, -1, 1844, 3370, 3371, -1, 1844, 3372, 3370, -1, 3373, 3369, 3359, -1, 1818, 1776, 1775, -1, 2947, 2946, 2958, -1, 3374, 3363, 3375, -1, 3374, 3362, 3363, -1, 2983, 3361, 2967, -1, 2983, 3360, 3361, -1, 3376, 1844, 3371, -1, 3377, 2943, 3365, -1, 3378, 3358, 1718, -1, 3378, 1718, 3357, -1, 3379, 2965, 3364, -1, 3380, 3377, 3365, -1, 1812, 1811, 1739, -1, 3381, 3367, 3366, -1, 3382, 3383, 3384, -1, 3381, 3373, 3367, -1, 3385, 3369, 3373, -1, 3386, 1795, 1778, -1, 3387, 3388, 2976, -1, 1817, 1776, 1818, -1, 3389, 3358, 3378, -1, 3389, 1792, 3358, -1, 2962, 2965, 3379, -1, 3390, 3377, 3380, -1, 1793, 1792, 3389, -1, 1837, 3374, 3375, -1, 1837, 3375, 1810, -1, 2975, 3387, 2976, -1, 3391, 3382, 3384, -1, 2989, 3390, 3380, -1, 3392, 3391, 3384, -1, 3392, 3384, 1796, -1, 3392, 1796, 1815, -1, 41, 1795, 3386, -1, 20, 3373, 3381, -1, 20, 3385, 3373, -1, 51, 1789, 52, -1, 19, 3385, 20, -1, 42, 41, 3386, -1, 25, 24, 2960, -1, 3393, 3391, 3392, -1, 64, 1820, 1783, -1, 64, 1783, 65, -1, 3010, 2972, 2949, -1, 3010, 3009, 2972, -1, 3006, 3390, 2989, -1, 1845, 1844, 3376, -1, 12, 11, 2998, -1, 3394, 3395, 3396, -1, 3397, 3398, 448, -1, 3399, 3394, 3396, -1, 3400, 3398, 3397, -1, 3401, 3399, 3400, -1, 3402, 3396, 3398, -1, 3402, 3399, 3396, -1, 3402, 3398, 3400, -1, 3402, 3400, 3399, -1, 3403, 3404, 3405, -1, 3403, 3406, 3404, -1, 22, 3407, 13, -1, 30, 3407, 22, -1, 3408, 3405, 17, -1, 3408, 17, 13, -1, 3408, 3407, 3403, -1, 3408, 3403, 3405, -1, 3408, 13, 3407, -1, 3409, 3410, 3411, -1, 937, 3412, 709, -1, 3413, 3409, 3411, -1, 1017, 3412, 937, -1, 1082, 3413, 1017, -1, 3414, 3411, 3412, -1, 3414, 3413, 3411, -1, 3414, 3412, 1017, -1, 3414, 1017, 3413, -1, 3415, 3416, 3417, -1, 3418, 3419, 3420, -1, 3420, 3419, 3421, -1, 3422, 3423, 3424, -1, 3416, 3423, 3422, -1, 3419, 3425, 3421, -1, 3426, 3427, 3428, -1, 3421, 3425, 3429, -1, 3424, 3430, 3431, -1, 3423, 3430, 3424, -1, 3425, 3432, 3429, -1, 3427, 3433, 3428, -1, 3429, 3432, 3434, -1, 3428, 3433, 3435, -1, 3432, 3436, 3434, -1, 3431, 3437, 3438, -1, 3430, 3437, 3431, -1, 3433, 3439, 3435, -1, 3435, 3439, 3440, -1, 3438, 3441, 3442, -1, 3437, 3441, 3438, -1, 3439, 3443, 3440, -1, 3440, 3443, 3444, -1, 3442, 3445, 3446, -1, 3441, 3445, 3442, -1, 3443, 3447, 3444, -1, 3444, 3447, 3448, -1, 3445, 3449, 3446, -1, 3446, 3449, 3450, -1, 3447, 3451, 3448, -1, 3448, 3451, 3452, -1, 3449, 3453, 3450, -1, 3450, 3453, 3454, -1, 3451, 3455, 3452, -1, 3452, 3455, 3456, -1, 3453, 3457, 3454, -1, 3454, 3457, 3458, -1, 3455, 3459, 3456, -1, 3456, 3459, 3460, -1, 3457, 3461, 3458, -1, 3458, 3461, 3462, -1, 3459, 3463, 3460, -1, 3460, 3463, 3464, -1, 3461, 3465, 3462, -1, 3462, 3465, 3466, -1, 3463, 3467, 3464, -1, 3464, 3467, 3468, -1, 3465, 3469, 3466, -1, 3466, 3469, 3470, -1, 3467, 3471, 3468, -1, 3468, 3471, 3472, -1, 3469, 3473, 3470, -1, 3470, 3473, 3474, -1, 3471, 3475, 3472, -1, 3472, 3475, 3476, -1, 3473, 3477, 3474, -1, 3474, 3477, 3478, -1, 3475, 3479, 3476, -1, 3476, 3479, 3480, -1, 3477, 3481, 3478, -1, 3478, 3481, 3482, -1, 3479, 3483, 3480, -1, 3480, 3483, 3484, -1, 3481, 3485, 3482, -1, 3482, 3485, 3486, -1, 3483, 3487, 3484, -1, 3484, 3487, 3488, -1, 3485, 3489, 3486, -1, 3486, 3489, 3490, -1, 3487, 3491, 3488, -1, 3488, 3491, 3492, -1, 3489, 3493, 3490, -1, 3490, 3493, 3494, -1, 3491, 3495, 3492, -1, 3492, 3495, 3496, -1, 3493, 3497, 3494, -1, 3494, 3497, 3498, -1, 3495, 3499, 3496, -1, 3496, 3499, 3500, -1, 3497, 3501, 3498, -1, 3498, 3501, 3502, -1, 3500, 3503, 3504, -1, 3499, 3503, 3500, -1, 3501, 3505, 3502, -1, 3502, 3505, 3506, -1, 3504, 3507, 3508, -1, 3503, 3507, 3504, -1, 3505, 3509, 3506, -1, 3506, 3509, 3510, -1, 3508, 3415, 3417, -1, 3507, 3415, 3508, -1, 3509, 3418, 3510, -1, 3510, 3418, 3420, -1, 3417, 3416, 3422, -1, 3511, 3512, 3513, -1, 3514, 3515, 3516, -1, 3517, 3518, 3519, -1, 3517, 3520, 3521, -1, 3517, 3519, 3520, -1, 3522, 3523, 3524, -1, 3517, 3521, 3525, -1, 3522, 3524, 3526, -1, 3527, 3525, 3528, -1, 3527, 3528, 3529, -1, 3530, 3531, 3532, -1, 3530, 3533, 3531, -1, 3534, 3535, 3536, -1, 3534, 3537, 3535, -1, 3538, 3512, 3511, -1, 3539, 3514, 3540, -1, 3539, 3540, 3541, -1, 3538, 3542, 3512, -1, 3543, 3529, 3515, -1, 3543, 3515, 3514, -1, 3544, 3511, 3545, -1, 3546, 3547, 3523, -1, 3548, 3518, 3517, -1, 3546, 3549, 3550, -1, 3546, 3523, 3522, -1, 3548, 3517, 3525, -1, 3548, 3525, 3527, -1, 3546, 3550, 3547, -1, 3551, 3541, 3537, -1, 3552, 3533, 3530, -1, 3551, 3537, 3534, -1, 3552, 3526, 3533, -1, 3553, 3542, 3538, -1, 3554, 3543, 3514, -1, 3554, 3514, 3539, -1, 3555, 3527, 3529, -1, 3556, 3557, 3558, -1, 3555, 3529, 3543, -1, 3553, 3532, 3542, -1, 3559, 3511, 3544, -1, 3560, 3536, 3561, -1, 3559, 3538, 3511, -1, 3562, 3544, 3545, -1, 3560, 3561, 3563, -1, 3562, 3545, 3564, -1, 3565, 3541, 3551, -1, 3565, 3539, 3541, -1, 3566, 3522, 3526, -1, 3567, 3543, 3554, -1, 3567, 3555, 3543, -1, 3566, 3526, 3552, -1, 3568, 3532, 3553, -1, 3568, 3530, 3532, -1, 3569, 3570, 3518, -1, 3569, 3527, 3555, -1, 3569, 3518, 3548, -1, 3569, 3548, 3527, -1, 3571, 3538, 3559, -1, 3572, 3534, 3536, -1, 3572, 3536, 3560, -1, 3571, 3553, 3538, -1, 3573, 3559, 3544, -1, 3573, 3544, 3562, -1, 3574, 3554, 3539, -1, 3574, 3539, 3565, -1, 3575, 3522, 3566, -1, 3575, 3546, 3522, -1, 3576, 3570, 3569, -1, 3575, 3577, 3549, -1, 3576, 3555, 3567, -1, 3575, 3549, 3546, -1, 3576, 3569, 3555, -1, 3578, 3562, 3564, -1, 3579, 3551, 3534, -1, 3580, 3552, 3530, -1, 3580, 3530, 3568, -1, 3579, 3534, 3572, -1, 3581, 3563, 3582, -1, 3581, 3560, 3563, -1, 3583, 3568, 3553, -1, 3583, 3553, 3571, -1, 3584, 3554, 3574, -1, 3584, 3567, 3554, -1, 3585, 3571, 3559, -1, 3585, 3559, 3573, -1, 3586, 3565, 3551, -1, 3587, 3564, 3588, -1, 3587, 3578, 3564, -1, 3586, 3551, 3579, -1, 3589, 3562, 3578, -1, 3589, 3573, 3562, -1, 3590, 3572, 3560, -1, 3590, 3560, 3581, -1, 3591, 3592, 3570, -1, 3593, 3566, 3552, -1, 3591, 3570, 3576, -1, 3593, 3552, 3580, -1, 3591, 3576, 3567, -1, 3591, 3567, 3584, -1, 3594, 3580, 3568, -1, 3594, 3568, 3583, -1, 3595, 3565, 3586, -1, 3595, 3574, 3565, -1, 3596, 3583, 3571, -1, 3596, 3571, 3585, -1, 3597, 3579, 3572, -1, 3597, 3572, 3590, -1, 3598, 3578, 3587, -1, 3599, 3581, 3582, -1, 3598, 3589, 3578, -1, 3599, 3582, 3600, -1, 3601, 3573, 3589, -1, 3601, 3585, 3573, -1, 3602, 3575, 3566, -1, 3602, 3577, 3575, -1, 3602, 3603, 3577, -1, 3604, 3579, 3597, -1, 3602, 3566, 3593, -1, 3604, 3586, 3579, -1, 3605, 3593, 3580, -1, 3605, 3580, 3594, -1, 3606, 3594, 3583, -1, 3606, 3583, 3596, -1, 3607, 3599, 3600, -1, 3608, 3581, 3599, -1, 3608, 3590, 3581, -1, 3609, 3587, 3588, -1, 3610, 3589, 3598, -1, 3610, 3601, 3589, -1, 3611, 3596, 3585, -1, 3612, 3595, 3586, -1, 3611, 3585, 3601, -1, 3612, 3586, 3604, -1, 3613, 3608, 3599, -1, 3613, 3599, 3607, -1, 3614, 3602, 3593, -1, 3614, 3593, 3605, -1, 3614, 3615, 3603, -1, 3614, 3603, 3602, -1, 3616, 3605, 3594, -1, 3617, 3590, 3608, -1, 3617, 3597, 3590, -1, 3616, 3594, 3606, -1, 3618, 3598, 3587, -1, 3619, 3607, 3600, -1, 3619, 3600, 3620, -1, 3618, 3587, 3609, -1, 3621, 3595, 3612, -1, 3622, 3601, 3610, -1, 3622, 3611, 3601, -1, 3621, 3623, 3595, -1, 3624, 3617, 3608, -1, 3625, 3606, 3596, -1, 3625, 3596, 3611, -1, 3624, 3608, 3613, -1, 3626, 3614, 3605, -1, 3627, 3597, 3617, -1, 3626, 3605, 3616, -1, 3626, 3615, 3614, -1, 3627, 3604, 3597, -1, 3628, 3607, 3619, -1, 3629, 3610, 3598, -1, 3628, 3613, 3607, -1, 3629, 3598, 3618, -1, 3630, 3611, 3622, -1, 3630, 3625, 3611, -1, 3631, 3619, 3620, -1, 3632, 3606, 3625, -1, 3632, 3616, 3606, -1, 3633, 3623, 3621, -1, 3633, 3634, 3635, -1, 3633, 3636, 3623, -1, 3633, 3635, 3636, -1, 3637, 3617, 3624, -1, 3637, 3627, 3617, -1, 3638, 3610, 3629, -1, 3638, 3622, 3610, -1, 3639, 3604, 3627, -1, 3640, 3632, 3625, -1, 3639, 3612, 3604, -1, 3640, 3625, 3630, -1, 3641, 3613, 3628, -1, 3642, 3615, 3626, -1, 3641, 3624, 3613, -1, 3642, 3616, 3632, -1, 3642, 3643, 3615, -1, 3642, 3626, 3616, -1, 3644, 3631, 3620, -1, 3644, 3620, 3645, -1, 3646, 3619, 3631, -1, 3647, 3622, 3638, -1, 3647, 3630, 3622, -1, 3646, 3628, 3619, -1, 3648, 3632, 3640, -1, 3648, 3643, 3642, -1, 3649, 3627, 3637, -1, 3649, 3639, 3627, -1, 3648, 3642, 3632, -1, 3650, 3621, 3612, -1, 3650, 3612, 3639, -1, 3651, 3652, 3653, -1, 3654, 3637, 3624, -1, 3654, 3624, 3641, -1, 3651, 3655, 3652, -1, 3656, 3630, 3647, -1, 3657, 3631, 3644, -1, 3656, 3640, 3630, -1, 3657, 3646, 3631, -1, 3658, 3641, 3628, -1, 3658, 3628, 3646, -1, 3659, 3660, 3655, -1, 3661, 3639, 3649, -1, 3661, 3650, 3639, -1, 3659, 3655, 3651, -1, 3662, 3663, 3634, -1, 3664, 3643, 3648, -1, 3664, 3648, 3640, -1, 3662, 3633, 3621, -1, 3664, 3640, 3656, -1, 3662, 3621, 3650, -1, 3664, 3665, 3643, -1, 3662, 3634, 3633, -1, 3666, 3649, 3637, -1, 3666, 3637, 3654, -1, 3667, 3668, 3660, -1, 3669, 3644, 3645, -1, 3667, 3660, 3659, -1, 3670, 3653, 3671, -1, 3672, 3658, 3646, -1, 3672, 3646, 3657, -1, 3670, 3651, 3653, -1, 3673, 3654, 3641, -1, 3673, 3641, 3658, -1, 3674, 3675, 3663, -1, 3676, 3668, 3667, -1, 3676, 3677, 3668, -1, 3674, 3663, 3662, -1, 3674, 3650, 3661, -1, 3674, 3662, 3650, -1, 3678, 3661, 3649, -1, 3678, 3649, 3666, -1, 3679, 3670, 3671, -1, 3680, 3644, 3669, -1, 3681, 3659, 3651, -1, 3681, 3651, 3670, -1, 3680, 3657, 3644, -1, 3682, 3658, 3672, -1, 3682, 3673, 3658, -1, 3683, 3684, 3677, -1, 3683, 3677, 3676, -1, 3685, 3666, 3654, -1, 3685, 3654, 3673, -1, 3686, 3661, 3678, -1, 3687, 3681, 3670, -1, 3686, 3675, 3674, -1, 3687, 3670, 3679, -1, 3686, 3674, 3661, -1, 3688, 3657, 3680, -1, 3689, 3667, 3659, -1, 3689, 3659, 3681, -1, 3688, 3672, 3657, -1, 3690, 3671, 3691, -1, 3690, 3679, 3671, -1, 3692, 3673, 3682, -1, 3693, 3694, 3684, -1, 3692, 3685, 3673, -1, 3693, 3684, 3683, -1, 3695, 3678, 3666, -1, 3695, 3666, 3685, -1, 3696, 3689, 3681, -1, 3696, 3681, 3687, -1, 3697, 3672, 3688, -1, 3697, 3682, 3672, -1, 3698, 3676, 3667, -1, 3699, 3685, 3692, -1, 3698, 3667, 3689, -1, 3699, 3695, 3685, -1, 3700, 3675, 3686, -1, 3700, 3701, 3675, -1, 3700, 3678, 3695, -1, 3702, 3687, 3679, -1, 3700, 3686, 3678, -1, 3702, 3679, 3690, -1, 3703, 3682, 3697, -1, 3704, 3690, 3691, -1, 3703, 3692, 3682, -1, 3705, 3706, 3694, -1, 3705, 3707, 3708, -1, 3705, 3708, 3706, -1, 3709, 3695, 3699, -1, 3709, 3700, 3695, -1, 3705, 3694, 3693, -1, 3709, 3701, 3700, -1, 3710, 3698, 3689, -1, 3711, 3692, 3703, -1, 3711, 3699, 3692, -1, 3710, 3689, 3696, -1, 3712, 3713, 3701, -1, 3712, 3709, 3699, -1, 3714, 3676, 3698, -1, 3712, 3701, 3709, -1, 3714, 3683, 3676, -1, 3712, 3699, 3711, -1, 3715, 3687, 3702, -1, 3715, 3696, 3687, -1, 3716, 3717, 3718, -1, 3719, 3691, 3720, -1, 3716, 3721, 3717, -1, 3716, 3722, 3723, -1, 3719, 3704, 3691, -1, 3724, 3690, 3704, -1, 3716, 3723, 3721, -1, 3724, 3702, 3690, -1, 3725, 3714, 3698, -1, 3725, 3698, 3710, -1, 3726, 3683, 3714, -1, 3727, 3728, 3729, -1, 3727, 3730, 3728, -1, 3726, 3693, 3683, -1, 3727, 3729, 3731, -1, 3732, 3710, 3696, -1, 3732, 3696, 3715, -1, 3733, 3724, 3704, -1, 3734, 3735, 3736, -1, 3734, 3736, 3737, -1, 3734, 3738, 3739, -1, 3734, 3739, 3740, -1, 3733, 3704, 3719, -1, 3734, 3737, 3738, -1, 3741, 3715, 3702, -1, 3734, 3740, 3735, -1, 3742, 3623, 3636, -1, 3741, 3702, 3724, -1, 3742, 3591, 3584, -1, 3743, 3714, 3725, -1, 3743, 3726, 3714, -1, 3744, 3705, 3693, -1, 3744, 3693, 3726, -1, 3744, 3707, 3705, -1, 3744, 3745, 3707, -1, 3746, 3711, 3747, -1, 3748, 3725, 3710, -1, 3746, 3712, 3711, -1, 3748, 3710, 3732, -1, 3746, 3747, 3749, -1, 3750, 3717, 3721, -1, 3751, 3719, 3720, -1, 3750, 3752, 3753, -1, 3750, 3721, 3752, -1, 3754, 3718, 3717, -1, 3755, 3434, 3756, -1, 3754, 3757, 3718, -1, 3758, 3741, 3724, -1, 3755, 3759, 3434, -1, 3758, 3724, 3733, -1, 3754, 3717, 3750, -1, 3754, 3760, 3757, -1, 3761, 3716, 3718, -1, 3761, 3718, 3762, -1, 3763, 3764, 3759, -1, 3761, 3722, 3716, -1, 3765, 3732, 3715, -1, 3761, 3766, 3722, -1, 3761, 3762, 3766, -1, 3765, 3715, 3741, -1, 3767, 3656, 3647, -1, 3763, 3759, 3755, -1, 3768, 3726, 3743, -1, 3767, 3664, 3656, -1, 3768, 3745, 3744, -1, 3767, 3769, 3664, -1, 3770, 3771, 3764, -1, 3768, 3772, 3745, -1, 3768, 3744, 3726, -1, 3773, 3684, 3694, -1, 3774, 3743, 3725, -1, 3773, 3769, 3767, -1, 3774, 3725, 3748, -1, 3773, 3694, 3706, -1, 3770, 3764, 3763, -1, 3775, 3665, 3664, -1, 3776, 3756, 3777, -1, 3775, 3664, 3769, -1, 3776, 3755, 3756, -1, 3778, 3733, 3719, -1, 3779, 3773, 3706, -1, 3778, 3719, 3751, -1, 3779, 3769, 3773, -1, 3779, 3775, 3769, -1, 3779, 3665, 3775, -1, 3779, 3708, 3665, -1, 3780, 3771, 3770, -1, 3779, 3706, 3708, -1, 3780, 3781, 3771, -1, 3782, 3741, 3758, -1, 3783, 3784, 3785, -1, 3782, 3765, 3741, -1, 3783, 3729, 3728, -1, 3783, 3728, 3784, -1, 3786, 3732, 3765, -1, 3787, 3729, 3783, -1, 3786, 3748, 3732, -1, 3787, 3788, 3789, -1, 3787, 3789, 3731, -1, 3787, 3731, 3729, -1, 3790, 3776, 3777, -1, 3791, 3768, 3743, -1, 3792, 3793, 3730, -1, 3791, 3743, 3774, -1, 3792, 3730, 3727, -1, 3791, 3772, 3768, -1, 3794, 3731, 3795, -1, 3796, 3755, 3776, -1, 3797, 3758, 3733, -1, 3794, 3727, 3731, -1, 3796, 3763, 3755, -1, 3797, 3733, 3778, -1, 3794, 3795, 3798, -1, 3794, 3793, 3792, -1, 3799, 3800, 3781, -1, 3794, 3798, 3793, -1, 3794, 3792, 3727, -1, 3801, 3802, 3803, -1, 3804, 3786, 3765, -1, 3801, 3739, 3802, -1, 3799, 3781, 3780, -1, 3804, 3765, 3782, -1, 3805, 3776, 3790, -1, 3801, 3740, 3739, -1, 3805, 3796, 3776, -1, 3806, 3748, 3786, -1, 3806, 3774, 3748, -1, 3807, 3808, 3809, -1, 3807, 3809, 3735, -1, 3807, 3735, 3740, -1, 3807, 3740, 3801, -1, 3810, 3742, 3584, -1, 3811, 3770, 3763, -1, 3810, 3584, 3574, -1, 3811, 3763, 3796, -1, 3812, 3810, 3574, -1, 3812, 3742, 3810, -1, 3813, 3777, 3814, -1, 3812, 3574, 3595, -1, 3812, 3623, 3742, -1, 3812, 3595, 3623, -1, 3813, 3790, 3777, -1, 3785, 3782, 3758, -1, 3785, 3758, 3797, -1, 3815, 3592, 3591, -1, 3816, 3817, 3800, -1, 3815, 3591, 3742, -1, 3818, 3635, 3592, -1, 3819, 3786, 3804, -1, 3818, 3592, 3815, -1, 3819, 3806, 3786, -1, 3818, 3815, 3742, -1, 3818, 3742, 3636, -1, 3816, 3800, 3799, -1, 3818, 3636, 3635, -1, 3820, 3796, 3805, -1, 3820, 3811, 3796, -1, 3821, 3711, 3703, -1, 3822, 3791, 3774, -1, 3821, 3703, 3697, -1, 3822, 3774, 3806, -1, 3821, 3747, 3711, -1, 3822, 3772, 3791, -1, 3822, 3823, 3772, -1, 3824, 3747, 3821, -1, 3825, 3770, 3811, -1, 3824, 3826, 3827, -1, 3824, 3827, 3749, -1, 3824, 3749, 3747, -1, 3825, 3780, 3770, -1, 3828, 3713, 3712, -1, 3828, 3712, 3746, -1, 3784, 3804, 3782, -1, 3829, 3830, 3713, -1, 3784, 3782, 3785, -1, 3829, 3828, 3746, -1, 3829, 3713, 3828, -1, 3829, 3749, 3831, -1, 3832, 3790, 3813, -1, 3829, 3831, 3830, -1, 3832, 3805, 3790, -1, 3829, 3746, 3749, -1, 3833, 3753, 3834, -1, 3833, 3750, 3753, -1, 3835, 3813, 3814, -1, 3836, 3822, 3806, -1, 3836, 3806, 3819, -1, 3836, 3823, 3822, -1, 3837, 3558, 3817, -1, 3837, 3556, 3558, -1, 3837, 3817, 3816, -1, 3838, 3825, 3811, -1, 3838, 3811, 3820, -1, 3839, 3833, 3840, -1, 3839, 3840, 3754, -1, 3728, 3819, 3804, -1, 3839, 3750, 3833, -1, 3839, 3754, 3750, -1, 3841, 3780, 3825, -1, 3728, 3804, 3784, -1, 3842, 3754, 3840, -1, 3841, 3799, 3780, -1, 3843, 3844, 3845, -1, 3846, 3820, 3805, -1, 3843, 3847, 3844, -1, 3848, 3760, 3754, -1, 3846, 3805, 3832, -1, 3848, 3754, 3842, -1, 3848, 3849, 3760, -1, 3850, 3647, 3638, -1, 3850, 3767, 3647, -1, 3851, 3814, 3852, -1, 3851, 3835, 3814, -1, 3730, 3823, 3836, -1, 3730, 3793, 3823, -1, 3853, 3832, 3813, -1, 3730, 3819, 3728, -1, 3854, 3767, 3850, -1, 3730, 3836, 3819, -1, 3854, 3850, 3855, -1, 3853, 3813, 3835, -1, 3854, 3855, 3773, -1, 3854, 3773, 3767, -1, 3856, 3847, 3843, -1, 3857, 3841, 3825, -1, 3857, 3825, 3838, -1, 3858, 3773, 3855, -1, 3856, 3859, 3847, -1, 3860, 3677, 3684, -1, 3861, 3799, 3841, -1, 3860, 3773, 3858, -1, 3860, 3684, 3773, -1, 3861, 3816, 3799, -1, 3862, 3785, 3797, -1, 3863, 3859, 3856, -1, 3863, 3864, 3859, -1, 3862, 3783, 3785, -1, 3865, 3838, 3820, -1, 3865, 3820, 3846, -1, 3866, 3835, 3851, -1, 3867, 3868, 3787, -1, 3869, 3845, 3870, -1, 3867, 3862, 3868, -1, 3867, 3783, 3862, -1, 3867, 3787, 3783, -1, 3866, 3853, 3835, -1, 3869, 3843, 3845, -1, 3871, 3832, 3853, -1, 3872, 3787, 3868, -1, 3871, 3846, 3832, -1, 3873, 3864, 3788, -1, 3873, 3788, 3787, -1, 3873, 3787, 3872, -1, 3874, 3841, 3857, -1, 3875, 3788, 3864, -1, 3876, 3801, 3803, -1, 3876, 3803, 3877, -1, 3874, 3861, 3841, -1, 3875, 3864, 3863, -1, 3878, 3837, 3816, -1, 3878, 3556, 3837, -1, 3878, 3879, 3556, -1, 3878, 3816, 3861, -1, 3880, 3857, 3838, -1, 3881, 3869, 3870, -1, 3882, 3801, 3876, -1, 3883, 3856, 3843, -1, 3882, 3807, 3801, -1, 3880, 3838, 3865, -1, 3882, 3884, 3807, -1, 3883, 3843, 3869, -1, 3882, 3876, 3884, -1, 3885, 3807, 3884, -1, 3886, 3851, 3852, -1, 3887, 3871, 3853, -1, 3888, 3889, 3808, -1, 3888, 3807, 3885, -1, 3888, 3808, 3807, -1, 3890, 3697, 3688, -1, 3887, 3853, 3866, -1, 3891, 3789, 3788, -1, 3890, 3821, 3697, -1, 3891, 3788, 3875, -1, 3892, 3865, 3846, -1, 3892, 3846, 3871, -1, 3893, 3879, 3878, -1, 3894, 3883, 3869, -1, 3893, 3861, 3874, -1, 3894, 3869, 3881, -1, 3893, 3878, 3861, -1, 3895, 3821, 3890, -1, 3893, 3896, 3879, -1, 3897, 3874, 3857, -1, 3898, 3863, 3856, -1, 3897, 3857, 3880, -1, 3898, 3856, 3883, -1, 3899, 3824, 3821, -1, 3900, 3866, 3851, -1, 3899, 3821, 3895, -1, 3899, 3895, 3901, -1, 3902, 3826, 3824, -1, 3902, 3903, 3826, -1, 3904, 3870, 3905, -1, 3902, 3824, 3899, -1, 3900, 3851, 3886, -1, 3902, 3899, 3901, -1, 3906, 3840, 3833, -1, 3904, 3881, 3870, -1, 3906, 3842, 3840, -1, 3907, 3892, 3871, -1, 3908, 3731, 3789, -1, 3908, 3789, 3891, -1, 3906, 3834, 3900, -1, 3907, 3871, 3887, -1, 3906, 3833, 3834, -1, 3909, 3865, 3892, -1, 3910, 3883, 3894, -1, 3911, 3842, 3906, -1, 3909, 3880, 3865, -1, 3910, 3898, 3883, -1, 3911, 3848, 3842, -1, 3911, 3849, 3848, -1, 3912, 3893, 3874, -1, 3911, 3913, 3849, -1, 3912, 3874, 3897, -1, 3914, 3638, 3629, -1, 3912, 3896, 3893, -1, 3915, 3863, 3898, -1, 3915, 3875, 3863, -1, 3914, 3858, 3855, -1, 3914, 3855, 3850, -1, 3834, 3887, 3866, -1, 3914, 3850, 3638, -1, 3916, 3858, 3914, -1, 3916, 3668, 3677, -1, 3834, 3866, 3900, -1, 3917, 3894, 3881, -1, 3916, 3677, 3860, -1, 3916, 3860, 3858, -1, 3918, 3909, 3892, -1, 3917, 3881, 3904, -1, 3918, 3892, 3907, -1, 3919, 3862, 3797, -1, 3919, 3868, 3862, -1, 3920, 3880, 3909, -1, 3919, 3872, 3868, -1, 3921, 3904, 3905, -1, 3919, 3797, 3778, -1, 3922, 3859, 3864, -1, 3920, 3897, 3880, -1, 3922, 3872, 3919, -1, 3923, 3731, 3908, -1, 3922, 3873, 3872, -1, 3923, 3795, 3731, -1, 3922, 3864, 3873, -1, 3923, 3798, 3795, -1, 3923, 3924, 3798, -1, 3925, 3898, 3910, -1, 3926, 3884, 3876, -1, 3925, 3915, 3898, -1, 3926, 3876, 3877, -1, 3753, 3887, 3834, -1, 3926, 3877, 3927, -1, 3753, 3907, 3887, -1, 3926, 3885, 3884, -1, 3928, 3885, 3926, -1, 3928, 3929, 3889, -1, 3928, 3889, 3888, -1, 3930, 3920, 3909, -1, 3931, 3891, 3875, -1, 3930, 3909, 3918, -1, 3928, 3888, 3885, -1, 3931, 3875, 3915, -1, 3932, 3890, 3688, -1, 3932, 3688, 3680, -1, 3933, 3912, 3897, -1, 3932, 3895, 3890, -1, 3934, 3910, 3894, -1, 3933, 3897, 3920, -1, 3934, 3894, 3917, -1, 3935, 3902, 3901, -1, 3933, 3936, 3896, -1, 3933, 3896, 3912, -1, 3935, 3895, 3932, -1, 3935, 3937, 3903, -1, 3938, 3904, 3921, -1, 3935, 3901, 3895, -1, 3938, 3917, 3904, -1, 3935, 3903, 3902, -1, 3939, 3906, 3900, -1, 3752, 3918, 3907, -1, 3940, 3905, 3941, -1, 3939, 3900, 3886, -1, 3940, 3921, 3905, -1, 3752, 3907, 3753, -1, 3942, 3915, 3925, -1, 3943, 3920, 3930, -1, 3943, 3936, 3933, -1, 3944, 3906, 3939, -1, 3945, 3906, 3944, -1, 3945, 3911, 3906, -1, 3943, 3933, 3920, -1, 3942, 3931, 3915, -1, 3945, 3913, 3911, -1, 3946, 3908, 3891, -1, 3945, 3947, 3913, -1, 3946, 3891, 3931, -1, 3948, 3629, 3618, -1, 3948, 3914, 3629, -1, 3949, 3925, 3910, -1, 3949, 3910, 3934, -1, 3721, 3918, 3752, -1, 3950, 3914, 3948, -1, 3721, 3930, 3918, -1, 3951, 3952, 3953, -1, 3954, 3934, 3917, -1, 3955, 3668, 3916, -1, 3954, 3917, 3938, -1, 3955, 3660, 3668, -1, 3951, 3947, 3952, -1, 3955, 3914, 3950, -1, 3955, 3916, 3914, -1, 3956, 3778, 3751, -1, 3957, 3938, 3921, -1, 3956, 3919, 3778, -1, 3957, 3921, 3940, -1, 3958, 3946, 3931, -1, 3959, 3919, 3956, -1, 3723, 3722, 3936, -1, 3958, 3931, 3942, -1, 3723, 3943, 3930, -1, 3960, 3922, 3919, -1, 3961, 3923, 3908, -1, 3960, 3919, 3959, -1, 3961, 3924, 3923, -1, 3723, 3936, 3943, -1, 3961, 3908, 3946, -1, 3723, 3930, 3721, -1, 3960, 3859, 3922, -1, 3961, 3962, 3924, -1, 3963, 3947, 3951, -1, 3960, 3847, 3859, -1, 3964, 3927, 3965, -1, 3963, 3913, 3947, -1, 3964, 3926, 3927, -1, 3965, 3940, 3941, -1, 3966, 3942, 3925, -1, 3967, 3926, 3964, -1, 3966, 3925, 3949, -1, 3968, 3929, 3928, -1, 3968, 3969, 3929, -1, 3968, 3926, 3967, -1, 3968, 3928, 3926, -1, 3970, 3913, 3963, -1, 3971, 3949, 3934, -1, 3971, 3934, 3954, -1, 3972, 3932, 3680, -1, 3970, 3849, 3913, -1, 3973, 3954, 3938, -1, 3972, 3680, 3669, -1, 3972, 3935, 3932, -1, 3974, 3953, 3975, -1, 3974, 3951, 3953, -1, 3973, 3938, 3957, -1, 3976, 3962, 3961, -1, 3977, 3935, 3972, -1, 3976, 3961, 3946, -1, 3978, 3937, 3935, -1, 3976, 3979, 3962, -1, 3978, 3980, 3937, -1, 3976, 3946, 3958, -1, 3978, 3935, 3977, -1, 3927, 3957, 3940, -1, 3927, 3940, 3965, -1, 3981, 3886, 3852, -1, 3981, 3939, 3886, -1, 3981, 3944, 3939, -1, 3982, 3849, 3970, -1, 3983, 3852, 3952, -1, 3984, 3942, 3966, -1, 3983, 3981, 3852, -1, 3984, 3958, 3942, -1, 3983, 3947, 3945, -1, 3983, 3952, 3947, -1, 3983, 3945, 3944, -1, 3983, 3944, 3981, -1, 3982, 3760, 3849, -1, 3985, 3949, 3971, -1, 3986, 3948, 3618, -1, 3986, 3950, 3948, -1, 3986, 3618, 3609, -1, 3987, 3655, 3660, -1, 3988, 3974, 3975, -1, 3985, 3966, 3949, -1, 3987, 3660, 3955, -1, 3987, 3950, 3986, -1, 3987, 3955, 3950, -1, 3989, 3971, 3954, -1, 3989, 3954, 3973, -1, 3990, 3951, 3974, -1, 3991, 3751, 3720, -1, 3990, 3963, 3951, -1, 3877, 3973, 3957, -1, 3991, 3959, 3956, -1, 3991, 3956, 3751, -1, 3992, 3720, 3844, -1, 3992, 3991, 3720, -1, 3992, 3844, 3847, -1, 3992, 3960, 3959, -1, 3877, 3957, 3927, -1, 3992, 3847, 3960, -1, 3993, 3958, 3984, -1, 3992, 3959, 3991, -1, 3994, 3760, 3982, -1, 3993, 3979, 3976, -1, 3993, 3976, 3958, -1, 3995, 3967, 3964, -1, 3995, 3965, 3941, -1, 3995, 3964, 3965, -1, 3996, 3984, 3966, -1, 3994, 3757, 3760, -1, 3997, 3998, 3969, -1, 3997, 3941, 3998, -1, 3999, 3990, 3974, -1, 3997, 3995, 3941, -1, 3997, 3969, 3968, -1, 3997, 3968, 3967, -1, 3996, 3966, 3985, -1, 3997, 3967, 3995, -1, 4000, 3985, 3971, -1, 4001, 3645, 3426, -1, 3999, 3974, 3988, -1, 4001, 3669, 3645, -1, 4000, 3971, 3989, -1, 4001, 3972, 3669, -1, 4002, 3963, 3990, -1, 4001, 3977, 3972, -1, 4003, 3977, 4001, -1, 4003, 4001, 3426, -1, 4002, 3970, 3963, -1, 4003, 3426, 3980, -1, 4003, 3980, 3978, -1, 4003, 3978, 3977, -1, 4004, 3588, 3652, -1, 4005, 3975, 4006, -1, 4004, 3655, 3987, -1, 4004, 3652, 3655, -1, 4004, 3609, 3588, -1, 4005, 3988, 3975, -1, 3803, 3989, 3973, -1, 4004, 3986, 3609, -1, 3803, 3973, 3877, -1, 4004, 3987, 3986, -1, 4007, 3757, 3994, -1, 4007, 3718, 3757, -1, 4008, 3993, 3984, -1, 4008, 3984, 3996, -1, 4009, 4002, 3990, -1, 4008, 3979, 3993, -1, 4008, 4010, 3979, -1, 4011, 3996, 3985, -1, 4009, 3990, 3999, -1, 4012, 3982, 3970, -1, 4011, 3985, 4000, -1, 4012, 3970, 4002, -1, 4013, 3999, 3988, -1, 4013, 3988, 4005, -1, 3802, 3989, 3803, -1, 3802, 4000, 3989, -1, 4014, 4005, 4006, -1, 4015, 4008, 3996, -1, 4016, 3762, 3718, -1, 4015, 3996, 4011, -1, 4015, 4010, 4008, -1, 4016, 3718, 4007, -1, 4016, 4017, 3766, -1, 4016, 3766, 3762, -1, 4018, 4012, 4002, -1, 4018, 4002, 4009, -1, 3739, 4011, 4000, -1, 3739, 4000, 3802, -1, 4019, 3982, 4012, -1, 4020, 3969, 3998, -1, 4019, 3994, 3982, -1, 4020, 3998, 4021, -1, 4022, 4009, 3999, -1, 4022, 3999, 4013, -1, 4023, 4013, 4005, -1, 4023, 4005, 4014, -1, 3738, 4011, 3739, -1, 4024, 4006, 4025, -1, 3738, 4015, 4011, -1, 3738, 4010, 4015, -1, 4024, 4014, 4006, -1, 3738, 3737, 4010, -1, 4026, 4012, 4018, -1, 4026, 4019, 4012, -1, 4027, 3929, 3969, -1, 4027, 3969, 4020, -1, 4028, 3994, 4019, -1, 4028, 4007, 3994, -1, 4029, 4009, 4022, -1, 4029, 4018, 4009, -1, 4030, 3889, 3929, -1, 4031, 4022, 4013, -1, 4030, 3929, 4027, -1, 4032, 4021, 4033, -1, 4031, 4013, 4023, -1, 4032, 4020, 4021, -1, 4034, 4023, 4014, -1, 4034, 4014, 4024, -1, 4035, 4028, 4019, -1, 4035, 4019, 4026, -1, 4036, 4016, 4007, -1, 4037, 3808, 3889, -1, 4036, 4017, 4016, -1, 4036, 4038, 4017, -1, 4037, 3889, 4030, -1, 4036, 4007, 4028, -1, 4039, 4024, 4025, -1, 4040, 4032, 4033, -1, 4041, 4026, 4018, -1, 4041, 4018, 4029, -1, 4042, 4020, 4032, -1, 4042, 4027, 4020, -1, 4043, 4022, 4031, -1, 4043, 4029, 4022, -1, 3736, 4044, 3737, -1, 4045, 4023, 4034, -1, 4045, 4031, 4023, -1, 4046, 3809, 3808, -1, 4047, 4038, 4036, -1, 4047, 4048, 4038, -1, 4046, 3808, 4037, -1, 4047, 4028, 4035, -1, 4047, 4036, 4028, -1, 4049, 4042, 4032, -1, 4049, 4032, 4040, -1, 4050, 4025, 4051, -1, 4050, 4039, 4025, -1, 4052, 4024, 4039, -1, 4053, 4030, 4027, -1, 4053, 4027, 4042, -1, 4052, 4034, 4024, -1, 4054, 4040, 4033, -1, 4055, 4035, 4026, -1, 4054, 4033, 4056, -1, 4055, 4026, 4041, -1, 4057, 3809, 4046, -1, 4057, 3735, 3809, -1, 4058, 4029, 4043, -1, 4058, 4041, 4029, -1, 4059, 4042, 4049, -1, 4059, 4053, 4042, -1, 4060, 4043, 4031, -1, 4060, 4031, 4045, -1, 4061, 4052, 4039, -1, 4062, 4030, 4053, -1, 4062, 4037, 4030, -1, 4061, 4039, 4050, -1, 4063, 4034, 4052, -1, 4064, 4040, 4054, -1, 4064, 4049, 4040, -1, 4063, 4045, 4034, -1, 4065, 4054, 4056, -1, 4066, 4048, 4047, -1, 4066, 4035, 4055, -1, 4066, 4047, 4035, -1, 4067, 3736, 3735, -1, 4068, 4055, 4041, -1, 4067, 4044, 3736, -1, 4067, 3735, 4057, -1, 4067, 4069, 4044, -1, 4070, 4053, 4059, -1, 4068, 4041, 4058, -1, 4070, 4062, 4053, -1, 4071, 4058, 4043, -1, 4071, 4043, 4060, -1, 4072, 4037, 4062, -1, 4073, 4052, 4061, -1, 4072, 4046, 4037, -1, 4074, 4059, 4049, -1, 4073, 4063, 4052, -1, 4074, 4049, 4064, -1, 4075, 4050, 4051, -1, 4076, 4064, 4054, -1, 4077, 4060, 4045, -1, 4076, 4054, 4065, -1, 4077, 4045, 4063, -1, 4078, 4056, 4079, -1, 4080, 4048, 4066, -1, 4080, 4055, 4068, -1, 4080, 4066, 4055, -1, 4078, 4065, 4056, -1, 4081, 4072, 4062, -1, 4080, 4082, 4048, -1, 4081, 4062, 4070, -1, 4083, 4058, 4071, -1, 4083, 4068, 4058, -1, 4084, 4057, 4046, -1, 4084, 4046, 4072, -1, 4085, 4063, 4073, -1, 4086, 4070, 4059, -1, 4086, 4059, 4074, -1, 4085, 4077, 4063, -1, 4087, 4050, 4075, -1, 4087, 4061, 4050, -1, 4088, 4064, 4076, -1, 4088, 4074, 4064, -1, 4089, 4071, 4060, -1, 4089, 4060, 4077, -1, 4090, 4076, 4065, -1, 4090, 4065, 4078, -1, 4091, 4080, 4068, -1, 4091, 4082, 4080, -1, 4091, 4068, 4083, -1, 4092, 4072, 4081, -1, 4093, 4089, 4077, -1, 4092, 4084, 4072, -1, 4093, 4077, 4085, -1, 4094, 4067, 4057, -1, 4094, 4069, 4067, -1, 4095, 4073, 4061, -1, 4094, 4057, 4084, -1, 4095, 4061, 4087, -1, 4094, 4096, 4069, -1, 4097, 4078, 4079, -1, 4098, 4083, 4071, -1, 4098, 4071, 4089, -1, 4099, 4081, 4070, -1, 4099, 4070, 4086, -1, 4100, 4051, 4101, -1, 4100, 4075, 4051, -1, 4102, 4086, 4074, -1, 4102, 4074, 4088, -1, 4103, 4098, 4089, -1, 4103, 4089, 4093, -1, 4104, 4088, 4076, -1, 4105, 4085, 4073, -1, 4105, 4073, 4095, -1, 4104, 4076, 4090, -1, 4106, 4094, 4084, -1, 4106, 4084, 4092, -1, 4106, 4096, 4094, -1, 4107, 4091, 4083, -1, 4106, 4108, 4096, -1, 4107, 4083, 4098, -1, 4109, 4079, 4110, -1, 4107, 4082, 4091, -1, 4109, 4097, 4079, -1, 4107, 4111, 4082, -1, 4112, 4075, 4100, -1, 4113, 4078, 4097, -1, 4112, 4087, 4075, -1, 4113, 4090, 4078, -1, 4114, 4107, 4098, -1, 4115, 4092, 4081, -1, 4114, 4098, 4103, -1, 4115, 4081, 4099, -1, 4114, 4111, 4107, -1, 4116, 4093, 4085, -1, 4116, 4085, 4105, -1, 4117, 4086, 4102, -1, 4117, 4099, 4086, -1, 4118, 4095, 4087, -1, 4119, 4088, 4104, -1, 4119, 4102, 4088, -1, 4118, 4087, 4112, -1, 4120, 4101, 4121, -1, 4120, 4100, 4101, -1, 4122, 4097, 4109, -1, 4122, 4113, 4097, -1, 4123, 4103, 4093, -1, 4123, 4093, 4116, -1, 4124, 4104, 4090, -1, 4124, 4090, 4113, -1, 4125, 4106, 4092, -1, 4126, 4120, 4121, -1, 4125, 4092, 4115, -1, 4125, 4108, 4106, -1, 4127, 4105, 4095, -1, 4128, 4099, 4117, -1, 4127, 4095, 4118, -1, 4128, 4115, 4099, -1, 4129, 4102, 4119, -1, 4129, 4117, 4102, -1, 4130, 4112, 4100, -1, 4130, 4100, 4120, -1, 4131, 4124, 4113, -1, 4131, 4113, 4122, -1, 4132, 4133, 4111, -1, 4132, 4114, 4103, -1, 4132, 4111, 4114, -1, 4132, 4103, 4123, -1, 4134, 4130, 4120, -1, 4135, 4109, 4110, -1, 4134, 4120, 4126, -1, 4136, 4104, 4124, -1, 4136, 4119, 4104, -1, 4137, 4116, 4105, -1, 4138, 4125, 4115, -1, 4137, 4105, 4127, -1, 4138, 4108, 4125, -1, 4138, 4115, 4128, -1, 4138, 4139, 4108, -1, 4140, 4118, 4112, -1, 4141, 4117, 4129, -1, 4140, 4112, 4130, -1, 4141, 4128, 4117, -1, 4142, 4124, 4131, -1, 4143, 4121, 4144, -1, 4142, 4136, 4124, -1, 4143, 4126, 4121, -1, 4145, 4122, 4109, -1, 4146, 4140, 4130, -1, 4146, 4130, 4134, -1, 4145, 4109, 4135, -1, 4147, 4119, 4136, -1, 4147, 4129, 4119, -1, 4148, 4116, 4137, -1, 4148, 4123, 4116, -1, 4149, 4118, 4140, -1, 4150, 4138, 4128, -1, 4150, 4139, 4138, -1, 4150, 4128, 4141, -1, 4149, 4127, 4118, -1, 4151, 4147, 4136, -1, 4151, 4136, 4142, -1, 4152, 4134, 4126, -1, 4153, 4131, 4122, -1, 4153, 4122, 4145, -1, 4152, 4126, 4143, -1, 4154, 4143, 4144, -1, 4155, 4141, 4129, -1, 4156, 4149, 4140, -1, 4155, 4129, 4147, -1, 4156, 4140, 4146, -1, 4157, 4135, 4110, -1, 4158, 4132, 4123, -1, 4157, 4110, 4159, -1, 4158, 4123, 4148, -1, 4158, 4160, 4133, -1, 4158, 4133, 4132, -1, 4161, 4155, 4147, -1, 4161, 4147, 4151, -1, 4162, 4127, 4149, -1, 4163, 4142, 4131, -1, 4162, 4137, 4127, -1, 4163, 4131, 4153, -1, 4164, 4146, 4134, -1, 4165, 4139, 4150, -1, 4165, 4150, 4141, -1, 4164, 4134, 4152, -1, 4165, 4166, 4139, -1, 4167, 4152, 4143, -1, 4165, 4141, 4155, -1, 4167, 4143, 4154, -1, 4168, 4135, 4157, -1, 4169, 4144, 4170, -1, 4168, 4145, 4135, -1, 4169, 4154, 4144, -1, 4171, 4155, 4161, -1, 4172, 4149, 4156, -1, 4171, 4165, 4155, -1, 4171, 4166, 4165, -1, 4173, 4151, 4142, -1, 4173, 4142, 4163, -1, 4172, 4162, 4149, -1, 4174, 4148, 4137, -1, 4174, 4137, 4162, -1, 4175, 4156, 4146, -1, 4176, 4153, 4145, -1, 4175, 4146, 4164, -1, 4176, 4145, 4168, -1, 4177, 4157, 4159, -1, 4178, 4152, 4167, -1, 4178, 4164, 4152, -1, 4177, 4159, 4179, -1, 4180, 4161, 4151, -1, 4180, 4151, 4173, -1, 4181, 4167, 4154, -1, 4181, 4154, 4169, -1, 4182, 4174, 4162, -1, 4182, 4162, 4172, -1, 4183, 4177, 4179, -1, 4184, 4160, 4158, -1, 4184, 4148, 4174, -1, 4185, 4163, 4153, -1, 4184, 4186, 4160, -1, 4185, 4153, 4176, -1, 4184, 4158, 4148, -1, 4187, 4169, 4170, -1, 4188, 4156, 4175, -1, 4189, 4168, 4157, -1, 4188, 4172, 4156, -1, 4189, 4157, 4177, -1, 4190, 4171, 4161, -1, 4191, 4175, 4164, -1, 4190, 4166, 4171, -1, 4190, 4161, 4180, -1, 4191, 4164, 4178, -1, 4190, 4192, 4166, -1, 4193, 4167, 4181, -1, 4193, 4178, 4167, -1, 4194, 4177, 4183, -1, 4194, 4189, 4177, -1, 4195, 4184, 4174, -1, 4195, 4174, 4182, -1, 4196, 4163, 4185, -1, 4196, 4173, 4163, -1, 4195, 4197, 4186, -1, 4195, 4186, 4184, -1, 4198, 4170, 4199, -1, 4198, 4187, 4170, -1, 4200, 4176, 4168, -1, 4200, 4168, 4189, -1, 4201, 4181, 4169, -1, 4201, 4169, 4187, -1, 4202, 4179, 4203, -1, 4204, 4182, 4172, -1, 4204, 4172, 4188, -1, 4202, 4183, 4179, -1, 4205, 4189, 4194, -1, 4206, 4188, 4175, -1, 4205, 4200, 4189, -1, 4206, 4175, 4191, -1, 4207, 4180, 4173, -1, 4207, 4173, 4196, -1, 4208, 4191, 4178, -1, 4208, 4178, 4193, -1, 4209, 4185, 4176, -1, 4209, 4176, 4200, -1, 4210, 4194, 4183, -1, 4211, 4187, 4198, -1, 4211, 4201, 4187, -1, 4210, 4183, 4202, -1, 4212, 4193, 4181, -1, 4212, 4181, 4201, -1, 4213, 4202, 4203, -1, 4214, 4195, 4182, -1, 4214, 4182, 4204, -1, 4214, 4197, 4195, -1, 4215, 4200, 4205, -1, 4216, 4188, 4206, -1, 4215, 4209, 4200, -1, 4216, 4204, 4188, -1, 4217, 4192, 4190, -1, 4217, 4180, 4207, -1, 4217, 4218, 4192, -1, 4217, 4190, 4180, -1, 4219, 4191, 4208, -1, 4220, 4196, 4185, -1, 4219, 4206, 4191, -1, 4220, 4185, 4209, -1, 4221, 4198, 4199, -1, 4222, 4212, 4201, -1, 4223, 4194, 4210, -1, 4223, 4205, 4194, -1, 4222, 4201, 4211, -1, 4224, 4208, 4193, -1, 4225, 4210, 4202, -1, 4224, 4193, 4212, -1, 4225, 4202, 4213, -1, 4226, 4214, 4204, -1, 4227, 4213, 4203, -1, 4226, 4204, 4216, -1, 4227, 4203, 4228, -1, 4226, 4229, 4197, -1, 4226, 4197, 4214, -1, 4230, 4206, 4219, -1, 4230, 4216, 4206, -1, 4231, 4209, 4215, -1, 4231, 4220, 4209, -1, 4232, 4211, 4198, -1, 4233, 4196, 4220, -1, 4233, 4207, 4196, -1, 4232, 4198, 4221, -1, 4234, 4212, 4222, -1, 4234, 4224, 4212, -1, 4235, 4215, 4205, -1, 4235, 4205, 4223, -1, 4236, 4219, 4208, -1, 4236, 4208, 4224, -1, 4237, 4210, 4225, -1, 4237, 4223, 4210, -1, 4238, 4229, 4226, -1, 4238, 4226, 4216, -1, 4239, 4213, 4227, -1, 4239, 4225, 4213, -1, 4238, 4216, 4230, -1, 4240, 4211, 4232, -1, 4241, 4220, 4231, -1, 4241, 4233, 4220, -1, 4240, 4222, 4211, -1, 4242, 4236, 4224, -1, 4243, 4217, 4207, -1, 4242, 4224, 4234, -1, 4243, 4218, 4217, -1, 4243, 4207, 4233, -1, 4243, 4244, 4218, -1, 4245, 4230, 4219, -1, 4246, 4227, 4228, -1, 4245, 4219, 4236, -1, 4247, 4199, 4248, -1, 4247, 4221, 4199, -1, 4249, 4215, 4235, -1, 4249, 4231, 4215, -1, 4250, 4234, 4222, -1, 4250, 4222, 4240, -1, 4251, 4235, 4223, -1, 4251, 4223, 4237, -1, 4252, 4245, 4236, -1, 4252, 4236, 4242, -1, 3516, 4237, 4225, -1, 3516, 4225, 4239, -1, 4253, 4229, 4238, -1, 4253, 4230, 4245, -1, 4254, 3519, 4244, -1, 4253, 4238, 4230, -1, 4254, 4233, 4241, -1, 4254, 4243, 4233, -1, 4253, 4255, 4229, -1, 4256, 4221, 4247, -1, 4254, 4244, 4243, -1, 4256, 4232, 4221, -1, 3535, 4228, 3561, -1, 3535, 4246, 4228, -1, 3524, 4242, 4234, -1, 4257, 4239, 4227, -1, 3524, 4234, 4250, -1, 4257, 4227, 4246, -1, 4258, 4245, 4252, -1, 4258, 4253, 4245, -1, 4258, 4255, 4253, -1, 3521, 4241, 4231, -1, 3521, 4231, 4249, -1, 3531, 4240, 4232, -1, 3528, 4249, 4235, -1, 3528, 4235, 4251, -1, 3531, 4232, 4256, -1, 3512, 4248, 3513, -1, 3512, 4247, 4248, -1, 3515, 4237, 3516, -1, 3515, 4251, 4237, -1, 3523, 4252, 4242, -1, 3523, 4242, 3524, -1, 3537, 4246, 3535, -1, 3537, 4257, 4246, -1, 3533, 4250, 4240, -1, 3540, 4239, 4257, -1, 3533, 4240, 3531, -1, 3540, 3516, 4239, -1, 3520, 3519, 4254, -1, 3520, 4254, 4241, -1, 3542, 4247, 3512, -1, 3520, 4241, 3521, -1, 3542, 4256, 4247, -1, 3525, 3521, 4249, -1, 3525, 4249, 3528, -1, 3547, 4252, 3523, -1, 3547, 4258, 4252, -1, 3547, 4255, 4258, -1, 3547, 3550, 4255, -1, 3529, 4251, 3515, -1, 3529, 3528, 4251, -1, 3526, 3524, 4250, -1, 3526, 4250, 3533, -1, 3536, 3535, 3561, -1, 3541, 3540, 4257, -1, 3532, 4256, 3542, -1, 3532, 3531, 4256, -1, 3541, 4257, 3537, -1, 3514, 3516, 3540, -1, 3511, 3513, 3545, -1, 4259, 4260, 4261, -1, 4259, 4262, 4260, -1, 4263, 4264, 4265, -1, 4266, 4267, 4268, -1, 4263, 4265, 4269, -1, 4266, 4268, 4262, -1, 4266, 4270, 4267, -1, 4271, 4272, 4273, -1, 4271, 4269, 4272, -1, 4274, 4275, 4276, -1, 4274, 4277, 4275, -1, 4274, 4276, 4278, -1, 4274, 4279, 4277, -1, 4280, 4281, 4282, -1, 4280, 4261, 4281, -1, 4283, 4284, 4285, -1, 4283, 4285, 4286, -1, 4287, 4262, 4259, -1, 4287, 4270, 4266, -1, 4288, 4264, 4263, -1, 4287, 4289, 4270, -1, 4287, 4266, 4262, -1, 4288, 4290, 4264, -1, 4291, 4269, 4271, -1, 4291, 4263, 4269, -1, 4292, 4293, 4294, -1, 4295, 4271, 4273, -1, 4292, 4294, 4296, -1, 4297, 4261, 4280, -1, 4297, 4259, 4261, -1, 4298, 4284, 4283, -1, 4298, 4278, 4284, -1, 4299, 4286, 4290, -1, 4300, 4282, 4301, -1, 4299, 4290, 4288, -1, 4300, 4301, 4302, -1, 4303, 4293, 4292, -1, 4304, 4263, 4291, -1, 4303, 4305, 4293, -1, 4304, 4288, 4263, -1, 4306, 4291, 4271, -1, 4307, 4287, 4259, -1, 4307, 4259, 4297, -1, 4306, 4271, 4295, -1, 4307, 4289, 4287, -1, 4308, 4280, 4282, -1, 4309, 4274, 4278, -1, 4309, 4278, 4298, -1, 4309, 4279, 4274, -1, 4308, 4282, 4300, -1, 4309, 4310, 4279, -1, 4311, 4295, 4273, -1, 4312, 4305, 4303, -1, 4311, 4273, 4313, -1, 4314, 4286, 4299, -1, 4314, 4283, 4286, -1, 4312, 4302, 4305, -1, 4315, 4296, 4316, -1, 4315, 4292, 4296, -1, 4317, 4299, 4288, -1, 4317, 4288, 4304, -1, 4318, 4297, 4280, -1, 4318, 4280, 4308, -1, 4319, 4304, 4291, -1, 4319, 4291, 4306, -1, 4320, 4300, 4302, -1, 4320, 4302, 4312, -1, 4321, 4311, 4313, -1, 4322, 4316, 4323, -1, 4324, 4295, 4311, -1, 4324, 4306, 4295, -1, 4322, 4315, 4316, -1, 4325, 4283, 4314, -1, 4326, 4303, 4292, -1, 4326, 4292, 4315, -1, 4325, 4298, 4283, -1, 4327, 4328, 4289, -1, 4329, 4314, 4299, -1, 4327, 4307, 4297, -1, 4329, 4299, 4317, -1, 4327, 4289, 4307, -1, 4327, 4297, 4318, -1, 4330, 4304, 4319, -1, 4330, 4317, 4304, -1, 4331, 4308, 4300, -1, 4331, 4300, 4320, -1, 4332, 4326, 4315, -1, 4332, 4315, 4322, -1, 4333, 4324, 4311, -1, 4333, 4311, 4321, -1, 4334, 4319, 4306, -1, 4334, 4306, 4324, -1, 4335, 4312, 4303, -1, 4335, 4303, 4326, -1, 4336, 4309, 4298, -1, 4337, 4322, 4323, -1, 4336, 4310, 4309, -1, 4336, 4298, 4325, -1, 4336, 4338, 4310, -1, 4339, 4308, 4331, -1, 4340, 4325, 4314, -1, 4340, 4314, 4329, -1, 4339, 4318, 4308, -1, 4341, 4326, 4332, -1, 4342, 4329, 4317, -1, 4342, 4317, 4330, -1, 4341, 4335, 4326, -1, 4343, 4313, 4344, -1, 4345, 4312, 4335, -1, 4343, 4321, 4313, -1, 4345, 4320, 4312, -1, 4346, 4324, 4333, -1, 4347, 4322, 4337, -1, 4346, 4334, 4324, -1, 4347, 4332, 4322, -1, 4348, 4330, 4319, -1, 4349, 4337, 4323, -1, 4348, 4319, 4334, -1, 4349, 4323, 4350, -1, 4351, 4325, 4340, -1, 4351, 4336, 4325, -1, 4351, 4338, 4336, -1, 4352, 4318, 4339, -1, 4352, 4353, 4328, -1, 4354, 4329, 4342, -1, 4352, 4328, 4327, -1, 4354, 4340, 4329, -1, 4352, 4327, 4318, -1, 4355, 4335, 4341, -1, 4356, 4333, 4321, -1, 4355, 4345, 4335, -1, 4356, 4321, 4343, -1, 4357, 4320, 4345, -1, 4357, 4331, 4320, -1, 4358, 4348, 4334, -1, 4358, 4334, 4346, -1, 4359, 4341, 4332, -1, 4359, 4332, 4347, -1, 4360, 4342, 4330, -1, 4360, 4330, 4348, -1, 4361, 4349, 4350, -1, 4362, 4351, 4340, -1, 4362, 4340, 4354, -1, 4362, 4363, 4338, -1, 4362, 4338, 4351, -1, 4364, 4337, 4349, -1, 4364, 4347, 4337, -1, 4365, 4346, 4333, -1, 4365, 4333, 4356, -1, 4366, 4357, 4345, -1, 4366, 4345, 4355, -1, 4367, 4348, 4358, -1, 4367, 4360, 4348, -1, 4368, 4342, 4360, -1, 4369, 4339, 4331, -1, 4368, 4354, 4342, -1, 4369, 4331, 4357, -1, 4370, 4355, 4341, -1, 4370, 4341, 4359, -1, 4371, 4349, 4361, -1, 4371, 4364, 4349, -1, 4372, 4346, 4365, -1, 4372, 4358, 4346, -1, 4373, 4360, 4367, -1, 4373, 4368, 4360, -1, 4374, 4359, 4347, -1, 4374, 4347, 4364, -1, 4375, 4362, 4354, -1, 4375, 4363, 4362, -1, 4375, 4354, 4368, -1, 4376, 4357, 4366, -1, 4376, 4369, 4357, -1, 4377, 4352, 4339, -1, 4377, 4353, 4352, -1, 4377, 4339, 4369, -1, 4377, 4378, 4353, -1, 4379, 4367, 4358, -1, 4379, 4358, 4372, -1, 4380, 4355, 4370, -1, 4380, 4366, 4355, -1, 4381, 4368, 4373, -1, 4381, 4375, 4368, -1, 4382, 4361, 4350, -1, 4381, 4363, 4375, -1, 4381, 4383, 4363, -1, 4382, 4350, 4384, -1, 4385, 4364, 4371, -1, 4385, 4374, 4364, -1, 4386, 4387, 4388, -1, 4386, 4388, 4389, -1, 4390, 4370, 4359, -1, 4390, 4359, 4374, -1, 4391, 4373, 4367, -1, 4391, 4367, 4379, -1, 4392, 4369, 4376, -1, 4392, 4377, 4369, -1, 4392, 4378, 4377, -1, 4393, 4376, 4366, -1, 4393, 4366, 4380, -1, 4394, 4395, 4387, -1, 4394, 4387, 4386, -1, 4396, 4361, 4382, -1, 4396, 4371, 4361, -1, 4397, 4381, 4373, -1, 4397, 4373, 4391, -1, 4397, 4383, 4381, -1, 4398, 4390, 4374, -1, 4398, 4374, 4385, -1, 4399, 4380, 4370, -1, 4399, 4370, 4390, -1, 4400, 4401, 4395, -1, 4402, 4403, 4378, -1, 4402, 4376, 4393, -1, 4400, 4395, 4394, -1, 4402, 4392, 4376, -1, 4402, 4378, 4392, -1, 4404, 4386, 4389, -1, 4405, 4371, 4396, -1, 4404, 4389, 4406, -1, 4405, 4385, 4371, -1, 4407, 4390, 4398, -1, 4408, 4409, 4401, -1, 4407, 4399, 4390, -1, 4408, 4401, 4400, -1, 4410, 4393, 4380, -1, 4410, 4380, 4399, -1, 4411, 4406, 4412, -1, 4411, 4404, 4406, -1, 4413, 4385, 4405, -1, 4414, 4386, 4404, -1, 4414, 4394, 4386, -1, 4413, 4398, 4385, -1, 4415, 4410, 4399, -1, 4415, 4399, 4407, -1, 4416, 4393, 4410, -1, 4416, 4402, 4393, -1, 4417, 4418, 4409, -1, 4416, 4403, 4402, -1, 4417, 4409, 4408, -1, 4419, 4407, 4398, -1, 4419, 4398, 4413, -1, 4420, 4416, 4410, -1, 4420, 4410, 4415, -1, 4421, 4404, 4411, -1, 4420, 4403, 4416, -1, 4421, 4414, 4404, -1, 4420, 4422, 4403, -1, 4423, 4415, 4407, -1, 4424, 4394, 4414, -1, 4424, 4400, 4394, -1, 4423, 4407, 4419, -1, 4425, 4415, 4423, -1, 4425, 4420, 4415, -1, 4425, 4422, 4420, -1, 4426, 4411, 4412, -1, 4427, 4428, 4418, -1, 4427, 4418, 4417, -1, 4429, 4430, 4431, -1, 4429, 4432, 4430, -1, 4433, 4424, 4414, -1, 4433, 4414, 4421, -1, 4434, 4432, 4429, -1, 4434, 4429, 4435, -1, 4436, 4408, 4400, -1, 4436, 4400, 4424, -1, 4437, 4421, 4411, -1, 4438, 4439, 4440, -1, 4437, 4411, 4426, -1, 4441, 4412, 4442, -1, 4441, 4426, 4412, -1, 4443, 4438, 4444, -1, 4445, 4446, 4428, -1, 4443, 4439, 4438, -1, 4445, 4447, 4446, -1, 4445, 4428, 4427, -1, 4448, 4449, 4450, -1, 4445, 4451, 4447, -1, 4448, 4452, 4449, -1, 4448, 4450, 4453, -1, 4448, 4453, 4454, -1, 4455, 4436, 4424, -1, 4455, 4424, 4433, -1, 4456, 4448, 4454, -1, 4457, 4417, 4408, -1, 4456, 4452, 4448, -1, 4458, 4459, 4460, -1, 4457, 4408, 4436, -1, 4458, 4293, 4305, -1, 4461, 4421, 4437, -1, 4461, 4433, 4421, -1, 4462, 4396, 4382, -1, 4463, 4441, 4442, -1, 4464, 4426, 4441, -1, 4465, 4462, 4466, -1, 4464, 4437, 4426, -1, 4465, 4396, 4462, -1, 4467, 4436, 4455, -1, 4467, 4457, 4436, -1, 4468, 4431, 4469, -1, 4468, 4435, 4429, -1, 4468, 4469, 4470, -1, 4468, 4470, 4435, -1, 4468, 4429, 4431, -1, 4471, 4432, 4434, -1, 4471, 4472, 4432, -1, 4473, 4417, 4457, -1, 4471, 4474, 4472, -1, 4473, 4427, 4417, -1, 4475, 4434, 4435, -1, 4476, 4455, 4433, -1, 4475, 4471, 4434, -1, 4476, 4433, 4461, -1, 4475, 4477, 4478, -1, 4475, 4435, 4477, -1, 4479, 4343, 4344, -1, 4480, 4464, 4441, -1, 4479, 4481, 4343, -1, 4480, 4441, 4463, -1, 4482, 4387, 4395, -1, 4482, 4388, 4387, -1, 4482, 4344, 4388, -1, 4483, 4461, 4437, -1, 4482, 4479, 4344, -1, 4483, 4437, 4464, -1, 4482, 4481, 4479, -1, 4484, 4365, 4356, -1, 4484, 4343, 4481, -1, 4485, 4457, 4467, -1, 4484, 4356, 4343, -1, 4486, 4395, 4401, -1, 4485, 4473, 4457, -1, 4487, 4445, 4427, -1, 4486, 4482, 4395, -1, 4487, 4451, 4445, -1, 4486, 4481, 4482, -1, 4486, 4484, 4481, -1, 4488, 4438, 4440, -1, 4487, 4427, 4473, -1, 4488, 4440, 4489, -1, 4487, 4490, 4451, -1, 4491, 4455, 4476, -1, 4492, 4489, 4493, -1, 4492, 4444, 4438, -1, 4492, 4493, 4494, -1, 4492, 4438, 4488, -1, 4491, 4467, 4455, -1, 4492, 4488, 4489, -1, 4492, 4494, 4444, -1, 4440, 4463, 4442, -1, 4440, 4442, 4489, -1, 4495, 4439, 4443, -1, 4495, 4496, 4497, -1, 4495, 4497, 4439, -1, 4498, 4464, 4480, -1, 4498, 4483, 4464, -1, 4499, 4444, 4500, -1, 4499, 4500, 4501, -1, 4499, 4495, 4443, -1, 4499, 4443, 4444, -1, 4502, 4476, 4461, -1, 4503, 4504, 4452, -1, 4503, 4505, 4504, -1, 4502, 4461, 4483, -1, 4503, 4452, 4456, -1, 4506, 4456, 4454, -1, 4507, 4473, 4485, -1, 4506, 4508, 4509, -1, 4507, 4490, 4487, -1, 4506, 4454, 4508, -1, 4507, 4487, 4473, -1, 4506, 4503, 4456, -1, 4510, 4485, 4467, -1, 4511, 4460, 4512, -1, 4510, 4467, 4491, -1, 4511, 4458, 4460, -1, 4513, 4458, 4511, -1, 4439, 4480, 4463, -1, 4513, 4293, 4458, -1, 4439, 4463, 4440, -1, 4513, 4512, 4294, -1, 4513, 4294, 4293, -1, 4513, 4511, 4512, -1, 4514, 4301, 4459, -1, 4514, 4459, 4458, -1, 4515, 4502, 4483, -1, 4515, 4483, 4498, -1, 4516, 4514, 4458, -1, 4516, 4458, 4305, -1, 4516, 4301, 4514, -1, 4516, 4302, 4301, -1, 4516, 4305, 4302, -1, 4517, 4476, 4502, -1, 4517, 4491, 4476, -1, 4518, 4382, 4384, -1, 4518, 4462, 4382, -1, 4519, 4518, 4384, -1, 4519, 4466, 4462, -1, 4520, 4485, 4510, -1, 4519, 4384, 4521, -1, 4520, 4507, 4485, -1, 4519, 4521, 4522, -1, 4519, 4522, 4466, -1, 4520, 4490, 4507, -1, 4519, 4462, 4518, -1, 4523, 4524, 4525, -1, 4520, 4526, 4490, -1, 4527, 4413, 4405, -1, 4523, 4528, 4524, -1, 4497, 4498, 4480, -1, 4527, 4396, 4465, -1, 4497, 4480, 4439, -1, 4527, 4405, 4396, -1, 4529, 4527, 4465, -1, 4529, 4466, 4530, -1, 4531, 4502, 4515, -1, 4529, 4530, 4532, -1, 4533, 4534, 4528, -1, 4531, 4517, 4502, -1, 4529, 4465, 4466, -1, 4535, 4474, 4471, -1, 4536, 4510, 4491, -1, 4535, 4537, 4474, -1, 4533, 4528, 4523, -1, 4536, 4491, 4517, -1, 4538, 4539, 4534, -1, 4540, 4535, 4471, -1, 4541, 4540, 4471, -1, 4538, 4534, 4533, -1, 4542, 4525, 4543, -1, 4541, 4471, 4475, -1, 4496, 4515, 4498, -1, 4496, 4498, 4497, -1, 4544, 4540, 4541, -1, 4542, 4523, 4525, -1, 4545, 4541, 4475, -1, 4545, 4544, 4541, -1, 4546, 4547, 4539, -1, 4548, 4536, 4517, -1, 4548, 4517, 4531, -1, 4545, 4475, 4478, -1, 4545, 4478, 4549, -1, 4546, 4539, 4538, -1, 4550, 4372, 4365, -1, 4551, 4520, 4510, -1, 4552, 4543, 4553, -1, 4551, 4526, 4520, -1, 4551, 4510, 4536, -1, 4550, 4365, 4484, -1, 4552, 4542, 4543, -1, 4554, 4484, 4486, -1, 4554, 4550, 4484, -1, 4555, 4533, 4523, -1, 4555, 4523, 4542, -1, 4556, 4554, 4486, -1, 4556, 4550, 4554, -1, 4557, 4531, 4515, -1, 4558, 4559, 4547, -1, 4557, 4515, 4496, -1, 4560, 4526, 4551, -1, 4561, 4556, 4486, -1, 4558, 4547, 4546, -1, 4560, 4536, 4548, -1, 4560, 4562, 4526, -1, 4563, 4401, 4409, -1, 4563, 4486, 4401, -1, 4560, 4551, 4536, -1, 4563, 4561, 4486, -1, 4564, 4542, 4552, -1, 4565, 4557, 4496, -1, 4564, 4555, 4542, -1, 4565, 4496, 4495, -1, 4566, 4533, 4555, -1, 4567, 4565, 4495, -1, 4566, 4538, 4533, -1, 4568, 4548, 4531, -1, 4567, 4495, 4499, -1, 4568, 4531, 4557, -1, 4569, 4552, 4553, -1, 4570, 4493, 4571, -1, 4572, 4565, 4567, -1, 4570, 4494, 4493, -1, 4573, 4574, 4559, -1, 4573, 4559, 4558, -1, 4575, 4567, 4499, -1, 4576, 4555, 4564, -1, 4575, 4572, 4567, -1, 4577, 4575, 4499, -1, 4576, 4566, 4555, -1, 4578, 4548, 4568, -1, 4577, 4501, 4579, -1, 4578, 4560, 4548, -1, 4577, 4499, 4501, -1, 4578, 4562, 4560, -1, 4580, 4581, 4505, -1, 4582, 4538, 4566, -1, 4583, 4494, 4570, -1, 4580, 4505, 4503, -1, 4582, 4546, 4538, -1, 4584, 4580, 4503, -1, 4585, 4552, 4569, -1, 4583, 4444, 4494, -1, 4585, 4564, 4552, -1, 4586, 4553, 4587, -1, 4588, 4503, 4506, -1, 4586, 4569, 4553, -1, 4589, 4500, 4444, -1, 4589, 4444, 4583, -1, 4590, 4584, 4503, -1, 4591, 4592, 3436, -1, 4590, 4503, 4588, -1, 4591, 4574, 4573, -1, 4593, 4506, 4509, -1, 4591, 4594, 4574, -1, 4593, 4509, 4595, -1, 4591, 3436, 4594, -1, 4593, 4588, 4506, -1, 4593, 4590, 4588, -1, 4596, 4582, 4566, -1, 4597, 4419, 4413, -1, 4598, 4571, 4599, -1, 4596, 4566, 4576, -1, 4598, 4570, 4571, -1, 4597, 4413, 4527, -1, 4600, 4558, 4546, -1, 4600, 4546, 4582, -1, 4601, 4564, 4585, -1, 4602, 4597, 4527, -1, 4603, 4501, 4500, -1, 4603, 4500, 4589, -1, 4601, 4576, 4564, -1, 4604, 4527, 4529, -1, 4605, 4586, 4587, -1, 4606, 4602, 4527, -1, 4607, 4598, 4599, -1, 4606, 4527, 4604, -1, 4608, 4604, 4529, -1, 4607, 4599, 4609, -1, 4608, 4529, 4532, -1, 4610, 4585, 4569, -1, 4608, 4532, 4611, -1, 4610, 4569, 4586, -1, 4608, 4606, 4604, -1, 4612, 4537, 4535, -1, 4613, 4582, 4596, -1, 4612, 4614, 4537, -1, 4615, 4570, 4598, -1, 4613, 4600, 4582, -1, 4612, 4535, 4540, -1, 4616, 4612, 4540, -1, 4617, 4573, 4558, -1, 4615, 4583, 4570, -1, 4616, 4540, 4544, -1, 4616, 4544, 4545, -1, 4616, 4545, 4549, -1, 4617, 4558, 4600, -1, 4618, 4501, 4603, -1, 4616, 4549, 4619, -1, 4620, 4576, 4601, -1, 4621, 4379, 4372, -1, 4620, 4596, 4576, -1, 4621, 4550, 4556, -1, 4621, 4556, 4561, -1, 4618, 4579, 4501, -1, 4622, 4598, 4607, -1, 4622, 4615, 4598, -1, 4621, 4372, 4550, -1, 4623, 4586, 4605, -1, 4624, 4409, 4418, -1, 4623, 4610, 4586, -1, 4624, 4563, 4409, -1, 4624, 4561, 4563, -1, 4624, 4621, 4561, -1, 4625, 4565, 4572, -1, 4626, 4583, 4615, -1, 4625, 4568, 4557, -1, 4626, 4589, 4583, -1, 4627, 4601, 4585, -1, 4627, 4585, 4610, -1, 4625, 4572, 4575, -1, 4625, 4557, 4565, -1, 4628, 4625, 4575, -1, 4629, 4600, 4613, -1, 4630, 4607, 4609, -1, 4628, 4579, 4631, -1, 4629, 4617, 4600, -1, 4628, 4577, 4579, -1, 4632, 4633, 4592, -1, 4628, 4575, 4577, -1, 4632, 4591, 4573, -1, 4634, 4635, 4581, -1, 4632, 4592, 4591, -1, 4636, 4631, 4579, -1, 4634, 4581, 4580, -1, 4636, 4579, 4618, -1, 4632, 4573, 4617, -1, 4634, 4580, 4584, -1, 4637, 4596, 4620, -1, 4638, 4595, 4639, -1, 4640, 4626, 4615, -1, 4638, 4634, 4584, -1, 4637, 4613, 4596, -1, 4638, 4584, 4590, -1, 4638, 4593, 4595, -1, 4430, 4587, 4431, -1, 4640, 4615, 4622, -1, 4638, 4590, 4593, -1, 4641, 4603, 4589, -1, 4430, 4605, 4587, -1, 4642, 4419, 4597, -1, 4642, 4423, 4419, -1, 4642, 4597, 4602, -1, 4641, 4589, 4626, -1, 4643, 4606, 4608, -1, 4644, 4627, 4610, -1, 4643, 4642, 4602, -1, 4645, 4622, 4607, -1, 4643, 4611, 4646, -1, 4644, 4610, 4623, -1, 4647, 4620, 4601, -1, 4645, 4607, 4630, -1, 4643, 4602, 4606, -1, 4643, 4608, 4611, -1, 4648, 4609, 4649, -1, 4650, 4612, 4616, -1, 4647, 4601, 4627, -1, 4648, 4630, 4609, -1, 4650, 4614, 4612, -1, 4651, 4617, 4629, -1, 4650, 4652, 4614, -1, 4651, 4632, 4617, -1, 4653, 4654, 4631, -1, 4653, 4655, 4654, -1, 4656, 4650, 4616, -1, 4651, 4633, 4632, -1, 4653, 4631, 4636, -1, 4657, 4629, 4613, -1, 4653, 4658, 4655, -1, 4657, 4613, 4637, -1, 4659, 4641, 4626, -1, 4659, 4626, 4640, -1, 4660, 4619, 4661, -1, 4660, 4616, 4619, -1, 4660, 4656, 4616, -1, 4662, 4618, 4603, -1, 4663, 4391, 4379, -1, 4432, 4605, 4430, -1, 4662, 4603, 4641, -1, 4663, 4379, 4621, -1, 4432, 4623, 4605, -1, 4664, 4622, 4645, -1, 4665, 4663, 4621, -1, 4664, 4640, 4622, -1, 4666, 4627, 4644, -1, 4666, 4647, 4627, -1, 4667, 4621, 4624, -1, 4668, 4637, 4620, -1, 4667, 4665, 4621, -1, 4668, 4620, 4647, -1, 4669, 4645, 4630, -1, 4667, 4624, 4418, -1, 4667, 4418, 4428, -1, 4670, 4651, 4629, -1, 4669, 4630, 4648, -1, 4670, 4633, 4651, -1, 4670, 4671, 4633, -1, 4672, 4568, 4625, -1, 4670, 4629, 4657, -1, 4672, 4578, 4568, -1, 4673, 4648, 4649, -1, 4674, 4672, 4625, -1, 4472, 4623, 4432, -1, 4675, 4662, 4641, -1, 4472, 4644, 4623, -1, 4675, 4641, 4659, -1, 4676, 4628, 4631, -1, 4676, 4625, 4628, -1, 4677, 4668, 4647, -1, 4678, 4636, 4618, -1, 4676, 4631, 4654, -1, 4678, 4618, 4662, -1, 4676, 4674, 4625, -1, 4677, 4647, 4666, -1, 4679, 4680, 4635, -1, 4679, 4634, 4638, -1, 4681, 4657, 4637, -1, 4682, 4659, 4640, -1, 4679, 4635, 4634, -1, 4682, 4640, 4664, -1, 4681, 4637, 4668, -1, 4683, 4679, 4638, -1, 4684, 4664, 4645, -1, 4685, 4639, 4686, -1, 4685, 4638, 4639, -1, 4684, 4645, 4669, -1, 4685, 4683, 4638, -1, 4687, 4425, 4423, -1, 4474, 4644, 4472, -1, 4687, 4423, 4642, -1, 4688, 4669, 4648, -1, 4687, 4642, 4643, -1, 4474, 4666, 4644, -1, 4689, 4668, 4677, -1, 4690, 4687, 4643, -1, 4688, 4648, 4673, -1, 4689, 4681, 4668, -1, 4691, 4678, 4662, -1, 4691, 4662, 4675, -1, 4692, 4643, 4646, -1, 4692, 4690, 4643, -1, 4693, 4657, 4681, -1, 4692, 4646, 4694, -1, 4693, 4670, 4657, -1, 4695, 4653, 4636, -1, 4696, 4697, 4698, -1, 4693, 4671, 4670, -1, 4695, 4658, 4653, -1, 4696, 4650, 4656, -1, 4695, 4636, 4678, -1, 4696, 4652, 4650, -1, 4695, 4699, 4658, -1, 4696, 4698, 4652, -1, 4700, 4697, 4696, -1, 4449, 4649, 4450, -1, 4700, 4660, 4661, -1, 4700, 4656, 4660, -1, 4700, 4661, 4697, -1, 4700, 4696, 4656, -1, 4449, 4673, 4649, -1, 4701, 4391, 4663, -1, 4701, 4397, 4391, -1, 4537, 4677, 4666, -1, 4702, 4675, 4659, -1, 4701, 4663, 4665, -1, 4537, 4666, 4474, -1, 4702, 4659, 4682, -1, 4703, 4701, 4665, -1, 4704, 4698, 4671, -1, 4703, 4665, 4667, -1, 4703, 4667, 4428, -1, 4704, 4671, 4693, -1, 4704, 4681, 4689, -1, 4705, 4682, 4664, -1, 4703, 4428, 4446, -1, 4704, 4693, 4681, -1, 4706, 4562, 4578, -1, 4705, 4664, 4684, -1, 4706, 4672, 4674, -1, 4707, 4684, 4669, -1, 4706, 4578, 4672, -1, 4708, 4562, 4706, -1, 4708, 4654, 4655, -1, 4707, 4669, 4688, -1, 4708, 4676, 4654, -1, 4708, 4674, 4676, -1, 4709, 4695, 4678, -1, 4708, 4655, 4562, -1, 4708, 4706, 4674, -1, 4614, 4689, 4677, -1, 4710, 4679, 4683, -1, 4709, 4678, 4691, -1, 4710, 4680, 4679, -1, 4614, 4677, 4537, -1, 4709, 4699, 4695, -1, 4452, 4673, 4449, -1, 4452, 4688, 4673, -1, 4710, 4711, 4712, -1, 4713, 4469, 4714, -1, 4710, 4712, 4680, -1, 4715, 4710, 4683, -1, 4713, 4470, 4469, -1, 4715, 4685, 4686, -1, 4715, 4683, 4685, -1, 4715, 4686, 4711, -1, 4715, 4711, 4710, -1, 4716, 4691, 4675, -1, 4717, 4425, 4687, -1, 4717, 4422, 4425, -1, 4716, 4675, 4702, -1, 4717, 3427, 4422, -1, 4717, 4687, 4690, -1, 4718, 3427, 4717, -1, 4719, 4702, 4682, -1, 4718, 4717, 4690, -1, 4719, 4682, 4705, -1, 4718, 4694, 3427, -1, 4652, 4698, 4704, -1, 4718, 4690, 4692, -1, 4718, 4692, 4694, -1, 4652, 4704, 4689, -1, 4720, 4383, 4397, -1, 4720, 4446, 4447, -1, 4721, 4705, 4684, -1, 4652, 4689, 4614, -1, 4720, 4397, 4701, -1, 4720, 4701, 4703, -1, 4720, 4703, 4446, -1, 4722, 4435, 4470, -1, 4720, 4447, 4383, -1, 4721, 4684, 4707, -1, 4504, 4688, 4452, -1, 4504, 4707, 4688, -1, 4722, 4470, 4713, -1, 4723, 4691, 4716, -1, 4723, 4699, 4709, -1, 4723, 4724, 4699, -1, 4723, 4709, 4691, -1, 4725, 4435, 4722, -1, 4725, 4477, 4435, -1, 4726, 4716, 4702, -1, 4726, 4702, 4719, -1, 4727, 4714, 4728, -1, 4729, 4719, 4705, -1, 4727, 4713, 4714, -1, 4729, 4705, 4721, -1, 4453, 4450, 4730, -1, 4731, 4477, 4725, -1, 4505, 4721, 4707, -1, 4505, 4707, 4504, -1, 4731, 4478, 4477, -1, 4732, 4724, 4723, -1, 4732, 4723, 4716, -1, 4733, 4728, 4734, -1, 4732, 4716, 4726, -1, 4733, 4727, 4728, -1, 4735, 4719, 4729, -1, 4735, 4726, 4719, -1, 4736, 4713, 4727, -1, 4736, 4722, 4713, -1, 4581, 4729, 4721, -1, 4581, 4721, 4505, -1, 4737, 4478, 4731, -1, 4737, 4549, 4478, -1, 4738, 4726, 4735, -1, 4738, 4732, 4726, -1, 4739, 4736, 4727, -1, 4738, 4712, 4724, -1, 4738, 4724, 4732, -1, 4739, 4727, 4733, -1, 4740, 4722, 4736, -1, 4635, 4735, 4729, -1, 4740, 4725, 4722, -1, 4635, 4729, 4581, -1, 4741, 4733, 4734, -1, 4742, 4730, 4743, -1, 4742, 4453, 4730, -1, 4744, 4549, 4737, -1, 4744, 4619, 4549, -1, 4745, 4736, 4739, -1, 4745, 4740, 4736, -1, 4746, 4731, 4725, -1, 4680, 4738, 4735, -1, 4680, 4735, 4635, -1, 4746, 4725, 4740, -1, 4680, 4712, 4738, -1, 4747, 4454, 4453, -1, 4748, 4739, 4733, -1, 4747, 4453, 4742, -1, 4748, 4733, 4741, -1, 4749, 4734, 4750, -1, 4749, 4741, 4734, -1, 4751, 4752, 4697, -1, 4753, 4508, 4454, -1, 4751, 4661, 4619, -1, 4751, 4697, 4661, -1, 4751, 4619, 4744, -1, 4753, 4454, 4747, -1, 4754, 4746, 4740, -1, 4755, 4743, 4756, -1, 4754, 4740, 4745, -1, 4755, 4742, 4743, -1, 4757, 4731, 4746, -1, 4757, 4737, 4731, -1, 4758, 4745, 4739, -1, 4758, 4739, 4748, -1, 4759, 4509, 4508, -1, 4759, 4508, 4753, -1, 4760, 4748, 4741, -1, 4760, 4741, 4749, -1, 4761, 4756, 4762, -1, 4763, 4749, 4750, -1, 4761, 4755, 4756, -1, 4764, 4742, 4755, -1, 4765, 4746, 4754, -1, 4764, 4747, 4742, -1, 4765, 4757, 4746, -1, 4766, 4744, 4737, -1, 4766, 4737, 4757, -1, 4767, 4745, 4758, -1, 4767, 4754, 4745, -1, 4768, 4595, 4509, -1, 4769, 4748, 4760, -1, 4768, 4509, 4759, -1, 4769, 4758, 4748, -1, 4770, 4755, 4761, -1, 4770, 4764, 4755, -1, 4771, 4760, 4749, -1, 4771, 4749, 4763, -1, 4772, 4747, 4764, -1, 4772, 4753, 4747, -1, 4773, 4757, 4765, -1, 4773, 4766, 4757, -1, 4774, 4775, 4752, -1, 4776, 4761, 4762, -1, 4774, 4744, 4766, -1, 4774, 4752, 4751, -1, 4777, 4639, 4595, -1, 4774, 4751, 4744, -1, 4777, 4595, 4768, -1, 4778, 4750, 4779, -1, 4778, 4763, 4750, -1, 4780, 4764, 4770, -1, 4780, 4772, 4764, -1, 4781, 4765, 4754, -1, 4782, 4759, 4753, -1, 4782, 4753, 4772, -1, 4781, 4754, 4767, -1, 4783, 4767, 4758, -1, 4783, 4758, 4769, -1, 4784, 4770, 4761, -1, 4785, 4769, 4760, -1, 4784, 4761, 4776, -1, 4785, 4760, 4771, -1, 4786, 4776, 4762, -1, 4786, 4762, 4787, -1, 4788, 4775, 4774, -1, 4788, 4766, 4773, -1, 4789, 4686, 4639, -1, 4788, 4774, 4766, -1, 4789, 4711, 4686, -1, 4790, 4778, 4779, -1, 4789, 4791, 4711, -1, 4789, 4639, 4777, -1, 4792, 4782, 4772, -1, 4792, 4772, 4780, -1, 4793, 4771, 4763, -1, 4794, 4759, 4782, -1, 4793, 4763, 4778, -1, 4795, 4765, 4781, -1, 4794, 4768, 4759, -1, 4795, 4773, 4765, -1, 4796, 4780, 4770, -1, 4797, 4767, 4783, -1, 4796, 4770, 4784, -1, 4797, 4781, 4767, -1, 4798, 4784, 4776, -1, 4799, 4769, 4785, -1, 4798, 4776, 4786, -1, 4799, 4783, 4769, -1, 4800, 4786, 4787, -1, 4801, 4778, 4790, -1, 4802, 4794, 4782, -1, 4802, 4782, 4792, -1, 4801, 4793, 4778, -1, 4803, 4771, 4793, -1, 4804, 4768, 4794, -1, 4804, 4777, 4768, -1, 4803, 4785, 4771, -1, 4805, 4788, 4773, -1, 4805, 4806, 4775, -1, 4807, 4792, 4780, -1, 4807, 4780, 4796, -1, 4805, 4773, 4795, -1, 4805, 4775, 4788, -1, 4808, 4795, 4781, -1, 4809, 4796, 4784, -1, 4809, 4784, 4798, -1, 4808, 4781, 4797, -1, 4810, 4797, 4783, -1, 4810, 4783, 4799, -1, 4811, 4798, 4786, -1, 4811, 4786, 4800, -1, 4812, 4793, 4801, -1, 4813, 4804, 4794, -1, 4812, 4803, 4793, -1, 4813, 4794, 4802, -1, 4814, 4779, 4815, -1, 4816, 4789, 4777, -1, 4816, 4777, 4804, -1, 4814, 4790, 4779, -1, 4816, 4791, 4789, -1, 4816, 4817, 4791, -1, 4818, 4799, 4785, -1, 4819, 4787, 4820, -1, 4818, 4785, 4803, -1, 4819, 4800, 4787, -1, 4821, 4806, 4805, -1, 4822, 4802, 4792, -1, 4821, 4805, 4795, -1, 4822, 4792, 4807, -1, 4821, 4795, 4808, -1, 4823, 4808, 4797, -1, 4824, 4807, 4796, -1, 4824, 4796, 4809, -1, 4823, 4797, 4810, -1, 4825, 4803, 4812, -1, 4826, 4809, 4798, -1, 4826, 4798, 4811, -1, 4825, 4818, 4803, -1, 4827, 4816, 4804, -1, 4827, 4804, 4813, -1, 4828, 4790, 4814, -1, 4827, 4817, 4816, -1, 4828, 4801, 4790, -1, 4829, 4819, 4820, -1, 4830, 4810, 4799, -1, 4830, 4799, 4818, -1, 4831, 4800, 4819, -1, 4832, 4833, 4806, -1, 4832, 4806, 4821, -1, 4832, 4821, 4808, -1, 4832, 4808, 4823, -1, 4831, 4811, 4800, -1, 4834, 4813, 4802, -1, 4835, 4818, 4825, -1, 4834, 4802, 4822, -1, 4835, 4830, 4818, -1, 4836, 4822, 4807, -1, 4837, 4812, 4801, -1, 4836, 4807, 4824, -1, 4837, 4801, 4828, -1, 4838, 4824, 4809, -1, 4839, 4823, 4810, -1, 4839, 4810, 4830, -1, 4838, 4809, 4826, -1, 4840, 4815, 4841, -1, 4840, 4814, 4815, -1, 4842, 4831, 4819, -1, 4842, 4819, 4829, -1, 4843, 4811, 4831, -1, 4843, 4826, 4811, -1, 4844, 4830, 4835, -1, 4844, 4839, 4830, -1, 4845, 4827, 4813, -1, 4845, 4846, 4817, -1, 4847, 4812, 4837, -1, 4845, 4813, 4834, -1, 4847, 4825, 4812, -1, 4845, 4817, 4827, -1, 4848, 4822, 4836, -1, 4849, 4833, 4832, -1, 4849, 4823, 4839, -1, 4848, 4834, 4822, -1, 4849, 4832, 4823, -1, 4850, 4836, 4824, -1, 4850, 4824, 4838, -1, 4851, 4828, 4814, -1, 4852, 4843, 4831, -1, 4851, 4814, 4840, -1, 4853, 4854, 4833, -1, 4853, 4839, 4844, -1, 4852, 4831, 4842, -1, 4853, 4849, 4839, -1, 4853, 4833, 4849, -1, 4855, 4825, 4847, -1, 4855, 4835, 4825, -1, 4856, 4820, 4857, -1, 4856, 4829, 4820, -1, 4858, 4838, 4826, -1, 4859, 4837, 4828, -1, 4859, 4828, 4851, -1, 4858, 4826, 4843, -1, 4860, 4834, 4848, -1, 4860, 4845, 4834, -1, 4861, 4841, 4862, -1, 4861, 4840, 4841, -1, 4860, 4846, 4845, -1, 4863, 4848, 4836, -1, 4863, 4836, 4850, -1, 4864, 4858, 4843, -1, 4865, 4844, 4835, -1, 4864, 4843, 4852, -1, 4865, 4835, 4855, -1, 4866, 4862, 4867, -1, 4866, 4861, 4862, -1, 4868, 4829, 4856, -1, 4868, 4842, 4829, -1, 4869, 4847, 4837, -1, 4869, 4837, 4859, -1, 4870, 4850, 4838, -1, 4870, 4838, 4858, -1, 4871, 4840, 4861, -1, 4872, 4860, 4848, -1, 4872, 4848, 4863, -1, 4872, 4846, 4860, -1, 4871, 4851, 4840, -1, 4872, 4873, 4846, -1, 4874, 4858, 4864, -1, 4874, 4870, 4858, -1, 4875, 4854, 4853, -1, 4875, 4853, 4844, -1, 4875, 4844, 4865, -1, 4876, 4852, 4842, -1, 4877, 4871, 4861, -1, 4876, 4842, 4868, -1, 4877, 4861, 4866, -1, 4878, 4850, 4870, -1, 4878, 4863, 4850, -1, 4879, 4855, 4847, -1, 4879, 4847, 4869, -1, 4880, 4856, 4857, -1, 4881, 4851, 4871, -1, 4880, 4857, 4882, -1, 4883, 4870, 4874, -1, 4881, 4859, 4851, -1, 4883, 4878, 4870, -1, 4884, 4864, 4852, -1, 4885, 4866, 4867, -1, 4884, 4852, 4876, -1, 4886, 4871, 4877, -1, 4886, 4881, 4871, -1, 4887, 4872, 4863, -1, 4887, 4863, 4878, -1, 4887, 4873, 4872, -1, 4888, 4865, 4855, -1, 4888, 4855, 4879, -1, 4889, 4856, 4880, -1, 4889, 4868, 4856, -1, 4890, 4859, 4881, -1, 4890, 4869, 4859, -1, 4891, 4887, 4878, -1, 4892, 4877, 4866, -1, 4891, 4878, 4883, -1, 4891, 4873, 4887, -1, 4892, 4866, 4885, -1, 4891, 4893, 4873, -1, 4894, 4864, 4884, -1, 4895, 4867, 4896, -1, 4895, 4885, 4867, -1, 4894, 4874, 4864, -1, 4897, 4876, 4868, -1, 4898, 4881, 4886, -1, 4897, 4868, 4889, -1, 4898, 4890, 4881, -1, 4899, 4900, 4854, -1, 4899, 4875, 4865, -1, 4899, 4865, 4888, -1, 4901, 4882, 4902, -1, 4899, 4854, 4875, -1, 4901, 4880, 4882, -1, 4903, 4879, 4869, -1, 4903, 4869, 4890, -1, 4904, 4883, 4874, -1, 4904, 4874, 4894, -1, 4905, 4877, 4892, -1, 4906, 4902, 4907, -1, 4906, 4901, 4902, -1, 4905, 4886, 4877, -1, 4908, 4884, 4876, -1, 4908, 4876, 4897, -1, 4909, 4885, 4895, -1, 4909, 4892, 4885, -1, 4910, 4895, 4896, -1, 4911, 4889, 4880, -1, 4912, 4903, 4890, -1, 4912, 4890, 4898, -1, 4911, 4880, 4901, -1, 4913, 4888, 4879, -1, 4914, 4891, 4883, -1, 4914, 4893, 4891, -1, 4913, 4879, 4903, -1, 4914, 4883, 4904, -1, 4915, 4898, 4886, -1, 4915, 4886, 4905, -1, 4916, 4901, 4906, -1, 4916, 4911, 4901, -1, 4917, 4905, 4892, -1, 4918, 4894, 4884, -1, 4917, 4892, 4909, -1, 4918, 4884, 4908, -1, 4919, 4909, 4895, -1, 4919, 4895, 4910, -1, 4920, 4897, 4889, -1, 4921, 4903, 4912, -1, 4920, 4889, 4911, -1, 4922, 4906, 4907, -1, 4921, 4913, 4903, -1, 4923, 4900, 4899, -1, 4923, 4899, 4888, -1, 4923, 4888, 4913, -1, 4924, 4911, 4916, -1, 4923, 4925, 4900, -1, 4926, 4896, 4927, -1, 4924, 4920, 4911, -1, 4926, 4910, 4896, -1, 4928, 4904, 4894, -1, 4929, 4912, 4898, -1, 4928, 4894, 4918, -1, 4929, 4898, 4915, -1, 4930, 4897, 4920, -1, 4931, 4915, 4905, -1, 4931, 4905, 4917, -1, 4930, 4908, 4897, -1, 4932, 4906, 4922, -1, 4933, 4909, 4919, -1, 4932, 4916, 4906, -1, 4933, 4917, 4909, -1, 4934, 4913, 4921, -1, 4935, 4907, 4936, -1, 4934, 4923, 4913, -1, 4934, 4925, 4923, -1, 4935, 4922, 4907, -1, 4937, 4920, 4924, -1, 4937, 4930, 4920, -1, 4938, 4926, 4927, -1, 4939, 4940, 4893, -1, 4939, 4914, 4904, -1, 4941, 4919, 4910, -1, 4939, 4904, 4928, -1, 4939, 4893, 4914, -1, 4941, 4910, 4926, -1, 4942, 4918, 4908, -1, 4943, 4921, 4912, -1, 4943, 4912, 4929, -1, 4942, 4908, 4930, -1, 4944, 4929, 4915, -1, 4944, 4915, 4931, -1, 4945, 4916, 4932, -1, 4945, 4924, 4916, -1, 4946, 4931, 4917, -1, 4947, 4932, 4922, -1, 4946, 4917, 4933, -1, 4947, 4922, 4935, -1, 4948, 4935, 4936, -1, 4949, 4926, 4938, -1, 4950, 4930, 4937, -1, 4949, 4941, 4926, -1, 4950, 4942, 4930, -1, 4951, 4918, 4942, -1, 4952, 4933, 4919, -1, 4952, 4919, 4941, -1, 4951, 4928, 4918, -1, 4953, 4934, 4921, -1, 4953, 4921, 4943, -1, 4953, 4925, 4934, -1, 4954, 4937, 4924, -1, 4953, 4955, 4925, -1, 4954, 4924, 4945, -1, 4956, 4929, 4944, -1, 4957, 4945, 4932, -1, 4956, 4943, 4929, -1, 4958, 4944, 4931, -1, 4958, 4931, 4946, -1, 4957, 4932, 4947, -1, 4959, 4947, 4935, -1, 4960, 4927, 4961, -1, 4959, 4935, 4948, -1, 4960, 4938, 4927, -1, 4962, 4951, 4942, -1, 4962, 4942, 4950, -1, 4963, 4952, 4941, -1, 4963, 4941, 4949, -1, 4964, 4928, 4951, -1, 4964, 4939, 4928, -1, 4965, 4946, 4933, -1, 4964, 4966, 4940, -1, 4964, 4940, 4939, -1, 4965, 4933, 4952, -1, 4967, 4948, 4936, -1, 4967, 4936, 4968, -1, 4969, 4953, 4943, -1, 4969, 4955, 4953, -1, 4969, 4943, 4956, -1, 4970, 4937, 4954, -1, 4970, 4950, 4937, -1, 4971, 4944, 4958, -1, 4971, 4956, 4944, -1, 4972, 4945, 4957, -1, 4973, 4949, 4938, -1, 4972, 4954, 4945, -1, 4973, 4938, 4960, -1, 4974, 4947, 4959, -1, 4974, 4957, 4947, -1, 4975, 4965, 4952, -1, 4975, 4952, 4963, -1, 4976, 4951, 4962, -1, 4976, 4964, 4951, -1, 4977, 4958, 4946, -1, 4976, 4966, 4964, -1, 4977, 4946, 4965, -1, 4978, 4955, 4969, -1, 4979, 4967, 4968, -1, 4978, 4969, 4956, -1, 4978, 4956, 4971, -1, 4978, 4980, 4955, -1, 4981, 4948, 4967, -1, 4982, 4963, 4949, -1, 4981, 4959, 4948, -1, 4982, 4949, 4973, -1, 4983, 4962, 4950, -1, 4983, 4950, 4970, -1, 4984, 4977, 4965, -1, 4984, 4965, 4975, -1, 4985, 4970, 4954, -1, 4985, 4954, 4972, -1, 4986, 4958, 4977, -1, 4987, 4972, 4957, -1, 4986, 4971, 4958, -1, 4988, 4961, 4989, -1, 4988, 4960, 4961, -1, 4987, 4957, 4974, -1, 4990, 4975, 4963, -1, 4990, 4963, 4982, -1, 4991, 4967, 4979, -1, 4991, 4981, 4967, -1, 4992, 4974, 4959, -1, 4992, 4959, 4981, -1, 4993, 4977, 4984, -1, 4993, 4986, 4977, -1, 4994, 4976, 4962, -1, 4994, 4995, 4966, -1, 4996, 4980, 4978, -1, 4994, 4966, 4976, -1, 4996, 4971, 4986, -1, 4994, 4962, 4983, -1, 4996, 4978, 4971, -1, 4997, 4983, 4970, -1, 4998, 4960, 4988, -1, 4997, 4970, 4985, -1, 4998, 4973, 4960, -1, 4999, 4985, 4972, -1, 5000, 4984, 4975, -1, 4999, 4972, 4987, -1, 5000, 4975, 4990, -1, 4460, 4968, 4512, -1, 5001, 4986, 4993, -1, 4460, 4979, 4968, -1, 5001, 4980, 4996, -1, 5002, 4992, 4981, -1, 5001, 4996, 4986, -1, 5001, 4277, 4980, -1, 5003, 4973, 4998, -1, 5003, 4982, 4973, -1, 5002, 4981, 4991, -1, 5004, 4987, 4974, -1, 4265, 4989, 5005, -1, 5004, 4974, 4992, -1, 5006, 4995, 4994, -1, 4265, 4988, 4989, -1, 5006, 4994, 4983, -1, 5006, 4983, 4997, -1, 4276, 4993, 4984, -1, 4276, 4984, 5000, -1, 4268, 4997, 4985, -1, 4268, 4985, 4999, -1, 4459, 4979, 4460, -1, 4285, 4990, 4982, -1, 4285, 4982, 5003, -1, 4459, 4991, 4979, -1, 4281, 5004, 4992, -1, 4264, 4988, 4265, -1, 4281, 4992, 5002, -1, 4264, 4998, 4988, -1, 4260, 4987, 5004, -1, 4275, 5001, 4993, -1, 4275, 4993, 4276, -1, 4275, 4277, 5001, -1, 4260, 4999, 4987, -1, 4267, 4997, 4268, -1, 4267, 5006, 4997, -1, 4284, 5000, 4990, -1, 4267, 4270, 4995, -1, 4267, 4995, 5006, -1, 4284, 4990, 4285, -1, 4301, 4991, 4459, -1, 4290, 4998, 4264, -1, 4301, 5002, 4991, -1, 4290, 5003, 4998, -1, 4261, 5004, 4281, -1, 4261, 4260, 5004, -1, 4269, 4265, 5005, -1, 4269, 5005, 4272, -1, 4262, 4268, 4999, -1, 4262, 4999, 4260, -1, 4278, 4276, 5000, -1, 4278, 5000, 4284, -1, 4286, 4285, 5003, -1, 4282, 4281, 5002, -1, 4282, 5002, 4301, -1, 4286, 5003, 4290, -1, 5007, 5008, 5009, -1, 5010, 5011, 5012, -1, 5013, 5011, 5010, -1, 5014, 5015, 5016, -1, 5014, 5016, 5017, -1, 5014, 5017, 5018, -1, 5019, 5020, 5015, -1, 5019, 5021, 5020, -1, 5019, 5015, 5014, -1, 5022, 5018, 5008, -1, 5022, 5007, 5023, -1, 5022, 5014, 5018, -1, 5022, 5008, 5007, -1, 5024, 5025, 5026, -1, 5024, 5026, 5027, -1, 5024, 5027, 5021, -1, 5024, 5021, 5019, -1, 5028, 5023, 5029, -1, 5028, 5022, 5023, -1, 5028, 5014, 5022, -1, 5028, 5019, 5014, -1, 5030, 5029, 5012, -1, 5030, 5011, 5025, -1, 5030, 5024, 5019, -1, 5030, 5028, 5029, -1, 5030, 5019, 5028, -1, 5030, 5012, 5011, -1, 5030, 5025, 5024, -1, 5031, 5032, 5033, -1, 5034, 5035, 5036, -1, 5037, 5034, 5036, -1, 5038, 5039, 5040, -1, 5038, 5040, 5041, -1, 5038, 5041, 5042, -1, 5043, 5044, 5039, -1, 5043, 5045, 5044, -1, 5043, 5039, 5038, -1, 5046, 5042, 5032, -1, 5046, 5031, 5047, -1, 5046, 5038, 5042, -1, 5046, 5032, 5031, -1, 5048, 5049, 5050, -1, 5048, 5050, 5051, -1, 5048, 5051, 5045, -1, 5048, 5045, 5043, -1, 5052, 5047, 5053, -1, 5052, 5046, 5047, -1, 5052, 5038, 5046, -1, 5052, 5043, 5038, -1, 5054, 5053, 5035, -1, 5054, 5034, 5049, -1, 5054, 5048, 5043, -1, 5054, 5052, 5053, -1, 5054, 5043, 5052, -1, 5054, 5035, 5034, -1, 5054, 5049, 5048, -1, 5055, 5056, 5057, -1, 5058, 5059, 5060, -1, 5061, 5057, 5062, -1, 5061, 5062, 5063, -1, 5061, 5064, 5055, -1, 5061, 5055, 5057, -1, 5065, 5063, 5059, -1, 5065, 5058, 5066, -1, 5065, 5066, 5064, -1, 5065, 5061, 5063, -1, 5065, 5059, 5058, -1, 5065, 5064, 5061, -1, 5067, 5068, 5069, -1, 5070, 5071, 5072, -1, 5073, 5071, 5070, -1, 5074, 5075, 5076, -1, 5074, 5076, 5077, -1, 5074, 5077, 5078, -1, 5079, 5080, 5081, -1, 5079, 5081, 5075, -1, 5079, 5075, 5074, -1, 5082, 5078, 5068, -1, 5082, 5067, 5083, -1, 5082, 5068, 5067, -1, 5082, 5074, 5078, -1, 5084, 5085, 5086, -1, 5084, 5086, 5087, -1, 5084, 5087, 5080, -1, 5084, 5080, 5079, -1, 5088, 5083, 5089, -1, 5088, 5082, 5083, -1, 5088, 5074, 5082, -1, 5088, 5079, 5074, -1, 5090, 5089, 5072, -1, 5090, 5071, 5085, -1, 5090, 5088, 5089, -1, 5090, 5084, 5079, -1, 5090, 5079, 5088, -1, 5090, 5072, 5071, -1, 5090, 5085, 5084, -1, 5091, 5092, 5093, -1, 5094, 5095, 5096, -1, 5097, 5095, 5094, -1, 5098, 5099, 5100, -1, 5098, 5100, 5101, -1, 5098, 5101, 5102, -1, 5103, 5104, 5105, -1, 5103, 5105, 5099, -1, 5103, 5099, 5098, -1, 5106, 5102, 5092, -1, 5106, 5091, 5107, -1, 5106, 5092, 5091, -1, 5106, 5098, 5102, -1, 5108, 5109, 5110, -1, 5108, 5110, 5111, -1, 5108, 5111, 5104, -1, 5108, 5104, 5103, -1, 5112, 5107, 5113, -1, 5112, 5106, 5107, -1, 5112, 5098, 5106, -1, 5112, 5103, 5098, -1, 5114, 5113, 5096, -1, 5114, 5095, 5109, -1, 5114, 5112, 5113, -1, 5114, 5108, 5103, -1, 5114, 5103, 5112, -1, 5114, 5096, 5095, -1, 5114, 5109, 5108, -1, 5115, 5116, 5117, -1, 5118, 5119, 5120, -1, 5121, 5122, 5123, -1, 5121, 5123, 5116, -1, 5121, 5115, 5124, -1, 5121, 5116, 5115, -1, 5125, 5126, 5122, -1, 5125, 5122, 5121, -1, 5127, 5124, 5128, -1, 5127, 5128, 5129, -1, 5127, 5121, 5124, -1, 5130, 5131, 5118, -1, 5130, 5120, 5126, -1, 5130, 5118, 5120, -1, 5130, 5126, 5125, -1, 5132, 5129, 5133, -1, 5132, 5133, 5134, -1, 5132, 5134, 5135, -1, 5132, 5127, 5129, -1, 5132, 5125, 5121, -1, 5132, 5121, 5127, -1, 5136, 5135, 5137, -1, 5136, 5137, 5138, -1, 5136, 5138, 5131, -1, 5136, 5132, 5135, -1, 5136, 5131, 5130, -1, 5136, 5130, 5125, -1, 5136, 5125, 5132, -1, 5139, 5140, 5141, -1, 5139, 5141, 5142, -1, 5143, 5139, 5142, -1, 5144, 5140, 5139, -1, 5145, 5143, 5142, -1, 5146, 5143, 5145, -1, 5147, 5144, 5139, -1, 5148, 5145, 5149, -1, 5148, 5146, 5145, -1, 5150, 5144, 5147, -1, 5151, 5152, 5153, -1, 5154, 5155, 5148, -1, 5154, 5148, 5149, -1, 5156, 5157, 5152, -1, 5158, 5157, 5156, -1, 5159, 5158, 5156, -1, 5160, 5155, 5154, -1, 5161, 5155, 5160, -1, 5162, 5159, 5163, -1, 5162, 5158, 5159, -1, 5164, 5161, 5160, -1, 5165, 5162, 5163, -1, 5166, 5167, 5161, -1, 5166, 5161, 5164, -1, 5168, 5167, 5166, -1, 5169, 5162, 5165, -1, 5151, 5156, 5152, -1, 5170, 5147, 5171, -1, 5170, 5171, 5151, -1, 5170, 5153, 5150, -1, 5170, 5151, 5153, -1, 5170, 5150, 5147, -1, 5172, 5165, 5167, -1, 5172, 5168, 5169, -1, 5172, 5169, 5165, -1, 5172, 5167, 5168, -1, 5173, 5174, 5175, -1, 5176, 5177, 5178, -1, 5179, 5180, 5181, -1, 5179, 5181, 5174, -1, 5179, 5173, 5182, -1, 5179, 5174, 5173, -1, 5183, 5184, 5180, -1, 5183, 5180, 5179, -1, 5185, 5182, 5186, -1, 5185, 5186, 5187, -1, 5185, 5179, 5182, -1, 5188, 5189, 5176, -1, 5188, 5178, 5184, -1, 5188, 5184, 5183, -1, 5188, 5176, 5178, -1, 5190, 5187, 5191, -1, 5190, 5191, 5192, -1, 5190, 5192, 5193, -1, 5190, 5185, 5187, -1, 5190, 5179, 5185, -1, 5190, 5183, 5179, -1, 5194, 5193, 5195, -1, 5194, 5195, 5196, -1, 5194, 5196, 5189, -1, 5194, 5189, 5188, -1, 5194, 5190, 5193, -1, 5194, 5188, 5183, -1, 5194, 5183, 5190, -1, 5197, 5198, 5199, -1, 5197, 5199, 5200, -1, 5201, 5197, 5200, -1, 5202, 5198, 5197, -1, 5203, 5201, 5200, -1, 5204, 5201, 5203, -1, 5205, 5202, 5197, -1, 5206, 5204, 5203, -1, 5207, 5206, 5203, -1, 5208, 5202, 5205, -1, 5209, 5210, 5211, -1, 5209, 5211, 5208, -1, 5212, 5213, 5206, -1, 5212, 5206, 5207, -1, 5214, 5215, 5210, -1, 5216, 5215, 5214, -1, 5217, 5216, 5214, -1, 5218, 5213, 5212, -1, 5219, 5213, 5218, -1, 5220, 5217, 5221, -1, 5220, 5216, 5217, -1, 5222, 5219, 5218, -1, 5223, 5220, 5221, -1, 5224, 5225, 5219, -1, 5224, 5219, 5222, -1, 5226, 5225, 5224, -1, 5227, 5220, 5223, -1, 5209, 5214, 5210, -1, 5228, 5205, 5229, -1, 5228, 5229, 5209, -1, 5228, 5208, 5205, -1, 5228, 5209, 5208, -1, 5230, 5223, 5225, -1, 5230, 5226, 5227, -1, 5230, 5227, 5223, -1, 5230, 5225, 5226, -1, 5231, 5232, 5233, -1, 5234, 5235, 5236, -1, 5237, 5235, 5234, -1, 5238, 5239, 5240, -1, 5238, 5240, 5241, -1, 5238, 5241, 5242, -1, 5243, 5244, 5239, -1, 5243, 5245, 5244, -1, 5243, 5239, 5238, -1, 5246, 5242, 5232, -1, 5246, 5231, 5247, -1, 5246, 5238, 5242, -1, 5246, 5232, 5231, -1, 5248, 5249, 5250, -1, 5248, 5250, 5251, -1, 5248, 5251, 5245, -1, 5248, 5245, 5243, -1, 5252, 5247, 5253, -1, 5252, 5246, 5247, -1, 5252, 5238, 5246, -1, 5252, 5243, 5238, -1, 5254, 5253, 5236, -1, 5254, 5235, 5249, -1, 5254, 5248, 5243, -1, 5254, 5252, 5253, -1, 5254, 5243, 5252, -1, 5254, 5236, 5235, -1, 5254, 5249, 5248, -1, 5255, 5256, 5257, -1, 5258, 5259, 5260, -1, 5261, 5259, 5258, -1, 5262, 5263, 5264, -1, 5262, 5264, 5265, -1, 5262, 5265, 5266, -1, 5267, 5268, 5263, -1, 5267, 5269, 5268, -1, 5267, 5263, 5262, -1, 5270, 5266, 5256, -1, 5270, 5255, 5271, -1, 5270, 5262, 5266, -1, 5270, 5256, 5255, -1, 5272, 5273, 5274, -1, 5272, 5274, 5275, -1, 5272, 5275, 5269, -1, 5272, 5269, 5267, -1, 5276, 5271, 5277, -1, 5276, 5270, 5271, -1, 5276, 5262, 5270, -1, 5276, 5267, 5262, -1, 5278, 5277, 5260, -1, 5278, 5259, 5273, -1, 5278, 5272, 5267, -1, 5278, 5276, 5277, -1, 5278, 5267, 5276, -1, 5278, 5260, 5259, -1, 5278, 5273, 5272, -1, 5279, 5280, 5281, -1, 5282, 5283, 5284, -1, 5285, 5283, 5282, -1, 5286, 5287, 5288, -1, 5286, 5288, 5289, -1, 5286, 5289, 5290, -1, 5291, 5292, 5287, -1, 5291, 5293, 5292, -1, 5291, 5287, 5286, -1, 5294, 5290, 5280, -1, 5294, 5279, 5295, -1, 5294, 5286, 5290, -1, 5294, 5280, 5279, -1, 5296, 5297, 5298, -1, 5296, 5298, 5299, -1, 5296, 5299, 5293, -1, 5296, 5293, 5291, -1, 5300, 5295, 5301, -1, 5300, 5294, 5295, -1, 5300, 5286, 5294, -1, 5300, 5291, 5286, -1, 5302, 5301, 5284, -1, 5302, 5283, 5297, -1, 5302, 5296, 5291, -1, 5302, 5300, 5301, -1, 5302, 5291, 5300, -1, 5302, 5284, 5283, -1, 5302, 5297, 5296, -1, 5303, 5304, 5305, -1, 5306, 5307, 5308, -1, 5309, 5305, 5310, -1, 5309, 5310, 5311, -1, 5309, 5312, 5303, -1, 5309, 5303, 5305, -1, 5313, 5311, 5307, -1, 5313, 5306, 5314, -1, 5313, 5314, 5312, -1, 5313, 5309, 5311, -1, 5313, 5307, 5306, -1, 5313, 5312, 5309, -1, 5315, 5316, 5317, -1, 5318, 5319, 5320, -1, 5321, 5318, 5320, -1, 5322, 5323, 5324, -1, 5322, 5324, 5325, -1, 5322, 5325, 5326, -1, 5327, 5328, 5329, -1, 5327, 5329, 5323, -1, 5327, 5323, 5322, -1, 5330, 5326, 5316, -1, 5330, 5315, 5331, -1, 5330, 5316, 5315, -1, 5330, 5322, 5326, -1, 5332, 5333, 5334, -1, 5332, 5334, 5335, -1, 5332, 5335, 5328, -1, 5332, 5328, 5327, -1, 5336, 5331, 5337, -1, 5336, 5330, 5331, -1, 5336, 5322, 5330, -1, 5336, 5327, 5322, -1, 5338, 5337, 5319, -1, 5338, 5318, 5333, -1, 5338, 5336, 5337, -1, 5338, 5332, 5327, -1, 5338, 5327, 5336, -1, 5338, 5319, 5318, -1, 5338, 5333, 5332, -1, 5339, 5340, 5341, -1, 5342, 5343, 5344, -1, 5345, 5346, 5347, -1, 5345, 5347, 5340, -1, 5345, 5339, 5348, -1, 5345, 5340, 5339, -1, 5349, 5350, 5346, -1, 5349, 5346, 5345, -1, 5351, 5348, 5352, -1, 5351, 5352, 5353, -1, 5351, 5345, 5348, -1, 5354, 5355, 5342, -1, 5354, 5344, 5350, -1, 5354, 5342, 5344, -1, 5354, 5350, 5349, -1, 5356, 5353, 5357, -1, 5356, 5357, 5358, -1, 5356, 5358, 5359, -1, 5356, 5351, 5353, -1, 5356, 5349, 5345, -1, 5356, 5345, 5351, -1, 5360, 5359, 5361, -1, 5360, 5361, 5362, -1, 5360, 5362, 5355, -1, 5360, 5356, 5359, -1, 5360, 5355, 5354, -1, 5360, 5354, 5349, -1, 5360, 5349, 5356, -1, 5363, 5364, 5365, -1, 5363, 5365, 5366, -1, 5367, 5363, 5366, -1, 5368, 5364, 5363, -1, 5369, 5367, 5366, -1, 5370, 5367, 5369, -1, 5371, 5368, 5363, -1, 5372, 5370, 5369, -1, 5373, 5372, 5369, -1, 5374, 5368, 5371, -1, 5375, 5376, 5377, -1, 5375, 5377, 5374, -1, 5378, 5379, 5372, -1, 5378, 5372, 5373, -1, 5380, 5381, 5376, -1, 5382, 5381, 5380, -1, 5383, 5382, 5380, -1, 5384, 5379, 5378, -1, 5385, 5379, 5384, -1, 5386, 5383, 5387, -1, 5386, 5382, 5383, -1, 5388, 5385, 5384, -1, 5389, 5386, 5387, -1, 5390, 5391, 5385, -1, 5390, 5385, 5388, -1, 5392, 5391, 5390, -1, 5393, 5386, 5389, -1, 5375, 5380, 5376, -1, 5394, 5371, 5395, -1, 5394, 5395, 5375, -1, 5394, 5374, 5371, -1, 5394, 5375, 5374, -1, 5396, 5389, 5391, -1, 5396, 5392, 5393, -1, 5396, 5393, 5389, -1, 5396, 5391, 5392, -1, 5397, 5398, 5399, -1, 5400, 5401, 5402, -1, 5403, 5404, 5405, -1, 5403, 5405, 5398, -1, 5403, 5397, 5406, -1, 5403, 5398, 5397, -1, 5407, 5408, 5404, -1, 5407, 5404, 5403, -1, 5409, 5406, 5410, -1, 5409, 5410, 5411, -1, 5409, 5403, 5406, -1, 5412, 5413, 5400, -1, 5412, 5402, 5408, -1, 5412, 5408, 5407, -1, 5412, 5400, 5402, -1, 5414, 5411, 5415, -1, 5414, 5415, 5416, -1, 5414, 5416, 5417, -1, 5414, 5409, 5411, -1, 5414, 5403, 5409, -1, 5414, 5407, 5403, -1, 5418, 5417, 5419, -1, 5418, 5419, 5420, -1, 5418, 5420, 5413, -1, 5418, 5413, 5412, -1, 5418, 5414, 5417, -1, 5418, 5412, 5407, -1, 5418, 5407, 5414, -1, 5421, 5422, 5423, -1, 5421, 5423, 5424, -1, 5425, 5421, 5424, -1, 5426, 5422, 5421, -1, 5427, 5425, 5424, -1, 5428, 5425, 5427, -1, 5429, 5426, 5421, -1, 5430, 5427, 5431, -1, 5430, 5428, 5427, -1, 5432, 5426, 5429, -1, 5433, 5434, 5435, -1, 5436, 5437, 5430, -1, 5436, 5430, 5431, -1, 5438, 5439, 5434, -1, 5440, 5439, 5438, -1, 5441, 5440, 5438, -1, 5442, 5437, 5436, -1, 5443, 5437, 5442, -1, 5444, 5441, 5445, -1, 5444, 5440, 5441, -1, 5446, 5443, 5442, -1, 5447, 5444, 5445, -1, 5448, 5449, 5443, -1, 5448, 5443, 5446, -1, 5450, 5449, 5448, -1, 5451, 5444, 5447, -1, 5433, 5438, 5434, -1, 5452, 5429, 5453, -1, 5452, 5453, 5433, -1, 5452, 5435, 5432, -1, 5452, 5433, 5435, -1, 5452, 5432, 5429, -1, 5454, 5447, 5449, -1, 5454, 5450, 5451, -1, 5454, 5451, 5447, -1, 5454, 5449, 5450, -1, 5455, 5456, 5457, -1, 5458, 5459, 5460, -1, 5461, 5457, 5462, -1, 5461, 5462, 5463, -1, 5461, 5464, 5455, -1, 5461, 5455, 5457, -1, 5465, 5463, 5459, -1, 5465, 5458, 5466, -1, 5465, 5466, 5464, -1, 5465, 5461, 5463, -1, 5465, 5459, 5458, -1, 5465, 5464, 5461, -1, 5467, 5468, 5469, -1, 5470, 5471, 5472, -1, 5473, 5470, 5472, -1, 5474, 5475, 5476, -1, 5474, 5476, 5477, -1, 5474, 5477, 5478, -1, 5479, 5480, 5481, -1, 5479, 5481, 5475, -1, 5479, 5475, 5474, -1, 5482, 5478, 5468, -1, 5482, 5467, 5483, -1, 5482, 5468, 5467, -1, 5482, 5474, 5478, -1, 5484, 5485, 5486, -1, 5484, 5486, 5487, -1, 5484, 5487, 5480, -1, 5484, 5480, 5479, -1, 5488, 5483, 5489, -1, 5488, 5482, 5483, -1, 5488, 5474, 5482, -1, 5488, 5479, 5474, -1, 5490, 5489, 5471, -1, 5490, 5470, 5485, -1, 5490, 5488, 5489, -1, 5490, 5484, 5479, -1, 5490, 5479, 5488, -1, 5490, 5471, 5470, -1, 5490, 5485, 5484, -1, 5491, 5492, 5493, -1, 5494, 5495, 5496, -1, 5497, 5495, 5494, -1, 5498, 5499, 5500, -1, 5498, 5500, 5501, -1, 5498, 5501, 5502, -1, 5503, 5504, 5505, -1, 5503, 5505, 5499, -1, 5503, 5499, 5498, -1, 5506, 5502, 5492, -1, 5506, 5491, 5507, -1, 5506, 5492, 5491, -1, 5506, 5498, 5502, -1, 5508, 5509, 5510, -1, 5508, 5510, 5511, -1, 5508, 5511, 5504, -1, 5508, 5504, 5503, -1, 5512, 5507, 5513, -1, 5512, 5506, 5507, -1, 5512, 5498, 5506, -1, 5512, 5503, 5498, -1, 5514, 5513, 5496, -1, 5514, 5495, 5509, -1, 5514, 5512, 5513, -1, 5514, 5508, 5503, -1, 5514, 5503, 5512, -1, 5514, 5496, 5495, -1, 5514, 5509, 5508, -1, 5515, 5516, 5517, -1, 5518, 5519, 5520, -1, 5521, 5519, 5518, -1, 5522, 5523, 5524, -1, 5522, 5524, 5525, -1, 5522, 5525, 5526, -1, 5527, 5528, 5529, -1, 5527, 5529, 5523, -1, 5527, 5523, 5522, -1, 5530, 5526, 5516, -1, 5530, 5515, 5531, -1, 5530, 5516, 5515, -1, 5530, 5522, 5526, -1, 5532, 5533, 5534, -1, 5532, 5534, 5535, -1, 5532, 5535, 5528, -1, 5532, 5528, 5527, -1, 5536, 5531, 5537, -1, 5536, 5530, 5531, -1, 5536, 5522, 5530, -1, 5536, 5527, 5522, -1, 5538, 5537, 5520, -1, 5538, 5519, 5533, -1, 5538, 5536, 5537, -1, 5538, 5532, 5527, -1, 5538, 5527, 5536, -1, 5538, 5520, 5519, -1, 5538, 5533, 5532, -1, 5539, 5540, 5541, -1, 5542, 5543, 5544, -1, 5545, 5543, 5542, -1, 5546, 5547, 5548, -1, 5546, 5548, 5549, -1, 5546, 5549, 5550, -1, 5551, 5552, 5553, -1, 5551, 5553, 5547, -1, 5551, 5547, 5546, -1, 5554, 5550, 5540, -1, 5554, 5539, 5555, -1, 5554, 5540, 5539, -1, 5554, 5546, 5550, -1, 5556, 5557, 5558, -1, 5556, 5558, 5559, -1, 5556, 5559, 5552, -1, 5556, 5552, 5551, -1, 5560, 5555, 5561, -1, 5560, 5554, 5555, -1, 5560, 5546, 5554, -1, 5560, 5551, 5546, -1, 5562, 5561, 5544, -1, 5562, 5543, 5557, -1, 5562, 5560, 5561, -1, 5562, 5556, 5551, -1, 5562, 5551, 5560, -1, 5562, 5544, 5543, -1, 5562, 5557, 5556, -1, 5563, 5564, 5565, -1, 5566, 5567, 5568, -1, 5569, 5570, 5571, -1, 5569, 5571, 5564, -1, 5569, 5563, 5572, -1, 5569, 5564, 5563, -1, 5573, 5574, 5570, -1, 5573, 5570, 5569, -1, 5575, 5572, 5576, -1, 5575, 5576, 5577, -1, 5575, 5569, 5572, -1, 5578, 5579, 5566, -1, 5578, 5568, 5574, -1, 5578, 5574, 5573, -1, 5578, 5566, 5568, -1, 5580, 5577, 5581, -1, 5580, 5581, 5582, -1, 5580, 5582, 5583, -1, 5580, 5575, 5577, -1, 5580, 5569, 5575, -1, 5580, 5573, 5569, -1, 5584, 5583, 5585, -1, 5584, 5585, 5586, -1, 5584, 5586, 5579, -1, 5584, 5579, 5578, -1, 5584, 5580, 5583, -1, 5584, 5578, 5573, -1, 5584, 5573, 5580, -1, 5587, 5588, 5589, -1, 5587, 5589, 5590, -1, 5591, 5587, 5590, -1, 5592, 5588, 5587, -1, 5593, 5591, 5590, -1, 5594, 5591, 5593, -1, 5595, 5592, 5587, -1, 5596, 5593, 5597, -1, 5596, 5594, 5593, -1, 5598, 5592, 5595, -1, 5599, 5600, 5601, -1, 5602, 5603, 5596, -1, 5602, 5596, 5597, -1, 5604, 5605, 5600, -1, 5606, 5605, 5604, -1, 5607, 5606, 5604, -1, 5608, 5603, 5602, -1, 5609, 5603, 5608, -1, 5610, 5607, 5611, -1, 5610, 5606, 5607, -1, 5612, 5609, 5608, -1, 5613, 5610, 5611, -1, 5614, 5615, 5609, -1, 5614, 5609, 5612, -1, 5616, 5615, 5614, -1, 5617, 5610, 5613, -1, 5599, 5604, 5600, -1, 5618, 5595, 5619, -1, 5618, 5619, 5599, -1, 5618, 5601, 5598, -1, 5618, 5599, 5601, -1, 5618, 5598, 5595, -1, 5620, 5613, 5615, -1, 5620, 5616, 5617, -1, 5620, 5617, 5613, -1, 5620, 5615, 5616, -1, 5621, 5622, 5623, -1, 5621, 5623, 5624, -1, 5625, 5621, 5624, -1, 5626, 5622, 5621, -1, 5627, 5625, 5624, -1, 5628, 5625, 5627, -1, 5629, 5626, 5621, -1, 5630, 5628, 5627, -1, 5631, 5630, 5627, -1, 5632, 5626, 5629, -1, 5633, 5634, 5635, -1, 5633, 5635, 5632, -1, 5636, 5637, 5630, -1, 5636, 5630, 5631, -1, 5638, 5639, 5634, -1, 5640, 5639, 5638, -1, 5641, 5640, 5638, -1, 5642, 5637, 5636, -1, 5643, 5637, 5642, -1, 5644, 5641, 5645, -1, 5644, 5640, 5641, -1, 5646, 5643, 5642, -1, 5647, 5644, 5645, -1, 5648, 5649, 5643, -1, 5648, 5643, 5646, -1, 5650, 5649, 5648, -1, 5651, 5644, 5647, -1, 5633, 5638, 5634, -1, 5652, 5629, 5653, -1, 5652, 5653, 5633, -1, 5652, 5632, 5629, -1, 5652, 5633, 5632, -1, 5654, 5647, 5649, -1, 5654, 5650, 5651, -1, 5654, 5651, 5647, -1, 5654, 5649, 5650, -1, 5655, 5656, 5657, -1, 5658, 5659, 5660, -1, 5661, 5662, 5663, -1, 5661, 5663, 5656, -1, 5661, 5655, 5664, -1, 5661, 5656, 5655, -1, 5665, 5666, 5662, -1, 5665, 5662, 5661, -1, 5667, 5664, 5668, -1, 5667, 5668, 5669, -1, 5667, 5661, 5664, -1, 5670, 5671, 5658, -1, 5670, 5660, 5666, -1, 5670, 5666, 5665, -1, 5670, 5658, 5660, -1, 5672, 5673, 5674, -1, 5672, 5669, 5675, -1, 5672, 5675, 5673, -1, 5672, 5667, 5669, -1, 5672, 5661, 5667, -1, 5672, 5665, 5661, -1, 5676, 5674, 5677, -1, 5676, 5677, 5678, -1, 5676, 5678, 5671, -1, 5676, 5665, 5672, -1, 5676, 5672, 5674, -1, 5676, 5671, 5670, -1, 5676, 5670, 5665, -1, 5679, 5680, 5681, -1, 5682, 5683, 5684, -1, 5685, 5682, 5684, -1, 5686, 5687, 5688, -1, 5686, 5688, 5689, -1, 5686, 5689, 5690, -1, 5691, 5692, 5687, -1, 5691, 5693, 5692, -1, 5691, 5687, 5686, -1, 5694, 5690, 5680, -1, 5694, 5679, 5695, -1, 5694, 5686, 5690, -1, 5694, 5680, 5679, -1, 5696, 5697, 5698, -1, 5696, 5698, 5699, -1, 5696, 5699, 5693, -1, 5696, 5693, 5691, -1, 5700, 5695, 5701, -1, 5700, 5694, 5695, -1, 5700, 5686, 5694, -1, 5700, 5691, 5686, -1, 5702, 5701, 5683, -1, 5702, 5682, 5697, -1, 5702, 5696, 5691, -1, 5702, 5700, 5701, -1, 5702, 5691, 5700, -1, 5702, 5683, 5682, -1, 5702, 5697, 5696, -1, 5703, 5704, 5705, -1, 5706, 5707, 5708, -1, 5709, 5707, 5706, -1, 5710, 5711, 5712, -1, 5710, 5712, 5713, -1, 5710, 5713, 5714, -1, 5715, 5716, 5717, -1, 5715, 5717, 5711, -1, 5715, 5711, 5710, -1, 5718, 5714, 5704, -1, 5718, 5703, 5719, -1, 5718, 5704, 5703, -1, 5718, 5710, 5714, -1, 5720, 5721, 5722, -1, 5720, 5722, 5723, -1, 5720, 5723, 5716, -1, 5720, 5716, 5715, -1, 5724, 5719, 5725, -1, 5724, 5718, 5719, -1, 5724, 5710, 5718, -1, 5724, 5715, 5710, -1, 5726, 5725, 5708, -1, 5726, 5707, 5721, -1, 5726, 5724, 5725, -1, 5726, 5720, 5715, -1, 5726, 5715, 5724, -1, 5726, 5708, 5707, -1, 5726, 5721, 5720, -1, 5727, 5728, 5729, -1, 5730, 5731, 5732, -1, 5733, 5729, 5734, -1, 5733, 5734, 5735, -1, 5733, 5736, 5727, -1, 5733, 5727, 5729, -1, 5737, 5735, 5731, -1, 5737, 5730, 5738, -1, 5737, 5738, 5736, -1, 5737, 5733, 5735, -1, 5737, 5736, 5733, -1, 5737, 5731, 5730, -1, 5739, 5740, 5741, -1, 5742, 5743, 5744, -1, 5745, 5743, 5742, -1, 5746, 5747, 5748, -1, 5746, 5748, 5749, -1, 5746, 5749, 5750, -1, 5751, 5752, 5747, -1, 5751, 5753, 5752, -1, 5751, 5747, 5746, -1, 5754, 5750, 5740, -1, 5754, 5739, 5755, -1, 5754, 5746, 5750, -1, 5754, 5740, 5739, -1, 5756, 5757, 5758, -1, 5756, 5758, 5759, -1, 5756, 5759, 5753, -1, 5756, 5753, 5751, -1, 5760, 5755, 5761, -1, 5760, 5754, 5755, -1, 5760, 5746, 5754, -1, 5760, 5751, 5746, -1, 5762, 5761, 5744, -1, 5762, 5743, 5757, -1, 5762, 5756, 5751, -1, 5762, 5760, 5761, -1, 5762, 5751, 5760, -1, 5762, 5744, 5743, -1, 5762, 5757, 5756, -1, 5763, 5764, 5765, -1, 5766, 5767, 5768, -1, 5769, 5767, 5766, -1, 5770, 5771, 5772, -1, 5770, 5772, 5773, -1, 5770, 5773, 5774, -1, 5775, 5776, 5777, -1, 5775, 5777, 5771, -1, 5775, 5771, 5770, -1, 5778, 5774, 5764, -1, 5778, 5763, 5779, -1, 5778, 5764, 5763, -1, 5778, 5770, 5774, -1, 5780, 5781, 5782, -1, 5780, 5782, 5783, -1, 5780, 5783, 5776, -1, 5780, 5776, 5775, -1, 5784, 5779, 5785, -1, 5784, 5778, 5779, -1, 5784, 5770, 5778, -1, 5784, 5775, 5770, -1, 5786, 5785, 5768, -1, 5786, 5767, 5781, -1, 5786, 5784, 5785, -1, 5786, 5780, 5775, -1, 5786, 5775, 5784, -1, 5786, 5768, 5767, -1, 5786, 5781, 5780, -1, 5787, 5788, 5789, -1, 5790, 5791, 5792, -1, 5793, 5794, 5795, -1, 5793, 5795, 5788, -1, 5793, 5787, 5796, -1, 5793, 5788, 5787, -1, 5797, 5798, 5794, -1, 5797, 5794, 5793, -1, 5799, 5796, 5800, -1, 5799, 5800, 5801, -1, 5799, 5793, 5796, -1, 5802, 5803, 5790, -1, 5802, 5792, 5798, -1, 5802, 5798, 5797, -1, 5802, 5790, 5792, -1, 5804, 5801, 5805, -1, 5804, 5805, 5806, -1, 5804, 5806, 5807, -1, 5804, 5799, 5801, -1, 5804, 5793, 5799, -1, 5804, 5797, 5793, -1, 5808, 5807, 5809, -1, 5808, 5809, 5810, -1, 5808, 5810, 5803, -1, 5808, 5803, 5802, -1, 5808, 5804, 5807, -1, 5808, 5802, 5797, -1, 5808, 5797, 5804, -1, 5811, 5812, 5813, -1, 5811, 5813, 5814, -1, 5815, 5811, 5814, -1, 5816, 5812, 5811, -1, 5817, 5815, 5814, -1, 5818, 5815, 5817, -1, 5819, 5816, 5811, -1, 5820, 5818, 5817, -1, 5821, 5820, 5817, -1, 5822, 5816, 5819, -1, 5823, 5824, 5825, -1, 5823, 5825, 5822, -1, 5826, 5827, 5820, -1, 5826, 5820, 5821, -1, 5828, 5829, 5824, -1, 5830, 5829, 5828, -1, 5831, 5830, 5828, -1, 5832, 5827, 5826, -1, 5833, 5827, 5832, -1, 5834, 5831, 5835, -1, 5834, 5830, 5831, -1, 5836, 5833, 5832, -1, 5837, 5834, 5835, -1, 5838, 5839, 5833, -1, 5838, 5833, 5836, -1, 5840, 5839, 5838, -1, 5841, 5834, 5837, -1, 5823, 5828, 5824, -1, 5842, 5819, 5843, -1, 5842, 5843, 5823, -1, 5842, 5822, 5819, -1, 5842, 5823, 5822, -1, 5844, 5837, 5839, -1, 5844, 5840, 5841, -1, 5844, 5841, 5837, -1, 5844, 5839, 5840, -1, 5845, 5846, 5847, -1, 5848, 5849, 5850, -1, 5851, 5852, 5853, -1, 5851, 5853, 5846, -1, 5851, 5845, 5854, -1, 5851, 5846, 5845, -1, 5855, 5856, 5852, -1, 5855, 5852, 5851, -1, 5857, 5854, 5858, -1, 5857, 5858, 5859, -1, 5857, 5851, 5854, -1, 5860, 5861, 5848, -1, 5860, 5850, 5856, -1, 5860, 5856, 5855, -1, 5860, 5848, 5850, -1, 5862, 5863, 5864, -1, 5862, 5859, 5865, -1, 5862, 5865, 5863, -1, 5862, 5857, 5859, -1, 5862, 5851, 5857, -1, 5862, 5855, 5851, -1, 5866, 5864, 5867, -1, 5866, 5867, 5868, -1, 5866, 5868, 5861, -1, 5866, 5855, 5862, -1, 5866, 5862, 5864, -1, 5866, 5861, 5860, -1, 5866, 5860, 5855, -1, 5869, 5870, 5871, -1, 5869, 5871, 5872, -1, 5873, 5869, 5872, -1, 5874, 5870, 5869, -1, 5875, 5873, 5872, -1, 5876, 5873, 5875, -1, 5877, 5874, 5869, -1, 5878, 5875, 5879, -1, 5878, 5876, 5875, -1, 5880, 5874, 5877, -1, 5881, 5882, 5883, -1, 5884, 5885, 5878, -1, 5884, 5878, 5879, -1, 5886, 5887, 5882, -1, 5888, 5887, 5886, -1, 5889, 5888, 5886, -1, 5890, 5885, 5884, -1, 5891, 5885, 5890, -1, 5892, 5889, 5893, -1, 5892, 5888, 5889, -1, 5894, 5891, 5890, -1, 5895, 5892, 5893, -1, 5896, 5897, 5891, -1, 5896, 5891, 5894, -1, 5898, 5897, 5896, -1, 5899, 5892, 5895, -1, 5881, 5886, 5882, -1, 5900, 5877, 5901, -1, 5900, 5901, 5881, -1, 5900, 5883, 5880, -1, 5900, 5881, 5883, -1, 5900, 5880, 5877, -1, 5902, 5895, 5897, -1, 5902, 5898, 5899, -1, 5902, 5899, 5895, -1, 5902, 5897, 5898, -1, 5903, 5904, 5905, -1, 5903, 5905, 5906, -1, 5907, 5903, 5906, -1, 5908, 5904, 5903, -1, 5909, 5907, 5906, -1, 5910, 5907, 5909, -1, 5911, 5908, 5903, -1, 5912, 5909, 5913, -1, 5912, 5910, 5909, -1, 5914, 5908, 5911, -1, 5915, 5916, 5917, -1, 5918, 5919, 5912, -1, 5918, 5912, 5913, -1, 5920, 5921, 5916, -1, 5922, 5921, 5920, -1, 5923, 5922, 5920, -1, 5924, 5919, 5918, -1, 5925, 5919, 5924, -1, 5926, 5923, 5927, -1, 5926, 5922, 5923, -1, 5928, 5925, 5924, -1, 5929, 5926, 5927, -1, 5930, 5931, 5925, -1, 5930, 5925, 5928, -1, 5932, 5931, 5930, -1, 5933, 5926, 5929, -1, 5915, 5920, 5916, -1, 5934, 5911, 5935, -1, 5934, 5935, 5915, -1, 5934, 5917, 5914, -1, 5934, 5915, 5917, -1, 5934, 5914, 5911, -1, 5936, 5929, 5931, -1, 5936, 5932, 5933, -1, 5936, 5933, 5929, -1, 5936, 5931, 5932, -1, 5937, 5938, 5939, -1, 5937, 5939, 5940, -1, 5941, 5937, 5940, -1, 5942, 5938, 5937, -1, 5943, 5941, 5940, -1, 5944, 5941, 5943, -1, 5945, 5942, 5937, -1, 5946, 5944, 5943, -1, 5947, 5946, 5943, -1, 5948, 5942, 5945, -1, 5949, 5950, 5951, -1, 5949, 5951, 5948, -1, 5952, 5953, 5946, -1, 5952, 5946, 5947, -1, 5954, 5955, 5950, -1, 5956, 5955, 5954, -1, 5957, 5956, 5954, -1, 5958, 5953, 5952, -1, 5959, 5953, 5958, -1, 5960, 5957, 5961, -1, 5960, 5956, 5957, -1, 5962, 5959, 5958, -1, 5963, 5960, 5961, -1, 5964, 5965, 5959, -1, 5964, 5959, 5962, -1, 5966, 5965, 5964, -1, 5967, 5960, 5963, -1, 5949, 5954, 5950, -1, 5968, 5945, 5969, -1, 5968, 5969, 5949, -1, 5968, 5948, 5945, -1, 5968, 5949, 5948, -1, 5970, 5963, 5965, -1, 5970, 5966, 5967, -1, 5970, 5967, 5963, -1, 5970, 5965, 5966, -1, 5971, 5972, 5973, -1, 5974, 5975, 5976, -1, 5977, 5978, 5979, -1, 5977, 5979, 5972, -1, 5977, 5971, 5980, -1, 5977, 5972, 5971, -1, 5981, 5982, 5978, -1, 5981, 5978, 5977, -1, 5983, 5980, 5984, -1, 5983, 5984, 5985, -1, 5983, 5977, 5980, -1, 5986, 5987, 5974, -1, 5986, 5976, 5982, -1, 5986, 5982, 5981, -1, 5986, 5974, 5976, -1, 5988, 5989, 5990, -1, 5988, 5985, 5991, -1, 5988, 5991, 5989, -1, 5988, 5983, 5985, -1, 5988, 5977, 5983, -1, 5988, 5981, 5977, -1, 5992, 5990, 5993, -1, 5992, 5993, 5994, -1, 5992, 5994, 5987, -1, 5992, 5981, 5988, -1, 5992, 5988, 5990, -1, 5992, 5987, 5986, -1, 5992, 5986, 5981, -1, 5995, 5996, 5997, -1, 5998, 5999, 6000, -1, 6001, 6002, 6003, -1, 6001, 6003, 5996, -1, 6001, 5995, 6004, -1, 6001, 5996, 5995, -1, 6005, 6006, 6002, -1, 6005, 6002, 6001, -1, 6007, 6004, 6008, -1, 6007, 6008, 6009, -1, 6007, 6001, 6004, -1, 6010, 6011, 5998, -1, 6010, 6000, 6006, -1, 6010, 6006, 6005, -1, 6010, 5998, 6000, -1, 6012, 6009, 6013, -1, 6012, 6013, 6014, -1, 6012, 6014, 6015, -1, 6012, 6007, 6009, -1, 6012, 6001, 6007, -1, 6012, 6005, 6001, -1, 6016, 6015, 6017, -1, 6016, 6017, 6018, -1, 6016, 6018, 6011, -1, 6016, 6011, 6010, -1, 6016, 6012, 6015, -1, 6016, 6010, 6005, -1, 6016, 6005, 6012, -1, 6019, 6020, 6021, -1, 6022, 6023, 6024, -1, 6025, 6021, 6026, -1, 6025, 6026, 6027, -1, 6025, 6028, 6019, -1, 6025, 6019, 6021, -1, 6029, 6027, 6023, -1, 6029, 6022, 6030, -1, 6029, 6030, 6028, -1, 6029, 6025, 6027, -1, 6029, 6028, 6025, -1, 6029, 6023, 6022, -1, 6031, 6032, 6033, -1, 6034, 6035, 6036, -1, 6037, 6034, 6036, -1, 6038, 6039, 6040, -1, 6038, 6040, 6041, -1, 6038, 6041, 6042, -1, 6043, 6044, 6045, -1, 6043, 6045, 6039, -1, 6043, 6039, 6038, -1, 6046, 6042, 6032, -1, 6046, 6031, 6047, -1, 6046, 6032, 6031, -1, 6046, 6038, 6042, -1, 6048, 6049, 6050, -1, 6048, 6050, 6051, -1, 6048, 6051, 6044, -1, 6048, 6044, 6043, -1, 6052, 6047, 6053, -1, 6052, 6046, 6047, -1, 6052, 6038, 6046, -1, 6052, 6043, 6038, -1, 6054, 6053, 6035, -1, 6054, 6034, 6049, -1, 6054, 6052, 6053, -1, 6054, 6048, 6043, -1, 6054, 6043, 6052, -1, 6054, 6035, 6034, -1, 6054, 6049, 6048, -1, 6055, 6056, 6057, -1, 6058, 6059, 6060, -1, 6061, 6059, 6058, -1, 6062, 6063, 6064, -1, 6062, 6064, 6065, -1, 6062, 6065, 6066, -1, 6067, 6068, 6063, -1, 6067, 6069, 6068, -1, 6067, 6063, 6062, -1, 6070, 6066, 6056, -1, 6070, 6055, 6071, -1, 6070, 6062, 6066, -1, 6070, 6056, 6055, -1, 6072, 6073, 6074, -1, 6072, 6074, 6075, -1, 6072, 6075, 6069, -1, 6072, 6069, 6067, -1, 6076, 6071, 6077, -1, 6076, 6070, 6071, -1, 6076, 6062, 6070, -1, 6076, 6067, 6062, -1, 6078, 6077, 6060, -1, 6078, 6059, 6073, -1, 6078, 6072, 6067, -1, 6078, 6076, 6077, -1, 6078, 6067, 6076, -1, 6078, 6060, 6059, -1, 6078, 6073, 6072, -1, 6079, 6080, 6081, -1, 6082, 6083, 6084, -1, 6085, 6083, 6082, -1, 6086, 6087, 6088, -1, 6086, 6088, 6089, -1, 6086, 6089, 6090, -1, 6091, 6092, 6087, -1, 6091, 6093, 6092, -1, 6091, 6087, 6086, -1, 6094, 6090, 6080, -1, 6094, 6079, 6095, -1, 6094, 6086, 6090, -1, 6094, 6080, 6079, -1, 6096, 6097, 6098, -1, 6096, 6098, 6099, -1, 6096, 6099, 6093, -1, 6096, 6093, 6091, -1, 6100, 6095, 6101, -1, 6100, 6094, 6095, -1, 6100, 6086, 6094, -1, 6100, 6091, 6086, -1, 6102, 6101, 6084, -1, 6102, 6083, 6097, -1, 6102, 6096, 6091, -1, 6102, 6100, 6101, -1, 6102, 6091, 6100, -1, 6102, 6084, 6083, -1, 6102, 6097, 6096, -1, 6103, 6104, 6105, -1, 6106, 6107, 6108, -1, 6109, 6107, 6106, -1, 6110, 6111, 6112, -1, 6110, 6112, 6113, -1, 6110, 6113, 6114, -1, 6115, 6116, 6117, -1, 6115, 6117, 6111, -1, 6115, 6111, 6110, -1, 6118, 6114, 6104, -1, 6118, 6103, 6119, -1, 6118, 6104, 6103, -1, 6118, 6110, 6114, -1, 6120, 6121, 6122, -1, 6120, 6122, 6123, -1, 6120, 6123, 6116, -1, 6120, 6116, 6115, -1, 6124, 6119, 6125, -1, 6124, 6118, 6119, -1, 6124, 6110, 6118, -1, 6124, 6115, 6110, -1, 6126, 6125, 6108, -1, 6126, 6107, 6121, -1, 6126, 6124, 6125, -1, 6126, 6120, 6115, -1, 6126, 6115, 6124, -1, 6126, 6108, 6107, -1, 6126, 6121, 6120, -1, 6127, 6128, 6129, -1, 6130, 6131, 6132, -1, 6133, 6134, 6135, -1, 6133, 6135, 6128, -1, 6133, 6127, 6136, -1, 6133, 6128, 6127, -1, 6137, 6138, 6134, -1, 6137, 6134, 6133, -1, 6139, 6136, 6140, -1, 6139, 6140, 6141, -1, 6139, 6133, 6136, -1, 6142, 6143, 6130, -1, 6142, 6132, 6138, -1, 6142, 6138, 6137, -1, 6142, 6130, 6132, -1, 6144, 6141, 6145, -1, 6144, 6145, 6146, -1, 6144, 6146, 6147, -1, 6144, 6139, 6141, -1, 6144, 6133, 6139, -1, 6144, 6137, 6133, -1, 6148, 6147, 6149, -1, 6148, 6149, 6150, -1, 6148, 6150, 6143, -1, 6148, 6143, 6142, -1, 6148, 6144, 6147, -1, 6148, 6142, 6137, -1, 6148, 6137, 6144, -1, 6151, 6152, 6153, -1, 6151, 6153, 6154, -1, 6155, 6151, 6154, -1, 6156, 6152, 6151, -1, 6157, 6155, 6154, -1, 6158, 6155, 6157, -1, 6159, 6156, 6151, -1, 6160, 6158, 6157, -1, 6161, 6160, 6157, -1, 6162, 6156, 6159, -1, 6163, 6164, 6165, -1, 6163, 6165, 6162, -1, 6166, 6167, 6160, -1, 6166, 6160, 6161, -1, 6168, 6169, 6164, -1, 6170, 6169, 6168, -1, 6171, 6170, 6168, -1, 6172, 6167, 6166, -1, 6173, 6167, 6172, -1, 6174, 6171, 6175, -1, 6174, 6170, 6171, -1, 6176, 6173, 6172, -1, 6177, 6174, 6175, -1, 6178, 6179, 6173, -1, 6178, 6173, 6176, -1, 6180, 6179, 6178, -1, 6181, 6174, 6177, -1, 6163, 6168, 6164, -1, 6182, 6159, 6183, -1, 6182, 6183, 6163, -1, 6182, 6162, 6159, -1, 6182, 6163, 6162, -1, 6184, 6177, 6179, -1, 6184, 6180, 6181, -1, 6184, 6181, 6177, -1, 6184, 6179, 6180, -1, 6185, 6186, 6187, -1, 6185, 6187, 6188, -1, 6189, 6185, 6188, -1, 6190, 6186, 6185, -1, 6191, 6189, 6188, -1, 6192, 6189, 6191, -1, 6193, 6190, 6185, -1, 6194, 6191, 6195, -1, 6194, 6192, 6191, -1, 6196, 6190, 6193, -1, 6197, 6198, 6199, -1, 6200, 6201, 6194, -1, 6200, 6194, 6195, -1, 6202, 6203, 6198, -1, 6204, 6203, 6202, -1, 6205, 6204, 6202, -1, 6206, 6201, 6200, -1, 6207, 6201, 6206, -1, 6208, 6205, 6209, -1, 6208, 6204, 6205, -1, 6210, 6207, 6206, -1, 6211, 6208, 6209, -1, 6212, 6213, 6207, -1, 6212, 6207, 6210, -1, 6214, 6213, 6212, -1, 6215, 6208, 6211, -1, 6197, 6202, 6198, -1, 6216, 6193, 6217, -1, 6216, 6217, 6197, -1, 6216, 6199, 6196, -1, 6216, 6197, 6199, -1, 6216, 6196, 6193, -1, 6218, 6211, 6213, -1, 6218, 6214, 6215, -1, 6218, 6215, 6211, -1, 6218, 6213, 6214, -1, 6219, 6220, 6221, -1, 6222, 6223, 6224, -1, 6225, 6226, 6227, -1, 6225, 6227, 6220, -1, 6225, 6219, 6228, -1, 6225, 6220, 6219, -1, 6229, 6230, 6226, -1, 6229, 6226, 6225, -1, 6231, 6228, 6232, -1, 6231, 6232, 6233, -1, 6231, 6225, 6228, -1, 6234, 6235, 6222, -1, 6234, 6224, 6230, -1, 6234, 6230, 6229, -1, 6234, 6222, 6224, -1, 6236, 6237, 6238, -1, 6236, 6233, 6239, -1, 6236, 6239, 6237, -1, 6236, 6231, 6233, -1, 6236, 6225, 6231, -1, 6236, 6229, 6225, -1, 6240, 6238, 6241, -1, 6240, 6241, 6242, -1, 6240, 6242, 6235, -1, 6240, 6229, 6236, -1, 6240, 6236, 6238, -1, 6240, 6235, 6234, -1, 6240, 6234, 6229, -1, 6243, 6244, 6245, -1, 6246, 6247, 6248, -1, 6249, 6245, 6250, -1, 6249, 6250, 6251, -1, 6249, 6252, 6243, -1, 6249, 6243, 6245, -1, 6253, 6251, 6247, -1, 6253, 6246, 6254, -1, 6253, 6254, 6252, -1, 6253, 6249, 6251, -1, 6253, 6252, 6249, -1, 6253, 6247, 6246, -1, 6255, 6256, 6257, -1, 6258, 6259, 6260, -1, 6261, 6259, 6258, -1, 6262, 6263, 6264, -1, 6262, 6264, 6265, -1, 6262, 6265, 6266, -1, 6267, 6268, 6263, -1, 6267, 6269, 6268, -1, 6267, 6263, 6262, -1, 6270, 6266, 6256, -1, 6270, 6255, 6271, -1, 6270, 6262, 6266, -1, 6270, 6256, 6255, -1, 6272, 6273, 6274, -1, 6272, 6274, 6275, -1, 6272, 6275, 6269, -1, 6272, 6269, 6267, -1, 6276, 6271, 6277, -1, 6276, 6270, 6271, -1, 6276, 6262, 6270, -1, 6276, 6267, 6262, -1, 6278, 6277, 6260, -1, 6278, 6259, 6273, -1, 6278, 6272, 6267, -1, 6278, 6276, 6277, -1, 6278, 6267, 6276, -1, 6278, 6260, 6259, -1, 6278, 6273, 6272, -1, 6279, 6280, 6281, -1, 6282, 6283, 6284, -1, 6285, 6283, 6282, -1, 6286, 6287, 6288, -1, 6286, 6288, 6289, -1, 6286, 6289, 6290, -1, 6291, 6292, 6287, -1, 6291, 6293, 6292, -1, 6291, 6287, 6286, -1, 6294, 6290, 6280, -1, 6294, 6279, 6295, -1, 6294, 6286, 6290, -1, 6294, 6280, 6279, -1, 6296, 6297, 6298, -1, 6296, 6298, 6299, -1, 6296, 6299, 6293, -1, 6296, 6293, 6291, -1, 6300, 6295, 6301, -1, 6300, 6294, 6295, -1, 6300, 6286, 6294, -1, 6300, 6291, 6286, -1, 6302, 6301, 6284, -1, 6302, 6283, 6297, -1, 6302, 6296, 6291, -1, 6302, 6300, 6301, -1, 6302, 6291, 6300, -1, 6302, 6284, 6283, -1, 6302, 6297, 6296, -1, 6303, 6304, 6305, -1, 6306, 6307, 6308, -1, 6309, 6306, 6308, -1, 6310, 6311, 6312, -1, 6310, 6312, 6313, -1, 6310, 6313, 6314, -1, 6315, 6316, 6317, -1, 6315, 6317, 6311, -1, 6315, 6311, 6310, -1, 6318, 6314, 6304, -1, 6318, 6303, 6319, -1, 6318, 6304, 6303, -1, 6318, 6310, 6314, -1, 6320, 6321, 6322, -1, 6320, 6322, 6323, -1, 6320, 6323, 6316, -1, 6320, 6316, 6315, -1, 6324, 6319, 6325, -1, 6324, 6318, 6319, -1, 6324, 6310, 6318, -1, 6324, 6315, 6310, -1, 6326, 6325, 6307, -1, 6326, 6306, 6321, -1, 6326, 6324, 6325, -1, 6326, 6320, 6315, -1, 6326, 6315, 6324, -1, 6326, 6307, 6306, -1, 6326, 6321, 6320, -1, 6327, 6328, 6329, -1, 6330, 6331, 6332, -1, 6333, 6331, 6330, -1, 6334, 6335, 6336, -1, 6334, 6336, 6337, -1, 6334, 6337, 6338, -1, 6339, 6340, 6341, -1, 6339, 6341, 6335, -1, 6339, 6335, 6334, -1, 6342, 6338, 6328, -1, 6342, 6327, 6343, -1, 6342, 6328, 6327, -1, 6342, 6334, 6338, -1, 6344, 6345, 6346, -1, 6344, 6346, 6347, -1, 6344, 6347, 6340, -1, 6344, 6340, 6339, -1, 6348, 6343, 6349, -1, 6348, 6342, 6343, -1, 6348, 6334, 6342, -1, 6348, 6339, 6334, -1, 6350, 6349, 6332, -1, 6350, 6331, 6345, -1, 6350, 6348, 6349, -1, 6350, 6344, 6339, -1, 6350, 6339, 6348, -1, 6350, 6332, 6331, -1, 6350, 6345, 6344, -1, 6351, 6352, 6353, -1, 6354, 6355, 6356, -1, 6357, 6358, 6359, -1, 6357, 6359, 6352, -1, 6357, 6351, 6360, -1, 6357, 6352, 6351, -1, 6361, 6362, 6358, -1, 6361, 6358, 6357, -1, 6363, 6360, 6364, -1, 6363, 6364, 6365, -1, 6363, 6357, 6360, -1, 6366, 6367, 6354, -1, 6366, 6356, 6362, -1, 6366, 6362, 6361, -1, 6366, 6354, 6356, -1, 6368, 6365, 6369, -1, 6368, 6369, 6370, -1, 6368, 6370, 6371, -1, 6368, 6363, 6365, -1, 6368, 6357, 6363, -1, 6368, 6361, 6357, -1, 6372, 6371, 6373, -1, 6372, 6373, 6374, -1, 6372, 6374, 6367, -1, 6372, 6367, 6366, -1, 6372, 6368, 6371, -1, 6372, 6366, 6361, -1, 6372, 6361, 6368, -1, 6375, 6376, 6377, -1, 6375, 6377, 6378, -1, 6379, 6375, 6378, -1, 6380, 6376, 6375, -1, 6381, 6379, 6378, -1, 6382, 6379, 6381, -1, 6383, 6380, 6375, -1, 6384, 6381, 6385, -1, 6384, 6382, 6381, -1, 6386, 6380, 6383, -1, 6387, 6388, 6389, -1, 6390, 6391, 6384, -1, 6390, 6384, 6385, -1, 6392, 6393, 6388, -1, 6394, 6393, 6392, -1, 6395, 6394, 6392, -1, 6396, 6391, 6390, -1, 6397, 6391, 6396, -1, 6398, 6395, 6399, -1, 6398, 6394, 6395, -1, 6400, 6397, 6396, -1, 6401, 6398, 6399, -1, 6402, 6403, 6397, -1, 6402, 6397, 6400, -1, 6404, 6403, 6402, -1, 6405, 6398, 6401, -1, 6387, 6392, 6388, -1, 6406, 6383, 6407, -1, 6406, 6407, 6387, -1, 6406, 6389, 6386, -1, 6406, 6387, 6389, -1, 6406, 6386, 6383, -1, 6408, 6401, 6403, -1, 6408, 6404, 6405, -1, 6408, 6405, 6401, -1, 6408, 6403, 6404, -1, 6409, 6410, 6411, -1, 6412, 6413, 6414, -1, 6415, 6416, 6417, -1, 6415, 6417, 6410, -1, 6415, 6409, 6418, -1, 6415, 6410, 6409, -1, 6419, 6420, 6416, -1, 6419, 6416, 6415, -1, 6421, 6418, 6422, -1, 6421, 6422, 6423, -1, 6421, 6415, 6418, -1, 6424, 6425, 6412, -1, 6424, 6414, 6420, -1, 6424, 6412, 6414, -1, 6424, 6420, 6419, -1, 6426, 6423, 6427, -1, 6426, 6427, 6428, -1, 6426, 6428, 6429, -1, 6426, 6421, 6423, -1, 6426, 6419, 6415, -1, 6426, 6415, 6421, -1, 6430, 6429, 6431, -1, 6430, 6431, 6432, -1, 6430, 6432, 6425, -1, 6430, 6426, 6429, -1, 6430, 6425, 6424, -1, 6430, 6424, 6419, -1, 6430, 6419, 6426, -1, 6433, 6434, 6435, -1, 6433, 6435, 6436, -1, 6437, 6433, 6436, -1, 6438, 6434, 6433, -1, 6439, 6437, 6436, -1, 6440, 6437, 6439, -1, 6441, 6438, 6433, -1, 6442, 6440, 6439, -1, 6443, 6442, 6439, -1, 6444, 6438, 6441, -1, 6445, 6446, 6447, -1, 6445, 6447, 6444, -1, 6448, 6449, 6442, -1, 6448, 6442, 6443, -1, 6450, 6451, 6446, -1, 6452, 6451, 6450, -1, 6453, 6452, 6450, -1, 6454, 6449, 6448, -1, 6455, 6449, 6454, -1, 6456, 6453, 6457, -1, 6456, 6452, 6453, -1, 6458, 6455, 6454, -1, 6459, 6456, 6457, -1, 6460, 6461, 6455, -1, 6460, 6455, 6458, -1, 6462, 6461, 6460, -1, 6463, 6456, 6459, -1, 6445, 6450, 6446, -1, 6464, 6441, 6465, -1, 6464, 6465, 6445, -1, 6464, 6444, 6441, -1, 6464, 6445, 6444, -1, 6466, 6459, 6461, -1, 6466, 6462, 6463, -1, 6466, 6463, 6459, -1, 6466, 6461, 6462, -1, 6467, 6468, 6469, -1, 6470, 6471, 6472, -1, 6473, 6471, 6470, -1, 6474, 6475, 6476, -1, 6474, 6476, 6477, -1, 6474, 6477, 6478, -1, 6479, 6480, 6475, -1, 6479, 6481, 6480, -1, 6479, 6475, 6474, -1, 6482, 6478, 6468, -1, 6482, 6467, 6483, -1, 6482, 6474, 6478, -1, 6482, 6468, 6467, -1, 6484, 6485, 6486, -1, 6484, 6486, 6487, -1, 6484, 6487, 6481, -1, 6484, 6481, 6479, -1, 6488, 6483, 6489, -1, 6488, 6482, 6483, -1, 6488, 6474, 6482, -1, 6488, 6479, 6474, -1, 6490, 6489, 6472, -1, 6490, 6471, 6485, -1, 6490, 6484, 6479, -1, 6490, 6488, 6489, -1, 6490, 6479, 6488, -1, 6490, 6472, 6471, -1, 6490, 6485, 6484, -1, 6491, 6492, 6493, -1, 6494, 6495, 6496, -1, 6497, 6495, 6494, -1, 6498, 6499, 6500, -1, 6498, 6500, 6501, -1, 6498, 6501, 6502, -1, 6503, 6504, 6505, -1, 6503, 6505, 6499, -1, 6503, 6499, 6498, -1, 6506, 6502, 6492, -1, 6506, 6491, 6507, -1, 6506, 6492, 6491, -1, 6506, 6498, 6502, -1, 6508, 6509, 6510, -1, 6508, 6510, 6511, -1, 6508, 6511, 6504, -1, 6508, 6504, 6503, -1, 6512, 6507, 6513, -1, 6512, 6506, 6507, -1, 6512, 6498, 6506, -1, 6512, 6503, 6498, -1, 6514, 6513, 6496, -1, 6514, 6495, 6509, -1, 6514, 6512, 6513, -1, 6514, 6508, 6503, -1, 6514, 6503, 6512, -1, 6514, 6496, 6495, -1, 6514, 6509, 6508, -1, 6515, 6516, 6517, -1, 6518, 6519, 6520, -1, 6521, 6519, 6518, -1, 6522, 6523, 6524, -1, 6522, 6524, 6525, -1, 6522, 6525, 6526, -1, 6527, 6528, 6529, -1, 6527, 6529, 6523, -1, 6527, 6523, 6522, -1, 6530, 6526, 6516, -1, 6530, 6515, 6531, -1, 6530, 6516, 6515, -1, 6530, 6522, 6526, -1, 6532, 6533, 6534, -1, 6532, 6534, 6535, -1, 6532, 6535, 6528, -1, 6532, 6528, 6527, -1, 6536, 6531, 6537, -1, 6536, 6530, 6531, -1, 6536, 6522, 6530, -1, 6536, 6527, 6522, -1, 6538, 6537, 6520, -1, 6538, 6519, 6533, -1, 6538, 6536, 6537, -1, 6538, 6532, 6527, -1, 6538, 6527, 6536, -1, 6538, 6520, 6519, -1, 6538, 6533, 6532, -1, 6539, 6540, 6541, -1, 6542, 6543, 6544, -1, 6545, 6541, 6546, -1, 6545, 6546, 6547, -1, 6545, 6548, 6539, -1, 6545, 6539, 6541, -1, 6549, 6547, 6543, -1, 6549, 6542, 6550, -1, 6549, 6550, 6548, -1, 6549, 6545, 6547, -1, 6549, 6543, 6542, -1, 6549, 6548, 6545, -1, 6551, 6552, 6553, -1, 6554, 6555, 6556, -1, 6557, 6554, 6556, -1, 6558, 6559, 6560, -1, 6558, 6560, 6561, -1, 6558, 6561, 6562, -1, 6563, 6564, 6565, -1, 6563, 6565, 6559, -1, 6563, 6559, 6558, -1, 6566, 6562, 6552, -1, 6566, 6551, 6567, -1, 6566, 6552, 6551, -1, 6566, 6558, 6562, -1, 6568, 6569, 6570, -1, 6568, 6570, 6571, -1, 6568, 6571, 6564, -1, 6568, 6564, 6563, -1, 6572, 6567, 6573, -1, 6572, 6566, 6567, -1, 6572, 6558, 6566, -1, 6572, 6563, 6558, -1, 6574, 6573, 6555, -1, 6574, 6554, 6569, -1, 6574, 6572, 6573, -1, 6574, 6568, 6563, -1, 6574, 6563, 6572, -1, 6574, 6555, 6554, -1, 6574, 6569, 6568, -1, 6575, 6576, 6577, -1, 6578, 6579, 6580, -1, 6581, 6577, 6582, -1, 6581, 6582, 6583, -1, 6581, 6584, 6575, -1, 6581, 6575, 6577, -1, 6585, 6583, 6579, -1, 6585, 6578, 6586, -1, 6585, 6586, 6584, -1, 6585, 6581, 6583, -1, 6585, 6584, 6581, -1, 6585, 6579, 6578, -1, 6587, 6588, 6589, -1, 6590, 6591, 6592, -1, 6593, 6591, 6590, -1, 6594, 6595, 6596, -1, 6594, 6596, 6597, -1, 6594, 6597, 6598, -1, 6599, 6600, 6595, -1, 6599, 6601, 6600, -1, 6599, 6595, 6594, -1, 6602, 6598, 6588, -1, 6602, 6587, 6603, -1, 6602, 6594, 6598, -1, 6602, 6588, 6587, -1, 6604, 6605, 6606, -1, 6604, 6606, 6607, -1, 6604, 6607, 6601, -1, 6604, 6601, 6599, -1, 6608, 6603, 6609, -1, 6608, 6602, 6603, -1, 6608, 6594, 6602, -1, 6608, 6599, 6594, -1, 6610, 6609, 6592, -1, 6610, 6591, 6605, -1, 6610, 6604, 6599, -1, 6610, 6608, 6609, -1, 6610, 6599, 6608, -1, 6610, 6592, 6591, -1, 6610, 6605, 6604, -1, 6611, 6612, 6613, -1, 6614, 6615, 6616, -1, 6617, 6615, 6614, -1, 6618, 6619, 6620, -1, 6618, 6620, 6621, -1, 6618, 6621, 6622, -1, 6623, 6624, 6625, -1, 6623, 6625, 6619, -1, 6623, 6619, 6618, -1, 6626, 6622, 6612, -1, 6626, 6611, 6627, -1, 6626, 6612, 6611, -1, 6626, 6618, 6622, -1, 6628, 6629, 6630, -1, 6628, 6630, 6631, -1, 6628, 6631, 6624, -1, 6628, 6624, 6623, -1, 6632, 6627, 6633, -1, 6632, 6626, 6627, -1, 6632, 6618, 6626, -1, 6632, 6623, 6618, -1, 6634, 6633, 6616, -1, 6634, 6615, 6629, -1, 6634, 6632, 6633, -1, 6634, 6628, 6623, -1, 6634, 6623, 6632, -1, 6634, 6616, 6615, -1, 6634, 6629, 6628, -1, 6635, 6636, 6637, -1, 6638, 6639, 6640, -1, 6641, 6639, 6638, -1, 6642, 6643, 6644, -1, 6642, 6644, 6645, -1, 6642, 6645, 6646, -1, 6647, 6648, 6643, -1, 6647, 6649, 6648, -1, 6647, 6643, 6642, -1, 6650, 6646, 6636, -1, 6650, 6635, 6651, -1, 6650, 6642, 6646, -1, 6650, 6636, 6635, -1, 6652, 6653, 6654, -1, 6652, 6654, 6655, -1, 6652, 6655, 6649, -1, 6652, 6649, 6647, -1, 6656, 6651, 6657, -1, 6656, 6650, 6651, -1, 6656, 6642, 6650, -1, 6656, 6647, 6642, -1, 6658, 6657, 6640, -1, 6658, 6639, 6653, -1, 6658, 6652, 6647, -1, 6658, 6656, 6657, -1, 6658, 6647, 6656, -1, 6658, 6640, 6639, -1, 6658, 6653, 6652, -1, 6659, 6660, 6661, -1, 6662, 6663, 6664, -1, 6665, 6662, 6664, -1, 6666, 6667, 6668, -1, 6666, 6668, 6669, -1, 6666, 6669, 6670, -1, 6671, 6672, 6673, -1, 6671, 6673, 6667, -1, 6671, 6667, 6666, -1, 6674, 6670, 6660, -1, 6674, 6659, 6675, -1, 6674, 6660, 6659, -1, 6674, 6666, 6670, -1, 6676, 6677, 6678, -1, 6676, 6678, 6679, -1, 6676, 6679, 6672, -1, 6676, 6672, 6671, -1, 6680, 6675, 6681, -1, 6680, 6674, 6675, -1, 6680, 6666, 6674, -1, 6680, 6671, 6666, -1, 6682, 6681, 6663, -1, 6682, 6662, 6677, -1, 6682, 6680, 6681, -1, 6682, 6676, 6671, -1, 6682, 6671, 6680, -1, 6682, 6663, 6662, -1, 6682, 6677, 6676, -1, 6683, 6684, 6685, -1, 6686, 6687, 6688, -1, 6689, 6690, 6691, -1, 6689, 6691, 6684, -1, 6689, 6683, 6692, -1, 6689, 6684, 6683, -1, 6693, 6694, 6690, -1, 6693, 6690, 6689, -1, 6695, 6692, 6696, -1, 6695, 6696, 6697, -1, 6695, 6689, 6692, -1, 6698, 6699, 6686, -1, 6698, 6688, 6694, -1, 6698, 6694, 6693, -1, 6698, 6686, 6688, -1, 6700, 6697, 6701, -1, 6700, 6701, 6702, -1, 6700, 6702, 6703, -1, 6700, 6695, 6697, -1, 6700, 6689, 6695, -1, 6700, 6693, 6689, -1, 6704, 6703, 6705, -1, 6704, 6705, 6706, -1, 6704, 6706, 6699, -1, 6704, 6699, 6698, -1, 6704, 6700, 6703, -1, 6704, 6698, 6693, -1, 6704, 6693, 6700, -1, 6707, 6708, 6709, -1, 6707, 6709, 6710, -1, 6711, 6707, 6710, -1, 6712, 6708, 6707, -1, 6713, 6711, 6710, -1, 6714, 6711, 6713, -1, 6715, 6712, 6707, -1, 6716, 6714, 6713, -1, 6717, 6716, 6713, -1, 6718, 6712, 6715, -1, 6719, 6720, 6721, -1, 6719, 6721, 6718, -1, 6722, 6723, 6716, -1, 6722, 6716, 6717, -1, 6724, 6725, 6720, -1, 6726, 6725, 6724, -1, 6727, 6726, 6724, -1, 6728, 6723, 6722, -1, 6729, 6723, 6728, -1, 6730, 6727, 6731, -1, 6730, 6726, 6727, -1, 6732, 6729, 6728, -1, 6733, 6730, 6731, -1, 6734, 6735, 6729, -1, 6734, 6729, 6732, -1, 6736, 6735, 6734, -1, 6737, 6730, 6733, -1, 6719, 6724, 6720, -1, 6738, 6715, 6739, -1, 6738, 6739, 6719, -1, 6738, 6718, 6715, -1, 6738, 6719, 6718, -1, 6740, 6733, 6735, -1, 6740, 6736, 6737, -1, 6740, 6737, 6733, -1, 6740, 6735, 6736, -1, 6741, 6742, 6743, -1, 6744, 6745, 6746, -1, 6747, 6748, 6749, -1, 6747, 6749, 6742, -1, 6747, 6741, 6750, -1, 6747, 6742, 6741, -1, 6751, 6752, 6748, -1, 6751, 6748, 6747, -1, 6753, 6750, 6754, -1, 6753, 6754, 6755, -1, 6753, 6747, 6750, -1, 6756, 6757, 6744, -1, 6756, 6746, 6752, -1, 6756, 6752, 6751, -1, 6756, 6744, 6746, -1, 6758, 6759, 6760, -1, 6758, 6755, 6761, -1, 6758, 6761, 6759, -1, 6758, 6753, 6755, -1, 6758, 6747, 6753, -1, 6758, 6751, 6747, -1, 6762, 6760, 6763, -1, 6762, 6763, 6764, -1, 6762, 6764, 6757, -1, 6762, 6751, 6758, -1, 6762, 6758, 6760, -1, 6762, 6757, 6756, -1, 6762, 6756, 6751, -1, 6765, 6766, 6767, -1, 6765, 6767, 6768, -1, 6769, 6765, 6768, -1, 6770, 6766, 6765, -1, 6771, 6769, 6768, -1, 6772, 6769, 6771, -1, 6773, 6770, 6765, -1, 6774, 6771, 6775, -1, 6774, 6772, 6771, -1, 6776, 6770, 6773, -1, 6777, 6778, 6779, -1, 6780, 6781, 6774, -1, 6780, 6774, 6775, -1, 6782, 6783, 6778, -1, 6784, 6783, 6782, -1, 6785, 6784, 6782, -1, 6786, 6781, 6780, -1, 6787, 6781, 6786, -1, 6788, 6785, 6789, -1, 6788, 6784, 6785, -1, 6790, 6787, 6786, -1, 6791, 6788, 6789, -1, 6792, 6793, 6787, -1, 6792, 6787, 6790, -1, 6794, 6793, 6792, -1, 6795, 6788, 6791, -1, 6777, 6782, 6778, -1, 6796, 6773, 6797, -1, 6796, 6797, 6777, -1, 6796, 6779, 6776, -1, 6796, 6777, 6779, -1, 6796, 6776, 6773, -1, 6798, 6791, 6793, -1, 6798, 6794, 6795, -1, 6798, 6795, 6791, -1, 6798, 6793, 6794, -1, 6799, 6800, 6801, -1, 6802, 6803, 6804, -1, 6805, 6803, 6802, -1, 6806, 6807, 6808, -1, 6806, 6808, 6809, -1, 6806, 6809, 6810, -1, 6811, 6812, 6813, -1, 6811, 6813, 6807, -1, 6811, 6807, 6806, -1, 6814, 6810, 6800, -1, 6814, 6799, 6815, -1, 6814, 6800, 6799, -1, 6814, 6806, 6810, -1, 6816, 6817, 6818, -1, 6816, 6818, 6819, -1, 6816, 6819, 6812, -1, 6816, 6812, 6811, -1, 6820, 6815, 6821, -1, 6820, 6814, 6815, -1, 6820, 6806, 6814, -1, 6820, 6811, 6806, -1, 6822, 6821, 6804, -1, 6822, 6803, 6817, -1, 6822, 6820, 6821, -1, 6822, 6816, 6811, -1, 6822, 6811, 6820, -1, 6822, 6804, 6803, -1, 6822, 6817, 6816, -1, 6823, 6824, 6825, -1, 6826, 6827, 6828, -1, 6829, 6827, 6826, -1, 6830, 6831, 6832, -1, 6830, 6832, 6833, -1, 6830, 6833, 6834, -1, 6835, 6836, 6831, -1, 6835, 6837, 6836, -1, 6835, 6831, 6830, -1, 6838, 6834, 6824, -1, 6838, 6823, 6839, -1, 6838, 6830, 6834, -1, 6838, 6824, 6823, -1, 6840, 6841, 6842, -1, 6840, 6842, 6843, -1, 6840, 6843, 6837, -1, 6840, 6837, 6835, -1, 6844, 6839, 6845, -1, 6844, 6838, 6839, -1, 6844, 6830, 6838, -1, 6844, 6835, 6830, -1, 6846, 6845, 6828, -1, 6846, 6827, 6841, -1, 6846, 6840, 6835, -1, 6846, 6844, 6845, -1, 6846, 6835, 6844, -1, 6846, 6828, 6827, -1, 6846, 6841, 6840, -1, 6847, 6848, 6849, -1, 6850, 6851, 6852, -1, 6853, 6850, 6852, -1, 6854, 6855, 6856, -1, 6854, 6856, 6857, -1, 6854, 6857, 6858, -1, 6859, 6860, 6855, -1, 6859, 6861, 6860, -1, 6859, 6855, 6854, -1, 6862, 6858, 6848, -1, 6862, 6847, 6863, -1, 6862, 6854, 6858, -1, 6862, 6848, 6847, -1, 6864, 6865, 6866, -1, 6864, 6866, 6867, -1, 6864, 6867, 6861, -1, 6864, 6861, 6859, -1, 6868, 6863, 6869, -1, 6868, 6862, 6863, -1, 6868, 6854, 6862, -1, 6868, 6859, 6854, -1, 6870, 6869, 6851, -1, 6870, 6850, 6865, -1, 6870, 6864, 6859, -1, 6870, 6868, 6869, -1, 6870, 6859, 6868, -1, 6870, 6851, 6850, -1, 6870, 6865, 6864, -1, 6871, 6872, 6873, -1, 6874, 6875, 6876, -1, 6877, 6875, 6874, -1, 6878, 6879, 6880, -1, 6878, 6880, 6881, -1, 6878, 6881, 6882, -1, 6883, 6884, 6885, -1, 6883, 6885, 6879, -1, 6883, 6879, 6878, -1, 6886, 6882, 6872, -1, 6886, 6871, 6887, -1, 6886, 6872, 6871, -1, 6886, 6878, 6882, -1, 6888, 6889, 6890, -1, 6888, 6890, 6891, -1, 6888, 6891, 6884, -1, 6888, 6884, 6883, -1, 6892, 6887, 6893, -1, 6892, 6886, 6887, -1, 6892, 6878, 6886, -1, 6892, 6883, 6878, -1, 6894, 6893, 6876, -1, 6894, 6875, 6889, -1, 6894, 6892, 6893, -1, 6894, 6888, 6883, -1, 6894, 6883, 6892, -1, 6894, 6876, 6875, -1, 6894, 6889, 6888, -1, 6895, 6896, 6897, -1, 6898, 6899, 6900, -1, 6901, 6902, 6903, -1, 6901, 6903, 6895, -1, 6901, 6897, 6904, -1, 6901, 6895, 6897, -1, 6905, 6906, 6900, -1, 6905, 6899, 6902, -1, 6905, 6904, 6906, -1, 6905, 6901, 6904, -1, 6905, 6902, 6901, -1, 6905, 6900, 6899, -1, 6907, 6908, 6909, -1, 6907, 6909, 6910, -1, 6911, 6907, 6910, -1, 6912, 6908, 6907, -1, 6913, 6911, 6910, -1, 6914, 6911, 6913, -1, 6915, 6912, 6907, -1, 6916, 6913, 6917, -1, 6916, 6914, 6913, -1, 6918, 6912, 6915, -1, 6919, 6920, 6921, -1, 6922, 6923, 6916, -1, 6922, 6916, 6917, -1, 6924, 6925, 6920, -1, 6926, 6925, 6924, -1, 6927, 6926, 6924, -1, 6928, 6923, 6922, -1, 6929, 6923, 6928, -1, 6930, 6927, 6931, -1, 6930, 6926, 6927, -1, 6932, 6929, 6928, -1, 6933, 6930, 6931, -1, 6934, 6935, 6929, -1, 6934, 6929, 6932, -1, 6936, 6935, 6934, -1, 6937, 6930, 6933, -1, 6919, 6924, 6920, -1, 6938, 6915, 6939, -1, 6938, 6939, 6919, -1, 6938, 6921, 6918, -1, 6938, 6919, 6921, -1, 6938, 6918, 6915, -1, 6940, 6933, 6935, -1, 6940, 6936, 6937, -1, 6940, 6937, 6933, -1, 6940, 6935, 6936, -1, 6941, 6942, 6943, -1, 6944, 6945, 6946, -1, 6947, 6948, 6949, -1, 6947, 6949, 6942, -1, 6947, 6941, 6950, -1, 6947, 6942, 6941, -1, 6951, 6952, 6948, -1, 6951, 6948, 6947, -1, 6953, 6950, 6954, -1, 6953, 6954, 6955, -1, 6953, 6947, 6950, -1, 6956, 6957, 6944, -1, 6956, 6946, 6952, -1, 6956, 6952, 6951, -1, 6956, 6944, 6946, -1, 6958, 6959, 6960, -1, 6958, 6955, 6961, -1, 6958, 6961, 6959, -1, 6958, 6953, 6955, -1, 6958, 6947, 6953, -1, 6958, 6951, 6947, -1, 6962, 6960, 6963, -1, 6962, 6963, 6964, -1, 6962, 6964, 6957, -1, 6962, 6951, 6958, -1, 6962, 6958, 6960, -1, 6962, 6957, 6956, -1, 6962, 6956, 6951, -1, 6965, 6966, 6967, -1, 6965, 6967, 6968, -1, 6969, 6965, 6968, -1, 6970, 6966, 6965, -1, 6971, 6969, 6968, -1, 6972, 6969, 6971, -1, 6973, 6970, 6965, -1, 6974, 6972, 6971, -1, 6975, 6974, 6971, -1, 6976, 6970, 6973, -1, 6977, 6978, 6979, -1, 6977, 6979, 6976, -1, 6980, 6981, 6974, -1, 6980, 6974, 6975, -1, 6982, 6983, 6978, -1, 6984, 6983, 6982, -1, 6985, 6984, 6982, -1, 6986, 6981, 6980, -1, 6987, 6981, 6986, -1, 6988, 6985, 6989, -1, 6988, 6984, 6985, -1, 6990, 6987, 6986, -1, 6991, 6988, 6989, -1, 6992, 6993, 6987, -1, 6992, 6987, 6990, -1, 6994, 6993, 6992, -1, 6995, 6988, 6991, -1, 6977, 6982, 6978, -1, 6996, 6973, 6997, -1, 6996, 6997, 6977, -1, 6996, 6976, 6973, -1, 6996, 6977, 6976, -1, 6998, 6991, 6993, -1, 6998, 6994, 6995, -1, 6998, 6995, 6991, -1, 6998, 6993, 6994, -1, 6999, 7000, 7001, -1, 7002, 7003, 7004, -1, 7005, 7006, 7007, -1, 7005, 7007, 7000, -1, 7005, 6999, 7008, -1, 7005, 7000, 6999, -1, 7009, 7010, 7006, -1, 7009, 7006, 7005, -1, 7011, 7008, 7012, -1, 7011, 7012, 7013, -1, 7011, 7005, 7008, -1, 7014, 7015, 7002, -1, 7014, 7004, 7010, -1, 7014, 7002, 7004, -1, 7014, 7010, 7009, -1, 7016, 7013, 7017, -1, 7016, 7017, 7018, -1, 7016, 7018, 7019, -1, 7016, 7011, 7013, -1, 7016, 7009, 7005, -1, 7016, 7005, 7011, -1, 7020, 7019, 7021, -1, 7020, 7021, 7022, -1, 7020, 7022, 7015, -1, 7020, 7016, 7019, -1, 7020, 7015, 7014, -1, 7020, 7014, 7009, -1, 7020, 7009, 7016, -1, 7023, 7024, 7025, -1, 7026, 7027, 7028, -1, 7029, 7026, 7028, -1, 7030, 7031, 7032, -1, 7030, 7032, 7033, -1, 7030, 7033, 7034, -1, 7035, 7036, 7037, -1, 7035, 7037, 7031, -1, 7035, 7031, 7030, -1, 7038, 7034, 7024, -1, 7038, 7023, 7039, -1, 7038, 7024, 7023, -1, 7038, 7030, 7034, -1, 7040, 7041, 7042, -1, 7040, 7042, 7043, -1, 7040, 7043, 7036, -1, 7040, 7036, 7035, -1, 7044, 7039, 7045, -1, 7044, 7038, 7039, -1, 7044, 7030, 7038, -1, 7044, 7035, 7030, -1, 7046, 7045, 7027, -1, 7046, 7026, 7041, -1, 7046, 7044, 7045, -1, 7046, 7040, 7035, -1, 7046, 7035, 7044, -1, 7046, 7027, 7026, -1, 7046, 7041, 7040, -1, 7047, 7048, 7049, -1, 7050, 7051, 7052, -1, 7053, 7051, 7050, -1, 7054, 7055, 7056, -1, 7054, 7056, 7057, -1, 7054, 7057, 7058, -1, 7059, 7060, 7061, -1, 7059, 7061, 7055, -1, 7059, 7055, 7054, -1, 7062, 7058, 7048, -1, 7062, 7047, 7063, -1, 7062, 7048, 7047, -1, 7062, 7054, 7058, -1, 7064, 7065, 7066, -1, 7064, 7066, 7067, -1, 7064, 7067, 7060, -1, 7064, 7060, 7059, -1, 7068, 7063, 7069, -1, 7068, 7062, 7063, -1, 7068, 7054, 7062, -1, 7068, 7059, 7054, -1, 7070, 7069, 7052, -1, 7070, 7051, 7065, -1, 7070, 7068, 7069, -1, 7070, 7064, 7059, -1, 7070, 7059, 7068, -1, 7070, 7052, 7051, -1, 7070, 7065, 7064, -1, 7071, 7072, 7073, -1, 7074, 7075, 7076, -1, 7077, 7078, 7079, -1, 7077, 7079, 7071, -1, 7077, 7073, 7080, -1, 7077, 7071, 7073, -1, 7081, 7082, 7076, -1, 7081, 7075, 7078, -1, 7081, 7080, 7082, -1, 7081, 7077, 7080, -1, 7081, 7078, 7077, -1, 7081, 7076, 7075, -1, 7083, 7084, 7085, -1, 7086, 7087, 7088, -1, 7089, 7087, 7086, -1, 7090, 7091, 7092, -1, 7090, 7092, 7093, -1, 7090, 7093, 7094, -1, 7095, 7096, 7091, -1, 7095, 7097, 7096, -1, 7095, 7091, 7090, -1, 7098, 7094, 7084, -1, 7098, 7083, 7099, -1, 7098, 7090, 7094, -1, 7098, 7084, 7083, -1, 7100, 7101, 7102, -1, 7100, 7102, 7103, -1, 7100, 7103, 7097, -1, 7100, 7097, 7095, -1, 7104, 7099, 7105, -1, 7104, 7098, 7099, -1, 7104, 7090, 7098, -1, 7104, 7095, 7090, -1, 7106, 7105, 7088, -1, 7106, 7087, 7101, -1, 7106, 7100, 7095, -1, 7106, 7104, 7105, -1, 7106, 7095, 7104, -1, 7106, 7088, 7087, -1, 7106, 7101, 7100, -1, 7107, 7108, 7109, -1, 7110, 7111, 7112, -1, 7113, 7111, 7110, -1, 7114, 7115, 7116, -1, 7114, 7116, 7117, -1, 7114, 7117, 7118, -1, 7119, 7120, 7115, -1, 7119, 7121, 7120, -1, 7119, 7115, 7114, -1, 7122, 7118, 7108, -1, 7122, 7107, 7123, -1, 7122, 7114, 7118, -1, 7122, 7108, 7107, -1, 7124, 7125, 7126, -1, 7124, 7126, 7127, -1, 7124, 7127, 7121, -1, 7124, 7121, 7119, -1, 7128, 7123, 7129, -1, 7128, 7122, 7123, -1, 7128, 7114, 7122, -1, 7128, 7119, 7114, -1, 7130, 7129, 7112, -1, 7130, 7111, 7125, -1, 7130, 7124, 7119, -1, 7130, 7128, 7129, -1, 7130, 7119, 7128, -1, 7130, 7112, 7111, -1, 7130, 7125, 7124, -1, 7131, 7132, 7133, -1, 7131, 7133, 7134, -1, 7135, 7131, 7134, -1, 7136, 7132, 7131, -1, 7137, 7135, 7134, -1, 7138, 7135, 7137, -1, 7139, 7136, 7131, -1, 7140, 7137, 7141, -1, 7140, 7138, 7137, -1, 7142, 7136, 7139, -1, 7143, 7144, 7145, -1, 7146, 7147, 7140, -1, 7146, 7140, 7141, -1, 7148, 7149, 7144, -1, 7150, 7149, 7148, -1, 7151, 7150, 7148, -1, 7152, 7147, 7146, -1, 7153, 7147, 7152, -1, 7154, 7151, 7155, -1, 7154, 7150, 7151, -1, 7156, 7153, 7152, -1, 7157, 7154, 7155, -1, 7158, 7159, 7153, -1, 7158, 7153, 7156, -1, 7160, 7159, 7158, -1, 7161, 7154, 7157, -1, 7143, 7148, 7144, -1, 7162, 7139, 7163, -1, 7162, 7163, 7143, -1, 7162, 7145, 7142, -1, 7162, 7143, 7145, -1, 7162, 7142, 7139, -1, 7164, 7157, 7159, -1, 7164, 7160, 7161, -1, 7164, 7161, 7157, -1, 7164, 7159, 7160, -1, 7165, 7166, 7167, -1, 7168, 7169, 7170, -1, 7171, 7172, 7173, -1, 7171, 7173, 7166, -1, 7171, 7165, 7174, -1, 7171, 7166, 7165, -1, 7175, 7176, 7172, -1, 7175, 7172, 7171, -1, 7177, 7174, 7178, -1, 7177, 7178, 7179, -1, 7177, 7171, 7174, -1, 7180, 7181, 7168, -1, 7180, 7170, 7176, -1, 7180, 7168, 7170, -1, 7180, 7176, 7175, -1, 7182, 7179, 7183, -1, 7182, 7183, 7184, -1, 7182, 7184, 7185, -1, 7182, 7177, 7179, -1, 7182, 7175, 7171, -1, 7182, 7171, 7177, -1, 7186, 7185, 7187, -1, 7186, 7187, 7188, -1, 7186, 7188, 7181, -1, 7186, 7182, 7185, -1, 7186, 7181, 7180, -1, 7186, 7180, 7175, -1, 7186, 7175, 7182, -1, 7189, 7190, 7191, -1, 7189, 7191, 7192, -1, 7193, 7189, 7192, -1, 7194, 7190, 7189, -1, 7195, 7193, 7192, -1, 7196, 7193, 7195, -1, 7197, 7194, 7189, -1, 7198, 7196, 7195, -1, 7199, 7198, 7195, -1, 7200, 7194, 7197, -1, 7201, 7202, 7203, -1, 7201, 7203, 7200, -1, 7204, 7205, 7198, -1, 7204, 7198, 7199, -1, 7206, 7207, 7202, -1, 7208, 7207, 7206, -1, 7209, 7208, 7206, -1, 7210, 7205, 7204, -1, 7211, 7205, 7210, -1, 7212, 7209, 7213, -1, 7212, 7208, 7209, -1, 7214, 7211, 7210, -1, 7215, 7212, 7213, -1, 7216, 7217, 7211, -1, 7216, 7211, 7214, -1, 7218, 7217, 7216, -1, 7219, 7212, 7215, -1, 7201, 7206, 7202, -1, 7220, 7197, 7221, -1, 7220, 7221, 7201, -1, 7220, 7200, 7197, -1, 7220, 7201, 7200, -1, 7222, 7215, 7217, -1, 7222, 7218, 7219, -1, 7222, 7219, 7215, -1, 7222, 7217, 7218, -1, 7223, 7224, 7225, -1, 7226, 7227, 7228, -1, 7229, 7230, 7231, -1, 7229, 7231, 7224, -1, 7229, 7223, 7232, -1, 7229, 7224, 7223, -1, 7233, 7234, 7230, -1, 7233, 7230, 7229, -1, 7235, 7232, 7236, -1, 7235, 7236, 7237, -1, 7235, 7229, 7232, -1, 7238, 7239, 7226, -1, 7238, 7228, 7234, -1, 7238, 7234, 7233, -1, 7238, 7226, 7228, -1, 7240, 7241, 7242, -1, 7240, 7237, 7243, -1, 7240, 7243, 7241, -1, 7240, 7235, 7237, -1, 7240, 7229, 7235, -1, 7240, 7233, 7229, -1, 7244, 7242, 7245, -1, 7244, 7245, 7246, -1, 7244, 7246, 7239, -1, 7244, 7233, 7240, -1, 7244, 7240, 7242, -1, 7244, 7239, 7238, -1, 7244, 7238, 7233, -1, 7247, 7248, 7249, -1, 7250, 7251, 7252, -1, 7253, 7254, 7255, -1, 7253, 7255, 7248, -1, 7253, 7247, 7256, -1, 7253, 7248, 7247, -1, 7257, 7258, 7254, -1, 7257, 7254, 7253, -1, 7259, 7256, 7260, -1, 7259, 7260, 7261, -1, 7259, 7253, 7256, -1, 7262, 7263, 7250, -1, 7262, 7252, 7258, -1, 7262, 7258, 7257, -1, 7262, 7250, 7252, -1, 7264, 7265, 7266, -1, 7264, 7261, 7267, -1, 7264, 7267, 7265, -1, 7264, 7259, 7261, -1, 7264, 7253, 7259, -1, 7264, 7257, 7253, -1, 7268, 7266, 7269, -1, 7268, 7269, 7270, -1, 7268, 7270, 7263, -1, 7268, 7257, 7264, -1, 7268, 7264, 7266, -1, 7268, 7263, 7262, -1, 7268, 7262, 7257, -1, 7271, 7272, 7273, -1, 7274, 7275, 7276, -1, 7277, 7278, 7279, -1, 7277, 7279, 7272, -1, 7277, 7271, 7280, -1, 7277, 7272, 7271, -1, 7281, 7282, 7278, -1, 7281, 7278, 7277, -1, 7283, 7280, 7284, -1, 7283, 7284, 7285, -1, 7283, 7277, 7280, -1, 7286, 7287, 7274, -1, 7286, 7276, 7282, -1, 7286, 7282, 7281, -1, 7286, 7274, 7276, -1, 7288, 7289, 7290, -1, 7288, 7285, 7291, -1, 7288, 7291, 7289, -1, 7288, 7283, 7285, -1, 7288, 7277, 7283, -1, 7288, 7281, 7277, -1, 7292, 7290, 7293, -1, 7292, 7293, 7294, -1, 7292, 7294, 7287, -1, 7292, 7281, 7288, -1, 7292, 7288, 7290, -1, 7292, 7287, 7286, -1, 7292, 7286, 7281, -1, 7295, 7296, 7297, -1, 7295, 7297, 7298, -1, 7299, 7295, 7298, -1, 7300, 7296, 7295, -1, 7301, 7299, 7298, -1, 7302, 7299, 7301, -1, 7303, 7300, 7295, -1, 7304, 7301, 7305, -1, 7304, 7302, 7301, -1, 7306, 7300, 7303, -1, 7307, 7308, 7309, -1, 7310, 7311, 7304, -1, 7310, 7304, 7305, -1, 7312, 7313, 7308, -1, 7314, 7313, 7312, -1, 7315, 7314, 7312, -1, 7316, 7311, 7310, -1, 7317, 7311, 7316, -1, 7318, 7315, 7319, -1, 7318, 7314, 7315, -1, 7320, 7317, 7316, -1, 7321, 7318, 7319, -1, 7322, 7323, 7317, -1, 7322, 7317, 7320, -1, 7324, 7323, 7322, -1, 7325, 7318, 7321, -1, 7307, 7312, 7308, -1, 7326, 7303, 7327, -1, 7326, 7327, 7307, -1, 7326, 7309, 7306, -1, 7326, 7307, 7309, -1, 7326, 7306, 7303, -1, 7328, 7321, 7323, -1, 7328, 7324, 7325, -1, 7328, 7325, 7321, -1, 7328, 7323, 7324, -1, 7329, 7330, 7331, -1, 7329, 7331, 7332, -1, 7333, 7329, 7332, -1, 7334, 7330, 7329, -1, 7335, 7333, 7332, -1, 7336, 7333, 7335, -1, 7337, 7334, 7329, -1, 7338, 7336, 7335, -1, 7339, 7338, 7335, -1, 7340, 7334, 7337, -1, 7341, 7342, 7343, -1, 7341, 7343, 7340, -1, 7344, 7345, 7338, -1, 7344, 7338, 7339, -1, 7346, 7347, 7342, -1, 7348, 7347, 7346, -1, 7349, 7348, 7346, -1, 7350, 7345, 7344, -1, 7351, 7345, 7350, -1, 7352, 7349, 7353, -1, 7352, 7348, 7349, -1, 7354, 7351, 7350, -1, 7355, 7352, 7353, -1, 7356, 7357, 7351, -1, 7356, 7351, 7354, -1, 7358, 7357, 7356, -1, 7359, 7352, 7355, -1, 7341, 7346, 7342, -1, 7360, 7337, 7361, -1, 7360, 7361, 7341, -1, 7360, 7340, 7337, -1, 7360, 7341, 7340, -1, 7362, 7355, 7357, -1, 7362, 7358, 7359, -1, 7362, 7359, 7355, -1, 7362, 7357, 7358, -1, 7363, 7364, 7365, -1, 7366, 7367, 7368, -1, 7369, 7370, 7371, -1, 7369, 7371, 7363, -1, 7369, 7365, 7372, -1, 7369, 7363, 7365, -1, 7373, 7374, 7368, -1, 7373, 7367, 7370, -1, 7373, 7372, 7374, -1, 7373, 7369, 7372, -1, 7373, 7370, 7369, -1, 7373, 7368, 7367, -1, 7375, 7376, 7377, -1, 7378, 7379, 7380, -1, 7381, 7378, 7380, -1, 7382, 7383, 7384, -1, 7382, 7384, 7385, -1, 7382, 7385, 7386, -1, 7387, 7388, 7389, -1, 7387, 7389, 7383, -1, 7387, 7383, 7382, -1, 7390, 7386, 7376, -1, 7390, 7375, 7391, -1, 7390, 7376, 7375, -1, 7390, 7382, 7386, -1, 7392, 7393, 7394, -1, 7392, 7394, 7395, -1, 7392, 7395, 7388, -1, 7392, 7388, 7387, -1, 7396, 7391, 7397, -1, 7396, 7390, 7391, -1, 7396, 7382, 7390, -1, 7396, 7387, 7382, -1, 7398, 7397, 7379, -1, 7398, 7378, 7393, -1, 7398, 7396, 7397, -1, 7398, 7392, 7387, -1, 7398, 7387, 7396, -1, 7398, 7379, 7378, -1, 7398, 7393, 7392, -1, 7399, 7400, 7401, -1, 7402, 7403, 7404, -1, 7405, 7403, 7402, -1, 7406, 7407, 7408, -1, 7406, 7408, 7409, -1, 7406, 7409, 7410, -1, 7411, 7412, 7413, -1, 7411, 7413, 7407, -1, 7411, 7407, 7406, -1, 7414, 7410, 7400, -1, 7414, 7399, 7415, -1, 7414, 7400, 7399, -1, 7414, 7406, 7410, -1, 7416, 7417, 7418, -1, 7416, 7418, 7419, -1, 7416, 7419, 7412, -1, 7416, 7412, 7411, -1, 7420, 7415, 7421, -1, 7420, 7414, 7415, -1, 7420, 7406, 7414, -1, 7420, 7411, 7406, -1, 7422, 7421, 7404, -1, 7422, 7403, 7417, -1, 7422, 7420, 7421, -1, 7422, 7416, 7411, -1, 7422, 7411, 7420, -1, 7422, 7404, 7403, -1, 7422, 7417, 7416, -1, 7423, 7424, 7425, -1, 7426, 7427, 7428, -1, 7429, 7427, 7426, -1, 7430, 7431, 7432, -1, 7430, 7432, 7433, -1, 7430, 7433, 7434, -1, 7435, 7436, 7437, -1, 7435, 7437, 7431, -1, 7435, 7431, 7430, -1, 7438, 7434, 7424, -1, 7438, 7423, 7439, -1, 7438, 7424, 7423, -1, 7438, 7430, 7434, -1, 7440, 7441, 7442, -1, 7440, 7442, 7443, -1, 7440, 7443, 7436, -1, 7440, 7436, 7435, -1, 7444, 7439, 7445, -1, 7444, 7438, 7439, -1, 7444, 7430, 7438, -1, 7444, 7435, 7430, -1, 7446, 7445, 7428, -1, 7446, 7427, 7441, -1, 7446, 7444, 7445, -1, 7446, 7440, 7435, -1, 7446, 7435, 7444, -1, 7446, 7428, 7427, -1, 7446, 7441, 7440, -1, 7447, 7448, 7449, -1, 7450, 7451, 7452, -1, 7453, 7451, 7450, -1, 7454, 7455, 7456, -1, 7454, 7456, 7457, -1, 7454, 7457, 7458, -1, 7459, 7460, 7455, -1, 7459, 7461, 7460, -1, 7459, 7455, 7454, -1, 7462, 7458, 7448, -1, 7462, 7447, 7463, -1, 7462, 7454, 7458, -1, 7462, 7448, 7447, -1, 7464, 7465, 7466, -1, 7464, 7466, 7467, -1, 7464, 7467, 7461, -1, 7464, 7461, 7459, -1, 7468, 7463, 7469, -1, 7468, 7462, 7463, -1, 7468, 7454, 7462, -1, 7468, 7459, 7454, -1, 7470, 7469, 7452, -1, 7470, 7451, 7465, -1, 7470, 7464, 7459, -1, 7470, 7468, 7469, -1, 7470, 7459, 7468, -1, 7470, 7452, 7451, -1, 7470, 7465, 7464, -1, 7471, 7472, 7473, -1, 7474, 7475, 7476, -1, 7477, 7475, 7474, -1, 7478, 7479, 7480, -1, 7478, 7480, 7481, -1, 7478, 7481, 7482, -1, 7483, 7484, 7485, -1, 7483, 7485, 7479, -1, 7483, 7479, 7478, -1, 7486, 7482, 7472, -1, 7486, 7471, 7487, -1, 7486, 7472, 7471, -1, 7486, 7478, 7482, -1, 7488, 7489, 7490, -1, 7488, 7490, 7491, -1, 7488, 7491, 7484, -1, 7488, 7484, 7483, -1, 7492, 7487, 7493, -1, 7492, 7486, 7487, -1, 7492, 7478, 7486, -1, 7492, 7483, 7478, -1, 7494, 7493, 7476, -1, 7494, 7475, 7489, -1, 7494, 7492, 7493, -1, 7494, 7488, 7483, -1, 7494, 7483, 7492, -1, 7494, 7476, 7475, -1, 7494, 7489, 7488, -1, 7495, 7496, 7497, -1, 7498, 7499, 7500, -1, 7501, 7499, 7498, -1, 7502, 7503, 7504, -1, 7502, 7504, 7505, -1, 7502, 7505, 7506, -1, 7507, 7508, 7509, -1, 7507, 7509, 7503, -1, 7507, 7503, 7502, -1, 7510, 7506, 7496, -1, 7510, 7495, 7511, -1, 7510, 7496, 7495, -1, 7510, 7502, 7506, -1, 7512, 7513, 7514, -1, 7512, 7514, 7515, -1, 7512, 7515, 7508, -1, 7512, 7508, 7507, -1, 7516, 7511, 7517, -1, 7516, 7510, 7511, -1, 7516, 7502, 7510, -1, 7516, 7507, 7502, -1, 7518, 7517, 7500, -1, 7518, 7499, 7513, -1, 7518, 7516, 7517, -1, 7518, 7512, 7507, -1, 7518, 7507, 7516, -1, 7518, 7500, 7499, -1, 7518, 7513, 7512, -1, 7519, 7520, 7521, -1, 7522, 7523, 7524, -1, 7525, 7522, 7524, -1, 7526, 7527, 7528, -1, 7526, 7528, 7529, -1, 7526, 7529, 7530, -1, 7531, 7532, 7527, -1, 7531, 7533, 7532, -1, 7531, 7527, 7526, -1, 7534, 7530, 7520, -1, 7534, 7519, 7535, -1, 7534, 7526, 7530, -1, 7534, 7520, 7519, -1, 7536, 7537, 7538, -1, 7536, 7538, 7539, -1, 7536, 7539, 7533, -1, 7536, 7533, 7531, -1, 7540, 7535, 7541, -1, 7540, 7534, 7535, -1, 7540, 7526, 7534, -1, 7540, 7531, 7526, -1, 7542, 7541, 7523, -1, 7542, 7522, 7537, -1, 7542, 7536, 7531, -1, 7542, 7540, 7541, -1, 7542, 7531, 7540, -1, 7542, 7523, 7522, -1, 7542, 7537, 7536, -1, 7543, 7544, 7545, -1, 7546, 7547, 7548, -1, 7549, 7550, 7551, -1, 7549, 7551, 7543, -1, 7549, 7545, 7552, -1, 7549, 7543, 7545, -1, 7553, 7554, 7548, -1, 7553, 7547, 7550, -1, 7553, 7552, 7554, -1, 7553, 7549, 7552, -1, 7553, 7550, 7549, -1, 7553, 7548, 7547, -1, 7555, 7556, 7557, -1, 7558, 7559, 7560, -1, 7561, 7559, 7558, -1, 7562, 7563, 7564, -1, 7562, 7564, 7565, -1, 7562, 7565, 7566, -1, 7567, 7568, 7563, -1, 7567, 7569, 7568, -1, 7567, 7563, 7562, -1, 7570, 7566, 7556, -1, 7570, 7555, 7571, -1, 7570, 7562, 7566, -1, 7570, 7556, 7555, -1, 7572, 7573, 7574, -1, 7572, 7574, 7575, -1, 7572, 7575, 7569, -1, 7572, 7569, 7567, -1, 7576, 7571, 7577, -1, 7576, 7570, 7571, -1, 7576, 7562, 7570, -1, 7576, 7567, 7562, -1, 7578, 7577, 7560, -1, 7578, 7559, 7573, -1, 7578, 7572, 7567, -1, 7578, 7576, 7577, -1, 7578, 7567, 7576, -1, 7578, 7560, 7559, -1, 7578, 7573, 7572, -1, 7579, 7580, 7581, -1, 7579, 7581, 7582, -1, 7583, 7579, 7582, -1, 7584, 7580, 7579, -1, 7585, 7583, 7582, -1, 7586, 7583, 7585, -1, 7587, 7584, 7579, -1, 7588, 7586, 7585, -1, 7589, 7588, 7585, -1, 7590, 7584, 7587, -1, 7591, 7592, 7593, -1, 7591, 7593, 7590, -1, 7594, 7595, 7588, -1, 7594, 7588, 7589, -1, 7596, 7597, 7592, -1, 7598, 7597, 7596, -1, 7599, 7598, 7596, -1, 7600, 7595, 7594, -1, 7601, 7595, 7600, -1, 7602, 7599, 7603, -1, 7602, 7598, 7599, -1, 7604, 7601, 7600, -1, 7605, 7602, 7603, -1, 7606, 7607, 7601, -1, 7606, 7601, 7604, -1, 7608, 7607, 7606, -1, 7609, 7602, 7605, -1, 7591, 7596, 7592, -1, 7610, 7587, 7611, -1, 7610, 7611, 7591, -1, 7610, 7590, 7587, -1, 7610, 7591, 7590, -1, 7612, 7605, 7607, -1, 7612, 7608, 7609, -1, 7612, 7609, 7605, -1, 7612, 7607, 7608, -1, 7613, 7614, 7615, -1, 7616, 7617, 7618, -1, 7619, 7620, 7621, -1, 7619, 7621, 7614, -1, 7619, 7613, 7622, -1, 7619, 7614, 7613, -1, 7623, 7624, 7620, -1, 7623, 7620, 7619, -1, 7625, 7622, 7626, -1, 7625, 7626, 7627, -1, 7625, 7619, 7622, -1, 7628, 7629, 7616, -1, 7628, 7618, 7624, -1, 7628, 7624, 7623, -1, 7628, 7616, 7618, -1, 7630, 7631, 7632, -1, 7630, 7627, 7633, -1, 7630, 7633, 7631, -1, 7630, 7625, 7627, -1, 7630, 7619, 7625, -1, 7630, 7623, 7619, -1, 7634, 7632, 7635, -1, 7634, 7635, 7636, -1, 7634, 7636, 7629, -1, 7634, 7623, 7630, -1, 7634, 7630, 7632, -1, 7634, 7629, 7628, -1, 7634, 7628, 7623, -1, 7637, 7638, 7639, -1, 7637, 7639, 7640, -1, 7641, 7637, 7640, -1, 7642, 7638, 7637, -1, 7643, 7641, 7640, -1, 7644, 7641, 7643, -1, 7645, 7642, 7637, -1, 7646, 7643, 7647, -1, 7646, 7644, 7643, -1, 7648, 7642, 7645, -1, 7649, 7650, 7651, -1, 7652, 7653, 7646, -1, 7652, 7646, 7647, -1, 7654, 7655, 7650, -1, 7656, 7655, 7654, -1, 7657, 7656, 7654, -1, 7658, 7653, 7652, -1, 7659, 7653, 7658, -1, 7660, 7657, 7661, -1, 7660, 7656, 7657, -1, 7662, 7659, 7658, -1, 7663, 7660, 7661, -1, 7664, 7665, 7659, -1, 7664, 7659, 7662, -1, 7666, 7665, 7664, -1, 7667, 7660, 7663, -1, 7649, 7654, 7650, -1, 7668, 7645, 7669, -1, 7668, 7669, 7649, -1, 7668, 7651, 7648, -1, 7668, 7649, 7651, -1, 7668, 7648, 7645, -1, 7670, 7663, 7665, -1, 7670, 7666, 7667, -1, 7670, 7667, 7663, -1, 7670, 7665, 7666, -1, 7671, 7672, 7673, -1, 7674, 7675, 7676, -1, 7677, 7678, 7679, -1, 7677, 7679, 7672, -1, 7677, 7671, 7680, -1, 7677, 7672, 7671, -1, 7681, 7682, 7678, -1, 7681, 7678, 7677, -1, 7683, 7680, 7684, -1, 7683, 7684, 7685, -1, 7683, 7677, 7680, -1, 7686, 7687, 7674, -1, 7686, 7676, 7682, -1, 7686, 7682, 7681, -1, 7686, 7674, 7676, -1, 7688, 7689, 7690, -1, 7688, 7685, 7691, -1, 7688, 7691, 7689, -1, 7688, 7683, 7685, -1, 7688, 7677, 7683, -1, 7688, 7681, 7677, -1, 7692, 7690, 7693, -1, 7692, 7693, 7694, -1, 7692, 7694, 7687, -1, 7692, 7681, 7688, -1, 7692, 7688, 7690, -1, 7692, 7687, 7686, -1, 7692, 7686, 7681, -1, 7695, 7696, 7697, -1, 7698, 7699, 7700, -1, 7701, 7697, 7702, -1, 7701, 7702, 7703, -1, 7701, 7704, 7695, -1, 7701, 7695, 7697, -1, 7705, 7703, 7699, -1, 7705, 7698, 7706, -1, 7705, 7706, 7704, -1, 7705, 7701, 7703, -1, 7705, 7699, 7698, -1, 7705, 7704, 7701, -1, 7707, 7708, 7709, -1, 7710, 7711, 7712, -1, 7713, 7711, 7710, -1, 7714, 7715, 7716, -1, 7714, 7716, 7717, -1, 7714, 7717, 7718, -1, 7719, 7720, 7715, -1, 7719, 7721, 7720, -1, 7719, 7715, 7714, -1, 7722, 7718, 7708, -1, 7722, 7707, 7723, -1, 7722, 7714, 7718, -1, 7722, 7708, 7707, -1, 7724, 7725, 7726, -1, 7724, 7726, 7727, -1, 7724, 7727, 7721, -1, 7724, 7721, 7719, -1, 7728, 7723, 7729, -1, 7728, 7722, 7723, -1, 7728, 7714, 7722, -1, 7728, 7719, 7714, -1, 7730, 7729, 7712, -1, 7730, 7711, 7725, -1, 7730, 7724, 7719, -1, 7730, 7728, 7729, -1, 7730, 7719, 7728, -1, 7730, 7712, 7711, -1, 7730, 7725, 7724, -1, 7731, 7732, 7733, -1, 7734, 7735, 7736, -1, 7737, 7735, 7734, -1, 7738, 7739, 7740, -1, 7738, 7740, 7741, -1, 7738, 7741, 7742, -1, 7743, 7744, 7739, -1, 7743, 7745, 7744, -1, 7743, 7739, 7738, -1, 7746, 7742, 7732, -1, 7746, 7731, 7747, -1, 7746, 7738, 7742, -1, 7746, 7732, 7731, -1, 7748, 7749, 7750, -1, 7748, 7750, 7751, -1, 7748, 7751, 7745, -1, 7748, 7745, 7743, -1, 7752, 7747, 7753, -1, 7752, 7746, 7747, -1, 7752, 7738, 7746, -1, 7752, 7743, 7738, -1, 7754, 7753, 7736, -1, 7754, 7735, 7749, -1, 7754, 7748, 7743, -1, 7754, 7752, 7753, -1, 7754, 7743, 7752, -1, 7754, 7736, 7735, -1, 7754, 7749, 7748, -1, 7755, 7756, 7757, -1, 7758, 7759, 7760, -1, 7761, 7758, 7760, -1, 7762, 7763, 7764, -1, 7762, 7764, 7765, -1, 7762, 7765, 7766, -1, 7767, 7768, 7769, -1, 7767, 7769, 7763, -1, 7767, 7763, 7762, -1, 7770, 7766, 7756, -1, 7770, 7755, 7771, -1, 7770, 7756, 7755, -1, 7770, 7762, 7766, -1, 7772, 7773, 7774, -1, 7772, 7774, 7775, -1, 7772, 7775, 7768, -1, 7772, 7768, 7767, -1, 7776, 7771, 7777, -1, 7776, 7770, 7771, -1, 7776, 7762, 7770, -1, 7776, 7767, 7762, -1, 7778, 7777, 7759, -1, 7778, 7758, 7773, -1, 7778, 7776, 7777, -1, 7778, 7772, 7767, -1, 7778, 7767, 7776, -1, 7778, 7759, 7758, -1, 7778, 7773, 7772, -1, 7779, 7780, 7781, -1, 7782, 7783, 7784, -1, 7785, 7783, 7782, -1, 7786, 7787, 7788, -1, 7786, 7788, 7789, -1, 7786, 7789, 7790, -1, 7791, 7792, 7793, -1, 7791, 7793, 7787, -1, 7791, 7787, 7786, -1, 7794, 7790, 7780, -1, 7794, 7779, 7795, -1, 7794, 7780, 7779, -1, 7794, 7786, 7790, -1, 7796, 7797, 7798, -1, 7796, 7798, 7799, -1, 7796, 7799, 7792, -1, 7796, 7792, 7791, -1, 7800, 7795, 7801, -1, 7800, 7794, 7795, -1, 7800, 7786, 7794, -1, 7800, 7791, 7786, -1, 7802, 7801, 7784, -1, 7802, 7783, 7797, -1, 7802, 7800, 7801, -1, 7802, 7796, 7791, -1, 7802, 7791, 7800, -1, 7802, 7784, 7783, -1, 7802, 7797, 7796, -1, 7803, 7804, 7805, -1, 7806, 7807, 7808, -1, 7809, 7810, 7811, -1, 7809, 7811, 7804, -1, 7809, 7803, 7812, -1, 7809, 7804, 7803, -1, 7813, 7814, 7810, -1, 7813, 7810, 7809, -1, 7815, 7812, 7816, -1, 7815, 7816, 7817, -1, 7815, 7809, 7812, -1, 7818, 7819, 7806, -1, 7818, 7808, 7814, -1, 7818, 7814, 7813, -1, 7818, 7806, 7808, -1, 7820, 7821, 7822, -1, 7820, 7817, 7823, -1, 7820, 7823, 7821, -1, 7820, 7815, 7817, -1, 7820, 7809, 7815, -1, 7820, 7813, 7809, -1, 7824, 7822, 7825, -1, 7824, 7825, 7826, -1, 7824, 7826, 7819, -1, 7824, 7813, 7820, -1, 7824, 7820, 7822, -1, 7824, 7819, 7818, -1, 7824, 7818, 7813, -1, 7827, 7828, 7829, -1, 7827, 7829, 7830, -1, 7831, 7827, 7830, -1, 7832, 7828, 7827, -1, 7833, 7831, 7830, -1, 7834, 7831, 7833, -1, 7835, 7832, 7827, -1, 7836, 7833, 7837, -1, 7836, 7834, 7833, -1, 7838, 7832, 7835, -1, 7839, 7840, 7841, -1, 7842, 7843, 7836, -1, 7842, 7836, 7837, -1, 7844, 7845, 7840, -1, 7846, 7845, 7844, -1, 7847, 7846, 7844, -1, 7848, 7843, 7842, -1, 7849, 7843, 7848, -1, 7850, 7847, 7851, -1, 7850, 7846, 7847, -1, 7852, 7849, 7848, -1, 7853, 7850, 7851, -1, 7854, 7855, 7849, -1, 7854, 7849, 7852, -1, 7856, 7855, 7854, -1, 7857, 7850, 7853, -1, 7839, 7844, 7840, -1, 7858, 7835, 7859, -1, 7858, 7859, 7839, -1, 7858, 7841, 7838, -1, 7858, 7839, 7841, -1, 7858, 7838, 7835, -1, 7860, 7853, 7855, -1, 7860, 7856, 7857, -1, 7860, 7857, 7853, -1, 7860, 7855, 7856, -1, 7861, 7862, 7863, -1, 7861, 7863, 7864, -1, 7865, 7861, 7864, -1, 7866, 7862, 7861, -1, 7867, 7865, 7864, -1, 7868, 7865, 7867, -1, 7869, 7866, 7861, -1, 7870, 7868, 7867, -1, 7871, 7870, 7867, -1, 7872, 7866, 7869, -1, 7873, 7874, 7875, -1, 7873, 7875, 7872, -1, 7876, 7877, 7870, -1, 7876, 7870, 7871, -1, 7878, 7879, 7874, -1, 7880, 7879, 7878, -1, 7881, 7880, 7878, -1, 7882, 7877, 7876, -1, 7883, 7877, 7882, -1, 7884, 7881, 7885, -1, 7884, 7880, 7881, -1, 7886, 7883, 7882, -1, 7887, 7884, 7885, -1, 7888, 7889, 7883, -1, 7888, 7883, 7886, -1, 7890, 7889, 7888, -1, 7891, 7884, 7887, -1, 7873, 7878, 7874, -1, 7892, 7869, 7893, -1, 7892, 7893, 7873, -1, 7892, 7872, 7869, -1, 7892, 7873, 7872, -1, 7894, 7887, 7889, -1, 7894, 7890, 7891, -1, 7894, 7891, 7887, -1, 7894, 7889, 7890, -1, 7895, 7896, 7897, -1, 7898, 7899, 7900, -1, 7901, 7902, 7903, -1, 7901, 7903, 7896, -1, 7901, 7895, 7904, -1, 7901, 7896, 7895, -1, 7905, 7906, 7902, -1, 7905, 7902, 7901, -1, 7907, 7904, 7908, -1, 7907, 7908, 7909, -1, 7907, 7901, 7904, -1, 7910, 7911, 7898, -1, 7910, 7900, 7906, -1, 7910, 7898, 7900, -1, 7910, 7906, 7905, -1, 7912, 7909, 7913, -1, 7912, 7913, 7914, -1, 7912, 7914, 7915, -1, 7912, 7907, 7909, -1, 7912, 7905, 7901, -1, 7912, 7901, 7907, -1, 7916, 7915, 7917, -1, 7916, 7917, 7918, -1, 7916, 7918, 7911, -1, 7916, 7912, 7915, -1, 7916, 7911, 7910, -1, 7916, 7910, 7905, -1, 7916, 7905, 7912, -1, 7919, 7920, 7921, -1, 7922, 7923, 7924, -1, 7925, 7926, 7927, -1, 7925, 7927, 7920, -1, 7925, 7919, 7928, -1, 7925, 7920, 7919, -1, 7929, 7930, 7926, -1, 7929, 7926, 7925, -1, 7931, 7928, 7932, -1, 7931, 7932, 7933, -1, 7931, 7925, 7928, -1, 7934, 7935, 7922, -1, 7934, 7924, 7930, -1, 7934, 7930, 7929, -1, 7934, 7922, 7924, -1, 7936, 7937, 7938, -1, 7936, 7933, 7939, -1, 7936, 7939, 7937, -1, 7936, 7931, 7933, -1, 7936, 7925, 7931, -1, 7936, 7929, 7925, -1, 7940, 7938, 7941, -1, 7940, 7941, 7942, -1, 7940, 7942, 7935, -1, 7940, 7929, 7936, -1, 7940, 7936, 7938, -1, 7940, 7935, 7934, -1, 7940, 7934, 7929, -1, 7943, 7944, 7945, -1, 7943, 7945, 7946, -1, 7947, 7943, 7946, -1, 7948, 7944, 7943, -1, 7949, 7947, 7946, -1, 7950, 7947, 7949, -1, 7951, 7948, 7943, -1, 7952, 7949, 7953, -1, 7952, 7950, 7949, -1, 7954, 7948, 7951, -1, 7955, 7956, 7957, -1, 7958, 7959, 7952, -1, 7958, 7952, 7953, -1, 7960, 7961, 7956, -1, 7962, 7961, 7960, -1, 7963, 7962, 7960, -1, 7964, 7959, 7958, -1, 7965, 7959, 7964, -1, 7966, 7963, 7967, -1, 7966, 7962, 7963, -1, 7968, 7965, 7964, -1, 7969, 7966, 7967, -1, 7970, 7971, 7965, -1, 7970, 7965, 7968, -1, 7972, 7971, 7970, -1, 7973, 7966, 7969, -1, 7955, 7960, 7956, -1, 7974, 7951, 7975, -1, 7974, 7975, 7955, -1, 7974, 7957, 7954, -1, 7974, 7955, 7957, -1, 7974, 7954, 7951, -1, 7976, 7969, 7971, -1, 7976, 7972, 7973, -1, 7976, 7973, 7969, -1, 7976, 7971, 7972, -1, 7977, 7978, 7979, -1, 7977, 7979, 7980, -1, 7981, 7977, 7980, -1, 7982, 7978, 7977, -1, 7983, 7981, 7980, -1, 7984, 7981, 7983, -1, 7985, 7982, 7977, -1, 7986, 7984, 7983, -1, 7987, 7986, 7983, -1, 7988, 7982, 7985, -1, 7989, 7990, 7991, -1, 7989, 7991, 7988, -1, 7992, 7993, 7986, -1, 7992, 7986, 7987, -1, 7994, 7995, 7990, -1, 7996, 7995, 7994, -1, 7997, 7996, 7994, -1, 7998, 7993, 7992, -1, 7999, 7993, 7998, -1, 8000, 7997, 8001, -1, 8000, 7996, 7997, -1, 8002, 7999, 7998, -1, 8003, 8000, 8001, -1, 8004, 8005, 7999, -1, 8004, 7999, 8002, -1, 8006, 8005, 8004, -1, 8007, 8000, 8003, -1, 7989, 7994, 7990, -1, 8008, 7985, 8009, -1, 8008, 8009, 7989, -1, 8008, 7988, 7985, -1, 8008, 7989, 7988, -1, 8010, 8003, 8005, -1, 8010, 8006, 8007, -1, 8010, 8007, 8003, -1, 8010, 8005, 8006, -1, 8011, 8012, 8013, -1, 8014, 8015, 8016, -1, 8017, 8018, 8019, -1, 8017, 8019, 8012, -1, 8017, 8011, 8020, -1, 8017, 8012, 8011, -1, 8021, 8022, 8018, -1, 8021, 8018, 8017, -1, 8023, 8020, 8024, -1, 8023, 8024, 8025, -1, 8023, 8017, 8020, -1, 8026, 8027, 8014, -1, 8026, 8016, 8022, -1, 8026, 8022, 8021, -1, 8026, 8014, 8016, -1, 8028, 8029, 8030, -1, 8028, 8025, 8031, -1, 8028, 8031, 8029, -1, 8028, 8023, 8025, -1, 8028, 8017, 8023, -1, 8028, 8021, 8017, -1, 8032, 8030, 8033, -1, 8032, 8033, 8034, -1, 8032, 8034, 8027, -1, 8032, 8021, 8028, -1, 8032, 8028, 8030, -1, 8032, 8027, 8026, -1, 8032, 8026, 8021, -1, 8035, 8036, 8037, -1, 8038, 8039, 8040, -1, 8041, 8042, 8043, -1, 8041, 8043, 8035, -1, 8041, 8037, 8044, -1, 8041, 8035, 8037, -1, 8045, 8046, 8040, -1, 8045, 8039, 8042, -1, 8045, 8044, 8046, -1, 8045, 8041, 8044, -1, 8045, 8042, 8041, -1, 8045, 8040, 8039, -1, 8047, 8048, 8049, -1, 8050, 8051, 8052, -1, 8053, 8051, 8050, -1, 8054, 8055, 8056, -1, 8054, 8056, 8057, -1, 8054, 8057, 8058, -1, 8059, 8060, 8055, -1, 8059, 8061, 8060, -1, 8059, 8055, 8054, -1, 8062, 8058, 8048, -1, 8062, 8047, 8063, -1, 8062, 8054, 8058, -1, 8062, 8048, 8047, -1, 8064, 8065, 8066, -1, 8064, 8066, 8067, -1, 8064, 8067, 8061, -1, 8064, 8061, 8059, -1, 8068, 8063, 8069, -1, 8068, 8062, 8063, -1, 8068, 8054, 8062, -1, 8068, 8059, 8054, -1, 8070, 8069, 8052, -1, 8070, 8051, 8065, -1, 8070, 8064, 8059, -1, 8070, 8068, 8069, -1, 8070, 8059, 8068, -1, 8070, 8052, 8051, -1, 8070, 8065, 8064, -1, 8071, 8072, 8073, -1, 8074, 8075, 8076, -1, 8077, 8075, 8074, -1, 8078, 8079, 8080, -1, 8078, 8080, 8081, -1, 8078, 8081, 8082, -1, 8083, 8084, 8079, -1, 8083, 8085, 8084, -1, 8083, 8079, 8078, -1, 8086, 8082, 8072, -1, 8086, 8071, 8087, -1, 8086, 8078, 8082, -1, 8086, 8072, 8071, -1, 8088, 8089, 8090, -1, 8088, 8090, 8091, -1, 8088, 8091, 8085, -1, 8088, 8085, 8083, -1, 8092, 8087, 8093, -1, 8092, 8086, 8087, -1, 8092, 8078, 8086, -1, 8092, 8083, 8078, -1, 8094, 8093, 8076, -1, 8094, 8075, 8089, -1, 8094, 8088, 8083, -1, 8094, 8092, 8093, -1, 8094, 8083, 8092, -1, 8094, 8076, 8075, -1, 8094, 8089, 8088, -1, 8095, 8096, 8097, -1, 8098, 8099, 8100, -1, 8101, 8098, 8100, -1, 8102, 8103, 8104, -1, 8102, 8104, 8105, -1, 8102, 8105, 8106, -1, 8107, 8108, 8109, -1, 8107, 8109, 8103, -1, 8107, 8103, 8102, -1, 8110, 8106, 8096, -1, 8110, 8095, 8111, -1, 8110, 8096, 8095, -1, 8110, 8102, 8106, -1, 8112, 8113, 8114, -1, 8112, 8114, 8115, -1, 8112, 8115, 8108, -1, 8112, 8108, 8107, -1, 8116, 8111, 8117, -1, 8116, 8110, 8111, -1, 8116, 8102, 8110, -1, 8116, 8107, 8102, -1, 8118, 8117, 8099, -1, 8118, 8098, 8113, -1, 8118, 8116, 8117, -1, 8118, 8112, 8107, -1, 8118, 8107, 8116, -1, 8118, 8099, 8098, -1, 8118, 8113, 8112, -1, 8119, 8120, 8121, -1, 8122, 8123, 8124, -1, 8125, 8123, 8122, -1, 8126, 8127, 8128, -1, 8126, 8128, 8129, -1, 8126, 8129, 8130, -1, 8131, 8132, 8127, -1, 8131, 8133, 8132, -1, 8131, 8127, 8126, -1, 8134, 8130, 8120, -1, 8134, 8119, 8135, -1, 8134, 8126, 8130, -1, 8134, 8120, 8119, -1, 8136, 8137, 8138, -1, 8136, 8138, 8139, -1, 8136, 8139, 8133, -1, 8136, 8133, 8131, -1, 8140, 8135, 8141, -1, 8140, 8134, 8135, -1, 8140, 8126, 8134, -1, 8140, 8131, 8126, -1, 8142, 8141, 8124, -1, 8142, 8123, 8137, -1, 8142, 8136, 8131, -1, 8142, 8140, 8141, -1, 8142, 8131, 8140, -1, 8142, 8124, 8123, -1, 8142, 8137, 8136, -1, 8143, 8144, 8145, -1, 8143, 8145, 8146, -1, 8147, 8143, 8146, -1, 8148, 8144, 8143, -1, 8149, 8147, 8146, -1, 8150, 8147, 8149, -1, 8151, 8148, 8143, -1, 8152, 8150, 8149, -1, 8153, 8152, 8149, -1, 8154, 8148, 8151, -1, 8155, 8156, 8157, -1, 8155, 8157, 8154, -1, 8158, 8159, 8152, -1, 8158, 8152, 8153, -1, 8160, 8161, 8156, -1, 8162, 8161, 8160, -1, 8163, 8162, 8160, -1, 8164, 8159, 8158, -1, 8165, 8159, 8164, -1, 8166, 8163, 8167, -1, 8166, 8162, 8163, -1, 8168, 8165, 8164, -1, 8169, 8166, 8167, -1, 8170, 8171, 8165, -1, 8170, 8165, 8168, -1, 8172, 8171, 8170, -1, 8173, 8166, 8169, -1, 8155, 8160, 8156, -1, 8174, 8151, 8175, -1, 8174, 8175, 8155, -1, 8174, 8154, 8151, -1, 8174, 8155, 8154, -1, 8176, 8169, 8171, -1, 8176, 8172, 8173, -1, 8176, 8173, 8169, -1, 8176, 8171, 8172, -1, 8177, 8178, 8179, -1, 8180, 8181, 8182, -1, 8183, 8184, 8185, -1, 8183, 8185, 8178, -1, 8183, 8177, 8186, -1, 8183, 8178, 8177, -1, 8187, 8188, 8184, -1, 8187, 8184, 8183, -1, 8189, 8186, 8190, -1, 8189, 8190, 8191, -1, 8189, 8183, 8186, -1, 8192, 8193, 8180, -1, 8192, 8182, 8188, -1, 8192, 8188, 8187, -1, 8192, 8180, 8182, -1, 8194, 8195, 8196, -1, 8194, 8191, 8197, -1, 8194, 8197, 8195, -1, 8194, 8189, 8191, -1, 8194, 8183, 8189, -1, 8194, 8187, 8183, -1, 8198, 8196, 8199, -1, 8198, 8199, 8200, -1, 8198, 8200, 8193, -1, 8198, 8187, 8194, -1, 8198, 8194, 8196, -1, 8198, 8193, 8192, -1, 8198, 8192, 8187, -1, 8201, 8202, 8203, -1, 8201, 8203, 8204, -1, 8205, 8201, 8204, -1, 8206, 8202, 8201, -1, 8207, 8205, 8204, -1, 8208, 8205, 8207, -1, 8209, 8206, 8201, -1, 8210, 8207, 8211, -1, 8210, 8208, 8207, -1, 8212, 8206, 8209, -1, 8213, 8214, 8215, -1, 8216, 8217, 8210, -1, 8216, 8210, 8211, -1, 8218, 8219, 8214, -1, 8220, 8219, 8218, -1, 8221, 8220, 8218, -1, 8222, 8217, 8216, -1, 8223, 8217, 8222, -1, 8224, 8221, 8225, -1, 8224, 8220, 8221, -1, 8226, 8223, 8222, -1, 8227, 8224, 8225, -1, 8228, 8229, 8223, -1, 8228, 8223, 8226, -1, 8230, 8229, 8228, -1, 8231, 8224, 8227, -1, 8213, 8218, 8214, -1, 8232, 8209, 8233, -1, 8232, 8233, 8213, -1, 8232, 8215, 8212, -1, 8232, 8213, 8215, -1, 8232, 8212, 8209, -1, 8234, 8227, 8229, -1, 8234, 8230, 8231, -1, 8234, 8231, 8227, -1, 8234, 8229, 8230, -1, 8235, 8236, 8237, -1, 8238, 8239, 8240, -1, 8241, 8242, 8243, -1, 8241, 8243, 8236, -1, 8241, 8235, 8244, -1, 8241, 8236, 8235, -1, 8245, 8246, 8242, -1, 8245, 8242, 8241, -1, 8247, 8244, 8248, -1, 8247, 8248, 8249, -1, 8247, 8241, 8244, -1, 8250, 8251, 8238, -1, 8250, 8240, 8246, -1, 8250, 8246, 8245, -1, 8250, 8238, 8240, -1, 8252, 8253, 8254, -1, 8252, 8249, 8255, -1, 8252, 8255, 8253, -1, 8252, 8247, 8249, -1, 8252, 8241, 8247, -1, 8252, 8245, 8241, -1, 8256, 8254, 8257, -1, 8256, 8257, 8258, -1, 8256, 8258, 8251, -1, 8256, 8245, 8252, -1, 8256, 8252, 8254, -1, 8256, 8251, 8250, -1, 8256, 8250, 8245, -1, 8259, 8260, 8261, -1, 8262, 8263, 8264, -1, 8265, 8263, 8262, -1, 8266, 8267, 8268, -1, 8266, 8268, 8269, -1, 8266, 8269, 8270, -1, 8271, 8272, 8267, -1, 8271, 8273, 8272, -1, 8271, 8267, 8266, -1, 8274, 8270, 8260, -1, 8274, 8259, 8275, -1, 8274, 8266, 8270, -1, 8274, 8260, 8259, -1, 8276, 8277, 8278, -1, 8276, 8278, 8279, -1, 8276, 8279, 8273, -1, 8276, 8273, 8271, -1, 8280, 8275, 8281, -1, 8280, 8274, 8275, -1, 8280, 8266, 8274, -1, 8280, 8271, 8266, -1, 8282, 8281, 8264, -1, 8282, 8263, 8277, -1, 8282, 8276, 8271, -1, 8282, 8280, 8281, -1, 8282, 8271, 8280, -1, 8282, 8264, 8263, -1, 8282, 8277, 8276, -1, 8283, 8284, 8285, -1, 8286, 8287, 8288, -1, 8289, 8287, 8286, -1, 8290, 8291, 8292, -1, 8290, 8292, 8293, -1, 8290, 8293, 8294, -1, 8295, 8296, 8297, -1, 8295, 8297, 8291, -1, 8295, 8291, 8290, -1, 8298, 8294, 8284, -1, 8298, 8283, 8299, -1, 8298, 8284, 8283, -1, 8298, 8290, 8294, -1, 8300, 8301, 8302, -1, 8300, 8302, 8303, -1, 8300, 8303, 8296, -1, 8300, 8296, 8295, -1, 8304, 8299, 8305, -1, 8304, 8298, 8299, -1, 8304, 8290, 8298, -1, 8304, 8295, 8290, -1, 8306, 8305, 8288, -1, 8306, 8287, 8301, -1, 8306, 8304, 8305, -1, 8306, 8300, 8295, -1, 8306, 8295, 8304, -1, 8306, 8288, 8287, -1, 8306, 8301, 8300, -1, 8307, 8308, 8309, -1, 8310, 8311, 8312, -1, 8313, 8311, 8310, -1, 8314, 8315, 8316, -1, 8314, 8316, 8317, -1, 8314, 8317, 8318, -1, 8319, 8320, 8315, -1, 8319, 8321, 8320, -1, 8319, 8315, 8314, -1, 8322, 8318, 8308, -1, 8322, 8307, 8323, -1, 8322, 8314, 8318, -1, 8322, 8308, 8307, -1, 8324, 8325, 8326, -1, 8324, 8326, 8327, -1, 8324, 8327, 8321, -1, 8324, 8321, 8319, -1, 8328, 8323, 8329, -1, 8328, 8322, 8323, -1, 8328, 8314, 8322, -1, 8328, 8319, 8314, -1, 8330, 8329, 8312, -1, 8330, 8311, 8325, -1, 8330, 8324, 8319, -1, 8330, 8328, 8329, -1, 8330, 8319, 8328, -1, 8330, 8312, 8311, -1, 8330, 8325, 8324, -1, 8331, 8332, 8333, -1, 8334, 8335, 8336, -1, 8337, 8334, 8336, -1, 8338, 8339, 8340, -1, 8338, 8340, 8341, -1, 8338, 8341, 8342, -1, 8343, 8344, 8339, -1, 8343, 8345, 8344, -1, 8343, 8339, 8338, -1, 8346, 8342, 8332, -1, 8346, 8331, 8347, -1, 8346, 8338, 8342, -1, 8346, 8332, 8331, -1, 8348, 8349, 8350, -1, 8348, 8350, 8351, -1, 8348, 8351, 8345, -1, 8348, 8345, 8343, -1, 8352, 8347, 8353, -1, 8352, 8346, 8347, -1, 8352, 8338, 8346, -1, 8352, 8343, 8338, -1, 8354, 8353, 8335, -1, 8354, 8334, 8349, -1, 8354, 8348, 8343, -1, 8354, 8352, 8353, -1, 8354, 8343, 8352, -1, 8354, 8335, 8334, -1, 8354, 8349, 8348, -1, 8355, 8356, 8357, -1, 8358, 8359, 8360, -1, 8361, 8357, 8362, -1, 8361, 8362, 8363, -1, 8361, 8364, 8355, -1, 8361, 8355, 8357, -1, 8365, 8363, 8359, -1, 8365, 8358, 8366, -1, 8365, 8366, 8364, -1, 8365, 8361, 8363, -1, 8365, 8359, 8358, -1, 8365, 8364, 8361, -1, 8367, 8368, 8369, -1, 8367, 8369, 8370, -1, 8371, 8367, 8370, -1, 8372, 8368, 8367, -1, 8373, 8371, 8370, -1, 8374, 8371, 8373, -1, 8375, 8372, 8367, -1, 8376, 8373, 8377, -1, 8376, 8374, 8373, -1, 8378, 8372, 8375, -1, 8379, 8380, 8381, -1, 8382, 8383, 8376, -1, 8382, 8376, 8377, -1, 8384, 8385, 8380, -1, 8386, 8385, 8384, -1, 8387, 8386, 8384, -1, 8388, 8383, 8382, -1, 8389, 8383, 8388, -1, 8390, 8387, 8391, -1, 8390, 8386, 8387, -1, 8392, 8389, 8388, -1, 8393, 8390, 8391, -1, 8394, 8395, 8389, -1, 8394, 8389, 8392, -1, 8396, 8395, 8394, -1, 8397, 8390, 8393, -1, 8379, 8384, 8380, -1, 8398, 8375, 8399, -1, 8398, 8399, 8379, -1, 8398, 8381, 8378, -1, 8398, 8379, 8381, -1, 8398, 8378, 8375, -1, 8400, 8393, 8395, -1, 8400, 8396, 8397, -1, 8400, 8397, 8393, -1, 8400, 8395, 8396, -1, 8401, 8402, 8403, -1, 8404, 8405, 8406, -1, 8407, 8408, 8409, -1, 8407, 8409, 8402, -1, 8407, 8401, 8410, -1, 8407, 8402, 8401, -1, 8411, 8412, 8408, -1, 8411, 8408, 8407, -1, 8413, 8410, 8414, -1, 8413, 8414, 8415, -1, 8413, 8407, 8410, -1, 8416, 8417, 8404, -1, 8416, 8406, 8412, -1, 8416, 8404, 8406, -1, 8416, 8412, 8411, -1, 8418, 8415, 8419, -1, 8418, 8419, 8420, -1, 8418, 8420, 8421, -1, 8418, 8413, 8415, -1, 8418, 8411, 8407, -1, 8418, 8407, 8413, -1, 8422, 8421, 8423, -1, 8422, 8423, 8424, -1, 8422, 8424, 8417, -1, 8422, 8418, 8421, -1, 8422, 8417, 8416, -1, 8422, 8416, 8411, -1, 8422, 8411, 8418, -1, 8425, 8426, 8427, -1, 8425, 8427, 8428, -1, 8429, 8425, 8428, -1, 8430, 8426, 8425, -1, 8431, 8429, 8428, -1, 8432, 8429, 8431, -1, 8433, 8430, 8425, -1, 8434, 8432, 8431, -1, 8435, 8434, 8431, -1, 8436, 8430, 8433, -1, 8437, 8438, 8439, -1, 8437, 8439, 8436, -1, 8440, 8441, 8434, -1, 8440, 8434, 8435, -1, 8442, 8443, 8438, -1, 8444, 8443, 8442, -1, 8445, 8444, 8442, -1, 8446, 8441, 8440, -1, 8447, 8441, 8446, -1, 8448, 8445, 8449, -1, 8448, 8444, 8445, -1, 8450, 8447, 8446, -1, 8451, 8448, 8449, -1, 8452, 8453, 8447, -1, 8452, 8447, 8450, -1, 8454, 8453, 8452, -1, 8455, 8448, 8451, -1, 8437, 8442, 8438, -1, 8456, 8433, 8457, -1, 8456, 8457, 8437, -1, 8456, 8436, 8433, -1, 8456, 8437, 8436, -1, 8458, 8451, 8453, -1, 8458, 8454, 8455, -1, 8458, 8455, 8451, -1, 8458, 8453, 8454, -1, 8459, 8460, 8461, -1, 8462, 8463, 8464, -1, 8465, 8466, 8467, -1, 8465, 8467, 8460, -1, 8465, 8459, 8468, -1, 8465, 8460, 8459, -1, 8469, 8470, 8466, -1, 8469, 8466, 8465, -1, 8471, 8468, 8472, -1, 8471, 8472, 8473, -1, 8471, 8465, 8468, -1, 8474, 8475, 8462, -1, 8474, 8464, 8470, -1, 8474, 8470, 8469, -1, 8474, 8462, 8464, -1, 8476, 8473, 8477, -1, 8476, 8477, 8478, -1, 8476, 8478, 8479, -1, 8476, 8471, 8473, -1, 8476, 8465, 8471, -1, 8476, 8469, 8465, -1, 8480, 8479, 8481, -1, 8480, 8481, 8482, -1, 8480, 8482, 8475, -1, 8480, 8475, 8474, -1, 8480, 8476, 8479, -1, 8480, 8474, 8469, -1, 8480, 8469, 8476, -1, 8483, 8484, 8485, -1, 8486, 8487, 8488, -1, 8489, 8487, 8486, -1, 8490, 8491, 8492, -1, 8490, 8492, 8493, -1, 8490, 8493, 8494, -1, 8495, 8496, 8491, -1, 8495, 8497, 8496, -1, 8495, 8491, 8490, -1, 8498, 8494, 8484, -1, 8498, 8483, 8499, -1, 8498, 8490, 8494, -1, 8498, 8484, 8483, -1, 8500, 8501, 8502, -1, 8500, 8502, 8503, -1, 8500, 8503, 8497, -1, 8500, 8497, 8495, -1, 8504, 8499, 8505, -1, 8504, 8498, 8499, -1, 8504, 8490, 8498, -1, 8504, 8495, 8490, -1, 8506, 8505, 8488, -1, 8506, 8487, 8501, -1, 8506, 8500, 8495, -1, 8506, 8504, 8505, -1, 8506, 8495, 8504, -1, 8506, 8488, 8487, -1, 8506, 8501, 8500, -1, 8507, 8508, 8509, -1, 8510, 8511, 8512, -1, 8513, 8511, 8510, -1, 8514, 8515, 8516, -1, 8514, 8516, 8517, -1, 8514, 8517, 8518, -1, 8519, 8520, 8521, -1, 8519, 8521, 8515, -1, 8519, 8515, 8514, -1, 8522, 8518, 8508, -1, 8522, 8507, 8523, -1, 8522, 8508, 8507, -1, 8522, 8514, 8518, -1, 8524, 8525, 8526, -1, 8524, 8526, 8527, -1, 8524, 8527, 8520, -1, 8524, 8520, 8519, -1, 8528, 8523, 8529, -1, 8528, 8522, 8523, -1, 8528, 8514, 8522, -1, 8528, 8519, 8514, -1, 8530, 8529, 8512, -1, 8530, 8511, 8525, -1, 8530, 8528, 8529, -1, 8530, 8524, 8519, -1, 8530, 8519, 8528, -1, 8530, 8512, 8511, -1, 8530, 8525, 8524, -1, 8531, 8532, 8533, -1, 8534, 8535, 8536, -1, 8537, 8535, 8534, -1, 8538, 8539, 8540, -1, 8538, 8540, 8541, -1, 8538, 8541, 8542, -1, 8543, 8544, 8545, -1, 8543, 8545, 8539, -1, 8543, 8539, 8538, -1, 8546, 8542, 8532, -1, 8546, 8531, 8547, -1, 8546, 8532, 8531, -1, 8546, 8538, 8542, -1, 8548, 8549, 8550, -1, 8548, 8550, 8551, -1, 8548, 8551, 8544, -1, 8548, 8544, 8543, -1, 8552, 8547, 8553, -1, 8552, 8546, 8547, -1, 8552, 8538, 8546, -1, 8552, 8543, 8538, -1, 8554, 8553, 8536, -1, 8554, 8535, 8549, -1, 8554, 8552, 8553, -1, 8554, 8548, 8543, -1, 8554, 8543, 8552, -1, 8554, 8536, 8535, -1, 8554, 8549, 8548, -1, 8555, 8556, 8557, -1, 8558, 8559, 8560, -1, 8561, 8557, 8562, -1, 8561, 8562, 8563, -1, 8561, 8564, 8555, -1, 8561, 8555, 8557, -1, 8565, 8563, 8559, -1, 8565, 8558, 8566, -1, 8565, 8566, 8564, -1, 8565, 8561, 8563, -1, 8565, 8564, 8561, -1, 8565, 8559, 8558, -1, 8567, 8568, 8569, -1, 8570, 8571, 8572, -1, 8573, 8570, 8572, -1, 8574, 8575, 8576, -1, 8574, 8576, 8577, -1, 8574, 8577, 8578, -1, 8579, 8580, 8581, -1, 8579, 8581, 8575, -1, 8579, 8575, 8574, -1, 8582, 8578, 8568, -1, 8582, 8567, 8583, -1, 8582, 8568, 8567, -1, 8582, 8574, 8578, -1, 8584, 8585, 8586, -1, 8584, 8586, 8587, -1, 8584, 8587, 8580, -1, 8584, 8580, 8579, -1, 8588, 8583, 8589, -1, 8588, 8582, 8583, -1, 8588, 8574, 8582, -1, 8588, 8579, 8574, -1, 8590, 8589, 8571, -1, 8590, 8570, 8585, -1, 8590, 8588, 8589, -1, 8590, 8584, 8579, -1, 8590, 8579, 8588, -1, 8590, 8571, 8570, -1, 8590, 8585, 8584, -1, 8591, 8592, 8593, -1, 8591, 8593, 8594, -1, 8595, 8591, 8594, -1, 8596, 8592, 8591, -1, 8597, 8595, 8594, -1, 8598, 8595, 8597, -1, 8599, 8596, 8591, -1, 8600, 8598, 8597, -1, 8601, 8600, 8597, -1, 8602, 8596, 8599, -1, 8603, 8604, 8605, -1, 8603, 8605, 8602, -1, 8606, 8607, 8600, -1, 8606, 8600, 8601, -1, 8608, 8609, 8604, -1, 8610, 8609, 8608, -1, 8611, 8610, 8608, -1, 8612, 8607, 8606, -1, 8613, 8607, 8612, -1, 8614, 8611, 8615, -1, 8614, 8610, 8611, -1, 8616, 8613, 8612, -1, 8617, 8614, 8615, -1, 8618, 8619, 8613, -1, 8618, 8613, 8616, -1, 8620, 8619, 8618, -1, 8621, 8614, 8617, -1, 8603, 8608, 8604, -1, 8622, 8599, 8623, -1, 8622, 8623, 8603, -1, 8622, 8602, 8599, -1, 8622, 8603, 8602, -1, 8624, 8617, 8619, -1, 8624, 8620, 8621, -1, 8624, 8621, 8617, -1, 8624, 8619, 8620, -1, 8625, 8626, 8627, -1, 8628, 8629, 8630, -1, 8631, 8632, 8633, -1, 8631, 8633, 8626, -1, 8631, 8625, 8634, -1, 8631, 8626, 8625, -1, 8635, 8636, 8632, -1, 8635, 8632, 8631, -1, 8637, 8634, 8638, -1, 8637, 8638, 8639, -1, 8637, 8631, 8634, -1, 8640, 8641, 8628, -1, 8640, 8630, 8636, -1, 8640, 8636, 8635, -1, 8640, 8628, 8630, -1, 8642, 8643, 8644, -1, 8642, 8639, 8645, -1, 8642, 8645, 8643, -1, 8642, 8637, 8639, -1, 8642, 8631, 8637, -1, 8642, 8635, 8631, -1, 8646, 8644, 8647, -1, 8646, 8647, 8648, -1, 8646, 8648, 8641, -1, 8646, 8635, 8642, -1, 8646, 8642, 8644, -1, 8646, 8641, 8640, -1, 8646, 8640, 8635, -1, 8649, 8650, 8651, -1, 8649, 8651, 8652, -1, 8653, 8649, 8652, -1, 8654, 8650, 8649, -1, 8655, 8653, 8652, -1, 8656, 8653, 8655, -1, 8657, 8654, 8649, -1, 8658, 8655, 8659, -1, 8658, 8656, 8655, -1, 8660, 8654, 8657, -1, 8661, 8662, 8663, -1, 8664, 8665, 8658, -1, 8664, 8658, 8659, -1, 8666, 8667, 8662, -1, 8668, 8667, 8666, -1, 8669, 8668, 8666, -1, 8670, 8665, 8664, -1, 8671, 8665, 8670, -1, 8672, 8669, 8673, -1, 8672, 8668, 8669, -1, 8674, 8671, 8670, -1, 8675, 8672, 8673, -1, 8676, 8677, 8671, -1, 8676, 8671, 8674, -1, 8678, 8677, 8676, -1, 8679, 8672, 8675, -1, 8661, 8666, 8662, -1, 8680, 8657, 8681, -1, 8680, 8681, 8661, -1, 8680, 8663, 8660, -1, 8680, 8661, 8663, -1, 8680, 8660, 8657, -1, 8682, 8675, 8677, -1, 8682, 8678, 8679, -1, 8682, 8679, 8675, -1, 8682, 8677, 8678, -1, 8683, 8684, 8685, -1, 8686, 8687, 8688, -1, 8689, 8690, 8691, -1, 8689, 8691, 8684, -1, 8689, 8683, 8692, -1, 8689, 8684, 8683, -1, 8693, 8694, 8690, -1, 8693, 8690, 8689, -1, 8695, 8692, 8696, -1, 8695, 8696, 8697, -1, 8695, 8689, 8692, -1, 8698, 8699, 8686, -1, 8698, 8688, 8694, -1, 8698, 8694, 8693, -1, 8698, 8686, 8688, -1, 8700, 8701, 8702, -1, 8700, 8697, 8703, -1, 8700, 8703, 8701, -1, 8700, 8695, 8697, -1, 8700, 8689, 8695, -1, 8700, 8693, 8689, -1, 8704, 8702, 8705, -1, 8704, 8705, 8706, -1, 8704, 8706, 8699, -1, 8704, 8693, 8700, -1, 8704, 8700, 8702, -1, 8704, 8699, 8698, -1, 8704, 8698, 8693, -1, 8707, 8708, 8709, -1, 8710, 8711, 8712, -1, 8713, 8714, 8715, -1, 8713, 8715, 8707, -1, 8713, 8709, 8716, -1, 8713, 8707, 8709, -1, 8717, 8718, 8712, -1, 8717, 8711, 8714, -1, 8717, 8716, 8718, -1, 8717, 8713, 8716, -1, 8717, 8714, 8713, -1, 8717, 8712, 8711, -1, 8719, 8720, 8721, -1, 8722, 8723, 8724, -1, 8725, 8723, 8722, -1, 8726, 8727, 8728, -1, 8726, 8728, 8729, -1, 8726, 8729, 8730, -1, 8731, 8732, 8727, -1, 8731, 8733, 8732, -1, 8731, 8727, 8726, -1, 8734, 8730, 8720, -1, 8734, 8719, 8735, -1, 8734, 8726, 8730, -1, 8734, 8720, 8719, -1, 8736, 8737, 8738, -1, 8736, 8738, 8739, -1, 8736, 8739, 8733, -1, 8736, 8733, 8731, -1, 8740, 8735, 8741, -1, 8740, 8734, 8735, -1, 8740, 8726, 8734, -1, 8740, 8731, 8726, -1, 8742, 8741, 8724, -1, 8742, 8723, 8737, -1, 8742, 8736, 8731, -1, 8742, 8740, 8741, -1, 8742, 8731, 8740, -1, 8742, 8724, 8723, -1, 8742, 8737, 8736, -1, 8743, 8744, 8745, -1, 8746, 8747, 8748, -1, 8749, 8747, 8746, -1, 8750, 8751, 8752, -1, 8750, 8752, 8753, -1, 8750, 8753, 8754, -1, 8755, 8756, 8757, -1, 8755, 8757, 8751, -1, 8755, 8751, 8750, -1, 8758, 8754, 8744, -1, 8758, 8743, 8759, -1, 8758, 8744, 8743, -1, 8758, 8750, 8754, -1, 8760, 8761, 8762, -1, 8760, 8762, 8763, -1, 8760, 8763, 8756, -1, 8760, 8756, 8755, -1, 8764, 8759, 8765, -1, 8764, 8758, 8759, -1, 8764, 8750, 8758, -1, 8764, 8755, 8750, -1, 8766, 8765, 8748, -1, 8766, 8747, 8761, -1, 8766, 8764, 8765, -1, 8766, 8760, 8755, -1, 8766, 8755, 8764, -1, 8766, 8748, 8747, -1, 8766, 8761, 8760, -1, 8767, 8768, 8769, -1, 8770, 8771, 8772, -1, 8773, 8771, 8770, -1, 8774, 8775, 8776, -1, 8774, 8776, 8777, -1, 8774, 8777, 8778, -1, 8779, 8780, 8775, -1, 8779, 8781, 8780, -1, 8779, 8775, 8774, -1, 8782, 8778, 8768, -1, 8782, 8767, 8783, -1, 8782, 8774, 8778, -1, 8782, 8768, 8767, -1, 8784, 8785, 8786, -1, 8784, 8786, 8787, -1, 8784, 8787, 8781, -1, 8784, 8781, 8779, -1, 8788, 8783, 8789, -1, 8788, 8782, 8783, -1, 8788, 8774, 8782, -1, 8788, 8779, 8774, -1, 8790, 8789, 8772, -1, 8790, 8771, 8785, -1, 8790, 8784, 8779, -1, 8790, 8788, 8789, -1, 8790, 8779, 8788, -1, 8790, 8772, 8771, -1, 8790, 8785, 8784, -1, 8791, 8792, 8793, -1, 8794, 8795, 8796, -1, 8797, 8794, 8796, -1, 8798, 8799, 8800, -1, 8798, 8800, 8801, -1, 8798, 8801, 8802, -1, 8803, 8804, 8799, -1, 8803, 8805, 8804, -1, 8803, 8799, 8798, -1, 8806, 8802, 8792, -1, 8806, 8791, 8807, -1, 8806, 8798, 8802, -1, 8806, 8792, 8791, -1, 8808, 8809, 8810, -1, 8808, 8810, 8811, -1, 8808, 8811, 8805, -1, 8808, 8805, 8803, -1, 8812, 8807, 8813, -1, 8812, 8806, 8807, -1, 8812, 8798, 8806, -1, 8812, 8803, 8798, -1, 8814, 8813, 8795, -1, 8814, 8794, 8809, -1, 8814, 8808, 8803, -1, 8814, 8812, 8813, -1, 8814, 8803, 8812, -1, 8814, 8795, 8794, -1, 8814, 8809, 8808, -1, 8815, 8816, 8817, -1, 8815, 8817, 8818, -1, 8819, 8815, 8818, -1, 8820, 8816, 8815, -1, 8821, 8819, 8818, -1, 8822, 8819, 8821, -1, 8823, 8820, 8815, -1, 8824, 8822, 8821, -1, 8825, 8824, 8821, -1, 8826, 8820, 8823, -1, 8827, 8828, 8829, -1, 8827, 8829, 8826, -1, 8830, 8831, 8824, -1, 8830, 8824, 8825, -1, 8832, 8833, 8828, -1, 8834, 8833, 8832, -1, 8835, 8834, 8832, -1, 8836, 8831, 8830, -1, 8837, 8831, 8836, -1, 8838, 8835, 8839, -1, 8838, 8834, 8835, -1, 8840, 8837, 8836, -1, 8841, 8838, 8839, -1, 8842, 8843, 8837, -1, 8842, 8837, 8840, -1, 8844, 8843, 8842, -1, 8845, 8838, 8841, -1, 8827, 8832, 8828, -1, 8846, 8823, 8847, -1, 8846, 8847, 8827, -1, 8846, 8826, 8823, -1, 8846, 8827, 8826, -1, 8848, 8841, 8843, -1, 8848, 8844, 8845, -1, 8848, 8845, 8841, -1, 8848, 8843, 8844, -1, 8849, 8850, 8851, -1, 8852, 8853, 8854, -1, 8855, 8856, 8857, -1, 8855, 8857, 8850, -1, 8855, 8849, 8858, -1, 8855, 8850, 8849, -1, 8859, 8860, 8856, -1, 8859, 8856, 8855, -1, 8861, 8858, 8862, -1, 8861, 8862, 8863, -1, 8861, 8855, 8858, -1, 8864, 8865, 8852, -1, 8864, 8854, 8860, -1, 8864, 8860, 8859, -1, 8864, 8852, 8854, -1, 8866, 8867, 8868, -1, 8866, 8863, 8869, -1, 8866, 8869, 8867, -1, 8866, 8861, 8863, -1, 8866, 8855, 8861, -1, 8866, 8859, 8855, -1, 8870, 8868, 8871, -1, 8870, 8871, 8872, -1, 8870, 8872, 8865, -1, 8870, 8859, 8866, -1, 8870, 8866, 8868, -1, 8870, 8865, 8864, -1, 8870, 8864, 8859, -1, 8873, 8874, 8875, -1, 8876, 8877, 8878, -1, 8879, 8880, 8881, -1, 8879, 8881, 8874, -1, 8879, 8873, 8882, -1, 8879, 8874, 8873, -1, 8883, 8884, 8880, -1, 8883, 8880, 8879, -1, 8885, 8882, 8886, -1, 8885, 8886, 8887, -1, 8885, 8879, 8882, -1, 8888, 8889, 8876, -1, 8888, 8878, 8884, -1, 8888, 8884, 8883, -1, 8888, 8876, 8878, -1, 8890, 8891, 8892, -1, 8890, 8887, 8893, -1, 8890, 8893, 8891, -1, 8890, 8885, 8887, -1, 8890, 8879, 8885, -1, 8890, 8883, 8879, -1, 8894, 8892, 8895, -1, 8894, 8895, 8896, -1, 8894, 8896, 8889, -1, 8894, 8883, 8890, -1, 8894, 8890, 8892, -1, 8894, 8889, 8888, -1, 8894, 8888, 8883, -1, 8897, 8898, 8899, -1, 8897, 8899, 8900, -1, 8901, 8897, 8900, -1, 8902, 8898, 8897, -1, 8903, 8901, 8900, -1, 8904, 8901, 8903, -1, 8905, 8902, 8897, -1, 8906, 8903, 8907, -1, 8906, 8904, 8903, -1, 8908, 8902, 8905, -1, 8909, 8910, 8911, -1, 8912, 8913, 8906, -1, 8912, 8906, 8907, -1, 8914, 8915, 8910, -1, 8916, 8915, 8914, -1, 8917, 8916, 8914, -1, 8918, 8913, 8912, -1, 8919, 8913, 8918, -1, 8920, 8917, 8921, -1, 8920, 8916, 8917, -1, 8922, 8919, 8918, -1, 8923, 8920, 8921, -1, 8924, 8925, 8919, -1, 8924, 8919, 8922, -1, 8926, 8925, 8924, -1, 8927, 8920, 8923, -1, 8909, 8914, 8910, -1, 8928, 8905, 8929, -1, 8928, 8929, 8909, -1, 8928, 8911, 8908, -1, 8928, 8909, 8911, -1, 8928, 8908, 8905, -1, 8930, 8923, 8925, -1, 8930, 8926, 8927, -1, 8930, 8927, 8923, -1, 8930, 8925, 8926, -1, 8931, 8932, 8933, -1, 8934, 8935, 8936, -1, 8937, 8934, 8936, -1, 8938, 8939, 8940, -1, 8938, 8940, 8941, -1, 8938, 8941, 8942, -1, 8943, 8944, 8945, -1, 8943, 8945, 8939, -1, 8943, 8939, 8938, -1, 8946, 8942, 8932, -1, 8946, 8931, 8947, -1, 8946, 8932, 8931, -1, 8946, 8938, 8942, -1, 8948, 8949, 8950, -1, 8948, 8950, 8951, -1, 8948, 8951, 8944, -1, 8948, 8944, 8943, -1, 8952, 8947, 8953, -1, 8952, 8946, 8947, -1, 8952, 8938, 8946, -1, 8952, 8943, 8938, -1, 8954, 8953, 8935, -1, 8954, 8934, 8949, -1, 8954, 8952, 8953, -1, 8954, 8948, 8943, -1, 8954, 8943, 8952, -1, 8954, 8935, 8934, -1, 8954, 8949, 8948, -1, 8955, 8956, 8957, -1, 8958, 8959, 8960, -1, 8961, 8959, 8958, -1, 8962, 8963, 8964, -1, 8962, 8964, 8965, -1, 8962, 8965, 8966, -1, 8967, 8968, 8969, -1, 8967, 8969, 8963, -1, 8967, 8963, 8962, -1, 8970, 8966, 8956, -1, 8970, 8955, 8971, -1, 8970, 8956, 8955, -1, 8970, 8962, 8966, -1, 8972, 8973, 8974, -1, 8972, 8974, 8975, -1, 8972, 8975, 8968, -1, 8972, 8968, 8967, -1, 8976, 8971, 8977, -1, 8976, 8970, 8971, -1, 8976, 8962, 8970, -1, 8976, 8967, 8962, -1, 8978, 8977, 8960, -1, 8978, 8959, 8973, -1, 8978, 8976, 8977, -1, 8978, 8972, 8967, -1, 8978, 8967, 8976, -1, 8978, 8960, 8959, -1, 8978, 8973, 8972, -1, 8979, 8980, 8981, -1, 8982, 8983, 8984, -1, 8985, 8983, 8982, -1, 8986, 8987, 8988, -1, 8986, 8988, 8989, -1, 8986, 8989, 8990, -1, 8991, 8992, 8993, -1, 8991, 8993, 8987, -1, 8991, 8987, 8986, -1, 8994, 8990, 8980, -1, 8994, 8979, 8995, -1, 8994, 8980, 8979, -1, 8994, 8986, 8990, -1, 8996, 8997, 8998, -1, 8996, 8998, 8999, -1, 8996, 8999, 8992, -1, 8996, 8992, 8991, -1, 9000, 8995, 9001, -1, 9000, 8994, 8995, -1, 9000, 8986, 8994, -1, 9000, 8991, 8986, -1, 9002, 9001, 8984, -1, 9002, 8983, 8997, -1, 9002, 9000, 9001, -1, 9002, 8996, 8991, -1, 9002, 8991, 9000, -1, 9002, 8984, 8983, -1, 9002, 8997, 8996, -1, 9003, 9004, 9005, -1, 9006, 9007, 9008, -1, 9009, 9007, 9006, -1, 9010, 9011, 9012, -1, 9010, 9012, 9013, -1, 9010, 9013, 9014, -1, 9015, 9016, 9017, -1, 9015, 9017, 9011, -1, 9015, 9011, 9010, -1, 9018, 9014, 9004, -1, 9018, 9003, 9019, -1, 9018, 9004, 9003, -1, 9018, 9010, 9014, -1, 9020, 9021, 9022, -1, 9020, 9022, 9023, -1, 9020, 9023, 9016, -1, 9020, 9016, 9015, -1, 9024, 9019, 9025, -1, 9024, 9018, 9019, -1, 9024, 9010, 9018, -1, 9024, 9015, 9010, -1, 9026, 9025, 9008, -1, 9026, 9007, 9021, -1, 9026, 9024, 9025, -1, 9026, 9020, 9015, -1, 9026, 9015, 9024, -1, 9026, 9008, 9007, -1, 9026, 9021, 9020, -1, 9027, 9028, 9029, -1, 9030, 9031, 9032, -1, 9033, 9034, 9035, -1, 9033, 9035, 9027, -1, 9033, 9029, 9036, -1, 9033, 9027, 9029, -1, 9037, 9038, 9032, -1, 9037, 9031, 9034, -1, 9037, 9036, 9038, -1, 9037, 9033, 9036, -1, 9037, 9034, 9033, -1, 9037, 9032, 9031, -1, 9039, 9040, 9041, -1, 9039, 9041, 9042, -1, 9043, 9039, 9042, -1, 9044, 9040, 9039, -1, 9045, 9043, 9042, -1, 9046, 9043, 9045, -1, 9047, 9044, 9039, -1, 9048, 9045, 9049, -1, 9048, 9046, 9045, -1, 9050, 9044, 9047, -1, 9051, 9052, 9053, -1, 9054, 9055, 9048, -1, 9054, 9048, 9049, -1, 9056, 9057, 9052, -1, 9058, 9057, 9056, -1, 9059, 9058, 9056, -1, 9060, 9055, 9054, -1, 9061, 9055, 9060, -1, 9062, 9059, 9063, -1, 9062, 9058, 9059, -1, 9064, 9061, 9060, -1, 9065, 9062, 9063, -1, 9066, 9067, 9061, -1, 9066, 9061, 9064, -1, 9068, 9067, 9066, -1, 9069, 9062, 9065, -1, 9051, 9056, 9052, -1, 9070, 9047, 9071, -1, 9070, 9071, 9051, -1, 9070, 9053, 9050, -1, 9070, 9051, 9053, -1, 9070, 9050, 9047, -1, 9072, 9065, 9067, -1, 9072, 9068, 9069, -1, 9072, 9069, 9065, -1, 9072, 9067, 9068, -1, 9073, 9074, 9075, -1, 9076, 9077, 9078, -1, 9079, 9080, 9081, -1, 9079, 9081, 9074, -1, 9079, 9073, 9082, -1, 9079, 9074, 9073, -1, 9083, 9084, 9080, -1, 9083, 9080, 9079, -1, 9085, 9082, 9086, -1, 9085, 9086, 9087, -1, 9085, 9079, 9082, -1, 9088, 9089, 9076, -1, 9088, 9078, 9084, -1, 9088, 9084, 9083, -1, 9088, 9076, 9078, -1, 9090, 9091, 9092, -1, 9090, 9087, 9093, -1, 9090, 9093, 9091, -1, 9090, 9085, 9087, -1, 9090, 9079, 9085, -1, 9090, 9083, 9079, -1, 9094, 9092, 9095, -1, 9094, 9095, 9096, -1, 9094, 9096, 9089, -1, 9094, 9083, 9090, -1, 9094, 9090, 9092, -1, 9094, 9089, 9088, -1, 9094, 9088, 9083, -1, 9097, 9098, 9099, -1, 9097, 9099, 9100, -1, 9101, 9097, 9100, -1, 9102, 9098, 9097, -1, 9103, 9101, 9100, -1, 9104, 9101, 9103, -1, 9105, 9102, 9097, -1, 9106, 9104, 9103, -1, 9107, 9106, 9103, -1, 9108, 9102, 9105, -1, 9109, 9110, 9111, -1, 9109, 9111, 9108, -1, 9112, 9113, 9106, -1, 9112, 9106, 9107, -1, 9114, 9115, 9110, -1, 9116, 9115, 9114, -1, 9117, 9116, 9114, -1, 9118, 9113, 9112, -1, 9119, 9113, 9118, -1, 9120, 9117, 9121, -1, 9120, 9116, 9117, -1, 9122, 9119, 9118, -1, 9123, 9120, 9121, -1, 9124, 9125, 9119, -1, 9124, 9119, 9122, -1, 9126, 9125, 9124, -1, 9127, 9120, 9123, -1, 9109, 9114, 9110, -1, 9128, 9105, 9129, -1, 9128, 9129, 9109, -1, 9128, 9108, 9105, -1, 9128, 9109, 9108, -1, 9130, 9123, 9125, -1, 9130, 9126, 9127, -1, 9130, 9127, 9123, -1, 9130, 9125, 9126, -1, 9131, 9132, 9133, -1, 9134, 9135, 9136, -1, 9137, 9138, 9139, -1, 9137, 9139, 9132, -1, 9137, 9131, 9140, -1, 9137, 9132, 9131, -1, 9141, 9142, 9138, -1, 9141, 9138, 9137, -1, 9143, 9140, 9144, -1, 9143, 9144, 9145, -1, 9143, 9137, 9140, -1, 9146, 9147, 9134, -1, 9146, 9136, 9142, -1, 9146, 9134, 9136, -1, 9146, 9142, 9141, -1, 9148, 9145, 9149, -1, 9148, 9149, 9150, -1, 9148, 9150, 9151, -1, 9148, 9143, 9145, -1, 9148, 9141, 9137, -1, 9148, 9137, 9143, -1, 9152, 9151, 9153, -1, 9152, 9153, 9154, -1, 9152, 9154, 9147, -1, 9152, 9148, 9151, -1, 9152, 9147, 9146, -1, 9152, 9146, 9141, -1, 9152, 9141, 9148, -1, 9155, 9156, 9157, -1, 9158, 9159, 9160, -1, 9161, 9162, 9163, -1, 9161, 9163, 9156, -1, 9161, 9155, 9164, -1, 9161, 9156, 9155, -1, 9165, 9166, 9162, -1, 9165, 9162, 9161, -1, 9167, 9164, 9168, -1, 9167, 9168, 9169, -1, 9167, 9161, 9164, -1, 9170, 9171, 9158, -1, 9170, 9160, 9166, -1, 9170, 9166, 9165, -1, 9170, 9158, 9160, -1, 9172, 9173, 9174, -1, 9172, 9169, 9175, -1, 9172, 9175, 9173, -1, 9172, 9167, 9169, -1, 9172, 9161, 9167, -1, 9172, 9165, 9161, -1, 9176, 9174, 9177, -1, 9176, 9177, 9178, -1, 9176, 9178, 9171, -1, 9176, 9165, 9172, -1, 9176, 9172, 9174, -1, 9176, 9171, 9170, -1, 9176, 9170, 9165, -1, 9179, 9180, 9181, -1, 9179, 9181, 9182, -1, 9183, 9179, 9182, -1, 9184, 9180, 9179, -1, 9185, 9183, 9182, -1, 9186, 9183, 9185, -1, 9187, 9184, 9179, -1, 9188, 9185, 9189, -1, 9188, 9186, 9185, -1, 9190, 9184, 9187, -1, 9191, 9192, 9193, -1, 9194, 9195, 9188, -1, 9194, 9188, 9189, -1, 9196, 9197, 9192, -1, 9198, 9197, 9196, -1, 9199, 9198, 9196, -1, 9200, 9195, 9194, -1, 9201, 9195, 9200, -1, 9202, 9199, 9203, -1, 9202, 9198, 9199, -1, 9204, 9201, 9200, -1, 9205, 9202, 9203, -1, 9206, 9207, 9201, -1, 9206, 9201, 9204, -1, 9208, 9207, 9206, -1, 9209, 9202, 9205, -1, 9191, 9196, 9192, -1, 9210, 9187, 9211, -1, 9210, 9211, 9191, -1, 9210, 9193, 9190, -1, 9210, 9191, 9193, -1, 9210, 9190, 9187, -1, 9212, 9205, 9207, -1, 9212, 9208, 9209, -1, 9212, 9209, 9205, -1, 9212, 9207, 9208, -1, 9213, 9214, 9215, -1, 9213, 9215, 9216, -1, 9217, 9213, 9216, -1, 9218, 9214, 9213, -1, 9219, 9217, 9216, -1, 9220, 9217, 9219, -1, 9221, 9218, 9213, -1, 9222, 9220, 9219, -1, 9223, 9222, 9219, -1, 9224, 9218, 9221, -1, 9225, 9226, 9227, -1, 9225, 9227, 9224, -1, 9228, 9229, 9222, -1, 9228, 9222, 9223, -1, 9230, 9231, 9226, -1, 9232, 9231, 9230, -1, 9233, 9232, 9230, -1, 9234, 9229, 9228, -1, 9235, 9229, 9234, -1, 9236, 9233, 9237, -1, 9236, 9232, 9233, -1, 9238, 9235, 9234, -1, 9239, 9236, 9237, -1, 9240, 9241, 9235, -1, 9240, 9235, 9238, -1, 9242, 9241, 9240, -1, 9243, 9236, 9239, -1, 9225, 9230, 9226, -1, 9244, 9221, 9245, -1, 9244, 9245, 9225, -1, 9244, 9224, 9221, -1, 9244, 9225, 9224, -1, 9246, 9239, 9241, -1, 9246, 9242, 9243, -1, 9246, 9243, 9239, -1, 9246, 9241, 9242, -1, 9247, 9248, 9249, -1, 9250, 9251, 9252, -1, 9253, 9254, 9255, -1, 9253, 9255, 9248, -1, 9253, 9247, 9256, -1, 9253, 9248, 9247, -1, 9257, 9258, 9254, -1, 9257, 9254, 9253, -1, 9259, 9256, 9260, -1, 9259, 9260, 9261, -1, 9259, 9253, 9256, -1, 9262, 9263, 9250, -1, 9262, 9252, 9258, -1, 9262, 9258, 9257, -1, 9262, 9250, 9252, -1, 9264, 9265, 9266, -1, 9264, 9261, 9267, -1, 9264, 9267, 9265, -1, 9264, 9259, 9261, -1, 9264, 9253, 9259, -1, 9264, 9257, 9253, -1, 9268, 9266, 9269, -1, 9268, 9269, 9270, -1, 9268, 9270, 9263, -1, 9268, 9257, 9264, -1, 9268, 9264, 9266, -1, 9268, 9263, 9262, -1, 9268, 9262, 9257, -1, 9271, 9272, 9273, -1, 9274, 9275, 9276, -1, 9277, 9278, 9279, -1, 9277, 9279, 9271, -1, 9277, 9273, 9280, -1, 9277, 9271, 9273, -1, 9281, 9282, 9276, -1, 9281, 9275, 9278, -1, 9281, 9280, 9282, -1, 9281, 9277, 9280, -1, 9281, 9278, 9277, -1, 9281, 9276, 9275, -1, 9283, 9284, 9285, -1, 9286, 9287, 9288, -1, 9289, 9287, 9286, -1, 9290, 9291, 9292, -1, 9290, 9292, 9293, -1, 9290, 9293, 9294, -1, 9295, 9296, 9291, -1, 9295, 9297, 9296, -1, 9295, 9291, 9290, -1, 9298, 9294, 9284, -1, 9298, 9283, 9299, -1, 9298, 9290, 9294, -1, 9298, 9284, 9283, -1, 9300, 9301, 9302, -1, 9300, 9302, 9303, -1, 9300, 9303, 9297, -1, 9300, 9297, 9295, -1, 9304, 9299, 9305, -1, 9304, 9298, 9299, -1, 9304, 9290, 9298, -1, 9304, 9295, 9290, -1, 9306, 9305, 9288, -1, 9306, 9287, 9301, -1, 9306, 9300, 9295, -1, 9306, 9304, 9305, -1, 9306, 9295, 9304, -1, 9306, 9288, 9287, -1, 9306, 9301, 9300, -1, 9307, 9308, 9309, -1, 9310, 9311, 9312, -1, 9313, 9311, 9310, -1, 9314, 9315, 9316, -1, 9314, 9316, 9317, -1, 9314, 9317, 9318, -1, 9319, 9320, 9315, -1, 9319, 9321, 9320, -1, 9319, 9315, 9314, -1, 9322, 9318, 9308, -1, 9322, 9307, 9323, -1, 9322, 9314, 9318, -1, 9322, 9308, 9307, -1, 9324, 9325, 9326, -1, 9324, 9326, 9327, -1, 9324, 9327, 9321, -1, 9324, 9321, 9319, -1, 9328, 9323, 9329, -1, 9328, 9322, 9323, -1, 9328, 9314, 9322, -1, 9328, 9319, 9314, -1, 9330, 9329, 9312, -1, 9330, 9311, 9325, -1, 9330, 9324, 9319, -1, 9330, 9328, 9329, -1, 9330, 9319, 9328, -1, 9330, 9312, 9311, -1, 9330, 9325, 9324, -1, 9331, 9332, 9333, -1, 9334, 9335, 9336, -1, 9337, 9334, 9336, -1, 9338, 9339, 9340, -1, 9338, 9340, 9341, -1, 9338, 9341, 9342, -1, 9343, 9344, 9345, -1, 9343, 9345, 9339, -1, 9343, 9339, 9338, -1, 9346, 9342, 9332, -1, 9346, 9331, 9347, -1, 9346, 9332, 9331, -1, 9346, 9338, 9342, -1, 9348, 9349, 9350, -1, 9348, 9350, 9351, -1, 9348, 9351, 9344, -1, 9348, 9344, 9343, -1, 9352, 9347, 9353, -1, 9352, 9346, 9347, -1, 9352, 9338, 9346, -1, 9352, 9343, 9338, -1, 9354, 9353, 9335, -1, 9354, 9334, 9349, -1, 9354, 9352, 9353, -1, 9354, 9348, 9343, -1, 9354, 9343, 9352, -1, 9354, 9335, 9334, -1, 9354, 9349, 9348, -1, 9355, 9356, 9357, -1, 9358, 9359, 9360, -1, 9361, 9359, 9358, -1, 9362, 9363, 9364, -1, 9362, 9364, 9365, -1, 9362, 9365, 9366, -1, 9367, 9368, 9363, -1, 9367, 9369, 9368, -1, 9367, 9363, 9362, -1, 9370, 9366, 9356, -1, 9370, 9355, 9371, -1, 9370, 9362, 9366, -1, 9370, 9356, 9355, -1, 9372, 9373, 9374, -1, 9372, 9374, 9375, -1, 9372, 9375, 9369, -1, 9372, 9369, 9367, -1, 9376, 9371, 9377, -1, 9376, 9370, 9371, -1, 9376, 9362, 9370, -1, 9376, 9367, 9362, -1, 9378, 9377, 9360, -1, 9378, 9359, 9373, -1, 9378, 9372, 9367, -1, 9378, 9376, 9377, -1, 9378, 9367, 9376, -1, 9378, 9360, 9359, -1, 9378, 9373, 9372, -1, 9379, 9380, 9381, -1, 9382, 9383, 9384, -1, 9385, 9386, 9387, -1, 9385, 9387, 9380, -1, 9385, 9379, 9388, -1, 9385, 9380, 9379, -1, 9389, 9390, 9386, -1, 9389, 9386, 9385, -1, 9391, 9388, 9392, -1, 9391, 9392, 9393, -1, 9391, 9385, 9388, -1, 9394, 9395, 9382, -1, 9394, 9384, 9390, -1, 9394, 9390, 9389, -1, 9394, 9382, 9384, -1, 9396, 9397, 9398, -1, 9396, 9393, 9399, -1, 9396, 9399, 9397, -1, 9396, 9391, 9393, -1, 9396, 9385, 9391, -1, 9396, 9389, 9385, -1, 9400, 9398, 9401, -1, 9400, 9401, 9402, -1, 9400, 9402, 9395, -1, 9400, 9389, 9396, -1, 9400, 9396, 9398, -1, 9400, 9395, 9394, -1, 9400, 9394, 9389, -1, 9403, 9404, 9405, -1, 9403, 9405, 9406, -1, 9407, 9403, 9406, -1, 9408, 9404, 9403, -1, 9409, 9407, 9406, -1, 9410, 9407, 9409, -1, 9411, 9408, 9403, -1, 9412, 9409, 9413, -1, 9412, 9410, 9409, -1, 9414, 9408, 9411, -1, 9415, 9416, 9417, -1, 9418, 9419, 9412, -1, 9418, 9412, 9413, -1, 9420, 9421, 9416, -1, 9422, 9421, 9420, -1, 9423, 9422, 9420, -1, 9424, 9419, 9418, -1, 9425, 9419, 9424, -1, 9426, 9423, 9427, -1, 9426, 9422, 9423, -1, 9428, 9425, 9424, -1, 9429, 9426, 9427, -1, 9430, 9431, 9425, -1, 9430, 9425, 9428, -1, 9432, 9431, 9430, -1, 9433, 9426, 9429, -1, 9415, 9420, 9416, -1, 9434, 9411, 9435, -1, 9434, 9435, 9415, -1, 9434, 9417, 9414, -1, 9434, 9415, 9417, -1, 9434, 9414, 9411, -1, 9436, 9429, 9431, -1, 9436, 9432, 9433, -1, 9436, 9433, 9429, -1, 9436, 9431, 9432, -1, 9437, 9438, 9439, -1, 9437, 9439, 9440, -1, 9441, 9437, 9440, -1, 9442, 9438, 9437, -1, 9443, 9441, 9440, -1, 9444, 9441, 9443, -1, 9445, 9442, 9437, -1, 9446, 9444, 9443, -1, 9447, 9446, 9443, -1, 9448, 9442, 9445, -1, 9449, 9450, 9451, -1, 9449, 9451, 9448, -1, 9452, 9453, 9446, -1, 9452, 9446, 9447, -1, 9454, 9455, 9450, -1, 9456, 9455, 9454, -1, 9457, 9456, 9454, -1, 9458, 9453, 9452, -1, 9459, 9453, 9458, -1, 9460, 9457, 9461, -1, 9460, 9456, 9457, -1, 9462, 9459, 9458, -1, 9463, 9460, 9461, -1, 9464, 9465, 9459, -1, 9464, 9459, 9462, -1, 9466, 9465, 9464, -1, 9467, 9460, 9463, -1, 9449, 9454, 9450, -1, 9468, 9445, 9469, -1, 9468, 9469, 9449, -1, 9468, 9448, 9445, -1, 9468, 9449, 9448, -1, 9470, 9463, 9465, -1, 9470, 9466, 9467, -1, 9470, 9467, 9463, -1, 9470, 9465, 9466, -1, 9471, 9472, 9473, -1, 9474, 9475, 9476, -1, 9477, 9478, 9479, -1, 9477, 9479, 9472, -1, 9477, 9471, 9480, -1, 9477, 9472, 9471, -1, 9481, 9482, 9478, -1, 9481, 9478, 9477, -1, 9483, 9480, 9484, -1, 9483, 9484, 9485, -1, 9483, 9477, 9480, -1, 9486, 9487, 9474, -1, 9486, 9476, 9482, -1, 9486, 9474, 9476, -1, 9486, 9482, 9481, -1, 9488, 9485, 9489, -1, 9488, 9489, 9490, -1, 9488, 9490, 9491, -1, 9488, 9483, 9485, -1, 9488, 9481, 9477, -1, 9488, 9477, 9483, -1, 9492, 9491, 9493, -1, 9492, 9493, 9494, -1, 9492, 9494, 9487, -1, 9492, 9488, 9491, -1, 9492, 9487, 9486, -1, 9492, 9486, 9481, -1, 9492, 9481, 9488, -1, 9495, 9496, 9497, -1, 9498, 9499, 9500, -1, 9501, 9498, 9500, -1, 9502, 9503, 9504, -1, 9502, 9504, 9505, -1, 9502, 9505, 9506, -1, 9507, 9508, 9509, -1, 9507, 9509, 9503, -1, 9507, 9503, 9502, -1, 9510, 9506, 9496, -1, 9510, 9495, 9511, -1, 9510, 9496, 9495, -1, 9510, 9502, 9506, -1, 9512, 9513, 9514, -1, 9512, 9514, 9515, -1, 9512, 9515, 9508, -1, 9512, 9508, 9507, -1, 9516, 9511, 9517, -1, 9516, 9510, 9511, -1, 9516, 9502, 9510, -1, 9516, 9507, 9502, -1, 9518, 9517, 9499, -1, 9518, 9498, 9513, -1, 9518, 9516, 9517, -1, 9518, 9512, 9507, -1, 9518, 9507, 9516, -1, 9518, 9499, 9498, -1, 9518, 9513, 9512, -1, 9519, 9520, 9521, -1, 9522, 9523, 9524, -1, 9525, 9526, 9527, -1, 9525, 9527, 9519, -1, 9525, 9521, 9528, -1, 9525, 9519, 9521, -1, 9529, 9530, 9524, -1, 9529, 9523, 9526, -1, 9529, 9528, 9530, -1, 9529, 9525, 9528, -1, 9529, 9526, 9525, -1, 9529, 9524, 9523, -1, 9531, 9532, 9533, -1, 9534, 9535, 9536, -1, 9537, 9535, 9534, -1, 9538, 9539, 9540, -1, 9538, 9540, 9541, -1, 9538, 9541, 9542, -1, 9543, 9544, 9539, -1, 9543, 9545, 9544, -1, 9543, 9539, 9538, -1, 9546, 9542, 9532, -1, 9546, 9531, 9547, -1, 9546, 9538, 9542, -1, 9546, 9532, 9531, -1, 9548, 9549, 9550, -1, 9548, 9550, 9551, -1, 9548, 9551, 9545, -1, 9548, 9545, 9543, -1, 9552, 9547, 9553, -1, 9552, 9546, 9547, -1, 9552, 9538, 9546, -1, 9552, 9543, 9538, -1, 9554, 9553, 9536, -1, 9554, 9535, 9549, -1, 9554, 9548, 9543, -1, 9554, 9552, 9553, -1, 9554, 9543, 9552, -1, 9554, 9536, 9535, -1, 9554, 9549, 9548, -1, 9555, 9556, 9557, -1, 9558, 9559, 9560, -1, 9561, 9559, 9558, -1, 9562, 9563, 9564, -1, 9562, 9564, 9565, -1, 9562, 9565, 9566, -1, 9567, 9568, 9569, -1, 9567, 9569, 9563, -1, 9567, 9563, 9562, -1, 9570, 9566, 9556, -1, 9570, 9555, 9571, -1, 9570, 9556, 9555, -1, 9570, 9562, 9566, -1, 9572, 9573, 9574, -1, 9572, 9574, 9575, -1, 9572, 9575, 9568, -1, 9572, 9568, 9567, -1, 9576, 9571, 9577, -1, 9576, 9570, 9571, -1, 9576, 9562, 9570, -1, 9576, 9567, 9562, -1, 9578, 9577, 9560, -1, 9578, 9559, 9573, -1, 9578, 9576, 9577, -1, 9578, 9572, 9567, -1, 9578, 9567, 9576, -1, 9578, 9560, 9559, -1, 9578, 9573, 9572, -1, 9579, 9580, 9581, -1, 9582, 9583, 9584, -1, 9585, 9583, 9582, -1, 9586, 9587, 9588, -1, 9586, 9588, 9589, -1, 9586, 9589, 9590, -1, 9591, 9592, 9587, -1, 9591, 9593, 9592, -1, 9591, 9587, 9586, -1, 9594, 9590, 9580, -1, 9594, 9579, 9595, -1, 9594, 9586, 9590, -1, 9594, 9580, 9579, -1, 9596, 9597, 9598, -1, 9596, 9598, 9599, -1, 9596, 9599, 9593, -1, 9596, 9593, 9591, -1, 9600, 9595, 9601, -1, 9600, 9594, 9595, -1, 9600, 9586, 9594, -1, 9600, 9591, 9586, -1, 9602, 9601, 9584, -1, 9602, 9583, 9597, -1, 9602, 9596, 9591, -1, 9602, 9600, 9601, -1, 9602, 9591, 9600, -1, 9602, 9584, 9583, -1, 9602, 9597, 9596, -1, 9603, 9604, 9605, -1, 9606, 9607, 9608, -1, 9609, 9610, 9611, -1, 9609, 9611, 9604, -1, 9609, 9603, 9612, -1, 9609, 9604, 9603, -1, 9613, 9614, 9610, -1, 9613, 9610, 9609, -1, 9615, 9612, 9616, -1, 9615, 9616, 9617, -1, 9615, 9609, 9612, -1, 9618, 9619, 9606, -1, 9618, 9608, 9614, -1, 9618, 9614, 9613, -1, 9618, 9606, 9608, -1, 9620, 9621, 9622, -1, 9620, 9617, 9623, -1, 9620, 9623, 9621, -1, 9620, 9615, 9617, -1, 9620, 9609, 9615, -1, 9620, 9613, 9609, -1, 9624, 9622, 9625, -1, 9624, 9625, 9626, -1, 9624, 9626, 9619, -1, 9624, 9613, 9620, -1, 9624, 9620, 9622, -1, 9624, 9619, 9618, -1, 9624, 9618, 9613, -1, 9627, 9628, 9629, -1, 9627, 9629, 9630, -1, 9631, 9627, 9630, -1, 9632, 9628, 9627, -1, 9633, 9631, 9630, -1, 9634, 9631, 9633, -1, 9635, 9632, 9627, -1, 9636, 9633, 9637, -1, 9636, 9634, 9633, -1, 9638, 9632, 9635, -1, 9639, 9640, 9641, -1, 9642, 9643, 9636, -1, 9642, 9636, 9637, -1, 9644, 9645, 9640, -1, 9646, 9645, 9644, -1, 9647, 9646, 9644, -1, 9648, 9643, 9642, -1, 9649, 9643, 9648, -1, 9650, 9647, 9651, -1, 9650, 9646, 9647, -1, 9652, 9649, 9648, -1, 9653, 9650, 9651, -1, 9654, 9655, 9649, -1, 9654, 9649, 9652, -1, 9656, 9655, 9654, -1, 9657, 9650, 9653, -1, 9639, 9644, 9640, -1, 9658, 9635, 9659, -1, 9658, 9659, 9639, -1, 9658, 9641, 9638, -1, 9658, 9639, 9641, -1, 9658, 9638, 9635, -1, 9660, 9653, 9655, -1, 9660, 9656, 9657, -1, 9660, 9657, 9653, -1, 9660, 9655, 9656, -1, 9661, 9662, 9663, -1, 9664, 9665, 9666, -1, 9667, 9668, 9669, -1, 9667, 9669, 9662, -1, 9667, 9661, 9670, -1, 9667, 9662, 9661, -1, 9671, 9672, 9668, -1, 9671, 9668, 9667, -1, 9673, 9670, 9674, -1, 9673, 9674, 9675, -1, 9673, 9667, 9670, -1, 9676, 9677, 9664, -1, 9676, 9666, 9672, -1, 9676, 9664, 9666, -1, 9676, 9672, 9671, -1, 9678, 9675, 9679, -1, 9678, 9679, 9680, -1, 9678, 9680, 9681, -1, 9678, 9673, 9675, -1, 9678, 9671, 9667, -1, 9678, 9667, 9673, -1, 9682, 9681, 9683, -1, 9682, 9683, 9684, -1, 9682, 9684, 9677, -1, 9682, 9678, 9681, -1, 9682, 9677, 9676, -1, 9682, 9676, 9671, -1, 9682, 9671, 9678, -1, 9685, 9686, 9687, -1, 9685, 9687, 9688, -1, 9689, 9685, 9688, -1, 9690, 9686, 9685, -1, 9691, 9689, 9688, -1, 9692, 9689, 9691, -1, 9693, 9690, 9685, -1, 9694, 9692, 9691, -1, 9695, 9694, 9691, -1, 9696, 9690, 9693, -1, 9697, 9698, 9699, -1, 9697, 9699, 9696, -1, 9700, 9701, 9694, -1, 9700, 9694, 9695, -1, 9702, 9703, 9698, -1, 9704, 9703, 9702, -1, 9705, 9704, 9702, -1, 9706, 9701, 9700, -1, 9707, 9701, 9706, -1, 9708, 9705, 9709, -1, 9708, 9704, 9705, -1, 9710, 9707, 9706, -1, 9711, 9708, 9709, -1, 9712, 9713, 9707, -1, 9712, 9707, 9710, -1, 9714, 9713, 9712, -1, 9715, 9708, 9711, -1, 9697, 9702, 9698, -1, 9716, 9693, 9717, -1, 9716, 9717, 9697, -1, 9716, 9696, 9693, -1, 9716, 9697, 9696, -1, 9718, 9711, 9713, -1, 9718, 9714, 9715, -1, 9718, 9715, 9711, -1, 9718, 9713, 9714, -1, 9719, 9720, 9721, -1, 9722, 9723, 9724, -1, 9725, 9723, 9722, -1, 9726, 9727, 9728, -1, 9726, 9728, 9729, -1, 9726, 9729, 9730, -1, 9731, 9732, 9733, -1, 9731, 9733, 9727, -1, 9731, 9727, 9726, -1, 9734, 9730, 9720, -1, 9734, 9719, 9735, -1, 9734, 9720, 9719, -1, 9734, 9726, 9730, -1, 9736, 9737, 9738, -1, 9736, 9738, 9739, -1, 9736, 9739, 9732, -1, 9736, 9732, 9731, -1, 9740, 9735, 9741, -1, 9740, 9734, 9735, -1, 9740, 9726, 9734, -1, 9740, 9731, 9726, -1, 9742, 9741, 9724, -1, 9742, 9723, 9737, -1, 9742, 9740, 9741, -1, 9742, 9736, 9731, -1, 9742, 9731, 9740, -1, 9742, 9724, 9723, -1, 9742, 9737, 9736, -1, 9743, 9744, 9745, -1, 9746, 9747, 9748, -1, 9749, 9747, 9746, -1, 9750, 9751, 9752, -1, 9750, 9752, 9753, -1, 9750, 9753, 9754, -1, 9755, 9756, 9757, -1, 9755, 9757, 9751, -1, 9755, 9751, 9750, -1, 9758, 9754, 9744, -1, 9758, 9743, 9759, -1, 9758, 9744, 9743, -1, 9758, 9750, 9754, -1, 9760, 9761, 9762, -1, 9760, 9762, 9763, -1, 9760, 9763, 9756, -1, 9760, 9756, 9755, -1, 9764, 9759, 9765, -1, 9764, 9758, 9759, -1, 9764, 9750, 9758, -1, 9764, 9755, 9750, -1, 9766, 9765, 9748, -1, 9766, 9747, 9761, -1, 9766, 9764, 9765, -1, 9766, 9760, 9755, -1, 9766, 9755, 9764, -1, 9766, 9748, 9747, -1, 9766, 9761, 9760, -1, 9767, 9768, 9769, -1, 9770, 9771, 9772, -1, 9773, 9774, 9775, -1, 9773, 9775, 9767, -1, 9773, 9769, 9776, -1, 9773, 9767, 9769, -1, 9777, 9778, 9772, -1, 9777, 9771, 9774, -1, 9777, 9776, 9778, -1, 9777, 9773, 9776, -1, 9777, 9774, 9773, -1, 9777, 9772, 9771, -1, 9779, 9780, 9781, -1, 9782, 9783, 9784, -1, 9785, 9782, 9784, -1, 9786, 9787, 9788, -1, 9786, 9788, 9789, -1, 9786, 9789, 9790, -1, 9791, 9792, 9793, -1, 9791, 9793, 9787, -1, 9791, 9787, 9786, -1, 9794, 9790, 9780, -1, 9794, 9779, 9795, -1, 9794, 9780, 9779, -1, 9794, 9786, 9790, -1, 9796, 9797, 9798, -1, 9796, 9798, 9799, -1, 9796, 9799, 9792, -1, 9796, 9792, 9791, -1, 9800, 9795, 9801, -1, 9800, 9794, 9795, -1, 9800, 9786, 9794, -1, 9800, 9791, 9786, -1, 9802, 9801, 9783, -1, 9802, 9782, 9797, -1, 9802, 9800, 9801, -1, 9802, 9796, 9791, -1, 9802, 9791, 9800, -1, 9802, 9783, 9782, -1, 9802, 9797, 9796, -1, 9803, 9804, 9805, -1, 9806, 9807, 9808, -1, 9809, 9807, 9806, -1, 9810, 9811, 9812, -1, 9810, 9812, 9813, -1, 9810, 9813, 9814, -1, 9815, 9816, 9811, -1, 9815, 9817, 9816, -1, 9815, 9811, 9810, -1, 9818, 9814, 9804, -1, 9818, 9803, 9819, -1, 9818, 9810, 9814, -1, 9818, 9804, 9803, -1, 9820, 9821, 9822, -1, 9820, 9822, 9823, -1, 9820, 9823, 9817, -1, 9820, 9817, 9815, -1, 9824, 9819, 9825, -1, 9824, 9818, 9819, -1, 9824, 9810, 9818, -1, 9824, 9815, 9810, -1, 9826, 9825, 9808, -1, 9826, 9807, 9821, -1, 9826, 9820, 9815, -1, 9826, 9824, 9825, -1, 9826, 9815, 9824, -1, 9826, 9808, 9807, -1, 9826, 9821, 9820, -1, 9827, 9828, 9829, -1, 9827, 9829, 9830, -1, 9831, 9827, 9830, -1, 9832, 9828, 9827, -1, 9833, 9831, 9830, -1, 9834, 9831, 9833, -1, 9835, 9832, 9827, -1, 9836, 9834, 9833, -1, 9837, 9836, 9833, -1, 9838, 9832, 9835, -1, 9839, 9840, 9841, -1, 9839, 9841, 9838, -1, 9842, 9843, 9836, -1, 9842, 9836, 9837, -1, 9844, 9845, 9840, -1, 9846, 9845, 9844, -1, 9847, 9846, 9844, -1, 9848, 9843, 9842, -1, 9849, 9843, 9848, -1, 9850, 9847, 9851, -1, 9850, 9846, 9847, -1, 9852, 9849, 9848, -1, 9853, 9850, 9851, -1, 9854, 9855, 9849, -1, 9854, 9849, 9852, -1, 9856, 9855, 9854, -1, 9857, 9850, 9853, -1, 9839, 9844, 9840, -1, 9858, 9835, 9859, -1, 9858, 9859, 9839, -1, 9858, 9838, 9835, -1, 9858, 9839, 9838, -1, 9860, 9853, 9855, -1, 9860, 9856, 9857, -1, 9860, 9857, 9853, -1, 9860, 9855, 9856, -1, 9861, 9862, 9863, -1, 9864, 9865, 9866, -1, 9867, 9868, 9869, -1, 9867, 9869, 9862, -1, 9867, 9861, 9870, -1, 9867, 9862, 9861, -1, 9871, 9872, 9868, -1, 9871, 9868, 9867, -1, 9873, 9870, 9874, -1, 9873, 9874, 9875, -1, 9873, 9867, 9870, -1, 9876, 9877, 9864, -1, 9876, 9866, 9872, -1, 9876, 9872, 9871, -1, 9876, 9864, 9866, -1, 9878, 9879, 9880, -1, 9878, 9875, 9881, -1, 9878, 9881, 9879, -1, 9878, 9873, 9875, -1, 9878, 9867, 9873, -1, 9878, 9871, 9867, -1, 9882, 9880, 9883, -1, 9882, 9883, 9884, -1, 9882, 9884, 9877, -1, 9882, 9871, 9878, -1, 9882, 9878, 9880, -1, 9882, 9877, 9876, -1, 9882, 9876, 9871, -1, 9885, 9886, 9887, -1, 9885, 9887, 9888, -1, 9889, 9885, 9888, -1, 9890, 9886, 9885, -1, 9891, 9889, 9888, -1, 9892, 9889, 9891, -1, 9893, 9890, 9885, -1, 9894, 9891, 9895, -1, 9894, 9892, 9891, -1, 9896, 9890, 9893, -1, 9897, 9898, 9899, -1, 9900, 9901, 9894, -1, 9900, 9894, 9895, -1, 9902, 9903, 9898, -1, 9904, 9903, 9902, -1, 9905, 9904, 9902, -1, 9906, 9901, 9900, -1, 9907, 9901, 9906, -1, 9908, 9905, 9909, -1, 9908, 9904, 9905, -1, 9910, 9907, 9906, -1, 9911, 9908, 9909, -1, 9912, 9913, 9907, -1, 9912, 9907, 9910, -1, 9914, 9913, 9912, -1, 9915, 9908, 9911, -1, 9897, 9902, 9898, -1, 9916, 9893, 9917, -1, 9916, 9917, 9897, -1, 9916, 9899, 9896, -1, 9916, 9897, 9899, -1, 9916, 9896, 9893, -1, 9918, 9911, 9913, -1, 9918, 9914, 9915, -1, 9918, 9915, 9911, -1, 9918, 9913, 9914, -1, 9919, 9920, 9921, -1, 9922, 9923, 9924, -1, 9925, 9926, 9927, -1, 9925, 9927, 9920, -1, 9925, 9919, 9928, -1, 9925, 9920, 9919, -1, 9929, 9930, 9926, -1, 9929, 9926, 9925, -1, 9931, 9928, 9932, -1, 9931, 9932, 9933, -1, 9931, 9925, 9928, -1, 9934, 9935, 9922, -1, 9934, 9924, 9930, -1, 9934, 9930, 9929, -1, 9934, 9922, 9924, -1, 9936, 9937, 9938, -1, 9936, 9933, 9939, -1, 9936, 9939, 9937, -1, 9936, 9931, 9933, -1, 9936, 9925, 9931, -1, 9936, 9929, 9925, -1, 9940, 9938, 9941, -1, 9940, 9941, 9942, -1, 9940, 9942, 9935, -1, 9940, 9929, 9936, -1, 9940, 9936, 9938, -1, 9940, 9935, 9934, -1, 9940, 9934, 9929, -1, 9943, 9944, 9945, -1, 9946, 9947, 9948, -1, 9949, 9947, 9946, -1, 9950, 9951, 9952, -1, 9950, 9952, 9953, -1, 9950, 9953, 9954, -1, 9955, 9956, 9957, -1, 9955, 9957, 9951, -1, 9955, 9951, 9950, -1, 9958, 9954, 9944, -1, 9958, 9943, 9959, -1, 9958, 9944, 9943, -1, 9958, 9950, 9954, -1, 9960, 9961, 9962, -1, 9960, 9962, 9963, -1, 9960, 9963, 9956, -1, 9960, 9956, 9955, -1, 9964, 9959, 9965, -1, 9964, 9958, 9959, -1, 9964, 9950, 9958, -1, 9964, 9955, 9950, -1, 9966, 9965, 9948, -1, 9966, 9947, 9961, -1, 9966, 9964, 9965, -1, 9966, 9960, 9955, -1, 9966, 9955, 9964, -1, 9966, 9948, 9947, -1, 9966, 9961, 9960, -1, 9967, 9968, 9969, -1, 9970, 9971, 9972, -1, 9973, 9974, 9975, -1, 9973, 9975, 9967, -1, 9973, 9969, 9976, -1, 9973, 9967, 9969, -1, 9977, 9978, 9972, -1, 9977, 9971, 9974, -1, 9977, 9976, 9978, -1, 9977, 9973, 9976, -1, 9977, 9974, 9973, -1, 9977, 9972, 9971, -1, 9979, 9980, 9981, -1, 9982, 9983, 9984, -1, 9985, 9983, 9982, -1, 9986, 9987, 9988, -1, 9986, 9988, 9989, -1, 9986, 9989, 9990, -1, 9991, 9992, 9987, -1, 9991, 9993, 9992, -1, 9991, 9987, 9986, -1, 9994, 9990, 9980, -1, 9994, 9979, 9995, -1, 9994, 9986, 9990, -1, 9994, 9980, 9979, -1, 9996, 9997, 9998, -1, 9996, 9998, 9999, -1, 9996, 9999, 9993, -1, 9996, 9993, 9991, -1, 10000, 9995, 10001, -1, 10000, 9994, 9995, -1, 10000, 9986, 9994, -1, 10000, 9991, 9986, -1, 10002, 10001, 9984, -1, 10002, 9983, 9997, -1, 10002, 9996, 9991, -1, 10002, 10000, 10001, -1, 10002, 9991, 10000, -1, 10002, 9984, 9983, -1, 10002, 9997, 9996, -1, 10003, 10004, 10005, -1, 10006, 10007, 10008, -1, 10009, 10007, 10006, -1, 10010, 10011, 10012, -1, 10010, 10012, 10013, -1, 10010, 10013, 10014, -1, 10015, 10016, 10011, -1, 10015, 10017, 10016, -1, 10015, 10011, 10010, -1, 10018, 10014, 10004, -1, 10018, 10003, 10019, -1, 10018, 10010, 10014, -1, 10018, 10004, 10003, -1, 10020, 10021, 10022, -1, 10020, 10022, 10023, -1, 10020, 10023, 10017, -1, 10020, 10017, 10015, -1, 10024, 10019, 10025, -1, 10024, 10018, 10019, -1, 10024, 10010, 10018, -1, 10024, 10015, 10010, -1, 10026, 10025, 10008, -1, 10026, 10007, 10021, -1, 10026, 10020, 10015, -1, 10026, 10024, 10025, -1, 10026, 10015, 10024, -1, 10026, 10008, 10007, -1, 10026, 10021, 10020, -1, 10027, 10028, 10029, -1, 10030, 10031, 10032, -1, 10033, 10030, 10032, -1, 10034, 10035, 10036, -1, 10034, 10036, 10037, -1, 10034, 10037, 10038, -1, 10039, 10040, 10035, -1, 10039, 10041, 10040, -1, 10039, 10035, 10034, -1, 10042, 10038, 10028, -1, 10042, 10027, 10043, -1, 10042, 10034, 10038, -1, 10042, 10028, 10027, -1, 10044, 10045, 10046, -1, 10044, 10046, 10047, -1, 10044, 10047, 10041, -1, 10044, 10041, 10039, -1, 10048, 10043, 10049, -1, 10048, 10042, 10043, -1, 10048, 10034, 10042, -1, 10048, 10039, 10034, -1, 10050, 10049, 10031, -1, 10050, 10030, 10045, -1, 10050, 10044, 10039, -1, 10050, 10048, 10049, -1, 10050, 10039, 10048, -1, 10050, 10031, 10030, -1, 10050, 10045, 10044, -1, 10051, 10052, 10053, -1, 10054, 10055, 10056, -1, 10057, 10058, 10059, -1, 10057, 10059, 10052, -1, 10057, 10051, 10060, -1, 10057, 10052, 10051, -1, 10061, 10062, 10058, -1, 10061, 10058, 10057, -1, 10063, 10060, 10064, -1, 10063, 10064, 10065, -1, 10063, 10057, 10060, -1, 10066, 10067, 10054, -1, 10066, 10056, 10062, -1, 10066, 10062, 10061, -1, 10066, 10054, 10056, -1, 10068, 10065, 10069, -1, 10068, 10069, 10070, -1, 10068, 10070, 10071, -1, 10068, 10063, 10065, -1, 10068, 10057, 10063, -1, 10068, 10061, 10057, -1, 10072, 10071, 10073, -1, 10072, 10073, 10074, -1, 10072, 10074, 10067, -1, 10072, 10067, 10066, -1, 10072, 10068, 10071, -1, 10072, 10066, 10061, -1, 10072, 10061, 10068, -1, 10075, 10076, 10077, -1, 10075, 10077, 10078, -1, 10079, 10075, 10078, -1, 10080, 10076, 10075, -1, 10081, 10079, 10078, -1, 10082, 10079, 10081, -1, 10083, 10080, 10075, -1, 10084, 10082, 10081, -1, 10085, 10084, 10081, -1, 10086, 10080, 10083, -1, 10087, 10088, 10089, -1, 10087, 10089, 10086, -1, 10090, 10091, 10084, -1, 10090, 10084, 10085, -1, 10092, 10093, 10088, -1, 10094, 10093, 10092, -1, 10095, 10094, 10092, -1, 10096, 10091, 10090, -1, 10097, 10091, 10096, -1, 10098, 10095, 10099, -1, 10098, 10094, 10095, -1, 10100, 10097, 10096, -1, 10101, 10098, 10099, -1, 10102, 10103, 10097, -1, 10102, 10097, 10100, -1, 10104, 10103, 10102, -1, 10105, 10098, 10101, -1, 10087, 10092, 10088, -1, 10106, 10083, 10107, -1, 10106, 10107, 10087, -1, 10106, 10086, 10083, -1, 10106, 10087, 10086, -1, 10108, 10101, 10103, -1, 10108, 10104, 10105, -1, 10108, 10105, 10101, -1, 10108, 10103, 10104, -1, 10109, 10110, 10111, -1, 10112, 10113, 10114, -1, 10115, 10116, 10117, -1, 10115, 10117, 10110, -1, 10115, 10109, 10118, -1, 10115, 10110, 10109, -1, 10119, 10120, 10116, -1, 10119, 10116, 10115, -1, 10121, 10118, 10122, -1, 10121, 10122, 10123, -1, 10121, 10115, 10118, -1, 10124, 10125, 10112, -1, 10124, 10114, 10120, -1, 10124, 10120, 10119, -1, 10124, 10112, 10114, -1, 10126, 10127, 10128, -1, 10126, 10123, 10129, -1, 10126, 10129, 10127, -1, 10126, 10121, 10123, -1, 10126, 10115, 10121, -1, 10126, 10119, 10115, -1, 10130, 10128, 10131, -1, 10130, 10131, 10132, -1, 10130, 10132, 10125, -1, 10130, 10119, 10126, -1, 10130, 10126, 10128, -1, 10130, 10125, 10124, -1, 10130, 10124, 10119, -1, 10133, 10134, 10135, -1, 10133, 10135, 10136, -1, 10137, 10133, 10136, -1, 10138, 10134, 10133, -1, 10139, 10137, 10136, -1, 10140, 10137, 10139, -1, 10141, 10138, 10133, -1, 10142, 10139, 10143, -1, 10142, 10140, 10139, -1, 10144, 10138, 10141, -1, 10145, 10146, 10147, -1, 10148, 10149, 10142, -1, 10148, 10142, 10143, -1, 10150, 10151, 10146, -1, 10152, 10151, 10150, -1, 10153, 10152, 10150, -1, 10154, 10149, 10148, -1, 10155, 10149, 10154, -1, 10156, 10153, 10157, -1, 10156, 10152, 10153, -1, 10158, 10155, 10154, -1, 10159, 10156, 10157, -1, 10160, 10161, 10155, -1, 10160, 10155, 10158, -1, 10162, 10161, 10160, -1, 10163, 10156, 10159, -1, 10145, 10150, 10146, -1, 10164, 10141, 10165, -1, 10164, 10165, 10145, -1, 10164, 10147, 10144, -1, 10164, 10145, 10147, -1, 10164, 10144, 10141, -1, 10166, 10159, 10161, -1, 10166, 10162, 10163, -1, 10166, 10163, 10159, -1, 10166, 10161, 10162, -1, 10167, 10168, 10169, -1, 10170, 10171, 10172, -1, 10173, 10170, 10172, -1, 10174, 10175, 10176, -1, 10174, 10176, 10177, -1, 10174, 10177, 10178, -1, 10179, 10180, 10175, -1, 10179, 10181, 10180, -1, 10179, 10175, 10174, -1, 10182, 10178, 10168, -1, 10182, 10167, 10183, -1, 10182, 10174, 10178, -1, 10182, 10168, 10167, -1, 10184, 10185, 10186, -1, 10184, 10186, 10187, -1, 10184, 10187, 10181, -1, 10184, 10181, 10179, -1, 10188, 10183, 10189, -1, 10188, 10182, 10183, -1, 10188, 10174, 10182, -1, 10188, 10179, 10174, -1, 10190, 10189, 10171, -1, 10190, 10170, 10185, -1, 10190, 10184, 10179, -1, 10190, 10188, 10189, -1, 10190, 10179, 10188, -1, 10190, 10171, 10170, -1, 10190, 10185, 10184, -1, 10191, 10192, 10193, -1, 10194, 10195, 10196, -1, 10197, 10195, 10194, -1, 10198, 10199, 10200, -1, 10198, 10200, 10201, -1, 10198, 10201, 10202, -1, 10203, 10204, 10205, -1, 10203, 10205, 10199, -1, 10203, 10199, 10198, -1, 10206, 10202, 10192, -1, 10206, 10191, 10207, -1, 10206, 10192, 10191, -1, 10206, 10198, 10202, -1, 10208, 10209, 10210, -1, 10208, 10210, 10211, -1, 10208, 10211, 10204, -1, 10208, 10204, 10203, -1, 10212, 10207, 10213, -1, 10212, 10206, 10207, -1, 10212, 10198, 10206, -1, 10212, 10203, 10198, -1, 10214, 10213, 10196, -1, 10214, 10195, 10209, -1, 10214, 10212, 10213, -1, 10214, 10208, 10203, -1, 10214, 10203, 10212, -1, 10214, 10196, 10195, -1, 10214, 10209, 10208, -1, 10215, 10216, 10217, -1, 10218, 10219, 10220, -1, 10221, 10217, 10222, -1, 10221, 10222, 10223, -1, 10221, 10224, 10215, -1, 10221, 10215, 10217, -1, 10225, 10223, 10219, -1, 10225, 10218, 10226, -1, 10225, 10226, 10224, -1, 10225, 10221, 10223, -1, 10225, 10219, 10218, -1, 10225, 10224, 10221, -1, 10227, 10228, 10229, -1, 10230, 10231, 10232, -1, 10233, 10231, 10230, -1, 10234, 10235, 10236, -1, 10234, 10236, 10237, -1, 10234, 10237, 10238, -1, 10239, 10240, 10235, -1, 10239, 10241, 10240, -1, 10239, 10235, 10234, -1, 10242, 10238, 10228, -1, 10242, 10227, 10243, -1, 10242, 10234, 10238, -1, 10242, 10228, 10227, -1, 10244, 10245, 10246, -1, 10244, 10246, 10247, -1, 10244, 10247, 10241, -1, 10244, 10241, 10239, -1, 10248, 10243, 10249, -1, 10248, 10242, 10243, -1, 10248, 10234, 10242, -1, 10248, 10239, 10234, -1, 10250, 10249, 10232, -1, 10250, 10231, 10245, -1, 10250, 10244, 10239, -1, 10250, 10248, 10249, -1, 10250, 10239, 10248, -1, 10250, 10232, 10231, -1, 10250, 10245, 10244, -1, 10251, 10252, 10253, -1, 10254, 10255, 10256, -1, 10257, 10255, 10254, -1, 10258, 10259, 10260, -1, 10258, 10260, 10261, -1, 10258, 10261, 10262, -1, 10263, 10264, 10265, -1, 10263, 10265, 10259, -1, 10263, 10259, 10258, -1, 10266, 10262, 10252, -1, 10266, 10251, 10267, -1, 10266, 10252, 10251, -1, 10266, 10258, 10262, -1, 10268, 10269, 10270, -1, 10268, 10270, 10271, -1, 10268, 10271, 10264, -1, 10268, 10264, 10263, -1, 10272, 10267, 10273, -1, 10272, 10266, 10267, -1, 10272, 10258, 10266, -1, 10272, 10263, 10258, -1, 10274, 10273, 10256, -1, 10274, 10255, 10269, -1, 10274, 10272, 10273, -1, 10274, 10268, 10263, -1, 10274, 10263, 10272, -1, 10274, 10256, 10255, -1, 10274, 10269, 10268, -1, 10275, 10276, 10277, -1, 10275, 10277, 10278, -1, 10279, 10275, 10278, -1, 10280, 10276, 10275, -1, 10281, 10279, 10278, -1, 10282, 10279, 10281, -1, 10283, 10280, 10275, -1, 10284, 10281, 10285, -1, 10284, 10282, 10281, -1, 10286, 10280, 10283, -1, 10287, 10288, 10289, -1, 10290, 10291, 10284, -1, 10290, 10284, 10285, -1, 10292, 10293, 10288, -1, 10294, 10293, 10292, -1, 10295, 10294, 10292, -1, 10296, 10291, 10290, -1, 10297, 10291, 10296, -1, 10298, 10295, 10299, -1, 10298, 10294, 10295, -1, 10300, 10297, 10296, -1, 10301, 10298, 10299, -1, 10302, 10303, 10297, -1, 10302, 10297, 10300, -1, 10304, 10303, 10302, -1, 10305, 10298, 10301, -1, 10287, 10292, 10288, -1, 10306, 10283, 10307, -1, 10306, 10307, 10287, -1, 10306, 10289, 10286, -1, 10306, 10287, 10289, -1, 10306, 10286, 10283, -1, 10308, 10301, 10303, -1, 10308, 10304, 10305, -1, 10308, 10305, 10301, -1, 10308, 10303, 10304, -1, 10309, 10310, 10311, -1, 10309, 10311, 10312, -1, 10313, 10309, 10312, -1, 10314, 10310, 10309, -1, 10315, 10313, 10312, -1, 10316, 10313, 10315, -1, 10317, 10314, 10309, -1, 10318, 10316, 10315, -1, 10319, 10318, 10315, -1, 10320, 10314, 10317, -1, 10321, 10322, 10323, -1, 10321, 10323, 10320, -1, 10324, 10325, 10318, -1, 10324, 10318, 10319, -1, 10326, 10327, 10322, -1, 10328, 10327, 10326, -1, 10329, 10328, 10326, -1, 10330, 10325, 10324, -1, 10331, 10325, 10330, -1, 10332, 10329, 10333, -1, 10332, 10328, 10329, -1, 10334, 10331, 10330, -1, 10335, 10332, 10333, -1, 10336, 10337, 10331, -1, 10336, 10331, 10334, -1, 10338, 10337, 10336, -1, 10339, 10332, 10335, -1, 10321, 10326, 10322, -1, 10340, 10317, 10341, -1, 10340, 10341, 10321, -1, 10340, 10320, 10317, -1, 10340, 10321, 10320, -1, 10342, 10335, 10337, -1, 10342, 10338, 10339, -1, 10342, 10339, 10335, -1, 10342, 10337, 10338, -1, 10343, 10344, 10345, -1, 10346, 10347, 10348, -1, 10349, 10350, 10351, -1, 10349, 10351, 10344, -1, 10349, 10343, 10352, -1, 10349, 10344, 10343, -1, 10353, 10354, 10350, -1, 10353, 10350, 10349, -1, 10355, 10352, 10356, -1, 10355, 10356, 10357, -1, 10355, 10349, 10352, -1, 10358, 10359, 10346, -1, 10358, 10348, 10354, -1, 10358, 10354, 10353, -1, 10358, 10346, 10348, -1, 10360, 10361, 10362, -1, 10360, 10357, 10363, -1, 10360, 10363, 10361, -1, 10360, 10355, 10357, -1, 10360, 10349, 10355, -1, 10360, 10353, 10349, -1, 10364, 10362, 10365, -1, 10364, 10365, 10366, -1, 10364, 10366, 10359, -1, 10364, 10353, 10360, -1, 10364, 10360, 10362, -1, 10364, 10359, 10358, -1, 10364, 10358, 10353, -1, 10367, 10368, 10369, -1, 10370, 10371, 10372, -1, 10373, 10374, 10375, -1, 10373, 10375, 10368, -1, 10373, 10367, 10376, -1, 10373, 10368, 10367, -1, 10377, 10378, 10374, -1, 10377, 10374, 10373, -1, 10379, 10376, 10380, -1, 10379, 10380, 10381, -1, 10379, 10373, 10376, -1, 10382, 10383, 10370, -1, 10382, 10372, 10378, -1, 10382, 10378, 10377, -1, 10382, 10370, 10372, -1, 10384, 10381, 10385, -1, 10384, 10385, 10386, -1, 10384, 10386, 10387, -1, 10384, 10379, 10381, -1, 10384, 10373, 10379, -1, 10384, 10377, 10373, -1, 10388, 10387, 10389, -1, 10388, 10389, 10390, -1, 10388, 10390, 10383, -1, 10388, 10383, 10382, -1, 10388, 10384, 10387, -1, 10388, 10382, 10377, -1, 10388, 10377, 10384, -1, 10391, 10392, 10393, -1, 10394, 10395, 10396, -1, 10397, 10393, 10398, -1, 10397, 10398, 10399, -1, 10397, 10400, 10391, -1, 10397, 10391, 10393, -1, 10401, 10399, 10395, -1, 10401, 10394, 10402, -1, 10401, 10402, 10400, -1, 10401, 10397, 10399, -1, 10401, 10395, 10394, -1, 10401, 10400, 10397, -1, 10403, 10404, 10405, -1, 10406, 10407, 10408, -1, 10409, 10406, 10408, -1, 10410, 10411, 10412, -1, 10410, 10412, 10413, -1, 10410, 10413, 10414, -1, 10415, 10416, 10417, -1, 10415, 10417, 10411, -1, 10415, 10411, 10410, -1, 10418, 10414, 10404, -1, 10418, 10403, 10419, -1, 10418, 10404, 10403, -1, 10418, 10410, 10414, -1, 10420, 10421, 10422, -1, 10420, 10422, 10423, -1, 10420, 10423, 10416, -1, 10420, 10416, 10415, -1, 10424, 10419, 10425, -1, 10424, 10418, 10419, -1, 10424, 10410, 10418, -1, 10424, 10415, 10410, -1, 10426, 10425, 10407, -1, 10426, 10406, 10421, -1, 10426, 10424, 10425, -1, 10426, 10420, 10415, -1, 10426, 10415, 10424, -1, 10426, 10407, 10406, -1, 10426, 10421, 10420, -1, 10427, 10428, 10429, -1, 10430, 10431, 10432, -1, 10433, 10431, 10430, -1, 10434, 10435, 10436, -1, 10434, 10436, 10437, -1, 10434, 10437, 10438, -1, 10439, 10440, 10441, -1, 10439, 10441, 10435, -1, 10439, 10435, 10434, -1, 10442, 10438, 10428, -1, 10442, 10427, 10443, -1, 10442, 10428, 10427, -1, 10442, 10434, 10438, -1, 10444, 10445, 10446, -1, 10444, 10446, 10447, -1, 10444, 10447, 10440, -1, 10444, 10440, 10439, -1, 10448, 10443, 10449, -1, 10448, 10442, 10443, -1, 10448, 10434, 10442, -1, 10448, 10439, 10434, -1, 10450, 10449, 10432, -1, 10450, 10431, 10445, -1, 10450, 10448, 10449, -1, 10450, 10444, 10439, -1, 10450, 10439, 10448, -1, 10450, 10432, 10431, -1, 10450, 10445, 10444, -1, 10451, 10452, 10453, -1, 10454, 10455, 10456, -1, 10457, 10455, 10454, -1, 10458, 10459, 10460, -1, 10458, 10460, 10461, -1, 10458, 10461, 10462, -1, 10463, 10464, 10465, -1, 10463, 10465, 10459, -1, 10463, 10459, 10458, -1, 10466, 10462, 10452, -1, 10466, 10451, 10467, -1, 10466, 10452, 10451, -1, 10466, 10458, 10462, -1, 10468, 10469, 10470, -1, 10468, 10470, 10471, -1, 10468, 10471, 10464, -1, 10468, 10464, 10463, -1, 10472, 10467, 10473, -1, 10472, 10466, 10467, -1, 10472, 10458, 10466, -1, 10472, 10463, 10458, -1, 10474, 10473, 10456, -1, 10474, 10455, 10469, -1, 10474, 10472, 10473, -1, 10474, 10468, 10463, -1, 10474, 10463, 10472, -1, 10474, 10456, 10455, -1, 10474, 10469, 10468, -1, 10475, 10476, 10477, -1, 10478, 10479, 10480, -1, 10481, 10479, 10478, -1, 10482, 10483, 10484, -1, 10482, 10484, 10485, -1, 10482, 10485, 10486, -1, 10487, 10488, 10489, -1, 10487, 10489, 10483, -1, 10487, 10483, 10482, -1, 10490, 10486, 10476, -1, 10490, 10475, 10491, -1, 10490, 10476, 10475, -1, 10490, 10482, 10486, -1, 10492, 10493, 10494, -1, 10492, 10494, 10495, -1, 10492, 10495, 10488, -1, 10492, 10488, 10487, -1, 10496, 10491, 10497, -1, 10496, 10490, 10491, -1, 10496, 10482, 10490, -1, 10496, 10487, 10482, -1, 10498, 10497, 10480, -1, 10498, 10479, 10493, -1, 10498, 10496, 10497, -1, 10498, 10492, 10487, -1, 10498, 10487, 10496, -1, 10498, 10480, 10479, -1, 10498, 10493, 10492, -1, 10499, 10500, 10501, -1, 10502, 10503, 10504, -1, 10505, 10501, 10506, -1, 10505, 10506, 10507, -1, 10505, 10508, 10499, -1, 10505, 10499, 10501, -1, 10509, 10507, 10503, -1, 10509, 10502, 10510, -1, 10509, 10510, 10508, -1, 10509, 10505, 10507, -1, 10509, 10508, 10505, -1, 10509, 10503, 10502, -1, 10511, 10512, 10513, -1, 10514, 10515, 10516, -1, 10517, 10514, 10516, -1, 10518, 10519, 10520, -1, 10518, 10520, 10521, -1, 10518, 10521, 10522, -1, 10523, 10524, 10525, -1, 10523, 10525, 10519, -1, 10523, 10519, 10518, -1, 10526, 10522, 10512, -1, 10526, 10511, 10527, -1, 10526, 10512, 10511, -1, 10526, 10518, 10522, -1, 10528, 10529, 10530, -1, 10528, 10530, 10531, -1, 10528, 10531, 10524, -1, 10528, 10524, 10523, -1, 10532, 10527, 10533, -1, 10532, 10526, 10527, -1, 10532, 10518, 10526, -1, 10532, 10523, 10518, -1, 10534, 10533, 10515, -1, 10534, 10514, 10529, -1, 10534, 10532, 10533, -1, 10534, 10528, 10523, -1, 10534, 10523, 10532, -1, 10534, 10515, 10514, -1, 10534, 10529, 10528, -1, 10535, 10536, 10537, -1, 10538, 10539, 10540, -1, 10541, 10539, 10538, -1, 10542, 10543, 10544, -1, 10542, 10544, 10545, -1, 10542, 10545, 10546, -1, 10547, 10548, 10543, -1, 10547, 10549, 10548, -1, 10547, 10543, 10542, -1, 10550, 10546, 10536, -1, 10550, 10535, 10551, -1, 10550, 10542, 10546, -1, 10550, 10536, 10535, -1, 10552, 10553, 10554, -1, 10552, 10554, 10555, -1, 10552, 10555, 10549, -1, 10552, 10549, 10547, -1, 10556, 10551, 10557, -1, 10556, 10550, 10551, -1, 10556, 10542, 10550, -1, 10556, 10547, 10542, -1, 10558, 10557, 10540, -1, 10558, 10539, 10553, -1, 10558, 10552, 10547, -1, 10558, 10556, 10557, -1, 10558, 10547, 10556, -1, 10558, 10540, 10539, -1, 10558, 10553, 10552, -1, 10559, 10560, 10561, -1, 10562, 10563, 10564, -1, 10565, 10563, 10562, -1, 10566, 10567, 10568, -1, 10566, 10568, 10569, -1, 10566, 10569, 10570, -1, 10571, 10572, 10567, -1, 10571, 10573, 10572, -1, 10571, 10567, 10566, -1, 10574, 10570, 10560, -1, 10574, 10559, 10575, -1, 10574, 10566, 10570, -1, 10574, 10560, 10559, -1, 10576, 10577, 10578, -1, 10576, 10578, 10579, -1, 10576, 10579, 10573, -1, 10576, 10573, 10571, -1, 10580, 10575, 10581, -1, 10580, 10574, 10575, -1, 10580, 10566, 10574, -1, 10580, 10571, 10566, -1, 10582, 10581, 10564, -1, 10582, 10563, 10577, -1, 10582, 10576, 10571, -1, 10582, 10580, 10581, -1, 10582, 10571, 10580, -1, 10582, 10564, 10563, -1, 10582, 10577, 10576, -1, 10583, 10584, 10585, -1, 10586, 10587, 10588, -1, 10589, 10587, 10586, -1, 10590, 10591, 10592, -1, 10590, 10592, 10593, -1, 10590, 10593, 10594, -1, 10595, 10596, 10597, -1, 10595, 10597, 10591, -1, 10595, 10591, 10590, -1, 10598, 10594, 10584, -1, 10598, 10583, 10599, -1, 10598, 10584, 10583, -1, 10598, 10590, 10594, -1, 10600, 10601, 10602, -1, 10600, 10602, 10603, -1, 10600, 10603, 10596, -1, 10600, 10596, 10595, -1, 10604, 10599, 10605, -1, 10604, 10598, 10599, -1, 10604, 10590, 10598, -1, 10604, 10595, 10590, -1, 10606, 10605, 10588, -1, 10606, 10587, 10601, -1, 10606, 10604, 10605, -1, 10606, 10600, 10595, -1, 10606, 10595, 10604, -1, 10606, 10588, 10587, -1, 10606, 10601, 10600, -1, 10607, 10608, 10609, -1, 10607, 10609, 10610, -1, 10611, 10607, 10610, -1, 10612, 10608, 10607, -1, 10613, 10611, 10610, -1, 10614, 10611, 10613, -1, 10615, 10612, 10607, -1, 10616, 10613, 10617, -1, 10616, 10614, 10613, -1, 10618, 10612, 10615, -1, 10619, 10620, 10621, -1, 10622, 10623, 10616, -1, 10622, 10616, 10617, -1, 10624, 10625, 10620, -1, 10626, 10625, 10624, -1, 10627, 10626, 10624, -1, 10628, 10623, 10622, -1, 10629, 10623, 10628, -1, 10630, 10627, 10631, -1, 10630, 10626, 10627, -1, 10632, 10629, 10628, -1, 10633, 10630, 10631, -1, 10634, 10635, 10629, -1, 10634, 10629, 10632, -1, 10636, 10635, 10634, -1, 10637, 10630, 10633, -1, 10619, 10624, 10620, -1, 10638, 10615, 10639, -1, 10638, 10639, 10619, -1, 10638, 10621, 10618, -1, 10638, 10619, 10621, -1, 10638, 10618, 10615, -1, 10640, 10633, 10635, -1, 10640, 10636, 10637, -1, 10640, 10637, 10633, -1, 10640, 10635, 10636, -1, 10641, 10642, 10643, -1, 10644, 10645, 10646, -1, 10647, 10648, 10649, -1, 10647, 10649, 10642, -1, 10647, 10641, 10650, -1, 10647, 10642, 10641, -1, 10651, 10652, 10648, -1, 10651, 10648, 10647, -1, 10653, 10650, 10654, -1, 10653, 10654, 10655, -1, 10653, 10647, 10650, -1, 10656, 10657, 10644, -1, 10656, 10646, 10652, -1, 10656, 10644, 10646, -1, 10656, 10652, 10651, -1, 10658, 10655, 10659, -1, 10658, 10659, 10660, -1, 10658, 10660, 10661, -1, 10658, 10653, 10655, -1, 10658, 10651, 10647, -1, 10658, 10647, 10653, -1, 10662, 10661, 10663, -1, 10662, 10663, 10664, -1, 10662, 10664, 10657, -1, 10662, 10658, 10661, -1, 10662, 10657, 10656, -1, 10662, 10656, 10651, -1, 10662, 10651, 10658, -1, 10665, 10666, 10667, -1, 10665, 10667, 10668, -1, 10669, 10665, 10668, -1, 10670, 10666, 10665, -1, 10671, 10669, 10668, -1, 10672, 10669, 10671, -1, 10673, 10670, 10665, -1, 10674, 10672, 10671, -1, 10675, 10674, 10671, -1, 10676, 10670, 10673, -1, 10677, 10678, 10679, -1, 10677, 10679, 10676, -1, 10680, 10681, 10674, -1, 10680, 10674, 10675, -1, 10682, 10683, 10678, -1, 10684, 10683, 10682, -1, 10685, 10684, 10682, -1, 10686, 10681, 10680, -1, 10687, 10681, 10686, -1, 10688, 10685, 10689, -1, 10688, 10684, 10685, -1, 10690, 10687, 10686, -1, 10691, 10688, 10689, -1, 10692, 10693, 10687, -1, 10692, 10687, 10690, -1, 10694, 10693, 10692, -1, 10695, 10688, 10691, -1, 10677, 10682, 10678, -1, 10696, 10673, 10697, -1, 10696, 10697, 10677, -1, 10696, 10676, 10673, -1, 10696, 10677, 10676, -1, 10698, 10691, 10693, -1, 10698, 10694, 10695, -1, 10698, 10695, 10691, -1, 10698, 10693, 10694, -1, 10699, 10700, 10701, -1, 10702, 10703, 10704, -1, 10705, 10706, 10707, -1, 10705, 10707, 10700, -1, 10705, 10699, 10708, -1, 10705, 10700, 10699, -1, 10709, 10710, 10706, -1, 10709, 10706, 10705, -1, 10711, 10708, 10712, -1, 10711, 10712, 10713, -1, 10711, 10705, 10708, -1, 10714, 10715, 10702, -1, 10714, 10704, 10710, -1, 10714, 10710, 10709, -1, 10714, 10702, 10704, -1, 10716, 10713, 10717, -1, 10716, 10717, 10718, -1, 10716, 10718, 10719, -1, 10716, 10711, 10713, -1, 10716, 10705, 10711, -1, 10716, 10709, 10705, -1, 10720, 10719, 10721, -1, 10720, 10721, 10722, -1, 10720, 10722, 10715, -1, 10720, 10715, 10714, -1, 10720, 10716, 10719, -1, 10720, 10714, 10709, -1, 10720, 10709, 10716, -1, 10723, 10724, 10725, -1, 10726, 10727, 10728, -1, 10729, 10730, 10731, -1, 10729, 10731, 10724, -1, 10729, 10723, 10732, -1, 10729, 10724, 10723, -1, 10733, 10734, 10730, -1, 10733, 10730, 10729, -1, 10735, 10732, 10736, -1, 10735, 10736, 10737, -1, 10735, 10729, 10732, -1, 10738, 10739, 10726, -1, 10738, 10728, 10734, -1, 10738, 10726, 10728, -1, 10738, 10734, 10733, -1, 10740, 10737, 10741, -1, 10740, 10741, 10742, -1, 10740, 10742, 10743, -1, 10740, 10735, 10737, -1, 10740, 10733, 10729, -1, 10740, 10729, 10735, -1, 10744, 10743, 10745, -1, 10744, 10745, 10746, -1, 10744, 10746, 10739, -1, 10744, 10740, 10743, -1, 10744, 10739, 10738, -1, 10744, 10738, 10733, -1, 10744, 10733, 10740, -1, 10747, 10748, 10749, -1, 10747, 10749, 10750, -1, 10751, 10747, 10750, -1, 10752, 10748, 10747, -1, 10753, 10751, 10750, -1, 10754, 10751, 10753, -1, 10755, 10752, 10747, -1, 10756, 10753, 10757, -1, 10756, 10754, 10753, -1, 10758, 10752, 10755, -1, 10759, 10760, 10761, -1, 10762, 10763, 10756, -1, 10762, 10756, 10757, -1, 10764, 10765, 10760, -1, 10766, 10765, 10764, -1, 10767, 10766, 10764, -1, 10768, 10763, 10762, -1, 10769, 10763, 10768, -1, 10770, 10767, 10771, -1, 10770, 10766, 10767, -1, 10772, 10769, 10768, -1, 10773, 10770, 10771, -1, 10774, 10775, 10769, -1, 10774, 10769, 10772, -1, 10776, 10775, 10774, -1, 10777, 10770, 10773, -1, 10759, 10764, 10760, -1, 10778, 10755, 10779, -1, 10778, 10779, 10759, -1, 10778, 10761, 10758, -1, 10778, 10759, 10761, -1, 10778, 10758, 10755, -1, 10780, 10773, 10775, -1, 10780, 10776, 10777, -1, 10780, 10777, 10773, -1, 10780, 10775, 10776, -1, 10781, 10782, 10783, -1, 10784, 10785, 10786, -1, 10787, 10788, 10789, -1, 10787, 10789, 10782, -1, 10787, 10781, 10790, -1, 10787, 10782, 10781, -1, 10791, 10792, 10788, -1, 10791, 10788, 10787, -1, 10793, 10790, 10794, -1, 10793, 10794, 10795, -1, 10793, 10787, 10790, -1, 10796, 10797, 10784, -1, 10796, 10786, 10792, -1, 10796, 10792, 10791, -1, 10796, 10784, 10786, -1, 10798, 10795, 10799, -1, 10798, 10799, 10800, -1, 10798, 10800, 10801, -1, 10798, 10793, 10795, -1, 10798, 10787, 10793, -1, 10798, 10791, 10787, -1, 10802, 10801, 10803, -1, 10802, 10803, 10804, -1, 10802, 10804, 10797, -1, 10802, 10797, 10796, -1, 10802, 10798, 10801, -1, 10802, 10796, 10791, -1, 10802, 10791, 10798, -1, 10805, 10806, 10807, -1, 10805, 10807, 10808, -1, 10809, 10805, 10808, -1, 10810, 10806, 10805, -1, 10811, 10809, 10808, -1, 10812, 10809, 10811, -1, 10813, 10810, 10805, -1, 10814, 10812, 10811, -1, 10815, 10814, 10811, -1, 10816, 10810, 10813, -1, 10817, 10818, 10819, -1, 10817, 10819, 10816, -1, 10820, 10821, 10814, -1, 10820, 10814, 10815, -1, 10822, 10823, 10818, -1, 10824, 10823, 10822, -1, 10825, 10824, 10822, -1, 10826, 10821, 10820, -1, 10827, 10821, 10826, -1, 10828, 10825, 10829, -1, 10828, 10824, 10825, -1, 10830, 10827, 10826, -1, 10831, 10828, 10829, -1, 10832, 10833, 10827, -1, 10832, 10827, 10830, -1, 10834, 10833, 10832, -1, 10835, 10828, 10831, -1, 10817, 10822, 10818, -1, 10836, 10813, 10837, -1, 10836, 10837, 10817, -1, 10836, 10816, 10813, -1, 10836, 10817, 10816, -1, 10838, 10831, 10833, -1, 10838, 10834, 10835, -1, 10838, 10835, 10831, -1, 10838, 10833, 10834, -1, 10839, 10840, 10841, -1, 10842, 10843, 10844, -1, 10845, 10843, 10842, -1, 10846, 10847, 10848, -1, 10846, 10848, 10849, -1, 10846, 10849, 10850, -1, 10851, 10852, 10847, -1, 10851, 10853, 10852, -1, 10851, 10847, 10846, -1, 10854, 10850, 10840, -1, 10854, 10839, 10855, -1, 10854, 10846, 10850, -1, 10854, 10840, 10839, -1, 10856, 10857, 10858, -1, 10856, 10858, 10859, -1, 10856, 10859, 10853, -1, 10856, 10853, 10851, -1, 10860, 10855, 10861, -1, 10860, 10854, 10855, -1, 10860, 10846, 10854, -1, 10860, 10851, 10846, -1, 10862, 10861, 10844, -1, 10862, 10843, 10857, -1, 10862, 10856, 10851, -1, 10862, 10860, 10861, -1, 10862, 10851, 10860, -1, 10862, 10844, 10843, -1, 10862, 10857, 10856, -1, 10863, 10864, 10865, -1, 10866, 10867, 10868, -1, 10869, 10867, 10866, -1, 10870, 10871, 10872, -1, 10870, 10872, 10873, -1, 10870, 10873, 10874, -1, 10875, 10876, 10877, -1, 10875, 10877, 10871, -1, 10875, 10871, 10870, -1, 10878, 10874, 10864, -1, 10878, 10863, 10879, -1, 10878, 10864, 10863, -1, 10878, 10870, 10874, -1, 10880, 10881, 10882, -1, 10880, 10882, 10883, -1, 10880, 10883, 10876, -1, 10880, 10876, 10875, -1, 10884, 10879, 10885, -1, 10884, 10878, 10879, -1, 10884, 10870, 10878, -1, 10884, 10875, 10870, -1, 10886, 10885, 10868, -1, 10886, 10867, 10881, -1, 10886, 10884, 10885, -1, 10886, 10880, 10875, -1, 10886, 10875, 10884, -1, 10886, 10868, 10867, -1, 10886, 10881, 10880, -1, 10887, 10888, 10889, -1, 10890, 10891, 10892, -1, 10893, 10891, 10890, -1, 10894, 10895, 10896, -1, 10894, 10896, 10897, -1, 10894, 10897, 10898, -1, 10899, 10900, 10895, -1, 10899, 10901, 10900, -1, 10899, 10895, 10894, -1, 10902, 10898, 10888, -1, 10902, 10887, 10903, -1, 10902, 10894, 10898, -1, 10902, 10888, 10887, -1, 10904, 10905, 10906, -1, 10904, 10906, 10907, -1, 10904, 10907, 10901, -1, 10904, 10901, 10899, -1, 10908, 10903, 10909, -1, 10908, 10902, 10903, -1, 10908, 10894, 10902, -1, 10908, 10899, 10894, -1, 10910, 10909, 10892, -1, 10910, 10891, 10905, -1, 10910, 10904, 10899, -1, 10910, 10908, 10909, -1, 10910, 10899, 10908, -1, 10910, 10892, 10891, -1, 10910, 10905, 10904, -1, 10911, 10912, 10913, -1, 10914, 10915, 10916, -1, 10917, 10914, 10916, -1, 10918, 10919, 10920, -1, 10918, 10920, 10921, -1, 10918, 10921, 10922, -1, 10923, 10924, 10919, -1, 10923, 10925, 10924, -1, 10923, 10919, 10918, -1, 10926, 10922, 10912, -1, 10926, 10911, 10927, -1, 10926, 10918, 10922, -1, 10926, 10912, 10911, -1, 10928, 10929, 10930, -1, 10928, 10930, 10931, -1, 10928, 10931, 10925, -1, 10928, 10925, 10923, -1, 10932, 10927, 10933, -1, 10932, 10926, 10927, -1, 10932, 10918, 10926, -1, 10932, 10923, 10918, -1, 10934, 10933, 10915, -1, 10934, 10914, 10929, -1, 10934, 10928, 10923, -1, 10934, 10932, 10933, -1, 10934, 10923, 10932, -1, 10934, 10915, 10914, -1, 10934, 10929, 10928, -1, 10935, 10936, 10937, -1, 10938, 10939, 10940, -1, 10941, 10937, 10942, -1, 10941, 10942, 10943, -1, 10941, 10944, 10935, -1, 10941, 10935, 10937, -1, 10945, 10943, 10939, -1, 10945, 10938, 10946, -1, 10945, 10946, 10944, -1, 10945, 10941, 10943, -1, 10945, 10939, 10938, -1, 10945, 10944, 10941, -1, 10947, 10948, 10949, -1, 10950, 10951, 10952, -1, 10953, 10951, 10950, -1, 10954, 10955, 10956, -1, 10954, 10956, 10957, -1, 10954, 10957, 10958, -1, 10959, 10960, 10961, -1, 10959, 10961, 10955, -1, 10959, 10955, 10954, -1, 10962, 10958, 10948, -1, 10962, 10947, 10963, -1, 10962, 10948, 10947, -1, 10962, 10954, 10958, -1, 10964, 10965, 10966, -1, 10964, 10966, 10967, -1, 10964, 10967, 10960, -1, 10964, 10960, 10959, -1, 10968, 10963, 10969, -1, 10968, 10962, 10963, -1, 10968, 10954, 10962, -1, 10968, 10959, 10954, -1, 10970, 10969, 10952, -1, 10970, 10951, 10965, -1, 10970, 10968, 10969, -1, 10970, 10964, 10959, -1, 10970, 10959, 10968, -1, 10970, 10952, 10951, -1, 10970, 10965, 10964, -1, 10971, 10972, 10973, -1, 10974, 10975, 10976, -1, 10977, 10975, 10974, -1, 10978, 10979, 10980, -1, 10978, 10980, 10981, -1, 10978, 10981, 10982, -1, 10983, 10984, 10985, -1, 10983, 10985, 10979, -1, 10983, 10979, 10978, -1, 10986, 10982, 10972, -1, 10986, 10971, 10987, -1, 10986, 10972, 10971, -1, 10986, 10978, 10982, -1, 10988, 10989, 10990, -1, 10988, 10990, 10991, -1, 10988, 10991, 10984, -1, 10988, 10984, 10983, -1, 10992, 10987, 10993, -1, 10992, 10986, 10987, -1, 10992, 10978, 10986, -1, 10992, 10983, 10978, -1, 10994, 10993, 10976, -1, 10994, 10975, 10989, -1, 10994, 10992, 10993, -1, 10994, 10988, 10983, -1, 10994, 10983, 10992, -1, 10994, 10976, 10975, -1, 10994, 10989, 10988, -1, 10995, 10996, 10997, -1, 10998, 10999, 11000, -1, 11001, 11002, 11003, -1, 11001, 11003, 10995, -1, 11001, 10997, 11004, -1, 11001, 10995, 10997, -1, 11005, 11006, 11000, -1, 11005, 10999, 11002, -1, 11005, 11004, 11006, -1, 11005, 11001, 11004, -1, 11005, 11002, 11001, -1, 11005, 11000, 10999, -1, 11007, 11008, 11009, -1, 11010, 11011, 11012, -1, 11013, 11010, 11012, -1, 11014, 11015, 11016, -1, 11014, 11016, 11017, -1, 11014, 11017, 11018, -1, 11019, 11020, 11021, -1, 11019, 11021, 11015, -1, 11019, 11015, 11014, -1, 11022, 11018, 11008, -1, 11022, 11007, 11023, -1, 11022, 11008, 11007, -1, 11022, 11014, 11018, -1, 11024, 11025, 11026, -1, 11024, 11026, 11027, -1, 11024, 11027, 11020, -1, 11024, 11020, 11019, -1, 11028, 11023, 11029, -1, 11028, 11022, 11023, -1, 11028, 11014, 11022, -1, 11028, 11019, 11014, -1, 11030, 11029, 11011, -1, 11030, 11010, 11025, -1, 11030, 11028, 11029, -1, 11030, 11024, 11019, -1, 11030, 11019, 11028, -1, 11030, 11011, 11010, -1, 11030, 11025, 11024, -1, 11031, 11032, 11033, -1, 11034, 11035, 11036, -1, 11037, 11035, 11034, -1, 11038, 11039, 11040, -1, 11038, 11040, 11041, -1, 11038, 11041, 11042, -1, 11043, 11044, 11039, -1, 11043, 11045, 11044, -1, 11043, 11039, 11038, -1, 11046, 11042, 11032, -1, 11046, 11031, 11047, -1, 11046, 11038, 11042, -1, 11046, 11032, 11031, -1, 11048, 11049, 11050, -1, 11048, 11050, 11051, -1, 11048, 11051, 11045, -1, 11048, 11045, 11043, -1, 11052, 11047, 11053, -1, 11052, 11046, 11047, -1, 11052, 11038, 11046, -1, 11052, 11043, 11038, -1, 11054, 11053, 11036, -1, 11054, 11035, 11049, -1, 11054, 11048, 11043, -1, 11054, 11052, 11053, -1, 11054, 11043, 11052, -1, 11054, 11036, 11035, -1, 11054, 11049, 11048, -1, 11055, 11056, 11057, -1, 11058, 11059, 11060, -1, 11061, 11059, 11058, -1, 11062, 11063, 11064, -1, 11062, 11064, 11065, -1, 11062, 11065, 11066, -1, 11067, 11068, 11069, -1, 11067, 11069, 11063, -1, 11067, 11063, 11062, -1, 11070, 11066, 11056, -1, 11070, 11055, 11071, -1, 11070, 11056, 11055, -1, 11070, 11062, 11066, -1, 11072, 11073, 11074, -1, 11072, 11074, 11075, -1, 11072, 11075, 11068, -1, 11072, 11068, 11067, -1, 11076, 11071, 11077, -1, 11076, 11070, 11071, -1, 11076, 11062, 11070, -1, 11076, 11067, 11062, -1, 11078, 11077, 11060, -1, 11078, 11059, 11073, -1, 11078, 11076, 11077, -1, 11078, 11072, 11067, -1, 11078, 11067, 11076, -1, 11078, 11060, 11059, -1, 11078, 11073, 11072, -1, 11079, 11080, 11081, -1, 11082, 11083, 11084, -1, 11085, 11082, 11084, -1, 11086, 11087, 11088, -1, 11086, 11088, 11089, -1, 11086, 11089, 11090, -1, 11091, 11092, 11087, -1, 11091, 11093, 11092, -1, 11091, 11087, 11086, -1, 11094, 11090, 11080, -1, 11094, 11079, 11095, -1, 11094, 11086, 11090, -1, 11094, 11080, 11079, -1, 11096, 11097, 11098, -1, 11096, 11098, 11099, -1, 11096, 11099, 11093, -1, 11096, 11093, 11091, -1, 11100, 11095, 11101, -1, 11100, 11094, 11095, -1, 11100, 11086, 11094, -1, 11100, 11091, 11086, -1, 11102, 11101, 11083, -1, 11102, 11082, 11097, -1, 11102, 11096, 11091, -1, 11102, 11100, 11101, -1, 11102, 11091, 11100, -1, 11102, 11083, 11082, -1, 11102, 11097, 11096, -1, 11103, 11104, 11105, -1, 11106, 11107, 11108, -1, 11109, 11110, 11111, -1, 11109, 11111, 11103, -1, 11109, 11105, 11112, -1, 11109, 11103, 11105, -1, 11113, 11114, 11108, -1, 11113, 11107, 11110, -1, 11113, 11112, 11114, -1, 11113, 11109, 11112, -1, 11113, 11110, 11109, -1, 11113, 11108, 11107, -1, 11115, 11116, 11117, -1, 11118, 11119, 11120, -1, 11121, 11119, 11118, -1, 11122, 11123, 11124, -1, 11122, 11124, 11125, -1, 11122, 11125, 11126, -1, 11127, 11128, 11123, -1, 11127, 11129, 11128, -1, 11127, 11123, 11122, -1, 11130, 11126, 11116, -1, 11130, 11115, 11131, -1, 11130, 11122, 11126, -1, 11130, 11116, 11115, -1, 11132, 11133, 11134, -1, 11132, 11134, 11135, -1, 11132, 11135, 11129, -1, 11132, 11129, 11127, -1, 11136, 11131, 11137, -1, 11136, 11130, 11131, -1, 11136, 11122, 11130, -1, 11136, 11127, 11122, -1, 11138, 11137, 11120, -1, 11138, 11119, 11133, -1, 11138, 11132, 11127, -1, 11138, 11136, 11137, -1, 11138, 11127, 11136, -1, 11138, 11120, 11119, -1, 11138, 11133, 11132, -1, 11139, 11140, 11141, -1, 11142, 11143, 11144, -1, 11145, 11143, 11142, -1, 11146, 11147, 11148, -1, 11146, 11148, 11149, -1, 11146, 11149, 11150, -1, 11151, 11152, 11147, -1, 11151, 11153, 11152, -1, 11151, 11147, 11146, -1, 11154, 11150, 11140, -1, 11154, 11139, 11155, -1, 11154, 11146, 11150, -1, 11154, 11140, 11139, -1, 11156, 11157, 11158, -1, 11156, 11158, 11159, -1, 11156, 11159, 11153, -1, 11156, 11153, 11151, -1, 11160, 11155, 11161, -1, 11160, 11154, 11155, -1, 11160, 11146, 11154, -1, 11160, 11151, 11146, -1, 11162, 11161, 11144, -1, 11162, 11143, 11157, -1, 11162, 11156, 11151, -1, 11162, 11160, 11161, -1, 11162, 11151, 11160, -1, 11162, 11144, 11143, -1, 11162, 11157, 11156, -1, 11163, 11164, 11165, -1, 11163, 11165, 11166, -1, 11167, 11163, 11166, -1, 11168, 11164, 11163, -1, 11169, 11167, 11166, -1, 11170, 11167, 11169, -1, 11171, 11168, 11163, -1, 11172, 11169, 11173, -1, 11172, 11170, 11169, -1, 11174, 11168, 11171, -1, 11175, 11176, 11177, -1, 11178, 11179, 11172, -1, 11178, 11172, 11173, -1, 11180, 11181, 11176, -1, 11182, 11181, 11180, -1, 11183, 11182, 11180, -1, 11184, 11179, 11178, -1, 11185, 11179, 11184, -1, 11186, 11183, 11187, -1, 11186, 11182, 11183, -1, 11188, 11185, 11184, -1, 11189, 11186, 11187, -1, 11190, 11191, 11185, -1, 11190, 11185, 11188, -1, 11192, 11191, 11190, -1, 11193, 11186, 11189, -1, 11175, 11180, 11176, -1, 11194, 11171, 11195, -1, 11194, 11195, 11175, -1, 11194, 11177, 11174, -1, 11194, 11175, 11177, -1, 11194, 11174, 11171, -1, 11196, 11189, 11191, -1, 11196, 11192, 11193, -1, 11196, 11193, 11189, -1, 11196, 11191, 11192, -1, 11197, 11198, 11199, -1, 11200, 11201, 11202, -1, 11203, 11204, 11205, -1, 11203, 11205, 11198, -1, 11203, 11197, 11206, -1, 11203, 11198, 11197, -1, 11207, 11208, 11204, -1, 11207, 11204, 11203, -1, 11209, 11206, 11210, -1, 11209, 11210, 11211, -1, 11209, 11203, 11206, -1, 11212, 11213, 11200, -1, 11212, 11202, 11208, -1, 11212, 11200, 11202, -1, 11212, 11208, 11207, -1, 11214, 11211, 11215, -1, 11214, 11215, 11216, -1, 11214, 11216, 11217, -1, 11214, 11209, 11211, -1, 11214, 11207, 11203, -1, 11214, 11203, 11209, -1, 11218, 11217, 11219, -1, 11218, 11219, 11220, -1, 11218, 11220, 11213, -1, 11218, 11214, 11217, -1, 11218, 11213, 11212, -1, 11218, 11212, 11207, -1, 11218, 11207, 11214, -1, 11221, 11222, 11223, -1, 11224, 11225, 11226, -1, 11227, 11228, 11229, -1, 11227, 11229, 11222, -1, 11227, 11221, 11230, -1, 11227, 11222, 11221, -1, 11231, 11232, 11228, -1, 11231, 11228, 11227, -1, 11233, 11230, 11234, -1, 11233, 11234, 11235, -1, 11233, 11227, 11230, -1, 11236, 11237, 11224, -1, 11236, 11226, 11232, -1, 11236, 11232, 11231, -1, 11236, 11224, 11226, -1, 11238, 11239, 11240, -1, 11238, 11235, 11241, -1, 11238, 11241, 11239, -1, 11238, 11233, 11235, -1, 11238, 11227, 11233, -1, 11238, 11231, 11227, -1, 11242, 11240, 11243, -1, 11242, 11243, 11244, -1, 11242, 11244, 11237, -1, 11242, 11231, 11238, -1, 11242, 11238, 11240, -1, 11242, 11237, 11236, -1, 11242, 11236, 11231, -1, 11245, 11246, 11247, -1, 11245, 11247, 11248, -1, 11249, 11245, 11248, -1, 11250, 11246, 11245, -1, 11251, 11249, 11248, -1, 11252, 11249, 11251, -1, 11253, 11250, 11245, -1, 11254, 11252, 11251, -1, 11255, 11254, 11251, -1, 11256, 11250, 11253, -1, 11257, 11258, 11259, -1, 11257, 11259, 11256, -1, 11260, 11261, 11254, -1, 11260, 11254, 11255, -1, 11262, 11263, 11258, -1, 11264, 11263, 11262, -1, 11265, 11264, 11262, -1, 11266, 11261, 11260, -1, 11267, 11261, 11266, -1, 11268, 11265, 11269, -1, 11268, 11264, 11265, -1, 11270, 11267, 11266, -1, 11271, 11268, 11269, -1, 11272, 11273, 11267, -1, 11272, 11267, 11270, -1, 11274, 11273, 11272, -1, 11275, 11268, 11271, -1, 11257, 11262, 11258, -1, 11276, 11253, 11277, -1, 11276, 11277, 11257, -1, 11276, 11256, 11253, -1, 11276, 11257, 11256, -1, 11278, 11271, 11273, -1, 11278, 11274, 11275, -1, 11278, 11275, 11271, -1, 11278, 11273, 11274, -1, 3273, 3272, 4867, -1, 11279, 11280, 11281, -1, 3272, 4896, 4867, -1, 1601, 4896, 3272, -1, 11282, 11283, 11279, -1, 11279, 11283, 11280, -1, 11284, 11283, 11282, -1, 11283, 11285, 11280, -1, 1601, 3287, 4896, -1, 11284, 11286, 11283, -1, 11287, 11288, 3287, -1, 11284, 11289, 11286, -1, 3287, 4927, 4896, -1, 11290, 11291, 11292, -1, 11284, 11293, 11289, -1, 11293, 11294, 11289, -1, 11294, 11295, 11296, -1, 11297, 11298, 11299, -1, 11300, 11298, 11297, -1, 11301, 3328, 11288, -1, 3287, 3328, 4927, -1, 11288, 3328, 3287, -1, 11301, 11302, 3328, -1, 3328, 3327, 4927, -1, 11303, 11304, 11290, -1, 11305, 11304, 11303, -1, 11290, 11304, 11291, -1, 3327, 4961, 4927, -1, 11294, 11306, 11295, -1, 3327, 1706, 4961, -1, 11294, 11307, 11306, -1, 11308, 11307, 11293, -1, 11293, 11307, 11294, -1, 11299, 11309, 11310, -1, 1706, 1708, 4961, -1, 11298, 11309, 11299, -1, 11307, 11311, 11306, -1, 11312, 11313, 11314, -1, 11308, 11315, 11307, -1, 1708, 4989, 4961, -1, 11308, 11316, 11315, -1, 11317, 11316, 11308, -1, 11318, 11319, 1708, -1, 11320, 11321, 11322, -1, 11323, 11321, 11320, -1, 11317, 11324, 11316, -1, 11325, 11326, 11312, -1, 11327, 11326, 11325, -1, 11312, 11326, 11313, -1, 11324, 11328, 11329, -1, 11319, 3383, 1708, -1, 11330, 3383, 11319, -1, 1708, 3383, 4989, -1, 11330, 11331, 3383, -1, 11321, 11332, 11322, -1, 4989, 3382, 5005, -1, 3383, 3382, 4989, -1, 11322, 11332, 11333, -1, 11324, 11334, 11328, -1, 3382, 3391, 5005, -1, 11335, 11336, 11337, -1, 11324, 11338, 11334, -1, 11317, 11338, 11324, -1, 11339, 11338, 11317, -1, 3391, 3393, 5005, -1, 11338, 11340, 11334, -1, 11339, 11341, 11338, -1, 11342, 11343, 11344, -1, 3393, 4272, 5005, -1, 11343, 11345, 11344, -1, 11339, 11346, 11341, -1, 11335, 11347, 11336, -1, 11348, 11346, 11339, -1, 11349, 11347, 11335, -1, 11350, 11347, 11349, -1, 11351, 11352, 3393, -1, 11348, 11353, 11346, -1, 11345, 11354, 11355, -1, 11343, 11354, 11345, -1, 11356, 11357, 11358, -1, 11353, 11359, 11360, -1, 3393, 191, 4272, -1, 11352, 191, 3393, -1, 11361, 191, 11352, -1, 11361, 11362, 191, -1, 4272, 190, 4273, -1, 191, 190, 4272, -1, 11353, 11363, 11359, -1, 190, 205, 4273, -1, 11364, 11365, 11366, -1, 11353, 11367, 11363, -1, 11348, 11367, 11353, -1, 11368, 11367, 11348, -1, 11365, 11369, 11366, -1, 11356, 11370, 11357, -1, 11371, 11370, 11356, -1, 11372, 11370, 11371, -1, 4273, 1893, 4313, -1, 205, 1893, 4273, -1, 11367, 11373, 11363, -1, 11368, 11374, 11367, -1, 11369, 11375, 11376, -1, 11377, 11378, 11368, -1, 11365, 11375, 11369, -1, 11368, 11378, 11374, -1, 11379, 11380, 1893, -1, 11381, 11382, 11383, -1, 11377, 11384, 11378, -1, 11385, 11386, 11387, -1, 11291, 11386, 11385, -1, 1893, 368, 4313, -1, 11388, 368, 11380, -1, 11389, 11390, 11304, -1, 11380, 368, 1893, -1, 11384, 11391, 11392, -1, 11291, 11390, 11386, -1, 11388, 11393, 368, -1, 368, 367, 4313, -1, 11304, 11390, 11291, -1, 4313, 367, 4344, -1, 11298, 11394, 11309, -1, 11384, 11395, 11391, -1, 11386, 11394, 11387, -1, 11387, 11394, 11298, -1, 367, 403, 4344, -1, 11377, 11396, 11384, -1, 11384, 11396, 11395, -1, 11397, 11396, 11377, -1, 11398, 11399, 11389, -1, 11313, 11399, 11398, -1, 4344, 1962, 4388, -1, 403, 1962, 4344, -1, 11396, 11400, 11395, -1, 11389, 11399, 11390, -1, 11397, 11401, 11396, -1, 11402, 11403, 11404, -1, 11309, 11403, 11402, -1, 11397, 11405, 11401, -1, 11406, 11405, 11397, -1, 11394, 11403, 11309, -1, 11326, 11407, 11313, -1, 11408, 11409, 1962, -1, 11406, 11410, 11405, -1, 11313, 11407, 11399, -1, 11411, 11407, 11326, -1, 11404, 11412, 11321, -1, 1962, 821, 4388, -1, 11321, 11412, 11332, -1, 11409, 821, 1962, -1, 11413, 821, 11409, -1, 11410, 11414, 11415, -1, 11403, 11412, 11404, -1, 11416, 11417, 11418, -1, 11413, 11419, 821, -1, 4388, 820, 4389, -1, 821, 820, 4388, -1, 11411, 11420, 11407, -1, 11421, 11420, 11411, -1, 11336, 11420, 11421, -1, 11410, 11422, 11414, -1, 820, 900, 4389, -1, 11412, 11423, 11332, -1, 11424, 11423, 11425, -1, 11406, 11426, 11410, -1, 11332, 11423, 11424, -1, 11410, 11426, 11422, -1, 11427, 11426, 11406, -1, 4389, 981, 4406, -1, 900, 981, 4389, -1, 11426, 11428, 11422, -1, 11417, 11429, 11418, -1, 11430, 11431, 11381, -1, 11427, 11432, 11426, -1, 11433, 11431, 11430, -1, 11381, 11431, 11382, -1, 11336, 11434, 11420, -1, 11347, 11434, 11336, -1, 11435, 11434, 11347, -1, 11436, 11437, 11427, -1, 11425, 11438, 11343, -1, 11343, 11438, 11354, -1, 11427, 11437, 11432, -1, 11439, 11440, 981, -1, 11423, 11438, 11425, -1, 11436, 11441, 11437, -1, 11417, 11442, 11429, -1, 11429, 11442, 11443, -1, 11440, 1394, 981, -1, 981, 1394, 4406, -1, 11444, 1394, 11440, -1, 11441, 11445, 11446, -1, 11447, 11448, 11435, -1, 11357, 11448, 11447, -1, 11435, 11448, 11434, -1, 11444, 11449, 1394, -1, 4406, 1393, 4412, -1, 1394, 1393, 4406, -1, 1393, 1479, 4412, -1, 11450, 11451, 11452, -1, 11354, 11451, 11450, -1, 11438, 11451, 11354, -1, 11441, 11453, 11445, -1, 11454, 11455, 11456, -1, 11441, 11457, 11453, -1, 4521, 11457, 11436, -1, 11436, 11457, 11441, -1, 4521, 11458, 11457, -1, 4521, 11459, 11458, -1, 11357, 11460, 11448, -1, 4521, 3401, 11459, -1, 11461, 11460, 11370, -1, 1479, 2118, 4412, -1, 11370, 11460, 11357, -1, 11451, 11462, 11452, -1, 4412, 2118, 4442, -1, 11457, 11463, 11453, -1, 11452, 11462, 11365, -1, 11365, 11462, 11375, -1, 4521, 3399, 3401, -1, 11464, 11465, 11466, -1, 4521, 3394, 3399, -1, 4384, 3394, 4521, -1, 11461, 11467, 11460, -1, 11468, 11467, 11461, -1, 11382, 11467, 11468, -1, 11469, 11470, 2118, -1, 11471, 11472, 11473, -1, 11375, 11472, 11471, -1, 11462, 11472, 11375, -1, 4384, 3395, 3394, -1, 11464, 11474, 11465, -1, 11455, 11475, 11456, -1, 11476, 11475, 11455, -1, 11477, 11475, 11476, -1, 2118, 1940, 4442, -1, 11478, 1940, 11470, -1, 11470, 1940, 2118, -1, 11431, 11479, 11382, -1, 11382, 11479, 11467, -1, 11480, 11479, 11431, -1, 3395, 11481, 11482, -1, 4442, 1939, 4489, -1, 11473, 11483, 11417, -1, 1940, 1939, 4442, -1, 11472, 11483, 11473, -1, 11478, 11484, 1940, -1, 11417, 11483, 11442, -1, 11474, 11485, 11486, -1, 1939, 2174, 4489, -1, 11464, 11485, 11474, -1, 3395, 11487, 11481, -1, 11488, 11489, 11490, -1, 4384, 446, 3395, -1, 3395, 446, 11487, -1, 4350, 446, 4384, -1, 4489, 2173, 4493, -1, 2174, 2173, 4489, -1, 11480, 11491, 11479, -1, 4350, 438, 446, -1, 11492, 11491, 11480, -1, 11456, 11491, 11492, -1, 446, 11493, 11487, -1, 11483, 11494, 11442, -1, 11495, 11494, 11496, -1, 11442, 11494, 11495, -1, 4323, 433, 4350, -1, 4350, 433, 438, -1, 4323, 434, 433, -1, 11497, 11498, 11499, -1, 11500, 11501, 2173, -1, 11502, 3410, 11489, -1, 11503, 3410, 11502, -1, 11489, 3410, 11490, -1, 11497, 11504, 11498, -1, 11456, 11505, 11491, -1, 11475, 11505, 11456, -1, 11506, 11505, 11475, -1, 11494, 11507, 11496, -1, 11508, 2337, 11501, -1, 2173, 2337, 4493, -1, 11496, 11507, 11464, -1, 11501, 2337, 2173, -1, 11464, 11507, 11485, -1, 434, 11509, 11510, -1, 4493, 2336, 4571, -1, 11497, 11511, 11504, -1, 11504, 11511, 11512, -1, 2337, 2336, 4493, -1, 11508, 11513, 2337, -1, 2336, 2425, 4571, -1, 11506, 11514, 11505, -1, 434, 11515, 11509, -1, 11516, 11514, 11506, -1, 11490, 11514, 11516, -1, 4316, 3093, 4323, -1, 4323, 3093, 434, -1, 434, 3093, 11515, -1, 11517, 11518, 11519, -1, 11485, 11518, 11517, -1, 11507, 11518, 11485, -1, 4571, 2493, 4599, -1, 11520, 11521, 1106, -1, 2425, 2493, 4571, -1, 4316, 381, 3093, -1, 3093, 11522, 11515, -1, 4316, 348, 381, -1, 11490, 11523, 11514, -1, 3410, 11523, 11490, -1, 4296, 348, 4316, -1, 3409, 11523, 3410, -1, 11518, 11524, 11519, -1, 11497, 11524, 11511, -1, 4296, 349, 348, -1, 11519, 11524, 11497, -1, 11525, 11526, 11527, -1, 11528, 11529, 2493, -1, 11521, 1570, 1106, -1, 11530, 1570, 11521, -1, 11531, 1570, 11530, -1, 11525, 11532, 11526, -1, 3409, 4524, 11523, -1, 3413, 4524, 3409, -1, 1082, 4524, 3413, -1, 11529, 2918, 2493, -1, 1094, 4524, 1082, -1, 1099, 4524, 1094, -1, 1106, 4524, 1099, -1, 11524, 11533, 11511, -1, 2493, 2918, 4599, -1, 11534, 11533, 11535, -1, 11529, 11536, 2918, -1, 11511, 11533, 11534, -1, 2918, 2917, 4599, -1, 4599, 2917, 4609, -1, 11532, 11537, 11538, -1, 11525, 11537, 11532, -1, 349, 11539, 11540, -1, 11541, 11542, 765, -1, 11536, 11543, 2918, -1, 2917, 2375, 4609, -1, 1106, 4525, 4524, -1, 1570, 4525, 1106, -1, 763, 4525, 1570, -1, 11535, 11544, 11525, -1, 11533, 11544, 11535, -1, 11525, 11544, 11537, -1, 11545, 11546, 11547, -1, 4294, 3071, 4296, -1, 4296, 3071, 349, -1, 4609, 2374, 4649, -1, 11548, 2021, 11542, -1, 11549, 2021, 11548, -1, 2375, 2374, 4609, -1, 11542, 2021, 765, -1, 349, 11550, 11539, -1, 11545, 11551, 11546, -1, 3071, 11550, 349, -1, 765, 4543, 766, -1, 4294, 286, 3071, -1, 763, 4543, 4525, -1, 766, 4543, 763, -1, 11552, 11553, 11554, -1, 11537, 11553, 11552, -1, 11544, 11553, 11537, -1, 4512, 278, 4294, -1, 4294, 278, 286, -1, 3071, 11555, 11550, -1, 11551, 11556, 11557, -1, 11545, 11556, 11551, -1, 4512, 279, 278, -1, 11558, 11559, 2374, -1, 2020, 4553, 2021, -1, 765, 4553, 4543, -1, 2021, 4553, 765, -1, 2374, 3131, 4649, -1, 11553, 11560, 11554, -1, 11559, 3131, 2374, -1, 11554, 11560, 11545, -1, 11545, 11560, 11556, -1, 11561, 11562, 2119, -1, 11559, 11563, 3131, -1, 4649, 3130, 4450, -1, 3131, 3130, 4649, -1, 11564, 11565, 11566, -1, 2067, 4587, 2020, -1, 2119, 4587, 2067, -1, 2020, 4587, 4553, -1, 279, 11567, 11568, -1, 3130, 3137, 4450, -1, 11569, 11570, 11571, -1, 11556, 11570, 11569, -1, 11560, 11570, 11556, -1, 11563, 11572, 3131, -1, 4968, 181, 4512, -1, 11573, 2484, 11562, -1, 4512, 181, 279, -1, 11574, 2484, 11573, -1, 11562, 2484, 2119, -1, 4450, 3143, 4730, -1, 11564, 11575, 11565, -1, 3137, 3143, 4450, -1, 4968, 158, 181, -1, 279, 11576, 11567, -1, 11575, 11577, 11578, -1, 181, 11576, 279, -1, 11564, 11577, 11575, -1, 2483, 4431, 2484, -1, 4936, 129, 4968, -1, 4968, 129, 158, -1, 2119, 4431, 4587, -1, 2484, 4431, 2119, -1, 181, 11579, 11576, -1, 11571, 11580, 11564, -1, 4936, 130, 129, -1, 11570, 11580, 11571, -1, 11564, 11580, 11577, -1, 11581, 11582, 1018, -1, 11583, 11584, 3143, -1, 11584, 3181, 3143, -1, 3143, 3181, 4730, -1, 4730, 3180, 4743, -1, 1014, 4469, 2483, -1, 3181, 3180, 4730, -1, 1018, 4469, 1014, -1, 2483, 4469, 4431, -1, 11585, 11586, 11587, -1, 11577, 11586, 11585, -1, 11580, 11586, 11577, -1, 11584, 11588, 3181, -1, 11589, 11590, 11591, -1, 3180, 2598, 4743, -1, 11592, 2991, 11582, -1, 11593, 2991, 11592, -1, 11582, 2991, 1018, -1, 4907, 2977, 4936, -1, 4936, 2977, 130, -1, 11589, 11594, 11590, -1, 2598, 2597, 4743, -1, 4743, 2597, 4756, -1, 2990, 4714, 2991, -1, 1018, 4714, 4469, -1, 130, 11595, 11596, -1, 2991, 4714, 1018, -1, 11587, 11597, 11589, -1, 4907, 2975, 2977, -1, 11586, 11597, 11587, -1, 11588, 11598, 3181, -1, 4907, 3387, 2975, -1, 4902, 3387, 4907, -1, 2977, 11599, 130, -1, 130, 11599, 11595, -1, 11589, 11600, 11594, -1, 11597, 11600, 11589, -1, 4902, 3388, 3387, -1, 11594, 11600, 11601, -1, 2977, 11602, 11599, -1, 11603, 11604, 3082, -1, 2597, 3224, 4756, -1, 3040, 4728, 2990, -1, 3082, 4728, 3040, -1, 2990, 4728, 4714, -1, 4756, 3223, 4762, -1, 11605, 11606, 11607, -1, 11600, 11606, 11605, -1, 3224, 3223, 4756, -1, 11597, 11606, 11600, -1, 3223, 2693, 4762, -1, 2597, 11608, 3224, -1, 11609, 11608, 2597, -1, 4882, 3340, 4902, -1, 4902, 3340, 3388, -1, 11610, 11611, 11612, -1, 2693, 2692, 4762, -1, 11604, 3139, 3082, -1, 4762, 2692, 4787, -1, 11613, 3139, 11604, -1, 11614, 3139, 11613, -1, 4882, 2901, 3340, -1, 11610, 11615, 11611, -1, 4857, 3323, 4882, -1, 3082, 4734, 4728, -1, 4882, 3323, 2901, -1, 3139, 4734, 3082, -1, 3138, 4734, 3139, -1, 11606, 11616, 11607, -1, 4857, 3324, 3323, -1, 11607, 11616, 11610, -1, 11608, 11617, 3224, -1, 2692, 3275, 4787, -1, 3275, 2773, 4787, -1, 11610, 11618, 11615, -1, 4787, 2773, 4820, -1, 11616, 11618, 11610, -1, 11615, 11618, 11619, -1, 2773, 2778, 4820, -1, 4820, 2777, 4857, -1, 4857, 2777, 3324, -1, 2778, 2777, 4820, -1, 11620, 11621, 1260, -1, 1261, 4750, 3138, -1, 1260, 4750, 1261, -1, 3388, 11622, 11623, -1, 11617, 11624, 3224, -1, 3138, 4750, 4734, -1, 11616, 11625, 11618, -1, 3388, 11626, 11622, -1, 3340, 11626, 3388, -1, 11618, 11625, 11627, -1, 3340, 11628, 11626, -1, 11625, 11629, 11627, -1, 2692, 11630, 3275, -1, 11631, 11630, 2692, -1, 11632, 11633, 11634, -1, 11635, 3184, 11621, -1, 11636, 3184, 11635, -1, 11621, 3184, 1260, -1, 1260, 4779, 4750, -1, 3184, 4779, 1260, -1, 11630, 11637, 3275, -1, 11625, 11638, 11629, -1, 3324, 11639, 11640, -1, 11629, 11638, 11632, -1, 3184, 3183, 4779, -1, 11637, 11641, 3275, -1, 11632, 11642, 11633, -1, 2777, 11643, 3324, -1, 3324, 11643, 11639, -1, 2777, 11644, 11643, -1, 11638, 11645, 11632, -1, 11632, 11645, 11642, -1, 11642, 11645, 11646, -1, 1361, 4815, 3183, -1, 1360, 4815, 1361, -1, 3183, 4815, 4779, -1, 11638, 11647, 11645, -1, 11647, 11648, 11645, -1, 11649, 11650, 1360, -1, 11647, 11651, 11648, -1, 1360, 4841, 4815, -1, 11651, 11652, 11653, -1, 11647, 11652, 11651, -1, 11653, 11654, 11655, -1, 1360, 3227, 4841, -1, 11656, 3227, 11650, -1, 11657, 3227, 11656, -1, 11650, 3227, 1360, -1, 3227, 1457, 4841, -1, 11653, 11658, 11654, -1, 11652, 11659, 11653, -1, 11653, 11659, 11658, -1, 11659, 11660, 11658, -1, 1457, 4862, 4841, -1, 1456, 4862, 1457, -1, 11652, 11661, 11659, -1, 1456, 1458, 4862, -1, 11661, 11662, 11659, -1, 11663, 11664, 1458, -1, 11661, 11665, 11662, -1, 1458, 4867, 4862, -1, 11661, 11282, 11665, -1, 11665, 11282, 11279, -1, 11279, 11281, 11666, -1, 1458, 3273, 4867, -1, 11664, 3273, 1458, -1, 11667, 3273, 11664, -1, 11667, 11668, 3273, -1, 4139, 2111, 4108, -1, 1841, 2111, 4139, -1, 11669, 2111, 1841, -1, 11669, 11670, 2111, -1, 11671, 11672, 11673, -1, 2111, 2110, 4108, -1, 11672, 11674, 11675, -1, 2110, 1303, 4108, -1, 11671, 11676, 11672, -1, 1303, 4096, 4108, -1, 1303, 1302, 4096, -1, 11677, 11678, 1302, -1, 11674, 11679, 11680, -1, 11672, 11679, 11674, -1, 11681, 11682, 11683, -1, 11676, 11679, 11672, -1, 11679, 11684, 11680, -1, 11676, 11685, 11679, -1, 11676, 11686, 11685, -1, 11678, 11687, 1302, -1, 11688, 11689, 11690, -1, 11691, 11689, 11688, -1, 11686, 11692, 11685, -1, 11687, 969, 1302, -1, 4096, 969, 4069, -1, 1302, 969, 4096, -1, 11686, 11693, 11692, -1, 11694, 11695, 11696, -1, 11683, 11695, 11694, -1, 11682, 11695, 11683, -1, 11687, 11697, 969, -1, 969, 670, 4069, -1, 11686, 11698, 11693, -1, 11699, 11700, 11691, -1, 670, 665, 4069, -1, 11691, 11700, 11689, -1, 4069, 665, 4044, -1, 11693, 11701, 11702, -1, 11703, 11704, 11705, -1, 665, 664, 4044, -1, 11706, 11707, 664, -1, 11693, 11708, 11701, -1, 11701, 11708, 11709, -1, 11698, 11708, 11693, -1, 11708, 11710, 11709, -1, 11711, 11712, 11713, -1, 11714, 11712, 11711, -1, 11704, 11715, 11705, -1, 11716, 11715, 11717, -1, 11718, 11719, 11698, -1, 11705, 11715, 11716, -1, 11698, 11719, 11708, -1, 11707, 11720, 664, -1, 11718, 11721, 11719, -1, 664, 1958, 4044, -1, 11720, 1958, 664, -1, 4044, 1958, 3737, -1, 11718, 11722, 11721, -1, 11720, 11723, 1958, -1, 11714, 11724, 11712, -1, 11725, 11724, 11714, -1, 1958, 1957, 3737, -1, 11718, 11726, 11722, -1, 11727, 11728, 11729, -1, 3737, 326, 4010, -1, 1957, 326, 3737, -1, 11722, 11730, 11731, -1, 326, 325, 4010, -1, 11732, 11733, 11734, -1, 11732, 11735, 11733, -1, 11728, 11736, 11729, -1, 11737, 11738, 325, -1, 11739, 11736, 11740, -1, 11729, 11736, 11739, -1, 11730, 11741, 11742, -1, 11726, 11741, 11722, -1, 11722, 11741, 11730, -1, 11741, 11743, 11742, -1, 11744, 11745, 11726, -1, 11726, 11745, 11741, -1, 11738, 11746, 325, -1, 11747, 11748, 11735, -1, 11735, 11748, 11733, -1, 11744, 11749, 11745, -1, 4010, 1889, 3979, -1, 325, 1889, 4010, -1, 11746, 1889, 325, -1, 11750, 11751, 11752, -1, 11753, 11754, 11744, -1, 11744, 11754, 11749, -1, 11746, 11755, 1889, -1, 1889, 128, 3979, -1, 3979, 125, 3962, -1, 128, 125, 3979, -1, 11756, 11757, 11758, -1, 11754, 11759, 11760, -1, 125, 124, 3962, -1, 11756, 11761, 11757, -1, 11751, 11762, 11752, -1, 11763, 11762, 11764, -1, 11752, 11762, 11763, -1, 11759, 11765, 11766, -1, 11753, 11765, 11754, -1, 11754, 11765, 11759, -1, 11767, 11768, 124, -1, 11765, 11769, 11766, -1, 11753, 11770, 11765, -1, 11771, 11772, 11761, -1, 11773, 11770, 11753, -1, 11761, 11772, 11757, -1, 11768, 11774, 124, -1, 11775, 11776, 11777, -1, 11778, 11779, 11682, -1, 11780, 11779, 11778, -1, 11773, 11781, 11770, -1, 124, 3376, 3962, -1, 11774, 3376, 124, -1, 3962, 3376, 3924, -1, 11782, 11783, 11773, -1, 11773, 11783, 11781, -1, 11774, 11784, 3376, -1, 3376, 3371, 3924, -1, 11695, 11785, 11786, -1, 3924, 3370, 3798, -1, 3371, 3370, 3924, -1, 11779, 11785, 11682, -1, 11682, 11785, 11695, -1, 11689, 11787, 11780, -1, 11700, 11787, 11689, -1, 11783, 11788, 11789, -1, 3370, 3372, 3798, -1, 11780, 11787, 11779, -1, 11788, 11790, 11791, -1, 11786, 11792, 11793, -1, 11782, 11790, 11783, -1, 11783, 11790, 11788, -1, 11785, 11792, 11786, -1, 11794, 11795, 3372, -1, 11790, 11796, 11791, -1, 11793, 11792, 11704, -1, 11797, 11798, 11700, -1, 11799, 11798, 11797, -1, 11800, 11801, 11782, -1, 11782, 11801, 11790, -1, 11700, 11798, 11787, -1, 11795, 11802, 3372, -1, 11800, 11803, 11801, -1, 3798, 1703, 3793, -1, 3372, 1703, 3798, -1, 11802, 1703, 3372, -1, 11704, 11804, 11715, -1, 11805, 11806, 11800, -1, 11792, 11804, 11704, -1, 11800, 11806, 11803, -1, 11802, 11807, 1703, -1, 1703, 1702, 3793, -1, 11715, 11804, 11808, -1, 11799, 11809, 11798, -1, 11712, 11809, 11799, -1, 11724, 11809, 11712, -1, 3793, 1700, 3823, -1, 1702, 1700, 3793, -1, 11810, 11811, 11812, -1, 11806, 11813, 11814, -1, 1700, 3314, 3823, -1, 11804, 11815, 11808, -1, 11816, 11815, 11728, -1, 11808, 11815, 11816, -1, 11817, 11818, 11724, -1, 11819, 11818, 11817, -1, 11805, 3406, 11806, -1, 11806, 3406, 11813, -1, 11724, 11818, 11809, -1, 11813, 3406, 11820, -1, 11821, 11822, 3314, -1, 11810, 11823, 11811, -1, 3406, 11824, 11820, -1, 11825, 11826, 11827, -1, 11777, 11826, 11825, -1, 3557, 3404, 11805, -1, 11776, 11826, 11777, -1, 11805, 3404, 3406, -1, 11728, 11828, 11736, -1, 3557, 3405, 3404, -1, 11736, 11828, 11829, -1, 11815, 11828, 11728, -1, 11822, 11830, 3314, -1, 11733, 11831, 11819, -1, 11748, 11831, 11733, -1, 11819, 11831, 11818, -1, 11830, 1598, 3314, -1, 3823, 1598, 3772, -1, 3314, 1598, 3823, -1, 3557, 17, 3405, -1, 3557, 16, 17, -1, 11823, 11832, 11811, -1, 3557, 14, 16, -1, 11833, 11832, 11823, -1, 3556, 15, 3557, -1, 11828, 11834, 11829, -1, 3557, 15, 14, -1, 11830, 11835, 1598, -1, 1598, 1597, 3772, -1, 11836, 11834, 11751, -1, 11829, 11834, 11836, -1, 11837, 11838, 11748, -1, 11839, 11838, 11837, -1, 11748, 11838, 11831, -1, 1597, 3266, 3772, -1, 3772, 3266, 3745, -1, 11840, 11841, 11842, -1, 15, 11843, 11844, -1, 3266, 3267, 3745, -1, 11834, 11845, 11751, -1, 11751, 11845, 11762, -1, 11762, 11845, 11846, -1, 11839, 11847, 11838, -1, 3556, 36, 15, -1, 11757, 11847, 11839, -1, 15, 36, 11843, -1, 11843, 36, 11848, -1, 11772, 11847, 11757, -1, 11849, 11850, 11851, -1, 11852, 11853, 3267, -1, 3879, 37, 3556, -1, 3556, 37, 36, -1, 11845, 11854, 11846, -1, 36, 11855, 11848, -1, 11856, 11854, 11776, -1, 11846, 11854, 11856, -1, 3879, 451, 37, -1, 11772, 11857, 11847, -1, 11858, 11857, 11772, -1, 11859, 11857, 11858, -1, 11853, 11860, 3267, -1, 3745, 3237, 3707, -1, 11850, 11861, 11851, -1, 11860, 3237, 3267, -1, 3267, 3237, 3745, -1, 3896, 452, 3879, -1, 11840, 11862, 11841, -1, 11863, 11862, 11864, -1, 3879, 452, 451, -1, 11841, 11862, 11863, -1, 3237, 1451, 3707, -1, 11860, 11865, 3237, -1, 11776, 11866, 11826, -1, 11854, 11866, 11776, -1, 11826, 11866, 11867, -1, 3707, 1454, 3708, -1, 1451, 1454, 3707, -1, 11832, 11868, 11811, -1, 11859, 11868, 11857, -1, 11811, 11868, 11859, -1, 1454, 3216, 3708, -1, 11869, 11870, 11861, -1, 11861, 11870, 11851, -1, 452, 11871, 11872, -1, 11873, 11874, 11875, -1, 452, 98, 11871, -1, 3896, 98, 452, -1, 11871, 98, 11876, -1, 11877, 11878, 11840, -1, 11867, 11878, 11877, -1, 11866, 11878, 11867, -1, 11879, 11880, 11832, -1, 11881, 11880, 11879, -1, 11882, 11883, 3216, -1, 11832, 11880, 11868, -1, 3936, 96, 3896, -1, 3896, 96, 98, -1, 11884, 11885, 11886, -1, 98, 11887, 11876, -1, 3936, 97, 96, -1, 11888, 11889, 11890, -1, 11874, 11889, 11888, -1, 11873, 11889, 11874, -1, 11885, 11891, 11886, -1, 11883, 11892, 3216, -1, 11878, 11893, 11840, -1, 3708, 1354, 3665, -1, 11840, 11893, 11862, -1, 3216, 1354, 3708, -1, 11892, 1354, 3216, -1, 11862, 11893, 11894, -1, 11851, 11895, 11881, -1, 3722, 101, 3936, -1, 3936, 101, 97, -1, 11881, 11895, 11880, -1, 11870, 11895, 11851, -1, 1354, 1353, 3665, -1, 11892, 11896, 1354, -1, 11891, 11897, 11886, -1, 1353, 1355, 3665, -1, 11898, 11897, 11891, -1, 3665, 1355, 3643, -1, 1355, 3176, 3643, -1, 11899, 11900, 11873, -1, 11894, 11900, 11899, -1, 11893, 11900, 11894, -1, 11901, 11902, 11870, -1, 101, 11903, 11904, -1, 11905, 11902, 11901, -1, 11870, 11902, 11895, -1, 11906, 11907, 11908, -1, 101, 171, 11903, -1, 3722, 171, 101, -1, 171, 11909, 11903, -1, 11873, 11910, 11889, -1, 11900, 11910, 11873, -1, 11889, 11910, 11911, -1, 3766, 172, 3722, -1, 11897, 11912, 11886, -1, 11886, 11912, 11905, -1, 3722, 172, 171, -1, 11905, 11912, 11902, -1, 11913, 11914, 3, -1, 11915, 11916, 3176, -1, 11906, 11917, 11907, -1, 11918, 11917, 11919, -1, 11907, 11917, 11918, -1, 11914, 11920, 3, -1, 171, 11921, 11909, -1, 11922, 11923, 11906, -1, 11911, 11923, 11922, -1, 3766, 174, 172, -1, 11910, 11923, 11911, -1, 11897, 3830, 11912, -1, 11924, 3830, 11897, -1, 11925, 3830, 11924, -1, 9, 3830, 11925, -1, 2, 3830, 9, -1, 1, 3830, 2, -1, 3176, 1256, 3643, -1, 3643, 1256, 3615, -1, 11920, 3291, 3, -1, 4017, 479, 3766, -1, 11926, 3291, 11920, -1, 3766, 479, 174, -1, 11916, 11927, 3176, -1, 11928, 11929, 11930, -1, 3176, 11927, 1256, -1, 1256, 1255, 3615, -1, 11906, 11931, 11917, -1, 11917, 11931, 11932, -1, 3615, 3127, 3603, -1, 11923, 11931, 11906, -1, 1255, 3127, 3615, -1, 11927, 11933, 1256, -1, 3, 3713, 1, -1, 3291, 3713, 3, -1, 1, 3713, 3830, -1, 3127, 3126, 3603, -1, 11934, 11935, 3262, -1, 11936, 11937, 11938, -1, 11929, 11937, 11936, -1, 479, 11939, 11940, -1, 11928, 11937, 11929, -1, 11935, 11941, 3262, -1, 479, 283, 11939, -1, 11931, 11942, 11932, -1, 4017, 283, 479, -1, 11943, 11942, 11928, -1, 11932, 11942, 11943, -1, 3291, 3701, 3713, -1, 2770, 3701, 3291, -1, 2768, 3701, 2770, -1, 283, 11944, 11939, -1, 4038, 284, 4017, -1, 4017, 284, 283, -1, 11945, 11946, 3126, -1, 11941, 2686, 3262, -1, 11947, 2686, 11941, -1, 11942, 11948, 11928, -1, 4038, 527, 284, -1, 11928, 11948, 11937, -1, 11937, 11948, 11949, -1, 283, 11950, 11944, -1, 3126, 1104, 3603, -1, 2768, 3675, 3701, -1, 2686, 3675, 3262, -1, 3603, 1104, 3577, -1, 4048, 528, 4038, -1, 3262, 3675, 2768, -1, 11951, 11952, 11953, -1, 4038, 528, 527, -1, 1104, 1103, 3577, -1, 3126, 11954, 1104, -1, 11946, 11954, 3126, -1, 11955, 11956, 3217, -1, 1103, 1105, 3577, -1, 3577, 1105, 3549, -1, 11957, 11958, 11951, -1, 11949, 11958, 11957, -1, 11948, 11958, 11949, -1, 2686, 3663, 3675, -1, 11954, 11959, 1104, -1, 2685, 3663, 2686, -1, 2687, 3663, 2685, -1, 1105, 1102, 3549, -1, 11960, 11961, 11962, -1, 11952, 11961, 11960, -1, 11951, 11961, 11952, -1, 11956, 11963, 3217, -1, 528, 11964, 11965, -1, 4048, 415, 528, -1, 528, 415, 11964, -1, 4082, 416, 4048, -1, 11963, 2593, 3217, -1, 11966, 2593, 11963, -1, 11951, 11967, 11961, -1, 4048, 416, 415, -1, 11961, 11967, 11968, -1, 11958, 11967, 11951, -1, 2687, 3634, 3663, -1, 415, 11969, 11964, -1, 2593, 3634, 3217, -1, 3217, 3634, 2687, -1, 4082, 417, 416, -1, 11970, 11971, 11972, -1, 3549, 1011, 3550, -1, 1102, 1011, 3549, -1, 4111, 574, 4082, -1, 4082, 574, 417, -1, 11973, 11974, 1102, -1, 1011, 1010, 3550, -1, 11967, 11975, 11968, -1, 11976, 11975, 11970, -1, 11968, 11975, 11976, -1, 415, 11977, 11969, -1, 2593, 3635, 3634, -1, 1010, 1008, 3550, -1, 2592, 3635, 2593, -1, 3550, 1008, 4255, -1, 3170, 3635, 2592, -1, 11974, 11978, 1102, -1, 11979, 11980, 3169, -1, 1102, 11978, 1011, -1, 11981, 11982, 11983, -1, 11971, 11982, 11981, -1, 1008, 2344, 4255, -1, 11970, 11982, 11971, -1, 11978, 11984, 1011, -1, 11980, 11985, 3169, -1, 4111, 864, 574, -1, 11982, 11986, 11987, -1, 11975, 11986, 11970, -1, 11970, 11986, 11982, -1, 3170, 3592, 3635, -1, 4133, 675, 4111, -1, 3169, 3592, 3170, -1, 4111, 675, 864, -1, 4133, 673, 675, -1, 864, 11988, 574, -1, 11985, 2457, 3169, -1, 11989, 2457, 11985, -1, 3169, 2457, 3592, -1, 574, 11988, 11990, -1, 4255, 942, 4229, -1, 2344, 942, 4255, -1, 4160, 674, 4133, -1, 11991, 11992, 11993, -1, 4133, 674, 673, -1, 11994, 11995, 11991, -1, 11987, 11995, 11994, -1, 942, 940, 4229, -1, 11986, 11995, 11987, -1, 4229, 1963, 4197, -1, 940, 1963, 4229, -1, 2457, 3570, 3592, -1, 2456, 3570, 2457, -1, 2458, 3570, 2456, -1, 1963, 1964, 4197, -1, 864, 11996, 11988, -1, 4160, 1419, 674, -1, 11997, 11998, 2455, -1, 4186, 758, 4160, -1, 4160, 758, 1419, -1, 11991, 11999, 11992, -1, 12000, 11999, 12001, -1, 4186, 755, 758, -1, 11992, 11999, 12000, -1, 4197, 756, 4186, -1, 1964, 756, 4197, -1, 11998, 12002, 2455, -1, 4186, 756, 755, -1, 12003, 12004, 2344, -1, 11995, 12005, 11991, -1, 11991, 12005, 11999, -1, 11999, 12005, 12006, -1, 864, 12007, 11996, -1, 2458, 3518, 3570, -1, 2455, 3518, 2458, -1, 2344, 12008, 942, -1, 12004, 12008, 2344, -1, 12008, 12009, 942, -1, 12010, 2371, 12002, -1, 12002, 2371, 2455, -1, 2455, 2371, 3518, -1, 1419, 12011, 674, -1, 674, 12011, 12012, -1, 12013, 12014, 12015, -1, 12016, 12017, 12013, -1, 12006, 12017, 12016, -1, 12005, 12017, 12006, -1, 2370, 3519, 2371, -1, 1419, 12018, 12011, -1, 2371, 3519, 3518, -1, 12019, 12020, 1964, -1, 2370, 2368, 3519, -1, 1419, 12021, 12018, -1, 1964, 12022, 756, -1, 12020, 12022, 1964, -1, 12022, 12023, 756, -1, 12024, 12025, 2790, -1, 12013, 12026, 12014, -1, 12027, 12026, 12028, -1, 12014, 12026, 12027, -1, 12017, 12029, 12013, -1, 12013, 12029, 12026, -1, 2790, 4244, 2368, -1, 2368, 4244, 3519, -1, 12029, 12030, 12026, -1, 12025, 12031, 2790, -1, 12032, 2301, 12031, -1, 12031, 2301, 2790, -1, 2790, 2301, 4244, -1, 12033, 12034, 12035, -1, 12030, 12034, 12033, -1, 12029, 12034, 12030, -1, 2301, 4218, 4244, -1, 2301, 2264, 4218, -1, 12035, 12036, 12037, -1, 2264, 2263, 4218, -1, 12034, 12038, 12035, -1, 2265, 4192, 2263, -1, 2263, 4192, 4218, -1, 12039, 12040, 2265, -1, 12036, 12041, 12042, -1, 12035, 12041, 12036, -1, 12038, 12041, 12035, -1, 12041, 12043, 12042, -1, 12038, 12044, 12041, -1, 12040, 12045, 2265, -1, 2265, 2171, 4192, -1, 12045, 2171, 2265, -1, 12045, 12046, 2171, -1, 12038, 12047, 12044, -1, 12044, 12047, 12048, -1, 2171, 4166, 4192, -1, 12047, 12049, 12048, -1, 2171, 2170, 4166, -1, 12049, 12050, 12051, -1, 2170, 1842, 4166, -1, 12047, 12052, 12049, -1, 1841, 4139, 1842, -1, 1842, 4139, 4166, -1, 12053, 12054, 1841, -1, 12049, 12055, 12050, -1, 12052, 12055, 12049, -1, 12050, 12055, 12056, -1, 12055, 12057, 12056, -1, 12052, 12058, 12055, -1, 12054, 11669, 1841, -1, 12058, 11671, 11673, -1, 12052, 11671, 12058, -1, 12059, 12060, 12061, -1, 12059, 12061, 12062, -1, 12063, 5055, 5064, -1, 12063, 5064, 12064, -1, 12063, 12064, 12065, -1, 12066, 12065, 12061, -1, 12066, 12063, 12065, -1, 12067, 5055, 12063, -1, 12067, 12063, 12066, -1, 12068, 5055, 12067, -1, 12068, 12067, 12066, -1, 12068, 12066, 12061, -1, 12069, 12068, 12061, -1, 12069, 12061, 12060, -1, 12069, 12070, 5055, -1, 12069, 12060, 12070, -1, 12069, 5055, 12068, -1, 12071, 12072, 11342, -1, 12071, 12073, 12072, -1, 12071, 11342, 11344, -1, 12074, 12075, 12073, -1, 12074, 12076, 12075, -1, 12077, 12073, 12071, -1, 12077, 12074, 12073, -1, 12078, 5066, 12076, -1, 12078, 5064, 5066, -1, 12078, 12074, 12077, -1, 12078, 12076, 12074, -1, 12079, 12078, 12077, -1, 12064, 12078, 12079, -1, 12064, 5064, 12078, -1, 12064, 12079, 12065, -1, 12061, 12065, 12080, -1, 12081, 11345, 11355, -1, 12082, 12083, 12084, -1, 12082, 12085, 12083, -1, 12082, 11355, 12085, -1, 12082, 12084, 12060, -1, 12082, 12081, 11355, -1, 12082, 12060, 12081, -1, 12070, 5056, 5055, -1, 12086, 12087, 5056, -1, 12086, 12084, 12087, -1, 12086, 12060, 12084, -1, 12086, 5056, 12070, -1, 12086, 12070, 12060, -1, 12088, 12077, 12071, -1, 12088, 12079, 12077, -1, 12088, 12071, 11344, -1, 12089, 12079, 12088, -1, 12089, 12088, 11344, -1, 12090, 12089, 11344, -1, 12091, 12065, 12079, -1, 12091, 12079, 12089, -1, 12091, 12089, 12090, -1, 12092, 11344, 11345, -1, 12092, 12080, 12065, -1, 12092, 12090, 11344, -1, 12092, 12091, 12090, -1, 12092, 12065, 12091, -1, 12093, 12092, 11345, -1, 12093, 12061, 12080, -1, 12093, 12080, 12092, -1, 12062, 12093, 11345, -1, 12062, 12061, 12093, -1, 12059, 11345, 12081, -1, 12059, 12062, 11345, -1, 12059, 12081, 12060, -1, 12094, 12095, 11322, -1, 12094, 12096, 12095, -1, 12097, 5176, 5189, -1, 12097, 5189, 12098, -1, 12097, 12098, 12099, -1, 12100, 12099, 12096, -1, 12100, 12097, 12099, -1, 12101, 5176, 12097, -1, 12101, 12097, 12100, -1, 12102, 5176, 12101, -1, 12102, 12101, 12100, -1, 12102, 12100, 12096, -1, 12103, 12102, 12096, -1, 12103, 12096, 12104, -1, 12103, 12105, 5176, -1, 12103, 12104, 12105, -1, 12103, 5176, 12102, -1, 12106, 12107, 11323, -1, 12106, 12108, 12107, -1, 12106, 11323, 11320, -1, 12109, 12110, 12108, -1, 12109, 12111, 12110, -1, 12112, 12109, 12108, -1, 12112, 12108, 12106, -1, 12113, 5189, 5196, -1, 12113, 5196, 12111, -1, 12113, 12109, 12112, -1, 12113, 12111, 12109, -1, 12114, 12113, 12112, -1, 12098, 5189, 12113, -1, 12098, 12114, 12099, -1, 12098, 12113, 12114, -1, 12096, 12099, 12115, -1, 12116, 11322, 11333, -1, 12117, 12118, 12119, -1, 12117, 12120, 12118, -1, 12117, 11333, 12120, -1, 12117, 12119, 12104, -1, 12117, 12116, 11333, -1, 12117, 12104, 12116, -1, 12105, 5177, 5176, -1, 12121, 12122, 5177, -1, 12121, 12119, 12122, -1, 12121, 12104, 12119, -1, 12121, 5177, 12105, -1, 12121, 12105, 12104, -1, 12123, 12112, 12106, -1, 12123, 12114, 12112, -1, 12123, 12106, 11320, -1, 12124, 12114, 12123, -1, 12124, 12123, 11320, -1, 12125, 12124, 11320, -1, 12126, 12099, 12114, -1, 12126, 12114, 12124, -1, 12126, 12124, 12125, -1, 12127, 11320, 11322, -1, 12127, 12115, 12099, -1, 12127, 12125, 11320, -1, 12127, 12099, 12126, -1, 12127, 12126, 12125, -1, 12128, 12127, 11322, -1, 12128, 12096, 12115, -1, 12128, 12115, 12127, -1, 12095, 12128, 11322, -1, 12095, 12096, 12128, -1, 12094, 11322, 12116, -1, 12094, 12104, 12096, -1, 12094, 12116, 12104, -1, 12129, 12130, 12131, -1, 12129, 12131, 12132, -1, 12129, 12132, 12133, -1, 12134, 5303, 5312, -1, 12134, 5312, 12135, -1, 12134, 12135, 12136, -1, 12137, 12136, 12132, -1, 12137, 12134, 12136, -1, 12138, 5303, 12134, -1, 12138, 12134, 12137, -1, 12139, 5303, 12138, -1, 12139, 12138, 12137, -1, 12139, 12137, 12132, -1, 12140, 12139, 12132, -1, 12140, 12132, 12131, -1, 12140, 12141, 5303, -1, 12140, 12131, 12141, -1, 12140, 5303, 12139, -1, 12142, 12143, 11416, -1, 12142, 12144, 12143, -1, 12142, 11416, 11418, -1, 12145, 12146, 12144, -1, 12145, 12147, 12146, -1, 12148, 12144, 12142, -1, 12148, 12145, 12144, -1, 12149, 5314, 12147, -1, 12149, 5312, 5314, -1, 12149, 12145, 12148, -1, 12149, 12147, 12145, -1, 12150, 12149, 12148, -1, 12135, 12149, 12150, -1, 12135, 5312, 12149, -1, 12135, 12150, 12136, -1, 12132, 12136, 12151, -1, 12130, 11429, 11443, -1, 12152, 12153, 12154, -1, 12152, 12155, 12153, -1, 12152, 11443, 12155, -1, 12152, 12154, 12131, -1, 12152, 12130, 11443, -1, 12152, 12131, 12130, -1, 12141, 5304, 5303, -1, 12156, 12157, 5304, -1, 12156, 12154, 12157, -1, 12156, 12131, 12154, -1, 12156, 5304, 12141, -1, 12156, 12141, 12131, -1, 12158, 12148, 12142, -1, 12158, 12150, 12148, -1, 12158, 12142, 11418, -1, 12159, 12150, 12158, -1, 12159, 12158, 11418, -1, 12160, 12159, 11418, -1, 12161, 12136, 12150, -1, 12161, 12150, 12159, -1, 12161, 12159, 12160, -1, 12162, 11418, 11429, -1, 12162, 12151, 12136, -1, 12162, 12160, 11418, -1, 12162, 12161, 12160, -1, 12162, 12136, 12161, -1, 12163, 12162, 11429, -1, 12163, 12132, 12151, -1, 12163, 12151, 12162, -1, 12133, 12163, 11429, -1, 12133, 12132, 12163, -1, 12129, 11429, 12130, -1, 12129, 12133, 11429, -1, 12164, 12165, 12166, -1, 12164, 12166, 11369, -1, 12167, 5400, 5413, -1, 12167, 5413, 12168, -1, 12167, 12168, 12169, -1, 12170, 12169, 12165, -1, 12170, 12167, 12169, -1, 12171, 5400, 12167, -1, 12171, 12167, 12170, -1, 12172, 5400, 12171, -1, 12172, 12171, 12170, -1, 12172, 12170, 12165, -1, 12173, 12172, 12165, -1, 12173, 12165, 12174, -1, 12173, 12175, 5400, -1, 12173, 12174, 12175, -1, 12173, 5400, 12172, -1, 12176, 12177, 11364, -1, 12176, 12178, 12177, -1, 12176, 11364, 11366, -1, 12179, 12180, 12178, -1, 12179, 12181, 12180, -1, 12182, 12179, 12178, -1, 12182, 12178, 12176, -1, 12183, 5413, 5420, -1, 12183, 5420, 12181, -1, 12183, 12179, 12182, -1, 12183, 12181, 12179, -1, 12184, 12183, 12182, -1, 12168, 5413, 12183, -1, 12168, 12183, 12184, -1, 12168, 12184, 12169, -1, 12165, 12169, 12185, -1, 12186, 11369, 11376, -1, 12187, 12188, 12189, -1, 12187, 12190, 12188, -1, 12187, 11376, 12190, -1, 12187, 12189, 12174, -1, 12187, 12186, 11376, -1, 12187, 12174, 12186, -1, 12175, 5401, 5400, -1, 12191, 12192, 5401, -1, 12191, 12189, 12192, -1, 12191, 5401, 12175, -1, 12191, 12174, 12189, -1, 12191, 12175, 12174, -1, 12193, 12182, 12176, -1, 12193, 12184, 12182, -1, 12193, 12176, 11366, -1, 12194, 12184, 12193, -1, 12194, 12193, 11366, -1, 12195, 12194, 11366, -1, 12196, 12169, 12184, -1, 12196, 12184, 12194, -1, 12196, 12194, 12195, -1, 12197, 11366, 11369, -1, 12197, 12185, 12169, -1, 12197, 12195, 11366, -1, 12197, 12169, 12196, -1, 12197, 12196, 12195, -1, 12198, 12165, 12185, -1, 12198, 12185, 12197, -1, 12198, 12197, 11369, -1, 12166, 12165, 12198, -1, 12166, 12198, 11369, -1, 12164, 11369, 12186, -1, 12164, 12174, 12165, -1, 12164, 12186, 12174, -1, 12199, 12200, 12201, -1, 12199, 12201, 12202, -1, 12199, 12202, 12203, -1, 12204, 5455, 5464, -1, 12204, 5464, 12205, -1, 12204, 12205, 12206, -1, 12207, 12206, 12202, -1, 12207, 12204, 12206, -1, 12208, 5455, 12204, -1, 12208, 12204, 12207, -1, 12209, 5455, 12208, -1, 12209, 12208, 12207, -1, 12209, 12207, 12202, -1, 12210, 12209, 12202, -1, 12210, 12202, 12201, -1, 12210, 12211, 5455, -1, 12210, 12201, 12211, -1, 12210, 5455, 12209, -1, 12212, 12213, 11327, -1, 12212, 12214, 12213, -1, 12212, 11327, 11325, -1, 12215, 12216, 12214, -1, 12215, 12217, 12216, -1, 12218, 12214, 12212, -1, 12218, 12215, 12214, -1, 12219, 5466, 12217, -1, 12219, 5464, 5466, -1, 12219, 12215, 12218, -1, 12219, 12217, 12215, -1, 12220, 12219, 12218, -1, 12205, 12219, 12220, -1, 12205, 5464, 12219, -1, 12205, 12220, 12206, -1, 12202, 12206, 12221, -1, 12200, 11312, 11314, -1, 12222, 12223, 12224, -1, 12222, 12225, 12223, -1, 12222, 11314, 12225, -1, 12222, 12224, 12201, -1, 12222, 12200, 11314, -1, 12222, 12201, 12200, -1, 12211, 5456, 5455, -1, 12226, 12227, 5456, -1, 12226, 12224, 12227, -1, 12226, 12201, 12224, -1, 12226, 5456, 12211, -1, 12226, 12211, 12201, -1, 12228, 12218, 12212, -1, 12228, 12220, 12218, -1, 12228, 12212, 11325, -1, 12229, 12220, 12228, -1, 12229, 12228, 11325, -1, 12230, 12229, 11325, -1, 12231, 12206, 12220, -1, 12231, 12220, 12229, -1, 12231, 12229, 12230, -1, 12232, 11325, 11312, -1, 12232, 12221, 12206, -1, 12232, 12230, 11325, -1, 12232, 12231, 12230, -1, 12232, 12206, 12231, -1, 12233, 12232, 11312, -1, 12233, 12202, 12221, -1, 12233, 12221, 12232, -1, 12203, 12233, 11312, -1, 12203, 12202, 12233, -1, 12199, 11312, 12200, -1, 12199, 12203, 11312, -1, 12234, 12235, 12236, -1, 12234, 12236, 11335, -1, 12237, 5566, 5579, -1, 12237, 5579, 12238, -1, 12237, 12238, 12239, -1, 12240, 12239, 12235, -1, 12240, 12237, 12239, -1, 12241, 5566, 12237, -1, 12241, 12237, 12240, -1, 12242, 5566, 12241, -1, 12242, 12241, 12240, -1, 12242, 12240, 12235, -1, 12243, 12242, 12235, -1, 12243, 12235, 12244, -1, 12243, 12245, 5566, -1, 12243, 12244, 12245, -1, 12243, 5566, 12242, -1, 12246, 12247, 11350, -1, 12246, 12248, 12247, -1, 12246, 11350, 11349, -1, 12249, 12250, 12248, -1, 12249, 12251, 12250, -1, 12252, 12249, 12248, -1, 12252, 12248, 12246, -1, 12253, 5579, 5586, -1, 12253, 5586, 12251, -1, 12253, 12249, 12252, -1, 12253, 12251, 12249, -1, 12254, 12253, 12252, -1, 12238, 5579, 12253, -1, 12238, 12253, 12254, -1, 12238, 12254, 12239, -1, 12235, 12239, 12255, -1, 12256, 11335, 11337, -1, 12257, 12258, 12259, -1, 12257, 12260, 12258, -1, 12257, 11337, 12260, -1, 12257, 12259, 12244, -1, 12257, 12256, 11337, -1, 12257, 12244, 12256, -1, 12245, 5567, 5566, -1, 12261, 12262, 5567, -1, 12261, 12259, 12262, -1, 12261, 12244, 12259, -1, 12261, 5567, 12245, -1, 12261, 12245, 12244, -1, 12263, 12252, 12246, -1, 12263, 12254, 12252, -1, 12263, 12246, 11349, -1, 12264, 12254, 12263, -1, 12264, 12263, 11349, -1, 12265, 12264, 11349, -1, 12266, 12239, 12254, -1, 12266, 12254, 12264, -1, 12266, 12264, 12265, -1, 12267, 11349, 11335, -1, 12267, 12255, 12239, -1, 12267, 12265, 11349, -1, 12267, 12239, 12266, -1, 12267, 12266, 12265, -1, 12268, 12235, 12255, -1, 12268, 12255, 12267, -1, 12268, 12267, 11335, -1, 12236, 12235, 12268, -1, 12236, 12268, 11335, -1, 12234, 11335, 12256, -1, 12234, 12244, 12235, -1, 12234, 12256, 12244, -1, 12269, 12270, 12271, -1, 12269, 12272, 12273, -1, 12269, 12273, 11299, -1, 12274, 5727, 5736, -1, 12274, 5736, 12275, -1, 12274, 12275, 12276, -1, 12277, 12276, 12272, -1, 12277, 12274, 12276, -1, 12278, 5727, 12274, -1, 12278, 12274, 12277, -1, 12279, 5727, 12278, -1, 12279, 12278, 12277, -1, 12279, 12277, 12272, -1, 12280, 12279, 12272, -1, 12280, 12272, 12271, -1, 12280, 12281, 5727, -1, 12280, 12271, 12281, -1, 12280, 5727, 12279, -1, 12282, 12283, 11300, -1, 12282, 12284, 12283, -1, 12282, 11300, 11297, -1, 12285, 12286, 12284, -1, 12285, 12287, 12286, -1, 12288, 12285, 12284, -1, 12288, 12284, 12282, -1, 12289, 5736, 5738, -1, 12289, 5738, 12287, -1, 12289, 12285, 12288, -1, 12289, 12287, 12285, -1, 12290, 12289, 12288, -1, 12275, 5736, 12289, -1, 12275, 12290, 12276, -1, 12275, 12289, 12290, -1, 12272, 12276, 12291, -1, 12270, 11299, 11310, -1, 12292, 12293, 12294, -1, 12292, 12295, 12293, -1, 12292, 11310, 12295, -1, 12292, 12294, 12271, -1, 12292, 12270, 11310, -1, 12292, 12271, 12270, -1, 12281, 5728, 5727, -1, 12296, 12297, 5728, -1, 12296, 12294, 12297, -1, 12296, 12271, 12294, -1, 12296, 5728, 12281, -1, 12296, 12281, 12271, -1, 12298, 12288, 12282, -1, 12298, 12290, 12288, -1, 12298, 12282, 11297, -1, 12299, 12290, 12298, -1, 12299, 12298, 11297, -1, 12300, 12299, 11297, -1, 12301, 12276, 12290, -1, 12301, 12290, 12299, -1, 12301, 12299, 12300, -1, 12302, 11297, 11299, -1, 12302, 12291, 12276, -1, 12302, 12300, 11297, -1, 12302, 12276, 12301, -1, 12302, 12301, 12300, -1, 12303, 12272, 12291, -1, 12303, 12291, 12302, -1, 12303, 12302, 11299, -1, 12273, 12272, 12303, -1, 12273, 12303, 11299, -1, 12269, 11299, 12270, -1, 12269, 12271, 12272, -1, 12304, 12305, 12306, -1, 12304, 12307, 11290, -1, 12304, 12308, 12307, -1, 12309, 5790, 5803, -1, 12309, 5803, 12310, -1, 12309, 12310, 12311, -1, 12312, 12311, 12308, -1, 12312, 12309, 12311, -1, 12313, 5790, 12309, -1, 12313, 12309, 12312, -1, 12314, 5790, 12313, -1, 12314, 12313, 12312, -1, 12314, 12312, 12308, -1, 12315, 12314, 12308, -1, 12315, 12308, 12306, -1, 12315, 12316, 5790, -1, 12315, 12306, 12316, -1, 12315, 5790, 12314, -1, 12317, 12318, 11305, -1, 12317, 12319, 12318, -1, 12317, 11305, 11303, -1, 12320, 12321, 12319, -1, 12320, 12322, 12321, -1, 12323, 12320, 12319, -1, 12323, 12319, 12317, -1, 12324, 5803, 5810, -1, 12324, 5810, 12322, -1, 12324, 12320, 12323, -1, 12324, 12322, 12320, -1, 12325, 12324, 12323, -1, 12310, 5803, 12324, -1, 12310, 12325, 12311, -1, 12310, 12324, 12325, -1, 12308, 12311, 12326, -1, 12305, 11290, 11292, -1, 12327, 12328, 12329, -1, 12327, 12330, 12328, -1, 12327, 11292, 12330, -1, 12327, 12329, 12306, -1, 12327, 12305, 11292, -1, 12327, 12306, 12305, -1, 12316, 5791, 5790, -1, 12331, 12332, 5791, -1, 12331, 12329, 12332, -1, 12331, 12306, 12329, -1, 12331, 5791, 12316, -1, 12331, 12316, 12306, -1, 12333, 12323, 12317, -1, 12333, 12325, 12323, -1, 12333, 12317, 11303, -1, 12334, 12325, 12333, -1, 12334, 12333, 11303, -1, 12335, 12334, 11303, -1, 12336, 12311, 12325, -1, 12336, 12325, 12334, -1, 12336, 12334, 12335, -1, 12337, 11303, 11290, -1, 12337, 12326, 12311, -1, 12337, 12335, 11303, -1, 12337, 12311, 12336, -1, 12337, 12336, 12335, -1, 12338, 12337, 11290, -1, 12338, 12308, 12326, -1, 12338, 12326, 12337, -1, 12307, 12338, 11290, -1, 12307, 12308, 12338, -1, 12304, 11290, 12305, -1, 12304, 12306, 12308, -1, 12339, 12340, 12341, -1, 12339, 12341, 12342, -1, 12339, 12342, 12343, -1, 12344, 5998, 6011, -1, 12344, 6011, 12345, -1, 12344, 12345, 12346, -1, 12347, 12346, 12342, -1, 12347, 12344, 12346, -1, 12348, 5998, 12344, -1, 12348, 12344, 12347, -1, 12349, 5998, 12348, -1, 12349, 12348, 12347, -1, 12349, 12347, 12342, -1, 12350, 12349, 12342, -1, 12350, 12342, 12341, -1, 12350, 12351, 5998, -1, 12350, 12341, 12351, -1, 12350, 5998, 12349, -1, 12352, 12353, 11466, -1, 12352, 12354, 12353, -1, 12352, 11466, 11465, -1, 12355, 12356, 12354, -1, 12355, 12357, 12356, -1, 12358, 12354, 12352, -1, 12358, 12355, 12354, -1, 12359, 6018, 12357, -1, 12359, 6011, 6018, -1, 12359, 12355, 12358, -1, 12359, 12357, 12355, -1, 12360, 12359, 12358, -1, 12345, 12359, 12360, -1, 12345, 6011, 12359, -1, 12345, 12360, 12346, -1, 12342, 12346, 12361, -1, 12340, 11474, 11486, -1, 12362, 12363, 12364, -1, 12362, 12365, 12363, -1, 12362, 11486, 12365, -1, 12362, 12364, 12341, -1, 12362, 12340, 11486, -1, 12362, 12341, 12340, -1, 12351, 5999, 5998, -1, 12366, 12367, 5999, -1, 12366, 12364, 12367, -1, 12366, 12341, 12364, -1, 12366, 5999, 12351, -1, 12366, 12351, 12341, -1, 12368, 12358, 12352, -1, 12368, 12360, 12358, -1, 12368, 12352, 11465, -1, 12369, 12360, 12368, -1, 12369, 12368, 11465, -1, 12370, 12369, 11465, -1, 12371, 12346, 12360, -1, 12371, 12360, 12369, -1, 12371, 12369, 12370, -1, 12372, 11465, 11474, -1, 12372, 12361, 12346, -1, 12372, 12370, 11465, -1, 12372, 12371, 12370, -1, 12372, 12346, 12371, -1, 12373, 12372, 11474, -1, 12373, 12342, 12361, -1, 12373, 12361, 12372, -1, 12343, 12373, 11474, -1, 12343, 12342, 12373, -1, 12339, 11474, 12340, -1, 12339, 12343, 11474, -1, 12374, 12375, 12376, -1, 12374, 12376, 12377, -1, 12374, 12377, 12378, -1, 12379, 6019, 6028, -1, 12379, 6028, 12380, -1, 12379, 12380, 12381, -1, 12382, 12381, 12377, -1, 12382, 12379, 12381, -1, 12383, 6019, 12379, -1, 12383, 12379, 12382, -1, 12384, 6019, 12383, -1, 12384, 12383, 12382, -1, 12384, 12382, 12377, -1, 12385, 12384, 12377, -1, 12385, 12377, 12376, -1, 12385, 12386, 6019, -1, 12385, 12376, 12386, -1, 12385, 6019, 12384, -1, 12387, 12388, 11499, -1, 12387, 12389, 12388, -1, 12387, 11499, 11498, -1, 12390, 12391, 12389, -1, 12390, 12392, 12391, -1, 12393, 12389, 12387, -1, 12393, 12390, 12389, -1, 12394, 6030, 12392, -1, 12394, 6028, 6030, -1, 12394, 12390, 12393, -1, 12394, 12392, 12390, -1, 12395, 12394, 12393, -1, 12380, 12394, 12395, -1, 12380, 6028, 12394, -1, 12380, 12395, 12381, -1, 12377, 12381, 12396, -1, 12375, 11504, 11512, -1, 12397, 12398, 12399, -1, 12397, 12400, 12398, -1, 12397, 11512, 12400, -1, 12397, 12399, 12376, -1, 12397, 12375, 11512, -1, 12397, 12376, 12375, -1, 12386, 6020, 6019, -1, 12401, 12402, 6020, -1, 12401, 12399, 12402, -1, 12401, 12376, 12399, -1, 12401, 6020, 12386, -1, 12401, 12386, 12376, -1, 12403, 12393, 12387, -1, 12403, 12395, 12393, -1, 12403, 12387, 11498, -1, 12404, 12395, 12403, -1, 12404, 12403, 11498, -1, 12405, 12404, 11498, -1, 12406, 12381, 12395, -1, 12406, 12395, 12404, -1, 12406, 12404, 12405, -1, 12407, 11498, 11504, -1, 12407, 12396, 12381, -1, 12407, 12405, 11498, -1, 12407, 12406, 12405, -1, 12407, 12381, 12406, -1, 12408, 12407, 11504, -1, 12408, 12377, 12396, -1, 12408, 12396, 12407, -1, 12378, 12408, 11504, -1, 12378, 12377, 12408, -1, 12374, 11504, 12375, -1, 12374, 12378, 11504, -1, 12409, 12410, 12411, -1, 12409, 12411, 12412, -1, 12413, 6130, 6143, -1, 12413, 6143, 12414, -1, 12413, 12414, 12415, -1, 12416, 12415, 12411, -1, 12416, 12413, 12415, -1, 12417, 6130, 12413, -1, 12417, 12413, 12416, -1, 12418, 6130, 12417, -1, 12418, 12417, 12416, -1, 12418, 12416, 12411, -1, 12419, 12418, 12411, -1, 12419, 12411, 12410, -1, 12419, 12420, 6130, -1, 12419, 12410, 12420, -1, 12419, 6130, 12418, -1, 12421, 12422, 11527, -1, 12421, 12423, 12422, -1, 12421, 11527, 11526, -1, 12424, 12425, 12423, -1, 12424, 12426, 12425, -1, 12427, 12423, 12421, -1, 12427, 12424, 12423, -1, 12428, 6150, 12426, -1, 12428, 6143, 6150, -1, 12428, 12424, 12427, -1, 12428, 12426, 12424, -1, 12429, 12428, 12427, -1, 12414, 12428, 12429, -1, 12414, 6143, 12428, -1, 12414, 12429, 12415, -1, 12411, 12415, 12430, -1, 12431, 11532, 11538, -1, 12432, 12433, 12434, -1, 12432, 12435, 12433, -1, 12432, 11538, 12435, -1, 12432, 12434, 12410, -1, 12432, 12431, 11538, -1, 12432, 12410, 12431, -1, 12420, 6131, 6130, -1, 12436, 12437, 6131, -1, 12436, 12434, 12437, -1, 12436, 12410, 12434, -1, 12436, 6131, 12420, -1, 12436, 12420, 12410, -1, 12438, 12427, 12421, -1, 12438, 12429, 12427, -1, 12438, 12421, 11526, -1, 12439, 12429, 12438, -1, 12439, 12438, 11526, -1, 12440, 12439, 11526, -1, 12441, 12415, 12429, -1, 12441, 12429, 12439, -1, 12441, 12439, 12440, -1, 12442, 11526, 11532, -1, 12442, 12430, 12415, -1, 12442, 12440, 11526, -1, 12442, 12441, 12440, -1, 12442, 12415, 12441, -1, 12443, 12442, 11532, -1, 12443, 12411, 12430, -1, 12443, 12430, 12442, -1, 12412, 12443, 11532, -1, 12412, 12411, 12443, -1, 12409, 11532, 12431, -1, 12409, 12412, 11532, -1, 12409, 12431, 12410, -1, 12444, 12445, 12446, -1, 12444, 12446, 12447, -1, 12444, 12447, 12448, -1, 12449, 6243, 6252, -1, 12449, 6252, 12450, -1, 12449, 12450, 12451, -1, 12452, 12451, 12447, -1, 12452, 12449, 12451, -1, 12453, 6243, 12449, -1, 12453, 12449, 12452, -1, 12454, 6243, 12453, -1, 12454, 12453, 12452, -1, 12454, 12452, 12447, -1, 12455, 12454, 12447, -1, 12455, 12447, 12446, -1, 12455, 12456, 6243, -1, 12455, 12446, 12456, -1, 12455, 6243, 12454, -1, 12457, 12458, 11547, -1, 12457, 12459, 12458, -1, 12457, 11547, 11546, -1, 12460, 12461, 12459, -1, 12460, 12462, 12461, -1, 12463, 12459, 12457, -1, 12463, 12460, 12459, -1, 12464, 6254, 12462, -1, 12464, 6252, 6254, -1, 12464, 12460, 12463, -1, 12464, 12462, 12460, -1, 12465, 12464, 12463, -1, 12450, 6252, 12464, -1, 12450, 12464, 12465, -1, 12450, 12465, 12451, -1, 12447, 12451, 12466, -1, 12445, 11551, 11557, -1, 12467, 12468, 12469, -1, 12467, 12470, 12468, -1, 12467, 11557, 12470, -1, 12467, 12469, 12446, -1, 12467, 12445, 11557, -1, 12467, 12446, 12445, -1, 12456, 6244, 6243, -1, 12471, 12472, 6244, -1, 12471, 12469, 12472, -1, 12471, 12446, 12469, -1, 12471, 6244, 12456, -1, 12471, 12456, 12446, -1, 12473, 12463, 12457, -1, 12473, 12465, 12463, -1, 12473, 12457, 11546, -1, 12474, 12465, 12473, -1, 12474, 12473, 11546, -1, 12475, 12474, 11546, -1, 12476, 12451, 12465, -1, 12476, 12465, 12474, -1, 12476, 12474, 12475, -1, 12477, 11546, 11551, -1, 12477, 12466, 12451, -1, 12477, 12475, 11546, -1, 12477, 12476, 12475, -1, 12477, 12451, 12476, -1, 12478, 12477, 11551, -1, 12478, 12447, 12466, -1, 12478, 12466, 12477, -1, 12448, 12478, 11551, -1, 12448, 12447, 12478, -1, 12444, 11551, 12445, -1, 12444, 12448, 11551, -1, 12479, 12480, 12481, -1, 12479, 12481, 12482, -1, 12483, 6354, 6367, -1, 12483, 6367, 12484, -1, 12483, 12484, 12485, -1, 12486, 12485, 12481, -1, 12486, 12483, 12485, -1, 12487, 6354, 12483, -1, 12487, 12483, 12486, -1, 12488, 6354, 12487, -1, 12488, 12487, 12486, -1, 12488, 12486, 12481, -1, 12489, 12488, 12481, -1, 12489, 12481, 12480, -1, 12489, 12490, 6354, -1, 12489, 12480, 12490, -1, 12489, 6354, 12488, -1, 12491, 12492, 11612, -1, 12491, 12493, 12492, -1, 12491, 11612, 11611, -1, 12494, 12495, 12493, -1, 12494, 12496, 12495, -1, 12497, 12493, 12491, -1, 12497, 12494, 12493, -1, 12498, 6374, 12496, -1, 12498, 6367, 6374, -1, 12498, 12494, 12497, -1, 12498, 12496, 12494, -1, 12499, 12498, 12497, -1, 12484, 12498, 12499, -1, 12484, 6367, 12498, -1, 12484, 12499, 12485, -1, 12481, 12485, 12500, -1, 12501, 11615, 11619, -1, 12502, 12503, 12504, -1, 12502, 12505, 12503, -1, 12502, 11619, 12505, -1, 12502, 12504, 12480, -1, 12502, 12501, 11619, -1, 12502, 12480, 12501, -1, 12490, 6355, 6354, -1, 12506, 12507, 6355, -1, 12506, 12504, 12507, -1, 12506, 12480, 12504, -1, 12506, 6355, 12490, -1, 12506, 12490, 12480, -1, 12508, 12497, 12491, -1, 12508, 12499, 12497, -1, 12508, 12491, 11611, -1, 12509, 12499, 12508, -1, 12509, 12508, 11611, -1, 12510, 12509, 11611, -1, 12511, 12485, 12499, -1, 12511, 12499, 12509, -1, 12511, 12509, 12510, -1, 12512, 11611, 11615, -1, 12512, 12500, 12485, -1, 12512, 12510, 11611, -1, 12512, 12511, 12510, -1, 12512, 12485, 12511, -1, 12513, 12512, 11615, -1, 12513, 12481, 12500, -1, 12513, 12500, 12512, -1, 12482, 12513, 11615, -1, 12482, 12481, 12513, -1, 12479, 11615, 12501, -1, 12479, 12482, 11615, -1, 12479, 12501, 12480, -1, 12514, 12515, 12516, -1, 12514, 12516, 12517, -1, 12518, 6539, 6548, -1, 12518, 6548, 12519, -1, 12518, 12519, 12520, -1, 12521, 12520, 12516, -1, 12521, 12518, 12520, -1, 12522, 6539, 12518, -1, 12522, 12518, 12521, -1, 12523, 6539, 12522, -1, 12523, 12522, 12521, -1, 12523, 12521, 12516, -1, 12524, 12523, 12516, -1, 12524, 12516, 12515, -1, 12524, 12525, 6539, -1, 12524, 12515, 12525, -1, 12524, 6539, 12523, -1, 12526, 12527, 11634, -1, 12526, 12528, 12527, -1, 12526, 11634, 11633, -1, 12529, 12530, 12528, -1, 12529, 12531, 12530, -1, 12532, 12528, 12526, -1, 12532, 12529, 12528, -1, 12533, 6550, 12531, -1, 12533, 6548, 6550, -1, 12533, 12529, 12532, -1, 12533, 12531, 12529, -1, 12534, 12533, 12532, -1, 12519, 6548, 12533, -1, 12519, 12533, 12534, -1, 12519, 12534, 12520, -1, 12516, 12520, 12535, -1, 12536, 11642, 11646, -1, 12537, 12538, 12539, -1, 12537, 12540, 12538, -1, 12537, 11646, 12540, -1, 12537, 12539, 12515, -1, 12537, 12536, 11646, -1, 12537, 12515, 12536, -1, 12525, 6540, 6539, -1, 12541, 12542, 6540, -1, 12541, 12539, 12542, -1, 12541, 12515, 12539, -1, 12541, 6540, 12525, -1, 12541, 12525, 12515, -1, 12543, 12532, 12526, -1, 12543, 12534, 12532, -1, 12543, 12526, 11633, -1, 12544, 12534, 12543, -1, 12544, 12543, 11633, -1, 12545, 12544, 11633, -1, 12546, 12520, 12534, -1, 12546, 12534, 12544, -1, 12546, 12544, 12545, -1, 12547, 11633, 11642, -1, 12547, 12535, 12520, -1, 12547, 12545, 11633, -1, 12547, 12546, 12545, -1, 12547, 12520, 12546, -1, 12548, 12547, 11642, -1, 12548, 12516, 12535, -1, 12548, 12535, 12547, -1, 12517, 12548, 11642, -1, 12517, 12516, 12548, -1, 12514, 11642, 12536, -1, 12514, 12517, 11642, -1, 12514, 12536, 12515, -1, 12549, 12550, 11594, -1, 12549, 12551, 12550, -1, 12552, 6575, 6584, -1, 12552, 6584, 12553, -1, 12552, 12553, 12554, -1, 12555, 12554, 12551, -1, 12555, 12552, 12554, -1, 12556, 6575, 12552, -1, 12556, 12552, 12555, -1, 12557, 6575, 12556, -1, 12557, 12556, 12555, -1, 12557, 12555, 12551, -1, 12558, 12557, 12551, -1, 12558, 12551, 12559, -1, 12558, 12560, 6575, -1, 12558, 12559, 12560, -1, 12558, 6575, 12557, -1, 12561, 12562, 11591, -1, 12561, 12563, 12562, -1, 12561, 11591, 11590, -1, 12564, 12565, 12563, -1, 12564, 12566, 12565, -1, 12567, 12564, 12563, -1, 12567, 12563, 12561, -1, 12568, 6584, 6586, -1, 12568, 6586, 12566, -1, 12568, 12564, 12567, -1, 12568, 12566, 12564, -1, 12569, 12568, 12567, -1, 12553, 6584, 12568, -1, 12553, 12568, 12569, -1, 12553, 12569, 12554, -1, 12551, 12554, 12570, -1, 12571, 11594, 11601, -1, 12572, 12573, 12574, -1, 12572, 12575, 12573, -1, 12572, 11601, 12575, -1, 12572, 12574, 12559, -1, 12572, 12571, 11601, -1, 12572, 12559, 12571, -1, 12560, 6576, 6575, -1, 12576, 12577, 6576, -1, 12576, 12574, 12577, -1, 12576, 12559, 12574, -1, 12576, 6576, 12560, -1, 12576, 12560, 12559, -1, 12578, 12567, 12561, -1, 12578, 12569, 12567, -1, 12578, 12561, 11590, -1, 12579, 12569, 12578, -1, 12579, 12578, 11590, -1, 12580, 12579, 11590, -1, 12581, 12554, 12569, -1, 12581, 12569, 12579, -1, 12581, 12579, 12580, -1, 12582, 11590, 11594, -1, 12582, 12570, 12554, -1, 12582, 12580, 11590, -1, 12582, 12554, 12581, -1, 12582, 12581, 12580, -1, 12583, 12582, 11594, -1, 12583, 12551, 12570, -1, 12583, 12570, 12582, -1, 12550, 12583, 11594, -1, 12550, 12551, 12583, -1, 12549, 11594, 12571, -1, 12549, 12559, 12551, -1, 12549, 12571, 12559, -1, 12584, 12585, 12586, -1, 12584, 12586, 11575, -1, 12587, 6686, 6699, -1, 12587, 6699, 12588, -1, 12587, 12588, 12589, -1, 12590, 12589, 12585, -1, 12590, 12587, 12589, -1, 12591, 6686, 12587, -1, 12591, 12587, 12590, -1, 12592, 6686, 12591, -1, 12592, 12591, 12590, -1, 12592, 12590, 12585, -1, 12593, 12592, 12585, -1, 12593, 12585, 12594, -1, 12593, 12595, 6686, -1, 12593, 12594, 12595, -1, 12593, 6686, 12592, -1, 12596, 12597, 11566, -1, 12596, 12598, 12597, -1, 12596, 11566, 11565, -1, 12599, 12600, 12598, -1, 12599, 12601, 12600, -1, 12602, 12599, 12598, -1, 12602, 12598, 12596, -1, 12603, 6699, 6706, -1, 12603, 6706, 12601, -1, 12603, 12599, 12602, -1, 12603, 12601, 12599, -1, 12604, 12603, 12602, -1, 12588, 6699, 12603, -1, 12588, 12604, 12589, -1, 12588, 12603, 12604, -1, 12585, 12589, 12605, -1, 12606, 11575, 11578, -1, 12607, 12608, 12609, -1, 12607, 12610, 12608, -1, 12607, 11578, 12610, -1, 12607, 12609, 12594, -1, 12607, 12606, 11578, -1, 12607, 12594, 12606, -1, 12595, 6687, 6686, -1, 12611, 12612, 6687, -1, 12611, 12609, 12612, -1, 12611, 12594, 12609, -1, 12611, 6687, 12595, -1, 12611, 12595, 12594, -1, 12613, 12602, 12596, -1, 12613, 12604, 12602, -1, 12613, 12596, 11565, -1, 12614, 12604, 12613, -1, 12614, 12613, 11565, -1, 12615, 12614, 11565, -1, 12616, 12589, 12604, -1, 12616, 12604, 12614, -1, 12616, 12614, 12615, -1, 12617, 11565, 11575, -1, 12617, 12605, 12589, -1, 12617, 12615, 11565, -1, 12617, 12589, 12616, -1, 12617, 12616, 12615, -1, 12618, 12585, 12605, -1, 12618, 12605, 12617, -1, 12618, 12617, 11575, -1, 12586, 12585, 12618, -1, 12586, 12618, 11575, -1, 12584, 11575, 12606, -1, 12584, 12594, 12585, -1, 12584, 12606, 12594, -1, 12619, 12620, 12621, -1, 12619, 12622, 11650, -1, 12619, 12621, 12622, -1, 12623, 12624, 12625, -1, 12623, 12625, 12626, -1, 12623, 12626, 12627, -1, 12628, 12627, 12621, -1, 12628, 12623, 12627, -1, 12629, 12624, 12623, -1, 12629, 12623, 12628, -1, 12630, 12624, 12629, -1, 12630, 12629, 12628, -1, 12630, 12628, 12621, -1, 12631, 12630, 12621, -1, 12631, 12621, 12620, -1, 12631, 12632, 12624, -1, 12631, 12620, 12632, -1, 12631, 12624, 12630, -1, 12633, 12634, 11657, -1, 12633, 12635, 12634, -1, 12633, 11657, 11656, -1, 12636, 12637, 12635, -1, 12636, 12638, 12637, -1, 12639, 12635, 12633, -1, 12639, 12636, 12635, -1, 12640, 12641, 12638, -1, 12640, 12625, 12641, -1, 12640, 12636, 12639, -1, 12640, 12638, 12636, -1, 12642, 12640, 12639, -1, 12626, 12625, 12640, -1, 12626, 12640, 12642, -1, 12626, 12642, 12627, -1, 12621, 12627, 12643, -1, 12644, 11650, 11649, -1, 12645, 12646, 12647, -1, 12645, 12648, 12646, -1, 12645, 11649, 12648, -1, 12645, 12647, 12620, -1, 12645, 12644, 11649, -1, 12645, 12620, 12644, -1, 12632, 12649, 12624, -1, 12650, 12651, 12649, -1, 12650, 12647, 12651, -1, 12650, 12620, 12647, -1, 12650, 12649, 12632, -1, 12650, 12632, 12620, -1, 12652, 12639, 12633, -1, 12652, 12642, 12639, -1, 12652, 12633, 11656, -1, 12653, 12642, 12652, -1, 12653, 12652, 11656, -1, 12654, 12653, 11656, -1, 12655, 12627, 12642, -1, 12655, 12642, 12653, -1, 12655, 12653, 12654, -1, 12656, 11656, 11650, -1, 12656, 12643, 12627, -1, 12656, 12654, 11656, -1, 12656, 12655, 12654, -1, 12656, 12627, 12655, -1, 12657, 12621, 12643, -1, 12657, 12643, 12656, -1, 12657, 12656, 11650, -1, 12622, 12657, 11650, -1, 12622, 12621, 12657, -1, 12619, 11650, 12644, -1, 12619, 12644, 12620, -1, 12658, 12659, 12660, -1, 12658, 12661, 12662, -1, 12658, 12662, 11664, -1, 12663, 12664, 12665, -1, 12663, 12665, 12666, -1, 12663, 12666, 12667, -1, 12668, 12667, 12661, -1, 12668, 12663, 12667, -1, 12669, 12664, 12663, -1, 12669, 12663, 12668, -1, 12670, 12664, 12669, -1, 12670, 12669, 12668, -1, 12670, 12668, 12661, -1, 12671, 12670, 12661, -1, 12671, 12661, 12660, -1, 12671, 12672, 12664, -1, 12671, 12660, 12672, -1, 12671, 12664, 12670, -1, 12673, 12674, 11668, -1, 12673, 12675, 12674, -1, 12673, 11668, 11667, -1, 12676, 12677, 12675, -1, 12676, 12678, 12677, -1, 12679, 12676, 12675, -1, 12679, 12675, 12673, -1, 12680, 12665, 12681, -1, 12680, 12681, 12678, -1, 12680, 12676, 12679, -1, 12680, 12678, 12676, -1, 12682, 12680, 12679, -1, 12666, 12665, 12680, -1, 12666, 12682, 12667, -1, 12666, 12680, 12682, -1, 12661, 12667, 12683, -1, 12659, 11664, 11663, -1, 12684, 12685, 12686, -1, 12684, 12687, 12685, -1, 12684, 11663, 12687, -1, 12684, 12686, 12660, -1, 12684, 12659, 11663, -1, 12684, 12660, 12659, -1, 12672, 12688, 12664, -1, 12689, 12690, 12688, -1, 12689, 12686, 12690, -1, 12689, 12660, 12686, -1, 12689, 12688, 12672, -1, 12689, 12672, 12660, -1, 12691, 12679, 12673, -1, 12691, 12682, 12679, -1, 12691, 12673, 11667, -1, 12692, 12682, 12691, -1, 12692, 12691, 11667, -1, 12693, 12692, 11667, -1, 12694, 12667, 12682, -1, 12694, 12682, 12692, -1, 12694, 12692, 12693, -1, 12695, 11667, 11664, -1, 12695, 12683, 12667, -1, 12695, 12693, 11667, -1, 12695, 12667, 12694, -1, 12695, 12694, 12693, -1, 12696, 12661, 12683, -1, 12696, 12683, 12695, -1, 12696, 12695, 11664, -1, 12662, 12661, 12696, -1, 12662, 12696, 11664, -1, 12658, 11664, 12659, -1, 12658, 12660, 12661, -1, 12697, 12698, 12699, -1, 12697, 12700, 11604, -1, 12697, 12699, 12700, -1, 12701, 12702, 12703, -1, 12701, 12703, 12704, -1, 12701, 12704, 12705, -1, 12706, 12705, 12699, -1, 12706, 12701, 12705, -1, 12707, 12702, 12701, -1, 12707, 12701, 12706, -1, 12708, 12702, 12707, -1, 12708, 12707, 12706, -1, 12708, 12706, 12699, -1, 12709, 12708, 12699, -1, 12709, 12699, 12698, -1, 12709, 12710, 12702, -1, 12709, 12698, 12710, -1, 12709, 12702, 12708, -1, 12711, 12712, 11614, -1, 12711, 12713, 12712, -1, 12711, 11614, 11613, -1, 12714, 12715, 12713, -1, 12714, 12716, 12715, -1, 12717, 12713, 12711, -1, 12717, 12714, 12713, -1, 12718, 12719, 12716, -1, 12718, 12703, 12719, -1, 12718, 12714, 12717, -1, 12718, 12716, 12714, -1, 12720, 12718, 12717, -1, 12704, 12718, 12720, -1, 12704, 12703, 12718, -1, 12704, 12720, 12705, -1, 12699, 12705, 12721, -1, 12722, 11604, 11603, -1, 12723, 12724, 12725, -1, 12723, 12726, 12724, -1, 12723, 11603, 12726, -1, 12723, 12725, 12698, -1, 12723, 12722, 11603, -1, 12723, 12698, 12722, -1, 12710, 12727, 12702, -1, 12728, 12729, 12727, -1, 12728, 12725, 12729, -1, 12728, 12698, 12725, -1, 12728, 12727, 12710, -1, 12728, 12710, 12698, -1, 12730, 12717, 12711, -1, 12730, 12720, 12717, -1, 12730, 12711, 11613, -1, 12731, 12720, 12730, -1, 12731, 12730, 11613, -1, 12732, 12731, 11613, -1, 12733, 12705, 12720, -1, 12733, 12720, 12731, -1, 12733, 12731, 12732, -1, 12734, 11613, 11604, -1, 12734, 12721, 12705, -1, 12734, 12732, 11613, -1, 12734, 12733, 12732, -1, 12734, 12705, 12733, -1, 12735, 12699, 12721, -1, 12735, 12721, 12734, -1, 12735, 12734, 11604, -1, 12700, 12735, 11604, -1, 12700, 12699, 12735, -1, 12697, 11604, 12722, -1, 12697, 12722, 12698, -1, 12736, 12737, 12738, -1, 12736, 12739, 12740, -1, 12736, 12740, 11621, -1, 12741, 12742, 12743, -1, 12741, 12743, 12744, -1, 12741, 12744, 12745, -1, 12746, 12745, 12739, -1, 12746, 12741, 12745, -1, 12747, 12742, 12741, -1, 12747, 12741, 12746, -1, 12748, 12742, 12747, -1, 12748, 12747, 12746, -1, 12748, 12746, 12739, -1, 12749, 12748, 12739, -1, 12749, 12739, 12738, -1, 12749, 12750, 12742, -1, 12749, 12738, 12750, -1, 12749, 12742, 12748, -1, 12751, 12752, 11636, -1, 12751, 12753, 12752, -1, 12751, 11636, 11635, -1, 12754, 12755, 12753, -1, 12754, 12756, 12755, -1, 12757, 12754, 12753, -1, 12757, 12753, 12751, -1, 12758, 12743, 12759, -1, 12758, 12759, 12756, -1, 12758, 12754, 12757, -1, 12758, 12756, 12754, -1, 12760, 12758, 12757, -1, 12744, 12743, 12758, -1, 12744, 12758, 12760, -1, 12744, 12760, 12745, -1, 12739, 12745, 12761, -1, 12737, 11621, 11620, -1, 12762, 12763, 12764, -1, 12762, 12765, 12763, -1, 12762, 11620, 12765, -1, 12762, 12764, 12738, -1, 12762, 12737, 11620, -1, 12762, 12738, 12737, -1, 12750, 12766, 12742, -1, 12767, 12768, 12766, -1, 12767, 12764, 12768, -1, 12767, 12766, 12750, -1, 12767, 12738, 12764, -1, 12767, 12750, 12738, -1, 12769, 12757, 12751, -1, 12769, 12760, 12757, -1, 12769, 12751, 11635, -1, 12770, 12760, 12769, -1, 12770, 12769, 11635, -1, 12771, 12770, 11635, -1, 12772, 12745, 12760, -1, 12772, 12760, 12770, -1, 12772, 12770, 12771, -1, 12773, 11635, 11621, -1, 12773, 12761, 12745, -1, 12773, 12771, 11635, -1, 12773, 12745, 12772, -1, 12773, 12772, 12771, -1, 12774, 12739, 12761, -1, 12774, 12761, 12773, -1, 12774, 12773, 11621, -1, 12740, 12739, 12774, -1, 12740, 12774, 11621, -1, 12736, 11621, 12737, -1, 12736, 12738, 12739, -1, 12775, 12776, 12777, -1, 12775, 12777, 12778, -1, 12775, 12778, 12779, -1, 12780, 12781, 12782, -1, 12780, 12782, 12783, -1, 12780, 12783, 12784, -1, 12785, 12784, 12778, -1, 12785, 12780, 12784, -1, 12786, 12781, 12780, -1, 12786, 12780, 12785, -1, 12787, 12781, 12786, -1, 12787, 12786, 12785, -1, 12787, 12785, 12778, -1, 12788, 12787, 12778, -1, 12788, 12778, 12777, -1, 12788, 12789, 12781, -1, 12788, 12777, 12789, -1, 12788, 12781, 12787, -1, 12790, 12791, 11393, -1, 12790, 12792, 12791, -1, 12790, 11393, 11388, -1, 12793, 12794, 12792, -1, 12793, 12795, 12794, -1, 12796, 12792, 12790, -1, 12796, 12793, 12792, -1, 12797, 12798, 12795, -1, 12797, 12782, 12798, -1, 12797, 12793, 12796, -1, 12797, 12795, 12793, -1, 12799, 12797, 12796, -1, 12783, 12797, 12799, -1, 12783, 12782, 12797, -1, 12783, 12799, 12784, -1, 12778, 12784, 12800, -1, 12776, 11380, 11379, -1, 12801, 12802, 12803, -1, 12801, 12804, 12802, -1, 12801, 11379, 12804, -1, 12801, 12803, 12777, -1, 12801, 12776, 11379, -1, 12801, 12777, 12776, -1, 12789, 12805, 12781, -1, 12806, 12807, 12805, -1, 12806, 12803, 12807, -1, 12806, 12777, 12803, -1, 12806, 12805, 12789, -1, 12806, 12789, 12777, -1, 12808, 12796, 12790, -1, 12808, 12799, 12796, -1, 12808, 12790, 11388, -1, 12809, 12799, 12808, -1, 12809, 12808, 11388, -1, 12810, 12809, 11388, -1, 12811, 12784, 12799, -1, 12811, 12799, 12809, -1, 12811, 12809, 12810, -1, 12812, 11388, 11380, -1, 12812, 12800, 12784, -1, 12812, 12810, 11388, -1, 12812, 12811, 12810, -1, 12812, 12784, 12811, -1, 12813, 12812, 11380, -1, 12813, 12778, 12800, -1, 12813, 12800, 12812, -1, 12779, 12813, 11380, -1, 12779, 12778, 12813, -1, 12775, 11380, 12776, -1, 12775, 12779, 11380, -1, 12814, 12815, 12816, -1, 12814, 12816, 12817, -1, 12814, 12817, 12818, -1, 12819, 12820, 12821, -1, 12819, 12821, 12822, -1, 12819, 12822, 12823, -1, 12824, 12823, 12817, -1, 12824, 12819, 12823, -1, 12825, 12820, 12819, -1, 12825, 12819, 12824, -1, 12826, 12820, 12825, -1, 12826, 12825, 12824, -1, 12826, 12824, 12817, -1, 12827, 12826, 12817, -1, 12827, 12817, 12816, -1, 12827, 12828, 12820, -1, 12827, 12816, 12828, -1, 12827, 12820, 12826, -1, 12829, 12830, 11362, -1, 12829, 12831, 12830, -1, 12829, 11362, 11361, -1, 12832, 12833, 12831, -1, 12832, 12834, 12833, -1, 12835, 12831, 12829, -1, 12835, 12832, 12831, -1, 12836, 12837, 12834, -1, 12836, 12821, 12837, -1, 12836, 12832, 12835, -1, 12836, 12834, 12832, -1, 12838, 12836, 12835, -1, 12822, 12836, 12838, -1, 12822, 12821, 12836, -1, 12822, 12838, 12823, -1, 12817, 12823, 12839, -1, 12815, 11352, 11351, -1, 12840, 12841, 12842, -1, 12840, 12843, 12841, -1, 12840, 11351, 12843, -1, 12840, 12842, 12816, -1, 12840, 12815, 11351, -1, 12840, 12816, 12815, -1, 12828, 12844, 12820, -1, 12845, 12846, 12844, -1, 12845, 12842, 12846, -1, 12845, 12816, 12842, -1, 12845, 12844, 12828, -1, 12845, 12828, 12816, -1, 12847, 12835, 12829, -1, 12847, 12838, 12835, -1, 12847, 12829, 11361, -1, 12848, 12838, 12847, -1, 12848, 12847, 11361, -1, 12849, 12848, 11361, -1, 12850, 12823, 12838, -1, 12850, 12838, 12848, -1, 12850, 12848, 12849, -1, 12851, 11361, 11352, -1, 12851, 12839, 12823, -1, 12851, 12849, 11361, -1, 12851, 12850, 12849, -1, 12851, 12823, 12850, -1, 12852, 12851, 11352, -1, 12852, 12817, 12839, -1, 12852, 12839, 12851, -1, 12818, 12852, 11352, -1, 12818, 12817, 12852, -1, 12814, 11352, 12815, -1, 12814, 12818, 11352, -1, 12853, 12854, 12855, -1, 12853, 12856, 11288, -1, 12853, 12857, 12856, -1, 12858, 12859, 12860, -1, 12858, 12860, 12861, -1, 12858, 12861, 12862, -1, 12863, 12862, 12857, -1, 12863, 12858, 12862, -1, 12864, 12859, 12858, -1, 12864, 12858, 12863, -1, 12865, 12859, 12864, -1, 12865, 12864, 12863, -1, 12865, 12863, 12857, -1, 12866, 12865, 12857, -1, 12866, 12857, 12855, -1, 12866, 12867, 12859, -1, 12866, 12855, 12867, -1, 12866, 12859, 12865, -1, 12868, 12869, 11302, -1, 12868, 12870, 12869, -1, 12868, 11302, 11301, -1, 12871, 12872, 12870, -1, 12871, 12873, 12872, -1, 12874, 12871, 12870, -1, 12874, 12870, 12868, -1, 12875, 12860, 12876, -1, 12875, 12876, 12873, -1, 12875, 12871, 12874, -1, 12875, 12873, 12871, -1, 12877, 12875, 12874, -1, 12861, 12860, 12875, -1, 12861, 12877, 12862, -1, 12861, 12875, 12877, -1, 12857, 12862, 12878, -1, 12854, 11288, 11287, -1, 12879, 12880, 12881, -1, 12879, 12882, 12880, -1, 12879, 11287, 12882, -1, 12879, 12881, 12855, -1, 12879, 12854, 11287, -1, 12879, 12855, 12854, -1, 12867, 12883, 12859, -1, 12884, 12885, 12883, -1, 12884, 12881, 12885, -1, 12884, 12855, 12881, -1, 12884, 12883, 12867, -1, 12884, 12867, 12855, -1, 12886, 12874, 12868, -1, 12886, 12877, 12874, -1, 12886, 12868, 11301, -1, 12887, 12877, 12886, -1, 12887, 12886, 11301, -1, 12888, 12887, 11301, -1, 12889, 12862, 12877, -1, 12889, 12877, 12887, -1, 12889, 12887, 12888, -1, 12890, 11301, 11288, -1, 12890, 12878, 12862, -1, 12890, 12888, 11301, -1, 12890, 12862, 12889, -1, 12890, 12889, 12888, -1, 12891, 12890, 11288, -1, 12891, 12857, 12878, -1, 12891, 12878, 12890, -1, 12856, 12891, 11288, -1, 12856, 12857, 12891, -1, 12853, 11288, 12854, -1, 12853, 12855, 12857, -1, 12892, 12893, 12894, -1, 12892, 12894, 11319, -1, 12895, 12896, 12897, -1, 12895, 12897, 12898, -1, 12895, 12898, 12899, -1, 12900, 12899, 12893, -1, 12900, 12895, 12899, -1, 12901, 12896, 12895, -1, 12901, 12895, 12900, -1, 12902, 12896, 12901, -1, 12902, 12901, 12900, -1, 12902, 12900, 12893, -1, 12903, 12902, 12893, -1, 12903, 12893, 12904, -1, 12903, 12905, 12896, -1, 12903, 12904, 12905, -1, 12903, 12896, 12902, -1, 12906, 12907, 11331, -1, 12906, 12908, 12907, -1, 12906, 11331, 11330, -1, 12909, 12910, 12908, -1, 12909, 12911, 12910, -1, 12912, 12909, 12908, -1, 12912, 12908, 12906, -1, 12913, 12897, 12914, -1, 12913, 12914, 12911, -1, 12913, 12909, 12912, -1, 12913, 12911, 12909, -1, 12915, 12913, 12912, -1, 12898, 12897, 12913, -1, 12898, 12913, 12915, -1, 12898, 12915, 12899, -1, 12893, 12899, 12916, -1, 12917, 11319, 11318, -1, 12918, 12919, 12920, -1, 12918, 12921, 12919, -1, 12918, 11318, 12921, -1, 12918, 12920, 12904, -1, 12918, 12917, 11318, -1, 12918, 12904, 12917, -1, 12905, 12922, 12896, -1, 12923, 12924, 12922, -1, 12923, 12920, 12924, -1, 12923, 12922, 12905, -1, 12923, 12904, 12920, -1, 12923, 12905, 12904, -1, 12925, 12912, 12906, -1, 12925, 12915, 12912, -1, 12925, 12906, 11330, -1, 12926, 12915, 12925, -1, 12926, 12925, 11330, -1, 12927, 12926, 11330, -1, 12928, 12899, 12915, -1, 12928, 12915, 12926, -1, 12928, 12926, 12927, -1, 12929, 11330, 11319, -1, 12929, 12916, 12899, -1, 12929, 12927, 11330, -1, 12929, 12899, 12928, -1, 12929, 12928, 12927, -1, 12930, 12893, 12916, -1, 12930, 12916, 12929, -1, 12930, 12929, 11319, -1, 12894, 12893, 12930, -1, 12894, 12930, 11319, -1, 12892, 11319, 12917, -1, 12892, 12904, 12893, -1, 12892, 12917, 12904, -1, 12931, 12932, 11521, -1, 12931, 12933, 12932, -1, 12934, 7695, 7704, -1, 12934, 7704, 12935, -1, 12934, 12935, 12936, -1, 12937, 12936, 12933, -1, 12937, 12934, 12936, -1, 12938, 7695, 12934, -1, 12938, 12934, 12937, -1, 12939, 7695, 12938, -1, 12939, 12938, 12937, -1, 12939, 12937, 12933, -1, 12940, 12939, 12933, -1, 12940, 12933, 12941, -1, 12940, 12942, 7695, -1, 12940, 12941, 12942, -1, 12940, 7695, 12939, -1, 12943, 12944, 11531, -1, 12943, 12945, 12944, -1, 12943, 11531, 11530, -1, 12946, 12947, 12945, -1, 12946, 12948, 12947, -1, 12949, 12945, 12943, -1, 12949, 12946, 12945, -1, 12950, 7706, 12948, -1, 12950, 7704, 7706, -1, 12950, 12946, 12949, -1, 12950, 12948, 12946, -1, 12951, 12950, 12949, -1, 12935, 7704, 12950, -1, 12935, 12950, 12951, -1, 12935, 12951, 12936, -1, 12933, 12936, 12952, -1, 12953, 11521, 11520, -1, 12954, 12955, 12956, -1, 12954, 12957, 12955, -1, 12954, 11520, 12957, -1, 12954, 12956, 12941, -1, 12954, 12953, 11520, -1, 12954, 12941, 12953, -1, 12942, 7696, 7695, -1, 12958, 12959, 7696, -1, 12958, 12956, 12959, -1, 12958, 12941, 12956, -1, 12958, 7696, 12942, -1, 12958, 12942, 12941, -1, 12960, 12949, 12943, -1, 12960, 12951, 12949, -1, 12960, 12943, 11530, -1, 12961, 12951, 12960, -1, 12961, 12960, 11530, -1, 12962, 12961, 11530, -1, 12963, 12936, 12951, -1, 12963, 12951, 12961, -1, 12963, 12961, 12962, -1, 12964, 11530, 11521, -1, 12964, 12952, 12936, -1, 12964, 12962, 11530, -1, 12964, 12963, 12962, -1, 12964, 12936, 12963, -1, 12965, 12933, 12952, -1, 12965, 12952, 12964, -1, 12965, 12964, 11521, -1, 12932, 12965, 11521, -1, 12932, 12933, 12965, -1, 12931, 11521, 12953, -1, 12931, 12953, 12941, -1, 12931, 12941, 12933, -1, 12966, 12967, 12968, -1, 12966, 12969, 12970, -1, 12966, 12970, 11542, -1, 12971, 12972, 12973, -1, 12971, 12973, 12974, -1, 12971, 12974, 12975, -1, 12976, 12975, 12969, -1, 12976, 12971, 12975, -1, 12977, 12972, 12971, -1, 12977, 12971, 12976, -1, 12978, 12972, 12977, -1, 12978, 12977, 12976, -1, 12978, 12976, 12969, -1, 12979, 12978, 12969, -1, 12979, 12969, 12968, -1, 12979, 12980, 12972, -1, 12979, 12968, 12980, -1, 12979, 12972, 12978, -1, 12981, 12982, 11549, -1, 12981, 12983, 12982, -1, 12981, 11549, 11548, -1, 12984, 12985, 12983, -1, 12984, 12986, 12985, -1, 12987, 12984, 12983, -1, 12987, 12983, 12981, -1, 12988, 12973, 12989, -1, 12988, 12989, 12986, -1, 12988, 12984, 12987, -1, 12988, 12986, 12984, -1, 12990, 12988, 12987, -1, 12974, 12973, 12988, -1, 12974, 12988, 12990, -1, 12974, 12990, 12975, -1, 12969, 12975, 12991, -1, 12967, 11542, 11541, -1, 12992, 12993, 12994, -1, 12992, 12995, 12993, -1, 12992, 11541, 12995, -1, 12992, 12994, 12968, -1, 12992, 12967, 11541, -1, 12992, 12968, 12967, -1, 12980, 12996, 12972, -1, 12997, 12998, 12996, -1, 12997, 12994, 12998, -1, 12997, 12996, 12980, -1, 12997, 12968, 12994, -1, 12997, 12980, 12968, -1, 12999, 12987, 12981, -1, 12999, 12990, 12987, -1, 12999, 12981, 11548, -1, 13000, 12990, 12999, -1, 13000, 12999, 11548, -1, 13001, 13000, 11548, -1, 13002, 12975, 12990, -1, 13002, 12990, 13000, -1, 13002, 13000, 13001, -1, 13003, 11548, 11542, -1, 13003, 12991, 12975, -1, 13003, 13001, 11548, -1, 13003, 12975, 13002, -1, 13003, 13002, 13001, -1, 13004, 12969, 12991, -1, 13004, 12991, 13003, -1, 13004, 13003, 11542, -1, 12970, 12969, 13004, -1, 12970, 13004, 11542, -1, 12966, 11542, 12967, -1, 12966, 12968, 12969, -1, 13005, 13006, 11582, -1, 13005, 13007, 13006, -1, 13008, 13009, 13010, -1, 13008, 13010, 13011, -1, 13008, 13011, 13012, -1, 13013, 13012, 13007, -1, 13013, 13008, 13012, -1, 13014, 13009, 13008, -1, 13014, 13008, 13013, -1, 13015, 13009, 13014, -1, 13015, 13014, 13013, -1, 13015, 13013, 13007, -1, 13016, 13015, 13007, -1, 13016, 13007, 13017, -1, 13016, 13018, 13009, -1, 13016, 13017, 13018, -1, 13016, 13009, 13015, -1, 13019, 13020, 11593, -1, 13019, 13021, 13020, -1, 13019, 11593, 11592, -1, 13022, 13023, 13021, -1, 13022, 13024, 13023, -1, 13025, 13021, 13019, -1, 13025, 13022, 13021, -1, 13026, 13027, 13024, -1, 13026, 13010, 13027, -1, 13026, 13022, 13025, -1, 13026, 13024, 13022, -1, 13028, 13026, 13025, -1, 13011, 13026, 13028, -1, 13011, 13010, 13026, -1, 13011, 13028, 13012, -1, 13007, 13012, 13029, -1, 13030, 11582, 11581, -1, 13031, 13032, 13033, -1, 13031, 13034, 13032, -1, 13031, 11581, 13034, -1, 13031, 13033, 13017, -1, 13031, 13030, 11581, -1, 13031, 13017, 13030, -1, 13018, 13035, 13009, -1, 13036, 13037, 13035, -1, 13036, 13033, 13037, -1, 13036, 13017, 13033, -1, 13036, 13035, 13018, -1, 13036, 13018, 13017, -1, 13038, 13025, 13019, -1, 13038, 13028, 13025, -1, 13038, 13019, 11592, -1, 13039, 13028, 13038, -1, 13039, 13038, 11592, -1, 13040, 13039, 11592, -1, 13041, 13012, 13028, -1, 13041, 13028, 13039, -1, 13041, 13039, 13040, -1, 13042, 11592, 11582, -1, 13042, 13029, 13012, -1, 13042, 13040, 11592, -1, 13042, 13041, 13040, -1, 13042, 13012, 13041, -1, 13043, 13007, 13029, -1, 13043, 13029, 13042, -1, 13043, 13042, 11582, -1, 13006, 13043, 11582, -1, 13006, 13007, 13043, -1, 13005, 11582, 13030, -1, 13005, 13030, 13017, -1, 13005, 13017, 13007, -1, 13044, 13045, 13046, -1, 13044, 13046, 11562, -1, 13047, 13048, 13049, -1, 13047, 13049, 13050, -1, 13047, 13050, 13051, -1, 13052, 13051, 13045, -1, 13052, 13047, 13051, -1, 13053, 13048, 13047, -1, 13053, 13047, 13052, -1, 13054, 13048, 13053, -1, 13054, 13053, 13052, -1, 13054, 13052, 13045, -1, 13055, 13054, 13045, -1, 13055, 13045, 13056, -1, 13055, 13057, 13048, -1, 13055, 13056, 13057, -1, 13055, 13048, 13054, -1, 13058, 13059, 11574, -1, 13058, 13060, 13059, -1, 13058, 11574, 11573, -1, 13061, 13062, 13060, -1, 13061, 13063, 13062, -1, 13064, 13061, 13060, -1, 13064, 13060, 13058, -1, 13065, 13049, 13066, -1, 13065, 13066, 13063, -1, 13065, 13061, 13064, -1, 13065, 13063, 13061, -1, 13067, 13065, 13064, -1, 13050, 13049, 13065, -1, 13050, 13065, 13067, -1, 13050, 13067, 13051, -1, 13045, 13051, 13068, -1, 13069, 11562, 11561, -1, 13070, 13071, 13072, -1, 13070, 13073, 13071, -1, 13070, 11561, 13073, -1, 13070, 13072, 13056, -1, 13070, 13069, 11561, -1, 13070, 13056, 13069, -1, 13057, 13074, 13048, -1, 13075, 13076, 13074, -1, 13075, 13072, 13076, -1, 13075, 13074, 13057, -1, 13075, 13056, 13072, -1, 13075, 13057, 13056, -1, 13077, 13064, 13058, -1, 13077, 13067, 13064, -1, 13077, 13058, 11573, -1, 13078, 13067, 13077, -1, 13078, 13077, 11573, -1, 13079, 13078, 11573, -1, 13080, 13051, 13067, -1, 13080, 13067, 13078, -1, 13080, 13078, 13079, -1, 13081, 11573, 11562, -1, 13081, 13068, 13051, -1, 13081, 13079, 11573, -1, 13081, 13051, 13080, -1, 13081, 13080, 13079, -1, 13082, 13045, 13068, -1, 13082, 13068, 13081, -1, 13082, 13081, 11562, -1, 13046, 13045, 13082, -1, 13046, 13082, 11562, -1, 13044, 11562, 13069, -1, 13044, 13056, 13045, -1, 13044, 13069, 13056, -1, 13083, 13084, 13085, -1, 13083, 13085, 13086, -1, 13087, 13088, 13089, -1, 13087, 13089, 13090, -1, 13087, 13090, 13091, -1, 13092, 13091, 13085, -1, 13092, 13087, 13091, -1, 13093, 13088, 13087, -1, 13093, 13087, 13092, -1, 13094, 13088, 13093, -1, 13094, 13093, 13092, -1, 13094, 13092, 13085, -1, 13095, 13094, 13085, -1, 13095, 13085, 13084, -1, 13095, 13096, 13088, -1, 13095, 13084, 13096, -1, 13095, 13088, 13094, -1, 13097, 13098, 11503, -1, 13097, 13099, 13098, -1, 13097, 11503, 11502, -1, 13100, 13101, 13099, -1, 13100, 13102, 13101, -1, 13103, 13099, 13097, -1, 13103, 13100, 13099, -1, 13104, 13105, 13102, -1, 13104, 13089, 13105, -1, 13104, 13100, 13103, -1, 13104, 13102, 13100, -1, 13106, 13104, 13103, -1, 13090, 13089, 13104, -1, 13090, 13104, 13106, -1, 13090, 13106, 13091, -1, 13085, 13091, 13107, -1, 13108, 11489, 11488, -1, 13109, 13110, 13111, -1, 13109, 13112, 13110, -1, 13109, 11488, 13112, -1, 13109, 13111, 13084, -1, 13109, 13108, 11488, -1, 13109, 13084, 13108, -1, 13096, 13113, 13088, -1, 13114, 13115, 13113, -1, 13114, 13111, 13115, -1, 13114, 13084, 13111, -1, 13114, 13113, 13096, -1, 13114, 13096, 13084, -1, 13116, 13103, 13097, -1, 13116, 13106, 13103, -1, 13116, 13097, 11502, -1, 13117, 13106, 13116, -1, 13117, 13116, 11502, -1, 13118, 13117, 11502, -1, 13119, 13091, 13106, -1, 13119, 13106, 13117, -1, 13119, 13117, 13118, -1, 13120, 11502, 11489, -1, 13120, 13107, 13091, -1, 13120, 13118, 11502, -1, 13120, 13119, 13118, -1, 13120, 13091, 13119, -1, 13121, 13120, 11489, -1, 13121, 13085, 13107, -1, 13121, 13107, 13120, -1, 13086, 13121, 11489, -1, 13086, 13085, 13121, -1, 13083, 11489, 13108, -1, 13083, 13086, 11489, -1, 13083, 13108, 13084, -1, 13122, 13123, 13124, -1, 13122, 13124, 13125, -1, 13122, 13125, 13126, -1, 13127, 8355, 8364, -1, 13127, 8364, 13128, -1, 13127, 13128, 13129, -1, 13130, 13129, 13125, -1, 13130, 13127, 13129, -1, 13131, 8355, 13127, -1, 13131, 13127, 13130, -1, 13132, 8355, 13131, -1, 13132, 13131, 13130, -1, 13132, 13130, 13125, -1, 13133, 13132, 13125, -1, 13133, 13125, 13124, -1, 13133, 13134, 8355, -1, 13133, 13124, 13134, -1, 13133, 8355, 13132, -1, 13135, 13136, 11477, -1, 13135, 13137, 13136, -1, 13135, 11477, 11476, -1, 13138, 13139, 13137, -1, 13138, 13140, 13139, -1, 13141, 13137, 13135, -1, 13141, 13138, 13137, -1, 13142, 8366, 13140, -1, 13142, 8364, 8366, -1, 13142, 13138, 13141, -1, 13142, 13140, 13138, -1, 13143, 13142, 13141, -1, 13128, 13142, 13143, -1, 13128, 8364, 13142, -1, 13128, 13143, 13129, -1, 13125, 13129, 13144, -1, 13123, 11455, 11454, -1, 13145, 13146, 13147, -1, 13145, 13148, 13146, -1, 13145, 11454, 13148, -1, 13145, 13147, 13124, -1, 13145, 13123, 11454, -1, 13145, 13124, 13123, -1, 13134, 8356, 8355, -1, 13149, 13150, 8356, -1, 13149, 13147, 13150, -1, 13149, 13124, 13147, -1, 13149, 8356, 13134, -1, 13149, 13134, 13124, -1, 13151, 13141, 13135, -1, 13151, 13143, 13141, -1, 13151, 13135, 11476, -1, 13152, 13143, 13151, -1, 13152, 13151, 11476, -1, 13153, 13152, 11476, -1, 13154, 13129, 13143, -1, 13154, 13143, 13152, -1, 13154, 13152, 13153, -1, 13155, 11476, 11455, -1, 13155, 13144, 13129, -1, 13155, 13153, 11476, -1, 13155, 13154, 13153, -1, 13155, 13129, 13154, -1, 13156, 13155, 11455, -1, 13156, 13125, 13144, -1, 13156, 13144, 13155, -1, 13126, 13156, 11455, -1, 13126, 13125, 13156, -1, 13122, 11455, 13123, -1, 13122, 13126, 11455, -1, 13157, 13158, 11381, -1, 13157, 13159, 13158, -1, 13160, 8462, 8475, -1, 13160, 8475, 13161, -1, 13160, 13161, 13162, -1, 13163, 13162, 13159, -1, 13163, 13160, 13162, -1, 13164, 8462, 13160, -1, 13164, 13160, 13163, -1, 13165, 8462, 13164, -1, 13165, 13164, 13163, -1, 13165, 13163, 13159, -1, 13166, 13165, 13159, -1, 13166, 13159, 13167, -1, 13166, 13168, 8462, -1, 13166, 13167, 13168, -1, 13166, 8462, 13165, -1, 13169, 13170, 11433, -1, 13169, 13171, 13170, -1, 13169, 11433, 11430, -1, 13172, 13173, 13171, -1, 13172, 13174, 13173, -1, 13175, 13171, 13169, -1, 13175, 13172, 13171, -1, 13176, 8482, 13174, -1, 13176, 8475, 8482, -1, 13176, 13172, 13175, -1, 13176, 13174, 13172, -1, 13177, 13176, 13175, -1, 13161, 13176, 13177, -1, 13161, 8475, 13176, -1, 13161, 13177, 13162, -1, 13159, 13162, 13178, -1, 13179, 11381, 11383, -1, 13180, 13181, 13182, -1, 13180, 13183, 13181, -1, 13180, 11383, 13183, -1, 13180, 13182, 13167, -1, 13180, 13179, 11383, -1, 13180, 13167, 13179, -1, 13168, 8463, 8462, -1, 13184, 13185, 8463, -1, 13184, 13182, 13185, -1, 13184, 13167, 13182, -1, 13184, 8463, 13168, -1, 13184, 13168, 13167, -1, 13186, 13175, 13169, -1, 13186, 13177, 13175, -1, 13186, 13169, 11430, -1, 13187, 13177, 13186, -1, 13187, 13186, 11430, -1, 13188, 13187, 11430, -1, 13189, 13162, 13177, -1, 13189, 13177, 13187, -1, 13189, 13187, 13188, -1, 13190, 11430, 11381, -1, 13190, 13178, 13162, -1, 13190, 13188, 11430, -1, 13190, 13189, 13188, -1, 13190, 13162, 13189, -1, 13191, 13159, 13178, -1, 13191, 13178, 13190, -1, 13191, 13190, 11381, -1, 13158, 13191, 11381, -1, 13158, 13159, 13191, -1, 13157, 11381, 13179, -1, 13157, 13179, 13167, -1, 13157, 13167, 13159, -1, 13192, 13193, 11356, -1, 13192, 13194, 13193, -1, 13195, 8555, 8564, -1, 13195, 8564, 13196, -1, 13195, 13196, 13197, -1, 13198, 13197, 13194, -1, 13198, 13195, 13197, -1, 13199, 8555, 13195, -1, 13199, 13195, 13198, -1, 13200, 8555, 13199, -1, 13200, 13199, 13198, -1, 13200, 13198, 13194, -1, 13201, 13200, 13194, -1, 13201, 13194, 13202, -1, 13201, 13203, 8555, -1, 13201, 13202, 13203, -1, 13201, 8555, 13200, -1, 13204, 13205, 11372, -1, 13204, 13206, 13205, -1, 13204, 11372, 11371, -1, 13207, 13208, 13206, -1, 13207, 13209, 13208, -1, 13210, 13207, 13206, -1, 13210, 13206, 13204, -1, 13211, 8564, 8566, -1, 13211, 8566, 13209, -1, 13211, 13207, 13210, -1, 13211, 13209, 13207, -1, 13212, 13211, 13210, -1, 13196, 8564, 13211, -1, 13196, 13212, 13197, -1, 13196, 13211, 13212, -1, 13194, 13197, 13213, -1, 13214, 11356, 11358, -1, 13215, 13216, 13217, -1, 13215, 13218, 13216, -1, 13215, 11358, 13218, -1, 13215, 13217, 13202, -1, 13215, 13214, 11358, -1, 13215, 13202, 13214, -1, 13203, 8556, 8555, -1, 13219, 13220, 8556, -1, 13219, 13217, 13220, -1, 13219, 13202, 13217, -1, 13219, 8556, 13203, -1, 13219, 13203, 13202, -1, 13221, 13210, 13204, -1, 13221, 13212, 13210, -1, 13221, 13204, 11371, -1, 13222, 13212, 13221, -1, 13222, 13221, 11371, -1, 13223, 13222, 11371, -1, 13224, 13197, 13212, -1, 13224, 13212, 13222, -1, 13224, 13222, 13223, -1, 13225, 11371, 11356, -1, 13225, 13213, 13197, -1, 13225, 13223, 11371, -1, 13225, 13197, 13224, -1, 13225, 13224, 13223, -1, 13226, 13225, 11356, -1, 13226, 13194, 13213, -1, 13226, 13213, 13225, -1, 13193, 13226, 11356, -1, 13193, 13194, 13226, -1, 13192, 11356, 13214, -1, 13192, 13202, 13194, -1, 13192, 13214, 13202, -1, 13227, 13228, 13229, -1, 13227, 13229, 13230, -1, 13227, 13230, 13231, -1, 13232, 13233, 13234, -1, 13232, 13234, 13235, -1, 13232, 13235, 13236, -1, 13237, 13236, 13230, -1, 13237, 13232, 13236, -1, 13238, 13233, 13232, -1, 13238, 13232, 13237, -1, 13239, 13233, 13238, -1, 13239, 13238, 13237, -1, 13239, 13237, 13230, -1, 13240, 13239, 13230, -1, 13240, 13230, 13229, -1, 13240, 13241, 13233, -1, 13240, 13229, 13241, -1, 13240, 13233, 13239, -1, 13242, 13243, 11572, -1, 13242, 13244, 13243, -1, 13242, 11572, 11563, -1, 13245, 13246, 13244, -1, 13245, 13247, 13246, -1, 13248, 13244, 13242, -1, 13248, 13245, 13244, -1, 13249, 13250, 13247, -1, 13249, 13234, 13250, -1, 13249, 13245, 13248, -1, 13249, 13247, 13245, -1, 13251, 13249, 13248, -1, 13235, 13234, 13249, -1, 13235, 13249, 13251, -1, 13235, 13251, 13236, -1, 13230, 13236, 13252, -1, 13228, 11559, 11558, -1, 13253, 13254, 13255, -1, 13253, 13256, 13254, -1, 13253, 11558, 13256, -1, 13253, 13255, 13229, -1, 13253, 13228, 11558, -1, 13253, 13229, 13228, -1, 13241, 13257, 13233, -1, 13258, 13259, 13257, -1, 13258, 13255, 13259, -1, 13258, 13229, 13255, -1, 13258, 13257, 13241, -1, 13258, 13241, 13229, -1, 13260, 13248, 13242, -1, 13260, 13251, 13248, -1, 13260, 13242, 11563, -1, 13261, 13251, 13260, -1, 13261, 13260, 11563, -1, 13262, 13261, 11563, -1, 13263, 13236, 13251, -1, 13263, 13251, 13261, -1, 13263, 13261, 13262, -1, 13264, 11563, 11559, -1, 13264, 13252, 13236, -1, 13264, 13262, 11563, -1, 13264, 13263, 13262, -1, 13264, 13236, 13263, -1, 13265, 13264, 11559, -1, 13265, 13230, 13252, -1, 13265, 13252, 13264, -1, 13231, 13265, 11559, -1, 13231, 13230, 13265, -1, 13227, 11559, 13228, -1, 13227, 13231, 11559, -1, 13266, 13267, 13268, -1, 13266, 13268, 13269, -1, 13266, 13269, 13270, -1, 13271, 13272, 13273, -1, 13271, 13273, 13274, -1, 13271, 13274, 13275, -1, 13276, 13275, 13269, -1, 13276, 13271, 13275, -1, 13277, 13272, 13271, -1, 13277, 13271, 13276, -1, 13278, 13272, 13277, -1, 13278, 13277, 13276, -1, 13278, 13276, 13269, -1, 13279, 13278, 13269, -1, 13279, 13269, 13268, -1, 13279, 13280, 13272, -1, 13279, 13268, 13280, -1, 13279, 13272, 13278, -1, 13281, 13282, 11543, -1, 13281, 13283, 13282, -1, 13281, 11543, 11536, -1, 13284, 13285, 13283, -1, 13284, 13286, 13285, -1, 13287, 13283, 13281, -1, 13287, 13284, 13283, -1, 13288, 13289, 13286, -1, 13288, 13273, 13289, -1, 13288, 13284, 13287, -1, 13288, 13286, 13284, -1, 13290, 13288, 13287, -1, 13274, 13288, 13290, -1, 13274, 13273, 13288, -1, 13274, 13290, 13275, -1, 13269, 13275, 13291, -1, 13267, 11529, 11528, -1, 13292, 13293, 13294, -1, 13292, 13295, 13293, -1, 13292, 11528, 13295, -1, 13292, 13294, 13268, -1, 13292, 13267, 11528, -1, 13292, 13268, 13267, -1, 13280, 13296, 13272, -1, 13297, 13298, 13296, -1, 13297, 13294, 13298, -1, 13297, 13268, 13294, -1, 13297, 13296, 13280, -1, 13297, 13280, 13268, -1, 13299, 13287, 13281, -1, 13299, 13290, 13287, -1, 13299, 13281, 11536, -1, 13300, 13290, 13299, -1, 13300, 13299, 11536, -1, 13301, 13300, 11536, -1, 13302, 13275, 13290, -1, 13302, 13290, 13300, -1, 13302, 13300, 13301, -1, 13303, 11536, 11529, -1, 13303, 13291, 13275, -1, 13303, 13301, 11536, -1, 13303, 13302, 13301, -1, 13303, 13275, 13302, -1, 13304, 13303, 11529, -1, 13304, 13269, 13291, -1, 13304, 13291, 13303, -1, 13270, 13304, 11529, -1, 13270, 13269, 13304, -1, 13266, 11529, 13267, -1, 13266, 13270, 11529, -1, 13305, 13306, 13307, -1, 13305, 13308, 11608, -1, 13305, 13307, 13308, -1, 13309, 13310, 13311, -1, 13309, 13311, 13312, -1, 13309, 13312, 13313, -1, 13314, 13313, 13307, -1, 13314, 13309, 13313, -1, 13315, 13310, 13309, -1, 13315, 13309, 13314, -1, 13316, 13310, 13315, -1, 13316, 13315, 13314, -1, 13316, 13314, 13307, -1, 13317, 13316, 13307, -1, 13317, 13307, 13306, -1, 13317, 13318, 13310, -1, 13317, 13306, 13318, -1, 13317, 13310, 13316, -1, 13319, 13320, 11624, -1, 13319, 13321, 13320, -1, 13319, 11624, 11617, -1, 13322, 13323, 13321, -1, 13322, 13324, 13323, -1, 13325, 13321, 13319, -1, 13325, 13322, 13321, -1, 13326, 13327, 13324, -1, 13326, 13311, 13327, -1, 13326, 13322, 13325, -1, 13326, 13324, 13322, -1, 13328, 13326, 13325, -1, 13312, 13326, 13328, -1, 13312, 13311, 13326, -1, 13312, 13328, 13313, -1, 13307, 13313, 13329, -1, 13330, 11608, 11609, -1, 13331, 13332, 13333, -1, 13331, 13334, 13332, -1, 13331, 11609, 13334, -1, 13331, 13333, 13306, -1, 13331, 13330, 11609, -1, 13331, 13306, 13330, -1, 13318, 13335, 13310, -1, 13336, 13337, 13335, -1, 13336, 13333, 13337, -1, 13336, 13306, 13333, -1, 13336, 13335, 13318, -1, 13336, 13318, 13306, -1, 13338, 13325, 13319, -1, 13338, 13328, 13325, -1, 13338, 13319, 11617, -1, 13339, 13328, 13338, -1, 13339, 13338, 11617, -1, 13340, 13339, 11617, -1, 13341, 13313, 13328, -1, 13341, 13328, 13339, -1, 13341, 13339, 13340, -1, 13342, 11617, 11608, -1, 13342, 13329, 13313, -1, 13342, 13340, 11617, -1, 13342, 13341, 13340, -1, 13342, 13313, 13341, -1, 13343, 13307, 13329, -1, 13343, 13329, 13342, -1, 13343, 13342, 11608, -1, 13308, 13343, 11608, -1, 13308, 13307, 13343, -1, 13305, 11608, 13330, -1, 13305, 13330, 13306, -1, 13344, 13345, 13346, -1, 13344, 13347, 13348, -1, 13344, 13348, 11584, -1, 13349, 13350, 13351, -1, 13349, 13351, 13352, -1, 13349, 13352, 13353, -1, 13354, 13353, 13347, -1, 13354, 13349, 13353, -1, 13355, 13350, 13349, -1, 13355, 13349, 13354, -1, 13356, 13350, 13355, -1, 13356, 13355, 13354, -1, 13356, 13354, 13347, -1, 13357, 13356, 13347, -1, 13357, 13347, 13346, -1, 13357, 13358, 13350, -1, 13357, 13346, 13358, -1, 13357, 13350, 13356, -1, 13359, 13360, 11598, -1, 13359, 13361, 13360, -1, 13359, 11598, 11588, -1, 13362, 13363, 13361, -1, 13362, 13364, 13363, -1, 13365, 13362, 13361, -1, 13365, 13361, 13359, -1, 13366, 13351, 13367, -1, 13366, 13367, 13364, -1, 13366, 13362, 13365, -1, 13366, 13364, 13362, -1, 13368, 13366, 13365, -1, 13352, 13351, 13366, -1, 13352, 13368, 13353, -1, 13352, 13366, 13368, -1, 13347, 13353, 13369, -1, 13345, 11584, 11583, -1, 13370, 13371, 13372, -1, 13370, 13373, 13371, -1, 13370, 11583, 13373, -1, 13370, 13372, 13346, -1, 13370, 13345, 11583, -1, 13370, 13346, 13345, -1, 13358, 13374, 13350, -1, 13375, 13376, 13374, -1, 13375, 13372, 13376, -1, 13375, 13346, 13372, -1, 13375, 13374, 13358, -1, 13375, 13358, 13346, -1, 13377, 13365, 13359, -1, 13377, 13368, 13365, -1, 13377, 13359, 11588, -1, 13378, 13368, 13377, -1, 13378, 13377, 11588, -1, 13379, 13378, 11588, -1, 13380, 13353, 13368, -1, 13380, 13368, 13378, -1, 13380, 13378, 13379, -1, 13381, 11588, 11584, -1, 13381, 13369, 13353, -1, 13381, 13379, 11588, -1, 13381, 13353, 13380, -1, 13381, 13380, 13379, -1, 13382, 13347, 13369, -1, 13382, 13369, 13381, -1, 13382, 13381, 11584, -1, 13348, 13347, 13382, -1, 13348, 13382, 11584, -1, 13344, 11584, 13345, -1, 13344, 13346, 13347, -1, 13383, 13384, 13385, -1, 13383, 13385, 13386, -1, 13387, 13388, 13389, -1, 13387, 13389, 13390, -1, 13387, 13390, 13391, -1, 13392, 13391, 13385, -1, 13392, 13387, 13391, -1, 13393, 13388, 13387, -1, 13393, 13387, 13392, -1, 13394, 13388, 13393, -1, 13394, 13393, 13392, -1, 13394, 13392, 13385, -1, 13395, 13394, 13385, -1, 13395, 13385, 13384, -1, 13395, 13396, 13388, -1, 13395, 13384, 13396, -1, 13395, 13388, 13394, -1, 13397, 13398, 11513, -1, 13397, 13399, 13398, -1, 13397, 11513, 11508, -1, 13400, 13401, 13399, -1, 13400, 13402, 13401, -1, 13403, 13399, 13397, -1, 13403, 13400, 13399, -1, 13404, 13405, 13402, -1, 13404, 13389, 13405, -1, 13404, 13400, 13403, -1, 13404, 13402, 13400, -1, 13406, 13404, 13403, -1, 13390, 13404, 13406, -1, 13390, 13389, 13404, -1, 13390, 13406, 13391, -1, 13385, 13391, 13407, -1, 13408, 11501, 11500, -1, 13409, 13410, 13411, -1, 13409, 13412, 13410, -1, 13409, 11500, 13412, -1, 13409, 13411, 13384, -1, 13409, 13408, 11500, -1, 13409, 13384, 13408, -1, 13396, 13413, 13388, -1, 13414, 13415, 13413, -1, 13414, 13411, 13415, -1, 13414, 13384, 13411, -1, 13414, 13413, 13396, -1, 13414, 13396, 13384, -1, 13416, 13403, 13397, -1, 13416, 13406, 13403, -1, 13416, 13397, 11508, -1, 13417, 13406, 13416, -1, 13417, 13416, 11508, -1, 13418, 13417, 11508, -1, 13419, 13391, 13406, -1, 13419, 13406, 13417, -1, 13419, 13417, 13418, -1, 13420, 11508, 11501, -1, 13420, 13407, 13391, -1, 13420, 13418, 11508, -1, 13420, 13419, 13418, -1, 13420, 13391, 13419, -1, 13421, 13420, 11501, -1, 13421, 13385, 13407, -1, 13421, 13407, 13420, -1, 13386, 13421, 11501, -1, 13386, 13385, 13421, -1, 13383, 11501, 13408, -1, 13383, 13386, 11501, -1, 13383, 13408, 13384, -1, 13422, 13423, 13424, -1, 13422, 13425, 11470, -1, 13422, 13424, 13425, -1, 13426, 13427, 13428, -1, 13426, 13428, 13429, -1, 13426, 13429, 13430, -1, 13431, 13430, 13424, -1, 13431, 13426, 13430, -1, 13432, 13427, 13426, -1, 13432, 13426, 13431, -1, 13433, 13427, 13432, -1, 13433, 13432, 13431, -1, 13433, 13431, 13424, -1, 13434, 13433, 13424, -1, 13434, 13424, 13423, -1, 13434, 13435, 13427, -1, 13434, 13423, 13435, -1, 13434, 13427, 13433, -1, 13436, 13437, 11484, -1, 13436, 13438, 13437, -1, 13436, 11484, 11478, -1, 13439, 13440, 13438, -1, 13439, 13441, 13440, -1, 13442, 13438, 13436, -1, 13442, 13439, 13438, -1, 13443, 13444, 13441, -1, 13443, 13428, 13444, -1, 13443, 13439, 13442, -1, 13443, 13441, 13439, -1, 13445, 13443, 13442, -1, 13429, 13428, 13443, -1, 13429, 13443, 13445, -1, 13429, 13445, 13430, -1, 13424, 13430, 13446, -1, 13447, 11470, 11469, -1, 13448, 13449, 13450, -1, 13448, 13451, 13449, -1, 13448, 11469, 13451, -1, 13448, 13450, 13423, -1, 13448, 13447, 11469, -1, 13448, 13423, 13447, -1, 13435, 13452, 13427, -1, 13453, 13454, 13452, -1, 13453, 13450, 13454, -1, 13453, 13423, 13450, -1, 13453, 13452, 13435, -1, 13453, 13435, 13423, -1, 13455, 13442, 13436, -1, 13455, 13445, 13442, -1, 13455, 13436, 11478, -1, 13456, 13445, 13455, -1, 13456, 13455, 11478, -1, 13457, 13456, 11478, -1, 13458, 13430, 13445, -1, 13458, 13445, 13456, -1, 13458, 13456, 13457, -1, 13459, 11478, 11470, -1, 13459, 13446, 13430, -1, 13459, 13457, 11478, -1, 13459, 13458, 13457, -1, 13459, 13430, 13458, -1, 13460, 13424, 13446, -1, 13460, 13446, 13459, -1, 13460, 13459, 11470, -1, 13425, 13460, 11470, -1, 13425, 13424, 13460, -1, 13422, 11470, 13447, -1, 13422, 13447, 13423, -1, 13461, 13462, 13463, -1, 13461, 13463, 13464, -1, 13461, 13464, 13465, -1, 13466, 13467, 13468, -1, 13466, 13468, 13469, -1, 13466, 13469, 13470, -1, 13471, 13470, 13464, -1, 13471, 13466, 13470, -1, 13472, 13467, 13466, -1, 13472, 13466, 13471, -1, 13473, 13467, 13472, -1, 13473, 13472, 13471, -1, 13473, 13471, 13464, -1, 13474, 13473, 13464, -1, 13474, 13464, 13463, -1, 13474, 13475, 13467, -1, 13474, 13463, 13475, -1, 13474, 13467, 13473, -1, 13476, 13477, 11482, -1, 13476, 13478, 13477, -1, 13476, 11482, 11481, -1, 13479, 13480, 13478, -1, 13479, 13481, 13480, -1, 13482, 13478, 13476, -1, 13482, 13479, 13478, -1, 13483, 13484, 13481, -1, 13483, 13468, 13484, -1, 13483, 13479, 13482, -1, 13483, 13481, 13479, -1, 13485, 13483, 13482, -1, 13469, 13468, 13483, -1, 13469, 13483, 13485, -1, 13469, 13485, 13470, -1, 13464, 13470, 13486, -1, 13462, 11487, 11493, -1, 13487, 13488, 13489, -1, 13487, 13490, 13488, -1, 13487, 11493, 13490, -1, 13487, 13489, 13463, -1, 13487, 13462, 11493, -1, 13487, 13463, 13462, -1, 13475, 13491, 13467, -1, 13492, 13493, 13491, -1, 13492, 13489, 13493, -1, 13492, 13463, 13489, -1, 13492, 13491, 13475, -1, 13492, 13475, 13463, -1, 13494, 13482, 13476, -1, 13494, 13485, 13482, -1, 13494, 13476, 11481, -1, 13495, 13485, 13494, -1, 13495, 13494, 11481, -1, 13496, 13495, 11481, -1, 13497, 13470, 13485, -1, 13497, 13485, 13495, -1, 13497, 13495, 13496, -1, 13498, 11481, 11487, -1, 13498, 13486, 13470, -1, 13498, 13496, 11481, -1, 13498, 13497, 13496, -1, 13498, 13470, 13497, -1, 13499, 13498, 11487, -1, 13499, 13464, 13486, -1, 13499, 13486, 13498, -1, 13465, 13499, 11487, -1, 13465, 13464, 13499, -1, 13461, 11487, 13462, -1, 13461, 13465, 11487, -1, 13500, 13501, 13502, -1, 13500, 13502, 13503, -1, 13500, 13503, 13504, -1, 13505, 13506, 13507, -1, 13505, 13507, 13508, -1, 13505, 13508, 13509, -1, 13510, 13509, 13503, -1, 13510, 13505, 13509, -1, 13511, 13506, 13505, -1, 13511, 13505, 13510, -1, 13512, 13506, 13511, -1, 13512, 13511, 13510, -1, 13512, 13510, 13503, -1, 13513, 13512, 13503, -1, 13513, 13503, 13502, -1, 13513, 13514, 13506, -1, 13513, 13502, 13514, -1, 13513, 13506, 13512, -1, 13515, 13516, 11510, -1, 13515, 13517, 13516, -1, 13515, 11510, 11509, -1, 13518, 13519, 13517, -1, 13518, 13520, 13519, -1, 13521, 13517, 13515, -1, 13521, 13518, 13517, -1, 13522, 13523, 13520, -1, 13522, 13507, 13523, -1, 13522, 13518, 13521, -1, 13522, 13520, 13518, -1, 13524, 13522, 13521, -1, 13508, 13507, 13522, -1, 13508, 13522, 13524, -1, 13508, 13524, 13509, -1, 13503, 13509, 13525, -1, 13501, 11515, 11522, -1, 13526, 13527, 13528, -1, 13526, 13529, 13527, -1, 13526, 11522, 13529, -1, 13526, 13528, 13502, -1, 13526, 13501, 11522, -1, 13526, 13502, 13501, -1, 13514, 13530, 13506, -1, 13531, 13532, 13530, -1, 13531, 13528, 13532, -1, 13531, 13502, 13528, -1, 13531, 13530, 13514, -1, 13531, 13514, 13502, -1, 13533, 13521, 13515, -1, 13533, 13524, 13521, -1, 13533, 13515, 11509, -1, 13534, 13524, 13533, -1, 13534, 13533, 11509, -1, 13535, 13534, 11509, -1, 13536, 13509, 13524, -1, 13536, 13524, 13534, -1, 13536, 13534, 13535, -1, 13537, 11509, 11515, -1, 13537, 13525, 13509, -1, 13537, 13535, 11509, -1, 13537, 13536, 13535, -1, 13537, 13509, 13536, -1, 13538, 13537, 11515, -1, 13538, 13503, 13525, -1, 13538, 13525, 13537, -1, 13504, 13538, 11515, -1, 13504, 13503, 13538, -1, 13500, 11515, 13501, -1, 13500, 13504, 11515, -1, 13539, 13540, 11550, -1, 13539, 13541, 13540, -1, 13542, 13543, 13544, -1, 13542, 13544, 13545, -1, 13542, 13545, 13546, -1, 13547, 13546, 13541, -1, 13547, 13542, 13546, -1, 13548, 13543, 13542, -1, 13548, 13542, 13547, -1, 13549, 13543, 13548, -1, 13549, 13548, 13547, -1, 13549, 13547, 13541, -1, 13550, 13549, 13541, -1, 13550, 13541, 13551, -1, 13550, 13552, 13543, -1, 13550, 13551, 13552, -1, 13550, 13543, 13549, -1, 13553, 13554, 11540, -1, 13553, 13555, 13554, -1, 13553, 11540, 11539, -1, 13556, 13557, 13555, -1, 13556, 13558, 13557, -1, 13559, 13555, 13553, -1, 13559, 13556, 13555, -1, 13560, 13561, 13558, -1, 13560, 13544, 13561, -1, 13560, 13556, 13559, -1, 13560, 13558, 13556, -1, 13562, 13560, 13559, -1, 13545, 13544, 13560, -1, 13545, 13560, 13562, -1, 13545, 13562, 13546, -1, 13541, 13546, 13563, -1, 13564, 11550, 11555, -1, 13565, 13566, 13567, -1, 13565, 13568, 13566, -1, 13565, 11555, 13568, -1, 13565, 13567, 13551, -1, 13565, 13564, 11555, -1, 13565, 13551, 13564, -1, 13552, 13569, 13543, -1, 13570, 13571, 13569, -1, 13570, 13567, 13571, -1, 13570, 13551, 13567, -1, 13570, 13569, 13552, -1, 13570, 13552, 13551, -1, 13572, 13559, 13553, -1, 13572, 13562, 13559, -1, 13572, 13553, 11539, -1, 13573, 13562, 13572, -1, 13573, 13572, 11539, -1, 13574, 13573, 11539, -1, 13575, 13546, 13562, -1, 13575, 13562, 13573, -1, 13575, 13573, 13574, -1, 13576, 11539, 11550, -1, 13576, 13563, 13546, -1, 13576, 13574, 11539, -1, 13576, 13575, 13574, -1, 13576, 13546, 13575, -1, 13577, 13541, 13563, -1, 13577, 13563, 13576, -1, 13577, 13576, 11550, -1, 13540, 13577, 11550, -1, 13540, 13541, 13577, -1, 13539, 11550, 13564, -1, 13539, 13564, 13551, -1, 13539, 13551, 13541, -1, 13578, 13579, 13580, -1, 13578, 13580, 13581, -1, 13578, 13581, 13582, -1, 13583, 13584, 13585, -1, 13583, 13585, 13586, -1, 13583, 13586, 13587, -1, 13588, 13587, 13581, -1, 13588, 13583, 13587, -1, 13589, 13584, 13583, -1, 13589, 13583, 13588, -1, 13590, 13584, 13589, -1, 13590, 13589, 13588, -1, 13590, 13588, 13581, -1, 13591, 13590, 13581, -1, 13591, 13581, 13580, -1, 13591, 13592, 13584, -1, 13591, 13580, 13592, -1, 13591, 13584, 13590, -1, 13593, 13594, 11568, -1, 13593, 13595, 13594, -1, 13593, 11568, 11567, -1, 13596, 13597, 13595, -1, 13596, 13598, 13597, -1, 13599, 13595, 13593, -1, 13599, 13596, 13595, -1, 13600, 13601, 13598, -1, 13600, 13585, 13601, -1, 13600, 13596, 13599, -1, 13600, 13598, 13596, -1, 13602, 13600, 13599, -1, 13586, 13600, 13602, -1, 13586, 13585, 13600, -1, 13586, 13602, 13587, -1, 13581, 13587, 13603, -1, 13579, 11576, 11579, -1, 13604, 13605, 13606, -1, 13604, 13607, 13605, -1, 13604, 11579, 13607, -1, 13604, 13606, 13580, -1, 13604, 13579, 11579, -1, 13604, 13580, 13579, -1, 13592, 13608, 13584, -1, 13609, 13610, 13608, -1, 13609, 13606, 13610, -1, 13609, 13580, 13606, -1, 13609, 13608, 13592, -1, 13609, 13592, 13580, -1, 13611, 13599, 13593, -1, 13611, 13602, 13599, -1, 13611, 13593, 11567, -1, 13612, 13602, 13611, -1, 13612, 13611, 11567, -1, 13613, 13612, 11567, -1, 13614, 13587, 13602, -1, 13614, 13602, 13612, -1, 13614, 13612, 13613, -1, 13615, 11567, 11576, -1, 13615, 13603, 13587, -1, 13615, 13613, 11567, -1, 13615, 13614, 13613, -1, 13615, 13587, 13614, -1, 13616, 13615, 11576, -1, 13616, 13581, 13603, -1, 13616, 13603, 13615, -1, 13582, 13616, 11576, -1, 13582, 13581, 13616, -1, 13578, 11576, 13579, -1, 13578, 13582, 11576, -1, 13617, 13618, 13619, -1, 13617, 13620, 11643, -1, 13617, 13619, 13620, -1, 13621, 13622, 13623, -1, 13621, 13623, 13624, -1, 13621, 13624, 13625, -1, 13626, 13625, 13619, -1, 13626, 13621, 13625, -1, 13627, 13622, 13621, -1, 13627, 13621, 13626, -1, 13628, 13622, 13627, -1, 13628, 13627, 13626, -1, 13628, 13626, 13619, -1, 13629, 13628, 13619, -1, 13629, 13619, 13618, -1, 13629, 13630, 13622, -1, 13629, 13618, 13630, -1, 13629, 13622, 13628, -1, 13631, 13632, 11640, -1, 13631, 13633, 13632, -1, 13631, 11640, 11639, -1, 13634, 13635, 13633, -1, 13634, 13636, 13635, -1, 13637, 13633, 13631, -1, 13637, 13634, 13633, -1, 13638, 13639, 13636, -1, 13638, 13623, 13639, -1, 13638, 13634, 13637, -1, 13638, 13636, 13634, -1, 13640, 13638, 13637, -1, 13624, 13623, 13638, -1, 13624, 13638, 13640, -1, 13624, 13640, 13625, -1, 13619, 13625, 13641, -1, 13642, 11643, 11644, -1, 13643, 13644, 13645, -1, 13643, 13646, 13644, -1, 13643, 11644, 13646, -1, 13643, 13645, 13618, -1, 13643, 13642, 11644, -1, 13643, 13618, 13642, -1, 13630, 13647, 13622, -1, 13648, 13649, 13647, -1, 13648, 13645, 13649, -1, 13648, 13618, 13645, -1, 13648, 13647, 13630, -1, 13648, 13630, 13618, -1, 13650, 13637, 13631, -1, 13650, 13640, 13637, -1, 13650, 13631, 11639, -1, 13651, 13640, 13650, -1, 13651, 13650, 11639, -1, 13652, 13651, 11639, -1, 13653, 13625, 13640, -1, 13653, 13640, 13651, -1, 13653, 13651, 13652, -1, 13654, 11639, 11643, -1, 13654, 13641, 13625, -1, 13654, 13652, 11639, -1, 13654, 13653, 13652, -1, 13654, 13625, 13653, -1, 13655, 13619, 13641, -1, 13655, 13641, 13654, -1, 13655, 13654, 11643, -1, 13620, 13655, 11643, -1, 13620, 13619, 13655, -1, 13617, 11643, 13642, -1, 13617, 13642, 13618, -1, 13656, 13657, 11630, -1, 13656, 13658, 13657, -1, 13659, 13660, 13661, -1, 13659, 13661, 13662, -1, 13659, 13662, 13663, -1, 13664, 13663, 13658, -1, 13664, 13659, 13663, -1, 13665, 13660, 13659, -1, 13665, 13659, 13664, -1, 13666, 13660, 13665, -1, 13666, 13665, 13664, -1, 13666, 13664, 13658, -1, 13667, 13666, 13658, -1, 13667, 13658, 13668, -1, 13667, 13669, 13660, -1, 13667, 13668, 13669, -1, 13667, 13660, 13666, -1, 13670, 13671, 11641, -1, 13670, 13672, 13671, -1, 13670, 11641, 11637, -1, 13673, 13674, 13672, -1, 13673, 13675, 13674, -1, 13676, 13673, 13672, -1, 13676, 13672, 13670, -1, 13677, 13661, 13678, -1, 13677, 13678, 13675, -1, 13677, 13673, 13676, -1, 13677, 13675, 13673, -1, 13679, 13677, 13676, -1, 13662, 13661, 13677, -1, 13662, 13679, 13663, -1, 13662, 13677, 13679, -1, 13658, 13663, 13680, -1, 13681, 11630, 11631, -1, 13682, 13683, 13684, -1, 13682, 13685, 13683, -1, 13682, 11631, 13685, -1, 13682, 13684, 13668, -1, 13682, 13681, 11631, -1, 13682, 13668, 13681, -1, 13669, 13686, 13660, -1, 13687, 13688, 13686, -1, 13687, 13684, 13688, -1, 13687, 13668, 13684, -1, 13687, 13686, 13669, -1, 13687, 13669, 13668, -1, 13689, 13676, 13670, -1, 13689, 13679, 13676, -1, 13689, 13670, 11637, -1, 13690, 13679, 13689, -1, 13690, 13689, 11637, -1, 13691, 13690, 11637, -1, 13692, 13663, 13679, -1, 13692, 13679, 13690, -1, 13692, 13690, 13691, -1, 13693, 11637, 11630, -1, 13693, 13680, 13663, -1, 13693, 13691, 11637, -1, 13693, 13663, 13692, -1, 13693, 13692, 13691, -1, 13694, 13693, 11630, -1, 13694, 13658, 13680, -1, 13694, 13680, 13693, -1, 13657, 13694, 11630, -1, 13657, 13658, 13694, -1, 13656, 11630, 13681, -1, 13656, 13668, 13658, -1, 13656, 13681, 13668, -1, 13695, 13696, 13697, -1, 13695, 13697, 13698, -1, 13695, 13698, 13699, -1, 13700, 13701, 13702, -1, 13700, 13702, 13703, -1, 13700, 13703, 13704, -1, 13705, 13704, 13698, -1, 13705, 13700, 13704, -1, 13706, 13701, 13700, -1, 13706, 13700, 13705, -1, 13707, 13701, 13706, -1, 13707, 13706, 13705, -1, 13707, 13705, 13698, -1, 13708, 13707, 13698, -1, 13708, 13698, 13697, -1, 13708, 13709, 13701, -1, 13708, 13697, 13709, -1, 13708, 13701, 13707, -1, 13710, 13711, 11596, -1, 13710, 13712, 13711, -1, 13710, 11596, 11595, -1, 13713, 13714, 13712, -1, 13713, 13715, 13714, -1, 13716, 13712, 13710, -1, 13716, 13713, 13712, -1, 13717, 13718, 13715, -1, 13717, 13702, 13718, -1, 13717, 13713, 13716, -1, 13717, 13715, 13713, -1, 13719, 13717, 13716, -1, 13703, 13702, 13717, -1, 13703, 13717, 13719, -1, 13703, 13719, 13704, -1, 13698, 13704, 13720, -1, 13696, 11599, 11602, -1, 13721, 13722, 13723, -1, 13721, 13724, 13722, -1, 13721, 11602, 13724, -1, 13721, 13723, 13697, -1, 13721, 13696, 11602, -1, 13721, 13697, 13696, -1, 13709, 13725, 13701, -1, 13726, 13727, 13725, -1, 13726, 13723, 13727, -1, 13726, 13697, 13723, -1, 13726, 13725, 13709, -1, 13726, 13709, 13697, -1, 13728, 13716, 13710, -1, 13728, 13719, 13716, -1, 13728, 13710, 11595, -1, 13729, 13719, 13728, -1, 13729, 13728, 11595, -1, 13730, 13729, 11595, -1, 13731, 13704, 13719, -1, 13731, 13719, 13729, -1, 13731, 13729, 13730, -1, 13732, 11595, 11599, -1, 13732, 13720, 13704, -1, 13732, 13730, 11595, -1, 13732, 13731, 13730, -1, 13732, 13704, 13731, -1, 13733, 13732, 11599, -1, 13733, 13698, 13720, -1, 13733, 13720, 13732, -1, 13699, 13733, 11599, -1, 13699, 13698, 13733, -1, 13695, 11599, 13696, -1, 13695, 13699, 11599, -1, 13734, 13735, 13736, -1, 13734, 13736, 11626, -1, 13737, 13738, 13739, -1, 13737, 13739, 13740, -1, 13737, 13740, 13741, -1, 13742, 13741, 13735, -1, 13742, 13737, 13741, -1, 13743, 13738, 13737, -1, 13743, 13737, 13742, -1, 13744, 13738, 13743, -1, 13744, 13743, 13742, -1, 13744, 13742, 13735, -1, 13745, 13744, 13735, -1, 13745, 13735, 13746, -1, 13745, 13747, 13738, -1, 13745, 13746, 13747, -1, 13745, 13738, 13744, -1, 13748, 13749, 11623, -1, 13748, 13750, 13749, -1, 13748, 11623, 11622, -1, 13751, 13752, 13750, -1, 13751, 13753, 13752, -1, 13754, 13751, 13750, -1, 13754, 13750, 13748, -1, 13755, 13739, 13756, -1, 13755, 13756, 13753, -1, 13755, 13751, 13754, -1, 13755, 13753, 13751, -1, 13757, 13755, 13754, -1, 13740, 13739, 13755, -1, 13740, 13757, 13741, -1, 13740, 13755, 13757, -1, 13735, 13741, 13758, -1, 13759, 11626, 11628, -1, 13760, 13761, 13762, -1, 13760, 13763, 13761, -1, 13760, 11628, 13763, -1, 13760, 13762, 13746, -1, 13760, 13759, 11628, -1, 13760, 13746, 13759, -1, 13747, 13764, 13738, -1, 13765, 13766, 13764, -1, 13765, 13762, 13766, -1, 13765, 13746, 13762, -1, 13765, 13764, 13747, -1, 13765, 13747, 13746, -1, 13767, 13754, 13748, -1, 13767, 13757, 13754, -1, 13767, 13748, 11622, -1, 13768, 13757, 13767, -1, 13768, 13767, 11622, -1, 13769, 13768, 11622, -1, 13770, 13741, 13757, -1, 13770, 13757, 13768, -1, 13770, 13768, 13769, -1, 13771, 11622, 11626, -1, 13771, 13758, 13741, -1, 13771, 13769, 11622, -1, 13771, 13741, 13770, -1, 13771, 13770, 13769, -1, 13772, 13735, 13758, -1, 13772, 13758, 13771, -1, 13772, 13771, 11626, -1, 13736, 13735, 13772, -1, 13736, 13772, 11626, -1, 13734, 11626, 13759, -1, 13734, 13746, 13735, -1, 13734, 13759, 13746, -1, 13773, 13774, 13775, -1, 13773, 13775, 13776, -1, 13777, 10054, 10067, -1, 13777, 10067, 13778, -1, 13777, 13778, 13779, -1, 13780, 13779, 13775, -1, 13780, 13777, 13779, -1, 13781, 10054, 13777, -1, 13781, 13777, 13780, -1, 13782, 10054, 13781, -1, 13782, 13781, 13780, -1, 13782, 13780, 13775, -1, 13783, 13782, 13775, -1, 13783, 13775, 13774, -1, 13783, 13784, 10054, -1, 13783, 13774, 13784, -1, 13783, 10054, 13782, -1, 13785, 13786, 11296, -1, 13785, 13787, 13786, -1, 13785, 11296, 11295, -1, 13788, 13789, 13787, -1, 13788, 13790, 13789, -1, 13791, 13787, 13785, -1, 13791, 13788, 13787, -1, 13792, 10074, 13790, -1, 13792, 10067, 10074, -1, 13792, 13788, 13791, -1, 13792, 13790, 13788, -1, 13793, 13792, 13791, -1, 13778, 10067, 13792, -1, 13778, 13792, 13793, -1, 13778, 13793, 13779, -1, 13775, 13779, 13794, -1, 13795, 11306, 11311, -1, 13796, 13797, 13798, -1, 13796, 13799, 13797, -1, 13796, 11311, 13799, -1, 13796, 13798, 13774, -1, 13796, 13795, 11311, -1, 13796, 13774, 13795, -1, 13784, 10055, 10054, -1, 13800, 13801, 10055, -1, 13800, 13798, 13801, -1, 13800, 13774, 13798, -1, 13800, 10055, 13784, -1, 13800, 13784, 13774, -1, 13802, 13791, 13785, -1, 13802, 13793, 13791, -1, 13802, 13785, 11295, -1, 13803, 13793, 13802, -1, 13803, 13802, 11295, -1, 13804, 13803, 11295, -1, 13805, 13779, 13793, -1, 13805, 13793, 13803, -1, 13805, 13803, 13804, -1, 13806, 11295, 11306, -1, 13806, 13794, 13779, -1, 13806, 13804, 11295, -1, 13806, 13805, 13804, -1, 13806, 13779, 13805, -1, 13807, 13806, 11306, -1, 13807, 13775, 13794, -1, 13807, 13794, 13806, -1, 13776, 13807, 11306, -1, 13776, 13775, 13807, -1, 13773, 11306, 13795, -1, 13773, 13776, 11306, -1, 13773, 13795, 13774, -1, 13808, 13809, 13810, -1, 13808, 13810, 13811, -1, 13808, 13811, 13812, -1, 13813, 10215, 10224, -1, 13813, 10224, 13814, -1, 13813, 13814, 13815, -1, 13816, 13815, 13811, -1, 13816, 13813, 13815, -1, 13817, 10215, 13813, -1, 13817, 13813, 13816, -1, 13818, 10215, 13817, -1, 13818, 13817, 13816, -1, 13818, 13816, 13811, -1, 13819, 13818, 13811, -1, 13819, 13811, 13810, -1, 13819, 13820, 10215, -1, 13819, 13810, 13820, -1, 13819, 10215, 13818, -1, 13821, 13822, 11329, -1, 13821, 13823, 13822, -1, 13821, 11329, 11328, -1, 13824, 13825, 13823, -1, 13824, 13826, 13825, -1, 13827, 13823, 13821, -1, 13827, 13824, 13823, -1, 13828, 10226, 13826, -1, 13828, 10224, 10226, -1, 13828, 13824, 13827, -1, 13828, 13826, 13824, -1, 13829, 13828, 13827, -1, 13814, 10224, 13828, -1, 13814, 13828, 13829, -1, 13814, 13829, 13815, -1, 13811, 13815, 13830, -1, 13809, 11334, 11340, -1, 13831, 13832, 13833, -1, 13831, 13834, 13832, -1, 13831, 11340, 13834, -1, 13831, 13833, 13810, -1, 13831, 13809, 11340, -1, 13831, 13810, 13809, -1, 13820, 10216, 10215, -1, 13835, 13836, 10216, -1, 13835, 13833, 13836, -1, 13835, 13810, 13833, -1, 13835, 10216, 13820, -1, 13835, 13820, 13810, -1, 13837, 13827, 13821, -1, 13837, 13829, 13827, -1, 13837, 13821, 11328, -1, 13838, 13829, 13837, -1, 13838, 13837, 11328, -1, 13839, 13838, 11328, -1, 13840, 13815, 13829, -1, 13840, 13829, 13838, -1, 13840, 13838, 13839, -1, 13841, 11328, 11334, -1, 13841, 13830, 13815, -1, 13841, 13839, 11328, -1, 13841, 13840, 13839, -1, 13841, 13815, 13840, -1, 13842, 13841, 11334, -1, 13842, 13811, 13830, -1, 13842, 13830, 13841, -1, 13812, 13842, 11334, -1, 13812, 13811, 13842, -1, 13808, 11334, 13809, -1, 13808, 13812, 11334, -1, 13843, 13844, 13845, -1, 13843, 13845, 13846, -1, 13843, 13846, 13847, -1, 13848, 10370, 10383, -1, 13848, 10383, 13849, -1, 13848, 13849, 13850, -1, 13851, 13850, 13846, -1, 13851, 13848, 13850, -1, 13852, 10370, 13848, -1, 13852, 13848, 13851, -1, 13853, 10370, 13852, -1, 13853, 13852, 13851, -1, 13853, 13851, 13846, -1, 13854, 13853, 13846, -1, 13854, 13846, 13845, -1, 13854, 13855, 10370, -1, 13854, 13845, 13855, -1, 13854, 10370, 13853, -1, 13856, 13857, 11655, -1, 13856, 13858, 13857, -1, 13856, 11655, 11654, -1, 13859, 13860, 13858, -1, 13859, 13861, 13860, -1, 13862, 13858, 13856, -1, 13862, 13859, 13858, -1, 13863, 10390, 13861, -1, 13863, 10383, 10390, -1, 13863, 13859, 13862, -1, 13863, 13861, 13859, -1, 13864, 13863, 13862, -1, 13849, 13863, 13864, -1, 13849, 10383, 13863, -1, 13849, 13864, 13850, -1, 13846, 13850, 13865, -1, 13844, 11658, 11660, -1, 13866, 13867, 13868, -1, 13866, 13869, 13867, -1, 13866, 11660, 13869, -1, 13866, 13868, 13845, -1, 13866, 13844, 11660, -1, 13866, 13845, 13844, -1, 13855, 10371, 10370, -1, 13870, 13871, 10371, -1, 13870, 13868, 13871, -1, 13870, 13845, 13868, -1, 13870, 10371, 13855, -1, 13870, 13855, 13845, -1, 13872, 13862, 13856, -1, 13872, 13864, 13862, -1, 13872, 13856, 11654, -1, 13873, 13864, 13872, -1, 13873, 13872, 11654, -1, 13874, 13873, 11654, -1, 13875, 13850, 13864, -1, 13875, 13864, 13873, -1, 13875, 13873, 13874, -1, 13876, 11654, 11658, -1, 13876, 13865, 13850, -1, 13876, 13874, 11654, -1, 13876, 13875, 13874, -1, 13876, 13850, 13875, -1, 13877, 13876, 11658, -1, 13877, 13846, 13865, -1, 13877, 13865, 13876, -1, 13847, 13877, 11658, -1, 13847, 13846, 13877, -1, 13843, 11658, 13844, -1, 13843, 13847, 11658, -1, 13878, 13879, 13880, -1, 13878, 13880, 11280, -1, 13881, 10391, 10400, -1, 13881, 10400, 13882, -1, 13881, 13882, 13883, -1, 13884, 13883, 13879, -1, 13884, 13881, 13883, -1, 13885, 10391, 13881, -1, 13885, 13881, 13884, -1, 13886, 10391, 13885, -1, 13886, 13885, 13884, -1, 13886, 13884, 13879, -1, 13887, 13886, 13879, -1, 13887, 13879, 13888, -1, 13887, 13889, 10391, -1, 13887, 13888, 13889, -1, 13887, 10391, 13886, -1, 13890, 13891, 11666, -1, 13890, 13892, 13891, -1, 13890, 11666, 11281, -1, 13893, 13894, 13892, -1, 13893, 13895, 13894, -1, 13896, 13893, 13892, -1, 13896, 13892, 13890, -1, 13897, 10400, 10402, -1, 13897, 10402, 13895, -1, 13897, 13893, 13896, -1, 13897, 13895, 13893, -1, 13898, 13897, 13896, -1, 13882, 10400, 13897, -1, 13882, 13897, 13898, -1, 13882, 13898, 13883, -1, 13879, 13883, 13899, -1, 13900, 11280, 11285, -1, 13901, 13902, 13903, -1, 13901, 13904, 13902, -1, 13901, 11285, 13904, -1, 13901, 13903, 13888, -1, 13901, 13900, 11285, -1, 13901, 13888, 13900, -1, 13889, 10392, 10391, -1, 13905, 13906, 10392, -1, 13905, 13903, 13906, -1, 13905, 13888, 13903, -1, 13905, 10392, 13889, -1, 13905, 13889, 13888, -1, 13907, 13896, 13890, -1, 13907, 13898, 13896, -1, 13907, 13890, 11281, -1, 13908, 13898, 13907, -1, 13908, 13907, 11281, -1, 13909, 13908, 11281, -1, 13910, 13883, 13898, -1, 13910, 13898, 13908, -1, 13910, 13908, 13909, -1, 13911, 11281, 11280, -1, 13911, 13899, 13883, -1, 13911, 13909, 11281, -1, 13911, 13883, 13910, -1, 13911, 13910, 13909, -1, 13912, 13879, 13899, -1, 13912, 13899, 13911, -1, 13912, 13911, 11280, -1, 13880, 13879, 13912, -1, 13880, 13912, 11280, -1, 13878, 11280, 13900, -1, 13878, 13888, 13879, -1, 13878, 13900, 13888, -1, 13913, 13914, 13915, -1, 13913, 13915, 11453, -1, 13916, 10499, 10508, -1, 13916, 10508, 13917, -1, 13916, 13917, 13918, -1, 13919, 13918, 13914, -1, 13919, 13916, 13918, -1, 13920, 10499, 13916, -1, 13920, 13916, 13919, -1, 13921, 10499, 13920, -1, 13921, 13920, 13919, -1, 13921, 13919, 13914, -1, 13922, 13921, 13914, -1, 13922, 13914, 13923, -1, 13922, 13924, 10499, -1, 13922, 13923, 13924, -1, 13922, 10499, 13921, -1, 13925, 13926, 11446, -1, 13925, 13927, 13926, -1, 13925, 11446, 11445, -1, 13928, 13929, 13927, -1, 13928, 13930, 13929, -1, 13931, 13928, 13927, -1, 13931, 13927, 13925, -1, 13932, 10508, 10510, -1, 13932, 10510, 13930, -1, 13932, 13928, 13931, -1, 13932, 13930, 13928, -1, 13933, 13932, 13931, -1, 13917, 10508, 13932, -1, 13917, 13933, 13918, -1, 13917, 13932, 13933, -1, 13914, 13918, 13934, -1, 13935, 11453, 11463, -1, 13936, 13937, 13938, -1, 13936, 13939, 13937, -1, 13936, 11463, 13939, -1, 13936, 13938, 13923, -1, 13936, 13935, 11463, -1, 13936, 13923, 13935, -1, 13924, 10500, 10499, -1, 13940, 13941, 10500, -1, 13940, 13938, 13941, -1, 13940, 10500, 13924, -1, 13940, 13923, 13938, -1, 13940, 13924, 13923, -1, 13942, 13931, 13925, -1, 13942, 13933, 13931, -1, 13942, 13925, 11445, -1, 13943, 13933, 13942, -1, 13943, 13942, 11445, -1, 13944, 13943, 11445, -1, 13945, 13918, 13933, -1, 13945, 13933, 13943, -1, 13945, 13943, 13944, -1, 13946, 11445, 11453, -1, 13946, 13934, 13918, -1, 13946, 13944, 11445, -1, 13946, 13918, 13945, -1, 13946, 13945, 13944, -1, 13947, 13914, 13934, -1, 13947, 13934, 13946, -1, 13947, 13946, 11453, -1, 13915, 13914, 13947, -1, 13915, 13947, 11453, -1, 13913, 11453, 13935, -1, 13913, 13923, 13914, -1, 13913, 13935, 13923, -1, 13948, 13949, 13950, -1, 13948, 13951, 13952, -1, 13948, 13952, 11422, -1, 13953, 10702, 10715, -1, 13953, 10715, 13954, -1, 13953, 13954, 13955, -1, 13956, 13955, 13951, -1, 13956, 13953, 13955, -1, 13957, 10702, 13953, -1, 13957, 13953, 13956, -1, 13958, 10702, 13957, -1, 13958, 13957, 13956, -1, 13958, 13956, 13951, -1, 13959, 13958, 13951, -1, 13959, 13951, 13950, -1, 13959, 13960, 10702, -1, 13959, 13950, 13960, -1, 13959, 10702, 13958, -1, 13961, 13962, 11415, -1, 13961, 13963, 13962, -1, 13961, 11415, 11414, -1, 13964, 13965, 13963, -1, 13964, 13966, 13965, -1, 13967, 13964, 13963, -1, 13967, 13963, 13961, -1, 13968, 10715, 10722, -1, 13968, 10722, 13966, -1, 13968, 13964, 13967, -1, 13968, 13966, 13964, -1, 13969, 13968, 13967, -1, 13954, 10715, 13968, -1, 13954, 13968, 13969, -1, 13954, 13969, 13955, -1, 13951, 13955, 13970, -1, 13949, 11422, 11428, -1, 13971, 13972, 13973, -1, 13971, 13974, 13972, -1, 13971, 11428, 13974, -1, 13971, 13973, 13950, -1, 13971, 13949, 11428, -1, 13971, 13950, 13949, -1, 13960, 10703, 10702, -1, 13975, 13976, 10703, -1, 13975, 13973, 13976, -1, 13975, 10703, 13960, -1, 13975, 13950, 13973, -1, 13975, 13960, 13950, -1, 13977, 13967, 13961, -1, 13977, 13969, 13967, -1, 13977, 13961, 11414, -1, 13978, 13969, 13977, -1, 13978, 13977, 11414, -1, 13979, 13978, 11414, -1, 13980, 13955, 13969, -1, 13980, 13969, 13978, -1, 13980, 13978, 13979, -1, 13981, 11414, 11422, -1, 13981, 13970, 13955, -1, 13981, 13979, 11414, -1, 13981, 13955, 13980, -1, 13981, 13980, 13979, -1, 13982, 13951, 13970, -1, 13982, 13970, 13981, -1, 13982, 13981, 11422, -1, 13952, 13951, 13982, -1, 13952, 13982, 11422, -1, 13948, 11422, 13949, -1, 13948, 13950, 13951, -1, 13983, 13984, 13985, -1, 13983, 13986, 11363, -1, 13983, 13985, 13986, -1, 13987, 10784, 10797, -1, 13987, 10797, 13988, -1, 13987, 13988, 13989, -1, 13990, 13989, 13985, -1, 13990, 13987, 13989, -1, 13991, 10784, 13987, -1, 13991, 13987, 13990, -1, 13992, 10784, 13991, -1, 13992, 13991, 13990, -1, 13992, 13990, 13985, -1, 13993, 13992, 13985, -1, 13993, 13985, 13984, -1, 13993, 13994, 10784, -1, 13993, 13984, 13994, -1, 13993, 10784, 13992, -1, 13995, 13996, 11360, -1, 13995, 13997, 13996, -1, 13995, 11360, 11359, -1, 13998, 13999, 13997, -1, 13998, 14000, 13999, -1, 14001, 13997, 13995, -1, 14001, 13998, 13997, -1, 14002, 10804, 14000, -1, 14002, 10797, 10804, -1, 14002, 13998, 14001, -1, 14002, 14000, 13998, -1, 14003, 14002, 14001, -1, 13988, 10797, 14002, -1, 13988, 14002, 14003, -1, 13988, 14003, 13989, -1, 13985, 13989, 14004, -1, 14005, 11363, 11373, -1, 14006, 14007, 14008, -1, 14006, 14009, 14007, -1, 14006, 11373, 14009, -1, 14006, 14008, 13984, -1, 14006, 14005, 11373, -1, 14006, 13984, 14005, -1, 13994, 10785, 10784, -1, 14010, 14011, 10785, -1, 14010, 14008, 14011, -1, 14010, 13984, 14008, -1, 14010, 10785, 13994, -1, 14010, 13994, 13984, -1, 14012, 14001, 13995, -1, 14012, 14003, 14001, -1, 14012, 13995, 11359, -1, 14013, 14003, 14012, -1, 14013, 14012, 11359, -1, 14014, 14013, 11359, -1, 14015, 13989, 14003, -1, 14015, 14003, 14013, -1, 14015, 14013, 14014, -1, 14016, 11359, 11363, -1, 14016, 14004, 13989, -1, 14016, 14014, 11359, -1, 14016, 14015, 14014, -1, 14016, 13989, 14015, -1, 14017, 13985, 14004, -1, 14017, 14004, 14016, -1, 14017, 14016, 11363, -1, 13986, 14017, 11363, -1, 13986, 13985, 14017, -1, 13983, 11363, 14005, -1, 13983, 14005, 13984, -1, 14018, 14019, 14020, -1, 14018, 14020, 11395, -1, 14021, 10935, 10944, -1, 14021, 10944, 14022, -1, 14021, 14022, 14023, -1, 14024, 14023, 14019, -1, 14024, 14021, 14023, -1, 14025, 10935, 14021, -1, 14025, 14021, 14024, -1, 14026, 10935, 14025, -1, 14026, 14025, 14024, -1, 14026, 14024, 14019, -1, 14027, 14026, 14019, -1, 14027, 14019, 14028, -1, 14027, 14029, 10935, -1, 14027, 14028, 14029, -1, 14027, 10935, 14026, -1, 14030, 14031, 11392, -1, 14030, 14032, 14031, -1, 14030, 11392, 11391, -1, 14033, 14034, 14032, -1, 14033, 14035, 14034, -1, 14036, 14033, 14032, -1, 14036, 14032, 14030, -1, 14037, 10944, 10946, -1, 14037, 10946, 14035, -1, 14037, 14033, 14036, -1, 14037, 14035, 14033, -1, 14038, 14037, 14036, -1, 14022, 10944, 14037, -1, 14022, 14037, 14038, -1, 14022, 14038, 14023, -1, 14019, 14023, 14039, -1, 14040, 11395, 11400, -1, 14041, 14042, 14043, -1, 14041, 14044, 14042, -1, 14041, 11400, 14044, -1, 14041, 14043, 14028, -1, 14041, 14040, 11400, -1, 14041, 14028, 14040, -1, 14029, 10936, 10935, -1, 14045, 14046, 10936, -1, 14045, 14043, 14046, -1, 14045, 14028, 14043, -1, 14045, 10936, 14029, -1, 14045, 14029, 14028, -1, 14047, 14036, 14030, -1, 14047, 14038, 14036, -1, 14047, 14030, 11391, -1, 14048, 14038, 14047, -1, 14048, 14047, 11391, -1, 14049, 14048, 11391, -1, 14050, 14023, 14038, -1, 14050, 14038, 14048, -1, 14050, 14048, 14049, -1, 14051, 11391, 11395, -1, 14051, 14039, 14023, -1, 14051, 14049, 11391, -1, 14051, 14023, 14050, -1, 14051, 14050, 14049, -1, 14052, 14019, 14039, -1, 14052, 14039, 14051, -1, 14052, 14051, 11395, -1, 14020, 14019, 14052, -1, 14020, 14052, 11395, -1, 14018, 11395, 14040, -1, 14018, 14028, 14019, -1, 14018, 14040, 14028, -1, 14053, 14054, 14055, -1, 14053, 14056, 14057, -1, 14053, 14057, 11409, -1, 14058, 14059, 14060, -1, 14058, 14060, 14061, -1, 14058, 14061, 14062, -1, 14063, 14062, 14056, -1, 14063, 14058, 14062, -1, 14064, 14059, 14058, -1, 14064, 14058, 14063, -1, 14065, 14059, 14064, -1, 14065, 14064, 14063, -1, 14065, 14063, 14056, -1, 14066, 14065, 14056, -1, 14066, 14056, 14055, -1, 14066, 14067, 14059, -1, 14066, 14055, 14067, -1, 14066, 14059, 14065, -1, 14068, 14069, 11419, -1, 14068, 14070, 14069, -1, 14068, 11419, 11413, -1, 14071, 14072, 14070, -1, 14071, 14073, 14072, -1, 14074, 14071, 14070, -1, 14074, 14070, 14068, -1, 14075, 14060, 14076, -1, 14075, 14076, 14073, -1, 14075, 14071, 14074, -1, 14075, 14073, 14071, -1, 14077, 14075, 14074, -1, 14061, 14060, 14075, -1, 14061, 14077, 14062, -1, 14061, 14075, 14077, -1, 14056, 14062, 14078, -1, 14054, 11409, 11408, -1, 14079, 14080, 14081, -1, 14079, 14082, 14080, -1, 14079, 11408, 14082, -1, 14079, 14081, 14055, -1, 14079, 14054, 11408, -1, 14079, 14055, 14054, -1, 14067, 14083, 14059, -1, 14084, 14085, 14083, -1, 14084, 14081, 14085, -1, 14084, 14055, 14081, -1, 14084, 14083, 14067, -1, 14084, 14067, 14055, -1, 14086, 14074, 14068, -1, 14086, 14077, 14074, -1, 14086, 14068, 11413, -1, 14087, 14077, 14086, -1, 14087, 14086, 11413, -1, 14088, 14087, 11413, -1, 14089, 14062, 14077, -1, 14089, 14077, 14087, -1, 14089, 14087, 14088, -1, 14090, 11413, 11409, -1, 14090, 14078, 14062, -1, 14090, 14088, 11413, -1, 14090, 14062, 14089, -1, 14090, 14089, 14088, -1, 14091, 14056, 14078, -1, 14091, 14078, 14090, -1, 14091, 14090, 11409, -1, 14057, 14056, 14091, -1, 14057, 14091, 11409, -1, 14053, 11409, 14054, -1, 14053, 14055, 14056, -1, 14092, 14093, 14094, -1, 14095, 14096, 14097, -1, 14098, 14099, 14100, -1, 14098, 14100, 14092, -1, 14098, 14094, 14101, -1, 14098, 14092, 14094, -1, 14102, 14103, 14097, -1, 14102, 14096, 14099, -1, 14102, 14101, 14103, -1, 14102, 14098, 14101, -1, 14102, 14099, 14098, -1, 14102, 14097, 14096, -1, 14104, 14105, 14106, -1, 14107, 14108, 14109, -1, 14110, 14111, 14112, -1, 14110, 14112, 14105, -1, 14110, 14104, 14113, -1, 14110, 14105, 14104, -1, 14114, 14115, 14111, -1, 14114, 14111, 14110, -1, 14116, 14113, 14117, -1, 14116, 14117, 14118, -1, 14116, 14110, 14113, -1, 14119, 14120, 14107, -1, 14119, 14109, 14115, -1, 14119, 14115, 14114, -1, 14119, 14107, 14109, -1, 14121, 14122, 14123, -1, 14121, 14118, 14124, -1, 14121, 14124, 14122, -1, 14121, 14116, 14118, -1, 14121, 14110, 14116, -1, 14121, 14114, 14110, -1, 14125, 14123, 14126, -1, 14125, 14126, 14127, -1, 14125, 14127, 14120, -1, 14125, 14114, 14121, -1, 14125, 14121, 14123, -1, 14125, 14120, 14119, -1, 14125, 14119, 14114, -1, 14128, 14129, 14130, -1, 14131, 14132, 14133, -1, 14134, 14135, 14136, -1, 14134, 14136, 14128, -1, 14134, 14130, 14137, -1, 14134, 14128, 14130, -1, 14138, 14139, 14133, -1, 14138, 14132, 14135, -1, 14138, 14137, 14139, -1, 14138, 14134, 14137, -1, 14138, 14135, 14134, -1, 14138, 14133, 14132, -1, 14140, 14141, 14142, -1, 14143, 14144, 14145, -1, 14146, 14147, 14148, -1, 14146, 14148, 14141, -1, 14146, 14140, 14149, -1, 14146, 14141, 14140, -1, 14150, 14151, 14147, -1, 14150, 14147, 14146, -1, 14152, 14149, 14153, -1, 14152, 14153, 14154, -1, 14152, 14146, 14149, -1, 14155, 14156, 14143, -1, 14155, 14145, 14151, -1, 14155, 14151, 14150, -1, 14155, 14143, 14145, -1, 14157, 14158, 14159, -1, 14157, 14154, 14160, -1, 14157, 14160, 14158, -1, 14157, 14152, 14154, -1, 14157, 14146, 14152, -1, 14157, 14150, 14146, -1, 14161, 14159, 14162, -1, 14161, 14162, 14163, -1, 14161, 14163, 14156, -1, 14161, 14150, 14157, -1, 14161, 14157, 14159, -1, 14161, 14156, 14155, -1, 14161, 14155, 14150, -1, 14164, 14165, 14166, -1, 14167, 14168, 14169, -1, 14170, 14171, 14172, -1, 14170, 14172, 14164, -1, 14170, 14166, 14173, -1, 14170, 14164, 14166, -1, 14174, 14175, 14169, -1, 14174, 14168, 14171, -1, 14174, 14173, 14175, -1, 14174, 14170, 14173, -1, 14174, 14171, 14170, -1, 14174, 14169, 14168, -1, 14176, 14177, 14178, -1, 14179, 14180, 14181, -1, 14182, 14183, 14184, -1, 14182, 14184, 14177, -1, 14182, 14176, 14185, -1, 14182, 14177, 14176, -1, 14186, 14187, 14183, -1, 14186, 14183, 14182, -1, 14188, 14185, 14189, -1, 14188, 14189, 14190, -1, 14188, 14182, 14185, -1, 14191, 14192, 14179, -1, 14191, 14181, 14187, -1, 14191, 14187, 14186, -1, 14191, 14179, 14181, -1, 14193, 14194, 14195, -1, 14193, 14190, 14196, -1, 14193, 14196, 14194, -1, 14193, 14188, 14190, -1, 14193, 14182, 14188, -1, 14193, 14186, 14182, -1, 14197, 14195, 14198, -1, 14197, 14198, 14199, -1, 14197, 14199, 14192, -1, 14197, 14186, 14193, -1, 14197, 14193, 14195, -1, 14197, 14192, 14191, -1, 14197, 14191, 14186, -1, 14200, 14201, 14202, -1, 14203, 14204, 14205, -1, 14206, 14207, 14208, -1, 14206, 14208, 14200, -1, 14206, 14202, 14209, -1, 14206, 14200, 14202, -1, 14210, 14211, 14205, -1, 14210, 14204, 14207, -1, 14210, 14209, 14211, -1, 14210, 14206, 14209, -1, 14210, 14207, 14206, -1, 14210, 14205, 14204, -1, 14212, 14213, 14214, -1, 14215, 14216, 14217, -1, 14218, 14219, 14220, -1, 14218, 14220, 14213, -1, 14218, 14212, 14221, -1, 14218, 14213, 14212, -1, 14222, 14223, 14219, -1, 14222, 14219, 14218, -1, 14224, 14221, 14225, -1, 14224, 14225, 14226, -1, 14224, 14218, 14221, -1, 14227, 14228, 14215, -1, 14227, 14217, 14223, -1, 14227, 14223, 14222, -1, 14227, 14215, 14217, -1, 14229, 14230, 14231, -1, 14229, 14226, 14232, -1, 14229, 14232, 14230, -1, 14229, 14224, 14226, -1, 14229, 14218, 14224, -1, 14229, 14222, 14218, -1, 14233, 14231, 14234, -1, 14233, 14234, 14235, -1, 14233, 14235, 14228, -1, 14233, 14222, 14229, -1, 14233, 14229, 14231, -1, 14233, 14228, 14227, -1, 14233, 14227, 14222, -1, 14236, 14237, 14238, -1, 14239, 14240, 14241, -1, 14242, 14243, 14244, -1, 14242, 14244, 14237, -1, 14242, 14236, 14245, -1, 14242, 14237, 14236, -1, 14246, 14247, 14243, -1, 14246, 14243, 14242, -1, 14248, 14245, 14249, -1, 14248, 14249, 14250, -1, 14248, 14242, 14245, -1, 14251, 14252, 14239, -1, 14251, 14241, 14247, -1, 14251, 14247, 14246, -1, 14251, 14239, 14241, -1, 14253, 14254, 14255, -1, 14253, 14250, 14256, -1, 14253, 14256, 14254, -1, 14253, 14248, 14250, -1, 14253, 14242, 14248, -1, 14253, 14246, 14242, -1, 14257, 14255, 14258, -1, 14257, 14258, 14259, -1, 14257, 14259, 14252, -1, 14257, 14246, 14253, -1, 14257, 14253, 14255, -1, 14257, 14252, 14251, -1, 14257, 14251, 14246, -1, 14260, 14261, 14262, -1, 14263, 14264, 14265, -1, 14266, 14267, 14268, -1, 14266, 14268, 14260, -1, 14266, 14262, 14269, -1, 14266, 14260, 14262, -1, 14270, 14271, 14265, -1, 14270, 14264, 14267, -1, 14270, 14269, 14271, -1, 14270, 14266, 14269, -1, 14270, 14267, 14266, -1, 14270, 14265, 14264, -1, 14272, 14273, 14274, -1, 14275, 14276, 14277, -1, 14278, 14279, 14280, -1, 14278, 14280, 14273, -1, 14278, 14272, 14281, -1, 14278, 14273, 14272, -1, 14282, 14283, 14279, -1, 14282, 14279, 14278, -1, 14284, 14281, 14285, -1, 14284, 14285, 14286, -1, 14284, 14278, 14281, -1, 14287, 14288, 14275, -1, 14287, 14277, 14283, -1, 14287, 14283, 14282, -1, 14287, 14275, 14277, -1, 14289, 14290, 14291, -1, 14289, 14286, 14292, -1, 14289, 14292, 14290, -1, 14289, 14284, 14286, -1, 14289, 14278, 14284, -1, 14289, 14282, 14278, -1, 14293, 14291, 14294, -1, 14293, 14294, 14295, -1, 14293, 14295, 14288, -1, 14293, 14282, 14289, -1, 14293, 14289, 14291, -1, 14293, 14288, 14287, -1, 14293, 14287, 14282, -1, 14296, 14297, 14298, -1, 14299, 14300, 14301, -1, 14302, 14303, 14304, -1, 14302, 14304, 14296, -1, 14302, 14298, 14305, -1, 14302, 14296, 14298, -1, 14306, 14307, 14301, -1, 14306, 14300, 14303, -1, 14306, 14305, 14307, -1, 14306, 14302, 14305, -1, 14306, 14303, 14302, -1, 14306, 14301, 14300, -1, 14308, 14309, 14310, -1, 14311, 14312, 14313, -1, 14314, 14315, 14316, -1, 14314, 14316, 14309, -1, 14314, 14308, 14317, -1, 14314, 14309, 14308, -1, 14318, 14319, 14315, -1, 14318, 14315, 14314, -1, 14320, 14317, 14321, -1, 14320, 14321, 14322, -1, 14320, 14314, 14317, -1, 14323, 14324, 14311, -1, 14323, 14313, 14319, -1, 14323, 14319, 14318, -1, 14323, 14311, 14313, -1, 14325, 14326, 14327, -1, 14325, 14322, 14328, -1, 14325, 14328, 14326, -1, 14325, 14320, 14322, -1, 14325, 14314, 14320, -1, 14325, 14318, 14314, -1, 14329, 14327, 14330, -1, 14329, 14330, 14331, -1, 14329, 14331, 14324, -1, 14329, 14318, 14325, -1, 14329, 14325, 14327, -1, 14329, 14324, 14323, -1, 14329, 14323, 14318, -1, 14332, 14333, 14334, -1, 14335, 14336, 14337, -1, 14338, 14339, 14340, -1, 14338, 14340, 14332, -1, 14338, 14334, 14341, -1, 14338, 14332, 14334, -1, 14342, 14343, 14337, -1, 14342, 14336, 14339, -1, 14342, 14341, 14343, -1, 14342, 14338, 14341, -1, 14342, 14339, 14338, -1, 14342, 14337, 14336, -1, 14344, 14345, 14346, -1, 14347, 14348, 14349, -1, 14350, 14351, 14352, -1, 14350, 14352, 14344, -1, 14350, 14346, 14353, -1, 14350, 14344, 14346, -1, 14354, 14355, 14349, -1, 14354, 14348, 14351, -1, 14354, 14353, 14355, -1, 14354, 14350, 14353, -1, 14354, 14351, 14350, -1, 14354, 14349, 14348, -1, 14356, 14357, 14358, -1, 14359, 14360, 14361, -1, 14362, 14363, 14364, -1, 14362, 14364, 14357, -1, 14362, 14356, 14365, -1, 14362, 14357, 14356, -1, 14366, 14367, 14363, -1, 14366, 14363, 14362, -1, 14368, 14365, 14369, -1, 14368, 14369, 14370, -1, 14368, 14362, 14365, -1, 14371, 14372, 14359, -1, 14371, 14361, 14367, -1, 14371, 14367, 14366, -1, 14371, 14359, 14361, -1, 14373, 14374, 14375, -1, 14373, 14370, 14376, -1, 14373, 14376, 14374, -1, 14373, 14368, 14370, -1, 14373, 14362, 14368, -1, 14373, 14366, 14362, -1, 14377, 14375, 14378, -1, 14377, 14378, 14379, -1, 14377, 14379, 14372, -1, 14377, 14366, 14373, -1, 14377, 14373, 14375, -1, 14377, 14372, 14371, -1, 14377, 14371, 14366, -1, 12624, 12649, 14380, -1, 14381, 14382, 14383, -1, 14384, 14380, 14385, -1, 14384, 14385, 14386, -1, 14384, 12625, 12624, -1, 14384, 12624, 14380, -1, 14387, 14386, 14382, -1, 14387, 14381, 12641, -1, 14387, 12641, 12625, -1, 14387, 14384, 14386, -1, 14387, 14382, 14381, -1, 14387, 12625, 14384, -1, 14388, 14389, 14390, -1, 12664, 12688, 14391, -1, 14392, 14393, 14394, -1, 14392, 14394, 14389, -1, 14392, 14388, 14395, -1, 14392, 14389, 14388, -1, 14396, 14397, 14393, -1, 14396, 14393, 14392, -1, 14398, 14395, 14399, -1, 14398, 14399, 14400, -1, 14398, 14392, 14395, -1, 14401, 12665, 12664, -1, 14401, 14391, 14397, -1, 14401, 14397, 14396, -1, 14401, 12664, 14391, -1, 14402, 14400, 14403, -1, 14402, 14403, 14404, -1, 14402, 14404, 14405, -1, 14402, 14398, 14400, -1, 14402, 14392, 14398, -1, 14402, 14396, 14392, -1, 14406, 14405, 14407, -1, 14406, 14407, 12681, -1, 14406, 12681, 12665, -1, 14406, 12665, 14401, -1, 14406, 14402, 14405, -1, 14406, 14401, 14396, -1, 14406, 14396, 14402, -1, 12702, 12727, 14408, -1, 14409, 14410, 14411, -1, 14412, 14408, 14413, -1, 14412, 14413, 14414, -1, 14412, 12703, 12702, -1, 14412, 12702, 14408, -1, 14415, 14414, 14410, -1, 14415, 14409, 12719, -1, 14415, 12719, 12703, -1, 14415, 14412, 14414, -1, 14415, 14410, 14409, -1, 14415, 12703, 14412, -1, 14416, 14417, 14418, -1, 12742, 12766, 14419, -1, 14420, 14421, 14422, -1, 14420, 14422, 14417, -1, 14420, 14416, 14423, -1, 14420, 14417, 14416, -1, 14424, 14425, 14421, -1, 14424, 14421, 14420, -1, 14426, 14423, 14427, -1, 14426, 14427, 14428, -1, 14426, 14420, 14423, -1, 14429, 12743, 12742, -1, 14429, 14419, 14425, -1, 14429, 14425, 14424, -1, 14429, 12742, 14419, -1, 14430, 14428, 14431, -1, 14430, 14431, 14432, -1, 14430, 14432, 14433, -1, 14430, 14426, 14428, -1, 14430, 14420, 14426, -1, 14430, 14424, 14420, -1, 14434, 14433, 14435, -1, 14434, 14435, 12759, -1, 14434, 12759, 12743, -1, 14434, 12743, 14429, -1, 14434, 14430, 14433, -1, 14434, 14429, 14424, -1, 14434, 14424, 14430, -1, 14436, 14437, 14438, -1, 12781, 12805, 14439, -1, 14440, 14441, 14442, -1, 14440, 14442, 14437, -1, 14440, 14436, 14443, -1, 14440, 14437, 14436, -1, 14444, 14445, 14441, -1, 14444, 14441, 14440, -1, 14446, 14443, 14447, -1, 14446, 14447, 14448, -1, 14446, 14440, 14443, -1, 14449, 12782, 12781, -1, 14449, 14439, 14445, -1, 14449, 14445, 14444, -1, 14449, 12781, 14439, -1, 14450, 14448, 14451, -1, 14450, 14451, 14452, -1, 14450, 14452, 14453, -1, 14450, 14446, 14448, -1, 14450, 14440, 14446, -1, 14450, 14444, 14440, -1, 14454, 14453, 14455, -1, 14454, 14455, 12798, -1, 14454, 12798, 12782, -1, 14454, 12782, 14449, -1, 14454, 14450, 14453, -1, 14454, 14449, 14444, -1, 14454, 14444, 14450, -1, 12820, 12844, 14456, -1, 14457, 14458, 14459, -1, 14460, 14456, 14461, -1, 14460, 14461, 14462, -1, 14460, 12821, 12820, -1, 14460, 12820, 14456, -1, 14463, 14462, 14458, -1, 14463, 14457, 12837, -1, 14463, 12837, 12821, -1, 14463, 14460, 14462, -1, 14463, 12821, 14460, -1, 14463, 14458, 14457, -1, 12859, 12883, 14464, -1, 14465, 14466, 14467, -1, 14468, 14464, 14469, -1, 14468, 14469, 14470, -1, 14468, 12860, 12859, -1, 14468, 12859, 14464, -1, 14471, 14470, 14466, -1, 14471, 14465, 12876, -1, 14471, 12876, 12860, -1, 14471, 14468, 14470, -1, 14471, 14466, 14465, -1, 14471, 12860, 14468, -1, 14472, 14473, 14474, -1, 12896, 12922, 14475, -1, 14476, 14477, 14478, -1, 14476, 14478, 14473, -1, 14476, 14472, 14479, -1, 14476, 14473, 14472, -1, 14480, 14481, 14477, -1, 14480, 14477, 14476, -1, 14482, 14479, 14483, -1, 14482, 14483, 14484, -1, 14482, 14476, 14479, -1, 14485, 12897, 12896, -1, 14485, 14475, 14481, -1, 14485, 14481, 14480, -1, 14485, 12896, 14475, -1, 14486, 14484, 14487, -1, 14486, 14487, 14488, -1, 14486, 14488, 14489, -1, 14486, 14482, 14484, -1, 14486, 14476, 14482, -1, 14486, 14480, 14476, -1, 14490, 14489, 14491, -1, 14490, 14491, 12914, -1, 14490, 12914, 12897, -1, 14490, 12897, 14485, -1, 14490, 14486, 14489, -1, 14490, 14485, 14480, -1, 14490, 14480, 14486, -1, 14492, 14493, 14494, -1, 14495, 14496, 14497, -1, 14498, 14499, 14500, -1, 14498, 14500, 14492, -1, 14498, 14494, 14501, -1, 14498, 14492, 14494, -1, 14502, 14503, 14497, -1, 14502, 14496, 14499, -1, 14502, 14501, 14503, -1, 14502, 14498, 14501, -1, 14502, 14499, 14498, -1, 14502, 14497, 14496, -1, 14504, 14505, 14506, -1, 12972, 12996, 14507, -1, 14508, 14509, 14510, -1, 14508, 14510, 14505, -1, 14508, 14504, 14511, -1, 14508, 14505, 14504, -1, 14512, 14513, 14509, -1, 14512, 14509, 14508, -1, 14514, 14511, 14515, -1, 14514, 14515, 14516, -1, 14514, 14508, 14511, -1, 14517, 12973, 12972, -1, 14517, 14507, 14513, -1, 14517, 14513, 14512, -1, 14517, 12972, 14507, -1, 14518, 14516, 14519, -1, 14518, 14519, 14520, -1, 14518, 14520, 14521, -1, 14518, 14514, 14516, -1, 14518, 14508, 14514, -1, 14518, 14512, 14508, -1, 14522, 14521, 14523, -1, 14522, 14523, 12989, -1, 14522, 12989, 12973, -1, 14522, 12973, 14517, -1, 14522, 14518, 14521, -1, 14522, 14517, 14512, -1, 14522, 14512, 14518, -1, 14524, 14525, 14526, -1, 13009, 13035, 14527, -1, 14528, 14529, 14530, -1, 14528, 14530, 14525, -1, 14528, 14524, 14531, -1, 14528, 14525, 14524, -1, 14532, 14533, 14529, -1, 14532, 14529, 14528, -1, 14534, 14531, 14535, -1, 14534, 14535, 14536, -1, 14534, 14528, 14531, -1, 14537, 13010, 13009, -1, 14537, 14527, 14533, -1, 14537, 14533, 14532, -1, 14537, 13009, 14527, -1, 14538, 14536, 14539, -1, 14538, 14539, 14540, -1, 14538, 14540, 14541, -1, 14538, 14534, 14536, -1, 14538, 14528, 14534, -1, 14538, 14532, 14528, -1, 14542, 14541, 14543, -1, 14542, 14543, 13027, -1, 14542, 13027, 13010, -1, 14542, 13010, 14537, -1, 14542, 14538, 14541, -1, 14542, 14537, 14532, -1, 14542, 14532, 14538, -1, 13048, 13074, 14544, -1, 14545, 14546, 14547, -1, 14548, 14544, 14549, -1, 14548, 14549, 14550, -1, 14548, 13049, 13048, -1, 14548, 13048, 14544, -1, 14551, 14550, 14546, -1, 14551, 14545, 13066, -1, 14551, 13066, 13049, -1, 14551, 14548, 14550, -1, 14551, 14546, 14545, -1, 14551, 13049, 14548, -1, 14552, 14553, 14554, -1, 13088, 13113, 14555, -1, 14556, 14557, 14558, -1, 14556, 14558, 14553, -1, 14556, 14552, 14559, -1, 14556, 14553, 14552, -1, 14560, 14561, 14557, -1, 14560, 14557, 14556, -1, 14562, 14559, 14563, -1, 14562, 14563, 14564, -1, 14562, 14556, 14559, -1, 14565, 13089, 13088, -1, 14565, 14555, 14561, -1, 14565, 14561, 14560, -1, 14565, 13088, 14555, -1, 14566, 14564, 14567, -1, 14566, 14567, 14568, -1, 14566, 14568, 14569, -1, 14566, 14562, 14564, -1, 14566, 14556, 14562, -1, 14566, 14560, 14556, -1, 14570, 14569, 14571, -1, 14570, 14571, 13105, -1, 14570, 13105, 13089, -1, 14570, 13089, 14565, -1, 14570, 14566, 14569, -1, 14570, 14565, 14560, -1, 14570, 14560, 14566, -1, 14572, 14573, 14574, -1, 14575, 14576, 14577, -1, 14578, 14579, 14580, -1, 14578, 14580, 14572, -1, 14578, 14574, 14581, -1, 14578, 14572, 14574, -1, 14582, 14583, 14577, -1, 14582, 14576, 14579, -1, 14582, 14581, 14583, -1, 14582, 14578, 14581, -1, 14582, 14579, 14578, -1, 14582, 14577, 14576, -1, 14584, 14585, 14586, -1, 14587, 14588, 14589, -1, 14590, 14591, 14592, -1, 14590, 14592, 14585, -1, 14590, 14584, 14593, -1, 14590, 14585, 14584, -1, 14594, 14595, 14591, -1, 14594, 14591, 14590, -1, 14596, 14593, 14597, -1, 14596, 14597, 14598, -1, 14596, 14590, 14593, -1, 14599, 14600, 14587, -1, 14599, 14589, 14595, -1, 14599, 14595, 14594, -1, 14599, 14587, 14589, -1, 14601, 14602, 14603, -1, 14601, 14598, 14604, -1, 14601, 14604, 14602, -1, 14601, 14596, 14598, -1, 14601, 14590, 14596, -1, 14601, 14594, 14590, -1, 14605, 14603, 14606, -1, 14605, 14606, 14607, -1, 14605, 14607, 14600, -1, 14605, 14594, 14601, -1, 14605, 14601, 14603, -1, 14605, 14600, 14599, -1, 14605, 14599, 14594, -1, 14608, 14609, 14610, -1, 14611, 14612, 14613, -1, 14614, 14615, 14616, -1, 14614, 14616, 14608, -1, 14614, 14610, 14617, -1, 14614, 14608, 14610, -1, 14618, 14619, 14613, -1, 14618, 14612, 14615, -1, 14618, 14617, 14619, -1, 14618, 14614, 14617, -1, 14618, 14615, 14614, -1, 14618, 14613, 14612, -1, 14620, 14621, 14622, -1, 13233, 13257, 14623, -1, 14624, 14625, 14626, -1, 14624, 14626, 14621, -1, 14624, 14620, 14627, -1, 14624, 14621, 14620, -1, 14628, 14629, 14625, -1, 14628, 14625, 14624, -1, 14630, 14627, 14631, -1, 14630, 14631, 14632, -1, 14630, 14624, 14627, -1, 14633, 13234, 13233, -1, 14633, 14623, 14629, -1, 14633, 14629, 14628, -1, 14633, 13233, 14623, -1, 14634, 14632, 14635, -1, 14634, 14635, 14636, -1, 14634, 14636, 14637, -1, 14634, 14630, 14632, -1, 14634, 14624, 14630, -1, 14634, 14628, 14624, -1, 14638, 14637, 14639, -1, 14638, 14639, 13250, -1, 14638, 13250, 13234, -1, 14638, 13234, 14633, -1, 14638, 14634, 14637, -1, 14638, 14633, 14628, -1, 14638, 14628, 14634, -1, 13272, 13296, 14640, -1, 14641, 14642, 14643, -1, 14644, 14640, 14645, -1, 14644, 14645, 14646, -1, 14644, 13273, 13272, -1, 14644, 13272, 14640, -1, 14647, 14646, 14642, -1, 14647, 14641, 13289, -1, 14647, 13289, 13273, -1, 14647, 14644, 14646, -1, 14647, 13273, 14644, -1, 14647, 14642, 14641, -1, 14648, 14649, 14650, -1, 13310, 13335, 14651, -1, 14652, 14653, 14654, -1, 14652, 14654, 14649, -1, 14652, 14648, 14655, -1, 14652, 14649, 14648, -1, 14656, 14657, 14653, -1, 14656, 14653, 14652, -1, 14658, 14655, 14659, -1, 14658, 14659, 14660, -1, 14658, 14652, 14655, -1, 14661, 13311, 13310, -1, 14661, 14651, 14657, -1, 14661, 14657, 14656, -1, 14661, 13310, 14651, -1, 14662, 14660, 14663, -1, 14662, 14663, 14664, -1, 14662, 14664, 14665, -1, 14662, 14658, 14660, -1, 14662, 14652, 14658, -1, 14662, 14656, 14652, -1, 14666, 14665, 14667, -1, 14666, 14667, 13327, -1, 14666, 13327, 13311, -1, 14666, 13311, 14661, -1, 14666, 14662, 14665, -1, 14666, 14661, 14656, -1, 14666, 14656, 14662, -1, 13350, 13374, 14668, -1, 14669, 14670, 14671, -1, 14672, 14668, 14673, -1, 14672, 14673, 14674, -1, 14672, 13351, 13350, -1, 14672, 13350, 14668, -1, 14675, 14674, 14670, -1, 14675, 14669, 13367, -1, 14675, 13367, 13351, -1, 14675, 14672, 14674, -1, 14675, 14670, 14669, -1, 14675, 13351, 14672, -1, 14676, 14677, 14678, -1, 13388, 13413, 14679, -1, 14680, 14681, 14682, -1, 14680, 14682, 14677, -1, 14680, 14676, 14683, -1, 14680, 14677, 14676, -1, 14684, 14685, 14681, -1, 14684, 14681, 14680, -1, 14686, 14683, 14687, -1, 14686, 14687, 14688, -1, 14686, 14680, 14683, -1, 14689, 13389, 13388, -1, 14689, 14679, 14685, -1, 14689, 14685, 14684, -1, 14689, 13388, 14679, -1, 14690, 14688, 14691, -1, 14690, 14691, 14692, -1, 14690, 14692, 14693, -1, 14690, 14686, 14688, -1, 14690, 14680, 14686, -1, 14690, 14684, 14680, -1, 14694, 14693, 14695, -1, 14694, 14695, 13405, -1, 14694, 13405, 13389, -1, 14694, 13389, 14689, -1, 14694, 14690, 14693, -1, 14694, 14689, 14684, -1, 14694, 14684, 14690, -1, 13427, 13452, 14696, -1, 14697, 14698, 14699, -1, 14700, 14696, 14701, -1, 14700, 14701, 14702, -1, 14700, 13428, 13427, -1, 14700, 13427, 14696, -1, 14703, 14702, 14698, -1, 14703, 14697, 13444, -1, 14703, 13444, 13428, -1, 14703, 14700, 14702, -1, 14703, 13428, 14700, -1, 14703, 14698, 14697, -1, 14704, 14705, 14706, -1, 13467, 13491, 14707, -1, 14708, 14709, 14710, -1, 14708, 14710, 14705, -1, 14708, 14704, 14711, -1, 14708, 14705, 14704, -1, 14712, 14713, 14709, -1, 14712, 14709, 14708, -1, 14714, 14711, 14715, -1, 14714, 14715, 14716, -1, 14714, 14708, 14711, -1, 14717, 13468, 13467, -1, 14717, 14707, 14713, -1, 14717, 14713, 14712, -1, 14717, 13467, 14707, -1, 14718, 14716, 14719, -1, 14718, 14719, 14720, -1, 14718, 14720, 14721, -1, 14718, 14714, 14716, -1, 14718, 14708, 14714, -1, 14718, 14712, 14708, -1, 14722, 14721, 14723, -1, 14722, 14723, 13484, -1, 14722, 13484, 13468, -1, 14722, 13468, 14717, -1, 14722, 14718, 14721, -1, 14722, 14717, 14712, -1, 14722, 14712, 14718, -1, 13506, 13530, 14724, -1, 14725, 14726, 14727, -1, 14728, 14724, 14729, -1, 14728, 14729, 14730, -1, 14728, 13507, 13506, -1, 14728, 13506, 14724, -1, 14731, 14730, 14726, -1, 14731, 14725, 13523, -1, 14731, 13523, 13507, -1, 14731, 14728, 14730, -1, 14731, 13507, 14728, -1, 14731, 14726, 14725, -1, 14732, 14733, 14734, -1, 13543, 13569, 14735, -1, 14736, 14737, 14738, -1, 14736, 14738, 14733, -1, 14736, 14732, 14739, -1, 14736, 14733, 14732, -1, 14740, 14741, 14737, -1, 14740, 14737, 14736, -1, 14742, 14739, 14743, -1, 14742, 14743, 14744, -1, 14742, 14736, 14739, -1, 14745, 13544, 13543, -1, 14745, 14735, 14741, -1, 14745, 14741, 14740, -1, 14745, 13543, 14735, -1, 14746, 14744, 14747, -1, 14746, 14747, 14748, -1, 14746, 14748, 14749, -1, 14746, 14742, 14744, -1, 14746, 14736, 14742, -1, 14746, 14740, 14736, -1, 14750, 14749, 14751, -1, 14750, 14751, 13561, -1, 14750, 13561, 13544, -1, 14750, 13544, 14745, -1, 14750, 14746, 14749, -1, 14750, 14745, 14740, -1, 14750, 14740, 14746, -1, 13584, 13608, 14752, -1, 14753, 14754, 14755, -1, 14756, 14752, 14757, -1, 14756, 14757, 14758, -1, 14756, 13585, 13584, -1, 14756, 13584, 14752, -1, 14759, 14758, 14754, -1, 14759, 14753, 13601, -1, 14759, 13601, 13585, -1, 14759, 14756, 14758, -1, 14759, 14754, 14753, -1, 14759, 13585, 14756, -1, 14760, 14761, 14762, -1, 13622, 13647, 14763, -1, 14764, 14765, 14766, -1, 14764, 14766, 14761, -1, 14764, 14760, 14767, -1, 14764, 14761, 14760, -1, 14768, 14769, 14765, -1, 14768, 14765, 14764, -1, 14770, 14767, 14771, -1, 14770, 14771, 14772, -1, 14770, 14764, 14767, -1, 14773, 13623, 13622, -1, 14773, 14763, 14769, -1, 14773, 14769, 14768, -1, 14773, 13622, 14763, -1, 14774, 14772, 14775, -1, 14774, 14775, 14776, -1, 14774, 14776, 14777, -1, 14774, 14770, 14772, -1, 14774, 14764, 14770, -1, 14774, 14768, 14764, -1, 14778, 14777, 14779, -1, 14778, 14779, 13639, -1, 14778, 13639, 13623, -1, 14778, 13623, 14773, -1, 14778, 14774, 14777, -1, 14778, 14773, 14768, -1, 14778, 14768, 14774, -1, 13660, 13686, 14780, -1, 14781, 14782, 14783, -1, 14784, 14780, 14785, -1, 14784, 14785, 14786, -1, 14784, 13661, 13660, -1, 14784, 13660, 14780, -1, 14787, 14786, 14782, -1, 14787, 14781, 13678, -1, 14787, 13678, 13661, -1, 14787, 14784, 14786, -1, 14787, 14782, 14781, -1, 14787, 13661, 14784, -1, 14788, 14789, 14790, -1, 13701, 13725, 14791, -1, 14792, 14793, 14794, -1, 14792, 14794, 14789, -1, 14792, 14788, 14795, -1, 14792, 14789, 14788, -1, 14796, 14797, 14793, -1, 14796, 14793, 14792, -1, 14798, 14795, 14799, -1, 14798, 14799, 14800, -1, 14798, 14792, 14795, -1, 14801, 13702, 13701, -1, 14801, 14791, 14797, -1, 14801, 14797, 14796, -1, 14801, 13701, 14791, -1, 14802, 14800, 14803, -1, 14802, 14803, 14804, -1, 14802, 14804, 14805, -1, 14802, 14798, 14800, -1, 14802, 14792, 14798, -1, 14802, 14796, 14792, -1, 14806, 14805, 14807, -1, 14806, 14807, 13718, -1, 14806, 13718, 13702, -1, 14806, 13702, 14801, -1, 14806, 14802, 14805, -1, 14806, 14801, 14796, -1, 14806, 14796, 14802, -1, 13738, 13764, 14808, -1, 14809, 14810, 14811, -1, 14812, 14808, 14813, -1, 14812, 14813, 14814, -1, 14812, 13739, 13738, -1, 14812, 13738, 14808, -1, 14815, 14814, 14810, -1, 14815, 14809, 13756, -1, 14815, 13756, 13739, -1, 14815, 14812, 14814, -1, 14815, 14810, 14809, -1, 14815, 13739, 14812, -1, 14816, 14817, 14818, -1, 14819, 14820, 14821, -1, 14822, 14823, 14824, -1, 14822, 14824, 14817, -1, 14822, 14816, 14825, -1, 14822, 14817, 14816, -1, 14826, 14827, 14823, -1, 14826, 14823, 14822, -1, 14828, 14825, 14829, -1, 14828, 14829, 14830, -1, 14828, 14822, 14825, -1, 14831, 14832, 14819, -1, 14831, 14821, 14827, -1, 14831, 14827, 14826, -1, 14831, 14819, 14821, -1, 14833, 14834, 14835, -1, 14833, 14830, 14836, -1, 14833, 14836, 14834, -1, 14833, 14828, 14830, -1, 14833, 14822, 14828, -1, 14833, 14826, 14822, -1, 14837, 14835, 14838, -1, 14837, 14838, 14839, -1, 14837, 14839, 14832, -1, 14837, 14826, 14833, -1, 14837, 14833, 14835, -1, 14837, 14832, 14831, -1, 14837, 14831, 14826, -1, 14840, 14841, 14842, -1, 14843, 14844, 14845, -1, 14846, 14847, 14848, -1, 14846, 14848, 14840, -1, 14846, 14842, 14849, -1, 14846, 14840, 14842, -1, 14850, 14851, 14845, -1, 14850, 14844, 14847, -1, 14850, 14849, 14851, -1, 14850, 14846, 14849, -1, 14850, 14847, 14846, -1, 14850, 14845, 14844, -1, 14852, 14853, 14854, -1, 14855, 14856, 14857, -1, 14858, 14859, 14860, -1, 14858, 14860, 14853, -1, 14858, 14852, 14861, -1, 14858, 14853, 14852, -1, 14862, 14863, 14859, -1, 14862, 14859, 14858, -1, 14864, 14861, 14865, -1, 14864, 14865, 14866, -1, 14864, 14858, 14861, -1, 14867, 14868, 14855, -1, 14867, 14857, 14863, -1, 14867, 14863, 14862, -1, 14867, 14855, 14857, -1, 14869, 14870, 14871, -1, 14869, 14866, 14872, -1, 14869, 14872, 14870, -1, 14869, 14864, 14866, -1, 14869, 14858, 14864, -1, 14869, 14862, 14858, -1, 14873, 14871, 14874, -1, 14873, 14874, 14875, -1, 14873, 14875, 14868, -1, 14873, 14862, 14869, -1, 14873, 14869, 14871, -1, 14873, 14868, 14867, -1, 14873, 14867, 14862, -1, 14876, 14877, 14878, -1, 14879, 14880, 14881, -1, 14882, 14883, 14884, -1, 14882, 14884, 14876, -1, 14882, 14878, 14885, -1, 14882, 14876, 14878, -1, 14886, 14887, 14881, -1, 14886, 14880, 14883, -1, 14886, 14885, 14887, -1, 14886, 14882, 14885, -1, 14886, 14883, 14882, -1, 14886, 14881, 14880, -1, 14888, 14889, 14890, -1, 14891, 14892, 14893, -1, 14894, 14895, 14896, -1, 14894, 14896, 14888, -1, 14894, 14890, 14897, -1, 14894, 14888, 14890, -1, 14898, 14899, 14893, -1, 14898, 14892, 14895, -1, 14898, 14897, 14899, -1, 14898, 14894, 14897, -1, 14898, 14895, 14894, -1, 14898, 14893, 14892, -1, 14900, 14901, 14902, -1, 14903, 14904, 14905, -1, 14906, 14907, 14908, -1, 14906, 14908, 14901, -1, 14906, 14900, 14909, -1, 14906, 14901, 14900, -1, 14910, 14911, 14907, -1, 14910, 14907, 14906, -1, 14912, 14909, 14913, -1, 14912, 14913, 14914, -1, 14912, 14906, 14909, -1, 14915, 14916, 14903, -1, 14915, 14905, 14911, -1, 14915, 14911, 14910, -1, 14915, 14903, 14905, -1, 14917, 14918, 14919, -1, 14917, 14914, 14920, -1, 14917, 14920, 14918, -1, 14917, 14912, 14914, -1, 14917, 14906, 14912, -1, 14917, 14910, 14906, -1, 14921, 14919, 14922, -1, 14921, 14922, 14923, -1, 14921, 14923, 14916, -1, 14921, 14910, 14917, -1, 14921, 14917, 14919, -1, 14921, 14916, 14915, -1, 14921, 14915, 14910, -1, 14924, 14925, 14926, -1, 14927, 14928, 14929, -1, 14930, 14931, 14932, -1, 14930, 14932, 14925, -1, 14930, 14924, 14933, -1, 14930, 14925, 14924, -1, 14934, 14935, 14931, -1, 14934, 14931, 14930, -1, 14936, 14933, 14937, -1, 14936, 14937, 14938, -1, 14936, 14930, 14933, -1, 14939, 14940, 14927, -1, 14939, 14929, 14935, -1, 14939, 14935, 14934, -1, 14939, 14927, 14929, -1, 14941, 14942, 14943, -1, 14941, 14938, 14944, -1, 14941, 14944, 14942, -1, 14941, 14936, 14938, -1, 14941, 14930, 14936, -1, 14941, 14934, 14930, -1, 14945, 14943, 14946, -1, 14945, 14946, 14947, -1, 14945, 14947, 14940, -1, 14945, 14934, 14941, -1, 14945, 14941, 14943, -1, 14945, 14940, 14939, -1, 14945, 14939, 14934, -1, 14948, 14949, 14950, -1, 14951, 14952, 14953, -1, 14954, 14955, 14956, -1, 14954, 14956, 14948, -1, 14954, 14950, 14957, -1, 14954, 14948, 14950, -1, 14958, 14959, 14953, -1, 14958, 14952, 14955, -1, 14958, 14957, 14959, -1, 14958, 14954, 14957, -1, 14958, 14955, 14954, -1, 14958, 14953, 14952, -1, 14059, 14083, 14960, -1, 14961, 14962, 14963, -1, 14964, 14960, 14965, -1, 14964, 14965, 14966, -1, 14964, 14060, 14059, -1, 14964, 14059, 14960, -1, 14967, 14966, 14962, -1, 14967, 14961, 14076, -1, 14967, 14076, 14060, -1, 14967, 14964, 14966, -1, 14967, 14962, 14961, -1, 14967, 14060, 14964, -1, 14968, 14094, 14969, -1, 14970, 14971, 14972, -1, 14970, 14968, 14971, -1, 14973, 14974, 14972, -1, 14973, 14975, 14976, -1, 14973, 14972, 14975, -1, 14977, 14976, 12000, -1, 14977, 14973, 14976, -1, 14978, 12001, 14979, -1, 14978, 12000, 12001, -1, 14978, 14979, 14980, -1, 14978, 14977, 12000, -1, 14981, 14977, 14978, -1, 14981, 14973, 14977, -1, 14981, 14978, 14980, -1, 14981, 14980, 14974, -1, 14981, 14974, 14973, -1, 14982, 14094, 14968, -1, 14982, 14968, 14970, -1, 14983, 14101, 14094, -1, 14983, 14982, 14970, -1, 14983, 14984, 14101, -1, 14983, 14972, 14984, -1, 14983, 14970, 14972, -1, 14983, 14094, 14982, -1, 14985, 14986, 11993, -1, 14985, 11993, 11992, -1, 14987, 14988, 14986, -1, 14987, 14989, 14988, -1, 14987, 14986, 14985, -1, 14990, 14987, 14985, -1, 14991, 14987, 14990, -1, 14991, 14989, 14987, -1, 14992, 14094, 14093, -1, 14992, 14993, 14989, -1, 14992, 14093, 14993, -1, 14992, 14989, 14991, -1, 14972, 14971, 14994, -1, 14974, 14984, 14972, -1, 14980, 14979, 14995, -1, 14996, 14101, 14984, -1, 14996, 14984, 14974, -1, 14996, 14974, 14980, -1, 14997, 14998, 14999, -1, 14997, 14995, 14998, -1, 14997, 14980, 14995, -1, 14997, 14996, 14980, -1, 15000, 14101, 14996, -1, 15001, 14999, 14103, -1, 15001, 14103, 14101, -1, 15001, 14997, 14999, -1, 15001, 14996, 14997, -1, 15001, 14101, 15000, -1, 15001, 15000, 14996, -1, 15002, 14990, 14985, -1, 15002, 14971, 14991, -1, 15002, 14985, 11992, -1, 15002, 14991, 14990, -1, 15003, 14971, 15002, -1, 15003, 15002, 11992, -1, 15004, 14994, 14971, -1, 15004, 14971, 15003, -1, 15004, 15003, 11992, -1, 14975, 11992, 12000, -1, 14975, 14994, 15004, -1, 14975, 14972, 14994, -1, 14975, 15004, 11992, -1, 14976, 14975, 12000, -1, 14969, 14991, 14971, -1, 14969, 14992, 14991, -1, 14969, 14094, 14992, -1, 14968, 14969, 14971, -1, 15005, 14104, 15006, -1, 15007, 15008, 15009, -1, 15007, 15005, 15008, -1, 15010, 15009, 15011, -1, 15010, 15012, 15009, -1, 15010, 15011, 15013, -1, 15014, 15013, 12027, -1, 15014, 15010, 15013, -1, 15015, 15014, 12027, -1, 15015, 12027, 12028, -1, 15015, 12028, 15016, -1, 15015, 15016, 15017, -1, 15018, 15010, 15014, -1, 15018, 15015, 15017, -1, 15018, 15014, 15015, -1, 15018, 15017, 15012, -1, 15018, 15012, 15010, -1, 15019, 14104, 15005, -1, 15019, 15005, 15007, -1, 15020, 15019, 15007, -1, 15020, 14113, 14104, -1, 15020, 15021, 14113, -1, 15020, 15009, 15021, -1, 15020, 15007, 15009, -1, 15020, 14104, 15019, -1, 15022, 15023, 12015, -1, 15022, 12015, 12014, -1, 15024, 15025, 15023, -1, 15024, 15026, 15025, -1, 15024, 15023, 15022, -1, 15027, 15024, 15022, -1, 15028, 15024, 15027, -1, 15028, 15026, 15024, -1, 15029, 15030, 15026, -1, 15029, 14106, 15030, -1, 15029, 14104, 14106, -1, 15029, 15026, 15028, -1, 15009, 15008, 15031, -1, 15012, 15021, 15009, -1, 15017, 15016, 15032, -1, 15033, 14113, 15021, -1, 15033, 15021, 15012, -1, 15033, 15012, 15017, -1, 15034, 15035, 15036, -1, 15034, 15032, 15035, -1, 15034, 15017, 15032, -1, 15034, 15033, 15017, -1, 15037, 14113, 15033, -1, 15038, 15036, 14117, -1, 15038, 14117, 14113, -1, 15038, 15034, 15036, -1, 15038, 15033, 15034, -1, 15038, 14113, 15037, -1, 15038, 15037, 15033, -1, 15039, 15027, 15022, -1, 15039, 15008, 15028, -1, 15039, 15022, 12014, -1, 15039, 15028, 15027, -1, 15040, 15008, 15039, -1, 15040, 15039, 12014, -1, 15041, 15031, 15008, -1, 15041, 15008, 15040, -1, 15041, 15040, 12014, -1, 15011, 12014, 12027, -1, 15011, 15009, 15031, -1, 15011, 15031, 15041, -1, 15011, 15041, 12014, -1, 15013, 15011, 12027, -1, 15006, 15028, 15008, -1, 15006, 15029, 15028, -1, 15006, 14104, 15029, -1, 15005, 15006, 15008, -1, 15042, 15043, 15044, -1, 15042, 14130, 15043, -1, 15045, 15044, 15046, -1, 15045, 15042, 15044, -1, 15047, 15048, 15046, -1, 15047, 15049, 15050, -1, 15047, 15046, 15049, -1, 15051, 15050, 11960, -1, 15051, 15047, 15050, -1, 15052, 11962, 15053, -1, 15052, 11960, 11962, -1, 15052, 15053, 15054, -1, 15052, 15051, 11960, -1, 15055, 15051, 15052, -1, 15055, 15047, 15051, -1, 15055, 15052, 15054, -1, 15055, 15054, 15048, -1, 15055, 15048, 15047, -1, 15056, 14130, 15042, -1, 15056, 15042, 15045, -1, 15057, 14137, 14130, -1, 15057, 15056, 15045, -1, 15057, 15058, 14137, -1, 15057, 15046, 15058, -1, 15057, 15045, 15046, -1, 15057, 14130, 15056, -1, 15059, 15060, 11953, -1, 15059, 11953, 11952, -1, 15061, 15062, 15060, -1, 15061, 15063, 15062, -1, 15061, 15060, 15059, -1, 15064, 15061, 15059, -1, 15065, 15061, 15064, -1, 15065, 15063, 15061, -1, 15066, 14130, 14129, -1, 15066, 15067, 15063, -1, 15066, 14129, 15067, -1, 15066, 15063, 15065, -1, 15046, 15044, 15068, -1, 15048, 15058, 15046, -1, 15054, 15053, 15069, -1, 15070, 14137, 15058, -1, 15070, 15058, 15048, -1, 15070, 15048, 15054, -1, 15071, 15072, 15073, -1, 15071, 15069, 15072, -1, 15071, 15054, 15069, -1, 15071, 15070, 15054, -1, 15074, 14137, 15070, -1, 15075, 15073, 14139, -1, 15075, 14139, 14137, -1, 15075, 15071, 15073, -1, 15075, 15070, 15071, -1, 15075, 14137, 15074, -1, 15075, 15074, 15070, -1, 15076, 15064, 15059, -1, 15076, 15044, 15065, -1, 15076, 15059, 11952, -1, 15076, 15065, 15064, -1, 15077, 15044, 15076, -1, 15077, 15076, 11952, -1, 15078, 15068, 15044, -1, 15078, 15044, 15077, -1, 15078, 15077, 11952, -1, 15049, 11952, 11960, -1, 15049, 15068, 15078, -1, 15049, 15046, 15068, -1, 15049, 15078, 11952, -1, 15050, 15049, 11960, -1, 15043, 15065, 15044, -1, 15043, 15066, 15065, -1, 15043, 14130, 15066, -1, 15079, 15080, 15081, -1, 15079, 14140, 15080, -1, 15082, 15081, 15083, -1, 15082, 15079, 15081, -1, 15084, 15083, 15085, -1, 15084, 15086, 15083, -1, 15084, 15085, 15087, -1, 15088, 15087, 11981, -1, 15088, 15084, 15087, -1, 15089, 15088, 11981, -1, 15089, 11981, 11983, -1, 15089, 11983, 15090, -1, 15089, 15090, 15091, -1, 15092, 15084, 15088, -1, 15092, 15089, 15091, -1, 15092, 15088, 15089, -1, 15092, 15091, 15086, -1, 15092, 15086, 15084, -1, 15093, 14140, 15079, -1, 15093, 15079, 15082, -1, 15094, 15093, 15082, -1, 15094, 14149, 14140, -1, 15094, 15095, 14149, -1, 15094, 15083, 15095, -1, 15094, 15082, 15083, -1, 15094, 14140, 15093, -1, 15096, 15097, 11972, -1, 15096, 11972, 11971, -1, 15098, 15099, 15097, -1, 15098, 15100, 15099, -1, 15098, 15097, 15096, -1, 15101, 15098, 15096, -1, 15102, 15098, 15101, -1, 15102, 15100, 15098, -1, 15103, 15104, 15100, -1, 15103, 14142, 15104, -1, 15103, 14140, 14142, -1, 15103, 15100, 15102, -1, 15083, 15081, 15105, -1, 15086, 15095, 15083, -1, 15091, 15090, 15106, -1, 15107, 14149, 15095, -1, 15107, 15095, 15086, -1, 15107, 15086, 15091, -1, 15108, 15109, 15110, -1, 15108, 15106, 15109, -1, 15108, 15091, 15106, -1, 15108, 15107, 15091, -1, 15111, 14149, 15107, -1, 15112, 15110, 14153, -1, 15112, 14153, 14149, -1, 15112, 15108, 15110, -1, 15112, 15107, 15108, -1, 15112, 14149, 15111, -1, 15112, 15111, 15107, -1, 15113, 15101, 15096, -1, 15113, 15096, 11971, -1, 15113, 15081, 15102, -1, 15113, 15102, 15101, -1, 15114, 15113, 11971, -1, 15114, 15081, 15113, -1, 15115, 15105, 15081, -1, 15115, 15114, 11971, -1, 15115, 15081, 15114, -1, 15085, 11971, 11981, -1, 15085, 15083, 15105, -1, 15085, 15105, 15115, -1, 15085, 15115, 11971, -1, 15087, 15085, 11981, -1, 15080, 15102, 15081, -1, 15080, 15103, 15102, -1, 15080, 14140, 15103, -1, 15116, 15117, 15118, -1, 15116, 14166, 15117, -1, 15119, 15118, 15120, -1, 15119, 15116, 15118, -1, 15121, 15122, 15120, -1, 15121, 15123, 15124, -1, 15121, 15120, 15123, -1, 15125, 15124, 11680, -1, 15125, 15121, 15124, -1, 15126, 11684, 15127, -1, 15126, 11680, 11684, -1, 15126, 15127, 15128, -1, 15126, 15125, 11680, -1, 15129, 15125, 15126, -1, 15129, 15121, 15125, -1, 15129, 15126, 15128, -1, 15129, 15128, 15122, -1, 15129, 15122, 15121, -1, 15130, 14166, 15116, -1, 15130, 15116, 15119, -1, 15131, 14173, 14166, -1, 15131, 15130, 15119, -1, 15131, 15132, 14173, -1, 15131, 15120, 15132, -1, 15131, 15119, 15120, -1, 15131, 14166, 15130, -1, 15133, 15134, 11675, -1, 15133, 11675, 11674, -1, 15135, 15136, 15134, -1, 15135, 15137, 15136, -1, 15135, 15134, 15133, -1, 15138, 15135, 15133, -1, 15139, 15135, 15138, -1, 15139, 15137, 15135, -1, 15140, 14166, 14165, -1, 15140, 15141, 15137, -1, 15140, 14165, 15141, -1, 15140, 15137, 15139, -1, 15120, 15118, 15142, -1, 15122, 15132, 15120, -1, 15128, 15127, 15143, -1, 15144, 14173, 15132, -1, 15144, 15132, 15122, -1, 15144, 15122, 15128, -1, 15145, 15146, 15147, -1, 15145, 15143, 15146, -1, 15145, 15128, 15143, -1, 15145, 15144, 15128, -1, 15148, 14173, 15144, -1, 15149, 15147, 14175, -1, 15149, 14175, 14173, -1, 15149, 15145, 15147, -1, 15149, 15144, 15145, -1, 15149, 14173, 15148, -1, 15149, 15148, 15144, -1, 15150, 15138, 15133, -1, 15150, 15118, 15139, -1, 15150, 15133, 11674, -1, 15150, 15139, 15138, -1, 15151, 15118, 15150, -1, 15151, 15150, 11674, -1, 15152, 15142, 15118, -1, 15152, 15118, 15151, -1, 15152, 15151, 11674, -1, 15123, 11674, 11680, -1, 15123, 15142, 15152, -1, 15123, 15120, 15142, -1, 15123, 15152, 11674, -1, 15124, 15123, 11680, -1, 15117, 15139, 15118, -1, 15117, 15140, 15139, -1, 15117, 14166, 15140, -1, 15153, 14176, 15154, -1, 15155, 15156, 15157, -1, 15155, 15153, 15156, -1, 15158, 15157, 15159, -1, 15158, 15160, 15157, -1, 15158, 15159, 15161, -1, 15162, 15161, 11709, -1, 15162, 15158, 15161, -1, 15163, 15162, 11709, -1, 15163, 11709, 11710, -1, 15163, 11710, 15164, -1, 15163, 15164, 15165, -1, 15166, 15158, 15162, -1, 15166, 15163, 15165, -1, 15166, 15162, 15163, -1, 15166, 15165, 15160, -1, 15166, 15160, 15158, -1, 15167, 14176, 15153, -1, 15167, 15153, 15155, -1, 15168, 15167, 15155, -1, 15168, 14185, 14176, -1, 15168, 15169, 14185, -1, 15168, 15157, 15169, -1, 15168, 15155, 15157, -1, 15168, 14176, 15167, -1, 15170, 15171, 11702, -1, 15170, 11702, 11701, -1, 15172, 15173, 15171, -1, 15172, 15174, 15173, -1, 15172, 15171, 15170, -1, 15175, 15172, 15170, -1, 15176, 15172, 15175, -1, 15176, 15174, 15172, -1, 15177, 15178, 15174, -1, 15177, 14178, 15178, -1, 15177, 14176, 14178, -1, 15177, 15174, 15176, -1, 15157, 15156, 15179, -1, 15160, 15169, 15157, -1, 15165, 15164, 15180, -1, 15181, 14185, 15169, -1, 15181, 15169, 15160, -1, 15181, 15160, 15165, -1, 15182, 15183, 15184, -1, 15182, 15180, 15183, -1, 15182, 15165, 15180, -1, 15182, 15181, 15165, -1, 15185, 14185, 15181, -1, 15186, 15184, 14189, -1, 15186, 14189, 14185, -1, 15186, 15182, 15184, -1, 15186, 15181, 15182, -1, 15186, 14185, 15185, -1, 15186, 15185, 15181, -1, 15187, 15175, 15170, -1, 15187, 15156, 15176, -1, 15187, 15170, 11701, -1, 15187, 15176, 15175, -1, 15188, 15156, 15187, -1, 15188, 15187, 11701, -1, 15189, 15179, 15156, -1, 15189, 15156, 15188, -1, 15189, 15188, 11701, -1, 15159, 11701, 11709, -1, 15159, 15157, 15179, -1, 15159, 15179, 15189, -1, 15159, 15189, 11701, -1, 15161, 15159, 11709, -1, 15154, 15176, 15156, -1, 15154, 15177, 15176, -1, 15154, 14176, 15177, -1, 15153, 15154, 15156, -1, 15190, 15191, 15192, -1, 15190, 14202, 15191, -1, 15193, 15192, 15194, -1, 15193, 15190, 15192, -1, 15195, 15194, 15196, -1, 15195, 15197, 15194, -1, 15195, 15196, 15198, -1, 15199, 15198, 12042, -1, 15199, 15195, 15198, -1, 15200, 15199, 12042, -1, 15200, 12042, 12043, -1, 15200, 12043, 15201, -1, 15200, 15201, 15202, -1, 15203, 15195, 15199, -1, 15203, 15200, 15202, -1, 15203, 15199, 15200, -1, 15203, 15202, 15197, -1, 15203, 15197, 15195, -1, 15204, 14202, 15190, -1, 15204, 15190, 15193, -1, 15205, 15204, 15193, -1, 15205, 14209, 14202, -1, 15205, 15206, 14209, -1, 15205, 15194, 15206, -1, 15205, 15193, 15194, -1, 15205, 14202, 15204, -1, 15207, 15208, 12037, -1, 15207, 12037, 12036, -1, 15209, 15210, 15208, -1, 15209, 15211, 15210, -1, 15209, 15208, 15207, -1, 15212, 15209, 15207, -1, 15213, 15209, 15212, -1, 15213, 15211, 15209, -1, 15214, 15215, 15211, -1, 15214, 14201, 15215, -1, 15214, 14202, 14201, -1, 15214, 15211, 15213, -1, 15194, 15192, 15216, -1, 15197, 15206, 15194, -1, 15202, 15201, 15217, -1, 15218, 14209, 15206, -1, 15218, 15206, 15197, -1, 15218, 15197, 15202, -1, 15219, 15220, 15221, -1, 15219, 15217, 15220, -1, 15219, 15202, 15217, -1, 15219, 15218, 15202, -1, 15222, 14209, 15218, -1, 15223, 15221, 14211, -1, 15223, 14211, 14209, -1, 15223, 15219, 15221, -1, 15223, 15218, 15219, -1, 15223, 14209, 15222, -1, 15223, 15222, 15218, -1, 15224, 15212, 15207, -1, 15224, 15207, 12036, -1, 15224, 15192, 15213, -1, 15224, 15213, 15212, -1, 15225, 15224, 12036, -1, 15225, 15192, 15224, -1, 15226, 15216, 15192, -1, 15226, 15225, 12036, -1, 15226, 15192, 15225, -1, 15196, 12036, 12042, -1, 15196, 15194, 15216, -1, 15196, 15216, 15226, -1, 15196, 15226, 12036, -1, 15198, 15196, 12042, -1, 15191, 15213, 15192, -1, 15191, 15214, 15213, -1, 15191, 14202, 15214, -1, 15227, 14212, 15228, -1, 15229, 15230, 15231, -1, 15229, 15227, 15230, -1, 15232, 15231, 15233, -1, 15232, 15234, 15231, -1, 15232, 15233, 15235, -1, 15236, 15235, 12056, -1, 15236, 15232, 15235, -1, 15237, 15236, 12056, -1, 15237, 12056, 12057, -1, 15237, 12057, 15238, -1, 15237, 15238, 15239, -1, 15240, 15232, 15236, -1, 15240, 15237, 15239, -1, 15240, 15236, 15237, -1, 15240, 15239, 15234, -1, 15240, 15234, 15232, -1, 15241, 14212, 15227, -1, 15241, 15227, 15229, -1, 15242, 15241, 15229, -1, 15242, 14221, 14212, -1, 15242, 15243, 14221, -1, 15242, 15231, 15243, -1, 15242, 15229, 15231, -1, 15242, 14212, 15241, -1, 15244, 15245, 12051, -1, 15244, 12051, 12050, -1, 15246, 15247, 15245, -1, 15246, 15248, 15247, -1, 15246, 15245, 15244, -1, 15249, 15246, 15244, -1, 15250, 15246, 15249, -1, 15250, 15248, 15246, -1, 15251, 15252, 15248, -1, 15251, 14214, 15252, -1, 15251, 14212, 14214, -1, 15251, 15248, 15250, -1, 15231, 15230, 15253, -1, 15234, 15243, 15231, -1, 15239, 15238, 15254, -1, 15255, 14221, 15243, -1, 15255, 15243, 15234, -1, 15255, 15234, 15239, -1, 15256, 15257, 15258, -1, 15256, 15254, 15257, -1, 15256, 15239, 15254, -1, 15256, 15255, 15239, -1, 15259, 14221, 15255, -1, 15260, 15258, 14225, -1, 15260, 14225, 14221, -1, 15260, 15256, 15258, -1, 15260, 15255, 15256, -1, 15260, 14221, 15259, -1, 15260, 15259, 15255, -1, 15261, 15249, 15244, -1, 15261, 15230, 15250, -1, 15261, 15244, 12050, -1, 15261, 15250, 15249, -1, 15262, 15230, 15261, -1, 15262, 15261, 12050, -1, 15263, 15253, 15230, -1, 15263, 15230, 15262, -1, 15263, 15262, 12050, -1, 15233, 12050, 12056, -1, 15233, 15231, 15253, -1, 15233, 15253, 15263, -1, 15233, 15263, 12050, -1, 15235, 15233, 12056, -1, 15228, 15250, 15230, -1, 15228, 15251, 15250, -1, 15228, 14212, 15251, -1, 15227, 15228, 15230, -1, 15264, 14236, 15265, -1, 15266, 15267, 15268, -1, 15266, 15264, 15267, -1, 15269, 15270, 15271, -1, 15269, 15272, 15268, -1, 15269, 15268, 15270, -1, 15273, 15271, 11936, -1, 15273, 15269, 15271, -1, 15274, 11938, 15275, -1, 15274, 11936, 11938, -1, 15274, 15275, 15276, -1, 15274, 15273, 11936, -1, 15277, 15273, 15274, -1, 15277, 15269, 15273, -1, 15277, 15274, 15276, -1, 15277, 15276, 15272, -1, 15277, 15272, 15269, -1, 15278, 14236, 15264, -1, 15278, 15264, 15266, -1, 15279, 14245, 14236, -1, 15279, 15278, 15266, -1, 15279, 15280, 14245, -1, 15279, 15268, 15280, -1, 15279, 15266, 15268, -1, 15279, 14236, 15278, -1, 15281, 15282, 11930, -1, 15281, 11930, 11929, -1, 15283, 15284, 15282, -1, 15283, 15285, 15284, -1, 15283, 15282, 15281, -1, 15286, 15283, 15281, -1, 15287, 15283, 15286, -1, 15287, 15285, 15283, -1, 15288, 14236, 14238, -1, 15288, 15289, 15285, -1, 15288, 14238, 15289, -1, 15288, 15285, 15287, -1, 15268, 15267, 15290, -1, 15272, 15280, 15268, -1, 15276, 15275, 15291, -1, 15292, 14245, 15280, -1, 15292, 15280, 15272, -1, 15292, 15272, 15276, -1, 15293, 15294, 15295, -1, 15293, 15291, 15294, -1, 15293, 15276, 15291, -1, 15293, 15292, 15276, -1, 15296, 14245, 15292, -1, 15297, 15295, 14249, -1, 15297, 14249, 14245, -1, 15297, 15293, 15295, -1, 15297, 15292, 15293, -1, 15297, 14245, 15296, -1, 15297, 15296, 15292, -1, 15298, 15286, 15281, -1, 15298, 15267, 15287, -1, 15298, 15281, 11929, -1, 15298, 15287, 15286, -1, 15299, 15267, 15298, -1, 15299, 15298, 11929, -1, 15300, 15290, 15267, -1, 15300, 15267, 15299, -1, 15300, 15299, 11929, -1, 15270, 11929, 11936, -1, 15270, 15268, 15290, -1, 15270, 15290, 15300, -1, 15270, 15300, 11929, -1, 15271, 15270, 11936, -1, 15265, 15287, 15267, -1, 15265, 15288, 15287, -1, 15265, 14236, 15288, -1, 15264, 15265, 15267, -1, 15301, 14262, 15302, -1, 15303, 15304, 15305, -1, 15303, 15301, 15304, -1, 15306, 15307, 15305, -1, 15306, 15308, 15309, -1, 15306, 15305, 15308, -1, 15310, 15309, 11918, -1, 15310, 15306, 15309, -1, 15311, 11919, 15312, -1, 15311, 11918, 11919, -1, 15311, 15312, 15313, -1, 15311, 15310, 11918, -1, 15314, 15310, 15311, -1, 15314, 15306, 15310, -1, 15314, 15311, 15313, -1, 15314, 15313, 15307, -1, 15314, 15307, 15306, -1, 15315, 14262, 15301, -1, 15315, 15301, 15303, -1, 15316, 14269, 14262, -1, 15316, 15315, 15303, -1, 15316, 15317, 14269, -1, 15316, 15305, 15317, -1, 15316, 15303, 15305, -1, 15316, 14262, 15315, -1, 15318, 15319, 11908, -1, 15318, 11908, 11907, -1, 15320, 15321, 15319, -1, 15320, 15322, 15321, -1, 15320, 15319, 15318, -1, 15323, 15320, 15318, -1, 15324, 15320, 15323, -1, 15324, 15322, 15320, -1, 15325, 14262, 14261, -1, 15325, 15326, 15322, -1, 15325, 14261, 15326, -1, 15325, 15322, 15324, -1, 15305, 15304, 15327, -1, 15307, 15317, 15305, -1, 15313, 15312, 15328, -1, 15329, 14269, 15317, -1, 15329, 15317, 15307, -1, 15329, 15307, 15313, -1, 15330, 15331, 15332, -1, 15330, 15328, 15331, -1, 15330, 15313, 15328, -1, 15330, 15329, 15313, -1, 15333, 14269, 15329, -1, 15334, 15332, 14271, -1, 15334, 14271, 14269, -1, 15334, 15330, 15332, -1, 15334, 15329, 15330, -1, 15334, 14269, 15333, -1, 15334, 15333, 15329, -1, 15335, 15323, 15318, -1, 15335, 15304, 15324, -1, 15335, 15318, 11907, -1, 15335, 15324, 15323, -1, 15336, 15304, 15335, -1, 15336, 15335, 11907, -1, 15337, 15327, 15304, -1, 15337, 15304, 15336, -1, 15337, 15336, 11907, -1, 15308, 11907, 11918, -1, 15308, 15327, 15337, -1, 15308, 15305, 15327, -1, 15308, 15337, 11907, -1, 15309, 15308, 11918, -1, 15302, 15324, 15304, -1, 15302, 15325, 15324, -1, 15302, 14262, 15325, -1, 15301, 15302, 15304, -1, 15338, 15339, 15340, -1, 15338, 14272, 15339, -1, 15341, 15340, 15342, -1, 15341, 15338, 15340, -1, 15343, 15344, 15345, -1, 15343, 15346, 15342, -1, 15343, 15342, 15344, -1, 15347, 15345, 11888, -1, 15347, 15343, 15345, -1, 15348, 11890, 15349, -1, 15348, 11888, 11890, -1, 15348, 15349, 15350, -1, 15348, 15347, 11888, -1, 15351, 15347, 15348, -1, 15351, 15343, 15347, -1, 15351, 15348, 15350, -1, 15351, 15350, 15346, -1, 15351, 15346, 15343, -1, 15352, 14272, 15338, -1, 15352, 15338, 15341, -1, 15353, 14281, 14272, -1, 15353, 15352, 15341, -1, 15353, 15354, 14281, -1, 15353, 15342, 15354, -1, 15353, 15341, 15342, -1, 15353, 14272, 15352, -1, 15355, 15356, 11875, -1, 15355, 11875, 11874, -1, 15357, 15358, 15356, -1, 15357, 15359, 15358, -1, 15357, 15356, 15355, -1, 15360, 15357, 15355, -1, 15361, 15357, 15360, -1, 15361, 15359, 15357, -1, 15362, 14272, 14274, -1, 15362, 15363, 15359, -1, 15362, 14274, 15363, -1, 15362, 15359, 15361, -1, 15342, 15340, 15364, -1, 15346, 15354, 15342, -1, 15350, 15349, 15365, -1, 15366, 14281, 15354, -1, 15366, 15354, 15346, -1, 15366, 15346, 15350, -1, 15367, 15368, 15369, -1, 15367, 15365, 15368, -1, 15367, 15350, 15365, -1, 15367, 15366, 15350, -1, 15370, 14281, 15366, -1, 15371, 15369, 14285, -1, 15371, 14285, 14281, -1, 15371, 15367, 15369, -1, 15371, 15366, 15367, -1, 15371, 14281, 15370, -1, 15371, 15370, 15366, -1, 15372, 15360, 15355, -1, 15372, 15340, 15361, -1, 15372, 15355, 11874, -1, 15372, 15361, 15360, -1, 15373, 15340, 15372, -1, 15373, 15372, 11874, -1, 15374, 15364, 15340, -1, 15374, 15340, 15373, -1, 15374, 15373, 11874, -1, 15344, 11874, 11888, -1, 15344, 15342, 15364, -1, 15344, 15364, 15374, -1, 15344, 15374, 11874, -1, 15345, 15344, 11888, -1, 15339, 15361, 15340, -1, 15339, 15362, 15361, -1, 15339, 14272, 15362, -1, 15375, 14298, 15376, -1, 15377, 15378, 15379, -1, 15377, 15375, 15378, -1, 15380, 15381, 15379, -1, 15380, 15382, 15383, -1, 15380, 15379, 15382, -1, 15384, 15383, 11863, -1, 15384, 15380, 15383, -1, 15385, 11864, 15386, -1, 15385, 11863, 11864, -1, 15385, 15386, 15387, -1, 15385, 15384, 11863, -1, 15388, 15384, 15385, -1, 15388, 15380, 15384, -1, 15388, 15385, 15387, -1, 15388, 15387, 15381, -1, 15388, 15381, 15380, -1, 15389, 14298, 15375, -1, 15389, 15375, 15377, -1, 15390, 14305, 14298, -1, 15390, 15389, 15377, -1, 15390, 15391, 14305, -1, 15390, 15379, 15391, -1, 15390, 15377, 15379, -1, 15390, 14298, 15389, -1, 15392, 15393, 11842, -1, 15392, 11842, 11841, -1, 15394, 15395, 15393, -1, 15394, 15396, 15395, -1, 15394, 15393, 15392, -1, 15397, 15394, 15392, -1, 15398, 15394, 15397, -1, 15398, 15396, 15394, -1, 15399, 14298, 14297, -1, 15399, 15400, 15396, -1, 15399, 14297, 15400, -1, 15399, 15396, 15398, -1, 15379, 15378, 15401, -1, 15381, 15391, 15379, -1, 15387, 15386, 15402, -1, 15403, 14305, 15391, -1, 15403, 15391, 15381, -1, 15403, 15381, 15387, -1, 15404, 15405, 15406, -1, 15404, 15402, 15405, -1, 15404, 15387, 15402, -1, 15404, 15403, 15387, -1, 15407, 14305, 15403, -1, 15408, 15406, 14307, -1, 15408, 14307, 14305, -1, 15408, 15404, 15406, -1, 15408, 15403, 15404, -1, 15408, 14305, 15407, -1, 15408, 15407, 15403, -1, 15409, 15397, 15392, -1, 15409, 15378, 15398, -1, 15409, 15392, 11841, -1, 15409, 15398, 15397, -1, 15410, 15378, 15409, -1, 15410, 15409, 11841, -1, 15411, 15401, 15378, -1, 15411, 15378, 15410, -1, 15411, 15410, 11841, -1, 15382, 11841, 11863, -1, 15382, 15401, 15411, -1, 15382, 15379, 15401, -1, 15382, 15411, 11841, -1, 15383, 15382, 11863, -1, 15376, 15398, 15378, -1, 15376, 15399, 15398, -1, 15376, 14298, 15399, -1, 15375, 15376, 15378, -1, 15412, 14308, 15413, -1, 15414, 15415, 15416, -1, 15414, 15412, 15415, -1, 15417, 15418, 15419, -1, 15417, 15420, 15416, -1, 15417, 15416, 15418, -1, 15421, 15419, 11739, -1, 15421, 15417, 15419, -1, 15422, 11740, 15423, -1, 15422, 11739, 11740, -1, 15422, 15423, 15424, -1, 15422, 15421, 11739, -1, 15425, 15421, 15422, -1, 15425, 15417, 15421, -1, 15425, 15422, 15424, -1, 15425, 15424, 15420, -1, 15425, 15420, 15417, -1, 15426, 14308, 15412, -1, 15426, 15412, 15414, -1, 15427, 14317, 14308, -1, 15427, 15426, 15414, -1, 15427, 15428, 14317, -1, 15427, 15416, 15428, -1, 15427, 15414, 15416, -1, 15427, 14308, 15426, -1, 15429, 15430, 11727, -1, 15429, 11727, 11729, -1, 15431, 15432, 15430, -1, 15431, 15433, 15432, -1, 15431, 15430, 15429, -1, 15434, 15431, 15429, -1, 15435, 15431, 15434, -1, 15435, 15433, 15431, -1, 15436, 14308, 14310, -1, 15436, 15437, 15433, -1, 15436, 14310, 15437, -1, 15436, 15433, 15435, -1, 15416, 15415, 15438, -1, 15420, 15428, 15416, -1, 15424, 15423, 15439, -1, 15440, 14317, 15428, -1, 15440, 15428, 15420, -1, 15440, 15420, 15424, -1, 15441, 15442, 15443, -1, 15441, 15439, 15442, -1, 15441, 15424, 15439, -1, 15441, 15440, 15424, -1, 15444, 14317, 15440, -1, 15445, 15443, 14321, -1, 15445, 14321, 14317, -1, 15445, 15441, 15443, -1, 15445, 15440, 15441, -1, 15445, 14317, 15444, -1, 15445, 15444, 15440, -1, 15446, 15434, 15429, -1, 15446, 15415, 15435, -1, 15446, 15429, 11729, -1, 15446, 15435, 15434, -1, 15447, 15415, 15446, -1, 15447, 15446, 11729, -1, 15448, 15438, 15415, -1, 15448, 15415, 15447, -1, 15448, 15447, 11729, -1, 15418, 11729, 11739, -1, 15418, 15416, 15438, -1, 15418, 15438, 15448, -1, 15418, 15448, 11729, -1, 15419, 15418, 11739, -1, 15413, 15435, 15415, -1, 15413, 15436, 15435, -1, 15413, 14308, 15436, -1, 15412, 15413, 15415, -1, 15449, 14334, 15450, -1, 15451, 15452, 15453, -1, 15451, 15449, 15452, -1, 15454, 15455, 15453, -1, 15454, 15456, 15457, -1, 15454, 15453, 15456, -1, 15458, 15457, 11716, -1, 15458, 15454, 15457, -1, 15459, 11717, 15460, -1, 15459, 11716, 11717, -1, 15459, 15460, 15461, -1, 15459, 15458, 11716, -1, 15462, 15458, 15459, -1, 15462, 15454, 15458, -1, 15462, 15459, 15461, -1, 15462, 15461, 15455, -1, 15462, 15455, 15454, -1, 15463, 14334, 15449, -1, 15463, 15449, 15451, -1, 15464, 14341, 14334, -1, 15464, 15463, 15451, -1, 15464, 15465, 14341, -1, 15464, 15453, 15465, -1, 15464, 15451, 15453, -1, 15464, 14334, 15463, -1, 15466, 15467, 11703, -1, 15466, 11703, 11705, -1, 15468, 15469, 15467, -1, 15468, 15470, 15469, -1, 15468, 15467, 15466, -1, 15471, 15468, 15466, -1, 15472, 15468, 15471, -1, 15472, 15470, 15468, -1, 15473, 14334, 14333, -1, 15473, 15474, 15470, -1, 15473, 14333, 15474, -1, 15473, 15470, 15472, -1, 15453, 15452, 15475, -1, 15455, 15465, 15453, -1, 15461, 15460, 15476, -1, 15477, 14341, 15465, -1, 15477, 15465, 15455, -1, 15477, 15455, 15461, -1, 15478, 15479, 15480, -1, 15478, 15476, 15479, -1, 15478, 15461, 15476, -1, 15478, 15477, 15461, -1, 15481, 14341, 15477, -1, 15482, 15480, 14343, -1, 15482, 14343, 14341, -1, 15482, 15478, 15480, -1, 15482, 15477, 15478, -1, 15482, 14341, 15481, -1, 15482, 15481, 15477, -1, 15483, 15471, 15466, -1, 15483, 15452, 15472, -1, 15483, 15466, 11705, -1, 15483, 15472, 15471, -1, 15484, 15452, 15483, -1, 15484, 15483, 11705, -1, 15485, 15475, 15452, -1, 15485, 15452, 15484, -1, 15485, 15484, 11705, -1, 15456, 11705, 11716, -1, 15456, 15475, 15485, -1, 15456, 15453, 15475, -1, 15456, 15485, 11705, -1, 15457, 15456, 11716, -1, 15450, 15472, 15452, -1, 15450, 15473, 15472, -1, 15450, 14334, 15473, -1, 15449, 15450, 15452, -1, 15486, 14346, 15487, -1, 15488, 15489, 15490, -1, 15488, 15486, 15489, -1, 15491, 15490, 15492, -1, 15491, 15493, 15490, -1, 15491, 15492, 15494, -1, 15495, 15494, 11763, -1, 15495, 15491, 15494, -1, 15496, 15495, 11763, -1, 15496, 11763, 11764, -1, 15496, 11764, 15497, -1, 15496, 15497, 15498, -1, 15499, 15491, 15495, -1, 15499, 15496, 15498, -1, 15499, 15495, 15496, -1, 15499, 15498, 15493, -1, 15499, 15493, 15491, -1, 15500, 14346, 15486, -1, 15500, 15486, 15488, -1, 15501, 15500, 15488, -1, 15501, 14353, 14346, -1, 15501, 15502, 14353, -1, 15501, 15490, 15502, -1, 15501, 15488, 15490, -1, 15501, 14346, 15500, -1, 15503, 15504, 11750, -1, 15503, 11750, 11752, -1, 15505, 15506, 15504, -1, 15505, 15507, 15506, -1, 15505, 15504, 15503, -1, 15508, 15505, 15503, -1, 15509, 15505, 15508, -1, 15509, 15507, 15505, -1, 15510, 15511, 15507, -1, 15510, 14345, 15511, -1, 15510, 14346, 14345, -1, 15510, 15507, 15509, -1, 15490, 15489, 15512, -1, 15493, 15502, 15490, -1, 15498, 15497, 15513, -1, 15514, 14353, 15502, -1, 15514, 15502, 15493, -1, 15514, 15493, 15498, -1, 15515, 15516, 15517, -1, 15515, 15513, 15516, -1, 15515, 15498, 15513, -1, 15515, 15514, 15498, -1, 15518, 14353, 15514, -1, 15519, 15517, 14355, -1, 15519, 14355, 14353, -1, 15519, 15515, 15517, -1, 15519, 15514, 15515, -1, 15519, 14353, 15518, -1, 15519, 15518, 15514, -1, 15520, 15508, 15503, -1, 15520, 15489, 15509, -1, 15520, 15503, 11752, -1, 15520, 15509, 15508, -1, 15521, 15489, 15520, -1, 15521, 15520, 11752, -1, 15522, 15512, 15489, -1, 15522, 15489, 15521, -1, 15522, 15521, 11752, -1, 15492, 11752, 11763, -1, 15492, 15490, 15512, -1, 15492, 15512, 15522, -1, 15492, 15522, 11752, -1, 15494, 15492, 11763, -1, 15487, 15509, 15489, -1, 15487, 15510, 15509, -1, 15487, 14346, 15510, -1, 15486, 15487, 15489, -1, 15523, 14356, 15524, -1, 15525, 15526, 15527, -1, 15525, 15523, 15526, -1, 15528, 15527, 15529, -1, 15528, 15530, 15527, -1, 15528, 15529, 15531, -1, 15532, 15531, 11825, -1, 15532, 15528, 15531, -1, 15533, 15532, 11825, -1, 15533, 11825, 11827, -1, 15533, 11827, 15534, -1, 15533, 15534, 15535, -1, 15536, 15528, 15532, -1, 15536, 15533, 15535, -1, 15536, 15532, 15533, -1, 15536, 15535, 15530, -1, 15536, 15530, 15528, -1, 15537, 14356, 15523, -1, 15537, 15523, 15525, -1, 15538, 15537, 15525, -1, 15538, 14365, 14356, -1, 15538, 15539, 14365, -1, 15538, 15527, 15539, -1, 15538, 15525, 15527, -1, 15538, 14356, 15537, -1, 15540, 15541, 11775, -1, 15540, 11775, 11777, -1, 15542, 15543, 15541, -1, 15542, 15544, 15543, -1, 15542, 15541, 15540, -1, 15545, 15542, 15540, -1, 15546, 15542, 15545, -1, 15546, 15544, 15542, -1, 15547, 15548, 15544, -1, 15547, 14358, 15548, -1, 15547, 14356, 14358, -1, 15547, 15544, 15546, -1, 15527, 15526, 15549, -1, 15530, 15539, 15527, -1, 15535, 15534, 15550, -1, 15551, 14365, 15539, -1, 15551, 15539, 15530, -1, 15551, 15530, 15535, -1, 15552, 15553, 15554, -1, 15552, 15550, 15553, -1, 15552, 15535, 15550, -1, 15552, 15551, 15535, -1, 15555, 14365, 15551, -1, 15556, 15554, 14369, -1, 15556, 14369, 14365, -1, 15556, 15552, 15554, -1, 15556, 15551, 15552, -1, 15556, 14365, 15555, -1, 15556, 15555, 15551, -1, 15557, 15545, 15540, -1, 15557, 15526, 15546, -1, 15557, 15540, 11777, -1, 15557, 15546, 15545, -1, 15558, 15526, 15557, -1, 15558, 15557, 11777, -1, 15559, 15549, 15526, -1, 15559, 15526, 15558, -1, 15559, 15558, 11777, -1, 15529, 11777, 11825, -1, 15529, 15527, 15549, -1, 15529, 15549, 15559, -1, 15529, 15559, 11777, -1, 15531, 15529, 11825, -1, 15524, 15546, 15526, -1, 15524, 15547, 15546, -1, 15524, 14356, 15547, -1, 15523, 15524, 15526, -1, 15560, 15561, 15562, -1, 15560, 6897, 15561, -1, 15563, 15562, 15564, -1, 15563, 15560, 15562, -1, 15565, 15566, 15564, -1, 15565, 15567, 15568, -1, 15565, 15564, 15567, -1, 15569, 15568, 12018, -1, 15569, 15565, 15568, -1, 15570, 12021, 15571, -1, 15570, 12018, 12021, -1, 15570, 15571, 15572, -1, 15570, 15569, 12018, -1, 15573, 15569, 15570, -1, 15573, 15565, 15569, -1, 15573, 15570, 15572, -1, 15573, 15572, 15566, -1, 15573, 15566, 15565, -1, 15574, 6897, 15560, -1, 15574, 15560, 15563, -1, 15575, 6904, 6897, -1, 15575, 15574, 15563, -1, 15575, 15576, 6904, -1, 15575, 15564, 15576, -1, 15575, 15563, 15564, -1, 15575, 6897, 15574, -1, 15577, 15578, 12012, -1, 15577, 12012, 12011, -1, 15579, 15580, 15578, -1, 15579, 15581, 15580, -1, 15579, 15578, 15577, -1, 15582, 15579, 15577, -1, 15583, 15579, 15582, -1, 15583, 15581, 15579, -1, 15584, 6897, 6896, -1, 15584, 15585, 15581, -1, 15584, 6896, 15585, -1, 15584, 15581, 15583, -1, 15564, 15562, 15586, -1, 15566, 15576, 15564, -1, 15572, 15571, 15587, -1, 15588, 6904, 15576, -1, 15588, 15576, 15566, -1, 15588, 15566, 15572, -1, 15589, 15590, 15591, -1, 15589, 15587, 15590, -1, 15589, 15572, 15587, -1, 15589, 15588, 15572, -1, 15592, 6904, 15588, -1, 15593, 15591, 6906, -1, 15593, 6906, 6904, -1, 15593, 15589, 15591, -1, 15593, 15588, 15589, -1, 15593, 6904, 15592, -1, 15593, 15592, 15588, -1, 15594, 15582, 15577, -1, 15594, 15562, 15583, -1, 15594, 15577, 12011, -1, 15594, 15583, 15582, -1, 15595, 15562, 15594, -1, 15595, 15594, 12011, -1, 15596, 15586, 15562, -1, 15596, 15562, 15595, -1, 15596, 15595, 12011, -1, 15567, 12011, 12018, -1, 15567, 15586, 15596, -1, 15567, 15564, 15586, -1, 15567, 15596, 12011, -1, 15568, 15567, 12018, -1, 15561, 15583, 15562, -1, 15561, 15584, 15583, -1, 15561, 6897, 15584, -1, 15597, 15598, 15599, -1, 15597, 6941, 15598, -1, 15600, 15599, 15601, -1, 15600, 15597, 15599, -1, 15602, 15601, 15603, -1, 15602, 15604, 15601, -1, 15602, 15603, 15605, -1, 15606, 15605, 12020, -1, 15606, 15602, 15605, -1, 15607, 15606, 12020, -1, 15607, 12020, 12019, -1, 15607, 12019, 15608, -1, 15607, 15608, 15609, -1, 15610, 15602, 15606, -1, 15610, 15607, 15609, -1, 15610, 15606, 15607, -1, 15610, 15609, 15604, -1, 15610, 15604, 15602, -1, 15611, 6941, 15597, -1, 15611, 15597, 15600, -1, 15612, 15611, 15600, -1, 15612, 6950, 6941, -1, 15612, 15613, 6950, -1, 15612, 15601, 15613, -1, 15612, 15600, 15601, -1, 15612, 6941, 15611, -1, 15614, 15615, 12023, -1, 15614, 12023, 12022, -1, 15616, 15617, 15615, -1, 15616, 15618, 15617, -1, 15616, 15615, 15614, -1, 15619, 15616, 15614, -1, 15620, 15616, 15619, -1, 15620, 15618, 15616, -1, 15621, 15622, 15618, -1, 15621, 6943, 15622, -1, 15621, 6941, 6943, -1, 15621, 15618, 15620, -1, 15601, 15599, 15623, -1, 15604, 15613, 15601, -1, 15609, 15608, 15624, -1, 15625, 6950, 15613, -1, 15625, 15613, 15604, -1, 15625, 15604, 15609, -1, 15626, 15627, 15628, -1, 15626, 15624, 15627, -1, 15626, 15609, 15624, -1, 15626, 15625, 15609, -1, 15629, 6950, 15625, -1, 15630, 15628, 6954, -1, 15630, 6954, 6950, -1, 15630, 15626, 15628, -1, 15630, 15625, 15626, -1, 15630, 6950, 15629, -1, 15630, 15629, 15625, -1, 15631, 15619, 15614, -1, 15631, 15614, 12022, -1, 15631, 15599, 15620, -1, 15631, 15620, 15619, -1, 15632, 15631, 12022, -1, 15632, 15599, 15631, -1, 15633, 15623, 15599, -1, 15633, 15632, 12022, -1, 15633, 15599, 15632, -1, 15603, 12022, 12020, -1, 15603, 15601, 15623, -1, 15603, 15623, 15633, -1, 15603, 15633, 12022, -1, 15605, 15603, 12020, -1, 15598, 15620, 15599, -1, 15598, 15621, 15620, -1, 15598, 6941, 15621, -1, 15634, 15635, 15636, -1, 15634, 7073, 15635, -1, 15637, 15636, 15638, -1, 15637, 15634, 15636, -1, 15639, 15640, 15641, -1, 15639, 15642, 15638, -1, 15639, 15638, 15640, -1, 15643, 15641, 11969, -1, 15643, 15639, 15641, -1, 15644, 11977, 15645, -1, 15644, 11969, 11977, -1, 15644, 15645, 15646, -1, 15644, 15643, 11969, -1, 15647, 15643, 15644, -1, 15647, 15639, 15643, -1, 15647, 15644, 15646, -1, 15647, 15646, 15642, -1, 15647, 15642, 15639, -1, 15648, 7073, 15634, -1, 15648, 15634, 15637, -1, 15649, 7080, 7073, -1, 15649, 15648, 15637, -1, 15649, 15650, 7080, -1, 15649, 15638, 15650, -1, 15649, 15637, 15638, -1, 15649, 7073, 15648, -1, 15651, 15652, 11965, -1, 15651, 11965, 11964, -1, 15653, 15654, 15652, -1, 15653, 15655, 15654, -1, 15653, 15652, 15651, -1, 15656, 15653, 15651, -1, 15657, 15653, 15656, -1, 15657, 15655, 15653, -1, 15658, 7073, 7072, -1, 15658, 15659, 15655, -1, 15658, 7072, 15659, -1, 15658, 15655, 15657, -1, 15638, 15636, 15660, -1, 15642, 15650, 15638, -1, 15646, 15645, 15661, -1, 15662, 7080, 15650, -1, 15662, 15650, 15642, -1, 15662, 15642, 15646, -1, 15663, 15664, 15665, -1, 15663, 15661, 15664, -1, 15663, 15646, 15661, -1, 15663, 15662, 15646, -1, 15666, 7080, 15662, -1, 15667, 15665, 7082, -1, 15667, 7082, 7080, -1, 15667, 15663, 15665, -1, 15667, 15662, 15663, -1, 15667, 7080, 15666, -1, 15667, 15666, 15662, -1, 15668, 15656, 15651, -1, 15668, 15636, 15657, -1, 15668, 15651, 11964, -1, 15668, 15657, 15656, -1, 15669, 15636, 15668, -1, 15669, 15668, 11964, -1, 15670, 15660, 15636, -1, 15670, 15636, 15669, -1, 15670, 15669, 11964, -1, 15640, 11964, 11969, -1, 15640, 15638, 15660, -1, 15640, 15660, 15670, -1, 15640, 15670, 11964, -1, 15641, 15640, 11969, -1, 15635, 15657, 15636, -1, 15635, 15658, 15657, -1, 15635, 7073, 15658, -1, 15671, 15672, 15673, -1, 15671, 7223, 15672, -1, 15674, 15673, 15675, -1, 15674, 15671, 15673, -1, 15676, 15675, 15677, -1, 15676, 15678, 15675, -1, 15676, 15677, 15679, -1, 15680, 15679, 11996, -1, 15680, 15676, 15679, -1, 15681, 15680, 11996, -1, 15681, 11996, 12007, -1, 15681, 12007, 15682, -1, 15681, 15682, 15683, -1, 15684, 15676, 15680, -1, 15684, 15681, 15683, -1, 15684, 15680, 15681, -1, 15684, 15683, 15678, -1, 15684, 15678, 15676, -1, 15685, 7223, 15671, -1, 15685, 15671, 15674, -1, 15686, 15685, 15674, -1, 15686, 7232, 7223, -1, 15686, 15687, 7232, -1, 15686, 15675, 15687, -1, 15686, 15674, 15675, -1, 15686, 7223, 15685, -1, 15688, 15689, 11990, -1, 15688, 11990, 11988, -1, 15690, 15691, 15689, -1, 15690, 15692, 15691, -1, 15690, 15689, 15688, -1, 15693, 15690, 15688, -1, 15694, 15690, 15693, -1, 15694, 15692, 15690, -1, 15695, 15696, 15692, -1, 15695, 7225, 15696, -1, 15695, 7223, 7225, -1, 15695, 15692, 15694, -1, 15675, 15673, 15697, -1, 15678, 15687, 15675, -1, 15683, 15682, 15698, -1, 15699, 7232, 15687, -1, 15699, 15687, 15678, -1, 15699, 15678, 15683, -1, 15700, 15701, 15702, -1, 15700, 15698, 15701, -1, 15700, 15683, 15698, -1, 15700, 15699, 15683, -1, 15703, 7232, 15699, -1, 15704, 15702, 7236, -1, 15704, 7236, 7232, -1, 15704, 15700, 15702, -1, 15704, 15699, 15700, -1, 15704, 7232, 15703, -1, 15704, 15703, 15699, -1, 15705, 15693, 15688, -1, 15705, 15688, 11988, -1, 15705, 15673, 15694, -1, 15705, 15694, 15693, -1, 15706, 15705, 11988, -1, 15706, 15673, 15705, -1, 15707, 15697, 15673, -1, 15707, 15706, 11988, -1, 15707, 15673, 15706, -1, 15677, 11988, 11996, -1, 15677, 15675, 15697, -1, 15677, 15697, 15707, -1, 15677, 15707, 11988, -1, 15679, 15677, 11996, -1, 15672, 15694, 15673, -1, 15672, 15695, 15694, -1, 15672, 7223, 15695, -1, 15708, 15709, 15710, -1, 15708, 7247, 15709, -1, 15711, 15710, 15712, -1, 15711, 15708, 15710, -1, 15713, 15714, 15715, -1, 15713, 15716, 15712, -1, 15713, 15712, 15714, -1, 15717, 15715, 11916, -1, 15717, 15713, 15715, -1, 15718, 11915, 15719, -1, 15718, 11916, 11915, -1, 15718, 15719, 15720, -1, 15718, 15717, 11916, -1, 15721, 15717, 15718, -1, 15721, 15713, 15717, -1, 15721, 15718, 15720, -1, 15721, 15720, 15716, -1, 15721, 15716, 15713, -1, 15722, 7247, 15708, -1, 15722, 15708, 15711, -1, 15723, 7256, 7247, -1, 15723, 15722, 15711, -1, 15723, 15724, 7256, -1, 15723, 15712, 15724, -1, 15723, 15711, 15712, -1, 15723, 7247, 15722, -1, 15725, 15726, 11933, -1, 15725, 11933, 11927, -1, 15727, 15728, 15726, -1, 15727, 15729, 15728, -1, 15727, 15726, 15725, -1, 15730, 15727, 15725, -1, 15731, 15727, 15730, -1, 15731, 15729, 15727, -1, 15732, 7247, 7249, -1, 15732, 15733, 15729, -1, 15732, 7249, 15733, -1, 15732, 15729, 15731, -1, 15712, 15710, 15734, -1, 15716, 15724, 15712, -1, 15720, 15719, 15735, -1, 15736, 7256, 15724, -1, 15736, 15724, 15716, -1, 15736, 15716, 15720, -1, 15737, 15738, 15739, -1, 15737, 15735, 15738, -1, 15737, 15720, 15735, -1, 15737, 15736, 15720, -1, 15740, 7256, 15736, -1, 15741, 15739, 7260, -1, 15741, 7260, 7256, -1, 15741, 15737, 15739, -1, 15741, 15736, 15737, -1, 15741, 7256, 15740, -1, 15741, 15740, 15736, -1, 15742, 15730, 15725, -1, 15742, 15710, 15731, -1, 15742, 15725, 11927, -1, 15742, 15731, 15730, -1, 15743, 15710, 15742, -1, 15743, 15742, 11927, -1, 15744, 15734, 15710, -1, 15744, 15710, 15743, -1, 15744, 15743, 11927, -1, 15714, 11927, 11916, -1, 15714, 15712, 15734, -1, 15714, 15734, 15744, -1, 15714, 15744, 11927, -1, 15715, 15714, 11916, -1, 15709, 15731, 15710, -1, 15709, 15732, 15731, -1, 15709, 7247, 15732, -1, 15745, 15746, 15747, -1, 15745, 7365, 15746, -1, 15748, 15747, 15749, -1, 15748, 15745, 15747, -1, 15750, 15751, 15752, -1, 15750, 15753, 15749, -1, 15750, 15749, 15751, -1, 15754, 15752, 11946, -1, 15754, 15750, 15752, -1, 15755, 11945, 15756, -1, 15755, 11946, 11945, -1, 15755, 15756, 15757, -1, 15755, 15754, 11946, -1, 15758, 15754, 15755, -1, 15758, 15750, 15754, -1, 15758, 15755, 15757, -1, 15758, 15757, 15753, -1, 15758, 15753, 15750, -1, 15759, 7365, 15745, -1, 15759, 15745, 15748, -1, 15760, 7372, 7365, -1, 15760, 15759, 15748, -1, 15760, 15761, 7372, -1, 15760, 15749, 15761, -1, 15760, 15748, 15749, -1, 15760, 7365, 15759, -1, 15762, 15763, 11959, -1, 15762, 11959, 11954, -1, 15764, 15765, 15763, -1, 15764, 15766, 15765, -1, 15764, 15763, 15762, -1, 15767, 15764, 15762, -1, 15768, 15764, 15767, -1, 15768, 15766, 15764, -1, 15769, 7365, 7364, -1, 15769, 15770, 15766, -1, 15769, 7364, 15770, -1, 15769, 15766, 15768, -1, 15749, 15747, 15771, -1, 15753, 15761, 15749, -1, 15757, 15756, 15772, -1, 15773, 7372, 15761, -1, 15773, 15761, 15753, -1, 15773, 15753, 15757, -1, 15774, 15775, 15776, -1, 15774, 15772, 15775, -1, 15774, 15757, 15772, -1, 15774, 15773, 15757, -1, 15777, 7372, 15773, -1, 15778, 15776, 7374, -1, 15778, 7374, 7372, -1, 15778, 15774, 15776, -1, 15778, 15773, 15774, -1, 15778, 7372, 15777, -1, 15778, 15777, 15773, -1, 15779, 15767, 15762, -1, 15779, 15747, 15768, -1, 15779, 15762, 11954, -1, 15779, 15768, 15767, -1, 15780, 15747, 15779, -1, 15780, 15779, 11954, -1, 15781, 15771, 15747, -1, 15781, 15747, 15780, -1, 15781, 15780, 11954, -1, 15751, 11954, 11946, -1, 15751, 15749, 15771, -1, 15751, 15771, 15781, -1, 15751, 15781, 11954, -1, 15752, 15751, 11946, -1, 15746, 15768, 15747, -1, 15746, 15769, 15768, -1, 15746, 7365, 15769, -1, 15782, 15783, 15784, -1, 15782, 7545, 15783, -1, 15785, 15784, 15786, -1, 15785, 15782, 15784, -1, 15787, 15786, 15788, -1, 15787, 15789, 15786, -1, 15787, 15788, 15790, -1, 15791, 15790, 12004, -1, 15791, 15787, 15790, -1, 15792, 15791, 12004, -1, 15792, 12004, 12003, -1, 15792, 12003, 15793, -1, 15792, 15793, 15794, -1, 15795, 15787, 15791, -1, 15795, 15792, 15794, -1, 15795, 15791, 15792, -1, 15795, 15794, 15789, -1, 15795, 15789, 15787, -1, 15796, 7545, 15782, -1, 15796, 15782, 15785, -1, 15797, 15796, 15785, -1, 15797, 7552, 7545, -1, 15797, 15798, 7552, -1, 15797, 15786, 15798, -1, 15797, 15785, 15786, -1, 15797, 7545, 15796, -1, 15799, 15800, 12009, -1, 15799, 12009, 12008, -1, 15801, 15802, 15800, -1, 15801, 15803, 15802, -1, 15801, 15800, 15799, -1, 15804, 15801, 15799, -1, 15805, 15801, 15804, -1, 15805, 15803, 15801, -1, 15806, 15807, 15803, -1, 15806, 7544, 15807, -1, 15806, 7545, 7544, -1, 15806, 15803, 15805, -1, 15786, 15784, 15808, -1, 15789, 15798, 15786, -1, 15794, 15793, 15809, -1, 15810, 7552, 15798, -1, 15810, 15798, 15789, -1, 15810, 15789, 15794, -1, 15811, 15812, 15813, -1, 15811, 15809, 15812, -1, 15811, 15794, 15809, -1, 15811, 15810, 15794, -1, 15814, 7552, 15810, -1, 15815, 15813, 7554, -1, 15815, 7554, 7552, -1, 15815, 15811, 15813, -1, 15815, 15810, 15811, -1, 15815, 7552, 15814, -1, 15815, 15814, 15810, -1, 15816, 15804, 15799, -1, 15816, 15799, 12008, -1, 15816, 15784, 15805, -1, 15816, 15805, 15804, -1, 15817, 15816, 12008, -1, 15817, 15784, 15816, -1, 15818, 15808, 15784, -1, 15818, 15817, 12008, -1, 15818, 15784, 15817, -1, 15788, 12008, 12004, -1, 15788, 15786, 15808, -1, 15788, 15808, 15818, -1, 15788, 15818, 12008, -1, 15790, 15788, 12004, -1, 15783, 15805, 15784, -1, 15783, 15806, 15805, -1, 15783, 7545, 15806, -1, 15819, 15820, 15821, -1, 15819, 7671, 15820, -1, 15822, 15821, 15823, -1, 15822, 15819, 15821, -1, 15824, 15823, 15825, -1, 15824, 15826, 15823, -1, 15824, 15825, 15827, -1, 15828, 15827, 11974, -1, 15828, 15824, 15827, -1, 15829, 15828, 11974, -1, 15829, 11974, 11973, -1, 15829, 11973, 15830, -1, 15829, 15830, 15831, -1, 15832, 15824, 15828, -1, 15832, 15829, 15831, -1, 15832, 15828, 15829, -1, 15832, 15831, 15826, -1, 15832, 15826, 15824, -1, 15833, 7671, 15819, -1, 15833, 15819, 15822, -1, 15834, 15833, 15822, -1, 15834, 7680, 7671, -1, 15834, 15835, 7680, -1, 15834, 15823, 15835, -1, 15834, 15822, 15823, -1, 15834, 7671, 15833, -1, 15836, 15837, 11984, -1, 15836, 11984, 11978, -1, 15838, 15839, 15837, -1, 15838, 15840, 15839, -1, 15838, 15837, 15836, -1, 15841, 15838, 15836, -1, 15842, 15838, 15841, -1, 15842, 15840, 15838, -1, 15843, 15844, 15840, -1, 15843, 7673, 15844, -1, 15843, 7671, 7673, -1, 15843, 15840, 15842, -1, 15823, 15821, 15845, -1, 15826, 15835, 15823, -1, 15831, 15830, 15846, -1, 15847, 7680, 15835, -1, 15847, 15835, 15826, -1, 15847, 15826, 15831, -1, 15848, 15849, 15850, -1, 15848, 15846, 15849, -1, 15848, 15831, 15846, -1, 15848, 15847, 15831, -1, 15851, 7680, 15847, -1, 15852, 15850, 7684, -1, 15852, 7684, 7680, -1, 15852, 15848, 15850, -1, 15852, 15847, 15848, -1, 15852, 7680, 15851, -1, 15852, 15851, 15847, -1, 15853, 15841, 15836, -1, 15853, 15836, 11978, -1, 15853, 15821, 15842, -1, 15853, 15842, 15841, -1, 15854, 15853, 11978, -1, 15854, 15821, 15853, -1, 15855, 15845, 15821, -1, 15855, 15854, 11978, -1, 15855, 15821, 15854, -1, 15825, 11978, 11974, -1, 15825, 15823, 15845, -1, 15825, 15845, 15855, -1, 15825, 15855, 11978, -1, 15827, 15825, 11974, -1, 15820, 15842, 15821, -1, 15820, 15843, 15842, -1, 15820, 7671, 15843, -1, 15856, 14494, 15857, -1, 15858, 15859, 15860, -1, 15858, 15856, 15859, -1, 15861, 15862, 15860, -1, 15861, 15863, 15864, -1, 15861, 15860, 15863, -1, 15865, 15864, 11848, -1, 15865, 15861, 15864, -1, 15866, 11855, 15867, -1, 15866, 11848, 11855, -1, 15866, 15867, 15868, -1, 15866, 15865, 11848, -1, 15869, 15865, 15866, -1, 15869, 15861, 15865, -1, 15869, 15866, 15868, -1, 15869, 15868, 15862, -1, 15869, 15862, 15861, -1, 15870, 14494, 15856, -1, 15870, 15856, 15858, -1, 15871, 14501, 14494, -1, 15871, 15870, 15858, -1, 15871, 15872, 14501, -1, 15871, 15860, 15872, -1, 15871, 15858, 15860, -1, 15871, 14494, 15870, -1, 15873, 15874, 11844, -1, 15873, 11844, 11843, -1, 15875, 15876, 15874, -1, 15875, 15877, 15876, -1, 15875, 15874, 15873, -1, 15878, 15875, 15873, -1, 15879, 15875, 15878, -1, 15879, 15877, 15875, -1, 15880, 14494, 14493, -1, 15880, 15881, 15877, -1, 15880, 14493, 15881, -1, 15880, 15877, 15879, -1, 15860, 15859, 15882, -1, 15862, 15872, 15860, -1, 15868, 15867, 15883, -1, 15884, 14501, 15872, -1, 15884, 15872, 15862, -1, 15884, 15862, 15868, -1, 15885, 15886, 15887, -1, 15885, 15883, 15886, -1, 15885, 15868, 15883, -1, 15885, 15884, 15868, -1, 15888, 14501, 15884, -1, 15889, 15887, 14503, -1, 15889, 14503, 14501, -1, 15889, 15885, 15887, -1, 15889, 15884, 15885, -1, 15889, 14501, 15888, -1, 15889, 15888, 15884, -1, 15890, 15878, 15873, -1, 15890, 15859, 15879, -1, 15890, 15873, 11843, -1, 15890, 15879, 15878, -1, 15891, 15859, 15890, -1, 15891, 15890, 11843, -1, 15892, 15882, 15859, -1, 15892, 15859, 15891, -1, 15892, 15891, 11843, -1, 15863, 11843, 11848, -1, 15863, 15882, 15892, -1, 15863, 15860, 15882, -1, 15863, 15892, 11843, -1, 15864, 15863, 11848, -1, 15857, 15879, 15859, -1, 15857, 15880, 15879, -1, 15857, 14494, 15880, -1, 15856, 15857, 15859, -1, 15893, 15894, 15895, -1, 15893, 7803, 15894, -1, 15896, 15895, 15897, -1, 15896, 15893, 15895, -1, 15898, 15897, 15899, -1, 15898, 15900, 15897, -1, 15898, 15899, 15901, -1, 15902, 15901, 11876, -1, 15902, 15898, 15901, -1, 15903, 15902, 11876, -1, 15903, 11876, 11887, -1, 15903, 11887, 15904, -1, 15903, 15904, 15905, -1, 15906, 15898, 15902, -1, 15906, 15903, 15905, -1, 15906, 15902, 15903, -1, 15906, 15905, 15900, -1, 15906, 15900, 15898, -1, 15907, 7803, 15893, -1, 15907, 15893, 15896, -1, 15908, 15907, 15896, -1, 15908, 7812, 7803, -1, 15908, 15909, 7812, -1, 15908, 15897, 15909, -1, 15908, 15896, 15897, -1, 15908, 7803, 15907, -1, 15910, 15911, 11872, -1, 15910, 11872, 11871, -1, 15912, 15913, 15911, -1, 15912, 15914, 15913, -1, 15912, 15911, 15910, -1, 15915, 15912, 15910, -1, 15916, 15912, 15915, -1, 15916, 15914, 15912, -1, 15917, 15918, 15914, -1, 15917, 7805, 15918, -1, 15917, 7803, 7805, -1, 15917, 15914, 15916, -1, 15897, 15895, 15919, -1, 15900, 15909, 15897, -1, 15905, 15904, 15920, -1, 15921, 7812, 15909, -1, 15921, 15909, 15900, -1, 15921, 15900, 15905, -1, 15922, 15923, 15924, -1, 15922, 15920, 15923, -1, 15922, 15905, 15920, -1, 15922, 15921, 15905, -1, 15925, 7812, 15921, -1, 15926, 15924, 7816, -1, 15926, 7816, 7812, -1, 15926, 15922, 15924, -1, 15926, 15921, 15922, -1, 15926, 7812, 15925, -1, 15926, 15925, 15921, -1, 15927, 15915, 15910, -1, 15927, 15910, 11871, -1, 15927, 15895, 15916, -1, 15927, 15916, 15915, -1, 15928, 15927, 11871, -1, 15928, 15895, 15927, -1, 15929, 15919, 15895, -1, 15929, 15928, 11871, -1, 15929, 15895, 15928, -1, 15899, 11871, 11876, -1, 15899, 15897, 15919, -1, 15899, 15919, 15929, -1, 15899, 15929, 11871, -1, 15901, 15899, 11876, -1, 15894, 15916, 15895, -1, 15894, 15917, 15916, -1, 15894, 7803, 15917, -1, 15930, 15931, 15932, -1, 15930, 8011, 15931, -1, 15933, 15932, 15934, -1, 15933, 15930, 15932, -1, 15935, 15936, 15934, -1, 15935, 15937, 15938, -1, 15935, 15934, 15937, -1, 15939, 15938, 11944, -1, 15939, 15935, 15938, -1, 15940, 11950, 15941, -1, 15940, 11944, 11950, -1, 15940, 15941, 15942, -1, 15940, 15939, 11944, -1, 15943, 15939, 15940, -1, 15943, 15935, 15939, -1, 15943, 15940, 15942, -1, 15943, 15942, 15936, -1, 15943, 15936, 15935, -1, 15944, 8011, 15930, -1, 15944, 15930, 15933, -1, 15945, 8020, 8011, -1, 15945, 15944, 15933, -1, 15945, 15946, 8020, -1, 15945, 15934, 15946, -1, 15945, 15933, 15934, -1, 15945, 8011, 15944, -1, 15947, 15948, 11940, -1, 15947, 11940, 11939, -1, 15949, 15950, 15948, -1, 15949, 15951, 15950, -1, 15949, 15948, 15947, -1, 15952, 15949, 15947, -1, 15953, 15949, 15952, -1, 15953, 15951, 15949, -1, 15954, 8011, 8013, -1, 15954, 15955, 15951, -1, 15954, 8013, 15955, -1, 15954, 15951, 15953, -1, 15934, 15932, 15956, -1, 15936, 15946, 15934, -1, 15942, 15941, 15957, -1, 15958, 8020, 15946, -1, 15958, 15946, 15936, -1, 15958, 15936, 15942, -1, 15959, 15960, 15961, -1, 15959, 15957, 15960, -1, 15959, 15942, 15957, -1, 15959, 15958, 15942, -1, 15962, 8020, 15958, -1, 15963, 15961, 8024, -1, 15963, 8024, 8020, -1, 15963, 15959, 15961, -1, 15963, 15958, 15959, -1, 15963, 8020, 15962, -1, 15963, 15962, 15958, -1, 15964, 15952, 15947, -1, 15964, 15932, 15953, -1, 15964, 15947, 11939, -1, 15964, 15953, 15952, -1, 15965, 15932, 15964, -1, 15965, 15964, 11939, -1, 15966, 15956, 15932, -1, 15966, 15932, 15965, -1, 15966, 15965, 11939, -1, 15937, 11939, 11944, -1, 15937, 15956, 15966, -1, 15937, 15934, 15956, -1, 15937, 15966, 11939, -1, 15938, 15937, 11944, -1, 15931, 15953, 15932, -1, 15931, 15954, 15953, -1, 15931, 8011, 15954, -1, 15967, 15968, 15969, -1, 15967, 8037, 15968, -1, 15970, 15969, 15971, -1, 15970, 15967, 15969, -1, 15972, 15971, 15973, -1, 15972, 15974, 15971, -1, 15972, 15973, 15975, -1, 15976, 15975, 11909, -1, 15976, 15972, 15975, -1, 15977, 15976, 11909, -1, 15977, 11909, 11921, -1, 15977, 11921, 15978, -1, 15977, 15978, 15979, -1, 15980, 15972, 15976, -1, 15980, 15977, 15979, -1, 15980, 15976, 15977, -1, 15980, 15979, 15974, -1, 15980, 15974, 15972, -1, 15981, 8037, 15967, -1, 15981, 15967, 15970, -1, 15982, 15981, 15970, -1, 15982, 8044, 8037, -1, 15982, 15983, 8044, -1, 15982, 15971, 15983, -1, 15982, 15970, 15971, -1, 15982, 8037, 15981, -1, 15984, 15985, 11904, -1, 15984, 11904, 11903, -1, 15986, 15987, 15985, -1, 15986, 15988, 15987, -1, 15986, 15985, 15984, -1, 15989, 15986, 15984, -1, 15990, 15986, 15989, -1, 15990, 15988, 15986, -1, 15991, 15992, 15988, -1, 15991, 8036, 15992, -1, 15991, 8037, 8036, -1, 15991, 15988, 15990, -1, 15971, 15969, 15993, -1, 15974, 15983, 15971, -1, 15979, 15978, 15994, -1, 15995, 8044, 15983, -1, 15995, 15983, 15974, -1, 15995, 15974, 15979, -1, 15996, 15997, 15998, -1, 15996, 15994, 15997, -1, 15996, 15979, 15994, -1, 15996, 15995, 15979, -1, 15999, 8044, 15995, -1, 16000, 15998, 8046, -1, 16000, 8046, 8044, -1, 16000, 15996, 15998, -1, 16000, 15995, 15996, -1, 16000, 8044, 15999, -1, 16000, 15999, 15995, -1, 16001, 15989, 15984, -1, 16001, 15984, 11903, -1, 16001, 15969, 15990, -1, 16001, 15990, 15989, -1, 16002, 16001, 11903, -1, 16002, 15969, 16001, -1, 16003, 15993, 15969, -1, 16003, 16002, 11903, -1, 16003, 15969, 16002, -1, 15973, 11903, 11909, -1, 15973, 15971, 15993, -1, 15973, 15993, 16003, -1, 15973, 16003, 11903, -1, 15975, 15973, 11909, -1, 15968, 15990, 15969, -1, 15968, 15991, 15990, -1, 15968, 8037, 15991, -1, 16004, 8235, 16005, -1, 16006, 16007, 16008, -1, 16006, 16004, 16007, -1, 16009, 16010, 16011, -1, 16009, 16012, 16008, -1, 16009, 16008, 16010, -1, 16013, 16011, 11820, -1, 16013, 16009, 16011, -1, 16014, 11824, 16015, -1, 16014, 11820, 11824, -1, 16014, 16015, 16016, -1, 16014, 16013, 11820, -1, 16017, 16013, 16014, -1, 16017, 16009, 16013, -1, 16017, 16014, 16016, -1, 16017, 16016, 16012, -1, 16017, 16012, 16009, -1, 16018, 8235, 16004, -1, 16018, 16004, 16006, -1, 16019, 8244, 8235, -1, 16019, 16018, 16006, -1, 16019, 16020, 8244, -1, 16019, 16008, 16020, -1, 16019, 16006, 16008, -1, 16019, 8235, 16018, -1, 16021, 16022, 11814, -1, 16021, 11814, 11813, -1, 16023, 16024, 16022, -1, 16023, 16025, 16024, -1, 16023, 16022, 16021, -1, 16026, 16023, 16021, -1, 16027, 16023, 16026, -1, 16027, 16025, 16023, -1, 16028, 8235, 8237, -1, 16028, 16029, 16025, -1, 16028, 8237, 16029, -1, 16028, 16025, 16027, -1, 16008, 16007, 16030, -1, 16012, 16020, 16008, -1, 16016, 16015, 16031, -1, 16032, 8244, 16020, -1, 16032, 16020, 16012, -1, 16032, 16012, 16016, -1, 16033, 16034, 16035, -1, 16033, 16031, 16034, -1, 16033, 16016, 16031, -1, 16033, 16032, 16016, -1, 16036, 8244, 16032, -1, 16037, 16035, 8248, -1, 16037, 8248, 8244, -1, 16037, 16033, 16035, -1, 16037, 16032, 16033, -1, 16037, 8244, 16036, -1, 16037, 16036, 16032, -1, 16038, 16026, 16021, -1, 16038, 16007, 16027, -1, 16038, 16021, 11813, -1, 16038, 16027, 16026, -1, 16039, 16007, 16038, -1, 16039, 16038, 11813, -1, 16040, 16030, 16007, -1, 16040, 16007, 16039, -1, 16040, 16039, 11813, -1, 16010, 11813, 11820, -1, 16010, 16008, 16030, -1, 16010, 16030, 16040, -1, 16010, 16040, 11813, -1, 16011, 16010, 11820, -1, 16005, 16027, 16007, -1, 16005, 16028, 16027, -1, 16005, 8235, 16028, -1, 16004, 16005, 16007, -1, 16041, 14574, 16042, -1, 16043, 16044, 16045, -1, 16043, 16041, 16044, -1, 16046, 16047, 16048, -1, 16046, 16049, 16045, -1, 16046, 16045, 16047, -1, 16050, 16048, 11791, -1, 16050, 16046, 16048, -1, 16051, 11796, 16052, -1, 16051, 11791, 11796, -1, 16051, 16052, 16053, -1, 16051, 16050, 11791, -1, 16054, 16050, 16051, -1, 16054, 16046, 16050, -1, 16054, 16051, 16053, -1, 16054, 16053, 16049, -1, 16054, 16049, 16046, -1, 16055, 14574, 16041, -1, 16055, 16041, 16043, -1, 16056, 14581, 14574, -1, 16056, 16055, 16043, -1, 16056, 16057, 14581, -1, 16056, 16045, 16057, -1, 16056, 16043, 16045, -1, 16056, 14574, 16055, -1, 16058, 16059, 11789, -1, 16058, 11789, 11788, -1, 16060, 16061, 16059, -1, 16060, 16062, 16061, -1, 16060, 16059, 16058, -1, 16063, 16060, 16058, -1, 16064, 16060, 16063, -1, 16064, 16062, 16060, -1, 16065, 14574, 14573, -1, 16065, 16066, 16062, -1, 16065, 14573, 16066, -1, 16065, 16062, 16064, -1, 16045, 16044, 16067, -1, 16049, 16057, 16045, -1, 16053, 16052, 16068, -1, 16069, 14581, 16057, -1, 16069, 16057, 16049, -1, 16069, 16049, 16053, -1, 16070, 16071, 16072, -1, 16070, 16068, 16071, -1, 16070, 16053, 16068, -1, 16070, 16069, 16053, -1, 16073, 14581, 16069, -1, 16074, 16072, 14583, -1, 16074, 14583, 14581, -1, 16074, 16070, 16072, -1, 16074, 16069, 16070, -1, 16074, 14581, 16073, -1, 16074, 16073, 16069, -1, 16075, 16063, 16058, -1, 16075, 16044, 16064, -1, 16075, 16058, 11788, -1, 16075, 16064, 16063, -1, 16076, 16044, 16075, -1, 16076, 16075, 11788, -1, 16077, 16067, 16044, -1, 16077, 16044, 16076, -1, 16077, 16076, 11788, -1, 16047, 11788, 11791, -1, 16047, 16045, 16067, -1, 16047, 16067, 16077, -1, 16047, 16077, 11788, -1, 16048, 16047, 11791, -1, 16042, 16064, 16044, -1, 16042, 16065, 16064, -1, 16042, 14574, 16065, -1, 16041, 16042, 16044, -1, 16078, 16079, 16080, -1, 16078, 14584, 16079, -1, 16081, 16080, 16082, -1, 16081, 16078, 16080, -1, 16083, 16084, 16085, -1, 16083, 16086, 16082, -1, 16083, 16082, 16084, -1, 16087, 16085, 11766, -1, 16087, 16083, 16085, -1, 16088, 11769, 16089, -1, 16088, 11766, 11769, -1, 16088, 16089, 16090, -1, 16088, 16087, 11766, -1, 16091, 16087, 16088, -1, 16091, 16083, 16087, -1, 16091, 16088, 16090, -1, 16091, 16090, 16086, -1, 16091, 16086, 16083, -1, 16092, 14584, 16078, -1, 16092, 16078, 16081, -1, 16093, 14593, 14584, -1, 16093, 16092, 16081, -1, 16093, 16094, 14593, -1, 16093, 16082, 16094, -1, 16093, 16081, 16082, -1, 16093, 14584, 16092, -1, 16095, 16096, 11760, -1, 16095, 11760, 11759, -1, 16097, 16098, 16096, -1, 16097, 16099, 16098, -1, 16097, 16096, 16095, -1, 16100, 16097, 16095, -1, 16101, 16097, 16100, -1, 16101, 16099, 16097, -1, 16102, 14584, 14586, -1, 16102, 16103, 16099, -1, 16102, 14586, 16103, -1, 16102, 16099, 16101, -1, 16082, 16080, 16104, -1, 16086, 16094, 16082, -1, 16090, 16089, 16105, -1, 16106, 14593, 16094, -1, 16106, 16094, 16086, -1, 16106, 16086, 16090, -1, 16107, 16108, 16109, -1, 16107, 16105, 16108, -1, 16107, 16090, 16105, -1, 16107, 16106, 16090, -1, 16110, 14593, 16106, -1, 16111, 16109, 14597, -1, 16111, 14597, 14593, -1, 16111, 16107, 16109, -1, 16111, 16106, 16107, -1, 16111, 14593, 16110, -1, 16111, 16110, 16106, -1, 16112, 16100, 16095, -1, 16112, 16080, 16101, -1, 16112, 16095, 11759, -1, 16112, 16101, 16100, -1, 16113, 16080, 16112, -1, 16113, 16112, 11759, -1, 16114, 16104, 16080, -1, 16114, 16080, 16113, -1, 16114, 16113, 11759, -1, 16084, 11759, 11766, -1, 16084, 16082, 16104, -1, 16084, 16104, 16114, -1, 16084, 16114, 11759, -1, 16085, 16084, 11766, -1, 16079, 16101, 16080, -1, 16079, 16102, 16101, -1, 16079, 14584, 16102, -1, 16115, 16116, 16117, -1, 16115, 14610, 16116, -1, 16118, 16117, 16119, -1, 16118, 16115, 16117, -1, 16120, 16119, 16121, -1, 16120, 16122, 16119, -1, 16120, 16121, 16123, -1, 16124, 16123, 11742, -1, 16124, 16120, 16123, -1, 16125, 16124, 11742, -1, 16125, 11742, 11743, -1, 16125, 11743, 16126, -1, 16125, 16126, 16127, -1, 16128, 16120, 16124, -1, 16128, 16125, 16127, -1, 16128, 16124, 16125, -1, 16128, 16127, 16122, -1, 16128, 16122, 16120, -1, 16129, 14610, 16115, -1, 16129, 16115, 16118, -1, 16130, 16129, 16118, -1, 16130, 14617, 14610, -1, 16130, 16131, 14617, -1, 16130, 16119, 16131, -1, 16130, 16118, 16119, -1, 16130, 14610, 16129, -1, 16132, 16133, 11731, -1, 16132, 11731, 11730, -1, 16134, 16135, 16133, -1, 16134, 16136, 16135, -1, 16134, 16133, 16132, -1, 16137, 16134, 16132, -1, 16138, 16134, 16137, -1, 16138, 16136, 16134, -1, 16139, 16140, 16136, -1, 16139, 14609, 16140, -1, 16139, 14610, 14609, -1, 16139, 16136, 16138, -1, 16119, 16117, 16141, -1, 16122, 16131, 16119, -1, 16127, 16126, 16142, -1, 16143, 14617, 16131, -1, 16143, 16131, 16122, -1, 16143, 16122, 16127, -1, 16144, 16145, 16146, -1, 16144, 16142, 16145, -1, 16144, 16127, 16142, -1, 16144, 16143, 16127, -1, 16147, 14617, 16143, -1, 16148, 16146, 14619, -1, 16148, 14619, 14617, -1, 16148, 16144, 16146, -1, 16148, 16143, 16144, -1, 16148, 14617, 16147, -1, 16148, 16147, 16143, -1, 16149, 16137, 16132, -1, 16149, 16132, 11730, -1, 16149, 16117, 16138, -1, 16149, 16138, 16137, -1, 16150, 16149, 11730, -1, 16150, 16117, 16149, -1, 16151, 16141, 16117, -1, 16151, 16150, 11730, -1, 16151, 16117, 16150, -1, 16121, 11730, 11742, -1, 16121, 16119, 16141, -1, 16121, 16141, 16151, -1, 16121, 16151, 11730, -1, 16123, 16121, 11742, -1, 16116, 16138, 16117, -1, 16116, 16139, 16138, -1, 16116, 14610, 16139, -1, 16152, 8683, 16153, -1, 16154, 16155, 16156, -1, 16154, 16152, 16155, -1, 16157, 16158, 16159, -1, 16157, 16160, 16156, -1, 16157, 16156, 16158, -1, 16161, 16159, 11738, -1, 16161, 16157, 16159, -1, 16162, 11737, 16163, -1, 16162, 11738, 11737, -1, 16162, 16163, 16164, -1, 16162, 16161, 11738, -1, 16165, 16161, 16162, -1, 16165, 16157, 16161, -1, 16165, 16162, 16164, -1, 16165, 16164, 16160, -1, 16165, 16160, 16157, -1, 16166, 8683, 16152, -1, 16166, 16152, 16154, -1, 16167, 8692, 8683, -1, 16167, 16166, 16154, -1, 16167, 16168, 8692, -1, 16167, 16156, 16168, -1, 16167, 16154, 16156, -1, 16167, 8683, 16166, -1, 16169, 16170, 11755, -1, 16169, 11755, 11746, -1, 16171, 16172, 16170, -1, 16171, 16173, 16172, -1, 16171, 16170, 16169, -1, 16174, 16171, 16169, -1, 16175, 16171, 16174, -1, 16175, 16173, 16171, -1, 16176, 8683, 8685, -1, 16176, 16177, 16173, -1, 16176, 8685, 16177, -1, 16176, 16173, 16175, -1, 16156, 16155, 16178, -1, 16160, 16168, 16156, -1, 16164, 16163, 16179, -1, 16180, 8692, 16168, -1, 16180, 16168, 16160, -1, 16180, 16160, 16164, -1, 16181, 16182, 16183, -1, 16181, 16179, 16182, -1, 16181, 16164, 16179, -1, 16181, 16180, 16164, -1, 16184, 8692, 16180, -1, 16185, 16183, 8696, -1, 16185, 8696, 8692, -1, 16185, 16181, 16183, -1, 16185, 16180, 16181, -1, 16185, 8692, 16184, -1, 16185, 16184, 16180, -1, 16186, 16174, 16169, -1, 16186, 16155, 16175, -1, 16186, 16169, 11746, -1, 16186, 16175, 16174, -1, 16187, 16155, 16186, -1, 16187, 16186, 11746, -1, 16188, 16178, 16155, -1, 16188, 16155, 16187, -1, 16188, 16187, 11746, -1, 16158, 11746, 11738, -1, 16158, 16156, 16178, -1, 16158, 16178, 16188, -1, 16158, 16188, 11746, -1, 16159, 16158, 11738, -1, 16153, 16175, 16155, -1, 16153, 16176, 16175, -1, 16153, 8683, 16176, -1, 16152, 16153, 16155, -1, 16189, 16190, 16191, -1, 16189, 8709, 16190, -1, 16192, 16191, 16193, -1, 16192, 16189, 16191, -1, 16194, 16195, 16196, -1, 16194, 16197, 16193, -1, 16194, 16193, 16195, -1, 16198, 16196, 11768, -1, 16198, 16194, 16196, -1, 16199, 11767, 16200, -1, 16199, 11768, 11767, -1, 16199, 16200, 16201, -1, 16199, 16198, 11768, -1, 16202, 16198, 16199, -1, 16202, 16194, 16198, -1, 16202, 16199, 16201, -1, 16202, 16201, 16197, -1, 16202, 16197, 16194, -1, 16203, 8709, 16189, -1, 16203, 16189, 16192, -1, 16204, 8716, 8709, -1, 16204, 16203, 16192, -1, 16204, 16205, 8716, -1, 16204, 16193, 16205, -1, 16204, 16192, 16193, -1, 16204, 8709, 16203, -1, 16206, 16207, 11784, -1, 16206, 11784, 11774, -1, 16208, 16209, 16207, -1, 16208, 16210, 16209, -1, 16208, 16207, 16206, -1, 16211, 16208, 16206, -1, 16212, 16208, 16211, -1, 16212, 16210, 16208, -1, 16213, 8709, 8708, -1, 16213, 16214, 16210, -1, 16213, 8708, 16214, -1, 16213, 16210, 16212, -1, 16193, 16191, 16215, -1, 16197, 16205, 16193, -1, 16201, 16200, 16216, -1, 16217, 8716, 16205, -1, 16217, 16205, 16197, -1, 16217, 16197, 16201, -1, 16218, 16219, 16220, -1, 16218, 16216, 16219, -1, 16218, 16201, 16216, -1, 16218, 16217, 16201, -1, 16221, 8716, 16217, -1, 16222, 16220, 8718, -1, 16222, 8718, 8716, -1, 16222, 16218, 16220, -1, 16222, 16217, 16218, -1, 16222, 8716, 16221, -1, 16222, 16221, 16217, -1, 16223, 16211, 16206, -1, 16223, 16191, 16212, -1, 16223, 16206, 11774, -1, 16223, 16212, 16211, -1, 16224, 16191, 16223, -1, 16224, 16223, 11774, -1, 16225, 16215, 16191, -1, 16225, 16191, 16224, -1, 16225, 16224, 11774, -1, 16195, 11774, 11768, -1, 16195, 16193, 16215, -1, 16195, 16215, 16225, -1, 16195, 16225, 11774, -1, 16196, 16195, 11768, -1, 16190, 16212, 16191, -1, 16190, 16213, 16212, -1, 16190, 8709, 16213, -1, 16226, 16227, 16228, -1, 16226, 8849, 16227, -1, 16229, 16228, 16230, -1, 16229, 16226, 16228, -1, 16231, 16232, 16230, -1, 16231, 16233, 16234, -1, 16231, 16230, 16233, -1, 16235, 16234, 11678, -1, 16235, 16231, 16234, -1, 16236, 11677, 16237, -1, 16236, 11678, 11677, -1, 16236, 16237, 16238, -1, 16236, 16235, 11678, -1, 16239, 16235, 16236, -1, 16239, 16231, 16235, -1, 16239, 16236, 16238, -1, 16239, 16238, 16232, -1, 16239, 16232, 16231, -1, 16240, 8849, 16226, -1, 16240, 16226, 16229, -1, 16241, 8858, 8849, -1, 16241, 16240, 16229, -1, 16241, 16242, 8858, -1, 16241, 16230, 16242, -1, 16241, 16229, 16230, -1, 16241, 8849, 16240, -1, 16243, 16244, 11697, -1, 16243, 11697, 11687, -1, 16245, 16246, 16244, -1, 16245, 16247, 16246, -1, 16245, 16244, 16243, -1, 16248, 16245, 16243, -1, 16249, 16245, 16248, -1, 16249, 16247, 16245, -1, 16250, 8849, 8851, -1, 16250, 16251, 16247, -1, 16250, 8851, 16251, -1, 16250, 16247, 16249, -1, 16230, 16228, 16252, -1, 16232, 16242, 16230, -1, 16238, 16237, 16253, -1, 16254, 8858, 16242, -1, 16254, 16242, 16232, -1, 16254, 16232, 16238, -1, 16255, 16256, 16257, -1, 16255, 16253, 16256, -1, 16255, 16238, 16253, -1, 16255, 16254, 16238, -1, 16258, 8858, 16254, -1, 16259, 16257, 8862, -1, 16259, 8862, 8858, -1, 16259, 16255, 16257, -1, 16259, 16254, 16255, -1, 16259, 8858, 16258, -1, 16259, 16258, 16254, -1, 16260, 16248, 16243, -1, 16260, 16228, 16249, -1, 16260, 16243, 11687, -1, 16260, 16249, 16248, -1, 16261, 16228, 16260, -1, 16261, 16260, 11687, -1, 16262, 16252, 16228, -1, 16262, 16228, 16261, -1, 16262, 16261, 11687, -1, 16233, 11687, 11678, -1, 16233, 16252, 16262, -1, 16233, 16230, 16252, -1, 16233, 16262, 11687, -1, 16234, 16233, 11678, -1, 16227, 16249, 16228, -1, 16227, 16250, 16249, -1, 16227, 8849, 16250, -1, 16263, 9029, 16264, -1, 16265, 16266, 16267, -1, 16265, 16263, 16266, -1, 16268, 16267, 16269, -1, 16268, 16270, 16267, -1, 16268, 16269, 16271, -1, 16272, 16271, 11707, -1, 16272, 16268, 16271, -1, 16273, 16272, 11707, -1, 16273, 11707, 11706, -1, 16273, 11706, 16274, -1, 16273, 16274, 16275, -1, 16276, 16268, 16272, -1, 16276, 16273, 16275, -1, 16276, 16272, 16273, -1, 16276, 16275, 16270, -1, 16276, 16270, 16268, -1, 16277, 9029, 16263, -1, 16277, 16263, 16265, -1, 16278, 16277, 16265, -1, 16278, 9036, 9029, -1, 16278, 16279, 9036, -1, 16278, 16267, 16279, -1, 16278, 16265, 16267, -1, 16278, 9029, 16277, -1, 16280, 16281, 11723, -1, 16280, 11723, 11720, -1, 16282, 16283, 16281, -1, 16282, 16284, 16283, -1, 16282, 16281, 16280, -1, 16285, 16282, 16280, -1, 16286, 16282, 16285, -1, 16286, 16284, 16282, -1, 16287, 16288, 16284, -1, 16287, 9028, 16288, -1, 16287, 9029, 9028, -1, 16287, 16284, 16286, -1, 16267, 16266, 16289, -1, 16270, 16279, 16267, -1, 16275, 16274, 16290, -1, 16291, 9036, 16279, -1, 16291, 16279, 16270, -1, 16291, 16270, 16275, -1, 16292, 16293, 16294, -1, 16292, 16290, 16293, -1, 16292, 16275, 16290, -1, 16292, 16291, 16275, -1, 16295, 9036, 16291, -1, 16296, 16294, 9038, -1, 16296, 9038, 9036, -1, 16296, 16292, 16294, -1, 16296, 16291, 16292, -1, 16296, 9036, 16295, -1, 16296, 16295, 16291, -1, 16297, 16285, 16280, -1, 16297, 16266, 16286, -1, 16297, 16280, 11720, -1, 16297, 16286, 16285, -1, 16298, 16266, 16297, -1, 16298, 16297, 11720, -1, 16299, 16289, 16266, -1, 16299, 16266, 16298, -1, 16299, 16298, 11720, -1, 16269, 11720, 11707, -1, 16269, 16267, 16289, -1, 16269, 16289, 16299, -1, 16269, 16299, 11720, -1, 16271, 16269, 11707, -1, 16264, 16286, 16266, -1, 16264, 16287, 16286, -1, 16264, 9029, 16287, -1, 16263, 16264, 16266, -1, 16300, 9073, 16301, -1, 16302, 16303, 16304, -1, 16302, 16300, 16303, -1, 16305, 16306, 16304, -1, 16305, 16307, 16308, -1, 16305, 16304, 16307, -1, 16309, 16308, 11795, -1, 16309, 16305, 16308, -1, 16310, 11794, 16311, -1, 16310, 11795, 11794, -1, 16310, 16311, 16312, -1, 16310, 16309, 11795, -1, 16313, 16309, 16310, -1, 16313, 16305, 16309, -1, 16313, 16310, 16312, -1, 16313, 16312, 16306, -1, 16313, 16306, 16305, -1, 16314, 9073, 16300, -1, 16314, 16300, 16302, -1, 16315, 9082, 9073, -1, 16315, 16314, 16302, -1, 16315, 16316, 9082, -1, 16315, 16304, 16316, -1, 16315, 16302, 16304, -1, 16315, 9073, 16314, -1, 16317, 16318, 11807, -1, 16317, 11807, 11802, -1, 16319, 16320, 16318, -1, 16319, 16321, 16320, -1, 16319, 16318, 16317, -1, 16322, 16319, 16317, -1, 16323, 16319, 16322, -1, 16323, 16321, 16319, -1, 16324, 9073, 9075, -1, 16324, 16325, 16321, -1, 16324, 9075, 16325, -1, 16324, 16321, 16323, -1, 16304, 16303, 16326, -1, 16306, 16316, 16304, -1, 16312, 16311, 16327, -1, 16328, 9082, 16316, -1, 16328, 16316, 16306, -1, 16328, 16306, 16312, -1, 16329, 16330, 16331, -1, 16329, 16327, 16330, -1, 16329, 16312, 16327, -1, 16329, 16328, 16312, -1, 16332, 9082, 16328, -1, 16333, 16331, 9086, -1, 16333, 9086, 9082, -1, 16333, 16329, 16331, -1, 16333, 16328, 16329, -1, 16333, 9082, 16332, -1, 16333, 16332, 16328, -1, 16334, 16322, 16317, -1, 16334, 16303, 16323, -1, 16334, 16317, 11802, -1, 16334, 16323, 16322, -1, 16335, 16303, 16334, -1, 16335, 16334, 11802, -1, 16336, 16326, 16303, -1, 16336, 16303, 16335, -1, 16336, 16335, 11802, -1, 16307, 11802, 11795, -1, 16307, 16326, 16336, -1, 16307, 16304, 16326, -1, 16307, 16336, 11802, -1, 16308, 16307, 11795, -1, 16301, 16323, 16303, -1, 16301, 16324, 16323, -1, 16301, 9073, 16324, -1, 16300, 16301, 16303, -1, 16337, 16338, 16339, -1, 16337, 11105, 16338, -1, 16340, 16339, 16341, -1, 16340, 16337, 16339, -1, 16342, 16343, 16341, -1, 16342, 16344, 16345, -1, 16342, 16341, 16344, -1, 16346, 16345, 11822, -1, 16346, 16342, 16345, -1, 16347, 11821, 16348, -1, 16347, 11822, 11821, -1, 16347, 16348, 16349, -1, 16347, 16346, 11822, -1, 16350, 16346, 16347, -1, 16350, 16342, 16346, -1, 16350, 16347, 16349, -1, 16350, 16349, 16343, -1, 16350, 16343, 16342, -1, 16351, 11105, 16337, -1, 16351, 16337, 16340, -1, 16352, 11112, 11105, -1, 16352, 16351, 16340, -1, 16352, 16353, 11112, -1, 16352, 16341, 16353, -1, 16352, 16340, 16341, -1, 16352, 11105, 16351, -1, 16354, 16355, 11835, -1, 16354, 11835, 11830, -1, 16356, 16357, 16355, -1, 16356, 16358, 16357, -1, 16356, 16355, 16354, -1, 16359, 16356, 16354, -1, 16360, 16356, 16359, -1, 16360, 16358, 16356, -1, 16361, 11105, 11104, -1, 16361, 16362, 16358, -1, 16361, 11104, 16362, -1, 16361, 16358, 16360, -1, 16341, 16339, 16363, -1, 16343, 16353, 16341, -1, 16349, 16348, 16364, -1, 16365, 11112, 16353, -1, 16365, 16353, 16343, -1, 16365, 16343, 16349, -1, 16366, 16367, 16368, -1, 16366, 16364, 16367, -1, 16366, 16349, 16364, -1, 16366, 16365, 16349, -1, 16369, 11112, 16365, -1, 16370, 16368, 11114, -1, 16370, 11114, 11112, -1, 16370, 16366, 16368, -1, 16370, 16365, 16366, -1, 16370, 11112, 16369, -1, 16370, 16369, 16365, -1, 16371, 16359, 16354, -1, 16371, 16339, 16360, -1, 16371, 16354, 11830, -1, 16371, 16360, 16359, -1, 16372, 16339, 16371, -1, 16372, 16371, 11830, -1, 16373, 16363, 16339, -1, 16373, 16339, 16372, -1, 16373, 16372, 11830, -1, 16344, 11830, 11822, -1, 16344, 16363, 16373, -1, 16344, 16341, 16363, -1, 16344, 16373, 11830, -1, 16345, 16344, 11822, -1, 16338, 16360, 16339, -1, 16338, 16361, 16360, -1, 16338, 11105, 16361, -1, 16374, 9247, 16375, -1, 16376, 16377, 16378, -1, 16376, 16374, 16377, -1, 16379, 16380, 16381, -1, 16379, 16382, 16378, -1, 16379, 16378, 16380, -1, 16383, 16381, 11914, -1, 16383, 16379, 16381, -1, 16384, 11913, 16385, -1, 16384, 11914, 11913, -1, 16384, 16385, 16386, -1, 16384, 16383, 11914, -1, 16387, 16383, 16384, -1, 16387, 16379, 16383, -1, 16387, 16384, 16386, -1, 16387, 16386, 16382, -1, 16387, 16382, 16379, -1, 16388, 9247, 16374, -1, 16388, 16374, 16376, -1, 16389, 9256, 9247, -1, 16389, 16388, 16376, -1, 16389, 16390, 9256, -1, 16389, 16378, 16390, -1, 16389, 16376, 16378, -1, 16389, 9247, 16388, -1, 16391, 16392, 11926, -1, 16391, 11926, 11920, -1, 16393, 16394, 16392, -1, 16393, 16395, 16394, -1, 16393, 16392, 16391, -1, 16396, 16393, 16391, -1, 16397, 16393, 16396, -1, 16397, 16395, 16393, -1, 16398, 9247, 9249, -1, 16398, 16399, 16395, -1, 16398, 9249, 16399, -1, 16398, 16395, 16397, -1, 16378, 16377, 16400, -1, 16382, 16390, 16378, -1, 16386, 16385, 16401, -1, 16402, 9256, 16390, -1, 16402, 16390, 16382, -1, 16402, 16382, 16386, -1, 16403, 16404, 16405, -1, 16403, 16401, 16404, -1, 16403, 16386, 16401, -1, 16403, 16402, 16386, -1, 16406, 9256, 16402, -1, 16407, 16405, 9260, -1, 16407, 9260, 9256, -1, 16407, 16403, 16405, -1, 16407, 16402, 16403, -1, 16407, 9256, 16406, -1, 16407, 16406, 16402, -1, 16408, 16396, 16391, -1, 16408, 16377, 16397, -1, 16408, 16391, 11920, -1, 16408, 16397, 16396, -1, 16409, 16377, 16408, -1, 16409, 16408, 11920, -1, 16410, 16400, 16377, -1, 16410, 16377, 16409, -1, 16410, 16409, 11920, -1, 16380, 11920, 11914, -1, 16380, 16378, 16400, -1, 16380, 16400, 16410, -1, 16380, 16410, 11920, -1, 16381, 16380, 11914, -1, 16375, 16397, 16377, -1, 16375, 16398, 16397, -1, 16375, 9247, 16398, -1, 16374, 16375, 16377, -1, 16411, 9273, 16412, -1, 16413, 16414, 16415, -1, 16413, 16411, 16414, -1, 16416, 16417, 16418, -1, 16416, 16419, 16415, -1, 16416, 16415, 16417, -1, 16420, 16418, 11935, -1, 16420, 16416, 16418, -1, 16421, 11934, 16422, -1, 16421, 11935, 11934, -1, 16421, 16422, 16423, -1, 16421, 16420, 11935, -1, 16424, 16420, 16421, -1, 16424, 16416, 16420, -1, 16424, 16421, 16423, -1, 16424, 16423, 16419, -1, 16424, 16419, 16416, -1, 16425, 9273, 16411, -1, 16425, 16411, 16413, -1, 16426, 9280, 9273, -1, 16426, 16425, 16413, -1, 16426, 16427, 9280, -1, 16426, 16415, 16427, -1, 16426, 16413, 16415, -1, 16426, 9273, 16425, -1, 16428, 16429, 11947, -1, 16428, 11947, 11941, -1, 16430, 16431, 16429, -1, 16430, 16432, 16431, -1, 16430, 16429, 16428, -1, 16433, 16430, 16428, -1, 16434, 16430, 16433, -1, 16434, 16432, 16430, -1, 16435, 9273, 9272, -1, 16435, 16436, 16432, -1, 16435, 9272, 16436, -1, 16435, 16432, 16434, -1, 16415, 16414, 16437, -1, 16419, 16427, 16415, -1, 16423, 16422, 16438, -1, 16439, 9280, 16427, -1, 16439, 16427, 16419, -1, 16439, 16419, 16423, -1, 16440, 16441, 16442, -1, 16440, 16438, 16441, -1, 16440, 16423, 16438, -1, 16440, 16439, 16423, -1, 16443, 9280, 16439, -1, 16444, 16442, 9282, -1, 16444, 9282, 9280, -1, 16444, 16440, 16442, -1, 16444, 16439, 16440, -1, 16444, 9280, 16443, -1, 16444, 16443, 16439, -1, 16445, 16433, 16428, -1, 16445, 16414, 16434, -1, 16445, 16428, 11941, -1, 16445, 16434, 16433, -1, 16446, 16414, 16445, -1, 16446, 16445, 11941, -1, 16447, 16437, 16414, -1, 16447, 16414, 16446, -1, 16447, 16446, 11941, -1, 16417, 11941, 11935, -1, 16417, 16415, 16437, -1, 16417, 16437, 16447, -1, 16417, 16447, 11941, -1, 16418, 16417, 11935, -1, 16412, 16434, 16414, -1, 16412, 16435, 16434, -1, 16412, 9273, 16435, -1, 16411, 16412, 16414, -1, 16448, 9379, 16449, -1, 16450, 16451, 16452, -1, 16450, 16448, 16451, -1, 16453, 16454, 16452, -1, 16453, 16455, 16456, -1, 16453, 16452, 16455, -1, 16457, 16456, 11956, -1, 16457, 16453, 16456, -1, 16458, 11955, 16459, -1, 16458, 11956, 11955, -1, 16458, 16459, 16460, -1, 16458, 16457, 11956, -1, 16461, 16457, 16458, -1, 16461, 16453, 16457, -1, 16461, 16458, 16460, -1, 16461, 16460, 16454, -1, 16461, 16454, 16453, -1, 16462, 9379, 16448, -1, 16462, 16448, 16450, -1, 16463, 9388, 9379, -1, 16463, 16462, 16450, -1, 16463, 16464, 9388, -1, 16463, 16452, 16464, -1, 16463, 16450, 16452, -1, 16463, 9379, 16462, -1, 16465, 16466, 11966, -1, 16465, 11966, 11963, -1, 16467, 16468, 16466, -1, 16467, 16469, 16468, -1, 16467, 16466, 16465, -1, 16470, 16467, 16465, -1, 16471, 16467, 16470, -1, 16471, 16469, 16467, -1, 16472, 9379, 9381, -1, 16472, 16473, 16469, -1, 16472, 9381, 16473, -1, 16472, 16469, 16471, -1, 16452, 16451, 16474, -1, 16454, 16464, 16452, -1, 16460, 16459, 16475, -1, 16476, 9388, 16464, -1, 16476, 16464, 16454, -1, 16476, 16454, 16460, -1, 16477, 16478, 16479, -1, 16477, 16475, 16478, -1, 16477, 16460, 16475, -1, 16477, 16476, 16460, -1, 16480, 9388, 16476, -1, 16481, 16479, 9392, -1, 16481, 9392, 9388, -1, 16481, 16477, 16479, -1, 16481, 16476, 16477, -1, 16481, 9388, 16480, -1, 16481, 16480, 16476, -1, 16482, 16470, 16465, -1, 16482, 16451, 16471, -1, 16482, 16465, 11963, -1, 16482, 16471, 16470, -1, 16483, 16451, 16482, -1, 16483, 16482, 11963, -1, 16484, 16474, 16451, -1, 16484, 16451, 16483, -1, 16484, 16483, 11963, -1, 16455, 11963, 11956, -1, 16455, 16474, 16484, -1, 16455, 16452, 16474, -1, 16455, 16484, 11963, -1, 16456, 16455, 11956, -1, 16449, 16471, 16451, -1, 16449, 16472, 16471, -1, 16449, 9379, 16472, -1, 16448, 16449, 16451, -1, 16485, 16486, 16487, -1, 16485, 9521, 16486, -1, 16488, 16487, 16489, -1, 16488, 16485, 16487, -1, 16490, 16491, 16489, -1, 16490, 16492, 16493, -1, 16490, 16489, 16492, -1, 16494, 16493, 11980, -1, 16494, 16490, 16493, -1, 16495, 11979, 16496, -1, 16495, 11980, 11979, -1, 16495, 16496, 16497, -1, 16495, 16494, 11980, -1, 16498, 16494, 16495, -1, 16498, 16490, 16494, -1, 16498, 16495, 16497, -1, 16498, 16497, 16491, -1, 16498, 16491, 16490, -1, 16499, 9521, 16485, -1, 16499, 16485, 16488, -1, 16500, 9528, 9521, -1, 16500, 16499, 16488, -1, 16500, 16501, 9528, -1, 16500, 16489, 16501, -1, 16500, 16488, 16489, -1, 16500, 9521, 16499, -1, 16502, 16503, 11989, -1, 16502, 11989, 11985, -1, 16504, 16505, 16503, -1, 16504, 16506, 16505, -1, 16504, 16503, 16502, -1, 16507, 16504, 16502, -1, 16508, 16504, 16507, -1, 16508, 16506, 16504, -1, 16509, 9521, 9520, -1, 16509, 16510, 16506, -1, 16509, 9520, 16510, -1, 16509, 16506, 16508, -1, 16489, 16487, 16511, -1, 16491, 16501, 16489, -1, 16497, 16496, 16512, -1, 16513, 9528, 16501, -1, 16513, 16501, 16491, -1, 16513, 16491, 16497, -1, 16514, 16515, 16516, -1, 16514, 16512, 16515, -1, 16514, 16497, 16512, -1, 16514, 16513, 16497, -1, 16517, 9528, 16513, -1, 16518, 16516, 9530, -1, 16518, 9530, 9528, -1, 16518, 16514, 16516, -1, 16518, 16513, 16514, -1, 16518, 9528, 16517, -1, 16518, 16517, 16513, -1, 16519, 16507, 16502, -1, 16519, 16487, 16508, -1, 16519, 16502, 11985, -1, 16519, 16508, 16507, -1, 16520, 16487, 16519, -1, 16520, 16519, 11985, -1, 16521, 16511, 16487, -1, 16521, 16487, 16520, -1, 16521, 16520, 11985, -1, 16492, 11985, 11980, -1, 16492, 16511, 16521, -1, 16492, 16489, 16511, -1, 16492, 16521, 11985, -1, 16493, 16492, 11980, -1, 16486, 16508, 16487, -1, 16486, 16509, 16508, -1, 16486, 9521, 16509, -1, 16522, 16523, 16524, -1, 16522, 9603, 16523, -1, 16525, 16524, 16526, -1, 16525, 16522, 16524, -1, 16527, 16528, 16526, -1, 16527, 16529, 16530, -1, 16527, 16526, 16529, -1, 16531, 16530, 12040, -1, 16531, 16527, 16530, -1, 16532, 12039, 16533, -1, 16532, 12040, 12039, -1, 16532, 16533, 16534, -1, 16532, 16531, 12040, -1, 16535, 16531, 16532, -1, 16535, 16527, 16531, -1, 16535, 16532, 16534, -1, 16535, 16534, 16528, -1, 16535, 16528, 16527, -1, 16536, 9603, 16522, -1, 16536, 16522, 16525, -1, 16537, 9612, 9603, -1, 16537, 16536, 16525, -1, 16537, 16538, 9612, -1, 16537, 16526, 16538, -1, 16537, 16525, 16526, -1, 16537, 9603, 16536, -1, 16539, 16540, 12046, -1, 16539, 12046, 12045, -1, 16541, 16542, 16540, -1, 16541, 16543, 16542, -1, 16541, 16540, 16539, -1, 16544, 16541, 16539, -1, 16545, 16541, 16544, -1, 16545, 16543, 16541, -1, 16546, 9603, 9605, -1, 16546, 16547, 16543, -1, 16546, 9605, 16547, -1, 16546, 16543, 16545, -1, 16526, 16524, 16548, -1, 16528, 16538, 16526, -1, 16534, 16533, 16549, -1, 16550, 9612, 16538, -1, 16550, 16538, 16528, -1, 16550, 16528, 16534, -1, 16551, 16552, 16553, -1, 16551, 16549, 16552, -1, 16551, 16534, 16549, -1, 16551, 16550, 16534, -1, 16554, 9612, 16550, -1, 16555, 16553, 9616, -1, 16555, 9616, 9612, -1, 16555, 16551, 16553, -1, 16555, 16550, 16551, -1, 16555, 9612, 16554, -1, 16555, 16554, 16550, -1, 16556, 16544, 16539, -1, 16556, 16524, 16545, -1, 16556, 16539, 12045, -1, 16556, 16545, 16544, -1, 16557, 16524, 16556, -1, 16557, 16556, 12045, -1, 16558, 16548, 16524, -1, 16558, 16524, 16557, -1, 16558, 16557, 12045, -1, 16529, 12045, 12040, -1, 16529, 16548, 16558, -1, 16529, 16526, 16548, -1, 16529, 16558, 12045, -1, 16530, 16529, 12040, -1, 16523, 16545, 16524, -1, 16523, 16546, 16545, -1, 16523, 9603, 16546, -1, 16559, 9769, 16560, -1, 16561, 16562, 16563, -1, 16561, 16559, 16562, -1, 16564, 16563, 16565, -1, 16564, 16566, 16563, -1, 16564, 16565, 16567, -1, 16568, 16567, 12054, -1, 16568, 16564, 16567, -1, 16569, 16568, 12054, -1, 16569, 12054, 12053, -1, 16569, 12053, 16570, -1, 16569, 16570, 16571, -1, 16572, 16564, 16568, -1, 16572, 16569, 16571, -1, 16572, 16568, 16569, -1, 16572, 16571, 16566, -1, 16572, 16566, 16564, -1, 16573, 9769, 16559, -1, 16573, 16559, 16561, -1, 16574, 16573, 16561, -1, 16574, 9776, 9769, -1, 16574, 16575, 9776, -1, 16574, 16563, 16575, -1, 16574, 16561, 16563, -1, 16574, 9769, 16573, -1, 16576, 16577, 11670, -1, 16576, 11670, 11669, -1, 16578, 16579, 16577, -1, 16578, 16580, 16579, -1, 16578, 16577, 16576, -1, 16581, 16578, 16576, -1, 16582, 16578, 16581, -1, 16582, 16580, 16578, -1, 16583, 16584, 16580, -1, 16583, 9768, 16584, -1, 16583, 9769, 9768, -1, 16583, 16580, 16582, -1, 16563, 16562, 16585, -1, 16566, 16575, 16563, -1, 16571, 16570, 16586, -1, 16587, 9776, 16575, -1, 16587, 16575, 16566, -1, 16587, 16566, 16571, -1, 16588, 16589, 16590, -1, 16588, 16586, 16589, -1, 16588, 16571, 16586, -1, 16588, 16587, 16571, -1, 16591, 9776, 16587, -1, 16592, 16590, 9778, -1, 16592, 9778, 9776, -1, 16592, 16588, 16590, -1, 16592, 16587, 16588, -1, 16592, 9776, 16591, -1, 16592, 16591, 16587, -1, 16593, 16581, 16576, -1, 16593, 16562, 16582, -1, 16593, 16576, 11669, -1, 16593, 16582, 16581, -1, 16594, 16562, 16593, -1, 16594, 16593, 11669, -1, 16595, 16585, 16562, -1, 16595, 16562, 16594, -1, 16595, 16594, 11669, -1, 16565, 11669, 12054, -1, 16565, 16563, 16585, -1, 16565, 16585, 16595, -1, 16565, 16595, 11669, -1, 16567, 16565, 12054, -1, 16560, 16582, 16562, -1, 16560, 16583, 16582, -1, 16560, 9769, 16583, -1, 16559, 16560, 16562, -1, 16596, 16597, 16598, -1, 16596, 9919, 16597, -1, 16599, 16598, 16600, -1, 16599, 16596, 16598, -1, 16601, 16602, 16600, -1, 16601, 16603, 16604, -1, 16601, 16600, 16603, -1, 16605, 16604, 11998, -1, 16605, 16601, 16604, -1, 16606, 11997, 16607, -1, 16606, 11998, 11997, -1, 16606, 16607, 16608, -1, 16606, 16605, 11998, -1, 16609, 16605, 16606, -1, 16609, 16601, 16605, -1, 16609, 16606, 16608, -1, 16609, 16608, 16602, -1, 16609, 16602, 16601, -1, 16610, 9919, 16596, -1, 16610, 16596, 16599, -1, 16611, 9928, 9919, -1, 16611, 16610, 16599, -1, 16611, 16612, 9928, -1, 16611, 16600, 16612, -1, 16611, 16599, 16600, -1, 16611, 9919, 16610, -1, 16613, 16614, 12010, -1, 16613, 12010, 12002, -1, 16615, 16616, 16614, -1, 16615, 16617, 16616, -1, 16615, 16614, 16613, -1, 16618, 16615, 16613, -1, 16619, 16615, 16618, -1, 16619, 16617, 16615, -1, 16620, 9919, 9921, -1, 16620, 16621, 16617, -1, 16620, 9921, 16621, -1, 16620, 16617, 16619, -1, 16600, 16598, 16622, -1, 16602, 16612, 16600, -1, 16608, 16607, 16623, -1, 16624, 9928, 16612, -1, 16624, 16612, 16602, -1, 16624, 16602, 16608, -1, 16625, 16626, 16627, -1, 16625, 16623, 16626, -1, 16625, 16608, 16623, -1, 16625, 16624, 16608, -1, 16628, 9928, 16624, -1, 16629, 16627, 9932, -1, 16629, 9932, 9928, -1, 16629, 16625, 16627, -1, 16629, 16624, 16625, -1, 16629, 9928, 16628, -1, 16629, 16628, 16624, -1, 16630, 16618, 16613, -1, 16630, 16598, 16619, -1, 16630, 16613, 12002, -1, 16630, 16619, 16618, -1, 16631, 16598, 16630, -1, 16631, 16630, 12002, -1, 16632, 16622, 16598, -1, 16632, 16598, 16631, -1, 16632, 16631, 12002, -1, 16603, 12002, 11998, -1, 16603, 16622, 16632, -1, 16603, 16600, 16622, -1, 16603, 16632, 12002, -1, 16604, 16603, 11998, -1, 16597, 16619, 16598, -1, 16597, 16620, 16619, -1, 16597, 9919, 16620, -1, 16633, 9969, 16634, -1, 16635, 16636, 16637, -1, 16635, 16633, 16636, -1, 16638, 16637, 16639, -1, 16638, 16640, 16637, -1, 16638, 16639, 16641, -1, 16642, 16641, 12025, -1, 16642, 16638, 16641, -1, 16643, 16642, 12025, -1, 16643, 12025, 12024, -1, 16643, 12024, 16644, -1, 16643, 16644, 16645, -1, 16646, 16638, 16642, -1, 16646, 16643, 16645, -1, 16646, 16642, 16643, -1, 16646, 16645, 16640, -1, 16646, 16640, 16638, -1, 16647, 9969, 16633, -1, 16647, 16633, 16635, -1, 16648, 16647, 16635, -1, 16648, 9976, 9969, -1, 16648, 16649, 9976, -1, 16648, 16637, 16649, -1, 16648, 16635, 16637, -1, 16648, 9969, 16647, -1, 16650, 16651, 12032, -1, 16650, 12032, 12031, -1, 16652, 16653, 16651, -1, 16652, 16654, 16653, -1, 16652, 16651, 16650, -1, 16655, 16652, 16650, -1, 16656, 16652, 16655, -1, 16656, 16654, 16652, -1, 16657, 16658, 16654, -1, 16657, 9968, 16658, -1, 16657, 9969, 9968, -1, 16657, 16654, 16656, -1, 16637, 16636, 16659, -1, 16640, 16649, 16637, -1, 16645, 16644, 16660, -1, 16661, 9976, 16649, -1, 16661, 16649, 16640, -1, 16661, 16640, 16645, -1, 16662, 16663, 16664, -1, 16662, 16660, 16663, -1, 16662, 16645, 16660, -1, 16662, 16661, 16645, -1, 16665, 9976, 16661, -1, 16666, 16664, 9978, -1, 16666, 9978, 9976, -1, 16666, 16662, 16664, -1, 16666, 16661, 16662, -1, 16666, 9976, 16665, -1, 16666, 16665, 16661, -1, 16667, 16655, 16650, -1, 16667, 16636, 16656, -1, 16667, 16650, 12031, -1, 16667, 16656, 16655, -1, 16668, 16636, 16667, -1, 16668, 16667, 12031, -1, 16669, 16659, 16636, -1, 16669, 16636, 16668, -1, 16669, 16668, 12031, -1, 16639, 12031, 12025, -1, 16639, 16637, 16659, -1, 16639, 16659, 16669, -1, 16639, 16669, 12031, -1, 16641, 16639, 12025, -1, 16634, 16656, 16636, -1, 16634, 16657, 16656, -1, 16634, 9969, 16657, -1, 16633, 16634, 16636, -1, 16670, 16671, 16672, -1, 16670, 14816, 16671, -1, 16673, 16672, 16674, -1, 16673, 16670, 16672, -1, 16675, 16676, 16674, -1, 16675, 16677, 16678, -1, 16675, 16674, 16677, -1, 16679, 16678, 11711, -1, 16679, 16675, 16678, -1, 16680, 11713, 16681, -1, 16680, 11711, 11713, -1, 16680, 16681, 16682, -1, 16680, 16679, 11711, -1, 16683, 16679, 16680, -1, 16683, 16675, 16679, -1, 16683, 16680, 16682, -1, 16683, 16682, 16676, -1, 16683, 16676, 16675, -1, 16684, 14816, 16670, -1, 16684, 16670, 16673, -1, 16685, 14825, 14816, -1, 16685, 16684, 16673, -1, 16685, 16686, 14825, -1, 16685, 16674, 16686, -1, 16685, 16673, 16674, -1, 16685, 14816, 16684, -1, 16687, 16688, 11725, -1, 16687, 11725, 11714, -1, 16689, 16690, 16688, -1, 16689, 16691, 16690, -1, 16689, 16688, 16687, -1, 16692, 16689, 16687, -1, 16693, 16689, 16692, -1, 16693, 16691, 16689, -1, 16694, 14816, 14818, -1, 16694, 16695, 16691, -1, 16694, 14818, 16695, -1, 16694, 16691, 16693, -1, 16674, 16672, 16696, -1, 16676, 16686, 16674, -1, 16682, 16681, 16697, -1, 16698, 14825, 16686, -1, 16698, 16686, 16676, -1, 16698, 16676, 16682, -1, 16699, 16700, 16701, -1, 16699, 16697, 16700, -1, 16699, 16682, 16697, -1, 16699, 16698, 16682, -1, 16702, 14825, 16698, -1, 16703, 16701, 14829, -1, 16703, 14829, 14825, -1, 16703, 16699, 16701, -1, 16703, 16698, 16699, -1, 16703, 14825, 16702, -1, 16703, 16702, 16698, -1, 16704, 16692, 16687, -1, 16704, 16672, 16693, -1, 16704, 16687, 11714, -1, 16704, 16693, 16692, -1, 16705, 16672, 16704, -1, 16705, 16704, 11714, -1, 16706, 16696, 16672, -1, 16706, 16672, 16705, -1, 16706, 16705, 11714, -1, 16677, 11714, 11711, -1, 16677, 16696, 16706, -1, 16677, 16674, 16696, -1, 16677, 16706, 11714, -1, 16678, 16677, 11711, -1, 16671, 16693, 16672, -1, 16671, 16694, 16693, -1, 16671, 14816, 16694, -1, 16707, 14842, 16708, -1, 16709, 16710, 16711, -1, 16709, 16707, 16710, -1, 16712, 16713, 16711, -1, 16712, 16714, 16715, -1, 16712, 16711, 16714, -1, 16716, 16715, 11732, -1, 16716, 16712, 16715, -1, 16717, 11734, 16718, -1, 16717, 11732, 11734, -1, 16717, 16718, 16719, -1, 16717, 16716, 11732, -1, 16720, 16716, 16717, -1, 16720, 16712, 16716, -1, 16720, 16717, 16719, -1, 16720, 16719, 16713, -1, 16720, 16713, 16712, -1, 16721, 14842, 16707, -1, 16721, 16707, 16709, -1, 16722, 14849, 14842, -1, 16722, 16721, 16709, -1, 16722, 16723, 14849, -1, 16722, 16711, 16723, -1, 16722, 16709, 16711, -1, 16722, 14842, 16721, -1, 16724, 16725, 11747, -1, 16724, 11747, 11735, -1, 16726, 16727, 16725, -1, 16726, 16728, 16727, -1, 16726, 16725, 16724, -1, 16729, 16726, 16724, -1, 16730, 16726, 16729, -1, 16730, 16728, 16726, -1, 16731, 14842, 14841, -1, 16731, 16732, 16728, -1, 16731, 14841, 16732, -1, 16731, 16728, 16730, -1, 16711, 16710, 16733, -1, 16713, 16723, 16711, -1, 16719, 16718, 16734, -1, 16735, 14849, 16723, -1, 16735, 16723, 16713, -1, 16735, 16713, 16719, -1, 16736, 16737, 16738, -1, 16736, 16734, 16737, -1, 16736, 16719, 16734, -1, 16736, 16735, 16719, -1, 16739, 14849, 16735, -1, 16740, 16738, 14851, -1, 16740, 14851, 14849, -1, 16740, 16736, 16738, -1, 16740, 16735, 16736, -1, 16740, 14849, 16739, -1, 16740, 16739, 16735, -1, 16741, 16729, 16724, -1, 16741, 16710, 16730, -1, 16741, 16724, 11735, -1, 16741, 16730, 16729, -1, 16742, 16710, 16741, -1, 16742, 16741, 11735, -1, 16743, 16733, 16710, -1, 16743, 16710, 16742, -1, 16743, 16742, 11735, -1, 16714, 11735, 11732, -1, 16714, 16733, 16743, -1, 16714, 16711, 16733, -1, 16714, 16743, 11735, -1, 16715, 16714, 11732, -1, 16708, 16730, 16710, -1, 16708, 16731, 16730, -1, 16708, 14842, 16731, -1, 16707, 16708, 16710, -1, 16744, 14852, 16745, -1, 16746, 16747, 16748, -1, 16746, 16744, 16747, -1, 16749, 16750, 16751, -1, 16749, 16752, 16748, -1, 16749, 16748, 16750, -1, 16753, 16751, 11694, -1, 16753, 16749, 16751, -1, 16754, 11696, 16755, -1, 16754, 11694, 11696, -1, 16754, 16755, 16756, -1, 16754, 16753, 11694, -1, 16757, 16753, 16754, -1, 16757, 16749, 16753, -1, 16757, 16754, 16756, -1, 16757, 16756, 16752, -1, 16757, 16752, 16749, -1, 16758, 14852, 16744, -1, 16758, 16744, 16746, -1, 16759, 14861, 14852, -1, 16759, 16758, 16746, -1, 16759, 16760, 14861, -1, 16759, 16748, 16760, -1, 16759, 16746, 16748, -1, 16759, 14852, 16758, -1, 16761, 16762, 11681, -1, 16761, 11681, 11683, -1, 16763, 16764, 16762, -1, 16763, 16765, 16764, -1, 16763, 16762, 16761, -1, 16766, 16763, 16761, -1, 16767, 16763, 16766, -1, 16767, 16765, 16763, -1, 16768, 14852, 14854, -1, 16768, 16769, 16765, -1, 16768, 14854, 16769, -1, 16768, 16765, 16767, -1, 16748, 16747, 16770, -1, 16752, 16760, 16748, -1, 16756, 16755, 16771, -1, 16772, 14861, 16760, -1, 16772, 16760, 16752, -1, 16772, 16752, 16756, -1, 16773, 16774, 16775, -1, 16773, 16771, 16774, -1, 16773, 16756, 16771, -1, 16773, 16772, 16756, -1, 16776, 14861, 16772, -1, 16777, 16775, 14865, -1, 16777, 14865, 14861, -1, 16777, 16773, 16775, -1, 16777, 16772, 16773, -1, 16777, 14861, 16776, -1, 16777, 16776, 16772, -1, 16778, 16766, 16761, -1, 16778, 16747, 16767, -1, 16778, 16761, 11683, -1, 16778, 16767, 16766, -1, 16779, 16747, 16778, -1, 16779, 16778, 11683, -1, 16780, 16770, 16747, -1, 16780, 16747, 16779, -1, 16780, 16779, 11683, -1, 16750, 11683, 11694, -1, 16750, 16748, 16770, -1, 16750, 16770, 16780, -1, 16750, 16780, 11683, -1, 16751, 16750, 11694, -1, 16745, 16767, 16747, -1, 16745, 16768, 16767, -1, 16745, 14852, 16768, -1, 16744, 16745, 16747, -1, 16781, 16782, 16783, -1, 16781, 14878, 16782, -1, 16784, 16783, 16785, -1, 16784, 16781, 16783, -1, 16786, 16785, 16787, -1, 16786, 16788, 16785, -1, 16786, 16787, 16789, -1, 16790, 16789, 11688, -1, 16790, 16786, 16789, -1, 16791, 16790, 11688, -1, 16791, 11688, 11690, -1, 16791, 11690, 16792, -1, 16791, 16792, 16793, -1, 16794, 16786, 16790, -1, 16794, 16791, 16793, -1, 16794, 16790, 16791, -1, 16794, 16793, 16788, -1, 16794, 16788, 16786, -1, 16795, 14878, 16781, -1, 16795, 16781, 16784, -1, 16796, 16795, 16784, -1, 16796, 14885, 14878, -1, 16796, 16797, 14885, -1, 16796, 16785, 16797, -1, 16796, 16784, 16785, -1, 16796, 14878, 16795, -1, 16798, 16799, 11699, -1, 16798, 11699, 11691, -1, 16800, 16801, 16799, -1, 16800, 16802, 16801, -1, 16800, 16799, 16798, -1, 16803, 16800, 16798, -1, 16804, 16800, 16803, -1, 16804, 16802, 16800, -1, 16805, 16806, 16802, -1, 16805, 14877, 16806, -1, 16805, 14878, 14877, -1, 16805, 16802, 16804, -1, 16785, 16783, 16807, -1, 16788, 16797, 16785, -1, 16793, 16792, 16808, -1, 16809, 14885, 16797, -1, 16809, 16797, 16788, -1, 16809, 16788, 16793, -1, 16810, 16811, 16812, -1, 16810, 16808, 16811, -1, 16810, 16793, 16808, -1, 16810, 16809, 16793, -1, 16813, 14885, 16809, -1, 16814, 16812, 14887, -1, 16814, 14887, 14885, -1, 16814, 16810, 16812, -1, 16814, 16809, 16810, -1, 16814, 14885, 16813, -1, 16814, 16813, 16809, -1, 16815, 16803, 16798, -1, 16815, 16798, 11691, -1, 16815, 16783, 16804, -1, 16815, 16804, 16803, -1, 16816, 16815, 11691, -1, 16816, 16783, 16815, -1, 16817, 16807, 16783, -1, 16817, 16816, 11691, -1, 16817, 16783, 16816, -1, 16787, 11691, 11688, -1, 16787, 16785, 16807, -1, 16787, 16807, 16817, -1, 16787, 16817, 11691, -1, 16789, 16787, 11688, -1, 16782, 16804, 16783, -1, 16782, 16805, 16804, -1, 16782, 14878, 16805, -1, 16818, 16819, 16820, -1, 16818, 14890, 16819, -1, 16821, 16820, 16822, -1, 16821, 16818, 16820, -1, 16823, 16822, 16824, -1, 16823, 16825, 16822, -1, 16823, 16824, 16826, -1, 16827, 16826, 11885, -1, 16827, 16823, 16826, -1, 16828, 16827, 11885, -1, 16828, 11885, 11884, -1, 16828, 11884, 16829, -1, 16828, 16829, 16830, -1, 16831, 16823, 16827, -1, 16831, 16828, 16830, -1, 16831, 16827, 16828, -1, 16831, 16830, 16825, -1, 16831, 16825, 16823, -1, 16832, 14890, 16818, -1, 16832, 16818, 16821, -1, 16833, 16832, 16821, -1, 16833, 14897, 14890, -1, 16833, 16834, 14897, -1, 16833, 16822, 16834, -1, 16833, 16821, 16822, -1, 16833, 14890, 16832, -1, 16835, 16836, 11898, -1, 16835, 11898, 11891, -1, 16837, 16838, 16836, -1, 16837, 16839, 16838, -1, 16837, 16836, 16835, -1, 16840, 16837, 16835, -1, 16841, 16837, 16840, -1, 16841, 16839, 16837, -1, 16842, 16843, 16839, -1, 16842, 14889, 16843, -1, 16842, 14890, 14889, -1, 16842, 16839, 16841, -1, 16822, 16820, 16844, -1, 16825, 16834, 16822, -1, 16830, 16829, 16845, -1, 16846, 14897, 16834, -1, 16846, 16834, 16825, -1, 16846, 16825, 16830, -1, 16847, 16848, 16849, -1, 16847, 16845, 16848, -1, 16847, 16830, 16845, -1, 16847, 16846, 16830, -1, 16850, 14897, 16846, -1, 16851, 16849, 14899, -1, 16851, 14899, 14897, -1, 16851, 16847, 16849, -1, 16851, 16846, 16847, -1, 16851, 14897, 16850, -1, 16851, 16850, 16846, -1, 16852, 16840, 16835, -1, 16852, 16835, 11891, -1, 16852, 16820, 16841, -1, 16852, 16841, 16840, -1, 16853, 16852, 11891, -1, 16853, 16820, 16852, -1, 16854, 16844, 16820, -1, 16854, 16853, 11891, -1, 16854, 16820, 16853, -1, 16824, 11891, 11885, -1, 16824, 16822, 16844, -1, 16824, 16844, 16854, -1, 16824, 16854, 11891, -1, 16826, 16824, 11885, -1, 16819, 16841, 16820, -1, 16819, 16842, 16841, -1, 16819, 14890, 16842, -1, 16855, 16856, 16857, -1, 16855, 14900, 16856, -1, 16858, 16857, 16859, -1, 16858, 16855, 16857, -1, 16860, 16859, 16861, -1, 16860, 16862, 16859, -1, 16860, 16861, 16863, -1, 16864, 16863, 11850, -1, 16864, 16860, 16863, -1, 16865, 16864, 11850, -1, 16865, 11850, 11849, -1, 16865, 11849, 16866, -1, 16865, 16866, 16867, -1, 16868, 16860, 16864, -1, 16868, 16865, 16867, -1, 16868, 16864, 16865, -1, 16868, 16867, 16862, -1, 16868, 16862, 16860, -1, 16869, 14900, 16855, -1, 16869, 16855, 16858, -1, 16870, 16869, 16858, -1, 16870, 14909, 14900, -1, 16870, 16871, 14909, -1, 16870, 16859, 16871, -1, 16870, 16858, 16859, -1, 16870, 14900, 16869, -1, 16872, 16873, 11869, -1, 16872, 11869, 11861, -1, 16874, 16875, 16873, -1, 16874, 16876, 16875, -1, 16874, 16873, 16872, -1, 16877, 16874, 16872, -1, 16878, 16874, 16877, -1, 16878, 16876, 16874, -1, 16879, 16880, 16876, -1, 16879, 14902, 16880, -1, 16879, 14900, 14902, -1, 16879, 16876, 16878, -1, 16859, 16857, 16881, -1, 16862, 16871, 16859, -1, 16867, 16866, 16882, -1, 16883, 14909, 16871, -1, 16883, 16871, 16862, -1, 16883, 16862, 16867, -1, 16884, 16885, 16886, -1, 16884, 16882, 16885, -1, 16884, 16867, 16882, -1, 16884, 16883, 16867, -1, 16887, 14909, 16883, -1, 16888, 16886, 14913, -1, 16888, 14913, 14909, -1, 16888, 16884, 16886, -1, 16888, 16883, 16884, -1, 16888, 14909, 16887, -1, 16888, 16887, 16883, -1, 16889, 16877, 16872, -1, 16889, 16872, 11861, -1, 16889, 16857, 16878, -1, 16889, 16878, 16877, -1, 16890, 16889, 11861, -1, 16890, 16857, 16889, -1, 16891, 16881, 16857, -1, 16891, 16890, 11861, -1, 16891, 16857, 16890, -1, 16861, 11861, 11850, -1, 16861, 16859, 16881, -1, 16861, 16881, 16891, -1, 16861, 16891, 11861, -1, 16863, 16861, 11850, -1, 16856, 16878, 16857, -1, 16856, 16879, 16878, -1, 16856, 14900, 16879, -1, 16892, 14924, 16893, -1, 16894, 16895, 16896, -1, 16894, 16892, 16895, -1, 16897, 16898, 16896, -1, 16897, 16899, 16900, -1, 16897, 16896, 16899, -1, 16901, 16900, 11756, -1, 16901, 16897, 16900, -1, 16902, 11758, 16903, -1, 16902, 11756, 11758, -1, 16902, 16903, 16904, -1, 16902, 16901, 11756, -1, 16905, 16901, 16902, -1, 16905, 16897, 16901, -1, 16905, 16902, 16904, -1, 16905, 16904, 16898, -1, 16905, 16898, 16897, -1, 16906, 14924, 16892, -1, 16906, 16892, 16894, -1, 16907, 14933, 14924, -1, 16907, 16906, 16894, -1, 16907, 16908, 14933, -1, 16907, 16896, 16908, -1, 16907, 16894, 16896, -1, 16907, 14924, 16906, -1, 16909, 16910, 11771, -1, 16909, 11771, 11761, -1, 16911, 16912, 16910, -1, 16911, 16913, 16912, -1, 16911, 16910, 16909, -1, 16914, 16911, 16909, -1, 16915, 16911, 16914, -1, 16915, 16913, 16911, -1, 16916, 14924, 14926, -1, 16916, 16917, 16913, -1, 16916, 14926, 16917, -1, 16916, 16913, 16915, -1, 16896, 16895, 16918, -1, 16898, 16908, 16896, -1, 16904, 16903, 16919, -1, 16920, 14933, 16908, -1, 16920, 16908, 16898, -1, 16920, 16898, 16904, -1, 16921, 16922, 16923, -1, 16921, 16919, 16922, -1, 16921, 16904, 16919, -1, 16921, 16920, 16904, -1, 16924, 14933, 16920, -1, 16925, 16923, 14937, -1, 16925, 14937, 14933, -1, 16925, 16921, 16923, -1, 16925, 16920, 16921, -1, 16925, 14933, 16924, -1, 16925, 16924, 16920, -1, 16926, 16914, 16909, -1, 16926, 16895, 16915, -1, 16926, 16909, 11761, -1, 16926, 16915, 16914, -1, 16927, 16895, 16926, -1, 16927, 16926, 11761, -1, 16928, 16918, 16895, -1, 16928, 16895, 16927, -1, 16928, 16927, 11761, -1, 16899, 11761, 11756, -1, 16899, 16918, 16928, -1, 16899, 16896, 16918, -1, 16899, 16928, 11761, -1, 16900, 16899, 11756, -1, 16893, 16915, 16895, -1, 16893, 16916, 16915, -1, 16893, 14924, 16916, -1, 16892, 16893, 16895, -1, 16929, 16930, 16931, -1, 16929, 14950, 16930, -1, 16932, 16931, 16933, -1, 16932, 16929, 16931, -1, 16934, 16933, 16935, -1, 16934, 16936, 16933, -1, 16934, 16935, 16937, -1, 16938, 16937, 11810, -1, 16938, 16934, 16937, -1, 16939, 16938, 11810, -1, 16939, 11810, 11812, -1, 16939, 11812, 16940, -1, 16939, 16940, 16941, -1, 16942, 16934, 16938, -1, 16942, 16939, 16941, -1, 16942, 16938, 16939, -1, 16942, 16941, 16936, -1, 16942, 16936, 16934, -1, 16943, 14950, 16929, -1, 16943, 16929, 16932, -1, 16944, 16943, 16932, -1, 16944, 14957, 14950, -1, 16944, 16945, 14957, -1, 16944, 16933, 16945, -1, 16944, 16932, 16933, -1, 16944, 14950, 16943, -1, 16946, 16947, 11833, -1, 16946, 11833, 11823, -1, 16948, 16949, 16947, -1, 16948, 16950, 16949, -1, 16948, 16947, 16946, -1, 16951, 16948, 16946, -1, 16952, 16948, 16951, -1, 16952, 16950, 16948, -1, 16953, 16954, 16950, -1, 16953, 14949, 16954, -1, 16953, 14950, 14949, -1, 16953, 16950, 16952, -1, 16933, 16931, 16955, -1, 16936, 16945, 16933, -1, 16941, 16940, 16956, -1, 16957, 14957, 16945, -1, 16957, 16945, 16936, -1, 16957, 16936, 16941, -1, 16958, 16959, 16960, -1, 16958, 16956, 16959, -1, 16958, 16941, 16956, -1, 16958, 16957, 16941, -1, 16961, 14957, 16957, -1, 16962, 16960, 14959, -1, 16962, 14959, 14957, -1, 16962, 16958, 16960, -1, 16962, 16957, 16958, -1, 16962, 14957, 16961, -1, 16962, 16961, 16957, -1, 16963, 16951, 16946, -1, 16963, 16946, 11823, -1, 16963, 16931, 16952, -1, 16963, 16952, 16951, -1, 16964, 16963, 11823, -1, 16964, 16931, 16963, -1, 16965, 16955, 16931, -1, 16965, 16964, 11823, -1, 16965, 16931, 16964, -1, 16935, 11823, 11810, -1, 16935, 16933, 16955, -1, 16935, 16955, 16965, -1, 16935, 16965, 11823, -1, 16937, 16935, 11810, -1, 16930, 16952, 16931, -1, 16930, 16953, 16952, -1, 16930, 14950, 16953, -1, 16966, 10997, 16967, -1, 16968, 16969, 16970, -1, 16968, 16966, 16969, -1, 16971, 16970, 16972, -1, 16971, 16973, 16970, -1, 16971, 16972, 16974, -1, 16975, 16974, 11883, -1, 16975, 16971, 16974, -1, 16976, 16975, 11883, -1, 16976, 11883, 11882, -1, 16976, 11882, 16977, -1, 16976, 16977, 16978, -1, 16979, 16971, 16975, -1, 16979, 16976, 16978, -1, 16979, 16975, 16976, -1, 16979, 16978, 16973, -1, 16979, 16973, 16971, -1, 16980, 10997, 16966, -1, 16980, 16966, 16968, -1, 16981, 16980, 16968, -1, 16981, 11004, 10997, -1, 16981, 16982, 11004, -1, 16981, 16970, 16982, -1, 16981, 16968, 16970, -1, 16981, 10997, 16980, -1, 16983, 16984, 11896, -1, 16983, 11896, 11892, -1, 16985, 16986, 16984, -1, 16985, 16987, 16986, -1, 16985, 16984, 16983, -1, 16988, 16985, 16983, -1, 16989, 16985, 16988, -1, 16989, 16987, 16985, -1, 16990, 16991, 16987, -1, 16990, 10996, 16991, -1, 16990, 10997, 10996, -1, 16990, 16987, 16989, -1, 16970, 16969, 16992, -1, 16973, 16982, 16970, -1, 16978, 16977, 16993, -1, 16994, 11004, 16982, -1, 16994, 16982, 16973, -1, 16994, 16973, 16978, -1, 16995, 16996, 16997, -1, 16995, 16993, 16996, -1, 16995, 16978, 16993, -1, 16995, 16994, 16978, -1, 16998, 11004, 16994, -1, 16999, 16997, 11006, -1, 16999, 11006, 11004, -1, 16999, 16995, 16997, -1, 16999, 16994, 16995, -1, 16999, 11004, 16998, -1, 16999, 16998, 16994, -1, 17000, 16988, 16983, -1, 17000, 16969, 16989, -1, 17000, 16983, 11892, -1, 17000, 16989, 16988, -1, 17001, 16969, 17000, -1, 17001, 17000, 11892, -1, 17002, 16992, 16969, -1, 17002, 16969, 17001, -1, 17002, 17001, 11892, -1, 16972, 11892, 11883, -1, 16972, 16970, 16992, -1, 16972, 16992, 17002, -1, 16972, 17002, 11892, -1, 16974, 16972, 11883, -1, 16967, 16989, 16969, -1, 16967, 16990, 16989, -1, 16967, 10997, 16990, -1, 16966, 16967, 16969, -1, 17003, 17004, 17005, -1, 17003, 17006, 17007, -1, 17003, 17007, 11440, -1, 17008, 17009, 17010, -1, 17008, 17010, 17011, -1, 17008, 17011, 17012, -1, 17013, 17012, 17006, -1, 17013, 17008, 17012, -1, 17014, 17009, 17008, -1, 17014, 17008, 17013, -1, 17015, 17009, 17014, -1, 17015, 17014, 17013, -1, 17015, 17013, 17006, -1, 17016, 17015, 17006, -1, 17016, 17006, 17005, -1, 17016, 17017, 17009, -1, 17016, 17005, 17017, -1, 17016, 17009, 17015, -1, 17018, 17019, 11449, -1, 17018, 17020, 17019, -1, 17018, 11449, 11444, -1, 17021, 17022, 17020, -1, 17021, 17023, 17022, -1, 17024, 17021, 17020, -1, 17024, 17020, 17018, -1, 17025, 17010, 17026, -1, 17025, 17026, 17023, -1, 17025, 17021, 17024, -1, 17025, 17023, 17021, -1, 17027, 17025, 17024, -1, 17011, 17010, 17025, -1, 17011, 17025, 17027, -1, 17011, 17027, 17012, -1, 17006, 17012, 17028, -1, 17004, 11440, 11439, -1, 17029, 17030, 17031, -1, 17029, 17032, 17030, -1, 17029, 11439, 17032, -1, 17029, 17031, 17005, -1, 17029, 17004, 11439, -1, 17029, 17005, 17004, -1, 17017, 17033, 17009, -1, 17034, 17035, 17033, -1, 17034, 17031, 17035, -1, 17034, 17033, 17017, -1, 17034, 17005, 17031, -1, 17034, 17017, 17005, -1, 17036, 17024, 17018, -1, 17036, 17027, 17024, -1, 17036, 17018, 11444, -1, 17037, 17027, 17036, -1, 17037, 17036, 11444, -1, 17038, 17037, 11444, -1, 17039, 17012, 17027, -1, 17039, 17027, 17037, -1, 17039, 17037, 17038, -1, 17040, 11444, 11440, -1, 17040, 17028, 17012, -1, 17040, 17038, 11444, -1, 17040, 17012, 17039, -1, 17040, 17039, 17038, -1, 17041, 17006, 17028, -1, 17041, 17028, 17040, -1, 17041, 17040, 11440, -1, 17007, 17006, 17041, -1, 17007, 17041, 11440, -1, 17003, 11440, 17004, -1, 17003, 17005, 17006, -1, 17042, 17043, 17044, -1, 17045, 17046, 17047, -1, 17045, 17048, 17046, -1, 17049, 17050, 17051, -1, 17049, 3501, 17050, -1, 17049, 17051, 17043, -1, 17052, 11597, 11586, -1, 17052, 17047, 11597, -1, 11436, 4522, 4521, -1, 17053, 3495, 3491, -1, 17053, 3491, 17054, -1, 17053, 17055, 17056, -1, 17053, 17054, 17055, -1, 17057, 17058, 17059, -1, 17057, 17059, 17060, -1, 17061, 17062, 17063, -1, 17061, 17064, 17062, -1, 17065, 17043, 17042, -1, 17065, 17049, 17043, -1, 17065, 3501, 17049, -1, 17065, 3505, 3501, -1, 17066, 17048, 17045, -1, 17066, 17067, 17048, -1, 17068, 17047, 17052, -1, 17068, 17045, 17047, -1, 17069, 17070, 11467, -1, 17069, 11467, 11479, -1, 17071, 17052, 11586, -1, 17072, 17042, 17058, -1, 17073, 17056, 17064, -1, 17072, 17058, 17057, -1, 17073, 17064, 17061, -1, 17074, 17060, 17075, -1, 17076, 17067, 17066, -1, 17076, 17063, 17067, -1, 17074, 17075, 17077, -1, 17078, 17079, 17070, -1, 17080, 17045, 17068, -1, 17080, 17066, 17045, -1, 17078, 17070, 17069, -1, 17081, 17068, 17052, -1, 17082, 17065, 17042, -1, 17082, 17042, 17072, -1, 17082, 3505, 17065, -1, 17081, 17052, 17071, -1, 17083, 17057, 17060, -1, 17083, 17060, 17074, -1, 17084, 3499, 3495, -1, 17084, 17056, 17073, -1, 17084, 17053, 17056, -1, 17084, 3495, 17053, -1, 17085, 17071, 11586, -1, 17086, 17077, 17079, -1, 17085, 11586, 11580, -1, 17086, 17079, 17078, -1, 17087, 17061, 17063, -1, 17088, 11479, 11491, -1, 17088, 17069, 11479, -1, 17087, 17063, 17076, -1, 17089, 17072, 17057, -1, 17090, 17066, 17080, -1, 17089, 17057, 17083, -1, 17090, 17076, 17066, -1, 17091, 17080, 17068, -1, 17091, 17068, 17081, -1, 17092, 17074, 17077, -1, 17092, 17077, 17086, -1, 17093, 17085, 11580, -1, 17094, 11491, 11505, -1, 17095, 17081, 17071, -1, 17095, 17071, 17085, -1, 17094, 17088, 11491, -1, 17096, 17078, 17069, -1, 17097, 17073, 17061, -1, 17096, 17069, 17088, -1, 17097, 17061, 17087, -1, 17098, 3509, 3505, -1, 17098, 17082, 17072, -1, 17098, 3505, 17082, -1, 17098, 17072, 17089, -1, 17099, 17087, 17076, -1, 17099, 17076, 17090, -1, 17100, 17083, 17074, -1, 17101, 17090, 17080, -1, 17100, 17074, 17092, -1, 17101, 17080, 17091, -1, 17102, 17096, 17088, -1, 17102, 17088, 17094, -1, 17103, 17085, 17093, -1, 17103, 17095, 17085, -1, 17104, 17091, 17081, -1, 17104, 17081, 17095, -1, 17105, 17078, 17096, -1, 17105, 17086, 17078, -1, 17106, 3503, 3499, -1, 17107, 17094, 11505, -1, 17106, 3499, 17084, -1, 17106, 17084, 17073, -1, 17106, 17073, 17097, -1, 17108, 17097, 17087, -1, 17109, 17089, 17083, -1, 17108, 17087, 17099, -1, 17109, 17083, 17100, -1, 17110, 17096, 17102, -1, 17111, 17099, 17090, -1, 17111, 17090, 17101, -1, 17110, 17105, 17096, -1, 17112, 11580, 11570, -1, 17113, 17086, 17105, -1, 17112, 17093, 11580, -1, 17113, 17092, 17086, -1, 17114, 17104, 17095, -1, 17115, 17094, 17107, -1, 17114, 17095, 17103, -1, 17115, 17102, 17094, -1, 17116, 17091, 17104, -1, 17117, 17107, 11505, -1, 17116, 17101, 17091, -1, 17117, 11505, 11514, -1, 17118, 3503, 17106, -1, 17119, 17098, 17089, -1, 17118, 17097, 17108, -1, 17119, 17089, 17109, -1, 17118, 17106, 17097, -1, 17119, 3509, 17098, -1, 17119, 3418, 3509, -1, 17120, 17099, 17111, -1, 17121, 17105, 17110, -1, 17120, 17108, 17099, -1, 17121, 17113, 17105, -1, 17122, 17092, 17113, -1, 17123, 17103, 17093, -1, 17122, 17100, 17092, -1, 17123, 17093, 17112, -1, 17124, 17104, 17114, -1, 17125, 17102, 17115, -1, 17124, 17116, 17104, -1, 17125, 17110, 17102, -1, 17126, 17111, 17101, -1, 17126, 17101, 17116, -1, 17127, 17117, 11514, -1, 17128, 3507, 3503, -1, 17129, 17107, 17117, -1, 17128, 3503, 17118, -1, 17128, 17118, 17108, -1, 17129, 17115, 17107, -1, 17128, 17108, 17120, -1, 17130, 17114, 17103, -1, 17130, 17103, 17123, -1, 17131, 17113, 17121, -1, 17132, 17116, 17124, -1, 17132, 17126, 17116, -1, 17131, 17122, 17113, -1, 17133, 17100, 17122, -1, 17133, 17109, 17100, -1, 17134, 17120, 17111, -1, 17134, 17111, 17126, -1, 17135, 17121, 17110, -1, 17135, 17110, 17125, -1, 17136, 17117, 17127, -1, 17136, 17129, 17117, -1, 17137, 17114, 17130, -1, 17137, 17124, 17114, -1, 17138, 17126, 17132, -1, 17138, 17134, 17126, -1, 17139, 17115, 17129, -1, 17139, 17125, 17115, -1, 17140, 17120, 17134, -1, 17140, 17128, 17120, -1, 17141, 17122, 17131, -1, 17140, 3507, 17128, -1, 17141, 17133, 17122, -1, 17142, 3418, 17119, -1, 17142, 17109, 17133, -1, 17142, 3419, 3418, -1, 17142, 17119, 17109, -1, 17143, 17132, 17124, -1, 17144, 17131, 17121, -1, 17143, 17124, 17137, -1, 17144, 17121, 17135, -1, 17145, 17134, 17138, -1, 17146, 17127, 11514, -1, 17145, 17140, 17134, -1, 17145, 3507, 17140, -1, 17146, 11514, 11523, -1, 17145, 3415, 3507, -1, 17147, 17129, 17136, -1, 17147, 17139, 17129, -1, 17148, 17149, 11560, -1, 17148, 11560, 11553, -1, 17150, 17135, 17125, -1, 17150, 17125, 17139, -1, 17151, 17138, 17132, -1, 17151, 17132, 17143, -1, 17152, 17133, 17141, -1, 17152, 17142, 17133, -1, 17152, 3419, 17142, -1, 17153, 17141, 17131, -1, 17153, 17131, 17144, -1, 17154, 17155, 17149, -1, 17156, 17127, 17146, -1, 17156, 17136, 17127, -1, 17154, 17149, 17148, -1, 17157, 17145, 17138, -1, 17157, 17138, 17151, -1, 17157, 3415, 17145, -1, 17158, 17150, 17139, -1, 17158, 17139, 17147, -1, 17159, 17144, 17135, -1, 17159, 17135, 17150, -1, 17160, 17161, 17155, -1, 17162, 17141, 17153, -1, 17162, 17152, 17141, -1, 17160, 17155, 17154, -1, 17162, 3425, 3419, -1, 17162, 3419, 17152, -1, 17163, 17136, 17156, -1, 17164, 11553, 11544, -1, 17164, 17148, 11553, -1, 17163, 17147, 17136, -1, 17165, 17150, 17158, -1, 17166, 17167, 17161, -1, 17165, 17159, 17150, -1, 17166, 17161, 17160, -1, 17168, 17153, 17144, -1, 17168, 17144, 17159, -1, 17169, 11544, 11533, -1, 17169, 17164, 11544, -1, 17170, 17148, 17164, -1, 17171, 17147, 17163, -1, 17171, 17158, 17147, -1, 17170, 17154, 17148, -1, 17172, 17168, 17159, -1, 17172, 17159, 17165, -1, 17173, 3425, 17162, -1, 17173, 17153, 17168, -1, 17173, 17162, 17153, -1, 17174, 17175, 17167, -1, 17176, 17165, 17158, -1, 17176, 17158, 17171, -1, 17174, 17167, 17166, -1, 17177, 3425, 17173, -1, 17177, 17173, 17168, -1, 17177, 3432, 3425, -1, 17178, 17164, 17169, -1, 17177, 17168, 17172, -1, 17178, 17170, 17164, -1, 17179, 17172, 17165, -1, 17180, 17154, 17170, -1, 17180, 17160, 17154, -1, 17179, 17165, 17176, -1, 17181, 17177, 17172, -1, 17181, 3432, 17177, -1, 17181, 17172, 17179, -1, 17182, 17169, 11533, -1, 17183, 17184, 17175, -1, 17183, 17175, 17174, -1, 17185, 17186, 17187, -1, 17185, 17187, 11377, -1, 17188, 17170, 17178, -1, 17188, 17180, 17170, -1, 17189, 17186, 17185, -1, 17189, 17185, 17190, -1, 17191, 17160, 17180, -1, 17191, 17166, 17160, -1, 17192, 17178, 17169, -1, 17192, 17169, 17182, -1, 17193, 17194, 17195, -1, 17196, 11533, 11524, -1, 17196, 17182, 11533, -1, 17197, 17193, 17198, -1, 17197, 17194, 17193, -1, 17199, 17200, 17184, -1, 17199, 3416, 17200, -1, 17199, 17184, 17183, -1, 17201, 17202, 11451, -1, 17201, 11451, 17203, -1, 17199, 3423, 3416, -1, 17201, 17204, 17202, -1, 17201, 17203, 17205, -1, 17206, 17180, 17188, -1, 17207, 17204, 17201, -1, 17206, 17191, 17180, -1, 17207, 17201, 17205, -1, 17208, 17174, 17166, -1, 17208, 17166, 17191, -1, 17209, 17070, 17079, -1, 17209, 17210, 17211, -1, 17212, 17178, 17192, -1, 17212, 17188, 17178, -1, 17213, 17156, 17146, -1, 17214, 17196, 11524, -1, 17215, 17182, 17196, -1, 17216, 17213, 4534, -1, 17216, 17156, 17213, -1, 17215, 17192, 17182, -1, 17217, 17191, 17206, -1, 17218, 11377, 11368, -1, 17217, 17208, 17191, -1, 17218, 11368, 17219, -1, 17218, 17190, 17185, -1, 17218, 17219, 17190, -1, 17218, 17185, 11377, -1, 17220, 17221, 17222, -1, 17220, 17186, 17189, -1, 17223, 17174, 17208, -1, 17223, 17183, 17174, -1, 17220, 17222, 17186, -1, 17224, 17189, 17190, -1, 17225, 17188, 17212, -1, 17224, 17220, 17189, -1, 17224, 17190, 17226, -1, 17225, 17206, 17188, -1, 17224, 17226, 17227, -1, 17228, 17215, 17196, -1, 17229, 17112, 11570, -1, 17229, 17230, 17112, -1, 17231, 11560, 17149, -1, 17231, 17149, 17155, -1, 17228, 17196, 17214, -1, 17231, 11570, 11560, -1, 17231, 17229, 11570, -1, 17232, 17212, 17192, -1, 17231, 17230, 17229, -1, 17232, 17192, 17215, -1, 17233, 17130, 17123, -1, 17233, 17112, 17230, -1, 17234, 17223, 17208, -1, 17234, 17208, 17217, -1, 17233, 17123, 17112, -1, 17235, 17155, 17161, -1, 17235, 17231, 17155, -1, 17236, 17199, 17183, -1, 17235, 17230, 17231, -1, 17236, 3423, 17199, -1, 17235, 17233, 17230, -1, 17237, 17195, 11518, -1, 17236, 17183, 17223, -1, 17236, 3430, 3423, -1, 17237, 17193, 17195, -1, 17238, 17206, 17225, -1, 17239, 11518, 11507, -1, 17239, 17198, 17193, -1, 17239, 11507, 17240, -1, 17239, 17237, 11518, -1, 17238, 17217, 17206, -1, 17239, 17193, 17237, -1, 17195, 17214, 11524, -1, 17239, 17240, 17198, -1, 17195, 11524, 11518, -1, 17241, 17194, 17197, -1, 17241, 17242, 17194, -1, 17241, 17243, 17242, -1, 17244, 17215, 17228, -1, 17245, 17198, 17246, -1, 17245, 17246, 17247, -1, 17244, 17232, 17215, -1, 17245, 17241, 17197, -1, 17245, 17197, 17198, -1, 17248, 17249, 17204, -1, 17250, 17225, 17212, -1, 17248, 17251, 17249, -1, 17250, 17212, 17232, -1, 17248, 17204, 17207, -1, 17252, 17207, 17205, -1, 17253, 17223, 17234, -1, 17252, 17254, 17255, -1, 17253, 17236, 17223, -1, 17252, 17205, 17254, -1, 17253, 3430, 17236, -1, 17252, 17248, 17207, -1, 17256, 17211, 11460, -1, 17257, 17234, 17217, -1, 17256, 17209, 17211, -1, 17257, 17217, 17238, -1, 17258, 17209, 17256, -1, 17258, 11467, 17070, -1, 17194, 17214, 17195, -1, 17258, 11460, 11467, -1, 17258, 17256, 11460, -1, 17258, 17070, 17209, -1, 17194, 17228, 17214, -1, 17259, 17075, 17210, -1, 17260, 17250, 17232, -1, 17259, 17210, 17209, -1, 17260, 17232, 17244, -1, 17261, 17075, 17259, -1, 17261, 17259, 17209, -1, 17261, 17079, 17077, -1, 17261, 17209, 17079, -1, 17261, 17077, 17075, -1, 17262, 17225, 17250, -1, 17263, 17146, 11523, -1, 17262, 17238, 17225, -1, 17263, 17213, 17146, -1, 17264, 17213, 17263, -1, 17264, 17263, 11523, -1, 17265, 17234, 17257, -1, 17264, 4534, 17213, -1, 17265, 17253, 17234, -1, 17264, 11523, 4524, -1, 17265, 3430, 17253, -1, 17264, 4524, 4528, -1, 17264, 4528, 4534, -1, 17265, 3437, 3430, -1, 17266, 17156, 17216, -1, 17242, 17244, 17228, -1, 17266, 17171, 17163, -1, 17242, 17228, 17194, -1, 17266, 17163, 17156, -1, 17267, 4522, 11436, -1, 17268, 17216, 4534, -1, 17268, 17266, 17216, -1, 17269, 17250, 17260, -1, 17270, 4466, 4522, -1, 17269, 17262, 17250, -1, 17268, 4534, 4539, -1, 17268, 4539, 4547, -1, 17271, 17221, 17220, -1, 17272, 17257, 17238, -1, 17270, 4522, 17267, -1, 17272, 17238, 17262, -1, 17271, 17273, 17221, -1, 17274, 4530, 4466, -1, 17275, 17220, 17224, -1, 17275, 17271, 17220, -1, 17274, 4466, 17270, -1, 17276, 17271, 17275, -1, 17276, 17275, 17224, -1, 17243, 17244, 17242, -1, 17277, 11436, 11427, -1, 17243, 17260, 17244, -1, 17277, 17267, 11436, -1, 17278, 17276, 17224, -1, 17279, 17272, 17262, -1, 17279, 17262, 17269, -1, 17280, 4532, 4530, -1, 17281, 17278, 17224, -1, 17282, 17265, 17257, -1, 17281, 17224, 17227, -1, 17282, 3437, 17265, -1, 17281, 17227, 17283, -1, 17280, 4530, 17274, -1, 17282, 17257, 17272, -1, 17284, 11427, 11406, -1, 17285, 17130, 17233, -1, 17285, 17137, 17130, -1, 17284, 17277, 11427, -1, 17286, 17285, 17233, -1, 17287, 17267, 17277, -1, 17286, 17233, 17235, -1, 17287, 17270, 17267, -1, 17288, 17260, 17243, -1, 17289, 17285, 17286, -1, 17288, 17269, 17260, -1, 17290, 4611, 4532, -1, 17289, 17286, 17235, -1, 17291, 3437, 17282, -1, 17291, 17272, 17279, -1, 17291, 3441, 3437, -1, 17290, 4532, 17280, -1, 17291, 17282, 17272, -1, 17292, 17289, 17235, -1, 17293, 17287, 17277, -1, 17294, 17161, 17167, -1, 17294, 17235, 17161, -1, 17294, 17292, 17235, -1, 17293, 17277, 17284, -1, 17295, 17274, 17270, -1, 17296, 17288, 17243, -1, 17297, 17269, 17288, -1, 17296, 17243, 17241, -1, 17297, 17279, 17269, -1, 17295, 17270, 17287, -1, 17298, 17296, 17241, -1, 17299, 11507, 11494, -1, 17299, 17240, 11507, -1, 17300, 17284, 11406, -1, 17301, 4646, 4611, -1, 17302, 17241, 17245, -1, 17301, 4611, 17290, -1, 17303, 17298, 17241, -1, 17303, 17241, 17302, -1, 17304, 17295, 17287, -1, 17305, 17247, 17306, -1, 17304, 17287, 17293, -1, 17307, 17279, 17297, -1, 17305, 17302, 17245, -1, 17307, 17291, 17279, -1, 17305, 17303, 17302, -1, 17308, 17274, 17295, -1, 17307, 3441, 17291, -1, 17305, 17245, 17247, -1, 17309, 17310, 17251, -1, 17308, 17280, 17274, -1, 17311, 17240, 17299, -1, 17309, 17251, 17248, -1, 17312, 17309, 17248, -1, 17312, 17248, 17252, -1, 17311, 17198, 17240, -1, 17313, 17293, 17284, -1, 17314, 17309, 17312, -1, 17313, 17284, 17300, -1, 17315, 11406, 11397, -1, 17314, 17312, 17252, -1, 17316, 17246, 17198, -1, 17315, 17300, 11406, -1, 17317, 4694, 4646, -1, 17317, 3427, 4694, -1, 17318, 17314, 17252, -1, 17317, 3433, 3427, -1, 17317, 4646, 17301, -1, 17316, 17198, 17311, -1, 17319, 17308, 17295, -1, 17320, 17252, 17255, -1, 17321, 17299, 11494, -1, 17320, 17255, 17322, -1, 17319, 17295, 17304, -1, 17321, 11494, 11483, -1, 17320, 17318, 17252, -1, 17323, 17176, 17171, -1, 17323, 17171, 17266, -1, 17324, 17290, 17280, -1, 17325, 17266, 17268, -1, 17324, 17280, 17308, -1, 17326, 17304, 17293, -1, 17325, 17323, 17266, -1, 17327, 17247, 17246, -1, 17327, 17246, 17316, -1, 17326, 17293, 17313, -1, 17328, 17315, 11397, -1, 17329, 17323, 17325, -1, 17330, 17321, 11483, -1, 17331, 17313, 17300, -1, 17330, 11483, 11472, -1, 17331, 17300, 17315, -1, 17332, 17325, 17268, -1, 17332, 17329, 17325, -1, 17333, 17299, 17321, -1, 17334, 17268, 4547, -1, 17335, 17308, 17319, -1, 17334, 4547, 4559, -1, 17334, 17332, 17268, -1, 17335, 17324, 17308, -1, 17333, 17311, 17299, -1, 17336, 17273, 17271, -1, 17336, 17276, 17278, -1, 17337, 17301, 17290, -1, 17336, 17338, 17273, -1, 17337, 17290, 17324, -1, 17339, 17306, 17247, -1, 17336, 17271, 17276, -1, 17339, 17247, 17327, -1, 17340, 17336, 17278, -1, 17340, 17278, 17281, -1, 17341, 17319, 17304, -1, 17340, 17281, 17283, -1, 17340, 17283, 17342, -1, 17341, 17304, 17326, -1, 17343, 17143, 17137, -1, 17344, 17333, 17321, -1, 17343, 17137, 17285, -1, 17345, 17331, 17315, -1, 17344, 17321, 17330, -1, 17343, 17285, 17289, -1, 17343, 17289, 17292, -1, 17345, 17315, 17328, -1, 17346, 17343, 17292, -1, 17347, 17316, 17311, -1, 17346, 17167, 17175, -1, 17346, 17294, 17167, -1, 17347, 17311, 17333, -1, 17346, 17292, 17294, -1, 17348, 17326, 17313, -1, 17349, 17297, 17288, -1, 17348, 17313, 17331, -1, 17350, 17337, 17324, -1, 17349, 17296, 17298, -1, 17351, 17330, 11472, -1, 17349, 17288, 17296, -1, 17350, 17324, 17335, -1, 17352, 17349, 17298, -1, 17352, 17306, 17353, -1, 17354, 3439, 3433, -1, 17354, 17317, 17301, -1, 17355, 17353, 17306, -1, 17352, 17305, 17306, -1, 17354, 3433, 17317, -1, 17355, 17306, 17339, -1, 17352, 17298, 17303, -1, 17352, 17303, 17305, -1, 17354, 17301, 17337, -1, 17356, 17357, 17310, -1, 17358, 17347, 17333, -1, 17359, 17319, 17341, -1, 17358, 17333, 17344, -1, 17356, 17309, 17314, -1, 17359, 17335, 17319, -1, 17356, 17314, 17318, -1, 17187, 11397, 11377, -1, 17356, 17310, 17309, -1, 17360, 17327, 17316, -1, 17361, 17356, 17318, -1, 17361, 17322, 17362, -1, 17360, 17316, 17347, -1, 17361, 17320, 17322, -1, 17187, 17328, 11397, -1, 17361, 17318, 17320, -1, 17363, 17176, 17323, -1, 17364, 17331, 17345, -1, 17365, 17344, 17330, -1, 17363, 17179, 17176, -1, 17365, 17330, 17351, -1, 17364, 17348, 17331, -1, 17363, 17323, 17329, -1, 17363, 17329, 17332, -1, 17366, 17332, 17334, -1, 17367, 17341, 17326, -1, 17368, 17351, 11472, -1, 17368, 11472, 11462, -1, 17366, 17363, 17332, -1, 17366, 4559, 4574, -1, 17367, 17326, 17348, -1, 17366, 17334, 4559, -1, 17369, 17338, 17336, -1, 17370, 3439, 17354, -1, 17371, 17372, 17353, -1, 17371, 3445, 17372, -1, 17370, 17337, 17350, -1, 17371, 17353, 17355, -1, 17369, 17373, 17338, -1, 17370, 17354, 17337, -1, 17371, 3449, 3445, -1, 17374, 17350, 17335, -1, 17375, 17360, 17347, -1, 17375, 17347, 17358, -1, 17376, 17369, 17336, -1, 17374, 17335, 17359, -1, 17186, 17345, 17328, -1, 17377, 17339, 17327, -1, 17378, 17340, 17342, -1, 17186, 17328, 17187, -1, 17377, 17327, 17360, -1, 17378, 17376, 17336, -1, 17378, 17336, 17340, -1, 17378, 17342, 17379, -1, 17380, 17151, 17143, -1, 17380, 17143, 17343, -1, 17381, 17358, 17344, -1, 17381, 17344, 17365, -1, 17382, 17348, 17364, -1, 17382, 17367, 17348, -1, 17383, 17380, 17343, -1, 17384, 17351, 17368, -1, 17385, 17341, 17367, -1, 17385, 17359, 17341, -1, 17386, 17346, 17175, -1, 17384, 17365, 17351, -1, 17386, 17343, 17346, -1, 17387, 17350, 17374, -1, 17386, 17175, 17184, -1, 17387, 3443, 3439, -1, 17386, 17383, 17343, -1, 17387, 3439, 17370, -1, 17388, 17368, 11462, -1, 17387, 17370, 17350, -1, 17389, 17307, 17297, -1, 17222, 17345, 17186, -1, 17390, 17360, 17375, -1, 17389, 17297, 17349, -1, 17389, 17349, 17352, -1, 17390, 17377, 17360, -1, 17391, 17389, 17352, -1, 17222, 17364, 17345, -1, 17392, 17355, 17339, -1, 17392, 17339, 17377, -1, 17393, 17367, 17382, -1, 17393, 17385, 17367, -1, 17394, 17391, 17352, -1, 17394, 17352, 17353, -1, 17394, 17353, 17372, -1, 17395, 17375, 17358, -1, 17396, 17359, 17385, -1, 17395, 17358, 17381, -1, 17397, 17398, 17357, -1, 17397, 17357, 17356, -1, 17396, 17374, 17359, -1, 17399, 17381, 17365, -1, 17399, 17365, 17384, -1, 17400, 17397, 17356, -1, 17401, 17362, 17402, -1, 17221, 17364, 17222, -1, 17401, 17356, 17361, -1, 17401, 17361, 17362, -1, 17401, 17400, 17356, -1, 17221, 17382, 17364, -1, 17403, 17384, 17368, -1, 17404, 17179, 17363, -1, 17405, 17385, 17393, -1, 17403, 17368, 17388, -1, 17405, 17396, 17385, -1, 17404, 17181, 17179, -1, 17406, 17392, 17377, -1, 17407, 17404, 17363, -1, 17408, 17387, 17374, -1, 17406, 17377, 17390, -1, 17408, 3443, 17387, -1, 17408, 17374, 17396, -1, 17409, 17371, 17355, -1, 17409, 3449, 17371, -1, 17409, 17355, 17392, -1, 17410, 17366, 4574, -1, 17409, 3453, 3449, -1, 17410, 17363, 17366, -1, 17410, 17407, 17363, -1, 17202, 11462, 11451, -1, 17410, 4574, 4594, -1, 17202, 17388, 11462, -1, 17411, 17373, 17369, -1, 17411, 3447, 17373, -1, 17412, 17375, 17395, -1, 17411, 17369, 17376, -1, 17412, 17390, 17375, -1, 17413, 3451, 3447, -1, 17273, 17393, 17382, -1, 17413, 17379, 3451, -1, 17273, 17382, 17221, -1, 17413, 3447, 17411, -1, 17413, 17378, 17379, -1, 17413, 17376, 17378, -1, 17414, 3447, 3443, -1, 17413, 17411, 17376, -1, 17415, 17380, 17383, -1, 17414, 17396, 17405, -1, 17414, 3443, 17408, -1, 17416, 17381, 17399, -1, 17415, 17151, 17380, -1, 17414, 17408, 17396, -1, 17415, 17157, 17151, -1, 17416, 17395, 17381, -1, 17417, 17399, 17384, -1, 17418, 17415, 17383, -1, 17418, 17386, 17184, -1, 17418, 17383, 17386, -1, 17418, 17184, 17200, -1, 17417, 17384, 17403, -1, 17419, 17392, 17406, -1, 17420, 17307, 17389, -1, 17338, 17405, 17393, -1, 17420, 3441, 17307, -1, 17338, 17393, 17273, -1, 17419, 3453, 17409, -1, 17420, 17389, 17391, -1, 17419, 17409, 17392, -1, 17420, 3445, 3441, -1, 17204, 17388, 17202, -1, 17421, 17372, 3445, -1, 17204, 17403, 17388, -1, 17421, 17391, 17394, -1, 17422, 11368, 11348, -1, 17421, 17394, 17372, -1, 17421, 3445, 17420, -1, 17422, 17219, 11368, -1, 17421, 17420, 17391, -1, 17423, 17398, 17397, -1, 17423, 17397, 17400, -1, 17424, 17390, 17412, -1, 17423, 3461, 17398, -1, 17425, 17402, 3465, -1, 17424, 17406, 17390, -1, 17425, 17400, 17401, -1, 17426, 17412, 17395, -1, 17425, 17401, 17402, -1, 17426, 17395, 17416, -1, 17425, 3465, 3461, -1, 17425, 17423, 17400, -1, 17425, 3461, 17423, -1, 17427, 3432, 17181, -1, 17427, 17181, 17404, -1, 17373, 17405, 17338, -1, 17428, 17399, 17417, -1, 17373, 3447, 17414, -1, 17428, 17416, 17399, -1, 17373, 17414, 17405, -1, 17427, 17404, 17407, -1, 17429, 3432, 17427, -1, 17429, 4594, 3436, -1, 17429, 3436, 3432, -1, 17430, 17190, 17219, -1, 17429, 17407, 17410, -1, 17249, 17403, 17204, -1, 17429, 17410, 4594, -1, 17249, 17417, 17403, -1, 17429, 17427, 17407, -1, 17430, 17219, 17422, -1, 17431, 3415, 17157, -1, 17431, 17200, 3416, -1, 17431, 17157, 17415, -1, 17431, 17415, 17418, -1, 17431, 17418, 17200, -1, 17431, 3416, 3415, -1, 17432, 17419, 17406, -1, 17432, 17406, 17424, -1, 17432, 3453, 17419, -1, 17432, 3457, 3453, -1, 17433, 17424, 17412, -1, 17434, 17190, 17430, -1, 17433, 17412, 17426, -1, 17434, 17226, 17190, -1, 17435, 11348, 11339, -1, 17436, 17416, 17428, -1, 17435, 17422, 11348, -1, 17436, 17426, 17416, -1, 17203, 11451, 11438, -1, 17251, 17428, 17417, -1, 17437, 17226, 17434, -1, 17251, 17417, 17249, -1, 17437, 17227, 17226, -1, 17438, 17424, 17433, -1, 17438, 17432, 17424, -1, 17438, 3457, 17432, -1, 17439, 11339, 11317, -1, 17439, 17435, 11339, -1, 17440, 17433, 17426, -1, 17440, 17426, 17436, -1, 17441, 17422, 17435, -1, 17441, 17430, 17422, -1, 17310, 17436, 17428, -1, 17442, 17227, 17437, -1, 17310, 17428, 17251, -1, 17443, 17438, 17433, -1, 17443, 17433, 17440, -1, 17442, 17283, 17227, -1, 17443, 3457, 17438, -1, 17444, 17441, 17435, -1, 17443, 3461, 3457, -1, 17444, 17435, 17439, -1, 17357, 17436, 17310, -1, 17445, 17430, 17441, -1, 17357, 17440, 17436, -1, 17445, 17434, 17430, -1, 17446, 17439, 11317, -1, 17447, 11438, 11423, -1, 17447, 17203, 11438, -1, 17448, 17283, 17442, -1, 17448, 17342, 17283, -1, 17449, 17441, 17444, -1, 17449, 17445, 17441, -1, 17398, 17440, 17357, -1, 17450, 17437, 17434, -1, 17398, 17443, 17440, -1, 17398, 3461, 17443, -1, 17450, 17434, 17445, -1, 17451, 17203, 17447, -1, 17451, 17205, 17203, -1, 17452, 17444, 17439, -1, 17452, 17439, 17446, -1, 17453, 11317, 11308, -1, 17453, 17446, 11317, -1, 17454, 3455, 3451, -1, 17455, 17254, 17205, -1, 17454, 3451, 17379, -1, 17454, 17342, 17448, -1, 17454, 17379, 17342, -1, 17455, 17205, 17451, -1, 17456, 17447, 11423, -1, 17456, 11423, 11412, -1, 17457, 17445, 17449, -1, 17457, 17450, 17445, -1, 17458, 17442, 17437, -1, 17458, 17437, 17450, -1, 17459, 17449, 17444, -1, 17459, 17444, 17452, -1, 17460, 17255, 17254, -1, 17460, 17254, 17455, -1, 17461, 17452, 17446, -1, 17461, 17446, 17453, -1, 17462, 11412, 11403, -1, 17462, 17456, 11412, -1, 17463, 17453, 11308, -1, 17464, 17451, 17447, -1, 17465, 17450, 17457, -1, 17465, 17458, 17450, -1, 17464, 17447, 17456, -1, 17466, 17448, 17442, -1, 17466, 17442, 17458, -1, 17467, 17322, 17255, -1, 17468, 17449, 17459, -1, 17467, 17255, 17460, -1, 17468, 17457, 17449, -1, 17469, 17452, 17461, -1, 17470, 17464, 17456, -1, 17469, 17459, 17452, -1, 17470, 17456, 17462, -1, 17471, 17461, 17453, -1, 17471, 17453, 17463, -1, 17472, 17451, 17464, -1, 17472, 17455, 17451, -1, 17473, 17462, 11403, -1, 17474, 17458, 17465, -1, 17474, 17466, 17458, -1, 17475, 3459, 3455, -1, 17475, 3455, 17454, -1, 17476, 17322, 17467, -1, 17475, 17448, 17466, -1, 17475, 17454, 17448, -1, 17476, 17362, 17322, -1, 17477, 11308, 11293, -1, 17477, 17463, 11308, -1, 17478, 17472, 17464, -1, 17478, 17464, 17470, -1, 17479, 17465, 17457, -1, 17480, 17460, 17455, -1, 17479, 17457, 17468, -1, 17480, 17455, 17472, -1, 17481, 17468, 17459, -1, 17482, 17470, 17462, -1, 17481, 17459, 17469, -1, 17482, 17462, 17473, -1, 17483, 17469, 17461, -1, 17483, 17461, 17471, -1, 17484, 11403, 11394, -1, 17485, 17466, 17474, -1, 17484, 17473, 11403, -1, 17485, 3459, 17475, -1, 17486, 17402, 17362, -1, 17486, 3465, 17402, -1, 17485, 17475, 17466, -1, 17486, 17362, 17476, -1, 17487, 17477, 11293, -1, 17486, 3469, 3465, -1, 17488, 17480, 17472, -1, 17488, 17472, 17478, -1, 17489, 17471, 17463, -1, 17490, 17467, 17460, -1, 17490, 17460, 17480, -1, 17489, 17463, 17477, -1, 17491, 17474, 17465, -1, 17492, 17470, 17482, -1, 17491, 17465, 17479, -1, 17492, 17478, 17470, -1, 17493, 17468, 17481, -1, 17494, 17482, 17473, -1, 17493, 17479, 17468, -1, 17494, 17473, 17484, -1, 17495, 17469, 17483, -1, 17495, 17481, 17469, -1, 17496, 17484, 11394, -1, 17497, 17477, 17487, -1, 17497, 17489, 17477, -1, 17498, 17490, 17480, -1, 17498, 17480, 17488, -1, 17499, 17471, 17489, -1, 17500, 17476, 17467, -1, 17500, 17467, 17490, -1, 17499, 17483, 17471, -1, 17501, 3463, 3459, -1, 17502, 17488, 17478, -1, 17501, 3459, 17485, -1, 17502, 17478, 17492, -1, 17501, 17474, 17491, -1, 17501, 17485, 17474, -1, 17503, 17491, 17479, -1, 17503, 17479, 17493, -1, 17504, 17482, 17494, -1, 17505, 17493, 17481, -1, 17504, 17492, 17482, -1, 17506, 17494, 17484, -1, 17505, 17481, 17495, -1, 17506, 17484, 17496, -1, 17507, 17489, 17497, -1, 17508, 17490, 17498, -1, 17507, 17499, 17489, -1, 17508, 17500, 17490, -1, 17509, 17486, 17476, -1, 17510, 11293, 11284, -1, 17509, 3469, 17486, -1, 17509, 17476, 17500, -1, 17510, 17487, 11293, -1, 17509, 3473, 3469, -1, 17511, 17496, 11394, -1, 17512, 17495, 17483, -1, 17511, 11394, 11386, -1, 17512, 17483, 17499, -1, 17513, 17501, 17491, -1, 17514, 17498, 17488, -1, 17514, 17488, 17502, -1, 17513, 17491, 17503, -1, 17513, 3463, 17501, -1, 17515, 17502, 17492, -1, 17516, 17503, 17493, -1, 17515, 17492, 17504, -1, 17516, 17493, 17505, -1, 17517, 17504, 17494, -1, 17517, 17494, 17506, -1, 17518, 17499, 17507, -1, 17518, 17512, 17499, -1, 17519, 17497, 17487, -1, 17519, 17487, 17510, -1, 17520, 17500, 17508, -1, 17520, 17509, 17500, -1, 17520, 3473, 17509, -1, 17521, 17511, 11386, -1, 17522, 17505, 17495, -1, 17522, 17495, 17512, -1, 17523, 3467, 3463, -1, 17524, 17496, 17511, -1, 17523, 3463, 17513, -1, 17523, 17513, 17503, -1, 17524, 17506, 17496, -1, 17523, 17503, 17516, -1, 17525, 17508, 17498, -1, 17525, 17498, 17514, -1, 17526, 17512, 17518, -1, 17526, 17522, 17512, -1, 17527, 17507, 17497, -1, 17528, 17514, 17502, -1, 17527, 17497, 17519, -1, 17528, 17502, 17515, -1, 17529, 17515, 17504, -1, 17529, 17504, 17517, -1, 17530, 17505, 17522, -1, 17530, 17516, 17505, -1, 17531, 17524, 17511, -1, 17532, 11284, 11282, -1, 17532, 17510, 11284, -1, 17531, 17511, 17521, -1, 17533, 17517, 17506, -1, 17533, 17506, 17524, -1, 17534, 17530, 17522, -1, 17534, 17522, 17526, -1, 17535, 17508, 17525, -1, 17535, 17520, 17508, -1, 17535, 3477, 3473, -1, 17536, 17518, 17507, -1, 17535, 3473, 17520, -1, 17536, 17507, 17527, -1, 17537, 17525, 17514, -1, 17538, 3467, 17523, -1, 17537, 17514, 17528, -1, 17539, 17528, 17515, -1, 17538, 17523, 17516, -1, 17538, 17516, 17530, -1, 17540, 17519, 17510, -1, 17539, 17515, 17529, -1, 17540, 17510, 17532, -1, 17541, 17524, 17531, -1, 17542, 3467, 17538, -1, 17542, 3471, 3467, -1, 17541, 17533, 17524, -1, 17542, 17530, 17534, -1, 17542, 17538, 17530, -1, 17543, 11386, 11390, -1, 17544, 17518, 17536, -1, 17544, 17526, 17518, -1, 17543, 17521, 11386, -1, 17545, 17517, 17533, -1, 17545, 17529, 17517, -1, 17546, 17519, 17540, -1, 17546, 17527, 17519, -1, 17547, 3477, 17535, -1, 17547, 17535, 17525, -1, 17547, 17525, 17537, -1, 17548, 11282, 11661, -1, 17548, 17532, 11282, -1, 17549, 17537, 17528, -1, 17549, 17528, 17539, -1, 17550, 17534, 17526, -1, 17551, 17545, 17533, -1, 17550, 17526, 17544, -1, 17551, 17533, 17541, -1, 17552, 11661, 11652, -1, 17553, 17531, 17521, -1, 17552, 17548, 11661, -1, 17553, 17521, 17543, -1, 17554, 17529, 17545, -1, 17555, 17536, 17527, -1, 17554, 17539, 17529, -1, 17555, 17527, 17546, -1, 17556, 17547, 17537, -1, 17556, 3477, 17547, -1, 17556, 17537, 17549, -1, 17557, 17540, 17532, -1, 17557, 17532, 17548, -1, 17556, 3481, 3477, -1, 17558, 17554, 17545, -1, 17558, 17545, 17551, -1, 17559, 17534, 17550, -1, 17559, 3471, 17542, -1, 17560, 17541, 17531, -1, 17559, 17542, 17534, -1, 17561, 17557, 17548, -1, 17560, 17531, 17553, -1, 17562, 17549, 17539, -1, 17561, 17548, 17552, -1, 17562, 17539, 17554, -1, 17563, 17544, 17536, -1, 17563, 17536, 17555, -1, 17564, 17543, 11390, -1, 17564, 11390, 11399, -1, 17565, 17562, 17554, -1, 17566, 17540, 17557, -1, 17565, 17554, 17558, -1, 17566, 17546, 17540, -1, 17567, 17551, 17541, -1, 17567, 17541, 17560, -1, 17568, 17552, 11652, -1, 17569, 17566, 17557, -1, 17570, 17556, 17549, -1, 17570, 3481, 17556, -1, 17569, 17557, 17561, -1, 17570, 17549, 17562, -1, 17571, 17553, 17543, -1, 17572, 17544, 17563, -1, 17572, 17550, 17544, -1, 17571, 17543, 17564, -1, 17573, 17555, 17546, -1, 17573, 17546, 17566, -1, 17574, 3481, 17570, -1, 17574, 17562, 17565, -1, 17574, 17570, 17562, -1, 17574, 3485, 3481, -1, 17575, 17561, 17552, -1, 17576, 17558, 17551, -1, 17575, 17552, 17568, -1, 17576, 17551, 17567, -1, 17577, 17568, 11652, -1, 17577, 11652, 11647, -1, 17578, 17560, 17553, -1, 17578, 17553, 17571, -1, 17579, 17573, 17566, -1, 17579, 17566, 17569, -1, 17580, 17559, 17550, -1, 17581, 11399, 11407, -1, 17580, 3475, 3471, -1, 17580, 3471, 17559, -1, 17581, 17564, 11399, -1, 17580, 17550, 17572, -1, 17582, 17565, 17558, -1, 17582, 17558, 17576, -1, 17583, 17563, 17555, -1, 17583, 17555, 17573, -1, 17584, 11407, 11420, -1, 17585, 17569, 17561, -1, 17584, 17581, 11407, -1, 17586, 17560, 17578, -1, 17585, 17561, 17575, -1, 17586, 17567, 17560, -1, 17587, 17575, 17568, -1, 17587, 17568, 17577, -1, 17588, 17564, 17581, -1, 17589, 17577, 11647, -1, 17588, 17571, 17564, -1, 17590, 17573, 17579, -1, 17590, 17583, 17573, -1, 17591, 17574, 17565, -1, 17591, 3485, 17574, -1, 17592, 17572, 17563, -1, 17591, 17565, 17582, -1, 17592, 17563, 17583, -1, 17593, 17569, 17585, -1, 17594, 17581, 17584, -1, 17594, 17588, 17581, -1, 17593, 17579, 17569, -1, 17595, 17585, 17575, -1, 17596, 17576, 17567, -1, 17596, 17567, 17586, -1, 17595, 17575, 17587, -1, 17597, 17571, 17588, -1, 17597, 17578, 17571, -1, 17598, 17587, 17577, -1, 17598, 17577, 17589, -1, 17599, 17584, 11420, -1, 17600, 17583, 17590, -1, 17600, 17592, 17583, -1, 17601, 3479, 3475, -1, 17602, 17588, 17594, -1, 17601, 3475, 17580, -1, 17602, 17597, 17588, -1, 17601, 17580, 17572, -1, 17601, 17572, 17592, -1, 17603, 17582, 17576, -1, 17604, 11647, 11638, -1, 17604, 17589, 11647, -1, 17603, 17576, 17596, -1, 17605, 17590, 17579, -1, 17606, 17578, 17597, -1, 17605, 17579, 17593, -1, 17606, 17586, 17578, -1, 17607, 17585, 17595, -1, 17607, 17593, 17585, -1, 17608, 17584, 17599, -1, 17608, 17594, 17584, -1, 17609, 17599, 11420, -1, 17610, 17595, 17587, -1, 17610, 17587, 17598, -1, 17609, 11420, 11434, -1, 17611, 17592, 17600, -1, 17612, 17597, 17602, -1, 17611, 3479, 17601, -1, 17612, 17606, 17597, -1, 17611, 17601, 17592, -1, 17613, 17591, 17582, -1, 17613, 17582, 17603, -1, 17614, 17604, 11638, -1, 17613, 3489, 3485, -1, 17613, 3485, 17591, -1, 17615, 17598, 17589, -1, 17616, 17596, 17586, -1, 17615, 17589, 17604, -1, 17617, 17590, 17605, -1, 17616, 17586, 17606, -1, 17617, 17600, 17590, -1, 17618, 17602, 17594, -1, 17619, 17605, 17593, -1, 17618, 17594, 17608, -1, 17619, 17593, 17607, -1, 17620, 17608, 17599, -1, 17620, 17599, 17609, -1, 17621, 17607, 17595, -1, 17621, 17595, 17610, -1, 17622, 17609, 11434, -1, 17623, 17606, 17612, -1, 17623, 17616, 17606, -1, 17624, 17604, 17614, -1, 17624, 17615, 17604, -1, 17625, 17603, 17596, -1, 17625, 17596, 17616, -1, 17626, 17610, 17598, -1, 17626, 17598, 17615, -1, 17627, 3483, 3479, -1, 17627, 3479, 17611, -1, 17628, 17602, 17618, -1, 17627, 17611, 17600, -1, 17627, 17600, 17617, -1, 17628, 17612, 17602, -1, 17629, 17617, 17605, -1, 17630, 17618, 17608, -1, 17629, 17605, 17619, -1, 17631, 17607, 17621, -1, 17630, 17608, 17620, -1, 17632, 17620, 17609, -1, 17631, 17619, 17607, -1, 17632, 17609, 17622, -1, 17633, 11638, 11625, -1, 17634, 17616, 17623, -1, 17634, 17625, 17616, -1, 17633, 17614, 11638, -1, 17635, 17626, 17615, -1, 17636, 17613, 17603, -1, 17636, 17603, 17625, -1, 17636, 3489, 17613, -1, 17635, 17615, 17624, -1, 17637, 17621, 17610, -1, 17636, 3493, 3489, -1, 17637, 17610, 17626, -1, 17638, 17622, 11434, -1, 17638, 11434, 11448, -1, 17639, 17627, 17617, -1, 17640, 17623, 17612, -1, 17639, 17617, 17629, -1, 17640, 17612, 17628, -1, 17639, 3483, 17627, -1, 17641, 17629, 17619, -1, 17642, 17618, 17630, -1, 17641, 17619, 17631, -1, 17642, 17628, 17618, -1, 17643, 17624, 17614, -1, 17644, 17620, 17632, -1, 17644, 17630, 17620, -1, 17643, 17614, 17633, -1, 17645, 17637, 17626, -1, 17646, 17636, 17625, -1, 17646, 17625, 17634, -1, 17645, 17626, 17635, -1, 17646, 3493, 17636, -1, 17647, 17631, 17621, -1, 17647, 17621, 17637, -1, 17648, 17638, 11448, -1, 17649, 3487, 3483, -1, 17649, 17639, 17629, -1, 17649, 17629, 17641, -1, 17650, 17622, 17638, -1, 17650, 17632, 17622, -1, 17649, 3483, 17639, -1, 17651, 17624, 17643, -1, 17652, 17634, 17623, -1, 17651, 17635, 17624, -1, 17652, 17623, 17640, -1, 17653, 17628, 17642, -1, 17653, 17640, 17628, -1, 17654, 17637, 17645, -1, 17654, 17647, 17637, -1, 17655, 17631, 17647, -1, 17656, 17642, 17630, -1, 17655, 17641, 17631, -1, 17656, 17630, 17644, -1, 17657, 17633, 11625, -1, 17657, 11625, 11616, -1, 17658, 17650, 17638, -1, 17658, 17638, 17648, -1, 17659, 17644, 17632, -1, 17660, 17645, 17635, -1, 17659, 17632, 17650, -1, 17660, 17635, 17651, -1, 17661, 17646, 17634, -1, 17662, 17647, 17654, -1, 17661, 17634, 17652, -1, 17662, 17655, 17647, -1, 17661, 3493, 17646, -1, 17661, 3497, 3493, -1, 17663, 3487, 17649, -1, 17663, 17649, 17641, -1, 17664, 17652, 17640, -1, 17663, 17641, 17655, -1, 17664, 17640, 17653, -1, 17665, 17643, 17633, -1, 17665, 17633, 17657, -1, 17666, 17653, 17642, -1, 17666, 17642, 17656, -1, 17667, 17654, 17645, -1, 17211, 11448, 11460, -1, 17211, 17648, 11448, -1, 17667, 17645, 17660, -1, 17668, 3491, 3487, -1, 17668, 3487, 17663, -1, 17669, 17650, 17658, -1, 17668, 17655, 17662, -1, 17668, 17663, 17655, -1, 17670, 17651, 17643, -1, 17669, 17659, 17650, -1, 17671, 17644, 17659, -1, 17670, 17643, 17665, -1, 17671, 17656, 17644, -1, 17672, 3497, 17661, -1, 17046, 11616, 11606, -1, 17672, 17661, 17652, -1, 17046, 17657, 11616, -1, 17672, 17652, 17664, -1, 17051, 17664, 17653, -1, 17051, 17653, 17666, -1, 17055, 17654, 17667, -1, 17055, 17662, 17654, -1, 17210, 17658, 17648, -1, 17210, 17648, 17211, -1, 17062, 17651, 17670, -1, 17062, 17660, 17651, -1, 17059, 17659, 17669, -1, 17059, 17671, 17659, -1, 17048, 17665, 17657, -1, 17044, 17656, 17671, -1, 17048, 17657, 17046, -1, 17044, 17666, 17656, -1, 17054, 3491, 17668, -1, 17050, 3497, 17672, -1, 17054, 17668, 17662, -1, 17050, 17664, 17051, -1, 17054, 17662, 17055, -1, 17050, 3501, 3497, -1, 17064, 17667, 17660, -1, 17050, 17672, 17664, -1, 17075, 17669, 17658, -1, 17075, 17658, 17210, -1, 17064, 17660, 17062, -1, 17067, 17665, 17048, -1, 17058, 17044, 17671, -1, 17067, 17670, 17665, -1, 17058, 17671, 17059, -1, 17043, 17051, 17666, -1, 17043, 17666, 17044, -1, 17047, 17046, 11606, -1, 17047, 11606, 11597, -1, 17056, 17055, 17667, -1, 17056, 17667, 17064, -1, 17060, 17059, 17669, -1, 17060, 17669, 17075, -1, 17063, 17062, 17670, -1, 17063, 17670, 17067, -1, 17042, 17044, 17058, -1, 17673, 17674, 17675, -1, 17009, 17033, 17676, -1, 17677, 17678, 17679, -1, 17677, 17679, 17674, -1, 17677, 17673, 17680, -1, 17677, 17674, 17673, -1, 17681, 17682, 17678, -1, 17681, 17678, 17677, -1, 17683, 17680, 17684, -1, 17683, 17684, 17685, -1, 17683, 17677, 17680, -1, 17686, 17010, 17009, -1, 17686, 17676, 17682, -1, 17686, 17682, 17681, -1, 17686, 17009, 17676, -1, 17687, 17685, 17688, -1, 17687, 17688, 17689, -1, 17687, 17689, 17690, -1, 17687, 17683, 17685, -1, 17687, 17677, 17683, -1, 17687, 17681, 17677, -1, 17691, 17690, 17692, -1, 17691, 17692, 17026, -1, 17691, 17026, 17010, -1, 17691, 17010, 17686, -1, 17691, 17687, 17690, -1, 17691, 17686, 17681, -1, 17691, 17681, 17687, -1, 17693, 17694, 17695, -1, 17693, 11221, 17694, -1, 17696, 17695, 17697, -1, 17696, 17693, 17695, -1, 17698, 17697, 17699, -1, 17698, 17700, 17697, -1, 17698, 17699, 17701, -1, 17702, 17701, 11853, -1, 17702, 17698, 17701, -1, 17703, 17702, 11853, -1, 17703, 11853, 11852, -1, 17703, 11852, 17704, -1, 17703, 17704, 17705, -1, 17706, 17698, 17702, -1, 17706, 17703, 17705, -1, 17706, 17702, 17703, -1, 17706, 17705, 17700, -1, 17706, 17700, 17698, -1, 17707, 11221, 17693, -1, 17707, 17693, 17696, -1, 17708, 17707, 17696, -1, 17708, 11230, 11221, -1, 17708, 17709, 11230, -1, 17708, 17697, 17709, -1, 17708, 17696, 17697, -1, 17708, 11221, 17707, -1, 17710, 17711, 11865, -1, 17710, 11865, 11860, -1, 17712, 17713, 17711, -1, 17712, 17714, 17713, -1, 17712, 17711, 17710, -1, 17715, 17712, 17710, -1, 17716, 17712, 17715, -1, 17716, 17714, 17712, -1, 17717, 17718, 17714, -1, 17717, 11223, 17718, -1, 17717, 11221, 11223, -1, 17717, 17714, 17716, -1, 17697, 17695, 17719, -1, 17700, 17709, 17697, -1, 17705, 17704, 17720, -1, 17721, 11230, 17709, -1, 17721, 17709, 17700, -1, 17721, 17700, 17705, -1, 17722, 17723, 17724, -1, 17722, 17720, 17723, -1, 17722, 17705, 17720, -1, 17722, 17721, 17705, -1, 17725, 11230, 17721, -1, 17726, 17724, 11234, -1, 17726, 11234, 11230, -1, 17726, 17722, 17724, -1, 17726, 17721, 17722, -1, 17726, 11230, 17725, -1, 17726, 17725, 17721, -1, 17727, 17715, 17710, -1, 17727, 17710, 11860, -1, 17727, 17695, 17716, -1, 17727, 17716, 17715, -1, 17728, 17727, 11860, -1, 17728, 17695, 17727, -1, 17729, 17719, 17695, -1, 17729, 17728, 11860, -1, 17729, 17695, 17728, -1, 17699, 11860, 11853, -1, 17699, 17697, 17719, -1, 17699, 17719, 17729, -1, 17699, 17729, 11860, -1, 17701, 17699, 11853, -1, 17694, 17716, 17695, -1, 17694, 17717, 17716, -1, 17694, 11221, 17717, -1, 17730, 17731, 17732, -1, 17733, 17734, 17735, -1, 17736, 3496, 3500, -1, 17733, 17737, 17734, -1, 17736, 17738, 3496, -1, 17739, 17740, 17741, -1, 17739, 11698, 11686, -1, 17742, 17743, 17744, -1, 17739, 11686, 17740, -1, 17739, 17741, 17745, -1, 17742, 17744, 17746, -1, 17747, 17745, 17748, -1, 17749, 17750, 17751, -1, 17747, 17748, 17752, -1, 17753, 17754, 17755, -1, 17749, 17751, 17756, -1, 17753, 17732, 17754, -1, 17757, 17735, 17730, -1, 17758, 17759, 17738, -1, 17757, 17733, 17735, -1, 17760, 17752, 17737, -1, 17758, 17738, 17736, -1, 17761, 17736, 3500, -1, 17760, 17737, 17733, -1, 17762, 17763, 17743, -1, 17764, 17739, 17745, -1, 17762, 11828, 11815, -1, 17764, 17745, 17747, -1, 17764, 11698, 17739, -1, 17762, 11815, 17763, -1, 17762, 17743, 17742, -1, 17765, 17730, 17732, -1, 17766, 17746, 17750, -1, 17765, 17732, 17753, -1, 17766, 17750, 17749, -1, 17767, 17733, 17757, -1, 17768, 17759, 17758, -1, 17767, 17760, 17733, -1, 17768, 17756, 17759, -1, 17769, 17752, 17760, -1, 17769, 17747, 17752, -1, 17770, 17755, 3502, -1, 17771, 17736, 17761, -1, 17771, 17758, 17736, -1, 17770, 3502, 3506, -1, 17772, 17761, 3500, -1, 17772, 3500, 3504, -1, 17773, 17730, 17765, -1, 17773, 17757, 17730, -1, 17774, 17746, 17766, -1, 17775, 17760, 17767, -1, 17774, 17742, 17746, -1, 17775, 17769, 17760, -1, 17776, 17749, 17756, -1, 17777, 11698, 17764, -1, 17776, 17756, 17768, -1, 17777, 11718, 11698, -1, 17777, 17747, 17769, -1, 17777, 17764, 17747, -1, 17778, 17768, 17758, -1, 17779, 17753, 17755, -1, 17779, 17755, 17770, -1, 17778, 17758, 17771, -1, 17780, 17771, 17761, -1, 17780, 17761, 17772, -1, 17781, 17767, 17757, -1, 17781, 17757, 17773, -1, 17782, 17762, 17742, -1, 17782, 11828, 17762, -1, 17783, 11718, 17777, -1, 17782, 17742, 17774, -1, 17783, 17769, 17775, -1, 17782, 11834, 11828, -1, 17783, 17777, 17769, -1, 17784, 17772, 3504, -1, 17785, 17765, 17753, -1, 17786, 17766, 17749, -1, 17786, 17749, 17776, -1, 17785, 17753, 17779, -1, 17787, 17770, 3506, -1, 17787, 3506, 3510, -1, 17788, 17768, 17778, -1, 17789, 17767, 17781, -1, 17789, 17775, 17767, -1, 17788, 17776, 17768, -1, 17790, 17771, 17780, -1, 17790, 17778, 17771, -1, 17791, 17773, 17765, -1, 17792, 3504, 3508, -1, 17792, 17784, 3504, -1, 17791, 17765, 17785, -1, 17793, 17780, 17772, -1, 17793, 17772, 17784, -1, 17794, 17770, 17787, -1, 17794, 17779, 17770, -1, 17795, 17774, 17766, -1, 17796, 11726, 11718, -1, 17795, 17766, 17786, -1, 17796, 17783, 17775, -1, 17796, 17775, 17789, -1, 17796, 11718, 17783, -1, 17797, 17786, 17776, -1, 17797, 17776, 17788, -1, 17798, 17773, 17791, -1, 17798, 17781, 17773, -1, 17799, 17788, 17778, -1, 17799, 17778, 17790, -1, 17800, 17785, 17779, -1, 17800, 17779, 17794, -1, 17801, 17793, 17784, -1, 17801, 17784, 17792, -1, 17802, 3510, 3420, -1, 17802, 17787, 3510, -1, 17803, 17790, 17780, -1, 17803, 17780, 17793, -1, 17804, 17782, 17774, -1, 17804, 11834, 17782, -1, 17804, 17774, 17795, -1, 17805, 17785, 17800, -1, 17804, 11845, 11834, -1, 17805, 17791, 17785, -1, 17806, 17786, 17797, -1, 17806, 17795, 17786, -1, 17807, 17802, 3420, -1, 17808, 17797, 17788, -1, 17808, 17788, 17799, -1, 17809, 17794, 17787, -1, 17809, 17787, 17802, -1, 17810, 17792, 3508, -1, 17811, 17793, 17801, -1, 17811, 17803, 17793, -1, 17812, 17799, 17790, -1, 17812, 17790, 17803, -1, 17813, 17798, 17791, -1, 17813, 17791, 17805, -1, 17814, 17802, 17807, -1, 17815, 17804, 17795, -1, 17815, 11845, 17804, -1, 17814, 17809, 17802, -1, 17815, 17795, 17806, -1, 17815, 11854, 11845, -1, 17816, 17794, 17809, -1, 17817, 17797, 17808, -1, 17817, 17806, 17797, -1, 17816, 17800, 17794, -1, 17818, 17801, 17792, -1, 17819, 17807, 3420, -1, 17818, 17792, 17810, -1, 17819, 3420, 3421, -1, 17820, 17798, 17813, -1, 17821, 17803, 17811, -1, 17821, 17812, 17803, -1, 17820, 17822, 17798, -1, 17823, 17809, 17814, -1, 17824, 17808, 17799, -1, 17824, 17799, 17812, -1, 17823, 17816, 17809, -1, 17825, 17800, 17816, -1, 17826, 17815, 17806, -1, 17826, 17806, 17817, -1, 17825, 17805, 17800, -1, 17826, 11854, 17815, -1, 17827, 17811, 17801, -1, 17828, 17807, 17819, -1, 17827, 17801, 17818, -1, 17829, 17812, 17821, -1, 17828, 17814, 17807, -1, 17829, 17824, 17812, -1, 17830, 17819, 3421, -1, 17831, 17808, 17824, -1, 17831, 17817, 17808, -1, 17832, 17833, 17822, -1, 17832, 11753, 11744, -1, 17832, 11744, 17833, -1, 17832, 17822, 17820, -1, 17834, 17825, 17816, -1, 17835, 17811, 17827, -1, 17834, 17816, 17823, -1, 17835, 17821, 17811, -1, 17836, 17805, 17825, -1, 17837, 17831, 17824, -1, 17836, 17813, 17805, -1, 17837, 17824, 17829, -1, 17838, 17814, 17828, -1, 17839, 11854, 17826, -1, 17839, 17817, 17831, -1, 17839, 11866, 11854, -1, 17839, 17826, 17817, -1, 17838, 17823, 17814, -1, 17840, 17830, 3421, -1, 17840, 3421, 3429, -1, 17841, 17829, 17821, -1, 17842, 17819, 17830, -1, 17842, 17828, 17819, -1, 17841, 17821, 17835, -1, 17843, 17831, 17837, -1, 17843, 11866, 17839, -1, 17844, 17836, 17825, -1, 17844, 17825, 17834, -1, 17843, 17839, 17831, -1, 17845, 17813, 17836, -1, 17845, 17820, 17813, -1, 17846, 3417, 3422, -1, 17847, 17834, 17823, -1, 17847, 17823, 17838, -1, 17846, 17848, 3417, -1, 17849, 17842, 17830, -1, 17850, 17829, 17841, -1, 17850, 17837, 17829, -1, 17849, 17830, 17840, -1, 17851, 17838, 17828, -1, 17851, 17828, 17842, -1, 17852, 17848, 17846, -1, 17852, 17853, 17848, -1, 17854, 17836, 17844, -1, 17854, 17845, 17836, -1, 17855, 11773, 11753, -1, 17856, 11866, 17843, -1, 17856, 17843, 17837, -1, 17856, 17837, 17850, -1, 17855, 17832, 17820, -1, 17855, 17820, 17845, -1, 17856, 11878, 11866, -1, 17855, 11753, 17832, -1, 17857, 17834, 17847, -1, 17857, 17844, 17834, -1, 17858, 17840, 3429, -1, 17859, 17860, 17853, -1, 17859, 17853, 17852, -1, 17861, 3422, 3424, -1, 17862, 17842, 17849, -1, 17861, 17846, 3422, -1, 17862, 17851, 17842, -1, 17863, 17838, 17851, -1, 17863, 17847, 17838, -1, 17864, 11782, 11773, -1, 17865, 17860, 17859, -1, 17865, 17866, 17860, -1, 17864, 11773, 17855, -1, 17864, 17845, 17854, -1, 17864, 17855, 17845, -1, 17867, 17854, 17844, -1, 17867, 17844, 17857, -1, 17868, 17861, 3424, -1, 17869, 17840, 17858, -1, 17870, 17852, 17846, -1, 17869, 17849, 17840, -1, 17870, 17846, 17861, -1, 17871, 17863, 17851, -1, 17871, 17851, 17862, -1, 17872, 17873, 17866, -1, 17872, 17866, 17865, -1, 17874, 17857, 17847, -1, 17874, 17847, 17863, -1, 17875, 17861, 17868, -1, 17876, 11782, 17864, -1, 17876, 17854, 17867, -1, 17875, 17870, 17861, -1, 17876, 17864, 17854, -1, 17877, 17849, 17869, -1, 17878, 17859, 17852, -1, 17877, 17862, 17849, -1, 17878, 17852, 17870, -1, 17879, 17874, 17863, -1, 17880, 3424, 3431, -1, 17880, 17868, 3424, -1, 17879, 17863, 17871, -1, 17881, 17882, 17873, -1, 17881, 17873, 17872, -1, 17883, 17857, 17874, -1, 17883, 17867, 17857, -1, 17884, 17878, 17870, -1, 17884, 17870, 17875, -1, 17885, 17862, 17877, -1, 17886, 17865, 17859, -1, 17885, 17871, 17862, -1, 17886, 17859, 17878, -1, 17887, 17883, 17874, -1, 17887, 17874, 17879, -1, 17888, 17876, 17867, -1, 17888, 17867, 17883, -1, 17888, 11800, 11782, -1, 17889, 17875, 17868, -1, 17888, 11782, 17876, -1, 17889, 17868, 17880, -1, 17890, 17879, 17871, -1, 17890, 17871, 17885, -1, 17891, 17880, 3431, -1, 17892, 17893, 17882, -1, 17892, 11893, 17893, -1, 17892, 17882, 17881, -1, 17894, 17883, 17887, -1, 17892, 11900, 11893, -1, 17894, 11800, 17888, -1, 17894, 17888, 17883, -1, 17895, 17879, 17890, -1, 17896, 17886, 17878, -1, 17896, 17878, 17884, -1, 17895, 17887, 17879, -1, 17897, 11805, 11800, -1, 17897, 11800, 17894, -1, 17897, 17894, 17887, -1, 17898, 17872, 17865, -1, 17897, 17887, 17895, -1, 17898, 17865, 17886, -1, 17899, 17875, 17889, -1, 17899, 17884, 17875, -1, 17900, 17901, 17902, -1, 17903, 3431, 3438, -1, 17900, 17904, 17901, -1, 17903, 17891, 3431, -1, 17900, 11868, 17905, -1, 17906, 17880, 17891, -1, 17900, 17905, 17904, -1, 17906, 17889, 17880, -1, 17907, 17886, 17896, -1, 17907, 17898, 17886, -1, 17908, 17872, 17898, -1, 17909, 17910, 17911, -1, 17908, 17881, 17872, -1, 17909, 17911, 17912, -1, 17909, 17912, 17913, -1, 17914, 17884, 17899, -1, 17914, 17896, 17884, -1, 17915, 17906, 17891, -1, 17916, 17917, 17918, -1, 17916, 17918, 11995, -1, 17916, 17919, 17920, -1, 17916, 17920, 17921, -1, 17915, 17891, 17903, -1, 17916, 17921, 17917, -1, 17922, 17899, 17889, -1, 17916, 11995, 17919, -1, 17923, 17822, 17833, -1, 17922, 17889, 17906, -1, 17923, 17796, 17789, -1, 17924, 17898, 17907, -1, 17924, 17908, 17898, -1, 17925, 17892, 17881, -1, 17925, 11900, 17892, -1, 17925, 17881, 17908, -1, 17925, 11910, 11900, -1, 17926, 17895, 17927, -1, 17928, 17907, 17896, -1, 17926, 17897, 17895, -1, 17928, 17896, 17914, -1, 17926, 17927, 3817, -1, 17929, 17901, 17904, -1, 17930, 17903, 3438, -1, 17929, 17931, 17932, -1, 17933, 3980, 3426, -1, 17929, 17904, 17931, -1, 17934, 17902, 17901, -1, 17933, 3426, 3428, -1, 17935, 17922, 17906, -1, 17935, 17906, 17915, -1, 17934, 17901, 17929, -1, 17934, 17936, 17937, -1, 17938, 3937, 3980, -1, 17934, 17937, 17902, -1, 17939, 17902, 17940, -1, 17939, 11868, 17900, -1, 17939, 17940, 11857, -1, 17938, 3980, 17933, -1, 17941, 17914, 17899, -1, 17939, 11857, 11868, -1, 17939, 17900, 17902, -1, 17941, 17899, 17922, -1, 17942, 17850, 17841, -1, 17943, 3903, 3937, -1, 17942, 17856, 17850, -1, 17944, 17908, 17924, -1, 17942, 17945, 17856, -1, 17944, 17925, 17908, -1, 17943, 3937, 17938, -1, 17944, 11910, 17925, -1, 17944, 11923, 11910, -1, 17946, 17924, 17907, -1, 17947, 17873, 17882, -1, 17946, 17907, 17928, -1, 17947, 17945, 17942, -1, 17947, 17882, 17893, -1, 17948, 3428, 3435, -1, 17949, 11878, 17856, -1, 17949, 17856, 17945, -1, 17948, 17933, 3428, -1, 17950, 17915, 17903, -1, 17951, 17949, 17945, -1, 17951, 17945, 17947, -1, 17951, 17947, 17893, -1, 17952, 3826, 3903, -1, 17950, 17903, 17930, -1, 17951, 11878, 17949, -1, 17951, 17893, 11893, -1, 17951, 11893, 11878, -1, 17953, 17922, 17935, -1, 17954, 17911, 17955, -1, 17954, 17912, 17911, -1, 17952, 3903, 17943, -1, 17953, 17941, 17922, -1, 17954, 17955, 17956, -1, 17957, 17948, 3435, -1, 17958, 17928, 17914, -1, 17959, 17960, 17961, -1, 17958, 17914, 17941, -1, 17959, 17913, 17912, -1, 17959, 17912, 17954, -1, 17959, 17961, 17913, -1, 17962, 11942, 17910, -1, 17963, 17933, 17948, -1, 17964, 17944, 17924, -1, 17962, 17910, 17909, -1, 17963, 17938, 17933, -1, 17964, 17924, 17946, -1, 17964, 11923, 17944, -1, 17965, 11942, 17962, -1, 17965, 17913, 17966, -1, 17967, 17935, 17915, -1, 17965, 17909, 17913, -1, 17968, 3827, 3826, -1, 17967, 17915, 17950, -1, 17965, 17966, 11948, -1, 17965, 17962, 17909, -1, 17965, 11948, 11942, -1, 17968, 3826, 17952, -1, 17969, 17920, 17970, -1, 17971, 17958, 17941, -1, 17969, 17970, 17972, -1, 17971, 17941, 17953, -1, 17973, 17948, 17957, -1, 17969, 17921, 17920, -1, 17973, 17963, 17948, -1, 17974, 17975, 17917, -1, 17976, 17946, 17928, -1, 17974, 17917, 17921, -1, 17976, 17928, 17958, -1, 17974, 17977, 17975, -1, 17978, 17938, 17963, -1, 17974, 17921, 17969, -1, 17979, 17789, 17781, -1, 17979, 17923, 17789, -1, 17980, 17979, 17781, -1, 17978, 17943, 17938, -1, 17980, 17822, 17923, -1, 17981, 3435, 3440, -1, 17980, 17923, 17979, -1, 17980, 17781, 17798, -1, 17980, 17798, 17822, -1, 17956, 17935, 17967, -1, 17956, 17953, 17935, -1, 17981, 17957, 3435, -1, 17982, 17796, 17923, -1, 17982, 11726, 17796, -1, 17983, 3749, 3827, -1, 17984, 17923, 17833, -1, 17984, 11726, 17982, -1, 17985, 17958, 17971, -1, 17984, 11744, 11726, -1, 17983, 3827, 17968, -1, 17984, 17982, 17923, -1, 17985, 17976, 17958, -1, 17984, 17833, 11744, -1, 17986, 17978, 17963, -1, 17987, 17890, 17885, -1, 17988, 17964, 17946, -1, 17987, 17895, 17890, -1, 17988, 11923, 17964, -1, 17987, 17927, 17895, -1, 17988, 17946, 17976, -1, 17986, 17963, 17973, -1, 17988, 11931, 11923, -1, 17989, 17943, 17978, -1, 17990, 17927, 17987, -1, 17990, 3781, 3800, -1, 17990, 3817, 17927, -1, 17990, 3800, 3817, -1, 17989, 17952, 17943, -1, 17991, 11805, 17897, -1, 17991, 17897, 17926, -1, 17992, 17957, 17981, -1, 17955, 17971, 17953, -1, 17993, 3557, 11805, -1, 17955, 17953, 17956, -1, 17993, 17991, 17926, -1, 17993, 11805, 17991, -1, 17992, 17973, 17957, -1, 17993, 3817, 3558, -1, 17993, 17926, 3817, -1, 17993, 3558, 3557, -1, 17994, 17932, 17995, -1, 17996, 17981, 3440, -1, 17997, 17976, 17985, -1, 17997, 17988, 17976, -1, 17994, 17929, 17932, -1, 17998, 3831, 3749, -1, 17997, 11931, 17988, -1, 17998, 3830, 3831, -1, 17998, 3749, 17983, -1, 17998, 11912, 3830, -1, 17999, 17989, 17978, -1, 18000, 17929, 17994, -1, 18000, 17994, 18001, -1, 17999, 17978, 17986, -1, 18000, 18001, 17934, -1, 17911, 17985, 17971, -1, 18000, 17934, 17929, -1, 17911, 17971, 17955, -1, 18002, 17934, 18001, -1, 18003, 17952, 17989, -1, 18003, 17968, 17952, -1, 18004, 3442, 3446, -1, 18005, 17936, 17934, -1, 18006, 17973, 17992, -1, 18004, 18007, 3442, -1, 18005, 17934, 18002, -1, 18005, 18008, 17936, -1, 18009, 17841, 17835, -1, 18009, 17942, 17841, -1, 18006, 17986, 17973, -1, 18010, 3440, 3444, -1, 18010, 17996, 3440, -1, 17910, 17985, 17911, -1, 17910, 11931, 17997, -1, 18011, 17992, 17981, -1, 17910, 11942, 11931, -1, 18012, 17942, 18009, -1, 18012, 18009, 18013, -1, 18011, 17981, 17996, -1, 17910, 17997, 17985, -1, 18012, 17947, 17942, -1, 18014, 18007, 18004, -1, 18015, 17989, 17999, -1, 18015, 18003, 17989, -1, 18016, 18012, 18013, -1, 18014, 18017, 18007, -1, 18016, 17947, 18012, -1, 18018, 17866, 17873, -1, 18018, 17947, 18016, -1, 18019, 17983, 17968, -1, 18018, 17873, 17947, -1, 18019, 17968, 18003, -1, 18020, 17956, 17967, -1, 18021, 18022, 18017, -1, 18020, 17954, 17956, -1, 18023, 17999, 17986, -1, 18023, 17986, 18006, -1, 18024, 17954, 18020, -1, 18025, 17996, 18010, -1, 18021, 18017, 18014, -1, 18026, 3446, 3450, -1, 18027, 17954, 18024, -1, 18025, 18011, 17996, -1, 18026, 18004, 3446, -1, 18028, 18006, 17992, -1, 18029, 17954, 18027, -1, 18029, 17959, 17954, -1, 18028, 17992, 18011, -1, 18030, 18022, 17960, -1, 18030, 17960, 17959, -1, 18031, 18003, 18015, -1, 18030, 18029, 18027, -1, 18030, 17959, 18029, -1, 18031, 18019, 18003, -1, 18032, 17972, 18033, -1, 18034, 17960, 18022, -1, 18034, 18022, 18021, -1, 18032, 17969, 17972, -1, 18035, 17998, 17983, -1, 18035, 17983, 18019, -1, 18035, 11912, 17998, -1, 18035, 11902, 11912, -1, 18036, 18026, 3450, -1, 18037, 18015, 17999, -1, 18038, 17974, 17969, -1, 18037, 17999, 18023, -1, 18038, 18039, 17974, -1, 18040, 18014, 18004, -1, 18038, 18032, 18039, -1, 18040, 18004, 18026, -1, 18038, 17969, 18032, -1, 18041, 18010, 3444, -1, 18042, 17974, 18039, -1, 18043, 17977, 17974, -1, 18043, 18044, 17977, -1, 18043, 17974, 18042, -1, 18045, 18028, 18011, -1, 18046, 17885, 17877, -1, 18045, 18011, 18025, -1, 18047, 17961, 17960, -1, 18046, 17987, 17885, -1, 18048, 18006, 18028, -1, 18048, 18023, 18006, -1, 18047, 17960, 18034, -1, 18049, 18019, 18031, -1, 18049, 18035, 18019, -1, 18049, 11902, 18035, -1, 18050, 17987, 18046, -1, 18051, 18040, 18026, -1, 18049, 11895, 11902, -1, 18051, 18026, 18036, -1, 18052, 17987, 18050, -1, 18053, 18015, 18037, -1, 18054, 17990, 17987, -1, 18055, 18021, 18014, -1, 18055, 18014, 18040, -1, 18054, 17987, 18052, -1, 18053, 18031, 18015, -1, 18056, 3781, 17990, -1, 18057, 18010, 18041, -1, 18056, 3771, 3781, -1, 18056, 17990, 18054, -1, 18058, 3450, 3454, -1, 18056, 18054, 18052, -1, 18057, 18025, 18010, -1, 18059, 18001, 17994, -1, 18058, 18036, 3450, -1, 18059, 18002, 18001, -1, 18060, 18028, 18045, -1, 18059, 17994, 17995, -1, 18061, 17961, 18047, -1, 18059, 17995, 18057, -1, 18060, 18048, 18028, -1, 18061, 17913, 17961, -1, 18062, 18002, 18059, -1, 18063, 18037, 18023, -1, 18062, 18005, 18002, -1, 18064, 18055, 18040, -1, 18062, 18008, 18005, -1, 18063, 18023, 18048, -1, 18064, 18040, 18051, -1, 18062, 18065, 18008, -1, 18066, 17835, 17827, -1, 18067, 11895, 18049, -1, 18067, 18049, 18031, -1, 18067, 18031, 18053, -1, 18066, 18009, 17835, -1, 18068, 18034, 18021, -1, 18068, 18021, 18055, -1, 18066, 18013, 18009, -1, 17995, 18025, 18057, -1, 18066, 18016, 18013, -1, 18069, 18016, 18066, -1, 18069, 17860, 17866, -1, 18069, 18018, 18016, -1, 18069, 17866, 18018, -1, 17995, 18045, 18025, -1, 18070, 18051, 18036, -1, 18071, 18024, 18020, -1, 18072, 18048, 18060, -1, 18070, 18036, 18058, -1, 18071, 18020, 17967, -1, 18071, 17967, 17950, -1, 18072, 18063, 18048, -1, 18073, 18022, 18030, -1, 18073, 18017, 18022, -1, 18074, 18053, 18037, -1, 18075, 18058, 3454, -1, 18074, 18037, 18063, -1, 18073, 18027, 18024, -1, 18073, 18030, 18027, -1, 18073, 18024, 18071, -1, 18076, 17966, 17913, -1, 18076, 11948, 17966, -1, 18076, 17913, 18061, -1, 18077, 18033, 18078, -1, 18076, 11958, 11948, -1, 18077, 18042, 18039, -1, 18079, 18055, 18064, -1, 18077, 18032, 18033, -1, 17932, 18060, 18045, -1, 18077, 18039, 18032, -1, 17932, 18045, 17995, -1, 18080, 18042, 18077, -1, 18080, 18081, 18044, -1, 18079, 18068, 18055, -1, 18082, 18047, 18034, -1, 18080, 18044, 18043, -1, 18080, 18043, 18042, -1, 18083, 18063, 18072, -1, 18082, 18034, 18068, -1, 18084, 18046, 17877, -1, 18083, 18074, 18063, -1, 18084, 17877, 17869, -1, 18084, 18050, 18046, -1, 18085, 18053, 18074, -1, 18086, 18064, 18051, -1, 18087, 18050, 18084, -1, 18085, 11880, 11895, -1, 18086, 18051, 18070, -1, 18085, 18067, 18053, -1, 18085, 11895, 18067, -1, 18087, 3764, 3771, -1, 18087, 18052, 18050, -1, 18087, 3771, 18056, -1, 18088, 18070, 18058, -1, 18087, 18056, 18052, -1, 18088, 18058, 18075, -1, 18089, 18059, 18057, -1, 17931, 18060, 17932, -1, 18089, 18057, 18041, -1, 17931, 18072, 18060, -1, 18090, 3454, 3458, -1, 18090, 18075, 3454, -1, 18091, 18082, 18068, -1, 18092, 18085, 18074, -1, 18091, 18068, 18079, -1, 18092, 18074, 18083, -1, 18093, 18059, 18089, -1, 18094, 18062, 18059, -1, 18092, 11880, 18085, -1, 18094, 18059, 18093, -1, 18094, 18065, 18062, -1, 18095, 18061, 18047, -1, 18094, 18096, 18065, -1, 18095, 18047, 18082, -1, 18097, 17827, 17818, -1, 18097, 18066, 17827, -1, 18098, 18079, 18064, -1, 18098, 18064, 18086, -1, 17904, 18072, 17931, -1, 18099, 18066, 18097, -1, 17904, 18083, 18072, -1, 18100, 17860, 18069, -1, 18101, 3448, 3452, -1, 18102, 18086, 18070, -1, 18100, 17853, 17860, -1, 18102, 18070, 18088, -1, 18100, 18069, 18066, -1, 18101, 18096, 3448, -1, 18100, 18066, 18099, -1, 18103, 18071, 17950, -1, 18103, 17950, 17930, -1, 18103, 18073, 18071, -1, 18104, 18088, 18075, -1, 18104, 18075, 18090, -1, 18105, 18073, 18103, -1, 18106, 18082, 18091, -1, 18106, 18095, 18082, -1, 17905, 18092, 18083, -1, 18107, 18017, 18073, -1, 17905, 11868, 11880, -1, 18107, 18007, 18017, -1, 17905, 18083, 17904, -1, 18107, 18073, 18105, -1, 18108, 18076, 18061, -1, 17905, 11880, 18092, -1, 18108, 11958, 18076, -1, 18109, 18078, 18110, -1, 18108, 18061, 18095, -1, 18108, 11967, 11958, -1, 18111, 18065, 18096, -1, 18109, 18077, 18078, -1, 18110, 18090, 3458, -1, 18111, 18096, 18101, -1, 18112, 18077, 18109, -1, 18113, 18091, 18079, -1, 18113, 18079, 18098, -1, 18114, 18081, 18080, -1, 18114, 18115, 18081, -1, 18114, 18077, 18112, -1, 18114, 18080, 18077, -1, 18116, 18065, 18111, -1, 18117, 18087, 18084, -1, 18116, 18008, 18065, -1, 18118, 18098, 18086, -1, 18117, 17869, 17858, -1, 18118, 18086, 18102, -1, 18117, 18084, 17869, -1, 18119, 18102, 18088, -1, 18120, 3452, 3456, -1, 18120, 18101, 3452, -1, 18121, 18087, 18117, -1, 18119, 18088, 18104, -1, 18122, 18095, 18106, -1, 18123, 3759, 3764, -1, 18122, 18108, 18095, -1, 18123, 18087, 18121, -1, 18122, 11967, 18108, -1, 18123, 3764, 18087, -1, 18124, 18041, 3444, -1, 18122, 11975, 11967, -1, 18124, 18089, 18041, -1, 18078, 18104, 18090, -1, 18124, 18093, 18089, -1, 18078, 18090, 18110, -1, 18125, 3444, 3448, -1, 18125, 18124, 3444, -1, 18125, 18094, 18093, -1, 18125, 18096, 18094, -1, 18125, 3448, 18096, -1, 18125, 18093, 18124, -1, 18126, 17936, 18008, -1, 18126, 18008, 18116, -1, 18127, 18091, 18113, -1, 18128, 18097, 17818, -1, 18127, 18106, 18091, -1, 18128, 18099, 18097, -1, 18129, 18113, 18098, -1, 18128, 17818, 17810, -1, 18130, 17848, 17853, -1, 18130, 17853, 18100, -1, 18130, 18100, 18099, -1, 18131, 18120, 3456, -1, 18129, 18098, 18118, -1, 18130, 18099, 18128, -1, 18132, 18118, 18102, -1, 18132, 18102, 18119, -1, 18133, 3438, 3442, -1, 18134, 18101, 18120, -1, 18133, 17930, 3438, -1, 18134, 18111, 18101, -1, 18133, 18103, 17930, -1, 18133, 18105, 18103, -1, 18135, 3442, 18007, -1, 18135, 18133, 3442, -1, 18033, 18119, 18104, -1, 18135, 18107, 18105, -1, 18135, 18007, 18107, -1, 18135, 18105, 18133, -1, 18033, 18104, 18078, -1, 18136, 17936, 18126, -1, 18137, 18122, 18106, -1, 18138, 18112, 18109, -1, 18137, 18106, 18127, -1, 18138, 18110, 3458, -1, 18138, 18109, 18110, -1, 18137, 11975, 18122, -1, 18139, 3458, 3462, -1, 18139, 3462, 18115, -1, 18139, 18138, 3458, -1, 18136, 17937, 17936, -1, 18139, 18115, 18114, -1, 18140, 18113, 18129, -1, 18139, 18114, 18112, -1, 18140, 18127, 18113, -1, 18139, 18112, 18138, -1, 18141, 18120, 18131, -1, 18142, 3429, 3434, -1, 18141, 18134, 18120, -1, 18142, 17858, 3429, -1, 18142, 18121, 18117, -1, 18143, 18129, 18118, -1, 18142, 18117, 17858, -1, 18143, 18118, 18132, -1, 18144, 18123, 18121, -1, 18144, 3434, 3759, -1, 18144, 18121, 18142, -1, 18144, 3759, 18123, -1, 18144, 18142, 3434, -1, 18145, 18130, 18128, -1, 18145, 3508, 3417, -1, 18146, 18111, 18134, -1, 18145, 17848, 18130, -1, 18146, 18116, 18111, -1, 18145, 18128, 17810, -1, 18147, 3456, 3460, -1, 18145, 17810, 3508, -1, 18145, 3417, 17848, -1, 18147, 18131, 3456, -1, 17972, 18132, 18119, -1, 17972, 18119, 18033, -1, 18148, 17937, 18136, -1, 18149, 18137, 18127, -1, 18148, 17902, 17937, -1, 18149, 18127, 18140, -1, 18150, 18134, 18141, -1, 18149, 11975, 18137, -1, 18150, 18146, 18134, -1, 18149, 11986, 11975, -1, 18151, 18129, 18143, -1, 18152, 18126, 18116, -1, 18152, 18116, 18146, -1, 18151, 18140, 18129, -1, 18153, 18141, 18131, -1, 18153, 18131, 18147, -1, 17970, 18132, 17972, -1, 17970, 18143, 18132, -1, 18154, 18147, 3460, -1, 18155, 18149, 18140, -1, 18155, 18140, 18151, -1, 18156, 17940, 17902, -1, 18155, 11986, 18149, -1, 18156, 17902, 18148, -1, 18156, 11857, 17940, -1, 18156, 11847, 11857, -1, 18157, 18146, 18150, -1, 18157, 18152, 18146, -1, 18158, 18136, 18126, -1, 17920, 18151, 18143, -1, 17920, 18143, 17970, -1, 18158, 18126, 18152, -1, 18159, 3462, 3466, -1, 18160, 18150, 18141, -1, 18160, 18141, 18153, -1, 18159, 18115, 3462, -1, 18161, 18153, 18147, -1, 18161, 18147, 18154, -1, 17919, 18155, 18151, -1, 18162, 3460, 3464, -1, 17919, 18151, 17920, -1, 18162, 18154, 3460, -1, 17919, 11986, 18155, -1, 17919, 11995, 11986, -1, 18163, 18152, 18157, -1, 18164, 18081, 18115, -1, 18163, 18158, 18152, -1, 18164, 18115, 18159, -1, 18165, 18148, 18136, -1, 18165, 18136, 18158, -1, 18166, 18157, 18150, -1, 18166, 18150, 18160, -1, 18167, 18044, 18081, -1, 18168, 18160, 18153, -1, 18167, 18081, 18164, -1, 18168, 18153, 18161, -1, 18169, 3466, 3470, -1, 18169, 18159, 3466, -1, 18170, 18161, 18154, -1, 18170, 18154, 18162, -1, 18171, 18158, 18163, -1, 18171, 18165, 18158, -1, 18172, 18156, 18148, -1, 18172, 11847, 18156, -1, 18172, 18148, 18165, -1, 18173, 17977, 18044, -1, 18172, 11838, 11847, -1, 18173, 18044, 18167, -1, 18174, 18162, 3464, -1, 18175, 18169, 3470, -1, 18176, 18163, 18157, -1, 18176, 18157, 18166, -1, 18177, 18164, 18159, -1, 18178, 18166, 18160, -1, 18178, 18160, 18168, -1, 18177, 18159, 18169, -1, 18179, 18168, 18161, -1, 17918, 12005, 11995, -1, 18179, 18161, 18170, -1, 18180, 17977, 18173, -1, 18180, 17975, 17977, -1, 18181, 18172, 18165, -1, 18181, 11831, 11838, -1, 18181, 18165, 18171, -1, 18181, 11838, 18172, -1, 18182, 3464, 3468, -1, 18183, 18177, 18169, -1, 18182, 18174, 3464, -1, 18183, 18169, 18175, -1, 18184, 18162, 18174, -1, 18184, 18170, 18162, -1, 18185, 18164, 18177, -1, 18185, 18167, 18164, -1, 18186, 18171, 18163, -1, 18187, 18175, 3470, -1, 18186, 18163, 18176, -1, 18187, 3470, 3474, -1, 18188, 17917, 17975, -1, 18189, 18176, 18166, -1, 18188, 17975, 18180, -1, 18189, 18166, 18178, -1, 18190, 18177, 18183, -1, 18190, 18185, 18177, -1, 18191, 18178, 18168, -1, 18191, 18168, 18179, -1, 18192, 18173, 18167, -1, 18193, 18184, 18174, -1, 18192, 18167, 18185, -1, 18193, 18174, 18182, -1, 18194, 18170, 18184, -1, 18195, 18183, 18175, -1, 18195, 18175, 18187, -1, 18194, 18179, 18170, -1, 18196, 18187, 3474, -1, 18197, 18181, 18171, -1, 18197, 18171, 18186, -1, 18197, 11831, 18181, -1, 18198, 12017, 12005, -1, 18198, 17918, 17917, -1, 18198, 12005, 17918, -1, 18199, 18186, 18176, -1, 18198, 17917, 18188, -1, 18199, 18176, 18189, -1, 18200, 18189, 18178, -1, 18201, 18185, 18190, -1, 18200, 18178, 18191, -1, 18201, 18192, 18185, -1, 18202, 18184, 18193, -1, 18203, 18180, 18173, -1, 18203, 18173, 18192, -1, 18202, 18194, 18184, -1, 18204, 18190, 18183, -1, 18204, 18183, 18195, -1, 18205, 18182, 3468, -1, 18206, 18191, 18179, -1, 18206, 18179, 18194, -1, 18207, 18195, 18187, -1, 18207, 18187, 18196, -1, 18208, 18196, 3474, -1, 18208, 3474, 3478, -1, 18209, 18197, 18186, -1, 18209, 18186, 18199, -1, 18209, 11831, 18197, -1, 18209, 11818, 11831, -1, 18210, 18192, 18201, -1, 18211, 18199, 18189, -1, 18210, 18203, 18192, -1, 18211, 18189, 18200, -1, 18212, 18188, 18180, -1, 18213, 18194, 18202, -1, 18212, 18180, 18203, -1, 18213, 18206, 18194, -1, 18214, 18201, 18190, -1, 18215, 18182, 18205, -1, 18215, 18193, 18182, -1, 18214, 18190, 18204, -1, 18216, 18204, 18195, -1, 18216, 18195, 18207, -1, 18217, 18200, 18191, -1, 18217, 18191, 18206, -1, 18218, 18207, 18196, -1, 18219, 11818, 18209, -1, 18218, 18196, 18208, -1, 18219, 18209, 18199, -1, 18219, 18199, 18211, -1, 18220, 18206, 18213, -1, 18221, 18203, 18210, -1, 18220, 18217, 18206, -1, 18221, 18212, 18203, -1, 18222, 12029, 12017, -1, 18223, 18202, 18193, -1, 18223, 18193, 18215, -1, 18222, 12017, 18198, -1, 18222, 18198, 18188, -1, 18222, 18188, 18212, -1, 18224, 18208, 3478, -1, 18225, 18211, 18200, -1, 18225, 18200, 18217, -1, 18226, 18201, 18214, -1, 18226, 18210, 18201, -1, 18227, 3468, 3472, -1, 18227, 18205, 3468, -1, 18228, 18204, 18216, -1, 18228, 18214, 18204, -1, 18229, 18217, 18220, -1, 18229, 18225, 18217, -1, 18230, 18216, 18207, -1, 18231, 18213, 18202, -1, 18231, 18202, 18223, -1, 18230, 18207, 18218, -1, 18232, 12034, 12029, -1, 18232, 12029, 18222, -1, 18232, 18222, 18212, -1, 18233, 18211, 18225, -1, 18232, 18212, 18221, -1, 18233, 11818, 18219, -1, 18233, 18219, 18211, -1, 18234, 3478, 3482, -1, 18234, 18224, 3478, -1, 18233, 11809, 11818, -1, 18235, 18215, 18205, -1, 18235, 18205, 18227, -1, 18236, 18218, 18208, -1, 18236, 18208, 18224, -1, 18237, 18233, 18225, -1, 18237, 18225, 18229, -1, 18238, 18221, 18210, -1, 18237, 11809, 18233, -1, 18238, 18210, 18226, -1, 18239, 18220, 18213, -1, 18239, 18213, 18231, -1, 18240, 18226, 18214, -1, 18240, 18214, 18228, -1, 18241, 18223, 18215, -1, 18241, 18215, 18235, -1, 18242, 18228, 18216, -1, 18242, 18216, 18230, -1, 18243, 3472, 3476, -1, 18243, 18227, 3472, -1, 18244, 18224, 18234, -1, 18244, 18236, 18224, -1, 18245, 18229, 18220, -1, 18245, 18220, 18239, -1, 18246, 18230, 18218, -1, 18246, 18218, 18236, -1, 18247, 18221, 18238, -1, 18247, 12034, 18232, -1, 18248, 18243, 3476, -1, 18247, 18232, 18221, -1, 18249, 18231, 18223, -1, 18250, 18238, 18226, -1, 18249, 18223, 18241, -1, 18250, 18226, 18240, -1, 18251, 18240, 18228, -1, 18251, 18228, 18242, -1, 18252, 18235, 18227, -1, 18252, 18227, 18243, -1, 18253, 18246, 18236, -1, 18254, 11798, 11809, -1, 18254, 18237, 18229, -1, 18253, 18236, 18244, -1, 18254, 11809, 18237, -1, 18254, 18229, 18245, -1, 18255, 18252, 18243, -1, 18256, 18234, 3482, -1, 18257, 18242, 18230, -1, 18255, 18243, 18248, -1, 18257, 18230, 18246, -1, 18258, 18239, 18231, -1, 18259, 12038, 12034, -1, 18259, 12034, 18247, -1, 18259, 18238, 18250, -1, 18258, 18231, 18249, -1, 18259, 18247, 18238, -1, 18260, 18240, 18251, -1, 18260, 18250, 18240, -1, 18261, 18241, 18235, -1, 18261, 18235, 18252, -1, 18262, 3476, 3480, -1, 18263, 18246, 18253, -1, 18263, 18257, 18246, -1, 18262, 18248, 3476, -1, 18264, 18252, 18255, -1, 18264, 18261, 18252, -1, 18265, 18244, 18234, -1, 18265, 18234, 18256, -1, 18266, 18251, 18242, -1, 18267, 18245, 18239, -1, 18266, 18242, 18257, -1, 18267, 18239, 18258, -1, 18268, 18241, 18261, -1, 18269, 18259, 18250, -1, 18269, 18250, 18260, -1, 18268, 18249, 18241, -1, 18269, 12038, 18259, -1, 18270, 18255, 18248, -1, 18271, 18257, 18263, -1, 18271, 18266, 18257, -1, 18270, 18248, 18262, -1, 18272, 18244, 18265, -1, 18273, 18262, 3480, -1, 18272, 18253, 18244, -1, 18274, 18260, 18251, -1, 18275, 18268, 18261, -1, 18274, 18251, 18266, -1, 18275, 18261, 18264, -1, 18276, 18245, 18267, -1, 18276, 18254, 18245, -1, 18277, 18256, 3482, -1, 18277, 3482, 3486, -1, 18276, 11787, 11798, -1, 18276, 11798, 18254, -1, 18278, 18274, 18266, -1, 18279, 18249, 18268, -1, 18278, 18266, 18271, -1, 18279, 18258, 18249, -1, 18280, 18263, 18253, -1, 18281, 18264, 18255, -1, 18280, 18253, 18272, -1, 18282, 12047, 12038, -1, 18282, 12038, 18269, -1, 18281, 18255, 18270, -1, 18282, 18260, 18274, -1, 18282, 18269, 18260, -1, 18283, 18270, 18262, -1, 18283, 18262, 18273, -1, 18284, 3480, 3484, -1, 18285, 18256, 18277, -1, 18285, 18265, 18256, -1, 18284, 18273, 3480, -1, 18286, 12047, 18282, -1, 18287, 18268, 18275, -1, 18287, 18279, 18268, -1, 18286, 18274, 18278, -1, 18286, 18282, 18274, -1, 18288, 18263, 18280, -1, 18288, 18271, 18263, -1, 18289, 18267, 18258, -1, 18289, 18258, 18279, -1, 18290, 18265, 18285, -1, 18290, 18272, 18265, -1, 18291, 18275, 18264, -1, 18291, 18264, 18281, -1, 18292, 18281, 18270, -1, 18293, 3486, 3490, -1, 18293, 18277, 3486, -1, 18292, 18270, 18283, -1, 18294, 18283, 18273, -1, 18295, 18278, 18271, -1, 18294, 18273, 18284, -1, 18295, 18271, 18288, -1, 18296, 18279, 18287, -1, 18296, 18289, 18279, -1, 18297, 18293, 3490, -1, 18298, 11787, 18276, -1, 18298, 18267, 18289, -1, 18299, 18280, 18272, -1, 18299, 18272, 18290, -1, 18298, 11779, 11787, -1, 18298, 18276, 18267, -1, 18300, 18284, 3484, -1, 18301, 18287, 18275, -1, 18302, 18285, 18277, -1, 18301, 18275, 18291, -1, 18302, 18277, 18293, -1, 18303, 12052, 12047, -1, 18304, 18291, 18281, -1, 18304, 18281, 18292, -1, 18303, 12047, 18286, -1, 18303, 18278, 18295, -1, 18303, 18286, 18278, -1, 18305, 18283, 18294, -1, 18305, 18292, 18283, -1, 18306, 18293, 18297, -1, 18306, 18302, 18293, -1, 18307, 18289, 18296, -1, 18307, 18298, 18289, -1, 18308, 18280, 18299, -1, 18307, 11779, 18298, -1, 18308, 18288, 18280, -1, 18307, 11785, 11779, -1, 18309, 3484, 3488, -1, 18309, 18300, 3484, -1, 18310, 18285, 18302, -1, 18310, 18290, 18285, -1, 18311, 18294, 18284, -1, 18311, 18284, 18300, -1, 18312, 3490, 3494, -1, 18313, 18296, 18287, -1, 18312, 18297, 3490, -1, 18313, 18287, 18301, -1, 18314, 18302, 18306, -1, 18315, 18291, 18304, -1, 18314, 18310, 18302, -1, 18315, 18301, 18291, -1, 18316, 18288, 18308, -1, 18317, 18304, 18292, -1, 18316, 18295, 18288, -1, 18317, 18292, 18305, -1, 18318, 18290, 18310, -1, 18318, 18299, 18290, -1, 18319, 18300, 18309, -1, 18320, 18297, 18312, -1, 18319, 18311, 18300, -1, 18321, 18305, 18294, -1, 18321, 18294, 18311, -1, 18320, 18306, 18297, -1, 18322, 18312, 3494, -1, 18323, 18307, 18296, -1, 18323, 18296, 18313, -1, 18323, 11785, 18307, -1, 18324, 18318, 18310, -1, 18324, 18310, 18314, -1, 18325, 18313, 18301, -1, 18326, 18303, 18295, -1, 18325, 18301, 18315, -1, 18326, 11671, 12052, -1, 18326, 18295, 18316, -1, 18326, 12052, 18303, -1, 18327, 18308, 18299, -1, 18328, 18315, 18304, -1, 18327, 18299, 18318, -1, 18328, 18304, 18317, -1, 18329, 18309, 3488, -1, 18330, 18314, 18306, -1, 18331, 18321, 18311, -1, 18330, 18306, 18320, -1, 18331, 18311, 18319, -1, 18332, 18317, 18305, -1, 18333, 18320, 18312, -1, 18333, 18312, 18322, -1, 18332, 18305, 18321, -1, 18334, 11785, 18323, -1, 18334, 18323, 18313, -1, 18335, 18322, 3494, -1, 18334, 18313, 18325, -1, 18334, 11792, 11785, -1, 18335, 3494, 3498, -1, 18336, 18325, 18315, -1, 18336, 18315, 18328, -1, 18337, 18327, 18318, -1, 18337, 18318, 18324, -1, 18338, 18319, 18309, -1, 18339, 18308, 18327, -1, 18338, 18309, 18329, -1, 18339, 18316, 18308, -1, 18340, 18332, 18321, -1, 18340, 18321, 18331, -1, 18341, 18324, 18314, -1, 18341, 18314, 18330, -1, 18342, 18317, 18332, -1, 18343, 18330, 18320, -1, 18343, 18320, 18333, -1, 18342, 18328, 18317, -1, 18344, 18334, 18325, -1, 18345, 18322, 18335, -1, 18344, 18325, 18336, -1, 18344, 11792, 18334, -1, 18345, 18333, 18322, -1, 18346, 18331, 18319, -1, 18347, 18327, 18337, -1, 18347, 18339, 18327, -1, 18346, 18319, 18338, -1, 18348, 11676, 11671, -1, 18349, 18342, 18332, -1, 18349, 18332, 18340, -1, 18348, 18326, 18316, -1, 18348, 18316, 18339, -1, 18348, 11671, 18326, -1, 18350, 18328, 18342, -1, 18351, 18335, 3498, -1, 18350, 18336, 18328, -1, 18352, 18329, 3488, -1, 18352, 3488, 3492, -1, 18353, 18337, 18324, -1, 18353, 18324, 18341, -1, 18354, 18340, 18331, -1, 18355, 18330, 18343, -1, 18355, 18341, 18330, -1, 18354, 18331, 18346, -1, 18356, 18342, 18349, -1, 18356, 18350, 18342, -1, 17734, 18343, 18333, -1, 17734, 18333, 18345, -1, 18357, 18344, 18336, -1, 18357, 11792, 18344, -1, 18358, 11686, 11676, -1, 18357, 18336, 18350, -1, 18358, 11676, 18348, -1, 18357, 11804, 11792, -1, 18358, 18339, 18347, -1, 18358, 18348, 18339, -1, 18359, 18329, 18352, -1, 18359, 18338, 18329, -1, 17754, 3498, 3502, -1, 17754, 18351, 3498, -1, 17744, 18340, 18354, -1, 17731, 18335, 18351, -1, 17731, 18345, 18335, -1, 17744, 18349, 18340, -1, 18360, 18350, 18356, -1, 17741, 18347, 18337, -1, 18360, 18357, 18350, -1, 17741, 18337, 18353, -1, 18360, 11804, 18357, -1, 17751, 18346, 18338, -1, 17751, 18338, 18359, -1, 17748, 18353, 18341, -1, 17748, 18341, 18355, -1, 17738, 18352, 3492, -1, 17737, 18355, 18343, -1, 17737, 18343, 17734, -1, 17738, 3492, 3496, -1, 17743, 18349, 17744, -1, 17743, 18356, 18349, -1, 17732, 18351, 17754, -1, 17732, 17731, 18351, -1, 17750, 18354, 18346, -1, 17735, 17734, 18345, -1, 17735, 18345, 17731, -1, 17750, 18346, 17751, -1, 17740, 11686, 18358, -1, 17740, 18347, 17741, -1, 17740, 18358, 18347, -1, 17759, 18359, 18352, -1, 17759, 18352, 17738, -1, 17745, 17741, 18353, -1, 17745, 18353, 17748, -1, 17763, 18356, 17743, -1, 17763, 18360, 18356, -1, 17763, 11804, 18360, -1, 17752, 18355, 17737, -1, 17763, 11815, 11804, -1, 17752, 17748, 18355, -1, 17746, 17744, 18354, -1, 17746, 18354, 17750, -1, 17755, 17754, 3502, -1, 17730, 17735, 17731, -1, 17756, 17751, 18359, -1, 17756, 18359, 17759, -1, 3545, 4363, 3564, -1, 4179, 4995, 4203, -1, 4338, 4363, 3545, -1, 4995, 4270, 4203, -1, 3564, 4383, 3588, -1, 4203, 4270, 4228, -1, 4363, 4383, 3564, -1, 4270, 4289, 4228, -1, 3588, 4447, 3652, -1, 4228, 4289, 3561, -1, 4383, 4447, 3588, -1, 3436, 4592, 3434, -1, 3434, 4592, 3756, -1, 4289, 4328, 3561, -1, 3652, 4451, 3653, -1, 3561, 4328, 3563, -1, 4447, 4451, 3652, -1, 4592, 4633, 3756, -1, 3756, 4633, 3777, -1, 4328, 4353, 3563, -1, 3563, 4353, 3582, -1, 3653, 4490, 3671, -1, 4451, 4490, 3653, -1, 4633, 4671, 3777, -1, 3777, 4671, 3814, -1, 4353, 4378, 3582, -1, 3582, 4378, 3600, -1, 3671, 4526, 3691, -1, 4490, 4526, 3671, -1, 4671, 4698, 3814, -1, 3814, 4698, 3852, -1, 4378, 4403, 3600, -1, 3600, 4403, 3620, -1, 3691, 4562, 3720, -1, 4526, 4562, 3691, -1, 4698, 4697, 3852, -1, 3852, 4697, 3952, -1, 4403, 4422, 3620, -1, 3620, 4422, 3645, -1, 4562, 4655, 3720, -1, 3720, 4655, 3844, -1, 4422, 3427, 3645, -1, 4697, 4752, 3952, -1, 3645, 3427, 3426, -1, 3952, 4752, 3953, -1, 4655, 4658, 3844, -1, 3844, 4658, 3845, -1, 4752, 4775, 3953, -1, 3953, 4775, 3975, -1, 4658, 4699, 3845, -1, 3845, 4699, 3870, -1, 4775, 4806, 3975, -1, 3975, 4806, 4006, -1, 4699, 4724, 3870, -1, 3870, 4724, 3905, -1, 4806, 4833, 4006, -1, 4006, 4833, 4025, -1, 4724, 4712, 3905, -1, 3905, 4712, 3941, -1, 4833, 4854, 4025, -1, 4025, 4854, 4051, -1, 4712, 4711, 3941, -1, 3941, 4711, 3998, -1, 4854, 4900, 4051, -1, 4051, 4900, 4101, -1, 4711, 4791, 3998, -1, 3998, 4791, 4021, -1, 4900, 4925, 4101, -1, 4101, 4925, 4121, -1, 4791, 4817, 4021, -1, 4021, 4817, 4033, -1, 4925, 4955, 4121, -1, 4121, 4955, 4144, -1, 4817, 4846, 4033, -1, 4033, 4846, 4056, -1, 4955, 4980, 4144, -1, 4144, 4980, 4170, -1, 4846, 4873, 4056, -1, 4056, 4873, 4079, -1, 4980, 4277, 4170, -1, 4170, 4277, 4199, -1, 4873, 4893, 4079, -1, 4079, 4893, 4110, -1, 4199, 4279, 4248, -1, 4277, 4279, 4199, -1, 4893, 4940, 4110, -1, 4110, 4940, 4159, -1, 4248, 4310, 3513, -1, 4279, 4310, 4248, -1, 4940, 4966, 4159, -1, 4159, 4966, 4179, -1, 3513, 4338, 3545, -1, 4310, 4338, 3513, -1, 4966, 4995, 4179, -1, 56, 11192, 1822, -1, 11193, 11192, 56, -1, 1822, 11190, 1803, -1, 11192, 11190, 1822, -1, 1803, 11188, 1789, -1, 11190, 11188, 1803, -1, 1789, 11184, 1758, -1, 11188, 11184, 1789, -1, 1758, 11178, 1756, -1, 11184, 11178, 1758, -1, 1756, 11173, 3326, -1, 11178, 11173, 1756, -1, 1725, 11243, 1697, -1, 11244, 11243, 1725, -1, 1697, 11240, 1663, -1, 11243, 11240, 1697, -1, 1663, 11239, 1640, -1, 11240, 11239, 1663, -1, 11125, 1665, 1664, -1, 11125, 11124, 1665, -1, 1665, 11123, 1716, -1, 11124, 11123, 1665, -1, 11123, 1726, 1716, -1, 11123, 11128, 1726, -1, 1726, 11129, 1757, -1, 11128, 11129, 1726, -1, 1757, 11135, 1771, -1, 11129, 11135, 1757, -1, 1771, 11134, 52, -1, 11135, 11134, 1771, -1, 51, 11148, 1802, -1, 11149, 11148, 51, -1, 1802, 11147, 1835, -1, 11148, 11147, 1802, -1, 1835, 11152, 54, -1, 11147, 11152, 1835, -1, 54, 11153, 1863, -1, 11152, 11153, 54, -1, 1863, 11159, 1874, -1, 11153, 11159, 1863, -1, 1874, 11158, 274, -1, 11159, 11158, 1874, -1, 272, 11064, 1903, -1, 11065, 11064, 272, -1, 1903, 11063, 1927, -1, 11064, 11063, 1903, -1, 1927, 11069, 307, -1, 11063, 11069, 1927, -1, 307, 11068, 1969, -1, 11069, 11068, 307, -1, 1969, 11075, 1983, -1, 11068, 11075, 1969, -1, 1983, 11074, 605, -1, 11075, 11074, 1983, -1, 603, 11088, 2010, -1, 11089, 11088, 603, -1, 2010, 11087, 2018, -1, 11088, 11087, 2010, -1, 2018, 11092, 767, -1, 11087, 11092, 2018, -1, 767, 11093, 2053, -1, 11092, 11093, 767, -1, 2053, 11099, 2063, -1, 11093, 11099, 2053, -1, 2063, 11098, 1385, -1, 11099, 11098, 2063, -1, 1383, 14696, 2095, -1, 14701, 14696, 1383, -1, 2114, 11469, 2118, -1, 2114, 13451, 11469, -1, 2114, 13449, 13451, -1, 2095, 13452, 2114, -1, 14696, 13452, 2095, -1, 2114, 13450, 13449, -1, 13452, 13454, 2114, -1, 2114, 13454, 13450, -1, 17019, 1395, 11449, -1, 17020, 1395, 17019, -1, 17022, 1395, 17020, -1, 17023, 1395, 17022, -1, 11449, 1395, 1394, -1, 17023, 17026, 1395, -1, 17026, 17692, 1395, -1, 17692, 2087, 1395, -1, 17692, 17690, 2087, -1, 17690, 1384, 2087, -1, 17690, 17689, 1384, -1, 17689, 2054, 1384, -1, 17689, 17688, 2054, -1, 2054, 17685, 782, -1, 17688, 17685, 2054, -1, 17685, 621, 782, -1, 17685, 17684, 621, -1, 628, 11274, 2011, -1, 11275, 11274, 628, -1, 2011, 11272, 1999, -1, 11274, 11272, 2011, -1, 1999, 11270, 604, -1, 11272, 11270, 1999, -1, 604, 11266, 1970, -1, 11270, 11266, 604, -1, 1970, 11260, 311, -1, 11266, 11260, 1970, -1, 311, 11255, 308, -1, 11260, 11255, 311, -1, 309, 11219, 1917, -1, 11220, 11219, 309, -1, 1917, 11217, 1904, -1, 11219, 11217, 1917, -1, 1904, 11216, 273, -1, 11217, 11216, 1904, -1, 273, 11215, 1864, -1, 11216, 11215, 273, -1, 1864, 11211, 60, -1, 11215, 11211, 1864, -1, 60, 11210, 55, -1, 11211, 11210, 60, -1, 1640, 11241, 1619, -1, 11239, 11241, 1640, -1, 1619, 11235, 1596, -1, 11241, 11235, 1619, -1, 1596, 11852, 3267, -1, 1596, 17704, 11852, -1, 1596, 17720, 17704, -1, 11235, 11234, 1596, -1, 1596, 17723, 17720, -1, 11234, 17724, 1596, -1, 1596, 17724, 17723, -1, 11835, 1599, 1598, -1, 16355, 1599, 11835, -1, 16357, 1599, 16355, -1, 16358, 1599, 16357, -1, 16362, 1599, 16358, -1, 11104, 1599, 16362, -1, 1599, 11103, 1620, -1, 11104, 11103, 1599, -1, 11103, 1639, 1620, -1, 11103, 11111, 1639, -1, 18361, 18362, 18363, -1, 6, 11924, 11897, -1, 6, 11925, 11924, -1, 6, 9, 11925, -1, 82, 18364, 70, -1, 18365, 6, 11897, -1, 4, 6, 18365, -1, 18366, 18367, 18368, -1, 18369, 18370, 18371, -1, 18372, 4, 18365, -1, 7, 4, 18372, -1, 18373, 18374, 18375, -1, 18373, 18376, 18374, -1, 18377, 11886, 11905, -1, 18378, 18364, 82, -1, 18379, 18366, 18368, -1, 18380, 18381, 18382, -1, 18383, 7, 18372, -1, 18384, 18385, 18386, -1, 18384, 18386, 18367, -1, 18384, 18367, 18366, -1, 18387, 3366, 7, -1, 18388, 18380, 18382, -1, 18387, 7, 18383, -1, 18389, 18390, 18391, -1, 18389, 18392, 18390, -1, 18393, 3381, 3366, -1, 18393, 3366, 18387, -1, 18394, 18395, 18396, -1, 18397, 3381, 18393, -1, 18398, 18395, 18394, -1, 18399, 18383, 18400, -1, 18399, 18387, 18383, -1, 18401, 18402, 18403, -1, 18404, 18405, 18406, -1, 18404, 18406, 18407, -1, 20, 3381, 18397, -1, 18408, 18409, 18410, -1, 18411, 18400, 18412, -1, 18411, 18399, 18400, -1, 85, 18378, 82, -1, 18413, 18366, 18379, -1, 18414, 18415, 18416, -1, 18417, 18, 20, -1, 18418, 18370, 18369, -1, 18419, 18412, 18415, -1, 18419, 18411, 18412, -1, 76, 18, 18417, -1, 18420, 18421, 18422, -1, 18423, 18413, 18379, -1, 18424, 18418, 18369, -1, 18425, 18380, 18388, -1, 18426, 76, 18417, -1, 104, 76, 18426, -1, 18427, 18421, 18420, -1, 18428, 11881, 11879, -1, 18428, 11851, 11881, -1, 18429, 18391, 18430, -1, 18429, 18389, 18391, -1, 11832, 18428, 11879, -1, 18431, 18409, 18408, -1, 94, 18378, 85, -1, 18432, 18415, 18414, -1, 18432, 18419, 18415, -1, 18433, 18419, 18432, -1, 18434, 18435, 18436, -1, 18433, 18437, 18419, -1, 18438, 18404, 18407, -1, 18439, 104, 18426, -1, 18438, 18407, 18440, -1, 18441, 18413, 18423, -1, 18442, 18437, 18433, -1, 18443, 18444, 18445, -1, 18446, 104, 18439, -1, 18446, 145, 104, -1, 18447, 18441, 18423, -1, 18448, 18431, 18408, -1, 18449, 18402, 18401, -1, 18450, 18428, 11832, -1, 18451, 179, 145, -1, 18451, 145, 18446, -1, 18452, 11961, 11968, -1, 11976, 18452, 11968, -1, 11435, 11347, 18453, -1, 18454, 18418, 18424, -1, 18455, 18409, 18431, -1, 18456, 18457, 18458, -1, 18459, 18460, 18461, -1, 18455, 18462, 18409, -1, 18463, 18435, 18434, -1, 18464, 179, 18451, -1, 18465, 18439, 18466, -1, 18465, 18446, 18439, -1, 116, 18467, 18468, -1, 116, 18468, 94, -1, 200, 179, 18464, -1, 18469, 18470, 18471, -1, 18472, 18454, 18424, -1, 18473, 18457, 18456, -1, 18474, 18441, 18447, -1, 18475, 18473, 18456, -1, 18476, 18430, 18444, -1, 18476, 18429, 18430, -1, 11447, 11435, 18453, -1, 18477, 18466, 18478, -1, 18477, 18465, 18466, -1, 18479, 18431, 18448, -1, 18480, 11447, 18453, -1, 18480, 18453, 18481, -1, 18480, 18481, 18482, -1, 18483, 18479, 18448, -1, 18484, 18485, 18486, -1, 18487, 18460, 18459, -1, 18488, 11811, 11859, -1, 18489, 18487, 18459, -1, 11858, 18488, 11859, -1, 18490, 18473, 18475, -1, 18491, 18476, 18444, -1, 18491, 18444, 18443, -1, 127, 18492, 18467, -1, 127, 18467, 116, -1, 11357, 11447, 18480, -1, 18493, 233, 200, -1, 18494, 18495, 18496, -1, 18497, 18490, 18475, -1, 18498, 18454, 18472, -1, 18494, 18499, 18495, -1, 267, 233, 18493, -1, 18500, 18478, 18485, -1, 18500, 18477, 18478, -1, 11587, 11589, 18501, -1, 18502, 18485, 18484, -1, 18502, 18500, 18485, -1, 18503, 18490, 18497, -1, 18504, 18487, 18489, -1, 18505, 18504, 18489, -1, 18506, 267, 18493, -1, 281, 267, 18506, -1, 18507, 18479, 18483, -1, 151, 18508, 18492, -1, 151, 18492, 127, -1, 18509, 18508, 151, -1, 18510, 18496, 18511, -1, 11585, 11587, 18501, -1, 18510, 18494, 18496, -1, 18512, 18513, 18514, -1, 18512, 18514, 18515, -1, 18516, 18517, 18518, -1, 18519, 18500, 18502, -1, 18520, 18507, 18483, -1, 18521, 18522, 18523, -1, 18524, 18470, 18469, -1, 18521, 18497, 18522, -1, 18521, 18503, 18497, -1, 18525, 18526, 18527, -1, 18525, 18527, 18528, -1, 18529, 18503, 18521, -1, 18530, 18476, 18491, -1, 18531, 18532, 18533, -1, 18534, 18504, 18505, -1, 18535, 281, 18506, -1, 18536, 18532, 18531, -1, 18537, 18538, 18500, -1, 178, 18509, 151, -1, 18537, 18500, 18519, -1, 18539, 18517, 18516, -1, 18540, 18498, 18472, -1, 18540, 18472, 18541, -1, 18540, 18541, 18542, -1, 18543, 18538, 18537, -1, 18544, 18512, 18515, -1, 18545, 18498, 18540, -1, 18544, 18515, 18546, -1, 18547, 18511, 18548, -1, 18549, 18550, 18551, -1, 18549, 18552, 18550, -1, 18547, 18510, 18511, -1, 18553, 18509, 178, -1, 18554, 281, 18535, -1, 18554, 299, 281, -1, 18555, 18539, 18516, -1, 18556, 18476, 18530, -1, 18556, 18557, 18476, -1, 18558, 18554, 18535, -1, 18559, 18560, 18517, -1, 18559, 18517, 18539, -1, 18561, 299, 18554, -1, 18561, 313, 299, -1, 18562, 18507, 18520, -1, 18563, 18564, 18565, -1, 18566, 18557, 18556, -1, 18567, 18525, 18528, -1, 18567, 18528, 18568, -1, 18569, 18544, 18546, -1, 187, 18553, 178, -1, 18569, 18546, 18570, -1, 18571, 313, 18561, -1, 18572, 18539, 18555, -1, 18573, 18554, 18558, -1, 18574, 18575, 18576, -1, 18577, 18572, 18555, -1, 316, 313, 18571, -1, 18578, 18573, 18558, -1, 11461, 11370, 18579, -1, 18580, 18574, 18576, -1, 198, 18553, 187, -1, 18581, 18572, 18577, -1, 18582, 11757, 11839, -1, 11468, 11461, 18579, -1, 18583, 18581, 18577, -1, 18584, 18573, 18578, -1, 18585, 18564, 18563, -1, 18586, 18567, 18568, -1, 18586, 18568, 18587, -1, 18588, 18584, 18578, -1, 18589, 18590, 18591, -1, 18589, 18592, 18590, -1, 18593, 18588, 18594, -1, 249, 18595, 18596, -1, 249, 18596, 198, -1, 18597, 18574, 18580, -1, 18598, 18581, 18583, -1, 18599, 333, 316, -1, 18600, 18601, 18602, -1, 365, 333, 18599, -1, 18603, 18601, 18600, -1, 18604, 18597, 18580, -1, 258, 18595, 249, -1, 258, 18605, 18595, -1, 18606, 18584, 18588, -1, 18607, 18606, 18588, -1, 18607, 18588, 18593, -1, 276, 18605, 258, -1, 18608, 18609, 18610, -1, 276, 18611, 18605, -1, 18612, 365, 18599, -1, 18613, 18611, 276, -1, 18614, 11982, 11987, -1, 392, 365, 18612, -1, 18615, 18616, 18617, -1, 18618, 18597, 18604, -1, 305, 18613, 276, -1, 18619, 18620, 18621, -1, 18619, 18621, 18609, -1, 18619, 18609, 18608, -1, 18622, 18623, 18624, -1, 18625, 18626, 18627, -1, 18625, 18627, 18616, -1, 18625, 18616, 18615, -1, 18628, 18613, 305, -1, 18629, 18606, 18607, -1, 18630, 18631, 18632, -1, 18630, 18632, 18633, -1, 11480, 11431, 18634, -1, 18635, 18636, 18637, -1, 18638, 18639, 18640, -1, 18641, 18618, 18604, -1, 18635, 18637, 18642, -1, 18643, 18644, 18635, -1, 18645, 18641, 18646, -1, 18647, 18648, 18626, -1, 18647, 18626, 18625, -1, 310, 18628, 305, -1, 18649, 392, 18612, -1, 11571, 11564, 18650, -1, 18651, 18606, 18629, -1, 18652, 18653, 18654, -1, 18651, 18655, 18606, -1, 18656, 18657, 18658, -1, 18659, 18660, 18661, -1, 11492, 11480, 18634, -1, 18662, 18660, 18659, -1, 18663, 18623, 18622, -1, 18664, 18639, 18638, -1, 18665, 18664, 18638, -1, 18666, 18667, 18620, -1, 18668, 18655, 18651, -1, 18666, 18620, 18619, -1, 18669, 18663, 18622, -1, 18670, 18625, 18671, -1, 18670, 18647, 18625, -1, 323, 18628, 310, -1, 18672, 18633, 18673, -1, 18672, 18630, 18633, -1, 18674, 18618, 18641, -1, 18675, 18664, 18665, -1, 18676, 392, 18649, -1, 18676, 407, 392, -1, 18677, 18675, 18665, -1, 18678, 18679, 18680, -1, 11569, 11571, 18650, -1, 18681, 18648, 18647, -1, 18682, 18671, 18683, -1, 18684, 18641, 18645, -1, 18682, 18670, 18671, -1, 18684, 18674, 18641, -1, 398, 18685, 18686, -1, 398, 18686, 323, -1, 18687, 18675, 18677, -1, 18688, 18676, 18649, -1, 18689, 18653, 18652, -1, 18690, 11733, 11819, -1, 11817, 18690, 11819, -1, 18691, 18682, 18683, -1, 18692, 18663, 18669, -1, 18691, 18683, 18693, -1, 18694, 407, 18676, -1, 421, 18685, 398, -1, 18694, 423, 407, -1, 421, 18693, 18685, -1, 18695, 18689, 18652, -1, 443, 18693, 421, -1, 443, 18691, 18693, -1, 18696, 18643, 18635, -1, 18697, 18619, 18698, -1, 18696, 18699, 18643, -1, 18697, 18666, 18619, -1, 18700, 18692, 18669, -1, 18701, 18691, 443, -1, 18702, 423, 18694, -1, 11506, 11475, 18703, -1, 18704, 18672, 18673, -1, 18704, 18673, 18705, -1, 11516, 11506, 18703, -1, 18706, 18676, 18688, -1, 593, 18701, 443, -1, 18707, 11516, 18703, -1, 427, 423, 18702, -1, 18707, 18703, 18708, -1, 18709, 18701, 593, -1, 11490, 11516, 18707, -1, 18710, 18706, 18688, -1, 615, 18709, 593, -1, 709, 18709, 615, -1, 18711, 18712, 18377, -1, 18711, 11901, 11870, -1, 18711, 11905, 11901, -1, 18711, 11870, 18416, -1, 18711, 18377, 11905, -1, 18713, 18415, 18712, -1, 18713, 18711, 18416, -1, 18713, 18712, 18711, -1, 18713, 18416, 18415, -1, 18714, 18715, 18437, -1, 18714, 18437, 18442, -1, 18714, 18442, 18458, -1, 18716, 18715, 18714, -1, 18717, 18718, 18719, -1, 18716, 18720, 18715, -1, 18716, 18714, 18458, -1, 18716, 18458, 18457, -1, 18721, 18722, 18720, -1, 18721, 18720, 18716, -1, 18723, 18692, 18700, -1, 18721, 18716, 18457, -1, 18724, 18486, 18722, -1, 18724, 18457, 18484, -1, 18724, 18721, 18457, -1, 18724, 18722, 18721, -1, 18724, 18484, 18486, -1, 18725, 18428, 18450, -1, 18725, 18726, 18428, -1, 18725, 18450, 18727, -1, 18728, 18514, 18513, -1, 18728, 18725, 18727, -1, 18728, 18729, 18726, -1, 18730, 18690, 11817, -1, 18728, 18727, 18514, -1, 18728, 18726, 18725, -1, 18731, 18728, 18513, -1, 18732, 18674, 18684, -1, 18731, 18733, 18729, -1, 18731, 18729, 18728, -1, 18734, 18523, 18522, -1, 18734, 18733, 18731, -1, 18735, 18689, 18695, -1, 18734, 18522, 18733, -1, 18734, 18731, 18513, -1, 18734, 18513, 18736, -1, 18734, 18736, 18523, -1, 18737, 18738, 18488, -1, 18737, 11858, 11772, -1, 18737, 11772, 18739, -1, 18737, 18488, 11858, -1, 18740, 18741, 18538, -1, 18740, 18543, 18742, -1, 18743, 18735, 18695, -1, 18740, 18538, 18543, -1, 18740, 18744, 18741, -1, 18745, 18737, 18739, -1, 18745, 18738, 18737, -1, 18745, 18570, 18738, -1, 18745, 18739, 18746, -1, 18747, 18740, 18742, -1, 18747, 18742, 18748, -1, 18749, 18750, 18751, -1, 18747, 18744, 18740, -1, 18752, 18753, 18754, -1, 18747, 18755, 18744, -1, 18756, 18569, 18570, -1, 18752, 18757, 18753, -1, 18756, 18570, 18745, -1, 18756, 18746, 18758, -1, 18756, 18745, 18746, -1, 18759, 18748, 18593, -1, 18759, 18593, 18594, -1, 18759, 18747, 18748, -1, 18759, 18755, 18747, -1, 18760, 18667, 18666, -1, 18759, 18594, 18755, -1, 18761, 18706, 18710, -1, 18762, 18763, 18529, -1, 18762, 18521, 18764, -1, 18765, 18766, 18767, -1, 18762, 18529, 18521, -1, 18765, 18768, 18766, -1, 18769, 18569, 18756, -1, 18769, 18756, 18758, -1, 18770, 18771, 18765, -1, 18769, 18758, 18772, -1, 18773, 18763, 18762, -1, 18773, 18764, 18774, -1, 18773, 18762, 18764, -1, 18775, 18776, 18777, -1, 18778, 18698, 18779, -1, 18775, 18777, 18748, -1, 18775, 18742, 18780, -1, 18775, 18780, 18781, -1, 18778, 18697, 18698, -1, 18775, 18748, 18742, -1, 18775, 18781, 18776, -1, 18782, 18569, 18769, -1, 18782, 18783, 18569, -1, 18782, 18772, 18784, -1, 18782, 18769, 18772, -1, 18785, 18661, 18660, -1, 18785, 18660, 18582, -1, 18785, 11837, 11748, -1, 18785, 11839, 11837, -1, 18785, 11748, 18661, -1, 18785, 18582, 11839, -1, 18786, 18763, 18773, -1, 18786, 18787, 18763, -1, 18786, 18632, 18631, -1, 18788, 18750, 18749, -1, 18786, 18773, 18774, -1, 18786, 18774, 18632, -1, 18789, 18783, 18782, -1, 18790, 18674, 18732, -1, 18789, 18791, 18783, -1, 18792, 18761, 18710, -1, 18789, 18784, 18624, -1, 18789, 18782, 18784, -1, 18793, 18787, 18786, -1, 18793, 18786, 18631, -1, 18793, 18794, 18787, -1, 18790, 18795, 18674, -1, 18796, 18791, 18789, -1, 18796, 18624, 18623, -1, 18797, 18792, 18798, -1, 18796, 18799, 18791, -1, 18796, 18789, 18624, -1, 18800, 18644, 18776, -1, 18801, 18802, 18803, -1, 18800, 18781, 18636, -1, 18800, 18635, 18644, -1, 18800, 18636, 18635, -1, 18800, 18776, 18781, -1, 18804, 18794, 18793, -1, 18801, 18803, 18805, -1, 18804, 18637, 18794, -1, 18804, 18631, 18806, -1, 18807, 18808, 18809, -1, 18804, 18806, 18642, -1, 18804, 18793, 18631, -1, 18804, 18642, 18637, -1, 18810, 18799, 18796, -1, 18810, 18796, 18623, -1, 18810, 18811, 18799, -1, 18812, 18808, 18807, -1, 18813, 18668, 18814, -1, 18813, 18815, 18816, -1, 18813, 18816, 18655, -1, 18813, 18655, 18668, -1, 18817, 18811, 18810, -1, 18818, 18718, 18717, -1, 18817, 18623, 18819, -1, 18817, 18810, 18623, -1, 18817, 18820, 18811, -1, 18821, 18813, 18814, -1, 18821, 18822, 18815, -1, 18821, 18815, 18813, -1, 18821, 18814, 18823, -1, 18824, 18819, 18825, -1, 18824, 18820, 18817, -1, 18824, 18705, 18820, -1, 18826, 18795, 18790, -1, 18824, 18817, 18819, -1, 18827, 18662, 18659, -1, 18827, 18803, 18802, -1, 18828, 18818, 18717, -1, 18827, 18659, 18803, -1, 18829, 18821, 18823, -1, 18829, 18797, 18798, -1, 18829, 18798, 18822, -1, 18829, 18823, 18797, -1, 18829, 18822, 18821, -1, 18830, 11817, 11724, -1, 18831, 18704, 18705, -1, 18831, 18824, 18825, -1, 18831, 18705, 18824, -1, 18830, 18730, 11817, -1, 18832, 18827, 18802, -1, 18832, 18662, 18827, -1, 18832, 18749, 18751, -1, 18833, 18735, 18743, -1, 18832, 18802, 18749, -1, 18832, 18751, 18662, -1, 18834, 18704, 18831, -1, 18834, 18825, 18835, -1, 18834, 18835, 18836, -1, 18834, 18831, 18825, -1, 18837, 18723, 18700, -1, 18837, 18700, 18750, -1, 18837, 18750, 18788, -1, 18837, 18788, 18838, -1, 18839, 18840, 18841, -1, 18839, 18841, 18842, -1, 18839, 18842, 18823, -1, 18839, 18814, 18843, -1, 18839, 18843, 18840, -1, 18839, 18823, 18814, -1, 18844, 18699, 18696, -1, 18844, 18696, 18845, -1, 18846, 18704, 18834, -1, 18846, 18836, 18847, -1, 18848, 18752, 18754, -1, 18848, 18754, 18849, -1, 18846, 18850, 18704, -1, 18846, 18834, 18836, -1, 18851, 18845, 18852, -1, 18851, 18699, 18844, -1, 18851, 18844, 18845, -1, 18851, 18853, 18699, -1, 18854, 18837, 18838, -1, 18855, 440, 427, -1, 18854, 18856, 18723, -1, 18857, 18858, 18859, -1, 18854, 18723, 18837, -1, 18860, 18761, 18792, -1, 18861, 18847, 18862, -1, 18861, 18850, 18846, -1, 18861, 18846, 18847, -1, 18861, 18863, 18850, -1, 18864, 18851, 18852, -1, 18864, 18853, 18851, -1, 18864, 18852, 18865, -1, 18864, 18866, 18853, -1, 18867, 18868, 18869, -1, 18867, 18869, 18856, -1, 18867, 18854, 18838, -1, 18867, 18838, 18868, -1, 18867, 18856, 18854, -1, 18870, 18871, 18730, -1, 18870, 18730, 18830, -1, 18870, 18830, 18872, -1, 18873, 18874, 18875, -1, 18876, 18779, 18877, -1, 447, 440, 18855, -1, 18873, 18841, 18840, -1, 18873, 18878, 18874, -1, 18876, 18778, 18779, -1, 18873, 18875, 18841, -1, 18873, 18840, 18878, -1, 18879, 18865, 18880, -1, 18881, 18801, 18805, -1, 18879, 18880, 18882, -1, 18879, 18882, 18883, -1, 18879, 18866, 18864, -1, 18879, 18864, 18865, -1, 18879, 18883, 18866, -1, 18881, 18805, 18884, -1, 18885, 18861, 18862, -1, 18885, 18863, 18861, -1, 18885, 18886, 18887, -1, 18885, 18887, 18863, -1, 18885, 18862, 18888, -1, 18889, 18890, 18891, -1, 18889, 18891, 18892, -1, 18889, 18892, 18893, -1, 18894, 18872, 18895, -1, 18896, 18860, 18792, -1, 18894, 18897, 18871, -1, 18894, 18871, 18870, -1, 18894, 18870, 18872, -1, 18898, 18885, 18888, -1, 18896, 18792, 18797, -1, 18898, 18899, 18886, -1, 18898, 18886, 18885, -1, 18898, 18888, 18900, -1, 18901, 18890, 18889, -1, 18901, 18889, 18893, -1, 18901, 18902, 18890, -1, 18903, 18857, 18859, -1, 18904, 18894, 18895, -1, 18904, 18895, 18905, -1, 18904, 18897, 18894, -1, 18906, 18898, 18900, -1, 18906, 18899, 18898, -1, 18906, 18907, 18899, -1, 18906, 18900, 18908, -1, 18909, 18910, 18911, -1, 18909, 18912, 18910, -1, 18909, 18913, 18912, -1, 18909, 18911, 18913, -1, 18914, 18901, 18893, -1, 18914, 18893, 18915, -1, 18916, 11999, 12006, -1, 18914, 18902, 18901, -1, 18914, 18917, 18902, -1, 18918, 18919, 18897, -1, 18918, 18905, 18920, -1, 18918, 18897, 18904, -1, 18918, 18904, 18905, -1, 12016, 18916, 12006, -1, 18921, 18906, 18908, -1, 18921, 18907, 18906, -1, 18922, 18818, 18828, -1, 18923, 18924, 11799, -1, 18923, 11797, 11700, -1, 18923, 11799, 11797, -1, 18923, 11700, 18925, -1, 18926, 18927, 18928, -1, 18926, 18929, 18927, -1, 18926, 18930, 18929, -1, 18931, 18932, 18933, -1, 18931, 18914, 18915, -1, 18931, 18915, 18932, -1, 18931, 18917, 18914, -1, 18931, 18933, 18917, -1, 18934, 18920, 18935, -1, 18934, 18935, 18936, -1, 18937, 18865, 18852, -1, 18934, 18918, 18920, -1, 18934, 18919, 18918, -1, 18934, 18936, 18919, -1, 18938, 18939, 18940, -1, 18938, 18907, 18921, -1, 18938, 18921, 18908, -1, 18938, 18941, 18907, -1, 18938, 18908, 18939, -1, 18942, 18924, 18923, -1, 18942, 18923, 18925, -1, 18942, 18943, 18924, -1, 18942, 18925, 18944, -1, 18942, 18944, 18943, -1, 18945, 18946, 18930, -1, 18945, 18926, 18928, -1, 18945, 18928, 18947, -1, 18945, 18947, 18946, -1, 18945, 18930, 18926, -1, 18948, 18949, 18950, -1, 18951, 447, 18855, -1, 18948, 18950, 18952, -1, 18953, 18940, 18954, -1, 18955, 18956, 18770, -1, 18953, 18938, 18940, -1, 18953, 18941, 18938, -1, 18953, 18957, 18941, -1, 18955, 18770, 18765, -1, 18958, 18959, 18960, -1, 18958, 18961, 18962, -1, 18958, 18963, 18959, -1, 18964, 18922, 18828, -1, 448, 447, 18951, -1, 18958, 18960, 18961, -1, 18965, 18949, 18948, -1, 18965, 18952, 18966, -1, 18965, 18967, 18949, -1, 18965, 18948, 18952, -1, 18968, 18954, 18969, -1, 18968, 18957, 18953, -1, 18968, 18970, 18957, -1, 18968, 18953, 18954, -1, 18971, 18972, 18973, -1, 18971, 18973, 18963, -1, 18971, 18958, 18962, -1, 18971, 18963, 18958, -1, 18971, 18974, 18972, -1, 18971, 18962, 18974, -1, 18975, 18965, 18966, -1, 18975, 18966, 18976, -1, 18975, 18967, 18965, -1, 18975, 18977, 18967, -1, 18978, 18970, 18968, -1, 18978, 18968, 18969, -1, 18978, 18979, 18980, -1, 18978, 18980, 18970, -1, 18978, 18969, 18981, -1, 18982, 18975, 18976, -1, 18983, 18849, 18984, -1, 18982, 18976, 18985, -1, 18983, 18848, 18849, -1, 18897, 18881, 18884, -1, 18982, 18985, 18986, -1, 18982, 18986, 18987, -1, 18982, 18987, 18977, -1, 18982, 18977, 18975, -1, 18897, 18884, 18871, -1, 18988, 18989, 18990, -1, 18988, 18990, 18991, -1, 18988, 18991, 18992, -1, 18988, 18993, 18989, -1, 18994, 18995, 18996, -1, 18997, 18857, 18903, -1, 18994, 18996, 18998, -1, 18994, 18998, 18999, -1, 19000, 18860, 18896, -1, 19001, 19002, 19003, -1, 19001, 11778, 11682, -1, 19001, 11780, 11778, -1, 19001, 11682, 19004, -1, 19001, 19004, 19002, -1, 19001, 19003, 11780, -1, 19005, 19006, 19007, -1, 19005, 11437, 19008, -1, 19005, 19007, 11426, -1, 19009, 18876, 18877, -1, 19005, 11432, 11437, -1, 19005, 11426, 11432, -1, 19005, 19008, 19006, -1, 19010, 19011, 18979, -1, 19010, 18979, 18978, -1, 19010, 18981, 19012, -1, 19010, 18978, 18981, -1, 19013, 19014, 18993, -1, 19013, 18988, 18992, -1, 19013, 18992, 19015, -1, 18912, 18888, 18862, -1, 19013, 18993, 18988, -1, 19016, 18997, 18903, -1, 19017, 19018, 18995, -1, 19017, 18995, 18994, -1, 19017, 18999, 19019, -1, 19017, 18994, 18999, -1, 19020, 18876, 19009, -1, 19021, 19013, 19015, -1, 19021, 19015, 19022, -1, 19023, 18865, 18937, -1, 19021, 19014, 19013, -1, 19024, 19025, 19011, -1, 19024, 19010, 19012, -1, 19024, 19011, 19010, -1, 19024, 19012, 19026, -1, 19027, 19018, 19017, -1, 19027, 19017, 19019, -1, 19027, 19019, 19028, -1, 19027, 19029, 19018, -1, 18874, 18883, 18882, -1, 19030, 19031, 19032, -1, 19030, 19032, 19033, -1, 19030, 19033, 19034, -1, 18874, 18878, 18883, -1, 19030, 19034, 19031, -1, 19035, 19036, 19037, -1, 19038, 18875, 18874, -1, 19035, 19039, 19040, -1, 19035, 19040, 19036, -1, 19035, 19037, 19039, -1, 19041, 19014, 19021, -1, 19041, 19022, 19042, -1, 19041, 19043, 19014, -1, 19041, 19021, 19022, -1, 19041, 19042, 19043, -1, 19044, 19024, 19026, -1, 19044, 19025, 19024, -1, 19045, 19023, 18937, -1, 19046, 19047, 19048, -1, 19049, 18860, 19000, -1, 19046, 19048, 19050, -1, 19051, 19029, 19027, -1, 19051, 19027, 19028, -1, 19049, 18891, 18860, -1, 19051, 19028, 19052, -1, 19051, 19053, 19029, -1, 19054, 19055, 19056, -1, 19054, 19056, 19057, -1, 19058, 18922, 18964, -1, 19054, 19059, 19055, -1, 19060, 19044, 19026, -1, 19060, 19025, 19044, -1, 19060, 19026, 19061, -1, 19060, 19062, 19025, -1, 11554, 11545, 19063, -1, 19060, 19061, 19064, -1, 19065, 19050, 19066, -1, 19065, 19067, 19047, -1, 19065, 19047, 19046, -1, 19065, 19046, 19050, -1, 19065, 19066, 19068, -1, 19065, 19068, 19067, -1, 19069, 448, 18951, -1, 19070, 19053, 19051, -1, 19070, 19071, 19053, -1, 19070, 19051, 19052, -1, 19072, 19059, 19054, -1, 19072, 19057, 19073, -1, 19072, 19054, 19057, -1, 19074, 19075, 19076, -1, 19077, 18916, 12016, -1, 19074, 19076, 19078, -1, 18913, 18888, 18912, -1, 19074, 19078, 19079, -1, 19074, 19080, 19075, -1, 19081, 19060, 19064, -1, 19081, 19082, 19062, -1, 19081, 19062, 19060, -1, 18892, 18891, 19049, -1, 19081, 19064, 19083, -1, 19084, 19071, 19070, -1, 19084, 19070, 19052, -1, 19084, 19085, 19086, -1, 19084, 19052, 19085, -1, 19084, 19086, 19071, -1, 19087, 19088, 19037, -1, 19087, 19089, 19088, -1, 19087, 19090, 19089, -1, 19087, 19037, 19090, -1, 18929, 18869, 18868, -1, 19091, 19073, 19092, -1, 19091, 19093, 19059, -1, 19091, 19072, 19073, -1, 19091, 19059, 19072, -1, 19094, 19095, 19082, -1, 19094, 19082, 19081, -1, 19094, 19081, 19083, -1, 19094, 19083, 19096, -1, 18930, 18869, 18929, -1, 19097, 19098, 19099, -1, 19097, 19099, 19100, -1, 18924, 11712, 11799, -1, 19097, 19101, 19098, -1, 19102, 19103, 19104, -1, 19102, 19079, 19103, -1, 19105, 19106, 19107, -1, 19102, 19074, 19079, -1, 19102, 19104, 19108, -1, 19102, 19108, 19080, -1, 19102, 19080, 19074, -1, 19109, 19110, 19111, -1, 19109, 19111, 19112, -1, 19109, 19113, 19110, -1, 19114, 19115, 19093, -1, 19116, 18997, 19016, -1, 19114, 19091, 19092, -1, 19114, 19093, 19091, -1, 19114, 19092, 19117, -1, 19118, 19119, 19095, -1, 19118, 19094, 19096, -1, 19118, 19095, 19094, -1, 19120, 19023, 19045, -1, 19121, 19100, 19122, -1, 19121, 19097, 19100, -1, 19121, 19101, 19097, -1, 19123, 19113, 19109, -1, 19123, 19124, 19113, -1, 19123, 19109, 19112, -1, 19123, 19112, 19125, -1, 19126, 19088, 19127, -1, 19126, 19127, 19128, -1, 19126, 19129, 19130, -1, 19126, 19130, 19088, -1, 19131, 19114, 19117, -1, 19131, 19115, 19114, -1, 19131, 19117, 19132, -1, 19133, 19134, 19135, -1, 19133, 19135, 19089, -1, 19133, 19136, 19134, -1, 11552, 11554, 19063, -1, 19133, 19137, 19136, -1, 19133, 19089, 19137, -1, 19138, 19139, 19119, -1, 19138, 19096, 19140, -1, 19138, 19118, 19096, -1, 19138, 19119, 19118, -1, 19141, 19106, 19105, -1, 19142, 19111, 19110, -1, 19142, 19122, 19111, -1, 19142, 19110, 19101, -1, 19142, 19101, 19121, -1, 19142, 19121, 19122, -1, 19143, 19144, 19145, -1, 19146, 11552, 19063, -1, 19143, 19147, 19144, -1, 19146, 19063, 19148, -1, 19149, 19126, 19128, -1, 19149, 19128, 19150, -1, 19149, 19129, 19126, -1, 19151, 19116, 19016, -1, 19152, 19123, 19125, -1, 19152, 19124, 19123, -1, 19152, 19153, 19154, -1, 19152, 19154, 19124, -1, 19152, 19125, 19153, -1, 19155, 19131, 19132, -1, 19155, 19156, 19157, -1, 19155, 19132, 19156, -1, 19155, 19157, 19115, -1, 19158, 19151, 19159, -1, 19155, 19115, 19131, -1, 19160, 19161, 19162, -1, 19163, 19164, 19139, -1, 19163, 19140, 19165, -1, 19163, 19138, 19140, -1, 19163, 19139, 19138, -1, 19166, 19143, 19145, -1, 19166, 19145, 19167, -1, 19160, 19168, 19161, -1, 19166, 19167, 19169, -1, 19166, 19136, 19147, -1, 19166, 19147, 19143, -1, 19170, 19171, 19129, -1, 19170, 19150, 19172, -1, 19170, 19129, 19149, -1, 19170, 19149, 19150, -1, 19173, 448, 19069, -1, 19173, 3397, 448, -1, 19174, 19175, 19176, -1, 19174, 11793, 11704, -1, 19174, 11704, 19177, -1, 19174, 19177, 19178, -1, 19179, 19173, 19069, -1, 19174, 19176, 11793, -1, 19180, 19181, 19164, -1, 19180, 19165, 19182, -1, 19180, 19163, 19165, -1, 19180, 19164, 19163, -1, 19183, 19184, 19185, -1, 19183, 19186, 19187, -1, 19183, 19187, 19184, -1, 19183, 19185, 19186, -1, 19188, 19170, 19172, -1, 19188, 19172, 19189, -1, 19188, 19190, 19171, -1, 19188, 19171, 19170, -1, 19188, 19189, 19190, -1, 19191, 19166, 19169, -1, 19191, 19134, 19136, -1, 19191, 19136, 19166, -1, 19192, 19193, 19194, -1, 19192, 19195, 19193, -1, 19196, 19181, 19180, -1, 19196, 19180, 19182, -1, 19197, 19198, 19199, -1, 19197, 19175, 19174, -1, 18950, 19038, 18874, -1, 19197, 19200, 19175, -1, 19197, 19178, 19198, -1, 19197, 19174, 19178, -1, 19201, 12016, 12013, -1, 19201, 19077, 12016, -1, 19202, 19134, 19191, -1, 19202, 19169, 19203, -1, 18950, 18949, 19038, -1, 19202, 19204, 19205, -1, 19202, 19205, 19134, -1, 19202, 19191, 19169, -1, 19206, 19207, 19208, -1, 19206, 19192, 19194, -1, 19206, 19208, 19209, -1, 19206, 19195, 19192, -1, 19206, 19209, 19195, -1, 19206, 19194, 19207, -1, 19210, 19182, 19211, -1, 19210, 19211, 19212, -1, 19210, 19181, 19196, -1, 19210, 19213, 19181, -1, 19210, 19196, 19182, -1, 19214, 19215, 19216, -1, 11537, 11552, 19146, -1, 19214, 19216, 19217, -1, 19214, 19218, 19215, -1, 19219, 19220, 19200, -1, 19219, 19200, 19197, -1, 19219, 19197, 19199, -1, 18959, 18911, 18910, -1, 19221, 19222, 19223, -1, 19221, 19185, 19224, -1, 19221, 19223, 19185, -1, 19221, 19224, 19222, -1, 19225, 19226, 19227, -1, 19225, 19202, 19203, -1, 19225, 19204, 19202, -1, 19225, 19227, 19204, -1, 19225, 19203, 19226, -1, 19228, 19213, 19210, -1, 19228, 19212, 19229, -1, 19228, 19230, 19213, -1, 19228, 19210, 19212, -1, 19231, 19218, 19214, -1, 19231, 19232, 19233, -1, 19231, 19233, 19218, -1, 19231, 19214, 19217, -1, 19234, 19235, 19220, -1, 19234, 19220, 19219, -1, 19234, 19219, 19199, -1, 19234, 19199, 19236, -1, 19237, 19116, 19151, -1, 19238, 19239, 11808, -1, 19238, 19240, 19239, -1, 19238, 11816, 11728, -1, 18941, 19120, 19045, -1, 19238, 11808, 11816, -1, 19238, 11728, 19241, -1, 19242, 11374, 19243, -1, 18941, 19045, 18907, -1, 19242, 19229, 11367, -1, 19242, 11367, 11374, -1, 19244, 3397, 19173, -1, 19242, 19243, 19230, -1, 19242, 19228, 19229, -1, 19242, 19230, 19228, -1, 19245, 19246, 19247, -1, 19245, 19247, 19248, -1, 19244, 3400, 3397, -1, 19245, 19249, 19246, -1, 19245, 19250, 19249, -1, 19251, 19252, 19232, -1, 19251, 19232, 19231, -1, 19251, 19253, 19252, -1, 19254, 19162, 19255, -1, 19251, 19217, 19253, -1, 19251, 19231, 19217, -1, 19254, 19160, 19162, -1, 19256, 19257, 19235, -1, 19256, 19234, 19236, -1, 19256, 19235, 19234, -1, 19256, 19236, 19258, -1, 19256, 19258, 19257, -1, 19259, 19238, 19241, -1, 19259, 19260, 19240, -1, 19259, 19241, 19261, -1, 19259, 19261, 19260, -1, 19259, 19240, 19238, -1, 19262, 19248, 19263, -1, 19262, 19263, 19250, -1, 19262, 19250, 19245, -1, 19262, 19245, 19248, -1, 19264, 19223, 19265, -1, 19264, 19265, 19266, -1, 19264, 19267, 19223, -1, 18935, 19268, 19269, -1, 18935, 19269, 18936, -1, 19264, 19270, 19267, -1, 19271, 19151, 19158, -1, 19272, 19273, 19274, -1, 19271, 19237, 19151, -1, 19272, 19274, 19224, -1, 19272, 19224, 19275, -1, 19276, 3400, 19244, -1, 19272, 19275, 19277, -1, 19272, 19277, 19273, -1, 19278, 19279, 19280, -1, 19281, 19173, 19179, -1, 19278, 19282, 19279, -1, 19283, 19284, 19285, -1, 19283, 19286, 19284, -1, 19283, 19285, 19287, -1, 19283, 19287, 19288, -1, 19283, 19288, 19286, -1, 19289, 19270, 19264, -1, 19289, 19266, 19290, -1, 19289, 19264, 19266, -1, 19291, 19280, 19292, -1, 19291, 19292, 19293, -1, 19291, 19277, 19282, -1, 19291, 19278, 19280, -1, 19291, 19282, 19278, -1, 19294, 19290, 19295, -1, 19294, 19289, 19290, -1, 19294, 19270, 19289, -1, 19294, 19296, 19270, -1, 19297, 19298, 19299, -1, 19300, 19281, 19179, -1, 19297, 19299, 19257, -1, 19297, 19257, 19301, -1, 19302, 19291, 19293, -1, 19302, 19277, 19291, -1, 19302, 19273, 19277, -1, 19303, 19296, 19294, -1, 19303, 19294, 19295, -1, 19303, 19295, 19304, -1, 19303, 19305, 19296, -1, 19306, 19297, 19301, -1, 19306, 19298, 19297, -1, 19306, 19301, 19307, -1, 3401, 3400, 19276, -1, 19308, 19286, 19309, -1, 19308, 19284, 19286, -1, 19308, 19310, 19284, -1, 18963, 18911, 18959, -1, 19308, 19309, 19310, -1, 19311, 19312, 19313, -1, 19311, 19314, 19312, -1, 19311, 19315, 19314, -1, 19316, 19317, 19318, -1, 19316, 19319, 19317, -1, 11459, 3401, 19276, -1, 19320, 19303, 19304, -1, 19320, 19305, 19303, -1, 19320, 19304, 19321, -1, 19320, 19322, 19305, -1, 19320, 19321, 19322, -1, 11458, 11459, 19276, -1, 19323, 19324, 19325, -1, 19323, 19325, 11736, -1, 19323, 11836, 11751, -1, 19323, 11829, 11836, -1, 19323, 11736, 11829, -1, 11457, 11458, 19276, -1, 19323, 11751, 19324, -1, 19326, 19293, 19327, -1, 19326, 19328, 19329, -1, 19330, 18915, 18893, -1, 19326, 19329, 19273, -1, 19326, 19273, 19302, -1, 19326, 19302, 19293, -1, 19331, 19332, 19298, -1, 19330, 18893, 19333, -1, 19331, 19306, 19307, -1, 19331, 19334, 19335, -1, 19331, 19298, 19306, -1, 19331, 19307, 19334, -1, 19336, 19315, 19311, -1, 19336, 19311, 19313, -1, 19336, 19313, 19337, -1, 19336, 19338, 19315, -1, 19339, 19340, 19341, -1, 19339, 19342, 19340, -1, 19339, 19341, 19319, -1, 19339, 19318, 19342, -1, 19339, 19319, 19316, -1, 19339, 19316, 19318, -1, 19343, 19331, 19335, -1, 19343, 19344, 19332, -1, 19343, 19332, 19331, -1, 19345, 19346, 19347, -1, 19345, 19347, 19328, -1, 19345, 19327, 19346, -1, 19345, 19326, 19327, -1, 19345, 19328, 19326, -1, 19348, 19337, 19349, -1, 19348, 19336, 19337, -1, 19348, 19338, 19336, -1, 19348, 19350, 19338, -1, 19351, 19352, 19353, -1, 19351, 19354, 19352, -1, 19351, 19355, 19354, -1, 19351, 19353, 19355, -1, 19356, 19357, 19344, -1, 19356, 19343, 19335, -1, 19356, 19344, 19343, -1, 18947, 18960, 18946, -1, 19356, 19335, 19358, -1, 19359, 19360, 19361, -1, 19359, 19361, 19362, -1, 19359, 19362, 19363, -1, 19364, 19350, 19348, -1, 19364, 19348, 19349, -1, 19364, 19365, 19350, -1, 19366, 19367, 19357, -1, 19366, 19358, 19368, -1, 19366, 19368, 19367, -1, 19369, 19255, 19370, -1, 19366, 19357, 19356, -1, 19366, 19356, 19358, -1, 19371, 19372, 19360, -1, 19371, 19359, 19363, -1, 19371, 19360, 19359, -1, 19369, 19254, 19255, -1, 19371, 19363, 19373, -1, 19371, 19373, 19372, -1, 19374, 19364, 19349, -1, 19374, 19349, 19375, -1, 19374, 19365, 19364, -1, 19374, 19376, 19365, -1, 18990, 19268, 18935, -1, 19377, 19378, 19379, -1, 19377, 19379, 19380, -1, 19377, 19381, 19382, -1, 19377, 19382, 19378, -1, 18990, 18989, 19268, -1, 19383, 19384, 19385, -1, 19383, 19385, 19386, -1, 19383, 19386, 19387, -1, 19383, 19388, 19384, -1, 19383, 19387, 19388, -1, 19389, 19347, 19390, -1, 19391, 19237, 19271, -1, 19389, 19392, 19393, -1, 19389, 19393, 19347, -1, 19394, 19374, 19375, -1, 19394, 19376, 19374, -1, 19394, 19375, 19395, -1, 19396, 19397, 19398, -1, 19394, 19395, 19376, -1, 19399, 19380, 19400, -1, 19401, 18990, 18935, -1, 19399, 19381, 19377, -1, 19399, 19377, 19380, -1, 19402, 19389, 19390, -1, 19402, 19390, 19403, -1, 18961, 18960, 18947, -1, 19402, 19392, 19389, -1, 19404, 19405, 19406, -1, 19402, 19407, 19392, -1, 19404, 19406, 19408, -1, 19409, 19410, 19411, -1, 19409, 19412, 19410, -1, 19409, 19413, 19414, -1, 19409, 19411, 19413, -1, 19415, 19416, 19417, -1, 19415, 19417, 19367, -1, 19415, 19367, 19418, -1, 19419, 19400, 19420, -1, 19419, 19381, 19399, -1, 19419, 19421, 19381, -1, 19422, 19281, 19300, -1, 19419, 19399, 19400, -1, 19423, 19403, 19424, -1, 19425, 19426, 19427, -1, 19425, 19428, 19426, -1, 19423, 19407, 19402, -1, 19423, 19402, 19403, -1, 19429, 19412, 19409, -1, 19429, 19409, 19414, -1, 19429, 19430, 19412, -1, 19431, 19432, 19433, -1, 19431, 19434, 19435, -1, 19431, 19435, 19436, -1, 19431, 19436, 19432, -1, 19437, 19422, 19300, -1, 19438, 19384, 19388, -1, 19438, 19439, 19440, -1, 19441, 19442, 19425, -1, 19438, 19440, 19384, -1, 19438, 19388, 19439, -1, 19443, 19416, 19415, -1, 19443, 19418, 19444, -1, 19443, 19415, 19418, -1, 19445, 18928, 18927, -1, 19446, 19447, 19421, -1, 19446, 19419, 19420, -1, 19446, 19421, 19419, -1, 19445, 18927, 19448, -1, 19449, 19424, 19450, -1, 19451, 19404, 19408, -1, 19449, 19407, 19423, -1, 19449, 19423, 19424, -1, 18932, 19437, 18933, -1, 19449, 19452, 19407, -1, 19449, 19453, 19452, -1, 19454, 19429, 19414, -1, 19455, 19237, 19391, -1, 19454, 19414, 19456, -1, 19454, 19430, 19429, -1, 19454, 19456, 19430, -1, 19455, 19457, 19237, -1, 19458, 19459, 19460, -1, 19458, 19461, 19459, -1, 19458, 19460, 19462, -1, 19463, 19464, 19416, -1, 19463, 19444, 19465, -1, 19463, 19443, 19444, -1, 19463, 19416, 19443, -1, 19466, 19433, 19467, -1, 19466, 19431, 19433, -1, 19466, 19434, 19431, -1, 19468, 19330, 19333, -1, 19466, 19467, 19434, -1, 19468, 19333, 19469, -1, 19470, 19471, 11856, -1, 19470, 19472, 19471, -1, 19470, 11856, 11776, -1, 19470, 11776, 19473, -1, 19474, 19420, 19475, -1, 19474, 19475, 11307, -1, 19474, 11307, 11315, -1, 19474, 19476, 19447, -1, 19474, 19447, 19446, -1, 19474, 19446, 19420, -1, 19474, 11315, 19476, -1, 19477, 19449, 19450, -1, 19477, 19453, 19449, -1, 19477, 19478, 19453, -1, 19479, 19461, 19458, -1, 19479, 19458, 19462, -1, 19479, 19480, 19461, -1, 19479, 19462, 19481, -1, 19482, 19397, 19396, -1, 19483, 19484, 19464, -1, 19483, 19465, 19485, -1, 19483, 19464, 19463, -1, 19483, 19463, 19465, -1, 19486, 19470, 19473, -1, 19486, 19472, 19470, -1, 19486, 19487, 19472, -1, 19486, 19473, 19488, -1, 19489, 19477, 19450, -1, 19489, 19450, 19490, -1, 19491, 19457, 19455, -1, 19489, 19490, 19492, -1, 19489, 19478, 19477, -1, 19489, 19492, 19478, -1, 19493, 19494, 19495, -1, 19493, 19495, 19496, -1, 19493, 19497, 19494, -1, 19493, 19496, 19497, -1, 19498, 19499, 19484, -1, 19498, 19484, 19483, -1, 19500, 19501, 19502, -1, 19498, 19483, 19485, -1, 19498, 19485, 19503, -1, 19504, 19480, 19479, -1, 19504, 19481, 19505, -1, 18998, 18943, 18944, -1, 19506, 19501, 19500, -1, 19504, 19507, 19508, -1, 19509, 18990, 19401, -1, 19504, 19508, 19480, -1, 19504, 19479, 19481, -1, 19510, 19511, 19512, -1, 19510, 19512, 19513, -1, 19514, 12026, 12030, -1, 19510, 19513, 19515, -1, 19516, 19517, 19518, -1, 19516, 19519, 19520, -1, 19516, 19518, 19519, -1, 19521, 19486, 19488, -1, 19521, 19487, 19486, -1, 19521, 19522, 19487, -1, 19521, 19488, 19523, -1, 19524, 19503, 19525, -1, 19524, 19525, 19526, -1, 19524, 19499, 19498, -1, 19524, 19526, 19499, -1, 19524, 19498, 19503, -1, 19527, 19504, 19505, -1, 19527, 19505, 19528, -1, 19529, 19509, 19401, -1, 19527, 19530, 19507, -1, 19527, 19507, 19504, -1, 19531, 19532, 19533, -1, 19531, 19533, 19511, -1, 19531, 19515, 19532, -1, 19531, 19511, 19510, -1, 19531, 19510, 19515, -1, 19534, 19516, 19520, -1, 19535, 19422, 19437, -1, 19534, 19536, 19517, -1, 19534, 19517, 19516, -1, 19537, 19522, 19521, -1, 19538, 19404, 19451, -1, 19537, 19523, 19539, -1, 19537, 19521, 19523, -1, 19540, 19527, 19528, -1, 19540, 19528, 19541, -1, 19540, 19530, 19527, -1, 19540, 19541, 19530, -1, 19542, 19492, 19543, -1, 19542, 19544, 19492, -1, 19545, 19546, 19547, -1, 19545, 19548, 19546, -1, 19545, 19549, 19548, -1, 19550, 19551, 19552, -1, 19550, 19553, 19554, -1, 19550, 19552, 19553, -1, 19555, 19445, 19448, -1, 19550, 19554, 19551, -1, 19556, 19557, 19558, -1, 19556, 19558, 19559, -1, 19556, 19559, 19536, -1, 19556, 19534, 19520, -1, 19556, 19520, 19557, -1, 19556, 19536, 19534, -1, 19560, 19561, 19522, -1, 19555, 19448, 19562, -1, 19560, 19537, 19539, -1, 19560, 19522, 19537, -1, 19560, 19539, 19563, -1, 19564, 11877, 11840, -1, 19564, 11867, 11877, -1, 19564, 11840, 19565, -1, 19564, 19566, 11867, -1, 19567, 11286, 19568, -1, 19567, 19542, 19543, -1, 19567, 19543, 19569, -1, 19567, 19569, 11283, -1, 19567, 11283, 11286, -1, 19567, 19568, 19544, -1, 19567, 19544, 19542, -1, 19570, 19538, 19451, -1, 19571, 19526, 19572, -1, 19573, 19535, 19437, -1, 19571, 19574, 19526, -1, 19571, 19575, 19574, -1, 19576, 19547, 19577, -1, 19576, 19577, 19578, -1, 19573, 19437, 18932, -1, 19576, 19545, 19547, -1, 19576, 19549, 19545, -1, 19579, 19563, 19580, -1, 19579, 19561, 19560, -1, 19581, 19468, 19469, -1, 19579, 19560, 19563, -1, 19579, 19582, 19561, -1, 19583, 19584, 19566, -1, 19581, 19469, 19585, -1, 19583, 19566, 19564, -1, 19583, 19565, 19584, -1, 19583, 19564, 19565, -1, 19586, 19549, 19576, -1, 19586, 19576, 19578, -1, 19586, 19587, 19549, -1, 19588, 19572, 19589, -1, 19590, 19591, 19592, -1, 19588, 19571, 19572, -1, 19588, 19575, 19571, -1, 19593, 19582, 19579, -1, 19593, 19580, 19594, -1, 19593, 19595, 19596, -1, 11535, 11525, 19597, -1, 19593, 19596, 19582, -1, 19593, 19579, 19580, -1, 19598, 19599, 19600, -1, 19598, 19601, 19599, -1, 19598, 19600, 19602, -1, 19603, 19604, 19605, -1, 19603, 19605, 19606, -1, 19607, 19590, 19592, -1, 19603, 19606, 19608, -1, 19603, 19608, 19604, -1, 19609, 19587, 19586, -1, 19609, 19578, 19610, -1, 19609, 19610, 19587, -1, 19609, 19586, 19578, -1, 19611, 19588, 19589, -1, 19611, 19575, 19588, -1, 19612, 18976, 18966, -1, 19611, 19589, 19613, -1, 19611, 19614, 19575, -1, 19615, 19593, 19594, -1, 19615, 19595, 19593, -1, 19616, 19601, 19598, -1, 19616, 19598, 19602, -1, 19617, 19618, 19441, -1, 19616, 19619, 19601, -1, 19616, 19602, 19620, -1, 19621, 19613, 19622, -1, 19617, 19441, 19425, -1, 19621, 19611, 19613, -1, 19621, 19614, 19611, -1, 19621, 19623, 19614, -1, 19003, 11689, 11780, -1, 19624, 19594, 19625, -1, 19624, 19626, 19595, -1, 19624, 19595, 19615, -1, 19624, 19615, 19594, -1, 19627, 19509, 19529, -1, 19628, 19629, 19630, -1, 19628, 19630, 19619, -1, 19628, 19619, 19616, -1, 19628, 19616, 19620, -1, 19628, 19620, 19631, -1, 19632, 19621, 19622, -1, 19632, 19622, 19633, -1, 19632, 19634, 19623, -1, 19632, 19623, 19621, -1, 19635, 19624, 19625, -1, 19635, 19625, 19636, -1, 19635, 19637, 19626, -1, 19635, 19626, 19624, -1, 19638, 19639, 19640, -1, 19641, 19642, 19643, -1, 19641, 19643, 19644, -1, 19645, 18998, 18944, -1, 19641, 19644, 19646, -1, 19647, 19648, 19634, -1, 19647, 19632, 19633, -1, 19647, 19634, 19632, -1, 19647, 19633, 19648, -1, 19649, 19650, 19651, -1, 19649, 19651, 19652, -1, 19649, 19653, 19650, -1, 19654, 19655, 19656, -1, 19654, 11894, 11899, -1, 19654, 11899, 19655, -1, 19654, 19656, 11894, -1, 19657, 19658, 19659, -1, 19657, 11665, 19660, -1, 19657, 19659, 11659, -1, 19657, 11662, 11665, -1, 19657, 11659, 11662, -1, 19657, 19660, 19658, -1, 19661, 19629, 19628, -1, 19661, 19631, 19662, -1, 19661, 19663, 19629, -1, 19661, 19628, 19631, -1, 19664, 19636, 19665, -1, 19664, 19635, 19636, -1, 19018, 19627, 19529, -1, 19664, 19637, 19635, -1, 19666, 19538, 19570, -1, 19664, 19667, 19637, -1, 19668, 19669, 19670, -1, 19668, 19670, 19671, -1, 19668, 19671, 19672, -1, 19668, 19672, 19673, -1, 19674, 19675, 19676, -1, 19674, 19642, 19641, -1, 19674, 19676, 19642, -1, 19674, 19641, 19646, -1, 19674, 19646, 19675, -1, 19677, 19672, 19653, -1, 11534, 11535, 19597, -1, 19677, 19653, 19649, -1, 19677, 19649, 19652, -1, 19677, 19652, 19672, -1, 19678, 19667, 19664, -1, 19678, 19664, 19665, -1, 19678, 19665, 19679, -1, 19680, 19663, 19661, -1, 19680, 19662, 19681, -1, 19680, 19681, 19663, -1, 19680, 19661, 19662, -1, 19682, 19669, 19668, -1, 19682, 19683, 19669, -1, 19682, 19668, 19673, -1, 19682, 19673, 19684, -1, 19685, 19686, 19687, -1, 19685, 19688, 19686, -1, 19014, 19555, 19562, -1, 19685, 19687, 19689, -1, 19685, 19689, 19688, -1, 19690, 19691, 19692, -1, 19690, 19693, 19691, -1, 19014, 19562, 18993, -1, 19690, 19694, 19693, -1, 19695, 19696, 19697, -1, 19698, 19699, 19667, -1, 19695, 19697, 19700, -1, 19698, 19679, 19701, -1, 19698, 19667, 19678, -1, 19698, 19678, 19679, -1, 19702, 18976, 19612, -1, 19703, 19694, 19690, -1, 19703, 19692, 19704, -1, 19703, 19690, 19692, -1, 19705, 19706, 19683, -1, 19707, 19590, 19607, -1, 19705, 19683, 19682, -1, 19056, 18987, 18986, -1, 19705, 19684, 19708, -1, 19705, 19682, 19684, -1, 19056, 19581, 19585, -1, 19709, 19710, 19711, -1, 19056, 19585, 18987, -1, 19709, 19712, 19710, -1, 19709, 19713, 19712, -1, 19714, 19698, 19701, -1, 19715, 19535, 19573, -1, 19714, 19716, 19699, -1, 19714, 19701, 19717, -1, 19714, 19717, 19716, -1, 19714, 19699, 19698, -1, 19718, 19703, 19704, -1, 19719, 19702, 19612, -1, 19718, 19694, 19703, -1, 19718, 19704, 19720, -1, 19718, 19721, 19694, -1, 19722, 19723, 19706, -1, 19722, 19705, 19708, -1, 19722, 19708, 19723, -1, 19722, 19706, 19705, -1, 19724, 19713, 19709, -1, 19724, 19709, 19711, -1, 19724, 19711, 19725, -1, 19055, 19581, 19056, -1, 19726, 19727, 19728, -1, 19729, 19707, 19607, -1, 19726, 19728, 19730, -1, 19726, 19730, 19731, -1, 19726, 19731, 19727, -1, 19732, 19733, 19734, -1, 19732, 19735, 19733, -1, 19732, 19734, 19736, -1, 19737, 19720, 19738, -1, 19737, 19738, 19721, -1, 19737, 19721, 19718, -1, 19737, 19718, 19720, -1, 19739, 19717, 19740, -1, 19739, 19741, 19742, -1, 19739, 19742, 19716, -1, 19739, 19740, 19743, -1, 19739, 19716, 19717, -1, 19744, 19639, 19638, -1, 19739, 19745, 19741, -1, 19739, 19743, 19745, -1, 19746, 19725, 19747, -1, 19746, 19713, 19724, -1, 19746, 19724, 19725, -1, 19746, 19748, 19713, -1, 19749, 18998, 19645, -1, 19750, 19751, 19735, -1, 19750, 19736, 19752, -1, 19750, 19732, 19736, -1, 19750, 19735, 19732, -1, 19753, 19754, 19755, -1, 19756, 19757, 19758, -1, 19753, 19759, 19760, -1, 19756, 19758, 19761, -1, 19753, 19755, 19759, -1, 19762, 19763, 19741, -1, 19762, 19741, 19745, -1, 19762, 19745, 19764, -1, 19765, 19747, 19766, -1, 19029, 19627, 19018, -1, 19765, 19746, 19747, -1, 19765, 19767, 19748, -1, 19765, 19748, 19746, -1, 19768, 19750, 19752, -1, 11437, 11441, 19008, -1, 19768, 19769, 19751, -1, 19768, 19751, 19750, -1, 19770, 19753, 19760, -1, 19770, 19760, 19771, -1, 19770, 19754, 19753, -1, 19772, 19773, 19763, -1, 19772, 19763, 19762, -1, 19772, 19762, 19764, -1, 19772, 19764, 19774, -1, 19775, 19765, 19766, -1, 19775, 19767, 19765, -1, 19775, 19766, 19776, -1, 19777, 19740, 19778, -1, 19034, 18969, 19031, -1, 19777, 19743, 19740, -1, 19777, 19778, 19779, -1, 19777, 19779, 19743, -1, 19780, 19752, 19781, -1, 19780, 19769, 19768, -1, 19780, 19768, 19752, -1, 19782, 19783, 19784, -1, 19034, 18981, 18969, -1, 19780, 19785, 19769, -1, 19786, 19770, 19771, -1, 19786, 19754, 19770, -1, 19786, 19771, 19787, -1, 19048, 18972, 18974, -1, 19786, 19787, 19788, -1, 19786, 19788, 19754, -1, 19789, 19774, 19790, -1, 19789, 19772, 19774, -1, 19789, 19773, 19772, -1, 19791, 19535, 19715, -1, 19792, 19793, 11922, -1, 19791, 19006, 19535, -1, 19792, 11922, 11906, -1, 19047, 18972, 19048, -1, 19792, 11906, 19794, -1, 19795, 11648, 19796, -1, 19795, 19797, 11648, -1, 19795, 19767, 19775, -1, 19795, 19776, 19797, -1, 19795, 19796, 19767, -1, 19795, 19775, 19776, -1, 19798, 19799, 19785, -1, 19798, 19781, 19800, -1, 19798, 19785, 19780, -1, 19798, 19780, 19781, -1, 18999, 18998, 19749, -1, 19801, 19696, 19695, -1, 19802, 19803, 19804, -1, 19802, 19804, 19805, -1, 19802, 19805, 19806, -1, 19802, 19806, 19807, -1, 19801, 19808, 19696, -1, 19809, 19790, 19810, -1, 19809, 19773, 19789, -1, 19809, 19811, 19773, -1, 19809, 19789, 19790, -1, 19812, 19792, 19794, -1, 19812, 19793, 19792, -1, 19812, 19813, 19793, -1, 19814, 19801, 19695, -1, 19812, 19794, 19815, -1, 19816, 19817, 19799, -1, 19818, 19702, 19719, -1, 19816, 19799, 19798, -1, 19816, 19798, 19800, -1, 19816, 19800, 19817, -1, 19819, 19820, 19821, -1, 19822, 19783, 19782, -1, 19819, 19823, 19824, -1, 19819, 19824, 19820, -1, 19825, 19810, 19826, -1, 19825, 19811, 19809, -1, 19825, 19809, 19810, -1, 19825, 19827, 19811, -1, 19828, 19829, 19803, -1, 19828, 19803, 19802, -1, 19828, 19802, 19807, -1, 19830, 19821, 19831, -1, 19830, 19819, 19821, -1, 19830, 19823, 19819, -1, 19832, 19833, 19834, -1, 19832, 19812, 19815, -1, 19835, 19707, 19729, -1, 19832, 19834, 19813, -1, 19832, 19813, 19812, -1, 19832, 19815, 19833, -1, 19836, 19826, 19837, -1, 19836, 19825, 19826, -1, 19836, 19827, 19825, -1, 19836, 19837, 19838, -1, 19836, 19838, 19827, -1, 19839, 19807, 19840, -1, 19839, 19829, 19828, -1, 19839, 19828, 19807, -1, 19839, 19841, 19842, -1, 19839, 19842, 19829, -1, 19007, 19006, 19791, -1, 19843, 19831, 19844, -1, 19843, 19830, 19831, -1, 19845, 19835, 19729, -1, 19843, 19846, 19823, -1, 19843, 19823, 19830, -1, 19847, 19848, 19849, -1, 19025, 19818, 19719, -1, 19847, 19850, 19848, -1, 19847, 19849, 19851, -1, 19852, 19853, 19854, -1, 19852, 19855, 19834, -1, 19852, 19834, 19853, -1, 19856, 19857, 19858, -1, 19859, 19860, 19861, -1, 19859, 19862, 19863, -1, 19856, 19864, 19857, -1, 19859, 19863, 19860, -1, 19859, 19838, 19837, -1, 19859, 19837, 19862, -1, 19859, 19861, 19865, -1, 19866, 19845, 19867, -1, 19859, 19865, 19838, -1, 19868, 19846, 19843, -1, 19869, 19749, 19645, -1, 19868, 19870, 19846, -1, 19869, 19645, 19871, -1, 19868, 19843, 19844, -1, 19868, 19844, 19870, -1, 19872, 19873, 19874, -1, 19872, 19840, 19873, -1, 19872, 19841, 19839, -1, 19872, 19839, 19840, -1, 19872, 19874, 19841, -1, 19875, 19876, 19877, -1, 19875, 19877, 19878, -1, 19875, 19879, 19876, -1, 19880, 19881, 19882, -1, 19880, 19883, 19881, -1, 19880, 19884, 19883, -1, 19885, 19851, 19886, -1, 19885, 19887, 19850, -1, 19885, 19886, 19887, -1, 19888, 19761, 19889, -1, 19885, 19850, 19847, -1, 19885, 19847, 19851, -1, 19890, 19855, 19852, -1, 19888, 19756, 19761, -1, 19890, 19852, 19854, -1, 19890, 19891, 19855, -1, 19892, 19893, 19894, -1, 19892, 11943, 11928, -1, 19892, 11932, 11943, -1, 19892, 11928, 19895, -1, 19892, 19894, 11932, -1, 19896, 19879, 19875, -1, 19896, 11627, 19897, -1, 19896, 19875, 19878, -1, 19896, 19878, 11618, -1, 19896, 11618, 11627, -1, 19896, 19897, 19879, -1, 19898, 19861, 19860, -1, 19898, 19860, 19899, -1, 19898, 19900, 19861, -1, 19901, 19880, 19882, -1, 19901, 19882, 19902, -1, 19901, 19903, 19884, -1, 19901, 19884, 19880, -1, 19904, 19854, 19905, -1, 19904, 19890, 19854, -1, 19904, 19891, 19890, -1, 19906, 19907, 19893, -1, 19906, 19893, 19892, -1, 19906, 19895, 19907, -1, 19906, 19892, 19895, -1, 19908, 19902, 19909, -1, 19908, 19901, 19902, -1, 19908, 19903, 19901, -1, 19910, 19900, 19898, -1, 19910, 19899, 19911, -1, 19910, 19898, 19899, -1, 19910, 19912, 19900, -1, 19913, 19914, 19915, -1, 19916, 19904, 19905, -1, 19916, 19905, 19917, -1, 19916, 19917, 19918, -1, 19916, 19918, 19891, -1, 19916, 19891, 19904, -1, 19919, 19920, 19921, -1, 19919, 19863, 19862, -1, 19919, 19921, 19863, -1, 19919, 19862, 19920, -1, 19922, 19923, 19924, -1, 19925, 19801, 19814, -1, 19922, 19926, 19927, -1, 19922, 19927, 19923, -1, 19922, 19924, 19928, -1, 19922, 19928, 19926, -1, 19929, 19930, 19931, -1, 19929, 19908, 19909, -1, 19929, 19903, 19908, -1, 19929, 19909, 19930, -1, 19929, 19931, 19903, -1, 19932, 19910, 19911, -1, 19932, 19911, 19933, -1, 19932, 19912, 19910, -1, 19934, 19935, 19936, -1, 19934, 19936, 19937, -1, 19934, 19938, 19935, -1, 19934, 19939, 19938, -1, 19940, 19941, 19912, -1, 19940, 19932, 19933, -1, 19940, 19912, 19932, -1, 19940, 19933, 19942, -1, 19943, 19917, 19944, -1, 19945, 19925, 19814, -1, 19943, 19946, 19917, -1, 19943, 19947, 19946, -1, 19948, 19835, 19845, -1, 19062, 19818, 19025, -1, 19949, 19950, 19951, -1, 19949, 19952, 19950, -1, 19949, 19951, 19953, -1, 19954, 19939, 19934, -1, 19954, 19934, 19937, -1, 19954, 19955, 19939, -1, 19956, 19940, 19942, -1, 19956, 19941, 19940, -1, 19956, 19957, 19941, -1, 19956, 19942, 19958, -1, 19042, 19036, 19043, -1, 19959, 19944, 19960, -1, 19961, 19871, 19962, -1, 19961, 19869, 19871, -1, 19959, 19947, 19943, -1, 19959, 19943, 19944, -1, 19963, 19964, 19928, -1, 19963, 19965, 19964, -1, 19963, 19924, 19965, -1, 19963, 19928, 19924, -1, 19966, 19952, 19949, -1, 19966, 19953, 19967, -1, 19966, 19949, 19953, -1, 19968, 19956, 19958, -1, 19968, 19957, 19956, -1, 19968, 19969, 19957, -1, 19968, 19958, 19970, -1, 19971, 19937, 19972, -1, 19971, 19954, 19937, -1, 19973, 19858, 19974, -1, 19971, 19975, 19976, -1, 19973, 19856, 19858, -1, 19971, 19976, 19955, -1, 19971, 19955, 19954, -1, 19977, 19960, 18390, -1, 19977, 19959, 19960, -1, 19977, 19947, 19959, -1, 19977, 19978, 19947, -1, 19977, 18390, 19978, -1, 19098, 19002, 19004, -1, 19979, 19980, 19981, -1, 19979, 19982, 18371, -1, 19979, 19981, 19982, -1, 19983, 19952, 19966, -1, 19983, 19966, 19967, -1, 19983, 19984, 19952, -1, 19983, 19967, 19985, -1, 19986, 19969, 19968, -1, 19037, 19036, 19042, -1, 19987, 19948, 19845, -1, 19987, 19845, 19866, -1, 19986, 19988, 19989, -1, 19986, 19989, 19969, -1, 19986, 19968, 19970, -1, 19990, 19978, 18392, -1, 19990, 19991, 19978, -1, 19990, 18392, 19992, -1, 19993, 19888, 19889, -1, 19994, 19971, 19972, -1, 19993, 19889, 19995, -1, 19994, 19975, 19971, -1, 19994, 19972, 18410, -1, 19994, 18409, 19975, -1, 19994, 18410, 18409, -1, 19996, 19997, 19980, -1, 19996, 19979, 18371, -1, 19996, 19980, 19979, -1, 19996, 18371, 18370, -1, 19998, 19999, 20000, -1, 19998, 20001, 19999, -1, 19080, 19032, 19075, -1, 19998, 20002, 20001, -1, 20003, 19985, 20004, -1, 19080, 19033, 19032, -1, 20003, 19983, 19985, -1, 20003, 19984, 19983, -1, 20003, 20004, 19984, -1, 20005, 18395, 20006, -1, 20005, 20007, 18396, -1, 20005, 20006, 20007, -1, 20005, 18396, 18395, -1, 20008, 19986, 19970, -1, 20008, 19970, 20009, -1, 20008, 19988, 19986, -1, 20010, 19066, 19050, -1, 20011, 19991, 19990, -1, 20011, 20012, 19991, -1, 20011, 19990, 19992, -1, 20013, 20000, 20014, -1, 20013, 19998, 20000, -1, 20013, 20002, 19998, -1, 20015, 20016, 20017, -1, 20018, 20019, 19997, -1, 20018, 19997, 19996, -1, 20018, 19996, 18370, -1, 20020, 20009, 20021, -1, 19068, 19076, 19067, -1, 20020, 20022, 19988, -1, 20020, 19988, 20008, -1, 20020, 20008, 20009, -1, 20023, 18396, 20012, -1, 20023, 18394, 18396, -1, 20023, 20012, 20011, -1, 20023, 19992, 20024, -1, 20023, 20024, 18394, -1, 20023, 20011, 19992, -1, 20025, 20014, 20026, -1, 20025, 20027, 20002, -1, 20025, 20002, 20013, -1, 20025, 20013, 20014, -1, 20028, 12041, 12044, -1, 20029, 20019, 20018, -1, 20029, 18445, 20019, -1, 20029, 18443, 18445, -1, 20029, 18370, 18443, -1, 20029, 20018, 18370, -1, 20030, 20031, 20032, -1, 20030, 20033, 20031, -1, 20034, 19925, 19945, -1, 20030, 20032, 20035, -1, 20036, 20021, 20037, -1, 20036, 20020, 20021, -1, 20036, 20022, 20020, -1, 20036, 18388, 20022, -1, 20038, 18427, 18469, -1, 20038, 18471, 20039, -1, 20038, 20039, 18421, -1, 20038, 18421, 18427, -1, 20038, 18469, 18471, -1, 20040, 20027, 20025, -1, 20040, 20026, 18420, -1, 20040, 20025, 20026, -1, 20040, 18420, 18422, -1, 20040, 18422, 20027, -1, 20041, 20037, 20042, -1, 20043, 19913, 19915, -1, 19099, 19098, 19004, -1, 20041, 18388, 20036, -1, 20041, 20036, 20037, -1, 20044, 18462, 18455, -1, 20044, 18455, 20045, -1, 20044, 18440, 20046, -1, 20044, 20046, 18462, -1, 19088, 19130, 19039, -1, 20047, 20033, 20030, -1, 19088, 19039, 19037, -1, 20047, 18527, 18526, -1, 20047, 20048, 20033, -1, 20047, 20030, 20035, -1, 20047, 20035, 18527, -1, 20049, 20050, 18398, -1, 20049, 18398, 18394, -1, 20049, 18394, 20051, -1, 20052, 20042, 20053, -1, 20052, 18425, 18388, -1, 19101, 19962, 19098, -1, 20052, 20041, 20042, -1, 19101, 19961, 19962, -1, 20052, 18388, 20041, -1, 20054, 20045, 20055, -1, 20054, 18440, 20044, -1, 20054, 20044, 20045, -1, 20056, 20048, 20047, -1, 19078, 19076, 19068, -1, 20056, 20057, 20048, -1, 20058, 20034, 19945, -1, 20056, 20047, 18526, -1, 20059, 18469, 18427, -1, 20059, 18427, 18550, -1, 20059, 18550, 18552, -1, 20059, 18552, 18469, -1, 20060, 20050, 20049, -1, 20060, 20049, 20051, -1, 20060, 20051, 20061, -1, 20062, 20053, 20063, -1, 20062, 20064, 18425, -1, 20062, 20052, 20053, -1, 20062, 18425, 20052, -1, 20065, 18438, 18440, -1, 20065, 20066, 18438, -1, 20065, 20054, 20055, -1, 20065, 20055, 20067, -1, 20065, 18440, 20054, -1, 20068, 20056, 18526, -1, 20068, 18526, 20069, -1, 20068, 20069, 18542, -1, 20068, 20057, 20056, -1, 20068, 18541, 20057, -1, 20068, 18542, 18541, -1, 20070, 18576, 18575, -1, 20071, 19973, 19974, -1, 20070, 18575, 20050, -1, 20070, 20060, 20061, -1, 20070, 20050, 20060, -1, 20072, 19066, 20010, -1, 20070, 20061, 18576, -1, 20073, 18452, 11976, -1, 20073, 20074, 18452, -1, 20073, 11976, 11970, -1, 20071, 19974, 20075, -1, 20073, 11970, 20076, -1, 20077, 20016, 20015, -1, 20078, 20063, 11577, -1, 20078, 11577, 11585, -1, 20078, 18501, 20064, -1, 20078, 20064, 20062, -1, 20078, 20062, 20063, -1, 20078, 11585, 18501, -1, 20079, 20080, 20066, -1, 20079, 20066, 20065, -1, 20079, 20065, 20067, -1, 20081, 18557, 18566, -1, 20081, 18566, 20082, -1, 20081, 20083, 20084, -1, 20085, 20086, 20087, -1, 20081, 20084, 18557, -1, 20085, 19995, 20086, -1, 20088, 20089, 18575, -1, 20088, 18575, 18574, -1, 20088, 18574, 20090, -1, 20085, 19993, 19995, -1, 20091, 20073, 20076, -1, 20091, 18587, 20074, -1, 20092, 19948, 19987, -1, 20091, 20076, 20093, -1, 20091, 20074, 20073, -1, 20094, 18680, 20080, -1, 20094, 20079, 20067, -1, 20094, 20067, 20095, -1, 20094, 20095, 18680, -1, 20094, 20080, 20079, -1, 20096, 20072, 20010, -1, 20097, 18520, 18470, -1, 20097, 18524, 20098, -1, 20097, 18470, 18524, -1, 20099, 20077, 20015, -1, 20100, 18551, 18602, -1, 20100, 18549, 18551, -1, 20100, 18602, 18601, -1, 20100, 18601, 18549, -1, 20101, 20102, 20089, -1, 20101, 20089, 20088, -1, 20101, 20088, 20090, -1, 20103, 20081, 20082, -1, 20104, 19993, 20085, -1, 20103, 20083, 20081, -1, 20103, 20082, 20105, -1, 20103, 20106, 20083, -1, 20107, 20097, 20098, -1, 20107, 18520, 20097, -1, 20107, 20098, 20108, -1, 20109, 20091, 20093, -1, 20109, 18587, 20091, -1, 20109, 18586, 18587, -1, 20109, 20093, 20110, -1, 20111, 18602, 20102, -1, 20111, 20102, 20101, -1, 20111, 20101, 20090, -1, 20111, 18600, 18602, -1, 20111, 20090, 20112, -1, 20113, 19913, 20043, -1, 20111, 20112, 18600, -1, 20114, 18645, 18646, -1, 20114, 20105, 18645, -1, 20114, 20106, 20103, -1, 20114, 20103, 20105, -1, 20114, 18646, 20106, -1, 20115, 18562, 18520, -1, 20115, 18520, 20107, -1, 20115, 20107, 20108, -1, 20115, 20108, 20116, -1, 20117, 18545, 18540, -1, 20117, 18540, 20118, -1, 20117, 20119, 18545, -1, 20120, 20109, 20110, -1, 20120, 18586, 20109, -1, 20121, 20034, 20058, -1, 20120, 20110, 20122, -1, 20123, 20116, 18608, -1, 20123, 18610, 18562, -1, 20123, 18608, 18610, -1, 20123, 20115, 20116, -1, 20123, 18562, 20115, -1, 11519, 11497, 20124, -1, 20125, 20118, 20126, -1, 20125, 20119, 20117, -1, 20125, 20117, 20118, -1, 20127, 20128, 20129, -1, 20127, 20105, 20082, -1, 20127, 20129, 20130, -1, 20127, 20130, 20105, -1, 20127, 20082, 20131, -1, 20127, 20131, 20128, -1, 20132, 18586, 20120, -1, 20132, 20133, 18586, -1, 20132, 20122, 20134, -1, 20132, 20120, 20122, -1, 20135, 20095, 18654, -1, 20135, 18680, 20095, -1, 20136, 11987, 11994, -1, 20136, 11991, 18809, -1, 20136, 18614, 11987, -1, 20137, 20138, 20139, -1, 20136, 18809, 18808, -1, 20136, 18808, 18614, -1, 20136, 11994, 11991, -1, 20137, 20139, 20140, -1, 19176, 11786, 11793, -1, 20141, 18679, 18678, -1, 19176, 11695, 11786, -1, 20141, 11556, 11569, -1, 20141, 18650, 18679, -1, 20141, 11569, 18650, -1, 20141, 18678, 20142, -1, 20141, 20142, 11556, -1, 20143, 20144, 18603, -1, 20143, 18600, 20145, -1, 20146, 20147, 20148, -1, 20143, 18603, 18600, -1, 20149, 20125, 20126, -1, 20149, 20119, 20125, -1, 20149, 20126, 18753, -1, 20150, 20151, 19948, -1, 20149, 20152, 20119, -1, 20149, 18753, 18757, -1, 19137, 19089, 19090, -1, 20153, 20132, 20134, -1, 20150, 19948, 20092, -1, 20153, 20133, 20132, -1, 20153, 20154, 20133, -1, 20155, 20147, 20146, -1, 20153, 20134, 18719, -1, 20156, 18680, 20135, -1, 20156, 20135, 18654, -1, 20156, 18678, 18680, -1, 20156, 18654, 18653, -1, 20156, 18653, 18678, -1, 20157, 20149, 18757, -1, 20158, 19913, 20113, -1, 20157, 20159, 20152, -1, 20157, 20152, 20149, -1, 20160, 20072, 20096, -1, 20161, 20144, 20143, -1, 20161, 20143, 20145, -1, 20161, 20145, 20162, -1, 20163, 18719, 18718, -1, 20163, 20164, 20154, -1, 20163, 20154, 20153, -1, 20163, 20153, 18719, -1, 20165, 18765, 18771, -1, 20165, 20129, 20128, -1, 20165, 18768, 18765, -1, 20165, 18771, 20129, -1, 20165, 20128, 18768, -1, 20166, 20077, 20099, -1, 20167, 18767, 18766, -1, 20167, 18757, 20168, -1, 20167, 20168, 18767, -1, 20167, 20159, 20157, -1, 20167, 18766, 20159, -1, 20167, 20157, 18757, -1, 20169, 18859, 18858, -1, 20169, 18858, 20144, -1, 20169, 20144, 20161, -1, 20169, 20162, 18859, -1, 20169, 20161, 20162, -1, 20170, 20163, 18718, -1, 20170, 20171, 20164, -1, 20170, 20164, 20163, -1, 20172, 18826, 20173, -1, 20172, 18795, 18826, -1, 20172, 20174, 20175, -1, 20172, 20175, 18795, -1, 20176, 20177, 18858, -1, 20176, 18858, 18857, -1, 20178, 20170, 18718, -1, 20178, 18718, 20179, -1, 20178, 20180, 20171, -1, 20178, 20171, 20170, -1, 20181, 18667, 18760, -1, 20181, 18743, 18667, -1, 20181, 18760, 20182, -1, 19129, 20160, 20096, -1, 20183, 20172, 20173, -1, 20183, 20174, 20172, -1, 20183, 20184, 20174, -1, 20183, 20173, 20185, -1, 20186, 20187, 20177, -1, 20188, 20151, 20150, -1, 20186, 20177, 20176, -1, 20186, 20176, 18857, -1, 20186, 18857, 20189, -1, 20190, 20179, 20191, -1, 20190, 18984, 20180, -1, 20190, 20180, 20178, -1, 20190, 20178, 20179, -1, 20192, 20166, 20099, -1, 20193, 20181, 20182, -1, 20193, 18743, 20181, -1, 20193, 20182, 20194, -1, 20195, 20189, 20196, -1, 20195, 20187, 20186, -1, 20195, 20186, 20189, -1, 20197, 18807, 19161, -1, 11405, 11410, 19157, -1, 20197, 18812, 18807, -1, 20198, 20043, 20199, -1, 20197, 19161, 19168, -1, 20198, 20113, 20043, -1, 20200, 19158, 19159, -1, 20200, 20185, 19158, -1, 20200, 20184, 20183, -1, 20200, 20183, 20185, -1, 20200, 19159, 20184, -1, 20201, 18984, 20190, -1, 20202, 19117, 19092, -1, 20201, 18983, 18984, -1, 20201, 20190, 20191, -1, 20203, 18743, 20193, -1, 20203, 20193, 20194, -1, 20203, 20194, 20204, -1, 20203, 18833, 18743, -1, 20205, 18877, 20187, -1, 20205, 20196, 19009, -1, 20205, 20187, 20195, -1, 20205, 20195, 20196, -1, 20205, 19009, 18877, -1, 20206, 19105, 19107, -1, 20206, 20197, 19168, -1, 20206, 18812, 20197, -1, 20206, 19168, 19105, -1, 20206, 19107, 18812, -1, 20207, 18983, 20201, -1, 20207, 20201, 20191, -1, 20207, 20191, 20208, -1, 20207, 20208, 20209, -1, 20210, 19058, 18964, -1, 20210, 19106, 19141, -1, 20210, 19141, 20211, -1, 20210, 18964, 19106, -1, 20212, 20213, 20214, -1, 20212, 20214, 20185, -1, 20212, 20173, 20215, -1, 20212, 20215, 20216, -1, 20212, 20216, 20213, -1, 20212, 20185, 20173, -1, 20217, 18955, 20218, -1, 20217, 18956, 18955, -1, 20219, 19146, 19148, -1, 20219, 20203, 20204, -1, 20219, 20204, 19146, -1, 20219, 19148, 18833, -1, 20219, 18833, 20203, -1, 20220, 18983, 20207, -1, 20220, 20209, 20221, -1, 20222, 19086, 19085, -1, 20220, 20223, 18983, -1, 20220, 20207, 20209, -1, 20224, 20218, 19406, -1, 20224, 20225, 18956, -1, 20224, 18956, 20217, -1, 20224, 20217, 20218, -1, 20226, 20227, 19058, -1, 20226, 20210, 20211, -1, 20226, 19058, 20210, -1, 20228, 19009, 20229, -1, 20228, 19020, 19009, -1, 20228, 20230, 19020, -1, 20231, 20221, 19398, -1, 20231, 20232, 20223, -1, 20231, 20220, 20221, -1, 20231, 20223, 20220, -1, 20233, 19406, 19405, -1, 20233, 20234, 20225, -1, 20233, 20224, 19406, -1, 20233, 20225, 20224, -1, 20235, 19501, 20227, -1, 20235, 19502, 19501, -1, 20235, 20227, 20226, -1, 19171, 20160, 19129, -1, 20235, 20211, 19502, -1, 20235, 20226, 20211, -1, 20236, 19370, 19077, -1, 20236, 19201, 20237, -1, 20236, 19077, 19201, -1, 20238, 20229, 20239, -1, 20238, 20230, 20228, -1, 20238, 20228, 20229, -1, 20240, 19428, 19425, -1, 20240, 19425, 19442, -1, 20240, 19442, 20213, -1, 20240, 20216, 19428, -1, 20240, 20213, 20216, -1, 20241, 20234, 20233, -1, 20241, 19427, 19426, -1, 20241, 19426, 20234, -1, 11401, 11405, 19157, -1, 20241, 20233, 19405, -1, 20241, 19405, 20242, -1, 20243, 20166, 20192, -1, 20241, 20242, 19427, -1, 20244, 19398, 19397, -1, 20244, 20245, 20246, -1, 20244, 20246, 20232, -1, 20244, 20231, 19398, -1, 20244, 20232, 20231, -1, 20247, 20230, 20238, -1, 20247, 20238, 20239, -1, 20247, 20239, 19592, -1, 20247, 19592, 19591, -1, 20247, 19591, 20230, -1, 20248, 19491, 19758, -1, 20248, 20249, 19457, -1, 20248, 19457, 19491, -1, 20250, 19370, 20236, -1, 20251, 20252, 20253, -1, 20250, 20237, 20254, -1, 20250, 19369, 19370, -1, 20250, 20236, 20237, -1, 20255, 20199, 20256, -1, 20257, 20258, 20245, -1, 20257, 20244, 19397, -1, 20257, 20245, 20244, -1, 20257, 19397, 20259, -1, 19156, 11401, 19157, -1, 20255, 20198, 20199, -1, 20260, 19591, 19590, -1, 20260, 20261, 19591, -1, 20262, 20249, 20248, -1, 20262, 20263, 20249, -1, 20264, 19117, 20202, -1, 20262, 20248, 19758, -1, 20265, 20254, 20266, -1, 20265, 19369, 20250, -1, 20265, 20250, 20254, -1, 20267, 19570, 20258, -1, 20267, 20257, 20259, -1, 20267, 20258, 20257, -1, 20268, 19086, 20222, -1, 20267, 20259, 20269, -1, 20270, 19590, 20271, -1, 20270, 20261, 20260, -1, 20272, 20273, 20274, -1, 20270, 20260, 19590, -1, 20275, 19396, 19640, -1, 20275, 19640, 19639, -1, 20275, 19639, 19482, -1, 20275, 19482, 19396, -1, 20276, 20262, 19758, -1, 20276, 19758, 19757, -1, 20277, 20252, 20251, -1, 20276, 20278, 20263, -1, 20279, 20264, 20202, -1, 20276, 20263, 20262, -1, 20280, 20266, 20281, -1, 20280, 19369, 20265, -1, 20280, 20282, 19369, -1, 20280, 20265, 20266, -1, 20283, 19570, 20267, -1, 20283, 20267, 20269, -1, 20284, 12033, 12035, -1, 20284, 12030, 12033, -1, 20284, 12035, 20285, -1, 20284, 19514, 12030, -1, 20286, 11534, 19597, -1, 20286, 20270, 20271, -1, 20286, 20261, 20270, -1, 20286, 20271, 20287, -1, 20286, 20287, 11511, -1, 20286, 11511, 11534, -1, 11396, 11401, 19156, -1, 20286, 19597, 20261, -1, 20288, 20289, 20290, -1, 20291, 19506, 19500, -1, 20292, 19140, 19096, -1, 20291, 19500, 19857, -1, 20288, 20293, 20289, -1, 20291, 19857, 19864, -1, 20294, 20278, 20276, -1, 20294, 19866, 19867, -1, 20294, 20276, 19757, -1, 20294, 19757, 19866, -1, 20294, 19867, 20278, -1, 20292, 19096, 20295, -1, 20296, 20281, 19695, -1, 19193, 19104, 19103, -1, 20296, 19695, 19700, -1, 20296, 20282, 20280, -1, 20296, 20280, 20281, -1, 20296, 19700, 20282, -1, 20297, 20298, 20299, -1, 20297, 19666, 19570, -1, 20297, 20283, 20269, -1, 20297, 19570, 20283, -1, 20297, 20269, 20298, -1, 20300, 19915, 19914, -1, 20300, 19914, 19514, -1, 20300, 20285, 19915, -1, 20300, 20284, 20285, -1, 20300, 19514, 20284, -1, 20301, 19784, 19506, -1, 20301, 19782, 19784, -1, 20301, 19864, 19782, -1, 19195, 19104, 19193, -1, 20301, 19506, 20291, -1, 20301, 20291, 19864, -1, 20302, 19617, 20303, -1, 20304, 20305, 20306, -1, 20302, 19618, 19617, -1, 20307, 20299, 20308, -1, 20307, 20309, 19666, -1, 20307, 19666, 20297, -1, 20307, 20297, 20299, -1, 20310, 19638, 19783, -1, 20310, 19744, 19638, -1, 20310, 19822, 20311, -1, 20310, 19783, 19822, -1, 20312, 20302, 20303, -1, 19145, 19144, 19086, -1, 20312, 20313, 19618, -1, 19145, 19086, 20268, -1, 20312, 19618, 20302, -1, 20312, 20303, 20017, -1, 20314, 20308, 20139, -1, 20314, 20315, 20309, -1, 20314, 20307, 20308, -1, 20314, 20309, 20307, -1, 20316, 19744, 20310, -1, 20316, 20310, 20311, -1, 20316, 20311, 20148, -1, 20316, 20148, 20147, -1, 20316, 20147, 20317, -1, 20316, 20317, 19744, -1, 20318, 20312, 20017, -1, 20318, 20017, 20016, -1, 20318, 20319, 20313, -1, 20318, 20313, 20312, -1, 20320, 20321, 20322, -1, 20320, 20322, 20315, -1, 20323, 20272, 20274, -1, 20320, 20314, 20139, -1, 20320, 20315, 20314, -1, 20320, 20139, 20138, -1, 20324, 20325, 20277, -1, 20326, 20087, 20086, -1, 20326, 20318, 20016, -1, 20326, 20086, 20319, -1, 20326, 20016, 20327, -1, 20324, 20328, 20325, -1, 20326, 20327, 20087, -1, 20326, 20319, 20318, -1, 20329, 19801, 20330, -1, 20329, 20330, 20331, -1, 20329, 19808, 19801, -1, 20329, 20075, 19808, -1, 20332, 19913, 20158, -1, 20332, 20333, 20334, -1, 20332, 20334, 19913, -1, 20335, 19125, 19112, -1, 20336, 20273, 20028, -1, 20337, 20256, 20272, -1, 20336, 12048, 12049, -1, 20337, 20255, 20256, -1, 20336, 12044, 12048, -1, 20336, 12049, 20274, -1, 20336, 20028, 12044, -1, 20336, 20274, 20273, -1, 20338, 20188, 11485, -1, 20338, 11517, 11519, -1, 20339, 20305, 20304, -1, 20338, 11485, 11517, -1, 20338, 20124, 20151, -1, 20338, 11519, 20124, -1, 20338, 20151, 20188, -1, 20340, 20320, 20138, -1, 20340, 20341, 20321, -1, 20340, 20321, 20320, -1, 20340, 20138, 20342, -1, 20343, 20329, 20331, -1, 20343, 20075, 20329, -1, 20343, 20331, 20344, -1, 20343, 20071, 20075, -1, 20345, 20264, 20279, -1, 20346, 20058, 20333, -1, 20346, 20158, 20347, -1, 20346, 20333, 20332, -1, 20346, 20332, 20158, -1, 20348, 20343, 20344, -1, 20348, 20344, 20349, -1, 20348, 20071, 20343, -1, 20350, 20192, 20341, -1, 20350, 20341, 20340, -1, 20350, 20340, 20342, -1, 20350, 20342, 20351, -1, 20352, 20058, 20346, -1, 20352, 20346, 20347, -1, 19181, 20345, 20279, -1, 20352, 20121, 20058, -1, 20352, 20347, 20353, -1, 20354, 20293, 20137, -1, 20355, 20356, 20357, -1, 20354, 20137, 20140, -1, 20355, 20357, 20358, -1, 20354, 20140, 20289, -1, 20359, 20268, 20222, -1, 20354, 20289, 20293, -1, 20360, 20277, 20325, -1, 20360, 20325, 20361, -1, 20359, 20222, 20362, -1, 20360, 20361, 20252, -1, 20360, 20252, 20277, -1, 20363, 20251, 20253, -1, 20363, 20349, 20251, -1, 20363, 20348, 20349, -1, 20363, 20253, 20071, -1, 20363, 20071, 20348, -1, 20364, 20350, 20351, -1, 20364, 20192, 20350, -1, 20365, 20155, 20146, -1, 20365, 20146, 20357, -1, 20366, 20121, 20352, -1, 20366, 20367, 20121, -1, 20366, 20352, 20353, -1, 20366, 20353, 20368, -1, 20369, 20370, 20104, -1, 20369, 20085, 20371, -1, 20369, 20104, 20085, -1, 20372, 20243, 20192, -1, 20373, 20292, 20295, -1, 20372, 20192, 20364, -1, 20372, 20364, 20351, -1, 20372, 20351, 20374, -1, 20372, 20374, 20375, -1, 20373, 20295, 20376, -1, 20377, 20356, 20304, -1, 20377, 20357, 20356, -1, 20377, 20365, 20357, -1, 20377, 20155, 20365, -1, 20377, 20306, 20155, -1, 20377, 20304, 20306, -1, 20378, 20366, 20368, -1, 20378, 20379, 20367, -1, 20378, 20367, 20366, -1, 20380, 20369, 20371, -1, 20380, 20371, 20381, -1, 20380, 20370, 20369, -1, 20382, 20339, 20383, -1, 20382, 20305, 20339, -1, 20382, 20288, 20290, -1, 20382, 20290, 20305, -1, 20384, 20243, 20372, -1, 20384, 20372, 20375, -1, 20384, 20375, 20385, -1, 20384, 20386, 20243, -1, 20387, 20378, 20368, -1, 20387, 20388, 20379, -1, 20387, 20389, 20388, -1, 20387, 20368, 20389, -1, 20387, 20379, 20378, -1, 20390, 20324, 20277, -1, 20390, 20391, 20324, -1, 20390, 20277, 20392, -1, 20390, 20392, 20391, -1, 20393, 20394, 20370, -1, 20393, 20370, 20380, -1, 20393, 20380, 20381, -1, 20393, 20381, 20395, -1, 20396, 20386, 20384, -1, 20396, 20385, 20397, -1, 20396, 20398, 20386, -1, 20396, 20384, 20385, -1, 20399, 20272, 20323, -1, 20399, 20337, 20272, -1, 20399, 20323, 20400, -1, 20401, 20402, 20403, -1, 20404, 19125, 20335, -1, 20401, 20383, 20402, -1, 20401, 20403, 20405, -1, 20401, 20405, 20288, -1, 20401, 20288, 20382, -1, 20401, 20382, 20383, -1, 20406, 20407, 20408, -1, 20406, 20409, 20410, -1, 20406, 20410, 20407, -1, 20411, 20393, 20395, -1, 20411, 20395, 20412, -1, 20411, 20413, 20394, -1, 19189, 19184, 19190, -1, 20411, 20394, 20393, -1, 20414, 20398, 20396, -1, 20414, 20396, 20397, -1, 20414, 20415, 20398, -1, 20416, 20337, 20399, -1, 20416, 20400, 20417, -1, 20416, 20399, 20400, -1, 20418, 20404, 20335, -1, 20419, 20408, 20420, -1, 20419, 20421, 20409, -1, 20419, 20409, 20406, -1, 20419, 20406, 20408, -1, 19213, 20345, 19181, -1, 20422, 20324, 20423, -1, 20422, 20423, 20424, -1, 20422, 20425, 20328, -1, 20422, 20328, 20324, -1, 20426, 20413, 20411, -1, 20426, 20412, 20427, -1, 20428, 12058, 11673, -1, 20428, 12055, 12058, -1, 20426, 20411, 20412, -1, 20429, 20430, 20431, -1, 19185, 19184, 19189, -1, 20429, 20431, 20432, -1, 20429, 20432, 20391, -1, 20429, 20433, 20430, -1, 20429, 20391, 20433, -1, 20434, 20415, 20414, -1, 20434, 20414, 20397, -1, 20434, 20435, 20415, -1, 20434, 20397, 20436, -1, 20437, 20416, 20417, -1, 20437, 20417, 20407, -1, 20433, 20391, 20392, -1, 20437, 20410, 20337, -1, 20437, 20407, 20410, -1, 20437, 20337, 20416, -1, 20438, 20439, 20440, -1, 20438, 20440, 20441, -1, 20442, 20359, 20362, -1, 20443, 20425, 20422, -1, 20443, 20424, 20444, -1, 20442, 20362, 20445, -1, 20446, 20355, 20358, -1, 20443, 20422, 20424, -1, 20447, 20419, 20420, -1, 20447, 20421, 20419, -1, 20447, 20420, 20448, -1, 20447, 20448, 20449, -1, 20447, 20449, 20421, -1, 20450, 20427, 20451, -1, 20450, 20451, 20452, -1, 20446, 20358, 20453, -1, 20450, 20452, 20413, -1, 20450, 20413, 20426, -1, 20450, 20426, 20427, -1, 20454, 20436, 20455, -1, 20454, 20434, 20436, -1, 20454, 20456, 20435, -1, 20454, 20435, 20434, -1, 20457, 20438, 20441, -1, 20457, 20430, 20439, -1, 20457, 20441, 20458, -1, 20457, 20458, 20459, -1, 20457, 20439, 20438, -1, 20460, 20444, 20461, -1, 20460, 20425, 20443, -1, 20460, 20443, 20444, -1, 20460, 20462, 20425, -1, 20463, 20464, 20428, -1, 20463, 11673, 11672, -1, 20463, 11672, 20465, -1, 19233, 20373, 20376, -1, 20463, 20465, 20466, -1, 19233, 20376, 19218, -1, 20463, 20428, 11673, -1, 20467, 20454, 20455, -1, 20467, 20455, 20468, -1, 20467, 20469, 20456, -1, 20467, 20456, 20454, -1, 20470, 20471, 20472, -1, 20470, 20472, 20473, -1, 20470, 20473, 20474, -1, 20470, 20474, 20471, -1, 20475, 20460, 20461, -1, 20475, 20461, 20476, -1, 20475, 20462, 20460, -1, 20475, 20477, 20462, -1, 20475, 20476, 20477, -1, 20478, 20431, 20430, -1, 20478, 20457, 20459, -1, 20478, 20430, 20457, -1, 20479, 20480, 20481, -1, 20479, 20481, 20482, -1, 20483, 20469, 20467, -1, 20483, 20467, 20468, -1, 19246, 19249, 19153, -1, 19246, 19153, 19125, -1, 20484, 20485, 20486, -1, 20484, 20487, 20464, -1, 20484, 20463, 20466, -1, 20484, 20466, 20485, -1, 20484, 20464, 20463, -1, 20488, 20478, 20459, -1, 20488, 20489, 20490, -1, 20488, 20490, 20431, -1, 20488, 20459, 20491, -1, 20492, 19207, 19194, -1, 20488, 20431, 20478, -1, 20493, 20479, 20482, -1, 20493, 20494, 20495, -1, 20493, 20480, 20479, -1, 20493, 20496, 20494, -1, 20493, 20495, 20480, -1, 20493, 20482, 20496, -1, 20497, 20483, 20468, -1, 20497, 20469, 20483, -1, 11496, 11464, 20452, -1, 20497, 20498, 20469, -1, 20497, 20468, 20499, -1, 20497, 20499, 20500, -1, 20501, 20412, 20395, -1, 19239, 11715, 11808, -1, 20502, 20503, 20504, -1, 20502, 20505, 20503, -1, 20502, 20506, 20505, -1, 20507, 20484, 20486, -1, 20507, 20487, 20484, -1, 20507, 20508, 20487, -1, 20509, 20510, 20511, -1, 20509, 20474, 20512, -1, 20509, 20511, 20474, -1, 20513, 20404, 20418, -1, 20509, 20512, 20510, -1, 20514, 20515, 20489, -1, 20514, 20489, 20488, -1, 20514, 20491, 20516, -1, 20514, 20488, 20491, -1, 20514, 20516, 20515, -1, 20517, 20498, 20497, -1, 20517, 20500, 20518, -1, 20517, 20519, 20498, -1, 19208, 19215, 19209, -1, 20517, 20497, 20500, -1, 20520, 20502, 20504, -1, 20520, 20521, 20506, -1, 20520, 20506, 20502, -1, 20520, 20522, 20521, -1, 20523, 20486, 20524, -1, 20523, 20507, 20486, -1, 20523, 20508, 20507, -1, 20523, 20525, 20508, -1, 20526, 20527, 11685, -1, 20526, 20528, 20527, -1, 20526, 11692, 11693, -1, 20526, 11685, 11692, -1, 20526, 11693, 20529, -1, 20530, 20519, 20517, -1, 20530, 20518, 11375, -1, 19223, 19267, 19186, -1, 20530, 11375, 11471, -1, 19223, 19186, 19185, -1, 20530, 20531, 20519, -1, 20530, 11471, 20531, -1, 20530, 20517, 20518, -1, 20532, 20533, 20534, -1, 20532, 20535, 20533, -1, 20532, 20534, 20536, -1, 20532, 20536, 20537, -1, 20538, 20539, 20522, -1, 20540, 20388, 20389, -1, 20538, 20504, 20541, -1, 20538, 20522, 20520, -1, 20538, 20541, 20539, -1, 20538, 20520, 20504, -1, 20542, 20524, 20543, -1, 20542, 20543, 20544, -1, 20545, 20513, 20418, -1, 20542, 20544, 20525, -1, 20542, 20525, 20523, -1, 20542, 20523, 20524, -1, 20546, 20526, 20529, -1, 20546, 20528, 20526, -1, 20546, 20547, 20528, -1, 20546, 20548, 20547, -1, 19216, 19215, 19208, -1, 20546, 20529, 20548, -1, 20549, 20550, 20535, -1, 20549, 20532, 20537, -1, 20549, 20535, 20532, -1, 20549, 20537, 20550, -1, 20551, 20511, 20552, -1, 20551, 20552, 20553, -1, 20551, 20554, 20511, -1, 20551, 20555, 20554, -1, 20556, 20557, 20558, -1, 20556, 20512, 20559, -1, 20556, 20559, 20560, -1, 20556, 20560, 20557, -1, 20556, 20558, 20512, -1, 20561, 20562, 20563, -1, 20561, 20563, 20564, -1, 20565, 20566, 20567, -1, 20565, 20568, 20569, -1, 20565, 20569, 20566, -1, 20565, 20570, 20568, -1, 20565, 20567, 20570, -1, 20462, 20446, 20453, -1, 19250, 20442, 20445, -1, 20571, 20553, 20572, -1, 20462, 20453, 20425, -1, 20571, 20551, 20553, -1, 19250, 20445, 19249, -1, 20571, 20555, 20551, -1, 20573, 20560, 20562, -1, 20573, 20564, 20574, -1, 20573, 20574, 20575, -1, 20573, 20562, 20561, -1, 20573, 20561, 20564, -1, 20576, 20572, 20577, -1, 20578, 19207, 20492, -1, 20576, 20579, 20555, -1, 20576, 20571, 20572, -1, 20576, 20555, 20571, -1, 11495, 11496, 20452, -1, 20580, 20544, 20581, -1, 20580, 20582, 20544, -1, 20580, 20583, 20582, -1, 20584, 20573, 20575, -1, 20584, 20557, 20560, -1, 20584, 20560, 20573, -1, 20585, 20577, 20586, -1, 20585, 20587, 20579, -1, 20585, 20576, 20577, -1, 20585, 20579, 20576, -1, 20588, 20581, 20589, -1, 20588, 20583, 20580, -1, 20588, 20580, 20581, -1, 20590, 20591, 20592, -1, 20590, 20570, 20567, -1, 20593, 20578, 20492, -1, 20590, 20592, 20570, -1, 20590, 20567, 20591, -1, 20594, 20595, 20596, -1, 20594, 20596, 20597, -1, 20451, 11495, 20452, -1, 20594, 20597, 20598, -1, 20599, 20600, 20601, -1, 20599, 20601, 20602, -1, 20603, 20586, 20604, -1, 20603, 20604, 20605, -1, 20603, 20605, 20587, -1, 20603, 20585, 20586, -1, 20603, 20587, 20585, -1, 20606, 20412, 20501, -1, 20607, 20608, 20609, -1, 20607, 20609, 11708, -1, 20607, 11721, 11722, -1, 20607, 11719, 11721, -1, 20607, 11708, 11719, -1, 20607, 11722, 20608, -1, 20610, 20611, 20557, -1, 20610, 20575, 20612, -1, 20610, 20584, 20575, -1, 20610, 20557, 20584, -1, 20610, 20613, 20611, -1, 20614, 20589, 20615, -1, 20614, 20588, 20589, -1, 20614, 20615, 20616, -1, 20614, 20617, 20583, -1, 20614, 20583, 20588, -1, 20618, 20619, 20595, -1, 20618, 20594, 20598, -1, 20618, 20595, 20594, -1, 20620, 20388, 20540, -1, 20618, 20598, 20621, -1, 20622, 20623, 20624, -1, 20622, 20625, 20600, -1, 20626, 20606, 20501, -1, 20622, 20602, 20623, -1, 20622, 20624, 20625, -1, 20622, 20599, 20602, -1, 20622, 20600, 20599, -1, 20627, 20617, 20614, -1, 20627, 20614, 20616, -1, 20628, 20513, 20545, -1, 20627, 20629, 20617, -1, 20630, 20612, 20631, -1, 20630, 20613, 20610, -1, 20630, 20610, 20612, -1, 20630, 20631, 20632, -1, 11378, 11384, 19243, -1, 20630, 20632, 20613, -1, 20633, 20634, 20619, -1, 20633, 20618, 20621, -1, 20633, 20621, 20635, -1, 20633, 20619, 20618, -1, 20636, 20637, 20638, -1, 20636, 20639, 20640, -1, 20636, 20638, 20639, -1, 20636, 20640, 20637, -1, 11442, 11495, 20451, -1, 20641, 20629, 20627, -1, 20641, 20627, 20616, -1, 20641, 20642, 20629, -1, 20641, 20616, 20643, -1, 20644, 20645, 20646, -1, 20644, 20646, 20647, -1, 20644, 20647, 20648, -1, 20644, 20649, 20645, -1, 20650, 20397, 20651, -1, 20652, 20653, 20634, -1, 20650, 20436, 20397, -1, 20652, 20634, 20633, -1, 20652, 20633, 20635, -1, 20481, 20403, 20402, -1, 20654, 20655, 20642, -1, 20654, 20642, 20641, -1, 20654, 20641, 20643, -1, 20654, 20643, 20656, -1, 20654, 20656, 20655, -1, 20657, 20658, 20649, -1, 20657, 20648, 20658, -1, 20657, 20644, 20648, -1, 20657, 20649, 20644, -1, 20659, 20660, 20653, -1, 20659, 20652, 20635, -1, 20659, 20653, 20652, -1, 20659, 20635, 20661, -1, 20480, 20403, 20481, -1, 20662, 20663, 20664, -1, 20662, 20665, 20663, -1, 20662, 20664, 20666, -1, 20662, 20666, 20667, -1, 20668, 20669, 20670, -1, 20668, 20671, 20669, -1, 20668, 20670, 20672, -1, 20668, 20672, 20673, -1, 20668, 20673, 20671, -1, 20674, 20632, 20675, -1, 20674, 20676, 20677, -1, 20674, 20677, 20632, -1, 20678, 20679, 20660, -1, 20678, 20659, 20661, -1, 20678, 20661, 20679, -1, 20678, 20660, 20659, -1, 20441, 20388, 20620, -1, 20680, 20662, 20667, -1, 20680, 20665, 20662, -1, 20680, 20667, 20681, -1, 20441, 20440, 20388, -1, 20682, 20675, 20683, -1, 20682, 20674, 20675, -1, 20682, 20676, 20674, -1, 20682, 20684, 20676, -1, 20685, 20686, 20687, -1, 20685, 20688, 20689, -1, 20690, 20578, 20593, -1, 20685, 20691, 20688, -1, 20685, 20689, 20686, -1, 20692, 20693, 20655, -1, 20692, 20694, 20693, -1, 20692, 20655, 20695, -1, 20696, 20697, 20665, -1, 20696, 20665, 20680, -1, 20696, 20680, 20681, -1, 20696, 20681, 20698, -1, 20699, 20683, 20700, -1, 20699, 20684, 20682, -1, 20699, 20682, 20683, -1, 20701, 20691, 20685, -1, 20701, 20685, 20687, -1, 20701, 20702, 20691, -1, 20703, 20704, 20705, -1, 20703, 20706, 20707, -1, 20703, 20708, 20706, -1, 20703, 20705, 20708, -1, 11374, 11378, 19243, -1, 20709, 20669, 20671, -1, 20709, 20710, 20711, -1, 20709, 20711, 20669, -1, 20709, 20671, 20710, -1, 20712, 20694, 20692, -1, 20713, 20420, 20408, -1, 20712, 20692, 20695, -1, 20712, 20695, 20714, -1, 20715, 20716, 20697, -1, 20715, 20696, 20698, -1, 20715, 20697, 20696, -1, 20717, 20700, 20718, -1, 20717, 20684, 20699, -1, 20717, 20699, 20700, -1, 19270, 20690, 20593, -1, 20717, 20719, 20684, -1, 20717, 20720, 20719, -1, 20721, 20701, 20687, -1, 20721, 20702, 20701, -1, 20721, 20722, 20702, -1, 20721, 20687, 20722, -1, 20723, 20724, 20725, -1, 20723, 20726, 20724, -1, 20723, 20727, 20726, -1, 20728, 19199, 19198, -1, 20729, 20694, 20712, -1, 20729, 20730, 20694, -1, 20729, 20714, 20731, -1, 20728, 19198, 20732, -1, 20729, 20712, 20714, -1, 20733, 20703, 20707, -1, 20733, 20734, 20704, -1, 20733, 20704, 20703, -1, 20733, 20707, 20734, -1, 20735, 20606, 20626, -1, 20736, 11749, 11754, -1, 20736, 11754, 20737, -1, 20736, 20738, 11749, -1, 20736, 20739, 20738, -1, 20740, 11332, 11424, -1, 20740, 20741, 20716, -1, 20740, 20715, 20698, -1, 20740, 11424, 20741, -1, 20740, 20716, 20715, -1, 20740, 20698, 20742, -1, 20740, 20742, 11332, -1, 20743, 20717, 20718, -1, 20469, 20735, 20626, -1, 20743, 20720, 20717, -1, 20743, 20744, 20720, -1, 20745, 20620, 20540, -1, 20746, 20727, 20723, -1, 20746, 20723, 20725, -1, 20746, 20725, 20747, -1, 20746, 20748, 20727, -1, 20749, 20731, 20750, -1, 20749, 20729, 20731, -1, 20749, 20730, 20729, -1, 20745, 20540, 20751, -1, 20749, 20752, 20730, -1, 20753, 20739, 20736, -1, 20753, 20737, 20754, -1, 20753, 20736, 20737, -1, 20753, 20755, 20739, -1, 20756, 20743, 20718, -1, 20756, 20718, 20757, -1, 20756, 20744, 20743, -1, 19257, 20628, 20545, -1, 20756, 20757, 20758, -1, 19257, 20545, 19235, -1, 20756, 20758, 20744, -1, 20759, 20760, 20761, -1, 20759, 20762, 20763, -1, 20759, 20761, 20762, -1, 20759, 20763, 20760, -1, 20764, 20752, 20749, -1, 20764, 20765, 20752, -1, 20764, 20750, 20766, -1, 19299, 20628, 19257, -1, 20764, 20749, 20750, -1, 20767, 20747, 20768, -1, 20767, 20746, 20747, -1, 20769, 20650, 20651, -1, 20767, 20770, 20771, -1, 20767, 20748, 20746, -1, 20767, 20771, 20748, -1, 20769, 20651, 20772, -1, 20773, 20774, 20775, -1, 20773, 20775, 20776, -1, 20773, 20776, 20777, -1, 19274, 19222, 19224, -1, 20778, 20779, 20780, -1, 20778, 20781, 20782, -1, 20778, 20780, 20781, -1, 20783, 20754, 20784, -1, 20785, 19227, 19226, -1, 20783, 20753, 20754, -1, 20783, 20755, 20753, -1, 20783, 20786, 20755, -1, 20787, 20764, 20766, -1, 20787, 20765, 20764, -1, 20787, 20788, 20765, -1, 20787, 20766, 20789, -1, 20787, 20789, 20788, -1, 20790, 20768, 20791, -1, 20790, 20767, 20768, -1, 20790, 20770, 20767, -1, 19263, 20792, 19250, -1, 20790, 20793, 20770, -1, 20794, 20795, 20796, -1, 20794, 20774, 20773, -1, 20794, 20777, 20795, -1, 20794, 20773, 20777, -1, 20794, 20796, 20774, -1, 20797, 20798, 20779, -1, 20797, 20778, 20782, -1, 20797, 20779, 20778, -1, 20799, 20786, 20783, -1, 20799, 20784, 20800, -1, 20799, 20783, 20784, -1, 20801, 20791, 20802, -1, 20801, 20790, 20791, -1, 20801, 20793, 20790, -1, 20801, 20802, 20793, -1, 19296, 20690, 19270, -1, 20803, 20804, 20758, -1, 20803, 20758, 20805, -1, 20806, 20807, 20808, -1, 20806, 20809, 20810, -1, 20806, 20808, 20809, -1, 20811, 20420, 20713, -1, 20812, 20813, 20814, -1, 20812, 20815, 20816, -1, 20812, 20814, 20815, -1, 20812, 20816, 20813, -1, 20817, 20818, 20819, -1, 20817, 20819, 20798, -1, 20820, 19288, 20792, -1, 20817, 20797, 20782, -1, 20820, 20792, 19263, -1, 20817, 20821, 20818, -1, 20817, 20782, 20821, -1, 20817, 20798, 20797, -1, 20822, 20800, 20823, -1, 20824, 20728, 20732, -1, 20822, 20786, 20799, -1, 20822, 20825, 20786, -1, 20822, 20799, 20800, -1, 20476, 20473, 20477, -1, 20824, 20732, 20826, -1, 20827, 11781, 11783, -1, 20827, 11770, 11781, -1, 20827, 11783, 20828, -1, 20827, 20829, 11770, -1, 20830, 11402, 20831, -1, 20830, 20803, 20805, -1, 20830, 20804, 20803, -1, 20830, 20805, 20832, -1, 20830, 20832, 11309, -1, 20833, 20811, 20713, -1, 20830, 11309, 11402, -1, 20830, 20831, 20804, -1, 20834, 20835, 20788, -1, 20498, 20735, 20469, -1, 20834, 20836, 20835, -1, 20834, 20788, 20837, -1, 20838, 20839, 20840, -1, 20838, 20806, 20810, -1, 20838, 20810, 20839, -1, 20838, 20807, 20806, -1, 20841, 20823, 20842, -1, 20841, 20843, 20825, -1, 20841, 20822, 20823, -1, 20841, 20825, 20822, -1, 20844, 20845, 20829, -1, 20844, 20828, 20845, -1, 20844, 20829, 20827, -1, 20844, 20827, 20828, -1, 20846, 20807, 20838, -1, 20474, 20473, 20476, -1, 19286, 19288, 20820, -1, 20846, 20847, 20807, -1, 20846, 20838, 20840, -1, 20848, 20834, 20837, -1, 20848, 20837, 20849, -1, 20848, 20836, 20834, -1, 20850, 20841, 20842, -1, 20850, 20842, 20851, -1, 20850, 20852, 20853, -1, 20854, 19227, 20785, -1, 20850, 20853, 20843, -1, 20850, 20843, 20841, -1, 20855, 20745, 20751, -1, 20856, 20857, 20858, -1, 20856, 20858, 20859, -1, 20855, 20751, 20860, -1, 20856, 20861, 20857, -1, 20862, 20863, 20864, -1, 20862, 20864, 20865, -1, 20862, 20865, 20866, -1, 20862, 20866, 20863, -1, 20867, 20840, 20868, -1, 20867, 20868, 20847, -1, 20867, 20846, 20840, -1, 20867, 20847, 20846, -1, 20869, 20836, 20848, -1, 20869, 20870, 20836, -1, 20869, 20849, 20871, -1, 20869, 20848, 20849, -1, 20872, 20850, 20851, -1, 20872, 20852, 20850, -1, 20873, 20859, 20874, -1, 20873, 20861, 20856, -1, 20873, 20856, 20859, -1, 20873, 20875, 20861, -1, 20876, 20870, 20869, -1, 20876, 20877, 20870, -1, 20876, 20869, 20871, -1, 20876, 20871, 20878, -1, 20879, 20851, 20880, -1, 20879, 20872, 20851, -1, 20521, 20769, 20772, -1, 20879, 20881, 20852, -1, 20521, 20772, 20506, -1, 19280, 19279, 19227, -1, 20879, 20852, 20872, -1, 20882, 20875, 20873, -1, 19280, 19227, 20854, -1, 20882, 20874, 20883, -1, 20882, 20884, 20885, -1, 20882, 20885, 20875, -1, 19317, 19252, 19253, -1, 20882, 20873, 20874, -1, 20886, 20876, 20878, -1, 20886, 20887, 20877, -1, 20886, 20878, 20888, -1, 20886, 20877, 20876, -1, 20889, 20880, 20890, -1, 20889, 20879, 20880, -1, 20889, 20891, 20881, -1, 20889, 20881, 20879, -1, 20892, 20893, 20894, -1, 20892, 20894, 20895, -1, 20892, 20895, 20896, -1, 20897, 20888, 20898, -1, 20897, 20898, 20887, -1, 20897, 20886, 20888, -1, 20897, 20887, 20886, -1, 20899, 20900, 20901, -1, 20534, 20448, 20420, -1, 20899, 20902, 20900, -1, 19319, 19252, 19317, -1, 20899, 20903, 20902, -1, 20534, 20533, 20448, -1, 20904, 11803, 20905, -1, 20904, 20906, 11801, -1, 20904, 20905, 20906, -1, 20904, 11801, 11803, -1, 20907, 11387, 20908, -1, 20907, 20909, 11291, -1, 20907, 11385, 11387, -1, 20907, 11291, 11385, -1, 20907, 20908, 20910, -1, 20907, 20910, 20909, -1, 20911, 20884, 20882, -1, 20912, 20496, 20482, -1, 20911, 20883, 20913, -1, 20911, 20882, 20883, -1, 20911, 20914, 20884, -1, 20915, 20890, 20916, -1, 19284, 20917, 19285, -1, 20915, 20889, 20890, -1, 20915, 20918, 20891, -1, 20915, 20891, 20889, -1, 20919, 20920, 20921, -1, 20919, 20922, 20923, -1, 20919, 20923, 20924, -1, 20527, 11679, 11685, -1, 20919, 20924, 20920, -1, 20925, 20893, 20892, -1, 20925, 20926, 20893, -1, 19314, 20826, 19260, -1, 20925, 20927, 20926, -1, 19314, 20824, 20826, -1, 20925, 20896, 20927, -1, 20925, 20892, 20896, -1, 20928, 20901, 20920, -1, 20928, 20903, 20899, -1, 20928, 20920, 20903, -1, 20928, 20899, 20901, -1, 20929, 20916, 20930, -1, 20931, 20811, 20833, -1, 20929, 20918, 20915, -1, 20929, 20915, 20916, -1, 20932, 20911, 20913, -1, 20932, 20913, 20933, -1, 20494, 20505, 20495, -1, 20932, 20914, 20911, -1, 20932, 20933, 20914, -1, 20934, 20921, 20935, -1, 20934, 20922, 20919, -1, 20934, 20936, 20922, -1, 20934, 20919, 20921, -1, 20937, 20938, 20939, -1, 20937, 20940, 20938, -1, 20937, 20941, 20940, -1, 20937, 20939, 20941, -1, 20942, 20943, 20944, -1, 20942, 20945, 20946, -1, 20942, 20944, 20945, -1, 20947, 20929, 20930, -1, 20947, 20930, 20948, -1, 20947, 20949, 20918, -1, 20947, 20918, 20929, -1, 20950, 20942, 20946, -1, 20950, 20946, 20951, -1, 20950, 20943, 20942, -1, 20952, 20935, 20953, -1, 20511, 20554, 20471, -1, 20954, 20785, 20955, -1, 20952, 20934, 20935, -1, 20952, 20936, 20934, -1, 20511, 20471, 20474, -1, 20954, 20854, 20785, -1, 20952, 20956, 20936, -1, 20957, 20958, 20959, -1, 20957, 20960, 20961, -1, 20957, 20961, 20958, -1, 20962, 20949, 20947, -1, 20962, 20948, 20963, -1, 20962, 20964, 20949, -1, 20962, 20963, 20964, -1, 20962, 20947, 20948, -1, 20965, 20950, 20951, -1, 20965, 20966, 20943, -1, 20967, 20931, 20833, -1, 20965, 20943, 20950, -1, 20965, 20951, 20968, -1, 20969, 20952, 20953, -1, 20969, 20956, 20952, -1, 20969, 20970, 20956, -1, 20969, 20953, 20970, -1, 20971, 20957, 20959, -1, 20971, 20960, 20957, -1, 20503, 20505, 20494, -1, 20971, 20959, 20972, -1, 20973, 20974, 20975, -1, 20973, 20976, 20977, -1, 20973, 20977, 20974, -1, 20973, 20975, 20976, -1, 20978, 20979, 20980, -1, 20978, 20981, 20982, -1, 20978, 20982, 20979, -1, 20983, 20968, 20984, -1, 20983, 20984, 20966, -1, 20983, 20965, 20968, -1, 20983, 20966, 20965, -1, 20985, 20986, 20987, -1, 20985, 20988, 20989, -1, 20985, 20989, 20964, -1, 20985, 20963, 20990, -1, 20985, 20964, 20963, -1, 20985, 20990, 20986, -1, 20985, 20987, 20988, -1, 20991, 20960, 20971, -1, 20991, 20972, 20992, -1, 20535, 20855, 20860, -1, 20991, 20993, 20960, -1, 20535, 20860, 20533, -1, 20991, 20971, 20972, -1, 20994, 20978, 20980, -1, 20994, 20981, 20978, -1, 20994, 20980, 20995, -1, 20996, 20496, 20912, -1, 20994, 20997, 20981, -1, 20998, 20999, 21000, -1, 20998, 21001, 20999, -1, 20998, 21000, 21002, -1, 21003, 20987, 21004, -1, 21003, 21005, 20988, -1, 21003, 20988, 20987, -1, 21006, 20992, 21007, -1, 21006, 21008, 20993, -1, 21006, 20993, 20991, -1, 21006, 20991, 20992, -1, 21009, 20997, 20994, -1, 21009, 20994, 20995, -1, 21009, 21010, 20997, -1, 21011, 21001, 20998, -1, 21011, 20998, 21002, -1, 21011, 21002, 21012, -1, 21013, 21004, 21014, -1, 21013, 21015, 21005, -1, 21013, 21003, 21004, -1, 21013, 21005, 21003, -1, 21016, 20996, 20912, -1, 21017, 21006, 21007, -1, 21017, 21007, 21018, -1, 21017, 21008, 21006, -1, 21019, 21020, 20986, -1, 21019, 20990, 21021, -1, 21019, 20986, 20990, -1, 21019, 21021, 21020, -1, 21022, 21023, 21010, -1, 21022, 21010, 21009, -1, 21022, 20995, 21024, -1, 21022, 21009, 20995, -1, 21025, 21001, 21011, -1, 21025, 21026, 21001, -1, 21025, 21011, 21012, -1, 21025, 21012, 21027, -1, 21025, 21027, 21026, -1, 21028, 21014, 21029, -1, 21028, 21015, 21013, -1, 21028, 21013, 21014, -1, 21030, 21018, 21031, -1, 21030, 21032, 21008, -1, 21030, 21017, 21018, -1, 21030, 11398, 21032, -1, 21030, 21008, 21017, -1, 21030, 21031, 11398, -1, 21033, 21022, 21024, -1, 21033, 21024, 21034, -1, 21033, 21023, 21022, -1, 21033, 21035, 21023, -1, 21036, 21037, 21038, -1, 21036, 21039, 21037, -1, 21036, 21038, 21040, -1, 21036, 21040, 21041, -1, 21042, 21029, 21043, -1, 21042, 21015, 21028, -1, 21042, 21028, 21029, -1, 21042, 21044, 21015, -1, 21045, 21035, 21033, -1, 21046, 20931, 20967, -1, 21045, 21034, 21047, -1, 21045, 21047, 21035, -1, 21045, 21033, 21034, -1, 21048, 21049, 21050, -1, 11473, 11417, 20531, -1, 21048, 21051, 21052, -1, 21048, 21050, 21051, -1, 19354, 19310, 19309, -1, 21053, 21044, 21042, -1, 21053, 21043, 21054, -1, 21053, 21055, 21044, -1, 21053, 21042, 21043, -1, 21056, 21039, 21036, -1, 21056, 21057, 21039, -1, 21056, 21036, 21041, -1, 21058, 21049, 21048, -1, 21058, 21048, 21052, -1, 21058, 21052, 21059, -1, 21060, 20955, 21061, -1, 21060, 20954, 20955, -1, 21062, 21054, 21063, -1, 21062, 21064, 21055, -1, 21062, 21053, 21054, -1, 21062, 21063, 21064, -1, 21062, 21055, 21053, -1, 21065, 21066, 21067, -1, 21065, 21067, 21057, -1, 19321, 21068, 21069, -1, 21065, 21057, 21056, -1, 19321, 21069, 19322, -1, 21065, 21056, 21041, -1, 21065, 21041, 21070, -1, 21071, 21058, 21059, -1, 21071, 21072, 21049, -1, 21071, 21059, 21073, -1, 21071, 21049, 21058, -1, 21074, 21075, 21076, -1, 21074, 21077, 21075, -1, 21074, 21078, 21077, -1, 21079, 21080, 21081, -1, 21079, 21082, 21083, -1, 21079, 21083, 21064, -1, 21079, 21063, 21080, -1, 21079, 21064, 21063, -1, 21079, 21084, 21082, -1, 21079, 21081, 21084, -1, 21085, 21073, 21086, -1, 21085, 21072, 21071, -1, 21087, 19260, 19261, -1, 21085, 21071, 21073, -1, 21087, 19314, 19260, -1, 21085, 21086, 21072, -1, 21088, 18367, 21066, -1, 21088, 21089, 18367, -1, 21088, 21066, 21065, -1, 21088, 21070, 21089, -1, 21088, 21065, 21070, -1, 21090, 21091, 21092, -1, 21090, 21092, 21093, -1, 21090, 21094, 21091, -1, 21095, 21096, 21097, -1, 21095, 21097, 21098, -1, 21095, 21099, 21096, -1, 21100, 21101, 21078, -1, 21100, 21078, 21074, -1, 21100, 21102, 21101, -1, 21100, 21076, 21102, -1, 21100, 21074, 21076, -1, 21103, 21090, 21093, -1, 21103, 21094, 21090, -1, 19361, 19360, 20917, -1, 21103, 21093, 11336, -1, 21103, 11336, 11421, -1, 21103, 21104, 21094, -1, 21103, 11421, 21104, -1, 21105, 20996, 21016, -1, 19361, 20917, 19284, -1, 21106, 21107, 21082, -1, 21106, 21082, 21084, -1, 21106, 21084, 21108, -1, 21109, 21095, 21098, -1, 21109, 21098, 21110, -1, 21109, 21099, 21095, -1, 21109, 21111, 21099, -1, 21112, 21110, 21113, -1, 21112, 21111, 21109, -1, 21112, 21109, 21110, -1, 21114, 21106, 21108, -1, 21114, 21115, 21107, -1, 21114, 21107, 21106, -1, 11346, 11353, 21116, -1, 21114, 21108, 21117, -1, 21118, 21081, 21080, -1, 21118, 21080, 18374, -1, 21118, 18374, 18376, -1, 21118, 18376, 21081, -1, 21119, 18361, 18401, -1, 21119, 18401, 18403, -1, 21119, 18362, 18361, -1, 21119, 18403, 21120, -1, 21119, 21120, 18362, -1, 21121, 19342, 19318, -1, 21122, 21123, 21111, -1, 21122, 21113, 18363, -1, 21122, 18363, 21123, -1, 21122, 21112, 21113, -1, 11471, 11473, 20531, -1, 19355, 19310, 19354, -1, 21122, 21111, 21112, -1, 21124, 21117, 21125, -1, 21124, 21114, 21117, -1, 21124, 21115, 21114, -1, 21126, 18385, 18384, -1, 21126, 18375, 18385, -1, 21126, 18384, 21127, -1, 21126, 21127, 21128, -1, 21129, 21125, 21130, -1, 19312, 19314, 21087, -1, 21129, 21124, 21125, -1, 21129, 21115, 21124, -1, 21129, 21131, 21115, -1, 21132, 21133, 21134, -1, 20555, 21105, 21016, -1, 21132, 21135, 21136, -1, 21132, 21136, 21133, -1, 21137, 21126, 21128, -1, 21137, 18375, 21126, -1, 21137, 18373, 18375, -1, 21138, 21130, 21139, -1, 21138, 21140, 21131, -1, 21138, 21129, 21130, -1, 21138, 21131, 21129, -1, 21141, 18401, 18361, -1, 21141, 18361, 18436, -1, 19378, 21068, 19321, -1, 21141, 18435, 18401, -1, 21142, 20486, 20485, -1, 21141, 18436, 18435, -1, 21142, 20485, 21143, -1, 21144, 21135, 21132, -1, 19378, 19382, 21068, -1, 21144, 21134, 18461, -1, 21144, 21132, 21134, -1, 21145, 21139, 18495, -1, 21145, 21146, 21140, -1, 21145, 21138, 21139, -1, 21145, 21140, 21138, -1, 21147, 21148, 21149, -1, 21147, 21149, 18373, -1, 21147, 21128, 21150, -1, 21147, 21137, 21128, -1, 21147, 18373, 21137, -1, 21151, 21135, 21144, -1, 21151, 18481, 21135, -1, 21151, 18461, 18460, -1, 21151, 21144, 18461, -1, 21152, 21153, 21154, -1, 21152, 21154, 21146, -1, 21152, 21146, 21145, -1, 21152, 21145, 18495, -1, 21155, 21147, 21150, -1, 21155, 18517, 21148, -1, 21155, 21148, 21147, -1, 21155, 21150, 18518, -1, 21155, 18518, 18517, -1, 21156, 18449, 21157, -1, 21156, 18402, 18449, -1, 21156, 18447, 18402, -1, 21158, 18460, 18482, -1, 21158, 18481, 21151, -1, 21158, 21151, 18460, -1, 20544, 20967, 20525, -1, 21158, 18482, 18481, -1, 21159, 18434, 18492, -1, 20544, 21046, 20967, -1, 21159, 18492, 18508, -1, 21159, 18508, 18463, -1, 19372, 21061, 19360, -1, 21159, 18463, 18434, -1, 19372, 21060, 21061, -1, 21160, 21152, 18495, -1, 21160, 18495, 18499, -1, 20582, 21046, 20544, -1, 21160, 21153, 21152, -1, 21161, 21156, 21157, -1, 21161, 21157, 21162, -1, 21161, 18447, 21156, -1, 11341, 11346, 21116, -1, 21163, 21164, 21153, -1, 21163, 18499, 21165, -1, 21163, 21160, 18499, -1, 21163, 21153, 21160, -1, 21166, 21162, 21167, -1, 21166, 18447, 21161, -1, 21166, 21161, 21162, -1, 21166, 18474, 18447, -1, 21168, 18505, 21164, -1, 20558, 20510, 20512, -1, 21168, 21165, 21169, -1, 21168, 21163, 21165, -1, 21168, 21164, 21163, -1, 21170, 18536, 18563, -1, 21170, 18532, 18536, -1, 21170, 18565, 21171, -1, 21170, 21171, 18532, -1, 21170, 18563, 18565, -1, 21172, 21166, 21167, -1, 21172, 21167, 18531, -1, 21172, 18474, 21166, -1, 21172, 18531, 18533, -1, 21173, 20515, 20516, -1, 21172, 18533, 18474, -1, 21174, 21169, 21175, -1, 21174, 18505, 21168, -1, 21174, 21168, 21169, -1, 21176, 19341, 19340, -1, 21177, 18548, 21178, -1, 20550, 21179, 20535, -1, 21176, 21116, 19341, -1, 21177, 21178, 18560, -1, 21176, 11341, 21116, -1, 21177, 18560, 18559, -1, 21177, 18559, 21180, -1, 21181, 21175, 21182, -1, 21181, 18505, 21174, -1, 21183, 19342, 21121, -1, 21181, 18534, 18505, -1, 21181, 21174, 21175, -1, 21184, 21180, 21185, -1, 21184, 18548, 21177, -1, 21184, 21177, 21180, -1, 21186, 18536, 18590, -1, 21186, 18592, 18563, -1, 21186, 18563, 18536, -1, 21186, 18590, 18592, -1, 21187, 18534, 21181, -1, 21187, 21182, 21188, -1, 21187, 21189, 18534, -1, 20579, 21105, 20555, -1, 21187, 21181, 21182, -1, 21190, 21191, 18547, -1, 21190, 18548, 21184, -1, 21190, 21184, 21185, -1, 21190, 21185, 21192, -1, 21190, 18547, 18548, -1, 21193, 21188, 11382, -1, 21193, 11382, 11468, -1, 21193, 18579, 21189, -1, 21194, 21183, 21121, -1, 21193, 11468, 18579, -1, 21193, 21187, 21188, -1, 21193, 21189, 21187, -1, 21195, 21179, 20550, -1, 21196, 21191, 21190, -1, 21195, 20566, 21179, -1, 21196, 21190, 21192, -1, 21196, 21197, 21191, -1, 21198, 21199, 18658, -1, 21198, 21192, 21199, -1, 21198, 21196, 21192, -1, 21198, 21197, 21196, -1, 21198, 18658, 21197, -1, 21200, 18564, 18585, -1, 21200, 18585, 21201, -1, 21200, 18583, 18564, -1, 21202, 21143, 21203, -1, 21204, 18589, 18591, -1, 21202, 21142, 21143, -1, 21204, 18591, 18605, -1, 21204, 18611, 18589, -1, 21204, 18605, 18611, -1, 21205, 21201, 21206, -1, 11338, 11341, 21176, -1, 21205, 21200, 21201, -1, 21205, 18583, 21200, -1, 21207, 21205, 21206, -1, 21207, 18598, 18583, -1, 21207, 18583, 21205, -1, 21207, 21206, 21208, -1, 21209, 19378, 19321, -1, 21210, 18598, 21207, -1, 21209, 19321, 21211, -1, 21210, 21207, 21208, -1, 21210, 21208, 18615, -1, 21210, 18615, 18617, -1, 21210, 18617, 18598, -1, 21212, 18658, 21199, -1, 21212, 21199, 18640, -1, 21213, 18656, 21214, -1, 21213, 21214, 11456, -1, 21213, 11492, 18634, -1, 21213, 11456, 11492, -1, 21213, 18657, 18656, -1, 21213, 18634, 18657, -1, 20567, 20566, 21195, -1, 21215, 18658, 21212, -1, 21215, 21212, 18640, -1, 21215, 18640, 18639, -1, 21215, 18656, 18658, -1, 21215, 18639, 18656, -1, 21216, 18648, 18681, -1, 21216, 18677, 18648, -1, 21216, 18681, 21217, -1, 21218, 18677, 21216, -1, 21218, 21216, 21217, -1, 21218, 21217, 21219, -1, 21220, 20515, 21173, -1, 19324, 19410, 19325, -1, 21221, 18687, 18677, -1, 21221, 21218, 21219, -1, 21221, 18677, 21218, -1, 21221, 21219, 21222, -1, 21223, 21221, 21222, -1, 21223, 18687, 21221, -1, 21223, 18707, 18708, -1, 21223, 21222, 18707, -1, 21223, 18708, 18687, -1, 20564, 20515, 21220, -1, 20564, 20563, 20515, -1, 21224, 19349, 19337, -1, 20601, 20539, 20541, -1, 20600, 20539, 20601, -1, 21225, 21183, 21194, -1, 20570, 21226, 20568, -1, 19381, 21225, 21194, -1, 20596, 21202, 21203, -1, 21227, 19335, 19334, -1, 20596, 21203, 20547, -1, 21227, 19334, 21228, -1, 19367, 19353, 19352, -1, 19367, 19352, 19357, -1, 19417, 19353, 19367, -1, 21229, 21209, 21211, -1, 21229, 21211, 21230, -1, 21231, 21220, 21173, -1, 21231, 21173, 21232, -1, 21233, 19347, 19346, -1, 19373, 21234, 19372, -1, 19411, 19410, 19324, -1, 21235, 19349, 21224, -1, 21236, 19387, 21234, -1, 21236, 21234, 19373, -1, 21237, 21235, 21224, -1, 19421, 21225, 19381, -1, 19388, 19387, 21236, -1, 21238, 21227, 21228, -1, 21238, 21228, 21239, -1, 21240, 19347, 21233, -1, 19452, 21230, 19407, -1, 19452, 21229, 21230, -1, 20640, 20592, 20591, -1, 21241, 21232, 21242, -1, 21241, 21231, 21232, -1, 20604, 21243, 21244, -1, 20604, 21244, 20605, -1, 21245, 21240, 21233, -1, 19471, 11762, 11846, -1, 11856, 19471, 11846, -1, 21246, 20547, 20548, -1, 21246, 20596, 20547, -1, 21247, 21235, 21237, -1, 19390, 19347, 21240, -1, 20645, 21241, 21242, -1, 20646, 21226, 20570, -1, 20646, 20645, 21226, -1, 19384, 21248, 19385, -1, 11452, 11365, 21249, -1, 21250, 20623, 20602, -1, 19435, 21247, 21237, -1, 20639, 20592, 20640, -1, 20597, 20596, 21246, -1, 19459, 21239, 19395, -1, 19459, 21238, 21239, -1, 20664, 21243, 20604, -1, 21251, 21240, 21245, -1, 20664, 20663, 21243, -1, 21252, 21251, 21245, -1, 20649, 21241, 20645, -1, 21253, 19459, 19395, -1, 21253, 19395, 19375, -1, 11450, 11452, 21249, -1, 19434, 21247, 19435, -1, 11316, 11324, 19476, -1, 21254, 11450, 21249, -1, 21254, 21249, 20625, -1, 21254, 20625, 20624, -1, 21255, 20623, 21250, -1, 21256, 21255, 21250, -1, 19456, 19436, 19430, -1, 11354, 11450, 21254, -1, 21257, 21251, 21252, -1, 21258, 20664, 20604, -1, 21258, 20604, 21259, -1, 11315, 11316, 19476, -1, 20608, 20688, 20609, -1, 19432, 19436, 19456, -1, 19511, 21257, 21252, -1, 19512, 19511, 21248, -1, 19512, 21248, 19384, -1, 21260, 19414, 19413, -1, 21260, 19413, 21261, -1, 21262, 19459, 21253, -1, 21263, 20635, 20621, -1, 19497, 19439, 19494, -1, 19497, 19440, 19439, -1, 21264, 21255, 21256, -1, 20665, 21264, 21256, -1, 21265, 20615, 21266, -1, 19460, 19459, 21262, -1, 21265, 20616, 20615, -1, 20655, 20638, 20637, -1, 20655, 20637, 20642, -1, 20693, 20638, 20655, -1, 19533, 21257, 19511, -1, 21267, 21258, 21259, -1, 21267, 21259, 21268, -1, 21269, 21261, 21270, -1, 21269, 21260, 21261, -1, 21271, 20632, 20631, -1, 20658, 21272, 20649, -1, 20689, 20688, 20608, -1, 21273, 20635, 21263, -1, 21274, 20673, 21272, -1, 21274, 21272, 20658, -1, 21275, 21273, 21263, -1, 20697, 21264, 20665, -1, 20671, 20673, 21274, -1, 21276, 21265, 21266, -1, 21276, 21266, 21277, -1, 21278, 20632, 21271, -1, 19546, 19467, 19433, -1, 20719, 21267, 21268, -1, 19546, 19548, 19467, -1, 20719, 21268, 20684, -1, 19522, 21269, 21270, -1, 19522, 21270, 19487, -1, 19554, 19505, 19481, -1, 21279, 19485, 19465, -1, 21280, 21278, 21271, -1, 21279, 19465, 21281, -1, 20738, 11741, 11745, -1, 19526, 19495, 19499, -1, 19526, 19496, 19495, -1, 11749, 20738, 11745, -1, 21282, 21273, 21275, -1, 20675, 20632, 21278, -1, 19574, 19496, 19526, -1, 19532, 19518, 19533, -1, 20669, 21283, 20670, -1, 20705, 21282, 21275, -1, 21284, 19492, 19490, -1, 19553, 19505, 19554, -1, 19519, 19518, 19532, -1, 20726, 21277, 20679, -1, 20726, 21276, 21277, -1, 21285, 21278, 21280, -1, 19566, 11826, 11867, -1, 21286, 21285, 21280, -1, 21287, 21279, 21281, -1, 21287, 21281, 21288, -1, 21289, 20679, 20661, -1, 21289, 20726, 20679, -1, 20704, 21282, 20705, -1, 11425, 11343, 20741, -1, 19541, 21287, 21288, -1, 21290, 19492, 21284, -1, 11289, 11294, 19568, -1, 21291, 21290, 21284, -1, 20722, 20708, 20702, -1, 21292, 21285, 21286, -1, 19604, 19552, 19551, -1, 11424, 11425, 20741, -1, 20706, 20708, 20722, -1, 19599, 21287, 19541, -1, 20774, 21292, 21286, -1, 19543, 19492, 21290, -1, 20775, 20774, 21283, -1, 20775, 21283, 20669, -1, 11286, 11289, 19568, -1, 21293, 20687, 20686, -1, 21293, 20686, 21294, -1, 21295, 19599, 19541, -1, 21295, 19541, 19528, -1, 21296, 20726, 21289, -1, 21297, 21290, 21291, -1, 21298, 21297, 21291, -1, 20762, 20711, 20710, -1, 20762, 20710, 20763, -1, 19608, 19552, 19604, -1, 20724, 20726, 21296, -1, 21299, 19557, 19520, -1, 21299, 19520, 21300, -1, 20796, 21292, 20774, -1, 19610, 21301, 19587, -1, 21302, 21293, 21294, -1, 21302, 21294, 21303, -1, 21304, 19594, 19580, -1, 21305, 21301, 19610, -1, 21306, 19599, 21295, -1, 21307, 21297, 21298, -1, 19642, 21307, 21298, -1, 21308, 19577, 21309, -1, 21308, 19578, 19577, -1, 19643, 19558, 19557, -1, 19643, 19642, 19558, -1, 19605, 21301, 21305, -1, 19605, 19604, 21301, -1, 21310, 21300, 21311, -1, 21310, 21299, 21300, -1, 19600, 19599, 21306, -1, 20809, 20808, 20734, -1, 20809, 20734, 20707, -1, 20786, 21302, 21303, -1, 20786, 21303, 20755, -1, 19650, 19584, 19565, -1, 19653, 19584, 19650, -1, 21312, 19594, 21304, -1, 20816, 20768, 20747, -1, 21313, 20750, 20731, -1, 21314, 21312, 21304, -1, 19676, 21307, 19642, -1, 21313, 20731, 21315, -1, 20788, 20761, 20760, -1, 20788, 20760, 20765, -1, 20835, 20761, 20788, -1, 21316, 21309, 21317, -1, 21318, 21313, 21315, -1, 21316, 21308, 21309, -1, 20795, 20780, 20796, -1, 21319, 21310, 21311, -1, 21319, 21311, 21320, -1, 21321, 20758, 20757, -1, 20815, 20768, 20816, -1, 20781, 20780, 20795, -1, 21322, 19622, 19613, -1, 19656, 11862, 11894, -1, 20829, 11765, 11770, -1, 21323, 21312, 21314, -1, 21324, 21313, 21318, -1, 19691, 19606, 19605, -1, 19691, 19693, 19606, -1, 19669, 21323, 21314, -1, 19667, 21317, 19637, -1, 20802, 21324, 21318, -1, 19667, 21316, 21317, -1, 21325, 19622, 21322, -1, 19710, 19634, 19648, -1, 21326, 20758, 21321, -1, 19710, 21319, 21320, -1, 19710, 21320, 19634, -1, 11404, 11321, 20831, -1, 21327, 21325, 21322, -1, 21328, 21326, 21321, -1, 19712, 21319, 19710, -1, 19683, 21323, 19669, -1, 20865, 20814, 20813, -1, 11665, 11279, 19660, -1, 19686, 19620, 19687, -1, 19686, 19631, 19620, -1, 20857, 21324, 20802, -1, 20805, 20758, 21326, -1, 19675, 19658, 19676, -1, 11402, 11404, 20831, -1, 19672, 19671, 19653, -1, 21329, 20802, 20791, -1, 21329, 20857, 20802, -1, 21330, 21325, 21327, -1, 21331, 21326, 21328, -1, 19659, 19658, 19675, -1, 21332, 21331, 21328, -1, 19681, 21330, 21327, -1, 20864, 20814, 20865, -1, 21333, 19651, 21334, -1, 21333, 19652, 19651, -1, 21335, 20821, 20782, -1, 21335, 20782, 21336, -1, 21337, 11899, 11873, -1, 21337, 19655, 11899, -1, 20868, 21338, 20847, -1, 21339, 20851, 20842, -1, 19733, 21330, 19681, -1, 21340, 21338, 20868, -1, 21341, 20857, 21329, -1, 21342, 21334, 21343, -1, 21342, 21333, 21334, -1, 21344, 21331, 21332, -1, 21345, 19681, 19662, -1, 21345, 19733, 19681, -1, 20893, 21344, 21332, -1, 19755, 19655, 21337, -1, 21346, 20840, 20839, -1, 21346, 20839, 21347, -1, 20894, 20818, 20821, -1, 20894, 20893, 20818, -1, 20866, 20865, 21338, -1, 20866, 21338, 21340, -1, 19731, 19689, 19727, -1, 21348, 21335, 21336, -1, 19731, 19688, 19689, -1, 21348, 21336, 21349, -1, 21350, 19720, 19704, -1, 20858, 20857, 21341, -1, 19738, 21351, 19721, -1, 20902, 20845, 20828, -1, 20903, 20845, 20902, -1, 21352, 20851, 21339, -1, 19759, 19755, 21337, -1, 21353, 21352, 21339, -1, 19754, 21343, 19755, -1, 20926, 21344, 20893, -1, 19754, 21342, 21343, -1, 21354, 21351, 19738, -1, 21355, 19733, 21345, -1, 21356, 21347, 21357, -1, 21356, 21346, 21347, -1, 21358, 19720, 21350, -1, 19728, 21351, 21354, -1, 19728, 19727, 21351, -1, 21359, 21348, 21349, -1, 21359, 21349, 21360, -1, 21361, 21358, 21350, -1, 19734, 19733, 21355, -1, 21362, 20878, 20871, -1, 20906, 11790, 11801, -1, 21363, 21352, 21353, -1, 21364, 19723, 19708, -1, 21365, 19723, 21364, -1, 19793, 11911, 11922, -1, 19793, 11889, 11911, -1, 20945, 20944, 20863, -1, 20945, 20863, 20866, -1, 20922, 21363, 21353, -1, 21366, 21358, 21361, -1, 20918, 21356, 21357, -1, 20918, 21357, 20891, -1, 21367, 20878, 21362, -1, 20958, 21360, 20887, -1, 20958, 21359, 21360, -1, 20958, 20887, 20898, -1, 21368, 21367, 21362, -1, 20961, 21359, 20958, -1, 11651, 11653, 19796, -1, 21369, 19766, 19747, -1, 19820, 19730, 19728, -1, 20936, 21363, 20922, -1, 19820, 19824, 19730, -1, 11387, 11298, 20908, -1, 21370, 21365, 21364, -1, 20939, 20874, 20941, -1, 20939, 20883, 20874, -1, 19803, 19779, 19778, -1, 20927, 20910, 20926, -1, 19787, 21371, 19788, -1, 19811, 21361, 19773, -1, 19811, 21366, 21361, -1, 20920, 20924, 20903, -1, 11648, 11651, 19796, -1, 21372, 21367, 21368, -1, 21373, 21374, 21375, -1, 21373, 21375, 21371, -1, 21373, 21371, 19787, -1, 21376, 19766, 21369, -1, 20909, 20910, 20927, -1, 21377, 21365, 21370, -1, 20933, 21372, 21368, -1, 21378, 21376, 21369, -1, 21379, 20901, 20900, -1, 21379, 20900, 21380, -1, 19829, 19779, 19803, -1, 11645, 11648, 19797, -1, 21381, 19781, 19752, -1, 21381, 19752, 21382, -1, 21383, 20905, 11803, -1, 21383, 11803, 11806, -1, 19805, 19804, 21384, -1, 19805, 21384, 21365, -1, 19805, 21365, 21377, -1, 21385, 21374, 21373, -1, 21385, 19883, 21374, -1, 21386, 21385, 21373, -1, 20982, 21372, 20933, -1, 21387, 21376, 21378, -1, 21388, 21380, 21389, -1, 21388, 21379, 21380, -1, 19817, 21387, 21378, -1, 21390, 21377, 21370, -1, 21391, 20982, 20933, -1, 21391, 20933, 20913, -1, 21390, 21370, 21392, -1, 20999, 20905, 21383, -1, 21393, 21381, 21382, -1, 21393, 21382, 21394, -1, 20977, 20938, 20940, -1, 20977, 20940, 20974, -1, 20984, 21395, 20966, -1, 21396, 21385, 21386, -1, 21397, 21396, 21386, -1, 21000, 20999, 21383, -1, 19876, 21387, 19817, -1, 21001, 21388, 21389, -1, 21001, 21389, 20999, -1, 21398, 21395, 20984, -1, 21399, 21390, 21392, -1, 21399, 21392, 21400, -1, 21401, 20982, 21391, -1, 21402, 19876, 19817, -1, 21402, 19817, 19800, -1, 21403, 20951, 21404, -1, 21403, 20968, 20951, -1, 19887, 21394, 19850, -1, 19887, 21393, 21394, -1, 20975, 20974, 21395, -1, 20975, 21395, 21398, -1, 19881, 19883, 21385, -1, 21405, 19844, 19831, -1, 20979, 20982, 21401, -1, 19894, 11917, 11932, -1, 21406, 21396, 21397, -1, 19870, 19848, 19846, -1, 21407, 20970, 20953, -1, 21408, 20970, 21407, -1, 19918, 21406, 21397, -1, 19849, 19848, 19870, -1, 21409, 21403, 21404, -1, 21409, 21404, 21410, -1, 19903, 21399, 21400, -1, 19903, 21400, 19884, -1, 21411, 19844, 21405, -1, 21412, 19876, 21402, -1, 21413, 21411, 21405, -1, 19853, 19834, 19833, -1, 11389, 11304, 21032, -1, 21414, 21007, 20992, -1, 21415, 21406, 19918, -1, 11629, 11632, 19897, -1, 21051, 21050, 20976, -1, 21051, 20976, 20975, -1, 21416, 21408, 21407, -1, 19877, 19876, 21412, -1, 21039, 21020, 21021, -1, 21027, 21417, 21026, -1, 21044, 21409, 21410, -1, 21044, 21410, 21015, -1, 21418, 21411, 21413, -1, 11398, 11389, 21032, -1, 11627, 11629, 19897, -1, 21419, 21420, 21421, -1, 21419, 21421, 21417, -1, 21419, 21417, 21027, -1, 19912, 21418, 21413, -1, 21422, 21007, 21414, -1, 21423, 21408, 21416, -1, 21424, 19833, 21425, -1, 21424, 19853, 19833, -1, 21426, 21422, 21414, -1, 21057, 21020, 21039, -1, 11313, 11398, 21031, -1, 21427, 20995, 21428, -1, 21427, 21024, 20995, -1, 19917, 21415, 19918, -1, 19946, 21415, 19917, -1, 21429, 19874, 19873, -1, 21038, 21408, 21423, -1, 21038, 21037, 21430, -1, 21038, 21430, 21408, -1, 19951, 19886, 19851, -1, 19951, 19950, 19886, -1, 21431, 21096, 21420, -1, 19941, 21418, 19912, -1, 21431, 21420, 21419, -1, 21432, 21431, 21419, -1, 19930, 19923, 19931, -1, 21433, 21425, 21434, -1, 21433, 21424, 21425, -1, 21435, 21422, 21426, -1, 21047, 21435, 21426, -1, 19924, 19923, 19930, -1, 21436, 19874, 21429, -1, 21437, 21416, 21438, -1, 21437, 21423, 21416, -1, 19955, 19921, 19920, -1, 19955, 19920, 19939, -1, 21439, 21427, 21428, -1, 21439, 21428, 21440, -1, 19935, 19874, 21436, -1, 19935, 19938, 21441, -1, 19935, 21441, 19874, -1, 21442, 21431, 21432, -1, 21443, 19907, 19895, -1, 19928, 20001, 19926, -1, 21444, 21434, 19907, -1, 21445, 21442, 21432, -1, 21444, 21433, 21434, -1, 21091, 21435, 21047, -1, 21446, 21438, 21447, -1, 21446, 21437, 21438, -1, 21448, 21436, 21429, -1, 21448, 21429, 21449, -1, 21450, 21047, 21034, -1, 21450, 21091, 21047, -1, 21101, 21440, 21078, -1, 21101, 21439, 21440, -1, 21097, 21096, 21431, -1, 21451, 21073, 21059, -1, 48, 21452, 21453, -1, 48, 21453, 30, -1, 21454, 21442, 21445, -1, 21086, 21077, 21072, -1, 20031, 11949, 11957, -1, 20031, 11937, 11949, -1, 21455, 21454, 21445, -1, 20007, 19964, 19965, -1, 21075, 21077, 21086, -1, 21456, 21448, 21449, -1, 21456, 21449, 21457, -1, 21111, 21447, 21099, -1, 21111, 21446, 21447, -1, 11951, 20031, 11957, -1, 21458, 21073, 21451, -1, 21459, 21444, 19907, -1, 21459, 19907, 21443, -1, 21460, 21091, 21450, -1, 21461, 21458, 21451, -1, 19999, 20001, 19928, -1, 58, 21452, 48, -1, 11607, 11610, 21462, -1, 58, 21455, 21452, -1, 21463, 21454, 21455, -1, 21464, 19985, 19967, -1, 11411, 11326, 21104, -1, 20006, 19964, 20007, -1, 21465, 19981, 21444, -1, 21465, 21444, 21459, -1, 21092, 21091, 21460, -1, 21466, 21458, 21461, -1, 19982, 19981, 21465, -1, 20027, 21456, 21457, -1, 20027, 21457, 20002, -1, 11421, 11411, 21104, -1, 11605, 11607, 21462, -1, 21115, 21466, 21461, -1, 21467, 11605, 21462, -1, 21467, 21462, 19984, -1, 21467, 19984, 20004, -1, 18381, 19985, 21464, -1, 70, 21455, 58, -1, 70, 21463, 21455, -1, 18392, 19978, 18390, -1, 18364, 21463, 70, -1, 18382, 18381, 21464, -1, 18368, 18367, 21089, -1, 11600, 11605, 21467, -1, 18405, 20009, 19970, -1, 18405, 19970, 18406, -1, 21133, 21136, 21102, -1, 21133, 21102, 21076, -1, 21131, 21466, 21115, -1, 20032, 20031, 11951, -1, 18363, 18362, 21123, -1, 11419, 822, 821, -1, 14069, 822, 11419, -1, 14070, 822, 14069, -1, 14072, 822, 14070, -1, 14073, 822, 14072, -1, 14076, 822, 14073, -1, 822, 14961, 907, -1, 14076, 14961, 822, -1, 14961, 577, 907, -1, 14961, 14963, 577, -1, 11013, 389, 489, -1, 11013, 11012, 389, -1, 389, 11011, 334, -1, 11012, 11011, 389, -1, 11011, 335, 334, -1, 11011, 11029, 335, -1, 11029, 319, 335, -1, 11029, 11023, 319, -1, 319, 11007, 320, -1, 11023, 11007, 319, -1, 320, 11009, 259, -1, 11007, 11009, 320, -1, 214, 11034, 149, -1, 11037, 11034, 214, -1, 149, 11036, 150, -1, 11034, 11036, 149, -1, 150, 11053, 1852, -1, 11036, 11053, 150, -1, 1852, 11047, 87, -1, 11053, 11047, 1852, -1, 87, 11031, 88, -1, 11047, 11031, 87, -1, 88, 11033, 1837, -1, 11031, 11033, 88, -1, 1810, 10950, 1811, -1, 10953, 10950, 1810, -1, 1811, 10952, 1734, -1, 10950, 10952, 1811, -1, 1734, 10969, 1735, -1, 10952, 10969, 1734, -1, 1735, 10963, 1736, -1, 10969, 10963, 1735, -1, 1736, 10947, 1741, -1, 10963, 10947, 1736, -1, 1741, 10949, 1713, -1, 10947, 10949, 1741, -1, 1689, 10974, 1687, -1, 10977, 10974, 1689, -1, 1687, 10976, 3280, -1, 10974, 10976, 1687, -1, 3280, 10993, 3281, -1, 10976, 10993, 3280, -1, 3281, 10987, 3277, -1, 10993, 10987, 3281, -1, 3277, 10971, 1588, -1, 10987, 10971, 3277, -1, 1588, 10973, 1559, -1, 10971, 10973, 1588, -1, 1560, 11000, 1452, -1, 10998, 11000, 1560, -1, 1453, 11882, 3216, -1, 1453, 16977, 11882, -1, 1453, 16993, 16977, -1, 1452, 11006, 1453, -1, 11000, 11006, 1452, -1, 1453, 16996, 16993, -1, 11006, 16997, 1453, -1, 1453, 16997, 16996, -1, 2015, 17682, 2028, -1, 17678, 17682, 2015, -1, 2028, 17676, 906, -1, 17682, 17676, 2028, -1, 906, 11439, 981, -1, 906, 17032, 11439, -1, 906, 17030, 17032, -1, 17676, 17033, 906, -1, 906, 17031, 17030, -1, 17033, 17035, 906, -1, 906, 17035, 17031, -1, 387, 17674, 502, -1, 17675, 17674, 387, -1, 502, 17679, 2004, -1, 17674, 17679, 502, -1, 2004, 17678, 2015, -1, 17679, 17678, 2004, -1, 1923, 11259, 1931, -1, 11256, 11259, 1923, -1, 1931, 11258, 318, -1, 11259, 11258, 1931, -1, 318, 11263, 332, -1, 11258, 11263, 318, -1, 148, 11246, 215, -1, 11247, 11246, 148, -1, 215, 11250, 1912, -1, 11246, 11250, 215, -1, 1912, 11256, 1923, -1, 11250, 11256, 1912, -1, 1825, 11208, 1838, -1, 11204, 11208, 1825, -1, 1838, 11202, 86, -1, 11208, 11202, 1838, -1, 86, 11201, 92, -1, 11202, 11201, 86, -1, 1739, 11198, 1812, -1, 11199, 11198, 1739, -1, 1812, 11205, 1813, -1, 11198, 11205, 1812, -1, 1813, 11204, 1825, -1, 11205, 11204, 1813, -1, 1714, 11177, 1720, -1, 11174, 11177, 1714, -1, 1720, 11176, 1742, -1, 11177, 11176, 1720, -1, 1742, 11181, 1737, -1, 11176, 11181, 1742, -1, 3293, 11164, 1688, -1, 11165, 11164, 3293, -1, 1688, 11168, 1690, -1, 11164, 11168, 1688, -1, 1690, 11174, 1714, -1, 11168, 11174, 1690, -1, 11228, 1574, 1563, -1, 11228, 11232, 1574, -1, 1574, 11226, 1587, -1, 11232, 11226, 1574, -1, 11226, 3279, 1587, -1, 11226, 11225, 3279, -1, 11865, 3236, 3237, -1, 17711, 3236, 11865, -1, 17713, 3236, 17711, -1, 17714, 3236, 17713, -1, 17718, 3236, 17714, -1, 17718, 11223, 3236, -1, 11223, 11222, 3236, -1, 11222, 1562, 3236, -1, 11222, 11229, 1562, -1, 11229, 1563, 1562, -1, 11229, 11228, 1563, -1, 11392, 19243, 11384, -1, 14031, 19243, 11392, -1, 14032, 19243, 14031, -1, 14034, 19243, 14032, -1, 14035, 19243, 14034, -1, 10946, 19243, 14035, -1, 19243, 10938, 19230, -1, 10946, 10938, 19243, -1, 10938, 19213, 19230, -1, 10938, 10940, 19213, -1, 10917, 19164, 19181, -1, 10917, 10916, 19164, -1, 19164, 10915, 19139, -1, 10916, 10915, 19164, -1, 10915, 19119, 19139, -1, 10915, 10933, 19119, -1, 10933, 19095, 19119, -1, 10933, 10927, 19095, -1, 19095, 10911, 19082, -1, 10927, 10911, 19095, -1, 19082, 10913, 19062, -1, 10911, 10913, 19082, -1, 19025, 10890, 19011, -1, 10893, 10890, 19025, -1, 19011, 10892, 18979, -1, 10890, 10892, 19011, -1, 18979, 10909, 18980, -1, 10892, 10909, 18979, -1, 18980, 10903, 18970, -1, 10909, 10903, 18980, -1, 18970, 10887, 18957, -1, 10903, 10887, 18970, -1, 18957, 10889, 18941, -1, 10887, 10889, 18957, -1, 18907, 10842, 18899, -1, 10845, 10842, 18907, -1, 18899, 10844, 18886, -1, 10842, 10844, 18899, -1, 18886, 10861, 18887, -1, 10844, 10861, 18886, -1, 18887, 10855, 18863, -1, 10861, 10855, 18887, -1, 18863, 10839, 18850, -1, 10855, 10839, 18863, -1, 18850, 10841, 18704, -1, 10839, 10841, 18850, -1, 18705, 10866, 18820, -1, 10869, 10866, 18705, -1, 18820, 10868, 18811, -1, 10866, 10868, 18820, -1, 18811, 10885, 18799, -1, 10868, 10885, 18811, -1, 18799, 10879, 18791, -1, 10885, 10879, 18799, -1, 18791, 10863, 18783, -1, 10879, 10863, 18791, -1, 18783, 10865, 18569, -1, 10863, 10865, 18783, -1, 18570, 14953, 18738, -1, 14951, 14953, 18570, -1, 18488, 11812, 11811, -1, 18488, 16940, 11812, -1, 18488, 16956, 16940, -1, 18738, 14959, 18488, -1, 14953, 14959, 18738, -1, 18488, 16959, 16956, -1, 14959, 16960, 18488, -1, 18488, 16960, 16959, -1, 19211, 10792, 19212, -1, 10788, 10792, 19211, -1, 19212, 10786, 19229, -1, 10792, 10786, 19212, -1, 19229, 11373, 11367, -1, 19229, 14009, 11373, -1, 19229, 14007, 14009, -1, 10786, 10785, 19229, -1, 19229, 14008, 14007, -1, 10785, 14011, 19229, -1, 19229, 14011, 14008, -1, 19140, 10782, 19165, -1, 10783, 10782, 19140, -1, 19165, 10789, 19182, -1, 10782, 10789, 19165, -1, 19182, 10788, 19211, -1, 10789, 10788, 19182, -1, 19061, 10819, 19064, -1, 10816, 10819, 19061, -1, 19064, 10818, 19083, -1, 10819, 10818, 19064, -1, 19083, 10823, 19096, -1, 10818, 10823, 19083, -1, 18981, 10806, 19012, -1, 10807, 10806, 18981, -1, 19012, 10810, 19026, -1, 10806, 10810, 19012, -1, 19026, 10816, 19061, -1, 10810, 10816, 19026, -1, 18939, 10734, 18940, -1, 10730, 10734, 18939, -1, 18940, 10728, 18954, -1, 10734, 10728, 18940, -1, 18954, 10727, 18969, -1, 10728, 10727, 18954, -1, 18888, 10724, 18900, -1, 10725, 10724, 18888, -1, 18900, 10731, 18908, -1, 10724, 10731, 18900, -1, 18908, 10730, 18939, -1, 10731, 10730, 18908, -1, 18835, 10761, 18836, -1, 10758, 10761, 18835, -1, 18836, 10760, 18847, -1, 10761, 10760, 18836, -1, 18847, 10765, 18862, -1, 10760, 10765, 18847, -1, 18623, 10748, 18819, -1, 10749, 10748, 18623, -1, 18819, 10752, 18825, -1, 10748, 10752, 18819, -1, 18825, 10758, 18835, -1, 10752, 10758, 18825, -1, 14931, 18772, 18758, -1, 14931, 14935, 18772, -1, 18772, 14929, 18784, -1, 14935, 14929, 18772, -1, 14929, 18624, 18784, -1, 14929, 14928, 18624, -1, 11771, 18739, 11772, -1, 16910, 18739, 11771, -1, 16912, 18739, 16910, -1, 16913, 18739, 16912, -1, 16917, 18739, 16913, -1, 16917, 14926, 18739, -1, 14926, 14925, 18739, -1, 14925, 18746, 18739, -1, 14925, 14932, 18746, -1, 14932, 18758, 18746, -1, 14932, 14931, 18758, -1, 13996, 21116, 11360, -1, 13997, 21116, 13996, -1, 13999, 21116, 13997, -1, 14000, 21116, 13999, -1, 11360, 21116, 11353, -1, 14000, 10804, 21116, -1, 10804, 10803, 21116, -1, 10803, 19341, 21116, -1, 10803, 10801, 19341, -1, 10801, 19319, 19341, -1, 10801, 10800, 19319, -1, 10800, 19252, 19319, -1, 10800, 10799, 19252, -1, 19252, 10795, 19232, -1, 10799, 10795, 19252, -1, 10795, 19233, 19232, -1, 10795, 10794, 19233, -1, 19218, 10834, 19215, -1, 10835, 10834, 19218, -1, 19215, 10832, 19209, -1, 10834, 10832, 19215, -1, 19209, 10830, 19195, -1, 10832, 10830, 19209, -1, 19195, 10826, 19104, -1, 10830, 10826, 19195, -1, 19104, 10820, 19108, -1, 10826, 10820, 19104, -1, 19108, 10815, 19080, -1, 10820, 10815, 19108, -1, 19075, 10745, 19076, -1, 10746, 10745, 19075, -1, 19076, 10743, 19067, -1, 10745, 10743, 19076, -1, 19067, 10742, 19047, -1, 10743, 10742, 19067, -1, 19047, 10741, 18972, -1, 10742, 10741, 19047, -1, 18972, 10737, 18973, -1, 10741, 10737, 18972, -1, 18973, 10736, 18963, -1, 10737, 10736, 18973, -1, 18959, 10776, 18960, -1, 10777, 10776, 18959, -1, 18960, 10774, 18946, -1, 10776, 10774, 18960, -1, 18946, 10772, 18930, -1, 10774, 10772, 18946, -1, 18930, 10768, 18869, -1, 10772, 10768, 18930, -1, 18869, 10762, 18856, -1, 10768, 10762, 18869, -1, 18856, 10757, 18723, -1, 10762, 10757, 18856, -1, 18700, 14946, 18750, -1, 14947, 14946, 18700, -1, 18750, 14943, 18751, -1, 14946, 14943, 18750, -1, 18751, 14942, 18662, -1, 14943, 14942, 18751, -1, 18662, 14944, 18660, -1, 14942, 14944, 18662, -1, 18660, 14938, 18582, -1, 14944, 14938, 18660, -1, 18582, 11758, 11757, -1, 18582, 16903, 11758, -1, 18582, 16919, 16903, -1, 14938, 14937, 18582, -1, 18582, 16922, 16919, -1, 14937, 16923, 18582, -1, 18582, 16923, 16922, -1, 19342, 10217, 19340, -1, 10222, 10217, 19342, -1, 21176, 11340, 11338, -1, 21176, 13834, 11340, -1, 21176, 13832, 13834, -1, 19340, 10216, 21176, -1, 10217, 10216, 19340, -1, 21176, 13833, 13832, -1, 10216, 13836, 21176, -1, 21176, 13836, 13833, -1, 19217, 10181, 19253, -1, 10180, 10181, 19217, -1, 19253, 10187, 19317, -1, 10181, 10187, 19253, -1, 19317, 10186, 19318, -1, 10187, 10186, 19317, -1, 19207, 10176, 19208, -1, 10177, 10176, 19207, -1, 19208, 10175, 19216, -1, 10176, 10175, 19208, -1, 19216, 10180, 19217, -1, 10175, 10180, 19216, -1, 19079, 10204, 19103, -1, 10205, 10204, 19079, -1, 19103, 10211, 19193, -1, 10204, 10211, 19103, -1, 19193, 10210, 19194, -1, 10211, 10210, 19193, -1, 19066, 10200, 19068, -1, 10201, 10200, 19066, -1, 19068, 10199, 19078, -1, 10200, 10199, 19068, -1, 19078, 10205, 19079, -1, 10199, 10205, 19078, -1, 18962, 10264, 18974, -1, 10265, 10264, 18962, -1, 18974, 10271, 19048, -1, 10264, 10271, 18974, -1, 19048, 10270, 19050, -1, 10271, 10270, 19048, -1, 18928, 10260, 18947, -1, 10261, 10260, 18928, -1, 18947, 10259, 18961, -1, 10260, 10259, 18947, -1, 18961, 10265, 18962, -1, 10259, 10265, 18961, -1, 18838, 10241, 18868, -1, 10240, 10241, 18838, -1, 18868, 10247, 18929, -1, 10241, 10247, 18868, -1, 18929, 10246, 18927, -1, 10247, 10246, 18929, -1, 10237, 18749, 18802, -1, 10237, 10236, 18749, -1, 18749, 10235, 18788, -1, 10236, 10235, 18749, -1, 10235, 18838, 18788, -1, 10235, 10240, 18838, -1, 11747, 18661, 11748, -1, 16725, 18661, 11747, -1, 16727, 18661, 16725, -1, 16728, 18661, 16727, -1, 16732, 18661, 16728, -1, 14841, 18661, 16732, -1, 18661, 14840, 18659, -1, 14841, 14840, 18661, -1, 14840, 18803, 18659, -1, 14840, 14848, 18803, -1, 13962, 19157, 11415, -1, 13963, 19157, 13962, -1, 13965, 19157, 13963, -1, 13966, 19157, 13965, -1, 11415, 19157, 11410, -1, 13966, 10722, 19157, -1, 10722, 10721, 19157, -1, 10721, 19115, 19157, -1, 10721, 10719, 19115, -1, 10719, 19093, 19115, -1, 10719, 10718, 19093, -1, 10718, 19059, 19093, -1, 10718, 10717, 19059, -1, 19059, 10713, 19055, -1, 10717, 10713, 19059, -1, 10713, 19581, 19055, -1, 10713, 10712, 19581, -1, 19585, 10694, 18987, -1, 10695, 10694, 19585, -1, 18987, 10692, 18977, -1, 10694, 10692, 18987, -1, 18977, 10690, 18967, -1, 10692, 10690, 18977, -1, 18967, 10686, 18949, -1, 10690, 10686, 18967, -1, 18949, 10680, 19038, -1, 10686, 10680, 18949, -1, 19038, 10675, 18875, -1, 10680, 10675, 19038, -1, 18878, 10663, 18883, -1, 10664, 10663, 18878, -1, 18883, 10661, 18866, -1, 10663, 10661, 18883, -1, 18866, 10660, 18853, -1, 10661, 10660, 18866, -1, 18853, 10659, 18699, -1, 10660, 10659, 18853, -1, 18699, 10655, 18643, -1, 10659, 10655, 18699, -1, 18643, 10654, 18644, -1, 10655, 10654, 18643, -1, 18636, 10636, 18637, -1, 10637, 10636, 18636, -1, 18637, 10634, 18794, -1, 10636, 10634, 18637, -1, 18794, 10632, 18787, -1, 10634, 10632, 18794, -1, 18787, 10628, 18763, -1, 10632, 10628, 18787, -1, 18763, 10622, 18529, -1, 10628, 10622, 18763, -1, 18529, 10617, 18503, -1, 10622, 10617, 18529, -1, 18497, 14922, 18522, -1, 14923, 14922, 18497, -1, 18522, 14919, 18733, -1, 14922, 14919, 18522, -1, 18733, 14918, 18729, -1, 14919, 14918, 18733, -1, 18729, 14920, 18726, -1, 14918, 14920, 18729, -1, 18726, 14914, 18428, -1, 14920, 14914, 18726, -1, 18428, 11849, 11851, -1, 18428, 16866, 11849, -1, 18428, 16882, 16866, -1, 14914, 14913, 18428, -1, 18428, 16885, 16882, -1, 14913, 16886, 18428, -1, 18428, 16886, 16885, -1, 19117, 10937, 19132, -1, 10942, 10937, 19117, -1, 19156, 11400, 11396, -1, 19156, 14044, 11400, -1, 19156, 14042, 14044, -1, 19132, 10936, 19156, -1, 10937, 10936, 19132, -1, 19156, 14043, 14042, -1, 10936, 14046, 19156, -1, 19156, 14046, 14043, -1, 19056, 10925, 19057, -1, 10924, 10925, 19056, -1, 19057, 10931, 19073, -1, 10925, 10931, 19057, -1, 19073, 10930, 19092, -1, 10931, 10930, 19073, -1, 18976, 10920, 18985, -1, 10921, 10920, 18976, -1, 18985, 10919, 18986, -1, 10920, 10919, 18985, -1, 18986, 10924, 19056, -1, 10919, 10924, 18986, -1, 18874, 10901, 18950, -1, 10900, 10901, 18874, -1, 18950, 10907, 18952, -1, 10901, 10907, 18950, -1, 18952, 10906, 18966, -1, 10907, 10906, 18952, -1, 18865, 10896, 18880, -1, 10897, 10896, 18865, -1, 18880, 10895, 18882, -1, 10896, 10895, 18880, -1, 18882, 10900, 18874, -1, 10895, 10900, 18882, -1, 18635, 10853, 18696, -1, 10852, 10853, 18635, -1, 18696, 10859, 18845, -1, 10853, 10859, 18696, -1, 18845, 10858, 18852, -1, 10859, 10858, 18845, -1, 18631, 10848, 18806, -1, 10849, 10848, 18631, -1, 18806, 10847, 18642, -1, 10848, 10847, 18806, -1, 18642, 10852, 18635, -1, 10847, 10852, 18642, -1, 18521, 10876, 18764, -1, 10877, 10876, 18521, -1, 18764, 10883, 18774, -1, 10876, 10883, 18764, -1, 18774, 10882, 18632, -1, 10883, 10882, 18774, -1, 10873, 18736, 18513, -1, 10873, 10872, 18736, -1, 18736, 10871, 18523, -1, 10872, 10871, 18736, -1, 10871, 18521, 18523, -1, 10871, 10877, 18521, -1, 11833, 18450, 11832, -1, 16947, 18450, 11833, -1, 16949, 18450, 16947, -1, 16950, 18450, 16949, -1, 16954, 18450, 16950, -1, 14949, 18450, 16954, -1, 18450, 14948, 18727, -1, 14949, 14948, 18450, -1, 14948, 18514, 18727, -1, 14948, 14956, 18514, -1, 11446, 19008, 11441, -1, 13926, 19008, 11446, -1, 13927, 19008, 13926, -1, 13929, 19008, 13927, -1, 13930, 19008, 13929, -1, 10510, 19008, 13930, -1, 19008, 10502, 19006, -1, 10510, 10502, 19008, -1, 10502, 19535, 19006, -1, 10502, 10504, 19535, -1, 10517, 18933, 19437, -1, 10517, 10516, 18933, -1, 18933, 10515, 18917, -1, 10516, 10515, 18933, -1, 10515, 18902, 18917, -1, 10515, 10533, 18902, -1, 10533, 18890, 18902, -1, 10533, 10527, 18890, -1, 18890, 10511, 18891, -1, 10527, 10511, 18890, -1, 18891, 10513, 18860, -1, 10511, 10513, 18891, -1, 18792, 10586, 18798, -1, 10589, 10586, 18792, -1, 18798, 10588, 18822, -1, 10586, 10588, 18798, -1, 18822, 10605, 18815, -1, 10588, 10605, 18822, -1, 18815, 10599, 18816, -1, 10605, 10599, 18815, -1, 18816, 10583, 18655, -1, 10599, 10583, 18816, -1, 18655, 10585, 18606, -1, 10583, 10585, 18655, -1, 18588, 10562, 18594, -1, 10565, 10562, 18588, -1, 18594, 10564, 18755, -1, 10562, 10564, 18594, -1, 18755, 10581, 18744, -1, 10564, 10581, 18755, -1, 18744, 10575, 18741, -1, 10581, 10575, 18744, -1, 18741, 10559, 18538, -1, 10575, 10559, 18741, -1, 18538, 10561, 18500, -1, 10559, 10561, 18538, -1, 18485, 10538, 18486, -1, 10541, 10538, 18485, -1, 18486, 10540, 18722, -1, 10538, 10540, 18486, -1, 18722, 10557, 18720, -1, 10540, 10557, 18722, -1, 18720, 10551, 18715, -1, 10557, 10551, 18720, -1, 18715, 10535, 18437, -1, 10551, 10535, 18715, -1, 18437, 10537, 18419, -1, 10535, 10537, 18437, -1, 18415, 14893, 18712, -1, 14891, 14893, 18415, -1, 18377, 11884, 11886, -1, 18377, 16829, 11884, -1, 18377, 16845, 16829, -1, 18712, 14899, 18377, -1, 14893, 14899, 18712, -1, 18377, 16848, 16845, -1, 14899, 16849, 18377, -1, 18377, 16849, 16848, -1, 19715, 10710, 19791, -1, 10706, 10710, 19715, -1, 19791, 10704, 19007, -1, 10710, 10704, 19791, -1, 19007, 11428, 11426, -1, 19007, 13974, 11428, -1, 19007, 13972, 13974, -1, 10704, 10703, 19007, -1, 19007, 13973, 13972, -1, 10703, 13976, 19007, -1, 19007, 13976, 13973, -1, 18915, 10700, 18932, -1, 10701, 10700, 18915, -1, 18932, 10707, 19573, -1, 10700, 10707, 18932, -1, 19573, 10706, 19715, -1, 10707, 10706, 19573, -1, 19000, 10679, 19049, -1, 10676, 10679, 19000, -1, 19049, 10678, 18892, -1, 10679, 10678, 19049, -1, 18892, 10683, 18893, -1, 10678, 10683, 18892, -1, 18823, 10666, 18797, -1, 10667, 10666, 18823, -1, 18797, 10670, 18896, -1, 10666, 10670, 18797, -1, 18896, 10676, 19000, -1, 10670, 10676, 18896, -1, 18629, 10652, 18651, -1, 10648, 10652, 18629, -1, 18651, 10646, 18668, -1, 10652, 10646, 18651, -1, 18668, 10645, 18814, -1, 10646, 10645, 18668, -1, 18748, 10642, 18593, -1, 10643, 10642, 18748, -1, 18593, 10649, 18607, -1, 10642, 10649, 18593, -1, 18607, 10648, 18629, -1, 10649, 10648, 18607, -1, 18519, 10621, 18537, -1, 10618, 10621, 18519, -1, 18537, 10620, 18543, -1, 10621, 10620, 18537, -1, 18543, 10625, 18742, -1, 10620, 10625, 18543, -1, 18457, 10608, 18484, -1, 10609, 10608, 18457, -1, 18484, 10612, 18502, -1, 10608, 10612, 18484, -1, 18502, 10618, 18519, -1, 10612, 10618, 18502, -1, 14907, 18433, 18432, -1, 14907, 14911, 18433, -1, 18433, 14905, 18442, -1, 14911, 14905, 18433, -1, 14905, 18458, 18442, -1, 14905, 14904, 18458, -1, 11869, 18416, 11870, -1, 16873, 18416, 11869, -1, 16875, 18416, 16873, -1, 16876, 18416, 16875, -1, 16880, 18416, 16876, -1, 16880, 14902, 18416, -1, 14902, 14901, 18416, -1, 14901, 18414, 18416, -1, 14901, 14908, 18414, -1, 14908, 18432, 18414, -1, 14908, 14907, 18432, -1, 11666, 19660, 11279, -1, 13891, 19660, 11666, -1, 13892, 19660, 13891, -1, 13894, 19660, 13892, -1, 13895, 19660, 13894, -1, 10402, 19660, 13895, -1, 19660, 10394, 19658, -1, 10402, 10394, 19660, -1, 10394, 19676, 19658, -1, 10394, 10396, 19676, -1, 10409, 19558, 19642, -1, 10409, 10408, 19558, -1, 19558, 10407, 19559, -1, 10408, 10407, 19558, -1, 10407, 19536, 19559, -1, 10407, 10425, 19536, -1, 10425, 19517, 19536, -1, 10425, 10419, 19517, -1, 19517, 10403, 19518, -1, 10419, 10403, 19517, -1, 19518, 10405, 19533, -1, 10403, 10405, 19518, -1, 19511, 10430, 21248, -1, 10433, 10430, 19511, -1, 21248, 10432, 19385, -1, 10430, 10432, 21248, -1, 19385, 10449, 19386, -1, 10432, 10449, 19385, -1, 19386, 10443, 19387, -1, 10449, 10443, 19386, -1, 19387, 10427, 21234, -1, 10443, 10427, 19387, -1, 21234, 10429, 19372, -1, 10427, 10429, 21234, -1, 19360, 10454, 20917, -1, 10457, 10454, 19360, -1, 20917, 10456, 19285, -1, 10454, 10456, 20917, -1, 19285, 10473, 19287, -1, 10456, 10473, 19285, -1, 19287, 10467, 19288, -1, 10473, 10467, 19287, -1, 19288, 10451, 20792, -1, 10467, 10451, 19288, -1, 20792, 10453, 19250, -1, 10451, 10453, 20792, -1, 19249, 10478, 19153, -1, 10481, 10478, 19249, -1, 19153, 10480, 19154, -1, 10478, 10480, 19153, -1, 19154, 10497, 19124, -1, 10480, 10497, 19154, -1, 19124, 10491, 19113, -1, 10497, 10491, 19124, -1, 19113, 10475, 19110, -1, 10491, 10475, 19113, -1, 19110, 10477, 19101, -1, 10475, 10477, 19110, -1, 19098, 14881, 19002, -1, 14879, 14881, 19098, -1, 19003, 11690, 11689, -1, 19003, 16792, 11690, -1, 19003, 16808, 16792, -1, 19002, 14887, 19003, -1, 14881, 14887, 19002, -1, 19003, 16811, 16808, -1, 14887, 16812, 19003, -1, 19003, 16812, 16811, -1, 19646, 10378, 19675, -1, 10374, 10378, 19646, -1, 19675, 10372, 19659, -1, 10378, 10372, 19675, -1, 19659, 11660, 11659, -1, 19659, 13869, 11660, -1, 19659, 13867, 13869, -1, 10372, 10371, 19659, -1, 19659, 13868, 13867, -1, 10371, 13871, 19659, -1, 19659, 13871, 13868, -1, 19557, 10368, 19643, -1, 10369, 10368, 19557, -1, 19643, 10375, 19644, -1, 10368, 10375, 19643, -1, 19644, 10374, 19646, -1, 10375, 10374, 19644, -1, 19515, 10323, 19532, -1, 10320, 10323, 19515, -1, 19532, 10322, 19519, -1, 10323, 10322, 19532, -1, 19519, 10327, 19520, -1, 10322, 10327, 19519, -1, 19384, 10310, 19512, -1, 10311, 10310, 19384, -1, 19512, 10314, 19513, -1, 10310, 10314, 19512, -1, 19513, 10320, 19515, -1, 10314, 10320, 19513, -1, 19363, 10354, 19373, -1, 10350, 10354, 19363, -1, 19373, 10348, 21236, -1, 10354, 10348, 19373, -1, 21236, 10347, 19388, -1, 10348, 10347, 21236, -1, 19284, 10344, 19361, -1, 10345, 10344, 19284, -1, 19361, 10351, 19362, -1, 10344, 10351, 19361, -1, 19362, 10350, 19363, -1, 10351, 10350, 19362, -1, 19248, 10289, 19263, -1, 10286, 10289, 19248, -1, 19263, 10288, 20820, -1, 10289, 10288, 19263, -1, 20820, 10293, 19286, -1, 10288, 10293, 20820, -1, 19125, 10276, 19246, -1, 10277, 10276, 19125, -1, 19246, 10280, 19247, -1, 10276, 10280, 19246, -1, 19247, 10286, 19248, -1, 10280, 10286, 19247, -1, 14859, 19122, 19100, -1, 14859, 14863, 19122, -1, 19122, 14857, 19111, -1, 14863, 14857, 19122, -1, 14857, 19112, 19111, -1, 14857, 14856, 19112, -1, 11681, 19004, 11682, -1, 16762, 19004, 11681, -1, 16764, 19004, 16762, -1, 16765, 19004, 16764, -1, 16769, 19004, 16765, -1, 16769, 14854, 19004, -1, 14854, 14853, 19004, -1, 14853, 19099, 19004, -1, 14853, 14860, 19099, -1, 14860, 19100, 19099, -1, 14860, 14859, 19100, -1, 13857, 19796, 11655, -1, 13858, 19796, 13857, -1, 13860, 19796, 13858, -1, 13861, 19796, 13860, -1, 11655, 19796, 11653, -1, 13861, 10390, 19796, -1, 10390, 10389, 19796, -1, 10389, 19767, 19796, -1, 10389, 10387, 19767, -1, 10387, 19748, 19767, -1, 10387, 10386, 19748, -1, 10386, 19713, 19748, -1, 10386, 10385, 19713, -1, 19713, 10381, 19712, -1, 10385, 10381, 19713, -1, 10381, 21319, 19712, -1, 10381, 10380, 21319, -1, 21320, 10338, 19634, -1, 10339, 10338, 21320, -1, 19634, 10336, 19623, -1, 10338, 10336, 19634, -1, 19623, 10334, 19614, -1, 10336, 10334, 19623, -1, 19614, 10330, 19575, -1, 10334, 10330, 19614, -1, 19575, 10324, 19574, -1, 10330, 10324, 19575, -1, 19574, 10319, 19496, -1, 10324, 10319, 19574, -1, 19495, 10365, 19499, -1, 10366, 10365, 19495, -1, 19499, 10362, 19484, -1, 10365, 10362, 19499, -1, 19484, 10361, 19464, -1, 10362, 10361, 19484, -1, 19464, 10363, 19416, -1, 10361, 10363, 19464, -1, 19416, 10357, 19417, -1, 10363, 10357, 19416, -1, 19417, 10356, 19353, -1, 10357, 10356, 19417, -1, 19352, 10304, 19357, -1, 10305, 10304, 19352, -1, 19357, 10302, 19344, -1, 10304, 10302, 19357, -1, 19344, 10300, 19332, -1, 10302, 10300, 19344, -1, 19332, 10296, 19298, -1, 10300, 10296, 19332, -1, 19298, 10290, 19299, -1, 10296, 10290, 19298, -1, 19299, 10285, 20628, -1, 10290, 10285, 19299, -1, 20545, 14874, 19235, -1, 14875, 14874, 20545, -1, 19235, 14871, 19220, -1, 14874, 14871, 19235, -1, 19220, 14870, 19200, -1, 14871, 14870, 19220, -1, 19200, 14872, 19175, -1, 14870, 14872, 19200, -1, 19175, 14866, 19176, -1, 14872, 14866, 19175, -1, 19176, 11696, 11695, -1, 19176, 16755, 11696, -1, 19176, 16771, 16755, -1, 14866, 14865, 19176, -1, 19176, 16774, 16771, -1, 14865, 16775, 19176, -1, 19176, 16775, 16774, -1, 19766, 6541, 19776, -1, 6546, 6541, 19766, -1, 19797, 11646, 11645, -1, 19797, 12540, 11646, -1, 19797, 12538, 12540, -1, 19776, 6540, 19797, -1, 6541, 6540, 19776, -1, 19797, 12539, 12538, -1, 6540, 12542, 19797, -1, 19797, 12542, 12539, -1, 19710, 6564, 19711, -1, 6565, 6564, 19710, -1, 19711, 6571, 19725, -1, 6564, 6571, 19711, -1, 19725, 6570, 19747, -1, 6571, 6570, 19725, -1, 19622, 6560, 19633, -1, 6561, 6560, 19622, -1, 19633, 6559, 19648, -1, 6560, 6559, 19633, -1, 19648, 6565, 19710, -1, 6559, 6565, 19648, -1, 19526, 6481, 19572, -1, 6480, 6481, 19526, -1, 19572, 6487, 19589, -1, 6481, 6487, 19572, -1, 19589, 6486, 19613, -1, 6487, 6486, 19589, -1, 19485, 6476, 19503, -1, 6477, 6476, 19485, -1, 19503, 6475, 19525, -1, 6476, 6475, 19503, -1, 19525, 6480, 19526, -1, 6475, 6480, 19525, -1, 19367, 6504, 19418, -1, 6505, 6504, 19367, -1, 19418, 6511, 19444, -1, 6504, 6511, 19418, -1, 19444, 6510, 19465, -1, 6511, 6510, 19444, -1, 19335, 6500, 19358, -1, 6501, 6500, 19335, -1, 19358, 6499, 19368, -1, 6500, 6499, 19358, -1, 19368, 6505, 19367, -1, 6499, 6505, 19368, -1, 19257, 6528, 19301, -1, 6529, 6528, 19257, -1, 19301, 6535, 19307, -1, 6528, 6535, 19301, -1, 19307, 6534, 19334, -1, 6535, 6534, 19307, -1, 6525, 19236, 19199, -1, 6525, 6524, 19236, -1, 19236, 6523, 19258, -1, 6524, 6523, 19236, -1, 6523, 19257, 19258, -1, 6523, 6529, 19257, -1, 11703, 19177, 11704, -1, 15467, 19177, 11703, -1, 15469, 19177, 15467, -1, 15470, 19177, 15469, -1, 15474, 19177, 15470, -1, 14333, 19177, 15474, -1, 19177, 14332, 19178, -1, 14333, 14332, 19177, -1, 14332, 19198, 19178, -1, 14332, 14340, 19198, -1, 11329, 19476, 11324, -1, 13822, 19476, 11329, -1, 13823, 19476, 13822, -1, 13825, 19476, 13823, -1, 13826, 19476, 13825, -1, 10226, 19476, 13826, -1, 19476, 10218, 19447, -1, 10226, 10218, 19476, -1, 10218, 19421, 19447, -1, 10218, 10220, 19421, -1, 10173, 19382, 19381, -1, 10173, 10172, 19382, -1, 19382, 10171, 21068, -1, 10172, 10171, 19382, -1, 10171, 21069, 21068, -1, 10171, 10189, 21069, -1, 10189, 19322, 21069, -1, 10189, 10183, 19322, -1, 19322, 10167, 19305, -1, 10183, 10167, 19322, -1, 19305, 10169, 19296, -1, 10167, 10169, 19305, -1, 19270, 10194, 19267, -1, 10197, 10194, 19270, -1, 19267, 10196, 19186, -1, 10194, 10196, 19267, -1, 19186, 10213, 19187, -1, 10196, 10213, 19186, -1, 19187, 10207, 19184, -1, 10213, 10207, 19187, -1, 19184, 10191, 19190, -1, 10207, 10191, 19184, -1, 19190, 10193, 19171, -1, 10191, 10193, 19190, -1, 19129, 10254, 19130, -1, 10257, 10254, 19129, -1, 19130, 10256, 19039, -1, 10254, 10256, 19130, -1, 19039, 10273, 19040, -1, 10256, 10273, 19039, -1, 19040, 10267, 19036, -1, 10273, 10267, 19040, -1, 19036, 10251, 19043, -1, 10267, 10251, 19036, -1, 19043, 10253, 19014, -1, 10251, 10253, 19043, -1, 18993, 10230, 18989, -1, 10233, 10230, 18993, -1, 18989, 10232, 19268, -1, 10230, 10232, 18989, -1, 19268, 10249, 19269, -1, 10232, 10249, 19268, -1, 19269, 10243, 18936, -1, 10249, 10243, 19269, -1, 18936, 10227, 18919, -1, 10243, 10227, 18936, -1, 18919, 10229, 18897, -1, 10227, 10229, 18919, -1, 18871, 14845, 18730, -1, 14843, 14845, 18871, -1, 18690, 11734, 11733, -1, 18690, 16718, 11734, -1, 18690, 16734, 16718, -1, 18730, 14851, 18690, -1, 14845, 14851, 18730, -1, 18690, 16737, 16734, -1, 14851, 16738, 18690, -1, 18690, 16738, 16737, -1, 19400, 10062, 19420, -1, 10058, 10062, 19400, -1, 19420, 10056, 19475, -1, 10062, 10056, 19420, -1, 19475, 11311, 11307, -1, 19475, 13799, 11311, -1, 19475, 13797, 13799, -1, 10056, 10055, 19475, -1, 19475, 13798, 13797, -1, 10055, 13801, 19475, -1, 19475, 13801, 13798, -1, 19378, 10052, 19379, -1, 10053, 10052, 19378, -1, 19379, 10059, 19380, -1, 10052, 10059, 19379, -1, 19380, 10058, 19400, -1, 10059, 10058, 19380, -1, 19290, 10089, 19295, -1, 10086, 10089, 19290, -1, 19295, 10088, 19304, -1, 10089, 10088, 19295, -1, 19304, 10093, 19321, -1, 10088, 10093, 19304, -1, 19223, 10076, 19265, -1, 10077, 10076, 19223, -1, 19265, 10080, 19266, -1, 10076, 10080, 19265, -1, 19266, 10086, 19290, -1, 10080, 10086, 19266, -1, 19150, 10120, 19172, -1, 10116, 10120, 19150, -1, 19172, 10114, 19189, -1, 10120, 10114, 19172, -1, 19189, 10113, 19185, -1, 10114, 10113, 19189, -1, 19088, 10110, 19127, -1, 10111, 10110, 19088, -1, 19127, 10117, 19128, -1, 10110, 10117, 19127, -1, 19128, 10116, 19150, -1, 10117, 10116, 19128, -1, 19015, 10147, 19022, -1, 10144, 10147, 19015, -1, 19022, 10146, 19042, -1, 10147, 10146, 19022, -1, 19042, 10151, 19037, -1, 10146, 10151, 19042, -1, 18990, 10134, 18991, -1, 10135, 10134, 18990, -1, 18991, 10138, 18992, -1, 10134, 10138, 18991, -1, 18992, 10144, 19015, -1, 10138, 10144, 18992, -1, 14823, 18905, 18895, -1, 14823, 14827, 18905, -1, 18905, 14821, 18920, -1, 14827, 14821, 18905, -1, 14821, 18935, 18920, -1, 14821, 14820, 18935, -1, 11725, 18830, 11724, -1, 16688, 18830, 11725, -1, 16690, 18830, 16688, -1, 16691, 18830, 16690, -1, 16695, 18830, 16691, -1, 16695, 14818, 18830, -1, 14818, 14817, 18830, -1, 14817, 18872, 18830, -1, 14817, 14824, 18872, -1, 14824, 18895, 18872, -1, 14824, 14823, 18895, -1, 13786, 19568, 11296, -1, 13787, 19568, 13786, -1, 13789, 19568, 13787, -1, 13790, 19568, 13789, -1, 11296, 19568, 11294, -1, 13790, 10074, 19568, -1, 10074, 10073, 19568, -1, 10073, 19544, 19568, -1, 10073, 10071, 19544, -1, 10071, 19492, 19544, -1, 10071, 10070, 19492, -1, 10070, 19478, 19492, -1, 10070, 10069, 19478, -1, 19478, 10065, 19453, -1, 10069, 10065, 19478, -1, 10065, 19452, 19453, -1, 10065, 10064, 19452, -1, 19407, 10104, 19392, -1, 10105, 10104, 19407, -1, 19392, 10102, 19393, -1, 10104, 10102, 19392, -1, 19393, 10100, 19347, -1, 10102, 10100, 19393, -1, 19347, 10096, 19328, -1, 10100, 10096, 19347, -1, 19328, 10090, 19329, -1, 10096, 10090, 19328, -1, 19329, 10085, 19273, -1, 10090, 10085, 19329, -1, 19277, 10131, 19282, -1, 10132, 10131, 19277, -1, 19282, 10128, 19279, -1, 10131, 10128, 19282, -1, 19279, 10127, 19227, -1, 10128, 10127, 19279, -1, 19227, 10129, 19204, -1, 10127, 10129, 19227, -1, 19204, 10123, 19205, -1, 10129, 10123, 19204, -1, 19205, 10122, 19134, -1, 10123, 10122, 19205, -1, 19136, 10162, 19147, -1, 10163, 10162, 19136, -1, 19147, 10160, 19144, -1, 10162, 10160, 19147, -1, 19144, 10158, 19086, -1, 10160, 10158, 19144, -1, 19086, 10154, 19071, -1, 10158, 10154, 19086, -1, 19071, 10148, 19053, -1, 10154, 10148, 19071, -1, 19053, 10143, 19029, -1, 10148, 10143, 19053, -1, 19018, 14838, 18995, -1, 14839, 14838, 19018, -1, 18995, 14835, 18996, -1, 14838, 14835, 18995, -1, 18996, 14834, 18998, -1, 14835, 14834, 18996, -1, 18998, 14836, 18943, -1, 14834, 14836, 18998, -1, 18943, 14830, 18924, -1, 14836, 14830, 18943, -1, 18924, 11713, 11712, -1, 18924, 16681, 11713, -1, 18924, 16697, 16681, -1, 14830, 14829, 18924, -1, 18924, 16700, 16697, -1, 14829, 16701, 18924, -1, 18924, 16701, 16700, -1, 21290, 10393, 19543, -1, 10398, 10393, 21290, -1, 19569, 11285, 11283, -1, 19569, 13904, 11285, -1, 19569, 13902, 13904, -1, 19543, 10392, 19569, -1, 10393, 10392, 19543, -1, 19569, 13903, 13902, -1, 10392, 13906, 19569, -1, 19569, 13906, 13903, -1, 19424, 10416, 19450, -1, 10417, 10416, 19424, -1, 19450, 10423, 19490, -1, 10416, 10423, 19450, -1, 19490, 10422, 21284, -1, 10423, 10422, 19490, -1, 21240, 10412, 19390, -1, 10413, 10412, 21240, -1, 19390, 10411, 19403, -1, 10412, 10411, 19390, -1, 19403, 10417, 19424, -1, 10411, 10417, 19403, -1, 19293, 10440, 19327, -1, 10441, 10440, 19293, -1, 19327, 10447, 19346, -1, 10440, 10447, 19327, -1, 19346, 10446, 21233, -1, 10447, 10446, 19346, -1, 20854, 10436, 19280, -1, 10437, 10436, 20854, -1, 19280, 10435, 19292, -1, 10436, 10435, 19280, -1, 19292, 10441, 19293, -1, 10435, 10441, 19292, -1, 19169, 10464, 19203, -1, 10465, 10464, 19169, -1, 19203, 10471, 19226, -1, 10464, 10471, 19203, -1, 19226, 10470, 20785, -1, 10471, 10470, 19226, -1, 20268, 10460, 19145, -1, 10461, 10460, 20268, -1, 19145, 10459, 19167, -1, 10460, 10459, 19145, -1, 19167, 10465, 19169, -1, 10459, 10465, 19167, -1, 19028, 10488, 19052, -1, 10489, 10488, 19028, -1, 19052, 10495, 19085, -1, 10488, 10495, 19052, -1, 19085, 10494, 20222, -1, 10495, 10494, 19085, -1, 10485, 18999, 19749, -1, 10485, 10484, 18999, -1, 18999, 10483, 19019, -1, 10484, 10483, 18999, -1, 10483, 19028, 19019, -1, 10483, 10489, 19028, -1, 11699, 18925, 11700, -1, 16799, 18925, 11699, -1, 16801, 18925, 16799, -1, 16802, 18925, 16801, -1, 16806, 18925, 16802, -1, 14877, 18925, 16806, -1, 18925, 14876, 18944, -1, 14877, 14876, 18925, -1, 14876, 19645, 18944, -1, 14876, 14884, 19645, -1, 11623, 2976, 3388, -1, 13749, 2976, 11623, -1, 13750, 2976, 13749, -1, 13752, 2976, 13750, -1, 13753, 2976, 13752, -1, 13756, 2976, 13753, -1, 2976, 14809, 2964, -1, 13756, 14809, 2976, -1, 14809, 2965, 2964, -1, 14809, 14811, 2965, -1, 10033, 2904, 2916, -1, 10033, 10032, 2904, -1, 2904, 10031, 2892, -1, 10032, 10031, 2904, -1, 10031, 2878, 2892, -1, 10031, 10049, 2878, -1, 10049, 2865, 2878, -1, 10049, 10043, 2865, -1, 2865, 10027, 2850, -1, 10043, 10027, 2865, -1, 2850, 10029, 2847, -1, 10027, 10029, 2850, -1, 2801, 10006, 2781, -1, 10009, 10006, 2801, -1, 2781, 10008, 2745, -1, 10006, 10008, 2781, -1, 2745, 10025, 2746, -1, 10008, 10025, 2745, -1, 2746, 10019, 2737, -1, 10025, 10019, 2746, -1, 2737, 10003, 2723, -1, 10019, 10003, 2737, -1, 2723, 10005, 2720, -1, 10003, 10005, 2723, -1, 2659, 9982, 2649, -1, 9985, 9982, 2659, -1, 2649, 9984, 2627, -1, 9982, 9984, 2649, -1, 2627, 10001, 2628, -1, 9984, 10001, 2627, -1, 2628, 9995, 2605, -1, 10001, 9995, 2628, -1, 2605, 9979, 2580, -1, 9995, 9979, 2605, -1, 2580, 9981, 2579, -1, 9979, 9981, 2580, -1, 2532, 9946, 2514, -1, 9949, 9946, 2532, -1, 2514, 9948, 2506, -1, 9946, 9948, 2514, -1, 2506, 9965, 2486, -1, 9948, 9965, 2506, -1, 2486, 9959, 2471, -1, 9965, 9959, 2486, -1, 2471, 9943, 2441, -1, 9959, 9943, 2471, -1, 2441, 9945, 2442, -1, 9943, 9945, 2441, -1, 2393, 9972, 2369, -1, 9970, 9972, 2393, -1, 2367, 12024, 2790, -1, 2367, 16644, 12024, -1, 2367, 16660, 16644, -1, 2369, 9978, 2367, -1, 9972, 9978, 2369, -1, 2367, 16663, 16660, -1, 9978, 16664, 2367, -1, 2367, 16664, 16663, -1, 3379, 14797, 2962, -1, 14793, 14797, 3379, -1, 2962, 14791, 2963, -1, 14797, 14791, 2962, -1, 2963, 11602, 2977, -1, 2963, 13724, 11602, -1, 2963, 13722, 13724, -1, 14791, 13725, 2963, -1, 2963, 13723, 13722, -1, 13725, 13727, 2963, -1, 2963, 13727, 13723, -1, 2891, 14789, 2903, -1, 14790, 14789, 2891, -1, 2903, 14794, 3364, -1, 14789, 14794, 2903, -1, 3364, 14793, 3379, -1, 14794, 14793, 3364, -1, 3309, 9841, 2848, -1, 9838, 9841, 3309, -1, 2848, 9840, 2849, -1, 9841, 9840, 2848, -1, 2849, 9845, 2864, -1, 9840, 9845, 2849, -1, 2747, 9828, 2780, -1, 9829, 9828, 2747, -1, 2780, 9832, 3298, -1, 9828, 9832, 2780, -1, 3298, 9838, 3309, -1, 9832, 9838, 3298, -1, 3241, 9872, 2721, -1, 9868, 9872, 3241, -1, 2721, 9866, 2722, -1, 9872, 9866, 2721, -1, 2722, 9865, 2736, -1, 9866, 9865, 2722, -1, 2629, 9862, 2648, -1, 9863, 9862, 2629, -1, 2648, 9869, 3228, -1, 9862, 9869, 2648, -1, 3228, 9868, 3241, -1, 9869, 9868, 3228, -1, 3190, 9899, 2577, -1, 9896, 9899, 3190, -1, 2577, 9898, 2578, -1, 9899, 9898, 2577, -1, 2578, 9903, 2603, -1, 9898, 9903, 2578, -1, 2487, 9886, 2513, -1, 9887, 9886, 2487, -1, 2513, 9890, 3179, -1, 9886, 9890, 2513, -1, 3179, 9896, 3190, -1, 9890, 9896, 3179, -1, 9926, 2443, 3125, -1, 9926, 9930, 2443, -1, 2443, 9924, 2444, -1, 9930, 9924, 2443, -1, 9924, 2469, 2444, -1, 9924, 9923, 2469, -1, 12010, 2372, 2371, -1, 16614, 2372, 12010, -1, 16616, 2372, 16614, -1, 16617, 2372, 16616, -1, 16621, 2372, 16617, -1, 16621, 9921, 2372, -1, 9921, 9920, 2372, -1, 9920, 2392, 2372, -1, 9920, 9927, 2392, -1, 9927, 3125, 2392, -1, 9927, 9926, 3125, -1, 13711, 131, 11596, -1, 13712, 131, 13711, -1, 13714, 131, 13712, -1, 13715, 131, 13714, -1, 11596, 131, 130, -1, 13715, 13718, 131, -1, 13718, 14807, 131, -1, 14807, 163, 131, -1, 14807, 14805, 163, -1, 14805, 3008, 163, -1, 14805, 14804, 3008, -1, 14804, 3009, 3008, -1, 14804, 14803, 3009, -1, 3009, 14800, 2972, -1, 14803, 14800, 3009, -1, 14800, 2973, 2972, -1, 14800, 14799, 2973, -1, 2948, 9856, 2946, -1, 9857, 9856, 2948, -1, 2946, 9854, 2944, -1, 9856, 9854, 2946, -1, 2944, 9852, 2920, -1, 9854, 9852, 2944, -1, 2920, 9848, 2921, -1, 9852, 9848, 2920, -1, 2921, 9842, 2842, -1, 9848, 9842, 2921, -1, 2842, 9837, 2843, -1, 9842, 9837, 2842, -1, 2845, 9883, 3303, -1, 9884, 9883, 2845, -1, 3303, 9880, 2835, -1, 9883, 9880, 3303, -1, 2835, 9879, 2811, -1, 9880, 9879, 2835, -1, 2811, 9881, 2812, -1, 9879, 9881, 2811, -1, 2812, 9875, 2725, -1, 9881, 9875, 2812, -1, 2725, 9874, 2726, -1, 9875, 9874, 2725, -1, 2727, 9914, 3238, -1, 9915, 9914, 2727, -1, 3238, 9912, 2709, -1, 9914, 9912, 3238, -1, 2709, 9910, 2665, -1, 9912, 9910, 2709, -1, 2665, 9906, 2666, -1, 9910, 9906, 2665, -1, 2666, 9900, 2587, -1, 9906, 9900, 2666, -1, 2587, 9895, 2561, -1, 9900, 9895, 2587, -1, 2557, 9941, 2558, -1, 9942, 9941, 2557, -1, 2558, 9938, 2555, -1, 9941, 9938, 2558, -1, 2555, 9937, 2539, -1, 9938, 9937, 2555, -1, 2539, 9939, 2540, -1, 9937, 9939, 2539, -1, 2540, 9933, 2454, -1, 9939, 9933, 2540, -1, 2454, 11997, 2455, -1, 2454, 16607, 11997, -1, 2454, 16623, 16607, -1, 9933, 9932, 2454, -1, 2454, 16626, 16623, -1, 9932, 16627, 2454, -1, 2454, 16627, 16626, -1, 134, 14752, 164, -1, 14757, 14752, 134, -1, 162, 11579, 181, -1, 162, 13607, 11579, -1, 162, 13605, 13607, -1, 164, 13608, 162, -1, 14752, 13608, 164, -1, 162, 13606, 13605, -1, 13608, 13610, 162, -1, 162, 13610, 13606, -1, 2949, 9508, 3010, -1, 9509, 9508, 2949, -1, 3010, 9515, 3011, -1, 9508, 9515, 3010, -1, 3011, 9514, 135, -1, 9515, 9514, 3011, -1, 2943, 9504, 2958, -1, 9505, 9504, 2943, -1, 2958, 9503, 2947, -1, 9504, 9503, 2958, -1, 2947, 9509, 2949, -1, 9503, 9509, 2947, -1, 2844, 9568, 2922, -1, 9569, 9568, 2844, -1, 2922, 9575, 2923, -1, 9568, 9575, 2922, -1, 2923, 9574, 2930, -1, 9575, 9574, 2923, -1, 2836, 9564, 2852, -1, 9565, 9564, 2836, -1, 2852, 9563, 3306, -1, 9564, 9563, 2852, -1, 3306, 9569, 2844, -1, 9563, 9569, 3306, -1, 2728, 9593, 2813, -1, 9592, 9593, 2728, -1, 2813, 9599, 2814, -1, 9593, 9599, 2813, -1, 2814, 9598, 2819, -1, 9599, 9598, 2814, -1, 2702, 9588, 2730, -1, 9589, 9588, 2702, -1, 2730, 9587, 3240, -1, 9588, 9587, 2730, -1, 3240, 9592, 2728, -1, 9587, 9592, 3240, -1, 2560, 9545, 2667, -1, 9544, 9545, 2560, -1, 2667, 9551, 2668, -1, 9545, 9551, 2667, -1, 2668, 9550, 2701, -1, 9551, 9550, 2668, -1, 9541, 2575, 2544, -1, 9541, 9540, 2575, -1, 2575, 9539, 2559, -1, 9540, 9539, 2575, -1, 9539, 2560, 2559, -1, 9539, 9544, 2560, -1, 11989, 2459, 2457, -1, 16503, 2459, 11989, -1, 16505, 2459, 16503, -1, 16506, 2459, 16505, -1, 16510, 2459, 16506, -1, 9520, 2459, 16510, -1, 2459, 9519, 2542, -1, 9520, 9519, 2459, -1, 9519, 2543, 2542, -1, 9519, 9527, 2543, -1, 11641, 2774, 3275, -1, 13671, 2774, 11641, -1, 13672, 2774, 13671, -1, 13674, 2774, 13672, -1, 13675, 2774, 13674, -1, 13678, 2774, 13675, -1, 2774, 14781, 2775, -1, 13678, 14781, 2774, -1, 14781, 2795, 2775, -1, 14781, 14783, 2795, -1, 9785, 2676, 2755, -1, 9785, 9784, 2676, -1, 2676, 9783, 2677, -1, 9784, 9783, 2676, -1, 9783, 2655, 2677, -1, 9783, 9801, 2655, -1, 9801, 2636, 2655, -1, 9801, 9795, 2636, -1, 2636, 9779, 2637, -1, 9795, 9779, 2636, -1, 2637, 9781, 2653, -1, 9779, 9781, 2637, -1, 2631, 9806, 3173, -1, 9809, 9806, 2631, -1, 3173, 9808, 2524, -1, 9806, 9808, 3173, -1, 2524, 9825, 2526, -1, 9808, 9825, 2524, -1, 2526, 9819, 2525, -1, 9825, 9819, 2526, -1, 2525, 9803, 3159, -1, 9819, 9803, 2525, -1, 3159, 9805, 2502, -1, 9803, 9805, 3159, -1, 2500, 9722, 3106, -1, 9725, 9722, 2500, -1, 3106, 9724, 2414, -1, 9722, 9724, 3106, -1, 2414, 9741, 2415, -1, 9724, 9741, 2414, -1, 2415, 9735, 2413, -1, 9741, 9735, 2415, -1, 2413, 9719, 3052, -1, 9735, 9719, 2413, -1, 3052, 9721, 2382, -1, 9719, 9721, 3052, -1, 2378, 9746, 2285, -1, 9749, 9746, 2378, -1, 2285, 9748, 2286, -1, 9746, 9748, 2285, -1, 2286, 9765, 2255, -1, 9748, 9765, 2286, -1, 2255, 9759, 2243, -1, 9765, 9759, 2255, -1, 2243, 9743, 2241, -1, 9759, 9743, 2243, -1, 2241, 9745, 2169, -1, 9743, 9745, 2241, -1, 2096, 9772, 2097, -1, 9770, 9772, 2096, -1, 1840, 12053, 1841, -1, 1840, 16570, 12053, -1, 1840, 16586, 16570, -1, 2097, 9778, 1840, -1, 9772, 9778, 2097, -1, 1840, 16589, 16586, -1, 9778, 16590, 1840, -1, 1840, 16590, 16589, -1, 2758, 14769, 2794, -1, 14765, 14769, 2758, -1, 2794, 14763, 2776, -1, 14769, 14763, 2794, -1, 2776, 11644, 2777, -1, 2776, 13646, 11644, -1, 2776, 13644, 13646, -1, 14763, 13647, 2776, -1, 2776, 13645, 13644, -1, 13647, 13649, 2776, -1, 2776, 13649, 13645, -1, 2678, 14761, 2756, -1, 14762, 14761, 2678, -1, 2756, 14766, 2757, -1, 14761, 14766, 2756, -1, 2757, 14765, 2758, -1, 14766, 14765, 2757, -1, 2634, 9699, 2652, -1, 9696, 9699, 2634, -1, 2652, 9698, 2638, -1, 9699, 9698, 2652, -1, 2638, 9703, 2639, -1, 9698, 9703, 2638, -1, 2523, 9686, 2632, -1, 9687, 9686, 2523, -1, 2632, 9690, 2633, -1, 9686, 9690, 2632, -1, 2633, 9696, 2634, -1, 9690, 9696, 2633, -1, 2504, 9672, 2511, -1, 9668, 9672, 2504, -1, 2511, 9666, 3161, -1, 9672, 9666, 2511, -1, 3161, 9665, 2522, -1, 9666, 9665, 3161, -1, 2412, 9662, 2501, -1, 9663, 9662, 2412, -1, 2501, 9669, 2503, -1, 9662, 9669, 2501, -1, 2503, 9668, 2504, -1, 9669, 9668, 2503, -1, 2381, 9641, 2395, -1, 9638, 9641, 2381, -1, 2395, 9640, 3072, -1, 9641, 9640, 2395, -1, 3072, 9645, 2411, -1, 9640, 9645, 3072, -1, 2254, 9628, 2379, -1, 9629, 9628, 2254, -1, 2379, 9632, 2380, -1, 9628, 9632, 2379, -1, 2380, 9638, 2381, -1, 9632, 9638, 2380, -1, 9610, 2252, 2234, -1, 9610, 9614, 2252, -1, 2252, 9608, 2242, -1, 9614, 9608, 2252, -1, 9608, 2244, 2242, -1, 9608, 9607, 2244, -1, 12046, 2098, 2171, -1, 16540, 2098, 12046, -1, 16542, 2098, 16540, -1, 16543, 2098, 16542, -1, 16547, 2098, 16543, -1, 16547, 9605, 2098, -1, 9605, 9604, 2098, -1, 9604, 2152, 2098, -1, 9604, 9611, 2152, -1, 9611, 2234, 2152, -1, 9611, 9610, 2234, -1, 13632, 2900, 11640, -1, 13633, 2900, 13632, -1, 13635, 2900, 13633, -1, 13636, 2900, 13635, -1, 11640, 2900, 3324, -1, 13636, 13639, 2900, -1, 13639, 14779, 2900, -1, 14779, 2875, 2900, -1, 14779, 14777, 2875, -1, 14777, 2860, 2875, -1, 14777, 14776, 2860, -1, 14776, 2826, 2860, -1, 14776, 14775, 2826, -1, 2826, 14772, 2827, -1, 14775, 14772, 2826, -1, 14772, 3259, 2827, -1, 14772, 14771, 3259, -1, 3260, 9714, 2750, -1, 9715, 9714, 3260, -1, 2750, 9712, 2739, -1, 9714, 9712, 2750, -1, 2739, 9710, 2732, -1, 9712, 9710, 2739, -1, 2732, 9706, 2697, -1, 9710, 9706, 2732, -1, 2697, 9700, 2698, -1, 9706, 9700, 2697, -1, 2698, 9695, 2618, -1, 9700, 9695, 2698, -1, 2617, 9683, 2623, -1, 9684, 9683, 2617, -1, 2623, 9681, 2608, -1, 9683, 9681, 2623, -1, 2608, 9680, 2584, -1, 9681, 9680, 2608, -1, 2584, 9679, 2548, -1, 9680, 9679, 2584, -1, 2548, 9675, 2547, -1, 9679, 9675, 2548, -1, 2547, 9674, 2492, -1, 9675, 9674, 2547, -1, 2491, 9656, 2498, -1, 9657, 9656, 2491, -1, 2498, 9654, 2479, -1, 9656, 9654, 2498, -1, 2479, 9652, 2466, -1, 9654, 9652, 2479, -1, 2466, 9648, 2428, -1, 9652, 9648, 2466, -1, 2428, 9642, 2429, -1, 9648, 9642, 2428, -1, 2429, 9637, 2912, -1, 9642, 9637, 2429, -1, 2833, 9625, 2365, -1, 9626, 9625, 2833, -1, 2365, 9622, 2348, -1, 9625, 9622, 2365, -1, 2348, 9621, 2324, -1, 9622, 9621, 2348, -1, 2324, 9623, 2300, -1, 9621, 9623, 2324, -1, 2300, 9617, 2262, -1, 9623, 9617, 2300, -1, 2262, 12039, 2265, -1, 2262, 16533, 12039, -1, 2262, 16549, 16533, -1, 9617, 9616, 2262, -1, 2262, 16552, 16549, -1, 9616, 16553, 2262, -1, 2262, 16553, 16552, -1, 2876, 14808, 2886, -1, 14813, 14808, 2876, -1, 2899, 11628, 3340, -1, 2899, 13763, 11628, -1, 2899, 13761, 13763, -1, 2886, 13764, 2899, -1, 14808, 13764, 2886, -1, 2899, 13762, 13761, -1, 13764, 13766, 2899, -1, 2899, 13766, 13762, -1, 2828, 10041, 2829, -1, 10040, 10041, 2828, -1, 2829, 10047, 2840, -1, 10041, 10047, 2829, -1, 2840, 10046, 2861, -1, 10047, 10046, 2840, -1, 2740, 10036, 2749, -1, 10037, 10036, 2740, -1, 2749, 10035, 2760, -1, 10036, 10035, 2749, -1, 2760, 10040, 2828, -1, 10035, 10040, 2760, -1, 2645, 10017, 2699, -1, 10016, 10017, 2645, -1, 2699, 10023, 2712, -1, 10017, 10023, 2699, -1, 2712, 10022, 2733, -1, 10023, 10022, 2712, -1, 2609, 10012, 2622, -1, 10013, 10012, 2609, -1, 2622, 10011, 2646, -1, 10012, 10011, 2622, -1, 2646, 10016, 2645, -1, 10011, 10016, 2646, -1, 2508, 9993, 2546, -1, 9992, 9993, 2508, -1, 2546, 9999, 2567, -1, 9993, 9999, 2546, -1, 2567, 9998, 2582, -1, 9999, 9998, 2567, -1, 2467, 9988, 2495, -1, 9989, 9988, 2467, -1, 2495, 9987, 2509, -1, 9988, 9987, 2495, -1, 2509, 9992, 2508, -1, 9987, 9992, 2509, -1, 2390, 9956, 2427, -1, 9957, 9956, 2390, -1, 2427, 9963, 2435, -1, 9956, 9963, 2427, -1, 2435, 9962, 2465, -1, 9963, 9962, 2435, -1, 9953, 2364, 2323, -1, 9953, 9952, 2364, -1, 2364, 9951, 2389, -1, 9952, 9951, 2364, -1, 9951, 2390, 2389, -1, 9951, 9957, 2390, -1, 12032, 2302, 2301, -1, 16651, 2302, 12032, -1, 16653, 2302, 16651, -1, 16654, 2302, 16653, -1, 16658, 2302, 16654, -1, 9968, 2302, 16658, -1, 2302, 9967, 2303, -1, 9968, 9967, 2302, -1, 9967, 2322, 2303, -1, 9967, 9975, 2322, -1, 11568, 280, 279, -1, 13594, 280, 11568, -1, 13595, 280, 13594, -1, 13597, 280, 13595, -1, 13598, 280, 13597, -1, 13601, 280, 13598, -1, 280, 14753, 3065, -1, 13601, 14753, 280, -1, 14753, 228, 3065, -1, 14753, 14755, 228, -1, 9501, 3041, 199, -1, 9501, 9500, 3041, -1, 3041, 9499, 3028, -1, 9500, 9499, 3041, -1, 9499, 3029, 3028, -1, 9499, 9517, 3029, -1, 9517, 3021, 3029, -1, 9517, 9511, 3021, -1, 3021, 9495, 3016, -1, 9511, 9495, 3021, -1, 3016, 9497, 3006, -1, 9495, 9497, 3016, -1, 2989, 9558, 2981, -1, 9561, 9558, 2989, -1, 2981, 9560, 2952, -1, 9558, 9560, 2981, -1, 2952, 9577, 2956, -1, 9560, 9577, 2952, -1, 2956, 9571, 2934, -1, 9577, 9571, 2956, -1, 2934, 9555, 2925, -1, 9571, 9555, 2934, -1, 2925, 9557, 2913, -1, 9555, 9557, 2925, -1, 2883, 9582, 2872, -1, 9585, 9582, 2883, -1, 2872, 9584, 2854, -1, 9582, 9584, 2872, -1, 2854, 9601, 2855, -1, 9584, 9601, 2854, -1, 2855, 9595, 2831, -1, 9601, 9595, 2855, -1, 2831, 9579, 2816, -1, 9595, 9579, 2831, -1, 2816, 9581, 2785, -1, 9579, 9581, 2816, -1, 2752, 9534, 2742, -1, 9537, 9534, 2752, -1, 2742, 9536, 2714, -1, 9534, 9536, 2742, -1, 2714, 9553, 2715, -1, 9536, 9553, 2714, -1, 2715, 9547, 2705, -1, 9553, 9547, 2715, -1, 2705, 9531, 2682, -1, 9547, 9531, 2705, -1, 2682, 9533, 2641, -1, 9531, 9533, 2682, -1, 2611, 9524, 2590, -1, 9522, 9524, 2611, -1, 2591, 11979, 3169, -1, 2591, 16496, 11979, -1, 2591, 16512, 16496, -1, 2590, 9530, 2591, -1, 9524, 9530, 2590, -1, 2591, 16515, 16512, -1, 9530, 16516, 2591, -1, 2591, 16516, 16515, -1, 3051, 14741, 3059, -1, 14737, 14741, 3051, -1, 3059, 14735, 3064, -1, 14741, 14735, 3059, -1, 3064, 11555, 3071, -1, 3064, 13568, 11555, -1, 3064, 13566, 13568, -1, 14735, 13569, 3064, -1, 3064, 13567, 13566, -1, 13569, 13571, 3064, -1, 3064, 13571, 13567, -1, 188, 14733, 3039, -1, 14734, 14733, 188, -1, 3039, 14738, 3045, -1, 14733, 14738, 3039, -1, 3045, 14737, 3051, -1, 14738, 14737, 3045, -1, 3000, 9451, 3005, -1, 9448, 9451, 3000, -1, 3005, 9450, 3014, -1, 9451, 9450, 3005, -1, 3014, 9455, 184, -1, 9450, 9455, 3014, -1, 2951, 9438, 2980, -1, 9439, 9438, 2951, -1, 2980, 9442, 2988, -1, 9438, 9442, 2980, -1, 2988, 9448, 3000, -1, 9442, 9448, 2988, -1, 2897, 9482, 2914, -1, 9478, 9482, 2897, -1, 2914, 9476, 2926, -1, 9482, 9476, 2914, -1, 2926, 9475, 2935, -1, 9476, 9475, 2926, -1, 2858, 9472, 2873, -1, 9473, 9472, 2858, -1, 2873, 9479, 2884, -1, 9472, 9479, 2873, -1, 2884, 9478, 2897, -1, 9479, 9478, 2884, -1, 2784, 9417, 2799, -1, 9414, 9417, 2784, -1, 2799, 9416, 2817, -1, 9417, 9416, 2799, -1, 2817, 9421, 2832, -1, 9416, 9421, 2817, -1, 2716, 9404, 2743, -1, 9405, 9404, 2716, -1, 2743, 9408, 2753, -1, 9404, 9408, 2743, -1, 2753, 9414, 2784, -1, 9408, 9414, 2753, -1, 9386, 2657, 2642, -1, 9386, 9390, 2657, -1, 2657, 9384, 2681, -1, 9390, 9384, 2657, -1, 9384, 2704, 2681, -1, 9384, 9383, 2704, -1, 11966, 2594, 2593, -1, 16466, 2594, 11966, -1, 16468, 2594, 16466, -1, 16469, 2594, 16468, -1, 16473, 2594, 16469, -1, 16473, 9381, 2594, -1, 9381, 9380, 2594, -1, 9380, 2612, 2594, -1, 9380, 9387, 2612, -1, 9387, 2642, 2612, -1, 9387, 9386, 2642, -1, 13554, 350, 11540, -1, 13555, 350, 13554, -1, 13557, 350, 13555, -1, 13558, 350, 13557, -1, 11540, 350, 349, -1, 13558, 13561, 350, -1, 13561, 14751, 350, -1, 14751, 373, 350, -1, 14751, 14749, 373, -1, 14749, 374, 373, -1, 14749, 14748, 374, -1, 14748, 3074, 374, -1, 14748, 14747, 3074, -1, 3074, 14744, 3067, -1, 14747, 14744, 3074, -1, 14744, 242, 3067, -1, 14744, 14743, 242, -1, 243, 9466, 3055, -1, 9467, 9466, 243, -1, 3055, 9464, 256, -1, 9466, 9464, 3055, -1, 256, 9462, 211, -1, 9464, 9462, 256, -1, 211, 9458, 3023, -1, 9462, 9458, 211, -1, 3023, 9452, 3024, -1, 9458, 9452, 3023, -1, 3024, 9447, 31, -1, 9452, 9447, 3024, -1, 33, 9493, 45, -1, 9494, 9493, 33, -1, 45, 9491, 46, -1, 9493, 9491, 45, -1, 46, 9490, 24, -1, 9491, 9490, 46, -1, 24, 9489, 2937, -1, 9490, 9489, 24, -1, 2937, 9485, 2938, -1, 9489, 9485, 2937, -1, 2938, 9484, 2928, -1, 9485, 9484, 2938, -1, 2910, 9432, 2909, -1, 9433, 9432, 2910, -1, 2909, 9430, 3344, -1, 9432, 9430, 2909, -1, 3344, 9428, 3317, -1, 9430, 9428, 3344, -1, 3317, 9424, 2838, -1, 9428, 9424, 3317, -1, 2838, 9418, 2824, -1, 9424, 9418, 2838, -1, 2824, 9413, 2803, -1, 9418, 9413, 2824, -1, 2791, 9401, 2792, -1, 9402, 9401, 2791, -1, 2792, 9398, 2789, -1, 9401, 9398, 2792, -1, 2789, 9397, 2765, -1, 9398, 9397, 2789, -1, 2765, 9399, 2707, -1, 9397, 9399, 2765, -1, 2707, 9393, 2689, -1, 9399, 9393, 2707, -1, 2689, 11955, 3217, -1, 2689, 16459, 11955, -1, 2689, 16475, 16459, -1, 9393, 9392, 2689, -1, 2689, 16478, 16475, -1, 9392, 16479, 2689, -1, 2689, 16479, 16478, -1, 356, 14724, 372, -1, 14729, 14724, 356, -1, 3092, 11522, 3093, -1, 3092, 13529, 11522, -1, 3092, 13527, 13529, -1, 372, 13530, 3092, -1, 14724, 13530, 372, -1, 3092, 13528, 13527, -1, 13530, 13532, 3092, -1, 3092, 13532, 13528, -1, 3061, 9344, 3069, -1, 9345, 9344, 3061, -1, 3069, 9351, 3077, -1, 9344, 9351, 3069, -1, 3077, 9350, 357, -1, 9351, 9350, 3077, -1, 234, 9340, 255, -1, 9341, 9340, 234, -1, 255, 9339, 3056, -1, 9340, 9339, 255, -1, 3056, 9345, 3061, -1, 9339, 9345, 3056, -1, 3003, 9369, 3025, -1, 9368, 9369, 3003, -1, 3025, 9375, 212, -1, 9369, 9375, 3025, -1, 212, 9374, 210, -1, 9375, 9374, 212, -1, 23, 9364, 44, -1, 9365, 9364, 23, -1, 44, 9363, 3002, -1, 9364, 9363, 44, -1, 3002, 9368, 3003, -1, 9363, 9368, 3002, -1, 2908, 9321, 2939, -1, 9320, 9321, 2908, -1, 2939, 9327, 2960, -1, 9321, 9327, 2939, -1, 2960, 9326, 25, -1, 9327, 9326, 2960, -1, 3337, 9316, 2906, -1, 9317, 9316, 3337, -1, 2906, 9315, 2907, -1, 9316, 9315, 2906, -1, 2907, 9320, 2908, -1, 9315, 9320, 2907, -1, 2804, 9297, 2823, -1, 9296, 9297, 2804, -1, 2823, 9303, 3316, -1, 9297, 9303, 2823, -1, 3316, 9302, 3329, -1, 9303, 9302, 3316, -1, 9293, 2787, 2763, -1, 9293, 9292, 2787, -1, 2787, 9291, 2788, -1, 9292, 9291, 2787, -1, 9291, 2804, 2788, -1, 9291, 9296, 2804, -1, 11947, 2688, 2686, -1, 16429, 2688, 11947, -1, 16431, 2688, 16429, -1, 16432, 2688, 16431, -1, 16436, 2688, 16432, -1, 9272, 2688, 16436, -1, 2688, 9271, 2764, -1, 9272, 9271, 2688, -1, 9271, 2762, 2764, -1, 9271, 9279, 2762, -1, 11510, 435, 434, -1, 13516, 435, 11510, -1, 13517, 435, 13516, -1, 13519, 435, 13517, -1, 13520, 435, 13519, -1, 13523, 435, 13520, -1, 435, 14725, 442, -1, 13523, 14725, 435, -1, 14725, 412, 442, -1, 14725, 14727, 412, -1, 9337, 364, 402, -1, 9337, 9336, 364, -1, 364, 9335, 340, -1, 9336, 9335, 364, -1, 9335, 341, 340, -1, 9335, 9353, 341, -1, 9353, 328, 341, -1, 9353, 9347, 328, -1, 328, 9331, 329, -1, 9347, 9331, 328, -1, 329, 9333, 306, -1, 9331, 9333, 329, -1, 288, 9358, 261, -1, 9361, 9358, 288, -1, 261, 9360, 262, -1, 9358, 9360, 261, -1, 262, 9377, 3047, -1, 9360, 9377, 262, -1, 3047, 9371, 226, -1, 9377, 9371, 3047, -1, 226, 9355, 227, -1, 9371, 9355, 226, -1, 227, 9357, 154, -1, 9355, 9357, 227, -1, 155, 9310, 67, -1, 9313, 9310, 155, -1, 67, 9312, 68, -1, 9310, 9312, 67, -1, 68, 9329, 2996, -1, 9312, 9329, 68, -1, 2996, 9323, 11, -1, 9329, 9323, 2996, -1, 11, 9307, 2998, -1, 9323, 9307, 11, -1, 2998, 9309, 2983, -1, 9307, 9309, 2998, -1, 2967, 9286, 2968, -1, 9289, 9286, 2967, -1, 2968, 9288, 3333, -1, 9286, 9288, 2968, -1, 3333, 9305, 3334, -1, 9288, 9305, 3333, -1, 3334, 9299, 3330, -1, 9305, 9299, 3334, -1, 3330, 9283, 2894, -1, 9299, 9283, 3330, -1, 2894, 9285, 2870, -1, 9283, 9285, 2894, -1, 2867, 9276, 2769, -1, 9274, 9276, 2867, -1, 2767, 11934, 3262, -1, 2767, 16422, 11934, -1, 2767, 16438, 16422, -1, 2769, 9282, 2767, -1, 9276, 9282, 2769, -1, 2767, 16441, 16438, -1, 9282, 16442, 2767, -1, 2767, 16442, 16441, -1, 3099, 14713, 3101, -1, 14709, 14713, 3099, -1, 3101, 14707, 441, -1, 14713, 14707, 3101, -1, 441, 11493, 446, -1, 441, 13490, 11493, -1, 441, 13488, 13490, -1, 14707, 13491, 441, -1, 441, 13489, 13488, -1, 13491, 13493, 441, -1, 441, 13493, 13489, -1, 363, 14705, 404, -1, 14706, 14705, 363, -1, 404, 14710, 3097, -1, 14705, 14710, 404, -1, 3097, 14709, 3099, -1, 14710, 14709, 3097, -1, 3084, 9227, 3088, -1, 9224, 9227, 3084, -1, 3088, 9226, 327, -1, 9227, 9226, 3088, -1, 327, 9231, 339, -1, 9226, 9231, 327, -1, 260, 9214, 289, -1, 9215, 9214, 260, -1, 289, 9218, 3080, -1, 9214, 9218, 289, -1, 3080, 9224, 3084, -1, 9218, 9224, 3080, -1, 3037, 9166, 3043, -1, 9162, 9166, 3037, -1, 3043, 9160, 225, -1, 9166, 9160, 3043, -1, 225, 9159, 230, -1, 9160, 9159, 225, -1, 66, 9156, 121, -1, 9157, 9156, 66, -1, 121, 9163, 3032, -1, 9156, 9163, 121, -1, 3032, 9162, 3037, -1, 9163, 9162, 3032, -1, 2984, 9193, 2986, -1, 9190, 9193, 2984, -1, 2986, 9192, 12, -1, 9193, 9192, 2986, -1, 12, 9197, 10, -1, 9192, 9197, 12, -1, 3345, 9180, 2969, -1, 9181, 9180, 3345, -1, 2969, 9184, 2970, -1, 9180, 9184, 2969, -1, 2970, 9190, 2984, -1, 9184, 9190, 2970, -1, 9254, 2880, 2869, -1, 9254, 9258, 2880, -1, 2880, 9252, 2895, -1, 9258, 9252, 2880, -1, 9252, 3332, 2895, -1, 9252, 9251, 3332, -1, 11926, 3290, 3291, -1, 16392, 3290, 11926, -1, 16394, 3290, 16392, -1, 16395, 3290, 16394, -1, 16399, 3290, 16395, -1, 16399, 9249, 3290, -1, 9249, 9248, 3290, -1, 9248, 2868, 3290, -1, 9248, 9255, 2868, -1, 9255, 2869, 2868, -1, 9255, 9254, 2869, -1, 13477, 3396, 11482, -1, 13478, 3396, 13477, -1, 13480, 3396, 13478, -1, 13481, 3396, 13480, -1, 11482, 3396, 3395, -1, 13481, 13484, 3396, -1, 13484, 14723, 3396, -1, 14723, 3398, 3396, -1, 14723, 14721, 3398, -1, 14721, 448, 3398, -1, 14721, 14720, 448, -1, 14720, 444, 448, -1, 14720, 14719, 444, -1, 444, 14716, 430, -1, 14719, 14716, 444, -1, 14716, 419, 430, -1, 14716, 14715, 419, -1, 422, 9242, 408, -1, 9243, 9242, 422, -1, 408, 9240, 409, -1, 9242, 9240, 408, -1, 409, 9238, 392, -1, 9240, 9238, 409, -1, 392, 9234, 342, -1, 9238, 9234, 392, -1, 342, 9228, 322, -1, 9234, 9228, 342, -1, 322, 9223, 317, -1, 9228, 9223, 322, -1, 314, 9177, 300, -1, 9178, 9177, 314, -1, 300, 9174, 301, -1, 9177, 9174, 300, -1, 301, 9173, 281, -1, 9174, 9173, 301, -1, 281, 9175, 250, -1, 9173, 9175, 281, -1, 250, 9169, 202, -1, 9175, 9169, 250, -1, 202, 9168, 201, -1, 9169, 9168, 202, -1, 180, 9208, 146, -1, 9209, 9208, 180, -1, 146, 9206, 147, -1, 9208, 9206, 146, -1, 147, 9204, 104, -1, 9206, 9204, 147, -1, 104, 9200, 38, -1, 9204, 9200, 104, -1, 38, 9194, 19, -1, 9200, 9194, 38, -1, 19, 9189, 3385, -1, 9194, 9189, 19, -1, 3373, 9269, 3367, -1, 9270, 9269, 3373, -1, 3367, 9266, 3368, -1, 9269, 9266, 3367, -1, 3368, 9265, 7, -1, 9266, 9265, 3368, -1, 7, 9267, 5, -1, 9265, 9267, 7, -1, 5, 9261, 0, -1, 9267, 9261, 5, -1, 0, 11913, 3, -1, 0, 16385, 11913, -1, 0, 16401, 16385, -1, 9261, 9260, 0, -1, 0, 16404, 16401, -1, 9260, 16405, 0, -1, 0, 16405, 16404, -1, 19173, 10501, 19244, -1, 10506, 10501, 19173, -1, 19276, 11463, 11457, -1, 19276, 13939, 11463, -1, 19276, 13937, 13939, -1, 19244, 10500, 19276, -1, 10501, 10500, 19244, -1, 19276, 13938, 13937, -1, 10500, 13941, 19276, -1, 19276, 13941, 13938, -1, 427, 10524, 18855, -1, 10525, 10524, 427, -1, 18855, 10531, 18951, -1, 10524, 10531, 18855, -1, 18951, 10530, 19069, -1, 10531, 10530, 18951, -1, 18676, 10520, 18694, -1, 10521, 10520, 18676, -1, 18694, 10519, 18702, -1, 10520, 10519, 18694, -1, 18702, 10525, 427, -1, 10519, 10525, 18702, -1, 316, 10596, 18599, -1, 10597, 10596, 316, -1, 18599, 10603, 18612, -1, 10596, 10603, 18599, -1, 18612, 10602, 18649, -1, 10603, 10602, 18612, -1, 18554, 10592, 18561, -1, 10593, 10592, 18554, -1, 18561, 10591, 18571, -1, 10592, 10591, 18561, -1, 18571, 10597, 316, -1, 10591, 10597, 18571, -1, 200, 10573, 18493, -1, 10572, 10573, 200, -1, 18493, 10579, 18506, -1, 10573, 10579, 18493, -1, 18506, 10578, 18535, -1, 10579, 10578, 18506, -1, 18446, 10568, 18451, -1, 10569, 10568, 18446, -1, 18451, 10567, 18464, -1, 10568, 10567, 18451, -1, 18464, 10572, 200, -1, 10567, 10572, 18464, -1, 20, 10549, 18417, -1, 10548, 10549, 20, -1, 18417, 10555, 18426, -1, 10549, 10555, 18417, -1, 18426, 10554, 18439, -1, 10555, 10554, 18426, -1, 10545, 18393, 18387, -1, 10545, 10544, 18393, -1, 18393, 10543, 18397, -1, 10544, 10543, 18393, -1, 10543, 20, 18397, -1, 10543, 10548, 20, -1, 11898, 18365, 11897, -1, 16836, 18365, 11898, -1, 16838, 18365, 16836, -1, 16839, 18365, 16838, -1, 16843, 18365, 16839, -1, 14889, 18365, 16843, -1, 18365, 14888, 18372, -1, 14889, 14888, 18365, -1, 14888, 18383, 18372, -1, 14888, 14896, 18383, -1, 11484, 1941, 1940, -1, 13437, 1941, 11484, -1, 13438, 1941, 13437, -1, 13440, 1941, 13438, -1, 13441, 1941, 13440, -1, 13444, 1941, 13441, -1, 1941, 14697, 1974, -1, 13444, 14697, 1941, -1, 14697, 1763, 1974, -1, 14697, 14699, 1763, -1, 11085, 1674, 1651, -1, 11085, 11084, 1674, -1, 1674, 11083, 2103, -1, 11084, 11083, 1674, -1, 11083, 2089, 2103, -1, 11083, 11101, 2089, -1, 11101, 2074, 2089, -1, 11101, 11095, 2074, -1, 2074, 11079, 1237, -1, 11095, 11079, 2074, -1, 1237, 11081, 1005, -1, 11079, 11081, 1237, -1, 917, 11058, 922, -1, 11061, 11058, 917, -1, 922, 11060, 2007, -1, 11058, 11060, 922, -1, 2007, 11077, 1995, -1, 11060, 11077, 2007, -1, 1995, 11071, 1996, -1, 11077, 11071, 1995, -1, 1996, 11055, 538, -1, 11071, 11055, 1996, -1, 538, 11057, 396, -1, 11055, 11057, 538, -1, 351, 11142, 360, -1, 11145, 11142, 351, -1, 360, 11144, 1921, -1, 11142, 11144, 360, -1, 1921, 11161, 1898, -1, 11144, 11161, 1921, -1, 1898, 11155, 1899, -1, 11161, 11155, 1898, -1, 1899, 11139, 253, -1, 11155, 11139, 1899, -1, 253, 11141, 157, -1, 11139, 11141, 253, -1, 118, 11118, 119, -1, 11121, 11118, 118, -1, 119, 11120, 1827, -1, 11118, 11120, 119, -1, 1827, 11137, 1808, -1, 11120, 11137, 1827, -1, 1808, 11131, 1791, -1, 11137, 11131, 1808, -1, 1791, 11115, 1792, -1, 11131, 11115, 1791, -1, 1792, 11117, 3358, -1, 11115, 11117, 1792, -1, 1718, 11108, 1701, -1, 11106, 11108, 1718, -1, 1699, 11821, 3314, -1, 1699, 16348, 11821, -1, 1699, 16364, 16348, -1, 1701, 11114, 1699, -1, 11108, 11114, 1701, -1, 1699, 16367, 16364, -1, 11114, 16368, 1699, -1, 1699, 16368, 16367, -1, 1910, 14685, 1973, -1, 14681, 14685, 1910, -1, 1973, 14679, 2008, -1, 14685, 14679, 1973, -1, 2008, 11500, 2173, -1, 2008, 13412, 11500, -1, 2008, 13410, 13412, -1, 14679, 13413, 2008, -1, 2008, 13411, 13410, -1, 13413, 13415, 2008, -1, 2008, 13415, 13411, -1, 1561, 14677, 1673, -1, 14678, 14677, 1561, -1, 1673, 14682, 1800, -1, 14677, 14682, 1673, -1, 1800, 14681, 1910, -1, 14682, 14681, 1800, -1, 1164, 9111, 1236, -1, 9108, 9111, 1164, -1, 1236, 9110, 1277, -1, 9111, 9110, 1236, -1, 1277, 9115, 1555, -1, 9110, 9115, 1277, -1, 2006, 9098, 921, -1, 9099, 9098, 2006, -1, 921, 9102, 1049, -1, 9098, 9102, 921, -1, 1049, 9108, 1164, -1, 9102, 9108, 1049, -1, 470, 9142, 537, -1, 9138, 9142, 470, -1, 537, 9136, 569, -1, 9142, 9136, 537, -1, 569, 9135, 1997, -1, 9136, 9135, 569, -1, 1920, 9132, 359, -1, 9133, 9132, 1920, -1, 359, 9139, 410, -1, 9132, 9139, 359, -1, 410, 9138, 470, -1, 9139, 9138, 410, -1, 224, 9053, 252, -1, 9050, 9053, 224, -1, 252, 9052, 263, -1, 9053, 9052, 252, -1, 263, 9057, 1897, -1, 9052, 9057, 263, -1, 27, 9040, 117, -1, 9041, 9040, 27, -1, 117, 9044, 176, -1, 9040, 9044, 117, -1, 176, 9050, 224, -1, 9044, 9050, 176, -1, 9080, 3389, 3378, -1, 9080, 9084, 3389, -1, 3389, 9078, 1793, -1, 9084, 9078, 3389, -1, 9078, 28, 1793, -1, 9078, 9077, 28, -1, 11807, 1704, 1703, -1, 16318, 1704, 11807, -1, 16320, 1704, 16318, -1, 16321, 1704, 16320, -1, 16325, 1704, 16321, -1, 16325, 9075, 1704, -1, 9075, 9074, 1704, -1, 9074, 3357, 1704, -1, 9074, 9081, 3357, -1, 9081, 3378, 3357, -1, 9081, 9080, 3378, -1, 13398, 2289, 11513, -1, 13399, 2289, 13398, -1, 13401, 2289, 13399, -1, 13402, 2289, 13401, -1, 11513, 2289, 2337, -1, 13402, 13405, 2289, -1, 13405, 14695, 2289, -1, 14695, 2247, 2289, -1, 14695, 14693, 2247, -1, 14693, 2229, 2247, -1, 14693, 14692, 2229, -1, 14692, 2204, 2229, -1, 14692, 14691, 2204, -1, 2204, 14688, 1918, -1, 14691, 14688, 2204, -1, 14688, 1805, 1918, -1, 14688, 14687, 1805, -1, 1806, 9126, 1901, -1, 9127, 9126, 1806, -1, 1901, 9124, 2151, -1, 9126, 9124, 1901, -1, 2151, 9122, 2145, -1, 9124, 9122, 2151, -1, 2145, 9118, 1414, -1, 9122, 9118, 2145, -1, 1414, 9112, 1224, -1, 9118, 9112, 1414, -1, 1224, 9107, 1225, -1, 9112, 9107, 1224, -1, 1210, 9153, 1207, -1, 9154, 9153, 1210, -1, 1207, 9151, 2058, -1, 9153, 9151, 1207, -1, 2058, 9150, 2049, -1, 9151, 9150, 2058, -1, 2049, 9149, 708, -1, 9150, 9149, 2049, -1, 708, 9145, 512, -1, 9149, 9145, 708, -1, 512, 9144, 513, -1, 9145, 9144, 512, -1, 511, 9068, 507, -1, 9069, 9068, 511, -1, 507, 9066, 1980, -1, 9068, 9066, 507, -1, 1980, 9064, 1972, -1, 9066, 9064, 1980, -1, 1972, 9060, 1933, -1, 9064, 9060, 1972, -1, 1933, 9054, 239, -1, 9060, 9054, 1933, -1, 239, 9049, 186, -1, 9054, 9049, 239, -1, 152, 9095, 237, -1, 9096, 9095, 152, -1, 237, 9092, 1870, -1, 9095, 9092, 237, -1, 1870, 9091, 1861, -1, 9092, 9091, 1870, -1, 1861, 9093, 1846, -1, 9091, 9093, 1861, -1, 1846, 9087, 1844, -1, 9093, 9087, 1846, -1, 1844, 11794, 3372, -1, 1844, 16311, 11794, -1, 1844, 16327, 16311, -1, 9087, 9086, 1844, -1, 1844, 16330, 16327, -1, 9086, 16331, 1844, -1, 1844, 16331, 16330, -1, 2246, 14640, 2261, -1, 14645, 14640, 2246, -1, 2288, 11528, 2493, -1, 2288, 13295, 11528, -1, 2288, 13293, 13295, -1, 2261, 13296, 2288, -1, 14640, 13296, 2261, -1, 2288, 13294, 13293, -1, 13296, 13298, 2288, -1, 2288, 13298, 13294, -1, 1900, 8805, 2203, -1, 8804, 8805, 1900, -1, 2203, 8811, 2215, -1, 8805, 8811, 2203, -1, 2215, 8810, 2228, -1, 8811, 8810, 2215, -1, 1829, 8800, 2157, -1, 8801, 8800, 1829, -1, 2157, 8799, 1906, -1, 8800, 8799, 2157, -1, 1906, 8804, 1900, -1, 8799, 8804, 1906, -1, 1206, 8756, 1413, -1, 8757, 8756, 1206, -1, 1413, 8763, 2135, -1, 8756, 8763, 1413, -1, 2135, 8762, 1830, -1, 8763, 8762, 2135, -1, 1190, 8752, 2066, -1, 8753, 8752, 1190, -1, 2066, 8751, 1208, -1, 8752, 8751, 2066, -1, 1208, 8757, 1206, -1, 8751, 8757, 1208, -1, 506, 8781, 707, -1, 8780, 8781, 506, -1, 707, 8787, 2042, -1, 8781, 8787, 707, -1, 2042, 8786, 1187, -1, 8787, 8786, 2042, -1, 497, 8776, 1989, -1, 8777, 8776, 497, -1, 1989, 8775, 508, -1, 8776, 8775, 1989, -1, 508, 8780, 506, -1, 8775, 8780, 508, -1, 236, 8733, 1934, -1, 8732, 8733, 236, -1, 1934, 8739, 1943, -1, 8733, 8739, 1934, -1, 1943, 8738, 498, -1, 8739, 8738, 1943, -1, 8729, 1883, 220, -1, 8729, 8728, 1883, -1, 1883, 8727, 238, -1, 8728, 8727, 1883, -1, 8727, 236, 238, -1, 8727, 8732, 236, -1, 11784, 1845, 3376, -1, 16207, 1845, 11784, -1, 16209, 1845, 16207, -1, 16210, 1845, 16209, -1, 16214, 1845, 16210, -1, 8708, 1845, 16214, -1, 1845, 8707, 1847, -1, 8708, 8707, 1845, -1, 8707, 221, 1847, -1, 8707, 8715, 221, -1, 11598, 2599, 3181, -1, 13360, 2599, 11598, -1, 13361, 2599, 13360, -1, 13363, 2599, 13361, -1, 13364, 2599, 13363, -1, 13367, 2599, 13364, -1, 2599, 14669, 2569, -1, 13367, 14669, 2599, -1, 14669, 2551, 2569, -1, 14669, 14671, 2551, -1, 8937, 2519, 2520, -1, 8937, 8936, 2519, -1, 2519, 8935, 3122, -1, 8936, 8935, 2519, -1, 8935, 3123, 3122, -1, 8935, 8953, 3123, -1, 8953, 2451, 3123, -1, 8953, 8947, 2451, -1, 2451, 8931, 2433, -1, 8947, 8931, 2451, -1, 2433, 8933, 2423, -1, 8931, 8933, 2433, -1, 2400, 8958, 2397, -1, 8961, 8958, 2400, -1, 2397, 8960, 2310, -1, 8958, 8960, 2397, -1, 2310, 8977, 2311, -1, 8960, 8977, 2310, -1, 2311, 8971, 2308, -1, 8977, 8971, 2311, -1, 2308, 8955, 2314, -1, 8971, 8955, 2308, -1, 2314, 8957, 2298, -1, 8955, 8957, 2314, -1, 2259, 8982, 2159, -1, 8985, 8982, 2259, -1, 2159, 8984, 2160, -1, 8982, 8984, 2159, -1, 2160, 9001, 2195, -1, 8984, 9001, 2160, -1, 2195, 8995, 2076, -1, 9001, 8995, 2195, -1, 2076, 8979, 2077, -1, 8995, 8979, 2076, -1, 2077, 8981, 1885, -1, 8979, 8981, 2077, -1, 1886, 9006, 1608, -1, 9009, 9006, 1886, -1, 1608, 9008, 1497, -1, 9006, 9008, 1608, -1, 1497, 9025, 1498, -1, 9008, 9025, 1497, -1, 1498, 9019, 1499, -1, 9025, 9019, 1498, -1, 1499, 9003, 2106, -1, 9019, 9003, 1499, -1, 2106, 9005, 1151, -1, 9003, 9005, 2106, -1, 1152, 9032, 837, -1, 9030, 9032, 1152, -1, 663, 11706, 664, -1, 663, 16274, 11706, -1, 663, 16290, 16274, -1, 837, 9038, 663, -1, 9032, 9038, 837, -1, 663, 16293, 16290, -1, 9038, 16294, 663, -1, 663, 16294, 16293, -1, 2534, 14657, 2550, -1, 14653, 14657, 2534, -1, 2550, 14651, 2596, -1, 14657, 14651, 2550, -1, 2596, 11609, 2597, -1, 2596, 13334, 11609, -1, 2596, 13332, 13334, -1, 14651, 13335, 2596, -1, 2596, 13333, 13332, -1, 13335, 13337, 2596, -1, 2596, 13337, 13333, -1, 2516, 14649, 2517, -1, 14650, 14649, 2516, -1, 2517, 14654, 2518, -1, 14649, 14654, 2517, -1, 2518, 14653, 2534, -1, 14654, 14653, 2518, -1, 2417, 8829, 2424, -1, 8826, 8829, 2417, -1, 2424, 8828, 2432, -1, 8829, 8828, 2424, -1, 2432, 8833, 2450, -1, 8828, 8833, 2432, -1, 2352, 8816, 2398, -1, 8817, 8816, 2352, -1, 2398, 8820, 2399, -1, 8816, 8820, 2398, -1, 2399, 8826, 2417, -1, 8820, 8826, 2399, -1, 2280, 8884, 2297, -1, 8880, 8884, 2280, -1, 2297, 8878, 2313, -1, 8884, 8878, 2297, -1, 2313, 8877, 2309, -1, 8878, 8877, 2313, -1, 2158, 8874, 2257, -1, 8875, 8874, 2158, -1, 2257, 8881, 2258, -1, 8874, 8881, 2257, -1, 2258, 8880, 2280, -1, 8881, 8880, 2258, -1, 2180, 8911, 2185, -1, 8908, 8911, 2180, -1, 2185, 8910, 2075, -1, 8911, 8910, 2185, -1, 2075, 8915, 2104, -1, 8910, 8915, 2075, -1, 1607, 8898, 2162, -1, 8899, 8898, 1607, -1, 2162, 8902, 2163, -1, 8898, 8902, 2162, -1, 2163, 8908, 2180, -1, 8902, 8908, 2163, -1, 8856, 2091, 2079, -1, 8856, 8860, 2091, -1, 2091, 8854, 2107, -1, 8860, 8854, 2091, -1, 8854, 1496, 2107, -1, 8854, 8853, 1496, -1, 11697, 968, 969, -1, 16244, 968, 11697, -1, 16246, 968, 16244, -1, 16247, 968, 16246, -1, 16251, 968, 16247, -1, 16251, 8851, 968, -1, 8851, 8850, 968, -1, 8850, 2061, 968, -1, 8850, 8857, 2061, -1, 8857, 2079, 2061, -1, 8857, 8856, 2079, -1, 13320, 2694, 11624, -1, 13321, 2694, 13320, -1, 13323, 2694, 13321, -1, 13324, 2694, 13323, -1, 11624, 2694, 3224, -1, 13324, 13327, 2694, -1, 13327, 14667, 2694, -1, 14667, 2661, 2694, -1, 14667, 14665, 2661, -1, 14665, 2614, 2661, -1, 14665, 14664, 2614, -1, 14664, 2601, 2614, -1, 14664, 14663, 2601, -1, 2601, 14660, 2571, -1, 14663, 14660, 2601, -1, 14660, 2572, 2571, -1, 14660, 14659, 2572, -1, 2537, 8844, 2528, -1, 8845, 8844, 2537, -1, 2528, 8842, 2529, -1, 8844, 8842, 2528, -1, 2529, 8840, 2482, -1, 8842, 8840, 2529, -1, 2482, 8836, 2462, -1, 8840, 8836, 2482, -1, 2462, 8830, 2463, -1, 8836, 8830, 2462, -1, 2463, 8825, 2405, -1, 8830, 8825, 2463, -1, 2404, 8895, 2409, -1, 8896, 8895, 2404, -1, 2409, 8892, 2407, -1, 8895, 8892, 2409, -1, 2407, 8891, 2355, -1, 8892, 8891, 2407, -1, 2355, 8893, 2327, -1, 8891, 8893, 2355, -1, 2327, 8887, 2328, -1, 8893, 8887, 2327, -1, 2328, 8886, 2269, -1, 8887, 8886, 2328, -1, 2268, 8926, 2276, -1, 8927, 8926, 2268, -1, 2276, 8924, 2277, -1, 8926, 8924, 2276, -1, 2277, 8922, 2222, -1, 8924, 8922, 2277, -1, 2222, 8918, 2213, -1, 8922, 8918, 2222, -1, 2213, 8912, 2200, -1, 8918, 8912, 2213, -1, 2200, 8907, 1938, -1, 8912, 8907, 2200, -1, 1871, 8871, 2165, -1, 8872, 8871, 1871, -1, 2165, 8868, 2166, -1, 8871, 8868, 2165, -1, 2166, 8867, 1727, -1, 8868, 8867, 2166, -1, 1727, 8869, 1728, -1, 8867, 8869, 1727, -1, 1728, 8863, 1301, -1, 8869, 8863, 1728, -1, 1301, 11677, 1302, -1, 1301, 16237, 11677, -1, 1301, 16253, 16237, -1, 8863, 8862, 1301, -1, 1301, 16256, 16253, -1, 8862, 16257, 1301, -1, 1301, 16257, 16256, -1, 3222, 14780, 2662, -1, 14785, 14780, 3222, -1, 2691, 11631, 2692, -1, 2691, 13685, 11631, -1, 2691, 13683, 13685, -1, 2662, 13686, 2691, -1, 14780, 13686, 2662, -1, 2691, 13684, 13683, -1, 13686, 13688, 2691, -1, 2691, 13688, 13684, -1, 2553, 9792, 2573, -1, 9793, 9792, 2553, -1, 2573, 9799, 2615, -1, 9792, 9799, 2573, -1, 2615, 9798, 3214, -1, 9799, 9798, 2615, -1, 3166, 9788, 2530, -1, 9789, 9788, 3166, -1, 2530, 9787, 2536, -1, 9788, 9787, 2530, -1, 2536, 9793, 2553, -1, 9787, 9793, 2536, -1, 2420, 9817, 2461, -1, 9816, 9817, 2420, -1, 2461, 9823, 2481, -1, 9817, 9823, 2461, -1, 2481, 9822, 3158, -1, 9823, 9822, 2481, -1, 3095, 9812, 2408, -1, 9813, 9812, 3095, -1, 2408, 9811, 2419, -1, 9812, 9811, 2408, -1, 2419, 9816, 2420, -1, 9811, 9816, 2419, -1, 2295, 9732, 2329, -1, 9733, 9732, 2295, -1, 2329, 9739, 2356, -1, 9732, 9739, 2329, -1, 2356, 9738, 3049, -1, 9739, 9738, 2356, -1, 2470, 9728, 2278, -1, 9729, 9728, 2470, -1, 2278, 9727, 2294, -1, 9728, 9727, 2278, -1, 2294, 9733, 2295, -1, 9727, 9733, 2294, -1, 2189, 9756, 2201, -1, 9757, 9756, 2189, -1, 2201, 9763, 2223, -1, 9756, 9763, 2201, -1, 2223, 9762, 2383, -1, 9763, 9762, 2223, -1, 9753, 1984, 1929, -1, 9753, 9752, 1984, -1, 1984, 9751, 2183, -1, 9752, 9751, 1984, -1, 9751, 2189, 2183, -1, 9751, 9757, 2189, -1, 11670, 2112, 2111, -1, 16577, 2112, 11670, -1, 16579, 2112, 16577, -1, 16580, 2112, 16579, -1, 16584, 2112, 16580, -1, 9768, 2112, 16584, -1, 2112, 9767, 1729, -1, 9768, 9767, 2112, -1, 9767, 1858, 1729, -1, 9767, 9775, 1858, -1, 11543, 2376, 2918, -1, 13282, 2376, 11543, -1, 13283, 2376, 13282, -1, 13285, 2376, 13283, -1, 13286, 2376, 13285, -1, 13289, 2376, 13286, -1, 2376, 14641, 2359, -1, 13289, 14641, 2376, -1, 14641, 2335, 2359, -1, 14641, 14643, 2335, -1, 8797, 2292, 2306, -1, 8797, 8796, 2292, -1, 2292, 8795, 2273, -1, 8796, 8795, 2292, -1, 8795, 2250, 2273, -1, 8795, 8813, 2250, -1, 8813, 2232, 2250, -1, 8813, 8807, 2232, -1, 2232, 8791, 2220, -1, 8807, 8791, 2232, -1, 2220, 8793, 2071, -1, 8791, 8793, 2220, -1, 2016, 8746, 2177, -1, 8749, 8746, 2016, -1, 2177, 8748, 2154, -1, 8746, 8748, 2177, -1, 2154, 8765, 2155, -1, 8748, 8765, 2154, -1, 2155, 8759, 2147, -1, 8765, 8759, 2155, -1, 2147, 8743, 2140, -1, 8759, 8743, 2147, -1, 2140, 8745, 1466, -1, 8743, 8745, 2140, -1, 1370, 8770, 2082, -1, 8773, 8770, 1370, -1, 2082, 8772, 2069, -1, 8770, 8772, 2082, -1, 2069, 8789, 2070, -1, 8772, 8789, 2069, -1, 2070, 8783, 2056, -1, 8789, 8783, 2070, -1, 2056, 8767, 2045, -1, 8783, 8767, 2056, -1, 2045, 8769, 737, -1, 8767, 8769, 2045, -1, 742, 8722, 2002, -1, 8725, 8722, 742, -1, 2002, 8724, 1993, -1, 8722, 8724, 2002, -1, 1993, 8741, 1986, -1, 8724, 8741, 1993, -1, 1986, 8735, 1976, -1, 8741, 8735, 1986, -1, 1976, 8719, 1951, -1, 8735, 8719, 1976, -1, 1951, 8721, 290, -1, 8719, 8721, 1951, -1, 291, 8712, 1888, -1, 8710, 8712, 291, -1, 123, 11767, 124, -1, 123, 16200, 11767, -1, 123, 16216, 16200, -1, 1888, 8718, 123, -1, 8712, 8718, 1888, -1, 123, 16219, 16216, -1, 8718, 16220, 123, -1, 123, 16220, 16219, -1, 2338, 14629, 2339, -1, 14625, 14629, 2338, -1, 2339, 14623, 2358, -1, 14629, 14623, 2339, -1, 2358, 11558, 2374, -1, 2358, 13256, 11558, -1, 2358, 13254, 13256, -1, 14623, 13257, 2358, -1, 2358, 13255, 13254, -1, 13257, 13259, 2358, -1, 2358, 13259, 13255, -1, 2272, 14621, 2291, -1, 14622, 14621, 2272, -1, 2291, 14626, 2305, -1, 14621, 14626, 2291, -1, 2305, 14625, 2338, -1, 14626, 14625, 2305, -1, 2207, 8605, 2209, -1, 8602, 8605, 2207, -1, 2209, 8604, 2219, -1, 8605, 8604, 2209, -1, 2219, 8609, 2231, -1, 8604, 8609, 2219, -1, 1955, 8592, 2178, -1, 8593, 8592, 1955, -1, 2178, 8596, 2187, -1, 8592, 8596, 2178, -1, 2187, 8602, 2207, -1, 8596, 8602, 2187, -1, 2130, 8636, 2131, -1, 8632, 8636, 2130, -1, 2131, 8630, 2141, -1, 8636, 8630, 2131, -1, 2141, 8629, 1956, -1, 8630, 8629, 2141, -1, 1182, 8626, 2084, -1, 8627, 8626, 1182, -1, 2084, 8633, 2093, -1, 8626, 8633, 2084, -1, 2093, 8632, 2130, -1, 8633, 8632, 2093, -1, 2032, 8663, 2033, -1, 8660, 8663, 2032, -1, 2033, 8662, 2047, -1, 8663, 8662, 2033, -1, 2047, 8667, 1183, -1, 8662, 8667, 2047, -1, 459, 8650, 2001, -1, 8651, 8650, 459, -1, 2001, 8654, 2013, -1, 8650, 8654, 2001, -1, 2013, 8660, 2032, -1, 8654, 8660, 2013, -1, 8690, 1936, 1925, -1, 8690, 8694, 1936, -1, 1936, 8688, 1950, -1, 8694, 8688, 1936, -1, 8688, 460, 1950, -1, 8688, 8687, 460, -1, 11755, 1890, 1889, -1, 16170, 1890, 11755, -1, 16172, 1890, 16170, -1, 16173, 1890, 16172, -1, 16177, 1890, 16173, -1, 16177, 8685, 1890, -1, 8685, 8684, 1890, -1, 8684, 1907, 1890, -1, 8684, 8691, 1907, -1, 8691, 1925, 1907, -1, 8691, 8690, 1925, -1, 13243, 3132, 11572, -1, 13244, 3132, 13243, -1, 13246, 3132, 13244, -1, 13247, 3132, 13246, -1, 11572, 3132, 3131, -1, 13247, 13250, 3132, -1, 13250, 14639, 3132, -1, 14639, 2475, 3132, -1, 14639, 14637, 2475, -1, 14637, 2446, 2475, -1, 14637, 14636, 2446, -1, 14636, 2385, 2446, -1, 14636, 14635, 2385, -1, 2385, 14632, 2362, -1, 14635, 14632, 2385, -1, 14632, 2361, 2362, -1, 14632, 14631, 2361, -1, 2342, 8620, 2343, -1, 8621, 8620, 2342, -1, 2343, 8618, 2332, -1, 8620, 8618, 2343, -1, 2332, 8616, 2319, -1, 8618, 8616, 2332, -1, 2319, 8612, 2236, -1, 8616, 8612, 2319, -1, 2236, 8606, 2237, -1, 8612, 8606, 2236, -1, 2237, 8601, 2115, -1, 8606, 8601, 2237, -1, 2121, 8647, 2137, -1, 8648, 8647, 2121, -1, 2137, 8644, 2138, -1, 8647, 8644, 2137, -1, 2138, 8643, 1978, -1, 8644, 8643, 2138, -1, 1978, 8645, 1966, -1, 8643, 8645, 1978, -1, 1966, 8639, 2149, -1, 8645, 8639, 1966, -1, 2149, 8638, 1547, -1, 8639, 8638, 2149, -1, 1440, 8678, 1590, -1, 8679, 8678, 1440, -1, 1590, 8676, 1591, -1, 8678, 8676, 1590, -1, 1591, 8674, 1294, -1, 8676, 8674, 1591, -1, 1294, 8670, 1287, -1, 8674, 8670, 1294, -1, 1287, 8664, 2051, -1, 8670, 8664, 1287, -1, 2051, 8659, 815, -1, 8664, 8659, 2051, -1, 713, 8705, 861, -1, 8706, 8705, 713, -1, 861, 8702, 862, -1, 8705, 8702, 861, -1, 862, 8701, 555, -1, 8702, 8701, 862, -1, 555, 8703, 551, -1, 8701, 8703, 555, -1, 551, 8697, 324, -1, 8703, 8697, 551, -1, 324, 11737, 325, -1, 324, 16163, 11737, -1, 324, 16179, 16163, -1, 8697, 8696, 324, -1, 324, 16182, 16179, -1, 8696, 16183, 324, -1, 324, 16183, 16182, -1, 2473, 14668, 2474, -1, 14673, 14668, 2473, -1, 3140, 11583, 3143, -1, 3140, 13373, 11583, -1, 3140, 13371, 13373, -1, 2474, 13374, 3140, -1, 14668, 13374, 2474, -1, 3140, 13372, 13371, -1, 13374, 13376, 3140, -1, 3140, 13376, 13372, -1, 2346, 8944, 2386, -1, 8945, 8944, 2346, -1, 2386, 8951, 2447, -1, 8944, 8951, 2386, -1, 2447, 8950, 2448, -1, 8951, 8950, 2447, -1, 2333, 8940, 2331, -1, 8941, 8940, 2333, -1, 2331, 8939, 2345, -1, 8940, 8939, 2331, -1, 2345, 8945, 2346, -1, 8939, 8945, 2345, -1, 2217, 8968, 2239, -1, 8969, 8968, 2217, -1, 2239, 8975, 2317, -1, 8968, 8975, 2239, -1, 2317, 8974, 2318, -1, 8975, 8974, 2317, -1, 2128, 8964, 2136, -1, 8965, 8964, 2128, -1, 2136, 8963, 2175, -1, 8964, 8963, 2136, -1, 2175, 8969, 2217, -1, 8963, 8969, 2175, -1, 2143, 8992, 1967, -1, 8993, 8992, 2143, -1, 1967, 8999, 1965, -1, 8992, 8999, 1967, -1, 1965, 8998, 2129, -1, 8999, 8998, 1965, -1, 1661, 8988, 1589, -1, 8989, 8988, 1661, -1, 1589, 8987, 1631, -1, 8988, 8987, 1589, -1, 1631, 8993, 2143, -1, 8987, 8993, 1631, -1, 2035, 9016, 1288, -1, 9017, 9016, 2035, -1, 1288, 9023, 1286, -1, 9016, 9023, 1288, -1, 1286, 9022, 1657, -1, 9023, 9022, 1286, -1, 9013, 860, 930, -1, 9013, 9012, 860, -1, 860, 9011, 903, -1, 9012, 9011, 860, -1, 9011, 2035, 903, -1, 9011, 9017, 2035, -1, 11723, 552, 1958, -1, 16281, 552, 11723, -1, 16283, 552, 16281, -1, 16284, 552, 16283, -1, 16288, 552, 16284, -1, 9028, 552, 16288, -1, 552, 9027, 550, -1, 9028, 9027, 552, -1, 9027, 926, 550, -1, 9027, 9035, 926, -1, 11372, 18579, 11370, -1, 13205, 18579, 11372, -1, 13206, 18579, 13205, -1, 13208, 18579, 13206, -1, 13209, 18579, 13208, -1, 8566, 18579, 13209, -1, 18579, 8558, 21189, -1, 8566, 8558, 18579, -1, 8558, 18534, 21189, -1, 8558, 8560, 18534, -1, 8573, 21164, 18505, -1, 8573, 8572, 21164, -1, 21164, 8571, 21153, -1, 8572, 8571, 21164, -1, 8571, 21154, 21153, -1, 8571, 8589, 21154, -1, 8589, 21146, 21154, -1, 8589, 8583, 21146, -1, 21146, 8567, 21140, -1, 8583, 8567, 21146, -1, 21140, 8569, 21131, -1, 8567, 8569, 21140, -1, 21115, 8486, 21107, -1, 8489, 8486, 21115, -1, 21107, 8488, 21082, -1, 8486, 8488, 21107, -1, 21082, 8505, 21083, -1, 8488, 8505, 21082, -1, 21083, 8499, 21064, -1, 8505, 8499, 21083, -1, 21064, 8483, 21055, -1, 8499, 8483, 21064, -1, 21055, 8485, 21044, -1, 8483, 8485, 21055, -1, 21015, 8510, 21005, -1, 8513, 8510, 21015, -1, 21005, 8512, 20988, -1, 8510, 8512, 21005, -1, 20988, 8529, 20989, -1, 8512, 8529, 20988, -1, 20989, 8523, 20964, -1, 8529, 8523, 20989, -1, 20964, 8507, 20949, -1, 8523, 8507, 20964, -1, 20949, 8509, 20918, -1, 8507, 8509, 20949, -1, 20891, 8534, 20881, -1, 8537, 8534, 20891, -1, 20881, 8536, 20852, -1, 8534, 8536, 20881, -1, 20852, 8553, 20853, -1, 8536, 8553, 20852, -1, 20853, 8547, 20843, -1, 8553, 8547, 20853, -1, 20843, 8531, 20825, -1, 8547, 8531, 20843, -1, 20825, 8533, 20786, -1, 8531, 8533, 20825, -1, 20755, 14613, 20739, -1, 14611, 14613, 20755, -1, 20738, 11743, 11741, -1, 20738, 16126, 11743, -1, 20738, 16142, 16126, -1, 20739, 14619, 20738, -1, 14613, 14619, 20739, -1, 20738, 16145, 16142, -1, 14619, 16146, 20738, -1, 20738, 16146, 16145, -1, 21175, 8470, 21182, -1, 8466, 8470, 21175, -1, 21182, 8464, 21188, -1, 8470, 8464, 21182, -1, 21188, 11383, 11382, -1, 21188, 13183, 11383, -1, 21188, 13181, 13183, -1, 8464, 8463, 21188, -1, 21188, 13182, 13181, -1, 8463, 13185, 21188, -1, 21188, 13185, 13182, -1, 18499, 8460, 21165, -1, 8461, 8460, 18499, -1, 21165, 8467, 21169, -1, 8460, 8467, 21165, -1, 21169, 8466, 21175, -1, 8467, 8466, 21169, -1, 21125, 8439, 21130, -1, 8436, 8439, 21125, -1, 21130, 8438, 21139, -1, 8439, 8438, 21130, -1, 21139, 8443, 18495, -1, 8438, 8443, 21139, -1, 21084, 8426, 21108, -1, 8427, 8426, 21084, -1, 21108, 8430, 21117, -1, 8426, 8430, 21108, -1, 21117, 8436, 21125, -1, 8430, 8436, 21117, -1, 21029, 8412, 21043, -1, 8408, 8412, 21029, -1, 21043, 8406, 21054, -1, 8412, 8406, 21043, -1, 21054, 8405, 21063, -1, 8406, 8405, 21054, -1, 20987, 8402, 21004, -1, 8403, 8402, 20987, -1, 21004, 8409, 21014, -1, 8402, 8409, 21004, -1, 21014, 8408, 21029, -1, 8409, 8408, 21014, -1, 20916, 8381, 20930, -1, 8378, 8381, 20916, -1, 20930, 8380, 20948, -1, 8381, 8380, 20930, -1, 20948, 8385, 20963, -1, 8380, 8385, 20948, -1, 20851, 8368, 20880, -1, 8369, 8368, 20851, -1, 20880, 8372, 20890, -1, 8368, 8372, 20880, -1, 20890, 8378, 20916, -1, 8372, 8378, 20890, -1, 14591, 20800, 20784, -1, 14591, 14595, 20800, -1, 20800, 14589, 20823, -1, 14595, 14589, 20800, -1, 14589, 20842, 20823, -1, 14589, 14588, 20842, -1, 11760, 20737, 11754, -1, 16096, 20737, 11760, -1, 16098, 20737, 16096, -1, 16099, 20737, 16098, -1, 16103, 20737, 16099, -1, 16103, 14586, 20737, -1, 14586, 14585, 20737, -1, 14585, 20754, 20737, -1, 14585, 14592, 20754, -1, 14592, 20784, 20754, -1, 14592, 14591, 20784, -1, 13170, 18634, 11433, -1, 13171, 18634, 13170, -1, 13173, 18634, 13171, -1, 13174, 18634, 13173, -1, 11433, 18634, 11431, -1, 13174, 8482, 18634, -1, 8482, 8481, 18634, -1, 8481, 18657, 18634, -1, 8481, 8479, 18657, -1, 8479, 18658, 18657, -1, 8479, 8478, 18658, -1, 8478, 21197, 18658, -1, 8478, 8477, 21197, -1, 21197, 8473, 21191, -1, 8477, 8473, 21197, -1, 8473, 18547, 21191, -1, 8473, 8472, 18547, -1, 18548, 8454, 21178, -1, 8455, 8454, 18548, -1, 21178, 8452, 18560, -1, 8454, 8452, 21178, -1, 18560, 8450, 18517, -1, 8452, 8450, 18560, -1, 18517, 8446, 21148, -1, 8450, 8446, 18517, -1, 21148, 8440, 21149, -1, 8446, 8440, 21148, -1, 21149, 8435, 18373, -1, 8440, 8435, 21149, -1, 18375, 8423, 18385, -1, 8424, 8423, 18375, -1, 18385, 8421, 18386, -1, 8423, 8421, 18385, -1, 18386, 8420, 18367, -1, 8421, 8420, 18386, -1, 18367, 8419, 21066, -1, 8420, 8419, 18367, -1, 21066, 8415, 21067, -1, 8419, 8415, 21066, -1, 21067, 8414, 21057, -1, 8415, 8414, 21067, -1, 21039, 8396, 21037, -1, 8397, 8396, 21039, -1, 21037, 8394, 21430, -1, 8396, 8394, 21037, -1, 21430, 8392, 21408, -1, 8394, 8392, 21430, -1, 21408, 8388, 20970, -1, 8392, 8388, 21408, -1, 20970, 8382, 20956, -1, 8388, 8382, 20970, -1, 20956, 8377, 20936, -1, 8382, 8377, 20956, -1, 20922, 14606, 20923, -1, 14607, 14606, 20922, -1, 20923, 14603, 20924, -1, 14606, 14603, 20923, -1, 20924, 14602, 20903, -1, 14603, 14602, 20924, -1, 20903, 14604, 20845, -1, 14602, 14604, 20903, -1, 20845, 14598, 20829, -1, 14604, 14598, 20845, -1, 20829, 11769, 11765, -1, 20829, 16089, 11769, -1, 20829, 16105, 16089, -1, 14598, 14597, 20829, -1, 20829, 16108, 16105, -1, 14597, 16109, 20829, -1, 20829, 16109, 16108, -1, 18639, 8357, 18656, -1, 8362, 8357, 18639, -1, 21214, 11454, 11456, -1, 21214, 13148, 11454, -1, 21214, 13146, 13148, -1, 18656, 8356, 21214, -1, 8357, 8356, 18656, -1, 21214, 13147, 13146, -1, 8356, 13150, 21214, -1, 21214, 13150, 13147, -1, 21185, 8345, 21192, -1, 8344, 8345, 21185, -1, 21192, 8351, 21199, -1, 8345, 8351, 21192, -1, 21199, 8350, 18640, -1, 8351, 8350, 21199, -1, 18539, 8340, 18559, -1, 8341, 8340, 18539, -1, 18559, 8339, 21180, -1, 8340, 8339, 18559, -1, 21180, 8344, 21185, -1, 8339, 8344, 21180, -1, 21128, 8321, 21150, -1, 8320, 8321, 21128, -1, 21150, 8327, 18518, -1, 8321, 8327, 21150, -1, 18518, 8326, 18516, -1, 8327, 8326, 18518, -1, 18366, 8316, 18384, -1, 8317, 8316, 18366, -1, 18384, 8315, 21127, -1, 8316, 8315, 18384, -1, 21127, 8320, 21128, -1, 8315, 8320, 21127, -1, 21041, 8273, 21070, -1, 8272, 8273, 21041, -1, 21070, 8279, 21089, -1, 8273, 8279, 21070, -1, 21089, 8278, 18368, -1, 8279, 8278, 21089, -1, 21423, 8268, 21038, -1, 8269, 8268, 21423, -1, 21038, 8267, 21040, -1, 8268, 8267, 21038, -1, 21040, 8272, 21041, -1, 8267, 8272, 21040, -1, 20935, 8296, 20953, -1, 8297, 8296, 20935, -1, 20953, 8303, 21407, -1, 8296, 8303, 20953, -1, 21407, 8302, 21416, -1, 8303, 8302, 21407, -1, 8293, 20920, 20901, -1, 8293, 8292, 20920, -1, 20920, 8291, 20921, -1, 8292, 8291, 20920, -1, 8291, 20935, 20921, -1, 8291, 8297, 20935, -1, 11789, 20828, 11783, -1, 16059, 20828, 11789, -1, 16061, 20828, 16059, -1, 16062, 20828, 16061, -1, 16066, 20828, 16062, -1, 14573, 20828, 16066, -1, 20828, 14572, 20902, -1, 14573, 14572, 20828, -1, 14572, 20900, 20902, -1, 14572, 14580, 20900, -1, 11477, 18703, 11475, -1, 13136, 18703, 11477, -1, 13137, 18703, 13136, -1, 13139, 18703, 13137, -1, 13140, 18703, 13139, -1, 8366, 18703, 13140, -1, 18703, 8358, 18708, -1, 8366, 8358, 18703, -1, 8358, 18687, 18708, -1, 8358, 8360, 18687, -1, 8337, 18648, 18677, -1, 8337, 8336, 18648, -1, 18648, 8335, 18626, -1, 8336, 8335, 18648, -1, 8335, 18627, 18626, -1, 8335, 8353, 18627, -1, 8353, 18616, 18627, -1, 8353, 8347, 18616, -1, 18616, 8331, 18617, -1, 8347, 8331, 18616, -1, 18617, 8333, 18598, -1, 8331, 8333, 18617, -1, 18583, 8310, 18564, -1, 8313, 8310, 18583, -1, 18564, 8312, 18565, -1, 8310, 8312, 18564, -1, 18565, 8329, 21171, -1, 8312, 8329, 18565, -1, 21171, 8323, 18532, -1, 8329, 8323, 21171, -1, 18532, 8307, 18533, -1, 8323, 8307, 18532, -1, 18533, 8309, 18474, -1, 8307, 8309, 18533, -1, 18447, 8262, 18402, -1, 8265, 8262, 18447, -1, 18402, 8264, 18403, -1, 8262, 8264, 18402, -1, 18403, 8281, 21120, -1, 8264, 8281, 18403, -1, 21120, 8275, 18362, -1, 8281, 8275, 21120, -1, 18362, 8259, 21123, -1, 8275, 8259, 18362, -1, 21123, 8261, 21111, -1, 8259, 8261, 21123, -1, 21099, 8286, 21096, -1, 8289, 8286, 21099, -1, 21096, 8288, 21420, -1, 8286, 8288, 21096, -1, 21420, 8305, 21421, -1, 8288, 8305, 21420, -1, 21421, 8299, 21417, -1, 8305, 8299, 21421, -1, 21417, 8283, 21026, -1, 8299, 8283, 21417, -1, 21026, 8285, 21001, -1, 8283, 8285, 21026, -1, 20999, 14577, 20905, -1, 14575, 14577, 20999, -1, 20906, 11796, 11790, -1, 20906, 16052, 11796, -1, 20906, 16068, 16052, -1, 20905, 14583, 20906, -1, 14577, 14583, 20905, -1, 20906, 16071, 16068, -1, 14583, 16072, 20906, -1, 20906, 16072, 16071, -1, 21219, 14561, 21222, -1, 14557, 14561, 21219, -1, 21222, 14555, 18707, -1, 14561, 14555, 21222, -1, 18707, 11488, 11490, -1, 18707, 13112, 11488, -1, 18707, 13110, 13112, -1, 14555, 13113, 18707, -1, 18707, 13111, 13110, -1, 13113, 13115, 18707, -1, 18707, 13115, 13111, -1, 18647, 14553, 18681, -1, 14554, 14553, 18647, -1, 18681, 14558, 21217, -1, 14553, 14558, 18681, -1, 21217, 14557, 21219, -1, 14558, 14557, 21217, -1, 21206, 8157, 21208, -1, 8154, 8157, 21206, -1, 21208, 8156, 18615, -1, 8157, 8156, 21208, -1, 18615, 8161, 18625, -1, 8156, 8161, 18615, -1, 18563, 8144, 18585, -1, 8145, 8144, 18563, -1, 18585, 8148, 21201, -1, 8144, 8148, 18585, -1, 21201, 8154, 21206, -1, 8148, 8154, 21201, -1, 21162, 8188, 21167, -1, 8184, 8188, 21162, -1, 21167, 8182, 18531, -1, 8188, 8182, 21167, -1, 18531, 8181, 18536, -1, 8182, 8181, 18531, -1, 18401, 8178, 18449, -1, 8179, 8178, 18401, -1, 18449, 8185, 21157, -1, 8178, 8185, 18449, -1, 21157, 8184, 21162, -1, 8185, 8184, 21157, -1, 21110, 8215, 21113, -1, 8212, 8215, 21110, -1, 21113, 8214, 18363, -1, 8215, 8214, 21113, -1, 18363, 8219, 18361, -1, 8214, 8219, 18363, -1, 21431, 8202, 21097, -1, 8203, 8202, 21431, -1, 21097, 8206, 21098, -1, 8202, 8206, 21097, -1, 21098, 8212, 21110, -1, 8206, 8212, 21098, -1, 8242, 21012, 21002, -1, 8242, 8246, 21012, -1, 21012, 8240, 21027, -1, 8246, 8240, 21012, -1, 8240, 21419, 21027, -1, 8240, 8239, 21419, -1, 11814, 21383, 11806, -1, 16022, 21383, 11814, -1, 16024, 21383, 16022, -1, 16025, 21383, 16024, -1, 16029, 21383, 16025, -1, 16029, 8237, 21383, -1, 8237, 8236, 21383, -1, 8236, 21000, 21383, -1, 8236, 8243, 21000, -1, 8243, 21002, 21000, -1, 8243, 8242, 21002, -1, 13098, 3411, 11503, -1, 13099, 3411, 13098, -1, 13101, 3411, 13099, -1, 13102, 3411, 13101, -1, 11503, 3411, 3410, -1, 13102, 13105, 3411, -1, 13105, 14571, 3411, -1, 14571, 3412, 3411, -1, 14571, 14569, 3412, -1, 14569, 709, 3412, -1, 14569, 14568, 709, -1, 14568, 18709, 709, -1, 14568, 14567, 18709, -1, 18709, 14564, 18701, -1, 14567, 14564, 18709, -1, 14564, 18691, 18701, -1, 14564, 14563, 18691, -1, 18693, 8172, 18685, -1, 8173, 8172, 18693, -1, 18685, 8170, 18686, -1, 8172, 8170, 18685, -1, 18686, 8168, 323, -1, 8170, 8168, 18686, -1, 323, 8164, 18628, -1, 8168, 8164, 323, -1, 18628, 8158, 18613, -1, 8164, 8158, 18628, -1, 18613, 8153, 18611, -1, 8158, 8153, 18613, -1, 18605, 8199, 18595, -1, 8200, 8199, 18605, -1, 18595, 8196, 18596, -1, 8199, 8196, 18595, -1, 18596, 8195, 198, -1, 8196, 8195, 18596, -1, 198, 8197, 18553, -1, 8195, 8197, 198, -1, 18553, 8191, 18509, -1, 8197, 8191, 18553, -1, 18509, 8190, 18508, -1, 8191, 8190, 18509, -1, 18492, 8230, 18467, -1, 8231, 8230, 18492, -1, 18467, 8228, 18468, -1, 8230, 8228, 18467, -1, 18468, 8226, 94, -1, 8228, 8226, 18468, -1, 94, 8222, 18378, -1, 8226, 8222, 94, -1, 18378, 8216, 18364, -1, 8222, 8216, 18378, -1, 18364, 8211, 21463, -1, 8216, 8211, 18364, -1, 21455, 8257, 21452, -1, 8258, 8257, 21455, -1, 21452, 8254, 21453, -1, 8257, 8254, 21452, -1, 21453, 8253, 30, -1, 8254, 8253, 21453, -1, 30, 8255, 3407, -1, 8253, 8255, 30, -1, 3407, 8249, 3403, -1, 8255, 8249, 3407, -1, 3403, 11824, 3406, -1, 3403, 16015, 11824, -1, 3403, 16031, 16015, -1, 8249, 8248, 3403, -1, 3403, 16034, 16031, -1, 8248, 16035, 3403, -1, 3403, 16035, 16034, -1, 936, 7697, 1016, -1, 7702, 7697, 936, -1, 1045, 11520, 1106, -1, 1045, 12957, 11520, -1, 1045, 12955, 12957, -1, 1016, 7696, 1045, -1, 7697, 7696, 1016, -1, 1045, 12956, 12955, -1, 7696, 12959, 1045, -1, 1045, 12959, 12956, -1, 443, 7768, 592, -1, 7769, 7768, 443, -1, 592, 7775, 698, -1, 7768, 7775, 592, -1, 698, 7774, 829, -1, 7775, 7774, 698, -1, 397, 7764, 420, -1, 7765, 7764, 397, -1, 420, 7763, 432, -1, 7764, 7763, 420, -1, 432, 7769, 443, -1, 7763, 7769, 432, -1, 276, 7792, 304, -1, 7793, 7792, 276, -1, 304, 7799, 321, -1, 7792, 7799, 304, -1, 321, 7798, 366, -1, 7799, 7798, 321, -1, 248, 7788, 257, -1, 7789, 7788, 248, -1, 257, 7787, 269, -1, 7788, 7787, 257, -1, 269, 7793, 276, -1, 7787, 7793, 269, -1, 151, 7745, 177, -1, 7744, 7745, 151, -1, 177, 7751, 196, -1, 7745, 7751, 177, -1, 196, 7750, 229, -1, 7751, 7750, 196, -1, 115, 7740, 126, -1, 7741, 7740, 115, -1, 126, 7739, 142, -1, 7740, 7739, 126, -1, 142, 7744, 151, -1, 7739, 7744, 142, -1, 70, 7721, 81, -1, 7720, 7721, 70, -1, 81, 7727, 93, -1, 7721, 7727, 81, -1, 93, 7726, 110, -1, 7727, 7726, 93, -1, 7717, 57, 47, -1, 7717, 7716, 57, -1, 57, 7715, 59, -1, 7716, 7715, 57, -1, 7715, 70, 59, -1, 7715, 7720, 70, -1, 11844, 21, 15, -1, 15874, 21, 11844, -1, 15876, 21, 15874, -1, 15877, 21, 15876, -1, 15881, 21, 15877, -1, 14493, 21, 15881, -1, 21, 14492, 29, -1, 14493, 14492, 21, -1, 14492, 43, 29, -1, 14492, 14500, 43, -1, 11574, 1015, 2484, -1, 13059, 1015, 11574, -1, 13060, 1015, 13059, -1, 13062, 1015, 13060, -1, 13063, 1015, 13062, -1, 13066, 1015, 13063, -1, 1015, 14545, 998, -1, 13066, 14545, 1015, -1, 14545, 980, 998, -1, 14545, 14547, 980, -1, 8101, 928, 948, -1, 8101, 8100, 928, -1, 928, 8099, 904, -1, 8100, 8099, 928, -1, 8099, 879, 904, -1, 8099, 8117, 879, -1, 8117, 855, 879, -1, 8117, 8111, 855, -1, 855, 8095, 842, -1, 8111, 8095, 855, -1, 842, 8097, 819, -1, 8095, 8097, 842, -1, 784, 8122, 769, -1, 8125, 8122, 784, -1, 769, 8124, 731, -1, 8122, 8124, 769, -1, 731, 8141, 732, -1, 8124, 8141, 731, -1, 732, 8135, 721, -1, 8141, 8135, 732, -1, 721, 8119, 705, -1, 8135, 8119, 721, -1, 705, 8121, 690, -1, 8119, 8121, 705, -1, 653, 8074, 645, -1, 8077, 8074, 653, -1, 645, 8076, 632, -1, 8074, 8076, 645, -1, 632, 8093, 633, -1, 8076, 8093, 632, -1, 633, 8087, 607, -1, 8093, 8087, 633, -1, 607, 8071, 591, -1, 8087, 8071, 607, -1, 591, 8073, 436, -1, 8071, 8073, 591, -1, 437, 8050, 562, -1, 8053, 8050, 437, -1, 562, 8052, 554, -1, 8050, 8052, 562, -1, 554, 8069, 542, -1, 8052, 8069, 554, -1, 542, 8063, 533, -1, 8069, 8063, 542, -1, 533, 8047, 525, -1, 8063, 8047, 533, -1, 525, 8049, 266, -1, 8047, 8049, 525, -1, 268, 8040, 478, -1, 8038, 8040, 268, -1, 170, 11921, 171, -1, 170, 15978, 11921, -1, 170, 15994, 15978, -1, 478, 8046, 170, -1, 8040, 8046, 478, -1, 170, 15997, 15994, -1, 8046, 15998, 170, -1, 170, 15998, 15997, -1, 978, 14533, 979, -1, 14529, 14533, 978, -1, 979, 14527, 997, -1, 14533, 14527, 979, -1, 997, 11581, 1018, -1, 997, 13034, 11581, -1, 997, 13032, 13034, -1, 14527, 13035, 997, -1, 997, 13033, 13032, -1, 13035, 13037, 997, -1, 997, 13037, 13033, -1, 902, 14525, 924, -1, 14526, 14525, 902, -1, 924, 14530, 947, -1, 14525, 14530, 924, -1, 947, 14529, 978, -1, 14530, 14529, 947, -1, 823, 7991, 824, -1, 7988, 7991, 823, -1, 824, 7990, 843, -1, 7991, 7990, 824, -1, 843, 7995, 856, -1, 7990, 7995, 843, -1, 733, 7978, 770, -1, 7979, 7978, 733, -1, 770, 7982, 785, -1, 7978, 7982, 770, -1, 785, 7988, 823, -1, 7982, 7988, 785, -1, 691, 7930, 692, -1, 7926, 7930, 691, -1, 692, 7924, 706, -1, 7930, 7924, 692, -1, 706, 7923, 722, -1, 7924, 7923, 706, -1, 634, 7920, 646, -1, 7921, 7920, 634, -1, 646, 7927, 654, -1, 7920, 7927, 646, -1, 654, 7926, 691, -1, 7927, 7926, 654, -1, 579, 7957, 580, -1, 7954, 7957, 579, -1, 580, 7956, 594, -1, 7957, 7956, 580, -1, 594, 7961, 608, -1, 7956, 7961, 594, -1, 337, 7944, 563, -1, 7945, 7944, 337, -1, 563, 7948, 568, -1, 7944, 7948, 563, -1, 568, 7954, 579, -1, 7948, 7954, 568, -1, 8018, 510, 495, -1, 8018, 8022, 510, -1, 510, 8016, 523, -1, 8022, 8016, 510, -1, 8016, 338, 523, -1, 8016, 8015, 338, -1, 11940, 480, 479, -1, 15948, 480, 11940, -1, 15950, 480, 15948, -1, 15951, 480, 15950, -1, 15955, 480, 15951, -1, 15955, 8013, 480, -1, 8013, 8012, 480, -1, 8012, 490, 480, -1, 8012, 8019, 490, -1, 8019, 495, 490, -1, 8019, 8018, 495, -1, 13020, 2992, 11593, -1, 13021, 2992, 13020, -1, 13023, 2992, 13021, -1, 13024, 2992, 13023, -1, 11593, 2992, 2991, -1, 13024, 13027, 2992, -1, 13027, 14543, 2992, -1, 14543, 1124, 2992, -1, 14543, 14541, 1124, -1, 14541, 1095, 1124, -1, 14541, 14540, 1095, -1, 14540, 1027, 1095, -1, 14540, 14539, 1027, -1, 1027, 14536, 1001, -1, 14539, 14536, 1027, -1, 14536, 1000, 1001, -1, 14536, 14535, 1000, -1, 986, 8006, 983, -1, 8007, 8006, 986, -1, 983, 8004, 976, -1, 8006, 8004, 983, -1, 976, 8002, 961, -1, 8004, 8002, 976, -1, 961, 7998, 867, -1, 8002, 7998, 961, -1, 867, 7992, 868, -1, 7998, 7992, 867, -1, 868, 7987, 835, -1, 7992, 7987, 868, -1, 836, 7941, 840, -1, 7942, 7941, 836, -1, 840, 7938, 827, -1, 7941, 7938, 840, -1, 827, 7937, 808, -1, 7938, 7937, 827, -1, 808, 7939, 725, -1, 7937, 7939, 808, -1, 725, 7933, 726, -1, 7939, 7933, 725, -1, 726, 7932, 716, -1, 7933, 7932, 726, -1, 714, 7972, 715, -1, 7973, 7972, 714, -1, 715, 7970, 697, -1, 7972, 7970, 715, -1, 697, 7968, 679, -1, 7970, 7968, 697, -1, 679, 7964, 614, -1, 7968, 7964, 679, -1, 614, 7958, 602, -1, 7964, 7958, 614, -1, 602, 7953, 462, -1, 7958, 7953, 602, -1, 429, 8033, 486, -1, 8034, 8033, 429, -1, 486, 8030, 487, -1, 8033, 8030, 486, -1, 487, 8029, 382, -1, 8030, 8029, 487, -1, 382, 8031, 379, -1, 8029, 8031, 382, -1, 379, 8025, 282, -1, 8031, 8025, 379, -1, 282, 11950, 283, -1, 282, 15941, 11950, -1, 282, 15957, 15941, -1, 8025, 8024, 282, -1, 282, 15960, 15957, -1, 8024, 15961, 282, -1, 282, 15961, 15960, -1, 1122, 14408, 1123, -1, 14413, 14408, 1122, -1, 3053, 11603, 3082, -1, 3053, 12726, 11603, -1, 3053, 12724, 12726, -1, 1123, 12727, 3053, -1, 14408, 12727, 1123, -1, 3053, 12725, 12724, -1, 12727, 12729, 3053, -1, 3053, 12729, 12725, -1, 985, 7036, 1026, -1, 7037, 7036, 985, -1, 1026, 7043, 1092, -1, 7036, 7043, 1026, -1, 1092, 7042, 1093, -1, 7043, 7042, 1092, -1, 974, 7032, 975, -1, 7033, 7032, 974, -1, 975, 7031, 984, -1, 7032, 7031, 975, -1, 984, 7037, 985, -1, 7031, 7037, 984, -1, 839, 7060, 869, -1, 7061, 7060, 839, -1, 869, 7067, 959, -1, 7060, 7067, 869, -1, 959, 7066, 960, -1, 7067, 7066, 959, -1, 828, 7056, 826, -1, 7057, 7056, 828, -1, 826, 7055, 838, -1, 7056, 7055, 826, -1, 838, 7061, 839, -1, 7055, 7061, 838, -1, 712, 7121, 724, -1, 7120, 7121, 712, -1, 724, 7127, 805, -1, 7121, 7127, 724, -1, 805, 7126, 806, -1, 7127, 7126, 805, -1, 682, 7116, 699, -1, 7117, 7116, 682, -1, 699, 7115, 711, -1, 7116, 7115, 699, -1, 711, 7120, 712, -1, 7115, 7120, 711, -1, 582, 7097, 613, -1, 7096, 7097, 582, -1, 613, 7103, 680, -1, 7097, 7103, 613, -1, 680, 7102, 681, -1, 7103, 7102, 680, -1, 7093, 485, 546, -1, 7093, 7092, 485, -1, 485, 7091, 529, -1, 7092, 7091, 485, -1, 7091, 582, 529, -1, 7091, 7096, 582, -1, 11965, 380, 528, -1, 15652, 380, 11965, -1, 15654, 380, 15652, -1, 15655, 380, 15654, -1, 15659, 380, 15655, -1, 7072, 380, 15659, -1, 380, 7071, 378, -1, 7072, 7071, 380, -1, 7071, 544, 378, -1, 7071, 7079, 544, -1, 12982, 920, 11549, -1, 12983, 920, 12982, -1, 12985, 920, 12983, -1, 12986, 920, 12985, -1, 11549, 920, 2021, -1, 12986, 12989, 920, -1, 12989, 14523, 920, -1, 14523, 877, 920, -1, 14523, 14521, 877, -1, 14521, 853, 877, -1, 14521, 14520, 853, -1, 14520, 816, 853, -1, 14520, 14519, 816, -1, 816, 14516, 817, -1, 14519, 14516, 816, -1, 14516, 1373, 817, -1, 14516, 14515, 1373, -1, 1374, 7890, 735, -1, 7891, 7890, 1374, -1, 735, 7888, 728, -1, 7890, 7888, 735, -1, 728, 7886, 718, -1, 7888, 7886, 728, -1, 718, 7882, 703, -1, 7886, 7882, 718, -1, 703, 7876, 798, -1, 7882, 7876, 703, -1, 798, 7871, 623, -1, 7876, 7871, 798, -1, 620, 7917, 627, -1, 7918, 7917, 620, -1, 627, 7915, 610, -1, 7917, 7915, 627, -1, 610, 7914, 597, -1, 7915, 7914, 610, -1, 597, 7913, 426, -1, 7914, 7913, 597, -1, 426, 7909, 361, -1, 7913, 7909, 426, -1, 361, 7908, 362, -1, 7909, 7908, 361, -1, 358, 7856, 353, -1, 7857, 7856, 358, -1, 353, 7854, 536, -1, 7856, 7854, 353, -1, 536, 7852, 531, -1, 7854, 7852, 536, -1, 531, 7848, 504, -1, 7852, 7848, 531, -1, 504, 7842, 222, -1, 7848, 7842, 504, -1, 222, 7837, 194, -1, 7842, 7837, 222, -1, 182, 7825, 217, -1, 7826, 7825, 182, -1, 217, 7822, 473, -1, 7825, 7822, 217, -1, 473, 7821, 471, -1, 7822, 7821, 473, -1, 471, 7823, 466, -1, 7821, 7823, 471, -1, 466, 7817, 95, -1, 7823, 7817, 466, -1, 95, 11887, 98, -1, 95, 15904, 11887, -1, 95, 15920, 15904, -1, 7817, 7816, 95, -1, 95, 15923, 15920, -1, 7816, 15924, 95, -1, 95, 15924, 15923, -1, 876, 14544, 894, -1, 14549, 14544, 876, -1, 919, 11561, 2119, -1, 919, 13073, 11561, -1, 919, 13071, 13073, -1, 894, 13074, 919, -1, 14544, 13074, 894, -1, 919, 13072, 13071, -1, 13074, 13076, 919, -1, 919, 13076, 13072, -1, 813, 8108, 814, -1, 8109, 8108, 813, -1, 814, 8115, 833, -1, 8108, 8115, 814, -1, 833, 8114, 852, -1, 8115, 8114, 833, -1, 729, 8104, 738, -1, 8105, 8104, 729, -1, 738, 8103, 736, -1, 8104, 8103, 738, -1, 736, 8109, 813, -1, 8103, 8109, 736, -1, 622, 8133, 701, -1, 8132, 8133, 622, -1, 701, 8139, 702, -1, 8133, 8139, 701, -1, 702, 8138, 719, -1, 8139, 8138, 702, -1, 611, 8128, 630, -1, 8129, 8128, 611, -1, 630, 8127, 629, -1, 8128, 8127, 630, -1, 629, 8132, 622, -1, 8127, 8132, 629, -1, 352, 8085, 425, -1, 8084, 8085, 352, -1, 425, 8091, 589, -1, 8085, 8091, 425, -1, 589, 8090, 598, -1, 8091, 8090, 589, -1, 347, 8080, 549, -1, 8081, 8080, 347, -1, 549, 8079, 354, -1, 8080, 8079, 549, -1, 354, 8084, 352, -1, 8079, 8084, 354, -1, 216, 8061, 505, -1, 8060, 8061, 216, -1, 505, 8067, 515, -1, 8061, 8067, 505, -1, 515, 8066, 345, -1, 8067, 8066, 515, -1, 8057, 475, 207, -1, 8057, 8056, 475, -1, 475, 8055, 218, -1, 8056, 8055, 475, -1, 8055, 216, 218, -1, 8055, 8060, 216, -1, 11904, 122, 101, -1, 15985, 122, 11904, -1, 15987, 122, 15985, -1, 15988, 122, 15987, -1, 15992, 122, 15988, -1, 8036, 122, 15992, -1, 122, 8035, 468, -1, 8036, 8035, 122, -1, 8035, 208, 468, -1, 8035, 8043, 208, -1, 11531, 764, 1570, -1, 12944, 764, 11531, -1, 12945, 764, 12944, -1, 12947, 764, 12945, -1, 12948, 764, 12947, -1, 7706, 764, 12948, -1, 764, 7698, 761, -1, 7706, 7698, 764, -1, 7698, 1322, 761, -1, 7698, 7700, 1322, -1, 7761, 685, 1216, -1, 7761, 7760, 685, -1, 685, 7759, 662, -1, 7760, 7759, 685, -1, 7759, 648, 662, -1, 7759, 7777, 648, -1, 7777, 638, 648, -1, 7777, 7771, 638, -1, 638, 7755, 639, -1, 7771, 7755, 638, -1, 639, 7757, 601, -1, 7755, 7757, 639, -1, 534, 7782, 540, -1, 7785, 7782, 534, -1, 540, 7784, 565, -1, 7782, 7784, 540, -1, 565, 7801, 557, -1, 7784, 7801, 565, -1, 557, 7795, 558, -1, 7801, 7795, 557, -1, 558, 7779, 371, -1, 7795, 7779, 558, -1, 371, 7781, 312, -1, 7779, 7781, 371, -1, 292, 7734, 298, -1, 7737, 7734, 292, -1, 298, 7736, 492, -1, 7734, 7736, 298, -1, 492, 7753, 483, -1, 7736, 7753, 492, -1, 483, 7747, 484, -1, 7753, 7747, 483, -1, 484, 7731, 232, -1, 7747, 7731, 484, -1, 232, 7733, 189, -1, 7731, 7733, 232, -1, 166, 7710, 167, -1, 7713, 7710, 166, -1, 167, 7712, 463, -1, 7710, 7712, 167, -1, 463, 7729, 457, -1, 7712, 7729, 463, -1, 457, 7723, 455, -1, 7729, 7723, 457, -1, 455, 7707, 109, -1, 7723, 7707, 455, -1, 109, 7709, 84, -1, 7707, 7709, 109, -1, 79, 14497, 450, -1, 14495, 14497, 79, -1, 35, 11855, 36, -1, 35, 15867, 11855, -1, 35, 15883, 15867, -1, 450, 14503, 35, -1, 14497, 14503, 450, -1, 35, 15886, 15883, -1, 14503, 15887, 35, -1, 35, 15887, 15886, -1, 1515, 14513, 1593, -1, 14509, 14513, 1515, -1, 1593, 14507, 762, -1, 14513, 14507, 1593, -1, 762, 11541, 765, -1, 762, 12995, 11541, -1, 762, 12993, 12995, -1, 14507, 12996, 762, -1, 762, 12994, 12993, -1, 12996, 12998, 762, -1, 762, 12998, 12994, -1, 661, 14505, 684, -1, 14506, 14505, 661, -1, 684, 14510, 1367, -1, 14505, 14510, 684, -1, 1367, 14509, 1515, -1, 14510, 14509, 1367, -1, 757, 7875, 807, -1, 7872, 7875, 757, -1, 807, 7874, 636, -1, 7875, 7874, 807, -1, 636, 7879, 637, -1, 7874, 7879, 636, -1, 566, 7862, 539, -1, 7863, 7862, 566, -1, 539, 7866, 640, -1, 7862, 7866, 539, -1, 640, 7872, 757, -1, 7866, 7872, 640, -1, 343, 7906, 370, -1, 7902, 7906, 343, -1, 370, 7900, 385, -1, 7906, 7900, 370, -1, 385, 7899, 559, -1, 7900, 7899, 385, -1, 493, 7896, 297, -1, 7897, 7896, 493, -1, 297, 7903, 315, -1, 7896, 7903, 297, -1, 315, 7902, 343, -1, 7903, 7902, 315, -1, 213, 7841, 231, -1, 7838, 7841, 213, -1, 231, 7840, 235, -1, 7841, 7840, 231, -1, 235, 7845, 482, -1, 7840, 7845, 235, -1, 137, 7828, 165, -1, 7829, 7828, 137, -1, 165, 7832, 193, -1, 7828, 7832, 165, -1, 193, 7838, 213, -1, 7832, 7838, 193, -1, 7810, 108, 103, -1, 7810, 7814, 108, -1, 108, 7808, 114, -1, 7814, 7808, 108, -1, 7808, 138, 114, -1, 7808, 7807, 138, -1, 11872, 80, 452, -1, 15911, 80, 11872, -1, 15913, 80, 15911, -1, 15914, 80, 15913, -1, 15918, 80, 15914, -1, 15918, 7805, 80, -1, 7805, 7804, 80, -1, 7804, 78, 80, -1, 7804, 7811, 78, -1, 7811, 103, 78, -1, 7811, 7810, 103, -1, 12907, 3384, 11331, -1, 12908, 3384, 12907, -1, 12910, 3384, 12908, -1, 12911, 3384, 12910, -1, 11331, 3384, 3383, -1, 12911, 12914, 3384, -1, 12914, 14491, 3384, -1, 14491, 1796, 3384, -1, 14491, 14489, 1796, -1, 14489, 1762, 1796, -1, 14489, 14488, 1762, -1, 14488, 1760, 1762, -1, 14488, 14487, 1760, -1, 1760, 14484, 1693, -1, 14487, 14484, 1760, -1, 14484, 1692, 1693, -1, 14484, 14483, 1692, -1, 1659, 7608, 1660, -1, 7609, 7608, 1659, -1, 1660, 7606, 1652, -1, 7608, 7606, 1660, -1, 1652, 7604, 1629, -1, 7606, 7604, 1652, -1, 1629, 7600, 1625, -1, 7604, 7600, 1629, -1, 1625, 7594, 1530, -1, 7600, 7594, 1625, -1, 1530, 7589, 1533, -1, 7594, 7589, 1530, -1, 1532, 7635, 3250, -1, 7636, 7635, 1532, -1, 3250, 7632, 1523, -1, 7635, 7632, 3250, -1, 1523, 7631, 1500, -1, 7632, 7631, 1523, -1, 1500, 7633, 1493, -1, 7631, 7633, 1500, -1, 1493, 7627, 1400, -1, 7633, 7627, 1493, -1, 1400, 7626, 1402, -1, 7627, 7626, 1400, -1, 1403, 7666, 3195, -1, 7667, 7666, 1403, -1, 3195, 7664, 1380, -1, 7666, 7664, 3195, -1, 1380, 7662, 1336, -1, 7664, 7662, 1380, -1, 1336, 7658, 1337, -1, 7662, 7658, 1336, -1, 1337, 7652, 1251, -1, 7658, 7652, 1337, -1, 1251, 7647, 1217, -1, 7652, 7647, 1251, -1, 1218, 7693, 1219, -1, 7694, 7693, 1218, -1, 1219, 7690, 1212, -1, 7693, 7690, 1219, -1, 1212, 7689, 1196, -1, 7690, 7689, 1212, -1, 1196, 7691, 1194, -1, 7689, 7691, 1196, -1, 1194, 7685, 1101, -1, 7691, 7685, 1194, -1, 1101, 11973, 1102, -1, 1101, 15830, 11973, -1, 1101, 15846, 15830, -1, 7685, 7684, 1101, -1, 1101, 15849, 15846, -1, 7684, 15850, 1101, -1, 1101, 15850, 15849, -1, 1795, 14456, 1815, -1, 14461, 14456, 1795, -1, 3392, 11351, 3393, -1, 3392, 12843, 11351, -1, 3392, 12841, 12843, -1, 1815, 12844, 3392, -1, 14456, 12844, 1815, -1, 3392, 12842, 12841, -1, 12844, 12846, 3392, -1, 3392, 12846, 12842, -1, 1655, 7388, 1761, -1, 7389, 7388, 1655, -1, 1761, 7395, 1764, -1, 7388, 7395, 1761, -1, 1764, 7394, 1778, -1, 7395, 7394, 1764, -1, 1650, 7384, 1676, -1, 7385, 7384, 1650, -1, 1676, 7383, 1654, -1, 7384, 7383, 1676, -1, 1654, 7389, 1655, -1, 7383, 7389, 1654, -1, 1529, 7412, 1626, -1, 7413, 7412, 1529, -1, 1626, 7419, 1628, -1, 7412, 7419, 1626, -1, 1628, 7418, 1637, -1, 7419, 7418, 1628, -1, 1521, 7408, 1540, -1, 7409, 7408, 1521, -1, 1540, 7407, 3253, -1, 7408, 7407, 1540, -1, 3253, 7413, 1529, -1, 7407, 7413, 3253, -1, 1399, 7436, 1494, -1, 7437, 7436, 1399, -1, 1494, 7443, 1495, -1, 7436, 7443, 1494, -1, 1495, 7442, 1506, -1, 7443, 7442, 1495, -1, 1371, 7432, 1405, -1, 7433, 7432, 1371, -1, 1405, 7431, 3199, -1, 7432, 7431, 1405, -1, 3199, 7437, 1399, -1, 7431, 7437, 3199, -1, 1215, 7461, 1334, -1, 7460, 7461, 1215, -1, 1334, 7467, 1335, -1, 7461, 7467, 1334, -1, 1335, 7466, 1369, -1, 7467, 7466, 1335, -1, 7457, 1239, 1195, -1, 7457, 7456, 1239, -1, 1239, 7455, 1214, -1, 7456, 7455, 1239, -1, 7455, 1215, 1214, -1, 7455, 7460, 1215, -1, 11959, 1107, 1104, -1, 15763, 1107, 11959, -1, 15765, 1107, 15763, -1, 15766, 1107, 15765, -1, 15770, 1107, 15766, -1, 7364, 1107, 15770, -1, 1107, 7363, 1192, -1, 7364, 7363, 1107, -1, 7363, 1193, 1192, -1, 7363, 7371, 1193, -1, 11302, 1707, 3328, -1, 12869, 1707, 11302, -1, 12870, 1707, 12869, -1, 12872, 1707, 12870, -1, 12873, 1707, 12872, -1, 12876, 1707, 12873, -1, 1707, 14465, 1685, -1, 12876, 14465, 1707, -1, 14465, 1682, 1685, -1, 14465, 14467, 1682, -1, 7525, 1605, 1623, -1, 7525, 7524, 1605, -1, 1605, 7523, 1584, -1, 7524, 7523, 1605, -1, 7523, 1572, 1584, -1, 7523, 7541, 1572, -1, 7541, 1553, 1572, -1, 7541, 7535, 1553, -1, 1553, 7519, 1535, -1, 7535, 7519, 1553, -1, 1535, 7521, 1536, -1, 7519, 7521, 1535, -1, 1483, 7474, 1464, -1, 7477, 7474, 1483, -1, 1464, 7476, 1425, -1, 7474, 7476, 1464, -1, 1425, 7493, 1426, -1, 7476, 7493, 1425, -1, 1426, 7487, 1415, -1, 7493, 7487, 1426, -1, 1415, 7471, 1397, -1, 7487, 7471, 1415, -1, 1397, 7473, 1391, -1, 7471, 7473, 1397, -1, 1329, 7498, 1318, -1, 7501, 7498, 1329, -1, 1318, 7500, 1292, -1, 7498, 7500, 1318, -1, 1292, 7517, 1293, -1, 7500, 7517, 1292, -1, 1293, 7511, 1267, -1, 7517, 7511, 1293, -1, 1267, 7495, 1244, -1, 7511, 7495, 1267, -1, 1244, 7497, 1241, -1, 7495, 7497, 1244, -1, 1177, 7558, 1158, -1, 7561, 7558, 1177, -1, 1158, 7560, 1147, -1, 7558, 7560, 1158, -1, 1147, 7577, 1132, -1, 7560, 7577, 1147, -1, 1132, 7571, 1119, -1, 7577, 7571, 1132, -1, 1119, 7555, 1087, -1, 7571, 7555, 1119, -1, 1087, 7557, 1088, -1, 7555, 7557, 1087, -1, 1035, 7548, 1009, -1, 7546, 7548, 1035, -1, 1007, 12003, 2344, -1, 1007, 15793, 12003, -1, 1007, 15809, 15793, -1, 1009, 7554, 1007, -1, 7548, 7554, 1009, -1, 1007, 15812, 15809, -1, 7554, 15813, 1007, -1, 1007, 15813, 15812, -1, 3321, 14481, 1683, -1, 14477, 14481, 3321, -1, 1683, 14475, 1684, -1, 14481, 14475, 1683, -1, 1684, 11318, 1708, -1, 1684, 12921, 11318, -1, 1684, 12919, 12921, -1, 14475, 12922, 1684, -1, 1684, 12920, 12919, -1, 12922, 12924, 1684, -1, 1684, 12924, 12920, -1, 1585, 14473, 1606, -1, 14474, 14473, 1585, -1, 1606, 14478, 3310, -1, 14473, 14478, 1606, -1, 3310, 14477, 3321, -1, 14478, 14477, 3310, -1, 3254, 7593, 1537, -1, 7590, 7593, 3254, -1, 1537, 7592, 1538, -1, 7593, 7592, 1537, -1, 1538, 7597, 1557, -1, 7592, 7597, 1538, -1, 1427, 7580, 1463, -1, 7581, 7580, 1427, -1, 1463, 7584, 3245, -1, 7580, 7584, 1463, -1, 3245, 7590, 3254, -1, 7584, 7590, 3245, -1, 3200, 7624, 1392, -1, 7620, 7624, 3200, -1, 1392, 7618, 1396, -1, 7624, 7618, 1392, -1, 1396, 7617, 1412, -1, 7618, 7617, 1396, -1, 1291, 7614, 1317, -1, 7615, 7614, 1291, -1, 1317, 7621, 3189, -1, 7614, 7621, 1317, -1, 3189, 7620, 3200, -1, 7621, 7620, 3189, -1, 3149, 7651, 1242, -1, 7648, 7651, 3149, -1, 1242, 7650, 1243, -1, 7651, 7650, 1242, -1, 1243, 7655, 1266, -1, 7650, 7655, 1243, -1, 1131, 7638, 1157, -1, 7639, 7638, 1131, -1, 1157, 7642, 3136, -1, 7638, 7642, 1157, -1, 3136, 7648, 3149, -1, 7642, 7648, 3136, -1, 7678, 1089, 2955, -1, 7678, 7682, 1089, -1, 1089, 7676, 1090, -1, 7682, 7676, 1089, -1, 7676, 1120, 1090, -1, 7676, 7675, 1120, -1, 11984, 1012, 1011, -1, 15837, 1012, 11984, -1, 15839, 1012, 15837, -1, 15840, 1012, 15839, -1, 15844, 1012, 15840, -1, 15844, 7673, 1012, -1, 7673, 7672, 1012, -1, 7672, 1034, 1012, -1, 7672, 7679, 1034, -1, 7679, 2955, 1034, -1, 7679, 7678, 2955, -1, 11362, 192, 191, -1, 12830, 192, 11362, -1, 12831, 192, 12830, -1, 12833, 192, 12831, -1, 12834, 192, 12833, -1, 12837, 192, 12834, -1, 192, 14457, 1877, -1, 12837, 14457, 192, -1, 14457, 91, 1877, -1, 14457, 14459, 91, -1, 7381, 1833, 49, -1, 7381, 7380, 1833, -1, 1833, 7379, 1798, -1, 7380, 7379, 1833, -1, 7379, 1799, 1798, -1, 7379, 7397, 1799, -1, 7397, 1782, 1799, -1, 7397, 7391, 1782, -1, 1782, 7375, 1768, -1, 7391, 7375, 1782, -1, 1768, 7377, 1752, -1, 7375, 7377, 1768, -1, 1722, 7402, 1710, -1, 7405, 7402, 1722, -1, 1710, 7404, 1667, -1, 7402, 7404, 1710, -1, 1667, 7421, 1668, -1, 7404, 7421, 1667, -1, 1668, 7415, 1643, -1, 7421, 7415, 1668, -1, 1643, 7399, 1632, -1, 7415, 7399, 1643, -1, 1632, 7401, 1617, -1, 7399, 7401, 1632, -1, 1576, 7426, 1565, -1, 7429, 7426, 1576, -1, 1565, 7428, 1542, -1, 7426, 7428, 1565, -1, 1542, 7445, 1543, -1, 7428, 7445, 1542, -1, 1543, 7439, 1518, -1, 7445, 7439, 1543, -1, 1518, 7423, 1503, -1, 7439, 7423, 1518, -1, 1503, 7425, 1468, -1, 7423, 7425, 1503, -1, 1432, 7450, 1421, -1, 7453, 7450, 1432, -1, 1421, 7452, 1388, -1, 7450, 7452, 1421, -1, 1388, 7469, 1389, -1, 7452, 7469, 1388, -1, 1389, 7463, 1375, -1, 7469, 7463, 1389, -1, 1375, 7447, 1350, -1, 7463, 7447, 1375, -1, 1350, 7449, 1311, -1, 7447, 7449, 1350, -1, 1273, 7368, 1253, -1, 7366, 7368, 1273, -1, 1254, 11945, 3126, -1, 1254, 15756, 11945, -1, 1254, 15772, 15756, -1, 1253, 7374, 1254, -1, 7368, 7374, 1253, -1, 1254, 15775, 15772, -1, 7374, 15776, 1254, -1, 1254, 15776, 15775, -1, 1855, 14445, 1866, -1, 14441, 14445, 1855, -1, 1866, 14439, 1876, -1, 14445, 14439, 1866, -1, 1876, 11379, 1893, -1, 1876, 12804, 11379, -1, 1876, 12802, 12804, -1, 14439, 12805, 1876, -1, 1876, 12803, 12802, -1, 12805, 12807, 1876, -1, 1876, 12807, 12803, -1, 1820, 14437, 1832, -1, 14438, 14437, 1820, -1, 1832, 14442, 1850, -1, 14437, 14442, 1832, -1, 1850, 14441, 1855, -1, 14442, 14441, 1850, -1, 1744, 7343, 1754, -1, 7340, 7343, 1744, -1, 1754, 7342, 1769, -1, 7343, 7342, 1754, -1, 1769, 7347, 1783, -1, 7342, 7347, 1769, -1, 1669, 7330, 1711, -1, 7331, 7330, 1669, -1, 1711, 7334, 1723, -1, 7330, 7334, 1711, -1, 1723, 7340, 1744, -1, 7334, 7340, 1723, -1, 1594, 7282, 1616, -1, 7278, 7282, 1594, -1, 1616, 7276, 1633, -1, 7282, 7276, 1616, -1, 1633, 7275, 1642, -1, 7276, 7275, 1633, -1, 1546, 7272, 1566, -1, 7273, 7272, 1546, -1, 1566, 7279, 1577, -1, 7272, 7279, 1566, -1, 1577, 7278, 1594, -1, 7279, 7278, 1577, -1, 1467, 7309, 1481, -1, 7306, 7309, 1467, -1, 1481, 7308, 1504, -1, 7309, 7308, 1481, -1, 1504, 7313, 1519, -1, 7308, 7313, 1504, -1, 1387, 7296, 1422, -1, 7297, 7296, 1387, -1, 1422, 7300, 1433, -1, 7296, 7300, 1422, -1, 1433, 7306, 1467, -1, 7300, 7306, 1433, -1, 7254, 1327, 1310, -1, 7254, 7258, 1327, -1, 1327, 7252, 1351, -1, 7258, 7252, 1327, -1, 7252, 1376, 1351, -1, 7252, 7251, 1376, -1, 11933, 1257, 1256, -1, 15726, 1257, 11933, -1, 15728, 1257, 15726, -1, 15729, 1257, 15728, -1, 15733, 1257, 15729, -1, 15733, 7249, 1257, -1, 7249, 7248, 1257, -1, 7248, 1274, 1257, -1, 7248, 7255, 1274, -1, 7255, 1310, 1274, -1, 7255, 7254, 1310, -1, 12791, 369, 11393, -1, 12792, 369, 12791, -1, 12794, 369, 12792, -1, 12795, 369, 12794, -1, 11393, 369, 368, -1, 12795, 12798, 369, -1, 12798, 14455, 369, -1, 14455, 400, 369, -1, 14455, 14453, 400, -1, 14453, 401, 400, -1, 14453, 14452, 401, -1, 14452, 1895, 401, -1, 14452, 14451, 1895, -1, 1895, 14448, 1879, -1, 14451, 14448, 1895, -1, 14448, 111, 1879, -1, 14448, 14447, 111, -1, 113, 7358, 1859, -1, 7359, 7358, 113, -1, 1859, 7356, 141, -1, 7358, 7356, 1859, -1, 141, 7354, 72, -1, 7356, 7354, 141, -1, 72, 7350, 1785, -1, 7354, 7350, 72, -1, 1785, 7344, 1786, -1, 7350, 7344, 1785, -1, 1786, 7339, 1766, -1, 7344, 7339, 1786, -1, 1749, 7293, 1750, -1, 7294, 7293, 1749, -1, 1750, 7290, 3355, -1, 7293, 7290, 1750, -1, 3355, 7289, 1680, -1, 7290, 7289, 3355, -1, 1680, 7291, 1647, -1, 7289, 7291, 1680, -1, 1647, 7285, 1648, -1, 7291, 7285, 1647, -1, 1648, 7284, 1635, -1, 7285, 7284, 1648, -1, 1614, 7324, 1613, -1, 7325, 7324, 1614, -1, 1613, 7322, 3292, -1, 7324, 7322, 1613, -1, 3292, 7320, 3265, -1, 7322, 7320, 3292, -1, 3265, 7316, 1525, -1, 7320, 7316, 3265, -1, 1525, 7310, 1510, -1, 7316, 7310, 1525, -1, 1510, 7305, 1486, -1, 7310, 7305, 1510, -1, 1472, 7269, 1473, -1, 7270, 7269, 1472, -1, 1473, 7266, 1474, -1, 7269, 7266, 1473, -1, 1474, 7265, 1449, -1, 7266, 7265, 1474, -1, 1449, 7267, 1378, -1, 7265, 7267, 1449, -1, 1378, 7261, 1357, -1, 7267, 7261, 1378, -1, 1357, 11915, 3176, -1, 1357, 15719, 11915, -1, 1357, 15735, 15719, -1, 7261, 7260, 1357, -1, 1357, 15738, 15735, -1, 7260, 15739, 1357, -1, 1357, 15739, 15738, -1, 376, 14960, 399, -1, 14965, 14960, 376, -1, 1960, 11408, 1962, -1, 1960, 14082, 11408, -1, 1960, 14080, 14082, -1, 399, 14083, 1960, -1, 14960, 14083, 399, -1, 1960, 14081, 14080, -1, 14083, 14085, 1960, -1, 1960, 14085, 14081, -1, 1868, 11020, 1880, -1, 11021, 11020, 1868, -1, 1880, 11027, 1909, -1, 11020, 11027, 1880, -1, 1909, 11026, 377, -1, 11027, 11026, 1909, -1, 102, 11016, 139, -1, 11017, 11016, 102, -1, 139, 11015, 1857, -1, 11016, 11015, 139, -1, 1857, 11021, 1868, -1, 11015, 11021, 1857, -1, 1748, 11045, 1787, -1, 11044, 11045, 1748, -1, 1787, 11051, 73, -1, 11045, 11051, 1787, -1, 73, 11050, 71, -1, 11051, 11050, 73, -1, 3350, 11040, 1746, -1, 11041, 11040, 3350, -1, 1746, 11039, 1747, -1, 11040, 11039, 1746, -1, 1747, 11044, 1748, -1, 11039, 11044, 1747, -1, 1612, 10960, 1646, -1, 10961, 10960, 1612, -1, 1646, 10967, 1679, -1, 10960, 10967, 1646, -1, 1679, 10966, 3343, -1, 10967, 10966, 1679, -1, 3283, 10956, 1610, -1, 10957, 10956, 3283, -1, 1610, 10955, 1611, -1, 10956, 10955, 1610, -1, 1611, 10961, 1612, -1, 10955, 10961, 1611, -1, 1485, 10984, 1508, -1, 10985, 10984, 1485, -1, 1508, 10991, 3264, -1, 10984, 10991, 1508, -1, 3264, 10990, 3276, -1, 10991, 10990, 3264, -1, 10981, 1470, 1447, -1, 10981, 10980, 1470, -1, 1470, 10979, 1471, -1, 10980, 10979, 1470, -1, 10979, 1485, 1471, -1, 10979, 10985, 1485, -1, 11896, 1356, 1354, -1, 16984, 1356, 11896, -1, 16986, 1356, 16984, -1, 16987, 1356, 16986, -1, 16991, 1356, 16987, -1, 10996, 1356, 16991, -1, 1356, 10995, 1448, -1, 10996, 10995, 1356, -1, 10995, 1446, 1448, -1, 10995, 11003, 1446, -1, 12752, 1362, 11636, -1, 12753, 1362, 12752, -1, 12755, 1362, 12753, -1, 12756, 1362, 12755, -1, 11636, 1362, 3184, -1, 12756, 12759, 1362, -1, 12759, 14435, 1362, -1, 14435, 1331, 1362, -1, 14435, 14433, 1331, -1, 14433, 1276, 1331, -1, 14433, 14432, 1276, -1, 14432, 1264, 1276, -1, 14432, 14431, 1264, -1, 1264, 14428, 1233, -1, 14431, 14428, 1264, -1, 14428, 1234, 1233, -1, 14428, 14427, 1234, -1, 1185, 7218, 1174, -1, 7219, 7218, 1185, -1, 1174, 7216, 1175, -1, 7218, 7216, 1174, -1, 1175, 7214, 1128, -1, 7216, 7214, 1175, -1, 1128, 7210, 1111, -1, 7214, 7210, 1128, -1, 1111, 7204, 1112, -1, 7210, 7204, 1111, -1, 1112, 7199, 1051, -1, 7204, 7199, 1112, -1, 1048, 7187, 1053, -1, 7188, 7187, 1048, -1, 1053, 7185, 1054, -1, 7187, 7185, 1053, -1, 1054, 7184, 994, -1, 7185, 7184, 1054, -1, 994, 7183, 970, -1, 7184, 7183, 994, -1, 970, 7179, 971, -1, 7183, 7179, 970, -1, 971, 7178, 898, -1, 7179, 7178, 971, -1, 897, 7160, 909, -1, 7161, 7160, 897, -1, 909, 7158, 910, -1, 7160, 7158, 909, -1, 910, 7156, 845, -1, 7158, 7156, 910, -1, 845, 7152, 831, -1, 7156, 7152, 845, -1, 831, 7146, 810, -1, 7152, 7146, 831, -1, 810, 7141, 788, -1, 7146, 7141, 810, -1, 779, 7245, 750, -1, 7246, 7245, 779, -1, 750, 7242, 751, -1, 7245, 7242, 750, -1, 751, 7241, 748, -1, 7242, 7241, 751, -1, 748, 7243, 694, -1, 7241, 7243, 748, -1, 694, 7237, 677, -1, 7243, 7237, 694, -1, 677, 12007, 864, -1, 677, 15682, 12007, -1, 677, 15698, 15682, -1, 7237, 7236, 677, -1, 677, 15701, 15698, -1, 7236, 15702, 677, -1, 677, 15702, 15701, -1, 3182, 14380, 1332, -1, 14385, 14380, 3182, -1, 1359, 11649, 1360, -1, 1359, 12648, 11649, -1, 1359, 12646, 12648, -1, 1332, 12649, 1359, -1, 14380, 12649, 1332, -1, 1359, 12647, 12646, -1, 12649, 12651, 1359, -1, 1359, 12651, 12647, -1, 1209, 6861, 1235, -1, 6860, 6861, 1209, -1, 1235, 6867, 1278, -1, 6861, 6867, 1235, -1, 1278, 6866, 3174, -1, 6867, 6866, 1278, -1, 3120, 6856, 1173, -1, 6857, 6856, 3120, -1, 1173, 6855, 1189, -1, 6856, 6855, 1173, -1, 1189, 6860, 1209, -1, 6855, 6860, 1189, -1, 1067, 6837, 1113, -1, 6836, 6837, 1067, -1, 1113, 6843, 1129, -1, 6837, 6843, 1113, -1, 1129, 6842, 3112, -1, 6843, 6842, 1129, -1, 2711, 6832, 1056, -1, 6833, 6832, 2711, -1, 1056, 6831, 1066, -1, 6832, 6831, 1056, -1, 1066, 6836, 1067, -1, 6831, 6836, 1066, -1, 932, 6812, 972, -1, 6813, 6812, 932, -1, 972, 6819, 995, -1, 6812, 6819, 972, -1, 995, 6818, 2644, -1, 6819, 6818, 995, -1, 2099, 6808, 911, -1, 6809, 6808, 2099, -1, 911, 6807, 931, -1, 6808, 6807, 911, -1, 931, 6813, 932, -1, 6807, 6813, 931, -1, 787, 6884, 811, -1, 6885, 6884, 787, -1, 811, 6891, 846, -1, 6884, 6891, 811, -1, 846, 6890, 2046, -1, 6891, 6890, 846, -1, 6881, 749, 1550, -1, 6881, 6880, 749, -1, 749, 6879, 778, -1, 6880, 6879, 749, -1, 6879, 787, 778, -1, 6879, 6885, 787, -1, 12012, 676, 674, -1, 15578, 676, 12012, -1, 15580, 676, 15578, -1, 15581, 676, 15580, -1, 15585, 676, 15581, -1, 6896, 676, 15585, -1, 676, 6895, 695, -1, 6896, 6895, 676, -1, 6895, 1434, 695, -1, 6895, 6903, 1434, -1, 11614, 1262, 3139, -1, 12712, 1262, 11614, -1, 12713, 1262, 12712, -1, 12715, 1262, 12713, -1, 12716, 1262, 12715, -1, 12719, 1262, 12716, -1, 1262, 14409, 1230, -1, 12719, 14409, 1262, -1, 14409, 1204, 1230, -1, 14409, 14411, 1204, -1, 7029, 1163, 1165, -1, 7029, 7028, 1163, -1, 1163, 7027, 2940, -1, 7028, 7027, 1163, -1, 7027, 2941, 2940, -1, 7027, 7045, 2941, -1, 7045, 1097, 2941, -1, 7045, 7039, 1097, -1, 1097, 7023, 1078, -1, 7039, 7023, 1097, -1, 1078, 7025, 1070, -1, 7023, 7025, 1078, -1, 1039, 7050, 1040, -1, 7053, 7050, 1039, -1, 1040, 7052, 951, -1, 7050, 7052, 1040, -1, 951, 7069, 952, -1, 7052, 7069, 951, -1, 952, 7063, 953, -1, 7069, 7063, 952, -1, 953, 7047, 955, -1, 7063, 7047, 953, -1, 955, 7049, 934, -1, 7047, 7049, 955, -1, 890, 7110, 889, -1, 7113, 7110, 890, -1, 889, 7112, 795, -1, 7110, 7112, 889, -1, 795, 7129, 796, -1, 7112, 7129, 795, -1, 796, 7123, 797, -1, 7129, 7123, 796, -1, 797, 7107, 801, -1, 7123, 7107, 797, -1, 801, 7109, 776, -1, 7107, 7109, 801, -1, 746, 7086, 740, -1, 7089, 7086, 746, -1, 740, 7088, 1041, -1, 7086, 7088, 740, -1, 1041, 7105, 1042, -1, 7088, 7105, 1041, -1, 1042, 7099, 688, -1, 7105, 7099, 1042, -1, 688, 7083, 668, -1, 7099, 7083, 688, -1, 668, 7085, 643, -1, 7083, 7085, 668, -1, 617, 7076, 467, -1, 7074, 7076, 617, -1, 414, 11977, 415, -1, 414, 15645, 11977, -1, 414, 15661, 15645, -1, 467, 7082, 414, -1, 7076, 7082, 467, -1, 414, 15664, 15661, -1, 7082, 15665, 414, -1, 414, 15665, 15664, -1, 1180, 14425, 1202, -1, 14421, 14425, 1180, -1, 1202, 14419, 1259, -1, 14425, 14419, 1202, -1, 1259, 11620, 1260, -1, 1259, 12765, 11620, -1, 1259, 12763, 12765, -1, 14419, 12766, 1259, -1, 1259, 12764, 12763, -1, 12766, 12768, 1259, -1, 1259, 12768, 12764, -1, 1160, 14417, 1161, -1, 14418, 14417, 1160, -1, 1161, 14422, 1162, -1, 14417, 14422, 1161, -1, 1162, 14421, 1180, -1, 14422, 14421, 1162, -1, 1064, 7203, 1069, -1, 7200, 7203, 1064, -1, 1069, 7202, 1079, -1, 7203, 7202, 1069, -1, 1079, 7207, 1098, -1, 7202, 7207, 1079, -1, 992, 7190, 1043, -1, 7191, 7190, 992, -1, 1043, 7194, 1044, -1, 7190, 7194, 1043, -1, 1044, 7200, 1064, -1, 7194, 7200, 1044, -1, 913, 7176, 935, -1, 7172, 7176, 913, -1, 935, 7170, 956, -1, 7176, 7170, 935, -1, 956, 7169, 950, -1, 7170, 7169, 956, -1, 848, 7166, 891, -1, 7167, 7166, 848, -1, 891, 7173, 892, -1, 7166, 7173, 891, -1, 892, 7172, 913, -1, 7173, 7172, 892, -1, 772, 7145, 781, -1, 7142, 7145, 772, -1, 781, 7144, 802, -1, 7145, 7144, 781, -1, 802, 7149, 799, -1, 7144, 7149, 802, -1, 741, 7132, 743, -1, 7133, 7132, 741, -1, 743, 7136, 745, -1, 7132, 7136, 743, -1, 745, 7142, 772, -1, 7136, 7142, 745, -1, 7230, 650, 642, -1, 7230, 7234, 650, -1, 650, 7228, 667, -1, 7234, 7228, 650, -1, 7228, 687, 667, -1, 7228, 7227, 687, -1, 11990, 573, 574, -1, 15689, 573, 11990, -1, 15691, 573, 15689, -1, 15692, 573, 15691, -1, 15696, 573, 15692, -1, 15696, 7225, 573, -1, 7225, 7224, 573, -1, 7224, 618, 573, -1, 7224, 7231, 618, -1, 7231, 642, 618, -1, 7231, 7230, 642, -1, 12674, 1602, 11668, -1, 12675, 1602, 12674, -1, 12677, 1602, 12675, -1, 12678, 1602, 12677, -1, 11668, 1602, 3273, -1, 12678, 12681, 1602, -1, 12681, 14407, 1602, -1, 14407, 1569, 1602, -1, 14407, 14405, 1569, -1, 14405, 1551, 1569, -1, 14405, 14404, 1551, -1, 14404, 1516, 1551, -1, 14404, 14403, 1516, -1, 1516, 14400, 1514, -1, 14403, 14400, 1516, -1, 14400, 3212, 1514, -1, 14400, 14399, 3212, -1, 3213, 6994, 1429, -1, 6995, 6994, 3213, -1, 1429, 6992, 1417, -1, 6994, 6992, 1429, -1, 1417, 6990, 1408, -1, 6992, 6990, 1417, -1, 1408, 6986, 1365, -1, 6990, 6986, 1408, -1, 1365, 6980, 1366, -1, 6986, 6980, 1365, -1, 1366, 6975, 1280, -1, 6980, 6975, 1366, -1, 1282, 7021, 1289, -1, 7022, 7021, 1282, -1, 1289, 7019, 1271, -1, 7021, 7019, 1289, -1, 1271, 7018, 1247, -1, 7019, 7018, 1271, -1, 1247, 7017, 1200, -1, 7018, 7017, 1247, -1, 1200, 7013, 1198, -1, 7017, 7013, 1200, -1, 1198, 7012, 1134, -1, 7013, 7012, 1198, -1, 1136, 6936, 1139, -1, 6937, 6936, 1136, -1, 1139, 6934, 1126, -1, 6936, 6934, 1139, -1, 1126, 6932, 1116, -1, 6934, 6932, 1126, -1, 1116, 6928, 1075, -1, 6932, 6928, 1116, -1, 1075, 6922, 1072, -1, 6928, 6922, 1075, -1, 1072, 6917, 2477, -1, 6922, 6917, 1072, -1, 2387, 6963, 1004, -1, 6964, 6963, 2387, -1, 1004, 6960, 988, -1, 6963, 6960, 1004, -1, 988, 6959, 966, -1, 6960, 6959, 988, -1, 966, 6961, 941, -1, 6959, 6961, 966, -1, 941, 6955, 939, -1, 6961, 6955, 941, -1, 939, 12019, 1964, -1, 939, 15608, 12019, -1, 939, 15624, 15608, -1, 6955, 6954, 939, -1, 939, 15627, 15624, -1, 6954, 15628, 939, -1, 939, 15628, 15627, -1, 1568, 14464, 1579, -1, 14469, 14464, 1568, -1, 1603, 11287, 3287, -1, 1603, 12882, 11287, -1, 1603, 12880, 12882, -1, 1579, 12883, 1603, -1, 14464, 12883, 1579, -1, 1603, 12881, 12880, -1, 12883, 12885, 1603, -1, 1603, 12885, 12881, -1, 1512, 7533, 1513, -1, 7532, 7533, 1512, -1, 1513, 7539, 1527, -1, 7533, 7539, 1513, -1, 1527, 7538, 1549, -1, 7539, 7538, 1527, -1, 1418, 7528, 1430, -1, 7529, 7528, 1418, -1, 1430, 7527, 1444, -1, 7528, 7527, 1430, -1, 1444, 7532, 1512, -1, 7527, 7532, 1444, -1, 1314, 7484, 1364, -1, 7485, 7484, 1314, -1, 1364, 7491, 1382, -1, 7484, 7491, 1364, -1, 1382, 7490, 1407, -1, 7491, 7490, 1382, -1, 1269, 7480, 1285, -1, 7481, 7480, 1269, -1, 1285, 7479, 1313, -1, 7480, 7479, 1285, -1, 1313, 7485, 1314, -1, 7479, 7485, 1313, -1, 1149, 7508, 1199, -1, 7509, 7508, 1149, -1, 1199, 7515, 1227, -1, 7508, 7515, 1199, -1, 1227, 7514, 1246, -1, 7515, 7514, 1227, -1, 1117, 7504, 1140, -1, 7505, 7504, 1117, -1, 1140, 7503, 1150, -1, 7504, 7503, 1140, -1, 1150, 7509, 1149, -1, 7503, 7509, 1150, -1, 1031, 7569, 1074, -1, 7568, 7569, 1031, -1, 1074, 7575, 1081, -1, 7569, 7575, 1074, -1, 1081, 7574, 1115, -1, 7575, 7574, 1081, -1, 7565, 1003, 965, -1, 7565, 7564, 1003, -1, 1003, 7563, 1032, -1, 7564, 7563, 1003, -1, 7563, 1031, 1032, -1, 7563, 7568, 1031, -1, 12009, 943, 942, -1, 15800, 943, 12009, -1, 15802, 943, 15800, -1, 15803, 943, 15802, -1, 15807, 943, 15803, -1, 7544, 943, 15807, -1, 943, 7543, 944, -1, 7544, 7543, 943, -1, 7543, 964, 944, -1, 7543, 7551, 964, -1, 11657, 1459, 3227, -1, 12634, 1459, 11657, -1, 12635, 1459, 12634, -1, 12637, 1459, 12635, -1, 12638, 1459, 12637, -1, 12641, 1459, 12638, -1, 1459, 14381, 1460, -1, 12641, 14381, 1459, -1, 14381, 1477, 1460, -1, 14381, 14383, 1477, -1, 6853, 1346, 1436, -1, 6853, 6852, 1346, -1, 1346, 6851, 1347, -1, 6852, 6851, 1346, -1, 6851, 1324, 1347, -1, 6851, 6869, 1324, -1, 6869, 1308, 1324, -1, 6869, 6863, 1308, -1, 1308, 6847, 1307, -1, 6863, 6847, 1308, -1, 1307, 6849, 1320, -1, 6847, 6849, 1307, -1, 1300, 6826, 3129, -1, 6829, 6826, 1300, -1, 3129, 6828, 1169, -1, 6826, 6828, 3129, -1, 1169, 6845, 1170, -1, 6828, 6845, 1169, -1, 1170, 6839, 1171, -1, 6845, 6839, 1170, -1, 1171, 6823, 3113, -1, 6839, 6823, 1171, -1, 3113, 6825, 1155, -1, 6823, 6825, 3113, -1, 1145, 6802, 2782, -1, 6805, 6802, 1145, -1, 2782, 6804, 1060, -1, 6802, 6804, 2782, -1, 1060, 6821, 1061, -1, 6804, 6821, 1060, -1, 1061, 6815, 1058, -1, 6821, 6815, 1061, -1, 1058, 6799, 2650, -1, 6815, 6799, 1058, -1, 2650, 6801, 1024, -1, 6799, 6801, 2650, -1, 1020, 6874, 915, -1, 6877, 6874, 1020, -1, 915, 6876, 916, -1, 6874, 6876, 915, -1, 916, 6893, 886, -1, 6876, 6893, 916, -1, 886, 6887, 873, -1, 6893, 6887, 886, -1, 873, 6871, 871, -1, 6887, 6871, 873, -1, 871, 6873, 865, -1, 6871, 6873, 871, -1, 858, 6900, 753, -1, 6898, 6900, 858, -1, 754, 12021, 1419, -1, 754, 15571, 12021, -1, 754, 15587, 15571, -1, 753, 6906, 754, -1, 6900, 6906, 753, -1, 754, 15590, 15587, -1, 6906, 15591, 754, -1, 754, 15591, 15590, -1, 1439, 14397, 1476, -1, 14393, 14397, 1439, -1, 1476, 14391, 1461, -1, 14397, 14391, 1476, -1, 1461, 11663, 1458, -1, 1461, 12687, 11663, -1, 1461, 12685, 12687, -1, 14391, 12688, 1461, -1, 1461, 12686, 12685, -1, 12688, 12690, 1461, -1, 1461, 12690, 12686, -1, 1345, 14389, 1437, -1, 14390, 14389, 1345, -1, 1437, 14394, 1438, -1, 14389, 14394, 1437, -1, 1438, 14393, 1439, -1, 14394, 14393, 1438, -1, 1299, 6979, 1321, -1, 6976, 6979, 1299, -1, 1321, 6978, 1305, -1, 6979, 6978, 1321, -1, 1305, 6983, 1306, -1, 6978, 6983, 1305, -1, 1168, 6966, 1297, -1, 6967, 6966, 1168, -1, 1297, 6970, 1298, -1, 6966, 6970, 1297, -1, 1298, 6976, 1299, -1, 6970, 6976, 1298, -1, 1144, 7010, 1154, -1, 7006, 7010, 1144, -1, 1154, 7004, 3116, -1, 7010, 7004, 1154, -1, 3116, 7003, 1167, -1, 7004, 7003, 3116, -1, 1062, 7000, 1142, -1, 7001, 7000, 1062, -1, 1142, 7007, 1143, -1, 7000, 7007, 1142, -1, 1143, 7006, 1144, -1, 7007, 7006, 1143, -1, 1023, 6921, 1037, -1, 6918, 6921, 1023, -1, 1037, 6920, 2674, -1, 6921, 6920, 1037, -1, 2674, 6925, 1059, -1, 6920, 6925, 2674, -1, 887, 6908, 1021, -1, 6909, 6908, 887, -1, 1021, 6912, 1022, -1, 6908, 6912, 1021, -1, 1022, 6918, 1023, -1, 6912, 6918, 1022, -1, 6948, 884, 863, -1, 6948, 6952, 884, -1, 884, 6946, 872, -1, 6952, 6946, 884, -1, 6946, 874, 872, -1, 6946, 6945, 874, -1, 12023, 759, 756, -1, 15615, 759, 12023, -1, 15617, 759, 15615, -1, 15618, 759, 15617, -1, 15622, 759, 15618, -1, 15622, 6943, 759, -1, 6943, 6942, 759, -1, 6942, 859, 759, -1, 6942, 6949, 859, -1, 6949, 863, 859, -1, 6949, 6948, 863, -1, 12597, 18650, 11566, -1, 12598, 18650, 12597, -1, 12600, 18650, 12598, -1, 12601, 18650, 12600, -1, 11566, 18650, 11564, -1, 12601, 6706, 18650, -1, 6706, 6705, 18650, -1, 6705, 18679, 18650, -1, 6705, 6703, 18679, -1, 6703, 18680, 18679, -1, 6703, 6702, 18680, -1, 6702, 20080, 18680, -1, 6702, 6701, 20080, -1, 20080, 6697, 20066, -1, 6701, 6697, 20080, -1, 6697, 18438, 20066, -1, 6697, 6696, 18438, -1, 18440, 6736, 20046, -1, 6737, 6736, 18440, -1, 20046, 6734, 18462, -1, 6736, 6734, 20046, -1, 18462, 6732, 18409, -1, 6734, 6732, 18462, -1, 18409, 6728, 19975, -1, 6732, 6728, 18409, -1, 19975, 6722, 19976, -1, 6728, 6722, 19975, -1, 19976, 6717, 19955, -1, 6722, 6717, 19976, -1, 19939, 6763, 19938, -1, 6764, 6763, 19939, -1, 19938, 6760, 21441, -1, 6763, 6760, 19938, -1, 21441, 6759, 19874, -1, 6760, 6759, 21441, -1, 19874, 6761, 19841, -1, 6759, 6761, 19874, -1, 19841, 6755, 19842, -1, 6761, 6755, 19841, -1, 19842, 6754, 19829, -1, 6755, 6754, 19842, -1, 19803, 6794, 19804, -1, 6795, 6794, 19803, -1, 19804, 6792, 21384, -1, 6794, 6792, 19804, -1, 21384, 6790, 21365, -1, 6792, 6790, 21384, -1, 21365, 6786, 19723, -1, 6790, 6786, 21365, -1, 19723, 6780, 19706, -1, 6786, 6780, 19723, -1, 19706, 6775, 19683, -1, 6780, 6775, 19706, -1, 19669, 14378, 19670, -1, 14379, 14378, 19669, -1, 19670, 14375, 19671, -1, 14378, 14375, 19670, -1, 19671, 14374, 19653, -1, 14375, 14374, 19671, -1, 19653, 14376, 19584, -1, 14374, 14376, 19653, -1, 19584, 14370, 19566, -1, 14376, 14370, 19584, -1, 19566, 11827, 11826, -1, 19566, 15534, 11827, -1, 19566, 15550, 15534, -1, 14370, 14369, 19566, -1, 19566, 15553, 15550, -1, 14369, 15554, 19566, -1, 19566, 15554, 15553, -1, 18653, 6245, 18678, -1, 6250, 6245, 18653, -1, 20142, 11557, 11556, -1, 20142, 12470, 11557, -1, 20142, 12468, 12470, -1, 18678, 6244, 20142, -1, 6245, 6244, 18678, -1, 20142, 12469, 12468, -1, 6244, 12472, 20142, -1, 20142, 12472, 12469, -1, 20055, 6316, 20067, -1, 6317, 6316, 20055, -1, 20067, 6323, 20095, -1, 6316, 6323, 20067, -1, 20095, 6322, 18654, -1, 6323, 6322, 20095, -1, 18431, 6312, 18455, -1, 6313, 6312, 18431, -1, 18455, 6311, 20045, -1, 6312, 6311, 18455, -1, 20045, 6317, 20055, -1, 6311, 6317, 20045, -1, 19937, 6340, 19972, -1, 6341, 6340, 19937, -1, 19972, 6347, 18410, -1, 6340, 6347, 19972, -1, 18410, 6346, 18408, -1, 6347, 6346, 18410, -1, 21436, 6336, 19935, -1, 6337, 6336, 21436, -1, 19935, 6335, 19936, -1, 6336, 6335, 19935, -1, 19936, 6341, 19937, -1, 6335, 6341, 19936, -1, 19807, 6293, 19840, -1, 6292, 6293, 19807, -1, 19840, 6299, 19873, -1, 6293, 6299, 19840, -1, 19873, 6298, 21429, -1, 6299, 6298, 19873, -1, 21377, 6288, 19805, -1, 6289, 6288, 21377, -1, 19805, 6287, 19806, -1, 6288, 6287, 19805, -1, 19806, 6292, 19807, -1, 6287, 6292, 19806, -1, 19684, 6269, 19708, -1, 6268, 6269, 19684, -1, 19708, 6275, 21364, -1, 6269, 6275, 19708, -1, 21364, 6274, 21370, -1, 6275, 6274, 21364, -1, 6265, 19672, 19652, -1, 6265, 6264, 19672, -1, 19672, 6263, 19673, -1, 6264, 6263, 19672, -1, 6263, 19684, 19673, -1, 6263, 6268, 19684, -1, 11842, 19565, 11840, -1, 15393, 19565, 11842, -1, 15395, 19565, 15393, -1, 15396, 19565, 15395, -1, 15400, 19565, 15396, -1, 14297, 19565, 15400, -1, 19565, 14296, 19650, -1, 14297, 14296, 19565, -1, 14296, 19651, 19650, -1, 14296, 14304, 19651, -1, 11591, 18501, 11589, -1, 12562, 18501, 11591, -1, 12563, 18501, 12562, -1, 12565, 18501, 12563, -1, 12566, 18501, 12565, -1, 6586, 18501, 12566, -1, 18501, 6578, 20064, -1, 6586, 6578, 18501, -1, 6578, 18425, 20064, -1, 6578, 6580, 18425, -1, 6665, 20022, 18388, -1, 6665, 6664, 20022, -1, 20022, 6663, 19988, -1, 6664, 6663, 20022, -1, 6663, 19989, 19988, -1, 6663, 6681, 19989, -1, 6681, 19969, 19989, -1, 6681, 6675, 19969, -1, 19969, 6659, 19957, -1, 6675, 6659, 19969, -1, 19957, 6661, 19941, -1, 6659, 6661, 19957, -1, 19912, 6638, 19900, -1, 6641, 6638, 19912, -1, 19900, 6640, 19861, -1, 6638, 6640, 19900, -1, 19861, 6657, 19865, -1, 6640, 6657, 19861, -1, 19865, 6651, 19838, -1, 6657, 6651, 19865, -1, 19838, 6635, 19827, -1, 6651, 6635, 19838, -1, 19827, 6637, 19811, -1, 6635, 6637, 19827, -1, 19773, 6590, 19763, -1, 6593, 6590, 19773, -1, 19763, 6592, 19741, -1, 6590, 6592, 19763, -1, 19741, 6609, 19742, -1, 6592, 6609, 19741, -1, 19742, 6603, 19716, -1, 6609, 6603, 19742, -1, 19716, 6587, 19699, -1, 6603, 6587, 19716, -1, 19699, 6589, 19667, -1, 6587, 6589, 19699, -1, 19637, 6614, 19626, -1, 6617, 6614, 19637, -1, 19626, 6616, 19595, -1, 6614, 6616, 19626, -1, 19595, 6633, 19596, -1, 6616, 6633, 19595, -1, 19596, 6627, 19582, -1, 6633, 6627, 19596, -1, 19582, 6611, 19561, -1, 6627, 6611, 19582, -1, 19561, 6613, 19522, -1, 6611, 6613, 19561, -1, 19487, 14349, 19472, -1, 14347, 14349, 19487, -1, 19471, 11764, 11762, -1, 19471, 15497, 11764, -1, 19471, 15513, 15497, -1, 19472, 14355, 19471, -1, 14349, 14355, 19472, -1, 19471, 15516, 15513, -1, 14355, 15517, 19471, -1, 19471, 15517, 15516, -1, 20042, 6694, 20053, -1, 6690, 6694, 20042, -1, 20053, 6688, 20063, -1, 6694, 6688, 20053, -1, 20063, 11578, 11577, -1, 20063, 12610, 11578, -1, 20063, 12608, 12610, -1, 6688, 6687, 20063, -1, 20063, 12609, 12608, -1, 6687, 12612, 20063, -1, 20063, 12612, 12609, -1, 20009, 6684, 20021, -1, 6685, 6684, 20009, -1, 20021, 6691, 20037, -1, 6684, 6691, 20021, -1, 20037, 6690, 20042, -1, 6691, 6690, 20037, -1, 19933, 6721, 19942, -1, 6718, 6721, 19933, -1, 19942, 6720, 19958, -1, 6721, 6720, 19942, -1, 19958, 6725, 19970, -1, 6720, 6725, 19958, -1, 19860, 6708, 19899, -1, 6709, 6708, 19860, -1, 19899, 6712, 19911, -1, 6708, 6712, 19899, -1, 19911, 6718, 19933, -1, 6712, 6718, 19911, -1, 19790, 6752, 19810, -1, 6748, 6752, 19790, -1, 19810, 6746, 19826, -1, 6752, 6746, 19810, -1, 19826, 6745, 19837, -1, 6746, 6745, 19826, -1, 19745, 6742, 19764, -1, 6743, 6742, 19745, -1, 19764, 6749, 19774, -1, 6742, 6749, 19764, -1, 19774, 6748, 19790, -1, 6749, 6748, 19774, -1, 19665, 6779, 19679, -1, 6776, 6779, 19665, -1, 19679, 6778, 19701, -1, 6779, 6778, 19679, -1, 19701, 6783, 19717, -1, 6778, 6783, 19701, -1, 19594, 6766, 19625, -1, 6767, 6766, 19594, -1, 19625, 6770, 19636, -1, 6766, 6770, 19625, -1, 19636, 6776, 19665, -1, 6770, 6776, 19636, -1, 14363, 19539, 19523, -1, 14363, 14367, 19539, -1, 19539, 14361, 19563, -1, 14367, 14361, 19539, -1, 14361, 19580, 19563, -1, 14361, 14360, 19580, -1, 11775, 19473, 11776, -1, 15541, 19473, 11775, -1, 15543, 19473, 15541, -1, 15544, 19473, 15543, -1, 15548, 19473, 15544, -1, 15548, 14358, 19473, -1, 14358, 14357, 19473, -1, 14357, 19488, 19473, -1, 14357, 14364, 19488, -1, 14364, 19523, 19488, -1, 14364, 14363, 19523, -1, 11634, 19897, 11632, -1, 12527, 19897, 11634, -1, 12528, 19897, 12527, -1, 12530, 19897, 12528, -1, 12531, 19897, 12530, -1, 6550, 19897, 12531, -1, 19897, 6542, 19879, -1, 6550, 6542, 19897, -1, 6542, 19876, 19879, -1, 6542, 6544, 19876, -1, 6557, 19799, 19817, -1, 6557, 6556, 19799, -1, 19799, 6555, 19785, -1, 6556, 6555, 19799, -1, 6555, 19769, 19785, -1, 6555, 6573, 19769, -1, 6573, 19751, 19769, -1, 6573, 6567, 19751, -1, 19751, 6551, 19735, -1, 6567, 6551, 19751, -1, 19735, 6553, 19733, -1, 6551, 6553, 19735, -1, 19681, 6470, 19663, -1, 6473, 6470, 19681, -1, 19663, 6472, 19629, -1, 6470, 6472, 19663, -1, 19629, 6489, 19630, -1, 6472, 6489, 19629, -1, 19630, 6483, 19619, -1, 6489, 6483, 19630, -1, 19619, 6467, 19601, -1, 6483, 6467, 19619, -1, 19601, 6469, 19599, -1, 6467, 6469, 19601, -1, 19541, 6494, 19530, -1, 6497, 6494, 19541, -1, 19530, 6496, 19507, -1, 6494, 6496, 19530, -1, 19507, 6513, 19508, -1, 6496, 6513, 19507, -1, 19508, 6507, 19480, -1, 6513, 6507, 19508, -1, 19480, 6491, 19461, -1, 6507, 6491, 19480, -1, 19461, 6493, 19459, -1, 6491, 6493, 19461, -1, 19395, 6518, 19376, -1, 6521, 6518, 19395, -1, 19376, 6520, 19365, -1, 6518, 6520, 19376, -1, 19365, 6537, 19350, -1, 6520, 6537, 19365, -1, 19350, 6531, 19338, -1, 6537, 6531, 19350, -1, 19338, 6515, 19315, -1, 6531, 6515, 19338, -1, 19315, 6517, 19314, -1, 6515, 6517, 19315, -1, 19260, 14337, 19240, -1, 14335, 14337, 19260, -1, 19239, 11717, 11715, -1, 19239, 15460, 11717, -1, 19239, 15476, 15460, -1, 19240, 14343, 19239, -1, 14337, 14343, 19240, -1, 19239, 15479, 15476, -1, 14343, 15480, 19239, -1, 19239, 15480, 15479, -1, 21412, 6362, 19877, -1, 6358, 6362, 21412, -1, 19877, 6356, 19878, -1, 6362, 6356, 19877, -1, 19878, 11619, 11618, -1, 19878, 12505, 11619, -1, 19878, 12503, 12505, -1, 6356, 6355, 19878, -1, 19878, 12504, 12503, -1, 6355, 12507, 19878, -1, 19878, 12507, 12504, -1, 19781, 6352, 19800, -1, 6353, 6352, 19781, -1, 19800, 6359, 21402, -1, 6352, 6359, 19800, -1, 21402, 6358, 21412, -1, 6359, 6358, 21402, -1, 21355, 6447, 19734, -1, 6444, 6447, 21355, -1, 19734, 6446, 19736, -1, 6447, 6446, 19734, -1, 19736, 6451, 19752, -1, 6446, 6451, 19736, -1, 19631, 6434, 19662, -1, 6435, 6434, 19631, -1, 19662, 6438, 21345, -1, 6434, 6438, 19662, -1, 21345, 6444, 21355, -1, 6438, 6444, 21345, -1, 21306, 6420, 19600, -1, 6416, 6420, 21306, -1, 19600, 6414, 19602, -1, 6420, 6414, 19600, -1, 19602, 6413, 19620, -1, 6414, 6413, 19602, -1, 19505, 6410, 19528, -1, 6411, 6410, 19505, -1, 19528, 6417, 21295, -1, 6410, 6417, 19528, -1, 21295, 6416, 21306, -1, 6417, 6416, 21295, -1, 21262, 6389, 19460, -1, 6386, 6389, 21262, -1, 19460, 6388, 19462, -1, 6389, 6388, 19460, -1, 19462, 6393, 19481, -1, 6388, 6393, 19462, -1, 19349, 6376, 19375, -1, 6377, 6376, 19349, -1, 19375, 6380, 21253, -1, 6376, 6380, 19375, -1, 21253, 6386, 21262, -1, 6380, 6386, 21253, -1, 14315, 19312, 21087, -1, 14315, 14319, 19312, -1, 19312, 14313, 19313, -1, 14319, 14313, 19312, -1, 14313, 19337, 19313, -1, 14313, 14312, 19337, -1, 11727, 19241, 11728, -1, 15430, 19241, 11727, -1, 15432, 19241, 15430, -1, 15433, 19241, 15432, -1, 15437, 19241, 15433, -1, 15437, 14310, 19241, -1, 14310, 14309, 19241, -1, 14309, 19261, 19241, -1, 14309, 14316, 19261, -1, 14316, 21087, 19261, -1, 14316, 14315, 21087, -1, 12492, 21462, 11612, -1, 12493, 21462, 12492, -1, 12495, 21462, 12493, -1, 12496, 21462, 12495, -1, 11612, 21462, 11610, -1, 12496, 6374, 21462, -1, 6374, 6373, 21462, -1, 6373, 19984, 21462, -1, 6373, 6371, 19984, -1, 6371, 19952, 19984, -1, 6371, 6370, 19952, -1, 6370, 19950, 19952, -1, 6370, 6369, 19950, -1, 19950, 6365, 19886, -1, 6369, 6365, 19950, -1, 6365, 19887, 19886, -1, 6365, 6364, 19887, -1, 19850, 6462, 19848, -1, 6463, 6462, 19850, -1, 19848, 6460, 19846, -1, 6462, 6460, 19848, -1, 19846, 6458, 19823, -1, 6460, 6458, 19846, -1, 19823, 6454, 19824, -1, 6458, 6454, 19823, -1, 19824, 6448, 19730, -1, 6454, 6448, 19824, -1, 19730, 6443, 19731, -1, 6448, 6443, 19730, -1, 19727, 6431, 21351, -1, 6432, 6431, 19727, -1, 21351, 6429, 19721, -1, 6431, 6429, 21351, -1, 19721, 6428, 19694, -1, 6429, 6428, 19721, -1, 19694, 6427, 19693, -1, 6428, 6427, 19694, -1, 19693, 6423, 19606, -1, 6427, 6423, 19693, -1, 19606, 6422, 19608, -1, 6423, 6422, 19606, -1, 19604, 6404, 21301, -1, 6405, 6404, 19604, -1, 21301, 6402, 19587, -1, 6404, 6402, 21301, -1, 19587, 6400, 19549, -1, 6402, 6400, 19587, -1, 19549, 6396, 19548, -1, 6400, 6396, 19549, -1, 19548, 6390, 19467, -1, 6396, 6390, 19548, -1, 19467, 6385, 19434, -1, 6390, 6385, 19467, -1, 19435, 14330, 19436, -1, 14331, 14330, 19435, -1, 19436, 14327, 19430, -1, 14330, 14327, 19436, -1, 19430, 14326, 19412, -1, 14327, 14326, 19430, -1, 19412, 14328, 19410, -1, 14326, 14328, 19412, -1, 19410, 14322, 19325, -1, 14328, 14322, 19410, -1, 19325, 11740, 11736, -1, 19325, 15423, 11740, -1, 19325, 15439, 15423, -1, 14322, 14321, 19325, -1, 19325, 15442, 15439, -1, 14321, 15443, 19325, -1, 19325, 15443, 15442, -1, 19985, 6577, 20004, -1, 6582, 6577, 19985, -1, 21467, 11601, 11600, -1, 21467, 12575, 11601, -1, 21467, 12573, 12575, -1, 20004, 6576, 21467, -1, 6577, 6576, 20004, -1, 21467, 12574, 12573, -1, 6576, 12577, 21467, -1, 21467, 12577, 12574, -1, 19851, 6672, 19951, -1, 6673, 6672, 19851, -1, 19951, 6679, 19953, -1, 6672, 6679, 19951, -1, 19953, 6678, 19967, -1, 6679, 6678, 19953, -1, 19844, 6668, 19870, -1, 6669, 6668, 19844, -1, 19870, 6667, 19849, -1, 6668, 6667, 19870, -1, 19849, 6673, 19851, -1, 6667, 6673, 19849, -1, 19728, 6649, 19820, -1, 6648, 6649, 19728, -1, 19820, 6655, 19821, -1, 6649, 6655, 19820, -1, 19821, 6654, 19831, -1, 6655, 6654, 19821, -1, 19720, 6644, 19738, -1, 6645, 6644, 19720, -1, 19738, 6643, 21354, -1, 6644, 6643, 19738, -1, 21354, 6648, 19728, -1, 6643, 6648, 21354, -1, 19605, 6601, 19691, -1, 6600, 6601, 19605, -1, 19691, 6607, 19692, -1, 6601, 6607, 19691, -1, 19692, 6606, 19704, -1, 6607, 6606, 19692, -1, 19578, 6596, 19610, -1, 6597, 6596, 19578, -1, 19610, 6595, 21305, -1, 6596, 6595, 19610, -1, 21305, 6600, 19605, -1, 6595, 6600, 21305, -1, 19433, 6624, 19546, -1, 6625, 6624, 19433, -1, 19546, 6631, 19547, -1, 6624, 6631, 19546, -1, 19547, 6630, 19577, -1, 6631, 6630, 19547, -1, 6621, 19456, 19414, -1, 6621, 6620, 19456, -1, 19456, 6619, 19432, -1, 6620, 6619, 19456, -1, 6619, 19433, 19432, -1, 6619, 6625, 19433, -1, 11750, 19324, 11751, -1, 15504, 19324, 11750, -1, 15506, 19324, 15504, -1, 15507, 19324, 15506, -1, 15511, 19324, 15507, -1, 14345, 19324, 15511, -1, 19324, 14344, 19411, -1, 14345, 14344, 19324, -1, 14344, 19413, 19411, -1, 14344, 14352, 19413, -1, 11547, 19063, 11545, -1, 12458, 19063, 11547, -1, 12459, 19063, 12458, -1, 12461, 19063, 12459, -1, 12462, 19063, 12461, -1, 6254, 19063, 12462, -1, 19063, 6246, 19148, -1, 6254, 6246, 19063, -1, 6246, 18833, 19148, -1, 6246, 6248, 18833, -1, 6309, 18667, 18743, -1, 6309, 6308, 18667, -1, 18667, 6307, 18620, -1, 6308, 6307, 18667, -1, 6307, 18621, 18620, -1, 6307, 6325, 18621, -1, 6325, 18609, 18621, -1, 6325, 6319, 18609, -1, 18609, 6303, 18610, -1, 6319, 6303, 18609, -1, 18610, 6305, 18562, -1, 6303, 6305, 18610, -1, 18520, 6330, 18470, -1, 6333, 6330, 18520, -1, 18470, 6332, 18471, -1, 6330, 6332, 18470, -1, 18471, 6349, 20039, -1, 6332, 6349, 18471, -1, 20039, 6343, 18421, -1, 6349, 6343, 20039, -1, 18421, 6327, 18422, -1, 6343, 6327, 18421, -1, 18422, 6329, 20027, -1, 6327, 6329, 18422, -1, 20002, 6282, 20001, -1, 6285, 6282, 20002, -1, 20001, 6284, 19926, -1, 6282, 6284, 20001, -1, 19926, 6301, 19927, -1, 6284, 6301, 19926, -1, 19927, 6295, 19923, -1, 6301, 6295, 19927, -1, 19923, 6279, 19931, -1, 6295, 6279, 19923, -1, 19931, 6281, 19903, -1, 6279, 6281, 19931, -1, 19884, 6258, 19883, -1, 6261, 6258, 19884, -1, 19883, 6260, 21374, -1, 6258, 6260, 19883, -1, 21374, 6277, 21375, -1, 6260, 6277, 21374, -1, 21375, 6271, 21371, -1, 6277, 6271, 21375, -1, 21371, 6255, 19788, -1, 6271, 6255, 21371, -1, 19788, 6257, 19754, -1, 6255, 6257, 19788, -1, 19755, 14301, 19655, -1, 14299, 14301, 19755, -1, 19656, 11864, 11862, -1, 19656, 15386, 11864, -1, 19656, 15402, 15386, -1, 19655, 14307, 19656, -1, 14301, 14307, 19655, -1, 19656, 15405, 15402, -1, 14307, 15406, 19656, -1, 19656, 15406, 15405, -1, 20194, 6138, 20204, -1, 6134, 6138, 20194, -1, 20204, 6132, 19146, -1, 6138, 6132, 20204, -1, 19146, 11538, 11537, -1, 19146, 12435, 11538, -1, 19146, 12433, 12435, -1, 6132, 6131, 19146, -1, 19146, 12434, 12433, -1, 6131, 12437, 19146, -1, 19146, 12437, 12434, -1, 18666, 6128, 18760, -1, 6129, 6128, 18666, -1, 18760, 6135, 20182, -1, 6128, 6135, 18760, -1, 20182, 6134, 20194, -1, 6135, 6134, 20182, -1, 20108, 6165, 20116, -1, 6162, 6165, 20108, -1, 20116, 6164, 18608, -1, 6165, 6164, 20116, -1, 18608, 6169, 18619, -1, 6164, 6169, 18608, -1, 18469, 6152, 18524, -1, 6153, 6152, 18469, -1, 18524, 6156, 20098, -1, 6152, 6156, 18524, -1, 20098, 6162, 20108, -1, 6156, 6162, 20098, -1, 20014, 6230, 20026, -1, 6226, 6230, 20014, -1, 20026, 6224, 18420, -1, 6230, 6224, 20026, -1, 18420, 6223, 18427, -1, 6224, 6223, 18420, -1, 19928, 6220, 19999, -1, 6221, 6220, 19928, -1, 19999, 6227, 20000, -1, 6220, 6227, 19999, -1, 20000, 6226, 20014, -1, 6227, 6226, 20000, -1, 19902, 6199, 19909, -1, 6196, 6199, 19902, -1, 19909, 6198, 19930, -1, 6199, 6198, 19909, -1, 19930, 6203, 19924, -1, 6198, 6203, 19930, -1, 21385, 6186, 19881, -1, 6187, 6186, 21385, -1, 19881, 6190, 19882, -1, 6186, 6190, 19881, -1, 19882, 6196, 19902, -1, 6190, 6196, 19882, -1, 14279, 19771, 19760, -1, 14279, 14283, 19771, -1, 19771, 14277, 19787, -1, 14283, 14277, 19771, -1, 14277, 21373, 19787, -1, 14277, 14276, 21373, -1, 11875, 21337, 11873, -1, 15356, 21337, 11875, -1, 15358, 21337, 15356, -1, 15359, 21337, 15358, -1, 15363, 21337, 15359, -1, 15363, 14274, 21337, -1, 14274, 14273, 21337, -1, 14273, 19759, 21337, -1, 14273, 14280, 19759, -1, 14280, 19760, 19759, -1, 14280, 14279, 19760, -1, 12422, 19597, 11527, -1, 12423, 19597, 12422, -1, 12425, 19597, 12423, -1, 12426, 19597, 12425, -1, 11527, 19597, 11525, -1, 12426, 6150, 19597, -1, 6150, 6149, 19597, -1, 6149, 20261, 19597, -1, 6149, 6147, 20261, -1, 6147, 19591, 20261, -1, 6147, 6146, 19591, -1, 6146, 20230, 19591, -1, 6146, 6145, 20230, -1, 20230, 6141, 19020, -1, 6145, 6141, 20230, -1, 6141, 18876, 19020, -1, 6141, 6140, 18876, -1, 18877, 6180, 20187, -1, 6181, 6180, 18877, -1, 20187, 6178, 20177, -1, 6180, 6178, 20187, -1, 20177, 6176, 18858, -1, 6178, 6176, 20177, -1, 18858, 6172, 20144, -1, 6176, 6172, 18858, -1, 20144, 6166, 18603, -1, 6172, 6166, 20144, -1, 18603, 6161, 18601, -1, 6166, 6161, 18603, -1, 18602, 6241, 20102, -1, 6242, 6241, 18602, -1, 20102, 6238, 20089, -1, 6241, 6238, 20102, -1, 20089, 6237, 18575, -1, 6238, 6237, 20089, -1, 18575, 6239, 20050, -1, 6237, 6239, 18575, -1, 20050, 6233, 18398, -1, 6239, 6233, 20050, -1, 18398, 6232, 18395, -1, 6233, 6232, 18398, -1, 18396, 6214, 20012, -1, 6215, 6214, 18396, -1, 20012, 6212, 19991, -1, 6214, 6212, 20012, -1, 19991, 6210, 19978, -1, 6212, 6210, 19991, -1, 19978, 6206, 19947, -1, 6210, 6206, 19978, -1, 19947, 6200, 19946, -1, 6206, 6200, 19947, -1, 19946, 6195, 21415, -1, 6200, 6195, 19946, -1, 19918, 14294, 19891, -1, 14295, 14294, 19918, -1, 19891, 14291, 19855, -1, 14294, 14291, 19891, -1, 19855, 14290, 19834, -1, 14291, 14290, 19855, -1, 19834, 14292, 19813, -1, 14290, 14292, 19834, -1, 19813, 14286, 19793, -1, 14292, 14286, 19813, -1, 19793, 11890, 11889, -1, 19793, 15349, 11890, -1, 19793, 15365, 15349, -1, 14286, 14285, 19793, -1, 19793, 15368, 15365, -1, 14285, 15369, 19793, -1, 19793, 15369, 15368, -1, 19590, 6021, 20271, -1, 6026, 6021, 19590, -1, 20287, 11512, 11511, -1, 20287, 12400, 11512, -1, 20287, 12398, 12400, -1, 20271, 6020, 20287, -1, 6021, 6020, 20271, -1, 20287, 12399, 12398, -1, 6020, 12402, 20287, -1, 20287, 12402, 12399, -1, 19009, 6044, 20229, -1, 6045, 6044, 19009, -1, 20229, 6051, 20239, -1, 6044, 6051, 20229, -1, 20239, 6050, 19592, -1, 6051, 6050, 20239, -1, 18857, 6040, 20189, -1, 6041, 6040, 18857, -1, 20189, 6039, 20196, -1, 6040, 6039, 20189, -1, 20196, 6045, 19009, -1, 6039, 6045, 20196, -1, 18600, 6116, 20145, -1, 6117, 6116, 18600, -1, 20145, 6123, 20162, -1, 6116, 6123, 20145, -1, 20162, 6122, 18859, -1, 6123, 6122, 20162, -1, 18574, 6112, 20090, -1, 6113, 6112, 18574, -1, 20090, 6111, 20112, -1, 6112, 6111, 20090, -1, 20112, 6117, 18600, -1, 6111, 6117, 20112, -1, 18394, 6093, 20051, -1, 6092, 6093, 18394, -1, 20051, 6099, 20061, -1, 6093, 6099, 20051, -1, 20061, 6098, 18576, -1, 6099, 6098, 20061, -1, 18392, 6088, 19992, -1, 6089, 6088, 18392, -1, 19992, 6087, 20024, -1, 6088, 6087, 19992, -1, 20024, 6092, 18394, -1, 6087, 6092, 20024, -1, 19917, 6069, 19944, -1, 6068, 6069, 19917, -1, 19944, 6075, 19960, -1, 6069, 6075, 19944, -1, 19960, 6074, 18390, -1, 6075, 6074, 19960, -1, 6065, 19854, 19853, -1, 6065, 6064, 19854, -1, 19854, 6063, 19905, -1, 6064, 6063, 19854, -1, 6063, 19917, 19905, -1, 6063, 6068, 19917, -1, 11908, 19794, 11906, -1, 15319, 19794, 11908, -1, 15321, 19794, 15319, -1, 15322, 19794, 15321, -1, 15326, 19794, 15322, -1, 14261, 19794, 15326, -1, 19794, 14260, 19815, -1, 14261, 14260, 19794, -1, 14260, 19833, 19815, -1, 14260, 14268, 19833, -1, 11499, 20124, 11497, -1, 12388, 20124, 11499, -1, 12389, 20124, 12388, -1, 12391, 20124, 12389, -1, 12392, 20124, 12391, -1, 6030, 20124, 12392, -1, 20124, 6022, 20151, -1, 6030, 6022, 20124, -1, 6022, 19948, 20151, -1, 6022, 6024, 19948, -1, 6037, 19867, 19845, -1, 6037, 6036, 19867, -1, 19867, 6035, 20278, -1, 6036, 6035, 19867, -1, 6035, 20263, 20278, -1, 6035, 6053, 20263, -1, 6053, 20249, 20263, -1, 6053, 6047, 20249, -1, 20249, 6031, 19457, -1, 6047, 6031, 20249, -1, 19457, 6033, 19237, -1, 6031, 6033, 19457, -1, 19151, 6106, 19159, -1, 6109, 6106, 19151, -1, 19159, 6108, 20184, -1, 6106, 6108, 19159, -1, 20184, 6125, 20174, -1, 6108, 6125, 20184, -1, 20174, 6119, 20175, -1, 6125, 6119, 20174, -1, 20175, 6103, 18795, -1, 6119, 6103, 20175, -1, 18795, 6105, 18674, -1, 6103, 6105, 18795, -1, 18641, 6082, 18646, -1, 6085, 6082, 18641, -1, 18646, 6084, 20106, -1, 6082, 6084, 18646, -1, 20106, 6101, 20083, -1, 6084, 6101, 20106, -1, 20083, 6095, 20084, -1, 6101, 6095, 20083, -1, 20084, 6079, 18557, -1, 6095, 6079, 20084, -1, 18557, 6081, 18476, -1, 6079, 6081, 18557, -1, 18444, 6058, 18445, -1, 6061, 6058, 18444, -1, 18445, 6060, 20019, -1, 6058, 6060, 18445, -1, 20019, 6077, 19997, -1, 6060, 6077, 20019, -1, 19997, 6071, 19980, -1, 6077, 6071, 19997, -1, 19980, 6055, 19981, -1, 6071, 6055, 19980, -1, 19981, 6057, 21444, -1, 6055, 6057, 19981, -1, 19907, 14265, 19893, -1, 14263, 14265, 19907, -1, 19894, 11919, 11917, -1, 19894, 15312, 11919, -1, 19894, 15328, 15312, -1, 19893, 14271, 19894, -1, 14265, 14271, 19893, -1, 19894, 15331, 15328, -1, 14271, 15332, 19894, -1, 19894, 15332, 15331, -1, 20092, 6006, 20150, -1, 6002, 6006, 20092, -1, 20150, 6000, 20188, -1, 6006, 6000, 20150, -1, 20188, 11486, 11485, -1, 20188, 12365, 11486, -1, 20188, 12363, 12365, -1, 6000, 5999, 20188, -1, 20188, 12364, 12363, -1, 5999, 12367, 20188, -1, 20188, 12367, 12364, -1, 19757, 5996, 19866, -1, 5997, 5996, 19757, -1, 19866, 6003, 19987, -1, 5996, 6003, 19866, -1, 19987, 6002, 20092, -1, 6003, 6002, 19987, -1, 19391, 5951, 19455, -1, 5948, 5951, 19391, -1, 19455, 5950, 19491, -1, 5951, 5950, 19455, -1, 19491, 5955, 19758, -1, 5950, 5955, 19491, -1, 20185, 5938, 19158, -1, 5939, 5938, 20185, -1, 19158, 5942, 19271, -1, 5938, 5942, 19158, -1, 19271, 5948, 19391, -1, 5942, 5948, 19271, -1, 18732, 5982, 18790, -1, 5978, 5982, 18732, -1, 18790, 5976, 18826, -1, 5982, 5976, 18790, -1, 18826, 5975, 20173, -1, 5976, 5975, 18826, -1, 20105, 5972, 18645, -1, 5973, 5972, 20105, -1, 18645, 5979, 18684, -1, 5972, 5979, 18645, -1, 18684, 5978, 18732, -1, 5979, 5978, 18684, -1, 18530, 5917, 18556, -1, 5914, 5917, 18530, -1, 18556, 5916, 18566, -1, 5917, 5916, 18556, -1, 18566, 5921, 20082, -1, 5916, 5921, 18566, -1, 18370, 5904, 18443, -1, 5905, 5904, 18370, -1, 18443, 5908, 18491, -1, 5904, 5908, 18443, -1, 18491, 5914, 18530, -1, 5908, 5914, 18491, -1, 14243, 21465, 21459, -1, 14243, 14247, 21465, -1, 21465, 14241, 19982, -1, 14247, 14241, 21465, -1, 14241, 18371, 19982, -1, 14241, 14240, 18371, -1, 11930, 19895, 11928, -1, 15282, 19895, 11930, -1, 15284, 19895, 15282, -1, 15285, 19895, 15284, -1, 15289, 19895, 15285, -1, 15289, 14238, 19895, -1, 14238, 14237, 19895, -1, 14237, 21443, 19895, -1, 14237, 14244, 21443, -1, 14244, 21459, 21443, -1, 14244, 14243, 21459, -1, 12353, 20452, 11466, -1, 12354, 20452, 12353, -1, 12356, 20452, 12354, -1, 12357, 20452, 12356, -1, 11466, 20452, 11464, -1, 12357, 6018, 20452, -1, 6018, 6017, 20452, -1, 6017, 20413, 20452, -1, 6017, 6015, 20413, -1, 6015, 20394, 20413, -1, 6015, 6014, 20394, -1, 6014, 20370, 20394, -1, 6014, 6013, 20370, -1, 20370, 6009, 20104, -1, 6013, 6009, 20370, -1, 6009, 19993, 20104, -1, 6009, 6008, 19993, -1, 19995, 5966, 20086, -1, 5967, 5966, 19995, -1, 20086, 5964, 20319, -1, 5966, 5964, 20086, -1, 20319, 5962, 20313, -1, 5964, 5962, 20319, -1, 20313, 5958, 19618, -1, 5962, 5958, 20313, -1, 19618, 5952, 19441, -1, 5958, 5952, 19618, -1, 19441, 5947, 19442, -1, 5952, 5947, 19441, -1, 19428, 5993, 19426, -1, 5994, 5993, 19428, -1, 19426, 5990, 20234, -1, 5993, 5990, 19426, -1, 20234, 5989, 20225, -1, 5990, 5989, 20234, -1, 20225, 5991, 18956, -1, 5989, 5991, 20225, -1, 18956, 5985, 18770, -1, 5991, 5985, 18956, -1, 18770, 5984, 18771, -1, 5985, 5984, 18770, -1, 18768, 5932, 18766, -1, 5933, 5932, 18768, -1, 18766, 5930, 20159, -1, 5932, 5930, 18766, -1, 20159, 5928, 20152, -1, 5930, 5928, 20159, -1, 20152, 5924, 20119, -1, 5928, 5924, 20152, -1, 20119, 5918, 18545, -1, 5924, 5918, 20119, -1, 18545, 5913, 18498, -1, 5918, 5913, 18545, -1, 18472, 14258, 18541, -1, 14259, 14258, 18472, -1, 18541, 14255, 20057, -1, 14258, 14255, 18541, -1, 20057, 14254, 20048, -1, 14255, 14254, 20057, -1, 20048, 14256, 20033, -1, 14254, 14256, 20048, -1, 20033, 14250, 20031, -1, 14256, 14250, 20033, -1, 20031, 11938, 11937, -1, 20031, 15275, 11938, -1, 20031, 15291, 15275, -1, 14250, 14249, 20031, -1, 20031, 15294, 15291, -1, 14249, 15295, 20031, -1, 20031, 15295, 15294, -1, 20412, 5305, 20427, -1, 5310, 5305, 20412, -1, 20451, 11443, 11442, -1, 20451, 12155, 11443, -1, 20451, 12153, 12155, -1, 20427, 5304, 20451, -1, 5305, 5304, 20427, -1, 20451, 12154, 12153, -1, 5304, 12157, 20451, -1, 20451, 12157, 12154, -1, 20085, 5328, 20371, -1, 5329, 5328, 20085, -1, 20371, 5335, 20381, -1, 5328, 5335, 20371, -1, 20381, 5334, 20395, -1, 5335, 5334, 20381, -1, 20016, 5324, 20327, -1, 5325, 5324, 20016, -1, 20327, 5323, 20087, -1, 5324, 5323, 20327, -1, 20087, 5329, 20085, -1, 5323, 5329, 20087, -1, 19425, 5293, 19617, -1, 5292, 5293, 19425, -1, 19617, 5299, 20303, -1, 5293, 5299, 19617, -1, 20303, 5298, 20017, -1, 5299, 5298, 20303, -1, 19405, 5288, 20242, -1, 5289, 5288, 19405, -1, 20242, 5287, 19427, -1, 5288, 5287, 20242, -1, 19427, 5292, 19425, -1, 5287, 5292, 19427, -1, 18765, 5269, 18955, -1, 5268, 5269, 18765, -1, 18955, 5275, 20218, -1, 5269, 5275, 18955, -1, 20218, 5274, 19406, -1, 5275, 5274, 20218, -1, 18757, 5264, 20168, -1, 5265, 5264, 18757, -1, 20168, 5263, 18767, -1, 5264, 5263, 20168, -1, 18767, 5268, 18765, -1, 5263, 5268, 18767, -1, 18540, 5245, 20118, -1, 5244, 5245, 18540, -1, 20118, 5251, 20126, -1, 5245, 5251, 20118, -1, 20126, 5250, 18753, -1, 5251, 5250, 20126, -1, 5241, 20069, 18526, -1, 5241, 5240, 20069, -1, 20069, 5239, 18542, -1, 5240, 5239, 20069, -1, 5239, 18540, 18542, -1, 5239, 5244, 18540, -1, 11953, 20032, 11951, -1, 15060, 20032, 11953, -1, 15062, 20032, 15060, -1, 15063, 20032, 15062, -1, 15067, 20032, 15063, -1, 14129, 20032, 15067, -1, 20032, 14128, 20035, -1, 14129, 14128, 20032, -1, 14128, 18527, 20035, -1, 14128, 14136, 18527, -1, 12318, 21032, 11305, -1, 12319, 21032, 12318, -1, 12321, 21032, 12319, -1, 12322, 21032, 12321, -1, 11305, 21032, 11304, -1, 12322, 5810, 21032, -1, 5810, 5809, 21032, -1, 5809, 21008, 21032, -1, 5809, 5807, 21008, -1, 5807, 20993, 21008, -1, 5807, 5806, 20993, -1, 5806, 20960, 20993, -1, 5806, 5805, 20960, -1, 20960, 5801, 20961, -1, 5805, 5801, 20960, -1, 5801, 21359, 20961, -1, 5801, 5800, 21359, -1, 21360, 5840, 20887, -1, 5841, 5840, 21360, -1, 20887, 5838, 20877, -1, 5840, 5838, 20887, -1, 20877, 5836, 20870, -1, 5838, 5836, 20877, -1, 20870, 5832, 20836, -1, 5836, 5832, 20870, -1, 20836, 5826, 20835, -1, 5832, 5826, 20836, -1, 20835, 5821, 20761, -1, 5826, 5821, 20835, -1, 20760, 5867, 20765, -1, 5868, 5867, 20760, -1, 20765, 5864, 20752, -1, 5867, 5864, 20765, -1, 20752, 5863, 20730, -1, 5864, 5863, 20752, -1, 20730, 5865, 20694, -1, 5863, 5865, 20730, -1, 20694, 5859, 20693, -1, 5865, 5859, 20694, -1, 20693, 5858, 20638, -1, 5859, 5858, 20693, -1, 20637, 5898, 20642, -1, 5899, 5898, 20637, -1, 20642, 5896, 20629, -1, 5898, 5896, 20642, -1, 20629, 5894, 20617, -1, 5896, 5894, 20629, -1, 20617, 5890, 20583, -1, 5894, 5890, 20617, -1, 20583, 5884, 20582, -1, 5890, 5884, 20583, -1, 20582, 5879, 21046, -1, 5884, 5879, 20582, -1, 20967, 14234, 20525, -1, 14235, 14234, 20967, -1, 20525, 14231, 20508, -1, 14234, 14231, 20525, -1, 20508, 14230, 20487, -1, 14231, 14230, 20508, -1, 20487, 14232, 20464, -1, 14230, 14232, 20487, -1, 20464, 14226, 20428, -1, 14232, 14226, 20464, -1, 20428, 12057, 12055, -1, 20428, 15238, 12057, -1, 20428, 15254, 15238, -1, 14226, 14225, 20428, -1, 20428, 15257, 15254, -1, 14225, 15258, 20428, -1, 20428, 15258, 15257, -1, 21007, 5457, 21018, -1, 5462, 5457, 21007, -1, 21031, 11314, 11313, -1, 21031, 12225, 11314, -1, 21031, 12223, 12225, -1, 21018, 5456, 21031, -1, 5457, 5456, 21018, -1, 21031, 12224, 12223, -1, 5456, 12227, 21031, -1, 21031, 12227, 12224, -1, 20958, 5480, 20959, -1, 5481, 5480, 20958, -1, 20959, 5487, 20972, -1, 5480, 5487, 20959, -1, 20972, 5486, 20992, -1, 5487, 5486, 20972, -1, 20878, 5476, 20888, -1, 5477, 5476, 20878, -1, 20888, 5475, 20898, -1, 5476, 5475, 20888, -1, 20898, 5481, 20958, -1, 5475, 5481, 20898, -1, 20788, 5504, 20837, -1, 5505, 5504, 20788, -1, 20837, 5511, 20849, -1, 5504, 5511, 20837, -1, 20849, 5510, 20871, -1, 5511, 5510, 20849, -1, 20750, 5500, 20766, -1, 5501, 5500, 20750, -1, 20766, 5499, 20789, -1, 5500, 5499, 20766, -1, 20789, 5505, 20788, -1, 5499, 5505, 20789, -1, 20655, 5528, 20695, -1, 5529, 5528, 20655, -1, 20695, 5535, 20714, -1, 5528, 5535, 20695, -1, 20714, 5534, 20731, -1, 5535, 5534, 20714, -1, 20616, 5524, 20643, -1, 5525, 5524, 20616, -1, 20643, 5523, 20656, -1, 5524, 5523, 20643, -1, 20656, 5529, 20655, -1, 5523, 5529, 20656, -1, 20544, 5552, 20581, -1, 5553, 5552, 20544, -1, 20581, 5559, 20589, -1, 5552, 5559, 20581, -1, 20589, 5558, 20615, -1, 5559, 5558, 20589, -1, 5549, 20524, 20486, -1, 5549, 5548, 20524, -1, 20524, 5547, 20543, -1, 5548, 5547, 20524, -1, 5547, 20544, 20543, -1, 5547, 5553, 20544, -1, 11675, 20465, 11672, -1, 15134, 20465, 11675, -1, 15136, 20465, 15134, -1, 15137, 20465, 15136, -1, 15141, 20465, 15137, -1, 14165, 20465, 15141, -1, 20465, 14164, 20466, -1, 14165, 14164, 20465, -1, 14164, 20485, 20466, -1, 14164, 14172, 20485, -1, 11300, 20908, 11298, -1, 12283, 20908, 11300, -1, 12284, 20908, 12283, -1, 12286, 20908, 12284, -1, 12287, 20908, 12286, -1, 5738, 20908, 12287, -1, 20908, 5730, 20910, -1, 5738, 5730, 20908, -1, 5730, 20926, 20910, -1, 5730, 5732, 20926, -1, 5685, 20818, 20893, -1, 5685, 5684, 20818, -1, 20818, 5683, 20819, -1, 5684, 5683, 20818, -1, 5683, 20798, 20819, -1, 5683, 5701, 20798, -1, 5701, 20779, 20798, -1, 5701, 5695, 20779, -1, 20779, 5679, 20780, -1, 5695, 5679, 20779, -1, 20780, 5681, 20796, -1, 5679, 5681, 20780, -1, 20774, 5706, 21283, -1, 5709, 5706, 20774, -1, 21283, 5708, 20670, -1, 5706, 5708, 21283, -1, 20670, 5725, 20672, -1, 5708, 5725, 20670, -1, 20672, 5719, 20673, -1, 5725, 5719, 20672, -1, 20673, 5703, 21272, -1, 5719, 5703, 20673, -1, 21272, 5705, 20649, -1, 5703, 5705, 21272, -1, 20645, 5766, 21226, -1, 5769, 5766, 20645, -1, 21226, 5768, 20568, -1, 5766, 5768, 21226, -1, 20568, 5785, 20569, -1, 5768, 5785, 20568, -1, 20569, 5779, 20566, -1, 5785, 5779, 20569, -1, 20566, 5763, 21179, -1, 5779, 5763, 20566, -1, 21179, 5765, 20535, -1, 5763, 5765, 21179, -1, 20533, 5742, 20448, -1, 5745, 5742, 20533, -1, 20448, 5744, 20449, -1, 5742, 5744, 20448, -1, 20449, 5761, 20421, -1, 5744, 5761, 20449, -1, 20421, 5755, 20409, -1, 5761, 5755, 20421, -1, 20409, 5739, 20410, -1, 5755, 5739, 20409, -1, 20410, 5741, 20337, -1, 5739, 5741, 20410, -1, 20272, 14205, 20273, -1, 14203, 14205, 20272, -1, 20028, 12043, 12041, -1, 20028, 15201, 12043, -1, 20028, 15217, 15201, -1, 20273, 14211, 20028, -1, 14205, 14211, 20273, -1, 20028, 15220, 15217, -1, 14211, 15221, 20028, -1, 20028, 15221, 15220, -1, 20896, 5798, 20927, -1, 5794, 5798, 20896, -1, 20927, 5792, 20909, -1, 5798, 5792, 20927, -1, 20909, 11292, 11291, -1, 20909, 12330, 11292, -1, 20909, 12328, 12330, -1, 5792, 5791, 20909, -1, 20909, 12329, 12328, -1, 5791, 12332, 20909, -1, 20909, 12332, 12329, -1, 20821, 5788, 20894, -1, 5789, 5788, 20821, -1, 20894, 5795, 20895, -1, 5788, 5795, 20894, -1, 20895, 5794, 20896, -1, 5795, 5794, 20895, -1, 20777, 5825, 20795, -1, 5822, 5825, 20777, -1, 20795, 5824, 20781, -1, 5825, 5824, 20795, -1, 20781, 5829, 20782, -1, 5824, 5829, 20781, -1, 20669, 5812, 20775, -1, 5813, 5812, 20669, -1, 20775, 5816, 20776, -1, 5812, 5816, 20775, -1, 20776, 5822, 20777, -1, 5816, 5822, 20776, -1, 20648, 5856, 20658, -1, 5852, 5856, 20648, -1, 20658, 5850, 21274, -1, 5856, 5850, 20658, -1, 21274, 5849, 20671, -1, 5850, 5849, 21274, -1, 20570, 5846, 20646, -1, 5847, 5846, 20570, -1, 20646, 5853, 20647, -1, 5846, 5853, 20646, -1, 20647, 5852, 20648, -1, 5853, 5852, 20647, -1, 20537, 5883, 20550, -1, 5880, 5883, 20537, -1, 20550, 5882, 21195, -1, 5883, 5882, 20550, -1, 21195, 5887, 20567, -1, 5882, 5887, 21195, -1, 20420, 5870, 20534, -1, 5871, 5870, 20420, -1, 20534, 5874, 20536, -1, 5870, 5874, 20534, -1, 20536, 5880, 20537, -1, 5874, 5880, 20536, -1, 14219, 20417, 20400, -1, 14219, 14223, 20417, -1, 20417, 14217, 20407, -1, 14223, 14217, 20417, -1, 14217, 20408, 20407, -1, 14217, 14216, 20408, -1, 12051, 20274, 12049, -1, 15245, 20274, 12051, -1, 15247, 20274, 15245, -1, 15248, 20274, 15247, -1, 15252, 20274, 15248, -1, 15252, 14214, 20274, -1, 14214, 14213, 20274, -1, 14213, 20323, 20274, -1, 14213, 14220, 20323, -1, 14220, 20400, 20323, -1, 14220, 14219, 20400, -1, 12247, 18453, 11350, -1, 12248, 18453, 12247, -1, 12250, 18453, 12248, -1, 12251, 18453, 12250, -1, 11350, 18453, 11347, -1, 12251, 5586, 18453, -1, 5586, 5585, 18453, -1, 5585, 18481, 18453, -1, 5585, 5583, 18481, -1, 5583, 21135, 18481, -1, 5583, 5582, 21135, -1, 5582, 21136, 21135, -1, 5582, 5581, 21136, -1, 21136, 5577, 21102, -1, 5581, 5577, 21136, -1, 5577, 21101, 21102, -1, 5577, 5576, 21101, -1, 21078, 5650, 21077, -1, 5651, 5650, 21078, -1, 21077, 5648, 21072, -1, 5650, 5648, 21077, -1, 21072, 5646, 21049, -1, 5648, 5646, 21072, -1, 21049, 5642, 21050, -1, 5646, 5642, 21049, -1, 21050, 5636, 20976, -1, 5642, 5636, 21050, -1, 20976, 5631, 20977, -1, 5636, 5631, 20976, -1, 20974, 5677, 21395, -1, 5678, 5677, 20974, -1, 21395, 5674, 20966, -1, 5677, 5674, 21395, -1, 20966, 5673, 20943, -1, 5674, 5673, 20966, -1, 20943, 5675, 20944, -1, 5673, 5675, 20943, -1, 20944, 5669, 20863, -1, 5675, 5669, 20944, -1, 20863, 5668, 20864, -1, 5669, 5668, 20863, -1, 20865, 5616, 21338, -1, 5617, 5616, 20865, -1, 21338, 5614, 20847, -1, 5616, 5614, 21338, -1, 20847, 5612, 20807, -1, 5614, 5612, 20847, -1, 20807, 5608, 20808, -1, 5612, 5608, 20807, -1, 20808, 5602, 20734, -1, 5608, 5602, 20808, -1, 20734, 5597, 20704, -1, 5602, 5597, 20734, -1, 20705, 14198, 20708, -1, 14199, 14198, 20705, -1, 20708, 14195, 20702, -1, 14198, 14195, 20708, -1, 20702, 14194, 20691, -1, 14195, 14194, 20702, -1, 20691, 14196, 20688, -1, 14194, 14196, 20691, -1, 20688, 14190, 20609, -1, 14196, 14190, 20688, -1, 20609, 11710, 11708, -1, 20609, 15164, 11710, -1, 20609, 15180, 15164, -1, 14190, 14189, 20609, -1, 20609, 15183, 15180, -1, 14189, 15184, 20609, -1, 20609, 15184, 15183, -1, 18460, 8557, 18482, -1, 8562, 8557, 18460, -1, 18480, 11358, 11357, -1, 18480, 13218, 11358, -1, 18480, 13216, 13218, -1, 18482, 8556, 18480, -1, 8557, 8556, 18482, -1, 18480, 13217, 13216, -1, 8556, 13220, 18480, -1, 18480, 13220, 13217, -1, 21076, 8580, 21133, -1, 8581, 8580, 21076, -1, 21133, 8587, 21134, -1, 8580, 8587, 21133, -1, 21134, 8586, 18461, -1, 8587, 8586, 21134, -1, 21073, 8576, 21086, -1, 8577, 8576, 21073, -1, 21086, 8575, 21075, -1, 8576, 8575, 21086, -1, 21075, 8581, 21076, -1, 8575, 8581, 21075, -1, 20975, 8497, 21051, -1, 8496, 8497, 20975, -1, 21051, 8503, 21052, -1, 8497, 8503, 21051, -1, 21052, 8502, 21059, -1, 8503, 8502, 21052, -1, 20968, 8492, 20984, -1, 8493, 8492, 20968, -1, 20984, 8491, 21398, -1, 8492, 8491, 20984, -1, 21398, 8496, 20975, -1, 8491, 8496, 21398, -1, 20866, 8520, 20945, -1, 8521, 8520, 20866, -1, 20945, 8527, 20946, -1, 8520, 8527, 20945, -1, 20946, 8526, 20951, -1, 8527, 8526, 20946, -1, 20840, 8516, 20868, -1, 8517, 8516, 20840, -1, 20868, 8515, 21340, -1, 8516, 8515, 20868, -1, 21340, 8521, 20866, -1, 8515, 8521, 21340, -1, 20707, 8544, 20809, -1, 8545, 8544, 20707, -1, 20809, 8551, 20810, -1, 8544, 8551, 20809, -1, 20810, 8550, 20839, -1, 8551, 8550, 20810, -1, 8541, 20722, 20687, -1, 8541, 8540, 20722, -1, 20722, 8539, 20706, -1, 8540, 8539, 20722, -1, 8539, 20707, 20706, -1, 8539, 8545, 20707, -1, 11731, 20608, 11722, -1, 16133, 20608, 11731, -1, 16135, 20608, 16133, -1, 16136, 20608, 16135, -1, 16140, 20608, 16136, -1, 14609, 20608, 16140, -1, 20608, 14608, 20689, -1, 14609, 14608, 20608, -1, 14608, 20686, 20689, -1, 14608, 14616, 20686, -1, 11327, 21104, 11326, -1, 12213, 21104, 11327, -1, 12214, 21104, 12213, -1, 12216, 21104, 12214, -1, 12217, 21104, 12216, -1, 5466, 21104, 12217, -1, 21104, 5458, 21094, -1, 5466, 5458, 21104, -1, 5458, 21091, 21094, -1, 5458, 5460, 21091, -1, 5473, 21035, 21047, -1, 5473, 5472, 21035, -1, 21035, 5471, 21023, -1, 5472, 5471, 21035, -1, 5471, 21010, 21023, -1, 5471, 5489, 21010, -1, 5489, 20997, 21010, -1, 5489, 5483, 20997, -1, 20997, 5467, 20981, -1, 5483, 5467, 20997, -1, 20981, 5469, 20982, -1, 5467, 5469, 20981, -1, 20933, 5494, 20914, -1, 5497, 5494, 20933, -1, 20914, 5496, 20884, -1, 5494, 5496, 20914, -1, 20884, 5513, 20885, -1, 5496, 5513, 20884, -1, 20885, 5507, 20875, -1, 5513, 5507, 20885, -1, 20875, 5491, 20861, -1, 5507, 5491, 20875, -1, 20861, 5493, 20857, -1, 5491, 5493, 20861, -1, 20802, 5518, 20793, -1, 5521, 5518, 20802, -1, 20793, 5520, 20770, -1, 5518, 5520, 20793, -1, 20770, 5537, 20771, -1, 5520, 5537, 20770, -1, 20771, 5531, 20748, -1, 5537, 5531, 20771, -1, 20748, 5515, 20727, -1, 5531, 5515, 20748, -1, 20727, 5517, 20726, -1, 5515, 5517, 20727, -1, 20679, 5542, 20660, -1, 5545, 5542, 20679, -1, 20660, 5544, 20653, -1, 5542, 5544, 20660, -1, 20653, 5561, 20634, -1, 5544, 5561, 20653, -1, 20634, 5555, 20619, -1, 5561, 5555, 20634, -1, 20619, 5539, 20595, -1, 5555, 5539, 20619, -1, 20595, 5541, 20596, -1, 5539, 5541, 20595, -1, 20547, 14169, 20528, -1, 14167, 14169, 20547, -1, 20527, 11684, 11679, -1, 20527, 15127, 11684, -1, 20527, 15143, 15127, -1, 20528, 14175, 20527, -1, 14169, 14175, 20528, -1, 20527, 15146, 15143, -1, 14175, 15147, 20527, -1, 20527, 15147, 15146, -1, 21460, 5574, 21092, -1, 5570, 5574, 21460, -1, 21092, 5568, 21093, -1, 5574, 5568, 21092, -1, 21093, 11337, 11336, -1, 21093, 12260, 11337, -1, 21093, 12258, 12260, -1, 5568, 5567, 21093, -1, 21093, 12259, 12258, -1, 5567, 12262, 21093, -1, 21093, 12262, 12259, -1, 21024, 5564, 21034, -1, 5565, 5564, 21024, -1, 21034, 5571, 21450, -1, 5564, 5571, 21034, -1, 21450, 5570, 21460, -1, 5571, 5570, 21450, -1, 21401, 5635, 20979, -1, 5632, 5635, 21401, -1, 20979, 5634, 20980, -1, 5635, 5634, 20979, -1, 20980, 5639, 20995, -1, 5634, 5639, 20980, -1, 20883, 5622, 20913, -1, 5623, 5622, 20883, -1, 20913, 5626, 21391, -1, 5622, 5626, 20913, -1, 21391, 5632, 21401, -1, 5626, 5632, 21391, -1, 21341, 5666, 20858, -1, 5662, 5666, 21341, -1, 20858, 5660, 20859, -1, 5666, 5660, 20858, -1, 20859, 5659, 20874, -1, 5660, 5659, 20859, -1, 20768, 5656, 20791, -1, 5657, 5656, 20768, -1, 20791, 5663, 21329, -1, 5656, 5663, 20791, -1, 21329, 5662, 21341, -1, 5663, 5662, 21329, -1, 21296, 5601, 20724, -1, 5598, 5601, 21296, -1, 20724, 5600, 20725, -1, 5601, 5600, 20724, -1, 20725, 5605, 20747, -1, 5600, 5605, 20725, -1, 20635, 5588, 20661, -1, 5589, 5588, 20635, -1, 20661, 5592, 21289, -1, 5588, 5592, 20661, -1, 21289, 5598, 21296, -1, 5592, 5598, 21289, -1, 14183, 20597, 21246, -1, 14183, 14187, 20597, -1, 20597, 14181, 20598, -1, 14187, 14181, 20597, -1, 14181, 20621, 20598, -1, 14181, 14180, 20621, -1, 11702, 20529, 11693, -1, 15171, 20529, 11702, -1, 15173, 20529, 15171, -1, 15174, 20529, 15173, -1, 15178, 20529, 15174, -1, 15178, 14178, 20529, -1, 14178, 14177, 20529, -1, 14177, 20548, 20529, -1, 14177, 14184, 20548, -1, 14184, 21246, 20548, -1, 14184, 14183, 21246, -1, 12177, 21249, 11364, -1, 12178, 21249, 12177, -1, 12180, 21249, 12178, -1, 12181, 21249, 12180, -1, 11364, 21249, 11365, -1, 12181, 5420, 21249, -1, 5420, 5419, 21249, -1, 5419, 20625, 21249, -1, 5419, 5417, 20625, -1, 5417, 20600, 20625, -1, 5417, 5416, 20600, -1, 5416, 20539, 20600, -1, 5416, 5415, 20539, -1, 20539, 5411, 20522, -1, 5415, 5411, 20539, -1, 5411, 20521, 20522, -1, 5411, 5410, 20521, -1, 20506, 5392, 20505, -1, 5393, 5392, 20506, -1, 20505, 5390, 20495, -1, 5392, 5390, 20505, -1, 20495, 5388, 20480, -1, 5390, 5388, 20495, -1, 20480, 5384, 20403, -1, 5388, 5384, 20480, -1, 20403, 5378, 20405, -1, 5384, 5378, 20403, -1, 20405, 5373, 20288, -1, 5378, 5373, 20405, -1, 20290, 5361, 20305, -1, 5362, 5361, 20290, -1, 20305, 5359, 20306, -1, 5361, 5359, 20305, -1, 20306, 5358, 20155, -1, 5359, 5358, 20306, -1, 20155, 5357, 20147, -1, 5358, 5357, 20155, -1, 20147, 5353, 20317, -1, 5357, 5353, 20147, -1, 20317, 5352, 19744, -1, 5353, 5352, 20317, -1, 19638, 5450, 19783, -1, 5451, 5450, 19638, -1, 19783, 5448, 19784, -1, 5450, 5448, 19783, -1, 19784, 5446, 19506, -1, 5448, 5446, 19784, -1, 19506, 5442, 19501, -1, 5446, 5442, 19506, -1, 19501, 5436, 20227, -1, 5442, 5436, 19501, -1, 20227, 5431, 19058, -1, 5436, 5431, 20227, -1, 18964, 14162, 19106, -1, 14163, 14162, 18964, -1, 19106, 14159, 19107, -1, 14162, 14159, 19106, -1, 19107, 14158, 18812, -1, 14159, 14158, 19107, -1, 18812, 14160, 18808, -1, 14158, 14160, 18812, -1, 18808, 14154, 18614, -1, 14160, 14154, 18808, -1, 18614, 11983, 11982, -1, 18614, 15090, 11983, -1, 18614, 15106, 15090, -1, 14154, 14153, 18614, -1, 18614, 15109, 15106, -1, 14153, 15110, 18614, -1, 18614, 15110, 15109, -1, 20623, 5057, 20624, -1, 5062, 5057, 20623, -1, 21254, 11355, 11354, -1, 21254, 12085, 11355, -1, 21254, 12083, 12085, -1, 20624, 5056, 21254, -1, 5057, 5056, 20624, -1, 21254, 12084, 12083, -1, 5056, 12087, 21254, -1, 21254, 12087, 12084, -1, 20504, 5045, 20541, -1, 5044, 5045, 20504, -1, 20541, 5051, 20601, -1, 5045, 5051, 20541, -1, 20601, 5050, 20602, -1, 5051, 5050, 20601, -1, 20496, 5040, 20494, -1, 5041, 5040, 20496, -1, 20494, 5039, 20503, -1, 5040, 5039, 20494, -1, 20503, 5044, 20504, -1, 5039, 5044, 20503, -1, 20383, 5021, 20402, -1, 5020, 5021, 20383, -1, 20402, 5027, 20481, -1, 5021, 5027, 20402, -1, 20481, 5026, 20482, -1, 5027, 5026, 20481, -1, 20356, 5016, 20304, -1, 5017, 5016, 20356, -1, 20304, 5015, 20339, -1, 5016, 5015, 20304, -1, 20339, 5020, 20383, -1, 5015, 5020, 20339, -1, 20311, 5080, 20148, -1, 5081, 5080, 20311, -1, 20148, 5087, 20146, -1, 5080, 5087, 20148, -1, 20146, 5086, 20357, -1, 5087, 5086, 20146, -1, 19864, 5076, 19782, -1, 5077, 5076, 19864, -1, 19782, 5075, 19822, -1, 5076, 5075, 19782, -1, 19822, 5081, 20311, -1, 5075, 5081, 19822, -1, 20211, 5104, 19502, -1, 5105, 5104, 20211, -1, 19502, 5111, 19500, -1, 5104, 5111, 19502, -1, 19500, 5110, 19857, -1, 5111, 5110, 19500, -1, 5101, 19105, 19168, -1, 5101, 5100, 19105, -1, 19105, 5099, 19141, -1, 5100, 5099, 19105, -1, 5099, 20211, 19141, -1, 5099, 5105, 20211, -1, 11993, 18809, 11991, -1, 14986, 18809, 11993, -1, 14988, 18809, 14986, -1, 14989, 18809, 14988, -1, 14993, 18809, 14989, -1, 14093, 18809, 14993, -1, 18809, 14092, 18807, -1, 14093, 14092, 18809, -1, 14092, 19161, 18807, -1, 14092, 14100, 19161, -1, 11416, 20531, 11417, -1, 12143, 20531, 11416, -1, 12144, 20531, 12143, -1, 12146, 20531, 12144, -1, 12147, 20531, 12146, -1, 5314, 20531, 12147, -1, 20531, 5306, 20519, -1, 5314, 5306, 20531, -1, 5306, 20498, 20519, -1, 5306, 5308, 20498, -1, 5321, 20456, 20469, -1, 5321, 5320, 20456, -1, 20456, 5319, 20435, -1, 5320, 5319, 20456, -1, 5319, 20415, 20435, -1, 5319, 5337, 20415, -1, 5337, 20398, 20415, -1, 5337, 5331, 20398, -1, 20398, 5315, 20386, -1, 5331, 5315, 20398, -1, 20386, 5317, 20243, -1, 5315, 5317, 20386, -1, 20192, 5282, 20341, -1, 5285, 5282, 20192, -1, 20341, 5284, 20321, -1, 5282, 5284, 20341, -1, 20321, 5301, 20322, -1, 5284, 5301, 20321, -1, 20322, 5295, 20315, -1, 5301, 5295, 20322, -1, 20315, 5279, 20309, -1, 5295, 5279, 20315, -1, 20309, 5281, 19666, -1, 5279, 5281, 20309, -1, 19570, 5258, 20258, -1, 5261, 5258, 19570, -1, 20258, 5260, 20245, -1, 5258, 5260, 20258, -1, 20245, 5277, 20246, -1, 5260, 5277, 20245, -1, 20246, 5271, 20232, -1, 5277, 5271, 20246, -1, 20232, 5255, 20223, -1, 5271, 5255, 20232, -1, 20223, 5257, 18983, -1, 5255, 5257, 20223, -1, 18984, 5234, 20180, -1, 5237, 5234, 18984, -1, 20180, 5236, 20171, -1, 5234, 5236, 20180, -1, 20171, 5253, 20164, -1, 5236, 5253, 20171, -1, 20164, 5247, 20154, -1, 5253, 5247, 20164, -1, 20154, 5231, 20133, -1, 5247, 5231, 20154, -1, 20133, 5233, 18586, -1, 5231, 5233, 20133, -1, 18587, 14133, 20074, -1, 14131, 14133, 18587, -1, 18452, 11962, 11961, -1, 18452, 15053, 11962, -1, 18452, 15069, 15053, -1, 20074, 14139, 18452, -1, 14133, 14139, 20074, -1, 18452, 15072, 15069, -1, 14139, 15073, 18452, -1, 18452, 15073, 15072, -1, 20499, 5408, 20500, -1, 5404, 5408, 20499, -1, 20500, 5402, 20518, -1, 5408, 5402, 20500, -1, 20518, 11376, 11375, -1, 20518, 12190, 11376, -1, 20518, 12188, 12190, -1, 5402, 5401, 20518, -1, 20518, 12189, 12188, -1, 5401, 12192, 20518, -1, 20518, 12192, 12189, -1, 20436, 5398, 20455, -1, 5399, 5398, 20436, -1, 20455, 5405, 20468, -1, 5398, 5405, 20455, -1, 20468, 5404, 20499, -1, 5405, 5404, 20468, -1, 20374, 5377, 20375, -1, 5374, 5377, 20374, -1, 20375, 5376, 20385, -1, 5377, 5376, 20375, -1, 20385, 5381, 20397, -1, 5376, 5381, 20385, -1, 20138, 5364, 20342, -1, 5365, 5364, 20138, -1, 20342, 5368, 20351, -1, 5364, 5368, 20342, -1, 20351, 5374, 20374, -1, 5368, 5374, 20351, -1, 20298, 5350, 20299, -1, 5346, 5350, 20298, -1, 20299, 5344, 20308, -1, 5350, 5344, 20299, -1, 20308, 5343, 20139, -1, 5344, 5343, 20308, -1, 19397, 5340, 20259, -1, 5341, 5340, 19397, -1, 20259, 5347, 20269, -1, 5340, 5347, 20259, -1, 20269, 5346, 20298, -1, 5347, 5346, 20269, -1, 20208, 5435, 20209, -1, 5432, 5435, 20208, -1, 20209, 5434, 20221, -1, 5435, 5434, 20209, -1, 20221, 5439, 19398, -1, 5434, 5439, 20221, -1, 18718, 5422, 20179, -1, 5423, 5422, 18718, -1, 20179, 5426, 20191, -1, 5422, 5426, 20179, -1, 20191, 5432, 20208, -1, 5426, 5432, 20191, -1, 14147, 20122, 20110, -1, 14147, 14151, 20122, -1, 20122, 14145, 20134, -1, 14151, 14145, 20122, -1, 14145, 18719, 20134, -1, 14145, 14144, 18719, -1, 11972, 20076, 11970, -1, 15097, 20076, 11972, -1, 15099, 20076, 15097, -1, 15100, 20076, 15099, -1, 15104, 20076, 15100, -1, 15104, 14142, 20076, -1, 14142, 14141, 20076, -1, 14141, 20093, 20076, -1, 14141, 14148, 20093, -1, 14148, 20110, 20093, -1, 14148, 14147, 20110, -1, 12107, 20831, 11323, -1, 12108, 20831, 12107, -1, 12110, 20831, 12108, -1, 12111, 20831, 12110, -1, 11323, 20831, 11321, -1, 12111, 5196, 20831, -1, 5196, 5195, 20831, -1, 5195, 20804, 20831, -1, 5195, 5193, 20804, -1, 5193, 20758, 20804, -1, 5193, 5192, 20758, -1, 5192, 20744, 20758, -1, 5192, 5191, 20744, -1, 20744, 5187, 20720, -1, 5191, 5187, 20744, -1, 5187, 20719, 20720, -1, 5187, 5186, 20719, -1, 20684, 5226, 20676, -1, 5227, 5226, 20684, -1, 20676, 5224, 20677, -1, 5226, 5224, 20676, -1, 20677, 5222, 20632, -1, 5224, 5222, 20677, -1, 20632, 5218, 20613, -1, 5222, 5218, 20632, -1, 20613, 5212, 20611, -1, 5218, 5212, 20613, -1, 20611, 5207, 20557, -1, 5212, 5207, 20611, -1, 20560, 5137, 20562, -1, 5138, 5137, 20560, -1, 20562, 5135, 20563, -1, 5137, 5135, 20562, -1, 20563, 5134, 20515, -1, 5135, 5134, 20563, -1, 20515, 5133, 20489, -1, 5134, 5133, 20515, -1, 20489, 5129, 20490, -1, 5133, 5129, 20489, -1, 20490, 5128, 20431, -1, 5129, 5128, 20490, -1, 20430, 5168, 20439, -1, 5169, 5168, 20430, -1, 20439, 5166, 20440, -1, 5168, 5166, 20439, -1, 20440, 5164, 20388, -1, 5166, 5164, 20440, -1, 20388, 5160, 20379, -1, 5164, 5160, 20388, -1, 20379, 5154, 20367, -1, 5160, 5154, 20379, -1, 20367, 5149, 20121, -1, 5154, 5149, 20367, -1, 20058, 14126, 20333, -1, 14127, 14126, 20058, -1, 20333, 14123, 20334, -1, 14126, 14123, 20333, -1, 20334, 14122, 19913, -1, 14123, 14122, 20334, -1, 19913, 14124, 19914, -1, 14122, 14124, 19913, -1, 19914, 14118, 19514, -1, 14124, 14118, 19914, -1, 19514, 12028, 12026, -1, 19514, 15016, 12028, -1, 19514, 15032, 15016, -1, 14118, 14117, 19514, -1, 19514, 15035, 15032, -1, 14117, 15036, 19514, -1, 19514, 15036, 15035, -1, 21326, 5729, 20805, -1, 5734, 5729, 21326, -1, 20832, 11310, 11309, -1, 20832, 12295, 11310, -1, 20832, 12293, 12295, -1, 20805, 5728, 20832, -1, 5729, 5728, 20805, -1, 20832, 12294, 12293, -1, 5728, 12297, 20832, -1, 20832, 12297, 12294, -1, 20700, 5693, 20718, -1, 5692, 5693, 20700, -1, 20718, 5699, 20757, -1, 5693, 5699, 20718, -1, 20757, 5698, 21321, -1, 5699, 5698, 20757, -1, 21278, 5688, 20675, -1, 5689, 5688, 21278, -1, 20675, 5687, 20683, -1, 5688, 5687, 20675, -1, 20683, 5692, 20700, -1, 5687, 5692, 20683, -1, 20575, 5716, 20612, -1, 5717, 5716, 20575, -1, 20612, 5723, 20631, -1, 5716, 5723, 20612, -1, 20631, 5722, 21271, -1, 5723, 5722, 20631, -1, 21220, 5712, 20564, -1, 5713, 5712, 21220, -1, 20564, 5711, 20574, -1, 5712, 5711, 20564, -1, 20574, 5717, 20575, -1, 5711, 5717, 20574, -1, 20459, 5776, 20491, -1, 5777, 5776, 20459, -1, 20491, 5783, 20516, -1, 5776, 5783, 20491, -1, 20516, 5782, 21173, -1, 5783, 5782, 20516, -1, 20620, 5772, 20441, -1, 5773, 5772, 20620, -1, 20441, 5771, 20458, -1, 5772, 5771, 20441, -1, 20458, 5777, 20459, -1, 5771, 5777, 20458, -1, 20353, 5753, 20368, -1, 5752, 5753, 20353, -1, 20368, 5759, 20389, -1, 5753, 5759, 20368, -1, 20389, 5758, 20540, -1, 5759, 5758, 20389, -1, 5749, 20158, 20113, -1, 5749, 5748, 20158, -1, 20158, 5747, 20347, -1, 5748, 5747, 20158, -1, 5747, 20353, 20347, -1, 5747, 5752, 20353, -1, 12037, 20285, 12035, -1, 15208, 20285, 12037, -1, 15210, 20285, 15208, -1, 15211, 20285, 15210, -1, 15215, 20285, 15211, -1, 14201, 20285, 15215, -1, 20285, 14200, 19915, -1, 14201, 14200, 20285, -1, 14200, 20043, 19915, -1, 14200, 14208, 20043, -1, 11342, 20741, 11343, -1, 12072, 20741, 11342, -1, 12073, 20741, 12072, -1, 12075, 20741, 12073, -1, 12076, 20741, 12075, -1, 5066, 20741, 12076, -1, 20741, 5058, 20716, -1, 5066, 5058, 20741, -1, 5058, 20697, 20716, -1, 5058, 5060, 20697, -1, 5037, 20663, 20665, -1, 5037, 5036, 20663, -1, 20663, 5035, 21243, -1, 5036, 5035, 20663, -1, 5035, 21244, 21243, -1, 5035, 5053, 21244, -1, 5053, 20605, 21244, -1, 5053, 5047, 20605, -1, 20605, 5031, 20587, -1, 5047, 5031, 20605, -1, 20587, 5033, 20579, -1, 5031, 5033, 20587, -1, 20555, 5010, 20554, -1, 5013, 5010, 20555, -1, 20554, 5012, 20471, -1, 5010, 5012, 20554, -1, 20471, 5029, 20472, -1, 5012, 5029, 20471, -1, 20472, 5023, 20473, -1, 5029, 5023, 20472, -1, 20473, 5007, 20477, -1, 5023, 5007, 20473, -1, 20477, 5009, 20462, -1, 5007, 5009, 20477, -1, 20425, 5070, 20328, -1, 5073, 5070, 20425, -1, 20328, 5072, 20325, -1, 5070, 5072, 20328, -1, 20325, 5089, 20361, -1, 5072, 5089, 20325, -1, 20361, 5083, 20252, -1, 5089, 5083, 20361, -1, 20252, 5067, 20253, -1, 5083, 5067, 20252, -1, 20253, 5069, 20071, -1, 5067, 5069, 20253, -1, 20075, 5094, 19808, -1, 5097, 5094, 20075, -1, 19808, 5096, 19696, -1, 5094, 5096, 19808, -1, 19696, 5113, 19697, -1, 5096, 5113, 19696, -1, 19697, 5107, 19700, -1, 5113, 5107, 19697, -1, 19700, 5091, 20282, -1, 5107, 5091, 19700, -1, 20282, 5093, 19369, -1, 5091, 5093, 20282, -1, 19370, 14097, 19077, -1, 14095, 14097, 19370, -1, 18916, 12001, 11999, -1, 18916, 14979, 12001, -1, 18916, 14995, 14979, -1, 19077, 14103, 18916, -1, 14097, 14103, 19077, -1, 18916, 14998, 14995, -1, 14103, 14999, 18916, -1, 18916, 14999, 14998, -1, 20681, 5184, 20698, -1, 5180, 5184, 20681, -1, 20698, 5178, 20742, -1, 5184, 5178, 20698, -1, 20742, 11333, 11332, -1, 20742, 12120, 11333, -1, 20742, 12118, 12120, -1, 5178, 5177, 20742, -1, 20742, 12119, 12118, -1, 5177, 12122, 20742, -1, 20742, 12122, 12119, -1, 20664, 5174, 20666, -1, 5175, 5174, 20664, -1, 20666, 5181, 20667, -1, 5174, 5181, 20666, -1, 20667, 5180, 20681, -1, 5181, 5180, 20667, -1, 20572, 5211, 20577, -1, 5208, 5211, 20572, -1, 20577, 5210, 20586, -1, 5211, 5210, 20577, -1, 20586, 5215, 20604, -1, 5210, 5215, 20586, -1, 20511, 5198, 20552, -1, 5199, 5198, 20511, -1, 20552, 5202, 20553, -1, 5198, 5202, 20552, -1, 20553, 5208, 20572, -1, 5202, 5208, 20553, -1, 20444, 5126, 20461, -1, 5122, 5126, 20444, -1, 20461, 5120, 20476, -1, 5126, 5120, 20461, -1, 20476, 5119, 20474, -1, 5120, 5119, 20476, -1, 20324, 5116, 20423, -1, 5117, 5116, 20324, -1, 20423, 5123, 20424, -1, 5116, 5123, 20423, -1, 20424, 5122, 20444, -1, 5123, 5122, 20424, -1, 20344, 5153, 20349, -1, 5150, 5153, 20344, -1, 20349, 5152, 20251, -1, 5153, 5152, 20349, -1, 20251, 5157, 20277, -1, 5152, 5157, 20251, -1, 19801, 5140, 20330, -1, 5141, 5140, 19801, -1, 20330, 5144, 20331, -1, 5140, 5144, 20330, -1, 20331, 5150, 20344, -1, 5144, 5150, 20331, -1, 14111, 20266, 20254, -1, 14111, 14115, 20266, -1, 20266, 14109, 20281, -1, 14115, 14109, 20266, -1, 14109, 19695, 20281, -1, 14109, 14108, 19695, -1, 12015, 19201, 12013, -1, 15023, 19201, 12015, -1, 15025, 19201, 15023, -1, 15026, 19201, 15025, -1, 15030, 19201, 15026, -1, 15030, 14106, 19201, -1, 14106, 14105, 19201, -1, 14105, 20237, 19201, -1, 14105, 14112, 20237, -1, 14112, 20254, 20237, -1, 14112, 14111, 20254, -1, 1639, 11110, 3338, -1, 11111, 11110, 1639, -1, 3338, 11107, 3348, -1, 11110, 11107, 3338, -1, 3348, 11106, 1718, -1, 11107, 11106, 3348, -1, 3358, 11117, 3347, -1, 3347, 11116, 3336, -1, 11117, 11116, 3347, -1, 3336, 11126, 1664, -1, 11116, 11126, 3336, -1, 11126, 11125, 1664, -1, 52, 11133, 53, -1, 11134, 11133, 52, -1, 53, 11119, 100, -1, 11133, 11119, 53, -1, 100, 11121, 118, -1, 11119, 11121, 100, -1, 11141, 99, 157, -1, 11141, 11140, 99, -1, 11140, 50, 99, -1, 11140, 11150, 50, -1, 11150, 51, 50, -1, 11150, 11149, 51, -1, 274, 11157, 303, -1, 11158, 11157, 274, -1, 303, 11143, 331, -1, 11157, 11143, 303, -1, 331, 11145, 351, -1, 11143, 11145, 331, -1, 11057, 330, 396, -1, 11057, 11056, 330, -1, 11056, 302, 330, -1, 11056, 11066, 302, -1, 11066, 272, 302, -1, 11066, 11065, 272, -1, 605, 11073, 652, -1, 11074, 11073, 605, -1, 652, 11059, 773, -1, 11073, 11059, 652, -1, 773, 11061, 917, -1, 11059, 11061, 773, -1, 11081, 882, 1005, -1, 11081, 11080, 882, -1, 11080, 744, 882, -1, 11080, 11090, 744, -1, 11090, 603, 744, -1, 11090, 11089, 603, -1, 1385, 11097, 1401, -1, 11098, 11097, 1385, -1, 1401, 11082, 1531, -1, 11097, 11082, 1401, -1, 1531, 11085, 1651, -1, 11082, 11085, 1531, -1, 1763, 14699, 1644, -1, 1644, 14698, 1509, -1, 14699, 14698, 1644, -1, 1509, 14702, 1383, -1, 14698, 14702, 1509, -1, 14702, 14701, 1383, -1, 11225, 3294, 3279, -1, 11225, 11224, 3294, -1, 11224, 3305, 3294, -1, 3305, 11237, 1725, -1, 11224, 11237, 3305, -1, 11237, 11244, 1725, -1, 3326, 11169, 3315, -1, 11173, 11169, 3326, -1, 3315, 11166, 3304, -1, 11169, 11166, 3315, -1, 3304, 11165, 3293, -1, 11166, 11165, 3304, -1, 11181, 1775, 1737, -1, 11181, 11182, 1775, -1, 11182, 1818, 1775, -1, 11182, 11186, 1818, -1, 11186, 56, 1818, -1, 11186, 11193, 56, -1, 55, 11206, 1817, -1, 11210, 11206, 55, -1, 1817, 11197, 1776, -1, 11206, 11197, 1817, -1, 1776, 11199, 1739, -1, 11197, 11199, 1776, -1, 11201, 246, 92, -1, 11201, 11200, 246, -1, 11200, 247, 246, -1, 11200, 11213, 247, -1, 11213, 309, 247, -1, 11213, 11220, 309, -1, 308, 11251, 244, -1, 11255, 11251, 308, -1, 244, 11248, 245, -1, 11251, 11248, 244, -1, 245, 11247, 148, -1, 11248, 11247, 245, -1, 11263, 431, 332, -1, 11263, 11264, 431, -1, 11264, 524, 431, -1, 524, 11268, 628, -1, 11264, 11268, 524, -1, 11268, 11275, 628, -1, 621, 17680, 521, -1, 17684, 17680, 621, -1, 521, 17673, 428, -1, 17680, 17673, 521, -1, 428, 17675, 387, -1, 17673, 17675, 428, -1, 5141, 19925, 5142, -1, 19801, 19925, 5141, -1, 5142, 20034, 5145, -1, 19925, 20034, 5142, -1, 5145, 20121, 5149, -1, 20034, 20121, 5145, -1, 14127, 20058, 14120, -1, 14120, 19945, 14107, -1, 20058, 19945, 14120, -1, 14107, 19814, 14108, -1, 19945, 19814, 14107, -1, 19814, 19695, 14108, -1, 5117, 20391, 5115, -1, 20324, 20391, 5117, -1, 5115, 20432, 5124, -1, 20391, 20432, 5115, -1, 5124, 20431, 5128, -1, 20432, 20431, 5124, -1, 5169, 20430, 5162, -1, 5162, 20433, 5158, -1, 20430, 20433, 5162, -1, 5158, 20392, 5157, -1, 20433, 20392, 5158, -1, 20392, 20277, 5157, -1, 5199, 20510, 5200, -1, 20511, 20510, 5199, -1, 5200, 20558, 5203, -1, 20510, 20558, 5200, -1, 5203, 20557, 5207, -1, 20558, 20557, 5203, -1, 5138, 20560, 5131, -1, 5131, 20559, 5118, -1, 20560, 20559, 5131, -1, 5118, 20512, 5119, -1, 20559, 20512, 5118, -1, 20512, 20474, 5119, -1, 5175, 21258, 5173, -1, 20664, 21258, 5175, -1, 5173, 21267, 5182, -1, 21258, 21267, 5173, -1, 5182, 20719, 5186, -1, 21267, 20719, 5182, -1, 5227, 20684, 5220, -1, 5220, 21268, 5216, -1, 20684, 21268, 5220, -1, 5216, 21259, 5215, -1, 21268, 21259, 5216, -1, 21259, 20604, 5215, -1, 19168, 5102, 5101, -1, 19168, 19160, 5102, -1, 19160, 5092, 5102, -1, 19160, 19254, 5092, -1, 19254, 5093, 5092, -1, 19254, 19369, 5093, -1, 14095, 19255, 14096, -1, 19370, 19255, 14095, -1, 14096, 19162, 14099, -1, 19255, 19162, 14096, -1, 14099, 19161, 14100, -1, 19162, 19161, 14099, -1, 19864, 5078, 5077, -1, 19864, 19856, 5078, -1, 19856, 5068, 5078, -1, 19856, 19973, 5068, -1, 19973, 5069, 5068, -1, 19973, 20071, 5069, -1, 5097, 19974, 5095, -1, 20075, 19974, 5097, -1, 5095, 19858, 5109, -1, 19974, 19858, 5095, -1, 5109, 19857, 5110, -1, 19858, 19857, 5109, -1, 20356, 5018, 5017, -1, 20356, 20355, 5018, -1, 20355, 5008, 5018, -1, 20355, 20446, 5008, -1, 20446, 5009, 5008, -1, 20446, 20462, 5009, -1, 5073, 20453, 5071, -1, 20425, 20453, 5073, -1, 5071, 20358, 5085, -1, 20453, 20358, 5071, -1, 5085, 20357, 5086, -1, 20358, 20357, 5085, -1, 20496, 5042, 5041, -1, 20496, 20996, 5042, -1, 20996, 5032, 5042, -1, 20996, 21105, 5032, -1, 21105, 5033, 5032, -1, 21105, 20579, 5033, -1, 5013, 21016, 5011, -1, 20555, 21016, 5013, -1, 5011, 20912, 5025, -1, 21016, 20912, 5011, -1, 5025, 20482, 5026, -1, 20912, 20482, 5025, -1, 20623, 5063, 5062, -1, 20623, 21255, 5063, -1, 21255, 5059, 5063, -1, 21255, 21264, 5059, -1, 21264, 5060, 5059, -1, 21264, 20697, 5060, -1, 5037, 21256, 5034, -1, 20665, 21256, 5037, -1, 5034, 21250, 5049, -1, 21256, 21250, 5034, -1, 5049, 20602, 5050, -1, 21250, 20602, 5049, -1, 20113, 5750, 5749, -1, 20113, 20198, 5750, -1, 20198, 5740, 5750, -1, 20198, 20255, 5740, -1, 20337, 5741, 20255, -1, 20255, 5741, 5740, -1, 14203, 20256, 14204, -1, 20272, 20256, 14203, -1, 14204, 20199, 14207, -1, 20256, 20199, 14204, -1, 14207, 20043, 14208, -1, 20199, 20043, 14207, -1, 20620, 5774, 5773, -1, 20620, 20745, 5774, -1, 20745, 5764, 5774, -1, 20745, 20855, 5764, -1, 20855, 5765, 5764, -1, 20855, 20535, 5765, -1, 5745, 20860, 5743, -1, 20533, 20860, 5745, -1, 5743, 20751, 5757, -1, 20860, 20751, 5743, -1, 5757, 20540, 5758, -1, 20751, 20540, 5757, -1, 21220, 5714, 5713, -1, 21220, 21231, 5714, -1, 21231, 5704, 5714, -1, 21231, 21241, 5704, -1, 21241, 5705, 5704, -1, 21241, 20649, 5705, -1, 5769, 21242, 5767, -1, 20645, 21242, 5769, -1, 5767, 21232, 5781, -1, 21242, 21232, 5767, -1, 5781, 21173, 5782, -1, 21232, 21173, 5781, -1, 21278, 5690, 5689, -1, 21278, 21285, 5690, -1, 21285, 5680, 5690, -1, 21285, 21292, 5680, -1, 20796, 5681, 21292, -1, 21292, 5681, 5680, -1, 5709, 21286, 5707, -1, 20774, 21286, 5709, -1, 5707, 21280, 5721, -1, 21286, 21280, 5707, -1, 5721, 21271, 5722, -1, 21280, 21271, 5721, -1, 21326, 5735, 5734, -1, 21326, 21331, 5735, -1, 21331, 5731, 5735, -1, 21331, 21344, 5731, -1, 21344, 5732, 5731, -1, 21344, 20926, 5732, -1, 5685, 21332, 5682, -1, 20893, 21332, 5685, -1, 5682, 21328, 5697, -1, 21332, 21328, 5682, -1, 5697, 21321, 5698, -1, 21328, 21321, 5697, -1, 5423, 18818, 5424, -1, 18718, 18818, 5423, -1, 5424, 18922, 5427, -1, 18818, 18922, 5424, -1, 5427, 19058, 5431, -1, 18922, 19058, 5427, -1, 14163, 18964, 14156, -1, 14156, 18828, 14143, -1, 18964, 18828, 14156, -1, 14143, 18717, 14144, -1, 18828, 18717, 14143, -1, 18717, 18719, 14144, -1, 5341, 19482, 5339, -1, 19397, 19482, 5341, -1, 5339, 19639, 5348, -1, 19482, 19639, 5339, -1, 5348, 19744, 5352, -1, 19639, 19744, 5348, -1, 5451, 19638, 5444, -1, 5444, 19640, 5440, -1, 19638, 19640, 5444, -1, 5440, 19396, 5439, -1, 19640, 19396, 5440, -1, 19396, 19398, 5439, -1, 5365, 20137, 5366, -1, 20138, 20137, 5365, -1, 5366, 20293, 5369, -1, 20137, 20293, 5366, -1, 5369, 20288, 5373, -1, 20293, 20288, 5369, -1, 5362, 20290, 5355, -1, 5355, 20289, 5342, -1, 20290, 20289, 5355, -1, 5342, 20140, 5343, -1, 20289, 20140, 5342, -1, 20140, 20139, 5343, -1, 5399, 20650, 5397, -1, 20436, 20650, 5399, -1, 5397, 20769, 5406, -1, 20650, 20769, 5397, -1, 5406, 20521, 5410, -1, 20769, 20521, 5406, -1, 5393, 20506, 5386, -1, 5386, 20772, 5382, -1, 20506, 20772, 5386, -1, 5382, 20651, 5381, -1, 20772, 20651, 5382, -1, 20651, 20397, 5381, -1, 18526, 5242, 5241, -1, 18526, 18525, 5242, -1, 18525, 5232, 5242, -1, 18525, 18567, 5232, -1, 18567, 5233, 5232, -1, 18567, 18586, 5233, -1, 14131, 18568, 14132, -1, 18587, 18568, 14131, -1, 14132, 18528, 14135, -1, 18568, 18528, 14132, -1, 14135, 18527, 14136, -1, 18528, 18527, 14135, -1, 18757, 5266, 5265, -1, 18757, 18752, 5266, -1, 18752, 5256, 5266, -1, 18752, 18848, 5256, -1, 18848, 5257, 5256, -1, 18848, 18983, 5257, -1, 5237, 18849, 5235, -1, 18984, 18849, 5237, -1, 5235, 18754, 5249, -1, 18849, 18754, 5235, -1, 5249, 18753, 5250, -1, 18754, 18753, 5249, -1, 19405, 5290, 5289, -1, 19405, 19404, 5290, -1, 19404, 5280, 5290, -1, 19404, 19538, 5280, -1, 19538, 5281, 5280, -1, 19538, 19666, 5281, -1, 5261, 19451, 5259, -1, 19570, 19451, 5261, -1, 5259, 19408, 5273, -1, 19451, 19408, 5259, -1, 5273, 19406, 5274, -1, 19408, 19406, 5273, -1, 20016, 5326, 5325, -1, 20016, 20077, 5326, -1, 20077, 5316, 5326, -1, 20077, 20166, 5316, -1, 20166, 5317, 5316, -1, 20166, 20243, 5317, -1, 5285, 20099, 5283, -1, 20192, 20099, 5285, -1, 5283, 20015, 5297, -1, 20099, 20015, 5283, -1, 5297, 20017, 5298, -1, 20015, 20017, 5297, -1, 20412, 5311, 5310, -1, 20412, 20606, 5311, -1, 20606, 5307, 5311, -1, 20606, 20735, 5307, -1, 20735, 5308, 5307, -1, 20735, 20498, 5308, -1, 5321, 20626, 5318, -1, 20469, 20626, 5321, -1, 5318, 20501, 5333, -1, 20626, 20501, 5318, -1, 5333, 20395, 5334, -1, 20501, 20395, 5333, -1, 20635, 21273, 5589, -1, 21273, 5590, 5589, -1, 21273, 21282, 5590, -1, 21282, 5593, 5590, -1, 21282, 20704, 5593, -1, 20704, 5597, 5593, -1, 14180, 21263, 20621, -1, 14179, 21263, 14180, -1, 14192, 21275, 14179, -1, 14179, 21275, 21263, -1, 14199, 20705, 14192, -1, 14192, 20705, 21275, -1, 20768, 20815, 5657, -1, 20815, 5655, 5657, -1, 20815, 20814, 5655, -1, 20814, 5664, 5655, -1, 20814, 20864, 5664, -1, 20864, 5668, 5664, -1, 5605, 20816, 20747, -1, 5606, 20816, 5605, -1, 5610, 20813, 5606, -1, 5606, 20813, 20816, -1, 5617, 20865, 5610, -1, 5610, 20865, 20813, -1, 20883, 20939, 5623, -1, 20939, 5624, 5623, -1, 20939, 20938, 5624, -1, 20938, 5627, 5624, -1, 20938, 20977, 5627, -1, 20977, 5631, 5627, -1, 5659, 20941, 20874, -1, 5658, 20941, 5659, -1, 5671, 20940, 5658, -1, 5658, 20940, 20941, -1, 5678, 20974, 5671, -1, 5671, 20974, 20940, -1, 21024, 21427, 5565, -1, 21427, 5563, 5565, -1, 21427, 21439, 5563, -1, 21439, 5572, 5563, -1, 21439, 21101, 5572, -1, 21101, 5576, 5572, -1, 5639, 21428, 20995, -1, 5640, 21428, 5639, -1, 5644, 21440, 5640, -1, 5640, 21440, 21428, -1, 5651, 21078, 5644, -1, 5644, 21078, 21440, -1, 21142, 5550, 20486, -1, 20486, 5550, 5549, -1, 21202, 5540, 21142, -1, 21142, 5540, 5550, -1, 20596, 5541, 21202, -1, 21202, 5541, 5540, -1, 14171, 20485, 14172, -1, 14168, 21143, 14171, -1, 14171, 21143, 20485, -1, 14167, 21203, 14168, -1, 14168, 21203, 21143, -1, 14167, 20547, 21203, -1, 21265, 5526, 20616, -1, 20616, 5526, 5525, -1, 21276, 5516, 21265, -1, 21265, 5516, 5526, -1, 20726, 5517, 21276, -1, 21276, 5517, 5516, -1, 5557, 20615, 5558, -1, 5543, 21266, 5557, -1, 5557, 21266, 20615, -1, 5545, 21277, 5543, -1, 5543, 21277, 21266, -1, 5545, 20679, 21277, -1, 21313, 5502, 20750, -1, 20750, 5502, 5501, -1, 21324, 5492, 21313, -1, 21313, 5492, 5502, -1, 20857, 5493, 21324, -1, 21324, 5493, 5492, -1, 5533, 20731, 5534, -1, 5519, 21315, 5533, -1, 5533, 21315, 20731, -1, 5521, 21318, 5519, -1, 5519, 21318, 21315, -1, 5521, 20802, 21318, -1, 21367, 5478, 20878, -1, 20878, 5478, 5477, -1, 21372, 5468, 21367, -1, 21367, 5468, 5478, -1, 20982, 5469, 21372, -1, 21372, 5469, 5468, -1, 5509, 20871, 5510, -1, 5495, 21362, 5509, -1, 5509, 21362, 20871, -1, 5497, 21368, 5495, -1, 5495, 21368, 21362, -1, 5497, 20933, 21368, -1, 21422, 5463, 21007, -1, 21007, 5463, 5462, -1, 21435, 5459, 21422, -1, 21422, 5459, 5463, -1, 21091, 5460, 21435, -1, 21435, 5460, 5459, -1, 5485, 20992, 5486, -1, 5470, 21414, 5485, -1, 5485, 21414, 20992, -1, 5473, 21426, 5470, -1, 5470, 21426, 21414, -1, 5473, 21047, 21426, -1, 20687, 8542, 8541, -1, 21293, 8542, 20687, -1, 21302, 8532, 21293, -1, 21293, 8532, 8542, -1, 20786, 8533, 21302, -1, 21302, 8533, 8532, -1, 14615, 20686, 14616, -1, 14612, 21294, 14615, -1, 14615, 21294, 20686, -1, 14611, 21303, 14612, -1, 14612, 21303, 21294, -1, 14611, 20755, 21303, -1, 20840, 8518, 8517, -1, 21346, 8518, 20840, -1, 21356, 8508, 21346, -1, 21346, 8508, 8518, -1, 20918, 8509, 21356, -1, 21356, 8509, 8508, -1, 8549, 20839, 8550, -1, 8535, 21347, 8549, -1, 8549, 21347, 20839, -1, 8537, 21357, 8535, -1, 8535, 21357, 21347, -1, 8537, 20891, 21357, -1, 20968, 8494, 8493, -1, 21403, 8494, 20968, -1, 21409, 8484, 21403, -1, 21403, 8484, 8494, -1, 21044, 8485, 21409, -1, 21409, 8485, 8484, -1, 8525, 20951, 8526, -1, 8511, 21404, 8525, -1, 8525, 21404, 20951, -1, 8513, 21410, 8511, -1, 8511, 21410, 21404, -1, 8513, 21015, 21410, -1, 21073, 8578, 8577, -1, 21458, 8578, 21073, -1, 21466, 8568, 21458, -1, 21458, 8568, 8578, -1, 21131, 8569, 21466, -1, 21466, 8569, 8568, -1, 8501, 21059, 8502, -1, 8487, 21451, 8501, -1, 8501, 21451, 21059, -1, 8489, 21461, 8487, -1, 8487, 21461, 21451, -1, 8489, 21115, 21461, -1, 18460, 8563, 8562, -1, 18487, 8563, 18460, -1, 18504, 8559, 18487, -1, 18487, 8559, 8563, -1, 18534, 8560, 18504, -1, 18504, 8560, 8559, -1, 8585, 18461, 8586, -1, 8570, 18459, 8585, -1, 8585, 18459, 18461, -1, 8573, 18489, 8570, -1, 8570, 18489, 18459, -1, 8573, 18505, 18489, -1, 20420, 20811, 5871, -1, 20811, 5872, 5871, -1, 20811, 20931, 5872, -1, 20931, 5875, 5872, -1, 20931, 21046, 5875, -1, 21046, 5879, 5875, -1, 14216, 20713, 20408, -1, 14215, 20713, 14216, -1, 14228, 20833, 14215, -1, 14215, 20833, 20713, -1, 14235, 20967, 14228, -1, 14228, 20967, 20833, -1, 20570, 20592, 5847, -1, 20592, 5845, 5847, -1, 20592, 20639, 5845, -1, 20639, 5854, 5845, -1, 20639, 20638, 5854, -1, 20638, 5858, 5854, -1, 5887, 20591, 20567, -1, 5888, 20591, 5887, -1, 5892, 20640, 5888, -1, 5888, 20640, 20591, -1, 5899, 20637, 5892, -1, 5892, 20637, 20640, -1, 20669, 20711, 5813, -1, 20711, 5814, 5813, -1, 20711, 20762, 5814, -1, 20762, 5817, 5814, -1, 20762, 20761, 5817, -1, 20761, 5821, 5817, -1, 5849, 20710, 20671, -1, 5848, 20710, 5849, -1, 5861, 20763, 5848, -1, 5848, 20763, 20710, -1, 5868, 20760, 5861, -1, 5861, 20760, 20763, -1, 20821, 21335, 5789, -1, 21335, 5787, 5789, -1, 21335, 21348, 5787, -1, 21348, 5796, 5787, -1, 21348, 21359, 5796, -1, 21359, 5800, 5796, -1, 5829, 21336, 20782, -1, 5830, 21336, 5829, -1, 5834, 21349, 5830, -1, 5830, 21349, 21336, -1, 5841, 21360, 5834, -1, 5834, 21360, 21349, -1, 5905, 18418, 5906, -1, 18370, 18418, 5905, -1, 5906, 18454, 5909, -1, 18418, 18454, 5906, -1, 5909, 18498, 5913, -1, 18454, 18498, 5909, -1, 14259, 18472, 14252, -1, 14252, 18424, 14239, -1, 18472, 18424, 14252, -1, 14239, 18369, 14240, -1, 18424, 18369, 14239, -1, 18369, 18371, 14240, -1, 5973, 20130, 5971, -1, 20105, 20130, 5973, -1, 5971, 20129, 5980, -1, 20130, 20129, 5971, -1, 5980, 18771, 5984, -1, 20129, 18771, 5980, -1, 5933, 18768, 5926, -1, 5926, 20128, 5922, -1, 18768, 20128, 5926, -1, 5922, 20131, 5921, -1, 20128, 20131, 5922, -1, 20131, 20082, 5921, -1, 5939, 20214, 5940, -1, 20185, 20214, 5939, -1, 5940, 20213, 5943, -1, 20214, 20213, 5940, -1, 5943, 19442, 5947, -1, 20213, 19442, 5943, -1, 5994, 19428, 5987, -1, 5987, 20216, 5974, -1, 19428, 20216, 5987, -1, 5974, 20215, 5975, -1, 20216, 20215, 5974, -1, 20215, 20173, 5975, -1, 5997, 19756, 5995, -1, 19757, 19756, 5997, -1, 5995, 19888, 6004, -1, 19756, 19888, 5995, -1, 6004, 19993, 6008, -1, 19888, 19993, 6004, -1, 5967, 19995, 5960, -1, 5960, 19889, 5956, -1, 19995, 19889, 5960, -1, 5956, 19761, 5955, -1, 19889, 19761, 5956, -1, 19761, 19758, 5955, -1, 6065, 19853, 6066, -1, 6066, 21424, 6056, -1, 19853, 21424, 6066, -1, 6056, 21433, 6057, -1, 21424, 21433, 6056, -1, 21433, 21444, 6057, -1, 14263, 21434, 14264, -1, 19907, 21434, 14263, -1, 14264, 21425, 14267, -1, 21434, 21425, 14264, -1, 14267, 19833, 14268, -1, 21425, 19833, 14267, -1, 18392, 6090, 6089, -1, 18392, 18389, 6090, -1, 18389, 6080, 6090, -1, 18389, 18429, 6080, -1, 18429, 6081, 6080, -1, 18429, 18476, 6081, -1, 6061, 18430, 6059, -1, 18444, 18430, 6061, -1, 6059, 18391, 6073, -1, 18430, 18391, 6059, -1, 6073, 18390, 6074, -1, 18391, 18390, 6073, -1, 18574, 6114, 6113, -1, 18574, 18597, 6114, -1, 18597, 6104, 6114, -1, 18597, 18618, 6104, -1, 18618, 6105, 6104, -1, 18618, 18674, 6105, -1, 6085, 18604, 6083, -1, 18641, 18604, 6085, -1, 6083, 18580, 6097, -1, 18604, 18580, 6083, -1, 6097, 18576, 6098, -1, 18580, 18576, 6097, -1, 18857, 6042, 6041, -1, 18857, 18997, 6042, -1, 18997, 6032, 6042, -1, 18997, 19116, 6032, -1, 19116, 6033, 6032, -1, 19116, 19237, 6033, -1, 6109, 19016, 6107, -1, 19151, 19016, 6109, -1, 6107, 18903, 6121, -1, 19016, 18903, 6107, -1, 6121, 18859, 6122, -1, 18903, 18859, 6121, -1, 6026, 19590, 6027, -1, 6027, 19707, 6023, -1, 19590, 19707, 6027, -1, 6023, 19835, 6024, -1, 19707, 19835, 6023, -1, 19835, 19948, 6024, -1, 6037, 19729, 6034, -1, 19845, 19729, 6037, -1, 6034, 19607, 6049, -1, 19729, 19607, 6034, -1, 6049, 19592, 6050, -1, 19607, 19592, 6049, -1, 6187, 21396, 6188, -1, 21385, 21396, 6187, -1, 6188, 21406, 6191, -1, 21396, 21406, 6188, -1, 6191, 21415, 6195, -1, 21406, 21415, 6191, -1, 14295, 19918, 14288, -1, 19918, 21397, 14288, -1, 21397, 14275, 14288, -1, 21397, 21386, 14275, -1, 21386, 14276, 14275, -1, 21386, 21373, 14276, -1, 6221, 19964, 6219, -1, 19928, 19964, 6221, -1, 6219, 20006, 6228, -1, 19964, 20006, 6219, -1, 6228, 18395, 6232, -1, 20006, 18395, 6228, -1, 18396, 6208, 6215, -1, 18396, 20007, 6208, -1, 20007, 6204, 6208, -1, 20007, 19965, 6204, -1, 19965, 6203, 6204, -1, 19965, 19924, 6203, -1, 6153, 18552, 6154, -1, 18469, 18552, 6153, -1, 6154, 18549, 6157, -1, 18552, 18549, 6154, -1, 6157, 18601, 6161, -1, 18549, 18601, 6157, -1, 18602, 6235, 6242, -1, 18602, 18551, 6235, -1, 18551, 6222, 6235, -1, 18551, 18550, 6222, -1, 18550, 6223, 6222, -1, 18550, 18427, 6223, -1, 6129, 18697, 6127, -1, 18666, 18697, 6129, -1, 6127, 18778, 6136, -1, 18697, 18778, 6127, -1, 6136, 18876, 6140, -1, 18778, 18876, 6136, -1, 6181, 18877, 6174, -1, 18877, 18779, 6174, -1, 18779, 6170, 6174, -1, 18779, 18698, 6170, -1, 18698, 6169, 6170, -1, 18698, 18619, 6169, -1, 6265, 19652, 6266, -1, 6266, 21333, 6256, -1, 19652, 21333, 6266, -1, 6256, 21342, 6257, -1, 21333, 21342, 6256, -1, 21342, 19754, 6257, -1, 14299, 21343, 14300, -1, 19755, 21343, 14299, -1, 14300, 21334, 14303, -1, 21343, 21334, 14300, -1, 14303, 19651, 14304, -1, 21334, 19651, 14303, -1, 6289, 21377, 6290, -1, 6290, 21390, 6280, -1, 21377, 21390, 6290, -1, 6280, 21399, 6281, -1, 21390, 21399, 6280, -1, 21399, 19903, 6281, -1, 6261, 21400, 6259, -1, 19884, 21400, 6261, -1, 6259, 21392, 6273, -1, 21400, 21392, 6259, -1, 6273, 21370, 6274, -1, 21392, 21370, 6273, -1, 6337, 21436, 6338, -1, 6338, 21448, 6328, -1, 21436, 21448, 6338, -1, 6328, 21456, 6329, -1, 21448, 21456, 6328, -1, 21456, 20027, 6329, -1, 6285, 21457, 6283, -1, 20002, 21457, 6285, -1, 6283, 21449, 6297, -1, 21457, 21449, 6283, -1, 6297, 21429, 6298, -1, 21449, 21429, 6297, -1, 6313, 18431, 6314, -1, 6314, 18479, 6304, -1, 18431, 18479, 6314, -1, 6304, 18507, 6305, -1, 18479, 18507, 6304, -1, 18507, 18562, 6305, -1, 6333, 18483, 6331, -1, 18520, 18483, 6333, -1, 6331, 18448, 6345, -1, 18483, 18448, 6331, -1, 6345, 18408, 6346, -1, 18448, 18408, 6345, -1, 6250, 18653, 6251, -1, 6251, 18689, 6247, -1, 18653, 18689, 6251, -1, 6247, 18735, 6248, -1, 18689, 18735, 6247, -1, 18735, 18833, 6248, -1, 6309, 18695, 6306, -1, 18743, 18695, 6309, -1, 6306, 18652, 6321, -1, 18695, 18652, 6306, -1, 6321, 18654, 6322, -1, 18652, 18654, 6321, -1, 6621, 19414, 6622, -1, 6622, 21260, 6612, -1, 19414, 21260, 6622, -1, 6612, 21269, 6613, -1, 21260, 21269, 6612, -1, 21269, 19522, 6613, -1, 14347, 21270, 14348, -1, 19487, 21270, 14347, -1, 14348, 21261, 14351, -1, 21270, 21261, 14348, -1, 14351, 19413, 14352, -1, 21261, 19413, 14351, -1, 6597, 19578, 6598, -1, 6598, 21308, 6588, -1, 19578, 21308, 6598, -1, 6588, 21316, 6589, -1, 21308, 21316, 6588, -1, 21316, 19667, 6589, -1, 6617, 21317, 6615, -1, 19637, 21317, 6617, -1, 6615, 21309, 6629, -1, 21317, 21309, 6615, -1, 6629, 19577, 6630, -1, 21309, 19577, 6629, -1, 6645, 19720, 6646, -1, 6646, 21358, 6636, -1, 19720, 21358, 6646, -1, 6636, 21366, 6637, -1, 21358, 21366, 6636, -1, 21366, 19811, 6637, -1, 6593, 21361, 6591, -1, 19773, 21361, 6593, -1, 6591, 21350, 6605, -1, 21361, 21350, 6591, -1, 6605, 19704, 6606, -1, 21350, 19704, 6605, -1, 6669, 19844, 6670, -1, 6670, 21411, 6660, -1, 19844, 21411, 6670, -1, 6660, 21418, 6661, -1, 21411, 21418, 6660, -1, 21418, 19941, 6661, -1, 6641, 21413, 6639, -1, 19912, 21413, 6641, -1, 6639, 21405, 6653, -1, 21413, 21405, 6639, -1, 6653, 19831, 6654, -1, 21405, 19831, 6653, -1, 6582, 19985, 6583, -1, 6583, 18381, 6579, -1, 19985, 18381, 6583, -1, 6579, 18380, 6580, -1, 18381, 18380, 6579, -1, 18380, 18425, 6580, -1, 6665, 18382, 6662, -1, 18388, 18382, 6665, -1, 6662, 21464, 6677, -1, 18382, 21464, 6662, -1, 6677, 19967, 6678, -1, 21464, 19967, 6677, -1, 6377, 21235, 6378, -1, 19349, 21235, 6377, -1, 6378, 21247, 6381, -1, 21235, 21247, 6378, -1, 6381, 19434, 6385, -1, 21247, 19434, 6381, -1, 19435, 14324, 14331, -1, 19435, 21237, 14324, -1, 21237, 14311, 14324, -1, 21237, 21224, 14311, -1, 21224, 14312, 14311, -1, 21224, 19337, 14312, -1, 6411, 19553, 6409, -1, 19505, 19553, 6411, -1, 6409, 19552, 6418, -1, 19553, 19552, 6409, -1, 6418, 19608, 6422, -1, 19552, 19608, 6418, -1, 19604, 6398, 6405, -1, 19604, 19551, 6398, -1, 19551, 6394, 6398, -1, 19551, 19554, 6394, -1, 19554, 6393, 6394, -1, 19554, 19481, 6393, -1, 6435, 19686, 6436, -1, 19631, 19686, 6435, -1, 6436, 19688, 6439, -1, 19686, 19688, 6436, -1, 6439, 19731, 6443, -1, 19688, 19731, 6439, -1, 19727, 6425, 6432, -1, 19727, 19689, 6425, -1, 19689, 6412, 6425, -1, 19689, 19687, 6412, -1, 19687, 6413, 6412, -1, 19687, 19620, 6413, -1, 6353, 21381, 6351, -1, 19781, 21381, 6353, -1, 6351, 21393, 6360, -1, 21381, 21393, 6351, -1, 6360, 19887, 6364, -1, 21393, 19887, 6360, -1, 19850, 6456, 6463, -1, 19850, 21394, 6456, -1, 21394, 6452, 6456, -1, 21394, 21382, 6452, -1, 21382, 6451, 6452, -1, 21382, 19752, 6451, -1, 6525, 19199, 6526, -1, 6526, 20728, 6516, -1, 19199, 20728, 6526, -1, 6516, 20824, 6517, -1, 20728, 20824, 6516, -1, 20824, 19314, 6517, -1, 14335, 20826, 14336, -1, 19260, 20826, 14335, -1, 14336, 20732, 14339, -1, 20826, 20732, 14336, -1, 14339, 19198, 14340, -1, 20732, 19198, 14339, -1, 6501, 19335, 6502, -1, 6502, 21227, 6492, -1, 19335, 21227, 6502, -1, 6492, 21238, 6493, -1, 21227, 21238, 6492, -1, 21238, 19459, 6493, -1, 6521, 21239, 6519, -1, 19395, 21239, 6521, -1, 6519, 21228, 6533, -1, 21239, 21228, 6519, -1, 6533, 19334, 6534, -1, 21228, 19334, 6533, -1, 6477, 19485, 6478, -1, 6478, 21279, 6468, -1, 19485, 21279, 6478, -1, 6468, 21287, 6469, -1, 21279, 21287, 6468, -1, 21287, 19599, 6469, -1, 6497, 21288, 6495, -1, 19541, 21288, 6497, -1, 6495, 21281, 6509, -1, 21288, 21281, 6495, -1, 6509, 19465, 6510, -1, 21281, 19465, 6509, -1, 6561, 19622, 6562, -1, 6562, 21325, 6552, -1, 19622, 21325, 6562, -1, 6552, 21330, 6553, -1, 21325, 21330, 6552, -1, 21330, 19733, 6553, -1, 6473, 21327, 6471, -1, 19681, 21327, 6473, -1, 6471, 21322, 6485, -1, 21327, 21322, 6471, -1, 6485, 19613, 6486, -1, 21322, 19613, 6485, -1, 6546, 19766, 6547, -1, 6547, 21376, 6543, -1, 19766, 21376, 6547, -1, 6543, 21387, 6544, -1, 21376, 21387, 6543, -1, 21387, 19876, 6544, -1, 6557, 21378, 6554, -1, 19817, 21378, 6557, -1, 6554, 21369, 6569, -1, 21378, 21369, 6554, -1, 6569, 19747, 6570, -1, 21369, 19747, 6569, -1, 6767, 21312, 6768, -1, 19594, 21312, 6767, -1, 6768, 21323, 6771, -1, 21312, 21323, 6768, -1, 6771, 19683, 6775, -1, 21323, 19683, 6771, -1, 19669, 14372, 14379, -1, 19669, 21314, 14372, -1, 21314, 14359, 14372, -1, 21314, 21304, 14359, -1, 21304, 14360, 14359, -1, 21304, 19580, 14360, -1, 6743, 19743, 6741, -1, 19745, 19743, 6743, -1, 6741, 19779, 6750, -1, 19743, 19779, 6741, -1, 6750, 19829, 6754, -1, 19779, 19829, 6750, -1, 19803, 6788, 6795, -1, 19803, 19778, 6788, -1, 19778, 6784, 6788, -1, 19778, 19740, 6784, -1, 19740, 6783, 6784, -1, 19740, 19717, 6783, -1, 6709, 19863, 6710, -1, 19860, 19863, 6709, -1, 6710, 19921, 6713, -1, 19863, 19921, 6710, -1, 6713, 19955, 6717, -1, 19921, 19955, 6713, -1, 19939, 6757, 6764, -1, 19939, 19920, 6757, -1, 19920, 6744, 6757, -1, 19920, 19862, 6744, -1, 19862, 6745, 6744, -1, 19862, 19837, 6745, -1, 6685, 18405, 6683, -1, 20009, 18405, 6685, -1, 6683, 18404, 6692, -1, 18405, 18404, 6683, -1, 6692, 18438, 6696, -1, 18404, 18438, 6692, -1, 18440, 6730, 6737, -1, 18440, 18407, 6730, -1, 18407, 6726, 6730, -1, 18407, 18406, 6726, -1, 18406, 6725, 6726, -1, 18406, 19970, 6725, -1, 6945, 2168, 874, -1, 6945, 6944, 2168, -1, 6944, 2249, 2168, -1, 6944, 6957, 2249, -1, 6957, 2387, 2249, -1, 6957, 6964, 2387, -1, 2477, 6913, 2349, -1, 6917, 6913, 2477, -1, 2349, 6910, 2238, -1, 6913, 6910, 2349, -1, 2238, 6909, 887, -1, 6910, 6909, 2238, -1, 6925, 1085, 1059, -1, 6925, 6926, 1085, -1, 6926, 1137, 1085, -1, 6926, 6930, 1137, -1, 6930, 1136, 1137, -1, 6930, 6937, 1136, -1, 1134, 7008, 1135, -1, 7012, 7008, 1134, -1, 1135, 6999, 1084, -1, 7008, 6999, 1135, -1, 1084, 7001, 1062, -1, 6999, 7001, 1084, -1, 7003, 1221, 1167, -1, 7003, 7002, 1221, -1, 7002, 1283, 1221, -1, 7002, 7015, 1283, -1, 7015, 1282, 1283, -1, 7015, 7022, 1282, -1, 1280, 6971, 1281, -1, 6975, 6971, 1280, -1, 1281, 6968, 1222, -1, 6971, 6968, 1281, -1, 1222, 6967, 1168, -1, 6968, 6967, 1222, -1, 6983, 3194, 1306, -1, 6983, 6984, 3194, -1, 6984, 3205, 3194, -1, 6984, 6988, 3205, -1, 6988, 3213, 3205, -1, 6988, 6995, 3213, -1, 3212, 14395, 3204, -1, 14399, 14395, 3212, -1, 3204, 14388, 3193, -1, 14395, 14388, 3204, -1, 3193, 14390, 1345, -1, 14388, 14390, 3193, -1, 6903, 6902, 1434, -1, 6902, 1677, 1434, -1, 6902, 6899, 1677, -1, 6899, 1773, 1677, -1, 6899, 6898, 1773, -1, 6898, 858, 1773, -1, 1672, 6882, 1550, -1, 1550, 6882, 6881, -1, 1772, 6872, 1672, -1, 1672, 6872, 6882, -1, 865, 6873, 1772, -1, 1772, 6873, 6872, -1, 6890, 6889, 2046, -1, 6889, 2193, 2046, -1, 6889, 6875, 2193, -1, 6875, 2282, 2193, -1, 6875, 6877, 2282, -1, 6877, 1020, 2282, -1, 2192, 6810, 2099, -1, 2099, 6810, 6809, -1, 2281, 6800, 2192, -1, 2192, 6800, 6810, -1, 1024, 6801, 2281, -1, 2281, 6801, 6800, -1, 6818, 6817, 2644, -1, 6817, 2821, 2644, -1, 6817, 6803, 2821, -1, 6803, 2932, 2821, -1, 6803, 6805, 2932, -1, 6805, 1145, 2932, -1, 2820, 6834, 2711, -1, 2711, 6834, 6833, -1, 2931, 6824, 2820, -1, 2820, 6824, 6834, -1, 1155, 6825, 2931, -1, 2931, 6825, 6824, -1, 6842, 6841, 3112, -1, 6841, 3124, 3112, -1, 6841, 6827, 3124, -1, 6827, 3135, 3124, -1, 3135, 6829, 1300, -1, 6827, 6829, 3135, -1, 3134, 6858, 3120, -1, 3120, 6858, 6857, -1, 3144, 6848, 3134, -1, 3134, 6848, 6858, -1, 1320, 6849, 3144, -1, 3144, 6849, 6848, -1, 6866, 6865, 3174, -1, 6865, 3185, 3174, -1, 6865, 6850, 3185, -1, 6850, 3192, 3185, -1, 6850, 6853, 3192, -1, 6853, 1436, 3192, -1, 3191, 14386, 3182, -1, 3182, 14386, 14385, -1, 3201, 14382, 3191, -1, 3191, 14382, 14386, -1, 1477, 14383, 3201, -1, 3201, 14383, 14382, -1, 964, 7550, 2585, -1, 7551, 7550, 964, -1, 2585, 7547, 2683, -1, 7550, 7547, 2585, -1, 2683, 7546, 1035, -1, 7547, 7546, 2683, -1, 1088, 7557, 2679, -1, 2679, 7556, 2583, -1, 7557, 7556, 2679, -1, 2583, 7566, 965, -1, 7556, 7566, 2583, -1, 7566, 7565, 965, -1, 1115, 7573, 3108, -1, 7574, 7573, 1115, -1, 3108, 7559, 3119, -1, 7573, 7559, 3108, -1, 3119, 7561, 1177, -1, 7559, 7561, 3119, -1, 1241, 7497, 3118, -1, 3118, 7496, 3107, -1, 7497, 7496, 3118, -1, 3107, 7506, 1117, -1, 7496, 7506, 3107, -1, 7506, 7505, 1117, -1, 1246, 7513, 3163, -1, 7514, 7513, 1246, -1, 3163, 7499, 3172, -1, 7513, 7499, 3163, -1, 3172, 7501, 1329, -1, 7499, 7501, 3172, -1, 1391, 7473, 3178, -1, 3178, 7472, 3168, -1, 7473, 7472, 3178, -1, 3168, 7482, 1269, -1, 7472, 7482, 3168, -1, 7482, 7481, 1269, -1, 1407, 7489, 3215, -1, 7490, 7489, 1407, -1, 3215, 7475, 3226, -1, 7489, 7475, 3215, -1, 3226, 7477, 1483, -1, 7475, 7477, 3226, -1, 1536, 7521, 3229, -1, 3229, 7520, 3221, -1, 7521, 7520, 3229, -1, 3221, 7530, 1418, -1, 7520, 7530, 3221, -1, 7530, 7529, 1418, -1, 1549, 7537, 3274, -1, 7538, 7537, 1549, -1, 3274, 7522, 3284, -1, 7537, 7522, 3274, -1, 3284, 7525, 1623, -1, 7522, 7525, 3284, -1, 1682, 14467, 3295, -1, 3295, 14466, 3282, -1, 14467, 14466, 3295, -1, 3282, 14470, 1568, -1, 14466, 14470, 3282, -1, 14470, 14469, 1568, -1, 7227, 1178, 687, -1, 7226, 1178, 7227, -1, 7239, 1315, 7226, -1, 7226, 1315, 1178, -1, 7246, 779, 7239, -1, 7239, 779, 1315, -1, 1295, 7133, 741, -1, 1424, 7134, 1295, -1, 1295, 7134, 7133, -1, 788, 7137, 1424, -1, 1424, 7137, 7134, -1, 788, 7141, 7137, -1, 7149, 850, 799, -1, 7150, 850, 7149, -1, 7154, 896, 7150, -1, 7150, 896, 850, -1, 7161, 897, 7154, -1, 7154, 897, 896, -1, 849, 7167, 848, -1, 899, 7165, 849, -1, 849, 7165, 7167, -1, 898, 7174, 899, -1, 899, 7174, 7165, -1, 898, 7178, 7174, -1, 7169, 990, 950, -1, 7168, 990, 7169, -1, 7181, 1047, 7168, -1, 7168, 1047, 990, -1, 7188, 1048, 7181, -1, 7181, 1048, 1047, -1, 991, 7191, 992, -1, 1050, 7192, 991, -1, 991, 7192, 7191, -1, 1051, 7195, 1050, -1, 1050, 7195, 7192, -1, 1051, 7199, 7195, -1, 7207, 3087, 1098, -1, 7208, 3087, 7207, -1, 7212, 3110, 7208, -1, 7208, 3110, 3087, -1, 7219, 1185, 7212, -1, 7212, 1185, 3110, -1, 3086, 14418, 1160, -1, 3109, 14416, 3086, -1, 3086, 14416, 14418, -1, 1234, 14423, 3109, -1, 3109, 14423, 14416, -1, 1234, 14427, 14423, -1, 7079, 7078, 544, -1, 7078, 545, 544, -1, 7078, 7075, 545, -1, 7075, 625, 545, -1, 7075, 7074, 625, -1, 7074, 617, 625, -1, 543, 7094, 546, -1, 546, 7094, 7093, -1, 624, 7084, 543, -1, 543, 7084, 7094, -1, 643, 7085, 624, -1, 624, 7085, 7084, -1, 7102, 7101, 681, -1, 7101, 1228, 681, -1, 7101, 7087, 1228, -1, 7087, 1348, 1228, -1, 7087, 7089, 1348, -1, 7089, 746, 1348, -1, 1226, 7118, 682, -1, 682, 7118, 7117, -1, 1343, 7108, 1226, -1, 1226, 7108, 7118, -1, 776, 7109, 1343, -1, 1343, 7109, 7108, -1, 7126, 7125, 806, -1, 7125, 1823, 806, -1, 7125, 7111, 1823, -1, 7111, 1914, 1823, -1, 7111, 7113, 1914, -1, 7113, 890, 1914, -1, 1882, 7058, 828, -1, 828, 7058, 7057, -1, 1981, 7048, 1882, -1, 1882, 7048, 7058, -1, 934, 7049, 1981, -1, 1981, 7049, 7048, -1, 7066, 7065, 960, -1, 7065, 2325, 960, -1, 7065, 7051, 2325, -1, 7051, 2436, 2325, -1, 7051, 7053, 2436, -1, 7053, 1039, 2436, -1, 2421, 7034, 974, -1, 974, 7034, 7033, -1, 2541, 7024, 2421, -1, 2421, 7024, 7034, -1, 1070, 7025, 2541, -1, 2541, 7025, 7024, -1, 7042, 7041, 1093, -1, 7041, 2994, 1093, -1, 7041, 7026, 2994, -1, 7026, 3068, 2994, -1, 7026, 7029, 3068, -1, 7029, 1165, 3068, -1, 3057, 14414, 1122, -1, 1122, 14414, 14413, -1, 3105, 14410, 3057, -1, 3057, 14410, 14414, -1, 1204, 14411, 3105, -1, 3105, 14411, 14410, -1, 1446, 11002, 3233, -1, 11003, 11002, 1446, -1, 3233, 10999, 3243, -1, 11002, 10999, 3233, -1, 3243, 10998, 1560, -1, 10999, 10998, 3243, -1, 1559, 10973, 3242, -1, 3242, 10972, 3232, -1, 10973, 10972, 3242, -1, 3232, 10982, 1447, -1, 10972, 10982, 3232, -1, 10982, 10981, 1447, -1, 3276, 10989, 3300, -1, 10990, 10989, 3276, -1, 3300, 10975, 3308, -1, 10989, 10975, 3300, -1, 3308, 10977, 1689, -1, 10975, 10977, 3308, -1, 1713, 10949, 3307, -1, 3307, 10948, 3299, -1, 10949, 10948, 3307, -1, 3299, 10958, 3283, -1, 10948, 10958, 3299, -1, 10958, 10957, 3283, -1, 3343, 10965, 3363, -1, 10966, 10965, 3343, -1, 3363, 10951, 3375, -1, 10965, 10951, 3363, -1, 3375, 10953, 1810, -1, 10951, 10953, 3375, -1, 1837, 11033, 3374, -1, 3374, 11032, 3362, -1, 11033, 11032, 3374, -1, 3362, 11042, 3350, -1, 11032, 11042, 3362, -1, 11042, 11041, 3350, -1, 71, 11049, 120, -1, 11050, 11049, 71, -1, 120, 11035, 169, -1, 11049, 11035, 120, -1, 169, 11037, 214, -1, 11035, 11037, 169, -1, 259, 11009, 197, -1, 197, 11008, 161, -1, 11009, 11008, 197, -1, 161, 11018, 102, -1, 11008, 11018, 161, -1, 11018, 11017, 102, -1, 377, 11025, 375, -1, 11026, 11025, 377, -1, 375, 11010, 424, -1, 11025, 11010, 375, -1, 424, 11013, 489, -1, 11010, 11013, 424, -1, 577, 14963, 476, -1, 476, 14962, 413, -1, 14963, 14962, 476, -1, 413, 14966, 376, -1, 14962, 14966, 413, -1, 14966, 14965, 376, -1, 7251, 3198, 1376, -1, 7251, 7250, 3198, -1, 7250, 3207, 3198, -1, 7250, 7263, 3207, -1, 7263, 1472, 3207, -1, 7263, 7270, 1472, -1, 1486, 7301, 3218, -1, 7305, 7301, 1486, -1, 3218, 7298, 3206, -1, 7301, 7298, 3218, -1, 3206, 7297, 1387, -1, 7298, 7297, 3206, -1, 7313, 1544, 1519, -1, 7313, 7314, 1544, -1, 7314, 1581, 1544, -1, 7314, 7318, 1581, -1, 7318, 1614, 1581, -1, 7318, 7325, 1614, -1, 1635, 7280, 1582, -1, 7284, 7280, 1635, -1, 1582, 7271, 1545, -1, 7280, 7271, 1582, -1, 1545, 7273, 1546, -1, 7271, 7273, 1545, -1, 7275, 1670, 1642, -1, 7275, 7274, 1670, -1, 7274, 1731, 1670, -1, 7274, 7287, 1731, -1, 7287, 1749, 1731, -1, 7287, 7294, 1749, -1, 1766, 7335, 1732, -1, 7339, 7335, 1766, -1, 1732, 7332, 1671, -1, 7335, 7332, 1732, -1, 1671, 7331, 1669, -1, 7332, 7331, 1671, -1, 7347, 65, 1783, -1, 7347, 7348, 65, -1, 7348, 69, 65, -1, 7348, 7352, 69, -1, 7352, 113, 69, -1, 7352, 7359, 113, -1, 111, 14443, 63, -1, 14447, 14443, 111, -1, 63, 14436, 64, -1, 14443, 14436, 63, -1, 64, 14438, 1820, -1, 14436, 14438, 64, -1, 1193, 7370, 3148, -1, 7371, 7370, 1193, -1, 3148, 7367, 3157, -1, 7370, 7367, 3148, -1, 3157, 7366, 1273, -1, 7367, 7366, 3157, -1, 1311, 7449, 3156, -1, 3156, 7448, 3147, -1, 7449, 7448, 3156, -1, 3147, 7458, 1195, -1, 7448, 7458, 3147, -1, 7458, 7457, 1195, -1, 1369, 7465, 3203, -1, 7466, 7465, 1369, -1, 3203, 7451, 3211, -1, 7465, 7451, 3203, -1, 3211, 7453, 1432, -1, 7451, 7453, 3211, -1, 1468, 7425, 3210, -1, 3210, 7424, 3202, -1, 7425, 7424, 3210, -1, 3202, 7434, 1371, -1, 7424, 7434, 3202, -1, 7434, 7433, 1371, -1, 1506, 7441, 3258, -1, 7442, 7441, 1506, -1, 3258, 7427, 3269, -1, 7441, 7427, 3258, -1, 3269, 7429, 1576, -1, 7427, 7429, 3269, -1, 1617, 7401, 3268, -1, 3268, 7400, 3257, -1, 7401, 7400, 3268, -1, 3257, 7410, 1521, -1, 7400, 7410, 3257, -1, 7410, 7409, 1521, -1, 1637, 7417, 3313, -1, 7418, 7417, 1637, -1, 3313, 7403, 3322, -1, 7417, 7403, 3313, -1, 3322, 7405, 1722, -1, 7403, 7405, 3322, -1, 1752, 7377, 3331, -1, 3331, 7376, 3320, -1, 7377, 7376, 3331, -1, 3320, 7386, 1650, -1, 7376, 7386, 3320, -1, 7386, 7385, 1650, -1, 1778, 7393, 3386, -1, 7394, 7393, 1778, -1, 3386, 7378, 42, -1, 7393, 7378, 3386, -1, 42, 7381, 49, -1, 7378, 7381, 42, -1, 91, 14459, 40, -1, 40, 14458, 41, -1, 14459, 14458, 40, -1, 41, 14462, 1795, -1, 14458, 14462, 41, -1, 14462, 14461, 1795, -1, 7675, 3104, 1120, -1, 7675, 7674, 3104, -1, 7674, 3117, 3104, -1, 7674, 7687, 3117, -1, 7687, 1218, 3117, -1, 7687, 7694, 1218, -1, 1217, 7643, 3128, -1, 7647, 7643, 1217, -1, 3128, 7640, 3115, -1, 7643, 7640, 3128, -1, 3115, 7639, 1131, -1, 7640, 7639, 3115, -1, 7655, 1339, 1266, -1, 7655, 7656, 1339, -1, 7656, 1340, 1339, -1, 7656, 7660, 1340, -1, 7660, 1403, 1340, -1, 7660, 7667, 1403, -1, 1402, 7622, 1342, -1, 7626, 7622, 1402, -1, 1342, 7613, 1341, -1, 7622, 7613, 1342, -1, 1341, 7615, 1291, -1, 7613, 7615, 1341, -1, 7617, 1491, 1412, -1, 7617, 7616, 1491, -1, 7616, 1488, 1491, -1, 7616, 7629, 1488, -1, 7629, 1532, 1488, -1, 7629, 7636, 1532, -1, 1533, 7585, 1489, -1, 7589, 7585, 1533, -1, 1489, 7582, 1490, -1, 7585, 7582, 1489, -1, 1490, 7581, 1427, -1, 7582, 7581, 1490, -1, 7597, 3289, 1557, -1, 7597, 7598, 3289, -1, 7598, 3302, 3289, -1, 7598, 7602, 3302, -1, 7602, 1659, 3302, -1, 7602, 7609, 1659, -1, 1692, 14479, 3301, -1, 14483, 14479, 1692, -1, 3301, 14472, 3288, -1, 14479, 14472, 3301, -1, 3288, 14474, 1585, -1, 14472, 14474, 3288, -1, 7807, 136, 138, -1, 7806, 136, 7807, -1, 7819, 156, 7806, -1, 7806, 156, 136, -1, 7826, 182, 7819, -1, 7819, 182, 156, -1, 153, 7829, 137, -1, 175, 7830, 153, -1, 153, 7830, 7829, -1, 194, 7833, 175, -1, 175, 7833, 7830, -1, 194, 7837, 7833, -1, 7845, 520, 482, -1, 7846, 520, 7845, -1, 7850, 517, 7846, -1, 7846, 517, 520, -1, 7857, 358, 7850, -1, 7850, 358, 517, -1, 519, 7897, 493, -1, 518, 7895, 519, -1, 519, 7895, 7897, -1, 362, 7904, 518, -1, 518, 7904, 7895, -1, 362, 7908, 7904, -1, 7899, 584, 559, -1, 7898, 584, 7899, -1, 7911, 585, 7898, -1, 7898, 585, 584, -1, 7918, 620, 7911, -1, 7911, 620, 585, -1, 587, 7863, 566, -1, 586, 7864, 587, -1, 587, 7864, 7863, -1, 623, 7867, 586, -1, 586, 7867, 7864, -1, 623, 7871, 7867, -1, 7879, 1109, 637, -1, 7880, 1109, 7879, -1, 7884, 1249, 7880, -1, 7880, 1249, 1109, -1, 7891, 1374, 7884, -1, 7884, 1374, 1249, -1, 1108, 14506, 661, -1, 1248, 14504, 1108, -1, 1108, 14504, 14506, -1, 1373, 14511, 1248, -1, 1248, 14511, 14504, -1, 1373, 14515, 14511, -1, 61, 7718, 47, -1, 47, 7718, 7717, -1, 74, 7708, 61, -1, 61, 7708, 7718, -1, 84, 7709, 74, -1, 74, 7709, 7708, -1, 14499, 43, 14500, -1, 14496, 62, 14499, -1, 14499, 62, 43, -1, 14495, 75, 14496, -1, 14496, 75, 62, -1, 14495, 79, 75, -1, 143, 7742, 115, -1, 115, 7742, 7741, -1, 159, 7732, 143, -1, 143, 7732, 7742, -1, 189, 7733, 159, -1, 159, 7733, 7732, -1, 7726, 7725, 110, -1, 7725, 144, 110, -1, 7725, 7711, 144, -1, 7711, 160, 144, -1, 7711, 7713, 160, -1, 7713, 166, 160, -1, 271, 7790, 248, -1, 248, 7790, 7789, -1, 287, 7780, 271, -1, 271, 7780, 7790, -1, 312, 7781, 287, -1, 287, 7781, 7780, -1, 7750, 7749, 229, -1, 7749, 254, 229, -1, 7749, 7735, 254, -1, 7735, 277, 254, -1, 7735, 7737, 277, -1, 7737, 292, 277, -1, 439, 7766, 397, -1, 397, 7766, 7765, -1, 501, 7756, 439, -1, 439, 7756, 7766, -1, 601, 7757, 501, -1, 501, 7757, 7756, -1, 7798, 7797, 366, -1, 7797, 411, 366, -1, 7797, 7783, 411, -1, 7783, 445, 411, -1, 7783, 7785, 445, -1, 7785, 534, 445, -1, 1055, 7703, 936, -1, 936, 7703, 7702, -1, 1203, 7699, 1055, -1, 1055, 7699, 7703, -1, 1322, 7700, 1203, -1, 1203, 7700, 7699, -1, 7773, 829, 7774, -1, 7758, 945, 7773, -1, 7773, 945, 829, -1, 7761, 1073, 7758, -1, 7758, 1073, 945, -1, 7761, 1216, 1073, -1, 8043, 8042, 208, -1, 8042, 209, 208, -1, 8042, 8039, 209, -1, 8039, 241, 209, -1, 8039, 8038, 241, -1, 8038, 268, 241, -1, 207, 8058, 8057, -1, 206, 8058, 207, -1, 240, 8048, 206, -1, 206, 8048, 8058, -1, 266, 8049, 240, -1, 240, 8049, 8048, -1, 8066, 8065, 345, -1, 8065, 346, 345, -1, 8065, 8051, 346, -1, 8051, 394, 346, -1, 8051, 8053, 394, -1, 8053, 437, 394, -1, 347, 8082, 8081, -1, 344, 8082, 347, -1, 393, 8072, 344, -1, 344, 8072, 8082, -1, 436, 8073, 393, -1, 393, 8073, 8072, -1, 8090, 8089, 598, -1, 8089, 775, 598, -1, 8089, 8075, 775, -1, 8075, 881, 775, -1, 8075, 8077, 881, -1, 8077, 653, 881, -1, 611, 8130, 8129, -1, 774, 8130, 611, -1, 880, 8120, 774, -1, 774, 8120, 8130, -1, 690, 8121, 880, -1, 880, 8121, 8120, -1, 8138, 8137, 719, -1, 8137, 1409, 719, -1, 8137, 8123, 1409, -1, 8123, 1522, 1409, -1, 8123, 8125, 1522, -1, 8125, 784, 1522, -1, 729, 8106, 8105, -1, 1501, 8106, 729, -1, 1621, 8096, 1501, -1, 1501, 8096, 8106, -1, 819, 8097, 1621, -1, 1621, 8097, 8096, -1, 8114, 8113, 852, -1, 8113, 2025, 852, -1, 8113, 8098, 2025, -1, 8098, 2102, 2025, -1, 8098, 8101, 2102, -1, 8101, 948, 2102, -1, 876, 14550, 14549, -1, 2086, 14550, 876, -1, 2181, 14546, 2086, -1, 2086, 14546, 14550, -1, 980, 14547, 2181, -1, 2181, 14547, 14546, -1, 8014, 336, 8015, -1, 8015, 336, 338, -1, 8027, 388, 8014, -1, 8014, 388, 336, -1, 8034, 429, 8027, -1, 8027, 429, 388, -1, 383, 7945, 337, -1, 418, 7946, 383, -1, 383, 7946, 7945, -1, 462, 7949, 418, -1, 418, 7949, 7946, -1, 462, 7953, 7949, -1, 7962, 657, 7961, -1, 7961, 657, 608, -1, 7966, 658, 7962, -1, 7962, 658, 657, -1, 7973, 714, 7966, -1, 7966, 714, 658, -1, 656, 7921, 634, -1, 659, 7919, 656, -1, 656, 7919, 7921, -1, 716, 7928, 659, -1, 659, 7928, 7919, -1, 716, 7932, 7928, -1, 7922, 791, 7923, -1, 7923, 791, 722, -1, 7935, 792, 7922, -1, 7922, 792, 791, -1, 7942, 836, 7935, -1, 7935, 836, 792, -1, 790, 7979, 733, -1, 793, 7980, 790, -1, 790, 7980, 7979, -1, 835, 7983, 793, -1, 793, 7983, 7980, -1, 835, 7987, 7983, -1, 7996, 2124, 7995, -1, 7995, 2124, 856, -1, 8000, 2208, 7996, -1, 7996, 2208, 2124, -1, 8007, 986, 8000, -1, 8000, 986, 2208, -1, 2122, 14526, 902, -1, 2206, 14524, 2122, -1, 2122, 14524, 14526, -1, 1000, 14531, 2206, -1, 2206, 14531, 14524, -1, 1000, 14535, 14531, -1, 8238, 21432, 8239, -1, 8239, 21432, 21419, -1, 8251, 21445, 8238, -1, 8238, 21445, 21432, -1, 8258, 21455, 8251, -1, 8251, 21455, 21445, -1, 21431, 21442, 8203, -1, 21442, 8204, 8203, -1, 21442, 21454, 8204, -1, 21463, 8207, 21454, -1, 21454, 8207, 8204, -1, 21463, 8211, 8207, -1, 8220, 18436, 8219, -1, 8219, 18436, 18361, -1, 8224, 18434, 8220, -1, 8220, 18434, 18436, -1, 8231, 18492, 8224, -1, 8224, 18492, 18434, -1, 18401, 18435, 8179, -1, 18435, 8177, 8179, -1, 18435, 18463, 8177, -1, 18463, 8186, 8177, -1, 18463, 18508, 8186, -1, 18508, 8190, 8186, -1, 8180, 18590, 8181, -1, 8181, 18590, 18536, -1, 8193, 18591, 8180, -1, 8180, 18591, 18590, -1, 8200, 18605, 8193, -1, 8193, 18605, 18591, -1, 18563, 18592, 8145, -1, 18592, 8146, 8145, -1, 18592, 18589, 8146, -1, 18589, 8149, 8146, -1, 18589, 18611, 8149, -1, 18611, 8153, 8149, -1, 8162, 18671, 8161, -1, 8161, 18671, 18625, -1, 8166, 18683, 8162, -1, 8162, 18683, 18671, -1, 8173, 18693, 8166, -1, 8166, 18693, 18683, -1, 18647, 18670, 14554, -1, 18670, 14552, 14554, -1, 18670, 18682, 14552, -1, 18691, 14559, 18682, -1, 18682, 14559, 14552, -1, 18691, 14563, 14559, -1, 21379, 8294, 20901, -1, 20901, 8294, 8293, -1, 21388, 8284, 21379, -1, 21379, 8284, 8294, -1, 21001, 8285, 21388, -1, 21388, 8285, 8284, -1, 14579, 20900, 14580, -1, 14576, 21380, 14579, -1, 14579, 21380, 20900, -1, 14575, 21389, 14576, -1, 14576, 21389, 21380, -1, 14575, 20999, 21389, -1, 21437, 8270, 21423, -1, 21423, 8270, 8269, -1, 21446, 8260, 21437, -1, 21437, 8260, 8270, -1, 21111, 8261, 21446, -1, 21446, 8261, 8260, -1, 8301, 21416, 8302, -1, 8287, 21438, 8301, -1, 8301, 21438, 21416, -1, 8289, 21447, 8287, -1, 8287, 21447, 21438, -1, 8289, 21099, 21447, -1, 18413, 8318, 18366, -1, 18366, 8318, 8317, -1, 18441, 8308, 18413, -1, 18413, 8308, 8318, -1, 18474, 8309, 18441, -1, 18441, 8309, 8308, -1, 8277, 18368, 8278, -1, 8263, 18379, 8277, -1, 8277, 18379, 18368, -1, 8265, 18423, 8263, -1, 8263, 18423, 18379, -1, 8265, 18447, 18423, -1, 18572, 8342, 18539, -1, 18539, 8342, 8341, -1, 18581, 8332, 18572, -1, 18572, 8332, 8342, -1, 18598, 8333, 18581, -1, 18581, 8333, 8332, -1, 8325, 18516, 8326, -1, 8311, 18555, 8325, -1, 8325, 18555, 18516, -1, 8313, 18577, 8311, -1, 8311, 18577, 18555, -1, 8313, 18583, 18577, -1, 18664, 8363, 18639, -1, 18639, 8363, 8362, -1, 18675, 8359, 18664, -1, 18664, 8359, 8363, -1, 18687, 8360, 18675, -1, 18675, 8360, 8359, -1, 8349, 18640, 8350, -1, 8334, 18638, 8349, -1, 8349, 18638, 18640, -1, 8337, 18665, 8334, -1, 8334, 18665, 18638, -1, 8337, 18677, 18665, -1, 20851, 21352, 8369, -1, 21352, 8370, 8369, -1, 21352, 21363, 8370, -1, 21363, 8373, 8370, -1, 21363, 20936, 8373, -1, 20936, 8377, 8373, -1, 14587, 21339, 14588, -1, 14588, 21339, 20842, -1, 14600, 21353, 14587, -1, 14587, 21353, 21339, -1, 14607, 20922, 14600, -1, 14600, 20922, 21353, -1, 20987, 20986, 8403, -1, 20986, 8401, 8403, -1, 20986, 21020, 8401, -1, 21020, 8410, 8401, -1, 21020, 21057, 8410, -1, 21057, 8414, 8410, -1, 8386, 20990, 8385, -1, 8385, 20990, 20963, -1, 8390, 21021, 8386, -1, 8386, 21021, 20990, -1, 8397, 21039, 8390, -1, 8390, 21039, 21021, -1, 21084, 21081, 8427, -1, 21081, 8428, 8427, -1, 21081, 18376, 8428, -1, 18376, 8431, 8428, -1, 18376, 18373, 8431, -1, 18373, 8435, 8431, -1, 8404, 21080, 8405, -1, 8405, 21080, 21063, -1, 8417, 18374, 8404, -1, 8404, 18374, 21080, -1, 8424, 18375, 8417, -1, 8417, 18375, 18374, -1, 18499, 18494, 8461, -1, 18494, 8459, 8461, -1, 18494, 18510, 8459, -1, 18510, 8468, 8459, -1, 18510, 18547, 8468, -1, 18547, 8472, 8468, -1, 8444, 18496, 8443, -1, 8443, 18496, 18495, -1, 8448, 18511, 8444, -1, 8444, 18511, 18496, -1, 8455, 18548, 8448, -1, 8448, 18548, 18511, -1, 926, 9034, 927, -1, 9035, 9034, 926, -1, 927, 9031, 1030, -1, 9034, 9031, 927, -1, 1030, 9030, 1152, -1, 9031, 9030, 1030, -1, 9005, 1029, 1151, -1, 9005, 9004, 1029, -1, 9004, 925, 1029, -1, 9004, 9014, 925, -1, 9014, 930, 925, -1, 9014, 9013, 930, -1, 1657, 9021, 1658, -1, 9022, 9021, 1657, -1, 1658, 9007, 1780, -1, 9021, 9007, 1658, -1, 1780, 9009, 1886, -1, 9007, 9009, 1780, -1, 8981, 1779, 1885, -1, 8981, 8980, 1779, -1, 8980, 1656, 1779, -1, 8980, 8990, 1656, -1, 8990, 1661, 1656, -1, 8990, 8989, 1661, -1, 2129, 8997, 2127, -1, 8998, 8997, 2129, -1, 2127, 8983, 2210, -1, 8997, 8983, 2127, -1, 2210, 8985, 2259, -1, 8983, 8985, 2210, -1, 8957, 2284, 2298, -1, 8957, 8956, 2284, -1, 8956, 2191, 2284, -1, 8956, 8966, 2191, -1, 8966, 2128, 2191, -1, 8966, 8965, 2128, -1, 2318, 8973, 2771, -1, 8974, 8973, 2318, -1, 2771, 8959, 2881, -1, 8973, 8959, 2771, -1, 2881, 8961, 2400, -1, 8959, 8961, 2881, -1, 8933, 2979, 2423, -1, 8933, 8932, 2979, -1, 8932, 2862, 2979, -1, 8932, 8942, 2862, -1, 8942, 2333, 2862, -1, 8942, 8941, 2333, -1, 2448, 8949, 3133, -1, 8950, 8949, 2448, -1, 3133, 8934, 3142, -1, 8949, 8934, 3133, -1, 3142, 8937, 2520, -1, 8934, 8937, 3142, -1, 14671, 3151, 2551, -1, 14671, 14670, 3151, -1, 14670, 3141, 3151, -1, 14670, 14674, 3141, -1, 14674, 2473, 3141, -1, 14674, 14673, 2473, -1, 460, 8687, 458, -1, 458, 8686, 572, -1, 8687, 8686, 458, -1, 572, 8699, 713, -1, 8686, 8699, 572, -1, 8699, 8706, 713, -1, 815, 8655, 671, -1, 8659, 8655, 815, -1, 671, 8652, 560, -1, 8655, 8652, 671, -1, 560, 8651, 459, -1, 8652, 8651, 560, -1, 1183, 8667, 1181, -1, 1181, 8668, 1442, -1, 8667, 8668, 1181, -1, 1442, 8672, 1440, -1, 8668, 8672, 1442, -1, 8672, 8679, 1440, -1, 1547, 8634, 1441, -1, 8638, 8634, 1547, -1, 1441, 8625, 1270, -1, 8634, 8625, 1441, -1, 1270, 8627, 1182, -1, 8625, 8627, 1270, -1, 1956, 8629, 1961, -1, 1961, 8628, 2117, -1, 8629, 8628, 1961, -1, 2117, 8641, 2121, -1, 8628, 8641, 2117, -1, 8641, 8648, 2121, -1, 2115, 8597, 2116, -1, 8601, 8597, 2115, -1, 2116, 8594, 1954, -1, 8597, 8594, 2116, -1, 1954, 8593, 1955, -1, 8594, 8593, 1954, -1, 2231, 8609, 2497, -1, 2497, 8610, 2625, -1, 8609, 8610, 2497, -1, 2625, 8614, 2342, -1, 8610, 8614, 2625, -1, 8614, 8621, 2342, -1, 2361, 14627, 2624, -1, 14631, 14627, 2361, -1, 2624, 14620, 2496, -1, 14627, 14620, 2624, -1, 2496, 14622, 2272, -1, 14620, 14622, 2496, -1, 221, 8714, 223, -1, 8715, 8714, 221, -1, 223, 8711, 265, -1, 8714, 8711, 223, -1, 265, 8710, 291, -1, 8711, 8710, 265, -1, 8721, 264, 290, -1, 8721, 8720, 264, -1, 8720, 219, 264, -1, 8720, 8730, 219, -1, 8730, 220, 219, -1, 8730, 8729, 220, -1, 498, 8737, 499, -1, 8738, 8737, 498, -1, 499, 8723, 599, -1, 8737, 8723, 499, -1, 599, 8725, 742, -1, 8723, 8725, 599, -1, 8769, 595, 737, -1, 8769, 8768, 595, -1, 8768, 496, 595, -1, 8768, 8778, 496, -1, 8778, 497, 496, -1, 8778, 8777, 497, -1, 1187, 8785, 1188, -1, 8786, 8785, 1187, -1, 1188, 8771, 1231, -1, 8785, 8771, 1188, -1, 1231, 8773, 1370, -1, 8771, 8773, 1231, -1, 8745, 1326, 1466, -1, 8745, 8744, 1326, -1, 8744, 1186, 1326, -1, 8744, 8754, 1186, -1, 8754, 1190, 1186, -1, 8754, 8753, 1190, -1, 1830, 8761, 1828, -1, 8762, 8761, 1830, -1, 1828, 8747, 1913, -1, 8761, 8747, 1828, -1, 1913, 8749, 2016, -1, 8747, 8749, 1913, -1, 8793, 1990, 2071, -1, 8793, 8792, 1990, -1, 8792, 1892, 1990, -1, 8792, 8802, 1892, -1, 8802, 1829, 1892, -1, 8802, 8801, 1829, -1, 2228, 8809, 2340, -1, 8810, 8809, 2228, -1, 2340, 8794, 2476, -1, 8809, 8794, 2340, -1, 2476, 8797, 2306, -1, 8794, 8797, 2476, -1, 14643, 2588, 2335, -1, 14643, 14642, 2588, -1, 14642, 2452, 2588, -1, 14642, 14646, 2452, -1, 14646, 2246, 2452, -1, 14646, 14645, 2246, -1, 1858, 9774, 2024, -1, 9775, 9774, 1858, -1, 2024, 9771, 2083, -1, 9774, 9771, 2024, -1, 2083, 9770, 2096, -1, 9771, 9770, 2083, -1, 9745, 2081, 2169, -1, 9745, 9744, 2081, -1, 9744, 2022, 2081, -1, 9744, 9754, 2022, -1, 9754, 1929, 2022, -1, 9754, 9753, 1929, -1, 2383, 9761, 2606, -1, 9762, 9761, 2383, -1, 2606, 9747, 2718, -1, 9761, 9747, 2606, -1, 2718, 9749, 2378, -1, 9747, 9749, 2718, -1, 9721, 2717, 2382, -1, 9721, 9720, 2717, -1, 9720, 2604, 2717, -1, 9720, 9730, 2604, -1, 9730, 2470, 2604, -1, 9730, 9729, 2470, -1, 3049, 9737, 3103, -1, 9738, 9737, 3049, -1, 3103, 9723, 3114, -1, 9737, 9723, 3103, -1, 3114, 9725, 2500, -1, 9723, 9725, 3114, -1, 9805, 3121, 2502, -1, 9805, 9804, 3121, -1, 9804, 3111, 3121, -1, 9804, 9814, 3111, -1, 9814, 3095, 3111, -1, 9814, 9813, 3095, -1, 3158, 9821, 3167, -1, 9822, 9821, 3158, -1, 3167, 9807, 3177, -1, 9821, 9807, 3167, -1, 3177, 9809, 2631, -1, 9807, 9809, 3177, -1, 9781, 3186, 2653, -1, 9781, 9780, 3186, -1, 9780, 3175, 3186, -1, 9780, 9790, 3175, -1, 9790, 3166, 3175, -1, 9790, 9789, 3166, -1, 3214, 9797, 3225, -1, 9798, 9797, 3214, -1, 3225, 9782, 3231, -1, 9797, 9782, 3225, -1, 3231, 9785, 2755, -1, 9782, 9785, 3231, -1, 14783, 3244, 2795, -1, 14783, 14782, 3244, -1, 14782, 3230, 3244, -1, 14782, 14786, 3230, -1, 14786, 3222, 3230, -1, 14786, 14785, 3222, -1, 1496, 8853, 1627, -1, 1627, 8852, 1753, -1, 8853, 8852, 1627, -1, 1753, 8865, 1871, -1, 8852, 8865, 1753, -1, 8865, 8872, 1871, -1, 1938, 8903, 1848, -1, 8907, 8903, 1938, -1, 1848, 8900, 1738, -1, 8903, 8900, 1848, -1, 1738, 8899, 1607, -1, 8900, 8899, 1738, -1, 2104, 8915, 2225, -1, 2225, 8916, 2267, -1, 8915, 8916, 2225, -1, 2267, 8920, 2268, -1, 8916, 8920, 2267, -1, 8920, 8927, 2268, -1, 2269, 8882, 2270, -1, 8886, 8882, 2269, -1, 2270, 8873, 2226, -1, 8882, 8873, 2270, -1, 2226, 8875, 2158, -1, 8873, 8875, 2226, -1, 2309, 8877, 2351, -1, 2351, 8876, 2403, -1, 8877, 8876, 2351, -1, 2403, 8889, 2404, -1, 8876, 8889, 2403, -1, 8889, 8896, 2404, -1, 2405, 8821, 2402, -1, 8825, 8821, 2405, -1, 2402, 8818, 2353, -1, 8821, 8818, 2402, -1, 2353, 8817, 2352, -1, 8818, 8817, 2353, -1, 2450, 8833, 3146, -1, 3146, 8834, 3155, -1, 8833, 8834, 3146, -1, 3155, 8838, 2537, -1, 8834, 8838, 3155, -1, 8838, 8845, 2537, -1, 2572, 14655, 3154, -1, 14659, 14655, 2572, -1, 3154, 14648, 3145, -1, 14655, 14648, 3154, -1, 3145, 14650, 2516, -1, 14648, 14650, 3145, -1, 28, 9077, 26, -1, 26, 9076, 89, -1, 9077, 9076, 26, -1, 89, 9089, 152, -1, 9076, 9089, 89, -1, 9089, 9096, 152, -1, 186, 9045, 132, -1, 9049, 9045, 186, -1, 132, 9042, 83, -1, 9045, 9042, 132, -1, 83, 9041, 27, -1, 9042, 9041, 83, -1, 1897, 9057, 1945, -1, 1945, 9058, 1946, -1, 9057, 9058, 1945, -1, 1946, 9062, 511, -1, 9058, 9062, 1946, -1, 9062, 9069, 511, -1, 513, 9140, 1947, -1, 9144, 9140, 513, -1, 1947, 9131, 1948, -1, 9140, 9131, 1947, -1, 1948, 9133, 1920, -1, 9131, 9133, 1948, -1, 1997, 9135, 2038, -1, 2038, 9134, 2039, -1, 9135, 9134, 2038, -1, 2039, 9147, 1210, -1, 9134, 9147, 2039, -1, 9147, 9154, 1210, -1, 1225, 9103, 2040, -1, 9107, 9103, 1225, -1, 2040, 9100, 2037, -1, 9103, 9100, 2040, -1, 2037, 9099, 2006, -1, 9100, 9099, 2037, -1, 1555, 9115, 1556, -1, 1556, 9116, 1695, -1, 9115, 9116, 1556, -1, 1695, 9120, 1806, -1, 9116, 9120, 1695, -1, 9120, 9127, 1806, -1, 1805, 14683, 1694, -1, 14687, 14683, 1805, -1, 1694, 14676, 1554, -1, 14683, 14676, 1694, -1, 1554, 14678, 1561, -1, 14676, 14678, 1554, -1, 10536, 18411, 10537, -1, 10537, 18411, 18419, -1, 10546, 18399, 10536, -1, 10536, 18399, 18411, -1, 10545, 18387, 10546, -1, 10546, 18387, 18399, -1, 18412, 14891, 18415, -1, 18400, 14892, 18412, -1, 18412, 14892, 14891, -1, 18383, 14895, 18400, -1, 18400, 14895, 14892, -1, 18383, 14896, 14895, -1, 10560, 18477, 10561, -1, 10561, 18477, 18500, -1, 10570, 18465, 10560, -1, 10560, 18465, 18477, -1, 10569, 18446, 10570, -1, 10570, 18446, 18465, -1, 18485, 18478, 10541, -1, 18478, 10539, 10541, -1, 18478, 18466, 10539, -1, 18466, 10553, 10539, -1, 18466, 18439, 10553, -1, 18439, 10554, 10553, -1, 10584, 18584, 10585, -1, 10585, 18584, 18606, -1, 10594, 18573, 10584, -1, 10584, 18573, 18584, -1, 10593, 18554, 10594, -1, 10594, 18554, 18573, -1, 18588, 18578, 10565, -1, 18578, 10563, 10565, -1, 18578, 18558, 10563, -1, 18558, 10577, 10563, -1, 18558, 18535, 10577, -1, 18535, 10578, 10577, -1, 10512, 18761, 10513, -1, 10513, 18761, 18860, -1, 10522, 18706, 10512, -1, 10512, 18706, 18761, -1, 10521, 18676, 10522, -1, 10522, 18676, 18706, -1, 18792, 18710, 10589, -1, 18710, 10587, 10589, -1, 18710, 18688, 10587, -1, 18688, 10601, 10587, -1, 18688, 18649, 10601, -1, 18649, 10602, 10601, -1, 10503, 19422, 10504, -1, 10504, 19422, 19535, -1, 10507, 19281, 10503, -1, 10503, 19281, 19422, -1, 10506, 19173, 10507, -1, 10507, 19173, 19281, -1, 19300, 10517, 19437, -1, 19179, 10514, 19300, -1, 19300, 10514, 10517, -1, 19069, 10529, 19179, -1, 19179, 10529, 10514, -1, 19069, 10530, 10529, -1, 3373, 9263, 9270, -1, 3359, 9263, 3373, -1, 3346, 9250, 3359, -1, 3359, 9250, 9263, -1, 3332, 9251, 3346, -1, 3346, 9251, 9250, -1, 9185, 3385, 9189, -1, 9185, 3369, 3385, -1, 9185, 9182, 3369, -1, 9182, 3356, 3369, -1, 9182, 9181, 3356, -1, 9181, 3345, 3356, -1, 180, 9202, 9209, -1, 105, 9202, 180, -1, 107, 9198, 105, -1, 105, 9198, 9202, -1, 10, 9197, 107, -1, 107, 9197, 9198, -1, 9168, 9164, 201, -1, 9164, 140, 201, -1, 9164, 9155, 140, -1, 9155, 106, 140, -1, 9155, 9157, 106, -1, 9157, 66, 106, -1, 314, 9171, 9178, -1, 296, 9171, 314, -1, 295, 9158, 296, -1, 296, 9158, 9171, -1, 230, 9159, 295, -1, 295, 9159, 9158, -1, 9223, 9219, 317, -1, 9219, 293, 317, -1, 9219, 9216, 293, -1, 9216, 294, 293, -1, 9216, 9215, 294, -1, 9215, 260, 294, -1, 422, 9236, 9243, -1, 406, 9236, 422, -1, 391, 9232, 406, -1, 406, 9232, 9236, -1, 339, 9231, 391, -1, 391, 9231, 9232, -1, 14711, 419, 14715, -1, 14711, 405, 419, -1, 14711, 14704, 405, -1, 14704, 390, 405, -1, 14704, 14706, 390, -1, 14706, 363, 390, -1, 3297, 9274, 2867, -1, 3286, 9275, 3297, -1, 3297, 9275, 9274, -1, 2762, 9278, 3286, -1, 3286, 9278, 9275, -1, 2762, 9279, 9278, -1, 9285, 3296, 2870, -1, 9284, 3296, 9285, -1, 9294, 3285, 9284, -1, 9284, 3285, 3296, -1, 9293, 2763, 9294, -1, 9294, 2763, 3285, -1, 3361, 9289, 2967, -1, 3352, 9287, 3361, -1, 3361, 9287, 9289, -1, 3329, 9301, 3352, -1, 3352, 9301, 9287, -1, 3329, 9302, 9301, -1, 9309, 3360, 2983, -1, 9308, 3360, 9309, -1, 9318, 3351, 9308, -1, 9308, 3351, 3360, -1, 9317, 3337, 9318, -1, 9318, 3337, 3351, -1, 90, 9313, 155, -1, 39, 9311, 90, -1, 90, 9311, 9313, -1, 25, 9325, 39, -1, 39, 9325, 9311, -1, 25, 9326, 9325, -1, 9357, 112, 154, -1, 9356, 112, 9357, -1, 9366, 77, 9356, -1, 9356, 77, 112, -1, 9365, 23, 9366, -1, 9366, 23, 77, -1, 275, 9361, 288, -1, 251, 9359, 275, -1, 275, 9359, 9361, -1, 210, 9373, 251, -1, 251, 9373, 9359, -1, 210, 9374, 9373, -1, 9333, 285, 306, -1, 9332, 285, 9333, -1, 9342, 270, 9332, -1, 9332, 270, 285, -1, 9341, 234, 9342, -1, 9342, 234, 270, -1, 386, 9337, 402, -1, 355, 9334, 386, -1, 386, 9334, 9337, -1, 357, 9349, 355, -1, 355, 9349, 9334, -1, 357, 9350, 9349, -1, 14727, 395, 412, -1, 14726, 395, 14727, -1, 14730, 384, 14726, -1, 14726, 384, 395, -1, 14729, 356, 14730, -1, 14730, 356, 384, -1, 2791, 9395, 9402, -1, 3252, 9395, 2791, -1, 3239, 9382, 3252, -1, 3252, 9382, 9395, -1, 2704, 9383, 3239, -1, 3239, 9383, 9382, -1, 9413, 9409, 2803, -1, 9409, 3263, 2803, -1, 9409, 9406, 3263, -1, 9406, 3251, 3263, -1, 9406, 9405, 3251, -1, 9405, 2716, 3251, -1, 2910, 9426, 9433, -1, 2888, 9426, 2910, -1, 2856, 9422, 2888, -1, 2888, 9422, 9426, -1, 2832, 9421, 2856, -1, 2856, 9421, 9422, -1, 9484, 9480, 2928, -1, 9480, 2889, 2928, -1, 9480, 9471, 2889, -1, 9471, 2857, 2889, -1, 9471, 9473, 2857, -1, 9473, 2858, 2857, -1, 33, 9487, 9494, -1, 32, 9487, 33, -1, 2954, 9474, 32, -1, 32, 9474, 9487, -1, 2935, 9475, 2954, -1, 2954, 9475, 9474, -1, 9447, 9443, 31, -1, 9443, 34, 31, -1, 9443, 9440, 34, -1, 9440, 2953, 34, -1, 9440, 9439, 2953, -1, 9439, 2951, 2953, -1, 243, 9460, 9467, -1, 204, 9460, 243, -1, 185, 9456, 204, -1, 204, 9456, 9460, -1, 184, 9455, 185, -1, 185, 9455, 9456, -1, 14743, 14739, 242, -1, 14739, 203, 242, -1, 14739, 14732, 203, -1, 14732, 183, 203, -1, 14732, 14734, 183, -1, 14734, 188, 183, -1, 3197, 9522, 2611, -1, 3188, 9523, 3197, -1, 3197, 9523, 9522, -1, 2543, 9526, 3188, -1, 3188, 9526, 9523, -1, 2543, 9527, 9526, -1, 9533, 3196, 2641, -1, 9532, 3196, 9533, -1, 9542, 3187, 9532, -1, 9532, 3187, 3196, -1, 9541, 2544, 9542, -1, 9542, 2544, 3187, -1, 3256, 9537, 2752, -1, 3247, 9535, 3256, -1, 3256, 9535, 9537, -1, 2701, 9549, 3247, -1, 3247, 9549, 9535, -1, 2701, 9550, 9549, -1, 9581, 3255, 2785, -1, 9580, 3255, 9581, -1, 9590, 3246, 9580, -1, 9580, 3246, 3255, -1, 9589, 2702, 9590, -1, 9590, 2702, 3246, -1, 3319, 9585, 2883, -1, 3312, 9583, 3319, -1, 3319, 9583, 9585, -1, 2819, 9597, 3312, -1, 3312, 9597, 9583, -1, 2819, 9598, 9597, -1, 9557, 3318, 2913, -1, 9556, 3318, 9557, -1, 9566, 3311, 9556, -1, 9556, 3311, 3318, -1, 9565, 2836, 9566, -1, 9566, 2836, 3311, -1, 3380, 9561, 2989, -1, 3365, 9559, 3380, -1, 3380, 9559, 9561, -1, 2930, 9573, 3365, -1, 3365, 9573, 9559, -1, 2930, 9574, 9573, -1, 9497, 3390, 3006, -1, 9496, 3390, 9497, -1, 9506, 3377, 9496, -1, 9496, 3377, 3390, -1, 9505, 2943, 9506, -1, 9506, 2943, 3377, -1, 173, 9501, 199, -1, 133, 9498, 173, -1, 173, 9498, 9501, -1, 135, 9513, 133, -1, 133, 9513, 9498, -1, 135, 9514, 9513, -1, 14755, 195, 228, -1, 14754, 195, 14755, -1, 14758, 168, 14754, -1, 14754, 168, 195, -1, 14757, 134, 14758, -1, 14758, 134, 168, -1, 3079, 9970, 2393, -1, 3018, 9971, 3079, -1, 3079, 9971, 9970, -1, 2322, 9974, 3018, -1, 3018, 9974, 9971, -1, 2322, 9975, 9974, -1, 9944, 3075, 9945, -1, 9945, 3075, 2442, -1, 9954, 3015, 9944, -1, 9944, 3015, 3075, -1, 9953, 2323, 9954, -1, 9954, 2323, 3015, -1, 3165, 9949, 2532, -1, 3153, 9947, 3165, -1, 3165, 9947, 9949, -1, 2465, 9961, 3153, -1, 3153, 9961, 9947, -1, 2465, 9962, 9961, -1, 9980, 3164, 9981, -1, 9981, 3164, 2579, -1, 9990, 3152, 9980, -1, 9980, 3152, 3164, -1, 9989, 2467, 9990, -1, 9990, 2467, 3152, -1, 3220, 9985, 2659, -1, 3209, 9983, 3220, -1, 3220, 9983, 9985, -1, 2582, 9997, 3209, -1, 3209, 9997, 9983, -1, 2582, 9998, 9997, -1, 10004, 3219, 10005, -1, 10005, 3219, 2720, -1, 10014, 3208, 10004, -1, 10004, 3208, 3219, -1, 10013, 2609, 10014, -1, 10014, 2609, 3208, -1, 3271, 10009, 2801, -1, 3261, 10007, 3271, -1, 3271, 10007, 10009, -1, 2733, 10021, 3261, -1, 3261, 10021, 10007, -1, 2733, 10022, 10021, -1, 10028, 3278, 10029, -1, 10029, 3278, 2847, -1, 10038, 3270, 10028, -1, 10028, 3270, 3278, -1, 10037, 2740, 10038, -1, 10038, 2740, 3270, -1, 3339, 10033, 2916, -1, 3325, 10030, 3339, -1, 3339, 10030, 10033, -1, 2861, 10045, 3325, -1, 3325, 10045, 10030, -1, 2861, 10046, 10045, -1, 14810, 3349, 14811, -1, 14811, 3349, 2965, -1, 14814, 3335, 14810, -1, 14810, 3335, 3349, -1, 14813, 2876, 14814, -1, 14814, 2876, 3335, -1, 2833, 9619, 9626, -1, 2695, 9619, 2833, -1, 2566, 9606, 2695, -1, 2695, 9606, 9619, -1, 2244, 9607, 2566, -1, 2566, 9607, 9606, -1, 9637, 9633, 2912, -1, 9633, 2797, 2912, -1, 9633, 9630, 2797, -1, 9630, 2663, 2797, -1, 2663, 9629, 2254, -1, 9630, 9629, 2663, -1, 2491, 9650, 9657, -1, 2490, 9650, 2491, -1, 2438, 9646, 2490, -1, 2490, 9646, 9650, -1, 2411, 9645, 2438, -1, 2438, 9645, 9646, -1, 9674, 9670, 2492, -1, 9670, 2489, 2492, -1, 9670, 9661, 2489, -1, 9661, 2439, 2489, -1, 9661, 9663, 2439, -1, 9663, 2412, 2439, -1, 2617, 9677, 9684, -1, 2620, 9677, 2617, -1, 2563, 9664, 2620, -1, 2620, 9664, 9677, -1, 2522, 9665, 2563, -1, 2563, 9665, 9664, -1, 9695, 9691, 2618, -1, 9691, 2619, 2618, -1, 9691, 9688, 2619, -1, 9688, 2564, 2619, -1, 2564, 9687, 2523, -1, 9688, 9687, 2564, -1, 3260, 9708, 9715, -1, 3249, 9708, 3260, -1, 3235, 9704, 3249, -1, 3249, 9704, 9708, -1, 2639, 9703, 3235, -1, 3235, 9703, 9704, -1, 14771, 14767, 3259, -1, 14767, 3248, 3259, -1, 14767, 14760, 3248, -1, 14760, 3234, 3248, -1, 3234, 14762, 2678, -1, 14760, 14762, 3234, -1, 2557, 9935, 9942, -1, 3162, 9935, 2557, -1, 3150, 9922, 3162, -1, 3162, 9922, 9935, -1, 2469, 9923, 3150, -1, 3150, 9923, 9922, -1, 9895, 9891, 2561, -1, 9891, 3171, 2561, -1, 9891, 9888, 3171, -1, 9888, 3160, 3171, -1, 9888, 9887, 3160, -1, 9887, 2487, 3160, -1, 2727, 9908, 9915, -1, 2671, 9908, 2727, -1, 2670, 9904, 2671, -1, 2671, 9904, 9908, -1, 2603, 9903, 2670, -1, 2670, 9903, 9904, -1, 9874, 9870, 2726, -1, 9870, 2672, 2726, -1, 9870, 9861, 2672, -1, 9861, 2673, 2672, -1, 9861, 9863, 2673, -1, 9863, 2629, 2673, -1, 2845, 9877, 9884, -1, 2808, 9877, 2845, -1, 2807, 9864, 2808, -1, 2808, 9864, 9877, -1, 2736, 9865, 2807, -1, 2807, 9865, 9864, -1, 9837, 9833, 2843, -1, 9833, 2809, 2843, -1, 9833, 9830, 2809, -1, 9830, 2806, 2809, -1, 9830, 9829, 2806, -1, 9829, 2747, 2806, -1, 2948, 9850, 9857, -1, 3354, 9850, 2948, -1, 3342, 9846, 3354, -1, 3354, 9846, 9850, -1, 2864, 9845, 3342, -1, 3342, 9845, 9846, -1, 14799, 14795, 2973, -1, 14795, 3353, 2973, -1, 14795, 14788, 3353, -1, 14788, 3341, 3353, -1, 14788, 14790, 3341, -1, 14790, 2891, 3341, -1, 10476, 19961, 10477, -1, 10477, 19961, 19101, -1, 10486, 19869, 10476, -1, 10476, 19869, 19961, -1, 10485, 19749, 10486, -1, 10486, 19749, 19869, -1, 19098, 19962, 14879, -1, 19962, 14880, 14879, -1, 19962, 19871, 14880, -1, 19871, 14883, 14880, -1, 19871, 19645, 14883, -1, 19645, 14884, 14883, -1, 10452, 20442, 10453, -1, 10453, 20442, 19250, -1, 10462, 20359, 10452, -1, 10452, 20359, 20442, -1, 10461, 20268, 10462, -1, 10462, 20268, 20359, -1, 19249, 20445, 10481, -1, 20445, 10479, 10481, -1, 20445, 20362, 10479, -1, 20362, 10493, 10479, -1, 20362, 20222, 10493, -1, 20222, 10494, 10493, -1, 10428, 21060, 10429, -1, 10429, 21060, 19372, -1, 10438, 20954, 10428, -1, 10428, 20954, 21060, -1, 10437, 20854, 10438, -1, 10438, 20854, 20954, -1, 19360, 21061, 10457, -1, 21061, 10455, 10457, -1, 21061, 20955, 10455, -1, 20955, 10469, 10455, -1, 20955, 20785, 10469, -1, 20785, 10470, 10469, -1, 10404, 21257, 10405, -1, 10405, 21257, 19533, -1, 10414, 21251, 10404, -1, 10404, 21251, 21257, -1, 10413, 21240, 10414, -1, 10414, 21240, 21251, -1, 19511, 21252, 10433, -1, 21252, 10431, 10433, -1, 21252, 21245, 10431, -1, 21245, 10445, 10431, -1, 21245, 21233, 10445, -1, 21233, 10446, 10445, -1, 10395, 21307, 10396, -1, 10396, 21307, 19676, -1, 10399, 21297, 10395, -1, 10395, 21297, 21307, -1, 10398, 21290, 10399, -1, 10399, 21290, 21297, -1, 19642, 21298, 10409, -1, 21298, 10406, 10409, -1, 21298, 21291, 10406, -1, 21291, 10421, 10406, -1, 21291, 21284, 10421, -1, 21284, 10422, 10421, -1, 10139, 19029, 10143, -1, 10136, 19627, 10139, -1, 10139, 19627, 19029, -1, 10135, 19509, 10136, -1, 10136, 19509, 19627, -1, 10135, 18990, 19509, -1, 19018, 14832, 14839, -1, 19529, 14832, 19018, -1, 19401, 14819, 19529, -1, 19529, 14819, 14832, -1, 18935, 14820, 19401, -1, 19401, 14820, 14819, -1, 10118, 19134, 10122, -1, 10109, 19135, 10118, -1, 10118, 19135, 19134, -1, 10111, 19089, 10109, -1, 10109, 19089, 19135, -1, 10111, 19088, 19089, -1, 19136, 10156, 10163, -1, 19137, 10156, 19136, -1, 19090, 10152, 19137, -1, 19137, 10152, 10156, -1, 19037, 10151, 19090, -1, 19090, 10151, 10152, -1, 10081, 19273, 10085, -1, 10078, 19274, 10081, -1, 10081, 19274, 19273, -1, 10077, 19222, 10078, -1, 10078, 19222, 19274, -1, 10077, 19223, 19222, -1, 19277, 10125, 10132, -1, 19275, 10125, 19277, -1, 19224, 10112, 19275, -1, 19275, 10112, 10125, -1, 19185, 10113, 19224, -1, 19224, 10113, 10112, -1, 10060, 19452, 10064, -1, 10051, 21229, 10060, -1, 10060, 21229, 19452, -1, 10053, 21209, 10051, -1, 10051, 21209, 21229, -1, 10053, 19378, 21209, -1, 19407, 10098, 10105, -1, 21230, 10098, 19407, -1, 21211, 10094, 21230, -1, 21230, 10094, 10098, -1, 19321, 10093, 21211, -1, 21211, 10093, 10094, -1, 10229, 18881, 18897, -1, 10228, 18881, 10229, -1, 10238, 18801, 10228, -1, 10228, 18801, 18881, -1, 10237, 18802, 10238, -1, 10238, 18802, 18801, -1, 18871, 18884, 14843, -1, 18884, 14844, 14843, -1, 18884, 18805, 14844, -1, 18805, 14847, 14844, -1, 18805, 18803, 14847, -1, 18803, 14848, 14847, -1, 10253, 19555, 19014, -1, 10252, 19555, 10253, -1, 10262, 19445, 10252, -1, 10252, 19445, 19555, -1, 10261, 18928, 10262, -1, 10262, 18928, 19445, -1, 18993, 19562, 10233, -1, 19562, 10231, 10233, -1, 19562, 19448, 10231, -1, 19448, 10245, 10231, -1, 19448, 18927, 10245, -1, 18927, 10246, 10245, -1, 10193, 20160, 19171, -1, 10192, 20160, 10193, -1, 10202, 20072, 10192, -1, 10192, 20072, 20160, -1, 10201, 19066, 10202, -1, 10202, 19066, 20072, -1, 19129, 20096, 10257, -1, 20096, 10255, 10257, -1, 20096, 20010, 10255, -1, 20010, 10269, 10255, -1, 20010, 19050, 10269, -1, 19050, 10270, 10269, -1, 10169, 20690, 19296, -1, 10168, 20690, 10169, -1, 10178, 20578, 10168, -1, 10168, 20578, 20690, -1, 10177, 19207, 10178, -1, 10178, 19207, 20578, -1, 19270, 20593, 10197, -1, 20593, 10195, 10197, -1, 20593, 20492, 10195, -1, 20492, 10209, 10195, -1, 20492, 19194, 10209, -1, 19194, 10210, 10209, -1, 10220, 21225, 19421, -1, 10219, 21225, 10220, -1, 10223, 21183, 10219, -1, 10219, 21183, 21225, -1, 10222, 19342, 10223, -1, 10223, 19342, 21183, -1, 19381, 21194, 10173, -1, 21194, 10170, 10173, -1, 21194, 21121, 10170, -1, 21121, 10185, 10170, -1, 21121, 19318, 10185, -1, 19318, 10186, 10185, -1, 10277, 20404, 10278, -1, 19125, 20404, 10277, -1, 10278, 20513, 10281, -1, 20404, 20513, 10278, -1, 10281, 20628, 10285, -1, 20513, 20628, 10281, -1, 20545, 14868, 14875, -1, 20545, 20418, 14868, -1, 20418, 14855, 14868, -1, 20418, 20335, 14855, -1, 20335, 14856, 14855, -1, 20335, 19112, 14856, -1, 10345, 19310, 10343, -1, 19284, 19310, 10345, -1, 10343, 19355, 10352, -1, 19310, 19355, 10343, -1, 10352, 19353, 10356, -1, 19355, 19353, 10352, -1, 19352, 10298, 10305, -1, 19352, 19354, 10298, -1, 19354, 10294, 10298, -1, 19354, 19309, 10294, -1, 19309, 10293, 10294, -1, 19309, 19286, 10293, -1, 10311, 19440, 10312, -1, 19384, 19440, 10311, -1, 10312, 19497, 10315, -1, 19440, 19497, 10312, -1, 10315, 19496, 10319, -1, 19497, 19496, 10315, -1, 19495, 10359, 10366, -1, 19495, 19494, 10359, -1, 19494, 10346, 10359, -1, 19494, 19439, 10346, -1, 19388, 10347, 19439, -1, 19439, 10347, 10346, -1, 10369, 21299, 10367, -1, 19557, 21299, 10369, -1, 10367, 21310, 10376, -1, 21299, 21310, 10367, -1, 10376, 21319, 10380, -1, 21310, 21319, 10376, -1, 21320, 10332, 10339, -1, 21320, 21311, 10332, -1, 21311, 10328, 10332, -1, 21311, 21300, 10328, -1, 19520, 10327, 21300, -1, 21300, 10327, 10328, -1, 10613, 18503, 10617, -1, 10610, 18490, 10613, -1, 10613, 18490, 18503, -1, 10609, 18473, 10610, -1, 10610, 18473, 18490, -1, 10609, 18457, 18473, -1, 18475, 14916, 18497, -1, 18497, 14916, 14923, -1, 18456, 14903, 18475, -1, 18475, 14903, 14916, -1, 18458, 14904, 18456, -1, 18456, 14904, 14903, -1, 10650, 18644, 10654, -1, 10641, 18776, 10650, -1, 10650, 18776, 18644, -1, 10643, 18777, 10641, -1, 10641, 18777, 18776, -1, 10643, 18748, 18777, -1, 18781, 10630, 18636, -1, 18636, 10630, 10637, -1, 18780, 10626, 18781, -1, 18781, 10626, 10630, -1, 18742, 10625, 18780, -1, 18780, 10625, 10626, -1, 10671, 18875, 10675, -1, 10668, 18841, 10671, -1, 10671, 18841, 18875, -1, 10667, 18842, 10668, -1, 10668, 18842, 18841, -1, 10667, 18823, 18842, -1, 18840, 10657, 18878, -1, 18878, 10657, 10664, -1, 18843, 10644, 18840, -1, 18840, 10644, 10657, -1, 18814, 10645, 18843, -1, 18843, 10645, 10644, -1, 10708, 19581, 10712, -1, 10699, 19468, 10708, -1, 10708, 19468, 19581, -1, 10701, 19330, 10699, -1, 10699, 19330, 19468, -1, 10701, 18915, 19330, -1, 19469, 10688, 19585, -1, 19585, 10688, 10695, -1, 19333, 10684, 19469, -1, 19469, 10684, 10688, -1, 18893, 10683, 19333, -1, 19333, 10683, 10684, -1, 10864, 18544, 10865, -1, 10865, 18544, 18569, -1, 10874, 18512, 10864, -1, 10864, 18512, 18544, -1, 10873, 18513, 10874, -1, 10874, 18513, 18512, -1, 18570, 18546, 14951, -1, 18546, 14952, 14951, -1, 18546, 18515, 14952, -1, 18515, 14955, 14952, -1, 18515, 18514, 14955, -1, 18514, 14956, 14955, -1, 10840, 18672, 10841, -1, 10841, 18672, 18704, -1, 10850, 18630, 10840, -1, 10840, 18630, 18672, -1, 10849, 18631, 10850, -1, 10850, 18631, 18630, -1, 18705, 18673, 10869, -1, 18673, 10867, 10869, -1, 18673, 18633, 10867, -1, 18633, 10881, 10867, -1, 18633, 18632, 10881, -1, 18632, 10882, 10881, -1, 10888, 19120, 10889, -1, 10889, 19120, 18941, -1, 10898, 19023, 10888, -1, 10888, 19023, 19120, -1, 10897, 18865, 10898, -1, 10898, 18865, 19023, -1, 18907, 19045, 10845, -1, 19045, 10843, 10845, -1, 19045, 18937, 10843, -1, 18937, 10857, 10843, -1, 18937, 18852, 10857, -1, 18852, 10858, 10857, -1, 10912, 19818, 10913, -1, 10913, 19818, 19062, -1, 10922, 19702, 10912, -1, 10912, 19702, 19818, -1, 10921, 18976, 10922, -1, 10922, 18976, 19702, -1, 19025, 19719, 10893, -1, 19719, 10891, 10893, -1, 19719, 19612, 10891, -1, 19612, 10905, 10891, -1, 19612, 18966, 10905, -1, 18966, 10906, 10905, -1, 10939, 20345, 10940, -1, 10940, 20345, 19213, -1, 10943, 20264, 10939, -1, 10939, 20264, 20345, -1, 10942, 19117, 10943, -1, 10943, 19117, 20264, -1, 19181, 20279, 10917, -1, 20279, 10914, 10917, -1, 20279, 20202, 10914, -1, 20202, 10929, 10914, -1, 20202, 19092, 10929, -1, 19092, 10930, 10929, -1, 10753, 18723, 10757, -1, 10750, 18692, 10753, -1, 10753, 18692, 18723, -1, 10749, 18663, 10750, -1, 10750, 18663, 18692, -1, 10749, 18623, 18663, -1, 18700, 14940, 14947, -1, 18669, 14940, 18700, -1, 18622, 14927, 18669, -1, 18669, 14927, 14940, -1, 18624, 14928, 18622, -1, 18622, 14928, 14927, -1, 10732, 18963, 10736, -1, 10723, 18911, 10732, -1, 10732, 18911, 18963, -1, 10725, 18913, 10723, -1, 10723, 18913, 18911, -1, 10725, 18888, 18913, -1, 18959, 10770, 10777, -1, 18910, 10770, 18959, -1, 18912, 10766, 18910, -1, 18910, 10766, 10770, -1, 18862, 10765, 18912, -1, 18912, 10765, 10766, -1, 10811, 19080, 10815, -1, 10808, 19033, 10811, -1, 10811, 19033, 19080, -1, 10807, 19034, 10808, -1, 10808, 19034, 19033, -1, 10807, 18981, 19034, -1, 19075, 10739, 10746, -1, 19032, 10739, 19075, -1, 19031, 10726, 19032, -1, 19032, 10726, 10739, -1, 18969, 10727, 19031, -1, 19031, 10727, 10726, -1, 10790, 19233, 10794, -1, 10781, 20373, 10790, -1, 10790, 20373, 19233, -1, 10783, 20292, 10781, -1, 10781, 20292, 20373, -1, 10783, 19140, 20292, -1, 19218, 10828, 10835, -1, 20376, 10828, 19218, -1, 20295, 10824, 20376, -1, 20376, 10824, 10828, -1, 19096, 10823, 20295, -1, 20295, 10823, 10824, -1, 11277, 21468, 21469, -1, 11277, 11253, 21468, -1, 11253, 21470, 21468, -1, 11253, 11245, 21470, -1, 11245, 21471, 21470, -1, 11245, 11249, 21471, -1, 11249, 21472, 21471, -1, 11249, 11252, 21472, -1, 11252, 21473, 21472, -1, 11252, 11254, 21473, -1, 21473, 11261, 21474, -1, 11254, 11261, 21473, -1, 21474, 11267, 21475, -1, 11261, 11267, 21474, -1, 21475, 11273, 21476, -1, 11267, 11273, 21475, -1, 21476, 11271, 21477, -1, 11273, 11271, 21476, -1, 21477, 11269, 21478, -1, 11271, 11269, 21477, -1, 21478, 11265, 21479, -1, 11269, 11265, 21478, -1, 21479, 11262, 21480, -1, 11265, 11262, 21479, -1, 11262, 21481, 21480, -1, 11262, 11257, 21481, -1, 11257, 21469, 21481, -1, 11257, 11277, 21469, -1, 21468, 21470, 21471, -1, 21479, 21480, 21481, -1, 21482, 21469, 21468, -1, 21482, 21471, 21472, -1, 21482, 21468, 21471, -1, 21483, 21472, 21473, -1, 21483, 21473, 21474, -1, 21483, 21482, 21472, -1, 21483, 21469, 21482, -1, 21484, 21478, 21479, -1, 21484, 21481, 21469, -1, 21484, 21479, 21481, -1, 21485, 21474, 21475, -1, 21485, 21475, 21476, -1, 21485, 21469, 21483, -1, 21485, 21483, 21474, -1, 21486, 21477, 21478, -1, 21486, 21476, 21477, -1, 21486, 21478, 21484, -1, 21486, 21469, 21485, -1, 21486, 21485, 21476, -1, 21486, 21484, 21469, -1, 11172, 21487, 21488, -1, 11172, 11179, 21487, -1, 11179, 21489, 21487, -1, 11179, 11185, 21489, -1, 11163, 21490, 21491, -1, 11163, 11167, 21490, -1, 11167, 21492, 21490, -1, 11167, 11170, 21492, -1, 11170, 21488, 21492, -1, 11170, 11172, 21488, -1, 11195, 11171, 21493, -1, 21493, 11171, 21494, -1, 21494, 11163, 21491, -1, 11171, 11163, 21494, -1, 11180, 11175, 21495, -1, 21495, 11175, 21496, -1, 21496, 11195, 21493, -1, 11175, 11195, 21496, -1, 21497, 11187, 21498, -1, 11189, 11187, 21497, -1, 21498, 11183, 21499, -1, 11187, 11183, 21498, -1, 21499, 11180, 21495, -1, 11183, 11180, 21499, -1, 11185, 21500, 21489, -1, 11185, 11191, 21500, -1, 11191, 21497, 21500, -1, 11191, 11189, 21497, -1, 21494, 21491, 21490, -1, 21499, 21495, 21496, -1, 21501, 21490, 21492, -1, 21501, 21493, 21494, -1, 21501, 21494, 21490, -1, 21502, 21492, 21488, -1, 21502, 21488, 21487, -1, 21502, 21501, 21492, -1, 21502, 21493, 21501, -1, 21503, 21498, 21499, -1, 21503, 21496, 21493, -1, 21503, 21499, 21496, -1, 21504, 21487, 21489, -1, 21504, 21489, 21500, -1, 21504, 21493, 21502, -1, 21504, 21502, 21487, -1, 21505, 21500, 21497, -1, 21505, 21497, 21498, -1, 21505, 21498, 21503, -1, 21505, 21493, 21504, -1, 21505, 21504, 21500, -1, 21505, 21503, 21493, -1, 10837, 21506, 21507, -1, 10837, 10813, 21506, -1, 10813, 21508, 21506, -1, 10813, 10805, 21508, -1, 10805, 21509, 21508, -1, 10805, 10809, 21509, -1, 10809, 21510, 21509, -1, 10809, 10812, 21510, -1, 10812, 21511, 21510, -1, 10812, 10814, 21511, -1, 21512, 21513, 10827, -1, 21513, 10821, 10827, -1, 21513, 21511, 10821, -1, 21511, 10814, 10821, -1, 21514, 21515, 10831, -1, 21515, 10833, 10831, -1, 21515, 21512, 10833, -1, 21512, 10827, 10833, -1, 21514, 10829, 21516, -1, 10831, 10829, 21514, -1, 21516, 10825, 21517, -1, 10829, 10825, 21516, -1, 21517, 10822, 21518, -1, 10825, 10822, 21517, -1, 10822, 21519, 21518, -1, 10822, 10817, 21519, -1, 10817, 21507, 21519, -1, 10817, 10837, 21507, -1, 21506, 21508, 21509, -1, 21517, 21518, 21519, -1, 21520, 21507, 21506, -1, 21520, 21509, 21510, -1, 21520, 21506, 21509, -1, 21521, 21510, 21511, -1, 21521, 21511, 21513, -1, 21521, 21520, 21510, -1, 21521, 21507, 21520, -1, 21522, 21516, 21517, -1, 21522, 21519, 21507, -1, 21522, 21517, 21519, -1, 21523, 21513, 21512, -1, 21523, 21512, 21515, -1, 21523, 21507, 21521, -1, 21523, 21521, 21513, -1, 21524, 21514, 21516, -1, 21524, 21515, 21514, -1, 21524, 21516, 21522, -1, 21524, 21507, 21523, -1, 21524, 21523, 21515, -1, 21524, 21522, 21507, -1, 21525, 10763, 10769, -1, 21526, 10763, 21525, -1, 21527, 10756, 21526, -1, 21526, 10756, 10763, -1, 10747, 21528, 21529, -1, 21528, 10751, 21530, -1, 10747, 10751, 21528, -1, 21530, 10754, 21527, -1, 10751, 10754, 21530, -1, 10754, 10756, 21527, -1, 10779, 10755, 21531, -1, 21531, 10755, 21532, -1, 21532, 10747, 21529, -1, 10755, 10747, 21532, -1, 10764, 10759, 21533, -1, 21533, 10759, 21534, -1, 21534, 10779, 21531, -1, 10759, 10779, 21534, -1, 10773, 10771, 21535, -1, 10771, 21536, 21535, -1, 10771, 10767, 21536, -1, 10767, 21537, 21536, -1, 10767, 10764, 21537, -1, 10764, 21533, 21537, -1, 21535, 10775, 10773, -1, 21538, 10775, 21535, -1, 21525, 10769, 21538, -1, 21538, 10769, 10775, -1, 21532, 21529, 21528, -1, 21537, 21533, 21534, -1, 21539, 21528, 21530, -1, 21539, 21531, 21532, -1, 21539, 21532, 21528, -1, 21540, 21530, 21527, -1, 21540, 21527, 21526, -1, 21540, 21539, 21530, -1, 21540, 21531, 21539, -1, 21541, 21536, 21537, -1, 21541, 21534, 21531, -1, 21541, 21537, 21534, -1, 21542, 21526, 21525, -1, 21542, 21525, 21538, -1, 21542, 21531, 21540, -1, 21542, 21540, 21526, -1, 21543, 21538, 21535, -1, 21543, 21535, 21536, -1, 21543, 21536, 21541, -1, 21543, 21531, 21542, -1, 21543, 21542, 21538, -1, 21543, 21541, 21531, -1, 10697, 21544, 21545, -1, 10697, 10673, 21544, -1, 10673, 21546, 21544, -1, 10673, 10665, 21546, -1, 10665, 21547, 21546, -1, 10665, 10669, 21547, -1, 10669, 21548, 21547, -1, 10669, 10672, 21548, -1, 10672, 21549, 21548, -1, 10672, 10674, 21549, -1, 21549, 10681, 21550, -1, 10674, 10681, 21549, -1, 21550, 10687, 21551, -1, 10681, 10687, 21550, -1, 21551, 10693, 21552, -1, 10687, 10693, 21551, -1, 21552, 10691, 21553, -1, 10693, 10691, 21552, -1, 21553, 10689, 21554, -1, 10691, 10689, 21553, -1, 21554, 10685, 21555, -1, 10689, 10685, 21554, -1, 21555, 10682, 21556, -1, 10685, 10682, 21555, -1, 10682, 21557, 21556, -1, 10682, 10677, 21557, -1, 10677, 21545, 21557, -1, 10677, 10697, 21545, -1, 21544, 21546, 21547, -1, 21555, 21556, 21557, -1, 21558, 21545, 21544, -1, 21558, 21547, 21548, -1, 21558, 21544, 21547, -1, 21559, 21548, 21549, -1, 21559, 21549, 21550, -1, 21559, 21558, 21548, -1, 21559, 21545, 21558, -1, 21560, 21554, 21555, -1, 21560, 21557, 21545, -1, 21560, 21555, 21557, -1, 21561, 21550, 21551, -1, 21561, 21551, 21552, -1, 21561, 21545, 21559, -1, 21561, 21559, 21550, -1, 21562, 21553, 21554, -1, 21562, 21552, 21553, -1, 21562, 21554, 21560, -1, 21562, 21545, 21561, -1, 21562, 21561, 21552, -1, 21562, 21560, 21545, -1, 10616, 21563, 21564, -1, 10616, 10623, 21563, -1, 10623, 21565, 21563, -1, 10623, 10629, 21565, -1, 10607, 21566, 21567, -1, 10607, 10611, 21566, -1, 10611, 21568, 21566, -1, 10611, 10614, 21568, -1, 10614, 21564, 21568, -1, 10614, 10616, 21564, -1, 10639, 10615, 21569, -1, 21569, 10615, 21570, -1, 21570, 10607, 21567, -1, 10615, 10607, 21570, -1, 10624, 10619, 21571, -1, 21571, 10619, 21572, -1, 21572, 10639, 21569, -1, 10619, 10639, 21572, -1, 10633, 10631, 21573, -1, 10631, 21574, 21573, -1, 10631, 10627, 21574, -1, 10627, 21575, 21574, -1, 10627, 10624, 21575, -1, 10624, 21571, 21575, -1, 10629, 21576, 21565, -1, 10629, 10635, 21576, -1, 10635, 21573, 21576, -1, 10635, 10633, 21573, -1, 21570, 21567, 21566, -1, 21575, 21571, 21572, -1, 21577, 21566, 21568, -1, 21577, 21569, 21570, -1, 21577, 21570, 21566, -1, 21578, 21568, 21564, -1, 21578, 21564, 21563, -1, 21578, 21577, 21568, -1, 21578, 21569, 21577, -1, 21579, 21574, 21575, -1, 21579, 21572, 21569, -1, 21579, 21575, 21572, -1, 21580, 21563, 21565, -1, 21580, 21565, 21576, -1, 21580, 21569, 21578, -1, 21580, 21578, 21563, -1, 21581, 21576, 21573, -1, 21581, 21573, 21574, -1, 21581, 21574, 21579, -1, 21581, 21569, 21580, -1, 21581, 21580, 21576, -1, 21581, 21579, 21569, -1, 10341, 21582, 21583, -1, 10341, 10317, 21582, -1, 10317, 21584, 21582, -1, 10317, 10309, 21584, -1, 21585, 10316, 10318, -1, 21585, 21586, 10316, -1, 21586, 10313, 10316, -1, 21586, 21587, 10313, -1, 21587, 10309, 10313, -1, 21587, 21584, 10309, -1, 21588, 21589, 10331, -1, 21589, 10325, 10331, -1, 21589, 21585, 10325, -1, 21585, 10318, 10325, -1, 21590, 21591, 10335, -1, 21591, 10337, 10335, -1, 21591, 21588, 10337, -1, 21588, 10331, 10337, -1, 21592, 21593, 10326, -1, 10326, 21593, 10329, -1, 10329, 21594, 10333, -1, 21593, 21594, 10329, -1, 10333, 21590, 10335, -1, 21594, 21590, 10333, -1, 10326, 21595, 21592, -1, 10326, 10321, 21595, -1, 10321, 21583, 21595, -1, 10321, 10341, 21583, -1, 21582, 21584, 21587, -1, 21593, 21592, 21595, -1, 21596, 21583, 21582, -1, 21596, 21587, 21586, -1, 21596, 21582, 21587, -1, 21597, 21586, 21585, -1, 21597, 21585, 21589, -1, 21597, 21596, 21586, -1, 21597, 21583, 21596, -1, 21598, 21594, 21593, -1, 21598, 21595, 21583, -1, 21598, 21593, 21595, -1, 21599, 21589, 21588, -1, 21599, 21588, 21591, -1, 21599, 21583, 21597, -1, 21599, 21597, 21589, -1, 21600, 21590, 21594, -1, 21600, 21591, 21590, -1, 21600, 21594, 21598, -1, 21600, 21583, 21599, -1, 21600, 21599, 21591, -1, 21600, 21598, 21583, -1, 21601, 10291, 10297, -1, 21602, 10291, 21601, -1, 21603, 10284, 21602, -1, 21602, 10284, 10291, -1, 21603, 10282, 10284, -1, 21603, 21604, 10282, -1, 21604, 10279, 10282, -1, 21604, 21605, 10279, -1, 21605, 10275, 10279, -1, 21605, 21606, 10275, -1, 10307, 10283, 21607, -1, 21607, 10283, 21608, -1, 21608, 10275, 21606, -1, 10283, 10275, 21608, -1, 10292, 10287, 21609, -1, 21609, 10287, 21610, -1, 21610, 10307, 21607, -1, 10287, 10307, 21610, -1, 21609, 21611, 10292, -1, 10292, 21611, 10295, -1, 10295, 21612, 10299, -1, 21611, 21612, 10295, -1, 10299, 21613, 10301, -1, 21612, 21613, 10299, -1, 21613, 10303, 10301, -1, 21614, 10303, 21613, -1, 21601, 10297, 21614, -1, 21614, 10297, 10303, -1, 21608, 21606, 21605, -1, 21611, 21609, 21610, -1, 21615, 21605, 21604, -1, 21615, 21607, 21608, -1, 21615, 21608, 21605, -1, 21616, 21604, 21603, -1, 21616, 21603, 21602, -1, 21616, 21615, 21604, -1, 21616, 21607, 21615, -1, 21617, 21612, 21611, -1, 21617, 21610, 21607, -1, 21617, 21611, 21610, -1, 21618, 21602, 21601, -1, 21618, 21601, 21614, -1, 21618, 21607, 21616, -1, 21618, 21616, 21602, -1, 21619, 21614, 21613, -1, 21619, 21613, 21612, -1, 21619, 21612, 21617, -1, 21619, 21607, 21618, -1, 21619, 21618, 21614, -1, 21619, 21617, 21607, -1, 21620, 10149, 10155, -1, 21621, 10149, 21620, -1, 21622, 10142, 21621, -1, 21621, 10142, 10149, -1, 21623, 10133, 21624, -1, 21624, 10137, 21625, -1, 10133, 10137, 21624, -1, 21625, 10140, 21622, -1, 10137, 10140, 21625, -1, 10140, 10142, 21622, -1, 10165, 10141, 21626, -1, 21626, 10141, 21627, -1, 21627, 10133, 21623, -1, 10141, 10133, 21627, -1, 10150, 10145, 21628, -1, 21628, 10145, 21629, -1, 21629, 10165, 21626, -1, 10145, 10165, 21629, -1, 10157, 21630, 10159, -1, 10153, 21631, 10157, -1, 10157, 21631, 21630, -1, 10150, 21632, 10153, -1, 10153, 21632, 21631, -1, 10150, 21628, 21632, -1, 21630, 10161, 10159, -1, 21633, 10161, 21630, -1, 21620, 10155, 21633, -1, 21633, 10155, 10161, -1, 21627, 21623, 21624, -1, 21632, 21628, 21629, -1, 21634, 21624, 21625, -1, 21634, 21626, 21627, -1, 21634, 21627, 21624, -1, 21635, 21625, 21622, -1, 21635, 21622, 21621, -1, 21635, 21634, 21625, -1, 21635, 21626, 21634, -1, 21636, 21631, 21632, -1, 21636, 21629, 21626, -1, 21636, 21632, 21629, -1, 21637, 21621, 21620, -1, 21637, 21620, 21633, -1, 21637, 21626, 21635, -1, 21637, 21635, 21621, -1, 21638, 21633, 21630, -1, 21638, 21630, 21631, -1, 21638, 21631, 21636, -1, 21638, 21626, 21637, -1, 21638, 21637, 21633, -1, 21638, 21636, 21626, -1, 10107, 21639, 21640, -1, 10107, 10083, 21639, -1, 10083, 21641, 21639, -1, 10083, 10075, 21641, -1, 21641, 10075, 21642, -1, 21642, 10079, 21643, -1, 10075, 10079, 21642, -1, 21643, 10082, 21644, -1, 10079, 10082, 21643, -1, 10082, 10084, 21644, -1, 21645, 21646, 10097, -1, 21646, 10091, 10097, -1, 21646, 21644, 10091, -1, 21644, 10084, 10091, -1, 21647, 21648, 10101, -1, 21648, 10103, 10101, -1, 21648, 21645, 10103, -1, 21645, 10097, 10103, -1, 21647, 10099, 21649, -1, 10101, 10099, 21647, -1, 21649, 10095, 21650, -1, 10099, 10095, 21649, -1, 21650, 10092, 21651, -1, 10095, 10092, 21650, -1, 10092, 21652, 21651, -1, 10092, 10087, 21652, -1, 10087, 21640, 21652, -1, 10087, 10107, 21640, -1, 21639, 21641, 21642, -1, 21650, 21651, 21652, -1, 21653, 21640, 21639, -1, 21653, 21642, 21643, -1, 21653, 21639, 21642, -1, 21654, 21643, 21644, -1, 21654, 21644, 21646, -1, 21654, 21653, 21643, -1, 21654, 21640, 21653, -1, 21655, 21649, 21650, -1, 21655, 21652, 21640, -1, 21655, 21650, 21652, -1, 21656, 21646, 21645, -1, 21656, 21645, 21648, -1, 21656, 21640, 21654, -1, 21656, 21654, 21646, -1, 21657, 21647, 21649, -1, 21657, 21648, 21647, -1, 21657, 21649, 21655, -1, 21657, 21640, 21656, -1, 21657, 21656, 21648, -1, 21657, 21655, 21640, -1, 21658, 9901, 9907, -1, 21659, 9901, 21658, -1, 21660, 9894, 21659, -1, 21659, 9894, 9901, -1, 9885, 21661, 21662, -1, 9885, 9889, 21661, -1, 9889, 21663, 21661, -1, 9889, 9892, 21663, -1, 9892, 21660, 21663, -1, 9892, 9894, 21660, -1, 9917, 9893, 21664, -1, 21664, 9893, 21665, -1, 21665, 9885, 21662, -1, 9893, 9885, 21665, -1, 9902, 9897, 21666, -1, 21666, 9897, 21667, -1, 21667, 9917, 21664, -1, 9897, 9917, 21667, -1, 9911, 9909, 21668, -1, 9909, 21669, 21668, -1, 9909, 9905, 21669, -1, 9905, 21670, 21669, -1, 9905, 9902, 21670, -1, 9902, 21666, 21670, -1, 21668, 9913, 9911, -1, 21671, 9913, 21668, -1, 21658, 9907, 21671, -1, 21671, 9907, 9913, -1, 21665, 21662, 21661, -1, 21670, 21666, 21667, -1, 21672, 21661, 21663, -1, 21672, 21664, 21665, -1, 21672, 21665, 21661, -1, 21673, 21663, 21660, -1, 21673, 21660, 21659, -1, 21673, 21672, 21663, -1, 21673, 21664, 21672, -1, 21674, 21669, 21670, -1, 21674, 21667, 21664, -1, 21674, 21670, 21667, -1, 21675, 21659, 21658, -1, 21675, 21658, 21671, -1, 21675, 21664, 21673, -1, 21675, 21673, 21659, -1, 21676, 21671, 21668, -1, 21676, 21668, 21669, -1, 21676, 21669, 21674, -1, 21676, 21664, 21675, -1, 21676, 21675, 21671, -1, 21676, 21674, 21664, -1, 9859, 21677, 21678, -1, 9859, 9835, 21677, -1, 9835, 21679, 21677, -1, 9835, 9827, 21679, -1, 9827, 21680, 21679, -1, 9827, 9831, 21680, -1, 9831, 21681, 21680, -1, 9831, 9834, 21681, -1, 9834, 21682, 21681, -1, 9834, 9836, 21682, -1, 21683, 21684, 9849, -1, 21684, 9843, 9849, -1, 21684, 21682, 9843, -1, 21682, 9836, 9843, -1, 21685, 21686, 9853, -1, 21686, 9855, 9853, -1, 21686, 21683, 9855, -1, 21683, 9849, 9855, -1, 21685, 9851, 21687, -1, 9853, 9851, 21685, -1, 21687, 9847, 21688, -1, 9851, 9847, 21687, -1, 21688, 9844, 21689, -1, 9847, 9844, 21688, -1, 9844, 21690, 21689, -1, 9844, 9839, 21690, -1, 9839, 21678, 21690, -1, 9839, 9859, 21678, -1, 21677, 21679, 21680, -1, 21688, 21689, 21690, -1, 21691, 21678, 21677, -1, 21691, 21680, 21681, -1, 21691, 21677, 21680, -1, 21692, 21681, 21682, -1, 21692, 21682, 21684, -1, 21692, 21691, 21681, -1, 21692, 21678, 21691, -1, 21693, 21687, 21688, -1, 21693, 21690, 21678, -1, 21693, 21688, 21690, -1, 21694, 21684, 21683, -1, 21694, 21683, 21686, -1, 21694, 21678, 21692, -1, 21694, 21692, 21684, -1, 21695, 21685, 21687, -1, 21695, 21686, 21685, -1, 21695, 21687, 21693, -1, 21695, 21678, 21694, -1, 21695, 21694, 21686, -1, 21695, 21693, 21678, -1, 9717, 21696, 21697, -1, 9717, 9693, 21696, -1, 9693, 21698, 21696, -1, 9693, 9685, 21698, -1, 9685, 21699, 21698, -1, 9685, 9689, 21699, -1, 9689, 21700, 21699, -1, 9689, 9692, 21700, -1, 9692, 21701, 21700, -1, 9692, 9694, 21701, -1, 21702, 21703, 9707, -1, 21703, 9701, 9707, -1, 21703, 21701, 9701, -1, 21701, 9694, 9701, -1, 21704, 21705, 9711, -1, 21705, 9713, 9711, -1, 21705, 21702, 9713, -1, 21702, 9707, 9713, -1, 21704, 9709, 21706, -1, 9711, 9709, 21704, -1, 21706, 9705, 21707, -1, 9709, 9705, 21706, -1, 21707, 9702, 21708, -1, 9705, 9702, 21707, -1, 9702, 21709, 21708, -1, 9702, 9697, 21709, -1, 9697, 21697, 21709, -1, 9697, 9717, 21697, -1, 21696, 21698, 21699, -1, 21707, 21708, 21709, -1, 21710, 21697, 21696, -1, 21710, 21699, 21700, -1, 21710, 21696, 21699, -1, 21711, 21700, 21701, -1, 21711, 21701, 21703, -1, 21711, 21710, 21700, -1, 21711, 21697, 21710, -1, 21712, 21706, 21707, -1, 21712, 21709, 21697, -1, 21712, 21707, 21709, -1, 21713, 21703, 21702, -1, 21713, 21702, 21705, -1, 21713, 21697, 21711, -1, 21713, 21711, 21703, -1, 21714, 21704, 21706, -1, 21714, 21705, 21704, -1, 21714, 21706, 21712, -1, 21714, 21697, 21713, -1, 21714, 21713, 21705, -1, 21714, 21712, 21697, -1, 21715, 9643, 9649, -1, 21716, 9643, 21715, -1, 21717, 9636, 21716, -1, 21716, 9636, 9643, -1, 9627, 21718, 21719, -1, 9627, 9631, 21718, -1, 9631, 21720, 21718, -1, 9631, 9634, 21720, -1, 9634, 21717, 21720, -1, 9634, 9636, 21717, -1, 9659, 9635, 21721, -1, 21721, 9635, 21722, -1, 21722, 9627, 21719, -1, 9635, 9627, 21722, -1, 9644, 9639, 21723, -1, 21723, 9639, 21724, -1, 21724, 9659, 21721, -1, 9639, 9659, 21724, -1, 9653, 9651, 21725, -1, 9651, 21726, 21725, -1, 9651, 9647, 21726, -1, 9647, 21727, 21726, -1, 9647, 9644, 21727, -1, 9644, 21723, 21727, -1, 21725, 9655, 9653, -1, 21728, 9655, 21725, -1, 21715, 9649, 21728, -1, 21728, 9649, 9655, -1, 21722, 21719, 21718, -1, 21727, 21723, 21724, -1, 21729, 21718, 21720, -1, 21729, 21721, 21722, -1, 21729, 21722, 21718, -1, 21730, 21720, 21717, -1, 21730, 21717, 21716, -1, 21730, 21729, 21720, -1, 21730, 21721, 21729, -1, 21731, 21726, 21727, -1, 21731, 21724, 21721, -1, 21731, 21727, 21724, -1, 21732, 21716, 21715, -1, 21732, 21715, 21728, -1, 21732, 21721, 21730, -1, 21732, 21730, 21716, -1, 21733, 21728, 21725, -1, 21733, 21725, 21726, -1, 21733, 21726, 21731, -1, 21733, 21721, 21732, -1, 21733, 21732, 21728, -1, 21733, 21731, 21721, -1, 9469, 21734, 21735, -1, 9469, 9445, 21734, -1, 9445, 21736, 21734, -1, 9445, 9437, 21736, -1, 9437, 21737, 21736, -1, 9437, 9441, 21737, -1, 9441, 21738, 21737, -1, 9441, 9444, 21738, -1, 9444, 21739, 21738, -1, 9444, 9446, 21739, -1, 21739, 9453, 21740, -1, 9446, 9453, 21739, -1, 21740, 9459, 21741, -1, 9453, 9459, 21740, -1, 21741, 9465, 21742, -1, 9459, 9465, 21741, -1, 21742, 9463, 21743, -1, 9465, 9463, 21742, -1, 21743, 9461, 21744, -1, 9463, 9461, 21743, -1, 21744, 9457, 21745, -1, 9461, 9457, 21744, -1, 21745, 9454, 21746, -1, 9457, 9454, 21745, -1, 9454, 21747, 21746, -1, 9454, 9449, 21747, -1, 9449, 21735, 21747, -1, 9449, 9469, 21735, -1, 21734, 21736, 21737, -1, 21745, 21746, 21747, -1, 21748, 21735, 21734, -1, 21748, 21737, 21738, -1, 21748, 21734, 21737, -1, 21749, 21738, 21739, -1, 21749, 21739, 21740, -1, 21749, 21748, 21738, -1, 21749, 21735, 21748, -1, 21750, 21744, 21745, -1, 21750, 21747, 21735, -1, 21750, 21745, 21747, -1, 21751, 21740, 21741, -1, 21751, 21741, 21742, -1, 21751, 21735, 21749, -1, 21751, 21749, 21740, -1, 21752, 21743, 21744, -1, 21752, 21742, 21743, -1, 21752, 21744, 21750, -1, 21752, 21735, 21751, -1, 21752, 21751, 21742, -1, 21752, 21750, 21735, -1, 9412, 21753, 21754, -1, 9412, 9419, 21753, -1, 9419, 21755, 21753, -1, 9419, 9425, 21755, -1, 9403, 21756, 21757, -1, 9403, 9407, 21756, -1, 9407, 21758, 21756, -1, 9407, 9410, 21758, -1, 9410, 21754, 21758, -1, 9410, 9412, 21754, -1, 9435, 9411, 21759, -1, 21759, 9411, 21760, -1, 21760, 9403, 21757, -1, 9411, 9403, 21760, -1, 9420, 9415, 21761, -1, 21761, 9415, 21762, -1, 21762, 9435, 21759, -1, 9415, 9435, 21762, -1, 9429, 9427, 21763, -1, 9427, 21764, 21763, -1, 9427, 9423, 21764, -1, 9423, 21765, 21764, -1, 9423, 9420, 21765, -1, 9420, 21761, 21765, -1, 9425, 21766, 21755, -1, 9425, 9431, 21766, -1, 9431, 21763, 21766, -1, 9431, 9429, 21763, -1, 21760, 21757, 21756, -1, 21765, 21761, 21762, -1, 21767, 21756, 21758, -1, 21767, 21759, 21760, -1, 21767, 21760, 21756, -1, 21768, 21758, 21754, -1, 21768, 21754, 21753, -1, 21768, 21767, 21758, -1, 21768, 21759, 21767, -1, 21769, 21764, 21765, -1, 21769, 21762, 21759, -1, 21769, 21765, 21762, -1, 21770, 21753, 21755, -1, 21770, 21755, 21766, -1, 21770, 21759, 21768, -1, 21770, 21768, 21753, -1, 21771, 21766, 21763, -1, 21771, 21763, 21764, -1, 21771, 21764, 21769, -1, 21771, 21759, 21770, -1, 21771, 21770, 21766, -1, 21771, 21769, 21759, -1, 9245, 21772, 21773, -1, 9245, 9221, 21772, -1, 9221, 21774, 21772, -1, 9221, 9213, 21774, -1, 9213, 21775, 21774, -1, 9213, 9217, 21775, -1, 9217, 21776, 21775, -1, 9217, 9220, 21776, -1, 9220, 21777, 21776, -1, 9220, 9222, 21777, -1, 21777, 9229, 21778, -1, 9222, 9229, 21777, -1, 21778, 9235, 21779, -1, 9229, 9235, 21778, -1, 21779, 9241, 21780, -1, 9235, 9241, 21779, -1, 21780, 9239, 21781, -1, 9241, 9239, 21780, -1, 21781, 9237, 21782, -1, 9239, 9237, 21781, -1, 21782, 9233, 21783, -1, 9237, 9233, 21782, -1, 21783, 9230, 21784, -1, 9233, 9230, 21783, -1, 9230, 21785, 21784, -1, 9230, 9225, 21785, -1, 9225, 21773, 21785, -1, 9225, 9245, 21773, -1, 21772, 21774, 21775, -1, 21783, 21784, 21785, -1, 21786, 21773, 21772, -1, 21786, 21775, 21776, -1, 21786, 21772, 21775, -1, 21787, 21776, 21777, -1, 21787, 21777, 21778, -1, 21787, 21786, 21776, -1, 21787, 21773, 21786, -1, 21788, 21782, 21783, -1, 21788, 21785, 21773, -1, 21788, 21783, 21785, -1, 21789, 21778, 21779, -1, 21789, 21779, 21780, -1, 21789, 21773, 21787, -1, 21789, 21787, 21778, -1, 21790, 21781, 21782, -1, 21790, 21780, 21781, -1, 21790, 21782, 21788, -1, 21790, 21773, 21789, -1, 21790, 21789, 21780, -1, 21790, 21788, 21773, -1, 9188, 21791, 21792, -1, 9188, 9195, 21791, -1, 9195, 21793, 21791, -1, 9195, 9201, 21793, -1, 9179, 21794, 21795, -1, 9179, 9183, 21794, -1, 9183, 21796, 21794, -1, 9183, 9186, 21796, -1, 9186, 21792, 21796, -1, 9186, 9188, 21792, -1, 9211, 9187, 21797, -1, 21797, 9187, 21798, -1, 21798, 9179, 21795, -1, 9187, 9179, 21798, -1, 9196, 9191, 21799, -1, 21799, 9191, 21800, -1, 21800, 9211, 21797, -1, 9191, 9211, 21800, -1, 9205, 9203, 21801, -1, 9203, 21802, 21801, -1, 9203, 9199, 21802, -1, 9199, 21803, 21802, -1, 9199, 9196, 21803, -1, 9196, 21799, 21803, -1, 9201, 21804, 21793, -1, 9201, 9207, 21804, -1, 9207, 21801, 21804, -1, 9207, 9205, 21801, -1, 21798, 21795, 21794, -1, 21803, 21799, 21800, -1, 21805, 21794, 21796, -1, 21805, 21797, 21798, -1, 21805, 21798, 21794, -1, 21806, 21796, 21792, -1, 21806, 21792, 21791, -1, 21806, 21805, 21796, -1, 21806, 21797, 21805, -1, 21807, 21802, 21803, -1, 21807, 21800, 21797, -1, 21807, 21803, 21800, -1, 21808, 21791, 21793, -1, 21808, 21793, 21804, -1, 21808, 21797, 21806, -1, 21808, 21806, 21791, -1, 21809, 21804, 21801, -1, 21809, 21801, 21802, -1, 21809, 21802, 21807, -1, 21809, 21797, 21808, -1, 21809, 21808, 21804, -1, 21809, 21807, 21797, -1, 9129, 21810, 21811, -1, 9129, 9105, 21810, -1, 9105, 21812, 21810, -1, 9105, 9097, 21812, -1, 9097, 21813, 21812, -1, 9097, 9101, 21813, -1, 9101, 21814, 21813, -1, 9101, 9104, 21814, -1, 9104, 21815, 21814, -1, 9104, 9106, 21815, -1, 21815, 9113, 21816, -1, 9106, 9113, 21815, -1, 21816, 9119, 21817, -1, 9113, 9119, 21816, -1, 21817, 9125, 21818, -1, 9119, 9125, 21817, -1, 21818, 9123, 21819, -1, 9125, 9123, 21818, -1, 21819, 9121, 21820, -1, 9123, 9121, 21819, -1, 21820, 9117, 21821, -1, 9121, 9117, 21820, -1, 21821, 9114, 21822, -1, 9117, 9114, 21821, -1, 9114, 21823, 21822, -1, 9114, 9109, 21823, -1, 9109, 21811, 21823, -1, 9109, 9129, 21811, -1, 21810, 21812, 21813, -1, 21821, 21822, 21823, -1, 21824, 21811, 21810, -1, 21824, 21813, 21814, -1, 21824, 21810, 21813, -1, 21825, 21814, 21815, -1, 21825, 21815, 21816, -1, 21825, 21824, 21814, -1, 21825, 21811, 21824, -1, 21826, 21820, 21821, -1, 21826, 21823, 21811, -1, 21826, 21821, 21823, -1, 21827, 21816, 21817, -1, 21827, 21817, 21818, -1, 21827, 21811, 21825, -1, 21827, 21825, 21816, -1, 21828, 21819, 21820, -1, 21828, 21818, 21819, -1, 21828, 21820, 21826, -1, 21828, 21811, 21827, -1, 21828, 21827, 21818, -1, 21828, 21826, 21811, -1, 9048, 21829, 21830, -1, 9048, 9055, 21829, -1, 9055, 21831, 21829, -1, 9055, 9061, 21831, -1, 9039, 21832, 21833, -1, 9039, 9043, 21832, -1, 9043, 21834, 21832, -1, 9043, 9046, 21834, -1, 9046, 21830, 21834, -1, 9046, 9048, 21830, -1, 9071, 9047, 21835, -1, 21835, 9047, 21836, -1, 21836, 9039, 21833, -1, 9047, 9039, 21836, -1, 9056, 9051, 21837, -1, 21837, 9051, 21838, -1, 21838, 9071, 21835, -1, 9051, 9071, 21838, -1, 21839, 9063, 21840, -1, 9065, 9063, 21839, -1, 21840, 9059, 21841, -1, 9063, 9059, 21840, -1, 21841, 9056, 21837, -1, 9059, 9056, 21841, -1, 9061, 21842, 21831, -1, 9061, 9067, 21842, -1, 9067, 21839, 21842, -1, 9067, 9065, 21839, -1, 21836, 21833, 21832, -1, 21841, 21837, 21838, -1, 21843, 21832, 21834, -1, 21843, 21835, 21836, -1, 21843, 21836, 21832, -1, 21844, 21834, 21830, -1, 21844, 21830, 21829, -1, 21844, 21843, 21834, -1, 21844, 21835, 21843, -1, 21845, 21840, 21841, -1, 21845, 21838, 21835, -1, 21845, 21841, 21838, -1, 21846, 21829, 21831, -1, 21846, 21831, 21842, -1, 21846, 21835, 21844, -1, 21846, 21844, 21829, -1, 21847, 21842, 21839, -1, 21847, 21839, 21840, -1, 21847, 21840, 21845, -1, 21847, 21835, 21846, -1, 21847, 21846, 21842, -1, 21847, 21845, 21835, -1, 21848, 8913, 8919, -1, 21849, 8913, 21848, -1, 21850, 8906, 21849, -1, 21849, 8906, 8913, -1, 21851, 8897, 21852, -1, 21852, 8901, 21853, -1, 8897, 8901, 21852, -1, 21853, 8904, 21850, -1, 8901, 8904, 21853, -1, 8904, 8906, 21850, -1, 8929, 8905, 21854, -1, 21854, 8905, 21855, -1, 21855, 8897, 21851, -1, 8905, 8897, 21855, -1, 8914, 8909, 21856, -1, 21856, 8909, 21857, -1, 21857, 8929, 21854, -1, 8909, 8929, 21857, -1, 21858, 8921, 21859, -1, 8923, 8921, 21858, -1, 21859, 8917, 21860, -1, 8921, 8917, 21859, -1, 21860, 8914, 21856, -1, 8917, 8914, 21860, -1, 21858, 8925, 8923, -1, 21861, 8925, 21858, -1, 21848, 8919, 21861, -1, 21861, 8919, 8925, -1, 21855, 21851, 21852, -1, 21860, 21856, 21857, -1, 21862, 21852, 21853, -1, 21862, 21854, 21855, -1, 21862, 21855, 21852, -1, 21863, 21853, 21850, -1, 21863, 21850, 21849, -1, 21863, 21862, 21853, -1, 21863, 21854, 21862, -1, 21864, 21859, 21860, -1, 21864, 21857, 21854, -1, 21864, 21860, 21857, -1, 21865, 21849, 21848, -1, 21865, 21848, 21861, -1, 21865, 21854, 21863, -1, 21865, 21863, 21849, -1, 21866, 21861, 21858, -1, 21866, 21858, 21859, -1, 21866, 21859, 21864, -1, 21866, 21854, 21865, -1, 21866, 21865, 21861, -1, 21866, 21864, 21854, -1, 8847, 21867, 21868, -1, 8847, 8823, 21867, -1, 8823, 21869, 21867, -1, 8823, 8815, 21869, -1, 21869, 8815, 21870, -1, 21870, 8819, 21871, -1, 8815, 8819, 21870, -1, 21871, 8822, 21872, -1, 8819, 8822, 21871, -1, 8822, 8824, 21872, -1, 21873, 21874, 8837, -1, 21874, 8831, 8837, -1, 21874, 21872, 8831, -1, 21872, 8824, 8831, -1, 21875, 21876, 8841, -1, 21876, 8843, 8841, -1, 21876, 21873, 8843, -1, 21873, 8837, 8843, -1, 21875, 8839, 21877, -1, 8841, 8839, 21875, -1, 21877, 8835, 21878, -1, 8839, 8835, 21877, -1, 21878, 8832, 21879, -1, 8835, 8832, 21878, -1, 8832, 21880, 21879, -1, 8832, 8827, 21880, -1, 8827, 21868, 21880, -1, 8827, 8847, 21868, -1, 21867, 21869, 21870, -1, 21878, 21879, 21880, -1, 21881, 21868, 21867, -1, 21881, 21870, 21871, -1, 21881, 21867, 21870, -1, 21882, 21871, 21872, -1, 21882, 21872, 21874, -1, 21882, 21881, 21871, -1, 21882, 21868, 21881, -1, 21883, 21877, 21878, -1, 21883, 21880, 21868, -1, 21883, 21878, 21880, -1, 21884, 21874, 21873, -1, 21884, 21873, 21876, -1, 21884, 21868, 21882, -1, 21884, 21882, 21874, -1, 21885, 21875, 21877, -1, 21885, 21876, 21875, -1, 21885, 21877, 21883, -1, 21885, 21868, 21884, -1, 21885, 21884, 21876, -1, 21885, 21883, 21868, -1, 21886, 8665, 8671, -1, 21887, 8665, 21886, -1, 21888, 8658, 21887, -1, 21887, 8658, 8665, -1, 8649, 21889, 21890, -1, 21889, 8653, 21891, -1, 8649, 8653, 21889, -1, 21891, 8656, 21888, -1, 8653, 8656, 21891, -1, 8656, 8658, 21888, -1, 8681, 8657, 21892, -1, 21892, 8657, 21893, -1, 21893, 8649, 21890, -1, 8657, 8649, 21893, -1, 8666, 8661, 21894, -1, 21894, 8661, 21895, -1, 21895, 8681, 21892, -1, 8661, 8681, 21895, -1, 21896, 8673, 21897, -1, 8675, 8673, 21896, -1, 21897, 8669, 21898, -1, 8673, 8669, 21897, -1, 21898, 8666, 21894, -1, 8669, 8666, 21898, -1, 21896, 8677, 8675, -1, 21899, 8677, 21896, -1, 21886, 8671, 21899, -1, 21899, 8671, 8677, -1, 21893, 21890, 21889, -1, 21898, 21894, 21895, -1, 21900, 21889, 21891, -1, 21900, 21892, 21893, -1, 21900, 21893, 21889, -1, 21901, 21891, 21888, -1, 21901, 21888, 21887, -1, 21901, 21900, 21891, -1, 21901, 21892, 21900, -1, 21902, 21897, 21898, -1, 21902, 21895, 21892, -1, 21902, 21898, 21895, -1, 21903, 21887, 21886, -1, 21903, 21886, 21899, -1, 21903, 21892, 21901, -1, 21903, 21901, 21887, -1, 21904, 21899, 21896, -1, 21904, 21896, 21897, -1, 21904, 21897, 21902, -1, 21904, 21892, 21903, -1, 21904, 21903, 21899, -1, 21904, 21902, 21892, -1, 8623, 21905, 21906, -1, 8623, 8599, 21905, -1, 8599, 21907, 21905, -1, 8599, 8591, 21907, -1, 8591, 21908, 21907, -1, 8591, 8595, 21908, -1, 8595, 21909, 21908, -1, 8595, 8598, 21909, -1, 8598, 21910, 21909, -1, 8598, 8600, 21910, -1, 21911, 21912, 8613, -1, 21912, 8607, 8613, -1, 21912, 21910, 8607, -1, 21910, 8600, 8607, -1, 21913, 21914, 8617, -1, 21914, 8619, 8617, -1, 21914, 21911, 8619, -1, 21911, 8613, 8619, -1, 21913, 8615, 21915, -1, 8617, 8615, 21913, -1, 21915, 8611, 21916, -1, 8615, 8611, 21915, -1, 21916, 8608, 21917, -1, 8611, 8608, 21916, -1, 8608, 21918, 21917, -1, 8608, 8603, 21918, -1, 8603, 21906, 21918, -1, 8603, 8623, 21906, -1, 21905, 21907, 21908, -1, 21916, 21917, 21918, -1, 21919, 21906, 21905, -1, 21919, 21908, 21909, -1, 21919, 21905, 21908, -1, 21920, 21909, 21910, -1, 21920, 21910, 21912, -1, 21920, 21919, 21909, -1, 21920, 21906, 21919, -1, 21921, 21915, 21916, -1, 21921, 21918, 21906, -1, 21921, 21916, 21918, -1, 21922, 21912, 21911, -1, 21922, 21911, 21914, -1, 21922, 21906, 21920, -1, 21922, 21920, 21912, -1, 21923, 21913, 21915, -1, 21923, 21914, 21913, -1, 21923, 21915, 21921, -1, 21923, 21906, 21922, -1, 21923, 21922, 21914, -1, 21923, 21921, 21906, -1, 8457, 21924, 21925, -1, 8457, 8433, 21924, -1, 8433, 21926, 21924, -1, 8433, 8425, 21926, -1, 21927, 8432, 8434, -1, 21927, 21928, 8432, -1, 21928, 8429, 8432, -1, 21928, 21929, 8429, -1, 21929, 8425, 8429, -1, 21929, 21926, 8425, -1, 21930, 21931, 8447, -1, 8447, 21931, 8441, -1, 8441, 21927, 8434, -1, 21931, 21927, 8441, -1, 21932, 21933, 8451, -1, 8451, 21933, 8453, -1, 8453, 21930, 8447, -1, 21933, 21930, 8453, -1, 21934, 21935, 8442, -1, 8442, 21935, 8445, -1, 8445, 21936, 8449, -1, 21935, 21936, 8445, -1, 8449, 21932, 8451, -1, 21936, 21932, 8449, -1, 8442, 21937, 21934, -1, 8442, 8437, 21937, -1, 8437, 21925, 21937, -1, 8437, 8457, 21925, -1, 21924, 21926, 21929, -1, 21935, 21934, 21937, -1, 21938, 21925, 21924, -1, 21938, 21929, 21928, -1, 21938, 21924, 21929, -1, 21939, 21928, 21927, -1, 21939, 21927, 21931, -1, 21939, 21938, 21928, -1, 21939, 21925, 21938, -1, 21940, 21936, 21935, -1, 21940, 21937, 21925, -1, 21940, 21935, 21937, -1, 21941, 21931, 21930, -1, 21941, 21930, 21933, -1, 21941, 21925, 21939, -1, 21941, 21939, 21931, -1, 21942, 21932, 21936, -1, 21942, 21933, 21932, -1, 21942, 21936, 21940, -1, 21942, 21925, 21941, -1, 21942, 21941, 21933, -1, 21942, 21940, 21925, -1, 21943, 8383, 8389, -1, 21943, 21944, 8383, -1, 21944, 8376, 8383, -1, 21944, 21945, 8376, -1, 21945, 8374, 8376, -1, 21945, 21946, 8374, -1, 21946, 8371, 8374, -1, 21946, 21947, 8371, -1, 21947, 8367, 8371, -1, 21947, 21948, 8367, -1, 8399, 8375, 21949, -1, 21949, 8375, 21950, -1, 21950, 8367, 21948, -1, 8375, 8367, 21950, -1, 8384, 8379, 21951, -1, 21951, 8379, 21952, -1, 21952, 8399, 21949, -1, 8379, 8399, 21952, -1, 21951, 21953, 8384, -1, 21953, 8387, 8384, -1, 21953, 21954, 8387, -1, 21954, 8391, 8387, -1, 21954, 21955, 8391, -1, 21955, 8393, 8391, -1, 21955, 8395, 8393, -1, 21955, 21956, 8395, -1, 21956, 8389, 8395, -1, 21956, 21943, 8389, -1, 21950, 21948, 21947, -1, 21953, 21951, 21952, -1, 21957, 21947, 21946, -1, 21957, 21949, 21950, -1, 21957, 21950, 21947, -1, 21958, 21946, 21945, -1, 21958, 21945, 21944, -1, 21958, 21957, 21946, -1, 21958, 21949, 21957, -1, 21959, 21954, 21953, -1, 21959, 21952, 21949, -1, 21959, 21953, 21952, -1, 21960, 21944, 21943, -1, 21960, 21943, 21956, -1, 21960, 21949, 21958, -1, 21960, 21958, 21944, -1, 21961, 21956, 21955, -1, 21961, 21955, 21954, -1, 21961, 21954, 21959, -1, 21961, 21949, 21960, -1, 21961, 21960, 21956, -1, 21961, 21959, 21949, -1, 21962, 8217, 8223, -1, 21962, 21963, 8217, -1, 21963, 8210, 8217, -1, 21963, 21964, 8210, -1, 21964, 8208, 8210, -1, 21964, 21965, 8208, -1, 21965, 8205, 8208, -1, 21965, 21966, 8205, -1, 21966, 8201, 8205, -1, 21966, 21967, 8201, -1, 8233, 8209, 21968, -1, 21968, 8209, 21969, -1, 21969, 8201, 21967, -1, 8209, 8201, 21969, -1, 8218, 8213, 21970, -1, 21970, 8213, 21971, -1, 21971, 8233, 21968, -1, 8213, 8233, 21971, -1, 21970, 21972, 8218, -1, 21972, 8221, 8218, -1, 21972, 21973, 8221, -1, 21973, 8225, 8221, -1, 21973, 21974, 8225, -1, 21974, 8227, 8225, -1, 21974, 8229, 8227, -1, 21974, 21975, 8229, -1, 21975, 8223, 8229, -1, 21975, 21962, 8223, -1, 21969, 21967, 21966, -1, 21972, 21970, 21971, -1, 21976, 21966, 21965, -1, 21976, 21968, 21969, -1, 21976, 21969, 21966, -1, 21977, 21965, 21964, -1, 21977, 21964, 21963, -1, 21977, 21976, 21965, -1, 21977, 21968, 21976, -1, 21978, 21973, 21972, -1, 21978, 21971, 21968, -1, 21978, 21972, 21971, -1, 21979, 21963, 21962, -1, 21979, 21962, 21975, -1, 21979, 21968, 21977, -1, 21979, 21977, 21963, -1, 21980, 21975, 21974, -1, 21980, 21974, 21973, -1, 21980, 21973, 21978, -1, 21980, 21968, 21979, -1, 21980, 21979, 21975, -1, 21980, 21978, 21968, -1, 8175, 21981, 21982, -1, 8175, 8151, 21981, -1, 8151, 21983, 21981, -1, 8151, 8143, 21983, -1, 21984, 8150, 8152, -1, 21984, 21985, 8150, -1, 21985, 8147, 8150, -1, 21985, 21986, 8147, -1, 21986, 8143, 8147, -1, 21986, 21983, 8143, -1, 21987, 21988, 8165, -1, 8165, 21988, 8159, -1, 8159, 21984, 8152, -1, 21988, 21984, 8159, -1, 21989, 21990, 8169, -1, 8169, 21990, 8171, -1, 8171, 21987, 8165, -1, 21990, 21987, 8171, -1, 21991, 21992, 8160, -1, 8160, 21992, 8163, -1, 8163, 21993, 8167, -1, 21992, 21993, 8163, -1, 8167, 21989, 8169, -1, 21993, 21989, 8167, -1, 8160, 21994, 21991, -1, 8160, 8155, 21994, -1, 8155, 21982, 21994, -1, 8155, 8175, 21982, -1, 21981, 21983, 21986, -1, 21992, 21991, 21994, -1, 21995, 21982, 21981, -1, 21995, 21986, 21985, -1, 21995, 21981, 21986, -1, 21996, 21985, 21984, -1, 21996, 21984, 21988, -1, 21996, 21995, 21985, -1, 21996, 21982, 21995, -1, 21997, 21993, 21992, -1, 21997, 21994, 21982, -1, 21997, 21992, 21994, -1, 21998, 21988, 21987, -1, 21998, 21987, 21990, -1, 21998, 21982, 21996, -1, 21998, 21996, 21988, -1, 21999, 21989, 21993, -1, 21999, 21990, 21989, -1, 21999, 21993, 21997, -1, 21999, 21982, 21998, -1, 21999, 21998, 21990, -1, 21999, 21997, 21982, -1, 8009, 22000, 22001, -1, 8009, 7985, 22000, -1, 7985, 22002, 22000, -1, 7985, 7977, 22002, -1, 22003, 7984, 7986, -1, 22003, 22004, 7984, -1, 22004, 7981, 7984, -1, 22004, 22005, 7981, -1, 22005, 7977, 7981, -1, 22005, 22002, 7977, -1, 22006, 22007, 7999, -1, 22007, 7993, 7999, -1, 22007, 22003, 7993, -1, 22003, 7986, 7993, -1, 22008, 22009, 8003, -1, 22009, 8005, 8003, -1, 22009, 22006, 8005, -1, 22006, 7999, 8005, -1, 22010, 22011, 7994, -1, 7994, 22011, 7997, -1, 7997, 22012, 8001, -1, 22011, 22012, 7997, -1, 8001, 22008, 8003, -1, 22012, 22008, 8001, -1, 7994, 22013, 22010, -1, 7994, 7989, 22013, -1, 7989, 22001, 22013, -1, 7989, 8009, 22001, -1, 22000, 22002, 22005, -1, 22011, 22010, 22013, -1, 22014, 22001, 22000, -1, 22014, 22005, 22004, -1, 22014, 22000, 22005, -1, 22015, 22004, 22003, -1, 22015, 22003, 22007, -1, 22015, 22014, 22004, -1, 22015, 22001, 22014, -1, 22016, 22012, 22011, -1, 22016, 22013, 22001, -1, 22016, 22011, 22013, -1, 22017, 22007, 22006, -1, 22017, 22006, 22009, -1, 22017, 22001, 22015, -1, 22017, 22015, 22007, -1, 22018, 22008, 22012, -1, 22018, 22009, 22008, -1, 22018, 22012, 22016, -1, 22018, 22001, 22017, -1, 22018, 22017, 22009, -1, 22018, 22016, 22001, -1, 22019, 7959, 7965, -1, 22020, 7959, 22019, -1, 22021, 7952, 22020, -1, 22020, 7952, 7959, -1, 7952, 22021, 7950, -1, 7950, 22022, 7947, -1, 22021, 22022, 7950, -1, 22022, 22023, 7947, -1, 22023, 7943, 7947, -1, 22023, 22024, 7943, -1, 7975, 7951, 22025, -1, 22025, 7951, 22026, -1, 22026, 7943, 22024, -1, 7951, 7943, 22026, -1, 7960, 7955, 22027, -1, 22027, 7955, 22028, -1, 22028, 7975, 22025, -1, 7955, 7975, 22028, -1, 22027, 22029, 7960, -1, 22029, 7963, 7960, -1, 22029, 22030, 7963, -1, 22030, 7967, 7963, -1, 22030, 22031, 7967, -1, 22031, 7969, 7967, -1, 22031, 7971, 7969, -1, 22032, 7971, 22031, -1, 22019, 7965, 22032, -1, 22032, 7965, 7971, -1, 22026, 22024, 22023, -1, 22029, 22027, 22028, -1, 22033, 22023, 22022, -1, 22033, 22025, 22026, -1, 22033, 22026, 22023, -1, 22034, 22022, 22021, -1, 22034, 22021, 22020, -1, 22034, 22033, 22022, -1, 22034, 22025, 22033, -1, 22035, 22030, 22029, -1, 22035, 22028, 22025, -1, 22035, 22029, 22028, -1, 22036, 22020, 22019, -1, 22036, 22019, 22032, -1, 22036, 22025, 22034, -1, 22036, 22034, 22020, -1, 22037, 22032, 22031, -1, 22037, 22031, 22030, -1, 22037, 22030, 22035, -1, 22037, 22025, 22036, -1, 22037, 22036, 22032, -1, 22037, 22035, 22025, -1, 7893, 22038, 22039, -1, 7893, 7869, 22038, -1, 7869, 22040, 22038, -1, 7869, 7861, 22040, -1, 22041, 7868, 7870, -1, 22041, 22042, 7868, -1, 22042, 7865, 7868, -1, 22042, 22043, 7865, -1, 22043, 7861, 7865, -1, 22043, 22040, 7861, -1, 22044, 22045, 7883, -1, 7883, 22045, 7877, -1, 7877, 22041, 7870, -1, 22045, 22041, 7877, -1, 22046, 22047, 7887, -1, 7887, 22047, 7889, -1, 7889, 22044, 7883, -1, 22047, 22044, 7889, -1, 22048, 22049, 7878, -1, 7878, 22049, 7881, -1, 7881, 22050, 7885, -1, 22049, 22050, 7881, -1, 7885, 22046, 7887, -1, 22050, 22046, 7885, -1, 7878, 22051, 22048, -1, 7878, 7873, 22051, -1, 7873, 22039, 22051, -1, 7873, 7893, 22039, -1, 22038, 22040, 22043, -1, 22049, 22048, 22051, -1, 22052, 22039, 22038, -1, 22052, 22043, 22042, -1, 22052, 22038, 22043, -1, 22053, 22042, 22041, -1, 22053, 22041, 22045, -1, 22053, 22052, 22042, -1, 22053, 22039, 22052, -1, 22054, 22050, 22049, -1, 22054, 22051, 22039, -1, 22054, 22049, 22051, -1, 22055, 22045, 22044, -1, 22055, 22044, 22047, -1, 22055, 22039, 22053, -1, 22055, 22053, 22045, -1, 22056, 22046, 22050, -1, 22056, 22047, 22046, -1, 22056, 22050, 22054, -1, 22056, 22039, 22055, -1, 22056, 22055, 22047, -1, 22056, 22054, 22039, -1, 22057, 7843, 7849, -1, 22057, 22058, 7843, -1, 22058, 7836, 7843, -1, 22058, 22059, 7836, -1, 22059, 7834, 7836, -1, 22059, 22060, 7834, -1, 22060, 7831, 7834, -1, 22060, 22061, 7831, -1, 22061, 7827, 7831, -1, 22061, 22062, 7827, -1, 7859, 7835, 22063, -1, 22063, 7835, 22064, -1, 22064, 7827, 22062, -1, 7835, 7827, 22064, -1, 7844, 7839, 22065, -1, 22065, 7839, 22066, -1, 22066, 7859, 22063, -1, 7839, 7859, 22066, -1, 22065, 22067, 7844, -1, 22067, 7847, 7844, -1, 22067, 22068, 7847, -1, 22068, 7851, 7847, -1, 22068, 22069, 7851, -1, 22069, 7853, 7851, -1, 22069, 7855, 7853, -1, 22069, 22070, 7855, -1, 22070, 7849, 7855, -1, 22070, 22057, 7849, -1, 22064, 22062, 22061, -1, 22067, 22065, 22066, -1, 22071, 22061, 22060, -1, 22071, 22063, 22064, -1, 22071, 22064, 22061, -1, 22072, 22060, 22059, -1, 22072, 22059, 22058, -1, 22072, 22071, 22060, -1, 22072, 22063, 22071, -1, 22073, 22068, 22067, -1, 22073, 22066, 22063, -1, 22073, 22067, 22066, -1, 22074, 22058, 22057, -1, 22074, 22057, 22070, -1, 22074, 22063, 22072, -1, 22074, 22072, 22058, -1, 22075, 22070, 22069, -1, 22075, 22069, 22068, -1, 22075, 22068, 22073, -1, 22075, 22063, 22074, -1, 22075, 22074, 22070, -1, 22075, 22073, 22063, -1, 22076, 7653, 7659, -1, 22077, 7653, 22076, -1, 22078, 7646, 22077, -1, 22077, 7646, 7653, -1, 7637, 22079, 22080, -1, 7637, 7641, 22079, -1, 7641, 22081, 22079, -1, 7641, 7644, 22081, -1, 7644, 22078, 22081, -1, 7644, 7646, 22078, -1, 7669, 7645, 22082, -1, 22082, 7645, 22083, -1, 22083, 7637, 22080, -1, 7645, 7637, 22083, -1, 7654, 7649, 22084, -1, 22084, 7649, 22085, -1, 22085, 7669, 22082, -1, 7649, 7669, 22085, -1, 22086, 7661, 22087, -1, 7663, 7661, 22086, -1, 22087, 7657, 22088, -1, 7661, 7657, 22087, -1, 22088, 7654, 22084, -1, 7657, 7654, 22088, -1, 22086, 7665, 7663, -1, 22089, 7665, 22086, -1, 22076, 7659, 22089, -1, 22089, 7659, 7665, -1, 22083, 22080, 22079, -1, 22088, 22084, 22085, -1, 22090, 22079, 22081, -1, 22090, 22082, 22083, -1, 22090, 22083, 22079, -1, 22091, 22081, 22078, -1, 22091, 22078, 22077, -1, 22091, 22090, 22081, -1, 22091, 22082, 22090, -1, 22092, 22087, 22088, -1, 22092, 22085, 22082, -1, 22092, 22088, 22085, -1, 22093, 22077, 22076, -1, 22093, 22076, 22089, -1, 22093, 22082, 22091, -1, 22093, 22091, 22077, -1, 22094, 22089, 22086, -1, 22094, 22086, 22087, -1, 22094, 22087, 22092, -1, 22094, 22082, 22093, -1, 22094, 22093, 22089, -1, 22094, 22092, 22082, -1, 7611, 22095, 22096, -1, 7611, 7587, 22095, -1, 7587, 22097, 22095, -1, 7587, 7579, 22097, -1, 7579, 22098, 22097, -1, 7579, 7583, 22098, -1, 7583, 22099, 22098, -1, 7583, 7586, 22099, -1, 7586, 22100, 22099, -1, 7586, 7588, 22100, -1, 22101, 22102, 7601, -1, 22102, 7595, 7601, -1, 22102, 22100, 7595, -1, 22100, 7588, 7595, -1, 22103, 22104, 7605, -1, 22104, 7607, 7605, -1, 22104, 22101, 7607, -1, 22101, 7601, 7607, -1, 22103, 7603, 22105, -1, 7605, 7603, 22103, -1, 22105, 7599, 22106, -1, 7603, 7599, 22105, -1, 22106, 7596, 22107, -1, 7599, 7596, 22106, -1, 7596, 22108, 22107, -1, 7596, 7591, 22108, -1, 7591, 22096, 22108, -1, 7591, 7611, 22096, -1, 22095, 22097, 22098, -1, 22106, 22107, 22108, -1, 22109, 22096, 22095, -1, 22109, 22098, 22099, -1, 22109, 22095, 22098, -1, 22110, 22099, 22100, -1, 22110, 22100, 22102, -1, 22110, 22109, 22099, -1, 22110, 22096, 22109, -1, 22111, 22105, 22106, -1, 22111, 22108, 22096, -1, 22111, 22106, 22108, -1, 22112, 22102, 22101, -1, 22112, 22101, 22104, -1, 22112, 22096, 22110, -1, 22112, 22110, 22102, -1, 22113, 22103, 22105, -1, 22113, 22104, 22103, -1, 22113, 22105, 22111, -1, 22113, 22096, 22112, -1, 22113, 22112, 22104, -1, 22113, 22111, 22096, -1, 7361, 22114, 22115, -1, 7361, 7337, 22114, -1, 7337, 22116, 22114, -1, 7337, 7329, 22116, -1, 7329, 22117, 22116, -1, 7329, 7333, 22117, -1, 7333, 22118, 22117, -1, 7333, 7336, 22118, -1, 7336, 22119, 22118, -1, 7336, 7338, 22119, -1, 22119, 7345, 22120, -1, 7338, 7345, 22119, -1, 22120, 7351, 22121, -1, 7345, 7351, 22120, -1, 22121, 7357, 22122, -1, 7351, 7357, 22121, -1, 22122, 7355, 22123, -1, 7357, 7355, 22122, -1, 22123, 7353, 22124, -1, 7355, 7353, 22123, -1, 22124, 7349, 22125, -1, 7353, 7349, 22124, -1, 22125, 7346, 22126, -1, 7349, 7346, 22125, -1, 7346, 22127, 22126, -1, 7346, 7341, 22127, -1, 7341, 22115, 22127, -1, 7341, 7361, 22115, -1, 22114, 22116, 22117, -1, 22125, 22126, 22127, -1, 22128, 22115, 22114, -1, 22128, 22117, 22118, -1, 22128, 22114, 22117, -1, 22129, 22118, 22119, -1, 22129, 22119, 22120, -1, 22129, 22128, 22118, -1, 22129, 22115, 22128, -1, 22130, 22124, 22125, -1, 22130, 22127, 22115, -1, 22130, 22125, 22127, -1, 22131, 22120, 22121, -1, 22131, 22121, 22122, -1, 22131, 22115, 22129, -1, 22131, 22129, 22120, -1, 22132, 22123, 22124, -1, 22132, 22122, 22123, -1, 22132, 22124, 22130, -1, 22132, 22115, 22131, -1, 22132, 22131, 22122, -1, 22132, 22130, 22115, -1, 7304, 22133, 22134, -1, 7304, 7311, 22133, -1, 7311, 22135, 22133, -1, 7311, 7317, 22135, -1, 7295, 22136, 22137, -1, 7295, 7299, 22136, -1, 7299, 22138, 22136, -1, 7299, 7302, 22138, -1, 7302, 22134, 22138, -1, 7302, 7304, 22134, -1, 7327, 7303, 22139, -1, 22139, 7303, 22140, -1, 22140, 7295, 22137, -1, 7303, 7295, 22140, -1, 7312, 7307, 22141, -1, 22141, 7307, 22142, -1, 22142, 7327, 22139, -1, 7307, 7327, 22142, -1, 22143, 7319, 22144, -1, 7321, 7319, 22143, -1, 22144, 7315, 22145, -1, 7319, 7315, 22144, -1, 22145, 7312, 22141, -1, 7315, 7312, 22145, -1, 7317, 22146, 22135, -1, 7317, 7323, 22146, -1, 7323, 22143, 22146, -1, 7323, 7321, 22143, -1, 22140, 22137, 22136, -1, 22145, 22141, 22142, -1, 22147, 22136, 22138, -1, 22147, 22139, 22140, -1, 22147, 22140, 22136, -1, 22148, 22138, 22134, -1, 22148, 22134, 22133, -1, 22148, 22147, 22138, -1, 22148, 22139, 22147, -1, 22149, 22144, 22145, -1, 22149, 22142, 22139, -1, 22149, 22145, 22142, -1, 22150, 22133, 22135, -1, 22150, 22135, 22146, -1, 22150, 22139, 22148, -1, 22150, 22148, 22133, -1, 22151, 22146, 22143, -1, 22151, 22143, 22144, -1, 22151, 22144, 22149, -1, 22151, 22139, 22150, -1, 22151, 22150, 22146, -1, 22151, 22149, 22139, -1, 7221, 22152, 22153, -1, 7221, 7197, 22152, -1, 7197, 22154, 22152, -1, 7197, 7189, 22154, -1, 7198, 22155, 7196, -1, 7196, 22156, 7193, -1, 22155, 22156, 7196, -1, 7193, 22157, 7189, -1, 22156, 22157, 7193, -1, 22157, 22154, 7189, -1, 22158, 22159, 7211, -1, 22159, 7205, 7211, -1, 22159, 22155, 7205, -1, 22155, 7198, 7205, -1, 22160, 22161, 7215, -1, 22161, 7217, 7215, -1, 22161, 22158, 7217, -1, 22158, 7211, 7217, -1, 22162, 22163, 7206, -1, 7206, 22163, 7209, -1, 7209, 22164, 7213, -1, 22163, 22164, 7209, -1, 7213, 22160, 7215, -1, 22164, 22160, 7213, -1, 7206, 22165, 22162, -1, 7206, 7201, 22165, -1, 7201, 22153, 22165, -1, 7201, 7221, 22153, -1, 22152, 22154, 22157, -1, 22163, 22162, 22165, -1, 22166, 22153, 22152, -1, 22166, 22157, 22156, -1, 22166, 22152, 22157, -1, 22167, 22156, 22155, -1, 22167, 22155, 22159, -1, 22167, 22166, 22156, -1, 22167, 22153, 22166, -1, 22168, 22164, 22163, -1, 22168, 22165, 22153, -1, 22168, 22163, 22165, -1, 22169, 22159, 22158, -1, 22169, 22158, 22161, -1, 22169, 22153, 22167, -1, 22169, 22167, 22159, -1, 22170, 22160, 22164, -1, 22170, 22161, 22160, -1, 22170, 22164, 22168, -1, 22170, 22153, 22169, -1, 22170, 22169, 22161, -1, 22170, 22168, 22153, -1, 22171, 7147, 7153, -1, 22172, 7147, 22171, -1, 22173, 7140, 22172, -1, 22172, 7140, 7147, -1, 7140, 22173, 7138, -1, 7138, 22174, 7135, -1, 22173, 22174, 7138, -1, 7135, 22175, 7131, -1, 22174, 22175, 7135, -1, 22175, 22176, 7131, -1, 7163, 7139, 22177, -1, 22177, 7139, 22178, -1, 22178, 7131, 22176, -1, 7139, 7131, 22178, -1, 7148, 7143, 22179, -1, 22179, 7143, 22180, -1, 22180, 7163, 22177, -1, 7143, 7163, 22180, -1, 22181, 7148, 22179, -1, 22182, 7151, 22181, -1, 22181, 7151, 7148, -1, 22183, 7155, 22182, -1, 22182, 7155, 7151, -1, 22183, 7157, 7155, -1, 22183, 7159, 7157, -1, 22184, 7159, 22183, -1, 22171, 7153, 22184, -1, 22184, 7153, 7159, -1, 22178, 22176, 22175, -1, 22181, 22179, 22180, -1, 22185, 22175, 22174, -1, 22185, 22177, 22178, -1, 22185, 22178, 22175, -1, 22186, 22174, 22173, -1, 22186, 22173, 22172, -1, 22186, 22185, 22174, -1, 22186, 22177, 22185, -1, 22187, 22182, 22181, -1, 22187, 22180, 22177, -1, 22187, 22181, 22180, -1, 22188, 22172, 22171, -1, 22188, 22171, 22184, -1, 22188, 22177, 22186, -1, 22188, 22186, 22172, -1, 22189, 22184, 22183, -1, 22189, 22183, 22182, -1, 22189, 22182, 22187, -1, 22189, 22177, 22188, -1, 22189, 22188, 22184, -1, 22189, 22187, 22177, -1, 6997, 22190, 22191, -1, 6997, 6973, 22190, -1, 6973, 22192, 22190, -1, 6973, 6965, 22192, -1, 6965, 22193, 22192, -1, 6965, 6969, 22193, -1, 6969, 22194, 22193, -1, 6969, 6972, 22194, -1, 6972, 22195, 22194, -1, 6972, 6974, 22195, -1, 22196, 22197, 6987, -1, 22197, 6981, 6987, -1, 22197, 22195, 6981, -1, 22195, 6974, 6981, -1, 22198, 22199, 6991, -1, 22199, 6993, 6991, -1, 22199, 22196, 6993, -1, 22196, 6987, 6993, -1, 22198, 6989, 22200, -1, 6991, 6989, 22198, -1, 22200, 6985, 22201, -1, 6989, 6985, 22200, -1, 22201, 6982, 22202, -1, 6985, 6982, 22201, -1, 6982, 22203, 22202, -1, 6982, 6977, 22203, -1, 6977, 22191, 22203, -1, 6977, 6997, 22191, -1, 22190, 22192, 22193, -1, 22201, 22202, 22203, -1, 22204, 22191, 22190, -1, 22204, 22193, 22194, -1, 22204, 22190, 22193, -1, 22205, 22194, 22195, -1, 22205, 22195, 22197, -1, 22205, 22204, 22194, -1, 22205, 22191, 22204, -1, 22206, 22200, 22201, -1, 22206, 22203, 22191, -1, 22206, 22201, 22203, -1, 22207, 22197, 22196, -1, 22207, 22196, 22199, -1, 22207, 22191, 22205, -1, 22207, 22205, 22197, -1, 22208, 22198, 22200, -1, 22208, 22199, 22198, -1, 22208, 22200, 22206, -1, 22208, 22191, 22207, -1, 22208, 22207, 22199, -1, 22208, 22206, 22191, -1, 22209, 6923, 6929, -1, 22210, 6923, 22209, -1, 22211, 6916, 22210, -1, 22210, 6916, 6923, -1, 6907, 22212, 22213, -1, 6907, 6911, 22212, -1, 6911, 22214, 22212, -1, 6911, 6914, 22214, -1, 6914, 22211, 22214, -1, 6914, 6916, 22211, -1, 6939, 6915, 22215, -1, 22215, 6915, 22216, -1, 22216, 6907, 22213, -1, 6915, 6907, 22216, -1, 6924, 6919, 22217, -1, 22217, 6919, 22218, -1, 22218, 6939, 22215, -1, 6919, 6939, 22218, -1, 22219, 6931, 22220, -1, 6933, 6931, 22219, -1, 22220, 6927, 22221, -1, 6931, 6927, 22220, -1, 22221, 6924, 22217, -1, 6927, 6924, 22221, -1, 22219, 6935, 6933, -1, 22222, 6935, 22219, -1, 22209, 6929, 22222, -1, 22222, 6929, 6935, -1, 22216, 22213, 22212, -1, 22221, 22217, 22218, -1, 22223, 22212, 22214, -1, 22223, 22215, 22216, -1, 22223, 22216, 22212, -1, 22224, 22214, 22211, -1, 22224, 22211, 22210, -1, 22224, 22223, 22214, -1, 22224, 22215, 22223, -1, 22225, 22220, 22221, -1, 22225, 22218, 22215, -1, 22225, 22221, 22218, -1, 22226, 22210, 22209, -1, 22226, 22209, 22222, -1, 22226, 22215, 22224, -1, 22226, 22224, 22210, -1, 22227, 22222, 22219, -1, 22227, 22219, 22220, -1, 22227, 22220, 22225, -1, 22227, 22215, 22226, -1, 22227, 22226, 22222, -1, 22227, 22225, 22215, -1, 22228, 6781, 6787, -1, 22228, 22229, 6781, -1, 22229, 6774, 6781, -1, 22229, 22230, 6774, -1, 22230, 6772, 6774, -1, 22230, 22231, 6772, -1, 22231, 6769, 6772, -1, 22231, 22232, 6769, -1, 22232, 6765, 6769, -1, 22232, 22233, 6765, -1, 6797, 6773, 22234, -1, 22234, 6773, 22235, -1, 22235, 6765, 22233, -1, 6773, 6765, 22235, -1, 6782, 6777, 22236, -1, 22236, 6777, 22237, -1, 22237, 6797, 22234, -1, 6777, 6797, 22237, -1, 22236, 22238, 6782, -1, 6782, 22238, 6785, -1, 6785, 22239, 6789, -1, 22238, 22239, 6785, -1, 6789, 22240, 6791, -1, 22239, 22240, 6789, -1, 22240, 6793, 6791, -1, 22240, 22241, 6793, -1, 22241, 6787, 6793, -1, 22241, 22228, 6787, -1, 22235, 22233, 22232, -1, 22238, 22236, 22237, -1, 22242, 22232, 22231, -1, 22242, 22234, 22235, -1, 22242, 22235, 22232, -1, 22243, 22231, 22230, -1, 22243, 22230, 22229, -1, 22243, 22242, 22231, -1, 22243, 22234, 22242, -1, 22244, 22239, 22238, -1, 22244, 22237, 22234, -1, 22244, 22238, 22237, -1, 22245, 22229, 22228, -1, 22245, 22228, 22241, -1, 22245, 22234, 22243, -1, 22245, 22243, 22229, -1, 22246, 22241, 22240, -1, 22246, 22240, 22239, -1, 22246, 22239, 22244, -1, 22246, 22234, 22245, -1, 22246, 22245, 22241, -1, 22246, 22244, 22234, -1, 6739, 22247, 22248, -1, 6739, 6715, 22247, -1, 6715, 22249, 22247, -1, 6715, 6707, 22249, -1, 22250, 6714, 6716, -1, 22250, 22251, 6714, -1, 22251, 6711, 6714, -1, 22251, 22252, 6711, -1, 22252, 6707, 6711, -1, 22252, 22249, 6707, -1, 22253, 22254, 6729, -1, 6729, 22254, 6723, -1, 6723, 22250, 6716, -1, 22254, 22250, 6723, -1, 22255, 22256, 6733, -1, 6733, 22256, 6735, -1, 6735, 22253, 6729, -1, 22256, 22253, 6735, -1, 22257, 22258, 6724, -1, 6724, 22258, 6727, -1, 6727, 22259, 6731, -1, 22258, 22259, 6727, -1, 6731, 22255, 6733, -1, 22259, 22255, 6731, -1, 6724, 22260, 22257, -1, 6724, 6719, 22260, -1, 6719, 22248, 22260, -1, 6719, 6739, 22248, -1, 22247, 22249, 22252, -1, 22258, 22257, 22260, -1, 22261, 22248, 22247, -1, 22261, 22252, 22251, -1, 22261, 22247, 22252, -1, 22262, 22251, 22250, -1, 22262, 22250, 22254, -1, 22262, 22261, 22251, -1, 22262, 22248, 22261, -1, 22263, 22259, 22258, -1, 22263, 22260, 22248, -1, 22263, 22258, 22260, -1, 22264, 22254, 22253, -1, 22264, 22253, 22256, -1, 22264, 22248, 22262, -1, 22264, 22262, 22254, -1, 22265, 22255, 22259, -1, 22265, 22256, 22255, -1, 22265, 22259, 22263, -1, 22265, 22248, 22264, -1, 22265, 22264, 22256, -1, 22265, 22263, 22248, -1, 6465, 22266, 22267, -1, 6465, 6441, 22266, -1, 6441, 22268, 22266, -1, 6441, 6433, 22268, -1, 22269, 6440, 6442, -1, 22269, 22270, 6440, -1, 22270, 6437, 6440, -1, 22270, 22271, 6437, -1, 22271, 6433, 6437, -1, 22271, 22268, 6433, -1, 22272, 22273, 6455, -1, 22273, 6449, 6455, -1, 22273, 22269, 6449, -1, 22269, 6442, 6449, -1, 22274, 22275, 6459, -1, 22275, 6461, 6459, -1, 22275, 22272, 6461, -1, 22272, 6455, 6461, -1, 22276, 22277, 6450, -1, 6450, 22277, 6453, -1, 6453, 22278, 6457, -1, 22277, 22278, 6453, -1, 6457, 22274, 6459, -1, 22278, 22274, 6457, -1, 6450, 22279, 22276, -1, 6450, 6445, 22279, -1, 6445, 22267, 22279, -1, 6445, 6465, 22267, -1, 22266, 22268, 22271, -1, 22277, 22276, 22279, -1, 22280, 22267, 22266, -1, 22280, 22271, 22270, -1, 22280, 22266, 22271, -1, 22281, 22270, 22269, -1, 22281, 22269, 22273, -1, 22281, 22280, 22270, -1, 22281, 22267, 22280, -1, 22282, 22278, 22277, -1, 22282, 22279, 22267, -1, 22282, 22277, 22279, -1, 22283, 22273, 22272, -1, 22283, 22272, 22275, -1, 22283, 22267, 22281, -1, 22283, 22281, 22273, -1, 22284, 22274, 22278, -1, 22284, 22275, 22274, -1, 22284, 22278, 22282, -1, 22284, 22267, 22283, -1, 22284, 22283, 22275, -1, 22284, 22282, 22267, -1, 22285, 6391, 6397, -1, 22286, 6391, 22285, -1, 22287, 6384, 22286, -1, 22286, 6384, 6391, -1, 22287, 6382, 6384, -1, 22287, 22288, 6382, -1, 22288, 6379, 6382, -1, 22288, 22289, 6379, -1, 22289, 6375, 6379, -1, 22289, 22290, 6375, -1, 6407, 6383, 22291, -1, 22291, 6383, 22292, -1, 22292, 6375, 22290, -1, 6383, 6375, 22292, -1, 6392, 6387, 22293, -1, 22293, 6387, 22294, -1, 22294, 6407, 22291, -1, 6387, 6407, 22294, -1, 22293, 22295, 6392, -1, 6392, 22295, 6395, -1, 6395, 22296, 6399, -1, 22295, 22296, 6395, -1, 6399, 22297, 6401, -1, 22296, 22297, 6399, -1, 22297, 6403, 6401, -1, 22298, 6403, 22297, -1, 22285, 6397, 22298, -1, 22298, 6397, 6403, -1, 22292, 22290, 22289, -1, 22295, 22293, 22294, -1, 22299, 22289, 22288, -1, 22299, 22291, 22292, -1, 22299, 22292, 22289, -1, 22300, 22288, 22287, -1, 22300, 22287, 22286, -1, 22300, 22299, 22288, -1, 22300, 22291, 22299, -1, 22301, 22296, 22295, -1, 22301, 22294, 22291, -1, 22301, 22295, 22294, -1, 22302, 22286, 22285, -1, 22302, 22285, 22298, -1, 22302, 22291, 22300, -1, 22302, 22300, 22286, -1, 22303, 22298, 22297, -1, 22303, 22297, 22296, -1, 22303, 22296, 22301, -1, 22303, 22291, 22302, -1, 22303, 22302, 22298, -1, 22303, 22301, 22291, -1, 22304, 6201, 6207, -1, 22304, 22305, 6201, -1, 22305, 6194, 6201, -1, 22305, 22306, 6194, -1, 22306, 6192, 6194, -1, 22306, 22307, 6192, -1, 22307, 6189, 6192, -1, 22307, 22308, 6189, -1, 22308, 6185, 6189, -1, 22308, 22309, 6185, -1, 6217, 6193, 22310, -1, 22310, 6193, 22311, -1, 22311, 6185, 22309, -1, 6193, 6185, 22311, -1, 6202, 6197, 22312, -1, 22312, 6197, 22313, -1, 22313, 6217, 22310, -1, 6197, 6217, 22313, -1, 22312, 22314, 6202, -1, 6202, 22314, 6205, -1, 6205, 22315, 6209, -1, 22314, 22315, 6205, -1, 6209, 22316, 6211, -1, 22315, 22316, 6209, -1, 22316, 6213, 6211, -1, 22316, 22317, 6213, -1, 22317, 6207, 6213, -1, 22317, 22304, 6207, -1, 22311, 22309, 22308, -1, 22314, 22312, 22313, -1, 22318, 22308, 22307, -1, 22318, 22310, 22311, -1, 22318, 22311, 22308, -1, 22319, 22307, 22306, -1, 22319, 22306, 22305, -1, 22319, 22318, 22307, -1, 22319, 22310, 22318, -1, 22320, 22315, 22314, -1, 22320, 22313, 22310, -1, 22320, 22314, 22313, -1, 22321, 22305, 22304, -1, 22321, 22304, 22317, -1, 22321, 22310, 22319, -1, 22321, 22319, 22305, -1, 22322, 22317, 22316, -1, 22322, 22316, 22315, -1, 22322, 22315, 22320, -1, 22322, 22310, 22321, -1, 22322, 22321, 22317, -1, 22322, 22320, 22310, -1, 6183, 22323, 22324, -1, 6183, 6159, 22323, -1, 6159, 22325, 22323, -1, 6159, 6151, 22325, -1, 22326, 6158, 6160, -1, 22326, 22327, 6158, -1, 22327, 6155, 6158, -1, 22327, 22328, 6155, -1, 22328, 6151, 6155, -1, 22328, 22325, 6151, -1, 22329, 22330, 6173, -1, 6173, 22330, 6167, -1, 6167, 22326, 6160, -1, 22330, 22326, 6167, -1, 22331, 22332, 6177, -1, 6177, 22332, 6179, -1, 6179, 22329, 6173, -1, 22332, 22329, 6179, -1, 22333, 22334, 6168, -1, 6168, 22334, 6171, -1, 6171, 22335, 6175, -1, 22334, 22335, 6171, -1, 6175, 22331, 6177, -1, 22335, 22331, 6175, -1, 6168, 22336, 22333, -1, 6168, 6163, 22336, -1, 6163, 22324, 22336, -1, 6163, 6183, 22324, -1, 22323, 22325, 22328, -1, 22334, 22333, 22336, -1, 22337, 22324, 22323, -1, 22337, 22328, 22327, -1, 22337, 22323, 22328, -1, 22338, 22327, 22326, -1, 22338, 22326, 22330, -1, 22338, 22337, 22327, -1, 22338, 22324, 22337, -1, 22339, 22335, 22334, -1, 22339, 22336, 22324, -1, 22339, 22334, 22336, -1, 22340, 22330, 22329, -1, 22340, 22329, 22332, -1, 22340, 22324, 22338, -1, 22340, 22338, 22330, -1, 22341, 22331, 22335, -1, 22341, 22332, 22331, -1, 22341, 22335, 22339, -1, 22341, 22324, 22340, -1, 22341, 22340, 22332, -1, 22341, 22339, 22324, -1, 5969, 22342, 22343, -1, 5969, 5945, 22342, -1, 5945, 22344, 22342, -1, 5945, 5937, 22344, -1, 22345, 5944, 5946, -1, 22345, 22346, 5944, -1, 22346, 5941, 5944, -1, 22346, 22347, 5941, -1, 22347, 5937, 5941, -1, 22347, 22344, 5937, -1, 22348, 22349, 5959, -1, 5959, 22349, 5953, -1, 5953, 22345, 5946, -1, 22349, 22345, 5953, -1, 22350, 22351, 5963, -1, 5963, 22351, 5965, -1, 5965, 22348, 5959, -1, 22351, 22348, 5965, -1, 22352, 22353, 5954, -1, 5954, 22353, 5957, -1, 5957, 22354, 5961, -1, 22353, 22354, 5957, -1, 5961, 22350, 5963, -1, 22354, 22350, 5961, -1, 5954, 22355, 22352, -1, 5954, 5949, 22355, -1, 5949, 22343, 22355, -1, 5949, 5969, 22343, -1, 22342, 22344, 22347, -1, 22353, 22352, 22355, -1, 22356, 22343, 22342, -1, 22356, 22347, 22346, -1, 22356, 22342, 22347, -1, 22357, 22346, 22345, -1, 22357, 22345, 22349, -1, 22357, 22356, 22346, -1, 22357, 22343, 22356, -1, 22358, 22354, 22353, -1, 22358, 22355, 22343, -1, 22358, 22353, 22355, -1, 22359, 22349, 22348, -1, 22359, 22348, 22351, -1, 22359, 22343, 22357, -1, 22359, 22357, 22349, -1, 22360, 22350, 22354, -1, 22360, 22351, 22350, -1, 22360, 22354, 22358, -1, 22360, 22343, 22359, -1, 22360, 22359, 22351, -1, 22360, 22358, 22343, -1, 22361, 5919, 5925, -1, 22361, 22362, 5919, -1, 22362, 5912, 5919, -1, 22362, 22363, 5912, -1, 22363, 5910, 5912, -1, 22363, 22364, 5910, -1, 22364, 5907, 5910, -1, 22364, 22365, 5907, -1, 22365, 5903, 5907, -1, 22365, 22366, 5903, -1, 5935, 5911, 22367, -1, 22367, 5911, 22368, -1, 22368, 5903, 22366, -1, 5911, 5903, 22368, -1, 5920, 5915, 22369, -1, 22369, 5915, 22370, -1, 22370, 5935, 22367, -1, 5915, 5935, 22370, -1, 22369, 22371, 5920, -1, 5920, 22371, 5923, -1, 5923, 22372, 5927, -1, 22371, 22372, 5923, -1, 5927, 22373, 5929, -1, 22372, 22373, 5927, -1, 22373, 5931, 5929, -1, 22373, 22374, 5931, -1, 22374, 5925, 5931, -1, 22374, 22361, 5925, -1, 22368, 22366, 22365, -1, 22371, 22369, 22370, -1, 22375, 22365, 22364, -1, 22375, 22367, 22368, -1, 22375, 22368, 22365, -1, 22376, 22364, 22363, -1, 22376, 22363, 22362, -1, 22376, 22375, 22364, -1, 22376, 22367, 22375, -1, 22377, 22372, 22371, -1, 22377, 22370, 22367, -1, 22377, 22371, 22370, -1, 22378, 22362, 22361, -1, 22378, 22361, 22374, -1, 22378, 22367, 22376, -1, 22378, 22376, 22362, -1, 22379, 22374, 22373, -1, 22379, 22373, 22372, -1, 22379, 22372, 22377, -1, 22379, 22367, 22378, -1, 22379, 22378, 22374, -1, 22379, 22377, 22367, -1, 22380, 5885, 5891, -1, 22381, 5885, 22380, -1, 22382, 5878, 22381, -1, 22381, 5878, 5885, -1, 22382, 5876, 5878, -1, 22382, 22383, 5876, -1, 22383, 5873, 5876, -1, 22383, 22384, 5873, -1, 22384, 5869, 5873, -1, 22384, 22385, 5869, -1, 5901, 5877, 22386, -1, 22386, 5877, 22387, -1, 22387, 5869, 22385, -1, 5877, 5869, 22387, -1, 5886, 5881, 22388, -1, 22388, 5881, 22389, -1, 22389, 5901, 22386, -1, 5881, 5901, 22389, -1, 22388, 22390, 5886, -1, 22390, 5889, 5886, -1, 22390, 22391, 5889, -1, 22391, 5893, 5889, -1, 22391, 22392, 5893, -1, 22392, 5895, 5893, -1, 22392, 5897, 5895, -1, 22393, 5897, 22392, -1, 22380, 5891, 22393, -1, 22393, 5891, 5897, -1, 22387, 22385, 22384, -1, 22390, 22388, 22389, -1, 22394, 22384, 22383, -1, 22394, 22386, 22387, -1, 22394, 22387, 22384, -1, 22395, 22383, 22382, -1, 22395, 22382, 22381, -1, 22395, 22394, 22383, -1, 22395, 22386, 22394, -1, 22396, 22391, 22390, -1, 22396, 22389, 22386, -1, 22396, 22390, 22389, -1, 22397, 22381, 22380, -1, 22397, 22380, 22393, -1, 22397, 22386, 22395, -1, 22397, 22395, 22381, -1, 22398, 22393, 22392, -1, 22398, 22392, 22391, -1, 22398, 22391, 22396, -1, 22398, 22386, 22397, -1, 22398, 22397, 22393, -1, 22398, 22396, 22386, -1, 5843, 22399, 22400, -1, 5843, 5819, 22399, -1, 5819, 22401, 22399, -1, 5819, 5811, 22401, -1, 22402, 5818, 5820, -1, 22402, 22403, 5818, -1, 22403, 5815, 5818, -1, 22403, 22404, 5815, -1, 22404, 5811, 5815, -1, 22404, 22401, 5811, -1, 22405, 22406, 5833, -1, 22406, 5827, 5833, -1, 22406, 22402, 5827, -1, 22402, 5820, 5827, -1, 22407, 22408, 5837, -1, 22408, 5839, 5837, -1, 22408, 22405, 5839, -1, 22405, 5833, 5839, -1, 22409, 22410, 5828, -1, 5828, 22410, 5831, -1, 5831, 22411, 5835, -1, 22410, 22411, 5831, -1, 5835, 22407, 5837, -1, 22411, 22407, 5835, -1, 5828, 22412, 22409, -1, 5828, 5823, 22412, -1, 5823, 22400, 22412, -1, 5823, 5843, 22400, -1, 22399, 22401, 22404, -1, 22410, 22409, 22412, -1, 22413, 22400, 22399, -1, 22413, 22404, 22403, -1, 22413, 22399, 22404, -1, 22414, 22403, 22402, -1, 22414, 22402, 22406, -1, 22414, 22413, 22403, -1, 22414, 22400, 22413, -1, 22415, 22411, 22410, -1, 22415, 22412, 22400, -1, 22415, 22410, 22412, -1, 22416, 22406, 22405, -1, 22416, 22405, 22408, -1, 22416, 22400, 22414, -1, 22416, 22414, 22406, -1, 22417, 22407, 22411, -1, 22417, 22408, 22407, -1, 22417, 22411, 22415, -1, 22417, 22400, 22416, -1, 22417, 22416, 22408, -1, 22417, 22415, 22400, -1, 5653, 22418, 22419, -1, 5653, 5629, 22418, -1, 5629, 22420, 22418, -1, 5629, 5621, 22420, -1, 22421, 5628, 5630, -1, 22421, 22422, 5628, -1, 22422, 5625, 5628, -1, 22422, 22423, 5625, -1, 22423, 5621, 5625, -1, 22423, 22420, 5621, -1, 22424, 22425, 5643, -1, 22425, 5637, 5643, -1, 22425, 22421, 5637, -1, 22421, 5630, 5637, -1, 22426, 22427, 5647, -1, 22427, 5649, 5647, -1, 22427, 22424, 5649, -1, 22424, 5643, 5649, -1, 22428, 22429, 5638, -1, 5638, 22429, 5641, -1, 5641, 22430, 5645, -1, 22429, 22430, 5641, -1, 5645, 22426, 5647, -1, 22430, 22426, 5645, -1, 5638, 22431, 22428, -1, 5638, 5633, 22431, -1, 5633, 22419, 22431, -1, 5633, 5653, 22419, -1, 22418, 22420, 22423, -1, 22429, 22428, 22431, -1, 22432, 22419, 22418, -1, 22432, 22423, 22422, -1, 22432, 22418, 22423, -1, 22433, 22422, 22421, -1, 22433, 22421, 22425, -1, 22433, 22432, 22422, -1, 22433, 22419, 22432, -1, 22434, 22430, 22429, -1, 22434, 22431, 22419, -1, 22434, 22429, 22431, -1, 22435, 22425, 22424, -1, 22435, 22424, 22427, -1, 22435, 22419, 22433, -1, 22435, 22433, 22425, -1, 22436, 22426, 22430, -1, 22436, 22427, 22426, -1, 22436, 22430, 22434, -1, 22436, 22419, 22435, -1, 22436, 22435, 22427, -1, 22436, 22434, 22419, -1, 22437, 5603, 5609, -1, 22438, 5603, 22437, -1, 22439, 5596, 22438, -1, 22438, 5596, 5603, -1, 22439, 5594, 5596, -1, 22439, 22440, 5594, -1, 22440, 5591, 5594, -1, 22440, 22441, 5591, -1, 22441, 5587, 5591, -1, 22441, 22442, 5587, -1, 5619, 5595, 22443, -1, 22443, 5595, 22444, -1, 22444, 5587, 22442, -1, 5595, 5587, 22444, -1, 5604, 5599, 22445, -1, 22445, 5599, 22446, -1, 22446, 5619, 22443, -1, 5599, 5619, 22446, -1, 22445, 22447, 5604, -1, 22447, 5607, 5604, -1, 22447, 22448, 5607, -1, 22448, 5611, 5607, -1, 22448, 22449, 5611, -1, 22449, 5613, 5611, -1, 22449, 5615, 5613, -1, 22450, 5615, 22449, -1, 22437, 5609, 22450, -1, 22450, 5609, 5615, -1, 22444, 22442, 22441, -1, 22447, 22445, 22446, -1, 22451, 22441, 22440, -1, 22451, 22443, 22444, -1, 22451, 22444, 22441, -1, 22452, 22440, 22439, -1, 22452, 22439, 22438, -1, 22452, 22451, 22440, -1, 22452, 22443, 22451, -1, 22453, 22448, 22447, -1, 22453, 22446, 22443, -1, 22453, 22447, 22446, -1, 22454, 22438, 22437, -1, 22454, 22437, 22450, -1, 22454, 22443, 22452, -1, 22454, 22452, 22438, -1, 22455, 22450, 22449, -1, 22455, 22449, 22448, -1, 22455, 22448, 22453, -1, 22455, 22443, 22454, -1, 22455, 22454, 22450, -1, 22455, 22453, 22443, -1, 22456, 5437, 5443, -1, 22457, 5437, 22456, -1, 22458, 5430, 22457, -1, 22457, 5430, 5437, -1, 5430, 22458, 5428, -1, 5428, 22459, 5425, -1, 22458, 22459, 5428, -1, 22459, 22460, 5425, -1, 22460, 5421, 5425, -1, 22460, 22461, 5421, -1, 5453, 5429, 22462, -1, 22462, 5429, 22463, -1, 22463, 5421, 22461, -1, 5429, 5421, 22463, -1, 5438, 5433, 22464, -1, 22464, 5433, 22465, -1, 22465, 5453, 22462, -1, 5433, 5453, 22465, -1, 22464, 22466, 5438, -1, 5438, 22466, 5441, -1, 5441, 22467, 5445, -1, 22466, 22467, 5441, -1, 5445, 22468, 5447, -1, 22467, 22468, 5445, -1, 22468, 5449, 5447, -1, 22469, 5449, 22468, -1, 22456, 5443, 22469, -1, 22469, 5443, 5449, -1, 22463, 22461, 22460, -1, 22466, 22464, 22465, -1, 22470, 22460, 22459, -1, 22470, 22462, 22463, -1, 22470, 22463, 22460, -1, 22471, 22459, 22458, -1, 22471, 22458, 22457, -1, 22471, 22470, 22459, -1, 22471, 22462, 22470, -1, 22472, 22467, 22466, -1, 22472, 22465, 22462, -1, 22472, 22466, 22465, -1, 22473, 22457, 22456, -1, 22473, 22456, 22469, -1, 22473, 22462, 22471, -1, 22473, 22471, 22457, -1, 22474, 22469, 22468, -1, 22474, 22468, 22467, -1, 22474, 22467, 22472, -1, 22474, 22462, 22473, -1, 22474, 22473, 22469, -1, 22474, 22472, 22462, -1, 5395, 22475, 22476, -1, 5395, 5371, 22475, -1, 5371, 22477, 22475, -1, 5371, 5363, 22477, -1, 22478, 5370, 5372, -1, 22478, 22479, 5370, -1, 22479, 5367, 5370, -1, 22479, 22480, 5367, -1, 22480, 5363, 5367, -1, 22480, 22477, 5363, -1, 22481, 22482, 5385, -1, 22482, 5379, 5385, -1, 22482, 22478, 5379, -1, 22478, 5372, 5379, -1, 22483, 22484, 5389, -1, 22484, 5391, 5389, -1, 22484, 22481, 5391, -1, 22481, 5385, 5391, -1, 22485, 22486, 5380, -1, 5380, 22486, 5383, -1, 5383, 22487, 5387, -1, 22486, 22487, 5383, -1, 5387, 22483, 5389, -1, 22487, 22483, 5387, -1, 5380, 22488, 22485, -1, 5380, 5375, 22488, -1, 5375, 22476, 22488, -1, 5375, 5395, 22476, -1, 22475, 22477, 22480, -1, 22486, 22485, 22488, -1, 22489, 22476, 22475, -1, 22489, 22480, 22479, -1, 22489, 22475, 22480, -1, 22490, 22479, 22478, -1, 22490, 22478, 22482, -1, 22490, 22489, 22479, -1, 22490, 22476, 22489, -1, 22491, 22487, 22486, -1, 22491, 22488, 22476, -1, 22491, 22486, 22488, -1, 22492, 22482, 22481, -1, 22492, 22481, 22484, -1, 22492, 22476, 22490, -1, 22492, 22490, 22482, -1, 22493, 22483, 22487, -1, 22493, 22484, 22483, -1, 22493, 22487, 22491, -1, 22493, 22476, 22492, -1, 22493, 22492, 22484, -1, 22493, 22491, 22476, -1, 5229, 22494, 22495, -1, 5229, 5205, 22494, -1, 5205, 22496, 22494, -1, 5205, 5197, 22496, -1, 5206, 22497, 5204, -1, 5204, 22498, 5201, -1, 22497, 22498, 5204, -1, 5201, 22499, 5197, -1, 22498, 22499, 5201, -1, 22499, 22496, 5197, -1, 22500, 22501, 5219, -1, 22501, 5213, 5219, -1, 22501, 22497, 5213, -1, 22497, 5206, 5213, -1, 22502, 22503, 5223, -1, 22503, 5225, 5223, -1, 22503, 22500, 5225, -1, 22500, 5219, 5225, -1, 22504, 22505, 5214, -1, 5214, 22505, 5217, -1, 5217, 22506, 5221, -1, 22505, 22506, 5217, -1, 5221, 22502, 5223, -1, 22506, 22502, 5221, -1, 5214, 22507, 22504, -1, 5214, 5209, 22507, -1, 5209, 22495, 22507, -1, 5209, 5229, 22495, -1, 22494, 22496, 22499, -1, 22505, 22504, 22507, -1, 22508, 22495, 22494, -1, 22508, 22499, 22498, -1, 22508, 22494, 22499, -1, 22509, 22498, 22497, -1, 22509, 22497, 22501, -1, 22509, 22508, 22498, -1, 22509, 22495, 22508, -1, 22510, 22506, 22505, -1, 22510, 22507, 22495, -1, 22510, 22505, 22507, -1, 22511, 22501, 22500, -1, 22511, 22500, 22503, -1, 22511, 22495, 22509, -1, 22511, 22509, 22501, -1, 22512, 22502, 22506, -1, 22512, 22503, 22502, -1, 22512, 22506, 22510, -1, 22512, 22495, 22511, -1, 22512, 22511, 22503, -1, 22512, 22510, 22495, -1, 22513, 5155, 5161, -1, 22514, 5155, 22513, -1, 22515, 5148, 22514, -1, 22514, 5148, 5155, -1, 5148, 22515, 5146, -1, 5146, 22516, 5143, -1, 22515, 22516, 5146, -1, 5143, 22517, 5139, -1, 22516, 22517, 5143, -1, 22517, 22518, 5139, -1, 5171, 5147, 22519, -1, 22519, 5147, 22520, -1, 22520, 5139, 22518, -1, 5147, 5139, 22520, -1, 5156, 5151, 22521, -1, 22521, 5151, 22522, -1, 22522, 5171, 22519, -1, 5151, 5171, 22522, -1, 22521, 22523, 5156, -1, 5156, 22523, 5159, -1, 5159, 22524, 5163, -1, 22523, 22524, 5159, -1, 5163, 22525, 5165, -1, 22524, 22525, 5163, -1, 22525, 5167, 5165, -1, 22526, 5167, 22525, -1, 22513, 5161, 22526, -1, 22526, 5161, 5167, -1, 22520, 22518, 22517, -1, 22523, 22521, 22522, -1, 22527, 22517, 22516, -1, 22527, 22519, 22520, -1, 22527, 22520, 22517, -1, 22528, 22516, 22515, -1, 22528, 22515, 22514, -1, 22528, 22527, 22516, -1, 22528, 22519, 22527, -1, 22529, 22524, 22523, -1, 22529, 22522, 22519, -1, 22529, 22523, 22522, -1, 22530, 22514, 22513, -1, 22530, 22513, 22526, -1, 22530, 22519, 22528, -1, 22530, 22528, 22514, -1, 22531, 22526, 22525, -1, 22531, 22525, 22524, -1, 22531, 22524, 22529, -1, 22531, 22519, 22530, -1, 22531, 22530, 22526, -1, 22531, 22529, 22519, -1 - ] - } - } - DEF fr_hub Shape { - appearance Appearance { - material Material { - } - texture ImageTexture { - url [ - "textures/metal.jpg" - ] - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - 0.048559859 -0.069640324 -0.050070167, 0.043693721 -0.072791681 -0.050070301, 0.048491523 -0.069542378 -0.049880549, -0.066166803 -0.053196251 -0.050069153, -0.069642901 -0.048556849 -0.050068974, -0.066074073 -0.053121626 -0.049879611, 0.043731749 -0.072855175 -0.050281674, -0.069545209 -0.048488766 -0.049879372, 0.043744713 -0.072876647 -0.050504148, 0.048616245 -0.069721505 -0.050503954, 0.048602015 -0.069700986 -0.050281599, -0.069724157 -0.048613399 -0.050502822, -0.069703683 -0.048599154 -0.050280228, -0.066243947 -0.05325824 -0.050503194, -0.066224501 -0.053242594 -0.050280571, 0.043344691 -0.072209984 -0.04952915, 0.03831552 -0.074999735 -0.049529403, 0.04323025 -0.072019264 -0.049504161, 0.038214415 -0.074801505 -0.04950425, -0.069086462 -0.048168778 -0.049527735, -0.072212771 -0.04334189 -0.049527481, -0.068903893 -0.048041567 -0.049502954, -0.072021976 -0.043227404 -0.049502447, 0.043453366 -0.072391316 -0.049603209, 0.038411692 -0.075187817 -0.049603298, -0.072393984 -0.043450534 -0.049601436, -0.069259897 -0.048289716 -0.049601927, 0.038498074 -0.075356632 -0.049722403, 0.043550909 -0.072553664 -0.049722135, -0.069415361 -0.048398197 -0.049720913, -0.072556615 -0.043548286 -0.049720645, 0.038569957 -0.075497642 -0.049880728, -0.072692275 -0.043629795 -0.04987897, 0.043632522 -0.072689578 -0.049880654, 0.038624376 -0.075603858 -0.05007045, -0.072794437 -0.043690801 -0.050068587, 0.038657904 -0.075669691 -0.050281808, -0.072857827 -0.043729037 -0.050279975, 0.038669288 -0.075691953 -0.050504357, -0.072879374 -0.043741971 -0.050502568, 0.033107862 -0.077439547 -0.049529418, 0.033020541 -0.077234983 -0.049504533, -0.075002283 -0.038312867 -0.049527258, -0.074804083 -0.038211778 -0.049502179, -0.07519044 -0.038408875 -0.049601257, 0.033191025 -0.077633828 -0.049603358, 0.033265561 -0.077808157 -0.049722612, -0.07535927 -0.038495243 -0.049720407, 0.033327714 -0.077953786 -0.049881086, -0.075500518 -0.038567215 -0.049878731, 0.033374488 -0.078063235 -0.050070569, -0.075606421 -0.038621426 -0.050068215, 0.033403739 -0.078131273 -0.050281852, -0.075672552 -0.038654983 -0.050279692, 0.033413559 -0.07815443 -0.050504476, -0.075694844 -0.038666487 -0.050502226, 0.027745932 -0.079518273 -0.049529552, -0.077442318 -0.033105195 -0.049526751, 0.027672604 -0.079308301 -0.049504414, 0.027815521 -0.079717696 -0.049603537, -0.077237546 -0.033017799 -0.049502119, -0.077636585 -0.033188269 -0.049600899, 0.027878046 -0.079896957 -0.049722731, -0.077810943 -0.033262774 -0.049720064, -0.077956617 -0.033324823 -0.049878374, 0.02793023 -0.08004649 -0.049881235, 0.02796945 -0.080158859 -0.050070673, -0.078066096 -0.033371955 -0.050068006, 0.027993709 -0.080228671 -0.050282061, 0.028002113 -0.080252379 -0.05050467, -0.078157023 -0.033410892 -0.050501928, -0.078134 -0.033400953 -0.050279379, 0.022254482 -0.081226349 -0.049529761, -0.079521105 -0.02774322 -0.049526647, 0.022195607 -0.081011727 -0.049504638, 0.022310272 -0.081430152 -0.049603581, -0.079310954 -0.027669668 -0.049501747, -0.079720601 -0.027812794 -0.049600601, 0.022360474 -0.081613168 -0.04972288, -0.079899549 -0.027875304 -0.04971987, 0.022402361 -0.081765831 -0.04988122, -0.080049247 -0.027927414 -0.04987812, 0.022433773 -0.081880823 -0.050070867, -0.080161512 -0.027966619 -0.050067857, 0.022459954 -0.081976205 -0.050504699, 0.022453278 -0.081952095 -0.050282076, -0.08025533 -0.027999133 -0.050501585, -0.080231413 -0.027991012 -0.050278991, 0.016659245 -0.08255583 -0.049529672, 0.016615257 -0.082337648 -0.049504802, -0.081229225 -0.022251621 -0.049526244, -0.081014618 -0.022192866 -0.049501255, 0.016701162 -0.082762897 -0.04960376, -0.081432939 -0.022307679 -0.049600229, 0.016738683 -0.082948789 -0.049723059, -0.081615835 -0.022357672 -0.049719408, 0.01677002 -0.083104149 -0.049881339, -0.081768692 -0.022399426 -0.049878001, 0.016793534 -0.08322081 -0.050070956, -0.081883505 -0.022430986 -0.05006744, 0.016813189 -0.083317801 -0.050504625, 0.016808361 -0.083293363 -0.050282136, -0.081979007 -0.022457033 -0.050501287, -0.081954792 -0.022450671 -0.050278813, 0.010986537 -0.083500236 -0.049529731, 0.010957554 -0.08327955 -0.049504891, -0.082558379 -0.016656741 -0.049525991, -0.082340434 -0.016612604 -0.049501032, 0.011014074 -0.083709732 -0.049603701, -0.082765684 -0.016698509 -0.049599886, 0.01103881 -0.083897591 -0.04972288, -0.08295165 -0.016735822 -0.049719304, 0.011059478 -0.084054708 -0.049881354, -0.083106741 -0.016767278 -0.049877539, 0.011075005 -0.084172755 -0.050070867, -0.083223566 -0.016790763 -0.050067157, 0.011084661 -0.084246054 -0.05028224, 0.011087894 -0.084271133 -0.050504774, -0.083320588 -0.016810358 -0.050501063, -0.083296001 -0.016805485 -0.0502785, 0.0052625239 -0.084055066 -0.049529836, 0.0052485317 -0.083833069 -0.049504802, -0.083502889 -0.010983914 -0.049525648, -0.083282337 -0.010954618 -0.049500704, 0.0052757114 -0.084266201 -0.049603611, -0.083712459 -0.011011332 -0.049599618, 0.0052876025 -0.084455535 -0.049722984, -0.083900496 -0.011036128 -0.049718812, 0.0052975118 -0.084613547 -0.049881443, -0.084057391 -0.011056706 -0.049877241, 0.0053048432 -0.084732234 -0.050071046, -0.084175542 -0.011072263 -0.050066799, 0.0053094327 -0.084806085 -0.050282255, -0.08424899 -0.011081815 -0.050278172, 0.0053109378 -0.084831193 -0.050504893, -0.084273711 -0.011085078 -0.050500855, -0.00048609078 -0.084218502 -0.04952985, -0.084057927 -0.0052597821 -0.049525365, -0.08383593 -0.0052458048 -0.049500346, -0.00048483908 -0.083995983 -0.049504817, -0.00048744678 -0.084429786 -0.04960379, -0.084268987 -0.0052728206 -0.049599275, -0.00048848987 -0.084619433 -0.049723104, -0.084457949 -0.0052847862 -0.049718305, -0.00048929453 -0.084777743 -0.049881354, -0.084616229 -0.0052946359 -0.049876869, -0.00048997998 -0.084896818 -0.050071061, -0.084735051 -0.005302161 -0.050066292, -0.00049032271 -0.084970802 -0.050282329, -0.00049048662 -0.084995985 -0.050504923, -0.084833995 -0.0053082258 -0.050500348, -0.084808975 -0.0053066611 -0.05027777, -0.006232515 -0.083988905 -0.049529657, -0.084221065 0.00048884749 -0.049524918, -0.083998591 0.00048750639 -0.049500018, -0.0062160045 -0.083767027 -0.049504802, -0.0062481165 -0.084199652 -0.049603656, -0.084432483 0.0004901439 -0.049599022, -0.0062621534 -0.084388569 -0.04972297, -0.084622234 0.00049130619 -0.049718156, -0.006273821 -0.084546641 -0.049881414, -0.084780499 0.00049221516 -0.049876541, -0.0062827021 -0.084665358 -0.050071061, -0.084899575 0.0004928112 -0.050066233, -0.0062900633 -0.084764168 -0.050504759, -0.006288141 -0.084739268 -0.050282121, -0.084998682 0.00049336255 -0.050500095, -0.08497344 0.00049325824 -0.050277665, -0.083991647 0.0062350482 -0.049524754, -0.083769679 0.0062187314 -0.049499735, -0.011949658 -0.08336778 -0.049529701, -0.011918128 -0.083147556 -0.049504876, -0.011979714 -0.083576903 -0.049603641, -0.084202453 0.0062509328 -0.049598753, -0.08439143 0.006264776 -0.049717918, -0.012006477 -0.083764687 -0.049722895, -0.012028977 -0.083921358 -0.04988122, -0.084549367 0.0062764734 -0.049876302, -0.01204595 -0.084039301 -0.050070897, -0.084668249 0.0062854141 -0.050065741, -0.012059987 -0.08413738 -0.050504744, -0.012056425 -0.084112629 -0.050282285, -0.084766999 0.0062928051 -0.050499797, -0.084741876 0.0062909126 -0.050277293, -0.083370537 0.01195237 -0.049524441, -0.083150253 0.011920884 -0.049499363, -0.017611086 -0.082357988 -0.049529538, -0.017564729 -0.082140326 -0.049504742, -0.017655402 -0.082564771 -0.049603805, -0.08357963 0.011982501 -0.049598351, -0.017695144 -0.082750067 -0.049722791, -0.082143098 0.017567471 -0.04949908, -0.080966726 0.023193419 -0.049523696, -0.08075273 0.023131981 -0.049498782, -0.083767369 0.012009501 -0.049717486, -0.017728224 -0.082904786 -0.04988125, -0.0839241 0.012031689 -0.049875841, -0.017753094 -0.083021373 -0.050070867, -0.084042251 0.012048855 -0.050065383, -0.017773762 -0.08311817 -0.050504714, -0.017768458 -0.083093792 -0.050282344, -0.084140137 0.012062937 -0.050499365, -0.084115237 0.012059256 -0.050276831, -0.023190692 -0.080963939 -0.049529731, -0.023129374 -0.080750272 -0.049504697, -0.082360864 0.017614096 -0.049524084, 0.080966905 -0.023187891 -0.049526438, 0.079195604 -0.028659299 -0.049526751, 0.080752984 -0.023126706 -0.049501434, -0.023248866 -0.081167355 -0.049603581, 0.078986198 -0.028583512 -0.049501702, -0.082567409 0.017658204 -0.049598113, -0.081169978 0.023251608 -0.04959777, 0.079394251 -0.028731123 -0.049600825, 0.081170052 -0.023246124 -0.049600378, -0.023301065 -0.081349552 -0.049722806, 0.081352428 -0.023298383 -0.049719602, 0.079572573 -0.028795704 -0.049719945, -0.082752824 0.017697826 -0.049717188, -0.081352338 0.023303866 -0.049716815, -0.023344725 -0.081501737 -0.04988113, 0.079721481 -0.028849453 -0.049878165, 0.081504703 -0.023341909 -0.049877912, -0.023377523 -0.081616327 -0.050070673, -0.082907647 0.017730892 -0.049875587, -0.081504554 0.023347393 -0.049875319, 0.079833508 -0.028890058 -0.050067872, 0.081619129 -0.023374721 -0.050067693, -0.023397714 -0.08168751 -0.050282195, -0.023404792 -0.081711531 -0.05050461, 0.07992667 -0.028923675 -0.050501734, 0.079903096 -0.028915375 -0.050279155, 0.081714153 -0.023401946 -0.05050154, 0.081690237 -0.02339527 -0.050279006, -0.08302401 0.017755732 -0.050065041, -0.081619188 0.023380265 -0.050064966, -0.028661966 -0.079192773 -0.049529582, -0.028586313 -0.07898359 -0.049504668, 0.077054843 -0.03399691 -0.049527019, 0.076851398 -0.033907145 -0.04950197, -0.083096519 0.017771333 -0.050276563, -0.081690311 0.023400813 -0.05027613, -0.02873385 -0.079391539 -0.049603492, -0.081714213 0.023407474 -0.050498769, -0.083121017 0.017776579 -0.050499171, 0.077248156 -0.034082323 -0.049601004, -0.028798535 -0.079569623 -0.049722612, 0.077421829 -0.034158826 -0.049720123, -0.028852209 -0.079718664 -0.049881205, 0.077566624 -0.034222722 -0.049878478, -0.028892845 -0.079830766 -0.050070688, 0.077675641 -0.034270748 -0.0500682, -0.028918192 -0.079900175 -0.050282001, 0.077743292 -0.03430064 -0.050279424, 0.077766255 -0.034310758 -0.050502047, -0.028926596 -0.079923794 -0.05050455, -0.033999592 -0.07705234 -0.049529523, 0.074555159 -0.039176092 -0.049527347, 0.074358344 -0.039072603 -0.049502298, -0.033909827 -0.076848552 -0.049504474, -0.034085006 -0.077245519 -0.049603343, 0.074742153 -0.039274424 -0.049601212, -0.034161434 -0.077419043 -0.049722463, 0.074910149 -0.039362654 -0.049720392, -0.034225509 -0.077563867 -0.049880981, 0.07505025 -0.039436221 -0.049878731, 0.075155765 -0.039491579 -0.050068483, -0.03427352 -0.077672854 -0.05007048, 0.075221121 -0.039525986 -0.050279915, -0.034313515 -0.077763468 -0.050504461, -0.034303308 -0.07774058 -0.050281957, 0.075243428 -0.039537728 -0.050502315, -0.039178774 -0.074552312 -0.049529165, 0.071707591 -0.044172391 -0.049527556, 0.071518123 -0.044055849 -0.049502671, -0.03907527 -0.074355468 -0.049504295, -0.039277196 -0.074739441 -0.049603269, 0.071887657 -0.04428345 -0.049601644, 0.072049007 -0.044382945 -0.049720779, -0.039365381 -0.074907109 -0.049722418, 0.072183862 -0.044465929 -0.049879104, -0.039439127 -0.075047448 -0.049880803, 0.07228525 -0.044528425 -0.050068647, -0.039494425 -0.075152889 -0.05007039, 0.072348177 -0.044567138 -0.050280109, -0.03954044 -0.075240672 -0.050504252, -0.039528698 -0.075218275 -0.050281733, 0.072369605 -0.044580355 -0.050502628, 0.068525881 -0.048963115 -0.049527958, -0.044175208 -0.07170485 -0.049529225, 0.068344727 -0.048833787 -0.049502835, -0.044058606 -0.071515173 -0.049504176, -0.044286147 -0.071884736 -0.049603179, 0.068697765 -0.04908593 -0.049601763, 0.068852141 -0.049196258 -0.049720913, -0.044385582 -0.072046265 -0.049722373, -0.044468567 -0.072181135 -0.049880698, 0.068980917 -0.049288258 -0.049879283, 0.069077864 -0.049357548 -0.050068855, -0.044531077 -0.072282508 -0.050070345, 0.069138035 -0.049400598 -0.050280228, 0.06915842 -0.049415037 -0.050502837, -0.044583172 -0.072366685 -0.050504193, -0.044569984 -0.072345451 -0.050281525, 0.06502451 -0.053525195 -0.049528167, -0.048965901 -0.068522975 -0.049528986, 0.064852729 -0.053383842 -0.049503192, -0.048836529 -0.06834203 -0.049503967, 0.065187737 -0.053659648 -0.049601987, -0.049088731 -0.068695009 -0.049603075, 0.065334111 -0.053779989 -0.049721226, -0.04919894 -0.068849191 -0.049722075, 0.06545642 -0.05388087 -0.049879715, -0.049290955 -0.068978086 -0.049880296, 0.065548331 -0.053956553 -0.050069168, -0.049360275 -0.069074899 -0.050069988, 0.065605417 -0.054003388 -0.050280496, -0.049403355 -0.069135338 -0.05028142, -0.049417794 -0.069155619 -0.050503984, 0.065624788 -0.054019451 -0.05050312, 0.061220065 -0.057838023 -0.04952848, 0.061058298 -0.057685211 -0.049503267, -0.05352807 -0.065021932 -0.049528688, -0.05338645 -0.064849943 -0.049503788, 0.061373651 -0.057983011 -0.049602419, -0.053662404 -0.065184861 -0.049602613, 0.061511517 -0.058113411 -0.049721405, -0.053782836 -0.065331593 -0.049721852, 0.061626658 -0.0582221 -0.049879923, -0.053883523 -0.065453619 -0.049880311, 0.061713144 -0.058303863 -0.050069362, -0.053959176 -0.065545604 -0.050069943, 0.061766922 -0.058354482 -0.050280854, -0.054006264 -0.06560263 -0.050281197, 0.061785266 -0.058371946 -0.050503328, 0.057130173 -0.061880961 -0.049528539, -0.054022118 -0.065622002 -0.050503716, -0.057840779 -0.061217353 -0.049528465, 0.056979239 -0.061717391 -0.04950355, -0.057687938 -0.061055586 -0.049503386, -0.057985857 -0.061371058 -0.049602553, 0.057273462 -0.062036127 -0.049602464, 0.057402283 -0.062175572 -0.049721718, -0.058116078 -0.06150873 -0.049721539, 0.057509527 -0.062291861 -0.049880087, -0.058224797 -0.061623812 -0.049880117, 0.057590336 -0.062379301 -0.050069645, -0.058306664 -0.061710358 -0.05006966, 0.057640493 -0.06243363 -0.050281018, -0.058357447 -0.061764136 -0.050280944, 0.057657525 -0.062452167 -0.050503582, -0.058374643 -0.06178236 -0.050503537, 0.052773982 -0.065635458 -0.049528882, -0.061883643 -0.057127327 -0.049528211, 0.052634344 -0.065461829 -0.049503922, 0.052906364 -0.065799981 -0.049602717, -0.061720133 -0.056976527 -0.049503237, -0.062039062 -0.057270825 -0.049602285, 0.053025216 -0.06594786 -0.049721837, -0.06217818 -0.057399482 -0.04972145, 0.053124368 -0.066071123 -0.049880221, -0.062294468 -0.05750668 -0.049879879, 0.053199008 -0.066164121 -0.050069883, -0.062382102 -0.057587475 -0.050069571, 0.053245425 -0.066221774 -0.050281346, 0.053260967 -0.066241279 -0.050503969, -0.062454998 -0.057654709 -0.050503328, -0.062436283 -0.057637796 -0.050280735, 0.048171535 -0.069083691 -0.049528912, -0.065638214 -0.052771002 -0.049528092, 0.048044235 -0.068901211 -0.049504042, 0.048292443 -0.06925711 -0.04960297, -0.065464765 -0.052631736 -0.049503028, -0.065802813 -0.052903503 -0.049602032, 0.048400983 -0.069412619 -0.049722031, -0.065950409 -0.053022489 -0.049721152, 0.038657963 -0.075675339 0.050273284, 0.043731749 -0.072860673 0.050273344, 0.038624346 -0.075609416 0.050061703, 0.038669273 -0.075697601 0.05049555, -0.075190544 -0.038414598 0.049596831, -0.0725566 -0.043553859 0.049715757, -0.072393909 -0.043456256 0.049596459, 0.043744743 -0.072882354 0.050495833, 0.043693781 -0.072797194 0.050061926, -0.075359419 -0.038500831 0.049715847, 0.043344602 -0.072215453 0.049521014, 0.048171446 -0.069089204 0.049521133, 0.043230176 -0.072024718 0.049495861, -0.072692335 -0.043635324 0.049873963, 0.04804416 -0.068906754 0.049496055, -0.075500399 -0.038572788 0.04987435, -0.072794423 -0.043696672 0.050063863, -0.07560657 -0.038627028 0.050064147, 0.048292413 -0.069262773 0.049595073, -0.075672299 -0.038660839 0.050275296, -0.072857872 -0.043734685 0.050275087, 0.043453336 -0.0723968 0.049594924, 0.048400953 -0.069418177 0.049714178, -0.0728793 -0.043747649 0.050497577, -0.075694725 -0.03867209 0.050497815, 0.043550909 -0.072559357 0.049714074, -0.072021902 -0.043232948 0.049497709, -0.069086447 -0.048174262 0.049522296, -0.068903863 -0.04804717 0.049497247, -0.072212577 -0.043347508 0.049522683, 0.043632403 -0.072695151 0.049872398, 0.048491567 -0.06954816 0.049872667, 0.048559636 -0.069645911 0.050062329, -0.069259763 -0.0482952 0.049596176, 0.04861629 -0.069727093 0.050496027, 0.048601791 -0.069706529 0.050273597, -0.069415331 -0.04840368 0.049715504, 0.052773848 -0.065640852 0.049521208, -0.069545299 -0.048494399 0.049873725, 0.052634314 -0.065467402 0.049496159, -0.081714213 0.023401946 0.050501302, -0.083121046 0.017771035 0.050500929, -0.081690043 0.023395032 0.050278932, -0.069642931 -0.048562407 0.050063491, 0.052906394 -0.065805584 0.049595401, -0.069703534 -0.048604816 0.0502747, -0.069724113 -0.048619106 0.050497293, 0.053025097 -0.065953359 0.049714461, -0.065637991 -0.052776679 0.049522176, -0.065464661 -0.052637279 0.049497128, 0.053124353 -0.06607686 0.049872831, -0.065802768 -0.052909076 0.04959619, 0.053198949 -0.066169709 0.050062478, 0.053261057 -0.066246986 0.050496385, 0.053245276 -0.066227287 0.050273776, -0.065950662 -0.053027898 0.049715102, 0.057130113 -0.06188646 0.049521536, -0.066073909 -0.053127214 0.049873546, 0.056979209 -0.061722979 0.049496412, -0.066166908 -0.053201824 0.050063223, 0.057273582 -0.062041774 0.04959555, -0.066224411 -0.053248078 0.050274447, -0.066243991 -0.053263828 0.050496951, 0.057402164 -0.06218113 0.04971455, -0.061883569 -0.057132944 0.049521834, -0.061720103 -0.056981966 0.049496815, 0.057509691 -0.062297419 0.049872801, -0.062038869 -0.057276294 0.049595788, 0.057590455 -0.062385038 0.050062731, 0.05765757 -0.0624578 0.050496399, 0.057640567 -0.062439382 0.05027394, -0.062178135 -0.05740498 0.049715057, 0.061220154 -0.05784364 0.049521804, -0.062294543 -0.057512403 0.049873278, 0.061058208 -0.05769065 0.0494968, 0.061373815 -0.057988778 0.049595729, -0.062382191 -0.057593137 0.050063029, -0.062454939 -0.057660401 0.050496787, -0.062436432 -0.057643414 0.050274268, 0.061511576 -0.05811888 0.049714804, -0.057840705 -0.061222985 0.04952158, 0.061626747 -0.058227599 0.049873248, -0.057687849 -0.061061129 0.049496621, -0.057985783 -0.061376512 0.049595729, 0.061713248 -0.058309421 0.050062791, 0.061785325 -0.058377564 0.050496534, 0.061766878 -0.058360219 0.050274283, -0.058115974 -0.061514437 0.049714625, 0.06502451 -0.053530768 0.049521998, -0.058224678 -0.061629474 0.049872935, 0.064852849 -0.05338943 0.049496949, -0.058306634 -0.061716035 0.050062597, 0.065187648 -0.053665191 0.049595922, -0.058374614 -0.061788082 0.050496504, -0.058357343 -0.061769724 0.050273955, 0.065334186 -0.053785697 0.049715027, -0.053528085 -0.065027371 0.049521416, -0.053386629 -0.064855546 0.049496368, 0.06545639 -0.053886443 0.049873263, -0.053662375 -0.065190583 0.049595475, 0.065548256 -0.053962022 0.050063282, 0.065605447 -0.05400911 0.050274387, -0.053782925 -0.065337017 0.049714461, 0.065624878 -0.054025039 0.050496757, 0.068525791 -0.048968583 0.049522236, 0.068344817 -0.048839286 0.049497277, -0.053883418 -0.065459266 0.049872771, -0.053959146 -0.065551117 0.050062358, 0.068697825 -0.049091488 0.049596161, -0.054006219 -0.065608218 0.050273821, -0.054022193 -0.065627575 0.050496325, 0.068851992 -0.049201787 0.04971537, -0.048965737 -0.068528697 0.049521208, -0.048836425 -0.068347543 0.049496055, 0.068980888 -0.049293771 0.049873799, -0.049088731 -0.068700641 0.049595132, 0.069077894 -0.049363092 0.050063372, 0.069158405 -0.049420565 0.050497264, 0.06913808 -0.049406156 0.050274819, -0.049198925 -0.068854988 0.049714297, 0.071707621 -0.044178128 0.049522504, 0.071518168 -0.044061422 0.049497366, -0.049290955 -0.068983719 0.049872726, -0.049360186 -0.069080591 0.050062239, 0.071887583 -0.044289023 0.049596548, -0.049403235 -0.069140717 0.050273657, 0.072049037 -0.044388503 0.049715579, -0.049417853 -0.069161251 0.050496101, -0.044175252 -0.071710497 0.049521148, -0.044058442 -0.071521014 0.04949601, 0.072183803 -0.044471413 0.049873903, -0.044286102 -0.071890518 0.049595013, 0.072285205 -0.044533998 0.050063714, 0.07236962 -0.044585928 0.050497457, 0.072348267 -0.04457283 0.050274968, -0.044385627 -0.072051808 0.049714208, 0.074555025 -0.03918159 0.049523041, 0.074358255 -0.039078087 0.049497873, -0.044468522 -0.072186679 0.049872458, -0.044531062 -0.072288111 0.050062165, 0.074742094 -0.039280027 0.049596786, -0.044570029 -0.072351083 0.050273567, -0.044583097 -0.072372288 0.050495923, 0.074910045 -0.039368182 0.049716026, -0.039178804 -0.07455796 0.049520865, 0.075050175 -0.039441794 0.049874246, -0.03907527 -0.074360877 0.049495906, -0.039277121 -0.074744925 0.049594954, 0.075155795 -0.039497256 0.050063953, 0.075243428 -0.039543435 0.050497755, 0.075221106 -0.039531678 0.050275177, -0.039365321 -0.074912757 0.049713999, 0.077054933 -0.034002483 0.049523219, 0.076851398 -0.033912629 0.049497992, -0.039438963 -0.075052947 0.049872443, 0.07724835 -0.034087777 0.049597085, -0.039494485 -0.075158611 0.050061837, -0.03954041 -0.07524617 0.050495684, -0.039528817 -0.075223967 0.050273344, 0.077421859 -0.034164324 0.049716339, -0.033999562 -0.077057853 0.049520835, 0.077566639 -0.03422831 0.049874544, -0.033909798 -0.076854169 0.049495518, -0.034084961 -0.077251211 0.049594581, 0.077675685 -0.034276441 0.050064191, 0.077766314 -0.03431651 0.050497964, 0.077743366 -0.034306273 0.050275505, -0.034161538 -0.077424645 0.04971388, 0.079195485 -0.028664753 0.049523368, 0.078986287 -0.0285891 0.049498275, 0.080966905 -0.023193523 0.049523845, -0.034225464 -0.077569455 0.0498721, -0.034273461 -0.077678353 0.050061822, 0.07939443 -0.02873683 0.049597427, 0.081169993 -0.023251757 0.049597681, -0.0343135 -0.07776922 0.050495759, -0.034303471 -0.077746108 0.050273091, 0.079572573 -0.028801143 0.049716383, 0.081352398 -0.023303941 0.04971686, -0.028662011 -0.079198375 0.049520507, -0.028586298 -0.078989118 0.049495503, 0.079721406 -0.028855219 0.049874783, 0.081504643 -0.023347646 0.04987511, -0.028733909 -0.079396933 0.049594432, 0.079833493 -0.028895751 0.050064459, 0.081619173 -0.023380235 0.050064817, -0.028798461 -0.079575419 0.049713567, -0.028852373 -0.079724222 0.049872026, 0.079902962 -0.028920919 0.050275981, 0.081690177 -0.023400813 0.050276235, 0.081714362 -0.023407727 0.050498694, 0.07992661 -0.028929427 0.050498188, -0.028892919 -0.079836309 0.050061643, -0.028926462 -0.079929367 0.050495505, -0.028918102 -0.079905823 0.050272927, -0.023190781 -0.080969706 0.049520537, -0.023129568 -0.080755666 0.04949531, -0.023248881 -0.081172809 0.049594507, -0.023301095 -0.081355095 0.049713671, -0.02334471 -0.081507221 0.049872056, -0.023377433 -0.081621885 0.050061524, 0.080752924 -0.02313216 0.049498573, -0.023397818 -0.081693009 0.050272912, -0.023404837 -0.081717044 0.050495446, -0.017611265 -0.082363561 0.049520448, -0.017564669 -0.082145795 0.04949528, -0.017655388 -0.0825703 0.049594417, -0.017695114 -0.082755715 0.049713477, -0.080966651 0.023187861 0.049526393, -0.082360581 0.017608464 0.049525961, -0.080752835 0.023126677 0.049501345, -0.01772818 -0.082910344 0.049871787, -0.082142979 0.017561883 0.049501017, -0.017753124 -0.08302699 0.050061285, -0.082567424 0.017652601 0.04959999, -0.081169933 0.023246035 0.049600258, -0.017768547 -0.083099291 0.050272778, -0.017773718 -0.083123878 0.050495327, -0.081352383 0.023298383 0.049719289, -0.082752675 0.017692208 0.049719259, -0.011949599 -0.083373338 0.049520403, -0.082907617 0.017725334 0.049877465, -0.011917859 -0.083153144 0.049495265, -0.081504554 0.023341775 0.049877942, -0.011979625 -0.083582669 0.049594462, -0.083023995 0.017750144 0.050067291, -0.081619084 0.023374543 0.050067559, -0.08309637 0.017765641 0.050278515, -0.012006611 -0.083770186 0.049713582, -0.083370402 0.011946872 0.049525648, -0.083150208 0.011915371 0.049500763, -0.012028873 -0.08392711 0.049871832, -0.083579719 0.011976913 0.049599677, -0.012045875 -0.084044963 0.050061449, -0.012059912 -0.084143072 0.050495237, -0.01205641 -0.084118247 0.050272897, -0.083767459 0.012003869 0.049718827, -0.08392407 0.01202631 0.049877167, -0.0062325001 -0.083994552 0.049520403, -0.0062159598 -0.083772644 0.049495295, -0.0062480718 -0.084205136 0.049594268, -0.084042013 0.012042984 0.050066873, -0.084115252 0.012053475 0.050278142, -0.084140033 0.012056962 0.050500691, -0.0062620491 -0.084394336 0.049713373, -0.083991408 0.0062295347 0.04952538, -0.083769605 0.0062130988 0.049500346, -0.0062736869 -0.084552318 0.049871668, -0.084202379 0.0062451065 0.049599439, -0.0062826127 -0.084671199 0.05006142, -0.08439146 0.0062592328 0.049718648, -0.0062900335 -0.084769845 0.050495178, -0.0062880218 -0.084744766 0.050272897, -0.084549338 0.00627096 0.049876824, -0.00048606098 -0.084223911 0.049520239, -0.00048474967 -0.084001511 0.049495235, -0.00048731267 -0.084435314 0.049594402, -0.0846681 0.0062797368 0.050066516, -0.084741905 0.0062852204 0.050277874, -0.084766924 0.0062870383 0.050500274, -0.00048837066 -0.084624901 0.049713388, -0.08422111 0.00048333406 0.049525112, -0.08399871 0.00048206747 0.049499899, -0.00048935413 -0.084783196 0.049871802, -0.00049003959 -0.084902465 0.05006133, -0.084432393 0.00048454106 0.049598977, -0.00049062073 -0.085001379 0.050495133, -0.00049036741 -0.084976405 0.050272673, -0.084622175 0.00048570335 0.049718261, 0.0052625239 -0.084060818 0.049520463, -0.084780514 0.00048647821 0.049876675, 0.0052485615 -0.083838746 0.049495384, -0.08489953 0.00048722327 0.050066262, 0.0052757263 -0.084271803 0.049594283, -0.084973529 0.00048772991 0.050277501, -0.084998652 0.00048783422 0.050499916, 0.0052876621 -0.084461197 0.049713418, -0.084058002 -0.0052653104 0.049524784, -0.083835959 -0.0052513331 0.049499616, 0.005297482 -0.084618896 0.049871817, -0.084268883 -0.005278483 0.049598724, 0.0053049624 -0.084738031 0.050061464, 0.0053112209 -0.084836826 0.050495192, 0.0053094923 -0.084811777 0.050272688, -0.084458143 -0.0052903593 0.049717948, -0.08461608 -0.005300194 0.049876258, 0.010986522 -0.083505899 0.049520373, 0.010957628 -0.083285078 0.049495295, -0.084735066 -0.0053076744 0.05006586, 0.011014074 -0.08371526 0.049594313, -0.084808871 -0.0053122044 0.050277069, -0.08483386 -0.0053139329 0.050499812, 0.011038825 -0.083903268 0.049713373, -0.083502874 -0.010989442 0.049524456, 0.011059552 -0.084060162 0.049871698, -0.083282232 -0.010960355 0.049499288, -0.083712444 -0.01101695 0.04959856, 0.01107505 -0.084178448 0.050061554, 0.011084631 -0.084251657 0.050272733, -0.083900377 -0.011041626 0.04971756, 0.011088029 -0.084276691 0.050495237, 0.016659364 -0.082561314 0.04952018, 0.016615286 -0.082343191 0.049495384, -0.084057465 -0.011062369 0.049875915, -0.084175497 -0.011077911 0.050065503, 0.016701266 -0.082768649 0.049594358, -0.084248826 -0.011087492 0.050276995, -0.084273621 -0.011090755 0.050499529, -0.082558423 -0.016662255 0.049524263, 0.016738668 -0.082954407 0.049713463, 0.016769975 -0.083109483 0.049871728, -0.082340345 -0.016618252 0.04949908, -0.082765654 -0.016703948 0.049598038, 0.016793534 -0.083226413 0.050061375, 0.016808227 -0.083298832 0.050272927, -0.082951486 -0.016741589 0.049717516, 0.016813233 -0.083323404 0.050495237, 0.022254527 -0.081231996 0.049520493, -0.083106741 -0.016772777 0.049875572, 0.022195771 -0.081017464 0.049495369, -0.083223552 -0.01679638 0.050065234, 0.022310361 -0.0814358 0.049594551, -0.083295971 -0.016811103 0.050276622, 0.022360548 -0.081618741 0.049713582, -0.083320752 -0.016815871 0.050499126, -0.081229106 -0.022257283 0.049523905, 0.022402346 -0.081771463 0.049871787, -0.081014529 -0.022198439 0.049498692, -0.081432953 -0.022313252 0.049597889, 0.022433713 -0.081886351 0.050061628, 0.022459999 -0.081981838 0.050495386, 0.022453398 -0.081957906 0.050272971, -0.081615821 -0.022363365 0.049716964, 0.027745917 -0.079523817 0.049520507, -0.081768557 -0.022405162 0.04987517, 0.027672604 -0.079313844 0.049495429, -0.081883311 -0.022436589 0.050064847, 0.027815595 -0.079723462 0.049594492, -0.081954703 -0.022456288 0.050276145, 0.027878031 -0.079902619 0.049713597, -0.081979126 -0.022462606 0.050498769, -0.07952106 -0.027748778 0.049523607, 0.02793026 -0.080051959 0.049871922, -0.079311028 -0.02767542 0.049498245, -0.079720616 -0.027818516 0.049597591, 0.02796945 -0.080164447 0.050061643, -0.079899579 -0.027880907 0.049716607, 0.028002128 -0.080258086 0.050495386, 0.027993903 -0.080234379 0.050272942, -0.080049306 -0.027932927 0.049874917, 0.033107966 -0.07744512 0.04952082, 0.033020601 -0.077240512 0.049495429, 0.03319113 -0.077639386 0.049594596, -0.080161676 -0.027972221 0.050064713, -0.08025524 -0.028004751 0.05049859, -0.080231547 -0.027996615 0.050275996, 0.033265531 -0.077813789 0.049713701, -0.077442318 -0.033110738 0.049523234, -0.077237666 -0.033023313 0.049498066, 0.033327952 -0.077959388 0.049872145, -0.077636465 -0.033193931 0.049597234, 0.033374667 -0.078069001 0.050061747, 0.033413559 -0.078160033 0.05049561, 0.033403799 -0.078137055 0.050272971, -0.077811033 -0.033268332 0.049716398, 0.038315669 -0.075005308 0.049520895, -0.077956513 -0.0333305 0.049874544, 0.038214549 -0.074807167 0.049495772, 0.038411722 -0.075193495 0.049594715, -0.078066021 -0.033377364 0.050064221, -0.078157008 -0.033416405 0.050498143, -0.078134164 -0.033406571 0.050275669, 0.038497999 -0.075362235 0.049713969, -0.075002223 -0.038318425 0.049522877, -0.074804127 -0.038217172 0.049497753, 0.038570046 -0.075503245 0.049872294, 0.047111899 0.071944356 0.063620031, 0.051812083 0.068644151 -0.063612163, 0.047111809 0.071951404 -0.063611954, 0.051812232 0.068636835 0.063619852, -0.063109621 0.058419034 0.063619301, -0.059066564 0.062510893 -0.06361261, -0.063109517 0.058426052 -0.063612819, -0.059066638 0.062503755 0.063619614, 0.042201132 0.074930221 0.06362012, 0.042200848 0.074937508 -0.06361185, -0.066870838 0.054073259 0.063619018, -0.066870913 0.054080352 -0.063612923, 0.037101656 0.077581808 0.063620478, 0.03710179 0.077588886 -0.063611746, 0.084072709 -0.01810877 0.063615009, 0.082675636 -0.023676515 -0.063617393, 0.084072694 -0.018101588 -0.063616991, 0.08267571 -0.023683622 0.063614681, -0.070333421 0.049485877 0.063618779, -0.070333526 0.049493149 -0.063613176, 0.031836838 0.0798866 0.063620538, 0.031836554 0.079893813 -0.063611507, 0.085094333 -0.0124529 0.063615412, 0.085094228 -0.012445748 -0.063616768, -0.073481873 0.0446776 0.063618585, -0.073481902 0.044684857 -0.063613534, 0.026429504 0.081834719 0.063620538, 0.0264294 0.081841782 -0.063611493, 0.085735783 -0.0067413002 0.063615754, 0.085735798 -0.006734252 -0.063616574, -0.07630235 0.039669976 0.063618317, -0.076302275 0.039677113 -0.063613847, 0.020904303 0.083417222 0.063620687, 0.020904213 0.083424404 -0.063611418, 0.085994393 -0.00099995732 0.063616082, 0.085994318 -0.00099274516 -0.063616112, -0.078781635 0.034484819 0.063618019, -0.078781739 0.034491971 -0.0636141, 0.01528573 0.084627092 0.063620776, 0.01528573 0.084634274 -0.063611284, 0.08586888 0.0047461838 0.063616186, 0.085868701 0.0047534406 -0.063615739, -0.080909327 0.029145777 0.063617676, -0.080909297 0.029152825 -0.063614473, 0.0095989108 0.085459068 0.063620806, -0.082675517 0.02367641 0.063617364, -0.082675651 0.023683816 -0.063614666, 0.0095989108 0.085466295 -0.063611209, 0.085359767 0.010471046 0.063616663, 0.085359856 0.010478169 -0.063615426, 0.0038691759 0.085909352 0.063620806, 0.0038691461 0.085916623 -0.06361118, 0.084469646 0.016149163 0.063617021, 0.084469557 0.016156107 -0.063615084, -0.0018776655 0.08597599 0.063620865, -0.0018777251 0.085983068 -0.063611299, 0.083202109 0.021754801 0.063617319, 0.083202049 0.021761984 -0.063614741, -0.0076163709 0.085658506 0.06362085, -0.0076164156 0.085665777 -0.063611269, 0.081562951 0.027263597 0.063617468, 0.081562981 0.027270645 -0.063614488, -0.013320982 0.084958553 0.063620806, -0.013320923 0.084965572 -0.063611284, 0.079559699 0.032650426 0.063617796, 0.079559684 0.032657713 -0.063614309, -0.018966109 0.083878979 0.06362085, -0.018966213 0.083886117 -0.063611358, 0.07720077 0.037891611 0.063618332, 0.07720086 0.037898749 -0.063614026, -0.024526447 0.082424805 0.063620597, -0.024526536 0.082432047 -0.063611433, 0.074497432 0.042963281 0.063618332, 0.074497342 0.042970657 -0.063613653, -0.029977292 0.080602661 0.063620552, -0.029977262 0.080609724 -0.063611463, 0.071461052 0.047843173 0.063618571, 0.071461201 0.047850505 -0.063613325, -0.035294235 0.078420311 0.063620508, -0.035294369 0.078427643 -0.063611642, 0.068105578 0.052509621 0.063618898, 0.068105549 0.052516639 -0.063613147, -0.040453613 0.075887784 0.063620448, -0.040453598 0.075894952 -0.063611761, 0.064446151 0.056941137 0.063619226, 0.064446151 0.056948349 -0.063612834, -0.045432329 0.073016435 0.06362012, -0.045432329 0.073023424 -0.063612029, 0.060498774 0.061118528 0.063619435, 0.060498714 0.061125606 -0.06361264, -0.050208136 0.069819018 0.063620165, -0.050208002 0.069825932 -0.063612074, 0.056281149 0.065023035 0.063619673, 0.056281045 0.065030009 -0.063612387, -0.054759443 0.066309318 0.063619718, -0.054759547 0.066316426 -0.063612208, 0.062317178 -0.016602263 -0.035786122, 0.053191245 -0.01523222 -0.051925063, 0.053399742 -0.014047131 -0.051852241, 0.062108666 -0.017787203 -0.035858765, 0.062271699 -0.01541698 -0.035572335, 0.053354442 -0.012861937 -0.051638708, 0.06197466 -0.014300033 -0.035230011, 0.053057313 -0.011745006 -0.051296189, 0.061443657 -0.013316393 -0.034778655, 0.052526221 -0.01076141 -0.050845027, 0.060709417 -0.012523472 -0.034245238, 0.051791981 -0.0099684745 -0.050311223, 0.059814453 -0.011967212 -0.033659905, 0.050897151 -0.0094121993 -0.049726039, 0.058811054 -0.011679709 -0.033057228, 0.049893543 -0.0091246963 -0.049123332, 0.057757109 -0.011678025 -0.032471925, 0.048839703 -0.0091230869 -0.048538178, 0.056714416 -0.01196219 -0.031938314, 0.047796831 -0.009407118 -0.048004523, 0.055743068 -0.012515292 -0.031487197, 0.046825647 -0.0099602938 -0.047553465, 0.054899856 -0.013305753 -0.031144843, 0.045982584 -0.010750696 -0.047211066, 0.054233715 -0.014287367 -0.030931205, 0.04531619 -0.01173234 -0.046997488, 0.044865802 -0.012847871 -0.046924874, 0.053783238 -0.015402958 -0.030858666, 0.068046659 -0.018389732 -0.029523745, 0.065124348 -0.018651173 -0.034425691, 0.065407112 -0.017111868 -0.03433767, 0.067821935 -0.019424036 -0.029565498, 0.068132997 -0.017345428 -0.029404238, 0.065383524 -0.01556614 -0.034078836, 0.068073854 -0.016306564 -0.029217914, 0.06794779 -0.015606195 -0.029054657, 0.06505464 -0.014091268 -0.033661768, 0.067757428 -0.014933094 -0.028862119, 0.067233294 -0.013756439 -0.02842465, 0.064437106 -0.012761489 -0.033107445, 0.066515103 -0.01273559 -0.027903333, 0.063561678 -0.011643335 -0.032443777, 0.065623447 -0.011898309 -0.027308598, 0.062472478 -0.010792837 -0.031703979, 0.064601213 -0.011284545 -0.026665419, 0.061223924 -0.010252669 -0.030925095, 0.063354835 -0.010888055 -0.025917217, 0.059878916 -0.01004988 -0.030146301, 0.061910838 -0.010822341 -0.025089428, 0.058504492 -0.010194957 -0.029406622, 0.060480773 -0.011148736 -0.024310037, 0.057169825 -0.010680273 -0.02874288, 0.059862494 -0.011428684 -0.023957968, 0.059281722 -0.011798695 -0.023582369, 0.05594188 -0.011481524 -0.028188735, 0.05825384 -0.012611285 -0.023140937, 0.054882109 -0.012558579 -0.027771816, 0.057372108 -0.013624609 -0.022812679, 0.054043695 -0.013857439 -0.027513102, 0.05667147 -0.01479958 -0.022610724, 0.053468615 -0.015313059 -0.027425602, 0.056178927 -0.016089633 -0.022542343, 0.055551007 -0.012240916 -0.029714882, 0.057021633 -0.011281222 -0.030378565, 0.054380968 -0.013645574 -0.029288843, 0.064583719 -0.017438635 -0.034743756, 0.063882604 -0.01636675 -0.034995452, 0.053893924 -0.014377072 -0.028323635, 0.063633576 -0.014555618 -0.034569129, 0.062893987 -0.012963042 -0.033905178, 0.061736062 -0.011745021 -0.033068791, 0.060273275 -0.011020571 -0.03214173, 0.05864875 -0.010860801 -0.031214744, 0.036990792 0.064934149 0.047110796, 0.037313133 0.06465216 0.046967506, 0.037148505 0.065211117 0.047571927, 0.0025649071 0.0740785 0.045616716, 0.001719743 0.07397759 0.044504136, 0.0071154535 0.073654652 0.044504106, 0.034961462 0.066792697 0.047965139, 0.036395758 0.066471875 0.048333853, 0.035454333 0.067428067 0.048634917, -0.0027414262 0.07783629 0.049378991, 0.0027334988 0.078950137 0.049504369, -0.0027806461 0.078948215 0.049504369, 0.034901679 0.067600936 0.048563331, 0.0026951134 0.07783787 0.049379021, -0.0027042329 0.07678014 0.049009055, 0.034457982 0.067152157 0.04805389, 0.0026584566 0.076781899 0.049009174, 0.033797026 0.06793794 0.048412979, -0.0026708543 0.075832888 0.048413396, 0.0026255846 0.075834468 0.048413396, 0.034251511 0.066955596 0.047765225, 0.034742117 0.066524222 0.047572136, -0.0026429594 0.075041637 0.047621548, 0.0025982857 0.075043306 0.047621757, 0.033982515 0.067047045 0.04771781, 0.033444405 0.067229018 0.04762125, 0.033179075 0.066695869 0.04667303, -0.0026090741 0.074076831 0.045616657, -0.003684938 0.073905721 0.044504136, 0.034120888 0.066392213 0.046967655, 0.033014417 0.06636475 0.045616329, -0.0081645846 0.077455491 0.049379036, -0.0082812309 0.078562051 0.049504355, 0.034594446 0.066241875 0.047110856, 0.031962305 0.070071533 0.049095124, 0.031471163 0.068940029 0.048333973, 0.033005208 0.068660036 0.048635095, 0.03263852 0.070318252 0.049281895, 0.031831741 0.071083024 0.049378723, -0.0080536902 0.076404765 0.0490091, 0.031629503 0.069953755 0.048981458, 0.032301307 0.067742884 0.047572076, -0.0079543889 0.07546182 0.048413351, 0.033269644 0.068418741 0.0485636, 0.031241626 0.069906443 0.048874944, -0.0078712106 0.074674323 0.047621623, 0.030475467 0.06981954 0.048635006, 0.030257165 0.070619136 0.049008816, 0.032502174 0.067199498 0.046967775, -0.0077702105 0.07371442 0.045616671, -0.0078089535 0.074082211 0.046673641, -0.009070158 0.073439524 0.044504136, 0.032164365 0.067455247 0.047110736, 0.030013263 0.069157496 0.047965229, 0.029899031 0.069957361 0.048563629, -0.015163511 0.0763942 0.049379036, -0.013741374 0.077792868 0.049504295, -0.01913473 0.076644748 0.049504206, -0.013547897 0.07669726 0.049378991, 0.029484987 0.069479316 0.048054069, 0.02874741 0.070223719 0.048413247, -0.014957756 0.075357571 0.0490091, -0.013363957 0.075656533 0.049009144, 0.029291421 0.069269046 0.047765285, 0.029805571 0.068877354 0.047572315, 0.029010057 0.069343537 0.047717959, 0.028447598 0.069490999 0.047621429, 0.028221995 0.068939626 0.046673328, -0.014773279 0.074427873 0.048413441, -0.013199329 0.074723274 0.048413306, 0.029191703 0.068702161 0.046967685, 0.02967906 0.068584979 0.047110856, 0.028081834 0.068597704 0.045616239, -0.014619231 0.073651269 0.047621652, -0.013061464 0.073943466 0.047621652, -0.0089792013 0.075968429 0.048834413, -0.018865138 0.075565428 0.049378783, -0.0093823671 0.075297639 0.048413336, -0.009465009 0.07416214 0.047164366, -0.0089353323 0.074331105 0.047320783, -0.014503181 0.073067188 0.046673462, -0.010693997 0.074322686 0.047621593, -0.012957841 0.073356986 0.046673506, -0.0094388127 0.075751364 0.048737928, -0.018609226 0.074540123 0.049009085, -0.014431268 0.072704449 0.045616671, -0.0144068 0.07258147 0.044504151, -0.012893468 0.072992936 0.045616731, -0.020699739 0.075083524 0.049378932, -0.024434805 0.07512334 0.04950422, -0.012504041 0.075468481 0.048834354, -0.018379629 0.073620439 0.048413187, -0.012004495 0.074924335 0.048413262, -0.012047648 0.07378675 0.047164112, -0.012383908 0.073834747 0.047320738, -0.020418882 0.074064866 0.049008951, -0.012076914 0.075375974 0.048737854, -0.0092347264 0.073545322 0.045616746, -0.010993183 0.073303103 0.045616612, -0.018187761 0.072852105 0.047621682, -0.0084281862 0.073642135 0.045616642, -0.0094308257 0.073893249 0.046673581, -0.010828584 0.073701411 0.046673581, -0.012004018 0.073519111 0.046673641, -0.020166904 0.073150888 0.048413292, -0.060771659 0.044039041 0.047570899, -0.061586455 0.044841647 0.048633754, -0.062118798 0.043411583 0.048332483, -0.061281025 0.045086175 0.048562214, -0.060038716 0.045097098 0.047619939, -0.018043607 0.072274312 0.046673432, -0.060194016 0.044147223 0.046966329, -0.059562594 0.04473941 0.046671927, -0.05926691 0.044517547 0.045615092, -0.019956678 0.072387785 0.047621667, -0.060513258 0.043851867 0.047109589, -0.017953992 0.071915582 0.045616686, -0.019666731 0.071336299 0.044503972, -0.024090707 0.074065343 0.049378797, -0.019798189 0.071813509 0.046673343, -0.06233941 0.041790113 0.047570884, -0.063183218 0.042562559 0.04863359, -0.063403636 0.042049021 0.048561975, -0.063170686 0.04059428 0.047619805, -0.023763746 0.073060438 0.04900901, -0.019700021 0.071457207 0.045616671, -0.062272266 0.041164041 0.046966255, -0.062074825 0.04161267 0.047109514, -0.062669531 0.040272355 0.046671718, -0.023470521 0.072158918 0.048413247, -0.062358245 0.040072292 0.045614794, -0.063817024 0.039496928 0.047570735, -0.064394116 0.04051584 0.048561931, -0.064673811 0.040261611 0.048633486, -0.065108135 0.038784772 0.048332408, -0.026125401 0.0733722 0.049378872, -0.029615879 0.073235869 0.049504101, -0.063251302 0.039643079 0.04696624, -0.023225695 0.071406007 0.047621518, -0.063545927 0.039329171 0.047109455, -0.025771022 0.072376803 0.049008921, -0.065479532 0.037365034 0.047963426, -0.066101149 0.037872702 0.048633248, -0.066290468 0.037332609 0.048561782, -0.023041338 0.07083948 0.046673357, -0.025453031 0.071483716 0.048413187, -0.022926927 0.070487738 0.045616433, -0.02482143 0.06971024 0.044503927, -0.06566757 0.036662489 0.047763437, -0.065217212 0.037139848 0.047570452, -0.025187463 0.070737839 0.04762134, -0.066660956 0.03625299 0.048411086, -0.065767422 0.036399797 0.047716051, -0.065965459 0.035874754 0.047619462, -0.06544216 0.03559041 0.046671376, -0.029198766 0.072204381 0.049378663, -0.024987698 0.070176736 0.046673372, -0.065106481 0.036516517 0.046965867, -0.064940184 0.036982179 0.047109097, -0.065117046 0.035413578 0.045614406, -0.028802454 0.071224689 0.049008802, -0.066523775 0.034745261 0.047570378, -0.067421198 0.035469696 0.048633143, -0.067753434 0.03395313 0.048332229, -0.067167267 0.035731703 0.048561633, -0.065972269 0.034928128 0.046965867, -0.024863631 0.069828361 0.045616537, -0.028447092 0.070345849 0.048413202, -0.066241294 0.03459774 0.047109231, -0.031411916 0.071269542 0.049378678, -0.034652531 0.070991576 0.04950422, -0.02815038 0.069611877 0.04762122, -0.068022862 0.032506198 0.047963291, -0.068671793 0.03298375 0.048633069, -0.068827167 0.032418922 0.048561513, -0.030985683 0.070302397 0.049008727, -0.068363518 0.031989753 0.048052028, -0.027926952 0.069059759 0.046673179, -0.069129601 0.031290442 0.048410907, -0.03060323 0.069434941 0.048413038, -0.068160266 0.031789854 0.047763273, -0.067748517 0.032292366 0.047570243, -0.02778843 0.068716839 0.045616552, -0.029844135 0.06771259 0.044503897, -0.068243504 0.031514466 0.047715828, -0.06840834 0.030964002 0.047619268, -0.067865729 0.030718371 0.046671033, -0.034164429 0.069991723 0.049378723, -0.067594707 0.031674743 0.046965718, -0.06752871 0.030565843 0.045614213, -0.030283958 0.068710491 0.047621518, -0.067460805 0.032155365 0.047108978, -0.071179986 0.02941528 0.049092576, -0.069814086 0.030491501 0.048632786, -0.071449757 0.030084297 0.0492796, -0.070040748 0.028942183 0.048331991, -0.033700824 0.069042072 0.049008578, -0.072177052 0.029269919 0.049376264, -0.071050584 0.029085875 0.048979118, -0.030043721 0.068165615 0.046673313, -0.068877548 0.029808834 0.047570065, -0.033285081 0.068190128 0.048412994, -0.069585338 0.0307585 0.048561424, -0.070991337 0.02869463 0.048872679, -0.071668521 0.027683899 0.049006373, -0.070881337 0.027921438 0.048632801, -0.02989468 0.067827269 0.045616448, -0.068342403 0.030027464 0.046965495, -0.074876621 0.021443516 0.049375758, -0.074243739 0.026994631 0.049501583, -0.075946152 0.021749794 0.049501151, -0.036530674 0.068786502 0.049378619, -0.039520398 0.068401262 0.049503729, -0.068585113 0.029682502 0.047108844, -0.032937825 0.067478597 0.047621295, -0.070206016 0.027475163 0.04796277, -0.071000367 0.027334034 0.048561186, -0.036034912 0.067853168 0.049008578, -0.032676488 0.066943526 0.046673402, -0.070508495 0.026935518 0.04805167, -0.071229503 0.026160762 0.048410654, -0.035590261 0.067015842 0.048412755, -0.032514259 0.066610992 0.045616329, -0.070291638 0.026748598 0.04776302, -0.069920242 0.027273506 0.047569975, 0.076190218 -0.016173884 0.049373701, 0.075946301 -0.021755487 0.049498588, 0.07727851 -0.016404763 0.049499005, 0.074876681 -0.021449283 0.049373537, -0.034707263 0.065353543 0.044503495, -0.038963839 0.067438036 0.049378648, 0.075156465 -0.015954286 0.049003974, -0.03521882 0.066316634 0.047621146, -0.070357382 0.026461557 0.047715455, -0.070486173 0.025887668 0.047618747, -0.069927081 0.025682524 0.046670824, 0.07386063 -0.021158114 0.049003616, -0.069723561 0.026664495 0.04696548, -0.069580108 0.02555494 0.045614034, 0.074229106 -0.015757352 0.048408166, -0.038435131 0.066523135 0.049008489, 0.072949409 -0.020896912 0.048407868, -0.069623515 0.027157754 0.04710862, 0.045151979 0.059932575 0.047555357, 0.044772536 0.059514448 0.046635151, 0.046030134 0.058872834 0.047110468, -0.034939542 0.065790698 0.046673134, 0.045643121 0.06049718 0.048333615, 0.044036269 0.060772732 0.047571778, 0.0438492 0.060514957 0.047110587, 0.046226501 0.059124023 0.047571659, 0.073454708 -0.015593007 0.047616616, 0.072188243 -0.020679057 0.047616258, 0.045612365 0.058421731 0.045595586, 0.046654791 0.057598695 0.045615852, 0.046315193 0.058541551 0.046967089, -0.037960783 0.0657022 0.048412874, 0.072871894 -0.015469223 0.0466685, 0.046575814 0.05750145 0.044503301, 0.04344815 0.060048684 0.045595706, 0.071615592 -0.020514786 0.046668246, 0.043409944 0.060726941 0.046967238, 0.042325705 0.06085062 0.04561606, 0.072510183 -0.015392378 0.045611531, 0.07126002 -0.020412892 0.045611337, 0.071139514 -0.020378426 0.044498757, -0.034766078 0.065464079 0.045616254, 0.04225415 0.060747743 0.04450345, 0.072437122 -0.015131176 0.044499055, 0.040671676 0.063058823 0.047555596, 0.041798443 0.062333107 0.047571957, 0.041128099 0.063652828 0.048333883, 0.039724618 0.064074397 0.047964901, -0.041454509 0.065936342 0.049378514, -0.044195816 0.065477893 0.049503624, 0.040316105 0.06261906 0.04663536, 0.041621 0.062068403 0.047110528, 0.039493948 0.063817963 0.047571898, 0.077132702 -0.010819599 0.049374074, 0.078234687 -0.010974303 0.049499229, 0.039326221 0.063547015 0.047110677, 0.041229695 0.061592937 0.045595795, 0.041925639 0.061761171 0.046967357, -0.037564769 0.065016553 0.047620952, 0.076086283 -0.010672837 0.049004182, 0.038952619 0.063057646 0.045595855, 0.037770808 0.06377773 0.04561618, 0.037706971 0.063670009 0.04450351, -0.04089196 0.065041736 0.049008444, 0.038868874 0.063728988 0.046967536, 0.035975814 0.065850854 0.047555685, 0.07514742 -0.010541067 0.048408419, 0.035645276 0.065390706 0.046635538, -0.037266791 0.064500913 0.046673059, 0.074363276 -0.010431275 0.047616825, 0.036627263 0.064436123 0.045595884, -0.040387392 0.064239144 0.04841277, 0.034249544 0.065730691 0.045595914, 0.032958448 0.066252768 0.044503689, 0.07377328 -0.010348246 0.046668783, -0.037081853 0.064180657 0.04561609, 0.031089246 0.068293765 0.047555864, 0.073407173 -0.010296971 0.045612052, 0.030784935 0.06781441 0.046635777, -0.039385349 0.062645718 0.044503495, 0.07334815 -0.0098033398 0.044499427, -0.04357329 0.064555839 0.049378216, 0.077699348 -0.0054126531 0.049374312, 0.031829953 0.066935778 0.045596004, -0.039966092 0.063568845 0.047621056, 0.078809291 -0.0054901689 0.049499586, 0.02936402 0.068053573 0.045596093, 0.076645106 -0.0053392947 0.049004495, 0.0280343 0.068481565 0.044503808, -0.042981967 0.063679814 0.049008399, -0.0095535517 0.077296674 0.049378961, -0.010790825 0.076066285 0.049009085, 0.07569924 -0.0052733868 0.048408821, -0.039649114 0.063064739 0.046672881, -0.010939598 0.077483431 0.049448505, -0.042451829 0.062894136 0.048412785, 0.074909508 -0.0052183419 0.047616974, -0.012245446 0.076915935 0.049378976, -0.03945221 0.06275174 0.045616001, -0.010732263 0.075117126 0.048413381, 0.07431528 -0.0051769018 0.046669006, -0.042008877 0.062237903 0.047621042, 0.073946342 -0.0051513165 0.045612201, 0.073867768 -0.0044229925 0.04449971, -0.061539307 0.042937696 0.047554493, -0.061110005 0.042569846 0.046634212, 0.077887595 2.0489097e-05 0.049374536, -0.046157137 0.06273438 0.049378246, -0.048655912 0.062235609 0.049503446, -0.060049906 0.043447331 0.045594782, -0.059166417 0.044442266 0.044502482, 0.079000026 2.0742416e-05 0.04949984, 0.076830611 2.0220876e-05 0.049004748, -0.041675642 0.061744228 0.04667294, -0.061596841 0.041225314 0.045594618, -0.062253043 0.040004656 0.044502348, -0.04553093 0.061883256 0.049008235, -0.064500213 0.03834635 0.047554255, -0.064050004 0.038003325 0.046634078, 0.075882718 1.9907951e-05 0.04840903, -0.063059077 0.038951814 0.045594603, -0.04146859 0.061437756 0.045616165, -0.043853402 0.059603691 0.044503331, 0.075091034 1.9684434e-05 0.047617391, -0.064439595 0.036622852 0.045594379, -0.065007046 0.03535378 0.044501901, -0.044969007 0.061119795 0.048412636, 0.074495226 1.9654632e-05 0.046669349, -0.06711936 0.033551916 0.047553957, -0.066649482 0.033234552 0.046633899, 0.074125558 1.9475818e-05 0.045612648, 0.073993549 0.00098071992 0.044500023, -0.047970667 0.061359182 0.049378276, 0.077696249 0.0054535568 0.049374864, -0.044499874 0.0604821 0.047620922, -0.065732285 0.034248993 0.045594066, 0.078806102 0.0055314153 0.049500212, -0.066939265 0.031825498 0.045594066, -0.067414671 0.030514255 0.044501826, 0.076641813 0.0053795874 0.049005091, -0.047319621 0.060526371 0.04900828, -0.069382772 0.02857995 0.047553524, -0.044146806 0.060002252 0.046672851, -0.068894431 0.028289154 0.046633556, 0.075696319 0.0053130537 0.048409298, -0.068055123 0.029363468 0.045593843, -0.046735734 0.05977948 0.048412547, -0.069082364 0.02685833 0.045593858, -0.069462344 0.025511816 0.044501424, 0.074906468 0.0052576959 0.047617838, -0.04392767 0.059704363 0.04561606, -0.046248198 0.059155911 0.047620803, 0.073943317 0.0051902682 0.045612767, 0.074312195 0.0052160919 0.046669558, 0.073724389 0.0063793361 0.044500366, -0.050613642 0.059197843 0.049378052, -0.052878767 0.058689803 0.049503237, 0.07712613 0.010860175 0.049375311, 0.078227907 0.011015117 0.0495006, -0.045881376 0.058686733 0.046672657, 0.076079816 0.010712713 0.049005285, -0.049926847 0.058394611 0.049008071, 0.076900065 0.012360528 0.049375266, 0.077268943 0.016445249 0.049500883, -0.045653641 0.058395252 0.045615897, 0.075140908 0.010580555 0.0484097, -0.048087537 0.056243524 0.044503242, -0.052134037 0.057863295 0.049377874, 0.075856552 0.01219289 0.049005568, -0.049310535 0.057673901 0.048412517, 0.074356973 0.010470226 0.047618046, -0.051426739 0.057077989 0.049007967, 0.074920535 0.012042373 0.04840976, -0.048796177 0.057072341 0.047620624, -0.050792158 0.05637385 0.048412308, 0.07413885 0.011916742 0.047618136, -0.048409075 0.056619629 0.046672612, 0.073401019 0.010335684 0.04561317, 0.073767111 0.010387167 0.046669915, 0.073061809 0.011743739 0.044500589, -0.050262243 0.055785626 0.04762058, 0.076180518 0.01621367 0.049375564, 0.073550835 0.011822149 0.046670064, -0.048168838 0.056338757 0.045615628, -0.054799944 0.055345416 0.049377739, -0.056844145 0.054858133 0.049503073, 0.075146869 0.015993714 0.049005896, -0.049863547 0.055343285 0.046672478, 0.073185518 0.011763647 0.045613259, 0.075792238 0.017940968 0.049375713, -0.054056317 0.054594412 0.049007952, 0.075933188 0.021795169 0.04950121, 0.074219763 0.015796334 0.048409909, -0.04961589 0.055068493 0.045615599, -0.052064821 0.052583307 0.044502914, 0.074763939 0.017697558 0.049005747, -0.05604361 0.054085642 0.049377739, 0.07344538 0.015631467 0.047618359, -0.053389236 0.053920791 0.048412204, 0.073841631 0.017478943 0.048410058, -0.055283263 0.05335176 0.049008101, 0.07286267 0.015507579 0.046670318, -0.052832291 0.053358227 0.04762052, 0.073071077 0.017296702 0.047618508, -0.054601029 0.052693546 0.048412159, 0.072501004 0.015430555 0.045613348, -0.052413136 0.052935019 0.04667227, 0.072009549 0.017045647 0.044500917, 0.074863806 0.02148819 0.049375772, -0.054031432 0.052143604 0.047620416, 0.072491303 0.017159656 0.046670228, -0.052153125 0.052672237 0.045615494, 0.073848084 0.021196723 0.049005896, -0.058693856 0.051197603 0.049377367, -0.060532779 0.050759375 0.04950285, 0.07213144 0.017074496 0.045613259, -0.053602889 0.051730201 0.046672419, 0.074280515 0.023425549 0.049375951, 0.07422772 0.027038947 0.049501538, -0.057897404 0.050502911 0.049007624, 0.072936922 0.020935103 0.048410118, -0.053336784 0.051473305 0.04561539, 0.073272556 0.023107663 0.049006104, -0.055764213 0.048642337 0.04450275, -0.059680134 0.050044373 0.049377456, 0.072175756 0.020716727 0.047618598, -0.057182953 0.049879774 0.048412055, 0.072368309 0.022822663 0.048410356, -0.058870435 0.049365416 0.04900746, 0.071603298 0.020552456 0.046670675, -0.056586429 0.049359411 0.047620177, -0.058143854 0.048756212 0.048411787, 0.071613371 0.022584423 0.047618628, 0.07124792 0.020450398 0.045613647, 0.070572942 0.022256389 0.044501185, -0.056137621 0.048967808 0.046672195, 0.073182315 0.026658073 0.049376249, -0.057537377 0.048247516 0.047620207, -0.055858925 0.0487248 0.04561536, 0.07104528 0.022405192 0.046670645, 0.072189391 0.026296422 0.049006373, -0.05708088 0.047864914 0.046672031, -0.06227459 0.046776623 0.049377322, -0.06392628 0.046413273 0.049502581, 0.070692599 0.022294044 0.045613855, -0.056797594 0.04762736 0.045615241, 0.071298659 0.025971949 0.048410565, -0.061429679 0.046142012 0.049007371, 0.072372019 0.028785199 0.049376339, 0.072160617 0.032150954 0.049501657, 0.070554823 0.025700942 0.047618926, -0.060671628 0.045572534 0.048411623, 0.071390092 0.02839461 0.049006462, 0.069994971 0.025497109 0.046670854, 0.070509151 0.028044194 0.048410743, 0.06964758 0.025370657 0.045613855, 0.068759933 0.027348533 0.044501513, 0.06977354 0.02775161 0.047618926, 0.071144253 0.031698167 0.049376488, 0.069220021 0.0275314 0.046670854, 0.070178911 0.03126812 0.049006492, 0.06887649 0.027394861 0.045614123, 0.069312871 0.030882239 0.048410833, 0.070077553 0.033991158 0.049376547, 0.069741771 0.037106127 0.049501956, 0.068589807 0.030560017 0.047619075, 0.069126651 0.033529907 0.049006641, 0.068045586 0.030317754 0.046670943, 0.068273738 0.033116192 0.048410952, 0.067707911 0.030167133 0.045614243, 0.066579863 0.03229481 0.044501752, 0.068759575 0.036583662 0.049376667, 0.067561567 0.032770708 0.047619313, 0.067826644 0.036087424 0.049006879, 0.067025468 0.032510847 0.046671271, 0.066989779 0.035641879 0.048411131, 0.066692829 0.032349512 0.045614362, 0.067409202 0.039015785 0.049376905, 0.066983372 0.041880921 0.049502224, 0.066290736 0.035270318 0.047619492, -0.07311143 0.026851967 0.049376115, 0.066494599 0.038486451 0.049006999, -0.07211931 0.026487559 0.049006343, -0.073860645 0.02115263 0.04900603, 0.065764934 0.034990445 0.04667142, 0.065674081 0.038011521 0.04841122, -0.072949275 0.020891577 0.048410431, 0.06543839 0.034816697 0.0456146, 0.064044863 0.037068576 0.04450202, 0.066039935 0.041290939 0.049377054, -0.072188273 0.020673618 0.047618702, 0.064988777 0.037614956 0.04761973, -0.071615353 0.02050966 0.046670645, 0.065143958 0.04073067 0.049007207, -0.07126011 0.020407856 0.045613706, -0.071139425 0.020373374 0.044501156, 0.073440209 -0.010058418 0.045611933, 0.064473376 0.037316471 0.04667148, 0.073970616 -0.0047908872 0.04561235, 0.064340144 0.040228084 0.048411489, 0.074123591 0.00050100684 0.045612559, 0.064153343 0.037131429 0.04561463, 0.073898792 0.0057901591 0.045612767, 0.048480153 0.060957268 0.049378127, 0.049022585 0.060521871 0.049378067, 0.048618704 0.062264562 0.049503416, 0.064381406 0.043832242 0.049377233, 0.063898593 0.046451226 0.049502552, 0.048357546 0.059700698 0.049008071, 0.063668862 0.039808452 0.047619581, 0.046947449 0.061692208 0.049281329, 0.046221465 0.062686995 0.049378216, 0.04415673 0.065504193 0.049503803, 0.063507676 0.043237433 0.049007237, 0.044473886 0.063938767 0.049378127, 0.044005573 0.064262122 0.049378127, 0.063163772 0.039492726 0.046671659, 0.04387036 0.063071236 0.049008459, 0.062724024 0.042704016 0.048411459, 0.042389005 0.064908475 0.049281508, 0.062850133 0.039296851 0.045614779, 0.041629136 0.065826386 0.049378395, 0.039479762 0.068424895 0.049503803, 0.061168045 0.041644573 0.044502199, 0.062998712 0.04579705 0.049377203, 0.039687783 0.06701456 0.049378455, 0.039306372 0.067239091 0.049378425, 0.039149225 0.066105366 0.049008429, 0.062069654 0.042258412 0.047619909, 0.037611067 0.067789033 0.049281716, 0.062143758 0.045175672 0.049007386, 0.036824256 0.068629652 0.049378484, 0.034610152 0.071012169 0.049504101, 0.034689963 0.06973277 0.049378455, 0.061577231 0.041923299 0.046671748, 0.034406543 0.069873065 0.049378693, 0.034219056 0.068786711 0.049008638, 0.061376899 0.044618323 0.048411667, 0.061271578 0.04171513 0.045614868, 0.029572099 0.073253632 0.049504101, 0.029507101 0.072079033 0.049378663, 0.060736611 0.044152752 0.047619969, 0.0074269474 0.07374984 0.045616716, 0.0077262223 0.073718935 0.045616716, 0.0077649057 0.07408686 0.046673656, 0.0025776923 0.074448034 0.046673387, 0.061009645 0.048414946 0.049377412, 0.06050241 0.050795496 0.04950276, 0.0021438003 0.074091956 0.045616716, 0.060254857 0.043802515 0.046671838, -0.0026220977 0.074446455 0.046673656, -0.0031501949 0.074055821 0.045616657, 0.06018199 0.047757894 0.049007565, 0.059955612 0.043585211 0.045614988, 0.057964668 0.045998544 0.044502467, 0.059439331 0.047168657 0.048411787, -0.062652305 0.046269521 0.049377203, 0.059650391 0.050079957 0.049377531, 0.0588191 0.046676576 0.047620147, -0.063344076 0.044694185 0.049280405, -0.064300582 0.043950409 0.049377263, -0.067008287 0.041840911 0.049502254, -0.065523222 0.042106137 0.049376979, 0.05884093 0.049400732 0.049007595, -0.065795377 0.041679665 0.049377084, -0.064634204 0.041534826 0.049007118, 0.05835259 0.046306312 0.046671927, -0.066394478 0.040023074 0.049280137, 0.058114946 0.048790962 0.048411906, -0.067273676 0.039248928 0.049376875, -0.069763869 0.037064463 0.04950206, -0.068422124 0.037210912 0.049376741, 0.058062822 0.04607664 0.045615107, -0.068602532 0.036877036 0.04937683, -0.067493677 0.036705971 0.049006924, 0.057508588 0.048282057 0.047620118, -0.06910114 0.035144642 0.049279898, 0.057312757 0.052739158 0.04937762, 0.056811512 0.054892167 0.049503028, -0.069903672 0.034347102 0.049376637, -0.072179735 0.032107994 0.049501806, -0.070956036 0.032117188 0.049376458, 0.057052329 0.047898844 0.046672195, -0.071060002 0.031886548 0.049376413, -0.069993213 0.031681284 0.04900673, 0.056535125 0.05202356 0.049007922, 0.056769162 0.04766123 0.045615256, 0.054452181 0.050107107 0.044502705, 0.07449469 0.00026161969 0.046669275, 0.056011409 0.054119065 0.04937765, 0.055837482 0.051381633 0.048411995, 0.07429038 0.005517602 0.046669826, 0.055251449 0.053384766 0.049007803, 0.047286063 0.059599251 0.048562884, 0.04726249 0.058348939 0.047620744, 0.047760874 0.058963954 0.048412383, 0.047047704 0.059917465 0.048634619, 0.055254877 0.050845459 0.047620296, 0.054569662 0.052725896 0.048412025, 0.054816604 0.0504421 0.046672314, 0.054000348 0.052175835 0.047620475, 0.044736654 0.062459767 0.04900834, 0.054544538 0.050191849 0.045615405, 0.044827789 0.061595932 0.048634648, 0.044328272 0.061830744 0.048563123, 0.053310037 0.056781858 0.049377948, 0.052843809 0.058721468 0.049503267, 0.04332912 0.062293068 0.048412502, 0.042877078 0.061643094 0.047620893, 0.053571969 0.05176197 0.046672434, 0.042832077 0.062876344 0.048563093, 0.042582393 0.063169032 0.048634648, 0.052586585 0.056011558 0.049007952, 0.053305924 0.051505163 0.045615464, 0.050649136 0.053948134 0.044502974, 0.052099556 0.057894334 0.049377799, 0.040111065 0.065526217 0.049008369, 0.05193767 0.055320427 0.048412144, 0.040246844 0.064681977 0.048634768, 0.051392764 0.057108849 0.049007982, 0.039719969 0.064887196 0.048563182, 0.038666278 0.065289602 0.048412859, 0.051395744 0.054743156 0.047620445, 0.038151681 0.065821335 0.048563331, 0.038262874 0.064608306 0.047621191, 0.050758481 0.056404069 0.048412353, 0.037893295 0.06608817 0.048634887, 0.050988048 0.054309025 0.046672463, 0.050229043 0.055815652 0.047620624, 0.050735116 0.054039285 0.045615584, 0.035276294 0.068250597 0.049008697, 0.049830467 0.055373013 0.046672434, 0.049583077 0.055098131 0.045615673, 0.046887577 0.057886004 0.046672642, 0.029106617 0.071101025 0.049008727, 0.0023660958 0.074455053 0.046673417, -0.0028939247 0.074436292 0.046673506, -0.0081397593 0.074046612 0.046673626, -0.064037487 0.042448744 0.049007207, -0.063836709 0.041022271 0.048411518, -0.066935062 0.037715375 0.049006984, 0.024166614 0.074040413 0.049378783, 0.024390042 0.075137988 0.049504131, 0.023838848 0.073035985 0.049008936, -0.069483057 0.032785222 0.049006775, 0.023544788 0.072134659 0.048413217, 0.023299098 0.07138215 0.047621489, 0.023114175 0.070815921 0.046673238, 0.022999376 0.070464432 0.045616418, 0.022960454 0.070345446 0.044503987, 0.018820047 0.075576708 0.049378991, 0.019089013 0.076656267 0.04950434, 0.018564761 0.07455121 0.049009055, 0.01833567 0.073631391 0.048413396, 0.018144429 0.072863027 0.047621667, 0.018000335 0.072285086 0.046673328, 0.017910987 0.071926311 0.045616627, 0.01776436 0.071833625 0.044503957, 0.013502091 0.076705426 0.049378961, 0.013695091 0.077801153 0.049504429, 0.013318926 0.075664535 0.049009115, 0.013154477 0.074730888 0.048413217, 0.013017446 0.073951274 0.047621697, 0.012914151 0.07336463 0.046673506, 0.042536885 0.061154217 0.04667294, 0.012849987 0.073000565 0.045616537, 0.012473077 0.07293877 0.044504046, 0.008118242 0.077460349 0.049379021, 0.0082342625 0.078566968 0.049504369, 0.0080082119 0.076409444 0.049009085, 0.0079093277 0.075466484 0.048413515, 0.0078268647 0.074679151 0.047621548, 0.039030522 0.06428729 0.047764927, 0.03877452 0.064394802 0.047717631, 0.037959218 0.064096093 0.046673059, -0.03670384 -0.044261977 0.0064975172, -0.035962716 -0.044631109 0.0051566511, -0.036623746 -0.044165373 0.005384922, -0.042663231 -0.036903158 0.0033804029, -0.043212384 -0.035014331 0.0025888681, -0.043827459 -0.035512865 0.0033805221, -0.034771845 -0.045674115 0.0055202246, -0.053480893 -0.0037558675 0.0016251206, -0.053756908 -0.0030070245 0.0016830266, -0.054535091 -0.0038299561 0.0019948781, -0.037754491 -0.036481127 0.0014978349, -0.040548205 -0.035073698 0.0016233921, -0.038554519 -0.037254199 0.0016232133, -0.040790245 -0.033051565 0.0014980882, -0.039314419 -0.037988469 0.0019929111, -0.041347638 -0.035764962 0.0019930303, -0.052371085 -0.0036779493 0.0014996976, -0.053889751 -0.0026300251 0.0017157793, -0.044577599 -0.036120698 0.0053854138, -0.046046272 -0.033605263 0.0043285489, -0.046344906 -0.03382352 0.0053853244, -0.055499867 -0.0027608126 0.0025520325, -0.055261403 -0.0015154183 0.0023455173, -0.04429023 -0.035887897 0.0043285638, -0.05345799 -0.0014327168 0.0015963465, -0.052492261 0.00090043247 0.0014999956, -0.042064652 -0.036385432 0.0025886595, -0.042475954 -0.034417406 0.0019932538, -0.05560939 0.00095391273 0.0025908947, -0.054640323 0.00030270219 0.0019816905, -0.054661438 0.00093771517 0.0019952059, -0.055567339 -0.00033712387 0.002552107, -0.053604722 0.00091949105 0.001625374, -0.047556207 -0.032097995 0.0053856075, -0.046446189 -0.033897355 0.0064982027, -0.053953305 -0.00027696788 0.0017158538, -0.04908666 -0.029946089 0.0064982921, -0.045564875 -0.033254221 0.0033807158, -0.053840801 0.00012366474 0.0016830862, -0.041654676 -0.033752099 0.0016234517, -0.053814515 0.0016865134 0.0016831756, -0.047249466 -0.031891152 0.0043287426, -0.05391407 0.0020721853 0.0017159283, -0.055529922 0.0020728111 0.0025523901, -0.055183813 0.0032973289 0.0023456961, -0.044925481 -0.032787383 0.0025889724, -0.05221419 0.0054720491 0.0015002638, -0.05337961 0.0032290965 0.0015965104, -0.046755984 -0.031557843 0.0033807755, -0.055314481 0.0057967901 0.0025911182, -0.054406643 0.0050569177 0.0019820333, -0.054371595 0.0056980997 0.0019953996, -0.055386603 0.0044930428 0.0025524944, -0.053320512 0.0055878907 0.0016256571, -0.053772464 0.004422009 0.0017160624, -0.04415971 -0.032228306 0.0019933283, -0.053625301 0.0048126131 0.0016834885, -0.048979625 -0.029880717 0.0053857565, -0.053463131 0.0063672215 0.0016835034, -0.046099603 -0.031114951 0.0025890768, -0.043515772 -0.02937068 0.0014983714, -0.043306038 -0.031605467 0.0016236007, -0.053528711 0.0067583919 0.0017165095, -0.055139542 0.0068906099 0.0025526136, -0.054687753 0.0080850273 0.0023459792, -0.051538482 0.010001913 0.0015004426, -0.052895457 0.0078659803 0.0015967786, -0.048664019 -0.029688075 0.0043290406, -0.054598749 0.010595903 0.0025911629, -0.053760141 0.0097726882 0.0019822717, -0.053668141 0.010415286 0.0019956976, -0.054786474 0.009289071 0.0025527179, -0.045313925 -0.030584365 0.0019933879, -0.053183258 0.0090871453 0.0017165244, -0.048155442 -0.029377803 0.0033809245, -0.052630678 0.010213763 0.0016260594, -0.053002462 0.0094651282 0.001683712, -0.050172612 -0.027831152 0.0053858608, -0.051391974 -0.02579017 0.006498456, -0.044437975 -0.029993162 0.0016235709, -0.04747957 -0.028965503 0.0025892556, -0.049849361 -0.027651593 0.0043288916, -0.046670333 -0.028471649 0.0019935519, -0.049328253 -0.027362689 0.0033808202, -0.051279902 -0.025733933 0.0053859055, -0.045768142 -0.027921319 0.0016236603, -0.045909956 -0.025466487 0.0014984608, -0.048635945 -0.026978567 0.0025892109, -0.05094941 -0.025567994 0.0043291301, -0.047806978 -0.026518643 0.0019936413, -0.050416857 -0.025301054 0.0033810139, -0.052407339 -0.02335231 0.0053860694, -0.053346053 -0.021458343 0.006498754, -0.046882913 -0.026005983 0.0016238987, -0.04970929 -0.024945721 0.0025894344, -0.052069679 -0.023201779 0.0043292642, -0.048861951 -0.024520442 0.0019936115, -0.053229704 -0.021411523 0.0053860843, -0.051525429 -0.022959352 0.0033813268, -0.047917575 -0.024046391 0.0016240925, -0.047954753 -0.021368042 0.0014987439, -0.052886665 -0.0212733 0.004329443, -0.050802261 -0.022637099 0.002589494, -0.052334115 -0.0210509 0.0033811927, -0.049936295 -0.022251129 0.0019940138, -0.054243162 -0.018695921 0.0053863823, -0.054935902 -0.016979501 0.0064990222, -0.051599607 -0.02075541 0.0025895536, -0.048971057 -0.021820977 0.0016241223, -0.05389367 -0.018575296 0.0043296069, -0.050720066 -0.020401582 0.0019941181, -0.054816201 -0.016942471 0.0053864419, -0.053330481 -0.018381163 0.003381446, -0.049634635 -0.017107129 0.0014991015, -0.049739584 -0.020007193 0.001624167, -0.05446291 -0.016833201 0.0043295175, -0.052581966 -0.018123239 0.0025900155, -0.05389379 -0.016657367 0.0033816099, -0.051685631 -0.017814234 0.0019939393, -0.055666283 -0.013897091 0.0053867102, -0.056150451 -0.0123851 0.0064992756, -0.053137481 -0.016423613 0.0025898665, -0.050686434 -0.017469883 0.0016242862, -0.055307388 -0.01380749 0.0043297112, -0.056396142 0.011213556 0.0065006167, -0.055156708 0.015797824 0.0053882152, -0.055277392 0.015832245 0.0065008849, -0.052231282 -0.01614356 0.0019941032, -0.056028008 -0.012358114 0.0053867847, -0.054729551 -0.013663352 0.0033817887, -0.051221818 -0.01583153 0.0016244203, -0.050936624 -0.012716204 0.0014993548, -0.055666968 -0.012278229 0.004330039, -0.053961366 -0.013471335 0.002589941, 0.055156842 -0.015798375 0.0053865463, 0.05366382 -0.020299345 0.005386129, 0.055277348 -0.01583302 0.0064990371, -0.055085152 -0.01214993 0.003381893, 0.053781107 -0.020343602 0.0064988881, -0.053041637 -0.013241798 0.0019943118, 0.054801255 -0.015696555 0.0043296069, 0.053318068 -0.02016829 0.004329294, 0.052760884 -0.019957691 0.0033813417, -0.054311961 -0.011979476 0.0025901198, 0.054228663 -0.015532523 0.0033815652, -0.056665599 -0.0089926571 0.0053867549, 0.053467557 -0.0153144 0.0025898665, 0.052020326 -0.01967755 0.002589643, -0.0569814 -0.0077058375 0.0064994246, -0.052016094 -0.012985796 0.0016245693, 0.051133633 -0.01934202 0.0019939542, 0.052556112 -0.015053421 0.001994282, -0.05338636 -0.011775106 0.0019944757, 0.051804259 -0.024661571 0.0053859949, -0.056300461 -0.0089344531 0.0043300539, 0.051917389 -0.024715543 0.0064985603, 0.05014503 -0.018968046 0.001624167, 0.049018681 -0.018799827 0.0014988929, 0.050470591 -0.014455989 0.0014991313, 0.05154036 -0.014762402 0.0016244799, 0.051470414 -0.024502486 0.0043292195, -0.056857109 -0.0076888651 0.0053869933, -0.051851109 -0.0082284212 0.0014994144, -0.052354291 -0.011547431 0.0016245991, -0.055711985 -0.008841306 0.0033819526, 0.050932541 -0.024246395 0.003381297, -0.056490466 -0.0076394826 0.0043302327, 0.050217688 -0.023906067 0.0025894642, -0.054929957 -0.0087171495 0.0025903583, 0.049361736 -0.02349858 0.0019937605, -0.055900544 -0.007559523 0.0033821315, 0.049590901 -0.028855324 0.0053858161, 0.049699157 -0.028918192 0.0064982921, -0.053993702 -0.0085685253 0.0019945502, 0.048407525 -0.023044243 0.001624018, 0.047193661 -0.023000628 0.0014986992, 0.049271166 -0.028669208 0.0043288916, -0.055115744 -0.0074534416 0.0025903732, -0.057233647 -0.0040197521 0.005387187, 0.048756331 -0.028369576 0.0033808947, -0.057422996 -0.0029740632 0.0064997971, -0.052950233 -0.0084027648 0.0016250014, 0.0480721 -0.027971387 0.0025891662, -0.054176331 -0.0073262602 0.0019946098, 0.047252521 -0.02749455 0.0019936413, -0.056864992 -0.0039937645 0.0043304712, -0.053128868 -0.0071847588 0.0016247034, 0.046339154 -0.02696301 0.001623705, 0.045009404 -0.027026296 0.0014984459, -0.056270614 -0.0039518774 0.0033822954, -0.055480778 -0.0038964748 0.0025906116, 0.044165105 -0.036624029 0.0053853393, 0.04331243 -0.037628621 0.0053853244, 0.044261634 -0.036704078 0.0064978451, 0.041079596 -0.040233776 0.0064975917, 0.043033376 -0.037385881 0.0043285191, 0.043880478 -0.03638804 0.0043286234, 0.042583674 -0.036995247 0.0033803731, 0.043421909 -0.036007762 0.0033805668, 0.042812452 -0.035502329 0.0025887638, 0.041985944 -0.036476031 0.0025888681, 0.040989906 -0.040146172 0.0053851455, 0.041270301 -0.035854131 0.0019931048, 0.042082742 -0.034896985 0.0019931942, -0.056323662 0.0109303 0.0053879917, 0.040725678 -0.039887175 0.004328385, -0.055960789 0.010859951 0.0043313503, -0.054801241 0.015696049 0.0043314546, 0.039868176 -0.041260421 0.0053850263, 0.037616715 -0.043488815 0.0064974874, 0.039632633 -0.034431323 0.0014980286, 0.040472433 -0.035160959 0.0016231835, 0.041269287 -0.034222409 0.0016233027, -0.055375919 0.010746494 0.0033829659, -0.054228559 0.015531942 0.0033833981, 0.040300161 -0.039470449 0.0033801645, -0.053467542 0.015314028 0.002591759, 0.03961122 -0.040994331 0.0043282658, 0.039734498 -0.038916469 0.0025886744, -0.052556083 0.015053228 0.001995936, 0.039197206 -0.040565819 0.0033802241, -0.051540166 0.014762193 0.0016260594, -0.050470635 0.014455691 0.0015009046, 0.039057285 -0.038252994 0.0019929558, 0.046152398 -0.027281612 0.0016237646, 0.037534773 -0.04339388 0.0053848922, 0.038647175 -0.039996505 0.0025884658, 0.045754626 -0.028630197 0.0017205179, 0.043954417 -0.030697539 0.0016236156, 0.044985473 -0.02916564 0.0016235858, 0.042482615 -0.030846104 0.0014983267, 0.036480889 -0.037754461 0.0014978498, 0.038302243 -0.037513584 0.0016232282, 0.04367049 -0.031100169 0.0016236156, 0.044820726 -0.031302661 0.0019933432, 0.037292838 -0.043114185 0.0043282062, 0.037988305 -0.039314613 0.0019929707, 0.043184623 -0.032376975 0.0017202944, 0.042348012 -0.032878056 0.0016232729, 0.036120489 -0.044577941 0.0053849518, 0.033897027 -0.046446592 0.0064971, 0.036903113 -0.04266353 0.0033801496, 0.0039934516 -0.056865036 0.0043275058, 0.0034933984 -0.057268485 0.0053841919, 0.0040194094 -0.057233915 0.0053841621, 0.0029737502 -0.057423487 0.0064968318, 0.037253976 -0.038554683 0.0016230941, 0.0019985884 -0.057243332 0.0050229877, 0.035887644 -0.044290632 0.0043281466, 0.00099223852 -0.057366535 0.0053841323, 0.036385223 -0.042064711 0.0025883466, 0.00033338368 -0.057374001 0.0053841472, -0.0017783791 -0.057472825 0.0064968169, -0.00098416209 -0.057366461 0.0053842217, 0.035512567 -0.043827727 0.0033800602, -0.0009778291 -0.056996778 0.004327327, -0.0013794601 -0.057358444 0.0053840876, 0.035764888 -0.041347623 0.0019927919, -0.0029104352 -0.057204112 0.0050229132, 0.033823043 -0.046345219 0.0053847432, -0.0038798451 -0.05724369 0.0053840876, -0.0065183491 -0.057129651 0.0064966679, 0.035014093 -0.043212578 0.0025884062, -0.0045806915 -0.05719173 0.0053840578, -0.0059802681 -0.057062358 0.0053841472, 0.035073563 -0.040548369 0.0016229749, -0.0062421709 -0.057034567 0.0053840131, 0.03305158 -0.040790394 0.0014975965, -0.0059416145 -0.056694612 0.0043274313, -0.0077981204 -0.056744948 0.0050230026, 0.033605158 -0.046046406 0.0043278635, 0.034417287 -0.042476013 0.0019927174, -0.0087241381 -0.056707919 0.0053841323, -0.01121372 -0.056396469 0.0064968318, 0.032097712 -0.04755646 0.0053847432, -0.0094614327 -0.056589469 0.0053840876, -0.010930672 -0.056324065 0.0053841025, 0.029945701 -0.049087167 0.006497249, 0.033253968 -0.045565352 0.0033800006, -0.026962817 -0.046339199 0.0016225725, -0.027281478 -0.046152368 0.0016228706, -0.027494416 -0.0472527 0.0019924194, -0.027026102 -0.045009539 0.0014974773, -0.028630137 -0.045754746 0.0017194897, 0.033752009 -0.041654885 0.0016229004, -0.029165447 -0.044985458 0.0016228408, 0.031890869 -0.047249943 0.0043279231, -0.030846044 -0.042482674 0.0014976412, -0.030697495 -0.043954372 0.0016230047, 0.032787174 -0.04492569 0.0025883168, -0.03109999 -0.043670446 0.0016227961, -0.031302437 -0.04482092 0.0019925684, 0.031557709 -0.046756074 0.0033798814, -0.032376796 -0.043184727 0.0017195642, -0.034431189 -0.039632738 0.0014978498, -0.032877997 -0.042348102 0.0016229004, 0.032228217 -0.04415983 0.0019925535, -0.034222171 -0.041269451 0.0016230941, -0.057268232 -0.0034937263 0.005387187, 0.029880419 -0.048980162 0.0053846091, 0.031114712 -0.046099976 0.0025881678, -0.057242915 -0.0019988269 0.0050260574, 0.02937074 -0.043515787 0.0014975071, 0.031605318 -0.043306321 0.0016228706, -0.057365939 -0.00099259615 0.0053873956, 0.029687762 -0.048664242 0.0043279082, -0.057373479 -0.0003336817 0.0053872764, -0.057472512 0.0017781109 0.0064999908, -0.057366103 0.00098380446 0.0053874701, -0.056996435 0.00097750127 0.0043305904, -0.057358071 0.0013790131 0.0053875148, 0.03058435 -0.045313969 0.001992479, 0.029377699 -0.048155755 0.0033798218, -0.057203844 0.0029102415 0.0050264746, 0.027830854 -0.050173074 0.0053845197, 0.025789961 -0.051392436 0.0064971745, -0.057243228 0.0038796067 0.0053874701, -0.057129249 0.0065178871 0.0065003484, 0.029993013 -0.044437975 0.0016227812, -0.057191491 0.0045805871 0.0053875744, -0.057062149 0.0059799701 0.005387634, -0.05703406 0.0062419176 0.0053878129, -0.056694314 0.0059415102 0.0043310076, 0.028965294 -0.047479838 0.0025881231, -0.056744561 0.0077980906 0.0050265789, 0.027651444 -0.049849659 0.0043278188, 0.028471589 -0.046670422 0.0019923896, -0.056707531 0.008723855 0.005387947, -0.056589201 0.0094608814 0.0053879321, 0.027362466 -0.049328595 0.0033795983, 0.047598809 -0.028383121 0.0024386644, 0.025733709 -0.05128023 0.0053845197, 0.047358602 -0.028584927 0.0023671538, 0.025466248 -0.045910105 0.0014975071, 0.027921155 -0.045768306 0.001622811, 0.026978463 -0.048636168 0.0025880039, 0.047048092 -0.029842064 0.0026680976, 0.046136856 -0.030517682 0.0023670793, 0.02556774 -0.050949708 0.0043277293, 0.04624711 -0.032298937 0.0033805817, 0.045963004 -0.030962259 0.0024384558, 0.04559803 -0.031845629 0.0025889724, 0.026518509 -0.047807053 0.0019923598, 0.045353189 -0.030526087 0.0019933879, 0.025300533 -0.05041723 0.0033796728, 0.045075864 -0.032239869 0.0024383217, 0.023351997 -0.052407697 0.0053845048, 0.044811562 -0.032432497 0.0023668706, 0.021457925 -0.053346515 0.0064969063, 0.026005939 -0.046882868 0.0016228259, 0.024945557 -0.049709678 0.0025879741, 0.044405863 -0.033647969 0.0026679337, 0.043433145 -0.034256712 0.0023667514, 0.023201644 -0.052069858 0.0043275803, 0.043231428 -0.034674004 0.0024381727, 0.024520367 -0.048862487 0.0019923598, 0.042638287 -0.034215927 0.0019931644, 0.021411031 -0.053230211 0.0053844303, 0.003896296 -0.055480897 0.0025877953, 0.0032998025 -0.056463614 0.003578037, 0.0039518028 -0.056270972 0.003379494, 0.022959039 -0.051525697 0.0033796132, 0.0029722452 -0.056553364 0.00368011, 0.024046376 -0.0479175 0.0016226023, 0.021368012 -0.047954902 0.0014972985, 0.00066700578 -0.057103738 0.0045544952, 0.021273062 -0.052887067 0.0043276399, 0.0016494691 -0.056306392 0.0032829195, 0.022636756 -0.050802529 0.0025880933, 0.00011326373 -0.057154536 0.0046699643, 0.02105093 -0.052334324 0.0033795387, 0.00050498545 -0.056918606 0.0041605234, 0.022251025 -0.049936473 0.00199233, 4.0233135e-06 -0.057005167 0.0043273419, 0.00050246716 -0.056629226 0.0036800355, 0.018695638 -0.054243565 0.0053842962, -0.0003233403 -0.057004184 0.0043273717, 0.016979441 -0.05493626 0.0064967573, -0.0009675473 -0.056401148 0.0033792853, 1.1235476e-05 -0.056559861 0.0035780519, -0.00095409155 -0.055609494 0.0025876015, 0.020755336 -0.051599801 0.0025880039, -0.0016049892 -0.056537136 0.0035780817, 0.021820888 -0.048971161 0.0016224682, 0.018575057 -0.053893834 0.0043275952, -0.0019248873 -0.056598738 0.0036800802, -0.0042397976 -0.056950137 0.0045545995, 0.020401552 -0.050720185 0.0019921213, 0.016942292 -0.05481647 0.0053842813, -0.0047956556 -0.056953177 0.0046700388, 0.018381104 -0.05333057 0.0033794791, -0.0032355189 -0.056237474 0.0032828152, 0.017107308 -0.04963474 0.0014972091, 0.020007148 -0.049739748 0.0016225576, -0.0044140816 -0.056749493 0.0041604936, -0.004899025 -0.056794256 0.0043274313, 0.016833112 -0.054463074 0.0043275207, 0.018123016 -0.05258216 0.0025879145, -0.0043916702 -0.056461006 0.0036800355, -0.0052468181 -0.056763291 0.0043273866, -0.0058795959 -0.056102216 0.0033794343, 0.016657174 -0.053893909 0.0033794791, -0.0048895925 -0.05634822 0.0035780519, 0.01781404 -0.051685795 0.0019920915, -0.0057970881 -0.055314735 0.0025876164, -0.0064977556 -0.056185544 0.0035780668, 0.013896897 -0.055666596 0.0053843707, 0.012384787 -0.05615066 0.006496653, -0.0068073124 -0.056220859 0.0036801547, 0.01642327 -0.053137556 0.0025877655, -0.0091153234 -0.056375459 0.0045546591, 0.01746954 -0.050686598 0.0016224235, -0.0096694082 -0.056330696 0.0046700537, -0.0080961734 -0.055745631 0.0032828152, 0.013807356 -0.055307731 0.004327476, 0.016143367 -0.05223158 0.0019921213, -0.0093004405 -0.056155786 0.0041605085, -0.0097659677 -0.056162298 0.0043275207, 0.012357682 -0.056028217 0.0053841919, 0.013662994 -0.054729775 0.0033793896, -0.00925304 -0.055870369 0.0036801994, -0.010131076 -0.056097671 0.0043274313, -0.010860443 -0.055960998 0.0043274164, -0.010746881 -0.055376112 0.0033793896, 0.01583147 -0.051222071 0.0016225129, -0.0097535104 -0.05571264 0.0035780668, -0.010595948 -0.054598942 0.0025877804, 0.012716159 -0.050936908 0.0014971495, 0.01227814 -0.055667207 0.0043274462, -0.028382868 -0.047598839 0.0024375767, -0.027971148 -0.048072055 0.0025879741, -0.028369382 -0.048756406 0.0033798218, 0.01347132 -0.053961694 0.00258784, -0.028584838 -0.047358632 0.0023660362, 0.012149706 -0.055085346 0.0033794492, -0.02984193 -0.047048107 0.0026672184, 0.013241515 -0.053041652 0.0019922405, 0.011979207 -0.054312289 0.0025876909, -0.030517444 -0.04613696 0.0023661256, -0.031845406 -0.045598164 0.0025882572, -0.03096199 -0.045963138 0.0024376214, 0.0089922994 -0.056665897 0.005384177, -0.032298639 -0.046247333 0.0033798665, -0.030525938 -0.045353442 0.0019925088, 0.0077055097 -0.056981653 0.0064967871, 0.012985781 -0.052016541 0.0016223341, -0.03223972 -0.045076042 0.0024376661, 0.011775091 -0.05338648 0.0019920766, -0.032432407 -0.044811457 0.0023661852, 0.0089344382 -0.05630067 0.0043273419, -0.033647731 -0.044405878 0.0026672035, 0.0076886714 -0.056857452 0.0053841621, -0.034256563 -0.04343307 0.0023664385, 0.011547446 -0.05235444 0.0016222894, 0.0082283467 -0.051851317 0.001497075, 0.0088410676 -0.055712342 0.0033794045, -0.036007479 -0.043422073 0.0033802986, -0.03467381 -0.043231592 0.0024378151, -0.035501987 -0.042812675 0.0025883913, -0.034896836 -0.042082772 0.0019927472, -0.034215853 -0.042638391 0.0019927919, 0.0076392591 -0.056490973 0.0043273568, -0.05646342 -0.0032999367 0.0035810024, 0.0087169856 -0.054930285 0.0025876164, -0.056553245 -0.0029724389 0.0036832392, 0.0075594038 -0.055900559 0.0033793747, -0.0571035 -0.00066716969 0.0045577884, 0.0085684061 -0.05399397 0.001992166, -0.056306094 -0.0016496778 0.0032859147, 0.0074532628 -0.055116147 0.0025876611, -0.057154268 -0.00011360645 0.0046733022, -0.056918472 -0.00050522387 0.0041635782, -0.057004943 -4.1723251e-06 0.0043307096, 0.0084027797 -0.052950323 0.0016223341, -0.056628957 -0.00050269067 0.0036832541, -0.05700396 0.00032301247 0.0043305755, 0.0073262304 -0.054176331 0.0019919723, -0.056400985 0.00096750259 0.0033825934, -0.056559771 -1.1205673e-05 0.0035811812, -0.056536824 0.0016046613 0.0035813153, 0.0071846247 -0.053129196 0.0016223043, 0.0036779493 -0.052371189 0.0014969707, -0.056598395 0.0019244105 0.0036835223, -0.056949779 0.0042395443 0.0045581013, 0.0038298666 -0.05453521 0.0019921511, -0.05695273 0.0047954619 0.0046735406, -0.056237146 0.0032351315 0.0032862872, 0.003755793 -0.053480998 0.0016223937, -0.056749195 0.0044140071 0.0041640252, -0.056793988 0.0048989356 0.0043307245, -0.056460604 0.0043915808 0.0036836267, -0.056762904 0.0052466094 0.0043309778, -0.056101874 0.0058792531 0.0033828765, -0.056347772 0.004889518 0.0035814345, -0.05618529 0.0064975917 0.0035817325, -0.056220531 0.0068071336 0.0036837906, -0.056375265 0.0091149658 0.0045583695, -0.056330368 0.0096691102 0.0046736449, -0.055745512 0.008096084 0.0032863915, -0.056155592 0.0093001723 0.0041642189, -0.05616203 0.0097657889 0.0043312311, -0.055870116 0.0092530847 0.00368388, -0.056097284 0.010130972 0.0043313056, -0.055712566 0.0097534806 0.003581807, 0.048237428 -0.029317454 0.0034298748, 0.047780171 -0.030443519 0.0037160367, 0.046984747 -0.031285673 0.0034297556, 0.046735466 -0.03264007 0.0043287277, 0.045643255 -0.033212334 0.0034295768, 0.045097098 -0.034292862 0.0037160367, -0.015798047 -0.055157155 0.0053843856, 0.044231787 -0.035070226 0.0034294575, -0.015832633 -0.055277675 0.0064969361, 0.0027606487 -0.055500224 0.0025491565, 0.001515463 -0.055261597 0.0023425072, -0.015696228 -0.054801449 0.0043275058, -0.015532345 -0.054228768 0.0033794343, 0.00033707917 -0.055567682 0.0025491565, -0.015314221 -0.05346781 0.0025878996, -0.00093771517 -0.054661527 0.0019919574, -0.0020729601 -0.055529907 0.0025490671, -0.015053228 -0.052556232 0.0019921064, -0.01041545 -0.05366832 0.0019922107, -0.0032974631 -0.055183828 0.002342388, -0.020298973 -0.053664178 0.0053842515, -0.020343333 -0.05378145 0.0064969659, -0.0044930726 -0.055386782 0.0025492162, -0.0144559 -0.050470755 0.0014970303, -0.014762297 -0.051540241 0.0016224235, -0.010001957 -0.051538542 0.0014971942, -0.010214061 -0.052630827 0.0016224235, -0.0056982934 -0.054371819 0.0019919574, -0.0068906546 -0.05513978 0.0025490373, -0.020167962 -0.053318292 0.0043275803, -0.019957468 -0.052761018 0.0033795685, -0.0080851167 -0.054687798 0.0023424327, -0.019677266 -0.052020401 0.0025879443, -0.0092892945 -0.054786727 0.0025490075, -0.019341812 -0.051133826 0.0019922704, -0.029317126 -0.048237622 0.0034286976, -0.028668776 -0.049271494 0.0043278784, -0.024661094 -0.051804572 0.0053843707, -0.024714917 -0.051917925 0.0064971, -0.018799707 -0.049018696 0.001497224, -0.018967792 -0.050145358 0.001622498, -0.030443251 -0.047780335 0.0037150979, -0.032639757 -0.046735778 0.0043280572, -0.03128539 -0.046984971 0.0034288466, -0.024502218 -0.051470563 0.004327625, -0.03321211 -0.045643315 0.0034287423, -0.024246141 -0.050932705 0.0033795834, -0.023905933 -0.050217912 0.0025879592, -0.034292579 -0.045097336 0.0037152022, -0.035069853 -0.044231877 0.0034289807, -0.023498312 -0.049361825 0.0019923002, -0.036387637 -0.043880641 0.0043281764, -0.028854787 -0.049591124 0.0053845346, -0.028917864 -0.049699575 0.0064970404, -0.02304402 -0.04840745 0.0016224682, -0.023000374 -0.04719381 0.0014974028, 0.049149066 -0.029489353 0.0051574409, 0.048921704 -0.029801711 0.005044356, 0.048391029 -0.030879095 0.0055210888, 0.047141418 -0.032923698 0.0064980686, 0.04764837 -0.031798065 0.0050441921, 0.047449887 -0.032152116 0.0051572472, 0.047038615 -0.032851875 0.0053855777, 0.04654406 -0.033449918 0.0051572323, -0.037628219 -0.043312714 0.0053849965, -0.040233403 -0.041079804 0.0064976215, 0.04629074 -0.033743858 0.0050440282, 0.045673817 -0.034772426 0.0055208355, -0.037385732 -0.043033645 0.0043282062, 0.044856757 -0.035627887 0.0050441325, 0.044630751 -0.035963193 0.0051570982, -0.036995009 -0.042583898 0.0033800304, 0.00300695 -0.053756982 0.0016800165, 0.0026299059 -0.05388999 0.001712963, -0.036475778 -0.041986093 0.002588436, 0.0014325082 -0.053457975 0.0015932471, -0.00090062618 -0.052492365 0.0014971197, -0.040145636 -0.040990308 0.0053851604, -0.0003028065 -0.054640636 0.0019786805, -0.00091966987 -0.053604886 0.001622349, 0.00027677417 -0.053953439 0.0017129481, -0.035854056 -0.041270301 0.001992777, -0.00012367964 -0.053840876 0.0016800314, -0.039887041 -0.040725887 0.0043283552, -0.0016864836 -0.053814575 0.001680091, -0.041260034 -0.03986837 0.0053851008, -0.0020722151 -0.053914264 0.0017129034, -0.043488353 -0.037617028 0.0064978153, -0.035160884 -0.040472507 0.0016231686, -0.0054721087 -0.05221419 0.0014970452, -0.0032291263 -0.053379714 0.0015932769, -0.039470166 -0.040300265 0.0033803284, -0.0050569326 -0.054406956 0.0019786805, -0.0055882484 -0.053320706 0.0016222745, -0.040993974 -0.039611354 0.0043283403, -0.004422009 -0.053772554 0.0017128885, -0.0389162 -0.039734691 0.0025886446, -0.0048127174 -0.053625509 0.001680091, -0.0063673258 -0.053463191 0.0016800463, -0.040565535 -0.03919743 0.0033804476, -0.03825286 -0.039057419 0.001992777, -0.0067588389 -0.053529069 0.001712963, -0.043393493 -0.037534952 0.0053853244, -0.0078661293 -0.052895516 0.0015935451, -0.0097728223 -0.053760305 0.0019786358, -0.039996281 -0.038647383 0.0025886595, -0.0090872049 -0.053183421 0.0017129332, -0.037513301 -0.038302273 0.0016230941, -0.0094652027 -0.053002477 0.0016801506, -0.043113858 -0.037292913 0.0043285638, -0.029488802 -0.049149439 0.0051562041, -0.029801413 -0.048922032 0.0050434619, -0.030878603 -0.048391238 0.005520165, -0.032923236 -0.047141716 0.0064974427, -0.031797662 -0.047648713 0.005043447, -0.032851502 -0.047038913 0.0053847283, -0.032151565 -0.047450274 0.0051563829, -0.033449486 -0.046544418 0.0051564574, -0.033743486 -0.046291038 0.0050435662, -0.035627574 -0.044857055 0.0050434768, -0.032851458 -0.047038347 -0.0053901076, -0.033449471 -0.046543837 -0.0051617175, -0.032639787 -0.046735093 -0.0043332577, -0.041260019 -0.039867952 -0.0053896159, -0.043393508 -0.037534401 -0.0053895414, -0.040993989 -0.039610952 -0.0043329448, -0.043488294 -0.037616208 -0.0065020323, -0.043113902 -0.037292421 -0.0043328404, -0.03374359 -0.046290427 -0.0050486922, -0.033212081 -0.045643017 -0.0034341365, -0.041654781 -0.033751994 -0.0016272664, -0.044159785 -0.032228053 -0.0019969195, -0.043306217 -0.031605124 -0.0016271621, -0.042475894 -0.034417182 -0.0019970983, -0.034292415 -0.045097053 -0.0037203878, -0.03477183 -0.045673385 -0.0055254996, -0.036703646 -0.044261262 -0.006502524, -0.032923177 -0.04714106 -0.0065026879, -0.042663261 -0.036902934 -0.0033846349, -0.044290304 -0.035887405 -0.0043325871, -0.043827593 -0.035512358 -0.0033845305, -0.035627589 -0.044856578 -0.005048573, -0.035070017 -0.044231564 -0.0034340918, -0.04443793 -0.029993072 -0.0016270131, -0.043515831 -0.029370636 -0.0015015751, -0.036387578 -0.043880284 -0.0043330789, -0.035962746 -0.044630438 -0.0051615983, -0.036623597 -0.044164911 -0.0053898692, -0.043212518 -0.035014018 -0.0025928319, -0.04492566 -0.032786936 -0.0025926232, -0.053480893 -0.0037557483 -0.0016256422, -0.053756773 -0.0030070543 -0.0016832799, -0.052371114 -0.0036778599 -0.0015003234, -0.054535076 -0.0038297325 -0.0019954741, -0.046446189 -0.033896521 -0.0065020472, -0.044577658 -0.036120206 -0.0053894818, -0.053889707 -0.0026298314 -0.0017161965, -0.055499807 -0.002760455 -0.0025524497, -0.045313835 -0.03058435 -0.0019968897, -0.055261433 -0.0015152544 -0.0023456812, -0.053458095 -0.0014324486 -0.0015963018, -0.045565084 -0.033253625 -0.0033845156, -0.05249235 0.00090049207 -0.001500085, -0.053953245 -0.00027674437 -0.0017160028, -0.046099588 -0.031114593 -0.0025926679, 0.055277333 -0.015832216 -0.0065009892, 0.053781077 -0.02034305 -0.0065012127, 0.055156812 -0.015797943 -0.005388245, -0.055567622 -0.00033685565 -0.0025524944, -0.053840771 0.00012388825 -0.0016832501, -0.046046138 -0.033604741 -0.004332453, -0.053604618 0.00091969967 -0.001625374, -0.054640517 0.00030308962 -0.0019818991, -0.055609465 0.00095412135 -0.0025907904, -0.054661334 0.00093789399 -0.0019950718, -0.045768127 -0.02792114 -0.001627028, -0.045909896 -0.025466174 -0.0015014261, -0.053814366 0.0016863793 -0.0016829222, -0.053913996 0.0020723343 -0.0017158985, -0.046755821 -0.031557456 -0.0033842772, -0.055183828 0.0032975674 -0.002345413, -0.055529743 0.0020730048 -0.0025523603, -0.046344966 -0.03382279 -0.0053893626, -0.05337958 0.0032291263 -0.0015963018, -0.052213937 0.0054721087 -0.0014997572, -0.046670318 -0.02847138 -0.0019967854, -0.053772479 0.0044220686 -0.001715824, -0.055386648 0.0044932812 -0.0025520474, -0.053625301 0.0048127621 -0.0016828626, -0.053320587 0.0055881143 -0.0016249865, -0.047249645 -0.031890675 -0.004332304, -0.054406703 0.0050572604 -0.0019814223, -0.054371789 0.005698517 -0.0019948184, -0.055314451 0.005797267 -0.0025906563, -0.047479659 -0.028965116 -0.0025924593, -0.053463012 0.0063673854 -0.0016829073, -0.046882793 -0.026005805 -0.0016267896, -0.053528786 0.0067588389 -0.0017157197, -0.055139557 0.0068907142 -0.0025518537, -0.049086571 -0.029945329 -0.0065017194, -0.047556087 -0.032097578 -0.0053892732, -0.054687724 0.0080852509 -0.0023452342, -0.052895397 0.0078662187 -0.0015959442, -0.048155501 -0.029377401 -0.003384158, -0.051538542 0.010002062 -0.0014995635, -0.053183332 0.0090872794 -0.0017156303, -0.047806948 -0.026518434 -0.0019964725, -0.054786429 0.0092893988 -0.0025516301, -0.053002313 0.0094652176 -0.0016827136, -0.052630693 0.010214001 -0.0016246885, -0.053668082 0.01041542 -0.0019946992, -0.053760186 0.0097729862 -0.001981318, -0.054598793 0.010596156 -0.0025902838, -0.048664033 -0.029687598 -0.0043324381, -0.04863593 -0.026978165 -0.0025923401, -0.047917485 -0.024046317 -0.0016266853, -0.047954932 -0.021368086 -0.0015011877, -0.04897964 -0.029880136 -0.0053890944, -0.049328372 -0.027362317 -0.0033840835, -0.04886204 -0.024520129 -0.0019965619, -0.049849302 -0.027651191 -0.0043322593, -0.049709395 -0.024945363 -0.0025923252, -0.048971027 -0.021820724 -0.001626581, -0.050172761 -0.027830571 -0.0053890347, -0.051391974 -0.025789484 -0.0065014064, -0.050416932 -0.025300652 -0.0033839792, -0.049936384 -0.022250861 -0.0019965172, -0.050949514 -0.025567576 -0.0043320954, -0.049739644 -0.020007163 -0.0016264021, -0.049634755 -0.017107233 -0.0015009642, -0.050802261 -0.022636801 -0.0025921166, -0.051279992 -0.025733382 -0.0053888708, -0.050720021 -0.020401478 -0.0019962639, -0.051525593 -0.022958815 -0.0033837855, -0.051599532 -0.020755157 -0.002592057, -0.0520695 -0.023201331 -0.0043319017, -0.05068624 -0.017469823 -0.0016262829, -0.05233407 -0.021050736 -0.0033836812, -0.052407369 -0.023351863 -0.0053888261, -0.053346127 -0.021457538 -0.0065012872, -0.051685661 -0.017813995 -0.0019962937, -0.052886859 -0.021272689 -0.0043318272, -0.051221773 -0.015831381 -0.0016262382, -0.050936788 -0.012716129 -0.0015008301, -0.052581981 -0.018122837 -0.0025918335, -0.053229839 -0.021410853 -0.0053885728, -0.052231461 -0.016143292 -0.0019961298, -0.053330272 -0.018380955 -0.0033835173, -0.053137466 -0.016423121 -0.0025917888, -0.053893581 -0.018574819 -0.0043317378, -0.052016169 -0.012985602 -0.0016260445, -0.053893834 -0.016657025 -0.0033834726, -0.054935992 -0.016978905 -0.0065008849, -0.054243326 -0.018695131 -0.0053886026, -0.053041562 -0.013241559 -0.0019958764, -0.05446291 -0.016832739 -0.0043315291, -0.052354246 -0.011547223 -0.0016259253, -0.051851228 -0.0082281977 -0.001500532, -0.053961411 -0.013471082 -0.00259161, -0.054816231 -0.016941994 -0.0053884238, -0.053386211 -0.011774808 -0.0019959211, -0.054729551 -0.01366283 -0.0033832639, -0.056396142 0.011214226 -0.0064994544, -0.055277258 0.015832946 -0.0064992011, -0.055156857 0.01579842 -0.0053864419, -0.054311946 -0.011979073 -0.0025916696, 0.051540241 -0.014762178 -0.0016261786, 0.050145179 -0.018967971 -0.001626417, 0.05047062 -0.01445578 -0.0015009344, -0.055307403 -0.013807029 -0.0043314099, 0.049018592 -0.018799618 -0.0015010536, 0.052556068 -0.015053093 -0.001996085, 0.051133558 -0.019341752 -0.0019961894, -0.055085197 -0.012149677 -0.0033832043, 0.052020162 -0.019677058 -0.002592057, -0.052950174 -0.0084025711 -0.0016257614, 0.053467527 -0.015314102 -0.0025917441, -0.055666193 -0.013896629 -0.0053881556, -0.056150481 -0.01238434 -0.0065006912, 0.054228663 -0.015532181 -0.0033833832, 0.05276075 -0.019957259 -0.0033836812, 0.05480133 -0.015695974 -0.0043314099, 0.053317994 -0.020167902 -0.0043317974, -0.055666864 -0.012277693 -0.0043313205, -0.053993687 -0.0085682422 -0.0019958466, 0.048407495 -0.02304399 -0.0016266406, 0.047193646 -0.02300036 -0.0015013665, 0.053663909 -0.020298734 -0.0053886026, -0.053128988 -0.0071846545 -0.0016257465, 0.049361587 -0.023498252 -0.0019964576, -0.056028068 -0.012357324 -0.0053881109, -0.054930046 -0.0087167025 -0.0025914162, 0.050217777 -0.023905724 -0.0025923699, -0.054176107 -0.0073262006 -0.0019955784, 0.050932541 -0.024246082 -0.0033839792, -0.055712059 -0.0088407844 -0.0033830851, 0.051470235 -0.024501979 -0.0043319613, -0.055115893 -0.0074531138 -0.0025911778, 0.046339199 -0.026962936 -0.0016269237, 0.045009464 -0.027026042 -0.0015016645, -0.056300297 -0.0089340657 -0.0043312162, 0.051804259 -0.02466096 -0.0053889304, 0.051917419 -0.024714723 -0.0065013915, -0.055900246 -0.0075592548 -0.0033830702, 0.04725261 -0.027494252 -0.0019968152, -0.0569814 -0.0077052116 -0.0065004826, -0.056665525 -0.0089921355 -0.0053880215, 0.048072159 -0.027971059 -0.0025924593, -0.056490749 -0.0076390356 -0.0043310374, 0.048756301 -0.028369039 -0.0033841282, 0.049271151 -0.028668702 -0.0043322742, -0.056857094 -0.007688418 -0.0053878576, -0.055480868 -0.003896296 -0.0025911182, 0.049590841 -0.028854638 -0.0053890795, 0.049699157 -0.028917596 -0.0065016747, -0.056270719 -0.0039514452 -0.0033827126, -0.056864992 -0.0039932132 -0.0043309331, -0.057422966 -0.002973333 -0.006500259, -0.057233781 -0.0040192008 -0.0053876638, 0.041269168 -0.034222305 -0.0016274601, 0.040472507 -0.035160899 -0.0016273558, 0.039632574 -0.034431204 -0.0015020072, 0.042082757 -0.034896806 -0.0019971132, 0.04127036 -0.035853818 -0.0019973069, 0.042812496 -0.035501868 -0.0025929213, 0.041985989 -0.036475644 -0.0025929958, 0.042583674 -0.036994949 -0.0033845901, 0.043421894 -0.036007181 -0.0033845603, 0.038302124 -0.037513301 -0.0016273707, 0.036480814 -0.037754416 -0.0015021414, -0.050470442 0.014455885 -0.001499176, -0.051540107 0.014762297 -0.0016244054, 0.043880507 -0.036387444 -0.004332751, 0.043033272 -0.037385479 -0.0043328553, -0.052556127 0.015053406 -0.001994282, 0.039057255 -0.038252831 -0.0019974262, 0.037254021 -0.038554683 -0.0016275346, -0.053467557 0.015314341 -0.0025900453, 0.041079462 -0.040233105 -0.0065023303, 0.04331252 -0.03762795 -0.005389601, 0.04426153 -0.036703259 -0.0065020472, 0.044165209 -0.036623433 -0.0053896457, 0.039734468 -0.038916126 -0.0025931001, -0.055375859 0.010746971 -0.0033819824, -0.054228559 0.015532449 -0.0033817291, 0.037988394 -0.039314419 -0.0019973218, -0.0559607 0.010860533 -0.0043300539, -0.054801226 0.015696555 -0.004329592, 0.040300161 -0.039470017 -0.0033847541, -0.056323543 0.010931015 -0.0053868443, 0.038647175 -0.039996251 -0.002593115, 0.046152294 -0.027281493 -0.0016268194, 0.045754775 -0.028630033 -0.0017236769, 0.040725663 -0.039886743 -0.0043330193, 0.044985518 -0.029165566 -0.0016269088, 0.035073534 -0.040548295 -0.0016276389, 0.033051506 -0.040790319 -0.0015022904, 0.042482629 -0.03084597 -0.0015018731, 0.043954283 -0.030697435 -0.0016271472, 0.039197236 -0.040565506 -0.0033849031, 0.043670505 -0.031099871 -0.0016272366, 0.04482083 -0.031302571 -0.0019969046, 0.04099001 -0.040145591 -0.0053897947, 0.043184683 -0.032376781 -0.0017240345, 0.035764888 -0.041347414 -0.0019976199, 0.042347878 -0.032877937 -0.0016271472, 0.039611191 -0.040993899 -0.0043329149, 0.0040194541 -0.057233378 -0.0053906739, 0.0034934282 -0.05726777 -0.0053907633, 0.0039934665 -0.056864634 -0.0043337792, 0.0029737353 -0.057422638 -0.0065032244, 0.033752009 -0.041654646 -0.001627773, 0.0019985586 -0.057242826 -0.005029425, 0.036385059 -0.042064384 -0.0025932938, 0.00099207461 -0.057365805 -0.005390808, 0.039868101 -0.041259706 -0.0053897947, 0.037616596 -0.043487936 -0.0065025091, 0.034417257 -0.04247573 -0.0019975603, -0.00098405778 -0.057365969 -0.0053906888, 0.00033333898 -0.057373464 -0.0053907037, -0.0017783195 -0.057472095 -0.0065034032, -0.0013792962 -0.057357833 -0.0053906888, -0.0009778291 -0.056996197 -0.0043337941, 0.036902949 -0.042663217 -0.0033849627, 0.035014227 -0.043212309 -0.0025933981, -0.0029105395 -0.057203665 -0.0050293356, -0.0038800538 -0.057243004 -0.0053907186, -0.0065183789 -0.057129055 -0.0065030754, 0.037292793 -0.043113679 -0.0043331087, -0.0059802085 -0.057061851 -0.0053906888, -0.0045807362 -0.057191163 -0.0053906441, 0.031605273 -0.043306082 -0.0016277879, -0.0062420815 -0.057033867 -0.0053906739, -0.0059416294 -0.05669418 -0.0043338686, 0.02937071 -0.043515608 -0.0015023649, 0.035512522 -0.043827355 -0.0033850819, -0.0077982694 -0.056744292 -0.0050294548, 0.037534669 -0.043393239 -0.0053900331, -0.01121375 -0.05639559 -0.0065031946, -0.0087240487 -0.056707323 -0.0053906292, 0.032228291 -0.044159591 -0.0019977093, -0.010930717 -0.056323558 -0.005390659, -0.0094613284 -0.056588948 -0.0053906292, -0.026962772 -0.04633908 -0.0016278028, -0.027281448 -0.046152368 -0.0016279668, -0.027025938 -0.045009404 -0.0015024841, 0.035887614 -0.044290185 -0.0043331236, -0.027494386 -0.047252461 -0.0019979328, 0.029993102 -0.044437855 -0.0016277879, 0.032787278 -0.044925451 -0.0025934577, -0.028630167 -0.045754582 -0.0017246753, -0.029165432 -0.044985339 -0.0016279221, -0.030846015 -0.042482719 -0.00150235, -0.03069751 -0.043954298 -0.0016278028, -0.031099811 -0.043670386 -0.0016277432, 0.03612031 -0.04457736 -0.0053899437, -0.031302541 -0.044820726 -0.0019977242, 0.033896968 -0.046445847 -0.0065026581, 0.03058444 -0.045313776 -0.001997754, -0.032376856 -0.043184772 -0.0017246604, 0.033253804 -0.045564935 -0.0033849925, -0.034431264 -0.03963244 -0.0015024245, -0.032877937 -0.042347893 -0.0016277134, -0.034222245 -0.041269124 -0.0016277879, -0.057268128 -0.0034931302 -0.0053875744, 0.031114653 -0.046099529 -0.0025933534, 0.033605129 -0.046046019 -0.0043332279, -0.057243153 -0.0019983351 -0.0050264597, 0.027921066 -0.045768142 -0.0016279072, 0.025466174 -0.045909867 -0.0015026331, -0.057366014 -0.00099188089 -0.0053874999, -0.057472542 0.0017788559 -0.0064998418, -0.057373732 -0.00033308566 -0.0053873807, -0.057366088 0.00098434091 -0.0053874552, 0.031557634 -0.046755776 -0.0033851862, -0.057357952 0.0013796836 -0.005387336, 0.033822954 -0.046344668 -0.0053901821, -0.056996465 0.0009779036 -0.0043303668, 0.028471529 -0.046670079 -0.0019979179, -0.057203829 0.0029108226 -0.0050259233, -0.057129338 0.0065187216 -0.0064996481, -0.057243362 0.0038802922 -0.0053872317, 0.031890661 -0.047249302 -0.0043333322, -0.057062089 0.005980432 -0.0053871572, -0.057191521 0.0045810193 -0.0053870976, 0.02896522 -0.04747957 -0.0025935471, -0.057034135 0.006242469 -0.0053872168, -0.056694344 0.0059419721 -0.0043302625, 0.026005998 -0.046882942 -0.0016280413, 0.029945716 -0.049086317 -0.0065029114, 0.032097712 -0.047555849 -0.0053901523, -0.056744561 0.0077984482 -0.0050258189, -0.056707561 0.0087244064 -0.0053870231, 0.029377624 -0.048155397 -0.003385216, -0.056589231 0.0094615817 -0.0053869188, 0.026518568 -0.047806889 -0.0019978136, 0.047598809 -0.028382733 -0.002442047, 0.029687881 -0.04866381 -0.0043334812, 0.047358572 -0.028584749 -0.0023704916, 0.026978314 -0.048635915 -0.0025937259, 0.047047943 -0.02984184 -0.0026715398, 0.024046391 -0.047917381 -0.0016281456, 0.021368116 -0.047954738 -0.0015028566, 0.029880524 -0.048979312 -0.0053903908, 0.045353189 -0.030525923 -0.0019968897, 0.027362466 -0.049328372 -0.0033854842, 0.046136931 -0.030517414 -0.0023705214, 0.045963019 -0.030961812 -0.0024420619, 0.024520263 -0.048861995 -0.0019980818, 0.045598015 -0.031845361 -0.0025927424, 0.046247035 -0.03229858 -0.003384307, 0.027651459 -0.049849167 -0.0043335557, 0.045075923 -0.032239586 -0.0024422705, 0.044811517 -0.032432258 -0.0023706704, 0.024945468 -0.04970932 -0.002593711, 0.021820813 -0.048970953 -0.0016281903, 0.044405818 -0.033647835 -0.0026717186, 0.042638302 -0.034215972 -0.0019972473, 0.027830809 -0.050172478 -0.0053903013, 0.025789782 -0.051391631 -0.0065029114, 0.025300652 -0.050416902 -0.0033854544, 0.043433011 -0.034256488 -0.0023708344, 0.043231487 -0.03467378 -0.002442345, 0.02225095 -0.049936295 -0.0019979328, 0.025567755 -0.050949261 -0.004333511, 0.0039517581 -0.056270465 -0.0033856779, 0.0032998919 -0.056463316 -0.0035844296, 0.0038963258 -0.055480614 -0.0025939941, 0.0029721558 -0.056553081 -0.003686592, 0.020007208 -0.049739614 -0.0016280413, 0.017107129 -0.04963465 -0.001502797, 0.02263698 -0.050802261 -0.0025937259, 0.0016493648 -0.056305915 -0.0032892972, 0.025733739 -0.051279709 -0.005390361, 0.020401493 -0.050719902 -0.0019980669, 0.022959143 -0.051525369 -0.0033854842, -0.00095395744 -0.055609033 -0.002594009, 1.1220574e-05 -0.056559548 -0.0035844594, -0.0009675324 -0.056400701 -0.0033857971, 0.020755336 -0.051599413 -0.0025937259, 0.00050248206 -0.056628719 -0.0036864877, 0.00050505996 -0.056918189 -0.0041668713, 0.00066691637 -0.057103246 -0.0045610368, 0.023201525 -0.0520695 -0.0043334961, 3.9935112e-06 -0.05700472 -0.0043337941, 0.01746963 -0.050686464 -0.0016281754, 0.00011339784 -0.057154074 -0.0046766251, 0.021050781 -0.052333936 -0.0033854693, -0.0003233552 -0.057003766 -0.0043337345, 0.021457881 -0.053345859 -0.0065030158, 0.023351938 -0.052407116 -0.0053904951, -0.001605168 -0.056536794 -0.0035845786, 0.017814085 -0.051685452 -0.0019981116, -0.0019248426 -0.05659844 -0.0036865771, 0.021273047 -0.05288662 -0.0043335706, -0.0032355785 -0.056237176 -0.0032892674, 0.015831411 -0.051221773 -0.0016281605, 0.012716144 -0.050936654 -0.0015029609, 0.018123031 -0.052581862 -0.0025937706, 0.021411121 -0.05322963 -0.0053904355, -0.0057971179 -0.055314332 -0.0025940388, -0.0048895627 -0.056347668 -0.0035844743, -0.005879581 -0.056101799 -0.0033857375, -0.0044141561 -0.056749076 -0.004166916, -0.0043918043 -0.056460455 -0.0036866069, 0.016143456 -0.05223155 -0.0019980967, 0.018381 -0.053330317 -0.0033855885, -0.0042397976 -0.056949571 -0.0045611709, -0.0048990846 -0.056793869 -0.0043337345, 0.016423449 -0.053137317 -0.0025938451, -0.0047957301 -0.05695267 -0.0046765655, 0.018575132 -0.053893387 -0.004333809, -0.0052469969 -0.056762636 -0.0043337196, 0.012985602 -0.052016169 -0.0016282946, -0.0064977854 -0.056185067 -0.0035844892, 0.016657189 -0.053893626 -0.0033857077, -0.0068072975 -0.056220502 -0.0036865175, 0.016979232 -0.05493556 -0.0065030903, 0.018695548 -0.054242834 -0.0053906441, 0.013241574 -0.053041473 -0.0019980818, -0.0080961138 -0.055745289 -0.0032891333, 0.016833171 -0.054462776 -0.0043335259, 0.011547521 -0.052354261 -0.0016283095, 0.0082283616 -0.051851153 -0.0015027672, -0.010595918 -0.054598749 -0.0025939345, -0.0097535998 -0.055712119 -0.0035845786, -0.010746777 -0.055375755 -0.0033856034, 0.013471186 -0.053961381 -0.0025939643, -0.0093005449 -0.056155309 -0.0041668415, -0.0092532188 -0.055869967 -0.0036865175, 0.016942218 -0.054815903 -0.0053906292, -0.0091153234 -0.056374967 -0.0045610666, 0.011775091 -0.053386241 -0.0019981116, -0.0097659677 -0.056161836 -0.0043337196, -0.0096692741 -0.056330279 -0.004676491, 0.013662934 -0.054729387 -0.0033856183, -0.010131136 -0.056097209 -0.0043337494, 0.011979252 -0.054311886 -0.0025939941, -0.010860354 -0.055960432 -0.0043337643, 0.013807297 -0.055307269 -0.0043337345, -0.028369322 -0.048756137 -0.0033852756, -0.028383002 -0.047598556 -0.0024430007, -0.027971089 -0.048071876 -0.0025936216, -0.028584763 -0.047358558 -0.0023715198, 0.012149751 -0.055085003 -0.0033856928, 0.0084027499 -0.052950054 -0.0016283393, -0.029841855 -0.047047824 -0.0026723295, 0.013896957 -0.055666044 -0.0053907186, -0.030525982 -0.04535313 -0.0019976795, 0.012384742 -0.056150079 -0.0065033436, 0.01227814 -0.055666715 -0.0043339133, -0.030517474 -0.046136662 -0.0023715794, -0.030962005 -0.045962781 -0.0024430156, 0.0085683763 -0.053993687 -0.0019981712, -0.031845436 -0.045597762 -0.002593413, -0.032298729 -0.046246842 -0.0033852309, -0.03223978 -0.045075729 -0.0024429858, 0.0071845949 -0.053129092 -0.0016283393, -0.032432243 -0.044811562 -0.0023713708, 0.003677845 -0.05237104 -0.0015031397, 0.012357771 -0.056027725 -0.0053906143, 0.0087169558 -0.054929912 -0.0025939941, -0.033647805 -0.044405594 -0.0026722848, 0.0073261708 -0.054176182 -0.0019983351, -0.034215942 -0.042638078 -0.0019977391, -0.034896895 -0.042082652 -0.0019975901, 0.0088410676 -0.055711985 -0.0033856332, -0.034256518 -0.043432936 -0.0023713708, -0.03467384 -0.043231264 -0.0024428219, 0.0074533522 -0.05511573 -0.0025939643, -0.035502091 -0.042812303 -0.002593264, -0.036007419 -0.04342176 -0.0033849776, 0.0089343786 -0.056300282 -0.0043337196, -0.05646342 -0.003299579 -0.0035815537, -0.056553185 -0.0029718727 -0.0036836416, 0.0075592846 -0.055900097 -0.0033856928, 0.0037557334 -0.053480819 -0.0016284436, -0.056306049 -0.001649186 -0.0032861829, 0.0077055544 -0.056980863 -0.006503284, 0.0089923292 -0.056665301 -0.0053906441, 0.0076391548 -0.056490541 -0.0043338984, -0.056559697 -1.0952353e-05 -0.0035813153, -0.056400985 0.00096777081 -0.0033824593, 0.0038298219 -0.054534957 -0.0019981712, -0.056918353 -0.00050480664 -0.0041638315, -0.056628898 -0.00050233305 -0.0036835372, 0.0076886415 -0.056856781 -0.0053907335, -0.057103485 -0.00066678226 -0.0045579672, -0.057004794 -3.6209822e-06 -0.004330799, -0.057154268 -0.00011307001 -0.0046733916, -0.057003886 0.00032360852 -0.0043306053, -0.056536838 0.0016052127 -0.0035813451, -0.05659841 0.0019249618 -0.0036833733, -0.056237251 0.0032356977 -0.0032857805, -0.056347802 0.0048897266 -0.003581062, -0.056102008 0.0058797896 -0.0033821762, -0.056749135 0.0044144839 -0.0041634738, -0.056460589 0.0043918639 -0.0036832243, -0.056949824 0.0042400211 -0.0045575649, -0.056793809 0.004899323 -0.0043304414, -0.056952789 0.0047960281 -0.0046730191, -0.056762949 0.0052471608 -0.0043302774, -0.056185186 0.0064979345 -0.0035810918, -0.056220576 0.0068074465 -0.0036830604, -0.055745348 0.0080963224 -0.0032857358, -0.055712193 0.0097537041 -0.0035807192, -0.056155592 0.0093007982 -0.0041631162, -0.055870086 0.0092533976 -0.0036830753, -0.05637525 0.0091155022 -0.0045573413, -0.056162059 0.0097661018 -0.0043300688, -0.056330442 0.0096696317 -0.0046726912, -0.056097329 0.010131404 -0.00432989, 0.048237458 -0.029316977 -0.0034332722, -0.010214061 -0.052630588 -0.0016282946, -0.014762208 -0.051540226 -0.0016281605, -0.010002226 -0.051538274 -0.0015030354, -0.01445587 -0.050470576 -0.0015027374, 0.047780231 -0.030443102 -0.003719613, -0.010415375 -0.053667977 -0.0019979924, -0.015053213 -0.052556053 -0.0019980669, 0.046984717 -0.03128539 -0.0034333766, 0.046735466 -0.032639652 -0.0043324381, -0.015314385 -0.053467289 -0.0025940239, 0.045643255 -0.033211887 -0.003433466, -0.015532181 -0.0542285 -0.0033856481, 0.045097381 -0.034292504 -0.0037198216, -0.015696287 -0.054801077 -0.0043337792, 0.044231802 -0.035069749 -0.0034337491, -0.018968031 -0.050145105 -0.0016280115, -0.018799603 -0.049018592 -0.001502797, 0.0027605891 -0.055499837 -0.002555564, -0.015832603 -0.05527699 -0.0065030456, -0.015798181 -0.055156499 -0.0053906143, -0.019341856 -0.051133394 -0.0019980967, 0.0015154183 -0.055261329 -0.0023486763, -0.019677222 -0.052020073 -0.0025938898, 0.00033710897 -0.055567414 -0.0025555342, -0.0020727813 -0.055529594 -0.0025555044, -0.00093775988 -0.054661423 -0.0019983202, -0.019957349 -0.052760646 -0.0033854395, -0.020167992 -0.053317726 -0.0043335706, -0.023044154 -0.048407286 -0.0016279519, -0.0032974184 -0.055183649 -0.0023486912, -0.023000509 -0.047193468 -0.0015026778, -0.0044931024 -0.055386528 -0.002555415, -0.020343125 -0.053780779 -0.0065029413, -0.020298958 -0.053663418 -0.0053905249, -0.0068906546 -0.055139452 -0.0025553554, -0.0056982636 -0.054371521 -0.0019983053, -0.023498416 -0.049361467 -0.0019979477, -0.0080850422 -0.054687634 -0.002348572, -0.023905858 -0.050217599 -0.0025936216, -0.0092893094 -0.054786533 -0.002555415, -0.024246112 -0.050932363 -0.0033854097, -0.029317066 -0.048237175 -0.0034341812, -0.028668866 -0.049270898 -0.0043335408, -0.024502292 -0.051470116 -0.0043335259, -0.030443177 -0.047779933 -0.0037205964, -0.024661273 -0.051803887 -0.0053903759, -0.03128548 -0.046984583 -0.0034342855, -0.024714917 -0.051917151 -0.0065029263, -0.028854817 -0.049590528 -0.0053903013, -0.028917924 -0.04969883 -0.0065028816, -0.035160944 -0.040472478 -0.001627624, 0.049149022 -0.029488623 -0.0051608831, 0.04892166 -0.02980122 -0.0050478578, -0.035853952 -0.041270167 -0.0019975007, 0.048390865 -0.030878589 -0.0055246204, 0.047141343 -0.032922834 -0.006501928, -0.036475852 -0.041985765 -0.0025932342, 0.047648236 -0.031797335 -0.0050481409, 0.047449872 -0.032151401 -0.0051609576, 0.047038674 -0.032851174 -0.0053893626, 0.046544135 -0.033449426 -0.0051610172, -0.036994979 -0.04258348 -0.0033849776, 0.0462908 -0.033743218 -0.0050480366, -0.03751342 -0.038302153 -0.001627475, -0.037754416 -0.036480829 -0.0015021563, 0.045673817 -0.034771651 -0.0055249035, 0.044856817 -0.035627425 -0.0050481111, -0.037385657 -0.043033063 -0.0043330044, 0.044630662 -0.035962492 -0.0051613152, -0.038252905 -0.039057091 -0.0019974113, 0.0030069798 -0.053756848 -0.0016861409, -0.038554549 -0.037253886 -0.0016273558, 0.00263004 -0.053889751 -0.0017191321, -0.040233567 -0.041079029 -0.0065024048, -0.037628263 -0.043312103 -0.0053897649, 0.0014324933 -0.05345799 -0.0015994608, -0.038916171 -0.039734289 -0.0025931299, -0.00090053678 -0.052492335 -0.001502946, 0.00027683377 -0.053953126 -0.0017190874, -0.039314598 -0.03798826 -0.0019973516, -0.03947024 -0.040299818 -0.0033847839, -0.00012360513 -0.053840727 -0.0016862601, -0.00091964006 -0.053604722 -0.0016283095, -0.00030292571 -0.054640457 -0.0019846112, -0.0016865283 -0.053814337 -0.0016862452, -0.039996251 -0.038646981 -0.0025931299, -0.0020723939 -0.053914145 -0.0017191321, -0.039886981 -0.04072538 -0.0043329149, -0.040548295 -0.035073489 -0.0016271621, -0.0407902 -0.033051431 -0.0015019327, -0.0032290369 -0.053379625 -0.0015994906, -0.0054720789 -0.052214116 -0.0015029907, -0.04056567 -0.039197102 -0.0033848137, -0.0044220835 -0.05377236 -0.0017190129, -0.0048127472 -0.053625301 -0.0016860813, -0.0055882037 -0.053320497 -0.0016282797, -0.04014571 -0.040989667 -0.0053898394, -0.0050570965 -0.054406747 -0.0019848645, -0.041347623 -0.035764843 -0.0019970685, -0.0063672513 -0.053463012 -0.0016861707, -0.0067587942 -0.053528875 -0.0017189682, -0.0078659356 -0.05289565 -0.0015994906, -0.042064577 -0.036384985 -0.002592966, -0.00908719 -0.053183168 -0.0017191768, -0.0094652772 -0.053002328 -0.0016861707, -0.0097728223 -0.053760096 -0.0019849092, -0.029488936 -0.049148858 -0.0051620603, -0.029801473 -0.048921466 -0.005048871, -0.030878559 -0.048390687 -0.005525589, -0.031797662 -0.047648132 -0.0050488561, -0.032151639 -0.047449768 -0.0051616728, 0.042414248 0.062924892 -0.048405662, 0.038395375 0.066551462 -0.049001217, 0.042944044 0.063710898 -0.049001455, 0.041971684 0.062268361 -0.047614068, 0.037526041 0.065044418 -0.047613889, 0.037921593 0.065730318 -0.048405603, 0.0063907504 0.07494086 -0.047757283, 0.0057023317 0.075178504 -0.047957152, 0.0063197464 0.075216755 -0.048046082, 0.0057465136 0.0748346 -0.047564238, 0.0066675544 0.074876174 -0.047709838, 0.0072963536 0.075533688 -0.048404947, 0.007220313 0.074745715 -0.047613367, 0.0071630478 0.074152559 -0.046665221, 0.041432098 0.061467692 -0.045609221, 0.042254135 0.060752824 -0.04449667, 0.037706882 0.063675046 -0.044496506, 0.0062033683 0.074393556 -0.046959832, 0.007127434 0.073784366 -0.045608357, 0.047934026 0.061393142 -0.049371317, 0.04415676 0.0655099 -0.049496472, 0.048618793 0.062270164 -0.049496576, 0.043534845 0.064587399 -0.049371138, 0.0057219565 0.074516892 -0.047103062, 0.0099826306 0.076372638 -0.049086809, 0.0098002702 0.075152382 -0.048326135, 0.0083505362 0.075727105 -0.04862693, 0.0095397383 0.076939866 -0.049273536, 0.047283515 0.060560212 -0.049001426, 0.010628968 0.07716164 -0.049370468, 0.010202557 0.07609649 -0.048973188, 0.0084619671 0.074576363 -0.047564283, 0.04670009 0.059813067 -0.048405826, 0.0079983026 0.075662509 -0.048555568, 0.010506406 0.075850919 -0.048866853, 0.046212837 0.059188887 -0.047614053, 0.011719048 0.075934336 -0.049000606, 0.011110589 0.075371712 -0.048627093, 0.0080040246 0.074221492 -0.046959817, 0.045618564 0.058427826 -0.0456094, 0.045846328 0.058719322 -0.046666235, 0.008426249 0.074259624 -0.047103122, 0.046575844 0.057506442 -0.044496968, 0.011152282 0.074565053 -0.047957286, 0.011672482 0.075183362 -0.048555672, 0.053309917 0.056787506 -0.04937163, 0.052843675 0.058727071 -0.049496919, 0.056811497 0.054897755 -0.049497291, 0.052099615 0.057899967 -0.049371436, 0.011770725 0.074558392 -0.048046067, 0.012790367 0.074799433 -0.0484052, 0.052586511 0.056016967 -0.049001709, 0.051392645 0.057114482 -0.049001679, 0.011823714 0.07427761 -0.047757298, 0.011180267 0.074217618 -0.047564209, 0.01210168 0.074191973 -0.047709808, 0.012656987 0.074019179 -0.047613457, 0.012556449 0.073431849 -0.046665177, 0.051937699 0.055325687 -0.048406065, 0.050758451 0.056409568 -0.048406169, 0.011608005 0.07374391 -0.046959922, 0.011132523 0.073902339 -0.047103181, 0.012494281 0.073067352 -0.045608431, 0.051395863 0.054748446 -0.047614336, 0.050228864 0.055821195 -0.047614336, 0.04783769 0.059700355 -0.048826724, 0.056011304 0.054124773 -0.049371734, 0.047824636 0.058917612 -0.048405841, 0.047293767 0.057910457 -0.04715687, 0.046933621 0.058334276 -0.047313318, 0.048421279 0.057396248 -0.047614262, 0.050988138 0.054314226 -0.046666488, 0.049830407 0.055378139 -0.046666354, 0.048112795 0.059272796 -0.048730418, 0.055251509 0.053390309 -0.049001992, 0.050735056 0.054044619 -0.045609578, 0.050649241 0.053953126 -0.044497117, 0.049583122 0.055103183 -0.045609638, 0.057312593 0.052744731 -0.049371704, 0.060502455 0.050801054 -0.049497291, 0.050563321 0.057410166 -0.048827067, 0.054569706 0.052731335 -0.048406288, 0.049851552 0.057212815 -0.048406184, 0.049285948 0.056224734 -0.047157109, 0.049596652 0.056087658 -0.047313571, 0.056534916 0.052029133 -0.049002036, 0.050152093 0.057557523 -0.048730493, 0.046771467 0.05750896 -0.0456094, 0.048135102 0.056372598 -0.045609489, 0.054000244 0.052181289 -0.047614589, 0.0461386 0.058018163 -0.045609429, 0.047122136 0.05770044 -0.04666616, 0.048206553 0.056797594 -0.04666625, 0.04910706 0.056020647 -0.046666354, 0.055837482 0.051386937 -0.048406377, 0.074872687 0.0051927418 -0.047568262, 0.075988978 0.005442515 -0.048631042, 0.075683489 0.0039470494 -0.048330069, 0.075859308 0.0058116615 -0.048559487, 0.074811056 0.0064786226 -0.047617346, 0.053571984 0.051767245 -0.046666428, 0.074439868 0.0055902749 -0.046963602, 0.074217692 0.0064270645 -0.046669319, 0.073849171 0.0063952059 -0.045612186, 0.055254832 0.050850824 -0.047614545, 0.074554622 0.005170837 -0.047106981, 0.053306028 0.051510215 -0.045609757, 0.05445224 0.050112009 -0.044497296, 0.059650078 0.050085619 -0.049371943, 0.054816455 0.050447434 -0.046666667, 0.075012296 0.0024549514 -0.047568426, 0.076136947 0.0026635975 -0.048631132, 0.076052114 0.0021113604 -0.048559695, 0.075084299 0.0010003597 -0.04761751, 0.058840975 0.049405992 -0.049002215, 0.054544419 0.050196975 -0.045609713, 0.0746236 0.0019594431 -0.046964005, 0.07469365 0.002444461 -0.04710713, 0.074488625 0.00099250674 -0.046669394, 0.058114856 0.04879643 -0.048406437, 0.074118882 0.00098741055 -0.045612514, 0.075051904 -0.00027287006 -0.047568366, 0.076080814 0.00028629601 -0.048559815, 0.076183453 -7.7605247e-05 -0.04863134, 0.07577005 -0.0015604794 -0.048330471, 0.061009631 0.048420459 -0.049371973, 0.063898563 0.046456918 -0.049497485, 0.07464911 0.00015065074 -0.046964034, 0.057508498 0.048287213 -0.047614753, 0.074733004 -0.00027170777 -0.047107235, 0.060181946 0.047763303 -0.04900226, 0.075333536 -0.0029616505 -0.047961637, 0.076129794 -0.0028600097 -0.048631489, 0.076004446 -0.0034184009 -0.048560098, 0.057052314 0.047904208 -0.046666622, 0.059439301 0.047174066 -0.048406482, 0.056769118 0.047666371 -0.045609772, 0.057964802 0.046003759 -0.044497535, 0.07512112 -0.0036570281 -0.047761694, 0.074991778 -0.0030136257 -0.047568679, 0.0588191 0.046681911 -0.047614887, 0.075746998 -0.0045303255 -0.048409536, 0.07506682 -0.0039327294 -0.047714338, 0.074956834 -0.0044830739 -0.047617763, 0.074362189 -0.004447639 -0.046669632, 0.062998593 0.045802772 -0.049372286, 0.058352605 0.046311557 -0.04666695, 0.07456781 -0.0034838617 -0.046964273, 0.074673176 -0.00300093 -0.047107473, 0.073993072 -0.0044254959 -0.045612976, 0.062143698 0.04518123 -0.049002394, 0.074832678 -0.0057368726 -0.047568858, 0.075977355 -0.0055972636 -0.048631564, 0.075456351 -0.0070599765 -0.048330694, 0.075900421 -0.0052407086 -0.048560113, 0.074461505 -0.0052898526 -0.046964377, 0.058062866 0.046081588 -0.0456101, 0.061377048 0.044623613 -0.048406646, 0.074514687 -0.0057126582 -0.047107637, 0.064381242 0.043837756 -0.049372315, 0.066983476 0.04188633 -0.049497798, 0.060736582 0.044158146 -0.047615051, 0.074918732 -0.0084301978 -0.04796192, 0.075722158 -0.0083683878 -0.048631787, 0.07555522 -0.0089299083 -0.048560321, 0.063507646 0.043243006 -0.049002454, 0.074934527 -0.0090484619 -0.048050642, 0.060254827 0.04380773 -0.046667099, 0.075214148 -0.010047436 -0.04840976, 0.062724084 0.042709455 -0.04840681, 0.074656039 -0.0091105551 -0.047762126, 0.074573025 -0.0084662884 -0.047568917, 0.059955806 0.043590218 -0.045610249, 0.061167911 0.04164958 -0.044497713, 0.074580833 -0.0093881786 -0.047714457, 0.074429274 -0.009942621 -0.047618076, 0.07383886 -0.0098636746 -0.046669945, 0.066039875 0.041296512 -0.049372435, 0.074115351 -0.0089089125 -0.04696463, 0.07347247 -0.009814918 -0.045613185, 0.062069669 0.042263731 -0.047615036, 0.074256197 -0.008430168 -0.047107682, 0.075960904 -0.01272358 -0.049091905, 0.075371981 -0.011087492 -0.048631832, 0.076544136 -0.012298867 -0.049278602, 0.074744016 -0.012522101 -0.048330992, 0.065143943 0.040736124 -0.049002737, 0.076730043 -0.01337482 -0.049375489, 0.075676784 -0.012934521 -0.048978239, 0.061577231 0.04192853 -0.046667144, 0.074215949 -0.011170775 -0.047569171, 0.06433998 0.040233642 -0.048407033, 0.075319052 -0.010739863 -0.048560321, 0.075419307 -0.013235182 -0.048871771, 0.075458899 -0.014450967 -0.049005687, 0.074916571 -0.013832897 -0.048632056, 0.061271593 0.041720316 -0.045610204, 0.073877856 -0.010702282 -0.046964541, 0.067409188 0.039021462 -0.049372479, 0.069741756 0.037111878 -0.049497962, 0.073900759 -0.011123329 -0.047108039, 0.063668787 0.039813906 -0.047615319, 0.074107468 -0.013854146 -0.047962114, 0.074706689 -0.014394268 -0.048560739, 0.066494569 0.038491905 -0.049002916, 0.074876562 -0.021443695 -0.049375832, 0.077278599 -0.016399145 -0.049501047, 0.075946257 -0.021749869 -0.049501345, 0.063163757 0.039498106 -0.046667248, 0.074078336 -0.014472052 -0.048051178, 0.07427983 -0.015510857 -0.048410147, 0.065674022 0.038016945 -0.048406959, 0.062850162 0.039301828 -0.045610398, 0.073795527 -0.014515728 -0.047762305, 0.073758319 -0.013873845 -0.047569275, 0.064044833 0.037073568 -0.044498101, 0.06875962 0.03658922 -0.049372613, 0.064988822 0.037620306 -0.047615424, 0.073698983 -0.014793873 -0.047714785, 0.073504835 -0.015349016 -0.047618374, 0.072921738 -0.015227318 -0.046670437, 0.073269039 -0.014286518 -0.046964824, 0.072559774 -0.015151829 -0.045613632, 0.067826658 0.036092728 -0.049002811, 0.073445141 -0.013814852 -0.047108099, -0.0065748692 0.074753657 -0.047547936, -0.0078808963 0.074319512 -0.047103062, -0.007914409 0.07463643 -0.047564238, -0.073198289 0.02662003 -0.049373135, -0.075946182 0.021755412 -0.049498856, -0.074243769 0.027000219 -0.049498588, 0.064473405 0.037321866 -0.046667308, -0.0064741671 0.074198052 -0.04662776, -0.0066924095 0.075492874 -0.048326001, -0.0051834881 0.074875727 -0.047564238, -0.074876711 0.021449044 -0.049373403, -0.0051614642 0.074557751 -0.047103092, -0.0077652484 0.073715433 -0.045588285, -0.0082981735 0.07418929 -0.046959922, -0.0090854466 0.073568851 -0.045608431, 0.06698969 0.035647333 -0.048407212, -0.072204888 0.026258767 -0.049003467, -0.0090700835 0.07344459 -0.04449597, -0.073860615 0.021158099 -0.049003631, -0.0050680935 0.073950037 -0.0455883, -0.0046762228 0.074505329 -0.046959639, -0.0036912411 0.074035868 -0.045608371, 0.064153239 0.03713651 -0.045610517, -0.0036850721 0.073910847 -0.044495925, -0.071314111 0.025934875 -0.048407704, -0.0011187792 0.075033829 -0.047547907, -0.0010499656 0.074472487 -0.046627715, -0.0024485141 0.074696109 -0.047102928, -0.0011915118 0.075779483 -0.04832615, 0.00022228062 0.075394154 -0.047957137, -0.072949201 0.020896956 -0.048408121, 0.070077509 0.033996701 -0.049372882, 0.072160497 0.032156587 -0.049498454, 0.00028218329 0.075054452 -0.047564328, 0.0002810061 0.074735582 -0.047103018, -0.0024589747 0.075014725 -0.047564209, -0.0023682714 0.074085474 -0.04558827, -0.0028697997 0.074596778 -0.046959698, 0.066290811 0.035275489 -0.047615588, -0.070569932 0.025664121 -0.04761596, -0.072188109 0.020678967 -0.047616303, 0.00033909082 0.074122503 -0.045588091, -0.07001023 0.025460601 -0.046668097, 0.06912671 0.033535495 -0.049003065, 0.00076545775 0.074648038 -0.046959803, 0.0017226487 0.07410796 -0.045608342, -0.071615383 0.020514876 -0.046668157, 0.0017198771 0.073982731 -0.044495851, -0.069662511 0.025334045 -0.045611218, -0.07126008 0.020413041 -0.045611501, -0.071139529 0.02037853 -0.04449895, 0.0043430179 0.074916542 -0.047547862, 0.0030095875 0.074994549 -0.047564283, 0.004315719 0.075665593 -0.048325956, 0.0043798089 0.074351117 -0.046627849, 0.002996847 0.074676082 -0.047103196, -0.069462478 0.025516927 -0.044498563, 0.065764785 0.034995615 -0.046667427, 0.0030410886 0.074060991 -0.04558821, 0.0025738925 0.074607491 -0.046959758, -0.071163073 0.031661034 -0.049372807, -0.07217969 0.032113299 -0.0494982, 0.068273783 0.033121556 -0.048407391, -0.070197731 0.031231686 -0.049003094, 0.005743891 0.073900431 -0.045588285, 0.0071155131 0.073659599 -0.044495866, 0.065438479 0.034821823 -0.045610711, 0.0097819567 0.074402079 -0.047547951, 0.0097862929 0.073834196 -0.046627745, 0.066579908 0.032299772 -0.044498309, 0.071144223 0.031703696 -0.049372897, -0.069331422 0.030846268 -0.048407555, 0.0084345788 0.073642001 -0.045588136, 0.067561522 0.032776058 -0.047615588, -0.06860812 0.030524299 -0.047615811, 0.011118442 0.07328482 -0.045588285, 0.012473017 0.072943836 -0.044495881, 0.070178851 0.031273529 -0.049003214, -0.068063676 0.03028205 -0.046667844, 0.049028039 0.060523048 -0.049371317, 0.0494266 0.058824196 -0.049001649, 0.067025498 0.032516062 -0.04666765, -0.067725778 0.030131817 -0.045611054, 0.050303161 0.059947804 -0.04944095, -0.067414626 0.030519173 -0.044498175, -0.068781465 0.036548227 -0.049372569, 0.06931299 0.030887663 -0.048407331, 0.051110283 0.058775172 -0.049371466, -0.069764078 0.03707011 -0.049498081, 0.06669274 0.032354459 -0.04561086, 0.048874393 0.058049709 -0.04840602, -0.067848206 0.036052182 -0.049002856, 0.068589807 0.030565277 -0.047615811, 0.074940845 0.0038519949 -0.04755187, 0.074382201 0.0037673116 -0.046631828, -0.067011029 0.035607502 -0.048407197, 0.072372049 0.028790742 -0.049373105, 0.07422778 0.027044594 -0.049498573, 0.073947281 0.005072698 -0.04559201, 0.073724285 0.0063843578 -0.044499695, -0.066311881 0.035235867 -0.047615513, 0.06804578 0.03032282 -0.046667546, 0.074083045 0.0023685396 -0.045592397, 0.073993549 0.00098568201 -0.044500142, -0.065785795 0.034956411 -0.046667472, 0.071390063 0.028400213 -0.049003258, 0.075022295 -0.0016105026 -0.047552243, 0.074458703 -0.001663357 -0.046632081, -0.065459266 0.034782752 -0.045610681, -0.065007165 0.035358697 -0.044498071, 0.074120075 -0.00033405423 -0.045592442, -0.066064581 0.041257098 -0.04937239, 0.067707911 0.030172125 -0.045611024, 0.068759888 0.027353629 -0.044498667, 0.074058414 -0.0030409992 -0.045592621, 0.073867872 -0.0044180751 -0.044500336, -0.067008451 0.041846469 -0.049497783, 0.070509046 0.028049543 -0.048407644, -0.065168291 0.040697381 -0.049002722, 0.074706227 -0.0070645809 -0.047552541, 0.074139282 -0.0070851445 -0.046632275, 0.073182285 0.026663616 -0.049373209, -0.064364031 0.040195093 -0.048406988, 0.069773555 0.02775687 -0.047615916, 0.073898152 -0.005739212 -0.045592844, 0.07363914 -0.0084341764 -0.045592755, -0.063692555 0.039775789 -0.0476152, 0.073348179 -0.0097982734 -0.044500679, 0.072189301 0.02630201 -0.049003363, 0.073993891 -0.012480989 -0.047552824, -0.063187271 0.039460123 -0.046667129, 0.069220036 0.027536675 -0.046667919, 0.073425591 -0.012469202 -0.046632767, 0.073282465 -0.011113733 -0.045593053, -0.062873632 0.039264187 -0.045610487, -0.062252924 0.040009752 -0.044497788, 0.07129851 0.025977507 -0.048407912, -0.063025936 0.045764998 -0.049372002, 0.072827622 -0.013782486 -0.045593098, 0.072437093 -0.015126184 -0.044500828, -0.063926294 0.046418682 -0.049497455, 0.068876445 0.027399912 -0.045611113, -0.062170774 0.045144156 -0.049002409, 0.070554748 0.025706336 -0.04761602, 0.074280381 0.023430958 -0.049373507, 0.075933114 0.021800876 -0.049499005, -0.061403677 0.044586957 -0.048406586, 0.069994986 0.025502414 -0.046667963, -0.060763016 0.044121772 -0.047614932, 0.073272452 0.023113146 -0.049003467, -0.059981629 0.043554455 -0.045610085, -0.060280845 0.043771729 -0.046667024, -0.059166521 0.044447139 -0.044497684, 0.069647476 0.025375664 -0.045611203, -0.059680164 0.050050095 -0.049371898, -0.060532659 0.050764889 -0.049497083, 0.070573062 0.02226159 -0.044498846, 0.074863791 0.021493807 -0.049373507, 0.072368369 0.022828013 -0.048408017, -0.058870494 0.049370959 -0.049002066, -0.058693901 0.051203132 -0.049371779, 0.073848024 0.021202266 -0.049003825, -0.05684422 0.054863691 -0.049497068, -0.058144078 0.048761845 -0.048406586, 0.071613207 0.022589639 -0.047616214, -0.057897419 0.05050844 -0.049002066, 0.072936863 0.020940408 -0.048408031, -0.057537347 0.048252925 -0.047614872, 0.071045235 0.022410572 -0.046668261, -0.057183102 0.049885198 -0.048406392, 0.072175756 0.020722061 -0.047616467, 0.070692524 0.022299156 -0.045611426, 0.075792357 0.017946556 -0.049373582, 0.077268869 0.016450852 -0.049499124, -0.056586415 0.049364656 -0.047614515, -0.056797385 0.047632322 -0.045609966, -0.057080999 0.047870278 -0.046666637, 0.071603149 0.020557716 -0.046668291, -0.055764318 0.048647448 -0.044497266, -0.056043819 0.05409126 -0.04937166, 0.074763939 0.017702997 -0.049003899, -0.056137457 0.048973083 -0.046666697, 0.071247861 0.020455465 -0.045611382, -0.055283174 0.053357258 -0.049001977, 0.072009504 0.017050639 -0.044499159, 0.076180607 0.016219199 -0.049373865, -0.055859044 0.048730031 -0.045609921, 0.073841482 0.01748465 -0.048408344, -0.054799914 0.055350974 -0.049371734, -0.052878872 0.058695391 -0.049496695, 0.075146869 0.015999064 -0.049004152, -0.054601163 0.05269894 -0.048406243, 0.073071018 0.017302081 -0.047616571, -0.054056481 0.05460006 -0.049001753, -0.054031566 0.052149072 -0.047614619, 0.074219614 0.015801832 -0.048408449, 0.072491407 0.017164826 -0.0466685, -0.05338946 0.053926378 -0.048406333, -0.053603068 0.051735461 -0.046666518, 0.07344529 0.015636861 -0.047616646, -0.052832261 0.053363562 -0.04761456, 0.07213138 0.017079577 -0.045611739, 0.076900065 0.012366071 -0.049374014, 0.078227922 0.011020765 -0.049499601, -0.053336754 0.051478386 -0.045609713, -0.052064925 0.052588195 -0.044497222, 0.072862715 0.015512705 -0.04666853, -0.052134305 0.057868883 -0.049371421, -0.052413166 0.052940249 -0.046666443, 0.075856552 0.012198418 -0.049004331, 0.072500914 0.015435547 -0.045611858, -0.051426798 0.057083771 -0.049001783, 0.073061809 0.011748776 -0.044499427, 0.077126175 0.010865569 -0.049374133, -0.052153036 0.052677274 -0.045609742, 0.07492052 0.012047768 -0.048408523, -0.050613612 0.059203506 -0.049371347, -0.048655778 0.062241018 -0.049496517, -0.050792202 0.056379303 -0.048406139, 0.076079845 0.010718152 -0.049004301, -0.049926683 0.05839999 -0.0490015, 0.074138805 0.011922121 -0.04761675, -0.050262138 0.055791095 -0.047614366, 0.075140968 0.010586038 -0.048408717, -0.049310789 0.057679474 -0.04840605, 0.073550761 0.011827514 -0.046668798, -0.049863592 0.05534859 -0.046666279, 0.074357003 0.010475546 -0.047616974, 0.073185727 0.011768654 -0.045611948, -0.048796266 0.057077855 -0.047614351, 0.0737672 0.010392413 -0.046668842, -0.049616098 0.055073649 -0.045609578, -0.048087493 0.056248456 -0.044496924, 0.07759729 0.0067199469 -0.049374491, 0.078805894 0.0055369884 -0.049499795, -0.047970623 0.061364561 -0.049371213, 0.07340087 0.01034081 -0.045612127, -0.048409104 0.056625068 -0.046666324, 0.076544315 0.0066287369 -0.049004629, -0.047319561 0.060531899 -0.04900153, -0.048168823 0.056343734 -0.04560934, 0.075599998 0.0065466762 -0.048408896, -0.046735868 0.059785083 -0.04840593, -0.046157211 0.062740073 -0.049371153, -0.044195876 0.065483704 -0.049496442, -0.046248123 0.05916132 -0.047614157, -0.045530885 0.061888829 -0.049001575, -0.04588148 0.058691978 -0.046666116, -0.044969052 0.061125234 -0.048405856, -0.045653731 0.058400586 -0.045609325, -0.043853492 0.059608564 -0.04449676, -0.044499785 0.06048733 -0.047614023, -0.04357329 0.064561293 -0.049371079, -0.044146881 0.060007662 -0.04666613, -0.042982206 0.063685536 -0.049001291, -0.043927819 0.059709609 -0.045609087, -0.042451814 0.062899292 -0.048405647, -0.041454419 0.065941975 -0.049371004, -0.039520442 0.068406954 -0.049496338, -0.042008772 0.062243223 -0.047613949, -0.040891975 0.065047145 -0.049001187, -0.041675672 0.061749563 -0.046666041, -0.040387481 0.064244583 -0.048405588, -0.041468605 0.061442807 -0.045609236, -0.039385468 0.0626508 -0.044496506, -0.038963944 0.067443669 -0.049370915, -0.039966136 0.063574269 -0.047614008, -0.038435087 0.066528514 -0.049001157, -0.03964892 0.063069999 -0.046665892, -0.037960887 0.06570752 -0.048405349, -0.03945221 0.062756896 -0.045609117, 0.076242372 -0.015920833 -0.049375668, -0.036530495 0.068791956 -0.04937084, -0.034652531 0.070997179 -0.049496055, 0.075207978 -0.015704736 -0.049005866, 0.073860541 -0.021152645 -0.049006239, -0.037564874 0.065021992 -0.047613814, 0.072949395 -0.020891592 -0.048410416, -0.036034912 0.067858621 -0.049001068, -0.037266865 0.064506054 -0.046665743, 0.072188154 -0.020673618 -0.047618717, -0.035590276 0.06702131 -0.048405498, 0.071615502 -0.020509556 -0.046670794, -0.037081882 0.064185902 -0.045608982, -0.034707412 0.065358534 -0.044496581, 0.07126002 -0.02040796 -0.045613945, 0.071139425 -0.020373285 -0.0445012, -0.034164339 0.0699974 -0.049370691, -0.067627743 0.03035149 -0.0456108, -0.035219014 0.066322073 -0.047613725, -0.065288901 0.035101146 -0.045610756, -0.033700898 0.06904766 -0.049000993, -0.062617213 0.039671764 -0.045610458, -0.059626237 0.044039905 -0.045610011, -0.034939691 0.065795809 -0.046665683, -0.0088558048 0.077385128 -0.049370244, -0.0095466077 0.077302992 -0.049370363, -0.0082812011 0.07856755 -0.049495727, -0.033285022 0.068195462 -0.048405305, -0.0094170421 0.076253995 -0.049000531, -0.034766108 0.065469161 -0.045608893, -0.0071665496 0.07719712 -0.049273521, -0.0060238391 0.077656955 -0.049370468, -0.0027805418 0.078953773 -0.049495682, -0.031411916 0.071274951 -0.049370781, -0.029615775 0.073241353 -0.04949601, -0.0038785338 0.077793494 -0.049370289, -0.032937869 0.067484036 -0.04761368, -0.0033100992 0.07781975 -0.049370348, -0.0038260072 0.076738 -0.049000666, -0.030985832 0.070308194 -0.049000889, -0.0015963912 0.077512577 -0.049273461, -0.032676607 0.066948771 -0.046665519, -0.00046572089 0.077888727 -0.049370378, 0.0027334839 0.078955635 -0.049495742, 0.0018101484 0.077869207 -0.049370393, 0.0022525042 0.077857599 -0.049370214, 0.0017856807 0.07681255 -0.049000695, -0.030603319 0.06944041 -0.048405394, -0.032514289 0.066616207 -0.045608819, -0.02984409 0.067717373 -0.044496149, -0.029198676 0.072209954 -0.049370766, 0.0039819926 0.077426702 -0.049273461, 0.0050944239 0.077723533 -0.049370363, 0.0082342625 0.078572363 -0.049495712, 0.0074892342 0.077529311 -0.049370453, -0.030284107 0.068715975 -0.047613665, 0.0078038275 0.077498302 -0.049370274, 0.0073875487 0.076477334 -0.049000695, -0.028802603 0.071230307 -0.049000755, -0.030043811 0.068170711 -0.046665594, 0.013694897 0.077806741 -0.049495712, -0.028447136 0.070351273 -0.048405245, 0.01312834 0.076775894 -0.049370363, 0.032744721 0.066503376 -0.045608982, 0.032474443 0.066635847 -0.045608938, 0.032636628 0.066968158 -0.046665654, 0.032958567 0.066257507 -0.044496387, 0.037228361 0.064528525 -0.046665639, 0.037043542 0.064208135 -0.045609087, -0.02989465 0.0678325 -0.045608953, 0.037407964 0.063996568 -0.045609072, -0.028150439 0.069617331 -0.047613531, 0.041638732 0.061774388 -0.046665892, 0.041879937 0.061163396 -0.045609221, -0.02612561 0.073377848 -0.049370646, -0.024434775 0.075129107 -0.049495935, -0.027926952 0.069065094 -0.046665773, -0.025770947 0.072382167 -0.049000904, 0.077649131 0.0060896724 -0.049374387, -0.027788386 0.068721965 -0.045608684, -0.024821609 0.06971544 -0.044496045, -0.025453061 0.071489096 -0.048405349, 0.077402204 0.0043869764 -0.049277559, 0.07781972 0.0032496899 -0.049374565, 0.079000056 2.6509166e-05 -0.049500167, 0.077880636 0.0010376424 -0.049374744, -0.024090663 0.074070945 -0.049370661, 0.077885628 0.00053179264 -0.049374714, 0.076823875 0.0010235161 -0.049004897, -0.025187567 0.070743456 -0.047613502, -0.023763835 0.073065951 -0.04900071, 0.077517048 -0.0011908114 -0.049277961, 0.077853009 -0.0023130178 -0.049374878, 0.078809291 -0.0054844022 -0.049500376, -0.024987653 0.070182011 -0.046665445, 0.077748239 -0.0046499521 -0.049375042, 0.077724785 -0.0050287694 -0.049375102, 0.076693356 -0.0045869052 -0.049005121, -0.023470446 0.072164297 -0.048405185, -0.024863631 0.069833636 -0.045608655, 0.077230588 -0.0067624152 -0.049278229, 0.077489153 -0.0078639388 -0.049375191, 0.078234479 -0.010968626 -0.049500659, -0.02322574 0.071411431 -0.047613546, 0.077201262 -0.01031284 -0.049375311, 0.077167451 -0.010563552 -0.049375385, 0.076153815 -0.010173023 -0.049005523, -0.020699859 0.075089306 -0.049370587, -0.01913473 0.076650485 -0.049495697, -0.023041368 0.070844874 -0.046665415, -0.020418972 0.074070349 -0.049000546, -0.063058898 0.039665058 -0.046667233, -0.022927016 0.070493102 -0.04560861, -0.019666731 0.071341306 -0.04449603, -0.060102791 0.044015959 -0.046666965, -0.018865228 0.075571045 -0.049370408, -0.0085620582 0.075600818 -0.048555657, -0.0093007833 0.075313002 -0.048404858, -0.020166934 0.073156327 -0.048405007, -0.0092036873 0.074527174 -0.047613338, -0.008190915 0.075744614 -0.048626974, -0.01860927 0.074545607 -0.049000725, -0.019956514 0.07239309 -0.047613442, -0.018379584 0.073625624 -0.048405126, -0.0048844963 0.076678082 -0.049000606, -0.019798219 0.071818799 -0.04666546, -0.0054192692 0.075993225 -0.048626766, -0.018188 0.072857693 -0.047613487, -0.0048710108 0.075927928 -0.048555508, -0.0037786812 0.075791076 -0.048405066, -0.003739208 0.075000286 -0.047613129, -0.019700065 0.071462274 -0.045608535, -0.0030481815 0.076022968 -0.048555598, -0.01516369 0.076399893 -0.049370497, -0.013741404 0.077798441 -0.049495667, -0.0026815385 0.076138929 -0.048626915, -0.018043697 0.072279677 -0.046665251, -0.014957815 0.075363263 -0.04900068, -0.017954066 0.071920767 -0.045608625, 0.00066305697 0.076830551 -0.049000591, -0.014406756 0.072586641 -0.044495896, -0.013547853 0.076702803 -0.049370378, 0.00010094047 0.07618618 -0.048626781, -0.014773384 0.074433237 -0.048404872, 0.00065672398 0.076081172 -0.048555523, 0.0017634928 0.075864807 -0.048404962, 0.0024815947 0.076043621 -0.048555568, 0.001745224 0.075073257 -0.047613353, -0.013364196 0.075662196 -0.049000561, -0.014619157 0.073656663 -0.047613382, 0.0028420389 0.076133072 -0.048626989, -0.013199151 0.074728519 -0.048405066, -0.01450333 0.073072478 -0.046665236, 0.0062072873 0.076582253 -0.049000636, -0.013061434 0.073948741 -0.047613233, -0.014431268 0.072709575 -0.045608565, 0.0056206286 0.075978518 -0.048626825, 0.006180957 0.075832546 -0.048555568, -0.012957931 0.073362395 -0.046665356, -0.012893528 0.072997957 -0.04560867, 0.012950212 0.075734109 -0.049000695, -0.0091307312 0.073936105 -0.046665236, 0.037411481 0.064422414 -0.046665773, 0.041864023 0.06162183 -0.046665981, 0.046107963 0.058514252 -0.046666116, 0.076801673 0.0021147728 -0.049004793, 0.075875953 0.0010109544 -0.048409253, 0.076753646 -0.0034345239 -0.049005151, 0.018697336 0.075612694 -0.049370378, 0.019088939 0.07666187 -0.049495712, 0.018443763 0.07458666 -0.049000636, 0.076305404 -0.0089662522 -0.049005255, 0.018215999 0.073666498 -0.048405036, 0.018026039 0.072897822 -0.047613382, 0.017883047 0.072319627 -0.04666546, 0.017794207 0.071960613 -0.045608655, 0.017764121 0.071838737 -0.04449603, 0.024046302 0.074085444 -0.049370527, 0.024389878 0.075143576 -0.049495816, 0.023720235 0.073080078 -0.04900077, 0.023427457 0.072178364 -0.04840523, 0.023183048 0.071425423 -0.047613591, 0.022999138 0.070858523 -0.046665341, 0.022885039 0.070506677 -0.04560867, 0.022960559 0.070350364 -0.04449603, 0.029155672 0.072227374 -0.049370632, 0.029572085 0.073259041 -0.049496025, 0.028760001 0.071247399 -0.049000889, 0.028405175 0.070368335 -0.04840517, 0.028108701 0.06963411 -0.047613591, 0.027885854 0.06908153 -0.046665549, -0.0037097335 0.074405462 -0.046665311, 0.027747333 0.068738833 -0.045608729, 0.028034285 0.068486691 -0.044496313, 0.034122795 0.07001771 -0.049370751, 0.034610361 0.071017817 -0.049496174, 0.033659726 0.069067851 -0.049000964, 0.033244297 0.068215355 -0.048405364, 0.032897562 0.067503721 -0.047613621, 0.0009239912 0.075207055 -0.047757357, 0.0011977702 0.075163066 -0.047709808, 0.038923547 0.06746693 -0.04937081, 0.039479584 0.068430632 -0.049496174, 0.0017314553 0.074477658 -0.0466654, 0.004509449 0.058015436 0.020638227, 0.0017997324 0.058162764 0.020638376, 0.0017838776 0.057646126 0.019047767, 0.0044694245 0.057500318 0.019047558, 0.0018603206 0.060116768 0.023329675, -0.0001834929 0.06149824 0.024312884, -0.00017938018 0.060145348 0.023329765, -0.00017607212 0.059026301 0.02208671, 0.0018257797 0.058998197 0.02208671, 0.0047657788 0.061313644 0.024312913, 0.0065381825 0.057302132 0.019047648, 0.0065183938 0.057128355 0.01738435, 0.0045742095 0.058849007 0.022086769, 0.0065969229 0.057815343 0.020638317, 0.0046609044 0.059964761 0.023329824, 0.0090817809 0.056954205 0.019047618, 0.011213899 0.05639492 0.01738435, 0.0066915154 0.058646172 0.02208674, 0.0091630816 0.057464585 0.020638376, 0.0068184137 0.059758037 0.023329794, 0.0096842051 0.060731381 0.024312735, 0.011247873 0.056566343 0.019047529, 0.0092948377 0.058290124 0.02208674, 0.011348635 0.057073236 0.020638376, 0.0094711185 0.059395283 0.023329586, 0.013635397 0.056038737 0.019047618, 0.015832722 0.055276275 0.017384231, 0.011511803 0.057893246 0.02208674, 0.013757557 0.056540683 0.020638287, 0.011730164 0.058990806 0.023329705, 0.014539629 0.059755206 0.024312794, 0.015880823 0.05544436 0.019047499, 0.013955265 0.057353258 0.02208662, 0.01602301 0.055940986 0.020638287, 0.01421985 0.058440551 0.023329675, 0.01810056 0.054759786 0.019047499, 0.020343512 0.053780019 0.017384171, 0.016253322 0.056744799 0.02208662, 0.018262714 0.055250466 0.020638317, 0.016561717 0.057820424 0.023329616, 0.019300997 0.058391392 0.024312735, 0.020405114 0.053943709 0.019047409, 0.018525034 0.056044415 0.02208665, 0.020588011 0.054426774 0.020638138, 0.018876374 0.057106927 0.023329437, 0.022448152 0.053125888 0.019047409, 0.024715126 0.05191645 0.017383963, 0.020883918 0.055208892 0.022086471, 0.022649348 0.053601801 0.020638168, 0.021279812 0.05625543 0.023329377, 0.023937076 0.056648955 0.024312496, 0.024790108 0.052074105 0.019047379, 0.022974819 0.054371938 0.022086591, 0.025012463 0.052540749 0.020637959, 0.02341035 0.055402815 0.023329347, 0.026650399 0.051147163 0.01904729, 0.028917879 0.049698025 0.017383903, 0.02537182 0.053295583 0.022086382, 0.026889235 0.051605359 0.020638019, 0.02585277 0.05430612 0.023329288, 0.028418005 0.054539189 0.024312586, 0.029005826 0.049849242 0.01904726, 0.027275532 0.052346975 0.022086352, 0.02926591 0.0502958 0.020637929, 0.027792752 0.053339377 0.023329228, 0.030679762 0.048836887 0.019047201, 0.0329234 0.047140315 0.017383665, 0.029686272 0.051018506 0.022086263, 0.030954599 0.0492744 0.02063787, 0.030249149 0.051985741 0.023329139, 0.032714486 0.052075624 0.024312168, 0.033023387 0.04728356 0.019047022, 0.031399429 0.049982473 0.022086203, 0.033319205 0.04770726 0.02063781, 0.03199473 0.050930083 0.023329228, 0.034510136 0.046209812 0.019046962, 0.036703765 0.044260561 0.017383665, 0.033798248 0.048392713 0.022086114, 0.034819305 0.04662393 0.020637542, 0.034439042 0.049310178 0.023329198, 0.036798909 0.049274355 0.024312258, 0.036815345 0.044395074 0.019046873, 0.035319611 0.047293708 0.022085905, 0.037145436 0.044792801 0.020637572, 0.03598921 0.04819037 0.02332899, 0.038116619 0.043283015 0.019046932, 0.040233523 0.041078568 0.017383426, 0.037679046 0.045436397 0.022085965, 0.059122652 -0.016935453 0.024308458, 0.060293779 -0.012123153 0.024308741, 0.057822034 -0.016562819 0.023325264, 0.038458034 0.043670863 0.020637572, -0.053987727 0.020289764 0.019045576, -0.055277258 0.01583153 0.017382085, -0.053780898 0.020342276 0.017382309, -0.055445358 0.01587972 0.019045249, 0.038393348 0.046297714 0.023328841, 0.040644586 0.046153352 0.024312019, -0.054471463 0.020471483 0.020636246, 0.039010823 0.044298306 0.022086054, -0.055942252 0.016021878 0.020635992, -0.055254206 0.020765573 0.022084564, -0.056746095 0.016252086 0.022084206, 0.040355891 0.041203186 0.019046783, -0.056301758 0.021159261 0.023327336, -0.057568312 0.02163516 0.024310723, -0.059122548 0.016932636 0.02431038, 0.039750278 0.045138136 0.023328811, -0.057821885 0.016560018 0.023327231, 0.040717542 0.041572347 0.020637482, -0.052179947 0.024568126 0.019045874, -0.051917389 0.024714038 0.017382458, -0.052647546 0.024788141 0.020636514, 0.041475877 0.040075704 0.019046664, 0.043488428 0.037615702 0.017383218, 0.041302592 0.042169735 0.022085696, -0.053404033 0.025144294 0.022084877, 0.041847512 0.040434554 0.020637363, -0.054416418 0.025621071 0.023327649, -0.055640548 0.02619721 0.024310872, 0.042085633 0.042969078 0.023328662, -0.050033689 0.028687075 0.019046009, -0.049699157 0.02891694 0.017382771, 0.044226602 0.042733267 0.024311692, 0.042448878 0.041015461 0.022085786, -0.050481975 0.028944165 0.020636722, -0.051207423 0.029360011 0.022085041, 0.043620795 0.037729874 0.019046575, 0.04325363 0.041793123 0.023328602, -0.052178234 0.029916614 0.023327976, -0.053352058 0.030589551 0.02431114, 0.044566184 0.036608145 0.019046366, 0.046446189 0.033895835 0.017383069, 0.044011399 0.038068071 0.020637304, -0.047563016 0.032620311 0.019046307, -0.047141373 0.032922313 0.017383099, 0.044965699 0.036936045 0.020637155, -0.047989354 0.032912448 0.020636842, 0.044644073 0.038614869 0.022085637, -0.04867892 0.033385262 0.022085324, 0.045611843 0.03746675 0.022085637, -0.049601838 0.034018129 0.02332814, -0.050717413 0.034783363 0.024311498, 0.045490339 0.039347053 0.023328424, 0.047521994 0.039035976 0.024311632, -0.044783935 0.036341742 0.019046575, -0.044261605 0.036702722 0.017383233, 0.046587452 0.033999071 0.019046217, -0.045185089 0.036667258 0.02063708, 0.046476454 0.038177356 0.023328394, -0.045834497 0.037194014 0.022085413, 0.047367468 0.032903343 0.019046307, 0.049086809 0.029944614 0.017382801, -0.046703458 0.037899271 0.023328349, 0.047004744 0.034303546 0.020636916, -0.047754034 0.038751721 0.024311498, -0.041714355 0.039827377 0.019046813, 0.047792032 0.033198312 0.020636916, -0.041079417 0.04023248 0.017383471, 0.047680348 0.034796342 0.022085458, 0.048478752 0.033675179 0.022085279, -0.042088032 0.04018423 0.020637348, -0.0426929 0.040761605 0.022085622, 0.048584387 0.035456017 0.023328215, 0.05050911 0.035085544 0.024311364, -0.043502301 0.041534349 0.023328543, -0.044480875 0.042468607 0.024311751, 0.049236029 0.030035615 0.019045979, 0.049397916 0.034313604 0.023328245, -0.038374051 0.043054789 0.019046947, -0.037616611 0.043487191 0.01738371, 0.049861655 0.028985307 0.019046009, 0.051391944 0.025788873 0.017382354, -0.038718075 0.04344067 0.020637512, 0.049677059 0.030304745 0.020636618, -0.039274424 0.044064745 0.02208592, 0.05030854 0.029244721 0.020636797, -0.04001902 0.044900134 0.023328707, 0.050391018 0.030740023 0.0220851, -0.040919289 0.045910224 0.024311855, -0.034785047 0.046003163 0.019046992, -0.033896878 0.046445221 0.017383665, 0.051031336 0.029665172 0.0220851, -0.035096675 0.046415299 0.020637691, 0.051346391 0.031322837 0.023327976, 0.053168625 0.030907318 0.024311125, 0.051548257 0.025867224 0.019045711, -0.035601214 0.047082081 0.022086173, 0.051998898 0.030227467 0.023327976, -0.036276147 0.047974735 0.023329124, 0.052010387 0.026098922 0.020636499, -0.037092149 0.049053907 0.024312064, -0.030970529 0.048652887 0.019047096, -0.029945761 0.049085721 0.017383978, 0.052757651 0.026473805 0.022084922, -0.031248197 0.049089044 0.02063784, 0.053757861 0.026975751 0.023327827, 0.055483386 0.026528701 0.024310976, -0.03169702 0.049794033 0.022086233, 0.053508297 0.021522075 0.019045681, 0.053346261 0.021456972 0.017382324, -0.032298133 0.050738394 0.023329258, -0.033024535 0.051879629 0.024312288, 0.05398798 0.021714702 0.020636261, -0.026954994 0.050987214 0.019047365, -0.025789768 0.051390871 0.017383918, 0.054763749 0.022026703 0.022084743, 0.055801988 0.022444218 0.023327559, -0.025868237 0.05154711 0.01904729, -0.027196646 0.051444113 0.020637989, 0.057438284 0.021978393 0.024310499, 0.055103108 0.017029732 0.019045323, 0.054935947 0.016978353 0.017382085, 0.056150511 0.012383789 0.017381936, -0.026100025 0.052009001 0.020638123, 0.055596814 0.017182216 0.020636052, -0.027587399 0.05218336 0.022086293, 0.056395575 0.017429307 0.022084415, -0.026475281 0.052756429 0.022086203, -0.02811043 0.053172365 0.023329228, -0.02874285 0.054368585 0.024312556, 0.057464883 0.017759651 0.023327172, 0.059020519 0.017285302 0.02431035, -0.022764847 0.052990869 0.01904726, -0.021457776 0.053345263 0.017384216, 0.056321159 0.01242128 0.019045085, -0.026977062 0.053756565 0.023329332, -0.024274632 0.056505293 0.02431266, 0.056825802 0.012532666 0.020635724, 0.057642549 0.012712479 0.022084117, -0.021523058 0.053507283 0.019047424, -0.022968754 0.05346559 0.020638108, 0.058735386 0.012953311 0.023327053, -0.02171579 0.053986594 0.020638138, 0.060220271 0.012479857 0.024310052, 0.05715473 0.0077277422 0.019044816, 0.056981504 0.0077045411 0.017381549, -0.02329877 0.054233864 0.022086456, -0.022028014 0.054762423 0.022086442, 0.057666764 0.0077969581 0.020635456, -0.023740679 0.055262178 0.023329467, 0.058495477 0.0079090297 0.022083849, -0.018426746 0.054650888 0.019047588, -0.016979262 0.054934964 0.017384186, 0.059604451 0.0080590248 0.023326755, 0.061029285 0.0075936168 0.024309903, -0.022445694 0.055800587 0.023329362, -0.019649029 0.058275253 0.024312779, -0.017030999 0.055102006 0.019047469, 0.057597622 0.0029818118 0.019044578, 0.057423115 0.0029726923 0.017381415, -0.018592089 0.055140555 0.020638093, 0.058113873 0.0030083805 0.020635188, -0.017183512 0.055595636 0.020638138, 0.058948919 0.0030514449 0.022083625, -0.018859088 0.05593279 0.022086784, 0.060066476 0.0031094551 0.023326308, 0.061442465 0.0026582927 0.024309501, -0.017430335 0.056394428 0.022086576, 0.057647198 -0.0017848462 0.019044384, 0.057472482 -0.0017793328 0.017380983, -0.019216716 0.056993246 0.023329422, -0.013969541 0.055956364 0.019047603, -0.012384683 0.056149349 0.017384231, 0.058163926 -0.0018008351 0.020634994, -0.017760843 0.057463408 0.023329496, 0.058999568 -0.0018268079 0.022083372, -0.014895946 0.059667364 0.024312764, -0.014094621 0.056457773 0.020638272, 0.060118303 -0.0018617064 0.023326114, 0.061457321 -0.0022945851 0.024309248, -0.012422353 0.056320101 0.019047707, 0.057303086 -0.0065391958 0.019044101, 0.057129413 -0.0065194517 0.017380789, -0.014297187 0.057268992 0.022086635, 0.057816595 -0.0065978467 0.020634636, -0.012533545 0.056824625 0.020638287, -0.014568269 0.058354691 0.023329675, 0.058647409 -0.0066928864 0.022082999, -0.01271376 0.057641298 0.022086591, 0.059759289 -0.0068197846 0.023325861, -0.0094215274 0.056899101 0.019047558, -0.0077055693 0.056980312 0.01738432, 0.061073482 -0.0072321743 0.024309054, 0.05656758 -0.01124908 0.019043759, 0.056395963 -0.011214718 0.017380446, 0.055277288 -0.015833691 0.017380312, -0.01295498 0.058734 0.023329616, -0.010046482 0.060672551 0.024312764, 0.055445418 -0.015881807 0.019043431, -0.0095059574 0.057408735 0.020638332, 0.057074428 -0.011349872 0.020634428, 0.055942208 -0.016024053 0.020634219, 0.057894543 -0.011513025 0.022082776, -0.0077289045 0.057153553 0.019047618, -0.0096424818 0.058233678 0.02208671, 0.056746095 -0.016254619 0.022082537, 0.058992207 -0.011731282 0.023325607, -0.0077983141 0.057665601 0.020638436, -0.0098253787 0.059337795 0.023329571, -0.00481233 0.057472691 0.019047707, -0.0029736459 0.057422087 0.01738441, -0.0079101622 0.058494091 0.02208668, -0.0048556328 0.057987496 0.020638347, -0.0080601573 0.059602976 0.023329705, -0.0051314533 0.061284155 0.024312794, -0.0029827058 0.05759646 0.019047707, -0.0049253106 0.058820859 0.02208671, -0.0030093491 0.058112621 0.020638347, -0.0050187111 0.059936047 0.023329705, -0.000172019 0.057673499 0.019047558, 0.0017786324 0.057471305 0.01738435, -0.0030528307 0.058947653 0.022086829, -0.00017365813 0.058190256 0.020638287, -0.0031105578 0.060065225 0.023329675, -0.071338341 -0.0014462024 0.030199796, -0.071246773 0.0038888305 0.030200049, -0.072457358 -0.0014688224 0.031442612, -0.069895834 0.0038153231 0.029217079, -0.069985628 -0.0014187396 0.029216781, -0.072364345 0.0039499104 0.031442985, 0.012249917 -0.071431041 0.031438738, 0.0088828504 -0.071927503 0.031438693, 0.012391344 -0.072255418 0.032887056, 0.0089854896 -0.072757646 0.032887071, 0.0069571435 -0.07297945 0.032887191, 0.0090488642 -0.073270649 0.03447783, -0.073199317 0.0039954484 0.032891437, -0.072695956 0.0094543844 0.03289175, -0.073715299 0.0040234774 0.034482047, 0.007006228 -0.073493943 0.034477711, -0.073208481 0.0095209926 0.034482315, 0.0036764145 -0.073735654 0.034477562, 0.0036850572 -0.073910326 0.036140859, -0.071866646 0.0093465596 0.031443313, 0.011832237 -0.068994492 0.029212907, 0.0087456405 -0.07081677 0.030195758, 0.012060821 -0.070328146 0.030195758, 0.0066432953 -0.069685847 0.029212862, -0.072292045 0.014965326 0.034482628, -0.073348135 0.009798646 0.036145687, -0.072436854 0.015126616 0.036146, -0.070971519 0.020325869 0.034482941, 0.0068777055 -0.072146848 0.031438679, -0.069415137 0.0090278387 0.029217333, -0.070756972 0.0092022866 0.030200511, 0.0036506802 -0.073219463 0.032886952, -0.071786061 0.014860675 0.032891944, -0.070474476 0.020183459 0.032892391, 0.0014945418 -0.073811948 0.034477592, -0.001719743 -0.07398209 0.036140978, -0.070967078 0.014691114 0.031443536, -0.069670692 0.019953564 0.031443968, 0.0067714602 -0.071032673 0.030195951, 0.0036089271 -0.07238403 0.031438813, -0.069871321 0.014464244 0.03020075, -0.068594858 0.019645378 0.030200899, -0.06854634 0.014190108 0.029217735, 0.0014840066 -0.073295206 0.032886997, -0.0017157197 -0.073807284 0.034477711, 0.0014170855 -0.069987297 0.029212832, 0.003553316 -0.071266413 0.030195758, 0.0014671236 -0.072459117 0.031438723, -0.0017036498 -0.073290452 0.032887116, -0.0040254593 -0.073717311 0.034477726, -0.0071153492 -0.073659196 0.036141068, 0.0014444441 -0.071340129 0.030195773, -0.0016842484 -0.072454363 0.031438664, -0.0039972216 -0.073201165 0.032887086, -0.0070986003 -0.073485032 0.034477651, -0.0038169324 -0.069897577 0.029212937, -0.0016582906 -0.071335405 0.030195966, -0.0039516389 -0.072366253 0.031438842, -0.0070489347 -0.072970614 0.032886997, -0.0095229447 -0.073210478 0.0344778, -0.012473062 -0.07294333 0.036141008, -0.0038905591 -0.07124877 0.030195817, -0.0069684982 -0.072138131 0.031438664, -0.0094562471 -0.072697774 0.032887131, -0.012443528 -0.072770908 0.034477741, -0.0068609118 -0.071024165 0.030195788, -0.0090296268 -0.069416806 0.029212981, -0.0093483776 -0.071868524 0.031438872, -0.012356445 -0.072261319 0.032887086, -0.014967144 -0.072294086 0.034477681, -0.017764077 -0.071838215 0.036140904, -0.0092040151 -0.070758656 0.030195937, -0.01221548 -0.071437076 0.031438783, -0.014862552 -0.071787849 0.032887056, -0.01772213 -0.071668565 0.034477681, -0.012026802 -0.070333913 0.030195922, -0.014191687 -0.068547934 0.029213011, -0.014692873 -0.070968941 0.031438857, -0.017598122 -0.071166575 0.032887191, -0.020327702 -0.070973352 0.034477741, -0.02296038 -0.070349857 0.036141142, -0.014466092 -0.06987305 0.030195847, -0.017397389 -0.070354849 0.031438828, -0.020185366 -0.070476368 0.03288731, -0.022906244 -0.07018362 0.034477845, -0.019274518 -0.06729573 0.029213071, -0.017128572 -0.06926845 0.030195951, -0.019955143 -0.069672436 0.031438768, -0.022745922 -0.06969212 0.03288728, -0.02557455 -0.069255903 0.034477949, -0.028034285 -0.068486243 0.036141142, -0.019647017 -0.068596512 0.030196071, -0.022486299 -0.068897203 0.031438842, -0.025395542 -0.068770885 0.032887295, -0.027967915 -0.068324462 0.034478039, -0.024249494 -0.065667257 0.029213309, -0.022139162 -0.06783329 0.030196026, -0.025105879 -0.067986503 0.031439111, -0.027772248 -0.067845926 0.032887325, -0.030678451 -0.06715104 0.034477934, -0.032958418 -0.066257283 0.036141455, -0.024718285 -0.066936538 0.03019613, -0.027455464 -0.067072019 0.031438947, -0.03046371 -0.066680908 0.032887459, -0.032880634 -0.066100597 0.034477964, -0.027031556 -0.066036195 0.030196294, -0.029088706 -0.06367144 0.02921322, -0.0301162 -0.065920025 0.031439066, -0.032650471 -0.065637827 0.032887533, -0.035610691 -0.064670667 0.034478173, -0.037706897 -0.063674435 0.036141321, -0.029651091 -0.064902231 0.030196339, -0.032277986 -0.064888939 0.031439081, -0.035361335 -0.064217791 0.032887772, -0.037617862 -0.063524097 0.034478202, -0.031779617 -0.063886985 0.030196354, -0.033765525 -0.061319694 0.029213503, -0.03495796 -0.063485339 0.031439304, -0.03735435 -0.063079327 0.032887593, -0.0711395 0.02037403 0.036146194, -0.040343776 -0.061828747 0.034478396, -0.042253956 -0.060752228 0.036141574, -0.03441824 -0.062504873 0.030196443, -0.036928326 -0.062359735 0.031439334, -0.067294061 0.019272819 0.029218078, -0.04006134 -0.061395809 0.032887757, 0.07097137 -0.020329803 0.034480676, 0.069298148 -0.02545616 0.034480438, 0.071139425 -0.020377964 0.036143914, -0.042154372 -0.06060867 0.034478411, 0.069462419 -0.025516465 0.036143735, -0.038253561 -0.05862464 0.029213592, -0.036358222 -0.061396733 0.030196577, 0.07047458 -0.020187497 0.032889947, 0.068813205 -0.025277793 0.032889843, -0.03960444 -0.060695261 0.031439409, 0.068028226 -0.024989441 0.03144145, 0.069670692 -0.019956976 0.031441599, -0.041859269 -0.0601843 0.032887831, 0.067255333 -0.030446693 0.034480035, 0.067414686 -0.030518875 0.036143318, -0.044851452 -0.058640867 0.03447859, -0.04657577 -0.057505891 0.036141843, 0.066977829 -0.024603531 0.03019847, -0.038992971 -0.059758082 0.030196577, 0.065665603 -0.024251118 0.029215455, 0.067294106 -0.019276187 0.029215679, 0.068594828 -0.01964888 0.030198872, 0.066784531 -0.030233428 0.03288959, -0.041381732 -0.059497759 0.031439468, -0.044537246 -0.058230191 0.032887951, 0.066022739 -0.029888451 0.031441033, -0.046465799 -0.057369992 0.034478575, 0.064853653 -0.035274819 0.034479782, 0.065007165 -0.035358399 0.036143154, -0.040742666 -0.058578938 0.030196697, -0.042527348 -0.055602297 0.029213727, 0.065003291 -0.029427081 0.030198157, -0.04402937 -0.057565808 0.031439513, 0.06366989 -0.029090613 0.029215068, 0.064399689 -0.035027742 0.032889038, -0.046140537 -0.056968302 0.032887965, -0.049108103 -0.055125207 0.034478679, -0.050649107 -0.053952754 0.036142111, 0.063664928 -0.034627944 0.031440675, -0.043349475 -0.056676969 0.030196637, 0.062105834 -0.039914697 0.034479633, 0.062252805 -0.04000923 0.036142841, -0.045614317 -0.056318402 0.031439692, 0.062681943 -0.034093425 0.030197978, 0.061317995 -0.033767268 0.029214948, -0.048764139 -0.054739133 0.03288804, 0.061671153 -0.039635152 0.032888994, -0.050529391 -0.053825289 0.034478754, 0.060967669 -0.039182857 0.031440616, -0.044909894 -0.0554488 0.030196905, -0.04656364 -0.052268609 0.029213965, 0.059026718 -0.044341564 0.034479231, 0.05916658 -0.044446677 0.036142573, -0.048208043 -0.054114595 0.031439736, -0.050175712 -0.05344823 0.032888189, 0.060026199 -0.038577959 0.030197591, 0.05862309 -0.038255125 0.02921474, -0.053089976 -0.051301062 0.034478918, -0.054452062 -0.050111547 0.03614223, 0.058613569 -0.044031203 0.0328888, -0.047463551 -0.053278983 0.030196995, 0.057945043 -0.04352887 0.031440347, -0.049603418 -0.052838504 0.031439841, 0.055632725 -0.048531979 0.034479141, -0.05432342 -0.049993068 0.034479037, 0.055764318 -0.048646912 0.036142245, -0.052718446 -0.050941825 0.032888308, 0.057050139 -0.042856634 0.030197486, 0.055600584 -0.042529151 0.029214457, -0.048837528 -0.052022576 0.030197129, 0.055243284 -0.048192367 0.032888383, -0.050339192 -0.048642799 0.029214174, -0.053943202 -0.049643099 0.032888398, 0.054613069 -0.047642291 0.031440049, -0.052117139 -0.050360754 0.031440064, -0.056775317 -0.047190279 0.034479052, 0.051941797 -0.052463576 0.034478754, 0.052064866 -0.052587643 0.036142141, -0.057964742 -0.046003163 0.036142513, 0.053769842 -0.04690671 0.030197293, 0.052267075 -0.04656513 0.029214263, -0.053327948 -0.049076602 0.031440005, 0.051578194 -0.052096084 0.032888144, -0.051312298 -0.049583077 0.030197114, 0.050989896 -0.051501766 0.031440005, -0.057827741 -0.045894578 0.034479186, -0.056377709 -0.046859875 0.032888651, 0.047973961 -0.05611515 0.034478664, -0.05383341 -0.044744968 0.029214457, -0.05250442 -0.048318863 0.030197263, 0.048087493 -0.056248069 0.036141858, 0.050202563 -0.050706431 0.030197054, 0.048641101 -0.05034095 0.029214188, -0.057422802 -0.045572996 0.032888591, -0.055734575 -0.046325296 0.031440347, 0.047638059 -0.055722073 0.032887921, 0.047094569 -0.055086449 0.031439736, -0.056767672 -0.045053184 0.031440243, -0.060142741 -0.042815581 0.03447935, 0.043749869 -0.059467286 0.034478396, -0.061167791 -0.041649267 0.036142617, 0.043853477 -0.059608117 0.036141783, -0.054874063 -0.045609906 0.030197382, 0.046367377 -0.054235741 0.03019689, 0.044743389 -0.053835154 0.029213846, 0.043443635 -0.059050828 0.032887936, -0.06102325 -0.041550905 0.034479454, -0.057026416 -0.040596962 0.029214501, -0.05589141 -0.044357389 0.030197427, -0.059721872 -0.042515635 0.03288877, 0.042947948 -0.058377057 0.031439662, -0.060596168 -0.04125984 0.032888815, -0.059040487 -0.042030573 0.031440318, 0.039292395 -0.06250228 0.034478173, 0.039385453 -0.062650204 0.036141559, 0.040595248 -0.057028279 0.029213652, 0.042284861 -0.05747579 0.030196682, -0.059905052 -0.040789127 0.031440422, 0.039017409 -0.062064469 0.032887548, -0.06317395 -0.038201451 0.034479633, -0.064044744 -0.03707321 0.036142975, 0.038572252 -0.061356381 0.031439424, -0.058128759 -0.041381657 0.03019762, 0.034625441 -0.065203518 0.034478128, 0.034707457 -0.065358087 0.036141336, -0.063893348 -0.03698574 0.034479767, -0.059900746 -0.036221817 0.029214814, -0.058979958 -0.0401593 0.030197665, 0.036220074 -0.059902474 0.029213443, 0.037976816 -0.060409039 0.030196458, -0.062731788 -0.037933782 0.03288886, 0.033371657 -0.065854341 0.034478232, 0.029844031 -0.067717016 0.036141276, 0.034383073 -0.06474708 0.032887563, -0.06344603 -0.036726534 0.032889053, -0.062016249 -0.037501052 0.03144066, 0.033137992 -0.065392897 0.032887489, -0.06272243 -0.036307573 0.031440809, 0.033990905 -0.064008296 0.031439111, 0.032759786 -0.064646989 0.031439215, -0.06585224 -0.033373535 0.034479856, -0.066579923 -0.03229934 0.036143228, -0.061058536 -0.036921784 0.030197799, 0.029773772 -0.067557156 0.034477949, -0.061753765 -0.035747007 0.030197933, 0.033465996 -0.063019902 0.030196264, -0.062440187 -0.031643942 0.029215068, -0.065391064 -0.033139661 0.032889351, 0.031642556 -0.062441826 0.029213235, 0.028357148 -0.068163902 0.03447786, 0.024821684 -0.069714934 0.036141008, 0.032254025 -0.063648686 0.030196324, -0.064645201 -0.032761753 0.031440929, 0.029565245 -0.067084193 0.032887504, -0.068161845 -0.028359041 0.034480125, -0.068759978 -0.027353197 0.036143392, 0.028158635 -0.067686662 0.03288731, -0.063646853 -0.032255813 0.030198127, 0.029227927 -0.06631875 0.031439036, -0.067684546 -0.028160483 0.03288959, 0.027837291 -0.066914394 0.031439066, -0.066912562 -0.027839109 0.031441242, 0.024763048 -0.069550142 0.034477919, 0.028776661 -0.065294772 0.03019616, -0.070090324 -0.023185939 0.034480453, 0.026887789 -0.064631775 0.029213145, -0.070573032 -0.022261038 0.036143705, -0.064630061 -0.026889458 0.029215366, -0.065879285 -0.027409256 0.03019838, 0.023184076 -0.070092306 0.034477875, 0.019666627 -0.071340755 0.036140993, -0.069599763 -0.02302368 0.032889843, 0.027407438 -0.065881073 0.03019622, 0.024589702 -0.069063261 0.032887429, -0.068805814 -0.022760898 0.03144148, 0.023021847 -0.069601655 0.032887235, -0.071626738 -0.017883465 0.03448081, 0.024309233 -0.068275288 0.031439021, -0.072009295 -0.017050207 0.036144033, -0.066458762 -0.021984369 0.029215693, -0.067743286 -0.022409454 0.030198723, 0.01962027 -0.071172252 0.0344778, -0.071125478 -0.017758161 0.032890081, 0.02275914 -0.068807572 0.031438828, 0.021982804 -0.06646052 0.029213086, 0.023933813 -0.06722106 0.03019613, -0.070314184 -0.017555401 0.031441674, 0.017881319 -0.071628809 0.034477875, 0.014406919 -0.072586134 0.036141053, -0.072762951 -0.012480527 0.034481019, 0.019483 -0.070673868 0.032887131, -0.073061809 -0.011748299 0.036144406, -0.067915574 -0.016956538 0.029215947, -0.069228366 -0.017284438 0.030198902, 0.022407681 -0.06774506 0.030196041, -0.072253495 -0.012393191 0.032890454, 0.017756224 -0.0711274 0.03288722, -0.071429238 -0.01225172 0.03144215, 0.019260526 -0.069867581 0.031438738, -0.073491901 -0.0070082098 0.034481481, 0.01437287 -0.072414666 0.034477651, -0.073724359 -0.0063839108 0.036144778, 0.017553702 -0.070315957 0.031438798, -0.068992749 -0.011833817 0.029216245, -0.070326418 -0.012062669 0.0301992, 0.016954869 -0.067917377 0.029212981, 0.018963203 -0.068788797 0.030195966, -0.072977394 -0.0069590658 0.032890841, -0.072145075 -0.0068796128 0.031442419, 0.014272258 -0.071907476 0.032887131, 0.012478575 -0.072764859 0.034477651, 0.0090701729 -0.073444068 0.036140904, -0.073810056 -0.0014965832 0.034481704, -0.073993474 -0.00098533928 0.036145076, 0.01728259 -0.069230214 0.030196056, -0.069684029 -0.0066448897 0.029216498, -0.071031123 -0.0067733973 0.030199349, 0.014109433 -0.071087286 0.031438828, -0.073293284 -0.0014860332 0.032891035, 0.013891563 -0.069989577 0.030195966, -0.073867664 0.0044184625 0.036145121, -0.065709323 -0.0023158044 0.026762992, -0.063424036 -0.0050549358 0.025536031, -0.06144239 -0.0026612282 0.024309337, -0.0610293 -0.007596612 0.024308935, -0.065107524 -0.0091715157 0.02676259, -0.064754471 0.011396512 0.026763722, -0.061778098 -0.022507861 0.02676183, -0.058357611 -0.025350079 0.025534898, -0.05743815 -0.021981135 0.02430822, -0.055483326 -0.026531696 0.024307966, -0.059087083 -0.028842062 0.026761577, -0.060293689 0.012120277 0.024310201, -0.061073467 0.0072294772 0.024309844, -0.059599519 -0.03248097 0.027988344, -0.065591142 0.0045654476 0.02676338, -0.055748716 -0.034860432 0.026761279, -0.0308505 -0.058064565 0.026759863, -0.034504488 -0.058451995 0.027986705, -0.061457142 0.0022914708 0.024309516, -0.036750495 -0.054521829 0.026759893, -0.027335405 -0.057455048 0.025532946, -0.028417781 -0.054542005 0.024306446, -0.023936972 -0.056651816 0.024306372, -0.024612218 -0.060971171 0.026759639, -0.011398017 -0.064756095 0.026759505, -0.0072259754 -0.063215017 0.025532722, -0.0096841902 -0.060734093 0.024305865, -0.0045669377 -0.065592721 0.026759356, -0.004765749 -0.061316326 0.02430591, -0.00065666437 -0.067873672 0.027986348, 0.0023143739 -0.065710843 0.026759386, -0.060220286 -0.012482718 0.024308771, -0.063791975 -0.015927106 0.026762217, 0.033367366 -0.059108794 0.027986631, 0.028840542 -0.059088573 0.026759863, 0.034858882 -0.055750325 0.026759937, 0.037092224 -0.049056739 0.024306655, 0.036088571 -0.052401483 0.025533423, 0.040495411 -0.05180122 0.026760295, -0.059020475 -0.017288014 0.024308398, 0.033024728 -0.051882312 0.024306491, 0.050380021 -0.042249769 0.026760682, 0.051131308 -0.037866116 0.025534108, 0.047754228 -0.038754568 0.02430734, 0.050717533 -0.034786314 0.024307474, 0.054520339 -0.036752135 0.026761025, 0.058450416 -0.034506261 0.027988181, 0.05806312 -0.03085196 0.026761323, -0.053168446 -0.030910373 0.024307847, 0.057568461 -0.021638066 0.02430819, 0.060164884 -0.020697922 0.025535151, 0.060969666 -0.024613693 0.026761815, 0.064183682 -0.022080392 0.027988762, -0.050509036 -0.035088375 0.024307504, -0.051799759 -0.040496781 0.026760831, -0.04752183 -0.039038792 0.024307206, -0.047282919 -0.045689285 0.026760489, -0.044226691 -0.042736158 0.024306923, -0.040644571 -0.046156272 0.024306759, -0.042248234 -0.050381631 0.026760325, -0.036798701 -0.049277186 0.024306759, -0.032714397 -0.052078575 0.024306551, -0.019300833 -0.058394328 0.024306029, -0.018104106 -0.063209876 0.026759461, -0.014539674 -0.059758082 0.024305969, 0.000183478 -0.06150113 0.024305925, 0.0051315278 -0.061286911 0.024305895, 0.0091702193 -0.065109015 0.02675949, 0.010046273 -0.060675368 0.024306014, 0.015925571 -0.063793853 0.026759505, 0.014896065 -0.05967024 0.024306014, 0.019648969 -0.058277965 0.024306089, 0.022506163 -0.061779648 0.026759669, 0.024274722 -0.056507841 0.024306387, 0.02874285 -0.054371417 0.024306327, 0.040919259 -0.045912936 0.024306893, 0.045687929 -0.047284424 0.026760459, 0.044481009 -0.042471528 0.024307102, 0.053352207 -0.030592367 0.024307683, 0.055640638 -0.026200131 0.024307966, -0.061998621 0.014292613 0.025536954, -0.066139832 0.015247062 0.027990907, -0.067854375 0.0016702414 0.027990252, -0.034313455 -0.077769876 0.062995598, -0.039540544 -0.075246841 0.062995777, 0.077766165 -0.034317091 0.062997982, 0.075243235 -0.039544076 0.062997684, -0.028926641 -0.079930097 0.062995464, 0.07992667 -0.028930053 0.062998325, -0.081714258 0.023401126 0.063001171, 0.081714302 -0.023408428 0.062998638, -0.023404762 -0.081717879 0.0629953, -0.083120942 0.017770186 0.063001081, -0.017773807 -0.083124533 0.062995374, -0.084139958 0.012056381 0.06300059, -0.012060016 -0.084143683 0.062995255, -0.084767148 0.0062864423 0.063000277, -0.0062900335 -0.084770501 0.06299518, -0.084998444 0.00048705935 0.063000187, -0.00049053133 -0.085002229 0.062995061, -0.084833965 -0.0053146034 0.062999621, 0.0053110868 -0.084837407 0.062995255, -0.08427377 -0.011091515 0.062999278, 0.011087909 -0.084277257 0.06299524, -0.083320528 -0.016816735 0.062998936, 0.016813219 -0.083324149 0.062995374, -0.081978887 -0.022463545 0.062998727, 0.022459969 -0.081982478 0.062995374, -0.080255255 -0.028005645 0.062998489, 0.028002113 -0.080258682 0.062995419, -0.078157216 -0.033417106 0.062998012, 0.033413634 -0.078160852 0.062995598, -0.075694814 -0.038672835 0.062997773, 0.038669243 -0.075698182 0.062995717, -0.072879314 -0.043748423 0.062997535, 0.043744892 -0.072882891 0.062995747, -0.069724187 -0.048619673 0.062997326, 0.048616469 -0.069727838 0.062996134, -0.066243961 -0.053264499 0.062996849, 0.053261191 -0.066247627 0.062996268, -0.062455058 -0.057661146 0.062996626, 0.057657599 -0.0624585 0.062996507, -0.058374569 -0.061788842 0.062996626, 0.061785251 -0.05837822 0.062996551, -0.054022238 -0.065628245 0.062996328, 0.065624833 -0.054025739 0.062996864, -0.049417824 -0.069161862 0.062996194, 0.069158494 -0.049421474 0.062997192, -0.044583142 -0.072373077 0.062995777, 0.072369486 -0.044586584 0.062997401, -0.083320662 -0.016809613 -0.063001081, 0.0053109974 -0.084830329 -0.063004911, -0.00049060583 -0.084995106 -0.063004866, -0.0842738 -0.011084393 -0.063000664, -0.0062900186 -0.084763512 -0.063004807, -0.084834144 -0.0053074509 -0.063000277, -0.012059972 -0.08413668 -0.063004792, 0.081714317 -0.023401171 -0.063001454, 0.07992664 -0.028923139 -0.063001707, -0.084998682 0.0004940927 -0.063000098, 0.07776618 -0.034310013 -0.06300211, -0.017773852 -0.083117455 -0.063004762, -0.084766939 0.0062936693 -0.06299974, -0.023404866 -0.081710756 -0.063004866, 0.075243339 -0.039537013 -0.063002273, -0.084140122 0.012063518 -0.062999487, -0.028926551 -0.079923198 -0.063004628, 0.072369441 -0.044579566 -0.06300281, -0.083121076 0.017777309 -0.062999204, -0.034313515 -0.077762783 -0.063004375, -0.081714258 0.023408234 -0.062998652, 0.06915845 -0.049414381 -0.063002914, -0.039540365 -0.075239867 -0.0630043, 0.065624714 -0.054018691 -0.063003108, -0.044583216 -0.072366014 -0.063004047, 0.061785161 -0.058371097 -0.063003376, -0.049417883 -0.069154903 -0.063003808, 0.05765748 -0.062451497 -0.063003555, -0.054022133 -0.065621287 -0.063003719, 0.053261116 -0.066240475 -0.063003838, -0.058374673 -0.06178163 -0.063003555, 0.04861629 -0.069720864 -0.063003972, -0.062454984 -0.057653964 -0.063003346, 0.043744773 -0.072875872 -0.063004211, -0.066244096 -0.053257599 -0.063003078, 0.038669273 -0.075691164 -0.063004255, -0.069724351 -0.048612669 -0.063002676, 0.033413589 -0.07815361 -0.063004643, -0.072879419 -0.043741196 -0.063002616, 0.028002128 -0.080251828 -0.063004673, -0.07569474 -0.038665816 -0.063002378, 0.022460088 -0.08197552 -0.063004762, -0.078157201 -0.033410043 -0.063001931, 0.016813174 -0.083317012 -0.063004792, -0.080255091 -0.027998507 -0.063001797, 0.011087909 -0.084270224 -0.063004911, -0.081978917 -0.022456512 -0.063001484, 0.01624541 0.042191148 -0.0014977157, 0.01586993 0.041302904 -0.0014977455, 0.016245425 0.042191073 0.0015022755, 0.015870079 0.04130277 0.0015022755, 0.015293077 0.04053022 -0.0014977157, 0.015293106 0.040530086 0.0015022457, 0.014547914 0.03991805 -0.0014977753, 0.014547884 0.039917976 0.0015022159, 0.013677925 0.039502189 -0.0014978945, 0.013677999 0.039502189 0.0015022457, 0.012733743 0.039306432 -0.0014978647, 0.012733668 0.039306283 0.0015021563, 0.011770144 0.039342538 -0.0014980137, 0.011770114 0.039342314 0.0015021265, 0.010843128 0.039607912 -0.0014978349, 0.010843053 0.039607912 0.0015022457, 0.010006517 0.040087774 -0.0014978945, 0.010006398 0.040087521 0.0015022159, 0.0093090385 0.040753663 -0.0014976561, 0.0093091875 0.040753469 0.0015022457, 0.0087912232 0.041567057 -0.0014976859, 0.0087912232 0.041566908 0.0015023649, 0.0084831417 0.042480737 -0.0014976263, 0.0084831715 0.042480588 0.0015023351, 0.0084027201 0.043441787 -0.0014976561, 0.0084027052 0.043441623 0.0015024543, 0.0085546374 0.044393912 -0.0014974475, 0.0085546076 0.044393823 0.0015025139, 0.035137966 -0.033486307 -0.0015021116, 0.034762502 -0.03437458 -0.0015021265, 0.035137922 -0.033486396 0.0014980286, 0.034762606 -0.034374699 0.001497969, 0.034185529 -0.035147041 -0.0015020519, 0.034185559 -0.035147384 0.0014979839, 0.033440366 -0.035759255 -0.0015022457, 0.033440411 -0.035759404 0.001497969, 0.032570437 -0.036175221 -0.0015020669, 0.032570377 -0.036175311 0.0014977604, 0.031626195 -0.036370963 -0.0015021414, 0.031626284 -0.036371052 0.0014980584, 0.030662701 -0.036334962 -0.0015020519, 0.030662745 -0.03633514 0.001497969, 0.029735625 -0.036069408 -0.0015021414, 0.029735595 -0.036069587 0.0014979988, 0.028899074 -0.035589874 -0.0015021116, 0.028899178 -0.035590008 0.0014980286, 0.028201669 -0.03492406 -0.0015019178, 0.028201535 -0.034924001 0.0014980584, 0.027683944 -0.034110427 -0.0015019476, 0.027683899 -0.034110591 0.0014979988, 0.027375713 -0.033196703 -0.0015019774, 0.027375713 -0.033196822 0.0014980435, 0.027295291 -0.032235697 -0.0015019029, 0.027295351 -0.032235742 0.0014980733, 0.027446985 -0.031283453 -0.0015018284, 0.027447194 -0.031283647 0.001498282, -0.039847001 -0.012009159 0.0014993548, -0.039846927 -0.012008861 -0.0015007555, -0.040222272 -0.012897387 0.0014992058, -0.040222377 -0.012897149 -0.0015006959, -0.040799156 -0.013669938 0.0014990717, -0.040799558 -0.013669759 -0.0015008301, -0.041544423 -0.014282137 0.0014989376, -0.041544452 -0.014281914 -0.0015008301, -0.042414278 -0.014697999 0.0014991313, -0.042414293 -0.014698029 -0.0015009344, -0.043358698 -0.014893979 0.0014990419, -0.043358579 -0.014893562 -0.001500994, -0.044322208 -0.014857844 0.0014991462, -0.044322208 -0.014857709 -0.0015008599, -0.045249298 -0.014592305 0.0014991015, -0.045249254 -0.014592186 -0.0015008301, -0.046085939 -0.014112622 0.0014991164, -0.0460857 -0.014112622 -0.0015008599, -0.046783298 -0.013446644 0.0014990419, -0.046783283 -0.01344645 -0.0015007704, -0.047301069 -0.012633309 0.0014992505, -0.047301099 -0.01263307 -0.0015008301, -0.047609255 -0.01171945 0.0014992058, -0.047609285 -0.011719227 -0.0015007406, -0.047689542 -0.010758713 0.0014994591, -0.047689542 -0.010758415 -0.0015007108, -0.047537759 -0.0098063946 0.0014995784, -0.047537848 -0.009806186 -0.0015006065, 0.0086264312 -0.025584877 -0.0015016198, 0.011647552 -0.02435866 0.0014984906, 0.011647537 -0.024358481 -0.0015013963, 0.014498621 -0.022777051 0.0014986992, 0.014498621 -0.022776827 -0.0015012473, 0.017138377 -0.020863548 0.0014989078, 0.017138377 -0.020863384 -0.0015012324, -0.025956184 0.0074343979 0.0015003234, -0.026663199 0.0042514652 0.0015002191, -0.025956303 0.0074344724 -0.0014997721, -0.026663259 0.0042516589 -0.0014997274, 0.019528225 -0.018645436 0.0014989525, 0.01952827 -0.018645361 -0.001500994, -0.026981115 0.0010065287 0.0015001446, -0.026981235 0.0010067672 -0.0014999658, 0.021633238 -0.016155601 0.0014990717, 0.021633327 -0.016155422 -0.001500994, -0.02690579 -0.0022528768 0.0014996976, -0.02690585 -0.0022527277 -0.0015000105, 0.023422927 -0.013430253 0.0014992952, 0.023422867 -0.013430059 -0.0015007406, -0.026438043 -0.0054798871 0.001499638, -0.026438057 -0.0054795444 -0.0015004277, 0.024870753 -0.010508969 0.001499325, 0.024871036 -0.010508925 -0.0015007108, -0.025584921 -0.0086265504 0.0014995039, -0.025584921 -0.0086263269 -0.0015004575, 0.025956318 -0.0074345618 0.0014996082, 0.025956318 -0.0074344426 -0.0015004873, -0.024358466 -0.011647478 0.0014992505, -0.024358496 -0.011647463 -0.0015005916, -0.022777051 -0.014498651 0.0014992803, -0.022776961 -0.014498517 -0.0015009046, -0.020863265 -0.017138436 0.0014989823, -0.020863086 -0.017138377 -0.0015010387, -0.01864551 -0.019528136 0.0014987588, -0.018645316 -0.019528165 -0.0015011728, -0.016155511 -0.021633342 0.0014986247, -0.016155407 -0.021633297 -0.0015012771, -0.013430074 -0.023423031 0.001498729, -0.013430178 -0.023422912 -0.0015013367, -0.010508955 -0.024871111 0.0014986694, -0.010508895 -0.024870902 -0.0015014559, -0.0074344575 -0.025956526 0.0014985502, -0.0074343681 -0.025956348 -0.0015015006, -0.0042515695 -0.026663318 0.0014985651, -0.0042516738 -0.02666305 -0.00150159, -0.0010065436 -0.026981354 0.0014984608, -0.0010065138 -0.026981264 -0.0015014708, 0.0022528768 -0.026905969 0.0014984906, 0.0022530258 -0.026905894 -0.0015016198, 0.0054796189 -0.026438251 0.0014985055, 0.0054796785 -0.026438206 -0.0015015751, 0.0086263716 -0.025585026 0.0014984459, -0.020343274 -0.053780153 -0.017384365, -0.015832722 -0.055276141 -0.017384335, -0.011213869 -0.056394905 -0.017384276, -0.0065183938 -0.05712837 -0.017384455, -0.0017783195 -0.057471484 -0.017384589, -0.055277199 0.015833676 -0.017380327, -0.056395844 0.011214688 -0.017380565, -0.057129264 0.006519109 -0.017380804, 0.0029738247 -0.057422027 -0.017384574, -0.057472587 0.0017794371 -0.017381117, 0.0077055097 -0.056980416 -0.017384484, 0.012384728 -0.056149408 -0.017384425, -0.057423115 -0.0029727817 -0.01738131, 0.016979247 -0.054934949 -0.017384365, 0.021457791 -0.053345248 -0.017384306, -0.056981266 -0.007704556 -0.017381638, -0.056150436 -0.01238361 -0.017381966, 0.025789917 -0.051391095 -0.017384112, -0.054935962 -0.016978249 -0.017382249, 0.029945746 -0.049085796 -0.017383978, -0.053346038 -0.021456987 -0.017382324, -0.051391795 -0.025788963 -0.017382741, 0.033896998 -0.046445265 -0.017383948, -0.049086884 -0.029944628 -0.01738292, 0.037616715 -0.043487415 -0.017383695, -0.046446174 -0.033896118 -0.017383143, -0.043488279 -0.037615821 -0.017383337, 0.041079462 -0.040232614 -0.017383635, 0.044261649 -0.036702767 -0.017383352, -0.040233478 -0.041078418 -0.017383575, 0.047141373 -0.032922447 -0.017383084, -0.03670387 -0.044260457 -0.017383724, 0.049699232 -0.028916925 -0.017382801, 0.051917449 -0.024714082 -0.017382726, -0.032923236 -0.047140554 -0.017383963, 0.053781152 -0.020342395 -0.017382264, -0.02891773 -0.049698204 -0.017384082, -0.024714917 -0.05191651 -0.017384186, 0.055277362 -0.015831634 -0.017382145, -0.017764211 -0.071834281 -0.036149293, -0.017764121 -0.071833819 -0.044504195, -0.022960454 -0.070345789 -0.036149099, -0.012473181 -0.0729388 -0.04450421, -0.022960559 -0.070345417 -0.044503927, -0.028034359 -0.068482131 -0.03614901, 0.071139336 -0.020373791 -0.036146343, 0.069462329 -0.025512293 -0.036146507, -0.028034255 -0.068481743 -0.044503912, -0.032958418 -0.066253155 -0.036148965, 0.069462463 -0.02551198 -0.044501498, 0.067414626 -0.030514732 -0.036147103, -0.032958463 -0.066252723 -0.044503808, -0.037706777 -0.063670576 -0.036148772, 0.067414641 -0.030514225 -0.044501737, 0.065007269 -0.035354242 -0.036147252, -0.037706956 -0.063670173 -0.04450354, -0.04225415 -0.060748249 -0.036148474, 0.065007254 -0.035353795 -0.044502035, 0.062252849 -0.040005192 -0.03614746, -0.042254105 -0.060747609 -0.044503495, -0.046575934 -0.057501808 -0.03614819, 0.062253043 -0.040004596 -0.044502363, 0.059166431 -0.044442609 -0.036147669, -0.046575814 -0.057501331 -0.044503272, -0.050649032 -0.053948656 -0.036148265, 0.059166506 -0.044442296 -0.044502527, 0.055764496 -0.048643053 -0.036147907, -0.050649166 -0.053948119 -0.044503123, -0.054452106 -0.050107583 -0.036147878, 0.055764452 -0.048642442 -0.044502884, 0.052064836 -0.05258368 -0.036148116, -0.054452121 -0.050107226 -0.044502929, -0.057964668 -0.04599911 -0.036147729, 0.052064791 -0.052583188 -0.044502959, 0.048087358 -0.056243807 -0.036148354, -0.057964653 -0.045998558 -0.044502646, -0.061167851 -0.041645229 -0.036147565, 0.048087463 -0.056243554 -0.044503182, 0.043853387 -0.059604034 -0.036148459, -0.061167821 -0.041644692 -0.044502541, -0.064044788 -0.037069112 -0.036147177, 0.043853462 -0.059603527 -0.044503346, 0.039385602 -0.062646136 -0.036148623, -0.064044759 -0.037068605 -0.044502258, -0.066579893 -0.032295272 -0.036146998, 0.039385468 -0.062645674 -0.044503614, 0.034707308 -0.06535387 -0.036148846, -0.066579923 -0.032294795 -0.044501826, -0.068759963 -0.02734904 -0.036146775, 0.034707472 -0.065353423 -0.044503719, 0.029844135 -0.067713037 -0.036149025, -0.068759903 -0.027348712 -0.044501543, -0.070572779 -0.02225697 -0.036146477, 0.029844075 -0.06771259 -0.044503853, 0.024821579 -0.069710985 -0.036149204, -0.070572898 -0.022256523 -0.044501349, -0.072009489 -0.01704596 -0.036146134, 0.024821579 -0.069710463 -0.044503957, 0.019666702 -0.071336776 -0.036149129, -0.0720094 -0.017045602 -0.044500992, -0.073061571 -0.01174438 -0.036145866, 0.019666642 -0.07133624 -0.044504121, 0.01440689 -0.072582006 -0.036149234, -0.073061794 -0.011743829 -0.044500813, -0.073724315 -0.0063797235 -0.036145568, 0.014406979 -0.072581545 -0.044504091, 0.0090701431 -0.07344003 -0.036149338, -0.073724255 -0.0063792318 -0.044500306, -0.073993519 -0.00098134577 -0.036145106, 0.0090702176 -0.073439494 -0.0445043, 0.0036850274 -0.073906347 -0.036149278, -0.073993564 -0.00098086894 -0.044499993, -0.073867992 0.0044225752 -0.036144912, 0.0036850572 -0.073905945 -0.04450424, -0.0017198026 -0.073978066 -0.036149278, -0.073867857 0.0044229925 -0.044499859, -0.07334815 0.0098028779 -0.036144674, -0.0017197132 -0.073977575 -0.044504255, -0.073348165 0.0098032057 -0.044499487, -0.072436869 0.015130714 -0.036144346, -0.007115528 -0.073655024 -0.036149338, -0.0071153939 -0.073654607 -0.04450427, -0.072437018 0.015131265 -0.044499353, -0.071139544 0.020377845 -0.036144033, -0.012473091 -0.072939277 -0.036149308, -0.011213765 -0.056397051 0.017378032, -0.0065184087 -0.057130367 0.017377973, -0.0017783046 -0.057473525 0.017378032, 0.0029736757 -0.057424217 0.017377928, -0.056395963 0.01121287 0.017381772, 0.0077055842 -0.056982338 0.017377853, -0.057129294 0.0065173656 0.01738143, 0.012384713 -0.056151435 0.017377898, -0.057472602 0.0017772913 0.017381266, 0.016979322 -0.05493696 0.017378181, -0.057423025 -0.0029747039 0.017381072, -0.056981355 -0.0077064484 0.017380685, 0.021457911 -0.053347155 0.017378151, -0.056150436 -0.012385622 0.017380387, 0.025789797 -0.051393017 0.017378137, -0.054935858 -0.01698029 0.017380178, 0.029945731 -0.049087837 0.017378464, -0.053346217 -0.02145876 0.017380059, 0.033896893 -0.046447232 0.017378569, -0.051391929 -0.02579096 0.017379567, 0.0376167 -0.043489397 0.017378867, -0.049086615 -0.02994667 0.017379537, 0.041079506 -0.040234566 0.017378986, -0.046446204 -0.033897996 0.017379284, 0.044261485 -0.036704689 0.017379031, -0.043488279 -0.037617639 0.017379075, 0.047141388 -0.032924384 0.017379314, -0.040233508 -0.041080371 0.017378807, 0.049699187 -0.028919026 0.017379493, -0.03670375 -0.044262648 0.017378643, 0.051917374 -0.024716049 0.017379597, -0.032923222 -0.047142267 0.017378479, 0.053781077 -0.020344302 0.017380089, -0.028917864 -0.049700141 0.017378345, -0.024714947 -0.051918477 0.017378166, -0.020343214 -0.053782031 0.017378092, -0.015832514 -0.055278525 0.017378077, -0.022960499 -0.070350423 0.044496059, -0.028034195 -0.068486735 0.044496074, -0.017764181 -0.071838766 0.044496059, -0.012472898 -0.072943822 0.044495851, -0.072436973 0.015126199 0.044500947, -0.0071154088 -0.073659688 0.044495866, -0.073348135 0.0097983479 0.044500321, -0.0017198175 -0.073982581 0.044495866, -0.073867828 0.0044181049 0.044500247, 0.0036850423 -0.073910788 0.044495776, -0.073993504 -0.00098587573 0.044499934, 0.0090701431 -0.073444575 0.044495881, -0.073724449 -0.0063841492 0.044499606, 0.0144068 -0.072586522 0.044495761, -0.07306172 -0.011748776 0.044499233, 0.019666687 -0.071341172 0.04449597, -0.072009459 -0.017050669 0.04449898, 0.024821758 -0.069715366 0.044496045, -0.070573002 -0.022261575 0.044498861, 0.029844254 -0.067717716 0.044496104, -0.068759978 -0.027353659 0.044498473, 0.034707457 -0.065358505 0.044496313, -0.066579878 -0.032299817 0.04449822, 0.039385349 -0.062650517 0.044496477, -0.064044759 -0.037073672 0.044497892, 0.043853417 -0.059608594 0.044496641, -0.061167896 -0.041649714 0.044497699, 0.048087358 -0.056248471 0.044496745, -0.057964683 -0.04600364 0.044497401, 0.052064791 -0.052588224 0.044497028, -0.054452047 -0.050112009 0.044497281, 0.055764586 -0.048647493 0.044497222, -0.050649107 -0.053953096 0.044497088, 0.05916661 -0.044447199 0.044497371, -0.046575889 -0.057506308 0.04449673, 0.062252879 -0.040009692 0.044497669, -0.042254016 -0.060752809 0.044496626, 0.06500712 -0.035358831 0.044497982, -0.037706926 -0.063675001 0.044496357, 0.067414612 -0.030519173 0.044498175, -0.032958403 -0.0662577 0.044496208, 0.06946224 -0.025516883 0.044498593, -0.054427803 0.020589128 -0.020633966, -0.052541956 0.025013432 -0.020633787, -0.052075207 0.02479127 -0.019043237, -0.055445373 0.015881866 -0.019043967, -0.055942237 0.016024143 -0.020634279, -0.053944439 0.020406261 -0.019043326, 0.024790168 0.052076265 -0.019041792, 0.026172787 0.051395476 -0.019041747, 0.024714991 0.051918462 -0.017378271, -0.055210009 0.02088505 -0.022082463, -0.053296939 0.025373012 -0.022082075, 0.0267867 0.052601308 -0.022080585, 0.029686317 0.051021054 -0.022080645, 0.029265851 0.050298139 -0.020632312, 0.026407436 0.051856026 -0.020632163, -0.056746021 0.016254574 -0.022082582, 0.025012299 0.052543104 -0.020632192, -0.056256801 0.021281123 -0.023325324, -0.05430755 0.025854126 -0.023324862, -0.055662781 0.026152968 -0.024307996, -0.057822153 0.016562879 -0.023325503, 0.027294576 0.053598598 -0.023323447, 0.030249104 0.051988319 -0.023323566, -0.057002321 0.021563128 -0.023955911, -0.057577446 0.02161333 -0.024308205, 0.025371745 0.05329825 -0.022080615, 0.021974906 0.053325504 -0.019041568, 0.020343244 0.05378215 -0.017378271, 0.027656302 0.054308787 -0.023954108, 0.027908549 0.054804265 -0.024306312, 0.059122592 -0.016932756 -0.024310425, 0.057822019 -0.016560018 -0.023327544, 0.025852829 0.054308593 -0.023323327, 0.023432285 0.056862533 -0.024306372, 0.022171795 0.053803414 -0.020632058, 0.020405248 0.05394569 -0.019041464, 0.022490337 0.05457665 -0.022080511, 0.020588115 0.05442901 -0.020632133, 0.022916794 0.055611268 -0.023323402, 0.017636016 0.054913297 -0.019041553, 0.015832677 0.055278346 -0.017378047, 0.020883858 0.05521144 -0.022080243, 0.023220435 0.056348324 -0.023953959, 0.017794088 0.055405498 -0.020632148, 0.021279886 0.056258023 -0.023323372, 0.018805742 0.058555722 -0.024306208, 0.015880793 0.05544652 -0.019041374, 0.018049821 0.056201681 -0.022080153, 0.016023099 0.055943176 -0.020631909, 0.018392146 0.057267278 -0.023323148, 0.013184071 0.056148753 -0.019041479, 0.011213839 0.056396931 -0.017378226, 0.016253307 0.056747317 -0.022080466, 0.018635765 0.05802612 -0.02395384, 0.013302311 0.056651831 -0.020631924, 0.016561419 0.057823285 -0.023323119, 0.01405862 0.059872821 -0.024306104, 0.011247963 0.056568593 -0.019041494, 0.013493389 0.057466224 -0.022080213, 0.011348784 0.057075396 -0.020631984, 0.013749272 0.058555692 -0.023323029, 0.0086474717 0.057023838 -0.019041345, 0.0065183938 0.057130277 -0.017378166, 0.011511773 0.057895735 -0.022080243, 0.013931334 0.059331581 -0.023953736, 0.0087249577 0.057535008 -0.02063182, 0.01173006 0.058993414 -0.023323148, 0.0092209876 0.06080617 -0.024306163, 0.0065382719 0.057304174 -0.019041315, 0.0088503659 0.058361813 -0.022080198, 0.0065967739 0.057817534 -0.02063179, 0.0090180635 0.059468448 -0.023323044, 0.0040552467 0.057533324 -0.019041285, 0.0017784536 0.057473525 -0.017377913, 0.0066915601 0.058648691 -0.022080168, 0.0091376603 0.060256451 -0.0239539, 0.0040916204 0.058048904 -0.020631954, 0.006818369 0.059760585 -0.023323059, 0.004324317 0.061349034 -0.024305984, 0.001783818 0.057648331 -0.019041255, 0.00415048 0.058882952 -0.022080153, 0.0017998219 0.058164954 -0.020631835, 0.0042291582 0.059999585 -0.023323134, -0.00056269765 0.057673141 -0.019041255, -0.0029736757 0.057424098 -0.017378017, 0.0018255711 0.059001103 -0.022080258, 0.0042852312 0.060794428 -0.023953602, -0.00056779385 0.058190018 -0.020631775, 0.0018603057 0.06011948 -0.023323029, -0.00060020387 0.061498448 -0.024306029, -0.0029828101 0.057598785 -0.019041225, -0.00057598948 0.059026212 -0.022080064, -0.0030095428 0.058114991 -0.020631835, -0.00058707595 0.060145497 -0.023323089, -0.005177319 0.057443082 -0.019041434, -0.007705465 0.056982413 -0.017378002, -0.00059472024 0.060942397 -0.023953691, -0.0030527115 0.058950216 -0.022080138, -0.005223766 0.057957947 -0.020631686, -0.0031105578 0.060067907 -0.023323089, -0.0055207312 0.061253086 -0.024305955, -0.0077289194 0.057155654 -0.019041359, -0.0052987784 0.058790848 -0.022080243, -0.059122562 0.016935408 -0.024308518, -0.0077982247 0.057668015 -0.02063185, 0.056565225 -0.011258215 -0.019045353, 0.056396082 -0.011212796 -0.017381936, 0.055445388 -0.015879571 -0.019045547, -0.0053992867 0.059905425 -0.023323119, 0.057071984 -0.011359006 -0.020635799, -0.0097586811 0.056844473 -0.019041419, -0.012384683 0.056151628 -0.017378107, 0.055942312 -0.016021967 -0.020635977, -0.0054707229 0.06069921 -0.02395381, -0.0079102218 0.058496654 -0.022080183, 0.057892203 -0.011522099 -0.022084132, 0.0567462 -0.016252086 -0.022084564, 0.058989659 -0.011740595 -0.023327157, -0.0098460764 0.057353795 -0.02063179, 0.057303056 -0.0065370202 -0.019044921, 0.057129338 -0.0065174997 -0.017381757, 0.057472587 -0.0017774701 -0.0173814, -0.0080601424 0.059605688 -0.023323059, 0.05781664 -0.006595701 -0.020635575, -0.010405928 0.060614645 -0.02430591, -0.012422368 0.056322187 -0.019041494, 0.05864732 -0.0066901892 -0.022083849, -0.0099874586 0.058177829 -0.022080168, 0.059759274 -0.0068171322 -0.023326978, -0.012533739 0.056827009 -0.020631894, -0.010176808 0.059281126 -0.02332294, 0.057647288 -0.0017826855 -0.019044608, -0.01427722 0.055880815 -0.019041494, -0.016979292 0.054936975 -0.017378166, 0.060551122 -0.0069074482 -0.023957431, 0.061179295 -0.0062718987 -0.024309888, -0.010311693 0.060066655 -0.023953602, 0.058163881 -0.0017987341 -0.020635322, -0.012713671 0.057643682 -0.022080317, 0.058999658 -0.0018243492 -0.022083536, -0.014405414 0.056381688 -0.02063188, 0.060118228 -0.0018590093 -0.023326591, -0.012954667 0.058736518 -0.023323223, -0.015224293 0.05958727 -0.024306118, 0.057597727 0.0029838383 -0.019044429, 0.057423204 0.0029745996 -0.017381072, 0.056981489 0.0077065527 -0.017380938, -0.01703091 0.055104196 -0.019041553, 0.0609148 -0.0018835366 -0.023957416, 0.061485052 -0.0013545454 -0.024309605, -0.014612243 0.057191938 -0.022080436, 0.058113798 0.0030105859 -0.020634815, -0.017183512 0.055597901 -0.020632192, 0.058948934 0.0030539334 -0.022083521, -0.014889196 0.058276162 -0.023323163, 0.060066462 0.0031119585 -0.023326322, -0.018704325 0.054558679 -0.019041464, -0.021457821 0.053347021 -0.017378181, 0.057154566 0.0077300668 -0.019044101, -0.015086576 0.059048459 -0.02395387, -0.017430425 0.056396961 -0.022080332, 0.060862452 0.0031530261 -0.02395685, 0.061396524 0.0035712868 -0.024309292, 0.057666868 0.0077992976 -0.020634681, -0.018871784 0.055047616 -0.020632043, 0.058495417 0.0079112798 -0.022083089, -0.017760918 0.057466179 -0.023323268, -0.019944891 0.058177412 -0.024306089, -0.019143179 0.055838659 -0.022080168, 0.059604421 0.0080615431 -0.02332592, 0.056321189 0.012423381 -0.019043863, 0.056150511 0.012385681 -0.017380565, -0.021523058 0.053509474 -0.019041494, 0.060394213 0.0081683546 -0.023956612, 0.060913712 0.0084742606 -0.024309158, -0.019506082 0.056897491 -0.023323193, -0.02171585 0.053988993 -0.020632133, 0.056825876 0.012534708 -0.020634338, 0.05764237 0.012715057 -0.022082806, -0.023011476 0.052886263 -0.019041583, -0.025789872 0.051392883 -0.017378449, 0.058735341 0.012956053 -0.023325801, -0.019764543 0.057651415 -0.02395387, -0.022028029 0.054764807 -0.022080526, 0.055124834 0.016960949 -0.019043595, 0.054936007 0.016980201 -0.017380431, -0.023217425 0.053360343 -0.020632073, 0.059513584 0.013127849 -0.023956373, 0.060039878 0.01332292 -0.024308711, 0.055618688 0.01711306 -0.020634219, -0.022445619 0.055803165 -0.023323208, -0.024537489 0.05639419 -0.024306312, -0.023551136 0.054127201 -0.022080347, 0.056418106 0.017359108 -0.022082657, -0.025868237 0.051549196 -0.019041643, 0.057487711 0.017688051 -0.023325443, -0.023997754 0.055153534 -0.023323238, 0.053590566 0.021318987 -0.019043401, 0.053346202 0.021458894 -0.017380103, -0.027170748 0.050874934 -0.019041657, -0.029945567 0.049087599 -0.017378479, 0.058249474 0.017922521 -0.023956135, 0.058780998 0.018086001 -0.024308354, -0.026100144 0.052011341 -0.020632297, 0.054070741 0.021510154 -0.020633891, -0.0243157 0.055884346 -0.02395393, 0.054847836 0.0218191 -0.022082299, -0.027414188 0.051330715 -0.020632282, -0.026475042 0.052758843 -0.022080481, 0.055887505 0.022232994 -0.023325294, 0.05171223 0.025540024 -0.019043252, -0.027808189 0.052068561 -0.02208069, 0.051391959 0.025790885 -0.01737994, -0.026977018 0.053759217 -0.023323372, 0.056627974 0.022527546 -0.023955807, 0.057144776 0.022733197 -0.024308175, -0.028972849 0.054249153 -0.024306417, -0.030036718 0.049237117 -0.019041657, 0.052175581 0.025768936 -0.020633817, -0.028335348 0.053055614 -0.023323476, -0.031155735 0.048536718 -0.019041941, -0.033896953 0.046447068 -0.017378747, 0.052925423 0.026139408 -0.022082001, -0.030305907 0.049678415 -0.020632282, 0.053928673 0.026634917 -0.023324981, 0.049502015 0.029597461 -0.019042999, 0.04908672 0.029946581 -0.017379537, -0.028710812 0.053758711 -0.023954213, 0.054643184 0.026987866 -0.023955628, 0.055141956 0.027234286 -0.024308041, -0.031434894 0.048971653 -0.020632327, -0.030741483 0.0503923 -0.02208063, 0.049945667 0.029862761 -0.020633489, -0.031886742 0.049675494 -0.022080719, 0.050663307 0.030291915 -0.022081956, -0.031324163 0.051347718 -0.023323536, -0.033222109 0.051756069 -0.02430661, 0.051623762 0.03086628 -0.023324609, -0.033999875 0.046588391 -0.019041866, 0.046974093 0.033464953 -0.01904279, 0.046446308 0.033897862 -0.017379224, -0.032491162 0.050617307 -0.02332367, 0.05230777 0.031275302 -0.023955479, -0.03494069 0.045887113 -0.019041866, -0.037616566 0.043489203 -0.017378733, 0.052784935 0.031560808 -0.024307743, -0.034304693 0.047005951 -0.020632535, 0.047394991 0.03376466 -0.02063331, 0.048076138 0.034249946 -0.022081703, -0.032921687 0.051288128 -0.023954302, -0.035253823 0.0462984 -0.02063252, 0.048987538 0.034899428 -0.023324579, -0.034797624 0.047681659 -0.022080854, 0.04414469 0.037117451 -0.019042447, 0.043488413 0.037617445 -0.017379075, -0.035760522 0.046963826 -0.022080824, 0.049636647 0.035361841 -0.023955122, 0.050089523 0.03568469 -0.02430746, -0.035457417 0.048585519 -0.023323476, 0.044540346 0.03745015 -0.020632923, -0.037731096 0.043621764 -0.019042119, 0.04518044 0.037988499 -0.022081345, -0.035927117 0.049229309 -0.023954362, -0.037258193 0.04893069 -0.024306566, -0.03643854 0.047854245 -0.023323774, 0.046037003 0.038708419 -0.023324266, 0.04103221 0.040532038 -0.019042224, 0.040233493 0.041080534 -0.017379045, -0.038069084 0.044012398 -0.020632699, 0.046647072 0.039221555 -0.023954824, -0.036921158 0.048488274 -0.023954332, 0.047072664 0.039579391 -0.024307117, -0.038616225 0.04464516 -0.022081032, 0.041399837 0.040895298 -0.020632863, -0.039348274 0.045491636 -0.023323789, 0.04199487 0.041482881 -0.022081211, -0.041204244 0.040356711 -0.019042403, -0.041079342 0.040234432 -0.017378807, 0.042790905 0.042269588 -0.023324072, -0.039869726 0.046094388 -0.023954391, 0.037656307 0.04368636 -0.019042209, 0.03670378 0.044262469 -0.017378703, -0.041055024 0.045791149 -0.024307027, -0.04157348 0.040718406 -0.020632893, 0.043357849 0.042829528 -0.023954794, 0.043753505 0.043220311 -0.024307013, -0.042170942 0.041303828 -0.022081211, 0.037993714 0.04407765 -0.020632654, -0.042970538 0.042086899 -0.023323953, 0.038539648 0.044711217 -0.022081062, -0.044396043 0.036816433 -0.019042462, -0.044261575 0.036704764 -0.017379224, 0.039270356 0.045558989 -0.023323908, -0.043539822 0.042644635 -0.02395463, -0.044588506 0.042358175 -0.024307042, 0.034038648 0.046560064 -0.019041985, 0.032923386 0.047142401 -0.017378554, -0.044793934 0.0371463 -0.020633012, 0.03979069 0.046162546 -0.023954585, 0.040153652 0.04658404 -0.024306819, -0.045437738 0.037680313 -0.022081405, 0.033023313 0.047285691 -0.019041941, 0.03434363 0.04697752 -0.020632535, -0.046299145 0.038394541 -0.023324311, -0.047284663 0.033024445 -0.019042611, -0.047141507 0.03292422 -0.017379373, -0.049699143 0.028918862 -0.017379627, 0.033319309 0.047709495 -0.02063255, -0.046912521 0.03890337 -0.023954973, 0.034837142 0.047652647 -0.022080883, -0.04783608 0.03865321 -0.024307325, -0.047708362 0.033320546 -0.020633191, 0.033798113 0.048395261 -0.022080824, -0.048394039 0.033799365 -0.022081643, 0.03549768 0.048556179 -0.023323685, 0.030202627 0.049135417 -0.019041985, 0.028918043 0.049700022 -0.017378464, -0.049311459 0.034440175 -0.02332443, 0.035967931 0.049199671 -0.023954377, 0.036296234 0.049648419 -0.024306625, -0.049850181 0.029006869 -0.019043013, -0.049964964 0.034896627 -0.023955226, -0.050776333 0.034700155 -0.024307445, -0.050297052 0.029266939 -0.020633504, 0.034438848 0.049312681 -0.023323715, 0.029005855 0.049851477 -0.019041792, 0.030473188 0.049575835 -0.020632312, -0.051019743 0.029687524 -0.022081807, 0.034895182 0.049966216 -0.023954287, -0.051986992 0.030250311 -0.023324862, 0.032205731 0.052394614 -0.02430664, -0.051917553 0.02471599 -0.017379895, 0.030911028 0.050288454 -0.022080645, -0.052675918 0.030651346 -0.023955435, -0.053391039 0.030524492 -0.024307609, 0.031497166 0.051241755 -0.023323551, 0.031914532 0.051920816 -0.023954317, -0.053781062 0.020344391 -0.017380193, -0.055026948 0.026196733 -0.023955643, -0.053391337 -0.045268342 -0.029219553, -0.056184828 -0.044586957 -0.030562699, -0.056656241 -0.041109025 -0.029219314, -0.056328654 -0.047758639 -0.034612015, -0.054342538 -0.050006837 -0.034611955, 0.059890896 -0.043207929 -0.034611717, 0.059047535 -0.044353336 -0.034611806, -0.056941181 -0.04518716 -0.031766102, -0.055445731 -0.047010198 -0.031766325, -0.057502523 -0.04563278 -0.033132911, -0.055992514 -0.047473446 -0.03313306, 0.05565232 -0.048545167 -0.03461194, 0.058694914 -0.044088662 -0.033132866, 0.055320039 -0.048255309 -0.033133194, -0.054018185 -0.049708322 -0.033133075, 0.059533283 -0.042950138 -0.033132732, -0.054709241 -0.046385691 -0.030562699, 0.058121979 -0.043658197 -0.031766132, 0.054779992 -0.047784507 -0.03176643, -0.052562892 -0.051874191 -0.034612119, 0.058952048 -0.042530686 -0.031766176, -0.053490907 -0.049223065 -0.031766504, 0.057349905 -0.043078214 -0.030562565, 0.056767613 -0.040954992 -0.029219225, 0.053514168 -0.045123115 -0.029219374, 0.054052234 -0.047149673 -0.030562937, -0.053810135 -0.045623437 -0.029566839, 0.062127605 -0.039924785 -0.034611523, -0.052249104 -0.051564574 -0.033133283, 0.058168992 -0.041965798 -0.03056246, -0.049821883 -0.049169332 -0.029219747, -0.052780271 -0.048569292 -0.030562893, 0.062981725 -0.038563624 -0.034611493, 0.06175676 -0.039686546 -0.033132732, -0.050547272 -0.05384022 -0.034612134, 0.057212889 -0.041276142 -0.029566824, -0.051738933 -0.051061392 -0.031766444, 0.06260553 -0.038333729 -0.033132538, -0.050245449 -0.053518802 -0.033133432, 0.061153859 -0.039299086 -0.031765997, -0.051051736 -0.050382838 -0.030562893, 0.061994404 -0.037959412 -0.031765878, -0.04849714 -0.05569391 -0.034612358, 0.060341507 -0.038777009 -0.030562401, 0.05969733 -0.03655307 -0.029218987, -0.049754962 -0.052996263 -0.031766832, 0.064876541 -0.035283342 -0.034611225, -0.050212666 -0.049554884 -0.029567167, 0.061170787 -0.037455246 -0.030562192, -0.048207521 -0.055361405 -0.033133522, 0.064489126 -0.035072595 -0.033132479, -0.045968041 -0.052789882 -0.029219851, -0.049094021 -0.052292347 -0.030563042, 0.065713078 -0.033699676 -0.034611106, -0.046482176 -0.057386339 -0.034612432, 0.06016545 -0.036839634 -0.029566452, -0.047737032 -0.054821014 -0.031766728, 0.063859671 -0.03473039 -0.031765819, -0.046204731 -0.057043776 -0.033133671, 0.065320641 -0.03349863 -0.033132374, -0.04710269 -0.054092795 -0.030563235, 0.062286139 -0.031942457 -0.029218882, 0.063011244 -0.034269065 -0.030562028, -0.044154555 -0.059195742 -0.034612522, -0.045753613 -0.05648692 -0.031766936, 0.064682961 -0.033171594 -0.031765535, 0.06727913 -0.030453458 -0.034610868, -0.046328604 -0.053203806 -0.029567376, -0.043891042 -0.058842495 -0.033133656, 0.0638237 -0.032731041 -0.030561939, -0.04514569 -0.055736467 -0.03056322, 0.066877425 -0.030271739 -0.033132166, -0.041852117 -0.056108981 -0.029220194, -0.042169049 -0.060626179 -0.034612492, 0.068069518 -0.028643385 -0.034610704, -0.0434625 -0.058267996 -0.031767115, 0.062774777 -0.03219305 -0.029566094, 0.06622456 -0.029976264 -0.031765327, -0.041917369 -0.06026426 -0.033133879, -0.042885214 -0.05749388 -0.030563354, 0.067663133 -0.028472483 -0.033132032, 0.064519867 -0.027149752 -0.029218435, 0.065344721 -0.029578015 -0.03056176, -0.039560258 -0.062359899 -0.03461279, -0.041508228 -0.059675977 -0.031767145, -0.042180404 -0.056549028 -0.02956748, 0.06932281 -0.025461301 -0.034610674, -0.039324075 -0.061987534 -0.033133909, 0.06700255 -0.028194442 -0.031765342, -0.040956736 -0.05888322 -0.030563414, -0.037497312 -0.059107974 -0.029220328, 0.06890884 -0.025309175 -0.033131942, -0.037631035 -0.063542634 -0.03461279, 0.066112325 -0.027819946 -0.030561611, -0.038940117 -0.061382428 -0.031767085, 0.070037454 -0.023423344 -0.034610555, 0.070996478 -0.020333022 -0.03461048, -0.03740634 -0.06316328 -0.033134073, 0.068236008 -0.025062054 -0.031765118, -0.038422748 -0.060567021 -0.030563548, 0.065025747 -0.027362674 -0.029565901, -0.034740046 -0.065168083 -0.034612864, 0.069619372 -0.02328375 -0.033131689, 0.070572421 -0.020211652 -0.03313151, -0.037041202 -0.062546685 -0.031767204, 0.067329586 -0.024729401 -0.030561388, -0.037791371 -0.059571728 -0.029567733, 0.06638521 -0.022202298 -0.029218122, -0.034532651 -0.064779148 -0.033134073, 0.068939671 -0.023056358 -0.031764969, 0.069883645 -0.020014495 -0.031764969, -0.032928497 -0.061770007 -0.029220402, -0.036549091 -0.061715871 -0.030563667, 0.068023771 -0.02275005 -0.030561447, 0.068955138 -0.019748554 -0.030561447, 0.067468345 -0.020413384 -0.029524639, 0.06698671 -0.021350235 -0.029404759, -0.032892197 -0.066119969 -0.034613013, 0.06690599 -0.022376329 -0.029565647, -0.034195513 -0.064146683 -0.031767204, -0.070542783 -0.00093574822 -0.029564351, -0.070896596 0.0013843179 -0.029829323, -0.069981009 -0.0016270876 -0.029216945, -0.069904298 0.0036598891 -0.029216796, -0.032695815 -0.065725237 -0.033134058, -0.033741325 -0.063294575 -0.030563653, -0.070286274 -0.0060825199 -0.029564694, -0.070803657 -0.0038827956 -0.029829368, -0.069654375 -0.011196822 -0.029564828, -0.070319772 -0.0091284513 -0.029829532, -0.069658563 -0.0069048554 -0.029217303, -0.029721662 -0.067604512 -0.034612969, -0.032376692 -0.065083563 -0.031767234, 0.042004421 -0.055995092 -0.02922006, 0.040106967 -0.058476448 -0.029832512, 0.037657812 -0.05900611 -0.029220343, 0.037548944 -0.059725061 -0.029567823, 0.041808262 -0.056824714 -0.02956745, -0.033186734 -0.062254339 -0.029567868, 0.04611142 -0.052664667 -0.029219881, 0.044337496 -0.055337369 -0.029832274, -0.029544175 -0.06720084 -0.033134162, 0.045844808 -0.053621203 -0.029567301, -0.028171718 -0.064079329 -0.029220462, -0.03194648 -0.064218983 -0.030563802, 0.049636796 -0.050131738 -0.029567108, 0.048323676 -0.051893175 -0.02983211, -0.071825415 0.0028501153 -0.030722454, -0.070423096 0.0042161644 -0.029563993, -0.071599796 0.0042864829 -0.030559823, -0.072563723 0.0043442398 -0.03176336, -0.027977854 -0.068344653 -0.034612954, -0.029255867 -0.066544741 -0.031767651, -0.072153971 0.0015889257 -0.031054601, -0.027810872 -0.067936555 -0.033134326, -0.071881562 0.00022497773 -0.030722558, -0.071721449 -0.00095127523 -0.030560151, -0.072687209 -0.00096409023 -0.031763628, -0.028867245 -0.065660685 -0.030563816, -0.071840316 -0.0024451762 -0.030722722, -0.027539238 -0.067273363 -0.031767502, -0.072075799 -0.003712222 -0.031054676, -0.024533749 -0.069655016 -0.034612954, -0.071703091 -0.0050673336 -0.030722976, -0.072422758 -0.0062673241 -0.031764165, -0.071460783 -0.0061842203 -0.030560523, -0.028392836 -0.064581722 -0.029567868, -0.071465015 -0.0077272952 -0.030723274, -0.027173549 -0.066379696 -0.030563891, -0.023254409 -0.066022888 -0.02922067, -0.022914276 -0.070204392 -0.034613073, -0.071608633 -0.0089930743 -0.031055078, -0.02438724 -0.069239095 -0.033134326, -0.071771905 -0.011537284 -0.031764299, -0.071135327 -0.010332182 -0.030723214, -0.070818484 -0.011384025 -0.030560821, 0.038176239 -0.060722977 -0.030563682, 0.039465204 -0.060077414 -0.03072612, 0.038690239 -0.061540395 -0.0317671, -0.022777393 -0.069785401 -0.033134237, -0.024149209 -0.068563238 -0.031767532, 0.040685549 -0.059608757 -0.031057954, 0.041632965 -0.058596075 -0.030725956, -0.022555128 -0.069104105 -0.031767607, 0.043079272 -0.058551893 -0.031766996, 0.042506918 -0.057774231 -0.030563414, -0.023828447 -0.067652464 -0.030563995, 0.043780968 -0.05700919 -0.030725867, -0.019205868 -0.071308166 -0.034613267, -0.018204406 -0.067589954 -0.0292207, -0.02225545 -0.068186238 -0.03056407, 0.044951782 -0.056461141 -0.031057671, 0.045833841 -0.05537203 -0.030725703, 0.04723841 -0.055251122 -0.031766802, 0.046610996 -0.054517075 -0.030563295, -0.023436725 -0.066540748 -0.029568031, 0.047859117 -0.053631559 -0.030725688, -0.017728373 -0.071689859 -0.034613207, -0.019091174 -0.070882529 -0.033134356, 0.048975512 -0.053008825 -0.031057552, 0.049786016 -0.051847622 -0.030725598, 0.051145598 -0.051655486 -0.031766683, 0.05046618 -0.050969407 -0.030563191, -0.01762253 -0.071261942 -0.033134565, -0.072808802 0.0029802918 -0.03204529, -0.01890479 -0.070190474 -0.031767771, -0.070971444 0.020329773 -0.034480721, -0.072291285 0.015100181 -0.03460823, -0.073279113 0.0043871552 -0.033130094, -0.073049128 0.0016696155 -0.032397851, -0.017450601 -0.070566088 -0.031767786, -0.070474491 0.020187244 -0.032890096, -0.071859688 0.01500985 -0.033129588, -0.072868973 0.00031901896 -0.032045394, -0.018653646 -0.069258079 -0.030564144, -0.071158126 0.014863372 -0.031762928, -0.073403686 -0.00097361207 -0.033130482, -0.069670618 0.019956917 -0.031441718, -0.072831541 -0.0023575723 -0.032045588, -0.013768286 -0.072554514 -0.034613267, -0.070212945 0.014665902 -0.030559197, -0.072975397 -0.0036772788 -0.032397971, -0.068594873 0.019648999 -0.030198932, -0.013050213 -0.068771228 -0.029220805, -0.017218709 -0.06962882 -0.030564114, -0.01834698 -0.068120033 -0.029568076, -0.073200598 0.0097829849 -0.034608692, -0.073136672 -0.0063291192 -0.033130735, -0.072696656 -0.0050160885 -0.032045648, -0.068557069 0.014141604 -0.029216141, -0.06905885 0.014424831 -0.029563472, -0.067294106 0.019276142 -0.029215798, -0.013686091 -0.072121471 -0.033134446, -0.072463438 -0.007682696 -0.03204596, -0.072763517 0.009724468 -0.033129826, -0.072510868 -0.0090042949 -0.032398388, -0.072053179 0.0096294135 -0.031763345, -0.013552457 -0.071417317 -0.031767845, -0.072479427 -0.011650905 -0.033131078, -0.07213451 -0.010324091 -0.032046005, -0.013372391 -0.07046859 -0.0305641, -0.071096003 0.0095015168 -0.030559555, 0.039938629 -0.060948119 -0.032048866, 0.039071605 -0.062147036 -0.033133864, -0.0082521886 -0.073386848 -0.034613296, 0.041145504 -0.06038028 -0.032401279, -0.013152599 -0.069310412 -0.029568389, -0.073719323 0.0044136345 -0.034608901, -0.069927529 0.0093453377 -0.029564008, 0.04350397 -0.059129149 -0.033133745, 0.042137951 -0.059448838 -0.03204897, -0.0082030445 -0.072948605 -0.033134595, -0.069428816 0.0089262426 -0.029216439, 0.044293195 -0.057860941 -0.032048687, -0.0081228167 -0.072236493 -0.03176783, 0.045451373 -0.057209536 -0.032401189, -0.0080148876 -0.071277082 -0.030564129, 0.046376958 -0.056204811 -0.032048613, 0.047704101 -0.055795833 -0.033133522, -0.0026889443 -0.073800296 -0.034613296, 0.048410043 -0.054463431 -0.032048523, -0.0078832358 -0.070105582 -0.0295683, -0.007821843 -0.069559991 -0.029220983, 0.049513638 -0.053732216 -0.032400817, -0.0026729554 -0.073359817 -0.033134624, 0.050367042 -0.052659094 -0.032048494, 0.051649854 -0.052164778 -0.033133343, -0.073643342 0.0017037243 -0.033847421, -0.0026468486 -0.072643608 -0.031767786, -0.073844656 -0.00097934902 -0.034609243, -0.0026117116 -0.071678534 -0.030564085, -0.073571026 -0.0036798865 -0.033847779, -0.073575884 -0.0063670129 -0.034609497, 0.0028896332 -0.07379286 -0.034613431, -0.072914809 -0.011720836 -0.03460978, -0.073105603 -0.0090437382 -0.033848166, -0.0025687367 -0.070500642 -0.029568151, -0.0025487393 -0.069952041 -0.029220939, 0.039306208 -0.06252028 -0.03461279, 0.041465223 -0.060882196 -0.033851117, 0.0028722584 -0.073352262 -0.033134535, 0.043765262 -0.059484363 -0.034612596, 0.0028443485 -0.072635993 -0.031767949, 0.045801476 -0.057690784 -0.033850878, 0.047990635 -0.056130901 -0.034612447, 0.0028064102 -0.071671084 -0.030564085, 0.05196017 -0.052477941 -0.034612209, 0.049893066 -0.054191366 -0.033850595, 0.0084515512 -0.073364049 -0.034613341, 0.0027603209 -0.070493311 -0.029568419, 0.0027388781 -0.069944873 -0.029220879, 0.0084011555 -0.072926238 -0.033134475, 0.0083191991 -0.072214216 -0.031767756, 0.0082086623 -0.07125482 -0.030564114, 0.013965309 -0.07251671 -0.034613237, -0.071864545 -0.017011911 -0.034610137, 0.0080108643 -0.069538504 -0.029220894, 0.0080736279 -0.070083842 -0.029568389, -0.068938315 -0.012143195 -0.029217467, -0.071435437 -0.016910508 -0.033131376, 0.013881981 -0.07208395 -0.033134401, -0.070738241 -0.016745403 -0.031764641, 0.01374653 -0.071380198 -0.031767875, -0.069798365 -0.016523033 -0.03056097, 0.013563856 -0.070431903 -0.030564159, -0.067825034 -0.017312244 -0.029217869, 0.019399583 -0.071255744 -0.034613177, -0.070430994 -0.022212192 -0.034610361, 0.013340965 -0.069274455 -0.02956818, -0.069973499 -0.023613796 -0.03461054, 0.013237134 -0.068735406 -0.029220834, -0.070010364 -0.022079721 -0.033131659, 0.019283682 -0.070830405 -0.033134416, 0.01909554 -0.070139095 -0.0317678, -0.069555834 -0.023472726 -0.033131778, -0.069327012 -0.02186437 -0.031764954, 0.018841758 -0.06920734 -0.030564055, -0.068876758 -0.023243725 -0.031764939, 0.024723083 -0.069588125 -0.034613207, -0.066324592 -0.022382483 -0.029218242, -0.068405986 -0.021573797 -0.030561373, 0.018387854 -0.067540303 -0.029220715, 0.018532053 -0.068069845 -0.029568166, 0.024575397 -0.06917268 -0.033134356, -0.068621472 -0.027294174 -0.034610793, -0.067961738 -0.022934988 -0.030561358, -0.067991331 -0.028828248 -0.034610882, 0.024335384 -0.068497315 -0.031767592, -0.068211913 -0.027131289 -0.033131853, 0.024012178 -0.067587599 -0.030563936, -0.066844881 -0.022557914 -0.029565468, -0.067585275 -0.02865614 -0.033132136, 0.029784098 -0.06757693 -0.034612983, 0.023433849 -0.065959439 -0.02922067, 0.023617402 -0.066476673 -0.029567972, -0.067545995 -0.026866376 -0.031765386, -0.066925466 -0.02837646 -0.031765386, 0.029606253 -0.06717363 -0.033134192, 0.02931723 -0.06651777 -0.031767502, -0.066648498 -0.026509464 -0.030561596, -0.064445719 -0.027325079 -0.02921845, 0.028927654 -0.065634146 -0.030563846, -0.066446036 -0.032230362 -0.034611076, -0.066036522 -0.027999565 -0.030561626, 0.034637585 -0.065222517 -0.03461282, -0.066049382 -0.032038152 -0.0331323, 0.028452337 -0.064555451 -0.029567912, 0.028346032 -0.064002424 -0.029220551, -0.065621242 -0.033878058 -0.034611076, 0.034430787 -0.064833179 -0.033133969, -0.064951196 -0.027539298 -0.029565886, 0.034094602 -0.064200386 -0.031767383, -0.065404564 -0.031725377 -0.03176558, 0.033641681 -0.063347444 -0.030563772, -0.065229267 -0.033675939 -0.0331323, -0.062199324 -0.032111824 -0.029218644, -0.064535573 -0.031303927 -0.030561894, 0.033088773 -0.062306434 -0.029567882, 0.03309615 -0.061680168 -0.029220343, -0.064592466 -0.033347234 -0.031765699, -0.063915893 -0.036994636 -0.03461121, -0.063734502 -0.032904282 -0.030561998, -0.063534394 -0.03677392 -0.033132449, -0.062876269 -0.038734823 -0.034611434, -0.062686905 -0.032363594 -0.02956602, -0.062913969 -0.036414847 -0.031765744, -0.062501237 -0.038503587 -0.033132657, -0.059597626 -0.03671518 -0.029218957, -0.062078148 -0.035931036 -0.030562207, -0.061044857 -0.041561499 -0.034611478, -0.061891064 -0.038127691 -0.031765968, -0.060680464 -0.04131338 -0.033132702, -0.061068878 -0.037621245 -0.030562326, -0.059773192 -0.043370575 -0.034611672, -0.060088009 -0.040910229 -0.031765983, -0.060065061 -0.0370031 -0.029566377, -0.059416518 -0.043111622 -0.033132851, -0.059289724 -0.040366858 -0.030562416, -0.057848066 -0.045906663 -0.034611702, -0.058836192 -0.042690769 -0.031766146, -0.058054611 -0.042123631 -0.030562565, 0.049955353 -0.049033791 -0.029219642, -0.057100445 -0.041431352 -0.029566705, 0.069842577 0.0046941638 -0.029216617, 0.065510884 0.0056047738 -0.026762903, 0.069289088 0.0099527389 -0.029216394, 0.064540043 0.012557343 -0.0267625, 0.065734848 -0.0014118254 -0.02676332, 0.069753081 -0.0058731288 -0.029217288, 0.069997579 -0.00059135258 -0.0292169, 0.069110617 -0.01112166 -0.029217586, 0.065209627 -0.0084121823 -0.026763678, -0.060143113 0.020761013 -0.025535241, -0.060917839 0.024741694 -0.02676177, -0.06564723 0.024300888 -0.02921544, -0.064160466 0.022147909 -0.027988791, -0.058507174 0.038432047 -0.029214799, -0.058325425 0.034716979 -0.027988002, -0.06124121 0.033906162 -0.029215008, -0.054287642 0.037094995 -0.026761025, -0.057932973 0.031095624 -0.026761442, -0.031122357 0.062702492 -0.029213458, -0.032684922 0.059488639 -0.027986676, -0.035766438 0.060174644 -0.029213622, -0.034035549 0.056256548 -0.026759997, -0.027843982 0.059564948 -0.026759803, -0.021328881 0.066673085 -0.029213205, -0.017884001 0.065478042 -0.027986318, -0.021334693 0.062193736 -0.026759684, -0.016235366 0.068092763 -0.02921319, -0.01458244 0.064114079 -0.026759654, 0.020339921 0.066981539 -0.02921319, 0.017768115 0.065509737 -0.027986318, 0.015226051 0.068325609 -0.029213056, -0.063625872 0.029186726 -0.029215232, 0.013296619 0.064393044 -0.02675961, 0.02008605 0.062608242 -0.026759699, 0.051357046 0.047566876 -0.029214382, 0.047770008 0.048220247 -0.027987272, 0.047620058 0.051307797 -0.029214069, 0.044224367 0.048656091 -0.026760429, 0.049159735 0.04366377 -0.026760757, 0.060732767 0.0348088 -0.029215023, 0.057712451 0.03572686 -0.027988166, 0.057932213 0.039293617 -0.029214785, 0.053534657 0.038173482 -0.026760936, 0.057299316 0.032248482 -0.026761472, 0.067857519 0.0015486777 -0.027990028, -0.055439427 0.04273878 -0.029214531, -0.052055463 0.046801552 -0.029214457, -0.050023511 0.042671412 -0.026760727, -0.048374087 0.05059734 -0.029214054, -0.045188889 0.047761545 -0.026760578, -0.044416994 0.054104716 -0.02921389, -0.039839298 0.052307144 -0.026760355, -0.040206417 0.057302967 -0.029213801, -0.026300579 0.064872876 -0.02921316, -0.01104936 0.069124237 -0.029213011, -0.0058001429 0.06976074 -0.029213101, -0.007663697 0.065303236 -0.026759595, -0.00051805377 0.06999974 -0.029212907, -0.00065769255 0.06574814 -0.02675958, 0.004767254 0.069838911 -0.029212937, 0.0063557625 0.065443546 -0.026759639, 0.010025293 0.069279894 -0.02921313, 0.025337711 0.065255031 -0.029213175, 0.026646569 0.060109988 -0.026760027, 0.030190989 0.063156337 -0.029213399, 0.032903075 0.056926325 -0.026760057, 0.034871995 0.060697243 -0.029213488, 0.039354056 0.057891756 -0.029213667, 0.038784847 0.053093851 -0.02676025, 0.043611497 0.054756001 -0.029213905, 0.054801002 0.043554544 -0.029214457, 0.063186809 0.030125111 -0.029215217, 0.065280497 0.025269538 -0.02921547, 0.060410723 0.025955543 -0.026761815, 0.067001536 0.020269856 -0.029215872, 0.062833652 0.019366816 -0.026762202, 0.068340227 0.01515457 -0.029216185, -0.013217553 0.084305942 -0.063202485, -0.01108788 0.084277138 -0.062995419, -0.01681301 0.083324045 -0.062995329, -0.013269156 0.084635228 -0.063407645, -0.011131316 0.084606782 -0.063202307, -0.011174738 0.084937274 -0.063407645, -0.016878769 0.083649784 -0.063202366, -0.018818885 0.083234847 -0.063202441, -0.022459999 0.081982374 -0.062995464, -0.016944736 0.083976686 -0.063407749, -0.018892422 0.083560109 -0.063407719, 0.082354262 -0.023584455 -0.063413754, -0.022547707 0.082302943 -0.063202441, -0.024336055 0.081792057 -0.0632025, -0.028002009 0.080258667 -0.062995657, -0.022635743 0.082624435 -0.063407689, -0.024431124 0.082111493 -0.063407719, -0.028111354 0.080572382 -0.06320256, -0.029744491 0.07998386 -0.063202605, -0.033413559 0.078160748 -0.062995687, -0.028221339 0.080887169 -0.063407972, -0.02986072 0.080296353 -0.063408002, -0.033544213 0.078466266 -0.06320259, -0.035020262 0.077818617 -0.063202664, -0.038669214 0.075698242 -0.062996, -0.033675179 0.078772798 -0.063408017, -0.035156995 0.078122556 -0.063408002, -0.038820401 0.075994164 -0.063202932, -0.040139511 0.075305611 -0.063202932, -0.043744788 0.07288295 -0.06299594, -0.03897208 0.076291189 -0.063408241, -0.040296346 0.075599924 -0.063408241, -0.043915749 0.073167726 -0.063202903, -0.044087365 0.073453635 -0.063408375, -0.048806265 0.070000246 -0.063203156, -0.048616201 0.069727778 -0.062996328, -0.048996732 0.070273682 -0.063408628, -0.053469151 0.066506401 -0.06320329, -0.053260997 0.066247523 -0.062996253, -0.053678095 0.066766322 -0.063408673, -0.057882994 0.062702626 -0.063203543, -0.057657555 0.062458411 -0.062996492, -0.058109 0.062947661 -0.063408941, -0.06202665 0.058606341 -0.063203737, -0.061785281 0.05837813 -0.062996835, -0.062268928 0.058835402 -0.063409254, -0.065881297 0.05423677 -0.063204154, -0.065624818 0.054025605 -0.062997028, -0.066138759 0.054448754 -0.063409373, -0.069428757 0.049614534 -0.063204214, -0.069158375 0.0494214 -0.062997207, -0.069699794 0.049808219 -0.063409641, -0.072652295 0.044760913 -0.063204557, -0.072369456 0.044586629 -0.062997729, -0.072936326 0.044935867 -0.06340985, -0.075537398 0.039698526 -0.063204959, -0.075243354 0.039544061 -0.062997907, -0.075832397 0.039853811 -0.063410431, -0.078070164 0.034451082 -0.063205123, -0.077766195 0.034317061 -0.062998146, -0.07837522 0.034585729 -0.06341061, -0.080238864 0.029043034 -0.063205361, -0.079926431 0.028930053 -0.062998354, -0.082033783 0.023499772 -0.063205779, -0.080552325 0.029156595 -0.063410759, -0.082354084 0.023591682 -0.063411042, 0.083420038 -0.017961159 -0.063208118, 0.083120987 -0.017770454 -0.06300123, 0.082033843 -0.023492754 -0.063208431, 0.083745807 -0.018031284 -0.063413486, 0.084433496 -0.012349159 -0.063207939, 0.084140167 -0.012056425 -0.063000903, 0.084763378 -0.012397364 -0.063413069, 0.085070044 -0.0066819638 -0.063207597, 0.084766984 -0.0062863231 -0.06300053, 0.085402444 -0.0067081302 -0.06341289, 0.085326552 -0.00098504126 -0.063207105, 0.084998757 -0.00048719347 -0.063000217, 0.085659936 -0.00098870695 -0.063412562, 0.085201964 0.0047164857 -0.063206911, 0.084833995 0.005314514 -0.062999815, 0.085534871 0.004734844 -0.063412085, 0.084697023 0.010396734 -0.063206717, 0.084273711 0.011091396 -0.062999561, 0.085027859 0.010437503 -0.063411877, 0.083813757 0.01603055 -0.063206136, 0.083320618 0.016816586 -0.062999129, 0.084141061 0.016093493 -0.063411623, 0.082555965 0.02159296 -0.063205823, 0.081979096 0.02246353 -0.062998787, 0.0828785 0.02167742 -0.063411266, 0.080929726 0.027058885 -0.063205615, 0.080255255 0.028005689 -0.062998638, 0.081245795 0.027164534 -0.063410848, 0.078941926 0.032403931 -0.063205332, 0.078157172 0.033417076 -0.062998265, 0.079250306 0.032530636 -0.06341055, 0.076601386 0.037604406 -0.063204885, 0.07569477 0.038672805 -0.062997937, 0.076900586 0.037751392 -0.063410372, 0.073918864 0.042636871 -0.063204646, 0.072879434 0.043748274 -0.062997788, 0.07316418 0.04391925 -0.063204721, 0.074207664 0.042803407 -0.063410133, 0.073450118 0.044090733 -0.063409925, 0.070906147 0.047478944 -0.063204512, 0.069724187 0.048619658 -0.062997386, 0.069996819 0.048809841 -0.063204288, 0.071183279 0.047664329 -0.06340988, 0.070270285 0.049000457 -0.06340979, 0.0675769 0.052108869 -0.063204154, 0.066243961 0.053264678 -0.062997192, 0.066502959 0.053472638 -0.063204125, 0.067840755 0.052312687 -0.063409507, 0.066762865 0.053681731 -0.063409507, 0.063945755 0.056506082 -0.063203856, 0.062454924 0.057661012 -0.062996835, 0.062699139 0.057886481 -0.063203812, 0.064195573 0.056726828 -0.063409239, 0.062943965 0.058112592 -0.063409239, 0.06002897 0.060651019 -0.063203752, 0.058374688 0.061788633 -0.0629967, 0.058602855 0.062030211 -0.063203603, 0.06026347 0.060888141 -0.063409075, 0.058831677 0.062272683 -0.063409045, 0.055844054 0.064525157 -0.063203618, 0.054022089 0.065628335 -0.062996402, 0.056062222 0.064777255 -0.063408911, 0.054233387 0.065884709 -0.063203529, 0.054445222 0.066142246 -0.063408747, 0.051409841 0.068110898 -0.06320326, 0.049417779 0.069161966 -0.062996224, 0.051610723 0.068377078 -0.063408569, 0.049611032 0.069432259 -0.063203171, 0.049805015 0.069703341 -0.063408405, 0.046745986 0.071392626 -0.063203052, 0.044583157 0.072372988 -0.06299606, 0.046928629 0.071671709 -0.063408479, 0.044757336 0.072656065 -0.063203111, 0.044932187 0.072939917 -0.06340833, 0.041873217 0.074355632 -0.063202873, 0.039540499 0.075246871 -0.062995777, 0.042036816 0.07464613 -0.063408241, 0.039695114 0.07554096 -0.063202962, 0.039850146 0.075836107 -0.0634083, 0.036813498 0.076986447 -0.063202754, 0.034313589 0.077769801 -0.062995777, 0.036957413 0.077287212 -0.063408092, 0.03444767 0.078073874 -0.063202605, 0.034582198 0.078378797 -0.063408047, 0.031589374 0.079273492 -0.063202664, 0.0289267 0.079929948 -0.062995642, 0.03171283 0.079583049 -0.063407943, 0.029039532 0.080242515 -0.06320262, 0.029153168 0.080555946 -0.063407749, 0.02622433 0.081206292 -0.063202515, 0.023404852 0.081717625 -0.062995508, 0.026326835 0.081523582 -0.063407987, 0.023496374 0.082037225 -0.06320256, 0.023588136 0.082357556 -0.063407794, 0.020741984 0.082776457 -0.063202441, 0.017773822 0.083124429 -0.062995389, 0.020822912 0.083100021 -0.063407913, 0.017843321 0.083449498 -0.063202381, 0.017913014 0.083775356 -0.063407585, 0.015167028 0.083977208 -0.063202441, 0.012059987 0.084143728 -0.062995568, 0.015226334 0.084305301 -0.063407764, 0.012107193 0.084472522 -0.063202485, 0.01215443 0.084802642 -0.063407674, 0.0095243603 0.084802657 -0.063202396, 0.0062899143 0.084770486 -0.062995419, 0.0095616579 0.085133821 -0.063407525, 0.0063146055 0.085101902 -0.063202336, 0.0063391477 0.085434392 -0.063407719, 0.0038392544 0.085249543 -0.063202262, 0.00049059093 0.085002109 -0.062995449, 0.0038540512 0.08558245 -0.063407749, 0.00049266219 0.085334361 -0.063202292, 0.00049449503 0.085667819 -0.063407868, -0.0018633008 0.085315526 -0.063202426, -0.005311057 0.084837407 -0.062995285, -0.001870513 0.08564876 -0.063407719, -0.0053317696 0.085169047 -0.063202351, -0.0053526908 0.08550185 -0.0634076, -0.0075571537 0.085000485 -0.063202366, -0.0075867176 0.085332572 -0.0634076, -0.013269097 0.084628105 0.063417077, -0.011174709 0.084929913 0.063417152, -0.013217539 0.084298983 0.063211694, -0.011131167 0.08459942 0.063211963, -0.011087805 0.084270149 0.063004658, -0.016813129 0.083317041 0.063004538, -0.016944766 0.083969355 0.063417137, -0.018892348 0.083552897 0.063417152, -0.016878724 0.083642676 0.063211948, -0.018818766 0.083227739 0.063211814, -0.022459954 0.081975415 0.063004628, -0.022635788 0.082617372 0.063417047, -0.02443105 0.082104325 0.063417107, -0.022547692 0.082295835 0.063211739, -0.024336159 0.081784934 0.063211694, -0.028002053 0.080251664 0.063004434, -0.028221339 0.080879986 0.063416928, -0.029860675 0.080289304 0.063417003, -0.028111368 0.080565289 0.063211754, -0.029744476 0.079976782 0.063211635, -0.033413738 0.07815358 0.063004464, -0.033675104 0.078765661 0.063416839, -0.035157025 0.078115433 0.063416958, -0.033544213 0.078459084 0.06321162, -0.035020232 0.077811494 0.063211575, -0.038669139 0.075691089 0.063004121, -0.03897199 0.076283917 0.06341663, -0.040296435 0.075592741 0.06341669, -0.038820386 0.075987011 0.063211277, -0.040139437 0.075298563 0.063211307, -0.043744713 0.072875857 0.063004062, -0.044087231 0.073446527 0.063416615, -0.043915689 0.073160589 0.063211232, -0.048996866 0.070266604 0.063416213, -0.04880625 0.069993198 0.063210934, -0.048616275 0.069720596 0.063004017, -0.053677991 0.066759139 0.063416019, -0.053469136 0.066499263 0.06321089, -0.053260952 0.0662404 0.063003778, -0.058109045 0.062940583 0.063415959, -0.057882831 0.062695429 0.063210636, -0.057657495 0.062451497 0.063003421, -0.062269017 0.05882813 0.063415766, -0.062026665 0.058599338 0.063210428, -0.061785176 0.058371007 0.063003197, -0.0661387 0.054441601 0.063415438, -0.065881297 0.054229826 0.063210145, -0.065624684 0.054018617 0.063003004, -0.069158271 0.049414292 0.063002795, -0.069699794 0.049801245 0.063415244, -0.069428816 0.049607471 0.063209966, -0.072936192 0.04492873 0.063414976, -0.072652519 0.044753775 0.063209727, -0.072369337 0.044579521 0.063002333, -0.075832471 0.039846689 0.063414633, -0.075537309 0.039691523 0.0632094, -0.07524325 0.039536893 0.063002095, -0.07837525 0.034578681 0.063414499, -0.078070164 0.03444396 0.063208997, -0.077766061 0.034309909 0.063001886, -0.080552518 0.029149503 0.063414037, -0.082354188 0.023584425 0.063413665, -0.080239028 0.02903612 0.063208804, -0.082033709 0.023492694 0.063208431, -0.079926521 0.028922826 0.063001618, 0.083745882 -0.018038422 0.063411519, 0.082354158 -0.023591548 0.063410982, 0.083419904 -0.017968193 0.063206002, 0.083121106 -0.017777517 0.062998772, 0.082033798 -0.023499861 0.063205689, 0.084763452 -0.012404472 0.063411564, 0.084433541 -0.012356088 0.06320633, 0.084140062 -0.012063637 0.062999323, 0.08540228 -0.0067151338 0.063412085, 0.085069999 -0.006689027 0.063206777, 0.084766999 -0.0062933862 0.062999576, 0.085659996 -0.00099599361 0.063412428, 0.085326687 -0.0009919852 0.063207045, 0.084998667 -0.00049422681 0.062999934, 0.085534811 0.0047277212 0.063412622, 0.085202172 0.0047093779 0.063207194, 0.084833905 0.0053076446 0.063000277, 0.085027903 0.010430202 0.06341289, 0.084696963 0.010389686 0.063207671, 0.084273741 0.011084482 0.063000575, 0.084141091 0.016086295 0.063413337, 0.083813712 0.016023666 0.063207924, 0.083320588 0.016809627 0.063000858, 0.082878575 0.021670312 0.06341362, 0.082556129 0.021586016 0.063208252, 0.081979081 0.022456303 0.063001186, 0.081245735 0.027157679 0.063413829, 0.080929667 0.027051806 0.06320861, 0.08025527 0.027998552 0.063001484, 0.079250202 0.032523572 0.063414276, 0.078941882 0.032396868 0.063208759, 0.078157157 0.033410028 0.063001662, 0.076900616 0.03774412 0.063414663, 0.076601446 0.037597403 0.063209087, 0.075694799 0.038665697 0.06300205, 0.074207649 0.042796344 0.063414842, 0.073450133 0.044083744 0.063414812, 0.073918849 0.042629808 0.063209474, 0.072879463 0.043741122 0.063002378, 0.073164299 0.043912143 0.063209504, 0.071183205 0.047657192 0.06341514, 0.07027027 0.048993364 0.06341508, 0.070906252 0.047471806 0.063209653, 0.069724262 0.048612669 0.063002646, 0.069996864 0.048802704 0.063209653, 0.067840874 0.05230543 0.063415289, 0.066762745 0.053674504 0.063415408, 0.067576915 0.05210191 0.06321004, 0.066244066 0.05325748 0.063002914, 0.066503018 0.053465754 0.06321007, 0.064195454 0.056719705 0.063415587, 0.062943876 0.058105439 0.063415706, 0.063945711 0.056499124 0.063210219, 0.062454939 0.057653964 0.063003242, 0.062699229 0.057879388 0.063210189, 0.060263485 0.060880825 0.063415885, 0.058831751 0.062265396 0.063415915, 0.060029 0.060644001 0.063210398, 0.058374614 0.06178169 0.063003391, 0.058602899 0.062023118 0.063210607, 0.056062341 0.064770088 0.063415945, 0.055844128 0.064518064 0.063210696, 0.054022104 0.065621287 0.063003659, 0.054445237 0.066135049 0.063416123, 0.054233313 0.06587781 0.063210726, 0.051610529 0.068370029 0.063416183, 0.051409811 0.068103939 0.063210934, 0.049417973 0.069154799 0.063003898, 0.049804986 0.069696397 0.063416272, 0.049611062 0.06942521 0.063210905, 0.046928614 0.071664453 0.063416481, 0.046746045 0.071385652 0.063211173, 0.044583082 0.072366118 0.063004136, 0.044932276 0.072932616 0.0634166, 0.044757336 0.072648868 0.063211143, 0.042036951 0.074639022 0.0634166, 0.041873425 0.07434845 0.063211292, 0.039540589 0.075239658 0.063004225, 0.039850146 0.075828925 0.063416481, 0.039695114 0.075533956 0.063211352, 0.036957502 0.077280089 0.063416779, 0.036813557 0.076979309 0.063211262, 0.03431347 0.077762693 0.063004404, 0.034582257 0.078371748 0.063416928, 0.03444773 0.078066722 0.063211352, 0.031712741 0.07957612 0.063416928, 0.031589508 0.079266384 0.06321156, 0.028926551 0.079922974 0.063004524, 0.029153228 0.080548882 0.063416898, 0.029039592 0.080235571 0.063211501, 0.026326805 0.081516296 0.063416988, 0.026224345 0.081199139 0.06321165, 0.023404807 0.081710726 0.063004583, 0.02358824 0.082350537 0.063417017, 0.0234963 0.082030118 0.063211828, 0.020823002 0.083092943 0.063417017, 0.020742059 0.082769394 0.063211739, 0.017773807 0.0831175 0.063004464, 0.017913014 0.083768234 0.063417137, 0.017843306 0.083442315 0.063211828, 0.015226245 0.084298134 0.063417256, 0.015167028 0.083969936 0.063211799, 0.012060165 0.084136486 0.063004583, 0.01215446 0.084795505 0.063417017, 0.012107164 0.084465623 0.063211709, 0.0095616877 0.085126609 0.063417286, 0.0095244348 0.084795505 0.063211799, 0.0062900782 0.084763512 0.063004524, 0.0063393414 0.085427195 0.063417226, 0.0063146353 0.085094839 0.063211888, 0.0038540661 0.085575297 0.063417256, 0.0038390756 0.08524248 0.063211858, 0.00049075484 0.084994957 0.063004792, 0.00049442053 0.085660547 0.063417196, 0.00049269199 0.085327268 0.063211888, -0.0018703938 0.085641608 0.063417256, -0.001863271 0.085308403 0.063211977, -0.0053109825 0.084830403 0.063004464, -0.0053527653 0.085494667 0.063417256, -0.0053317547 0.085162118 0.063211992, -0.0075867772 0.08532542 0.063417286, -0.0075570941 0.084993273 0.063211799, 0.013217613 -0.084305912 0.063202247, 0.011131272 -0.084606558 0.063202277, 0.011174724 -0.084937215 0.06340757, 0.013269201 -0.084635228 0.063407645, 0.016944811 -0.083976671 0.06340766, 0.013321057 -0.084965572 0.06361112, 0.018966034 -0.083886206 0.063611433, 0.018892482 -0.083560064 0.063407838, 0.016878858 -0.083649799 0.063202247, 0.018818915 -0.083234966 0.063202456, 0.022635892 -0.082624465 0.063407615, 0.024526507 -0.082432017 0.063611493, 0.024431095 -0.082111582 0.063407823, 0.022547677 -0.082302928 0.063202336, 0.024336189 -0.081792042 0.063202396, 0.028221354 -0.080887243 0.063407898, 0.029977426 -0.080609947 0.063611507, 0.029860944 -0.080296308 0.063407853, 0.028111592 -0.080572516 0.06320262, 0.029744655 -0.079983979 0.06320259, 0.033675253 -0.078772828 0.063407853, 0.03529422 -0.078427464 0.063611567, 0.03515707 -0.078122541 0.063407883, 0.033544213 -0.078466311 0.063202694, 0.035020262 -0.077818394 0.063202545, 0.038972288 -0.076291054 0.063407943, 0.040453687 -0.075895011 0.063611701, 0.040296465 -0.075599924 0.063408017, 0.038820595 -0.075994253 0.063202813, 0.040139601 -0.07530576 0.063202888, 0.044087321 -0.07345368 0.063408211, 0.045432404 -0.073023453 0.063611925, 0.043915763 -0.073167875 0.063202932, 0.04899697 -0.070273891 0.063408643, 0.050208226 -0.069825947 0.063612029, 0.048806354 -0.070000425 0.063203141, 0.053678095 -0.066766322 0.063408807, 0.054759562 -0.066316441 0.063612238, 0.053469345 -0.066506416 0.063203365, 0.058109075 -0.062947512 0.063408867, 0.05906643 -0.062510714 0.063612536, 0.05788295 -0.062702626 0.063203618, 0.062269077 -0.058835343 0.063409179, 0.063109651 -0.058426067 0.063612655, 0.062026829 -0.058606431 0.063203856, 0.066138685 -0.054448768 0.063409284, 0.066870853 -0.054080471 0.063612893, 0.065881461 -0.054236963 0.063204035, 0.069700047 -0.049808457 0.063409448, 0.07033354 -0.049493104 0.063613221, 0.069428727 -0.049614727 0.063204303, 0.072936341 -0.044935837 0.06340979, 0.073482007 -0.044684887 0.063613534, 0.072652608 -0.044761002 0.063204572, 0.075832441 -0.039853662 0.063410118, 0.076302171 -0.039677098 0.063613832, 0.075537488 -0.039698631 0.06320481, 0.078375265 -0.034585878 0.063410357, 0.078781739 -0.034492016 0.063614115, 0.078070283 -0.034451172 0.063205123, 0.080552578 -0.029156759 0.063410714, 0.080909431 -0.029152974 0.063614383, 0.080239043 -0.029043138 0.063205466, -0.083745703 0.018031076 0.063413441, -0.08407253 0.018101633 0.063617036, -0.0834198 0.017960966 0.063208103, -0.084763229 0.012397185 0.063413173, -0.085094169 0.012445658 0.063616648, -0.084433451 0.012348965 0.06320776, -0.085402206 0.0067079812 0.063412771, -0.085735664 0.0067340732 0.063616484, -0.08506991 0.0066818744 0.063207477, -0.085659817 0.00098878145 0.063412473, -0.085994288 0.00099267066 0.063616142, -0.085326537 0.00098492205 0.063207209, -0.085534841 -0.0047348291 0.063412085, -0.085868835 -0.0047533661 0.063615784, -0.085202143 -0.0047165304 0.063206866, -0.085027874 -0.010437325 0.063412055, -0.085359737 -0.010478258 0.063615486, -0.084696904 -0.010396779 0.063206509, -0.08414115 -0.016093433 0.063411579, -0.084469348 -0.01615639 0.063615054, -0.083813593 -0.016030684 0.063206077, -0.082878575 -0.021677375 0.063411236, -0.083202049 -0.021761984 0.063614756, -0.08255592 -0.021593168 0.063205898, -0.081245601 -0.027164742 0.063410908, -0.081562966 -0.027270705 0.063614666, -0.080929667 -0.027058989 0.063205615, -0.079250291 -0.03253071 0.063410595, -0.079559416 -0.032657698 0.063614056, -0.078941658 -0.032404095 0.063205287, -0.076900661 -0.037751362 0.063410267, -0.077200741 -0.037898704 0.063613951, -0.074497327 -0.042970508 0.063613638, -0.076601356 -0.037604392 0.063204855, -0.074207515 -0.042803347 0.063409939, -0.073450118 -0.044090852 0.063409895, -0.071460932 -0.047850445 0.063613296, -0.073918849 -0.042636856 0.063204601, -0.073164269 -0.043919235 0.063204587, -0.07118313 -0.047664315 0.063409999, -0.070270181 -0.049000561 0.063409656, -0.068105653 -0.052516699 0.063613102, -0.070906222 -0.047478974 0.063204512, -0.069996819 -0.048809841 0.063204348, -0.067840651 -0.052312553 0.063409403, -0.066762626 -0.053681627 0.063409314, -0.064445987 -0.056948379 0.063612759, -0.067576706 -0.052109078 0.063204125, -0.066502735 -0.053472936 0.06320405, -0.064195454 -0.056726903 0.063409314, -0.062944025 -0.058112517 0.063409135, -0.060498625 -0.061125726 0.063612565, -0.063945666 -0.056506172 0.063203856, -0.06269899 -0.057886556 0.063203782, -0.06026341 -0.060888156 0.063408956, -0.058831617 -0.062272608 0.063408896, -0.056281045 -0.065030053 0.063612312, -0.060028985 -0.060651287 0.063203692, -0.05860281 -0.062030166 0.063203618, -0.056062132 -0.064777255 0.063408822, -0.05584392 -0.064525187 0.063203573, -0.054445103 -0.066142365 0.063408628, -0.051812068 -0.068643972 0.063612193, -0.054233417 -0.065884948 0.063203439, -0.0516105 -0.068377286 0.063408539, -0.051409796 -0.068111107 0.06320326, -0.049804792 -0.06970349 0.063408434, -0.047111586 -0.071951523 0.063611835, -0.049611062 -0.069432199 0.063203186, -0.046928585 -0.071671754 0.06340839, -0.046745896 -0.071392775 0.063202932, -0.044932276 -0.072939709 0.063408256, -0.042200968 -0.074937448 0.06361191, -0.044757366 -0.07265605 0.063203007, -0.042036936 -0.074646145 0.063408256, -0.041873142 -0.074355647 0.063202828, -0.039850071 -0.075836211 0.063408256, -0.037101582 -0.077588901 0.063611716, -0.039695099 -0.075541094 0.063202888, -0.036957383 -0.077287123 0.063408196, -0.036813527 -0.076986447 0.063202679, -0.034582242 -0.078378767 0.063408077, -0.03183645 -0.079893708 0.063611522, -0.034447461 -0.078073859 0.063202754, -0.0317128 -0.079583108 0.063407913, -0.031589493 -0.079273492 0.063202649, -0.029153109 -0.080555961 0.063407943, -0.026429474 -0.081841677 0.063611463, -0.029039472 -0.080242634 0.063202634, -0.026326776 -0.081523582 0.063407779, -0.026224315 -0.081206292 0.06320253, -0.023587942 -0.08235772 0.063407794, -0.020904198 -0.0834243 0.063611403, -0.023496225 -0.0820373 0.063202381, -0.020822987 -0.083099917 0.063407779, -0.020741984 -0.082776546 0.063202366, -0.017913029 -0.083775476 0.063407838, -0.015285686 -0.084634334 0.063611403, -0.017843217 -0.083449557 0.063202381, -0.01522626 -0.084305197 0.063407674, -0.015167102 -0.083977208 0.063202396, -0.01215446 -0.084802523 0.063407555, -0.0095987469 -0.085466236 0.063611209, -0.012107238 -0.084472597 0.063202322, -0.0095615387 -0.085133925 0.063407555, -0.0095243007 -0.084802791 0.063202187, -0.0063392818 -0.085434362 0.063407511, -0.0038691461 -0.085916474 0.063611269, -0.0063145906 -0.085101843 0.063202232, -0.003854081 -0.08558245 0.06340754, -0.0038390756 -0.085249633 0.063202277, -0.00049437582 -0.085667938 0.063407525, 0.0018779486 -0.085983127 0.063611254, -0.00049257278 -0.08533439 0.063202277, 0.0018707067 -0.08564879 0.06340754, 0.0018632263 -0.085315451 0.063202247, 0.0053527057 -0.085501835 0.063407511, 0.0076164603 -0.085665688 0.063611314, 0.0053319782 -0.085169107 0.063202202, 0.0075868219 -0.085332602 0.06340766, 0.0075574219 -0.085000575 0.063202232, 0.013217673 -0.084298953 -0.063211814, 0.011131167 -0.08459954 -0.063211873, 0.013269201 -0.08462818 -0.063417286, 0.011174738 -0.084930077 -0.06341739, 0.013321042 -0.084958553 -0.06362088, 0.016878918 -0.0836429 -0.063211903, 0.01881896 -0.083227858 -0.063211888, 0.016944736 -0.083969548 -0.063417077, 0.018966079 -0.083878949 -0.063620791, 0.018892363 -0.083552793 -0.063417077, 0.022547722 -0.082295999 -0.063211828, 0.024336025 -0.081784919 -0.063211754, 0.022635832 -0.082617372 -0.063417137, 0.024526447 -0.082424954 -0.063620716, 0.024431109 -0.08210434 -0.063416943, 0.028111532 -0.080565333 -0.063211635, 0.029744729 -0.079976931 -0.063211769, 0.028221443 -0.080880091 -0.063416973, 0.029977366 -0.080602661 -0.063620672, 0.029860854 -0.080289245 -0.063416958, 0.033544183 -0.078459203 -0.063211471, 0.035020381 -0.07781148 -0.06321153, 0.033675313 -0.078765631 -0.063416883, 0.035294339 -0.078420356 -0.063620448, 0.035157084 -0.078115419 -0.063416854, 0.038820431 -0.075987056 -0.063211426, 0.040139645 -0.075298876 -0.063211292, 0.03897211 -0.076284006 -0.063416854, 0.040453702 -0.075887859 -0.063620329, 0.040296465 -0.075592726 -0.063416719, 0.043915689 -0.073160827 -0.063211277, 0.044087425 -0.073446602 -0.06341657, 0.045432329 -0.07301642 -0.06362015, 0.048806265 -0.069993392 -0.063211143, 0.048996955 -0.070266604 -0.063416466, 0.050208107 -0.069818869 -0.063619941, 0.053469241 -0.066499561 -0.063210994, 0.05367814 -0.066759065 -0.063416183, 0.054759547 -0.066309199 -0.063619748, 0.057883039 -0.062695578 -0.063210621, 0.05810912 -0.062940508 -0.063415945, 0.059066385 -0.062503621 -0.063619539, 0.062026754 -0.058599249 -0.063210309, 0.062269002 -0.058828235 -0.06341581, 0.063109547 -0.05841887 -0.063619331, 0.065881386 -0.05422999 -0.063210025, 0.0661387 -0.054441541 -0.063415602, 0.066870853 -0.05407311 -0.063619003, 0.069428772 -0.04960756 -0.063209891, 0.069700107 -0.04980126 -0.063415304, 0.070333436 -0.049485907 -0.063618988, 0.072652549 -0.044753954 -0.063209698, 0.072936341 -0.044928715 -0.063415036, 0.073481888 -0.044677764 -0.063618481, 0.075537443 -0.039691746 -0.063209414, 0.075832427 -0.03984645 -0.063414827, 0.076302141 -0.039669916 -0.063618213, 0.078070298 -0.034444258 -0.063209102, 0.078375354 -0.034578726 -0.063414335, 0.078781649 -0.034484893 -0.063618034, 0.080238983 -0.029036224 -0.063208759, 0.080552563 -0.029149607 -0.063414171, 0.080909446 -0.029145807 -0.063617691, -0.0834198 0.017967939 -0.063206166, -0.083745673 0.018038273 -0.063411415, -0.084072664 0.018108636 -0.063614905, -0.084433541 0.012356147 -0.063206419, -0.084763199 0.012404412 -0.063411683, -0.085094154 0.01245293 -0.063615456, -0.08506988 0.0066889375 -0.063206881, -0.085402519 0.0067152679 -0.063411921, -0.085735723 0.0067413747 -0.06361559, -0.085326463 0.0009919554 -0.06320715, -0.085659936 0.00099590421 -0.063412443, -0.085994303 0.00099988282 -0.063615963, -0.085202113 -0.0047093928 -0.063207462, -0.085534945 -0.0047278553 -0.063412681, -0.085868612 -0.0047462136 -0.063616499, -0.084696978 -0.01038982 -0.063207716, -0.085027769 -0.010430127 -0.063412845, -0.085359678 -0.010471106 -0.063616559, -0.083813667 -0.01602371 -0.063207999, -0.084140942 -0.01608634 -0.063413158, -0.084469542 -0.016149119 -0.063616797, -0.082556039 -0.021585882 -0.063208163, -0.0828785 -0.021670267 -0.063413709, -0.083202109 -0.021754846 -0.063617259, -0.080929667 -0.027051896 -0.063208625, -0.081245631 -0.02715762 -0.063413948, -0.081562832 -0.027263507 -0.063617468, -0.078941628 -0.032396927 -0.063209027, -0.079250306 -0.032523587 -0.063414261, -0.079559624 -0.032650575 -0.063618034, -0.076601446 -0.037597343 -0.063209191, -0.076900721 -0.037744313 -0.063414603, -0.077200755 -0.037891567 -0.063618183, -0.073918968 -0.042629883 -0.063209519, -0.073164314 -0.043912098 -0.063209593, -0.074207738 -0.042796299 -0.063414827, -0.074497372 -0.042963296 -0.063618422, -0.073450089 -0.044083729 -0.063414916, -0.071460947 -0.047843352 -0.063618883, -0.070906162 -0.047472 -0.063209608, -0.069996819 -0.048802689 -0.063209891, -0.071183279 -0.047657236 -0.063414991, -0.070270211 -0.048993275 -0.063415349, -0.068105519 -0.052509472 -0.063618913, -0.067576975 -0.052101776 -0.063209951, -0.066502959 -0.053465813 -0.063210011, -0.067840755 -0.052305371 -0.063415259, -0.066762671 -0.053674459 -0.063415423, -0.064446092 -0.056941196 -0.063619345, -0.063945666 -0.056499138 -0.063210264, -0.062699184 -0.057879284 -0.063210458, -0.064195469 -0.056719795 -0.063415587, -0.062943846 -0.058105394 -0.063415796, -0.060498685 -0.061118662 -0.06361939, -0.060029 -0.06064406 -0.063210502, -0.05860278 -0.062023193 -0.063210666, -0.060263485 -0.060881078 -0.063415781, -0.058831662 -0.062265545 -0.063416004, -0.056281179 -0.065022975 -0.063619748, -0.055843949 -0.064518183 -0.063210741, -0.056062311 -0.064770192 -0.063415959, -0.054233387 -0.06587781 -0.063210979, -0.054445103 -0.066135094 -0.063416064, -0.051812127 -0.068637058 -0.063619822, -0.051409796 -0.068103984 -0.063210949, -0.051610515 -0.068370104 -0.063416272, -0.049610958 -0.069425166 -0.063211069, -0.049804792 -0.069696337 -0.063416332, -0.047111675 -0.071944356 -0.063620135, -0.046746016 -0.071385756 -0.063211113, -0.04692851 -0.071664587 -0.063416481, -0.044757336 -0.072648838 -0.063211232, -0.044932172 -0.072932631 -0.063416526, -0.042200997 -0.074930221 -0.063620239, -0.041873172 -0.074348539 -0.063211381, -0.042036831 -0.074638948 -0.063416645, -0.039695099 -0.075533971 -0.063211471, -0.039850175 -0.075828925 -0.06341663, -0.037101552 -0.077581778 -0.063620374, -0.036813542 -0.076979384 -0.063211471, -0.036957428 -0.077280074 -0.063416719, -0.034447625 -0.078066796 -0.063211396, -0.034582302 -0.078371495 -0.063416928, -0.031836644 -0.079886615 -0.063620627, -0.031589523 -0.079266369 -0.063211635, -0.031712875 -0.079575792 -0.063417032, -0.029039606 -0.08023563 -0.063211426, -0.029153094 -0.080548912 -0.063416958, -0.026429579 -0.081834435 -0.063620791, -0.026224196 -0.081199452 -0.06321156, -0.026326612 -0.081516579 -0.063416988, -0.023496285 -0.082030192 -0.063211694, -0.023588032 -0.082350612 -0.063417077, -0.020904332 -0.083417088 -0.063620806, -0.020741984 -0.082769498 -0.063211769, -0.020823002 -0.083092794 -0.063417062, -0.017843232 -0.083442405 -0.063211754, -0.017913043 -0.083768219 -0.063417107, -0.015285596 -0.084627196 -0.063620821, -0.015167043 -0.08397001 -0.063211843, -0.01522629 -0.084298104 -0.063417047, -0.012107223 -0.084465474 -0.063211799, -0.012154415 -0.084795386 -0.063417241, -0.0095988363 -0.085459083 -0.063620761, -0.0095243156 -0.084795579 -0.063211799, -0.0095614791 -0.085126862 -0.063417241, -0.006314531 -0.085094869 -0.063211754, -0.006339252 -0.085427299 -0.063417271, -0.0038692504 -0.085909277 -0.063620999, -0.0038391501 -0.085242391 -0.063211769, -0.0038540959 -0.085575417 -0.063417345, -0.00049251318 -0.085327327 -0.063211948, -0.00049437582 -0.085660785 -0.063417271, 0.0018779486 -0.085976049 -0.06362085, 0.0018632263 -0.085308403 -0.063211963, 0.0018704981 -0.085641742 -0.06341733, 0.0053318441 -0.085162044 -0.063211992, 0.0053526312 -0.085494697 -0.063417226, 0.0076164901 -0.08565864 -0.063620925, 0.0075572878 -0.084993571 -0.063211769, 0.0075868368 -0.085325345 -0.063417301, -0.063621387 -0.016592935 -0.026764095, -0.065028161 -0.009715274 -0.026763722, -0.060251698 -0.012327045 -0.024310008, -0.061045036 -0.0074645579 -0.02430971, -0.065693393 -0.0027268231 -0.026763186, -0.061446831 -0.0025543123 -0.024309576, -0.061454251 0.0023723841 -0.024309322, -0.065609962 0.0042929351 -0.026763007, -0.061067328 0.007283926 -0.024309129, -0.064778462 0.01126346 -0.026762649, -0.060288474 0.01214847 -0.024308681, 0.059100822 -0.024118066 -0.025657713, 0.055223376 -0.027065679 -0.024310976, 0.058105126 -0.023476213 -0.024985671, 0.056748703 -0.037235484 -0.027992025, 0.057636693 -0.023047209 -0.024642318, 0.056515351 -0.033600435 -0.026765078, 0.057212785 -0.022558481 -0.024310753, 0.052610621 -0.039434567 -0.026765317, 0.030047745 -0.060860008 -0.027993664, 0.031538814 -0.057690769 -0.026766539, 0.025207967 -0.060724303 -0.026766732, 0.011760071 -0.064688399 -0.026766866, 0.014998689 -0.066195384 -0.027993679, 0.018589914 -0.063065737 -0.026766747, -0.019607097 -0.064979807 -0.027993664, -0.016104534 -0.063745752 -0.026766703, -0.022809252 -0.061665431 -0.026766688, -0.049836352 -0.046078488 -0.027992651, -0.046313137 -0.046669334 -0.026765853, -0.051025048 -0.041465461 -0.026765451, 0.059775785 -0.027383342 -0.026764706, 0.062583193 -0.02455619 -0.027618572, -0.055155382 -0.035788968 -0.026765123, -0.059221938 -0.033161297 -0.027991727, -0.058656573 -0.029704526 -0.02676481, 0.061382607 -0.024667233 -0.026997954, 0.060202941 -0.024518564 -0.026334375, -0.067860067 0.0014284402 -0.027990088, -0.062013626 0.014230251 -0.025535524, 0.052879617 -0.031399369 -0.024311259, 0.050196543 -0.035531119 -0.024311453, -0.06615591 0.015180796 -0.027989119, 0.047191218 -0.039435148 -0.024311662, 0.048106208 -0.044818789 -0.026765689, 0.065233946 -0.023324415 -0.028801784, 0.063892573 -0.024133936 -0.028236464, 0.043883234 -0.043086052 -0.0243119, 0.043053433 -0.049692199 -0.026765987, 0.0402935 -0.046460375 -0.024312079, 0.036445245 -0.049536541 -0.024312451, 0.037509993 -0.053999349 -0.026766285, 0.032363057 -0.052294835 -0.024312496, 0.028073087 -0.05471769 -0.024312511, 0.023603097 -0.056789204 -0.024312735, 0.01898171 -0.058496192 -0.02431275, 0.014238343 -0.05982779 -0.024312899, 0.009403497 -0.060775459 -0.024312899, 0.0047960281 -0.065573454 -0.026767001, 0.0045085698 -0.061333299 -0.024312869, -0.00041525066 -0.061497331 -0.024312899, -0.0022229105 -0.065710902 -0.026767001, -0.0053365678 -0.06126669 -0.024312958, -0.0092161447 -0.065099433 -0.026766837, -0.010223702 -0.060643002 -0.024312779, -0.015045106 -0.059629932 -0.024312899, -0.019770056 -0.058234379 -0.02431263, -0.024367958 -0.056465134 -0.024312675, -0.029253915 -0.058882207 -0.026766449, -0.028809741 -0.05433324 -0.024312392, -0.03536509 -0.055427462 -0.02676627, -0.033066466 -0.051852867 -0.024312466, -0.037110895 -0.049039885 -0.024312153, -0.041073278 -0.051341131 -0.026766106, -0.040917397 -0.045911789 -0.024311975, -0.044461206 -0.042489216 -0.024311766, -0.047719777 -0.038794056 -0.024311796, -0.05067195 -0.034849852 -0.024311364, -0.053299069 -0.030682027 -0.024311215, -0.055583894 -0.026317373 -0.024310842, -0.061489582 -0.023281366 -0.026764452, -0.057512239 -0.02178365 -0.024310589, -0.059071392 -0.017110214 -0.024310529, -0.046860799 0.05708167 -0.03460604, -0.04799059 0.056134731 -0.034606054, -0.048087478 0.056248009 -0.036142111, 0.060161352 0.040805906 -0.031761527, 0.056941375 0.045190707 -0.031761184, 0.060754389 0.041208148 -0.033128187, -0.041198835 0.058717385 -0.030556932, -0.040521652 0.057752311 -0.029561162, -0.042506829 0.057777658 -0.030556768, -0.038176075 0.06072624 -0.030556753, 0.057502657 0.045636356 -0.033127859, 0.05936195 0.040263727 -0.03055802, 0.056184798 0.044590294 -0.030557558, -0.043765217 0.059488147 -0.034606099, -0.046580687 0.056740522 -0.033127174, -0.043503836 0.059132695 -0.033127114, -0.047704086 0.055799544 -0.033127189, 0.057848126 0.045910463 -0.034606516, 0.054342717 0.050010726 -0.034606561, 0.057964683 0.046003103 -0.036142513, 0.05445224 0.050111398 -0.03614229, -0.046126157 0.056186691 -0.031760469, 0.055261508 0.043857545 -0.029561996, 0.05838652 0.039601982 -0.029562145, -0.043079227 0.058555529 -0.031760395, -0.04723838 0.055254668 -0.031760588, 0.054018259 0.049711928 -0.033127591, -0.045513362 0.055440098 -0.030557021, 0.053490847 0.049226657 -0.03176108, -0.051035464 0.053381234 -0.034606174, -0.052064925 0.052587733 -0.03614229, 0.052780181 0.048572659 -0.030557528, -0.046610743 0.054520577 -0.030557096, 0.050547481 0.05384399 -0.034606174, -0.044765219 0.054528758 -0.029561162, 0.050649062 0.053952709 -0.036142126, 0.051912725 0.047774345 -0.029561818, -0.050730765 0.053062648 -0.033127382, -0.050235584 0.052544519 -0.031760886, 0.050245523 0.053522408 -0.033127353, 0.049754992 0.052999958 -0.031760916, -0.049568221 0.05184631 -0.030557126, -0.054919183 0.049376845 -0.034606457, 0.049093992 0.052295759 -0.030557171, -0.055764422 0.048647076 -0.036142364, -0.048753574 0.050994366 -0.02956149, -0.054591313 0.049081877 -0.033127695, 0.048287064 0.051436305 -0.029561415, -0.054058373 0.048602551 -0.031760991, -0.053340331 0.047956914 -0.030557364, -0.058489591 0.045090511 -0.034606561, -0.05916658 0.044446647 -0.036142692, -0.052463546 0.047168911 -0.029561535, -0.058140337 0.044821069 -0.033127874, -0.057572559 0.044383451 -0.031761199, -0.056807727 0.043793768 -0.030557647, -0.061726183 0.040546864 -0.034606814, -0.062252864 0.040009096 -0.036142945, -0.055874363 0.043074101 -0.029561833, -0.061357692 0.040304765 -0.033128262, -0.060758412 0.039911076 -0.031761527, -0.059951365 0.039380789 -0.03055796, -0.064610571 0.035771862 -0.034607247, -0.06500718 0.035358444 -0.036143154, -0.058966219 0.03873378 -0.029562265, 0.035948515 0.060704827 -0.029560909, -0.064224645 0.035557911 -0.033128336, -0.063597783 0.035210997 -0.031761825, -0.062752709 0.0347431 -0.030558065, -0.067126215 0.030792579 -0.034607366, 0.032892376 0.066123843 -0.034605488, 0.027977899 0.068348274 -0.034605384, 0.032958597 0.06625703 -0.036141485, -0.067414507 0.030518726 -0.036143318, 0.02803424 0.068486109 -0.036141276, -0.061721504 0.034172013 -0.02956225, 0.031421557 0.063166901 -0.029560894, 0.031946495 0.06422244 -0.030556649, -0.066725492 0.030608833 -0.03312856, 0.027811006 0.067940161 -0.033126593, 0.032695875 0.065728754 -0.033126563, -0.066073909 0.030309811 -0.031762049, 0.027539328 0.06727697 -0.031759977, 0.032376528 0.065087169 -0.031760156, 0.027173579 0.066383019 -0.030556262, -0.065196127 0.029907137 -0.030558437, -0.069258973 0.025637865 -0.034607738, 0.022914335 0.070208147 -0.03460522, -0.069462299 0.025516436 -0.036143765, 0.02296041 0.070349962 -0.036141112, 0.021458939 0.070666835 -0.034605145, -0.064124808 0.029415578 -0.029562637, 0.017764121 0.071838304 -0.036141008, 0.022777557 0.069788978 -0.033126518, -0.068845257 0.025484666 -0.033128902, 0.021330699 0.07024464 -0.033126503, -0.06817323 0.025235847 -0.031762272, 0.022555143 0.069107667 -0.031759799, -0.067267522 0.024900511 -0.030558735, 0.021122605 0.069558859 -0.031759843, -0.066162139 0.024491295 -0.02956304, 0.02225554 0.068189561 -0.030556321, 0.046461597 0.053570032 -0.029826164, 0.017728508 0.071693584 -0.034604967, 0.044403762 0.054823861 -0.029561311, 0.040283605 0.057918847 -0.029561058, 0.042356417 0.056871444 -0.029825926, 0.020841926 0.068634778 -0.030556351, 0.016063735 0.072084904 -0.03460525, 0.012473091 0.072943166 -0.036141053, 0.017622545 0.071265534 -0.033126429, 0.038017541 0.059858963 -0.029825836, 0.020499378 0.06750679 -0.029560581, 0.033468857 0.062516361 -0.029825762, 0.015967757 0.071654305 -0.033126414, 0.048158124 0.053366497 -0.030719668, 0.017450571 0.070569709 -0.031759694, 0.01581192 0.070954815 -0.031759769, 0.047391295 0.054433092 -0.031051442, 0.046177045 0.055089667 -0.030719489, 0.017218664 0.069632187 -0.030556098, 0.045753658 0.056490436 -0.031760469, 0.045145735 0.055739909 -0.030556962, 0.044098988 0.056766957 -0.030719459, 0.012447983 0.072796419 -0.034604967, 0.043267578 0.057765335 -0.031051368, 0.015601888 0.070012167 -0.030556321, 0.012373567 0.072361887 -0.033126459, 0.040956721 0.058886603 -0.030556813, 0.041996449 0.058339551 -0.030719444, 0.041508228 0.059679434 -0.031760454, 0.039800286 0.059859499 -0.030719325, 0.010576785 0.07309179 -0.034605041, 0.0071154833 0.073659331 -0.036141083, 0.01534538 0.068861559 -0.029560462, 0.038910449 0.060785756 -0.031051144, 0.037041232 0.062550232 -0.031760141, 0.037587658 0.061272934 -0.030719236, 0.03654927 0.061719075 -0.030556738, 0.012252897 0.071655199 -0.031759679, 0.010513574 0.072655246 -0.033126146, 0.035285875 0.062626854 -0.030719161, 0.012089983 0.070703298 -0.030556157, 0.034343332 0.063478023 -0.03105092, 0.032975003 0.063873887 -0.030719087, 0.007101059 0.073510855 -0.034605026, 0.010410935 0.071945846 -0.031759709, 0.048871309 0.0540535 -0.032042369, 0.0070587844 0.073071942 -0.033126414, 0.048014924 0.055079311 -0.032394856, 0.010272682 0.07099013 -0.030556157, 0.046864584 0.055802509 -0.032042325, 0.046204925 0.057047307 -0.033127248, 0.0050294846 0.073681772 -0.034604967, 0.044783324 0.057486042 -0.032042131, 0.001719743 0.073982194 -0.036140904, 0.0069897622 0.072358504 -0.03175962, 0.043858349 0.058443129 -0.032394543, 0.010103837 0.069823414 -0.029560387, 0.042654097 0.059083208 -0.032042146, 0.0049993396 0.073241711 -0.033126339, 0.041917339 0.060268 -0.033127084, 0.0068969578 0.071397185 -0.030556083, 0.040455326 0.060609892 -0.032042086, 0.0017164797 0.073833272 -0.034605056, 0.039466843 0.061494112 -0.032394409, 0.038214788 0.062047273 -0.032041892, 0.0374064 0.063166991 -0.03312692, 0.0049507916 0.0725265 -0.03175965, 0.03591004 0.063408881 -0.032041878, 0.0017059594 0.073392242 -0.033126399, 0.071567953 -0.018219739 -0.034610301, 0.072437137 -0.01512675 -0.036146209, 0.034864053 0.064215928 -0.03239429, 0.0048848838 0.071562961 -0.030556157, 0.071140662 -0.018110991 -0.033131406, 0.03357026 0.064678237 -0.032041758, -0.00054648519 0.073851049 -0.034604996, -0.0036849231 0.073910296 -0.036141023, 0.048417613 0.055517554 -0.033844531, 0.0016893744 0.07267575 -0.031759709, 0.072291389 -0.015096366 -0.034609959, 0.0465758 0.05750595 -0.036141902, 0.046482101 0.057390213 -0.03460592, 0.070446163 -0.017934144 -0.031764805, 0.0048047155 0.070387021 -0.029560238, 0.044233322 0.058905765 -0.033844292, 0.04225415 0.060752332 -0.036141798, -0.00054331124 0.073410079 -0.033126161, 0.071859717 -0.015006214 -0.033131301, 0.042169049 0.060630113 -0.034605876, 0.039812684 0.061979249 -0.033844128, 0.0016669929 0.071710184 -0.030556008, 0.069510251 -0.017695934 -0.030561104, 0.037631184 0.063546404 -0.034605607, 0.037706986 0.063674539 -0.03614153, 0.035179645 0.064721659 -0.033843994, -0.0036775172 0.073761538 -0.034605116, 0.072912827 -0.011733264 -0.034609988, 0.073348165 -0.0097986907 -0.036145672, -0.00053803623 0.072693527 -0.031759694, 0.071158201 -0.014859781 -0.031764492, 0.068367973 -0.017405257 -0.029565334, -0.0036556721 0.073321119 -0.03312625, 0.072477594 -0.011663303 -0.033131033, -0.00053070486 0.071727619 -0.030556053, 0.070212871 -0.014662519 -0.030561015, -0.0061192811 0.073599264 -0.034604952, -0.0090699494 0.073444098 -0.036141038, 0.073200554 -0.0097791851 -0.03460972, -0.0036199093 0.072605103 -0.031759664, 0.071769953 -0.011549458 -0.031764373, -0.00052207708 0.070548713 -0.029560387, 0.072763577 -0.0097208917 -0.033130914, -0.0060827136 0.073159575 -0.033126369, -0.0035718381 0.071640477 -0.030556127, 0.070816562 -0.011396021 -0.030560806, 0.072053283 -0.0096259713 -0.031764328, -0.0090517998 0.073296234 -0.034605011, -0.0060234815 0.072445363 -0.031759679, 0.07359077 -0.0061959922 -0.034609437, 0.073867932 -0.0044186562 -0.036145389, -0.0089976937 0.072858661 -0.033126384, 0.069652781 -0.011208802 -0.029565081, 0.071095958 -0.0094982535 -0.030560866, -0.0059433877 0.071482986 -0.030556098, 0.07315129 -0.0061591119 -0.03313081, -0.011657134 0.072927266 -0.034605101, -0.014406815 0.072586223 -0.036141098, -0.0089099407 0.072147235 -0.031759664, 0.073719338 -0.0044096559 -0.034609452, -0.0058456361 0.070308119 -0.029560342, -0.01158765 0.07249178 -0.033126384, 0.072437182 -0.0060991049 -0.031763986, 0.073279053 -0.0043834895 -0.033130646, -0.0087914616 0.071188718 -0.030556083, 0.07147494 -0.0060181618 -0.030560464, -0.014377862 0.072440103 -0.034605175, 0.072563678 -0.0043406487 -0.031763911, -0.01147446 0.071784124 -0.031759739, 0.073848531 -0.00062356889 -0.034609109, 0.073993504 0.00098527968 -0.036145106, -0.014291853 0.072007343 -0.033126354, 0.070300072 -0.0059193373 -0.029564679, 0.071599737 -0.0042831004 -0.030560389, -0.011322126 0.070830375 -0.030556083, -0.017128676 0.071839318 -0.034605145, 0.07384482 0.00098329782 -0.034609213, -0.019666687 0.07134077 -0.036141023, -0.014152423 0.07130447 -0.031759709, 0.07340765 -0.0006198287 -0.033130452, -0.01113604 0.069666401 -0.029560596, 0.073403999 0.00097720325 -0.033130422, -0.01702638 0.071410239 -0.033126324, -0.013964355 0.070356995 -0.030556098, 0.072691068 -0.00061386824 -0.031763718, 0.072687194 0.000967592 -0.031763598, -0.019627079 0.071197435 -0.03460519, 0.071725205 -0.0006056577 -0.030560225, -0.016860157 0.070713133 -0.031759873, 0.07368508 0.0049526691 -0.03460899, 0.073724315 0.0063838512 -0.036144882, -0.019509837 0.070772082 -0.033126414, 0.071721599 0.00095483661 -0.030560076, -0.016636088 0.0697736 -0.030556262, 0.073576093 0.0063708276 -0.03460893, 0.070546627 -0.00059580803 -0.029564545, -0.022502273 0.070341423 -0.03460519, -0.024821535 0.069714963 -0.036141276, 0.073245153 0.0049229562 -0.033130154, -0.01931946 0.070081159 -0.031759754, 0.073136792 0.0063326657 -0.033130065, -0.016362727 0.068626866 -0.029560462, -0.022368029 0.069921389 -0.033126503, 0.072530016 0.0048748404 -0.03176333, -0.019062862 0.069150031 -0.030556262, 0.072422788 0.0062708557 -0.031763494, 0.071566507 0.0048100352 -0.030559897, -0.024771765 0.069574744 -0.034605175, -0.022149652 0.069238752 -0.031759918, 0.073101267 0.010500506 -0.034608513, 0.073061794 0.011748299 -0.03614451, 0.071460545 0.0061875582 -0.030559689, -0.024623901 0.069159299 -0.033126473, 0.070390373 0.0047310293 -0.029564053, -0.021855295 0.068318948 -0.030556276, 0.072664693 0.010437772 -0.033129841, -0.027747512 0.06844224 -0.034605205, -0.02984412 0.067717105 -0.036141232, 0.071955338 0.010335743 -0.031763032, -0.024383456 0.068483964 -0.031759903, -0.021496192 0.067196101 -0.029560462, 0.070999384 0.010198593 -0.030559614, 0.072100237 0.015988573 -0.034608319, -0.0275819 0.068033606 -0.033126414, 0.072009534 0.017050251 -0.036144182, -0.0240594 0.067574039 -0.030556351, 0.069832504 0.010030851 -0.0295638, 0.071669772 0.015892997 -0.033129647, -0.029783994 0.067580894 -0.034605429, 0.070969865 0.015737697 -0.031762972, -0.027312592 0.067369074 -0.031759784, -0.029606327 0.067177236 -0.033126548, 0.070027173 0.015528589 -0.030559152, -0.026949942 0.066474304 -0.030556396, 0.070687681 0.021385357 -0.034607887, 0.070573017 0.022260994 -0.036143854, -0.032834515 0.066152483 -0.03460528, -0.034707323 0.065358073 -0.03614144, 0.068876356 0.015273526 -0.029563457, -0.029317334 0.066521272 -0.031759828, -0.026506826 0.065381721 -0.02956064, 0.07026571 0.02125755 -0.033129185, -0.032638386 0.065757155 -0.033126742, 0.069579691 0.021049857 -0.031762525, -0.028927684 0.065637618 -0.030556485, 0.068655387 0.020770177 -0.030559078, -0.034637585 0.065226361 -0.034605563, 0.068871915 0.026659921 -0.034607634, 0.068759888 0.027353108 -0.036143601, -0.032319754 0.065115422 -0.031760082, 0.067526951 0.020428896 -0.029563233, -0.034430683 0.06483674 -0.033126757, 0.068460882 0.026500776 -0.033128947, -0.031890661 0.06425032 -0.030556515, 0.067792326 0.026241973 -0.031762287, -0.034094647 0.064203858 -0.031760097, -0.037734151 0.063485175 -0.034605697, 0.066891745 0.025893241 -0.030558601, -0.039385468 0.062650159 -0.036141574, 0.066663101 0.031782866 -0.0346075, 0.066579983 0.032299235 -0.036143363, -0.031366393 0.063194394 -0.029560715, -0.033641681 0.063350916 -0.030556574, 0.065792322 0.025467739 -0.029562846, -0.03750892 0.063106075 -0.03312695, 0.066265047 0.031592891 -0.033128649, -0.039306194 0.062523931 -0.034605637, 0.065618291 0.031284392 -0.031762034, -0.037142649 0.062490091 -0.031760186, 0.064746574 0.030868664 -0.030558407, -0.039071649 0.062150747 -0.033126965, 0.06407398 0.036724001 -0.034607172, 0.064044729 0.03707324 -0.036143109, -0.036649331 0.061659858 -0.030556709, 0.063682288 0.030361518 -0.029562682, -0.038690209 0.061544046 -0.031760484, 0.063691601 0.036504745 -0.033128306, -0.042418361 0.060455769 -0.034605786, -0.043853551 0.059608027 -0.036141887, 0.063069716 0.036148086 -0.03176187, -0.036047071 0.060646519 -0.029561043, 0.062231913 0.035668075 -0.030558065, 0.061119437 0.041455582 -0.034606844, 0.061167926 0.041649148 -0.036142766, -0.04216516 0.060094714 -0.033127114, 0.061209187 0.035081699 -0.029562458, -0.041753545 0.059508011 -0.03176032, 0.05225268 -0.025610045 -0.020636573, 0.05003503 -0.029710367 -0.020636812, 0.049590617 -0.029446483 -0.019046217, -0.044059455 -0.042105272 -0.02395986, -0.045490399 -0.039346963 -0.023328617, -0.043482929 -0.041554496 -0.02332893, 0.053003684 -0.025978029 -0.022085086, -0.038716257 -0.04344216 -0.020637497, -0.040355816 -0.04120329 -0.019046798, -0.038372353 -0.043056369 -0.019046888, 0.050754055 -0.030137107 -0.022085115, 0.054008469 -0.026470333 -0.023327962, 0.051716313 -0.030708522 -0.023328215, -0.040717289 -0.041572616 -0.020637512, -0.042085648 -0.042969018 -0.02332902, -0.042673916 -0.040781289 -0.022085771, -0.041302487 -0.042169884 -0.022085637, 0.053654268 -0.021155775 -0.01904577, 0.051788703 -0.025382549 -0.019045904, -0.036815375 -0.044395059 -0.019047007, 0.054724529 -0.026821375 -0.023959056, 0.052401736 -0.031115517 -0.023959219, -0.039272577 -0.044066414 -0.022086039, -0.037145033 -0.04479298 -0.020637661, 0.054134935 -0.021345258 -0.02063635, -0.040017128 -0.044901818 -0.0233289, 0.054913089 -0.021651939 -0.022084817, -0.03480278 -0.045989752 -0.01904723, 0.05653961 -0.021372512 -0.023582816, 0.055954129 -0.022062421 -0.023327783, -0.037678972 -0.045436457 -0.022086114, 0.056836739 -0.021994099 -0.023958787, 0.056695834 -0.022354677 -0.023958713, -0.040547624 -0.045497015 -0.023960054, -0.035114616 -0.046401724 -0.020637587, -0.038393348 -0.046297818 -0.02332899, -0.033023357 -0.047283754 -0.019047156, -0.035619318 -0.047068521 -0.022086143, -0.033319443 -0.04770723 -0.02063784, -0.03629452 -0.047960863 -0.023329139, -0.031009808 -0.048627973 -0.019047245, -0.033798099 -0.048392877 -0.022086233, -0.036775604 -0.048596576 -0.023960277, -0.031287745 -0.049063623 -0.020637721, -0.034438819 -0.049310237 -0.023329198, -0.029005766 -0.049849391 -0.01904735, -0.031737283 -0.049768701 -0.022086114, -0.029265672 -0.050295964 -0.020638004, -0.032338932 -0.050712124 -0.023329347, -0.027017772 -0.050954103 -0.019047454, -0.029686302 -0.051018521 -0.02208665, -0.032767624 -0.051384434 -0.023960397, -0.027259856 -0.051410556 -0.020638123, -0.030249119 -0.051985547 -0.023329318, -0.024789974 -0.052074268 -0.019047529, -0.027651593 -0.052149415 -0.022086367, -0.02501224 -0.052540854 -0.020638078, -0.028175831 -0.053137928 -0.023329481, -0.02285248 -0.052953199 -0.019047663, -0.028549388 -0.053842425 -0.023960546, -0.02537173 -0.053295717 -0.022086486, -0.023057222 -0.053427517 -0.020638138, -0.025852621 -0.05430612 -0.023329437, -0.020405084 -0.053943545 -0.019047692, -0.023388505 -0.054195374 -0.022086561, -0.020587906 -0.054426774 -0.020638227, -0.023831934 -0.055222899 -0.023329496, -0.018540353 -0.054612413 -0.019047692, -0.024147868 -0.055954903 -0.02396059, -0.020883828 -0.055208817 -0.022086635, -0.01870653 -0.055101931 -0.020638138, -0.021279752 -0.056255639 -0.02332972, -0.015880838 -0.055444211 -0.019047692, -0.018975213 -0.05589354 -0.02208674, -0.01602307 -0.05594112 -0.020638242, -0.019335151 -0.056953087 -0.023329511, -0.014109507 -0.055921346 -0.019047752, -0.019591391 -0.057708159 -0.023960575, -0.016253322 -0.056744948 -0.02208674, -0.014235914 -0.056422323 -0.020638347, -0.016561508 -0.057820603 -0.023329735, -0.011247799 -0.056566387 -0.019047543, -0.014440358 -0.057233214 -0.022086814, -0.011348784 -0.057073161 -0.020638362, -0.014714062 -0.058318272 -0.023329824, -0.0095879138 -0.056871265 -0.019047707, -0.014909163 -0.059091195 -0.023960724, -0.011511713 -0.057893291 -0.022086844, -0.0096737742 -0.057380825 -0.020638272, -0.011730105 -0.058990717 -0.023329794, -0.0098127574 -0.058205292 -0.022086725, -0.0065381378 -0.057301983 -0.019047737, -0.0099988729 -0.059308723 -0.023329735, -0.0065966696 -0.057815373 -0.020638406, -0.056538537 0.011392862 -0.019043922, -0.0050047636 -0.0574563 -0.019047767, -0.057045266 0.011494949 -0.020634592, -0.010131299 -0.060095027 -0.023960948, -0.0066915751 -0.058646262 -0.02208671, -0.057864919 0.011660188 -0.02208288, -0.0050496906 -0.057970956 -0.020638317, -0.058962002 0.011881337 -0.023325846, -0.0068184435 -0.059757918 -0.02332969, -0.057269141 0.0068305731 -0.019044131, -0.0051221102 -0.058804125 -0.022086829, -0.059743598 0.012038827 -0.023956686, -0.057782188 0.0068918616 -0.02063477, -0.0017837137 -0.057646319 -0.019047886, -0.0052192807 -0.059918717 -0.023329794, -0.05861266 0.0069910437 -0.022083193, -0.00038951635 -0.057672381 -0.019047916, -0.059723794 0.007123664 -0.023326024, -0.0017998964 -0.058162749 -0.020638391, -0.0052884817 -0.060713097 -0.023960799, -0.05763188 0.0022245198 -0.019044444, -0.00039301813 -0.058189228 -0.020638421, -0.060515404 0.0072180033 -0.023957103, -0.001825586 -0.058998451 -0.022086829, -0.00039872527 -0.059025407 -0.022086799, -0.058148459 0.0022446066 -0.020635083, -0.058984011 0.0022770464 -0.022083476, -0.0018601418 -0.060116962 -0.023329869, -0.06010215 0.00232023 -0.023326367, -0.057625011 -0.002395615 -0.019044608, 0.0029829144 -0.057596773 -0.019047797, -0.00040629506 -0.060144156 -0.02332972, -0.060898885 0.0023510158 -0.023957357, 0.0042283088 -0.057518616 -0.019047901, 0.0030095428 -0.058112741 -0.020638391, -0.05814147 -0.0024170727 -0.020635188, -0.00041165948 -0.060941637 -0.023960873, -0.058976918 -0.0024516732 -0.0220837, 0.004266113 -0.058033913 -0.020638555, -0.060095012 -0.0024981201 -0.02332662, -0.05724822 -0.0070005506 -0.019044891, 0.0030527711 -0.058947623 -0.022086874, 0.0043272972 -0.058867782 -0.022086903, -0.060891777 -0.0025312155 -0.023957625, 0.0031107068 -0.060065225 -0.02332978, -0.057761118 -0.00706321 -0.020635486, 0.007728979 -0.057153702 -0.019047767, -0.058591276 -0.0071646869 -0.022083893, 0.0031517744 -0.060861379 -0.023960844, -0.059702009 -0.007300362 -0.023326918, 0.0044094175 -0.059983909 -0.02332966, 0.0077982545 -0.057665661 -0.020638376, -0.056504056 -0.011560425 -0.019045115, -0.060493588 -0.007397145 -0.023957834, 0.0044678003 -0.060778975 -0.023960829, 0.0079102516 -0.058494225 -0.022086814, -0.057010472 -0.011664003 -0.020635739, 0.0080602169 -0.05960314 -0.023329899, -0.057829663 -0.011831611 -0.022084147, -0.058926031 -0.012055814 -0.023327127, 0.012422442 -0.056320131 -0.019047812, -0.055397347 -0.016046196 -0.019045383, 0.0081671178 -0.060393304 -0.023960605, 0.012533695 -0.056824788 -0.020638302, -0.059707299 -0.012215495 -0.023958087, -0.055893824 -0.016189873 -0.020635903, 0.012713879 -0.057641193 -0.022086799, 0.012954831 -0.05873403 -0.023329765, -0.056696892 -0.01642248 -0.022084519, 0.01703082 -0.055101857 -0.019047633, -0.057771936 -0.016733736 -0.02332741, 0.013126627 -0.059512615 -0.023960873, -0.053935051 -0.020428896 -0.019045681, 0.017183512 -0.055595666 -0.020638227, -0.058537737 -0.016955629 -0.023958325, 0.017430484 -0.056394592 -0.022086799, -0.053508192 -0.021522075 -0.019045711, 0.017760947 -0.057463571 -0.02332963, -0.05441843 -0.020611972 -0.02063641, 0.021523029 -0.053507224 -0.019047648, -0.053987592 -0.021714881 -0.020636246, 0.017996326 -0.058225349 -0.023960546, -0.055200517 -0.020908162 -0.022084758, 0.021716028 -0.053986728 -0.020638183, -0.0547636 -0.022026733 -0.022084787, 0.022028029 -0.054762378 -0.022086605, -0.05624713 -0.021304578 -0.023327619, -0.052126721 -0.024680674 -0.019045919, 0.022445738 -0.055800617 -0.023329541, 0.025868371 -0.051547199 -0.019047484, -0.056992546 -0.02158688 -0.023958445, -0.055802003 -0.022444353 -0.023327604, 0.02274321 -0.05654031 -0.023960531, 0.026100084 -0.052009076 -0.020638108, -0.051548272 -0.025867134 -0.019045979, 0.026475176 -0.052756399 -0.022086561, -0.052593797 -0.024901703 -0.020636618, -0.056541741 -0.02274172 -0.023958758, 0.026977047 -0.053756475 -0.023329318, -0.052009985 -0.026098981 -0.020636603, 0.030036673 -0.049234897 -0.019047335, -0.053349659 -0.025259435 -0.022085086, 0.02733475 -0.054469064 -0.023960292, -0.052757576 -0.02647382 -0.022084877, 0.030305907 -0.049675986 -0.020638004, -0.05436106 -0.025738418 -0.023327872, 0.030741498 -0.05038996 -0.022086307, -0.049983859 -0.028773755 -0.019046083, 0.031324282 -0.051345065 -0.023329362, -0.055081785 -0.026079416 -0.023958892, 0.034000009 -0.046586484 -0.019047275, -0.053757668 -0.026975736 -0.023328066, 0.031739518 -0.052025706 -0.023960397, -0.049236089 -0.030035645 -0.019046322, 0.034304634 -0.047003835 -0.020637661, -0.050431818 -0.029031649 -0.020636782, 0.034797758 -0.04767932 -0.022086367, -0.049677223 -0.030304819 -0.020636842, 0.035457268 -0.048582971 -0.023329139, -0.051156431 -0.029448718 -0.02208522, 0.037731186 -0.043619618 -0.019046992, -0.050390869 -0.030740306 -0.022085294, 0.0359274 -0.049227104 -0.023960263, -0.052126363 -0.03000699 -0.023328215, 0.038069203 -0.044010311 -0.020637542, -0.047520205 -0.032682374 -0.019046426, 0.038616225 -0.044642717 -0.02208592, -0.052817389 -0.030404821 -0.023959115, -0.051346287 -0.031322867 -0.023328334, 0.039348334 -0.045489013 -0.023328915, 0.041153774 -0.040406495 -0.019046843, -0.047946006 -0.032975361 -0.020637065, 0.039869994 -0.046092123 -0.023960084, -0.046587333 -0.033998981 -0.019046366, 0.041522428 -0.040768415 -0.020637482, -0.04863508 -0.033449233 -0.022085413, 0.042119175 -0.041354194 -0.022085741, -0.047004849 -0.03430362 -0.02063714, 0.042917728 -0.042138025 -0.023328885, -0.049557179 -0.034083217 -0.0233282, 0.044256061 -0.036982611 -0.019046634, -0.047680199 -0.03479661 -0.022085413, -0.044751614 -0.036381468 -0.01904659, 0.043486759 -0.042696789 -0.023959771, -0.050214022 -0.03453508 -0.023959443, 0.044652537 -0.037313879 -0.020637333, -0.048584402 -0.035456136 -0.023328483, 0.04529427 -0.037849963 -0.022085696, -0.04515259 -0.036707371 -0.020637229, 0.046152964 -0.038567573 -0.023328662, -0.043620393 -0.037729964 -0.01904662, 0.047074318 -0.033321455 -0.019046411, -0.045801431 -0.037234738 -0.022085726, 0.046764806 -0.039078861 -0.023959562, -0.044011295 -0.038068205 -0.020637199, 0.047496229 -0.033620015 -0.02063708, -0.046669766 -0.037940517 -0.023328558, -0.041695818 -0.039846763 -0.019046888, 0.048178777 -0.03410311 -0.022085398, 0.049092129 -0.034749627 -0.023328364, -0.044643998 -0.038614914 -0.022085682, -0.047288477 -0.038443565 -0.023959532, -0.042069346 -0.040203795 -0.020637318, 0.049742982 -0.035210386 -0.023959473, -0.059166417 0.044442579 0.036147565, -0.062253028 0.040005192 0.036147326, 0.037707031 0.063670501 0.036148787, 0.032958537 0.066252977 0.036148787, -0.06500715 0.03535445 0.036146984, 0.028034329 0.068482235 0.036148697, -0.067414641 0.030514807 0.036146879, 0.022960514 0.070345908 0.036148995, 0.072437093 -0.015130714 0.036144286, -0.069462225 0.025512293 0.036146656, 0.017764241 0.071834117 0.036149055, 0.073348165 -0.0098026991 0.036144599, 0.012473047 0.072939277 0.036149055, 0.073867872 -0.0044225305 0.036144838, 0.0071154833 0.073655039 0.036149114, 0.073993579 0.00098134577 0.036145002, 0.001719892 0.073978066 0.036149055, 0.073724359 0.0063797385 0.036145329, -0.003684938 0.073906258 0.036149144, 0.073061824 0.011744335 0.036145687, -0.009070009 0.07344006 0.036149204, 0.072009623 0.017046109 0.036145985, -0.01440677 0.072582096 0.036149144, 0.070572987 0.02225706 0.036146253, -0.019666642 0.071336731 0.036149085, 0.068760008 0.027349144 0.0361467, -0.024821401 0.06971091 0.03614904, 0.066579938 0.032295302 0.036146849, -0.02984415 0.067713007 0.036148921, 0.064044848 0.037069112 0.036147028, -0.034707308 0.06535393 0.036148623, 0.06116794 0.041645259 0.036147296, -0.039385438 0.062646151 0.036148667, 0.057964727 0.04599914 0.036147624, -0.043853387 0.059604123 0.036148503, 0.054452196 0.050107524 0.036147863, -0.048087418 0.056243777 0.036148161, 0.050649136 0.053948581 0.036148041, -0.052064851 0.052583829 0.036148056, 0.046575934 0.057501808 0.036148369, -0.055764318 0.048642889 0.036147892, 0.04225409 0.060748354 0.036148489, 0.020343363 0.053780645 0.0065030158, 0.015832692 0.05527693 0.0065030754, 0.011213899 0.056395635 0.0065031946, 0.0065182447 0.057129055 0.0065031052, 0.056396097 -0.011214137 0.0064992905, 0.0017784238 0.05747208 0.0065031648, -0.0029737055 0.057422891 0.006503135, 0.057129472 -0.0065187961 0.006499514, -0.0077054501 0.056980923 0.0065031648, 0.057472587 -0.0017788708 0.0064999163, -0.012384668 0.056150094 0.0065030456, 0.05742304 0.0029733926 0.0065000653, -0.016979262 0.054935604 0.0065030456, 0.056981489 0.007705152 0.0065002441, -0.021457791 0.053345889 0.0065030456, -0.025789827 0.051391661 0.0065028816, 0.056150571 0.01238434 0.0065006912, -0.029945582 0.049086347 0.0065026879, 0.054936051 0.016978845 0.0065009892, -0.033896863 0.046445772 0.0065026432, 0.053346246 0.021457508 0.0065011084, -0.03761667 0.043487936 0.0065024197, 0.051392034 0.025789469 0.006501317, -0.041079313 0.04023318 0.0065023154, 0.049086735 0.029945418 0.006501615, -0.044261634 0.036703438 0.0065020621, 0.046446338 0.033896625 0.0065018833, -0.047141567 0.032923043 0.0065018535, 0.043488413 0.037616342 0.0065019429, -0.049699113 0.028917611 0.0065016896, 0.040233612 0.041079178 0.0065020919, -0.051917419 0.024714664 0.0065013766, 0.03670387 0.044261083 0.0065023601, -0.053780973 0.020342976 0.0065012127, 0.032923296 0.047141045 0.0065027177, 0.028917909 0.049698785 0.0065026283, 0.02471517 0.051916912 0.0065028667, 0.001778394 0.057472795 -0.0064967275, 0.0065183938 0.05712989 -0.0064968765, -0.0029736757 0.057423353 -0.0064968765, 0.056395978 -0.011213481 -0.0065006316, -0.0077054352 0.056981742 -0.006496802, 0.057129368 -0.0065180063 -0.0065004379, -0.012384757 0.056150734 -0.0064968765, 0.057472587 -0.0017779768 -0.00650011, -0.016979277 0.05493632 -0.0064969957, 0.057423025 0.002974093 -0.0064998567, -0.021457925 0.053346455 -0.0064969361, 0.056981474 0.0077058077 -0.0064995736, -0.025789812 0.051392317 -0.0064971298, 0.056150332 0.012385204 -0.0064993352, -0.029945761 0.049087286 -0.0064973533, 0.054935992 0.01697959 -0.0064991117, -0.033896923 0.046446547 -0.0064974278, 0.053346187 0.021458164 -0.0064988732, -0.037616611 0.043488741 -0.0064974725, 0.051391914 0.025790319 -0.0064985752, -0.041079417 0.04023385 -0.006497696, 0.049086779 0.02994597 -0.0064984858, -0.04426156 0.036704063 -0.0064980388, 0.046446264 0.033897236 -0.006498158, -0.047141448 0.032923743 -0.0064980984, 0.043488443 0.037616953 -0.006498009, -0.049699008 0.028918222 -0.0064985156, 0.040233597 0.041079879 -0.0064975321, -0.051917344 0.024715498 -0.0064985901, 0.036703825 0.044261947 -0.0064976215, -0.053781062 0.020343661 -0.0064989477, 0.032923341 0.047141656 -0.0064974427, 0.028917924 0.049699634 -0.0064974129, 0.024715051 0.051917806 -0.0064971745, 0.020343423 0.053781375 -0.0064970553, 0.015832677 0.05527769 -0.0064969063, 0.011213854 0.056396425 -0.0064968467, -0.04658556 -0.0081453472 -0.0015003532, 0.030846223 0.042482629 -0.0014976263, 0.034431338 0.039632604 -0.0014977455, 0.016155556 0.021633312 -0.001498729, -0.044026166 -0.0069214553 -0.0015006363, -0.044970453 -0.0071170926 -0.0015004277, -0.043062627 -0.0069573969 -0.0015004873, 0.013430282 0.023422956 -0.001498729, 0.010509059 0.024871022 -0.0014987737, 0.027026042 0.045009345 -0.0014975071, 0.035289794 -0.032534048 -0.0015019178, 0.0074344575 0.025956258 -0.0014986247, 0.035209253 -0.031572983 -0.0015018284, 0.0042515099 0.026663065 -0.0014986694, 0.034901097 -0.030659392 -0.0015019029, 0.02300033 0.047193527 -0.0014973581, 0.016397268 0.043143392 -0.0014977455, 0.016316727 0.044104591 -0.0014977157, 0.034383461 -0.029846087 -0.0015017986, 0.0010066926 0.026981279 -0.0014985651, 0.033685908 -0.029179931 -0.0015016347, -0.0022527725 0.026905984 -0.0014985353, 0.032849357 -0.028700367 -0.0015016943, 0.018799618 0.049018651 -0.0014972985, 0.01549077 0.045831606 -0.0014973879, 0.014793351 0.04649739 -0.0014974177, 0.016008735 0.045018092 -0.0014975369, 0.01445581 0.05047065 -0.0014970899, 0.013029739 0.047242716 -0.0014972985, 0.0120662 0.047278613 -0.0014973879, 0.01395686 0.046977073 -0.0014973283, 0.010002106 0.051538616 -0.0014972985, 0.010251954 0.04666692 -0.0014975071, 0.0095068067 0.046054825 -0.0014974475, 0.011122003 0.04708305 -0.0014973879, -0.049018756 0.018799856 -0.0014989376, -0.024870947 0.010509148 -0.0014995635, -0.047193512 0.023000404 -0.0014987141, -0.023422956 0.013430297 -0.0014993101, 0.0054721236 0.05221425 -0.0014972389, 0.0089297593 0.045282274 -0.0014975965, 0.02782242 -0.030395165 -0.0015018433, 0.028399423 -0.02962257 -0.0015017092, 0.00090065598 0.052492574 -0.0014971793, 0.029144526 -0.029010519 -0.0015017092, -0.045009464 0.027026132 -0.0014986247, -0.021633193 0.016155556 -0.001499027, -0.042482615 0.030846 -0.0014983565, -0.0036779642 0.052371219 -0.0014971495, -0.039632559 0.034431428 -0.001498118, -0.019528091 0.018645301 -0.0014990419, -0.0082283169 0.051851168 -0.0014972091, -0.005479604 0.026438192 -0.0014985651, 0.030014455 -0.028594583 -0.0015015453, -0.03648074 0.037754565 -0.0014978945, 0.030958742 -0.028398812 -0.0015015155, -0.017138302 0.020863354 -0.0014989078, -0.012716025 0.050936937 -0.0014972389, -0.0086264759 0.025584966 -0.0014986098, 0.031922281 -0.028434694 -0.0015015751, -0.033051431 0.04079026 -0.001497671, -0.017107248 0.049634814 -0.0014971495, -0.02937071 0.043515652 -0.0014974028, -0.014498517 0.022776976 -0.0014988482, -0.021367908 0.047954738 -0.0014973134, -0.011647478 0.024358585 -0.0014986545, -0.025466174 0.045909971 -0.0014974326, 0.051538393 -0.010002047 -0.0015004575, 0.026663035 -0.0042514503 -0.0015003979, 0.052214071 -0.0054720938 -0.0015004575, 0.02698119 -0.0010064989 -0.0015000701, 0.05249241 -0.00090052187 -0.0015002042, 0.02690579 0.0022530407 -0.0014999211, 0.051851243 0.0082282871 -0.0014995039, 0.05237107 0.0036778599 -0.0014999211, 0.026438162 0.0054796636 -0.0014997572, 0.050936773 0.012716159 -0.0014994442, 0.025584936 0.008626461 -0.0014994889, 0.049634591 0.017107204 -0.001499325, 0.047954872 0.021368057 -0.0014989674, 0.024358585 0.011647448 -0.0014993697, 0.04591012 0.025466219 -0.0014984906, 0.022776991 0.014498651 -0.0014992356, 0.043515712 0.02937077 -0.0014983416, 0.02086331 0.017138362 -0.0014991164, 0.040790349 0.033051684 -0.001498282, -0.039695114 -0.011056811 -0.0015008301, -0.03977567 -0.010095656 -0.001500681, -0.040083677 -0.0091820359 -0.0015005022, -0.040601537 -0.0083685368 -0.0015004724, -0.041298956 -0.0077026337 -0.0015006363, 0.037754461 0.036480993 -0.0014980137, 0.018645331 0.019528344 -0.0014989823, -0.042135611 -0.0072230101 -0.001500532, -0.047162488 -0.0089179575 -0.001500532, -0.045840248 -0.0075331926 -0.0015004277, -0.045840293 -0.0075333118 0.001499474, -0.046585515 -0.0081452727 0.0014994889, -0.044970334 -0.0071173608 0.0014997125, -0.044026107 -0.0069216788 0.0014996529, -0.043062389 -0.0069576502 0.0014996231, 0.016155571 0.021633238 0.0015010685, 0.013430238 0.023422807 0.001501292, 0.010508955 0.024870813 0.0015013367, 0.030846104 0.042482525 0.0015023649, 0.027025998 0.04500936 0.0015024841, 0.035289675 -0.032534003 0.0014979541, 0.0074345618 0.025956169 0.0015014261, 0.035209268 -0.031573221 0.0014982224, 0.0042515844 0.026663199 0.0015014112, 0.023000389 0.047193468 0.0015025735, 0.016397223 0.043143272 0.0015024245, 0.034901246 -0.030659527 0.0014980882, 0.016316757 0.04410404 0.0015024245, 0.034383401 -0.029845998 0.0014982522, 0.0010067672 0.026980907 0.0015015304, 0.033685818 -0.029180169 0.0014983863, -0.0022529215 0.026905715 0.0015016198, 0.032849431 -0.028700501 0.001498282, 0.018799648 0.049018458 0.0015026927, 0.015490696 0.045831561 0.0015024543, 0.014793411 0.046497226 0.0015025735, 0.016008586 0.045017928 0.0015024245, 0.014456019 0.050470397 0.0015027821, 0.013029739 0.047242522 0.0015025437, 0.012066156 0.047278464 0.0015026629, 0.013956785 0.046977043 0.0015026629, 0.010002166 0.051538393 0.0015027225, 0.010252088 0.046666607 0.0015026927, 0.0095068812 0.046054617 0.0015026331, 0.011121973 0.047082871 0.0015025735, -0.049018711 0.018799692 0.0015010089, -0.024870992 0.01050885 0.0015004873, 0.005472213 0.052213997 0.0015029013, 0.0089300573 0.045282081 0.0015025735, -0.047193453 0.023000106 0.0015011728, -0.023422897 0.013430133 0.0015006959, 0.027822509 -0.030395344 0.0014981478, 0.028399453 -0.029622793 0.0014982969, 0.00090059638 0.052492172 0.0015029013, 0.029144496 -0.029010624 0.0014983863, -0.045009434 0.027026132 0.0015014857, -0.021633178 0.016155466 0.0015008748, -0.003677845 0.05237101 0.0015029311, -0.042482615 0.03084591 0.0015017241, -0.0082282424 0.051851198 0.0015030503, -0.0054796934 0.026438013 0.0015015006, -0.019528195 0.018645167 0.0015011579, -0.039632559 0.034431055 0.0015018284, 0.0300145 -0.028594702 0.0014984459, 0.030958667 -0.028399065 0.0014983714, -0.01271604 0.05093655 0.0015028417, -0.0086264759 0.025584787 0.0015013516, -0.017138302 0.020863175 0.0015010983, -0.036480889 0.037754267 0.0015020967, 0.031922281 -0.028434873 0.0014983118, -0.017107233 0.049634531 0.0015028417, -0.033051372 0.040790215 0.0015022457, -0.021367997 0.047954604 0.0015026629, -0.011647344 0.024358377 0.0015013516, -0.014498413 0.022776902 0.0015013069, -0.029370621 0.043515667 0.0015024543, -0.025466248 0.045909882 0.0015024543, 0.051538393 -0.010002196 0.0014992952, 0.052214116 -0.005472213 0.0014997274, 0.026663333 -0.0042516887 0.0014996976, 0.026981205 -0.0010066777 0.0014998317, 0.052492365 -0.0009007901 0.0014998019, 0.026905894 0.0022527426 0.0015001744, 0.052371144 0.0036777854 0.0015000999, 0.051851213 0.0082282722 0.0015004277, 0.026438087 0.0054794252 0.0015000999, 0.050936684 0.01271604 0.0015006959, 0.025584802 0.0086262673 0.0015003979, 0.04963468 0.017107069 0.0015009046, 0.047954753 0.021367803 0.0015011728, 0.024358571 0.011647314 0.0015007108, 0.045910031 0.025466189 0.0015014708, 0.022776932 0.014498621 0.001500681, 0.043515697 0.029370517 0.0015016198, 0.020863265 0.017138258 0.0015009046, 0.040790305 0.033051401 0.0015019178, -0.039695084 -0.011056915 0.0014992505, -0.03977561 -0.010095984 0.001499474, -0.040083617 -0.0091821104 0.0014994293, -0.040601462 -0.0083688051 0.0014995337, -0.041299015 -0.0077027828 0.0014995039, 0.037754431 0.036480799 0.0015020967, 0.018645301 0.019528061 0.0015010387, -0.042135403 -0.0072232485 0.001499638, 0.034431398 0.039632469 0.0015021563, -0.047162458 -0.0089178979 0.0014995039, -0.064852774 0.053389505 -0.049497142, -0.068344787 0.048839286 -0.049497366, -0.061058193 0.05769065 -0.049496844, -0.016615346 0.082343146 -0.049495533, -0.01095739 0.083284929 -0.049495369, -0.022195622 0.081017241 -0.049495503, -0.056979284 0.061722934 -0.049496397, 0.039520472 -0.068401515 -0.049504012, -0.027672604 0.079313725 -0.049495652, 0.034652531 -0.07099165 -0.049504012, -0.052634478 0.065467447 -0.049496442, 0.044195816 -0.065478042 -0.049503639, -0.048044339 0.068906859 -0.049496412, 0.029615834 -0.073235929 -0.04950425, -0.033020452 0.077240437 -0.049495727, -0.043229938 0.072024599 -0.049496204, -0.0382144 0.074807033 -0.04949595, 0.048655897 -0.062235475 -0.049503669, 0.024434716 -0.07512331 -0.049504399, 0.052878827 -0.058689907 -0.049503446, 0.019134849 -0.076644868 -0.049504504, 0.056844309 -0.054858342 -0.049503148, 0.013741553 -0.077792928 -0.049504548, 0.060532719 -0.050759271 -0.049502879, 0.0082811117 -0.078562021 -0.049504548, 0.063926205 -0.046413377 -0.049502745, 0.0027806908 -0.078948498 -0.049504578, 0.067008331 -0.041840971 -0.049502403, -0.002733469 -0.078950167 -0.049504548, 0.069764048 -0.037064657 -0.049502254, -0.0082342774 -0.078566983 -0.049504355, 0.072179675 -0.032107905 -0.049501836, -0.013695002 -0.077801079 -0.049504429, 0.074243858 -0.026994601 -0.049501643, -0.019088939 -0.076656356 -0.049504459, 0.082143083 -0.017562017 -0.049501225, -0.024389789 -0.075138062 -0.049504325, 0.083150357 -0.011915341 -0.049500853, -0.029572055 -0.073253602 -0.049504161, 0.083769828 -0.006213069 -0.04950045, -0.034610108 -0.071012393 -0.049504116, 0.083998591 -0.00048196316 -0.049500257, -0.039479554 -0.068425149 -0.049503937, 0.083835885 0.0052513331 -0.049499869, -0.044156507 -0.065504521 -0.049503788, -0.048618674 -0.062264651 -0.04950358, 0.083282217 0.010960296 -0.049499497, -0.052843839 -0.058721483 -0.049503401, 0.082340449 0.016618162 -0.049499229, -0.056811407 -0.054892257 -0.049503163, 0.081014588 0.022198603 -0.049498916, -0.06050241 -0.050795615 -0.049502879, 0.079311132 0.02767539 -0.049498498, -0.063898519 -0.046451494 -0.049502775, 0.077237591 0.033023283 -0.04949823, -0.066983387 -0.041880757 -0.049502432, 0.074804217 0.038216963 -0.049497932, -0.069741845 -0.03710638 -0.049502149, 0.072021976 0.043232948 -0.049497783, -0.072160482 -0.032150984 -0.04950206, 0.068903983 0.048046947 -0.049497351, -0.074227691 -0.027039051 -0.049501523, 0.06546472 0.052637219 -0.049497142, -0.075933203 -0.021795273 -0.049501345, 0.061720163 0.056981921 -0.049496844, -0.077268749 -0.016445339 -0.049501002, 0.057687759 0.061061129 -0.049496606, -0.078227818 -0.011015296 -0.049500778, 0.053386718 0.064855367 -0.049496382, -0.078805894 -0.0055315644 -0.049500376, 0.048836589 0.068347484 -0.049496427, -0.078999966 -2.0831823e-05 -0.049500167, 0.044058666 0.071520805 -0.049495965, -0.078809321 0.0054900497 -0.049499974, 0.03907533 0.074360698 -0.049495742, -0.078234509 0.01097402 -0.049499348, 0.033909827 0.07685408 -0.049495697, -0.07727854 0.016404688 -0.049499214, 0.028586283 0.078989044 -0.049495608, 0.023129418 0.080755666 -0.049495637, 0.017564848 0.08214587 -0.049495608, -0.078986302 0.028589144 -0.049498484, -0.076851219 0.033912465 -0.049498305, 0.011918098 0.083153114 -0.049495414, 0.0062159896 0.08377248 -0.049495384, -0.074358121 0.039077967 -0.049497738, 0.00048479438 0.084001318 -0.049495369, -0.071518168 0.044061244 -0.049497709, -0.0052485168 0.083838642 -0.049495503, 0.012059987 0.084142983 -0.050495401, 0.017773896 0.083123729 -0.050495431, 0.084140152 -0.012057185 -0.05050078, 0.083121046 -0.017771095 -0.050501183, 0.023404747 0.081717059 -0.05049555, -0.079926506 0.028929502 -0.05049853, 0.028926462 0.079929367 -0.050495654, -0.07776618 0.034316227 -0.050498143, 0.034313545 0.077769071 -0.050495684, -0.07524313 0.039543197 -0.050497919, 0.039540485 0.075246066 -0.050495788, -0.072369635 0.044586092 -0.050497577, 0.044583157 0.072372243 -0.050496012, -0.069158465 0.049420729 -0.050497368, 0.049417973 0.069161177 -0.050496265, -0.065624818 0.054024979 -0.050497085, 0.054022253 0.06562753 -0.050496295, -0.061785385 0.058377653 -0.050496966, 0.058374569 0.061788097 -0.050496534, -0.05765754 0.0624578 -0.050496548, 0.062454969 0.057660222 -0.050496846, -0.053261101 0.066246882 -0.050496265, 0.066243976 0.053263828 -0.050497159, -0.048616216 0.069726989 -0.05049628, 0.069724202 0.048619002 -0.050497442, -0.043744788 0.072882295 -0.050495967, 0.072879493 0.043747514 -0.050497606, -0.038669243 0.075697407 -0.050495744, 0.075694725 0.038672119 -0.050498053, -0.033413514 0.078159928 -0.050495878, 0.078157157 0.033416167 -0.050498232, -0.028002009 0.080257952 -0.050495535, 0.08025521 0.028004825 -0.05049853, -0.022459954 0.081981689 -0.050495401, 0.081979096 0.022462696 -0.050498649, -0.01681304 0.083323374 -0.050495416, 0.083320528 0.016815916 -0.050499171, -0.011087969 0.084276453 -0.050495401, 0.084273726 0.011090696 -0.050499454, -0.0053109378 0.084836617 -0.050495476, 0.08483398 0.0053137243 -0.050499931, 0.00049059093 0.085001424 -0.050495207, 0.084998712 -0.00048780441 -0.050500259, 0.0062900335 0.084769636 -0.050495476, 0.084766865 -0.0062870383 -0.050500497, 0.034313589 0.077763364 0.050504297, -0.07776624 0.034310818 0.050501868, -0.079926506 0.028923646 0.05050157, 0.02892673 0.079923779 0.050504416, 0.023404747 0.081711411 0.050504506, 0.083121166 -0.017776743 0.050498903, 0.017773926 0.083118066 0.050504595, 0.084140256 -0.012062773 0.05049935, 0.012060106 0.08413738 0.050504476, 0.084766909 -0.0062927008 0.050499514, 0.006290108 0.084764063 0.050504684, 0.084998637 -0.00049340725 0.050499916, 0.00049060583 0.084995762 0.050504625, 0.084833965 0.0053082258 0.050500169, -0.0053109229 0.084831119 0.050504684, 0.084273756 0.011085227 0.050500602, -0.011087924 0.084270984 0.050504684, 0.083320618 0.016810402 0.05050087, -0.016813159 0.083317801 0.050504684, 0.081979007 0.022457048 0.050501168, -0.022459984 0.081976056 0.05050458, 0.080255151 0.027999207 0.050501436, -0.028001994 0.080252394 0.050504535, 0.078157216 0.033410728 0.050501764, -0.033413678 0.078154385 0.050504312, 0.075694829 0.038666397 0.050502032, -0.038669154 0.075691819 0.050504163, 0.072879583 0.043741807 0.050502568, -0.043744758 0.072876424 0.050504044, 0.069724232 0.04861328 0.050502658, -0.04861629 0.069721371 0.050503865, 0.06624414 0.053258121 0.050502926, -0.053260908 0.066241115 0.050503641, 0.062454969 0.057654753 0.050503045, -0.057657555 0.062452182 0.050503522, 0.058374614 0.061782286 0.050503492, -0.061785191 0.058371827 0.05050312, 0.054022223 0.065621912 0.050503582, -0.065624759 0.054019287 0.050503016, 0.049417913 0.069155574 0.050503939, -0.069158375 0.049414992 0.050502822, 0.044583112 0.072366655 0.05050388, -0.07236962 0.044580266 0.050502509, 0.03954047 0.075240478 0.050504237, -0.07524319 0.039537653 0.050502166, -0.05284375 -0.0587271 0.049496651, -0.056811377 -0.054897815 0.049496815, -0.078227893 -0.011020944 0.049499243, -0.077268705 -0.016450942 0.049499065, -0.06050235 -0.050801054 0.049497142, -0.075933143 -0.02180095 0.049498677, -0.063898534 -0.046456888 0.049497321, -0.074227646 -0.027044564 0.049498588, -0.066983178 -0.041886583 0.049497575, -0.072160646 -0.032156587 0.049498171, 0.074804217 0.038211539 0.049502134, 0.072022006 0.043227196 0.049502343, -0.069741726 -0.037111923 0.049497828, 0.068903968 0.048041508 0.049502641, 0.077237815 0.033017591 0.049501747, 0.065464735 0.052631557 0.049502939, 0.079311088 0.027669713 0.049501538, 0.061720163 0.056976393 0.049503148, 0.081014559 0.022192985 0.049501121, 0.057687968 0.061055332 0.049503416, 0.082340479 0.016612574 0.049501032, 0.053386629 0.064850017 0.049503535, 0.083282381 0.010954484 0.049500525, 0.04883641 0.068342015 0.049503803, 0.083835974 0.0052458346 0.049500361, 0.044058651 0.071515262 0.049504012, 0.083998725 -0.0004876554 0.04949981, 0.039075404 0.074355334 0.049504071, 0.083769917 -0.0062188655 0.049499616, 0.033909827 0.076848656 0.049504101, 0.083150268 -0.011920869 0.049499199, 0.028586417 0.078983471 0.04950431, 0.082143098 -0.01756753 0.049499035, 0.023129582 0.080750093 0.049504489, 0.017564803 0.082140282 0.049504548, 0.074243799 -0.027000248 0.049498439, 0.011918157 0.083147392 0.049504668, 0.07217972 -0.032113418 0.049498081, 0.006216079 0.083766937 0.049504697, 0.069764137 -0.037070364 0.049497843, 0.00048476458 0.083995834 0.049504638, 0.067008317 -0.041846499 0.049497649, -0.0052484274 0.083833128 0.049504548, 0.06392622 -0.046418831 0.049497321, -0.01095745 0.083279505 0.049504668, 0.060532719 -0.050764948 0.049497113, -0.016615331 0.082337454 0.049504459, 0.056844279 -0.0548639 0.04949683, -0.022195697 0.081011698 0.049504489, 0.052878916 -0.058695361 0.04949668, -0.027672499 0.079308093 0.049504444, 0.048655793 -0.062241048 0.049496442, -0.033020377 0.077234879 0.04950425, 0.04419592 -0.065483436 0.049496338, -0.038214386 0.07480146 0.049504116, 0.039520428 -0.068406954 0.049496084, -0.043230116 0.072019264 0.049504176, 0.034652561 -0.070997253 0.049496099, -0.048044235 0.068901151 0.049503714, 0.029615894 -0.073241547 0.049495742, -0.052634373 0.065461844 0.049503669, 0.02443479 -0.075128824 0.049495608, -0.056979194 0.061717302 0.049503326, 0.019134924 -0.076650575 0.049495548, -0.061058313 0.057685241 0.049503312, 0.013741419 -0.07779856 0.049495667, -0.064852521 0.053383842 0.049502999, 0.0082812458 -0.078567564 0.049495503, 0.0027807206 -0.078953996 0.049495474, -0.068344623 0.048833609 0.049502745, -0.0027334243 -0.078955486 0.049495399, -0.071518153 0.044055656 0.049502417, -0.0082342178 -0.078572541 0.049495459, -0.074358091 0.039072484 0.049502224, -0.013694927 -0.077806771 0.049495652, -0.076851368 0.033907175 0.049501836, -0.019088984 -0.076661691 0.049495652, -0.078986272 0.028583512 0.049501598, -0.024389908 -0.075143605 0.049495697, -0.02957207 -0.073259309 0.049495831, -0.077278569 0.016399145 0.049500898, -0.034610093 -0.071017921 0.049496055, -0.078234404 0.010968417 0.04950054, -0.039479524 -0.068430752 0.049496129, -0.078809232 0.0054844171 0.049500197, -0.044156626 -0.065510064 0.049496308, -0.078999817 -2.6449561e-05 0.049499869, -0.04861854 -0.062270239 0.049496382, -0.078805909 -0.0055373013 0.049499691, 0.063424051 0.0050521344 0.025536433, 0.065107509 0.0091685057 0.026763469, 0.065709442 0.0023127198 0.026763171, 0.061777979 0.022504717 0.026764333, 0.058357373 0.025347307 0.02553767, 0.069415316 -0.0090310872 0.029216304, 0.064754546 -0.011399597 0.026762411, 0.06854637 -0.014193341 0.029215977, 0.059087187 0.028839096 0.026764721, 0.059900969 0.03621833 0.029218882, 0.059599578 0.032477632 0.027991772, 0.062440053 0.031640902 0.029218644, 0.055748865 0.034857199 0.026765138, 0.069895968 -0.0038185418 0.029216573, 0.065591395 -0.0045683533 0.026762843, 0.033765733 0.061316133 0.029220223, 0.035375029 0.057926193 0.027993172, 0.038253456 0.058621541 0.029219955, 0.036750704 0.054518759 0.026766151, 0.030850589 0.058061525 0.02676636, 0.027335614 0.057452098 0.025539517, 0.069684163 0.0066414326 0.029217243, 0.069985732 0.0014153421 0.029216871, 0.024612278 0.060968146 0.02676639, 0.0045667589 0.065589681 0.026766837, 0.0072261393 0.063211814 0.025539815, 0.011398047 0.064753056 0.026766807, 0.068992943 0.011830419 0.029217482, 0.0038169622 0.069894239 0.029220849, 0.00065672398 0.067870244 0.027993917, -0.0023143291 0.065707937 0.026766807, -0.0014170706 0.069984168 0.02922079, -0.036220044 0.059899271 0.029220179, -0.033367187 0.059105471 0.027993232, -0.031642348 0.062438384 0.029220372, 0.067915723 0.016953126 0.029217839, 0.063792273 0.015923902 0.026764095, -0.028840497 0.059085593 0.026766464, 0.066458732 0.021981105 0.029218018, -0.034858793 0.055747196 0.026766151, -0.036088482 0.052398607 0.025539115, -0.040495276 0.051798165 0.026766032, 0.064630225 0.02688612 0.029218465, -0.050380021 0.042246684 0.026765406, -0.051131263 0.037863106 0.025538534, -0.05452016 0.036749259 0.026765019, -0.05862315 0.038251892 0.029218912, -0.058450431 0.034502938 0.027992085, -0.058063135 0.030848995 0.02676478, -0.061317891 0.0337639 0.029218793, -0.060164765 0.020694882 0.025537342, -0.060969755 0.024610788 0.026764527, 0.057026669 0.04059349 0.029219061, -0.065665632 0.02424781 0.029218301, -0.064183578 0.022077158 0.02799128, 0.051799729 0.040493637 0.026765436, 0.053833574 0.044741571 0.029219449, 0.050339356 0.048639387 0.029219598, 0.047283024 0.045686379 0.026765585, 0.046563625 0.052265406 0.029219717, 0.042527437 0.05559884 0.029219925, 0.042248338 0.050378636 0.026765943, 0.029088974 0.063668042 0.029220462, 0.024249703 0.065663725 0.029220611, 0.019274563 0.067292467 0.029220611, 0.018104166 0.063206926 0.026766658, 0.014191747 0.068544745 0.029220641, 0.009029597 0.069413498 0.02922076, -0.0066431165 0.069682419 0.02922073, -0.011832029 0.06899105 0.02922073, -0.0091700852 0.06510596 0.026766807, -0.01695478 0.067913935 0.029220715, -0.015925437 0.063790724 0.026766762, -0.021982729 0.066457003 0.029220551, -0.026887625 0.064628348 0.029220566, -0.022506475 0.061776668 0.026766598, -0.040595189 0.057024896 0.02921997, -0.044743255 0.05383195 0.029219866, -0.045687988 0.047281474 0.026765674, -0.048641115 0.050337613 0.029219612, -0.052266896 0.046561956 0.029219419, -0.055600435 0.042525724 0.029219225, -0.063669726 0.029087186 0.029218465, 0.061998621 -0.014295414 0.025535375, 0.066139966 -0.015250415 0.027989194, 0.067854568 -0.0016734153 0.02798976, 0.071246982 -0.0038925409 0.030199677, 0.071338549 0.0014425963 0.03019996, -0.012249947 0.071427628 0.031446815, -0.0088828206 0.071923926 0.031446785, -0.01239118 0.072251692 0.032895267, 0.072457403 0.0014653206 0.03144291, 0.072364241 -0.003953442 0.031442583, -0.008985281 0.072753847 0.032895267, -0.0069570839 0.072975606 0.032895297, -0.0090487599 0.073266655 0.034485936, -0.0070061386 0.073490024 0.034485847, 0.073715433 -0.004027456 0.034481406, 0.072695881 -0.0094581544 0.032890514, 0.073208362 -0.0095250756 0.034481242, 0.073199406 -0.0039992183 0.032890946, 0.071866736 -0.0093501955 0.03144218, -0.0036764145 0.073731527 0.034485966, -0.0087457299 0.070813462 0.030203909, -0.012060732 0.070324615 0.030203789, 0.072292224 -0.014969334 0.034480885, -0.0068778992 0.072143272 0.031446844, 0.070756942 -0.0092058331 0.030199334, -0.0036505759 0.073215663 0.032895267, 0.071786016 -0.014864236 0.032890335, -0.0014945269 0.073808104 0.034485906, 0.070967168 -0.01469475 0.031441942, -0.0067716837 0.071029261 0.030203998, 0.069871277 -0.01446788 0.030199081, -0.0036089718 0.072380558 0.031446874, -0.0014840364 0.073291525 0.032895446, 0.0017157793 0.073803335 0.034485996, -0.0035531521 0.071262866 0.030203938, -0.0014670193 0.072455585 0.031446964, 0.001703769 0.073286727 0.032895297, 0.0040254593 0.073713526 0.034485936, -0.0014443099 0.071336687 0.030203819, 0.0016843081 0.072450861 0.031446785, 0.0039974451 0.073197454 0.032895178, 0.0070985556 0.073481232 0.034485817, 0.001658231 0.071332186 0.030204028, 0.0039516687 0.072362691 0.031446785, 0.0070489645 0.072966754 0.032895237, 0.0095231533 0.073206455 0.034485966, 0.0038906038 0.071245149 0.030203938, 0.0069685578 0.072134539 0.031446934, 0.0094563961 0.072693929 0.032895327, 0.012443542 0.072766975 0.034485877, 0.0068610013 0.071020663 0.030203998, 0.0093485713 0.071864948 0.031447023, 0.01235652 0.072257608 0.032895148, 0.014967144 0.072290137 0.034485936, 0.0092041194 0.070755318 0.030203998, 0.012215495 0.071433455 0.031446815, 0.014862597 0.071784139 0.032895029, 0.017722219 0.071664542 0.034485847, 0.012026995 0.070330352 0.030203909, 0.014693111 0.070965305 0.031446904, 0.017598063 0.071162909 0.032895058, 0.020327777 0.070969418 0.034485757, 0.014466196 0.069869444 0.030203849, 0.017397434 0.070351228 0.031446636, 0.02018553 0.070472702 0.032895088, 0.022906393 0.070179671 0.034485847, 0.017128825 0.069264799 0.030203849, 0.019955158 0.069668978 0.031446815, 0.022745997 0.069688439 0.032895297, 0.025574654 0.069251925 0.034485728, 0.019647032 0.068593204 0.030203849, 0.022486448 0.068893701 0.031446576, 0.025395602 0.06876716 0.032895029, 0.027968019 0.068320349 0.034485757, 0.022139221 0.067829788 0.030203849, 0.025105894 0.067982793 0.031446695, 0.027772307 0.067842364 0.032894939, 0.03067857 0.067147091 0.034485608, 0.024718225 0.066933081 0.030203879, 0.027455598 0.067068368 0.031446517, 0.030463696 0.066677138 0.032895029, 0.032880753 0.066096559 0.034485459, 0.027031481 0.066032842 0.030203551, 0.03011623 0.065916657 0.031446457, 0.03265056 0.065633953 0.03289479, 0.035610914 0.064666733 0.034485459, 0.029651135 0.0648987 0.030203611, 0.03227815 0.064885333 0.031446397, 0.035361469 0.064214081 0.032894909, 0.037617922 0.063520178 0.03448531, 0.031779706 0.063883439 0.030203521, 0.034958065 0.063481703 0.031446338, 0.037354529 0.063075468 0.032894701, 0.040343732 0.061824635 0.034485281, 0.034418255 0.062501401 0.030203432, 0.036928475 0.062356204 0.031446338, 0.040061474 0.06139192 0.032894552, -0.069298059 0.025452226 0.034483343, 0.042154402 0.060604677 0.034485191, 0.036358297 0.061393172 0.030203313, -0.068813115 0.025274128 0.03289263, 0.039604574 0.060691744 0.031446159, -0.068028137 0.024985716 0.031444296, 0.04185921 0.060180604 0.032894552, -0.067255393 0.030442685 0.034483522, 0.044851333 0.058636963 0.034485132, 0.038992971 0.05975458 0.030203372, -0.066977575 0.024600044 0.030201286, -0.066784576 0.030229747 0.032892823, 0.041381717 0.059494287 0.031446129, -0.066022724 0.029884979 0.031444535, 0.044537544 0.058226436 0.032894552, 0.046465933 0.057365879 0.034485102, 0.040742815 0.058575615 0.030203164, -0.064853594 0.035270885 0.034483612, -0.065003231 0.029423326 0.030201644, 0.044029444 0.057562411 0.031446069, -0.064399451 0.035023943 0.032893151, 0.046140641 0.056964546 0.032894284, -0.063664898 0.034624711 0.031444684, 0.049108148 0.055121079 0.034484833, 0.043349475 0.056673482 0.030203104, -0.06210576 0.039910734 0.034484044, 0.045614153 0.05631493 0.03144595, -0.062682003 0.034089908 0.030201972, -0.061671063 0.039631486 0.032893404, 0.048764259 0.054735497 0.032894164, 0.05052954 0.053821132 0.034484863, -0.06096755 0.039179415 0.031444967, 0.044909984 0.05544515 0.030202925, -0.059026569 0.04433763 0.034484372, 0.048208088 0.054111063 0.031445861, -0.06002605 0.038574398 0.030202091, 0.050175905 0.0534444 0.032894045, -0.058613509 0.044027478 0.032893583, 0.05309011 0.051297158 0.034484714, 0.04746367 0.053275526 0.030202985, -0.057944864 0.043525249 0.031445175, 0.049603373 0.052834883 0.031445801, -0.05563271 0.048528001 0.034484625, 0.05432348 0.049989209 0.034484655, -0.057050049 0.042853028 0.030202314, 0.052718416 0.050938204 0.032894075, -0.055243149 0.048188463 0.032893941, 0.048837408 0.052019194 0.030202895, 0.053943381 0.049639404 0.032894045, 0.052117109 0.050357088 0.031445533, -0.054612994 0.047638923 0.031445533, 0.056775242 0.047186345 0.034484416, -0.051941827 0.052459449 0.034484744, -0.053769678 0.046903089 0.030202553, 0.053327933 0.049073234 0.031445444, 0.051312402 0.04957971 0.030202776, -0.051578179 0.052092433 0.032894209, 0.057827875 0.045890391 0.034484327, -0.050989792 0.051498339 0.031445697, 0.056377783 0.046856031 0.032893926, -0.047974005 0.056111187 0.034484804, 0.052504465 0.048315331 0.030202568, -0.050202355 0.050702974 0.030202731, 0.057422966 0.045569211 0.032893777, -0.047638044 0.055718422 0.032894313, 0.055734634 0.046321616 0.031445593, 0.056767866 0.045049518 0.031445354, -0.047094569 0.055082858 0.03144592, 0.060142905 0.042811617 0.034484208, -0.043749779 0.059463233 0.034485161, 0.054874077 0.045606419 0.030202568, -0.046367198 0.054232314 0.030202985, -0.043443561 0.059047207 0.032894507, 0.061023429 0.041546836 0.034484118, 0.05589129 0.044353843 0.030202419, 0.059721872 0.04251197 0.032893479, -0.042947963 0.058373556 0.031446055, 0.060596243 0.041256115 0.032893449, -0.039292395 0.062498167 0.034485295, 0.059040532 0.042026967 0.031445116, -0.042284712 0.057472214 0.030203164, 0.059905007 0.040785536 0.031445086, -0.039017349 0.062060654 0.03289479, 0.063174173 0.038197383 0.03448385, -0.038572207 0.061352834 0.031446114, 0.058128878 0.04137817 0.03020215, -0.034625381 0.065199614 0.03448534, 0.063893408 0.036981642 0.03448382, 0.058979973 0.040155768 0.03020218, -0.037976578 0.060405523 0.030203223, 0.062731802 0.037930101 0.03289327, -0.033371434 0.065850258 0.034485474, -0.034382969 0.064743251 0.032894701, 0.063446224 0.036722839 0.032893211, 0.062016442 0.037497446 0.031444907, -0.033137813 0.065389201 0.032894894, 0.062722415 0.036304012 0.031444758, -0.033990905 0.064004883 0.031446382, -0.032760009 0.064643636 0.031446353, 0.065852299 0.033369422 0.034483641, 0.061058745 0.036918402 0.030202091, -0.029773608 0.067553118 0.034485757, 0.061753884 0.03574343 0.030201972, -0.033465877 0.063016355 0.030203342, 0.065391198 0.033136249 0.032892972, -0.02835691 0.068159863 0.034485653, -0.032253802 0.063645199 0.030203506, 0.064645216 0.032758266 0.031444639, -0.029565066 0.067080334 0.032895029, 0.068161935 0.028355017 0.034483463, -0.028158471 0.067682743 0.032895014, 0.063646927 0.032252267 0.030201733, -0.029227957 0.066315264 0.031446502, 0.067684785 0.028156623 0.032892674, -0.027837336 0.066910923 0.031446502, 0.066912621 0.027835563 0.031444281, -0.024763018 0.069546297 0.034485728, -0.028776497 0.065291137 0.030203596, 0.070090473 0.023182005 0.034483135, 0.065879479 0.027405754 0.030201316, -0.023183942 0.070088536 0.034485549, -0.027407438 0.065877602 0.030203715, 0.069599703 0.02301994 0.032892495, -0.024589598 0.069059446 0.032895073, 0.068805799 0.022757322 0.031444132, -0.023021668 0.069597855 0.032894969, 0.071626991 0.017879382 0.034482837, -0.024309009 0.068271682 0.031446561, 0.067743316 0.022405967 0.030201107, -0.01962018 0.071168318 0.034485742, 0.071125552 0.017754361 0.032892078, -0.02275905 0.068804041 0.031446546, -0.023933768 0.067217618 0.0302037, 0.070314303 0.017551795 0.031443745, -0.017881364 0.071624935 0.034485891, 0.072763085 0.012476608 0.034482479, -0.019482821 0.070670232 0.032895103, 0.06922859 0.017280713 0.030200928, -0.02240774 0.067741603 0.030203596, 0.07225363 0.012389377 0.032891721, -0.017756134 0.071123526 0.032895342, 0.071429431 0.012248144 0.031443387, -0.019260526 0.069864079 0.031446666, 0.073492065 0.0070041567 0.034482241, -0.014372796 0.072410464 0.034485996, -0.017553568 0.070312425 0.031446666, 0.070326447 0.012058958 0.030200541, -0.018963307 0.068785354 0.030203879, 0.072977543 0.0069552064 0.032891542, 0.07214509 0.0068759322 0.031443179, -0.014272153 0.071903884 0.032895207, -0.012478709 0.072760984 0.034485966, 0.07381022 0.0014925152 0.034481883, -0.017282486 0.069226578 0.030203879, 0.071031094 0.0067698658 0.030200303, -0.014109373 0.07108359 0.031446904, 0.073293447 0.0014821291 0.03289111, -0.013891339 0.069986045 0.030203849, -0.004509449 -0.05801779 0.02063176, -0.0017998368 -0.058164969 0.020631805, -0.001783669 -0.057648301 0.019041061, -0.00446935 -0.057502523 0.01904127, -0.0018601865 -0.060119554 0.023322865, 0.00017948449 -0.060148031 0.023322895, 0.00017619133 -0.059028998 0.022080138, -0.0018256158 -0.059000924 0.022080213, -0.0065382123 -0.05730404 0.019041225, -0.0045741647 -0.058851674 0.022080019, -0.0065968186 -0.057817683 0.02063179, -0.0046608597 -0.059967428 0.02332294, -0.009081766 -0.05695647 0.019041196, -0.0066915303 -0.058648705 0.022080138, -0.0091632307 -0.057466835 0.020631954, -0.0068184882 -0.059760526 0.023323044, -0.011247814 -0.056568593 0.019041166, -0.0092948228 -0.058292717 0.022080138, -0.011348665 -0.057075545 0.020631835, -0.009471029 -0.05939801 0.023322985, -0.013635382 -0.056040958 0.01904121, -0.011511803 -0.057895795 0.022080064, -0.013757437 -0.056543186 0.020631939, -0.01173009 -0.058993265 0.023322955, -0.015880674 -0.055446446 0.0190413, -0.013955206 -0.057355866 0.022080272, -0.01602304 -0.05594334 0.020631835, -0.014219746 -0.058443308 0.023323148, -0.018100306 -0.05476214 0.01904121, -0.016253352 -0.056747332 0.022080362, -0.018262744 -0.055252686 0.020631939, -0.016561463 -0.057823196 0.023323059, -0.020405203 -0.053945661 0.019041404, -0.018525049 -0.056046933 0.022080272, -0.020587876 -0.054429218 0.020631894, -0.018876284 -0.05710946 0.023323119, -0.022448152 -0.053127959 0.019041389, -0.020883888 -0.055211455 0.022080407, -0.022649348 -0.05360432 0.020632073, -0.021279693 -0.056258231 0.023323119, -0.024790213 -0.052076265 0.019041553, -0.022974789 -0.054374561 0.022080287, -0.025012493 -0.052543119 0.020632073, -0.023410335 -0.055405393 0.023323193, -0.026650295 -0.051149204 0.019041613, -0.025371611 -0.053298324 0.022080317, -0.026889056 -0.051607788 0.020632088, -0.025852755 -0.054308653 0.023323268, -0.029005736 -0.049851269 0.019041687, -0.027275383 -0.052349478 0.022080377, -0.029265761 -0.05029811 0.020632252, -0.027792603 -0.05334194 0.023323372, -0.030679643 -0.048839048 0.019041702, -0.029686362 -0.051021054 0.022080481, -0.030954361 -0.049276933 0.020632252, -0.030249193 -0.051988319 0.023323312, -0.033023313 -0.047285765 0.019041821, -0.031399235 -0.049985111 0.022080511, -0.033319339 -0.047709763 0.020632505, -0.031994596 -0.050932556 0.023323312, -0.034509897 -0.046211913 0.019041866, -0.033798113 -0.048395127 0.022080809, -0.03481926 -0.046626076 0.020632431, -0.034438848 -0.049312755 0.023323566, -0.03681536 -0.044397205 0.019042045, -0.035319522 -0.047296315 0.02208069, -0.037145168 -0.044795215 0.020632699, -0.035989225 -0.048192888 0.023323625, -0.03811647 -0.043285251 0.019041985, -0.037678942 -0.045438975 0.022080809, -0.038458005 -0.043673217 0.020632699, 0.053987846 -0.02029191 0.019043267, -0.038393229 -0.046300381 0.023323566, -0.039010823 -0.044300675 0.022080928, 0.054471612 -0.020473763 0.020633772, 0.05525434 -0.020768091 0.02208215, -0.040355757 -0.041205421 0.019042, -0.039750248 -0.045140877 0.023323864, 0.056301907 -0.021161824 0.023325086, -0.040717363 -0.041574746 0.020632759, 0.052179918 -0.024570167 0.019043073, 0.05264762 -0.0247906 0.020633861, -0.041475818 -0.040077806 0.019042253, -0.041302472 -0.042172253 0.022081152, 0.053404137 -0.025146961 0.022081941, -0.041847453 -0.040436924 0.020632938, 0.054416507 -0.025623679 0.023324817, -0.042085513 -0.042971835 0.023323804, 0.050033867 -0.028689414 0.01904273, -0.042448878 -0.041018113 0.022081137, 0.050482064 -0.028946489 0.020633459, -0.043620616 -0.037732109 0.019042358, 0.051207528 -0.029362544 0.022081673, -0.043253615 -0.041795939 0.023324117, 0.052178428 -0.029919177 0.023324549, -0.04456611 -0.036610425 0.019042209, -0.044011429 -0.038070261 0.020632863, 0.047563046 -0.032622442 0.019042671, -0.044965431 -0.036938652 0.020632982, 0.047989339 -0.032914698 0.020633146, -0.044643834 -0.038617745 0.02208133, 0.048678815 -0.033387795 0.022081584, 0.049601704 -0.034020931 0.02332437, -0.04561165 -0.037469447 0.022081509, -0.045490339 -0.039349541 0.023324102, 0.044783831 -0.036343753 0.019042298, -0.046587512 -0.034001142 0.019042492, 0.045185149 -0.036669567 0.020633012, -0.046476334 -0.038179815 0.023324102, -0.047367573 -0.032905519 0.019042522, 0.045834467 -0.037196591 0.022081286, -0.047004908 -0.034305856 0.02063328, 0.046703503 -0.037901774 0.023324147, 0.041714296 -0.039829582 0.019042179, -0.047791824 -0.033200547 0.020633236, -0.04768014 -0.034799069 0.022081301, 0.042088121 -0.040186584 0.020632833, -0.048478693 -0.033677831 0.022081584, 0.042692885 -0.040764078 0.022080988, -0.048584163 -0.035458729 0.023324355, 0.043502271 -0.041536912 0.023323953, 0.038374215 -0.043057144 0.019042, -0.049236074 -0.030037805 0.01904276, -0.049397811 -0.034316212 0.023324341, -0.04986167 -0.028987333 0.01904282, 0.038717985 -0.04344292 0.020632505, -0.049677223 -0.030307025 0.02063337, 0.039274365 -0.044067308 0.022081017, -0.050308526 -0.029247254 0.020633563, 0.040018961 -0.044902787 0.023323789, -0.050391048 -0.03074263 0.022081807, -0.051031426 -0.029667616 0.022081792, 0.034785241 -0.046005249 0.019041851, 0.035096854 -0.046417713 0.02063258, -0.051346377 -0.031325549 0.023324564, -0.051548302 -0.025869295 0.019043162, 0.035601258 -0.047084659 0.022080824, -0.051998824 -0.03023009 0.023324534, 0.036276162 -0.047977298 0.023323759, -0.052010208 -0.026101291 0.020633727, 0.030970559 -0.048655137 0.019041613, -0.052757427 -0.026476443 0.022081956, 0.031248257 -0.049091145 0.020632237, -0.053757831 -0.026978269 0.023324803, -0.053508237 -0.021524161 0.019043341, 0.031697109 -0.049796686 0.022080407, 0.032298118 -0.050740749 0.023323417, -0.053987846 -0.021717325 0.020633906, 0.026955053 -0.050989285 0.019041494, -0.054763496 -0.02202943 0.022082224, 0.025868326 -0.051549286 0.019041479, -0.055801764 -0.022447079 0.023324981, 0.027196616 -0.051446334 0.020632282, -0.055102944 -0.017031968 0.019043639, 0.026100084 -0.052011386 0.020632178, -0.055596679 -0.017184675 0.0206341, 0.027587384 -0.052185863 0.022080511, -0.056395784 -0.017431676 0.022082373, 0.026475251 -0.052758858 0.022080481, 0.028110445 -0.053175166 0.023323283, -0.057464808 -0.017762288 0.023325354, 0.022764966 -0.052993119 0.01904133, -0.056321174 -0.012423351 0.019043699, 0.026977196 -0.053759187 0.023323357, -0.056825757 -0.012534901 0.020634264, 0.021523073 -0.053509369 0.019041508, -0.057642549 -0.012714982 0.022082806, 0.022968918 -0.053468049 0.020632014, -0.058735341 -0.012956053 0.023325592, 0.021716058 -0.053989202 0.020631954, -0.057154551 -0.0077300519 0.019043908, 0.023298934 -0.054236501 0.022080392, 0.022028044 -0.054764897 0.022080258, -0.057666793 -0.007799387 0.020634741, 0.023740783 -0.055264756 0.023323253, -0.058495462 -0.0079115778 0.022082984, 0.018427059 -0.054653063 0.01904127, -0.059604555 -0.0080614984 0.023325935, 0.022445723 -0.055803284 0.02332297, 0.017030865 -0.055104017 0.019041449, -0.057597756 -0.0029838383 0.01904431, 0.01859194 -0.055142835 0.020632014, -0.058113813 -0.0030106604 0.020634875, 0.017183647 -0.055597991 0.020631969, -0.058948979 -0.003053993 0.022083223, 0.018859297 -0.055935234 0.022080258, -0.060066491 -0.0031118095 0.023326188, 0.017430484 -0.056396931 0.022080347, 0.019216865 -0.056995884 0.023323163, -0.057647124 0.0017827302 0.019044608, 0.013969496 -0.055958509 0.019041255, -0.058163717 0.0017985702 0.020635232, 0.017760843 -0.057466179 0.023322955, -0.058999643 0.0018243343 0.022083402, 0.01409471 -0.056460127 0.020631984, -0.060118198 0.0018590093 0.023326471, 0.012422338 -0.056322098 0.019041076, -0.057302982 0.0065369755 0.019044921, 0.014297247 -0.057271525 0.022080109, -0.057816476 0.0065956414 0.020635471, 0.012533695 -0.056827083 0.020631924, 0.014568314 -0.058357298 0.023323029, -0.0586472 0.0066902786 0.022083804, 0.012713745 -0.057643741 0.022080362, -0.059759215 0.0068170875 0.02332674, 0.0094214976 -0.056901217 0.019041255, -0.056567386 0.011246771 0.019045174, 0.012954921 -0.058736488 0.023322999, 0.0095059574 -0.05741109 0.02063182, -0.057074189 0.011347473 0.020635784, -0.057894409 0.011510506 0.022084117, 0.0077291131 -0.057155803 0.019041166, 0.009642601 -0.05823645 0.022080153, -0.058992133 0.011728793 0.023326889, 0.0077981651 -0.057667986 0.02063182, 0.0098254383 -0.059340402 0.02332288, 0.0048123896 -0.057474807 0.019041106, 0.0079103857 -0.058496773 0.022080123, 0.0048555434 -0.05798994 0.020631775, 0.0080601424 -0.059605777 0.02332297, 0.0029826611 -0.057598725 0.019041017, 0.0049252808 -0.058823228 0.022080109, 0.0030095428 -0.058114946 0.020631909, 0.0050187409 -0.059938625 0.023322865, 0.00017209351 -0.057675675 0.019041196, 0.0030527711 -0.058950275 0.022080228, 0.00017367303 -0.058192626 0.020631835, 0.0031107515 -0.060067818 0.023322925, -0.037043601 -0.064203054 -0.04561615, -0.04353483 -0.064581916 -0.049378365, -0.038923651 -0.067461312 -0.049378559, -0.0063906759 -0.074935496 -0.047765732, -0.0057022721 -0.075173095 -0.047965601, -0.0063196868 -0.07521151 -0.048054442, -0.0057463646 -0.074829325 -0.047572866, -0.042944014 -0.063705459 -0.049008533, -0.038395584 -0.066545993 -0.049008772, -0.0066674799 -0.074870914 -0.047718391, -0.0072965026 -0.075528234 -0.04841347, -0.0072203279 -0.074740276 -0.047621682, -0.0071629435 -0.074147344 -0.046673551, -0.042414159 -0.062919408 -0.04841283, -0.037921533 -0.065724999 -0.048412889, -0.006203264 -0.074388444 -0.046968222, -0.0071273893 -0.073779419 -0.045616969, -0.0057218671 -0.074511603 -0.047111556, -0.0099826753 -0.07636714 -0.049095392, -0.0098001808 -0.075147107 -0.048334554, -0.0083507299 -0.075721562 -0.048635587, -0.0095395446 -0.076934248 -0.049282297, -0.041971743 -0.062262937 -0.047620952, -0.010628998 -0.077155992 -0.049378991, -0.010202497 -0.076090887 -0.048981726, -0.037525937 -0.065039173 -0.04762122, -0.0084621459 -0.074570999 -0.047572792, -0.0079983026 -0.07565701 -0.048564062, -0.041431844 -0.061462715 -0.045615956, -0.047933877 -0.061387688 -0.049378201, -0.010506362 -0.07584551 -0.048875496, -0.011110455 -0.075366244 -0.048635542, -0.011718944 -0.075928792 -0.049009129, -0.0080039203 -0.074216232 -0.046968162, -0.047283351 -0.060554713 -0.04900834, -0.0084260702 -0.074254468 -0.047111362, -0.046700224 -0.059807539 -0.048412576, -0.011152163 -0.074559629 -0.047965571, -0.011672407 -0.075177893 -0.048564047, -0.046212912 -0.059183568 -0.047620803, -0.045618728 -0.058422625 -0.045615941, -0.045846224 -0.058714211 -0.046672761, -0.011770651 -0.074553013 -0.048054487, -0.012790218 -0.074794233 -0.048413441, -0.011823744 -0.074272349 -0.047765568, -0.011180118 -0.074212313 -0.047572702, -0.053310066 -0.056782067 -0.049378008, -0.052099526 -0.057894528 -0.049377978, -0.012101755 -0.074186638 -0.047718138, -0.012656882 -0.074013963 -0.047621638, -0.012556553 -0.073426649 -0.046673581, -0.01160787 -0.073738739 -0.046968162, -0.011132568 -0.073897138 -0.047111526, -0.052586541 -0.056011662 -0.049008116, -0.012494072 -0.073062271 -0.045616671, -0.0513926 -0.057108954 -0.049008116, -0.047837913 -0.059694946 -0.048833549, -0.05193767 -0.055320472 -0.048412308, -0.050758451 -0.056404248 -0.048412383, -0.047824472 -0.058912337 -0.048412532, -0.046933562 -0.058329046 -0.047319978, -0.047293693 -0.057905301 -0.047163442, -0.04811278 -0.059267268 -0.048736945, -0.048421383 -0.057390809 -0.047620624, -0.051395819 -0.054743171 -0.047620416, -0.050228834 -0.055815697 -0.047620654, -0.056011438 -0.05411917 -0.049377695, -0.050988138 -0.054308996 -0.046672508, -0.049830422 -0.055372939 -0.046672493, -0.05056338 -0.057404488 -0.04883334, -0.049851447 -0.057207495 -0.048412472, -0.049285889 -0.056219459 -0.047163352, -0.055251226 -0.053384915 -0.049007982, -0.049596578 -0.056082264 -0.047319859, -0.050151855 -0.057552084 -0.04873687, -0.050734967 -0.054039553 -0.045615748, -0.049583137 -0.055098221 -0.045615688, -0.046771467 -0.057503909 -0.045615926, -0.048135102 -0.056367412 -0.045615748, -0.046138629 -0.058013052 -0.045615941, -0.047122091 -0.057695046 -0.046672657, -0.048206434 -0.056792468 -0.046672612, -0.049107 -0.056015581 -0.046672568, -0.057312712 -0.052739024 -0.049377695, -0.074872613 -0.0051874071 -0.047568709, -0.075859189 -0.0058061779 -0.048560128, -0.075988963 -0.0054370165 -0.048631668, -0.074811146 -0.0064731687 -0.047617882, -0.054569483 -0.052726254 -0.048412263, -0.075683489 -0.0039420277 -0.048330501, -0.05653508 -0.052023709 -0.049007893, -0.074439943 -0.0055851042 -0.046964139, -0.074217498 -0.006422013 -0.046669856, -0.073849335 -0.0063901246 -0.045612961, -0.054000229 -0.052176028 -0.047620445, -0.074554577 -0.0051655918 -0.047107592, -0.055837408 -0.051381677 -0.048412055, -0.053571835 -0.051762015 -0.046672329, -0.075012356 -0.0024495572 -0.04756853, -0.076136976 -0.0026581138 -0.048631579, -0.076052114 -0.0021058917 -0.048560023, -0.055254832 -0.050845563 -0.047620371, -0.075084284 -0.00099511445 -0.04761745, -0.053305954 -0.051505223 -0.045615673, -0.074623689 -0.0019540042 -0.046964258, -0.074693665 -0.0024392009 -0.047107443, -0.059650287 -0.05008021 -0.049377531, -0.074488536 -0.00098711252 -0.046669498, -0.074118808 -0.00098246336 -0.045612633, -0.054816499 -0.050442144 -0.0466723, -0.075051695 0.00027798116 -0.04756844, -0.076183394 8.3118677e-05 -0.048631191, -0.075769991 0.0015657842 -0.048330128, -0.076080814 -0.00028073788 -0.04855977, -0.058840841 -0.049400568 -0.049007639, -0.074648991 -0.00014537573 -0.046964049, -0.054544389 -0.050191879 -0.045615539, -0.074733153 0.00027690828 -0.047107175, -0.058114856 -0.04879117 -0.048411995, -0.075333416 0.0029669702 -0.047961146, -0.076129496 0.0028654784 -0.048631042, -0.076004282 0.0034237951 -0.048559666, -0.061009556 -0.04841502 -0.049377427, -0.057508558 -0.048281983 -0.047620222, -0.060181946 -0.047757909 -0.049007565, -0.07512106 0.0036624819 -0.047761261, -0.074991614 0.0030187666 -0.047568247, -0.075747058 0.0045357645 -0.04840906, -0.057052255 -0.047899023 -0.04667218, -0.075066805 0.0039379895 -0.047713727, -0.059439108 -0.047168732 -0.048411801, -0.074956775 0.0044883341 -0.047617212, -0.074362218 0.0044528395 -0.046669275, -0.074567795 0.0034894049 -0.046963871, -0.073992848 0.0044305027 -0.04561241, -0.056769252 -0.0476612 -0.045615301, -0.074673161 0.0030061007 -0.047107145, -0.074832454 0.0057423264 -0.047568262, -0.075977296 0.0056026876 -0.048630893, -0.075456277 0.0070652515 -0.048329949, -0.058819354 -0.046676531 -0.047620028, -0.07590045 0.0052459389 -0.048559517, -0.07446143 0.0052951574 -0.046963811, -0.062998578 -0.045797154 -0.049377352, -0.058352664 -0.046306252 -0.046671972, -0.074514627 0.0057177842 -0.047106981, -0.062143758 -0.045175731 -0.04900752, -0.074918613 0.0084355325 -0.047960922, -0.075722173 0.0083737969 -0.048630774, -0.058062777 -0.046076417 -0.04561533, -0.075555146 0.0089353025 -0.048559144, -0.061376914 -0.044618219 -0.048411682, -0.064381227 -0.043832377 -0.049377114, -0.074934527 0.0090539306 -0.048049673, -0.075214058 0.01005286 -0.048408657, -0.060736626 -0.044152826 -0.047619909, -0.074656129 0.0091157109 -0.04776074, -0.074572891 0.0084713697 -0.047568023, -0.063507646 -0.043237701 -0.049007237, -0.074580863 0.0093934536 -0.047713473, -0.074429438 0.0099479556 -0.047616988, -0.07383889 0.0098688453 -0.046668902, -0.060254738 -0.043802634 -0.046671912, -0.074115485 0.0089141577 -0.046963423, -0.073472366 0.0098199099 -0.045612037, -0.06272395 -0.04270415 -0.048411638, -0.074256346 0.0084356517 -0.047106728, -0.075960949 0.012729123 -0.049090341, -0.075371787 0.01109308 -0.048630685, -0.076543897 0.012304336 -0.049277171, -0.076730028 0.013380259 -0.04937385, -0.074743971 0.012527332 -0.048329607, -0.059955686 -0.043585286 -0.045615107, -0.075676724 0.012940049 -0.04897669, -0.074215963 0.011175975 -0.047567919, -0.075319067 0.010745257 -0.048559129, -0.06603995 -0.041291073 -0.049377039, -0.062069729 -0.042258486 -0.047619864, -0.075419277 0.013240531 -0.048870295, -0.075458705 0.01445663 -0.049004123, -0.074916571 0.013838276 -0.048630476, -0.073877692 0.010707378 -0.046963438, -0.065143928 -0.040730685 -0.049007148, -0.061577156 -0.041923195 -0.046671823, -0.064339966 -0.040228352 -0.048411578, -0.07390067 0.011128604 -0.047106609, -0.074107423 0.013859421 -0.04796052, -0.074706703 0.014399692 -0.048559129, -0.061271414 -0.041715294 -0.045614943, -0.067409292 -0.039015904 -0.04937683, -0.063668713 -0.039808437 -0.04761973, -0.074078232 0.014477253 -0.048049465, -0.074279904 0.01551649 -0.048408419, -0.06649451 -0.038486406 -0.049007043, -0.073795497 0.014521047 -0.047760785, -0.063163668 -0.039492667 -0.046671554, -0.073758379 0.013879031 -0.047567695, -0.065673947 -0.038011625 -0.04841131, -0.073699176 0.014799088 -0.047712967, -0.07350488 0.01535432 -0.047616556, -0.072921664 0.015232325 -0.046668604, -0.07326898 0.014291629 -0.046963051, -0.072559804 0.01515685 -0.045611694, -0.062850192 -0.039296776 -0.045614883, -0.073445082 0.013820082 -0.047106385, 0.073198214 -0.026614457 -0.049376279, 0.0065748245 -0.074748248 -0.047556326, 0.006692484 -0.075487405 -0.048334405, 0.0051835328 -0.074870318 -0.047572687, 0.0064742416 -0.074192926 -0.046636075, 0.0078808814 -0.074314252 -0.047111511, -0.068759769 -0.036583677 -0.049376816, 0.0051614791 -0.074552551 -0.047111496, 0.0079146326 -0.074631214 -0.047572687, -0.064988911 -0.037615046 -0.047619551, 0.0077653676 -0.073710352 -0.04559648, 0.0082982033 -0.074183986 -0.046968102, 0.072204903 -0.026253328 -0.049006328, 0.0090855509 -0.073563948 -0.045616791, 0.0050680488 -0.073944867 -0.045596614, -0.067826569 -0.03608726 -0.049006999, 0.0046764612 -0.074500084 -0.046968192, 0.003691256 -0.07403098 -0.045616746, 0.071314007 -0.025929332 -0.048410714, 0.0011187941 -0.075028569 -0.04755643, 0.0024484992 -0.074690923 -0.047111467, 0.0024590194 -0.075009331 -0.047572702, -0.06447342 -0.037316665 -0.046671554, 0.0011914819 -0.075774014 -0.048334643, -0.00022235513 -0.075388834 -0.047965586, -0.00028215349 -0.075049251 -0.047572687, -0.0002809763 -0.074730396 -0.047111511, 0.001050055 -0.074467257 -0.046636149, 0.070570096 -0.02565892 -0.047618821, 0.002368331 -0.074080527 -0.045596629, 0.0028697699 -0.074591503 -0.046968281, -0.06698963 -0.035642192 -0.04841128, 0.070010215 -0.025455236 -0.046670839, -0.00033888221 -0.074117407 -0.04559651, -0.0017227381 -0.074103042 -0.045616776, -0.064153358 -0.037131444 -0.045614645, -0.00076533854 -0.074642733 -0.046968237, 0.069662675 -0.025328979 -0.045614094, -0.0043429732 -0.074911252 -0.047556341, -0.003009513 -0.074989304 -0.047572806, -0.0043156296 -0.075660497 -0.048334673, -0.070077524 -0.033991203 -0.049376532, -0.0029966235 -0.074670866 -0.047111496, -0.004379794 -0.074345797 -0.046636239, -0.0030411631 -0.074055865 -0.045596689, -0.0025739223 -0.074602172 -0.046968028, 0.071163192 -0.031655625 -0.049376369, -0.06629087 -0.035270154 -0.047619492, -0.0057439357 -0.073895425 -0.045596451, -0.069126591 -0.033529893 -0.049006656, 0.070197672 -0.031226158 -0.049006686, -0.0097818971 -0.074396551 -0.047556341, 0.069331303 -0.030840829 -0.048410967, -0.0097863674 -0.073828936 -0.046636194, -0.065764874 -0.034990445 -0.046671569, -0.008434549 -0.07363677 -0.04559648, -0.068273664 -0.033116296 -0.048411205, 0.06860809 -0.030519113 -0.047619268, -0.011118397 -0.073279589 -0.045596451, -0.065438464 -0.034816757 -0.04561466, 0.068063796 -0.030276969 -0.046671242, -0.049028009 -0.060517356 -0.049378037, -0.071144313 -0.031698108 -0.049376547, -0.049426705 -0.058818623 -0.049008295, 0.067725942 -0.030126631 -0.045614302, -0.050303087 -0.059942365 -0.049447626, -0.067561343 -0.032770798 -0.047619328, 0.068781406 -0.036542729 -0.049376711, -0.051110342 -0.058769494 -0.049377918, -0.070178807 -0.031268209 -0.049006656, -0.048874319 -0.058044448 -0.048412532, -0.067025527 -0.032510862 -0.046671256, 0.067848191 -0.036046654 -0.049006939, -0.074940667 -0.0038467497 -0.047552377, -0.074382246 -0.0037619025 -0.046632037, -0.069312975 -0.03088209 -0.048410967, 0.067010999 -0.035602018 -0.048411295, -0.073947147 -0.0050678551 -0.045592695, 0.066311777 -0.035230443 -0.047619507, -0.066692695 -0.032349452 -0.045614436, -0.074082956 -0.0023634732 -0.045592502, -0.068589807 -0.030560121 -0.047619194, 0.065785691 -0.034951165 -0.046671465, -0.075022191 0.0016156137 -0.047551975, -0.074458763 0.0016686767 -0.046631843, -0.072371945 -0.028785378 -0.04937619, 0.065459266 -0.034777701 -0.045614615, -0.07412003 0.00033903122 -0.045592263, -0.06804584 -0.030317605 -0.046671122, 0.066064671 -0.041251495 -0.04937692, -0.074058369 0.003046006 -0.045592159, -0.071389839 -0.02839461 -0.049006566, 0.065168187 -0.040691808 -0.049007252, -0.074706152 0.0070698112 -0.047551706, -0.074139267 0.0070903897 -0.046631709, -0.067707852 -0.030167222 -0.045614362, -0.073898003 0.0057443231 -0.045592129, 0.06436412 -0.040189758 -0.048411459, -0.070509136 -0.028044298 -0.048410729, -0.073638976 0.0084393471 -0.045591876, 0.063692629 -0.039770469 -0.047619835, -0.073993891 0.012486458 -0.047551483, 0.063187286 -0.039455056 -0.046671748, -0.07318227 -0.026658207 -0.049376026, -0.073425561 0.012474313 -0.046631217, 0.062873647 -0.039259166 -0.045614958, -0.069773406 -0.027751759 -0.047618896, -0.07328251 0.011118695 -0.045591637, -0.072189122 -0.026296511 -0.049006253, -0.072827652 0.013787717 -0.045591637, 0.063025862 -0.045759469 -0.049377292, -0.069219962 -0.027531594 -0.046671078, 0.062170744 -0.045138642 -0.049007446, -0.07129845 -0.025972098 -0.048410773, 0.061403692 -0.044581607 -0.048411861, -0.068876341 -0.027394861 -0.045614153, 0.060763091 -0.044116497 -0.047620088, -0.070554748 -0.025701001 -0.047618806, -0.074280396 -0.023425519 -0.049376011, 0.059981704 -0.043549344 -0.045615226, 0.060281023 -0.043766648 -0.046671942, -0.069994986 -0.025497019 -0.046670839, 0.059680253 -0.050044477 -0.049377397, -0.073272541 -0.023107752 -0.049006328, 0.05887045 -0.049365386 -0.049007729, -0.069647416 -0.025370643 -0.045614108, 0.058693886 -0.051197678 -0.04937759, -0.074863702 -0.021488369 -0.049375966, -0.072368294 -0.022822544 -0.04841055, 0.058144063 -0.048756331 -0.048411846, -0.073847935 -0.021196783 -0.049006045, 0.057897463 -0.050503045 -0.049007714, 0.057537377 -0.048247755 -0.047620252, -0.071613118 -0.022584602 -0.047618747, 0.057183132 -0.049879909 -0.048412099, -0.072936803 -0.020935118 -0.048410296, -0.07104516 -0.022405311 -0.046670794, 0.0565864 -0.049359351 -0.047620326, -0.072175875 -0.020716786 -0.047618613, 0.056797609 -0.04762736 -0.045615405, 0.057081044 -0.047864899 -0.046672091, -0.070692539 -0.022294253 -0.045613825, 0.056043625 -0.054085627 -0.049377829, -0.075792342 -0.017940849 -0.049375683, 0.056137666 -0.048967913 -0.046672285, -0.071603253 -0.020552516 -0.046670645, 0.055283204 -0.053351715 -0.049007967, -0.074763924 -0.017697453 -0.049006045, 0.055858999 -0.048724905 -0.04561533, 0.054799914 -0.055345401 -0.049377754, -0.071247846 -0.020450592 -0.045613766, 0.054601118 -0.052693442 -0.048412189, -0.076180652 -0.01621373 -0.0493754, -0.073841438 -0.017479062 -0.048410207, 0.054056451 -0.054594561 -0.049007997, 0.054031491 -0.052143797 -0.047620505, -0.075146914 -0.01599355 -0.049005747, -0.073071167 -0.017296717 -0.047618374, 0.053389326 -0.05392085 -0.048412114, 0.053602874 -0.051730111 -0.046672329, -0.07421948 -0.015796512 -0.048410162, -0.072491333 -0.017159596 -0.046670333, 0.052832291 -0.053358212 -0.04762052, 0.053336754 -0.051473349 -0.045615718, -0.073445261 -0.015631586 -0.047618389, -0.072131351 -0.017074451 -0.045613542, 0.052134201 -0.05786328 -0.049377963, -0.076899797 -0.012360677 -0.04937543, 0.052413255 -0.052935004 -0.04667227, -0.072862625 -0.015507668 -0.046670243, 0.051426798 -0.057078153 -0.049008116, 0.052153125 -0.052672327 -0.045615777, -0.075856462 -0.012192816 -0.049005568, -0.072500885 -0.015430748 -0.045613572, 0.050613612 -0.059197932 -0.049378127, -0.077126086 -0.01086022 -0.049375311, 0.050792232 -0.05637379 -0.048412323, -0.074920639 -0.012042582 -0.048409805, 0.049926862 -0.058394641 -0.04900822, -0.076079652 -0.010712817 -0.049005508, 0.050262302 -0.055785671 -0.047620639, -0.074138835 -0.011916637 -0.047618046, 0.049310803 -0.05767417 -0.048412502, -0.075140879 -0.01058051 -0.048409894, 0.049863592 -0.055343285 -0.046672508, -0.073550761 -0.011822209 -0.046670124, 0.048796311 -0.057072446 -0.047620744, -0.074356958 -0.010470137 -0.047618046, 0.049616098 -0.055068567 -0.045615762, -0.073185652 -0.011763632 -0.045613304, 0.047970712 -0.061359063 -0.049378186, -0.073767081 -0.010387242 -0.046670035, 0.048409194 -0.056619704 -0.046672657, -0.077597216 -0.0067142844 -0.049375027, 0.047319785 -0.060526475 -0.049008429, -0.073401034 -0.010335535 -0.045613319, 0.048168853 -0.056338668 -0.045615852, -0.076544404 -0.0066231936 -0.0490053, 0.046735927 -0.059779719 -0.048412591, -0.075599805 -0.006541416 -0.048409656, 0.046157226 -0.062734634 -0.049378157, 0.046248421 -0.059156045 -0.047620758, 0.04553099 -0.06188342 -0.049008369, 0.045881316 -0.058686689 -0.046672687, 0.044969007 -0.061119705 -0.048412755, 0.04565382 -0.058395401 -0.04561609, 0.044499859 -0.0604821 -0.047620848, 0.043573558 -0.064555794 -0.049378321, 0.044146895 -0.060002238 -0.046672672, 0.042982236 -0.063679963 -0.049008548, 0.043927819 -0.059704438 -0.045615897, 0.042451844 -0.062894225 -0.048412889, 0.041454479 -0.065936446 -0.049378321, 0.042008772 -0.062237859 -0.047621116, 0.04089202 -0.06504181 -0.049008593, 0.041675657 -0.061744228 -0.04667297, 0.040387362 -0.064239144 -0.04841277, 0.041468859 -0.06143786 -0.045616046, 0.038963839 -0.067438304 -0.049378455, 0.039966092 -0.06356895 -0.047621131, 0.038435206 -0.066522941 -0.049008697, 0.039649069 -0.063064739 -0.046673074, 0.037960917 -0.065702319 -0.048412889, -0.076242477 0.015926167 -0.049373776, 0.039452165 -0.062751725 -0.04561618, -0.075207978 0.01571025 -0.049004063, 0.036530703 -0.068786561 -0.049378604, 0.037564814 -0.065016791 -0.047621116, 0.036035016 -0.067853078 -0.049008772, 0.03726697 -0.064501122 -0.046672866, 0.035590395 -0.067015976 -0.048413068, 0.037081867 -0.06418094 -0.045616224, 0.067627892 -0.030346528 -0.045614287, 0.034164533 -0.069991857 -0.049378663, 0.065289155 -0.035096169 -0.045614719, 0.035219014 -0.066316739 -0.047621235, 0.062617362 -0.039666682 -0.045614868, 0.059626162 -0.044034675 -0.045615226, 0.033700943 -0.069041923 -0.049008861, 0.008855924 -0.077379555 -0.049378946, 0.0095466524 -0.077297404 -0.049379036, 0.0094170123 -0.076248601 -0.049009308, 0.034939736 -0.065790638 -0.046673059, 0.033285052 -0.068190262 -0.048412964, 0.0071664006 -0.077191591 -0.049282134, 0.0060238093 -0.077651277 -0.049378857, 0.034766242 -0.065464243 -0.045616299, 0.0038785636 -0.07778807 -0.049379095, 0.0033101141 -0.077814266 -0.049379066, 0.031411871 -0.071269527 -0.049378797, 0.0038258135 -0.076732501 -0.049009159, 0.0015964955 -0.077507094 -0.049282238, 0.032937929 -0.067478791 -0.04762125, 0.0004658848 -0.077883244 -0.049379081, 0.030985788 -0.070302442 -0.049008995, -0.0018101335 -0.077863649 -0.049379185, -0.0022525638 -0.077852145 -0.049379155, -0.0017856508 -0.076807052 -0.049009249, 0.032676563 -0.066943422 -0.046673253, -0.0039818287 -0.077421159 -0.049282148, 0.030603409 -0.069435075 -0.048413202, -0.0050945282 -0.077717841 -0.049379125, -0.0074891895 -0.077523738 -0.04937914, 0.032514274 -0.066611096 -0.045616344, -0.007803753 -0.077492759 -0.049378976, -0.0073876232 -0.076471791 -0.0490091, 0.029198766 -0.072204575 -0.049378812, 0.030283973 -0.068710655 -0.047621369, 0.028802529 -0.071224689 -0.049008906, -0.013128355 -0.076770306 -0.049378887, -0.032744735 -0.066498414 -0.045616239, -0.032474443 -0.066630751 -0.045616403, -0.032636523 -0.066962957 -0.046673238, 0.030043885 -0.068165585 -0.046673402, -0.037228316 -0.064523265 -0.04667303, -0.037407711 -0.063991532 -0.045616195, 0.028447166 -0.070345953 -0.048413038, -0.041638643 -0.061769083 -0.046673074, -0.041879922 -0.06115815 -0.04561621, 0.029894814 -0.067827314 -0.045616359, 0.028150454 -0.069612041 -0.047621474, 0.02612552 -0.073372334 -0.049378842, -0.077649102 -0.006084159 -0.049375132, 0.027927071 -0.069059715 -0.046673447, 0.025771126 -0.072376922 -0.049008951, -0.077402085 -0.0043816268 -0.049278185, -0.077819705 -0.0032442063 -0.049374893, 0.027788356 -0.068716913 -0.045616567, -0.077880546 -0.0010320693 -0.049374551, -0.077885494 -0.00052639842 -0.049374759, -0.076823816 -0.0010180324 -0.049004987, 0.025453165 -0.071483806 -0.048413381, 0.024090633 -0.074065357 -0.049378887, -0.077516988 0.0011962354 -0.049277782, 0.025187582 -0.070738003 -0.047621429, -0.077853024 0.0023186654 -0.049374551, -0.077748284 0.0046555102 -0.049374357, -0.07772474 0.0050342232 -0.049374431, -0.076693431 0.0045924485 -0.049004599, 0.023763791 -0.073060408 -0.049009085, -0.077230603 0.0067678988 -0.049277574, 0.024987668 -0.07017678 -0.046673298, 0.023470655 -0.072159037 -0.048413351, -0.077489167 0.0078694671 -0.049374148, -0.077201292 0.010318369 -0.049374148, -0.077167496 0.010569125 -0.049373999, 0.02486372 -0.06982848 -0.045616671, -0.076153755 0.010178357 -0.049004376, 0.023225814 -0.071406141 -0.047621578, 0.020699754 -0.075083628 -0.049379036, 0.063058898 -0.039659768 -0.046671525, 0.023041531 -0.070839599 -0.046673477, 0.060102865 -0.044010863 -0.046672016, 0.020418882 -0.074064881 -0.04900904, 0.0085618794 -0.075595289 -0.048564121, 0.0092037916 -0.074521989 -0.047621712, 0.0093009472 -0.075307697 -0.04841356, 0.022927046 -0.070487902 -0.045616671, 0.0081909597 -0.075739041 -0.048635602, 0.018865362 -0.075565457 -0.049378872, 0.020167053 -0.073150977 -0.048413366, 0.018609315 -0.074540123 -0.049009085, 0.0048843324 -0.076672316 -0.04900904, 0.019956633 -0.07238774 -0.047621548, 0.0054193586 -0.075987712 -0.048635513, 0.0048710555 -0.075922519 -0.048564076, 0.018379658 -0.073620424 -0.048413217, 0.0037788302 -0.07578589 -0.04841353, 0.0037392676 -0.074995175 -0.047621638, 0.019798294 -0.071813479 -0.046673417, 0.0030482709 -0.076017454 -0.048564121, 0.0026815534 -0.076133609 -0.048635542, 0.018187895 -0.072852284 -0.047621578, 0.019699946 -0.071457118 -0.045616791, 0.015163541 -0.076394439 -0.049379066, 0.018043578 -0.072274387 -0.046673492, -0.00066307187 -0.076825023 -0.049009189, 0.014957964 -0.075357601 -0.049009085, -0.00010095537 -0.076180667 -0.048635557, -0.00065667927 -0.076075673 -0.048564076, 0.017954022 -0.071915597 -0.045616597, -0.0017635971 -0.075859368 -0.048413485, 0.013547882 -0.076697364 -0.049378917, -0.0024815202 -0.076038122 -0.048564151, -0.0017452687 -0.075067878 -0.047621742, 0.014773294 -0.074428082 -0.04841347, -0.0028418601 -0.076127723 -0.048635498, 0.013364032 -0.075656563 -0.049009189, 0.014619231 -0.073651373 -0.047621697, -0.0062072277 -0.076576769 -0.049009234, 0.01319924 -0.074723229 -0.0484135, -0.0056205392 -0.075973138 -0.048635527, 0.014503226 -0.073067218 -0.046673432, -0.0061808378 -0.075827047 -0.048564062, 0.013061583 -0.073943675 -0.047621757, 0.014431283 -0.072704494 -0.045616791, 0.012957692 -0.073356867 -0.046673566, -0.012950286 -0.075728476 -0.049009189, 0.012893572 -0.072992995 -0.045616671, -0.037411466 -0.064417213 -0.04667297, -0.041864216 -0.061616674 -0.046672985, 0.0091308057 -0.0739308 -0.046673551, -0.046108067 -0.058508843 -0.046672732, -0.076801509 -0.0021093637 -0.049005002, -0.075875893 -0.0010056049 -0.048409298, -0.076753646 0.0034401864 -0.049004748, -0.076305255 0.008971706 -0.049004376, -0.018697456 -0.075607106 -0.049379036, -0.018443659 -0.074581355 -0.04900898, -0.018216029 -0.073661149 -0.048413381, -0.018025979 -0.072892502 -0.047621638, -0.017882958 -0.072314247 -0.046673447, -0.017794222 -0.071955368 -0.045616806, -0.024046406 -0.074079752 -0.049378857, -0.02372019 -0.073074654 -0.049008936, -0.023427442 -0.072172984 -0.048413306, -0.023183063 -0.071420029 -0.047621444, -0.022999078 -0.070853412 -0.046673387, -0.02288489 -0.07050173 -0.045616478, -0.029155523 -0.072221965 -0.049378753, -0.028759941 -0.071242064 -0.049008936, 0.003709659 -0.074400201 -0.046673551, -0.028405085 -0.070363075 -0.048413292, -0.028108716 -0.06962882 -0.047621354, -0.027885661 -0.069076553 -0.046673253, -0.027747363 -0.068733603 -0.045616627, -0.034122512 -0.070012286 -0.049378544, -0.033659682 -0.069062114 -0.049008638, -0.00092378259 -0.075201884 -0.047765702, -0.033244327 -0.06821011 -0.048412979, -0.0011978298 -0.075157598 -0.047718212, -0.0017312169 -0.074472561 -0.04667379, -0.032897517 -0.067498416 -0.047621354, 0.03344956 0.046544403 -0.0051564574, 0.032851517 0.047038868 -0.0053848028, 0.032639742 0.046735734 -0.0043280423, 0.043393552 0.037534997 -0.0053853989, 0.041259915 0.039868578 -0.0053852797, 0.040994167 0.03961134 -0.0043284297, 0.043113768 0.037292942 -0.0043284595, 0.033743545 0.046290889 -0.0050436258, 0.033212081 0.045643464 -0.0034291744, 0.042475864 0.034417465 -0.0019931495, 0.044159919 0.032228351 -0.0019934773, 0.041654676 0.033752024 -0.0016234219, 0.034292474 0.045097262 -0.0037153363, 0.043306082 0.031605497 -0.0016235709, 0.034772024 0.045673996 -0.0055203438, 0.042663291 0.036903203 -0.0033804178, 0.044290453 0.035887748 -0.0043286383, 0.043827742 0.035512641 -0.003380537, 0.035070032 0.044231772 -0.0034292638, 0.035627663 0.044857025 -0.0050436854, 0.036387652 0.043880656 -0.0043283105, 0.044438034 0.029993117 -0.0016237795, 0.03596285 0.044631004 -0.0051565766, 0.04492566 0.032787308 -0.0025889575, 0.043212458 0.035014167 -0.0025888383, 0.036623791 0.044165149 -0.0053851008, 0.05453521 0.0038298815 -0.0019949377, 0.053756952 0.0030070245 -0.0016830862, 0.053480893 0.0037558973 -0.00162521, 0.044577822 0.036120564 -0.0053854883, 0.053889826 0.0026298612 -0.0017158389, 0.055261388 0.0015154481 -0.0023455322, 0.05550009 0.0027606487 -0.0025521517, 0.045313895 0.030584455 -0.0019935369, 0.053458035 0.0014325231 -0.001596421, 0.045565188 0.033254072 -0.0033807456, 0.053953409 0.00027681887 -0.0017161071, 0.055567428 0.00033722818 -0.0025523305, 0.046099678 0.031114802 -0.0025891662, 0.053840846 -0.00012375414 -0.0016830564, 0.053604752 -0.00091964006 -0.0016255528, 0.046046138 0.033605218 -0.0043286979, 0.054640457 -0.00030294061 -0.001981765, 0.055609226 -0.00095383823 -0.0025910288, 0.054661393 -0.00093758106 -0.001995191, 0.045768157 0.0279212 -0.0016238987, 0.053814486 -0.0016864389 -0.0016831458, 0.046755984 0.031557769 -0.0033807456, 0.053914234 -0.0020723492 -0.0017162561, 0.055529892 -0.0020727366 -0.0025524348, 0.055183753 -0.0032971203 -0.0023458451, 0.046344906 0.033823311 -0.0053856671, 0.053379536 -0.0032289028 -0.0015965849, 0.046670422 0.02847147 -0.0019937754, 0.053772449 -0.004422009 -0.0017163306, 0.055386603 -0.004493013 -0.0025524795, 0.053625405 -0.0048128217 -0.0016835332, 0.053320661 -0.0055880696 -0.0016256869, 0.04724969 0.031891018 -0.0043289065, 0.054406807 -0.0050568879 -0.0019820184, 0.054371685 -0.0056981295 -0.0019955039, 0.055314615 -0.0057969093 -0.0025912374, 0.053463027 -0.0063674003 -0.0016836524, 0.047479704 0.028965399 -0.0025892556, 0.046882898 0.026005968 -0.0016238689, 0.053528994 -0.0067586005 -0.0017165095, 0.055139765 -0.0068906099 -0.0025526583, 0.047556236 0.03209807 -0.0053856671, 0.054687768 -0.0080849081 -0.0023459792, 0.052895561 -0.0078660995 -0.0015967935, 0.04815565 0.029377729 -0.0033810139, 0.054786518 -0.0092892498 -0.0025529563, 0.053183138 -0.0090872198 -0.0017164946, 0.047807157 0.026518643 -0.0019936562, 0.052630708 -0.010214046 -0.0016258657, 0.053002477 -0.0094651282 -0.0016837567, 0.053668067 -0.010415241 -0.0019958317, 0.053760201 -0.0097727031 -0.0019822568, 0.048664108 0.029688001 -0.0043288767, 0.054598823 -0.010595888 -0.0025914311, 0.048636138 0.026978523 -0.0025894046, 0.047917515 0.024046302 -0.0016239583, 0.048979744 0.029880643 -0.0053859353, 0.049328431 0.027362645 -0.0033810735, 0.0488621 0.024520323 -0.0019937158, 0.049849302 0.027651697 -0.0043290854, 0.049709409 0.024945587 -0.002589494, 0.048971131 0.021821022 -0.0016242266, 0.050172687 0.027831063 -0.0053859353, 0.050417051 0.025300801 -0.0033812225, 0.049936444 0.022251204 -0.0019938946, 0.050949469 0.025567994 -0.0043290854, 0.049739584 0.020007223 -0.001624167, 0.05080232 0.022637025 -0.002589643, 0.051280126 0.025733784 -0.0053861439, 0.050720066 0.020401686 -0.001994133, 0.051525608 0.022959366 -0.0033813119, 0.051599592 0.020755425 -0.0025897324, 0.052069679 0.023201719 -0.0043293834, 0.050686598 0.017469779 -0.0016243756, 0.052334145 0.02105093 -0.0033813417, 0.052407354 0.02335231 -0.0053861439, 0.051685646 0.017814279 -0.0019940734, 0.052886829 0.02127336 -0.0043294728, 0.051221937 0.01583153 -0.0016244352, 0.052581921 0.018123224 -0.0025898814, 0.053229913 0.0214113 -0.0053862631, 0.052231535 0.016143516 -0.001994282, 0.053330436 0.018381223 -0.0033814013, 0.053137377 0.016423449 -0.002589941, 0.053893775 0.018575266 -0.0043295622, 0.052016109 0.012985691 -0.0016246438, 0.05389376 0.016657248 -0.0033816993, 0.054243207 0.01869601 -0.0053864419, 0.053041637 0.013241664 -0.0019945204, 0.05446285 0.01683332 -0.0043297112, 0.052354321 0.011547491 -0.0016246736, 0.053961411 0.013471246 -0.0025901198, 0.054816216 0.016942471 -0.0053865612, 0.053386301 0.011775166 -0.00199458, 0.054729551 0.013663158 -0.0033817589, 0.054312095 0.011979401 -0.00259009, -0.050145119 0.018968061 -0.0016242266, 0.055307537 0.01380749 -0.00432989, -0.051133409 0.019341901 -0.0019942373, 0.055085242 0.012149975 -0.0033818185, -0.052020162 0.019677356 -0.0025896877, 0.052950114 0.0084026754 -0.0016250014, 0.055666342 0.013897091 -0.0053865612, -0.052760839 0.019957349 -0.003381446, -0.053317979 0.020168424 -0.0043294728, 0.055667102 0.012278289 -0.0043299794, -0.048407197 0.023044124 -0.0016241521, 0.053993776 0.0085683614 -0.0019946992, -0.053663731 0.020299196 -0.0053862482, 0.053129077 0.0071845949 -0.0016250312, 0.056027934 0.012357935 -0.0053868592, 0.054930076 0.0087169558 -0.0025902689, -0.049361676 0.023498535 -0.0019937903, -0.050217524 0.023905978 -0.0025894493, 0.05417639 0.0073261857 -0.0019948483, -0.050932541 0.024246231 -0.0033811629, 0.055712163 0.0088411868 -0.0033821762, -0.05147022 0.024502456 -0.0043292195, 0.055115893 0.0074534863 -0.0025905371, -0.046339169 0.026962936 -0.0016238689, 0.056300402 0.0089345276 -0.0043300986, -0.051804215 0.02466163 -0.0053859949, 0.055900365 0.0075594336 -0.0033820868, -0.047252595 0.027494505 -0.0019937754, 0.056665704 0.0089925677 -0.0053870529, -0.04807207 0.027971253 -0.0025893003, 0.05649069 0.0076394975 -0.0043302476, -0.048756197 0.028369531 -0.0033810139, -0.049271122 0.028669134 -0.0043289959, 0.056857154 0.0076888949 -0.005387187, 0.055480778 0.0038964152 -0.0025906265, -0.049590707 0.02885507 -0.0053857118, 0.05627054 0.003951937 -0.0033823252, 0.056864858 0.0039936304 -0.0043302774, 0.057233661 0.0040196925 -0.0053872764, -0.041269228 0.034222424 -0.0016234517, -0.040472418 0.035161048 -0.0016234368, -0.041270196 0.035854235 -0.0019932836, -0.042082548 0.03489697 -0.0019931197, -0.042812392 0.035502255 -0.0025888681, -0.041985989 0.036476061 -0.0025888383, -0.042583525 0.036995158 -0.0033806413, -0.04342185 0.036007464 -0.0033803135, -0.038302124 0.037513345 -0.001623258, -0.043033347 0.037386015 -0.0043286532, -0.043880388 0.03638798 -0.0043287277, -0.03905721 0.038252994 -0.0019928813, -0.037254006 0.038554654 -0.0016231835, -0.043312594 0.037628666 -0.005385384, -0.04416503 0.03662397 -0.0053855032, -0.039734498 0.038916409 -0.0025887638, 0.055375978 -0.010746881 -0.0033830851, -0.037988231 0.039314628 -0.0019929707, 0.055960819 -0.010860115 -0.0043312609, -0.040299937 0.039470315 -0.0033803135, 0.056323722 -0.010930508 -0.0053881705, -0.0386471 0.039996475 -0.0025886744, -0.046152145 0.027281493 -0.001623854, -0.040725604 0.039887264 -0.0043284446, -0.045754567 0.028630108 -0.0017205477, -0.035073385 0.04054825 -0.0016231388, -0.044985428 0.029165655 -0.0016237348, -0.043954343 0.030697554 -0.0016236603, -0.044820711 0.031302646 -0.0019934624, -0.043670386 0.031099975 -0.001623556, -0.039197281 0.040565804 -0.0033801645, -0.040989831 0.040146053 -0.0053852946, -0.035764828 0.041347787 -0.0019927919, -0.043184578 0.032376841 -0.001720354, -0.042348102 0.032878131 -0.0016234964, -0.0040192306 0.057233885 -0.0053841174, -0.003493309 0.057268396 -0.0053842068, -0.0039934218 0.056865156 -0.0043273568, -0.039611116 0.040994212 -0.0043283999, -0.033751965 0.041654855 -0.0016230196, -0.0019985735 0.057243273 -0.0050229728, -0.036385074 0.042064607 -0.0025884062, -0.039867938 0.041260287 -0.0053850561, -0.00099202991 0.057366356 -0.0053842366, 0.00098413229 0.05736661 -0.0053842068, -0.00033336878 0.057373941 -0.0053843558, -0.034417316 0.042475969 -0.0019928366, 0.0013793409 0.057358399 -0.0053842962, 0.00097772479 0.056996763 -0.0043273568, -0.036903083 0.042663619 -0.0033800602, -0.035014063 0.043212608 -0.0025885254, 0.0029105842 0.057204232 -0.0050230622, 0.003880173 0.057243496 -0.0053842664, -0.037292659 0.043114007 -0.0043282211, 0.0059803128 0.057062536 -0.0053842068, 0.0045806468 0.057191923 -0.0053842068, 0.0062424839 0.057034284 -0.0053842366, -0.031605214 0.043306112 -0.0016229004, 0.005941838 0.056694552 -0.004327476, -0.035512522 0.043827727 -0.0033801645, 0.0077982545 0.056744769 -0.0050230622, -0.037534654 0.043393895 -0.0053850263, 0.0087240338 0.056707859 -0.0053842366, -0.032228321 0.044159934 -0.0019927025, 0.010930806 0.056324154 -0.0053844452, 0.0094613731 0.056589559 -0.0053841472, 0.027494505 0.047252506 -0.0019926429, 0.027281508 0.046152368 -0.0016227961, 0.026962951 0.046339124 -0.0016227663, -0.035887629 0.044290587 -0.0043281019, 0.028630123 0.045754746 -0.0017195642, -0.029993072 0.044437945 -0.0016229004, -0.032787204 0.044925705 -0.0025882721, 0.029165477 0.044985458 -0.0016228557, 0.03069748 0.043954343 -0.0016228259, 0.031302571 0.044820815 -0.0019927025, 0.031099916 0.04367052 -0.0016228855, -0.0361204 0.044577867 -0.0053848922, 0.032376766 0.043184772 -0.0017198026, -0.030584246 0.045314088 -0.0019927323, -0.033253938 0.045565128 -0.0033798516, 0.032878011 0.042348057 -0.0016230643, 0.034222364 0.041269317 -0.0016230643, 0.057268143 0.0034937114 -0.0053872913, -0.031114548 0.046099842 -0.0025883168, -0.033605158 0.046046421 -0.0043281019, 0.057243034 0.0019987822 -0.0050261766, -0.02792117 0.045768082 -0.0016227067, 0.057366222 0.00099234283 -0.0053874552, -0.03155756 0.046755955 -0.0033799857, 0.057373792 0.0003336668 -0.0053875148, 0.057366222 -0.00098393857 -0.005387485, 0.057358027 -0.0013792217 -0.0053875297, 0.056996584 -0.00097750127 -0.0043306351, -0.033823028 0.046345159 -0.0053849369, -0.028471544 0.046670601 -0.0019926429, 0.057204053 -0.0029103011 -0.0050265491, 0.057243243 -0.0038797408 -0.0053877532, -0.031890795 0.047249869 -0.0043279678, 0.057062209 -0.005979985 -0.0053877831, 0.057191595 -0.0045803785 -0.0053877383, -0.02896525 0.047479719 -0.0025882423, 0.057034075 -0.0062419772 -0.0053878576, 0.056694403 -0.0059414655 -0.004331097, -0.026005879 0.046882957 -0.0016227216, 0.056744576 -0.0077980161 -0.0050266981, -0.032097578 0.047556177 -0.0053848475, 0.056707516 -0.0087238103 -0.0053879619, -0.029377446 0.048155561 -0.0033798069, 0.056589246 -0.0094609261 -0.0053878725, -0.026518553 0.047807202 -0.001992479, -0.047598705 0.028383002 -0.0024387389, -0.029687718 0.048664257 -0.0043279529, -0.047358528 0.028584957 -0.0023672879, -0.026978344 0.048636213 -0.0025880784, -0.047047853 0.029842094 -0.0026681721, -0.024046376 0.047917679 -0.001622647, -0.045353338 0.030526236 -0.0019934773, -0.029880539 0.048980132 -0.0053847879, -0.027362436 0.049328446 -0.0033797324, -0.046136916 0.030517653 -0.0023670644, -0.045963019 0.03096208 -0.0024386197, -0.045598015 0.031845629 -0.0025891662, -0.024520278 0.048862174 -0.0019925088, -0.04624705 0.032298908 -0.0033807904, -0.045075893 0.032239765 -0.0024386048, -0.027651355 0.049849629 -0.0043277889, -0.044811577 0.032432556 -0.0023671091, -0.024945468 0.049709454 -0.002588138, -0.021820784 0.048971042 -0.0016227365, -0.044405773 0.033647954 -0.0026678741, -0.042638257 0.034216166 -0.0019931793, -0.027830675 0.05017294 -0.0053846538, -0.025300339 0.050417006 -0.0033796281, -0.043432847 0.034256577 -0.0023669004, -0.043231487 0.034674063 -0.0024385303, -0.022250906 0.049936354 -0.0019923002, -0.0255678 0.050949767 -0.0043277889, -0.0039516389 0.056270674 -0.0033793747, -0.0032996535 0.056463525 -0.0035782456, -0.0038961172 0.055481002 -0.0025877357, -0.0029720962 0.056553394 -0.0036803186, -0.020007238 0.049739793 -0.001622498, -0.022636846 0.050802469 -0.0025879145, -0.0016493499 0.056306422 -0.0032829344, -0.02573368 0.05128026 -0.0053844005, -0.020401597 0.050720304 -0.0019924045, 0.00095400214 0.055609539 -0.0025878847, -1.1146069e-05 0.056559861 -0.0035781264, 0.00096768141 0.056400999 -0.0033793151, -0.022959039 0.051525623 -0.0033796877, -0.00050237775 0.056629062 -0.0036801398, -0.00050494075 0.056918442 -0.0041604638, -0.020755291 0.051599681 -0.0025879294, -0.00066697598 0.057103872 -0.0045547187, -0.023201525 0.052069768 -0.004327625, -4.0233135e-06 0.057005122 -0.0043274164, -0.017469734 0.050686598 -0.0016224086, -0.00011330843 0.057154506 -0.0046700835, -0.021050781 0.052334428 -0.0033795238, 0.00032317638 0.057004303 -0.0043273866, -0.023351982 0.052407578 -0.0053845048, 0.0016050339 0.056537047 -0.0035781264, -0.017813981 0.051685616 -0.00199233, 0.001924932 0.056598827 -0.0036803186, -0.021273032 0.052886963 -0.0043274015, 0.0032356381 0.056237429 -0.003282845, -0.015831321 0.051221937 -0.0016224682, -0.018123016 0.052582085 -0.0025878698, 0.0057969987 0.05531469 -0.0025877655, 0.0048897266 0.056348041 -0.003578186, 0.0058796704 0.056101993 -0.0033792257, -0.021411031 0.053230122 -0.0053843856, 0.0044142902 0.056749269 -0.0041605234, 0.0043917894 0.056460753 -0.0036802888, -0.01614356 0.052231625 -0.0019923002, 0.0042397678 0.056950137 -0.0045546591, -0.01838091 0.0533306 -0.0033795387, 0.0048992336 0.056794181 -0.0043273568, -0.016423404 0.053137317 -0.0025879294, 0.0047957599 0.056953162 -0.0046700835, -0.018575102 0.05389376 -0.0043274611, 0.0052470267 0.056763053 -0.0043275654, -0.012985557 0.052016258 -0.0016224682, 0.0064979494 0.056185275 -0.003578186, -0.016657233 0.053894058 -0.0033795536, 0.0068074167 0.056220666 -0.0036803186, -0.018695548 0.05424358 -0.0053844154, -0.013241604 0.053041726 -0.0019921958, 0.0080962777 0.055745423 -0.003282845, -0.016833037 0.054463059 -0.0043275356, 0.010596037 0.054598927 -0.0025877059, 0.0097537041 0.055712461 -0.003578335, 0.010746807 0.055376232 -0.0033796132, -0.011547446 0.05235447 -0.0016225874, -0.013471097 0.053961381 -0.0025879145, 0.0092532933 0.05587028 -0.0036803782, 0.00930053 0.056155801 -0.0041605234, 0.0091152787 0.056375384 -0.0045548677, -0.016942188 0.054816321 -0.0053844899, -0.011774912 0.05338636 -0.001992166, 0.009765923 0.056162491 -0.0043274164, 0.0096694529 0.056330889 -0.0046703219, -0.013662919 0.054729655 -0.0033794641, 0.01013118 0.056097656 -0.0043274462, 0.010860234 0.055961087 -0.0043275356, -0.011979192 0.054312408 -0.0025878847, 0.027971163 0.048072129 -0.0025881231, 0.028382882 0.047598898 -0.0024378002, 0.028369352 0.048756674 -0.0033798814, 0.028584778 0.047358721 -0.0023663044, -0.013807252 0.055307701 -0.0043275803, -0.012149662 0.055085242 -0.0033794791, -0.0084026456 0.052950025 -0.0016223192, 0.02984193 0.047048062 -0.0026671886, -0.013896793 0.055666521 -0.0053843707, 0.030525923 0.045353383 -0.0019927621, 0.030517608 0.046136916 -0.0023661554, -0.012277991 0.055667087 -0.0043273717, 0.03096199 0.045963049 -0.0024376512, 0.031845436 0.04559809 -0.0025882125, 0.032298803 0.046247214 -0.0033800602, -0.0085683316 0.053994074 -0.0019921362, 0.03223975 0.045076028 -0.0024379194, -0.0071845204 0.053129047 -0.0016223192, 0.032432348 0.044811651 -0.0023663342, -0.012357682 0.056028217 -0.0053843707, 0.033647805 0.044405803 -0.0026672781, -0.0087168664 0.054930359 -0.0025878251, -0.0073261708 0.054176405 -0.0019921064, 0.034215957 0.042638436 -0.0019928515, 0.034896806 0.042082816 -0.0019928813, -0.0088410378 0.055712253 -0.0033795834, 0.034256399 0.043433025 -0.0023664832, 0.03467384 0.043231592 -0.0024379194, -0.0074532777 0.055115953 -0.0025877655, 0.035502002 0.042812705 -0.0025885105, 0.036007404 0.043422073 -0.00338009, -0.0089344978 0.056300819 -0.0043275356, 0.056463405 0.0032999516 -0.0035810471, 0.056553319 0.002972275 -0.0036831796, -0.0075594634 0.055900484 -0.0033793151, -0.0037557185 0.053480893 -0.0016222894, 0.056306079 0.0016497076 -0.0032859296, -0.0089924484 0.056665927 -0.0053842515, -0.0076392144 0.056490898 -0.0043273568, 0.056559727 1.1309981e-05 -0.0035814047, 0.056400806 -0.00096733868 -0.0033825785, -0.0038298965 0.05453527 -0.0019920468, 0.056918383 0.00050516427 -0.0041635931, 0.056629032 0.00050261617 -0.0036833882, -0.007688731 0.056857526 -0.0053842366, 0.057103589 0.00066721439 -0.0045578182, 0.057004958 4.1425228e-06 -0.0043307096, 0.057154328 0.00011369586 -0.0046734363, 0.057004035 -0.00032313168 -0.0043306798, 0.056537107 -0.0016049743 -0.0035814196, 0.05659847 -0.0019246787 -0.0036835968, 0.056237295 -0.0032353997 -0.0032863021, 0.056347921 -0.0048895925 -0.0035815388, 0.056101918 -0.0058793724 -0.0033829808, 0.056749314 -0.0044140965 -0.0041639656, 0.056460544 -0.0043916404 -0.0036835968, 0.056949884 -0.0042396784 -0.004558146, 0.056793958 -0.0048989654 -0.0043309033, 0.056952849 -0.0047955662 -0.0046735704, 0.056762829 -0.0052465647 -0.0043308437, 0.056185111 -0.0064976066 -0.0035817921, 0.056220546 -0.006807223 -0.0036837757, 0.055745363 -0.0080959499 -0.0032865256, 0.055712342 -0.0097534359 -0.0035818368, 0.056155652 -0.009300217 -0.0041641742, 0.055869997 -0.0092529953 -0.0036839694, 0.05637531 -0.009115085 -0.0045583248, 0.056162074 -0.0097657442 -0.004331246, 0.056330636 -0.0096692592 -0.0046739727, 0.056097314 -0.010130957 -0.0043311864, -0.048237517 0.029317468 -0.0034300387, 0.010214001 0.052630767 -0.001622349, 0.014762312 0.05154027 -0.001622498, -0.047780156 0.030443579 -0.0037161708, 0.010415345 0.05366835 -0.0019920766, 0.015053287 0.052556306 -0.0019922554, -0.046984687 0.031285688 -0.0034297109, -0.046735451 0.032639802 -0.0043287426, 0.015314385 0.053467602 -0.0025879145, -0.045643136 0.03321217 -0.0034296513, 0.015532151 0.054228827 -0.0033795834, -0.045097098 0.034292728 -0.0037159771, 0.015696332 0.054801583 -0.004327625, -0.044231787 0.035070226 -0.0034296811, 0.018968061 0.050145105 -0.0016224384, -0.0027605891 0.05550006 -0.0025491416, 0.015798286 0.05515711 -0.0053845942, 0.019341797 0.051133811 -0.0019923151, -0.0015152991 0.055261597 -0.0023424625, -0.00033691525 0.055567637 -0.0025493503, 0.019677222 0.052020118 -0.0025880039, 0.0020728111 0.055530027 -0.0025492311, 0.00093787909 0.054661334 -0.0019921958, 0.019957274 0.052761003 -0.0033795238, 0.02016817 0.053318053 -0.0043275952, 0.0032974482 0.055183798 -0.0023424625, 0.02304408 0.048407644 -0.0016225576, 0.0044931769 0.055386782 -0.0025492609, 0.020298958 0.053664103 -0.0053843856, 0.0068906844 0.055139706 -0.0025491416, 0.0056982636 0.054371834 -0.0019920766, 0.02349849 0.049361795 -0.0019923151, 0.023905918 0.050217852 -0.0025880933, 0.0080851316 0.054687977 -0.0023424327, 0.0092893243 0.054786786 -0.0025492013, 0.024246186 0.050932601 -0.0033796728, 0.029317245 0.048237607 -0.0034289062, 0.02866888 0.0492713 -0.0043278933, 0.024502173 0.051470712 -0.0043276548, 0.030443311 0.047780424 -0.0037152171, 0.024661168 0.051804557 -0.0053843856, 0.031285629 0.046984777 -0.0034290254, 0.028854936 0.04959102 -0.0053847432, 0.035161048 0.040472448 -0.0016230941, -0.049149022 0.029489145 -0.0051576048, -0.048921689 0.029801741 -0.0050445944, 0.035854146 0.041270494 -0.0019928813, -0.048390895 0.030879006 -0.0055210888, -0.0476484 0.031797916 -0.0050442815, 0.036475882 0.041986108 -0.0025885701, -0.047449857 0.032152027 -0.0051573515, -0.047038615 0.032851741 -0.005385682, -0.04654403 0.033449829 -0.0051573366, 0.036995128 0.042583704 -0.0033801198, -0.04629074 0.03374359 -0.0050443113, 0.037513375 0.038302287 -0.0016233027, -0.045673594 0.034772053 -0.0055209249, -0.044856668 0.035627812 -0.0050442964, 0.037385643 0.043033645 -0.0043281615, -0.044630677 0.035963237 -0.0051572323, 0.038252875 0.039057314 -0.0019929409, -0.0030069947 0.053756878 -0.0016800165, 0.038554624 0.037254095 -0.0016233325, -0.0026299357 0.053889766 -0.0017130971, 0.037628189 0.043312728 -0.0053851604, -0.0014324784 0.05345808 -0.0015933514, 0.03891623 0.039734662 -0.0025886893, -0.00027683377 0.05395335 -0.0017130077, 0.039314643 0.037988588 -0.0019930899, 0.00012385845 0.053840786 -0.0016801059, 0.00091972947 0.053604618 -0.001622349, 0.039470121 0.040300369 -0.0033802986, 0.00030294061 0.054640561 -0.0019786358, 0.039996356 0.03864722 -0.0025886893, 0.0016865134 0.053814605 -0.0016801059, 0.0020723045 0.053914249 -0.0017130375, 0.03988719 0.040725797 -0.0043283105, 0.040548325 0.035073653 -0.0016234219, 0.0032291412 0.05337964 -0.0015934706, 0.040565789 0.0391974 -0.0033803284, 0.0044220388 0.053772524 -0.0017130375, 0.0048128068 0.05362545 -0.0016801357, 0.0055882633 0.053320691 -0.0016221702, 0.040145695 0.040990114 -0.0053852499, 0.0050572157 0.054406971 -0.0019787252, 0.041347682 0.035764992 -0.0019932389, 0.0063674152 0.053463161 -0.0016802251, 0.0067589283 0.05352895 -0.0017130971, 0.0078661442 0.052895397 -0.0015935302, 0.042064577 0.036385313 -0.0025888383, 0.0090872049 0.053183317 -0.0017130077, 0.0094650388 0.053002462 -0.0016802847, 0.0097728372 0.053760409 -0.0019786656, 0.029488996 0.04914923 -0.0051563382, 0.029801443 0.048922002 -0.0050434768, 0.030878723 0.048391253 -0.0055202246, 0.031797782 0.047648534 -0.0050435066, 0.032151833 0.04745011 -0.0051566064, 0.035962805 0.044630513 0.005161494, 0.036623761 0.044164553 0.0053897798, 0.042663276 0.03690289 0.0033845603, 0.043212503 0.035013899 0.0025927126, 0.043827698 0.035512194 0.0033844709, 0.035627589 0.044856369 0.0050485432, 0.034771964 0.045673415 0.0055253506, 0.053481072 0.0037556738 0.0016255975, 0.053756848 0.0030069798 0.0016833544, 0.054535165 0.003829658 0.0019953251, 0.04054828 0.035073459 0.0016272664, 0.038554534 0.037253886 0.001627475, 0.039314643 0.037988201 0.0019972622, 0.041347623 0.035764784 0.0019971132, 0.044290468 0.035887271 0.0043325126, 0.046046227 0.033604845 0.004332453, 0.044577628 0.036120072 0.0053893924, 0.055499882 0.0027602911 0.0025523901, 0.053889796 0.0026299059 0.0017161071, 0.055261463 0.001515165 0.002345711, 0.046344891 0.033822715 0.0053892434, 0.053457931 0.0014325231 0.0015964508, 0.042064741 0.036384925 0.0025927126, 0.042476013 0.034417152 0.001997143, 0.055609375 -0.00095431507 0.0025907457, 0.054640502 -0.00030308962 0.0019817054, 0.054661363 -0.00093790889 0.0019952059, 0.053604767 -0.00091972947 0.0016251206, 0.055567384 0.00033687055 0.0025521219, 0.047556102 0.03209734 0.0053892136, 0.05395329 0.00027653575 0.0017158687, 0.045565039 0.033253744 0.0033842921, 0.053840697 -0.00012379885 0.0016831458, 0.041654781 0.033751935 0.0016272962, 0.053814486 -0.0016866922 0.0016829669, 0.04724966 0.031890661 0.0043324232, 0.05391413 -0.0020723343 0.0017157793, 0.055529892 -0.0020731539 0.0025519133, 0.044925615 0.03278695 0.0025927126, 0.055183828 -0.0032975376 0.0023452938, 0.0533797 -0.0032290965 0.0015959442, 0.055314556 -0.0057971627 0.0025904775, 0.054406777 -0.0050570965 0.0019814074, 0.054371685 -0.0056983382 0.0019947737, 0.046756029 0.031557441 0.0033843517, 0.053320736 -0.0055882484 0.0016250163, 0.055386513 -0.0044934452 0.0025519729, 0.044159845 0.032228217 0.0019968152, 0.053772464 -0.0044222772 0.0017158389, 0.053625435 -0.0048127621 0.0016828775, 0.048979774 0.029880092 0.0053890646, 0.053462908 -0.0063673705 0.0016827285, 0.046099767 0.031114489 0.0025924146, 0.05352886 -0.0067587793 0.0017155111, 0.043306097 0.031605214 0.0016269982, 0.055139586 -0.006890893 0.0025519431, 0.054687843 -0.0080851763 0.0023451149, 0.052895442 -0.0078661293 0.0015958548, 0.048664123 0.029687569 0.0043323338, 0.054598957 -0.010596275 0.002590239, 0.05376038 -0.0097730905 0.0019810796, 0.053668082 -0.01041545 0.0019944757, 0.054786637 -0.0092895776 0.0025517493, 0.04531388 0.030584201 0.0019967556, 0.053183123 -0.009087339 0.0017153919, 0.048155531 0.029377282 0.0033841431, 0.052630633 -0.010214135 0.0016248077, 0.053002343 -0.009465158 0.0016826093, 0.050172672 0.027830541 0.0053890347, 0.044438064 0.029992819 0.0016270578, 0.0474796 0.02896516 0.0025922954, 0.049849316 0.027651221 0.0043319762, 0.046670228 0.028471336 0.001996696, 0.049328625 0.027362078 0.0033841431, 0.051280037 0.025733307 0.0053889155, 0.045768112 0.027921081 0.0016268492, 0.048636153 0.026978269 0.002592355, 0.050949603 0.025567487 0.0043320656, 0.047807112 0.026518449 0.0019966662, 0.050417036 0.025300324 0.0033840239, 0.052407369 0.023351714 0.0053885579, 0.046882883 0.026005805 0.0016269088, 0.049709484 0.024945289 0.0025921762, 0.052069589 0.023201317 0.0043319464, 0.0488621 0.024520069 0.0019964576, 0.053229839 0.021410689 0.0053886175, 0.051525608 0.022958845 0.0033837557, 0.04791759 0.024046063 0.00162673, 0.052886903 0.021272793 0.0043317378, 0.050802305 0.022636622 0.0025919676, 0.052334189 0.021050602 0.0033836663, 0.049936399 0.022250935 0.0019963086, 0.054243252 0.018695205 0.0053884089, 0.051599637 0.020755097 0.0025919378, 0.048971176 0.02182062 0.0016265213, 0.053893685 0.01857473 0.0043316483, 0.050720021 0.020401508 0.0019962788, 0.054816142 0.016941935 0.0053882301, 0.053330421 0.018380702 0.0033835769, 0.049739674 0.020007044 0.0016264617, 0.054462805 0.016832933 0.0043314993, 0.052582055 0.018122777 0.0025918484, 0.053893745 0.01665701 0.0033834577, 0.051685676 0.017813891 0.0019961298, 0.055666342 0.01389648 0.0053881407, 0.053137258 0.016423211 0.0025916398, 0.050686613 0.017469555 0.0016263723, 0.055307508 0.013806969 0.0043314099, 0.05223164 0.016143218 0.0019959807, 0.056028038 0.012357309 0.0053880811, 0.054729596 0.013662696 0.003383249, 0.051221997 0.015831292 0.0016262233, 0.055666953 0.012277782 0.0043312311, 0.053961396 0.013470992 0.0025915205, -0.053663641 0.020298645 0.0053884685, 0.055085286 0.012149528 0.0033831, -0.053318039 0.020168096 0.0043315887, 0.053041562 0.013241529 0.0019957423, 0.054312095 0.011978924 0.0025916398, -0.05276072 0.01995714 0.0033835918, 0.056665629 0.0089920163 0.0053878129, -0.052020207 0.019677192 0.0025919378, 0.052016273 0.012985438 0.0016260147, -0.051133484 0.019341528 0.0019961596, 0.05338636 0.011774793 0.0019957423, -0.05180414 0.024660945 0.0053887218, 0.056300431 0.0089342743 0.0043311119, -0.050145105 0.018967822 0.001626417, 0.056857184 0.0076882839 0.0053877831, 0.052354336 0.011547163 0.0016259253, -0.05147019 0.02450183 0.0043319464, 0.055712208 0.0088407844 0.003382951, -0.050932437 0.024245903 0.0033839941, -0.050217524 0.023905635 0.0025919974, 0.056490645 0.0076390058 0.0043310821, 0.054930151 0.0087167472 0.0025912523, -0.049361646 0.023498476 0.0019964725, -0.049590692 0.028854519 0.0053888857, 0.05590035 0.0075590163 0.0033829212, 0.053993836 0.0085681826 0.0019956231, -0.048407435 0.023044124 0.0016266108, 0.055115908 0.0074530542 0.0025911629, -0.049271196 0.028668642 0.0043322444, 0.057233751 0.0040189326 0.0053875744, -0.048756287 0.028369024 0.0033841282, 0.052950159 0.0084026009 0.0016257763, -0.048071951 0.027970806 0.0025923699, 0.054176465 0.0073258877 0.0019954145, -0.047252625 0.027494401 0.0019966215, 0.056864887 0.0039931983 0.0043309331, 0.053129047 0.007184431 0.0016256571, -0.046339154 0.026962698 0.0016268194, 0.056270614 0.0039514601 0.0033827424, 0.055480808 0.0038960874 0.0025908947, -0.043312475 0.037627861 0.0053895265, -0.044165239 0.036623523 0.005389452, -0.043033332 0.037385538 0.0043326318, -0.043880343 0.036387399 0.0043325424, -0.042583585 0.036994919 0.0033844858, -0.043421835 0.036007196 0.0033844709, -0.041985959 0.036475733 0.0025928766, -0.042812377 0.035501912 0.0025927871, -0.04098992 0.040145501 0.0053894222, 0.056323916 -0.010931224 0.0053867847, -0.042082742 0.034896776 0.0019972622, -0.041270182 0.035853982 0.0019970685, -0.040725663 0.039886758 0.0043327957, -0.039868131 0.041259646 0.0053897053, 0.055960804 -0.010860562 0.004330039, -0.041269213 0.034222245 0.0016273707, -0.040472433 0.035160854 0.0016273409, -0.040299982 0.039470047 0.0033846796, 0.055376053 -0.01074709 0.0033819973, -0.039611042 0.04099384 0.0043327212, -0.039734542 0.038916066 0.0025930405, -0.03919737 0.040565535 0.0033847392, -0.039057076 0.038252771 0.0019972026, -0.046152309 0.027281404 0.0016268492, -0.037534624 0.04339321 0.0053897202, -0.045754522 0.028629988 0.0017237961, -0.0386471 0.039996102 0.0025931001, -0.038302243 0.03751339 0.0016274154, -0.044985443 0.029165328 0.0016270727, -0.043954283 0.030697227 0.0016271621, -0.043670371 0.031099707 0.0016271472, -0.037292734 0.043113753 0.0043330044, -0.044820622 0.031302527 0.0019968748, -0.037988275 0.039314449 0.0019974411, -0.043184623 0.032376766 0.0017238557, -0.042348087 0.032877982 0.0016272366, -0.036120385 0.044577494 0.0053899437, -0.00401932 0.057233319 0.0053906441, -0.0034933984 0.057267919 0.0053905249, -0.0039934516 0.056864589 0.0043338835, -0.036903039 0.042663231 0.0033848435, -0.037253991 0.038554534 0.0016273409, -0.035887584 0.0442902 0.0043330193, -0.0019985139 0.057242796 0.0050293505, -0.0009920001 0.057365835 0.0053906441, -0.036385074 0.042064264 0.0025932491, -0.00033336878 0.05737339 0.0053906739, 0.00098437071 0.057365716 0.0053905547, -0.035512492 0.04382734 0.0033849776, 0.0013795197 0.057357609 0.0053905547, 0.0009778738 0.056996197 0.0043337047, -0.035764858 0.041347474 0.0019975156, 0.0029105842 0.057203636 0.0050293505, -0.033822909 0.046344653 0.0053898841, 0.0038799047 0.057243019 0.0053906143, -0.035014138 0.043212146 0.002593115, 0.004580766 0.057191223 0.0053906441, 0.0059802234 0.057061762 0.0053906441, -0.035073593 0.04054825 0.0016276091, 0.0059416294 0.056694135 0.0043338537, 0.0062422752 0.057033777 0.0053905845, -0.033604994 0.046045959 0.004333213, 0.0077982843 0.056744188 0.0050293505, -0.034417212 0.042475641 0.0019975007, 0.0087241232 0.056707039 0.0053906143, -0.032097638 0.047555715 0.0053899735, 0.0094613135 0.056588754 0.0053904355, 0.010930717 0.056323528 0.0053904951, -0.033253983 0.045564815 0.0033849776, 0.027281463 0.046152249 0.0016278923, 0.026963025 0.046339035 0.0016279817, 0.027494475 0.047252476 0.0019978881, -0.033751905 0.041654736 0.0016276836, 0.028630137 0.045754567 0.0017246306, 0.029165417 0.044985443 0.0016278923, -0.03189075 0.047249451 0.0043331981, 0.030697465 0.043954208 0.0016277432, -0.032787144 0.044925347 0.0025933385, 0.03109993 0.043670341 0.0016275346, 0.031302631 0.044820666 0.0019976199, 0.032376826 0.043184459 0.001724422, -0.031557485 0.046755642 0.0033853352, 0.032878175 0.042347714 0.0016277134, -0.032228231 0.044159606 0.0019976646, 0.034222394 0.041269034 0.0016275644, 0.057268322 0.0034931302 0.0053876042, -0.029880449 0.048979506 0.0053901523, -0.031114593 0.046099499 0.0025934577, 0.057243094 0.0019982606 0.0050261915, -0.031605363 0.043306038 0.001627773, 0.057366118 0.00099189579 0.005387336, 0.057373807 0.00033298135 0.0053873956, -0.029687762 0.04866375 0.0043332279, 0.057366282 -0.00098453462 0.0053873658, 0.056996405 -0.00097800791 0.0043305159, 0.057358071 -0.0013796091 0.0053872466, -0.030584365 0.04531385 0.0019976646, -0.029377535 0.048155382 0.0033853352, 0.057203963 -0.0029108971 0.0050258934, -0.02783066 0.050172463 0.0053901225, 0.057243451 -0.0038803071 0.0053871274, -0.029993102 0.044437811 0.0016276091, 0.057191581 -0.0045812279 0.005387038, 0.057062089 -0.0059805214 0.0053869933, 0.057034075 -0.0062425286 0.0053869933, -0.028965235 0.047479406 0.0025934577, 0.056694314 -0.0059418082 0.0043302625, 0.056744605 -0.0077986568 0.0050257444, -0.027651444 0.049848959 0.0043334812, 0.056707591 -0.0087244064 0.0053868592, -0.028471529 0.046670124 0.0019976646, 0.056589246 -0.0094617009 0.0053867996, -0.027362511 0.049328193 0.0033853054, -0.047598705 0.028382748 0.0024418086, -0.047358543 0.028584778 0.0023704767, -0.02573368 0.051279679 0.0053903311, -0.027921066 0.045767918 0.0016278774, -0.026978463 0.048635811 0.0025935918, -0.047047839 0.029841647 0.00267151, -0.025567561 0.050949112 0.0043334663, -0.046136811 0.030517355 0.0023705214, -0.026518524 0.047806799 0.0019977987, -0.045597985 0.031845152 0.0025923848, -0.045962974 0.030961677 0.0024418682, -0.046246991 0.032298356 0.0033843815, -0.045353308 0.030525953 0.0019968897, -0.025300592 0.050416633 0.0033853352, -0.045075879 0.032239497 0.0024419874, -0.044811457 0.032432154 0.0023706853, -0.023351952 0.052407056 0.0053903461, -0.026005954 0.046882838 0.0016279221, -0.024945602 0.049709201 0.002593562, -0.044405684 0.033647463 0.0026717186, -0.023201436 0.052069277 0.0043337196, -0.043432951 0.034256384 0.0023707002, -0.043231472 0.034673631 0.0024422258, -0.024520278 0.04886198 0.001997903, -0.042638332 0.034215853 0.0019970983, -0.02141121 0.053229615 0.0053904355, -0.0039517581 0.056270257 0.0033856928, -0.0032996535 0.056463048 0.0035843551, -0.022959098 0.05152522 0.0033853203, -0.0038961768 0.055480585 0.0025940239, -0.0029720962 0.056552827 0.0036865473, -0.024046272 0.047917441 0.0016281009, -0.00066694617 0.057103217 0.0045610368, -0.021272972 0.05288659 0.0043336302, -0.02263689 0.050802156 0.0025937259, -0.0016495287 0.05630593 0.0032891333, -0.00011327863 0.05715403 0.0046764016, -0.021050885 0.052333996 0.0033854991, -0.00050500035 0.056918055 0.0041669309, -3.7848949e-06 0.057004616 0.0043338239, -0.022250816 0.04993622 0.0019978583, -0.00050246716 0.056628585 0.0036866665, -0.018695489 0.054242924 0.0053904355, 0.00032320619 0.057003751 0.0043337643, 0.00096774101 0.056400552 0.0033854246, -0.020755351 0.051599398 0.0025937259, -1.1205673e-05 0.056559563 0.0035842657, 0.00095403194 0.055609122 0.0025938451, 0.0016050637 0.056536749 0.0035844147, -0.021820769 0.048970863 0.0016280264, -0.018574953 0.053893328 0.0043336749, 0.0019248128 0.056598186 0.0036865175, -0.020401612 0.050719872 0.0019980967, 0.0042398572 0.056949601 0.0045610964, 0.0047958791 0.05695267 0.0046764612, -0.016942173 0.054815874 0.0053904355, -0.018381 0.053330243 0.0033854544, 0.0032356381 0.056237057 0.0032892525, -0.020007074 0.049739376 0.0016281009, -0.016833082 0.054462597 0.0043335557, 0.004414171 0.056749046 0.0041667819, 0.004899174 0.056793809 0.0043338835, -0.018122941 0.052581772 0.0025937855, 0.0043919086 0.056460366 0.0036864877, 0.0052469671 0.056762516 0.0043336749, 0.0058796108 0.056101531 0.003385812, -0.016657189 0.053893507 0.003385514, 0.0048897564 0.056347743 0.0035843849, 0.0057972372 0.055314347 0.0025939047, -0.017814025 0.051685497 0.0019979775, 0.0064978898 0.056184918 0.0035844147, -0.013896778 0.055666015 0.0053905249, 0.0068075657 0.056220308 0.0036865771, 0.0091153979 0.056374907 0.0045608878, -0.01642327 0.053137034 0.0025937557, -0.017469525 0.05068621 0.0016282201, 0.0096695423 0.0563301 0.0046765208, -0.013807163 0.055307224 0.0043336153, 0.0080961883 0.055745199 0.0032892823, -0.016143233 0.052231342 0.0019979775, 0.0093004405 0.056155428 0.0041668117, -0.012357712 0.05602774 0.0053905249, 0.0097659528 0.056161836 0.0043336749, 0.0092531443 0.055869937 0.0036864281, -0.013662994 0.054729357 0.003385514, 0.01013127 0.056097135 0.0043335855, 0.010860294 0.055960461 0.0043336451, 0.010746807 0.05537577 0.0033857226, -0.015831321 0.051221848 0.0016281605, 0.0097535551 0.055712208 0.0035844147, 0.010595948 0.05459851 0.0025939941, -0.012278095 0.055666625 0.0043337345, 0.028383017 0.047598556 0.0024428964, 0.027971193 0.048071846 0.0025935173, -0.013471186 0.053961053 0.0025940239, 0.028369352 0.048756287 0.0033852756, 0.028584793 0.047358483 0.0023714602, -0.012149796 0.055084914 0.0033856034, 0.029841989 0.047047839 0.0026724637, -0.013241634 0.053041384 0.0019980669, 0.030517504 0.046136782 0.0023714006, -0.011979267 0.054311946 0.0025939047, 0.032298595 0.046246827 0.0033851862, 0.03096199 0.045962766 0.0024426877, 0.031845436 0.045597717 0.0025932789, -0.0089922845 0.056665257 0.0053906739, 0.030525967 0.04535304 0.0019976199, -0.012985423 0.052016139 0.0016282201, 0.032239765 0.045075819 0.0024425983, 0.032432288 0.044811323 0.0023712814, -0.011774942 0.053386167 0.0019980371, -0.0089343488 0.056300029 0.0043337345, 0.033647761 0.04440558 0.0026723146, -0.0076886117 0.056856737 0.0053906441, 0.034256473 0.043432847 0.0023714006, -0.011547372 0.052354231 0.0016281903, -0.0088409185 0.05571188 0.0033856034, 0.036007494 0.043421715 0.003384918, 0.034673914 0.043231368 0.0024426877, 0.035502031 0.042812228 0.0025931001, 0.034896851 0.042082652 0.0019974113, 0.034215972 0.042638093 0.0019975901, -0.0076391101 0.056490436 0.0043336153, 0.056463346 0.0032996237 0.0035813451, -0.0087169111 0.054930061 0.0025939643, 0.056553096 0.0029719025 0.0036835074, 0.057103619 0.00066649914 0.0045578182, -0.0075594783 0.055900246 0.0033856332, -0.0085682869 0.053993821 0.0019982755, 0.056306049 0.0016493946 0.0032861531, -0.0074533224 0.055115566 0.0025939047, 0.057154268 0.00011312962 0.004673332, 0.056918323 0.00050473213 0.0041635334, 0.057004943 3.7103891e-06 0.0043305755, -0.0084026903 0.052949876 0.0016283393, 0.056628913 0.00050234795 0.0036834776, 0.057003945 -0.00032354891 0.0043304563, -0.0073261857 0.054176301 0.0019981265, 0.056400865 -0.00096786022 0.0033823848, 0.056559727 1.0952353e-05 0.0035810471, 0.056536958 -0.0016053468 0.0035812259, -0.0071844608 0.053129002 0.0016281605, 0.05659844 -0.0019249767 0.0036832094, 0.056949839 -0.0042401254 0.00455755, 0.056952938 -0.0047960281 0.0046730936, -0.0038297772 0.054535031 0.0019983053, 0.056237251 -0.0032358021 0.0032858849, 0.056749046 -0.0044144541 0.0041635036, -0.0037558377 0.053480744 0.0016283691, 0.056794047 -0.0048993975 0.0043303967, 0.056460723 -0.004392013 0.0036832094, 0.056762859 -0.0052470863 0.0043302178, 0.056101903 -0.0058798045 0.003382057, 0.056348026 -0.0048899949 0.0035809577, 0.056185216 -0.0064979941 0.0035810173, 0.056220591 -0.0068075508 0.0036830753, 0.056375265 -0.0091154873 0.0045572966, 0.056330487 -0.0096696764 0.0046726167, 0.055745468 -0.0080965161 0.0032856017, 0.056155607 -0.0093006939 0.004163146, 0.056162119 -0.0097661912 0.0043299943, 0.055870101 -0.0092533827 0.0036828071, 0.056097373 -0.010131314 0.0043300241, 0.055712417 -0.0097539276 0.0035807192, -0.048237547 0.029316962 0.0034332424, -0.047780231 0.030442983 0.0037196428, -0.046984732 0.03128542 0.0034333169, -0.046735376 0.032639459 0.0043324381, -0.045643121 0.033211797 0.003433466, -0.045097008 0.034292251 0.0037197024, 0.015798211 0.055156454 0.0053905547, -0.044231802 0.035069644 0.0034335256, -0.0027605295 0.055499688 0.0025554001, 0.015696317 0.054800987 0.0043336451, -0.0015153289 0.055261374 0.0023486018, 0.015532374 0.05422838 0.0033855438, -0.00033697486 0.055567294 0.0025554299, 0.015314311 0.053467199 0.0025939047, 0.00093787909 0.054661036 0.0019982159, 0.0020729303 0.055529639 0.0025553405, 0.010415435 0.053668082 0.0019981563, 0.015053242 0.052556038 0.0019980669, 0.0032973886 0.055183575 0.0023487806, 0.020298958 0.053663418 0.0053905249, 0.0044932961 0.05538626 0.0025553107, 0.014762282 0.051540136 0.0016281605, 0.01021415 0.052630797 0.0016281605, 0.020168155 0.053317577 0.0043337345, 0.0056982338 0.054371521 0.0019979775, 0.0068908036 0.055139512 0.0025554001, 0.019957304 0.052760512 0.0033854842, 0.0080852211 0.054687724 0.002348572, 0.019677326 0.052020028 0.0025936365, 0.0092893839 0.054786354 0.0025553107, 0.029317021 0.048237413 0.0034340322, 0.028668895 0.049270838 0.0043334067, 0.019341841 0.051133379 0.0019978583, 0.024661168 0.051803842 0.0053902268, 0.030443281 0.047779903 0.0037205219, 0.018967941 0.05014506 0.0016280711, 0.031285509 0.046984568 0.0034340918, 0.024502173 0.051470205 0.0043335259, 0.032639831 0.046735138 0.0043331981, 0.03321217 0.045642957 0.0034341514, 0.024246216 0.050932184 0.0033853948, 0.023906007 0.050217494 0.0025936365, 0.034292623 0.045096934 0.0037202835, 0.035069853 0.044231698 0.0034340024, 0.036387742 0.043880269 0.0043331087, 0.023498431 0.049361467 0.0019980371, 0.028854951 0.049590409 0.0053901374, 0.02304408 0.048407406 0.0016280115, -0.049149036 0.029488683 0.0051607788, -0.048921779 0.029801175 0.0050476789, -0.04839094 0.03087844 0.0055246502, -0.047648251 0.031797275 0.0050479174, -0.047449976 0.032151386 0.0051608831, -0.04703854 0.032851338 0.0053893179, -0.046544135 0.033449143 0.0051609278, 0.037628263 0.043312028 0.0053898096, -0.046290681 0.033743143 0.0050479323, -0.045673653 0.034771591 0.0055247098, 0.037385821 0.043033063 0.0043330491, -0.044856727 0.035627306 0.0050481111, -0.044630677 0.035962507 0.0051610917, 0.036994919 0.042583451 0.0033849776, -0.0030070245 0.053756669 0.0016861558, -0.0026299655 0.053889692 0.0017189384, 0.036475793 0.041985765 0.0025930703, -0.0014324486 0.053457886 0.0015993714, 0.0401458 0.040989518 0.0053895414, 0.00030303001 0.054640457 0.0019848049, 0.00091964006 0.053604603 0.0016284883, -0.00027680397 0.053953156 0.0017190576, 0.035854101 0.041270196 0.0019973814, 0.00012379885 0.053840652 0.0016860068, 0.039887056 0.040725514 0.0043328106, 0.0016864836 0.053814337 0.001686126, 0.041260049 0.039867729 0.0053896904, 0.0020723641 0.053913951 0.0017190278, 0.035161018 0.040472388 0.001627475, 0.0032289922 0.05337958 0.0015995502, 0.03947027 0.040300101 0.0033847988, 0.0050571263 0.054406747 0.0019847155, 0.0055881143 0.053320527 0.0016283989, 0.040994078 0.039610982 0.0043327808, 0.0044220686 0.053772315 0.0017189682, 0.038916364 0.039734259 0.0025930703, 0.0048127472 0.053625062 0.0016860366, 0.006367445 0.053462908 0.0016860068, 0.040565759 0.039197162 0.0033846498, 0.038252994 0.039057001 0.0019974113, 0.0067588091 0.05352883 0.0017190874, 0.043393523 0.03753452 0.0053893626, 0.0078662336 0.052895412 0.0015992224, 0.0097729564 0.053760067 0.0019846857, 0.039996341 0.038646892 0.0025928319, 0.0090873539 0.053183079 0.0017189384, 0.037513435 0.038302049 0.001627475, 0.0094651282 0.053002179 0.0016860664, 0.043113843 0.037292585 0.0043325722, 0.029488996 0.049148694 0.0051618218, 0.029801428 0.048921347 0.005048871, 0.030878663 0.048390776 0.0055255592, 0.031797692 0.047647893 0.0050487816, 0.032151788 0.047449484 0.0051618814, 0.032851636 0.047038168 0.005389899, 0.033449516 0.046543896 0.0051618218, 0.033743456 0.046290383 0.0050487816, -0.0025648177 -0.074083507 0.045608491, -0.034961373 -0.066798195 0.047957703, -0.036395624 -0.066477448 0.048326537, -0.035454243 -0.067433581 0.048627347, 0.002741605 -0.077842116 0.049370438, -0.034901574 -0.067606345 0.048555955, -0.0026948899 -0.077843592 0.049370334, -0.034457788 -0.067157462 0.048046574, -0.033796966 -0.067943469 0.048405424, 0.0027042478 -0.076785743 0.049000546, -0.0026584268 -0.076787412 0.049000487, 0.0026710927 -0.075838506 0.048405021, -0.0026255995 -0.075840041 0.048404932, 0.0026430935 -0.075047061 0.047613338, -0.0025980622 -0.075048551 0.047613278, -0.034251422 -0.066960976 0.047757551, -0.034741923 -0.066529706 0.047564551, -0.033982456 -0.067052752 0.04771027, -0.03344427 -0.067234546 0.047613844, -0.033179075 -0.06670101 0.046665519, 0.0026091933 -0.074082255 0.045608461, -0.034120932 -0.066397414 0.046960235, -0.033014223 -0.066369936 0.045608819, 0.0081647485 -0.077461198 0.049370468, -0.034594402 -0.066247165 0.047103435, -0.031962261 -0.070077255 0.049087286, -0.031471074 -0.068945587 0.048326299, -0.033004954 -0.068665624 0.048627272, -0.032638326 -0.070323929 0.049273804, 0.0080538094 -0.07641007 0.049000472, -0.031831652 -0.071088746 0.049370706, -0.031629369 -0.069959372 0.048973694, -0.032301307 -0.067748442 0.0475647, -0.033269599 -0.068424344 0.048555881, 0.0079544783 -0.075467169 0.048404738, -0.031241581 -0.069911793 0.048867077, 0.0078715235 -0.074679881 0.047613218, -0.030475274 -0.069825128 0.048627213, -0.030257076 -0.07062462 0.049000964, -0.032502025 -0.067204729 0.046960175, 0.0077702701 -0.073719546 0.045608431, 0.0078090131 -0.074087426 0.046665221, -0.032164007 -0.067460805 0.047103301, -0.030013144 -0.069162816 0.047957495, -0.029898971 -0.069962904 0.048555672, 0.015163645 -0.076399803 0.049370259, 0.013547882 -0.076702967 0.049370304, -0.029484808 -0.069484845 0.048046336, -0.028747395 -0.070229009 0.048405126, 0.014957979 -0.075363204 0.049000621, 0.013364151 -0.075662106 0.049000651, -0.029291272 -0.069274664 0.047757521, -0.029805556 -0.068882927 0.047564566, -0.029009923 -0.06934914 0.047710091, 0.014773384 -0.074433342 0.048404962, 0.013199285 -0.074728712 0.048405036, -0.028447524 -0.069496289 0.047613561, -0.02822195 -0.06894505 0.046665549, -0.029191628 -0.068707526 0.046959996, -0.029678956 -0.068590447 0.047103316, -0.028081715 -0.068602785 0.04560867, 0.014619142 -0.073656797 0.047613442, 0.013061553 -0.07394892 0.047613278, 0.0089792162 -0.075973943 0.048825964, 0.018865258 -0.075570986 0.049370363, 0.014503062 -0.073072344 0.046665236, 0.0093824267 -0.075303033 0.048404947, 0.0089353323 -0.074336529 0.047312409, 0.0094652176 -0.074167669 0.047156125, 0.0094389468 -0.075756788 0.048729315, 0.01295799 -0.073362231 0.04666546, 0.010694191 -0.074328035 0.047613353, 0.01860933 -0.074545711 0.049000561, 0.014431342 -0.072709695 0.045608401, 0.012893736 -0.072998017 0.045608491, 0.020699844 -0.075089201 0.049370617, 0.018379584 -0.073625684 0.048405021, 0.012504041 -0.075473934 0.0488258, 0.012004629 -0.074929923 0.048404887, 0.012047574 -0.073792055 0.047156096, 0.012384132 -0.073840335 0.047312498, 0.020419031 -0.074070305 0.049000427, 0.012077108 -0.075381264 0.04872936, 0.0092347562 -0.073550463 0.045608327, 0.010993242 -0.073308215 0.045608342, 0.018188 -0.072857663 0.047613487, 0.0084281564 -0.073647201 0.045608401, 0.0094308555 -0.07389842 0.046665296, 0.010828704 -0.073706493 0.046665311, 0.012004003 -0.073524401 0.046665266, 0.020166993 -0.073156312 0.048405051, 0.060771599 -0.044044435 0.047565982, 0.061281025 -0.045091569 0.048557073, 0.061586544 -0.044847161 0.048628598, 0.060038656 -0.045102462 0.047614932, 0.062118769 -0.043416947 0.048327848, 0.018043682 -0.072279572 0.046665505, 0.060193986 -0.044152483 0.046961486, 0.059562445 -0.044744655 0.046666995, 0.059266835 -0.044522509 0.04561013, 0.019956648 -0.072393194 0.047613427, 0.060513526 -0.043857321 0.047104672, 0.017953932 -0.071920782 0.045608476, 0.024090737 -0.074071005 0.049370483, 0.019798383 -0.071818873 0.046665341, 0.062339649 -0.041795552 0.047565982, 0.063183308 -0.042567953 0.048628747, 0.063403577 -0.042054489 0.048557252, 0.063170731 -0.040599719 0.047615215, 0.023763865 -0.073065892 0.04900068, 0.019699976 -0.071462274 0.045608565, 0.062272221 -0.041169375 0.046961635, 0.062074795 -0.041617885 0.047104686, 0.062669486 -0.040277615 0.046667233, 0.062358484 -0.040077686 0.045610264, 0.023470789 -0.072164536 0.048405007, 0.063817054 -0.039502487 0.04756625, 0.064394236 -0.040521353 0.048557416, 0.06467396 -0.040267095 0.048628911, 0.065108195 -0.038790166 0.048327982, 0.02612555 -0.073377937 0.049370572, 0.063251391 -0.039648414 0.04696162, 0.02322571 -0.071411476 0.047613531, 0.063546166 -0.03933464 0.047105089, 0.02577126 -0.072382405 0.049000844, 0.065479651 -0.037370473 0.047959238, 0.066101372 -0.037878036 0.048628896, 0.066290572 -0.037338138 0.048557505, 0.023041457 -0.070844889 0.0466654, 0.025453165 -0.071489155 0.048405215, 0.022927284 -0.070493191 0.045608625, 0.065667868 -0.036668167 0.047759384, 0.066661119 -0.036258548 0.048407033, 0.065217093 -0.037145182 0.047566369, 0.025187552 -0.070743337 0.047613561, 0.065767363 -0.03640531 0.047711879, 0.029198736 -0.072210222 0.049370587, 0.065965414 -0.035880342 0.047615692, 0.065442234 -0.035595477 0.046667457, 0.065106705 -0.036521971 0.046961978, 0.065117374 -0.035418779 0.045610487, 0.024987727 -0.070182011 0.046665564, 0.064940333 -0.036987454 0.04710488, 0.028802559 -0.071230337 0.04900077, 0.066524059 -0.03475067 0.047566369, 0.067167193 -0.035737112 0.048557565, 0.067421243 -0.035475194 0.048629135, 0.067753568 -0.03395851 0.04832828, 0.065972462 -0.034933522 0.046962082, 0.024863601 -0.069833651 0.045608521, 0.028447166 -0.070351332 0.048405051, 0.066241533 -0.034603193 0.047105163, 0.031411871 -0.07127513 0.049370587, 0.02815038 -0.06961745 0.047613502, 0.068022817 -0.032511517 0.047959596, 0.068671748 -0.032989234 0.048629269, 0.068827316 -0.032424465 0.048557773, 0.030985802 -0.070307821 0.049000874, 0.068363667 -0.031995252 0.048048407, 0.069129616 -0.031295717 0.048407257, 0.027927101 -0.069064975 0.04666537, 0.030603275 -0.069440395 0.048405305, 0.068160161 -0.031795219 0.047759637, 0.067748636 -0.03229776 0.047566682, 0.027788356 -0.068722084 0.04560867, 0.068243623 -0.03151983 0.047712192, 0.06840837 -0.030969217 0.047615692, 0.067865714 -0.030723721 0.04666771, 0.034164608 -0.069997311 0.049370766, 0.067594856 -0.031679869 0.046962187, 0.067528769 -0.030570939 0.045610741, 0.030284077 -0.0687159 0.047613665, 0.067460984 -0.032160729 0.047105312, 0.071180224 -0.029420882 0.049089387, 0.070040882 -0.028947622 0.048328429, 0.069814175 -0.030496955 0.048629552, 0.07144998 -0.030089661 0.049276233, 0.07217744 -0.02927573 0.049372971, 0.033701107 -0.06904754 0.049000904, 0.071050689 -0.029091433 0.048975721, 0.068877488 -0.029814437 0.047566667, 0.030043945 -0.068170771 0.04666549, 0.069585323 -0.030764014 0.048557907, 0.03328523 -0.068195626 0.04840526, 0.070991442 -0.028700143 0.048869535, 0.071668565 -0.027689591 0.049003124, 0.070881411 -0.027926788 0.048629612, 0.029894844 -0.067832381 0.045608759, 0.068342477 -0.030032933 0.046962157, 0.036530703 -0.06879212 0.04937093, 0.068584949 -0.029687867 0.047105566, 0.032937899 -0.067484245 0.04761368, 0.070206016 -0.027480483 0.047959745, 0.071000472 -0.027339339 0.048558056, 0.036035135 -0.067858785 0.049001142, 0.032676578 -0.066948831 0.046665579, 0.07050848 -0.026940927 0.048048526, 0.071229532 -0.026166186 0.048407674, 0.035590366 -0.067021355 0.048405379, -0.076190174 0.016168073 0.04937546, 0.032514349 -0.066616341 0.045608759, 0.070291832 -0.026753962 0.047759846, 0.069920301 -0.027279019 0.047566757, 0.038963988 -0.067443848 0.04937087, -0.075156376 0.015948623 0.049005821, 0.035218984 -0.066322163 0.047613874, 0.070357367 -0.026467115 0.047712326, 0.070486441 -0.025893331 0.047615916, 0.06992723 -0.025687724 0.046667919, -0.074229032 0.015751943 0.048410043, 0.069723725 -0.02666977 0.046962246, 0.069580078 -0.0255602 0.045611054, 0.038435176 -0.066528663 0.049001172, 0.069623306 -0.027163073 0.047105685, -0.045151994 -0.059938028 0.047548816, -0.044772401 -0.059519768 0.04662843, -0.046030194 -0.058878332 0.047103807, 0.034939587 -0.065795898 0.046665758, -0.045642972 -0.060502753 0.048326686, -0.044036224 -0.060778245 0.047564894, -0.043849215 -0.060520083 0.047103748, -0.046226352 -0.059129357 0.047564983, -0.073454529 0.015587628 0.047618344, -0.045612246 -0.058427125 0.045589015, -0.046654806 -0.057603747 0.045609221, -0.046315074 -0.058546796 0.046960488, -0.07287176 0.015463948 0.046670273, 0.037960917 -0.065707654 0.048405528, -0.043448135 -0.060053885 0.045588881, -0.072509974 0.015387297 0.045613453, -0.043409854 -0.060732335 0.046960503, -0.042325705 -0.060855672 0.045609087, 0.034766182 -0.065469354 0.045608833, -0.040671647 -0.063064143 0.047548577, -0.041620925 -0.062073603 0.047103599, -0.041798428 -0.062338501 0.04756479, -0.041127965 -0.063658223 0.048326552, 0.041454524 -0.065941915 0.049370974, -0.039724633 -0.064079881 0.047957703, -0.039493844 -0.063823476 0.047564834, -0.077132657 0.010814011 0.049375251, -0.039326027 -0.063552484 0.047103569, -0.04031606 -0.06262432 0.046628237, -0.04122974 -0.061598152 0.045588791, -0.041925624 -0.06176649 0.046960428, 0.037564963 -0.0650222 0.047613889, -0.07608594 0.010667354 0.049005419, -0.038952515 -0.063062817 0.045588776, -0.037770614 -0.063783199 0.045609102, -0.038868636 -0.063734427 0.046960175, 0.040892035 -0.065047279 0.049001217, -0.075147226 0.010535717 0.048409671, -0.035975859 -0.065856084 0.047548339, -0.037148386 -0.065216526 0.047564805, -0.036990568 -0.064939544 0.04710348, -0.035645187 -0.065396011 0.046628177, 0.037267014 -0.064506307 0.046665803, -0.036627397 -0.064440981 0.045588598, -0.037313148 -0.064657584 0.046960324, -0.074363157 0.010425687 0.047618046, 0.040387526 -0.064244747 0.048405543, -0.034249425 -0.065735921 0.045588538, -0.07377331 0.01034309 0.046669871, 0.037081927 -0.064186081 0.045609027, -0.031089276 -0.0682991 0.04754822, -0.073407069 0.01029171 0.04561314, -0.030784979 -0.067819685 0.046628088, 0.043573305 -0.064561263 0.049371019, -0.077699274 0.005407244 0.049374983, -0.031829953 -0.066941082 0.045588583, 0.039966121 -0.063574493 0.047613978, -0.029364064 -0.068058982 0.045588553, 0.042982087 -0.063685447 0.049001127, -0.076644868 0.0053337812 0.049005181, 0.009553656 -0.077302098 0.049370423, -0.07569927 0.0052679479 0.048409551, 0.039649114 -0.06306991 0.046665892, 0.010790989 -0.076071709 0.049000472, 0.010939911 -0.077489316 0.049439788, 0.042451829 -0.062899649 0.048405707, 0.012245536 -0.076921582 0.049370483, -0.074909434 0.0052129477 0.047617644, 0.03945224 -0.062756881 0.045609027, -0.074315161 0.0051716715 0.046669692, 0.010732383 -0.07512255 0.048404828, 0.042008758 -0.062243357 0.047613934, 0.061539158 -0.042942971 0.047549546, -0.073946282 0.0051459819 0.045612857, 0.061110124 -0.042575255 0.046629563, 0.046157181 -0.062740073 0.049371019, 0.060049921 -0.043452531 0.0455897, -0.07788752 -2.5987625e-05 0.04937461, -0.076830596 -2.5644898e-05 0.049004793, 0.061596826 -0.041230351 0.045589879, 0.041675553 -0.061749443 0.046665892, 0.064500287 -0.038351953 0.047549948, 0.064050123 -0.038008541 0.046629846, 0.045530885 -0.06188871 0.049001276, -0.075882301 -2.5585294e-05 0.048409134, 0.063059181 -0.038957104 0.045590043, 0.041468769 -0.061442897 0.045609102, -0.075090796 -2.5197864e-05 0.047617421, 0.064439714 -0.036627993 0.045590222, 0.044969112 -0.061125115 0.048405692, -0.074495316 -2.4870038e-05 0.046669468, 0.06711939 -0.03355743 0.047550231, 0.066649497 -0.033239827 0.04662998, -0.074125379 -2.4616718e-05 0.045612514, 0.047970757 -0.061364576 0.049371064, 0.065732241 -0.034254104 0.045590371, -0.07769601 -0.0054591894 0.049374506, 0.044499964 -0.060487464 0.047614068, 0.066939443 -0.031830654 0.04559046, 0.047319725 -0.060531974 0.049001366, -0.076641753 -0.0053850263 0.049004361, 0.069382876 -0.028585345 0.04755035, 0.044146836 -0.060007468 0.046666101, 0.068894491 -0.02829434 0.046630323, -0.07569617 -0.0053187609 0.048408777, 0.068055421 -0.029368699 0.045590654, 0.046735838 -0.059785098 0.048405737, 0.069082588 -0.026863486 0.045590788, -0.074906409 -0.0052631795 0.047617182, 0.043927744 -0.059709668 0.045609027, 0.046248287 -0.05916138 0.047614068, -0.073943287 -0.0051953793 0.045612186, -0.07431221 -0.0052213818 0.046669006, -0.077126309 -0.010865614 0.049374044, 0.050613493 -0.05920352 0.049371347, 0.045881212 -0.058691859 0.04666619, -0.076079592 -0.01071839 0.049004257, 0.049926952 -0.058400065 0.0490015, -0.076899856 -0.01236625 0.049374029, 0.045653686 -0.058400616 0.045609206, -0.075140953 -0.010586098 0.048408568, 0.052134186 -0.057868987 0.049371451, -0.075856373 -0.012198478 0.049004227, 0.049310789 -0.057679564 0.048405856, -0.074357003 -0.010475501 0.047616661, 0.051426873 -0.057083592 0.049001649, -0.074920565 -0.012047648 0.048408493, 0.048796341 -0.057077795 0.047614247, 0.050792262 -0.056379229 0.048405871, -0.074138865 -0.011922136 0.047616795, 0.048409209 -0.056624845 0.046666309, -0.07340084 -0.01034078 0.045611858, -0.073767006 -0.010392502 0.046668842, 0.050262302 -0.055791065 0.047614232, -0.076180503 -0.016219348 0.049373865, -0.073550656 -0.011827499 0.046668753, 0.048168853 -0.056344017 0.04560937, 0.05479981 -0.0553509 0.049371526, -0.075146839 -0.015999287 0.049003929, 0.049863547 -0.055348292 0.046666324, -0.073185593 -0.011768684 0.045611829, 0.054056317 -0.054599971 0.049001634, -0.075792223 -0.017946765 0.049373612, -0.074219376 -0.015801802 0.048408166, 0.049616039 -0.055073634 0.045609325, -0.074763864 -0.017703071 0.04900381, 0.056043714 -0.054091126 0.049371615, 0.053389356 -0.053926244 0.048406079, -0.07344532 -0.015636876 0.047616705, -0.073841229 -0.01748465 0.048408121, 0.055283278 -0.053357407 0.049001664, -0.072862491 -0.015512854 0.046668649, 0.05283235 -0.053363651 0.04761444, -0.073071063 -0.01730217 0.047616467, 0.054601088 -0.052698821 0.048406139, -0.072500899 -0.015435755 0.045611635, 0.05241321 -0.052940235 0.046666399, -0.074863747 -0.021493882 0.049373403, 0.054031283 -0.052148893 0.047614604, -0.072491273 -0.017164901 0.04666841, 0.052153155 -0.052677229 0.045609549, -0.07384792 -0.021202162 0.049003601, 0.058693916 -0.051203266 0.04937166, -0.072131366 -0.017079681 0.045611605, 0.053602934 -0.051735327 0.046666384, -0.074280247 -0.023431093 0.049373269, -0.072936743 -0.020940691 0.048407957, 0.057897538 -0.05050841 0.049002096, 0.053336725 -0.05147849 0.045609623, -0.073272362 -0.023113161 0.049003452, 0.059680238 -0.050050139 0.049371794, -0.072175726 -0.020722046 0.047616214, 0.057183087 -0.049885377 0.048406288, -0.072368279 -0.022828043 0.048407778, 0.058870435 -0.0493709 0.049002007, -0.071603119 -0.020557836 0.046668231, 0.056586385 -0.04936479 0.047614783, -0.071613118 -0.022589862 0.047616228, 0.058144093 -0.04876183 0.048406467, -0.071247712 -0.020455703 0.045611486, 0.056137636 -0.048973233 0.046666712, -0.073182136 -0.026663899 0.049373195, 0.057537407 -0.04825297 0.047614783, -0.071045145 -0.022410542 0.046668142, 0.05585891 -0.048729941 0.045609653, -0.072189257 -0.02630204 0.049003243, 0.05708088 -0.047870114 0.046666652, 0.062274799 -0.046782404 0.049372032, -0.070692524 -0.02229923 0.045611292, -0.07129854 -0.025977284 0.048407644, 0.056797624 -0.047632456 0.045609787, 0.061429694 -0.046147466 0.049002156, -0.07237196 -0.028790802 0.049372971, -0.070554554 -0.02570641 0.047616139, 0.060671717 -0.045577928 0.048406646, -0.071389943 -0.028400123 0.049003288, -0.069995001 -0.025502264 0.046667963, -0.070509017 -0.028049693 0.04840757, -0.069647357 -0.025375783 0.045611173, -0.069773421 -0.027756974 0.047615841, -0.071144179 -0.03170386 0.049372941, -0.069219932 -0.02753678 0.046667933, -0.070179 -0.03127335 0.049003109, -0.068876296 -0.027400017 0.045611098, -0.069312796 -0.030887857 0.048407525, -0.070077494 -0.033996791 0.049372658, -0.068589985 -0.030565396 0.047615692, -0.069126561 -0.03353557 0.049002945, -0.068045646 -0.030322775 0.046667695, -0.068273664 -0.033121601 0.048407272, -0.067707986 -0.030172318 0.045610756, -0.06875959 -0.036589354 0.049372658, -0.067561328 -0.032776013 0.047615722, -0.067826584 -0.036092803 0.049002737, -0.067025274 -0.032515988 0.046667561, -0.066989556 -0.035647437 0.048407093, -0.066692606 -0.032354578 0.04561083, -0.067409173 -0.039021492 0.04937239, -0.066290617 -0.035275668 0.047615618, 0.07311134 -0.026857466 0.04937315, -0.066494629 -0.03849189 0.049002647, 0.072119385 -0.026493028 0.049003363, -0.065764889 -0.034995571 0.046667382, -0.065673918 -0.038017005 0.048406973, -0.065438449 -0.034821793 0.045610607, -0.066039979 -0.041296765 0.049372599, -0.064988852 -0.037620485 0.047615379, -0.065143824 -0.040736273 0.049002483, -0.073440149 0.010053411 0.04561311, -0.064473361 -0.03732188 0.046667457, -0.073970392 0.0047857016 0.045612797, -0.064339995 -0.040233552 0.048406988, -0.074123666 -0.00050599873 0.045612395, -0.064153284 -0.03713654 0.045610487, -0.073898658 -0.0057955533 0.045612246, -0.064381078 -0.043837905 0.049372226, -0.048480317 -0.060962737 0.049371347, -0.0490226 -0.060527489 0.049371213, -0.048357412 -0.059706211 0.049001485, -0.063668698 -0.039813787 0.04761529, -0.046947509 -0.061697781 0.049274445, -0.063507542 -0.043242961 0.049002394, -0.046221495 -0.062692761 0.049371168, -0.044473857 -0.063944355 0.049371019, -0.063163489 -0.039498061 0.046667263, -0.044005543 -0.064267516 0.049371168, -0.043870211 -0.063076913 0.049001291, -0.062724039 -0.042709425 0.048406839, -0.042388931 -0.064914316 0.049274176, -0.062850207 -0.039301813 0.045610338, -0.041629136 -0.065831825 0.049371004, -0.039687648 -0.067020431 0.04937093, -0.062998638 -0.045802638 0.049372032, -0.039306283 -0.067244694 0.049370885, -0.03914924 -0.066110834 0.049001083, -0.062069565 -0.04226397 0.047615096, -0.037611008 -0.067794621 0.049274102, -0.062143788 -0.045181125 0.049002185, -0.036824211 -0.06863527 0.049370766, -0.034689799 -0.069738537 0.049370736, -0.061577171 -0.041928396 0.04666695, -0.034406498 -0.069878727 0.049370617, -0.03421922 -0.068792194 0.049000919, -0.061377034 -0.044623658 0.048406631, -0.061271399 -0.041720405 0.04561013, -0.029506952 -0.072084695 0.049370572, -0.060736552 -0.044158086 0.047615021, -0.0074269325 -0.073754996 0.045608357, -0.0077260584 -0.073724344 0.045608461, -0.0077646971 -0.074092016 0.046665266, -0.0025776029 -0.07445319 0.046665132, -0.061009794 -0.048420489 0.049371928, -0.0021437705 -0.074097052 0.045608461, -0.060254708 -0.043807834 0.04666695, 0.0026222318 -0.074451804 0.046665266, 0.0031503886 -0.074061051 0.045608401, -0.060181856 -0.047763526 0.049002126, -0.059955806 -0.043590233 0.045610264, -0.059439287 -0.047173992 0.048406452, 0.06265229 -0.046275184 0.049372107, -0.059650213 -0.050085708 0.049371898, -0.058819115 -0.046681896 0.047614917, 0.063344166 -0.044699937 0.049275175, 0.064300522 -0.043956071 0.049372226, 0.065523162 -0.042111665 0.049372405, -0.058840871 -0.049406126 0.049002081, 0.065795273 -0.041685238 0.049372256, 0.064634234 -0.041540235 0.049002513, -0.058352441 -0.046311602 0.046666712, 0.066394582 -0.040028736 0.049275592, -0.058114856 -0.04879649 0.048406497, 0.067273751 -0.039254516 0.049372539, 0.068422124 -0.037216425 0.049372554, -0.058062777 -0.046081528 0.0456101, 0.068602771 -0.036882818 0.049372524, 0.067493811 -0.036711469 0.049002767, -0.057508588 -0.048287332 0.047614828, 0.069101229 -0.035150409 0.04927586, -0.057312578 -0.052744776 0.049371704, 0.06990388 -0.03435275 0.049372777, 0.07095626 -0.032122806 0.049372837, -0.057052121 -0.047904328 0.046666756, 0.071059957 -0.031892121 0.049372777, 0.069993302 -0.031686708 0.04900296, -0.056535125 -0.052028939 0.049001992, -0.056768969 -0.04766649 0.045609936, -0.056011334 -0.054124713 0.049371645, -0.074494585 -0.00026679039 0.046669379, -0.074290305 -0.0055229664 0.046669051, -0.055837184 -0.051387116 0.048406258, -0.047286198 -0.059604675 0.048556298, -0.047262445 -0.058354288 0.047614098, -0.047760546 -0.058969587 0.048405662, -0.05525142 -0.053390369 0.049001783, -0.055254817 -0.050850824 0.047614634, -0.04704757 -0.059922948 0.04862766, -0.054569542 -0.052731514 0.048406184, -0.05481638 -0.050447568 0.046666518, -0.054000229 -0.052181244 0.047614634, -0.044736713 -0.06246528 0.049001321, -0.044827819 -0.061601222 0.048627853, -0.054544359 -0.050197035 0.045609668, -0.044328317 -0.061836183 0.048556104, -0.04332903 -0.062298626 0.048405632, -0.042877018 -0.061648428 0.047614023, -0.053309858 -0.056787714 0.049371526, -0.053571999 -0.051767394 0.046666369, -0.042832002 -0.062881872 0.048556075, -0.042582169 -0.06317459 0.048627585, -0.052586481 -0.056017101 0.049001798, -0.053305879 -0.051510364 0.045609593, -0.052099481 -0.057899922 0.049371243, -0.040110976 -0.06553176 0.049001187, -0.051937565 -0.055325851 0.048406005, -0.0402468 -0.064687461 0.048627526, -0.051392496 -0.057114333 0.049001679, -0.039719731 -0.064892769 0.048555985, -0.038666204 -0.065295145 0.048405692, -0.051395759 -0.05474861 0.047614425, -0.038151592 -0.065826803 0.048555925, -0.03826265 -0.064613864 0.047613859, -0.037893295 -0.066093668 0.04862754, -0.050758302 -0.056409687 0.048405915, -0.050988048 -0.054314226 0.046666205, -0.050229028 -0.055821016 0.047614366, -0.050735041 -0.054044664 0.045609608, -0.035276085 -0.068256274 0.049001098, -0.049830511 -0.055378228 0.04666625, -0.049583003 -0.055103406 0.045609519, -0.029106602 -0.071106672 0.04900068, -0.046887502 -0.057891175 0.04666613, -0.0023659021 -0.074460194 0.046665147, 0.0028941333 -0.074441686 0.046665117, 0.0081397742 -0.074051827 0.046665311, 0.064037547 -0.042454153 0.049002275, 0.063836724 -0.041027769 0.048406884, 0.066935048 -0.037720859 0.049002692, -0.024166584 -0.074046165 0.049370557, -0.023838788 -0.073041454 0.049000725, 0.069483057 -0.03279075 0.049003094, -0.02354458 -0.072140262 0.048404962, -0.023299038 -0.071387589 0.047613516, -0.02311407 -0.070821226 0.046665475, -0.022999272 -0.070469663 0.045608595, -0.018820092 -0.075582236 0.049370408, -0.018564612 -0.074556768 0.049000561, -0.018335551 -0.073636785 0.048404902, -0.018144339 -0.072868541 0.047613233, -0.018000454 -0.072290465 0.046665236, -0.017910972 -0.071931541 0.04560864, -0.013502032 -0.076711059 0.049370423, -0.013318971 -0.075670093 0.049000606, -0.013154402 -0.074736536 0.048404947, -0.013017118 -0.073956639 0.047613278, -0.012913927 -0.073369965 0.04666537, -0.042536706 -0.061159372 0.046666056, -0.012849838 -0.073005661 0.045608461, -0.0081182867 -0.077465966 0.049370304, -0.0080081224 -0.076414853 0.049000531, -0.0079093724 -0.075472012 0.048404947, -0.0078267306 -0.07468462 0.047613323, -0.039030433 -0.064292654 0.047757939, -0.03877449 -0.064400077 0.047710374, -0.037959352 -0.064101279 0.046665788, 0.061691433 -0.021336451 -0.034569383, 0.062651157 -0.022482678 -0.033662185, 0.061423168 -0.023283988 -0.03310807, 0.063710868 -0.021405652 -0.034079134, 0.060220867 -0.022295967 -0.033905804, 0.060148895 -0.020674929 -0.035230279, 0.062861741 -0.019931719 -0.034995601, 0.060992032 -0.019884497 -0.035572574, 0.061658159 -0.018902838 -0.035786167, 0.064549342 -0.020106673 -0.034337834, 0.053333849 -0.016332135 -0.028323874, 0.053185999 -0.016852438 -0.027513236, 0.053359956 -0.017210633 -0.029289126, 0.064023882 -0.019393593 -0.034744054, 0.053574696 -0.016587839 -0.030931354, 0.053620189 -0.017773196 -0.031145304, 0.053209573 -0.018398166 -0.027772143, 0.05360879 -0.0190216 -0.029715285, 0.053917259 -0.018890306 -0.031487584, 0.053538367 -0.019872963 -0.028189257, 0.054348499 -0.020614281 -0.030378953, 0.054448277 -0.019873619 -0.031938747, 0.055182487 -0.020666733 -0.032472476, 0.054155976 -0.021202654 -0.028743431, 0.055031225 -0.022320911 -0.029407188, 0.055506349 -0.021832213 -0.031215295, 0.05607748 -0.021223083 -0.033057585, 0.05612053 -0.02317144 -0.030147076, 0.056969136 -0.022556722 -0.032142639, 0.057080969 -0.021510601 -0.033660382, 0.057369009 -0.023711517 -0.0309259, 0.058714002 -0.023914129 -0.031704709, 0.058593571 -0.022716403 -0.033069506, 0.058134779 -0.021512285 -0.034245446, 0.06008856 -0.023769259 -0.032444507, 0.059177622 -0.021228313 -0.034779206, 0.055913761 -0.017444968 -0.022610873, 0.055886343 -0.018812492 -0.022813037, 0.056097582 -0.0201388 -0.023141131, 0.044657409 -0.014032885 -0.046997637, 0.044702768 -0.015218318 -0.047211453, 0.044999823 -0.016335249 -0.047554001, 0.045530722 -0.017318726 -0.04800497, 0.046265185 -0.018111661 -0.048538789, 0.048163697 -0.018955499 -0.04972671, 0.04716 -0.018668041 -0.049124017, 0.049217343 -0.018957242 -0.050311789, 0.050260201 -0.018672973 -0.050845459, 0.051231414 -0.018119752 -0.051296651, 0.052074671 -0.017329544 -0.051638886, 0.052740946 -0.016347915 -0.051852539, -0.038657799 0.075669393 0.050281793, -0.043731883 0.07285507 0.050281584, -0.038624093 0.075603604 0.05007042, 0.075359449 0.038495332 0.049720317, 0.072556674 0.043548241 0.049720615, 0.075190529 0.038408905 0.049601257, -0.043344587 0.072210014 0.049529195, -0.04817158 0.06908375 0.049529016, 0.072692305 0.043629706 0.049879014, 0.075500444 0.038567156 0.049878776, 0.075606689 0.038621336 0.050068378, 0.072794586 0.043690905 0.050068676, -0.048292398 0.069256946 0.049602807, 0.075672507 0.038655013 0.050279796, 0.072857887 0.043729022 0.050280005, -0.04345344 0.072391346 0.049603149, -0.043550864 0.072553724 0.049722254, -0.048400864 0.0694125 0.04972209, 0.069086522 0.048168659 0.049527824, 0.072212771 0.043341771 0.049527496, -0.043632537 0.072689578 0.049880505, -0.048491299 0.069542408 0.049880266, 0.069259912 0.048289582 0.049601704, -0.048559636 0.069640234 0.050070018, 0.072394148 0.043450505 0.049601436, -0.043693751 0.07279171 0.050070435, 0.06941539 0.048398033 0.049720913, -0.048601881 0.069700837 0.05028145, 0.069545358 0.048488602 0.049879193, -0.052773729 0.065635264 0.049528733, 0.06964308 0.04855676 0.050068855, -0.052906379 0.065800115 0.049602762, 0.069703713 0.04859893 0.050280333, -0.053025126 0.065947682 0.049721971, 0.065638229 0.052770987 0.049527913, -0.053124353 0.066071168 0.049880087, 0.065802917 0.052903578 0.049601942, -0.053199038 0.066164136 0.050069913, 0.065950692 0.053022176 0.04972133, -0.053245381 0.066221669 0.050281152, -0.057130203 0.061880887 0.049528733, 0.066074088 0.053121388 0.049879491, 0.066166818 0.053196102 0.050069153, -0.057273552 0.062036201 0.049602583, 0.066224456 0.053242415 0.050280631, -0.057402015 0.062175393 0.049721718, 0.061883748 0.057127342 0.049528182, -0.057509542 0.06229189 0.049880072, 0.062038928 0.057270557 0.04960227, -0.05759038 0.062379375 0.050069749, -0.057640582 0.0624336 0.050281137, 0.062178284 0.057399243 0.04972142, -0.061220035 0.057837993 0.049528301, 0.062294573 0.05750683 0.049879581, -0.061373591 0.057983071 0.0496023, 0.062382281 0.05758743 0.050069481, 0.06243667 0.057637781 0.05028069, -0.061511382 0.058113217 0.049721375, 0.057840675 0.061217234 0.049528599, -0.061626658 0.058222055 0.049879834, 0.057986021 0.06137079 0.049602538, -0.061713085 0.058303684 0.050069407, -0.061767116 0.058354661 0.050280735, 0.058116227 0.061508536 0.049721718, -0.065024644 0.053525254 0.049528033, 0.058224887 0.061623707 0.049880087, 0.058306694 0.061710492 0.050069451, -0.065187618 0.053659514 0.049602032, 0.058357388 0.061764047 0.050280929, -0.065333948 0.053780019 0.049721211, 0.053528011 0.065021679 0.049528658, -0.065456286 0.053880796 0.049879506, 0.05366236 0.065184921 0.049602747, -0.065548435 0.053956538 0.050069228, -0.065605372 0.054003462 0.050280601, 0.053783 0.065331072 0.049721897, -0.068525836 0.048963144 0.049527884, 0.053883553 0.065453574 0.049880207, 0.05395931 0.065545395 0.050069988, -0.068697721 0.049085826 0.049601793, 0.054006219 0.065602526 0.050281167, -0.068852007 0.049195945 0.049720958, 0.048965842 0.06852296 0.049528867, -0.068980917 0.049288228 0.049879208, 0.049088717 0.068694994 0.049602896, -0.069077805 0.049357563 0.05006896, -0.069137931 0.049400523 0.050280213, 0.049198955 0.06884934 0.049721926, -0.071707442 0.044172555 0.049527481, 0.049290985 0.068978086 0.049880296, 0.049360365 0.069074914 0.050070018, -0.071887404 0.044283345 0.04960157, 0.049403369 0.069134936 0.050281495, -0.072049007 0.0443829 0.049720809, 0.044175267 0.071704805 0.049529016, -0.072183877 0.044465959 0.049879119, 0.044286013 0.071884751 0.049603105, -0.072285235 0.044528246 0.050068662, -0.072348014 0.044567093 0.050279975, 0.044385701 0.072046131 0.049722433, -0.074554861 0.039175972 0.049527198, 0.044468701 0.072181091 0.049880564, 0.044531196 0.072282419 0.050070196, -0.074742004 0.039274216 0.049601182, 0.04456985 0.072345436 0.050281644, -0.074909806 0.03936258 0.049720392, 0.039178818 0.074552372 0.049529165, -0.075050071 0.039436057 0.049878761, 0.039277077 0.074739441 0.049603224, -0.075155497 0.039491549 0.050068319, -0.075221062 0.03952603 0.050279751, 0.039365411 0.074907243 0.049722344, 0.039439082 0.075047344 0.049880505, -0.077054903 0.033996969 0.049527138, -0.07724829 0.034082279 0.049601048, 0.039494514 0.075152799 0.050070345, 0.039528817 0.075218245 0.050281882, -0.077421695 0.034158751 0.049720168, 0.033999711 0.077052131 0.049529433, -0.077566713 0.034222752 0.049878553, 0.034085035 0.077245414 0.049603492, -0.0776757 0.034270838 0.050068021, -0.077743381 0.034300834 0.050279438, 0.034161627 0.077418923 0.049722522, 0.034225404 0.077563763 0.049880892, -0.07919541 0.028659075 0.049526721, 0.034273565 0.077672899 0.050070584, -0.079394236 0.028731123 0.049600676, 0.034303397 0.07774058 0.050281882, 0.028662056 0.079192668 0.049529463, -0.079572394 0.02879563 0.04971993, 0.028734028 0.07939136 0.049603462, -0.079721481 0.028849453 0.049878106, 0.028798431 0.079569831 0.049722642, -0.079833373 0.028889969 0.050067827, 0.028852403 0.079718545 0.049881041, -0.079903036 0.028915003 0.050279036, 0.028893024 0.079830557 0.050070494, 0.028918028 0.07990022 0.050281912, 0.023190767 0.080964059 0.049529701, 0.023249 0.081167161 0.049603552, 0.023301125 0.081349552 0.04972285, 0.023344755 0.081501737 0.04988113, 0.023377597 0.081616238 0.050070733, 0.023397923 0.081687301 0.050282151, 0.017611176 0.082357883 0.049529791, 0.017655581 0.082564533 0.049603671, 0.017695218 0.082749993 0.049722731, 0.017728209 0.082904786 0.04988113, 0.082360834 -0.017614275 0.04952392, 0.017753214 0.083021328 0.050070912, 0.017768562 0.083093658 0.050282091, 0.082567424 -0.017658293 0.049597934, 0.011949778 0.08336781 0.049529701, 0.082752854 -0.017697886 0.049717069, 0.082907662 -0.017730996 0.049875572, 0.011979818 0.083576888 0.049603701, 0.08302404 -0.017755881 0.05006513, 0.012006789 0.083764642 0.04972294, 0.083096474 -0.017771304 0.050276563, 0.012028992 0.083921358 0.04988125, 0.083370626 -0.011952654 0.049524322, 0.012046039 0.084039256 0.050070852, 0.083579883 -0.011982486 0.049598277, 0.01205647 0.08411254 0.05028218, 0.083767474 -0.012009323 0.04971756, 0.0062324107 0.083988771 0.049529791, 0.083924383 -0.012032002 0.0498759, 0.0062480867 0.084199756 0.049603701, 0.084042177 -0.012048855 0.050065562, 0.0062622428 0.084388599 0.04972297, 0.084115401 -0.012059376 0.050276697, 0.083991662 -0.0062351227 0.049524635, 0.0062738359 0.084546521 0.04988122, 0.084202483 -0.0062510818 0.049598634, 0.0062826574 0.084665477 0.050070882, 0.0062880814 0.084739164 0.05028218, 0.084391549 -0.0062649548 0.049717635, 0.00048610568 0.084218532 0.049529821, 0.084549502 -0.0062766373 0.049876049, 0.00048726797 0.084429726 0.049603879, 0.084668264 -0.0062855333 0.050065905, 0.084741905 -0.0062909275 0.050277099, 0.00048848987 0.084619269 0.049722731, 0.00048938394 0.084777698 0.04988122, 0.084221229 -0.0004889369 0.049524888, 0.084432587 -0.0004901886 0.049598992, 0.00049012899 0.084896684 0.050071031, 0.00049039721 0.084970802 0.0502823, 0.08462216 -0.00049127638 0.049718127, -0.0052624345 0.084055245 0.049529761, 0.084780484 -0.00049221516 0.049876511, -0.0052757561 0.084266156 0.049603701, 0.084899768 -0.00049288571 0.050066158, 0.084973529 -0.00049313903 0.050277501, -0.0052874088 0.084455222 0.04972291, -0.0052973628 0.084613428 0.049881279, 0.084058017 0.0052596927 0.049525365, 0.084268942 0.005272761 0.049599305, -0.0053047836 0.084732339 0.050070882, -0.0053094923 0.084806129 0.050282419, 0.084458217 0.0052846521 0.04971844, -0.010986447 0.083500102 0.049529701, 0.084616333 0.005294621 0.049876794, -0.011014074 0.083709747 0.049603581, 0.084735155 0.0053020269 0.050066516, 0.084808916 0.0053066462 0.050277889, -0.01103881 0.083897695 0.049722821, 0.083503112 0.010983601 0.049525559, -0.011059403 0.084054694 0.049881071, -0.01107499 0.084172711 0.050071001, 0.083712563 0.011011168 0.049599648, -0.011084676 0.084246129 0.050282121, 0.083900571 0.011035994 0.049718797, -0.01665929 0.082555667 0.049529701, 0.08405751 0.011056513 0.049877137, -0.016701132 0.082762748 0.049603745, 0.084175587 0.011072204 0.05006665, 0.08424893 0.01108174 0.050278127, -0.016738594 0.082948789 0.04972288, -0.016770065 0.083103985 0.049881265, 0.082558617 0.016656473 0.049525857, -0.01679346 0.083220646 0.050070748, 0.082765594 0.016698346 0.049599946, -0.016808122 0.083293259 0.050282136, 0.082951501 0.016735807 0.049719065, -0.022254467 0.081226364 0.049529657, 0.083106771 0.016767204 0.049877435, 0.083223417 0.016790777 0.050067008, -0.022310257 0.081430167 0.049603552, 0.083296046 0.016805381 0.050278485, -0.022360444 0.081613168 0.049722806, -0.022402316 0.081765756 0.049881101, 0.081229135 0.02225171 0.049526364, 0.081433058 0.022307381 0.049600303, -0.022433817 0.081880718 0.050070778, -0.022453249 0.081951961 0.05028227, 0.08161594 0.022357553 0.049719334, -0.027745992 0.079518333 0.049529478, 0.081768662 0.022399306 0.049877793, -0.02781558 0.079717785 0.049603567, 0.081883505 0.022430897 0.050067425, 0.081954822 0.022450447 0.050278813, -0.027877927 0.079896837 0.049722522, 0.079521194 0.027742997 0.049526662, -0.027930111 0.080046266 0.049880892, 0.079720721 0.027812585 0.049600452, -0.02796948 0.080159009 0.050070629, -0.027993709 0.080228686 0.050281987, 0.079899713 0.02787514 0.049719691, -0.033107996 0.077439517 0.049529418, 0.080049202 0.027927309 0.049877942, 0.080161721 0.027966544 0.050067693, -0.033191085 0.077633917 0.049603477, 0.080231577 0.027991042 0.050279111, -0.033265471 0.077808172 0.049722478, 0.077442318 0.03310506 0.049526751, -0.033327848 0.077953741 0.049880907, 0.0776366 0.03318812 0.049600989, -0.033374548 0.07806313 0.050070658, -0.033403635 0.078131273 0.050281957, 0.077811047 0.033262655 0.049720079, -0.038315624 0.07499963 0.049529061, 0.077956647 0.033324957 0.04987824, -0.038411513 0.075187683 0.049603254, 0.07806614 0.033371717 0.05006817, 0.078134164 0.033400878 0.050279409, -0.038497925 0.075356588 0.049722403, 0.075002447 0.038312778 0.049527317, -0.038569942 0.075497583 0.049880698, 0.066074029 0.05312705 -0.049873605, 0.069545344 0.048494205 -0.049873859, 0.065950572 0.053027883 -0.049715132, -0.048400775 0.069418117 -0.049714223, -0.043632582 0.072695181 -0.049872398, -0.043550894 0.072559297 -0.049714118, -0.048559591 0.069645777 -0.050062314, -0.043693766 0.072797239 -0.05006209, -0.048491403 0.069547817 -0.049872667, 0.069415331 0.048403665 -0.049715474, 0.066166788 0.053201765 -0.050063252, 0.06964317 0.048562348 -0.050063521, -0.043731779 0.072860643 -0.050273418, -0.048601836 0.069706559 -0.050273687, 0.069703579 0.048604652 -0.050274774, 0.066224456 0.053248107 -0.050274581, -0.038315579 0.075005099 -0.049520895, -0.043344527 0.072215557 -0.049521074, 0.069086581 0.048174217 -0.04952246, 0.072212845 0.043347389 -0.049522698, -0.038411766 0.075193346 -0.049594671, -0.043453321 0.07239677 -0.049595147, 0.072394013 0.043456152 -0.049596682, 0.069259882 0.048295215 -0.049596429, -0.038497955 0.075362191 -0.049713835, 0.072556645 0.043553695 -0.049715787, 0.072692439 0.04363516 -0.049873993, -0.038569957 0.075503245 -0.049872369, -0.038624197 0.075609356 -0.050061956, 0.072794616 0.043696538 -0.050063789, -0.038657963 0.075675294 -0.05027315, 0.072857931 0.043734536 -0.050275102, -0.033107877 0.077445045 -0.049520791, 0.075002372 0.038318381 -0.049523056, -0.033191085 0.077639297 -0.049594685, 0.075190663 0.038414523 -0.049596831, -0.033265471 0.077813849 -0.049713895, 0.07535933 0.038500667 -0.049716011, -0.033327788 0.077959239 -0.049872085, 0.075500444 0.038572758 -0.04987444, -0.033374727 0.078068897 -0.050061688, 0.075606465 0.038627073 -0.050064147, -0.03340362 0.078136697 -0.050273225, 0.075672492 0.038660601 -0.05027543, -0.027745843 0.079523832 -0.049520701, 0.077442259 0.033110559 -0.049523264, -0.027815536 0.079723507 -0.049594581, 0.077636629 0.033193707 -0.049597353, 0.077811077 0.033268288 -0.049716368, -0.027877823 0.079902381 -0.049713746, -0.027930185 0.080051959 -0.049872056, 0.077956602 0.0333305 -0.049874708, -0.02796936 0.080164522 -0.050061703, 0.078066096 0.033377334 -0.050064355, -0.027993813 0.080234349 -0.050273016, 0.07813403 0.033406392 -0.050275639, -0.022254512 0.081231996 -0.049520418, 0.079521269 0.027748555 -0.049523532, -0.022310331 0.08143577 -0.049594373, 0.07972078 0.027818307 -0.049597487, -0.022360399 0.081618637 -0.049713522, 0.079899818 0.027880788 -0.049716637, -0.022402331 0.081771344 -0.049871922, 0.080049187 0.027932957 -0.04987511, 0.08016175 0.027972177 -0.050064728, -0.022433743 0.081886262 -0.050061479, -0.022453398 0.081957579 -0.050272882, 0.080231592 0.02799657 -0.050275952, -0.016659334 0.08256124 -0.049520344, 0.08122921 0.022257328 -0.04952383, -0.016701207 0.08276841 -0.049594447, 0.081433102 0.022312999 -0.04959774, -0.016738653 0.082954302 -0.049713597, 0.081615865 0.022363305 -0.049717009, -0.016769871 0.083109394 -0.049871847, 0.081768617 0.022404969 -0.049875289, -0.016793668 0.083226383 -0.050061569, 0.08188343 0.022436455 -0.050065011, -0.016808257 0.083298951 -0.050272837, 0.081954688 0.022456095 -0.050276235, -0.010986492 0.083505705 -0.049520418, 0.082558587 0.016662031 -0.049524248, -0.011014014 0.083715156 -0.049594313, 0.082765788 0.01670377 -0.049598187, 0.082951486 0.01674144 -0.049717322, -0.011038825 0.083903208 -0.049713507, -0.011059508 0.084060073 -0.049871922, 0.083106875 0.016772673 -0.049875632, 0.083223537 0.016796455 -0.050065175, -0.01107496 0.084178373 -0.050061345, 0.083296135 0.016810894 -0.050276592, -0.011084571 0.084251732 -0.050272852, -0.00526236 0.084060818 -0.049520448, 0.083502889 0.010989368 -0.049524531, 0.083712533 0.011016846 -0.049598336, -0.0052756965 0.084271759 -0.049594402, 0.083900586 0.011041567 -0.049717635, -0.0052874982 0.08446084 -0.049713507, 0.084057614 0.011062235 -0.04987587, -0.0052974224 0.084619001 -0.049871847, -0.005304873 0.084737927 -0.050061509, 0.084175512 0.011077881 -0.050065592, 0.08424896 0.011087477 -0.050276831, -0.0053094774 0.084811792 -0.050272763, 0.084057942 0.00526537 -0.049524784, 0.00048615038 0.084223926 -0.049520478, 0.00048737228 0.084435225 -0.049594387, 0.084268987 0.0052785575 -0.049598813, 0.00048835576 0.08462505 -0.049713582, 0.084458083 0.0052903444 -0.049718022, 0.00048927963 0.084783271 -0.049871832, 0.084616244 0.0053000897 -0.049876332, 0.00048996508 0.08490248 -0.050061285, 0.084735006 0.0053077191 -0.050065771, 0.00049044192 0.08497633 -0.050272763, 0.084808975 0.0053121746 -0.050277337, 0.084221154 -0.00048337877 -0.049525127, 0.0062325448 0.083994359 -0.049520344, 0.084432572 -0.00048452616 -0.049599126, 0.0062482059 0.08420518 -0.049594268, 0.08462213 -0.00048553944 -0.049718171, 0.0062621534 0.084394336 -0.049713552, 0.084780484 -0.00048652291 -0.049876541, 0.0062739104 0.084552094 -0.049871877, 0.084899664 -0.00048738718 -0.050066113, 0.0062825829 0.084670976 -0.05006136, 0.084973678 -0.00048772991 -0.050277486, 0.0062882304 0.084744766 -0.050272793, 0.083991781 -0.0062296242 -0.049525529, 0.011949733 0.083373219 -0.049520388, 0.084202483 -0.0062454343 -0.04959932, 0.011979744 0.08358252 -0.049594373, 0.084391549 -0.0062593967 -0.049718544, 0.012006581 0.083770201 -0.049713507, 0.012029037 0.08392708 -0.049871847, 0.084549531 -0.0062709749 -0.049877003, 0.012046009 0.084044829 -0.05006142, 0.084668338 -0.0062798709 -0.050066635, 0.084741995 -0.0062852949 -0.050277904, 0.012056515 0.084118217 -0.050272748, 0.083370641 -0.011946991 -0.049525931, 0.017611206 0.082363471 -0.049520418, 0.083579719 -0.011976883 -0.049599811, 0.017655388 0.082570091 -0.049594447, 0.017695099 0.082755595 -0.049713463, 0.083767503 -0.012003809 -0.049718782, 0.083924219 -0.01202634 -0.049877331, 0.017728239 0.082910344 -0.049871892, 0.084042251 -0.012043148 -0.050066948, 0.017753243 0.083026946 -0.050061554, 0.084115312 -0.012053713 -0.050278261, 0.017768651 0.083099321 -0.050272778, -0.079195529 0.028664738 -0.049523532, 0.08236064 -0.017608449 -0.04952617, 0.023190513 0.080969766 -0.049520567, 0.023248807 0.081172779 -0.049594417, -0.079394266 0.0287368 -0.049597502, 0.082567453 -0.017652735 -0.049600095, 0.023301125 0.081355155 -0.049713627, -0.079572394 0.028801307 -0.049716547, 0.082752869 -0.017692223 -0.049719289, -0.079721525 0.028855085 -0.049874946, 0.023344636 0.081507191 -0.049872071, 0.082907647 -0.017725393 -0.049877658, -0.079833388 0.028895631 -0.05006443, 0.023377478 0.08162199 -0.050061673, -0.079902902 0.028920859 -0.050275907, 0.083024219 -0.017750308 -0.050067201, 0.023397878 0.081692964 -0.050272942, 0.028661996 0.079198286 -0.049520612, -0.077054739 0.034002513 -0.049523056, 0.083096504 -0.01776588 -0.050278649, -0.077248141 0.034087613 -0.049597189, 0.028734013 0.079396948 -0.049594432, 0.028798372 0.079575256 -0.049713671, -0.07742162 0.034164354 -0.049716353, 0.028852269 0.079724312 -0.049872085, -0.077566653 0.034228235 -0.049874559, -0.077675626 0.034276396 -0.050064102, 0.028892815 0.079836294 -0.050061747, -0.077743188 0.034306109 -0.050275519, 0.028918013 0.079905793 -0.050273076, -0.074555054 0.039181575 -0.049522817, 0.033999786 0.07705766 -0.04952085, -0.074742153 0.039280012 -0.049596846, 0.034084991 0.077250987 -0.049594626, -0.07491 0.039368257 -0.049716011, 0.034161597 0.077424437 -0.049713805, -0.075050294 0.039441735 -0.049874291, 0.034225687 0.077569321 -0.04987222, -0.07515569 0.039497271 -0.050064057, 0.03427349 0.077678427 -0.050061956, -0.075221032 0.039531574 -0.050275326, 0.034303382 0.077746227 -0.050273269, -0.071707651 0.044177979 -0.049522579, 0.039178923 0.074557737 -0.049520954, -0.071887523 0.044288799 -0.049596608, 0.039277181 0.074745014 -0.049594894, -0.072048932 0.044388294 -0.049715683, 0.039365515 0.074912697 -0.04971382, -0.072183847 0.044471517 -0.049874008, 0.039439097 0.075052947 -0.049872532, -0.072285369 0.044533908 -0.05006367, 0.03949447 0.075158492 -0.050062016, -0.072348163 0.04457286 -0.050274968, 0.039528817 0.075223923 -0.050273359, -0.068525791 0.048968583 -0.049522474, 0.044175342 0.071710333 -0.049521044, -0.0686979 0.049091622 -0.049596325, 0.044286326 0.07189025 -0.049595177, -0.068852037 0.049201578 -0.049715459, 0.044385806 0.07205157 -0.049714163, -0.068980932 0.049293891 -0.049873888, 0.044468686 0.072186485 -0.049872473, 0.044531211 0.072287947 -0.05006215, -0.069077834 0.049363077 -0.050063416, -0.06913799 0.049406096 -0.050274789, 0.04456991 0.07235086 -0.050273508, -0.065024689 0.053530902 -0.049522072, 0.048965871 0.068528518 -0.049521163, -0.065187827 0.053665236 -0.049596161, 0.049088791 0.068700507 -0.049595132, -0.065334141 0.053785726 -0.049715176, 0.049198985 0.068854794 -0.049714327, 0.049291015 0.068983629 -0.049872696, -0.065456331 0.053886279 -0.049873367, -0.065548286 0.053962037 -0.050063133, 0.049360201 0.069080725 -0.050062358, -0.065605476 0.054009065 -0.050274536, 0.049403325 0.069140822 -0.050273567, -0.06122008 0.057843462 -0.049521893, 0.053528011 0.065027341 -0.049521282, -0.061373547 0.057988465 -0.049595818, 0.053662509 0.065190479 -0.049595356, 0.05378294 0.065336794 -0.049714565, -0.061511368 0.058118805 -0.049714878, -0.061626583 0.058227673 -0.049873188, 0.053883523 0.065459177 -0.049872801, -0.061713383 0.058309361 -0.05006294, 0.05395928 0.065551013 -0.050062448, -0.061766908 0.058360159 -0.050274149, 0.054006204 0.065608248 -0.050273851, 0.057840645 0.061222881 -0.049521625, -0.057130203 0.061886474 -0.049521625, -0.057273418 0.0620417 -0.049595416, -0.057402015 0.062180951 -0.049714729, 0.057985768 0.061376408 -0.04959552, 0.058116093 0.061514229 -0.049714774, -0.057509482 0.062297329 -0.049873069, 0.058224782 0.06162934 -0.049873114, -0.057590157 0.062385008 -0.050062686, 0.058306605 0.061715916 -0.050062776, -0.057640344 0.062439173 -0.050273955, 0.058357447 0.061769634 -0.05027397, -0.052773833 0.065640852 -0.049521267, 0.061883703 0.05713293 -0.049521834, -0.052906498 0.065805718 -0.049595475, 0.062038884 0.057276294 -0.049595997, -0.053025126 0.065953389 -0.049714446, 0.062178195 0.057404891 -0.049714983, -0.053124398 0.066076696 -0.049872816, 0.062294632 0.057512268 -0.049873382, -0.053199098 0.066169664 -0.050062403, 0.062382206 0.057593077 -0.050062969, -0.053245172 0.066227287 -0.050273895, 0.062436506 0.057643294 -0.050274357, -0.04817155 0.069089323 -0.049521104, 0.065637961 0.052776679 -0.049522012, -0.048292488 0.069262564 -0.049595073, 0.065802917 0.052908957 -0.049596116, -0.0068444908 0.011536166 -0.028899416, -0.0063545555 0.010909081 -0.028899312, -0.0070569068 0.011324048 -0.028599426, -0.0066115111 0.010754213 -0.028599545, -0.0060290098 0.010183275 -0.028899342, -0.006315574 0.010094315 -0.028599545, -0.00588651 0.0094004571 -0.028899327, -0.0061860681 0.0093827397 -0.028599501, -0.0059354603 0.0086063743 -0.028899476, -0.0062305778 0.0086608827 -0.028599575, -0.0061733127 0.007847324 -0.028899565, -0.0064465702 0.0079707205 -0.028599501, -0.0068215728 0.0073523223 -0.028599679, -0.006585598 0.0071669966 -0.028899729, -0.0073335767 0.006841585 -0.028599679, -0.007148847 0.0066051632 -0.02889961, -0.0079529136 0.0064681321 -0.02859959, -0.0078301877 0.0061944127 -0.02889967, -0.0086438209 0.0062540025 -0.02859965, -0.0085901022 0.0059588552 -0.028899685, -0.0093658268 0.0062112361 -0.02859965, -0.0093842447 0.0059117526 -0.02889964, -0.010076925 0.0063424706 -0.02859962, -0.010166571 0.0060561597 -0.028899863, -0.010736033 0.0066400766 -0.028599635, -0.010891631 0.0063835979 -0.028899729, -0.011304975 0.0070868284 -0.02859965, -0.011517212 0.0068750083 -0.028899759, -0.011589006 0.0069491714 -0.028899729, -0.0116584 0.007025525 -0.028899729, -0.011725321 0.0071042478 -0.02889964, -0.01164037 0.0074878037 -0.02859965, -0.011840492 0.0075356364 -0.028740138, -0.011901394 0.0079410225 -0.02859965, -0.011958465 0.0079784691 -0.028636292, -0.012079567 0.0084326565 -0.028599665, 0.010225013 0.0010199845 -0.028900057, 0.0099977702 0.0017923415 -0.028600037, 0.010437295 0.0012319982 -0.028600097, 0.0097326189 0.0016509295 -0.028899908, 0.0097026676 0.0024407506 -0.028599948, 0.009406656 0.0023819208 -0.028899789, 0.0095687062 0.0031402409 -0.028599963, 0.0092661977 0.0031700134 -0.028899774, 0.009603411 0.0038518757 -0.028599933, 0.0093196929 0.0039687008 -0.028899804, 0.0098049194 0.00453493 -0.028599828, 0.0095638186 0.0047310293 -0.028899819, 0.010161832 0.0051513314 -0.028599814, 0.0099842399 0.0054119974 -0.028899759, 0.010654166 0.0056661963 -0.028599843, 0.010556504 0.0059717745 -0.028899759, 0.011253744 0.006050542 -0.028599679, 0.011246607 0.0063771605 -0.02889958, 0.011927202 0.0062828511 -0.028599605, 0.012013957 0.0066048205 -0.02889967, 0.012444973 0.0064888597 -0.028740019, 0.012636408 0.0063497126 -0.028599694, 0.012887478 0.00636971 -0.028636321, 0.013341382 0.0062473118 -0.028599858, 0.011324197 -0.039650515 -0.025511861, 0.010992065 -0.039370865 -0.02551201, 0.011331007 -0.039643735 -0.025609493, 0.010997653 -0.03936322 -0.025609449, 0.011304051 -0.039670557 -0.025418118, 0.010975733 -0.039394334 -0.025417998, 0.010211095 -0.038995162 -0.025609255, 0.010616392 -0.039153486 -0.025511861, 0.010208592 -0.03900443 -0.02551192, 0.01062049 -0.039144665 -0.025609449, 0.010913327 -0.039483026 -0.025255933, 0.010949016 -0.039432064 -0.025331527, 0.011227325 -0.039747044 -0.025255844, 0.011271328 -0.039703116 -0.025331646, 0.010604411 -0.039179146 -0.025418073, 0.010201201 -0.039032042 -0.025417954, 0.010189131 -0.039076552 -0.025331527, 0.010584652 -0.039221123 -0.025331497, 0.010173008 -0.039136574 -0.025255829, 0.010558367 -0.039277464 -0.025255814, -0.029821128 -0.031764269 -0.023986101, -0.029977977 -0.031564251 -0.023986101, -0.029759765 -0.031703129 -0.023939967, -0.029904112 -0.031519383 -0.023939893, -0.030042693 -0.031603709 -0.024048373, -0.029853955 -0.031063735 -0.02390191, -0.029940948 -0.030859426 -0.023911461, -0.02984482 -0.030875579 -0.023901731, -0.029951379 -0.031070545 -0.023911431, -0.030000955 -0.031306908 -0.023939952, -0.030044883 -0.031077236 -0.023939788, -0.029911548 -0.031278118 -0.023911491, -0.030155674 -0.031355873 -0.024048269, -0.030083328 -0.031332999 -0.023986116, -0.029881254 -0.030656502 -0.023911446, -0.029791519 -0.030695096 -0.02390191, -0.030033499 -0.030843884 -0.023939922, -0.03020665 -0.031088531 -0.024048224, -0.030131057 -0.031083301 -0.023986056, -0.029874742 -0.031817794 -0.024048358, -0.029775247 -0.030473575 -0.023911402, -0.02969712 -0.030532211 -0.023901761, -0.029967323 -0.030619547 -0.023939922, -0.030193359 -0.030816495 -0.024048209, -0.030118674 -0.03082934 -0.023986176, -0.029629067 -0.030320898 -0.023911461, -0.029567137 -0.030396044 -0.023901775, -0.029850185 -0.030417442 -0.023939937, -0.030046776 -0.030585408 -0.023986027, -0.030116379 -0.030555442 -0.024048105, -0.029451087 -0.0302068 -0.023911253, -0.029408529 -0.030294538 -0.023901746, -0.029688716 -0.030248314 -0.023939937, -0.029919356 -0.030365586 -0.023985982, -0.029979989 -0.030319959 -0.024048254, -0.029251292 -0.030137762 -0.023911357, -0.029230669 -0.030233085 -0.023901761, -0.029492021 -0.030122429 -0.023939863, -0.029743701 -0.030181572 -0.023986027, -0.029791892 -0.030123174 -0.024048269, -0.028856829 -0.030242577 -0.023901761, -0.029040784 -0.030118123 -0.023911387, -0.028831467 -0.030148357 -0.023911461, -0.029043287 -0.030215576 -0.023901835, -0.029034331 -0.029862061 -0.024048299, -0.028764948 -0.029901117 -0.024048358, -0.028784588 -0.029974222 -0.023986042, -0.029693455 -0.031637013 -0.023911536, -0.029824063 -0.031470656 -0.023911431, -0.029624373 -0.031568199 -0.023901775, -0.029271021 -0.030046046 -0.023939848, -0.029740646 -0.031420037 -0.02390188, -0.029562756 -0.029976279 -0.024048135, -0.029529706 -0.030044377 -0.023986012, -0.02981849 -0.031248778 -0.02390182, -0.029038459 -0.03002429 -0.023939937, -0.028807074 -0.030057818 -0.023939893, -0.029305264 -0.029887706 -0.02404812, -0.029289484 -0.02996169 -0.023985967, -0.029036224 -0.029937759 -0.023986027, -0.041782543 0.012299642 -0.024045914, -0.041707188 0.012308121 -0.023983628, -0.041725606 0.012049437 -0.024045795, -0.041654125 0.012074441 -0.023983687, -0.041572511 0.012102678 -0.023937404, -0.041621298 0.012317538 -0.023937315, -0.041203082 0.012988001 -0.023899347, -0.041396424 0.012901381 -0.023909062, -0.04127194 0.013057083 -0.023908943, -0.041391179 0.012689516 -0.023899376, -0.041313827 0.012849256 -0.023899347, -0.041483179 0.012721717 -0.023908883, -0.041527793 0.012527362 -0.023909003, -0.041571707 0.012752786 -0.023937494, -0.04162091 0.01253809 -0.023937374, -0.041782081 0.012556493 -0.02404587, -0.04170689 0.01254788 -0.023983598, -0.041475713 0.012951225 -0.023937404, -0.041338146 0.013123497 -0.023937404, -0.041724771 0.012806758 -0.024045914, -0.041653171 0.012781516 -0.023983642, -0.041549012 0.012997434 -0.023983613, -0.041399226 0.013184682 -0.023983508, -0.041613102 0.013037682 -0.024045691, -0.04145278 0.013238221 -0.024045691, -0.041273445 0.011797652 -0.023908988, -0.041397601 0.011953846 -0.023909137, -0.041204423 0.011866689 -0.023899287, -0.0413149 0.012005597 -0.023899332, -0.041483849 0.012133479 -0.023909047, -0.041391805 0.012165606 -0.023899361, -0.041339919 0.01173149 -0.023937449, -0.041477114 0.011903957 -0.023937434, -0.041528046 0.012328029 -0.023908898, -0.041431159 0.012338892 -0.023899257, -0.041614458 0.011817783 -0.024045795, -0.041550338 0.01185818 -0.023983672, -0.041454792 0.01161696 -0.02404587, -0.041401088 0.01167047 -0.023983553, -0.041430846 0.012516439 -0.023899302, -0.012056977 0.04301399 -0.025251195, -0.012049764 0.043075889 -0.025326863, -0.011543319 0.042896137 -0.02525112, -0.01152271 0.042954713 -0.025326833, -0.011507392 0.042998239 -0.025413513, -0.012044683 0.043121621 -0.02541329, -0.014088869 0.042445645 -0.025604695, -0.013645753 0.042785868 -0.025507137, -0.014082104 0.042438686 -0.025507197, -0.013146251 0.043036193 -0.025604695, -0.01365079 0.042794004 -0.025604591, -0.013142958 0.043027297 -0.025507316, -0.01259917 0.043150663 -0.025507301, -0.013133645 0.043000281 -0.025413319, -0.012596056 0.043122351 -0.025413379, -0.012583867 0.043014586 -0.025251344, -0.012590781 0.043076381 -0.025326967, -0.013630733 0.042761907 -0.025413215, -0.014062092 0.042418703 -0.025413454, -0.013098016 0.042898074 -0.025251299, -0.013118342 0.042956725 -0.025327012, -0.013606146 0.042722672 -0.025326937, -0.014029339 0.042385831 -0.025327027, -0.0135732 0.042669982 -0.025251284, -0.0139855 0.042341903 -0.025251225, -0.010560215 0.042434216 -0.025507227, -0.010995835 0.04278256 -0.025507241, -0.010553375 0.042441055 -0.025604725, -0.010990709 0.042790651 -0.025604799, -0.011497915 0.043025091 -0.025507301, -0.011494756 0.043034166 -0.025604725, -0.010580406 0.042414144 -0.025413364, -0.011010885 0.04275839 -0.02541326, -0.012041479 0.043149963 -0.025507316, -0.012040421 0.043159485 -0.025604695, -0.011068732 0.042666718 -0.025251225, -0.011035621 0.042719573 -0.025326893, -0.010657072 0.042337671 -0.025251269, -0.010613054 0.0423816 -0.025326818, -0.012600273 0.043160215 -0.025604695, 0.032825261 0.030725494 -0.025413945, 0.032342166 0.031048104 -0.025327742, 0.032366291 0.031087309 -0.02541402, 0.032309607 0.030995071 -0.025251791, 0.032792494 0.030692905 -0.025327787, 0.03126362 0.031480193 -0.025605366, 0.030672356 0.031443223 -0.025507897, 0.030670583 0.031452745 -0.02560541, 0.031262949 0.031470582 -0.025507897, 0.031834856 0.031331033 -0.02541405, 0.031260952 0.031442344 -0.02541393, 0.031843543 0.03135787 -0.025507897, 0.031801671 0.031227767 -0.02525185, 0.0318207 0.03128691 -0.025327682, 0.030104786 0.03127721 -0.025507808, 0.030100837 0.03128624 -0.025605366, 0.030676916 0.031415209 -0.025414154, 0.03125304 0.031334206 -0.02525194, 0.031257525 0.031396106 -0.025327474, 0.03274855 0.030649021 -0.025251865, 0.029592156 0.030982316 -0.025507852, 0.029586494 0.030990079 -0.025605351, 0.030115828 0.031251132 -0.02541399, 0.030694768 0.031308368 -0.025251821, 0.030684546 0.031369597 -0.025327802, 0.029163793 0.030574828 -0.025507987, 0.029156372 0.030580834 -0.025605351, 0.029609233 0.030959576 -0.025414005, 0.030134022 0.031208768 -0.025327563, 0.03015843 0.031151488 -0.02525191, 0.028843492 0.030077785 -0.025508016, 0.028834805 0.030081838 -0.025605395, 0.029185623 0.030556768 -0.02541405, 0.029636964 0.030922472 -0.025327727, 0.029674187 0.030872643 -0.02525191, 0.028582931 0.028930321 -0.025605515, 0.028675944 0.028345212 -0.025508076, 0.028666601 0.028342739 -0.025605604, 0.028649345 0.02951926 -0.025508016, 0.028640002 0.029521212 -0.025605619, 0.028869048 0.030065238 -0.025413945, 0.029221281 0.030527249 -0.025327727, 0.029269263 0.030487537 -0.025251806, 0.028592363 0.028930694 -0.025508076, 0.028703406 0.028352559 -0.025414154, 0.032845393 0.0307457 -0.025507852, 0.032381043 0.031111643 -0.025507763, 0.032852277 0.030752271 -0.02560541, 0.032386065 0.031120002 -0.025605395, 0.028677285 0.02951321 -0.025414139, 0.028966457 0.030017957 -0.025251985, 0.028910607 0.030045077 -0.025327757, 0.031846404 0.031367227 -0.025605321, 0.028620914 0.02893126 -0.025414094, 0.028747961 0.02836442 -0.025327772, 0.028722346 0.029503196 -0.025327697, 0.028783068 0.029490054 -0.025252044, 0.028667152 0.028932348 -0.025327802, 0.028808117 0.028380394 -0.025252044, 0.028729171 0.028933853 -0.025252104, 0.040574938 -0.010472953 -0.024047181, 0.040446669 -0.010319784 -0.024047077, 0.040628582 -0.010419279 -0.023984835, 0.04034704 -0.010146528 -0.024047092, 0.040278912 -0.0099587142 -0.024047077, 0.040352076 -0.009939 -0.023984864, 0.040756285 -0.010292202 -0.023910329, 0.040656582 -0.010173157 -0.023910299, 0.040825233 -0.010223299 -0.023900598, 0.040736541 -0.010117292 -0.023900688, 0.040689766 -0.010358453 -0.023938671, 0.040579647 -0.01022695 -0.023938805, 0.040620461 -0.0098674446 -0.023900554, 0.04057911 -0.010038525 -0.023910254, 0.040526286 -0.0098926276 -0.023910299, 0.040435627 -0.0099168122 -0.023938701, 0.040667683 -0.0099974722 -0.023900583, 0.040508807 -0.010276422 -0.023984879, 0.040494069 -0.010078177 -0.023938701, 0.04041563 -0.010114565 -0.023984894, 0.037194207 0.037102625 -0.027150616, 0.033913806 0.04012312 -0.027150169, 0.037407577 0.037315622 -0.027053133, -0.040653288 -0.034187689 -0.026913345, -0.037788779 -0.03769277 -0.026726797, -0.040849343 -0.034352198 -0.026726678, -0.037607506 -0.03751196 -0.026913494, -0.040437266 -0.034005672 -0.027056962, -0.040206388 -0.033811793 -0.027154371, -0.037194103 -0.037099555 -0.02715461, -0.037407517 -0.037312537 -0.027057201, -0.043406188 -0.030616686 -0.026912883, -0.04361552 -0.030764401 -0.026726365, -0.043175533 -0.030453995 -0.027056679, -0.042929217 -0.030280143 -0.027154028, -0.045846477 -0.026825145 -0.026912823, -0.046067491 -0.026954696 -0.026726261, -0.045602724 -0.026682645 -0.027056679, -0.045342624 -0.026530534 -0.027153954, -0.047956362 -0.02284053 -0.026912615, -0.048187628 -0.022950709 -0.026725993, -0.047701567 -0.02271913 -0.027056277, -0.047429249 -0.022589594 -0.027153835, -0.049720928 -0.018691286 -0.026912332, -0.049960464 -0.018781438 -0.026725769, -0.049456641 -0.018591985 -0.027056038, -0.049174368 -0.018485904 -0.027153417, -0.051127002 -0.014407292 -0.026912212, -0.051373288 -0.014476866 -0.026725665, -0.050855264 -0.014330566 -0.027055949, -0.050565049 -0.014249057 -0.027153328, -0.052164868 -0.010019481 -0.02691181, -0.052416176 -0.010067895 -0.026725307, -0.051887393 -0.0099662989 -0.027055651, -0.051591188 -0.0099093616 -0.027152956, -0.052826509 -0.0055596083 -0.026911527, -0.053081304 -0.0055864304 -0.026724905, -0.052545801 -0.0055299997 -0.027055383, -0.052245915 -0.0054983646 -0.027152777, -0.053107917 -0.0010594875 -0.026911393, -0.053363904 -0.001064539 -0.026724726, -0.052825645 -0.0010538399 -0.027055085, -0.052524075 -0.0010477901 -0.027152568, -0.053006634 0.0034481883 -0.02691108, -0.05326207 0.0034646839 -0.026724473, -0.052724794 0.0034297258 -0.027054787, -0.052424043 0.0034102499 -0.027152196, -0.05252327 0.0079310089 -0.026910856, -0.052776456 0.0079691708 -0.026724279, -0.052244112 0.0078889281 -0.027054727, -0.051946089 0.0078437626 -0.027152196, -0.05166164 0.012356564 -0.026910514, -0.051910669 0.012416273 -0.026724011, -0.051387012 0.012291148 -0.027054474, -0.051093832 0.012220964 -0.027151689, -0.050427452 0.016693503 -0.02691038, -0.050670728 0.016773894 -0.026723787, -0.050159559 0.016604736 -0.027054071, -0.049873367 0.01650998 -0.02715148, -0.048830375 0.020909876 -0.026910096, -0.049065933 0.021010652 -0.026723504, -0.048570901 0.020798847 -0.027053922, -0.048293844 0.02068004 -0.027151361, -0.046881422 0.024975777 -0.026909828, -0.047107249 0.025096148 -0.026723295, -0.046632141 0.024842992 -0.027053669, -0.046366155 0.024701327 -0.027151063, -0.044594467 0.028861493 -0.026909724, -0.044809461 0.029000625 -0.026723012, -0.044357494 0.028708041 -0.027053446, -0.044104517 0.028544396 -0.027150869, -0.041986227 0.032539323 -0.026909366, -0.042188734 0.032696322 -0.026722819, -0.041763112 0.03236647 -0.027053192, -0.041524827 0.032181799 -0.027150586, -0.039075643 0.035982952 -0.026909351, -0.039264143 0.036156371 -0.026722699, -0.03886801 0.03579177 -0.027053013, -0.038646236 0.035587549 -0.027150542, -0.035883367 0.039167017 -0.026908979, -0.036056444 0.039355859 -0.026722476, -0.035692647 0.038959011 -0.027052924, -0.035489082 0.038736701 -0.027150318, -0.03243269 0.042069227 -0.026908845, -0.032589123 0.042272076 -0.026722386, -0.032260299 0.041845694 -0.027052566, -0.032076299 0.041606709 -0.027150154, -0.028748274 0.044668123 -0.026908696, -0.028886884 0.0448834 -0.026722118, -0.028595433 0.044430599 -0.027052552, -0.02843225 0.044177234 -0.027149975, -0.024856761 0.046945289 -0.026908532, -0.024976552 0.047171578 -0.026721999, -0.024724528 0.046695724 -0.027052388, -0.024583608 0.046429411 -0.027149871, -0.020786032 0.048884124 -0.026908532, -0.020886362 0.049119756 -0.026722103, -0.02067554 0.048624337 -0.027052343, -0.020557553 0.048346981 -0.027149901, -0.016565621 0.050470814 -0.026908472, -0.016645461 0.050714165 -0.02672191, -0.016477555 0.050202623 -0.027052298, -0.016383559 0.049916252 -0.027149692, -0.012225896 0.051693901 -0.026908353, -0.012284815 0.051943108 -0.026721761, -0.012160912 0.051419184 -0.027052194, -0.012091458 0.05112572 -0.027149498, -0.0077979863 0.05254443 -0.026908308, -0.0078356415 0.052797809 -0.026721761, -0.0077565312 0.052265182 -0.027052149, -0.0077122599 0.051966891 -0.027149573, -0.0033139288 0.053016335 -0.026908234, -0.0033298284 0.053272218 -0.026721671, -0.0032963008 0.052734762 -0.027052075, -0.0032774359 0.052433833 -0.027149439, 0.0011940151 0.053106517 -0.026908368, 0.0011998117 0.053362548 -0.026721746, 0.0011876374 0.052824274 -0.027052149, 0.0011807382 0.052523077 -0.027149543, 0.0056933165 0.052814022 -0.026908323, 0.0057207048 0.053068578 -0.026721597, 0.0056630969 0.052533314 -0.027052119, 0.0056307465 0.052233502 -0.027149498, 0.010151699 0.052140996 -0.026908487, 0.010200575 0.052392259 -0.026721731, 0.010097757 0.051863834 -0.027052253, 0.010040119 0.051567942 -0.027149543, 0.014536783 0.051092297 -0.026908413, 0.014606833 0.051338315 -0.026721686, 0.014459565 0.050820693 -0.027052164, 0.014377058 0.050530776 -0.027149752, 0.018817201 0.049675331 -0.026908383, 0.018907875 0.049914882 -0.026721939, 0.01871717 0.049411386 -0.027052402, 0.018610463 0.049129456 -0.027149737, 0.022962138 0.047900498 -0.026908532, 0.023072794 0.048131421 -0.026722118, 0.022839963 0.047645956 -0.027052566, 0.022709787 0.047374129 -0.027149856, 0.026941404 0.045780659 -0.026908785, 0.027071431 0.046001419 -0.026722118, 0.026798353 0.045537457 -0.027052671, 0.026645318 0.045277655 -0.02715002, 0.030726805 0.043330953 -0.0269088, 0.030874908 0.043539986 -0.026722193, 0.030563504 0.04310067 -0.027052656, 0.030388981 0.042854726 -0.027150139, 0.034290656 0.040569022 -0.026909158, 0.034456 0.04076466 -0.026722312, 0.037788868 0.037695795 -0.02672264, 0.037607566 0.03751494 -0.026909187, 0.03410849 0.040353462 -0.02705279, -0.044509768 -0.013676494 -0.025400802, -0.044997647 -0.013062984 -0.025400802, -0.044509903 -0.013676852 -0.015400857, -0.044997588 -0.013063535 -0.015400887, -0.045336902 -0.012356982 -0.015400842, -0.045336932 -0.012356505 -0.025400728, -0.045510426 -0.011592612 -0.015400872, -0.045510396 -0.01159215 -0.025400609, -0.045509398 -0.010808393 -0.025400564, -0.045509338 -0.010809049 -0.015400559, -0.045333952 -0.01004447 -0.025400639, -0.045333907 -0.010045066 -0.015400603, -0.044992983 -0.0093387365 -0.025400639, -0.044992954 -0.0093393326 -0.015400589, -0.04450351 -0.008726567 -0.025400534, -0.04450357 -0.0087273419 -0.015400574, -0.029973045 -0.034387693 -0.024987698, -0.029430792 -0.032373905 -0.022901922, -0.029662296 -0.032289237 -0.022901848, -0.030546054 -0.034178495 -0.024987772, -0.029875591 -0.032165751 -0.022901729, -0.031074107 -0.033872634 -0.024987698, -0.031541079 -0.033479825 -0.024987713, -0.030064255 -0.032006994 -0.022901893, 0.044362605 -0.0095371008 -0.02446492, 0.044805661 -0.010411456 -0.02498652, 0.044885695 -0.009584412 -0.024986461, 0.044768453 -0.0087615848 -0.024986282, 0.042753041 -0.0092991441 -0.022900522, 0.043320477 -0.0095812976 -0.023422092, 0.043805763 -0.010092944 -0.023943573, 0.040344492 -0.011294544 -0.023422211, 0.040954322 -0.011009961 -0.022900611, 0.040649086 -0.010870069 -0.02290085, 0.040385365 -0.010662138 -0.022900596, 0.038908705 -0.012134939 -0.024986491, 0.040543318 -0.011971146 -0.023943588, 0.039783061 -0.012173295 -0.024465024, 0.039561316 -0.012649566 -0.024986669, 0.040316716 -0.012995839 -0.02498664, 0.042768151 -0.0099658072 -0.022900507, 0.042657956 -0.010283098 -0.022900745, 0.044532955 -0.011196479 -0.02498661, 0.043397591 -0.011075169 -0.023943648, 0.042476028 -0.010565013 -0.022900611, 0.042232662 -0.01079677 -0.022900641, 0.043480545 -0.012467816 -0.024986595, 0.044082746 -0.011895195 -0.024986595, 0.042612448 -0.011792704 -0.023943767, 0.041941687 -0.01096417 -0.022900596, 0.042760402 -0.012882352 -0.024986669, 0.041597739 -0.012111291 -0.023943648, 0.041619375 -0.011058375 -0.022900686, 0.04128404 -0.011073947 -0.022900745, 0.041132614 -0.013154104 -0.02498661, 0.041962743 -0.013115421 -0.024986431, 0.042800441 -0.0096314549 -0.022900626, -0.039705783 0.010155424 -0.023942381, -0.040177643 0.011090949 -0.022899434, -0.040486515 0.011020884 -0.022899404, -0.040255576 0.0089481175 -0.024985254, -0.039491341 0.0091216415 -0.024985418, -0.040646166 0.0099695027 -0.023942545, -0.04080312 0.011021525 -0.022899345, -0.041039303 0.0089492351 -0.024985582, -0.04158619 0.010157749 -0.023942262, -0.041111887 0.011092037 -0.022899434, -0.041803181 0.0091243833 -0.024985224, -0.039569691 0.010815799 -0.023420975, -0.039644375 0.011425018 -0.022899389, -0.039892137 0.011228025 -0.02289927, -0.038991377 0.0099480152 -0.024463847, -0.038784668 0.0094606727 -0.024985328, -0.038171321 0.0099486113 -0.024985299, -0.04172045 0.010818541 -0.023421004, -0.041396871 0.011229888 -0.022899419, -0.041644305 0.01142773 -0.022899389, -0.043121159 0.0099548995 -0.024985299, -0.04230094 0.0099520385 -0.024463728, -0.0425089 0.0094652772 -0.02498515, -0.0063488185 0.012030244 -0.025399387, -0.0063488483 0.012030348 -0.027899399, -0.0068823844 0.012479261 -0.027899474, -0.0071070939 0.012625873 -0.025399357, -0.0074858665 0.012828693 -0.027899265, -0.0090482384 0.013203323 -0.029977471, -0.0081408173 0.013067871 -0.027899414, -0.0081406683 0.013067961 -0.029819772, -0.0079859495 0.013022527 -0.025399372, -0.0089343041 0.013197646 -0.025399238, -0.0098970681 0.013140708 -0.025399387, -0.0099702477 0.013126954 -0.03010577, -0.010818005 0.012854874 -0.025399432, -0.010851219 0.012840167 -0.030195966, -0.011643797 0.01235725 -0.025399387, -0.011645183 0.012356043 -0.030243054, -0.012308776 0.011698827 -0.030243799, -0.012326583 0.011676207 -0.025399268, -0.012800649 0.01090762 -0.030197948, -0.012826264 0.010851428 -0.025399506, -0.013095066 0.010029122 -0.030108988, -0.013114333 0.0099312812 -0.025399521, -0.013179719 0.0091080815 -0.029981688, -0.013045833 0.00817509 -0.027899548, -0.013140425 0.0086385012 -0.029904559, -0.013045698 0.0081750453 -0.029819995, -0.013173744 0.0089688748 -0.025399432, -0.013001233 0.0080200881 -0.025399625, -0.012808219 0.0075195879 -0.027899697, -0.012606427 0.0071402192 -0.02539967, -0.012460291 0.0069153011 -0.027899683, -0.012012824 0.0063804239 -0.025399745, -0.012012675 0.0063805729 -0.027899742, 0.015393361 0.0061752945 -0.025399789, 0.015393227 0.0061753392 -0.030134216, 0.014858484 0.0066253245 -0.030048147, 0.014634922 0.0067709386 -0.02539973, 0.014252603 0.0069756508 -0.029941693, 0.013601393 0.0072128624 -0.027899593, 0.013601527 0.0072129816 -0.02982001, 0.013756096 0.0071677268 -0.025399655, 0.012807772 0.0073427558 -0.025399595, 0.012661517 0.0073492378 -0.027899697, 0.011845261 0.0072856843 -0.02539973, 0.011716023 0.007260263 -0.027899653, 0.01092422 0.0070000589 -0.02539967, 0.010818154 0.0069506466 -0.027899653, 0.010098368 0.0065021515 -0.02539973, 0.010018498 0.0064380318 -0.027899653, 0.0094156712 0.0058211684 -0.02539973, 0.0093621463 0.0057515353 -0.027899593, 0.0089157522 0.004996568 -0.025399715, 0.0088863075 0.0049296767 -0.027899697, 0.0086277574 0.0040763319 -0.025399819, 0.0086174607 0.0040187836 -0.027899876, 0.0085683763 0.0031138659 -0.025399864, 0.008571133 0.0030701607 -0.027900025, 0.0087410212 0.0021650195 -0.025399938, 0.0087497383 0.0021372288 -0.027899861, 0.0091355592 0.001285404 -0.025400087, 0.009143129 0.0012727529 -0.027900055, 0.0097292513 0.00052563846 -0.025400013, 0.009729296 0.00052550435 -0.02790007, -0.0012942106 -0.0091382563 -0.027900636, -0.00054825842 -0.0097265989 -0.025400534, -0.00054828823 -0.0097264051 -0.027900577, -0.0013067126 -0.0091309547 -0.025400624, -0.0021576881 -0.0087426752 -0.027900666, -0.0021855384 -0.0087340623 -0.025400579, -0.0030899793 -0.0085617453 -0.027900472, -0.003133744 -0.0085590333 -0.02540049, -0.0040387064 -0.0086057931 -0.027900696, -0.0040963739 -0.0086161345 -0.025400594, -0.0049501657 -0.0088722855 -0.027900562, -0.0050173402 -0.0089018047 -0.025400713, -0.0057733655 -0.0093461424 -0.027900517, -0.0058432668 -0.0093995631 -0.025400519, -0.0064615458 -0.01000081 -0.027900621, -0.0065259337 -0.010080442 -0.025400653, -0.0069760233 -0.010799184 -0.027900651, -0.0070257336 -0.010905191 -0.025400534, -0.0072878897 -0.01169607 -0.027900726, -0.0073138475 -0.011825398 -0.025400743, -0.0073793083 -0.0126414 -0.027900755, -0.0072452873 -0.013581753 -0.02790089, -0.0072451681 -0.013581693 -0.029821217, -0.0070082098 -0.014235795 -0.029943451, -0.0073731989 -0.012788147 -0.025400847, -0.0072006285 -0.013736725 -0.025400788, -0.0068060458 -0.014616445 -0.025400966, -0.0066616833 -0.014838427 -0.030049071, -0.0062122941 -0.015376419 -0.025400877, -0.0062122494 -0.01537621 -0.030135363, 0.0091785491 -0.016857505 -0.030883253, 0.0066857338 -0.017992049 -0.030883193, 0.0092354715 -0.016962066 -0.03088434, 0.0067272484 -0.018103734 -0.03088443, 0.0066043884 -0.017773226 -0.030838639, 0.0066445917 -0.017881498 -0.030868083, 0.0091219842 -0.016753808 -0.030867964, 0.0040076375 -0.018532008 -0.030838832, 0.0040569305 -0.018760413 -0.030883387, 0.0040820837 -0.018876836 -0.030884415, 0.0013291538 -0.018913746 -0.030838788, 0.0040319115 -0.018645018 -0.030868009, 0.013425097 0.013393104 -0.030837148, 0.015194178 0.011346266 -0.030837178, 0.013506874 0.013474688 -0.030866221, 0.0013455153 -0.01914686 -0.030883297, 0.0013537705 -0.019265547 -0.03088443, 0.013590515 0.01355806 -0.030881703, 0.015381366 0.011486024 -0.030881613, 0.013674796 0.013642088 -0.030882701, -0.0013763011 -0.018910512 -0.030838847, 0.0013371557 -0.019028887 -0.030868024, 0.015476689 0.011557207 -0.030882806, 0.016654089 0.0090684146 -0.030837253, 0.015286833 0.011415258 -0.03086637, -0.0013933182 -0.019143462 -0.030883417, -0.0014018714 -0.01926218 -0.03088446, -0.0040538311 -0.018522084 -0.030838698, -0.00138475 -0.01902549 -0.030867979, 0.016859129 0.0091801435 -0.030881777, 0.016963691 0.0092370808 -0.030882895, 0.016755462 0.0091236383 -0.030866429, 0.01777491 0.0066059828 -0.030837536, -0.0041036904 -0.018750131 -0.030883327, -0.0041291714 -0.018866584 -0.03088443, 0.017993778 0.0066874772 -0.030881986, -0.0066488087 -0.017756462 -0.030838698, -0.0040785223 -0.018634841 -0.030867964, 0.018105477 0.006728828 -0.030883014, 0.018533781 0.0040091276 -0.030837595, 0.017883092 0.0066462159 -0.030866742, -0.0067306608 -0.017975435 -0.030883238, -0.0067723393 -0.018086806 -0.03088443, -0.006689325 -0.0178646 -0.030867979, 0.01876229 0.0040584505 -0.030882105, -0.0091083944 -0.016629621 -0.030838564, 0.018878624 0.0040836185 -0.030883104, 0.018646717 0.0040335357 -0.030866757, -0.0092205554 -0.016834512 -0.030883238, 0.018915594 0.0013305992 -0.030837774, -0.0092777759 -0.016938984 -0.03088434, -0.0091638118 -0.01673083 -0.030867919, 0.019148722 0.0013470799 -0.030882254, 0.01926747 0.0013554841 -0.030883268, -0.011382595 -0.015163958 -0.030838624, 0.019030705 0.0013387352 -0.030866846, -0.013674617 -0.013638824 -0.030884057, -0.011522695 -0.015350923 -0.030883253, -0.013590351 -0.013554856 -0.030882969, 0.018912256 -0.0013748407 -0.030837834, -0.011594132 -0.015446037 -0.030884326, 0.019145072 -0.0013916194 -0.030882239, 0.019263998 -0.0014003962 -0.030883506, -0.011451885 -0.01525633 -0.030867785, -0.013506636 -0.013471276 -0.030867755, -0.013425037 -0.013389871 -0.030838475, 0.018523723 -0.0040522665 -0.030838013, 0.019027367 -0.0013831854 -0.0308671, 0.018751919 -0.0041022152 -0.030882612, 0.018868282 -0.0041275471 -0.03088364, 0.017758295 -0.0066471398 -0.030838117, 0.018636495 -0.0040767342 -0.030867264, 0.017976999 -0.0067290217 -0.030882671, 0.018088564 -0.0067707002 -0.030883729, 0.016631365 -0.0091068894 -0.030838221, 0.017866522 -0.0066875815 -0.030867338, 0.016836166 -0.0092189014 -0.030882776, 0.016940773 -0.0092761368 -0.030883878, 0.015165836 -0.011380836 -0.0308384, 0.016732663 -0.0091623813 -0.030867413, 0.015352622 -0.011521041 -0.030883059, 0.01544781 -0.011592448 -0.030883998, 0.013391495 -0.013423339 -0.030838549, 0.015258163 -0.011450142 -0.030867741, 0.013556585 -0.013588756 -0.030883104, 0.013640553 -0.013672933 -0.030884102, 0.011344746 -0.015192643 -0.030838639, 0.013473004 -0.013504997 -0.030867741, 0.011484325 -0.015379623 -0.030883178, 0.011555552 -0.015475079 -0.030884281, 0.011413679 -0.015285 -0.030867934, 0.0090668648 -0.016652495 -0.030838683, 0.016142532 0.043292597 -0.015397653, 0.016142488 0.043293193 -0.027208924, 0.015845791 0.044111729 -0.027069315, 0.015845522 0.044111863 -0.015397623, 0.015412539 0.044864684 -0.026948825, 0.015410647 0.044867367 -0.015397578, 0.014851183 0.045536205 -0.026850134, 0.014851227 0.045535535 -0.015397459, -0.037183881 -0.010429442 -0.028444648, -0.037307903 -0.010277763 -0.028437138, -0.03718397 -0.010429546 -0.025400639, -0.037323266 -0.01025416 -0.025400668, -0.037400171 -0.01010485 -0.028433099, -0.037420049 -0.010052383 -0.025400579, -0.037463605 -0.0098785907 -0.028432816, -0.037469745 -0.0098339468 -0.025400579, -0.037472621 -0.0096435547 -0.02843748, -0.037469491 -0.0096101314 -0.025400415, -0.037426591 -0.0094131976 -0.028446957, -0.037419245 -0.0093919039 -0.025400624, -0.037327915 -0.0091992766 -0.028460652, -0.03732194 -0.0091901571 -0.025400534, -0.037182197 -0.009015128 -0.028477803, -0.037182048 -0.0090153068 -0.025400564, 0.020985752 -0.0095620155 -0.030657485, 0.021393612 -0.0086109936 -0.030657306, 0.015984431 -0.024381265 -0.030123845, 0.013109848 -0.01897186 -0.030657843, 0.012245327 -0.019540951 -0.030657932, 0.021948755 -0.0070777535 -0.030657038, 0.021758467 -0.0076425225 -0.030657157, 0.022576421 -0.0094285756 -0.030552372, 0.01810126 -0.024952173 -0.029941082, 0.01566343 -0.022667661 -0.03028436, 0.0048379302 -0.021375045 -0.030735359, 0.0055671185 -0.020503566 -0.030777425, 0.0072311163 -0.022020429 -0.030649543, 0.01394783 -0.018364623 -0.030657843, 0.016664654 -0.021942034 -0.030284122, 0.020216569 -0.02552247 -0.029735178, 0.014757812 -0.017720312 -0.030657843, -0.014398843 -0.014361218 -0.030830026, -0.013859823 -0.016339272 -0.030766115, -0.015122682 -0.015083387 -0.030770183, -0.015846536 -0.015805244 -0.030704543, 0.017632425 -0.021172419 -0.030284062, 0.015538111 -0.017040372 -0.030657843, -0.011872858 -0.016873553 -0.030813739, -0.0098857433 -0.017408252 -0.030847982, 0.022329524 -0.026092276 -0.029505789, 0.019727215 -0.023687854 -0.029941037, 0.018564716 -0.020359889 -0.030284032, -0.007898435 -0.017942801 -0.030869991, -0.0059112757 -0.018477812 -0.030880019, 0.016287103 -0.016326129 -0.030657679, 0.020770222 -0.022778913 -0.029940963, -0.0039242059 -0.019012973 -0.030879512, 0.019459575 -0.019506559 -0.030284047, -0.001936987 -0.019548431 -0.030867904, 4.9993396e-05 -0.020083904 -0.030844688, 0.02444008 -0.026661292 -0.029252321, 0.023138925 -0.025377184 -0.029505819, 0.017003193 -0.01557903 -0.030657753, 0.0024441332 -0.020729482 -0.030799896, 0.021771297 -0.021824151 -0.029941052, 0.020315155 -0.018614039 -0.030283898, 0.021320686 -0.0047256798 -0.030739382, 0.024254397 -0.024313346 -0.029505864, 0.027164638 -0.026614308 -0.02897428, 0.027188405 -0.026741728 -0.028957978, 0.02063559 -0.0021595955 -0.030806243, 0.027180552 -0.026858836 -0.028946146, 0.027149826 -0.026959792 -0.028938487, 0.027097732 -0.027052 -0.028934166, 0.027038321 -0.027120352 -0.028933197, 0.01995042 0.00040709972 -0.030850649, 0.026975974 -0.027170405 -0.028934419, 0.026906699 -0.027209565 -0.028937742, 0.026832223 -0.027236849 -0.028942779, 0.0267542 -0.027251437 -0.028949708, 0.026675075 -0.027252749 -0.028958082, 0.026548102 -0.027229652 -0.028974324, 0.019265607 0.0029740334 -0.030874431, 0.017685041 -0.014800444 -0.030657694, 0.022728652 -0.020825341 -0.029940948, 0.018581301 0.0055409074 -0.030879438, 0.017897025 0.0081083179 -0.030866385, 0.021129966 -0.017683864 -0.030283853, 0.025320798 -0.02320078 -0.02950564, 0.026332885 -0.023498163 -0.029375926, 0.017213225 0.010675311 -0.030833796, 0.018331409 -0.013992116 -0.030657619, 0.023640051 -0.019784659 -0.029940799, 0.016529754 0.01324214 -0.030779719, 0.025500074 -0.020377845 -0.029724702, 0.02190198 -0.016717955 -0.030283794, 0.024665877 -0.017253354 -0.03002198, 0.014398977 0.014364421 -0.030828491, 0.018940717 -0.013155565 -0.030657604, 0.01512292 0.015086561 -0.030768499, 0.01584661 0.015808374 -0.030702949, 0.0226302 -0.01571852 -0.030283779, 0.0085591674 -0.021413341 -0.030658171, 0.019511893 -0.012292668 -0.03065756, 0.0096234828 -0.02266556 -0.030540526, 0.0095112771 -0.021007851 -0.030657932, 0.023830622 -0.014124691 -0.03026931, 0.023312673 -0.014687374 -0.030283719, 0.011745319 -0.023238033 -0.030422539, 0.023203805 -0.011777744 -0.030423522, 0.02004391 -0.011404872 -0.030657485, 0.010444358 -0.020559981 -0.030657947, 0.026610926 -0.027244955 -0.028965935, 0.013865635 -0.023809761 -0.030284047, 0.011356235 -0.020070553 -0.030658111, 0.020535588 -0.010494113 -0.030657411, -0.038839951 0.0094269961 -0.028489098, -0.038171351 0.0099489391 -0.028578714, -0.039610565 0.0090824962 -0.028371632, -0.040435746 0.0089329928 -0.028233603, -0.041269302 0.0089833438 -0.028082877, -0.042069197 0.0092303902 -0.02792722, -0.042625695 0.0095426887 -0.02781108, -0.04312107 0.0099552274 -0.027700335, -0.030544326 -0.034179166 -0.027389973, -0.02997309 -0.034387589 -0.027434364, -0.031074882 -0.033872068 -0.027364254, -0.031540856 -0.033479825 -0.027358025, 0.044886112 -0.0096112341 -0.027375787, 0.044768468 -0.0087614208 -0.027432889, 0.044811979 -0.010381997 -0.02735664, 0.044600651 -0.011048779 -0.027366817, 0.044263616 -0.011656418 -0.027402312, 0.043811947 -0.012186587 -0.027461529, 0.043267503 -0.012614578 -0.027542323, 0.042651877 -0.012926444 -0.027640671, 0.041986987 -0.013111129 -0.027753353, 0.041301146 -0.013161913 -0.027875572, 0.04061918 -0.013077989 -0.028002903, 0.039967716 -0.012862712 -0.028129995, 0.039405853 -0.01254864 -0.0282446, 0.038908675 -0.01213488 -0.028351843, 0.053843841 0.015390888 -0.015399233, 0.05219461 0.020291954 -0.012898892, 0.052356884 0.019869596 -0.019295171, 0.050498381 0.024206951 -0.019294798, 0.050340906 0.024532735 -0.012898698, 0.048281163 0.028372481 -0.01929459, 0.032483295 -0.045615584 -0.012902811, 0.036139339 -0.042777315 -0.012902409, 0.035299465 -0.043472633 -0.019298643, 0.038834035 -0.040346637 -0.015402362, 0.03883411 -0.04034628 -0.019298404, 0.048142895 0.028606161 -0.01289846, 0.045721039 0.032336697 -0.019294292, -0.039647341 -0.039547831 -0.012902245, -0.03624621 -0.042686686 -0.012902454, -0.03964752 -0.039547324 -0.019298345, -0.036177233 -0.042744949 -0.019298598, 0.045616344 0.03248398 -0.012898281, 0.042836428 0.036071166 -0.019294098, -0.032597259 -0.04553403 -0.012902617, 0.042777985 0.036140054 -0.012898088, 0.039647549 0.039549619 -0.019293919, -0.032449916 -0.045638695 -0.019298747, 0.039647534 0.039549157 -0.012897789, 0.040250108 -0.038934171 -0.015402257, 0.043385208 -0.035407051 -0.019298077, 0.040250137 -0.038933933 -0.019298404, 0.039548457 -0.039646804 -0.012902334, 0.039311767 -0.039881483 -0.015402377, 0.039783806 -0.039410517 -0.015402243, -0.028725713 -0.048070416 -0.012902796, -0.028492332 -0.048208788 -0.019298822, -0.02465786 -0.050278306 -0.012902856, -0.024332359 -0.050436512 -0.019298911, 0.042687401 -0.036245555 -0.01290223, 0.045534864 -0.032596543 -0.012901857, 0.046212211 -0.031628758 -0.019297987, -0.020421818 -0.052142963 -0.012902915, -0.019999593 -0.052305788 -0.019299179, -0.015524849 -0.053804129 -0.015403003, 0.048071235 -0.028724968 -0.012901679, 0.048710942 -0.027625903 -0.019297734, -0.015524864 -0.053803846 -0.019299269, 0.050279066 -0.024657339 -0.01290147, 0.050863937 -0.023426533 -0.019297555, 0.052143574 -0.020421132 -0.012901112, -0.016045883 -0.053651139 -0.012903154, -0.014883101 -0.053985238 -0.015403032, -0.014239416 -0.054158553 -0.015403062, 0.052655786 -0.019061133 -0.019297153, -0.013593584 -0.054324284 -0.015403122, -0.0089718252 -0.05527553 -0.019299135, -0.013593674 -0.054323971 -0.019299209, 0.053652033 -0.016045362 -0.012901053, 0.054073811 -0.014560625 -0.01929687, -0.011560559 -0.054793343 -0.012903184, 0.05479376 -0.011559933 -0.012900621, 0.055107683 -0.0099563003 -0.01929678, -0.0069963336 -0.055560455 -0.012903184, -0.0042861104 -0.055834696 -0.01929909, 0.055561364 -0.0069957674 -0.012900427, 0.05575034 -0.0052814931 -0.019296467, -0.0023840815 -0.05594857 -0.012903243, 0.00042997301 -0.055997357 -0.019299269, 0.05594936 -0.0023834407 -0.012900233, 0.0022440851 -0.055954307 -0.012903243, 0.0051429719 -0.05576241 -0.019299179, 0.055997208 -0.00056907535 -0.019296125, 0.055955067 0.0022449344 -0.012899995, 0.006857276 -0.055577889 -0.012903154, 0.0098194927 -0.05513145 -0.019299179, 0.055846378 0.0041473359 -0.01929599, 0.055578679 0.0068579614 -0.012899593, 0.055299059 0.0088343918 -0.019295573, 0.011423469 -0.054821774 -0.012903109, 0.014426336 -0.054108799 -0.019299269, 0.015911803 -0.053691283 -0.012903154, 0.01893051 -0.052702114 -0.01929909, 0.054359093 0.013458416 -0.015399426, 0.054359034 0.013458624 -0.019295484, 0.054822728 0.011424109 -0.012899414, 0.020291209 -0.052193835 -0.01290302, 0.023300394 -0.050921425 -0.01929909, 0.024532095 -0.050340027 -0.012902826, 0.027504757 -0.048778906 -0.019298822, 0.053843781 0.015391096 -0.019295335, 0.028605416 -0.048142076 -0.012902841, 0.031514063 -0.04628998 -0.019298762, 0.053691953 0.015912428 -0.01289928, 0.054194957 0.014104471 -0.015399307, 0.054023251 0.014748901 -0.015399322, -0.033721745 -0.047104374 -0.021501482, -0.03431347 -0.043283612 -0.023813426, -0.037496597 -0.044158638 -0.021501228, -0.033949718 -0.040096566 -0.02612555, -0.030461609 -0.042806596 -0.026125655, -0.02905634 -0.046974495 -0.02381371, -0.029716671 -0.049728245 -0.021501482, -0.025508523 -0.052012548 -0.021501616, -0.026758447 -0.045213759 -0.026125893, 0.039199606 -0.040712491 -0.022714302, 0.040912822 -0.041014194 -0.021501079, 0.040615499 -0.039300144 -0.022714272, 0.03738603 -0.044252604 -0.021501273, -0.021126226 -0.053940997 -0.02150166, -0.023406282 -0.050030008 -0.023813754, -0.022865847 -0.047301665 -0.026125893, -0.018811926 -0.049055099 -0.026125893, -0.014624879 -0.050461844 -0.026126027, -0.017439663 -0.052409068 -0.023813918, -0.015784845 -0.054769561 -0.022301033, -0.016599506 -0.055501595 -0.021501973, 0.044159994 -0.037495509 -0.0215009, -0.013853714 -0.055289596 -0.022301033, -0.011237279 -0.054079413 -0.023814186, -0.012693748 -0.050981864 -0.026126057, -0.0083665103 -0.051867887 -0.026126087, -0.011959478 -0.056682855 -0.021501943, -0.007237643 -0.057476893 -0.021502092, -0.0048829913 -0.055018231 -0.023814052, -0.0039802492 -0.052387491 -0.026126131, 0.00043424964 -0.052536577 -0.026126191, -0.0024664253 -0.057878122 -0.021501854, 0.0015373677 -0.055213228 -0.023814186, 0.0048457533 -0.052314356 -0.026126206, 0.0023216754 -0.057884082 -0.021502018, 0.0070938319 -0.05749467 -0.021502107, 0.0079371035 -0.054661334 -0.023813993, 0.0092227906 -0.051722541 -0.026126251, 0.0118175 -0.056712493 -0.021501869, 0.014229313 -0.053370327 -0.023814112, 0.013534784 -0.050765082 -0.026126102, 0.017751187 -0.049448967 -0.026126012, 0.016460612 -0.05554305 -0.021501958, 0.020329162 -0.051357463 -0.023813859, 0.021841958 -0.047783136 -0.026125953, 0.020991191 -0.053993851 -0.021501839, 0.025378332 -0.052076116 -0.021501765, 0.026154131 -0.048650026 -0.02381371, 0.025778517 -0.04577966 -0.026125759, 0.029592156 -0.049802527 -0.021501541, 0.03162539 -0.045284703 -0.023813486, 0.029532686 -0.043452546 -0.02612564, 0.033078223 -0.040818334 -0.02612561, 0.033603832 -0.047188759 -0.021501452, 0.036668971 -0.041307211 -0.023813218, 0.036389992 -0.037895814 -0.026125342, 0.03880696 -0.040318742 -0.023191035, 0.041216567 -0.03677091 -0.023813009, 0.040222898 -0.038906559 -0.023190916, 0.037805974 -0.036483243 -0.026125297, 0.040737048 -0.033178806 -0.026125118, 0.04520689 -0.031737357 -0.023812875, 0.043380052 -0.029639974 -0.026124865, 0.045716494 -0.025891483 -0.02612485, 0.04710573 -0.033720657 -0.021500766, 0.049729586 -0.029715508 -0.021500334, 0.048585847 -0.026274383 -0.023812428, 0.04772982 -0.02196008 -0.026124403, 0.05201368 -0.025507495 -0.021500245, 0.051307768 -0.020456254 -0.02381213, 0.049405783 -0.017873362 -0.026124343, 0.053942487 -0.021125063 -0.021499962, 0.055502817 -0.016598299 -0.021499738, 0.053335845 -0.014361501 -0.023811907, 0.050732553 -0.013660297 -0.02612409, 0.051700756 -0.0093507469 -0.026123866, 0.056684002 -0.011958122 -0.021499366, 0.054642752 -0.0080724806 -0.02381146, 0.052303568 -0.004975155 -0.02612339, 0.057478026 -0.0072364807 -0.021499053, 0.055210561 -0.0016743988 -0.023811087, 0.052536815 -0.00056445599 -0.026123315, 0.057879522 -0.0024653822 -0.021498919, 0.057885468 0.0023227036 -0.021498561, 0.055031776 0.0047465265 -0.023810759, 0.052398637 0.0038505495 -0.026123121, 0.051890269 0.0082381666 -0.026122853, 0.057496041 0.0070949346 -0.021498471, 0.054108694 0.011103302 -0.023810223, 0.05101499 0.012567461 -0.026122615, 0.055325359 0.01371637 -0.022297174, 0.05671379 0.011818767 -0.021498069, 0.054810271 0.015648946 -0.022297069, 0.05245401 0.01730983 -0.023810104, 0.050499797 0.014499918 -0.026122421, 0.049103558 0.018690512 -0.026122332, 0.055544242 0.016461805 -0.021497905, 0.053995222 0.020992294 -0.021497697, 0.050089911 0.0232822 -0.02380982, 0.047360197 0.022748932 -0.026122063, 0.04528217 0.02664648 -0.026121721, 0.052077323 0.02537939 -0.021497458, 0.047048524 0.028939888 -0.023809388, 0.042884126 0.030355796 -0.026121557, 0.049803674 0.029593483 -0.021497115, 0.047189966 0.03360492 -0.021496966, 0.043370649 0.034206182 -0.023809031, 0.040182918 0.033850521 -0.026121289, 0.044253826 0.037387177 -0.021496639, -0.035874739 -0.040209338 -0.024969414, -0.037197694 -0.0371034 -0.026125446, -0.037669644 -0.042221278 -0.022657245, -0.041015223 -0.0409116 -0.02150102, 0.040300459 0.035775378 -0.024965093, 0.037197769 0.037106231 -0.026121184, 0.04231675 0.037564993 -0.022652879, 0.041015387 0.040913805 -0.02149646, 0.040615514 -0.039300203 -0.019888118, 0.040483385 -0.039167717 -0.019674778, 0.039199606 -0.040712744 -0.019888371, 0.039067268 -0.040580213 -0.019674748, 0.054810092 0.015648931 -0.020435616, 0.055325359 0.013716325 -0.020435676, -0.013853684 -0.05528973 -0.020439371, -0.01578486 -0.054769695 -0.020439371, -0.030729353 -0.03267023 -0.025255531, -0.031074196 -0.032230616 -0.025255382, -0.03130576 -0.031721994 -0.025255308, -0.031410798 -0.031173095 -0.025255337, -0.031383589 -0.030614793 -0.025255516, -0.031225488 -0.030078873 -0.025255442, -0.030945376 -0.029595405 -0.025255322, -0.030559197 -0.02919139 -0.025255337, -0.030088812 -0.028889835 -0.025255278, -0.029560417 -0.028707713 -0.025255337, -0.029003978 -0.028655306 -0.025255412, -0.02845107 -0.028735474 -0.025255263, 0.039720371 -0.011325404 -0.02525425, 0.039457068 -0.011010766 -0.025254428, 0.0392524 -0.010655299 -0.025254056, 0.039112419 -0.010269478 -0.025254101, -0.042309374 0.01076445 -0.025252908, -0.042637393 0.011176899 -0.025252953, -0.042865485 0.011652112 -0.025252879, -0.042982116 0.012165993 -0.025252953, -0.042981476 0.012693062 -0.025252849, -0.042863533 0.01320681 -0.025252745, -0.042634353 0.013681173 -0.025252834, -0.042305306 0.014092982 -0.025252774, 0.013694078 0.0044804364 -0.026899755, 0.013931587 0.0041764081 -0.026899979, 0.013693988 0.004480347 -0.025399759, 0.013931468 0.0041763633 -0.025399834, 0.014089435 0.0038243532 -0.026899815, 0.014089331 0.0038245022 -0.025399819, 0.014158547 0.0034450293 -0.026900008, 0.014158562 0.0034449846 -0.025399894, 0.014134705 0.0030599087 -0.02689983, 0.01413469 0.0030599833 -0.025399819, 0.014019519 0.0026919097 -0.026899919, 0.014019459 0.0026920736 -0.0253997, 0.013819516 0.0023620725 -0.026899964, 0.013819486 0.0023620874 -0.025399983, 0.013546512 0.0020897985 -0.026900083, 0.013546526 0.002089709 -0.025399879, 0.013216093 0.0018905997 -0.026899993, 0.013216108 0.001890406 -0.025399968, 0.012847766 0.001776278 -0.026900023, 0.012847885 0.0017761141 -0.025399983, 0.012462765 0.0017533898 -0.026899919, 0.012462646 0.0017534196 -0.025399968, 0.012083441 0.0018233359 -0.026899949, 0.012083396 0.0018233061 -0.025400043, 0.011731923 0.0019821674 -0.026900008, 0.011731818 0.0019821525 -0.025399908, 0.011428475 0.002220422 -0.026899993, 0.011428535 0.0022204667 -0.025400028, -0.0080479532 0.010335222 -0.026899412, -0.0078106076 0.010031447 -0.026899427, -0.0080480576 0.010335192 -0.025399491, -0.0078104734 0.010031343 -0.025399476, -0.0076526999 0.0096794367 -0.026899591, -0.0076526999 0.0096794069 -0.025399521, -0.0075836927 0.0093000233 -0.026899472, -0.0075835586 0.009299919 -0.025399581, -0.0076073706 0.0089150071 -0.026899591, -0.0076073855 0.008915022 -0.025399581, -0.0077226013 0.0085469633 -0.02689971, -0.0077225864 0.0085468441 -0.02539961, -0.0079225451 0.0082169771 -0.026899576, -0.00792256 0.0082171112 -0.025399625, -0.0081956834 0.0079444945 -0.02689968, -0.008195594 0.0079445094 -0.025399566, -0.0085261166 0.0077455789 -0.026899695, -0.0085259825 0.007745564 -0.025399595, -0.0088943541 0.0076312274 -0.026899606, -0.0088944435 0.0076313019 -0.02539961, -0.0092794597 0.0076084435 -0.026899666, -0.0092794448 0.0076083839 -0.02539964, -0.0096587688 0.0076784194 -0.026899725, -0.0096586943 0.0076783299 -0.025399715, -0.010010347 0.0078373104 -0.026899666, -0.010010302 0.0078372061 -0.025399521, -0.0103136 0.0080754012 -0.026899621, -0.0103136 0.0080754012 -0.02539964, -0.0022475123 -0.011421368 -0.025400624, -0.002247408 -0.011421338 -0.026900843, -0.0020100027 -0.011725441 -0.025400832, -0.0020100474 -0.011725396 -0.026900694, -0.0018522143 -0.012077242 -0.025400847, -0.0018520951 -0.012077212 -0.026900813, -0.0017829984 -0.012456939 -0.025400788, -0.0017831177 -0.012456864 -0.026900768, -0.0018068254 -0.012841761 -0.025400788, -0.0018069148 -0.012841627 -0.026900738, -0.0019221753 -0.013209909 -0.025400847, -0.0019220859 -0.013209775 -0.026900813, -0.0021220148 -0.013539627 -0.025400832, -0.0021220446 -0.013539746 -0.026900798, -0.0023952425 -0.013812184 -0.025400847, -0.0023950636 -0.013812184 -0.026900813, -0.0027254522 -0.014011234 -0.025400802, -0.0027254224 -0.014011234 -0.026900798, -0.0030938983 -0.01412566 -0.025400773, -0.0030938387 -0.014125541 -0.026900843, -0.0034789145 -0.014148489 -0.025400802, -0.003478989 -0.01414834 -0.026900932, -0.0038582832 -0.014078408 -0.025400802, -0.0038582832 -0.014078364 -0.026900724, -0.0042097121 -0.013919592 -0.025400877, -0.0042098016 -0.013919488 -0.026900887, -0.0045131147 -0.013681382 -0.025400922, -0.0045130849 -0.013681427 -0.026900753, -0.011304736 0.0070866793 -0.026899591, -0.010736048 0.0066398829 -0.026899666, -0.01007691 0.0063423067 -0.02689971, -0.0093656778 0.0062110871 -0.02689971, -0.0086438656 0.0062538683 -0.02689971, -0.0079530329 0.0064682215 -0.0268998, -0.0073336065 0.0068415254 -0.026899755, -0.0068216473 0.0073520839 -0.02689968, -0.0064466149 0.0079706758 -0.026899621, -0.0062307268 0.0086608678 -0.026899666, -0.0061860234 0.0093827248 -0.02689968, -0.006315574 0.010094225 -0.026899457, -0.006611526 0.010754123 -0.026899487, -0.0070568919 0.011323914 -0.026899397, 0.01043722 0.0012317598 -0.026900008, 0.010962054 0.0008122921 -0.028599963, 0.011006057 0.00078508258 -0.026900068, 0.011566907 0.00052009523 -0.028600082, 0.01166527 0.00048735738 -0.026900008, 0.012221724 0.00036969781 -0.028600022, 0.012376443 0.00035601854 -0.026899949, 0.012893468 0.00036895275 -0.028600007, 0.013098344 0.00039891899 -0.026900113, 0.013548598 0.00051762164 -0.028600037, 0.013789222 0.00061313808 -0.026899919, 0.014154151 0.00080831349 -0.028599963, 0.014679998 0.0012266338 -0.030319318, 0.014679939 0.0012265444 -0.028600097, 0.015067458 0.0017016083 -0.0304396, 0.014408439 0.00098660588 -0.026899964, 0.014920548 0.0014972836 -0.026899934, 0.015295535 0.0021156371 -0.026899993, 0.015351146 0.0022475868 -0.030540228, 0.015511587 0.0028058141 -0.026899904, 0.015529513 0.0029155463 -0.030623794, 0.015556082 0.0035277605 -0.02689974, 0.015550107 0.0036085993 -0.030672178, 0.015426457 0.0042393357 -0.02689977, 0.015410632 0.0042894632 -0.0306817, 0.015117303 0.004921332 -0.030652463, 0.015130594 0.0048991442 -0.02689971, 0.014685199 0.0054693371 -0.030585244, 0.014685184 0.0054690093 -0.026899889, -0.0055042803 -0.01466991 -0.030586258, -0.0055042207 -0.014670178 -0.026901037, -0.0050311089 -0.015056148 -0.030647188, -0.0049355477 -0.01511687 -0.026900932, -0.0044924766 -0.015337333 -0.030679241, -0.004276365 -0.015414342 -0.026901007, -0.0038184524 -0.015518904 -0.030679196, -0.0035650879 -0.015545622 -0.026900992, -0.0031205267 -0.01553981 -0.030639917, -0.0028431863 -0.015503019 -0.026900828, -0.002437517 -0.015399218 -0.030563697, -0.0021525174 -0.015288591 -0.026900828, -0.0018049181 -0.015104085 -0.030454829, -0.0012616813 -0.014675125 -0.028600946, -0.0012616962 -0.014675111 -0.030320182, -0.0015330762 -0.014915347 -0.026900828, -0.0010210276 -0.01440452 -0.026900709, -0.00084218383 -0.014150336 -0.028600872, -0.00064608455 -0.013786018 -0.026900768, -0.00054985285 -0.013545737 -0.028600872, -0.00043010712 -0.013095766 -0.026900798, -0.00039957464 -0.012890771 -0.028600842, -0.00038561225 -0.012373865 -0.026900813, -0.00039871037 -0.012219027 -0.028600946, -0.00051490963 -0.011662498 -0.026900724, -0.00054734945 -0.011564076 -0.028600708, -0.0008110851 -0.011002705 -0.026900694, -0.00083807111 -0.010958418 -0.028600588, -0.0012563467 -0.010432675 -0.026900619, -0.0012563467 -0.010432646 -0.028600618, -0.032326013 0.04904516 -0.020900011, -0.036167502 0.046284944 -0.020900026, -0.033063233 0.046431959 -0.018917158, -0.029116109 0.049003765 -0.018916979, -0.028274789 0.051487431 -0.020899788, -0.02497007 0.051240712 -0.018916845, -0.044789895 -0.038000792 -0.02090466, -0.040355355 -0.04025355 -0.018921986, -0.043541849 -0.036783531 -0.018921912, -0.041586801 -0.041481555 -0.020905063, -0.024040103 0.053595513 -0.020899549, -0.020653382 0.053127632 -0.018916786, -0.04770261 -0.034273446 -0.020904541, -0.046430767 -0.033062398 -0.018921629, -0.01964964 0.055356115 -0.020899579, -0.016195804 0.054651827 -0.018916637, -0.050305977 -0.030323803 -0.020904422, -0.049002498 -0.029115126 -0.018921241, -0.015131772 0.056757912 -0.020899385, -0.011627302 0.055802524 -0.018916607, -0.0105156 0.057791337 -0.020899326, -0.052582815 -0.026177689 -0.020904213, -0.051239654 -0.024969101 -0.018921167, -0.0069796294 0.056572229 -0.018916503, -0.0058313161 0.058450177 -0.020899326, -0.002284199 0.056955293 -0.018916562, -0.054518983 -0.021861643 -0.020903856, -0.053126633 -0.020652533 -0.018920854, -0.0011092126 0.058729813 -0.020899266, 0.0024267584 0.056949407 -0.018916562, -0.056101277 -0.017403677 -0.020903677, 0.0036199391 0.058628842 -0.020899296, -0.054650679 -0.016194701 -0.018920541, 0.0071212798 0.056554511 -0.018916547, 0.0083258599 0.058147386 -0.020899296, -0.057319775 -0.01283291 -0.020903334, -0.055801436 -0.011626482 -0.018920496, 0.011767283 0.055773169 -0.018916652, 0.01297763 0.057288751 -0.020899624, -0.058166727 -0.0081790239 -0.020903111, -0.056571051 -0.0069785714 -0.018920004, 0.016332626 0.054611102 -0.018916577, 0.017545238 0.056058675 -0.020899519, -0.058636427 -0.0034719557 -0.020902842, -0.056954294 -0.0022831559 -0.018919826, 0.020786449 0.053075939 -0.018916786, 0.021999151 0.054465115 -0.020899743, -0.058725715 0.0012576282 -0.020902544, 0.02509822 0.051178113 -0.018916845, -0.056948453 0.0024280399 -0.018919602, 0.026310414 0.052518263 -0.020899758, -0.058434099 0.0059790164 -0.020902291, 0.029238716 0.048930675 -0.018917099, -0.056553289 0.0071222633 -0.018919215, 0.030450955 0.050230876 -0.020899892, -0.057763547 0.010661408 -0.020902112, -0.05577217 0.011768281 -0.018918961, 0.033179596 0.046348944 -0.018916994, 0.034394056 0.047617823 -0.0209001, 0.036893547 0.043450609 -0.018917307, -0.056718633 0.015275046 -0.02090171, -0.054609895 0.01633361 -0.018918768, 0.038114056 0.04469578 -0.020900115, 0.040355548 0.04025571 -0.018917382, -0.0553056 0.019789413 -0.020901605, -0.053074777 0.020787597 -0.018918425, 0.041586965 0.041483954 -0.020900398, -0.053534016 0.024175555 -0.020901456, -0.051176876 0.025099352 -0.018918261, -0.051415116 0.028404891 -0.020901069, -0.048929468 0.029239729 -0.018917978, -0.048962876 0.032449946 -0.020900875, -0.046347842 0.033180594 -0.018918008, -0.046193019 0.036284626 -0.020900398, -0.043449655 0.036894575 -0.018917531, -0.043123588 0.039883777 -0.020900384, -0.040254548 0.040356562 -0.018917412, -0.039774746 0.043224603 -0.020900145, -0.036784545 0.043542922 -0.018917158, -0.015108287 0.011341155 -0.031848714, -0.015496179 0.010396317 -0.031790227, -0.015687928 0.010524943 -0.031848744, -0.015884072 0.010656491 -0.031879246, -0.015297219 0.011483148 -0.031879276, 0.0090740472 0.016570151 -0.031848356, 0.0069034249 0.017337441 -0.031789839, 0.0066237301 0.017692968 -0.031848341, 0.0067066103 0.017914027 -0.031879008, 0.0091874897 0.016777366 -0.031878948, -0.014294252 0.012710288 -0.031879067, -0.015487686 0.01162608 -0.031881496, -0.013675794 0.01371181 -0.031881422, 0.011481389 0.015299067 -0.031878933, 0.009301886 0.016986281 -0.031881288, 0.011624351 0.015489638 -0.031881288, 0.013541594 0.013509229 -0.031879157, -0.0135075 0.013543278 -0.031879097, 0.011339694 0.015110165 -0.031848475, 0.013374403 0.01334247 -0.03184855, 0.011303887 0.014847994 -0.031789958, 0.0091882944 0.01624231 -0.031789884, -0.014117584 0.01255317 -0.03184852, -0.013945162 0.012399808 -0.031790048, -0.013340816 0.013375998 -0.031848595, -0.012137011 0.014174655 -0.031790018, 0.013710156 0.013677552 -0.031881362, -0.012440816 0.014529571 -0.031878963, -0.011585459 0.015518486 -0.031881198, -0.01144284 0.015327767 -0.031878948, -0.014892191 -0.011240944 -0.031791434, -0.013210744 -0.013176039 -0.031791657, -0.013374224 -0.013339177 -0.031850144, -0.012287095 0.014350086 -0.031848609, 0.013210908 0.0131796 -0.031790063, -0.010357991 0.016081154 -0.031879023, -0.0092592686 0.017009482 -0.031881168, -0.015265062 -0.011522338 -0.031880468, -0.013710111 -0.01367408 -0.031882957, -0.015516773 -0.011583716 -0.031882793, -0.013541386 -0.013505876 -0.031880751, -0.011301622 0.015138507 -0.031848386, -0.015076518 -0.011379957 -0.031850055, -0.016292736 -0.0090935677 -0.031791523, -0.010104999 0.01568833 -0.031789973, -0.01023002 0.015882447 -0.031848431, -0.016700655 -0.0093212277 -0.031880438, -0.017007738 -0.0092574358 -0.031882703, -0.016494364 -0.009205997 -0.031849802, -0.017385557 -0.0067745298 -0.03179124, -0.0091453195 0.016800344 -0.031878889, -0.0080840588 0.017336011 -0.031878874, -0.0067447275 0.018154174 -0.031881109, -0.017820925 -0.0069441646 -0.03188023, -0.018152311 -0.0067428201 -0.031882659, -0.0090323985 0.01659286 -0.031848401, -0.017600745 -0.006858319 -0.031849802, -0.0181503 -0.004327476 -0.03179118, -0.0078867078 0.016912654 -0.031789988, -0.0079843402 0.01712203 -0.031848505, -0.018604741 -0.0044359416 -0.031880066, -0.018927425 -0.0040908158 -0.03188242, -0.0066616684 0.017930999 -0.031878918, -0.01837483 -0.00438115 -0.031849727, -0.0056612343 0.018271491 -0.031878844, -0.0040926337 0.018929213 -0.031881049, -0.01857233 -0.0017988831 -0.031790957, -0.019037351 -0.0018441528 -0.031880021, -0.019317105 -0.0013555735 -0.031882241, -0.0065793395 0.017709419 -0.03184855, -0.0055229664 0.017825186 -0.031789929, -0.018802196 -0.0018211901 -0.031849384, -0.018643945 0.00076383352 -0.031790823, -0.0055912733 0.018045813 -0.031848267, -0.019110575 0.00078287721 -0.031879798, -0.019313812 0.0014074296 -0.031882018, -0.0040421486 0.018696427 -0.031878859, -0.0031340867 0.018869951 -0.031878799, -0.0013572127 0.019318938 -0.031881198, -0.018874645 0.00077314675 -0.03184922, -0.01836361 0.003312096 -0.031790644, -0.0039923638 0.018465638 -0.031848341, -0.018823341 0.0033949763 -0.031879693, -0.018917173 0.0041418374 -0.031882003, -0.0030574501 0.018409058 -0.031789854, -0.00309515 0.018636748 -0.031848192, -0.018684343 0.0040908307 -0.031879634, -0.001340434 0.019081384 -0.031878754, -0.018590763 0.003353104 -0.031849205, -0.00054892898 0.019120485 -0.031878725, 0.0014056861 0.019315615 -0.031881124, -0.018453613 0.0040403903 -0.031849161, -0.017736509 0.0057979375 -0.031790614, -0.0013239235 0.018845797 -0.031848311, -0.00053554773 0.018653542 -0.03178978, -0.018180549 0.0059429109 -0.031879529, -0.018135428 0.0067917705 -0.031882003, -0.00054207444 0.01888442 -0.031848297, -0.017912313 0.0067082644 -0.031879634, 0.0013884157 0.019077972 -0.031878695, -0.017955959 0.005869478 -0.031848982, 0.0013712496 0.018842384 -0.031848192, -0.017691121 0.0066255927 -0.031849012, -0.016774654 0.0081741661 -0.031790435, 0.0019962639 0.018554166 -0.031789824, -0.017194539 0.0083788484 -0.031879336, -0.016984463 0.0093036592 -0.031881675, 0.0040890723 0.01868628 -0.031878769, 0.0041399598 0.018918812 -0.031881183, -0.016775504 0.009189263 -0.031879395, 0.0040386617 0.01845552 -0.031848446, 0.0044911802 0.018112719 -0.031789839, -0.016982168 0.0082751811 -0.031848773, -0.016568273 0.0090759099 -0.031848818, 0.0067900419 0.018137231 -0.031881094, 0.014143333 0.044830143 -0.027344525, 0.014143273 0.044830024 -0.026397571, 0.013588071 0.045294017 -0.027272776, 0.013443619 0.045389399 -0.026397541, 0.012965083 0.045647249 -0.027230501, 0.012637064 0.045779169 -0.026397541, 0.012043357 0.045937479 -0.02722089, 0.011764064 0.045979485 -0.026397616, 0.011077344 0.045998305 -0.027266458, 0.010868371 0.045980588 -0.026397347, 0.010125816 0.045825481 -0.027364135, 0.0099948943 0.045782372 -0.026397616, 0.0091873556 0.045394838 -0.026397333, 0.0092454255 0.045430481 -0.027507782, 0.0084863901 0.044836983 -0.026397705, 0.0084863901 0.044837147 -0.027687773, -0.037328616 -0.011532411 -0.028866678, -0.036996007 -0.011654481 -0.026400641, -0.037323415 -0.011534765 -0.026400581, -0.036996037 -0.011654377 -0.028886229, -0.037627548 -0.011358455 -0.028850049, -0.037625134 -0.011360303 -0.02640073, -0.037891805 -0.011135712 -0.02883634, -0.03789188 -0.011135653 -0.026400656, -0.025415391 -0.005386889 -0.031430706, -0.025628865 -0.004257381 -0.031430542, -0.02241379 -0.0037231743 -0.031683087, -0.021997049 -0.0056894422 -0.031683341, -0.022227019 -0.0047109276 -0.031683341, -0.029052764 -0.0061579645 -0.031070992, -0.029296845 -0.0048668534 -0.031070918, -0.025152266 -0.006505847 -0.031430677, -0.032290623 -0.0068445951 -0.030686155, -0.035734728 -0.007616058 -0.030208439, -0.034264848 -0.006152153 -0.030450493, -0.021723688 -0.0066568255 -0.031683519, -0.02875188 -0.0074371397 -0.031071037, -0.024839669 -0.0076120645 -0.031430706, -0.03195633 -0.0082661957 -0.03068608, -0.021407917 -0.0076112747 -0.031683564, -0.028394639 -0.0087016374 -0.031071052, -0.035352722 -0.0091449469 -0.030211568, -0.036862761 -0.010623425 -0.029933974, -0.037063181 -0.010542199 -0.029907286, -0.037238523 -0.010415226 -0.029886186, -0.037342861 -0.010299265 -0.029875383, -0.037428558 -0.010160595 -0.029868126, -0.037487432 -0.01000829 -0.029865161, -0.037516847 -0.0098555982 -0.02986677, -0.037519574 -0.0097081661 -0.029872432, -0.037497923 -0.00956209 -0.029881343, -0.03745237 -0.0094214529 -0.02989392, -0.037384346 -0.0092908144 -0.029909119, -0.037326425 -0.0092095435 -0.029920861, -0.037259594 -0.0091350377 -0.02993387, -0.024478689 -0.0087031871 -0.031431034, -0.031559244 -0.0096716285 -0.030686349, -0.033972651 -0.011399329 -0.030309334, -0.021050215 -0.0085505396 -0.031683564, -0.027981803 -0.0099491477 -0.031071201, -0.024069652 -0.0097776353 -0.03143099, -0.031100407 -0.011058182 -0.030686274, -0.031103849 -0.012169585 -0.030636966, -0.020651415 -0.0094732791 -0.031683579, -0.027514309 -0.011177123 -0.031071261, -0.02825895 -0.012932807 -0.0309183, -0.023613572 -0.010832652 -0.031431019, -0.020211965 -0.010377616 -0.031683549, -0.026992992 -0.012383103 -0.031071275, -0.025401205 -0.013699412 -0.031159103, -0.023111269 -0.011866614 -0.031430975, -0.019733071 -0.011261493 -0.031683654, -0.022563592 -0.012877211 -0.031431139, -0.023084626 -0.014320552 -0.031324536, -0.019215539 -0.012123376 -0.031683728, -0.021971866 -0.013862714 -0.031431049, -0.020822942 -0.014927104 -0.031461969, -0.018660456 -0.012961492 -0.031683818, -0.018068731 -0.013774291 -0.031683713, -0.018513203 -0.015546054 -0.031578287, -0.017441556 -0.014560059 -0.031683981, -0.016780451 -0.015317321 -0.031683952, -0.01454249 -0.014504418 -0.031820357, -0.0066100061 0.021407217 -0.031703278, -0.004734844 0.023281887 -0.031607777, -0.01537469 -0.015334532 -0.031749874, -0.016206503 -0.016164348 -0.031672254, -0.0084446967 0.019573599 -0.031772733, -0.010301322 0.017718166 -0.031820998, -0.011318803 0.016701967 -0.031838775, -0.012337402 0.015684932 -0.031850919, -0.01335609 0.014668345 -0.03185685, -0.014374658 0.013652474 -0.031857923, -0.015393287 0.012636811 -0.031853199, -0.016411111 0.011622265 -0.031842634, -0.017429531 0.010607451 -0.031826541, -0.018450022 0.0095911175 -0.031804517, -0.020154178 0.007894516 -0.031753197, -0.021860689 0.0061956942 -0.031682715, -0.023565859 0.0044987053 -0.031591445, 0.015360996 0.016743869 -0.031682134, 0.015374869 0.015338108 -0.03174825, 0.014542773 0.014508083 -0.031818435, 0.016206697 0.016167715 -0.031670377, 0.015760273 0.017849922 -0.031604096, 0.014605433 0.017406881 -0.031682178, 0.015301868 0.019577637 -0.031523749, 0.013821244 0.018036038 -0.031681895, 0.014836863 0.02132912 -0.031429186, 0.013009861 0.0186297 -0.03168194, 0.01217334 0.019186884 -0.031682, 0.013919488 0.021938801 -0.031429097, 0.014386356 0.023026809 -0.031324103, 0.011312842 0.019706503 -0.031681925, 0.012935519 0.022533134 -0.031429067, 0.013920352 0.024782375 -0.031201139, 0.010430157 0.020187557 -0.031682, 0.01192604 0.02308318 -0.031429097, 0.013471425 0.026472703 -0.031068727, 0.0095269829 0.020629391 -0.031681821, 0.010893553 0.023588121 -0.031428963, 0.0086052567 0.021030471 -0.031682029, 0.012452573 0.026963606 -0.031069055, 0.012554809 0.029924214 -0.030753389, 0.013009876 0.028210789 -0.030917466, 0.009839505 0.024046957 -0.031429008, 0.007666707 0.021390572 -0.031682, 0.011247858 0.027487919 -0.031068981, 0.0087663233 0.024458423 -0.031428948, 0.0067130476 0.021708667 -0.03168191, 0.010020971 0.027958572 -0.031069085, 0.0076759011 0.02482231 -0.031429023, 0.011137724 0.031074449 -0.030684203, 0.011636436 0.033380076 -0.030374795, 0.0057461709 0.021984607 -0.031681702, 0.0087743849 0.028374672 -0.031069025, 0.006570518 0.025137722 -0.031429023, 0.0097523481 0.031536818 -0.030684009, 0.010717362 0.036837742 -0.029931203, 0.0047683567 0.022217095 -0.031681731, 0.0075108558 0.028734937 -0.031068921, 0.0054522902 0.025403649 -0.031428888, 0.0083478838 0.031937197 -0.030683994, 0.0037809759 0.022406265 -0.031681687, 0.0062324852 0.02903904 -0.031068906, 0.0092352182 0.035331547 -0.03020899, 0.0076897591 0.035699829 -0.03020905, 0.0092299283 0.03723821 -0.029931396, 0.009400323 0.037371382 -0.029904723, 0.0095980018 0.037459597 -0.029883578, 0.0097505301 0.037491992 -0.029872507, 0.0099135488 0.037497059 -0.029865414, 0.010074854 0.037471771 -0.029862568, 0.010221824 0.037420899 -0.029864237, 0.010350779 0.037349463 -0.029869705, 0.010466531 0.037257776 -0.029878646, 0.010565683 0.037147745 -0.029891223, 0.010644644 0.037023664 -0.029906496, 0.010686249 0.036932945 -0.029918313, 0.0043233335 0.02561985 -0.031428948, 0.0069272071 0.032275274 -0.03068383, 0.0062030554 0.034214631 -0.030453876, 0.0027861893 0.022551566 -0.031681672, 0.0049419701 0.02928631 -0.031068921, 0.0031858385 0.025786147 -0.031429037, 0.0054927617 0.032550141 -0.030683935, 0.0046659559 0.032678813 -0.030683845, 0.0017859489 0.02265285 -0.031681627, 0.0036417544 0.029476136 -0.031068951, 0.0031731129 0.031187043 -0.030884787, 0.0020422339 0.025901869 -0.031428978, 0.0016401857 0.029654965 -0.031068951, 0.00078240037 0.022709683 -0.031681925, 0.00089462101 0.025966823 -0.031428903, 0.0001412183 0.028156534 -0.031227648, -0.00022290647 0.022722065 -0.031681627, -0.00025488436 0.025981054 -0.031428933, -0.0013866276 0.026629567 -0.031368613, -0.001227662 0.022689953 -0.031681895, -0.0014038235 0.025944218 -0.031428903, -0.0028890222 0.025127396 -0.031487301, -0.002230078 0.022613436 -0.03168188, -0.0032280535 0.022492677 -0.031681702, -0.004219681 0.02232784 -0.031681716, -0.022315398 0.0042772293 -0.031682834, -0.022482619 0.0032860637 -0.031682774, -0.025270447 0.0028022528 -0.031477466, -0.022605866 0.0022883415 -0.031682938, -0.022684902 0.0012862533 -0.031682998, -0.025938898 0.0014704019 -0.031430274, -0.026751727 0.0013279617 -0.031359002, -0.022719562 0.00028139353 -0.031683162, -0.025978401 0.00032159686 -0.031430364, -0.028268069 -0.00018127263 -0.031218156, -0.022709668 -0.00072357059 -0.031683207, -0.02596724 -0.00082787871 -0.031430379, -0.029747024 -0.0016534775 -0.031060517, -0.022655323 -0.0017275363 -0.031683072, -0.025905147 -0.0019756258 -0.031430557, -0.03126736 -0.0031672716 -0.030877411, -0.022556618 -0.0027278364 -0.031683162, -0.025792286 -0.0031196177 -0.031430572, -0.029483408 -0.0035662055 -0.031070799, -0.032741725 -0.0046351999 -0.030678436, -0.04241313 0.010661334 -0.028202966, -0.042714342 0.011026815 -0.02810587, -0.042413011 0.010660991 -0.025606498, -0.042761549 0.011099353 -0.025606528, -0.04294242 0.011445373 -0.028022006, -0.043003798 0.011603996 -0.025606409, -0.043087065 0.011900082 -0.027954727, -0.043127745 0.012149915 -0.025606364, -0.043142512 0.01237452 -0.027907208, -0.043126926 0.012709677 -0.025606409, -0.043106407 0.012853116 -0.027881071, -0.043001756 0.013255298 -0.025606364, -0.042980194 0.013314322 -0.027877375, -0.042758346 0.013759464 -0.025606304, -0.042767704 0.013744399 -0.027896687, -0.042601973 0.013980016 -0.027918965, -0.04240872 0.014196649 -0.025606364, -0.042408586 0.014196768 -0.02794911, -0.030833036 -0.032773599 -0.025608942, -0.030832991 -0.032773525 -0.02787903, -0.031199381 -0.032306731 -0.025608957, -0.031370863 -0.031968877 -0.027933329, -0.031445339 -0.031766206 -0.025608927, -0.031512931 -0.031505689 -0.027993143, -0.031556979 -0.031183288 -0.025608763, -0.031562954 -0.031025767 -0.02807112, -0.031527907 -0.030590355 -0.025608808, -0.031520113 -0.030547053 -0.028164178, -0.031359941 -0.030021086 -0.025608793, -0.031387761 -0.030088082 -0.028268635, -0.031062558 -0.029507339 -0.025608793, -0.031176001 -0.029671758 -0.028378054, -0.030652389 -0.029078215 -0.025608778, -0.030486301 -0.028952718 -0.028619274, -0.030152604 -0.02875793 -0.025608748, -0.030073732 -0.028721169 -0.028727457, -0.029591411 -0.028564602 -0.025608554, -0.029619336 -0.028570607 -0.028827772, -0.029141858 -0.028509125 -0.028916121, -0.029000342 -0.028508946 -0.025608823, -0.028774172 -0.028524786 -0.028972954, -0.028412968 -0.028594032 -0.025608823, -0.028412908 -0.028593928 -0.029019311, 0.03961657 -0.011428744 -0.02560772, 0.039616629 -0.011428669 -0.028808862, 0.039337024 -0.011094704 -0.02560772, 0.03933315 -0.011088833 -0.028892949, 0.039119527 -0.01071699 -0.025607765, 0.039117888 -0.010713443 -0.028962791, 0.038971007 -0.010307178 -0.025607765, 0.038971052 -0.010307074 -0.029018313, -0.032364413 0.049103364 -0.020917743, -0.02833885 0.051604047 -0.02095142, -0.032399207 0.049156234 -0.020951629, -0.028308243 0.051548302 -0.020917594, -0.036322922 0.046483725 -0.021126032, -0.032469586 0.049263105 -0.021197125, -0.036328405 0.04649058 -0.021197483, -0.032464817 0.049255848 -0.021125957, -0.036307395 0.046463922 -0.021058843, -0.032450929 0.049234793 -0.021058783, -0.036282271 0.046431839 -0.020999715, -0.032428622 0.049200788 -0.020999461, -0.036249489 0.046389908 -0.020951852, -0.036210284 0.04633978 -0.020917773, -0.039945498 0.043410257 -0.02112627, -0.03995122 0.043416575 -0.021197438, -0.039928377 0.043391854 -0.021059066, -0.039900795 0.043361753 -0.020999685, -0.03986463 0.043322399 -0.020951763, -0.039821669 0.043275744 -0.020918131, -0.043308765 0.040055186 -0.021126479, -0.043315127 0.040061116 -0.021197841, -0.043290362 0.040038094 -0.02105926, -0.043260485 0.040010557 -0.021000028, -0.043221176 0.039974138 -0.020952046, -0.043174744 0.039931193 -0.020918146, -0.046391383 0.036440372 -0.021126628, -0.046398148 0.036445692 -0.0211979, -0.04637146 0.036424831 -0.021059513, -0.046339676 0.036399767 -0.021000162, -0.04629761 0.036366746 -0.020952299, -0.04624787 0.036327541 -0.020918459, -0.04917334 0.032589465 -0.021126881, -0.049180344 0.0325941 -0.021198258, -0.049152121 0.032575384 -0.021059856, -0.049118221 0.032553047 -0.021000385, -0.049073696 0.032523483 -0.020952493, -0.049020797 0.032488286 -0.020918667, -0.0516361 0.028526857 -0.021127194, -0.05164358 0.028531075 -0.021198392, -0.051613897 0.028514594 -0.021059945, -0.051578283 0.028495073 -0.021000728, -0.051531404 0.028469056 -0.020952657, -0.051476106 0.028438568 -0.020918936, -0.053763777 0.024279371 -0.021127447, -0.053771734 0.024282888 -0.02119869, -0.053740844 0.024268895 -0.021060184, -0.053703889 0.02425243 -0.021000788, -0.053655162 0.024230197 -0.020952865, -0.05359742 0.02420418 -0.020919099, -0.055543184 0.019874528 -0.021127656, -0.055551261 0.0198773 -0.021198839, -0.055519253 0.019865856 -0.021060303, -0.055481032 0.019852281 -0.021001145, -0.055430755 0.019834235 -0.020953253, -0.055371091 0.019812971 -0.020919323, -0.056962132 0.015340522 -0.02112785, -0.056970507 0.015342891 -0.021199137, -0.056937754 0.015334114 -0.021060675, -0.056898564 0.015323564 -0.021001458, -0.056846946 0.015309423 -0.020953462, -0.056785762 0.015293121 -0.020919606, -0.058011606 0.010707244 -0.021128073, -0.058020189 0.010708988 -0.021199346, -0.057986826 0.010702744 -0.021060884, -0.05794701 0.010695323 -0.021001518, -0.057894275 0.010685697 -0.020953581, -0.057832107 0.010674119 -0.020919725, -0.058685184 0.0060046464 -0.021128371, -0.058693573 0.0060055852 -0.021199808, -0.058660075 0.0060021281 -0.021061212, -0.058619589 0.0059980005 -0.021001831, -0.058566466 0.0059923679 -0.020954028, -0.058503389 0.00598602 -0.020919949, -0.058977813 0.0012629479 -0.021128669, -0.058986425 0.0012630671 -0.021199927, -0.041765347 -0.041659862 -0.021131083, -0.04498893 -0.038169473 -0.021202207, -0.041771382 -0.041665852 -0.021202371, -0.058952555 0.0012623668 -0.021061569, -0.058912069 0.0012615472 -0.021002069, -0.058858648 0.0012604892 -0.020954311, -0.058795244 0.0012590736 -0.020920306, -0.041636065 -0.041530758 -0.020922795, 0.038277805 0.044887811 -0.021126255, 0.04177165 0.041668326 -0.021197617, 0.038283259 0.044894278 -0.021197513, 0.041765496 0.041662097 -0.021126464, -0.058888182 -0.0034869015 -0.021129027, -0.058896855 -0.0034874976 -0.021200225, 0.038261414 0.044868559 -0.021059126, -0.05886288 -0.0034854561 -0.021061704, 0.04174763 0.04164429 -0.021059215, -0.058822483 -0.0034831017 -0.021002471, 0.038234919 0.044837683 -0.020999759, 0.041718885 0.04161571 -0.020999819, 0.038200229 0.044796973 -0.020951807, 0.041680977 0.041577891 -0.020952001, -0.058769077 -0.0034798682 -0.020954505, 0.038159251 0.044748724 -0.020917907, -0.058705941 -0.0034760982 -0.020920709, 0.041636109 0.041533068 -0.020918116, 0.034541801 0.047822446 -0.021126047, 0.034546703 0.047829196 -0.021197364, -0.058416471 -0.0082141161 -0.021129191, -0.058425024 -0.0082154274 -0.021200448, 0.03452687 0.047801971 -0.021058977, -0.058391467 -0.0082105994 -0.021061942, -0.058351219 -0.0082049817 -0.021002665, 0.034503251 0.047768861 -0.020999551, 0.034471899 0.047725648 -0.020951748, -0.058298409 -0.0081975609 -0.020954624, 0.034434676 0.047674164 -0.020917848, -0.058235511 -0.0081887245 -0.020920977, -0.057566151 -0.012888119 -0.021129355, -0.057574496 -0.012890056 -0.021200642, 0.030581817 0.050446808 -0.021126017, 0.030586198 0.050454095 -0.021197334, 0.030568495 0.050424963 -0.021058857, -0.057541355 -0.012882516 -0.0210623, 0.030547574 0.050390556 -0.020999327, -0.057501778 -0.012873694 -0.021002874, 0.030519873 0.050344586 -0.020951673, -0.057449624 -0.012862012 -0.020955056, 0.030487061 0.05029054 -0.02091752, -0.057387844 -0.012848139 -0.020921096, 0.026423335 0.052743837 -0.021125838, -0.056342378 -0.017478436 -0.021129772, -0.056350484 -0.017481059 -0.021201029, 0.026427343 0.052751645 -0.021197081, -0.056318089 -0.017470881 -0.021062553, 0.02641204 0.052721307 -0.021058649, 0.026393875 0.052685052 -0.020999238, -0.056279406 -0.017458946 -0.021003291, 0.026369929 0.05263713 -0.02095139, -0.056228191 -0.017442971 -0.020955265, 0.026341587 0.052580729 -0.02091749, -0.056167632 -0.017424375 -0.020921499, -0.054752946 -0.021955475 -0.021129832, -0.054760903 -0.021958619 -0.021201134, 0.022093609 0.054699183 -0.021125585, 0.022096992 0.054706976 -0.021196902, 0.022084162 0.054675609 -0.021058396, -0.054729491 -0.021945968 -0.021062627, 0.022068962 0.054638043 -0.020999193, -0.054692015 -0.021930963 -0.021003366, 0.02204898 0.054588363 -0.020951211, -0.054642245 -0.021910906 -0.020955548, 0.022025302 0.054529652 -0.02091746, -0.0545834 -0.021887407 -0.020921618, 0.017620653 0.056299582 -0.02112557, -0.052808732 -0.02628991 -0.021130294, -0.052816376 -0.026293799 -0.021201372, 0.017623231 0.056307644 -0.021196783, 0.017613083 0.056275442 -0.0210585, -0.052786067 -0.026278764 -0.02106306, 0.017601028 0.056236595 -0.020999163, -0.052749604 -0.026260823 -0.021003678, 0.017585009 0.056185678 -0.020951241, -0.052701756 -0.026236892 -0.02095589, 0.017566144 0.056125224 -0.020917356, -0.052645147 -0.02620849 -0.020921886, 0.01303336 0.057534873 -0.021125495, 0.013035327 0.057543173 -0.021196842, -0.05052188 -0.030454069 -0.021130487, -0.050529182 -0.030458584 -0.02120173, 0.013027787 0.057510182 -0.021058336, -0.050500259 -0.030440912 -0.021063253, 0.013018876 0.057470605 -0.020999089, -0.050465509 -0.030420035 -0.021003887, 0.013006896 0.057418451 -0.020951018, -0.050419733 -0.030392393 -0.020956069, 0.012993038 0.057356581 -0.020917222, -0.050365463 -0.030359685 -0.020922229, 0.0083616078 0.05839698 -0.021125421, -0.047907412 -0.034420639 -0.021130756, -0.047914416 -0.034425691 -0.021201998, 0.0083626509 0.058405533 -0.021196753, 0.0083579868 0.058371961 -0.021058232, -0.047886789 -0.034405917 -0.021063447, -0.047853991 -0.03438209 -0.02100417, 0.0083523393 0.058331802 -0.020998865, 0.0083447099 0.058279008 -0.020951018, -0.047810495 -0.034350887 -0.020956397, -0.047758967 -0.034314036 -0.020922512, 0.0083356649 0.058216259 -0.020917058, 0.0036355555 0.058880448 -0.02112551, 0.0036362112 0.058889046 -0.021196738, -0.044982299 -0.038163945 -0.02113089, -0.041747421 -0.04164198 -0.021063864, 0.0036340356 0.05885531 -0.021058202, -0.044962958 -0.038147748 -0.021063656, -0.041718841 -0.041613296 -0.021004662, -0.044931993 -0.038121477 -0.021004319, 0.0036313832 0.05881466 -0.020998821, 0.0036282539 0.058761343 -0.020951077, -0.041680813 -0.0415757 -0.02095668, -0.044891149 -0.038086697 -0.020956516, 0.0036241859 0.058698133 -0.020917311, -0.044843003 -0.038045749 -0.020922467, -0.0011139512 0.058982 -0.021125481, -0.0011141151 0.058990523 -0.021196738, -0.0011135042 0.058956817 -0.021058276, -0.001112774 0.058916181 -0.020999074, -0.0011117011 0.058862746 -0.020951018, -0.0011105686 0.058799624 -0.020917252, -0.005856365 0.058701143 -0.021125406, -0.0058573186 0.058709756 -0.021196753, -0.0058539212 0.058676228 -0.021058202, -0.0058499426 0.058635637 -0.020999014, -0.0058444887 0.058582455 -0.020951077, -0.0058383644 0.058519483 -0.020917252, -0.010560662 0.058039531 -0.021125391, -0.010562167 0.058048025 -0.021196753, -0.010556191 0.05801478 -0.021058366, -0.010549039 0.057974845 -0.020999044, -0.010539278 0.057922289 -0.020951077, -0.010528058 0.057860017 -0.020917118, -0.015196741 0.05700165 -0.02112554, -0.015198886 0.05700998 -0.021196842, -0.015190169 0.056977093 -0.021058455, -0.015179738 0.056937814 -0.020999074, -0.015165865 0.0568863 -0.020951152, -0.015149742 0.056825101 -0.020917431, -0.019734085 0.055593893 -0.02112554, -0.019736946 0.055602029 -0.021196768, -0.019725576 0.055570051 -0.021058485, -0.019711986 0.055531979 -0.020999044, -0.01969409 0.055481583 -0.020951256, -0.019672826 0.055421755 -0.020917341, -0.024143428 0.053825855 -0.02112557, -0.024146974 0.053833634 -0.021196947, -0.024133086 0.053802684 -0.02105847, -0.024116501 0.053765744 -0.020999223, -0.024094552 0.053716734 -0.020951331, -0.024068594 0.053659067 -0.02091746, -0.028396308 0.051708505 -0.021125779, -0.028400406 0.051716089 -0.02119717, -0.028384045 0.051686168 -0.021058679, -0.028364524 0.051650643 -0.020999357, 0.0036343634 0.058861852 -0.021884233, -0.0011140257 0.058983773 -0.021822825, 0.0036356002 0.058882251 -0.021822959, -0.0011136532 0.058963358 -0.021884188, 0.0036324114 0.058828846 -0.021939546, -0.0011130124 0.058930218 -0.021939442, -0.0011122227 0.058886006 -0.02198641, 0.0036296695 0.058784604 -0.021986619, 0.0083619207 0.058398575 -0.021823019, 0.0036360621 0.05888918 -0.021758795, 0.0083629042 0.058405623 -0.021758884, 0.0083589554 0.058378398 -0.021884114, 0.0083542764 0.058345541 -0.021939635, -0.044908956 -0.038101822 -0.021992132, -0.041697249 -0.041591972 -0.021992385, -0.041728526 -0.041623265 -0.021945179, 0.0083479732 0.058301955 -0.021986455, 0.013033733 0.057536453 -0.021823093, 0.013035357 0.057543263 -0.021758825, 0.013029262 0.057516456 -0.021884248, 0.013021946 0.05748418 -0.021939665, 0.013012111 0.057441205 -0.021986723, 0.017621219 0.056301177 -0.021823093, 0.01762335 0.056307733 -0.021758914, 0.022096932 0.054707095 -0.021758914, 0.017614961 0.056281641 -0.021884277, 0.017605081 0.056250036 -0.02193971, 0.017591938 0.056207895 -0.021986589, 0.022094429 0.054700613 -0.021823227, 0.026427269 0.052751511 -0.021759138, 0.02208662 0.054681525 -0.021884486, 0.022074297 0.054650843 -0.021939695, 0.022057712 0.054610074 -0.021986634, 0.02642411 0.052745461 -0.021823421, 0.026414901 0.052727044 -0.021884531, 0.026400164 0.052697524 -0.021939814, 0.026380375 0.052658111 -0.021986842, 0.030582532 0.050448269 -0.021823421, 0.030586183 0.050453961 -0.021759361, 0.030572087 0.050430655 -0.021884754, 0.030554861 0.050402343 -0.021940097, 0.030531913 0.050364569 -0.021986991, 0.034542695 0.047823712 -0.021823615, 0.034546703 0.047829285 -0.021759421, 0.03453061 0.047806904 -0.021884754, 0.034511328 0.047780305 -0.021940261, 0.034485504 0.047744498 -0.021987304, 0.038278759 0.044889107 -0.021823809, 0.038283274 0.044894263 -0.021759734, 0.041771561 0.041668251 -0.021759659, 0.041766763 0.041663393 -0.021823913, 0.038265571 0.044873536 -0.021884948, 0.041752174 0.041648954 -0.021885142, 0.038244024 0.044848338 -0.021940455, 0.041728765 0.041625664 -0.021940589, 0.041697398 0.041594297 -0.021987513, 0.038215324 0.044814706 -0.021987379, -0.044983581 -0.038165063 -0.021828264, -0.041771442 -0.041665763 -0.021764427, -0.044988811 -0.038169503 -0.021764159, -0.041766509 -0.041661009 -0.021828637, -0.044967785 -0.038151771 -0.021889567, -0.041752011 -0.04164654 -0.021889985, -0.044942677 -0.038130313 -0.021945089, -0.047908902 -0.034421682 -0.021828175, -0.047914416 -0.034425631 -0.021764129, -0.047892168 -0.034409672 -0.021889359, -0.047865376 -0.034390196 -0.021944761, -0.0478293 -0.034364715 -0.021991774, -0.050523371 -0.030454963 -0.021827951, -0.050529376 -0.030458599 -0.021763816, -0.050505638 -0.030444294 -0.021889225, -0.050477505 -0.030427188 -0.021944553, -0.050439566 -0.030404538 -0.021991566, -0.052810207 -0.026290849 -0.021827668, -0.052816376 -0.026293859 -0.021763474, -0.052791893 -0.026281625 -0.021888942, -0.052762195 -0.026266664 -0.021944389, -0.052722543 -0.026247159 -0.021991208, -0.05475457 -0.021956041 -0.021827474, -0.054761007 -0.021958634 -0.02176325, -0.054735452 -0.021948323 -0.021888703, -0.05470483 -0.021936074 -0.021944016, -0.054663777 -0.021919712 -0.021991134, -0.056343809 -0.017478913 -0.021827385, -0.056350514 -0.01748085 -0.021762997, -0.056324273 -0.017472699 -0.02188848, -0.056292593 -0.017463103 -0.021943942, -0.056250557 -0.017449901 -0.021990672, -0.057567745 -0.012888432 -0.021827042, -0.057574436 -0.012889981 -0.021762714, -0.057547644 -0.012883857 -0.021888345, -0.057515249 -0.012876689 -0.021943659, -0.057472274 -0.012867048 -0.021990597, -0.058418125 -0.0082144588 -0.021826744, -0.058424994 -0.0082153678 -0.021762624, -0.058397874 -0.0082114637 -0.021887958, -0.058365107 -0.0082069635 -0.021943256, -0.058321401 -0.00820072 -0.021990374, -0.05888994 -0.0034869909 -0.021826431, -0.058896825 -0.0034873784 -0.021762297, -0.058869287 -0.0034856945 -0.021887571, -0.058836192 -0.0034838468 -0.021943048, -0.058792233 -0.0034811646 -0.021990076, -0.058979586 0.0012630671 -0.021826193, -0.058986485 0.0012631863 -0.021761924, -0.058959007 0.0012624413 -0.021887332, -0.058926001 0.0012618154 -0.02194275, -0.058881775 0.0012609214 -0.021989882, -0.058686823 0.0060047507 -0.02182585, -0.058693528 0.0060055107 -0.02176185, -0.058666363 0.0060027838 -0.021887034, -0.058633551 0.0059993714 -0.021942586, -0.058589563 0.0059948117 -0.021989524, -0.058013305 0.010707587 -0.021825731, -0.058020219 0.010708943 -0.021761402, -0.057993218 0.010703951 -0.02188693, -0.057960808 0.010697931 -0.021942303, -0.057917252 0.010689825 -0.021989182, -0.056963623 0.015341103 -0.021825537, -0.056970507 0.015342847 -0.021761209, -0.056943908 0.015335709 -0.021886602, -0.05691202 0.015327021 -0.021942079, -0.056869268 0.015315607 -0.021989033, -0.055544645 0.019874945 -0.02182515, -0.055551246 0.01987721 -0.021760896, -0.055525452 0.019868046 -0.021886334, -0.055494323 0.019856989 -0.021941721, -0.055452615 0.019842073 -0.021988615, -0.053765431 0.024279907 -0.021824762, -0.053771749 0.024282843 -0.021760717, -0.053746864 0.024271712 -0.02188617, -0.0537166 0.024258032 -0.021941453, -0.053676262 0.024239808 -0.021988437, -0.051637307 0.028527662 -0.021824539, -0.051643699 0.028531164 -0.021760464, -0.051619351 0.028517649 -0.021885991, -0.051590547 0.028501689 -0.0219412, -0.051551789 0.028480217 -0.021988094, -0.049174488 0.03259027 -0.021824434, -0.049180299 0.032594115 -0.02176021, -0.049157515 0.032579049 -0.021885574, -0.049129844 0.032560647 -0.021941021, -0.049093217 0.032536328 -0.021988109, -0.046392858 0.036441475 -0.021824315, -0.046398342 0.036445975 -0.021760046, -0.046376675 0.036428839 -0.02188541, -0.046350583 0.036408439 -0.021940887, -0.046315894 0.036381081 -0.021987885, -0.043309972 0.040056467 -0.021824017, -0.043315053 0.040061131 -0.021759972, -0.043295026 0.040042371 -0.021885365, -0.043270618 0.040019944 -0.021940589, -0.043238312 0.039990053 -0.021987453, -0.039946422 0.043411493 -0.021823883, -0.03995131 0.043416649 -0.02175954, -0.039932668 0.043396369 -0.021884993, -0.039910212 0.04337208 -0.021940455, -0.03988035 0.043339521 -0.021987364, -0.036323965 0.046485096 -0.0218236, -0.036328286 0.046490759 -0.02175945, -0.036311343 0.046468899 -0.021884874, -0.036290899 0.046442941 -0.021940231, -0.036263719 0.046408162 -0.02198714, -0.03246583 0.049257427 -0.021823481, -0.032469615 0.049263045 -0.021759316, -0.032454506 0.049240157 -0.021884695, -0.032436267 0.04921259 -0.021940187, -0.032411963 0.049175605 -0.021987021, -0.028396994 0.051709995 -0.021823451, -0.028400421 0.051716074 -0.021759197, -0.028387174 0.051692039 -0.021884561, -0.028371245 0.051662937 -0.021939993, -0.028350011 0.051624209 -0.021986932, -0.024144173 0.053827375 -0.021823138, -0.024146959 0.053833574 -0.021759063, -0.024135694 0.053808585 -0.021884471, -0.024122164 0.05377838 -0.021939769, -0.024104103 0.053738073 -0.021986723, -0.019734651 0.055595517 -0.021823198, -0.01973699 0.055602059 -0.021758899, -0.019727737 0.055576175 -0.021884456, -0.019716725 0.055544943 -0.021939695, -0.019701853 0.055503324 -0.021986589, -0.015197247 0.057003155 -0.021823242, -0.015198946 0.057009891 -0.021759018, -0.015191764 0.056983531 -0.021884337, -0.01518333 0.056951538 -0.021939874, -0.015172109 0.056908831 -0.021986678, -0.010561153 0.058041289 -0.021822944, -0.010562226 0.05804795 -0.02175875, -0.010557458 0.058021158 -0.021884233, -0.010551527 0.057988629 -0.021939665, -0.010543615 0.057945088 -0.02198647, -0.0058567524 0.058702826 -0.021823004, -0.0058572441 0.058709815 -0.021758825, -0.0058544874 0.058682427 -0.021884203, -0.0058512837 0.058649674 -0.021939561, -0.0058469325 0.058605656 -0.021986514, -0.0011142194 0.058990598 -0.02175878, -0.046347871 0.033180237 -0.012898147, -0.043449581 0.036894262 -0.012898102, -0.048929617 0.029239401 -0.012898356, 0.036893517 0.043450236 -0.012897685, 0.040355518 0.040255323 -0.012897775, -0.051176816 0.025098979 -0.012898698, 0.033179477 0.046348676 -0.012897626, -0.053074807 0.020787284 -0.012898818, 0.029238805 0.048930302 -0.012897223, -0.054609835 0.016333267 -0.01289919, 0.025098294 0.051177606 -0.012897208, -0.055772111 0.011767924 -0.012899399, 0.020786539 0.053075328 -0.012897044, -0.05655323 0.0071219653 -0.012899607, 0.016332671 0.054610789 -0.012897, -0.056948379 0.0024275631 -0.01289995, 0.011767104 0.05577293 -0.012896985, -0.05695422 -0.0022836477 -0.012900189, 0.0071214139 0.056554079 -0.01289697, -0.056571096 -0.0069788992 -0.012900338, 0.0024269223 0.056949079 -0.01289691, -0.055801377 -0.011626825 -0.01290068, -0.0022841543 0.056954861 -0.012896985, -0.054650754 -0.016195029 -0.012900993, -0.0069795549 0.056571946 -0.01289703, -0.053126559 -0.020652831 -0.012901172, -0.011627316 0.055802062 -0.01289703, -0.05123955 -0.024969429 -0.012901515, -0.01619567 0.054651409 -0.01289703, -0.049002424 -0.029115453 -0.012901828, -0.020653456 0.053127393 -0.012897253, -0.046430811 -0.033062607 -0.012901872, -0.02496998 0.051240265 -0.012897164, -0.043541744 -0.036783844 -0.012902036, -0.040355429 -0.040253967 -0.012902215, -0.02911602 0.049003273 -0.012897298, -0.033063278 0.046431601 -0.012897417, -0.036784545 0.043542847 -0.012897611, -0.040254533 0.040356204 -0.012897864, 0.011420295 0.054962367 -0.024354175, 0.017723843 0.053264871 -0.024354398, 0.0049625337 0.055916578 -0.024354145, -0.0015624017 0.05611451 -0.024354145, -0.008066237 0.05555369 -0.024354175, -0.014460742 0.054241717 -0.024354279, -0.020660013 0.052196085 -0.024354354, -0.026579812 0.049444824 -0.024354562, -0.032140017 0.04602465 -0.024354741, -0.037265748 0.041982338 -0.02435483, -0.041887268 0.037372142 -0.024355218, -0.04594256 0.032256603 -0.024355516, -0.049376622 0.026704907 -0.024355784, -0.052142873 0.020791978 -0.024356157, -0.054203823 0.014598027 -0.024356514, -0.055531934 0.0082066357 -0.024356738, -0.056109086 0.0017041713 -0.02435717, -0.055927411 -0.0048209578 -0.024357587, -0.054989249 -0.011281326 -0.0243579, -0.053307757 -0.017588913 -0.024358302, -0.050905138 -0.023658618 -0.024358705, -0.04781428 -0.029408485 -0.024358869, -0.044076726 -0.034760401 -0.024359107, 0.03645204 0.040859103 -0.025538772, 0.034872055 0.043990985 -0.02435486, 0.038289592 0.042918727 -0.023170978, -0.040948644 -0.036348239 -0.025543004, -0.043013006 -0.038180798 -0.023175687, 0.029529423 0.047741711 -0.024354622, 0.023787439 0.050847054 -0.024354443, -0.039658248 -0.020363972 -0.028856978, -0.045671329 -0.020953357 -0.027681038, -0.04052031 -0.018589914 -0.028856859, -0.03624846 -0.017949656 -0.029597342, -0.034906209 -0.019922256 -0.029640332, -0.032656759 -0.018914461 -0.030030295, -0.038718581 -0.022098407 -0.028857112, -0.033990815 -0.021446735 -0.029640466, -0.030866474 -0.019395322 -0.030220896, -0.029075593 -0.01987645 -0.030395418, -0.043640688 -0.024907693 -0.027681276, 0.027913332 0.02820234 -0.02972199, 0.027988434 0.027920142 -0.029745936, 0.02595304 0.025889665 -0.030189201, -0.037702933 -0.023789391 -0.028857023, 0.021391988 0.023607731 -0.030825138, 0.023912728 0.023854658 -0.030586466, 0.021868527 0.021815345 -0.030938029, 0.027801424 0.028970182 -0.029644549, -0.033008605 -0.022929475 -0.029640466, -0.027260348 -0.020363972 -0.030556113, -0.028531909 -0.021751583 -0.030303508, -0.025486663 -0.020840272 -0.030697688, -0.036613867 -0.025433943 -0.028857306, -0.031962082 -0.024366945 -0.029640839, 0.0315139 0.032431468 -0.028730929, 0.033953235 0.033869818 -0.028176025, 0.032326087 0.032246947 -0.0286448, -0.041268378 -0.028667361 -0.027681381, -0.027541742 -0.022992402 -0.030303821, -0.023665875 -0.02132915 -0.030827373, -0.035452992 -0.027028456 -0.028857246, -0.030852944 -0.025756866 -0.029640809, -0.026497677 -0.024188235 -0.03030403, -0.023912817 -0.02385132 -0.030589178, -0.025952891 -0.025886446 -0.030192077, -0.029099405 -0.027725667 -0.02964054, -0.029929936 -0.027817488 -0.029528469, -0.034222633 -0.02857025 -0.028857335, -0.031392395 -0.028580487 -0.02925086, -0.029683322 -0.027096316 -0.029640809, -0.030709952 -0.028109312 -0.029395849, -0.038573176 -0.032202452 -0.027681589, -0.032925233 -0.030056104 -0.028857544, -0.031939283 -0.029203132 -0.02910167, -0.032319039 -0.029943138 -0.028956577, -0.032506332 -0.030753657 -0.028825343, 0.033618405 0.035053372 -0.028046265, 0.03557612 0.035488561 -0.027677789, 0.030683398 0.032411754 -0.028844699, 0.030139998 0.032851502 -0.028854057, -0.010101706 0.047507092 -0.028045416, -0.010365486 0.043518826 -0.028824136, -0.011507004 0.048915565 -0.027676925, -0.0093165934 0.042251706 -0.029099897, -0.0097617805 0.04294911 -0.028955489, -0.0082794279 0.043807805 -0.028853461, -0.047479898 0.010222226 -0.0280478, -0.04315941 0.010087073 -0.028904736, -0.042575538 0.0096175373 -0.029031038, -0.04190582 0.0092894137 -0.029164374, -0.048884884 0.011631042 -0.027679279, -0.043785319 0.0083907545 -0.028855264, -0.035136029 -0.03352882 -0.028050154, -0.021868259 -0.021811977 -0.030940413, -0.032500386 -0.03150636 -0.028725579, -0.033953205 -0.033866704 -0.028179854, -0.035575971 -0.035485715 -0.027681768, -0.028270468 -0.027840987 -0.029725268, -0.02798833 -0.02791664 -0.029749036, -0.032326087 -0.032243714 -0.028648496, 0.024256214 0.026438698 -0.030301034, 0.027866662 0.029737443 -0.029543817, 0.027172402 0.029617205 -0.02963762, 0.028570578 0.03121762 -0.029272094, 0.028127804 0.030521646 -0.029414713, 0.023063004 0.027485877 -0.03030102, 0.020436123 0.027202532 -0.030554101, 0.0098571032 0.046860933 -0.02819033, 0.0088211447 0.046393797 -0.028328285, 0.029886305 0.03219156 -0.028978333, 0.0083216727 0.046051845 -0.028416023, 0.0291688 0.031785578 -0.029123574, 0.0078665912 0.045650199 -0.02851212, 0.025835708 0.030790091 -0.02963765, 0.021824777 0.02847901 -0.03030096, 0.028657407 0.034152597 -0.028853804, 0.024448648 0.031902596 -0.029637486, 0.032300457 0.038493961 -0.027677581, 0.020543724 0.029416397 -0.0303009, 0.019952178 0.02902244 -0.030393109, 0.027118832 0.035386816 -0.028853744, 0.023013636 0.032953024 -0.029637545, 0.030566216 0.03988497 -0.027677581, 0.025527045 0.036551714 -0.028853819, 0.021533534 0.033938736 -0.029637352, 0.019475073 0.030816942 -0.030218452, 0.018998101 0.03261058 -0.030027494, 0.028772146 0.04119809 -0.027677551, 0.023885265 0.037645161 -0.0288537, 0.02001138 0.034858003 -0.029637203, 0.026921779 0.042430282 -0.027677491, 0.022196889 0.038664758 -0.02885364, 0.018449858 0.035709038 -0.029637322, 0.018041536 0.036206931 -0.029594094, 0.025018603 0.043579683 -0.027677268, 0.020464838 0.039608821 -0.028853536, 0.023066506 0.04464373 -0.027677238, 0.018692911 0.040475219 -0.02885361, 0.017082334 0.039812952 -0.029089734, 0.021069214 0.045620441 -0.027677223, 0.019030824 0.046507657 -0.027677327, 0.016120538 0.043427616 -0.028512165, 0.016955107 0.04730393 -0.027677089, 0.015705019 0.044482633 -0.028339073, 0.015059024 0.045416042 -0.0281986, 0.014846087 0.048007697 -0.027677, 0.014214844 0.046178341 -0.028099686, 0.013215408 0.046728641 -0.028047338, 0.012708038 0.048617348 -0.027677104, 0.012112394 0.047034621 -0.02804549, 0.010973558 0.047078639 -0.028094351, 0.010545164 0.049131826 -0.027676985, 0.0061617643 0.049871534 -0.027677029, 0.0063436627 0.044129848 -0.028853416, 0.0048674345 0.042655602 -0.029161006, 0.0035044402 0.044445395 -0.028853253, 0.0033563524 0.041146725 -0.029452726, 0.0018676817 0.039659947 -0.029717863, 0.0015350878 0.044557095 -0.028853312, 0.00036886334 0.038163275 -0.029962286, -0.00039429963 0.040192008 -0.029636964, -0.0011317283 0.036664531 -0.030185148, 0.0017302483 0.050220981 -0.027676895, -0.012651429 0.044160724 -0.028589278, -0.011896864 0.044140995 -0.028633133, -0.00043727458 0.044581324 -0.028853282, -0.0021715462 0.04013513 -0.029637173, -0.0026189834 0.035179049 -0.030385062, -0.0035212934 0.035707057 -0.030300528, -0.0041298121 0.033669949 -0.030567035, -0.0024087876 0.044518337 -0.028853327, -0.0039446652 0.039999783 -0.029637128, -0.0027149171 0.050177351 -0.027676955, -0.013318241 0.04403463 -0.028575957, -0.0043756515 0.044368267 -0.028853402, -0.0057101548 0.039786115 -0.029637143, -0.0050972551 0.0355165 -0.030300468, -0.0066632032 0.035256058 -0.030300528, -0.0074833333 0.030320242 -0.030898616, -0.0063337237 0.044131175 -0.028853372, -0.0074642599 0.039494619 -0.029637158, -0.0089899898 0.040645048 -0.029393151, -0.0090541095 0.041467875 -0.029248923, -0.0071388781 0.049740911 -0.02767694, -0.0082160383 0.034926906 -0.030300513, -0.0099771619 0.038406149 -0.029721588, -0.0094641894 0.039063737 -0.029637128, -0.0091287941 0.039825723 -0.029525489, -0.0097530037 0.034529433 -0.030300617, -0.012187079 0.036199525 -0.029957518, -0.0091467053 0.028658852 -0.031027436, -0.011089981 0.043924287 -0.028714478, -0.011270657 0.034064204 -0.030300766, -0.011111706 0.029186398 -0.030898556, -0.014373541 0.034017056 -0.030148968, -0.010827303 0.0269804 -0.031135276, -0.015784934 0.047707051 -0.027677163, -0.013949096 0.043775991 -0.028587729, -0.014366999 0.043511868 -0.028612167, -0.014743418 0.043187723 -0.028649271, -0.014236957 0.032934755 -0.030300647, -0.013647497 0.028090194 -0.03089872, -0.012618184 0.025192022 -0.03122586, -0.016569331 0.031825334 -0.030300736, -0.017879695 0.046962202 -0.027677193, -0.016386494 0.04154776 -0.028838262, -0.015679821 0.032272637 -0.030300811, -0.014876559 0.027458906 -0.03089878, -0.014409631 0.023403525 -0.031292915, -0.019939318 0.046125278 -0.027677104, -0.018030182 0.039907128 -0.029003188, -0.01607658 0.026773989 -0.03089866, -0.020381853 0.028020039 -0.030470967, -0.021960139 0.045198366 -0.027677193, -0.01967372 0.038266987 -0.029143989, -0.017245039 0.026036739 -0.030898914, -0.016202152 0.021614611 -0.031337097, -0.023937762 0.044182658 -0.027677357, -0.021316141 0.036627606 -0.029260859, -0.022951096 0.038221925 -0.028853714, -0.022959635 0.034987435 -0.02935496, -0.018379718 0.025248393 -0.030898899, -0.025868595 0.043080509 -0.027677447, -0.024619251 0.037169397 -0.028853729, -0.019478664 0.024410665 -0.030898839, -0.021999106 0.026406765 -0.030508384, -0.017995358 0.019825056 -0.031359062, -0.027748927 0.041894168 -0.027677447, -0.026239172 0.036043838 -0.028853744, -0.024601325 0.033349276 -0.029425994, -0.020539284 0.023525298 -0.030899003, -0.023615867 0.02479358 -0.030525625, -0.029574648 0.040625691 -0.027677566, -0.027807698 0.034847885 -0.028853878, -0.026245475 0.031709149 -0.029474109, -0.021559566 0.022593707 -0.030898973, -0.019720465 0.01810433 -0.031359464, -0.031342849 0.039277554 -0.02767773, -0.029321939 0.033583805 -0.028853908, -0.027888119 0.030070335 -0.029499784, -0.022537917 0.021617979 -0.030899033, -0.025233284 0.023180246 -0.030522704, -0.033049375 0.037853032 -0.02767773, -0.030778632 0.032253936 -0.028854087, -0.029448628 0.028513744 -0.02950345, -0.023471907 0.020599723 -0.030899167, -0.026875824 0.021542042 -0.030498847, -0.032175109 0.030860916 -0.028854027, -0.031009167 0.026957184 -0.02948691, -0.024360016 0.019541413 -0.030899331, -0.021445617 0.01638411 -0.031339645, -0.036265314 0.03478393 -0.027677819, -0.033508688 0.029407442 -0.028854266, -0.025200501 0.018444628 -0.030899212, -0.028517947 0.019904539 -0.03045395, -0.034776658 0.027896672 -0.028854251, -0.0325699 0.025400624 -0.029449984, -0.025991738 0.01731202 -0.030899286, -0.030160502 0.018266946 -0.030387983, -0.02317223 0.014662728 -0.031299338, -0.039197594 0.031442657 -0.027678087, -0.035976395 0.026330784 -0.028854355, -0.034131005 0.023843989 -0.029392689, -0.026731983 0.016145363 -0.03089945, -0.037106007 0.024713799 -0.028854445, -0.036384359 0.021597117 -0.029273674, -0.027419835 0.014947072 -0.030899405, -0.03180337 0.016629308 -0.030300319, -0.024900198 0.01294066 -0.031237647, -0.041822881 0.027855366 -0.02767837, -0.038162664 0.023048252 -0.028854489, -0.028054103 0.013719648 -0.030899629, -0.033446655 0.014991269 -0.030190453, -0.026558563 0.011287943 -0.03115809, -0.028633416 0.012465164 -0.030899674, -0.044120997 0.024049938 -0.027678415, -0.038637877 0.01935026 -0.029111043, -0.040050134 0.019585341 -0.028854683, -0.033498317 0.012851715 -0.03030175, -0.035088256 0.013354972 -0.030058295, -0.028216258 0.0096364319 -0.031057432, -0.040877149 0.01779452 -0.028854832, -0.040892497 0.017102629 -0.028903872, -0.044119313 0.012842476 -0.028588086, -0.043950677 0.013580889 -0.028578028, -0.046073675 0.020056382 -0.027678639, -0.034034073 0.011357576 -0.030301809, -0.036721274 0.011727303 -0.02990371, -0.029622957 0.0098857582 -0.030899793, -0.0300311 0.0085659623 -0.030899867, -0.02986142 0.007997632 -0.030935943, -0.046915591 0.01799877 -0.027678743, -0.043149188 0.014852926 -0.028650761, -0.034502923 0.0098411143 -0.030301929, -0.038379267 0.010075063 -0.029723018, -0.047665775 0.015905917 -0.027678907, -0.043620989 0.0142636 -0.028599501, -0.034904495 0.0083052963 -0.030302122, -0.040433317 0.0091062933 -0.029426306, -0.039701045 0.0092614889 -0.029542401, -0.039019406 0.0095747858 -0.02964133, -0.038685054 0.0098048598 -0.029685676, -0.031518668 0.0063468814 -0.03079094, -0.035237581 0.0067531765 -0.030302256, -0.033031851 0.0048394203 -0.03063789, -0.039474159 0.0075648874 -0.029638916, -0.04118064 0.0091160685 -0.029298142, -0.044118986 0.012086824 -0.028629154, -0.04395102 0.011350974 -0.028698415, -0.043624431 0.010672748 -0.028791979, -0.035501719 0.0051880032 -0.030302122, -0.039769977 0.0058113635 -0.02963908, -0.035696432 0.0036125332 -0.030302197, -0.034540668 0.0033362359 -0.030465096, -0.044113621 0.0064460337 -0.028855562, -0.03998816 0.0040465444 -0.029639274, -0.049721494 0.007265076 -0.027679443, -0.044355437 0.0044883192 -0.028855562, -0.040127903 0.0022738576 -0.029639319, -0.036063924 0.0018187165 -0.030269563, -0.049993858 0.0050583929 -0.027679503, -0.044510573 0.0025218725 -0.028855652, -0.040189117 0.000496611 -0.029639155, -0.050168768 0.0028422475 -0.027679667, -0.044578508 0.0005505532 -0.028855756, -0.040171653 -0.0012816936 -0.029639348, -0.039594233 -0.0016981661 -0.029731676, -0.050245374 0.00062032044 -0.027679622, -0.046374083 -0.0086379498 -0.028342023, -0.046859503 -0.0096640736 -0.028201789, -0.044559062 -0.0014218241 -0.028855875, -0.050223455 -0.0016028732 -0.027679801, -0.044452563 -0.0033913553 -0.028855979, -0.041613504 -0.0037102699 -0.029369086, -0.050103486 -0.0038226545 -0.02768001, -0.049885213 -0.0060353279 -0.027680203, -0.043623731 -0.0057133287 -0.028966993, -0.049569368 -0.0082360506 -0.027680188, -0.04566817 -0.0077505708 -0.028515115, -0.049156412 -0.010420531 -0.027680486, -0.047097698 -0.01077643 -0.028102845, -0.048647448 -0.012584642 -0.027680531, -0.046787947 -0.013025373 -0.028048947, -0.047074214 -0.011917099 -0.028050646, -0.048043072 -0.014724135 -0.02768074, -0.046256617 -0.014033616 -0.028098002, -0.045509875 -0.01489161 -0.028194025, -0.04734464 -0.01683493 -0.027680591, -0.043466032 -0.016010046 -0.028515652, -0.044587478 -0.015555233 -0.028331831, -0.04404141 -0.015816718 -0.028419465, -0.046553478 -0.018912628 -0.027680919, -0.039851874 -0.016981512 -0.02909331, 0.021655351 0.023855835 -0.029774517, 0.022948965 0.027106673 -0.029342234, 0.021181211 0.0256349 -0.029645547, 0.024068072 0.0261181 -0.029342428, 0.027939141 0.030981183 -0.028362647, 0.025363058 0.029958025 -0.028778374, 0.027566299 0.030201539 -0.02850607, 0.026599839 0.028865293 -0.028778374, 0.033949807 0.040099546 -0.026120961, 0.032077134 0.034808531 -0.027284965, 0.035639197 0.035551518 -0.026632831, 0.031668261 0.032667458 -0.027657524, 0.03079927 0.032703206 -0.027770206, 0.029950202 0.032537848 -0.0279046, 0.029163033 0.032180801 -0.028053507, 0.021789357 0.028047398 -0.029342264, 0.020707473 0.027412787 -0.029501364, 0.027621254 0.027553588 -0.02881676, 0.027499855 0.028009236 -0.028778598, 0.025794461 0.02573134 -0.029211283, 0.028061882 0.033145517 -0.028053567, 0.028479889 0.031651571 -0.028209448, 0.027380019 0.028679401 -0.028713718, 0.024081498 0.030997396 -0.028778434, 0.030585691 0.036126211 -0.027284816, 0.034076259 0.03399244 -0.027117178, 0.032508969 0.032429233 -0.027574062, 0.026643947 0.034295782 -0.028053448, 0.022757441 0.031982422 -0.028778255, 0.020234078 0.029189453 -0.029342115, 0.030461773 0.042809397 -0.026120812, 0.029040098 0.037380099 -0.027284801, 0.025178835 0.035385415 -0.028053492, 0.021392763 0.032910913 -0.028778195, 0.019288093 0.032738343 -0.028976515, 0.027443305 0.038567677 -0.027284577, 0.023669243 0.036412567 -0.028053477, 0.019990519 0.033780769 -0.028778061, 0.026758417 0.045216724 -0.026120782, 0.025797904 0.039687112 -0.027284622, 0.022117838 0.037375167 -0.028053463, 0.024106875 0.040736586 -0.027284622, 0.020527244 0.038271934 -0.028053284, 0.018343836 0.036280781 -0.028545961, 0.022866011 0.047304466 -0.026120558, 0.022373438 0.041713595 -0.027284622, 0.020600215 0.042617306 -0.027284399, 0.017401963 0.039814994 -0.028048918, 0.018812001 0.049058005 -0.026120514, 0.018790692 0.043445468 -0.027284354, 0.016462386 0.043339744 -0.027484447, 0.015986696 0.044553831 -0.027284399, 0.016947806 0.044197068 -0.027284428, 0.015225589 0.045618981 -0.027124852, 0.014624998 0.050464869 -0.026120439, 0.014486492 0.046284318 -0.027038157, 0.013638064 0.046799585 -0.026984617, 0.023963779 0.023905426 -0.029568583, 0.022129714 0.022076085 -0.029889211, 0.027383119 0.029351979 -0.028632656, 0.028149977 0.025569871 -0.028971896, 0.031725317 0.012157306 -0.029552892, 0.027981058 0.009743914 -0.030071855, 0.032388076 0.0096715838 -0.029575646, 0.025897339 0.0079409927 -0.030326501, 0.025416553 0.0097440779 -0.030314133, 0.027515396 0.010990217 -0.030071691, 0.024936005 0.011546567 -0.03028965, 0.031062752 0.014642835 -0.029504403, 0.026994199 0.012214541 -0.030071646, 0.026418835 0.013414145 -0.030071542, 0.024455532 0.013349175 -0.030252948, 0.025790006 0.014586538 -0.030071571, 0.023975194 0.015151545 -0.030203581, 0.025109276 0.015729651 -0.030071497, 0.030400291 0.017128006 -0.029429764, 0.029421836 0.016640365 -0.029575229, 0.024377897 0.016841114 -0.030071363, 0.0235136 0.016883269 -0.030143753, 0.029738098 0.019612521 -0.029328242, 0.028645143 0.017944574 -0.029575199, 0.029208377 0.021599129 -0.029227421, 0.027810678 0.019212544 -0.02957505, 0.028679043 0.023585036 -0.029108837, 0.026920229 0.020441711 -0.029574782, 0.023052081 0.018614769 -0.030071631, 0.025975406 0.021629646 -0.029574916, 0.022590846 0.020345792 -0.029986709, 0.02791591 0.023245454 -0.02922681, 0.024978191 0.022774041 -0.029574841, 0.026844323 0.024475306 -0.02922672, -0.023963571 -0.023902118 -0.029571369, -0.022834733 -0.024919406 -0.029577523, -0.022129595 -0.022072688 -0.029891565, -0.020396858 -0.022539034 -0.029989481, -0.025143057 -0.02821745 -0.029010832, -0.024177626 -0.026385114 -0.029306859, -0.02762112 -0.027550459 -0.028819844, -0.025794208 -0.025728315 -0.029214039, -0.021692827 -0.025919482 -0.029577523, -0.018663332 -0.023005664 -0.030074179, -0.022663385 -0.028885216 -0.029172763, -0.022968799 -0.027444109 -0.029306918, -0.020182714 -0.029553175 -0.029307112, -0.020507306 -0.026867315 -0.029577732, -0.016929269 -0.023472503 -0.030146345, -0.015789181 -0.025065362 -0.030074105, -0.015194878 -0.023939401 -0.030206099, -0.019280374 -0.027760804 -0.029577687, -0.014647916 -0.025748849 -0.030074254, -0.013397604 -0.024423227 -0.030255333, -0.017700389 -0.030221432 -0.02941364, -0.01801464 -0.028598368 -0.029577643, -0.013476983 -0.026380554 -0.030074298, -0.011599794 -0.024907216 -0.030291781, -0.015713632 -0.030756235 -0.029479817, -0.016712353 -0.029378325 -0.029577732, -0.012278959 -0.026959121 -0.030074209, -0.015376583 -0.030099019 -0.029577702, -0.011738524 -0.031826809 -0.029561758, -0.01105614 -0.027483135 -0.030074328, -0.013726249 -0.031291738 -0.029529199, -0.0098019838 -0.025391355 -0.030316144, -0.014009595 -0.030758977 -0.029577851, -0.0080041289 -0.025875509 -0.030328527, -0.0098110884 -0.027951866 -0.030074239, -0.0097509176 -0.03236188 -0.029577926, -0.024965599 -0.038403779 -0.027600065, -0.022117808 -0.037372425 -0.028057635, -0.023902729 -0.036256775 -0.028057769, -0.027905345 -0.03921397 -0.027121216, -0.026232332 -0.040352449 -0.02712138, -0.026558012 -0.03732045 -0.027599931, -0.032509029 -0.032426268 -0.027577728, -0.034076273 -0.033989429 -0.027121082, -0.032105103 -0.033159316 -0.027529716, -0.023329258 -0.039419279 -0.027600124, -0.027435556 -0.042203248 -0.026637182, -0.029185206 -0.041012824 -0.026637077, -0.021868184 -0.036804616 -0.028171122, -0.020527244 -0.038269028 -0.028057575, -0.019323736 -0.037489846 -0.028285354, -0.024512842 -0.041419387 -0.027121395, -0.021651581 -0.040365204 -0.02760008, -0.025637031 -0.04331927 -0.026637301, -0.01890032 -0.039098203 -0.02805765, -0.016778395 -0.038175195 -0.02836968, -0.02274999 -0.042413265 -0.027121469, -0.019935548 -0.041239798 -0.02760008, -0.023793459 -0.044358671 -0.026637286, -0.017240196 -0.039857745 -0.028057665, -0.020947039 -0.043331891 -0.027121335, -0.018184483 -0.042041153 -0.02760011, -0.021907732 -0.045319647 -0.02663742, -0.015549392 -0.040547326 -0.028057635, -0.014232278 -0.038860887 -0.028424472, -0.019107088 -0.044174224 -0.027121469, -0.016401187 -0.042768314 -0.027600333, -0.019983262 -0.04620041 -0.026637435, -0.013831213 -0.041165084 -0.028057739, -0.011685506 -0.039546832 -0.028450102, -0.013159141 -0.045018479 -0.027378276, -0.017233178 -0.044938326 -0.027121663, -0.032617211 -0.035391822 -0.027120963, -0.031549543 -0.033782631 -0.027515754, -0.030867621 -0.034267768 -0.027536705, -0.014588773 -0.043419883 -0.027600318, -0.030445591 -0.034468263 -0.027563125, -0.034113228 -0.037015155 -0.026636809, -0.035639092 -0.035548702 -0.026636854, -0.018023595 -0.046999559 -0.02663742, -0.02999942 -0.034614891 -0.027599841, -0.031100586 -0.036731631 -0.027121201, -0.027968541 -0.035161778 -0.027772397, -0.015328929 -0.045622975 -0.027121618, -0.028103247 -0.036171153 -0.027599826, -0.025936142 -0.035709128 -0.027925, -0.0160321 -0.047715694 -0.026637584, -0.032527134 -0.03841643 -0.026637048, -0.02952899 -0.03800647 -0.027121261, -0.030883402 -0.039749846 -0.026637107, 0.0011267811 0.045715407 -0.027611062, -0.00087940693 0.04572095 -0.027610943, 0.0010161102 0.041227669 -0.028445438, -0.00043427944 0.052539513 -0.026120231, -0.0007931143 0.04123272 -0.028445423, -0.011398867 0.044285819 -0.027611107, -0.01353474 0.050768018 -0.02612026, -0.012268603 0.044401228 -0.027544051, -0.013145104 0.044309765 -0.027513012, -0.0017253906 0.036515519 -0.029192477, -0.0026007444 0.04115811 -0.028445646, -0.0032742172 0.034970403 -0.029396504, 0.012693793 0.05098477 -0.026120409, 0.010419875 0.047258317 -0.027060553, 0.011706814 0.04731977 -0.026984587, -0.0039348304 0.036642015 -0.029149368, -0.004824236 0.03342396 -0.029578492, -0.013977215 0.044014454 -0.02752085, -0.0028838813 0.045638174 -0.027611136, -0.0044034421 0.041004464 -0.028445452, -0.0099130124 0.028346956 -0.030028075, -0.013443604 0.034313008 -0.029149368, -0.011611089 0.026652709 -0.030130625, -0.0055381656 0.036434144 -0.02914919, -0.0048827976 0.045467973 -0.027610913, -0.017750978 0.049451694 -0.026120514, -0.014506221 0.043695658 -0.027549043, 0.0075268298 0.045746058 -0.027484089, 0.0083664656 0.051870808 -0.026120365, 0.0059905946 0.044213325 -0.02782844, -0.0048456788 0.052317441 -0.026120171, -0.01497896 0.04328987 -0.027595386, 0.0091892481 0.046890676 -0.027190387, 0.0083060116 0.046400025 -0.027325109, -0.0061975121 0.040771976 -0.028445542, -0.0071309507 0.036156222 -0.029149219, -0.0065194964 0.031732708 -0.029752612, -0.0087936223 0.039506674 -0.028576374, -0.0086160451 0.040359542 -0.028440565, -0.0068723857 0.045210019 -0.027611107, -0.00797984 0.040460795 -0.028445289, -0.0086409301 0.041226596 -0.028290674, -0.0088670701 0.042065546 -0.028133959, -0.0087098628 0.035808548 -0.029149383, -0.0082157999 0.030040264 -0.029902294, -0.0097164214 0.03803131 -0.028777927, -0.0091673434 0.038714558 -0.028691024, -0.0092227608 0.051725477 -0.02612032, -0.0088485926 0.044864982 -0.027611151, -0.0092820674 0.042829156 -0.027979568, -0.0090293288 0.031111583 -0.029752612, -0.011579454 0.036172658 -0.028978869, -0.0098623633 0.043474615 -0.027835995, -0.010807812 0.044433802 -0.027611062, -0.010580808 0.043970197 -0.027710587, -0.010385334 0.030685648 -0.029752612, -0.013034403 0.029657498 -0.02975288, -0.015308782 0.032452345 -0.029290393, -0.016545832 0.04263097 -0.027611166, -0.016468093 0.041804716 -0.027768061, -0.014322698 0.029057086 -0.029752702, -0.013309792 0.024958149 -0.030210868, -0.017175034 0.030590698 -0.029402718, -0.018399686 0.041864157 -0.027611166, -0.017958254 0.040318355 -0.027920678, -0.015583336 0.028400958 -0.029752716, -0.018668741 0.029100403 -0.029472172, -0.020163074 0.02760984 -0.02952382, -0.015008882 0.023263007 -0.030269802, -0.021841899 0.047786057 -0.026120424, -0.020218119 0.041016906 -0.027611211, -0.019449294 0.038831189 -0.028053522, -0.016813785 0.027690038 -0.029752806, -0.021997511 0.040090695 -0.027611375, -0.020940959 0.037342981 -0.028167009, -0.025778234 0.045782447 -0.026120692, -0.023734957 0.039087117 -0.027611241, -0.022806421 0.035482287 -0.028281331, -0.029532641 0.043455407 -0.026120797, -0.019175798 0.026110068 -0.02975291, -0.016708404 0.021567583 -0.030307844, -0.025426388 0.038008481 -0.027611449, -0.024672836 0.033620462 -0.028365612, -0.020302355 0.025243849 -0.02975291, -0.018408194 0.019872129 -0.030325994, -0.021657631 0.026118979 -0.029558092, -0.027068838 0.036856622 -0.027611613, -0.023152396 0.024628043 -0.029574722, -0.033078119 0.040821284 -0.026120976, -0.028659254 0.035633981 -0.027611658, -0.026539683 0.031758294 -0.028420478, -0.03019467 0.034342512 -0.027611509, -0.028407007 0.029895693 -0.028446063, -0.03241092 0.033909693 -0.027373195, -0.036389902 0.03789863 -0.02612114, -0.0017533302 0.049111143 -0.02689822, -0.0059611797 0.048779517 -0.026898235, 0.0051286966 0.045440882 -0.027611032, 0.0044516921 0.042678162 -0.028148472, 0.003980279 0.052390277 -0.026120409, 0.0031306148 0.045622036 -0.027611017, 0.0029104501 0.041140586 -0.02844432, 0.0013671368 0.039600924 -0.028716832, -0.0096379519 0.04760389 -0.027022719, -0.010125145 0.048087969 -0.026898369, -0.00017827749 0.038059056 -0.028965995, -0.019113034 0.045273051 -0.026898533, -0.022927552 0.043465868 -0.026898503, 0.011619568 0.046995029 -0.01539737, 0.011619523 0.046995744 -0.02673842, 0.010643557 0.046960354 -0.02679494, 0.010565221 0.046948448 -0.015397489, 0.0096968412 0.046737313 -0.026885659, 0.0095442533 0.046681657 -0.01539737, 0.0086705089 0.046250835 -0.027030095, 0.0086017996 0.046206757 -0.015397415, 0.0077801794 0.045545086 -0.027208731, 0.0077802241 0.045544401 -0.015397459, 0.0077204704 0.045485497 -0.027223706, -0.044335231 -0.016004622 -0.027328745, -0.044053197 -0.016765296 -0.027328789, -0.043379262 -0.016352281 -0.027487844, -0.039856717 -0.017300546 -0.028052256, -0.049103364 -0.018687606 -0.026124224, -0.050499767 -0.014497042 -0.026124015, -0.046135619 -0.014603108 -0.02706404, -0.046832219 -0.013519362 -0.02698791, -0.047360063 -0.022745952 -0.026124492, -0.043309435 -0.018602222 -0.0273287, -0.042489082 -0.020406425 -0.027329028, -0.036325023 -0.018251508 -0.028549045, -0.037951455 -0.020232454 -0.028134018, -0.032785043 -0.019204438 -0.028979361, -0.033829108 -0.019904226 -0.028781116, -0.041593701 -0.022174329 -0.027328998, -0.04528214 -0.026643619 -0.026124731, -0.037067428 -0.021809727 -0.028133973, -0.045201793 -0.015485093 -0.027193874, -0.032962441 -0.02130869 -0.02878125, -0.029238373 -0.02015911 -0.029344842, -0.040624738 -0.023903087 -0.027329177, -0.036117837 -0.023348644 -0.028134152, -0.032037631 -0.022675499 -0.02878134, -0.02746281 -0.020637095 -0.029504225, -0.042884007 -0.030352965 -0.02612491, -0.03958407 -0.025589764 -0.027329192, -0.028100133 -0.021717578 -0.029345021, -0.02568616 -0.021115273 -0.02964811, -0.035104394 -0.024846137 -0.028134227, -0.031056136 -0.02400206 -0.02878131, -0.038473323 -0.027230933 -0.0273294, -0.027162462 -0.022879511 -0.029345065, -0.023908332 -0.021593928 -0.029777125, -0.034028813 -0.02629979 -0.028134391, -0.030654699 -0.027644366 -0.028442234, -0.030019671 -0.025286287 -0.028781608, -0.031394199 -0.02810438 -0.028291598, -0.037294701 -0.028824061 -0.0273294, -0.040182859 -0.033847749 -0.026125148, -0.028076321 -0.027427912 -0.028781593, -0.026176646 -0.024000973 -0.029345185, -0.028946683 -0.027294099 -0.028694302, -0.03289333 -0.027706996 -0.028134346, -0.032007456 -0.028725535 -0.028134465, -0.028930128 -0.026525795 -0.028781682, -0.029823557 -0.027368188 -0.028578997, -0.036050007 -0.030366197 -0.02732943, -0.032458961 -0.029473126 -0.027979434, -0.034741625 -0.031854823 -0.02732949, -0.032723114 -0.030303881 -0.027835637, -0.032786325 -0.031178564 -0.027710587, -0.032701358 -0.031814739 -0.027635738, -0.046507746 -0.013433412 -0.015400827, -0.046507761 -0.01343292 -0.026741683, -0.045988426 -0.014261559 -0.026798487, -0.045940474 -0.014323115 -0.015400827, -0.045323655 -0.014968053 -0.026888922, -0.045199007 -0.015074104 -0.015400901, -0.044386521 -0.015615374 -0.027033791, -0.044316232 -0.015652686 -0.015400872, -0.04333204 -0.016032547 -0.027212232, -0.043331951 -0.016033232 -0.01540105, -0.043250501 -0.016054496 -0.027227238, -0.0016068667 -0.042260796 -0.028265312, -0.0011285245 -0.045791298 -0.027600437, 0.0009368062 -0.042945921 -0.028145, 0.0010659844 -0.028318331 -0.030208379, 0.0020330399 -0.032168671 -0.029775694, 0.0034443587 -0.028959006 -0.03012386, 0.0023679435 -0.035625845 -0.029319778, 0.00062003732 -0.03222692 -0.029775575, 0.00088113546 -0.045796782 -0.027600393, 0.0034421086 -0.032048494 -0.029775679, 0.004403919 -0.036174178 -0.029213652, 0.0028888732 -0.045714095 -0.027600393, 0.0034790337 -0.043630362 -0.027994335, 0.0048444867 -0.03186658 -0.029775724, 0.0055843443 -0.029535517 -0.030027702, 0.0064390004 -0.036722496 -0.029089153, 0.0062376261 -0.031623632 -0.029775739, 0.0084729195 -0.037270129 -0.028945431, 0.0077232122 -0.030111641 -0.029911846, 0.00761877 -0.031319499 -0.029775664, 0.010505483 -0.037817672 -0.028782159, 0.01039283 -0.035804734 -0.029088914, 0.011626884 -0.038319454 -0.028652027, 0.011090815 -0.03802377 -0.02872391, 0.0098609179 -0.030687585 -0.029775634, 0.010307848 -0.045059353 -0.027516529, 0.011144653 -0.044781566 -0.027531862, 0.011890963 -0.04431726 -0.027584538, 0.012507454 -0.043691352 -0.027671665, 0.012806386 -0.039586663 -0.028385743, 0.01195319 -0.035314426 -0.02908878, 0.012293383 -0.038885474 -0.028527915, 0.011997238 -0.031263068 -0.029618576, 0.013322666 -0.039360628 -0.028395057, 0.013142601 -0.04038769 -0.028232172, 0.013490647 -0.034756169 -0.029088616, 0.014042616 -0.031814083 -0.029447541, 0.01322113 -0.042111367 -0.027924418, 0.014685571 -0.043387324 -0.027600423, 0.013283327 -0.041244954 -0.028075442, 0.015036374 -0.038738325 -0.028395012, 0.015002266 -0.034131169 -0.029088736, 0.016574562 -0.042701483 -0.027600303, 0.016721055 -0.038041621 -0.028394938, 0.016484961 -0.033440188 -0.029088736, 0.0160864 -0.032364845 -0.029255867, 0.018128127 -0.032914653 -0.029043704, 0.018431604 -0.041933358 -0.027600199, 0.018373445 -0.037271604 -0.028394803, 0.020253181 -0.041084632 -0.027600259, 0.019990757 -0.036429793 -0.028394729, 0.020167783 -0.033464089 -0.028810114, 0.022035792 -0.040156811 -0.027600095, 0.029300943 -0.03592445 -0.027488932, 0.030590177 -0.036119506 -0.027288839, 0.027023435 -0.035310864 -0.027861699, 0.021569341 -0.035517827 -0.028394744, 0.022456512 -0.034080639 -0.028521791, 0.02377598 -0.039151564 -0.027600154, 0.031893283 -0.035992995 -0.027129337, 0.0060198605 -0.044314757 -0.027813062, 0.025470272 -0.038071096 -0.027600095, 0.024741799 -0.034696266 -0.028205648, 0.027115777 -0.036917284 -0.02760005, 0.015268862 -0.046249747 -0.026998088, 0.012958929 -0.042940661 -0.027787298, 0.03283897 -0.035685703 -0.027042612, 0.033709437 -0.035208553 -0.026989117, 0.019128427 -0.045306474 -0.026894942, -0.0052721351 -0.033568069 -0.029554591, -0.0050166398 -0.031840175 -0.02977556, -0.0078195333 -0.032882199 -0.029578075, -0.0060728788 -0.026395425 -0.030328393, -0.003692925 -0.027036592 -0.030309722, -0.0091066957 -0.044890746 -0.027600244, -0.011229366 -0.045544013 -0.027377099, -0.0097543597 -0.040066808 -0.028450102, -0.0077165067 -0.040615499 -0.028431892, -0.0036152601 -0.032029465 -0.02977556, -0.0027249008 -0.034254074 -0.029504091, -0.0013131946 -0.027677417 -0.03027004, 0.0085593611 -0.044998407 -0.027600467, 0.0094280839 -0.045132726 -0.027540073, -0.0071288794 -0.045247182 -0.027600288, -0.0056792349 -0.041164219 -0.02839534, -0.0022067428 -0.032157108 -0.029775679, -0.0051374584 -0.045516118 -0.027600378, -0.0036426336 -0.041712597 -0.028339759, -0.00017797947 -0.034940168 -0.029425874, -0.00079424679 -0.032222867 -0.029775679, -0.0031359792 -0.045697793 -0.027600482, 0.02933903 -0.035602242 -0.027228311, 0.029420614 -0.035624236 -0.02721338, 0.029420629 -0.035624802 -0.015402094, 0.020947263 -0.033342287 -0.02845782, 0.012512431 -0.031070888 -0.029316559, -0.0059900433 -0.026089087 -0.015401497, 0.0032681376 -0.028581515 -0.029866397, -0.0059901625 -0.026088133 -0.030060157, 0.0086024255 -0.044775724 -0.027439669, 0.0086509287 -0.044788718 -0.027435005, 0.008650884 -0.044788897 -0.024988368, 0.00047895312 -0.042587966 -0.028009564, -0.0096955895 -0.039848357 -0.024988011, -0.0046066493 -0.041218504 -0.028207436, -0.0096955597 -0.03984803 -0.028287873, 0.00026923418 -0.035282135 -0.029209539, -0.0078754574 -0.033088759 -0.029380694, -0.0078753084 -0.033088997 -0.024987742, 0.010471165 -0.038029656 -0.024988085, 0.0053540766 -0.036651522 -0.028956547, 0.010431722 -0.038018823 -0.02858521, 0.01047112 -0.038029328 -0.028581455, 0.010707542 -0.042237461 -0.022902608, 0.010191321 -0.04267551 -0.022902444, 0.010475948 -0.0424878 -0.022902429, 0.010244891 -0.04017143 -0.022902384, 0.0099287778 -0.040043861 -0.022902325, 0.010521203 -0.040371224 -0.022902265, 0.01074174 -0.040631056 -0.022902489, 0.010893717 -0.040936291 -0.022902444, 0.010968238 -0.041269079 -0.022902399, 0.010960966 -0.041609749 -0.022902384, 0.010872364 -0.041939095 -0.022902369, 0.0095308721 -0.042823315 -0.022902369, 0.0098700672 -0.042789444 -0.022902399, 0.0091933459 -0.042775035 -0.022902355, -0.0084177256 -0.035103291 -0.022901997, -0.0091531873 -0.03783451 -0.022902101, 0.035194814 -0.021491393 -0.028449014, 0.036103696 -0.019927114 -0.02844888, 0.033047944 -0.018872812 -0.028969169, 0.039026096 -0.023831248 -0.027614981, 0.040033832 -0.02209644 -0.027614906, 0.044050828 -0.012268797 -0.027614251, 0.044585839 -0.01157327 -0.027547181, 0.044944674 -0.010768488 -0.027516186, 0.032484785 -0.016761065 -0.029195428, 0.036943078 -0.018324241 -0.028448865, 0.031921029 -0.014647156 -0.029399261, 0.035715818 -0.032650918 -0.027064979, 0.035125449 -0.033796072 -0.026989102, 0.03369911 -0.014910743 -0.029152215, 0.031356752 -0.0125314 -0.02958101, 0.04510504 -0.009900108 -0.027523875, 0.040964574 -0.020319209 -0.027614787, 0.037711248 -0.016686201 -0.028448686, 0.029504269 -0.0055861026 -0.030029699, 0.036436528 -0.0055116713 -0.029151723, 0.028886169 -0.0032682568 -0.030132294, 0.034320742 -0.013418376 -0.029152021, 0.041816533 -0.018503115 -0.027614638, 0.045093209 -0.0092826188 -0.027551934, 0.035852507 -0.029389128 -0.0274885, 0.035293475 -0.027292326 -0.027832538, 0.04497844 -0.0086703598 -0.027598336, 0.03601256 -0.031401098 -0.027195007, 0.036029473 -0.030390814 -0.027329743, 0.038406938 -0.015016183 -0.028448611, 0.034876361 -0.011900067 -0.029151917, 0.030739665 -0.010217682 -0.029754937, 0.038609266 -0.012135357 -0.028579444, 0.039259106 -0.012715638 -0.028443471, 0.042587727 -0.0166509 -0.027614519, 0.039028645 -0.013317138 -0.028448492, 0.040022522 -0.013127521 -0.028293818, 0.040862128 -0.013351306 -0.028137207, 0.035364732 -0.010358989 -0.029152021, 0.030122191 -0.0079024583 -0.029904395, 0.037792757 -0.010598481 -0.028780624, 0.03811042 -0.01141572 -0.02869387, 0.043277204 -0.014766991 -0.027614608, 0.041730881 -0.013373718 -0.027982578, 0.031456664 -0.0077334344 -0.029754817, 0.037114829 -0.0080558211 -0.028981522, 0.042579919 -0.013193905 -0.027839139, 0.043883324 -0.012854561 -0.027614325, 0.043368474 -0.012819499 -0.027713686, 0.031765714 -0.0063463151 -0.029754758, 0.032199904 -0.0035379231 -0.02975449, 0.035757646 -0.0029659569 -0.02929242, 0.045191005 -0.0069839507 -0.027613953, 0.044436678 -0.0066381693 -0.027770847, 0.032324135 -0.0021222681 -0.02975443, 0.028267875 -0.00094993412 -0.030212417, 0.035078406 -0.00041873753 -0.029404238, 0.045453936 -0.0049952269 -0.027613997, 0.043894663 -0.004604429 -0.027923271, 0.032386199 -0.00070245564 -0.02975443, 0.034534812 0.0016199946 -0.029473603, 0.033990994 0.0036593527 -0.029525131, 0.027649507 0.0013691634 -0.030270845, 0.045629397 -0.0029966682 -0.027613729, 0.043352008 -0.0025696903 -0.028055981, 0.03238593 0.00071869791 -0.029754296, 0.045716956 -0.00099225342 -0.027613595, 0.042809337 -0.0005338192 -0.028169051, 0.045716554 0.0010138303 -0.027613595, 0.042130396 0.0020122826 -0.028283074, 0.032198355 0.0035541356 -0.029754102, 0.02703096 0.0036887825 -0.030308813, 0.04562825 0.0030180216 -0.027613431, 0.041451499 0.0045593083 -0.028367251, 0.032011673 0.0049630105 -0.029753938, 0.026412308 0.0060084164 -0.030326635, 0.033447057 0.0056992322 -0.029558927, 0.045451969 0.0050163716 -0.027613297, 0.032903269 0.0077389181 -0.02957572, 0.045188367 0.0070051104 -0.027613088, 0.04077211 0.0071072429 -0.02842176, 0.044837579 0.0089803934 -0.027613118, 0.040092647 0.0096557736 -0.028447285, 0.045568153 0.011115491 -0.027374983, 0.043406919 -0.023034796 -0.026902229, 0.045223817 -0.019224986 -0.02690208, 0.036787361 -0.027159616 -0.02761513, 0.034733206 -0.025191963 -0.028152198, 0.037943274 -0.025520027 -0.0276151, 0.034172386 -0.023088515 -0.02844809, 0.033610359 -0.020982012 -0.02872017, 0.046044007 -0.015453026 -0.027026191, 0.046706691 -0.015272871 -0.026901782, 0.048762932 -0.0060819089 -0.026901409, 0.049105033 -0.0018748194 -0.026901126, 0.034888461 -0.033559009 -0.01540193, 0.034888446 -0.033558384 -0.026742861, 0.035346299 -0.032694921 -0.02679947, 0.035375401 -0.032622769 -0.015401959, 0.035626039 -0.031764314 -0.026889905, 0.035654917 -0.031605005 -0.015401796, 0.035718009 -0.030631691 -0.027034432, 0.035714552 -0.030551508 -0.01540184, 0.035551935 -0.029508218 -0.027213007, 0.035552055 -0.029508889 -0.015401721, 0.035530269 -0.029426634 -0.027227879, 0.040217146 0.017277062 -0.027990565, 0.041290939 0.019833863 -0.027596787, 0.039455473 0.01895225 -0.027990475, 0.046251819 0.019869119 -0.026633829, 0.047046095 0.017907441 -0.026633754, 0.04498288 0.017122045 -0.027118027, 0.044223398 0.018997848 -0.027118042, 0.038623899 0.020593986 -0.027990401, 0.037403777 0.019741282 -0.028261736, 0.042088076 0.018080771 -0.027596906, 0.043385804 0.02083993 -0.027117893, 0.04042083 0.021551952 -0.027596608, 0.045375839 0.021795869 -0.026633516, 0.037724242 0.022199258 -0.027990341, 0.036725208 0.022286475 -0.02814135, 0.042471424 0.022645324 -0.027117759, 0.039479196 0.023231924 -0.027596593, 0.044419557 0.023683891 -0.026633367, 0.041482136 0.024410546 -0.027117535, 0.038467899 0.024871036 -0.027596474, 0.036046982 0.024830401 -0.02799052, 0.043384805 0.02553001 -0.026633412, 0.040419459 0.026132673 -0.027117595, 0.037388399 0.026466101 -0.027596384, 0.035369143 0.027373075 -0.02780889, 0.042273432 0.027331278 -0.026633456, 0.039285317 0.027808502 -0.027117357, 0.036242962 0.028014153 -0.027596295, 0.041087314 0.029083908 -0.026633158, 0.033318058 0.031967506 -0.027522698, 0.032927126 0.032224402 -0.027543128, 0.03808178 0.029435441 -0.027117401, 0.035033584 0.029512838 -0.02759628, 0.034691453 0.029914051 -0.027596176, 0.039828464 0.030785426 -0.026633099, 0.045058325 0.013049453 -0.02737391, 0.041526005 0.013837829 -0.027990833, 0.039577499 0.011588097 -0.028447047, 0.039033756 0.01362741 -0.028428897, 0.03681086 0.031010062 -0.027117461, 0.034393966 0.030694634 -0.027537838, 0.04345794 0.014481679 -0.027596965, 0.040907741 0.015571162 -0.027990803, 0.038490236 0.015666127 -0.028392151, 0.038499221 0.032432362 -0.026632994, 0.045662716 0.015216172 -0.027118251, 0.035474837 0.03252995 -0.027117312, 0.033927366 0.031392381 -0.027512908, 0.042810991 0.016295567 -0.027596936, 0.047757164 0.015914068 -0.026634037, 0.037101954 0.034021974 -0.026633069, 0.037947103 0.01770407 -0.028336316, 0.016164318 0.043211803 -0.02722393, 0.018403262 0.034814328 -0.028454021, 0.020653397 0.026373893 -0.029313356, 0.025589585 0.0078581572 -0.015399694, 0.023119614 0.017123505 -0.029863834, 0.02558966 0.0078589618 -0.030058265, 0.034476966 0.029840037 -0.02743569, 0.034464106 0.029888496 -0.027430639, 0.03446418 0.029888406 -0.024984196, 0.036644191 0.021711051 -0.028005973, 0.039358616 0.011529654 -0.024985135, 0.03800106 0.016622081 -0.028204381, 0.039358661 0.011529773 -0.028284833, 0.030422136 0.017876595 -0.029206678, 0.032594889 0.009726584 -0.029378325, 0.032594994 0.0097263604 -0.024985284, 0.027700365 0.028085098 -0.024984464, 0.02906552 0.022964939 -0.02895318, 0.02771087 0.028045818 -0.028581589, 0.027700454 0.028085321 -0.028577641, 0.037343338 0.010992154 -0.022899568, 0.032448635 0.029351085 -0.022898421, 0.034610376 0.010263517 -0.022899404, 0.032321766 0.029667348 -0.02289854, 0.032122925 0.029944301 -0.022898331, 0.031863451 0.030165508 -0.022898361, 0.031558588 0.03031832 -0.022898391, 0.031226143 0.0303936 -0.022898301, 0.030885354 0.030387089 -0.022898376, 0.030555874 0.030299291 -0.022898331, 0.029817909 0.029620215 -0.022898421, 0.029715598 0.028622419 -0.022898465, 0.030006185 0.029904291 -0.022898301, 0.030257091 0.03013508 -0.022898421, 0.029702842 0.029299065 -0.022898391, 0.029668301 0.028959945 -0.02289845, -0.045503184 -0.0076049715 -0.027226627, -0.045562893 -0.0076645613 -0.027211681, -0.045562893 -0.007665202 -0.015400484, -0.039350212 -0.0014673918 -0.028456122, -0.033165753 0.0047018379 -0.029314667, -0.019599274 0.018233418 -0.015399098, -0.026387632 0.011462957 -0.029864132, -0.019599363 0.018234342 -0.030057549, -0.043079272 0.014940277 -0.027436376, -0.043114841 0.014904857 -0.027431533, -0.043114915 0.014904544 -0.024985135, -0.037123144 0.020881578 -0.028005987, -0.029663056 0.028322741 -0.024984255, -0.033394322 0.024601221 -0.028203845, -0.029663026 0.028322995 -0.028283775, -0.030691206 0.017410189 -0.029206544, -0.024719536 0.02336733 -0.02937755, -0.024719536 0.023366913 -0.024984449, -0.034419507 0.013691217 -0.028953701, -0.038142532 0.0099775791 -0.028582498, -0.026192605 0.02484338 -0.022898436, -0.041641802 0.01342763 -0.022899255, -0.028190017 0.026846007 -0.022898555, -0.041839674 0.013180375 -0.022899389, -0.041977361 0.012895256 -0.022899315, -0.041978449 0.011961132 -0.022899315, -0.041841418 0.011675507 -0.022899374, -0.042048186 0.012586623 -0.022899345, -0.042048544 0.012269825 -0.022899434, -0.041388839 0.016946271 -0.027809456, -0.043250605 0.015088916 -0.02759701, -0.039525867 0.01880461 -0.027990893, -0.037661806 0.020663977 -0.028141409, -0.035796806 0.022524342 -0.028261527, -0.034304082 0.024013385 -0.028335944, -0.032810941 0.025502831 -0.028391495, -0.03131716 0.026992887 -0.028428018, -0.029822871 0.028483406 -0.028446227, -0.026436239 0.021352425 -0.029551491, -0.02456829 0.023215696 -0.029574797, -0.028303981 0.019489408 -0.029500961, -0.030171454 0.017626703 -0.029423028, -0.032038212 0.015764594 -0.029316604, -0.0335311 0.014275759 -0.029210895, -0.035023406 0.012787223 -0.029086277, -0.036514595 0.011299759 -0.028942779, -0.038005069 0.0098131299 -0.028779551, -0.044092953 -0.005745098 -0.027859986, -0.04576312 -0.0074108243 -0.027487174, -0.042420089 -0.0040764511 -0.028204024, -0.040744334 -0.0024048835 -0.028519973, -0.039065942 -0.00073131919 -0.028808087, -0.037570328 0.00076048076 -0.029041842, -0.036073029 0.002253592 -0.029254019, -0.034574538 0.0037483424 -0.02944544, -0.033074677 0.0052441508 -0.029616371, -0.031508029 0.0068065971 -0.029773578, -0.029940367 0.0083699822 -0.029909626, -0.028371885 0.0099341422 -0.030025512, -0.026802734 0.011499003 -0.03012161, -0.025058553 0.013238579 -0.030205905, -0.023314074 0.014978528 -0.030267566, -0.021569133 0.016718969 -0.030307487, -0.019824028 0.018459707 -0.030325964, -0.0053604692 0.010390624 -0.025399372, -0.0051879138 0.009441793 -0.025399595, -0.010754213 0.0094956756 -0.025399566, -0.010639027 0.0098638088 -0.025399446, -0.010375649 0.0053880513 -0.02539973, -0.0094273537 0.0052129477 -0.025399819, -0.0057552457 0.011270478 -0.025399506, -0.0084648132 0.0052700341 -0.025399789, -0.010439008 0.010193542 -0.025399461, -0.011254475 0.0057846755 -0.025399759, -0.0083513558 0.010573432 -0.025399551, -0.0075437725 0.0055556446 -0.025399774, -0.010165945 0.010466039 -0.025399476, -0.0087029636 0.010732278 -0.025399327, -0.0067178607 0.0060535073 -0.025399804, -0.0098354965 0.010665148 -0.025399432, -0.0090821981 0.01080218 -0.025399417, -0.0094673038 0.010779604 -0.025399357, -0.0060352385 0.0067345351 -0.02539964, -0.01055105 0.0083793402 -0.025399655, -0.00553523 0.0075589716 -0.02539973, -0.010708958 0.0087312162 -0.025399551, -0.0052472651 0.0084792823 -0.02539961, -0.01077804 0.00911057 -0.025399536, -0.0049774945 -0.012646139 -0.025400773, -0.0049538016 -0.012260988 -0.025400817, 0.0004401058 -0.011366189 -0.025400639, 0.00061275065 -0.01231496 -0.025400817, -0.0045749992 -0.016368851 -0.025400981, -0.0036267638 -0.016543895 -0.025401056, -0.0026641488 -0.016486809 -0.025400981, -0.0054538101 -0.015971944 -0.025400952, -0.0048384815 -0.011892945 -0.025400832, 4.5344234e-05 -0.010486275 -0.025400698, -0.0017432421 -0.016201138 -0.025400996, -0.0046386421 -0.011562973 -0.025400564, -0.00091736019 -0.015703395 -0.025401011, -0.0025508404 -0.011183307 -0.025400653, -0.0043655038 -0.011290655 -0.025400832, -0.0029023886 -0.01102449 -0.025400624, -0.00023466349 -0.015022352 -0.025400817, -0.0047506094 -0.013377428 -0.025400937, -0.0040352494 -0.011091381 -0.025400639, -0.0032816529 -0.010954514 -0.025400609, 0.00026533008 -0.014197588 -0.025400788, -0.0036667883 -0.010977298 -0.025400594, -0.0049083978 -0.013025552 -0.025400892, 0.00055333972 -0.013277531 -0.025400773, 0.016381651 0.0045356452 -0.025399819, 0.016554266 0.0035868585 -0.025399834, 0.010987848 0.0036408007 -0.025399938, 0.011102974 0.0040090829 -0.025399849, 0.015987068 0.0054155588 -0.025399834, 0.011366442 -0.0004670769 -0.025400132, 0.012314826 -0.00064197183 -0.025400087, 0.011302978 0.0043387562 -0.025399923, 0.013277397 -0.00058500469 -0.025400028, 0.01048772 -7.0124865e-05 -0.025400072, 0.011576042 0.0046111494 -0.025399759, 0.014198408 -0.00029927492 -0.025399998, 0.01339069 0.0047185868 -0.025399879, 0.013039187 0.0048773736 -0.025399819, 0.01190649 0.0048103333 -0.025399849, 0.0150242 0.00019851327 -0.025400013, 0.012659937 0.0049473643 -0.025399759, 0.012274861 0.0049245507 -0.025399953, 0.015706912 0.00087945163 -0.025400117, 0.011190951 0.0025244206 -0.025399983, 0.016206831 0.0017040372 -0.025399819, 0.011033058 0.0028762519 -0.025399998, 0.016494825 0.002624467 -0.025400043, 0.010964096 0.0032558441 -0.025399983, 0.00020295382 0.0142674 -0.030572519, 0.0013358146 0.014206246 -0.030572504, 0.000376001 0.010046467 -0.029724345, -0.012428194 0.0096056163 -0.030933276, -0.012267873 0.010260731 -0.031009391, -0.01245375 0.0089384168 -0.030834883, -0.01234737 0.0082840621 -0.030718774, -0.011976495 0.010875463 -0.031058967, -0.011567205 0.011417821 -0.031079531, 0.0079701245 0.0080015361 -0.029942468, 0.010329366 0.009843424 -0.030572683, 0.0090505928 0.0077103525 -0.030056462, 0.0095147789 0.010632962 -0.030572563, 0.011078611 0.0089916438 -0.030572757, 0.010128707 0.0074202716 -0.030191064, 0.011204392 0.0071305186 -0.030346557, 0.011757806 0.0080831945 -0.030572817, 0.013346493 0.006553784 -0.030718952, 0.014836833 0.00096361339 -0.030719116, 0.014259055 -0.00048480928 -0.030573294, 0.01326625 -0.0006031245 -0.03034687, 0.014175311 -0.001616016 -0.030573383, 0.012477472 -0.0013896823 -0.030191615, -0.010463893 0.012202218 -0.031030998, 0.014001921 -0.0027372092 -0.030573294, 0.011687115 -0.002178371 -0.030057058, 0.013740197 -0.0038409978 -0.030573562, 0.010894731 -0.0029685348 -0.029942915, 0.013391346 -0.0049204826 -0.030573398, 0.010101199 -0.0037601739 -0.029849514, 0.012957796 -0.0059688836 -0.030573681, 0.0093065351 -0.0045527518 -0.029777139, 0.012442604 -0.0069795698 -0.030573606, 0.0045310706 -0.0093161613 -0.029777348, 0.005859524 -0.013006747 -0.030573994, 0.0037365109 -0.010108933 -0.029850066, 0.0068745613 -0.012500152 -0.03057386, 0.0048076212 -0.013431326 -0.030573994, 0.0029429793 -0.010900557 -0.029943317, 0.0037250519 -0.013770819 -0.030574039, 0.0021507889 -0.011690676 -0.030057594, 0.0026190728 -0.01402317 -0.030573949, 0.0013602972 -0.012479305 -0.030192301, 0.001496464 -0.014186993 -0.030574113, 0.00057156384 -0.013265863 -0.03034775, 0.00036452711 -0.014260858 -0.030573919, -0.00099897385 -0.014832705 -0.030719995, -0.0071567297 -0.011184826 -0.030347511, -0.0081817061 -0.01168637 -0.030573726, -0.0074437708 -0.010108456 -0.03019239, -0.0065853149 -0.013328344 -0.030720025, -0.0090844482 -0.010999352 -0.030573905, -0.0077314228 -0.0090294778 -0.0300574, -0.0099296719 -0.010243028 -0.030573696, -0.0080196112 -0.0079484433 -0.029943317, -0.010712355 -0.0094217211 -0.030573621, -0.008308351 -0.0068653375 -0.029849753, -0.01142706 -0.0085407346 -0.030573815, 0.015403748 0.0049396753 -0.031059146, 0.017491236 0.0065008104 -0.03179054, 0.015669405 0.0043137521 -0.031079993, -0.014228359 0.0010547787 -0.030573204, -0.014099628 0.0021817833 -0.030573055, -0.010624319 0.0018211454 -0.029849201, -0.010913089 0.0029041767 -0.029942736, -0.013881937 0.0032950491 -0.030573085, -0.011201188 0.003985256 -0.030056655, -0.013576314 0.0043876469 -0.030572891, -0.011488855 0.0050641447 -0.030191347, 0.018238172 0.0039453357 -0.031790584, 0.015798271 0.0029653311 -0.031031474, -0.013184935 0.0054523945 -0.030572936, -0.011775956 0.0061406046 -0.030346557, -0.012710199 0.006482631 -0.030572847, -0.0090736896 0.012484387 -0.030861497, -0.0082223713 0.014620394 -0.031223968, -0.008251369 0.012369767 -0.03071855, -0.0063719153 0.012766883 -0.030572474, -0.0098201483 0.012410507 -0.0309643, -0.0086567253 0.014693171 -0.031303704, -0.0055245906 0.015522435 -0.031140521, 0.018613651 0.0013096333 -0.031790733, -0.0053375959 0.013232812 -0.03057234, -0.004269436 0.013615027 -0.030572474, -0.0020592213 0.014119402 -0.030572474, -0.0018896163 0.016367584 -0.031140596, -0.00093108416 0.014238492 -0.030572504, 0.0025475472 0.0094616562 -0.029682666, 0.0026060939 0.011756703 -0.030086309, 0.0036334991 0.0091691315 -0.029693067, 0.0014615208 0.0097541809 -0.029693186, 0.003568843 0.013815433 -0.030572489, 0.0024600029 0.014055118 -0.030572429, 0.00099951029 0.016446039 -0.031140521, 0.0067324936 0.012580678 -0.030572459, 0.006366238 0.010550275 -0.030142829, 0.005711928 0.01307556 -0.030572429, 0.007710591 0.012006074 -0.030572593, 0.0046551228 0.013488233 -0.030572429, 0.0046750605 0.015799075 -0.031140596, 0.0068879873 0.0082927942 -0.029848889, 0.0074020773 0.010109484 -0.030185506, 0.0058039725 0.0085848272 -0.029776379, 0.0086400658 0.011355266 -0.030572712, 0.0073637664 0.014739022 -0.031140566, 0.012244329 0.011024058 -0.03114073, 0.014951795 0.011165351 -0.031790212, 0.01430881 0.0087519884 -0.03122434, 0.013964638 0.0063194484 -0.030834839, 0.016388237 0.0089238584 -0.031790495, 0.015016362 0.005499348 -0.031009227, 0.015789896 0.0071433038 -0.031384602, 0.014527932 0.0059655756 -0.030933052, 0.015347466 0.0016190261 -0.030862287, 0.016772255 -6.4566731e-05 -0.031224683, 0.015656829 0.0023030043 -0.030964896, 0.017050192 0.00027742982 -0.031304672, 0.018610448 -0.0013526678 -0.031791016, 0.01625213 -0.0026967674 -0.031141624, 0.018228173 -0.0039874017 -0.031791136, 0.0111797 -0.0088623911 -0.03057383, 0.0099328458 -0.0070250481 -0.030112624, 0.011848643 -0.0079459548 -0.030573681, 0.0085112303 -0.0053462088 -0.029725179, 0.015661716 -0.0051099211 -0.031141832, 0.017474934 -0.0065409392 -0.031791225, 0.014923722 -0.011199147 -0.031791523, 0.014079943 -0.0085525364 -0.031142071, 0.016365886 -0.0089611858 -0.031791404, 0.0069717616 -0.0099699646 -0.030112952, 0.0078460276 -0.011914358 -0.030573875, 0.0053266883 -0.0085228533 -0.029725313, 0.0087680072 -0.011253476 -0.03057383, 0.012633681 -0.01057221 -0.031142175, 0.010440081 -0.0097225308 -0.0305738, 0.013177782 -0.013208985 -0.031791598, 0.010503829 -0.012690067 -0.03114216, 0.0096345246 -0.010521278 -0.030573845, 0.011163577 -0.014950037 -0.031791821, 0.008476153 -0.014125288 -0.031142294, 0.0089219958 -0.016386628 -0.031791866, 0.0050248653 -0.015687779 -0.031142399, 0.0039436221 -0.018236354 -0.031791836, 0.0064990222 -0.017489403 -0.031791881, 0.0026086867 -0.016265109 -0.031142339, 0.0013078749 -0.018611878 -0.031792, 2.4423003e-05 -0.016770527 -0.031225845, -0.0015122443 -0.01525183 -0.03083621, -0.00024364889 -0.016997233 -0.03129065, -0.0027498603 -0.015752047 -0.031010613, -0.0013543814 -0.018608421 -0.031792045, -0.0021021664 -0.015563026 -0.030934468, -0.0089629889 -0.016364053 -0.031791732, -0.0087859631 -0.014285401 -0.031225502, -0.0058360696 -0.014707297 -0.03096582, -0.0062733144 -0.014097914 -0.030863136, -0.011200815 -0.014921948 -0.031791821, -0.012069717 -0.0076058656 -0.030573681, -0.010583475 -0.0063061714 -0.030143768, -0.0085976124 -0.0057808757 -0.029777154, -0.01263614 -0.0066227764 -0.030573606, -0.011089832 -0.012181371 -0.03114222, -0.013554916 -0.0093619376 -0.031142086, -0.014074057 -0.0023378432 -0.030573264, -0.011842951 -0.0023406148 -0.030093446, -0.0138437 -0.0034487993 -0.030573428, -0.014789537 -0.0072565228 -0.031141892, -0.013122305 -0.0055980086 -0.030573457, -0.01583761 -0.0045348257 -0.031141609, -0.013525769 -0.0045377612 -0.030573457, -0.014266953 -7.8931451e-05 -0.030573219, -0.016453043 -0.0008405298 -0.031141609, -0.014215529 -0.0012123436 -0.030573264, -0.0039891303 -0.018226266 -0.031791896, -0.016343638 0.0020737201 -0.031141371, -0.0041024685 -0.015723899 -0.031080991, -0.0047470629 -0.015505448 -0.031071618, -0.0034280121 -0.015807271 -0.031060442, -0.015858293 0.0044657588 -0.031141162, -0.014537826 0.0083660036 -0.031224325, -0.003174454 0.013911217 -0.03057231, -0.0037310869 0.016048208 -0.031140596, -0.0044027567 0.017011315 -0.031455025, -0.0053337216 -0.015161008 -0.031032503, -0.0065427274 -0.017473057 -0.031791821, 0.0047191978 0.0088769197 -0.029724538, 0.0049265921 0.0099410862 -0.029905573, 0.0040764064 0.012510329 -0.03031908, 0.0028556585 0.016226947 -0.031140611, 0.003446877 0.017230406 -0.031455308, 0.0081264526 0.013052031 -0.030846402, 0.0092893541 0.014915302 -0.031455263, 0.010413751 0.011311114 -0.030846491, 0.011903241 0.012925327 -0.031455442, 0.0077150166 -0.006140247 -0.029694006, 0.0083927661 -0.0070842206 -0.029886603, 0.0069189072 -0.0069345534 -0.02968365, 0.014970079 -0.0068766773 -0.031141788, 0.0070523322 -0.008419469 -0.029886708, 0.0061226785 -0.0077289343 -0.029693991, 0.016126126 -0.0069738775 -0.031456366, 0.0067956597 -0.015006244 -0.031142414, 0.0076120347 -0.015833899 -0.031457007, -0.0088869631 -0.0046951473 -0.029725194, -0.0099590123 -0.0048849881 -0.029906422, -0.0091766268 -0.0036088526 -0.029693723, -0.012402758 -0.010841891 -0.031142205, -0.0097560436 -0.0014353842 -0.029693782, -0.010525957 -0.0030827224 -0.029883534, -0.009466365 -0.0025221407 -0.029683426, -0.013502255 -0.011241004 -0.031456664, -0.013105452 -0.0013193488 -0.030323356, -0.016250685 -0.0027053058 -0.031141505, -0.017261058 -0.0032787621 -0.031456262, -0.015322566 0.0064484179 -0.031182587, -0.016419783 0.0062549114 -0.03145586, 0.0099785775 0.013110578 -0.0311407, 0.0086925626 -0.0091618448 -0.030207917, -0.01188226 -0.0042576641 -0.030206054, -0.011768401 -0.00017188489 -0.030033782, -0.010335103 0.000736624 -0.029776737, -0.010045707 -0.00034889579 -0.029724866, -0.0061093569 0.011792988 -0.030346245, -0.0050337911 0.01150322 -0.030191019, -0.0039553344 0.011212945 -0.030056268, -0.0028750449 0.01092197 -0.0299422, -0.0017926693 0.010630623 -0.029848874, -0.00070893764 0.010338694 -0.029776186, 0.027490303 0.022952825 -0.030310601, 0.029178947 0.023447737 -0.030074567, 0.022943094 0.017774463 -0.031140894, 0.035452455 0.027031347 -0.02885443, 0.035256341 0.02686505 -0.028903335, 0.034436479 0.029944181 -0.028649971, 0.041268483 0.028670534 -0.027678236, 0.042929351 0.030283004 -0.027150825, 0.02306062 0.021053866 -0.03089954, 0.022406414 0.019792199 -0.031048387, 0.026448146 0.024146304 -0.030310541, 0.028587982 0.025667489 -0.02992326, 0.038573146 0.032205597 -0.027677983, 0.040206581 0.033814564 -0.027150661, -0.024493247 -0.025536165 -0.030373231, -0.0211097 -0.023006186 -0.030902013, -0.023922428 -0.026071623 -0.030373231, -0.021783844 -0.0284224 -0.030313596, -0.022154197 -0.029485315 -0.03015916, -0.019482478 -0.022452816 -0.031068549, -0.020071447 -0.023917362 -0.030902103, 0.0061387122 -0.03191784 -0.030750081, 0.0043316782 -0.028865114 -0.031125948, 0.0087688863 -0.030062854 -0.030891687, 0.0082007498 -0.034858093 -0.030313954, 0.0082012862 -0.037661403 -0.029906973, -0.031976044 -0.032947332 -0.02859804, 0.0059704483 -0.037059605 -0.030061871, 0.0044362396 -0.030906394 -0.03090249, 0.0066508949 -0.035186797 -0.030314013, 0.047381207 0.010670528 -0.028047651, 0.051591411 0.0099123865 -0.027152017, 0.043611839 0.0092481375 -0.028855413, 0.0431602 0.011168137 -0.028855368, 0.050564945 0.014252022 -0.027151629, 0.039984331 0.0091191977 -0.029501185, -0.031472385 -0.033550993 -0.028580084, -0.033913597 -0.040120289 -0.027154818, -0.030840531 -0.034022912 -0.028596446, -0.030446574 -0.034217432 -0.028619945, 0.034147084 0.030675113 -0.028597042, 0.033694237 0.031321257 -0.028576657, 0.033104107 0.031844154 -0.028590664, 0.032728314 0.032070979 -0.028612837, -0.01708129 -0.023098096 -0.031173199, -0.018993676 -0.024781883 -0.030902222, -0.017878905 -0.025597632 -0.030902296, -0.014679134 -0.02374357 -0.031253934, -0.01923874 -0.030269146 -0.030305982, -0.032300413 -0.038490847 -0.027682021, -0.030028671 -0.034359708 -0.028653681, -0.027786732 -0.034962595 -0.028842673, -0.016728982 -0.026363552 -0.030902207, -0.030566156 -0.03988196 -0.027682096, -0.030388936 -0.04285194 -0.027154848, -0.025544092 -0.035565808 -0.02900739, -0.015546322 -0.02707769 -0.030902296, -0.012276009 -0.02438961 -0.031312168, -0.016323581 -0.031053513 -0.030415028, -0.028772071 -0.04119496 -0.027681991, -0.02330175 -0.036169007 -0.029148102, -0.023884848 -0.037641346 -0.028858066, -0.021060884 -0.036771804 -0.029265136, -0.014333338 -0.02773881 -0.030902281, -0.026921526 -0.042427346 -0.027682155, -0.026645273 -0.04527466 -0.027154997, -0.022196501 -0.038661078 -0.02885811, -0.013092265 -0.028345764 -0.030902341, -0.0098718703 -0.025036231 -0.03134875, -0.014116243 -0.031647295 -0.030473366, -0.025018543 -0.043576792 -0.02768223, -0.020464525 -0.039605111 -0.028858244, -0.018818736 -0.037375063 -0.029358894, -0.011825591 -0.028897062 -0.030902341, -0.011907607 -0.032241762 -0.03051132, -0.02306655 -0.044640452 -0.027682349, -0.022709683 -0.047371089 -0.027155146, -0.018692598 -0.040471494 -0.028858215, -0.0165793 -0.037977636 -0.029429868, -0.010535762 -0.02939181 -0.030902296, -0.0074655265 -0.025683954 -0.03136386, -0.021069124 -0.045617327 -0.027682438, -0.016883954 -0.041258723 -0.028858319, -0.014336631 -0.038581386 -0.029478118, -0.009225294 -0.029829189 -0.030902475, -0.0097015053 -0.032835618 -0.03052865, -0.019030705 -0.046504572 -0.027682334, -0.018610284 -0.049126476 -0.027155191, -0.015042409 -0.041965142 -0.028858215, -0.012096256 -0.039184496 -0.029503778, -0.0078967065 -0.030207992 -0.030902684, -0.0050594062 -0.026332095 -0.031357765, -0.007494092 -0.033430189 -0.030526087, -0.016954869 -0.04730086 -0.027682498, -0.01317142 -0.042589366 -0.028858274, -0.0065528005 -0.030527741 -0.030902505, -0.014846072 -0.048004478 -0.027682468, -0.014376864 -0.050527781 -0.027155444, -0.011274546 -0.043130398 -0.028858289, -0.0099678338 -0.039757639 -0.029507309, -0.0051957965 -0.030787781 -0.030902356, -0.0052504241 -0.034034654 -0.030502528, -0.0093555748 -0.043586925 -0.028858379, -0.0078395456 -0.040330857 -0.029490665, -0.0038288385 -0.030987307 -0.03090255, -0.0026513636 -0.02698116 -0.031330451, -0.0030059218 -0.034639433 -0.03045778, -0.010545105 -0.049128503 -0.027682573, -0.010039896 -0.051564932 -0.027155444, -0.007418409 -0.043958113 -0.028858483, -0.0057111979 -0.040904447 -0.029453814, -0.002454415 -0.031126484 -0.030902475, -0.0054667443 -0.044243112 -0.028858528, -0.0035824031 -0.041477829 -0.029396489, -0.0010749698 -0.031204462 -0.03090255, -0.00032448769 -0.027608678 -0.031283557, -0.00076173246 -0.035244539 -0.030391708, -0.0061616302 -0.049868435 -0.027682751, -0.0056306422 -0.052230567 -0.027155519, -0.0035042614 -0.0444417 -0.028858304, 0.012091592 -0.051122814 -0.027155384, 0.007712394 -0.051964 -0.027155489, 0.0087129027 -0.044792607 -0.028654233, 0.00030642748 -0.031221598 -0.030902445, 0.0094593763 -0.044906333 -0.028602749, 0.0020046234 -0.028236955 -0.031215549, 0.0014828146 -0.035849422 -0.030304074, -0.0015349686 -0.04455322 -0.028858468, -0.00050990283 -0.042305991 -0.029277295, 0.0016870946 -0.031177342 -0.03090249, 0.012146518 -0.043735653 -0.028701335, 0.011593461 -0.044249177 -0.028632283, -0.0017300844 -0.050217927 -0.027682647, -0.0011807531 -0.052519947 -0.027155399, 0.00043734908 -0.044577584 -0.028858408, 0.0025624335 -0.043134123 -0.029114723, 0.0035149157 -0.035636991 -0.030314013, 0.003727749 -0.036454782 -0.030194134, 0.0024087727 -0.044514492 -0.028858349, 0.0027150065 -0.050174147 -0.027682647, 0.0032775104 -0.052430868 -0.027155519, 0.0049318373 -0.050005063 -0.027682662, 0.005636394 -0.043963134 -0.028907344, 0.007139042 -0.04973796 -0.027682722, 0.016383633 -0.049913064 -0.027155235, 0.010465905 -0.038272381 -0.029725805, 0.0097347349 -0.034461245 -0.030313924, 0.011831388 -0.039010435 -0.029545173, 0.011219233 -0.038576812 -0.029644057, 0.012570977 -0.043114066 -0.028795034, 0.010852695 -0.0384022 -0.029688448, 0.011507109 -0.048912376 -0.027682588, 0.010215342 -0.044850469 -0.028581411, 0.010939181 -0.044627339 -0.028591514, 0.012620926 -0.03814134 -0.029644012, 0.012697041 -0.040219173 -0.029300958, 0.012331858 -0.039567217 -0.029428944, 0.01274249 -0.033466235 -0.03031382, 0.013034046 -0.031214699 -0.030582577, 0.014004543 -0.042322844 -0.028858319, 0.012845367 -0.042418346 -0.028907612, 0.012960106 -0.041678146 -0.029034093, 0.012909338 -0.040933847 -0.029167175, 0.014295772 -0.037545636 -0.029644012, 0.015785038 -0.047703996 -0.027682498, 0.015862986 -0.041661918 -0.028858289, 0.015942618 -0.036876515 -0.029643968, 0.017879799 -0.046959087 -0.027682468, 0.020557716 -0.048343986 -0.027155221, 0.017690361 -0.040919363 -0.028858215, 0.035489216 -0.038733825 -0.027154714, 0.031800523 -0.035746828 -0.028203353, 0.032882944 -0.035397246 -0.028104141, 0.017558277 -0.03613539 -0.029643804, 0.016969517 -0.032277301 -0.030219972, 0.019939497 -0.046122313 -0.027682483, 0.019483164 -0.040097058 -0.028858125, 0.019139677 -0.035323367 -0.029643863, 0.018758804 -0.032760412 -0.030029222, 0.021960318 -0.045195132 -0.027682349, 0.024583533 -0.046426415 -0.027155221, 0.021237776 -0.039195836 -0.028858095, 0.023937806 -0.044179574 -0.02768223, 0.038646355 -0.035584643 -0.027154565, 0.035283282 -0.033040345 -0.028098926, 0.03565295 -0.03196457 -0.028194904, 0.022950798 -0.038218275 -0.02885811, 0.022345617 -0.033728525 -0.029596373, 0.025868803 -0.043077484 -0.027682364, 0.028432384 -0.044174314 -0.027154967, 0.024618939 -0.037165537 -0.02885811, 0.027748927 -0.041891009 -0.027682096, 0.026238725 -0.036040202 -0.028858006, 0.02594246 -0.034699321 -0.029093191, 0.029574946 -0.040622607 -0.027682081, 0.032076374 -0.041603923 -0.027154908, 0.031342685 -0.039274558 -0.027682021, 0.029547706 -0.035672188 -0.028516665, 0.030669197 -0.035839841 -0.028343663, 0.033049479 -0.037849635 -0.027681872, 0.034691483 -0.036350906 -0.027681857, 0.033859134 -0.034806654 -0.028051972, 0.034675732 -0.034004673 -0.028050169, 0.036265463 -0.034780711 -0.027681872, 0.037768498 -0.033142477 -0.027681664, 0.041525021 -0.032179028 -0.027154207, 0.035766333 -0.030834004 -0.028332666, 0.035719946 -0.030230373 -0.028420433, 0.039197534 -0.031439424 -0.027681589, 0.035044178 -0.02755563 -0.028857484, 0.035599574 -0.029635206 -0.028516352, 0.035975993 -0.02632764 -0.028857425, 0.03395398 -0.023475081 -0.029456958, 0.037105396 -0.024710208 -0.028857276, 0.033410639 -0.021442026 -0.029721543, 0.034392029 -0.020767838 -0.029642999, 0.032863423 -0.019394606 -0.029965773, 0.041822895 -0.027852163 -0.027681351, 0.044104502 -0.028541371 -0.027154163, 0.038162231 -0.023044795 -0.028857201, 0.035276935 -0.019226372 -0.029642984, 0.032315627 -0.017345116 -0.030188605, 0.039144248 -0.021334186 -0.028857216, 0.036092862 -0.017646879 -0.029642865, 0.044121087 -0.024046853 -0.027681276, 0.04636623 -0.024698257 -0.027153969, 0.032835871 -0.014290854 -0.030312866, 0.031220973 -0.013249919 -0.030570224, 0.040049687 -0.019581825 -0.028857052, 0.036838323 -0.016033217 -0.029642805, 0.033435881 -0.01282452 -0.030312538, 0.030614182 -0.010980189 -0.030746445, 0.040876791 -0.017791182 -0.028856933, 0.037511528 -0.01438807 -0.02964282, 0.046073839 -0.020053297 -0.027680993, 0.048293918 -0.020677298 -0.027153715, 0.03397058 -0.011333138 -0.030312568, 0.029996455 -0.0086698234 -0.030901283, 0.041623831 -0.015965521 -0.028856903, 0.038111329 -0.012714833 -0.029642671, 0.039053023 -0.012004495 -0.029528305, 0.039693385 -0.012534484 -0.029396206, 0.040438026 -0.012890488 -0.029251948, 0.034438685 -0.0098193586 -0.030312464, 0.038247794 -0.010560066 -0.0297243, 0.038560882 -0.011333033 -0.0296399, 0.042289272 -0.014108703 -0.028856635, 0.041248158 -0.013055056 -0.029103085, 0.042074725 -0.013018146 -0.028958634, 0.030376971 -0.0072247237 -0.030901209, 0.029389352 -0.0063981265 -0.03102991, 0.047665924 -0.015902877 -0.027680725, 0.049873471 -0.01650697 -0.027153492, 0.042869732 -0.012780279 -0.028827071, 0.034839243 -0.0082864612 -0.030312389, 0.043583199 -0.012355417 -0.028717488, 0.037456498 -0.0075975955 -0.029956058, 0.035171837 -0.0067372471 -0.03031233, 0.030896828 -0.0045117736 -0.030901, 0.028775901 -0.0041030943 -0.031137392, 0.048884958 -0.011627883 -0.027680427, 0.051093876 -0.012217924 -0.027153268, 0.044174507 -0.011764839 -0.028636262, 0.044864565 -0.0093111694 -0.028615147, 0.044568777 -0.011121601 -0.028592542, 0.044793114 -0.01048094 -0.028578877, 0.044884369 -0.0098053068 -0.028590873, 0.035435572 -0.0051747561 -0.030312121, 0.036674008 -0.0046675205 -0.030144915, 0.031066298 -0.0031407773 -0.030900925, 0.028123856 -0.0016623884 -0.031227574, 0.035888463 -0.0017246008 -0.030295327, 0.031174988 -0.0017635524 -0.03090094, 0.049721688 -0.0072619617 -0.027680159, 0.051946104 -0.0078409612 -0.027152941, 0.044772223 -0.0088234097 -0.028652236, 0.044173479 -0.0065805167 -0.028840989, 0.04435496 -0.0044850856 -0.028856248, 0.043574452 -0.004336521 -0.029005587, 0.031222403 -0.00038278103 -0.030900687, 0.027471796 0.00077876449 -0.031294137, 0.035103366 0.0012170821 -0.030407548, 0.049994186 -0.005055353 -0.027680114, 0.052424103 -0.0034073144 -0.027152702, 0.044510007 -0.002518639 -0.028856054, 0.042975664 -0.0020932853 -0.02914606, 0.031208843 0.00099870563 -0.030900776, 0.050168842 -0.0028390437 -0.027680084, 0.044577837 -0.00054742396 -0.028855979, 0.042377308 0.0001489222 -0.029263079, 0.031134129 0.0023781657 -0.030900717, 0.026819974 0.003220886 -0.031338051, 0.034513861 0.0034258217 -0.030467644, 0.050245464 -0.0006172806 -0.027679801, 0.052524343 0.0010508597 -0.027152464, 0.044558585 0.0014249086 -0.028855905, 0.041778609 0.0023924708 -0.029356733, 0.030998588 0.0037531555 -0.030900523, 0.033924669 0.005634293 -0.030506939, 0.050223559 0.0016058832 -0.027679697, 0.044451952 0.0033945292 -0.028855786, 0.041180819 0.0046332628 -0.029427454, 0.030802399 0.0051204413 -0.030900449, 0.026168048 0.0056641251 -0.031359717, 0.050103441 0.0038259774 -0.027679652, 0.052246019 0.0055013597 -0.027152181, 0.044258371 0.0053575635 -0.028855607, 0.040582389 0.0068772286 -0.029475585, 0.030545726 0.0064779073 -0.030900478, 0.033335656 0.0078433156 -0.030525833, 0.049885407 0.006038487 -0.027679577, 0.043978065 0.0073099434 -0.028855547, 0.03022936 0.007822752 -0.0309003, 0.025630713 0.0076795667 -0.031361252, 0.032746628 0.010052532 -0.030524507, 0.049569428 0.0082391053 -0.027679339, 0.02985391 0.0091522485 -0.030900359, 0.039416477 0.011248901 -0.029504493, 0.029419944 0.010463685 -0.030900136, 0.025093004 0.0096975863 -0.031347901, 0.032151744 0.012284547 -0.030502558, 0.042623907 0.013066202 -0.028855219, 0.038848832 0.013378784 -0.029487699, 0.028928444 0.01175496 -0.030900031, 0.024555504 0.011715651 -0.031319663, 0.031556979 0.01451692 -0.030459896, 0.042004362 0.01493901 -0.028854996, 0.038281187 0.015508741 -0.029450595, 0.028380156 0.013022989 -0.030900016, 0.047344655 0.016838014 -0.027678877, 0.049174294 0.018488914 -0.027151555, 0.041302517 0.016782299 -0.028855041, 0.02777648 0.014265582 -0.030899912, 0.024017528 0.013736323 -0.031275988, 0.030962199 0.016749784 -0.030396238, 0.040519789 0.018592879 -0.028854817, 0.037713498 0.017638847 -0.029393137, 0.027118176 0.01548025 -0.030899853, 0.030367538 0.018982857 -0.03031078, 0.045671433 0.020956457 -0.027678639, 0.047429457 0.02259253 -0.027151331, 0.026406944 0.016664654 -0.030899882, 0.023480013 0.015756056 -0.031216383, 0.044699788 0.022956267 -0.027678564, 0.045342803 0.026533291 -0.027151048, 0.0368945 0.020713657 -0.029273704, 0.038718164 0.022101134 -0.028854683, 0.025644109 0.017816409 -0.030899614, 0.029772878 0.021216199 -0.030203819, 0.043640733 0.024910957 -0.027678415, 0.03770268 0.023792148 -0.028854653, 0.036075413 0.023788631 -0.029110998, 0.024830893 0.018933341 -0.030899599, -0.011420324 -0.054959729 -0.024360389, -0.017723575 -0.053262174 -0.024360269, -0.014606729 -0.051335365 -0.026727602, -0.008347854 -0.058299437 -0.021993026, -0.013012037 -0.057438821 -0.021993116, -0.017591789 -0.056205377 -0.021993101, -0.0049623698 -0.055913851 -0.024360418, -0.0057206452 -0.053065941 -0.026727781, -0.0011995584 -0.053359777 -0.026727661, -0.003629595 -0.058782056 -0.021993041, 0.0015624613 -0.056111708 -0.024360567, 0.0033300072 -0.053269252 -0.026727721, 0.0058469176 -0.058603138 -0.021993175, 0.0011122972 -0.058883756 -0.02199319, 0.0080663264 -0.055551201 -0.024360344, 0.007835716 -0.052794889 -0.026727647, 0.012284979 -0.051940098 -0.026727647, 0.010543779 -0.057942659 -0.021993205, 0.01446107 -0.054239184 -0.024360284, 0.016645536 -0.050711229 -0.026727602, 0.019701988 -0.05550088 -0.021993011, 0.015172124 -0.056906343 -0.021993071, 0.020660013 -0.052193493 -0.024360225, 0.020886421 -0.049116895 -0.026727468, 0.024104223 -0.053735629 -0.021992818, 0.026579872 -0.049441949 -0.024359956, 0.024976641 -0.047168747 -0.026727498, 0.028886914 -0.044880524 -0.026727244, 0.032412022 -0.049173281 -0.021992594, 0.028350011 -0.051621959 -0.021992639, 0.032140017 -0.046022058 -0.024359837, 0.032589257 -0.042269155 -0.02672711, 0.036263868 -0.046405733 -0.021992266, 0.037265792 -0.041979551 -0.024359658, 0.036056608 -0.039353132 -0.026727036, 0.039264083 -0.036153451 -0.026726827, 0.039880499 -0.043337196 -0.021992281, 0.041887507 -0.0373694 -0.024359465, 0.042188838 -0.032693341 -0.02672644, 0.046316057 -0.036378622 -0.021991819, 0.043238401 -0.039987609 -0.021991923, 0.045942664 -0.032254025 -0.024359182, 0.044809535 -0.028997704 -0.02672635, 0.049093157 -0.032533839 -0.021991715, 0.049376711 -0.026702285 -0.024358809, 0.047107562 -0.025093138 -0.02672632, 0.049065948 -0.021007717 -0.026725829, 0.053676397 -0.024237528 -0.021991149, 0.051551923 -0.028477862 -0.021991402, 0.052143022 -0.02078934 -0.024358436, 0.050670922 -0.016771078 -0.026725769, 0.05545269 -0.019839615 -0.021991, 0.054204032 -0.014595181 -0.024358153, 0.051910773 -0.012413383 -0.026725411, 0.057917342 -0.010687545 -0.021990255, 0.056869492 -0.015313148 -0.021990806, 0.055532068 -0.0082039833 -0.024357602, 0.05277662 -0.0079663396 -0.026725233, 0.053262189 -0.0034618676 -0.026724964, 0.058589652 -0.0059924424 -0.02199018, 0.05610919 -0.0017016381 -0.024357483, 0.053363964 0.0010675043 -0.026724637, 0.058792412 0.0034835339 -0.021989644, 0.058881894 -0.0012585819 -0.021990046, 0.055927515 0.0048238039 -0.024356991, 0.053081408 0.0055892915 -0.026724562, 0.058321461 0.0082030892 -0.021989271, 0.054989427 0.011283845 -0.024356723, 0.052416176 0.010070801 -0.026724249, 0.051373482 0.014479592 -0.026723787, 0.056250572 0.017452195 -0.021988779, 0.057472497 0.012869403 -0.021989241, 0.053307757 0.017591581 -0.024356291, 0.049960554 0.01878424 -0.026723728, 0.054663986 0.021921903 -0.021988571, 0.050905228 0.023661256 -0.024355978, 0.048187658 0.022953555 -0.02672334, 0.04606761 0.026957527 -0.026723251, 0.052722827 0.026249409 -0.021988168, 0.047814339 0.029411107 -0.024355739, 0.043615624 0.030767113 -0.026722968, 0.047829568 0.034366965 -0.021987855, 0.050439596 0.030406862 -0.021988153, 0.044076771 0.034763068 -0.024355337, 0.040849373 0.034355253 -0.026722863, 0.04490909 0.038104162 -0.021987677, -0.036451787 -0.040856302 -0.025543198, -0.034455955 -0.040761665 -0.026727036, -0.034871817 -0.043988138 -0.024359614, -0.038289547 -0.042916059 -0.02317597, -0.038215354 -0.044812247 -0.0219924, 0.040948823 0.036350936 -0.025538951, 0.043013215 0.038183197 -0.023171216, -0.03087464 -0.043536901 -0.026727125, -0.03448537 -0.047742024 -0.021992609, -0.029529452 -0.047739163 -0.024360001, -0.027071193 -0.045998439 -0.026727363, -0.026380211 -0.052655637 -0.021992743, -0.030531809 -0.05036214 -0.021992683, -0.023787379 -0.050844505 -0.024360031, -0.023072705 -0.048128515 -0.026727527, -0.01890789 -0.049911752 -0.026727602, -0.022057623 -0.054607525 -0.021992788, -0.010200515 -0.052389413 -0.026727632, 0.03995128 -0.043414116 -0.021202549, 0.036328241 -0.046488136 -0.021764666, 0.03995131 -0.043414235 -0.021764457, 0.036328256 -0.046488136 -0.021202534, 0.043315336 -0.040058702 -0.021202341, 0.043315277 -0.040058732 -0.021764413, 0.046398431 -0.036443368 -0.021201983, 0.046398357 -0.036443383 -0.021764234, -0.038283169 -0.044892013 -0.021202475, -0.038283229 -0.044891924 -0.021764562, 0.049180388 -0.032591641 -0.021201894, 0.049180493 -0.032591641 -0.021764025, -0.034546718 -0.047826946 -0.021202639, -0.034546643 -0.047826901 -0.021764785, 0.051643685 -0.028528675 -0.02120173, 0.05164358 -0.028528631 -0.021763667, -0.030586168 -0.050451621 -0.021202832, -0.030586198 -0.050451547 -0.021764904, 0.053771809 -0.024280444 -0.021201313, 0.053771824 -0.024280667 -0.021763474, -0.026427105 -0.052749202 -0.021202937, -0.026427045 -0.052749157 -0.021765023, 0.05555132 -0.019874975 -0.021201193, 0.055551291 -0.019874975 -0.02176325, -0.022096798 -0.05470477 -0.021202937, -0.022096843 -0.054704651 -0.021765068, 0.056970432 -0.015340447 -0.021200895, 0.056970596 -0.015340298 -0.021763027, -0.017623097 -0.056305319 -0.021203175, -0.017623171 -0.05630523 -0.021765336, 0.058020324 -0.010706514 -0.021200746, 0.058020294 -0.010706425 -0.021762654, -0.013035268 -0.057540789 -0.021203145, -0.013035193 -0.057540685 -0.021765262, 0.058693796 -0.0060031116 -0.021200329, 0.058693811 -0.0060030669 -0.021762371, -0.0083627105 -0.058403015 -0.021203309, -0.0083627254 -0.058402985 -0.021765456, 0.058986604 -0.0012607872 -0.021200076, 0.058986545 -0.0012607723 -0.021762162, -0.0036359429 -0.058886722 -0.021203369, -0.0036360621 -0.058886692 -0.021765366, 0.058896825 0.0034899563 -0.021199852, 0.05889684 0.0034898371 -0.021761924, 0.0011143237 -0.058988303 -0.021203354, 0.0011143237 -0.058988348 -0.021765411, 0.058425277 0.0082176924 -0.02119951, 0.0058573782 -0.058707431 -0.021203384, 0.0058573633 -0.058707401 -0.021765456, 0.058425233 0.0082176626 -0.021761775, 0.057574645 0.012892276 -0.021199256, 0.010562509 -0.058045715 -0.021203354, 0.010562465 -0.058045685 -0.021765336, 0.057574451 0.01289244 -0.021761328, 0.056350619 0.017483383 -0.021199003, 0.01519911 -0.057007566 -0.02120313, 0.015199065 -0.057007566 -0.021765381, 0.056350619 0.017483398 -0.021761149, 0.054761156 0.021960974 -0.021198705, 0.01973708 -0.055599689 -0.021203175, 0.019737005 -0.055599615 -0.021765172, 0.054761067 0.021961108 -0.021760687, 0.052816495 0.026296154 -0.021198496, 0.024146959 -0.05383113 -0.021203101, 0.024147004 -0.05383113 -0.021765053, 0.052816525 0.026296154 -0.021760494, 0.050529301 0.030461013 -0.021198347, 0.050529316 0.03046082 -0.0217603, 0.028400481 -0.05171375 -0.021202996, 0.028400451 -0.051713705 -0.021764964, 0.04791452 0.034428149 -0.021198109, 0.04791449 0.034428075 -0.021760151, 0.03246972 -0.049260765 -0.021202654, 0.032469705 -0.049260661 -0.02176474, 0.044988841 0.038172022 -0.0211979, 0.044988945 0.038171843 -0.021760002, 0.040254667 -0.040354803 -0.012902409, 0.036784664 -0.043541342 -0.012902558, 0.036784634 -0.043540895 -0.018922195, 0.043449685 -0.036892712 -0.01290217, 0.040254667 -0.040354386 -0.018922031, 0.04344964 -0.036892325 -0.018921897, 0.04634805 -0.033178732 -0.012902081, 0.046347946 -0.033178419 -0.018921673, -0.036893547 -0.043449029 -0.012902439, -0.036893427 -0.043448523 -0.018922254, 0.048929542 -0.02923803 -0.012901708, 0.048929542 -0.029237658 -0.018921345, -0.033179328 -0.046347246 -0.012902677, -0.033179417 -0.046346828 -0.018922448, 0.05117707 -0.025097758 -0.012901425, 0.051176995 -0.025097281 -0.018921196, -0.029238686 -0.048928693 -0.012902975, -0.029238656 -0.04892841 -0.018922478, 0.053074852 -0.020785779 -0.012901276, 0.053074867 -0.020785257 -0.018920898, -0.025098279 -0.051176131 -0.01290293, -0.025098324 -0.051175788 -0.018922657, 0.054610074 -0.016331851 -0.012901053, 0.054610163 -0.016331494 -0.01892066, -0.02078627 -0.053074092 -0.012903005, -0.0207863 -0.053073645 -0.018922612, 0.055772334 -0.011766389 -0.01290074, 0.055772275 -0.011766106 -0.018920451, -0.016332597 -0.054609254 -0.012903258, -0.016332522 -0.054609001 -0.018922716, 0.056553379 -0.0071205944 -0.012900457, 0.056553498 -0.007120207 -0.018920094, -0.01176694 -0.055771545 -0.012903184, -0.011767015 -0.055771112 -0.01892294, 0.056948394 -0.0024262071 -0.012900308, 0.056948394 -0.0024257451 -0.018919811, -0.0071211308 -0.056552768 -0.012903288, -0.00712125 -0.05655238 -0.018922865, 0.056954369 0.0022850931 -0.01290001, 0.056954265 0.0022853464 -0.018919617, -0.0024266988 -0.056947812 -0.012903377, -0.0024267137 -0.056947336 -0.01892297, 0.056571171 0.0069803298 -0.012899697, 0.056571111 0.0069806129 -0.018919513, 0.0022843033 -0.056953534 -0.012903348, 0.0022842586 -0.056953162 -0.01892294, 0.0558016 0.011628136 -0.012899473, 0.0069797486 -0.056570336 -0.012903184, 0.0069797188 -0.056569993 -0.01892291, 0.055801645 0.011628389 -0.01891908, 0.054650813 0.01619634 -0.01289925, 0.054650888 0.016196683 -0.018918842, 0.011627585 -0.055800706 -0.012903154, 0.011627421 -0.055800483 -0.018922895, 0.053126827 0.020654231 -0.012898803, 0.016195834 -0.054649889 -0.012903214, 0.016195834 -0.054649517 -0.018922955, 0.053126842 0.020654514 -0.018918633, 0.051239729 0.02497074 -0.012898639, 0.020653471 -0.053125829 -0.01290299, 0.020653561 -0.053125471 -0.018922761, 0.051239774 0.024970993 -0.018918395, 0.049002543 0.029116869 -0.012898386, 0.049002588 0.029117256 -0.018918097, 0.024970219 -0.051238954 -0.012903035, 0.024970144 -0.051238656 -0.018922701, 0.046430811 0.033064082 -0.012898222, 0.046430916 0.03306441 -0.018917784, 0.029116198 -0.049001813 -0.012902737, 0.029116362 -0.049001634 -0.018922284, 0.043541998 0.036785305 -0.012898088, 0.043541893 0.036785722 -0.018917575, 0.033063322 -0.046430051 -0.012902752, 0.033063337 -0.046429694 -0.018922418, -0.042777956 -0.036138564 -0.012902066, -0.04561612 -0.03248249 -0.012901872, -0.048142821 -0.028604478 -0.012901649, -0.050340727 -0.024531424 -0.012901425, -0.052194551 -0.020290479 -0.012901157, -0.053691909 -0.01591076 -0.012900859, -0.054822475 -0.011422768 -0.0129008, -0.0555785 -0.0068566948 -0.012900397, -0.055955052 -0.0022434443 -0.012900144, -0.055949315 0.0023848116 -0.012899771, -0.055561274 0.0069970936 -0.012899637, -0.054793745 0.011561379 -0.012899444, -0.053651735 0.016046762 -0.012899205, -0.052143708 0.020422384 -0.012898862, -0.050279096 0.024658665 -0.012898654, -0.048070908 0.028726354 -0.012898445, -0.0455347 0.032598063 -0.012898177, -0.042687401 0.036246985 -0.012898222, -0.039548442 0.03964828 -0.0128977, -0.03613919 0.042778566 -0.012897611, 0.036246374 0.042687953 -0.012897789, -0.032483175 0.045616984 -0.012897432, 0.032597348 0.045535445 -0.012897611, -0.028605118 0.048143581 -0.012897328, 0.028725937 0.048071846 -0.012897417, -0.02453196 0.050341278 -0.012897149, 0.024658099 0.050279722 -0.012897223, -0.02029112 0.052195281 -0.012897149, 0.020421892 0.052144274 -0.012897208, -0.015911639 0.053692698 -0.012897, 0.016046077 0.053652555 -0.01289703, -0.011423349 0.054823324 -0.012897015, 0.011560723 0.05479452 -0.012896895, -0.0068571866 0.05557932 -0.012897059, 0.0069963932 0.055562004 -0.01289697, -0.0022441149 0.055955872 -0.012896761, 0.0023843646 0.055949971 -0.01289697, -0.0036343336 -0.058859318 -0.021890804, 0.0011137724 -0.058960944 -0.021890834, 0.0011143088 -0.058981374 -0.02182965, -0.0036356747 -0.058879778 -0.021829531, -0.0036323071 -0.058826134 -0.021946147, 0.001113221 -0.058927864 -0.021946222, -0.0083616972 -0.058396414 -0.02182956, -0.0083588809 -0.058376014 -0.021890864, -0.0083540678 -0.058343396 -0.021946058, -0.013033733 -0.057534039 -0.021829575, -0.013029158 -0.057514027 -0.021890759, -0.013021842 -0.057481706 -0.021946102, -0.01762104 -0.056298718 -0.021829352, -0.017614901 -0.056279182 -0.021890625, -0.017605111 -0.056247547 -0.021946028, -0.02209419 -0.054698154 -0.021829277, -0.02208662 -0.054679111 -0.021890551, -0.022074088 -0.054648519 -0.021945909, -0.026423946 -0.052743018 -0.021829247, -0.026414841 -0.052724734 -0.021890402, -0.02639994 -0.052695259 -0.021945894, -0.030582473 -0.050445691 -0.021829203, -0.030571818 -0.050428197 -0.021890342, -0.030554742 -0.050399974 -0.02194567, -0.034542635 -0.047821164 -0.02182889, -0.034530595 -0.047804728 -0.021890193, -0.034511209 -0.047777921 -0.021945491, -0.038278669 -0.044886559 -0.021828726, -0.038265526 -0.044871137 -0.02188997, -0.038244024 -0.044845775 -0.021945447, 0.0449837 0.038167536 -0.021824136, 0.044967979 0.038154259 -0.02188538, 0.044942841 0.038132817 -0.021940723, 0.047908768 0.034424037 -0.021824256, 0.047892183 0.034411997 -0.021885529, 0.04786548 0.034392655 -0.021941006, 0.050523356 0.030457377 -0.021824479, 0.050505847 0.030446887 -0.021885753, 0.050477311 0.030429706 -0.02194126, 0.052810207 0.026293218 -0.021824881, 0.052792013 0.026283845 -0.021886051, 0.05276233 0.026269183 -0.021941379, 0.054754749 0.021958455 -0.021825075, 0.054735601 0.021950826 -0.021886304, 0.054704949 0.021938443 -0.021941572, 0.056343988 0.017481163 -0.021825284, 0.056324244 0.017475277 -0.021886542, 0.056292742 0.017465487 -0.0219419, 0.057567731 0.01289086 -0.021825641, 0.057547748 0.012886137 -0.021886796, 0.057515517 0.012879252 -0.021942258, 0.058418259 0.0082167834 -0.021825925, 0.058398023 0.0082139224 -0.02188696, 0.058365151 0.0082093626 -0.021942422, 0.05889 0.00348939 -0.021826118, 0.058869556 0.0034880489 -0.021887392, 0.05883643 0.0034863651 -0.021942735, 0.05897969 -0.0012604445 -0.021826237, 0.058959067 -0.0012601316 -0.021887466, 0.058926076 -0.001259461 -0.021943137, 0.058686793 -0.0060023516 -0.02182667, 0.058666363 -0.0060001761 -0.021887809, 0.058633536 -0.0059970021 -0.021943197, 0.058013529 -0.010705113 -0.021826863, 0.057993352 -0.010701597 -0.021888137, 0.057960793 -0.010695636 -0.021943495, 0.056963786 -0.015338659 -0.021827221, 0.056944117 -0.01533325 -0.021888256, 0.056912065 -0.015324712 -0.021943688, 0.055544838 -0.019872636 -0.021827281, 0.055525392 -0.019865721 -0.021888509, 0.055494368 -0.019854531 -0.021943972, 0.05376552 -0.024277762 -0.021827742, 0.053746864 -0.024269208 -0.021888793, 0.053716674 -0.024255469 -0.021944195, 0.051637456 -0.028525189 -0.021828055, 0.051619574 -0.02851522 -0.02188918, 0.051590577 -0.02849932 -0.021944419, 0.049174622 -0.032587752 -0.02182813, 0.04915753 -0.032576472 -0.021889403, 0.049130008 -0.032558292 -0.021944717, 0.046392798 -0.036439121 -0.021828294, 0.046376824 -0.036426425 -0.021889493, 0.046350718 -0.036405846 -0.02194491, 0.043310195 -0.040053993 -0.021828532, 0.04329522 -0.040039971 -0.021889865, 0.043270841 -0.040017635 -0.021945164, 0.039946675 -0.04340902 -0.021828681, 0.039932832 -0.043394119 -0.021890014, 0.039910406 -0.043369696 -0.021945328, 0.036324039 -0.046482712 -0.021828935, 0.036311373 -0.046466634 -0.021890074, 0.036291078 -0.046440542 -0.021945551, 0.032465845 -0.04925482 -0.021829024, 0.03245458 -0.049237788 -0.021890432, 0.032436326 -0.049210191 -0.02194564, 0.028397053 -0.051707491 -0.021829158, 0.028387129 -0.051689371 -0.021890432, 0.028371453 -0.051660657 -0.021945819, 0.024144292 -0.053824961 -0.021829292, 0.024135813 -0.053806052 -0.021890566, 0.024122223 -0.053775921 -0.021945938, 0.019734725 -0.055593193 -0.021829486, 0.019727886 -0.055573717 -0.02189067, 0.019716889 -0.055542618 -0.021945983, 0.015197322 -0.057000875 -0.021829531, 0.015192047 -0.056981131 -0.021890759, 0.015183464 -0.056949154 -0.021946102, 0.010561317 -0.058038786 -0.02182956, 0.010557503 -0.058018625 -0.0218907, 0.010551602 -0.057986096 -0.021946058, 0.005856663 -0.058700502 -0.02182956, 0.0058545619 -0.058680013 -0.021890849, 0.0058512986 -0.058647066 -0.021946117, 0.058351442 0.0082073212 -0.021001816, 0.058822572 0.0034854561 -0.021002144, 0.058863163 0.0034876764 -0.021061301, 0.058235779 0.0081910491 -0.020919994, 0.058705941 0.0034783632 -0.020920336, 0.058636561 0.0034742355 -0.020902574, 0.058166832 0.0081814378 -0.020902231, 0.05754149 0.012884781 -0.021060869, 0.058391586 0.0082131028 -0.021061122, 0.057501972 0.012876123 -0.021001413, 0.057387948 0.012850493 -0.020919651, 0.057319924 0.012835234 -0.020902038, 0.056318104 0.017473206 -0.021060735, 0.056279451 0.017461315 -0.021001294, 0.056167766 0.017426774 -0.020919636, -0.038113967 -0.044693381 -0.020905152, 0.056101382 0.017406151 -0.020901784, 0.054729581 0.021948367 -0.021060273, 0.05469197 0.021933332 -0.021001056, 0.054583549 0.021889776 -0.020919278, 0.054519057 0.021863759 -0.020901486, 0.052786186 0.026281074 -0.021060079, 0.052749887 0.026262954 -0.021000803, 0.052645206 0.026211068 -0.02091898, 0.052583024 0.02617994 -0.020901173, 0.050500348 0.03044346 -0.021059886, 0.050465614 0.03042236 -0.021000564, 0.050365612 0.03036207 -0.020918906, 0.050305888 0.030326128 -0.02090098, 0.047886834 0.034408391 -0.021059647, 0.047853962 0.034384668 -0.021000251, 0.047759116 0.03431648 -0.020918548, 0.047702581 0.034275889 -0.020900786, 0.044963092 0.038149983 -0.021059319, 0.044932142 0.038123891 -0.021000177, 0.044843063 0.038048223 -0.020918369, 0.044790015 0.038003162 -0.020900518, -0.038261205 -0.044866085 -0.021063998, -0.038235039 -0.044835255 -0.021004707, -0.038159132 -0.044746369 -0.020923033, -0.034526721 -0.047799453 -0.021064296, -0.034503058 -0.047766462 -0.021004915, -0.034434706 -0.047671765 -0.020923197, -0.034393951 -0.047615528 -0.020905301, -0.030568555 -0.050422743 -0.021064505, -0.030547485 -0.050388083 -0.021005243, -0.030486822 -0.050288185 -0.020923361, -0.030450836 -0.050228432 -0.020905674, -0.026411936 -0.052719042 -0.021064386, -0.026393786 -0.052682757 -0.021005228, -0.026341483 -0.052578315 -0.020923316, -0.02631034 -0.052516103 -0.020905703, -0.022084042 -0.054673299 -0.021064788, -0.022068843 -0.054635793 -0.021005288, -0.022025228 -0.054527491 -0.020923525, -0.021999091 -0.054462865 -0.020905659, -0.017613113 -0.056272939 -0.021064833, -0.017600924 -0.05623436 -0.021005407, -0.017565951 -0.056122825 -0.020923585, -0.017545208 -0.056056336 -0.020905674, -0.013027713 -0.057507858 -0.021064743, -0.013018847 -0.05746834 -0.021005392, -0.012992799 -0.057354227 -0.020923674, -0.01297754 -0.057286397 -0.020905852, -0.0083578676 -0.058369637 -0.021064773, -0.0083521605 -0.058329463 -0.021005481, -0.0083356351 -0.05821383 -0.020923734, -0.008325696 -0.058145091 -0.020905986, -0.0036338866 -0.058852896 -0.021064967, -0.0036314875 -0.05881232 -0.02100566, -0.0036242306 -0.058695748 -0.020923778, -0.0036199093 -0.058626354 -0.020905897, 0.0011136383 -0.058954418 -0.021064878, 0.0011128634 -0.058913842 -0.02100575, 0.0011106879 -0.058796972 -0.020923778, 0.0011093915 -0.058727548 -0.020905957, 0.0058539361 -0.058673561 -0.021064848, 0.0058499277 -0.058633476 -0.021005541, 0.005838275 -0.058517024 -0.020923749, 0.0058313906 -0.058447734 -0.020906046, 0.010556474 -0.058012351 -0.021064743, 0.010549158 -0.057972342 -0.021005511, 0.010528162 -0.057857513 -0.02092351, 0.010515824 -0.057789057 -0.020906106, 0.015190378 -0.056974843 -0.021064773, 0.015179873 -0.056935504 -0.021005511, 0.015149802 -0.056822777 -0.020923749, 0.015131891 -0.056755573 -0.020905837, 0.019725755 -0.055567771 -0.021064848, 0.01971221 -0.055529565 -0.021005318, 0.019673079 -0.05541949 -0.020923674, 0.019649819 -0.055353984 -0.020905748, 0.02413322 -0.05380027 -0.021064639, 0.024116606 -0.053763315 -0.021005377, 0.024068773 -0.053656727 -0.020923525, 0.024040237 -0.053593025 -0.020905569, 0.028384238 -0.051683918 -0.021064386, 0.028364614 -0.051648393 -0.021005139, 0.028308362 -0.051546022 -0.020923376, 0.028274834 -0.051485017 -0.020905554, 0.032450929 -0.049232334 -0.021064371, 0.032428697 -0.049198404 -0.021005005, 0.032364488 -0.04910098 -0.020923316, 0.032326117 -0.049042895 -0.020905465, 0.036307424 -0.046461642 -0.021064177, 0.036282524 -0.046429619 -0.021004826, 0.036210477 -0.0463375 -0.020923167, 0.036167726 -0.046282604 -0.020905346, 0.039928421 -0.043389246 -0.021063983, 0.039900973 -0.043359414 -0.021004692, 0.039821833 -0.043273538 -0.020922884, 0.039774671 -0.0432221 -0.020905077, 0.043290436 -0.04003565 -0.02106373, 0.0432605 -0.040008083 -0.021004394, 0.043174833 -0.039928749 -0.020922601, 0.043123797 -0.039881527 -0.020904943, 0.046371683 -0.036422551 -0.021063775, 0.046339706 -0.036397263 -0.021004245, 0.0462479 -0.036325082 -0.020922601, 0.046193272 -0.036282316 -0.02090463, 0.049152195 -0.03257294 -0.021063402, 0.049118266 -0.032550484 -0.021004006, 0.04902105 -0.032486156 -0.020922303, 0.048962966 -0.032447651 -0.020904571, 0.051613912 -0.028512254 -0.021063179, 0.051578432 -0.02849257 -0.021003976, 0.05147624 -0.028436095 -0.020922139, 0.051415235 -0.028402597 -0.020904213, 0.053740904 -0.024266645 -0.021062896, 0.053703964 -0.024249867 -0.021003664, 0.053597495 -0.024201736 -0.020921946, 0.053534105 -0.02417317 -0.020904019, 0.055519447 -0.019863486 -0.021062747, 0.055481255 -0.019849911 -0.021003336, 0.05537124 -0.019810647 -0.020921454, 0.055305734 -0.019787028 -0.020903811, 0.056937799 -0.015331745 -0.021062404, 0.056898668 -0.015321091 -0.021003097, 0.056785837 -0.015290722 -0.020921305, 0.056718752 -0.015272677 -0.020903498, 0.057987019 -0.010700345 -0.021062225, 0.057947263 -0.010692909 -0.021002874, 0.057832167 -0.010671854 -0.020921066, 0.057763726 -0.010659039 -0.020903125, 0.05866003 -0.0059996694 -0.021061793, 0.058619663 -0.0059956163 -0.021002531, 0.058503479 -0.0059836656 -0.020920873, 0.058434308 -0.0059764981 -0.020902976, 0.058952704 -0.0012600124 -0.021061644, 0.058912233 -0.0012592375 -0.021002233, 0.058795244 -0.0012566149 -0.02092059, 0.0587257 -0.0012550801 -0.020902812, 0.029680505 -0.034658596 -0.027692303, 0.021171153 -0.032366961 -0.028936133, 0.029680565 -0.034658626 -0.026402026, 0.012632355 -0.030067474 -0.029797226, 0.0035984367 -0.027634621 -0.030329034, -0.0062149763 -0.024991959 -0.03052628, -0.015606582 -0.022462934 -0.030379042, -0.043071926 -0.015066907 -0.026400864, -0.033182025 -0.017730117 -0.029099897, -0.038149416 -0.016392469 -0.028459623, -0.043071821 -0.015066966 -0.02769129, 0.015176356 0.043035671 -0.027688012, 0.017446548 0.034520581 -0.028932393, 0.015176132 0.043035552 -0.026397571, 0.019724458 0.025976285 -0.029794082, 0.022134617 0.016936138 -0.030326545, 0.024752691 0.0071162283 -0.030524418, 0.027258456 -0.0022819489 -0.030378103, 0.034585685 -0.029765755 -0.026401788, 0.031947121 -0.01986897 -0.029100105, 0.033272356 -0.024839789 -0.0284601, 0.034585685 -0.029765576 -0.027692035, -0.044856831 -0.0083725601 -0.027690753, -0.038617536 -0.0021490008 -0.028934404, -0.044856742 -0.008372575 -0.026400596, -0.032356873 0.0040962845 -0.029795289, -0.025732949 0.010703608 -0.030326918, -0.018537581 0.017880842 -0.030523956, -0.011651471 0.024749815 -0.030376509, 0.0012349784 0.0376039 -0.029096812, 0.0048771352 0.041237071 -0.028456435, 0.010556877 0.038310662 -0.026398018, 0.010965303 0.038089782 -0.026398048, 0.01459077 0.044295385 -0.026397586, 0.014938697 0.04369092 -0.026397541, 0.010108486 0.038431451 -0.026397794, 0.0096444339 0.038445532 -0.026397958, 0.009189412 0.038352221 -0.026397884, 0.008768335 0.03815642 -0.026397839, 0.0084037185 0.037868708 -0.026398048, 0.028618053 -0.027132183 -0.026401535, 0.02865921 -0.026669562 -0.02640149, 0.028592467 -0.026210055 -0.026401624, 0.028471619 -0.027572721 -0.026401564, 0.028227225 -0.027967677 -0.026401654, 0.034719095 -0.030684888 -0.026401788, 0.034637019 -0.031609967 -0.026401758, 0.034343779 -0.032491103 -0.026401937, 0.033855185 -0.033281118 -0.026401907, 0.033197612 -0.033937007 -0.026402041, 0.027898461 -0.028295606 -0.02640152, 0.032406613 -0.03442359 -0.026402056, 0.031524718 -0.034714609 -0.026402026, 0.030599341 -0.034794271 -0.026402012, 0.027502865 -0.028538808 -0.026401684, 0.027061924 -0.028684348 -0.026401743, 0.026139796 -0.028656229 -0.026401699, -0.038364515 -0.010381579 -0.026400685, -0.03817071 -0.010785222 -0.02640073, 0.026599184 -0.028724372 -0.026401758, -0.043934658 -0.014722958 -0.026400819, -0.044694796 -0.014189288 -0.026400745, -0.037888333 -0.0083073676 -0.026400477, -0.038167864 -0.0086572617 -0.026400506, -0.038362727 -0.0090604126 -0.026400581, -0.038462952 -0.0094970614 -0.026400492, -0.038463503 -0.0099448264 -0.026400551, -0.045311376 -0.013494715 -0.026400819, -0.04543364 -0.0091004223 -0.026400596, -0.045751065 -0.012676731 -0.026400894, -0.04582727 -0.0099415481 -0.026400685, -0.045990288 -0.011779219 -0.0264007, 0.011748552 0.036968127 -0.026397958, -0.046016172 -0.010850877 -0.02640076, 0.011577696 0.037399799 -0.026397988, 0.011311755 0.037780568 -0.026398063, 0.018517375 -0.026603431 -0.029777899, 0.026139826 -0.028656214 -0.028887317, 0.010885149 -0.024548188 -0.030366048, 0.00094138086 -0.021870345 -0.03074187, -0.010244876 -0.01885809 -0.03076759, -0.028448775 -0.013955802 -0.029864132, -0.019882232 -0.016262934 -0.030466601, 0.013782218 0.029340595 -0.029774696, 0.011748657 0.036968186 -0.028883561, 0.015818268 0.021703616 -0.030363366, 0.018471181 0.011752963 -0.030739889, 0.021455571 0.00055940449 -0.030766368, 0.026312128 -0.017656952 -0.029864371, 0.024026707 -0.0090844482 -0.030466244, 0.028592378 -0.02621001 -0.028887227, -0.032299429 -0.0027322322 -0.029776663, -0.037888363 -0.0083071142 -0.028886288, -0.026703432 0.0028499365 -0.030364528, -0.019412383 0.010122672 -0.030740038, -0.011210442 0.01830402 -0.030765504, 0.0021368861 0.031617805 -0.029861599, -0.0041443706 0.025352523 -0.030464381, 0.0084035695 0.037869081 -0.028883487, 0.043802232 -0.0090191066 -0.027950495, 0.043881565 -0.0095028877 -0.027903855, 0.043802157 -0.0090192109 -0.025607631, 0.043885991 -0.0096069872 -0.025607646, 0.043865308 -0.0099879652 -0.027880386, 0.043828696 -0.010197729 -0.025607795, 0.043755367 -0.010462239 -0.027880177, 0.043633893 -0.010758311 -0.02560775, 0.043555096 -0.01090683 -0.027903765, 0.04331243 -0.011257291 -0.025607839, 0.043273866 -0.01130259 -0.027949318, 0.042882353 -0.011666477 -0.025607824, 0.04292202 -0.011636004 -0.028015316, 0.042514905 -0.011893854 -0.028098732, 0.042367935 -0.011962608 -0.025607854, 0.042066321 -0.012069017 -0.028196275, 0.04179807 -0.012129173 -0.025607735, 0.041595846 -0.012154222 -0.028303683, 0.041205123 -0.012156501 -0.025607854, 0.041122556 -0.012148947 -0.02841641, 0.040622443 -0.01204358 -0.025607735, 0.04063195 -0.012046456 -0.02853775, 0.040191814 -0.011858985 -0.028651267, 0.040082723 -0.011796251 -0.025607869, 0.039881319 -0.011659026 -0.028734729, 0.033497855 0.029630914 -0.027948245, 0.038363606 0.0113803 -0.028797656, 0.033497825 0.029630721 -0.025605559, 0.040633366 0.0028665066 -0.028676763, 0.042224348 -0.0031006336 -0.028395697, 0.028666526 0.028342858 -0.029016048, 0.028586596 0.028839901 -0.028949857, 0.028606817 0.029336438 -0.028866082, 0.028724968 0.029819563 -0.028766945, 0.028933972 0.030265525 -0.028657436, 0.029226467 0.030662045 -0.02854073, 0.029606894 0.031005234 -0.028416499, 0.030028731 0.031254292 -0.028299809, 0.030496836 0.031417295 -0.028188884, 0.03098768 0.031485125 -0.028089195, 0.03148596 0.031454071 -0.028004497, 0.031968907 0.031324357 -0.027938947, 0.032417297 0.031100601 -0.027895555, 0.032813609 0.030790463 -0.027876079, 0.033131853 0.030418128 -0.025605351, 0.03313832 0.030408978 -0.027881697, 0.03334929 0.030040413 -0.025605381, 0.033351824 0.030035108 -0.027906239, 0.034032658 0.0082157254 -0.029817119, 0.031678721 0.017044604 -0.02968353, 0.030162886 0.022730663 -0.029420316, 0.042152688 -0.0094590783 -0.023900673, 0.042179257 -0.0096454918 -0.023900509, 0.042161256 -0.0098328441 -0.023900554, 0.041860968 -0.01029864 -0.023900583, 0.042099491 -0.010010689 -0.023900628, 0.041997388 -0.010168895 -0.023900673, 0.041697845 -0.010392547 -0.023900509, 0.041517168 -0.010445371 -0.023900643, 0.041144386 -0.010418266 -0.023900703, 0.041329011 -0.010454103 -0.023900583, 0.040973112 -0.010339916 -0.023900613, 0.031665698 0.029523566 -0.023898363, 0.031777233 0.029368192 -0.023898318, 0.031848416 0.029190898 -0.023898408, 0.031520247 0.029647455 -0.023898348, 0.030478939 0.02950114 -0.023898348, 0.030619487 0.029630706 -0.023898423, 0.030786976 0.029722586 -0.023898438, 0.030316129 0.028782234 -0.023898467, 0.030373394 0.029341832 -0.023898438, 0.030971736 0.02977176 -0.023898557, 0.031162918 0.029775485 -0.023898318, 0.031349406 0.029733121 -0.023898423, 0.030309007 0.029161781 -0.023898438, 0.030289412 0.028971732 -0.023898512, -0.029713064 -0.033421993 -0.027951688, -0.030124173 -0.033271685 -0.02790913, -0.029713079 -0.033422127 -0.025608957, -0.030122519 -0.0332724 -0.025608882, -0.030499578 -0.033054143 -0.027884811, -0.030499503 -0.033054054 -0.025608867, 0.0089108944 -0.043823019 -0.027952299, -0.0093274713 -0.038911521 -0.028800681, 0.0089109391 -0.043823123 -0.025609523, -0.017835572 -0.036620378 -0.028679028, -0.0237986 -0.035014659 -0.028397441, 0.010211095 -0.038995057 -0.029019833, 0.010681525 -0.039174214 -0.028953716, 0.01110138 -0.039439902 -0.028869882, 0.011460871 -0.039783806 -0.028770819, 0.011697352 -0.040110558 -0.025609329, 0.011742488 -0.040188029 -0.028661281, 0.011939615 -0.040639445 -0.028544724, 0.011943206 -0.040650994 -0.025609434, 0.012046516 -0.041140601 -0.028420582, 0.012054786 -0.041233867 -0.025609419, 0.012051195 -0.041630492 -0.02830407, 0.012025833 -0.041826859 -0.025609404, 0.011958644 -0.042117327 -0.028193101, 0.011857897 -0.042396218 -0.025609523, 0.011771813 -0.042576477 -0.028093353, 0.011560544 -0.042909831 -0.025609478, 0.011495784 -0.042992458 -0.02800864, 0.01115036 -0.04333885 -0.025609598, 0.011142105 -0.043345705 -0.027943134, 0.010724127 -0.043622106 -0.027899757, 0.010650635 -0.043659285 -0.025609627, 0.010257199 -0.043810233 -0.027880311, 0.010089293 -0.043852568 -0.025609583, 0.0097645968 -0.043900698 -0.027885824, 0.0094982833 -0.043908402 -0.025609583, 0.0093340874 -0.043898687 -0.027910426, -0.0099027157 -0.033578351 -0.029819697, -0.0010798723 -0.035954461 -0.029686451, 0.0046024024 -0.037484646 -0.029423714, 0.010296151 -0.041706175 -0.023902372, 0.010349959 -0.041330531 -0.023902357, 0.010345936 -0.041521519 -0.023902446, 0.010223106 -0.040972963 -0.023902342, 0.010308161 -0.041144058 -0.023902342, 0.010099441 -0.04082714 -0.023902461, 0.01007399 -0.042013809 -0.023902401, 0.010203734 -0.04187353 -0.023902386, 0.0099144429 -0.042118996 -0.023902372, 0.0097342879 -0.042183131 -0.023902401, 0.0093549043 -0.042174891 -0.02390255, 0.0097672343 -0.040643647 -0.023902327, 0.009944424 -0.040715232 -0.023902506, 0.0095440894 -0.042202055 -0.023902491, -0.029269233 -0.03177391 -0.02390188, -0.029399008 -0.031726331 -0.02390185, -0.029518694 -0.031656966 -0.023901761, -0.014088914 0.042445719 -0.02794756, -0.013707697 0.04275769 -0.027900726, -0.013276473 0.042986885 -0.027877137, -0.012806237 0.043128446 -0.027877346, -0.012317821 0.043175578 -0.027901471, -0.011832237 0.043126896 -0.027948201, -0.01136446 0.042984486 -0.028015375, -0.010937065 0.042756081 -0.028099731, -0.01056172 0.042449504 -0.028198779, -0.010254264 0.042078763 -0.028307378, -0.01020503 0.042003006 -0.025604725, -0.010024577 0.041658208 -0.02842167, -0.0099627227 0.041498333 -0.025604859, -0.0098758936 0.041185036 -0.028541818, -0.009838745 0.040952399 -0.025604919, -0.0098235458 0.040706813 -0.028655693, -0.0098394006 0.040392578 -0.025604874, -0.0098641962 0.040226012 -0.028763369, -0.0099648386 0.039846972 -0.025604993, -0.009996444 0.039761543 -0.028860033, -0.010208264 0.039342776 -0.025604889, -0.010217413 0.03932865 -0.028943226, -0.010377407 0.039106354 -0.028982565, -0.010557815 0.038905576 -0.025604859, -0.01055789 0.038905695 -0.029015422, -0.029036 0.027535886 -0.028796822, -0.022797778 0.03375864 -0.028674975, -0.018425599 0.038119957 -0.028393358, -0.038877606 0.010656789 -0.029016972, -0.039268017 0.010339156 -0.028950855, -0.038877577 0.0106567 -0.025606483, -0.039315626 0.010308191 -0.025606528, -0.039707974 0.010108411 -0.028867096, -0.039820358 0.010066047 -0.025606513, -0.040185586 0.00996916 -0.028768033, -0.040366247 0.00994201 -0.025606588, -0.04067634 0.0099271536 -0.028658569, -0.040926084 0.0099428892 -0.025606558, -0.041165873 0.0099820197 -0.028541788, -0.041471705 0.01006791 -0.025606766, -0.041653261 0.010139972 -0.028417766, -0.041975752 0.010311499 -0.025606677, -0.042054683 0.010363549 -0.028308362, -0.024129838 0.025367841 -0.02981627, -0.030598953 0.018914878 -0.02968353, -0.034765124 0.014759064 -0.029420748, -0.012179419 0.04145515 -0.023897812, -0.011997044 0.041397959 -0.023897737, -0.011833519 0.041298956 -0.023897737, -0.012558371 0.041432723 -0.023897529, -0.012370184 0.041466877 -0.023897707, -0.011698589 0.041163653 -0.023897693, -0.011599883 0.040999725 -0.023897722, -0.011543319 0.040817529 -0.023897678, -0.011531934 0.040626496 -0.023897722, -0.012732789 0.041354463 -0.023897707, -0.011566669 0.040438682 -0.023897797, -0.011645302 0.040264398 -0.023897722, -0.012883425 0.041236922 -0.023897722, -0.011763424 0.040113986 -0.023897737, -0.040083036 0.011865243 -0.023899317, -0.040382132 0.011677667 -0.023899272, -0.040222123 0.011754677 -0.023899436, -0.040555179 0.011638507 -0.023899376, -0.040732801 0.011638924 -0.023899376, -0.040905908 0.011678562 -0.023899436, -0.041065812 0.011755735 -0.023899391, 0.022391185 -0.019647852 -0.031061709, 0.01901266 -0.018233553 -0.031399682, 0.019800752 -0.017374635 -0.031399503, 0.02150014 -0.020619139 -0.031061754, 0.026369274 -0.025288969 -0.030209407, 0.022828951 -0.023920149 -0.030679867, 0.023864746 -0.022887021 -0.030679852, 0.012544423 -0.018936366 -0.031684607, 0.011694521 -0.019472793 -0.031684548, 0.0092594028 -0.017005965 -0.031883255, 0.026633754 -0.022873253 -0.03041102, 0.027632967 -0.026609957 -0.029934883, 0.014547765 -0.021960944 -0.031399757, 0.013562098 -0.022583067 -0.031399876, 0.027663186 -0.026824117 -0.02990821, 0.016303718 -0.024931401 -0.03106229, 0.027640626 -0.027039394 -0.029887319, 0.027592435 -0.02718766 -0.029876411, 0.027515128 -0.027331308 -0.029869035, 0.027412817 -0.027458608 -0.029866219, 0.02522473 -0.026430711 -0.030209571, 0.013369769 -0.018363044 -0.031684443, 0.011585608 -0.015515119 -0.03188318, 0.015505105 -0.021296099 -0.03139995, 0.020549953 -0.016481772 -0.031399697, 0.017073944 -0.014981508 -0.031684279, 0.017719924 -0.01421161 -0.03168419, 0.024853826 -0.021809012 -0.030679747, -0.014070839 -0.016736895 -0.031740591, 0.014169127 -0.017753661 -0.031684414, 0.01753363 -0.024082452 -0.031062037, 0.020384595 -0.026034534 -0.030679896, 0.018375382 -0.025491297 -0.030878931, -0.011624292 -0.015486106 -0.031883016, 0.018331364 -0.013414115 -0.03168419, 0.015487865 -0.011622578 -0.031882733, 0.02323848 -0.018638268 -0.031061724, -0.011943772 -0.01730758 -0.03179203, 0.016432062 -0.020589381 -0.031399667, -0.0093017668 -0.016982734 -0.031883255, 0.021259025 -0.015556648 -0.031399533, 0.014940634 -0.017109588 -0.031684399, 0.013675898 -0.013708383 -0.031883121, -0.0098010749 -0.017882794 -0.031828627, -0.0076587051 -0.018458396 -0.031850949, 0.025794342 -0.020688161 -0.030679777, 0.025633097 -0.019132704 -0.0308121, 0.02612634 -0.020975694 -0.030623794, 0.018581793 -0.023283571 -0.031062111, 0.018906847 -0.012590051 -0.031684071, 0.016984552 -0.0092999786 -0.031882823, 0.022460341 -0.026595339 -0.030451879, -0.0067899376 -0.01813367 -0.03188315, 0.017326578 -0.019842342 -0.031399623, -0.0055175871 -0.01903455 -0.031859905, 0.024040416 -0.017592013 -0.031061843, 0.025127694 -0.017243683 -0.030986637, -0.0041399151 -0.018915355 -0.031883106, 0.021926358 -0.014600992 -0.031399503, 0.024631441 -0.015389875 -0.031140357, -0.0033770502 -0.019611254 -0.031855509, -0.0014056414 -0.019311875 -0.03188327, 0.01944527 -0.011741355 -0.031684026, 0.015682802 -0.016431883 -0.031684339, 0.019593626 -0.022438556 -0.031062037, -0.0012372732 -0.020188287 -0.031838, 0.022550896 -0.01361689 -0.031399414, 0.024128407 -0.01351063 -0.031278744, 0.00090362132 -0.020766526 -0.031806439, 0.019945607 -0.010869697 -0.031683952, 0.02362901 -0.011646211 -0.031399265, 0.018187508 -0.019056514 -0.031399667, 0.0013573468 -0.019315571 -0.031883284, 0.020407006 -0.0099766701 -0.031683937, 0.0032292902 -0.021395117 -0.031754956, 0.0208285 -0.0090643764 -0.031683832, 0.018135458 -0.0067881942 -0.031882569, 0.02297467 -0.0092024803 -0.031533167, 0.0040926784 -0.018925771 -0.03188324, 0.021209121 -0.0081341714 -0.031683862, 0.0055558532 -0.022024214 -0.031684726, 0.021748438 -0.024906576 -0.030679807, 0.021548077 -0.0071879774 -0.031683818, 0.022321388 -0.0067639798 -0.031641081, 0.024463847 -0.0271364 -0.030209646, 0.016394392 -0.015722156 -0.031684279, 0.0067446679 -0.018150628 -0.031883195, 0.021845162 -0.0062279403 -0.031683803, 0.018917099 -0.0041381419 -0.031882435, 0.021662787 -0.004304409 -0.031725585, 0.0078806579 -0.022653267 -0.031593189, 0.021013632 -0.0018791556 -0.031787127, 0.020566911 -0.021549895 -0.031061947, 0.019313768 -0.0014037341 -0.031882152, 0.020410031 0.00037744641 -0.031826511, 0.019317195 0.0013591647 -0.031882107, 0.019807279 0.0026337355 -0.031850114, 0.0189275 0.0040944219 -0.031881914, 0.019205466 0.004889071 -0.031858698, 0.018152386 0.0067465305 -0.03188172, 0.018604383 0.0071449727 -0.031852573, 0.017007828 0.0092609525 -0.031881571, 0.018005162 0.0093965679 -0.031831726, 0.017406181 0.011649922 -0.031795412, 0.015516922 0.011587262 -0.031881541, 0.016807064 0.013906166 -0.031742215, 0.027295142 -0.027560264 -0.029867887, 0.027168795 -0.027636096 -0.029873386, 0.027031526 -0.027690664 -0.029882431, 0.026886865 -0.02772148 -0.029894903, 0.026739925 -0.027728006 -0.029910311, 0.026640445 -0.02771844 -0.029921889, 0.02654247 -0.027697876 -0.029934898, 0.0090140253 -0.020849109 -0.031684533, 0.010204464 -0.023281842 -0.031479046, 0.009927392 -0.020429984 -0.031684563, 0.012222663 -0.023827896 -0.031360731, 0.010821462 -0.019970968 -0.031684458, 0.01428847 -0.0243866 -0.031219751, -0.038090333 -0.010903761 -0.028827399, -0.03824921 -0.010647893 -0.028821439, -0.038402766 -0.010259092 -0.028817967, -0.038472041 -0.0098484755 -0.028820828, -0.03845343 -0.009424448 -0.028829381, -0.03834644 -0.0090153366 -0.028843522, -0.038156405 -0.0086388737 -0.02886273, 0.0086195469 0.038055584 -0.028867468, 0.008847028 0.038202688 -0.028853714, 0.0091389865 0.0383351 -0.028839856, 0.0094445348 0.038418189 -0.028828934, 0.0097637177 0.038452372 -0.028820902, 0.010079816 0.038435489 -0.028816447, 0.010384798 0.038370669 -0.028815284, 0.010705471 0.038244039 -0.028817937, 0.01106368 0.03801614 -0.028826818, 0.011364311 0.037719294 -0.028841034, 0.011595413 0.03736636 -0.028860182, 0.028646067 -0.026490122 -0.028871164, 0.028659493 -0.026760802 -0.028857335, 0.02862829 -0.027079672 -0.028843433, 0.028547525 -0.027385697 -0.02883251, 0.028417528 -0.027679503 -0.028824732, 0.028244898 -0.027944624 -0.028820246, 0.028036118 -0.028176323 -0.028819129, 0.027766362 -0.028390884 -0.028821692, 0.027389899 -0.028586999 -0.028830498, 0.026982412 -0.028698966 -0.028844625, 0.026561096 -0.028722793 -0.028863758, 0.030476719 -0.034788549 -0.027539313, 0.031270564 -0.034758136 -0.027412876, 0.032201231 -0.034511983 -0.027298942, 0.033048004 -0.0340496 -0.027235031, 0.033760145 -0.033396497 -0.027225286, 0.034295663 -0.032590151 -0.027270854, 0.034621835 -0.031679526 -0.027368695, 0.034719944 -0.030719697 -0.027511939, -0.045367464 -0.0089968443 -0.027537942, -0.045737892 -0.0096996427 -0.027411476, -0.045990065 -0.010628745 -0.027297631, -0.046012819 -0.011593416 -0.027233794, -0.045803457 -0.01253657 -0.027224094, -0.045373246 -0.013403535 -0.027269736, -0.044747517 -0.014141411 -0.027367577, -0.043965265 -0.014706135 -0.02751112, 0.014932886 0.043703541 -0.027552053, 0.014586508 0.044301495 -0.027437598, 0.0039923787 -0.018462062 -0.031850472, 0.0066617131 -0.017927274 -0.031880841, 0.0040422976 -0.018692821 -0.031880885, 0.0065794736 -0.017705843 -0.031850189, 0.0013406128 -0.019077897 -0.031880841, 0.0013240129 -0.018842235 -0.031850442, -0.0013882518 -0.019074276 -0.03188093, 0.015326023 0.011444837 -0.031879216, -0.0013712496 -0.018838674 -0.031850398, -0.0040890425 -0.018682688 -0.031880915, 0.015136749 0.011303529 -0.031848818, -0.004038468 -0.018451884 -0.031850547, 0.01679866 0.0091471076 -0.03187938, 0.016591176 0.009034276 -0.031848833, -0.0067063868 -0.017910555 -0.031880841, -0.0066236854 -0.017689273 -0.031850442, 0.017929032 0.006663546 -0.03187947, 0.01770775 0.0065813214 -0.031848982, -0.0091874003 -0.01677379 -0.031880781, -0.009073928 -0.016566619 -0.031850189, 0.018694729 0.0040439069 -0.031879738, 0.01846391 0.0039941669 -0.031849235, -0.01148127 -0.015295506 -0.031880751, 0.019079641 0.0013425201 -0.031879723, -0.011339575 -0.015106469 -0.031850025, 0.018844023 0.0013258904 -0.03184928, 0.019076303 -0.0013864636 -0.031879902, 0.018840596 -0.0013693422 -0.03184934, 0.018684521 -0.0040872395 -0.031880066, 0.018453896 -0.0040367693 -0.031849533, 0.017912328 -0.0067047179 -0.031880274, 0.017691135 -0.0066218972 -0.031849653, 0.016775593 -0.0091855526 -0.031880453, 0.016568378 -0.0090721697 -0.031849861, 0.015297487 -0.011479542 -0.031880572, 0.015108407 -0.011337832 -0.031850085, 0.013507679 -0.013539732 -0.031880662, 0.01334098 -0.013372377 -0.031850114, 0.011443019 -0.015324175 -0.031880841, 0.011301845 -0.015134946 -0.031850308, 0.0091454685 -0.016796708 -0.031880945, 0.0090325475 -0.016589239 -0.031850427, -0.0064795464 -0.012571827 -0.028700158, -0.0062790066 -0.013324022 -0.030320123, -0.0066332519 -0.011995748 -0.028900757, -0.0063806474 -0.012942925 -0.028626755, -0.0062790513 -0.013324037 -0.028600886, -0.007432729 -0.0089966208 -0.029653162, -0.0085961372 -0.0046331435 -0.02931866, -0.010925755 0.0041051507 -0.029652476, -0.0097625703 -0.00025804341 -0.029318288, -0.012079462 0.0084327161 -0.030318812, 0.014128715 0.00067672133 -0.028699577, 0.013706565 0.00025568902 -0.028900042, 0.014400735 0.00094804168 -0.028625995, 0.011509016 -0.0019363314 -0.02965261, 0.0083120465 -0.0051254034 -0.02931866, 0.0019091964 -0.011512086 -0.029653326, -0.00028835237 -0.013704285 -0.028900877, 0.0051062256 -0.0083232671 -0.029318854, -0.0009290427 -0.014343157 -0.028637484, -0.00060430169 -0.014019534 -0.0287413, -0.0076491237 0.011899844 -0.028698683, -0.0084007382 0.012102351 -0.030318603, -0.0070733279 0.011744738 -0.028899536, -0.008019954 0.011999771 -0.02862528, -0.0084006786 0.012102246 -0.028599411, -0.0040760487 0.010937721 -0.02965194, 0.00028428435 0.0097635835 -0.029317796, 0.0090167373 0.0074119419 -0.029652178, 0.0046564937 0.0085861832 -0.029317945, 0.013341337 0.0062474757 -0.030318946, -0.0025223047 -0.0093647987 -0.028900623, -0.0069184899 0.011607945 -0.028899297, -0.0069948137 0.011677504 -0.028899416, -0.00010377169 -0.012943313 -0.028900757, 0.0122253 6.7546964e-05 -0.028900057, 0.012976721 7.6666474e-05 -0.028900042, -0.00010353327 -0.01216045 -0.028900877, 0.011491477 0.00022874773 -0.028900012, -0.003297016 -0.0092522353 -0.028900713, -0.0040764958 -0.0093253702 -0.028900564, -0.00028756261 -0.011399567 -0.028900698, 0.01081273 0.0005518347 -0.028900057, -0.0048169047 -0.0095803291 -0.028900683, -0.00064609945 -0.0107034 -0.028900608, -0.0054764599 -0.01000233 -0.028900653, -0.0011583716 -0.010111347 -0.028900474, -0.0060177743 -0.010567844 -0.028900638, -0.0017957091 -0.0096565336 -0.028900579, -0.0064109266 -0.011244893 -0.028900757, -0.0018156767 -0.0099916011 -0.028600603, -0.0018250495 -0.0099859536 -0.02690053, -0.0024632812 -0.0096947998 -0.028600618, -0.0024842918 -0.0096881986 -0.026900738, -0.0031624734 -0.0095591843 -0.028600648, -0.0031954348 -0.009556964 -0.026900664, -0.0038741529 -0.0095921308 -0.028600618, -0.0039174259 -0.0095998347 -0.026900589, -0.0045577586 -0.0097920448 -0.028600633, -0.0046081096 -0.009814024 -0.026900694, -0.0051751435 -0.010147303 -0.028600663, -0.005227387 -0.010187447 -0.026900619, -0.0056913793 -0.010638267 -0.028600663, -0.0057394803 -0.010698259 -0.026900545, -0.0060771704 -0.011237055 -0.028600797, -0.006114468 -0.011316732 -0.026900753, -0.0063109696 -0.011909842 -0.028600693, -0.0063305646 -0.012006953 -0.026900843, -0.0063795298 -0.012618944 -0.028600886, -0.0060999244 -0.013817444 -0.030424222, -0.006375134 -0.012728691 -0.026900843, -0.0062456578 -0.013440162 -0.026900783, -0.0059495568 -0.014100179 -0.026900828, -0.0058369637 -0.014272943 -0.030514419, 0.014288574 0.0058034062 -0.030513063, 0.014116511 0.0059158802 -0.02689977, 0.013833076 0.0060676038 -0.030422881, 0.013457343 0.0062133968 -0.02689971, 0.01274614 0.0063446611 -0.026899815, 0.012024209 0.0063019991 -0.02689968, 0.011333406 0.0060876906 -0.0268998, 0.010714114 0.0057142973 -0.02689977, 0.010202095 0.0052033812 -0.026899815, 0.0098270923 0.0045850575 -0.026899874, 0.0096110404 0.0038949102 -0.026899949, 0.0095664561 0.0031730831 -0.026899904, 0.0096960962 0.0024614483 -0.026899979, 0.009991914 0.0018015951 -0.026899993, -0.0074569434 0.011660635 -0.028599396, -0.0076255798 0.011770755 -0.026899487, -0.0079096109 0.011922985 -0.028599307, -0.0090871006 0.012204275 -0.030453399, -0.0082846284 0.012068391 -0.026899323, -0.0089959651 0.012199655 -0.026899353, -0.0097178519 0.012156829 -0.026899293, -0.0097813457 0.012144849 -0.030562267, -0.010408685 0.01194261 -0.026899338, -0.010443449 0.011926919 -0.030638427, -0.011028051 0.011569351 -0.026899353, -0.011037692 0.011562079 -0.030677661, -0.011540055 0.011058435 -0.026899412, -0.011899039 0.010474995 -0.030638501, -0.011914954 0.010440096 -0.026899502, -0.012118742 0.0098131299 -0.030562446, -0.012130916 0.0097498298 -0.026899531, -0.01217559 0.0090278536 -0.02689968, -0.012046024 0.008316353 -0.026899636, -0.011750132 0.0076566488 -0.026899651, -0.009467259 0.010779589 -0.026899546, -0.0098357201 0.010665134 -0.026899397, -0.010165945 0.010465994 -0.026899576, -0.01055114 0.0083793402 -0.026899651, -0.010439083 0.010193676 -0.026899561, -0.010638997 0.0098637491 -0.026899517, -0.0083513856 0.010573581 -0.026899561, -0.010754243 0.0094956458 -0.02689968, -0.010708958 0.0087313205 -0.026899576, -0.010778069 0.0091107339 -0.02689974, -0.0087029189 0.010732278 -0.026899531, -0.0090822875 0.010802224 -0.026899442, -0.0040351748 -0.011091515 -0.026900634, -0.0043655634 -0.011290729 -0.026900768, -0.0046385676 -0.011562899 -0.026900753, -0.004838571 -0.01189287 -0.026900813, -0.004750669 -0.013377473 -0.026900768, -0.0049537569 -0.012260944 -0.026900798, -0.0049084574 -0.013025329 -0.026900783, -0.0049775094 -0.0126459 -0.026900768, -0.0025508106 -0.011183053 -0.026900753, -0.0029024482 -0.011024326 -0.026900619, -0.0032817721 -0.010954395 -0.026900664, -0.0036668479 -0.010977164 -0.026900813, 0.012274846 0.0049246997 -0.02689983, 0.011906505 0.0048103184 -0.02689983, 0.011576205 0.00461106 -0.026899815, 0.011302978 0.0043387413 -0.026899725, 0.011103153 0.0040090233 -0.026899844, 0.01339069 0.0047186762 -0.026899695, 0.011190966 0.0025244355 -0.026900008, 0.010987923 0.0036407113 -0.026899889, 0.011033118 0.0028763264 -0.026899964, 0.013039216 0.0048773885 -0.02689983, 0.010964006 0.0032558292 -0.026899874, 0.012659878 0.0049473494 -0.026899815, -0.01151374 0.039863721 -0.024044156, -0.038981095 0.010760441 -0.025253087, -0.039833575 0.011614949 -0.024045914, -0.010661229 0.039009273 -0.025251314, -0.040034398 0.01145491 -0.02404578, -0.03939344 0.010432273 -0.025253057, -0.039868444 0.010204241 -0.025252983, -0.040265828 0.011343941 -0.024045825, -0.040382445 0.010087669 -0.025253117, -0.040516093 0.011287168 -0.0240459, -0.040909529 0.01008822 -0.025252968, -0.040772855 0.011287466 -0.0240459, -0.041423231 0.010206088 -0.025253162, -0.041023076 0.011344999 -0.024045989, -0.041897818 0.010435551 -0.025252998, -0.041254267 0.011456609 -0.02404581, -0.013132989 0.041487172 -0.024044186, -0.012915298 0.041657329 -0.02404429, -0.012663081 0.041770354 -0.024044231, -0.01239118 0.041819826 -0.024044186, -0.012115404 0.041802928 -0.024044082, -0.011851579 0.041720197 -0.024044201, -0.011615247 0.041577056 -0.024044156, -0.011419967 0.041381285 -0.024044186, -0.010329127 0.041925177 -0.02525124, -0.011277318 0.041144609 -0.024044231, -0.010100946 0.041450083 -0.025251403, -0.011195466 0.040880665 -0.024044186, -0.009984374 0.040936068 -0.025251508, -0.011179149 0.040604785 -0.024044171, -0.0099850148 0.040409207 -0.025251389, -0.011229247 0.040332913 -0.024044201, -0.010102838 0.039895564 -0.025251254, -0.011342928 0.040080965 -0.024044335, -0.010332048 0.039420798 -0.025251523, 0.033356383 0.02959305 -0.02525197, 0.042494401 -0.0093679726 -0.024047092, 0.032190055 0.029282019 -0.024045005, 0.043660745 -0.0090570599 -0.025254115, 0.042532712 -0.0096375942 -0.024047151, 0.043739498 -0.0096099079 -0.025254115, 0.042506635 -0.0099084079 -0.024047062, 0.043685794 -0.010166481 -0.02525419, 0.043502301 -0.010694206 -0.025254115, 0.042417184 -0.010165676 -0.024047107, 0.043199584 -0.01116398 -0.025254339, 0.042269766 -0.010394379 -0.024047092, 0.04279466 -0.011549085 -0.025254354, 0.04207252 -0.010582015 -0.0240473, 0.042310402 -0.011827826 -0.025254369, 0.04183656 -0.01071763 -0.024047196, 0.041773945 -0.011984706 -0.025254413, 0.041575328 -0.010794073 -0.024047196, 0.041215822 -0.012010559 -0.025254264, 0.041303411 -0.010806724 -0.024047151, 0.040667191 -0.01190415 -0.025254294, 0.041036144 -0.010754943 -0.024047226, 0.040159017 -0.011671245 -0.02525422, 0.04078871 -0.010641575 -0.024047032, 0.029974505 0.028691307 -0.024044961, 0.029935956 0.028964981 -0.024045005, 0.029964179 0.029240012 -0.024044871, 0.030057281 0.029500246 -0.024045005, 0.030209973 0.029730484 -0.024044991, 0.03041324 0.029917806 -0.024044901, 0.030655488 0.030050635 -0.024044856, 0.030922621 0.030121908 -0.024044931, 0.031198919 0.030127212 -0.024044797, 0.031468421 0.030066207 -0.024044916, 0.031715512 0.029942214 -0.024044856, 0.031925797 0.029763058 -0.024044901, 0.033011764 0.030334339 -0.025252014, 0.032087013 0.029538512 -0.024044901, 0.033216536 0.029978827 -0.02525191, 0.0098592192 -0.040302277 -0.024048805, 0.010115489 -0.040405899 -0.024048775, 0.010339484 -0.040567532 -0.024048895, 0.010518253 -0.040778309 -0.02404888, 0.011572227 -0.040186703 -0.025255799, 0.010641456 -0.041025847 -0.024048865, 0.011803776 -0.04069531 -0.025255784, 0.01070188 -0.041295499 -0.024049044, 0.011908755 -0.041244268 -0.025255889, 0.01069589 -0.041571856 -0.024048924, 0.01188153 -0.041802526 -0.025255889, 0.010623977 -0.041838735 -0.024048954, 0.011723414 -0.042338446 -0.025256008, 0.010490343 -0.042080641 -0.024048969, 0.011443406 -0.042822018 -0.025256038, 0.010302663 -0.042283475 -0.024048969, 0.011057198 -0.043225929 -0.025256038, 0.010071933 -0.042435676 -0.024048939, 0.010586709 -0.043527707 -0.025256053, 0.0098115057 -0.042528167 -0.024048954, 0.010058463 -0.043709621 -0.025256097, 0.0095364749 -0.042555571 -0.02404888, 0.0095021427 -0.043761984 -0.025256142, 0.0092629492 -0.042516351 -0.024048954, 0.0089489818 -0.04368189 -0.025256082, -0.029674977 -0.03328079 -0.025255516, -0.030060306 -0.033139974 -0.025255382, -0.029361114 -0.032115161 -0.024048358, -0.029548839 -0.032046437 -0.024048403, -0.029721811 -0.031946406 -0.024048418, -0.030415505 -0.032934248 -0.025255427, -0.040956348 0.039644197 -0.020434007, -0.040912747 0.041016519 -0.021496505, -0.03954035 0.041056618 -0.020433977, -0.044159859 0.037497893 -0.021496579, -0.044253647 -0.037384823 -0.021500781, -0.042836338 -0.03606908 -0.019298196, -0.037385985 0.044255093 -0.021496251, -0.038833976 0.040348589 -0.019293919, -0.035299286 0.043474808 -0.019293666, -0.047189862 -0.03360264 -0.021500692, -0.045720994 -0.032334507 -0.019297883, -0.033603773 0.047191232 -0.021496087, -0.031513929 0.046292335 -0.019293562, -0.029592037 0.049805015 -0.021495998, -0.027504832 0.048780978 -0.019293323, -0.049803644 -0.029590845 -0.021500364, -0.048281059 -0.02837047 -0.019297764, -0.025378242 0.0520785 -0.021495774, -0.02330026 0.050923496 -0.019293204, -0.052077278 -0.025377035 -0.021500126, -0.050498292 -0.024204925 -0.019297361, -0.020991057 0.053996384 -0.02149573, -0.018930495 0.052704379 -0.019293174, -0.053995073 -0.020989954 -0.021499872, -0.05235666 -0.019867659 -0.019297153, -0.016460493 0.055545479 -0.02149567, -0.014426008 0.054110989 -0.01929301, -0.054343581 -0.015522376 -0.019886807, -0.053843617 -0.01538913 -0.019296795, -0.011817485 0.056714803 -0.021495491, -0.0098193288 0.055133522 -0.019293025, -0.055544138 -0.016459242 -0.021499723, -0.0070938021 0.05749701 -0.021495521, -0.054858923 -0.01358968 -0.019886807, -0.0051428676 0.055764526 -0.019292995, -0.055299073 -0.0088322759 -0.019296616, -0.054358989 -0.013456434 -0.01929687, -0.0023214966 0.057886496 -0.021495551, -0.05671376 -0.011816382 -0.021499395, -0.00042979419 0.055999413 -0.01929301, 0.0024664849 0.057880566 -0.021495521, 0.00428617 0.05583702 -0.019293085, -0.057495818 -0.0070925355 -0.021499231, -0.055846184 -0.0041453689 -0.019296288, 0.0072378218 0.057479188 -0.021495521, 0.0089718252 0.05527766 -0.019293025, -0.057885304 -0.0023204833 -0.021498874, -0.055997089 0.00057129562 -0.01929605, -0.057879299 0.0024677068 -0.021498427, -0.055750147 0.0052837282 -0.019295901, 0.013728276 0.054825783 -0.019882798, 0.013593748 0.054326102 -0.019293115, -0.057478115 0.0072389394 -0.021498322, 0.011959553 0.056685179 -0.02149561, -0.055107564 0.0099584758 -0.019295424, -0.056683883 0.011960536 -0.021498054, -0.054073781 0.014562815 -0.01929535, 0.016599536 0.05550392 -0.02149561, 0.015659466 0.054305717 -0.019882992, -0.055502668 0.016600624 -0.021497786, 0.019999772 0.052307993 -0.0192931, -0.052655697 0.019063383 -0.019295052, 0.015524954 0.053806126 -0.019293189, -0.053942472 0.021127403 -0.021497652, 0.02112633 0.053943545 -0.021495655, 0.024332404 0.050438628 -0.019293278, -0.050863877 0.023428887 -0.019294813, 0.025508612 0.052014679 -0.021495804, -0.052013621 0.025509626 -0.021497205, 0.028492302 0.048211023 -0.019293576, -0.048710972 0.027627975 -0.019294575, 0.029716924 0.049730688 -0.021495998, -0.049729273 0.029718041 -0.02149713, 0.032450065 0.045641094 -0.019293532, -0.046212256 0.031630933 -0.019294351, 0.033722013 0.047106832 -0.021496117, -0.047105521 0.033723041 -0.021496773, 0.036177322 0.042747036 -0.019293666, 0.037496671 0.044161111 -0.021496266, -0.043385118 0.035409167 -0.019294173, -0.040250018 0.038936049 -0.019293845, -0.00043340027 0.014762089 -0.029663771, -0.0015901476 0.014682546 -0.029663935, -0.0016386062 0.01131694 -0.028951317, 0.00072598457 0.014750615 -0.029663801, -0.00054773688 0.011023119 -0.028878659, 0.00054442883 0.01072906 -0.028826937, 0.0018809587 0.014648199 -0.029663831, 0.001637131 0.010434821 -0.028795794, -0.016068786 0.010069191 -0.030837119, 0.0030243248 0.014455467 -0.029663935, 0.0027302802 0.010140449 -0.028785393, 0.0041490644 0.014173582 -0.029663965, 0.003823638 0.0098459721 -0.028795838, -0.014527604 0.012188211 -0.030837089, 0.0052481294 0.013804317 -0.02966395, 0.0063149035 0.013349861 -0.02966401, 0.0049163401 0.0095517039 -0.028827026, 0.0073427558 0.012813568 -0.02966401, 0.0060083866 0.0092577487 -0.028878763, 0.0083253086 0.012197912 -0.029664144, 0.0070993155 0.0089637935 -0.028951421, 0.0092565119 0.011507139 -0.029664025, 0.0081887096 0.0086706132 -0.029044792, 0.010130823 0.010745376 -0.029664218, 0.0092765391 0.0083775818 -0.029158488, 0.010942429 0.0099174678 -0.029663995, 0.010361865 0.0080852807 -0.029293254, 0.011686698 0.0090283751 -0.029664278, 0.011444688 0.0077939183 -0.029448137, -0.012708962 0.014074445 -0.030836999, 0.012358889 0.0080835819 -0.029664204, 0.014646515 -0.0018792152 -0.029664755, 0.013804868 -0.0010586977 -0.029448748, 0.013010934 -0.0018508136 -0.029293731, 0.015386105 0.00051863492 -0.029820368, 0.014453813 -0.0030226707 -0.029664949, 0.012215033 -0.0026444197 -0.029159352, 0.014171958 -0.0041472912 -0.029665068, 0.011417598 -0.0034400821 -0.029045403, -0.010647893 0.015691906 -0.030836895, 0.013802752 -0.0052464306 -0.029664934, 0.010618716 -0.0042368323 -0.028952241, 0.013348475 -0.0063131899 -0.029665053, 0.009818837 -0.0050347745 -0.028879628, 0.01281181 -0.0073409826 -0.029665098, 0.0099157542 -0.010940701 -0.029665351, 0.0074154139 -0.0074323714 -0.028786466, 0.0066137761 -0.0082318485 -0.028796613, 0.010743737 -0.010128975 -0.029665366, 0.0090266168 -0.011684954 -0.029665411, 0.0049735308 -0.013902396 -0.029665396, 0.0042121112 -0.010627583 -0.028952509, 0.0034131706 -0.011424616 -0.029045701, 0.0060490668 -0.013469324 -0.029665545, 0.0038673431 -0.014249772 -0.029665411, 0.0026156455 -0.012219876 -0.029159799, 0.0027374029 -0.01450932 -0.029665634, 0.001819849 -0.013013989 -0.029294416, 0.0015903264 -0.014679238 -0.029665649, 0.0010258406 -0.013805822 -0.029449478, -0.00055548549 -0.01538308 -0.029821366, -0.0083251894 -0.012194559 -0.029665411, -0.0078206658 -0.011423379 -0.029449403, -0.0092564374 -0.011503845 -0.029665396, -0.008109659 -0.01033999 -0.029294088, -0.01013054 -0.010741964 -0.029665262, -0.0083991289 -0.0092537105 -0.02915962, -0.010942265 -0.0099140555 -0.029665291, -0.0086894035 -0.0081653893 -0.029045507, -0.011686504 -0.0090248883 -0.029665172, -0.0089798719 -0.0070750713 -0.028952196, -0.01235874 -0.0080802292 -0.029665232, -0.0092710704 -0.0059834272 -0.028879672, -0.012954772 -0.0070855319 -0.029664963, -0.0095623434 -0.0048906505 -0.028827757, -0.013470888 -0.006047383 -0.029665098, -0.0098538548 -0.0037971586 -0.028796464, -0.013903841 -0.0049719661 -0.029664978, -0.010145545 -0.0027032793 -0.028786123, 0.015910611 0.0055372864 -0.030206606, 0.016286761 0.0048067421 -0.030244365, -0.014251247 -0.00386554 -0.029664904, -0.01451084 -0.0027354956 -0.029664963, -0.01043725 -0.0016095042 -0.028796479, -0.014680833 -0.0015886277 -0.02966477, -0.010728776 -0.0005159229 -0.028827533, -0.014760464 -0.00043183565 -0.02966474, -0.01102002 0.00057683885 -0.028879285, -0.014748812 0.000727579 -0.029664591, -0.011311218 0.0016684532 -0.028951824, -0.014646336 0.0018826574 -0.029664665, -0.011601821 0.0027587712 -0.029044956, -0.01445365 0.0030258298 -0.029664621, -0.011892036 0.0038471222 -0.029158875, -0.014171854 0.0041507185 -0.029664472, -0.01218155 0.0049332529 -0.029293269, -0.013802633 0.0052497834 -0.029664367, -0.012470454 0.0060170144 -0.029448271, -0.013348386 0.0063165128 -0.029664457, -0.0088320673 0.01509656 -0.030389085, -0.0083833486 0.017009959 -0.030836791, 0.016522467 0.0039068311 -0.030243605, 0.016543671 0.0029760897 -0.030196294, -0.0061156452 0.015729114 -0.030213907, -0.0059587657 0.0180033 -0.03083688, -0.0060490668 0.013472483 -0.029663935, -0.0049734265 0.013905764 -0.02966398, 5.1483512e-05 0.016876236 -0.030213699, 0.0018025935 0.018878207 -0.030836716, -0.00081671774 0.01894626 -0.030836701, 0.0030311048 0.01660192 -0.030213818, 0.0043874383 0.018449396 -0.030836776, 0.0054407865 0.015975177 -0.030213818, 0.0068885684 0.017668396 -0.030836701, 0.0088850111 0.014347687 -0.030213922, 0.011450812 0.015115708 -0.030836985, 0.0092581809 0.016550153 -0.03083688, 0.016350672 0.0020700544 -0.030105963, 0.010899454 0.01288417 -0.030213982, 0.013027653 0.010727271 -0.03021419, 0.014520437 0.0091949552 -0.030302286, 0.014867768 0.0090803057 -0.03036961, 0.01748924 4.2483211e-05 -0.03038983, 0.015957996 0.0012381524 -0.029978439, 0.017182782 -0.00033396482 -0.030302659, 0.01662688 -0.0028795898 -0.030214965, 0.010341957 -0.0074740201 -0.029213488, 0.011505485 -0.0092548281 -0.029665291, 0.012196258 -0.00832358 -0.029665321, 0.0082168579 -0.0066327453 -0.028796807, 0.0090181679 -0.0058335811 -0.028827801, 0.014385924 -0.0088184476 -0.030215159, 0.012551337 -0.011277542 -0.030215368, 0.0064725727 -0.011165336 -0.029244199, 0.0070873797 -0.012952968 -0.029665515, 0.0050119609 -0.0098298192 -0.028879791, 0.005812645 -0.0090309829 -0.028828055, 0.008082062 -0.012357205 -0.029665455, 0.010725439 -0.013025939 -0.030215472, 0.0051537156 -0.016066864 -0.03021574, 0.0026955307 -0.016656235 -0.03021574, 0.00029270351 -0.017181784 -0.030303672, -0.0011948794 -0.015901342 -0.029964149, -4.2259693e-05 -0.017458856 -0.030382693, -0.0019304305 -0.016279191 -0.030083537, -0.0092296898 -0.014495507 -0.030303523, -0.009115234 -0.014844581 -0.030371159, -0.011279255 -0.012549475 -0.030215248, -0.012982264 -0.010778487 -0.030215338, -0.015098065 -0.011470392 -0.03083846, -0.015054613 -0.0076213926 -0.030215204, -0.017602369 -0.007049337 -0.030838132, -0.016499013 -0.0093440562 -0.030838266, -0.016145259 -0.0049057156 -0.03021504, -0.018388435 -0.0046273172 -0.030837983, -0.016827196 0.0012649447 -0.030214623, -0.018730268 0.0029578507 -0.030837595, -0.018957466 0.00042177737 -0.030837879, -0.0028203279 -0.016511604 -0.030181617, -0.015143484 0.0081278086 -0.03030239, -0.01727277 0.0078254938 -0.030837387, -0.0043521821 0.015214458 -0.029929772, -0.0038670897 0.014252946 -0.029663965, -0.0027370602 0.014512554 -0.02966395, -0.0048854947 0.017244056 -0.030516118, -0.0034204125 0.018652901 -0.030836776, -0.0014486909 0.015758276 -0.029929578, -0.001595661 0.017851725 -0.030516207, 0.0072089881 0.015258849 -0.030213773, 0.0072941184 0.01637128 -0.030516207, 0.015260443 -0.0041801631 -0.02993089, -0.0037456304 -0.016534343 -0.030238211, -0.0046529472 -0.016343281 -0.030249268, 0.017295957 -0.0046906769 -0.030517444, 0.014201656 -0.0069756359 -0.029930949, 0.016104698 -0.0078599155 -0.030517593, 0.0088649988 -0.013104945 -0.029931381, 0.010025188 -0.014853075 -0.030518055, 0.0062416941 -0.014538318 -0.029931411, 0.0070523471 -0.016473427 -0.030518189, -0.014107123 -0.0092579573 -0.030215278, -0.014748365 -0.010179147 -0.030517668, -0.015502989 -0.003164798 -0.029930755, -0.017550826 -0.0036226064 -0.030517235, -0.018842831 -0.0021218807 -0.030837834, -0.015820891 -0.0002591908 -0.029930621, -0.0054897815 -0.015949845 -0.030214325, -0.017917886 -0.00033245981 -0.03051728, -0.017622158 0.0032617152 -0.030517235, -0.01816529 0.0054406673 -0.030837581, -0.016706854 0.0069025457 -0.030563295, -0.003085807 0.016591832 -0.030213803, 0.015788347 -0.005955413 -0.030215025, 0.0080839545 -0.014810786 -0.030215576, -0.016772658 -0.0018517226 -0.030214965, -0.0059841424 0.012487173 -0.029448003, -0.0049012899 0.012195498 -0.029292956, -0.0038157403 0.011903226 -0.029158473, -0.0027280152 0.011610344 -0.029044479, -0.043379873 0.02964285 -0.026121527, -0.039093554 0.023875475 -0.027596459, -0.0380086 0.025566995 -0.027596354, -0.028876722 0.01432623 -0.029773012, -0.028220668 0.015579 -0.029772907, -0.045716256 0.025894403 -0.026121989, -0.040102959 0.022137791 -0.027596593, -0.029477194 0.013045847 -0.029773191, -0.04103525 0.02035746 -0.027596638, -0.047729701 0.021962896 -0.026122063, -0.030021101 0.011740476 -0.02977322, -0.030506998 0.01041232 -0.029773295, -0.030934364 0.0090642571 -0.02977334, -0.039000332 0.0090928972 -0.028649285, -0.036205545 0.0089044571 -0.029086322, -0.03847611 0.0094092935 -0.028721303, -0.044177696 0.013605177 -0.027513385, -0.050732315 0.013663232 -0.026122436, -0.044355661 0.012741506 -0.027528509, -0.044326514 0.011863008 -0.027581409, -0.0440927 0.011016175 -0.027668521, -0.040687725 0.00870502 -0.028382838, -0.036561266 0.0073078573 -0.029086351, -0.039824009 0.0087987632 -0.028525323, -0.049405575 0.017876238 -0.026122227, -0.040749758 0.0081448555 -0.028392211, -0.041549489 0.0088145584 -0.028229281, -0.03684637 0.0056972206 -0.029086351, -0.043081462 0.0096083581 -0.027921617, -0.044918582 0.0089779645 -0.027597338, -0.042362228 0.0091210604 -0.028072655, -0.041067734 0.0063496232 -0.028392434, -0.037060797 0.0040755719 -0.029086649, -0.045269176 0.0069991648 -0.027597442, -0.051700681 0.0093536675 -0.026122615, -0.041306823 0.0045425296 -0.028392389, -0.037203789 0.0024460256 -0.029086664, -0.045532539 0.0050068051 -0.027597591, -0.041466147 0.0027261823 -0.028392524, -0.045708224 0.0030048788 -0.027597606, -0.052536651 0.00056728721 -0.026123285, -0.052303687 0.0049781948 -0.026122883, -0.041545689 0.00090481341 -0.028392717, -0.045795947 0.0009971112 -0.02759771, -0.051890165 -0.0082351267 -0.026123703, -0.041545421 -0.00091813505 -0.028392658, -0.046576574 -0.0084298253 -0.027287394, -0.045795426 -0.0010124445 -0.027598023, -0.052398488 -0.0038474202 -0.026123405, -0.047118589 -0.0096216798 -0.027127907, -0.045706972 -0.0030200481 -0.027598038, -0.045530394 -0.0050218552 -0.027598202, -0.047689125 0.0099037886 -0.026994899, -0.043668509 0.010250062 -0.027784452, -0.05101493 -0.012564555 -0.026123971, -0.047325343 -0.010594264 -0.027041271, -0.047347382 -0.011586875 -0.02698794, -0.048801988 0.0060896575 -0.026892006, -0.0250673 0.020267218 -0.029772654, -0.03780596 0.036486328 -0.026121169, -0.034324452 0.030334264 -0.027595967, -0.033828199 0.032498598 -0.027372971, -0.040736794 0.033181682 -0.026121408, -0.025932208 0.019148096 -0.029772744, -0.043801367 0.014403716 -0.027536929, -0.035621986 0.028799802 -0.027596325, -0.026746884 0.017992392 -0.029772833, -0.036850706 0.027209654 -0.02759625, -0.0275103 0.016801894 -0.029772863, 0.034313604 0.043286309 -0.023808584, 0.02905637 0.046977177 -0.023808405, -0.03954044 0.041056573 -0.022295594, -0.040956423 0.039644331 -0.022295758, 0.023406476 0.05003269 -0.023808211, 0.017439902 0.052411586 -0.023808032, 0.015659526 0.054305792 -0.022708878, 0.011237592 0.054081962 -0.023807913, 0.013728201 0.054825887 -0.022709012, 0.0048830211 0.055020943 -0.023808047, -0.0015373081 0.055215821 -0.023807809, -0.0079370439 0.054663971 -0.023807898, -0.014229238 0.053373054 -0.023808017, -0.020329058 0.051360026 -0.023808092, -0.026153982 0.048652768 -0.023808196, -0.031625271 0.045287445 -0.023808435, -0.036668748 0.041309819 -0.023808643, -0.041216433 0.036773413 -0.023809001, -0.045206815 0.031740025 -0.023809239, -0.048585758 0.02627708 -0.023809597, -0.051307648 0.020458922 -0.023809731, -0.053335711 0.014364228 -0.023810223, -0.054642484 0.0080751926 -0.023810551, -0.055210367 0.0016769767 -0.023810849, -0.055031508 -0.004743889 -0.023811176, -0.054858848 -0.013589635 -0.022712722, -0.054108575 -0.011100605 -0.023811609, -0.052453905 -0.017307147 -0.023812026, -0.054343671 -0.015522256 -0.022712722, -0.050089911 -0.023279712 -0.023812205, -0.047048315 -0.028937221 -0.023812637, -0.04337059 -0.034203589 -0.02381289, 0.035874829 0.04021199 -0.024964869, 0.037669629 0.042223632 -0.022652566, -0.040300339 -0.035772473 -0.024969116, -0.042316556 -0.037562504 -0.022656932, -0.053843766 -0.015389174 -0.015400901, -0.038834035 0.040348247 -0.015397817, -0.040250048 0.038935795 -0.015397832, -0.039311633 0.039883092 -0.015397787, -0.039783657 0.039412245 -0.015397862, 0.015524894 0.053805977 -0.015397042, 0.014883339 0.053986847 -0.015397012, 0.014239594 0.054160312 -0.015397012, 0.013593733 0.054325923 -0.015396878, -0.0543589 -0.013456687 -0.015400931, -0.054194868 -0.014102876 -0.015400872, -0.054023087 -0.014747173 -0.015400931, -0.017450511 -0.023001894 -0.029855043, -0.0079213232 -0.025568277 -0.030060142, -0.0079212338 -0.025568992 -0.015401542, -0.026014373 -0.02069594 -0.02934885, -0.034176961 -0.01849778 -0.028539836, -0.038721457 -0.017274141 -0.02793926, 0.028647155 -0.0036091655 -0.029854029, 0.026104689 0.0059263855 -0.030058369, 0.026104882 0.0059255958 -0.015399694, 0.03093186 -0.012178808 -0.029348165, 0.033109486 -0.02034688 -0.028540105, 0.034321994 -0.024894699 -0.027939707, -0.011196434 0.026616231 -0.029852539, -0.018183306 0.019646615 -0.030057594, -0.01818344 0.019645885 -0.015399009, -0.004917413 0.032879457 -0.029345602, 0.0010675788 0.038849324 -0.028536737, 0.004399702 0.042173281 -0.027935907, 0.034147546 -0.031508148 -0.025401697, 0.033463418 -0.032970503 -0.025401816, 0.033890948 -0.032279328 -0.025401831, 0.032195807 -0.033970177 -0.025401965, 0.032888129 -0.033544406 -0.025402024, 0.014394119 0.04366231 -0.025397584, 0.0088395327 0.044483215 -0.025397509, 0.014693186 0.042906746 -0.025397658, 0.01182282 0.045467675 -0.02539742, 0.012607604 0.045256242 -0.02539739, 0.011010557 0.045492142 -0.025397643, 0.010214508 0.045328945 -0.025397614, 0.0094775707 0.044986308 -0.025397509, 0.0099624097 0.037442088 -0.025397837, 0.0097302347 0.037449256 -0.025397956, 0.0095027834 0.037402555 -0.025397941, 0.031424105 -0.034224749 -0.02540198, 0.0092922598 0.037304685 -0.025397941, 0.0091099292 0.037160903 -0.025397941, 0.03421928 -0.030698806 -0.025401786, 0.030614495 -0.034294501 -0.025402024, 0.034102544 -0.02989462 -0.025401682, 0.029810563 -0.034175888 -0.025402054, 0.027659565 -0.026697442 -0.025401548, 0.027639076 -0.026928753 -0.025401682, 0.027626067 -0.0264678 -0.025401488, 0.027565703 -0.027149051 -0.025401458, 0.027443469 -0.027346432 -0.025401622, 0.027279139 -0.027510494 -0.025401607, 0.02708143 -0.027632147 -0.025401711, 0.026860997 -0.027704969 -0.025401548, 0.02639991 -0.027690977 -0.025401771, -0.042941898 -0.014584363 -0.025400758, -0.036735862 -0.01068902 -0.025400639, -0.037050441 -0.010541841 -0.025400624, -0.036899701 -0.010629103 -0.025400594, 0.026629612 -0.027724788 -0.025401771, 0.013928786 0.044328645 -0.025397539, 0.013322368 0.04486981 -0.025397539, -0.044042885 -0.014069155 -0.025400788, -0.043514952 -0.014374912 -0.025400728, 0.010782331 0.036710396 -0.025397956, 0.010696903 0.036926419 -0.02539812, 0.010564014 0.037116811 -0.025398046, 0.010390699 0.037271321 -0.025398001, 0.010186434 0.037381813 -0.025397941, 0.026399851 -0.027690813 -0.028478906, 0.026369184 -0.027682468 -0.028481171, 0.018721849 -0.025623068 -0.029373169, 0.011046633 -0.023556069 -0.029960677, 0.0012390316 -0.020915017 -0.030328661, -0.0099878609 -0.017891586 -0.030354485, -0.028169364 -0.012995601 -0.029455572, -0.019598559 -0.015303582 -0.030056342, -0.036704987 -0.010696679 -0.028480783, -0.036735877 -0.010688782 -0.028477937, 0.010782376 0.03671065 -0.02847515, 0.010790557 0.036679968 -0.028477564, 0.012831002 0.029026464 -0.029370263, 0.014880195 0.021340594 -0.029958412, 0.017496973 0.011525497 -0.030326933, 0.020508319 0.00023035705 -0.030351847, 0.025342241 -0.017901093 -0.029455259, 0.023058087 -0.009333089 -0.030055285, 0.027617499 -0.026436776 -0.028481603, 0.027626157 -0.026467413 -0.028478816, -0.037159622 -0.0089927614 -0.028479993, -0.031517178 -0.0033643991 -0.029376671, -0.025850713 0.0022880286 -0.029964879, -0.018643722 0.0094769746 -0.030329257, -0.010427803 0.017672345 -0.030351147, 0.0028605163 0.03092736 -0.02944918, -0.003389731 0.024692789 -0.030049562, 0.0090873837 0.037138447 -0.028477579, 0.0091098249 0.037161008 -0.028473303, 0.038517058 -0.011667088 -0.024986535, 0.038518459 -0.011669323 -0.028441578, 0.038212702 -0.011138558 -0.02498658, 0.038213193 -0.011139438 -0.028518528, 0.038004681 -0.010564715 -0.024986535, 0.038004816 -0.010564819 -0.028580025, 0.042045951 0.0014507324 -0.028100714, 0.039873883 0.0095973313 -0.028284907, 0.039873898 0.0095971376 -0.024985284, 0.043401778 -0.0036352575 -0.027830541, 0.044755533 -0.0087127537 -0.027437821, 0.027582631 0.028934002 -0.028487071, 0.027582839 0.028920606 -0.02498433, 0.027674168 0.029783711 -0.028367594, 0.0276687 0.029759988 -0.024984092, 0.027967215 0.030582771 -0.028226778, 0.027953014 0.030554339 -0.024984166, 0.028443396 0.03128624 -0.028072983, 0.028419122 0.031257764 -0.024984062, 0.02907221 0.031852201 -0.027915582, 0.029040009 0.031829119 -0.024984136, 0.029823035 0.03225258 -0.027762726, 0.029779628 0.032235205 -0.024984121, 0.030594885 0.032452494 -0.024984032, 0.030648753 0.032459974 -0.027623683, 0.031438485 0.032468602 -0.024984077, 0.031503886 0.032461315 -0.027506948, 0.032261267 0.032282069 -0.024984106, 0.032334328 0.032255262 -0.027420163, 0.033015713 0.03190425 -0.024984121, 0.033093706 0.031851292 -0.027368248, 0.0336577 0.031356782 -0.024984062, 0.033676535 0.031336322 -0.02735424, 0.03409113 0.030774489 -0.027369067, 0.034150124 0.030671477 -0.024984077, 0.03430894 0.030343011 -0.027394265, 0.037994251 -0.010525256 -0.028583676, 0.035825625 -0.0023914129 -0.029120371, 0.033110172 0.0077939034 -0.024985626, 0.034468278 0.0027000606 -0.029304668, 0.033110276 0.0077940375 -0.029378518, 0.040020153 -0.010027781 -0.022900626, 0.040227115 -0.010473102 -0.02290073, 0.040104166 -0.010259464 -0.02290073, 0.037858561 0.0090597421 -0.022899553, 0.035125405 0.0083310157 -0.022899717, -0.032053843 -0.032826036 -0.024987847, -0.032061011 -0.032814205 -0.027382329, -0.032398254 -0.032069489 -0.024987787, -0.032405898 -0.032044917 -0.027442753, -0.032554373 -0.031253442 -0.024987489, -0.032556504 -0.03122139 -0.027535409, -0.032513872 -0.030423462 -0.024987668, -0.032507703 -0.030387685 -0.027654991, -0.032278731 -0.02962631 -0.024987504, -0.032262966 -0.029589847 -0.02779451, -0.031862304 -0.02890712 -0.024987504, -0.031837493 -0.028874189 -0.027945906, -0.031288058 -0.028306454 -0.024987414, -0.03125836 -0.028282061 -0.02809985, -0.030588448 -0.027858078 -0.02498734, -0.03055346 -0.027841166 -0.028248951, -0.029802695 -0.027587205 -0.024987444, -0.029761165 -0.027578175 -0.028384835, -0.028975368 -0.027509272 -0.0249874, -0.028955415 -0.0275096 -0.028495833, -0.028153002 -0.027628496 -0.0249874, -0.028153032 -0.027628243 -0.028581008, -0.019768 -0.037135839 -0.028102756, -0.011626661 -0.039328218 -0.028287664, -0.01162672 -0.039328411 -0.02498813, -0.024850577 -0.035767078 -0.027832419, -0.029924572 -0.034400702 -0.027439043, 0.011264995 -0.038352042 -0.028490856, 0.011253521 -0.038345695 -0.0249881, 0.011955142 -0.038856208 -0.028371364, 0.011937425 -0.038839683 -0.024987951, 0.012500688 -0.039509386 -0.028230667, 0.012483314 -0.03948319 -0.024988085, 0.012871683 -0.040273592 -0.028077051, 0.012859404 -0.0402385 -0.024988055, 0.013047338 -0.041100904 -0.027919814, 0.013043761 -0.041061819 -0.024988234, 0.013018712 -0.041951373 -0.027766749, 0.013025776 -0.041905418 -0.024988204, 0.012806222 -0.042720139 -0.024988309, 0.012785584 -0.042770311 -0.027627692, 0.012398377 -0.04345867 -0.024988309, 0.012359202 -0.043511495 -0.027511343, 0.011825487 -0.044078141 -0.024988338, 0.011765391 -0.044127479 -0.027424499, 0.011121005 -0.044542417 -0.024988398, 0.011035919 -0.044583306 -0.027372509, 0.010325834 -0.044824824 -0.024988472, 0.010298669 -0.044830441 -0.027358517, 0.0096047223 -0.044908687 -0.027373239, 0.0094861835 -0.044908509 -0.024988383, 0.009122327 -0.044881478 -0.027398467, -0.028113663 -0.027638808 -0.028584599, -0.019985035 -0.029827833 -0.02912198, -0.0098066032 -0.032569051 -0.024987683, -0.014897183 -0.03119801 -0.029306531, -0.0098064542 -0.032568663 -0.029380888, -0.01034902 -0.034583271 -0.022902086, -0.02869527 -0.029642716 -0.022901759, -0.011084333 -0.037314281 -0.022902235, -0.029962033 -0.029916599 -0.022901669, -0.029679298 -0.029735327 -0.022901744, -0.029361933 -0.029626071 -0.022901639, -0.029027611 -0.029594421 -0.022901624, -0.030194074 -0.030159384 -0.022901744, -0.030362383 -0.030449882 -0.022901714, -0.030410632 -0.031437203 -0.022901699, -0.03027153 -0.031742766 -0.022901744, -0.030457407 -0.030772045 -0.022901714, -0.030473769 -0.031107381 -0.022901684, -0.01412566 0.043675885 -0.027373195, -0.014795244 0.043153673 -0.027429983, -0.014795214 0.04315345 -0.024983421, -0.014130324 0.043672979 -0.024983332, -0.013360515 0.044018283 -0.024983332, -0.013349056 0.044022024 -0.027353436, -0.012530386 0.044169456 -0.024983302, -0.012513787 0.04417035 -0.027372077, -0.011688158 0.044117361 -0.024983421, -0.011670187 0.044114187 -0.027427495, -0.010882944 0.043865293 -0.024983451, -0.01086463 0.043857187 -0.027516812, -0.010161459 0.043427929 -0.024983451, -0.010147333 0.043416783 -0.027634069, -0.0095656365 0.042830497 -0.024983361, -0.0095561445 0.042818829 -0.02777274, -0.0091300309 0.042107955 -0.024983689, -0.0091273189 0.042102516 -0.02792348, -0.0088799298 0.041301966 -0.024983436, -0.0088805854 0.041305855 -0.02807875, -0.0088300258 0.040459722 -0.0249836, -0.0088294148 0.040470719 -0.028229907, -0.0089832693 0.039629981 -0.0249836, -0.0089779347 0.039647266 -0.028367847, -0.009330377 0.038861051 -0.024983659, -0.0093188882 0.038880423 -0.028485149, -0.0095641613 0.038522273 -0.028535306, -0.0098516941 0.038197547 -0.024983823, -0.0098516494 0.038197696 -0.028577074, -0.022277683 0.035689801 -0.028098702, -0.028246999 0.029735506 -0.028283834, -0.028247014 0.029735327 -0.02498427, -0.01855126 0.039407015 -0.027828142, -0.014830768 0.043118149 -0.027434692, -0.04364872 0.010633379 -0.027569339, -0.043608949 0.010568112 -0.024985239, -0.043948054 0.01127468 -0.02498512, -0.043996856 0.01142548 -0.027464047, -0.044121593 0.012039155 -0.02498515, -0.044135317 0.012195498 -0.027397543, -0.044120669 0.012822866 -0.024985075, -0.044110581 0.012899637 -0.027363688, -0.043945208 0.013586804 -0.024985164, -0.043945312 0.013586596 -0.027355596, -0.043645114 0.014226213 -0.027374312, -0.043604299 0.014292493 -0.024984941, -0.043400347 0.014582723 -0.027398363, -0.0098803788 0.038168758 -0.02858083, -0.015840337 0.032223955 -0.029118538, -0.023303553 0.02477932 -0.024984449, -0.019570976 0.028502747 -0.029303223, -0.023303509 0.024779648 -0.02937749, -0.011209041 0.041546091 -0.022897735, -0.011324733 0.039674133 -0.022897765, -0.011033103 0.041254178 -0.02289775, -0.010931998 0.040928617 -0.02289775, -0.010911882 0.040588066 -0.022897691, -0.010973677 0.040252864 -0.02289772, -0.011114106 0.039942265 -0.022897825, -0.011449859 0.04178746 -0.02289778, -0.011741474 0.041964203 -0.02289775, -0.012066826 0.042066187 -0.022897616, -0.012407035 0.042087004 -0.02289772, -0.01274249 0.042026043 -0.022897542, -0.013053462 0.041886613 -0.022897631, -0.013322249 0.041676745 -0.022897646, -0.024776444 0.026255846 -0.0228986, -0.026774034 0.028258473 -0.022898465, -0.025308043 -0.0063417554 -0.030417398, -0.028078005 -0.0083915442 -0.030107304, -0.024997994 -0.0074708462 -0.030417398, -0.0284262 -0.0071233511 -0.030107245, -0.036851928 -0.010107279 -0.028945237, -0.035093173 -0.0087946355 -0.029249981, -0.036923856 -0.010029957 -0.028937459, -0.036977708 -0.0099388212 -0.028933197, -0.037007406 -0.0098533332 -0.028932124, -0.035318598 -0.0078404993 -0.029249817, -0.03160961 -0.0079212189 -0.029730946, -0.037019521 -0.009774372 -0.028933272, -0.037018821 -0.0096947551 -0.02893661, -0.037005141 -0.0096164495 -0.028941914, -0.036978811 -0.0095417947 -0.028948754, -0.03694053 -0.0094724 -0.028957173, -0.036901698 -0.009420678 -0.028965011, -0.03685692 -0.0093740821 -0.02897346, -0.036632448 -0.010215715 -0.02897352, -0.02463758 -0.0085846782 -0.030417472, -0.021548897 -0.0064397752 -0.03069663, -0.021238163 -0.0074000955 -0.030696839, -0.033756122 -0.010989308 -0.029346555, -0.031222284 -0.009331286 -0.02973114, -0.020884782 -0.0083453953 -0.030696958, -0.018105417 -0.0067254901 -0.030883789, -0.027673125 -0.0096426904 -0.030107275, -0.024227709 -0.0096814781 -0.030417591, -0.030876145 -0.01176393 -0.029674083, -0.03077215 -0.010722637 -0.029731125, -0.020489156 -0.0092740357 -0.030697003, -0.016963705 -0.0092335641 -0.030883923, -0.027992606 -0.012539521 -0.02995798, -0.027212515 -0.010874495 -0.03010729, -0.023768798 -0.010758787 -0.030417711, -0.020052433 -0.01018402 -0.030696943, -0.025105715 -0.013315633 -0.030198738, -0.026697308 -0.012084514 -0.030107394, -0.023262084 -0.011814356 -0.030417591, -0.022793651 -0.013937354 -0.030361548, -0.019575268 -0.011073336 -0.030697018, -0.019058734 -0.01194036 -0.030697107, -0.015476719 -0.011553973 -0.030884027, -0.020479664 -0.014559537 -0.030499414, -0.018503666 -0.012783423 -0.030697122, -0.017283201 -0.014390692 -0.030697286, -0.018163741 -0.015182182 -0.030613154, -0.016619951 -0.01515165 -0.030697197, 0.010290921 0.036670566 -0.028962299, 0.010265499 0.036730006 -0.028954551, 0.010309041 0.036608383 -0.028970972, 0.010224596 0.036797822 -0.028946117, -0.0037780702 0.023612753 -0.030593276, -0.0056129396 0.021781042 -0.030695096, -0.0040819198 0.018880308 -0.030882299, -0.0067269802 0.018106997 -0.030882463, -0.0074488521 0.019948542 -0.030772343, -0.009284988 0.01811564 -0.030827239, -0.0092353225 0.016965464 -0.030882478, -0.010309249 0.017093584 -0.030849189, -0.01133351 0.016071454 -0.030864701, -0.011555582 0.015478358 -0.030882597, -0.012357771 0.015049547 -0.03087455, -0.013382152 0.014027372 -0.030878991, -0.013640434 0.01367636 -0.030882627, -0.014406592 0.013005733 -0.030878156, -0.015447736 0.011596069 -0.03088282, -0.01543124 0.011983782 -0.030871883, -0.016455948 0.010962039 -0.030860111, -0.016940653 0.0092796385 -0.030882806, -0.017480522 0.0099403858 -0.030842349, -0.01923722 0.0081890225 -0.03079702, -0.018088356 0.0067741275 -0.030882955, -0.020993739 0.0064382851 -0.030731916, -0.018868297 0.0041310936 -0.030883163, -0.022749752 0.0046880245 -0.030645102, -0.036754355 -0.010172561 -0.028957054, 0.015383735 0.01754728 -0.030636117, 0.015194863 0.016583681 -0.030695468, 0.01492092 0.01928553 -0.030557215, 0.014435634 0.017248601 -0.030695498, 0.011594355 0.01544942 -0.030882552, 0.014458522 0.021023184 -0.030465141, 0.013647318 0.017879128 -0.030695364, 0.012831435 0.018473387 -0.030695334, 0.011989906 0.019030392 -0.030695364, 0.013996318 0.022759765 -0.030359581, 0.0092778951 0.016942218 -0.030882388, 0.011124015 0.019549236 -0.030695304, 0.012904689 0.022677958 -0.030415669, 0.013534099 0.024495676 -0.030239791, 0.01023595 0.020028666 -0.03069523, 0.011874259 0.023234144 -0.030415773, 0.01307252 0.026230052 -0.030105472, 0.0093270987 0.020467594 -0.030695215, 0.0067724735 0.018090352 -0.030882373, 0.010820046 0.02374348 -0.030415744, 0.0083994418 0.020865574 -0.030695155, 0.012153029 0.026668578 -0.030105293, 0.012611181 0.02796331 -0.029955566, 0.0097438544 0.024205074 -0.030415729, 0.0074549764 0.02122131 -0.03069526, 0.010944486 0.02718693 -0.030105159, 0.012149855 0.029695451 -0.029790416, 0.0086482167 0.02461791 -0.030415595, 0.0064954013 0.021534443 -0.030695274, 0.0041293055 0.018870011 -0.030882448, 0.0097137243 0.027650625 -0.030105129, 0.0075351894 0.024981022 -0.030415565, 0.01080142 0.030746922 -0.029728845, 0.011228591 0.033155337 -0.029413134, 0.0055228621 0.021804214 -0.030695125, 0.0084635317 0.028058633 -0.030105159, 0.0064068586 0.025293753 -0.03041552, 0.009411186 0.031200692 -0.02972874, 0.004539147 0.022030011 -0.030695125, 0.007196039 0.028410107 -0.030105174, 0.0052656531 0.025555924 -0.03041552, 0.008002162 0.031591311 -0.029728681, 0.0035462081 0.022211492 -0.030695081, 0.0014021397 0.019265667 -0.030882418, 0.0059143454 0.028704315 -0.030105159, 0.0088839531 0.035072654 -0.029247582, 0.0080453008 0.035415068 -0.029227629, 0.0094678104 0.03683494 -0.028970942, 0.0095662028 0.036919057 -0.028954536, 0.0096716732 0.0369706 -0.028942555, 0.0097744912 0.036994517 -0.028934911, 0.0098803043 0.036995634 -0.028930455, 0.0099691749 0.036978155 -0.02892971, 0.01004377 0.036949456 -0.028930709, 0.010112301 0.036908939 -0.028934032, 0.010173202 0.036858127 -0.028939337, 0.0041138083 0.025766373 -0.03041552, 0.0065768212 0.031918511 -0.029728681, 0.0066215992 0.033994049 -0.029463351, 0.0025462508 0.022348195 -0.03069514, 0.0046206117 0.028940827 -0.030105114, 0.0029536635 0.025925159 -0.030415565, 0.0051382184 0.032181635 -0.029728666, 0.0037705004 0.031148583 -0.029874146, 0.0051966906 0.032571793 -0.029678717, 0.0015411079 0.022439823 -0.030695066, 0.0033176392 0.029119015 -0.030105203, 0.0023432374 0.029723778 -0.03004989, 0.0017877966 0.0260313 -0.030415401, 0.0009150058 0.02829808 -0.03020677, 0.00053288043 0.022486418 -0.030695111, 0.00061812997 0.026085332 -0.03041558, -0.00051423907 0.026871145 -0.030345008, -0.00047640502 0.022487596 -0.030695051, -0.001353696 0.01926896 -0.030882299, -0.00055266917 0.026086807 -0.030415475, -0.001944676 0.025443137 -0.030465022, -0.0014847964 0.022443756 -0.03069526, -0.0024901479 0.022354543 -0.030695125, -0.0034905374 0.022220343 -0.030695185, -0.022028178 0.0045407414 -0.030696228, -0.024505168 0.002938509 -0.030534893, -0.022209704 0.0035479367 -0.030696079, -0.019263819 0.0014036894 -0.030883282, -0.022346392 0.0025478452 -0.030696169, -0.026053786 0.001395002 -0.030416802, -0.022438288 0.0015427768 -0.030696407, -0.027601361 -0.00014747679 -0.030277967, -0.022484735 0.00053450465 -0.030696392, -0.022486016 -0.00047473609 -0.030696392, -0.019267306 -0.001352191 -0.030883431, -0.029147759 -0.0016890019 -0.030117571, -0.026085109 -0.00055114925 -0.030417025, -0.022441983 -0.0014831573 -0.030696481, -0.030692756 -0.0032291412 -0.029935122, -0.026034072 -0.0017208904 -0.030417159, -0.025930583 -0.0028870106 -0.030417144, -0.022218585 -0.0034888983 -0.030696601, -0.0188784 -0.0040803999 -0.030883715, -0.032236457 -0.0047678202 -0.029730007, -0.029125392 -0.0032431632 -0.030106813, -0.025774822 -0.0040474981 -0.030417323, -0.022039518 -0.0044820011 -0.030696601, -0.033778399 -0.0063049942 -0.029501826, -0.028950453 -0.0045464039 -0.030106977, -0.025567234 -0.0051998794 -0.030417293, -0.021816179 -0.0054665208 -0.03069663, -0.02871722 -0.0058407933 -0.030106977, -0.031933218 -0.0064951032 -0.029730901, -0.036899194 -0.010628834 -0.028465003, -0.037050307 -0.010541186 -0.028453648, 0.0092127025 0.037250489 -0.028464749, 0.009326309 0.037324905 -0.02845566, 0.0094814301 0.037395522 -0.028445706, 0.0096458197 0.037438437 -0.028438061, 0.0098159313 0.037453145 -0.028432682, 0.0099846125 0.03743881 -0.028430015, 0.010150298 0.037395522 -0.028429925, 0.010305613 0.03732504 -0.028432503, 0.01044625 0.037229449 -0.028437555, 0.010571152 0.03710869 -0.028445199, 0.010699227 0.036921665 -0.028458625, 0.027652517 -0.026604384 -0.028468147, 0.027659431 -0.026743308 -0.028458849, 0.027642399 -0.026911646 -0.028449088, 0.027596846 -0.027074575 -0.028441474, 0.027524173 -0.027228221 -0.028436363, 0.027427092 -0.027366534 -0.028433621, 0.027307138 -0.027487338 -0.028433546, 0.027169541 -0.027585447 -0.028436139, 0.027016595 -0.027659416 -0.028441057, 0.02684927 -0.0277071 -0.02844888, 0.026623458 -0.027724236 -0.028462291, 0.030396 -0.035785615 -0.027056143, 0.030462906 -0.035790101 -0.015402064, 0.031385526 -0.035751671 -0.02692385, 0.031516641 -0.035733044 -0.015402049, 0.032469526 -0.035480365 -0.026811302, 0.032534838 -0.035455972 -0.015402049, 0.033472449 -0.034970716 -0.026743054, 0.033472419 -0.03497152 -0.015402049, -0.046191618 -0.0084304065 -0.02705425, -0.046227187 -0.0084852576 -0.015400454, -0.046656236 -0.0093033016 -0.026922196, -0.046704695 -0.0094262958 -0.015400469, -0.046963468 -0.010379925 -0.026809603, -0.046973974 -0.010446846 -0.015400708, -0.047023177 -0.011500284 -0.026741594, -0.047023013 -0.01150094 -0.015400708, 0.014523417 0.04583697 -0.026809826, 0.014452308 0.045894712 -0.015397385, 0.01416786 0.046108931 -0.026776448, 0.014017224 0.046209052 -0.015397459, 0.013550684 0.046475694 -0.02673845, 0.013550699 0.046475053 -0.015397459, 0.009163931 0.016734257 -0.030866012, 0.0066894293 0.017868176 -0.030866057, -0.016266719 0.01019305 -0.030881777, 0.0067306608 0.017978713 -0.030881301, -0.016836077 0.0092222095 -0.030881792, 0.0092206597 0.016837761 -0.030881315, 0.011522919 0.015354186 -0.03088139, -0.016166627 0.010130286 -0.030866504, -0.016732454 0.0091655105 -0.030866355, 0.011451975 0.015259728 -0.030865997, -0.015352488 0.011524454 -0.030881703, -0.015258044 0.011453599 -0.030866355, -0.014706641 0.012338236 -0.030881599, -0.014616117 0.012262374 -0.03086628, -0.013556302 0.01359202 -0.030881569, -0.015284047 -0.01161176 -0.030883089, -0.01347293 0.013508394 -0.030866221, -0.015190065 -0.011540234 -0.030867577, -0.012865633 0.014247715 -0.03088142, -0.016702354 -0.0094590783 -0.03088291, -0.012786478 0.014160112 -0.030866221, -0.016599476 -0.0094010085 -0.030867636, -0.01148425 0.015383095 -0.030881405, -0.017819196 -0.0071361661 -0.030882686, -0.010779008 0.01588513 -0.030881301, -0.017709509 -0.0070922971 -0.030867413, -0.011413649 0.015288323 -0.030866086, -0.018614858 -0.0046842396 -0.030882686, -0.010712683 0.015787467 -0.030866101, -0.018500477 -0.0046554506 -0.030867249, -0.009178251 0.016860768 -0.03088133, -0.019074723 -0.0021480769 -0.030882373, -0.0084865838 0.017219424 -0.030881345, -0.0091218948 0.01675719 -0.030866072, -0.019148394 -0.0013438165 -0.030882299, -0.0084343702 0.017113358 -0.030866042, -0.01895757 -0.0021348 -0.0308671, -0.0066856891 0.017995447 -0.03088136, -0.019030601 -0.0013353974 -0.03086704, -0.0060320795 0.018225089 -0.03088133, -0.019191101 0.00042693317 -0.030882254, -0.0066444129 0.017884761 -0.030866072, -0.019072965 0.00042426586 -0.030867055, -0.0059951693 0.018112987 -0.030865952, -0.019145027 0.0013951361 -0.030882239, -0.0040568411 0.018763855 -0.030881286, -0.019027218 0.0013864636 -0.030866876, -0.0040318668 0.018648356 -0.030865908, -0.018960923 0.0029943138 -0.030882239, -0.0013453364 0.019150227 -0.03088139, -0.018844262 0.002975896 -0.030866861, -0.0013370812 0.01903221 -0.030865863, -0.018751904 0.0041054785 -0.03088221, 0.0013934076 0.01914677 -0.03088136, -0.01863642 0.0040802062 -0.030866757, 0.0013848096 0.019028991 -0.030865923, -0.018389165 0.0055076331 -0.030882061, -0.018276006 0.005473882 -0.030866683, 0.0041038841 0.018753499 -0.03088133, 0.0040786415 0.018638164 -0.030866086, -0.017976999 0.0067324936 -0.030881897, -0.017866254 0.0066909194 -0.030866444, -0.01748541 0.007921651 -0.030881971, -0.017377973 0.0078731328 -0.030866534, 0.015386179 0.00051857531 -0.027899995, -0.00055536628 -0.015383169 -0.027901024, -0.010375589 0.0053881258 -0.027899742, -0.011254385 0.0057847947 -0.027899787, -0.0051878989 0.0094420016 -0.027899355, -0.00524728 0.0084795207 -0.027899683, -0.0053605139 0.010390714 -0.027899459, -0.0055352896 0.0075591505 -0.027899578, -0.0057551265 0.011270612 -0.027899325, -0.0060351789 0.0067346096 -0.027899638, 0.011235386 -0.00042337179 -0.027899981, 0.00059503317 -0.01210849 -0.0279008, 0.01210846 -0.00062380731 -0.027900234, -0.0067179352 0.0060536414 -0.027899876, 0.00059393048 -0.01300402 -0.02790086, 0.013004169 -0.00062488019 -0.027900055, 0.010428861 -3.3840537e-05 -0.02790001, 0.00039690733 -0.01123482 -0.027900577, 0.00039359927 -0.013877049 -0.02790083, 0.013877705 -0.00042669475 -0.027900115, 9.2089176e-06 -0.010427445 -0.027900651, 0.014685199 -3.9070845e-05 -0.027899981, 3.9637089e-06 -0.014683619 -0.027900934, -0.0075437725 0.0055556297 -0.027899742, -0.0084646642 0.0052700639 -0.027899787, -0.0094273239 0.0052129775 -0.027899846, -0.042914316 0.011489287 -0.023942173, -0.043100089 0.012429625 -0.023942262, -0.042911947 0.01336962 -0.023942217, -0.042253748 0.011353269 -0.023420885, -0.04312174 0.010775045 -0.024463832, -0.042251155 0.013503939 -0.02342093, -0.043117583 0.014084518 -0.024463713, -0.0098814517 0.040947661 -0.023940772, -0.010241419 0.041980058 -0.023940474, -0.01000531 0.039861023 -0.023940712, -0.013351202 0.042315811 -0.023419142, -0.013132185 0.04299587 -0.023940518, -0.013904914 0.043199375 -0.024462089, -0.010685757 0.039643556 -0.02341938, -0.0098033994 0.039087757 -0.024462149, -0.012045264 0.043116838 -0.023940578, -0.011013567 0.042754397 -0.023940533, 0.032946616 0.030587137 -0.023941219, 0.032067582 0.031237528 -0.023941204, 0.029147759 0.028916761 -0.023419932, 0.028668612 0.029446572 -0.023941353, 0.028105497 0.028879076 -0.024462849, 0.032794684 0.029889032 -0.023419932, 0.0337172 0.030375183 -0.0244627, 0.029107228 0.030448169 -0.023941249, 0.02993688 0.03116034 -0.023941219, 0.030993477 0.03144224 -0.023941115, 0.011017695 -0.043388173 -0.0239456, 0.011732012 -0.042560086 -0.023945317, 0.010014772 -0.043824062 -0.023945451, 0.010467678 -0.039699107 -0.02342388, 0.011166036 -0.039548919 -0.023945078, 0.010956109 -0.038777635 -0.024466634, 0.0094862431 -0.043343648 -0.023423895, 0.0094460547 -0.044385657 -0.024467036, 0.011814296 -0.040429622 -0.023945212, 0.012016326 -0.041504204 -0.023945332, -0.028929442 -0.02803269 -0.024466038, -0.028976277 -0.029074311 -0.023423165, -0.029486656 -0.028587878 -0.023944482, -0.031373173 -0.03184551 -0.02394484, -0.031510457 -0.030790865 -0.023944706, -0.031189352 -0.029777139 -0.023944721, -0.03046985 -0.028993815 -0.023944438, -0.030696854 -0.032046273 -0.023423329, -0.03157708 -0.032605365 -0.024466366, 0.0088395327 0.044482514 -0.015397593, 0.014693096 0.04290612 -0.015397549, 0.034102589 -0.02989538 -0.015401721, 0.029810607 -0.034176439 -0.015402034, -0.042942032 -0.014584735 -0.015400812, -0.043515012 -0.014375374 -0.015400827, 0.014394 0.043661803 -0.015397549, -0.04404287 -0.014069691 -0.015400946, 0.013928756 0.044328019 -0.015397608, 0.030614436 -0.034295216 -0.01540184, 0.031424165 -0.034225389 -0.015401974, 0.013322338 0.044868946 -0.015397564, 0.032195896 -0.033970743 -0.015402034, 0.0094776005 0.044985697 -0.015397504, 0.032888114 -0.033544824 -0.015402034, 0.033463478 -0.032971054 -0.015401959, 0.012607604 0.045255646 -0.015397415, 0.011822835 0.04546693 -0.015397504, 0.033890933 -0.032279983 -0.01540181, 0.010214567 0.045328215 -0.015397444, 0.011010647 0.045491531 -0.015397444, 0.034147486 -0.031508863 -0.015401855, 0.034219295 -0.030699402 -0.015401796, 0.040653333 0.034190461 -0.026909411, 0.040437296 0.034008741 -0.027053252, 0.043406412 0.030619666 -0.02690956, 0.043175653 0.030456752 -0.027053371, 0.045846567 0.02682814 -0.026909798, 0.045602962 0.026685536 -0.027053654, 0.047956511 0.022843525 -0.026910007, 0.047701523 0.022722185 -0.027053788, 0.049720868 0.018694326 -0.026910275, 0.049456492 0.018594846 -0.027054057, 0.051127046 0.014410287 -0.026910424, 0.050855309 0.014333755 -0.02705425, 0.052164748 0.010022447 -0.026910737, 0.051887393 0.0099691749 -0.027054548, 0.052826762 0.0055624098 -0.026911005, 0.052545875 0.0055329353 -0.027054757, 0.053108007 0.0010623336 -0.026911229, 0.052825719 0.0010567904 -0.02705507, 0.053006619 -0.0034452826 -0.026911572, 0.052724928 -0.0034270138 -0.027055308, 0.05252336 -0.0079280883 -0.02691181, 0.052244172 -0.0078858435 -0.027055517, 0.051661655 -0.012353927 -0.026912019, 0.051387057 -0.012288183 -0.027055845, 0.050427675 -0.016690344 -0.026912183, 0.050159767 -0.01660192 -0.027056009, 0.04883042 -0.020906866 -0.026912451, 0.048571005 -0.020795643 -0.027056366, 0.046881527 -0.024972782 -0.026912674, 0.046632335 -0.024839953 -0.0270565, 0.044594631 -0.028858498 -0.026912898, 0.044357598 -0.028705209 -0.027056664, 0.041986465 -0.032536373 -0.026913121, 0.041763276 -0.032363489 -0.027056903, 0.039075732 -0.035979897 -0.02691333, 0.038868144 -0.035788715 -0.027057081, 0.035883546 -0.039164394 -0.026913434, 0.03569293 -0.038956061 -0.02705729, 0.032432839 -0.042066127 -0.026913583, 0.032260343 -0.041842669 -0.027057528, 0.028748244 -0.044665143 -0.026913896, 0.028595597 -0.044427812 -0.027057812, 0.024856791 -0.046942294 -0.026913911, 0.024724677 -0.046692759 -0.027057797, 0.020786136 -0.048881188 -0.02691406, 0.020675689 -0.048621401 -0.027057678, 0.016565681 -0.050467804 -0.02691406, 0.016477734 -0.050199762 -0.027057856, 0.012225896 -0.051690891 -0.02691412, 0.012161031 -0.051416293 -0.027057901, 0.0077981353 -0.052541718 -0.026914269, 0.0077566504 -0.052262381 -0.027058035, 0.0033139884 -0.053013712 -0.026914313, 0.0032964498 -0.052731782 -0.02705802, -0.0011939853 -0.053103819 -0.026914343, -0.0011875629 -0.052821383 -0.027058005, -0.0056932122 -0.05281119 -0.026914299, -0.0056629628 -0.052530363 -0.027058035, -0.01015152 -0.052138031 -0.026914403, -0.010097623 -0.051860601 -0.027057976, -0.014536664 -0.051089212 -0.026914179, -0.014459372 -0.050817743 -0.027057886, -0.018817082 -0.049672425 -0.026913971, -0.018717065 -0.049408436 -0.027057812, -0.022961959 -0.047897816 -0.026914015, -0.022839978 -0.047643095 -0.027057841, -0.026941374 -0.045777828 -0.026913702, -0.026798084 -0.045534536 -0.027057692, -0.030726641 -0.043328047 -0.026913658, -0.030563444 -0.043097749 -0.027057543, -0.034290537 -0.040566117 -0.026913613, -0.034108356 -0.040350586 -0.027057379, 0.042072594 -0.010231033 -0.023910329, 0.04218699 -0.010053411 -0.02391021, 0.042348176 -0.0098737925 -0.023938671, 0.04227142 -0.010094434 -0.02393873, 0.042256519 -0.0098536015 -0.023910403, 0.042432502 -0.0098921955 -0.023984835, 0.042457074 -0.0096392334 -0.02398482, 0.042370528 -0.009641096 -0.023938715, 0.041919366 -0.010376796 -0.023910344, 0.042144895 -0.010290876 -0.023938864, 0.042349085 -0.010132402 -0.023984745, 0.042421132 -0.0093874186 -0.023984879, 0.041736007 -0.010482222 -0.023910239, 0.041975483 -0.010451958 -0.023938715, 0.042211369 -0.010345936 -0.023985058, 0.041533187 -0.010541663 -0.023910314, 0.041772947 -0.010568544 -0.023938701, 0.042027265 -0.010521308 -0.023985013, 0.041322067 -0.010551423 -0.023910329, 0.041548669 -0.010634169 -0.023938715, 0.041806921 -0.010648042 -0.023984894, 0.041114524 -0.01051116 -0.023910403, 0.041315213 -0.010644987 -0.023938671, 0.04156284 -0.010719314 -0.023984849, 0.040922195 -0.010423005 -0.023910373, 0.041085809 -0.010600403 -0.023938745, 0.042337626 -0.0094097406 -0.023938626, 0.0422768 -0.0096431673 -0.023910284, 0.042246968 -0.0094339252 -0.023910224, 0.041308939 -0.010731071 -0.023984924, 0.04087323 -0.010503113 -0.023938656, 0.041059285 -0.010682553 -0.023984909, 0.040828347 -0.010576874 -0.023984909, 0.030047759 0.028710857 -0.023982629, 0.030130997 0.028733268 -0.023936585, 0.03022185 0.028757319 -0.023908094, 0.032116845 0.029262483 -0.023982838, 0.03203319 0.029240072 -0.02393657, 0.031942561 0.029216111 -0.023908064, 0.030286089 0.029385507 -0.023908049, 0.031382143 0.029825121 -0.023908153, 0.031625926 0.029807046 -0.023936465, 0.031574011 0.029728979 -0.023908094, 0.03144291 0.029994801 -0.023982689, 0.030213654 0.029183477 -0.023908004, 0.031182438 0.029965758 -0.023936406, 0.031413689 0.029913425 -0.023936361, 0.031191111 0.030051798 -0.02398257, 0.030191839 0.028969899 -0.023907945, 0.030122235 0.029204115 -0.023936525, 0.031862721 0.02941528 -0.023908079, 0.031737402 0.029589653 -0.023908153, 0.030098155 0.028968111 -0.02393651, 0.030011669 0.028966576 -0.023982719, 0.031806484 0.029653206 -0.023936376, 0.030404568 0.029564515 -0.023907974, 0.031673729 0.029879048 -0.023982704, 0.031945035 0.02946046 -0.023936525, 0.03020215 0.029427648 -0.023936406, 0.031870127 0.029711708 -0.023982748, 0.030037954 0.029223189 -0.023982793, 0.030562654 0.029709831 -0.023908094, 0.032020628 0.02950196 -0.023982614, 0.030333325 0.029625282 -0.023936585, 0.030124873 0.029466271 -0.023982599, 0.030750781 0.02981317 -0.023908094, 0.030507863 0.029785991 -0.02393654, 0.030267462 0.029681355 -0.023982689, 0.030958176 0.029868484 -0.023908094, 0.030715838 0.029900163 -0.023936465, 0.030457526 0.02985622 -0.023982674, 0.031172693 0.029872626 -0.023907989, 0.030945122 0.029961497 -0.023936376, 0.030683726 0.029980436 -0.023982704, 0.030933112 0.030046895 -0.023982719, 0.033488512 0.029628351 -0.025507838, 0.033340603 0.030036256 -0.025507867, 0.033461004 0.029620945 -0.025414199, 0.033314884 0.030024558 -0.025414184, 0.033124045 0.030412614 -0.025507912, 0.033272937 0.030005023 -0.025327682, 0.03341642 0.029609099 -0.025327668, 0.033100694 0.030396521 -0.025414079, 0.033062816 0.030370012 -0.025327608, 0.038980305 -0.010304749 -0.025510266, 0.039007738 -0.010297477 -0.025416419, 0.039052367 -0.010285348 -0.025329873, 0.043792978 -0.0090215802 -0.025510207, 0.0437655 -0.0090290308 -0.025416404, 0.043720797 -0.0090408176 -0.025329858, 0.04235293 -0.01192759 -0.025416628, 0.042859554 -0.011635795 -0.025416568, 0.042364076 -0.01195389 -0.025510296, 0.042876601 -0.011658862 -0.025510311, 0.04233475 -0.011885136 -0.025330007, 0.039128363 -0.010712877 -0.025510311, 0.039344788 -0.011089131 -0.025510207, 0.041784182 -0.012045994 -0.025329933, 0.041791856 -0.012091622 -0.025416374, 0.039154083 -0.010700718 -0.02541633, 0.043625385 -0.010754332 -0.025510207, 0.039623514 -0.011422023 -0.025510281, 0.043305084 -0.011251241 -0.025510222, 0.043283224 -0.011233091 -0.025416434, 0.042831898 -0.01159896 -0.025330037, 0.039368108 -0.011072785 -0.025416508, 0.039195865 -0.010681421 -0.025329918, 0.043819368 -0.010195583 -0.025510147, 0.040087894 -0.011788115 -0.025510311, 0.043599755 -0.010741755 -0.02541633, 0.039643601 -0.011401877 -0.025416449, 0.043247461 -0.011203617 -0.025329962, 0.039406076 -0.01104635 -0.025329977, 0.04387635 -0.0096071064 -0.025510132, 0.040625349 -0.012034371 -0.025510207, 0.043791622 -0.010189444 -0.025416508, 0.043558106 -0.010721445 -0.025329977, 0.040102586 -0.011763722 -0.025416464, 0.039676294 -0.011369288 -0.025329962, 0.043847904 -0.0096076578 -0.025416359, 0.041205898 -0.01214695 -0.025510222, 0.043746486 -0.010179654 -0.025330007, 0.040634066 -0.012007326 -0.025416553, 0.043801755 -0.0096087009 -0.025329918, 0.040126681 -0.011724368 -0.025329903, 0.04179661 -0.012119621 -0.025510252, 0.041208014 -0.012118608 -0.025416642, 0.040648147 -0.011963397 -0.025329962, 0.041211307 -0.012072444 -0.025329918, -0.0099231601 0.04040207 -0.025327116, -0.010044247 0.039874971 -0.025327176, -0.010000721 0.039859563 -0.025413543, -0.0098772645 0.040396899 -0.025413603, -0.010213196 0.04199788 -0.025507331, -0.0099717677 0.041494995 -0.02550742, -0.0098483264 0.040951252 -0.025507301, -0.009998709 0.041485742 -0.025413424, -0.0098766237 0.040948108 -0.025413483, -0.0099225342 0.040943086 -0.025327116, -0.010237262 0.041982934 -0.025413424, -0.010042295 0.041470572 -0.025327086, -0.010276392 0.041958317 -0.025327101, -0.01061742 0.038965181 -0.02532725, -0.010564506 0.038912371 -0.025507405, -0.01021634 0.039347842 -0.02550745, -0.0099738985 0.039850131 -0.025507346, -0.010584757 0.038932607 -0.025413722, -0.010240451 0.03936322 -0.025413662, -0.0098491013 0.040393755 -0.025507376, -0.010279596 0.039387777 -0.025327057, -0.04240185 0.014189899 -0.025508806, -0.042381778 0.014169663 -0.025414973, -0.0423491 0.014136896 -0.025328562, -0.038884282 0.010663494 -0.025509015, -0.038904354 0.010683537 -0.025415331, -0.038937151 0.010716394 -0.02532877, -0.041970775 0.010319769 -0.02550903, -0.041459054 0.010103881 -0.025415286, -0.041468546 0.010077149 -0.025509045, -0.041955635 0.010343775 -0.025415301, -0.042386055 0.010687917 -0.025415316, -0.041930974 0.010382846 -0.025328815, -0.042750135 0.013754174 -0.025508806, -0.042992622 0.013252079 -0.025508925, -0.042353362 0.010720566 -0.025328711, -0.04036738 0.0099516511 -0.025509074, -0.042725995 0.013739124 -0.025414929, -0.040924981 0.0099522769 -0.025509104, -0.043117493 0.012708649 -0.025508791, -0.040921822 0.009980455 -0.025415242, -0.04144378 0.010147572 -0.025328815, -0.042965859 0.013242707 -0.025415108, -0.039823502 0.010075077 -0.025508925, -0.042686865 0.013714492 -0.025328681, -0.043118119 0.012150928 -0.025508881, -0.040370569 0.0099800676 -0.025415212, -0.040916517 0.010026455 -0.0253288, -0.043089122 0.012705311 -0.025415063, -0.039320722 0.010316387 -0.025508955, -0.042922258 0.013227433 -0.025328532, -0.042994708 0.011607185 -0.025508836, -0.039832935 0.0101019 -0.025415227, -0.040375665 0.010025874 -0.025328755, -0.043089971 0.012154013 -0.025415078, -0.039335817 0.010340467 -0.025415257, -0.043043256 0.0127002 -0.025328726, -0.03984803 0.01014547 -0.025328755, -0.042753398 0.01110442 -0.025509074, -0.039360359 0.010379732 -0.025328785, -0.042967916 0.011616543 -0.025415197, -0.043044031 0.012159109 -0.025328711, -0.042406335 0.010668054 -0.025508866, -0.042729318 0.011119395 -0.025415137, -0.042924255 0.011631638 -0.02532874, -0.042690128 0.011144012 -0.025328681, -0.012952268 0.041305929 -0.023907319, -0.012831435 0.041518375 -0.023935854, -0.012783095 0.041437998 -0.023907363, -0.012375966 0.041564286 -0.023907453, -0.011434585 0.040620551 -0.023907498, -0.011473566 0.040409386 -0.023907349, -0.011355072 0.040851668 -0.023935854, -0.011340976 0.040614679 -0.023935884, -0.01144734 0.040834814 -0.023907319, -0.012587219 0.041525856 -0.023907274, -0.012614951 0.041615501 -0.023935795, -0.011270016 0.040867016 -0.023982048, -0.011425272 0.041078195 -0.023935869, -0.011346444 0.041113541 -0.023981974, -0.011561975 0.040213749 -0.023907423, -0.013079628 0.041433364 -0.023982108, -0.012876093 0.041592345 -0.023982033, -0.013018519 0.041372165 -0.02393575, -0.01169461 0.040044889 -0.023907483, -0.012161762 0.041551158 -0.023907319, -0.01138404 0.040381342 -0.023935825, -0.012381583 0.041658074 -0.023935795, -0.011254877 0.04060933 -0.023981974, -0.011481673 0.040165171 -0.023935795, -0.011628196 0.039978594 -0.023935959, -0.012640625 0.041697979 -0.023981914, -0.011956856 0.041486681 -0.023907334, -0.011301592 0.040355504 -0.023981974, -0.011567339 0.039917365 -0.023982018, -0.011407822 0.040120393 -0.023982078, -0.012144849 0.041643262 -0.023935705, -0.01238665 0.041744187 -0.023981959, -0.011773363 0.041375712 -0.023907259, -0.011918336 0.041572571 -0.023935795, -0.012129053 0.041728318 -0.023981988, -0.011621788 0.041223779 -0.023907408, -0.011715323 0.041449308 -0.023935854, -0.011882797 0.041651353 -0.023981839, -0.011510983 0.04103981 -0.023907349, -0.011547834 0.041281343 -0.02393572, -0.011661917 0.041517287 -0.023981974, -0.011479676 0.041334718 -0.023982003, -0.039886892 0.011668518 -0.023983687, -0.039947987 0.011729702 -0.023937434, -0.040014207 0.011796072 -0.023908868, -0.04031916 0.011497289 -0.023937479, -0.040524587 0.011362463 -0.023983628, -0.040534019 0.011448324 -0.023937553, -0.041117802 0.011673152 -0.023908883, -0.040938243 0.011586666 -0.023909003, -0.040743858 0.011541888 -0.023908928, -0.040969357 0.011497959 -0.023937404, -0.040754452 0.011448726 -0.023937434, -0.040764317 0.011362851 -0.023983613, -0.041167781 0.011593848 -0.023937374, -0.040998012 0.011416525 -0.023983598, -0.0412139 0.011520743 -0.023983642, -0.040170208 0.011672109 -0.023909032, -0.040350094 0.011585847 -0.023909003, -0.040120304 0.011592522 -0.023937374, -0.040544465 0.011541754 -0.023909047, -0.040074497 0.011519283 -0.023983598, -0.040290788 0.011415571 -0.023983672, 0.009282738 -0.042443275 -0.023986816, -0.02934137 -0.032041922 -0.023986131, -0.029319063 -0.031958595 -0.023939863, 0.009305045 -0.042359725 -0.023940414, -0.029294491 -0.031868011 -0.02391158, 0.0093295425 -0.042269155 -0.023912027, -0.029440284 -0.031814888 -0.023911327, -0.029480025 -0.031899691 -0.023939997, -0.029574707 -0.03173697 -0.023911521, -0.029516727 -0.031977877 -0.023986131, -0.029628605 -0.031813771 -0.023939893, -0.029678255 -0.031884402 -0.023986146, 0.010553807 -0.041810453 -0.023986697, 0.010429025 -0.042036191 -0.023986712, 0.010473639 -0.041777939 -0.023940518, 0.0099914968 -0.040629998 -0.023911998, 0.010165572 -0.040755674 -0.023911953, 0.0099578202 -0.042206436 -0.023912117, 0.0097556412 -0.042278275 -0.023912013, 0.009817034 -0.040458903 -0.023940369, 0.010037005 -0.040547788 -0.023940578, 0.0097925067 -0.040549397 -0.023912072, 0.010304511 -0.040919244 -0.023911953, 0.010137126 -0.04208827 -0.023912042, 0.009999752 -0.042290464 -0.023940578, 0.010197774 -0.042159811 -0.023940459, 0.010253787 -0.042225674 -0.023986772, 0.010358885 -0.041985646 -0.023940578, 0.010229364 -0.040686667 -0.023940414, 0.0095420331 -0.042299509 -0.023912102, 0.0098394454 -0.040375412 -0.023986578, 0.010078803 -0.040472165 -0.023986638, 0.010400116 -0.04111138 -0.023912162, 0.0097759813 -0.042369872 -0.023940563, 0.010382846 -0.040867671 -0.023940474, 0.010038197 -0.042367667 -0.023986742, 0.010288 -0.040623367 -0.023986593, 0.0095399171 -0.042393386 -0.023940533, 0.0097950101 -0.042454109 -0.023986682, 0.01044701 -0.041321009 -0.023912057, 0.0095380843 -0.042479768 -0.023986742, 0.01048857 -0.041080087 -0.023940474, 0.010455012 -0.040820137 -0.023986444, 0.010442451 -0.041535646 -0.023912042, 0.010540426 -0.041311517 -0.023940444, 0.010569975 -0.041050911 -0.023986727, 0.010386735 -0.041742876 -0.023911968, 0.010535359 -0.041548908 -0.023940444, 0.01062654 -0.041303143 -0.023986608, 0.010282889 -0.04193069 -0.023911938, 0.010620877 -0.041560963 -0.023986697, -0.028415576 -0.0286033 -0.025511131, -0.028422996 -0.028630778 -0.025417507, -0.028434873 -0.028675243 -0.025331005, -0.031547308 -0.031182632 -0.02551125, -0.031409025 -0.031754747 -0.025417462, -0.031436205 -0.031763405 -0.025511384, -0.031518966 -0.031180546 -0.025417462, -0.029000536 -0.028518558 -0.02551122, -0.03149046 -0.030596793 -0.025417551, -0.031472892 -0.031177402 -0.02533111, -0.029589355 -0.028573886 -0.025511131, -0.031444877 -0.030604556 -0.025331154, -0.030826256 -0.032766744 -0.025511414, -0.02900137 -0.028546974 -0.025417477, -0.03119114 -0.032301456 -0.025511339, -0.030148491 -0.028766543 -0.025511295, -0.031166881 -0.032286704 -0.025417686, -0.031365022 -0.031740755 -0.025331125, -0.02958326 -0.028601795 -0.025417522, -0.030494124 -0.033046216 -0.025511518, -0.029002473 -0.028593138 -0.02533102, -0.03064619 -0.029085621 -0.02551128, -0.030806094 -0.032746792 -0.025417611, -0.031127349 -0.032262951 -0.025331214, -0.030136049 -0.028792173 -0.025417536, -0.030118376 -0.033263907 -0.025511429, -0.02957353 -0.028647006 -0.025331005, -0.029710621 -0.033412874 -0.025511488, -0.03105478 -0.029513165 -0.025511265, -0.030477658 -0.033023089 -0.02541773, -0.030773371 -0.032714218 -0.025331199, -0.030628189 -0.0291076 -0.025417387, -0.030106246 -0.033238024 -0.025417715, -0.029703215 -0.033385351 -0.025417656, -0.030115858 -0.028833851 -0.025331065, -0.030451179 -0.032985121 -0.025331214, -0.031351253 -0.030024827 -0.02551128, -0.029691115 -0.033340707 -0.025331199, -0.030086622 -0.033196121 -0.025331214, -0.03103213 -0.029530272 -0.025417477, -0.030598789 -0.029143244 -0.02533102, -0.031518459 -0.03059192 -0.025511384, -0.031325147 -0.030035987 -0.025417581, -0.030995116 -0.029557928 -0.025330991, -0.031282514 -0.030054465 -0.025331214, 0.011144266 -0.043331757 -0.025512069, 0.010646403 -0.043650538 -0.025512084, 0.008913517 -0.04381384 -0.025512204, 0.010087356 -0.04384324 -0.025512114, 0.01063396 -0.043625042 -0.025418311, 0.010081306 -0.043815538 -0.025418416, 0.010071561 -0.043770403 -0.02533181, 0.0095005035 -0.043824181 -0.025331795, 0.0094992518 -0.04387033 -0.025418222, 0.011552885 -0.042904124 -0.025512114, 0.011126146 -0.043309569 -0.025418177, 0.010613859 -0.043583453 -0.025331825, 0.01184909 -0.042392328 -0.02551198, 0.011530042 -0.042887077 -0.025418058, 0.01109679 -0.043273911 -0.025331855, 0.012016386 -0.04182519 -0.025511965, 0.011823028 -0.042381212 -0.025418222, 0.011493191 -0.042859331 -0.025331706, 0.012045234 -0.041234598 -0.025511906, 0.011988446 -0.041820452 -0.025418058, 0.011780515 -0.042362854 -0.02533184, 0.011934072 -0.04065384 -0.025511965, 0.012016907 -0.04123646 -0.025417998, 0.011942804 -0.041812778 -0.025331661, 0.011689112 -0.040115595 -0.025511891, 0.011907101 -0.040662557 -0.025418043, 0.0089207739 -0.043786392 -0.025418267, 0.0094986856 -0.043898746 -0.02551195, 0.011970773 -0.041239798 -0.025331676, 0.011664793 -0.040130377 -0.025418133, 0.0089329034 -0.043741807 -0.025331855, 0.011862993 -0.0406764 -0.025331706, 0.01162535 -0.040154517 -0.025331616 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 3, 4, 5, -1, 0, 6, 1, -1, 5, 4, 7, -1, 8, 6, 9, -1, 9, 6, 10, -1, 11, 12, 13, -1, 10, 6, 0, -1, 13, 12, 14, -1, 14, 12, 3, -1, 15, 16, 17, -1, 3, 12, 4, -1, 17, 16, 18, -1, 19, 20, 21, -1, 21, 20, 22, -1, 23, 24, 15, -1, 15, 24, 16, -1, 19, 25, 20, -1, 26, 25, 19, -1, 23, 27, 24, -1, 28, 27, 23, -1, 29, 30, 26, -1, 28, 31, 27, -1, 26, 30, 25, -1, 29, 32, 30, -1, 33, 31, 28, -1, 7, 32, 29, -1, 33, 34, 31, -1, 7, 35, 32, -1, 1, 34, 33, -1, 8, 36, 6, -1, 4, 35, 7, -1, 1, 36, 34, -1, 4, 37, 35, -1, 38, 36, 8, -1, 39, 37, 11, -1, 6, 36, 1, -1, 11, 37, 12, -1, 12, 37, 4, -1, 18, 40, 41, -1, 16, 40, 18, -1, 22, 42, 43, -1, 20, 42, 22, -1, 20, 44, 42, -1, 16, 45, 40, -1, 25, 44, 20, -1, 24, 45, 16, -1, 24, 46, 45, -1, 27, 46, 24, -1, 25, 47, 44, -1, 30, 47, 25, -1, 31, 48, 27, -1, 27, 48, 46, -1, 30, 49, 47, -1, 34, 50, 31, -1, 32, 49, 30, -1, 31, 50, 48, -1, 35, 51, 32, -1, 32, 51, 49, -1, 34, 52, 50, -1, 38, 52, 36, -1, 37, 53, 35, -1, 39, 53, 37, -1, 54, 52, 38, -1, 36, 52, 34, -1, 55, 53, 39, -1, 35, 53, 51, -1, 40, 56, 41, -1, 42, 57, 43, -1, 41, 56, 58, -1, 45, 59, 40, -1, 43, 57, 60, -1, 40, 59, 56, -1, 42, 61, 57, -1, 46, 62, 45, -1, 44, 61, 42, -1, 45, 62, 59, -1, 44, 63, 61, -1, 47, 63, 44, -1, 49, 64, 47, -1, 46, 65, 62, -1, 48, 65, 46, -1, 48, 66, 65, -1, 47, 64, 63, -1, 50, 66, 48, -1, 51, 67, 49, -1, 52, 68, 50, -1, 49, 67, 64, -1, 54, 68, 52, -1, 69, 68, 54, -1, 70, 71, 55, -1, 50, 68, 66, -1, 55, 71, 53, -1, 53, 71, 51, -1, 51, 71, 67, -1, 56, 72, 58, -1, 57, 73, 60, -1, 58, 72, 74, -1, 59, 75, 56, -1, 60, 73, 76, -1, 57, 77, 73, -1, 56, 75, 72, -1, 61, 77, 57, -1, 62, 78, 59, -1, 63, 79, 61, -1, 59, 78, 75, -1, 61, 79, 77, -1, 62, 80, 78, -1, 65, 80, 62, -1, 64, 81, 63, -1, 63, 81, 79, -1, 66, 82, 65, -1, 67, 83, 64, -1, 65, 82, 80, -1, 84, 85, 69, -1, 64, 83, 81, -1, 69, 85, 68, -1, 68, 85, 66, -1, 86, 87, 70, -1, 66, 85, 82, -1, 70, 87, 71, -1, 71, 87, 67, -1, 67, 87, 83, -1, 72, 88, 74, -1, 74, 88, 89, -1, 73, 90, 76, -1, 76, 90, 91, -1, 75, 92, 72, -1, 77, 93, 73, -1, 73, 93, 90, -1, 72, 92, 88, -1, 78, 94, 75, -1, 75, 94, 92, -1, 77, 95, 93, -1, 79, 95, 77, -1, 80, 96, 78, -1, 78, 96, 94, -1, 81, 97, 79, -1, 79, 97, 95, -1, 82, 98, 80, -1, 80, 98, 96, -1, 81, 99, 97, -1, 83, 99, 81, -1, 100, 101, 84, -1, 84, 101, 85, -1, 85, 101, 82, -1, 102, 103, 86, -1, 82, 101, 98, -1, 86, 103, 87, -1, 87, 103, 83, -1, 83, 103, 99, -1, 89, 104, 105, -1, 88, 104, 89, -1, 90, 106, 91, -1, 91, 106, 107, -1, 92, 108, 88, -1, 93, 109, 90, -1, 90, 109, 106, -1, 88, 108, 104, -1, 94, 110, 92, -1, 92, 110, 108, -1, 95, 111, 93, -1, 93, 111, 109, -1, 96, 112, 94, -1, 94, 112, 110, -1, 97, 113, 95, -1, 96, 114, 112, -1, 95, 113, 111, -1, 98, 114, 96, -1, 99, 115, 97, -1, 97, 115, 113, -1, 98, 116, 114, -1, 117, 116, 100, -1, 100, 116, 101, -1, 118, 119, 102, -1, 101, 116, 98, -1, 102, 119, 103, -1, 103, 119, 99, -1, 99, 119, 115, -1, 105, 120, 121, -1, 104, 120, 105, -1, 106, 122, 107, -1, 107, 122, 123, -1, 104, 124, 120, -1, 109, 125, 106, -1, 106, 125, 122, -1, 108, 124, 104, -1, 110, 126, 108, -1, 108, 126, 124, -1, 109, 127, 125, -1, 111, 127, 109, -1, 110, 128, 126, -1, 111, 129, 127, -1, 112, 128, 110, -1, 114, 130, 112, -1, 113, 129, 111, -1, 112, 130, 128, -1, 113, 131, 129, -1, 116, 132, 114, -1, 117, 132, 116, -1, 115, 131, 113, -1, 114, 132, 130, -1, 119, 133, 115, -1, 115, 133, 131, -1, 134, 132, 117, -1, 135, 133, 118, -1, 120, 136, 121, -1, 118, 133, 119, -1, 123, 137, 138, -1, 121, 136, 139, -1, 124, 140, 120, -1, 122, 137, 123, -1, 120, 140, 136, -1, 122, 141, 137, -1, 125, 141, 122, -1, 126, 142, 124, -1, 127, 143, 125, -1, 124, 142, 140, -1, 125, 143, 141, -1, 126, 144, 142, -1, 129, 145, 127, -1, 127, 145, 143, -1, 128, 144, 126, -1, 130, 146, 128, -1, 131, 147, 129, -1, 128, 146, 144, -1, 132, 148, 130, -1, 129, 147, 145, -1, 134, 148, 132, -1, 149, 148, 134, -1, 150, 151, 135, -1, 130, 148, 146, -1, 135, 151, 133, -1, 131, 151, 147, -1, 136, 152, 139, -1, 133, 151, 131, -1, 138, 153, 154, -1, 137, 153, 138, -1, 139, 152, 155, -1, 136, 156, 152, -1, 141, 157, 137, -1, 137, 157, 153, -1, 140, 156, 136, -1, 142, 158, 140, -1, 143, 159, 141, -1, 141, 159, 157, -1, 140, 158, 156, -1, 142, 160, 158, -1, 144, 160, 142, -1, 143, 161, 159, -1, 145, 161, 143, -1, 146, 162, 144, -1, 147, 163, 145, -1, 144, 162, 160, -1, 145, 163, 161, -1, 164, 165, 149, -1, 149, 165, 148, -1, 148, 165, 146, -1, 166, 167, 150, -1, 150, 167, 151, -1, 146, 165, 162, -1, 151, 167, 147, -1, 147, 167, 163, -1, 154, 168, 169, -1, 152, 170, 155, -1, 153, 168, 154, -1, 155, 170, 171, -1, 156, 172, 152, -1, 157, 173, 153, -1, 152, 172, 170, -1, 153, 173, 168, -1, 159, 174, 157, -1, 157, 174, 173, -1, 158, 175, 156, -1, 156, 175, 172, -1, 158, 176, 175, -1, 160, 176, 158, -1, 159, 177, 174, -1, 161, 177, 159, -1, 162, 178, 160, -1, 163, 179, 161, -1, 160, 178, 176, -1, 180, 181, 164, -1, 161, 179, 177, -1, 164, 181, 165, -1, 162, 181, 178, -1, 182, 183, 166, -1, 165, 181, 162, -1, 166, 183, 167, -1, 167, 183, 163, -1, 163, 183, 179, -1, 169, 184, 185, -1, 170, 186, 171, -1, 168, 184, 169, -1, 171, 186, 187, -1, 170, 188, 186, -1, 168, 189, 184, -1, 172, 188, 170, -1, 173, 189, 168, -1, 175, 190, 172, -1, 191, 192, 193, -1, 174, 194, 173, -1, 173, 194, 189, -1, 172, 190, 188, -1, 176, 195, 175, -1, 174, 196, 194, -1, 177, 196, 174, -1, 175, 195, 190, -1, 178, 197, 176, -1, 179, 198, 177, -1, 176, 197, 195, -1, 199, 200, 180, -1, 177, 198, 196, -1, 180, 200, 181, -1, 178, 200, 197, -1, 201, 202, 182, -1, 181, 200, 178, -1, 182, 202, 183, -1, 183, 202, 179, -1, 179, 202, 198, -1, 187, 203, 204, -1, 186, 203, 187, -1, 185, 205, 191, -1, 191, 205, 192, -1, 184, 205, 185, -1, 206, 207, 208, -1, 186, 209, 203, -1, 208, 207, 210, -1, 188, 209, 186, -1, 192, 211, 212, -1, 206, 213, 207, -1, 184, 211, 205, -1, 214, 213, 206, -1, 189, 211, 184, -1, 188, 215, 209, -1, 190, 215, 188, -1, 205, 211, 192, -1, 216, 217, 214, -1, 212, 218, 219, -1, 190, 220, 215, -1, 214, 217, 213, -1, 211, 218, 212, -1, 195, 220, 190, -1, 216, 221, 217, -1, 194, 218, 189, -1, 222, 221, 216, -1, 189, 218, 211, -1, 195, 223, 220, -1, 219, 224, 225, -1, 222, 226, 221, -1, 197, 223, 195, -1, 196, 224, 194, -1, 227, 226, 222, -1, 197, 228, 223, -1, 218, 224, 219, -1, 229, 228, 199, -1, 199, 228, 200, -1, 230, 231, 232, -1, 194, 224, 218, -1, 200, 228, 197, -1, 233, 231, 227, -1, 225, 234, 235, -1, 203, 236, 204, -1, 232, 231, 233, -1, 227, 231, 226, -1, 196, 234, 224, -1, 198, 234, 196, -1, 224, 234, 225, -1, 204, 236, 237, -1, 210, 238, 239, -1, 234, 240, 235, -1, 235, 240, 241, -1, 209, 242, 203, -1, 198, 240, 234, -1, 207, 238, 210, -1, 241, 240, 243, -1, 203, 242, 236, -1, 243, 240, 244, -1, 207, 245, 238, -1, 244, 240, 201, -1, 201, 240, 202, -1, 202, 240, 198, -1, 215, 246, 209, -1, 213, 245, 207, -1, 213, 247, 245, -1, 209, 246, 242, -1, 217, 247, 213, -1, 220, 248, 215, -1, 221, 249, 217, -1, 215, 248, 246, -1, 217, 249, 247, -1, 223, 250, 220, -1, 221, 251, 249, -1, 220, 250, 248, -1, 223, 252, 250, -1, 226, 251, 221, -1, 228, 252, 223, -1, 226, 253, 251, -1, 229, 252, 228, -1, 254, 253, 230, -1, 255, 252, 229, -1, 230, 253, 231, -1, 231, 253, 226, -1, 236, 256, 237, -1, 238, 257, 239, -1, 239, 257, 258, -1, 237, 256, 259, -1, 242, 260, 236, -1, 245, 261, 238, -1, 236, 260, 256, -1, 238, 261, 257, -1, 246, 262, 242, -1, 247, 263, 245, -1, 242, 262, 260, -1, 245, 263, 261, -1, 248, 264, 246, -1, 247, 265, 263, -1, 246, 264, 262, -1, 249, 265, 247, -1, 251, 266, 249, -1, 249, 266, 265, -1, 250, 267, 248, -1, 248, 267, 264, -1, 251, 268, 266, -1, 269, 270, 255, -1, 253, 268, 251, -1, 252, 270, 250, -1, 254, 268, 253, -1, 255, 270, 252, -1, 271, 268, 254, -1, 250, 270, 267, -1, 256, 272, 259, -1, 258, 273, 274, -1, 259, 272, 275, -1, 257, 273, 258, -1, 260, 276, 256, -1, 257, 277, 273, -1, 256, 276, 272, -1, 261, 277, 257, -1, 263, 278, 261, -1, 260, 279, 276, -1, 261, 278, 277, -1, 262, 279, 260, -1, 263, 280, 278, -1, 265, 280, 263, -1, 264, 281, 262, -1, 262, 281, 279, -1, 265, 282, 280, -1, 267, 283, 264, -1, 264, 283, 281, -1, 266, 282, 265, -1, 271, 284, 268, -1, 285, 286, 269, -1, 287, 284, 271, -1, 269, 286, 270, -1, 268, 284, 266, -1, 270, 286, 267, -1, 266, 284, 282, -1, 267, 286, 283, -1, 273, 288, 274, -1, 272, 289, 275, -1, 274, 288, 290, -1, 275, 289, 291, -1, 272, 292, 289, -1, 277, 293, 273, -1, 276, 292, 272, -1, 273, 293, 288, -1, 278, 294, 277, -1, 279, 295, 276, -1, 276, 295, 292, -1, 277, 294, 293, -1, 279, 296, 295, -1, 278, 297, 294, -1, 281, 296, 279, -1, 280, 297, 278, -1, 282, 298, 280, -1, 283, 299, 281, -1, 280, 298, 297, -1, 284, 300, 282, -1, 281, 299, 296, -1, 301, 300, 287, -1, 302, 303, 285, -1, 285, 303, 286, -1, 287, 300, 284, -1, 286, 303, 283, -1, 282, 300, 298, -1, 288, 304, 290, -1, 283, 303, 299, -1, 289, 305, 291, -1, 290, 304, 306, -1, 291, 305, 307, -1, 293, 308, 288, -1, 288, 308, 304, -1, 292, 309, 289, -1, 294, 310, 293, -1, 289, 309, 305, -1, 295, 311, 292, -1, 293, 310, 308, -1, 294, 312, 310, -1, 292, 311, 309, -1, 296, 313, 295, -1, 297, 312, 294, -1, 297, 314, 312, -1, 295, 313, 311, -1, 296, 315, 313, -1, 298, 314, 297, -1, 299, 315, 296, -1, 298, 316, 314, -1, 301, 316, 300, -1, 299, 317, 315, -1, 300, 316, 298, -1, 318, 317, 302, -1, 319, 316, 301, -1, 302, 317, 303, -1, 304, 320, 306, -1, 303, 317, 299, -1, 306, 320, 321, -1, 307, 322, 323, -1, 305, 322, 307, -1, 304, 324, 320, -1, 305, 325, 322, -1, 308, 324, 304, -1, 309, 325, 305, -1, 308, 326, 324, -1, 309, 327, 325, -1, 310, 326, 308, -1, 311, 327, 309, -1, 310, 328, 326, -1, 312, 328, 310, -1, 311, 329, 327, -1, 314, 330, 312, -1, 313, 329, 311, -1, 312, 330, 328, -1, 315, 331, 313, -1, 319, 332, 316, -1, 314, 332, 330, -1, 313, 331, 329, -1, 317, 333, 315, -1, 318, 333, 317, -1, 334, 332, 319, -1, 315, 333, 331, -1, 316, 332, 314, -1, 320, 335, 321, -1, 336, 333, 318, -1, 322, 337, 323, -1, 321, 335, 338, -1, 323, 337, 339, -1, 322, 340, 337, -1, 324, 341, 320, -1, 325, 340, 322, -1, 320, 341, 335, -1, 326, 342, 324, -1, 324, 342, 341, -1, 325, 343, 340, -1, 327, 343, 325, -1, 326, 344, 342, -1, 328, 344, 326, -1, 327, 345, 343, -1, 330, 346, 328, -1, 329, 345, 327, -1, 331, 347, 329, -1, 328, 346, 344, -1, 330, 348, 346, -1, 332, 348, 330, -1, 329, 347, 345, -1, 334, 348, 332, -1, 333, 349, 331, -1, 350, 348, 334, -1, 336, 349, 333, -1, 351, 349, 336, -1, 335, 352, 338, -1, 331, 349, 347, -1, 337, 353, 339, -1, 338, 352, 354, -1, 341, 355, 335, -1, 339, 353, 356, -1, 335, 355, 352, -1, 340, 357, 337, -1, 337, 357, 353, -1, 342, 358, 341, -1, 343, 359, 340, -1, 341, 358, 355, -1, 340, 359, 357, -1, 344, 360, 342, -1, 343, 361, 359, -1, 342, 360, 358, -1, 345, 361, 343, -1, 344, 362, 360, -1, 346, 362, 344, -1, 347, 363, 345, -1, 348, 364, 346, -1, 345, 363, 361, -1, 365, 364, 350, -1, 350, 364, 348, -1, 346, 364, 362, -1, 366, 367, 351, -1, 351, 367, 349, -1, 349, 367, 347, -1, 347, 367, 363, -1, 352, 368, 354, -1, 353, 369, 356, -1, 354, 368, 370, -1, 355, 371, 352, -1, 356, 369, 372, -1, 352, 371, 368, -1, 357, 373, 353, -1, 353, 373, 369, -1, 358, 374, 355, -1, 355, 374, 371, -1, 357, 375, 373, -1, 359, 375, 357, -1, 360, 2, 358, -1, 358, 2, 374, -1, 361, 5, 359, -1, 359, 5, 375, -1, 362, 0, 360, -1, 360, 0, 2, -1, 361, 3, 5, -1, 9, 10, 365, -1, 363, 3, 361, -1, 365, 10, 364, -1, 364, 10, 362, -1, 13, 14, 366, -1, 362, 10, 0, -1, 366, 14, 367, -1, 367, 14, 363, -1, 363, 14, 3, -1, 368, 15, 370, -1, 370, 15, 17, -1, 369, 19, 372, -1, 372, 19, 21, -1, 371, 23, 368, -1, 368, 23, 15, -1, 369, 26, 19, -1, 373, 26, 369, -1, 371, 28, 23, -1, 374, 28, 371, -1, 375, 29, 373, -1, 373, 29, 26, -1, 2, 33, 374, -1, 5, 7, 375, -1, 374, 33, 28, -1, 375, 7, 29, -1, 2, 1, 33, -1, 376, 377, 378, -1, 379, 377, 376, -1, 380, 381, 382, -1, 383, 377, 379, -1, 378, 377, 384, -1, 385, 381, 380, -1, 386, 387, 388, -1, 385, 389, 381, -1, 388, 387, 390, -1, 391, 389, 385, -1, 391, 392, 389, -1, 393, 392, 391, -1, 386, 394, 387, -1, 395, 396, 393, -1, 397, 394, 386, -1, 397, 398, 394, -1, 399, 396, 400, -1, 393, 396, 392, -1, 401, 398, 397, -1, 400, 396, 395, -1, 402, 403, 404, -1, 405, 403, 402, -1, 406, 407, 401, -1, 401, 407, 398, -1, 384, 408, 406, -1, 405, 409, 403, -1, 406, 408, 407, -1, 382, 409, 405, -1, 410, 411, 383, -1, 384, 411, 408, -1, 383, 411, 377, -1, 377, 411, 384, -1, 382, 412, 409, -1, 381, 412, 382, -1, 387, 413, 390, -1, 381, 414, 412, -1, 389, 414, 381, -1, 390, 413, 415, -1, 416, 417, 418, -1, 392, 419, 389, -1, 394, 420, 387, -1, 387, 420, 413, -1, 389, 419, 414, -1, 396, 421, 392, -1, 399, 421, 396, -1, 392, 421, 419, -1, 422, 421, 399, -1, 398, 423, 394, -1, 394, 423, 420, -1, 404, 424, 425, -1, 407, 426, 398, -1, 403, 424, 404, -1, 398, 426, 423, -1, 409, 427, 403, -1, 403, 427, 424, -1, 408, 428, 407, -1, 407, 428, 426, -1, 429, 430, 410, -1, 412, 431, 409, -1, 410, 430, 411, -1, 409, 431, 427, -1, 411, 430, 408, -1, 408, 430, 428, -1, 413, 432, 415, -1, 414, 433, 412, -1, 412, 433, 431, -1, 415, 432, 434, -1, 419, 435, 414, -1, 413, 436, 432, -1, 414, 435, 433, -1, 421, 437, 419, -1, 420, 436, 413, -1, 422, 437, 421, -1, 438, 437, 422, -1, 419, 437, 435, -1, 423, 439, 420, -1, 420, 439, 436, -1, 424, 440, 425, -1, 425, 440, 441, -1, 423, 442, 439, -1, 426, 442, 423, -1, 427, 443, 424, -1, 424, 443, 440, -1, 428, 444, 426, -1, 426, 444, 442, -1, 445, 446, 429, -1, 429, 446, 430, -1, 428, 446, 444, -1, 430, 446, 428, -1, 431, 447, 427, -1, 427, 447, 443, -1, 432, 448, 434, -1, 431, 449, 447, -1, 433, 449, 431, -1, 434, 448, 450, -1, 436, 451, 432, -1, 435, 452, 433, -1, 432, 451, 448, -1, 433, 452, 449, -1, 453, 454, 438, -1, 438, 454, 437, -1, 437, 454, 435, -1, 436, 455, 451, -1, 439, 455, 436, -1, 435, 454, 452, -1, 440, 456, 441, -1, 442, 457, 439, -1, 441, 456, 458, -1, 439, 457, 455, -1, 443, 459, 440, -1, 440, 459, 456, -1, 444, 460, 442, -1, 442, 460, 457, -1, 461, 462, 445, -1, 445, 462, 446, -1, 443, 463, 459, -1, 446, 462, 444, -1, 447, 463, 443, -1, 444, 462, 460, -1, 448, 464, 450, -1, 449, 465, 447, -1, 447, 465, 463, -1, 450, 464, 466, -1, 452, 467, 449, -1, 451, 468, 448, -1, 448, 468, 464, -1, 449, 467, 465, -1, 469, 470, 453, -1, 453, 470, 454, -1, 452, 470, 467, -1, 454, 470, 452, -1, 451, 471, 468, -1, 455, 471, 451, -1, 458, 472, 473, -1, 456, 472, 458, -1, 455, 474, 471, -1, 457, 474, 455, -1, 459, 475, 456, -1, 457, 476, 474, -1, 460, 476, 457, -1, 456, 475, 472, -1, 462, 477, 460, -1, 460, 477, 476, -1, 463, 478, 459, -1, 479, 477, 461, -1, 459, 478, 475, -1, 461, 477, 462, -1, 466, 480, 481, -1, 463, 482, 478, -1, 465, 482, 463, -1, 464, 480, 466, -1, 465, 483, 482, -1, 468, 484, 464, -1, 467, 483, 465, -1, 467, 485, 483, -1, 464, 484, 480, -1, 486, 485, 469, -1, 471, 487, 468, -1, 469, 485, 470, -1, 470, 485, 467, -1, 468, 487, 484, -1, 473, 488, 489, -1, 472, 488, 473, -1, 474, 490, 471, -1, 471, 490, 487, -1, 472, 491, 488, -1, 474, 492, 490, -1, 475, 491, 472, -1, 476, 492, 474, -1, 493, 494, 479, -1, 479, 494, 477, -1, 475, 495, 491, -1, 476, 494, 492, -1, 477, 494, 476, -1, 481, 496, 497, -1, 478, 495, 475, -1, 482, 498, 478, -1, 480, 496, 481, -1, 478, 498, 495, -1, 483, 499, 482, -1, 482, 499, 498, -1, 484, 500, 480, -1, 485, 501, 483, -1, 480, 500, 496, -1, 486, 501, 485, -1, 483, 501, 499, -1, 484, 502, 500, -1, 487, 502, 484, -1, 503, 501, 486, -1, 488, 504, 489, -1, 489, 504, 505, -1, 487, 506, 502, -1, 490, 506, 487, -1, 488, 507, 504, -1, 492, 508, 490, -1, 490, 508, 506, -1, 491, 507, 488, -1, 509, 510, 493, -1, 493, 510, 494, -1, 494, 510, 492, -1, 491, 511, 507, -1, 492, 510, 508, -1, 497, 512, 513, -1, 495, 511, 491, -1, 495, 514, 511, -1, 496, 512, 497, -1, 498, 514, 495, -1, 499, 515, 498, -1, 498, 515, 514, -1, 500, 516, 496, -1, 501, 517, 499, -1, 503, 517, 501, -1, 496, 516, 512, -1, 518, 517, 503, -1, 502, 519, 500, -1, 499, 517, 515, -1, 500, 519, 516, -1, 504, 520, 505, -1, 506, 521, 502, -1, 505, 520, 522, -1, 502, 521, 519, -1, 504, 523, 520, -1, 508, 524, 506, -1, 507, 523, 504, -1, 506, 524, 521, -1, 525, 526, 509, -1, 509, 526, 510, -1, 510, 526, 508, -1, 511, 527, 507, -1, 508, 526, 524, -1, 513, 528, 529, -1, 507, 527, 523, -1, 514, 530, 511, -1, 512, 528, 513, -1, 511, 530, 527, -1, 512, 531, 528, -1, 515, 532, 514, -1, 516, 531, 512, -1, 514, 532, 530, -1, 533, 534, 518, -1, 515, 534, 532, -1, 518, 534, 517, -1, 517, 534, 515, -1, 519, 535, 516, -1, 520, 536, 522, -1, 516, 535, 531, -1, 521, 537, 519, -1, 519, 537, 535, -1, 522, 536, 538, -1, 523, 539, 520, -1, 524, 540, 521, -1, 520, 539, 536, -1, 521, 540, 537, -1, 541, 542, 525, -1, 525, 542, 526, -1, 526, 542, 524, -1, 527, 543, 523, -1, 524, 542, 540, -1, 523, 543, 539, -1, 529, 544, 545, -1, 545, 544, 546, -1, 527, 547, 543, -1, 528, 544, 529, -1, 530, 547, 527, -1, 532, 548, 530, -1, 546, 549, 550, -1, 530, 548, 547, -1, 528, 549, 544, -1, 531, 549, 528, -1, 551, 552, 533, -1, 544, 549, 546, -1, 533, 552, 534, -1, 534, 552, 532, -1, 532, 552, 548, -1, 550, 553, 554, -1, 536, 555, 538, -1, 531, 553, 549, -1, 535, 553, 531, -1, 538, 555, 556, -1, 549, 553, 550, -1, 554, 557, 558, -1, 536, 559, 555, -1, 537, 557, 535, -1, 539, 559, 536, -1, 553, 557, 554, -1, 535, 557, 553, -1, 558, 560, 561, -1, 543, 562, 539, -1, 540, 560, 537, -1, 539, 562, 559, -1, 537, 560, 557, -1, 547, 563, 543, -1, 557, 560, 558, -1, 540, 564, 560, -1, 561, 564, 565, -1, 565, 564, 566, -1, 566, 564, 567, -1, 543, 563, 562, -1, 567, 564, 541, -1, 560, 564, 561, -1, 542, 564, 540, -1, 548, 568, 547, -1, 541, 564, 542, -1, 547, 568, 563, -1, 569, 570, 551, -1, 551, 570, 552, -1, 552, 570, 548, -1, 548, 570, 568, -1, 556, 571, 572, -1, 555, 571, 556, -1, 559, 573, 555, -1, 555, 573, 571, -1, 559, 574, 573, -1, 562, 574, 559, -1, 562, 575, 574, -1, 563, 575, 562, -1, 563, 576, 575, -1, 568, 576, 563, -1, 545, 546, 577, -1, 568, 578, 576, -1, 579, 578, 569, -1, 569, 578, 570, -1, 570, 578, 568, -1, 571, 580, 572, -1, 572, 580, 581, -1, 573, 582, 571, -1, 571, 582, 580, -1, 574, 583, 573, -1, 573, 583, 582, -1, 584, 585, 586, -1, 575, 587, 574, -1, 574, 587, 583, -1, 586, 585, 588, -1, 576, 589, 575, -1, 584, 590, 585, -1, 575, 589, 587, -1, 591, 590, 584, -1, 578, 592, 576, -1, 579, 592, 578, -1, 576, 592, 589, -1, 593, 592, 579, -1, 594, 595, 591, -1, 580, 596, 581, -1, 591, 595, 590, -1, 594, 597, 595, -1, 581, 596, 598, -1, 599, 597, 594, -1, 582, 600, 580, -1, 580, 600, 596, -1, 599, 601, 597, -1, 602, 601, 599, -1, 417, 603, 418, -1, 418, 603, 602, -1, 602, 603, 601, -1, 582, 604, 600, -1, 583, 604, 582, -1, 588, 605, 606, -1, 587, 607, 583, -1, 585, 605, 588, -1, 583, 607, 604, -1, 585, 608, 605, -1, 589, 609, 587, -1, 587, 609, 607, -1, 590, 608, 585, -1, 610, 611, 593, -1, 592, 611, 589, -1, 593, 611, 592, -1, 590, 612, 608, -1, 595, 612, 590, -1, 589, 611, 609, -1, 597, 613, 595, -1, 595, 613, 612, -1, 596, 614, 598, -1, 598, 614, 615, -1, 600, 616, 596, -1, 597, 617, 613, -1, 601, 617, 597, -1, 596, 616, 614, -1, 601, 618, 617, -1, 619, 618, 417, -1, 417, 618, 603, -1, 600, 620, 616, -1, 603, 618, 601, -1, 604, 620, 600, -1, 605, 621, 606, -1, 606, 621, 622, -1, 607, 623, 604, -1, 608, 624, 605, -1, 604, 623, 620, -1, 605, 624, 621, -1, 609, 625, 607, -1, 607, 625, 623, -1, 612, 626, 608, -1, 627, 628, 610, -1, 610, 628, 611, -1, 611, 628, 609, -1, 608, 626, 624, -1, 609, 628, 625, -1, 612, 629, 626, -1, 614, 630, 615, -1, 613, 629, 612, -1, 615, 630, 631, -1, 614, 632, 630, -1, 613, 633, 629, -1, 617, 633, 613, -1, 616, 632, 614, -1, 617, 634, 633, -1, 618, 634, 617, -1, 619, 634, 618, -1, 635, 634, 619, -1, 620, 636, 616, -1, 616, 636, 632, -1, 621, 637, 622, -1, 622, 637, 638, -1, 623, 639, 620, -1, 620, 639, 636, -1, 625, 640, 623, -1, 624, 641, 621, -1, 623, 640, 639, -1, 621, 641, 637, -1, 642, 643, 627, -1, 627, 643, 628, -1, 626, 644, 624, -1, 625, 643, 640, -1, 628, 643, 625, -1, 624, 644, 641, -1, 630, 645, 631, -1, 626, 646, 644, -1, 629, 646, 626, -1, 631, 645, 647, -1, 633, 648, 629, -1, 632, 649, 630, -1, 629, 648, 646, -1, 630, 649, 645, -1, 634, 650, 633, -1, 635, 650, 634, -1, 651, 650, 635, -1, 632, 652, 649, -1, 633, 650, 648, -1, 636, 652, 632, -1, 637, 653, 638, -1, 638, 653, 654, -1, 639, 655, 636, -1, 636, 655, 652, -1, 641, 656, 637, -1, 640, 657, 639, -1, 637, 656, 653, -1, 639, 657, 655, -1, 658, 659, 642, -1, 642, 659, 643, -1, 640, 659, 657, -1, 644, 660, 641, -1, 643, 659, 640, -1, 641, 660, 656, -1, 646, 661, 644, -1, 647, 662, 663, -1, 644, 661, 660, -1, 645, 662, 647, -1, 648, 664, 646, -1, 645, 665, 662, -1, 646, 664, 661, -1, 651, 666, 650, -1, 649, 665, 645, -1, 667, 666, 651, -1, 648, 666, 664, -1, 650, 666, 648, -1, 649, 668, 665, -1, 653, 669, 654, -1, 652, 668, 649, -1, 655, 670, 652, -1, 654, 669, 671, -1, 652, 670, 668, -1, 656, 672, 653, -1, 653, 672, 669, -1, 657, 673, 655, -1, 655, 673, 670, -1, 659, 674, 657, -1, 656, 675, 672, -1, 660, 675, 656, -1, 676, 674, 658, -1, 657, 674, 673, -1, 658, 674, 659, -1, 662, 677, 663, -1, 663, 677, 678, -1, 661, 679, 660, -1, 660, 679, 675, -1, 664, 680, 661, -1, 662, 681, 677, -1, 661, 680, 679, -1, 667, 682, 666, -1, 665, 681, 662, -1, 664, 682, 680, -1, 666, 682, 664, -1, 683, 682, 667, -1, 669, 684, 671, -1, 665, 685, 681, -1, 668, 685, 665, -1, 670, 686, 668, -1, 671, 684, 687, -1, 668, 686, 685, -1, 672, 688, 669, -1, 673, 689, 670, -1, 669, 688, 684, -1, 670, 689, 686, -1, 674, 690, 673, -1, 675, 691, 672, -1, 676, 690, 674, -1, 672, 691, 688, -1, 692, 690, 676, -1, 673, 690, 689, -1, 677, 693, 678, -1, 679, 694, 675, -1, 675, 694, 691, -1, 678, 693, 695, -1, 679, 696, 694, -1, 677, 697, 693, -1, 680, 696, 679, -1, 683, 698, 682, -1, 681, 697, 677, -1, 680, 698, 696, -1, 682, 698, 680, -1, 685, 699, 681, -1, 700, 698, 683, -1, 681, 699, 697, -1, 684, 701, 687, -1, 686, 702, 685, -1, 687, 701, 703, -1, 688, 704, 684, -1, 685, 702, 699, -1, 686, 705, 702, -1, 689, 705, 686, -1, 684, 704, 701, -1, 706, 707, 692, -1, 692, 707, 690, -1, 691, 708, 688, -1, 690, 707, 689, -1, 689, 707, 705, -1, 688, 708, 704, -1, 693, 709, 695, -1, 694, 710, 691, -1, 691, 710, 708, -1, 695, 709, 711, -1, 696, 712, 694, -1, 697, 713, 693, -1, 693, 713, 709, -1, 694, 712, 710, -1, 698, 714, 696, -1, 700, 714, 698, -1, 696, 714, 712, -1, 699, 715, 697, -1, 716, 714, 700, -1, 697, 715, 713, -1, 701, 717, 703, -1, 702, 718, 699, -1, 703, 717, 719, -1, 699, 718, 715, -1, 704, 720, 701, -1, 701, 720, 717, -1, 705, 721, 702, -1, 702, 721, 718, -1, 708, 722, 704, -1, 723, 724, 706, -1, 706, 724, 707, -1, 707, 724, 705, -1, 705, 724, 721, -1, 704, 722, 720, -1, 710, 725, 708, -1, 709, 726, 711, -1, 708, 725, 722, -1, 711, 726, 727, -1, 713, 728, 709, -1, 712, 729, 710, -1, 710, 729, 725, -1, 709, 728, 726, -1, 730, 731, 716, -1, 714, 731, 712, -1, 716, 731, 714, -1, 712, 731, 729, -1, 713, 732, 728, -1, 715, 732, 713, -1, 717, 733, 719, -1, 719, 733, 734, -1, 718, 735, 715, -1, 720, 736, 717, -1, 715, 735, 732, -1, 721, 737, 718, -1, 717, 736, 733, -1, 718, 737, 735, -1, 738, 739, 723, -1, 722, 740, 720, -1, 721, 739, 737, -1, 723, 739, 724, -1, 724, 739, 721, -1, 720, 740, 736, -1, 726, 741, 727, -1, 725, 742, 722, -1, 727, 741, 743, -1, 722, 742, 740, -1, 726, 744, 741, -1, 729, 745, 725, -1, 728, 744, 726, -1, 725, 745, 742, -1, 746, 747, 730, -1, 730, 747, 731, -1, 728, 748, 744, -1, 731, 747, 729, -1, 729, 747, 745, -1, 732, 748, 728, -1, 733, 749, 734, -1, 734, 749, 750, -1, 732, 751, 748, -1, 735, 751, 732, -1, 735, 378, 751, -1, 733, 380, 749, -1, 736, 380, 733, -1, 737, 378, 735, -1, 737, 376, 378, -1, 379, 376, 738, -1, 738, 376, 739, -1, 740, 385, 736, -1, 739, 376, 737, -1, 736, 385, 380, -1, 743, 386, 388, -1, 742, 391, 740, -1, 740, 391, 385, -1, 741, 386, 743, -1, 745, 393, 742, -1, 744, 397, 741, -1, 742, 393, 391, -1, 741, 397, 386, -1, 400, 395, 746, -1, 746, 395, 747, -1, 748, 401, 744, -1, 745, 395, 393, -1, 747, 395, 745, -1, 749, 405, 750, -1, 744, 401, 397, -1, 750, 405, 402, -1, 751, 406, 748, -1, 748, 406, 401, -1, 378, 384, 751, -1, 749, 382, 405, -1, 751, 384, 406, -1, 380, 382, 749, -1, 752, 753, 754, -1, 752, 755, 753, -1, 756, 757, 758, -1, 756, 759, 757, -1, 760, 754, 761, -1, 760, 752, 754, -1, 762, 758, 763, -1, 762, 756, 758, -1, 764, 761, 765, -1, 766, 767, 768, -1, 764, 760, 761, -1, 766, 769, 767, -1, 770, 763, 771, -1, 770, 762, 763, -1, 772, 765, 773, -1, 774, 766, 768, -1, 774, 768, 775, -1, 772, 764, 765, -1, 776, 771, 777, -1, 776, 770, 771, -1, 778, 773, 779, -1, 780, 775, 781, -1, 778, 772, 773, -1, 780, 774, 775, -1, 782, 777, 783, -1, 782, 776, 777, -1, 784, 779, 785, -1, 784, 778, 779, -1, 786, 781, 787, -1, 786, 780, 781, -1, 788, 783, 789, -1, 788, 782, 783, -1, 790, 785, 791, -1, 792, 787, 793, -1, 790, 784, 785, -1, 792, 786, 787, -1, 794, 789, 795, -1, 794, 788, 789, -1, 796, 790, 791, -1, 797, 795, 798, -1, 797, 794, 795, -1, 796, 791, 799, -1, 800, 793, 801, -1, 800, 792, 793, -1, 802, 796, 799, -1, 802, 799, 803, -1, 804, 801, 805, -1, 804, 800, 801, -1, 806, 802, 803, -1, 806, 803, 807, -1, 808, 805, 809, -1, 808, 804, 805, -1, 810, 806, 807, -1, 810, 807, 811, -1, 812, 809, 813, -1, 812, 808, 809, -1, 814, 810, 811, -1, 814, 811, 815, -1, 816, 813, 817, -1, 816, 812, 813, -1, 818, 814, 815, -1, 818, 815, 819, -1, 820, 817, 821, -1, 820, 816, 817, -1, 822, 818, 819, -1, 822, 819, 823, -1, 824, 821, 825, -1, 824, 820, 821, -1, 826, 822, 823, -1, 826, 823, 827, -1, 828, 825, 829, -1, 828, 824, 825, -1, 830, 827, 831, -1, 832, 829, 833, -1, 830, 826, 827, -1, 832, 828, 829, -1, 834, 831, 835, -1, 834, 830, 831, -1, 836, 833, 837, -1, 836, 832, 833, -1, 838, 835, 839, -1, 838, 834, 835, -1, 840, 837, 841, -1, 840, 836, 837, -1, 842, 839, 843, -1, 842, 838, 839, -1, 844, 841, 845, -1, 844, 840, 841, -1, 846, 843, 847, -1, 846, 842, 843, -1, 755, 845, 753, -1, 755, 844, 845, -1, 759, 847, 757, -1, 759, 846, 847, -1, 848, 849, 850, -1, 848, 851, 849, -1, 852, 850, 853, -1, 852, 848, 850, -1, 854, 853, 855, -1, 854, 852, 853, -1, 856, 855, 857, -1, 856, 854, 855, -1, 858, 857, 859, -1, 858, 856, 857, -1, 860, 859, 861, -1, 860, 858, 859, -1, 862, 861, 863, -1, 862, 860, 861, -1, 864, 863, 865, -1, 864, 862, 863, -1, 866, 865, 867, -1, 866, 864, 865, -1, 868, 867, 869, -1, 868, 866, 867, -1, 870, 869, 871, -1, 870, 868, 869, -1, 872, 871, 873, -1, 872, 873, 874, -1, 872, 870, 871, -1, 875, 872, 874, -1, 876, 877, 878, -1, 876, 879, 877, -1, 880, 878, 881, -1, 880, 876, 878, -1, 882, 880, 881, -1, 883, 881, 884, -1, 883, 882, 881, -1, 885, 883, 884, -1, 886, 884, 887, -1, 886, 885, 884, -1, 888, 887, 889, -1, 888, 886, 887, -1, 890, 889, 891, -1, 890, 888, 889, -1, 892, 891, 893, -1, 892, 890, 891, -1, 894, 893, 895, -1, 894, 892, 893, -1, 896, 895, 897, -1, 896, 894, 895, -1, 898, 897, 899, -1, 898, 896, 897, -1, 900, 898, 899, -1, 901, 899, 902, -1, 901, 900, 899, -1, 903, 902, 904, -1, 903, 901, 902, -1, 905, 904, 906, -1, 905, 903, 904, -1, 907, 906, 908, -1, 907, 905, 906, -1, 909, 907, 908, -1, 910, 902, 899, -1, 910, 904, 902, -1, 910, 911, 868, -1, 910, 899, 911, -1, 912, 870, 872, -1, 912, 872, 875, -1, 912, 906, 904, -1, 912, 910, 870, -1, 912, 904, 910, -1, 913, 878, 877, -1, 913, 877, 851, -1, 913, 851, 914, -1, 913, 914, 878, -1, 915, 875, 908, -1, 915, 908, 906, -1, 915, 912, 875, -1, 915, 906, 912, -1, 914, 851, 848, -1, 914, 848, 852, -1, 914, 881, 878, -1, 916, 852, 854, -1, 916, 884, 881, -1, 916, 914, 852, -1, 916, 881, 914, -1, 917, 854, 856, -1, 917, 856, 858, -1, 917, 887, 884, -1, 917, 889, 887, -1, 917, 916, 854, -1, 917, 884, 916, -1, 918, 858, 860, -1, 918, 891, 889, -1, 918, 917, 858, -1, 918, 889, 917, -1, 919, 860, 862, -1, 919, 893, 891, -1, 919, 895, 893, -1, 919, 891, 918, -1, 919, 918, 860, -1, 920, 862, 864, -1, 920, 897, 895, -1, 920, 919, 862, -1, 920, 895, 919, -1, 911, 864, 866, -1, 911, 866, 868, -1, 911, 899, 897, -1, 911, 897, 920, -1, 911, 920, 864, -1, 910, 868, 870, -1, 921, 922, 923, -1, 924, 925, 926, -1, 927, 928, 929, -1, 930, 931, 932, -1, 927, 929, 933, -1, 930, 934, 931, -1, 935, 934, 930, -1, 936, 927, 933, -1, 935, 937, 934, -1, 936, 933, 938, -1, 939, 940, 937, -1, 939, 937, 935, -1, 941, 927, 936, -1, 941, 942, 927, -1, 943, 940, 939, -1, 943, 944, 940, -1, 945, 938, 946, -1, 945, 946, 947, -1, 945, 936, 938, -1, 945, 941, 936, -1, 948, 949, 925, -1, 950, 947, 951, -1, 952, 932, 953, -1, 950, 942, 941, -1, 952, 930, 932, -1, 950, 945, 947, -1, 950, 954, 942, -1, 950, 941, 945, -1, 955, 956, 957, -1, 955, 958, 959, -1, 960, 930, 952, -1, 955, 957, 958, -1, 960, 935, 930, -1, 961, 955, 959, -1, 961, 956, 955, -1, 962, 957, 956, -1, 963, 939, 935, -1, 962, 964, 957, -1, 963, 935, 960, -1, 962, 946, 964, -1, 965, 961, 959, -1, 966, 943, 939, -1, 965, 956, 961, -1, 965, 967, 956, -1, 965, 959, 968, -1, 965, 968, 967, -1, 969, 946, 962, -1, 966, 939, 963, -1, 969, 947, 946, -1, 969, 951, 947, -1, 970, 949, 971, -1, 970, 972, 949, -1, 973, 969, 962, -1, 974, 956, 967, -1, 974, 967, 975, -1, 976, 977, 978, -1, 976, 979, 977, -1, 980, 974, 975, -1, 980, 975, 981, -1, 982, 979, 976, -1, 982, 983, 979, -1, 984, 974, 980, -1, 984, 985, 974, -1, 986, 980, 981, -1, 986, 981, 987, -1, 986, 984, 980, -1, 986, 987, 988, -1, 989, 990, 983, -1, 989, 983, 982, -1, 991, 985, 984, -1, 991, 992, 985, -1, 991, 984, 986, -1, 991, 986, 988, -1, 991, 988, 993, -1, 994, 995, 990, -1, 994, 990, 989, -1, 996, 963, 960, -1, 997, 976, 978, -1, 998, 999, 1000, -1, 998, 1000, 966, -1, 1001, 995, 994, -1, 998, 1002, 999, -1, 998, 963, 996, -1, 1001, 1003, 995, -1, 998, 996, 1004, -1, 998, 966, 963, -1, 1005, 976, 997, -1, 1005, 982, 976, -1, 1006, 1003, 1001, -1, 1006, 1007, 1008, -1, 1006, 1008, 1003, -1, 1009, 978, 1010, -1, 1009, 997, 978, -1, 1011, 983, 990, -1, 1012, 982, 1005, -1, 1013, 1014, 1002, -1, 1013, 1015, 1014, -1, 1012, 989, 982, -1, 1013, 995, 1015, -1, 1016, 997, 1009, -1, 1013, 1017, 1011, -1, 1013, 1011, 990, -1, 1013, 990, 995, -1, 1018, 1019, 972, -1, 1016, 1005, 997, -1, 1020, 994, 989, -1, 1018, 1021, 1022, -1, 1018, 972, 1021, -1, 1020, 989, 1012, -1, 1023, 1022, 999, -1, 1023, 999, 1002, -1, 1023, 1019, 1018, -1, 1023, 1024, 1019, -1, 1023, 1002, 1014, -1, 1023, 1014, 1024, -1, 1023, 1018, 1022, -1, 1025, 1012, 1005, -1, 1026, 1027, 1028, -1, 1025, 1005, 1016, -1, 1026, 1029, 1027, -1, 1026, 1030, 1029, -1, 1031, 1001, 994, -1, 1032, 1033, 1030, -1, 1031, 994, 1020, -1, 1032, 1034, 1033, -1, 1032, 1030, 1026, -1, 1035, 1020, 1012, -1, 1035, 1012, 1025, -1, 1036, 1032, 1026, -1, 1037, 1006, 1001, -1, 1037, 1007, 1006, -1, 1037, 1001, 1031, -1, 1037, 1038, 1007, -1, 1039, 1009, 1010, -1, 1040, 1031, 1020, -1, 1040, 1020, 1035, -1, 1041, 1028, 1042, -1, 1041, 1042, 1043, -1, 1041, 1043, 1044, -1, 1045, 1016, 1009, -1, 1045, 1009, 1039, -1, 1046, 1037, 1031, -1, 1047, 1041, 1044, -1, 1046, 1031, 1040, -1, 1046, 1038, 1037, -1, 1047, 1048, 1041, -1, 1047, 1044, 1049, -1, 1050, 1025, 1016, -1, 1047, 1049, 1051, -1, 1052, 1053, 1054, -1, 1052, 1044, 1053, -1, 1050, 1016, 1045, -1, 1052, 1054, 1055, -1, 1056, 1010, 1057, -1, 1056, 1039, 1010, -1, 1058, 1044, 1052, -1, 1058, 1049, 1044, -1, 1058, 1051, 1049, -1, 1059, 1035, 1025, -1, 1059, 1025, 1050, -1, 1060, 1058, 1052, -1, 1061, 1039, 1056, -1, 1061, 1045, 1039, -1, 1062, 1063, 1064, -1, 1062, 1055, 1063, -1, 1065, 1040, 1035, -1, 1065, 1035, 1059, -1, 1066, 1050, 1045, -1, 1066, 1045, 1061, -1, 1067, 1046, 1040, -1, 1067, 1038, 1046, -1, 1067, 1040, 1065, -1, 1067, 1068, 1038, -1, 1069, 1070, 1062, -1, 1069, 1062, 1064, -1, 1071, 1059, 1050, -1, 1069, 1064, 1072, -1, 1071, 1050, 1066, -1, 1073, 1074, 1075, -1, 1073, 1069, 1072, -1, 1076, 1056, 1057, -1, 1073, 1072, 1074, -1, 1077, 1065, 1059, -1, 1078, 1079, 1070, -1, 1078, 1069, 1073, -1, 1077, 1059, 1071, -1, 1078, 1070, 1069, -1, 1078, 1073, 1075, -1, 1078, 1075, 1080, -1, 1081, 1056, 1076, -1, 1082, 1083, 1084, -1, 1081, 1061, 1056, -1, 1082, 1074, 1085, -1, 1082, 1085, 1083, -1, 1086, 1075, 1074, -1, 1087, 1067, 1065, -1, 1087, 1068, 1067, -1, 1087, 1065, 1077, -1, 1086, 1074, 1082, -1, 1086, 1080, 1075, -1, 1088, 1066, 1061, -1, 1088, 1061, 1081, -1, 1089, 1086, 1082, -1, 1090, 1057, 1091, -1, 1090, 1076, 1057, -1, 1092, 1071, 1066, -1, 1093, 1084, 1094, -1, 1093, 1094, 1095, -1, 1092, 1066, 1088, -1, 1096, 1081, 1076, -1, 1096, 1076, 1090, -1, 1097, 1093, 1095, -1, 1098, 1077, 1071, -1, 1097, 1095, 1099, -1, 1098, 1071, 1092, -1, 1100, 1081, 1096, -1, 1101, 1093, 1097, -1, 1100, 1088, 1081, -1, 1101, 1102, 1093, -1, 1103, 1077, 1098, -1, 1103, 1104, 1068, -1, 1103, 1068, 1087, -1, 1103, 1087, 1077, -1, 1105, 1099, 1106, -1, 1105, 1106, 1107, -1, 1105, 1101, 1097, -1, 1105, 1097, 1099, -1, 1108, 1090, 1091, -1, 1109, 1107, 1110, -1, 1109, 1102, 1101, -1, 1111, 1088, 1100, -1, 1109, 1112, 1102, -1, 1109, 1101, 1105, -1, 1109, 1105, 1107, -1, 1113, 1114, 1115, -1, 1113, 1116, 1114, -1, 1111, 1092, 1088, -1, 1117, 1096, 1090, -1, 1113, 1115, 1118, -1, 1119, 1116, 1113, -1, 1117, 1090, 1108, -1, 1120, 1098, 1092, -1, 1119, 1113, 1118, -1, 1121, 1114, 1116, -1, 1120, 1092, 1111, -1, 1122, 1096, 1117, -1, 1121, 1106, 1123, -1, 1121, 1123, 1114, -1, 1124, 1125, 1126, -1, 1124, 1126, 1116, -1, 1122, 1100, 1096, -1, 1124, 1118, 1125, -1, 1124, 1116, 1119, -1, 1124, 1119, 1118, -1, 1127, 1103, 1098, -1, 1128, 1106, 1121, -1, 1127, 1104, 1103, -1, 1128, 1107, 1106, -1, 1127, 1098, 1120, -1, 1128, 1110, 1107, -1, 1129, 1130, 1131, -1, 1132, 1091, 1133, -1, 1132, 1108, 1091, -1, 1134, 1128, 1121, -1, 1135, 1100, 1122, -1, 1136, 1126, 1137, -1, 1135, 1111, 1100, -1, 1136, 1116, 1126, -1, 1138, 1108, 1132, -1, 1138, 1117, 1108, -1, 1139, 1111, 1135, -1, 1140, 1137, 1141, -1, 1139, 1120, 1111, -1, 1140, 1136, 1137, -1, 1142, 1122, 1117, -1, 1142, 1117, 1138, -1, 1143, 1104, 1127, -1, 1143, 1127, 1120, -1, 1144, 1145, 1136, -1, 1146, 1147, 1148, -1, 1143, 1120, 1139, -1, 1144, 1136, 1140, -1, 1146, 1149, 1147, -1, 1143, 1150, 1104, -1, 1151, 1132, 1133, -1, 1152, 1149, 1146, -1, 1153, 1135, 1122, -1, 1154, 1155, 1156, -1, 1152, 1157, 1149, -1, 1153, 1122, 1142, -1, 1154, 1140, 1141, -1, 1154, 1144, 1140, -1, 1154, 1141, 1155, -1, 1158, 1156, 1159, -1, 1160, 1157, 1152, -1, 1158, 1145, 1144, -1, 1161, 1138, 1132, -1, 1158, 1154, 1156, -1, 1160, 1162, 1157, -1, 1158, 1163, 1145, -1, 1161, 1132, 1151, -1, 1158, 1144, 1154, -1, 1164, 1165, 1166, -1, 1167, 1139, 1135, -1, 1164, 1168, 1169, -1, 1167, 1135, 1153, -1, 1164, 1170, 1165, -1, 1164, 1169, 1170, -1, 1164, 1171, 1168, -1, 1172, 1162, 1160, -1, 1164, 1166, 1171, -1, 1172, 1173, 1162, -1, 1174, 1175, 1176, -1, 1174, 1166, 1165, -1, 1174, 1176, 1166, -1, 1177, 1142, 1138, -1, 1178, 1173, 1172, -1, 1177, 1138, 1161, -1, 1174, 1179, 1175, -1, 1180, 1165, 1170, -1, 1178, 1181, 1173, -1, 1180, 1182, 1183, -1, 1184, 1185, 1181, -1, 1180, 1170, 1182, -1, 1184, 1186, 1185, -1, 1187, 1143, 1139, -1, 1180, 1188, 1179, -1, 1187, 1150, 1143, -1, 1180, 1183, 1188, -1, 1184, 1181, 1178, -1, 1180, 1174, 1165, -1, 1184, 1189, 1186, -1, 1187, 1139, 1167, -1, 1180, 1179, 1174, -1, 1190, 1191, 1192, -1, 1190, 1192, 1193, -1, 1194, 1133, 1195, -1, 1190, 1196, 1197, -1, 1194, 1151, 1133, -1, 1190, 1193, 1198, -1, 1199, 1148, 1200, -1, 1190, 1201, 1196, -1, 1190, 1198, 1201, -1, 1199, 1146, 1148, -1, 1190, 1197, 1191, -1, 1202, 1183, 1203, -1, 1204, 1153, 1142, -1, 1202, 1203, 1197, -1, 1205, 1146, 1199, -1, 1202, 1197, 1196, -1, 1204, 1142, 1177, -1, 1205, 1152, 1146, -1, 1202, 1188, 1183, -1, 1206, 1202, 1196, -1, 1206, 1188, 1202, -1, 1206, 1207, 1208, -1, 1209, 1151, 1194, -1, 1206, 1196, 1201, -1, 1209, 1161, 1151, -1, 1206, 1210, 1207, -1, 1206, 1201, 1210, -1, 1206, 1208, 1188, -1, 1211, 923, 928, -1, 1211, 928, 927, -1, 1211, 921, 923, -1, 1212, 1152, 1205, -1, 1211, 1213, 921, -1, 1214, 1167, 1153, -1, 1211, 927, 942, -1, 1212, 1160, 1152, -1, 1211, 954, 1213, -1, 1214, 1153, 1204, -1, 1211, 942, 954, -1, 1215, 1160, 1212, -1, 1216, 1207, 922, -1, 1216, 1208, 1207, -1, 1216, 922, 921, -1, 1215, 1172, 1160, -1, 1217, 1177, 1161, -1, 1216, 921, 1213, -1, 1218, 1208, 1216, -1, 1217, 1161, 1209, -1, 1218, 1216, 1213, -1, 1218, 951, 1219, -1, 1220, 1172, 1215, -1, 1218, 1219, 1208, -1, 1218, 1213, 954, -1, 1220, 1178, 1172, -1, 1218, 950, 951, -1, 1221, 1150, 1187, -1, 1218, 954, 950, -1, 1221, 1187, 1167, -1, 1222, 956, 974, -1, 1221, 1167, 1214, -1, 1222, 973, 962, -1, 1223, 1184, 1178, -1, 1222, 1224, 973, -1, 1223, 1178, 1220, -1, 1221, 1225, 1150, -1, 1222, 974, 985, -1, 1223, 1226, 1189, -1, 1222, 992, 1224, -1, 1227, 1194, 1195, -1, 1222, 985, 992, -1, 1223, 1189, 1184, -1, 1222, 962, 956, -1, 1228, 1199, 1200, -1, 1229, 951, 969, -1, 1229, 969, 973, -1, 1229, 973, 1224, -1, 1230, 1204, 1177, -1, 1230, 1177, 1217, -1, 1229, 1219, 951, -1, 1228, 1200, 1231, -1, 1232, 1229, 1224, -1, 1232, 1219, 1229, -1, 1232, 991, 993, -1, 1232, 1224, 992, -1, 1232, 992, 991, -1, 1233, 1205, 1199, -1, 1232, 993, 1234, -1, 1235, 1194, 1227, -1, 1232, 1234, 1219, -1, 1233, 1199, 1228, -1, 1235, 1209, 1194, -1, 1236, 1237, 1004, -1, 1236, 960, 952, -1, 1236, 1004, 996, -1, 1238, 1205, 1233, -1, 1239, 1204, 1230, -1, 1236, 952, 953, -1, 1239, 1214, 1204, -1, 1236, 996, 960, -1, 1240, 953, 977, -1, 1240, 1237, 1236, -1, 1238, 1212, 1205, -1, 1241, 1217, 1209, -1, 1242, 1212, 1238, -1, 1240, 1236, 953, -1, 1242, 1215, 1212, -1, 1243, 1240, 977, -1, 1241, 1209, 1235, -1, 1243, 977, 979, -1, 1243, 1017, 1237, -1, 1243, 1011, 1017, -1, 1243, 1237, 1240, -1, 1244, 1214, 1239, -1, 1243, 983, 1011, -1, 1244, 1221, 1214, -1, 1243, 979, 983, -1, 1244, 1225, 1221, -1, 1245, 1004, 1237, -1, 1246, 1215, 1242, -1, 1245, 998, 1004, -1, 1246, 1220, 1215, -1, 1245, 1013, 1002, -1, 1245, 1237, 1017, -1, 1247, 1230, 1217, -1, 1245, 1017, 1013, -1, 1245, 1002, 998, -1, 1248, 1249, 1226, -1, 1250, 1028, 1041, -1, 1250, 1251, 1036, -1, 1250, 1036, 1026, -1, 1252, 1228, 1231, -1, 1247, 1217, 1241, -1, 1250, 1026, 1028, -1, 1250, 1041, 1048, -1, 1250, 1048, 1251, -1, 1253, 1195, 1254, -1, 1255, 1032, 1036, -1, 1255, 1256, 1034, -1, 1253, 1227, 1195, -1, 1255, 1036, 1251, -1, 1252, 1231, 1257, -1, 1255, 1034, 1032, -1, 1258, 1233, 1228, -1, 1259, 1239, 1230, -1, 1260, 1255, 1251, -1, 1258, 1228, 1252, -1, 1260, 1256, 1255, -1, 1260, 1047, 1051, -1, 1260, 1251, 1048, -1, 1260, 1051, 1261, -1, 1259, 1230, 1247, -1, 1260, 1048, 1047, -1, 1260, 1261, 1256, -1, 1262, 1227, 1253, -1, 1263, 1079, 1264, -1, 1263, 1062, 1070, -1, 1265, 1238, 1233, -1, 1263, 1070, 1079, -1, 1263, 1060, 1052, -1, 1262, 1235, 1227, -1, 1263, 1264, 1060, -1, 1263, 1052, 1055, -1, 1263, 1055, 1062, -1, 1266, 1261, 1051, -1, 1267, 1239, 1259, -1, 1266, 1060, 1264, -1, 1265, 1233, 1258, -1, 1267, 1268, 1225, -1, 1266, 1058, 1060, -1, 1269, 1242, 1238, -1, 1267, 1244, 1239, -1, 1266, 1051, 1058, -1, 1267, 1225, 1244, -1, 1270, 1264, 1079, -1, 1270, 1080, 1271, -1, 1272, 1235, 1262, -1, 1270, 1079, 1078, -1, 1270, 1078, 1080, -1, 1269, 1238, 1265, -1, 1270, 1266, 1264, -1, 1273, 1242, 1269, -1, 1270, 1271, 1261, -1, 1272, 1241, 1235, -1, 1270, 1261, 1266, -1, 1274, 1082, 1084, -1, 1274, 1089, 1082, -1, 1273, 1246, 1242, -1, 1274, 1084, 1093, -1, 1274, 1275, 1089, -1, 1274, 1093, 1102, -1, 1276, 1277, 1249, -1, 1278, 1253, 1254, -1, 1274, 1112, 1275, -1, 1279, 1252, 1257, -1, 1274, 1102, 1112, -1, 1280, 1247, 1241, -1, 1281, 1271, 1080, -1, 1281, 1080, 1086, -1, 1281, 1086, 1089, -1, 1279, 1257, 1282, -1, 1280, 1241, 1272, -1, 1281, 1089, 1275, -1, 1283, 1109, 1110, -1, 1283, 1110, 1284, -1, 1285, 1252, 1279, -1, 1283, 1271, 1281, -1, 1283, 1275, 1112, -1, 1286, 1253, 1278, -1, 1283, 1112, 1109, -1, 1283, 1281, 1275, -1, 1283, 1284, 1271, -1, 1286, 1262, 1253, -1, 1287, 1121, 1116, -1, 1287, 1136, 1145, -1, 1287, 1134, 1121, -1, 1285, 1258, 1252, -1, 1288, 1259, 1247, -1, 1287, 1116, 1136, -1, 1287, 1289, 1134, -1, 1288, 1247, 1280, -1, 1287, 1163, 1289, -1, 1290, 1258, 1285, -1, 1287, 1145, 1163, -1, 1290, 1265, 1258, -1, 1291, 1110, 1128, -1, 1291, 1284, 1110, -1, 1292, 1272, 1262, -1, 1291, 1128, 1134, -1, 1292, 1262, 1286, -1, 1291, 1134, 1289, -1, 1293, 1159, 1294, -1, 1293, 1291, 1289, -1, 1295, 1269, 1265, -1, 1293, 1158, 1159, -1, 1296, 1267, 1259, -1, 1293, 1289, 1163, -1, 1295, 1265, 1290, -1, 1296, 1268, 1267, -1, 1293, 1163, 1158, -1, 1296, 1259, 1288, -1, 1293, 1294, 1284, -1, 1293, 1284, 1291, -1, 1297, 1272, 1292, -1, 1298, 1277, 1299, -1, 1298, 1300, 1277, -1, 1297, 1280, 1272, -1, 1301, 1254, 1302, -1, 1303, 1282, 1304, -1, 1301, 1278, 1254, -1, 1303, 1279, 1282, -1, 1305, 1288, 1280, -1, 1305, 1280, 1297, -1, 1306, 1279, 1303, -1, 1306, 1285, 1279, -1, 1307, 1286, 1278, -1, 1307, 1278, 1301, -1, 1308, 1303, 1304, -1, 1308, 1304, 1309, -1, 1310, 1288, 1305, -1, 1311, 1290, 1285, -1, 1310, 1268, 1296, -1, 1310, 1296, 1288, -1, 1311, 1285, 1306, -1, 1310, 1312, 1268, -1, 1313, 1301, 1302, -1, 1314, 1303, 1308, -1, 1315, 1292, 1286, -1, 1314, 1306, 1303, -1, 1315, 1286, 1307, -1, 1316, 1290, 1311, -1, 1317, 1307, 1301, -1, 1316, 1295, 1290, -1, 1317, 1301, 1313, -1, 1318, 1311, 1306, -1, 1318, 1306, 1314, -1, 1319, 1297, 1292, -1, 1319, 1292, 1315, -1, 1320, 1307, 1317, -1, 1320, 1315, 1307, -1, 1321, 1311, 1318, -1, 1321, 1316, 1311, -1, 1322, 1297, 1319, -1, 1323, 1300, 1324, -1, 1322, 1305, 1297, -1, 1323, 1325, 1300, -1, 1326, 1319, 1315, -1, 1326, 1315, 1320, -1, 1327, 1308, 1309, -1, 1328, 1316, 1321, -1, 1329, 1310, 1305, -1, 1328, 1324, 1316, -1, 1329, 1305, 1322, -1, 1329, 1312, 1310, -1, 1330, 1302, 1331, -1, 1330, 1313, 1302, -1, 1332, 1308, 1327, -1, 1332, 1314, 1308, -1, 1333, 1322, 1319, -1, 1334, 1323, 1324, -1, 1333, 1319, 1326, -1, 1334, 1325, 1323, -1, 1334, 1324, 1328, -1, 1335, 1327, 1309, -1, 1336, 1317, 1313, -1, 1335, 1309, 1337, -1, 1336, 1313, 1330, -1, 1338, 1314, 1332, -1, 1339, 1322, 1333, -1, 1339, 1329, 1322, -1, 1339, 1312, 1329, -1, 1338, 1318, 1314, -1, 1339, 1340, 1312, -1, 1341, 1327, 1335, -1, 1342, 1330, 1331, -1, 1341, 1332, 1327, -1, 1343, 1321, 1318, -1, 1344, 1320, 1317, -1, 1343, 1318, 1338, -1, 1344, 1317, 1336, -1, 1345, 1338, 1332, -1, 1345, 1332, 1341, -1, 1346, 1330, 1342, -1, 1346, 1336, 1330, -1, 1347, 1328, 1321, -1, 1348, 1326, 1320, -1, 1347, 1321, 1343, -1, 1348, 1320, 1344, -1, 1349, 1343, 1338, -1, 1349, 1338, 1345, -1, 1350, 1344, 1336, -1, 1350, 1336, 1346, -1, 1351, 1325, 1334, -1, 1351, 1334, 1328, -1, 1352, 1333, 1326, -1, 1351, 1328, 1347, -1, 1351, 1353, 1325, -1, 1352, 1326, 1348, -1, 1354, 1335, 1337, -1, 1355, 1344, 1350, -1, 1356, 1347, 1343, -1, 1355, 1348, 1344, -1, 1356, 1343, 1349, -1, 1357, 1339, 1333, -1, 1357, 1340, 1339, -1, 1357, 1333, 1352, -1, 1358, 1335, 1354, -1, 1359, 1331, 1360, -1, 1358, 1341, 1335, -1, 1359, 1342, 1331, -1, 1361, 1351, 1347, -1, 1362, 1348, 1355, -1, 1361, 1347, 1356, -1, 1362, 1352, 1348, -1, 1361, 1353, 1351, -1, 1363, 1337, 1364, -1, 1363, 1354, 1337, -1, 1365, 1342, 1359, -1, 1366, 1345, 1341, -1, 1366, 1341, 1358, -1, 1365, 1346, 1342, -1, 1367, 1352, 1362, -1, 1367, 1340, 1357, -1, 1368, 1358, 1354, -1, 1367, 1369, 1340, -1, 1367, 1357, 1352, -1, 1370, 1359, 1360, -1, 1368, 1354, 1363, -1, 1371, 1349, 1345, -1, 1372, 1350, 1346, -1, 1371, 1345, 1366, -1, 1372, 1346, 1365, -1, 1373, 1366, 1358, -1, 1373, 1358, 1368, -1, 1374, 1359, 1370, -1, 1374, 1365, 1359, -1, 1375, 1356, 1349, -1, 1376, 1355, 1350, -1, 1375, 1349, 1371, -1, 1376, 1350, 1372, -1, 1377, 1372, 1365, -1, 1378, 1371, 1366, -1, 1378, 1366, 1373, -1, 1377, 1365, 1374, -1, 1379, 1380, 1353, -1, 1379, 1356, 1375, -1, 1379, 1361, 1356, -1, 1379, 1353, 1361, -1, 1381, 1355, 1376, -1, 1381, 1362, 1355, -1, 1382, 1363, 1364, -1, 1383, 1376, 1372, -1, 1383, 1372, 1377, -1, 1384, 1367, 1362, -1, 1385, 1375, 1371, -1, 1384, 1362, 1381, -1, 1385, 1371, 1378, -1, 1384, 1369, 1367, -1, 1386, 1368, 1363, -1, 1386, 1363, 1382, -1, 1387, 1381, 1376, -1, 1387, 1376, 1383, -1, 1388, 1360, 1389, -1, 1388, 1370, 1360, -1, 1390, 1380, 1379, -1, 1390, 1379, 1375, -1, 1390, 1375, 1385, -1, 1391, 1381, 1387, -1, 1391, 1384, 1381, -1, 1392, 1368, 1386, -1, 1391, 1369, 1384, -1, 1392, 1373, 1368, -1, 1391, 1256, 1369, -1, 1393, 1370, 1388, -1, 1394, 1364, 1395, -1, 1393, 1374, 1370, -1, 1394, 1382, 1364, -1, 1396, 1373, 1392, -1, 1396, 1378, 1373, -1, 1397, 1374, 1393, -1, 1397, 1377, 1374, -1, 1398, 1382, 1394, -1, 1030, 1383, 1377, -1, 1030, 1377, 1397, -1, 1398, 1386, 1382, -1, 1399, 1378, 1396, -1, 1033, 1387, 1383, -1, 1033, 1383, 1030, -1, 1399, 1385, 1378, -1, 1400, 1392, 1386, -1, 1400, 1386, 1398, -1, 1034, 1391, 1387, -1, 1034, 1256, 1391, -1, 1034, 1387, 1033, -1, 1401, 1390, 1385, -1, 1401, 1385, 1399, -1, 1401, 1402, 1380, -1, 1401, 1380, 1390, -1, 1403, 1392, 1400, -1, 1403, 1396, 1392, -1, 1404, 1394, 1395, -1, 1405, 1396, 1403, -1, 1405, 1399, 1396, -1, 1406, 1394, 1404, -1, 1406, 1398, 1394, -1, 1407, 1401, 1399, -1, 1407, 1402, 1401, -1, 1407, 1399, 1405, -1, 1408, 1400, 1398, -1, 1408, 1398, 1406, -1, 1409, 1404, 1395, -1, 1409, 1395, 1410, -1, 1411, 1403, 1400, -1, 1411, 1400, 1408, -1, 1412, 1404, 1409, -1, 1412, 1406, 1404, -1, 1413, 1405, 1403, -1, 1413, 1403, 1411, -1, 1414, 1408, 1406, -1, 1414, 1406, 1412, -1, 1415, 1402, 1407, -1, 1415, 1407, 1405, -1, 1415, 1405, 1413, -1, 1415, 1416, 1402, -1, 1417, 1409, 1410, -1, 1418, 1411, 1408, -1, 1418, 1408, 1414, -1, 1419, 1409, 1417, -1, 1419, 1412, 1409, -1, 1420, 1413, 1411, -1, 1420, 1411, 1418, -1, 1421, 1414, 1412, -1, 1421, 1412, 1419, -1, 1422, 1415, 1413, -1, 1422, 1416, 1415, -1, 1422, 1413, 1420, -1, 1423, 1410, 1424, -1, 1423, 1417, 1410, -1, 1425, 1418, 1414, -1, 1425, 1414, 1421, -1, 1426, 1130, 1129, -1, 1427, 1419, 1417, -1, 1428, 1426, 1129, -1, 1427, 1417, 1423, -1, 1428, 1129, 1429, -1, 1430, 1420, 1418, -1, 1430, 1418, 1425, -1, 1141, 1428, 1429, -1, 1431, 1421, 1419, -1, 1141, 1429, 1432, -1, 1431, 1419, 1427, -1, 1433, 1434, 1416, -1, 1433, 1416, 1422, -1, 1433, 1422, 1420, -1, 1433, 1420, 1430, -1, 1155, 1141, 1432, -1, 1435, 1423, 1424, -1, 1155, 1432, 1436, -1, 1437, 1425, 1421, -1, 1437, 1421, 1431, -1, 1156, 1155, 1436, -1, 1156, 1436, 1438, -1, 1439, 1423, 1435, -1, 1159, 1156, 1438, -1, 1439, 1427, 1423, -1, 1159, 1438, 1440, -1, 1159, 1440, 1441, -1, 1159, 1441, 1294, -1, 1442, 1220, 1246, -1, 1442, 1248, 1226, -1, 1442, 1246, 1248, -1, 1442, 1223, 1220, -1, 1443, 1425, 1437, -1, 1442, 1226, 1223, -1, 1443, 1430, 1425, -1, 1444, 1246, 1273, -1, 1444, 1273, 1276, -1, 1444, 1248, 1246, -1, 1445, 1427, 1439, -1, 1444, 1249, 1248, -1, 1444, 1276, 1249, -1, 1446, 1299, 1277, -1, 1445, 1431, 1427, -1, 1446, 1277, 1276, -1, 1447, 1430, 1443, -1, 1448, 1300, 1298, -1, 1447, 1434, 1433, -1, 1448, 1324, 1300, -1, 1447, 1433, 1430, -1, 1449, 1450, 1451, -1, 1452, 1424, 1453, -1, 1449, 1454, 1450, -1, 1452, 1435, 1424, -1, 1455, 1431, 1445, -1, 1455, 1437, 1431, -1, 1456, 1449, 1451, -1, 1457, 1451, 1458, -1, 1459, 1435, 1452, -1, 1457, 1456, 1451, -1, 1457, 1458, 1460, -1, 1459, 1439, 1435, -1, 1461, 1460, 1458, -1, 1462, 1437, 1455, -1, 1461, 1463, 1460, -1, 1462, 1443, 1437, -1, 1464, 1445, 1439, -1, 1465, 1461, 1458, -1, 1464, 1439, 1459, -1, 1466, 1443, 1462, -1, 1466, 1447, 1443, -1, 1466, 1434, 1447, -1, 1467, 1458, 1468, -1, 1466, 1469, 1434, -1, 1467, 1465, 1458, -1, 1470, 1452, 1453, -1, 1467, 1468, 1471, -1, 1472, 1473, 1471, -1, 1474, 1455, 1445, -1, 1472, 1471, 1468, -1, 1474, 1445, 1464, -1, 1475, 1472, 1468, -1, 1476, 1452, 1470, -1, 1477, 1478, 1479, -1, 1476, 1459, 1452, -1, 1477, 1468, 1478, -1, 1480, 1462, 1455, -1, 1480, 1455, 1474, -1, 1477, 1475, 1468, -1, 1481, 1479, 1478, -1, 1481, 1482, 1479, -1, 1483, 1464, 1459, -1, 958, 1481, 1478, -1, 1483, 1459, 1476, -1, 1484, 1469, 1466, -1, 1484, 1462, 1480, -1, 959, 1478, 1485, -1, 959, 1485, 1486, -1, 1484, 1466, 1462, -1, 1487, 1474, 1464, -1, 959, 958, 1478, -1, 1487, 1464, 1483, -1, 1488, 1489, 1490, -1, 1488, 926, 1489, -1, 1488, 1490, 1491, -1, 1488, 924, 926, -1, 1492, 1453, 1493, -1, 1488, 1491, 924, -1, 1494, 925, 924, -1, 1492, 1470, 1453, -1, 1494, 948, 925, -1, 1495, 1480, 1474, -1, 1494, 1496, 948, -1, 1495, 1474, 1487, -1, 1497, 949, 948, -1, 1497, 971, 949, -1, 1498, 1470, 1492, -1, 1498, 1476, 1470, -1, 1021, 972, 970, -1, 1019, 1008, 1007, -1, 1499, 1469, 1484, -1, 1499, 1484, 1480, -1, 1499, 1480, 1495, -1, 1019, 1007, 972, -1, 1499, 1500, 1469, -1, 1501, 1476, 1498, -1, 1502, 1388, 1389, -1, 1501, 1483, 1476, -1, 1502, 1393, 1388, -1, 1503, 1492, 1493, -1, 1504, 1487, 1483, -1, 1505, 1502, 1389, -1, 1504, 1483, 1501, -1, 1506, 1389, 1507, -1, 1506, 1507, 1508, -1, 1506, 1505, 1389, -1, 1509, 1498, 1492, -1, 1510, 1508, 1507, -1, 1510, 1511, 1508, -1, 1509, 1492, 1503, -1, 1512, 1495, 1487, -1, 1512, 1487, 1504, -1, 1513, 1510, 1507, -1, 1514, 1501, 1498, -1, 1514, 1498, 1509, -1, 1515, 1507, 1516, -1, 1515, 1513, 1507, -1, 1515, 1516, 1517, -1, 1518, 1499, 1495, -1, 1518, 1500, 1499, -1, 1519, 1517, 1516, -1, 1518, 1495, 1512, -1, 1519, 1520, 1517, -1, 1521, 1504, 1501, -1, 1521, 1501, 1514, -1, 1522, 1519, 1516, -1, 1523, 1493, 1524, -1, 1523, 1503, 1493, -1, 1525, 1516, 1526, -1, 1525, 1526, 1527, -1, 1525, 1522, 1516, -1, 1528, 1512, 1504, -1, 1529, 1530, 1527, -1, 1528, 1504, 1521, -1, 1529, 1527, 1526, -1, 1531, 1509, 1503, -1, 1531, 1503, 1523, -1, 1115, 1529, 1526, -1, 1532, 1500, 1518, -1, 1532, 1533, 1500, -1, 1118, 1526, 1130, -1, 1532, 1518, 1512, -1, 1118, 1115, 1526, -1, 1532, 1512, 1528, -1, 1118, 1130, 1426, -1, 1534, 1273, 1269, -1, 1535, 1523, 1524, -1, 1534, 1299, 1446, -1, 1534, 1276, 1273, -1, 1534, 1269, 1295, -1, 1536, 1514, 1509, -1, 1534, 1446, 1276, -1, 1534, 1295, 1299, -1, 1537, 1316, 1324, -1, 1537, 1448, 1298, -1, 1537, 1298, 1299, -1, 1536, 1509, 1531, -1, 1537, 1324, 1448, -1, 1537, 1295, 1316, -1, 1537, 1299, 1295, -1, 1538, 1523, 1535, -1, 1539, 1540, 1541, -1, 1538, 1531, 1523, -1, 1539, 1541, 1454, -1, 1542, 1539, 1454, -1, 1542, 1449, 1456, -1, 1543, 1521, 1514, -1, 1542, 1454, 1449, -1, 1543, 1514, 1536, -1, 1544, 1536, 1531, -1, 1168, 1542, 1456, -1, 1544, 1531, 1538, -1, 1545, 1521, 1543, -1, 1545, 1528, 1521, -1, 1546, 1543, 1536, -1, 1547, 1457, 1460, -1, 1546, 1536, 1544, -1, 1547, 1460, 1463, -1, 1548, 1528, 1545, -1, 1549, 1168, 1456, -1, 1549, 1457, 1547, -1, 1549, 1456, 1457, -1, 1548, 1533, 1532, -1, 1548, 1532, 1528, -1, 1550, 1549, 1547, -1, 1550, 1547, 1463, -1, 1551, 1524, 1552, -1, 1550, 1463, 1553, -1, 1550, 1553, 1554, -1, 1551, 1535, 1524, -1, 1555, 1543, 1546, -1, 1555, 1545, 1543, -1, 1556, 1553, 1463, -1, 1556, 1554, 1553, -1, 1557, 1463, 1461, -1, 1558, 1535, 1551, -1, 1557, 1461, 1465, -1, 1557, 1556, 1463, -1, 1558, 1538, 1535, -1, 1559, 1548, 1545, -1, 1559, 1545, 1555, -1, 1559, 1533, 1548, -1, 1192, 1557, 1465, -1, 1559, 1560, 1533, -1, 1561, 1551, 1552, -1, 1562, 1471, 1473, -1, 1563, 1538, 1558, -1, 1563, 1544, 1538, -1, 1562, 1467, 1471, -1, 1564, 1465, 1467, -1, 1565, 1551, 1561, -1, 1564, 1467, 1562, -1, 1565, 1558, 1551, -1, 1564, 1192, 1465, -1, 1566, 1473, 1567, -1, 1566, 1562, 1473, -1, 1568, 1544, 1563, -1, 1566, 1564, 1562, -1, 1569, 1570, 1567, -1, 1569, 1567, 1473, -1, 1568, 1546, 1544, -1, 1571, 1563, 1558, -1, 1571, 1558, 1565, -1, 1572, 1569, 1473, -1, 1573, 1555, 1546, -1, 1573, 1546, 1568, -1, 1572, 1472, 1475, -1, 1572, 1473, 1472, -1, 1574, 1568, 1563, -1, 1574, 1563, 1571, -1, 928, 1572, 1475, -1, 1575, 1559, 1555, -1, 1575, 1560, 1559, -1, 1576, 1477, 1479, -1, 1575, 1555, 1573, -1, 1576, 1479, 1482, -1, 1450, 1552, 1451, -1, 1450, 1561, 1552, -1, 929, 1477, 1576, -1, 929, 1475, 1477, -1, 1577, 1573, 1568, -1, 929, 928, 1475, -1, 1577, 1568, 1574, -1, 933, 1482, 938, -1, 933, 929, 1576, -1, 1454, 1561, 1450, -1, 933, 1576, 1482, -1, 1454, 1565, 1561, -1, 964, 946, 938, -1, 964, 938, 1482, -1, 1578, 1575, 1573, -1, 957, 1481, 958, -1, 1578, 1573, 1577, -1, 1578, 1560, 1575, -1, 957, 964, 1482, -1, 1578, 1179, 1560, -1, 1541, 1571, 1565, -1, 957, 1482, 1481, -1, 1541, 1565, 1454, -1, 1540, 1574, 1571, -1, 1540, 1571, 1541, -1, 1579, 1577, 1574, -1, 968, 1486, 1580, -1, 968, 959, 1486, -1, 1579, 1574, 1540, -1, 1175, 1578, 1577, -1, 1175, 1179, 1578, -1, 1175, 1577, 1579, -1, 975, 968, 1580, -1, 975, 1580, 981, -1, 975, 967, 968, -1, 1581, 1491, 944, -1, 1581, 924, 1491, -1, 1581, 944, 943, -1, 1581, 1494, 924, -1, 1581, 943, 1496, -1, 1581, 1496, 1494, -1, 1582, 1496, 943, -1, 1582, 1497, 948, -1, 1582, 948, 1496, -1, 1582, 943, 966, -1, 1582, 966, 971, -1, 1582, 971, 1497, -1, 1583, 971, 966, -1, 1583, 1021, 970, -1, 1583, 970, 971, -1, 1000, 1583, 966, -1, 1022, 1000, 999, -1, 1022, 1583, 1000, -1, 1022, 1021, 1583, -1, 1015, 995, 1003, -1, 1024, 1003, 1008, -1, 1024, 1014, 1015, -1, 1024, 1015, 1003, -1, 1024, 1008, 1019, -1, 1029, 1030, 1397, -1, 1029, 1397, 1393, -1, 1027, 1393, 1502, -1, 1027, 1502, 1505, -1, 1027, 1029, 1393, -1, 1028, 1027, 1505, -1, 1584, 1506, 1508, -1, 1584, 1508, 1511, -1, 1042, 1506, 1584, -1, 1042, 1505, 1506, -1, 1042, 1028, 1505, -1, 1043, 1042, 1584, -1, 1043, 1584, 1511, -1, 1043, 1585, 1044, -1, 1043, 1511, 1585, -1, 1053, 1044, 1585, -1, 1053, 1585, 1511, -1, 1054, 1511, 1510, -1, 1054, 1510, 1513, -1, 1054, 1053, 1511, -1, 1055, 1054, 1513, -1, 1586, 1515, 1517, -1, 1586, 1517, 1520, -1, 1063, 1515, 1586, -1, 1063, 1513, 1515, -1, 1063, 1055, 1513, -1, 1064, 1063, 1586, -1, 1064, 1586, 1520, -1, 1064, 1520, 1072, -1, 1085, 1072, 1520, -1, 1085, 1074, 1072, -1, 1083, 1085, 1520, -1, 1083, 1520, 1519, -1, 1083, 1519, 1522, -1, 1587, 1485, 1588, -1, 1587, 1486, 1485, -1, 1589, 1486, 1587, -1, 1084, 1083, 1522, -1, 1589, 1580, 1486, -1, 1590, 1527, 1530, -1, 1590, 1525, 1527, -1, 1591, 1580, 1589, -1, 1094, 1522, 1525, -1, 1094, 1084, 1522, -1, 1094, 1525, 1590, -1, 1591, 981, 1580, -1, 1592, 987, 981, -1, 1095, 1530, 1099, -1, 1095, 1094, 1590, -1, 1095, 1590, 1530, -1, 1592, 981, 1591, -1, 1123, 1106, 1099, -1, 1593, 987, 1592, -1, 1593, 988, 987, -1, 1123, 1099, 1530, -1, 1594, 988, 1593, -1, 1594, 993, 988, -1, 1114, 1530, 1529, -1, 1594, 1234, 993, -1, 1114, 1123, 1530, -1, 1594, 1595, 1234, -1, 1114, 1529, 1115, -1, 1596, 1587, 1588, -1, 1596, 1588, 1597, -1, 1598, 1589, 1587, -1, 1598, 1587, 1596, -1, 1125, 1426, 1428, -1, 1599, 1591, 1589, -1, 1125, 1118, 1426, -1, 1599, 1589, 1598, -1, 1137, 1125, 1428, -1, 1137, 1126, 1125, -1, 1600, 1592, 1591, -1, 1137, 1428, 1141, -1, 1600, 1591, 1599, -1, 1171, 1542, 1168, -1, 1601, 1593, 1592, -1, 1171, 1539, 1542, -1, 1171, 1540, 1539, -1, 1601, 1592, 1600, -1, 1602, 1594, 1593, -1, 1602, 1595, 1594, -1, 1176, 1540, 1171, -1, 1602, 1603, 1595, -1, 1176, 1579, 1540, -1, 1602, 1593, 1601, -1, 1176, 1175, 1579, -1, 1604, 1596, 1597, -1, 1166, 1176, 1171, -1, 1604, 1597, 1605, -1, 1606, 1598, 1596, -1, 1606, 1596, 1604, -1, 1607, 1599, 1598, -1, 1169, 1549, 1550, -1, 1607, 1598, 1606, -1, 1169, 1550, 1554, -1, 1169, 1168, 1549, -1, 1608, 1599, 1607, -1, 1608, 1600, 1599, -1, 1182, 1169, 1554, -1, 1609, 1601, 1600, -1, 1182, 1170, 1169, -1, 1182, 1554, 1610, -1, 1182, 1610, 1183, -1, 1609, 1600, 1608, -1, 1191, 1557, 1192, -1, 1611, 1612, 1603, -1, 1611, 1603, 1602, -1, 1611, 1601, 1609, -1, 1191, 1554, 1556, -1, 1611, 1602, 1601, -1, 1191, 1556, 1557, -1, 1613, 1604, 1605, -1, 1203, 1554, 1191, -1, 1613, 1605, 1614, -1, 1203, 1610, 1554, -1, 1203, 1183, 1610, -1, 1615, 1606, 1604, -1, 1197, 1203, 1191, -1, 1615, 1604, 1613, -1, 1193, 1564, 1566, -1, 1193, 1192, 1564, -1, 1616, 1606, 1615, -1, 1616, 1607, 1606, -1, 1617, 1607, 1616, -1, 1617, 1608, 1607, -1, 1490, 1609, 1608, -1, 1490, 1608, 1617, -1, 1489, 1611, 1609, -1, 1618, 1193, 1566, -1, 1489, 1609, 1490, -1, 1618, 1198, 1193, -1, 1489, 926, 1612, -1, 1618, 1566, 1567, -1, 1489, 1612, 1611, -1, 934, 1614, 931, -1, 1619, 1567, 1570, -1, 934, 1613, 1614, -1, 1619, 1570, 1620, -1, 1619, 1618, 1567, -1, 937, 1613, 934, -1, 1210, 1620, 1207, -1, 937, 1615, 1613, -1, 1210, 1198, 1618, -1, 1210, 1201, 1198, -1, 1210, 1619, 1620, -1, 1210, 1618, 1619, -1, 923, 1570, 1569, -1, 940, 1616, 1615, -1, 940, 1615, 937, -1, 923, 1569, 1572, -1, 923, 1572, 928, -1, 922, 1620, 1570, -1, 922, 1207, 1620, -1, 944, 1616, 940, -1, 922, 1570, 923, -1, 944, 1617, 1616, -1, 1491, 1490, 1617, -1, 1491, 1617, 944, -1, 1621, 1622, 1623, -1, 1624, 1625, 1626, -1, 1627, 1622, 1621, -1, 1628, 1629, 1630, -1, 1631, 1632, 1633, -1, 1634, 1632, 1631, -1, 1633, 1632, 1635, -1, 1635, 1632, 1636, -1, 1637, 1629, 1628, -1, 1637, 1638, 1629, -1, 1639, 1640, 1641, -1, 1642, 1638, 1643, -1, 1644, 1640, 1639, -1, 1630, 1638, 1642, -1, 1629, 1638, 1630, -1, 1637, 1645, 1638, -1, 1646, 1645, 1637, -1, 1647, 1648, 1625, -1, 1638, 1645, 1643, -1, 1636, 1648, 1647, -1, 1649, 1650, 1651, -1, 1652, 1650, 1649, -1, 1651, 1650, 1653, -1, 1641, 1654, 1655, -1, 1643, 1656, 1652, -1, 1655, 1654, 1657, -1, 1645, 1656, 1643, -1, 1646, 1656, 1645, -1, 1626, 1658, 1644, -1, 1652, 1656, 1650, -1, 1644, 1658, 1640, -1, 1653, 1659, 1646, -1, 1650, 1659, 1653, -1, 1646, 1659, 1656, -1, 1656, 1659, 1650, -1, 1634, 1660, 1632, -1, 1646, 1661, 1653, -1, 1632, 1660, 1636, -1, 1636, 1660, 1648, -1, 1653, 1661, 1651, -1, 1640, 1662, 1641, -1, 1661, 1663, 1651, -1, 1641, 1662, 1654, -1, 1664, 1663, 1665, -1, 1651, 1663, 1664, -1, 1625, 1666, 1626, -1, 1646, 1663, 1661, -1, 1626, 1666, 1658, -1, 1667, 1668, 1646, -1, 1646, 1668, 1663, -1, 1663, 1668, 1665, -1, 1640, 1669, 1662, -1, 1670, 1671, 1672, -1, 1673, 1671, 1670, -1, 1658, 1669, 1640, -1, 1672, 1671, 1674, -1, 1673, 1675, 1671, -1, 1648, 1676, 1625, -1, 1625, 1676, 1666, -1, 1668, 1675, 1665, -1, 1667, 1675, 1668, -1, 1665, 1675, 1673, -1, 1674, 1677, 1667, -1, 1654, 1678, 1657, -1, 1671, 1677, 1674, -1, 1675, 1677, 1671, -1, 1667, 1677, 1675, -1, 1667, 1679, 1674, -1, 1674, 1679, 1672, -1, 1666, 1680, 1658, -1, 1658, 1680, 1669, -1, 1681, 1682, 1634, -1, 1679, 1683, 1672, -1, 1634, 1682, 1660, -1, 1672, 1683, 1684, -1, 1648, 1682, 1676, -1, 1667, 1683, 1679, -1, 1660, 1682, 1648, -1, 1684, 1683, 1685, -1, 1686, 1687, 1667, -1, 1654, 1688, 1678, -1, 1667, 1687, 1683, -1, 1683, 1687, 1685, -1, 1662, 1688, 1654, -1, 1689, 1690, 1691, -1, 1692, 1690, 1689, -1, 1676, 1693, 1666, -1, 1666, 1693, 1680, -1, 1687, 1694, 1685, -1, 1669, 1695, 1662, -1, 1686, 1694, 1687, -1, 1685, 1694, 1692, -1, 1692, 1694, 1690, -1, 1696, 1697, 1686, -1, 1662, 1695, 1688, -1, 1691, 1697, 1696, -1, 1690, 1697, 1691, -1, 1686, 1697, 1694, -1, 1694, 1697, 1690, -1, 1678, 1698, 1657, -1, 1657, 1698, 1699, -1, 1681, 1700, 1682, -1, 1682, 1700, 1676, -1, 1676, 1700, 1693, -1, 1680, 1701, 1669, -1, 1669, 1701, 1695, -1, 1688, 1702, 1678, -1, 1678, 1702, 1698, -1, 1693, 1703, 1680, -1, 1680, 1703, 1701, -1, 1688, 1704, 1702, -1, 1695, 1704, 1688, -1, 1698, 1705, 1699, -1, 1693, 1706, 1703, -1, 1707, 1706, 1681, -1, 1681, 1706, 1700, -1, 1700, 1706, 1693, -1, 1695, 1708, 1704, -1, 1701, 1708, 1695, -1, 1698, 1709, 1705, -1, 1702, 1709, 1698, -1, 1701, 1710, 1708, -1, 1703, 1710, 1701, -1, 1702, 1711, 1709, -1, 1704, 1711, 1702, -1, 1699, 1712, 1713, -1, 1705, 1712, 1699, -1, 1706, 1714, 1703, -1, 1707, 1714, 1706, -1, 1703, 1714, 1710, -1, 1708, 1715, 1704, -1, 1704, 1715, 1711, -1, 1709, 1716, 1705, -1, 1705, 1716, 1712, -1, 1710, 1717, 1708, -1, 1708, 1717, 1715, -1, 1712, 1718, 1713, -1, 1711, 1719, 1709, -1, 1709, 1719, 1716, -1, 1714, 1720, 1710, -1, 1721, 1720, 1707, -1, 1707, 1720, 1714, -1, 1710, 1720, 1717, -1, 1716, 1722, 1712, -1, 1712, 1722, 1718, -1, 1715, 1723, 1711, -1, 1711, 1723, 1719, -1, 1719, 1724, 1716, -1, 1716, 1724, 1722, -1, 1717, 1725, 1715, -1, 1715, 1725, 1723, -1, 1718, 1726, 1713, -1, 1713, 1726, 1727, -1, 1723, 1728, 1719, -1, 1719, 1728, 1724, -1, 1721, 1729, 1720, -1, 1720, 1729, 1717, -1, 1717, 1729, 1725, -1, 1722, 1730, 1718, -1, 1718, 1730, 1726, -1, 1725, 1731, 1723, -1, 1723, 1731, 1728, -1, 1726, 1732, 1727, -1, 1724, 1733, 1722, -1, 1722, 1733, 1730, -1, 1734, 1735, 1721, -1, 1721, 1735, 1729, -1, 1729, 1735, 1725, -1, 1725, 1735, 1731, -1, 1730, 1736, 1726, -1, 1726, 1736, 1732, -1, 1728, 1737, 1724, -1, 1724, 1737, 1733, -1, 1733, 1738, 1730, -1, 1730, 1738, 1736, -1, 1728, 1739, 1737, -1, 1731, 1739, 1728, -1, 1732, 1740, 1727, -1, 1727, 1740, 1741, -1, 1737, 1742, 1733, -1, 1733, 1742, 1738, -1, 1734, 1743, 1735, -1, 1735, 1743, 1731, -1, 1731, 1743, 1739, -1, 1732, 1744, 1740, -1, 1736, 1744, 1732, -1, 1745, 1746, 1747, -1, 1737, 1748, 1742, -1, 1739, 1748, 1737, -1, 1740, 1749, 1741, -1, 1736, 1750, 1744, -1, 1738, 1750, 1736, -1, 1734, 1751, 1743, -1, 1739, 1751, 1748, -1, 1752, 1751, 1734, -1, 1743, 1751, 1739, -1, 1740, 1753, 1749, -1, 1744, 1753, 1740, -1, 1738, 1754, 1750, -1, 1755, 1756, 1757, -1, 1742, 1754, 1738, -1, 1750, 1758, 1744, -1, 1744, 1758, 1753, -1, 1757, 1756, 1759, -1, 1748, 1760, 1742, -1, 1761, 1762, 1755, -1, 1742, 1760, 1754, -1, 1755, 1762, 1756, -1, 1761, 1763, 1762, -1, 1750, 1764, 1758, -1, 1754, 1764, 1750, -1, 1765, 1763, 1761, -1, 1749, 1766, 1741, -1, 1767, 1768, 1765, -1, 1741, 1766, 1769, -1, 1765, 1768, 1763, -1, 1748, 1770, 1760, -1, 1751, 1770, 1748, -1, 1752, 1770, 1751, -1, 1767, 1771, 1768, -1, 1772, 1771, 1767, -1, 1760, 1773, 1754, -1, 1754, 1773, 1764, -1, 1756, 1774, 1759, -1, 1749, 1775, 1766, -1, 1759, 1774, 1776, -1, 1753, 1775, 1749, -1, 1772, 1777, 1771, -1, 1778, 1777, 1779, -1, 1780, 1777, 1772, -1, 1779, 1777, 1780, -1, 1762, 1781, 1756, -1, 1766, 1782, 1769, -1, 1783, 1784, 1752, -1, 1760, 1784, 1773, -1, 1770, 1784, 1760, -1, 1756, 1781, 1774, -1, 1752, 1784, 1770, -1, 1758, 1785, 1753, -1, 1753, 1785, 1775, -1, 1762, 1786, 1781, -1, 1763, 1786, 1762, -1, 1775, 1787, 1766, -1, 1768, 1788, 1763, -1, 1766, 1787, 1782, -1, 1763, 1788, 1786, -1, 1758, 1789, 1785, -1, 1768, 1790, 1788, -1, 1764, 1789, 1758, -1, 1771, 1790, 1768, -1, 1785, 1791, 1775, -1, 1775, 1791, 1787, -1, 1776, 1792, 1793, -1, 1774, 1792, 1776, -1, 1773, 1794, 1764, -1, 1777, 1795, 1771, -1, 1778, 1795, 1777, -1, 1764, 1794, 1789, -1, 1796, 1795, 1778, -1, 1771, 1795, 1790, -1, 1774, 1797, 1792, -1, 1789, 1798, 1785, -1, 1785, 1798, 1791, -1, 1781, 1797, 1774, -1, 1782, 1799, 1769, -1, 1781, 1800, 1797, -1, 1769, 1799, 1801, -1, 1786, 1800, 1781, -1, 1783, 1802, 1784, -1, 1784, 1802, 1773, -1, 1773, 1802, 1794, -1, 1788, 1803, 1786, -1, 1789, 1804, 1798, -1, 1786, 1803, 1800, -1, 1794, 1804, 1789, -1, 1788, 1805, 1803, -1, 1790, 1805, 1788, -1, 1782, 1806, 1799, -1, 1787, 1806, 1782, -1, 1637, 1807, 1783, -1, 1783, 1807, 1802, -1, 1802, 1807, 1794, -1, 1796, 1808, 1795, -1, 1795, 1808, 1790, -1, 1794, 1807, 1804, -1, 1790, 1808, 1805, -1, 1809, 1808, 1796, -1, 1787, 1810, 1806, -1, 1791, 1810, 1787, -1, 1798, 1811, 1791, -1, 1791, 1811, 1810, -1, 1798, 1630, 1811, -1, 1804, 1630, 1798, -1, 1637, 1628, 1807, -1, 1807, 1628, 1804, -1, 1804, 1628, 1630, -1, 1812, 1813, 1814, -1, 1814, 1813, 1815, -1, 1812, 1816, 1813, -1, 1817, 1816, 1812, -1, 1817, 1818, 1816, -1, 1819, 1818, 1817, -1, 1820, 1821, 1819, -1, 1819, 1821, 1818, -1, 1813, 1822, 1815, -1, 1820, 1823, 1821, -1, 1824, 1823, 1820, -1, 1745, 1825, 1746, -1, 1816, 1826, 1813, -1, 1813, 1826, 1822, -1, 1746, 1827, 1828, -1, 1822, 1829, 1815, -1, 1815, 1829, 1830, -1, 1825, 1827, 1746, -1, 1831, 1832, 1833, -1, 1833, 1832, 1824, -1, 1828, 1834, 1835, -1, 1824, 1832, 1823, -1, 1818, 1836, 1816, -1, 1816, 1836, 1826, -1, 1827, 1834, 1828, -1, 1835, 1689, 1837, -1, 1822, 1838, 1829, -1, 1826, 1838, 1822, -1, 1821, 1839, 1818, -1, 1834, 1689, 1835, -1, 1818, 1839, 1836, -1, 1837, 1691, 1840, -1, 1689, 1691, 1837, -1, 1836, 1841, 1826, -1, 1826, 1841, 1838, -1, 1840, 1696, 1842, -1, 1842, 1696, 1843, -1, 1843, 1696, 1686, -1, 1823, 1844, 1821, -1, 1691, 1696, 1840, -1, 1821, 1844, 1839, -1, 1809, 1845, 1808, -1, 1829, 1846, 1830, -1, 1808, 1845, 1805, -1, 1839, 1847, 1836, -1, 1836, 1847, 1841, -1, 1809, 1848, 1845, -1, 1849, 1850, 1851, -1, 1851, 1850, 1809, -1, 1852, 1853, 1831, -1, 1832, 1853, 1823, -1, 1809, 1850, 1848, -1, 1831, 1853, 1832, -1, 1823, 1853, 1844, -1, 1851, 1854, 1849, -1, 1849, 1854, 1855, -1, 1838, 1856, 1829, -1, 1829, 1856, 1846, -1, 1844, 1857, 1839, -1, 1851, 1858, 1854, -1, 1839, 1857, 1847, -1, 1831, 1859, 1851, -1, 1851, 1859, 1858, -1, 1830, 1860, 1861, -1, 1833, 1859, 1831, -1, 1846, 1860, 1830, -1, 1838, 1862, 1856, -1, 1863, 1864, 1865, -1, 1865, 1864, 1866, -1, 1841, 1862, 1838, -1, 1852, 1867, 1853, -1, 1853, 1867, 1844, -1, 1864, 1868, 1866, -1, 1844, 1867, 1857, -1, 1856, 1869, 1846, -1, 1846, 1869, 1860, -1, 1868, 1870, 1866, -1, 1841, 1871, 1862, -1, 1847, 1871, 1841, -1, 1866, 1872, 1873, -1, 1873, 1872, 1874, -1, 1870, 1872, 1866, -1, 1856, 1875, 1869, -1, 1862, 1875, 1856, -1, 1876, 1877, 1874, -1, 1874, 1877, 1873, -1, 1857, 1878, 1847, -1, 1847, 1878, 1871, -1, 1877, 1879, 1873, -1, 1860, 1880, 1861, -1, 1879, 1881, 1873, -1, 1873, 1881, 1882, -1, 1871, 1883, 1862, -1, 1882, 1884, 1885, -1, 1881, 1884, 1882, -1, 1862, 1883, 1875, -1, 1852, 1886, 1867, -1, 1885, 1887, 1882, -1, 1867, 1886, 1857, -1, 1888, 1886, 1852, -1, 1889, 1887, 1885, -1, 1857, 1886, 1878, -1, 1887, 1890, 1882, -1, 1869, 1891, 1860, -1, 1860, 1891, 1880, -1, 1889, 1890, 1887, -1, 1878, 1892, 1871, -1, 1871, 1892, 1883, -1, 1882, 1893, 1894, -1, 1890, 1893, 1882, -1, 1880, 1895, 1861, -1, 1894, 1896, 1897, -1, 1893, 1896, 1894, -1, 1861, 1895, 1898, -1, 1875, 1899, 1869, -1, 1900, 1901, 1902, -1, 1903, 1901, 1900, -1, 1869, 1899, 1891, -1, 1903, 1904, 1901, -1, 1888, 1905, 1886, -1, 1886, 1905, 1878, -1, 1878, 1905, 1892, -1, 1903, 1906, 1904, -1, 1880, 1907, 1895, -1, 1908, 1906, 1903, -1, 1891, 1907, 1880, -1, 1909, 1906, 1908, -1, 1883, 1910, 1875, -1, 1908, 1911, 1909, -1, 1909, 1911, 1912, -1, 1875, 1910, 1899, -1, 1899, 1913, 1891, -1, 1908, 1914, 1911, -1, 1891, 1913, 1907, -1, 1915, 1916, 1908, -1, 1892, 1917, 1883, -1, 1908, 1916, 1914, -1, 1918, 1916, 1915, -1, 1883, 1917, 1910, -1, 1806, 1919, 1799, -1, 1895, 1920, 1898, -1, 1799, 1919, 1801, -1, 1899, 1921, 1913, -1, 1919, 1922, 1801, -1, 1910, 1921, 1899, -1, 1923, 1924, 1888, -1, 1888, 1924, 1905, -1, 1892, 1924, 1917, -1, 1905, 1924, 1892, -1, 1922, 1925, 1801, -1, 1907, 1926, 1895, -1, 1925, 1927, 1801, -1, 1801, 1927, 1928, -1, 1895, 1926, 1920, -1, 1928, 1927, 1929, -1, 1930, 1931, 1929, -1, 1917, 1932, 1910, -1, 1910, 1932, 1921, -1, 1929, 1931, 1928, -1, 1913, 1933, 1907, -1, 1907, 1933, 1926, -1, 1931, 1934, 1928, -1, 1898, 1935, 1936, -1, 1920, 1935, 1898, -1, 1934, 1937, 1928, -1, 1928, 1937, 1938, -1, 1923, 1939, 1924, -1, 1938, 1940, 1941, -1, 1924, 1939, 1917, -1, 1917, 1939, 1932, -1, 1937, 1940, 1938, -1, 1941, 1942, 1938, -1, 1943, 1942, 1941, -1, 1921, 1944, 1913, -1, 1913, 1944, 1933, -1, 1942, 1945, 1938, -1, 1926, 1946, 1920, -1, 1920, 1946, 1935, -1, 1943, 1945, 1942, -1, 1932, 1947, 1921, -1, 1921, 1947, 1944, -1, 1945, 1948, 1938, -1, 1938, 1948, 1745, -1, 1948, 1949, 1745, -1, 1745, 1949, 1825, -1, 1926, 1950, 1946, -1, 1805, 1951, 1803, -1, 1933, 1950, 1926, -1, 1803, 1951, 1800, -1, 1935, 1952, 1936, -1, 1805, 1953, 1951, -1, 1845, 1953, 1805, -1, 1954, 1955, 1923, -1, 1848, 1953, 1845, -1, 1923, 1955, 1939, -1, 1932, 1955, 1947, -1, 1939, 1955, 1932, -1, 1944, 1956, 1933, -1, 1848, 1957, 1953, -1, 1933, 1956, 1950, -1, 1848, 1958, 1957, -1, 1850, 1958, 1848, -1, 1935, 1959, 1952, -1, 1946, 1959, 1935, -1, 1960, 1961, 1962, -1, 1947, 1963, 1944, -1, 1962, 1961, 1855, -1, 1849, 1964, 1850, -1, 1855, 1964, 1849, -1, 1850, 1964, 1958, -1, 1944, 1963, 1956, -1, 1958, 1964, 1961, -1, 1961, 1964, 1855, -1, 1946, 1965, 1959, -1, 1962, 1966, 1960, -1, 1950, 1965, 1946, -1, 1855, 1966, 1962, -1, 1952, 1967, 1936, -1, 1858, 1968, 1854, -1, 1854, 1968, 1855, -1, 1936, 1967, 1969, -1, 1855, 1968, 1966, -1, 1955, 1970, 1947, -1, 1947, 1970, 1963, -1, 1954, 1970, 1955, -1, 1956, 1971, 1950, -1, 1950, 1971, 1965, -1, 1858, 1972, 1968, -1, 1858, 1973, 1972, -1, 1959, 1974, 1952, -1, 1859, 1973, 1858, -1, 1952, 1974, 1967, -1, 1819, 1975, 1820, -1, 1820, 1975, 1824, -1, 1963, 1976, 1956, -1, 1956, 1976, 1971, -1, 1833, 1977, 1859, -1, 1824, 1977, 1833, -1, 1859, 1977, 1973, -1, 1975, 1977, 1824, -1, 1973, 1977, 1975, -1, 1967, 1978, 1969, -1, 1979, 1980, 1981, -1, 1981, 1980, 1863, -1, 1965, 1982, 1959, -1, 1980, 1983, 1863, -1, 1959, 1982, 1974, -1, 1863, 1983, 1864, -1, 1864, 1983, 1868, -1, 1970, 1984, 1963, -1, 1954, 1984, 1970, -1, 1985, 1984, 1954, -1, 1963, 1984, 1976, -1, 1868, 1986, 1870, -1, 1974, 1987, 1967, -1, 1870, 1986, 1872, -1, 1967, 1987, 1978, -1, 1868, 1988, 1986, -1, 1971, 1989, 1965, -1, 1965, 1989, 1982, -1, 1983, 1988, 1868, -1, 1872, 1990, 1874, -1, 1986, 1990, 1872, -1, 1982, 1991, 1974, -1, 1974, 1991, 1987, -1, 1986, 1992, 1990, -1, 1988, 1992, 1986, -1, 1976, 1993, 1971, -1, 1992, 1994, 1990, -1, 1971, 1993, 1989, -1, 1988, 1995, 1992, -1, 1978, 1996, 1969, -1, 1994, 1997, 1990, -1, 1874, 1997, 1876, -1, 1990, 1997, 1874, -1, 1969, 1996, 1998, -1, 1876, 1997, 1999, -1, 1999, 2000, 2001, -1, 1992, 2000, 1994, -1, 1982, 2002, 1991, -1, 1994, 2000, 1997, -1, 1989, 2002, 1982, -1, 1995, 2000, 1992, -1, 1997, 2000, 1999, -1, 2001, 2003, 1999, -1, 1976, 2004, 1993, -1, 1985, 2004, 1984, -1, 1984, 2004, 1976, -1, 1999, 2003, 1876, -1, 1987, 2005, 1978, -1, 1978, 2005, 1996, -1, 2003, 2006, 1876, -1, 1877, 2006, 1879, -1, 1876, 2006, 1877, -1, 1879, 2007, 1881, -1, 1993, 2008, 1989, -1, 1989, 2008, 2002, -1, 1881, 2007, 1884, -1, 1996, 2009, 1998, -1, 2007, 2010, 1884, -1, 1884, 2010, 1885, -1, 1987, 2011, 2005, -1, 1991, 2011, 1987, -1, 2006, 2012, 1879, -1, 2013, 2014, 1985, -1, 1879, 2012, 2007, -1, 1985, 2014, 2004, -1, 2004, 2014, 1993, -1, 2012, 2015, 2007, -1, 1993, 2014, 2008, -1, 2007, 2015, 2010, -1, 2015, 2016, 2010, -1, 2005, 2017, 1996, -1, 1996, 2017, 2009, -1, 2002, 2018, 1991, -1, 2012, 2019, 2015, -1, 2010, 2020, 1885, -1, 1991, 2018, 2011, -1, 2016, 2020, 2010, -1, 1889, 2020, 2021, -1, 1885, 2020, 1889, -1, 2011, 2022, 2005, -1, 2015, 2023, 2016, -1, 2005, 2022, 2017, -1, 2019, 2023, 2015, -1, 2016, 2023, 2020, -1, 2020, 2023, 2021, -1, 2008, 2024, 2002, -1, 2021, 2023, 2025, -1, 2002, 2024, 2018, -1, 2021, 2026, 1889, -1, 2025, 2026, 2021, -1, 1998, 2027, 2028, -1, 2009, 2027, 1998, -1, 2026, 2029, 1889, -1, 1889, 2029, 1890, -1, 2018, 2030, 2011, -1, 1890, 2031, 1893, -1, 2011, 2030, 2022, -1, 1893, 2031, 1896, -1, 2013, 2032, 2014, -1, 1896, 2033, 1897, -1, 2014, 2032, 2008, -1, 2008, 2032, 2024, -1, 2031, 2033, 1896, -1, 1890, 2034, 2031, -1, 2017, 2035, 2009, -1, 2009, 2035, 2027, -1, 2029, 2034, 1890, -1, 2018, 2036, 2030, -1, 2034, 2037, 2031, -1, 2031, 2037, 2033, -1, 2024, 2036, 2018, -1, 2037, 2038, 2033, -1, 2027, 2039, 2028, -1, 2017, 2040, 2035, -1, 2034, 2041, 2037, -1, 2033, 2042, 1897, -1, 2043, 2042, 2044, -1, 2022, 2040, 2017, -1, 2038, 2042, 2033, -1, 2013, 2045, 2032, -1, 1897, 2042, 2043, -1, 2024, 2045, 2036, -1, 2044, 2046, 2047, -1, 2048, 2045, 2013, -1, 2037, 2046, 2038, -1, 2032, 2045, 2024, -1, 2041, 2046, 2037, -1, 2042, 2046, 2044, -1, 2038, 2046, 2042, -1, 2027, 2049, 2039, -1, 1902, 2050, 2051, -1, 2035, 2049, 2027, -1, 2051, 2050, 2052, -1, 2022, 2053, 2040, -1, 1904, 2054, 1901, -1, 1902, 2054, 2050, -1, 1901, 2054, 1902, -1, 2030, 2053, 2022, -1, 2040, 2055, 2035, -1, 2035, 2055, 2049, -1, 1904, 2056, 2054, -1, 2030, 2057, 2053, -1, 2036, 2057, 2030, -1, 2040, 2058, 2055, -1, 2053, 2058, 2040, -1, 1906, 2059, 1904, -1, 1904, 2059, 2056, -1, 2060, 2061, 1912, -1, 2039, 2062, 2028, -1, 2063, 2061, 2060, -1, 1909, 2064, 1906, -1, 1912, 2064, 1909, -1, 1906, 2064, 2059, -1, 2028, 2062, 2065, -1, 2061, 2064, 1912, -1, 2059, 2064, 2061, -1, 2045, 2066, 2036, -1, 2048, 2066, 2045, -1, 2036, 2066, 2057, -1, 1912, 2067, 2060, -1, 2060, 2067, 2063, -1, 2053, 2068, 2058, -1, 1911, 2069, 1912, -1, 2057, 2068, 2053, -1, 1914, 2069, 1911, -1, 1912, 2069, 2067, -1, 2049, 2070, 2039, -1, 2039, 2070, 2062, -1, 1914, 2071, 2069, -1, 2062, 2072, 2065, -1, 1914, 2073, 2071, -1, 1916, 2073, 1914, -1, 2048, 2074, 2066, -1, 2075, 2074, 2048, -1, 2066, 2074, 2057, -1, 2057, 2074, 2068, -1, 2055, 2076, 2049, -1, 2077, 2078, 2079, -1, 2079, 2078, 2080, -1, 1916, 2081, 2073, -1, 2049, 2076, 2070, -1, 2073, 2081, 2078, -1, 2078, 2081, 2080, -1, 1918, 2081, 1916, -1, 2080, 2081, 1918, -1, 2062, 2082, 2072, -1, 1810, 2083, 1806, -1, 2070, 2082, 2062, -1, 1811, 2083, 1810, -1, 2058, 2084, 2055, -1, 2055, 2084, 2076, -1, 1919, 2085, 1922, -1, 2083, 2085, 1806, -1, 1806, 2085, 1919, -1, 2076, 2086, 2070, -1, 2070, 2086, 2082, -1, 1922, 2087, 1925, -1, 1925, 2087, 1927, -1, 2068, 2088, 2058, -1, 2058, 2088, 2084, -1, 2085, 2089, 1922, -1, 1922, 2089, 2087, -1, 2076, 2090, 2086, -1, 2084, 2090, 2076, -1, 2087, 2091, 1927, -1, 1927, 2091, 1929, -1, 2072, 1865, 2065, -1, 2087, 2092, 2091, -1, 2065, 1865, 1866, -1, 2089, 2092, 2087, -1, 2092, 2093, 2091, -1, 2075, 2094, 2074, -1, 2089, 2095, 2092, -1, 2074, 2094, 2068, -1, 2068, 2094, 2088, -1, 1929, 2096, 1930, -1, 2091, 2096, 1929, -1, 2088, 2097, 2084, -1, 2093, 2096, 2091, -1, 2084, 2097, 2090, -1, 1930, 2096, 2098, -1, 2098, 2099, 1649, -1, 2072, 1863, 1865, -1, 2092, 2099, 2093, -1, 2082, 1863, 2072, -1, 2095, 2099, 2092, -1, 2093, 2099, 2096, -1, 2096, 2099, 2098, -1, 1649, 2100, 2098, -1, 2075, 2101, 2094, -1, 2102, 2101, 2075, -1, 2098, 2100, 1930, -1, 2094, 2101, 2088, -1, 2088, 2101, 2097, -1, 1930, 2103, 1931, -1, 2086, 1981, 2082, -1, 2082, 1981, 1863, -1, 1931, 2103, 1934, -1, 2100, 2103, 1930, -1, 2086, 1979, 1981, -1, 1934, 2104, 1937, -1, 2090, 1979, 2086, -1, 1937, 2104, 1940, -1, 2097, 2105, 2090, -1, 1940, 2106, 1941, -1, 2104, 2106, 1940, -1, 2090, 2105, 1979, -1, 2103, 2107, 1934, -1, 1934, 2107, 2104, -1, 2102, 2108, 2101, -1, 2104, 2109, 2106, -1, 2101, 2108, 2097, -1, 2107, 2109, 2104, -1, 2097, 2108, 2105, -1, 2109, 2110, 2106, -1, 2107, 2111, 2109, -1, 1941, 2112, 1943, -1, 1943, 2112, 2113, -1, 2106, 2112, 1941, -1, 2110, 2112, 2106, -1, 2113, 2114, 1670, -1, 2112, 2114, 2113, -1, 2109, 2114, 2110, -1, 2111, 2114, 2109, -1, 2110, 2114, 2112, -1, 2113, 2115, 1943, -1, 1670, 2115, 2113, -1, 1943, 2116, 1945, -1, 2115, 2116, 1943, -1, 1948, 2117, 1949, -1, 1945, 2117, 1948, -1, 1949, 2118, 1825, -1, 2117, 2118, 1949, -1, 2116, 2119, 1945, -1, 1945, 2119, 2117, -1, 2117, 2120, 2118, -1, 2119, 2120, 2117, -1, 2120, 2121, 2118, -1, 2119, 2122, 2120, -1, 1825, 2123, 1827, -1, 1827, 2123, 1834, -1, 2118, 2123, 1825, -1, 2121, 2123, 2118, -1, 2122, 2124, 2120, -1, 2123, 2124, 1834, -1, 1834, 2124, 1689, -1, 2121, 2124, 2123, -1, 2120, 2124, 2121, -1, 1953, 2125, 1951, -1, 1957, 2125, 1953, -1, 1951, 2125, 1800, -1, 1800, 2125, 1797, -1, 1957, 2126, 2125, -1, 1960, 2127, 1961, -1, 1958, 2127, 1957, -1, 1961, 2127, 1958, -1, 2128, 2127, 1960, -1, 1957, 2127, 2126, -1, 1966, 2129, 1960, -1, 1968, 2129, 1966, -1, 1972, 2129, 1968, -1, 1960, 2129, 2128, -1, 1972, 2130, 2129, -1, 1897, 2131, 1894, -1, 1817, 2132, 1819, -1, 1894, 2131, 2133, -1, 1819, 2132, 1975, -1, 1972, 2132, 2130, -1, 1973, 2132, 1972, -1, 1975, 2132, 1973, -1, 1979, 2134, 1980, -1, 1980, 2134, 1983, -1, 2105, 2134, 1979, -1, 1983, 2134, 1988, -1, 2134, 2135, 1988, -1, 2043, 2136, 1897, -1, 1897, 2136, 2131, -1, 2044, 2137, 2043, -1, 2043, 2137, 2136, -1, 2135, 2138, 1988, -1, 1988, 2138, 1995, -1, 2044, 2139, 2137, -1, 1995, 2138, 2000, -1, 2047, 2139, 2044, -1, 2000, 2138, 2001, -1, 2140, 2141, 2001, -1, 2001, 2141, 2003, -1, 2047, 2142, 2139, -1, 2003, 2141, 2006, -1, 2143, 2142, 2047, -1, 2006, 2141, 2012, -1, 2141, 2144, 2012, -1, 2131, 2145, 2133, -1, 2133, 2145, 2146, -1, 2144, 2147, 2012, -1, 2148, 2149, 2150, -1, 2150, 2149, 2151, -1, 2151, 2149, 2143, -1, 2023, 2147, 2025, -1, 2143, 2149, 2142, -1, 2012, 2147, 2019, -1, 2019, 2147, 2023, -1, 2152, 2153, 2025, -1, 2136, 2154, 2131, -1, 2025, 2153, 2026, -1, 2026, 2153, 2029, -1, 2131, 2154, 2145, -1, 2029, 2153, 2034, -1, 2137, 2155, 2136, -1, 2153, 2156, 2034, -1, 2136, 2155, 2154, -1, 2139, 2157, 2137, -1, 2137, 2157, 2155, -1, 2156, 2158, 2034, -1, 2034, 2158, 2041, -1, 2046, 2158, 2047, -1, 2041, 2158, 2046, -1, 2142, 2159, 2139, -1, 2139, 2159, 2157, -1, 2056, 2160, 2054, -1, 2054, 2160, 2050, -1, 2052, 2160, 2161, -1, 2145, 2162, 2146, -1, 2050, 2160, 2052, -1, 2146, 2162, 2163, -1, 2164, 2165, 2148, -1, 2142, 2165, 2159, -1, 2056, 2166, 2160, -1, 2148, 2165, 2149, -1, 2149, 2165, 2142, -1, 2167, 2168, 2063, -1, 2059, 2168, 2056, -1, 2063, 2168, 2061, -1, 2154, 2169, 2145, -1, 2056, 2168, 2166, -1, 2061, 2168, 2059, -1, 2067, 2170, 2063, -1, 2145, 2169, 2162, -1, 2071, 2170, 2069, -1, 2063, 2170, 2167, -1, 2155, 2171, 2154, -1, 2069, 2170, 2067, -1, 2154, 2171, 2169, -1, 2157, 2172, 2155, -1, 2155, 2172, 2171, -1, 2071, 2173, 2170, -1, 2073, 2174, 2071, -1, 2078, 2174, 2073, -1, 2077, 2174, 2078, -1, 2071, 2174, 2173, -1, 2159, 2175, 2157, -1, 2157, 2175, 2172, -1, 2176, 2174, 2077, -1, 2163, 2177, 2178, -1, 2083, 1642, 2085, -1, 1811, 1642, 2083, -1, 2162, 2177, 2163, -1, 2085, 1642, 2089, -1, 1630, 1642, 1811, -1, 2159, 2179, 2175, -1, 2180, 2179, 2164, -1, 2164, 2179, 2165, -1, 1642, 1643, 2089, -1, 2165, 2179, 2159, -1, 2162, 2161, 2177, -1, 2169, 2161, 2162, -1, 2089, 1652, 2095, -1, 2099, 1652, 1649, -1, 2095, 1652, 2099, -1, 1643, 1652, 2089, -1, 2169, 2052, 2161, -1, 1651, 1664, 1649, -1, 2171, 2052, 2169, -1, 1649, 1664, 2100, -1, 2100, 1664, 2103, -1, 2103, 1664, 2107, -1, 2171, 2051, 2052, -1, 2172, 2051, 2171, -1, 1664, 1665, 2107, -1, 2175, 1902, 2172, -1, 2172, 1902, 2051, -1, 1665, 1673, 2107, -1, 2107, 1673, 2111, -1, 2114, 1673, 1670, -1, 2111, 1673, 2114, -1, 1672, 1684, 1670, -1, 2180, 1900, 2179, -1, 2175, 1900, 1902, -1, 1670, 1684, 2115, -1, 2116, 1684, 2119, -1, 1903, 1900, 2180, -1, 2115, 1684, 2116, -1, 2179, 1900, 2175, -1, 1684, 1685, 2119, -1, 2119, 1692, 2122, -1, 2124, 1692, 1689, -1, 1685, 1692, 2119, -1, 2122, 1692, 2124, -1, 1797, 2181, 1792, -1, 1792, 2181, 1793, -1, 1797, 2182, 2181, -1, 2125, 2182, 1797, -1, 2126, 2182, 2125, -1, 2126, 2183, 2182, -1, 1793, 2183, 2184, -1, 2181, 2183, 1793, -1, 2182, 2183, 2181, -1, 2127, 2185, 2126, -1, 2128, 2185, 2127, -1, 2126, 2185, 2183, -1, 2183, 2186, 2184, -1, 2128, 2186, 2185, -1, 2187, 2186, 2128, -1, 2185, 2186, 2183, -1, 2184, 2186, 2187, -1, 2128, 2188, 2187, -1, 1623, 2189, 1621, -1, 1621, 2189, 2190, -1, 2187, 2188, 2184, -1, 2129, 2191, 2128, -1, 2128, 2191, 2188, -1, 2130, 2191, 2129, -1, 2188, 2192, 2184, -1, 2176, 2193, 1623, -1, 2191, 2192, 2188, -1, 2184, 2192, 1814, -1, 1623, 2193, 2189, -1, 2130, 2192, 2191, -1, 2132, 2194, 2130, -1, 2130, 2194, 2192, -1, 1817, 2194, 2132, -1, 2194, 2195, 2192, -1, 2192, 2195, 1814, -1, 1817, 2195, 2194, -1, 1812, 2195, 1817, -1, 2176, 2196, 2193, -1, 1814, 2195, 1812, -1, 2108, 2197, 2105, -1, 2077, 2196, 2176, -1, 2102, 2197, 2108, -1, 2105, 2198, 2134, -1, 2134, 2198, 2135, -1, 2079, 2199, 2077, -1, 2197, 2198, 2105, -1, 2102, 2198, 2197, -1, 2198, 2200, 2135, -1, 2077, 2199, 2196, -1, 2201, 2200, 2102, -1, 2189, 2202, 2190, -1, 2102, 2200, 2198, -1, 2138, 2203, 2001, -1, 2001, 2203, 2140, -1, 2140, 2203, 2204, -1, 2200, 2205, 2135, -1, 2135, 2205, 2138, -1, 2079, 2206, 2199, -1, 2138, 2205, 2203, -1, 2201, 2205, 2200, -1, 2080, 2206, 2079, -1, 2204, 2207, 2201, -1, 2203, 2207, 2204, -1, 2189, 2208, 2202, -1, 2201, 2207, 2205, -1, 2193, 2208, 2189, -1, 2205, 2207, 2203, -1, 2201, 2209, 2204, -1, 2202, 2210, 2190, -1, 2204, 2209, 2140, -1, 2201, 2211, 2209, -1, 2140, 2211, 2141, -1, 2190, 2210, 2212, -1, 2141, 2211, 2144, -1, 1915, 2213, 1918, -1, 2209, 2211, 2140, -1, 1918, 2213, 2080, -1, 2080, 2213, 2206, -1, 2214, 2215, 2201, -1, 2193, 2216, 2208, -1, 2196, 2216, 2193, -1, 2201, 2215, 2211, -1, 2211, 2215, 2144, -1, 2147, 2217, 2025, -1, 2025, 2217, 2152, -1, 2152, 2217, 2218, -1, 2202, 2219, 2210, -1, 2208, 2219, 2202, -1, 2214, 2220, 2215, -1, 2144, 2220, 2147, -1, 2147, 2220, 2217, -1, 2199, 2221, 2196, -1, 2215, 2220, 2144, -1, 2196, 2221, 2216, -1, 2218, 2222, 2214, -1, 2217, 2222, 2218, -1, 2214, 2222, 2220, -1, 2220, 2222, 2217, -1, 2218, 2223, 2152, -1, 2216, 2224, 2208, -1, 2214, 2223, 2218, -1, 2208, 2224, 2219, -1, 2206, 2225, 2199, -1, 2223, 2226, 2152, -1, 2199, 2225, 2221, -1, 2152, 2226, 2153, -1, 2214, 2226, 2223, -1, 2153, 2226, 2156, -1, 2210, 2227, 2212, -1, 2150, 2228, 2214, -1, 2214, 2228, 2226, -1, 2226, 2228, 2156, -1, 2047, 2229, 2143, -1, 2216, 2230, 2224, -1, 2158, 2229, 2047, -1, 2221, 2230, 2216, -1, 2228, 2231, 2156, -1, 1631, 2232, 1915, -1, 2156, 2231, 2158, -1, 2206, 2232, 2225, -1, 2150, 2231, 2228, -1, 1915, 2232, 2213, -1, 2158, 2231, 2229, -1, 2213, 2232, 2206, -1, 2151, 2233, 2150, -1, 2143, 2233, 2151, -1, 2229, 2233, 2143, -1, 2219, 2234, 2210, -1, 2150, 2233, 2231, -1, 2231, 2233, 2229, -1, 2210, 2234, 2227, -1, 2161, 2235, 2177, -1, 2225, 1635, 2221, -1, 2177, 2235, 2178, -1, 2221, 1635, 2230, -1, 2161, 2236, 2235, -1, 2166, 2236, 2160, -1, 2212, 1639, 1655, -1, 2160, 2236, 2161, -1, 2227, 1639, 2212, -1, 2178, 2237, 2238, -1, 2219, 1624, 2234, -1, 2235, 2237, 2178, -1, 2166, 2237, 2236, -1, 2224, 1624, 2219, -1, 2236, 2237, 2235, -1, 2232, 1633, 2225, -1, 2167, 2239, 2168, -1, 2225, 1633, 1635, -1, 2168, 2239, 2166, -1, 1631, 1633, 2232, -1, 2166, 2239, 2237, -1, 2234, 1644, 2227, -1, 2240, 2241, 2167, -1, 2227, 1644, 1639, -1, 2238, 2241, 2240, -1, 2237, 2241, 2238, -1, 2167, 2241, 2239, -1, 2239, 2241, 2237, -1, 2167, 2242, 2240, -1, 2240, 2242, 2238, -1, 2230, 1647, 2224, -1, 2224, 1647, 1624, -1, 2170, 2243, 2167, -1, 2234, 1626, 1644, -1, 2173, 2243, 2170, -1, 2167, 2243, 2242, -1, 2243, 1627, 2242, -1, 1624, 1626, 2234, -1, 1635, 1636, 2230, -1, 2242, 1627, 2238, -1, 2238, 1627, 1621, -1, 2173, 1627, 2243, -1, 2230, 1636, 1647, -1, 2173, 2244, 1627, -1, 1639, 1641, 1655, -1, 2174, 2244, 2173, -1, 2176, 2244, 2174, -1, 2244, 1622, 1627, -1, 2176, 1622, 2244, -1, 1623, 1622, 2176, -1, 1647, 1625, 1624, -1, 2245, 2246, 2247, -1, 2248, 2249, 2250, -1, 2251, 2249, 2248, -1, 2250, 2249, 2252, -1, 2247, 2253, 2254, -1, 2255, 2256, 2257, -1, 2246, 2253, 2247, -1, 2258, 2256, 2255, -1, 2254, 2253, 2259, -1, 2253, 2260, 2259, -1, 2261, 2260, 2262, -1, 2262, 2260, 2246, -1, 2263, 2264, 2265, -1, 2252, 2264, 2263, -1, 2246, 2260, 2253, -1, 2259, 2266, 2267, -1, 2257, 2268, 2269, -1, 2267, 2266, 2270, -1, 2260, 2266, 2259, -1, 2266, 2271, 2270, -1, 2260, 2271, 2266, -1, 2272, 2271, 2261, -1, 2273, 2274, 2258, -1, 2270, 2271, 2272, -1, 2261, 2271, 2260, -1, 2275, 2276, 2277, -1, 2258, 2274, 2256, -1, 2278, 2276, 2275, -1, 2279, 2280, 2251, -1, 2249, 2280, 2252, -1, 2252, 2280, 2264, -1, 2251, 2280, 2249, -1, 2278, 2281, 2276, -1, 2282, 2281, 2278, -1, 2256, 2283, 2257, -1, 2284, 2281, 2282, -1, 2276, 2281, 2277, -1, 2257, 2283, 2268, -1, 2281, 2285, 2277, -1, 2273, 2286, 2274, -1, 2284, 2285, 2281, -1, 2265, 2286, 2273, -1, 2277, 2285, 2287, -1, 2285, 2288, 2287, -1, 2256, 2289, 2283, -1, 2284, 2288, 2285, -1, 2290, 2291, 2292, -1, 2293, 2288, 2284, -1, 2288, 2294, 2287, -1, 2274, 2289, 2256, -1, 2264, 2295, 2265, -1, 2287, 2294, 2296, -1, 2293, 2297, 2288, -1, 2265, 2295, 2286, -1, 2288, 2297, 2294, -1, 2294, 2297, 2296, -1, 2298, 2297, 2293, -1, 2296, 2297, 2299, -1, 2299, 2297, 2298, -1, 2268, 2300, 2269, -1, 2269, 2300, 2301, -1, 2299, 2302, 2296, -1, 2296, 2302, 2287, -1, 2299, 2303, 2302, -1, 2286, 2304, 2274, -1, 2302, 2303, 2287, -1, 2305, 2303, 2306, -1, 2274, 2304, 2289, -1, 2306, 2303, 2299, -1, 2279, 2307, 2280, -1, 2280, 2307, 2264, -1, 2264, 2307, 2295, -1, 2303, 2308, 2287, -1, 2305, 2308, 2303, -1, 2287, 2308, 2309, -1, 2283, 2310, 2268, -1, 2305, 2311, 2308, -1, 2308, 2311, 2309, -1, 2268, 2310, 2300, -1, 2312, 2311, 2305, -1, 2309, 2313, 2314, -1, 2295, 2315, 2286, -1, 2311, 2313, 2309, -1, 2286, 2315, 2304, -1, 2314, 2316, 2317, -1, 2317, 2316, 2318, -1, 2312, 2316, 2311, -1, 2313, 2316, 2314, -1, 2311, 2316, 2313, -1, 2289, 2319, 2283, -1, 2318, 2316, 2312, -1, 2314, 2320, 2309, -1, 2283, 2319, 2310, -1, 2317, 2320, 2314, -1, 2300, 2321, 2301, -1, 2317, 2322, 2320, -1, 2320, 2322, 2309, -1, 2323, 2322, 2317, -1, 2324, 2325, 2279, -1, 2279, 2325, 2307, -1, 2326, 2322, 2323, -1, 2307, 2325, 2295, -1, 2295, 2325, 2315, -1, 2322, 2327, 2309, -1, 2289, 2328, 2319, -1, 2326, 2327, 2322, -1, 2304, 2328, 2289, -1, 2309, 2327, 2329, -1, 2327, 2330, 2329, -1, 2326, 2330, 2327, -1, 2300, 2331, 2321, -1, 2332, 2330, 2326, -1, 2329, 2333, 2334, -1, 2310, 2331, 2300, -1, 2334, 2333, 2335, -1, 2330, 2333, 2329, -1, 2335, 2336, 2337, -1, 2337, 2336, 2332, -1, 2304, 2338, 2328, -1, 2332, 2336, 2330, -1, 2333, 2336, 2335, -1, 2315, 2338, 2304, -1, 2330, 2336, 2333, -1, 2310, 2339, 2331, -1, 2319, 2339, 2310, -1, 2301, 2340, 2341, -1, 2321, 2340, 2301, -1, 2315, 2342, 2338, -1, 2324, 2342, 2325, -1, 2325, 2342, 2315, -1, 2319, 2343, 2339, -1, 2328, 2343, 2319, -1, 2321, 2344, 2340, -1, 2331, 2344, 2321, -1, 2328, 2345, 2343, -1, 2338, 2345, 2328, -1, 2339, 2346, 2331, -1, 2331, 2346, 2344, -1, 2340, 2347, 2341, -1, 2324, 2348, 2342, -1, 2349, 2348, 2324, -1, 2338, 2348, 2345, -1, 2342, 2348, 2338, -1, 2339, 2350, 2346, -1, 2343, 2350, 2339, -1, 2344, 2351, 2340, -1, 2340, 2351, 2347, -1, 2343, 2352, 2350, -1, 2345, 2352, 2343, -1, 2347, 2353, 2341, -1, 2341, 2353, 2354, -1, 2344, 2355, 2351, -1, 2346, 2355, 2344, -1, 2348, 2356, 2345, -1, 2349, 2356, 2348, -1, 2345, 2356, 2352, -1, 2347, 2357, 2353, -1, 2351, 2357, 2347, -1, 2350, 2358, 2346, -1, 2346, 2358, 2355, -1, 2355, 2359, 2351, -1, 2351, 2359, 2357, -1, 2350, 2360, 2358, -1, 2352, 2360, 2350, -1, 2353, 2361, 2354, -1, 2358, 2362, 2355, -1, 2355, 2362, 2359, -1, 2349, 2363, 2356, -1, 2364, 2363, 2349, -1, 2356, 2363, 2352, -1, 2352, 2363, 2360, -1, 2357, 2365, 2353, -1, 2353, 2365, 2361, -1, 2360, 2366, 2358, -1, 2358, 2366, 2362, -1, 2361, 2367, 2354, -1, 2354, 2367, 2368, -1, 2357, 2369, 2365, -1, 2359, 2369, 2357, -1, 2364, 2370, 2363, -1, 2360, 2370, 2366, -1, 2363, 2370, 2360, -1, 2365, 2371, 2361, -1, 2361, 2371, 2367, -1, 2362, 2372, 2359, -1, 2359, 2372, 2369, -1, 2369, 2373, 2365, -1, 2365, 2373, 2371, -1, 2366, 2374, 2362, -1, 2362, 2374, 2372, -1, 2367, 2375, 2368, -1, 2372, 2376, 2369, -1, 2369, 2376, 2373, -1, 2377, 2378, 2364, -1, 2366, 2378, 2374, -1, 2364, 2378, 2370, -1, 2370, 2378, 2366, -1, 2371, 2379, 2367, -1, 2367, 2379, 2375, -1, 2372, 2380, 2376, -1, 2374, 2380, 2372, -1, 2375, 2381, 2368, -1, 2368, 2381, 2382, -1, 2373, 2383, 2371, -1, 2371, 2383, 2379, -1, 2374, 2384, 2380, -1, 2378, 2384, 2374, -1, 2377, 2384, 2378, -1, 2375, 2385, 2381, -1, 2379, 2385, 2375, -1, 2373, 2386, 2383, -1, 2376, 2386, 2373, -1, 2387, 2388, 2389, -1, 2383, 2390, 2379, -1, 2379, 2390, 2385, -1, 2391, 2392, 2393, -1, 2380, 2394, 2376, -1, 2393, 2392, 2395, -1, 2376, 2394, 2386, -1, 2396, 2397, 2391, -1, 2383, 2398, 2390, -1, 2386, 2398, 2383, -1, 2391, 2397, 2392, -1, 2396, 2399, 2397, -1, 2381, 2400, 2382, -1, 2401, 2399, 2396, -1, 2384, 2402, 2380, -1, 2403, 2402, 2377, -1, 2404, 2405, 2401, -1, 2377, 2402, 2384, -1, 2401, 2405, 2399, -1, 2380, 2402, 2394, -1, 2406, 2407, 2404, -1, 2394, 2408, 2386, -1, 2386, 2408, 2398, -1, 2404, 2407, 2405, -1, 2385, 2409, 2381, -1, 2392, 2410, 2395, -1, 2381, 2409, 2400, -1, 2395, 2410, 2411, -1, 2291, 2412, 2292, -1, 2406, 2412, 2407, -1, 2400, 2413, 2382, -1, 2292, 2412, 2406, -1, 2382, 2413, 2277, -1, 2397, 2414, 2392, -1, 2392, 2414, 2410, -1, 2403, 2415, 2402, -1, 2402, 2415, 2394, -1, 2394, 2415, 2408, -1, 2390, 2416, 2385, -1, 2385, 2416, 2409, -1, 2397, 2417, 2414, -1, 2409, 2418, 2400, -1, 2399, 2417, 2397, -1, 2400, 2418, 2413, -1, 2405, 2419, 2399, -1, 2398, 2420, 2390, -1, 2399, 2419, 2417, -1, 2390, 2420, 2416, -1, 2407, 2421, 2405, -1, 2405, 2421, 2419, -1, 2409, 2422, 2418, -1, 2416, 2422, 2409, -1, 2411, 2423, 2424, -1, 2398, 2425, 2420, -1, 2410, 2423, 2411, -1, 2408, 2425, 2398, -1, 2412, 2426, 2407, -1, 2291, 2426, 2412, -1, 2407, 2426, 2421, -1, 2427, 2426, 2291, -1, 2420, 2428, 2416, -1, 2416, 2428, 2422, -1, 2414, 2429, 2410, -1, 2413, 2275, 2277, -1, 2410, 2429, 2423, -1, 2430, 2431, 2403, -1, 2403, 2431, 2415, -1, 2415, 2431, 2408, -1, 2408, 2431, 2425, -1, 2414, 2432, 2429, -1, 2417, 2432, 2414, -1, 2425, 2433, 2420, -1, 2417, 2434, 2432, -1, 2419, 2434, 2417, -1, 2420, 2433, 2428, -1, 2413, 2278, 2275, -1, 2419, 2435, 2434, -1, 2418, 2278, 2413, -1, 2421, 2435, 2419, -1, 2425, 2436, 2433, -1, 2431, 2436, 2425, -1, 2430, 2436, 2431, -1, 2418, 2437, 2278, -1, 2427, 2438, 2426, -1, 2426, 2438, 2421, -1, 2422, 2437, 2418, -1, 2439, 2438, 2427, -1, 2421, 2438, 2435, -1, 2428, 2440, 2422, -1, 2422, 2440, 2437, -1, 2433, 2441, 2428, -1, 2428, 2441, 2440, -1, 2442, 2443, 2430, -1, 2430, 2443, 2436, -1, 2436, 2443, 2433, -1, 2433, 2443, 2441, -1, 2444, 2445, 2446, -1, 2447, 2448, 2444, -1, 2444, 2448, 2445, -1, 2449, 2450, 2447, -1, 2447, 2450, 2448, -1, 2449, 2451, 2450, -1, 2452, 2451, 2449, -1, 2446, 2453, 2454, -1, 2455, 2334, 2456, -1, 2445, 2453, 2446, -1, 2457, 2458, 2452, -1, 2329, 2334, 2455, -1, 2452, 2458, 2451, -1, 2456, 2335, 2459, -1, 2448, 2460, 2445, -1, 2334, 2335, 2456, -1, 2445, 2460, 2453, -1, 2453, 2461, 2454, -1, 2459, 2337, 2462, -1, 2463, 2464, 2465, -1, 2457, 2464, 2458, -1, 2465, 2464, 2466, -1, 2466, 2464, 2457, -1, 2450, 2467, 2448, -1, 2335, 2337, 2459, -1, 2462, 2468, 2469, -1, 2448, 2467, 2460, -1, 2337, 2468, 2462, -1, 2460, 2470, 2453, -1, 2453, 2470, 2461, -1, 2469, 2471, 2472, -1, 2468, 2471, 2469, -1, 2451, 2473, 2450, -1, 2450, 2473, 2467, -1, 2472, 2474, 2389, -1, 2471, 2474, 2472, -1, 2389, 2474, 2387, -1, 2467, 2475, 2460, -1, 2429, 2476, 2423, -1, 2460, 2475, 2470, -1, 2423, 2476, 2424, -1, 2476, 2477, 2424, -1, 2451, 2478, 2473, -1, 2458, 2478, 2451, -1, 2477, 2479, 2424, -1, 2454, 2480, 2481, -1, 2461, 2480, 2454, -1, 2424, 2479, 2482, -1, 2482, 2479, 2483, -1, 2473, 2484, 2467, -1, 2483, 2485, 2482, -1, 2486, 2485, 2483, -1, 2467, 2484, 2475, -1, 2458, 2487, 2478, -1, 2485, 2488, 2482, -1, 2463, 2487, 2464, -1, 2464, 2487, 2458, -1, 2461, 2489, 2480, -1, 2446, 2490, 2444, -1, 2470, 2489, 2461, -1, 2482, 2490, 2446, -1, 2488, 2490, 2482, -1, 2473, 2491, 2484, -1, 2492, 2493, 2494, -1, 2478, 2491, 2473, -1, 2495, 2493, 2492, -1, 2480, 2496, 2481, -1, 2495, 2497, 2493, -1, 2470, 2498, 2489, -1, 2495, 2499, 2497, -1, 2475, 2498, 2470, -1, 2463, 2500, 2487, -1, 2478, 2500, 2491, -1, 2501, 2500, 2463, -1, 2487, 2500, 2478, -1, 2489, 2502, 2480, -1, 2503, 2504, 2505, -1, 2495, 2504, 2499, -1, 2505, 2504, 2495, -1, 2480, 2502, 2496, -1, 2503, 2506, 2507, -1, 2505, 2506, 2503, -1, 2475, 2508, 2498, -1, 2484, 2508, 2475, -1, 2489, 2509, 2502, -1, 2505, 2510, 2506, -1, 2505, 2511, 2510, -1, 2498, 2509, 2489, -1, 2512, 2511, 2505, -1, 2491, 2513, 2484, -1, 2514, 2515, 2512, -1, 2484, 2513, 2508, -1, 2496, 2516, 2481, -1, 2512, 2515, 2511, -1, 2512, 2517, 2514, -1, 2514, 2517, 2518, -1, 2481, 2516, 2519, -1, 2508, 2520, 2498, -1, 2498, 2520, 2509, -1, 2512, 2521, 2517, -1, 2500, 2522, 2491, -1, 2501, 2522, 2500, -1, 2517, 2521, 2518, -1, 2491, 2522, 2513, -1, 2523, 2524, 2512, -1, 2512, 2524, 2521, -1, 2496, 2525, 2516, -1, 2502, 2525, 2496, -1, 2526, 2527, 2523, -1, 2523, 2527, 2524, -1, 2528, 2529, 2530, -1, 2508, 2531, 2520, -1, 2513, 2531, 2508, -1, 2532, 2529, 2528, -1, 2516, 2533, 2519, -1, 2509, 2534, 2502, -1, 2529, 2535, 2530, -1, 2535, 2536, 2530, -1, 2502, 2534, 2525, -1, 2537, 2536, 2538, -1, 2530, 2536, 2537, -1, 2538, 2539, 2537, -1, 2501, 2540, 2522, -1, 2541, 2539, 2538, -1, 2542, 2540, 2501, -1, 2522, 2540, 2513, -1, 2513, 2540, 2531, -1, 2525, 2543, 2516, -1, 2539, 2544, 2537, -1, 2516, 2543, 2533, -1, 2520, 2545, 2509, -1, 2509, 2545, 2534, -1, 2546, 2547, 2548, -1, 2544, 2547, 2537, -1, 2537, 2547, 2546, -1, 2443, 2549, 2441, -1, 2534, 2550, 2525, -1, 2525, 2550, 2543, -1, 2442, 2549, 2443, -1, 2520, 2551, 2545, -1, 2531, 2551, 2520, -1, 2442, 2552, 2549, -1, 2533, 2553, 2519, -1, 2519, 2553, 2554, -1, 2442, 2555, 2552, -1, 2556, 2557, 2442, -1, 2558, 2557, 2556, -1, 2534, 2559, 2550, -1, 2545, 2559, 2534, -1, 2442, 2557, 2555, -1, 2556, 2560, 2558, -1, 2542, 2561, 2540, -1, 2558, 2560, 2562, -1, 2540, 2561, 2531, -1, 2531, 2561, 2551, -1, 2543, 2563, 2533, -1, 2556, 2564, 2560, -1, 2533, 2563, 2553, -1, 2565, 2566, 2556, -1, 2551, 2567, 2545, -1, 2545, 2567, 2559, -1, 2556, 2566, 2564, -1, 2568, 2569, 2565, -1, 2543, 2570, 2563, -1, 2565, 2569, 2566, -1, 2550, 2570, 2543, -1, 2565, 2571, 2568, -1, 2568, 2571, 2572, -1, 2553, 2573, 2554, -1, 2574, 2575, 2542, -1, 2542, 2575, 2561, -1, 2571, 2576, 2572, -1, 2551, 2575, 2567, -1, 2561, 2575, 2551, -1, 2565, 2576, 2571, -1, 2387, 2577, 2565, -1, 2559, 2578, 2550, -1, 2565, 2577, 2576, -1, 2550, 2578, 2570, -1, 2474, 2579, 2387, -1, 2553, 2580, 2573, -1, 2387, 2579, 2577, -1, 2563, 2580, 2553, -1, 2432, 2581, 2429, -1, 2434, 2581, 2432, -1, 2559, 2582, 2578, -1, 2567, 2582, 2559, -1, 2429, 2583, 2476, -1, 2581, 2583, 2429, -1, 2563, 2584, 2580, -1, 2476, 2583, 2477, -1, 2570, 2584, 2563, -1, 2583, 2585, 2477, -1, 2554, 2586, 2587, -1, 2573, 2586, 2554, -1, 2567, 2588, 2582, -1, 2574, 2588, 2575, -1, 2479, 2589, 2483, -1, 2575, 2588, 2567, -1, 2483, 2589, 2486, -1, 2578, 2590, 2570, -1, 2477, 2591, 2479, -1, 2479, 2591, 2589, -1, 2585, 2591, 2477, -1, 2570, 2590, 2584, -1, 2589, 2592, 2486, -1, 2580, 2593, 2573, -1, 2486, 2592, 2594, -1, 2573, 2593, 2586, -1, 2591, 2592, 2589, -1, 2594, 2592, 2595, -1, 2582, 2596, 2578, -1, 2594, 2597, 2486, -1, 2595, 2597, 2594, -1, 2485, 2598, 2488, -1, 2578, 2596, 2590, -1, 2486, 2598, 2485, -1, 2597, 2598, 2486, -1, 2580, 2599, 2593, -1, 2584, 2599, 2580, -1, 2586, 2600, 2587, -1, 2598, 2601, 2488, -1, 2490, 2602, 2444, -1, 2574, 2603, 2588, -1, 2604, 2603, 2574, -1, 2444, 2602, 2447, -1, 2582, 2603, 2596, -1, 2588, 2603, 2582, -1, 2590, 2605, 2584, -1, 2490, 2606, 2602, -1, 2488, 2606, 2490, -1, 2601, 2606, 2488, -1, 2447, 2607, 2449, -1, 2584, 2605, 2599, -1, 2449, 2607, 2452, -1, 2586, 2608, 2600, -1, 2606, 2607, 2602, -1, 2602, 2607, 2447, -1, 2593, 2608, 2586, -1, 2596, 2609, 2590, -1, 2610, 2611, 2612, -1, 2590, 2609, 2605, -1, 2494, 2611, 2610, -1, 2497, 2613, 2493, -1, 2493, 2613, 2494, -1, 2600, 2614, 2587, -1, 2494, 2613, 2611, -1, 2587, 2614, 2615, -1, 2599, 2616, 2593, -1, 2593, 2616, 2608, -1, 2497, 2617, 2613, -1, 2596, 2618, 2609, -1, 2603, 2618, 2596, -1, 2604, 2618, 2603, -1, 2608, 2619, 2600, -1, 2600, 2619, 2614, -1, 2599, 2620, 2616, -1, 2605, 2620, 2599, -1, 2621, 2622, 2623, -1, 2616, 2624, 2608, -1, 2625, 2626, 2622, -1, 2608, 2624, 2619, -1, 2617, 2626, 2625, -1, 2497, 2627, 2617, -1, 2617, 2627, 2626, -1, 2504, 2627, 2499, -1, 2499, 2627, 2497, -1, 2605, 2628, 2620, -1, 2609, 2628, 2605, -1, 2626, 2629, 2622, -1, 2614, 2630, 2615, -1, 2627, 2631, 2626, -1, 2504, 2631, 2627, -1, 2620, 2632, 2616, -1, 2503, 2631, 2504, -1, 2626, 2631, 2629, -1, 2616, 2632, 2624, -1, 2622, 2633, 2623, -1, 2623, 2633, 2507, -1, 2507, 2633, 2503, -1, 2631, 2633, 2629, -1, 2503, 2633, 2631, -1, 2634, 2635, 2604, -1, 2629, 2633, 2622, -1, 2618, 2635, 2609, -1, 2604, 2635, 2618, -1, 2507, 2636, 2623, -1, 2609, 2635, 2628, -1, 2623, 2636, 2621, -1, 2614, 2637, 2630, -1, 2619, 2637, 2614, -1, 2507, 2638, 2636, -1, 2506, 2638, 2507, -1, 2628, 2639, 2620, -1, 2510, 2638, 2506, -1, 2620, 2639, 2632, -1, 2510, 2640, 2638, -1, 2615, 2641, 2642, -1, 2630, 2641, 2615, -1, 2624, 2643, 2619, -1, 2619, 2643, 2637, -1, 2628, 2644, 2639, -1, 2645, 2646, 2647, -1, 2634, 2644, 2635, -1, 2635, 2644, 2628, -1, 2640, 2648, 2649, -1, 2637, 2650, 2630, -1, 2649, 2648, 2646, -1, 2630, 2650, 2641, -1, 2632, 2651, 2624, -1, 2624, 2651, 2643, -1, 2510, 2652, 2640, -1, 2640, 2652, 2648, -1, 2511, 2652, 2510, -1, 2515, 2652, 2511, -1, 2648, 2653, 2646, -1, 2643, 2654, 2637, -1, 2637, 2654, 2650, -1, 2648, 2655, 2653, -1, 2652, 2655, 2648, -1, 2515, 2655, 2652, -1, 2632, 2656, 2651, -1, 2639, 2656, 2632, -1, 2514, 2655, 2515, -1, 2647, 2657, 2518, -1, 2518, 2657, 2514, -1, 2653, 2657, 2646, -1, 2641, 2658, 2642, -1, 2514, 2657, 2655, -1, 2655, 2657, 2653, -1, 2646, 2657, 2647, -1, 2647, 2659, 2645, -1, 2518, 2659, 2647, -1, 2651, 2660, 2643, -1, 2521, 2661, 2518, -1, 2643, 2660, 2654, -1, 2662, 2663, 2634, -1, 2634, 2663, 2644, -1, 2518, 2661, 2659, -1, 2644, 2663, 2639, -1, 2639, 2663, 2656, -1, 2650, 2664, 2641, -1, 2641, 2664, 2658, -1, 2521, 2665, 2661, -1, 2651, 2666, 2660, -1, 2656, 2666, 2651, -1, 2642, 2667, 2668, -1, 2658, 2667, 2642, -1, 2669, 2670, 2671, -1, 2654, 2672, 2650, -1, 2650, 2672, 2664, -1, 2665, 2673, 2674, -1, 2656, 2675, 2666, -1, 2674, 2673, 2670, -1, 2524, 2676, 2521, -1, 2662, 2675, 2663, -1, 2527, 2676, 2524, -1, 2663, 2675, 2656, -1, 2521, 2676, 2665, -1, 2665, 2676, 2673, -1, 2658, 2677, 2667, -1, 2673, 2678, 2670, -1, 2664, 2677, 2658, -1, 2526, 2679, 2527, -1, 2654, 2680, 2672, -1, 2527, 2679, 2676, -1, 2676, 2679, 2673, -1, 2673, 2679, 2678, -1, 2660, 2680, 2654, -1, 2670, 2681, 2671, -1, 2664, 2682, 2677, -1, 2671, 2681, 2683, -1, 2672, 2682, 2664, -1, 2679, 2681, 2678, -1, 2683, 2681, 2526, -1, 2526, 2681, 2679, -1, 2678, 2681, 2670, -1, 2666, 2684, 2660, -1, 2685, 2686, 2687, -1, 2660, 2684, 2680, -1, 2687, 2686, 2532, -1, 2532, 2688, 2529, -1, 2672, 2689, 2682, -1, 2529, 2688, 2535, -1, 2680, 2689, 2672, -1, 2686, 2688, 2532, -1, 2667, 2690, 2668, -1, 2688, 2691, 2535, -1, 2675, 2692, 2666, -1, 2536, 2693, 2538, -1, 2662, 2692, 2675, -1, 2538, 2693, 2541, -1, 2694, 2692, 2662, -1, 2666, 2692, 2684, -1, 2684, 2695, 2680, -1, 2536, 2696, 2693, -1, 2680, 2695, 2689, -1, 2535, 2696, 2536, -1, 2691, 2696, 2535, -1, 2696, 2697, 2693, -1, 2667, 2698, 2690, -1, 2541, 2697, 2699, -1, 2699, 2697, 2700, -1, 2693, 2697, 2541, -1, 2677, 2698, 2667, -1, 2699, 2701, 2541, -1, 2700, 2701, 2699, -1, 2690, 2702, 2668, -1, 2541, 2703, 2539, -1, 2668, 2702, 2704, -1, 2539, 2703, 2544, -1, 2692, 2705, 2684, -1, 2701, 2703, 2541, -1, 2684, 2705, 2695, -1, 2694, 2705, 2692, -1, 2682, 2706, 2677, -1, 2703, 2707, 2544, -1, 2677, 2706, 2698, -1, 2698, 2708, 2690, -1, 2690, 2708, 2702, -1, 2547, 2709, 2548, -1, 2548, 2709, 2710, -1, 2689, 2711, 2682, -1, 2547, 2712, 2709, -1, 2544, 2712, 2547, -1, 2682, 2711, 2706, -1, 2707, 2712, 2544, -1, 2709, 2713, 2710, -1, 2698, 2714, 2708, -1, 2712, 2713, 2709, -1, 2706, 2714, 2698, -1, 2710, 2713, 2715, -1, 2715, 2713, 2716, -1, 2695, 2717, 2689, -1, 2689, 2717, 2711, -1, 2440, 2718, 2437, -1, 2441, 2718, 2440, -1, 2552, 2719, 2549, -1, 2549, 2719, 2441, -1, 2441, 2719, 2718, -1, 2711, 2720, 2706, -1, 2706, 2720, 2714, -1, 2702, 2721, 2704, -1, 2552, 2722, 2719, -1, 2723, 2724, 2694, -1, 2694, 2724, 2705, -1, 2695, 2724, 2717, -1, 2705, 2724, 2695, -1, 2717, 2725, 2711, -1, 2711, 2725, 2720, -1, 2298, 2726, 2727, -1, 2708, 2728, 2702, -1, 2702, 2728, 2721, -1, 2722, 2729, 2730, -1, 2730, 2729, 2726, -1, 2723, 2731, 2724, -1, 2724, 2731, 2717, -1, 2552, 2732, 2722, -1, 2717, 2731, 2725, -1, 2722, 2732, 2729, -1, 2714, 2612, 2708, -1, 2555, 2732, 2552, -1, 2708, 2612, 2728, -1, 2557, 2732, 2555, -1, 2729, 2733, 2726, -1, 2557, 2734, 2732, -1, 2720, 2610, 2714, -1, 2558, 2734, 2557, -1, 2714, 2610, 2612, -1, 2732, 2734, 2729, -1, 2729, 2734, 2733, -1, 2727, 2735, 2562, -1, 2733, 2735, 2726, -1, 2562, 2735, 2558, -1, 2726, 2735, 2727, -1, 2720, 2494, 2610, -1, 2558, 2735, 2734, -1, 2725, 2494, 2720, -1, 2734, 2735, 2733, -1, 2727, 2736, 2298, -1, 2562, 2736, 2727, -1, 2564, 2737, 2560, -1, 2560, 2737, 2562, -1, 2495, 2492, 2723, -1, 2723, 2492, 2731, -1, 2731, 2492, 2725, -1, 2562, 2737, 2736, -1, 2725, 2492, 2494, -1, 2564, 2738, 2737, -1, 2318, 2739, 2740, -1, 2738, 2741, 2742, -1, 2742, 2741, 2739, -1, 2569, 2743, 2566, -1, 2566, 2743, 2564, -1, 2564, 2743, 2738, -1, 2738, 2743, 2741, -1, 2741, 2744, 2739, -1, 2568, 2745, 2569, -1, 2569, 2745, 2743, -1, 2743, 2745, 2741, -1, 2741, 2745, 2744, -1, 2740, 2746, 2572, -1, 2739, 2746, 2740, -1, 2572, 2746, 2568, -1, 2568, 2746, 2745, -1, 2744, 2746, 2739, -1, 2745, 2746, 2744, -1, 2572, 2747, 2740, -1, 2740, 2747, 2318, -1, 2572, 2748, 2747, -1, 2576, 2748, 2572, -1, 2576, 2749, 2748, -1, 2337, 2750, 2468, -1, 2749, 2751, 2752, -1, 2752, 2751, 2750, -1, 2577, 2753, 2576, -1, 2579, 2753, 2577, -1, 2576, 2753, 2749, -1, 2749, 2753, 2751, -1, 2751, 2754, 2750, -1, 2751, 2755, 2754, -1, 2474, 2755, 2579, -1, 2753, 2755, 2751, -1, 2579, 2755, 2753, -1, 2754, 2756, 2750, -1, 2474, 2756, 2755, -1, 2468, 2756, 2471, -1, 2471, 2756, 2474, -1, 2755, 2756, 2754, -1, 2750, 2756, 2468, -1, 2435, 2757, 2434, -1, 2758, 2759, 2760, -1, 2581, 2757, 2583, -1, 2583, 2757, 2585, -1, 2760, 2759, 2761, -1, 2434, 2757, 2581, -1, 2757, 2762, 2585, -1, 2763, 2764, 2758, -1, 2595, 2765, 2766, -1, 2758, 2764, 2759, -1, 2762, 2765, 2585, -1, 2585, 2765, 2591, -1, 2592, 2765, 2595, -1, 2591, 2765, 2592, -1, 2763, 2767, 2764, -1, 2669, 2767, 2763, -1, 2766, 2768, 2595, -1, 2595, 2768, 2597, -1, 2597, 2768, 2598, -1, 2598, 2768, 2601, -1, 2671, 2769, 2669, -1, 2669, 2769, 2767, -1, 2768, 2770, 2601, -1, 2683, 2771, 2671, -1, 2671, 2771, 2769, -1, 2607, 2772, 2452, -1, 2759, 2773, 2761, -1, 2452, 2772, 2457, -1, 2601, 2772, 2606, -1, 2606, 2772, 2607, -1, 2770, 2772, 2601, -1, 2761, 2773, 2774, -1, 2617, 2775, 2613, -1, 2612, 2775, 2728, -1, 2776, 2777, 2523, -1, 2611, 2775, 2612, -1, 2683, 2777, 2771, -1, 2613, 2775, 2611, -1, 2523, 2777, 2526, -1, 2526, 2777, 2683, -1, 2764, 2778, 2759, -1, 2759, 2778, 2773, -1, 2617, 2779, 2775, -1, 2767, 2780, 2764, -1, 2764, 2780, 2778, -1, 2621, 2781, 2622, -1, 2617, 2781, 2779, -1, 2622, 2781, 2625, -1, 2625, 2781, 2617, -1, 2621, 2782, 2783, -1, 2769, 2784, 2767, -1, 2636, 2782, 2621, -1, 2638, 2782, 2636, -1, 2767, 2784, 2780, -1, 2640, 2782, 2638, -1, 2771, 2785, 2769, -1, 2769, 2785, 2784, -1, 2773, 2786, 2774, -1, 2640, 2787, 2782, -1, 2774, 2786, 2788, -1, 2649, 2789, 2640, -1, 2645, 2789, 2646, -1, 2790, 2791, 2776, -1, 2646, 2789, 2649, -1, 2776, 2791, 2777, -1, 2640, 2789, 2787, -1, 2777, 2791, 2771, -1, 2645, 2792, 2793, -1, 2771, 2791, 2785, -1, 2778, 2794, 2773, -1, 2661, 2792, 2659, -1, 2773, 2794, 2786, -1, 2665, 2792, 2661, -1, 2659, 2792, 2645, -1, 2665, 2795, 2792, -1, 2778, 2796, 2794, -1, 2780, 2796, 2778, -1, 2665, 2797, 2795, -1, 2674, 2797, 2665, -1, 2784, 2798, 2780, -1, 2670, 2797, 2674, -1, 2669, 2797, 2670, -1, 2780, 2798, 2796, -1, 2685, 2799, 2686, -1, 2686, 2799, 2688, -1, 2800, 2799, 2685, -1, 2784, 2801, 2798, -1, 2688, 2799, 2691, -1, 2785, 2801, 2784, -1, 2788, 2528, 2530, -1, 2786, 2528, 2788, -1, 2799, 2802, 2691, -1, 2785, 2803, 2801, -1, 2790, 2803, 2791, -1, 2697, 2804, 2700, -1, 2805, 2803, 2790, -1, 2802, 2804, 2691, -1, 2791, 2803, 2785, -1, 2700, 2804, 2247, -1, 2696, 2804, 2697, -1, 2691, 2804, 2696, -1, 2700, 2254, 2701, -1, 2701, 2254, 2703, -1, 2794, 2532, 2786, -1, 2703, 2254, 2707, -1, 2247, 2254, 2700, -1, 2786, 2532, 2528, -1, 2794, 2687, 2532, -1, 2796, 2687, 2794, -1, 2254, 2259, 2707, -1, 2798, 2685, 2796, -1, 2713, 2267, 2716, -1, 2712, 2267, 2713, -1, 2707, 2267, 2712, -1, 2796, 2685, 2687, -1, 2259, 2267, 2707, -1, 2716, 2267, 2270, -1, 2801, 2800, 2798, -1, 2718, 2282, 2437, -1, 2798, 2800, 2685, -1, 2722, 2282, 2719, -1, 2437, 2282, 2278, -1, 2719, 2282, 2718, -1, 2722, 2284, 2282, -1, 2805, 2806, 2803, -1, 2807, 2806, 2805, -1, 2801, 2806, 2800, -1, 2803, 2806, 2801, -1, 2730, 2293, 2722, -1, 2726, 2293, 2730, -1, 2298, 2293, 2726, -1, 2722, 2293, 2284, -1, 2736, 2306, 2298, -1, 2737, 2306, 2736, -1, 2738, 2306, 2737, -1, 2298, 2306, 2299, -1, 2738, 2305, 2306, -1, 2738, 2312, 2305, -1, 2742, 2312, 2738, -1, 2318, 2312, 2739, -1, 2739, 2312, 2742, -1, 2318, 2323, 2317, -1, 2747, 2323, 2318, -1, 2748, 2323, 2747, -1, 2749, 2323, 2748, -1, 2749, 2326, 2323, -1, 2548, 2808, 2546, -1, 2337, 2332, 2750, -1, 2752, 2332, 2749, -1, 2749, 2332, 2326, -1, 2750, 2332, 2752, -1, 2439, 2809, 2438, -1, 2438, 2809, 2435, -1, 2809, 2810, 2435, -1, 2710, 2811, 2548, -1, 2548, 2811, 2808, -1, 2757, 2810, 2762, -1, 2435, 2810, 2757, -1, 2439, 2812, 2809, -1, 2810, 2812, 2762, -1, 2813, 2812, 2439, -1, 2809, 2812, 2810, -1, 2715, 2814, 2710, -1, 2762, 2815, 2765, -1, 2710, 2814, 2811, -1, 2765, 2815, 2766, -1, 2812, 2815, 2762, -1, 2813, 2816, 2812, -1, 2812, 2816, 2815, -1, 2815, 2816, 2766, -1, 2817, 2816, 2813, -1, 2766, 2816, 2817, -1, 2813, 2818, 2817, -1, 2817, 2818, 2766, -1, 2716, 2819, 2715, -1, 2715, 2819, 2814, -1, 2768, 2820, 2770, -1, 2818, 2820, 2766, -1, 2808, 2821, 2546, -1, 2766, 2820, 2768, -1, 2546, 2821, 2822, -1, 2820, 2823, 2770, -1, 2818, 2823, 2820, -1, 2465, 2823, 2813, -1, 2813, 2823, 2818, -1, 2823, 2824, 2770, -1, 2270, 2825, 2716, -1, 2770, 2824, 2772, -1, 2772, 2824, 2457, -1, 2716, 2825, 2819, -1, 2465, 2826, 2823, -1, 2823, 2826, 2824, -1, 2824, 2826, 2457, -1, 2811, 2827, 2808, -1, 2466, 2826, 2465, -1, 2457, 2826, 2466, -1, 2808, 2827, 2821, -1, 2728, 2828, 2721, -1, 2721, 2828, 2704, -1, 2821, 2829, 2822, -1, 2828, 2830, 2704, -1, 2831, 2832, 2261, -1, 2779, 2830, 2775, -1, 2261, 2832, 2272, -1, 2272, 2832, 2270, -1, 2728, 2830, 2828, -1, 2270, 2832, 2825, -1, 2775, 2830, 2728, -1, 2830, 2833, 2704, -1, 2814, 2834, 2811, -1, 2811, 2834, 2827, -1, 2779, 2833, 2830, -1, 2704, 2833, 2835, -1, 2779, 2836, 2833, -1, 2827, 2837, 2821, -1, 2833, 2836, 2835, -1, 2821, 2837, 2829, -1, 2781, 2836, 2779, -1, 2814, 2838, 2834, -1, 2836, 2839, 2835, -1, 2835, 2839, 2840, -1, 2819, 2838, 2814, -1, 2840, 2841, 2783, -1, 2783, 2841, 2621, -1, 2621, 2841, 2781, -1, 2839, 2841, 2840, -1, 2781, 2841, 2836, -1, 2836, 2841, 2839, -1, 2783, 2842, 2840, -1, 2834, 2843, 2827, -1, 2827, 2843, 2837, -1, 2840, 2842, 2835, -1, 2782, 2844, 2783, -1, 2825, 2845, 2819, -1, 2783, 2844, 2842, -1, 2842, 2844, 2835, -1, 2819, 2845, 2838, -1, 2787, 2844, 2782, -1, 2822, 2846, 2847, -1, 2829, 2846, 2822, -1, 2787, 2848, 2844, -1, 2844, 2848, 2835, -1, 2835, 2848, 2849, -1, 2838, 2850, 2834, -1, 2789, 2851, 2787, -1, 2848, 2851, 2849, -1, 2834, 2850, 2843, -1, 2787, 2851, 2848, -1, 2849, 2852, 2853, -1, 2831, 2854, 2832, -1, 2851, 2852, 2849, -1, 2832, 2854, 2825, -1, 2793, 2855, 2645, -1, 2825, 2854, 2845, -1, 2645, 2855, 2789, -1, 2853, 2855, 2793, -1, 2789, 2855, 2851, -1, 2837, 2856, 2829, -1, 2852, 2855, 2853, -1, 2829, 2856, 2846, -1, 2851, 2855, 2852, -1, 2853, 2857, 2849, -1, 2793, 2857, 2853, -1, 2845, 2250, 2838, -1, 2795, 2858, 2792, -1, 2838, 2250, 2850, -1, 2792, 2858, 2793, -1, 2846, 2255, 2847, -1, 2857, 2858, 2849, -1, 2793, 2858, 2857, -1, 2795, 2859, 2858, -1, 2858, 2859, 2849, -1, 2849, 2859, 2760, -1, 2837, 2860, 2856, -1, 2843, 2860, 2837, -1, 2797, 2861, 2795, -1, 2831, 2248, 2854, -1, 2859, 2861, 2760, -1, 2251, 2248, 2831, -1, 2795, 2861, 2859, -1, 2845, 2248, 2250, -1, 2854, 2248, 2845, -1, 2758, 2862, 2763, -1, 2760, 2862, 2758, -1, 2856, 2258, 2846, -1, 2861, 2862, 2760, -1, 2763, 2863, 2669, -1, 2669, 2863, 2797, -1, 2862, 2863, 2763, -1, 2846, 2258, 2255, -1, 2797, 2863, 2861, -1, 2850, 2263, 2843, -1, 2861, 2863, 2862, -1, 2843, 2263, 2860, -1, 2806, 2864, 2800, -1, 2807, 2864, 2806, -1, 2860, 2273, 2856, -1, 2800, 2865, 2799, -1, 2799, 2865, 2802, -1, 2856, 2273, 2258, -1, 2864, 2865, 2800, -1, 2250, 2252, 2850, -1, 2262, 2866, 2807, -1, 2850, 2252, 2263, -1, 2865, 2866, 2802, -1, 2864, 2866, 2865, -1, 2255, 2257, 2847, -1, 2807, 2866, 2864, -1, 2804, 2867, 2247, -1, 2802, 2867, 2804, -1, 2847, 2257, 2269, -1, 2866, 2867, 2802, -1, 2263, 2265, 2860, -1, 2245, 2868, 2262, -1, 2247, 2868, 2245, -1, 2860, 2265, 2273, -1, 2867, 2868, 2247, -1, 2262, 2868, 2866, -1, 2866, 2868, 2867, -1, 2262, 2246, 2245, -1, 2869, 2870, 2871, -1, 2872, 2873, 2874, -1, 2875, 2876, 2877, -1, 2875, 2878, 2876, -1, 2872, 2874, 2869, -1, 2879, 2880, 2881, -1, 2879, 2881, 2882, -1, 2879, 2877, 2880, -1, 2879, 2875, 2877, -1, 2883, 2884, 2885, -1, 2886, 2882, 2887, -1, 2888, 2889, 2890, -1, 2886, 2879, 2882, -1, 2888, 2891, 2889, -1, 2886, 2878, 2875, -1, 2886, 2892, 2878, -1, 2886, 2875, 2879, -1, 2893, 2894, 2895, -1, 2893, 2895, 2896, -1, 2897, 2891, 2888, -1, 2897, 2871, 2891, -1, 2893, 2896, 2898, -1, 2899, 2893, 2898, -1, 2899, 2894, 2893, -1, 2900, 2895, 2894, -1, 2901, 2871, 2897, -1, 2900, 2881, 2902, -1, 2901, 2869, 2871, -1, 2900, 2902, 2895, -1, 2903, 2894, 2899, -1, 2903, 2899, 2898, -1, 2904, 2872, 2869, -1, 2903, 2905, 2906, -1, 2903, 2906, 2894, -1, 2903, 2898, 2905, -1, 2904, 2869, 2901, -1, 2907, 2887, 2882, -1, 2907, 2882, 2881, -1, 2907, 2881, 2900, -1, 2908, 2884, 2909, -1, 2910, 2907, 2900, -1, 2908, 2911, 2884, -1, 2912, 2906, 2913, -1, 2912, 2894, 2906, -1, 2914, 2915, 2916, -1, 2914, 2917, 2915, -1, 2918, 2913, 2919, -1, 2918, 2912, 2913, -1, 2920, 2917, 2914, -1, 2920, 2921, 2917, -1, 2922, 2923, 2912, -1, 2922, 2912, 2918, -1, 2924, 2918, 2919, -1, 2924, 2922, 2918, -1, 2924, 2919, 2925, -1, 2924, 2925, 2926, -1, 2927, 2928, 2921, -1, 2927, 2921, 2920, -1, 2929, 2922, 2924, -1, 2929, 2923, 2922, -1, 2929, 2930, 2923, -1, 2929, 2924, 2926, -1, 2929, 2926, 2931, -1, 2932, 2933, 2928, -1, 2932, 2928, 2927, -1, 2934, 2901, 2897, -1, 2935, 2914, 2916, -1, 2936, 2937, 2938, -1, 2936, 2938, 2904, -1, 2936, 2939, 2937, -1, 2940, 2933, 2932, -1, 2936, 2901, 2934, -1, 2940, 2941, 2933, -1, 2936, 2934, 2942, -1, 2936, 2904, 2901, -1, 2943, 2914, 2935, -1, 2943, 2920, 2914, -1, 2944, 2941, 2940, -1, 2944, 2945, 2946, -1, 2944, 2946, 2941, -1, 2947, 2916, 2948, -1, 2947, 2935, 2916, -1, 2949, 2921, 2928, -1, 2950, 2920, 2943, -1, 2951, 2952, 2939, -1, 2950, 2927, 2920, -1, 2951, 2953, 2952, -1, 2951, 2933, 2953, -1, 2954, 2935, 2947, -1, 2951, 2949, 2928, -1, 2951, 2955, 2949, -1, 2951, 2928, 2933, -1, 2956, 2957, 2911, -1, 2954, 2943, 2935, -1, 2958, 2932, 2927, -1, 2956, 2959, 2960, -1, 2956, 2911, 2959, -1, 2958, 2927, 2950, -1, 2961, 2960, 2937, -1, 2961, 2937, 2939, -1, 2961, 2957, 2956, -1, 2961, 2962, 2957, -1, 2961, 2939, 2952, -1, 2961, 2952, 2962, -1, 2961, 2956, 2960, -1, 2963, 2950, 2943, -1, 2964, 2965, 2966, -1, 2963, 2943, 2954, -1, 2964, 2967, 2965, -1, 2964, 2968, 2967, -1, 2969, 2940, 2932, -1, 2970, 2971, 2968, -1, 2969, 2932, 2958, -1, 2970, 2972, 2971, -1, 2970, 2968, 2964, -1, 2973, 2958, 2950, -1, 2973, 2950, 2963, -1, 2974, 2970, 2964, -1, 2975, 2944, 2940, -1, 2975, 2945, 2944, -1, 2975, 2940, 2969, -1, 2975, 2976, 2945, -1, 2977, 2947, 2948, -1, 2978, 2969, 2958, -1, 2978, 2958, 2973, -1, 2979, 2966, 2980, -1, 2979, 2980, 2981, -1, 2979, 2981, 2982, -1, 2983, 2954, 2947, -1, 2983, 2947, 2977, -1, 2984, 2975, 2969, -1, 2985, 2979, 2982, -1, 2984, 2969, 2978, -1, 2984, 2976, 2975, -1, 2985, 2986, 2979, -1, 2985, 2982, 2987, -1, 2988, 2963, 2954, -1, 2985, 2987, 2989, -1, 2990, 2991, 2992, -1, 2990, 2982, 2991, -1, 2988, 2954, 2983, -1, 2990, 2992, 2993, -1, 2994, 2948, 2995, -1, 2994, 2977, 2948, -1, 2996, 2982, 2990, -1, 2996, 2987, 2982, -1, 2996, 2989, 2987, -1, 2997, 2973, 2963, -1, 2997, 2963, 2988, -1, 2998, 2996, 2990, -1, 2999, 2977, 2994, -1, 2999, 2983, 2977, -1, 3000, 3001, 3002, -1, 3000, 2993, 3001, -1, 3003, 2978, 2973, -1, 3003, 2973, 2997, -1, 3004, 2988, 2983, -1, 3004, 2983, 2999, -1, 3005, 2984, 2978, -1, 3005, 2976, 2984, -1, 3005, 2978, 3003, -1, 3005, 3006, 2976, -1, 3007, 3008, 3000, -1, 3007, 3000, 3002, -1, 3009, 2997, 2988, -1, 3007, 3002, 3010, -1, 3009, 2988, 3004, -1, 3011, 3012, 3013, -1, 3011, 3007, 3010, -1, 3014, 2994, 2995, -1, 3011, 3010, 3012, -1, 3015, 3003, 2997, -1, 3016, 3017, 3008, -1, 3016, 3007, 3011, -1, 3015, 2997, 3009, -1, 3016, 3008, 3007, -1, 3016, 3011, 3013, -1, 3016, 3013, 3018, -1, 3019, 2994, 3014, -1, 3020, 3021, 3022, -1, 3019, 2999, 2994, -1, 3020, 3012, 3023, -1, 3020, 3023, 3021, -1, 3024, 3013, 3012, -1, 3025, 3005, 3003, -1, 3025, 3006, 3005, -1, 3025, 3003, 3015, -1, 3024, 3012, 3020, -1, 3024, 3018, 3013, -1, 3026, 3004, 2999, -1, 3026, 2999, 3019, -1, 3027, 3024, 3020, -1, 3028, 2995, 3029, -1, 3028, 3014, 2995, -1, 3030, 3009, 3004, -1, 3031, 3022, 3032, -1, 3031, 3032, 3033, -1, 3030, 3004, 3026, -1, 3034, 3019, 3014, -1, 3034, 3014, 3028, -1, 3035, 3031, 3033, -1, 3036, 3015, 3009, -1, 3035, 3033, 3037, -1, 3036, 3009, 3030, -1, 3038, 3019, 3034, -1, 3039, 3031, 3035, -1, 3038, 3026, 3019, -1, 3039, 3040, 3031, -1, 3041, 3015, 3036, -1, 3041, 3042, 3006, -1, 3041, 3006, 3025, -1, 3041, 3025, 3015, -1, 3043, 3037, 3044, -1, 3043, 3044, 3045, -1, 3043, 3039, 3035, -1, 3043, 3035, 3037, -1, 3046, 3028, 3029, -1, 3047, 3045, 3048, -1, 3047, 3040, 3039, -1, 3049, 3026, 3038, -1, 3047, 3050, 3040, -1, 3047, 3039, 3043, -1, 3047, 3043, 3045, -1, 3051, 3052, 3053, -1, 3051, 3054, 3052, -1, 3049, 3030, 3026, -1, 3055, 3034, 3028, -1, 3051, 3053, 3056, -1, 3057, 3054, 3051, -1, 3055, 3028, 3046, -1, 3058, 3036, 3030, -1, 3057, 3051, 3056, -1, 3059, 3052, 3054, -1, 3058, 3030, 3049, -1, 3060, 3034, 3055, -1, 3059, 3044, 3061, -1, 3059, 3061, 3052, -1, 3062, 3063, 3064, -1, 3062, 3064, 3054, -1, 3060, 3038, 3034, -1, 3062, 3056, 3063, -1, 3062, 3054, 3057, -1, 3062, 3057, 3056, -1, 3065, 3041, 3036, -1, 3066, 3044, 3059, -1, 3065, 3042, 3041, -1, 3066, 3045, 3044, -1, 3065, 3036, 3058, -1, 3066, 3048, 3045, -1, 3067, 3029, 3068, -1, 3067, 3046, 3029, -1, 3069, 3066, 3059, -1, 3070, 3038, 3060, -1, 3071, 3064, 3072, -1, 3070, 3049, 3038, -1, 3071, 3054, 3064, -1, 3073, 3046, 3067, -1, 3073, 3055, 3046, -1, 3074, 3075, 3076, -1, 3077, 3049, 3070, -1, 3078, 3072, 3079, -1, 3077, 3058, 3049, -1, 3078, 3071, 3072, -1, 3080, 3060, 3055, -1, 3080, 3055, 3073, -1, 3081, 3042, 3065, -1, 3081, 3065, 3058, -1, 3082, 3083, 3071, -1, 3081, 3058, 3077, -1, 3082, 3071, 3078, -1, 3081, 3084, 3042, -1, 3085, 3067, 3068, -1, 3086, 3070, 3060, -1, 3087, 3088, 3089, -1, 3086, 3060, 3080, -1, 3087, 3078, 3079, -1, 3087, 3082, 3078, -1, 3087, 3079, 3088, -1, 3090, 3089, 3091, -1, 3090, 3083, 3082, -1, 3092, 3073, 3067, -1, 3090, 3087, 3089, -1, 3090, 3093, 3083, -1, 3092, 3067, 3085, -1, 3090, 3082, 3087, -1, 3094, 3095, 3096, -1, 3097, 3098, 3099, -1, 3100, 3077, 3070, -1, 3094, 3101, 3095, -1, 3100, 3070, 3086, -1, 3094, 3102, 3103, -1, 3097, 3104, 3098, -1, 3094, 3105, 3101, -1, 3094, 3103, 3105, -1, 3094, 3096, 3102, -1, 3106, 3107, 3095, -1, 3106, 3108, 3107, -1, 3106, 3095, 3101, -1, 3109, 3080, 3073, -1, 3110, 3104, 3097, -1, 3109, 3073, 3092, -1, 3106, 3111, 3108, -1, 3110, 3112, 3104, -1, 3113, 3101, 3105, -1, 3113, 3114, 3115, -1, 3113, 3105, 3114, -1, 3116, 3081, 3077, -1, 3113, 3117, 3111, -1, 3116, 3084, 3081, -1, 3113, 3115, 3117, -1, 3113, 3106, 3101, -1, 3118, 3112, 3110, -1, 3116, 3077, 3100, -1, 3113, 3111, 3106, -1, 3119, 3120, 3121, -1, 3119, 3122, 3123, -1, 3118, 3124, 3112, -1, 3125, 3068, 3126, -1, 3119, 3123, 3127, -1, 3125, 3085, 3068, -1, 3119, 3128, 3120, -1, 3119, 3127, 3128, -1, 3119, 3129, 3122, -1, 3119, 3121, 3129, -1, 3130, 3131, 3121, -1, 3132, 3086, 3080, -1, 3130, 3115, 3131, -1, 3130, 3121, 3120, -1, 3133, 3124, 3118, -1, 3133, 3134, 3124, -1, 3132, 3080, 3109, -1, 3130, 3117, 3115, -1, 3135, 3130, 3120, -1, 3135, 3117, 3130, -1, 3135, 3120, 3128, -1, 3136, 3134, 3133, -1, 3137, 3085, 3125, -1, 3135, 3138, 3139, -1, 3137, 3092, 3085, -1, 3135, 3128, 3138, -1, 3136, 3140, 3134, -1, 3135, 3141, 3117, -1, 3142, 3143, 3140, -1, 3135, 3139, 3141, -1, 3142, 3144, 3143, -1, 3145, 3146, 3147, -1, 3145, 3147, 2876, -1, 3142, 3140, 3136, -1, 3145, 3148, 3149, -1, 3142, 3150, 3144, -1, 3145, 2876, 2878, -1, 3151, 3100, 3086, -1, 3145, 2892, 3148, -1, 3145, 2878, 2892, -1, 3151, 3086, 3132, -1, 3145, 3149, 3146, -1, 3152, 3139, 3153, -1, 3154, 3099, 3155, -1, 3154, 3097, 3099, -1, 3152, 3153, 3149, -1, 3152, 3141, 3139, -1, 3156, 3109, 3092, -1, 3152, 3149, 3148, -1, 3157, 3097, 3154, -1, 3158, 3141, 3152, -1, 3156, 3092, 3137, -1, 3158, 3152, 3148, -1, 3158, 2887, 3159, -1, 3157, 3110, 3097, -1, 3158, 3159, 3141, -1, 3158, 3148, 2892, -1, 3158, 2886, 2887, -1, 3160, 3084, 3116, -1, 3158, 2892, 2886, -1, 3160, 3116, 3100, -1, 3161, 2900, 2894, -1, 3160, 3100, 3151, -1, 3161, 2910, 2900, -1, 3161, 2930, 3162, -1, 3160, 3163, 3084, -1, 3161, 2912, 2923, -1, 3161, 3162, 2910, -1, 3164, 3125, 3126, -1, 3161, 2923, 2930, -1, 3161, 2894, 2912, -1, 3165, 3110, 3157, -1, 3166, 2907, 2910, -1, 3166, 2910, 3162, -1, 3165, 3118, 3110, -1, 3167, 3132, 3109, -1, 3166, 3159, 2887, -1, 3168, 3118, 3165, -1, 3167, 3109, 3156, -1, 3166, 2887, 2907, -1, 3169, 3162, 2930, -1, 3169, 3166, 3162, -1, 3169, 3159, 3166, -1, 3168, 3133, 3118, -1, 3169, 2929, 2931, -1, 3169, 2930, 2929, -1, 3169, 2931, 3170, -1, 3171, 3125, 3164, -1, 3169, 3170, 3159, -1, 3172, 3133, 3168, -1, 3173, 2897, 2888, -1, 3172, 3136, 3133, -1, 3171, 3137, 3125, -1, 3173, 2942, 2934, -1, 3173, 3174, 2942, -1, 3175, 3132, 3167, -1, 3173, 2888, 2890, -1, 3176, 3142, 3136, -1, 3175, 3151, 3132, -1, 3173, 2934, 2897, -1, 3176, 3136, 3172, -1, 3177, 2890, 2915, -1, 3176, 3178, 3150, -1, 3177, 3174, 3173, -1, 3176, 3150, 3142, -1, 3177, 3173, 2890, -1, 3179, 3154, 3155, -1, 3180, 3156, 3137, -1, 3181, 2915, 2917, -1, 3180, 3137, 3171, -1, 3181, 3177, 2915, -1, 3181, 2949, 2955, -1, 3179, 3155, 3182, -1, 3181, 2921, 2949, -1, 3181, 2917, 2921, -1, 3183, 3151, 3175, -1, 3181, 2955, 3174, -1, 3183, 3160, 3151, -1, 3181, 3174, 3177, -1, 3183, 3163, 3160, -1, 3184, 2951, 2939, -1, 3185, 3157, 3154, -1, 3184, 2942, 3174, -1, 3184, 2936, 2942, -1, 3184, 2955, 2951, -1, 3186, 3167, 3156, -1, 3184, 2939, 2936, -1, 3185, 3154, 3179, -1, 3184, 3174, 2955, -1, 3187, 2966, 2979, -1, 3187, 3188, 2974, -1, 3189, 3157, 3185, -1, 3187, 2974, 2964, -1, 3186, 3156, 3180, -1, 3187, 2964, 2966, -1, 3187, 2979, 2986, -1, 3187, 2986, 3188, -1, 3190, 3126, 3191, -1, 3192, 2970, 2974, -1, 3192, 3193, 2972, -1, 3190, 3164, 3126, -1, 3192, 2974, 3188, -1, 3189, 3165, 3157, -1, 3194, 3165, 3189, -1, 3192, 2972, 2970, -1, 3194, 3168, 3165, -1, 3195, 3175, 3167, -1, 3196, 3192, 3188, -1, 3196, 3193, 3192, -1, 3196, 2985, 2989, -1, 3196, 3188, 2986, -1, 3196, 2989, 3197, -1, 3195, 3167, 3186, -1, 3196, 2986, 2985, -1, 3196, 3197, 3193, -1, 3198, 3168, 3194, -1, 3199, 3164, 3190, -1, 3200, 3017, 3201, -1, 3198, 3172, 3168, -1, 3200, 3000, 3008, -1, 3200, 3008, 3017, -1, 3200, 2998, 2990, -1, 3199, 3171, 3164, -1, 3200, 3201, 2998, -1, 3202, 3203, 3178, -1, 3200, 2990, 2993, -1, 3200, 2993, 3000, -1, 3204, 3197, 2989, -1, 3205, 3179, 3182, -1, 3206, 3175, 3195, -1, 3204, 2998, 3201, -1, 3206, 3207, 3163, -1, 3204, 2996, 2998, -1, 3206, 3183, 3175, -1, 3204, 2989, 2996, -1, 3206, 3163, 3183, -1, 3208, 3201, 3017, -1, 3208, 3018, 3209, -1, 3205, 3182, 3210, -1, 3211, 3171, 3199, -1, 3208, 3017, 3016, -1, 3212, 3185, 3179, -1, 3208, 3016, 3018, -1, 3208, 3204, 3201, -1, 3212, 3179, 3205, -1, 3208, 3209, 3197, -1, 3211, 3180, 3171, -1, 3208, 3197, 3204, -1, 3213, 3020, 3022, -1, 3213, 3027, 3020, -1, 3213, 3022, 3031, -1, 3213, 3214, 3027, -1, 3213, 3031, 3040, -1, 3215, 3190, 3191, -1, 3213, 3050, 3214, -1, 3216, 3189, 3185, -1, 3213, 3040, 3050, -1, 3217, 3186, 3180, -1, 3218, 3209, 3018, -1, 3218, 3018, 3024, -1, 3218, 3024, 3027, -1, 3217, 3180, 3211, -1, 3218, 3027, 3214, -1, 3216, 3185, 3212, -1, 3219, 3047, 3048, -1, 3220, 3194, 3189, -1, 3219, 3048, 3221, -1, 3219, 3209, 3218, -1, 3219, 3214, 3050, -1, 3222, 3190, 3215, -1, 3219, 3050, 3047, -1, 3219, 3218, 3214, -1, 3219, 3221, 3209, -1, 3222, 3199, 3190, -1, 3223, 3071, 3083, -1, 3220, 3189, 3216, -1, 3223, 3059, 3054, -1, 3224, 3194, 3220, -1, 3223, 3069, 3059, -1, 3225, 3195, 3186, -1, 3223, 3054, 3071, -1, 3223, 3226, 3069, -1, 3225, 3186, 3217, -1, 3223, 3093, 3226, -1, 3224, 3198, 3194, -1, 3223, 3083, 3093, -1, 3227, 3048, 3066, -1, 3227, 3221, 3048, -1, 3228, 3229, 3203, -1, 3230, 3211, 3199, -1, 3227, 3066, 3069, -1, 3231, 3205, 3210, -1, 3230, 3199, 3222, -1, 3227, 3069, 3226, -1, 3232, 3091, 3233, -1, 3231, 3210, 3234, -1, 3232, 3221, 3227, -1, 3232, 3227, 3226, -1, 3235, 3206, 3195, -1, 3232, 3090, 3091, -1, 3235, 3207, 3206, -1, 3232, 3226, 3093, -1, 3235, 3195, 3225, -1, 3232, 3093, 3090, -1, 3236, 3205, 3231, -1, 3232, 3233, 3221, -1, 3237, 3211, 3230, -1, 3236, 3212, 3205, -1, 3237, 3217, 3211, -1, 3238, 3191, 3239, -1, 3240, 3212, 3236, -1, 3240, 3216, 3212, -1, 3238, 3215, 3191, -1, 3241, 3225, 3217, -1, 3241, 3217, 3237, -1, 3242, 3220, 3216, -1, 3242, 3216, 3240, -1, 3243, 3222, 3215, -1, 3243, 3215, 3238, -1, 3244, 3229, 3245, -1, 3244, 3246, 3229, -1, 3247, 3225, 3241, -1, 3247, 3207, 3235, -1, 3247, 3235, 3225, -1, 3248, 3234, 3249, -1, 3247, 3250, 3207, -1, 3251, 3238, 3239, -1, 3248, 3231, 3234, -1, 3252, 3230, 3222, -1, 3253, 3231, 3248, -1, 3253, 3236, 3231, -1, 3252, 3222, 3243, -1, 3254, 3248, 3249, -1, 3255, 3243, 3238, -1, 3254, 3249, 3256, -1, 3255, 3238, 3251, -1, 3257, 3240, 3236, -1, 3257, 3236, 3253, -1, 3258, 3237, 3230, -1, 3258, 3230, 3252, -1, 3259, 3248, 3254, -1, 3260, 3243, 3255, -1, 3259, 3253, 3248, -1, 3260, 3252, 3243, -1, 3261, 3240, 3257, -1, 3262, 3237, 3258, -1, 3262, 3241, 3237, -1, 3261, 3242, 3240, -1, 3263, 3257, 3253, -1, 3263, 3253, 3259, -1, 3264, 3258, 3252, -1, 3264, 3252, 3260, -1, 3265, 3247, 3241, -1, 3265, 3241, 3262, -1, 3265, 3250, 3247, -1, 3266, 3239, 3267, -1, 3266, 3251, 3239, -1, 3268, 3257, 3263, -1, 3268, 3261, 3257, -1, 3269, 3246, 3270, -1, 3271, 3262, 3258, -1, 3271, 3258, 3264, -1, 3269, 3272, 3246, -1, 3273, 3254, 3256, -1, 3274, 3255, 3251, -1, 3274, 3251, 3266, -1, 3275, 3261, 3268, -1, 3275, 3270, 3261, -1, 3276, 3262, 3271, -1, 3276, 3265, 3262, -1, 3277, 3254, 3273, -1, 3276, 3250, 3265, -1, 3276, 3278, 3250, -1, 3277, 3259, 3254, -1, 3279, 3266, 3267, -1, 3280, 3269, 3270, -1, 3280, 3272, 3269, -1, 3281, 3260, 3255, -1, 3280, 3270, 3275, -1, 3281, 3255, 3274, -1, 3282, 3273, 3256, -1, 3282, 3256, 3283, -1, 3284, 3266, 3279, -1, 3285, 3259, 3277, -1, 3284, 3274, 3266, -1, 3285, 3263, 3259, -1, 3286, 3264, 3260, -1, 3287, 3277, 3273, -1, 3287, 3273, 3282, -1, 3286, 3260, 3281, -1, 3288, 3268, 3263, -1, 3289, 3281, 3274, -1, 3288, 3263, 3285, -1, 3289, 3274, 3284, -1, 3290, 3271, 3264, -1, 3291, 3285, 3277, -1, 3291, 3277, 3287, -1, 3290, 3264, 3286, -1, 3292, 3275, 3268, -1, 3293, 3281, 3289, -1, 3293, 3286, 3281, -1, 3292, 3268, 3288, -1, 3294, 3285, 3291, -1, 3295, 3276, 3271, -1, 3294, 3288, 3285, -1, 3295, 3278, 3276, -1, 3295, 3271, 3290, -1, 3296, 3267, 3297, -1, 3298, 3272, 3280, -1, 3296, 3279, 3267, -1, 3298, 3280, 3275, -1, 3298, 3275, 3292, -1, 3298, 3299, 3272, -1, 3300, 3286, 3293, -1, 3301, 3282, 3283, -1, 3300, 3290, 3286, -1, 3302, 3292, 3288, -1, 3303, 3279, 3296, -1, 3302, 3288, 3294, -1, 3303, 3284, 3279, -1, 3304, 3290, 3300, -1, 3304, 3278, 3295, -1, 3305, 3282, 3301, -1, 3304, 3306, 3278, -1, 3305, 3287, 3282, -1, 3304, 3295, 3290, -1, 3307, 3296, 3297, -1, 3308, 3292, 3302, -1, 3308, 3298, 3292, -1, 3308, 3299, 3298, -1, 3309, 3289, 3284, -1, 3310, 3283, 3311, -1, 3310, 3301, 3283, -1, 3309, 3284, 3303, -1, 3312, 3291, 3287, -1, 3312, 3287, 3305, -1, 3313, 3296, 3307, -1, 3313, 3303, 3296, -1, 3314, 3305, 3301, -1, 3315, 3293, 3289, -1, 3314, 3301, 3310, -1, 3315, 3289, 3309, -1, 3316, 3294, 3291, -1, 3316, 3291, 3312, -1, 3317, 3309, 3303, -1, 3317, 3303, 3313, -1, 3318, 3305, 3314, -1, 3319, 3293, 3315, -1, 3318, 3312, 3305, -1, 3319, 3300, 3293, -1, 3320, 3302, 3294, -1, 3320, 3294, 3316, -1, 3321, 3315, 3309, -1, 3321, 3309, 3317, -1, 3322, 3304, 3300, -1, 3323, 3316, 3312, -1, 3322, 3300, 3319, -1, 3322, 3306, 3304, -1, 3323, 3312, 3318, -1, 3324, 3319, 3315, -1, 3324, 3315, 3321, -1, 3325, 3308, 3302, -1, 3325, 3326, 3299, -1, 3325, 3299, 3308, -1, 3325, 3302, 3320, -1, 3327, 3297, 3328, -1, 3327, 3307, 3297, -1, 3329, 3310, 3311, -1, 3330, 3319, 3324, -1, 3331, 3320, 3316, -1, 3330, 3322, 3319, -1, 3331, 3316, 3323, -1, 3330, 3306, 3322, -1, 3330, 3193, 3306, -1, 3332, 3307, 3327, -1, 3333, 3310, 3329, -1, 3332, 3313, 3307, -1, 3333, 3314, 3310, -1, 3334, 3320, 3331, -1, 3335, 3313, 3332, -1, 3334, 3326, 3325, -1, 3335, 3317, 3313, -1, 3334, 3325, 3320, -1, 3336, 3314, 3333, -1, 3336, 3318, 3314, -1, 2968, 3321, 3317, -1, 2968, 3317, 3335, -1, 3337, 3311, 3338, -1, 3337, 3329, 3311, -1, 2971, 3324, 3321, -1, 2971, 3321, 2968, -1, 3339, 3323, 3318, -1, 2972, 3330, 3324, -1, 3339, 3318, 3336, -1, 2972, 3193, 3330, -1, 2972, 3324, 2971, -1, 3340, 3329, 3337, -1, 3340, 3333, 3329, -1, 3341, 3323, 3339, -1, 3341, 3331, 3323, -1, 3342, 3333, 3340, -1, 3342, 3336, 3333, -1, 3343, 3331, 3341, -1, 3343, 3344, 3326, -1, 3343, 3326, 3334, -1, 3343, 3334, 3331, -1, 3345, 3336, 3342, -1, 3345, 3339, 3336, -1, 3346, 3337, 3338, -1, 3347, 3341, 3339, -1, 3347, 3339, 3345, -1, 3348, 3337, 3346, -1, 3348, 3340, 3337, -1, 3349, 3343, 3341, -1, 3349, 3344, 3343, -1, 3349, 3341, 3347, -1, 3350, 3342, 3340, -1, 3350, 3340, 3348, -1, 3351, 3346, 3338, -1, 3351, 3338, 3352, -1, 3353, 3345, 3342, -1, 3353, 3342, 3350, -1, 3354, 3348, 3346, -1, 3354, 3346, 3351, -1, 3355, 3347, 3345, -1, 3355, 3345, 3353, -1, 3356, 3348, 3354, -1, 3356, 3350, 3348, -1, 3357, 3344, 3349, -1, 3357, 3349, 3347, -1, 3357, 3347, 3355, -1, 3357, 3358, 3344, -1, 3359, 3351, 3352, -1, 3360, 3353, 3350, -1, 3360, 3350, 3356, -1, 3361, 3354, 3351, -1, 3361, 3351, 3359, -1, 3362, 3355, 3353, -1, 3362, 3353, 3360, -1, 3363, 3356, 3354, -1, 3363, 3354, 3361, -1, 3364, 3355, 3362, -1, 3364, 3357, 3355, -1, 3364, 3358, 3357, -1, 3365, 3075, 3074, -1, 3366, 3352, 3367, -1, 3366, 3359, 3352, -1, 3368, 3365, 3074, -1, 3368, 3074, 3369, -1, 3370, 3360, 3356, -1, 3370, 3356, 3363, -1, 3079, 3368, 3369, -1, 3079, 3369, 3371, -1, 3372, 3361, 3359, -1, 3372, 3359, 3366, -1, 3373, 3362, 3360, -1, 3088, 3079, 3371, -1, 3373, 3360, 3370, -1, 3088, 3371, 3374, -1, 3375, 3363, 3361, -1, 3375, 3361, 3372, -1, 3089, 3088, 3374, -1, 3089, 3374, 3376, -1, 3377, 3378, 3358, -1, 3377, 3364, 3362, -1, 3377, 3358, 3364, -1, 3377, 3362, 3373, -1, 3091, 3089, 3376, -1, 3091, 3376, 3379, -1, 3091, 3379, 3380, -1, 3381, 3366, 3367, -1, 3091, 3380, 3233, -1, 3382, 3172, 3198, -1, 3382, 3202, 3178, -1, 3382, 3198, 3202, -1, 3383, 3363, 3375, -1, 3382, 3176, 3172, -1, 3382, 3178, 3176, -1, 3383, 3370, 3363, -1, 3384, 3198, 3224, -1, 3384, 3224, 3228, -1, 3384, 3202, 3198, -1, 3384, 3203, 3202, -1, 3384, 3228, 3203, -1, 3385, 3372, 3366, -1, 3386, 3245, 3229, -1, 3386, 3229, 3228, -1, 3385, 3366, 3381, -1, 3387, 3246, 3244, -1, 3388, 3373, 3370, -1, 3387, 3270, 3246, -1, 3388, 3370, 3383, -1, 3389, 3390, 3391, -1, 3392, 3372, 3385, -1, 3389, 3393, 3390, -1, 3392, 3375, 3372, -1, 3394, 3378, 3377, -1, 3394, 3373, 3388, -1, 3395, 3389, 3391, -1, 3394, 3377, 3373, -1, 3396, 3391, 3397, -1, 3398, 3367, 3399, -1, 3396, 3395, 3391, -1, 3398, 3381, 3367, -1, 3396, 3397, 3400, -1, 3401, 3375, 3392, -1, 3402, 3400, 3397, -1, 3401, 3383, 3375, -1, 3402, 3403, 3400, -1, 3404, 3385, 3381, -1, 3405, 3402, 3397, -1, 3404, 3381, 3398, -1, 3406, 3383, 3401, -1, 3406, 3388, 3383, -1, 3407, 3397, 3408, -1, 3407, 3405, 3397, -1, 3407, 3408, 3409, -1, 3410, 3411, 3409, -1, 3412, 3385, 3404, -1, 3410, 3409, 3408, -1, 3412, 3392, 3385, -1, 3413, 3388, 3406, -1, 3413, 3394, 3388, -1, 3413, 3414, 3378, -1, 3413, 3378, 3394, -1, 3415, 3398, 3399, -1, 3416, 3410, 3408, -1, 3417, 3418, 3419, -1, 3420, 3392, 3412, -1, 3417, 3408, 3418, -1, 3417, 3416, 3408, -1, 3421, 3422, 3419, -1, 3421, 3419, 3418, -1, 3420, 3401, 3392, -1, 3423, 3398, 3415, -1, 3423, 3404, 3398, -1, 3424, 3401, 3420, -1, 2896, 3421, 3418, -1, 2898, 3418, 3425, -1, 3424, 3406, 3401, -1, 2898, 2896, 3418, -1, 3426, 3412, 3404, -1, 2898, 3425, 3427, -1, 3426, 3404, 3423, -1, 3428, 3429, 3430, -1, 3428, 3431, 3429, -1, 3428, 3430, 3432, -1, 3428, 3433, 3431, -1, 3434, 3413, 3406, -1, 3428, 3432, 3433, -1, 3434, 3406, 3424, -1, 3434, 3414, 3413, -1, 3435, 2885, 3433, -1, 3436, 3420, 3412, -1, 3435, 2883, 2885, -1, 3435, 3437, 2883, -1, 3436, 3412, 3426, -1, 3438, 2884, 2883, -1, 3438, 2909, 2884, -1, 3439, 3415, 3399, -1, 3439, 3399, 3440, -1, 2959, 2911, 2908, -1, 2957, 2946, 2945, -1, 3441, 3424, 3420, -1, 3441, 3420, 3436, -1, 2957, 2945, 2911, -1, 3442, 3423, 3415, -1, 3442, 3415, 3439, -1, 3443, 3327, 3328, -1, 3443, 3332, 3327, -1, 3444, 3434, 3424, -1, 3444, 3424, 3441, -1, 3444, 3414, 3434, -1, 3444, 3445, 3414, -1, 3446, 3426, 3423, -1, 3446, 3423, 3442, -1, 3447, 3443, 3328, -1, 3448, 3328, 3449, -1, 3448, 3449, 3450, -1, 3448, 3447, 3328, -1, 3451, 3439, 3440, -1, 3452, 3450, 3449, -1, 3452, 3453, 3450, -1, 3454, 3436, 3426, -1, 3454, 3426, 3446, -1, 3455, 3442, 3439, -1, 3456, 3452, 3449, -1, 3457, 3449, 3458, -1, 3455, 3439, 3451, -1, 3459, 3441, 3436, -1, 3457, 3456, 3449, -1, 3457, 3458, 3460, -1, 3459, 3436, 3454, -1, 3461, 3460, 3458, -1, 3461, 3462, 3460, -1, 3463, 3446, 3442, -1, 3463, 3442, 3455, -1, 3464, 3444, 3441, -1, 3465, 3461, 3458, -1, 3464, 3445, 3444, -1, 3464, 3441, 3459, -1, 3466, 3458, 3467, -1, 3468, 3454, 3446, -1, 3466, 3467, 3469, -1, 3468, 3446, 3463, -1, 3466, 3465, 3458, -1, 3470, 3471, 3469, -1, 3472, 3440, 3473, -1, 3470, 3469, 3467, -1, 3472, 3451, 3440, -1, 3474, 3459, 3454, -1, 3474, 3454, 3468, -1, 3053, 3470, 3467, -1, 3056, 3467, 3075, -1, 3475, 3455, 3451, -1, 3056, 3053, 3467, -1, 3056, 3075, 3365, -1, 3476, 3224, 3220, -1, 3476, 3245, 3386, -1, 3475, 3451, 3472, -1, 3476, 3228, 3224, -1, 3477, 3445, 3464, -1, 3476, 3220, 3242, -1, 3477, 3478, 3445, -1, 3476, 3386, 3228, -1, 3477, 3464, 3459, -1, 3476, 3242, 3245, -1, 3479, 3261, 3270, -1, 3477, 3459, 3474, -1, 3479, 3387, 3244, -1, 3479, 3244, 3245, -1, 3479, 3270, 3387, -1, 3480, 3472, 3473, -1, 3479, 3242, 3261, -1, 3479, 3245, 3242, -1, 3481, 3482, 3393, -1, 3483, 3463, 3455, -1, 3481, 3484, 3482, -1, 3483, 3455, 3475, -1, 3485, 3481, 3393, -1, 3485, 3389, 3395, -1, 3485, 3393, 3389, -1, 3486, 3475, 3472, -1, 3486, 3472, 3480, -1, 3487, 3463, 3483, -1, 3487, 3468, 3463, -1, 3102, 3485, 3395, -1, 3488, 3475, 3486, -1, 3489, 3396, 3400, -1, 3488, 3483, 3475, -1, 3490, 3468, 3487, -1, 3489, 3400, 3403, -1, 3490, 3474, 3468, -1, 3491, 3102, 3395, -1, 3491, 3396, 3489, -1, 3491, 3395, 3396, -1, 3492, 3483, 3488, -1, 3493, 3489, 3403, -1, 3493, 3491, 3489, -1, 3493, 3403, 3494, -1, 3492, 3487, 3483, -1, 3493, 3494, 3495, -1, 3496, 3474, 3490, -1, 3496, 3478, 3477, -1, 3496, 3477, 3474, -1, 3497, 3494, 3403, -1, 3497, 3495, 3494, -1, 3498, 3473, 3499, -1, 3500, 3497, 3403, -1, 3498, 3480, 3473, -1, 3501, 3490, 3487, -1, 3500, 3403, 3402, -1, 3500, 3402, 3405, -1, 3501, 3487, 3492, -1, 3502, 3486, 3480, -1, 3502, 3480, 3498, -1, 3122, 3500, 3405, -1, 3503, 3496, 3490, -1, 3503, 3490, 3501, -1, 3504, 3407, 3409, -1, 3503, 3478, 3496, -1, 3504, 3409, 3411, -1, 3503, 3505, 3478, -1, 3506, 3498, 3499, -1, 3507, 3407, 3504, -1, 3508, 3486, 3502, -1, 3507, 3122, 3405, -1, 3507, 3405, 3407, -1, 3509, 3504, 3411, -1, 3509, 3507, 3504, -1, 3508, 3488, 3486, -1, 3509, 3411, 3510, -1, 3511, 3512, 3510, -1, 3513, 3498, 3506, -1, 3513, 3502, 3498, -1, 3511, 3510, 3411, -1, 3514, 3488, 3508, -1, 3515, 3411, 3410, -1, 3515, 3511, 3411, -1, 3514, 3492, 3488, -1, 3516, 3508, 3502, -1, 3515, 3410, 3416, -1, 3516, 3502, 3513, -1, 3517, 3492, 3514, -1, 3517, 3501, 3492, -1, 3147, 3515, 3416, -1, 3518, 3419, 3422, -1, 3519, 3514, 3508, -1, 3519, 3508, 3516, -1, 3518, 3417, 3419, -1, 3520, 3503, 3501, -1, 3521, 3416, 3417, -1, 3520, 3505, 3503, -1, 3520, 3501, 3517, -1, 3390, 3506, 3499, -1, 3521, 3147, 3416, -1, 3390, 3499, 3391, -1, 3521, 3417, 3518, -1, 3522, 3422, 2880, -1, 3522, 3518, 3422, -1, 3522, 3521, 3518, -1, 3523, 3517, 3514, -1, 2902, 2880, 3422, -1, 3523, 3514, 3519, -1, 2902, 2881, 2880, -1, 3393, 3513, 3506, -1, 2895, 3422, 3421, -1, 3393, 3506, 3390, -1, 2895, 3421, 2896, -1, 3524, 3517, 3523, -1, 3524, 3505, 3520, -1, 2895, 2902, 3422, -1, 3524, 3520, 3517, -1, 3524, 3111, 3505, -1, 3482, 3516, 3513, -1, 3482, 3513, 3393, -1, 2905, 2898, 3427, -1, 3484, 3519, 3516, -1, 2905, 3427, 3525, -1, 3484, 3516, 3482, -1, 3526, 3523, 3519, -1, 3526, 3519, 3484, -1, 3108, 3524, 3523, -1, 2913, 2906, 2905, -1, 3108, 3111, 3524, -1, 2913, 2905, 3525, -1, 3108, 3523, 3526, -1, 2913, 3525, 2919, -1, 3527, 3432, 2873, -1, 3527, 3435, 3433, -1, 3527, 3433, 3432, -1, 3527, 2873, 2872, -1, 3527, 2872, 3437, -1, 3527, 3437, 3435, -1, 3528, 3437, 2872, -1, 3528, 3438, 2883, -1, 3528, 2883, 3437, -1, 3528, 2872, 2904, -1, 3528, 2904, 2909, -1, 3528, 2909, 3438, -1, 3529, 2909, 2904, -1, 3529, 2959, 2908, -1, 3529, 2908, 2909, -1, 2938, 3529, 2904, -1, 2960, 2938, 2937, -1, 2960, 3529, 2938, -1, 2960, 2959, 3529, -1, 2953, 2933, 2941, -1, 2962, 2941, 2946, -1, 2962, 2953, 2941, -1, 2962, 2952, 2953, -1, 2962, 2946, 2957, -1, 2967, 2968, 3335, -1, 2967, 3335, 3332, -1, 2965, 3332, 3443, -1, 2965, 3443, 3447, -1, 2965, 2967, 3332, -1, 2966, 2965, 3447, -1, 3530, 3448, 3450, -1, 3530, 3450, 3453, -1, 2980, 3448, 3530, -1, 2980, 3447, 3448, -1, 2980, 2966, 3447, -1, 2981, 2980, 3530, -1, 2981, 3530, 3453, -1, 2981, 3531, 2982, -1, 2981, 3453, 3531, -1, 2991, 2982, 3531, -1, 2991, 3531, 3453, -1, 2992, 3453, 3452, -1, 2992, 3452, 3456, -1, 2992, 2991, 3453, -1, 2993, 2992, 3456, -1, 3532, 3457, 3460, -1, 3532, 3460, 3462, -1, 3001, 3457, 3532, -1, 3001, 3456, 3457, -1, 3001, 2993, 3456, -1, 3002, 3001, 3532, -1, 3002, 3532, 3462, -1, 3002, 3462, 3010, -1, 3023, 3010, 3462, -1, 3023, 3012, 3010, -1, 3021, 3023, 3462, -1, 3021, 3462, 3461, -1, 3021, 3461, 3465, -1, 3533, 3425, 3534, -1, 3533, 3427, 3425, -1, 3535, 3427, 3533, -1, 3022, 3021, 3465, -1, 3535, 3525, 3427, -1, 3536, 3469, 3471, -1, 3536, 3466, 3469, -1, 3537, 3525, 3535, -1, 3537, 2919, 3525, -1, 3032, 3465, 3466, -1, 3032, 3022, 3465, -1, 3032, 3466, 3536, -1, 3538, 2919, 3537, -1, 3538, 2925, 2919, -1, 3033, 3471, 3037, -1, 3033, 3032, 3536, -1, 3033, 3536, 3471, -1, 3061, 3044, 3037, -1, 3539, 2926, 2925, -1, 3539, 2925, 3538, -1, 3061, 3037, 3471, -1, 3540, 2931, 2926, -1, 3540, 3170, 2931, -1, 3052, 3471, 3470, -1, 3540, 2926, 3539, -1, 3052, 3061, 3471, -1, 3540, 3541, 3170, -1, 3052, 3470, 3053, -1, 3542, 3534, 3543, -1, 3542, 3533, 3534, -1, 3544, 3535, 3533, -1, 3544, 3533, 3542, -1, 3063, 3365, 3368, -1, 3545, 3535, 3544, -1, 3063, 3056, 3365, -1, 3545, 3537, 3535, -1, 3072, 3063, 3368, -1, 3546, 3538, 3537, -1, 3072, 3064, 3063, -1, 3072, 3368, 3079, -1, 3546, 3537, 3545, -1, 3096, 3485, 3102, -1, 3547, 3539, 3538, -1, 3096, 3481, 3485, -1, 3096, 3484, 3481, -1, 3547, 3538, 3546, -1, 3548, 3540, 3539, -1, 3107, 3484, 3096, -1, 3548, 3541, 3540, -1, 3548, 3549, 3541, -1, 3107, 3526, 3484, -1, 3548, 3539, 3547, -1, 3107, 3108, 3526, -1, 3550, 3543, 3551, -1, 3095, 3107, 3096, -1, 3550, 3542, 3543, -1, 3552, 3542, 3550, -1, 3552, 3544, 3542, -1, 3553, 3545, 3544, -1, 3103, 3491, 3493, -1, 3103, 3493, 3495, -1, 3553, 3544, 3552, -1, 3103, 3102, 3491, -1, 3554, 3546, 3545, -1, 3554, 3545, 3553, -1, 3555, 3546, 3554, -1, 3114, 3103, 3495, -1, 3114, 3105, 3103, -1, 3555, 3547, 3546, -1, 3114, 3495, 3556, -1, 3114, 3556, 3115, -1, 3129, 3497, 3500, -1, 3557, 3547, 3555, -1, 3129, 3500, 3122, -1, 3557, 3558, 3549, -1, 3129, 3495, 3497, -1, 3557, 3549, 3548, -1, 3557, 3548, 3547, -1, 3131, 3495, 3129, -1, 3559, 3551, 3560, -1, 3559, 3550, 3551, -1, 3131, 3556, 3495, -1, 3131, 3115, 3556, -1, 3561, 3552, 3550, -1, 3121, 3131, 3129, -1, 3561, 3550, 3559, -1, 3562, 3552, 3561, -1, 3123, 3122, 3507, -1, 3562, 3553, 3552, -1, 3123, 3507, 3509, -1, 3563, 3553, 3562, -1, 3563, 3554, 3553, -1, 3430, 3554, 3563, -1, 3430, 3555, 3554, -1, 3429, 3557, 3555, -1, 3429, 3558, 3557, -1, 3564, 3123, 3509, -1, 3429, 3555, 3430, -1, 3564, 3127, 3123, -1, 3564, 3509, 3510, -1, 3429, 3431, 3558, -1, 3565, 3510, 3512, -1, 3566, 3560, 3567, -1, 3565, 3512, 3568, -1, 3566, 3559, 3560, -1, 3565, 3564, 3510, -1, 2870, 3561, 3559, -1, 3138, 3568, 3139, -1, 3138, 3127, 3564, -1, 3138, 3128, 3127, -1, 3138, 3565, 3568, -1, 3138, 3564, 3565, -1, 2870, 3559, 3566, -1, 2874, 3561, 2870, -1, 2874, 3562, 3561, -1, 3146, 3511, 3515, -1, 3146, 3515, 3147, -1, 3146, 3512, 3511, -1, 3153, 3512, 3146, -1, 3153, 3568, 3512, -1, 2873, 3563, 3562, -1, 3153, 3139, 3568, -1, 2873, 3562, 2874, -1, 3149, 3153, 3146, -1, 3432, 3430, 3563, -1, 3432, 3563, 2873, -1, 3433, 2885, 3431, -1, 2876, 3147, 3521, -1, 2891, 3567, 2889, -1, 2891, 3566, 3567, -1, 2876, 3521, 3522, -1, 2871, 3566, 2891, -1, 2871, 2870, 3566, -1, 2877, 2876, 3522, -1, 2869, 2874, 2870, -1, 2877, 3522, 2880, -1, 3569, 3570, 3571, -1, 3569, 3571, 3572, -1, 3573, 3574, 3575, -1, 3573, 3576, 3577, -1, 3573, 3578, 3574, -1, 3573, 3575, 3576, -1, 3579, 3572, 3580, -1, 3581, 3577, 3570, -1, 3581, 3570, 3569, -1, 3582, 3569, 3572, -1, 3582, 3572, 3579, -1, 3583, 3573, 3577, -1, 3583, 3577, 3581, -1, 3583, 3578, 3573, -1, 3584, 3580, 3585, -1, 3584, 3579, 3580, -1, 3586, 3581, 3569, -1, 3586, 3569, 3582, -1, 3587, 3582, 3579, -1, 3587, 3579, 3584, -1, 3588, 3583, 3581, -1, 3588, 3578, 3583, -1, 3588, 3581, 3586, -1, 3588, 3589, 3578, -1, 3590, 3584, 3585, -1, 3591, 3586, 3582, -1, 3591, 3582, 3587, -1, 3592, 3587, 3584, -1, 3592, 3584, 3590, -1, 3593, 3588, 3586, -1, 3593, 3589, 3588, -1, 3593, 3586, 3591, -1, 3594, 3585, 3595, -1, 3594, 3590, 3585, -1, 3596, 3587, 3592, -1, 3596, 3591, 3587, -1, 3597, 3592, 3590, -1, 3597, 3590, 3594, -1, 3598, 3599, 3589, -1, 3598, 3589, 3593, -1, 3598, 3593, 3591, -1, 3598, 3591, 3596, -1, 3600, 3594, 3595, -1, 3601, 3596, 3592, -1, 3601, 3592, 3597, -1, 3602, 3597, 3594, -1, 3602, 3594, 3600, -1, 3603, 3599, 3598, -1, 3603, 3596, 3601, -1, 3603, 3598, 3596, -1, 3604, 3595, 3605, -1, 3604, 3600, 3595, -1, 3606, 3601, 3597, -1, 3606, 3597, 3602, -1, 3607, 3602, 3600, -1, 3607, 3600, 3604, -1, 3608, 3601, 3606, -1, 3608, 3599, 3603, -1, 3608, 3609, 3599, -1, 3608, 3603, 3601, -1, 3610, 3604, 3605, -1, 3611, 3606, 3602, -1, 3611, 3602, 3607, -1, 3612, 3607, 3604, -1, 3612, 3604, 3610, -1, 3613, 3606, 3611, -1, 3613, 3609, 3608, -1, 3613, 3608, 3606, -1, 3614, 3605, 3615, -1, 3614, 3610, 3605, -1, 3616, 3611, 3607, -1, 3616, 3607, 3612, -1, 3617, 3612, 3610, -1, 3617, 3610, 3614, -1, 3618, 3613, 3611, -1, 3618, 3609, 3613, -1, 3618, 3611, 3616, -1, 3618, 3619, 3609, -1, 3620, 3614, 3615, -1, 3621, 3612, 3617, -1, 3621, 3616, 3612, -1, 3622, 3617, 3614, -1, 3622, 3614, 3620, -1, 3623, 3616, 3621, -1, 3623, 3618, 3616, -1, 3623, 3619, 3618, -1, 3624, 3615, 3625, -1, 3624, 3620, 3615, -1, 3626, 3621, 3617, -1, 3626, 3617, 3622, -1, 3627, 3622, 3620, -1, 3627, 3620, 3624, -1, 3628, 3623, 3621, -1, 3628, 3621, 3626, -1, 3628, 3619, 3623, -1, 3628, 3629, 3619, -1, 3630, 3624, 3625, -1, 3631, 3626, 3622, -1, 3631, 3622, 3627, -1, 3632, 3627, 3624, -1, 3632, 3624, 3630, -1, 3633, 3628, 3626, -1, 3633, 3626, 3631, -1, 3633, 3629, 3628, -1, 3634, 3625, 3635, -1, 3634, 3630, 3625, -1, 3636, 3631, 3627, -1, 3636, 3627, 3632, -1, 3637, 3632, 3630, -1, 3637, 3630, 3634, -1, 3638, 3639, 3629, -1, 3638, 3631, 3636, -1, 3638, 3629, 3633, -1, 3638, 3633, 3631, -1, 3640, 3634, 3635, -1, 3641, 3636, 3632, -1, 3641, 3632, 3637, -1, 3642, 3637, 3634, -1, 3642, 3634, 3640, -1, 3643, 3639, 3638, -1, 3643, 3636, 3641, -1, 3643, 3638, 3636, -1, 3644, 3635, 3645, -1, 3644, 3640, 3635, -1, 3646, 3637, 3642, -1, 3646, 3641, 3637, -1, 3647, 3640, 3644, -1, 3647, 3642, 3640, -1, 3648, 3643, 3641, -1, 3648, 3641, 3646, -1, 3648, 3649, 3639, -1, 3648, 3639, 3643, -1, 3650, 3644, 3645, -1, 3651, 3646, 3642, -1, 3651, 3642, 3647, -1, 3652, 3647, 3644, -1, 3652, 3644, 3650, -1, 3653, 3646, 3651, -1, 3653, 3649, 3648, -1, 3653, 3648, 3646, -1, 3654, 3645, 3655, -1, 3654, 3650, 3645, -1, 3656, 3647, 3652, -1, 3656, 3651, 3647, -1, 3657, 3658, 3659, -1, 3660, 3652, 3650, -1, 3660, 3650, 3654, -1, 3661, 3662, 3663, -1, 3661, 3664, 3662, -1, 3665, 3651, 3656, -1, 3665, 3653, 3651, -1, 3665, 3649, 3653, -1, 3665, 3666, 3649, -1, 3667, 3664, 3661, -1, 3668, 3656, 3652, -1, 3668, 3652, 3660, -1, 3667, 3669, 3664, -1, 3670, 3671, 3669, -1, 3672, 3654, 3655, -1, 3670, 3669, 3667, -1, 3673, 3674, 3675, -1, 3676, 3665, 3656, -1, 3673, 3671, 3670, -1, 3676, 3656, 3668, -1, 3673, 3677, 3671, -1, 3676, 3666, 3665, -1, 3673, 3675, 3677, -1, 3678, 3660, 3654, -1, 3679, 3663, 3680, -1, 3679, 3661, 3663, -1, 3678, 3654, 3672, -1, 3681, 3661, 3679, -1, 3682, 3672, 3655, -1, 3682, 3655, 3683, -1, 3681, 3667, 3661, -1, 3684, 3668, 3660, -1, 3685, 3667, 3681, -1, 3684, 3660, 3678, -1, 3685, 3670, 3667, -1, 3686, 3678, 3672, -1, 3687, 3670, 3685, -1, 3687, 3673, 3670, -1, 3686, 3672, 3682, -1, 3687, 3688, 3674, -1, 3687, 3674, 3673, -1, 3689, 3676, 3668, -1, 3689, 3666, 3676, -1, 3690, 3679, 3680, -1, 3689, 3668, 3684, -1, 3690, 3680, 3691, -1, 3689, 3692, 3666, -1, 3693, 3678, 3686, -1, 3693, 3684, 3678, -1, 3694, 3681, 3679, -1, 3694, 3679, 3690, -1, 3695, 3681, 3694, -1, 3696, 3682, 3683, -1, 3695, 3685, 3681, -1, 3697, 3689, 3684, -1, 3697, 3692, 3689, -1, 3697, 3684, 3693, -1, 3698, 3685, 3695, -1, 3698, 3699, 3688, -1, 3700, 3696, 3683, -1, 3698, 3687, 3685, -1, 3700, 3683, 3701, -1, 3698, 3688, 3687, -1, 3702, 3686, 3682, -1, 3703, 3691, 3704, -1, 3702, 3682, 3696, -1, 3703, 3690, 3691, -1, 3705, 3696, 3700, -1, 3706, 3694, 3690, -1, 3705, 3702, 3696, -1, 3706, 3690, 3703, -1, 3707, 3693, 3686, -1, 3707, 3686, 3702, -1, 3708, 3694, 3706, -1, 3708, 3695, 3694, -1, 3709, 3707, 3702, -1, 3710, 3711, 3699, -1, 3710, 3698, 3695, -1, 3709, 3702, 3705, -1, 3710, 3699, 3698, -1, 3710, 3695, 3708, -1, 3712, 3697, 3693, -1, 3712, 3713, 3692, -1, 3712, 3692, 3697, -1, 3714, 3704, 3715, -1, 3712, 3693, 3707, -1, 3714, 3703, 3704, -1, 3716, 3700, 3701, -1, 3717, 3703, 3714, -1, 3718, 3713, 3712, -1, 3718, 3707, 3709, -1, 3717, 3706, 3703, -1, 3718, 3712, 3707, -1, 3719, 3708, 3706, -1, 3720, 3701, 3721, -1, 3719, 3706, 3717, -1, 3720, 3716, 3701, -1, 3722, 3711, 3710, -1, 3723, 3705, 3700, -1, 3722, 3724, 3711, -1, 3723, 3700, 3716, -1, 3722, 3710, 3708, -1, 3722, 3708, 3719, -1, 3725, 3714, 3715, -1, 3726, 3723, 3716, -1, 3726, 3716, 3720, -1, 3725, 3715, 3727, -1, 3728, 3709, 3705, -1, 3728, 3705, 3723, -1, 3729, 3728, 3723, -1, 3730, 3714, 3725, -1, 3730, 3717, 3714, -1, 3731, 3719, 3717, -1, 3729, 3723, 3726, -1, 3731, 3717, 3730, -1, 3732, 3709, 3728, -1, 3732, 3733, 3713, -1, 3732, 3713, 3718, -1, 3734, 3722, 3719, -1, 3732, 3718, 3709, -1, 3734, 3724, 3722, -1, 3734, 3735, 3724, -1, 3734, 3719, 3731, -1, 3736, 3720, 3721, -1, 3737, 3733, 3732, -1, 3737, 3732, 3728, -1, 3738, 3727, 3739, -1, 3737, 3728, 3729, -1, 3738, 3725, 3727, -1, 3740, 3721, 3741, -1, 3740, 3736, 3721, -1, 3742, 3730, 3725, -1, 3743, 3720, 3736, -1, 3742, 3725, 3738, -1, 3744, 3731, 3730, -1, 3743, 3726, 3720, -1, 3745, 3743, 3736, -1, 3744, 3730, 3742, -1, 3745, 3736, 3740, -1, 3746, 3731, 3744, -1, 3746, 3734, 3731, -1, 3746, 3735, 3734, -1, 3747, 3729, 3726, -1, 3746, 3748, 3735, -1, 3747, 3726, 3743, -1, 3749, 3739, 3750, -1, 3751, 3747, 3743, -1, 3751, 3743, 3745, -1, 3749, 3738, 3739, -1, 3752, 3738, 3749, -1, 3753, 3733, 3737, -1, 3753, 3737, 3729, -1, 3753, 3729, 3747, -1, 3752, 3742, 3738, -1, 3753, 3754, 3733, -1, 3755, 3740, 3741, -1, 3756, 3742, 3752, -1, 3757, 3747, 3751, -1, 3756, 3744, 3742, -1, 3757, 3753, 3747, -1, 3758, 3748, 3746, -1, 3757, 3754, 3753, -1, 3758, 3746, 3744, -1, 3758, 3744, 3756, -1, 3759, 3740, 3755, -1, 3758, 3760, 3748, -1, 3759, 3745, 3740, -1, 3761, 3750, 3762, -1, 3761, 3749, 3750, -1, 3763, 3751, 3745, -1, 3764, 3749, 3761, -1, 3763, 3745, 3759, -1, 3764, 3752, 3749, -1, 3765, 3757, 3751, -1, 3765, 3754, 3757, -1, 3765, 3751, 3763, -1, 3765, 3766, 3754, -1, 3767, 3756, 3752, -1, 3768, 3741, 3769, -1, 3768, 3755, 3741, -1, 3767, 3752, 3764, -1, 3770, 3771, 3760, -1, 3772, 3755, 3768, -1, 3770, 3758, 3756, -1, 3770, 3760, 3758, -1, 3770, 3756, 3767, -1, 3772, 3759, 3755, -1, 3773, 3762, 3774, -1, 3775, 3759, 3772, -1, 3775, 3763, 3759, -1, 3773, 3761, 3762, -1, 3776, 3763, 3775, -1, 3777, 3773, 3774, -1, 3776, 3765, 3763, -1, 3776, 3766, 3765, -1, 3778, 3764, 3761, -1, 3776, 3779, 3766, -1, 3780, 3781, 3782, -1, 3780, 3769, 3781, -1, 3778, 3761, 3773, -1, 3780, 3768, 3769, -1, 3783, 3773, 3777, -1, 3783, 3778, 3773, -1, 3784, 3772, 3768, -1, 3785, 3767, 3764, -1, 3784, 3768, 3780, -1, 3785, 3764, 3778, -1, 3786, 3775, 3772, -1, 3787, 3778, 3783, -1, 3786, 3772, 3784, -1, 3787, 3785, 3778, -1, 3788, 3789, 3771, -1, 3790, 3776, 3775, -1, 3788, 3771, 3770, -1, 3790, 3779, 3776, -1, 3788, 3770, 3767, -1, 3790, 3775, 3786, -1, 3788, 3767, 3785, -1, 3790, 3791, 3779, -1, 3792, 3774, 3793, -1, 3794, 3780, 3782, -1, 3792, 3777, 3774, -1, 3795, 3796, 3789, -1, 3795, 3785, 3787, -1, 3795, 3789, 3788, -1, 3797, 3784, 3780, -1, 3795, 3788, 3785, -1, 3797, 3780, 3794, -1, 3798, 3786, 3784, -1, 3799, 3792, 3793, -1, 3798, 3784, 3797, -1, 3800, 3783, 3777, -1, 3800, 3777, 3792, -1, 3801, 3790, 3786, -1, 3802, 3792, 3799, -1, 3801, 3791, 3790, -1, 3801, 3803, 3791, -1, 3801, 3786, 3798, -1, 3802, 3800, 3792, -1, 3804, 3782, 3805, -1, 3806, 3783, 3800, -1, 3804, 3794, 3782, -1, 3806, 3787, 3783, -1, 3807, 3800, 3802, -1, 3807, 3806, 3800, -1, 3808, 3797, 3794, -1, 3809, 3795, 3787, -1, 3809, 3787, 3806, -1, 3808, 3794, 3804, -1, 3809, 3796, 3795, -1, 3810, 3798, 3797, -1, 3810, 3797, 3808, -1, 3811, 3793, 3812, -1, 3813, 3814, 3803, -1, 3811, 3799, 3793, -1, 3815, 3809, 3806, -1, 3813, 3801, 3798, -1, 3813, 3803, 3801, -1, 3815, 3806, 3807, -1, 3815, 3796, 3809, -1, 3813, 3798, 3810, -1, 3815, 3816, 3796, -1, 3817, 3811, 3812, -1, 3818, 3805, 3819, -1, 3818, 3804, 3805, -1, 3820, 3802, 3799, -1, 3820, 3799, 3811, -1, 3821, 3808, 3804, -1, 3821, 3804, 3818, -1, 3822, 3820, 3811, -1, 3822, 3811, 3817, -1, 3823, 3808, 3821, -1, 3824, 3807, 3802, -1, 3823, 3810, 3808, -1, 3824, 3802, 3820, -1, 3825, 3810, 3823, -1, 3825, 3826, 3814, -1, 3827, 3820, 3822, -1, 3825, 3814, 3813, -1, 3827, 3824, 3820, -1, 3825, 3813, 3810, -1, 3828, 3819, 3829, -1, 3830, 3815, 3807, -1, 3830, 3816, 3815, -1, 3830, 3807, 3824, -1, 3831, 3812, 3832, -1, 3828, 3818, 3819, -1, 3831, 3817, 3812, -1, 3833, 3818, 3828, -1, 3834, 3824, 3827, -1, 3833, 3821, 3818, -1, 3834, 3816, 3830, -1, 3835, 3823, 3821, -1, 3834, 3830, 3824, -1, 3834, 3836, 3816, -1, 3835, 3821, 3833, -1, 3837, 3822, 3817, -1, 3838, 3825, 3823, -1, 3837, 3817, 3831, -1, 3838, 3826, 3825, -1, 3838, 3823, 3835, -1, 3838, 3839, 3826, -1, 3840, 3831, 3832, -1, 3841, 3828, 3829, -1, 3841, 3829, 3842, -1, 3843, 3827, 3822, -1, 3843, 3822, 3837, -1, 3844, 3828, 3841, -1, 3845, 3837, 3831, -1, 3844, 3833, 3828, -1, 3845, 3831, 3840, -1, 3846, 3834, 3827, -1, 3847, 3835, 3833, -1, 3846, 3836, 3834, -1, 3846, 3827, 3843, -1, 3847, 3833, 3844, -1, 3848, 3843, 3837, -1, 3848, 3837, 3845, -1, 3849, 3838, 3835, -1, 3849, 3839, 3838, -1, 3849, 3835, 3847, -1, 3850, 3832, 3851, -1, 3849, 3852, 3839, -1, 3850, 3840, 3832, -1, 3853, 3854, 3855, -1, 3853, 3842, 3854, -1, 3853, 3841, 3842, -1, 3856, 3857, 3836, -1, 3856, 3836, 3846, -1, 3853, 3855, 3858, -1, 3856, 3846, 3843, -1, 3856, 3843, 3848, -1, 3859, 3840, 3850, -1, 3860, 3844, 3841, -1, 3859, 3845, 3840, -1, 3860, 3853, 3858, -1, 3860, 3858, 3861, -1, 3860, 3841, 3853, -1, 3862, 3847, 3844, -1, 3863, 3850, 3851, -1, 3862, 3844, 3860, -1, 3862, 3860, 3861, -1, 3864, 3845, 3859, -1, 3862, 3861, 3865, -1, 3864, 3848, 3845, -1, 3866, 3849, 3847, -1, 3866, 3852, 3849, -1, 3866, 3865, 3659, -1, 3866, 3862, 3865, -1, 3866, 3847, 3862, -1, 3867, 3859, 3850, -1, 3866, 3659, 3658, -1, 3866, 3658, 3852, -1, 3867, 3850, 3863, -1, 3868, 3857, 3856, -1, 3868, 3856, 3848, -1, 3868, 3848, 3864, -1, 3869, 3851, 3870, -1, 3869, 3863, 3851, -1, 3871, 3864, 3859, -1, 3871, 3859, 3867, -1, 3872, 3867, 3863, -1, 3872, 3863, 3869, -1, 3873, 3874, 3857, -1, 3873, 3857, 3868, -1, 3873, 3864, 3871, -1, 3873, 3868, 3864, -1, 3875, 3869, 3870, -1, 3876, 3871, 3867, -1, 3876, 3867, 3872, -1, 3877, 3869, 3875, -1, 3877, 3872, 3869, -1, 3878, 3873, 3871, -1, 3878, 3874, 3873, -1, 3878, 3871, 3876, -1, 3879, 3870, 3880, -1, 3879, 3875, 3870, -1, 3881, 3872, 3877, -1, 3881, 3876, 3872, -1, 3882, 3877, 3875, -1, 3882, 3875, 3879, -1, 3883, 3878, 3876, -1, 3883, 3874, 3878, -1, 3883, 3876, 3881, -1, 3883, 3574, 3874, -1, 3571, 3879, 3880, -1, 3576, 3877, 3882, -1, 3576, 3881, 3877, -1, 3570, 3882, 3879, -1, 3570, 3879, 3571, -1, 3575, 3881, 3576, -1, 3575, 3574, 3883, -1, 3575, 3883, 3881, -1, 3572, 3880, 3580, -1, 3572, 3571, 3880, -1, 3577, 3576, 3882, -1, 3577, 3882, 3570, -1, 3884, 3885, 3886, -1, 3887, 3885, 3888, -1, 3886, 3885, 3889, -1, 3888, 3885, 3884, -1, 3890, 3891, 3892, -1, 3893, 3894, 3895, -1, 3896, 3897, 3898, -1, 3895, 3894, 3899, -1, 3898, 3897, 3900, -1, 3899, 3901, 3902, -1, 3889, 3903, 3896, -1, 3896, 3903, 3897, -1, 3904, 3905, 3906, -1, 3906, 3905, 3890, -1, 3907, 3905, 3904, -1, 3900, 3908, 3909, -1, 3890, 3905, 3891, -1, 3910, 3908, 3911, -1, 3909, 3908, 3910, -1, 3893, 3912, 3894, -1, 3891, 3912, 3893, -1, 3913, 3914, 3887, -1, 3894, 3915, 3899, -1, 3887, 3914, 3885, -1, 3885, 3914, 3889, -1, 3889, 3914, 3903, -1, 3911, 3916, 3917, -1, 3899, 3915, 3901, -1, 3901, 3918, 3902, -1, 3897, 3916, 3900, -1, 3900, 3916, 3908, -1, 3902, 3918, 3919, -1, 3908, 3916, 3911, -1, 3917, 3920, 3921, -1, 3907, 3922, 3905, -1, 3905, 3922, 3891, -1, 3903, 3920, 3897, -1, 3891, 3922, 3912, -1, 3916, 3920, 3917, -1, 3897, 3920, 3916, -1, 3912, 3923, 3894, -1, 3921, 3924, 3925, -1, 3894, 3923, 3915, -1, 3926, 3924, 3913, -1, 3913, 3924, 3914, -1, 3920, 3924, 3921, -1, 3914, 3924, 3903, -1, 3903, 3924, 3920, -1, 3901, 3927, 3918, -1, 3925, 3924, 3926, -1, 3915, 3927, 3901, -1, 3918, 3928, 3919, -1, 3929, 3930, 3907, -1, 3907, 3930, 3922, -1, 3912, 3930, 3923, -1, 3922, 3930, 3912, -1, 3923, 3931, 3915, -1, 3915, 3931, 3927, -1, 3927, 3932, 3918, -1, 3918, 3932, 3928, -1, 3928, 3933, 3919, -1, 3919, 3933, 3934, -1, 3923, 3935, 3931, -1, 3929, 3935, 3930, -1, 3930, 3935, 3923, -1, 3931, 3936, 3927, -1, 3927, 3936, 3932, -1, 3932, 3937, 3928, -1, 3928, 3937, 3933, -1, 3933, 3938, 3934, -1, 3939, 3940, 3929, -1, 3929, 3940, 3935, -1, 3935, 3940, 3931, -1, 3931, 3940, 3936, -1, 3932, 3941, 3937, -1, 3936, 3941, 3932, -1, 3937, 3942, 3933, -1, 3933, 3942, 3938, -1, 3934, 3943, 3944, -1, 3938, 3943, 3934, -1, 3939, 3945, 3940, -1, 3940, 3945, 3936, -1, 3936, 3945, 3941, -1, 3941, 3946, 3937, -1, 3937, 3946, 3942, -1, 3942, 3947, 3938, -1, 3938, 3947, 3943, -1, 3943, 3948, 3944, -1, 3945, 3949, 3941, -1, 3950, 3949, 3939, -1, 3939, 3949, 3945, -1, 3941, 3949, 3946, -1, 3942, 3951, 3947, -1, 3946, 3951, 3942, -1, 3947, 3952, 3943, -1, 3943, 3952, 3948, -1, 3948, 3953, 3944, -1, 3944, 3953, 3954, -1, 3946, 3955, 3951, -1, 3949, 3955, 3946, -1, 3950, 3955, 3949, -1, 3951, 3956, 3947, -1, 3947, 3956, 3952, -1, 3952, 3957, 3948, -1, 3948, 3957, 3953, -1, 3953, 3958, 3954, -1, 3955, 3959, 3951, -1, 3950, 3959, 3955, -1, 3951, 3959, 3956, -1, 3960, 3959, 3950, -1, 3956, 3961, 3952, -1, 3952, 3961, 3957, -1, 3957, 3962, 3953, -1, 3953, 3962, 3958, -1, 3958, 3963, 3954, -1, 3954, 3963, 3964, -1, 3956, 3965, 3961, -1, 3959, 3965, 3956, -1, 3960, 3965, 3959, -1, 3957, 3966, 3962, -1, 3961, 3966, 3957, -1, 3962, 3967, 3958, -1, 3958, 3967, 3963, -1, 3963, 3968, 3964, -1, 3969, 3970, 3960, -1, 3960, 3970, 3965, -1, 3965, 3970, 3961, -1, 3961, 3970, 3966, -1, 3966, 3971, 3962, -1, 3962, 3971, 3967, -1, 3967, 3972, 3963, -1, 3963, 3972, 3968, -1, 3968, 3973, 3964, -1, 3964, 3973, 3974, -1, 3969, 3975, 3970, -1, 3966, 3975, 3971, -1, 3970, 3975, 3966, -1, 3971, 3976, 3967, -1, 3967, 3976, 3972, -1, 3972, 3977, 3968, -1, 3968, 3977, 3973, -1, 3973, 3978, 3974, -1, 3979, 3980, 3969, -1, 3975, 3980, 3971, -1, 3969, 3980, 3975, -1, 3971, 3980, 3976, -1, 3976, 3981, 3972, -1, 3972, 3981, 3977, -1, 3977, 3982, 3973, -1, 3973, 3982, 3978, -1, 3974, 3983, 3984, -1, 3978, 3983, 3974, -1, 3979, 3985, 3980, -1, 3980, 3985, 3976, -1, 3976, 3985, 3981, -1, 3981, 3986, 3977, -1, 3977, 3986, 3982, -1, 3982, 3987, 3978, -1, 3978, 3987, 3983, -1, 3983, 3988, 3984, -1, 3979, 3989, 3985, -1, 3990, 3989, 3979, -1, 3981, 3989, 3986, -1, 3985, 3989, 3981, -1, 3986, 3991, 3982, -1, 3982, 3991, 3987, -1, 3987, 3992, 3983, -1, 3983, 3992, 3988, -1, 3988, 3993, 3984, -1, 3984, 3993, 3994, -1, 3990, 3995, 3989, -1, 3989, 3995, 3986, -1, 3986, 3995, 3991, -1, 3987, 3996, 3992, -1, 3991, 3996, 3987, -1, 3992, 3997, 3988, -1, 3988, 3997, 3993, -1, 3993, 3998, 3994, -1, 3990, 3999, 3995, -1, 3995, 3999, 3991, -1, 4000, 3999, 3990, -1, 3991, 3999, 3996, -1, 3996, 4001, 3992, -1, 3992, 4001, 3997, -1, 3997, 4002, 3993, -1, 3993, 4002, 3998, -1, 3910, 3911, 4003, -1, 3998, 4004, 3994, -1, 3994, 4004, 4005, -1, 3996, 4006, 4001, -1, 4000, 4006, 3999, -1, 3999, 4006, 3996, -1, 4001, 4007, 3997, -1, 3997, 4007, 4002, -1, 3926, 4008, 3925, -1, 4002, 4009, 3998, -1, 3998, 4009, 4004, -1, 4010, 4011, 4012, -1, 4004, 4013, 4005, -1, 4012, 4011, 4014, -1, 4015, 4016, 4000, -1, 4006, 4016, 4001, -1, 4001, 4016, 4007, -1, 4017, 4018, 4010, -1, 4000, 4016, 4006, -1, 4010, 4018, 4011, -1, 4007, 4019, 4002, -1, 4002, 4019, 4009, -1, 4017, 4020, 4018, -1, 4021, 4020, 4017, -1, 4009, 4022, 4004, -1, 4004, 4022, 4013, -1, 4014, 4023, 4024, -1, 4013, 4025, 4005, -1, 4011, 4023, 4014, -1, 4005, 4025, 4026, -1, 4021, 4027, 4020, -1, 4015, 4028, 4016, -1, 4029, 4027, 4030, -1, 4031, 4027, 4021, -1, 4016, 4028, 4007, -1, 4030, 4027, 4031, -1, 4007, 4028, 4019, -1, 4018, 4032, 4011, -1, 4019, 4033, 4009, -1, 4009, 4033, 4022, -1, 4011, 4032, 4023, -1, 4022, 4034, 4013, -1, 4020, 4035, 4018, -1, 4018, 4035, 4032, -1, 4013, 4034, 4025, -1, 4025, 4036, 4026, -1, 4024, 4037, 4038, -1, 4015, 4039, 4028, -1, 4040, 4039, 4015, -1, 4023, 4037, 4024, -1, 4028, 4039, 4019, -1, 4019, 4039, 4033, -1, 4020, 4041, 4035, -1, 4022, 4042, 4034, -1, 4043, 4041, 4029, -1, 4029, 4041, 4027, -1, 4033, 4042, 4022, -1, 4027, 4041, 4020, -1, 4032, 4044, 4023, -1, 4023, 4044, 4037, -1, 4034, 4045, 4025, -1, 4025, 4045, 4036, -1, 4036, 4046, 4026, -1, 4026, 4046, 4047, -1, 4032, 4048, 4044, -1, 4035, 4048, 4032, -1, 4040, 4049, 4039, -1, 4039, 4049, 4033, -1, 4037, 4050, 4038, -1, 4033, 4049, 4042, -1, 4038, 4050, 4051, -1, 4042, 4052, 4034, -1, 4035, 4053, 4048, -1, 4034, 4052, 4045, -1, 4054, 4053, 4043, -1, 4041, 4053, 4035, -1, 4043, 4053, 4041, -1, 4045, 4055, 4036, -1, 4036, 4055, 4046, -1, 4037, 4056, 4050, -1, 4046, 4057, 4047, -1, 4044, 4056, 4037, -1, 4048, 4058, 4044, -1, 4049, 4059, 4042, -1, 4060, 4059, 4040, -1, 4040, 4059, 4049, -1, 4042, 4059, 4052, -1, 4044, 4058, 4056, -1, 4051, 4061, 4062, -1, 4050, 4061, 4051, -1, 4052, 4063, 4045, -1, 4045, 4063, 4055, -1, 4046, 4064, 4057, -1, 4048, 4065, 4058, -1, 4054, 4065, 4053, -1, 4055, 4064, 4046, -1, 4066, 4065, 4054, -1, 4053, 4065, 4048, -1, 4057, 4067, 4047, -1, 4047, 4067, 4068, -1, 4050, 4069, 4061, -1, 4060, 4070, 4059, -1, 4056, 4069, 4050, -1, 4059, 4070, 4052, -1, 4052, 4070, 4063, -1, 4056, 4071, 4069, -1, 4055, 4072, 4064, -1, 4058, 4071, 4056, -1, 4061, 4073, 4062, -1, 4063, 4072, 4055, -1, 4067, 4074, 4068, -1, 4062, 4073, 4075, -1, 4064, 4076, 4057, -1, 4066, 4077, 4065, -1, 4057, 4076, 4067, -1, 4065, 4077, 4058, -1, 4078, 4077, 4066, -1, 4058, 4077, 4071, -1, 4060, 4079, 4070, -1, 4061, 4080, 4073, -1, 4070, 4079, 4063, -1, 4081, 4079, 4060, -1, 4063, 4079, 4072, -1, 4076, 4082, 4067, -1, 4069, 4080, 4061, -1, 4071, 4083, 4069, -1, 4067, 4082, 4074, -1, 4069, 4083, 4080, -1, 4064, 4084, 4076, -1, 4072, 4084, 4064, -1, 4074, 4085, 4068, -1, 4075, 4086, 4087, -1, 4073, 4086, 4075, -1, 4068, 4085, 4088, -1, 4071, 4089, 4083, -1, 4077, 4089, 4071, -1, 4078, 4089, 4077, -1, 4090, 4089, 4078, -1, 4084, 4091, 4076, -1, 4076, 4091, 4082, -1, 4080, 4092, 4073, -1, 4079, 4093, 4072, -1, 4073, 4092, 4086, -1, 4081, 4093, 4079, -1, 4072, 4093, 4084, -1, 4080, 4094, 4092, -1, 4085, 4095, 4088, -1, 4074, 4096, 4085, -1, 4083, 4094, 4080, -1, 4082, 4096, 4074, -1, 4086, 4097, 4087, -1, 4098, 4099, 4081, -1, 4081, 4099, 4093, -1, 4087, 4097, 4100, -1, 4084, 4099, 4091, -1, 4093, 4099, 4084, -1, 4090, 4101, 4089, -1, 4083, 4101, 4094, -1, 4102, 4101, 4090, -1, 4085, 4103, 4095, -1, 4089, 4101, 4083, -1, 4096, 4103, 4085, -1, 4091, 4104, 4082, -1, 4082, 4104, 4096, -1, 4092, 4105, 4086, -1, 4086, 4105, 4097, -1, 4094, 4106, 4092, -1, 4104, 4107, 4096, -1, 4092, 4106, 4105, -1, 4096, 4107, 4103, -1, 4095, 4108, 4088, -1, 4097, 4109, 4100, -1, 4088, 4108, 4110, -1, 4100, 4109, 4111, -1, 4098, 4112, 4099, -1, 4099, 4112, 4091, -1, 4101, 4113, 4094, -1, 4091, 4112, 4104, -1, 4114, 4113, 4102, -1, 4094, 4113, 4106, -1, 4102, 4113, 4101, -1, 4097, 4115, 4109, -1, 4108, 4116, 4110, -1, 4117, 4118, 4098, -1, 4098, 4118, 4112, -1, 4104, 4118, 4107, -1, 4112, 4118, 4104, -1, 4105, 4115, 4097, -1, 4095, 4119, 4108, -1, 4105, 4120, 4115, -1, 4103, 4119, 4095, -1, 4106, 4120, 4105, -1, 4119, 4121, 4108, -1, 4108, 4121, 4116, -1, 4107, 4122, 4103, -1, 4111, 4123, 4124, -1, 4109, 4123, 4111, -1, 4103, 4122, 4119, -1, 4125, 4126, 4114, -1, 4114, 4126, 4113, -1, 4106, 4126, 4120, -1, 4113, 4126, 4106, -1, 4119, 4127, 4121, -1, 4122, 4127, 4119, -1, 4115, 4128, 4109, -1, 4109, 4128, 4123, -1, 4116, 4129, 4110, -1, 4110, 4129, 4130, -1, 4115, 4131, 4128, -1, 4120, 4131, 4115, -1, 4117, 4132, 4118, -1, 4118, 4132, 4107, -1, 4107, 4132, 4122, -1, 4124, 4133, 4134, -1, 4123, 4133, 4124, -1, 4129, 4135, 4130, -1, 4136, 4137, 4117, -1, 4117, 4137, 4132, -1, 4138, 4139, 4125, -1, 4122, 4137, 4127, -1, 4126, 4139, 4120, -1, 4132, 4137, 4122, -1, 4125, 4139, 4126, -1, 4120, 4139, 4131, -1, 4116, 4140, 4129, -1, 4133, 4141, 4134, -1, 4121, 4140, 4116, -1, 4134, 4141, 4142, -1, 4123, 4143, 4133, -1, 4140, 4144, 4129, -1, 4129, 4144, 4135, -1, 4128, 4143, 4123, -1, 4127, 4145, 4121, -1, 4143, 4146, 4133, -1, 4121, 4145, 4140, -1, 4133, 4146, 4141, -1, 4140, 4147, 4144, -1, 4145, 4147, 4140, -1, 4128, 4148, 4143, -1, 4131, 4148, 4128, -1, 4148, 4149, 4143, -1, 4130, 4150, 4151, -1, 4135, 4150, 4130, -1, 4143, 4149, 4146, -1, 4127, 4152, 4145, -1, 4141, 4153, 4142, -1, 4136, 4152, 4137, -1, 4137, 4152, 4127, -1, 4145, 4154, 4147, -1, 4138, 4155, 4139, -1, 4136, 4154, 4152, -1, 4139, 4155, 4131, -1, 4156, 4154, 4136, -1, 4152, 4154, 4145, -1, 4144, 4157, 4135, -1, 4158, 4155, 4138, -1, 4131, 4155, 4148, -1, 4153, 4159, 4142, -1, 4135, 4157, 4150, -1, 4142, 4159, 4160, -1, 4148, 4161, 4149, -1, 4155, 4161, 4148, -1, 4158, 4161, 4155, -1, 4144, 4162, 4157, -1, 4146, 4163, 4141, -1, 4147, 4162, 4144, -1, 4141, 4163, 4153, -1, 4150, 4164, 4151, -1, 4151, 4164, 4165, -1, 4163, 4166, 4153, -1, 4156, 4167, 4154, -1, 4147, 4167, 4162, -1, 4154, 4167, 4147, -1, 4153, 4166, 4159, -1, 4149, 4168, 4146, -1, 4150, 4169, 4164, -1, 4146, 4168, 4163, -1, 4163, 4170, 4166, -1, 4157, 4169, 4150, -1, 4168, 4170, 4163, -1, 4162, 4171, 4157, -1, 4159, 4172, 4160, -1, 4157, 4171, 4169, -1, 4161, 4173, 4149, -1, 4164, 4174, 4165, -1, 4158, 4173, 4161, -1, 4175, 4173, 4158, -1, 4149, 4173, 4168, -1, 4165, 4174, 4176, -1, 4177, 4178, 4156, -1, 4162, 4178, 4171, -1, 4172, 4179, 4160, -1, 4160, 4179, 4180, -1, 4167, 4178, 4162, -1, 4156, 4178, 4167, -1, 4169, 4181, 4164, -1, 4168, 4182, 4170, -1, 4175, 4182, 4173, -1, 4173, 4182, 4168, -1, 4166, 4183, 4159, -1, 4164, 4181, 4174, -1, 4159, 4183, 4172, -1, 4169, 4184, 4181, -1, 4171, 4184, 4169, -1, 4183, 4185, 4172, -1, 4172, 4185, 4179, -1, 4174, 4186, 4176, -1, 4166, 4187, 4183, -1, 4170, 4187, 4166, -1, 4176, 4186, 4188, -1, 4189, 4190, 4177, -1, 4177, 4190, 4178, -1, 4179, 4191, 4180, -1, 4178, 4190, 4171, -1, 4171, 4190, 4184, -1, 4174, 4192, 4186, -1, 4183, 4193, 4185, -1, 4181, 4192, 4174, -1, 4187, 4193, 4183, -1, 4194, 4195, 4175, -1, 4184, 4196, 4181, -1, 4170, 4195, 4187, -1, 4175, 4195, 4182, -1, 4182, 4195, 4170, -1, 4181, 4196, 4192, -1, 4180, 4197, 4198, -1, 4186, 4199, 4188, -1, 4191, 4197, 4180, -1, 4185, 4200, 4179, -1, 4188, 4199, 4201, -1, 4179, 4200, 4191, -1, 4202, 4203, 4189, -1, 4189, 4203, 4190, -1, 4184, 4203, 4196, -1, 4190, 4203, 4184, -1, 4194, 4204, 4195, -1, 4187, 4204, 4193, -1, 4195, 4204, 4187, -1, 4192, 4205, 4186, -1, 4186, 4205, 4199, -1, 4200, 4206, 4191, -1, 4191, 4206, 4197, -1, 4192, 4207, 4205, -1, 4185, 4208, 4200, -1, 4196, 4207, 4192, -1, 4193, 4208, 4185, -1, 4199, 4209, 4201, -1, 4197, 4210, 4198, -1, 4201, 4209, 4211, -1, 4200, 4212, 4206, -1, 4213, 4214, 4202, -1, 4208, 4212, 4200, -1, 4202, 4214, 4203, -1, 4203, 4214, 4196, -1, 4196, 4214, 4207, -1, 4215, 4216, 4194, -1, 4194, 4216, 4204, -1, 4199, 4217, 4209, -1, 4204, 4216, 4193, -1, 4193, 4216, 4208, -1, 4205, 4217, 4199, -1, 4207, 4218, 4205, -1, 4206, 4219, 4197, -1, 4197, 4219, 4210, -1, 4205, 4218, 4217, -1, 4198, 4220, 4221, -1, 4210, 4220, 4198, -1, 4209, 4222, 4211, -1, 4211, 4222, 4223, -1, 4215, 4224, 4216, -1, 4225, 4226, 4213, -1, 4208, 4224, 4212, -1, 4213, 4226, 4214, -1, 4216, 4224, 4208, -1, 4207, 4226, 4218, -1, 4206, 4227, 4219, -1, 4214, 4226, 4207, -1, 4209, 4228, 4222, -1, 4212, 4227, 4206, -1, 4217, 4228, 4209, -1, 4210, 3892, 4220, -1, 4218, 3886, 4217, -1, 4219, 3892, 4210, -1, 4217, 3886, 4228, -1, 4220, 3895, 4221, -1, 4222, 3898, 4223, -1, 4215, 4229, 4224, -1, 4223, 3898, 4230, -1, 4212, 4229, 4227, -1, 3904, 4229, 4215, -1, 4224, 4229, 4212, -1, 4219, 3890, 3892, -1, 3888, 3884, 4225, -1, 4225, 3884, 4226, -1, 4226, 3884, 4218, -1, 4218, 3884, 3886, -1, 4227, 3890, 4219, -1, 4228, 3896, 4222, -1, 3892, 3893, 4220, -1, 4222, 3896, 3898, -1, 4220, 3893, 3895, -1, 3895, 3899, 4221, -1, 4228, 3889, 3896, -1, 3886, 3889, 4228, -1, 4221, 3899, 3902, -1, 4229, 3906, 4227, -1, 3904, 3906, 4229, -1, 4227, 3906, 3890, -1, 4230, 3900, 3909, -1, 3898, 3900, 4230, -1, 3892, 3891, 3893, -1, 4231, 4232, 4233, -1, 4233, 4232, 4234, -1, 4235, 4232, 4231, -1, 4234, 4232, 4235, -1, 3913, 4236, 3926, -1, 4237, 4238, 4239, -1, 4240, 4238, 4241, -1, 4242, 4236, 4243, -1, 4241, 4238, 4237, -1, 4239, 4238, 4240, -1, 4136, 4244, 4156, -1, 3887, 4245, 3913, -1, 4241, 4244, 4246, -1, 4236, 4245, 4243, -1, 4246, 4244, 4136, -1, 4156, 4244, 4241, -1, 4247, 4248, 4000, -1, 4000, 4248, 4015, -1, 4243, 4245, 4249, -1, 4015, 4248, 4250, -1, 3913, 4245, 4236, -1, 4250, 4248, 4247, -1, 4225, 4231, 3888, -1, 4247, 4251, 4252, -1, 4252, 4251, 4253, -1, 4253, 4251, 4254, -1, 4245, 4231, 4249, -1, 4254, 4251, 4247, -1, 4255, 4256, 4257, -1, 4249, 4231, 4233, -1, 4258, 4256, 4255, -1, 4213, 4235, 4225, -1, 4259, 4256, 4258, -1, 4257, 4256, 4259, -1, 4258, 4260, 4261, -1, 4225, 4235, 4231, -1, 3929, 4260, 3939, -1, 4261, 4260, 3929, -1, 4234, 4235, 4262, -1, 3939, 4260, 4258, -1, 4202, 4263, 4213, -1, 4138, 4264, 4158, -1, 4189, 4263, 4202, -1, 4158, 4264, 4265, -1, 4266, 4264, 4138, -1, 4213, 4263, 4235, -1, 4265, 4264, 4266, -1, 4235, 4263, 4262, -1, 4267, 4268, 4269, -1, 4262, 4263, 4270, -1, 4271, 4268, 4267, -1, 4263, 4237, 4270, -1, 4266, 4268, 4271, -1, 4177, 4237, 4189, -1, 4269, 4268, 4266, -1, 4272, 4273, 4274, -1, 4274, 4273, 4275, -1, 4270, 4237, 4239, -1, 4276, 4273, 4272, -1, 4189, 4237, 4263, -1, 4275, 4273, 4276, -1, 4156, 4241, 4177, -1, 4066, 4277, 4276, -1, 4278, 4277, 4054, -1, 4177, 4241, 4237, -1, 4276, 4277, 4278, -1, 4054, 4277, 4066, -1, 4240, 4241, 4279, -1, 4117, 4246, 4136, -1, 4280, 4281, 3657, -1, 4282, 4281, 4280, -1, 4241, 4246, 4279, -1, 3657, 4283, 4030, -1, 4281, 4283, 3657, -1, 4279, 4246, 4284, -1, 4030, 4283, 4029, -1, 4098, 4285, 4117, -1, 4029, 4283, 4282, -1, 4282, 4283, 4281, -1, 4246, 4285, 4284, -1, 4117, 4285, 4246, -1, 4284, 4285, 4286, -1, 4098, 4287, 4285, -1, 4081, 4287, 4098, -1, 4060, 4287, 4081, -1, 4288, 4287, 4289, -1, 4286, 4287, 4288, -1, 4285, 4287, 4286, -1, 4040, 4290, 4060, -1, 4287, 4290, 4289, -1, 4289, 4290, 4291, -1, 4060, 4290, 4287, -1, 4015, 4250, 4040, -1, 4290, 4250, 4291, -1, 4040, 4250, 4290, -1, 4291, 4250, 4292, -1, 3990, 4247, 4000, -1, 4292, 4247, 4252, -1, 4250, 4247, 4292, -1, 3979, 4254, 3990, -1, 4253, 4254, 4293, -1, 3990, 4254, 4247, -1, 3969, 4294, 3979, -1, 3960, 4294, 3969, -1, 4293, 4294, 4295, -1, 3979, 4294, 4254, -1, 4254, 4294, 4293, -1, 3950, 4255, 3960, -1, 4295, 4255, 4257, -1, 3960, 4255, 4294, -1, 4294, 4255, 4295, -1, 3950, 4258, 4255, -1, 3939, 4258, 3950, -1, 4259, 4258, 4296, -1, 4258, 4261, 4296, -1, 3907, 4261, 3929, -1, 4296, 4261, 4297, -1, 3904, 4298, 3907, -1, 3907, 4298, 4261, -1, 4261, 4298, 4297, -1, 4297, 4298, 4299, -1, 4215, 4300, 3904, -1, 4194, 4300, 4215, -1, 3904, 4300, 4298, -1, 4298, 4300, 4299, -1, 4301, 4300, 4302, -1, 4299, 4300, 4301, -1, 4300, 4303, 4302, -1, 4175, 4303, 4194, -1, 4194, 4303, 4300, -1, 4302, 4303, 4304, -1, 4303, 4265, 4304, -1, 4175, 4265, 4303, -1, 4158, 4265, 4175, -1, 4304, 4265, 4305, -1, 4125, 4266, 4138, -1, 4305, 4266, 4271, -1, 4265, 4266, 4305, -1, 4114, 4269, 4125, -1, 4267, 4269, 4306, -1, 4125, 4269, 4266, -1, 4269, 4307, 4306, -1, 4102, 4307, 4114, -1, 4090, 4307, 4102, -1, 4306, 4307, 4308, -1, 4114, 4307, 4269, -1, 4078, 4272, 4090, -1, 4308, 4272, 4274, -1, 4090, 4272, 4307, -1, 4307, 4272, 4308, -1, 4078, 4276, 4272, -1, 4066, 4276, 4078, -1, 4275, 4276, 4309, -1, 4276, 4278, 4309, -1, 4043, 4278, 4054, -1, 4309, 4278, 4310, -1, 4278, 4282, 4310, -1, 4043, 4282, 4278, -1, 4029, 4282, 4043, -1, 4310, 4282, 4280, -1, 4242, 4311, 4236, -1, 3675, 4311, 4242, -1, 4311, 4312, 4236, -1, 3926, 4312, 4008, -1, 4008, 4312, 3675, -1, 3675, 4312, 4311, -1, 4236, 4312, 3926, -1, 3888, 4313, 3887, -1, 3887, 4313, 4245, -1, 4231, 4313, 3888, -1, 4245, 4313, 4231, -1, 551, 4314, 569, -1, 4315, 4314, 551, -1, 541, 4316, 567, -1, 4317, 4316, 541, -1, 569, 4318, 579, -1, 567, 4319, 566, -1, 4314, 4318, 569, -1, 4316, 4319, 567, -1, 416, 4320, 417, -1, 4319, 4321, 566, -1, 579, 4322, 593, -1, 4318, 4322, 579, -1, 417, 4323, 619, -1, 4320, 4323, 417, -1, 593, 4324, 610, -1, 4322, 4324, 593, -1, 4323, 4325, 619, -1, 619, 4325, 635, -1, 610, 4326, 627, -1, 4324, 4326, 610, -1, 4325, 4327, 635, -1, 635, 4327, 651, -1, 627, 4328, 642, -1, 4326, 4328, 627, -1, 4327, 4329, 651, -1, 651, 4329, 667, -1, 4328, 4330, 642, -1, 642, 4330, 658, -1, 4329, 4331, 667, -1, 667, 4331, 683, -1, 4330, 4332, 658, -1, 658, 4332, 676, -1, 4331, 4333, 683, -1, 683, 4333, 700, -1, 4332, 4334, 676, -1, 676, 4334, 692, -1, 4333, 4335, 700, -1, 700, 4335, 716, -1, 4334, 4336, 692, -1, 692, 4336, 706, -1, 4335, 4337, 716, -1, 716, 4337, 730, -1, 4336, 4338, 706, -1, 706, 4338, 723, -1, 4337, 4339, 730, -1, 730, 4339, 746, -1, 4338, 4340, 723, -1, 723, 4340, 738, -1, 4339, 4341, 746, -1, 746, 4341, 400, -1, 4340, 4342, 738, -1, 738, 4342, 379, -1, 4341, 4343, 400, -1, 400, 4343, 399, -1, 4342, 4344, 379, -1, 379, 4344, 383, -1, 4343, 4345, 399, -1, 399, 4345, 422, -1, 4344, 4346, 383, -1, 383, 4346, 410, -1, 4345, 4347, 422, -1, 422, 4347, 438, -1, 4346, 4348, 410, -1, 410, 4348, 429, -1, 4347, 4349, 438, -1, 438, 4349, 453, -1, 4348, 4350, 429, -1, 429, 4350, 445, -1, 4349, 4351, 453, -1, 453, 4351, 469, -1, 4350, 4352, 445, -1, 445, 4352, 461, -1, 4351, 4353, 469, -1, 469, 4353, 486, -1, 4352, 4354, 461, -1, 461, 4354, 479, -1, 4353, 4355, 486, -1, 486, 4355, 503, -1, 479, 4356, 493, -1, 4354, 4356, 479, -1, 4355, 4357, 503, -1, 503, 4357, 518, -1, 493, 4358, 509, -1, 4356, 4358, 493, -1, 518, 4359, 533, -1, 4357, 4359, 518, -1, 509, 4360, 525, -1, 4358, 4360, 509, -1, 533, 4315, 551, -1, 4359, 4315, 533, -1, 525, 4317, 541, -1, 4360, 4317, 525, -1, 102, 4361, 118, -1, 4362, 4363, 134, -1, 134, 4363, 149, -1, 118, 4364, 135, -1, 4361, 4364, 118, -1, 149, 4365, 164, -1, 4363, 4365, 149, -1, 135, 4366, 150, -1, 4364, 4366, 135, -1, 164, 4367, 180, -1, 4365, 4367, 164, -1, 4368, 4369, 232, -1, 232, 4369, 230, -1, 150, 4370, 166, -1, 4366, 4370, 150, -1, 4369, 4371, 230, -1, 180, 4372, 199, -1, 4367, 4372, 180, -1, 230, 4371, 254, -1, 166, 4373, 182, -1, 4370, 4373, 166, -1, 199, 4374, 229, -1, 4372, 4374, 199, -1, 4371, 4375, 254, -1, 254, 4375, 271, -1, 182, 4376, 201, -1, 4373, 4376, 182, -1, 229, 4377, 255, -1, 4374, 4377, 229, -1, 4375, 4378, 271, -1, 271, 4378, 287, -1, 201, 4379, 244, -1, 4376, 4379, 201, -1, 255, 4380, 269, -1, 4377, 4380, 255, -1, 244, 4381, 243, -1, 4379, 4381, 244, -1, 4378, 4382, 287, -1, 287, 4382, 301, -1, 4380, 4383, 269, -1, 269, 4383, 285, -1, 4382, 4384, 301, -1, 301, 4384, 319, -1, 4383, 4385, 285, -1, 285, 4385, 302, -1, 4384, 4386, 319, -1, 319, 4386, 334, -1, 4385, 4387, 302, -1, 302, 4387, 318, -1, 4386, 4388, 334, -1, 334, 4388, 350, -1, 4387, 4389, 318, -1, 318, 4389, 336, -1, 4388, 4390, 350, -1, 350, 4390, 365, -1, 4389, 4391, 336, -1, 336, 4391, 351, -1, 4390, 4392, 365, -1, 365, 4392, 9, -1, 4391, 4393, 351, -1, 351, 4393, 366, -1, 4392, 4394, 9, -1, 9, 4394, 8, -1, 4393, 4395, 366, -1, 366, 4395, 13, -1, 4394, 4396, 8, -1, 8, 4396, 38, -1, 4395, 4397, 13, -1, 13, 4397, 11, -1, 4396, 4398, 38, -1, 38, 4398, 54, -1, 4397, 4399, 11, -1, 11, 4399, 39, -1, 4398, 4400, 54, -1, 54, 4400, 69, -1, 4399, 4401, 39, -1, 39, 4401, 55, -1, 4400, 4402, 69, -1, 69, 4402, 84, -1, 4401, 4403, 55, -1, 55, 4403, 70, -1, 4402, 4404, 84, -1, 84, 4404, 100, -1, 4403, 4405, 70, -1, 70, 4405, 86, -1, 4404, 4406, 100, -1, 100, 4406, 117, -1, 4405, 4407, 86, -1, 86, 4407, 102, -1, 4406, 4362, 117, -1, 117, 4362, 134, -1, 4407, 4361, 102, -1, 4408, 4409, 4410, -1, 4410, 4409, 4411, -1, 4411, 4412, 4413, -1, 4409, 4412, 4411, -1, 4413, 4414, 4415, -1, 4412, 4414, 4413, -1, 4415, 4416, 4417, -1, 4414, 4416, 4415, -1, 4417, 4418, 4419, -1, 4416, 4418, 4417, -1, 4419, 4420, 4421, -1, 4418, 4420, 4419, -1, 4421, 4422, 4423, -1, 4420, 4422, 4421, -1, 4423, 4424, 4425, -1, 4422, 4424, 4423, -1, 4425, 4426, 4427, -1, 4424, 4426, 4425, -1, 4427, 4428, 4429, -1, 4426, 4428, 4427, -1, 4429, 4430, 4431, -1, 4428, 4430, 4429, -1, 4431, 4432, 4433, -1, 4430, 4432, 4431, -1, 4433, 4434, 4435, -1, 4432, 4434, 4433, -1, 4436, 4437, 4438, -1, 4438, 4437, 4439, -1, 4439, 4440, 4441, -1, 4437, 4440, 4439, -1, 4441, 4442, 4443, -1, 4440, 4442, 4441, -1, 4443, 4444, 4445, -1, 4442, 4444, 4443, -1, 4445, 4446, 4447, -1, 4444, 4446, 4445, -1, 4447, 4448, 4449, -1, 4446, 4448, 4447, -1, 4449, 4450, 4451, -1, 4448, 4450, 4449, -1, 4451, 4452, 4453, -1, 4450, 4452, 4451, -1, 4453, 4454, 4455, -1, 4452, 4454, 4453, -1, 4455, 4456, 4457, -1, 4454, 4456, 4455, -1, 4457, 4458, 4459, -1, 4456, 4458, 4457, -1, 4459, 4460, 4461, -1, 4458, 4460, 4459, -1, 4461, 4462, 4463, -1, 4460, 4462, 4461, -1, 4464, 4465, 4466, -1, 4466, 4467, 4468, -1, 4465, 4467, 4466, -1, 4468, 4469, 4470, -1, 4467, 4469, 4468, -1, 4470, 4471, 4472, -1, 4469, 4471, 4470, -1, 4472, 4473, 4474, -1, 4471, 4473, 4472, -1, 4474, 4475, 4476, -1, 4473, 4475, 4474, -1, 4476, 4477, 4478, -1, 4475, 4477, 4476, -1, 4478, 4479, 4480, -1, 4477, 4479, 4478, -1, 4480, 4481, 4482, -1, 4479, 4481, 4480, -1, 4482, 4483, 4484, -1, 4481, 4483, 4482, -1, 4484, 4485, 4486, -1, 4483, 4485, 4484, -1, 4486, 4487, 4488, -1, 4485, 4487, 4486, -1, 4488, 4489, 4490, -1, 4487, 4489, 4488, -1, 4489, 4491, 4490, -1, 4492, 4493, 4494, -1, 4493, 4495, 4494, -1, 4494, 4495, 4496, -1, 4496, 4497, 4498, -1, 4495, 4497, 4496, -1, 4499, 4500, 4501, -1, 4501, 4500, 4502, -1, 4498, 4503, 4504, -1, 4497, 4503, 4498, -1, 4502, 4505, 4506, -1, 4500, 4505, 4502, -1, 4504, 4507, 4508, -1, 4503, 4507, 4504, -1, 4506, 4509, 4510, -1, 4505, 4509, 4506, -1, 4508, 4511, 4512, -1, 4507, 4511, 4508, -1, 4510, 4513, 4514, -1, 4509, 4513, 4510, -1, 4512, 4515, 4516, -1, 4511, 4515, 4512, -1, 4514, 4517, 4518, -1, 4513, 4517, 4514, -1, 4516, 4519, 4520, -1, 4515, 4519, 4516, -1, 4518, 4521, 4522, -1, 4517, 4521, 4518, -1, 4522, 4523, 4524, -1, 4521, 4523, 4522, -1, 4524, 4525, 4526, -1, 4523, 4525, 4524, -1, 4526, 4527, 4528, -1, 4525, 4527, 4526, -1, 4528, 4529, 4530, -1, 4527, 4529, 4528, -1, 4529, 4531, 4530, -1, 4530, 4531, 4532, -1, 4531, 4533, 4532, -1, 4532, 4533, 4534, -1, 4533, 4535, 4534, -1, 4534, 4535, 4536, -1, 4535, 4537, 4536, -1, 4536, 4537, 4538, -1, 4537, 4539, 4538, -1, 4538, 4539, 4540, -1, 4539, 4541, 4540, -1, 4540, 4541, 4542, -1, 4541, 4543, 4542, -1, 4542, 4543, 4544, -1, 4543, 4545, 4544, -1, 4544, 4545, 4492, -1, 4545, 4493, 4492, -1, 4546, 2776, 4547, -1, 4548, 2523, 4549, -1, 4547, 2523, 4548, -1, 2776, 2523, 4547, -1, 4549, 2512, 4550, -1, 2523, 2512, 4549, -1, 2388, 2387, 4551, -1, 4551, 2387, 4552, -1, 2512, 2505, 4550, -1, 4552, 2565, 4553, -1, 2387, 2565, 4552, -1, 4550, 2495, 4554, -1, 2505, 2495, 4550, -1, 4553, 2556, 4555, -1, 2565, 2556, 4553, -1, 4556, 2723, 4557, -1, 4554, 2723, 4556, -1, 2495, 2723, 4554, -1, 4555, 2442, 4558, -1, 2556, 2442, 4555, -1, 2723, 2694, 4557, -1, 2442, 2430, 4558, -1, 4559, 2662, 4560, -1, 4557, 2662, 4559, -1, 4558, 2430, 4561, -1, 2694, 2662, 4557, -1, 2430, 2403, 4561, -1, 2662, 2634, 4560, -1, 4561, 2403, 4562, -1, 4560, 2604, 4563, -1, 2403, 2377, 4562, -1, 2634, 2604, 4560, -1, 4562, 2377, 4564, -1, 4563, 2574, 4565, -1, 2377, 2364, 4564, -1, 2604, 2574, 4563, -1, 4564, 2364, 4566, -1, 2574, 2542, 4565, -1, 2364, 2349, 4566, -1, 4566, 2349, 4567, -1, 4565, 2542, 4568, -1, 2542, 2501, 4568, -1, 2349, 2324, 4567, -1, 4567, 2324, 4569, -1, 4568, 2501, 4570, -1, 2501, 2463, 4570, -1, 2324, 2279, 4569, -1, 4571, 2279, 4572, -1, 4569, 2279, 4571, -1, 4570, 2463, 4573, -1, 2279, 2251, 4572, -1, 2463, 2465, 4573, -1, 4573, 2465, 4574, -1, 2251, 2831, 4572, -1, 2465, 2813, 4574, -1, 4572, 2831, 4575, -1, 4574, 2813, 4576, -1, 2831, 2261, 4575, -1, 2813, 2439, 4576, -1, 4575, 2261, 4577, -1, 4576, 2439, 4578, -1, 2439, 2427, 4578, -1, 2261, 2262, 4577, -1, 4578, 2427, 4579, -1, 4577, 2262, 4580, -1, 2427, 2291, 4579, -1, 2262, 2807, 4580, -1, 4579, 2291, 4581, -1, 4582, 2807, 4583, -1, 4580, 2807, 4582, -1, 2291, 2290, 4581, -1, 4581, 2290, 4584, -1, 2807, 2805, 4583, -1, 2805, 2790, 4583, -1, 4583, 2790, 4546, -1, 2790, 2776, 4546, -1, 4585, 4586, 4587, -1, 4588, 4586, 4585, -1, 4587, 4589, 4590, -1, 4586, 4589, 4587, -1, 4591, 3380, 4592, -1, 4590, 4593, 4594, -1, 4589, 4593, 4590, -1, 4592, 4595, 4596, -1, 3380, 4595, 4592, -1, 4594, 4597, 4598, -1, 4593, 4597, 4594, -1, 4595, 4599, 4596, -1, 4596, 4599, 4600, -1, 4598, 4601, 4602, -1, 4597, 4601, 4598, -1, 4599, 4603, 4600, -1, 4600, 4603, 4604, -1, 4602, 4605, 4606, -1, 4601, 4605, 4602, -1, 4603, 4607, 4604, -1, 4604, 4607, 4608, -1, 4606, 4609, 4610, -1, 4605, 4609, 4606, -1, 4607, 4611, 4608, -1, 4608, 4611, 4612, -1, 4610, 4613, 4614, -1, 4609, 4613, 4610, -1, 4611, 4615, 4612, -1, 4612, 4615, 4616, -1, 4613, 4617, 4614, -1, 4614, 4617, 4618, -1, 4615, 4619, 4616, -1, 4616, 4619, 4620, -1, 4617, 4621, 4618, -1, 4618, 4621, 4622, -1, 4619, 4623, 4620, -1, 4620, 4623, 4624, -1, 4621, 4625, 4622, -1, 4622, 4625, 4626, -1, 4623, 4627, 4624, -1, 4624, 4627, 4628, -1, 4625, 4629, 4626, -1, 4626, 4629, 4630, -1, 4627, 4631, 4628, -1, 4628, 4631, 4632, -1, 4629, 4633, 4630, -1, 4630, 4633, 4634, -1, 4631, 4635, 4632, -1, 4632, 4635, 4636, -1, 4633, 4637, 4634, -1, 4634, 4637, 4638, -1, 4635, 4639, 4636, -1, 4636, 4639, 4640, -1, 4637, 4641, 4638, -1, 4638, 4641, 4642, -1, 4639, 4643, 4640, -1, 4640, 4643, 4644, -1, 4641, 4645, 4642, -1, 4642, 4645, 4646, -1, 4643, 4647, 4644, -1, 4644, 4647, 4648, -1, 4645, 4649, 4646, -1, 4646, 4649, 4650, -1, 4647, 4651, 4648, -1, 4648, 4651, 4652, -1, 4649, 4653, 4650, -1, 4650, 4653, 4654, -1, 4651, 4655, 4652, -1, 4652, 4655, 4656, -1, 4653, 4657, 4654, -1, 4654, 4657, 4658, -1, 4655, 4659, 4656, -1, 4656, 4659, 4660, -1, 4658, 4661, 4662, -1, 4657, 4661, 4658, -1, 4659, 4663, 4660, -1, 4662, 4664, 4665, -1, 4660, 4663, 4666, -1, 4661, 4664, 4662, -1, 4663, 4667, 4666, -1, 4665, 4668, 4669, -1, 4666, 4667, 4670, -1, 4664, 4668, 4665, -1, 4668, 3144, 4669, -1, 4670, 4588, 4585, -1, 4667, 4588, 4670, -1, 4671, 4672, 1894, -1, 4672, 4673, 1873, -1, 1747, 3662, 1745, -1, 1873, 4674, 1866, -1, 4673, 4674, 1873, -1, 1745, 4675, 1938, -1, 3662, 4675, 1745, -1, 1866, 4676, 2065, -1, 4674, 4676, 1866, -1, 1938, 4677, 1928, -1, 4675, 4677, 1938, -1, 2065, 4678, 2028, -1, 1928, 4679, 1801, -1, 4676, 4678, 2065, -1, 4677, 4679, 1928, -1, 2028, 4680, 1998, -1, 1801, 4681, 1769, -1, 4679, 4681, 1801, -1, 4678, 4680, 2028, -1, 4681, 4682, 1769, -1, 1998, 4683, 1969, -1, 1769, 4682, 1741, -1, 4680, 4683, 1998, -1, 4682, 4684, 1741, -1, 1969, 4685, 1936, -1, 1741, 4684, 1727, -1, 4683, 4685, 1969, -1, 4684, 4686, 1727, -1, 1727, 4686, 1713, -1, 1936, 4687, 1898, -1, 4685, 4687, 1936, -1, 4686, 4688, 1713, -1, 1713, 4688, 1699, -1, 4687, 4689, 1898, -1, 1898, 4689, 1861, -1, 4688, 4690, 1699, -1, 1699, 4690, 1657, -1, 4689, 4691, 1861, -1, 1861, 4691, 1830, -1, 4690, 4692, 1657, -1, 1657, 4692, 1655, -1, 4691, 4693, 1830, -1, 1830, 4693, 1815, -1, 4692, 4694, 1655, -1, 1655, 4694, 2212, -1, 4693, 4695, 1815, -1, 4694, 4696, 2212, -1, 1815, 4695, 1814, -1, 2212, 4696, 2190, -1, 4695, 4697, 1814, -1, 4696, 4698, 2190, -1, 1814, 4697, 2184, -1, 2190, 4698, 1621, -1, 4697, 4699, 2184, -1, 4698, 4700, 1621, -1, 2184, 4699, 1793, -1, 1621, 4700, 2238, -1, 4699, 4701, 1793, -1, 4700, 4702, 2238, -1, 1793, 4701, 1776, -1, 2238, 4702, 2178, -1, 4701, 4703, 1776, -1, 4702, 4704, 2178, -1, 1776, 4703, 1759, -1, 2178, 4704, 2163, -1, 4703, 3855, 1759, -1, 1759, 3855, 1757, -1, 4704, 4705, 2163, -1, 2163, 4705, 2146, -1, 4705, 4706, 2146, -1, 2146, 4706, 2133, -1, 4706, 4707, 2133, -1, 2133, 4671, 1894, -1, 4707, 4671, 2133, -1, 1882, 4672, 1873, -1, 1894, 4672, 1882, -1, 3964, 4708, 3954, -1, 4709, 4708, 3964, -1, 3954, 4710, 3944, -1, 4708, 4710, 3954, -1, 4003, 1441, 3910, -1, 3944, 4711, 3934, -1, 4710, 4711, 3944, -1, 3910, 4712, 3909, -1, 1441, 4712, 3910, -1, 3934, 4713, 3919, -1, 4711, 4713, 3934, -1, 4712, 4714, 3909, -1, 3909, 4714, 4230, -1, 3919, 4715, 3902, -1, 4713, 4715, 3919, -1, 4714, 4716, 4230, -1, 4230, 4716, 4223, -1, 3902, 4717, 4221, -1, 4715, 4717, 3902, -1, 4716, 4718, 4223, -1, 4223, 4718, 4211, -1, 4221, 4719, 4198, -1, 4717, 4719, 4221, -1, 4718, 4720, 4211, -1, 4211, 4720, 4201, -1, 4198, 4721, 4180, -1, 4719, 4721, 4198, -1, 4720, 4722, 4201, -1, 4201, 4722, 4188, -1, 4721, 4723, 4180, -1, 4180, 4723, 4160, -1, 4722, 4724, 4188, -1, 4188, 4724, 4176, -1, 4723, 4725, 4160, -1, 4160, 4725, 4142, -1, 4724, 4726, 4176, -1, 4176, 4726, 4165, -1, 4725, 4727, 4142, -1, 4142, 4727, 4134, -1, 4726, 4728, 4165, -1, 4165, 4728, 4151, -1, 4727, 4729, 4134, -1, 4134, 4729, 4124, -1, 4728, 4730, 4151, -1, 4151, 4730, 4130, -1, 4729, 4731, 4124, -1, 4124, 4731, 4111, -1, 4730, 4732, 4130, -1, 4130, 4732, 4110, -1, 4731, 4733, 4111, -1, 4111, 4733, 4100, -1, 4732, 4734, 4110, -1, 4110, 4734, 4088, -1, 4733, 4735, 4100, -1, 4100, 4735, 4087, -1, 4734, 4736, 4088, -1, 4088, 4736, 4068, -1, 4735, 4737, 4087, -1, 4087, 4737, 4075, -1, 4736, 4738, 4068, -1, 4068, 4738, 4047, -1, 4737, 4739, 4075, -1, 4075, 4739, 4062, -1, 4738, 4740, 4047, -1, 4047, 4740, 4026, -1, 4739, 4741, 4062, -1, 4062, 4741, 4051, -1, 4740, 4742, 4026, -1, 4026, 4742, 4005, -1, 4741, 4743, 4051, -1, 4051, 4743, 4038, -1, 4742, 4744, 4005, -1, 4005, 4744, 3994, -1, 4038, 4745, 4024, -1, 4743, 4745, 4038, -1, 4744, 4746, 3994, -1, 4024, 4747, 4014, -1, 3994, 4746, 3984, -1, 4745, 4747, 4024, -1, 4746, 4748, 3984, -1, 4014, 4749, 4012, -1, 3984, 4748, 3974, -1, 4747, 4749, 4014, -1, 4749, 1186, 4012, -1, 3974, 4709, 3964, -1, 4748, 4709, 3974, -1, 4750, 4751, 4752, -1, 4750, 4753, 4754, -1, 4750, 4755, 4753, -1, 4756, 4757, 4758, -1, 4750, 4752, 4755, -1, 4759, 4760, 4751, -1, 4761, 4762, 4763, -1, 4759, 4751, 4750, -1, 4761, 4763, 4764, -1, 4759, 4754, 4765, -1, 4759, 4750, 4754, -1, 4766, 4764, 4757, -1, 4767, 4768, 4760, -1, 4767, 4769, 4768, -1, 4766, 4757, 4756, -1, 4767, 4760, 4759, -1, 4767, 4759, 4765, -1, 4767, 4765, 4770, -1, 4771, 4772, 4762, -1, 4773, 4767, 4770, -1, 4771, 4762, 4761, -1, 4773, 4769, 4767, -1, 4773, 4770, 4774, -1, 4773, 4774, 4769, -1, 4775, 4761, 4764, -1, 4775, 4764, 4766, -1, 4776, 4756, 4758, -1, 4776, 4758, 4777, -1, 4778, 4779, 4772, -1, 4778, 4772, 4771, -1, 901, 4780, 4781, -1, 4782, 4771, 4761, -1, 4782, 4761, 4775, -1, 4782, 4779, 4778, -1, 4782, 4778, 4771, -1, 4782, 4783, 4779, -1, 4784, 4766, 4756, -1, 4784, 4756, 4776, -1, 4785, 4776, 4777, -1, 4786, 4775, 4766, -1, 4786, 4766, 4784, -1, 4787, 4784, 4776, -1, 4787, 4776, 4785, -1, 4788, 4782, 4775, -1, 4788, 4775, 4786, -1, 4789, 4777, 4790, -1, 4789, 4785, 4777, -1, 4791, 4784, 4787, -1, 4791, 4786, 4784, -1, 4792, 4783, 4782, -1, 4792, 4782, 4788, -1, 4793, 4787, 4785, -1, 4793, 4785, 4789, -1, 4794, 4795, 4783, -1, 4794, 4783, 4792, -1, 4794, 4788, 4786, -1, 4794, 4786, 4791, -1, 4794, 4792, 4788, -1, 4796, 4789, 4790, -1, 4797, 4791, 4787, -1, 4797, 4787, 4793, -1, 4798, 4793, 4789, -1, 4798, 4789, 4796, -1, 4799, 4791, 4797, -1, 4799, 4794, 4791, -1, 4800, 4790, 4801, -1, 4800, 4796, 4790, -1, 4802, 4793, 4798, -1, 4802, 4797, 4793, -1, 4803, 4794, 4799, -1, 4803, 4795, 4794, -1, 4804, 4798, 4796, -1, 4804, 4796, 4800, -1, 4805, 4797, 4802, -1, 4805, 4795, 4803, -1, 4805, 4806, 4795, -1, 4805, 4799, 4797, -1, 4805, 4803, 4799, -1, 4807, 4800, 4801, -1, 4808, 4798, 4804, -1, 4808, 4802, 4798, -1, 4809, 4800, 4807, -1, 4809, 4804, 4800, -1, 4810, 4805, 4802, -1, 4810, 4802, 4808, -1, 4811, 4801, 4812, -1, 4811, 4807, 4801, -1, 4813, 4808, 4804, -1, 4813, 4804, 4809, -1, 4814, 4806, 4805, -1, 4814, 4805, 4810, -1, 4815, 4809, 4807, -1, 4815, 4807, 4811, -1, 4816, 4810, 4808, -1, 4816, 4808, 4813, -1, 4816, 4806, 4814, -1, 4816, 4814, 4810, -1, 4816, 4817, 4806, -1, 4818, 4811, 4812, -1, 4819, 4813, 4809, -1, 4819, 4809, 4815, -1, 4820, 4815, 4811, -1, 4820, 4811, 4818, -1, 4821, 4816, 4813, -1, 4821, 4813, 4819, -1, 4822, 4812, 4823, -1, 4822, 4818, 4812, -1, 4824, 4819, 4815, -1, 4824, 4815, 4820, -1, 4825, 4817, 4816, -1, 4825, 4816, 4821, -1, 4826, 4820, 4818, -1, 4826, 4818, 4822, -1, 4827, 4821, 4819, -1, 4827, 4819, 4824, -1, 4827, 4817, 4825, -1, 4827, 4828, 4817, -1, 4827, 4825, 4821, -1, 4829, 4822, 4823, -1, 4830, 4824, 4820, -1, 4830, 4820, 4826, -1, 4831, 4826, 4822, -1, 4831, 4822, 4829, -1, 4832, 4824, 4830, -1, 4832, 4827, 4824, -1, 4833, 4823, 4834, -1, 4833, 4829, 4823, -1, 4835, 4830, 4826, -1, 4835, 4826, 4831, -1, 4836, 4828, 4827, -1, 4836, 4827, 4832, -1, 4837, 4831, 4829, -1, 4837, 4829, 4833, -1, 4838, 4832, 4830, -1, 4838, 4839, 4828, -1, 4838, 4830, 4835, -1, 4838, 4828, 4836, -1, 4838, 4836, 4832, -1, 4840, 4833, 4834, -1, 4841, 4835, 4831, -1, 4841, 4831, 4837, -1, 4842, 4833, 4840, -1, 4842, 4837, 4833, -1, 4843, 4835, 4841, -1, 4843, 4838, 4835, -1, 4844, 4834, 4845, -1, 4844, 4840, 4834, -1, 4846, 4838, 4843, -1, 4846, 4839, 4838, -1, 4847, 4837, 4842, -1, 4847, 4841, 4837, -1, 4848, 4842, 4840, -1, 4848, 4840, 4844, -1, 4849, 4843, 4841, -1, 4849, 4846, 4843, -1, 4849, 4839, 4846, -1, 4849, 4850, 4839, -1, 4849, 4841, 4847, -1, 4851, 4844, 4845, -1, 4852, 4847, 4842, -1, 4852, 4842, 4848, -1, 4853, 4774, 4770, -1, 4854, 4848, 4844, -1, 4854, 4844, 4851, -1, 4855, 4584, 4856, -1, 4855, 4857, 4584, -1, 4858, 4849, 4847, -1, 4858, 4847, 4852, -1, 4859, 4857, 4855, -1, 4860, 4845, 4861, -1, 4860, 4851, 4845, -1, 4859, 4862, 4857, -1, 4863, 4850, 4849, -1, 4863, 4849, 4858, -1, 4864, 4852, 4848, -1, 4865, 4866, 4862, -1, 4864, 4848, 4854, -1, 4865, 4862, 4859, -1, 4867, 901, 4781, -1, 4867, 4866, 4865, -1, 4867, 900, 901, -1, 4867, 4781, 4866, -1, 4868, 4854, 4851, -1, 4869, 4870, 4871, -1, 4869, 4855, 4856, -1, 4868, 4851, 4860, -1, 4869, 4856, 4870, -1, 4872, 4858, 4852, -1, 4872, 4850, 4863, -1, 4872, 4852, 4864, -1, 4873, 4855, 4869, -1, 4872, 4863, 4858, -1, 4872, 4874, 4850, -1, 4875, 4860, 4861, -1, 4873, 4859, 4855, -1, 4876, 4859, 4873, -1, 4877, 4854, 4868, -1, 4877, 4864, 4854, -1, 4876, 4865, 4859, -1, 4878, 900, 4867, -1, 4878, 4867, 4865, -1, 4879, 4868, 4860, -1, 4879, 4860, 4875, -1, 4878, 4865, 4876, -1, 4878, 898, 900, -1, 4880, 4872, 4864, -1, 4881, 4869, 4871, -1, 4880, 4864, 4877, -1, 4882, 4861, 4883, -1, 4882, 4875, 4861, -1, 4884, 4885, 898, -1, 4884, 4878, 4885, -1, 4884, 898, 4878, -1, 4886, 4874, 4872, -1, 4886, 4872, 4880, -1, 4887, 4873, 4869, -1, 4888, 4877, 4868, -1, 4888, 4868, 4879, -1, 4887, 4869, 4881, -1, 4889, 4876, 4873, -1, 4889, 4873, 4887, -1, 4890, 4879, 4875, -1, 4890, 4875, 4882, -1, 4891, 4878, 4876, -1, 4892, 4880, 4877, -1, 4891, 4885, 4878, -1, 4892, 4874, 4886, -1, 4892, 4877, 4888, -1, 4891, 4876, 4889, -1, 4892, 4893, 4874, -1, 4894, 4881, 4871, -1, 4892, 4886, 4880, -1, 4894, 4895, 4896, -1, 4894, 4871, 4895, -1, 4897, 4882, 4883, -1, 4898, 4891, 4899, -1, 4900, 4888, 4879, -1, 4898, 4899, 4885, -1, 4900, 4879, 4890, -1, 4898, 4885, 4891, -1, 4901, 4887, 4881, -1, 4901, 4881, 4894, -1, 4902, 4890, 4882, -1, 4903, 4889, 4887, -1, 4902, 4882, 4897, -1, 4903, 4887, 4901, -1, 4904, 4892, 4888, -1, 4904, 4888, 4900, -1, 4905, 4899, 4891, -1, 4906, 4883, 4907, -1, 4905, 4889, 4903, -1, 4906, 4897, 4883, -1, 4905, 4891, 4889, -1, 4908, 4894, 4896, -1, 4909, 4892, 4904, -1, 4909, 4893, 4892, -1, 4910, 4900, 4890, -1, 4910, 4890, 4902, -1, 4911, 4899, 4905, -1, 4911, 4912, 4899, -1, 4911, 4905, 4912, -1, 4913, 4901, 4894, -1, 4913, 4894, 4908, -1, 4914, 4902, 4897, -1, 4914, 4897, 4906, -1, 4915, 4901, 4913, -1, 4916, 4917, 4893, -1, 4916, 4900, 4910, -1, 4916, 4904, 4900, -1, 4916, 4893, 4909, -1, 4916, 4909, 4904, -1, 4915, 4903, 4901, -1, 4918, 4910, 4902, -1, 4919, 4903, 4915, -1, 4919, 4905, 4903, -1, 4919, 4912, 4905, -1, 4918, 4902, 4914, -1, 4920, 4908, 4896, -1, 4920, 4896, 4921, -1, 4922, 4906, 4907, -1, 4923, 4912, 4919, -1, 4923, 4924, 4912, -1, 4925, 4910, 4918, -1, 4923, 4919, 4924, -1, 4925, 4916, 4910, -1, 4926, 4906, 4922, -1, 4927, 4913, 4908, -1, 4927, 4908, 4920, -1, 4926, 4914, 4906, -1, 4928, 4915, 4913, -1, 4929, 4907, 4930, -1, 4929, 4922, 4907, -1, 4928, 4913, 4927, -1, 4931, 4915, 4928, -1, 4932, 4917, 4916, -1, 4932, 4916, 4925, -1, 4931, 4919, 4915, -1, 4933, 4918, 4914, -1, 4931, 4924, 4919, -1, 4933, 4914, 4926, -1, 4934, 4921, 4935, -1, 4936, 4926, 4922, -1, 4934, 4920, 4921, -1, 4936, 4922, 4929, -1, 4937, 4924, 4931, -1, 4937, 4938, 4924, -1, 4939, 4920, 4934, -1, 4940, 4917, 4932, -1, 4940, 4925, 4918, -1, 4940, 4918, 4933, -1, 4939, 4927, 4920, -1, 4940, 4932, 4925, -1, 4940, 4941, 4917, -1, 4942, 4926, 4936, -1, 4942, 4933, 4926, -1, 4943, 4928, 4927, -1, 4943, 4927, 4939, -1, 4944, 4929, 4930, -1, 4945, 4928, 4943, -1, 4945, 4931, 4928, -1, 4946, 4933, 4942, -1, 4946, 4940, 4933, -1, 4947, 4935, 4948, -1, 4949, 4930, 4950, -1, 4949, 4944, 4930, -1, 4947, 4934, 4935, -1, 4951, 4937, 4931, -1, 4951, 4931, 4945, -1, 4951, 4952, 4938, -1, 4953, 4936, 4929, -1, 4951, 4938, 4937, -1, 4953, 4929, 4944, -1, 4954, 4939, 4934, -1, 4954, 4934, 4947, -1, 4955, 4941, 4940, -1, 4955, 4940, 4946, -1, 4956, 4943, 4939, -1, 4957, 4944, 4949, -1, 4957, 4953, 4944, -1, 4956, 4939, 4954, -1, 4958, 4942, 4936, -1, 4959, 4945, 4943, -1, 4958, 4936, 4953, -1, 4959, 4943, 4956, -1, 4960, 4947, 4948, -1, 4961, 4958, 4953, -1, 4960, 4948, 4962, -1, 4961, 4953, 4957, -1, 4963, 4946, 4942, -1, 4963, 4941, 4955, -1, 4964, 4965, 4952, -1, 4963, 4942, 4958, -1, 4964, 4951, 4945, -1, 4963, 4955, 4946, -1, 4964, 4952, 4951, -1, 4963, 4966, 4941, -1, 4964, 4945, 4959, -1, 4967, 4949, 4950, -1, 4968, 4954, 4947, -1, 4968, 4947, 4960, -1, 4969, 4958, 4961, -1, 4969, 4963, 4958, -1, 4970, 4950, 4971, -1, 4972, 4956, 4954, -1, 4970, 4967, 4950, -1, 4972, 4954, 4968, -1, 4973, 4949, 4967, -1, 4974, 4959, 4956, -1, 4973, 4957, 4949, -1, 4974, 4956, 4972, -1, 4975, 4962, 4976, -1, 4975, 4960, 4962, -1, 4977, 4966, 4963, -1, 4977, 4963, 4969, -1, 4978, 4979, 4965, -1, 4980, 4973, 4967, -1, 4978, 4965, 4964, -1, 4980, 4967, 4970, -1, 4978, 4964, 4959, -1, 4981, 4961, 4957, -1, 4978, 4959, 4974, -1, 4981, 4957, 4973, -1, 4982, 4960, 4975, -1, 4982, 4968, 4960, -1, 4983, 4981, 4973, -1, 4983, 4973, 4980, -1, 4984, 4968, 4982, -1, 4985, 4969, 4961, -1, 4985, 4966, 4977, -1, 4984, 4972, 4968, -1, 4985, 4986, 4966, -1, 4987, 4974, 4972, -1, 4987, 4972, 4984, -1, 4985, 4961, 4981, -1, 4985, 4977, 4969, -1, 4988, 4970, 4971, -1, 4989, 4976, 4990, -1, 4991, 4981, 4983, -1, 4989, 4975, 4976, -1, 4992, 4978, 4974, -1, 4991, 4985, 4981, -1, 4992, 4974, 4987, -1, 4993, 4971, 4994, -1, 4992, 4995, 4979, -1, 4993, 4988, 4971, -1, 4992, 4979, 4978, -1, 4996, 4970, 4988, -1, 4997, 4975, 4989, -1, 4996, 4980, 4970, -1, 4997, 4982, 4975, -1, 4998, 4984, 4982, -1, 4999, 4986, 4985, -1, 4999, 4985, 4991, -1, 5000, 4988, 4993, -1, 4998, 4982, 4997, -1, 5001, 4984, 4998, -1, 5000, 4996, 4988, -1, 5001, 4987, 4984, -1, 5002, 4983, 4980, -1, 5002, 4980, 4996, -1, 5003, 4990, 5004, -1, 5005, 5002, 4996, -1, 5003, 4989, 4990, -1, 5005, 4996, 5000, -1, 5006, 4995, 4992, -1, 5006, 4987, 5001, -1, 5006, 5007, 4995, -1, 5006, 4992, 4987, -1, 5008, 4983, 5002, -1, 5009, 4997, 4989, -1, 5009, 4989, 5003, -1, 5008, 4991, 4983, -1, 5010, 4993, 4994, -1, 5011, 4998, 4997, -1, 5012, 4986, 4999, -1, 5012, 4999, 4991, -1, 5011, 4997, 5009, -1, 5012, 4991, 5008, -1, 5012, 5013, 4986, -1, 5014, 5002, 5005, -1, 5015, 5001, 4998, -1, 5014, 5008, 5002, -1, 5015, 4998, 5011, -1, 5016, 5004, 5017, -1, 5018, 4993, 5010, -1, 5016, 5003, 5004, -1, 5018, 5000, 4993, -1, 5019, 5006, 5001, -1, 5020, 5008, 5014, -1, 5019, 5007, 5006, -1, 5020, 5012, 5008, -1, 5019, 5001, 5015, -1, 5020, 5013, 5012, -1, 5019, 5021, 5007, -1, 5022, 5005, 5000, -1, 5023, 5009, 5003, -1, 5022, 5000, 5018, -1, 5024, 5014, 5005, -1, 5023, 5003, 5016, -1, 5025, 5011, 5009, -1, 5024, 5005, 5022, -1, 5025, 5009, 5023, -1, 5026, 4994, 5027, -1, 5028, 5015, 5011, -1, 5026, 5010, 4994, -1, 5028, 5011, 5025, -1, 5029, 5014, 5024, -1, 5030, 5017, 5031, -1, 5029, 5020, 5014, -1, 5029, 5013, 5020, -1, 5030, 5016, 5017, -1, 5029, 5024, 5032, -1, 5029, 5032, 5013, -1, 5033, 5018, 5010, -1, 5034, 5019, 5015, -1, 5034, 5021, 5019, -1, 5033, 5010, 5026, -1, 5034, 5035, 5021, -1, 5034, 5015, 5028, -1, 5036, 5022, 5018, -1, 5037, 5023, 5016, -1, 5036, 5018, 5033, -1, 5038, 5024, 5022, -1, 5037, 5016, 5030, -1, 5038, 5032, 5024, -1, 5038, 5022, 5036, -1, 5039, 5025, 5023, -1, 5040, 5027, 5041, -1, 5039, 5023, 5037, -1, 5040, 5026, 5027, -1, 5042, 5028, 5025, -1, 5042, 5025, 5039, -1, 5043, 5032, 5038, -1, 5043, 5038, 5044, -1, 5045, 5031, 5046, -1, 5043, 5044, 5032, -1, 5045, 5030, 5031, -1, 5047, 5026, 5040, -1, 5047, 5033, 5026, -1, 5048, 5049, 5035, -1, 5048, 5028, 5042, -1, 5048, 5035, 5034, -1, 5050, 5033, 5047, -1, 5048, 5034, 5028, -1, 5050, 5036, 5033, -1, 5051, 5045, 5046, -1, 5052, 5037, 5030, -1, 5053, 5036, 5050, -1, 5053, 5038, 5036, -1, 5053, 5044, 5038, -1, 5052, 5030, 5045, -1, 5054, 5055, 5056, -1, 5054, 5041, 5055, -1, 5054, 5040, 5041, -1, 5057, 5045, 5051, -1, 5057, 5052, 5045, -1, 5058, 5044, 5053, -1, 5059, 5039, 5037, -1, 5058, 5053, 5060, -1, 5058, 5060, 5044, -1, 5061, 5040, 5054, -1, 5059, 5037, 5052, -1, 5061, 5047, 5040, -1, 5062, 5052, 5057, -1, 5062, 5059, 5052, -1, 5063, 5047, 5061, -1, 5064, 5042, 5039, -1, 5063, 5050, 5047, -1, 5064, 5039, 5059, -1, 5065, 5046, 5066, -1, 5067, 5050, 5063, -1, 5067, 5053, 5050, -1, 5065, 5051, 5046, -1, 5067, 5060, 5053, -1, 5068, 5069, 5049, -1, 5068, 5042, 5064, -1, 5070, 5054, 5056, -1, 5068, 5049, 5048, -1, 5068, 5048, 5042, -1, 5071, 5072, 5060, -1, 5071, 5060, 5067, -1, 5071, 5067, 5072, -1, 5073, 5054, 5070, -1, 5074, 5059, 5062, -1, 5074, 5064, 5059, -1, 5073, 5061, 5054, -1, 5075, 5065, 5066, -1, 5076, 5051, 5065, -1, 5077, 5063, 5061, -1, 5076, 5057, 5051, -1, 5077, 5061, 5073, -1, 5078, 5068, 5064, -1, 5079, 5063, 5077, -1, 5078, 5080, 5069, -1, 5078, 5064, 5074, -1, 5078, 5069, 5068, -1, 5079, 5067, 5063, -1, 5079, 5072, 5067, -1, 4763, 5065, 5075, -1, 4752, 5056, 5081, -1, 4763, 5076, 5065, -1, 4752, 5070, 5056, -1, 5082, 5057, 5076, -1, 5083, 5084, 5072, -1, 5083, 5079, 5084, -1, 5082, 5062, 5057, -1, 5083, 5072, 5079, -1, 4751, 5070, 4752, -1, 4762, 5082, 5076, -1, 4762, 5076, 4763, -1, 4751, 5073, 5070, -1, 5085, 5074, 5062, -1, 5085, 5062, 5082, -1, 4760, 5073, 4751, -1, 4757, 5066, 4758, -1, 4760, 5077, 5073, -1, 4768, 5077, 4760, -1, 4757, 5075, 5066, -1, 5086, 5080, 5078, -1, 5086, 5078, 5074, -1, 4768, 5084, 5079, -1, 5086, 5074, 5085, -1, 4768, 5079, 5077, -1, 4755, 5087, 4551, -1, 4755, 5081, 5087, -1, 4772, 5082, 4762, -1, 4755, 4551, 4753, -1, 4772, 5080, 5086, -1, 4772, 5086, 5085, -1, 4772, 4779, 5080, -1, 4772, 5085, 5082, -1, 4764, 4763, 5075, -1, 4755, 4752, 5081, -1, 4764, 5075, 4757, -1, 5088, 4768, 4769, -1, 5088, 5084, 4768, -1, 5088, 4769, 5084, -1, 5089, 5090, 5091, -1, 5092, 5093, 4614, -1, 4608, 5094, 4604, -1, 5095, 5094, 4608, -1, 5096, 5097, 5098, -1, 5098, 5097, 5099, -1, 5100, 5101, 5095, -1, 5102, 5101, 5100, -1, 5099, 5103, 5092, -1, 5095, 5104, 5094, -1, 5092, 5103, 5093, -1, 5101, 5104, 5095, -1, 5096, 5105, 5097, -1, 5102, 5106, 5101, -1, 5090, 5105, 5096, -1, 5107, 5106, 5102, -1, 5093, 5108, 4614, -1, 5101, 5109, 5104, -1, 4614, 5108, 4610, -1, 5106, 5109, 5101, -1, 5097, 5110, 5099, -1, 5107, 5111, 5106, -1, 5099, 5110, 5103, -1, 5112, 5111, 5113, -1, 5113, 5111, 5114, -1, 5114, 5111, 5107, -1, 5090, 5115, 5105, -1, 5094, 5116, 4604, -1, 5089, 5115, 5090, -1, 5103, 5117, 5093, -1, 5106, 5118, 5109, -1, 5111, 5118, 5106, -1, 5093, 5117, 5108, -1, 5119, 5120, 5089, -1, 5105, 5120, 5097, -1, 5116, 5121, 4604, -1, 5097, 5120, 5110, -1, 5115, 5120, 5105, -1, 4604, 5121, 4600, -1, 5089, 5120, 5115, -1, 5094, 5122, 5116, -1, 5108, 5123, 4610, -1, 5104, 5122, 5094, -1, 5112, 5124, 5111, -1, 5103, 5125, 5117, -1, 5111, 5124, 5118, -1, 5110, 5125, 5103, -1, 5116, 5126, 5121, -1, 5122, 5126, 5116, -1, 5117, 5127, 5108, -1, 5108, 5127, 5123, -1, 5109, 5128, 5104, -1, 5104, 5128, 5122, -1, 5120, 5129, 5110, -1, 5110, 5129, 5125, -1, 5122, 5130, 5126, -1, 4610, 5131, 4606, -1, 5128, 5130, 5122, -1, 5123, 5131, 4610, -1, 5118, 5132, 5109, -1, 5133, 5132, 5112, -1, 5112, 5132, 5124, -1, 5109, 5132, 5128, -1, 5125, 5134, 5117, -1, 5124, 5132, 5118, -1, 5117, 5134, 5127, -1, 5121, 5135, 4600, -1, 5119, 5136, 5120, -1, 5120, 5136, 5129, -1, 5128, 5137, 5130, -1, 5127, 5138, 5123, -1, 5132, 5137, 5128, -1, 5126, 5139, 5121, -1, 5123, 5138, 5131, -1, 5121, 5139, 5135, -1, 5140, 5141, 5119, -1, 5119, 5141, 5136, -1, 5125, 5141, 5134, -1, 5129, 5141, 5125, -1, 5136, 5141, 5129, -1, 5135, 5142, 4600, -1, 5131, 5143, 4606, -1, 4600, 5142, 4596, -1, 5133, 5144, 5132, -1, 5127, 5145, 5138, -1, 5132, 5144, 5137, -1, 5134, 5145, 5127, -1, 5130, 5146, 5126, -1, 5126, 5146, 5139, -1, 5138, 5147, 5131, -1, 5131, 5147, 5143, -1, 5135, 5148, 5142, -1, 5134, 5149, 5145, -1, 5139, 5148, 5135, -1, 5141, 5149, 5134, -1, 5150, 5151, 5133, -1, 5130, 5151, 5146, -1, 5137, 5151, 5130, -1, 4606, 5152, 4602, -1, 5133, 5151, 5144, -1, 5143, 5152, 4606, -1, 5144, 5151, 5137, -1, 5138, 5153, 5147, -1, 5139, 5154, 5148, -1, 5145, 5153, 5138, -1, 5146, 5154, 5139, -1, 5142, 5155, 4596, -1, 5141, 5156, 5149, -1, 5140, 5156, 5141, -1, 5147, 5157, 5143, -1, 5151, 5158, 5146, -1, 5146, 5158, 5154, -1, 5143, 5157, 5152, -1, 5145, 5159, 5153, -1, 5148, 5160, 5142, -1, 5140, 5159, 5156, -1, 5142, 5160, 5155, -1, 5161, 5159, 5140, -1, 5149, 5159, 5145, -1, 5156, 5159, 5149, -1, 5152, 5162, 4602, -1, 5155, 5163, 4596, -1, 4596, 5163, 4592, -1, 5153, 5164, 5147, -1, 5147, 5164, 5157, -1, 5150, 5165, 5151, -1, 5151, 5165, 5158, -1, 5154, 5166, 5148, -1, 5152, 5167, 5162, -1, 5148, 5166, 5160, -1, 5157, 5167, 5152, -1, 5159, 5168, 5153, -1, 5153, 5168, 5164, -1, 5155, 5169, 5163, -1, 5160, 5169, 5155, -1, 5170, 5171, 5150, -1, 4602, 5172, 4598, -1, 5154, 5171, 5166, -1, 5162, 5172, 4602, -1, 5158, 5171, 5154, -1, 5164, 5173, 5157, -1, 5157, 5173, 5167, -1, 5150, 5171, 5165, -1, 5165, 5171, 5158, -1, 5161, 5174, 5159, -1, 5159, 5174, 5168, -1, 5163, 5175, 4592, -1, 5167, 5176, 5162, -1, 5162, 5176, 5172, -1, 5166, 5177, 5160, -1, 5160, 5177, 5169, -1, 5164, 5178, 5173, -1, 5179, 5178, 5161, -1, 5161, 5178, 5174, -1, 5174, 5178, 5168, -1, 5168, 5178, 5164, -1, 5169, 5180, 5163, -1, 5163, 5180, 5175, -1, 5172, 5181, 4598, -1, 5171, 5182, 5166, -1, 5167, 5183, 5176, -1, 5166, 5182, 5177, -1, 5173, 5183, 5167, -1, 4591, 5184, 5185, -1, 5176, 5186, 5172, -1, 4592, 5184, 4591, -1, 5175, 5184, 4592, -1, 5172, 5186, 5181, -1, 5177, 5187, 5169, -1, 5178, 5188, 5173, -1, 5173, 5188, 5183, -1, 5169, 5187, 5180, -1, 5171, 5189, 5182, -1, 5181, 5190, 4598, -1, 5170, 5189, 5171, -1, 4598, 5190, 4594, -1, 5185, 5191, 5192, -1, 5180, 5191, 5175, -1, 5183, 5193, 5176, -1, 5175, 5191, 5184, -1, 5176, 5193, 5186, -1, 5184, 5191, 5185, -1, 5182, 5194, 5177, -1, 5179, 5195, 5178, -1, 5196, 5194, 5170, -1, 5170, 5194, 5189, -1, 5178, 5195, 5188, -1, 5186, 5197, 5181, -1, 5189, 5194, 5182, -1, 5177, 5194, 5187, -1, 5192, 5198, 5199, -1, 5181, 5197, 5190, -1, 5180, 5198, 5191, -1, 5200, 5201, 5179, -1, 5187, 5198, 5180, -1, 5179, 5201, 5195, -1, 5183, 5201, 5193, -1, 5191, 5198, 5192, -1, 5188, 5201, 5183, -1, 5199, 5202, 5203, -1, 5195, 5201, 5188, -1, 5204, 5202, 5205, -1, 5190, 5206, 4594, -1, 5198, 5202, 5199, -1, 5194, 5202, 5187, -1, 5187, 5202, 5198, -1, 5203, 5202, 5204, -1, 5205, 5207, 5196, -1, 5186, 5208, 5197, -1, 5196, 5207, 5194, -1, 5202, 5207, 5205, -1, 5193, 5208, 5186, -1, 5194, 5207, 5202, -1, 5209, 5210, 5211, -1, 5211, 5210, 5212, -1, 5190, 5213, 5206, -1, 5197, 5213, 5190, -1, 5201, 5214, 5193, -1, 5193, 5214, 5208, -1, 5215, 5216, 5211, -1, 5217, 5218, 5219, -1, 4594, 5220, 4590, -1, 5206, 5220, 4594, -1, 5208, 5221, 5197, -1, 5222, 5223, 5224, -1, 5197, 5221, 5213, -1, 5224, 5223, 5225, -1, 5226, 5223, 5222, -1, 5200, 5227, 5201, -1, 5201, 5227, 5214, -1, 5228, 5229, 5222, -1, 5213, 5230, 5206, -1, 5231, 5229, 5228, -1, 5206, 5230, 5220, -1, 5232, 5233, 5200, -1, 5208, 5233, 5221, -1, 5200, 5233, 5227, -1, 5234, 5235, 5228, -1, 5214, 5233, 5208, -1, 5212, 5236, 5237, -1, 5238, 5236, 5239, -1, 5227, 5233, 5214, -1, 5210, 5236, 5212, -1, 5220, 5240, 4590, -1, 5237, 5236, 5238, -1, 5221, 5241, 5213, -1, 5210, 5242, 5236, -1, 5213, 5241, 5230, -1, 5220, 5243, 5240, -1, 5210, 5244, 5242, -1, 5245, 5244, 5209, -1, 5246, 5244, 5245, -1, 5230, 5243, 5220, -1, 5209, 5244, 5210, -1, 5221, 5247, 5241, -1, 5216, 5248, 5211, -1, 5211, 5248, 5209, -1, 5233, 5247, 5221, -1, 5209, 5248, 5245, -1, 5230, 5249, 5243, -1, 5245, 5248, 5246, -1, 5241, 5249, 5230, -1, 5216, 5250, 5248, -1, 4590, 5251, 4587, -1, 5215, 5252, 5216, -1, 5240, 5251, 4590, -1, 5216, 5252, 5250, -1, 5253, 5252, 5254, -1, 5233, 5255, 5247, -1, 5254, 5252, 5215, -1, 5218, 5256, 5219, -1, 5232, 5255, 5233, -1, 5255, 5257, 5247, -1, 5241, 5257, 5249, -1, 5254, 5256, 5253, -1, 5232, 5257, 5255, -1, 5215, 5256, 5254, -1, 5258, 5257, 5232, -1, 5219, 5256, 5215, -1, 5247, 5257, 5241, -1, 5251, 5259, 4587, -1, 5218, 5260, 5256, -1, 5240, 5261, 5251, -1, 5243, 5261, 5240, -1, 5262, 5263, 5264, -1, 5217, 5263, 5218, -1, 5264, 5263, 5217, -1, 5218, 5263, 5260, -1, 5265, 5266, 5267, -1, 5251, 5268, 5259, -1, 5223, 5266, 5225, -1, 5225, 5266, 5265, -1, 5261, 5268, 5251, -1, 5243, 5269, 5261, -1, 5223, 5270, 5266, -1, 5249, 5269, 5243, -1, 5226, 5271, 5223, -1, 5223, 5271, 5270, -1, 5269, 5272, 5261, -1, 5273, 5271, 5274, -1, 5261, 5272, 5268, -1, 5274, 5271, 5226, -1, 5249, 5275, 5269, -1, 5257, 5275, 5249, -1, 5229, 5276, 5222, -1, 5274, 5276, 5273, -1, 5222, 5276, 5226, -1, 5226, 5276, 5274, -1, 4587, 5277, 4585, -1, 5259, 5277, 4587, -1, 5278, 5279, 5258, -1, 5229, 5280, 5276, -1, 5229, 5281, 5280, -1, 5275, 5279, 5269, -1, 5231, 5281, 5229, -1, 5269, 5279, 5272, -1, 5282, 5281, 5283, -1, 5283, 5281, 5231, -1, 5258, 5284, 5257, -1, 5279, 5284, 5258, -1, 5275, 5284, 5279, -1, 5257, 5284, 5275, -1, 5283, 5285, 5282, -1, 5228, 5285, 5231, -1, 5231, 5285, 5283, -1, 5277, 5286, 4585, -1, 5235, 5285, 5228, -1, 5268, 5287, 5259, -1, 5259, 5287, 5277, -1, 5235, 5288, 5285, -1, 5234, 5289, 5235, -1, 5290, 5289, 5291, -1, 5291, 5289, 5234, -1, 5235, 5289, 5288, -1, 5277, 5292, 5286, -1, 5204, 879, 5203, -1, 5287, 5292, 5277, -1, 5236, 5293, 5239, -1, 5272, 5294, 5268, -1, 5242, 5293, 5236, -1, 5295, 5296, 4669, -1, 5239, 5293, 5297, -1, 5268, 5294, 5287, -1, 4669, 5296, 4665, -1, 5242, 5298, 5293, -1, 5287, 5299, 5292, -1, 5300, 5301, 5295, -1, 5294, 5299, 5287, -1, 5242, 5302, 5298, -1, 5295, 5301, 5296, -1, 5244, 5302, 5242, -1, 5279, 5303, 5272, -1, 5246, 5302, 5244, -1, 5272, 5303, 5294, -1, 5300, 5304, 5301, -1, 5305, 5302, 5246, -1, 5306, 5304, 5300, -1, 5250, 5307, 5248, -1, 5286, 5308, 4585, -1, 5306, 5309, 5304, -1, 5248, 5307, 5246, -1, 5246, 5307, 5305, -1, 4585, 5308, 4670, -1, 5250, 5310, 5307, -1, 5311, 5309, 5306, -1, 5312, 5313, 5278, -1, 5294, 5313, 5299, -1, 5303, 5313, 5294, -1, 5278, 5314, 5279, -1, 4665, 5315, 4662, -1, 5316, 5317, 5253, -1, 5279, 5314, 5303, -1, 5313, 5314, 5278, -1, 5296, 5315, 4665, -1, 5250, 5317, 5310, -1, 5303, 5314, 5313, -1, 5252, 5317, 5250, -1, 5318, 5319, 5320, -1, 5253, 5317, 5252, -1, 5320, 5319, 5311, -1, 5311, 5319, 5309, -1, 5286, 5321, 5308, -1, 5253, 5322, 5316, -1, 5292, 5321, 5286, -1, 5256, 5322, 5253, -1, 5260, 5322, 5256, -1, 5301, 5323, 5296, -1, 5296, 5323, 5315, -1, 5260, 5324, 5322, -1, 5304, 5325, 5301, -1, 5299, 5326, 5292, -1, 5292, 5326, 5321, -1, 5301, 5325, 5323, -1, 5327, 5328, 5262, -1, 5260, 5328, 5324, -1, 5313, 5329, 5299, -1, 5262, 5328, 5263, -1, 5263, 5328, 5260, -1, 5304, 5330, 5325, -1, 5299, 5329, 5326, -1, 5309, 5330, 5304, -1, 5267, 5331, 5332, -1, 5270, 5331, 5266, -1, 5308, 5333, 4670, -1, 5266, 5331, 5267, -1, 4670, 5333, 4666, -1, 5270, 5334, 5331, -1, 5312, 5335, 5313, -1, 5315, 5336, 4662, -1, 5313, 5335, 5329, -1, 4662, 5336, 4658, -1, 5309, 5337, 5330, -1, 5319, 5337, 5309, -1, 5338, 5339, 5273, -1, 5318, 5337, 5319, -1, 5270, 5339, 5334, -1, 5321, 5340, 5308, -1, 5341, 5337, 5318, -1, 5271, 5339, 5270, -1, 5273, 5339, 5271, -1, 5273, 5342, 5338, -1, 5308, 5340, 5333, -1, 5323, 5297, 5315, -1, 5276, 5342, 5273, -1, 5280, 5342, 5276, -1, 5321, 5343, 5340, -1, 5315, 5297, 5336, -1, 5326, 5343, 5321, -1, 5280, 5344, 5342, -1, 5325, 5239, 5323, -1, 5323, 5239, 5297, -1, 5329, 5345, 5326, -1, 5280, 5346, 5344, -1, 5326, 5345, 5343, -1, 5330, 5238, 5325, -1, 5281, 5346, 5280, -1, 5325, 5238, 5239, -1, 5347, 5346, 5282, -1, 4666, 5348, 4660, -1, 5282, 5346, 5281, -1, 5333, 5348, 4666, -1, 5282, 5349, 5347, -1, 5285, 5349, 5282, -1, 5329, 5350, 5345, -1, 5288, 5349, 5285, -1, 5351, 5350, 5312, -1, 5288, 5352, 5349, -1, 5312, 5350, 5335, -1, 5335, 5350, 5329, -1, 5341, 5237, 5337, -1, 5333, 5353, 5348, -1, 5212, 5237, 5341, -1, 5330, 5237, 5238, -1, 5289, 5354, 5288, -1, 5337, 5237, 5330, -1, 5288, 5354, 5352, -1, 5355, 5354, 5290, -1, 5340, 5353, 5333, -1, 5290, 5354, 5289, -1, 5293, 5356, 5297, -1, 5340, 5357, 5353, -1, 5305, 5356, 5302, -1, 4654, 5356, 5358, -1, 5298, 5356, 5293, -1, 5358, 5356, 5305, -1, 5297, 5356, 5336, -1, 5343, 5357, 5340, -1, 5302, 5356, 5298, -1, 5345, 5359, 5343, -1, 4658, 5356, 4654, -1, 5336, 5356, 4658, -1, 5358, 5360, 4654, -1, 5343, 5359, 5357, -1, 5316, 5360, 5317, -1, 5317, 5360, 5310, -1, 5361, 5360, 5316, -1, 4650, 5360, 5361, -1, 5305, 5360, 5358, -1, 5348, 5362, 4660, -1, 5307, 5360, 5305, -1, 4654, 5360, 4650, -1, 5310, 5360, 5307, -1, 5363, 5364, 5327, -1, 4660, 5362, 4656, -1, 5316, 5364, 5361, -1, 5361, 5364, 4650, -1, 5351, 5365, 5350, -1, 5322, 5364, 5316, -1, 5350, 5365, 5345, -1, 5324, 5364, 5322, -1, 5345, 5365, 5359, -1, 5328, 5364, 5324, -1, 5327, 5364, 5328, -1, 4646, 5364, 5363, -1, 5366, 5365, 5351, -1, 4650, 5364, 4646, -1, 5367, 5368, 4628, -1, 5353, 5369, 5348, -1, 5339, 5368, 5334, -1, 5332, 5368, 5367, -1, 5334, 5368, 5331, -1, 4624, 5368, 5370, -1, 5370, 5368, 5338, -1, 5331, 5368, 5332, -1, 5348, 5369, 5362, -1, 5338, 5368, 5339, -1, 5357, 5371, 5353, -1, 4628, 5368, 4624, -1, 5353, 5371, 5369, -1, 5344, 5372, 5342, -1, 5370, 5372, 4624, -1, 5347, 5372, 5346, -1, 5338, 5372, 5370, -1, 4620, 5372, 5373, -1, 5373, 5372, 5347, -1, 5359, 5374, 5357, -1, 5342, 5372, 5338, -1, 4624, 5372, 4620, -1, 5346, 5372, 5344, -1, 5375, 5376, 5355, -1, 5357, 5374, 5371, -1, 5354, 5376, 5352, -1, 5355, 5376, 5354, -1, 5362, 5377, 4656, -1, 5373, 5376, 4620, -1, 5347, 5376, 5373, -1, 5349, 5376, 5347, -1, 4616, 5376, 5375, -1, 4620, 5376, 4616, -1, 4656, 5377, 4652, -1, 5352, 5376, 5349, -1, 5365, 5378, 5359, -1, 5366, 5378, 5365, -1, 5379, 5378, 5366, -1, 5359, 5378, 5374, -1, 5219, 5215, 5211, -1, 5369, 5380, 5362, -1, 5362, 5380, 5377, -1, 5369, 5381, 5380, -1, 5371, 5381, 5369, -1, 5374, 5382, 5371, -1, 5371, 5382, 5381, -1, 5377, 5383, 4652, -1, 4652, 5383, 4648, -1, 5363, 5384, 4646, -1, 4646, 5384, 4642, -1, 5385, 5386, 5379, -1, 5264, 5217, 5387, -1, 5374, 5386, 5382, -1, 5379, 5386, 5378, -1, 5387, 5217, 5219, -1, 5378, 5386, 5374, -1, 5327, 5388, 5363, -1, 5377, 5389, 5383, -1, 5363, 5388, 5384, -1, 5380, 5389, 5377, -1, 5262, 5390, 5327, -1, 5327, 5390, 5388, -1, 5381, 5391, 5380, -1, 5380, 5391, 5389, -1, 5387, 5392, 5264, -1, 5382, 5393, 5381, -1, 5264, 5392, 5262, -1, 5262, 5392, 5390, -1, 5381, 5393, 5391, -1, 5394, 5392, 5387, -1, 5383, 5395, 4648, -1, 4642, 5396, 4638, -1, 4648, 5395, 4644, -1, 5384, 5396, 4642, -1, 5385, 5397, 5386, -1, 4638, 5398, 4634, -1, 5399, 5397, 5385, -1, 5386, 5397, 5382, -1, 5396, 5398, 4638, -1, 5388, 5400, 5384, -1, 5382, 5397, 5393, -1, 5389, 5401, 5383, -1, 5384, 5400, 5396, -1, 5383, 5401, 5395, -1, 5391, 5402, 5389, -1, 5396, 5403, 5398, -1, 5400, 5403, 5396, -1, 5389, 5402, 5401, -1, 5390, 5404, 5388, -1, 5393, 5405, 5391, -1, 5388, 5404, 5400, -1, 5391, 5405, 5402, -1, 5404, 5406, 5400, -1, 5400, 5406, 5403, -1, 5395, 5407, 4644, -1, 4644, 5407, 4640, -1, 5408, 5409, 5394, -1, 5394, 5409, 5392, -1, 5410, 5411, 5399, -1, 5392, 5409, 5390, -1, 5399, 5411, 5397, -1, 5390, 5409, 5404, -1, 5397, 5411, 5393, -1, 5393, 5411, 5405, -1, 5401, 5412, 5395, -1, 5398, 5413, 4634, -1, 5395, 5412, 5407, -1, 5409, 5414, 5404, -1, 5404, 5414, 5406, -1, 5413, 5415, 4634, -1, 5402, 5416, 5401, -1, 5401, 5416, 5412, -1, 4634, 5415, 4630, -1, 5398, 5417, 5413, -1, 5403, 5417, 5398, -1, 5405, 5418, 5402, -1, 5402, 5418, 5416, -1, 5409, 5419, 5414, -1, 5408, 5419, 5409, -1, 5417, 5420, 5413, -1, 5407, 5421, 4640, -1, 5413, 5420, 5415, -1, 4640, 5421, 4636, -1, 5422, 5423, 5410, -1, 5403, 5424, 5417, -1, 5410, 5423, 5411, -1, 5411, 5423, 5405, -1, 5405, 5423, 5418, -1, 5406, 5424, 5403, -1, 5424, 5425, 5417, -1, 5412, 5426, 5407, -1, 5407, 5426, 5421, -1, 5417, 5425, 5420, -1, 5412, 5427, 5426, -1, 5414, 5428, 5406, -1, 5406, 5428, 5424, -1, 5419, 5428, 5414, -1, 5408, 5428, 5419, -1, 5416, 5427, 5412, -1, 5429, 5428, 5408, -1, 5416, 5430, 5427, -1, 5415, 5431, 4630, -1, 5418, 5430, 5416, -1, 5428, 5432, 5424, -1, 5424, 5432, 5425, -1, 4636, 5433, 4632, -1, 5420, 5434, 5415, -1, 5421, 5433, 4636, -1, 5415, 5434, 5431, -1, 5418, 5435, 5430, -1, 5436, 5435, 5422, -1, 5422, 5435, 5423, -1, 5423, 5435, 5418, -1, 5431, 5437, 4630, -1, 5426, 5438, 5421, -1, 5421, 5438, 5433, -1, 4630, 5437, 4626, -1, 5428, 5439, 5432, -1, 5429, 5439, 5428, -1, 5426, 5440, 5438, -1, 5425, 5441, 5420, -1, 5420, 5441, 5434, -1, 5427, 5440, 5426, -1, 5430, 5442, 5427, -1, 5434, 5443, 5431, -1, 5427, 5442, 5440, -1, 5431, 5443, 5437, -1, 5433, 5367, 4632, -1, 5444, 5445, 5429, -1, 5432, 5445, 5425, -1, 5425, 5445, 5441, -1, 4632, 5367, 4628, -1, 5439, 5445, 5432, -1, 5435, 5446, 5430, -1, 5429, 5445, 5439, -1, 5436, 5446, 5435, -1, 5430, 5446, 5442, -1, 5447, 5446, 5436, -1, 5434, 5448, 5443, -1, 5441, 5448, 5434, -1, 5433, 5332, 5367, -1, 5437, 5449, 4626, -1, 5438, 5332, 5433, -1, 5440, 5267, 5438, -1, 5438, 5267, 5332, -1, 5445, 5450, 5441, -1, 5441, 5450, 5448, -1, 5443, 5451, 5437, -1, 5442, 5265, 5440, -1, 5437, 5451, 5449, -1, 5440, 5265, 5267, -1, 5449, 5452, 4626, -1, 4626, 5452, 4622, -1, 5444, 5453, 5445, -1, 5224, 5225, 5447, -1, 5445, 5453, 5450, -1, 5446, 5225, 5442, -1, 5447, 5225, 5446, -1, 5442, 5225, 5265, -1, 5443, 5454, 5451, -1, 5448, 5454, 5443, -1, 5449, 5455, 5452, -1, 5451, 5455, 5449, -1, 5456, 5457, 5444, -1, 5444, 5457, 5453, -1, 5450, 5457, 5448, -1, 5453, 5457, 5450, -1, 5448, 5457, 5454, -1, 5452, 5458, 4622, -1, 5454, 5459, 5451, -1, 5451, 5459, 5455, -1, 5455, 5460, 5452, -1, 5452, 5460, 5458, -1, 5457, 5461, 5454, -1, 5454, 5461, 5459, -1, 4622, 5462, 4618, -1, 5458, 5462, 4622, -1, 5459, 5463, 5455, -1, 5455, 5463, 5460, -1, 5456, 5464, 5457, -1, 5457, 5464, 5461, -1, 5458, 5465, 5462, -1, 5460, 5465, 5458, -1, 5461, 5466, 5459, -1, 5456, 5466, 5464, -1, 5464, 5466, 5461, -1, 5091, 5466, 5456, -1, 5459, 5466, 5463, -1, 5462, 5467, 4618, -1, 5463, 5468, 5460, -1, 5460, 5468, 5465, -1, 5462, 5098, 5467, -1, 5465, 5098, 5462, -1, 5375, 5100, 4616, -1, 5466, 5469, 5463, -1, 5463, 5469, 5468, -1, 4616, 5100, 4612, -1, 5470, 5234, 5228, -1, 5291, 5234, 5470, -1, 5355, 5102, 5375, -1, 5467, 5092, 4618, -1, 4618, 5092, 4614, -1, 5375, 5102, 5100, -1, 5468, 5096, 5465, -1, 5465, 5096, 5098, -1, 5355, 5107, 5102, -1, 5091, 5471, 5466, -1, 5466, 5471, 5469, -1, 5290, 5107, 5355, -1, 5098, 5099, 5467, -1, 5113, 5114, 5470, -1, 5467, 5099, 5092, -1, 5470, 5114, 5291, -1, 5291, 5114, 5290, -1, 5290, 5114, 5107, -1, 5469, 5090, 5468, -1, 5100, 5095, 4612, -1, 5468, 5090, 5096, -1, 4612, 5095, 4608, -1, 5091, 5090, 5471, -1, 5471, 5090, 5469, -1, 5472, 5473, 5474, -1, 4924, 5473, 4912, -1, 5475, 5473, 4924, -1, 5474, 5473, 5475, -1, 5473, 5476, 4912, -1, 5477, 5476, 5478, -1, 4899, 5476, 4885, -1, 4912, 5476, 4899, -1, 890, 5479, 888, -1, 894, 5480, 892, -1, 892, 5480, 890, -1, 5476, 5480, 4885, -1, 5477, 5480, 5476, -1, 4885, 5480, 894, -1, 5479, 5480, 5477, -1, 890, 5480, 5479, -1, 5479, 886, 888, -1, 4774, 5481, 5482, -1, 5320, 5481, 4853, -1, 4853, 5481, 4774, -1, 5483, 5484, 5320, -1, 5479, 885, 886, -1, 5481, 5484, 5482, -1, 5320, 5484, 5481, -1, 5482, 5484, 5483, -1, 5485, 5486, 5487, -1, 5488, 5486, 5485, -1, 5479, 883, 885, -1, 5489, 5486, 5488, -1, 5487, 5486, 5489, -1, 5490, 5491, 5492, -1, 5493, 5491, 5494, -1, 5492, 5491, 5493, -1, 5494, 5491, 5490, -1, 5495, 5496, 5497, -1, 5479, 882, 883, -1, 5498, 5496, 5495, -1, 5499, 5496, 5498, -1, 5497, 5496, 5499, -1, 5500, 5501, 5502, -1, 5503, 5482, 5483, -1, 5502, 5501, 5504, -1, 5504, 5501, 5505, -1, 4774, 5482, 4769, -1, 5505, 5501, 5500, -1, 5506, 5507, 5508, -1, 5487, 5489, 5503, -1, 5508, 5507, 5509, -1, 5510, 5507, 5506, -1, 5509, 5507, 5510, -1, 5482, 5489, 4769, -1, 5511, 5512, 5513, -1, 5503, 5489, 5482, -1, 5513, 5512, 5514, -1, 5515, 5512, 5511, -1, 4769, 5489, 5084, -1, 5514, 5512, 5515, -1, 5472, 5516, 5473, -1, 5517, 5488, 5485, -1, 5476, 5516, 5478, -1, 5489, 5488, 5084, -1, 5478, 5516, 5472, -1, 5473, 5516, 5476, -1, 5072, 5488, 5060, -1, 5084, 5488, 5072, -1, 5518, 5519, 5517, -1, 5517, 5519, 5488, -1, 5488, 5519, 5060, -1, 5060, 5519, 5044, -1, 5520, 5521, 5518, -1, 5522, 5521, 5520, -1, 5518, 5521, 5519, -1, 5519, 5521, 5044, -1, 5044, 5521, 5032, -1, 5521, 5523, 5032, -1, 5524, 5523, 5522, -1, 5013, 5523, 4986, -1, 5032, 5523, 5013, -1, 5522, 5523, 5521, -1, 5524, 5493, 5523, -1, 5492, 5493, 5524, -1, 5523, 5493, 4986, -1, 4986, 5493, 4966, -1, 5525, 5494, 5490, -1, 5493, 5494, 4966, -1, 4966, 5494, 4941, -1, 5494, 5497, 4941, -1, 5495, 5497, 5525, -1, 5525, 5497, 5494, -1, 4917, 5497, 4893, -1, 4941, 5497, 4917, -1, 5526, 5499, 5498, -1, 4893, 5499, 4874, -1, 5497, 5499, 4893, -1, 5527, 5528, 5526, -1, 5499, 5528, 4874, -1, 4874, 5528, 4850, -1, 5526, 5528, 5499, -1, 5529, 5530, 5527, -1, 5531, 5530, 5529, -1, 5528, 5530, 4850, -1, 5527, 5530, 5528, -1, 4839, 5530, 4828, -1, 4850, 5530, 4839, -1, 5530, 5532, 4828, -1, 5531, 5532, 5530, -1, 5533, 5532, 5531, -1, 4828, 5532, 4817, -1, 5502, 5504, 5533, -1, 5532, 5504, 4817, -1, 4817, 5504, 4806, -1, 5533, 5504, 5532, -1, 5534, 5505, 5500, -1, 4795, 5505, 4783, -1, 4806, 5505, 4795, -1, 5504, 5505, 4806, -1, 5505, 5535, 4783, -1, 5536, 5535, 5534, -1, 5534, 5535, 5505, -1, 4783, 5535, 4779, -1, 5536, 5537, 5535, -1, 5535, 5537, 4779, -1, 5538, 5537, 5536, -1, 5539, 5537, 5538, -1, 4779, 5537, 5080, -1, 5539, 5540, 5537, -1, 5537, 5540, 5080, -1, 5541, 5540, 5539, -1, 5069, 5540, 5049, -1, 5080, 5540, 5069, -1, 5540, 5509, 5049, -1, 5508, 5509, 5541, -1, 5049, 5509, 5035, -1, 5541, 5509, 5540, -1, 5509, 5510, 5035, -1, 5542, 5510, 5506, -1, 5035, 5510, 5021, -1, 5542, 5514, 5510, -1, 5513, 5514, 5542, -1, 5007, 5514, 4995, -1, 5021, 5514, 5007, -1, 5510, 5514, 5021, -1, 5543, 5515, 5511, -1, 5514, 5515, 4995, -1, 4995, 5515, 4979, -1, 5544, 5545, 5543, -1, 5515, 5545, 4979, -1, 4885, 896, 898, -1, 4979, 5545, 4965, -1, 5543, 5545, 5515, -1, 5546, 5547, 5544, -1, 5548, 5547, 5546, -1, 4885, 894, 896, -1, 4952, 5547, 4938, -1, 4965, 5547, 4952, -1, 5544, 5547, 5545, -1, 5545, 5547, 4965, -1, 5474, 5475, 5548, -1, 4938, 5475, 4924, -1, 5547, 5475, 4938, -1, 5548, 5475, 5547, -1, 5549, 5550, 5551, -1, 5552, 5553, 5549, -1, 5552, 5554, 5553, -1, 5552, 815, 5554, -1, 5555, 5549, 5551, -1, 5556, 5551, 5557, -1, 5556, 5555, 5551, -1, 5558, 5549, 5555, -1, 5558, 5552, 5549, -1, 5558, 815, 5552, -1, 5558, 819, 815, -1, 5559, 5558, 5555, -1, 5559, 5555, 5556, -1, 5559, 819, 5558, -1, 768, 767, 5560, -1, 5561, 5556, 5557, -1, 5562, 5557, 5563, -1, 5562, 5561, 5557, -1, 5564, 823, 819, -1, 5564, 5559, 5556, -1, 5564, 819, 5559, -1, 5564, 5556, 5561, -1, 5565, 823, 5564, -1, 5565, 5561, 5562, -1, 5565, 5564, 5561, -1, 5566, 5562, 5563, -1, 5567, 5563, 5568, -1, 5567, 5566, 5563, -1, 5569, 823, 5565, -1, 5569, 5562, 5566, -1, 5569, 827, 823, -1, 5569, 5565, 5562, -1, 5570, 5569, 5566, -1, 5570, 827, 5569, -1, 5570, 5566, 5567, -1, 5571, 5567, 5568, -1, 5572, 5568, 5573, -1, 5572, 5571, 5568, -1, 5574, 5570, 5567, -1, 5574, 827, 5570, -1, 5574, 5567, 5571, -1, 5574, 831, 827, -1, 5575, 831, 5574, -1, 5575, 5574, 5571, -1, 5575, 5571, 5572, -1, 5576, 5572, 5573, -1, 5577, 5573, 5578, -1, 5577, 5576, 5573, -1, 5579, 5572, 5576, -1, 5579, 831, 5575, -1, 5579, 5575, 5572, -1, 5579, 835, 831, -1, 5580, 5579, 5576, -1, 5580, 835, 5579, -1, 5580, 5576, 5577, -1, 5581, 5577, 5578, -1, 5582, 5580, 5577, -1, 5582, 5577, 5581, -1, 5582, 835, 5580, -1, 5582, 839, 835, -1, 5583, 5578, 5584, -1, 5583, 5581, 5578, -1, 5585, 5582, 5581, -1, 5585, 839, 5582, -1, 5585, 5581, 5583, -1, 5585, 843, 839, -1, 5586, 5584, 5587, -1, 5586, 5583, 5584, -1, 5588, 843, 5585, -1, 5588, 5585, 5583, -1, 5588, 5583, 5586, -1, 5588, 847, 843, -1, 5589, 5587, 5590, -1, 5589, 5586, 5587, -1, 5591, 5588, 5586, -1, 5591, 847, 5588, -1, 5591, 5586, 5589, -1, 5591, 757, 847, -1, 5592, 5590, 5593, -1, 5592, 5589, 5590, -1, 5594, 5591, 5589, -1, 5594, 757, 5591, -1, 5594, 5589, 5592, -1, 5594, 758, 757, -1, 5595, 5593, 5596, -1, 5595, 5592, 5593, -1, 5597, 5594, 5592, -1, 5597, 758, 5594, -1, 5597, 5592, 5595, -1, 5597, 763, 758, -1, 5598, 5596, 5599, -1, 5598, 5595, 5596, -1, 5600, 5597, 5595, -1, 5600, 763, 5597, -1, 5600, 5595, 5598, -1, 5600, 771, 763, -1, 5601, 5599, 5602, -1, 5601, 5598, 5599, -1, 5603, 5600, 5598, -1, 5603, 5598, 5601, -1, 5603, 771, 5600, -1, 5603, 777, 771, -1, 5604, 5602, 5605, -1, 5604, 5601, 5602, -1, 5606, 5603, 5601, -1, 5606, 5601, 5604, -1, 5606, 777, 5603, -1, 5606, 783, 777, -1, 5607, 5605, 5608, -1, 5607, 5604, 5605, -1, 5609, 5604, 5607, -1, 5609, 5606, 5604, -1, 5609, 783, 5606, -1, 5609, 789, 783, -1, 5610, 5607, 5608, -1, 5610, 5608, 5611, -1, 5610, 5611, 4381, -1, 5610, 4381, 5612, -1, 5613, 5612, 5614, -1, 5613, 5610, 5612, -1, 5613, 5609, 5607, -1, 5613, 795, 789, -1, 5613, 5607, 5610, -1, 5613, 5614, 795, -1, 5613, 789, 5609, -1, 798, 795, 5614, -1, 5615, 4368, 5616, -1, 5615, 5617, 4368, -1, 5618, 768, 5560, -1, 5618, 5617, 5615, -1, 5618, 5560, 5617, -1, 5619, 5616, 5620, -1, 5619, 5615, 5616, -1, 5621, 768, 5618, -1, 5621, 5618, 5615, -1, 5621, 775, 768, -1, 5621, 5615, 5619, -1, 5622, 5620, 5623, -1, 5622, 5619, 5620, -1, 5624, 775, 5621, -1, 5624, 5621, 5619, -1, 5624, 5619, 5622, -1, 5624, 781, 775, -1, 5625, 5623, 5626, -1, 5625, 5622, 5623, -1, 5627, 5624, 5622, -1, 5627, 787, 781, -1, 5627, 781, 5624, -1, 5627, 5622, 5625, -1, 5628, 5626, 5629, -1, 5628, 5625, 5626, -1, 5630, 787, 5627, -1, 5630, 5627, 5625, -1, 5630, 5625, 5628, -1, 5630, 793, 787, -1, 5631, 5629, 5632, -1, 5631, 5628, 5629, -1, 5633, 801, 793, -1, 5633, 5630, 5628, -1, 5633, 793, 5630, -1, 5633, 5628, 5631, -1, 5634, 5632, 5635, -1, 5634, 5631, 5632, -1, 5636, 801, 5633, -1, 5636, 5633, 5631, -1, 5636, 5631, 5634, -1, 5636, 805, 801, -1, 5637, 5635, 5638, -1, 5637, 5634, 5635, -1, 5639, 809, 805, -1, 5639, 5636, 5634, -1, 5639, 805, 5636, -1, 5639, 5634, 5637, -1, 5640, 5638, 5641, -1, 5640, 5637, 5638, -1, 5642, 5639, 5637, -1, 5642, 809, 5639, -1, 5642, 813, 809, -1, 5642, 5637, 5640, -1, 5643, 5641, 5644, -1, 5643, 5640, 5641, -1, 5645, 813, 5642, -1, 5645, 5642, 5640, -1, 5645, 817, 813, -1, 5645, 5640, 5643, -1, 5646, 5644, 5647, -1, 5646, 5643, 5644, -1, 5648, 817, 5645, -1, 5648, 5645, 5643, -1, 5648, 821, 817, -1, 5648, 5643, 5646, -1, 5649, 5647, 5650, -1, 5649, 5646, 5647, -1, 5651, 5649, 5650, -1, 5652, 821, 5648, -1, 5652, 5646, 5649, -1, 5652, 5648, 5646, -1, 5652, 825, 821, -1, 5653, 5652, 5649, -1, 5653, 825, 5652, -1, 5653, 829, 825, -1, 5653, 5649, 5651, -1, 5654, 5650, 5655, -1, 5654, 5651, 5650, -1, 5656, 5654, 5655, -1, 5657, 5651, 5654, -1, 5657, 829, 5653, -1, 5657, 5653, 5651, -1, 5658, 5657, 5654, -1, 5658, 5654, 5656, -1, 5658, 829, 5657, -1, 5658, 833, 829, -1, 5659, 5655, 5660, -1, 5659, 5656, 5655, -1, 5661, 5659, 5660, -1, 5662, 5658, 5656, -1, 5662, 5656, 5659, -1, 5662, 833, 5658, -1, 5663, 833, 5662, -1, 5663, 837, 833, -1, 5663, 5659, 5661, -1, 5663, 5662, 5659, -1, 5664, 5660, 5665, -1, 5664, 5661, 5660, -1, 5666, 5664, 5665, -1, 5667, 837, 5663, -1, 5667, 5663, 5661, -1, 5667, 5661, 5664, -1, 5668, 837, 5667, -1, 5668, 5667, 5664, -1, 5668, 841, 837, -1, 5668, 5664, 5666, -1, 5669, 5665, 5670, -1, 5669, 5666, 5665, -1, 5671, 5669, 5670, -1, 5672, 841, 5668, -1, 5672, 5668, 5666, -1, 5672, 5666, 5669, -1, 5673, 5669, 5671, -1, 5673, 841, 5672, -1, 5673, 5672, 5669, -1, 5673, 845, 841, -1, 5674, 5670, 5675, -1, 5674, 5671, 5670, -1, 5676, 5671, 5674, -1, 5676, 5673, 5671, -1, 5676, 845, 5673, -1, 5677, 5674, 5675, -1, 5678, 845, 5676, -1, 5678, 5674, 5677, -1, 5678, 753, 845, -1, 5678, 5676, 5674, -1, 5679, 5675, 5680, -1, 5679, 5677, 5675, -1, 5681, 5678, 5677, -1, 5681, 753, 5678, -1, 5681, 5677, 5679, -1, 5682, 5679, 5680, -1, 5683, 753, 5681, -1, 5683, 5681, 5679, -1, 5683, 5679, 5682, -1, 5683, 754, 753, -1, 5684, 5680, 5685, -1, 5684, 5682, 5680, -1, 5686, 5683, 5682, -1, 5686, 754, 5683, -1, 5686, 5682, 5684, -1, 5687, 5684, 5685, -1, 5688, 754, 5686, -1, 5688, 5686, 5684, -1, 5688, 5684, 5687, -1, 5688, 761, 754, -1, 5689, 5685, 5690, -1, 5689, 5687, 5685, -1, 5691, 5688, 5687, -1, 5691, 761, 5688, -1, 5691, 5687, 5689, -1, 5692, 5689, 5690, -1, 5693, 761, 5691, -1, 5693, 5691, 5689, -1, 5693, 5689, 5692, -1, 5693, 765, 761, -1, 5694, 5690, 5695, -1, 5694, 5692, 5690, -1, 5696, 5693, 5692, -1, 5696, 765, 5693, -1, 5696, 5692, 5694, -1, 5697, 5694, 5695, -1, 5698, 765, 5696, -1, 5698, 5696, 5694, -1, 5698, 773, 765, -1, 5698, 5694, 5697, -1, 5699, 5695, 5700, -1, 5699, 5697, 5695, -1, 5701, 773, 5698, -1, 5701, 5698, 5697, -1, 5701, 5697, 5699, -1, 5702, 5699, 5700, -1, 5703, 773, 5701, -1, 5703, 779, 773, -1, 5703, 5701, 5699, -1, 5703, 5699, 5702, -1, 5704, 5702, 5700, -1, 5704, 5700, 5705, -1, 5706, 5702, 5704, -1, 5706, 779, 5703, -1, 5706, 5703, 5702, -1, 5707, 5704, 5705, -1, 5708, 785, 779, -1, 5708, 5704, 5707, -1, 5708, 5706, 5704, -1, 5708, 779, 5706, -1, 5709, 5705, 5710, -1, 5709, 5707, 5705, -1, 5711, 5708, 5707, -1, 5711, 5707, 5709, -1, 5711, 785, 5708, -1, 5712, 5709, 5710, -1, 5713, 5709, 5712, -1, 5713, 785, 5711, -1, 5713, 791, 785, -1, 5713, 5711, 5709, -1, 5714, 5712, 5710, -1, 5714, 5710, 5715, -1, 5716, 5713, 5712, -1, 5716, 5712, 5714, -1, 5716, 791, 5713, -1, 5717, 5714, 5715, -1, 5718, 5716, 5714, -1, 5718, 5714, 5717, -1, 5718, 791, 5716, -1, 5718, 799, 791, -1, 5719, 5717, 5715, -1, 5719, 5715, 5720, -1, 5721, 5717, 5719, -1, 5721, 5718, 5717, -1, 5721, 799, 5718, -1, 5722, 5719, 5720, -1, 5723, 5721, 5719, -1, 5723, 799, 5721, -1, 5723, 5719, 5722, -1, 5723, 803, 799, -1, 5724, 5720, 5725, -1, 5724, 5722, 5720, -1, 5726, 803, 5723, -1, 5726, 5723, 5722, -1, 5726, 5722, 5724, -1, 5727, 5724, 5725, -1, 5728, 5726, 5724, -1, 5728, 803, 5726, -1, 5728, 5724, 5727, -1, 5728, 807, 803, -1, 5729, 5725, 5730, -1, 5729, 5727, 5725, -1, 5731, 5728, 5727, -1, 5731, 807, 5728, -1, 5731, 5727, 5729, -1, 5732, 5729, 5730, -1, 5733, 5731, 5729, -1, 5733, 807, 5731, -1, 5733, 5729, 5732, -1, 5733, 811, 807, -1, 5734, 5730, 5550, -1, 5734, 5732, 5730, -1, 5735, 811, 5733, -1, 5735, 5733, 5732, -1, 5735, 5732, 5734, -1, 5553, 5734, 5550, -1, 5554, 5735, 5734, -1, 5554, 5734, 5553, -1, 5554, 811, 5735, -1, 5554, 815, 811, -1, 5549, 5553, 5550, -1, 5736, 5737, 814, -1, 5738, 5739, 5737, -1, 5738, 5740, 5739, -1, 5738, 5737, 5736, -1, 5738, 5741, 5740, -1, 5742, 814, 818, -1, 5742, 5736, 814, -1, 5743, 5742, 818, -1, 5744, 5738, 5736, -1, 5744, 5741, 5738, -1, 5744, 5736, 5742, -1, 5745, 5741, 5744, -1, 5745, 5746, 5741, -1, 5745, 5742, 5743, -1, 5745, 5744, 5742, -1, 5747, 818, 822, -1, 5747, 5743, 818, -1, 5748, 5747, 822, -1, 5749, 5743, 5747, -1, 5749, 5746, 5745, -1, 5749, 5745, 5743, -1, 5750, 5751, 5746, -1, 5750, 5749, 5747, -1, 5750, 5747, 5748, -1, 5750, 5746, 5749, -1, 5752, 822, 826, -1, 5752, 5748, 822, -1, 5753, 5752, 826, -1, 5754, 5750, 5748, -1, 5754, 5748, 5752, -1, 5754, 5751, 5750, -1, 5755, 5752, 5753, -1, 5755, 5751, 5754, -1, 5755, 5756, 5751, -1, 5755, 5754, 5752, -1, 5757, 826, 830, -1, 5757, 5753, 826, -1, 5758, 5757, 830, -1, 5759, 5753, 5757, -1, 5759, 5755, 5753, -1, 5759, 5756, 5755, -1, 5760, 5757, 5758, -1, 5760, 5756, 5759, -1, 5760, 5759, 5757, -1, 5760, 5761, 5756, -1, 5762, 830, 834, -1, 5762, 5758, 830, -1, 5763, 5762, 834, -1, 5764, 5760, 5758, -1, 5764, 5761, 5760, -1, 5764, 5758, 5762, -1, 5765, 5761, 5764, -1, 5765, 5762, 5763, -1, 5765, 5764, 5762, -1, 5765, 5766, 5761, -1, 5767, 834, 838, -1, 5767, 5763, 834, -1, 5768, 5765, 5763, -1, 5768, 5766, 5765, -1, 5768, 5763, 5767, -1, 5769, 838, 842, -1, 5769, 5767, 838, -1, 5770, 5766, 5768, -1, 5770, 5768, 5767, -1, 5770, 5767, 5769, -1, 5770, 5771, 5766, -1, 5772, 842, 846, -1, 5772, 5769, 842, -1, 5773, 5770, 5769, -1, 5773, 5771, 5770, -1, 5773, 5769, 5772, -1, 5773, 5774, 5771, -1, 5775, 846, 759, -1, 5775, 5772, 846, -1, 5776, 5773, 5772, -1, 5776, 5774, 5773, -1, 5776, 5772, 5775, -1, 5776, 5777, 5774, -1, 5778, 759, 756, -1, 5778, 5775, 759, -1, 5779, 5776, 5775, -1, 5779, 5777, 5776, -1, 5779, 5775, 5778, -1, 5779, 5780, 5777, -1, 5781, 756, 762, -1, 5781, 5778, 756, -1, 5782, 5779, 5778, -1, 5782, 5780, 5779, -1, 5782, 5778, 5781, -1, 5782, 5783, 5780, -1, 5782, 5784, 5783, -1, 5785, 762, 770, -1, 5785, 5781, 762, -1, 5786, 5782, 5781, -1, 5786, 5784, 5782, -1, 5786, 5781, 5785, -1, 5787, 770, 776, -1, 5787, 5785, 770, -1, 5788, 5784, 5786, -1, 5788, 5786, 5785, -1, 5788, 5785, 5787, -1, 5788, 5789, 5784, -1, 5790, 776, 782, -1, 5790, 5787, 776, -1, 5791, 5788, 5787, -1, 5791, 5789, 5788, -1, 5791, 5787, 5790, -1, 5791, 5792, 5789, -1, 5793, 782, 788, -1, 5793, 5790, 782, -1, 5794, 5791, 5790, -1, 5794, 5792, 5791, -1, 5794, 5790, 5793, -1, 5794, 5795, 5792, -1, 5796, 788, 794, -1, 5796, 5793, 788, -1, 5796, 794, 5797, -1, 5798, 5797, 5799, -1, 5798, 5796, 5797, -1, 5798, 5800, 5795, -1, 5798, 5799, 5800, -1, 5798, 5794, 5793, -1, 5798, 5795, 5794, -1, 5798, 5793, 5796, -1, 5797, 794, 797, -1, 4320, 5800, 5799, -1, 5801, 769, 766, -1, 5801, 5802, 769, -1, 5803, 5804, 4321, -1, 5803, 5802, 5801, -1, 5803, 5805, 5802, -1, 5803, 4321, 5805, -1, 5806, 766, 774, -1, 5806, 5801, 766, -1, 5807, 5801, 5806, -1, 5807, 5803, 5801, -1, 5807, 5804, 5803, -1, 5807, 5808, 5804, -1, 5809, 5806, 774, -1, 5809, 774, 780, -1, 5810, 5811, 5808, -1, 5810, 5806, 5809, -1, 5810, 5808, 5807, -1, 5810, 5807, 5806, -1, 5812, 780, 786, -1, 5812, 5809, 780, -1, 5813, 5809, 5812, -1, 5813, 5810, 5809, -1, 5813, 5811, 5810, -1, 5813, 5814, 5811, -1, 5815, 786, 792, -1, 5815, 5812, 786, -1, 5816, 5813, 5812, -1, 5816, 5814, 5813, -1, 5816, 5812, 5815, -1, 5816, 5817, 5814, -1, 5818, 792, 800, -1, 5818, 5815, 792, -1, 5819, 5817, 5816, -1, 5819, 5815, 5818, -1, 5819, 5820, 5817, -1, 5819, 5816, 5815, -1, 5821, 5818, 800, -1, 5821, 800, 804, -1, 5822, 5819, 5818, -1, 5822, 5823, 5820, -1, 5822, 5820, 5819, -1, 5822, 5818, 5821, -1, 5824, 804, 808, -1, 5824, 5821, 804, -1, 5825, 5823, 5822, -1, 5825, 5822, 5821, -1, 5825, 5826, 5823, -1, 5825, 5821, 5824, -1, 5827, 808, 812, -1, 5827, 5824, 808, -1, 5828, 5825, 5824, -1, 5828, 5829, 5826, -1, 5828, 5826, 5825, -1, 5828, 5824, 5827, -1, 5830, 5827, 812, -1, 5830, 812, 816, -1, 5831, 5829, 5828, -1, 5831, 5828, 5827, -1, 5831, 5827, 5830, -1, 5831, 5832, 5829, -1, 5833, 816, 820, -1, 5833, 5830, 816, -1, 5834, 5831, 5830, -1, 5834, 5832, 5831, -1, 5834, 5830, 5833, -1, 5834, 5835, 5832, -1, 5836, 820, 824, -1, 5836, 5833, 820, -1, 5837, 5836, 824, -1, 5837, 824, 828, -1, 5838, 5835, 5834, -1, 5838, 5834, 5833, -1, 5838, 5833, 5836, -1, 5838, 5839, 5835, -1, 5840, 5839, 5838, -1, 5840, 5836, 5837, -1, 5840, 5838, 5836, -1, 5841, 5837, 828, -1, 5842, 5841, 828, -1, 5842, 828, 832, -1, 5843, 5840, 5837, -1, 5843, 5839, 5840, -1, 5843, 5837, 5841, -1, 5843, 5844, 5839, -1, 5845, 5841, 5842, -1, 5845, 5843, 5841, -1, 5845, 5844, 5843, -1, 5846, 5842, 832, -1, 5847, 5846, 832, -1, 5847, 832, 836, -1, 5848, 5842, 5846, -1, 5848, 5844, 5845, -1, 5848, 5849, 5844, -1, 5848, 5845, 5842, -1, 5850, 5848, 5846, -1, 5850, 5849, 5848, -1, 5850, 5846, 5847, -1, 5851, 5847, 836, -1, 5852, 836, 840, -1, 5852, 5851, 836, -1, 5853, 5850, 5847, -1, 5853, 5847, 5851, -1, 5853, 5854, 5849, -1, 5853, 5849, 5850, -1, 5855, 5853, 5851, -1, 5855, 5854, 5853, -1, 5855, 5851, 5852, -1, 5856, 5852, 840, -1, 5857, 5856, 840, -1, 5857, 840, 844, -1, 5858, 5855, 5852, -1, 5858, 5852, 5856, -1, 5858, 5859, 5854, -1, 5858, 5854, 5855, -1, 5860, 5858, 5856, -1, 5860, 5859, 5858, -1, 5860, 5856, 5857, -1, 5861, 5857, 844, -1, 5862, 5860, 5857, -1, 5862, 5857, 5861, -1, 5862, 5859, 5860, -1, 5862, 5863, 5859, -1, 5864, 844, 755, -1, 5864, 5861, 844, -1, 5865, 5861, 5864, -1, 5865, 5862, 5861, -1, 5865, 5863, 5862, -1, 5866, 5864, 755, -1, 5867, 5863, 5865, -1, 5867, 5864, 5866, -1, 5867, 5868, 5863, -1, 5867, 5865, 5864, -1, 5869, 755, 752, -1, 5869, 5866, 755, -1, 5870, 5867, 5866, -1, 5870, 5868, 5867, -1, 5870, 5866, 5869, -1, 5871, 5869, 752, -1, 5872, 5870, 5869, -1, 5872, 5868, 5870, -1, 5872, 5873, 5868, -1, 5872, 5869, 5871, -1, 5874, 752, 760, -1, 5874, 5871, 752, -1, 5875, 5872, 5871, -1, 5875, 5873, 5872, -1, 5875, 5871, 5874, -1, 5876, 5874, 760, -1, 5877, 5875, 5874, -1, 5877, 5873, 5875, -1, 5877, 5878, 5873, -1, 5877, 5874, 5876, -1, 5879, 760, 764, -1, 5879, 5876, 760, -1, 5880, 5877, 5876, -1, 5880, 5878, 5877, -1, 5880, 5876, 5879, -1, 5881, 5879, 764, -1, 5882, 5880, 5879, -1, 5882, 5878, 5880, -1, 5882, 5883, 5878, -1, 5882, 5879, 5881, -1, 5884, 764, 772, -1, 5884, 5881, 764, -1, 5885, 5882, 5881, -1, 5885, 5883, 5882, -1, 5885, 5881, 5884, -1, 5886, 5884, 772, -1, 5887, 5888, 5883, -1, 5887, 5885, 5884, -1, 5887, 5883, 5885, -1, 5887, 5884, 5886, -1, 5889, 772, 778, -1, 5889, 5886, 772, -1, 5890, 5888, 5887, -1, 5890, 5887, 5886, -1, 5890, 5886, 5889, -1, 5891, 5889, 778, -1, 5892, 5893, 5888, -1, 5892, 5888, 5890, -1, 5892, 5890, 5889, -1, 5892, 5889, 5891, -1, 5894, 5891, 778, -1, 5894, 778, 784, -1, 5895, 5891, 5894, -1, 5895, 5893, 5892, -1, 5895, 5892, 5891, -1, 5896, 5894, 784, -1, 5897, 5898, 5893, -1, 5897, 5894, 5896, -1, 5897, 5895, 5894, -1, 5897, 5893, 5895, -1, 5899, 784, 790, -1, 5899, 5896, 784, -1, 5900, 5897, 5896, -1, 5900, 5898, 5897, -1, 5900, 5896, 5899, -1, 5901, 5899, 790, -1, 5902, 5898, 5900, -1, 5902, 5899, 5901, -1, 5902, 5900, 5899, -1, 5902, 5903, 5898, -1, 5904, 5901, 790, -1, 5904, 790, 796, -1, 5905, 5901, 5904, -1, 5905, 5902, 5901, -1, 5905, 5903, 5902, -1, 5906, 5904, 796, -1, 5907, 5904, 5906, -1, 5907, 5905, 5904, -1, 5907, 5903, 5905, -1, 5907, 5908, 5903, -1, 5909, 796, 802, -1, 5909, 5906, 796, -1, 5910, 5907, 5906, -1, 5910, 5908, 5907, -1, 5910, 5906, 5909, -1, 5911, 5909, 802, -1, 5912, 5910, 5909, -1, 5912, 5909, 5911, -1, 5912, 5908, 5910, -1, 5912, 5913, 5908, -1, 5914, 802, 806, -1, 5914, 5911, 802, -1, 5915, 5912, 5911, -1, 5915, 5913, 5912, -1, 5915, 5911, 5914, -1, 5916, 5914, 806, -1, 5917, 5914, 5916, -1, 5917, 5915, 5914, -1, 5917, 5913, 5915, -1, 5917, 5918, 5913, -1, 5919, 5916, 806, -1, 5919, 806, 810, -1, 5920, 5916, 5919, -1, 5920, 5917, 5916, -1, 5920, 5918, 5917, -1, 5921, 5919, 810, -1, 5922, 5919, 5921, -1, 5922, 5920, 5919, -1, 5922, 5918, 5920, -1, 5922, 5740, 5918, -1, 5737, 810, 814, -1, 5737, 5921, 810, -1, 5739, 5922, 5921, -1, 5739, 5740, 5922, -1, 5739, 5921, 5737, -1, 5923, 5924, 5925, -1, 5923, 4334, 5924, -1, 5923, 5925, 5926, -1, 5923, 4336, 4334, -1, 5927, 5928, 5929, -1, 5927, 5926, 5928, -1, 5930, 5927, 5929, -1, 5931, 5923, 5926, -1, 5931, 4336, 5923, -1, 5931, 5926, 5927, -1, 5932, 4336, 5931, -1, 5932, 5927, 5930, -1, 5932, 4338, 4336, -1, 5932, 5931, 5927, -1, 5933, 5929, 5934, -1, 5933, 5930, 5929, -1, 5935, 5933, 5934, -1, 5936, 5930, 5933, -1, 5936, 5932, 5930, -1, 5936, 4338, 5932, -1, 5937, 4340, 4338, -1, 5937, 5936, 5933, -1, 5937, 5933, 5935, -1, 5937, 4338, 5936, -1, 5938, 5934, 5939, -1, 5938, 5935, 5934, -1, 5940, 5938, 5939, -1, 5941, 5937, 5935, -1, 5941, 5935, 5938, -1, 5941, 4340, 5937, -1, 5942, 5938, 5940, -1, 5942, 4340, 5941, -1, 5942, 4342, 4340, -1, 5942, 5941, 5938, -1, 5943, 5939, 5944, -1, 5943, 5940, 5939, -1, 5945, 5943, 5944, -1, 5946, 5940, 5943, -1, 5946, 5942, 5940, -1, 5946, 4342, 5942, -1, 5947, 5943, 5945, -1, 5947, 4342, 5946, -1, 5947, 5946, 5943, -1, 5947, 4344, 4342, -1, 5948, 5944, 5949, -1, 5948, 5945, 5944, -1, 5950, 5948, 5949, -1, 5951, 5947, 5945, -1, 5951, 4344, 5947, -1, 5951, 5945, 5948, -1, 5952, 4344, 5951, -1, 5952, 5948, 5950, -1, 5952, 5951, 5948, -1, 5952, 4346, 4344, -1, 5953, 5949, 5954, -1, 5953, 5950, 5949, -1, 5955, 5952, 5950, -1, 5955, 4346, 5952, -1, 5955, 5950, 5953, -1, 5956, 5954, 5957, -1, 5956, 5953, 5954, -1, 5958, 4346, 5955, -1, 5958, 5955, 5953, -1, 5958, 5953, 5956, -1, 5958, 4348, 4346, -1, 5959, 5957, 5960, -1, 5959, 5956, 5957, -1, 5961, 5958, 5956, -1, 5961, 4348, 5958, -1, 5961, 5956, 5959, -1, 5961, 4350, 4348, -1, 5962, 5960, 5963, -1, 5962, 5959, 5960, -1, 5964, 5961, 5959, -1, 5964, 4350, 5961, -1, 5964, 5959, 5962, -1, 5964, 4352, 4350, -1, 5965, 5963, 5966, -1, 5965, 5962, 5963, -1, 5967, 5964, 5962, -1, 5967, 4352, 5964, -1, 5967, 5962, 5965, -1, 5967, 4354, 4352, -1, 5968, 5966, 5969, -1, 5968, 5965, 5966, -1, 5970, 5967, 5965, -1, 5970, 4354, 5967, -1, 5970, 5965, 5968, -1, 5970, 4356, 4354, -1, 5971, 5969, 5972, -1, 5971, 5968, 5969, -1, 5973, 5970, 5968, -1, 5973, 4356, 5970, -1, 5973, 5968, 5971, -1, 5973, 4358, 4356, -1, 5974, 5972, 5975, -1, 5974, 5971, 5972, -1, 5976, 5973, 5971, -1, 5976, 4358, 5973, -1, 5976, 5971, 5974, -1, 5976, 4360, 4358, -1, 5977, 5975, 5978, -1, 5977, 5974, 5975, -1, 5979, 5976, 5974, -1, 5979, 4360, 5976, -1, 5979, 5974, 5977, -1, 5979, 4317, 4360, -1, 5980, 5978, 5981, -1, 5980, 5977, 5978, -1, 5982, 5979, 5977, -1, 5982, 4317, 5979, -1, 5982, 5977, 5980, -1, 5982, 4316, 4317, -1, 5983, 5981, 5984, -1, 5983, 5980, 5981, -1, 5983, 5984, 5802, -1, 5985, 5802, 5805, -1, 5985, 5983, 5802, -1, 5985, 5805, 4319, -1, 5985, 5982, 5980, -1, 5985, 4316, 5982, -1, 5985, 4319, 4316, -1, 5985, 5980, 5983, -1, 5802, 5984, 769, -1, 4321, 4319, 5805, -1, 5986, 5797, 797, -1, 5986, 797, 5987, -1, 5988, 5799, 5797, -1, 5988, 4320, 5799, -1, 5988, 5797, 5986, -1, 5988, 4323, 4320, -1, 5989, 5987, 5990, -1, 5989, 5986, 5987, -1, 5991, 5986, 5989, -1, 5991, 4323, 5988, -1, 5991, 4325, 4323, -1, 5991, 5988, 5986, -1, 5992, 5989, 5990, -1, 5992, 5990, 5993, -1, 5994, 5991, 5989, -1, 5994, 4327, 4325, -1, 5994, 5989, 5992, -1, 5994, 4325, 5991, -1, 5995, 5993, 5996, -1, 5995, 5992, 5993, -1, 5997, 5992, 5995, -1, 5997, 5994, 5992, -1, 5997, 4327, 5994, -1, 5997, 4329, 4327, -1, 5998, 5995, 5996, -1, 5998, 5996, 5999, -1, 6000, 4329, 5997, -1, 6000, 5995, 5998, -1, 6000, 4331, 4329, -1, 6000, 5997, 5995, -1, 6001, 5999, 6002, -1, 6001, 5998, 5999, -1, 6003, 5998, 6001, -1, 6003, 4333, 4331, -1, 6003, 6000, 5998, -1, 6003, 4331, 6000, -1, 6004, 6001, 6002, -1, 6004, 6002, 6005, -1, 6006, 6003, 6001, -1, 6006, 4333, 6003, -1, 6006, 6001, 6004, -1, 6006, 4335, 4333, -1, 6007, 6005, 6008, -1, 6007, 6004, 6005, -1, 6009, 6006, 6004, -1, 6009, 4335, 6006, -1, 6009, 4337, 4335, -1, 6009, 6004, 6007, -1, 6010, 6008, 6011, -1, 6010, 6007, 6008, -1, 6012, 6009, 6007, -1, 6012, 4337, 6009, -1, 6012, 4339, 4337, -1, 6012, 6007, 6010, -1, 6013, 6010, 6011, -1, 6013, 6011, 6014, -1, 6015, 4339, 6012, -1, 6015, 6012, 6010, -1, 6015, 6010, 6013, -1, 6015, 4341, 4339, -1, 6016, 6017, 6018, -1, 6016, 6014, 6017, -1, 6016, 6013, 6014, -1, 6019, 6015, 6013, -1, 6019, 6013, 6016, -1, 6019, 4343, 4341, -1, 6019, 4341, 6015, -1, 6020, 6016, 6018, -1, 6021, 6018, 6022, -1, 6021, 6020, 6018, -1, 6023, 6016, 6020, -1, 6023, 4343, 6019, -1, 6023, 6019, 6016, -1, 6023, 4345, 4343, -1, 6024, 6023, 6020, -1, 6024, 6020, 6021, -1, 6024, 4345, 6023, -1, 6025, 6021, 6022, -1, 6026, 6025, 6022, -1, 6026, 6022, 6027, -1, 6028, 6021, 6025, -1, 6028, 4345, 6024, -1, 6028, 4347, 4345, -1, 6028, 6024, 6021, -1, 6029, 4347, 6028, -1, 6029, 6028, 6025, -1, 6029, 6025, 6026, -1, 6030, 6026, 6027, -1, 6031, 6030, 6027, -1, 6031, 6027, 6032, -1, 6033, 6026, 6030, -1, 6033, 6029, 6026, -1, 6033, 4347, 6029, -1, 6033, 4349, 4347, -1, 6034, 6033, 6030, -1, 6034, 4349, 6033, -1, 6034, 6030, 6031, -1, 6035, 6031, 6032, -1, 6036, 6032, 6037, -1, 6036, 6035, 6032, -1, 6038, 4349, 6034, -1, 6038, 6031, 6035, -1, 6038, 6034, 6031, -1, 6038, 4351, 4349, -1, 6039, 6038, 6035, -1, 6039, 4351, 6038, -1, 6039, 6035, 6036, -1, 6040, 6036, 6037, -1, 6041, 6040, 6037, -1, 6041, 6037, 6042, -1, 6043, 4351, 6039, -1, 6043, 6039, 6036, -1, 6043, 4353, 4351, -1, 6043, 6036, 6040, -1, 6044, 6040, 6041, -1, 6044, 6043, 6040, -1, 6044, 4353, 6043, -1, 6045, 6041, 6042, -1, 6046, 6044, 6041, -1, 6046, 4353, 6044, -1, 6046, 4355, 4353, -1, 6046, 6041, 6045, -1, 6047, 6045, 6042, -1, 6047, 6042, 6048, -1, 6049, 6045, 6047, -1, 6049, 6046, 6045, -1, 6049, 4355, 6046, -1, 6050, 6047, 6048, -1, 6051, 6049, 6047, -1, 6051, 4355, 6049, -1, 6051, 6047, 6050, -1, 6051, 4357, 4355, -1, 6052, 6048, 6053, -1, 6052, 6050, 6048, -1, 6054, 6051, 6050, -1, 6054, 4357, 6051, -1, 6054, 6050, 6052, -1, 6055, 6052, 6053, -1, 6056, 6054, 6052, -1, 6056, 4357, 6054, -1, 6056, 4359, 4357, -1, 6056, 6052, 6055, -1, 6057, 6053, 6058, -1, 6057, 6055, 6053, -1, 6059, 6056, 6055, -1, 6059, 4359, 6056, -1, 6059, 6055, 6057, -1, 6060, 6057, 6058, -1, 6061, 6059, 6057, -1, 6061, 4359, 6059, -1, 6061, 4315, 4359, -1, 6061, 6057, 6060, -1, 6062, 6058, 6063, -1, 6062, 6060, 6058, -1, 6064, 6061, 6060, -1, 6064, 4315, 6061, -1, 6064, 6060, 6062, -1, 6065, 6062, 6063, -1, 6066, 6064, 6062, -1, 6066, 4315, 6064, -1, 6066, 4314, 4315, -1, 6066, 6062, 6065, -1, 6067, 6063, 6068, -1, 6067, 6065, 6063, -1, 6069, 6066, 6065, -1, 6069, 4314, 6066, -1, 6069, 6065, 6067, -1, 6070, 6067, 6068, -1, 6071, 6069, 6067, -1, 6071, 4318, 4314, -1, 6071, 4314, 6069, -1, 6071, 6067, 6070, -1, 6072, 6068, 6073, -1, 6072, 6070, 6068, -1, 6074, 4318, 6071, -1, 6074, 6071, 6070, -1, 6074, 6070, 6072, -1, 6075, 6072, 6073, -1, 6076, 4318, 6074, -1, 6076, 4322, 4318, -1, 6076, 6074, 6072, -1, 6076, 6072, 6075, -1, 6077, 6075, 6073, -1, 6077, 6073, 6078, -1, 6079, 6075, 6077, -1, 6079, 4322, 6076, -1, 6079, 6076, 6075, -1, 6080, 6077, 6078, -1, 6081, 4324, 4322, -1, 6081, 6077, 6080, -1, 6081, 6079, 6077, -1, 6081, 4322, 6079, -1, 6082, 6078, 6083, -1, 6082, 6080, 6078, -1, 6084, 6081, 6080, -1, 6084, 4324, 6081, -1, 6084, 6080, 6082, -1, 6085, 6082, 6083, -1, 6086, 4324, 6084, -1, 6086, 6082, 6085, -1, 6086, 6084, 6082, -1, 6086, 4326, 4324, -1, 6087, 6085, 6083, -1, 6087, 6083, 6088, -1, 6089, 6085, 6087, -1, 6089, 6086, 6085, -1, 6089, 4326, 6086, -1, 6090, 6087, 6088, -1, 6091, 6087, 6090, -1, 6091, 6089, 6087, -1, 6091, 4326, 6089, -1, 6091, 4328, 4326, -1, 6092, 6090, 6088, -1, 6092, 6088, 6093, -1, 6094, 6090, 6092, -1, 6094, 6091, 6090, -1, 6094, 4328, 6091, -1, 6095, 6092, 6093, -1, 6096, 6094, 6092, -1, 6096, 4328, 6094, -1, 6096, 6092, 6095, -1, 6096, 4330, 4328, -1, 6097, 6095, 6093, -1, 6097, 6093, 6098, -1, 6099, 6095, 6097, -1, 6099, 4330, 6096, -1, 6099, 6096, 6095, -1, 6100, 6097, 6098, -1, 6101, 6099, 6097, -1, 6101, 6097, 6100, -1, 6101, 4330, 6099, -1, 6101, 4332, 4330, -1, 6102, 6098, 6103, -1, 6102, 6100, 6098, -1, 6104, 6101, 6100, -1, 6104, 4332, 6101, -1, 6104, 6100, 6102, -1, 6105, 6102, 6103, -1, 6106, 6102, 6105, -1, 6106, 6104, 6102, -1, 6106, 4332, 6104, -1, 6106, 4334, 4332, -1, 5925, 6103, 5928, -1, 5925, 6105, 6103, -1, 5924, 6105, 5925, -1, 5924, 6106, 6105, -1, 5924, 4334, 6106, -1, 5926, 5925, 5928, -1, 6107, 6108, 4406, -1, 6107, 4406, 4404, -1, 6109, 6108, 6107, -1, 6109, 6110, 6108, -1, 6109, 6111, 6110, -1, 6112, 6107, 4404, -1, 6113, 6112, 4404, -1, 6113, 4404, 4402, -1, 6114, 6107, 6112, -1, 6114, 6109, 6107, -1, 6114, 6111, 6109, -1, 6114, 6115, 6111, -1, 6116, 6112, 6113, -1, 6116, 6114, 6112, -1, 6116, 6115, 6114, -1, 6117, 6113, 4402, -1, 6118, 4402, 4400, -1, 6118, 6117, 4402, -1, 6119, 6120, 6115, -1, 6119, 6116, 6113, -1, 6119, 6115, 6116, -1, 6119, 6113, 6117, -1, 6121, 6120, 6119, -1, 6121, 6117, 6118, -1, 6121, 6119, 6117, -1, 6122, 6118, 4400, -1, 6123, 4400, 4398, -1, 6123, 6122, 4400, -1, 6124, 6120, 6121, -1, 6124, 6118, 6122, -1, 6124, 6125, 6120, -1, 6124, 6121, 6118, -1, 6126, 6124, 6122, -1, 6126, 6125, 6124, -1, 6126, 6122, 6123, -1, 6127, 6123, 4398, -1, 6128, 4398, 4396, -1, 6128, 6127, 4398, -1, 6129, 6126, 6123, -1, 6129, 6125, 6126, -1, 6129, 6123, 6127, -1, 6129, 6130, 6125, -1, 6131, 6130, 6129, -1, 6131, 6129, 6127, -1, 6131, 6127, 6128, -1, 6132, 6128, 4396, -1, 6133, 4396, 4394, -1, 6133, 6132, 4396, -1, 6134, 6128, 6132, -1, 6134, 6130, 6131, -1, 6134, 6131, 6128, -1, 6134, 6135, 6130, -1, 6136, 6134, 6132, -1, 6136, 6135, 6134, -1, 6136, 6132, 6133, -1, 6137, 6133, 4394, -1, 6138, 6136, 6133, -1, 6138, 6133, 6137, -1, 6138, 6135, 6136, -1, 6138, 6139, 6135, -1, 6140, 4394, 4392, -1, 6140, 6137, 4394, -1, 6141, 6138, 6137, -1, 6141, 6137, 6140, -1, 6141, 6139, 6138, -1, 6141, 6142, 6139, -1, 6143, 4392, 4390, -1, 6143, 6140, 4392, -1, 6144, 6142, 6141, -1, 6144, 6140, 6143, -1, 6144, 6141, 6140, -1, 6144, 6145, 6142, -1, 6146, 4390, 4388, -1, 6146, 6143, 4390, -1, 6147, 6144, 6143, -1, 6147, 6145, 6144, -1, 6147, 6143, 6146, -1, 6147, 6148, 6145, -1, 6149, 4388, 4386, -1, 6149, 6146, 4388, -1, 6150, 6147, 6146, -1, 6150, 6148, 6147, -1, 6150, 6146, 6149, -1, 6150, 6151, 6148, -1, 6152, 4386, 4384, -1, 6152, 6149, 4386, -1, 6153, 6150, 6149, -1, 6153, 6151, 6150, -1, 6153, 6149, 6152, -1, 6153, 6154, 6151, -1, 6155, 4384, 4382, -1, 6155, 6152, 4384, -1, 6156, 6153, 6152, -1, 6156, 6154, 6153, -1, 6156, 6152, 6155, -1, 6156, 6157, 6154, -1, 6158, 4382, 4378, -1, 6158, 6155, 4382, -1, 6159, 6156, 6155, -1, 6159, 6155, 6158, -1, 6159, 6157, 6156, -1, 6159, 6160, 6157, -1, 6161, 4378, 4375, -1, 6161, 6158, 4378, -1, 6162, 6159, 6158, -1, 6162, 6158, 6161, -1, 6162, 6160, 6159, -1, 6162, 6163, 6160, -1, 6164, 4375, 4371, -1, 6164, 6161, 4375, -1, 6165, 6161, 6164, -1, 6165, 6162, 6161, -1, 6165, 6163, 6162, -1, 6165, 6166, 6163, -1, 6167, 6164, 4371, -1, 6167, 4371, 4369, -1, 6167, 4369, 4368, -1, 6167, 4368, 5617, -1, 6168, 5617, 5560, -1, 6168, 6167, 5617, -1, 6168, 6165, 6164, -1, 6168, 6164, 6167, -1, 6168, 5560, 6169, -1, 6168, 6166, 6165, -1, 6168, 6169, 6166, -1, 767, 6169, 5560, -1, 6170, 5612, 4381, -1, 6170, 4381, 4379, -1, 6171, 5614, 5612, -1, 6171, 798, 5614, -1, 6171, 5612, 6170, -1, 6171, 6172, 798, -1, 6173, 6170, 4379, -1, 6173, 4379, 4376, -1, 6174, 6171, 6170, -1, 6174, 6172, 6171, -1, 6174, 6170, 6173, -1, 6174, 6175, 6172, -1, 6176, 4376, 4373, -1, 6176, 6173, 4376, -1, 6177, 6173, 6176, -1, 6177, 6178, 6175, -1, 6177, 6174, 6173, -1, 6177, 6175, 6174, -1, 6179, 4373, 4370, -1, 6179, 6176, 4373, -1, 6180, 6177, 6176, -1, 6180, 6178, 6177, -1, 6180, 6181, 6178, -1, 6180, 6176, 6179, -1, 6182, 4370, 4366, -1, 6182, 6179, 4370, -1, 6183, 6180, 6179, -1, 6183, 6179, 6182, -1, 6183, 6184, 6181, -1, 6183, 6181, 6180, -1, 6185, 4366, 4364, -1, 6185, 6182, 4366, -1, 6186, 6183, 6182, -1, 6186, 6187, 6184, -1, 6186, 6184, 6183, -1, 6186, 6182, 6185, -1, 6188, 4364, 4361, -1, 6188, 6185, 4364, -1, 6189, 6187, 6186, -1, 6189, 6186, 6185, -1, 6189, 6185, 6188, -1, 6189, 6190, 6187, -1, 6191, 4361, 4407, -1, 6191, 6188, 4361, -1, 6192, 6193, 6190, -1, 6192, 6189, 6188, -1, 6192, 6190, 6189, -1, 6192, 6188, 6191, -1, 6194, 4407, 4405, -1, 6194, 6191, 4407, -1, 6195, 6193, 6192, -1, 6195, 6191, 6194, -1, 6195, 6196, 6193, -1, 6195, 6192, 6191, -1, 6197, 4405, 4403, -1, 6197, 6194, 4405, -1, 6198, 6195, 6194, -1, 6198, 6196, 6195, -1, 6198, 6194, 6197, -1, 6198, 6199, 6196, -1, 6200, 4403, 4401, -1, 6200, 6197, 4403, -1, 6201, 6198, 6197, -1, 6201, 6199, 6198, -1, 6201, 6197, 6200, -1, 6201, 6202, 6199, -1, 6203, 4401, 4399, -1, 6203, 6200, 4401, -1, 6204, 6203, 4399, -1, 6205, 6202, 6201, -1, 6205, 6200, 6203, -1, 6205, 6201, 6200, -1, 6205, 6206, 6202, -1, 6207, 6205, 6203, -1, 6207, 6206, 6205, -1, 6207, 6208, 6206, -1, 6207, 6203, 6204, -1, 6209, 4399, 4397, -1, 6209, 6204, 4399, -1, 6210, 6209, 4397, -1, 6211, 6204, 6209, -1, 6211, 6208, 6207, -1, 6211, 6207, 6204, -1, 6212, 6208, 6211, -1, 6212, 6211, 6209, -1, 6212, 6209, 6210, -1, 6212, 6213, 6208, -1, 6214, 4397, 4395, -1, 6214, 6210, 4397, -1, 6215, 6214, 4395, -1, 6216, 6210, 6214, -1, 6216, 6212, 6210, -1, 6216, 6213, 6212, -1, 6217, 6216, 6214, -1, 6217, 6214, 6215, -1, 6217, 6213, 6216, -1, 6217, 6218, 6213, -1, 6219, 4395, 4393, -1, 6219, 6215, 4395, -1, 6220, 6219, 4393, -1, 6221, 6218, 6217, -1, 6221, 6217, 6215, -1, 6221, 6215, 6219, -1, 6222, 6221, 6219, -1, 6222, 6218, 6221, -1, 6222, 6223, 6218, -1, 6222, 6219, 6220, -1, 6224, 4393, 4391, -1, 6224, 6220, 4393, -1, 6225, 6224, 4391, -1, 6226, 6220, 6224, -1, 6226, 6223, 6222, -1, 6226, 6222, 6220, -1, 6227, 6224, 6225, -1, 6227, 6223, 6226, -1, 6227, 6228, 6223, -1, 6227, 6226, 6224, -1, 6229, 6225, 4391, -1, 6229, 4391, 4389, -1, 6230, 6228, 6227, -1, 6230, 6227, 6225, -1, 6230, 6225, 6229, -1, 6231, 6229, 4389, -1, 6232, 6228, 6230, -1, 6232, 6230, 6229, -1, 6232, 6229, 6231, -1, 6232, 6233, 6228, -1, 6234, 4389, 4387, -1, 6234, 6231, 4389, -1, 6235, 6232, 6231, -1, 6235, 6233, 6232, -1, 6235, 6231, 6234, -1, 6236, 6234, 4387, -1, 6237, 6235, 6234, -1, 6237, 6233, 6235, -1, 6237, 6234, 6236, -1, 6237, 6238, 6233, -1, 6239, 4387, 4385, -1, 6239, 6236, 4387, -1, 6240, 6237, 6236, -1, 6240, 6238, 6237, -1, 6240, 6236, 6239, -1, 6241, 6239, 4385, -1, 6242, 6238, 6240, -1, 6242, 6240, 6239, -1, 6242, 6239, 6241, -1, 6242, 6243, 6238, -1, 6244, 4385, 4383, -1, 6244, 6241, 4385, -1, 6245, 6242, 6241, -1, 6245, 6243, 6242, -1, 6245, 6241, 6244, -1, 6246, 6244, 4383, -1, 6247, 6243, 6245, -1, 6247, 6245, 6244, -1, 6247, 6244, 6246, -1, 6247, 6248, 6243, -1, 6249, 4383, 4380, -1, 6249, 6246, 4383, -1, 6250, 6247, 6246, -1, 6250, 6248, 6247, -1, 6250, 6246, 6249, -1, 6251, 6249, 4380, -1, 6252, 6248, 6250, -1, 6252, 6250, 6249, -1, 6252, 6249, 6251, -1, 6252, 6253, 6248, -1, 6254, 4380, 4377, -1, 6254, 6251, 4380, -1, 6255, 6252, 6251, -1, 6255, 6253, 6252, -1, 6255, 6251, 6254, -1, 6256, 6254, 4377, -1, 6257, 6255, 6254, -1, 6257, 6258, 6253, -1, 6257, 6253, 6255, -1, 6257, 6254, 6256, -1, 6259, 6256, 4377, -1, 6259, 4377, 4374, -1, 6260, 6256, 6259, -1, 6260, 6258, 6257, -1, 6260, 6257, 6256, -1, 6261, 6259, 4374, -1, 6262, 6263, 6258, -1, 6262, 6259, 6261, -1, 6262, 6260, 6259, -1, 6262, 6258, 6260, -1, 6264, 4374, 4372, -1, 6264, 6261, 4374, -1, 6265, 6262, 6261, -1, 6265, 6261, 6264, -1, 6265, 6263, 6262, -1, 6266, 6264, 4372, -1, 6267, 6264, 6266, -1, 6267, 6263, 6265, -1, 6267, 6268, 6263, -1, 6267, 6265, 6264, -1, 6269, 6266, 4372, -1, 6269, 4372, 4367, -1, 6270, 6267, 6266, -1, 6270, 6266, 6269, -1, 6270, 6268, 6267, -1, 6271, 6269, 4367, -1, 6272, 6270, 6269, -1, 6272, 6269, 6271, -1, 6272, 6268, 6270, -1, 6272, 6273, 6268, -1, 6274, 6271, 4367, -1, 6274, 4367, 4365, -1, 6275, 6271, 6274, -1, 6275, 6272, 6271, -1, 6275, 6273, 6272, -1, 6276, 6274, 4365, -1, 6277, 6275, 6274, -1, 6277, 6273, 6275, -1, 6277, 6274, 6276, -1, 6277, 6278, 6273, -1, 6279, 4365, 4363, -1, 6279, 6276, 4365, -1, 6280, 6278, 6277, -1, 6280, 6277, 6276, -1, 6280, 6276, 6279, -1, 6281, 6279, 4363, -1, 6282, 6280, 6279, -1, 6282, 6278, 6280, -1, 6282, 6279, 6281, -1, 6282, 6283, 6278, -1, 6284, 4363, 4362, -1, 6284, 6281, 4363, -1, 6285, 6282, 6281, -1, 6285, 6283, 6282, -1, 6285, 6281, 6284, -1, 6286, 6284, 4362, -1, 6287, 6285, 6284, -1, 6287, 6283, 6285, -1, 6287, 6284, 6286, -1, 6287, 6288, 6283, -1, 6289, 4362, 4406, -1, 6289, 6286, 4362, -1, 6290, 6288, 6287, -1, 6290, 6287, 6286, -1, 6290, 6286, 6289, -1, 6108, 6289, 4406, -1, 6110, 6290, 6289, -1, 6110, 6289, 6108, -1, 6110, 6288, 6290, -1, 6110, 6111, 6288, -1, 6291, 6292, 6293, -1, 5387, 6292, 6291, -1, 5219, 6292, 5387, -1, 6293, 6292, 6294, -1, 5219, 6295, 6292, -1, 6292, 6295, 6294, -1, 5211, 6295, 5219, -1, 6296, 6295, 6297, -1, 6294, 6295, 6296, -1, 6295, 6298, 6297, -1, 5341, 6298, 5212, -1, 6297, 6298, 6299, -1, 6298, 6300, 6299, -1, 5318, 6300, 5341, -1, 6299, 6300, 6301, -1, 5341, 6300, 6298, -1, 6302, 6303, 6304, -1, 5112, 6305, 5133, -1, 6304, 6303, 6306, -1, 5133, 6305, 6307, -1, 6306, 6303, 6308, -1, 6309, 6305, 5112, -1, 6307, 6305, 6309, -1, 5436, 6310, 5447, -1, 5447, 6310, 6311, -1, 6311, 6310, 6312, -1, 6312, 6310, 5436, -1, 6313, 6314, 5399, -1, 5399, 6314, 5410, -1, 5410, 6314, 6315, -1, 6315, 6314, 6313, -1, 5278, 6316, 6317, -1, 5258, 6316, 5278, -1, 6318, 6316, 5258, -1, 6317, 6316, 6318, -1, 5089, 6319, 5119, -1, 5119, 6319, 6320, -1, 6321, 6319, 5089, -1, 5150, 6322, 5170, -1, 6320, 6319, 6321, -1, 5170, 6322, 6323, -1, 6324, 6325, 6326, -1, 5444, 6325, 5456, -1, 6323, 6322, 6327, -1, 6326, 6325, 5444, -1, 6327, 6322, 6328, -1, 5456, 6325, 6324, -1, 6328, 6322, 6302, -1, 5211, 6329, 6295, -1, 6298, 6329, 5212, -1, 6302, 6322, 6303, -1, 5212, 6329, 5211, -1, 5133, 6307, 5150, -1, 6295, 6329, 6298, -1, 5150, 6307, 6322, -1, 6300, 6330, 6301, -1, 6301, 6330, 4853, -1, 6322, 6307, 6303, -1, 6331, 6307, 6332, -1, 6303, 6307, 6331, -1, 5320, 6333, 5318, -1, 5113, 6309, 5112, -1, 6300, 6333, 6330, -1, 6330, 6333, 4853, -1, 4853, 6333, 5320, -1, 6307, 6309, 6332, -1, 5318, 6333, 6300, -1, 6332, 6309, 6334, -1, 5470, 6335, 5113, -1, 5196, 5170, 6336, -1, 6336, 5170, 6337, -1, 5113, 6335, 6309, -1, 6337, 5170, 6323, -1, 6309, 6335, 6334, -1, 6334, 6335, 6338, -1, 5228, 6339, 5470, -1, 5222, 6339, 5228, -1, 6335, 6339, 6338, -1, 6340, 6339, 6341, -1, 6338, 6339, 6340, -1, 5470, 6339, 6335, -1, 5224, 6342, 5222, -1, 5222, 6342, 6339, -1, 6339, 6342, 6341, -1, 6341, 6342, 6343, -1, 5447, 6311, 5224, -1, 5224, 6311, 6342, -1, 6342, 6311, 6343, -1, 6343, 6311, 6344, -1, 5422, 6312, 5436, -1, 6345, 6312, 6346, -1, 6344, 6312, 6345, -1, 6311, 6312, 6344, -1, 5410, 6315, 5422, -1, 6312, 6315, 6346, -1, 5422, 6315, 6312, -1, 6346, 6315, 6347, -1, 5385, 6313, 5399, -1, 6315, 6313, 6347, -1, 6347, 6313, 6348, -1, 5385, 6349, 6313, -1, 5379, 6349, 5385, -1, 6350, 6349, 6351, -1, 6348, 6349, 6350, -1, 6313, 6349, 6348, -1, 5366, 6352, 5379, -1, 5351, 6352, 5366, -1, 6349, 6352, 6351, -1, 5379, 6352, 6349, -1, 6351, 6352, 6353, -1, 5312, 6354, 5351, -1, 6352, 6354, 6353, -1, 5351, 6354, 6352, -1, 6353, 6354, 6355, -1, 5278, 6317, 5312, -1, 5312, 6317, 6354, -1, 6354, 6317, 6355, -1, 6356, 6317, 6357, -1, 6355, 6317, 6356, -1, 5232, 6318, 5258, -1, 6357, 6318, 6358, -1, 6317, 6318, 6357, -1, 5200, 6359, 5232, -1, 6358, 6359, 6360, -1, 5232, 6359, 6318, -1, 6318, 6359, 6358, -1, 6359, 6361, 6360, -1, 5179, 6361, 5200, -1, 5161, 6361, 5179, -1, 6362, 6361, 6363, -1, 6360, 6361, 6362, -1, 5200, 6361, 6359, -1, 5140, 6364, 5161, -1, 5161, 6364, 6361, -1, 6361, 6364, 6363, -1, 6363, 6364, 6365, -1, 6364, 6320, 6365, -1, 5119, 6320, 5140, -1, 5140, 6320, 6364, -1, 6365, 6320, 6366, -1, 5091, 6321, 5089, -1, 6320, 6321, 6366, -1, 6367, 6321, 6368, -1, 6366, 6321, 6367, -1, 5456, 6324, 5091, -1, 6368, 6324, 6369, -1, 5091, 6324, 6321, -1, 6321, 6324, 6368, -1, 5429, 6326, 5444, -1, 6369, 6326, 6370, -1, 6324, 6326, 6369, -1, 5408, 6371, 5429, -1, 6372, 6371, 6373, -1, 6370, 6371, 6372, -1, 6326, 6371, 6370, -1, 5429, 6371, 6326, -1, 5394, 6291, 5408, -1, 5387, 6291, 5394, -1, 6373, 6291, 6293, -1, 5408, 6291, 6371, -1, 6371, 6291, 6373, -1, 6374, 6375, 6376, -1, 6377, 6378, 6379, -1, 6380, 6381, 6382, -1, 6382, 6381, 5524, -1, 5524, 6381, 6383, -1, 6383, 6381, 6380, -1, 6379, 6378, 6384, -1, 6385, 6386, 6377, -1, 6387, 6388, 6374, -1, 6389, 6388, 6387, -1, 6377, 6386, 6378, -1, 6374, 6390, 6375, -1, 6391, 6392, 6393, -1, 6388, 6390, 6374, -1, 6393, 6392, 6394, -1, 6389, 6395, 6388, -1, 6385, 6396, 6386, -1, 6397, 6396, 6385, -1, 6398, 6395, 6389, -1, 5513, 6396, 6397, -1, 5542, 6396, 5513, -1, 6388, 6399, 6390, -1, 6395, 6399, 6388, -1, 6384, 6400, 6391, -1, 6382, 6401, 6398, -1, 6398, 6401, 6395, -1, 6391, 6400, 6392, -1, 879, 876, 5203, -1, 6384, 6402, 6400, -1, 6375, 6403, 6376, -1, 6378, 6402, 6384, -1, 6376, 6403, 6404, -1, 6386, 6405, 6378, -1, 5520, 6406, 5522, -1, 6378, 6405, 6402, -1, 6395, 6406, 6399, -1, 6401, 6406, 6395, -1, 6392, 6407, 6394, -1, 6406, 6408, 5522, -1, 6401, 6408, 6406, -1, 6382, 6408, 6401, -1, 6394, 6407, 6409, -1, 5522, 6408, 6382, -1, 6396, 6410, 6386, -1, 6375, 6411, 6403, -1, 5506, 6410, 5542, -1, 5542, 6410, 6396, -1, 6386, 6410, 6405, -1, 6390, 6411, 6375, -1, 6399, 6412, 6390, -1, 6400, 6413, 6392, -1, 6390, 6412, 6411, -1, 6392, 6413, 6407, -1, 6402, 6414, 6400, -1, 6406, 6415, 6399, -1, 6400, 6414, 6413, -1, 6399, 6415, 6412, -1, 6403, 6416, 6404, -1, 6402, 6417, 6414, -1, 6405, 6417, 6402, -1, 6404, 6416, 6418, -1, 5520, 6419, 6406, -1, 6406, 6419, 6415, -1, 6411, 6420, 6403, -1, 5508, 6421, 5506, -1, 6403, 6420, 6416, -1, 5506, 6421, 6410, -1, 6410, 6421, 6405, -1, 6405, 6421, 6417, -1, 6411, 6422, 6420, -1, 6412, 6422, 6411, -1, 6415, 6423, 6412, -1, 6412, 6423, 6422, -1, 6416, 6424, 6418, -1, 6418, 6424, 6425, -1, 5518, 6426, 5520, -1, 5520, 6426, 6419, -1, 6419, 6426, 6415, -1, 6415, 6426, 6423, -1, 6420, 6427, 6416, -1, 6416, 6427, 6424, -1, 6422, 6428, 6420, -1, 6420, 6428, 6427, -1, 6423, 6429, 6422, -1, 6422, 6429, 6428, -1, 6424, 6430, 6425, -1, 6425, 6430, 6431, -1, 5517, 6432, 5518, -1, 5518, 6432, 6426, -1, 6426, 6432, 6423, -1, 6423, 6432, 6429, -1, 6424, 6433, 6430, -1, 6427, 6433, 6424, -1, 6427, 6434, 6433, -1, 6428, 6434, 6427, -1, 6429, 6435, 6428, -1, 6428, 6435, 6434, -1, 6430, 6436, 6431, -1, 6431, 6436, 6437, -1, 5485, 6438, 5517, -1, 5517, 6438, 6432, -1, 6432, 6438, 6429, -1, 6429, 6438, 6435, -1, 5538, 6439, 5539, -1, 6433, 6440, 6430, -1, 6430, 6440, 6436, -1, 6434, 6441, 6433, -1, 6433, 6441, 6440, -1, 6434, 6442, 6441, -1, 6435, 6442, 6434, -1, 6436, 6443, 6437, -1, 6444, 6445, 6446, -1, 6437, 6443, 6447, -1, 6446, 6445, 6448, -1, 6435, 6449, 6442, -1, 5487, 6449, 5485, -1, 5536, 6450, 5538, -1, 5485, 6449, 6438, -1, 6451, 6450, 5536, -1, 6438, 6449, 6435, -1, 6436, 6452, 6443, -1, 6444, 6453, 6445, -1, 6440, 6452, 6436, -1, 6454, 6453, 6444, -1, 6440, 6455, 6452, -1, 6441, 6455, 6440, -1, 6454, 6456, 6453, -1, 6457, 6456, 6454, -1, 5534, 6458, 5536, -1, 6441, 6459, 6455, -1, 6451, 6458, 6457, -1, 5536, 6458, 6451, -1, 6442, 6459, 6441, -1, 6457, 6458, 6456, -1, 6443, 6460, 6447, -1, 6445, 6461, 6448, -1, 6462, 6460, 5295, -1, 6448, 6461, 6463, -1, 6447, 6460, 6462, -1, 6461, 6464, 6463, -1, 5503, 6465, 5487, -1, 6463, 6464, 6466, -1, 5487, 6465, 6449, -1, 6442, 6465, 6459, -1, 6445, 6467, 6461, -1, 6449, 6465, 6442, -1, 6443, 6468, 6460, -1, 6460, 6468, 5295, -1, 6453, 6467, 6445, -1, 5295, 6468, 5300, -1, 6452, 6468, 6443, -1, 6467, 6469, 6461, -1, 6455, 6470, 6452, -1, 6461, 6469, 6464, -1, 6452, 6470, 6468, -1, 6468, 6470, 5300, -1, 5300, 6470, 5306, -1, 6456, 6471, 6453, -1, 6453, 6471, 6467, -1, 6455, 6472, 6470, -1, 6470, 6472, 5306, -1, 5306, 6472, 5311, -1, 6467, 6473, 6469, -1, 6459, 6472, 6455, -1, 6471, 6473, 6467, -1, 5320, 6474, 5483, -1, 5500, 6475, 5534, -1, 5483, 6474, 5503, -1, 5534, 6475, 6458, -1, 5503, 6474, 6465, -1, 6458, 6475, 6456, -1, 6459, 6474, 6472, -1, 6465, 6474, 6459, -1, 6456, 6475, 6471, -1, 6472, 6474, 5311, -1, 5311, 6474, 5320, -1, 5541, 6476, 5508, -1, 5508, 6476, 6421, -1, 6464, 6477, 6466, -1, 6478, 6476, 5541, -1, 6479, 6480, 5539, -1, 6471, 6481, 6473, -1, 6475, 6481, 6471, -1, 5539, 6480, 5541, -1, 6477, 6482, 6466, -1, 6466, 6482, 6483, -1, 6469, 6484, 6464, -1, 6464, 6484, 6477, -1, 6439, 6485, 5539, -1, 5500, 6486, 6475, -1, 6475, 6486, 6481, -1, 6450, 6487, 5538, -1, 6477, 6488, 6482, -1, 6484, 6488, 6477, -1, 6417, 6489, 6414, -1, 6469, 6490, 6484, -1, 6421, 6489, 6417, -1, 6473, 6490, 6469, -1, 6476, 6489, 6421, -1, 6490, 6491, 6484, -1, 6476, 6492, 6489, -1, 6484, 6491, 6488, -1, 6478, 6493, 6476, -1, 6473, 6494, 6490, -1, 6476, 6493, 6492, -1, 5502, 6494, 5500, -1, 6495, 6493, 6496, -1, 6481, 6494, 6473, -1, 6496, 6493, 6478, -1, 5500, 6494, 6486, -1, 6486, 6494, 6481, -1, 6496, 6497, 6495, -1, 6478, 6497, 6496, -1, 6482, 6498, 6483, -1, 5541, 6497, 6478, -1, 6480, 6497, 5541, -1, 6480, 6499, 6497, -1, 6494, 6500, 6490, -1, 6490, 6500, 6491, -1, 6488, 6501, 6482, -1, 6502, 6503, 6479, -1, 6480, 6503, 6499, -1, 6482, 6501, 6498, -1, 6479, 6503, 6480, -1, 6504, 6503, 6502, -1, 5539, 6505, 6479, -1, 6479, 6505, 6502, -1, 6483, 6506, 6507, -1, 6485, 6505, 5539, -1, 6498, 6506, 6483, -1, 6502, 6505, 6504, -1, 5502, 6508, 6494, -1, 6494, 6508, 6500, -1, 6485, 6509, 6505, -1, 6510, 6511, 6512, -1, 6488, 6513, 6501, -1, 6491, 6513, 6488, -1, 6512, 6511, 6439, -1, 6439, 6511, 6485, -1, 6498, 6514, 6506, -1, 6485, 6511, 6509, -1, 6512, 6515, 6510, -1, 6439, 6515, 6512, -1, 5538, 6515, 6439, -1, 6501, 6514, 6498, -1, 6487, 6515, 5538, -1, 5502, 6516, 6508, -1, 6508, 6516, 6500, -1, 6491, 6516, 6513, -1, 5533, 6516, 5502, -1, 6500, 6516, 6491, -1, 6487, 6517, 6515, -1, 6457, 6518, 6451, -1, 6506, 6519, 6507, -1, 6451, 6518, 6450, -1, 6450, 6518, 6487, -1, 6501, 6520, 6514, -1, 6487, 6518, 6517, -1, 6489, 6521, 6414, -1, 6513, 6520, 6501, -1, 6492, 6521, 6489, -1, 6414, 6521, 6413, -1, 6506, 6522, 6519, -1, 6492, 6523, 6521, -1, 6514, 6522, 6506, -1, 6513, 6524, 6520, -1, 6516, 6524, 6513, -1, 6493, 6525, 6492, -1, 6495, 6525, 6493, -1, 6492, 6525, 6523, -1, 6526, 6525, 6495, -1, 6519, 6527, 6507, -1, 6497, 6528, 6495, -1, 6499, 6528, 6497, -1, 6507, 6527, 6529, -1, 6495, 6528, 6526, -1, 6520, 6530, 6514, -1, 6514, 6530, 6522, -1, 6499, 6531, 6528, -1, 5533, 6532, 6516, -1, 6516, 6532, 6524, -1, 6462, 5295, 4669, -1, 6503, 6533, 6499, -1, 6504, 6533, 6503, -1, 6499, 6533, 6531, -1, 6522, 6534, 6519, -1, 6535, 6533, 6504, -1, 6519, 6534, 6527, -1, 6524, 6536, 6520, -1, 5531, 6536, 5533, -1, 6505, 6537, 6504, -1, 6532, 6536, 6524, -1, 6509, 6537, 6505, -1, 6520, 6536, 6530, -1, 6504, 6537, 6535, -1, 5533, 6536, 6532, -1, 6527, 6538, 6529, -1, 6509, 6539, 6537, -1, 6509, 6540, 6539, -1, 6541, 6540, 6510, -1, 6530, 6542, 6522, -1, 6510, 6540, 6511, -1, 6522, 6542, 6534, -1, 6511, 6540, 6509, -1, 6510, 6543, 6541, -1, 6534, 6544, 6527, -1, 6515, 6543, 6510, -1, 6527, 6544, 6538, -1, 5185, 6545, 4591, -1, 6517, 6543, 6515, -1, 4591, 6545, 6546, -1, 6517, 6547, 6543, -1, 6536, 6548, 6530, -1, 6530, 6548, 6542, -1, 5192, 6549, 5185, -1, 5185, 6549, 6545, -1, 6517, 6550, 6547, -1, 6457, 6550, 6518, -1, 6538, 6551, 6529, -1, 6518, 6550, 6517, -1, 6454, 6550, 6457, -1, 6529, 6551, 6552, -1, 6407, 6553, 6409, -1, 6534, 6554, 6544, -1, 6413, 6553, 6407, -1, 6542, 6554, 6534, -1, 6545, 6555, 6546, -1, 6409, 6553, 6556, -1, 6556, 6553, 6557, -1, 6557, 6553, 6526, -1, 5192, 6558, 6549, -1, 6521, 6553, 6413, -1, 6523, 6553, 6521, -1, 6525, 6553, 6523, -1, 5531, 6559, 6536, -1, 6526, 6553, 6525, -1, 6536, 6559, 6548, -1, 5199, 6558, 5192, -1, 6556, 6560, 6561, -1, 6557, 6560, 6556, -1, 6526, 6560, 6557, -1, 6544, 6562, 6538, -1, 6545, 6563, 6555, -1, 6561, 6560, 6564, -1, 6528, 6560, 6526, -1, 6549, 6563, 6545, -1, 6564, 6560, 6535, -1, 6538, 6562, 6551, -1, 6531, 6560, 6528, -1, 6533, 6560, 6531, -1, 6535, 6560, 6533, -1, 6537, 6565, 6535, -1, 5529, 6566, 5531, -1, 876, 6567, 5203, -1, 6568, 6565, 6541, -1, 5531, 6566, 6559, -1, 6540, 6565, 6539, -1, 6541, 6565, 6540, -1, 6542, 6566, 6554, -1, 6561, 6565, 6569, -1, 6548, 6566, 6542, -1, 6539, 6565, 6537, -1, 6559, 6566, 6548, -1, 5199, 6567, 6558, -1, 6564, 6565, 6561, -1, 5203, 6567, 5199, -1, 6569, 6565, 6568, -1, 6535, 6565, 6564, -1, 6541, 6570, 6568, -1, 6551, 6571, 6552, -1, 6454, 6570, 6550, -1, 6446, 6570, 6444, -1, 6546, 6572, 6573, -1, 6569, 6570, 6446, -1, 6555, 6572, 6546, -1, 6550, 6570, 6547, -1, 6543, 6570, 6541, -1, 6554, 6574, 6544, -1, 6547, 6570, 6543, -1, 6568, 6570, 6569, -1, 6544, 6574, 6562, -1, 6444, 6570, 6454, -1, 6549, 6575, 6563, -1, 6558, 6575, 6549, -1, 6567, 6576, 882, -1, 876, 6576, 6567, -1, 6562, 6577, 6551, -1, 882, 6576, 880, -1, 880, 6576, 876, -1, 6551, 6577, 6571, -1, 6555, 6578, 6572, -1, 6563, 6578, 6555, -1, 6566, 6579, 6554, -1, 6554, 6579, 6574, -1, 6567, 6580, 6558, -1, 6571, 6581, 6552, -1, 882, 6580, 6567, -1, 6552, 6581, 6582, -1, 5479, 6580, 882, -1, 6558, 6580, 6575, -1, 6572, 6583, 6573, -1, 6574, 6584, 6562, -1, 6562, 6584, 6577, -1, 6563, 6585, 6578, -1, 5529, 6586, 6566, -1, 6566, 6586, 6579, -1, 6575, 6585, 6563, -1, 6572, 6587, 6583, -1, 6577, 6588, 6571, -1, 6571, 6588, 6581, -1, 6578, 6587, 6572, -1, 5527, 6589, 5529, -1, 6574, 6589, 6584, -1, 6580, 6590, 6575, -1, 5529, 6589, 6586, -1, 6579, 6589, 6574, -1, 6575, 6590, 6585, -1, 6586, 6589, 6579, -1, 6578, 6591, 6587, -1, 6581, 6592, 6582, -1, 6585, 6591, 6578, -1, 6584, 6593, 6577, -1, 6577, 6593, 6588, -1, 6583, 6594, 6573, -1, 6573, 6594, 6595, -1, 6588, 6596, 6581, -1, 5479, 6597, 6580, -1, 6581, 6596, 6592, -1, 6580, 6597, 6590, -1, 6585, 6598, 6591, -1, 6590, 6598, 6585, -1, 6584, 6599, 6593, -1, 5479, 6598, 6597, -1, 6589, 6599, 6584, -1, 5477, 6598, 5479, -1, 6597, 6598, 6590, -1, 6587, 6600, 6583, -1, 6592, 6601, 6582, -1, 6582, 6601, 6602, -1, 6583, 6600, 6594, -1, 6588, 6603, 6596, -1, 6594, 6604, 6595, -1, 6593, 6603, 6588, -1, 5527, 6605, 6589, -1, 6589, 6605, 6599, -1, 6596, 6606, 6592, -1, 6587, 6607, 6600, -1, 6591, 6607, 6587, -1, 6594, 6608, 6604, -1, 6600, 6608, 6594, -1, 6592, 6606, 6601, -1, 6599, 6609, 6593, -1, 6593, 6609, 6603, -1, 5527, 6609, 6605, -1, 6605, 6609, 6599, -1, 5526, 6609, 5527, -1, 6598, 6610, 6591, -1, 6591, 6610, 6607, -1, 6601, 6611, 6602, -1, 6600, 6612, 6608, -1, 6607, 6612, 6600, -1, 6596, 6613, 6606, -1, 6604, 6614, 6595, -1, 6603, 6613, 6596, -1, 6595, 6614, 6615, -1, 6601, 6616, 6611, -1, 5477, 6617, 6598, -1, 6606, 6616, 6601, -1, 6598, 6617, 6610, -1, 6607, 6618, 6612, -1, 6603, 6619, 6613, -1, 6617, 6618, 6610, -1, 5478, 6618, 5477, -1, 6609, 6619, 6603, -1, 5477, 6618, 6617, -1, 6610, 6618, 6607, -1, 6611, 6620, 6602, -1, 6614, 6621, 6615, -1, 6602, 6620, 6622, -1, 6613, 6623, 6606, -1, 6608, 6624, 6604, -1, 6606, 6623, 6616, -1, 6604, 6624, 6614, -1, 6609, 6625, 6619, -1, 5526, 6625, 6609, -1, 6624, 6626, 6614, -1, 6614, 6626, 6621, -1, 6616, 6627, 6611, -1, 6611, 6627, 6620, -1, 5498, 6628, 5526, -1, 6612, 6629, 6608, -1, 5526, 6628, 6625, -1, 6608, 6629, 6624, -1, 6613, 6628, 6623, -1, 6629, 6630, 6624, -1, 6619, 6628, 6613, -1, 6625, 6628, 6619, -1, 6624, 6630, 6626, -1, 6620, 6631, 6622, -1, 6618, 6632, 6612, -1, 6612, 6632, 6629, -1, 6616, 6633, 6627, -1, 6623, 6633, 6616, -1, 6621, 6634, 6615, -1, 6615, 6634, 6635, -1, 6627, 6636, 6620, -1, 6629, 6637, 6630, -1, 6620, 6636, 6631, -1, 6632, 6637, 6629, -1, 5472, 6637, 5478, -1, 6628, 6638, 6623, -1, 6623, 6638, 6633, -1, 6634, 6639, 6635, -1, 6618, 6640, 6632, -1, 5478, 6640, 6618, -1, 6631, 6641, 6622, -1, 6632, 6640, 6637, -1, 6637, 6640, 5478, -1, 6622, 6641, 6642, -1, 6626, 6643, 6621, -1, 6621, 6643, 6634, -1, 6633, 6644, 6627, -1, 6627, 6644, 6636, -1, 6643, 6645, 6634, -1, 5498, 6646, 6628, -1, 6628, 6646, 6638, -1, 6634, 6645, 6639, -1, 6636, 6647, 6631, -1, 6626, 6648, 6643, -1, 6631, 6647, 6641, -1, 6630, 6648, 6626, -1, 5495, 6649, 5498, -1, 6643, 6650, 6645, -1, 5498, 6649, 6646, -1, 6638, 6649, 6633, -1, 6633, 6649, 6644, -1, 6648, 6650, 6643, -1, 6646, 6649, 6638, -1, 6630, 6651, 6648, -1, 6641, 6652, 6642, -1, 6637, 6651, 6630, -1, 6644, 6653, 6636, -1, 6636, 6653, 6647, -1, 6635, 6654, 6655, -1, 6639, 6654, 6635, -1, 6651, 6656, 6648, -1, 6647, 6657, 6641, -1, 6648, 6656, 6650, -1, 6641, 6657, 6652, -1, 5474, 6656, 5472, -1, 6651, 6658, 6656, -1, 6644, 6659, 6653, -1, 6637, 6658, 6651, -1, 6656, 6658, 5472, -1, 6649, 6659, 6644, -1, 5472, 6658, 6637, -1, 6645, 6660, 6639, -1, 6639, 6660, 6654, -1, 6652, 6661, 6642, -1, 6642, 6661, 6662, -1, 6650, 6663, 6645, -1, 6653, 6664, 6647, -1, 6647, 6664, 6657, -1, 6645, 6663, 6660, -1, 5495, 6665, 6649, -1, 6656, 6666, 6650, -1, 6650, 6666, 6663, -1, 6649, 6665, 6659, -1, 6654, 6667, 6655, -1, 6657, 6668, 6652, -1, 6652, 6668, 6661, -1, 6655, 6667, 6669, -1, 5525, 6670, 5495, -1, 5495, 6670, 6665, -1, 6656, 6671, 6666, -1, 6659, 6670, 6653, -1, 5474, 6671, 6656, -1, 6653, 6670, 6664, -1, 6665, 6670, 6659, -1, 6654, 6672, 6667, -1, 6661, 6673, 6662, -1, 6660, 6672, 6654, -1, 6663, 6674, 6660, -1, 6664, 6675, 6657, -1, 6657, 6675, 6668, -1, 6660, 6674, 6672, -1, 6661, 6676, 6673, -1, 6666, 6677, 6663, -1, 6668, 6676, 6661, -1, 6670, 6678, 6664, -1, 6663, 6677, 6674, -1, 6667, 6679, 6669, -1, 6664, 6678, 6675, -1, 6669, 6679, 6680, -1, 6662, 6681, 6682, -1, 6673, 6681, 6662, -1, 5548, 6683, 5474, -1, 6666, 6683, 6677, -1, 6671, 6683, 6666, -1, 6675, 6684, 6668, -1, 5474, 6683, 6671, -1, 6668, 6684, 6676, -1, 6670, 6685, 6678, -1, 6672, 6686, 6667, -1, 6667, 6686, 6679, -1, 5525, 6685, 6670, -1, 6673, 6687, 6681, -1, 6674, 6688, 6672, -1, 6672, 6688, 6686, -1, 6676, 6687, 6673, -1, 6678, 6689, 6675, -1, 6675, 6689, 6684, -1, 6685, 6689, 6678, -1, 5490, 6689, 5525, -1, 6677, 6690, 6674, -1, 5525, 6689, 6685, -1, 6674, 6690, 6688, -1, 6681, 6691, 6682, -1, 6679, 6692, 6680, -1, 6680, 6692, 6693, -1, 6676, 6694, 6687, -1, 6684, 6694, 6676, -1, 5546, 6695, 5548, -1, 6683, 6695, 6677, -1, 5548, 6695, 6683, -1, 6677, 6695, 6690, -1, 6681, 6696, 6691, -1, 6687, 6696, 6681, -1, 6679, 6697, 6692, -1, 6686, 6697, 6679, -1, 6684, 6698, 6694, -1, 6689, 6698, 6684, -1, 6688, 6699, 6686, -1, 6686, 6699, 6697, -1, 6687, 6700, 6696, -1, 6694, 6700, 6687, -1, 6691, 6701, 6682, -1, 6690, 6702, 6688, -1, 6688, 6702, 6699, -1, 6682, 6701, 6703, -1, 6693, 6704, 6705, -1, 5490, 6706, 6689, -1, 6689, 6706, 6698, -1, 6692, 6704, 6693, -1, 5492, 6707, 5490, -1, 5490, 6707, 6706, -1, 5544, 6708, 5546, -1, 6694, 6707, 6700, -1, 5546, 6708, 6695, -1, 6698, 6707, 6694, -1, 6695, 6708, 6690, -1, 6706, 6707, 6698, -1, 6690, 6708, 6702, -1, 6691, 6709, 6701, -1, 6697, 6710, 6692, -1, 6696, 6709, 6691, -1, 6692, 6710, 6704, -1, 6701, 6711, 6703, -1, 6697, 6712, 6710, -1, 6699, 6712, 6697, -1, 6700, 6713, 6696, -1, 6696, 6713, 6709, -1, 6702, 6714, 6699, -1, 6699, 6714, 6712, -1, 6709, 6715, 6701, -1, 6701, 6715, 6711, -1, 6705, 6716, 6717, -1, 6704, 6716, 6705, -1, 6700, 6718, 6713, -1, 6707, 6718, 6700, -1, 5543, 6719, 5544, -1, 5544, 6719, 6708, -1, 6708, 6719, 6702, -1, 6702, 6719, 6714, -1, 6713, 6720, 6709, -1, 6710, 6721, 6704, -1, 6709, 6720, 6715, -1, 6704, 6721, 6716, -1, 6711, 6722, 6703, -1, 6703, 6722, 6723, -1, 6710, 6724, 6721, -1, 5492, 6725, 6707, -1, 6712, 6724, 6710, -1, 6707, 6725, 6718, -1, 6712, 6726, 6724, -1, 5524, 6383, 5492, -1, 5492, 6383, 6725, -1, 6714, 6726, 6712, -1, 6718, 6383, 6713, -1, 6713, 6383, 6720, -1, 6725, 6383, 6718, -1, 6717, 6727, 6728, -1, 6722, 6387, 6723, -1, 6716, 6727, 6717, -1, 6711, 6729, 6722, -1, 6714, 6730, 6726, -1, 5511, 6730, 5543, -1, 6715, 6729, 6711, -1, 5543, 6730, 6719, -1, 6719, 6730, 6714, -1, 6716, 6379, 6727, -1, 6729, 6389, 6722, -1, 6722, 6389, 6387, -1, 6721, 6379, 6716, -1, 6720, 6731, 6715, -1, 6724, 6377, 6721, -1, 6715, 6731, 6729, -1, 6721, 6377, 6379, -1, 6724, 6385, 6377, -1, 6729, 6398, 6389, -1, 6731, 6398, 6729, -1, 6726, 6385, 6724, -1, 6383, 6380, 6720, -1, 6727, 6391, 6728, -1, 6720, 6380, 6731, -1, 6728, 6391, 6393, -1, 6387, 6374, 6723, -1, 6723, 6374, 6376, -1, 6730, 6397, 6726, -1, 5511, 6397, 6730, -1, 6726, 6397, 6385, -1, 5522, 6382, 5524, -1, 5513, 6397, 5511, -1, 6727, 6384, 6391, -1, 6379, 6384, 6727, -1, 6731, 6382, 6398, -1, 6380, 6382, 6731, -1, 6732, 6733, 6734, -1, 6735, 6366, 6736, -1, 6735, 6736, 6737, -1, 6738, 6733, 6732, -1, 6739, 6740, 6741, -1, 6738, 6742, 6733, -1, 6743, 6744, 6742, -1, 6739, 6745, 6740, -1, 6746, 6737, 6747, -1, 6746, 6747, 6748, -1, 6746, 6366, 6735, -1, 6743, 6742, 6738, -1, 6746, 6735, 6737, -1, 6749, 4579, 4581, -1, 6749, 6750, 4579, -1, 6746, 6365, 6366, -1, 6749, 4581, 4857, -1, 6751, 6741, 4577, -1, 6752, 6331, 6753, -1, 6754, 6748, 6745, -1, 6752, 6744, 6743, -1, 6752, 6303, 6331, -1, 6752, 6753, 6744, -1, 6754, 6745, 6739, -1, 6755, 6739, 6741, -1, 6756, 6749, 4857, -1, 6755, 6741, 6751, -1, 6756, 4857, 4862, -1, 6756, 6732, 6750, -1, 6756, 6750, 6749, -1, 6757, 6746, 6748, -1, 6757, 6748, 6754, -1, 6758, 6738, 6732, -1, 6758, 6732, 6756, -1, 6758, 4862, 4866, -1, 6759, 4577, 4580, -1, 6759, 6751, 4577, -1, 6758, 6756, 4862, -1, 6758, 4866, 6760, -1, 6761, 6743, 6738, -1, 6762, 6754, 6739, -1, 6761, 6758, 6760, -1, 6762, 6739, 6755, -1, 6761, 6738, 6758, -1, 6761, 6760, 6763, -1, 6764, 6752, 6743, -1, 6764, 6303, 6752, -1, 6765, 6365, 6746, -1, 6764, 6743, 6761, -1, 6765, 6746, 6757, -1, 6764, 6761, 6763, -1, 6764, 6763, 6308, -1, 6764, 6308, 6303, -1, 6766, 6755, 6751, -1, 6766, 6751, 6759, -1, 6767, 6757, 6754, -1, 6767, 6754, 6762, -1, 6767, 6365, 6765, -1, 6767, 6765, 6757, -1, 6767, 6363, 6365, -1, 6768, 6759, 4580, -1, 6769, 6762, 6755, -1, 6769, 6755, 6766, -1, 6770, 6766, 6759, -1, 6770, 6759, 6768, -1, 6771, 6762, 6769, -1, 6771, 6767, 6762, -1, 6772, 4580, 4582, -1, 6772, 6768, 4580, -1, 6773, 6769, 6766, -1, 6773, 6766, 6770, -1, 6774, 6363, 6767, -1, 6774, 6767, 6771, -1, 6775, 6770, 6768, -1, 6775, 6768, 6772, -1, 6776, 6769, 6773, -1, 6776, 6362, 6363, -1, 6776, 6771, 6769, -1, 6776, 6363, 6774, -1, 6776, 6774, 6771, -1, 6777, 6772, 4582, -1, 6778, 6773, 6770, -1, 6778, 6770, 6775, -1, 6779, 6772, 6777, -1, 6779, 6775, 6772, -1, 6780, 6773, 6778, -1, 6780, 6776, 6773, -1, 6781, 4582, 4583, -1, 6781, 6777, 4582, -1, 6782, 6775, 6779, -1, 6782, 6778, 6775, -1, 6783, 6776, 6780, -1, 6783, 6362, 6776, -1, 6784, 6779, 6777, -1, 6784, 6777, 6781, -1, 6785, 6783, 6780, -1, 6785, 6778, 6782, -1, 6785, 6362, 6783, -1, 6785, 6360, 6362, -1, 6785, 6780, 6778, -1, 6786, 6781, 4583, -1, 6787, 6782, 6779, -1, 6787, 6779, 6784, -1, 6788, 6784, 6781, -1, 6788, 6781, 6786, -1, 6789, 6782, 6787, -1, 6789, 6785, 6782, -1, 6790, 4583, 4546, -1, 6790, 6786, 4583, -1, 6791, 6785, 6789, -1, 6791, 6360, 6785, -1, 6792, 6787, 6784, -1, 6792, 6784, 6788, -1, 6793, 6788, 6786, -1, 6793, 6786, 6790, -1, 6794, 6789, 6787, -1, 6794, 6787, 6792, -1, 6794, 6791, 6789, -1, 6794, 6360, 6791, -1, 6794, 6358, 6360, -1, 6795, 6790, 4546, -1, 6796, 6792, 6788, -1, 6796, 6788, 6793, -1, 6797, 6793, 6790, -1, 6797, 6790, 6795, -1, 6798, 6794, 6792, -1, 6798, 6792, 6796, -1, 6799, 4546, 4547, -1, 6799, 6795, 4546, -1, 6800, 6358, 6794, -1, 6800, 6794, 6798, -1, 6801, 6796, 6793, -1, 6801, 6793, 6797, -1, 6802, 6797, 6795, -1, 6802, 6795, 6799, -1, 6803, 6798, 6796, -1, 6803, 6358, 6800, -1, 6803, 6796, 6801, -1, 6803, 6357, 6358, -1, 6803, 6800, 6798, -1, 6804, 6799, 4547, -1, 6805, 6801, 6797, -1, 6805, 6797, 6802, -1, 6806, 6802, 6799, -1, 6806, 6799, 6804, -1, 6807, 6803, 6801, -1, 6807, 6801, 6805, -1, 6808, 4547, 4548, -1, 6808, 6804, 4547, -1, 6809, 6803, 6807, -1, 6809, 6357, 6803, -1, 6810, 6805, 6802, -1, 6810, 6802, 6806, -1, 6811, 6804, 6808, -1, 6811, 6806, 6804, -1, 6812, 6356, 6357, -1, 6812, 6805, 6810, -1, 6812, 6807, 6805, -1, 6812, 6357, 6809, -1, 6812, 6809, 6807, -1, 6813, 6808, 4548, -1, 6814, 6806, 6811, -1, 6814, 6810, 6806, -1, 6815, 6808, 6813, -1, 6815, 6811, 6808, -1, 6816, 6810, 6814, -1, 6816, 6812, 6810, -1, 6817, 6813, 4548, -1, 6817, 4548, 4549, -1, 6818, 6356, 6812, -1, 6818, 6812, 6816, -1, 4857, 4581, 4584, -1, 6819, 6814, 6811, -1, 6819, 6811, 6815, -1, 6820, 6815, 6813, -1, 6820, 6813, 6817, -1, 6821, 6356, 6818, -1, 6821, 6816, 6814, -1, 6821, 6814, 6819, -1, 6821, 6818, 6816, -1, 6821, 6355, 6356, -1, 6822, 6819, 6815, -1, 6822, 6815, 6820, -1, 6823, 6817, 4549, -1, 6824, 6819, 6822, -1, 6824, 6821, 6819, -1, 4781, 6760, 4866, -1, 6825, 6820, 6817, -1, 4780, 6760, 4781, -1, 6826, 4753, 4551, -1, 6825, 6817, 6823, -1, 6827, 4549, 4550, -1, 6827, 6823, 4549, -1, 6826, 4551, 4552, -1, 6828, 4754, 4753, -1, 6829, 6355, 6821, -1, 6829, 6821, 6824, -1, 6830, 6822, 6820, -1, 6830, 6820, 6825, -1, 6828, 4753, 6826, -1, 6831, 4765, 4754, -1, 6831, 4754, 6828, -1, 6832, 6823, 6827, -1, 6833, 4770, 4765, -1, 6832, 6825, 6823, -1, 6834, 6824, 6822, -1, 6833, 4765, 6831, -1, 6834, 6355, 6829, -1, 6834, 6822, 6830, -1, 6834, 6829, 6824, -1, 6835, 6826, 4552, -1, 6835, 4552, 4553, -1, 6834, 6353, 6355, -1, 6836, 6830, 6825, -1, 6836, 6825, 6832, -1, 6837, 4853, 4770, -1, 6837, 6301, 4853, -1, 6837, 4770, 6833, -1, 6838, 6828, 6826, -1, 6839, 6827, 4550, -1, 6838, 6826, 6835, -1, 6840, 6834, 6830, -1, 6840, 6830, 6836, -1, 6841, 6828, 6838, -1, 6842, 4550, 4554, -1, 6842, 6839, 4550, -1, 6841, 6831, 6828, -1, 6843, 6831, 6841, -1, 6844, 6832, 6827, -1, 6843, 6833, 6831, -1, 6844, 6827, 6839, -1, 6845, 6353, 6834, -1, 6846, 6835, 4553, -1, 6845, 6834, 6840, -1, 6846, 4553, 4555, -1, 6847, 6839, 6842, -1, 6848, 6301, 6837, -1, 6847, 6844, 6839, -1, 6848, 6299, 6301, -1, 6848, 6833, 6843, -1, 6849, 6836, 6832, -1, 6848, 6837, 6833, -1, 6849, 6832, 6844, -1, 6850, 6849, 6844, -1, 6851, 6838, 6835, -1, 6851, 6835, 6846, -1, 6850, 6844, 6847, -1, 6852, 6841, 6838, -1, 6852, 6838, 6851, -1, 6853, 6840, 6836, -1, 6853, 6353, 6845, -1, 6853, 6351, 6353, -1, 6853, 6836, 6849, -1, 6853, 6845, 6840, -1, 6854, 6841, 6852, -1, 6854, 6843, 6841, -1, 6855, 4555, 4558, -1, 6856, 6842, 4554, -1, 6857, 6849, 6850, -1, 6855, 6846, 4555, -1, 6858, 6848, 6843, -1, 6857, 6853, 6849, -1, 6858, 6299, 6848, -1, 6858, 6297, 6299, -1, 6859, 4554, 4556, -1, 6858, 6843, 6854, -1, 6859, 6856, 4554, -1, 6860, 6847, 6842, -1, 6861, 6846, 6855, -1, 6861, 6851, 6846, -1, 6860, 6842, 6856, -1, 6862, 6351, 6853, -1, 6863, 6851, 6861, -1, 6863, 6852, 6851, -1, 6862, 6853, 6857, -1, 6864, 6860, 6856, -1, 6865, 6852, 6863, -1, 6864, 6856, 6859, -1, 6865, 6854, 6852, -1, 6866, 6855, 4558, -1, 6867, 6850, 6847, -1, 6867, 6847, 6860, -1, 6866, 4558, 4561, -1, 6868, 6867, 6860, -1, 6869, 6297, 6858, -1, 6869, 6854, 6865, -1, 6868, 6860, 6864, -1, 6869, 6296, 6297, -1, 6870, 6850, 6867, -1, 6869, 6858, 6854, -1, 6870, 6857, 6850, -1, 6871, 6855, 6866, -1, 6871, 6861, 6855, -1, 6872, 6859, 4556, -1, 6873, 6861, 6871, -1, 6874, 6351, 6862, -1, 6874, 6862, 6857, -1, 6873, 6863, 6861, -1, 6874, 6350, 6351, -1, 6874, 6857, 6870, -1, 6875, 6865, 6863, -1, 6876, 6867, 6868, -1, 6875, 6863, 6873, -1, 6876, 6870, 6867, -1, 6877, 6864, 6859, -1, 6878, 4561, 4562, -1, 6878, 6866, 4561, -1, 6877, 6859, 6872, -1, 6879, 6296, 6869, -1, 6879, 6865, 6875, -1, 6880, 6874, 6870, -1, 6879, 6294, 6296, -1, 6880, 6350, 6874, -1, 6880, 6870, 6876, -1, 6879, 6869, 6865, -1, 6881, 6864, 6877, -1, 6882, 6866, 6878, -1, 6882, 6871, 6866, -1, 6881, 6868, 6864, -1, 6883, 6876, 6868, -1, 6883, 6868, 6881, -1, 6884, 6871, 6882, -1, 6884, 6873, 6871, -1, 6885, 6875, 6873, -1, 6885, 6873, 6884, -1, 6886, 4556, 4557, -1, 6886, 6872, 4556, -1, 6887, 6878, 4562, -1, 6888, 6880, 6876, -1, 6888, 6350, 6880, -1, 6888, 6876, 6883, -1, 6887, 4562, 4564, -1, 6888, 6883, 6348, -1, 6888, 6348, 6350, -1, 6889, 6872, 6886, -1, 6889, 6877, 6872, -1, 6890, 6875, 6885, -1, 6890, 6879, 6875, -1, 6890, 6293, 6294, -1, 6890, 6294, 6879, -1, 6891, 6882, 6878, -1, 6892, 6881, 6877, -1, 6891, 6878, 6887, -1, 6892, 6877, 6889, -1, 6893, 6881, 6892, -1, 6893, 6883, 6881, -1, 6893, 6348, 6883, -1, 6894, 6884, 6882, -1, 6894, 6882, 6891, -1, 6895, 4557, 4559, -1, 6895, 6886, 4557, -1, 6896, 6885, 6884, -1, 6896, 6884, 6894, -1, 6897, 6348, 6893, -1, 6897, 6893, 6347, -1, 6898, 6887, 4564, -1, 6897, 6347, 6348, -1, 6899, 6886, 6895, -1, 6898, 4564, 4566, -1, 6899, 6889, 6886, -1, 6900, 6890, 6885, -1, 6900, 6293, 6890, -1, 6900, 6373, 6293, -1, 6901, 6889, 6899, -1, 6901, 6892, 6889, -1, 6900, 6885, 6896, -1, 6902, 6898, 4566, -1, 6903, 6893, 6892, -1, 6904, 6887, 6898, -1, 6903, 6892, 6901, -1, 6903, 6347, 6893, -1, 6904, 6891, 6887, -1, 6905, 6895, 4559, -1, 6905, 4559, 4560, -1, 6906, 6904, 6898, -1, 6906, 6898, 6902, -1, 6907, 6347, 6903, -1, 6907, 6903, 6346, -1, 6908, 6894, 6891, -1, 6907, 6346, 6347, -1, 6908, 6891, 6904, -1, 6909, 6899, 6895, -1, 6909, 6895, 6905, -1, 6910, 6904, 6906, -1, 6910, 6908, 6904, -1, 6911, 6901, 6899, -1, 6912, 6896, 6894, -1, 6911, 6899, 6909, -1, 6912, 6894, 6908, -1, 6913, 4566, 4567, -1, 6914, 6903, 6901, -1, 6914, 6346, 6903, -1, 6913, 6902, 4566, -1, 6914, 6901, 6911, -1, 6915, 4560, 4563, -1, 6916, 6372, 6373, -1, 6916, 6373, 6900, -1, 6915, 6905, 4560, -1, 6916, 6900, 6896, -1, 6916, 6896, 6912, -1, 6917, 6908, 6910, -1, 6918, 6346, 6914, -1, 6918, 6345, 6346, -1, 6918, 6914, 6345, -1, 6917, 6912, 6908, -1, 6919, 6909, 6905, -1, 6920, 6913, 4567, -1, 6919, 6905, 6915, -1, 6921, 6909, 6919, -1, 6921, 6911, 6909, -1, 6922, 6906, 6902, -1, 6922, 6902, 6913, -1, 6923, 6912, 6917, -1, 6923, 6370, 6372, -1, 6924, 6914, 6911, -1, 6923, 6372, 6916, -1, 6923, 6916, 6912, -1, 6924, 6911, 6921, -1, 6925, 6922, 6913, -1, 6924, 6345, 6914, -1, 6925, 6913, 6920, -1, 6926, 4563, 4565, -1, 6926, 6915, 4563, -1, 6927, 6906, 6922, -1, 6928, 6344, 6345, -1, 6928, 6924, 6344, -1, 6928, 6345, 6924, -1, 6927, 6910, 6906, -1, 6929, 6922, 6925, -1, 6930, 6919, 6915, -1, 6929, 6927, 6922, -1, 6930, 6915, 6926, -1, 6931, 6910, 6927, -1, 6931, 6917, 6910, -1, 6932, 6921, 6919, -1, 6933, 6920, 4567, -1, 6932, 6919, 6930, -1, 6933, 4567, 4569, -1, 6934, 6921, 6932, -1, 6935, 6923, 6917, -1, 6934, 6924, 6921, -1, 6935, 6370, 6923, -1, 6934, 6344, 6924, -1, 6935, 6917, 6931, -1, 6936, 4565, 4568, -1, 6937, 6927, 6929, -1, 6937, 6370, 6935, -1, 6937, 6931, 6927, -1, 6936, 6926, 4565, -1, 6937, 6935, 6931, -1, 6938, 6934, 6343, -1, 6937, 6369, 6370, -1, 6938, 6344, 6934, -1, 6939, 6933, 4569, -1, 6938, 6343, 6344, -1, 6940, 6930, 6926, -1, 6941, 6925, 6920, -1, 6940, 6926, 6936, -1, 6941, 6920, 6933, -1, 6942, 6932, 6930, -1, 6943, 6941, 6933, -1, 6943, 6933, 6939, -1, 6942, 6930, 6940, -1, 6944, 6934, 6932, -1, 6944, 6343, 6934, -1, 6944, 6932, 6942, -1, 6945, 6925, 6941, -1, 6945, 6929, 6925, -1, 6946, 4568, 4570, -1, 6947, 6941, 6943, -1, 6947, 6945, 6941, -1, 6946, 6936, 4568, -1, 6948, 6343, 6944, -1, 6949, 6937, 6929, -1, 6948, 6944, 6341, -1, 6949, 6929, 6945, -1, 6948, 6341, 6343, -1, 6950, 6940, 6936, -1, 6951, 4569, 4571, -1, 6950, 6936, 6946, -1, 6951, 6939, 4569, -1, 6952, 6942, 6940, -1, 6953, 6369, 6937, -1, 6953, 6937, 6949, -1, 6952, 6940, 6950, -1, 6954, 6369, 6953, -1, 6955, 6942, 6952, -1, 6954, 6945, 6947, -1, 6955, 6944, 6942, -1, 6955, 6341, 6944, -1, 6954, 6949, 6945, -1, 6954, 6953, 6949, -1, 6954, 6368, 6369, -1, 6956, 4570, 4573, -1, 6956, 6946, 4570, -1, 6957, 6943, 6939, -1, 6957, 6939, 6951, -1, 6958, 6341, 6955, -1, 6958, 6340, 6341, -1, 6959, 6951, 4571, -1, 6960, 6946, 6956, -1, 6961, 6947, 6943, -1, 6960, 6950, 6946, -1, 6961, 6943, 6957, -1, 6962, 6952, 6950, -1, 6962, 6950, 6960, -1, 6963, 6957, 6951, -1, 6963, 6951, 6959, -1, 6964, 6955, 6952, -1, 6965, 6947, 6961, -1, 6964, 6952, 6962, -1, 6965, 6954, 6947, -1, 6966, 4573, 4574, -1, 6967, 6961, 6957, -1, 6966, 6956, 4573, -1, 6967, 6957, 6963, -1, 6968, 4571, 4572, -1, 6968, 6959, 4571, -1, 6969, 6958, 6955, -1, 6969, 6340, 6958, -1, 6969, 6955, 6964, -1, 6969, 6338, 6340, -1, 6970, 6954, 6965, -1, 6971, 6960, 6956, -1, 6970, 6368, 6954, -1, 6971, 6956, 6966, -1, 6972, 6367, 6368, -1, 6972, 6965, 6961, -1, 6972, 6961, 6967, -1, 6972, 6970, 6965, -1, 6973, 6962, 6960, -1, 6972, 6368, 6970, -1, 6974, 6959, 6968, -1, 6973, 6960, 6971, -1, 6974, 6963, 6959, -1, 6975, 6964, 6962, -1, 6975, 6962, 6973, -1, 6976, 6968, 4572, -1, 6977, 4574, 4576, -1, 6977, 6966, 4574, -1, 6978, 6967, 6963, -1, 6978, 6963, 6974, -1, 6979, 6969, 6964, -1, 6979, 6338, 6969, -1, 6979, 6964, 6975, -1, 6979, 6334, 6338, -1, 6980, 6974, 6968, -1, 6980, 6968, 6976, -1, 6981, 6966, 6977, -1, 6981, 6971, 6966, -1, 6982, 6967, 6978, -1, 6982, 6972, 6967, -1, 6983, 4572, 4575, -1, 6984, 6973, 6971, -1, 6984, 6971, 6981, -1, 6983, 6976, 4572, -1, 6985, 6975, 6973, -1, 6986, 6974, 6980, -1, 6985, 6973, 6984, -1, 6986, 6978, 6974, -1, 6734, 4576, 4578, -1, 6987, 6972, 6982, -1, 6734, 6977, 4576, -1, 6987, 6367, 6972, -1, 6988, 6976, 6983, -1, 6989, 6979, 6975, -1, 6989, 6334, 6979, -1, 6989, 6975, 6985, -1, 6989, 6332, 6334, -1, 6988, 6980, 6976, -1, 6733, 6977, 6734, -1, 6736, 6978, 6986, -1, 6736, 6367, 6987, -1, 6733, 6981, 6977, -1, 6736, 6366, 6367, -1, 6736, 6987, 6982, -1, 6736, 6982, 6978, -1, 6742, 6981, 6733, -1, 6742, 6984, 6981, -1, 6740, 6983, 4575, -1, 6747, 6986, 6980, -1, 6747, 6980, 6988, -1, 6744, 6985, 6984, -1, 6744, 6984, 6742, -1, 6745, 6983, 6740, -1, 6750, 4578, 4579, -1, 6750, 6734, 4578, -1, 6745, 6988, 6983, -1, 6737, 6736, 6986, -1, 6737, 6986, 6747, -1, 6753, 6331, 6332, -1, 6741, 6740, 4575, -1, 6753, 6989, 6985, -1, 6741, 4575, 4577, -1, 6753, 6332, 6989, -1, 6753, 6985, 6744, -1, 6732, 6734, 6750, -1, 6748, 6988, 6745, -1, 6748, 6747, 6988, -1, 6990, 1261, 6991, -1, 6992, 1219, 6993, -1, 1208, 1219, 6992, -1, 6991, 1271, 6994, -1, 1261, 1271, 6991, -1, 6993, 1234, 6995, -1, 1219, 1234, 6993, -1, 6994, 1284, 6996, -1, 1271, 1284, 6994, -1, 1234, 1595, 6995, -1, 1186, 1189, 4012, -1, 6995, 1595, 6997, -1, 4012, 1189, 6998, -1, 6996, 1294, 6999, -1, 1284, 1294, 6996, -1, 6997, 1603, 7000, -1, 6999, 1441, 4003, -1, 1595, 1603, 6997, -1, 1294, 1441, 6999, -1, 6998, 1226, 7001, -1, 1189, 1226, 6998, -1, 7000, 1612, 7002, -1, 1603, 1612, 7000, -1, 1226, 1249, 7001, -1, 7001, 1249, 7003, -1, 7002, 926, 7004, -1, 1612, 926, 7002, -1, 1249, 1277, 7003, -1, 7003, 1277, 7005, -1, 7004, 925, 7006, -1, 926, 925, 7004, -1, 1277, 1300, 7005, -1, 7005, 1300, 7007, -1, 7006, 949, 7008, -1, 925, 949, 7006, -1, 1300, 1325, 7007, -1, 7007, 1325, 7009, -1, 7008, 972, 7010, -1, 1325, 1353, 7009, -1, 949, 972, 7008, -1, 7009, 1353, 7011, -1, 972, 1007, 7010, -1, 7010, 1007, 7012, -1, 1353, 1380, 7011, -1, 7011, 1380, 7013, -1, 1007, 1038, 7012, -1, 7012, 1038, 7014, -1, 1380, 1402, 7013, -1, 7013, 1402, 7015, -1, 1038, 1068, 7014, -1, 7014, 1068, 7016, -1, 1402, 1416, 7015, -1, 7015, 1416, 7017, -1, 1068, 1104, 7016, -1, 7016, 1104, 7018, -1, 1416, 1434, 7017, -1, 7017, 1434, 7019, -1, 1104, 1150, 7018, -1, 7018, 1150, 7020, -1, 1434, 1469, 7019, -1, 7019, 1469, 7021, -1, 1150, 1225, 7020, -1, 7020, 1225, 7022, -1, 1469, 1500, 7021, -1, 7021, 1500, 7023, -1, 1225, 1268, 7022, -1, 7022, 1268, 7024, -1, 1500, 1533, 7023, -1, 7023, 1533, 7025, -1, 1268, 1312, 7024, -1, 7024, 1312, 7026, -1, 1533, 1560, 7025, -1, 7025, 1560, 7027, -1, 1312, 1340, 7026, -1, 7026, 1340, 7028, -1, 1560, 1179, 7027, -1, 7027, 1179, 7029, -1, 1340, 1369, 7028, -1, 7028, 1369, 7030, -1, 1179, 1188, 7029, -1, 7029, 1188, 7031, -1, 1369, 1256, 7030, -1, 7030, 1256, 6990, -1, 1188, 1208, 7031, -1, 7031, 1208, 6992, -1, 1256, 1261, 6990, -1, 7032, 3595, 7033, -1, 3605, 3595, 7032, -1, 3595, 3585, 7033, -1, 7033, 3585, 7034, -1, 7034, 3580, 7035, -1, 3585, 3580, 7034, -1, 3855, 3854, 1757, -1, 1757, 3854, 7036, -1, 7037, 3880, 7038, -1, 7035, 3880, 7037, -1, 3580, 3880, 7035, -1, 7036, 3842, 7039, -1, 3854, 3842, 7036, -1, 7038, 3870, 7040, -1, 3880, 3870, 7038, -1, 7039, 3829, 7041, -1, 3842, 3829, 7039, -1, 7040, 3851, 7042, -1, 3870, 3851, 7040, -1, 7041, 3819, 7043, -1, 3829, 3819, 7041, -1, 7042, 3832, 7044, -1, 3851, 3832, 7042, -1, 3819, 3805, 7043, -1, 7043, 3805, 7045, -1, 7044, 3812, 7046, -1, 3832, 3812, 7044, -1, 3805, 3782, 7045, -1, 7046, 3793, 7047, -1, 7045, 3782, 7048, -1, 3812, 3793, 7046, -1, 7047, 3774, 7049, -1, 3782, 3781, 7048, -1, 3793, 3774, 7047, -1, 7048, 3781, 7050, -1, 7049, 3762, 7051, -1, 3781, 3769, 7050, -1, 3774, 3762, 7049, -1, 7050, 3769, 7052, -1, 7051, 3750, 7053, -1, 3769, 3741, 7052, -1, 3762, 3750, 7051, -1, 7052, 3741, 7054, -1, 3750, 3739, 7053, -1, 7053, 3739, 7055, -1, 3741, 3721, 7054, -1, 7054, 3721, 7056, -1, 3739, 3727, 7055, -1, 7055, 3727, 7057, -1, 3721, 3701, 7056, -1, 7056, 3701, 7058, -1, 3727, 3715, 7057, -1, 7057, 3715, 7059, -1, 3701, 3683, 7058, -1, 7058, 3683, 7060, -1, 3715, 3704, 7059, -1, 7059, 3704, 7061, -1, 3683, 3655, 7060, -1, 7060, 3655, 7062, -1, 3704, 3691, 7061, -1, 7061, 3691, 7063, -1, 3655, 3645, 7062, -1, 3691, 3680, 7063, -1, 7062, 3645, 7064, -1, 7063, 3680, 7065, -1, 3680, 3663, 7065, -1, 3645, 3635, 7064, -1, 7065, 3663, 1747, -1, 7064, 3635, 7066, -1, 3663, 3662, 1747, -1, 3635, 3625, 7066, -1, 7066, 3625, 7067, -1, 3625, 3615, 7067, -1, 7067, 3615, 7068, -1, 3615, 3605, 7068, -1, 7068, 3605, 7032, -1, 6635, 3197, 6615, -1, 6529, 3159, 6507, -1, 3141, 3159, 6529, -1, 6615, 3209, 6595, -1, 3197, 3209, 6615, -1, 6507, 3170, 6483, -1, 3159, 3170, 6507, -1, 6595, 3221, 6573, -1, 3209, 3221, 6595, -1, 3170, 3541, 6483, -1, 3144, 3150, 4669, -1, 6483, 3541, 6466, -1, 4669, 3150, 6462, -1, 6573, 3233, 6546, -1, 3221, 3233, 6573, -1, 6466, 3549, 6463, -1, 6546, 3380, 4591, -1, 3541, 3549, 6466, -1, 3233, 3380, 6546, -1, 6462, 3178, 6447, -1, 3150, 3178, 6462, -1, 6463, 3558, 6448, -1, 3549, 3558, 6463, -1, 3178, 3203, 6447, -1, 6447, 3203, 6437, -1, 6448, 3431, 6446, -1, 3558, 3431, 6448, -1, 3203, 3229, 6437, -1, 6437, 3229, 6431, -1, 6446, 2885, 6569, -1, 3431, 2885, 6446, -1, 3229, 3246, 6431, -1, 6431, 3246, 6425, -1, 6569, 2884, 6561, -1, 2885, 2884, 6569, -1, 3246, 3272, 6425, -1, 6425, 3272, 6418, -1, 6561, 2911, 6556, -1, 3272, 3299, 6418, -1, 2884, 2911, 6561, -1, 6418, 3299, 6404, -1, 2911, 2945, 6556, -1, 6556, 2945, 6409, -1, 3299, 3326, 6404, -1, 6404, 3326, 6376, -1, 2945, 2976, 6409, -1, 6409, 2976, 6394, -1, 3326, 3344, 6376, -1, 6376, 3344, 6723, -1, 2976, 3006, 6394, -1, 6394, 3006, 6393, -1, 3344, 3358, 6723, -1, 6723, 3358, 6703, -1, 3006, 3042, 6393, -1, 6393, 3042, 6728, -1, 3358, 3378, 6703, -1, 6703, 3378, 6682, -1, 3042, 3084, 6728, -1, 6728, 3084, 6717, -1, 3378, 3414, 6682, -1, 6682, 3414, 6662, -1, 3084, 3163, 6717, -1, 6717, 3163, 6705, -1, 3414, 3445, 6662, -1, 6662, 3445, 6642, -1, 3163, 3207, 6705, -1, 6705, 3207, 6693, -1, 3445, 3478, 6642, -1, 6642, 3478, 6622, -1, 3207, 3250, 6693, -1, 6693, 3250, 6680, -1, 3478, 3505, 6622, -1, 6622, 3505, 6602, -1, 3250, 3278, 6680, -1, 6680, 3278, 6669, -1, 3505, 3111, 6602, -1, 6602, 3111, 6582, -1, 3278, 3306, 6669, -1, 6669, 3306, 6655, -1, 3111, 3117, 6582, -1, 6582, 3117, 6552, -1, 3306, 3193, 6655, -1, 6655, 3193, 6635, -1, 3117, 3141, 6552, -1, 6552, 3141, 6529, -1, 3193, 3197, 6635, -1, 4823, 7069, 4834, -1, 7070, 7069, 4823, -1, 4584, 2290, 4856, -1, 4834, 7071, 4845, -1, 7069, 7071, 4834, -1, 4856, 7072, 4870, -1, 2290, 7072, 4856, -1, 4845, 7073, 4861, -1, 7071, 7073, 4845, -1, 4870, 7074, 4871, -1, 7072, 7074, 4870, -1, 4861, 7075, 4883, -1, 7073, 7075, 4861, -1, 4871, 7076, 4895, -1, 7074, 7076, 4871, -1, 4883, 7077, 4907, -1, 7075, 7077, 4883, -1, 4895, 7078, 4896, -1, 7076, 7078, 4895, -1, 4907, 7079, 4930, -1, 7077, 7079, 4907, -1, 7078, 7080, 4896, -1, 4896, 7080, 4921, -1, 4930, 7081, 4950, -1, 7079, 7081, 4930, -1, 7080, 7082, 4921, -1, 4921, 7082, 4935, -1, 4950, 7083, 4971, -1, 7081, 7083, 4950, -1, 7082, 7084, 4935, -1, 4935, 7084, 4948, -1, 4971, 7085, 4994, -1, 7083, 7085, 4971, -1, 7084, 7086, 4948, -1, 4948, 7086, 4962, -1, 7085, 7087, 4994, -1, 4994, 7087, 5027, -1, 7086, 7088, 4962, -1, 4962, 7088, 4976, -1, 7087, 7089, 5027, -1, 5027, 7089, 5041, -1, 7088, 7090, 4976, -1, 4976, 7090, 4990, -1, 7089, 7091, 5041, -1, 5041, 7091, 5055, -1, 7090, 7092, 4990, -1, 4990, 7092, 5004, -1, 7091, 7093, 5055, -1, 5055, 7093, 5056, -1, 7092, 7094, 5004, -1, 5004, 7094, 5017, -1, 7093, 7095, 5056, -1, 5056, 7095, 5081, -1, 7094, 7096, 5017, -1, 7095, 7097, 5081, -1, 5017, 7096, 5031, -1, 5081, 7097, 5087, -1, 7096, 7098, 5031, -1, 7097, 7099, 5087, -1, 5031, 7098, 5046, -1, 5087, 7099, 4551, -1, 7099, 2388, 4551, -1, 7098, 7100, 5046, -1, 5046, 7100, 5066, -1, 7100, 7101, 5066, -1, 5066, 7101, 4758, -1, 7101, 7102, 4758, -1, 4758, 7102, 4777, -1, 7102, 7103, 4777, -1, 4777, 7103, 4790, -1, 4790, 7104, 4801, -1, 7103, 7104, 4790, -1, 4801, 7105, 4812, -1, 7104, 7105, 4801, -1, 4812, 7070, 4823, -1, 7105, 7070, 4812, -1, 2277, 7106, 2382, -1, 7107, 7108, 7109, -1, 2287, 7110, 7111, -1, 2287, 7112, 7110, -1, 2287, 7111, 2277, -1, 4444, 4442, 2454, -1, 4444, 2454, 2481, -1, 4440, 2454, 4442, -1, 4446, 4444, 2481, -1, 4437, 2454, 4440, -1, 4437, 2446, 2454, -1, 4414, 7109, 7113, -1, 4448, 4446, 2481, -1, 4416, 4414, 7113, -1, 4448, 2481, 2519, -1, 4416, 7113, 7114, -1, 4412, 7107, 7109, -1, 4436, 2446, 4437, -1, 4412, 7109, 4414, -1, 4450, 4448, 2519, -1, 4418, 4416, 7114, -1, 4409, 7115, 7107, -1, 4409, 7107, 4412, -1, 7116, 2446, 4436, -1, 4420, 7114, 7117, -1, 4452, 4450, 2519, -1, 4452, 2519, 2554, -1, 4420, 4418, 7114, -1, 4408, 7115, 4409, -1, 4422, 4420, 7117, -1, 7118, 2482, 2446, -1, 7118, 2446, 7116, -1, 4454, 4452, 2554, -1, 4422, 7117, 7119, -1, 2309, 4502, 7112, -1, 7120, 2482, 7118, -1, 4456, 4454, 2554, -1, 2309, 7112, 2287, -1, 4456, 2554, 2587, -1, 7121, 7115, 4408, -1, 7121, 4408, 7122, -1, 4424, 4422, 7119, -1, 7123, 7121, 7122, -1, 7124, 2424, 2482, -1, 7124, 2482, 7120, -1, 4426, 4424, 7119, -1, 4458, 4456, 2587, -1, 4426, 7119, 7125, -1, 7126, 2424, 7124, -1, 4428, 4426, 7125, -1, 4428, 7125, 7127, -1, 7128, 2411, 2424, -1, 7128, 2424, 7126, -1, 4430, 4428, 7127, -1, 2329, 4501, 4502, -1, 2329, 4502, 2309, -1, 7129, 7121, 7123, -1, 7129, 7130, 7131, -1, 7129, 7132, 7130, -1, 7129, 7123, 7132, -1, 7133, 7129, 7131, -1, 7133, 7134, 7135, -1, 7133, 7136, 7134, -1, 7133, 7131, 7136, -1, 4496, 4462, 4460, -1, 2455, 4501, 2329, -1, 7137, 7133, 7135, -1, 4494, 4460, 4458, -1, 7137, 7138, 7139, -1, 7137, 7140, 7138, -1, 7137, 7135, 7140, -1, 7141, 4501, 2455, -1, 7141, 7142, 4501, -1, 4494, 4458, 2587, -1, 4494, 4496, 4460, -1, 4492, 4494, 2587, -1, 4492, 2587, 2615, -1, 4492, 2615, 2642, -1, 7143, 7142, 7141, -1, 7143, 7144, 7142, -1, 7145, 7137, 7139, -1, 7145, 7146, 4434, -1, 7145, 7139, 7146, -1, 4498, 4462, 4496, -1, 4498, 7147, 4462, -1, 4498, 7148, 7147, -1, 7149, 7145, 4434, -1, 7149, 4434, 4432, -1, 4504, 7150, 7148, -1, 7151, 7144, 7143, -1, 7151, 7152, 7144, -1, 7153, 7152, 7151, -1, 4504, 7148, 4498, -1, 4544, 4492, 2642, -1, 4544, 2642, 2668, -1, 7154, 4430, 7127, -1, 7154, 7149, 4432, -1, 7154, 4432, 4430, -1, 4542, 4544, 2668, -1, 7155, 7152, 7153, -1, 7155, 7156, 7152, -1, 4542, 2668, 2704, -1, 4542, 2704, 2835, -1, 7157, 7154, 7127, -1, 7157, 7127, 7158, -1, 4508, 7159, 7150, -1, 7160, 7156, 7155, -1, 4508, 7161, 7159, -1, 7160, 7162, 7156, -1, 4508, 7150, 4504, -1, 7163, 7158, 7164, -1, 7163, 7157, 7158, -1, 4512, 7165, 7161, -1, 7166, 7162, 7160, -1, 7167, 7163, 7164, -1, 7168, 7169, 7162, -1, 4512, 7161, 4508, -1, 7168, 7162, 7166, -1, 4540, 4542, 2835, -1, 4540, 2835, 2849, -1, 7170, 7164, 7171, -1, 7170, 7167, 7164, -1, 7172, 7171, 7169, -1, 7172, 7170, 7171, -1, 7172, 7169, 7168, -1, 4516, 7128, 7165, -1, 4516, 2395, 2411, -1, 4516, 2411, 7128, -1, 4516, 7165, 4512, -1, 4538, 2849, 2760, -1, 4538, 4540, 2849, -1, 4520, 2395, 4516, -1, 4520, 7173, 2393, -1, 4520, 2393, 2395, -1, 4536, 4538, 2760, -1, 4536, 2760, 2761, -1, 4536, 2761, 2774, -1, 4534, 4536, 2774, -1, 4534, 2774, 2788, -1, 7174, 7173, 4520, -1, 7174, 7175, 7173, -1, 4532, 4534, 2788, -1, 4532, 2788, 2530, -1, 7176, 7177, 7175, -1, 7176, 7175, 7174, -1, 7178, 7179, 7180, -1, 7178, 7180, 7177, -1, 7178, 7177, 7176, -1, 4530, 4532, 2530, -1, 4530, 2530, 2537, -1, 4530, 2537, 2546, -1, 7181, 7182, 7179, -1, 7181, 7179, 7178, -1, 4528, 4530, 2546, -1, 4528, 2546, 2822, -1, 7183, 7184, 7182, -1, 7183, 7182, 7181, -1, 4526, 2822, 2847, -1, 4526, 4528, 2822, -1, 2269, 4526, 2847, -1, 7185, 7184, 7183, -1, 7186, 7185, 7183, -1, 4524, 4526, 2269, -1, 7187, 7185, 7186, -1, 7188, 7187, 7186, -1, 7189, 7187, 7188, -1, 7190, 7189, 7188, -1, 4471, 2269, 2301, -1, 4473, 4471, 2301, -1, 4469, 4524, 2269, -1, 4469, 2269, 4471, -1, 4475, 2301, 2341, -1, 4475, 4473, 2301, -1, 4467, 4522, 4524, -1, 4467, 4524, 4469, -1, 4477, 4475, 2341, -1, 4465, 4518, 4522, -1, 4465, 4522, 4467, -1, 7191, 7189, 7190, -1, 4479, 2341, 2354, -1, 4479, 4477, 2341, -1, 7192, 4518, 4465, -1, 4481, 4479, 2354, -1, 7193, 4514, 4518, -1, 7193, 4518, 7192, -1, 4483, 4481, 2354, -1, 7194, 4514, 7193, -1, 7194, 4510, 4514, -1, 7195, 4510, 7194, -1, 7196, 4510, 7195, -1, 2368, 4483, 2354, -1, 2368, 4485, 4483, -1, 2368, 4487, 4485, -1, 7197, 7191, 7190, -1, 7197, 7190, 7198, -1, 4489, 4487, 2368, -1, 4506, 4510, 7196, -1, 7199, 4506, 7196, -1, 4502, 7199, 7112, -1, 4502, 4506, 7199, -1, 2382, 7200, 4491, -1, 2382, 7106, 7200, -1, 2382, 4489, 2368, -1, 2382, 4491, 4489, -1, 7108, 7197, 7198, -1, 7108, 7198, 7109, -1, 2277, 7201, 7106, -1, 2277, 7111, 7201, -1, 7202, 1637, 7203, -1, 7204, 1637, 7202, -1, 7203, 1637, 1783, -1, 7205, 1646, 7204, -1, 7206, 1646, 7205, -1, 7204, 1646, 1637, -1, 4443, 4445, 1852, -1, 1852, 4445, 1888, -1, 1852, 4441, 4443, -1, 4445, 4447, 1888, -1, 1831, 4439, 1852, -1, 1852, 4439, 4441, -1, 7207, 4415, 7208, -1, 4415, 4417, 7208, -1, 1888, 4449, 1923, -1, 7208, 4417, 7209, -1, 4447, 4449, 1888, -1, 7210, 4413, 7207, -1, 7207, 4413, 4415, -1, 1831, 4438, 4439, -1, 4417, 4419, 7209, -1, 4449, 4451, 1923, -1, 7210, 4411, 4413, -1, 7211, 4411, 7210, -1, 1831, 7212, 4438, -1, 7209, 4421, 7213, -1, 4419, 4421, 7209, -1, 7211, 4410, 4411, -1, 1923, 4453, 1954, -1, 4421, 4423, 7213, -1, 4451, 4453, 1923, -1, 1851, 7214, 1831, -1, 1831, 7214, 7212, -1, 7213, 4423, 7215, -1, 7211, 7216, 4410, -1, 4453, 4455, 1954, -1, 4410, 7216, 7217, -1, 1851, 7218, 7214, -1, 4500, 1667, 7206, -1, 7206, 1667, 1646, -1, 1954, 4457, 1985, -1, 4455, 4457, 1954, -1, 4423, 4425, 7215, -1, 7216, 7219, 7217, -1, 1809, 7220, 1851, -1, 1851, 7220, 7218, -1, 4425, 4427, 7215, -1, 7215, 4427, 7221, -1, 4457, 4459, 1985, -1, 4427, 4429, 7221, -1, 1809, 7222, 7220, -1, 7221, 4429, 7223, -1, 1796, 7224, 1809, -1, 4429, 4431, 7223, -1, 1809, 7224, 7222, -1, 7216, 7225, 7219, -1, 7226, 7225, 7227, -1, 7228, 7225, 7226, -1, 7219, 7225, 7228, -1, 4500, 1686, 1667, -1, 4499, 1686, 4500, -1, 7225, 7229, 7227, -1, 7230, 7229, 7231, -1, 7232, 7229, 7230, -1, 7227, 7229, 7232, -1, 4461, 4493, 4459, -1, 4499, 1843, 1686, -1, 7229, 7233, 7231, -1, 4459, 4493, 1985, -1, 7234, 7233, 7235, -1, 7236, 7233, 7234, -1, 7231, 7233, 7236, -1, 4463, 4495, 4461, -1, 4499, 7237, 1843, -1, 4461, 4495, 4493, -1, 7238, 7237, 4499, -1, 4493, 4545, 1985, -1, 7233, 7239, 7235, -1, 7240, 7239, 4435, -1, 2013, 4545, 2048, -1, 7235, 7239, 7240, -1, 1985, 4545, 2013, -1, 4463, 4497, 4495, -1, 7238, 7241, 7237, -1, 7242, 7241, 7238, -1, 7243, 4497, 4463, -1, 7244, 4497, 7243, -1, 7239, 7245, 4435, -1, 7246, 4503, 7244, -1, 4435, 7245, 4433, -1, 7242, 7247, 7241, -1, 7248, 7247, 7242, -1, 4431, 7249, 7223, -1, 7244, 4503, 4497, -1, 7245, 7249, 4433, -1, 4545, 4543, 2048, -1, 4433, 7249, 4431, -1, 7248, 7250, 7247, -1, 2048, 4543, 2075, -1, 7249, 7251, 7223, -1, 7223, 7251, 7252, -1, 2102, 4541, 2201, -1, 2075, 4541, 2102, -1, 7253, 7254, 7248, -1, 4543, 4541, 2075, -1, 7255, 4507, 7246, -1, 7248, 7254, 7250, -1, 7256, 4507, 7255, -1, 7246, 4507, 4503, -1, 7252, 7257, 7258, -1, 7251, 7257, 7252, -1, 7259, 7260, 7253, -1, 7261, 4511, 7256, -1, 7253, 7260, 7254, -1, 7257, 7262, 7258, -1, 7259, 7263, 7260, -1, 7256, 4511, 4507, -1, 7258, 7264, 7265, -1, 7262, 7264, 7258, -1, 2201, 4539, 2214, -1, 7266, 7267, 7259, -1, 4541, 4539, 2201, -1, 7259, 7267, 7263, -1, 7265, 7268, 7266, -1, 7266, 7268, 7267, -1, 7264, 7268, 7265, -1, 7224, 4515, 7261, -1, 1778, 4515, 1796, -1, 1796, 4515, 7224, -1, 7261, 4515, 4511, -1, 2214, 4537, 2150, -1, 4539, 4537, 2214, -1, 1779, 4519, 1778, -1, 7269, 4519, 1779, -1, 1778, 4519, 4515, -1, 2148, 4535, 2164, -1, 2150, 4535, 2148, -1, 4537, 4535, 2150, -1, 4535, 4533, 2164, -1, 2164, 4533, 2180, -1, 7270, 7271, 7269, -1, 7269, 7271, 4519, -1, 2180, 4531, 1903, -1, 4533, 4531, 2180, -1, 7270, 7272, 7271, -1, 7273, 7272, 7270, -1, 7273, 7274, 7272, -1, 7275, 7274, 7273, -1, 7276, 7274, 7275, -1, 1908, 4529, 1915, -1, 1903, 4529, 1908, -1, 4531, 4529, 1903, -1, 7276, 7277, 7274, -1, 7278, 7277, 7276, -1, 1915, 4527, 1631, -1, 4529, 4527, 1915, -1, 7278, 7279, 7277, -1, 7280, 7279, 7278, -1, 1631, 4525, 1634, -1, 4527, 4525, 1631, -1, 7280, 7281, 7279, -1, 4525, 1681, 1634, -1, 7281, 7282, 7279, -1, 4525, 4523, 1681, -1, 7281, 7283, 7282, -1, 7283, 7284, 7282, -1, 7283, 7285, 7284, -1, 7285, 7286, 7284, -1, 1681, 4470, 1707, -1, 4470, 4472, 1707, -1, 4523, 4468, 1681, -1, 1681, 4468, 4470, -1, 1707, 4474, 1721, -1, 4472, 4474, 1707, -1, 4521, 4466, 4523, -1, 4523, 4466, 4468, -1, 4474, 4476, 1721, -1, 4517, 4464, 4521, -1, 4521, 4464, 4466, -1, 7285, 7287, 7286, -1, 1721, 4478, 1734, -1, 4476, 4478, 1721, -1, 4517, 7288, 4464, -1, 4478, 4480, 1734, -1, 4517, 7289, 7288, -1, 4513, 7289, 4517, -1, 4480, 4482, 1734, -1, 4513, 7290, 7289, -1, 4509, 7290, 4513, -1, 4509, 7291, 7290, -1, 4509, 7292, 7291, -1, 7287, 7293, 7286, -1, 7286, 7293, 7294, -1, 4482, 1752, 1734, -1, 4484, 1752, 4482, -1, 4486, 1752, 4484, -1, 4486, 4488, 1752, -1, 4509, 4505, 7292, -1, 4505, 7295, 7292, -1, 4505, 4500, 7295, -1, 7295, 4500, 7206, -1, 7293, 7296, 7294, -1, 7294, 7296, 7207, -1, 7297, 1783, 4490, -1, 7203, 1783, 7297, -1, 4488, 1783, 1752, -1, 4490, 1783, 4488, -1, 7296, 7210, 7207, -1, 7164, 7265, 7171, -1, 7258, 7265, 7164, -1, 7171, 7266, 7169, -1, 7265, 7266, 7171, -1, 7169, 7259, 7162, -1, 7266, 7259, 7169, -1, 4519, 7271, 4520, -1, 4520, 7271, 7174, -1, 7162, 7253, 7156, -1, 7259, 7253, 7162, -1, 7174, 7272, 7176, -1, 7271, 7272, 7174, -1, 7156, 7248, 7152, -1, 7253, 7248, 7156, -1, 7176, 7274, 7178, -1, 7272, 7274, 7176, -1, 7152, 7242, 7144, -1, 7248, 7242, 7152, -1, 7178, 7277, 7181, -1, 7274, 7277, 7178, -1, 7144, 7238, 7142, -1, 7242, 7238, 7144, -1, 7181, 7279, 7183, -1, 7277, 7279, 7181, -1, 7142, 4499, 4501, -1, 7238, 4499, 7142, -1, 7183, 7282, 7186, -1, 7279, 7282, 7183, -1, 7186, 7284, 7188, -1, 7282, 7284, 7186, -1, 7188, 7286, 7190, -1, 7284, 7286, 7188, -1, 7190, 7294, 7198, -1, 7286, 7294, 7190, -1, 7198, 7207, 7109, -1, 7294, 7207, 7198, -1, 7207, 7208, 7109, -1, 7109, 7208, 7113, -1, 7208, 7209, 7113, -1, 7113, 7209, 7114, -1, 7209, 7213, 7114, -1, 7114, 7213, 7117, -1, 7213, 7215, 7117, -1, 7117, 7215, 7119, -1, 7215, 7221, 7119, -1, 7119, 7221, 7125, -1, 7221, 7223, 7125, -1, 7125, 7223, 7127, -1, 7223, 7252, 7127, -1, 7127, 7252, 7158, -1, 7252, 7258, 7158, -1, 7158, 7258, 7164, -1, 4491, 7200, 4490, -1, 4490, 7200, 7297, -1, 7297, 7106, 7203, -1, 7200, 7106, 7297, -1, 7203, 7201, 7202, -1, 7106, 7201, 7203, -1, 7202, 7111, 7204, -1, 7201, 7111, 7202, -1, 7204, 7110, 7205, -1, 7111, 7110, 7204, -1, 7205, 7112, 7206, -1, 7110, 7112, 7205, -1, 7206, 7199, 7295, -1, 7112, 7199, 7206, -1, 7295, 7196, 7292, -1, 7199, 7196, 7295, -1, 7292, 7195, 7291, -1, 7196, 7195, 7292, -1, 7291, 7194, 7290, -1, 7195, 7194, 7291, -1, 7290, 7193, 7289, -1, 7194, 7193, 7290, -1, 7289, 7192, 7288, -1, 7193, 7192, 7289, -1, 7288, 4465, 4464, -1, 7192, 4465, 7288, -1, 4462, 7147, 4463, -1, 4463, 7147, 7243, -1, 7243, 7148, 7244, -1, 7147, 7148, 7243, -1, 7244, 7150, 7246, -1, 7148, 7150, 7244, -1, 7246, 7159, 7255, -1, 7150, 7159, 7246, -1, 7255, 7161, 7256, -1, 7159, 7161, 7255, -1, 7256, 7165, 7261, -1, 7161, 7165, 7256, -1, 7261, 7128, 7224, -1, 7165, 7128, 7261, -1, 7224, 7126, 7222, -1, 7128, 7126, 7224, -1, 7222, 7124, 7220, -1, 7126, 7124, 7222, -1, 7220, 7120, 7218, -1, 7124, 7120, 7220, -1, 7218, 7118, 7214, -1, 7120, 7118, 7218, -1, 7214, 7116, 7212, -1, 7118, 7116, 7214, -1, 7212, 4436, 4438, -1, 7116, 4436, 7212, -1, 4434, 7146, 4435, -1, 4435, 7146, 7240, -1, 7240, 7139, 7235, -1, 7146, 7139, 7240, -1, 7235, 7138, 7234, -1, 7139, 7138, 7235, -1, 7234, 7140, 7236, -1, 7138, 7140, 7234, -1, 7236, 7135, 7231, -1, 7140, 7135, 7236, -1, 7231, 7134, 7230, -1, 7135, 7134, 7231, -1, 7230, 7136, 7232, -1, 7134, 7136, 7230, -1, 7232, 7131, 7227, -1, 7136, 7131, 7232, -1, 7227, 7130, 7226, -1, 7131, 7130, 7227, -1, 7226, 7132, 7228, -1, 7130, 7132, 7226, -1, 7228, 7123, 7219, -1, 7132, 7123, 7228, -1, 7219, 7122, 7217, -1, 7123, 7122, 7219, -1, 7217, 4408, 4410, -1, 7122, 4408, 7217, -1, 7298, 3249, 3234, -1, 7298, 3234, 7299, -1, 7300, 3249, 7298, -1, 7300, 3256, 3249, -1, 7301, 7302, 3499, -1, 7301, 3499, 3473, -1, 7303, 7301, 3473, -1, 7303, 3473, 3440, -1, 7304, 3256, 7300, -1, 7305, 17, 18, -1, 7304, 3283, 3256, -1, 7306, 7303, 3440, -1, 7306, 3440, 3399, -1, 7307, 18, 41, -1, 7307, 7305, 18, -1, 7308, 3283, 7304, -1, 7308, 3311, 3283, -1, 7309, 370, 17, -1, 7310, 3311, 7308, -1, 7309, 17, 7305, -1, 7311, 7307, 41, -1, 7310, 3338, 3311, -1, 7311, 41, 58, -1, 7312, 7306, 3399, -1, 7312, 3399, 3367, -1, 7313, 3338, 7310, -1, 7313, 3352, 3338, -1, 7314, 7312, 3367, -1, 7314, 3352, 7313, -1, 7314, 3367, 3352, -1, 7315, 370, 7309, -1, 7315, 354, 370, -1, 7316, 58, 74, -1, 7316, 7311, 58, -1, 7317, 354, 7315, -1, 7317, 338, 354, -1, 7318, 7316, 74, -1, 7318, 74, 89, -1, 7319, 338, 7317, -1, 7319, 321, 338, -1, 7320, 7318, 89, -1, 7320, 89, 105, -1, 7321, 321, 7319, -1, 7321, 306, 321, -1, 7322, 7320, 105, -1, 7322, 105, 121, -1, 7323, 306, 7321, -1, 7323, 290, 306, -1, 7324, 7322, 121, -1, 7324, 121, 139, -1, 7325, 290, 7323, -1, 7325, 274, 290, -1, 7326, 7324, 139, -1, 7326, 139, 155, -1, 7327, 258, 274, -1, 7327, 274, 7325, -1, 7328, 7326, 155, -1, 7328, 155, 171, -1, 7329, 239, 258, -1, 7329, 258, 7327, -1, 7330, 7328, 171, -1, 7330, 171, 187, -1, 7331, 239, 7329, -1, 7331, 210, 239, -1, 7332, 7330, 187, -1, 7332, 187, 204, -1, 3076, 208, 210, -1, 3076, 210, 7331, -1, 7333, 208, 3076, -1, 7334, 204, 237, -1, 7334, 7332, 204, -1, 3075, 7333, 3076, -1, 7335, 7333, 3075, -1, 7336, 237, 259, -1, 7336, 7334, 237, -1, 3467, 7335, 3075, -1, 7337, 7335, 3467, -1, 7338, 259, 275, -1, 7338, 7336, 259, -1, 3458, 7337, 3467, -1, 7339, 7337, 3458, -1, 7340, 275, 291, -1, 7340, 7338, 275, -1, 3449, 7339, 3458, -1, 7341, 7339, 3449, -1, 7342, 7340, 291, -1, 7342, 291, 307, -1, 3328, 7341, 3449, -1, 7343, 7342, 307, -1, 7344, 7341, 3328, -1, 323, 7343, 307, -1, 3297, 7344, 3328, -1, 7345, 7343, 323, -1, 7346, 7344, 3297, -1, 339, 7345, 323, -1, 3267, 7346, 3297, -1, 7347, 7345, 339, -1, 7348, 7346, 3267, -1, 356, 7347, 339, -1, 3239, 7348, 3267, -1, 7349, 7347, 356, -1, 7350, 7348, 3239, -1, 372, 7349, 356, -1, 3191, 7350, 3239, -1, 7351, 7349, 372, -1, 7352, 7350, 3191, -1, 21, 7351, 372, -1, 3126, 7352, 3191, -1, 7353, 7351, 21, -1, 7354, 7352, 3126, -1, 22, 7353, 21, -1, 3068, 7354, 3126, -1, 7355, 7353, 22, -1, 7356, 7354, 3068, -1, 43, 7355, 22, -1, 3029, 7356, 3068, -1, 7357, 7355, 43, -1, 7358, 7356, 3029, -1, 60, 7357, 43, -1, 2995, 7358, 3029, -1, 7359, 7357, 60, -1, 7360, 7358, 2995, -1, 76, 7359, 60, -1, 2948, 7360, 2995, -1, 7361, 7359, 76, -1, 7362, 7360, 2948, -1, 91, 7361, 76, -1, 2916, 7362, 2948, -1, 7363, 7361, 91, -1, 7364, 7362, 2916, -1, 107, 7363, 91, -1, 2915, 7364, 2916, -1, 7365, 7363, 107, -1, 7366, 7364, 2915, -1, 123, 7365, 107, -1, 2890, 7366, 2915, -1, 7367, 7365, 123, -1, 7368, 2890, 2889, -1, 7368, 7366, 2890, -1, 138, 7367, 123, -1, 7369, 7367, 138, -1, 7370, 7368, 2889, -1, 7370, 2889, 3567, -1, 154, 7369, 138, -1, 7371, 7369, 154, -1, 7372, 7370, 3567, -1, 7372, 3567, 3560, -1, 169, 7371, 154, -1, 7373, 7371, 169, -1, 7374, 7372, 3560, -1, 7374, 3560, 3551, -1, 185, 7373, 169, -1, 7375, 7373, 185, -1, 7376, 7374, 3551, -1, 7376, 3551, 3543, -1, 191, 7375, 185, -1, 3098, 7375, 191, -1, 193, 3098, 191, -1, 7377, 7376, 3543, -1, 7377, 3543, 3534, -1, 7378, 3534, 3425, -1, 7378, 7377, 3534, -1, 7379, 3098, 193, -1, 7379, 3099, 3098, -1, 7380, 3099, 7379, -1, 7380, 3155, 3099, -1, 7381, 3425, 3418, -1, 7381, 7378, 3425, -1, 7382, 7381, 3418, -1, 7382, 3418, 3408, -1, 7383, 3155, 7380, -1, 7383, 3182, 3155, -1, 7384, 3408, 3397, -1, 7384, 7382, 3408, -1, 7385, 3210, 3182, -1, 7385, 3182, 7383, -1, 7386, 3397, 3391, -1, 7386, 7384, 3397, -1, 7299, 3234, 3210, -1, 7299, 3210, 7385, -1, 7302, 7386, 3391, -1, 7302, 3391, 3499, -1, 7387, 5715, 7388, -1, 5720, 5715, 7387, -1, 7389, 5620, 7390, -1, 5623, 5620, 7389, -1, 7388, 5710, 7391, -1, 5715, 5710, 7388, -1, 5620, 5616, 7390, -1, 243, 4381, 7392, -1, 7390, 4368, 232, -1, 5616, 4368, 7390, -1, 7391, 5705, 7393, -1, 5710, 5705, 7391, -1, 7392, 5611, 7394, -1, 4381, 5611, 7392, -1, 7393, 5700, 7395, -1, 5705, 5700, 7393, -1, 5611, 5608, 7394, -1, 7394, 5608, 7396, -1, 7395, 5695, 7397, -1, 5700, 5695, 7395, -1, 5608, 5605, 7396, -1, 7396, 5605, 7398, -1, 7397, 5690, 7399, -1, 5695, 5690, 7397, -1, 5605, 5602, 7398, -1, 7398, 5602, 7400, -1, 5690, 5685, 7399, -1, 7399, 5685, 7401, -1, 5602, 5599, 7400, -1, 7400, 5599, 7402, -1, 5685, 5680, 7401, -1, 7401, 5680, 7403, -1, 5599, 5596, 7402, -1, 7402, 5596, 7404, -1, 5680, 5675, 7403, -1, 7403, 5675, 7405, -1, 5596, 5593, 7404, -1, 7404, 5593, 7406, -1, 5675, 5670, 7405, -1, 7405, 5670, 7407, -1, 5593, 5590, 7406, -1, 7406, 5590, 7408, -1, 5670, 5665, 7407, -1, 7407, 5665, 7409, -1, 5590, 5587, 7408, -1, 7408, 5587, 7410, -1, 5665, 5660, 7409, -1, 7409, 5660, 7411, -1, 5587, 5584, 7410, -1, 7410, 5584, 7412, -1, 5660, 5655, 7411, -1, 7411, 5655, 7413, -1, 5584, 5578, 7412, -1, 7412, 5578, 7414, -1, 5655, 5650, 7413, -1, 7413, 5650, 7415, -1, 5578, 5573, 7414, -1, 7414, 5573, 7416, -1, 5650, 5647, 7415, -1, 7415, 5647, 7417, -1, 5573, 5568, 7416, -1, 7416, 5568, 7418, -1, 5647, 5644, 7417, -1, 7417, 5644, 7419, -1, 5568, 5563, 7418, -1, 7418, 5563, 7420, -1, 5644, 5641, 7419, -1, 7419, 5641, 7421, -1, 5563, 5557, 7420, -1, 7420, 5557, 7422, -1, 5641, 5638, 7421, -1, 7421, 5638, 7423, -1, 5557, 5551, 7422, -1, 7422, 5551, 7424, -1, 5638, 5635, 7423, -1, 7423, 5635, 7425, -1, 5551, 5550, 7424, -1, 7424, 5550, 7426, -1, 7425, 5632, 7427, -1, 5635, 5632, 7425, -1, 5550, 5730, 7426, -1, 7426, 5730, 7428, -1, 7427, 5629, 7429, -1, 5632, 5629, 7427, -1, 7428, 5725, 7430, -1, 5730, 5725, 7428, -1, 7429, 5626, 7431, -1, 5629, 5626, 7429, -1, 7430, 5720, 7387, -1, 5725, 5720, 7430, -1, 7431, 5623, 7389, -1, 5626, 5623, 7431, -1, 5878, 5883, 7432, -1, 7433, 5795, 7434, -1, 5792, 5795, 7433, -1, 7435, 5888, 7436, -1, 7434, 5800, 416, -1, 5883, 5888, 7435, -1, 5795, 5800, 7434, -1, 566, 4321, 7437, -1, 5800, 4320, 416, -1, 7436, 5893, 7438, -1, 5888, 5893, 7436, -1, 7437, 5804, 7439, -1, 4321, 5804, 7437, -1, 7438, 5898, 7440, -1, 5893, 5898, 7438, -1, 5804, 5808, 7439, -1, 7439, 5808, 7441, -1, 7440, 5903, 7442, -1, 5898, 5903, 7440, -1, 5808, 5811, 7441, -1, 7441, 5811, 7443, -1, 7442, 5908, 7444, -1, 5903, 5908, 7442, -1, 5811, 5814, 7443, -1, 7443, 5814, 7445, -1, 5908, 5913, 7444, -1, 7444, 5913, 7446, -1, 5814, 5817, 7445, -1, 7445, 5817, 7447, -1, 5913, 5918, 7446, -1, 7446, 5918, 7448, -1, 5817, 5820, 7447, -1, 7447, 5820, 7449, -1, 5918, 5740, 7448, -1, 7448, 5740, 7450, -1, 5820, 5823, 7449, -1, 7449, 5823, 7451, -1, 5740, 5741, 7450, -1, 7450, 5741, 7452, -1, 5823, 5826, 7451, -1, 7451, 5826, 7453, -1, 5741, 5746, 7452, -1, 7452, 5746, 7454, -1, 5826, 5829, 7453, -1, 7453, 5829, 7455, -1, 5746, 5751, 7454, -1, 7454, 5751, 7456, -1, 5829, 5832, 7455, -1, 7455, 5832, 7457, -1, 5751, 5756, 7456, -1, 7456, 5756, 7458, -1, 5832, 5835, 7457, -1, 7457, 5835, 7459, -1, 5756, 5761, 7458, -1, 7458, 5761, 7460, -1, 5835, 5839, 7459, -1, 7459, 5839, 7461, -1, 5761, 5766, 7460, -1, 7460, 5766, 7462, -1, 5839, 5844, 7461, -1, 7461, 5844, 7463, -1, 5766, 5771, 7462, -1, 7462, 5771, 7464, -1, 5844, 5849, 7463, -1, 7463, 5849, 7465, -1, 5771, 5774, 7464, -1, 7464, 5774, 7466, -1, 5849, 5854, 7465, -1, 7465, 5854, 7467, -1, 5774, 5777, 7466, -1, 7466, 5777, 7468, -1, 5854, 5859, 7467, -1, 7467, 5859, 7469, -1, 5777, 5780, 7468, -1, 7468, 5780, 7470, -1, 5859, 5863, 7469, -1, 7469, 5863, 7471, -1, 7470, 5783, 7472, -1, 5780, 5783, 7470, -1, 5863, 5868, 7471, -1, 7471, 5868, 7473, -1, 7472, 5784, 7474, -1, 5783, 5784, 7472, -1, 7473, 5873, 7475, -1, 5868, 5873, 7473, -1, 7474, 5789, 7476, -1, 5784, 5789, 7474, -1, 7475, 5878, 7432, -1, 5873, 5878, 7475, -1, 7476, 5792, 7433, -1, 5789, 5792, 7476, -1, 7432, 5883, 7435, -1, 458, 473, 7477, -1, 458, 7477, 7478, -1, 687, 7479, 671, -1, 687, 7480, 7479, -1, 441, 458, 7478, -1, 441, 7478, 7481, -1, 703, 7480, 687, -1, 703, 7482, 7480, -1, 425, 441, 7481, -1, 425, 7481, 7483, -1, 719, 7484, 7482, -1, 719, 7482, 703, -1, 404, 7483, 7485, -1, 404, 425, 7483, -1, 734, 7486, 7484, -1, 734, 7484, 719, -1, 1410, 7487, 7488, -1, 402, 7485, 7489, -1, 402, 404, 7485, -1, 750, 7489, 7486, -1, 750, 7486, 734, -1, 1424, 7488, 7490, -1, 750, 402, 7489, -1, 1424, 1410, 7488, -1, 1395, 7491, 7487, -1, 1395, 7487, 1410, -1, 1453, 1424, 7490, -1, 1453, 7490, 7492, -1, 1364, 7491, 1395, -1, 1364, 7493, 7491, -1, 1493, 1453, 7492, -1, 1493, 7492, 7494, -1, 1337, 7495, 7493, -1, 1337, 7493, 1364, -1, 1524, 1493, 7494, -1, 1524, 7494, 7496, -1, 1309, 7497, 7495, -1, 1309, 7495, 1337, -1, 1552, 1524, 7496, -1, 1552, 7496, 7498, -1, 1304, 7499, 7497, -1, 1304, 7497, 1309, -1, 1451, 7498, 7500, -1, 1451, 1552, 7498, -1, 1282, 7501, 7499, -1, 1282, 7499, 1304, -1, 1458, 7500, 7502, -1, 1458, 1451, 7500, -1, 1257, 7503, 7501, -1, 1257, 7501, 1282, -1, 1468, 7502, 7504, -1, 1468, 1458, 7502, -1, 1231, 7505, 7503, -1, 1231, 7503, 1257, -1, 1478, 7504, 7506, -1, 1478, 1468, 7504, -1, 1200, 7507, 7505, -1, 1200, 7505, 1231, -1, 1485, 7506, 7508, -1, 1485, 1478, 7506, -1, 1148, 7509, 7507, -1, 1148, 7507, 1200, -1, 1588, 7508, 7510, -1, 1588, 1485, 7508, -1, 1147, 577, 7509, -1, 1147, 7509, 1148, -1, 545, 577, 1147, -1, 1597, 7510, 7511, -1, 1597, 1588, 7510, -1, 7512, 545, 1147, -1, 529, 545, 7512, -1, 1605, 7511, 7513, -1, 1605, 1597, 7511, -1, 7514, 529, 7512, -1, 513, 529, 7514, -1, 1614, 7513, 7515, -1, 1614, 1605, 7513, -1, 7516, 513, 7514, -1, 497, 513, 7516, -1, 931, 7515, 7517, -1, 931, 1614, 7515, -1, 7518, 497, 7516, -1, 481, 497, 7518, -1, 932, 931, 7517, -1, 932, 7517, 7519, -1, 7520, 481, 7518, -1, 953, 932, 7519, -1, 466, 481, 7520, -1, 7521, 953, 7519, -1, 7522, 466, 7520, -1, 977, 953, 7521, -1, 450, 466, 7522, -1, 7523, 977, 7521, -1, 7524, 450, 7522, -1, 978, 977, 7523, -1, 434, 450, 7524, -1, 7525, 978, 7523, -1, 7526, 434, 7524, -1, 1010, 978, 7525, -1, 415, 434, 7526, -1, 7527, 1010, 7525, -1, 7528, 415, 7526, -1, 1057, 1010, 7527, -1, 390, 415, 7528, -1, 7529, 1057, 7527, -1, 7530, 390, 7528, -1, 1091, 1057, 7529, -1, 388, 390, 7530, -1, 7531, 1091, 7529, -1, 7532, 388, 7530, -1, 1133, 1091, 7531, -1, 743, 388, 7532, -1, 7533, 1133, 7531, -1, 7534, 743, 7532, -1, 1195, 1133, 7533, -1, 727, 743, 7534, -1, 7535, 1195, 7533, -1, 7536, 727, 7534, -1, 1254, 1195, 7535, -1, 711, 727, 7536, -1, 7537, 1254, 7535, -1, 7538, 711, 7536, -1, 1302, 1254, 7537, -1, 695, 711, 7538, -1, 7539, 1302, 7537, -1, 7540, 695, 7538, -1, 1331, 1302, 7539, -1, 678, 695, 7540, -1, 7541, 1331, 7539, -1, 7542, 678, 7540, -1, 1360, 1331, 7541, -1, 663, 678, 7542, -1, 7543, 1360, 7541, -1, 7544, 663, 7542, -1, 1389, 1360, 7543, -1, 647, 7544, 7545, -1, 647, 663, 7544, -1, 7546, 1389, 7543, -1, 1507, 1389, 7546, -1, 631, 7545, 7547, -1, 631, 647, 7545, -1, 7548, 1507, 7546, -1, 1516, 1507, 7548, -1, 615, 7547, 7549, -1, 615, 631, 7547, -1, 7550, 1516, 7548, -1, 1526, 1516, 7550, -1, 598, 7549, 7551, -1, 598, 615, 7549, -1, 7552, 1526, 7550, -1, 1130, 1526, 7552, -1, 581, 7551, 7553, -1, 581, 598, 7551, -1, 7554, 1130, 7552, -1, 1131, 1130, 7554, -1, 572, 7553, 7555, -1, 572, 581, 7553, -1, 586, 1131, 7554, -1, 556, 7555, 7556, -1, 556, 572, 7555, -1, 588, 7557, 1131, -1, 588, 1131, 586, -1, 538, 7556, 7558, -1, 538, 556, 7556, -1, 606, 7559, 7557, -1, 606, 7557, 588, -1, 522, 7558, 7560, -1, 522, 538, 7558, -1, 622, 7561, 7559, -1, 622, 7559, 606, -1, 505, 7560, 7562, -1, 505, 522, 7560, -1, 638, 7561, 622, -1, 638, 7563, 7561, -1, 489, 7562, 7564, -1, 489, 505, 7562, -1, 654, 7565, 7563, -1, 654, 7563, 638, -1, 473, 7564, 7477, -1, 473, 489, 7564, -1, 671, 7479, 7565, -1, 671, 7565, 654, -1, 3826, 7566, 3814, -1, 7567, 7566, 7568, -1, 3814, 7566, 7567, -1, 7569, 7570, 3779, -1, 7571, 7572, 7573, -1, 3766, 7570, 7574, -1, 7574, 7570, 7569, -1, 3658, 7572, 3852, -1, 3779, 7570, 3766, -1, 7575, 7576, 7577, -1, 7574, 7576, 7578, -1, 7579, 7580, 7571, -1, 7578, 7576, 7575, -1, 7577, 7576, 7574, -1, 7572, 7580, 3852, -1, 7581, 7582, 7583, -1, 7583, 7582, 7584, -1, 7585, 7582, 7581, -1, 3852, 7580, 3839, -1, 7584, 7582, 7585, -1, 7571, 7580, 7572, -1, 7585, 7586, 3629, -1, 7587, 7568, 7588, -1, 3629, 7586, 3619, -1, 7589, 7586, 7585, -1, 3619, 7586, 7589, -1, 7580, 7568, 3839, -1, 7590, 7591, 7592, -1, 3589, 7591, 3578, -1, 3839, 7568, 3826, -1, 3578, 7591, 7590, -1, 7593, 7567, 7587, -1, 7592, 7591, 3589, -1, 7594, 7595, 7590, -1, 7590, 7595, 7596, -1, 7587, 7567, 7568, -1, 7597, 7595, 7594, -1, 7596, 7595, 7597, -1, 3814, 7567, 3803, -1, 7598, 7599, 7600, -1, 7601, 7602, 7593, -1, 7600, 7599, 7603, -1, 7604, 7602, 7601, -1, 7605, 7599, 7598, -1, 7603, 7599, 7605, -1, 7593, 7602, 7567, -1, 3760, 7606, 7607, -1, 7567, 7602, 3803, -1, 3771, 7606, 3760, -1, 3803, 7602, 3791, -1, 7605, 7606, 3771, -1, 7602, 7569, 3791, -1, 7607, 7606, 7605, -1, 7608, 7569, 7604, -1, 7609, 7610, 3724, -1, 3724, 7610, 3711, -1, 7611, 7610, 7609, -1, 3791, 7569, 3779, -1, 3711, 7610, 7611, -1, 7604, 7569, 7602, -1, 7612, 7613, 7611, -1, 7577, 7574, 7608, -1, 7614, 7613, 7615, -1, 7611, 7613, 7614, -1, 7608, 7574, 7569, -1, 7615, 7613, 7612, -1, 3766, 7574, 3754, -1, 3674, 7616, 3675, -1, 7617, 7616, 3674, -1, 7618, 7578, 7575, -1, 3675, 7616, 4008, -1, 7574, 7578, 3754, -1, 7619, 7620, 7617, -1, 4008, 7620, 7619, -1, 7617, 7620, 7616, -1, 3754, 7578, 3733, -1, 7616, 7620, 4008, -1, 7578, 7621, 3733, -1, 7622, 7621, 7618, -1, 7618, 7621, 7578, -1, 3733, 7621, 3713, -1, 7623, 7624, 7622, -1, 7625, 7624, 7623, -1, 3692, 7624, 3666, -1, 3713, 7624, 3692, -1, 7621, 7624, 3713, -1, 7622, 7624, 7621, -1, 7626, 7627, 7625, -1, 7624, 7627, 3666, -1, 3666, 7627, 3649, -1, 7625, 7627, 7624, -1, 7583, 7584, 7626, -1, 7627, 7584, 3649, -1, 7626, 7584, 7627, -1, 3649, 7584, 3639, -1, 7584, 7585, 3639, -1, 7628, 7585, 7581, -1, 3639, 7585, 3629, -1, 7629, 7589, 7628, -1, 3619, 7589, 3609, -1, 7628, 7589, 7585, -1, 7630, 7631, 7629, -1, 7632, 7631, 7630, -1, 7629, 7631, 7589, -1, 3609, 7631, 3599, -1, 7589, 7631, 3609, -1, 7633, 7592, 7632, -1, 3599, 7592, 3589, -1, 7631, 7592, 3599, -1, 7632, 7592, 7631, -1, 7633, 7590, 7592, -1, 7594, 7590, 7633, -1, 3578, 7590, 3574, -1, 7590, 7596, 3574, -1, 7634, 7596, 7597, -1, 3574, 7596, 3874, -1, 7635, 7636, 7634, -1, 7634, 7636, 7596, -1, 7596, 7636, 3874, -1, 3874, 7636, 3857, -1, 7637, 7638, 7635, -1, 7639, 7638, 7637, -1, 7635, 7638, 7636, -1, 7636, 7638, 3857, -1, 3836, 7638, 3816, -1, 3857, 7638, 3836, -1, 7640, 7641, 7639, -1, 7639, 7641, 7638, -1, 3816, 7641, 3796, -1, 7638, 7641, 3816, -1, 7600, 7603, 7640, -1, 7640, 7603, 7641, -1, 3796, 7603, 3789, -1, 7641, 7603, 3796, -1, 7642, 7605, 7598, -1, 3789, 7605, 3771, -1, 7603, 7605, 3789, -1, 7643, 7607, 7642, -1, 3760, 7607, 3748, -1, 7642, 7607, 7605, -1, 7607, 7644, 3748, -1, 7645, 7644, 7643, -1, 7646, 7644, 7645, -1, 3748, 7644, 3735, -1, 7643, 7644, 7607, -1, 7647, 7609, 7646, -1, 3735, 7609, 3724, -1, 7646, 7609, 7644, -1, 7644, 7609, 3735, -1, 7647, 7611, 7609, -1, 7612, 7611, 7647, -1, 3711, 7611, 3699, -1, 7611, 7614, 3699, -1, 7648, 7614, 7615, -1, 3699, 7614, 3688, -1, 7614, 7617, 3688, -1, 7648, 7617, 7614, -1, 7619, 7617, 7648, -1, 3688, 7617, 3674, -1, 3658, 7649, 7572, -1, 3657, 7649, 3658, -1, 7649, 7650, 7572, -1, 7573, 7650, 4030, -1, 4030, 7650, 3657, -1, 3657, 7650, 7649, -1, 7572, 7650, 7573, -1, 7588, 7651, 7579, -1, 7579, 7651, 7580, -1, 7568, 7651, 7588, -1, 7580, 7651, 7568, -1, 7568, 7566, 3826, -1, 7579, 7652, 7588, -1, 7588, 7652, 7653, -1, 7654, 7655, 7656, -1, 7657, 7652, 7658, -1, 7659, 7660, 7661, -1, 7661, 7660, 7662, -1, 7663, 7664, 7665, -1, 7666, 7664, 7663, -1, 7658, 7667, 7666, -1, 7662, 7668, 7008, -1, 7666, 7667, 7664, -1, 7635, 7669, 7670, -1, 7634, 7669, 7635, -1, 7665, 7671, 7001, -1, 7670, 7669, 7654, -1, 7654, 7669, 7655, -1, 6998, 7671, 4010, -1, 7001, 7671, 6998, -1, 7659, 7672, 7660, -1, 7655, 7672, 7659, -1, 7571, 7673, 7579, -1, 7579, 7673, 7652, -1, 7660, 7674, 7662, -1, 7652, 7673, 7658, -1, 7662, 7674, 7668, -1, 7658, 7673, 7667, -1, 7664, 7675, 7665, -1, 7671, 7675, 4010, -1, 7665, 7675, 7671, -1, 7668, 7676, 7008, -1, 4010, 7675, 4017, -1, 7008, 7676, 7006, -1, 7667, 7677, 7664, -1, 7664, 7677, 7675, -1, 7634, 7678, 7669, -1, 7669, 7678, 7655, -1, 7675, 7677, 4017, -1, 7655, 7678, 7672, -1, 4017, 7677, 4021, -1, 7573, 7679, 7571, -1, 7667, 7679, 7677, -1, 7672, 7680, 7660, -1, 7673, 7679, 7667, -1, 7677, 7679, 4021, -1, 7660, 7680, 7674, -1, 7571, 7679, 7673, -1, 4031, 7679, 7573, -1, 4021, 7679, 4031, -1, 7674, 7681, 7668, -1, 7668, 7681, 7676, -1, 7676, 7682, 7006, -1, 7597, 7683, 7634, -1, 7634, 7683, 7678, -1, 7678, 7683, 7672, -1, 7672, 7683, 7680, -1, 7674, 7684, 7681, -1, 7680, 7684, 7674, -1, 7681, 7685, 7676, -1, 7676, 7685, 7682, -1, 7682, 7686, 7006, -1, 7006, 7686, 7004, -1, 7597, 7687, 7683, -1, 7683, 7687, 7680, -1, 7680, 7687, 7684, -1, 7684, 7688, 7681, -1, 7681, 7688, 7685, -1, 7685, 7689, 7682, -1, 7682, 7689, 7686, -1, 7686, 7690, 7004, -1, 7594, 7691, 7597, -1, 7597, 7691, 7687, -1, 7687, 7691, 7684, -1, 7684, 7691, 7688, -1, 7685, 7692, 7689, -1, 7688, 7692, 7685, -1, 7689, 7693, 7686, -1, 7686, 7693, 7690, -1, 7004, 7694, 7002, -1, 7690, 7694, 7004, -1, 7594, 7695, 7691, -1, 7691, 7695, 7688, -1, 7688, 7695, 7692, -1, 7689, 7696, 7693, -1, 7692, 7696, 7689, -1, 7693, 7697, 7690, -1, 7690, 7697, 7694, -1, 7694, 7698, 7002, -1, 7695, 7699, 7692, -1, 7633, 7699, 7594, -1, 7692, 7699, 7696, -1, 7594, 7699, 7695, -1, 7693, 7700, 7697, -1, 7696, 7700, 7693, -1, 7697, 7701, 7694, -1, 7694, 7701, 7698, -1, 7698, 7702, 7002, -1, 7002, 7702, 7000, -1, 7696, 7703, 7700, -1, 7699, 7703, 7696, -1, 7633, 7703, 7699, -1, 7697, 7704, 7701, -1, 7700, 7704, 7697, -1, 7701, 7705, 7698, -1, 7698, 7705, 7702, -1, 7702, 7706, 7000, -1, 7703, 7707, 7700, -1, 7632, 7707, 7633, -1, 7633, 7707, 7703, -1, 7700, 7707, 7704, -1, 7704, 7708, 7701, -1, 7701, 7708, 7705, -1, 7705, 7709, 7702, -1, 7702, 7709, 7706, -1, 7706, 7710, 7000, -1, 7000, 7710, 6997, -1, 7704, 7711, 7708, -1, 7632, 7711, 7707, -1, 7707, 7711, 7704, -1, 7708, 7712, 7705, -1, 7705, 7712, 7709, -1, 7709, 7713, 7706, -1, 7706, 7713, 7710, -1, 7710, 7714, 6997, -1, 7630, 7715, 7632, -1, 7632, 7715, 7711, -1, 7708, 7715, 7712, -1, 7711, 7715, 7708, -1, 7709, 7716, 7713, -1, 7712, 7716, 7709, -1, 7713, 7717, 7710, -1, 7710, 7717, 7714, -1, 7714, 7718, 6997, -1, 6997, 7718, 6995, -1, 7630, 7719, 7715, -1, 7715, 7719, 7712, -1, 7712, 7719, 7716, -1, 7716, 7720, 7713, -1, 7713, 7720, 7717, -1, 7717, 7721, 7714, -1, 7714, 7721, 7718, -1, 7718, 7722, 6995, -1, 7629, 7723, 7630, -1, 7719, 7723, 7716, -1, 7716, 7723, 7720, -1, 7630, 7723, 7719, -1, 7720, 7724, 7717, -1, 7717, 7724, 7721, -1, 7718, 7725, 7722, -1, 7721, 7725, 7718, -1, 7722, 7726, 6995, -1, 6995, 7726, 6993, -1, 7629, 7727, 7723, -1, 7720, 7727, 7724, -1, 7723, 7727, 7720, -1, 7724, 7728, 7721, -1, 7721, 7728, 7725, -1, 7722, 7729, 7726, -1, 7725, 7729, 7722, -1, 7726, 7730, 6993, -1, 7628, 7731, 7629, -1, 7629, 7731, 7727, -1, 7724, 7731, 7728, -1, 7727, 7731, 7724, -1, 7728, 7732, 7725, -1, 7725, 7732, 7729, -1, 7729, 7733, 7726, -1, 7726, 7733, 7730, -1, 7730, 7734, 6993, -1, 6993, 7734, 6992, -1, 7731, 7735, 7728, -1, 7628, 7735, 7731, -1, 7728, 7735, 7732, -1, 7729, 7736, 7733, -1, 7732, 7736, 7729, -1, 7733, 7737, 7730, -1, 7730, 7737, 7734, -1, 7734, 7738, 6992, -1, 7581, 7739, 7628, -1, 7735, 7739, 7732, -1, 7628, 7739, 7735, -1, 7732, 7739, 7736, -1, 7736, 7740, 7733, -1, 7733, 7740, 7737, -1, 7737, 7741, 7734, -1, 7734, 7741, 7738, -1, 6998, 4010, 4012, -1, 7738, 7742, 6992, -1, 6992, 7742, 7031, -1, 7736, 7743, 7740, -1, 7739, 7743, 7736, -1, 7581, 7743, 7739, -1, 7737, 7744, 7741, -1, 7740, 7744, 7737, -1, 7573, 4030, 4031, -1, 7741, 7745, 7738, -1, 7738, 7745, 7742, -1, 3911, 7746, 4003, -1, 7742, 7747, 7031, -1, 4003, 7746, 6999, -1, 7583, 7748, 7581, -1, 7743, 7748, 7740, -1, 7581, 7748, 7743, -1, 3917, 7749, 3911, -1, 7740, 7748, 7744, -1, 7744, 7750, 7741, -1, 3911, 7749, 7746, -1, 7741, 7750, 7745, -1, 3917, 7751, 7749, -1, 3921, 7751, 3917, -1, 7745, 7752, 7742, -1, 7742, 7752, 7747, -1, 7746, 7753, 6999, -1, 6999, 7753, 6996, -1, 7747, 7754, 7031, -1, 7031, 7754, 7029, -1, 7744, 7755, 7750, -1, 7619, 7756, 4008, -1, 3925, 7756, 3921, -1, 4008, 7756, 3925, -1, 7583, 7755, 7748, -1, 3921, 7756, 7751, -1, 7748, 7755, 7744, -1, 7749, 7757, 7746, -1, 7750, 7758, 7745, -1, 7745, 7758, 7752, -1, 7746, 7757, 7753, -1, 7749, 7759, 7757, -1, 7752, 7760, 7747, -1, 7747, 7760, 7754, -1, 7751, 7759, 7749, -1, 7754, 7761, 7029, -1, 7626, 7762, 7583, -1, 6996, 7763, 6994, -1, 7755, 7762, 7750, -1, 7753, 7763, 6996, -1, 7583, 7762, 7755, -1, 7750, 7762, 7758, -1, 7751, 7764, 7759, -1, 7756, 7764, 7751, -1, 7758, 7765, 7752, -1, 7648, 7764, 7619, -1, 7619, 7764, 7756, -1, 7752, 7765, 7760, -1, 7757, 7766, 7753, -1, 7760, 7767, 7754, -1, 7753, 7766, 7763, -1, 7754, 7767, 7761, -1, 7759, 7768, 7757, -1, 7029, 7769, 7027, -1, 7761, 7769, 7029, -1, 7757, 7768, 7766, -1, 7626, 7770, 7762, -1, 7758, 7770, 7765, -1, 7762, 7770, 7758, -1, 6994, 7771, 6991, -1, 7763, 7771, 6994, -1, 7765, 7772, 7760, -1, 7759, 7773, 7768, -1, 7760, 7772, 7767, -1, 7615, 7773, 7648, -1, 7764, 7773, 7759, -1, 7648, 7773, 7764, -1, 7766, 7774, 7763, -1, 7767, 7775, 7761, -1, 7761, 7775, 7769, -1, 7763, 7774, 7771, -1, 7769, 7776, 7027, -1, 7768, 7777, 7766, -1, 7626, 7778, 7770, -1, 7625, 7778, 7626, -1, 7770, 7778, 7765, -1, 7766, 7777, 7774, -1, 7765, 7778, 7772, -1, 6991, 7779, 6990, -1, 7772, 7780, 7767, -1, 7767, 7780, 7775, -1, 7771, 7779, 6991, -1, 7768, 7781, 7777, -1, 7769, 7782, 7776, -1, 7615, 7781, 7773, -1, 7775, 7782, 7769, -1, 7612, 7781, 7615, -1, 7773, 7781, 7768, -1, 7774, 7783, 7771, -1, 7027, 7784, 7025, -1, 7776, 7784, 7027, -1, 7771, 7783, 7779, -1, 7625, 7785, 7778, -1, 7778, 7785, 7772, -1, 7772, 7785, 7780, -1, 7777, 7786, 7774, -1, 7774, 7786, 7783, -1, 7775, 7787, 7782, -1, 7780, 7787, 7775, -1, 7779, 7788, 6990, -1, 7784, 7789, 7025, -1, 6990, 7788, 7030, -1, 7777, 7790, 7786, -1, 7776, 7791, 7784, -1, 7781, 7790, 7777, -1, 7647, 7790, 7612, -1, 7612, 7790, 7781, -1, 7782, 7791, 7776, -1, 7783, 7792, 7779, -1, 7623, 7793, 7625, -1, 7779, 7792, 7788, -1, 7785, 7793, 7780, -1, 7780, 7793, 7787, -1, 7625, 7793, 7785, -1, 7791, 7794, 7784, -1, 7784, 7794, 7789, -1, 7787, 7795, 7782, -1, 7783, 7796, 7792, -1, 7786, 7796, 7783, -1, 7782, 7795, 7791, -1, 7789, 7797, 7025, -1, 7788, 7798, 7030, -1, 7030, 7798, 7028, -1, 7025, 7797, 7023, -1, 7790, 7799, 7786, -1, 7647, 7799, 7790, -1, 7646, 7799, 7647, -1, 7791, 7800, 7794, -1, 7786, 7799, 7796, -1, 7795, 7800, 7791, -1, 7787, 7801, 7795, -1, 7623, 7801, 7793, -1, 7793, 7801, 7787, -1, 7788, 7802, 7798, -1, 7792, 7802, 7788, -1, 7797, 7803, 7023, -1, 7796, 7804, 7792, -1, 7792, 7804, 7802, -1, 7789, 7805, 7797, -1, 7794, 7805, 7789, -1, 7798, 7806, 7028, -1, 7622, 7807, 7623, -1, 7028, 7806, 7026, -1, 7801, 7807, 7795, -1, 7795, 7807, 7800, -1, 7623, 7807, 7801, -1, 7799, 7808, 7796, -1, 7646, 7808, 7799, -1, 7796, 7808, 7804, -1, 7797, 7809, 7803, -1, 7645, 7808, 7646, -1, 7805, 7809, 7797, -1, 7798, 7810, 7806, -1, 7800, 7811, 7794, -1, 7794, 7811, 7805, -1, 7802, 7810, 7798, -1, 7811, 7812, 7805, -1, 7804, 7813, 7802, -1, 7802, 7813, 7810, -1, 7805, 7812, 7809, -1, 7803, 7814, 7023, -1, 7023, 7814, 7021, -1, 7026, 7815, 7024, -1, 7806, 7815, 7026, -1, 7622, 7816, 7807, -1, 7808, 7817, 7804, -1, 7807, 7816, 7800, -1, 7800, 7816, 7811, -1, 7643, 7817, 7645, -1, 7804, 7817, 7813, -1, 7645, 7817, 7808, -1, 7810, 7818, 7806, -1, 7814, 7819, 7021, -1, 7618, 7820, 7622, -1, 7622, 7820, 7816, -1, 7806, 7818, 7815, -1, 7811, 7820, 7812, -1, 7816, 7820, 7811, -1, 7803, 7821, 7814, -1, 7809, 7821, 7803, -1, 7810, 7822, 7818, -1, 7813, 7822, 7810, -1, 7814, 7823, 7819, -1, 7821, 7823, 7814, -1, 7024, 7824, 7022, -1, 7812, 7825, 7809, -1, 7815, 7824, 7024, -1, 7642, 7826, 7643, -1, 7809, 7825, 7821, -1, 7817, 7826, 7813, -1, 7643, 7826, 7817, -1, 7813, 7826, 7822, -1, 7821, 7827, 7823, -1, 7818, 7828, 7815, -1, 7825, 7827, 7821, -1, 7815, 7828, 7824, -1, 7819, 7829, 7021, -1, 7021, 7829, 7019, -1, 7822, 7830, 7818, -1, 7812, 7831, 7825, -1, 7818, 7830, 7828, -1, 7618, 7831, 7820, -1, 7820, 7831, 7812, -1, 7022, 7832, 7020, -1, 7829, 7833, 7019, -1, 7824, 7832, 7022, -1, 7575, 7834, 7618, -1, 7618, 7834, 7831, -1, 7642, 7835, 7826, -1, 7598, 7835, 7642, -1, 7825, 7834, 7827, -1, 7826, 7835, 7822, -1, 7831, 7834, 7825, -1, 7822, 7835, 7830, -1, 7819, 7836, 7829, -1, 7832, 7837, 7020, -1, 7020, 7837, 7018, -1, 7823, 7836, 7819, -1, 7824, 7838, 7832, -1, 7836, 7839, 7829, -1, 7829, 7839, 7833, -1, 7823, 7840, 7836, -1, 7828, 7838, 7824, -1, 7827, 7840, 7823, -1, 7832, 7841, 7837, -1, 7838, 7841, 7832, -1, 7840, 7842, 7836, -1, 7830, 7843, 7828, -1, 7836, 7842, 7839, -1, 7828, 7843, 7838, -1, 7838, 7844, 7841, -1, 7019, 7845, 7017, -1, 7843, 7844, 7838, -1, 7833, 7845, 7019, -1, 7827, 7846, 7840, -1, 7837, 7847, 7018, -1, 7575, 7846, 7834, -1, 7834, 7846, 7827, -1, 7840, 7848, 7842, -1, 7598, 7849, 7835, -1, 7577, 7848, 7575, -1, 7835, 7849, 7830, -1, 7846, 7848, 7840, -1, 7830, 7849, 7843, -1, 7575, 7848, 7846, -1, 7833, 7850, 7845, -1, 7839, 7850, 7833, -1, 7600, 7849, 7598, -1, 7847, 7851, 7018, -1, 7018, 7851, 7016, -1, 7843, 7852, 7844, -1, 7842, 7853, 7839, -1, 7849, 7852, 7843, -1, 7600, 7852, 7849, -1, 7839, 7853, 7850, -1, 7837, 7854, 7847, -1, 7841, 7854, 7837, -1, 7845, 7855, 7017, -1, 7017, 7855, 7015, -1, 7854, 7856, 7847, -1, 7847, 7856, 7851, -1, 7842, 7857, 7853, -1, 7848, 7857, 7842, -1, 7577, 7857, 7848, -1, 7844, 7858, 7841, -1, 7841, 7858, 7854, -1, 7850, 7859, 7845, -1, 7845, 7859, 7855, -1, 7854, 7860, 7856, -1, 7858, 7860, 7854, -1, 7850, 7861, 7859, -1, 7851, 7862, 7016, -1, 7853, 7861, 7850, -1, 7852, 7863, 7844, -1, 7855, 7864, 7015, -1, 7640, 7863, 7600, -1, 7600, 7863, 7852, -1, 7844, 7863, 7858, -1, 7015, 7864, 7013, -1, 7608, 7865, 7577, -1, 7016, 7866, 7014, -1, 7857, 7865, 7853, -1, 7862, 7866, 7016, -1, 7577, 7865, 7857, -1, 7853, 7865, 7861, -1, 7640, 7867, 7863, -1, 7858, 7867, 7860, -1, 7859, 7868, 7855, -1, 7863, 7867, 7858, -1, 7856, 7869, 7851, -1, 7855, 7868, 7864, -1, 7851, 7869, 7862, -1, 7861, 7870, 7859, -1, 7859, 7870, 7868, -1, 7869, 7871, 7862, -1, 7862, 7871, 7866, -1, 7864, 7872, 7013, -1, 7856, 7873, 7869, -1, 7860, 7873, 7856, -1, 7013, 7872, 7011, -1, 7604, 7874, 7608, -1, 7866, 7875, 7014, -1, 7608, 7874, 7865, -1, 7861, 7874, 7870, -1, 7865, 7874, 7861, -1, 7868, 7876, 7864, -1, 7869, 7877, 7871, -1, 7873, 7877, 7869, -1, 7864, 7876, 7872, -1, 7639, 7878, 7640, -1, 7868, 7879, 7876, -1, 7860, 7878, 7873, -1, 7640, 7878, 7867, -1, 7870, 7879, 7868, -1, 7867, 7878, 7860, -1, 7014, 7880, 7012, -1, 7872, 7881, 7011, -1, 7875, 7880, 7014, -1, 7871, 7882, 7866, -1, 7011, 7881, 7009, -1, 7866, 7882, 7875, -1, 7601, 7883, 7604, -1, 7604, 7883, 7874, -1, 7874, 7883, 7870, -1, 7639, 7884, 7878, -1, 7870, 7883, 7879, -1, 7873, 7884, 7877, -1, 7878, 7884, 7873, -1, 7876, 7885, 7872, -1, 7872, 7885, 7881, -1, 7882, 7886, 7875, -1, 7875, 7886, 7880, -1, 7876, 7887, 7885, -1, 7871, 7888, 7882, -1, 7879, 7887, 7876, -1, 7877, 7888, 7871, -1, 7881, 7889, 7009, -1, 7880, 7890, 7012, -1, 7009, 7889, 7007, -1, 7882, 7891, 7886, -1, 7593, 7892, 7601, -1, 7888, 7891, 7882, -1, 7601, 7892, 7883, -1, 7883, 7892, 7879, -1, 7879, 7892, 7887, -1, 7637, 7893, 7639, -1, 7639, 7893, 7884, -1, 7881, 7894, 7889, -1, 7884, 7893, 7877, -1, 7877, 7893, 7888, -1, 7885, 7894, 7881, -1, 7887, 7895, 7885, -1, 7886, 7896, 7880, -1, 7880, 7896, 7890, -1, 7885, 7895, 7894, -1, 7012, 7897, 7010, -1, 7890, 7897, 7012, -1, 7889, 7898, 7007, -1, 7007, 7898, 7005, -1, 7637, 7899, 7893, -1, 7587, 7900, 7593, -1, 7888, 7899, 7891, -1, 7593, 7900, 7892, -1, 7893, 7899, 7888, -1, 7886, 7901, 7896, -1, 7892, 7900, 7887, -1, 7887, 7900, 7895, -1, 7891, 7901, 7886, -1, 7894, 7902, 7889, -1, 7890, 7656, 7897, -1, 7889, 7902, 7898, -1, 7895, 7657, 7894, -1, 7894, 7657, 7902, -1, 7896, 7656, 7890, -1, 7897, 7661, 7010, -1, 7005, 7663, 7003, -1, 7637, 7903, 7899, -1, 7898, 7663, 7005, -1, 7891, 7903, 7901, -1, 7635, 7903, 7637, -1, 7899, 7903, 7891, -1, 7896, 7654, 7656, -1, 7588, 7653, 7587, -1, 7895, 7653, 7657, -1, 7587, 7653, 7900, -1, 7900, 7653, 7895, -1, 7901, 7654, 7896, -1, 7656, 7659, 7897, -1, 7902, 7666, 7898, -1, 7898, 7666, 7663, -1, 7897, 7659, 7661, -1, 7661, 7662, 7010, -1, 7902, 7658, 7666, -1, 7657, 7658, 7902, -1, 7010, 7662, 7008, -1, 7903, 7670, 7901, -1, 7635, 7670, 7903, -1, 7901, 7670, 7654, -1, 7003, 7665, 7001, -1, 7663, 7665, 7003, -1, 7656, 7655, 7659, -1, 7653, 7652, 7657, -1, 7904, 7905, 7906, -1, 7904, 7906, 7907, -1, 7908, 4296, 7909, -1, 7908, 7910, 7911, -1, 7908, 4259, 4296, -1, 7908, 7909, 7910, -1, 7912, 7907, 4672, -1, 7913, 7911, 7905, -1, 7913, 7905, 7904, -1, 7914, 7904, 7907, -1, 7914, 7907, 7912, -1, 7915, 7908, 7911, -1, 7915, 7911, 7913, -1, 7915, 4259, 7908, -1, 7916, 4672, 4671, -1, 7916, 7912, 4672, -1, 4280, 3657, 3659, -1, 7917, 7913, 7904, -1, 7917, 7904, 7914, -1, 7918, 7914, 7912, -1, 7918, 7912, 7916, -1, 7919, 7915, 7913, -1, 7919, 4259, 7915, -1, 7919, 7913, 7917, -1, 7919, 4257, 4259, -1, 7920, 7916, 4671, -1, 7921, 7917, 7914, -1, 7921, 7914, 7918, -1, 7922, 7918, 7916, -1, 7922, 7916, 7920, -1, 7923, 7919, 7917, -1, 7923, 7917, 7921, -1, 7923, 4257, 7919, -1, 7924, 4671, 4707, -1, 7924, 7920, 4671, -1, 7925, 7921, 7918, -1, 7925, 7918, 7922, -1, 7926, 7922, 7920, -1, 7926, 7920, 7924, -1, 7927, 4295, 4257, -1, 7927, 7921, 7925, -1, 7927, 4257, 7923, -1, 7927, 7923, 7921, -1, 7928, 7924, 4707, -1, 7929, 7925, 7922, -1, 7929, 7922, 7926, -1, 7930, 7926, 7924, -1, 7930, 7924, 7928, -1, 7931, 4295, 7927, -1, 7931, 7925, 7929, -1, 7931, 7927, 7925, -1, 7932, 4707, 4706, -1, 7932, 7928, 4707, -1, 7933, 7929, 7926, -1, 7933, 7926, 7930, -1, 7934, 7930, 7928, -1, 7934, 7928, 7932, -1, 7935, 7929, 7933, -1, 7935, 4295, 7931, -1, 7935, 4293, 4295, -1, 7935, 7931, 7929, -1, 7936, 7932, 4706, -1, 7937, 7930, 7934, -1, 7937, 7933, 7930, -1, 7938, 7934, 7932, -1, 7938, 7932, 7936, -1, 7939, 7935, 7933, -1, 7939, 4293, 7935, -1, 7939, 7933, 7937, -1, 7940, 4706, 4705, -1, 7940, 7936, 4706, -1, 7941, 7937, 7934, -1, 7941, 7934, 7938, -1, 7942, 7938, 7936, -1, 7942, 7936, 7940, -1, 7943, 4293, 7939, -1, 7943, 7937, 7941, -1, 7943, 7939, 7937, -1, 7943, 4253, 4293, -1, 7944, 7940, 4705, -1, 7945, 7938, 7942, -1, 7945, 7941, 7938, -1, 7946, 7942, 7940, -1, 7946, 7940, 7944, -1, 7947, 7941, 7945, -1, 7947, 7943, 7941, -1, 7947, 4253, 7943, -1, 7948, 4705, 4704, -1, 7948, 7944, 4705, -1, 7949, 7945, 7942, -1, 7949, 7942, 7946, -1, 7950, 7946, 7944, -1, 7950, 7944, 7948, -1, 7951, 7947, 7945, -1, 7951, 7945, 7949, -1, 7951, 4253, 7947, -1, 7951, 4252, 4253, -1, 7952, 7948, 4704, -1, 7953, 7949, 7946, -1, 7953, 7946, 7950, -1, 7954, 7950, 7948, -1, 7954, 7948, 7952, -1, 7955, 7951, 7949, -1, 7955, 7949, 7953, -1, 7955, 4252, 7951, -1, 7956, 4704, 4702, -1, 7956, 7952, 4704, -1, 7957, 7953, 7950, -1, 7957, 7950, 7954, -1, 7958, 7954, 7952, -1, 7958, 7952, 7956, -1, 7959, 7955, 7953, -1, 7959, 4292, 4252, -1, 7959, 7953, 7957, -1, 7959, 4252, 7955, -1, 7960, 7956, 4702, -1, 7961, 7957, 7954, -1, 7961, 7954, 7958, -1, 7962, 7958, 7956, -1, 7962, 7956, 7960, -1, 7963, 4292, 7959, -1, 7963, 7957, 7961, -1, 7963, 7959, 7957, -1, 7964, 4702, 4700, -1, 7964, 7960, 4702, -1, 7965, 7961, 7958, -1, 7965, 7958, 7962, -1, 7966, 7960, 7964, -1, 7966, 7962, 7960, -1, 7967, 7963, 7961, -1, 7967, 7961, 7965, -1, 7967, 4291, 4292, -1, 7967, 4292, 7963, -1, 7968, 7964, 4700, -1, 7969, 7965, 7962, -1, 7969, 7962, 7966, -1, 7970, 7966, 7964, -1, 7970, 7964, 7968, -1, 7971, 7965, 7969, -1, 7971, 4291, 7967, -1, 7971, 7967, 7965, -1, 7972, 7968, 4700, -1, 7972, 4700, 4698, -1, 7973, 7966, 7970, -1, 7973, 7969, 7966, -1, 7974, 7970, 7968, -1, 3675, 4242, 3677, -1, 7974, 7968, 7972, -1, 7975, 3858, 3855, -1, 7976, 7969, 7973, -1, 7976, 7971, 7969, -1, 7976, 4291, 7971, -1, 7975, 3855, 4703, -1, 7976, 4289, 4291, -1, 7977, 7973, 7970, -1, 7978, 3861, 3858, -1, 7977, 7970, 7974, -1, 7978, 3858, 7975, -1, 7979, 3865, 3861, -1, 7980, 7972, 4698, -1, 7979, 3861, 7978, -1, 7981, 7976, 7973, -1, 7982, 3865, 7979, -1, 7981, 7973, 7977, -1, 7982, 3659, 3865, -1, 7981, 4289, 7976, -1, 7982, 4280, 3659, -1, 7983, 7974, 7972, -1, 7984, 7975, 4703, -1, 7983, 7972, 7980, -1, 7984, 4703, 4701, -1, 7985, 7978, 7975, -1, 7986, 7980, 4698, -1, 7986, 4698, 4696, -1, 7985, 7975, 7984, -1, 7987, 7977, 7974, -1, 7987, 7974, 7983, -1, 7988, 7978, 7985, -1, 7988, 7979, 7978, -1, 7989, 7983, 7980, -1, 7990, 7979, 7988, -1, 7989, 7980, 7986, -1, 7990, 4310, 4280, -1, 7990, 4309, 4310, -1, 7990, 4280, 7982, -1, 7990, 7982, 7979, -1, 7991, 7981, 7977, -1, 7991, 4289, 7981, -1, 7991, 7977, 7987, -1, 7992, 7984, 4701, -1, 7992, 4701, 4699, -1, 7991, 4288, 4289, -1, 7993, 7983, 7989, -1, 7993, 7987, 7983, -1, 7994, 7985, 7984, -1, 7994, 7984, 7992, -1, 7995, 7986, 4696, -1, 7996, 7988, 7985, -1, 7997, 7991, 7987, -1, 7996, 7985, 7994, -1, 7997, 4288, 7991, -1, 7997, 7987, 7993, -1, 7998, 7988, 7996, -1, 7999, 7995, 4696, -1, 7998, 7990, 7988, -1, 7998, 4309, 7990, -1, 7999, 4696, 4694, -1, 8000, 7989, 7986, -1, 8001, 4699, 4697, -1, 8001, 7992, 4699, -1, 8000, 7986, 7995, -1, 8002, 7995, 7999, -1, 8002, 8000, 7995, -1, 8003, 7992, 8001, -1, 8004, 7993, 7989, -1, 8003, 7994, 7992, -1, 8004, 7989, 8000, -1, 8005, 7996, 7994, -1, 8005, 7994, 8003, -1, 8006, 7998, 7996, -1, 8007, 8004, 8000, -1, 8006, 4309, 7998, -1, 8006, 4275, 4309, -1, 8007, 8000, 8002, -1, 8006, 7996, 8005, -1, 8008, 7997, 7993, -1, 8008, 4288, 7997, -1, 8009, 4697, 4695, -1, 8008, 4286, 4288, -1, 8008, 7993, 8004, -1, 8009, 8001, 4697, -1, 8010, 7999, 4694, -1, 8011, 8001, 8009, -1, 8012, 8004, 8007, -1, 8011, 8003, 8001, -1, 8012, 8008, 8004, -1, 8012, 4286, 8008, -1, 8013, 8010, 4694, -1, 8014, 8003, 8011, -1, 8013, 4694, 4692, -1, 8014, 8005, 8003, -1, 8015, 8002, 7999, -1, 8016, 4275, 8006, -1, 8016, 8005, 8014, -1, 8016, 4274, 4275, -1, 8015, 7999, 8010, -1, 8016, 8006, 8005, -1, 8017, 8009, 4695, -1, 8018, 8010, 8013, -1, 8017, 4695, 4693, -1, 8018, 8015, 8010, -1, 8019, 8002, 8015, -1, 8019, 8007, 8002, -1, 8020, 8009, 8017, -1, 8021, 8019, 8015, -1, 8020, 8011, 8009, -1, 8022, 8014, 8011, -1, 8021, 8015, 8018, -1, 8023, 4284, 4286, -1, 8022, 8011, 8020, -1, 8023, 8012, 8007, -1, 8024, 4274, 8016, -1, 8023, 4286, 8012, -1, 8023, 8007, 8019, -1, 8024, 4308, 4274, -1, 8024, 8014, 8022, -1, 8024, 8016, 8014, -1, 8025, 8017, 4693, -1, 8026, 8013, 4692, -1, 8027, 4284, 8023, -1, 8027, 8019, 8021, -1, 8025, 4693, 4691, -1, 8027, 8023, 8019, -1, 8028, 4692, 4690, -1, 8029, 8017, 8025, -1, 8028, 8026, 4692, -1, 8030, 8018, 8013, -1, 8029, 8020, 8017, -1, 8030, 8013, 8026, -1, 8031, 8022, 8020, -1, 8032, 8030, 8026, -1, 8031, 8020, 8029, -1, 8032, 8026, 8028, -1, 8033, 8022, 8031, -1, 8033, 4308, 8024, -1, 8033, 4306, 4308, -1, 8034, 8021, 8018, -1, 8034, 8018, 8030, -1, 8033, 8024, 8022, -1, 8035, 8034, 8030, -1, 8036, 4691, 4689, -1, 8036, 8025, 4691, -1, 8035, 8030, 8032, -1, 8037, 8025, 8036, -1, 8038, 4284, 8027, -1, 8038, 8027, 8021, -1, 8038, 8021, 8034, -1, 8038, 4279, 4284, -1, 8037, 8029, 8025, -1, 8039, 8028, 4690, -1, 8040, 8031, 8029, -1, 8040, 8029, 8037, -1, 8041, 8034, 8035, -1, 8041, 8038, 8034, -1, 8041, 4279, 8038, -1, 8042, 8033, 8031, -1, 8042, 4306, 8033, -1, 8042, 4267, 4306, -1, 8043, 8032, 8028, -1, 8042, 8031, 8040, -1, 8044, 8036, 4689, -1, 8043, 8028, 8039, -1, 8044, 4689, 4687, -1, 8045, 8035, 8032, -1, 8045, 8032, 8043, -1, 8046, 8036, 8044, -1, 8046, 8037, 8036, -1, 8047, 8041, 8035, -1, 8047, 8035, 8045, -1, 8047, 4279, 8041, -1, 8047, 4240, 4279, -1, 8048, 4690, 4688, -1, 8049, 8037, 8046, -1, 8048, 8039, 4690, -1, 8049, 8040, 8037, -1, 8050, 8042, 8040, -1, 8050, 4271, 4267, -1, 8051, 8043, 8039, -1, 8051, 8039, 8048, -1, 8050, 4267, 8042, -1, 8050, 8040, 8049, -1, 8052, 4687, 4685, -1, 8052, 8044, 4687, -1, 8053, 8045, 8043, -1, 8053, 8043, 8051, -1, 8054, 8052, 4685, -1, 8055, 8045, 8053, -1, 8055, 8047, 8045, -1, 8056, 8046, 8044, -1, 8055, 4240, 8047, -1, 8055, 4239, 4240, -1, 8057, 4688, 4686, -1, 8056, 8044, 8052, -1, 8057, 8048, 4688, -1, 8058, 8052, 8054, -1, 8059, 8048, 8057, -1, 8058, 8056, 8052, -1, 8059, 8051, 8048, -1, 8060, 8049, 8046, -1, 8060, 8046, 8056, -1, 8061, 8051, 8059, -1, 8061, 8053, 8051, -1, 8062, 8056, 8058, -1, 8062, 8060, 8056, -1, 8063, 4271, 8050, -1, 8063, 4305, 4271, -1, 8064, 8055, 8053, -1, 8064, 8053, 8061, -1, 8063, 8050, 8049, -1, 8064, 4239, 8055, -1, 8063, 8049, 8060, -1, 8064, 4270, 4239, -1, 8065, 4685, 4683, -1, 8066, 4686, 4684, -1, 8065, 8054, 4685, -1, 8066, 8057, 4686, -1, 8067, 4304, 4305, -1, 8067, 8060, 8062, -1, 8067, 4305, 8063, -1, 8068, 8059, 8057, -1, 8067, 8063, 8060, -1, 8068, 8057, 8066, -1, 8069, 8065, 4683, -1, 8070, 8061, 8059, -1, 8071, 8054, 8065, -1, 8070, 8059, 8068, -1, 8071, 8058, 8054, -1, 8072, 8064, 8061, -1, 8073, 8065, 8069, -1, 8072, 4270, 8064, -1, 8072, 4262, 4270, -1, 8072, 8061, 8070, -1, 8073, 8071, 8065, -1, 8074, 4684, 4682, -1, 8075, 8058, 8071, -1, 8074, 8066, 4684, -1, 8075, 8062, 8058, -1, 8076, 8071, 8073, -1, 8077, 8066, 8074, -1, 8077, 8068, 8066, -1, 8076, 8075, 8071, -1, 8078, 8067, 8062, -1, 8078, 8062, 8075, -1, 8078, 4304, 8067, -1, 8079, 8068, 8077, -1, 8079, 8070, 8068, -1, 8080, 4683, 4680, -1, 8080, 8069, 4683, -1, 8081, 8070, 8079, -1, 8082, 8078, 8075, -1, 8081, 4234, 4262, -1, 8082, 8075, 8076, -1, 8081, 8072, 8070, -1, 8082, 4304, 8078, -1, 8081, 4262, 8072, -1, 8082, 4302, 4304, -1, 8083, 8080, 4680, -1, 8084, 4682, 4681, -1, 8084, 8074, 4682, -1, 8085, 8069, 8080, -1, 8086, 8074, 8084, -1, 8085, 8073, 8069, -1, 8086, 8077, 8074, -1, 8087, 8085, 8080, -1, 8087, 8080, 8083, -1, 8088, 8077, 8086, -1, 8089, 8076, 8073, -1, 8088, 8079, 8077, -1, 8089, 8073, 8085, -1, 8090, 8079, 8088, -1, 8090, 4233, 4234, -1, 8091, 8085, 8087, -1, 8090, 4234, 8081, -1, 8091, 8089, 8085, -1, 8090, 8081, 8079, -1, 8092, 8082, 8076, -1, 8092, 4302, 8082, -1, 8092, 8076, 8089, -1, 8093, 4681, 4679, -1, 8094, 4680, 4678, -1, 8093, 8084, 4681, -1, 8095, 8084, 8093, -1, 8095, 8086, 8084, -1, 8094, 8083, 4680, -1, 8096, 8089, 8091, -1, 8096, 4302, 8092, -1, 8096, 8092, 8089, -1, 8097, 8088, 8086, -1, 8096, 4301, 4302, -1, 8098, 8087, 8083, -1, 8098, 8083, 8094, -1, 8097, 8086, 8095, -1, 8099, 8090, 8088, -1, 8099, 4233, 8090, -1, 8099, 8088, 8097, -1, 8099, 4249, 4233, -1, 8100, 8094, 4678, -1, 8101, 4679, 4677, -1, 8102, 8091, 8087, -1, 8102, 8087, 8098, -1, 8101, 8093, 4679, -1, 8103, 8095, 8093, -1, 8104, 8098, 8094, -1, 8104, 8094, 8100, -1, 8103, 8093, 8101, -1, 8105, 8096, 8091, -1, 8105, 4301, 8096, -1, 8105, 8091, 8102, -1, 8106, 8095, 8103, -1, 8107, 8098, 8104, -1, 8107, 8102, 8098, -1, 8106, 8097, 8095, -1, 8108, 8099, 8097, -1, 8108, 4249, 8099, -1, 8108, 8097, 8106, -1, 8109, 4678, 4676, -1, 8109, 8100, 4678, -1, 8108, 4243, 4249, -1, 8110, 4675, 3662, -1, 8110, 4677, 4675, -1, 8110, 8101, 4677, -1, 8111, 4301, 8105, -1, 8111, 4299, 4301, -1, 8111, 8105, 8102, -1, 8110, 3662, 3664, -1, 8111, 8102, 8107, -1, 8112, 8100, 8109, -1, 8112, 8104, 8100, -1, 8113, 8103, 8101, -1, 8113, 8110, 3664, -1, 8113, 3664, 3669, -1, 8113, 8101, 8110, -1, 8114, 8106, 8103, -1, 8115, 8109, 4676, -1, 8114, 8103, 8113, -1, 8116, 8104, 8112, -1, 8114, 8113, 3669, -1, 8114, 3669, 3671, -1, 8116, 8107, 8104, -1, 8117, 8108, 8106, -1, 8117, 4243, 8108, -1, 8117, 8114, 3671, -1, 8117, 3671, 3677, -1, 8118, 8112, 8109, -1, 8117, 8106, 8114, -1, 8117, 3677, 4242, -1, 8117, 4242, 4243, -1, 8118, 8109, 8115, -1, 8119, 4299, 8111, -1, 8119, 8111, 8107, -1, 8119, 8107, 8116, -1, 8120, 4676, 4674, -1, 8120, 8115, 4676, -1, 8121, 8116, 8112, -1, 8121, 8112, 8118, -1, 8122, 8118, 8115, -1, 8122, 8115, 8120, -1, 8123, 4299, 8119, -1, 8123, 4297, 4299, -1, 8123, 8116, 8121, -1, 8123, 8119, 8116, -1, 8124, 8120, 4674, -1, 8125, 8121, 8118, -1, 8125, 8118, 8122, -1, 8126, 8120, 8124, -1, 8126, 8122, 8120, -1, 8127, 8123, 8121, -1, 8127, 4297, 8123, -1, 8127, 8121, 8125, -1, 8128, 4674, 4673, -1, 8128, 8124, 4674, -1, 8129, 8122, 8126, -1, 8129, 8125, 8122, -1, 8130, 8126, 8124, -1, 8130, 8124, 8128, -1, 8131, 8127, 8125, -1, 8131, 4297, 8127, -1, 8131, 8125, 8129, -1, 8131, 4296, 4297, -1, 7906, 8128, 4673, -1, 7910, 8126, 8130, -1, 7910, 8129, 8126, -1, 7905, 8130, 8128, -1, 7905, 8128, 7906, -1, 7909, 8129, 7910, -1, 7909, 4296, 8131, -1, 7909, 8131, 8129, -1, 7907, 4673, 4672, -1, 7907, 7906, 4673, -1, 7911, 7910, 8130, -1, 7911, 8130, 7905, -1, 8132, 4601, 4597, -1, 8133, 8134, 7340, -1, 8135, 8136, 8137, -1, 8133, 7340, 7342, -1, 8135, 8138, 8136, -1, 8139, 8140, 8134, -1, 8139, 8134, 8133, -1, 8141, 8142, 8143, -1, 8141, 8143, 8144, -1, 8141, 8137, 8142, -1, 8141, 8135, 8137, -1, 8145, 8146, 8140, -1, 8147, 8144, 8148, -1, 8147, 8138, 8135, -1, 8145, 8140, 8139, -1, 8147, 8149, 8138, -1, 8147, 8141, 8144, -1, 8147, 8135, 8141, -1, 8150, 8151, 8152, -1, 8150, 8152, 8153, -1, 8154, 8146, 8145, -1, 8150, 8153, 8155, -1, 8156, 8150, 8155, -1, 8154, 8157, 8146, -1, 8156, 8151, 8150, -1, 8158, 8159, 8152, -1, 8158, 8152, 8151, -1, 8160, 4605, 4601, -1, 8158, 8143, 8159, -1, 8161, 7342, 7343, -1, 8161, 8133, 7342, -1, 8162, 8156, 8155, -1, 8162, 8151, 8156, -1, 8162, 8163, 8151, -1, 8162, 8155, 8164, -1, 8162, 8164, 8163, -1, 8165, 8143, 8158, -1, 8166, 8139, 8133, -1, 8165, 8148, 8144, -1, 8165, 8144, 8143, -1, 8166, 8133, 8161, -1, 8167, 8165, 8158, -1, 8168, 8145, 8139, -1, 8169, 8151, 8163, -1, 8169, 8163, 8170, -1, 8168, 8139, 8166, -1, 8171, 8154, 8145, -1, 8171, 8145, 8168, -1, 8172, 4605, 8173, -1, 8174, 8169, 8170, -1, 8172, 4609, 4605, -1, 8174, 8170, 8175, -1, 8176, 8169, 8174, -1, 8176, 8177, 8169, -1, 8178, 7345, 7347, -1, 8178, 8179, 7345, -1, 8180, 8176, 8174, -1, 8180, 8174, 8175, -1, 8180, 8175, 8181, -1, 8180, 8181, 8182, -1, 8183, 8184, 8177, -1, 8183, 8177, 8176, -1, 8183, 8176, 8180, -1, 8185, 8179, 8178, -1, 8183, 8180, 8182, -1, 8183, 8182, 8186, -1, 8185, 8187, 8179, -1, 8188, 8168, 8166, -1, 8189, 8190, 8187, -1, 8189, 8187, 8185, -1, 8191, 8168, 8188, -1, 8191, 8192, 8171, -1, 8191, 8193, 8192, -1, 8191, 8188, 8194, -1, 8191, 8171, 8168, -1, 8191, 8195, 8193, -1, 8196, 8190, 8189, -1, 8196, 8197, 8190, -1, 8198, 8178, 7347, -1, 8199, 8197, 8196, -1, 8199, 8200, 8197, -1, 8201, 8187, 8190, -1, 8202, 8203, 8195, -1, 8204, 8178, 8198, -1, 8202, 8205, 8203, -1, 8202, 8197, 8205, -1, 8202, 8206, 8201, -1, 8204, 8185, 8178, -1, 8202, 8201, 8190, -1, 8202, 8190, 8197, -1, 8207, 4613, 8208, -1, 8209, 8210, 4609, -1, 8207, 8200, 8199, -1, 8209, 8211, 8212, -1, 8209, 4609, 8211, -1, 8207, 8208, 8200, -1, 8213, 8195, 8203, -1, 8213, 8212, 8193, -1, 8213, 8203, 8214, -1, 8215, 7347, 7349, -1, 8213, 8214, 8210, -1, 8213, 8210, 8209, -1, 8215, 8198, 7347, -1, 8213, 8209, 8212, -1, 8213, 8193, 8195, -1, 8216, 8217, 8218, -1, 8216, 8219, 8217, -1, 8220, 8185, 8204, -1, 8216, 8218, 8221, -1, 8220, 8189, 8185, -1, 8222, 8204, 8198, -1, 8223, 8224, 8219, -1, 8222, 8198, 8215, -1, 8223, 8225, 8224, -1, 8223, 8219, 8216, -1, 8226, 8196, 8189, -1, 8226, 8189, 8220, -1, 8227, 8223, 8216, -1, 8228, 8204, 8222, -1, 8228, 8220, 8204, -1, 8229, 8199, 8196, -1, 8229, 8196, 8226, -1, 8230, 8221, 8231, -1, 8230, 8231, 8232, -1, 8233, 8226, 8220, -1, 8230, 8232, 8234, -1, 8233, 8220, 8228, -1, 8235, 8207, 8199, -1, 8235, 8199, 8229, -1, 8235, 4617, 4613, -1, 8235, 4613, 8207, -1, 8236, 8230, 8234, -1, 8236, 8237, 8230, -1, 8238, 8215, 7349, -1, 8236, 8234, 8239, -1, 8236, 8239, 8240, -1, 8241, 8229, 8226, -1, 8242, 8243, 8244, -1, 8241, 8226, 8233, -1, 8242, 8234, 8245, -1, 8242, 8245, 8243, -1, 8246, 8222, 8215, -1, 8247, 8239, 8234, -1, 8247, 8240, 8239, -1, 8246, 8215, 8238, -1, 8247, 8234, 8242, -1, 8248, 8229, 8241, -1, 8248, 8235, 8229, -1, 8248, 4617, 8235, -1, 8249, 8247, 8242, -1, 8250, 8228, 8222, -1, 8250, 8222, 8246, -1, 8251, 8244, 8252, -1, 8251, 8252, 8253, -1, 8254, 7349, 7351, -1, 8254, 8238, 7349, -1, 8255, 8233, 8228, -1, 8255, 8228, 8250, -1, 8256, 8246, 8238, -1, 8257, 8258, 8251, -1, 8256, 8238, 8254, -1, 8257, 8253, 8259, -1, 8260, 8241, 8233, -1, 8257, 8251, 8253, -1, 8260, 8233, 8255, -1, 8261, 8257, 8259, -1, 8262, 8250, 8246, -1, 8261, 8263, 8264, -1, 8262, 8246, 8256, -1, 8261, 8259, 8263, -1, 8265, 8264, 8266, -1, 8265, 8258, 8257, -1, 8267, 8248, 8241, -1, 8267, 4617, 8248, -1, 8265, 8268, 8258, -1, 8267, 8241, 8260, -1, 8265, 8261, 8264, -1, 8265, 8257, 8261, -1, 8267, 4621, 4617, -1, 8269, 8270, 8271, -1, 8272, 8255, 8250, -1, 8272, 8250, 8262, -1, 8269, 8263, 8273, -1, 8269, 8273, 8270, -1, 8274, 8266, 8264, -1, 8275, 8254, 7351, -1, 8274, 8263, 8269, -1, 8274, 8264, 8263, -1, 8276, 8260, 8255, -1, 8276, 8255, 8272, -1, 8277, 8274, 8269, -1, 8278, 8254, 8275, -1, 8278, 8256, 8254, -1, 8279, 8271, 8280, -1, 8281, 8267, 8260, -1, 8279, 8280, 8282, -1, 8281, 4621, 8267, -1, 8281, 8260, 8276, -1, 8283, 8256, 8278, -1, 8283, 8262, 8256, -1, 8284, 7351, 7353, -1, 8285, 8279, 8282, -1, 8284, 8275, 7351, -1, 8285, 8282, 8286, -1, 8287, 8272, 8262, -1, 8287, 8262, 8283, -1, 8288, 8279, 8285, -1, 8288, 8289, 8279, -1, 8290, 8278, 8275, -1, 8290, 8275, 8284, -1, 8291, 8286, 8292, -1, 8291, 8292, 8293, -1, 8291, 8288, 8285, -1, 8294, 8276, 8272, -1, 8291, 8285, 8286, -1, 8295, 8293, 8296, -1, 8294, 8272, 8287, -1, 8295, 8291, 8293, -1, 8295, 8289, 8288, -1, 8297, 8283, 8278, -1, 8295, 8298, 8289, -1, 8295, 8288, 8291, -1, 8297, 8278, 8290, -1, 8299, 8300, 8301, -1, 8299, 8301, 8302, -1, 8299, 8303, 8300, -1, 8304, 4621, 8281, -1, 8304, 8281, 8276, -1, 8304, 4625, 4621, -1, 8304, 8276, 8294, -1, 8305, 8303, 8299, -1, 8305, 8299, 8302, -1, 8306, 8307, 8300, -1, 8306, 8300, 8303, -1, 8308, 8284, 7353, -1, 8306, 8292, 8307, -1, 8309, 8283, 8297, -1, 8310, 8302, 8311, -1, 8310, 8311, 8312, -1, 8309, 8287, 8283, -1, 8310, 8312, 8303, -1, 8310, 8305, 8302, -1, 8310, 8303, 8305, -1, 8313, 8293, 8292, -1, 8314, 8284, 8308, -1, 8313, 8296, 8293, -1, 8313, 8292, 8306, -1, 8314, 8290, 8284, -1, 8315, 8287, 8309, -1, 8315, 8294, 8287, -1, 8316, 8297, 8290, -1, 8317, 8313, 8306, -1, 8318, 8312, 8319, -1, 8316, 8290, 8314, -1, 8318, 8303, 8312, -1, 8320, 8294, 8315, -1, 8320, 4625, 8304, -1, 8320, 8304, 8294, -1, 8321, 8308, 7353, -1, 8321, 7353, 7355, -1, 3104, 7375, 3098, -1, 8322, 8309, 8297, -1, 8323, 8319, 8324, -1, 8323, 8318, 8319, -1, 8322, 8297, 8316, -1, 8325, 8308, 8321, -1, 8325, 8314, 8308, -1, 8326, 8318, 8323, -1, 8327, 8315, 8309, -1, 8326, 8328, 8318, -1, 8327, 8309, 8322, -1, 8329, 8316, 8314, -1, 8330, 8323, 8324, -1, 8330, 8324, 8331, -1, 8329, 8314, 8325, -1, 8330, 8331, 8332, -1, 8330, 8326, 8323, -1, 8333, 8332, 8334, -1, 8333, 8328, 8326, -1, 8335, 8320, 8315, -1, 8335, 8315, 8327, -1, 8333, 8336, 8328, -1, 8333, 8330, 8332, -1, 8337, 3074, 3076, -1, 8335, 4629, 4625, -1, 8333, 8326, 8330, -1, 8335, 4625, 8320, -1, 8338, 8339, 8340, -1, 8338, 8341, 8342, -1, 8343, 8321, 7355, -1, 8338, 8344, 8341, -1, 8338, 8340, 8344, -1, 8338, 8345, 8339, -1, 8337, 3076, 7331, -1, 8338, 8342, 8345, -1, 8346, 8322, 8316, -1, 8347, 8348, 8342, -1, 8349, 3369, 3074, -1, 8347, 8350, 8348, -1, 8346, 8316, 8329, -1, 8347, 8342, 8341, -1, 8347, 4655, 8350, -1, 8351, 8341, 8344, -1, 8352, 8325, 8321, -1, 8351, 8353, 8354, -1, 8351, 8344, 8353, -1, 8349, 3074, 8337, -1, 8351, 4659, 4655, -1, 8355, 3371, 3369, -1, 8352, 8321, 8343, -1, 8351, 8354, 4659, -1, 8351, 8347, 8341, -1, 8351, 4655, 8347, -1, 8356, 8357, 8358, -1, 8359, 8327, 8322, -1, 8356, 8358, 8360, -1, 8359, 8322, 8346, -1, 8356, 8360, 8361, -1, 8356, 8361, 8362, -1, 8355, 3369, 8349, -1, 8356, 8363, 8364, -1, 8365, 3374, 3371, -1, 8356, 8362, 8363, -1, 8356, 8364, 8357, -1, 8366, 8354, 8367, -1, 8366, 8367, 8357, -1, 8368, 8325, 8352, -1, 8366, 8357, 8364, -1, 8365, 3371, 8355, -1, 8368, 8329, 8325, -1, 8366, 4659, 8354, -1, 8369, 3376, 3374, -1, 8370, 4659, 8366, -1, 8370, 8371, 4663, -1, 8369, 3374, 8365, -1, 8372, 8335, 8327, -1, 8370, 8366, 8364, -1, 8372, 4629, 8335, -1, 8370, 8364, 8363, -1, 8372, 8327, 8359, -1, 8370, 8373, 8371, -1, 8370, 8363, 8373, -1, 8374, 3379, 3376, -1, 8370, 4663, 4659, -1, 8374, 3380, 3379, -1, 8375, 8376, 8377, -1, 8378, 7355, 7357, -1, 8375, 8379, 8376, -1, 8374, 4595, 3380, -1, 8378, 8343, 7355, -1, 8375, 8377, 8136, -1, 8375, 8380, 8379, -1, 8374, 3376, 8369, -1, 8375, 8136, 8138, -1, 8375, 8149, 8380, -1, 8375, 8138, 8149, -1, 8381, 8371, 8382, -1, 8383, 7331, 7329, -1, 8384, 8346, 8329, -1, 8381, 4663, 8371, -1, 8383, 8337, 7331, -1, 8384, 8329, 8368, -1, 8381, 8382, 8379, -1, 8381, 8379, 8380, -1, 8385, 8381, 8380, -1, 8385, 8148, 4667, -1, 8386, 8343, 8378, -1, 8385, 4667, 4663, -1, 8386, 8352, 8343, -1, 8385, 8380, 8149, -1, 8387, 8349, 8337, -1, 8385, 8147, 8148, -1, 8385, 4663, 8381, -1, 8385, 8149, 8147, -1, 8388, 8151, 8169, -1, 8387, 8337, 8383, -1, 8388, 8167, 8158, -1, 8389, 8349, 8387, -1, 8388, 8390, 8167, -1, 8389, 8355, 8349, -1, 8391, 8359, 8346, -1, 8388, 8169, 8177, -1, 8388, 8184, 8390, -1, 8388, 8177, 8184, -1, 8391, 8346, 8384, -1, 8388, 8158, 8151, -1, 8392, 8165, 8167, -1, 8392, 8167, 8390, -1, 8392, 8148, 8165, -1, 8393, 8368, 8352, -1, 8392, 4667, 8148, -1, 8394, 8355, 8389, -1, 8393, 8352, 8386, -1, 8395, 8392, 8390, -1, 8395, 4667, 8392, -1, 8395, 8390, 8184, -1, 8395, 8184, 8183, -1, 8395, 8183, 8186, -1, 8394, 8365, 8355, -1, 8396, 4629, 8372, -1, 8395, 8186, 4588, -1, 8397, 8365, 8394, -1, 8396, 8372, 8359, -1, 8395, 4588, 4667, -1, 8396, 8359, 8391, -1, 8398, 8166, 8161, -1, 8396, 4633, 4629, -1, 8398, 8188, 8166, -1, 8397, 8369, 8365, -1, 8399, 8378, 7357, -1, 8398, 8161, 7343, -1, 8398, 8400, 8194, -1, 8401, 8369, 8397, -1, 8398, 8194, 8188, -1, 8401, 4595, 8374, -1, 8402, 7343, 7345, -1, 8402, 8400, 8398, -1, 8401, 8374, 8369, -1, 8403, 8384, 8368, -1, 8401, 4599, 4595, -1, 8403, 8368, 8393, -1, 8402, 8398, 7343, -1, 8404, 8383, 7329, -1, 8405, 7345, 8179, -1, 8404, 7329, 7327, -1, 8405, 8206, 8400, -1, 8405, 8402, 7345, -1, 8406, 8378, 8399, -1, 8405, 8201, 8206, -1, 8405, 8187, 8201, -1, 8405, 8400, 8402, -1, 8406, 8386, 8378, -1, 8405, 8179, 8187, -1, 8407, 8202, 8195, -1, 8407, 8400, 8206, -1, 8408, 8384, 8403, -1, 8407, 8191, 8194, -1, 8409, 8383, 8404, -1, 8408, 8391, 8384, -1, 8407, 8195, 8191, -1, 8407, 8194, 8400, -1, 8407, 8206, 8202, -1, 8409, 8387, 8383, -1, 8410, 8216, 8221, -1, 8410, 8411, 8227, -1, 8410, 8221, 8230, -1, 8412, 8393, 8386, -1, 8410, 8227, 8216, -1, 8413, 8387, 8409, -1, 8410, 8230, 8237, -1, 8410, 8237, 8411, -1, 8412, 8386, 8406, -1, 8414, 8227, 8411, -1, 8413, 8389, 8387, -1, 8414, 4653, 8225, -1, 8414, 8223, 8227, -1, 8415, 8389, 8413, -1, 8416, 8391, 8408, -1, 8414, 8225, 8223, -1, 8415, 8394, 8389, -1, 8416, 8396, 8391, -1, 8416, 4633, 8396, -1, 8417, 4653, 8414, -1, 8417, 8414, 8411, -1, 8417, 8236, 8240, -1, 8417, 8411, 8237, -1, 8418, 8403, 8393, -1, 8417, 8240, 4657, -1, 8417, 8237, 8236, -1, 8419, 8397, 8394, -1, 8417, 4657, 4653, -1, 8420, 8251, 8258, -1, 8419, 8394, 8415, -1, 8418, 8393, 8412, -1, 8420, 8268, 8421, -1, 8420, 8258, 8268, -1, 8420, 8249, 8242, -1, 8420, 8244, 8251, -1, 8422, 7357, 7359, -1, 8420, 8242, 8244, -1, 8423, 4603, 4599, -1, 8420, 8421, 8249, -1, 8422, 8399, 7357, -1, 8424, 4657, 8240, -1, 8424, 8240, 8247, -1, 8424, 8249, 8421, -1, 8424, 8247, 8249, -1, 8425, 8408, 8403, -1, 8426, 7327, 7325, -1, 8427, 8424, 8421, -1, 8427, 4657, 8424, -1, 8426, 8404, 7327, -1, 8427, 8266, 4661, -1, 8425, 8403, 8418, -1, 8427, 8421, 8268, -1, 8427, 8268, 8265, -1, 8428, 8399, 8422, -1, 8427, 8265, 8266, -1, 8429, 8409, 8404, -1, 8427, 4661, 4657, -1, 8430, 8269, 8271, -1, 8428, 8406, 8399, -1, 8430, 8277, 8269, -1, 8429, 8404, 8426, -1, 8430, 8271, 8279, -1, 8430, 8279, 8289, -1, 8430, 8298, 8431, -1, 8430, 8289, 8298, -1, 8432, 8416, 8408, -1, 8430, 8431, 8277, -1, 8432, 4637, 4633, -1, 8433, 4661, 8266, -1, 8434, 8413, 8409, -1, 8432, 8408, 8425, -1, 8433, 8274, 8277, -1, 8434, 8409, 8429, -1, 8432, 4633, 8416, -1, 8433, 8266, 8274, -1, 8433, 8277, 8431, -1, 8435, 8406, 8428, -1, 8436, 8296, 4664, -1, 8437, 8415, 8413, -1, 8436, 4661, 8433, -1, 8436, 8431, 8298, -1, 8436, 8295, 8296, -1, 8435, 8412, 8406, -1, 8436, 8298, 8295, -1, 8436, 8433, 8431, -1, 8436, 4664, 4661, -1, 8437, 8413, 8434, -1, 8438, 8306, 8303, -1, 8438, 8317, 8306, -1, 8438, 8303, 8318, -1, 8439, 8419, 8415, -1, 8440, 8422, 7359, -1, 8438, 8441, 8317, -1, 8438, 8318, 8328, -1, 8438, 8336, 8441, -1, 8439, 8415, 8437, -1, 8438, 8328, 8336, -1, 8442, 4607, 4603, -1, 8443, 8412, 8435, -1, 8444, 4664, 8296, -1, 8444, 8296, 8313, -1, 8443, 8418, 8412, -1, 8444, 8313, 8317, -1, 8445, 8428, 8422, -1, 8444, 8317, 8441, -1, 8446, 4668, 4664, -1, 8447, 7325, 7323, -1, 8446, 8444, 8441, -1, 8445, 8422, 8440, -1, 8446, 4664, 8444, -1, 8446, 8441, 8336, -1, 8447, 8426, 7325, -1, 8446, 8333, 8334, -1, 8448, 8425, 8418, -1, 8446, 8336, 8333, -1, 8446, 8334, 4668, -1, 8449, 8429, 8426, -1, 8449, 8426, 8447, -1, 8448, 8418, 8443, -1, 8450, 8435, 8428, -1, 8450, 8428, 8445, -1, 8451, 8429, 8449, -1, 8451, 8434, 8429, -1, 8452, 4637, 8432, -1, 8452, 8432, 8425, -1, 8452, 8425, 8448, -1, 8453, 8434, 8451, -1, 8454, 8435, 8450, -1, 8454, 8443, 8435, -1, 8453, 8437, 8434, -1, 8455, 7359, 7361, -1, 8455, 8440, 7359, -1, 8456, 4607, 8457, -1, 8456, 4611, 4607, -1, 8458, 8448, 8443, -1, 8458, 8443, 8454, -1, 8459, 7323, 7321, -1, 8460, 8440, 8455, -1, 8459, 8447, 7323, -1, 8461, 8447, 8459, -1, 8461, 8449, 8447, -1, 8460, 8445, 8440, -1, 8462, 4637, 8452, -1, 8462, 8452, 8448, -1, 8462, 8448, 8458, -1, 8463, 8459, 7321, -1, 8462, 4641, 4637, -1, 8463, 7321, 7319, -1, 8464, 8455, 7361, -1, 8465, 8445, 8460, -1, 8465, 8450, 8445, -1, 8466, 8451, 8449, -1, 8466, 8449, 8461, -1, 8467, 8460, 8455, -1, 8468, 8461, 8459, -1, 8468, 8459, 8463, -1, 8467, 8455, 8464, -1, 8469, 8451, 8466, -1, 8469, 8453, 8451, -1, 8470, 8454, 8450, -1, 8470, 8450, 8465, -1, 8471, 8466, 8461, -1, 8472, 8465, 8460, -1, 8471, 8461, 8468, -1, 8472, 8460, 8467, -1, 8473, 8458, 8454, -1, 8473, 8454, 8470, -1, 8474, 8466, 8471, -1, 8475, 8465, 8472, -1, 8474, 8469, 8466, -1, 8475, 8470, 8465, -1, 8476, 4611, 8477, -1, 8476, 4615, 4611, -1, 8478, 8462, 8458, -1, 8478, 4641, 8462, -1, 8478, 8458, 8473, -1, 8479, 8463, 7319, -1, 8480, 7361, 7363, -1, 8480, 8464, 7361, -1, 8481, 8469, 8474, -1, 8481, 8477, 8469, -1, 8482, 8473, 8470, -1, 8483, 8468, 8463, -1, 8482, 8470, 8475, -1, 8483, 8463, 8479, -1, 8484, 8464, 8480, -1, 8484, 8467, 8464, -1, 8485, 8476, 8477, -1, 8485, 4615, 8476, -1, 8485, 8477, 8481, -1, 8486, 8479, 7319, -1, 8487, 8473, 8482, -1, 8487, 4641, 8478, -1, 8487, 8478, 8473, -1, 8486, 7319, 7317, -1, 8487, 4645, 4641, -1, 8488, 8471, 8468, -1, 8489, 8480, 7363, -1, 8488, 8468, 8483, -1, 8490, 8472, 8467, -1, 8491, 8479, 8486, -1, 8491, 8483, 8479, -1, 8490, 8467, 8484, -1, 8492, 8474, 8471, -1, 8492, 8471, 8488, -1, 8493, 8480, 8489, -1, 8493, 8484, 8480, -1, 8494, 8475, 8472, -1, 8495, 8483, 8491, -1, 8494, 8472, 8490, -1, 8495, 8488, 8483, -1, 8496, 8481, 8474, -1, 8497, 8490, 8484, -1, 8497, 8484, 8493, -1, 8496, 8474, 8492, -1, 8498, 8482, 8475, -1, 8499, 8492, 8488, -1, 8499, 8488, 8495, -1, 8498, 8475, 8494, -1, 8500, 4615, 8485, -1, 8500, 8485, 8481, -1, 8501, 8494, 8490, -1, 8500, 8481, 8496, -1, 8501, 8490, 8497, -1, 8500, 4619, 4615, -1, 8502, 8487, 8482, -1, 8502, 4645, 8487, -1, 8503, 8486, 7317, -1, 8502, 8482, 8498, -1, 8504, 7363, 7365, -1, 8505, 8496, 8492, -1, 8505, 8492, 8499, -1, 8504, 8489, 7363, -1, 8506, 8494, 8501, -1, 8506, 8498, 8494, -1, 8507, 8491, 8486, -1, 8507, 8486, 8503, -1, 8508, 8500, 8496, -1, 8509, 8489, 8504, -1, 8508, 8496, 8505, -1, 8508, 4619, 8500, -1, 8509, 8493, 8489, -1, 8510, 8498, 8506, -1, 8511, 7317, 7315, -1, 8510, 4645, 8502, -1, 8511, 8503, 7317, -1, 8510, 8502, 8498, -1, 8510, 4649, 4645, -1, 8512, 8504, 7365, -1, 8513, 8495, 8491, -1, 8513, 8491, 8507, -1, 8514, 8497, 8493, -1, 8515, 8507, 8503, -1, 8514, 8493, 8509, -1, 8515, 8503, 8511, -1, 8516, 8504, 8512, -1, 8517, 8499, 8495, -1, 8517, 8495, 8513, -1, 8516, 8509, 8504, -1, 8518, 8501, 8497, -1, 8518, 8497, 8514, -1, 8519, 8513, 8507, -1, 8519, 8507, 8515, -1, 8520, 8514, 8509, -1, 8520, 8509, 8516, -1, 8521, 8505, 8499, -1, 8521, 8499, 8517, -1, 8522, 8501, 8518, -1, 8523, 8517, 8513, -1, 8522, 8506, 8501, -1, 8523, 8513, 8519, -1, 8524, 8514, 8520, -1, 8524, 8518, 8514, -1, 8525, 8508, 8505, -1, 8525, 4619, 8508, -1, 8525, 4623, 4619, -1, 8525, 8505, 8521, -1, 8526, 8506, 8522, -1, 8526, 8510, 8506, -1, 8526, 4649, 8510, -1, 8527, 8511, 7315, -1, 8528, 8518, 8524, -1, 8528, 8522, 8518, -1, 8529, 8517, 8523, -1, 8530, 7365, 7367, -1, 8530, 8512, 7365, -1, 8529, 8521, 8517, -1, 8531, 8511, 8527, -1, 8531, 8515, 8511, -1, 8532, 8526, 8522, -1, 8532, 4649, 8526, -1, 8532, 8522, 8528, -1, 8532, 4653, 4649, -1, 8533, 4623, 8525, -1, 8534, 8516, 8512, -1, 8533, 8525, 8521, -1, 8534, 8512, 8530, -1, 8533, 8521, 8529, -1, 8535, 8515, 8531, -1, 8535, 8519, 8515, -1, 8536, 8520, 8516, -1, 8537, 7315, 7309, -1, 8536, 8516, 8534, -1, 8537, 8527, 7315, -1, 8219, 8524, 8520, -1, 8538, 8519, 8535, -1, 8219, 8520, 8536, -1, 8538, 8523, 8519, -1, 8224, 8528, 8524, -1, 8224, 8524, 8219, -1, 8539, 8527, 8537, -1, 8225, 8532, 8528, -1, 8225, 4653, 8532, -1, 8539, 8531, 8527, -1, 8225, 8528, 8224, -1, 8540, 8523, 8538, -1, 8540, 8529, 8523, -1, 8541, 8531, 8539, -1, 8541, 8535, 8531, -1, 8542, 8533, 8529, -1, 8542, 8529, 8540, -1, 8542, 4627, 4623, -1, 8542, 4623, 8533, -1, 8543, 8538, 8535, -1, 8543, 8535, 8541, -1, 8544, 8537, 7309, -1, 8545, 8538, 8543, -1, 8545, 8540, 8538, -1, 8546, 8539, 8537, -1, 8546, 8537, 8544, -1, 8547, 8542, 8540, -1, 8547, 4627, 8542, -1, 8547, 8540, 8545, -1, 8548, 8541, 8539, -1, 8548, 8539, 8546, -1, 8549, 8544, 7309, -1, 8549, 7309, 7305, -1, 8550, 8543, 8541, -1, 8550, 8541, 8548, -1, 8551, 8546, 8544, -1, 8551, 8544, 8549, -1, 8552, 8545, 8543, -1, 8552, 8543, 8550, -1, 8553, 8548, 8546, -1, 8553, 8546, 8551, -1, 8554, 4627, 8547, -1, 8554, 8547, 8545, -1, 8554, 8545, 8552, -1, 8554, 4631, 4627, -1, 8555, 8549, 7305, -1, 8556, 8548, 8553, -1, 8556, 8550, 8548, -1, 8557, 8551, 8549, -1, 8557, 8549, 8555, -1, 8558, 8552, 8550, -1, 8558, 8550, 8556, -1, 8559, 8553, 8551, -1, 8559, 8551, 8557, -1, 8560, 7375, 3104, -1, 8561, 8554, 8552, -1, 8561, 4631, 8554, -1, 8561, 8552, 8558, -1, 8562, 8560, 3104, -1, 8562, 3104, 3112, -1, 8563, 7305, 7307, -1, 8563, 8555, 7305, -1, 8564, 8556, 8553, -1, 8324, 8562, 3112, -1, 8324, 3112, 3124, -1, 8564, 8553, 8559, -1, 8565, 8555, 8563, -1, 8331, 8324, 3124, -1, 8565, 8557, 8555, -1, 8331, 3124, 3134, -1, 8566, 8558, 8556, -1, 8566, 8556, 8564, -1, 8332, 8331, 3134, -1, 8332, 3134, 3140, -1, 8567, 8559, 8557, -1, 8334, 3144, 4668, -1, 8567, 8557, 8565, -1, 8334, 8332, 3140, -1, 8334, 3140, 3143, -1, 8334, 3143, 3144, -1, 8568, 4631, 8561, -1, 8568, 4635, 4631, -1, 8569, 8423, 4599, -1, 8568, 8561, 8558, -1, 8569, 8397, 8419, -1, 8568, 8558, 8566, -1, 8569, 8401, 8397, -1, 8569, 4599, 8401, -1, 8569, 8419, 8423, -1, 8570, 8563, 7307, -1, 8571, 8442, 4603, -1, 8571, 8439, 8442, -1, 8571, 8423, 8419, -1, 8571, 4603, 8423, -1, 8571, 8419, 8439, -1, 8572, 8564, 8559, -1, 8572, 8559, 8567, -1, 8573, 4607, 8442, -1, 8573, 8457, 4607, -1, 8574, 8477, 4611, -1, 8575, 8563, 8570, -1, 8575, 8565, 8563, -1, 8574, 4611, 8456, -1, 8576, 8577, 7322, -1, 8576, 8578, 8577, -1, 8579, 8566, 8564, -1, 8579, 8564, 8572, -1, 8580, 8565, 8575, -1, 8580, 8567, 8565, -1, 8581, 8576, 7322, -1, 8582, 7322, 7324, -1, 8583, 8566, 8579, -1, 8582, 7324, 8584, -1, 8582, 8581, 7322, -1, 8583, 4635, 8568, -1, 8583, 8568, 8566, -1, 8585, 8584, 7324, -1, 8586, 7307, 7311, -1, 8586, 8570, 7307, -1, 8585, 8587, 8584, -1, 8588, 8585, 7324, -1, 8589, 8567, 8580, -1, 8589, 8572, 8567, -1, 8590, 7324, 7326, -1, 8591, 8570, 8586, -1, 8590, 7326, 8592, -1, 8590, 8588, 7324, -1, 8593, 8594, 8592, -1, 8591, 8575, 8570, -1, 8595, 8572, 8589, -1, 8593, 8592, 7326, -1, 8596, 8593, 7326, -1, 8595, 8579, 8572, -1, 8597, 8580, 8575, -1, 8597, 8575, 8591, -1, 8598, 7328, 8599, -1, 8600, 4635, 8583, -1, 8598, 7326, 7328, -1, 8600, 8579, 8595, -1, 8598, 8596, 7326, -1, 8600, 4639, 4635, -1, 8600, 8583, 8579, -1, 8601, 8602, 8599, -1, 8601, 8599, 7328, -1, 8603, 8586, 7311, -1, 8604, 8580, 8597, -1, 8604, 8589, 8580, -1, 8153, 8601, 7328, -1, 8605, 8591, 8586, -1, 8155, 8153, 7328, -1, 8155, 7328, 7330, -1, 8155, 7330, 8606, -1, 8605, 8586, 8603, -1, 8607, 8608, 8609, -1, 8610, 8595, 8589, -1, 8607, 4597, 8608, -1, 8610, 8589, 8604, -1, 8607, 8609, 8611, -1, 8607, 8132, 4597, -1, 8607, 8611, 8132, -1, 8612, 4601, 8132, -1, 8613, 8597, 8591, -1, 8612, 8160, 4601, -1, 8613, 8591, 8605, -1, 8612, 8614, 8160, -1, 8615, 4605, 8160, -1, 8616, 8600, 8595, -1, 8616, 4639, 8600, -1, 8615, 8173, 4605, -1, 8616, 8595, 8610, -1, 8211, 4609, 8172, -1, 8617, 8604, 8597, -1, 8617, 8597, 8613, -1, 8210, 8208, 4613, -1, 8210, 4613, 4609, -1, 8618, 7311, 7316, -1, 8619, 8530, 7367, -1, 8618, 8603, 7311, -1, 8620, 8610, 8604, -1, 8620, 8604, 8617, -1, 8619, 8534, 8530, -1, 8621, 8605, 8603, -1, 8621, 8603, 8618, -1, 8622, 8619, 7367, -1, 8623, 7367, 7369, -1, 8624, 8616, 8610, -1, 8623, 7369, 8625, -1, 8624, 4639, 8616, -1, 8624, 8610, 8620, -1, 8623, 8622, 7367, -1, 8624, 4643, 4639, -1, 8626, 8625, 7369, -1, 8626, 8627, 8625, -1, 8628, 8613, 8605, -1, 8628, 8605, 8621, -1, 8629, 8618, 7316, -1, 8630, 8626, 7369, -1, 8631, 8617, 8613, -1, 8632, 7369, 7371, -1, 8632, 8630, 7369, -1, 8631, 8613, 8628, -1, 8632, 7371, 8633, -1, 8634, 8633, 7371, -1, 8634, 8635, 8633, -1, 8636, 8621, 8618, -1, 8636, 8618, 8629, -1, 8637, 8634, 7371, -1, 8638, 8620, 8617, -1, 8638, 8617, 8631, -1, 8639, 8628, 8621, -1, 8640, 7371, 7373, -1, 8640, 8637, 7371, -1, 8640, 7373, 8641, -1, 8639, 8621, 8636, -1, 8642, 8641, 7373, -1, 8643, 8624, 8620, -1, 8642, 8644, 8641, -1, 8643, 4643, 8624, -1, 8643, 8620, 8638, -1, 8645, 8628, 8639, -1, 8645, 8631, 8628, -1, 8301, 8642, 7373, -1, 8646, 7316, 7318, -1, 8302, 8301, 7373, -1, 8302, 7373, 7375, -1, 8646, 8629, 7316, -1, 8302, 7375, 8560, -1, 8647, 8442, 8439, -1, 8647, 8453, 8457, -1, 8648, 8638, 8631, -1, 8647, 8437, 8453, -1, 8648, 8631, 8645, -1, 8647, 8457, 8573, -1, 8647, 8573, 8442, -1, 8647, 8439, 8437, -1, 8649, 8574, 8456, -1, 8649, 8456, 8457, -1, 8649, 8457, 8453, -1, 8650, 8629, 8646, -1, 8649, 8453, 8469, -1, 8650, 8636, 8629, -1, 8649, 8469, 8477, -1, 8649, 8477, 8574, -1, 8651, 8652, 8653, -1, 8651, 8653, 8578, -1, 8654, 4647, 4643, -1, 8654, 8643, 8638, -1, 8654, 4643, 8643, -1, 8654, 8638, 8648, -1, 8655, 8578, 8576, -1, 8655, 8576, 8581, -1, 8656, 8646, 7318, -1, 8655, 8651, 8578, -1, 8339, 8655, 8581, -1, 8657, 8636, 8650, -1, 8657, 8639, 8636, -1, 8658, 8650, 8646, -1, 8659, 8582, 8584, -1, 8658, 8646, 8656, -1, 8660, 8639, 8657, -1, 8659, 8584, 8587, -1, 8661, 8339, 8581, -1, 8660, 8645, 8639, -1, 8661, 8581, 8582, -1, 8661, 8582, 8659, -1, 8662, 8659, 8587, -1, 8663, 8650, 8658, -1, 8662, 8661, 8659, -1, 8662, 8664, 8665, -1, 8662, 8587, 8664, -1, 8663, 8657, 8650, -1, 8666, 8645, 8660, -1, 8666, 8648, 8645, -1, 8667, 8665, 8664, -1, 8667, 8664, 8587, -1, 8668, 8585, 8588, -1, 8669, 8660, 8657, -1, 8668, 8587, 8585, -1, 8668, 8667, 8587, -1, 8669, 8657, 8663, -1, 8670, 8648, 8666, -1, 8670, 4647, 8654, -1, 8360, 8668, 8588, -1, 8670, 8654, 8648, -1, 8671, 7318, 7320, -1, 8671, 8656, 7318, -1, 8672, 8666, 8660, -1, 8673, 8592, 8594, -1, 8672, 8660, 8669, -1, 8673, 8590, 8592, -1, 8674, 8658, 8656, -1, 8675, 8360, 8588, -1, 8674, 8656, 8671, -1, 8675, 8588, 8590, -1, 8675, 8590, 8673, -1, 8676, 8673, 8594, -1, 8677, 8670, 8666, -1, 8676, 8675, 8673, -1, 8677, 8666, 8672, -1, 8676, 8594, 8678, -1, 8677, 4647, 8670, -1, 8677, 4651, 4647, -1, 8679, 8671, 7320, -1, 8680, 8678, 8594, -1, 8680, 8681, 8678, -1, 8682, 8663, 8658, -1, 8682, 8658, 8674, -1, 8683, 8594, 8593, -1, 8683, 8680, 8594, -1, 8683, 8593, 8596, -1, 8684, 8671, 8679, -1, 8684, 8674, 8671, -1, 8685, 8669, 8663, -1, 8377, 8683, 8596, -1, 8686, 8599, 8602, -1, 8685, 8663, 8682, -1, 8686, 8598, 8599, -1, 8687, 8674, 8684, -1, 8687, 8682, 8674, -1, 8688, 8596, 8598, -1, 8688, 8377, 8596, -1, 8689, 8669, 8685, -1, 8688, 8598, 8686, -1, 8690, 8686, 8602, -1, 8690, 8602, 8142, -1, 8689, 8672, 8669, -1, 8691, 8685, 8682, -1, 8690, 8688, 8686, -1, 8691, 8682, 8687, -1, 8159, 8142, 8602, -1, 8159, 8143, 8142, -1, 8692, 8672, 8689, -1, 8692, 8677, 8672, -1, 8692, 4651, 8677, -1, 8577, 8679, 7320, -1, 8152, 8159, 8602, -1, 8152, 8602, 8601, -1, 8577, 7320, 7322, -1, 8152, 8601, 8153, -1, 8693, 8685, 8691, -1, 8693, 8689, 8685, -1, 8578, 8684, 8679, -1, 8578, 8679, 8577, -1, 8164, 8606, 8694, -1, 8695, 8692, 8689, -1, 8164, 8155, 8606, -1, 8695, 4651, 8692, -1, 8695, 8689, 8693, -1, 8695, 4655, 4651, -1, 8653, 8687, 8684, -1, 8170, 8163, 8164, -1, 8653, 8684, 8578, -1, 8170, 8694, 8175, -1, 8170, 8164, 8694, -1, 8652, 8691, 8687, -1, 8696, 8611, 8157, -1, 8696, 8612, 8132, -1, 8652, 8687, 8653, -1, 8696, 8132, 8611, -1, 8696, 8157, 8154, -1, 8696, 8154, 8614, -1, 8696, 8614, 8612, -1, 8697, 8154, 8171, -1, 8698, 8693, 8691, -1, 8697, 8614, 8154, -1, 8697, 8160, 8614, -1, 8697, 8171, 8173, -1, 8698, 8691, 8652, -1, 8697, 8615, 8160, -1, 8697, 8173, 8615, -1, 8350, 8695, 8693, -1, 8699, 8173, 8171, -1, 8350, 4655, 8695, -1, 8699, 8211, 8172, -1, 8350, 8693, 8698, -1, 8699, 8172, 8173, -1, 8192, 8699, 8171, -1, 8212, 8211, 8699, -1, 8212, 8192, 8193, -1, 8212, 8699, 8192, -1, 8205, 8197, 8200, -1, 8214, 8203, 8205, -1, 8214, 8205, 8200, -1, 8214, 8200, 8208, -1, 8214, 8208, 8210, -1, 8217, 8536, 8534, -1, 8217, 8219, 8536, -1, 8218, 8534, 8619, -1, 8218, 8619, 8622, -1, 8218, 8217, 8534, -1, 8221, 8218, 8622, -1, 8700, 8623, 8625, -1, 8700, 8625, 8627, -1, 8231, 8221, 8622, -1, 8231, 8623, 8700, -1, 8231, 8622, 8623, -1, 8232, 8700, 8627, -1, 8232, 8231, 8700, -1, 8232, 8627, 8701, -1, 8232, 8701, 8234, -1, 8245, 8701, 8627, -1, 8245, 8234, 8701, -1, 8243, 8626, 8630, -1, 8243, 8627, 8626, -1, 8243, 8245, 8627, -1, 8244, 8243, 8630, -1, 8702, 8632, 8633, -1, 8702, 8633, 8635, -1, 8252, 8632, 8702, -1, 8252, 8630, 8632, -1, 8252, 8244, 8630, -1, 8253, 8252, 8702, -1, 8253, 8702, 8635, -1, 8253, 8635, 8259, -1, 8273, 8259, 8635, -1, 8273, 8263, 8259, -1, 8270, 8634, 8637, -1, 8270, 8273, 8635, -1, 8270, 8635, 8634, -1, 8271, 8270, 8637, -1, 8703, 8640, 8641, -1, 8703, 8641, 8644, -1, 8280, 8271, 8637, -1, 8280, 8637, 8640, -1, 8280, 8640, 8703, -1, 8704, 7330, 7332, -1, 8704, 8606, 7330, -1, 8282, 8703, 8644, -1, 8282, 8280, 8703, -1, 8282, 8644, 8286, -1, 8307, 8292, 8286, -1, 8705, 8694, 8606, -1, 8307, 8286, 8644, -1, 8705, 8606, 8704, -1, 8300, 8307, 8644, -1, 8706, 8175, 8694, -1, 8300, 8644, 8642, -1, 8300, 8642, 8301, -1, 8706, 8694, 8705, -1, 8707, 8175, 8706, -1, 8707, 8181, 8175, -1, 8708, 8181, 8707, -1, 8708, 8182, 8181, -1, 8311, 8560, 8562, -1, 8709, 8186, 8182, -1, 8709, 4588, 8186, -1, 8311, 8302, 8560, -1, 8709, 8182, 8708, -1, 8709, 4586, 4588, -1, 8710, 8704, 7332, -1, 8319, 8312, 8311, -1, 8710, 7332, 7334, -1, 8319, 8311, 8562, -1, 8319, 8562, 8324, -1, 8345, 8651, 8655, -1, 8345, 8655, 8339, -1, 8711, 8705, 8704, -1, 8345, 8652, 8651, -1, 8711, 8704, 8710, -1, 8712, 8705, 8711, -1, 8348, 8652, 8345, -1, 8712, 8706, 8705, -1, 8348, 8698, 8652, -1, 8348, 8350, 8698, -1, 8342, 8348, 8345, -1, 8713, 8707, 8706, -1, 8713, 8706, 8712, -1, 8714, 8708, 8707, -1, 8714, 8707, 8713, -1, 8715, 8709, 8708, -1, 8715, 4586, 8709, -1, 8715, 4589, 4586, -1, 8715, 8708, 8714, -1, 8340, 8339, 8661, -1, 8340, 8662, 8665, -1, 8716, 7334, 7336, -1, 8340, 8661, 8662, -1, 8716, 8710, 7334, -1, 8717, 8710, 8716, -1, 8717, 8711, 8710, -1, 8353, 8340, 8665, -1, 8353, 8344, 8340, -1, 8353, 8665, 8718, -1, 8353, 8718, 8354, -1, 8358, 8665, 8667, -1, 8719, 8711, 8717, -1, 8358, 8668, 8360, -1, 8719, 8712, 8711, -1, 8358, 8667, 8668, -1, 8720, 8712, 8719, -1, 8367, 8665, 8358, -1, 8720, 8713, 8712, -1, 8367, 8718, 8665, -1, 8367, 8354, 8718, -1, 8357, 8367, 8358, -1, 8721, 8714, 8713, -1, 8721, 8713, 8720, -1, 8722, 4593, 4589, -1, 8722, 4589, 8715, -1, 8722, 8715, 8714, -1, 8722, 8714, 8721, -1, 8361, 8675, 8676, -1, 8361, 8360, 8675, -1, 8723, 7336, 7338, -1, 8723, 8716, 7336, -1, 8724, 8716, 8723, -1, 8724, 8717, 8716, -1, 8725, 8361, 8676, -1, 8726, 8717, 8724, -1, 8725, 8362, 8361, -1, 8726, 8719, 8717, -1, 8725, 8676, 8678, -1, 8727, 8681, 8728, -1, 8729, 8719, 8726, -1, 8727, 8725, 8678, -1, 8727, 8678, 8681, -1, 8729, 8720, 8719, -1, 8373, 8728, 8371, -1, 8373, 8362, 8725, -1, 8609, 8721, 8720, -1, 8373, 8363, 8362, -1, 8609, 8720, 8729, -1, 8373, 8725, 8727, -1, 8373, 8727, 8728, -1, 8608, 8722, 8721, -1, 8608, 8721, 8609, -1, 8376, 8681, 8680, -1, 8608, 4597, 4593, -1, 8376, 8680, 8683, -1, 8608, 4593, 8722, -1, 8376, 8683, 8377, -1, 8382, 8728, 8681, -1, 8382, 8371, 8728, -1, 8134, 7338, 7340, -1, 8382, 8681, 8376, -1, 8134, 8723, 7338, -1, 8140, 8723, 8134, -1, 8379, 8382, 8376, -1, 8140, 8724, 8723, -1, 8146, 8726, 8724, -1, 8136, 8377, 8688, -1, 8136, 8688, 8690, -1, 8146, 8724, 8140, -1, 8157, 8726, 8146, -1, 8157, 8729, 8726, -1, 8611, 8609, 8729, -1, 8137, 8136, 8690, -1, 8611, 8729, 8157, -1, 8137, 8690, 8142, -1, 7100, 8730, 8731, -1, 8731, 8730, 8732, -1, 7094, 8733, 8734, -1, 8734, 8733, 8735, -1, 8735, 8733, 8736, -1, 8730, 8737, 8732, -1, 8732, 8737, 8738, -1, 8739, 8740, 8741, -1, 8738, 8737, 8742, -1, 8741, 8740, 8743, -1, 8737, 8744, 8742, -1, 7098, 8744, 7100, -1, 7100, 8744, 8730, -1, 8745, 8746, 8747, -1, 8736, 8746, 8745, -1, 8730, 8744, 8737, -1, 8748, 8749, 8750, -1, 8743, 8751, 7189, -1, 8742, 8749, 8748, -1, 8744, 8749, 8742, -1, 8744, 8752, 8749, -1, 8749, 8752, 8750, -1, 8739, 8753, 8740, -1, 7098, 8752, 8744, -1, 8754, 8753, 8739, -1, 8755, 8752, 7098, -1, 8750, 8752, 8755, -1, 8756, 8757, 8758, -1, 8758, 8757, 7180, -1, 7092, 8759, 7094, -1, 7094, 8759, 8733, -1, 8733, 8759, 8736, -1, 8736, 8759, 8746, -1, 8757, 8760, 7180, -1, 8761, 8760, 8762, -1, 8756, 8760, 8757, -1, 8762, 8760, 8756, -1, 8740, 8763, 8743, -1, 8743, 8763, 8751, -1, 8760, 8764, 7180, -1, 8761, 8764, 8760, -1, 7180, 8764, 7177, -1, 8747, 8765, 8754, -1, 8754, 8765, 8753, -1, 8764, 8766, 7177, -1, 8761, 8766, 8764, -1, 8767, 8766, 8761, -1, 8753, 8768, 8740, -1, 8740, 8768, 8763, -1, 8766, 8769, 7177, -1, 7177, 8769, 8770, -1, 8746, 8771, 8747, -1, 8767, 8772, 8766, -1, 8766, 8772, 8769, -1, 8769, 8772, 8770, -1, 8773, 8772, 8767, -1, 8747, 8771, 8765, -1, 8770, 8772, 8774, -1, 8774, 8772, 8773, -1, 8751, 8775, 7189, -1, 7189, 8775, 7187, -1, 8774, 8776, 8770, -1, 8765, 8777, 8753, -1, 8770, 8776, 7177, -1, 8753, 8777, 8768, -1, 8776, 8778, 7177, -1, 8774, 8778, 8776, -1, 8779, 8778, 8774, -1, 8780, 8778, 8779, -1, 8759, 8781, 8746, -1, 7092, 8781, 8759, -1, 8778, 8782, 7177, -1, 8746, 8781, 8771, -1, 8780, 8782, 8778, -1, 7177, 8782, 7175, -1, 8751, 8783, 8775, -1, 8780, 8784, 8782, -1, 8785, 8784, 8780, -1, 8763, 8783, 8751, -1, 8782, 8784, 7175, -1, 7175, 8786, 8787, -1, 8765, 8788, 8777, -1, 8784, 8786, 7175, -1, 8771, 8788, 8765, -1, 8787, 8789, 8790, -1, 8790, 8789, 8791, -1, 8791, 8789, 8785, -1, 8785, 8789, 8784, -1, 8786, 8789, 8787, -1, 8784, 8789, 8786, -1, 8787, 8792, 7175, -1, 8768, 8793, 8763, -1, 8790, 8792, 8787, -1, 8763, 8793, 8783, -1, 8775, 8794, 7187, -1, 8792, 8795, 7175, -1, 8790, 8795, 8792, -1, 8796, 8795, 8790, -1, 7090, 8797, 7092, -1, 7092, 8797, 8781, -1, 8798, 8795, 8796, -1, 8781, 8797, 8771, -1, 8771, 8797, 8788, -1, 8795, 8799, 7175, -1, 8777, 8800, 8768, -1, 8798, 8799, 8795, -1, 8768, 8800, 8793, -1, 7175, 8799, 7173, -1, 8801, 8802, 8798, -1, 8799, 8802, 7173, -1, 8798, 8802, 8799, -1, 8775, 8803, 8794, -1, 8783, 8803, 8775, -1, 8804, 8805, 8806, -1, 7173, 8805, 8804, -1, 8802, 8805, 7173, -1, 8801, 8807, 8802, -1, 8777, 8808, 8800, -1, 8806, 8807, 8809, -1, 8805, 8807, 8806, -1, 8788, 8808, 8777, -1, 8802, 8807, 8805, -1, 8809, 8807, 8801, -1, 8783, 8810, 8803, -1, 8793, 8810, 8783, -1, 7187, 8811, 7185, -1, 8794, 8811, 7187, -1, 8788, 8812, 8808, -1, 7090, 8812, 8797, -1, 8797, 8812, 8788, -1, 8793, 8813, 8810, -1, 8800, 8813, 8793, -1, 8803, 8814, 8794, -1, 8794, 8814, 8811, -1, 8800, 8815, 8813, -1, 8808, 8815, 8800, -1, 8803, 8816, 8814, -1, 8810, 8816, 8803, -1, 8811, 8817, 7185, -1, 7088, 8818, 7090, -1, 7090, 8818, 8812, -1, 8808, 8818, 8815, -1, 8812, 8818, 8808, -1, 8810, 8819, 8816, -1, 8813, 8819, 8810, -1, 8814, 8820, 8811, -1, 8811, 8820, 8817, -1, 8815, 8821, 8813, -1, 8813, 8821, 8819, -1, 8817, 8822, 7185, -1, 7185, 8822, 7184, -1, 8814, 8823, 8820, -1, 8816, 8823, 8814, -1, 8818, 8824, 8815, -1, 7088, 8824, 8818, -1, 8815, 8824, 8821, -1, 8817, 8825, 8822, -1, 8820, 8825, 8817, -1, 8819, 8826, 8816, -1, 8816, 8826, 8823, -1, 8823, 8827, 8820, -1, 8820, 8827, 8825, -1, 8821, 8828, 8819, -1, 8819, 8828, 8826, -1, 8822, 8829, 7184, -1, 8823, 8830, 8827, -1, 8826, 8830, 8823, -1, 7086, 8831, 7088, -1, 8824, 8831, 8821, -1, 7088, 8831, 8824, -1, 8821, 8831, 8828, -1, 8825, 8832, 8822, -1, 8822, 8832, 8829, -1, 8828, 8833, 8826, -1, 8826, 8833, 8830, -1, 8829, 8834, 7184, -1, 7184, 8834, 7182, -1, 8825, 8835, 8832, -1, 8827, 8835, 8825, -1, 7086, 8836, 8831, -1, 8828, 8836, 8833, -1, 8831, 8836, 8828, -1, 8832, 8837, 8829, -1, 8829, 8837, 8834, -1, 8830, 8838, 8827, -1, 8827, 8838, 8835, -1, 8835, 8839, 8832, -1, 8832, 8839, 8837, -1, 8830, 8840, 8838, -1, 8833, 8840, 8830, -1, 8834, 8841, 7182, -1, 8838, 8842, 8835, -1, 8835, 8842, 8839, -1, 7084, 8843, 7086, -1, 7086, 8843, 8836, -1, 8836, 8843, 8833, -1, 8833, 8843, 8840, -1, 8837, 8844, 8834, -1, 8834, 8844, 8841, -1, 8838, 8845, 8842, -1, 8840, 8845, 8838, -1, 8841, 8846, 7182, -1, 7182, 8846, 7179, -1, 8839, 8847, 8837, -1, 8837, 8847, 8844, -1, 8840, 8848, 8845, -1, 8843, 8848, 8840, -1, 7084, 8848, 8843, -1, 8841, 8849, 8846, -1, 8844, 8849, 8841, -1, 8839, 8850, 8847, -1, 7072, 2290, 2292, -1, 8842, 8850, 8839, -1, 8844, 8851, 8849, -1, 8847, 8851, 8844, -1, 2456, 8852, 2455, -1, 8845, 8853, 8842, -1, 2455, 8852, 7141, -1, 2456, 8854, 8852, -1, 8842, 8853, 8850, -1, 2459, 8854, 2456, -1, 8850, 8855, 8847, -1, 8847, 8855, 8851, -1, 2462, 8856, 2459, -1, 8846, 8857, 7179, -1, 2459, 8856, 8854, -1, 7082, 8858, 7084, -1, 2469, 8859, 2462, -1, 8848, 8858, 8845, -1, 2462, 8859, 8856, -1, 7084, 8858, 8848, -1, 8845, 8858, 8853, -1, 2469, 8860, 8859, -1, 8850, 8861, 8855, -1, 2472, 8860, 2469, -1, 8853, 8861, 8850, -1, 8852, 8862, 7141, -1, 8849, 8863, 8846, -1, 8846, 8863, 8857, -1, 7141, 8862, 7143, -1, 7099, 8864, 2388, -1, 8857, 8865, 7179, -1, 2389, 8864, 2472, -1, 2388, 8864, 2389, -1, 2472, 8864, 8860, -1, 7179, 8865, 7180, -1, 7082, 8866, 8858, -1, 8858, 8866, 8853, -1, 8853, 8866, 8861, -1, 8851, 8867, 8849, -1, 8852, 8868, 8862, -1, 8849, 8867, 8863, -1, 8854, 8868, 8852, -1, 8856, 8869, 8854, -1, 8863, 8870, 8857, -1, 8854, 8869, 8868, -1, 8857, 8870, 8865, -1, 8859, 8871, 8856, -1, 8855, 8872, 8851, -1, 8856, 8871, 8869, -1, 8860, 8873, 8859, -1, 8851, 8872, 8867, -1, 8859, 8873, 8871, -1, 8863, 8874, 8870, -1, 8862, 8875, 7143, -1, 8867, 8874, 8863, -1, 8855, 8876, 8872, -1, 7143, 8875, 7151, -1, 8861, 8876, 8855, -1, 7099, 8877, 8864, -1, 7097, 8877, 7099, -1, 8864, 8877, 8860, -1, 8860, 8877, 8873, -1, 8872, 8878, 8867, -1, 8862, 8879, 8875, -1, 8867, 8878, 8874, -1, 8865, 8758, 7180, -1, 8868, 8879, 8862, -1, 7080, 8880, 7082, -1, 8868, 8881, 8879, -1, 7082, 8880, 8866, -1, 8869, 8881, 8868, -1, 8866, 8880, 8861, -1, 8861, 8880, 8876, -1, 8876, 8882, 8872, -1, 8872, 8882, 8878, -1, 8871, 8883, 8869, -1, 8869, 8883, 8881, -1, 8870, 8756, 8865, -1, 8871, 8884, 8883, -1, 8865, 8756, 8758, -1, 8873, 8884, 8871, -1, 7080, 8885, 8880, -1, 8880, 8885, 8876, -1, 8876, 8885, 8882, -1, 8874, 8886, 8870, -1, 7095, 8887, 7097, -1, 8873, 8887, 8884, -1, 8877, 8887, 8873, -1, 8870, 8886, 8756, -1, 7097, 8887, 8877, -1, 8878, 8888, 8874, -1, 8874, 8888, 8886, -1, 8878, 8889, 8888, -1, 8882, 8889, 8878, -1, 7078, 8890, 7080, -1, 7080, 8890, 8885, -1, 8885, 8890, 8882, -1, 8882, 8890, 8889, -1, 8891, 8892, 7155, -1, 8891, 8893, 8892, -1, 8894, 8893, 8891, -1, 8895, 8896, 8894, -1, 8894, 8896, 8893, -1, 8895, 8897, 8896, -1, 8898, 8897, 8895, -1, 8892, 8899, 7155, -1, 7155, 8899, 7160, -1, 7173, 8804, 2393, -1, 2393, 8804, 2391, -1, 8898, 8900, 8897, -1, 8901, 8900, 8898, -1, 8892, 8902, 8899, -1, 8804, 8806, 2391, -1, 2391, 8806, 2396, -1, 8893, 8902, 8892, -1, 8899, 8903, 7160, -1, 7089, 8904, 7091, -1, 7091, 8904, 8905, -1, 8806, 8809, 2396, -1, 8905, 8904, 8901, -1, 8901, 8904, 8900, -1, 2396, 8809, 2401, -1, 8896, 8906, 8893, -1, 8809, 8907, 2401, -1, 8893, 8906, 8902, -1, 8902, 8908, 8899, -1, 2401, 8907, 2404, -1, 8899, 8908, 8903, -1, 8907, 8909, 2404, -1, 8897, 8910, 8896, -1, 2404, 8909, 2406, -1, 8896, 8910, 8906, -1, 8909, 8911, 2406, -1, 2292, 8911, 7072, -1, 2406, 8911, 2292, -1, 8906, 8912, 8902, -1, 8902, 8912, 8908, -1, 8879, 8913, 8875, -1, 8875, 8913, 7151, -1, 8900, 8914, 8897, -1, 8897, 8914, 8910, -1, 8913, 8915, 7151, -1, 7160, 8916, 7166, -1, 7153, 8917, 8918, -1, 8903, 8916, 7160, -1, 7151, 8917, 7153, -1, 8915, 8917, 7151, -1, 8919, 8920, 8918, -1, 8918, 8920, 7153, -1, 8910, 8921, 8906, -1, 8906, 8921, 8912, -1, 7089, 8922, 8904, -1, 8904, 8922, 8900, -1, 8900, 8922, 8914, -1, 8903, 8923, 8916, -1, 8920, 8924, 7153, -1, 7155, 8925, 8891, -1, 8924, 8925, 7153, -1, 7153, 8925, 7155, -1, 8908, 8923, 8903, -1, 8926, 8927, 8928, -1, 8914, 8929, 8910, -1, 8910, 8929, 8921, -1, 7071, 8927, 8926, -1, 8916, 8930, 7166, -1, 7071, 8931, 8927, -1, 8908, 8932, 8923, -1, 8912, 8932, 8908, -1, 7089, 8933, 8922, -1, 7071, 8934, 8931, -1, 8914, 8933, 8929, -1, 8922, 8933, 8914, -1, 8935, 8936, 7069, -1, 7087, 8933, 7089, -1, 7069, 8936, 7071, -1, 8923, 8937, 8916, -1, 7071, 8936, 8934, -1, 8935, 8938, 8939, -1, 7069, 8938, 8935, -1, 8916, 8937, 8930, -1, 8912, 8940, 8932, -1, 8921, 8940, 8912, -1, 8932, 8941, 8923, -1, 7069, 8942, 8938, -1, 7070, 8943, 7069, -1, 8923, 8941, 8937, -1, 8921, 8944, 8940, -1, 8929, 8944, 8921, -1, 7069, 8943, 8942, -1, 8945, 8946, 7070, -1, 7070, 8946, 8943, -1, 7070, 8947, 8945, -1, 8930, 8948, 7166, -1, 8945, 8947, 8949, -1, 7166, 8948, 7168, -1, 8940, 8950, 8932, -1, 7070, 8951, 8947, -1, 8932, 8950, 8941, -1, 8933, 8952, 8929, -1, 8947, 8951, 8949, -1, 7087, 8952, 8933, -1, 7105, 8953, 7070, -1, 8929, 8952, 8944, -1, 7070, 8953, 8951, -1, 8930, 8954, 8948, -1, 8937, 8954, 8930, -1, 8955, 8956, 7105, -1, 7105, 8956, 8953, -1, 8957, 8958, 8959, -1, 8944, 8960, 8940, -1, 8959, 8958, 7115, -1, 8940, 8960, 8950, -1, 8958, 8961, 7115, -1, 8948, 8962, 7168, -1, 8941, 8963, 8937, -1, 8961, 8964, 7115, -1, 8937, 8963, 8954, -1, 7115, 8964, 7107, -1, 7107, 8964, 8965, -1, 8966, 8967, 8965, -1, 7087, 8968, 8952, -1, 7085, 8968, 7087, -1, 8965, 8967, 7107, -1, 8952, 8968, 8944, -1, 8944, 8968, 8960, -1, 8967, 8969, 7107, -1, 8954, 8970, 8948, -1, 8948, 8970, 8962, -1, 8950, 8971, 8941, -1, 8941, 8971, 8963, -1, 8969, 8972, 7107, -1, 7107, 8972, 7108, -1, 7108, 8972, 8973, -1, 8890, 8974, 8889, -1, 8954, 8975, 8970, -1, 7078, 8974, 8890, -1, 8963, 8975, 8954, -1, 8960, 8976, 8950, -1, 8950, 8976, 8971, -1, 7078, 8977, 8974, -1, 7168, 8978, 7172, -1, 8962, 8978, 7168, -1, 7078, 8979, 8977, -1, 8971, 8980, 8963, -1, 7076, 8981, 7078, -1, 7078, 8981, 8979, -1, 8963, 8980, 8975, -1, 8982, 8981, 7076, -1, 8982, 8983, 8984, -1, 7076, 8983, 8982, -1, 7085, 8985, 8968, -1, 8968, 8985, 8960, -1, 8960, 8985, 8976, -1, 8970, 8986, 8962, -1, 7076, 8987, 8983, -1, 8962, 8986, 8978, -1, 7074, 8988, 7076, -1, 8971, 8989, 8980, -1, 7076, 8988, 8987, -1, 8976, 8989, 8971, -1, 8990, 8991, 7074, -1, 7074, 8991, 8988, -1, 8975, 8992, 8970, -1, 7074, 8993, 8990, -1, 8990, 8993, 8994, -1, 8970, 8992, 8986, -1, 8978, 8995, 7172, -1, 7074, 8996, 8993, -1, 7083, 8997, 7085, -1, 7085, 8997, 8985, -1, 8993, 8996, 8994, -1, 8985, 8997, 8976, -1, 8976, 8997, 8989, -1, 7072, 8998, 7074, -1, 7074, 8998, 8996, -1, 8980, 8999, 8975, -1, 8975, 8999, 8992, -1, 7072, 9000, 8998, -1, 8911, 9000, 7072, -1, 8986, 9001, 8978, -1, 8978, 9001, 8995, -1, 8883, 9002, 8881, -1, 8881, 9002, 8879, -1, 8989, 9003, 8980, -1, 8980, 9003, 8999, -1, 8879, 9004, 8913, -1, 8913, 9004, 8915, -1, 9002, 9004, 8879, -1, 8986, 9005, 9001, -1, 8992, 9005, 8986, -1, 9004, 9006, 8915, -1, 8995, 9007, 7172, -1, 7172, 9007, 7170, -1, 8918, 9008, 8919, -1, 8917, 9008, 8918, -1, 8989, 9009, 9003, -1, 7083, 9009, 8997, -1, 8997, 9009, 8989, -1, 8992, 9010, 9005, -1, 8915, 9011, 8917, -1, 9006, 9011, 8915, -1, 8917, 9011, 9008, -1, 8919, 9012, 9013, -1, 8999, 9010, 8992, -1, 9008, 9012, 8919, -1, 9001, 9014, 8995, -1, 9013, 9012, 9015, -1, 8995, 9014, 9007, -1, 9011, 9012, 9008, -1, 9013, 9016, 8919, -1, 9015, 9016, 9013, -1, 9003, 9017, 8999, -1, 8919, 9018, 8920, -1, 8999, 9017, 9010, -1, 8920, 9018, 8924, -1, 9005, 9019, 9001, -1, 9016, 9018, 8919, -1, 9001, 9019, 9014, -1, 9007, 9020, 7170, -1, 9018, 9021, 8924, -1, 8891, 9022, 8894, -1, 7083, 9023, 9009, -1, 8925, 9022, 8891, -1, 9009, 9023, 9003, -1, 7081, 9023, 7083, -1, 9003, 9023, 9017, -1, 9005, 9024, 9019, -1, 8924, 9025, 8925, -1, 9021, 9025, 8924, -1, 8925, 9025, 9022, -1, 8894, 9026, 8895, -1, 8895, 9026, 8898, -1, 9010, 9024, 9005, -1, 9022, 9026, 8894, -1, 9025, 9026, 9022, -1, 9007, 9027, 9020, -1, 9014, 9027, 9007, -1, 9017, 9028, 9010, -1, 9029, 9030, 9031, -1, 8928, 9030, 9029, -1, 9010, 9028, 9024, -1, 8927, 9032, 8928, -1, 8931, 9032, 8927, -1, 7170, 9033, 7167, -1, 8928, 9032, 9030, -1, 9020, 9033, 7170, -1, 9019, 9034, 9014, -1, 9014, 9034, 9027, -1, 8931, 9035, 9032, -1, 9023, 9036, 9017, -1, 7081, 9036, 9023, -1, 9017, 9036, 9028, -1, 9027, 9037, 9020, -1, 9020, 9037, 9033, -1, 9038, 9039, 9040, -1, 9024, 9041, 9019, -1, 9019, 9041, 9034, -1, 9042, 9043, 9039, -1, 9035, 9043, 9042, -1, 9027, 9044, 9037, -1, 9034, 9044, 9027, -1, 8931, 9045, 9035, -1, 9035, 9045, 9043, -1, 8934, 9045, 8931, -1, 8936, 9045, 8934, -1, 9024, 9046, 9041, -1, 9043, 9047, 9039, -1, 9028, 9046, 9024, -1, 9033, 9048, 7167, -1, 9045, 9049, 9043, -1, 9043, 9049, 9047, -1, 8936, 9049, 9045, -1, 8935, 9049, 8936, -1, 9041, 9050, 9034, -1, 9039, 9051, 9040, -1, 9047, 9051, 9039, -1, 8939, 9051, 8935, -1, 9034, 9050, 9044, -1, 9049, 9051, 9047, -1, 8935, 9051, 9049, -1, 9040, 9051, 8939, -1, 7079, 9052, 7081, -1, 9040, 9053, 9038, -1, 9036, 9052, 9028, -1, 7081, 9052, 9036, -1, 8939, 9053, 9040, -1, 9028, 9052, 9046, -1, 9033, 9054, 9048, -1, 9037, 9054, 9033, -1, 8939, 9055, 9053, -1, 8938, 9055, 8939, -1, 8942, 9055, 8938, -1, 9041, 9056, 9050, -1, 9046, 9056, 9041, -1, 8942, 9057, 9055, -1, 7167, 9058, 7163, -1, 9048, 9058, 7167, -1, 9044, 9059, 9037, -1, 9037, 9059, 9054, -1, 9060, 9061, 9062, -1, 7079, 9063, 9052, -1, 9052, 9063, 9046, -1, 9046, 9063, 9056, -1, 9057, 9064, 9065, -1, 9065, 9064, 9061, -1, 9054, 9066, 9048, -1, 9048, 9066, 9058, -1, 9057, 9067, 9064, -1, 9050, 9068, 9044, -1, 9044, 9068, 9059, -1, 8942, 9067, 9057, -1, 8943, 9067, 8942, -1, 8946, 9067, 8943, -1, 9064, 9069, 9061, -1, 9059, 9070, 9054, -1, 9054, 9070, 9066, -1, 9064, 9071, 9069, -1, 9067, 9071, 9064, -1, 8946, 9071, 9067, -1, 9056, 9072, 9050, -1, 8945, 9071, 8946, -1, 9050, 9072, 9068, -1, 9062, 9073, 8949, -1, 9061, 9073, 9062, -1, 9069, 9073, 9061, -1, 8949, 9073, 8945, -1, 9058, 9074, 7163, -1, 8945, 9073, 9071, -1, 9071, 9073, 9069, -1, 9062, 9075, 9060, -1, 8949, 9075, 9062, -1, 9068, 9076, 9059, -1, 9059, 9076, 9070, -1, 8949, 9077, 9075, -1, 8951, 9077, 8949, -1, 7077, 9078, 7079, -1, 7079, 9078, 9063, -1, 9056, 9078, 9072, -1, 9063, 9078, 9056, -1, 9066, 9079, 9058, -1, 9058, 9079, 9074, -1, 8951, 9080, 9077, -1, 9068, 9081, 9076, -1, 9072, 9081, 9068, -1, 9082, 9083, 9084, -1, 7163, 9085, 7157, -1, 9074, 9085, 7163, -1, 9070, 9086, 9066, -1, 9087, 9088, 9083, -1, 9066, 9086, 9079, -1, 9080, 9088, 9087, -1, 8953, 9089, 8951, -1, 9072, 9090, 9081, -1, 8956, 9089, 8953, -1, 8951, 9089, 9080, -1, 9078, 9090, 9072, -1, 7077, 9090, 9078, -1, 9080, 9089, 9088, -1, 9074, 9091, 9085, -1, 9088, 9092, 9083, -1, 9079, 9091, 9074, -1, 8955, 9093, 8956, -1, 8956, 9093, 9089, -1, 9070, 9094, 9086, -1, 9089, 9093, 9088, -1, 9088, 9093, 9092, -1, 9093, 9095, 9092, -1, 9076, 9094, 9070, -1, 9084, 9095, 9096, -1, 9086, 9097, 9079, -1, 9096, 9095, 8955, -1, 8955, 9095, 9093, -1, 9083, 9095, 9084, -1, 9079, 9097, 9091, -1, 9092, 9095, 9083, -1, 9098, 9099, 8957, -1, 9100, 9099, 9098, -1, 9099, 9101, 8957, -1, 9076, 9102, 9094, -1, 8958, 9101, 8961, -1, 9081, 9102, 9076, -1, 9086, 9103, 9097, -1, 8957, 9101, 8958, -1, 9094, 9103, 9086, -1, 9085, 9104, 7157, -1, 9101, 9105, 8961, -1, 9081, 9106, 9102, -1, 8964, 9107, 8965, -1, 9090, 9106, 9081, -1, 8965, 9107, 8966, -1, 7077, 9106, 9090, -1, 7075, 9106, 7077, -1, 8961, 9108, 8964, -1, 9102, 9109, 9094, -1, 8964, 9108, 9107, -1, 9094, 9109, 9103, -1, 9105, 9108, 8961, -1, 8966, 9110, 9111, -1, 9111, 9110, 9112, -1, 9091, 9113, 9085, -1, 9108, 9110, 9107, -1, 9107, 9110, 8966, -1, 9085, 9113, 9104, -1, 9111, 9114, 8966, -1, 9112, 9114, 9111, -1, 9104, 9115, 7157, -1, 9114, 9116, 8966, -1, 7157, 9115, 7154, -1, 8966, 9116, 8967, -1, 8967, 9116, 8969, -1, 9106, 9117, 9102, -1, 9102, 9117, 9109, -1, 7075, 9117, 9106, -1, 9116, 9118, 8969, -1, 9097, 9119, 9091, -1, 9091, 9119, 9113, -1, 9104, 9120, 9115, -1, 8972, 9121, 8973, -1, 9113, 9120, 9104, -1, 8973, 9121, 9122, -1, 9103, 9123, 9097, -1, 8972, 9124, 9121, -1, 8969, 9124, 8972, -1, 9118, 9124, 8969, -1, 9097, 9123, 9119, -1, 9121, 9125, 9122, -1, 9119, 9126, 9113, -1, 9124, 9125, 9121, -1, 9113, 9126, 9120, -1, 9127, 9125, 9128, -1, 9122, 9125, 9127, -1, 9103, 9129, 9123, -1, 9109, 9129, 9103, -1, 8888, 9130, 8886, -1, 8889, 9130, 8888, -1, 8974, 9131, 8889, -1, 8977, 9131, 8974, -1, 9119, 9132, 9126, -1, 8889, 9131, 9130, -1, 9123, 9132, 9119, -1, 9115, 9133, 7154, -1, 8977, 9134, 9131, -1, 7073, 9135, 7075, -1, 9117, 9135, 9109, -1, 7075, 9135, 9117, -1, 9109, 9135, 9129, -1, 9129, 9136, 9123, -1, 9123, 9136, 9132, -1, 8773, 9137, 9138, -1, 9120, 9139, 9115, -1, 9115, 9139, 9133, -1, 9134, 9140, 9141, -1, 9141, 9140, 9137, -1, 7073, 9142, 9135, -1, 8977, 9143, 9134, -1, 9129, 9142, 9136, -1, 9135, 9142, 9129, -1, 8981, 9143, 8979, -1, 8979, 9143, 8977, -1, 9134, 9143, 9140, -1, 9126, 9031, 9120, -1, 9120, 9031, 9139, -1, 9140, 9144, 9137, -1, 9143, 9145, 9140, -1, 9132, 9029, 9126, -1, 8982, 9145, 8981, -1, 8981, 9145, 9143, -1, 9126, 9029, 9031, -1, 9140, 9145, 9144, -1, 9138, 9146, 8984, -1, 8984, 9146, 8982, -1, 9137, 9146, 9138, -1, 9144, 9146, 9137, -1, 8982, 9146, 9145, -1, 9136, 8928, 9132, -1, 9145, 9146, 9144, -1, 9132, 8928, 9029, -1, 9138, 9147, 8773, -1, 8984, 9147, 9138, -1, 8983, 9148, 8984, -1, 7071, 8926, 7073, -1, 8984, 9148, 9147, -1, 7073, 8926, 9142, -1, 8987, 9148, 8983, -1, 9142, 8926, 9136, -1, 9136, 8926, 8928, -1, 8987, 9149, 9148, -1, 8791, 9150, 9151, -1, 9149, 9152, 9153, -1, 9153, 9152, 9150, -1, 8988, 9154, 8987, -1, 8987, 9154, 9149, -1, 8991, 9154, 8988, -1, 9149, 9154, 9152, -1, 9152, 9155, 9150, -1, 8990, 9156, 8991, -1, 8991, 9156, 9154, -1, 9154, 9156, 9152, -1, 9152, 9156, 9155, -1, 9151, 9157, 8994, -1, 8994, 9157, 8990, -1, 9155, 9157, 9150, -1, 9150, 9157, 9151, -1, 8990, 9157, 9156, -1, 9156, 9157, 9155, -1, 9151, 9158, 8791, -1, 8994, 9158, 9151, -1, 8996, 9159, 8994, -1, 8994, 9159, 9158, -1, 8996, 9160, 9159, -1, 8809, 9161, 8907, -1, 9160, 9162, 9163, -1, 9163, 9162, 9161, -1, 8998, 9164, 8996, -1, 9000, 9164, 8998, -1, 8996, 9164, 9160, -1, 9160, 9164, 9162, -1, 9162, 9165, 9161, -1, 9162, 9166, 9165, -1, 8911, 9166, 9000, -1, 9000, 9166, 9164, -1, 9164, 9166, 9162, -1, 9165, 9167, 9161, -1, 9166, 9167, 9165, -1, 8911, 9167, 9166, -1, 8909, 9167, 8911, -1, 8907, 9167, 8909, -1, 9161, 9167, 8907, -1, 8883, 9168, 9002, -1, 9169, 9170, 7137, -1, 9002, 9168, 9004, -1, 9004, 9168, 9006, -1, 8884, 9168, 8883, -1, 7137, 9170, 7133, -1, 9168, 9171, 9006, -1, 9172, 9173, 9169, -1, 9169, 9173, 9170, -1, 9171, 9174, 9006, -1, 9015, 9174, 9175, -1, 9006, 9174, 9011, -1, 9012, 9174, 9015, -1, 9011, 9174, 9012, -1, 9082, 9176, 9172, -1, 9015, 9177, 9016, -1, 9172, 9176, 9173, -1, 9175, 9177, 9015, -1, 9016, 9177, 9018, -1, 9084, 9178, 9082, -1, 9018, 9177, 9021, -1, 9082, 9178, 9176, -1, 9177, 9179, 9021, -1, 9096, 9180, 9084, -1, 9084, 9180, 9178, -1, 8898, 9181, 8901, -1, 9179, 9181, 9021, -1, 9170, 9182, 7133, -1, 9021, 9181, 9025, -1, 9026, 9181, 8898, -1, 9025, 9181, 9026, -1, 7133, 9182, 7129, -1, 9032, 9183, 9030, -1, 9035, 9183, 9032, -1, 9031, 9183, 9139, -1, 7104, 9184, 7105, -1, 9030, 9183, 9031, -1, 9096, 9184, 9180, -1, 7105, 9184, 8955, -1, 8955, 9184, 9096, -1, 9173, 9185, 9170, -1, 9170, 9185, 9182, -1, 9035, 9186, 9183, -1, 9039, 9187, 9042, -1, 9173, 9188, 9185, -1, 9042, 9187, 9035, -1, 9176, 9188, 9173, -1, 9038, 9187, 9039, -1, 9035, 9187, 9186, -1, 9038, 9189, 9190, -1, 9055, 9189, 9053, -1, 9178, 9191, 9176, -1, 9053, 9189, 9038, -1, 9057, 9189, 9055, -1, 9176, 9191, 9188, -1, 9178, 9192, 9191, -1, 9180, 9192, 9178, -1, 9057, 9193, 9189, -1, 7129, 9194, 7121, -1, 9182, 9194, 7129, -1, 9065, 9195, 9057, -1, 9061, 9195, 9065, -1, 9060, 9195, 9061, -1, 7103, 9196, 7104, -1, 7104, 9196, 9184, -1, 9057, 9195, 9193, -1, 9184, 9196, 9180, -1, 9180, 9196, 9192, -1, 9060, 9197, 9198, -1, 9075, 9197, 9060, -1, 9077, 9197, 9075, -1, 9080, 9197, 9077, -1, 9185, 9199, 9182, -1, 9182, 9199, 9194, -1, 9188, 9200, 9185, -1, 9080, 9201, 9197, -1, 9185, 9200, 9199, -1, 9080, 9202, 9201, -1, 9188, 9203, 9200, -1, 9083, 9202, 9087, -1, 9087, 9202, 9080, -1, 9191, 9203, 9188, -1, 9082, 9202, 9083, -1, 9099, 9204, 9101, -1, 9205, 9204, 9100, -1, 9192, 9206, 9191, -1, 9100, 9204, 9099, -1, 9101, 9204, 9105, -1, 9191, 9206, 9203, -1, 7121, 8959, 7115, -1, 9194, 8959, 7121, -1, 9204, 9207, 9105, -1, 9192, 9208, 9206, -1, 9112, 9209, 8732, -1, 7102, 9208, 7103, -1, 7103, 9208, 9196, -1, 9207, 9209, 9105, -1, 9196, 9208, 9192, -1, 9110, 9209, 9112, -1, 9105, 9209, 9108, -1, 9108, 9209, 9110, -1, 9114, 8738, 9116, -1, 9116, 8738, 9118, -1, 9199, 8957, 9194, -1, 9112, 8738, 9114, -1, 8732, 8738, 9112, -1, 9194, 8957, 8959, -1, 9199, 9098, 8957, -1, 8738, 8742, 9118, -1, 9200, 9098, 9199, -1, 9200, 9100, 9098, -1, 9125, 8748, 9128, -1, 9118, 8748, 9124, -1, 9203, 9100, 9200, -1, 9124, 8748, 9125, -1, 9128, 8748, 8750, -1, 8742, 8748, 9118, -1, 9206, 9205, 9203, -1, 9134, 8762, 9131, -1, 9203, 9205, 9100, -1, 9130, 8762, 8886, -1, 8886, 8762, 8756, -1, 9131, 8762, 9130, -1, 9134, 8761, 8762, -1, 9208, 9210, 9206, -1, 7102, 9210, 9208, -1, 9206, 9210, 9205, -1, 7101, 9210, 7102, -1, 8773, 8767, 9137, -1, 9141, 8767, 9134, -1, 9137, 8767, 9141, -1, 9134, 8767, 8761, -1, 9147, 8779, 8773, -1, 9148, 8779, 9147, -1, 9149, 8779, 9148, -1, 8773, 8779, 8774, -1, 9149, 8780, 8779, -1, 8791, 8785, 9150, -1, 9149, 8785, 8780, -1, 9153, 8785, 9149, -1, 9150, 8785, 9153, -1, 8791, 8796, 8790, -1, 9160, 8796, 9159, -1, 9158, 8796, 8791, -1, 9159, 8796, 9158, -1, 9160, 8798, 8796, -1, 8809, 8801, 9161, -1, 9163, 8801, 9160, -1, 8973, 9211, 7108, -1, 9160, 8801, 8798, -1, 9161, 8801, 9163, -1, 7095, 9212, 8887, -1, 8887, 9212, 8884, -1, 8884, 9213, 9168, -1, 9122, 9214, 8973, -1, 9168, 9213, 9171, -1, 8973, 9214, 9211, -1, 9212, 9213, 8884, -1, 9213, 9215, 9171, -1, 9212, 9215, 9213, -1, 7093, 9215, 7095, -1, 7095, 9215, 9212, -1, 9215, 9216, 9171, -1, 9122, 9217, 9214, -1, 9171, 9216, 9174, -1, 9127, 9217, 9122, -1, 9174, 9216, 9175, -1, 7093, 9218, 9215, -1, 9216, 9218, 9175, -1, 9215, 9218, 9216, -1, 9219, 9218, 7093, -1, 9175, 9218, 9219, -1, 7093, 9220, 9219, -1, 9219, 9220, 9175, -1, 9128, 9221, 9127, -1, 9127, 9221, 9217, -1, 9220, 9222, 9175, -1, 9211, 9223, 7108, -1, 9175, 9222, 9177, -1, 9177, 9222, 9179, -1, 7108, 9223, 7197, -1, 9222, 9224, 9179, -1, 9220, 9224, 9222, -1, 7093, 9224, 9220, -1, 7091, 9224, 7093, -1, 9224, 9225, 9179, -1, 8750, 9226, 9128, -1, 9181, 9225, 8901, -1, 9128, 9226, 9221, -1, 9179, 9225, 9181, -1, 7091, 9227, 9224, -1, 9224, 9227, 9225, -1, 9225, 9227, 8901, -1, 8905, 9227, 7091, -1, 9214, 9228, 9211, -1, 8901, 9227, 8905, -1, 9211, 9228, 9223, -1, 9139, 9229, 9133, -1, 9223, 9230, 7197, -1, 9133, 9229, 7154, -1, 9229, 9231, 7154, -1, 9139, 9231, 9229, -1, 7096, 9232, 7098, -1, 9186, 9231, 9183, -1, 7098, 9232, 8755, -1, 8755, 9232, 8750, -1, 8750, 9232, 9226, -1, 9183, 9231, 9139, -1, 9186, 9233, 9231, -1, 9217, 9234, 9214, -1, 7154, 9233, 7149, -1, 9214, 9234, 9228, -1, 9231, 9233, 7154, -1, 9187, 9235, 9186, -1, 9233, 9235, 7149, -1, 9228, 9236, 9223, -1, 9186, 9235, 9233, -1, 9223, 9236, 9230, -1, 9235, 9237, 7149, -1, 7149, 9237, 9238, -1, 9217, 9239, 9234, -1, 9221, 9239, 9217, -1, 9190, 9240, 9038, -1, 9187, 9240, 9235, -1, 9038, 9240, 9187, -1, 9235, 9240, 9237, -1, 9237, 9240, 9238, -1, 9238, 9240, 9190, -1, 9234, 9241, 9228, -1, 9228, 9241, 9236, -1, 9238, 9242, 7149, -1, 9190, 9242, 9238, -1, 9193, 9243, 9189, -1, 9226, 9244, 9221, -1, 9189, 9243, 9190, -1, 9190, 9243, 9242, -1, 9221, 9244, 9239, -1, 9242, 9243, 7149, -1, 7197, 9245, 7191, -1, 9230, 9245, 7197, -1, 9193, 9246, 9243, -1, 9243, 9246, 7149, -1, 7149, 9246, 7145, -1, 9239, 9247, 9234, -1, 9246, 9248, 7145, -1, 9195, 9248, 9193, -1, 9234, 9247, 9241, -1, 9193, 9248, 9246, -1, 7145, 9249, 9250, -1, 7096, 9251, 9232, -1, 9248, 9249, 7145, -1, 9232, 9251, 9226, -1, 9060, 9252, 9195, -1, 9226, 9251, 9244, -1, 9250, 9252, 9198, -1, 9230, 9253, 9245, -1, 9198, 9252, 9060, -1, 9195, 9252, 9248, -1, 9248, 9252, 9249, -1, 9249, 9252, 9250, -1, 9250, 9254, 7145, -1, 9198, 9254, 9250, -1, 9236, 9253, 9230, -1, 9244, 8735, 9239, -1, 9239, 8735, 9247, -1, 9254, 9255, 7145, -1, 9201, 9255, 9197, -1, 9197, 9255, 9198, -1, 9245, 8741, 7191, -1, 9198, 9255, 9254, -1, 7145, 9256, 7137, -1, 9255, 9256, 7145, -1, 9236, 9257, 9253, -1, 9201, 9256, 9255, -1, 9241, 9257, 9236, -1, 7096, 8734, 9251, -1, 9202, 9258, 9201, -1, 7094, 8734, 7096, -1, 9256, 9258, 7137, -1, 9201, 9258, 9256, -1, 9244, 8734, 8735, -1, 7137, 9259, 9169, -1, 9251, 8734, 9244, -1, 9169, 9259, 9172, -1, 9258, 9259, 7137, -1, 9082, 9260, 9202, -1, 9245, 8739, 8741, -1, 9172, 9260, 9082, -1, 9202, 9260, 9258, -1, 9253, 8739, 9245, -1, 9259, 9260, 9172, -1, 9247, 8745, 9241, -1, 9258, 9260, 9259, -1, 9241, 8745, 9257, -1, 9210, 9261, 9205, -1, 7101, 9261, 9210, -1, 9204, 9262, 9207, -1, 9261, 9262, 9205, -1, 9253, 8754, 8739, -1, 9205, 9262, 9204, -1, 9257, 8754, 9253, -1, 7100, 9263, 7101, -1, 9247, 8736, 8745, -1, 9262, 9263, 9207, -1, 8735, 8736, 9247, -1, 9261, 9263, 9262, -1, 7101, 9263, 9261, -1, 9207, 9264, 9209, -1, 8741, 8743, 7191, -1, 9209, 9264, 8732, -1, 9263, 9264, 9207, -1, 7191, 8743, 7189, -1, 8745, 8747, 9257, -1, 8731, 9265, 7100, -1, 8732, 9265, 8731, -1, 7100, 9265, 9263, -1, 9264, 9265, 8732, -1, 9257, 8747, 8754, -1, 9263, 9265, 9264, -1, 7064, 9266, 9267, -1, 9268, 9269, 9270, -1, 9271, 9266, 9272, -1, 9273, 9274, 9275, -1, 7293, 9276, 9277, -1, 7287, 9276, 7293, -1, 9277, 9276, 9278, -1, 7275, 9274, 9273, -1, 9278, 9276, 9279, -1, 9280, 9281, 9282, -1, 9283, 9284, 9285, -1, 7275, 9284, 9274, -1, 9274, 9284, 9275, -1, 9282, 9281, 9286, -1, 9275, 9284, 9283, -1, 7273, 9287, 7275, -1, 9284, 9287, 9285, -1, 7275, 9287, 9284, -1, 9288, 9289, 9269, -1, 9279, 9289, 9288, -1, 9290, 9291, 9292, -1, 9292, 9291, 9293, -1, 9294, 9291, 9290, -1, 9286, 9295, 7058, -1, 7273, 9296, 9287, -1, 7058, 9295, 7056, -1, 9294, 9296, 9291, -1, 9270, 9297, 9280, -1, 9285, 9296, 9294, -1, 9280, 9297, 9281, -1, 9287, 9296, 9285, -1, 9293, 9298, 7273, -1, 7273, 9298, 9296, -1, 9296, 9298, 9291, -1, 9291, 9298, 9293, -1, 9276, 9299, 9279, -1, 9279, 9299, 9289, -1, 7273, 9300, 9293, -1, 7287, 9299, 9276, -1, 9293, 9300, 9292, -1, 9281, 9301, 9286, -1, 9286, 9301, 9295, -1, 9292, 9302, 9303, -1, 7273, 9302, 9300, -1, 9300, 9302, 9292, -1, 9269, 9304, 9270, -1, 9303, 9302, 9305, -1, 9270, 9304, 9297, -1, 7270, 9306, 7273, -1, 7273, 9306, 9302, -1, 9302, 9306, 9305, -1, 9307, 9308, 9309, -1, 9297, 9310, 9281, -1, 9281, 9310, 9301, -1, 9309, 9308, 9311, -1, 9312, 9308, 9307, -1, 9289, 9313, 9269, -1, 7270, 9314, 9306, -1, 9269, 9313, 9304, -1, 9305, 9314, 9312, -1, 9306, 9314, 9305, -1, 9312, 9314, 9308, -1, 9311, 9315, 7270, -1, 9295, 9316, 7056, -1, 9308, 9315, 9311, -1, 9314, 9315, 9308, -1, 7270, 9315, 9314, -1, 7270, 9317, 9311, -1, 9311, 9317, 9309, -1, 9304, 9318, 9297, -1, 9297, 9318, 9310, -1, 9317, 9319, 9309, -1, 7287, 9320, 9299, -1, 9309, 9319, 9321, -1, 7285, 9320, 7287, -1, 9289, 9320, 9313, -1, 7270, 9319, 9317, -1, 9299, 9320, 9289, -1, 9321, 9319, 9322, -1, 7269, 9323, 7270, -1, 9301, 9324, 9295, -1, 7270, 9323, 9319, -1, 9295, 9324, 9316, -1, 9319, 9323, 9322, -1, 9325, 9326, 9327, -1, 9328, 9326, 9325, -1, 9304, 9329, 9318, -1, 9313, 9329, 9304, -1, 7269, 9330, 9323, -1, 9323, 9330, 9322, -1, 9310, 9331, 9301, -1, 9328, 9330, 9326, -1, 9322, 9330, 9328, -1, 9301, 9331, 9324, -1, 9332, 9333, 7269, -1, 9327, 9333, 9332, -1, 9326, 9333, 9327, -1, 7269, 9333, 9330, -1, 9316, 9334, 7056, -1, 9330, 9333, 9326, -1, 7056, 9334, 7054, -1, 7285, 9335, 9320, -1, 9320, 9335, 9313, -1, 9313, 9335, 9329, -1, 9318, 9336, 9310, -1, 9310, 9336, 9331, -1, 9316, 9337, 9334, -1, 9324, 9337, 9316, -1, 9329, 9338, 9318, -1, 9318, 9338, 9336, -1, 9324, 9339, 9337, -1, 9331, 9339, 9324, -1, 9334, 9340, 7054, -1, 9329, 9341, 9338, -1, 7283, 9341, 7285, -1, 7285, 9341, 9335, -1, 9335, 9341, 9329, -1, 9331, 9342, 9339, -1, 9336, 9342, 9331, -1, 9334, 9343, 9340, -1, 9337, 9343, 9334, -1, 9336, 9344, 9342, -1, 9338, 9344, 9336, -1, 9339, 9345, 9337, -1, 9337, 9345, 9343, -1, 9340, 9346, 7054, -1, 7054, 9346, 7052, -1, 9338, 9347, 9344, -1, 9341, 9347, 9338, -1, 7283, 9347, 9341, -1, 9339, 9348, 9345, -1, 9342, 9348, 9339, -1, 9340, 9349, 9346, -1, 9343, 9349, 9340, -1, 9344, 9350, 9342, -1, 9342, 9350, 9348, -1, 9346, 9351, 7052, -1, 9345, 9352, 9343, -1, 9343, 9352, 9349, -1, 7281, 9353, 7283, -1, 7283, 9353, 9347, -1, 9344, 9353, 9350, -1, 9347, 9353, 9344, -1, 9349, 9354, 9346, -1, 9346, 9354, 9351, -1, 9348, 9355, 9345, -1, 9345, 9355, 9352, -1, 9349, 9356, 9354, -1, 9352, 9356, 9349, -1, 9348, 9357, 9355, -1, 9350, 9357, 9348, -1, 9351, 9358, 7052, -1, 7052, 9358, 7050, -1, 9355, 9359, 9352, -1, 9352, 9359, 9356, -1, 7281, 9360, 9353, -1, 9353, 9360, 9350, -1, 9350, 9360, 9357, -1, 9351, 9361, 9358, -1, 9354, 9361, 9351, -1, 9357, 9362, 9355, -1, 9355, 9362, 9359, -1, 9358, 9363, 7050, -1, 9356, 9364, 9354, -1, 9354, 9364, 9361, -1, 7280, 9365, 7281, -1, 7281, 9365, 9360, -1, 9357, 9365, 9362, -1, 9360, 9365, 9357, -1, 9361, 9366, 9358, -1, 9358, 9366, 9363, -1, 9356, 9367, 9364, -1, 9359, 9367, 9356, -1, 9361, 9368, 9366, -1, 9364, 9368, 9361, -1, 9359, 9369, 9367, -1, 9362, 9369, 9359, -1, 7050, 9370, 7048, -1, 9363, 9370, 7050, -1, 9367, 9371, 9364, -1, 9364, 9371, 9368, -1, 7280, 9372, 9365, -1, 9365, 9372, 9362, -1, 9362, 9372, 9369, -1, 9366, 9373, 9363, -1, 9363, 9373, 9370, -1, 7036, 1755, 1757, -1, 9367, 9374, 9371, -1, 9369, 9374, 9367, -1, 9370, 9375, 7048, -1, 9366, 9376, 9373, -1, 9368, 9376, 9366, -1, 7278, 9377, 7280, -1, 9369, 9377, 9374, -1, 7280, 9377, 9372, -1, 9372, 9377, 9369, -1, 9370, 9378, 9375, -1, 9373, 9378, 9370, -1, 9371, 9379, 9368, -1, 9368, 9379, 9376, -1, 1746, 9380, 1747, -1, 1747, 9380, 7065, -1, 9376, 9381, 9373, -1, 9373, 9381, 9378, -1, 1746, 9382, 9380, -1, 1828, 9382, 1746, -1, 9374, 9383, 9371, -1, 9371, 9383, 9379, -1, 9379, 9384, 9376, -1, 1835, 9385, 1828, -1, 9376, 9384, 9381, -1, 1828, 9385, 9382, -1, 9375, 9386, 7048, -1, 1837, 9387, 1835, -1, 7048, 9386, 7045, -1, 1835, 9387, 9385, -1, 9377, 9388, 9374, -1, 1837, 9389, 9387, -1, 9374, 9388, 9383, -1, 7278, 9388, 9377, -1, 1840, 9389, 1837, -1, 9383, 9390, 9379, -1, 9380, 9391, 7065, -1, 9379, 9390, 9384, -1, 7065, 9391, 7063, -1, 9375, 9392, 9386, -1, 9378, 9392, 9375, -1, 7237, 9393, 1843, -1, 1842, 9393, 1840, -1, 1843, 9393, 1842, -1, 1840, 9393, 9389, -1, 9386, 9394, 7045, -1, 7276, 9395, 7278, -1, 9380, 9396, 9391, -1, 7278, 9395, 9388, -1, 9382, 9396, 9380, -1, 9388, 9395, 9383, -1, 9383, 9395, 9390, -1, 9381, 9397, 9378, -1, 9385, 9398, 9382, -1, 9378, 9397, 9392, -1, 9382, 9398, 9396, -1, 9385, 9399, 9398, -1, 9392, 9400, 9386, -1, 9387, 9399, 9385, -1, 9386, 9400, 9394, -1, 9381, 9401, 9397, -1, 9387, 9402, 9399, -1, 9384, 9401, 9381, -1, 9389, 9402, 9387, -1, 9391, 9403, 7063, -1, 9397, 9404, 9392, -1, 9392, 9404, 9400, -1, 7063, 9403, 7061, -1, 9390, 9405, 9384, -1, 9393, 9406, 9389, -1, 7241, 9406, 7237, -1, 7237, 9406, 9393, -1, 9384, 9405, 9401, -1, 9389, 9406, 9402, -1, 9401, 9407, 9397, -1, 9397, 9407, 9404, -1, 9396, 9408, 9391, -1, 9391, 9408, 9403, -1, 9394, 9409, 7045, -1, 9398, 9410, 9396, -1, 7045, 9409, 7043, -1, 9396, 9410, 9408, -1, 7276, 9411, 9395, -1, 9395, 9411, 9390, -1, 9390, 9411, 9405, -1, 9399, 9412, 9398, -1, 9398, 9412, 9410, -1, 9401, 9413, 9407, -1, 9405, 9413, 9401, -1, 9399, 9414, 9412, -1, 9394, 9415, 9409, -1, 9400, 9415, 9394, -1, 9402, 9414, 9399, -1, 7275, 9416, 7276, -1, 7276, 9416, 9411, -1, 9411, 9416, 9405, -1, 7241, 9417, 9406, -1, 9406, 9417, 9402, -1, 9405, 9416, 9413, -1, 9402, 9417, 9414, -1, 7247, 9417, 7241, -1, 9400, 9418, 9415, -1, 9404, 9418, 9400, -1, 9407, 9419, 9404, -1, 9404, 9419, 9418, -1, 9407, 9275, 9419, -1, 9413, 9275, 9407, -1, 7275, 9273, 9416, -1, 9416, 9273, 9413, -1, 9413, 9273, 9275, -1, 7057, 9420, 7055, -1, 9421, 9420, 7057, -1, 9421, 9422, 9420, -1, 9423, 9422, 9421, -1, 9423, 9424, 9422, -1, 9425, 9424, 9423, -1, 9425, 9426, 9424, -1, 9427, 9426, 9425, -1, 9420, 9428, 7055, -1, 7036, 9429, 1755, -1, 9430, 9431, 9427, -1, 9427, 9431, 9426, -1, 9422, 9432, 9420, -1, 9420, 9432, 9428, -1, 7055, 9433, 7053, -1, 9428, 9433, 7055, -1, 9429, 9434, 1755, -1, 1755, 9434, 1761, -1, 9435, 9436, 9430, -1, 7254, 9436, 9435, -1, 9430, 9436, 9431, -1, 9424, 9437, 9422, -1, 9434, 9438, 1761, -1, 9422, 9437, 9432, -1, 1761, 9438, 1765, -1, 9432, 9439, 9428, -1, 9428, 9439, 9433, -1, 9438, 9325, 1765, -1, 9426, 9440, 9424, -1, 1765, 9325, 1767, -1, 9424, 9440, 9437, -1, 9325, 9327, 1767, -1, 1767, 9327, 1772, -1, 9437, 9441, 9432, -1, 9432, 9441, 9439, -1, 1779, 9332, 7269, -1, 9431, 9442, 9426, -1, 9327, 9332, 1772, -1, 9426, 9442, 9440, -1, 1772, 9332, 1780, -1, 1780, 9332, 1779, -1, 9417, 9443, 9414, -1, 9433, 9444, 7053, -1, 7247, 9443, 9417, -1, 7247, 9445, 9443, -1, 9440, 9446, 9437, -1, 9437, 9446, 9441, -1, 7260, 9447, 7254, -1, 7250, 9448, 7247, -1, 9431, 9447, 9442, -1, 9449, 9448, 7250, -1, 7254, 9447, 9436, -1, 7247, 9448, 9445, -1, 9436, 9447, 9431, -1, 7250, 9450, 9449, -1, 9439, 9451, 9433, -1, 9433, 9451, 9444, -1, 9449, 9450, 9452, -1, 9442, 9453, 9440, -1, 7250, 9454, 9450, -1, 9440, 9453, 9446, -1, 7254, 9455, 7250, -1, 7250, 9455, 9454, -1, 7053, 9456, 7051, -1, 9444, 9456, 7053, -1, 9435, 9455, 7254, -1, 9457, 9458, 7038, -1, 9459, 9458, 9457, -1, 9439, 9460, 9451, -1, 9441, 9460, 9439, -1, 7260, 9461, 9447, -1, 9447, 9461, 9442, -1, 9442, 9461, 9453, -1, 9451, 9462, 9444, -1, 9458, 9463, 7038, -1, 9444, 9462, 9456, -1, 9463, 9464, 7038, -1, 9441, 9465, 9460, -1, 9446, 9465, 9441, -1, 7038, 9466, 7037, -1, 7037, 9466, 9467, -1, 9464, 9466, 7038, -1, 9451, 9468, 9462, -1, 9460, 9468, 9451, -1, 9467, 9469, 7037, -1, 9470, 9469, 9467, -1, 9453, 9471, 9446, -1, 9446, 9471, 9465, -1, 9469, 9472, 7037, -1, 9456, 9473, 7051, -1, 7037, 9474, 7035, -1, 9465, 9475, 9460, -1, 9472, 9474, 7037, -1, 7035, 9476, 9477, -1, 9460, 9475, 9468, -1, 9474, 9476, 7035, -1, 7260, 9478, 9461, -1, 9479, 9480, 9477, -1, 9461, 9478, 9453, -1, 9477, 9480, 7035, -1, 7263, 9478, 7260, -1, 9453, 9478, 9471, -1, 9462, 9481, 9456, -1, 9479, 9482, 9480, -1, 9456, 9481, 9473, -1, 9480, 9482, 7035, -1, 9471, 9483, 9465, -1, 9465, 9483, 9475, -1, 7035, 9484, 7034, -1, 9482, 9484, 7035, -1, 9473, 9485, 7051, -1, 9484, 9486, 7034, -1, 7034, 9486, 9487, -1, 7051, 9485, 7049, -1, 9468, 9488, 9462, -1, 7211, 9489, 9490, -1, 9462, 9488, 9481, -1, 9490, 9489, 9491, -1, 9471, 9492, 9483, -1, 7211, 9493, 9489, -1, 7263, 9492, 9478, -1, 9478, 9492, 9471, -1, 7210, 9494, 7211, -1, 9481, 9495, 9473, -1, 7211, 9494, 9493, -1, 9473, 9495, 9485, -1, 9496, 9494, 7210, -1, 9468, 9497, 9488, -1, 7210, 9498, 9496, -1, 9475, 9497, 9468, -1, 9496, 9498, 9499, -1, 7210, 9500, 9498, -1, 9488, 9501, 9481, -1, 9481, 9501, 9495, -1, 7296, 9502, 7210, -1, 7210, 9502, 9500, -1, 9483, 9503, 9475, -1, 9475, 9503, 9497, -1, 9504, 9502, 7296, -1, 9415, 9505, 9409, -1, 9485, 9506, 7049, -1, 9409, 9505, 7043, -1, 9497, 9507, 9488, -1, 9505, 9508, 7043, -1, 9488, 9507, 9501, -1, 7263, 9509, 9492, -1, 7267, 9509, 7263, -1, 9492, 9509, 9483, -1, 9483, 9509, 9503, -1, 9508, 9510, 7043, -1, 9510, 9511, 7043, -1, 9495, 9512, 9485, -1, 7043, 9511, 7041, -1, 9485, 9512, 9506, -1, 7041, 9511, 9513, -1, 9514, 9515, 9513, -1, 9503, 9516, 9497, -1, 9497, 9516, 9507, -1, 9513, 9515, 7041, -1, 9501, 9517, 9495, -1, 9495, 9517, 9512, -1, 9515, 9518, 7041, -1, 7049, 9519, 7047, -1, 9506, 9519, 7049, -1, 9518, 9520, 7041, -1, 7041, 9520, 7039, -1, 9503, 9521, 9516, -1, 7039, 9522, 9523, -1, 7267, 9521, 9509, -1, 9509, 9521, 9503, -1, 9520, 9522, 7039, -1, 9523, 9524, 7039, -1, 9507, 9525, 9501, -1, 9526, 9524, 9523, -1, 9501, 9525, 9517, -1, 9524, 9527, 7039, -1, 9512, 9528, 9506, -1, 9506, 9528, 9519, -1, 9526, 9527, 9524, -1, 9527, 9529, 7039, -1, 9516, 9530, 9507, -1, 9507, 9530, 9525, -1, 7039, 9529, 7036, -1, 7036, 9531, 9429, -1, 9512, 9532, 9528, -1, 9529, 9531, 7036, -1, 9412, 9533, 9410, -1, 9517, 9532, 9512, -1, 9414, 9533, 9412, -1, 9443, 9534, 9414, -1, 9519, 9535, 7047, -1, 9445, 9534, 9443, -1, 9516, 9536, 9530, -1, 9414, 9534, 9533, -1, 7268, 9536, 7267, -1, 7267, 9536, 9521, -1, 9521, 9536, 9516, -1, 9517, 9537, 9532, -1, 9445, 9538, 9534, -1, 9525, 9537, 9517, -1, 9519, 9539, 9535, -1, 9448, 9540, 9445, -1, 9445, 9540, 9538, -1, 9528, 9539, 9519, -1, 9525, 9541, 9537, -1, 9542, 9543, 9452, -1, 9544, 9543, 9542, -1, 9540, 9545, 9543, -1, 9449, 9545, 9448, -1, 9530, 9541, 9525, -1, 9448, 9545, 9540, -1, 9543, 9545, 9452, -1, 9532, 9546, 9528, -1, 9452, 9545, 9449, -1, 9452, 9547, 9542, -1, 9528, 9546, 9539, -1, 9542, 9547, 9544, -1, 9452, 9548, 9547, -1, 9535, 9549, 7047, -1, 9450, 9548, 9452, -1, 7047, 9549, 7046, -1, 9454, 9548, 9450, -1, 7268, 9550, 9536, -1, 9530, 9550, 9541, -1, 9536, 9550, 9530, -1, 9537, 9551, 9532, -1, 9532, 9551, 9546, -1, 9454, 9552, 9548, -1, 9539, 9553, 9535, -1, 9455, 9554, 9454, -1, 9454, 9554, 9552, -1, 9427, 9555, 9430, -1, 9535, 9553, 9549, -1, 9425, 9555, 9427, -1, 9541, 9556, 9537, -1, 9555, 9557, 9430, -1, 9455, 9557, 9554, -1, 9435, 9557, 9455, -1, 9430, 9557, 9435, -1, 9537, 9556, 9551, -1, 9554, 9557, 9555, -1, 9549, 9558, 7046, -1, 9559, 9560, 9459, -1, 9546, 9561, 9539, -1, 9562, 9560, 9559, -1, 9459, 9563, 9458, -1, 9539, 9561, 9553, -1, 9560, 9563, 9459, -1, 9458, 9563, 9463, -1, 7268, 9564, 9550, -1, 7264, 9564, 7268, -1, 9550, 9564, 9541, -1, 9463, 9565, 9464, -1, 9541, 9564, 9556, -1, 9464, 9565, 9466, -1, 9553, 9566, 9549, -1, 9549, 9566, 9558, -1, 9546, 9567, 9561, -1, 9463, 9568, 9565, -1, 9563, 9568, 9463, -1, 9565, 9569, 9466, -1, 9551, 9567, 9546, -1, 9466, 9569, 9467, -1, 9561, 9570, 9553, -1, 9565, 9571, 9569, -1, 9568, 9571, 9565, -1, 9553, 9570, 9566, -1, 9571, 9572, 9569, -1, 9556, 9573, 9551, -1, 9551, 9573, 9567, -1, 9568, 9574, 9571, -1, 9558, 9575, 7046, -1, 9569, 9576, 9467, -1, 7046, 9575, 7044, -1, 9572, 9576, 9569, -1, 9467, 9576, 9470, -1, 9470, 9576, 9577, -1, 9561, 9578, 9570, -1, 9577, 9579, 9580, -1, 9567, 9578, 9561, -1, 9576, 9579, 9577, -1, 9571, 9579, 9572, -1, 9574, 9579, 9571, -1, 9572, 9579, 9576, -1, 9580, 9581, 9577, -1, 7264, 9582, 9564, -1, 9564, 9582, 9556, -1, 9556, 9582, 9573, -1, 9577, 9581, 9470, -1, 9558, 9583, 9575, -1, 9566, 9583, 9558, -1, 9581, 9584, 9470, -1, 9470, 9584, 9469, -1, 9469, 9584, 9472, -1, 9573, 9585, 9567, -1, 9567, 9585, 9578, -1, 9472, 9586, 9474, -1, 9474, 9586, 9476, -1, 9476, 9587, 9477, -1, 9575, 9588, 7044, -1, 9586, 9587, 9476, -1, 9570, 9589, 9566, -1, 9566, 9589, 9583, -1, 9584, 9590, 9472, -1, 9472, 9590, 9586, -1, 7262, 9591, 7264, -1, 7264, 9591, 9582, -1, 9582, 9591, 9573, -1, 9573, 9591, 9585, -1, 9583, 9592, 9575, -1, 9586, 9593, 9587, -1, 9575, 9592, 9588, -1, 9590, 9593, 9586, -1, 9593, 9594, 9587, -1, 9578, 9595, 9570, -1, 9590, 9596, 9593, -1, 9570, 9595, 9589, -1, 9477, 9597, 9479, -1, 9587, 9597, 9477, -1, 9479, 9597, 9598, -1, 9594, 9597, 9587, -1, 9589, 9599, 9583, -1, 9598, 9600, 9601, -1, 9583, 9599, 9592, -1, 9593, 9600, 9594, -1, 9596, 9600, 9593, -1, 9597, 9600, 9598, -1, 9578, 9602, 9595, -1, 9594, 9600, 9597, -1, 9585, 9602, 9578, -1, 9601, 9603, 9598, -1, 9598, 9603, 9479, -1, 7044, 9604, 7042, -1, 9588, 9604, 7044, -1, 9479, 9605, 9482, -1, 9603, 9605, 9479, -1, 9482, 9606, 9484, -1, 9595, 9607, 9589, -1, 9589, 9607, 9599, -1, 9484, 9606, 9486, -1, 7262, 9608, 9591, -1, 9606, 9609, 9486, -1, 9591, 9608, 9585, -1, 9486, 9609, 9487, -1, 9585, 9608, 9602, -1, 9588, 9610, 9604, -1, 9592, 9610, 9588, -1, 9605, 9611, 9482, -1, 9595, 9612, 9607, -1, 9482, 9611, 9606, -1, 9611, 9613, 9606, -1, 9606, 9613, 9609, -1, 9602, 9612, 9595, -1, 9604, 9614, 7042, -1, 9613, 9615, 9609, -1, 9611, 9616, 9613, -1, 9592, 9617, 9610, -1, 9487, 9618, 9619, -1, 9619, 9618, 9620, -1, 9609, 9618, 9487, -1, 9599, 9617, 9592, -1, 9615, 9618, 9609, -1, 7262, 9621, 9608, -1, 9620, 9622, 9623, -1, 9602, 9621, 9612, -1, 7257, 9621, 7262, -1, 9618, 9622, 9620, -1, 9608, 9621, 9602, -1, 9613, 9622, 9615, -1, 9610, 9624, 9604, -1, 9616, 9622, 9613, -1, 9615, 9622, 9618, -1, 9604, 9624, 9614, -1, 9491, 9625, 9626, -1, 9599, 9627, 9617, -1, 9626, 9625, 9628, -1, 9489, 9629, 9491, -1, 9493, 9629, 9489, -1, 9607, 9627, 9599, -1, 9617, 9630, 9610, -1, 9491, 9629, 9625, -1, 9610, 9630, 9624, -1, 9493, 9631, 9629, -1, 9607, 9632, 9627, -1, 9612, 9632, 9607, -1, 9493, 9633, 9631, -1, 9627, 9634, 9617, -1, 9494, 9633, 9493, -1, 9617, 9634, 9630, -1, 9635, 9636, 9637, -1, 9637, 9636, 9499, -1, 9614, 9638, 7042, -1, 9496, 9639, 9494, -1, 9499, 9639, 9496, -1, 9494, 9639, 9633, -1, 7042, 9638, 7040, -1, 9636, 9639, 9499, -1, 9633, 9639, 9636, -1, 9621, 9640, 9612, -1, 7257, 9640, 9621, -1, 9637, 9641, 9635, -1, 9612, 9640, 9632, -1, 9499, 9641, 9637, -1, 9498, 9642, 9499, -1, 9500, 9642, 9498, -1, 9632, 9643, 9627, -1, 9627, 9643, 9634, -1, 9499, 9642, 9641, -1, 9624, 9644, 9614, -1, 9500, 9645, 9642, -1, 9614, 9644, 9638, -1, 9638, 9646, 7040, -1, 9500, 9647, 9645, -1, 7251, 9648, 7257, -1, 7257, 9648, 9640, -1, 9502, 9647, 9500, -1, 9640, 9648, 9632, -1, 9632, 9648, 9643, -1, 9630, 9649, 9624, -1, 9650, 9651, 9652, -1, 9652, 9651, 9653, -1, 9502, 9654, 9647, -1, 9651, 9654, 9653, -1, 9624, 9649, 9644, -1, 9647, 9654, 9651, -1, 9504, 9654, 9502, -1, 9653, 9654, 9504, -1, 9644, 9655, 9638, -1, 9638, 9655, 9646, -1, 9418, 9656, 9415, -1, 9419, 9656, 9418, -1, 9634, 9657, 9630, -1, 9505, 9658, 9508, -1, 9630, 9657, 9649, -1, 9656, 9658, 9415, -1, 9415, 9658, 9505, -1, 9508, 9659, 9510, -1, 9649, 9660, 9644, -1, 9644, 9660, 9655, -1, 9510, 9659, 9511, -1, 9643, 9661, 9634, -1, 9508, 9662, 9659, -1, 9634, 9661, 9657, -1, 9658, 9662, 9508, -1, 9649, 9663, 9660, -1, 9657, 9663, 9649, -1, 9659, 9664, 9511, -1, 9511, 9664, 9513, -1, 9646, 9457, 7040, -1, 9662, 9665, 9659, -1, 7040, 9457, 7038, -1, 9659, 9665, 9664, -1, 9665, 9666, 9664, -1, 7251, 9667, 9648, -1, 9648, 9667, 9643, -1, 9643, 9667, 9661, -1, 9662, 9668, 9665, -1, 9513, 9669, 9514, -1, 9664, 9669, 9513, -1, 9661, 9670, 9657, -1, 9666, 9669, 9664, -1, 9657, 9670, 9663, -1, 9514, 9669, 9671, -1, 9671, 9672, 9290, -1, 9655, 9459, 9646, -1, 9665, 9672, 9666, -1, 9646, 9459, 9457, -1, 9668, 9672, 9665, -1, 9669, 9672, 9671, -1, 9666, 9672, 9669, -1, 9290, 9673, 9671, -1, 7249, 9674, 7251, -1, 7251, 9674, 9667, -1, 9667, 9674, 9661, -1, 9671, 9673, 9514, -1, 9514, 9675, 9515, -1, 9661, 9674, 9670, -1, 9660, 9559, 9655, -1, 9655, 9559, 9459, -1, 9515, 9675, 9518, -1, 9673, 9675, 9514, -1, 9518, 9676, 9520, -1, 9663, 9562, 9660, -1, 9520, 9676, 9522, -1, 9660, 9562, 9559, -1, 9522, 9677, 9523, -1, 9663, 9678, 9562, -1, 9670, 9678, 9663, -1, 9676, 9677, 9522, -1, 9518, 9679, 9676, -1, 9675, 9679, 9518, -1, 9679, 9680, 9676, -1, 7249, 9681, 9674, -1, 9676, 9680, 9677, -1, 9674, 9681, 9670, -1, 9670, 9681, 9678, -1, 9680, 9682, 9677, -1, 9679, 9683, 9680, -1, 9523, 9684, 9526, -1, 9526, 9684, 9685, -1, 9677, 9684, 9523, -1, 9682, 9684, 9677, -1, 9685, 9686, 9307, -1, 9684, 9686, 9685, -1, 9680, 9686, 9682, -1, 9683, 9686, 9680, -1, 9682, 9686, 9684, -1, 9685, 9687, 9526, -1, 9307, 9687, 9685, -1, 9526, 9688, 9527, -1, 9687, 9688, 9526, -1, 9527, 9689, 9529, -1, 9529, 9689, 9531, -1, 9689, 9690, 9531, -1, 9531, 9690, 9429, -1, 9688, 9691, 9527, -1, 9527, 9691, 9689, -1, 9689, 9692, 9690, -1, 9691, 9692, 9689, -1, 9692, 9693, 9690, -1, 9691, 9694, 9692, -1, 9434, 9695, 9438, -1, 9429, 9695, 9434, -1, 9690, 9695, 9429, -1, 9693, 9695, 9690, -1, 9694, 9696, 9692, -1, 9695, 9696, 9438, -1, 9438, 9696, 9325, -1, 9693, 9696, 9695, -1, 9692, 9696, 9693, -1, 9410, 9697, 9408, -1, 9533, 9697, 9410, -1, 9534, 9697, 9533, -1, 9538, 9697, 9534, -1, 9538, 9698, 9697, -1, 9540, 9699, 9538, -1, 9538, 9699, 9698, -1, 9700, 9699, 9544, -1, 9543, 9699, 9540, -1, 9544, 9699, 9543, -1, 9547, 9701, 9544, -1, 9544, 9701, 9700, -1, 9548, 9701, 9547, -1, 9552, 9701, 9548, -1, 9552, 9702, 9701, -1, 9487, 9703, 7034, -1, 9423, 9704, 9425, -1, 7034, 9703, 7033, -1, 9552, 9704, 9702, -1, 9554, 9704, 9552, -1, 9425, 9704, 9555, -1, 9555, 9704, 9554, -1, 9563, 9705, 9568, -1, 9562, 9705, 9560, -1, 9487, 9706, 9703, -1, 9678, 9705, 9562, -1, 9619, 9706, 9487, -1, 9560, 9705, 9563, -1, 9705, 9707, 9568, -1, 9620, 9708, 9619, -1, 9619, 9708, 9706, -1, 9707, 9709, 9568, -1, 9568, 9709, 9574, -1, 9579, 9709, 9580, -1, 9620, 9710, 9708, -1, 9574, 9709, 9579, -1, 9623, 9710, 9620, -1, 9711, 9712, 9580, -1, 9580, 9712, 9581, -1, 9584, 9712, 9590, -1, 9713, 9714, 9623, -1, 9581, 9712, 9584, -1, 9623, 9714, 9710, -1, 9712, 9715, 9590, -1, 9703, 9716, 7033, -1, 7033, 9716, 7032, -1, 9715, 9717, 9590, -1, 7229, 9718, 7233, -1, 7233, 9718, 9719, -1, 9719, 9718, 9713, -1, 9590, 9717, 9596, -1, 9713, 9718, 9714, -1, 9600, 9717, 9601, -1, 9596, 9717, 9600, -1, 9706, 9720, 9703, -1, 9721, 9722, 9601, -1, 9703, 9720, 9716, -1, 9603, 9722, 9605, -1, 9605, 9722, 9611, -1, 9601, 9722, 9603, -1, 9706, 9723, 9720, -1, 9708, 9723, 9706, -1, 9722, 9724, 9611, -1, 9710, 9725, 9708, -1, 9724, 9726, 9611, -1, 9708, 9725, 9723, -1, 9611, 9726, 9616, -1, 9622, 9726, 9623, -1, 9616, 9726, 9622, -1, 9628, 9727, 9728, -1, 9714, 9729, 9710, -1, 9710, 9729, 9725, -1, 9625, 9727, 9628, -1, 9629, 9727, 9625, -1, 7032, 9730, 7068, -1, 9631, 9727, 9629, -1, 9716, 9730, 7032, -1, 9631, 9731, 9727, -1, 7225, 9732, 7229, -1, 7229, 9732, 9718, -1, 9718, 9732, 9714, -1, 9714, 9732, 9729, -1, 9635, 9733, 9636, -1, 9631, 9733, 9731, -1, 9720, 9734, 9716, -1, 9633, 9733, 9631, -1, 9735, 9733, 9635, -1, 9636, 9733, 9633, -1, 9641, 9736, 9635, -1, 9716, 9734, 9730, -1, 9645, 9736, 9642, -1, 9723, 9737, 9720, -1, 9642, 9736, 9641, -1, 9720, 9737, 9734, -1, 9635, 9736, 9735, -1, 9725, 9738, 9723, -1, 9645, 9739, 9736, -1, 9723, 9738, 9737, -1, 9645, 9740, 9739, -1, 9651, 9740, 9647, -1, 9650, 9740, 9651, -1, 9647, 9740, 9645, -1, 9741, 9740, 9650, -1, 9729, 9742, 9725, -1, 9725, 9742, 9738, -1, 7068, 9743, 7067, -1, 9656, 9283, 9658, -1, 9730, 9743, 7068, -1, 9419, 9283, 9656, -1, 9658, 9283, 9662, -1, 9275, 9283, 9419, -1, 9729, 9744, 9742, -1, 7216, 9744, 7225, -1, 7225, 9744, 9732, -1, 9732, 9744, 9729, -1, 9730, 9728, 9743, -1, 9283, 9285, 9662, -1, 9734, 9728, 9730, -1, 9662, 9294, 9668, -1, 9672, 9294, 9290, -1, 9668, 9294, 9672, -1, 9734, 9628, 9728, -1, 9285, 9294, 9662, -1, 9292, 9303, 9290, -1, 9290, 9303, 9673, -1, 9737, 9628, 9734, -1, 9673, 9303, 9675, -1, 9675, 9303, 9679, -1, 9737, 9626, 9628, -1, 9738, 9626, 9737, -1, 9742, 9491, 9738, -1, 9738, 9491, 9626, -1, 9303, 9305, 9679, -1, 9679, 9312, 9683, -1, 9686, 9312, 9307, -1, 9683, 9312, 9686, -1, 9305, 9312, 9679, -1, 9309, 9321, 9307, -1, 7216, 9490, 9744, -1, 7211, 9490, 7216, -1, 9307, 9321, 9687, -1, 9742, 9490, 9491, -1, 9687, 9321, 9688, -1, 9744, 9490, 9742, -1, 9688, 9321, 9691, -1, 9321, 9322, 9691, -1, 9691, 9328, 9694, -1, 9694, 9328, 9696, -1, 9696, 9328, 9325, -1, 9322, 9328, 9691, -1, 9403, 9745, 7061, -1, 9408, 9745, 9403, -1, 9408, 9746, 9745, -1, 9697, 9746, 9408, -1, 9698, 9746, 9697, -1, 9745, 9747, 7061, -1, 7061, 9747, 7059, -1, 9746, 9747, 9745, -1, 9698, 9747, 9746, -1, 9698, 9748, 9747, -1, 9700, 9748, 9699, -1, 9699, 9748, 9698, -1, 9747, 9749, 7059, -1, 9700, 9749, 9748, -1, 9750, 9749, 9700, -1, 7059, 9749, 9750, -1, 9748, 9749, 9747, -1, 9700, 9751, 9750, -1, 9267, 9752, 7064, -1, 7064, 9752, 7062, -1, 9750, 9751, 7059, -1, 9701, 9753, 9700, -1, 9702, 9753, 9701, -1, 9700, 9753, 9751, -1, 9753, 9754, 9751, -1, 9751, 9754, 7059, -1, 9702, 9754, 9753, -1, 9741, 9755, 9267, -1, 7059, 9754, 7057, -1, 9267, 9755, 9752, -1, 9704, 9756, 9702, -1, 9702, 9756, 9754, -1, 9423, 9756, 9704, -1, 9756, 9757, 9754, -1, 9754, 9757, 7057, -1, 9423, 9757, 9756, -1, 7057, 9757, 9421, -1, 9741, 9758, 9755, -1, 9421, 9757, 9423, -1, 9681, 9759, 9678, -1, 9650, 9758, 9741, -1, 7249, 9759, 9681, -1, 9678, 9760, 9705, -1, 9705, 9760, 9707, -1, 9652, 9761, 9650, -1, 9759, 9760, 9678, -1, 7249, 9760, 9759, -1, 9650, 9761, 9758, -1, 9760, 9762, 9707, -1, 7245, 9762, 7249, -1, 9752, 9763, 7062, -1, 7249, 9762, 9760, -1, 9709, 9764, 9580, -1, 9580, 9764, 9711, -1, 9711, 9764, 9765, -1, 9762, 9766, 9707, -1, 9652, 9767, 9761, -1, 9707, 9766, 9709, -1, 7245, 9766, 9762, -1, 9653, 9767, 9652, -1, 9709, 9766, 9764, -1, 9765, 9768, 7245, -1, 9764, 9768, 9765, -1, 9752, 9769, 9763, -1, 7245, 9768, 9766, -1, 9755, 9769, 9752, -1, 9766, 9768, 9764, -1, 7245, 9770, 9765, -1, 9763, 9771, 7062, -1, 9765, 9770, 9711, -1, 7062, 9771, 7060, -1, 9712, 9772, 9715, -1, 9711, 9772, 9712, -1, 7245, 9772, 9770, -1, 9504, 9773, 9653, -1, 7296, 9773, 9504, -1, 9770, 9772, 9711, -1, 9653, 9773, 9767, -1, 7239, 9774, 7245, -1, 9755, 9775, 9769, -1, 9758, 9775, 9755, -1, 9772, 9774, 9715, -1, 7245, 9774, 9772, -1, 9717, 9776, 9601, -1, 9601, 9776, 9721, -1, 9721, 9776, 9777, -1, 9763, 9778, 9771, -1, 9769, 9778, 9763, -1, 7239, 9779, 9774, -1, 9715, 9779, 9717, -1, 9761, 9780, 9758, -1, 9717, 9779, 9776, -1, 9774, 9779, 9715, -1, 9758, 9780, 9775, -1, 9777, 9781, 7239, -1, 9776, 9781, 9777, -1, 7239, 9781, 9779, -1, 9779, 9781, 9776, -1, 7239, 9782, 9777, -1, 9777, 9782, 9721, -1, 9775, 9783, 9769, -1, 9769, 9783, 9778, -1, 9767, 9784, 9761, -1, 9721, 9785, 9722, -1, 9782, 9785, 9721, -1, 7239, 9785, 9782, -1, 9761, 9784, 9780, -1, 9722, 9785, 9724, -1, 9771, 9786, 7060, -1, 7233, 9787, 7239, -1, 7239, 9787, 9785, -1, 9785, 9787, 9724, -1, 9623, 9788, 9713, -1, 9726, 9788, 9623, -1, 9780, 9789, 9775, -1, 9775, 9789, 9783, -1, 9787, 9790, 9724, -1, 7293, 9791, 7296, -1, 9724, 9790, 9726, -1, 7296, 9791, 9773, -1, 7233, 9790, 9787, -1, 9767, 9791, 9784, -1, 9726, 9790, 9788, -1, 9773, 9791, 9767, -1, 9719, 9792, 7233, -1, 9713, 9792, 9719, -1, 9788, 9792, 9713, -1, 9778, 9793, 9771, -1, 7233, 9792, 9790, -1, 9790, 9792, 9788, -1, 9771, 9793, 9786, -1, 9784, 9278, 9780, -1, 9728, 9794, 9743, -1, 9743, 9794, 7067, -1, 9780, 9278, 9789, -1, 9731, 9795, 9727, -1, 9728, 9795, 9794, -1, 9727, 9795, 9728, -1, 7060, 9282, 7058, -1, 9786, 9282, 7060, -1, 9731, 9796, 9795, -1, 9778, 9268, 9793, -1, 7067, 9796, 7066, -1, 9794, 9796, 7067, -1, 9783, 9268, 9778, -1, 9795, 9796, 9794, -1, 9791, 9277, 9784, -1, 9731, 9797, 9796, -1, 7293, 9277, 9791, -1, 9733, 9797, 9731, -1, 9784, 9277, 9278, -1, 9735, 9797, 9733, -1, 9793, 9280, 9786, -1, 9796, 9798, 7066, -1, 9786, 9280, 9282, -1, 7066, 9798, 9799, -1, 9799, 9798, 9735, -1, 9797, 9798, 9796, -1, 9735, 9798, 9797, -1, 9799, 9800, 7066, -1, 9735, 9800, 9799, -1, 9789, 9288, 9783, -1, 9783, 9288, 9268, -1, 9735, 9801, 9800, -1, 9793, 9270, 9280, -1, 9736, 9801, 9735, -1, 9739, 9801, 9736, -1, 9268, 9270, 9793, -1, 9739, 9272, 9801, -1, 9789, 9279, 9288, -1, 7066, 9272, 7064, -1, 9800, 9272, 7066, -1, 9278, 9279, 9789, -1, 9801, 9272, 9800, -1, 9740, 9271, 9739, -1, 9739, 9271, 9272, -1, 9282, 9286, 7058, -1, 9741, 9271, 9740, -1, 9272, 9266, 7064, -1, 9741, 9266, 9271, -1, 9267, 9266, 9741, -1, 9288, 9269, 9268, -1, 9802, 4715, 4713, -1, 9803, 9804, 9805, -1, 9806, 7547, 7545, -1, 9803, 9805, 9807, -1, 9806, 9808, 7547, -1, 9809, 9807, 9810, -1, 9811, 9808, 9806, -1, 9811, 9812, 9808, -1, 9809, 9803, 9807, -1, 9813, 9814, 9812, -1, 9813, 9812, 9811, -1, 9815, 9816, 9814, -1, 9817, 9803, 9809, -1, 9817, 9818, 9803, -1, 9815, 9814, 9813, -1, 9819, 9810, 9820, -1, 9819, 9820, 9821, -1, 9819, 9817, 9809, -1, 9819, 9809, 9810, -1, 9822, 4717, 4715, -1, 9823, 9821, 9824, -1, 9825, 7545, 7544, -1, 9823, 9818, 9817, -1, 9825, 9806, 7545, -1, 9823, 9819, 9821, -1, 9823, 9826, 9818, -1, 9823, 9817, 9819, -1, 9827, 9828, 9829, -1, 9827, 9829, 9830, -1, 9831, 9811, 9806, -1, 9827, 9830, 9832, -1, 9831, 9806, 9825, -1, 9833, 9827, 9832, -1, 9833, 9828, 9827, -1, 9834, 9835, 9829, -1, 9834, 9829, 9828, -1, 9836, 9813, 9811, -1, 9834, 9820, 9835, -1, 9836, 9811, 9831, -1, 9837, 9833, 9832, -1, 9837, 9828, 9833, -1, 9838, 9815, 9813, -1, 9837, 9839, 9828, -1, 9837, 9832, 9840, -1, 9837, 9840, 9839, -1, 9838, 9813, 9836, -1, 9841, 9820, 9834, -1, 9841, 9824, 9821, -1, 9841, 9821, 9820, -1, 9842, 4717, 9843, -1, 9844, 9841, 9834, -1, 9842, 4719, 4717, -1, 9845, 9828, 9839, -1, 9845, 9839, 9846, -1, 9847, 7542, 7540, -1, 9847, 9848, 7542, -1, 9849, 9845, 9846, -1, 9849, 9846, 9850, -1, 9851, 9852, 9848, -1, 9851, 9848, 9847, -1, 9853, 9845, 9849, -1, 9853, 9854, 9845, -1, 9855, 9853, 9849, -1, 9855, 9849, 9850, -1, 9856, 9857, 9852, -1, 9855, 9850, 9858, -1, 9856, 9852, 9851, -1, 9855, 9858, 9859, -1, 9860, 9861, 9854, -1, 9860, 9854, 9853, -1, 9860, 9853, 9855, -1, 9860, 9855, 9859, -1, 9860, 9859, 9862, -1, 9863, 9857, 9856, -1, 9863, 9864, 9857, -1, 9865, 9836, 9831, -1, 9866, 9847, 7540, -1, 9867, 9864, 9863, -1, 9868, 9869, 9838, -1, 9868, 9870, 9869, -1, 9868, 9865, 9871, -1, 9868, 9838, 9836, -1, 9867, 9872, 9864, -1, 9868, 9873, 9870, -1, 9868, 9836, 9865, -1, 9874, 9847, 9866, -1, 9874, 9851, 9847, -1, 9875, 4721, 9876, -1, 9875, 9872, 9867, -1, 9875, 9876, 9872, -1, 9877, 7540, 7538, -1, 9877, 9866, 7540, -1, 9878, 9851, 9874, -1, 9879, 9852, 9857, -1, 9880, 9881, 9873, -1, 9880, 9882, 9881, -1, 9878, 9856, 9851, -1, 9880, 9864, 9882, -1, 9883, 9874, 9866, -1, 9880, 9879, 9857, -1, 9883, 9866, 9877, -1, 9880, 9884, 9879, -1, 9880, 9857, 9864, -1, 9885, 9886, 4719, -1, 9887, 9863, 9856, -1, 9885, 9888, 9889, -1, 9885, 4719, 9888, -1, 9887, 9856, 9878, -1, 9890, 9873, 9881, -1, 9890, 9881, 9891, -1, 9890, 9891, 9886, -1, 9890, 9885, 9889, -1, 9890, 9886, 9885, -1, 9890, 9870, 9873, -1, 9892, 9874, 9883, -1, 9890, 9889, 9870, -1, 9893, 9894, 9895, -1, 9893, 9896, 9894, -1, 9893, 9895, 9897, -1, 9892, 9878, 9874, -1, 9898, 9867, 9863, -1, 9898, 9863, 9887, -1, 9899, 9896, 9893, -1, 9899, 9900, 9896, -1, 9899, 9901, 9900, -1, 9902, 9887, 9878, -1, 9902, 9878, 9892, -1, 9903, 9899, 9893, -1, 9904, 9875, 9867, -1, 9904, 9867, 9898, -1, 9904, 4723, 4721, -1, 9904, 4721, 9875, -1, 9905, 9877, 7538, -1, 9906, 9898, 9887, -1, 9906, 9887, 9902, -1, 9907, 9897, 9908, -1, 9907, 9908, 9909, -1, 9907, 9909, 9910, -1, 9911, 9883, 9877, -1, 9911, 9877, 9905, -1, 9912, 9904, 9898, -1, 9913, 9907, 9910, -1, 9912, 9898, 9906, -1, 9912, 4723, 9904, -1, 9913, 9914, 9907, -1, 9913, 9910, 9915, -1, 9913, 9915, 9916, -1, 9917, 9892, 9883, -1, 9917, 9883, 9911, -1, 9918, 9919, 9920, -1, 9918, 9910, 9919, -1, 9918, 9920, 9921, -1, 9922, 7538, 7536, -1, 9922, 9905, 7538, -1, 9923, 9910, 9918, -1, 9923, 9915, 9910, -1, 9923, 9916, 9915, -1, 9924, 9902, 9892, -1, 9924, 9892, 9917, -1, 9925, 9923, 9918, -1, 9926, 9911, 9905, -1, 9927, 9921, 9928, -1, 9926, 9905, 9922, -1, 9927, 9928, 9929, -1, 9930, 9906, 9902, -1, 9930, 9902, 9924, -1, 9931, 9917, 9911, -1, 9931, 9911, 9926, -1, 9932, 9912, 9906, -1, 9932, 4723, 9912, -1, 9932, 9906, 9930, -1, 9933, 9929, 9934, -1, 9932, 4725, 4723, -1, 9933, 9935, 9927, -1, 9936, 9924, 9917, -1, 9933, 9927, 9929, -1, 9936, 9917, 9931, -1, 9937, 9933, 9934, -1, 9938, 9922, 7536, -1, 9937, 9939, 9940, -1, 9937, 9934, 9939, -1, 9941, 9935, 9933, -1, 9941, 9940, 9942, -1, 9943, 9930, 9924, -1, 9941, 9944, 9935, -1, 9943, 9924, 9936, -1, 9941, 9937, 9940, -1, 9941, 9933, 9937, -1, 9945, 9926, 9922, -1, 9946, 9947, 9948, -1, 9945, 9922, 9938, -1, 9946, 9939, 9947, -1, 9946, 9948, 9949, -1, 9950, 9942, 9940, -1, 9951, 9932, 9930, -1, 9951, 4725, 9932, -1, 9950, 9939, 9946, -1, 9951, 9930, 9943, -1, 9950, 9940, 9939, -1, 9952, 9931, 9926, -1, 9952, 9926, 9945, -1, 9953, 9950, 9946, -1, 9954, 7536, 7534, -1, 9954, 9938, 7536, -1, 9955, 9936, 9931, -1, 9956, 9949, 9957, -1, 9956, 9957, 9958, -1, 9955, 9931, 9952, -1, 9959, 9945, 9938, -1, 9960, 9958, 9961, -1, 9959, 9938, 9954, -1, 9960, 9956, 9958, -1, 9962, 9943, 9936, -1, 9962, 9936, 9955, -1, 9963, 9952, 9945, -1, 9964, 9956, 9960, -1, 9964, 9965, 9956, -1, 9963, 9945, 9959, -1, 9966, 4725, 9951, -1, 9966, 9951, 9943, -1, 9966, 4727, 4725, -1, 9967, 9961, 9968, -1, 9966, 9943, 9962, -1, 9967, 9968, 9969, -1, 9967, 9964, 9960, -1, 9967, 9960, 9961, -1, 9970, 9954, 7534, -1, 9971, 9969, 9972, -1, 9971, 9967, 9969, -1, 9971, 9965, 9964, -1, 9973, 9952, 9963, -1, 9971, 9974, 9965, -1, 9971, 9964, 9967, -1, 9975, 9976, 9977, -1, 9975, 9978, 9979, -1, 9973, 9955, 9952, -1, 9980, 9954, 9970, -1, 9975, 9977, 9978, -1, 9981, 9976, 9975, -1, 9980, 9959, 9954, -1, 9981, 9975, 9979, -1, 9982, 9977, 9976, -1, 9983, 9955, 9973, -1, 9983, 9962, 9955, -1, 9982, 9984, 9977, -1, 9982, 9968, 9984, -1, 9985, 9963, 9959, -1, 9985, 9959, 9980, -1, 9986, 9987, 9988, -1, 9986, 9979, 9987, -1, 9986, 9988, 9976, -1, 9986, 9976, 9981, -1, 9986, 9981, 9979, -1, 9989, 9966, 9962, -1, 9989, 4727, 9966, -1, 9990, 9969, 9968, -1, 9990, 9972, 9969, -1, 9989, 9962, 9983, -1, 9990, 9968, 9982, -1, 1149, 7512, 1147, -1, 9991, 7534, 7532, -1, 9991, 9970, 7534, -1, 9992, 9990, 9982, -1, 9993, 9963, 9985, -1, 9994, 9988, 9995, -1, 9993, 9973, 9963, -1, 9994, 9976, 9988, -1, 9996, 9980, 9970, -1, 9996, 9970, 9991, -1, 9997, 9983, 9973, -1, 9997, 9973, 9993, -1, 9998, 9994, 9995, -1, 9998, 9995, 9999, -1, 10000, 9985, 9980, -1, 10000, 9980, 9996, -1, 10001, 1129, 1131, -1, 10002, 4727, 9989, -1, 10002, 9989, 9983, -1, 10003, 9994, 9998, -1, 10002, 4729, 4727, -1, 10002, 9983, 9997, -1, 10003, 10004, 9994, -1, 10005, 9991, 7532, -1, 10001, 1131, 7557, -1, 10006, 1429, 1129, -1, 10007, 9993, 9985, -1, 10008, 10009, 10010, -1, 10007, 9985, 10000, -1, 10008, 9998, 9999, -1, 10008, 10003, 9998, -1, 10006, 1129, 10001, -1, 10008, 9999, 10009, -1, 10011, 1432, 1429, -1, 10012, 10010, 10013, -1, 10011, 1436, 1432, -1, 10012, 10008, 10010, -1, 10014, 9996, 9991, -1, 10012, 10004, 10003, -1, 10014, 9991, 10005, -1, 10012, 10015, 10004, -1, 10012, 10003, 10008, -1, 10011, 1429, 10006, -1, 10016, 10017, 10018, -1, 10019, 9997, 9993, -1, 10016, 10020, 10021, -1, 10019, 9993, 10007, -1, 10016, 10022, 10017, -1, 10016, 10021, 10022, -1, 10016, 10018, 10023, -1, 10016, 10023, 10020, -1, 10024, 1436, 10011, -1, 10025, 10018, 10017, -1, 10025, 10026, 10027, -1, 10028, 1438, 1436, -1, 10028, 1436, 10024, -1, 10025, 4742, 10026, -1, 10029, 9996, 10014, -1, 10025, 10027, 10018, -1, 10030, 10025, 10017, -1, 10030, 10017, 10022, -1, 10031, 1440, 1438, -1, 10029, 10000, 9996, -1, 10030, 10032, 10033, -1, 10031, 1441, 1440, -1, 10034, 10002, 9997, -1, 10030, 10022, 10032, -1, 10031, 4712, 1441, -1, 10034, 4729, 10002, -1, 10030, 4744, 4742, -1, 10034, 9997, 10019, -1, 10030, 10033, 4744, -1, 10030, 4742, 10025, -1, 10031, 1438, 10028, -1, 10035, 10036, 10037, -1, 10035, 10037, 10038, -1, 10039, 10005, 7532, -1, 10035, 10038, 10040, -1, 10039, 7532, 7530, -1, 10035, 10040, 10041, -1, 10042, 7557, 7559, -1, 10035, 10043, 10044, -1, 10035, 10041, 10043, -1, 10042, 10001, 7557, -1, 10035, 10044, 10036, -1, 10045, 10033, 10046, -1, 10045, 10046, 10036, -1, 10047, 10007, 10000, -1, 10045, 10036, 10044, -1, 10047, 10000, 10029, -1, 10045, 4744, 10033, -1, 10048, 10006, 10001, -1, 10049, 10045, 10044, -1, 10049, 4744, 10045, -1, 10049, 10050, 4746, -1, 10048, 10001, 10042, -1, 10049, 10043, 10051, -1, 10049, 10044, 10043, -1, 10052, 10014, 10005, -1, 10049, 10051, 10050, -1, 10053, 10011, 10006, -1, 10049, 4746, 4744, -1, 10052, 10005, 10039, -1, 10054, 10055, 9804, -1, 10054, 10056, 10055, -1, 10054, 9804, 9803, -1, 10054, 10057, 10056, -1, 10058, 10019, 10007, -1, 10054, 9803, 9818, -1, 10053, 10006, 10048, -1, 10054, 9826, 10057, -1, 10054, 9818, 9826, -1, 10058, 10007, 10047, -1, 10059, 10050, 10060, -1, 10059, 4746, 10050, -1, 10061, 10011, 10053, -1, 10059, 10060, 10056, -1, 10062, 10029, 10014, -1, 10059, 10056, 10057, -1, 10062, 10014, 10052, -1, 10063, 10059, 10057, -1, 10061, 10024, 10011, -1, 10063, 9824, 4748, -1, 10064, 10024, 10061, -1, 10063, 4746, 10059, -1, 10063, 4748, 4746, -1, 10063, 10057, 9826, -1, 10063, 9823, 9824, -1, 10065, 4729, 10034, -1, 10063, 9826, 9823, -1, 10064, 10028, 10024, -1, 10065, 10034, 10019, -1, 10066, 9828, 9845, -1, 10065, 10019, 10058, -1, 10066, 9844, 9834, -1, 10067, 10028, 10064, -1, 10066, 9845, 9854, -1, 10065, 4731, 4729, -1, 10066, 9861, 10068, -1, 10067, 10031, 10028, -1, 10066, 9854, 9861, -1, 10067, 4712, 10031, -1, 10069, 10039, 7530, -1, 10066, 10068, 9844, -1, 10067, 4714, 4712, -1, 10066, 9834, 9828, -1, 10070, 10042, 7559, -1, 10071, 9841, 9844, -1, 10071, 9824, 9841, -1, 10072, 10047, 10029, -1, 10071, 4748, 9824, -1, 10070, 7559, 7561, -1, 10071, 9844, 10068, -1, 10072, 10029, 10062, -1, 10073, 10071, 10068, -1, 10073, 4748, 10071, -1, 10073, 10068, 9861, -1, 10073, 9861, 9860, -1, 10073, 9860, 9862, -1, 10074, 10039, 10069, -1, 10073, 9862, 4709, -1, 10075, 10042, 10070, -1, 10073, 4709, 4748, -1, 10074, 10052, 10039, -1, 10076, 9825, 7544, -1, 10075, 10048, 10042, -1, 10076, 9865, 9831, -1, 10076, 9871, 9865, -1, 10077, 10048, 10075, -1, 10078, 10047, 10072, -1, 10076, 10079, 9871, -1, 10078, 10058, 10047, -1, 10076, 9831, 9825, -1, 10080, 7544, 7542, -1, 10077, 10053, 10048, -1, 10080, 10076, 7544, -1, 10081, 10062, 10052, -1, 10080, 10079, 10076, -1, 10082, 7542, 9848, -1, 10082, 10079, 10080, -1, 10082, 9852, 9879, -1, 10081, 10052, 10074, -1, 10082, 9848, 9852, -1, 10082, 9884, 10079, -1, 10083, 10053, 10077, -1, 10084, 10058, 10078, -1, 10082, 9879, 9884, -1, 10083, 10061, 10053, -1, 10084, 10065, 10058, -1, 10082, 10080, 7542, -1, 10085, 10061, 10083, -1, 10084, 4731, 10065, -1, 10086, 9880, 9873, -1, 10085, 10064, 10061, -1, 10086, 9868, 9871, -1, 10086, 9873, 9868, -1, 10086, 9871, 10079, -1, 10087, 10072, 10062, -1, 10086, 10079, 9884, -1, 10086, 9884, 9880, -1, 10087, 10062, 10081, -1, 10088, 9893, 9897, -1, 10089, 4716, 4714, -1, 10088, 10090, 9903, -1, 10088, 9903, 9893, -1, 10088, 9907, 9914, -1, 10088, 9897, 9907, -1, 10088, 9914, 10090, -1, 10091, 7530, 7528, -1, 10092, 9903, 10090, -1, 10093, 7561, 7563, -1, 10092, 4741, 9901, -1, 10091, 10069, 7530, -1, 10092, 9901, 9899, -1, 10093, 10070, 7561, -1, 10092, 9899, 9903, -1, 10094, 10070, 10093, -1, 10095, 4741, 10092, -1, 10096, 10078, 10072, -1, 10095, 10092, 10090, -1, 10095, 9913, 9916, -1, 10095, 10090, 9914, -1, 10095, 9916, 4743, -1, 10096, 10072, 10087, -1, 10095, 9914, 9913, -1, 10095, 4743, 4741, -1, 10094, 10075, 10070, -1, 10097, 10098, 9925, -1, 10099, 10069, 10091, -1, 10097, 9935, 9944, -1, 10097, 9944, 10098, -1, 10097, 9921, 9927, -1, 10100, 10077, 10075, -1, 10099, 10074, 10069, -1, 10097, 9918, 9921, -1, 10100, 10075, 10094, -1, 10097, 9927, 9935, -1, 10097, 9925, 9918, -1, 10101, 9925, 10098, -1, 10101, 4743, 9916, -1, 10102, 10084, 10078, -1, 10102, 4733, 4731, -1, 10101, 9916, 9923, -1, 10103, 10083, 10077, -1, 10102, 10078, 10096, -1, 10101, 9923, 9925, -1, 10102, 4731, 10084, -1, 10104, 4743, 10101, -1, 10103, 10077, 10100, -1, 10104, 9942, 4745, -1, 10105, 10074, 10099, -1, 10104, 10098, 9944, -1, 10104, 9944, 9941, -1, 10104, 9941, 9942, -1, 10106, 10085, 10083, -1, 10104, 10101, 10098, -1, 10104, 4745, 4743, -1, 10106, 10083, 10103, -1, 10105, 10081, 10074, -1, 10107, 9953, 9946, -1, 10107, 9946, 9949, -1, 10107, 10108, 9953, -1, 10109, 4718, 4716, -1, 10107, 9949, 9956, -1, 10107, 9956, 9965, -1, 10107, 9974, 10108, -1, 10110, 10091, 7528, -1, 10107, 9965, 9974, -1, 10111, 4745, 9942, -1, 10112, 10093, 7563, -1, 10111, 9953, 10108, -1, 10113, 10081, 10105, -1, 10111, 9950, 9953, -1, 10111, 9942, 9950, -1, 10112, 7563, 7565, -1, 10114, 9972, 4747, -1, 10113, 10087, 10081, -1, 10114, 4745, 10111, -1, 10115, 10099, 10091, -1, 10114, 10111, 10108, -1, 10114, 10108, 9974, -1, 10116, 10093, 10112, -1, 10114, 9971, 9972, -1, 10116, 10094, 10093, -1, 10114, 9974, 9971, -1, 10114, 4747, 4745, -1, 10115, 10091, 10110, -1, 10117, 9982, 9976, -1, 10117, 9992, 9982, -1, 10118, 10096, 10087, -1, 10117, 10119, 9992, -1, 10117, 9976, 9994, -1, 10117, 9994, 10004, -1, 10120, 10094, 10116, -1, 10118, 10087, 10113, -1, 10117, 10015, 10119, -1, 10117, 10004, 10015, -1, 10120, 10100, 10094, -1, 10121, 4747, 9972, -1, 10122, 10105, 10099, -1, 10121, 9992, 10119, -1, 10121, 9972, 9990, -1, 10122, 10099, 10115, -1, 10121, 9990, 9992, -1, 10123, 4749, 4747, -1, 10124, 10103, 10100, -1, 10123, 10013, 4749, -1, 10123, 4747, 10121, -1, 10125, 4733, 10102, -1, 10123, 10121, 10119, -1, 10125, 10102, 10096, -1, 10123, 10119, 10015, -1, 10125, 10096, 10118, -1, 10123, 10012, 10013, -1, 10123, 10015, 10012, -1, 10124, 10100, 10120, -1, 10126, 10113, 10105, -1, 10126, 10105, 10122, -1, 10127, 4718, 10128, -1, 10127, 4720, 4718, -1, 10129, 10112, 7565, -1, 10130, 7528, 7526, -1, 10130, 10110, 7528, -1, 10129, 7565, 7479, -1, 10131, 10118, 10113, -1, 10132, 10112, 10129, -1, 10132, 10116, 10112, -1, 10131, 10113, 10126, -1, 10133, 10115, 10110, -1, 10133, 10110, 10130, -1, 10134, 10129, 7479, -1, 10134, 7479, 7480, -1, 10135, 4733, 10125, -1, 10135, 10125, 10118, -1, 10135, 10118, 10131, -1, 10136, 10120, 10116, -1, 10135, 4735, 4733, -1, 10137, 10130, 7526, -1, 10136, 10116, 10132, -1, 10138, 10129, 10134, -1, 10138, 10132, 10129, -1, 10139, 10115, 10133, -1, 10140, 10124, 10120, -1, 10139, 10122, 10115, -1, 10140, 10120, 10136, -1, 10141, 10133, 10130, -1, 10141, 10130, 10137, -1, 10142, 10136, 10132, -1, 10143, 10126, 10122, -1, 10143, 10122, 10139, -1, 10142, 10132, 10138, -1, 10144, 10139, 10133, -1, 10144, 10133, 10141, -1, 10145, 10140, 10136, -1, 10146, 10131, 10126, -1, 10145, 10136, 10142, -1, 10147, 4720, 10148, -1, 10146, 10126, 10143, -1, 10147, 4722, 4720, -1, 10149, 10143, 10139, -1, 10149, 10139, 10144, -1, 10150, 10134, 7480, -1, 10151, 10148, 10140, -1, 10152, 10135, 10131, -1, 10152, 4735, 10135, -1, 10152, 10131, 10146, -1, 10151, 10140, 10145, -1, 10153, 7526, 7524, -1, 10154, 10138, 10134, -1, 10153, 10137, 7526, -1, 10154, 10134, 10150, -1, 10155, 10146, 10143, -1, 10156, 10148, 10151, -1, 10155, 10143, 10149, -1, 10156, 4722, 10147, -1, 10156, 10147, 10148, -1, 10157, 10141, 10137, -1, 10158, 10150, 7480, -1, 10157, 10137, 10153, -1, 10158, 7480, 7482, -1, 10159, 10142, 10138, -1, 10159, 10138, 10154, -1, 10160, 10146, 10155, -1, 10160, 4735, 10152, -1, 10160, 10152, 10146, -1, 10161, 10154, 10150, -1, 10160, 4737, 4735, -1, 10161, 10150, 10158, -1, 10162, 10153, 7524, -1, 10163, 10144, 10141, -1, 10164, 10145, 10142, -1, 10163, 10141, 10157, -1, 10164, 10142, 10159, -1, 10165, 10159, 10154, -1, 10165, 10154, 10161, -1, 10166, 10153, 10162, -1, 10166, 10157, 10153, -1, 10167, 10151, 10145, -1, 10168, 10149, 10144, -1, 10167, 10145, 10164, -1, 10168, 10144, 10163, -1, 10169, 10159, 10165, -1, 10169, 10164, 10159, -1, 10170, 10163, 10157, -1, 10170, 10157, 10166, -1, 10171, 10156, 10151, -1, 10171, 4722, 10156, -1, 10172, 10155, 10149, -1, 10171, 10151, 10167, -1, 10172, 10149, 10168, -1, 10171, 4724, 4722, -1, 10173, 10158, 7482, -1, 10174, 10163, 10170, -1, 10174, 10168, 10163, -1, 10175, 10164, 10169, -1, 10175, 10167, 10164, -1, 10176, 10160, 10155, -1, 10176, 4737, 10160, -1, 10176, 10155, 10172, -1, 10177, 10161, 10158, -1, 10178, 7524, 7522, -1, 10177, 10158, 10173, -1, 10178, 10162, 7524, -1, 10179, 10167, 10175, -1, 10180, 10172, 10168, -1, 10179, 10171, 10167, -1, 10180, 10168, 10174, -1, 10179, 4724, 10171, -1, 10181, 10173, 7482, -1, 10181, 7482, 7484, -1, 10182, 10165, 10161, -1, 10183, 10162, 10178, -1, 10182, 10161, 10177, -1, 10183, 10166, 10162, -1, 10184, 4737, 10176, -1, 10184, 10176, 10172, -1, 10184, 4739, 4737, -1, 10184, 10172, 10180, -1, 10185, 10177, 10173, -1, 10186, 10178, 7522, -1, 10185, 10173, 10181, -1, 10187, 10169, 10165, -1, 10188, 10170, 10166, -1, 10187, 10165, 10182, -1, 10188, 10166, 10183, -1, 10189, 10182, 10177, -1, 10190, 10178, 10186, -1, 10189, 10177, 10185, -1, 10190, 10183, 10178, -1, 10191, 10175, 10169, -1, 10192, 10174, 10170, -1, 10191, 10169, 10187, -1, 10192, 10170, 10188, -1, 10193, 10187, 10182, -1, 10194, 10188, 10183, -1, 10193, 10182, 10189, -1, 10194, 10183, 10190, -1, 10195, 10179, 10175, -1, 10195, 4724, 10179, -1, 10195, 4726, 4724, -1, 10196, 10180, 10174, -1, 10195, 10175, 10191, -1, 10196, 10174, 10192, -1, 10197, 10181, 7484, -1, 10198, 10188, 10194, -1, 10198, 10192, 10188, -1, 10199, 10187, 10193, -1, 10200, 10184, 10180, -1, 10199, 10191, 10187, -1, 10200, 4739, 10184, -1, 10200, 10180, 10196, -1, 10201, 10181, 10197, -1, 10202, 10192, 10198, -1, 10201, 10185, 10181, -1, 10202, 10196, 10192, -1, 10203, 7522, 7520, -1, 10204, 4726, 10195, -1, 10204, 10195, 10191, -1, 10204, 10191, 10199, -1, 10203, 10186, 7522, -1, 10205, 10185, 10201, -1, 10205, 10189, 10185, -1, 10206, 4739, 10200, -1, 10206, 10200, 10196, -1, 10206, 10196, 10202, -1, 10206, 4741, 4739, -1, 10207, 10190, 10186, -1, 10208, 7484, 7486, -1, 10208, 10197, 7484, -1, 10209, 10189, 10205, -1, 10207, 10186, 10203, -1, 10209, 10193, 10189, -1, 10210, 10194, 10190, -1, 10210, 10190, 10207, -1, 10211, 10197, 10208, -1, 9896, 10198, 10194, -1, 10211, 10201, 10197, -1, 9896, 10194, 10210, -1, 10212, 10193, 10209, -1, 9900, 10202, 10198, -1, 10212, 10199, 10193, -1, 9900, 10198, 9896, -1, 10213, 10205, 10201, -1, 10213, 10201, 10211, -1, 9901, 10206, 10202, -1, 9901, 4741, 10206, -1, 9901, 10202, 9900, -1, 10214, 10204, 10199, -1, 10214, 10199, 10212, -1, 10214, 4728, 4726, -1, 10214, 4726, 10204, -1, 10215, 10209, 10205, -1, 10215, 10205, 10213, -1, 10216, 10208, 7486, -1, 10217, 10209, 10215, -1, 10217, 10212, 10209, -1, 10218, 10208, 10216, -1, 10218, 10211, 10208, -1, 10219, 10214, 10212, -1, 10219, 4728, 10214, -1, 10219, 10212, 10217, -1, 10220, 10211, 10218, -1, 10220, 10213, 10211, -1, 10221, 10216, 7486, -1, 10221, 7486, 7489, -1, 10222, 10215, 10213, -1, 10222, 10213, 10220, -1, 10223, 10218, 10216, -1, 10223, 10216, 10221, -1, 10224, 10217, 10215, -1, 10224, 10215, 10222, -1, 10225, 10220, 10218, -1, 10225, 10218, 10223, -1, 10226, 4728, 10219, -1, 10226, 10219, 10217, -1, 10226, 10217, 10224, -1, 10226, 4730, 4728, -1, 10227, 10221, 7489, -1, 10228, 10222, 10220, -1, 10228, 10220, 10225, -1, 10229, 10223, 10221, -1, 10229, 10221, 10227, -1, 10230, 10224, 10222, -1, 10230, 10222, 10228, -1, 10231, 10225, 10223, -1, 10231, 10223, 10229, -1, 10232, 10226, 10224, -1, 10232, 4730, 10226, -1, 10232, 10224, 10230, -1, 10233, 10227, 7489, -1, 10233, 7489, 7485, -1, 10234, 10228, 10225, -1, 10234, 10225, 10231, -1, 10235, 7512, 1149, -1, 10236, 10229, 10227, -1, 10236, 10227, 10233, -1, 10237, 10235, 1149, -1, 10237, 1149, 1157, -1, 10238, 10230, 10228, -1, 10238, 10228, 10234, -1, 9999, 10237, 1157, -1, 10239, 10231, 10229, -1, 10239, 10229, 10236, -1, 9999, 1157, 1162, -1, 10240, 4730, 10232, -1, 10240, 4732, 4730, -1, 10240, 10232, 10230, -1, 10240, 10230, 10238, -1, 10009, 9999, 1162, -1, 10009, 1162, 1173, -1, 10241, 10233, 7485, -1, 10242, 10234, 10231, -1, 10242, 10231, 10239, -1, 10010, 10009, 1173, -1, 10010, 1173, 1181, -1, 10013, 1186, 4749, -1, 10243, 10233, 10241, -1, 10243, 10236, 10233, -1, 10013, 10010, 1181, -1, 10013, 1181, 1185, -1, 10013, 1185, 1186, -1, 10244, 10089, 4714, -1, 10244, 10064, 10085, -1, 10244, 10067, 10064, -1, 10245, 10238, 10234, -1, 10244, 4714, 10067, -1, 10245, 10234, 10242, -1, 10244, 10085, 10089, -1, 10246, 10109, 4716, -1, 10246, 10106, 10109, -1, 10246, 10089, 10085, -1, 10247, 10236, 10243, -1, 10246, 4716, 10089, -1, 10246, 10085, 10106, -1, 10247, 10239, 10236, -1, 10248, 4718, 10109, -1, 10248, 10128, 4718, -1, 10249, 10238, 10245, -1, 10250, 10148, 4720, -1, 10249, 4732, 10240, -1, 10249, 10240, 10238, -1, 10250, 4720, 10127, -1, 10251, 7485, 7483, -1, 10252, 10253, 7564, -1, 10252, 10254, 10253, -1, 10251, 10241, 7485, -1, 10255, 10239, 10247, -1, 10256, 10252, 7564, -1, 10255, 10242, 10239, -1, 10257, 10241, 10251, -1, 10258, 7564, 7562, -1, 10258, 7562, 10259, -1, 10258, 10256, 7564, -1, 10257, 10243, 10241, -1, 10260, 10242, 10255, -1, 10261, 10259, 7562, -1, 10261, 10262, 10259, -1, 10260, 10245, 10242, -1, 10263, 10247, 10243, -1, 10263, 10243, 10257, -1, 10264, 10261, 7562, -1, 10265, 4732, 10249, -1, 10266, 7562, 7560, -1, 10265, 10245, 10260, -1, 10265, 4734, 4732, -1, 10266, 7560, 10267, -1, 10265, 10249, 10245, -1, 10266, 10264, 7562, -1, 10268, 10251, 7483, -1, 10269, 10270, 10267, -1, 10269, 10267, 7560, -1, 10271, 10247, 10263, -1, 10272, 10269, 7560, -1, 10271, 10255, 10247, -1, 10273, 10257, 10251, -1, 10274, 7558, 10275, -1, 10273, 10251, 10268, -1, 10274, 10272, 7560, -1, 10276, 10260, 10255, -1, 10274, 7560, 7558, -1, 10276, 10255, 10271, -1, 10277, 10278, 10275, -1, 10277, 10275, 7558, -1, 10279, 10263, 10257, -1, 10279, 10257, 10273, -1, 10280, 10265, 10260, -1, 10280, 4734, 10265, -1, 9830, 10277, 7558, -1, 10280, 10260, 10276, -1, 9832, 9830, 7558, -1, 9832, 7558, 7556, -1, 9832, 7556, 10281, -1, 10282, 10271, 10263, -1, 10282, 10263, 10279, -1, 10283, 10284, 10285, -1, 10283, 4713, 10284, -1, 10283, 10285, 10286, -1, 10283, 9802, 4713, -1, 10283, 10286, 9802, -1, 10287, 7483, 7481, -1, 10288, 4715, 9802, -1, 10287, 10268, 7483, -1, 10288, 9822, 4715, -1, 10289, 10276, 10271, -1, 10288, 10290, 9822, -1, 10289, 10271, 10282, -1, 10291, 4717, 9822, -1, 10292, 10273, 10268, -1, 10291, 9843, 4717, -1, 10292, 10268, 10287, -1, 9888, 4719, 9842, -1, 9886, 9876, 4721, -1, 10293, 10280, 10276, -1, 10293, 4734, 10280, -1, 10293, 10276, 10289, -1, 9886, 4721, 4719, -1, 10293, 4736, 4734, -1, 10294, 10279, 10273, -1, 10295, 10203, 7520, -1, 10294, 10273, 10292, -1, 10295, 10207, 10203, -1, 10296, 10287, 7481, -1, 10297, 10282, 10279, -1, 10297, 10279, 10294, -1, 10298, 10295, 7520, -1, 10299, 7520, 7518, -1, 10299, 7518, 10300, -1, 10299, 10298, 7520, -1, 10301, 10292, 10287, -1, 10302, 10300, 7518, -1, 10302, 10303, 10300, -1, 10301, 10287, 10296, -1, 10304, 10289, 10282, -1, 10304, 10282, 10297, -1, 10305, 10302, 7518, -1, 10306, 10294, 10292, -1, 10307, 7518, 7516, -1, 10306, 10292, 10301, -1, 10307, 7516, 10308, -1, 10307, 10305, 7518, -1, 10309, 10293, 10289, -1, 10309, 4736, 10293, -1, 10310, 10308, 7516, -1, 10309, 10289, 10304, -1, 10310, 10311, 10308, -1, 10312, 10294, 10306, -1, 10312, 10297, 10294, -1, 10313, 10310, 7516, -1, 10314, 7481, 7478, -1, 10315, 10313, 7516, -1, 10314, 10296, 7481, -1, 10315, 7516, 7514, -1, 10315, 7514, 10316, -1, 10317, 10304, 10297, -1, 10317, 10297, 10312, -1, 10318, 10316, 7514, -1, 10318, 10319, 10316, -1, 10320, 10296, 10314, -1, 10320, 10301, 10296, -1, 9978, 10318, 7514, -1, 10321, 4738, 4736, -1, 10321, 10309, 10304, -1, 9979, 7514, 7512, -1, 10321, 4736, 10309, -1, 9979, 9978, 7514, -1, 10321, 10304, 10317, -1, 9979, 7512, 10235, -1, 10322, 10314, 7478, -1, 10323, 10109, 10106, -1, 10323, 10128, 10248, -1, 10323, 10248, 10109, -1, 10323, 10124, 10128, -1, 10323, 10106, 10103, -1, 10323, 10103, 10124, -1, 10324, 10140, 10148, -1, 10324, 10148, 10250, -1, 10325, 10301, 10320, -1, 10324, 10124, 10140, -1, 10325, 10306, 10301, -1, 10324, 10127, 10128, -1, 10324, 10250, 10127, -1, 10324, 10128, 10124, -1, 10326, 10327, 10328, -1, 10329, 10320, 10314, -1, 10326, 10328, 10254, -1, 10329, 10314, 10322, -1, 10330, 10306, 10325, -1, 10331, 10252, 10256, -1, 10331, 10254, 10252, -1, 10330, 10312, 10306, -1, 10331, 10326, 10254, -1, 10332, 10320, 10329, -1, 10020, 10331, 10256, -1, 10332, 10325, 10320, -1, 10333, 10312, 10330, -1, 10333, 10317, 10312, -1, 10334, 10330, 10325, -1, 10335, 10258, 10259, -1, 10335, 10259, 10262, -1, 10336, 10020, 10256, -1, 10334, 10325, 10332, -1, 10337, 10317, 10333, -1, 10336, 10256, 10258, -1, 10336, 10258, 10335, -1, 10337, 4738, 10321, -1, 10337, 10321, 10317, -1, 10338, 10335, 10262, -1, 10338, 10336, 10335, -1, 10338, 10339, 10340, -1, 10338, 10262, 10339, -1, 10341, 7478, 7477, -1, 10341, 10322, 7478, -1, 10342, 10333, 10330, -1, 10342, 10330, 10334, -1, 10343, 10340, 10339, -1, 10343, 10339, 10262, -1, 10344, 10261, 10264, -1, 10345, 10329, 10322, -1, 10344, 10262, 10261, -1, 10345, 10322, 10341, -1, 10344, 10343, 10262, -1, 10038, 10344, 10264, -1, 10346, 10337, 10333, -1, 10346, 10333, 10342, -1, 10346, 4738, 10337, -1, 10346, 4740, 4738, -1, 10347, 10341, 7477, -1, 10348, 10267, 10270, -1, 10348, 10266, 10267, -1, 10349, 10332, 10329, -1, 10349, 10329, 10345, -1, 10350, 10038, 10264, -1, 10350, 10264, 10266, -1, 10351, 10341, 10347, -1, 10350, 10266, 10348, -1, 10351, 10345, 10341, -1, 10352, 10348, 10270, -1, 10352, 10350, 10348, -1, 10352, 10270, 10353, -1, 10354, 10334, 10332, -1, 10355, 10353, 10270, -1, 10354, 10332, 10349, -1, 10355, 10356, 10353, -1, 10357, 10270, 10269, -1, 10358, 10345, 10351, -1, 10358, 10349, 10345, -1, 10357, 10269, 10272, -1, 10359, 10334, 10354, -1, 10357, 10355, 10270, -1, 10359, 10342, 10334, -1, 10360, 10354, 10349, -1, 10360, 10349, 10358, -1, 10361, 10342, 10359, -1, 9804, 10357, 10272, -1, 10361, 10346, 10342, -1, 10362, 10275, 10278, -1, 10361, 4740, 10346, -1, 10362, 10274, 10275, -1, 10253, 10347, 7477, -1, 10253, 7477, 7564, -1, 9805, 10272, 10274, -1, 9805, 9804, 10272, -1, 9805, 10274, 10362, -1, 10363, 10354, 10360, -1, 9807, 10278, 9810, -1, 10363, 10359, 10354, -1, 9807, 10362, 10278, -1, 10254, 10351, 10347, -1, 9807, 9805, 10362, -1, 9835, 9810, 10278, -1, 10254, 10347, 10253, -1, 9835, 9820, 9810, -1, 10364, 10361, 10359, -1, 10364, 4740, 10361, -1, 9829, 9835, 10278, -1, 10364, 10359, 10363, -1, 9829, 10278, 10277, -1, 10364, 4742, 4740, -1, 10328, 10358, 10351, -1, 9829, 10277, 9830, -1, 10328, 10351, 10254, -1, 10327, 10360, 10358, -1, 10327, 10358, 10328, -1, 9840, 10281, 10365, -1, 10366, 10363, 10360, -1, 10366, 10360, 10327, -1, 9840, 9832, 10281, -1, 10026, 10364, 10363, -1, 10026, 4742, 10364, -1, 10026, 10363, 10366, -1, 9846, 9839, 9840, -1, 9846, 10365, 9850, -1, 9846, 9840, 10365, -1, 10367, 10286, 9816, -1, 10367, 9802, 10286, -1, 10367, 10288, 9802, -1, 10367, 9816, 9815, -1, 10367, 9815, 10290, -1, 10367, 10290, 10288, -1, 10368, 9815, 9838, -1, 10368, 10290, 9815, -1, 10368, 9822, 10290, -1, 10368, 9838, 9843, -1, 10368, 10291, 9822, -1, 10368, 9843, 10291, -1, 10369, 9843, 9838, -1, 10369, 9888, 9842, -1, 10369, 9842, 9843, -1, 9869, 10369, 9838, -1, 9889, 9888, 10369, -1, 9889, 9869, 9870, -1, 9889, 10369, 9869, -1, 9882, 9864, 9872, -1, 9891, 9881, 9882, -1, 9891, 9882, 9872, -1, 9891, 9876, 9886, -1, 9891, 9872, 9876, -1, 9894, 10210, 10207, -1, 9894, 9896, 10210, -1, 9895, 10295, 10298, -1, 9895, 10207, 10295, -1, 9895, 9894, 10207, -1, 9897, 9895, 10298, -1, 10370, 10299, 10300, -1, 10370, 10300, 10303, -1, 9908, 9897, 10298, -1, 9908, 10299, 10370, -1, 9908, 10298, 10299, -1, 9909, 10370, 10303, -1, 9909, 9908, 10370, -1, 9909, 10303, 10371, -1, 9909, 10371, 9910, -1, 9919, 10371, 10303, -1, 9919, 9910, 10371, -1, 9920, 10302, 10305, -1, 9920, 10303, 10302, -1, 9920, 9919, 10303, -1, 9921, 9920, 10305, -1, 10372, 10307, 10308, -1, 10372, 10308, 10311, -1, 9928, 9921, 10305, -1, 9928, 10305, 10307, -1, 9928, 10307, 10372, -1, 9929, 10372, 10311, -1, 9929, 9928, 10372, -1, 9929, 10311, 9934, -1, 9947, 9934, 10311, -1, 9947, 9939, 9934, -1, 9948, 9947, 10311, -1, 9948, 10310, 10313, -1, 9948, 10311, 10310, -1, 10373, 7556, 7555, -1, 10373, 10281, 7556, -1, 10374, 10365, 10281, -1, 9949, 9948, 10313, -1, 10374, 10281, 10373, -1, 10375, 10315, 10316, -1, 10375, 10316, 10319, -1, 9957, 10313, 10315, -1, 10376, 9850, 10365, -1, 9957, 9949, 10313, -1, 9957, 10315, 10375, -1, 10376, 10365, 10374, -1, 9958, 10319, 9961, -1, 10377, 9850, 10376, -1, 10377, 9858, 9850, -1, 9958, 10375, 10319, -1, 9958, 9957, 10375, -1, 9984, 9961, 10319, -1, 9984, 9968, 9961, -1, 10378, 9858, 10377, -1, 10378, 9859, 9858, -1, 10379, 9862, 9859, -1, 10379, 4709, 9862, -1, 10379, 9859, 10378, -1, 9977, 9984, 10319, -1, 10379, 4708, 4709, -1, 9977, 10319, 10318, -1, 9977, 10318, 9978, -1, 10380, 10373, 7555, -1, 10380, 7555, 7553, -1, 10381, 10374, 10373, -1, 10381, 10373, 10380, -1, 9987, 9979, 10235, -1, 10382, 10376, 10374, -1, 9987, 10235, 10237, -1, 10382, 10374, 10381, -1, 10383, 10377, 10376, -1, 9995, 9987, 10237, -1, 9995, 9988, 9987, -1, 9995, 10237, 9999, -1, 10383, 10376, 10382, -1, 10023, 10326, 10331, -1, 10023, 10331, 10020, -1, 10384, 10378, 10377, -1, 10384, 10377, 10383, -1, 10023, 10327, 10326, -1, 10385, 10379, 10378, -1, 10027, 10327, 10023, -1, 10385, 4708, 10379, -1, 10385, 4710, 4708, -1, 10385, 10378, 10384, -1, 10027, 10366, 10327, -1, 10027, 10026, 10366, -1, 10386, 7553, 7551, -1, 10386, 10380, 7553, -1, 10018, 10027, 10023, -1, 10387, 10381, 10380, -1, 10387, 10380, 10386, -1, 10388, 10382, 10381, -1, 10021, 10020, 10336, -1, 10021, 10336, 10338, -1, 10388, 10381, 10387, -1, 10021, 10338, 10340, -1, 10389, 10383, 10382, -1, 10389, 10382, 10388, -1, 10390, 10383, 10389, -1, 10032, 10021, 10340, -1, 10032, 10022, 10021, -1, 10390, 10384, 10383, -1, 10032, 10340, 10391, -1, 10032, 10391, 10033, -1, 10392, 10384, 10390, -1, 10037, 10340, 10343, -1, 10392, 4711, 4710, -1, 10037, 10344, 10038, -1, 10037, 10343, 10344, -1, 10392, 4710, 10385, -1, 10392, 10385, 10384, -1, 10393, 10386, 7551, -1, 10393, 7551, 7549, -1, 10046, 10340, 10037, -1, 10046, 10391, 10340, -1, 10046, 10033, 10391, -1, 10394, 10387, 10386, -1, 10036, 10046, 10037, -1, 10394, 10386, 10393, -1, 10395, 10387, 10394, -1, 10040, 10350, 10352, -1, 10395, 10388, 10387, -1, 10040, 10038, 10350, -1, 10396, 10388, 10395, -1, 10396, 10389, 10388, -1, 10285, 10389, 10396, -1, 10285, 10390, 10389, -1, 10284, 10392, 10390, -1, 10397, 10040, 10352, -1, 10284, 4711, 10392, -1, 10397, 10041, 10040, -1, 10284, 10390, 10285, -1, 10397, 10352, 10353, -1, 10284, 4713, 4711, -1, 9808, 10393, 7549, -1, 10398, 10356, 10399, -1, 9808, 7549, 7547, -1, 10398, 10397, 10353, -1, 9812, 10393, 9808, -1, 10398, 10353, 10356, -1, 9812, 10394, 10393, -1, 10051, 10399, 10050, -1, 10051, 10043, 10041, -1, 10051, 10397, 10398, -1, 10051, 10398, 10399, -1, 10051, 10041, 10397, -1, 9814, 10394, 9812, -1, 10055, 10356, 10355, -1, 9814, 10395, 10394, -1, 10055, 10357, 9804, -1, 10055, 10355, 10357, -1, 10060, 10399, 10356, -1, 10060, 10050, 10399, -1, 9816, 10395, 9814, -1, 10060, 10356, 10055, -1, 9816, 10396, 10395, -1, 10286, 10285, 10396, -1, 10286, 10396, 9816, -1, 10056, 10060, 10055, -1, 10400, 10401, 10402, -1, 10400, 10403, 10401, -1, 10400, 10404, 10405, -1, 10400, 10402, 10404, -1, 10406, 10407, 10408, -1, 10406, 10408, 851, -1, 10406, 10409, 10403, -1, 10406, 10400, 10407, -1, 10406, 10403, 10400, -1, 10410, 908, 875, -1, 10410, 10411, 908, -1, 10410, 875, 10412, -1, 10410, 10412, 10411, -1, 10413, 851, 877, -1, 10413, 877, 10409, -1, 10413, 10406, 851, -1, 10413, 10409, 10406, -1, 10412, 875, 10414, -1, 10412, 10414, 10415, -1, 10412, 10416, 10411, -1, 10417, 10415, 10418, -1, 10417, 10419, 10416, -1, 10417, 10412, 10415, -1, 10417, 10416, 10412, -1, 10420, 10418, 10421, -1, 10420, 10421, 10422, -1, 10420, 10423, 10419, -1, 10420, 10424, 10423, -1, 10420, 10417, 10418, -1, 10420, 10419, 10417, -1, 10425, 10422, 10426, -1, 10425, 10427, 10424, -1, 10425, 10420, 10422, -1, 10425, 10424, 10420, -1, 10428, 10426, 10429, -1, 10428, 10430, 10427, -1, 10428, 10431, 10430, -1, 10428, 10425, 10426, -1, 10428, 10427, 10425, -1, 10432, 10429, 10433, -1, 10432, 10434, 10431, -1, 10432, 10428, 10429, -1, 10432, 10431, 10428, -1, 10404, 10433, 10435, -1, 10404, 10435, 10405, -1, 10404, 10402, 10434, -1, 10404, 10434, 10432, -1, 10404, 10432, 10433, -1, 10400, 10405, 10407, -1, 10436, 909, 908, -1, 10436, 908, 10411, -1, 10437, 10411, 10416, -1, 10437, 10436, 10411, -1, 10438, 10416, 10419, -1, 10438, 10437, 10416, -1, 6760, 10419, 10423, -1, 6760, 10438, 10419, -1, 6763, 6760, 10423, -1, 6308, 10423, 10424, -1, 6308, 6763, 10423, -1, 6306, 6308, 10424, -1, 6304, 10424, 10427, -1, 6304, 6306, 10424, -1, 6302, 10427, 10430, -1, 6302, 6304, 10427, -1, 6328, 10430, 10431, -1, 6328, 6302, 10430, -1, 6327, 6328, 10431, -1, 6323, 10431, 10434, -1, 6323, 6327, 10431, -1, 6337, 10434, 10402, -1, 6337, 6323, 10434, -1, 6336, 10402, 10401, -1, 6336, 6337, 10402, -1, 5196, 10401, 10403, -1, 5196, 6336, 10401, -1, 5205, 10403, 10409, -1, 5205, 5196, 10403, -1, 5204, 10409, 877, -1, 5204, 5205, 10409, -1, 879, 5204, 877, -1, 6760, 4780, 10438, -1, 4780, 10437, 10438, -1, 4780, 10436, 10437, -1, 4780, 909, 10436, -1, 4780, 907, 909, -1, 4780, 905, 907, -1, 4780, 903, 905, -1, 4780, 901, 903, -1, 10439, 874, 10440, -1, 10440, 874, 10441, -1, 10441, 874, 10442, -1, 10442, 874, 10443, -1, 10443, 10444, 10445, -1, 874, 10444, 10443, -1, 873, 871, 874, -1, 871, 869, 874, -1, 869, 867, 874, -1, 867, 865, 874, -1, 865, 863, 874, -1, 10444, 849, 10446, -1, 10446, 849, 10447, -1, 10447, 849, 10448, -1, 10448, 849, 10449, -1, 10449, 849, 10450, -1, 874, 849, 10444, -1, 863, 861, 874, -1, 874, 861, 849, -1, 861, 859, 849, -1, 849, 853, 850, -1, 859, 857, 849, -1, 849, 855, 853, -1, 857, 855, 849, -1, 875, 874, 10439, -1, 10414, 10439, 10440, -1, 10414, 875, 10439, -1, 10415, 10440, 10441, -1, 10415, 10414, 10440, -1, 10418, 10441, 10442, -1, 10418, 10415, 10441, -1, 10421, 10442, 10443, -1, 10421, 10418, 10442, -1, 10422, 10443, 10445, -1, 10422, 10421, 10443, -1, 10426, 10445, 10444, -1, 10426, 10422, 10445, -1, 10429, 10444, 10446, -1, 10429, 10426, 10444, -1, 10433, 10446, 10447, -1, 10433, 10429, 10446, -1, 10435, 10447, 10448, -1, 10435, 10433, 10447, -1, 10405, 10448, 10449, -1, 10405, 10435, 10448, -1, 10407, 10449, 10450, -1, 10407, 10405, 10449, -1, 10408, 10407, 10450, -1, 851, 10450, 849, -1, 851, 10408, 10450, -1, 6063, 6058, 6248, -1, 5978, 6163, 6166, -1, 5978, 5975, 6163, -1, 6068, 6253, 6258, -1, 6068, 6063, 6253, -1, 5981, 6166, 6169, -1, 5981, 5978, 6166, -1, 797, 798, 6172, -1, 6073, 6258, 6263, -1, 5984, 6169, 767, -1, 6073, 6068, 6258, -1, 5984, 5981, 6169, -1, 5987, 6172, 6175, -1, 5987, 797, 6172, -1, 769, 5984, 767, -1, 6078, 6263, 6268, -1, 6078, 6073, 6263, -1, 5990, 6175, 6178, -1, 5990, 5987, 6175, -1, 6083, 6268, 6273, -1, 6083, 6078, 6268, -1, 5993, 6178, 6181, -1, 5993, 5990, 6178, -1, 6088, 6273, 6278, -1, 6088, 6083, 6273, -1, 5996, 6181, 6184, -1, 5996, 5993, 6181, -1, 6093, 6088, 6278, -1, 6093, 6278, 6283, -1, 5999, 6184, 6187, -1, 5999, 5996, 6184, -1, 6098, 6093, 6283, -1, 6098, 6283, 6288, -1, 6002, 6187, 6190, -1, 6002, 5999, 6187, -1, 6103, 6098, 6288, -1, 6103, 6288, 6111, -1, 6005, 6190, 6193, -1, 6005, 6002, 6190, -1, 5928, 6103, 6111, -1, 5928, 6111, 6115, -1, 6008, 6193, 6196, -1, 6008, 6005, 6193, -1, 5929, 5928, 6115, -1, 5929, 6115, 6120, -1, 6011, 6196, 6199, -1, 6011, 6008, 6196, -1, 5934, 5929, 6120, -1, 5934, 6120, 6125, -1, 6014, 6199, 6202, -1, 6014, 6011, 6199, -1, 5939, 5934, 6125, -1, 5939, 6125, 6130, -1, 6017, 6202, 6206, -1, 6017, 6014, 6202, -1, 5944, 5939, 6130, -1, 5944, 6130, 6135, -1, 6018, 6206, 6208, -1, 6018, 6017, 6206, -1, 5949, 6135, 6139, -1, 5949, 5944, 6135, -1, 6022, 6208, 6213, -1, 6022, 6018, 6208, -1, 5954, 6139, 6142, -1, 5954, 5949, 6139, -1, 6027, 6213, 6218, -1, 6027, 6022, 6213, -1, 5957, 6142, 6145, -1, 5957, 5954, 6142, -1, 6032, 6218, 6223, -1, 6032, 6027, 6218, -1, 5960, 6145, 6148, -1, 5960, 5957, 6145, -1, 6037, 6223, 6228, -1, 6037, 6032, 6223, -1, 5963, 6148, 6151, -1, 5963, 5960, 6148, -1, 6042, 6228, 6233, -1, 6042, 6037, 6228, -1, 5966, 6151, 6154, -1, 5966, 5963, 6151, -1, 6048, 6233, 6238, -1, 6048, 6042, 6233, -1, 5969, 6154, 6157, -1, 5969, 5966, 6154, -1, 6053, 6238, 6243, -1, 6053, 6048, 6238, -1, 5972, 6157, 6160, -1, 5972, 5969, 6157, -1, 6058, 6243, 6248, -1, 6058, 6053, 6243, -1, 5975, 6160, 6163, -1, 5975, 5972, 6160, -1, 6063, 6248, 6253, -1, 10451, 10452, 10453, -1, 7458, 10452, 10451, -1, 7462, 10452, 7460, -1, 10454, 10455, 10456, -1, 7460, 10452, 7458, -1, 10457, 10458, 7533, -1, 10454, 10459, 10455, -1, 10460, 10459, 10454, -1, 10461, 10462, 10460, -1, 7533, 10458, 7535, -1, 10460, 10462, 10459, -1, 10457, 10463, 10458, -1, 10464, 10465, 10461, -1, 10461, 10465, 10462, -1, 10466, 10463, 10457, -1, 7459, 10465, 7457, -1, 7457, 10465, 10464, -1, 10467, 10468, 10466, -1, 7488, 10469, 7490, -1, 10466, 10468, 10463, -1, 10470, 10469, 7488, -1, 10471, 10472, 10467, -1, 10467, 10472, 10468, -1, 10470, 10473, 10469, -1, 10471, 10474, 10472, -1, 10475, 10473, 10470, -1, 10476, 10474, 10471, -1, 10455, 10477, 10475, -1, 7464, 10478, 7462, -1, 10452, 10478, 10476, -1, 7462, 10478, 10452, -1, 10475, 10477, 10473, -1, 10476, 10478, 10474, -1, 10459, 10479, 10455, -1, 10458, 10480, 7535, -1, 10455, 10479, 10477, -1, 10459, 10481, 10479, -1, 7535, 10480, 7537, -1, 10462, 10481, 10459, -1, 566, 7437, 565, -1, 10463, 10482, 10458, -1, 10458, 10482, 10480, -1, 10462, 10483, 10481, -1, 7459, 10483, 10465, -1, 7461, 10483, 7459, -1, 10465, 10483, 10462, -1, 10463, 10484, 10482, -1, 10469, 10485, 7490, -1, 10468, 10484, 10463, -1, 7490, 10485, 7492, -1, 10468, 10486, 10484, -1, 10472, 10486, 10468, -1, 10469, 10487, 10485, -1, 10474, 10488, 10472, -1, 10473, 10487, 10469, -1, 10472, 10488, 10486, -1, 10477, 10489, 10473, -1, 7466, 10490, 7464, -1, 10474, 10490, 10488, -1, 7464, 10490, 10478, -1, 10478, 10490, 10474, -1, 10473, 10489, 10487, -1, 10480, 10491, 7537, -1, 10477, 10492, 10489, -1, 10479, 10492, 10477, -1, 7537, 10491, 7539, -1, 10481, 10493, 10479, -1, 10482, 10494, 10480, -1, 10480, 10494, 10491, -1, 10479, 10493, 10492, -1, 7463, 10495, 7461, -1, 10483, 10495, 10481, -1, 7461, 10495, 10483, -1, 10482, 10496, 10494, -1, 10481, 10495, 10493, -1, 10485, 10497, 7492, -1, 10484, 10496, 10482, -1, 7492, 10497, 7494, -1, 10486, 10498, 10484, -1, 10487, 10499, 10485, -1, 10484, 10498, 10496, -1, 10485, 10499, 10497, -1, 10488, 10500, 10486, -1, 10486, 10500, 10498, -1, 7466, 10501, 10490, -1, 10489, 10502, 10487, -1, 10490, 10501, 10488, -1, 10488, 10501, 10500, -1, 10487, 10502, 10499, -1, 10491, 10503, 7539, -1, 10489, 10504, 10502, -1, 10492, 10504, 10489, -1, 7539, 10503, 7541, -1, 10494, 10505, 10491, -1, 10491, 10505, 10503, -1, 10493, 10506, 10492, -1, 10492, 10506, 10504, -1, 7465, 10507, 7463, -1, 7463, 10507, 10495, -1, 10494, 10508, 10505, -1, 10495, 10507, 10493, -1, 10493, 10507, 10506, -1, 10496, 10508, 10494, -1, 10497, 10509, 7494, -1, 7494, 10509, 7496, -1, 10498, 10510, 10496, -1, 10496, 10510, 10508, -1, 10497, 10511, 10509, -1, 10499, 10511, 10497, -1, 10500, 10512, 10498, -1, 10498, 10512, 10510, -1, 7468, 10513, 7466, -1, 7466, 10513, 10501, -1, 10501, 10513, 10500, -1, 10502, 10514, 10499, -1, 10500, 10513, 10512, -1, 10499, 10514, 10511, -1, 10503, 10515, 7541, -1, 10502, 10516, 10514, -1, 7541, 10515, 7543, -1, 10504, 10516, 10502, -1, 10506, 10517, 10504, -1, 10505, 10518, 10503, -1, 10504, 10517, 10516, -1, 10503, 10518, 10515, -1, 7467, 10519, 7465, -1, 10506, 10519, 10517, -1, 7465, 10519, 10507, -1, 10508, 10520, 10505, -1, 10507, 10519, 10506, -1, 10505, 10520, 10518, -1, 7496, 10521, 7498, -1, 10509, 10521, 7496, -1, 10508, 10522, 10520, -1, 10510, 10522, 10508, -1, 10511, 10523, 10509, -1, 10509, 10523, 10521, -1, 10510, 10524, 10522, -1, 10512, 10524, 10510, -1, 10513, 10525, 10512, -1, 7470, 10525, 7468, -1, 10511, 10526, 10523, -1, 10512, 10525, 10524, -1, 10514, 10526, 10511, -1, 7468, 10525, 10513, -1, 10515, 10527, 7543, -1, 10516, 10528, 10514, -1, 7543, 10527, 7546, -1, 10514, 10528, 10526, -1, 10516, 10529, 10528, -1, 10517, 10529, 10516, -1, 10518, 10530, 10515, -1, 10517, 10531, 10529, -1, 10515, 10530, 10527, -1, 7469, 10531, 7467, -1, 7467, 10531, 10519, -1, 10519, 10531, 10517, -1, 10518, 10532, 10530, -1, 10520, 10532, 10518, -1, 7498, 10533, 7500, -1, 10522, 10534, 10520, -1, 10521, 10533, 7498, -1, 10520, 10534, 10532, -1, 10521, 10535, 10533, -1, 10522, 10536, 10534, -1, 10524, 10536, 10522, -1, 10523, 10535, 10521, -1, 7472, 10537, 7470, -1, 7470, 10537, 10525, -1, 10525, 10537, 10524, -1, 10523, 10538, 10535, -1, 10524, 10537, 10536, -1, 10526, 10538, 10523, -1, 10527, 10539, 7546, -1, 10528, 10540, 10526, -1, 7546, 10539, 7548, -1, 10526, 10540, 10538, -1, 10529, 10541, 10528, -1, 10530, 10542, 10527, -1, 10528, 10541, 10540, -1, 10527, 10542, 10539, -1, 10531, 10543, 10529, -1, 7469, 10543, 10531, -1, 10529, 10543, 10541, -1, 10530, 10544, 10542, -1, 10532, 10544, 10530, -1, 7471, 10543, 7469, -1, 10533, 10545, 7500, -1, 7500, 10545, 7502, -1, 10532, 10546, 10544, -1, 10534, 10546, 10532, -1, 10533, 10547, 10545, -1, 10536, 10548, 10534, -1, 10535, 10547, 10533, -1, 10534, 10548, 10546, -1, 7474, 10549, 7472, -1, 10536, 10549, 10548, -1, 10537, 10549, 10536, -1, 7472, 10549, 10537, -1, 10535, 10550, 10547, -1, 10538, 10550, 10535, -1, 10539, 10551, 7548, -1, 10538, 10552, 10550, -1, 10540, 10552, 10538, -1, 7548, 10551, 7550, -1, 10541, 10553, 10540, -1, 10539, 10554, 10551, -1, 10542, 10554, 10539, -1, 10540, 10553, 10552, -1, 10543, 10555, 10541, -1, 7471, 10555, 10543, -1, 7473, 10555, 7471, -1, 10541, 10555, 10553, -1, 10542, 10556, 10554, -1, 10544, 10556, 10542, -1, 10545, 10557, 7502, -1, 10544, 10558, 10556, -1, 7502, 10557, 7504, -1, 10546, 10558, 10544, -1, 10547, 10559, 10545, -1, 10548, 10560, 10546, -1, 10545, 10559, 10557, -1, 10546, 10560, 10558, -1, 7476, 10561, 7474, -1, 7474, 10561, 10549, -1, 10549, 10561, 10548, -1, 10550, 10562, 10547, -1, 10548, 10561, 10560, -1, 10547, 10562, 10559, -1, 10552, 10563, 10550, -1, 10550, 10563, 10562, -1, 10551, 10564, 7550, -1, 7550, 10564, 7552, -1, 10551, 10565, 10564, -1, 10553, 10566, 10552, -1, 10552, 10566, 10563, -1, 10554, 10565, 10551, -1, 7475, 10567, 7473, -1, 7473, 10567, 10555, -1, 10555, 10567, 10553, -1, 10553, 10567, 10566, -1, 10556, 10568, 10554, -1, 10557, 10569, 7504, -1, 10554, 10568, 10565, -1, 7504, 10569, 7506, -1, 10556, 10570, 10568, -1, 10559, 10571, 10557, -1, 10558, 10570, 10556, -1, 10557, 10571, 10569, -1, 10560, 10572, 10558, -1, 10558, 10572, 10570, -1, 7476, 10573, 10561, -1, 10562, 10574, 10559, -1, 7433, 10573, 7476, -1, 10561, 10573, 10560, -1, 10560, 10573, 10572, -1, 10559, 10574, 10571, -1, 10563, 10575, 10562, -1, 7554, 10576, 584, -1, 10562, 10575, 10574, -1, 10564, 10576, 7552, -1, 10563, 10577, 10575, -1, 10566, 10577, 10563, -1, 7552, 10576, 7554, -1, 584, 10578, 591, -1, 7432, 10579, 7475, -1, 7475, 10579, 10567, -1, 10567, 10579, 10566, -1, 10565, 10578, 10564, -1, 10576, 10578, 584, -1, 10566, 10579, 10577, -1, 10564, 10578, 10576, -1, 10569, 10580, 7506, -1, 591, 10581, 594, -1, 10578, 10581, 591, -1, 7506, 10580, 7508, -1, 10568, 10581, 10565, -1, 10571, 10582, 10569, -1, 10565, 10581, 10578, -1, 10569, 10582, 10580, -1, 594, 10583, 599, -1, 10568, 10583, 10581, -1, 10570, 10583, 10568, -1, 10574, 10584, 10571, -1, 10581, 10583, 594, -1, 10570, 10585, 10583, -1, 599, 10585, 602, -1, 10571, 10584, 10582, -1, 10574, 10586, 10584, -1, 10572, 10585, 10570, -1, 10575, 10586, 10574, -1, 10583, 10585, 599, -1, 7434, 10587, 7433, -1, 602, 10587, 418, -1, 10577, 10588, 10575, -1, 10572, 10587, 10585, -1, 10585, 10587, 602, -1, 418, 10587, 7434, -1, 7433, 10587, 10573, -1, 10575, 10588, 10586, -1, 10573, 10587, 10572, -1, 7435, 10589, 7432, -1, 7432, 10589, 10579, -1, 10577, 10589, 10588, -1, 10579, 10589, 10577, -1, 7508, 10590, 7510, -1, 10580, 10590, 7508, -1, 10582, 10591, 10580, -1, 10580, 10591, 10590, -1, 10582, 10592, 10591, -1, 10584, 10592, 10582, -1, 10584, 10593, 10592, -1, 10586, 10593, 10584, -1, 10586, 10594, 10593, -1, 10588, 10594, 10586, -1, 10588, 10595, 10594, -1, 7436, 10595, 7435, -1, 7435, 10595, 10589, -1, 7554, 584, 586, -1, 10589, 10595, 10588, -1, 10590, 10596, 7510, -1, 7510, 10596, 7511, -1, 10591, 10597, 10590, -1, 10590, 10597, 10596, -1, 10592, 10598, 10591, -1, 10591, 10598, 10597, -1, 7434, 416, 418, -1, 10593, 10599, 10592, -1, 10592, 10599, 10598, -1, 546, 10600, 577, -1, 10594, 10601, 10593, -1, 577, 10600, 7509, -1, 10593, 10601, 10599, -1, 10595, 10602, 10594, -1, 550, 10603, 546, -1, 7436, 10602, 10595, -1, 7438, 10602, 7436, -1, 546, 10603, 10600, -1, 10594, 10602, 10601, -1, 10596, 10604, 7511, -1, 554, 10605, 550, -1, 550, 10605, 10603, -1, 7511, 10604, 7513, -1, 554, 10606, 10605, -1, 10597, 10607, 10596, -1, 10596, 10607, 10604, -1, 558, 10606, 554, -1, 561, 10608, 558, -1, 558, 10608, 10606, -1, 10597, 10609, 10607, -1, 7437, 10610, 565, -1, 7439, 10610, 7437, -1, 565, 10610, 561, -1, 561, 10610, 10608, -1, 10598, 10609, 10597, -1, 10599, 10611, 10598, -1, 7509, 10612, 7507, -1, 10598, 10611, 10609, -1, 10600, 10612, 7509, -1, 10601, 10613, 10599, -1, 10599, 10613, 10611, -1, 10600, 10614, 10612, -1, 7440, 10615, 7438, -1, 10603, 10614, 10600, -1, 10601, 10615, 10613, -1, 7438, 10615, 10602, -1, 10602, 10615, 10601, -1, 10605, 10616, 10603, -1, 10603, 10616, 10614, -1, 10604, 10617, 7513, -1, 10606, 10618, 10605, -1, 7513, 10617, 7515, -1, 10605, 10618, 10616, -1, 10607, 10619, 10604, -1, 10604, 10619, 10617, -1, 10608, 10620, 10606, -1, 10606, 10620, 10618, -1, 10609, 10621, 10607, -1, 10608, 10622, 10620, -1, 10607, 10621, 10619, -1, 10610, 10622, 10608, -1, 7441, 10622, 7439, -1, 7439, 10622, 10610, -1, 10612, 10623, 7507, -1, 10609, 10624, 10621, -1, 7507, 10623, 7505, -1, 10611, 10624, 10609, -1, 10614, 10625, 10612, -1, 10613, 10626, 10611, -1, 10612, 10625, 10623, -1, 10611, 10626, 10624, -1, 7442, 10627, 7440, -1, 7440, 10627, 10615, -1, 10615, 10627, 10613, -1, 10613, 10627, 10626, -1, 10616, 10628, 10614, -1, 10617, 10629, 7515, -1, 10614, 10628, 10625, -1, 10616, 10630, 10628, -1, 7515, 10629, 7517, -1, 10617, 10631, 10629, -1, 10618, 10630, 10616, -1, 10619, 10631, 10617, -1, 10620, 10632, 10618, -1, 10618, 10632, 10630, -1, 10620, 10633, 10632, -1, 10622, 10633, 10620, -1, 10621, 10634, 10619, -1, 7441, 10633, 10622, -1, 10619, 10634, 10631, -1, 10621, 10635, 10634, -1, 10624, 10635, 10621, -1, 7505, 10636, 7503, -1, 10623, 10636, 7505, -1, 10625, 10637, 10623, -1, 10626, 10638, 10624, -1, 10623, 10637, 10636, -1, 10624, 10638, 10635, -1, 7444, 10639, 7442, -1, 7442, 10639, 10627, -1, 10627, 10639, 10626, -1, 10628, 10640, 10625, -1, 10626, 10639, 10638, -1, 10625, 10640, 10637, -1, 10629, 10641, 7517, -1, 7517, 10641, 7519, -1, 10630, 10642, 10628, -1, 10628, 10642, 10640, -1, 10629, 10643, 10641, -1, 10632, 10644, 10630, -1, 10631, 10643, 10629, -1, 10630, 10644, 10642, -1, 7443, 10645, 7441, -1, 10634, 10646, 10631, -1, 7441, 10645, 10633, -1, 10632, 10645, 10644, -1, 10633, 10645, 10632, -1, 10631, 10646, 10643, -1, 10635, 10647, 10634, -1, 7503, 10648, 7501, -1, 10634, 10647, 10646, -1, 10636, 10648, 7503, -1, 10637, 10649, 10636, -1, 10638, 10650, 10635, -1, 10635, 10650, 10647, -1, 10636, 10649, 10648, -1, 10638, 10651, 10650, -1, 7446, 10651, 7444, -1, 7444, 10651, 10639, -1, 10637, 10652, 10649, -1, 10639, 10651, 10638, -1, 10640, 10652, 10637, -1, 7519, 10653, 7521, -1, 10641, 10653, 7519, -1, 10640, 10654, 10652, -1, 10642, 10654, 10640, -1, 10641, 10655, 10653, -1, 10642, 10656, 10654, -1, 10643, 10655, 10641, -1, 10644, 10656, 10642, -1, 10645, 10657, 10644, -1, 10644, 10657, 10656, -1, 7443, 10657, 10645, -1, 10643, 10658, 10655, -1, 7445, 10657, 7443, -1, 10646, 10658, 10643, -1, 10648, 10659, 7501, -1, 10647, 10660, 10646, -1, 7501, 10659, 7499, -1, 10646, 10660, 10658, -1, 10650, 10661, 10647, -1, 10649, 10662, 10648, -1, 10647, 10661, 10660, -1, 10648, 10662, 10659, -1, 7446, 10663, 10651, -1, 7448, 10663, 7446, -1, 10650, 10663, 10661, -1, 10652, 10664, 10649, -1, 10651, 10663, 10650, -1, 10653, 10665, 7521, -1, 10649, 10664, 10662, -1, 10652, 10666, 10664, -1, 7521, 10665, 7523, -1, 10654, 10666, 10652, -1, 10653, 10667, 10665, -1, 10654, 10668, 10666, -1, 10655, 10667, 10653, -1, 10656, 10668, 10654, -1, 7445, 10669, 10657, -1, 7447, 10669, 7445, -1, 10657, 10669, 10656, -1, 10655, 10670, 10667, -1, 10656, 10669, 10668, -1, 10658, 10670, 10655, -1, 10660, 10671, 10658, -1, 7499, 10672, 7497, -1, 10658, 10671, 10670, -1, 10659, 10672, 7499, -1, 10660, 10673, 10671, -1, 10662, 10674, 10659, -1, 10661, 10673, 10660, -1, 7450, 10675, 7448, -1, 10659, 10674, 10672, -1, 7448, 10675, 10663, -1, 10664, 10676, 10662, -1, 10663, 10675, 10661, -1, 10661, 10675, 10673, -1, 10665, 10677, 7523, -1, 10662, 10676, 10674, -1, 10664, 10678, 10676, -1, 7523, 10677, 7525, -1, 10666, 10678, 10664, -1, 10666, 10679, 10678, -1, 10667, 10680, 10665, -1, 10665, 10680, 10677, -1, 10668, 10679, 10666, -1, 7447, 10681, 10669, -1, 10667, 10682, 10680, -1, 10668, 10681, 10679, -1, 10670, 10682, 10667, -1, 7449, 10681, 7447, -1, 10669, 10681, 10668, -1, 10671, 10683, 10670, -1, 10672, 10684, 7497, -1, 7497, 10684, 7495, -1, 10670, 10683, 10682, -1, 10674, 10685, 10672, -1, 10671, 10686, 10683, -1, 10672, 10685, 10684, -1, 10673, 10686, 10671, -1, 7452, 10687, 7450, -1, 7450, 10687, 10675, -1, 10676, 10688, 10674, -1, 10675, 10687, 10673, -1, 10673, 10687, 10686, -1, 10677, 10689, 7525, -1, 10674, 10688, 10685, -1, 10678, 10690, 10676, -1, 10676, 10690, 10688, -1, 7525, 10689, 7527, -1, 10680, 10691, 10677, -1, 10679, 10692, 10678, -1, 10677, 10691, 10689, -1, 10678, 10692, 10690, -1, 10681, 10693, 10679, -1, 7449, 10693, 10681, -1, 10682, 10694, 10680, -1, 7453, 10693, 7451, -1, 10680, 10694, 10691, -1, 7451, 10693, 7449, -1, 10679, 10693, 10692, -1, 10684, 10695, 7495, -1, 10682, 10696, 10694, -1, 10683, 10696, 10682, -1, 7495, 10695, 7493, -1, 10685, 10697, 10684, -1, 10686, 10698, 10683, -1, 10684, 10697, 10695, -1, 10683, 10698, 10696, -1, 7454, 10699, 7452, -1, 7452, 10699, 10687, -1, 10688, 10700, 10685, -1, 10687, 10699, 10686, -1, 10686, 10699, 10698, -1, 10685, 10700, 10697, -1, 10689, 10701, 7527, -1, 10688, 10702, 10700, -1, 10690, 10702, 10688, -1, 7527, 10701, 7529, -1, 10692, 10703, 10690, -1, 10689, 10704, 10701, -1, 10690, 10703, 10702, -1, 10691, 10704, 10689, -1, 7455, 10705, 7453, -1, 7453, 10705, 10693, -1, 10693, 10705, 10692, -1, 10694, 10706, 10691, -1, 10692, 10705, 10703, -1, 10691, 10706, 10704, -1, 10695, 10707, 7493, -1, 10696, 10708, 10694, -1, 7493, 10707, 7491, -1, 10694, 10708, 10706, -1, 10697, 10709, 10695, -1, 10696, 10710, 10708, -1, 10698, 10710, 10696, -1, 10695, 10709, 10707, -1, 7456, 10711, 7454, -1, 7454, 10711, 10699, -1, 10699, 10711, 10698, -1, 10697, 10712, 10709, -1, 10700, 10712, 10697, -1, 10698, 10711, 10710, -1, 10701, 10713, 7529, -1, 10702, 10714, 10700, -1, 7529, 10713, 7531, -1, 10700, 10714, 10712, -1, 10701, 10715, 10713, -1, 10703, 10716, 10702, -1, 10702, 10716, 10714, -1, 10704, 10715, 10701, -1, 7455, 10717, 10705, -1, 10705, 10717, 10703, -1, 10703, 10717, 10716, -1, 10706, 10718, 10704, -1, 7491, 10719, 7487, -1, 10704, 10718, 10715, -1, 10707, 10719, 7491, -1, 10706, 10720, 10718, -1, 10708, 10720, 10706, -1, 10709, 10456, 10707, -1, 10708, 10453, 10720, -1, 10707, 10456, 10719, -1, 10710, 10453, 10708, -1, 10710, 10451, 10453, -1, 10712, 10454, 10709, -1, 7458, 10451, 7456, -1, 7456, 10451, 10711, -1, 10711, 10451, 10710, -1, 10709, 10454, 10456, -1, 10714, 10460, 10712, -1, 7531, 10457, 7533, -1, 10712, 10460, 10454, -1, 10713, 10457, 7531, -1, 10716, 10461, 10714, -1, 10714, 10461, 10460, -1, 10715, 10466, 10713, -1, 7457, 10464, 7455, -1, 10713, 10466, 10457, -1, 7455, 10464, 10717, -1, 10716, 10464, 10461, -1, 10717, 10464, 10716, -1, 7487, 10470, 7488, -1, 10719, 10470, 7487, -1, 10715, 10467, 10466, -1, 10718, 10467, 10715, -1, 10720, 10471, 10718, -1, 10456, 10475, 10719, -1, 10718, 10471, 10467, -1, 10719, 10475, 10470, -1, 10453, 10476, 10720, -1, 10456, 10455, 10475, -1, 10720, 10476, 10471, -1, 10453, 10452, 10476, -1, 10721, 10722, 10723, -1, 10724, 10725, 10726, -1, 10727, 10728, 10729, -1, 10723, 10722, 10730, -1, 10731, 10732, 10721, -1, 10729, 10728, 10725, -1, 7412, 10733, 7410, -1, 10721, 10732, 10722, -1, 7410, 10733, 10734, -1, 10734, 10733, 10727, -1, 7411, 10735, 7409, -1, 10727, 10733, 10728, -1, 7409, 10735, 10736, -1, 10736, 10735, 10731, -1, 10731, 10735, 10732, -1, 7313, 10737, 7314, -1, 10738, 10737, 7313, -1, 10739, 10740, 7358, -1, 7358, 10740, 7356, -1, 10738, 10741, 10737, -1, 10742, 10741, 10738, -1, 10739, 10743, 10740, -1, 10744, 10743, 10739, -1, 10742, 10745, 10741, -1, 10744, 10746, 10743, -1, 10726, 10745, 10742, -1, 10730, 10746, 10744, -1, 10730, 10747, 10746, -1, 10726, 10748, 10745, -1, 10722, 10747, 10730, -1, 10725, 10748, 10726, -1, 10728, 10749, 10725, -1, 10725, 10749, 10748, -1, 10722, 10750, 10747, -1, 10733, 10751, 10728, -1, 10732, 10750, 10722, -1, 10728, 10751, 10749, -1, 10732, 10752, 10750, -1, 7414, 10751, 7412, -1, 7412, 10751, 10733, -1, 7413, 10752, 7411, -1, 7411, 10752, 10735, -1, 10735, 10752, 10732, -1, 7314, 10753, 7312, -1, 10737, 10753, 7314, -1, 7356, 10754, 7354, -1, 10740, 10754, 7356, -1, 10737, 10755, 10753, -1, 10740, 10756, 10754, -1, 10741, 10755, 10737, -1, 10745, 10757, 10741, -1, 10741, 10757, 10755, -1, 10743, 10756, 10740, -1, 10743, 10758, 10756, -1, 10746, 10758, 10743, -1, 10745, 10759, 10757, -1, 10747, 10760, 10746, -1, 10748, 10759, 10745, -1, 10749, 10761, 10748, -1, 10746, 10760, 10758, -1, 10748, 10761, 10759, -1, 10750, 10762, 10747, -1, 7414, 10763, 10751, -1, 10747, 10762, 10760, -1, 7416, 10763, 7414, -1, 10752, 10764, 10750, -1, 7413, 10764, 10752, -1, 10749, 10763, 10761, -1, 10751, 10763, 10749, -1, 7415, 10764, 7413, -1, 10753, 10765, 7312, -1, 10750, 10764, 10762, -1, 10754, 10766, 7354, -1, 7312, 10765, 7306, -1, 10755, 10767, 10753, -1, 7354, 10766, 7352, -1, 10753, 10767, 10765, -1, 10756, 10768, 10754, -1, 10754, 10768, 10766, -1, 10758, 10769, 10756, -1, 10755, 10770, 10767, -1, 10757, 10770, 10755, -1, 10756, 10769, 10768, -1, 10759, 10771, 10757, -1, 10758, 10772, 10769, -1, 10760, 10772, 10758, -1, 10757, 10771, 10770, -1, 10759, 10773, 10771, -1, 10761, 10773, 10759, -1, 10760, 10774, 10772, -1, 10762, 10774, 10760, -1, 7418, 10775, 7416, -1, 7416, 10775, 10763, -1, 10763, 10775, 10761, -1, 7417, 10776, 7415, -1, 7415, 10776, 10764, -1, 10761, 10775, 10773, -1, 10764, 10776, 10762, -1, 10762, 10776, 10774, -1, 10765, 10777, 7306, -1, 10766, 10778, 7352, -1, 7306, 10777, 7303, -1, 10767, 10779, 10765, -1, 7352, 10778, 7350, -1, 10765, 10779, 10777, -1, 10768, 10780, 10766, -1, 10766, 10780, 10778, -1, 10770, 10781, 10767, -1, 10768, 10782, 10780, -1, 10769, 10782, 10768, -1, 10767, 10781, 10779, -1, 10771, 10783, 10770, -1, 10770, 10783, 10781, -1, 10772, 10784, 10769, -1, 10769, 10784, 10782, -1, 10772, 10785, 10784, -1, 10773, 10786, 10771, -1, 10774, 10785, 10772, -1, 10771, 10786, 10783, -1, 7420, 10787, 7418, -1, 10775, 10787, 10773, -1, 7419, 10788, 7417, -1, 7417, 10788, 10776, -1, 10773, 10787, 10786, -1, 10776, 10788, 10774, -1, 7418, 10787, 10775, -1, 10774, 10788, 10785, -1, 10777, 10789, 7303, -1, 10778, 10790, 7350, -1, 7303, 10789, 7301, -1, 7350, 10790, 7348, -1, 10779, 10791, 10777, -1, 10777, 10791, 10789, -1, 10780, 10792, 10778, -1, 10778, 10792, 10790, -1, 10779, 10793, 10791, -1, 10780, 10794, 10792, -1, 10781, 10793, 10779, -1, 10782, 10794, 10780, -1, 10783, 10795, 10781, -1, 10784, 10796, 10782, -1, 10781, 10795, 10793, -1, 10782, 10796, 10794, -1, 10783, 10797, 10795, -1, 10785, 10798, 10784, -1, 10786, 10797, 10783, -1, 10784, 10798, 10796, -1, 7422, 10799, 7420, -1, 7421, 10800, 7419, -1, 7420, 10799, 10787, -1, 7419, 10800, 10788, -1, 10787, 10799, 10786, -1, 10788, 10800, 10785, -1, 10785, 10800, 10798, -1, 10786, 10799, 10797, -1, 7301, 10801, 7302, -1, 10790, 10802, 7348, -1, 10789, 10801, 7301, -1, 7348, 10802, 7346, -1, 10791, 10803, 10789, -1, 10792, 10804, 10790, -1, 10789, 10803, 10801, -1, 10790, 10804, 10802, -1, 10792, 10805, 10804, -1, 10791, 10806, 10803, -1, 10793, 10806, 10791, -1, 10794, 10805, 10792, -1, 10795, 10807, 10793, -1, 10796, 10808, 10794, -1, 10794, 10808, 10805, -1, 10793, 10807, 10806, -1, 10796, 10809, 10808, -1, 10795, 10810, 10807, -1, 10797, 10810, 10795, -1, 10798, 10809, 10796, -1, 7423, 10811, 7421, -1, 10797, 10812, 10810, -1, 7421, 10811, 10800, -1, 10800, 10811, 10798, -1, 7424, 10812, 7422, -1, 7422, 10812, 10799, -1, 10798, 10811, 10809, -1, 10799, 10812, 10797, -1, 7302, 10813, 7386, -1, 10802, 10814, 7346, -1, 10801, 10813, 7302, -1, 7346, 10814, 7344, -1, 10804, 10815, 10802, -1, 10801, 10816, 10813, -1, 10802, 10815, 10814, -1, 10803, 10816, 10801, -1, 10804, 10817, 10815, -1, 10805, 10817, 10804, -1, 10803, 10818, 10816, -1, 10806, 10818, 10803, -1, 10808, 10819, 10805, -1, 10806, 10820, 10818, -1, 10805, 10819, 10817, -1, 10807, 10820, 10806, -1, 10810, 10821, 10807, -1, 10808, 10822, 10819, -1, 10807, 10821, 10820, -1, 10809, 10822, 10808, -1, 10811, 10823, 10809, -1, 10812, 10824, 10810, -1, 7424, 10824, 10812, -1, 7425, 10823, 7423, -1, 10810, 10824, 10821, -1, 10809, 10823, 10822, -1, 7423, 10823, 10811, -1, 7426, 10824, 7424, -1, 10814, 10825, 7344, -1, 7344, 10825, 7341, -1, 7386, 10826, 7384, -1, 10813, 10826, 7386, -1, 10816, 10827, 10813, -1, 10815, 10828, 10814, -1, 10813, 10827, 10826, -1, 10814, 10828, 10825, -1, 10818, 10829, 10816, -1, 10815, 10830, 10828, -1, 10817, 10830, 10815, -1, 10816, 10829, 10827, -1, 10820, 10831, 10818, -1, 10817, 10832, 10830, -1, 10819, 10832, 10817, -1, 10818, 10831, 10829, -1, 10821, 10833, 10820, -1, 10822, 10834, 10819, -1, 10819, 10834, 10832, -1, 10820, 10833, 10831, -1, 10824, 10835, 10821, -1, 7427, 10836, 7425, -1, 7426, 10835, 10824, -1, 7425, 10836, 10823, -1, 7428, 10835, 7426, -1, 10823, 10836, 10822, -1, 10821, 10835, 10833, -1, 10822, 10836, 10834, -1, 10825, 10837, 7341, -1, 10826, 10838, 7384, -1, 7341, 10837, 7339, -1, 7384, 10838, 7382, -1, 10828, 10839, 10825, -1, 10826, 10840, 10838, -1, 10825, 10839, 10837, -1, 10827, 10840, 10826, -1, 10828, 10841, 10839, -1, 10830, 10841, 10828, -1, 10829, 10842, 10827, -1, 10827, 10842, 10840, -1, 10832, 10843, 10830, -1, 10829, 10844, 10842, -1, 10831, 10844, 10829, -1, 10830, 10843, 10841, -1, 10834, 10845, 10832, -1, 10831, 10846, 10844, -1, 10833, 10846, 10831, -1, 10832, 10845, 10843, -1, 7429, 10847, 7427, -1, 7430, 10848, 7428, -1, 7427, 10847, 10836, -1, 7428, 10848, 10835, -1, 10835, 10848, 10833, -1, 10836, 10847, 10834, -1, 10834, 10847, 10845, -1, 10833, 10848, 10846, -1, 10837, 10849, 7339, -1, 10838, 10850, 7382, -1, 7382, 10850, 7381, -1, 7339, 10849, 7337, -1, 10837, 10851, 10849, -1, 10838, 10852, 10850, -1, 10839, 10851, 10837, -1, 10840, 10852, 10838, -1, 10841, 10853, 10839, -1, 10842, 10854, 10840, -1, 10839, 10853, 10851, -1, 10840, 10854, 10852, -1, 10844, 10855, 10842, -1, 10841, 10856, 10853, -1, 10843, 10856, 10841, -1, 10842, 10855, 10854, -1, 10844, 10857, 10855, -1, 10845, 10858, 10843, -1, 10846, 10857, 10844, -1, 10843, 10858, 10856, -1, 7431, 10859, 7429, -1, 7387, 10860, 7430, -1, 7429, 10859, 10847, -1, 7430, 10860, 10848, -1, 10847, 10859, 10845, -1, 10848, 10860, 10846, -1, 10845, 10859, 10858, -1, 10846, 10860, 10857, -1, 10849, 10861, 7337, -1, 10850, 10862, 7381, -1, 7381, 10862, 7378, -1, 7337, 10861, 7335, -1, 10849, 10863, 10861, -1, 10852, 10864, 10850, -1, 10851, 10863, 10849, -1, 10850, 10864, 10862, -1, 7333, 206, 208, -1, 10854, 10865, 10852, -1, 10851, 10866, 10863, -1, 10853, 10866, 10851, -1, 10852, 10865, 10864, -1, 10856, 10867, 10853, -1, 10854, 10868, 10865, -1, 10855, 10868, 10854, -1, 10853, 10867, 10866, -1, 10856, 10869, 10867, -1, 10857, 10870, 10855, -1, 10858, 10869, 10856, -1, 10855, 10870, 10868, -1, 7389, 10871, 7431, -1, 7431, 10871, 10859, -1, 7388, 10872, 7387, -1, 7390, 232, 233, -1, 10859, 10871, 10858, -1, 7387, 10872, 10860, -1, 10860, 10872, 10857, -1, 10858, 10871, 10869, -1, 10857, 10872, 10870, -1, 192, 10873, 193, -1, 7333, 10874, 206, -1, 7378, 10875, 7377, -1, 193, 10873, 7379, -1, 10861, 10874, 7335, -1, 10862, 10875, 7378, -1, 7335, 10874, 7333, -1, 10864, 10876, 10862, -1, 212, 10877, 192, -1, 206, 10878, 214, -1, 192, 10877, 10873, -1, 10862, 10876, 10875, -1, 10863, 10878, 10861, -1, 10874, 10878, 206, -1, 10864, 10879, 10876, -1, 219, 10880, 212, -1, 10861, 10878, 10874, -1, 212, 10880, 10877, -1, 214, 10881, 216, -1, 10878, 10881, 214, -1, 216, 10881, 222, -1, 10865, 10879, 10864, -1, 219, 10882, 10880, -1, 10866, 10881, 10863, -1, 10865, 10883, 10879, -1, 10863, 10881, 10878, -1, 225, 10882, 219, -1, 10868, 10883, 10865, -1, 10866, 10884, 10881, -1, 235, 10885, 225, -1, 10868, 10886, 10883, -1, 10867, 10884, 10866, -1, 225, 10885, 10882, -1, 10881, 10884, 222, -1, 10870, 10886, 10868, -1, 7392, 10887, 243, -1, 10867, 10888, 10884, -1, 241, 10887, 235, -1, 222, 10888, 227, -1, 10870, 10889, 10886, -1, 243, 10887, 241, -1, 235, 10887, 10885, -1, 7391, 10889, 7388, -1, 7388, 10889, 10872, -1, 10869, 10888, 10867, -1, 10872, 10889, 10870, -1, 10884, 10888, 222, -1, 10875, 10890, 7377, -1, 7379, 10891, 7380, -1, 10888, 10892, 227, -1, 7390, 10892, 7389, -1, 10873, 10891, 7379, -1, 227, 10892, 233, -1, 10869, 10892, 10888, -1, 233, 10892, 7390, -1, 7377, 10890, 7376, -1, 7389, 10892, 10871, -1, 10873, 10893, 10891, -1, 10871, 10892, 10869, -1, 10877, 10893, 10873, -1, 10875, 10894, 10890, -1, 10876, 10894, 10875, -1, 10879, 10895, 10876, -1, 10877, 10896, 10893, -1, 10876, 10895, 10894, -1, 10880, 10896, 10877, -1, 10883, 10897, 10879, -1, 10880, 10898, 10896, -1, 10879, 10897, 10895, -1, 10882, 10898, 10880, -1, 10882, 10899, 10898, -1, 10886, 10900, 10883, -1, 10885, 10899, 10882, -1, 10883, 10900, 10897, -1, 10887, 10901, 10885, -1, 10885, 10901, 10899, -1, 7392, 10901, 10887, -1, 10889, 10902, 10886, -1, 7391, 10902, 10889, -1, 7394, 10901, 7392, -1, 7393, 10902, 7391, -1, 10886, 10902, 10900, -1, 10891, 10903, 7380, -1, 10890, 10904, 7376, -1, 7380, 10903, 7383, -1, 7376, 10904, 7374, -1, 10893, 10905, 10891, -1, 10894, 10906, 10890, -1, 10890, 10906, 10904, -1, 10891, 10905, 10903, -1, 10893, 10907, 10905, -1, 10895, 10908, 10894, -1, 10896, 10907, 10893, -1, 10894, 10908, 10906, -1, 10896, 10909, 10907, -1, 10898, 10909, 10896, -1, 10897, 10910, 10895, -1, 10895, 10910, 10908, -1, 10899, 10911, 10898, -1, 10897, 10912, 10910, -1, 10898, 10911, 10909, -1, 10900, 10912, 10897, -1, 7396, 10913, 7394, -1, 10899, 10913, 10911, -1, 7395, 10914, 7393, -1, 10901, 10913, 10899, -1, 7393, 10914, 10902, -1, 7394, 10913, 10901, -1, 10902, 10914, 10900, -1, 10903, 10915, 7383, -1, 10900, 10914, 10912, -1, 10904, 10916, 7374, -1, 7383, 10915, 7385, -1, 7374, 10916, 7372, -1, 10905, 10917, 10903, -1, 10904, 10918, 10916, -1, 10903, 10917, 10915, -1, 10907, 10919, 10905, -1, 10905, 10919, 10917, -1, 10906, 10918, 10904, -1, 10908, 10920, 10906, -1, 10906, 10920, 10918, -1, 10907, 10921, 10919, -1, 10910, 10922, 10908, -1, 10909, 10921, 10907, -1, 10909, 10923, 10921, -1, 10908, 10922, 10920, -1, 10910, 10924, 10922, -1, 10911, 10923, 10909, -1, 10912, 10924, 10910, -1, 10913, 10925, 10911, -1, 10911, 10925, 10923, -1, 7398, 10925, 7396, -1, 7397, 10926, 7395, -1, 7396, 10925, 10913, -1, 7395, 10926, 10914, -1, 10914, 10926, 10912, -1, 10915, 10927, 7385, -1, 10912, 10926, 10924, -1, 7385, 10927, 7299, -1, 10916, 10928, 7372, -1, 10917, 10929, 10915, -1, 7372, 10928, 7370, -1, 10915, 10929, 10927, -1, 10918, 10930, 10916, -1, 10916, 10930, 10928, -1, 10917, 10931, 10929, -1, 10918, 10932, 10930, -1, 10919, 10931, 10917, -1, 10920, 10932, 10918, -1, 10919, 10933, 10931, -1, 10921, 10933, 10919, -1, 10922, 10934, 10920, -1, 10920, 10934, 10932, -1, 10924, 10935, 10922, -1, 10921, 10936, 10933, -1, 10923, 10936, 10921, -1, 10922, 10935, 10934, -1, 7398, 10937, 10925, -1, 10925, 10937, 10923, -1, 10923, 10937, 10936, -1, 7399, 10938, 7397, -1, 7397, 10938, 10926, -1, 7400, 10937, 7398, -1, 10926, 10938, 10924, -1, 10924, 10938, 10935, -1, 7299, 10939, 7298, -1, 10928, 10940, 7370, -1, 10927, 10939, 7299, -1, 7370, 10940, 7368, -1, 10927, 10941, 10939, -1, 10928, 10942, 10940, -1, 10930, 10942, 10928, -1, 10929, 10941, 10927, -1, 10929, 10943, 10941, -1, 10932, 10944, 10930, -1, 10931, 10943, 10929, -1, 10930, 10944, 10942, -1, 10932, 10945, 10944, -1, 10931, 10946, 10943, -1, 10934, 10945, 10932, -1, 10933, 10946, 10931, -1, 10936, 10947, 10933, -1, 10935, 10948, 10934, -1, 10933, 10947, 10946, -1, 7402, 10949, 7400, -1, 10934, 10948, 10945, -1, 10937, 10949, 10936, -1, 10935, 10950, 10948, -1, 7400, 10949, 10937, -1, 7401, 10950, 7399, -1, 10936, 10949, 10947, -1, 7399, 10950, 10938, -1, 10938, 10950, 10935, -1, 7298, 10951, 7300, -1, 7368, 10952, 7366, -1, 10940, 10952, 7368, -1, 10939, 10951, 7298, -1, 10939, 10953, 10951, -1, 10941, 10953, 10939, -1, 10940, 10954, 10952, -1, 10942, 10954, 10940, -1, 10942, 10955, 10954, -1, 10943, 10956, 10941, -1, 10941, 10956, 10953, -1, 10944, 10955, 10942, -1, 10943, 10957, 10956, -1, 10946, 10957, 10943, -1, 10944, 10958, 10955, -1, 10947, 10959, 10946, -1, 10945, 10958, 10944, -1, 10948, 10960, 10945, -1, 10946, 10959, 10957, -1, 10945, 10960, 10958, -1, 7404, 10961, 7402, -1, 10950, 10962, 10948, -1, 7402, 10961, 10949, -1, 7401, 10962, 10950, -1, 10947, 10961, 10959, -1, 10948, 10962, 10960, -1, 10949, 10961, 10947, -1, 7403, 10962, 7401, -1, 10952, 10963, 7366, -1, 10951, 10964, 7300, -1, 7300, 10964, 7304, -1, 7366, 10963, 7364, -1, 10951, 10965, 10964, -1, 10953, 10965, 10951, -1, 10953, 10966, 10965, -1, 10954, 10967, 10952, -1, 10952, 10967, 10963, -1, 10955, 10968, 10954, -1, 10956, 10966, 10953, -1, 10954, 10968, 10967, -1, 10957, 10969, 10956, -1, 10956, 10969, 10966, -1, 10958, 10970, 10955, -1, 10959, 10971, 10957, -1, 10955, 10970, 10968, -1, 10958, 10972, 10970, -1, 10957, 10971, 10969, -1, 10960, 10972, 10958, -1, 7404, 10973, 10961, -1, 10959, 10973, 10971, -1, 7406, 10973, 7404, -1, 7405, 10974, 7403, -1, 10962, 10974, 10960, -1, 10961, 10973, 10959, -1, 7403, 10974, 10962, -1, 10964, 10975, 7304, -1, 10960, 10974, 10972, -1, 10963, 10976, 7364, -1, 7304, 10975, 7308, -1, 7364, 10976, 7362, -1, 10964, 10977, 10975, -1, 10963, 10978, 10976, -1, 10967, 10978, 10963, -1, 10965, 10977, 10964, -1, 10966, 10979, 10965, -1, 10968, 10980, 10967, -1, 10965, 10979, 10977, -1, 10967, 10980, 10978, -1, 10969, 10981, 10966, -1, 10970, 10982, 10968, -1, 10966, 10981, 10979, -1, 10968, 10982, 10980, -1, 10971, 10983, 10969, -1, 10969, 10983, 10981, -1, 10972, 10984, 10970, -1, 7408, 10985, 7406, -1, 10970, 10984, 10982, -1, 10973, 10985, 10971, -1, 7406, 10985, 10973, -1, 7407, 10986, 7405, -1, 10971, 10985, 10983, -1, 7405, 10986, 10974, -1, 10974, 10986, 10972, -1, 10975, 10987, 7308, -1, 10972, 10986, 10984, -1, 10976, 10988, 7362, -1, 7308, 10987, 7310, -1, 7362, 10988, 7360, -1, 10977, 10989, 10975, -1, 10975, 10989, 10987, -1, 10978, 10990, 10976, -1, 10976, 10990, 10988, -1, 10979, 10724, 10977, -1, 10980, 10723, 10978, -1, 10977, 10724, 10989, -1, 10978, 10723, 10990, -1, 10979, 10729, 10724, -1, 10981, 10729, 10979, -1, 10982, 10721, 10980, -1, 10980, 10721, 10723, -1, 10981, 10727, 10729, -1, 10983, 10727, 10981, -1, 10982, 10731, 10721, -1, 10984, 10731, 10982, -1, 7410, 10734, 7408, -1, 7408, 10734, 10985, -1, 10985, 10734, 10983, -1, 7409, 10736, 7407, -1, 7407, 10736, 10986, -1, 10983, 10734, 10727, -1, 10986, 10736, 10984, -1, 10984, 10736, 10731, -1, 7310, 10738, 7313, -1, 10988, 10739, 7360, -1, 10987, 10738, 7310, -1, 7360, 10739, 7358, -1, 10989, 10742, 10987, -1, 10987, 10742, 10738, -1, 10990, 10744, 10988, -1, 10988, 10744, 10739, -1, 10989, 10726, 10742, -1, 10724, 10726, 10989, -1, 10990, 10730, 10744, -1, 10723, 10730, 10990, -1, 10729, 10725, 10724, -1, 10991, 10992, 10993, -1, 10993, 10992, 10994, -1, 10994, 10995, 10996, -1, 10992, 10995, 10994, -1, 10996, 10997, 10998, -1, 10995, 10997, 10996, -1, 10998, 10999, 11000, -1, 10997, 10999, 10998, -1, 11000, 11001, 11002, -1, 10999, 11001, 11000, -1, 11001, 11003, 11002, -1, 11001, 11004, 11003, -1, 11004, 11005, 11003, -1, 11004, 11006, 11005, -1, 11006, 11007, 11005, -1, 11006, 11008, 11007, -1, 11008, 11009, 11007, -1, 11008, 11010, 11009, -1, 11010, 11011, 11009, -1, 11010, 11012, 11011, -1, 11012, 11013, 11011, -1, 11012, 11014, 11013, -1, 11014, 11015, 11013, -1, 11014, 11016, 11015, -1, 11016, 11017, 11015, -1, 11016, 11018, 11017, -1, 11018, 11019, 11017, -1, 11019, 11020, 11017, -1, 11017, 11021, 11022, -1, 11020, 11021, 11017, -1, 11021, 11023, 11022, -1, 11023, 11024, 11022, -1, 11023, 11025, 11024, -1, 11025, 11026, 11024, -1, 11027, 11028, 11029, -1, 11027, 11030, 11028, -1, 11030, 11031, 11028, -1, 11030, 11032, 11031, -1, 11032, 11033, 11031, -1, 11032, 11034, 11033, -1, 11034, 11035, 11033, -1, 11034, 11036, 11035, -1, 11036, 11037, 11035, -1, 11036, 11038, 11037, -1, 11038, 11039, 11037, -1, 11038, 11040, 11039, -1, 11040, 11041, 11039, -1, 11040, 11042, 11041, -1, 11042, 11043, 11041, -1, 11042, 11044, 11043, -1, 11044, 11045, 11043, -1, 11044, 11046, 11045, -1, 11045, 11047, 11048, -1, 11046, 11047, 11045, -1, 11047, 11049, 11048, -1, 11049, 11050, 11048, -1, 11051, 11052, 11053, -1, 11053, 11052, 11054, -1, 11055, 11056, 11051, -1, 11051, 11056, 11052, -1, 11057, 11058, 11059, -1, 11054, 11058, 11060, -1, 11060, 11058, 11057, -1, 11052, 11058, 11054, -1, 11061, 11062, 11063, -1, 11064, 11062, 11055, -1, 11063, 11062, 11064, -1, 11055, 11062, 11056, -1, 11059, 11065, 11066, -1, 11052, 11065, 11058, -1, 11056, 11065, 11052, -1, 11058, 11065, 11059, -1, 11067, 11068, 11069, -1, 11066, 11068, 11067, -1, 11069, 11068, 11070, -1, 11070, 11068, 11061, -1, 11065, 11068, 11066, -1, 11056, 11068, 11065, -1, 11061, 11068, 11062, -1, 11062, 11068, 11056, -1, 11071, 11072, 11073, -1, 11073, 11072, 11074, -1, 11075, 11072, 11071, -1, 11076, 11077, 11078, -1, 11079, 11077, 11076, -1, 11080, 11081, 11082, -1, 11082, 11081, 11079, -1, 11083, 11084, 11075, -1, 11074, 11084, 11080, -1, 11075, 11084, 11072, -1, 11072, 11084, 11074, -1, 11078, 11085, 11086, -1, 11077, 11085, 11078, -1, 11081, 11087, 11079, -1, 11079, 11087, 11077, -1, 11088, 11089, 11083, -1, 11080, 11089, 11081, -1, 11090, 11075, 11071, -1, 11083, 11089, 11084, -1, 11084, 11089, 11080, -1, 11086, 11091, 11092, -1, 11085, 11091, 11086, -1, 11077, 11093, 11085, -1, 11087, 11093, 11077, -1, 11094, 11095, 11088, -1, 11088, 11095, 11089, -1, 11081, 11095, 11087, -1, 11089, 11095, 11081, -1, 11092, 11096, 11097, -1, 11091, 11096, 11092, -1, 11085, 11098, 11091, -1, 11093, 11098, 11085, -1, 11095, 11099, 11087, -1, 11100, 11099, 11094, -1, 11094, 11099, 11095, -1, 11087, 11099, 11093, -1, 11097, 11101, 11102, -1, 11096, 11101, 11097, -1, 11098, 11103, 11091, -1, 11091, 11103, 11096, -1, 11099, 11104, 11093, -1, 11093, 11104, 11098, -1, 11100, 11104, 11099, -1, 11105, 11104, 11100, -1, 11102, 11106, 11107, -1, 11101, 11106, 11102, -1, 11096, 11108, 11101, -1, 11103, 11108, 11096, -1, 11104, 11109, 11098, -1, 11110, 11109, 11105, -1, 11098, 11109, 11103, -1, 11105, 11109, 11104, -1, 11111, 11112, 11113, -1, 11106, 11112, 11107, -1, 11107, 11112, 11114, -1, 11114, 11112, 11111, -1, 11115, 11116, 11117, -1, 11118, 11119, 11120, -1, 11108, 11121, 11101, -1, 11120, 11119, 11122, -1, 11101, 11121, 11106, -1, 11123, 11124, 11110, -1, 11110, 11124, 11109, -1, 11122, 11082, 11125, -1, 11103, 11124, 11108, -1, 11109, 11124, 11103, -1, 11113, 11126, 11127, -1, 11119, 11082, 11122, -1, 11112, 11126, 11113, -1, 11121, 11126, 11106, -1, 11073, 11074, 11118, -1, 11106, 11126, 11112, -1, 11128, 11129, 11123, -1, 11118, 11074, 11119, -1, 11108, 11129, 11121, -1, 11124, 11129, 11108, -1, 11125, 11079, 11076, -1, 11123, 11129, 11124, -1, 11128, 11130, 11129, -1, 11082, 11079, 11125, -1, 11127, 11130, 11117, -1, 11115, 11130, 11128, -1, 11126, 11130, 11127, -1, 11121, 11130, 11126, -1, 11129, 11130, 11121, -1, 11117, 11130, 11115, -1, 11119, 11080, 11082, -1, 11074, 11080, 11119, -1, 11131, 11132, 11133, -1, 11133, 11132, 11134, -1, 11135, 11132, 11136, -1, 11134, 11132, 11135, -1, 11137, 11138, 11139, -1, 11140, 11138, 11141, -1, 11141, 11138, 11137, -1, 11142, 11138, 11140, -1, 11143, 11144, 11142, -1, 11145, 11144, 11143, -1, 11146, 11147, 11131, -1, 11131, 11147, 11132, -1, 11136, 11147, 11145, -1, 11132, 11147, 11136, -1, 11139, 11148, 11149, -1, 11138, 11148, 11139, -1, 11142, 11148, 11138, -1, 11144, 11148, 11142, -1, 11150, 11151, 11146, -1, 11146, 11151, 11147, -1, 11145, 11151, 11144, -1, 11147, 11151, 11145, -1, 11149, 11152, 11153, -1, 11154, 11152, 11150, -1, 11150, 11152, 11151, -1, 11153, 11152, 11154, -1, 11148, 11152, 11149, -1, 11144, 11152, 11148, -1, 11151, 11152, 11144, -1, 11154, 11155, 11153, -1, 11156, 11157, 11158, -1, 11158, 11157, 11159, -1, 11159, 11160, 11161, -1, 11157, 11160, 11159, -1, 11162, 11163, 11156, -1, 11156, 11163, 11157, -1, 11161, 11164, 11165, -1, 11160, 11164, 11161, -1, 11163, 11135, 11157, -1, 11157, 11135, 11160, -1, 11166, 11167, 11168, -1, 11169, 11167, 11162, -1, 11168, 11167, 11169, -1, 11162, 11167, 11163, -1, 11165, 11143, 11170, -1, 11164, 11143, 11165, -1, 11160, 11136, 11164, -1, 11135, 11136, 11160, -1, 11133, 11134, 11166, -1, 11167, 11134, 11163, -1, 11166, 11134, 11167, -1, 11163, 11134, 11135, -1, 11170, 11142, 11140, -1, 11143, 11142, 11170, -1, 11164, 11145, 11143, -1, 11136, 11145, 11164, -1, 11171, 11172, 11173, -1, 11173, 11172, 11174, -1, 11174, 11172, 11175, -1, 11175, 11172, 11176, -1, 11177, 11178, 11179, -1, 11180, 11178, 11181, -1, 11181, 11178, 11177, -1, 11182, 11178, 11180, -1, 11183, 11184, 11182, -1, 11185, 11184, 11183, -1, 11186, 11187, 11171, -1, 11171, 11187, 11172, -1, 11176, 11187, 11185, -1, 11172, 11187, 11176, -1, 11179, 11188, 11189, -1, 11178, 11188, 11179, -1, 11182, 11188, 11178, -1, 11184, 11188, 11182, -1, 11190, 11191, 11186, -1, 11186, 11191, 11187, -1, 11185, 11191, 11184, -1, 11187, 11191, 11185, -1, 11189, 11192, 11193, -1, 11194, 11192, 11190, -1, 11188, 11192, 11189, -1, 11190, 11192, 11191, -1, 11193, 11192, 11194, -1, 11184, 11192, 11188, -1, 11191, 11192, 11184, -1, 11194, 11195, 11193, -1, 11196, 11197, 11198, -1, 11198, 11197, 11199, -1, 11199, 11200, 11201, -1, 11197, 11200, 11199, -1, 11202, 11203, 11196, -1, 11196, 11203, 11197, -1, 11201, 11204, 11205, -1, 11200, 11204, 11201, -1, 11203, 11175, 11197, -1, 11197, 11175, 11200, -1, 11206, 11207, 11208, -1, 11209, 11207, 11202, -1, 11208, 11207, 11209, -1, 11202, 11207, 11203, -1, 11205, 11183, 11210, -1, 11204, 11183, 11205, -1, 11175, 11176, 11200, -1, 11200, 11176, 11204, -1, 11173, 11174, 11206, -1, 11207, 11174, 11203, -1, 11203, 11174, 11175, -1, 11206, 11174, 11207, -1, 11210, 11182, 11180, -1, 11183, 11182, 11210, -1, 11204, 11185, 11183, -1, 11176, 11185, 11204, -1, 11211, 11212, 11213, -1, 11214, 11212, 11215, -1, 11216, 11217, 11218, -1, 11219, 11217, 11216, -1, 11220, 11221, 11222, -1, 11222, 11221, 11219, -1, 11223, 11224, 11214, -1, 11213, 11224, 11220, -1, 11214, 11224, 11212, -1, 11212, 11224, 11213, -1, 11218, 11225, 11226, -1, 11217, 11225, 11218, -1, 11221, 11227, 11219, -1, 11219, 11227, 11217, -1, 11228, 11229, 11223, -1, 11220, 11229, 11221, -1, 11223, 11229, 11224, -1, 11230, 11214, 11215, -1, 11224, 11229, 11220, -1, 11226, 11231, 11232, -1, 11225, 11231, 11226, -1, 11217, 11233, 11225, -1, 11227, 11233, 11217, -1, 11234, 11235, 11228, -1, 11228, 11235, 11229, -1, 11221, 11235, 11227, -1, 11229, 11235, 11221, -1, 11232, 11236, 11237, -1, 11231, 11236, 11232, -1, 11225, 11238, 11231, -1, 11233, 11238, 11225, -1, 11235, 11239, 11227, -1, 11240, 11239, 11234, -1, 11234, 11239, 11235, -1, 11227, 11239, 11233, -1, 11237, 11241, 11242, -1, 11236, 11241, 11237, -1, 11238, 11243, 11231, -1, 11231, 11243, 11236, -1, 11239, 11244, 11233, -1, 11233, 11244, 11238, -1, 11240, 11244, 11239, -1, 11245, 11244, 11240, -1, 11246, 11247, 11248, -1, 11242, 11249, 11250, -1, 11241, 11249, 11242, -1, 11236, 11251, 11241, -1, 11243, 11251, 11236, -1, 11244, 11252, 11238, -1, 11253, 11252, 11245, -1, 11238, 11252, 11243, -1, 11245, 11252, 11244, -1, 11247, 11254, 11255, -1, 11249, 11254, 11250, -1, 11250, 11254, 11246, -1, 11246, 11254, 11247, -1, 11256, 11257, 11258, -1, 11258, 11257, 11259, -1, 11251, 11260, 11241, -1, 11241, 11260, 11249, -1, 11261, 11262, 11253, -1, 11259, 11222, 11263, -1, 11253, 11262, 11252, -1, 11243, 11262, 11251, -1, 11252, 11262, 11243, -1, 11257, 11222, 11259, -1, 11255, 11264, 11265, -1, 11254, 11264, 11255, -1, 11260, 11264, 11249, -1, 11211, 11213, 11256, -1, 11249, 11264, 11254, -1, 11261, 11266, 11262, -1, 11256, 11213, 11257, -1, 11267, 11266, 11261, -1, 11251, 11266, 11260, -1, 11263, 11219, 11216, -1, 11262, 11266, 11251, -1, 11265, 11268, 11269, -1, 11222, 11219, 11263, -1, 11269, 11268, 11270, -1, 11270, 11268, 11267, -1, 11264, 11268, 11265, -1, 11267, 11268, 11266, -1, 11260, 11268, 11264, -1, 11266, 11268, 11260, -1, 11257, 11220, 11222, -1, 11213, 11220, 11257, -1, 11215, 11212, 11211, -1, 11271, 11272, 11273, -1, 11274, 11275, 11276, -1, 11277, 11278, 11279, -1, 11279, 11278, 11280, -1, 11281, 11282, 11277, -1, 11277, 11282, 11278, -1, 11283, 11284, 11285, -1, 11285, 11284, 11286, -1, 11280, 11284, 11287, -1, 11287, 11284, 11283, -1, 11278, 11284, 11280, -1, 11273, 11288, 11281, -1, 11281, 11288, 11282, -1, 11272, 11288, 11273, -1, 11286, 11289, 11276, -1, 11282, 11289, 11278, -1, 11278, 11289, 11284, -1, 11284, 11289, 11286, -1, 11274, 11290, 11272, -1, 11289, 11290, 11276, -1, 11272, 11290, 11288, -1, 11288, 11290, 11282, -1, 11282, 11290, 11289, -1, 11276, 11290, 11274, -1, 11291, 11292, 11293, -1, 11294, 11295, 11296, -1, 11294, 11297, 11295, -1, 11298, 11297, 11294, -1, 11298, 11299, 11300, -1, 11298, 11301, 11297, -1, 11298, 11300, 11301, -1, 11302, 11294, 11296, -1, 11302, 11296, 11303, -1, 11304, 11305, 11299, -1, 11304, 11294, 11302, -1, 11304, 11299, 11298, -1, 11304, 11298, 11294, -1, 11306, 11303, 11307, -1, 11306, 11302, 11303, -1, 11308, 11302, 11306, -1, 11308, 11304, 11302, -1, 11308, 11305, 11304, -1, 11308, 11309, 11305, -1, 11310, 11307, 11311, -1, 11310, 11306, 11307, -1, 11312, 11309, 11308, -1, 11312, 11306, 11310, -1, 11312, 11308, 11306, -1, 11312, 11313, 11309, -1, 11314, 11310, 11311, -1, 11314, 11311, 11315, -1, 11316, 11317, 11313, -1, 11316, 11312, 11310, -1, 11316, 11313, 11312, -1, 11316, 11310, 11314, -1, 11318, 11315, 11319, -1, 11318, 11314, 11315, -1, 11320, 11317, 11316, -1, 11320, 11316, 11314, -1, 11320, 11314, 11318, -1, 11320, 11321, 11317, -1, 11322, 11319, 11323, -1, 11322, 11318, 11319, -1, 11324, 11318, 11322, -1, 11324, 11325, 11321, -1, 11324, 11320, 11318, -1, 11324, 11321, 11320, -1, 11326, 11323, 11327, -1, 11326, 11322, 11323, -1, 11328, 11324, 11322, -1, 11328, 11325, 11324, -1, 11328, 11322, 11326, -1, 11328, 11329, 11325, -1, 11330, 11326, 11327, -1, 11330, 11327, 11331, -1, 11332, 11329, 11328, -1, 11332, 11326, 11330, -1, 11332, 11328, 11326, -1, 11332, 11333, 11329, -1, 11334, 11330, 11331, -1, 11334, 11331, 11335, -1, 11336, 11333, 11332, -1, 11336, 11337, 11333, -1, 11336, 11332, 11330, -1, 11336, 11330, 11334, -1, 11338, 11334, 11335, -1, 11338, 11335, 11339, -1, 11340, 11336, 11334, -1, 11340, 11341, 11337, -1, 11340, 11334, 11338, -1, 11340, 11337, 11336, -1, 11342, 11339, 11343, -1, 11342, 11338, 11339, -1, 11344, 11338, 11342, -1, 11344, 11341, 11340, -1, 11344, 11345, 11341, -1, 11344, 11340, 11338, -1, 11346, 11343, 11347, -1, 11346, 11342, 11343, -1, 11348, 11345, 11344, -1, 11348, 11344, 11342, -1, 11348, 11349, 11345, -1, 11348, 11342, 11346, -1, 11350, 11347, 11351, -1, 11350, 11346, 11347, -1, 11352, 11346, 11350, -1, 11352, 11348, 11346, -1, 11352, 11349, 11348, -1, 11352, 11353, 11349, -1, 11354, 11351, 11355, -1, 11354, 11350, 11351, -1, 11356, 11353, 11352, -1, 11356, 11350, 11354, -1, 11356, 11357, 11353, -1, 11356, 11352, 11350, -1, 11358, 11354, 11355, -1, 11358, 11355, 11359, -1, 11360, 11357, 11356, -1, 11360, 11354, 11358, -1, 11360, 11356, 11354, -1, 11360, 11361, 11357, -1, 11362, 11359, 11363, -1, 11362, 11358, 11359, -1, 11364, 11360, 11358, -1, 11364, 11361, 11360, -1, 11364, 11358, 11362, -1, 11364, 11365, 11361, -1, 11366, 11363, 11367, -1, 11366, 11362, 11363, -1, 11368, 11364, 11362, -1, 11368, 11365, 11364, -1, 11368, 11369, 11365, -1, 11368, 11362, 11366, -1, 11370, 11367, 11371, -1, 11370, 11366, 11367, -1, 11372, 11368, 11366, -1, 11372, 11373, 11369, -1, 11372, 11369, 11368, -1, 11372, 11366, 11370, -1, 11374, 11371, 11375, -1, 11374, 11370, 11371, -1, 11376, 11377, 11373, -1, 11376, 11372, 11370, -1, 11376, 11373, 11372, -1, 11376, 11370, 11374, -1, 11378, 11375, 11379, -1, 11378, 11374, 11375, -1, 11380, 11381, 11377, -1, 11380, 11377, 11376, -1, 11380, 11376, 11374, -1, 11380, 11374, 11378, -1, 11382, 11379, 11383, -1, 11382, 11378, 11379, -1, 11384, 11385, 11381, -1, 11384, 11381, 11380, -1, 11384, 11380, 11378, -1, 11384, 11378, 11382, -1, 11386, 11383, 11387, -1, 11386, 11382, 11383, -1, 11388, 11389, 11385, -1, 11388, 11385, 11384, -1, 11388, 11384, 11382, -1, 11388, 11382, 11386, -1, 11390, 11387, 11391, -1, 11390, 11386, 11387, -1, 11392, 11393, 11389, -1, 11392, 11389, 11388, -1, 11392, 11388, 11386, -1, 11392, 11386, 11390, -1, 11394, 11391, 11395, -1, 11394, 11390, 11391, -1, 11396, 11390, 11394, -1, 11396, 11397, 11393, -1, 11396, 11393, 11392, -1, 11396, 11392, 11390, -1, 11398, 11395, 11399, -1, 11398, 11394, 11395, -1, 11400, 11394, 11398, -1, 11400, 11401, 11397, -1, 11400, 11397, 11396, -1, 11400, 11396, 11394, -1, 11402, 11399, 11403, -1, 11402, 11398, 11399, -1, 11404, 11401, 11400, -1, 11404, 11398, 11402, -1, 11404, 11405, 11401, -1, 11404, 11400, 11398, -1, 11406, 11403, 11407, -1, 11406, 11402, 11403, -1, 11408, 11404, 11402, -1, 11408, 11405, 11404, -1, 11408, 11402, 11406, -1, 11408, 11409, 11405, -1, 11410, 11406, 11407, -1, 11410, 11407, 11411, -1, 11412, 11406, 11410, -1, 11412, 11408, 11406, -1, 11412, 11409, 11408, -1, 11412, 11413, 11409, -1, 11414, 11411, 11415, -1, 11414, 11410, 11411, -1, 11416, 11410, 11414, -1, 11416, 11412, 11410, -1, 11416, 11413, 11412, -1, 11416, 11417, 11413, -1, 11418, 11415, 11419, -1, 11418, 11414, 11415, -1, 11420, 11416, 11414, -1, 11420, 11417, 11416, -1, 11420, 11414, 11418, -1, 11420, 11421, 11417, -1, 11422, 11419, 11423, -1, 11422, 11418, 11419, -1, 11424, 11420, 11418, -1, 11424, 11421, 11420, -1, 11424, 11418, 11422, -1, 11424, 11425, 11421, -1, 11426, 11423, 11427, -1, 11426, 11422, 11423, -1, 11428, 11424, 11422, -1, 11428, 11425, 11424, -1, 11428, 11422, 11426, -1, 11428, 11429, 11425, -1, 11430, 11427, 11431, -1, 11430, 11426, 11427, -1, 11432, 11428, 11426, -1, 11432, 11429, 11428, -1, 11432, 11426, 11430, -1, 11432, 11433, 11429, -1, 11434, 11431, 11435, -1, 11434, 11430, 11431, -1, 11436, 11432, 11430, -1, 11436, 11433, 11432, -1, 11436, 11430, 11434, -1, 11436, 11437, 11433, -1, 11438, 11439, 11440, -1, 11438, 11435, 11439, -1, 11438, 11440, 11441, -1, 11438, 11434, 11435, -1, 11442, 11436, 11434, -1, 11442, 11434, 11438, -1, 11442, 11293, 11292, -1, 11442, 11441, 11293, -1, 11442, 11437, 11436, -1, 11442, 11438, 11441, -1, 11442, 11292, 11437, -1, 11443, 11444, 11445, -1, 11445, 11444, 11446, -1, 11447, 11448, 11449, -1, 11446, 11448, 11447, -1, 11444, 11448, 11446, -1, 11448, 11450, 11449, -1, 11449, 11451, 11452, -1, 11450, 11451, 11449, -1, 11452, 11453, 11454, -1, 11451, 11453, 11452, -1, 11454, 11455, 11456, -1, 11453, 11455, 11454, -1, 11456, 11457, 11458, -1, 11455, 11457, 11456, -1, 11459, 11460, 11461, -1, 11462, 11461, 11463, -1, 11462, 11459, 11461, -1, 11464, 11462, 11463, -1, 11465, 11463, 11466, -1, 11465, 11464, 11463, -1, 11467, 11468, 11469, -1, 11467, 11469, 11470, -1, 11467, 11470, 11471, -1, 11467, 11472, 11473, -1, 11467, 11473, 11468, -1, 11467, 11471, 11472, -1, 11474, 11475, 11476, -1, 11474, 11476, 11477, -1, 11474, 11477, 11478, -1, 11474, 11479, 11475, -1, 11480, 11478, 11481, -1, 11480, 11481, 11482, -1, 11480, 11479, 11474, -1, 11480, 11482, 11479, -1, 11480, 11474, 11478, -1, 11473, 11483, 11484, -1, 11473, 11485, 11468, -1, 11486, 11484, 11487, -1, 11486, 11487, 11488, -1, 11486, 11489, 11490, -1, 11486, 11490, 11485, -1, 11486, 11473, 11484, -1, 11486, 11485, 11473, -1, 11491, 11488, 11492, -1, 11491, 11493, 11489, -1, 11491, 11489, 11486, -1, 11491, 11486, 11488, -1, 11494, 11492, 11495, -1, 11494, 11495, 11496, -1, 11494, 11497, 11498, -1, 11494, 11498, 11493, -1, 11494, 11491, 11492, -1, 11494, 11493, 11491, -1, 11479, 11496, 11475, -1, 11479, 11482, 11497, -1, 11479, 11497, 11494, -1, 11479, 11494, 11496, -1, 11472, 11471, 11499, -1, 11472, 11499, 11483, -1, 11472, 11483, 11473, -1, 11500, 11501, 11502, -1, 11500, 11503, 11504, -1, 11505, 11502, 11506, -1, 11505, 11507, 11503, -1, 11505, 11500, 11502, -1, 11505, 11503, 11500, -1, 11508, 11506, 11509, -1, 11508, 11510, 11507, -1, 11508, 11507, 11505, -1, 11508, 11505, 11506, -1, 11511, 11512, 11513, -1, 11511, 11513, 11501, -1, 11511, 11501, 11500, -1, 11514, 11504, 11515, -1, 11514, 11515, 11516, -1, 11514, 11516, 11512, -1, 11514, 11512, 11511, -1, 11514, 11511, 11500, -1, 11514, 11500, 11504, -1, 11517, 11509, 11518, -1, 11517, 11518, 11519, -1, 11517, 11519, 11520, -1, 11517, 11508, 11509, -1, 11521, 11520, 11522, -1, 11521, 11522, 11510, -1, 11521, 11517, 11520, -1, 11521, 11510, 11508, -1, 11521, 11508, 11517, -1, 11523, 11524, 11525, -1, 11526, 11525, 11527, -1, 11526, 11523, 11525, -1, 11528, 11529, 11530, -1, 11531, 11527, 11529, -1, 11531, 11526, 11527, -1, 11532, 11529, 11528, -1, 11532, 11531, 11529, -1, 11533, 11528, 11534, -1, 11533, 11532, 11528, -1, 11535, 11534, 11536, -1, 11535, 11533, 11534, -1, 11537, 11536, 11538, -1, 11537, 11538, 11539, -1, 11537, 11535, 11536, -1, 11540, 11539, 11541, -1, 11540, 11537, 11539, -1, 11542, 11541, 11543, -1, 11542, 11540, 11541, -1, 11544, 11543, 11545, -1, 11544, 11542, 11543, -1, 11546, 11545, 11547, -1, 11546, 11547, 11548, -1, 11549, 11544, 11545, -1, 11549, 11545, 11546, -1, 11550, 11546, 11551, -1, 11550, 11549, 11546, -1, 11552, 11551, 11553, -1, 11552, 11550, 11551, -1, 11554, 11553, 11555, -1, 11554, 11552, 11553, -1, 11556, 11557, 11558, -1, 11559, 11558, 11560, -1, 11559, 11556, 11558, -1, 11561, 11560, 11562, -1, 11561, 11559, 11560, -1, 11563, 11559, 11561, -1, 11564, 11561, 11565, -1, 11564, 11563, 11561, -1, 11566, 11565, 11567, -1, 11566, 11564, 11565, -1, 11568, 11567, 11569, -1, 11568, 11566, 11567, -1, 11570, 11569, 11571, -1, 11570, 11568, 11569, -1, 11572, 11571, 11573, -1, 11572, 11570, 11571, -1, 11574, 11573, 11575, -1, 11574, 11572, 11573, -1, 11576, 11575, 11577, -1, 11576, 11574, 11575, -1, 11578, 11577, 11579, -1, 11578, 11576, 11577, -1, 11580, 11579, 11581, -1, 11580, 11578, 11579, -1, 11582, 11581, 11583, -1, 11582, 11580, 11581, -1, 11584, 11583, 11585, -1, 11584, 11582, 11583, -1, 11586, 11587, 11588, -1, 11589, 11586, 11590, -1, 11589, 11587, 11586, -1, 11591, 11590, 11592, -1, 11591, 11589, 11590, -1, 11593, 11592, 11594, -1, 11593, 11591, 11592, -1, 11595, 11594, 11596, -1, 11595, 11593, 11594, -1, 11597, 11596, 11598, -1, 11597, 11595, 11596, -1, 11599, 11598, 11600, -1, 11599, 11597, 11598, -1, 11601, 11600, 11602, -1, 11601, 11599, 11600, -1, 11603, 11602, 11604, -1, 11603, 11601, 11602, -1, 11605, 11604, 11606, -1, 11605, 11603, 11604, -1, 11607, 11608, 11609, -1, 11610, 11606, 11607, -1, 11610, 11605, 11606, -1, 11611, 11610, 11607, -1, 11612, 11609, 11613, -1, 11612, 11607, 11609, -1, 11612, 11611, 11607, -1, 11614, 11613, 11615, -1, 11614, 11612, 11613, -1, 11616, 11617, 11618, -1, 11618, 11617, 11619, -1, 11620, 11621, 11622, -1, 11616, 11621, 11617, -1, 11623, 11621, 11620, -1, 11622, 11621, 11616, -1, 11619, 11624, 11625, -1, 11617, 11624, 11619, -1, 11626, 11627, 11623, -1, 11621, 11627, 11617, -1, 11623, 11627, 11621, -1, 11617, 11627, 11624, -1, 11628, 11629, 11630, -1, 11624, 11631, 11625, -1, 11625, 11631, 11632, -1, 11633, 11634, 11635, -1, 11636, 11637, 11626, -1, 11624, 11637, 11631, -1, 11635, 11634, 11638, -1, 11627, 11637, 11624, -1, 11626, 11637, 11627, -1, 11639, 11640, 11629, -1, 11630, 11640, 11633, -1, 11629, 11640, 11630, -1, 11633, 11640, 11634, -1, 11632, 11641, 11642, -1, 11631, 11641, 11632, -1, 11643, 11644, 11636, -1, 11638, 11645, 11646, -1, 11636, 11644, 11637, -1, 11634, 11645, 11638, -1, 11637, 11644, 11631, -1, 11631, 11644, 11641, -1, 11640, 11647, 11634, -1, 11648, 11647, 11639, -1, 11641, 11649, 11642, -1, 11634, 11647, 11645, -1, 11642, 11649, 11650, -1, 11639, 11647, 11640, -1, 11645, 11651, 11646, -1, 11652, 11653, 11643, -1, 11641, 11653, 11649, -1, 11646, 11651, 11654, -1, 11644, 11653, 11641, -1, 11643, 11653, 11644, -1, 11655, 11656, 11648, -1, 11645, 11656, 11651, -1, 11648, 11656, 11647, -1, 11647, 11656, 11645, -1, 11650, 11657, 11658, -1, 11649, 11657, 11650, -1, 11652, 11659, 11653, -1, 11653, 11659, 11649, -1, 11651, 11660, 11654, -1, 11661, 11659, 11652, -1, 11654, 11660, 11662, -1, 11649, 11659, 11657, -1, 11656, 11663, 11651, -1, 11657, 11664, 11658, -1, 11665, 11663, 11655, -1, 11655, 11663, 11656, -1, 11651, 11663, 11660, -1, 11658, 11664, 11666, -1, 11659, 11667, 11657, -1, 11657, 11667, 11664, -1, 11662, 11668, 11669, -1, 11661, 11667, 11659, -1, 11660, 11668, 11662, -1, 11670, 11667, 11661, -1, 11665, 11671, 11663, -1, 11672, 11673, 11674, -1, 11675, 11671, 11665, -1, 11663, 11671, 11660, -1, 11664, 11673, 11666, -1, 11660, 11671, 11668, -1, 11676, 11673, 11672, -1, 11666, 11673, 11676, -1, 11669, 11677, 11678, -1, 11674, 11679, 11680, -1, 11680, 11679, 11681, -1, 11668, 11677, 11669, -1, 11673, 11679, 11674, -1, 11670, 11679, 11667, -1, 11681, 11679, 11670, -1, 11682, 11683, 11675, -1, 11667, 11679, 11664, -1, 11664, 11679, 11673, -1, 11668, 11683, 11677, -1, 11675, 11683, 11671, -1, 11671, 11683, 11668, -1, 11677, 11684, 11678, -1, 11678, 11684, 11685, -1, 11686, 11687, 11682, -1, 11683, 11687, 11677, -1, 11682, 11687, 11683, -1, 11677, 11687, 11684, -1, 11685, 11688, 11689, -1, 11684, 11688, 11685, -1, 11690, 11691, 11686, -1, 11687, 11691, 11684, -1, 11686, 11691, 11687, -1, 11684, 11691, 11688, -1, 11689, 11692, 11693, -1, 11688, 11692, 11689, -1, 11694, 11695, 11690, -1, 11690, 11695, 11691, -1, 11688, 11695, 11692, -1, 11691, 11695, 11688, -1, 11693, 11696, 11697, -1, 11692, 11696, 11693, -1, 11698, 11699, 11694, -1, 11692, 11699, 11696, -1, 11694, 11699, 11695, -1, 11695, 11699, 11692, -1, 11697, 11700, 11701, -1, 11696, 11700, 11697, -1, 11702, 11703, 11698, -1, 11698, 11703, 11699, -1, 11699, 11703, 11696, -1, 11696, 11703, 11700, -1, 11700, 11704, 11701, -1, 11701, 11704, 11705, -1, 11702, 11706, 11703, -1, 11700, 11706, 11704, -1, 11707, 11706, 11702, -1, 11703, 11706, 11700, -1, 11705, 11616, 11618, -1, 11704, 11616, 11705, -1, 11620, 11622, 11707, -1, 11706, 11622, 11704, -1, 11707, 11622, 11706, -1, 11704, 11622, 11616, -1, 11708, 11709, 11710, -1, 11711, 11710, 11712, -1, 11711, 11708, 11710, -1, 11713, 11712, 11714, -1, 11713, 11711, 11712, -1, 11715, 11713, 11714, -1, 11716, 11717, 11718, -1, 11718, 11717, 11719, -1, 11719, 11720, 11721, -1, 11717, 11720, 11719, -1, 11721, 11722, 11723, -1, 11720, 11722, 11721, -1, 11723, 11724, 11725, -1, 11722, 11724, 11723, -1, 11725, 11726, 11727, -1, 11724, 11726, 11725, -1, 11727, 11728, 11729, -1, 11726, 11728, 11727, -1, 11729, 11730, 11731, -1, 11728, 11730, 11729, -1, 11732, 11733, 11689, -1, 11734, 11735, 11736, -1, 11737, 11738, 11739, -1, 11740, 11741, 11734, -1, 11739, 11738, 11733, -1, 11734, 11741, 11735, -1, 11733, 11738, 11689, -1, 11689, 11738, 11737, -1, 11742, 11743, 11625, -1, 11619, 11743, 11744, -1, 11744, 11743, 11742, -1, 11735, 11745, 11705, -1, 11625, 11743, 11619, -1, 11735, 11746, 11745, -1, 11741, 11746, 11735, -1, 11747, 11746, 11740, -1, 11740, 11746, 11741, -1, 11745, 11748, 11705, -1, 11749, 11750, 11672, -1, 11751, 11750, 11749, -1, 11705, 11748, 11701, -1, 11752, 11750, 11751, -1, 11747, 11753, 11746, -1, 11750, 11676, 11672, -1, 11745, 11753, 11748, -1, 11746, 11753, 11745, -1, 11748, 11754, 11701, -1, 11750, 11755, 11676, -1, 11755, 11756, 11676, -1, 11757, 11758, 11747, -1, 11747, 11758, 11753, -1, 11756, 11666, 11676, -1, 11753, 11759, 11748, -1, 11756, 11760, 11666, -1, 11760, 11658, 11666, -1, 11748, 11759, 11754, -1, 11760, 11761, 11658, -1, 11754, 11762, 11701, -1, 11761, 11650, 11658, -1, 11758, 11763, 11753, -1, 11757, 11763, 11758, -1, 11761, 11764, 11650, -1, 11753, 11763, 11759, -1, 11759, 11765, 11754, -1, 11766, 11642, 11764, -1, 11754, 11765, 11762, -1, 11764, 11642, 11650, -1, 11766, 11767, 11642, -1, 11768, 11769, 11757, -1, 11757, 11769, 11763, -1, 11767, 11632, 11642, -1, 11762, 11770, 11701, -1, 11767, 11771, 11632, -1, 11759, 11772, 11765, -1, 11771, 11625, 11632, -1, 11771, 11742, 11625, -1, 11763, 11772, 11759, -1, 11737, 11685, 11689, -1, 11762, 11773, 11770, -1, 11737, 11774, 11685, -1, 11765, 11773, 11762, -1, 11768, 11775, 11769, -1, 11776, 11775, 11777, -1, 11774, 11778, 11685, -1, 11777, 11775, 11779, -1, 11779, 11775, 11780, -1, 11780, 11775, 11781, -1, 11778, 11678, 11685, -1, 11781, 11775, 11782, -1, 11778, 11783, 11678, -1, 11782, 11775, 11784, -1, 11784, 11775, 11785, -1, 11785, 11775, 11786, -1, 11786, 11775, 11787, -1, 11787, 11775, 11788, -1, 11789, 11775, 11768, -1, 11788, 11775, 11789, -1, 11783, 11669, 11678, -1, 11763, 11775, 11772, -1, 11769, 11775, 11763, -1, 11783, 11790, 11669, -1, 11770, 11791, 11701, -1, 11701, 11791, 11697, -1, 11790, 11662, 11669, -1, 11772, 11792, 11765, -1, 11765, 11792, 11773, -1, 11793, 11654, 11662, -1, 11793, 11794, 11654, -1, 11773, 11795, 11770, -1, 11770, 11795, 11791, -1, 11794, 11646, 11654, -1, 11792, 11796, 11797, -1, 11797, 11796, 11776, -1, 11775, 11796, 11772, -1, 11776, 11796, 11775, -1, 11794, 11798, 11646, -1, 11772, 11796, 11792, -1, 11798, 11638, 11646, -1, 11791, 11799, 11697, -1, 11792, 11800, 11773, -1, 11797, 11800, 11792, -1, 11798, 11801, 11638, -1, 11802, 11800, 11797, -1, 11795, 11800, 11802, -1, 11773, 11800, 11795, -1, 11791, 11803, 11799, -1, 11801, 11635, 11638, -1, 11804, 11803, 11802, -1, 11802, 11803, 11795, -1, 11795, 11803, 11791, -1, 11801, 11805, 11635, -1, 11799, 11806, 11697, -1, 11801, 11807, 11805, -1, 11801, 11808, 11807, -1, 11804, 11809, 11803, -1, 11799, 11809, 11806, -1, 11790, 11793, 11662, -1, 11803, 11809, 11799, -1, 11744, 11810, 11619, -1, 11806, 11811, 11697, -1, 11812, 11810, 11744, -1, 11697, 11811, 11693, -1, 11812, 11813, 11810, -1, 11810, 11813, 11619, -1, 11814, 11815, 11804, -1, 11809, 11815, 11806, -1, 11816, 11813, 11812, -1, 11806, 11815, 11811, -1, 11619, 11813, 11618, -1, 11811, 11815, 11814, -1, 11804, 11815, 11809, -1, 11817, 11818, 11814, -1, 11816, 11819, 11813, -1, 11811, 11818, 11693, -1, 11813, 11819, 11618, -1, 11814, 11818, 11811, -1, 11820, 11788, 11789, -1, 11821, 11822, 11816, -1, 11818, 11823, 11693, -1, 11819, 11822, 11618, -1, 11817, 11823, 11818, -1, 11816, 11822, 11819, -1, 11734, 11736, 11821, -1, 11739, 11732, 11817, -1, 11823, 11732, 11693, -1, 11822, 11736, 11618, -1, 11693, 11732, 11689, -1, 11618, 11736, 11705, -1, 11817, 11732, 11823, -1, 11821, 11736, 11822, -1, 11739, 11733, 11732, -1, 11736, 11735, 11705, -1, 11824, 11515, 11504, -1, 11824, 11516, 11515, -1, 11824, 11825, 11516, -1, 11826, 11504, 11503, -1, 11826, 11824, 11504, -1, 11827, 11503, 11507, -1, 11827, 11826, 11503, -1, 11828, 11507, 11510, -1, 11828, 11827, 11507, -1, 11829, 11510, 11522, -1, 11829, 11828, 11510, -1, 11830, 11522, 11520, -1, 11830, 11829, 11522, -1, 11831, 11830, 11520, -1, 11832, 11459, 11462, -1, 11832, 11833, 11459, -1, 11834, 11462, 11464, -1, 11834, 11832, 11462, -1, 11835, 11464, 11465, -1, 11835, 11834, 11464, -1, 11836, 11470, 11469, -1, 11836, 11837, 11470, -1, 11838, 11469, 11468, -1, 11838, 11836, 11469, -1, 11839, 11468, 11485, -1, 11839, 11838, 11468, -1, 11840, 11485, 11490, -1, 11840, 11839, 11485, -1, 11841, 11490, 11489, -1, 11841, 11840, 11490, -1, 11842, 11489, 11493, -1, 11842, 11841, 11489, -1, 11843, 11493, 11498, -1, 11843, 11842, 11493, -1, 11844, 11843, 11498, -1, 11845, 11498, 11497, -1, 11845, 11844, 11498, -1, 11846, 11497, 11482, -1, 11846, 11845, 11497, -1, 11847, 11482, 11481, -1, 11847, 11846, 11482, -1, 11848, 11481, 11478, -1, 11848, 11847, 11481, -1, 11849, 11848, 11478, -1, 11850, 11851, 11852, -1, 11853, 11854, 11855, -1, 11851, 11854, 11853, -1, 11856, 11857, 11858, -1, 11858, 11859, 11860, -1, 11855, 11861, 11862, -1, 11857, 11859, 11858, -1, 11854, 11861, 11855, -1, 11863, 11864, 11865, -1, 11865, 11864, 11866, -1, 11862, 11867, 11868, -1, 11861, 11867, 11862, -1, 11864, 11869, 11866, -1, 11868, 11870, 11871, -1, 11867, 11870, 11868, -1, 11866, 11869, 11872, -1, 11870, 11873, 11871, -1, 11874, 11875, 11876, -1, 11859, 11877, 11878, -1, 11878, 11877, 11879, -1, 11869, 11880, 11872, -1, 11879, 11877, 11874, -1, 11872, 11880, 11881, -1, 11857, 11877, 11859, -1, 11880, 11882, 11881, -1, 11881, 11882, 11883, -1, 11877, 11884, 11874, -1, 11874, 11884, 11875, -1, 11875, 11885, 11886, -1, 11882, 11887, 11883, -1, 11883, 11887, 11888, -1, 11884, 11885, 11875, -1, 11887, 11889, 11888, -1, 11886, 11890, 11891, -1, 11888, 11889, 11892, -1, 11885, 11890, 11886, -1, 11890, 11893, 11891, -1, 11891, 11893, 11894, -1, 11893, 11895, 11894, -1, 11889, 11896, 11897, -1, 11897, 11896, 11898, -1, 11894, 11895, 11899, -1, 11898, 11896, 11900, -1, 11887, 11896, 11889, -1, 11900, 11901, 11902, -1, 11895, 11903, 11899, -1, 11899, 11903, 11904, -1, 11900, 11905, 11901, -1, 11896, 11905, 11900, -1, 11903, 11906, 11904, -1, 11904, 11906, 11907, -1, 11901, 11908, 11909, -1, 11905, 11908, 11901, -1, 11906, 11910, 11907, -1, 11907, 11910, 11911, -1, 11909, 11912, 11913, -1, 11908, 11912, 11909, -1, 11910, 11914, 11911, -1, 11913, 11915, 11916, -1, 11911, 11914, 11917, -1, 11912, 11915, 11913, -1, 11914, 11918, 11917, -1, 11916, 11919, 11920, -1, 11915, 11919, 11916, -1, 11917, 11918, 11921, -1, 11921, 11922, 11923, -1, 11918, 11922, 11921, -1, 11920, 11924, 11925, -1, 11919, 11924, 11920, -1, 11925, 11926, 11927, -1, 11923, 11928, 11929, -1, 11924, 11926, 11925, -1, 11922, 11930, 11923, -1, 11923, 11930, 11928, -1, 11927, 11931, 11932, -1, 11926, 11931, 11927, -1, 11932, 11933, 11934, -1, 11931, 11933, 11932, -1, 11850, 11852, 11935, -1, 11934, 11936, 11937, -1, 11928, 11938, 11939, -1, 11933, 11936, 11934, -1, 11939, 11938, 11940, -1, 11940, 11938, 11850, -1, 11930, 11938, 11928, -1, 11937, 11856, 11858, -1, 11936, 11856, 11937, -1, 11852, 11851, 11853, -1, 11938, 11851, 11850, -1, 11941, 11942, 11943, -1, 11944, 11942, 11945, -1, 11941, 11946, 11942, -1, 11942, 11946, 11945, -1, 11947, 11946, 11941, -1, 11948, 11946, 11947, -1, 11945, 11946, 11949, -1, 11950, 11951, 11952, -1, 11953, 11951, 11950, -1, 11954, 11955, 11948, -1, 11948, 11955, 11946, -1, 11946, 11955, 11949, -1, 11949, 11955, 11956, -1, 11956, 11955, 11957, -1, 11958, 11959, 11960, -1, 11960, 11959, 11961, -1, 11961, 11959, 11954, -1, 11955, 11959, 11957, -1, 11954, 11959, 11955, -1, 11957, 11959, 11958, -1, 11951, 11962, 11952, -1, 11963, 11964, 11965, -1, 11965, 11964, 11966, -1, 11967, 11964, 11963, -1, 11968, 11964, 11967, -1, 11966, 11969, 11970, -1, 11970, 11969, 11971, -1, 11964, 11969, 11966, -1, 11968, 11969, 11964, -1, 11972, 11969, 11968, -1, 11972, 11973, 11969, -1, 11971, 11973, 11974, -1, 11975, 11973, 11972, -1, 11976, 11973, 11975, -1, 11969, 11973, 11971, -1, 11974, 11977, 11978, -1, 11973, 11977, 11974, -1, 11976, 11977, 11973, -1, 11979, 11977, 11976, -1, 11978, 11980, 11981, -1, 11981, 11980, 11982, -1, 11977, 11980, 11978, -1, 11979, 11980, 11977, -1, 11983, 11980, 11979, -1, 11982, 11984, 11985, -1, 11986, 11984, 11983, -1, 11987, 11984, 11986, -1, 11980, 11984, 11982, -1, 11983, 11984, 11980, -1, 11984, 11988, 11985, -1, 11987, 11988, 11984, -1, 11985, 11988, 11989, -1, 11990, 11988, 11987, -1, 11961, 11963, 11960, -1, 11989, 11991, 11992, -1, 11992, 11991, 11993, -1, 11988, 11991, 11989, -1, 11990, 11991, 11988, -1, 11961, 11967, 11963, -1, 11994, 11991, 11990, -1, 11953, 11991, 11994, -1, 11993, 11995, 11996, -1, 11996, 11995, 11997, -1, 11997, 11995, 11950, -1, 11991, 11995, 11993, -1, 11950, 11995, 11953, -1, 11953, 11995, 11991, -1, 11952, 11998, 11999, -1, 11999, 11998, 12000, -1, 12000, 11998, 12001, -1, 11962, 11998, 11952, -1, 12001, 12002, 12003, -1, 12003, 12002, 12004, -1, 11998, 12002, 12001, -1, 11962, 12002, 11998, -1, 12005, 12002, 11962, -1, 12006, 12002, 12005, -1, 12004, 12007, 12008, -1, 12009, 12007, 12006, -1, 12002, 12007, 12004, -1, 12006, 12007, 12002, -1, 12008, 12010, 12011, -1, 12012, 12010, 12009, -1, 12013, 12010, 12012, -1, 12009, 12010, 12007, -1, 12007, 12010, 12008, -1, 12013, 12014, 12010, -1, 12010, 12014, 12011, -1, 12011, 12014, 12015, -1, 12015, 12014, 12016, -1, 12017, 12014, 12013, -1, 12017, 12018, 12014, -1, 12014, 12018, 12016, -1, 12016, 12018, 12019, -1, 12020, 12018, 12017, -1, 12019, 12021, 12022, -1, 12020, 12021, 12018, -1, 12018, 12021, 12019, -1, 12023, 12021, 12020, -1, 12024, 12021, 12023, -1, 12022, 12025, 12026, -1, 12026, 12025, 12027, -1, 12021, 12025, 12022, -1, 12024, 12025, 12021, -1, 12028, 12025, 12024, -1, 12027, 12029, 12030, -1, 12030, 12029, 12031, -1, 12031, 12029, 12032, -1, 12025, 12029, 12027, -1, 12028, 12029, 12025, -1, 12032, 12029, 12028, -1, 12033, 12034, 12035, -1, 12035, 12034, 12036, -1, 12037, 12034, 12033, -1, 12038, 12034, 12037, -1, 12036, 12039, 12040, -1, 12040, 12039, 12041, -1, 12042, 12039, 12038, -1, 12038, 12039, 12034, -1, 12034, 12039, 12036, -1, 12042, 12043, 12039, -1, 12041, 12043, 12044, -1, 12045, 12043, 12042, -1, 12046, 12043, 12045, -1, 12031, 12037, 12033, -1, 12039, 12043, 12041, -1, 12032, 12037, 12031, -1, 12043, 12047, 12044, -1, 12046, 12047, 12043, -1, 12044, 12047, 12048, -1, 12049, 12047, 12046, -1, 11944, 12050, 11942, -1, 12051, 12050, 11944, -1, 11942, 12052, 11943, -1, 12050, 12052, 11942, -1, 11943, 12052, 12053, -1, 12051, 12052, 12050, -1, 12053, 12052, 12051, -1, 12047, 12054, 12048, -1, 12048, 12054, 12055, -1, 12049, 12056, 12047, -1, 12055, 12056, 12057, -1, 12047, 12056, 12054, -1, 12054, 12056, 12055, -1, 12057, 12056, 12049, -1, 11943, 11865, 11866, -1, 11962, 12058, 11875, -1, 11875, 12058, 12059, -1, 11943, 12053, 11865, -1, 12057, 12049, 11871, -1, 11871, 12049, 11868, -1, 12058, 11951, 12060, -1, 11868, 12046, 11862, -1, 11962, 11951, 12058, -1, 12049, 12046, 11868, -1, 12061, 11858, 11860, -1, 12060, 11858, 12061, -1, 11951, 11953, 12060, -1, 12060, 11953, 11858, -1, 11862, 12045, 11855, -1, 12046, 12045, 11862, -1, 11858, 11994, 11937, -1, 12045, 12042, 11855, -1, 11953, 11994, 11858, -1, 11855, 12042, 11853, -1, 11937, 11990, 11934, -1, 11994, 11990, 11937, -1, 12042, 12038, 11853, -1, 11853, 12038, 11852, -1, 11934, 11987, 11932, -1, 11990, 11987, 11934, -1, 11852, 12062, 11935, -1, 11932, 11986, 11927, -1, 11987, 11986, 11932, -1, 12038, 12037, 11852, -1, 11852, 12037, 12062, -1, 11986, 11983, 11927, -1, 11927, 11983, 11925, -1, 12037, 12063, 12062, -1, 11983, 11979, 11925, -1, 12063, 12032, 11929, -1, 11925, 11979, 11920, -1, 11929, 12032, 11923, -1, 12037, 12032, 12063, -1, 11979, 11976, 11920, -1, 11920, 11976, 11916, -1, 11923, 12028, 11921, -1, 12032, 12028, 11923, -1, 11976, 11975, 11916, -1, 11916, 11975, 11913, -1, 11921, 12024, 11917, -1, 12028, 12024, 11921, -1, 12024, 12023, 11917, -1, 11975, 11972, 11913, -1, 11913, 11972, 11909, -1, 12023, 11911, 11917, -1, 12023, 12020, 11911, -1, 11909, 11968, 11901, -1, 11972, 11968, 11909, -1, 12020, 11907, 11911, -1, 12020, 12017, 11907, -1, 11901, 11967, 11902, -1, 11968, 11967, 11901, -1, 12017, 11904, 11907, -1, 11967, 12064, 11902, -1, 12017, 12013, 11904, -1, 12013, 11899, 11904, -1, 12013, 12012, 11899, -1, 11967, 11961, 12064, -1, 12064, 11961, 12065, -1, 12012, 11894, 11899, -1, 11961, 11888, 12065, -1, 12012, 12009, 11894, -1, 12065, 11888, 11892, -1, 11961, 11954, 11888, -1, 12009, 11891, 11894, -1, 12009, 12006, 11891, -1, 11954, 11883, 11888, -1, 11954, 11948, 11883, -1, 12006, 11886, 11891, -1, 11948, 11881, 11883, -1, 12006, 12005, 11886, -1, 11948, 11947, 11881, -1, 12005, 11875, 11886, -1, 11947, 11872, 11881, -1, 12005, 11962, 11875, -1, 11947, 11941, 11872, -1, 11941, 11866, 11872, -1, 11875, 12059, 11876, -1, 11941, 11943, 11866, -1, 12066, 12067, 11090, -1, 11075, 12067, 11083, -1, 11090, 12067, 11075, -1, 11083, 12068, 11088, -1, 12067, 12068, 11083, -1, 11088, 12069, 11094, -1, 12068, 12069, 11088, -1, 11094, 12070, 11100, -1, 12069, 12070, 11094, -1, 11100, 12071, 11105, -1, 12070, 12071, 11100, -1, 11105, 12072, 11110, -1, 12071, 12072, 11105, -1, 11110, 12073, 11123, -1, 12072, 12073, 11110, -1, 11123, 12074, 11128, -1, 12073, 12074, 11123, -1, 11128, 12075, 11115, -1, 12074, 12075, 11128, -1, 12075, 12076, 11115, -1, 11115, 12077, 11116, -1, 12076, 12077, 11115, -1, 12078, 12079, 11271, -1, 11271, 12079, 11272, -1, 11274, 12080, 11275, -1, 11272, 12080, 11274, -1, 12079, 12080, 11272, -1, 12080, 12081, 11275, -1, 12082, 12083, 11168, -1, 11168, 12083, 11166, -1, 11166, 12084, 11133, -1, 12083, 12084, 11166, -1, 11133, 12085, 11131, -1, 12084, 12085, 11133, -1, 11131, 12086, 11146, -1, 12085, 12086, 11131, -1, 11146, 12087, 11150, -1, 12086, 12087, 11146, -1, 11154, 12088, 11155, -1, 11150, 12088, 11154, -1, 12087, 12088, 11150, -1, 12088, 12089, 11155, -1, 12090, 12091, 12092, -1, 12092, 12091, 12093, -1, 12093, 12094, 12095, -1, 12091, 12094, 12093, -1, 12095, 12096, 12097, -1, 12094, 12096, 12095, -1, 12097, 12098, 12099, -1, 12096, 12098, 12097, -1, 12099, 12100, 12101, -1, 12098, 12100, 12099, -1, 12101, 12102, 12103, -1, 12100, 12102, 12101, -1, 12103, 12104, 12105, -1, 12102, 12104, 12103, -1, 12105, 12106, 12107, -1, 12104, 12106, 12105, -1, 12107, 12108, 12109, -1, 12106, 12108, 12107, -1, 12109, 12110, 12111, -1, 12108, 12110, 12109, -1, 12111, 12112, 12113, -1, 12110, 12112, 12111, -1, 12113, 12114, 12115, -1, 12112, 12114, 12113, -1, 12115, 12116, 12117, -1, 12114, 12116, 12115, -1, 12118, 12119, 12120, -1, 12120, 12119, 12121, -1, 12121, 12122, 12123, -1, 12119, 12122, 12121, -1, 12123, 12124, 12125, -1, 12122, 12124, 12123, -1, 12125, 12126, 12127, -1, 12124, 12126, 12125, -1, 12127, 12128, 12129, -1, 12126, 12128, 12127, -1, 12129, 12130, 12131, -1, 12128, 12130, 12129, -1, 12131, 12132, 12133, -1, 12130, 12132, 12131, -1, 12133, 12134, 12135, -1, 12132, 12134, 12133, -1, 12135, 12136, 12137, -1, 12134, 12136, 12135, -1, 12137, 12138, 12139, -1, 12136, 12138, 12137, -1, 12139, 12140, 12141, -1, 12138, 12140, 12139, -1, 12141, 12142, 12143, -1, 12140, 12142, 12141, -1, 12143, 12144, 12145, -1, 12142, 12144, 12143, -1, 12146, 12147, 12148, -1, 12148, 12149, 12150, -1, 12147, 12149, 12148, -1, 12150, 12151, 12152, -1, 12149, 12151, 12150, -1, 12152, 12153, 12154, -1, 12151, 12153, 12152, -1, 12154, 12155, 12156, -1, 12153, 12155, 12154, -1, 12156, 12157, 12158, -1, 12155, 12157, 12156, -1, 12158, 12159, 12160, -1, 12157, 12159, 12158, -1, 12160, 12161, 12162, -1, 12159, 12161, 12160, -1, 12162, 12163, 12164, -1, 12161, 12163, 12162, -1, 12164, 12165, 12166, -1, 12163, 12165, 12164, -1, 12166, 12167, 12168, -1, 12165, 12167, 12166, -1, 12168, 12169, 12170, -1, 12167, 12169, 12168, -1, 12170, 12171, 12172, -1, 12169, 12171, 12170, -1, 12171, 12173, 12172, -1, 12174, 12175, 11017, -1, 11017, 12175, 11015, -1, 11015, 12176, 11013, -1, 12175, 12176, 11015, -1, 11013, 12177, 11011, -1, 12176, 12177, 11013, -1, 11011, 12178, 11009, -1, 12177, 12178, 11011, -1, 11009, 12179, 11007, -1, 12178, 12179, 11009, -1, 11007, 12180, 11005, -1, 12179, 12180, 11007, -1, 11005, 12181, 11003, -1, 12180, 12181, 11005, -1, 11003, 12182, 11002, -1, 12181, 12182, 11003, -1, 11002, 12183, 11000, -1, 12182, 12183, 11002, -1, 11000, 12184, 10998, -1, 12183, 12184, 11000, -1, 10998, 12185, 10996, -1, 12184, 12185, 10998, -1, 10996, 12186, 10994, -1, 12185, 12186, 10996, -1, 10994, 12187, 10993, -1, 12186, 12187, 10994, -1, 11029, 12188, 12189, -1, 12189, 12190, 12191, -1, 12188, 12190, 12189, -1, 12191, 12192, 12193, -1, 12190, 12192, 12191, -1, 12193, 12194, 12195, -1, 12192, 12194, 12193, -1, 12195, 12196, 12197, -1, 12194, 12196, 12195, -1, 12197, 12198, 12199, -1, 12196, 12198, 12197, -1, 12200, 12201, 12202, -1, 12199, 12203, 12201, -1, 12198, 12203, 12199, -1, 12203, 12204, 12201, -1, 12202, 12205, 12206, -1, 12201, 12205, 12202, -1, 12204, 12205, 12201, -1, 12206, 12207, 12208, -1, 12205, 12207, 12206, -1, 12208, 12209, 12210, -1, 12207, 12209, 12208, -1, 12210, 12211, 12212, -1, 12209, 12211, 12210, -1, 12213, 12214, 12215, -1, 12212, 12214, 12213, -1, 12211, 12214, 12212, -1, 12214, 12216, 12215, -1, 12217, 12218, 12219, -1, 12219, 12220, 12221, -1, 12218, 12220, 12219, -1, 12221, 12222, 12223, -1, 12220, 12222, 12221, -1, 12223, 12224, 12225, -1, 12222, 12224, 12223, -1, 12225, 12226, 12227, -1, 12224, 12226, 12225, -1, 12227, 12228, 12229, -1, 12226, 12228, 12227, -1, 12229, 12230, 12231, -1, 12228, 12230, 12229, -1, 12228, 12232, 12230, -1, 12230, 12233, 12234, -1, 12232, 12233, 12230, -1, 12234, 12235, 12236, -1, 12233, 12235, 12234, -1, 12236, 12237, 12238, -1, 12235, 12237, 12236, -1, 12238, 12239, 12240, -1, 12237, 12239, 12238, -1, 12240, 12241, 12242, -1, 12239, 12241, 12240, -1, 12242, 12243, 12244, -1, 12241, 12243, 12242, -1, 12244, 12245, 12246, -1, 12243, 12245, 12244, -1, 12247, 12248, 12249, -1, 12250, 12247, 12249, -1, 12251, 12247, 12250, -1, 12252, 12251, 12250, -1, 12253, 12254, 12255, -1, 12253, 12256, 12254, -1, 12257, 12251, 12252, -1, 12258, 12257, 12252, -1, 12259, 12255, 12260, -1, 12259, 12253, 12255, -1, 12261, 12257, 12258, -1, 12262, 12261, 12258, -1, 12263, 12260, 12264, -1, 12265, 12261, 12262, -1, 12263, 12259, 12260, -1, 12266, 12265, 12262, -1, 12267, 12265, 12266, -1, 12268, 12264, 12269, -1, 12268, 12263, 12264, -1, 12270, 12267, 12266, -1, 12271, 12267, 12270, -1, 12272, 12271, 12270, -1, 12273, 12269, 12274, -1, 12273, 12268, 12269, -1, 12275, 12271, 12272, -1, 12276, 12275, 12272, -1, 12277, 12273, 12274, -1, 12278, 12275, 12276, -1, 12277, 12274, 12279, -1, 12280, 12278, 12276, -1, 12281, 12278, 12280, -1, 12282, 12277, 12279, -1, 12282, 12279, 12283, -1, 12284, 12281, 12280, -1, 12285, 12281, 12284, -1, 12286, 12282, 12283, -1, 12286, 12283, 12287, -1, 12288, 12285, 12284, -1, 12289, 12285, 12288, -1, 12290, 12286, 12287, -1, 12290, 12287, 12291, -1, 12292, 12289, 12288, -1, 12293, 12289, 12292, -1, 12294, 12290, 12291, -1, 12295, 12293, 12292, -1, 12294, 12291, 12296, -1, 12297, 12293, 12295, -1, 12298, 12294, 12296, -1, 12299, 12297, 12295, -1, 12298, 12296, 12300, -1, 12301, 12297, 12299, -1, 12302, 12300, 12303, -1, 12304, 12301, 12299, -1, 12302, 12298, 12300, -1, 12305, 12301, 12304, -1, 12306, 12305, 12304, -1, 12307, 12303, 12308, -1, 12307, 12302, 12303, -1, 12309, 12305, 12306, -1, 12310, 12309, 12306, -1, 12311, 12308, 12312, -1, 12311, 12307, 12308, -1, 12313, 12309, 12310, -1, 12314, 12312, 12315, -1, 12314, 12311, 12312, -1, 12316, 12315, 12317, -1, 12316, 12314, 12315, -1, 12318, 12317, 12319, -1, 12318, 12316, 12317, -1, 12320, 12319, 12321, -1, 12320, 12318, 12319, -1, 12322, 12321, 12323, -1, 12322, 12320, 12321, -1, 12324, 12323, 12325, -1, 12324, 12322, 12323, -1, 12248, 12325, 12249, -1, 12248, 12324, 12325, -1, 12326, 12327, 12328, -1, 12326, 12329, 12330, -1, 12331, 12332, 12333, -1, 12326, 12328, 12329, -1, 12331, 12333, 12334, -1, 12331, 12334, 12335, -1, 12336, 12337, 12338, -1, 12339, 12340, 12341, -1, 12339, 12335, 12340, -1, 12336, 12330, 12337, -1, 12339, 12341, 12342, -1, 12343, 12336, 12338, -1, 12344, 12342, 12345, -1, 12344, 12346, 12347, -1, 12344, 12339, 12342, -1, 12344, 12345, 12346, -1, 12344, 12347, 12331, -1, 12348, 12349, 12326, -1, 12344, 12331, 12335, -1, 12348, 12326, 12330, -1, 12344, 12335, 12339, -1, 12348, 12330, 12336, -1, 12350, 12336, 12343, -1, 12350, 12351, 12349, -1, 12350, 12348, 12336, -1, 12342, 12341, 12352, -1, 12350, 12349, 12348, -1, 12353, 12343, 12338, -1, 12353, 12338, 12354, -1, 12355, 12353, 12354, -1, 12356, 12357, 12358, -1, 12359, 12350, 12343, -1, 12359, 12343, 12353, -1, 12360, 12346, 12345, -1, 12359, 12351, 12350, -1, 12361, 12354, 12362, -1, 12363, 12364, 12365, -1, 12361, 12355, 12354, -1, 12363, 12366, 12364, -1, 12367, 12359, 12353, -1, 12368, 12366, 12363, -1, 12368, 12369, 12356, -1, 12367, 12370, 12351, -1, 12367, 12353, 12355, -1, 12368, 12358, 12366, -1, 12367, 12351, 12359, -1, 12368, 12356, 12358, -1, 12371, 12355, 12361, -1, 12371, 12370, 12367, -1, 12372, 12365, 12373, -1, 12372, 12363, 12365, -1, 12371, 12367, 12355, -1, 12374, 12368, 12363, -1, 12374, 12375, 12369, -1, 12376, 12361, 12362, -1, 12374, 12363, 12372, -1, 12377, 12362, 12378, -1, 12374, 12369, 12368, -1, 12377, 12376, 12362, -1, 12379, 12373, 12380, -1, 12381, 12370, 12371, -1, 12381, 12371, 12361, -1, 12379, 12372, 12373, -1, 12381, 12361, 12376, -1, 12382, 12383, 12375, -1, 12382, 12375, 12374, -1, 12381, 12384, 12370, -1, 12382, 12374, 12372, -1, 12385, 12376, 12377, -1, 12382, 12372, 12379, -1, 12385, 12381, 12376, -1, 12385, 12384, 12381, -1, 12386, 12380, 12387, -1, 12388, 12377, 12378, -1, 12386, 12379, 12380, -1, 12389, 12383, 12382, -1, 12389, 12382, 12379, -1, 12390, 12378, 12391, -1, 12389, 12379, 12386, -1, 12390, 12388, 12378, -1, 12389, 12392, 12383, -1, 12393, 12387, 12394, -1, 12395, 12385, 12377, -1, 12393, 12386, 12387, -1, 12395, 12384, 12385, -1, 12395, 12377, 12388, -1, 12395, 12396, 12384, -1, 12397, 12398, 12392, -1, 12397, 12386, 12393, -1, 12399, 12388, 12390, -1, 12397, 12389, 12386, -1, 12399, 12395, 12388, -1, 12397, 12392, 12389, -1, 12399, 12396, 12395, -1, 12400, 12393, 12394, -1, 12400, 12394, 12401, -1, 12402, 12390, 12391, -1, 12403, 12391, 12404, -1, 12405, 12406, 12398, -1, 12403, 12402, 12391, -1, 12405, 12398, 12397, -1, 12405, 12393, 12400, -1, 12405, 12397, 12393, -1, 12407, 12399, 12390, -1, 12407, 12396, 12399, -1, 12408, 12401, 12409, -1, 12407, 12390, 12402, -1, 12408, 12400, 12401, -1, 12407, 12410, 12396, -1, 12411, 12402, 12403, -1, 12411, 12407, 12402, -1, 12412, 12408, 12409, -1, 12411, 12410, 12407, -1, 12413, 12403, 12404, -1, 12414, 12406, 12405, -1, 12414, 12405, 12400, -1, 12414, 12400, 12408, -1, 12415, 12404, 12416, -1, 12417, 12418, 12406, -1, 12415, 12413, 12404, -1, 12417, 12406, 12414, -1, 12417, 12408, 12412, -1, 12417, 12414, 12408, -1, 12419, 12403, 12413, -1, 12419, 12420, 12410, -1, 12421, 12409, 12422, -1, 12419, 12411, 12403, -1, 12421, 12412, 12409, -1, 12419, 12410, 12411, -1, 12423, 12420, 12419, -1, 12423, 12419, 12413, -1, 12424, 12421, 12422, -1, 12423, 12413, 12415, -1, 12425, 12415, 12416, -1, 12426, 12417, 12412, -1, 12426, 12418, 12417, -1, 12426, 12412, 12421, -1, 12427, 12415, 12425, -1, 12428, 12418, 12426, -1, 12428, 12429, 12418, -1, 12427, 12430, 12420, -1, 12428, 12426, 12421, -1, 12428, 12421, 12424, -1, 12427, 12423, 12415, -1, 12427, 12420, 12423, -1, 12431, 12422, 12432, -1, 12433, 12416, 12434, -1, 12431, 12424, 12422, -1, 12433, 12425, 12416, -1, 12435, 12431, 12432, -1, 12436, 12437, 12430, -1, 12438, 12429, 12428, -1, 12438, 12428, 12424, -1, 12436, 12427, 12425, -1, 12438, 12424, 12431, -1, 12436, 12430, 12427, -1, 12436, 12425, 12433, -1, 12439, 12327, 12429, -1, 12334, 12434, 12440, -1, 12439, 12429, 12438, -1, 12439, 12431, 12435, -1, 12439, 12438, 12431, -1, 12334, 12433, 12434, -1, 12329, 12432, 12337, -1, 12333, 12437, 12436, -1, 12333, 12332, 12437, -1, 12329, 12435, 12432, -1, 12333, 12436, 12433, -1, 12333, 12433, 12334, -1, 12330, 12329, 12337, -1, 12335, 12440, 12340, -1, 12328, 12327, 12439, -1, 12328, 12439, 12435, -1, 12335, 12334, 12440, -1, 12328, 12435, 12329, -1, 12331, 12347, 12332, -1, 12326, 12349, 12327, -1, 12441, 12442, 12443, -1, 12443, 12444, 12445, -1, 12442, 12444, 12443, -1, 12445, 12446, 12447, -1, 12444, 12446, 12445, -1, 12447, 12448, 12449, -1, 12446, 12448, 12447, -1, 12449, 12450, 12451, -1, 12448, 12450, 12449, -1, 12450, 12452, 12451, -1, 12451, 12453, 12454, -1, 12452, 12453, 12451, -1, 12454, 12455, 12456, -1, 12453, 12455, 12454, -1, 12457, 12458, 12459, -1, 12457, 12460, 12458, -1, 12461, 12459, 12462, -1, 12461, 12457, 12459, -1, 12463, 12462, 12464, -1, 12463, 12461, 12462, -1, 12465, 12466, 12467, -1, 12468, 12469, 12387, -1, 12470, 12466, 12465, -1, 12470, 12471, 12466, -1, 12472, 12469, 12468, -1, 12472, 12465, 12469, -1, 12473, 12471, 12470, -1, 12473, 12474, 12475, -1, 12473, 12475, 12471, -1, 12476, 12468, 12387, -1, 12476, 12387, 12380, -1, 12477, 12470, 12465, -1, 12477, 12465, 12472, -1, 12478, 12472, 12468, -1, 12478, 12468, 12476, -1, 12479, 12473, 12470, -1, 12479, 12470, 12477, -1, 12479, 12474, 12473, -1, 12480, 12476, 12380, -1, 12481, 12477, 12472, -1, 12481, 12472, 12478, -1, 12482, 12483, 12484, -1, 12482, 12484, 12485, -1, 12482, 12485, 12486, -1, 12482, 12486, 12487, -1, 12482, 12487, 12488, -1, 12482, 12488, 12489, -1, 12482, 12489, 12490, -1, 12482, 12490, 12491, -1, 12482, 12491, 12492, -1, 12482, 12492, 12493, -1, 12482, 12493, 12494, -1, 12482, 12494, 12495, -1, 12482, 12495, 12474, -1, 12482, 12474, 12479, -1, 12496, 12478, 12476, -1, 12496, 12476, 12480, -1, 12497, 12483, 12482, -1, 12497, 12479, 12477, -1, 12497, 12498, 12483, -1, 12497, 12482, 12479, -1, 12497, 12477, 12481, -1, 12499, 12480, 12380, -1, 12500, 12481, 12478, -1, 12500, 12478, 12496, -1, 12501, 12496, 12480, -1, 12501, 12480, 12499, -1, 12502, 12481, 12500, -1, 12502, 12503, 12498, -1, 12502, 12500, 12503, -1, 12502, 12498, 12497, -1, 12502, 12497, 12481, -1, 12504, 12380, 12373, -1, 12504, 12499, 12380, -1, 12505, 12506, 12503, -1, 12505, 12503, 12500, -1, 12505, 12500, 12496, -1, 12505, 12496, 12501, -1, 12507, 12501, 12499, -1, 12507, 12499, 12504, -1, 12508, 12504, 12373, -1, 12509, 12510, 12506, -1, 12509, 12506, 12505, -1, 12509, 12501, 12507, -1, 12509, 12505, 12501, -1, 12511, 12510, 12509, -1, 12511, 12507, 12504, -1, 12511, 12509, 12507, -1, 12511, 12504, 12508, -1, 12512, 12508, 12373, -1, 12513, 12514, 12510, -1, 12513, 12510, 12511, -1, 12513, 12511, 12508, -1, 12513, 12508, 12512, -1, 12513, 12512, 12514, -1, 12515, 12373, 12365, -1, 12515, 12512, 12373, -1, 12515, 12514, 12512, -1, 12516, 12517, 12514, -1, 12516, 12514, 12515, -1, 12518, 12517, 12516, -1, 12518, 12516, 12515, -1, 12518, 12515, 12365, -1, 12519, 12520, 12517, -1, 12519, 12517, 12518, -1, 12519, 12518, 12365, -1, 12521, 12365, 12364, -1, 12521, 12519, 12365, -1, 12521, 12520, 12519, -1, 12522, 12520, 12521, -1, 12522, 12364, 12523, -1, 12524, 12525, 12391, -1, 12522, 12523, 12526, -1, 12522, 12526, 12527, -1, 12522, 12527, 12520, -1, 12522, 12521, 12364, -1, 12378, 12524, 12391, -1, 12528, 12524, 12378, -1, 12362, 12528, 12378, -1, 12529, 12528, 12362, -1, 12530, 12529, 12362, -1, 12354, 12530, 12362, -1, 12531, 12530, 12354, -1, 12532, 12531, 12354, -1, 12338, 12532, 12354, -1, 12533, 12532, 12338, -1, 12534, 12533, 12338, -1, 12337, 12534, 12338, -1, 12535, 12534, 12337, -1, 12432, 12535, 12337, -1, 12432, 12536, 12535, -1, 12537, 12536, 12432, -1, 12422, 12537, 12432, -1, 12538, 12537, 12422, -1, 12539, 12538, 12422, -1, 12409, 12539, 12422, -1, 12540, 12539, 12409, -1, 12541, 12542, 12543, -1, 12541, 12544, 12542, -1, 12541, 12545, 12544, -1, 12541, 12543, 12352, -1, 12546, 12352, 12341, -1, 12546, 12541, 12352, -1, 12546, 12545, 12541, -1, 12546, 12547, 12545, -1, 12548, 12546, 12341, -1, 12548, 12547, 12546, -1, 12548, 12549, 12547, -1, 12550, 12548, 12341, -1, 12550, 12549, 12548, -1, 12551, 12341, 12340, -1, 12551, 12550, 12341, -1, 12551, 12549, 12550, -1, 12552, 12553, 12549, -1, 12552, 12551, 12553, -1, 12552, 12549, 12551, -1, 12554, 12551, 12340, -1, 12554, 12553, 12551, -1, 12555, 12553, 12554, -1, 12555, 12556, 12553, -1, 12557, 12554, 12340, -1, 12558, 12554, 12557, -1, 12558, 12556, 12555, -1, 12558, 12555, 12554, -1, 12558, 12559, 12556, -1, 12560, 12340, 12440, -1, 12560, 12557, 12340, -1, 12561, 12557, 12560, -1, 12561, 12559, 12558, -1, 12561, 12558, 12557, -1, 12562, 12560, 12440, -1, 12563, 12559, 12561, -1, 12563, 12564, 12565, -1, 12563, 12565, 12559, -1, 12566, 12560, 12562, -1, 12566, 12561, 12560, -1, 12567, 12562, 12440, -1, 12568, 12561, 12566, -1, 12568, 12564, 12563, -1, 12568, 12563, 12561, -1, 12569, 12562, 12567, -1, 12569, 12566, 12562, -1, 12570, 12440, 12434, -1, 12570, 12567, 12440, -1, 12571, 12566, 12569, -1, 12571, 12568, 12566, -1, 12572, 12569, 12567, -1, 12572, 12567, 12570, -1, 12573, 12564, 12568, -1, 12573, 12568, 12571, -1, 12573, 12574, 12564, -1, 12575, 12570, 12434, -1, 12576, 12571, 12569, -1, 12576, 12569, 12572, -1, 12577, 12572, 12570, -1, 12577, 12570, 12575, -1, 12578, 12573, 12571, -1, 12578, 12574, 12573, -1, 12578, 12571, 12576, -1, 12578, 12579, 12574, -1, 12580, 12575, 12434, -1, 12581, 12572, 12577, -1, 12581, 12576, 12572, -1, 12582, 12577, 12575, -1, 12582, 12575, 12580, -1, 12583, 12576, 12581, -1, 12583, 12578, 12576, -1, 12584, 12580, 12434, -1, 12585, 12577, 12582, -1, 12585, 12581, 12577, -1, 12586, 12579, 12578, -1, 12586, 12578, 12583, -1, 12586, 12583, 12587, -1, 12586, 12587, 12588, -1, 12586, 12588, 12589, -1, 12586, 12589, 12590, -1, 12586, 12590, 12591, -1, 12586, 12591, 12592, -1, 12586, 12592, 12593, -1, 12586, 12593, 12594, -1, 12586, 12594, 12595, -1, 12586, 12595, 12596, -1, 12586, 12596, 12597, -1, 12586, 12597, 12598, -1, 12586, 12598, 12599, -1, 12586, 12599, 12579, -1, 12600, 12582, 12580, -1, 12600, 12580, 12584, -1, 12601, 12583, 12581, -1, 12601, 12581, 12585, -1, 12601, 12587, 12583, -1, 12601, 12602, 12587, -1, 12603, 12434, 12416, -1, 12603, 12584, 12434, -1, 12604, 12582, 12600, -1, 12604, 12585, 12582, -1, 12605, 12584, 12603, -1, 12605, 12600, 12584, -1, 12606, 12602, 12601, -1, 12606, 12601, 12585, -1, 12606, 12604, 12607, -1, 12606, 12585, 12604, -1, 12606, 12607, 12602, -1, 12608, 12603, 12416, -1, 12609, 12607, 12604, -1, 12609, 12605, 12610, -1, 12609, 12604, 12600, -1, 12609, 12610, 12607, -1, 12609, 12600, 12605, -1, 12611, 12610, 12605, -1, 12611, 12605, 12603, -1, 12611, 12612, 12610, -1, 12611, 12603, 12608, -1, 12613, 12608, 12416, -1, 12614, 12608, 12613, -1, 12614, 12611, 12608, -1, 12614, 12612, 12611, -1, 12614, 12615, 12612, -1, 12616, 12416, 12404, -1, 12616, 12613, 12416, -1, 12617, 12615, 12614, -1, 12617, 12613, 12616, -1, 12617, 12618, 12615, -1, 12617, 12614, 12613, -1, 12619, 12616, 12404, -1, 12620, 12616, 12619, -1, 12620, 12617, 12616, -1, 12620, 12618, 12617, -1, 12620, 12621, 12618, -1, 12622, 12620, 12619, -1, 12622, 12621, 12620, -1, 12622, 12619, 12404, -1, 12623, 12404, 12391, -1, 12623, 12621, 12622, -1, 12623, 12525, 12621, -1, 12623, 12622, 12404, -1, 12624, 12525, 12623, -1, 12624, 12623, 12391, -1, 12624, 12391, 12525, -1, 12625, 12540, 12409, -1, 12626, 12409, 12401, -1, 12626, 12625, 12409, -1, 12626, 12540, 12625, -1, 12626, 12627, 12540, -1, 12628, 12626, 12401, -1, 12628, 12627, 12626, -1, 12629, 12628, 12401, -1, 12630, 12631, 12627, -1, 12630, 12627, 12628, -1, 12630, 12628, 12629, -1, 12630, 12629, 12631, -1, 12632, 12401, 12394, -1, 12632, 12629, 12401, -1, 12632, 12631, 12629, -1, 12633, 12634, 12631, -1, 12633, 12631, 12632, -1, 12635, 12632, 12394, -1, 12636, 12637, 12634, -1, 12636, 12632, 12635, -1, 12636, 12634, 12633, -1, 12636, 12633, 12632, -1, 12638, 12635, 12394, -1, 12639, 12635, 12638, -1, 12639, 12640, 12637, -1, 12639, 12637, 12636, -1, 12639, 12636, 12635, -1, 12641, 12394, 12387, -1, 12641, 12638, 12394, -1, 12642, 12638, 12641, -1, 12642, 12639, 12638, -1, 12642, 12640, 12639, -1, 12467, 12641, 12387, -1, 12643, 12644, 12640, -1, 12643, 12640, 12642, -1, 12466, 12642, 12641, -1, 12466, 12641, 12467, -1, 12469, 12467, 12387, -1, 12471, 12475, 12644, -1, 12471, 12644, 12643, -1, 12471, 12643, 12642, -1, 12471, 12642, 12466, -1, 12465, 12467, 12469, -1, 12645, 12646, 12647, -1, 12647, 12646, 12648, -1, 12648, 12649, 12650, -1, 12646, 12649, 12648, -1, 12650, 12651, 12652, -1, 12649, 12651, 12650, -1, 12652, 12653, 12654, -1, 12651, 12653, 12652, -1, 12654, 12655, 12656, -1, 12653, 12655, 12654, -1, 12656, 12657, 12658, -1, 12655, 12657, 12656, -1, 12657, 12659, 12658, -1, 12658, 12660, 12661, -1, 12659, 12660, 12658, -1, 12660, 12662, 12661, -1, 12663, 12664, 12665, -1, 12665, 12666, 12667, -1, 12664, 12666, 12665, -1, 12667, 12668, 12669, -1, 12666, 12668, 12667, -1, 12669, 12670, 12671, -1, 12668, 12670, 12669, -1, 12671, 12672, 12673, -1, 12670, 12672, 12671, -1, 12672, 12674, 12673, -1, 12675, 12676, 12677, -1, 12673, 12676, 12675, -1, 12674, 12676, 12673, -1, 12677, 12678, 12679, -1, 12676, 12678, 12677, -1, 12679, 12680, 12681, -1, 12678, 12680, 12679, -1, 12680, 12682, 12681, -1, 12681, 12683, 12684, -1, 12682, 12683, 12681, -1, 12684, 12685, 12686, -1, 12683, 12685, 12684, -1, 12685, 12687, 12686, -1, 12688, 12689, 12690, -1, 12690, 12691, 12692, -1, 12689, 12691, 12690, -1, 12692, 12693, 12694, -1, 12691, 12693, 12692, -1, 12693, 12695, 12694, -1, 12696, 12697, 12698, -1, 12696, 12699, 12697, -1, 12696, 12251, 12699, -1, 12696, 12247, 12251, -1, 12700, 12701, 12702, -1, 12700, 12703, 12701, -1, 12704, 12703, 12700, -1, 12704, 12705, 12703, -1, 12706, 12707, 12705, -1, 12706, 12705, 12704, -1, 12708, 12698, 12707, -1, 12708, 12707, 12706, -1, 12709, 12696, 12698, -1, 12709, 12247, 12696, -1, 12709, 12698, 12708, -1, 12709, 12324, 12248, -1, 12709, 12248, 12247, -1, 12710, 12702, 12711, -1, 12710, 12700, 12702, -1, 12712, 12704, 12700, -1, 12712, 12700, 12710, -1, 12713, 12706, 12704, -1, 12713, 12704, 12712, -1, 12714, 12708, 12706, -1, 12714, 12706, 12713, -1, 12715, 12708, 12714, -1, 12715, 12709, 12708, -1, 12715, 12324, 12709, -1, 12716, 12711, 12717, -1, 12716, 12710, 12711, -1, 12718, 12712, 12710, -1, 12718, 12710, 12716, -1, 12719, 12713, 12712, -1, 12719, 12712, 12718, -1, 12720, 12714, 12713, -1, 12720, 12713, 12719, -1, 12721, 12715, 12714, -1, 12721, 12324, 12715, -1, 12721, 12714, 12720, -1, 12721, 12322, 12324, -1, 12722, 12717, 12723, -1, 12722, 12716, 12717, -1, 12724, 12718, 12716, -1, 12724, 12716, 12722, -1, 12725, 12719, 12718, -1, 12725, 12718, 12724, -1, 12726, 12720, 12719, -1, 12726, 12719, 12725, -1, 12727, 12320, 12322, -1, 12727, 12720, 12726, -1, 12727, 12721, 12720, -1, 12727, 12322, 12721, -1, 12728, 12723, 12729, -1, 12728, 12722, 12723, -1, 12730, 12724, 12722, -1, 12730, 12722, 12728, -1, 12731, 12725, 12724, -1, 12731, 12724, 12730, -1, 12732, 12726, 12725, -1, 12732, 12725, 12731, -1, 12733, 12318, 12320, -1, 12733, 12320, 12727, -1, 12733, 12727, 12726, -1, 12733, 12726, 12732, -1, 12734, 12729, 12735, -1, 12734, 12728, 12729, -1, 12736, 12728, 12734, -1, 12736, 12730, 12728, -1, 12737, 12730, 12736, -1, 12737, 12731, 12730, -1, 12738, 12731, 12737, -1, 12738, 12732, 12731, -1, 12739, 12733, 12732, -1, 12739, 12732, 12738, -1, 12739, 12316, 12318, -1, 12739, 12318, 12733, -1, 12740, 12735, 12741, -1, 12740, 12734, 12735, -1, 12742, 12734, 12740, -1, 12742, 12736, 12734, -1, 12743, 12736, 12742, -1, 12743, 12737, 12736, -1, 12744, 12737, 12743, -1, 12744, 12738, 12737, -1, 12745, 12316, 12739, -1, 12745, 12738, 12744, -1, 12745, 12314, 12316, -1, 12745, 12739, 12738, -1, 12746, 12740, 12741, -1, 12746, 12741, 12747, -1, 12748, 12740, 12746, -1, 12748, 12742, 12740, -1, 12749, 12743, 12742, -1, 12749, 12742, 12748, -1, 12750, 12744, 12743, -1, 12750, 12743, 12749, -1, 12751, 12745, 12744, -1, 12751, 12314, 12745, -1, 12751, 12744, 12750, -1, 12751, 12311, 12314, -1, 12752, 12747, 12753, -1, 12752, 12746, 12747, -1, 12754, 12748, 12746, -1, 12754, 12746, 12752, -1, 12755, 12749, 12748, -1, 12755, 12748, 12754, -1, 12756, 12750, 12749, -1, 12756, 12749, 12755, -1, 12757, 12751, 12750, -1, 12757, 12311, 12751, -1, 12757, 12750, 12756, -1, 12757, 12307, 12311, -1, 12758, 12752, 12753, -1, 12758, 12753, 12759, -1, 12760, 12754, 12752, -1, 12760, 12752, 12758, -1, 12761, 12754, 12760, -1, 12761, 12755, 12754, -1, 12762, 12756, 12755, -1, 12762, 12755, 12761, -1, 12763, 12302, 12307, -1, 12763, 12756, 12762, -1, 12763, 12757, 12756, -1, 12763, 12307, 12757, -1, 12764, 12758, 12759, -1, 12764, 12759, 12765, -1, 12766, 12760, 12758, -1, 12766, 12758, 12764, -1, 12767, 12760, 12766, -1, 12767, 12761, 12760, -1, 12768, 12762, 12761, -1, 12768, 12761, 12767, -1, 12769, 12298, 12302, -1, 12769, 12302, 12763, -1, 12769, 12763, 12762, -1, 12769, 12762, 12768, -1, 12770, 12765, 12771, -1, 12770, 12764, 12765, -1, 12772, 12773, 12774, -1, 12775, 12764, 12770, -1, 12775, 12766, 12764, -1, 12776, 12767, 12766, -1, 12776, 12766, 12775, -1, 12777, 12767, 12776, -1, 12777, 12768, 12767, -1, 12778, 12768, 12777, -1, 12256, 12253, 12779, -1, 12778, 12298, 12769, -1, 12778, 12294, 12298, -1, 12778, 12769, 12768, -1, 12780, 12781, 12782, -1, 12780, 12783, 12781, -1, 12784, 12771, 12785, -1, 12784, 12770, 12771, -1, 12786, 12783, 12780, -1, 12787, 12770, 12784, -1, 12786, 12788, 12783, -1, 12787, 12775, 12770, -1, 12789, 12776, 12775, -1, 12789, 12775, 12787, -1, 12790, 12791, 12788, -1, 12790, 12788, 12786, -1, 12792, 12791, 12790, -1, 12792, 12793, 12791, -1, 12794, 12776, 12789, -1, 12795, 12793, 12792, -1, 12794, 12777, 12776, -1, 12796, 12778, 12777, -1, 12795, 12309, 12313, -1, 12796, 12294, 12778, -1, 12795, 12797, 12793, -1, 12796, 12777, 12794, -1, 12795, 12313, 12797, -1, 12796, 12290, 12294, -1, 12798, 12782, 12799, -1, 12800, 12785, 12801, -1, 12798, 12780, 12782, -1, 12802, 12786, 12780, -1, 12800, 12784, 12785, -1, 12802, 12780, 12798, -1, 12803, 12784, 12800, -1, 12803, 12787, 12784, -1, 12804, 12789, 12787, -1, 12805, 12786, 12802, -1, 12805, 12790, 12786, -1, 12804, 12787, 12803, -1, 12806, 12790, 12805, -1, 12807, 12794, 12789, -1, 12806, 12792, 12790, -1, 12808, 12309, 12795, -1, 12807, 12789, 12804, -1, 12808, 12795, 12792, -1, 12808, 12792, 12806, -1, 12809, 12796, 12794, -1, 12809, 12290, 12796, -1, 12808, 12305, 12309, -1, 12809, 12794, 12807, -1, 12809, 12286, 12290, -1, 12810, 12801, 12811, -1, 12812, 12799, 12813, -1, 12810, 12800, 12801, -1, 12812, 12798, 12799, -1, 12814, 12798, 12812, -1, 12815, 12803, 12800, -1, 12814, 12802, 12798, -1, 12815, 12800, 12810, -1, 12816, 12805, 12802, -1, 12816, 12802, 12814, -1, 12817, 12804, 12803, -1, 12818, 12805, 12816, -1, 12817, 12803, 12815, -1, 12819, 12807, 12804, -1, 12818, 12806, 12805, -1, 12819, 12804, 12817, -1, 12820, 12806, 12818, -1, 12820, 12305, 12808, -1, 12821, 12807, 12819, -1, 12820, 12808, 12806, -1, 12821, 12809, 12807, -1, 12821, 12286, 12809, -1, 12820, 12301, 12305, -1, 12821, 12282, 12286, -1, 12822, 12812, 12813, -1, 12823, 12811, 12824, -1, 12822, 12813, 12825, -1, 12823, 12810, 12811, -1, 12826, 12810, 12823, -1, 12826, 12815, 12810, -1, 12827, 12814, 12812, -1, 12827, 12812, 12822, -1, 12828, 12816, 12814, -1, 12829, 12815, 12826, -1, 12828, 12814, 12827, -1, 12829, 12817, 12815, -1, 12830, 12816, 12828, -1, 12831, 12819, 12817, -1, 12830, 12818, 12816, -1, 12832, 12820, 12818, -1, 12832, 12818, 12830, -1, 12831, 12817, 12829, -1, 12833, 12821, 12819, -1, 12832, 12301, 12820, -1, 12833, 12282, 12821, -1, 12833, 12273, 12277, -1, 12832, 12297, 12301, -1, 12833, 12277, 12282, -1, 12833, 12819, 12831, -1, 12834, 12824, 12835, -1, 12836, 12825, 12837, -1, 12834, 12823, 12824, -1, 12836, 12822, 12825, -1, 12838, 12827, 12822, -1, 12839, 12823, 12834, -1, 12838, 12822, 12836, -1, 12839, 12826, 12823, -1, 12840, 12828, 12827, -1, 12841, 12829, 12826, -1, 12840, 12827, 12838, -1, 12842, 12830, 12828, -1, 12841, 12826, 12839, -1, 12843, 12829, 12841, -1, 12843, 12831, 12829, -1, 12842, 12828, 12840, -1, 12844, 12297, 12832, -1, 12844, 12832, 12830, -1, 12845, 12273, 12833, -1, 12844, 12293, 12297, -1, 12845, 12833, 12831, -1, 12844, 12830, 12842, -1, 12846, 12836, 12837, -1, 12845, 12831, 12843, -1, 12847, 12835, 12848, -1, 12846, 12837, 12849, -1, 12847, 12834, 12835, -1, 12850, 12836, 12846, -1, 12851, 12839, 12834, -1, 12851, 12834, 12847, -1, 12850, 12838, 12836, -1, 12852, 12838, 12850, -1, 12852, 12840, 12838, -1, 12853, 12841, 12839, -1, 12853, 12839, 12851, -1, 12854, 12840, 12852, -1, 12855, 12843, 12841, -1, 12854, 12842, 12840, -1, 12856, 12844, 12842, -1, 12855, 12841, 12853, -1, 12856, 12842, 12854, -1, 12856, 12293, 12844, -1, 12857, 12263, 12268, -1, 12857, 12268, 12273, -1, 12857, 12273, 12845, -1, 12856, 12289, 12293, -1, 12857, 12843, 12855, -1, 12858, 12846, 12849, -1, 12857, 12845, 12843, -1, 12858, 12849, 12859, -1, 12860, 12848, 12861, -1, 12860, 12847, 12848, -1, 12862, 12850, 12846, -1, 12863, 12851, 12847, -1, 12862, 12846, 12858, -1, 12863, 12847, 12860, -1, 12864, 12852, 12850, -1, 12864, 12850, 12862, -1, 12865, 12851, 12863, -1, 12865, 12853, 12851, -1, 12866, 12852, 12864, -1, 12867, 12853, 12865, -1, 12866, 12854, 12852, -1, 12868, 12856, 12854, -1, 12867, 12855, 12853, -1, 12868, 12854, 12866, -1, 12869, 12855, 12867, -1, 12869, 12263, 12857, -1, 12868, 12285, 12289, -1, 12869, 12857, 12855, -1, 12868, 12289, 12856, -1, 12870, 12858, 12859, -1, 12871, 12861, 12872, -1, 12870, 12859, 12873, -1, 12871, 12860, 12861, -1, 12874, 12862, 12858, -1, 12875, 12863, 12860, -1, 12874, 12858, 12870, -1, 12875, 12860, 12871, -1, 12876, 12863, 12875, -1, 12877, 12862, 12874, -1, 12876, 12865, 12863, -1, 12877, 12864, 12862, -1, 12878, 12866, 12864, -1, 12879, 12865, 12876, -1, 12878, 12864, 12877, -1, 12879, 12867, 12865, -1, 12880, 12869, 12867, -1, 12880, 12263, 12869, -1, 12881, 12281, 12285, -1, 12881, 12285, 12868, -1, 12880, 12867, 12879, -1, 12881, 12866, 12878, -1, 12880, 12253, 12259, -1, 12881, 12868, 12866, -1, 12880, 12259, 12263, -1, 12882, 12873, 12883, -1, 12884, 12872, 12773, -1, 12884, 12772, 12885, -1, 12882, 12870, 12873, -1, 12884, 12773, 12772, -1, 12886, 12874, 12870, -1, 12884, 12871, 12872, -1, 12887, 12875, 12871, -1, 12886, 12870, 12882, -1, 12887, 12884, 12885, -1, 12887, 12885, 12888, -1, 12887, 12871, 12884, -1, 12889, 12876, 12875, -1, 12890, 12877, 12874, -1, 12889, 12875, 12887, -1, 12890, 12874, 12886, -1, 12889, 12887, 12888, -1, 12891, 12877, 12890, -1, 12889, 12888, 12892, -1, 12893, 12879, 12876, -1, 12891, 12878, 12877, -1, 12893, 12876, 12889, -1, 12894, 12878, 12891, -1, 12893, 12889, 12892, -1, 12893, 12892, 12779, -1, 12894, 12278, 12281, -1, 12895, 12879, 12893, -1, 12894, 12281, 12881, -1, 12895, 12880, 12879, -1, 12894, 12881, 12878, -1, 12895, 12253, 12880, -1, 12895, 12893, 12779, -1, 12895, 12779, 12253, -1, 12896, 12883, 12897, -1, 12896, 12882, 12883, -1, 12898, 12882, 12896, -1, 12898, 12886, 12882, -1, 12899, 12890, 12886, -1, 12899, 12886, 12898, -1, 12900, 12890, 12899, -1, 12900, 12891, 12890, -1, 12901, 12894, 12891, -1, 12901, 12278, 12894, -1, 12901, 12891, 12900, -1, 12901, 12275, 12278, -1, 12902, 12897, 12903, -1, 12902, 12896, 12897, -1, 12904, 12896, 12902, -1, 12904, 12898, 12896, -1, 12905, 12898, 12904, -1, 12905, 12899, 12898, -1, 12906, 12899, 12905, -1, 12906, 12900, 12899, -1, 12907, 12900, 12906, -1, 12907, 12901, 12900, -1, 12907, 12275, 12901, -1, 12907, 12271, 12275, -1, 12908, 12903, 12909, -1, 12908, 12902, 12903, -1, 12910, 12904, 12902, -1, 12910, 12902, 12908, -1, 12911, 12905, 12904, -1, 12911, 12904, 12910, -1, 12912, 12906, 12905, -1, 12912, 12905, 12911, -1, 12913, 12907, 12906, -1, 12913, 12271, 12907, -1, 12913, 12906, 12912, -1, 12913, 12267, 12271, -1, 12914, 12909, 12915, -1, 12914, 12908, 12909, -1, 12916, 12910, 12908, -1, 12916, 12908, 12914, -1, 12917, 12911, 12910, -1, 12917, 12910, 12916, -1, 12918, 12912, 12911, -1, 12918, 12911, 12917, -1, 12919, 12912, 12918, -1, 12919, 12913, 12912, -1, 12919, 12267, 12913, -1, 12919, 12261, 12265, -1, 12919, 12265, 12267, -1, 12920, 12915, 12921, -1, 12920, 12914, 12915, -1, 12922, 12916, 12914, -1, 12922, 12914, 12920, -1, 12923, 12917, 12916, -1, 12923, 12916, 12922, -1, 12924, 12918, 12917, -1, 12924, 12917, 12923, -1, 12925, 12919, 12918, -1, 12925, 12261, 12919, -1, 12925, 12257, 12261, -1, 12925, 12918, 12924, -1, 12926, 12921, 12927, -1, 12926, 12920, 12921, -1, 12928, 12920, 12926, -1, 12928, 12922, 12920, -1, 12929, 12923, 12922, -1, 12929, 12922, 12928, -1, 12930, 12923, 12929, -1, 12930, 12924, 12923, -1, 12931, 12257, 12925, -1, 12931, 12925, 12924, -1, 12931, 12924, 12930, -1, 12932, 12927, 12933, -1, 12932, 12926, 12927, -1, 12934, 12928, 12926, -1, 12934, 12926, 12932, -1, 12935, 12928, 12934, -1, 12935, 12929, 12928, -1, 12697, 12929, 12935, -1, 12697, 12930, 12929, -1, 12699, 12930, 12697, -1, 12699, 12251, 12257, -1, 12699, 12257, 12931, -1, 12699, 12931, 12930, -1, 12703, 12933, 12701, -1, 12703, 12932, 12933, -1, 12705, 12934, 12932, -1, 12705, 12932, 12703, -1, 12707, 12934, 12705, -1, 12707, 12935, 12934, -1, 12698, 12935, 12707, -1, 12698, 12697, 12935, -1, 12936, 12937, 12938, -1, 12936, 12939, 12937, -1, 12940, 12939, 12936, -1, 12940, 12941, 12939, -1, 12940, 12942, 12941, -1, 12940, 12943, 12942, -1, 12944, 12945, 12946, -1, 12944, 12938, 12945, -1, 12947, 12938, 12944, -1, 12947, 12936, 12938, -1, 12948, 12940, 12936, -1, 12948, 12943, 12940, -1, 12948, 12936, 12947, -1, 12949, 12950, 12951, -1, 12948, 12952, 12943, -1, 12953, 12946, 12954, -1, 12953, 12944, 12946, -1, 12955, 12944, 12953, -1, 12955, 12947, 12944, -1, 12956, 12948, 12947, -1, 12956, 12952, 12948, -1, 12956, 12947, 12955, -1, 12956, 12957, 12952, -1, 12958, 12959, 12960, -1, 12958, 12954, 12959, -1, 12958, 12953, 12954, -1, 12961, 12953, 12958, -1, 12961, 12955, 12953, -1, 12962, 12956, 12955, -1, 12962, 12957, 12956, -1, 12962, 12955, 12961, -1, 12962, 12963, 12957, -1, 12964, 12960, 12965, -1, 12964, 12958, 12960, -1, 12966, 12958, 12964, -1, 12966, 12961, 12958, -1, 12967, 12962, 12961, -1, 12967, 12963, 12962, -1, 12967, 12961, 12966, -1, 12967, 12968, 12963, -1, 12969, 12964, 12965, -1, 12970, 12964, 12969, -1, 12970, 12966, 12964, -1, 12971, 12967, 12966, -1, 12971, 12968, 12967, -1, 12971, 12966, 12970, -1, 12971, 12972, 12968, -1, 12973, 12965, 12974, -1, 12973, 12969, 12965, -1, 12975, 12969, 12973, -1, 12975, 12970, 12969, -1, 12976, 12971, 12970, -1, 12976, 12977, 12972, -1, 12976, 12972, 12971, -1, 12976, 12970, 12975, -1, 12978, 12974, 12979, -1, 12978, 12973, 12974, -1, 12980, 12973, 12978, -1, 12980, 12975, 12973, -1, 12981, 12982, 12977, -1, 12981, 12976, 12975, -1, 12981, 12977, 12976, -1, 12981, 12975, 12980, -1, 12983, 12984, 12985, -1, 12983, 12979, 12984, -1, 12983, 12985, 12986, -1, 12983, 12978, 12979, -1, 12987, 12986, 12988, -1, 12987, 12983, 12986, -1, 12987, 12978, 12983, -1, 12987, 12980, 12978, -1, 12989, 12980, 12987, -1, 12989, 12988, 12990, -1, 12989, 12990, 12991, -1, 12989, 12992, 12982, -1, 12989, 12991, 12992, -1, 12989, 12982, 12981, -1, 12989, 12981, 12980, -1, 12989, 12987, 12988, -1, 12993, 12994, 12995, -1, 12993, 12996, 12994, -1, 12997, 12996, 12993, -1, 12997, 12998, 12996, -1, 12999, 12951, 12998, -1, 12999, 12998, 12997, -1, 12999, 12949, 12951, -1, 13000, 12993, 12995, -1, 13000, 12995, 13001, -1, 13002, 12997, 12993, -1, 13002, 12993, 13000, -1, 13003, 12997, 13002, -1, 13003, 13004, 12949, -1, 13003, 12949, 12999, -1, 13003, 12999, 12997, -1, 13005, 13001, 13006, -1, 13005, 13000, 13001, -1, 13007, 13000, 13005, -1, 13007, 13002, 13000, -1, 13008, 13003, 13002, -1, 13008, 13002, 13007, -1, 13008, 13009, 13004, -1, 13008, 13004, 13003, -1, 13010, 13005, 13006, -1, 13010, 13006, 13011, -1, 13012, 13007, 13005, -1, 13012, 13005, 13010, -1, 13013, 13007, 13012, -1, 13013, 13014, 13009, -1, 13013, 13008, 13007, -1, 13013, 13009, 13008, -1, 13015, 13011, 13016, -1, 13015, 13010, 13011, -1, 13017, 13012, 13010, -1, 13017, 13010, 13015, -1, 13018, 13012, 13017, -1, 13018, 13013, 13012, -1, 13018, 13019, 13014, -1, 13018, 13014, 13013, -1, 13020, 13016, 13021, -1, 13020, 13015, 13016, -1, 13022, 13017, 13015, -1, 13022, 13015, 13020, -1, 13023, 13018, 13017, -1, 13023, 13024, 13019, -1, 13023, 13017, 13022, -1, 13023, 13019, 13018, -1, 13025, 13021, 13026, -1, 13025, 13020, 13021, -1, 13027, 13022, 13020, -1, 13027, 13020, 13025, -1, 13028, 13024, 13023, -1, 13028, 13022, 13027, -1, 13028, 13023, 13022, -1, 13028, 13029, 13024, -1, 13030, 13025, 13026, -1, 13030, 13026, 13031, -1, 13032, 13027, 13025, -1, 13032, 13025, 13030, -1, 13033, 13028, 13027, -1, 13033, 13027, 13032, -1, 13033, 13034, 13029, -1, 13033, 13029, 13028, -1, 13035, 13031, 13036, -1, 13035, 13030, 13031, -1, 13037, 13030, 13035, -1, 13037, 13032, 13030, -1, 13038, 13034, 13033, -1, 13038, 13033, 13032, -1, 13038, 13039, 13034, -1, 13038, 13032, 13037, -1, 13040, 13036, 13041, -1, 13040, 13035, 13036, -1, 13042, 13037, 13035, -1, 13042, 13035, 13040, -1, 13043, 13039, 13038, -1, 13043, 13038, 13037, -1, 13043, 13044, 13039, -1, 13043, 13037, 13042, -1, 13045, 13040, 13041, -1, 13045, 13041, 13046, -1, 13047, 13042, 13040, -1, 13047, 13040, 13045, -1, 13048, 13043, 13042, -1, 13048, 13044, 13043, -1, 13048, 13049, 13044, -1, 13048, 13042, 13047, -1, 13050, 13046, 13051, -1, 13050, 13045, 13046, -1, 13052, 13047, 13045, -1, 13052, 13045, 13050, -1, 13053, 13047, 13052, -1, 13053, 13054, 13049, -1, 13053, 13049, 13048, -1, 13053, 13048, 13047, -1, 13055, 13051, 13056, -1, 13055, 13050, 13051, -1, 13057, 13052, 13050, -1, 13057, 13050, 13055, -1, 13058, 13053, 13052, -1, 13058, 13059, 13054, -1, 13058, 13054, 13053, -1, 13058, 13052, 13057, -1, 13060, 13056, 13061, -1, 13060, 13055, 13056, -1, 13062, 13057, 13055, -1, 13062, 13055, 13060, -1, 13063, 13064, 13059, -1, 13063, 13058, 13057, -1, 13063, 13059, 13058, -1, 13063, 13057, 13062, -1, 13065, 13061, 13066, -1, 13065, 13060, 13061, -1, 13067, 13062, 13060, -1, 13067, 13060, 13065, -1, 13068, 13069, 13064, -1, 13068, 13064, 13063, -1, 13068, 13063, 13062, -1, 13068, 13062, 13067, -1, 13070, 13066, 13071, -1, 13070, 13065, 13066, -1, 13072, 13065, 13070, -1, 13072, 13067, 13065, -1, 13073, 13068, 13067, -1, 13073, 13067, 13072, -1, 13073, 13074, 13069, -1, 13073, 13069, 13068, -1, 13075, 13071, 13076, -1, 13075, 13070, 13071, -1, 13077, 13070, 13075, -1, 13077, 13072, 13070, -1, 13078, 13074, 13073, -1, 13078, 13072, 13077, -1, 13078, 13073, 13072, -1, 13078, 13079, 13074, -1, 13080, 13076, 13081, -1, 13080, 13075, 13076, -1, 13082, 13077, 13075, -1, 13082, 13075, 13080, -1, 13083, 13078, 13077, -1, 13083, 13079, 13078, -1, 13083, 13077, 13082, -1, 13083, 13084, 13079, -1, 13085, 13081, 13086, -1, 13085, 13080, 13081, -1, 13087, 13080, 13085, -1, 13087, 13082, 13080, -1, 13088, 13083, 13082, -1, 13088, 13084, 13083, -1, 13088, 13089, 13084, -1, 13088, 13082, 13087, -1, 13090, 13086, 13091, -1, 13090, 13085, 13086, -1, 13092, 13087, 13085, -1, 13092, 13085, 13090, -1, 13093, 13088, 13087, -1, 13093, 13089, 13088, -1, 13093, 13087, 13092, -1, 13093, 13094, 13089, -1, 13095, 13091, 13096, -1, 13095, 13090, 13091, -1, 13097, 13092, 13090, -1, 13097, 13090, 13095, -1, 13098, 13093, 13092, -1, 13098, 13094, 13093, -1, 13098, 13092, 13097, -1, 13098, 13099, 13094, -1, 13100, 13096, 13101, -1, 13100, 13095, 13096, -1, 13102, 13097, 13095, -1, 13102, 13095, 13100, -1, 13103, 13098, 13097, -1, 13103, 13099, 13098, -1, 13103, 13097, 13102, -1, 13103, 13104, 13099, -1, 13105, 13101, 13106, -1, 13105, 13100, 13101, -1, 13107, 13102, 13100, -1, 13107, 13100, 13105, -1, 13108, 13103, 13102, -1, 13108, 13104, 13103, -1, 13108, 13102, 13107, -1, 13108, 13109, 13104, -1, 13110, 13106, 13111, -1, 13110, 13105, 13106, -1, 13112, 13107, 13105, -1, 13112, 13105, 13110, -1, 13113, 13114, 13109, -1, 13113, 13108, 13107, -1, 13113, 13109, 13108, -1, 13113, 13107, 13112, -1, 13115, 13111, 13116, -1, 13115, 13110, 13111, -1, 13117, 13112, 13110, -1, 13117, 13110, 13115, -1, 13118, 13119, 13114, -1, 13118, 13114, 13113, -1, 13118, 13113, 13112, -1, 13118, 13112, 13117, -1, 13120, 13116, 13121, -1, 13120, 13115, 13116, -1, 13122, 13115, 13120, -1, 13122, 13117, 13115, -1, 13123, 13124, 13119, -1, 13123, 13118, 13117, -1, 13123, 13119, 13118, -1, 13123, 13117, 13122, -1, 13125, 13121, 13126, -1, 13125, 13120, 13121, -1, 13127, 13120, 13125, -1, 13127, 13122, 13120, -1, 13128, 13122, 13127, -1, 13128, 13129, 13124, -1, 13128, 13124, 13123, -1, 13128, 13123, 13122, -1, 13130, 13126, 13131, -1, 13130, 13125, 13126, -1, 13132, 13127, 13125, -1, 13132, 13125, 13130, -1, 13133, 13128, 13127, -1, 13133, 13127, 13132, -1, 13133, 13134, 13129, -1, 13133, 13129, 13128, -1, 12937, 13131, 13135, -1, 12937, 13130, 13131, -1, 12939, 13130, 12937, -1, 12939, 13132, 13130, -1, 12941, 13133, 13132, -1, 12941, 13134, 13133, -1, 12941, 13132, 12939, -1, 12941, 12942, 13134, -1, 12938, 12937, 13135, -1, 12938, 13135, 12945, -1, 13136, 12319, 12317, -1, 13136, 13137, 12319, -1, 13138, 12317, 12315, -1, 13138, 13136, 12317, -1, 13139, 12310, 12306, -1, 13139, 12306, 12304, -1, 13139, 13140, 12310, -1, 13141, 13138, 12315, -1, 13142, 12304, 12299, -1, 13142, 13139, 12304, -1, 13143, 12315, 12312, -1, 13143, 12312, 12308, -1, 13143, 13141, 12315, -1, 13144, 12299, 12295, -1, 13144, 13142, 12299, -1, 13145, 13143, 12308, -1, 13146, 13144, 12295, -1, 13147, 12308, 12303, -1, 13147, 12303, 12300, -1, 13147, 13145, 12308, -1, 13148, 13146, 12295, -1, 13148, 12295, 12292, -1, 13148, 12292, 12288, -1, 13149, 13147, 12300, -1, 13150, 13148, 12288, -1, 13151, 12300, 12296, -1, 13151, 13149, 12300, -1, 13152, 12288, 12284, -1, 13152, 12284, 12280, -1, 13152, 13150, 12288, -1, 13153, 12296, 12291, -1, 13153, 13151, 12296, -1, 13154, 12280, 12276, -1, 13154, 13152, 12280, -1, 13155, 12291, 12287, -1, 13155, 12287, 12283, -1, 13156, 13154, 12276, -1, 13155, 13153, 12291, -1, 13157, 13155, 12283, -1, 13158, 12276, 12272, -1, 13158, 12272, 12270, -1, 13158, 13156, 12276, -1, 13159, 13157, 12283, -1, 13159, 12283, 12279, -1, 13159, 12279, 12274, -1, 13160, 12270, 12266, -1, 13160, 13158, 12270, -1, 13161, 13159, 12274, -1, 13162, 13160, 12266, -1, 13163, 13161, 12274, -1, 13164, 12266, 12262, -1, 13163, 12274, 12269, -1, 13164, 12262, 12258, -1, 13163, 12269, 12264, -1, 13164, 13162, 12266, -1, 13165, 13163, 12264, -1, 13166, 13164, 12258, -1, 13167, 13165, 12264, -1, 13167, 12264, 12260, -1, 13167, 12260, 12255, -1, 13168, 12258, 12252, -1, 13168, 12252, 12250, -1, 13168, 13166, 12258, -1, 13169, 13167, 12255, -1, 13170, 13169, 12255, -1, 13171, 12250, 12249, -1, 13171, 13168, 12250, -1, 13170, 12255, 12254, -1, 13172, 13171, 12249, -1, 13173, 12249, 12325, -1, 13173, 13172, 12249, -1, 13174, 12325, 12323, -1, 13174, 13173, 12325, -1, 13137, 12323, 12321, -1, 13137, 12321, 12319, -1, 13137, 13174, 12323, -1, 12723, 12717, 13081, -1, 12729, 13076, 13071, -1, 12729, 12723, 13076, -1, 12781, 12985, 12984, -1, 12735, 13071, 13066, -1, 12735, 12729, 13071, -1, 12782, 12984, 12979, -1, 12782, 12781, 12984, -1, 12741, 13066, 13061, -1, 12741, 12735, 13066, -1, 12799, 12979, 12974, -1, 12799, 12782, 12979, -1, 12747, 13061, 13056, -1, 12747, 12741, 13061, -1, 12813, 12974, 12965, -1, 12813, 12799, 12974, -1, 12753, 13056, 13051, -1, 12753, 12747, 13056, -1, 12825, 12813, 12965, -1, 12825, 12965, 12960, -1, 12759, 13051, 13046, -1, 12759, 12753, 13051, -1, 12837, 12825, 12960, -1, 12837, 12960, 12959, -1, 12765, 13046, 13041, -1, 12765, 12759, 13046, -1, 12849, 12837, 12959, -1, 12849, 12959, 12954, -1, 12771, 13041, 13036, -1, 12771, 12765, 13041, -1, 12859, 12954, 12946, -1, 12859, 12849, 12954, -1, 12785, 13036, 13031, -1, 12785, 12771, 13036, -1, 12873, 12946, 12945, -1, 12873, 12859, 12946, -1, 12801, 12785, 13031, -1, 12801, 13031, 13026, -1, 12883, 12945, 13135, -1, 12883, 12873, 12945, -1, 12811, 12801, 13026, -1, 12811, 13026, 13021, -1, 12897, 13135, 13131, -1, 12897, 12883, 13135, -1, 12824, 12811, 13021, -1, 12824, 13021, 13016, -1, 12903, 13131, 13126, -1, 12903, 12897, 13131, -1, 12835, 12824, 13016, -1, 12835, 13016, 13011, -1, 12909, 13126, 13121, -1, 12909, 12903, 13126, -1, 12848, 12835, 13011, -1, 12848, 13011, 13006, -1, 12915, 13121, 13116, -1, 12915, 12909, 13121, -1, 12861, 12848, 13006, -1, 12861, 13006, 13001, -1, 12921, 13116, 13111, -1, 12921, 12915, 13116, -1, 12872, 12861, 13001, -1, 12872, 13001, 12995, -1, 12927, 13111, 13106, -1, 12927, 12921, 13111, -1, 12773, 12872, 12995, -1, 12773, 12995, 12994, -1, 12774, 12773, 12994, -1, 12933, 13106, 13101, -1, 12933, 12927, 13106, -1, 12701, 13101, 13096, -1, 12701, 12933, 13101, -1, 12702, 13096, 13091, -1, 12702, 12701, 13096, -1, 12711, 13091, 13086, -1, 12711, 12702, 13091, -1, 12717, 13086, 13081, -1, 12717, 12711, 13086, -1, 12723, 13081, 13076, -1, 13175, 13176, 11419, -1, 13175, 12957, 13176, -1, 13175, 12952, 12957, -1, 13177, 12952, 13175, -1, 13177, 11411, 11407, -1, 13177, 12943, 12952, -1, 13177, 13175, 11411, -1, 13178, 11407, 11403, -1, 13178, 13177, 11407, -1, 13178, 12943, 13177, -1, 13178, 13134, 12942, -1, 13178, 12942, 12943, -1, 13179, 11403, 11399, -1, 13179, 11399, 11395, -1, 13179, 13134, 13178, -1, 13179, 13178, 11403, -1, 13179, 13129, 13134, -1, 13180, 13179, 11395, -1, 13180, 11395, 11391, -1, 13180, 13119, 13124, -1, 13180, 13124, 13129, -1, 13180, 13129, 13179, -1, 13181, 11391, 11387, -1, 13181, 13114, 13119, -1, 13181, 13119, 13180, -1, 13181, 13180, 11391, -1, 13182, 11387, 11383, -1, 13182, 11383, 11379, -1, 13182, 13114, 13181, -1, 13182, 13181, 11387, -1, 13182, 13104, 13109, -1, 13182, 13109, 13114, -1, 13183, 11379, 11375, -1, 13183, 13104, 13182, -1, 13183, 13182, 11379, -1, 13183, 13099, 13104, -1, 13184, 13183, 11375, -1, 13184, 11375, 11371, -1, 13184, 13089, 13094, -1, 13184, 13094, 13099, -1, 13184, 13099, 13183, -1, 13185, 11371, 11367, -1, 13185, 11367, 11363, -1, 13185, 13184, 11371, -1, 13185, 13089, 13184, -1, 13185, 13084, 13089, -1, 13186, 11363, 11359, -1, 13186, 13079, 13084, -1, 13186, 13084, 13185, -1, 13186, 13185, 11363, -1, 13187, 11359, 11355, -1, 13187, 11355, 11351, -1, 13187, 13069, 13074, -1, 13187, 13074, 13079, -1, 13187, 13186, 11359, -1, 13187, 13079, 13186, -1, 13188, 13069, 13187, -1, 13188, 13187, 11351, -1, 13188, 11351, 11347, -1, 13188, 13064, 13069, -1, 13189, 13188, 11347, -1, 13189, 13064, 13188, -1, 13189, 11347, 11343, -1, 13189, 13054, 13059, -1, 13189, 13059, 13064, -1, 13190, 13189, 11343, -1, 13190, 11343, 11339, -1, 13190, 11339, 11335, -1, 13190, 13054, 13189, -1, 13190, 13049, 13054, -1, 13191, 11335, 11331, -1, 13191, 13190, 11335, -1, 13191, 13039, 13044, -1, 13191, 13044, 13049, -1, 13191, 13049, 13190, -1, 13192, 11331, 11327, -1, 13192, 13191, 11331, -1, 13192, 13034, 13039, -1, 13192, 13039, 13191, -1, 13193, 11327, 11323, -1, 13193, 11323, 11319, -1, 13193, 13192, 11327, -1, 13193, 13029, 13034, -1, 13193, 13034, 13192, -1, 13194, 13029, 13193, -1, 13194, 11319, 11315, -1, 13194, 13019, 13024, -1, 13194, 13024, 13029, -1, 13194, 13193, 11319, -1, 13195, 11315, 11311, -1, 13195, 11311, 11307, -1, 13195, 13014, 13019, -1, 13195, 13019, 13194, -1, 13195, 13194, 11315, -1, 13196, 13195, 11307, -1, 13196, 11307, 11303, -1, 13196, 13004, 13009, -1, 13196, 13009, 13014, -1, 13196, 13014, 13195, -1, 13197, 13004, 13196, -1, 13197, 11303, 11296, -1, 13197, 12949, 13004, -1, 13197, 13196, 11303, -1, 13198, 11440, 11439, -1, 13198, 11439, 13199, -1, 13200, 13198, 13199, -1, 13200, 12992, 12991, -1, 13200, 12991, 11440, -1, 13200, 11440, 13198, -1, 13200, 13199, 12992, -1, 13201, 13197, 11296, -1, 13201, 11296, 11295, -1, 13202, 13197, 13201, -1, 13202, 12949, 13197, -1, 13202, 13201, 11295, -1, 13202, 11295, 12950, -1, 13202, 12950, 12949, -1, 13199, 11439, 11435, -1, 13199, 12982, 12992, -1, 13203, 11435, 11431, -1, 13203, 12972, 12977, -1, 13203, 12977, 12982, -1, 13203, 13199, 11435, -1, 13203, 12982, 13199, -1, 13204, 11431, 11427, -1, 13204, 11427, 11423, -1, 13204, 12972, 13203, -1, 13204, 13203, 11431, -1, 13204, 12968, 12972, -1, 13176, 11423, 11419, -1, 13176, 13204, 11423, -1, 13176, 12968, 13204, -1, 13176, 12957, 12963, -1, 13176, 12963, 12968, -1, 13175, 11419, 11415, -1, 13175, 11415, 11411, -1, 13205, 11313, 13206, -1, 13205, 13207, 13208, -1, 13205, 13206, 13207, -1, 13209, 13205, 13208, -1, 13209, 13208, 13210, -1, 13211, 13205, 13209, -1, 13212, 13209, 13210, -1, 13212, 13210, 13213, -1, 13212, 13213, 13214, -1, 13215, 13205, 13211, -1, 13216, 13217, 13218, -1, 13215, 11313, 13205, -1, 13215, 11309, 11313, -1, 13219, 13211, 13209, -1, 13220, 13221, 13222, -1, 13219, 13215, 13211, -1, 13219, 11309, 13215, -1, 13219, 13209, 13212, -1, 13223, 13216, 13218, -1, 13224, 13212, 13214, -1, 13224, 13214, 13225, -1, 13226, 13225, 13227, -1, 13228, 13212, 13224, -1, 13228, 13219, 13212, -1, 13229, 13224, 13225, -1, 13230, 13231, 13232, -1, 13229, 13225, 13226, -1, 13233, 11309, 13219, -1, 13233, 13219, 13228, -1, 13233, 11305, 11309, -1, 13234, 13226, 13227, -1, 13234, 13227, 13235, -1, 13236, 13224, 13229, -1, 13236, 11305, 13233, -1, 13236, 13233, 13228, -1, 13236, 13228, 13224, -1, 13237, 13229, 13226, -1, 13237, 13226, 13234, -1, 13238, 13234, 13235, -1, 13238, 13235, 13239, -1, 13238, 13240, 13241, -1, 13238, 13239, 13240, -1, 13238, 13241, 13242, -1, 13243, 13236, 13229, -1, 13243, 13229, 13237, -1, 13243, 13237, 13244, -1, 13245, 13244, 13237, -1, 13245, 13237, 13234, -1, 13245, 13234, 13238, -1, 13245, 13238, 13242, -1, 13245, 13242, 13246, -1, 13245, 13246, 13244, -1, 13247, 11305, 13236, -1, 13247, 13236, 13243, -1, 13247, 11299, 11305, -1, 13248, 13243, 13244, -1, 13248, 11299, 13247, -1, 13248, 13247, 13243, -1, 13248, 13244, 13249, -1, 13248, 13249, 13250, -1, 13248, 13250, 13251, -1, 13252, 13231, 13230, -1, 13252, 11292, 11291, -1, 13252, 13253, 13231, -1, 13252, 11291, 13253, -1, 13252, 13230, 13254, -1, 13252, 13255, 11292, -1, 13252, 13254, 13255, -1, 13256, 13257, 13258, -1, 13256, 11397, 11401, -1, 13256, 13258, 11397, -1, 13256, 13259, 13260, -1, 13256, 13260, 13257, -1, 13256, 13261, 13259, -1, 13256, 11401, 13261, -1, 13262, 13263, 13264, -1, 13262, 13264, 13265, -1, 13262, 11345, 13266, -1, 13262, 13267, 11341, -1, 13262, 13266, 13263, -1, 13262, 13265, 13267, -1, 13262, 11341, 11345, -1, 13268, 11299, 13248, -1, 13239, 13235, 13269, -1, 13268, 13248, 13251, -1, 13268, 13251, 13270, -1, 13268, 13270, 13271, -1, 13268, 13271, 13272, -1, 13268, 13272, 11300, -1, 13268, 11300, 11299, -1, 13273, 13241, 13240, -1, 13274, 13273, 13240, -1, 13271, 13270, 13275, -1, 13276, 13223, 13218, -1, 13276, 13221, 13220, -1, 13276, 13277, 13223, -1, 13276, 13218, 13221, -1, 13278, 13279, 13280, -1, 13278, 13280, 13277, -1, 13278, 13277, 13276, -1, 13281, 13220, 13282, -1, 13281, 13276, 13220, -1, 11417, 13283, 13284, -1, 13255, 13254, 13285, -1, 11417, 13284, 13286, -1, 13255, 13285, 13287, -1, 11417, 13286, 13288, -1, 13255, 13287, 13279, -1, 13289, 13276, 13281, -1, 13289, 13278, 13276, -1, 13289, 13279, 13278, -1, 13290, 13281, 13282, -1, 13291, 13255, 13279, -1, 13291, 13279, 13289, -1, 13292, 13289, 13281, -1, 13292, 13290, 13282, -1, 13292, 13281, 13290, -1, 13293, 11292, 13255, -1, 13293, 13255, 13291, -1, 13294, 13282, 13295, -1, 13296, 13289, 13292, -1, 13296, 13291, 13289, -1, 13297, 13292, 13282, -1, 13297, 13282, 13294, -1, 13297, 13294, 13295, -1, 13298, 11437, 11292, -1, 13298, 11292, 13293, -1, 13298, 13293, 13291, -1, 13298, 13291, 13296, -1, 13299, 13292, 13297, -1, 13299, 13296, 13292, -1, 13300, 13297, 13295, -1, 13300, 13295, 13301, -1, 13300, 13301, 13302, -1, 13303, 13298, 13296, -1, 13303, 11437, 13298, -1, 13303, 13296, 13299, -1, 13304, 13299, 13297, -1, 13304, 13297, 13300, -1, 13305, 13300, 13302, -1, 13306, 11433, 11437, -1, 13306, 13299, 13304, -1, 13306, 13303, 13299, -1, 13306, 11437, 13303, -1, 13307, 13300, 13305, -1, 13307, 13304, 13300, -1, 13308, 13305, 13302, -1, 13308, 13302, 13309, -1, 13310, 11433, 13306, -1, 13310, 13306, 13304, -1, 13310, 13304, 13307, -1, 13311, 13307, 13305, -1, 13311, 13305, 13308, -1, 13311, 13308, 13309, -1, 13312, 13310, 13307, -1, 13312, 11429, 11433, -1, 13312, 11433, 13310, -1, 13312, 13307, 13311, -1, 13313, 13311, 13309, -1, 13313, 13309, 13314, -1, 13315, 13312, 13311, -1, 13315, 13313, 13314, -1, 13315, 11429, 13312, -1, 13315, 13311, 13313, -1, 13316, 11425, 11429, -1, 13316, 13315, 13314, -1, 13316, 13314, 13317, -1, 13316, 11429, 13315, -1, 13316, 13317, 11425, -1, 13318, 13317, 13319, -1, 13318, 13319, 13320, -1, 13318, 11425, 13317, -1, 13321, 13318, 13320, -1, 13321, 11421, 11425, -1, 13321, 11425, 13318, -1, 13321, 13320, 13322, -1, 13321, 13322, 13323, -1, 13321, 13323, 11421, -1, 13324, 11417, 11421, -1, 13324, 13323, 13325, -1, 13324, 13325, 13326, -1, 13324, 11421, 13323, -1, 13327, 13324, 13326, -1, 13327, 13326, 13283, -1, 13327, 11417, 13324, -1, 13327, 13283, 11417, -1, 13328, 11413, 11417, -1, 13328, 13288, 13329, -1, 13328, 13329, 13330, -1, 13328, 11417, 13288, -1, 13331, 11413, 13328, -1, 13331, 13328, 13330, -1, 13331, 13330, 13332, -1, 13331, 13332, 13333, -1, 13334, 13333, 13335, -1, 13334, 13331, 13333, -1, 13336, 13335, 13337, -1, 13338, 11409, 11413, -1, 13338, 11413, 13331, -1, 13338, 13331, 13334, -1, 13339, 11397, 13340, -1, 13341, 13338, 13334, -1, 13341, 11409, 13338, -1, 13341, 13334, 13335, -1, 13341, 13335, 13336, -1, 13342, 13337, 13343, -1, 13342, 13336, 13337, -1, 13344, 13343, 13345, -1, 13346, 13341, 13336, -1, 13346, 13336, 13342, -1, 13347, 13342, 13343, -1, 13347, 13343, 13344, -1, 13347, 13344, 13345, -1, 13348, 11405, 11409, -1, 13348, 13341, 13346, -1, 13348, 11409, 13341, -1, 11393, 11397, 13339, -1, 11393, 13339, 13349, -1, 13350, 13342, 13347, -1, 13350, 13348, 13346, -1, 13350, 11405, 13348, -1, 13350, 13346, 13342, -1, 13351, 13345, 13352, -1, 13351, 13347, 13345, -1, 13353, 13352, 13345, -1, 13353, 13345, 13354, -1, 13355, 13350, 13347, -1, 13355, 13347, 13351, -1, 13356, 13351, 13352, -1, 13356, 13357, 13358, -1, 13356, 13352, 13353, -1, 13356, 13353, 13357, -1, 13359, 11401, 11405, -1, 13359, 11405, 13350, -1, 13359, 13350, 13355, -1, 13360, 13353, 13354, -1, 13360, 13361, 13362, -1, 13360, 13362, 13363, -1, 13360, 13363, 13357, -1, 13360, 13357, 13353, -1, 13261, 13358, 13259, -1, 13261, 13351, 13356, -1, 13261, 13356, 13358, -1, 13261, 11401, 13359, -1, 13261, 13359, 13355, -1, 13261, 13355, 13351, -1, 13364, 13365, 13361, -1, 13364, 13354, 13366, -1, 13364, 13361, 13360, -1, 13364, 13360, 13354, -1, 13258, 13340, 11397, -1, 13258, 13257, 13367, -1, 13258, 13367, 13340, -1, 13368, 13365, 13364, -1, 13368, 13364, 13366, -1, 13369, 13368, 13366, -1, 13369, 13370, 13365, -1, 13369, 13371, 13370, -1, 13369, 13366, 13371, -1, 13369, 13365, 13368, -1, 13372, 11393, 13349, -1, 13372, 13349, 13373, -1, 13372, 13373, 13374, -1, 13372, 13374, 13375, -1, 13376, 13370, 13371, -1, 13377, 13376, 13371, -1, 13377, 13378, 13379, -1, 13377, 13371, 13378, -1, 13380, 11389, 11393, -1, 13380, 13372, 13375, -1, 13380, 11393, 13372, -1, 13380, 13375, 13381, -1, 13382, 13379, 13370, -1, 13382, 13370, 13376, -1, 13382, 13377, 13379, -1, 13382, 13376, 13377, -1, 13383, 13379, 13378, -1, 13383, 13378, 13384, -1, 13385, 13380, 13381, -1, 13385, 11389, 13380, -1, 13385, 13381, 13386, -1, 13387, 13379, 13383, -1, 13387, 13383, 13384, -1, 13387, 13388, 13379, -1, 13389, 11385, 11389, -1, 13389, 11389, 13385, -1, 13389, 13385, 13386, -1, 13389, 13386, 13390, -1, 13391, 13387, 13384, -1, 13391, 13388, 13387, -1, 13391, 13384, 13392, -1, 13393, 13390, 13394, -1, 13393, 11385, 13389, -1, 13393, 13389, 13390, -1, 13395, 13394, 13396, -1, 13395, 13393, 13394, -1, 13397, 13391, 13392, -1, 13397, 13388, 13391, -1, 13398, 11381, 11385, -1, 13398, 11385, 13393, -1, 13398, 13393, 13395, -1, 13399, 13395, 13396, -1, 13400, 13401, 13388, -1, 13400, 13392, 13402, -1, 13400, 13388, 13397, -1, 13400, 13397, 13392, -1, 13403, 11381, 13398, -1, 13403, 13398, 13395, -1, 13403, 13395, 13399, -1, 13404, 13396, 13405, -1, 13404, 13399, 13396, -1, 13406, 13407, 13401, -1, 13406, 13401, 13400, -1, 13406, 13400, 13402, -1, 13408, 13403, 13399, -1, 13408, 11377, 11381, -1, 13408, 11381, 13403, -1, 13408, 13399, 13404, -1, 13409, 13404, 13405, -1, 13409, 13405, 13410, -1, 13411, 13406, 13402, -1, 13411, 13407, 13406, -1, 13411, 13402, 13412, -1, 13413, 13404, 13409, -1, 13413, 11377, 13408, -1, 13413, 13408, 13404, -1, 13414, 13409, 13410, -1, 13414, 13410, 13415, -1, 13416, 13407, 13411, -1, 13416, 13411, 13412, -1, 13416, 13417, 13407, -1, 13416, 13412, 13417, -1, 13418, 11373, 11377, -1, 13418, 11377, 13413, -1, 13418, 13413, 13409, -1, 13418, 13409, 13414, -1, 13419, 11373, 13418, -1, 13419, 13414, 13415, -1, 13419, 13418, 13414, -1, 13419, 13415, 13420, -1, 13421, 13422, 13417, -1, 13421, 13417, 13412, -1, 13423, 13420, 13424, -1, 13423, 13419, 13420, -1, 13425, 13422, 13421, -1, 13425, 13421, 13412, -1, 13425, 13412, 13426, -1, 13427, 11369, 11373, -1, 13427, 11373, 13419, -1, 13427, 13419, 13423, -1, 13428, 13423, 13424, -1, 13428, 13427, 13423, -1, 13428, 11369, 13427, -1, 13429, 13430, 13422, -1, 13429, 13422, 13425, -1, 13429, 13425, 13426, -1, 13431, 13428, 13424, -1, 13431, 13424, 13432, -1, 13433, 13430, 13429, -1, 13433, 13434, 13430, -1, 13433, 13429, 13426, -1, 13433, 13426, 13435, -1, 13436, 11365, 11369, -1, 13436, 11369, 13428, -1, 13436, 13428, 13431, -1, 13437, 11365, 13436, -1, 13437, 13431, 13432, -1, 13437, 13432, 13438, -1, 13437, 13436, 13431, -1, 13439, 13433, 13435, -1, 13439, 13434, 13433, -1, 13440, 13438, 13441, -1, 13440, 13437, 13438, -1, 13442, 13434, 13439, -1, 13442, 13443, 13434, -1, 13442, 13444, 13443, -1, 13442, 13439, 13435, -1, 13442, 13435, 13444, -1, 13445, 11361, 11365, -1, 13445, 11365, 13437, -1, 13445, 13437, 13440, -1, 13446, 11361, 13445, -1, 13446, 13440, 13441, -1, 13446, 13445, 13440, -1, 13447, 13448, 13443, -1, 13447, 13443, 13444, -1, 13447, 13444, 13449, -1, 13450, 13448, 13447, -1, 13450, 13447, 13449, -1, 13451, 11357, 11361, -1, 13451, 11361, 13446, -1, 13451, 13441, 13452, -1, 13451, 13446, 13441, -1, 13453, 11357, 13451, -1, 13453, 13451, 13452, -1, 13454, 13455, 13448, -1, 13454, 13449, 13456, -1, 13454, 13448, 13450, -1, 13454, 13450, 13449, -1, 13457, 13452, 13458, -1, 13457, 13453, 13452, -1, 13459, 11349, 13460, -1, 13461, 11357, 13453, -1, 13461, 13457, 13458, -1, 13461, 13453, 13457, -1, 13461, 11353, 11357, -1, 13462, 13463, 13455, -1, 13462, 13455, 13454, -1, 13462, 13454, 13456, -1, 13462, 13456, 13464, -1, 13465, 13456, 13466, -1, 13465, 13464, 13456, -1, 13467, 13458, 13468, -1, 13467, 13461, 13458, -1, 13467, 11349, 11353, -1, 13467, 11353, 13461, -1, 13469, 13462, 13464, -1, 13469, 13465, 13466, -1, 13469, 13470, 13463, -1, 13469, 13463, 13462, -1, 13469, 13464, 13465, -1, 13471, 13468, 13472, -1, 13471, 13472, 13460, -1, 13471, 11349, 13467, -1, 13471, 13460, 11349, -1, 13471, 13467, 13468, -1, 13473, 13469, 13466, -1, 13473, 13470, 13469, -1, 13473, 13474, 13475, -1, 13473, 13475, 13476, -1, 13473, 13476, 13477, -1, 13473, 13477, 13470, -1, 13473, 13466, 13478, -1, 13479, 13473, 13478, -1, 13479, 13474, 13473, -1, 13479, 13478, 13480, -1, 13481, 13482, 13474, -1, 13481, 13474, 13479, -1, 13266, 13483, 13484, -1, 13266, 13484, 13485, -1, 13266, 13485, 13263, -1, 13266, 11345, 13483, -1, 13486, 13479, 13480, -1, 13267, 13265, 13482, -1, 13267, 13482, 13481, -1, 13487, 13481, 13479, -1, 13487, 13479, 13486, -1, 11345, 13459, 13483, -1, 13488, 13486, 13480, -1, 13488, 13480, 13489, -1, 11345, 11349, 13459, -1, 13490, 13481, 13487, -1, 13490, 13267, 13481, -1, 13491, 13487, 13486, -1, 13491, 13488, 13489, -1, 13491, 13486, 13488, -1, 13492, 11341, 13267, -1, 13492, 13267, 13490, -1, 13493, 13490, 13487, -1, 13493, 13487, 13491, -1, 13494, 13491, 13489, -1, 13494, 13489, 13495, -1, 13496, 11341, 13492, -1, 13496, 13492, 13490, -1, 13496, 13490, 13493, -1, 13496, 11337, 11341, -1, 13497, 13493, 13491, -1, 13497, 13491, 13494, -1, 13498, 13494, 13495, -1, 13499, 13493, 13497, -1, 13499, 13496, 13493, -1, 13499, 11337, 13496, -1, 13500, 13497, 13494, -1, 13500, 13494, 13498, -1, 13501, 13498, 13495, -1, 13501, 13495, 13502, -1, 13503, 13497, 13500, -1, 11325, 13504, 13505, -1, 13503, 13499, 13497, -1, 13503, 11337, 13499, -1, 13503, 11333, 11337, -1, 13506, 13500, 13498, -1, 13506, 13498, 13501, -1, 13506, 13501, 13502, -1, 13507, 13503, 13500, -1, 13507, 13500, 13506, -1, 13507, 11333, 13503, -1, 13508, 13506, 13502, -1, 13508, 13502, 13509, -1, 13510, 13507, 13506, -1, 13510, 11333, 13507, -1, 13510, 13506, 13508, -1, 13510, 11329, 11333, -1, 13511, 11329, 13510, -1, 13511, 13508, 13509, -1, 13511, 13510, 13508, -1, 13511, 13509, 13512, -1, 13513, 11329, 13511, -1, 13513, 13504, 11325, -1, 13513, 13512, 13514, -1, 13513, 13514, 13504, -1, 13513, 13511, 13512, -1, 13513, 11325, 11329, -1, 13515, 11325, 13505, -1, 13515, 13505, 13516, -1, 13517, 11325, 13515, -1, 13517, 13518, 11321, -1, 13517, 13516, 13519, -1, 13517, 13519, 13518, -1, 13517, 11321, 11325, -1, 13517, 13515, 13516, -1, 13520, 11321, 13518, -1, 13520, 13518, 13521, -1, 13520, 11317, 11321, -1, 13520, 13521, 13522, -1, 13523, 11317, 13520, -1, 13523, 13520, 13522, -1, 13523, 13524, 11317, -1, 13523, 13522, 13525, -1, 13523, 13525, 13526, -1, 13523, 13526, 13524, -1, 13527, 11317, 13524, -1, 13527, 13524, 13528, -1, 13527, 11313, 11317, -1, 13207, 13528, 13208, -1, 13206, 11313, 13527, -1, 13206, 13528, 13207, -1, 13206, 13527, 13528, -1, 13529, 13530, 13531, -1, 13532, 13530, 13529, -1, 13533, 13534, 13535, -1, 13532, 13534, 13530, -1, 13536, 13534, 13532, -1, 13535, 13534, 13536, -1, 13537, 13538, 12055, -1, 12055, 13538, 13539, -1, 13540, 13538, 13541, -1, 13541, 13538, 13542, -1, 13542, 13538, 13543, -1, 13539, 13538, 13540, -1, 13531, 13544, 13545, -1, 13546, 13547, 13548, -1, 13530, 13544, 13531, -1, 13543, 13549, 13550, -1, 13547, 13551, 13548, -1, 13550, 13549, 13533, -1, 13533, 13549, 13534, -1, 13534, 13552, 13530, -1, 13544, 13552, 13545, -1, 13530, 13552, 13544, -1, 13537, 13553, 13538, -1, 13543, 13553, 13549, -1, 13554, 13540, 13555, -1, 13538, 13553, 13543, -1, 13534, 13556, 13552, -1, 13549, 13556, 13534, -1, 13545, 13557, 13558, -1, 13552, 13557, 13545, -1, 13559, 13560, 13537, -1, 13553, 13560, 13549, -1, 13549, 13560, 13556, -1, 13537, 13560, 13553, -1, 13552, 13561, 13557, -1, 13554, 13539, 13540, -1, 13556, 13561, 13552, -1, 13558, 13562, 13563, -1, 13557, 13562, 13558, -1, 13560, 13564, 13556, -1, 13559, 13564, 13560, -1, 13556, 13564, 13561, -1, 13561, 13565, 13557, -1, 13557, 13565, 13562, -1, 13562, 13566, 13563, -1, 13567, 13568, 13559, -1, 13564, 13568, 13561, -1, 13561, 13568, 13565, -1, 13559, 13568, 13564, -1, 13565, 13569, 13562, -1, 13562, 13569, 13566, -1, 13568, 13570, 13565, -1, 13565, 13570, 13569, -1, 13567, 13570, 13568, -1, 13569, 13571, 13566, -1, 13566, 13571, 13563, -1, 13563, 13571, 13572, -1, 13573, 13574, 13567, -1, 13569, 13574, 13571, -1, 13567, 13574, 13570, -1, 13570, 13574, 13569, -1, 13573, 13575, 13574, -1, 13571, 13575, 13572, -1, 13574, 13575, 13571, -1, 13572, 13575, 13576, -1, 13577, 13578, 13573, -1, 13576, 13578, 13579, -1, 13575, 13578, 13576, -1, 13573, 13578, 13575, -1, 13580, 13581, 13577, -1, 13579, 13581, 13580, -1, 13578, 13581, 13579, -1, 13577, 13581, 13578, -1, 13577, 13582, 13580, -1, 13577, 13583, 13582, -1, 13582, 13583, 13584, -1, 13584, 13583, 13585, -1, 13586, 13532, 13587, -1, 13548, 13532, 13586, -1, 13587, 13532, 13529, -1, 13551, 13532, 13548, -1, 13535, 13536, 13588, -1, 13588, 13536, 13551, -1, 13551, 13536, 13532, -1, 13589, 13546, 13548, -1, 13590, 13591, 13592, -1, 13592, 13591, 13593, -1, 13593, 13591, 13594, -1, 13594, 13595, 13596, -1, 13591, 13595, 13594, -1, 13590, 13595, 13591, -1, 13597, 13598, 13590, -1, 13595, 13598, 13596, -1, 13590, 13598, 13595, -1, 13596, 13599, 13600, -1, 13597, 13599, 13598, -1, 13598, 13599, 13596, -1, 13600, 13601, 13602, -1, 13599, 13601, 13600, -1, 13601, 13603, 13602, -1, 13604, 13605, 13597, -1, 13599, 13605, 13601, -1, 13597, 13605, 13599, -1, 13602, 13606, 13607, -1, 13603, 13606, 13602, -1, 13608, 13609, 13604, -1, 13601, 13609, 13603, -1, 13605, 13609, 13601, -1, 13604, 13609, 13605, -1, 13610, 13611, 13608, -1, 13606, 13611, 13607, -1, 13608, 13611, 13609, -1, 13609, 13611, 13603, -1, 13603, 13611, 13606, -1, 13612, 13613, 13610, -1, 13607, 13613, 13614, -1, 13611, 13613, 13607, -1, 13610, 13613, 13611, -1, 13614, 13615, 13616, -1, 13613, 13615, 13614, -1, 13589, 13617, 13612, -1, 13612, 13617, 13613, -1, 13613, 13617, 13615, -1, 13616, 13618, 13587, -1, 13587, 13618, 13586, -1, 13615, 13618, 13616, -1, 13586, 13619, 13548, -1, 13589, 13619, 13617, -1, 13618, 13619, 13586, -1, 13548, 13619, 13589, -1, 13617, 13619, 13615, -1, 13615, 13619, 13618, -1, 13620, 13621, 13622, -1, 13622, 13621, 13623, -1, 13624, 13625, 13626, -1, 13627, 13625, 13620, -1, 13626, 13625, 13627, -1, 13620, 13625, 13621, -1, 13623, 13628, 13629, -1, 13621, 13628, 13623, -1, 13630, 13631, 13624, -1, 13621, 13631, 13628, -1, 13624, 13631, 13625, -1, 13625, 13631, 13621, -1, 13628, 13631, 13630, -1, 13632, 13633, 13630, -1, 13629, 13633, 13634, -1, 13630, 13633, 13628, -1, 13628, 13633, 13629, -1, 13634, 13635, 13636, -1, 13633, 13637, 13634, -1, 13634, 13637, 13635, -1, 13632, 13637, 13633, -1, 13636, 13638, 13639, -1, 13635, 13638, 13636, -1, 13640, 13641, 13632, -1, 13632, 13641, 13637, -1, 13637, 13641, 13635, -1, 13639, 13642, 13643, -1, 13638, 13642, 13639, -1, 13644, 13645, 13640, -1, 13641, 13645, 13635, -1, 13635, 13645, 13638, -1, 13640, 13645, 13641, -1, 13642, 13646, 13643, -1, 13644, 13647, 13645, -1, 13638, 13647, 13642, -1, 13645, 13647, 13638, -1, 13648, 13649, 13650, -1, 13643, 13649, 13651, -1, 13650, 13649, 13646, -1, 13646, 13649, 13643, -1, 13650, 13652, 13644, -1, 13644, 13652, 13647, -1, 13646, 13652, 13650, -1, 13642, 13652, 13646, -1, 13647, 13652, 13642, -1, 13653, 13654, 13655, -1, 13655, 13654, 13648, -1, 13651, 13654, 13653, -1, 13648, 13654, 13649, -1, 13649, 13654, 13651, -1, 13656, 13657, 13658, -1, 13659, 13660, 13661, -1, 13661, 13660, 13656, -1, 13662, 13663, 13664, -1, 13656, 13665, 13657, -1, 11949, 13666, 11945, -1, 13659, 13666, 13660, -1, 11945, 13666, 13667, -1, 13667, 13666, 13659, -1, 13668, 13669, 13670, -1, 13657, 13669, 13668, -1, 13660, 13671, 13656, -1, 13656, 13671, 13665, -1, 13665, 13672, 13657, -1, 13657, 13672, 13669, -1, 11949, 13673, 13666, -1, 13660, 13673, 13671, -1, 13666, 13673, 13660, -1, 13670, 13674, 13675, -1, 13669, 13674, 13670, -1, 13671, 13676, 13665, -1, 13665, 13676, 13672, -1, 13669, 13677, 13674, -1, 13672, 13677, 13669, -1, 13673, 13678, 13671, -1, 11956, 13678, 11949, -1, 13671, 13678, 13676, -1, 11949, 13678, 13673, -1, 13674, 13679, 13675, -1, 13676, 13680, 13672, -1, 13672, 13680, 13677, -1, 13674, 13681, 13679, -1, 13677, 13681, 13674, -1, 13676, 13682, 13680, -1, 11956, 13682, 13678, -1, 13678, 13682, 13676, -1, 13675, 13683, 13684, -1, 13679, 13683, 13675, -1, 13680, 13685, 13677, -1, 13677, 13685, 13681, -1, 13681, 13686, 13679, -1, 13679, 13686, 13683, -1, 11956, 13687, 13682, -1, 11957, 13687, 11956, -1, 13680, 13687, 13685, -1, 13682, 13687, 13680, -1, 13684, 13688, 13689, -1, 13689, 13688, 13690, -1, 13683, 13688, 13684, -1, 13681, 13691, 13686, -1, 13685, 13691, 13681, -1, 13664, 13692, 13693, -1, 13693, 13692, 13694, -1, 13686, 13695, 13683, -1, 13694, 13692, 13696, -1, 13688, 13695, 13690, -1, 13683, 13695, 13688, -1, 13663, 13692, 13664, -1, 11944, 13697, 12051, -1, 13698, 13697, 13663, -1, 11957, 13699, 13687, -1, 12051, 13697, 13698, -1, 13687, 13699, 13685, -1, 13663, 13697, 13692, -1, 13685, 13699, 13691, -1, 13700, 13701, 13702, -1, 13696, 13701, 13700, -1, 13695, 13703, 13690, -1, 13692, 13701, 13696, -1, 13686, 13703, 13695, -1, 13691, 13703, 13686, -1, 13702, 13704, 13705, -1, 13690, 13706, 11958, -1, 11958, 13706, 11957, -1, 11957, 13706, 13699, -1, 13703, 13706, 13690, -1, 13699, 13706, 13691, -1, 13692, 13707, 13701, -1, 13691, 13706, 13703, -1, 13697, 13707, 13692, -1, 11944, 13707, 13697, -1, 13701, 13708, 13702, -1, 13702, 13708, 13704, -1, 13705, 13661, 13658, -1, 13704, 13661, 13705, -1, 11945, 13709, 11944, -1, 13701, 13709, 13708, -1, 11944, 13709, 13707, -1, 13707, 13709, 13701, -1, 13704, 13659, 13661, -1, 13708, 13659, 13704, -1, 13661, 13656, 13658, -1, 11945, 13667, 13709, -1, 13709, 13667, 13708, -1, 13708, 13667, 13659, -1, 13658, 13657, 13668, -1, 13710, 13711, 13712, -1, 13713, 13711, 13710, -1, 13712, 13711, 13714, -1, 13715, 13716, 13717, -1, 13717, 13716, 13718, -1, 13719, 13720, 13721, -1, 13714, 13720, 13719, -1, 13722, 13723, 13724, -1, 13721, 13725, 13726, -1, 13716, 13727, 13718, -1, 13711, 13728, 13714, -1, 13714, 13728, 13720, -1, 13720, 13729, 13721, -1, 13730, 13731, 13732, -1, 13721, 13729, 13725, -1, 13725, 13733, 13726, -1, 13720, 13734, 13729, -1, 13727, 13735, 13736, -1, 13737, 13738, 13739, -1, 13740, 13734, 13728, -1, 13736, 13735, 13741, -1, 13723, 13738, 13742, -1, 13728, 13734, 13720, -1, 13716, 13735, 13727, -1, 13742, 13738, 13743, -1, 13743, 13738, 13737, -1, 13722, 13738, 13723, -1, 13725, 13744, 13733, -1, 13729, 13744, 13725, -1, 13726, 13745, 13746, -1, 13747, 13745, 13748, -1, 13733, 13745, 13726, -1, 13734, 13749, 13729, -1, 13729, 13749, 13744, -1, 13748, 13750, 13751, -1, 13751, 13750, 13752, -1, 13744, 13750, 13733, -1, 13733, 13750, 13745, -1, 13745, 13750, 13748, -1, 13747, 13753, 13745, -1, 13746, 13753, 13754, -1, 13754, 13753, 13755, -1, 13755, 13753, 13756, -1, 13756, 13753, 13747, -1, 13745, 13753, 13746, -1, 13757, 13758, 13749, -1, 13752, 13758, 13759, -1, 13749, 13758, 13744, -1, 13750, 13758, 13752, -1, 13744, 13758, 13750, -1, 13754, 13760, 13730, -1, 13755, 13760, 13754, -1, 13761, 13760, 13755, -1, 13762, 13763, 13764, -1, 13764, 13763, 13715, -1, 13715, 13763, 13716, -1, 13760, 13765, 13730, -1, 13731, 13765, 13761, -1, 13730, 13765, 13731, -1, 13761, 13765, 13760, -1, 13731, 13766, 13732, -1, 13767, 13766, 13731, -1, 13741, 13768, 13769, -1, 13735, 13768, 13741, -1, 13732, 13770, 13771, -1, 13772, 13770, 13767, -1, 13766, 13770, 13732, -1, 13767, 13770, 13766, -1, 13769, 13773, 13774, -1, 13770, 13775, 13771, -1, 13776, 13777, 13778, -1, 13772, 13775, 13770, -1, 13779, 13780, 13773, -1, 13773, 13780, 13774, -1, 13774, 13780, 13781, -1, 13772, 13782, 13775, -1, 13771, 13782, 13778, -1, 13776, 13782, 13772, -1, 13775, 13782, 13771, -1, 13778, 13782, 13776, -1, 13781, 13783, 13784, -1, 13785, 13786, 13783, -1, 13783, 13786, 13784, -1, 13784, 13786, 13787, -1, 13788, 13786, 13785, -1, 13778, 13789, 13790, -1, 13777, 13789, 13778, -1, 13786, 13791, 13787, -1, 13788, 13791, 13786, -1, 13787, 13791, 13792, -1, 13790, 13793, 13794, -1, 13789, 13793, 13790, -1, 13795, 13793, 13777, -1, 13777, 13793, 13789, -1, 13794, 13793, 13795, -1, 13788, 13796, 13791, -1, 13795, 13797, 13794, -1, 13791, 13796, 13792, -1, 13798, 13796, 13788, -1, 13796, 13799, 13792, -1, 13798, 13799, 13796, -1, 13792, 13799, 13800, -1, 13798, 13801, 13799, -1, 13799, 13801, 13800, -1, 13800, 13801, 13802, -1, 13802, 13801, 13803, -1, 13803, 13801, 13804, -1, 13804, 13801, 13798, -1, 13713, 13805, 13711, -1, 13740, 13805, 13713, -1, 13711, 13805, 13728, -1, 13728, 13805, 13740, -1, 13734, 13806, 13749, -1, 13749, 13806, 13757, -1, 13757, 13806, 13740, -1, 13740, 13806, 13734, -1, 13739, 13807, 13808, -1, 13809, 13807, 13738, -1, 13738, 13807, 13739, -1, 13808, 13810, 13811, -1, 13811, 13810, 13812, -1, 13757, 13813, 13758, -1, 13759, 13814, 13762, -1, 13807, 13810, 13808, -1, 13763, 13814, 13716, -1, 13809, 13810, 13807, -1, 13757, 13814, 13813, -1, 13813, 13814, 13758, -1, 13716, 13814, 13757, -1, 13758, 13814, 13759, -1, 13812, 13712, 13815, -1, 13762, 13814, 13763, -1, 13769, 13816, 13773, -1, 13810, 13710, 13812, -1, 13773, 13816, 13779, -1, 13809, 13710, 13810, -1, 13768, 13816, 13769, -1, 13713, 13710, 13809, -1, 13735, 13816, 13768, -1, 13812, 13710, 13712, -1, 13779, 13816, 13735, -1, 13780, 13817, 13781, -1, 13781, 13817, 13783, -1, 13783, 13817, 13785, -1, 13815, 13714, 13719, -1, 13785, 13817, 13779, -1, 13779, 13817, 13780, -1, 13712, 13714, 13815, -1, 13818, 13819, 13820, -1, 13821, 13820, 13822, -1, 13821, 13818, 13820, -1, 13823, 13822, 13824, -1, 13823, 13821, 13822, -1, 13825, 13824, 13826, -1, 13825, 13823, 13824, -1, 13827, 13825, 13826, -1, 13723, 13820, 13724, -1, 13724, 13820, 13819, -1, 13723, 13822, 13820, -1, 13723, 13742, 13822, -1, 13743, 13824, 13742, -1, 13742, 13824, 13822, -1, 13737, 13826, 13743, -1, 13743, 13826, 13824, -1, 13737, 13828, 13826, -1, 13829, 13830, 13831, -1, 13831, 13830, 13832, -1, 13833, 13830, 13829, -1, 13834, 13835, 13836, -1, 13837, 13838, 13833, -1, 13830, 13838, 13832, -1, 13833, 13838, 13830, -1, 13832, 13839, 13840, -1, 13837, 13839, 13838, -1, 13838, 13839, 13832, -1, 13840, 13841, 13842, -1, 13839, 13841, 13840, -1, 13841, 13843, 13842, -1, 13837, 13844, 13839, -1, 13845, 13844, 13837, -1, 13839, 13844, 13841, -1, 13841, 13846, 13843, -1, 13835, 13833, 13847, -1, 13847, 13833, 13829, -1, 13842, 13848, 13849, -1, 13834, 13833, 13835, -1, 13843, 13848, 13842, -1, 13844, 13850, 13841, -1, 13841, 13850, 13846, -1, 13845, 13850, 13844, -1, 13846, 13851, 13843, -1, 13843, 13851, 13848, -1, 13849, 13852, 13853, -1, 13848, 13852, 13849, -1, 13854, 13855, 13845, -1, 13850, 13855, 13846, -1, 13845, 13855, 13850, -1, 13846, 13855, 13851, -1, 13853, 13856, 13857, -1, 13848, 13858, 13852, -1, 13851, 13858, 13848, -1, 13852, 13859, 13853, -1, 13853, 13859, 13856, -1, 13854, 13860, 13855, -1, 13851, 13860, 13858, -1, 13855, 13860, 13851, -1, 13857, 13861, 13862, -1, 13856, 13861, 13857, -1, 13858, 13863, 13852, -1, 13852, 13863, 13859, -1, 13864, 13865, 13866, -1, 13859, 13865, 13856, -1, 13856, 13865, 13861, -1, 13858, 13867, 13863, -1, 13860, 13867, 13858, -1, 13868, 13867, 13854, -1, 13854, 13867, 13860, -1, 13869, 13870, 13871, -1, 13861, 13870, 13862, -1, 13862, 13870, 13622, -1, 13622, 13870, 13620, -1, 13620, 13870, 13627, -1, 13627, 13870, 13869, -1, 13866, 13872, 13873, -1, 13863, 13872, 13859, -1, 13865, 13872, 13866, -1, 13859, 13872, 13865, -1, 13871, 13874, 13875, -1, 13875, 13874, 13864, -1, 13864, 13874, 13865, -1, 13865, 13874, 13861, -1, 13870, 13874, 13871, -1, 13861, 13874, 13870, -1, 13868, 13876, 13867, -1, 13873, 13876, 13877, -1, 13867, 13876, 13863, -1, 13863, 13876, 13872, -1, 13872, 13876, 13873, -1, 13877, 13878, 13879, -1, 13879, 13878, 13880, -1, 13880, 13878, 13881, -1, 13663, 13878, 13698, -1, 13698, 13878, 12051, -1, 12051, 13878, 13868, -1, 13876, 13878, 13877, -1, 13868, 13878, 13876, -1, 13881, 13878, 13663, -1, 13869, 13626, 13627, -1, 13881, 13663, 13662, -1, 13882, 13883, 13884, -1, 13885, 13884, 13886, -1, 13885, 13882, 13884, -1, 13887, 13886, 13888, -1, 13887, 13885, 13886, -1, 13889, 13888, 13890, -1, 13889, 13887, 13888, -1, 13891, 13889, 13890, -1, 13835, 13884, 13836, -1, 13836, 13884, 13883, -1, 13835, 13886, 13884, -1, 13835, 13847, 13886, -1, 13829, 13888, 13847, -1, 13847, 13888, 13886, -1, 13831, 13890, 13829, -1, 13829, 13890, 13888, -1, 13831, 13892, 13890, -1, 13893, 13894, 13895, -1, 13896, 13897, 13898, -1, 13899, 13897, 13900, -1, 13900, 13897, 13896, -1, 13894, 13901, 13895, -1, 11971, 13901, 13894, -1, 13898, 13902, 13903, -1, 13897, 13902, 13898, -1, 13899, 13902, 13897, -1, 13903, 13902, 13899, -1, 11974, 13904, 11971, -1, 13905, 13904, 11974, -1, 13895, 13904, 13905, -1, 11971, 13904, 13901, -1, 13901, 13904, 13895, -1, 13903, 13906, 13898, -1, 13907, 13906, 13908, -1, 13908, 13906, 13903, -1, 13898, 13906, 13907, -1, 13908, 13909, 13907, -1, 13910, 13909, 13908, -1, 13911, 13912, 13913, -1, 13913, 13912, 13910, -1, 13907, 13912, 13911, -1, 13910, 13912, 13909, -1, 13909, 13912, 13907, -1, 13913, 13914, 13911, -1, 13915, 13914, 13916, -1, 13917, 13914, 13915, -1, 13918, 11981, 13919, -1, 13916, 13914, 13913, -1, 11978, 11981, 13918, -1, 13911, 13914, 13917, -1, 13919, 11981, 13920, -1, 13920, 11981, 13921, -1, 13922, 13923, 13924, -1, 13924, 13923, 13915, -1, 13915, 13923, 13917, -1, 13917, 13923, 13925, -1, 13922, 13926, 13923, -1, 13927, 13926, 13922, -1, 13923, 13928, 13925, -1, 13925, 13928, 13929, -1, 13930, 13931, 13932, -1, 13932, 13931, 13927, -1, 13927, 13931, 13926, -1, 13926, 13933, 13923, -1, 13923, 13933, 13928, -1, 13928, 13934, 13929, -1, 13926, 13935, 13933, -1, 11982, 13935, 13931, -1, 13931, 13935, 13926, -1, 13933, 13936, 13928, -1, 13928, 13936, 13934, -1, 13929, 13937, 13938, -1, 13938, 13937, 13939, -1, 13934, 13937, 13929, -1, 13933, 13940, 13936, -1, 13935, 13940, 13933, -1, 13936, 13941, 13934, -1, 13934, 13941, 13937, -1, 13940, 13942, 13936, -1, 11985, 13942, 13940, -1, 11989, 13942, 11985, -1, 13936, 13942, 13941, -1, 13937, 13943, 13939, -1, 13941, 13943, 13937, -1, 13939, 13943, 13944, -1, 13942, 13945, 13941, -1, 11989, 13945, 13942, -1, 13941, 13945, 13943, -1, 13946, 11993, 13947, -1, 13948, 11993, 13946, -1, 13943, 13949, 13944, -1, 13944, 13949, 13950, -1, 11992, 13951, 11989, -1, 11989, 13951, 13945, -1, 13945, 13951, 13943, -1, 13949, 13951, 13950, -1, 11993, 13952, 13947, -1, 13943, 13951, 13949, -1, 11974, 13953, 13905, -1, 13951, 13954, 13950, -1, 13950, 13954, 13955, -1, 11992, 13954, 13951, -1, 11993, 13956, 11992, -1, 13954, 13956, 13955, -1, 11992, 13956, 13954, -1, 13955, 13956, 13948, -1, 13948, 13956, 11993, -1, 11982, 13957, 11981, -1, 11981, 13957, 13921, -1, 13921, 13957, 13958, -1, 13958, 13957, 13930, -1, 13930, 13957, 13931, -1, 13952, 11996, 13959, -1, 13931, 13957, 11982, -1, 13959, 11996, 13960, -1, 11982, 13961, 13935, -1, 13940, 13961, 11985, -1, 13935, 13961, 13940, -1, 11985, 13961, 11982, -1, 11993, 11996, 13952, -1, 13962, 13963, 13964, -1, 13964, 13963, 13965, -1, 13965, 13963, 13966, -1, 11966, 13967, 11965, -1, 11965, 13967, 13968, -1, 13968, 13967, 13969, -1, 13969, 13967, 13970, -1, 13963, 13971, 13966, -1, 13972, 13971, 13962, -1, 13966, 13971, 13973, -1, 11974, 11978, 13953, -1, 13962, 13971, 13963, -1, 13953, 11978, 13974, -1, 13974, 11978, 13975, -1, 13970, 13976, 13977, -1, 13967, 13976, 13970, -1, 11966, 13976, 13967, -1, 11978, 13918, 13975, -1, 13971, 13978, 13973, -1, 13972, 13978, 13971, -1, 11970, 13979, 11966, -1, 13977, 13979, 13980, -1, 11966, 13979, 13976, -1, 13976, 13979, 13977, -1, 13981, 13982, 13972, -1, 13973, 13982, 13896, -1, 13978, 13982, 13973, -1, 13972, 13982, 13978, -1, 13980, 13983, 13893, -1, 13979, 13983, 13980, -1, 11970, 13983, 13979, -1, 13982, 13900, 13896, -1, 13981, 13900, 13982, -1, 13899, 13900, 13981, -1, 13983, 13894, 13893, -1, 11970, 13894, 13983, -1, 11971, 13894, 11970, -1, 13984, 13985, 13986, -1, 13987, 13984, 13986, -1, 13988, 13987, 13986, -1, 13989, 13988, 13986, -1, 13990, 13988, 13989, -1, 13991, 13990, 13989, -1, 13992, 13993, 13994, -1, 13995, 13992, 13994, -1, 13996, 13997, 13995, -1, 13996, 13995, 13994, -1, 13998, 13997, 13996, -1, 13999, 14000, 14001, -1, 14002, 14003, 13999, -1, 14002, 13999, 14001, -1, 14004, 14003, 14002, -1, 14005, 14004, 14002, -1, 14006, 14007, 14008, -1, 14009, 14010, 14011, -1, 14011, 14010, 14012, -1, 14012, 14010, 14013, -1, 14013, 14010, 14014, -1, 14014, 14010, 14015, -1, 14015, 14010, 14016, -1, 14016, 14010, 14006, -1, 14006, 14010, 14007, -1, 14007, 14017, 14018, -1, 14010, 14017, 14007, -1, 14010, 14019, 14017, -1, 14020, 14021, 14010, -1, 14010, 14021, 14019, -1, 13992, 13953, 13974, -1, 13905, 13995, 13895, -1, 13995, 13893, 13895, -1, 13893, 13997, 13980, -1, 13995, 13997, 13893, -1, 13997, 13977, 13980, -1, 13997, 13970, 13977, -1, 13997, 13998, 13970, -1, 13998, 13969, 13970, -1, 13992, 13995, 13953, -1, 13953, 13995, 13905, -1, 14000, 13962, 13964, -1, 13972, 13999, 13981, -1, 13999, 13899, 13981, -1, 13899, 14003, 13903, -1, 13999, 14003, 13899, -1, 14003, 13908, 13903, -1, 14003, 13910, 13908, -1, 14003, 14004, 13910, -1, 14004, 13913, 13910, -1, 14000, 13999, 13962, -1, 13962, 13999, 13972, -1, 13984, 13948, 13946, -1, 13984, 13955, 13948, -1, 13955, 13987, 13950, -1, 13987, 13944, 13950, -1, 13987, 13939, 13944, -1, 13987, 13938, 13939, -1, 13938, 13988, 13929, -1, 13988, 13925, 13929, -1, 13988, 13917, 13925, -1, 13988, 13911, 13917, -1, 13911, 13990, 13907, -1, 13990, 13898, 13907, -1, 13990, 13896, 13898, -1, 13990, 13973, 13896, -1, 13973, 13991, 13966, -1, 13990, 13991, 13973, -1, 13991, 13965, 13966, -1, 13984, 13987, 13955, -1, 13987, 13988, 13938, -1, 13988, 13990, 13911, -1, 14010, 14001, 14020, -1, 14002, 14001, 14010, -1, 14021, 13994, 14019, -1, 13996, 13994, 14021, -1, 14022, 14023, 14024, -1, 14025, 14026, 14022, -1, 12004, 14026, 14025, -1, 14022, 14026, 14023, -1, 14027, 12015, 14028, -1, 14028, 12015, 14029, -1, 14030, 14031, 14032, -1, 14023, 14031, 14030, -1, 12000, 14033, 14034, -1, 14032, 14035, 14036, -1, 12015, 14037, 14029, -1, 14026, 14038, 14023, -1, 14023, 14038, 14031, -1, 14031, 14039, 14032, -1, 14040, 14041, 14042, -1, 14032, 14039, 14035, -1, 14035, 14043, 14036, -1, 14031, 14044, 14039, -1, 14037, 12016, 14045, -1, 14046, 12001, 14047, -1, 12008, 14044, 14038, -1, 14045, 12016, 14048, -1, 14033, 12001, 14049, -1, 14038, 14044, 14031, -1, 12015, 12016, 14037, -1, 14049, 12001, 14050, -1, 14050, 12001, 14046, -1, 12000, 12001, 14033, -1, 14035, 14051, 14043, -1, 14039, 14051, 14035, -1, 14036, 14052, 14053, -1, 14054, 14052, 14055, -1, 14043, 14052, 14036, -1, 14044, 14056, 14039, -1, 14039, 14056, 14051, -1, 14055, 14057, 14058, -1, 14058, 14057, 14059, -1, 14051, 14057, 14043, -1, 14043, 14057, 14052, -1, 14052, 14057, 14055, -1, 14054, 14060, 14052, -1, 14053, 14060, 14061, -1, 14061, 14060, 14062, -1, 14062, 14060, 14063, -1, 14063, 14060, 14054, -1, 14052, 14060, 14053, -1, 12011, 14064, 14056, -1, 14059, 14064, 14065, -1, 14056, 14064, 14051, -1, 14057, 14064, 14059, -1, 14051, 14064, 14057, -1, 14061, 14066, 14040, -1, 14062, 14066, 14061, -1, 14067, 14066, 14062, -1, 14068, 14069, 14070, -1, 14070, 14069, 14027, -1, 14027, 14069, 12015, -1, 14066, 14071, 14040, -1, 14041, 14071, 14067, -1, 14040, 14071, 14041, -1, 14067, 14071, 14066, -1, 14041, 14072, 14042, -1, 14073, 14072, 14041, -1, 14048, 14074, 14075, -1, 12016, 14074, 14048, -1, 14042, 14076, 14077, -1, 14078, 14076, 14073, -1, 14072, 14076, 14042, -1, 14073, 14076, 14072, -1, 14075, 14079, 14080, -1, 14076, 14081, 14077, -1, 14082, 14083, 14084, -1, 14078, 14081, 14076, -1, 12019, 14085, 14079, -1, 14079, 14085, 14080, -1, 14080, 14085, 14086, -1, 14078, 14087, 14081, -1, 14077, 14087, 14084, -1, 14082, 14087, 14078, -1, 14081, 14087, 14077, -1, 14084, 14087, 14082, -1, 14086, 14088, 14089, -1, 12022, 14090, 14088, -1, 14088, 14090, 14089, -1, 14089, 14090, 14091, -1, 12026, 14090, 12022, -1, 14084, 14092, 14093, -1, 14083, 14092, 14084, -1, 14090, 14094, 14091, -1, 12026, 14094, 14090, -1, 14091, 14094, 14095, -1, 14093, 14096, 14097, -1, 14092, 14096, 14093, -1, 14098, 14096, 14083, -1, 14083, 14096, 14092, -1, 14097, 14096, 14098, -1, 12026, 14099, 14094, -1, 14098, 14100, 14097, -1, 14094, 14099, 14095, -1, 12027, 14099, 12026, -1, 14099, 14101, 14095, -1, 12027, 14101, 14099, -1, 14095, 14101, 14102, -1, 12027, 14103, 14101, -1, 14101, 14103, 14102, -1, 14102, 14103, 14104, -1, 14104, 14103, 14105, -1, 14105, 14103, 12030, -1, 12030, 14103, 12027, -1, 12004, 14106, 14026, -1, 12008, 14106, 12004, -1, 14026, 14106, 14038, -1, 14038, 14106, 12008, -1, 14044, 14107, 14056, -1, 14056, 14107, 12011, -1, 12011, 14107, 12008, -1, 12008, 14107, 14044, -1, 14047, 14108, 14109, -1, 12003, 14108, 12001, -1, 12001, 14108, 14047, -1, 14109, 14110, 14111, -1, 14111, 14110, 14112, -1, 12011, 14113, 14064, -1, 14065, 14114, 14068, -1, 14108, 14110, 14109, -1, 14069, 14114, 12015, -1, 12003, 14110, 14108, -1, 12011, 14114, 14113, -1, 14113, 14114, 14064, -1, 12015, 14114, 12011, -1, 14064, 14114, 14065, -1, 14112, 14022, 14024, -1, 14068, 14114, 14069, -1, 14075, 14115, 14079, -1, 14110, 14025, 14112, -1, 14079, 14115, 12019, -1, 12003, 14025, 14110, -1, 14074, 14115, 14075, -1, 12004, 14025, 12003, -1, 12016, 14115, 14074, -1, 14112, 14025, 14022, -1, 12019, 14115, 12016, -1, 14085, 14116, 14086, -1, 14086, 14116, 14088, -1, 14088, 14116, 12022, -1, 14024, 14023, 14030, -1, 12022, 14116, 12019, -1, 12019, 14116, 14085, -1, 14117, 14118, 14119, -1, 14120, 14119, 14121, -1, 14120, 14117, 14119, -1, 14122, 14121, 14123, -1, 14122, 14120, 14121, -1, 14124, 14123, 14125, -1, 14124, 14122, 14123, -1, 14126, 14124, 14125, -1, 14033, 14119, 14034, -1, 14034, 14119, 14118, -1, 14033, 14121, 14119, -1, 14033, 14049, 14121, -1, 14050, 14123, 14049, -1, 14049, 14123, 14121, -1, 14046, 14125, 14050, -1, 14050, 14125, 14123, -1, 14046, 14127, 14125, -1, 14128, 14129, 14130, -1, 12040, 14131, 12036, -1, 12036, 14131, 14132, -1, 14133, 14131, 14134, -1, 14132, 14131, 14133, -1, 14130, 14135, 14136, -1, 14137, 14138, 14129, -1, 14134, 14138, 14137, -1, 14129, 14139, 14130, -1, 14130, 14139, 14135, -1, 12040, 14140, 14131, -1, 14131, 14140, 14134, -1, 14134, 14140, 14138, -1, 14136, 14141, 14142, -1, 14135, 14141, 14136, -1, 14138, 14143, 14129, -1, 14129, 14143, 14139, -1, 14135, 14144, 14141, -1, 14141, 14144, 14142, -1, 14139, 14144, 14135, -1, 14138, 14145, 14143, -1, 12041, 14145, 12040, -1, 12040, 14145, 14140, -1, 14140, 14145, 14138, -1, 14139, 14146, 14144, -1, 14143, 14146, 14139, -1, 14142, 14147, 14148, -1, 14144, 14147, 14142, -1, 14145, 14149, 14143, -1, 14143, 14149, 14146, -1, 12041, 14149, 14145, -1, 14144, 14150, 14147, -1, 14146, 14150, 14144, -1, 14147, 14151, 14148, -1, 14148, 14151, 14152, -1, 12044, 14153, 12041, -1, 12041, 14153, 14149, -1, 14149, 14153, 14146, -1, 14146, 14153, 14150, -1, 14150, 14154, 14147, -1, 14147, 14154, 14151, -1, 14151, 14155, 14152, -1, 14150, 14156, 14154, -1, 14153, 14156, 14150, -1, 14157, 13554, 14158, -1, 14158, 13554, 13555, -1, 12044, 14156, 14153, -1, 14154, 14159, 14151, -1, 14151, 14159, 14155, -1, 14152, 14160, 14161, -1, 14155, 14160, 14152, -1, 12048, 14162, 12044, -1, 14163, 14164, 14165, -1, 12044, 14162, 14156, -1, 14165, 14164, 14166, -1, 14154, 14162, 14159, -1, 14156, 14162, 14154, -1, 14161, 14167, 14168, -1, 14159, 14167, 14155, -1, 14163, 14169, 14164, -1, 14155, 14167, 14160, -1, 14160, 14167, 14161, -1, 14166, 14170, 14171, -1, 14164, 14170, 14166, -1, 12048, 14172, 14162, -1, 14162, 14172, 14159, -1, 14159, 14172, 14167, -1, 14163, 14173, 14169, -1, 14168, 14174, 14175, -1, 14175, 14174, 14157, -1, 14164, 14176, 14170, -1, 14167, 14174, 14168, -1, 14169, 14176, 14164, -1, 14157, 14174, 13554, -1, 12036, 14177, 12035, -1, 12055, 14178, 12048, -1, 12035, 14177, 14163, -1, 13554, 14178, 13539, -1, 13539, 14178, 12055, -1, 14163, 14177, 14173, -1, 14172, 14178, 14167, -1, 14171, 14128, 14179, -1, 14167, 14178, 14174, -1, 12048, 14178, 14172, -1, 14174, 14178, 13554, -1, 14170, 14128, 14171, -1, 14173, 14133, 14169, -1, 14169, 14133, 14176, -1, 14170, 14137, 14128, -1, 14176, 14137, 14170, -1, 14173, 14132, 14133, -1, 12036, 14132, 14177, -1, 14177, 14132, 14173, -1, 14179, 14130, 14136, -1, 14128, 14130, 14179, -1, 14133, 14134, 14176, -1, 14176, 14134, 14137, -1, 14137, 14129, 14128, -1, 14180, 11709, 11708, -1, 14181, 14180, 11708, -1, 14182, 14181, 11708, -1, 14183, 14182, 11708, -1, 14184, 14182, 14183, -1, 14185, 14184, 14183, -1, 14186, 14187, 14188, -1, 14189, 14186, 14188, -1, 14190, 14191, 14189, -1, 14190, 14189, 14188, -1, 14192, 14191, 14190, -1, 14193, 14194, 14195, -1, 14196, 14197, 14193, -1, 14196, 14193, 14195, -1, 14198, 14197, 14196, -1, 14199, 14198, 14196, -1, 14200, 14201, 14202, -1, 14203, 14204, 14201, -1, 14204, 14205, 14201, -1, 14205, 14206, 14201, -1, 14206, 14207, 14201, -1, 14208, 14209, 14207, -1, 14207, 14209, 14201, -1, 14210, 14211, 14212, -1, 14212, 14211, 14213, -1, 14213, 14211, 14209, -1, 14201, 14211, 14202, -1, 14209, 14211, 14201, -1, 14210, 14214, 14211, -1, 14214, 14215, 14211, -1, 14186, 14152, 14161, -1, 14148, 14189, 14142, -1, 14189, 14136, 14142, -1, 14136, 14191, 14179, -1, 14189, 14191, 14136, -1, 14191, 14171, 14179, -1, 14191, 14166, 14171, -1, 14191, 14192, 14166, -1, 14192, 14165, 14166, -1, 14186, 14189, 14152, -1, 14152, 14189, 14148, -1, 14194, 13590, 13592, -1, 13597, 14193, 13604, -1, 14193, 13608, 13604, -1, 13608, 14197, 13610, -1, 14193, 14197, 13608, -1, 14197, 13612, 13610, -1, 14197, 13589, 13612, -1, 13589, 14198, 13546, -1, 14197, 14198, 13589, -1, 14198, 13547, 13546, -1, 14194, 14193, 13590, -1, 13590, 14193, 13597, -1, 14180, 13576, 13579, -1, 13576, 14181, 13572, -1, 14181, 13563, 13572, -1, 14181, 13558, 13563, -1, 13558, 14182, 13545, -1, 14181, 14182, 13558, -1, 14182, 13531, 13545, -1, 14182, 13529, 13531, -1, 14182, 13587, 13529, -1, 13616, 14184, 13614, -1, 13587, 14184, 13616, -1, 14184, 13607, 13614, -1, 14184, 13602, 13607, -1, 14184, 13600, 13602, -1, 13596, 14185, 13594, -1, 13600, 14185, 13596, -1, 14184, 14185, 13600, -1, 14185, 13593, 13594, -1, 14180, 14181, 13576, -1, 14182, 14184, 13587, -1, 14190, 14188, 14201, -1, 14190, 14201, 14200, -1, 14196, 14195, 14202, -1, 14196, 14202, 14211, -1, 14216, 14217, 14218, -1, 14219, 14216, 14218, -1, 14220, 14219, 14218, -1, 14221, 14220, 14218, -1, 14222, 14220, 14221, -1, 14223, 14222, 14221, -1, 14224, 14225, 14226, -1, 14227, 14224, 14226, -1, 14228, 14229, 14227, -1, 14228, 14227, 14226, -1, 14230, 14229, 14228, -1, 14231, 14232, 14233, -1, 11516, 14234, 14231, -1, 11516, 14231, 14233, -1, 14235, 14234, 11516, -1, 11825, 14235, 11516, -1, 11512, 11501, 11513, -1, 11512, 11502, 11501, -1, 14236, 14237, 11512, -1, 14238, 14237, 14236, -1, 11502, 11519, 11506, -1, 11506, 11519, 11509, -1, 11509, 11519, 11518, -1, 14237, 11519, 11512, -1, 11512, 11519, 11502, -1, 14239, 14240, 14237, -1, 11519, 14241, 14242, -1, 14240, 14243, 14237, -1, 14237, 14243, 11519, -1, 11519, 14244, 14241, -1, 14243, 14244, 11519, -1, 14224, 14245, 14246, -1, 14247, 14227, 14248, -1, 14227, 14249, 14248, -1, 14249, 14229, 14250, -1, 14227, 14229, 14249, -1, 14229, 14251, 14250, -1, 14229, 14252, 14251, -1, 14229, 14230, 14252, -1, 14230, 14253, 14252, -1, 14224, 14227, 14245, -1, 14245, 14227, 14247, -1, 14232, 14254, 14255, -1, 14256, 14231, 14257, -1, 14231, 14258, 14257, -1, 14258, 14234, 14259, -1, 14231, 14234, 14258, -1, 14234, 14260, 14259, -1, 14234, 14261, 14260, -1, 14234, 14235, 14261, -1, 14235, 14262, 14261, -1, 14232, 14231, 14254, -1, 14254, 14231, 14256, -1, 14216, 14263, 14264, -1, 14216, 14265, 14263, -1, 14265, 14219, 14266, -1, 14219, 14267, 14266, -1, 14219, 14268, 14267, -1, 14219, 14269, 14268, -1, 14269, 14220, 14270, -1, 14220, 14271, 14270, -1, 14220, 14272, 14271, -1, 14220, 14273, 14272, -1, 14273, 14222, 14274, -1, 14222, 14275, 14274, -1, 14222, 14276, 14275, -1, 14222, 14277, 14276, -1, 14277, 14223, 14278, -1, 14222, 14223, 14277, -1, 14223, 14279, 14278, -1, 14216, 14219, 14265, -1, 14219, 14220, 14269, -1, 14220, 14222, 14273, -1, 11512, 14233, 14236, -1, 11516, 14233, 11512, -1, 14228, 14226, 14237, -1, 14228, 14237, 14238, -1, 14280, 12121, 12123, -1, 14280, 12123, 14281, -1, 11542, 11544, 14282, -1, 11542, 14282, 14283, -1, 12139, 14284, 14285, -1, 14286, 12121, 14280, -1, 12137, 14285, 14287, -1, 11540, 14283, 14288, -1, 12137, 12139, 14285, -1, 11540, 11542, 14283, -1, 12141, 14289, 14284, -1, 11523, 12120, 12121, -1, 11523, 14290, 12120, -1, 12141, 14284, 12139, -1, 11523, 12121, 14286, -1, 12135, 14287, 14291, -1, 12135, 12137, 14287, -1, 11537, 14288, 14292, -1, 11537, 11540, 14288, -1, 12143, 11554, 14289, -1, 11526, 14293, 14290, -1, 12143, 14289, 12141, -1, 11526, 14290, 11523, -1, 12133, 14291, 14294, -1, 12133, 12135, 14291, -1, 11535, 11537, 14292, -1, 11535, 14292, 14295, -1, 11531, 14296, 14293, -1, 11531, 14293, 11526, -1, 12145, 11554, 12143, -1, 11533, 14295, 14297, -1, 11533, 11535, 14295, -1, 12131, 14294, 14298, -1, 12131, 12133, 14294, -1, 11532, 14297, 14296, -1, 11532, 11533, 14297, -1, 11532, 14296, 11531, -1, 14299, 11552, 11554, -1, 14299, 11550, 11552, -1, 14299, 11554, 12145, -1, 12129, 14298, 14300, -1, 12129, 12131, 14298, -1, 14301, 11550, 14299, -1, 12127, 14300, 14302, -1, 12127, 12129, 14300, -1, 11549, 11550, 14301, -1, 14303, 11549, 14301, -1, 12125, 12127, 14302, -1, 14281, 12125, 14302, -1, 12123, 12125, 14281, -1, 11544, 11549, 14303, -1, 11544, 14303, 14282, -1, 11605, 11610, 14304, -1, 11605, 14304, 14305, -1, 14306, 12148, 12150, -1, 14306, 12150, 14307, -1, 12166, 14308, 14309, -1, 12164, 14309, 14310, -1, 12164, 12166, 14309, -1, 12168, 14311, 14308, -1, 11603, 11605, 14305, -1, 12168, 14308, 12166, -1, 11603, 14305, 14312, -1, 14313, 12148, 14306, -1, 12162, 14310, 14314, -1, 12162, 12164, 14310, -1, 12170, 14311, 12168, -1, 11601, 14312, 14315, -1, 11601, 11603, 14312, -1, 12160, 14314, 14316, -1, 12160, 12162, 14314, -1, 11587, 12146, 12148, -1, 11587, 14317, 12146, -1, 12172, 11614, 14311, -1, 12172, 11612, 11614, -1, 11587, 12148, 14313, -1, 12172, 14311, 12170, -1, 11599, 14315, 14318, -1, 11599, 11601, 14315, -1, 11589, 14319, 14317, -1, 12158, 14316, 14320, -1, 12158, 12160, 14316, -1, 11589, 14317, 11587, -1, 14321, 11611, 11612, -1, 11597, 14318, 14322, -1, 11597, 11599, 14318, -1, 14321, 11612, 12172, -1, 11591, 14323, 14319, -1, 11591, 14319, 11589, -1, 12156, 14320, 14324, -1, 12156, 12158, 14320, -1, 11595, 14322, 14325, -1, 11595, 11597, 14322, -1, 11593, 14325, 14323, -1, 11593, 14323, 11591, -1, 14326, 11611, 14321, -1, 11593, 11595, 14325, -1, 12154, 14324, 14327, -1, 12154, 12156, 14324, -1, 11610, 11611, 14326, -1, 14304, 11610, 14326, -1, 12152, 12154, 14327, -1, 14307, 12152, 14327, -1, 12150, 12152, 14307, -1, 14328, 12095, 14329, -1, 14328, 12093, 12095, -1, 11574, 11576, 14330, -1, 11574, 14330, 14331, -1, 14332, 12092, 12093, -1, 14332, 12093, 14328, -1, 12111, 14333, 14334, -1, 11572, 14331, 14335, -1, 11572, 11574, 14331, -1, 12109, 14334, 14336, -1, 12109, 12111, 14334, -1, 11556, 12092, 14332, -1, 12113, 14337, 14333, -1, 12113, 14333, 12111, -1, 11570, 14335, 14338, -1, 11570, 11572, 14335, -1, 12107, 14336, 14339, -1, 12107, 12109, 14336, -1, 11559, 14340, 12092, -1, 11559, 14341, 14340, -1, 12115, 11584, 14337, -1, 11559, 12092, 11556, -1, 12115, 14337, 12113, -1, 11568, 14338, 14342, -1, 12105, 14339, 14343, -1, 11568, 11570, 14338, -1, 12105, 12107, 14339, -1, 11563, 14344, 14341, -1, 11563, 14341, 11559, -1, 11566, 11568, 14342, -1, 11566, 14342, 14345, -1, 11564, 14345, 14344, -1, 11564, 11566, 14345, -1, 12117, 11584, 12115, -1, 11564, 14344, 11563, -1, 12103, 14343, 14346, -1, 12103, 12105, 14343, -1, 14347, 11582, 11584, -1, 14347, 11580, 11582, -1, 14347, 11584, 12117, -1, 12101, 14346, 14348, -1, 12101, 12103, 14346, -1, 14349, 11580, 14347, -1, 12099, 14348, 14350, -1, 12099, 12101, 14348, -1, 11578, 11580, 14349, -1, 14351, 11578, 14349, -1, 12097, 12099, 14350, -1, 14329, 12097, 14350, -1, 12095, 12097, 14329, -1, 11576, 11578, 14351, -1, 11576, 14351, 14330, -1, 14352, 14353, 14354, -1, 14355, 12327, 14356, -1, 14357, 12327, 14355, -1, 14358, 12327, 14357, -1, 14359, 12349, 14360, -1, 14356, 12349, 14359, -1, 14361, 14362, 14363, -1, 12327, 12349, 14356, -1, 14364, 14362, 14361, -1, 14363, 14365, 14366, -1, 14362, 14365, 14363, -1, 14367, 14368, 14369, -1, 14366, 14368, 14367, -1, 14365, 14368, 14366, -1, 14370, 14371, 14372, -1, 14372, 14373, 14374, -1, 14371, 14373, 14372, -1, 14360, 12351, 14375, -1, 14374, 14376, 14377, -1, 14373, 14376, 14374, -1, 12349, 12351, 14360, -1, 14377, 14378, 14379, -1, 14376, 14378, 14377, -1, 14378, 14380, 14379, -1, 14379, 14380, 14381, -1, 14380, 14382, 14381, -1, 14381, 14382, 14383, -1, 14382, 14384, 14383, -1, 14385, 14386, 14387, -1, 14388, 14386, 14385, -1, 14387, 14389, 14390, -1, 14386, 14389, 14387, -1, 14390, 14391, 14392, -1, 14389, 14391, 14390, -1, 14392, 14393, 14394, -1, 14391, 14393, 14392, -1, 14394, 14395, 14396, -1, 14393, 14395, 14394, -1, 14396, 14397, 14398, -1, 14395, 14397, 14396, -1, 14399, 14400, 14401, -1, 14402, 14400, 14399, -1, 14400, 14403, 14401, -1, 14401, 14403, 14404, -1, 14403, 14405, 14404, -1, 14404, 14405, 14406, -1, 14405, 14407, 14406, -1, 14406, 14407, 14408, -1, 14407, 14409, 14408, -1, 14410, 14411, 14412, -1, 14413, 14414, 14415, -1, 14415, 14414, 14416, -1, 14414, 14417, 14416, -1, 14416, 14417, 14418, -1, 14418, 14419, 14420, -1, 14417, 14419, 14418, -1, 14412, 14421, 14422, -1, 14419, 14423, 14420, -1, 14420, 14423, 14424, -1, 14423, 14425, 14424, -1, 14424, 14425, 14358, -1, 14411, 14421, 14412, -1, 14426, 14427, 14428, -1, 14428, 14427, 14429, -1, 14430, 14431, 14426, -1, 14375, 14431, 14430, -1, 14427, 14431, 12384, -1, 14426, 14431, 14427, -1, 12351, 14431, 14375, -1, 12370, 14431, 12351, -1, 12384, 14431, 12370, -1, 12384, 14432, 14427, -1, 14421, 14433, 14422, -1, 14427, 14432, 14429, -1, 14434, 14432, 14435, -1, 14429, 14432, 14434, -1, 12396, 14432, 12384, -1, 14436, 14437, 14438, -1, 12420, 14437, 12410, -1, 14439, 14440, 14441, -1, 14442, 14440, 14439, -1, 14354, 14440, 14442, -1, 14353, 14440, 14354, -1, 14443, 14440, 14444, -1, 14444, 14440, 14353, -1, 12420, 14445, 14437, -1, 14352, 14445, 14353, -1, 14437, 14445, 14438, -1, 14438, 14445, 14352, -1, 12430, 14445, 12420, -1, 14446, 14447, 14448, -1, 14449, 14447, 14446, -1, 14450, 14451, 14448, -1, 14443, 14451, 14450, -1, 12332, 14451, 12437, -1, 14452, 14453, 14361, -1, 14454, 14453, 14452, -1, 14364, 14453, 14455, -1, 14449, 14453, 14447, -1, 14447, 14453, 14454, -1, 14455, 14453, 14449, -1, 14361, 14453, 14364, -1, 14448, 14456, 14446, -1, 14451, 14456, 14448, -1, 12332, 14456, 14451, -1, 12347, 14456, 12332, -1, 14362, 14457, 14365, -1, 14365, 14457, 14368, -1, 14458, 14457, 12360, -1, 14369, 14459, 14460, -1, 14457, 14459, 14368, -1, 14368, 14459, 14369, -1, 14458, 14459, 14457, -1, 14461, 14459, 14458, -1, 14462, 14463, 14410, -1, 14464, 14463, 14462, -1, 14460, 14463, 14464, -1, 14459, 14463, 14460, -1, 14410, 14463, 14411, -1, 14461, 14463, 14459, -1, 14411, 14463, 14461, -1, 14465, 14466, 14370, -1, 14370, 14466, 14371, -1, 14371, 14466, 14373, -1, 14467, 14468, 14465, -1, 14422, 14468, 14467, -1, 14433, 14468, 14422, -1, 14466, 14468, 14469, -1, 14469, 14468, 14433, -1, 14465, 14468, 14466, -1, 14373, 14470, 14376, -1, 14376, 14470, 14378, -1, 14466, 14470, 14373, -1, 14469, 14470, 14466, -1, 14471, 14470, 14469, -1, 14472, 14473, 14474, -1, 14383, 14473, 14475, -1, 14384, 14473, 14383, -1, 14474, 14473, 14384, -1, 14378, 14476, 14380, -1, 14471, 14476, 14470, -1, 14477, 14476, 14471, -1, 14470, 14476, 14378, -1, 14478, 14479, 14480, -1, 14384, 14479, 14474, -1, 14388, 14481, 14482, -1, 14483, 14481, 14385, -1, 14385, 14481, 14388, -1, 14482, 14481, 14484, -1, 14474, 14485, 14472, -1, 14472, 14485, 14486, -1, 14487, 14485, 14478, -1, 14479, 14485, 14474, -1, 14478, 14485, 14479, -1, 14484, 14488, 14482, -1, 14489, 14488, 14484, -1, 14486, 14488, 14489, -1, 14490, 14488, 14487, -1, 14487, 14488, 14485, -1, 14485, 14488, 14486, -1, 14482, 14491, 14388, -1, 14488, 14491, 14482, -1, 14492, 14491, 14490, -1, 14490, 14491, 14488, -1, 14389, 14493, 14391, -1, 14494, 14493, 14495, -1, 14391, 14496, 14393, -1, 14393, 14496, 14395, -1, 14493, 14496, 14391, -1, 14497, 14496, 14494, -1, 14494, 14496, 14493, -1, 14398, 14498, 14499, -1, 14497, 14498, 14496, -1, 14397, 14498, 14398, -1, 14395, 14498, 14397, -1, 14496, 14498, 14395, -1, 14498, 14500, 14499, -1, 14501, 14500, 14502, -1, 14497, 14500, 14498, -1, 14503, 14500, 14501, -1, 14499, 14500, 14503, -1, 14502, 14500, 14497, -1, 14504, 14505, 14506, -1, 14402, 14505, 14400, -1, 14507, 14505, 14402, -1, 14506, 14505, 14507, -1, 14508, 14505, 14504, -1, 14509, 14510, 14409, -1, 14408, 14510, 14511, -1, 14409, 14510, 14408, -1, 14512, 14510, 14509, -1, 14505, 14513, 14400, -1, 14508, 14513, 14505, -1, 14403, 14513, 14405, -1, 12357, 14513, 14508, -1, 14400, 14513, 14403, -1, 14409, 14514, 14509, -1, 12369, 14514, 12356, -1, 14515, 14516, 14517, -1, 14514, 14518, 14509, -1, 12375, 14518, 12369, -1, 14509, 14518, 14512, -1, 14512, 14518, 14519, -1, 12369, 14518, 14514, -1, 12375, 14520, 14518, -1, 14518, 14520, 14519, -1, 12383, 14520, 12375, -1, 14519, 14520, 14521, -1, 14521, 14520, 14517, -1, 14522, 14523, 14413, -1, 12398, 14523, 12392, -1, 14524, 14523, 14522, -1, 14502, 14525, 14501, -1, 12398, 14526, 14523, -1, 14413, 14526, 14414, -1, 14414, 14526, 14417, -1, 14527, 14525, 14528, -1, 14529, 14525, 14527, -1, 12406, 14526, 12398, -1, 14501, 14525, 14529, -1, 14523, 14526, 14413, -1, 14417, 14530, 14419, -1, 14526, 14530, 14417, -1, 12406, 14530, 14526, -1, 12418, 14530, 12406, -1, 14425, 14531, 14358, -1, 14358, 14531, 12327, -1, 12327, 14531, 12429, -1, 14532, 14533, 14436, -1, 14432, 14533, 14435, -1, 14435, 14533, 14532, -1, 14436, 14533, 14437, -1, 14437, 14534, 12410, -1, 12396, 14534, 14432, -1, 14533, 14534, 14437, -1, 14432, 14534, 14533, -1, 14535, 14536, 14506, -1, 12410, 14534, 12396, -1, 14528, 14536, 14535, -1, 14537, 14538, 14454, -1, 14441, 14538, 14537, -1, 14447, 14538, 14448, -1, 14454, 14538, 14447, -1, 14440, 14539, 14441, -1, 14525, 14536, 14528, -1, 14443, 14539, 14440, -1, 14448, 14539, 14450, -1, 14538, 14539, 14448, -1, 14441, 14539, 14538, -1, 14450, 14539, 14443, -1, 14445, 14540, 14353, -1, 14443, 14540, 14451, -1, 14444, 14540, 14443, -1, 14353, 14540, 14444, -1, 12430, 14541, 14445, -1, 14451, 14541, 12437, -1, 14540, 14541, 14451, -1, 14445, 14541, 14540, -1, 12437, 14541, 12430, -1, 14456, 14542, 14446, -1, 14536, 14504, 14506, -1, 14449, 14542, 14455, -1, 14446, 14542, 14449, -1, 14456, 14543, 14542, -1, 12347, 14543, 14456, -1, 12346, 14543, 12347, -1, 14455, 14544, 14364, -1, 14362, 14544, 14457, -1, 14364, 14544, 14362, -1, 12360, 14545, 12346, -1, 14544, 14545, 14457, -1, 14457, 14545, 12360, -1, 14546, 14547, 14548, -1, 14475, 14547, 14546, -1, 14473, 14547, 14475, -1, 14380, 14549, 14382, -1, 14382, 14549, 14384, -1, 14476, 14549, 14380, -1, 14384, 14549, 14479, -1, 14483, 14550, 14481, -1, 14551, 14550, 14483, -1, 14548, 14550, 14551, -1, 14547, 14550, 14548, -1, 14479, 14552, 14480, -1, 14476, 14552, 14549, -1, 14480, 14552, 14477, -1, 14549, 14552, 14479, -1, 14477, 14552, 14476, -1, 14386, 14553, 14389, -1, 14491, 14553, 14388, -1, 14389, 14553, 14493, -1, 14388, 14553, 14386, -1, 14491, 14554, 14553, -1, 14495, 14554, 14492, -1, 14553, 14554, 14493, -1, 14492, 14554, 14491, -1, 14493, 14554, 14495, -1, 14555, 14556, 14557, -1, 14511, 14556, 14555, -1, 14510, 14556, 14511, -1, 14513, 14558, 14405, -1, 14407, 14558, 14409, -1, 14409, 14558, 14514, -1, 14405, 14558, 14407, -1, 14559, 14560, 14516, -1, 14561, 14560, 14559, -1, 14557, 14560, 14561, -1, 14556, 14560, 14557, -1, 12357, 14562, 14513, -1, 14514, 14562, 12356, -1, 14513, 14562, 14558, -1, 14558, 14562, 14514, -1, 12356, 14562, 12357, -1, 14524, 14563, 14515, -1, 14522, 14563, 14524, -1, 14515, 14563, 14516, -1, 14517, 14564, 14515, -1, 14515, 14564, 14524, -1, 14524, 14564, 14523, -1, 14520, 14564, 14517, -1, 14520, 14565, 14564, -1, 12383, 14565, 14520, -1, 14523, 14565, 12392, -1, 12392, 14565, 12383, -1, 14564, 14565, 14523, -1, 14530, 14566, 14419, -1, 14419, 14566, 14423, -1, 14423, 14566, 14425, -1, 14531, 14566, 12429, -1, 14425, 14566, 14531, -1, 14566, 14567, 12429, -1, 12418, 14567, 14530, -1, 12429, 14567, 12418, -1, 14530, 14567, 14566, -1, 14455, 14568, 14544, -1, 14543, 14568, 14542, -1, 12346, 14568, 14543, -1, 14545, 14568, 12346, -1, 14544, 14568, 14545, -1, 14542, 14568, 14455, -1, 14472, 14569, 14473, -1, 14484, 14569, 14489, -1, 14473, 14569, 14547, -1, 14489, 14569, 14486, -1, 14486, 14569, 14472, -1, 14550, 14569, 14481, -1, 14547, 14569, 14550, -1, 14481, 14569, 14484, -1, 14512, 14570, 14510, -1, 14510, 14570, 14556, -1, 14521, 14570, 14519, -1, 14519, 14570, 14512, -1, 14560, 14570, 14516, -1, 14556, 14570, 14560, -1, 14516, 14570, 14517, -1, 14517, 14570, 14521, -1, 14413, 14571, 14522, -1, 14563, 14571, 14516, -1, 14415, 14571, 14413, -1, 14516, 14571, 14559, -1, 14572, 14571, 14415, -1, 14573, 14571, 14572, -1, 14559, 14571, 14573, -1, 14522, 14571, 14563, -1, 14428, 14429, 14574, -1, 14574, 14434, 14575, -1, 14429, 14434, 14574, -1, 14575, 14435, 14576, -1, 14434, 14435, 14575, -1, 14576, 14532, 14577, -1, 14435, 14532, 14576, -1, 14577, 14436, 14578, -1, 14532, 14436, 14577, -1, 14436, 14438, 14578, -1, 14578, 14438, 14579, -1, 14579, 14352, 14354, -1, 14438, 14352, 14579, -1, 14580, 14581, 14582, -1, 14583, 14584, 14585, -1, 14583, 14586, 14584, -1, 14583, 14587, 14586, -1, 14588, 14589, 13222, -1, 14588, 13222, 13221, -1, 14590, 13221, 13218, -1, 14590, 13218, 13217, -1, 14590, 13217, 14591, -1, 14590, 14580, 14589, -1, 14590, 14591, 14580, -1, 14590, 14588, 13221, -1, 14590, 14589, 14588, -1, 14592, 14593, 14587, -1, 14592, 14583, 14585, -1, 14592, 14587, 14583, -1, 14592, 14585, 14593, -1, 14594, 13239, 13269, -1, 14594, 13240, 13239, -1, 14594, 13269, 14595, -1, 14594, 13274, 13240, -1, 14596, 14597, 14598, -1, 14596, 14594, 14595, -1, 14596, 14595, 14599, -1, 14596, 14599, 14600, -1, 14596, 14600, 14597, -1, 14596, 13274, 14594, -1, 14596, 14598, 13274, -1, 14601, 14602, 14603, -1, 14601, 14604, 14605, -1, 14606, 13271, 13275, -1, 14601, 14607, 14608, -1, 14601, 14605, 14609, -1, 13272, 13271, 14606, -1, 14601, 14603, 14604, -1, 14601, 14609, 14607, -1, 14601, 14608, 14602, -1, 14610, 14611, 14612, -1, 14610, 14613, 14614, -1, 14610, 14615, 14613, -1, 14610, 14614, 14611, -1, 14610, 14612, 14615, -1, 14616, 13272, 14606, -1, 11300, 13272, 14616, -1, 14617, 11300, 14616, -1, 14617, 14616, 14618, -1, 14617, 14618, 14619, -1, 14593, 14585, 14620, -1, 14621, 14593, 14620, -1, 13231, 14622, 14623, -1, 13231, 14623, 13232, -1, 13253, 14621, 14622, -1, 13253, 14622, 13231, -1, 11291, 14593, 14621, -1, 11291, 14621, 13253, -1, 14595, 13269, 14599, -1, 14600, 14599, 14624, -1, 14625, 14624, 14598, -1, 14625, 14600, 14624, -1, 14597, 14625, 14598, -1, 14597, 14600, 14625, -1, 14626, 14624, 14627, -1, 14626, 14598, 14624, -1, 14626, 14628, 14598, -1, 14629, 14617, 14619, -1, 14629, 14619, 14630, -1, 14629, 14630, 14631, -1, 14632, 14626, 14627, -1, 14632, 14628, 14626, -1, 14633, 14629, 14631, -1, 14633, 14617, 14629, -1, 14633, 14634, 14617, -1, 14633, 14631, 14635, -1, 14636, 14632, 14627, -1, 14636, 14627, 14637, -1, 14636, 14628, 14632, -1, 14636, 14638, 14628, -1, 14639, 14633, 14635, -1, 14639, 14635, 14640, -1, 14639, 14634, 14633, -1, 14641, 14640, 14642, -1, 14641, 14639, 14640, -1, 14643, 14636, 14637, -1, 14643, 14638, 14636, -1, 14644, 14634, 14639, -1, 14644, 14645, 14634, -1, 14644, 14639, 14641, -1, 14646, 14641, 14642, -1, 14647, 14637, 14648, -1, 14647, 14643, 14637, -1, 14647, 14638, 14643, -1, 14647, 14649, 14638, -1, 14650, 14645, 14644, -1, 14650, 14644, 14641, -1, 14650, 14641, 14646, -1, 14651, 14642, 14652, -1, 14651, 14646, 14642, -1, 14653, 14648, 14654, -1, 14653, 14647, 14648, -1, 14653, 14649, 14647, -1, 14653, 14654, 14649, -1, 14655, 14645, 14650, -1, 14655, 14650, 14646, -1, 14655, 14646, 14651, -1, 14655, 14656, 14645, -1, 14657, 14651, 14652, -1, 14657, 14652, 14658, -1, 14659, 14648, 14660, -1, 14659, 14654, 14648, -1, 14661, 14655, 14651, -1, 14661, 14651, 14657, -1, 14661, 14656, 14655, -1, 14662, 14658, 14663, -1, 14662, 14657, 14658, -1, 14664, 14660, 14665, -1, 14664, 14659, 14660, -1, 14664, 14654, 14659, -1, 14664, 14665, 14654, -1, 14666, 14657, 14662, -1, 14666, 14667, 14656, -1, 14666, 14661, 14657, -1, 14666, 14656, 14661, -1, 14668, 14663, 14669, -1, 14668, 14662, 14663, -1, 14670, 14660, 14671, -1, 14670, 14665, 14660, -1, 14670, 14672, 14665, -1, 14673, 14667, 14666, -1, 14673, 14666, 14662, -1, 14673, 14662, 14668, -1, 14674, 14668, 14669, -1, 14675, 14672, 14670, -1, 14675, 14670, 14671, -1, 14676, 14668, 14674, -1, 14676, 14677, 14667, -1, 14676, 14673, 14668, -1, 14676, 14667, 14673, -1, 14678, 14674, 14669, -1, 14678, 14676, 14674, -1, 14678, 14677, 14676, -1, 14678, 14669, 14679, -1, 14680, 14672, 14675, -1, 14680, 14675, 14671, -1, 14680, 14681, 14672, -1, 14682, 14678, 14679, -1, 14682, 14679, 14683, -1, 14684, 14671, 14685, -1, 14684, 14681, 14680, -1, 14684, 14680, 14671, -1, 14684, 14686, 14681, -1, 14687, 14678, 14682, -1, 14687, 14688, 14677, -1, 14687, 14677, 14678, -1, 14689, 14682, 14683, -1, 14689, 14683, 14690, -1, 14689, 14688, 14687, -1, 14689, 14687, 14682, -1, 14691, 14684, 14685, -1, 14691, 14686, 14684, -1, 14692, 14690, 14693, -1, 14692, 14689, 14690, -1, 14694, 14695, 14696, -1, 14694, 14685, 14695, -1, 14694, 14686, 14691, -1, 14694, 14691, 14685, -1, 14694, 14696, 14686, -1, 14697, 14698, 14688, -1, 14697, 14689, 14692, -1, 14697, 14688, 14689, -1, 14699, 14697, 14692, -1, 14699, 14698, 14697, -1, 14699, 14692, 14693, -1, 14700, 14701, 14702, -1, 14703, 14696, 14695, -1, 14700, 14702, 14704, -1, 14703, 14695, 14705, -1, 14703, 14706, 14696, -1, 14707, 14699, 14693, -1, 14707, 14693, 14708, -1, 14709, 14703, 14705, -1, 14710, 14700, 14711, -1, 14709, 14706, 14703, -1, 14712, 14699, 14707, -1, 14712, 14698, 14699, -1, 14712, 14713, 14698, -1, 14712, 14707, 14708, -1, 14714, 14712, 14708, -1, 14714, 14713, 14712, -1, 14714, 14708, 14715, -1, 14716, 14709, 14705, -1, 14716, 14717, 14706, -1, 14716, 14706, 14709, -1, 14718, 14714, 14715, -1, 14608, 14705, 14602, -1, 14608, 14716, 14705, -1, 14608, 14717, 14716, -1, 14608, 14607, 14717, -1, 14719, 14720, 14713, -1, 14719, 14713, 14714, -1, 14719, 14714, 14718, -1, 14721, 14701, 14720, -1, 14721, 14718, 14715, -1, 14721, 14720, 14719, -1, 14721, 14715, 14722, -1, 14721, 14719, 14718, -1, 14609, 14605, 14607, -1, 14723, 14702, 14701, -1, 14723, 14722, 14702, -1, 14723, 14721, 14722, -1, 14723, 14701, 14721, -1, 14724, 14700, 14710, -1, 14604, 14725, 14605, -1, 14726, 14725, 14604, -1, 14726, 14727, 14728, -1, 14724, 14710, 14729, -1, 14726, 14728, 14730, -1, 14726, 14604, 14603, -1, 14726, 14730, 14725, -1, 14731, 14711, 14700, -1, 14731, 14700, 14704, -1, 14731, 14704, 14732, -1, 14731, 14732, 14733, -1, 14731, 14733, 14711, -1, 14734, 14735, 14736, -1, 14734, 14736, 14727, -1, 14734, 14726, 14603, -1, 14734, 14727, 14726, -1, 14737, 14603, 14738, -1, 14737, 14734, 14603, -1, 14739, 14735, 14734, -1, 14739, 14740, 14741, -1, 14739, 14741, 14742, -1, 14739, 14742, 14735, -1, 14743, 14734, 14737, -1, 14743, 14737, 14738, -1, 14744, 14740, 14739, -1, 14744, 14724, 14729, -1, 14744, 14729, 14740, -1, 14745, 14739, 14734, -1, 14745, 14734, 14743, -1, 14746, 14743, 14738, -1, 14747, 14748, 14724, -1, 14747, 14724, 14744, -1, 14747, 14739, 14745, -1, 14747, 14744, 14739, -1, 14749, 14745, 14743, -1, 14750, 14751, 14752, -1, 14749, 14743, 14746, -1, 14753, 14738, 14754, -1, 14753, 14746, 14738, -1, 14755, 14748, 14747, -1, 14755, 14745, 14749, -1, 14755, 14747, 14745, -1, 14756, 14749, 14746, -1, 14756, 14746, 14753, -1, 14757, 14754, 14758, -1, 14757, 14753, 14754, -1, 14759, 14748, 14755, -1, 14759, 14760, 14748, -1, 14759, 14755, 14749, -1, 14759, 14749, 14756, -1, 14761, 14753, 14757, -1, 14761, 14756, 14753, -1, 14761, 14757, 14758, -1, 14762, 14760, 14759, -1, 14762, 14759, 14756, -1, 14763, 14764, 14765, -1, 14762, 14756, 14761, -1, 14766, 14761, 14758, -1, 14766, 14758, 14767, -1, 14768, 14761, 14766, -1, 14768, 14762, 14761, -1, 14768, 14769, 14760, -1, 14768, 14760, 14762, -1, 14770, 14766, 14767, -1, 14771, 14768, 14766, -1, 14771, 14766, 14770, -1, 14771, 14769, 14768, -1, 14772, 14767, 14773, -1, 14772, 14770, 14767, -1, 14774, 14772, 14773, -1, 14774, 14769, 14771, -1, 14774, 14770, 14772, -1, 14774, 14775, 14769, -1, 14774, 14771, 14770, -1, 14774, 14773, 14775, -1, 14776, 14773, 14777, -1, 14776, 14777, 14778, -1, 14776, 14775, 14773, -1, 14779, 14778, 14751, -1, 14779, 14750, 14775, -1, 14779, 14776, 14778, -1, 14779, 14775, 14776, -1, 14779, 14751, 14750, -1, 14780, 14752, 14781, -1, 14780, 14781, 14782, -1, 14780, 14763, 14750, -1, 14780, 14750, 14752, -1, 14783, 14780, 14782, -1, 14783, 14764, 14763, -1, 14783, 14782, 14764, -1, 14783, 14763, 14780, -1, 14784, 14763, 14765, -1, 14784, 14785, 14763, -1, 14784, 14765, 14786, -1, 14784, 14786, 14787, -1, 14788, 14789, 14785, -1, 14788, 14787, 14790, -1, 14788, 14790, 14789, -1, 14788, 14784, 14787, -1, 14788, 14785, 14784, -1, 14791, 14785, 14789, -1, 14791, 14789, 14792, -1, 14793, 14792, 14794, -1, 14793, 14791, 14792, -1, 14795, 14794, 14796, -1, 14797, 14785, 14791, -1, 14797, 14798, 14785, -1, 14797, 14791, 14793, -1, 14799, 14793, 14794, -1, 14799, 14794, 14795, -1, 14799, 14795, 14796, -1, 14799, 14798, 14797, -1, 14799, 14797, 14793, -1, 14800, 14796, 14801, -1, 14802, 14799, 14796, -1, 14802, 14796, 14800, -1, 14803, 14800, 14801, -1, 14804, 14805, 14798, -1, 14804, 14798, 14799, -1, 14804, 14799, 14802, -1, 14806, 14801, 14807, -1, 14806, 14803, 14801, -1, 14808, 14805, 14804, -1, 14808, 14802, 14800, -1, 14808, 14800, 14803, -1, 14808, 14804, 14802, -1, 14809, 14806, 14807, -1, 14809, 14803, 14806, -1, 14810, 14807, 14811, -1, 14812, 14808, 14803, -1, 14812, 14803, 14809, -1, 14813, 14809, 14807, -1, 14813, 14807, 14810, -1, 14814, 14815, 14805, -1, 14814, 14805, 14808, -1, 14814, 14808, 14812, -1, 14816, 14811, 14817, -1, 14816, 14810, 14811, -1, 14818, 14815, 14814, -1, 14818, 14812, 14809, -1, 14818, 14809, 14813, -1, 14818, 14814, 14812, -1, 14819, 14820, 14821, -1, 14819, 14821, 14822, -1, 14819, 14813, 14810, -1, 14819, 14816, 14820, -1, 14819, 14810, 14816, -1, 14823, 14816, 14817, -1, 14823, 14824, 14825, -1, 14823, 14825, 14820, -1, 14823, 14820, 14816, -1, 14826, 14813, 14819, -1, 14826, 14822, 14827, -1, 14826, 14827, 14828, -1, 14826, 14819, 14822, -1, 14826, 14818, 14813, -1, 14829, 14817, 14830, -1, 14829, 14823, 14817, -1, 14831, 14826, 14828, -1, 14831, 14832, 14815, -1, 14831, 14833, 14832, -1, 14831, 14818, 14826, -1, 14831, 14828, 14833, -1, 14831, 14815, 14818, -1, 14834, 14824, 14823, -1, 14835, 14832, 14833, -1, 14834, 14829, 14830, -1, 14834, 14823, 14829, -1, 14834, 14830, 14836, -1, 14834, 14836, 14824, -1, 14837, 14836, 14830, -1, 14838, 14830, 14839, -1, 14838, 14837, 14830, -1, 14840, 14841, 14842, -1, 14840, 14843, 14841, -1, 14840, 14842, 14844, -1, 14840, 14844, 14845, -1, 14840, 14845, 14846, -1, 14840, 14846, 14843, -1, 14847, 14838, 14848, -1, 14847, 14836, 14837, -1, 14847, 14837, 14838, -1, 14847, 14848, 14836, -1, 14849, 14848, 14838, -1, 14849, 14838, 14839, -1, 14849, 14839, 14850, -1, 14849, 14851, 14848, -1, 14852, 14849, 14850, -1, 14852, 14851, 14849, -1, 14853, 14854, 14855, -1, 14853, 14855, 14856, -1, 14857, 14853, 14856, -1, 14857, 14856, 14858, -1, 14859, 14852, 14850, -1, 14859, 14851, 14852, -1, 14859, 14850, 14860, -1, 14859, 14861, 14851, -1, 14862, 14863, 14854, -1, 14862, 14853, 14857, -1, 14862, 14854, 14853, -1, 14841, 14832, 14835, -1, 14864, 14857, 14858, -1, 14841, 14835, 14842, -1, 14864, 14858, 14865, -1, 14866, 14859, 14860, -1, 14866, 14861, 14859, -1, 14855, 14841, 14843, -1, 14867, 14862, 14857, -1, 14867, 14863, 14862, -1, 14867, 14857, 14864, -1, 14868, 14864, 14865, -1, 14868, 14865, 14869, -1, 14870, 14860, 14871, -1, 14870, 14861, 14866, -1, 14870, 14872, 14861, -1, 14870, 14866, 14860, -1, 14873, 14874, 14863, -1, 14873, 14863, 14867, -1, 14873, 14867, 14864, -1, 14873, 14864, 14868, -1, 14875, 14868, 14869, -1, 14875, 14869, 14876, -1, 14854, 14841, 14855, -1, 14877, 14870, 14871, -1, 14877, 14872, 14870, -1, 14877, 14878, 14872, -1, 14879, 14874, 14873, -1, 14879, 14873, 14868, -1, 14879, 14868, 14875, -1, 14880, 14875, 14876, -1, 14880, 14876, 14881, -1, 14882, 14871, 14883, -1, 14882, 14877, 14871, -1, 14882, 14878, 14877, -1, 14884, 14879, 14875, -1, 14884, 14885, 14874, -1, 14884, 14874, 14879, -1, 14884, 14875, 14880, -1, 14886, 14880, 14881, -1, 14886, 14881, 14887, -1, 14888, 14882, 14883, -1, 14888, 14883, 14889, -1, 14888, 14889, 14878, -1, 14888, 14878, 14882, -1, 14890, 14880, 14886, -1, 14890, 14885, 14884, -1, 14890, 14884, 14880, -1, 14891, 14886, 14887, -1, 14892, 14889, 14883, -1, 14892, 14883, 14893, -1, 14892, 14894, 14889, -1, 14895, 14611, 14885, -1, 14895, 14890, 14886, -1, 14895, 14885, 14890, -1, 14895, 14886, 14891, -1, 14612, 14895, 14891, -1, 14612, 14611, 14895, -1, 14612, 14887, 14615, -1, 14612, 14891, 14887, -1, 14896, 14892, 14893, -1, 14896, 14894, 14892, -1, 14613, 14615, 14897, -1, 14898, 14896, 14893, -1, 14898, 14894, 14896, -1, 14898, 14899, 14900, -1, 14898, 14893, 14899, -1, 14898, 14900, 14894, -1, 14901, 14614, 14613, -1, 14901, 14613, 14897, -1, 14901, 14897, 14902, -1, 14903, 14900, 14899, -1, 14903, 14899, 14904, -1, 14903, 14905, 14900, -1, 14906, 14901, 14902, -1, 14906, 14902, 14907, -1, 14908, 14903, 14904, -1, 14908, 14905, 14903, -1, 14909, 14910, 14614, -1, 14909, 14901, 14906, -1, 14909, 14614, 14901, -1, 14911, 14910, 14909, -1, 14911, 14906, 14907, -1, 14911, 14909, 14906, -1, 14912, 14908, 14904, -1, 14912, 14905, 14908, -1, 14912, 14904, 14913, -1, 14912, 14914, 14905, -1, 14915, 14911, 14907, -1, 14915, 14907, 14916, -1, 14917, 14912, 14913, -1, 14917, 14914, 14912, -1, 14917, 14918, 14914, -1, 14919, 14920, 14910, -1, 14919, 14911, 14915, -1, 14919, 14910, 14911, -1, 14921, 14917, 14913, -1, 14921, 14918, 14917, -1, 14921, 14913, 14922, -1, 14923, 14924, 14920, -1, 14923, 14915, 14916, -1, 14923, 14920, 14919, -1, 14923, 14919, 14915, -1, 14923, 14916, 14925, -1, 14926, 14923, 14925, -1, 14927, 14918, 14921, -1, 14927, 14921, 14922, -1, 14927, 14922, 14582, -1, 14927, 14928, 14918, -1, 14929, 14923, 14926, -1, 14929, 14924, 14923, -1, 14930, 14926, 14925, -1, 14930, 14929, 14926, -1, 14930, 14924, 14929, -1, 14930, 14925, 14931, -1, 14932, 14927, 14582, -1, 14932, 14928, 14927, -1, 14932, 14581, 14928, -1, 14932, 14582, 14581, -1, 14586, 14931, 14584, -1, 14586, 14587, 14924, -1, 14586, 14924, 14930, -1, 14586, 14930, 14931, -1, 14580, 14582, 14589, -1, 14580, 14591, 14581, -1, 14933, 14934, 14935, -1, 14933, 14936, 14937, -1, 14933, 14937, 14938, -1, 14933, 14938, 14934, -1, 14939, 14940, 14941, -1, 14939, 14942, 14936, -1, 14939, 14933, 14940, -1, 14939, 14936, 14933, -1, 14943, 14941, 14944, -1, 14943, 14939, 14941, -1, 14943, 14942, 14939, -1, 14943, 14945, 14946, -1, 14943, 14946, 14942, -1, 14947, 14944, 14948, -1, 14947, 14948, 14949, -1, 14947, 14945, 14943, -1, 14947, 14943, 14944, -1, 14947, 14950, 14945, -1, 14951, 14947, 14949, -1, 14951, 14949, 14952, -1, 14951, 14953, 14954, -1, 14951, 14954, 14950, -1, 14951, 14950, 14947, -1, 14955, 14952, 14956, -1, 14955, 14957, 14953, -1, 14955, 14953, 14951, -1, 14955, 14951, 14952, -1, 14958, 14956, 14959, -1, 14958, 14959, 14960, -1, 14958, 14957, 14955, -1, 14958, 14955, 14956, -1, 14958, 14961, 14962, -1, 14958, 14962, 14957, -1, 14963, 14961, 14958, -1, 14963, 14960, 14964, -1, 14963, 14958, 14960, -1, 14963, 14965, 14961, -1, 14966, 14964, 14967, -1, 14966, 14967, 14968, -1, 14966, 14969, 14965, -1, 14966, 14965, 14963, -1, 14966, 14963, 14964, -1, 14970, 14968, 14971, -1, 14970, 14966, 14968, -1, 14970, 14972, 14973, -1, 14970, 14969, 14966, -1, 14970, 14973, 14969, -1, 14974, 14971, 14975, -1, 14974, 14976, 14972, -1, 14974, 14970, 14971, -1, 14974, 14972, 14970, -1, 14977, 14974, 14975, -1, 14977, 14975, 14978, -1, 14977, 14978, 14979, -1, 14977, 14980, 14981, -1, 14977, 14981, 14976, -1, 14977, 14976, 14974, -1, 14982, 14980, 14977, -1, 14982, 14977, 14979, -1, 14982, 14979, 14983, -1, 14982, 14984, 14980, -1, 14985, 14982, 14983, -1, 14985, 14984, 14982, -1, 14985, 14983, 14986, -1, 14985, 14987, 14988, -1, 14985, 14988, 14984, -1, 14989, 14985, 14986, -1, 14989, 14986, 14990, -1, 14989, 14990, 14991, -1, 14989, 14987, 14985, -1, 14989, 14992, 14987, -1, 14993, 14991, 14994, -1, 14993, 14989, 14991, -1, 14993, 14995, 14996, -1, 14993, 14996, 14992, -1, 14993, 14992, 14989, -1, 14997, 14994, 14998, -1, 14997, 14993, 14994, -1, 14997, 14999, 14995, -1, 14997, 14995, 14993, -1, 15000, 14998, 15001, -1, 15000, 15001, 15002, -1, 15000, 15003, 15004, -1, 15000, 15004, 14999, -1, 15000, 14999, 14997, -1, 15000, 14997, 14998, -1, 15005, 15002, 15006, -1, 15005, 15007, 15003, -1, 15005, 15003, 15000, -1, 15005, 15000, 15002, -1, 15008, 15006, 15009, -1, 15008, 15009, 15010, -1, 15008, 15011, 15007, -1, 15008, 15005, 15006, -1, 15008, 15007, 15005, -1, 15012, 15010, 15013, -1, 15012, 15014, 15015, -1, 15012, 15015, 15011, -1, 15012, 15008, 15010, -1, 15012, 15011, 15008, -1, 15016, 15012, 15013, -1, 15016, 15013, 15017, -1, 15016, 15018, 15014, -1, 15016, 15014, 15012, -1, 15019, 12950, 11295, -1, 15019, 11295, 15020, -1, 15019, 15020, 15021, -1, 15022, 12950, 15019, -1, 15022, 15019, 15021, -1, 15022, 15023, 12950, -1, 15022, 15021, 15023, -1, 15024, 15016, 15017, -1, 15024, 15017, 11440, -1, 15025, 15018, 15016, -1, 15025, 15016, 15024, -1, 15025, 15024, 11440, -1, 15025, 11440, 12991, -1, 15025, 12991, 15018, -1, 15021, 15020, 15026, -1, 15021, 15027, 15023, -1, 15028, 15026, 15029, -1, 15028, 15030, 15031, -1, 15028, 15031, 15027, -1, 15028, 15021, 15026, -1, 15028, 15027, 15021, -1, 15032, 15029, 15033, -1, 15032, 15033, 15034, -1, 15032, 15030, 15028, -1, 15032, 15028, 15029, -1, 15032, 15035, 15030, -1, 14934, 15034, 14935, -1, 14934, 15032, 15034, -1, 14934, 15035, 15032, -1, 14934, 14938, 15035, -1, 14933, 14935, 15036, -1, 14933, 15036, 14940, -1, 15037, 15038, 15039, -1, 15037, 15040, 15038, -1, 15041, 15039, 15042, -1, 15041, 15037, 15039, -1, 15043, 15042, 15044, -1, 15043, 15041, 15042, -1, 15045, 12774, 12994, -1, 15045, 12994, 15046, -1, 15047, 15044, 15048, -1, 15047, 15043, 15044, -1, 15049, 15046, 15050, -1, 15049, 15045, 15046, -1, 15051, 15048, 15052, -1, 15051, 15047, 15048, -1, 15053, 15050, 15054, -1, 15053, 15049, 15050, -1, 15055, 15052, 15056, -1, 15055, 15051, 15052, -1, 15057, 15054, 15058, -1, 15057, 15053, 15054, -1, 15059, 15056, 15060, -1, 15059, 15055, 15056, -1, 15061, 15057, 15058, -1, 15061, 15058, 15062, -1, 15063, 15060, 15064, -1, 15065, 15061, 15062, -1, 15063, 15059, 15060, -1, 15065, 15062, 15066, -1, 15067, 15064, 15068, -1, 15069, 15066, 15070, -1, 15067, 15063, 15064, -1, 15069, 15065, 15066, -1, 15071, 15068, 15072, -1, 15073, 15069, 15070, -1, 15071, 15067, 15068, -1, 15073, 15070, 15074, -1, 15075, 15072, 15076, -1, 15077, 15074, 15078, -1, 15077, 15073, 15074, -1, 15075, 15071, 15072, -1, 15079, 15075, 15076, -1, 15079, 15076, 15080, -1, 15081, 15078, 15082, -1, 15081, 15077, 15078, -1, 15083, 15079, 15080, -1, 15084, 15082, 15085, -1, 15083, 15080, 15086, -1, 15084, 15081, 15082, -1, 15087, 15083, 15086, -1, 15088, 15085, 15089, -1, 15087, 15086, 15090, -1, 15088, 15084, 15085, -1, 15091, 15087, 15090, -1, 15092, 15089, 15093, -1, 15091, 15090, 15094, -1, 15092, 15088, 15089, -1, 15095, 15091, 15094, -1, 15096, 15093, 15097, -1, 15095, 15094, 15098, -1, 15096, 15092, 15093, -1, 15099, 15095, 15098, -1, 15100, 15097, 15101, -1, 15099, 15098, 15102, -1, 15100, 15096, 15097, -1, 15103, 15099, 15102, -1, 15103, 15102, 15104, -1, 15105, 15101, 15106, -1, 15105, 15100, 15101, -1, 15107, 15103, 15104, -1, 15107, 15104, 15108, -1, 15109, 15106, 15110, -1, 15109, 15105, 15106, -1, 15111, 15107, 15108, -1, 15111, 15108, 15112, -1, 15040, 15110, 15038, -1, 15040, 15109, 15110, -1, 12781, 15112, 12985, -1, 12781, 15111, 15112, -1, 15113, 15114, 15115, -1, 15116, 15117, 15118, -1, 15116, 15113, 15117, -1, 15119, 15118, 15120, -1, 15119, 15116, 15118, -1, 15121, 13170, 12254, -1, 15121, 12254, 15122, -1, 15123, 15120, 15124, -1, 15123, 15119, 15120, -1, 15125, 15122, 15126, -1, 15125, 15121, 15122, -1, 15127, 15124, 15128, -1, 15127, 15123, 15124, -1, 15129, 15126, 15130, -1, 15129, 15125, 15126, -1, 15131, 15128, 15132, -1, 15131, 15127, 15128, -1, 15133, 15130, 15134, -1, 15133, 15129, 15130, -1, 15135, 15132, 15136, -1, 15135, 15131, 15132, -1, 15137, 15133, 15134, -1, 15137, 15134, 15138, -1, 15139, 15136, 15140, -1, 15139, 15135, 15136, -1, 15141, 15138, 15142, -1, 15141, 15137, 15138, -1, 15143, 15140, 15144, -1, 15143, 15139, 15140, -1, 15145, 15142, 15146, -1, 15145, 15141, 15142, -1, 15147, 15144, 15148, -1, 15149, 15146, 15150, -1, 15147, 15143, 15144, -1, 15149, 15145, 15146, -1, 15151, 15148, 15152, -1, 15153, 15149, 15150, -1, 15151, 15147, 15148, -1, 15153, 15150, 15154, -1, 15155, 15152, 15156, -1, 15157, 15154, 15158, -1, 15157, 15153, 15154, -1, 15155, 15151, 15152, -1, 15159, 15155, 15156, -1, 15160, 15158, 15161, -1, 15159, 15156, 15162, -1, 15160, 15157, 15158, -1, 15163, 15159, 15162, -1, 15163, 15162, 15164, -1, 15165, 15161, 15166, -1, 15165, 15160, 15161, -1, 15167, 15163, 15164, -1, 15168, 15166, 15169, -1, 15167, 15164, 15170, -1, 15168, 15165, 15166, -1, 15171, 15167, 15170, -1, 15172, 15169, 15173, -1, 15171, 15170, 15174, -1, 15172, 15168, 15169, -1, 15175, 15171, 15174, -1, 15175, 15174, 15176, -1, 15177, 15173, 15178, -1, 15177, 15172, 15173, -1, 15179, 15175, 15176, -1, 15179, 15176, 15180, -1, 15181, 15178, 15182, -1, 15181, 15177, 15178, -1, 15183, 15179, 15180, -1, 15183, 15180, 15184, -1, 15183, 15184, 12310, -1, 15185, 15182, 15186, -1, 13140, 15183, 12310, -1, 15185, 15181, 15182, -1, 15114, 15186, 15115, -1, 15114, 15185, 15186, -1, 15113, 15115, 15117, -1, 11915, 15157, 15160, -1, 11912, 15153, 15157, -1, 11912, 15157, 11915, -1, 11919, 15160, 15165, -1, 11919, 11915, 15160, -1, 11908, 15149, 15153, -1, 11908, 15153, 11912, -1, 11924, 11919, 15165, -1, 11905, 15145, 15149, -1, 11905, 15149, 11908, -1, 15168, 11924, 15165, -1, 11926, 11924, 15168, -1, 11896, 15141, 15145, -1, 11896, 15145, 11905, -1, 15172, 11926, 15168, -1, 11931, 11926, 15172, -1, 11887, 15137, 15141, -1, 11887, 15141, 11896, -1, 15177, 11931, 15172, -1, 11933, 11931, 15177, -1, 11882, 15133, 15137, -1, 11882, 15137, 11887, -1, 15181, 11933, 15177, -1, 11936, 11933, 15181, -1, 11880, 15133, 11882, -1, 11880, 15129, 15133, -1, 15185, 11936, 15181, -1, 11856, 11936, 15185, -1, 11869, 15129, 11880, -1, 11869, 15125, 15129, -1, 15114, 11856, 15185, -1, 11857, 11856, 15114, -1, 11864, 15121, 15125, -1, 11864, 15125, 11869, -1, 15113, 11857, 15114, -1, 11863, 13170, 15121, -1, 11863, 15121, 11864, -1, 11877, 11857, 15113, -1, 15116, 11877, 15113, -1, 11884, 11877, 15116, -1, 15187, 13169, 13170, -1, 15187, 13170, 11863, -1, 15119, 11884, 15116, -1, 11885, 11884, 15119, -1, 15188, 13167, 13169, -1, 15188, 13169, 15187, -1, 15123, 11885, 15119, -1, 11890, 11885, 15123, -1, 15189, 13165, 13167, -1, 15189, 13167, 15188, -1, 15127, 11890, 15123, -1, 11893, 11890, 15127, -1, 15190, 13163, 13165, -1, 15190, 13165, 15189, -1, 15131, 11893, 15127, -1, 11895, 11893, 15131, -1, 15191, 13161, 13163, -1, 15191, 13163, 15190, -1, 15135, 11895, 15131, -1, 11903, 11895, 15135, -1, 15192, 13159, 13161, -1, 15192, 13161, 15191, -1, 15139, 11903, 15135, -1, 11906, 11903, 15139, -1, 15193, 13157, 13159, -1, 15193, 13159, 15192, -1, 15143, 11906, 15139, -1, 15194, 13155, 13157, -1, 15194, 13157, 15193, -1, 11910, 11906, 15143, -1, 15147, 11910, 15143, -1, 15195, 13153, 13155, -1, 15195, 13155, 15194, -1, 11914, 11910, 15147, -1, 15196, 13153, 15195, -1, 13151, 13153, 15196, -1, 15151, 11918, 11914, -1, 15151, 11914, 15147, -1, 15197, 13151, 15196, -1, 13149, 13151, 15197, -1, 15155, 11918, 15151, -1, 15155, 11922, 11918, -1, 15198, 13149, 15197, -1, 13147, 13149, 15198, -1, 15159, 11922, 15155, -1, 15159, 11930, 11922, -1, 15199, 13147, 15198, -1, 13145, 13147, 15199, -1, 15163, 11930, 15159, -1, 15163, 11938, 11930, -1, 15200, 13145, 15199, -1, 13143, 13145, 15200, -1, 15167, 11938, 15163, -1, 15167, 11851, 11938, -1, 15201, 13143, 15200, -1, 13141, 13143, 15201, -1, 15171, 11851, 15167, -1, 15171, 11854, 11851, -1, 15202, 13141, 15201, -1, 13138, 13141, 15202, -1, 15175, 11854, 15171, -1, 15175, 11861, 11854, -1, 15203, 13138, 15202, -1, 13136, 13138, 15203, -1, 15179, 11861, 15175, -1, 15179, 11867, 11861, -1, 15204, 13136, 15203, -1, 13137, 13136, 15204, -1, 15183, 11867, 15179, -1, 15183, 11870, 11867, -1, 15205, 13137, 15204, -1, 13140, 11873, 11870, -1, 13140, 11870, 15183, -1, 13174, 13137, 15205, -1, 15206, 13174, 15205, -1, 13139, 15207, 11873, -1, 13139, 11873, 13140, -1, 13173, 13174, 15206, -1, 15208, 13173, 15206, -1, 13142, 15209, 15207, -1, 13142, 15207, 13139, -1, 13172, 13173, 15208, -1, 15210, 13172, 15208, -1, 13144, 15211, 15209, -1, 13144, 15209, 13142, -1, 13171, 13172, 15210, -1, 15212, 13171, 15210, -1, 13146, 15211, 13144, -1, 13146, 15213, 15211, -1, 13168, 13171, 15212, -1, 15214, 13168, 15212, -1, 13148, 15215, 15213, -1, 13148, 15213, 13146, -1, 13166, 13168, 15214, -1, 15216, 13166, 15214, -1, 13150, 15217, 15215, -1, 13150, 15215, 13148, -1, 13164, 13166, 15216, -1, 15218, 13164, 15216, -1, 13152, 15219, 15217, -1, 13152, 15217, 13150, -1, 13162, 15218, 15220, -1, 13162, 13164, 15218, -1, 13154, 15221, 15219, -1, 13154, 15219, 13152, -1, 13160, 15220, 15222, -1, 13160, 13162, 15220, -1, 13156, 15223, 15221, -1, 13156, 15221, 13154, -1, 13158, 15222, 15223, -1, 13158, 13160, 15222, -1, 13158, 15223, 13156, -1, 15224, 15225, 15226, -1, 15224, 15226, 15227, -1, 15228, 15225, 15224, -1, 15228, 15229, 15225, -1, 15228, 14946, 15229, -1, 15228, 14942, 14946, -1, 15230, 15078, 15074, -1, 15230, 15227, 15078, -1, 15231, 15227, 15230, -1, 15231, 15224, 15227, -1, 15232, 15228, 15224, -1, 15232, 14942, 15228, -1, 15232, 15224, 15231, -1, 15232, 14936, 14942, -1, 15232, 14937, 14936, -1, 15233, 15074, 15070, -1, 15233, 15230, 15074, -1, 15234, 15230, 15233, -1, 15234, 15231, 15230, -1, 15235, 14937, 15232, -1, 15235, 15232, 15231, -1, 15235, 15231, 15234, -1, 15236, 15070, 15066, -1, 15236, 15233, 15070, -1, 15237, 15234, 15233, -1, 15237, 15233, 15236, -1, 15238, 14937, 15235, -1, 15238, 15235, 15234, -1, 15238, 15234, 15237, -1, 15238, 14938, 14937, -1, 15239, 15066, 15062, -1, 15239, 15236, 15066, -1, 15240, 15236, 15239, -1, 15240, 15237, 15236, -1, 15241, 15238, 15237, -1, 15241, 14938, 15238, -1, 15241, 15237, 15240, -1, 15241, 15035, 14938, -1, 15242, 15062, 15058, -1, 15242, 15239, 15062, -1, 15243, 15240, 15239, -1, 15243, 15239, 15242, -1, 15244, 15241, 15240, -1, 15244, 15035, 15241, -1, 15244, 15240, 15243, -1, 15244, 15030, 15035, -1, 15245, 15058, 15054, -1, 15245, 15242, 15058, -1, 15246, 15242, 15245, -1, 15246, 15243, 15242, -1, 15247, 15244, 15243, -1, 15247, 15030, 15244, -1, 15247, 15031, 15030, -1, 15247, 15243, 15246, -1, 15247, 15027, 15031, -1, 15248, 15054, 15050, -1, 15248, 15245, 15054, -1, 15249, 15245, 15248, -1, 15249, 15246, 15245, -1, 15250, 15247, 15246, -1, 15250, 15027, 15247, -1, 15250, 15246, 15249, -1, 15251, 15050, 15046, -1, 15251, 15046, 12996, -1, 15251, 15248, 15050, -1, 15252, 15249, 15248, -1, 15252, 12996, 12998, -1, 15252, 15248, 15251, -1, 15252, 15251, 12996, -1, 15253, 15249, 15252, -1, 15253, 12998, 12951, -1, 15253, 12951, 15023, -1, 15253, 15252, 12998, -1, 15253, 15023, 15027, -1, 15253, 15027, 15250, -1, 15253, 15250, 15249, -1, 12996, 15046, 12994, -1, 12950, 15023, 12951, -1, 15254, 12986, 12985, -1, 15254, 12985, 15112, -1, 15255, 12988, 12986, -1, 15255, 12986, 15254, -1, 15256, 12990, 12988, -1, 15256, 12991, 12990, -1, 15256, 12988, 15255, -1, 15256, 15018, 12991, -1, 15257, 15254, 15112, -1, 15257, 15112, 15108, -1, 15258, 15255, 15254, -1, 15258, 15254, 15257, -1, 15259, 15255, 15258, -1, 15259, 15014, 15018, -1, 15259, 15018, 15256, -1, 15259, 15256, 15255, -1, 15260, 15108, 15104, -1, 15260, 15257, 15108, -1, 15261, 15257, 15260, -1, 15261, 15258, 15257, -1, 15262, 15259, 15258, -1, 15262, 15258, 15261, -1, 15262, 15015, 15014, -1, 15262, 15014, 15259, -1, 15263, 15260, 15104, -1, 15263, 15104, 15102, -1, 15264, 15261, 15260, -1, 15264, 15260, 15263, -1, 15265, 15261, 15264, -1, 15265, 15011, 15015, -1, 15265, 15262, 15261, -1, 15265, 15015, 15262, -1, 15266, 15102, 15098, -1, 15266, 15263, 15102, -1, 15267, 15264, 15263, -1, 15267, 15263, 15266, -1, 15268, 15264, 15267, -1, 15268, 15265, 15264, -1, 15268, 15011, 15265, -1, 15268, 15007, 15011, -1, 15269, 15098, 15094, -1, 15269, 15266, 15098, -1, 15270, 15267, 15266, -1, 15270, 15266, 15269, -1, 15271, 15003, 15007, -1, 15271, 15267, 15270, -1, 15271, 15268, 15267, -1, 15271, 15007, 15268, -1, 15272, 15094, 15090, -1, 15272, 15269, 15094, -1, 15273, 15270, 15269, -1, 15273, 15269, 15272, -1, 15274, 15003, 15271, -1, 15274, 15271, 15270, -1, 15274, 15004, 15003, -1, 15274, 15270, 15273, -1, 15275, 15272, 15090, -1, 15275, 15090, 15086, -1, 15276, 15273, 15272, -1, 15276, 15272, 15275, -1, 15277, 15004, 15274, -1, 15277, 15273, 15276, -1, 15277, 14999, 15004, -1, 15277, 15274, 15273, -1, 15278, 15086, 15080, -1, 15278, 15275, 15086, -1, 15279, 15275, 15278, -1, 15279, 15276, 15275, -1, 15280, 15276, 15279, -1, 15280, 14999, 15277, -1, 15280, 14995, 14999, -1, 15280, 15277, 15276, -1, 15281, 15278, 15080, -1, 15281, 15080, 15076, -1, 15282, 15279, 15278, -1, 15282, 15278, 15281, -1, 15283, 14995, 15280, -1, 15283, 15280, 15279, -1, 15283, 14996, 14995, -1, 15283, 15279, 15282, -1, 15284, 15281, 15076, -1, 15284, 15076, 15072, -1, 15285, 15281, 15284, -1, 15285, 15282, 15281, -1, 15286, 14996, 15283, -1, 15286, 15283, 15282, -1, 15286, 14992, 14996, -1, 15286, 15282, 15285, -1, 15287, 15284, 15072, -1, 15287, 15072, 15068, -1, 15288, 15285, 15284, -1, 15288, 15284, 15287, -1, 15289, 15285, 15288, -1, 15289, 14987, 14992, -1, 15289, 14992, 15286, -1, 15289, 15286, 15285, -1, 15290, 15287, 15068, -1, 15290, 15068, 15064, -1, 15291, 15287, 15290, -1, 15291, 15288, 15287, -1, 15292, 14988, 14987, -1, 15292, 14984, 14988, -1, 15292, 14987, 15289, -1, 15292, 15289, 15288, -1, 15292, 15288, 15291, -1, 15293, 15064, 15060, -1, 15293, 15290, 15064, -1, 15294, 15291, 15290, -1, 15294, 15290, 15293, -1, 15295, 14984, 15292, -1, 15295, 15292, 15291, -1, 15295, 15291, 15294, -1, 15296, 15060, 15056, -1, 15296, 15293, 15060, -1, 15297, 15294, 15293, -1, 15297, 15293, 15296, -1, 15298, 14984, 15295, -1, 15298, 14980, 14984, -1, 15298, 14981, 14980, -1, 15298, 15295, 15294, -1, 15298, 15294, 15297, -1, 15299, 15056, 15052, -1, 15299, 15296, 15056, -1, 15300, 15296, 15299, -1, 15300, 15297, 15296, -1, 15301, 15297, 15300, -1, 15301, 14981, 15298, -1, 15301, 15298, 15297, -1, 15302, 15052, 15048, -1, 15302, 15299, 15052, -1, 15303, 15300, 15299, -1, 15303, 15299, 15302, -1, 15304, 15301, 15300, -1, 15304, 14981, 15301, -1, 15304, 15300, 15303, -1, 15304, 14976, 14981, -1, 15304, 14972, 14976, -1, 15305, 15048, 15044, -1, 15305, 15302, 15048, -1, 15306, 15303, 15302, -1, 15306, 15302, 15305, -1, 15307, 15304, 15303, -1, 15307, 14972, 15304, -1, 15307, 15303, 15306, -1, 15308, 15044, 15042, -1, 15308, 15305, 15044, -1, 15309, 15306, 15305, -1, 15309, 15305, 15308, -1, 15310, 14972, 15307, -1, 15310, 15307, 15306, -1, 15310, 15306, 15309, -1, 15310, 14973, 14972, -1, 15310, 14969, 14973, -1, 15311, 15308, 15042, -1, 15311, 15042, 15039, -1, 15312, 15309, 15308, -1, 15312, 15308, 15311, -1, 15313, 15310, 15309, -1, 15313, 14969, 15310, -1, 15313, 15309, 15312, -1, 15314, 15039, 15038, -1, 15314, 15311, 15039, -1, 15315, 15312, 15311, -1, 15315, 15311, 15314, -1, 15316, 14969, 15313, -1, 15316, 15313, 15312, -1, 15316, 15312, 15315, -1, 15316, 14965, 14969, -1, 15317, 15038, 15110, -1, 15317, 15314, 15038, -1, 15318, 15315, 15314, -1, 15318, 15314, 15317, -1, 15319, 15316, 15315, -1, 15319, 14965, 15316, -1, 15319, 15315, 15318, -1, 15319, 14961, 14965, -1, 15320, 15110, 15106, -1, 15320, 15317, 15110, -1, 15321, 15318, 15317, -1, 15321, 15317, 15320, -1, 15322, 15319, 15318, -1, 15322, 14961, 15319, -1, 15322, 15318, 15321, -1, 15322, 14962, 14961, -1, 15322, 14957, 14962, -1, 15323, 15106, 15101, -1, 15323, 15320, 15106, -1, 15324, 15321, 15320, -1, 15324, 15320, 15323, -1, 15325, 15322, 15321, -1, 15325, 14957, 15322, -1, 15325, 15321, 15324, -1, 15326, 15101, 15097, -1, 15326, 15323, 15101, -1, 15327, 15324, 15323, -1, 15327, 15323, 15326, -1, 15328, 14953, 14957, -1, 15328, 15324, 15327, -1, 15328, 14957, 15325, -1, 15328, 15325, 15324, -1, 15329, 15097, 15093, -1, 15329, 15326, 15097, -1, 15330, 15327, 15326, -1, 15330, 15326, 15329, -1, 15331, 14954, 14953, -1, 15331, 14953, 15328, -1, 15331, 15328, 15327, -1, 15331, 15327, 15330, -1, 15332, 15093, 15089, -1, 15332, 15329, 15093, -1, 15333, 15329, 15332, -1, 15333, 15330, 15329, -1, 15334, 15330, 15333, -1, 15334, 14950, 14954, -1, 15334, 14945, 14950, -1, 15334, 14954, 15331, -1, 15334, 15331, 15330, -1, 15335, 15089, 15085, -1, 15335, 15332, 15089, -1, 15336, 15333, 15332, -1, 15336, 15332, 15335, -1, 15337, 15334, 15333, -1, 15337, 14945, 15334, -1, 15337, 15333, 15336, -1, 15226, 15335, 15085, -1, 15226, 15085, 15082, -1, 15225, 15335, 15226, -1, 15225, 15336, 15335, -1, 15229, 14945, 15337, -1, 15229, 15337, 15336, -1, 15229, 15336, 15225, -1, 15229, 14946, 14945, -1, 15227, 15226, 15082, -1, 15227, 15082, 15078, -1, 15338, 15339, 15340, -1, 15341, 15342, 15339, -1, 15341, 15343, 15342, -1, 15341, 15339, 15338, -1, 15341, 15344, 15343, -1, 15345, 15083, 15087, -1, 15345, 15346, 15083, -1, 15347, 15338, 15346, -1, 15347, 15346, 15345, -1, 15348, 15338, 15347, -1, 15348, 15341, 15338, -1, 15348, 15344, 15341, -1, 15348, 15349, 15344, -1, 15350, 15087, 15091, -1, 15045, 12772, 12774, -1, 15350, 15345, 15087, -1, 15351, 15347, 15345, -1, 15351, 15345, 15350, -1, 15352, 15347, 15351, -1, 15353, 12256, 12779, -1, 15352, 15354, 15349, -1, 15352, 15348, 15347, -1, 15352, 15349, 15348, -1, 15355, 15091, 15095, -1, 15355, 15350, 15091, -1, 15356, 15351, 15350, -1, 15356, 15350, 15355, -1, 15357, 15358, 15354, -1, 15357, 15352, 15351, -1, 15357, 15354, 15352, -1, 15357, 15351, 15356, -1, 15359, 15095, 15099, -1, 15359, 15355, 15095, -1, 15360, 15355, 15359, -1, 15360, 15356, 15355, -1, 15361, 15362, 15358, -1, 15361, 15358, 15357, -1, 15361, 15357, 15356, -1, 15361, 15356, 15360, -1, 15363, 15099, 15103, -1, 15363, 15359, 15099, -1, 15364, 15360, 15359, -1, 15364, 15359, 15363, -1, 15365, 15366, 15362, -1, 15365, 15362, 15361, -1, 15365, 15361, 15360, -1, 15365, 15360, 15364, -1, 15367, 15103, 15107, -1, 15367, 15363, 15103, -1, 15368, 15364, 15363, -1, 15368, 15363, 15367, -1, 15369, 15364, 15368, -1, 15369, 15366, 15365, -1, 15369, 15370, 15366, -1, 15369, 15365, 15364, -1, 15371, 15107, 15111, -1, 15371, 12783, 12788, -1, 15371, 15367, 15107, -1, 15371, 15111, 12783, -1, 15372, 15367, 15371, -1, 15372, 12788, 12791, -1, 15372, 12791, 12793, -1, 15372, 15371, 12788, -1, 15372, 15368, 15367, -1, 15373, 15370, 15369, -1, 15373, 15372, 12793, -1, 15373, 15368, 15372, -1, 15373, 12793, 12797, -1, 15373, 15374, 15370, -1, 15373, 12797, 15374, -1, 15373, 15369, 15368, -1, 12783, 15111, 12781, -1, 12313, 15374, 12797, -1, 15375, 12885, 12772, -1, 15375, 12888, 12885, -1, 15375, 12772, 15045, -1, 15376, 12888, 15375, -1, 15376, 12892, 12888, -1, 15377, 15353, 12779, -1, 15377, 12779, 12892, -1, 15377, 12892, 15376, -1, 15378, 15045, 15049, -1, 15378, 15375, 15045, -1, 15379, 15376, 15375, -1, 15379, 15375, 15378, -1, 15380, 15377, 15376, -1, 15380, 15353, 15377, -1, 15380, 15376, 15379, -1, 15380, 15381, 15353, -1, 15382, 15049, 15053, -1, 15382, 15378, 15049, -1, 15383, 15379, 15378, -1, 15383, 15378, 15382, -1, 15384, 15381, 15380, -1, 15384, 15380, 15379, -1, 15384, 15379, 15383, -1, 15384, 15385, 15381, -1, 15386, 15053, 15057, -1, 15386, 15382, 15053, -1, 15387, 15383, 15382, -1, 15387, 15382, 15386, -1, 15388, 15385, 15384, -1, 15388, 15384, 15383, -1, 15388, 15383, 15387, -1, 15388, 15389, 15385, -1, 15390, 15386, 15057, -1, 15390, 15057, 15061, -1, 15391, 15386, 15390, -1, 15391, 15387, 15386, -1, 15392, 15389, 15388, -1, 15392, 15388, 15387, -1, 15392, 15387, 15391, -1, 15392, 15393, 15389, -1, 15394, 15390, 15061, -1, 15394, 15061, 15065, -1, 15395, 15391, 15390, -1, 15395, 15390, 15394, -1, 15396, 15391, 15395, -1, 15396, 15397, 15393, -1, 15396, 15392, 15391, -1, 15396, 15393, 15392, -1, 15398, 15394, 15065, -1, 15398, 15065, 15069, -1, 15399, 15394, 15398, -1, 15399, 15395, 15394, -1, 15400, 15397, 15396, -1, 15400, 15395, 15399, -1, 15400, 15396, 15395, -1, 15400, 15401, 15397, -1, 15402, 15069, 15073, -1, 15402, 15398, 15069, -1, 15403, 15399, 15398, -1, 15403, 15398, 15402, -1, 15404, 15401, 15400, -1, 15404, 15400, 15399, -1, 15404, 15405, 15401, -1, 15404, 15399, 15403, -1, 15406, 15402, 15073, -1, 15406, 15073, 15077, -1, 15407, 15402, 15406, -1, 15407, 15403, 15402, -1, 15408, 15404, 15403, -1, 15408, 15409, 15405, -1, 15408, 15403, 15407, -1, 15408, 15405, 15404, -1, 15410, 15406, 15077, -1, 15410, 15077, 15081, -1, 15411, 15407, 15406, -1, 15411, 15406, 15410, -1, 15412, 15409, 15408, -1, 15412, 15408, 15407, -1, 15412, 15407, 15411, -1, 15412, 15413, 15409, -1, 15414, 15081, 15084, -1, 15414, 15410, 15081, -1, 15415, 15410, 15414, -1, 15415, 15411, 15410, -1, 15416, 15412, 15411, -1, 15416, 15413, 15412, -1, 15416, 15411, 15415, -1, 15416, 15417, 15413, -1, 15418, 15084, 15088, -1, 15418, 15414, 15084, -1, 15419, 15415, 15414, -1, 15419, 15414, 15418, -1, 15420, 15416, 15415, -1, 15420, 15417, 15416, -1, 15420, 15415, 15419, -1, 15420, 15421, 15417, -1, 15422, 15088, 15092, -1, 15422, 15418, 15088, -1, 15423, 15419, 15418, -1, 15423, 15418, 15422, -1, 15424, 15425, 15421, -1, 15424, 15420, 15419, -1, 15424, 15421, 15420, -1, 15424, 15419, 15423, -1, 15426, 15092, 15096, -1, 15426, 15422, 15092, -1, 15427, 15422, 15426, -1, 15427, 15423, 15422, -1, 15428, 15429, 15425, -1, 15428, 15425, 15424, -1, 15428, 15424, 15423, -1, 15428, 15423, 15427, -1, 15430, 15096, 15100, -1, 15430, 15426, 15096, -1, 15431, 15426, 15430, -1, 15431, 15427, 15426, -1, 15432, 15427, 15431, -1, 15432, 15433, 15429, -1, 15432, 15429, 15428, -1, 15432, 15428, 15427, -1, 15434, 15100, 15105, -1, 15434, 15430, 15100, -1, 15435, 15431, 15430, -1, 15435, 15430, 15434, -1, 15436, 15432, 15431, -1, 15436, 15433, 15432, -1, 15436, 15431, 15435, -1, 15436, 15437, 15433, -1, 15438, 15105, 15109, -1, 15438, 15434, 15105, -1, 15439, 15434, 15438, -1, 15439, 15435, 15434, -1, 15440, 15435, 15439, -1, 15440, 15436, 15435, -1, 15440, 15437, 15436, -1, 15440, 15441, 15437, -1, 15442, 15109, 15040, -1, 15442, 15438, 15109, -1, 15443, 15439, 15438, -1, 15443, 15438, 15442, -1, 15444, 15441, 15440, -1, 15444, 15440, 15439, -1, 15444, 15445, 15441, -1, 15444, 15439, 15443, -1, 15446, 15040, 15037, -1, 15446, 15442, 15040, -1, 15447, 15443, 15442, -1, 15447, 15442, 15446, -1, 15448, 15444, 15443, -1, 15448, 15445, 15444, -1, 15448, 15443, 15447, -1, 15448, 15449, 15445, -1, 15450, 15037, 15041, -1, 15450, 15446, 15037, -1, 15451, 15447, 15446, -1, 15451, 15446, 15450, -1, 15452, 15447, 15451, -1, 15452, 15448, 15447, -1, 15452, 15449, 15448, -1, 15452, 15453, 15449, -1, 15454, 15041, 15043, -1, 15454, 15450, 15041, -1, 15455, 15451, 15450, -1, 15455, 15450, 15454, -1, 15456, 15452, 15451, -1, 15456, 15453, 15452, -1, 15456, 15451, 15455, -1, 15456, 15457, 15453, -1, 15458, 15043, 15047, -1, 15458, 15454, 15043, -1, 15459, 15455, 15454, -1, 15459, 15454, 15458, -1, 15460, 15456, 15455, -1, 15460, 15457, 15456, -1, 15460, 15455, 15459, -1, 15460, 15461, 15457, -1, 15462, 15047, 15051, -1, 15462, 15458, 15047, -1, 15463, 15458, 15462, -1, 15463, 15459, 15458, -1, 15464, 15465, 15461, -1, 15464, 15459, 15463, -1, 15464, 15460, 15459, -1, 15464, 15461, 15460, -1, 15466, 15051, 15055, -1, 15466, 15462, 15051, -1, 15467, 15463, 15462, -1, 15467, 15462, 15466, -1, 15468, 15469, 15465, -1, 15468, 15465, 15464, -1, 15468, 15464, 15463, -1, 15468, 15463, 15467, -1, 15470, 15055, 15059, -1, 15470, 15466, 15055, -1, 15471, 15467, 15466, -1, 15471, 15466, 15470, -1, 15472, 15469, 15468, -1, 15472, 15473, 15469, -1, 15472, 15467, 15471, -1, 15472, 15468, 15467, -1, 15474, 15470, 15059, -1, 15474, 15059, 15063, -1, 15475, 15470, 15474, -1, 15475, 15471, 15470, -1, 15476, 15471, 15475, -1, 15476, 15477, 15473, -1, 15476, 15473, 15472, -1, 15476, 15472, 15471, -1, 15478, 15063, 15067, -1, 15478, 15474, 15063, -1, 15479, 15475, 15474, -1, 15479, 15474, 15478, -1, 15480, 15477, 15476, -1, 15480, 15475, 15479, -1, 15480, 15481, 15477, -1, 15480, 15476, 15475, -1, 15482, 15478, 15067, -1, 15482, 15067, 15071, -1, 15483, 15479, 15478, -1, 15483, 15478, 15482, -1, 15484, 15480, 15479, -1, 15484, 15481, 15480, -1, 15484, 15479, 15483, -1, 15484, 15485, 15481, -1, 15486, 15071, 15075, -1, 15486, 15482, 15071, -1, 15487, 15483, 15482, -1, 15487, 15482, 15486, -1, 15488, 15484, 15483, -1, 15488, 15485, 15484, -1, 15488, 15483, 15487, -1, 15488, 15489, 15485, -1, 15340, 15075, 15079, -1, 15340, 15486, 15075, -1, 15339, 15486, 15340, -1, 15339, 15487, 15486, -1, 15342, 15488, 15487, -1, 15342, 15489, 15488, -1, 15342, 15487, 15339, -1, 15342, 15343, 15489, -1, 15346, 15079, 15083, -1, 15346, 15340, 15079, -1, 15338, 15340, 15346, -1, 15490, 15491, 15492, -1, 15491, 15493, 15492, -1, 15493, 15494, 15492, -1, 15494, 15495, 15492, -1, 15496, 15497, 15495, -1, 15498, 15497, 15496, -1, 15499, 15497, 15498, -1, 15495, 15497, 15492, -1, 15499, 15500, 15497, -1, 15501, 15502, 15503, -1, 15502, 15504, 15503, -1, 15504, 15505, 15503, -1, 15505, 15506, 15503, -1, 15507, 15508, 15506, -1, 15509, 15508, 15507, -1, 15510, 15508, 15509, -1, 15506, 15508, 15503, -1, 15510, 15511, 15508, -1, 15512, 15513, 15514, -1, 15513, 15515, 15514, -1, 15515, 15516, 15514, -1, 15516, 15517, 15514, -1, 15518, 12455, 15517, -1, 15519, 12455, 15518, -1, 15520, 12455, 15519, -1, 15517, 12455, 15514, -1, 15520, 12456, 12455, -1, 15521, 15503, 15522, -1, 15521, 12446, 12444, -1, 15521, 12444, 12442, -1, 15521, 12442, 15523, -1, 15521, 15523, 15524, -1, 15521, 15524, 15503, -1, 15525, 12446, 15521, -1, 15525, 12450, 12448, -1, 15525, 12448, 12446, -1, 12452, 12450, 15525, -1, 12453, 12452, 15525, -1, 12455, 15525, 15526, -1, 12455, 15526, 15527, -1, 12455, 15527, 15528, -1, 12455, 12453, 15525, -1, 15529, 12455, 15528, -1, 15530, 15531, 15508, -1, 15532, 15508, 15531, -1, 15533, 15530, 15508, -1, 15534, 15508, 15535, -1, 15534, 15535, 15536, -1, 15534, 15536, 15537, -1, 15534, 15537, 15538, -1, 15534, 15538, 15539, -1, 15534, 15533, 15508, -1, 15540, 15539, 15541, -1, 15540, 15541, 15542, -1, 15540, 15542, 15543, -1, 15540, 15543, 15492, -1, 15540, 15534, 15539, -1, 15544, 15540, 15492, -1, 15545, 15544, 15492, -1, 15497, 15546, 15492, -1, 15497, 15547, 15548, -1, 15497, 15548, 12464, -1, 15497, 12464, 12462, -1, 15497, 12462, 12459, -1, 15497, 12459, 12458, -1, 15497, 12458, 15546, -1, 15549, 15545, 15492, -1, 15546, 15549, 15492, -1, 15550, 15547, 15497, -1, 15551, 15547, 15550, -1, 15514, 15552, 15553, -1, 15514, 15553, 15554, -1, 15514, 15554, 15555, -1, 15514, 15555, 15556, -1, 15514, 15556, 15547, -1, 15557, 15547, 15551, -1, 15558, 15514, 15547, -1, 15559, 15547, 15557, -1, 15560, 15558, 15547, -1, 15561, 15547, 15559, -1, 15562, 15503, 15508, -1, 15562, 15508, 15532, -1, 15563, 15560, 15547, -1, 15564, 15503, 15562, -1, 15563, 15547, 15561, -1, 15514, 12455, 15552, -1, 15552, 12455, 15529, -1, 15565, 15503, 15564, -1, 15522, 15503, 15565, -1, 15566, 15567, 15546, -1, 15568, 15566, 15546, -1, 15569, 15568, 15546, -1, 15570, 15569, 15546, -1, 12458, 15571, 15572, -1, 12458, 15572, 15570, -1, 12458, 15570, 15546, -1, 12460, 15571, 12458, -1, 15573, 15574, 15562, -1, 15575, 15573, 15562, -1, 15576, 15575, 15562, -1, 15577, 15576, 15562, -1, 15532, 15578, 15579, -1, 15532, 15579, 15577, -1, 15532, 15577, 15562, -1, 15580, 15578, 15532, -1, 15581, 15582, 15552, -1, 15583, 15581, 15552, -1, 15584, 15583, 15552, -1, 15585, 15584, 15552, -1, 15529, 15586, 15587, -1, 15529, 15587, 15585, -1, 15529, 15585, 15552, -1, 15588, 15586, 15529, -1, 15589, 15590, 15591, -1, 15591, 15590, 15592, -1, 15592, 15593, 15594, -1, 15590, 15593, 15592, -1, 15594, 15595, 15596, -1, 15593, 15595, 15594, -1, 15596, 15597, 15598, -1, 15595, 15597, 15596, -1, 15598, 15599, 15600, -1, 15597, 15599, 15598, -1, 15599, 15601, 15600, -1, 15600, 15602, 15603, -1, 15601, 15602, 15600, -1, 15603, 15604, 15605, -1, 15602, 15604, 15603, -1, 15605, 15606, 15607, -1, 15604, 15606, 15605, -1, 15607, 15608, 15609, -1, 15606, 15608, 15607, -1, 15608, 15610, 15609, -1, 15609, 15611, 15612, -1, 15610, 15611, 15609, -1, 15612, 15613, 12688, -1, 15611, 15613, 15612, -1, 15613, 12689, 12688, -1, 15614, 15615, 15616, -1, 15617, 15591, 15615, -1, 15618, 15591, 15617, -1, 15615, 15591, 15616, -1, 15618, 15589, 15591, -1, 15619, 15620, 11248, -1, 11248, 15620, 11246, -1, 11246, 15621, 11250, -1, 15620, 15621, 11246, -1, 11250, 15622, 11242, -1, 15621, 15622, 11250, -1, 11242, 15623, 11237, -1, 15622, 15623, 11242, -1, 11237, 15624, 11232, -1, 15623, 15624, 11237, -1, 15624, 15625, 11232, -1, 11232, 15626, 11226, -1, 15625, 15626, 11232, -1, 11226, 15627, 11218, -1, 15626, 15627, 11226, -1, 11218, 15628, 11216, -1, 15627, 15628, 11218, -1, 11216, 15629, 11263, -1, 15628, 15629, 11216, -1, 11263, 15630, 11259, -1, 15629, 15630, 11263, -1, 15630, 15631, 11259, -1, 11259, 15632, 11258, -1, 15631, 15632, 11259, -1, 15633, 15634, 15635, -1, 11258, 15634, 15633, -1, 15632, 15634, 11258, -1, 15635, 15636, 15616, -1, 15634, 15636, 15635, -1, 15636, 15614, 15616, -1, 12695, 15637, 12694, -1, 15638, 11248, 15637, -1, 15639, 11248, 15638, -1, 15637, 11248, 12694, -1, 15639, 15619, 11248, -1, 15640, 15641, 15642, -1, 15643, 15644, 15645, -1, 15646, 15642, 15644, -1, 15646, 15644, 15643, -1, 15647, 15640, 15642, -1, 15647, 15642, 15646, -1, 15648, 15647, 15649, -1, 15648, 15640, 15647, -1, 11280, 15648, 15650, -1, 11280, 15650, 11279, -1, 11280, 15640, 15648, -1, 11283, 11280, 11287, -1, 11283, 15640, 11280, -1, 15651, 15652, 15653, -1, 15654, 15651, 15653, -1, 15655, 15656, 15657, -1, 15658, 15659, 15655, -1, 15658, 15657, 15660, -1, 15658, 15660, 15661, -1, 15658, 15661, 15662, -1, 15658, 15662, 15654, -1, 15658, 15653, 15640, -1, 15658, 15640, 11283, -1, 15658, 15654, 15653, -1, 15658, 15655, 15657, -1, 15663, 15659, 15658, -1, 15664, 15663, 15658, -1, 15665, 15666, 15667, -1, 15667, 15666, 15668, -1, 15668, 15669, 15670, -1, 15666, 15669, 15668, -1, 15670, 12664, 12663, -1, 15669, 12664, 15670, -1, 15671, 15672, 15673, -1, 15674, 15667, 15672, -1, 15675, 15667, 15674, -1, 15672, 15667, 15673, -1, 15675, 15665, 15667, -1, 11057, 15676, 11060, -1, 11060, 15677, 11054, -1, 15676, 15677, 11060, -1, 11054, 15678, 11053, -1, 15677, 15678, 11054, -1, 11053, 15679, 15680, -1, 15678, 15679, 11053, -1, 15679, 15681, 15680, -1, 15680, 15682, 15683, -1, 15681, 15682, 15680, -1, 15683, 15684, 15685, -1, 15682, 15684, 15683, -1, 15685, 15686, 15687, -1, 15684, 15686, 15685, -1, 15687, 15688, 15689, -1, 15686, 15688, 15687, -1, 15689, 15690, 15691, -1, 15688, 15690, 15689, -1, 15691, 15692, 15693, -1, 15690, 15692, 15691, -1, 15692, 15694, 15693, -1, 15693, 15695, 15696, -1, 15694, 15695, 15693, -1, 15696, 15697, 15698, -1, 15695, 15697, 15696, -1, 15698, 15699, 15700, -1, 15697, 15699, 15698, -1, 15700, 15701, 15673, -1, 15699, 15701, 15700, -1, 15701, 15671, 15673, -1, 12687, 15702, 12686, -1, 15703, 11057, 15702, -1, 15704, 11057, 15703, -1, 15702, 11057, 12686, -1, 15704, 15676, 11057, -1, 15705, 15706, 15707, -1, 15708, 15709, 15706, -1, 15710, 15706, 15705, -1, 15710, 15708, 15706, -1, 15711, 15705, 15712, -1, 15713, 15705, 15711, -1, 15714, 15705, 15713, -1, 15715, 15716, 15717, -1, 15715, 15717, 15710, -1, 15715, 15714, 15718, -1, 15715, 15710, 15705, -1, 15715, 15705, 15714, -1, 11107, 11114, 11111, -1, 15719, 11111, 15716, -1, 15719, 15716, 15715, -1, 15720, 11111, 15719, -1, 11102, 11107, 11111, -1, 15721, 11111, 15720, -1, 11092, 11097, 11102, -1, 11092, 11102, 11111, -1, 11122, 15721, 11120, -1, 11122, 11111, 15721, -1, 11086, 11092, 11111, -1, 11076, 11122, 11125, -1, 11076, 11078, 11086, -1, 11076, 11111, 11122, -1, 11076, 11086, 11111, -1, 15722, 15723, 11177, -1, 11177, 15723, 11181, -1, 11181, 15724, 11180, -1, 15723, 15724, 11181, -1, 11180, 15725, 11210, -1, 15724, 15725, 11180, -1, 11210, 15726, 11205, -1, 15725, 15726, 11210, -1, 11205, 15727, 11201, -1, 15726, 15727, 11205, -1, 11201, 15728, 11199, -1, 15727, 15728, 11201, -1, 11199, 15729, 11198, -1, 15728, 15729, 11199, -1, 15729, 15730, 11198, -1, 11198, 15731, 15732, -1, 15730, 15731, 11198, -1, 15732, 15733, 15734, -1, 15731, 15733, 15732, -1, 15734, 15735, 15736, -1, 15733, 15735, 15734, -1, 15736, 15737, 15738, -1, 15735, 15737, 15736, -1, 15738, 15739, 15740, -1, 15737, 15739, 15738, -1, 15740, 15741, 15742, -1, 15739, 15741, 15740, -1, 15741, 15743, 15742, -1, 15742, 15744, 15745, -1, 15743, 15744, 15742, -1, 15744, 15746, 15745, -1, 12662, 15747, 12661, -1, 15748, 11177, 15747, -1, 15749, 11177, 15748, -1, 15747, 11177, 12661, -1, 15749, 15722, 11177, -1, 15750, 15751, 15752, -1, 15752, 15751, 15753, -1, 15753, 15754, 15755, -1, 15751, 15754, 15753, -1, 15755, 15756, 15757, -1, 15754, 15756, 15755, -1, 15757, 15758, 15759, -1, 15756, 15758, 15757, -1, 15759, 15760, 15761, -1, 15758, 15760, 15759, -1, 15761, 15762, 15763, -1, 15760, 15762, 15761, -1, 15763, 15764, 12647, -1, 15762, 15764, 15763, -1, 15764, 12645, 12647, -1, 15746, 15765, 15745, -1, 15766, 15752, 15765, -1, 15767, 15752, 15766, -1, 15765, 15752, 15745, -1, 15767, 15750, 15752, -1, 15768, 15769, 15770, -1, 15771, 15772, 15768, -1, 15771, 15770, 15773, -1, 15771, 15773, 15774, -1, 15771, 15774, 15775, -1, 15771, 15775, 15776, -1, 15771, 15768, 15770, -1, 15777, 15776, 15778, -1, 15777, 15778, 15779, -1, 15777, 15771, 15776, -1, 15780, 15779, 15781, -1, 15780, 15777, 15779, -1, 15782, 15780, 15781, -1, 15783, 15782, 15784, -1, 11158, 15783, 15785, -1, 11158, 15785, 15786, -1, 11158, 15786, 15787, -1, 11158, 15787, 15788, -1, 11158, 15782, 15783, -1, 11137, 15780, 15782, -1, 11141, 15782, 11158, -1, 11141, 11137, 15782, -1, 11161, 11158, 11159, -1, 11140, 11141, 11158, -1, 11165, 11158, 11161, -1, 11170, 11140, 11158, -1, 11170, 11158, 11165, -1, 15789, 15790, 15791, -1, 15789, 15792, 15790, -1, 15793, 15794, 15795, -1, 15796, 15797, 15798, -1, 15793, 15799, 15800, -1, 15801, 15802, 15797, -1, 15793, 15800, 15803, -1, 15801, 15804, 15802, -1, 15793, 15803, 15805, -1, 15801, 15797, 15796, -1, 15793, 15805, 15806, -1, 15793, 15806, 15807, -1, 15793, 15807, 15808, -1, 15793, 15809, 15794, -1, 15793, 15808, 15809, -1, 15810, 15796, 15811, -1, 15812, 15801, 15796, -1, 15813, 15814, 15815, -1, 15813, 15791, 15814, -1, 15816, 15792, 15789, -1, 15817, 12523, 12364, -1, 15812, 15796, 15810, -1, 15817, 12526, 12523, -1, 15816, 15795, 15792, -1, 15817, 12527, 12526, -1, 15816, 15799, 15793, -1, 15816, 15793, 15795, -1, 15818, 15810, 15811, -1, 15819, 15804, 15801, -1, 15819, 15820, 15821, -1, 15822, 15817, 12364, -1, 15819, 15821, 15804, -1, 15823, 15815, 15824, -1, 15819, 15801, 15812, -1, 15825, 15791, 15813, -1, 15826, 15817, 15822, -1, 15825, 15789, 15791, -1, 15827, 15810, 15818, -1, 15828, 15826, 15822, -1, 15827, 15812, 15810, -1, 15829, 15813, 15815, -1, 15830, 15811, 15831, -1, 15829, 15815, 15823, -1, 15832, 15826, 15828, -1, 15833, 15832, 15828, -1, 15834, 15825, 15835, -1, 15834, 15835, 15836, -1, 15830, 15818, 15811, -1, 15834, 15836, 15799, -1, 15834, 15799, 15816, -1, 15834, 15789, 15825, -1, 15837, 15820, 15819, -1, 15834, 15816, 15789, -1, 15837, 15819, 15812, -1, 15838, 15824, 15839, -1, 15837, 15812, 15827, -1, 15837, 15840, 15820, -1, 15841, 15833, 15828, -1, 15842, 15827, 15818, -1, 15838, 15823, 15824, -1, 15843, 15833, 15841, -1, 15844, 15835, 15825, -1, 15844, 15845, 15835, -1, 15842, 15818, 15830, -1, 15846, 15843, 15841, -1, 15844, 15813, 15829, -1, 15844, 15825, 15813, -1, 15844, 15829, 15845, -1, 15847, 15848, 15845, -1, 15849, 15843, 15846, -1, 15847, 15829, 15823, -1, 15847, 15823, 15838, -1, 15847, 15845, 15829, -1, 15850, 15849, 15846, -1, 15851, 15838, 15839, -1, 15852, 15830, 15831, -1, 15853, 15837, 15827, -1, 15854, 15849, 15850, -1, 15855, 15856, 15848, -1, 15855, 15851, 15856, -1, 15853, 15840, 15837, -1, 15855, 15848, 15847, -1, 15853, 15827, 15842, -1, 15855, 15847, 15838, -1, 15855, 15838, 15851, -1, 15857, 15854, 15850, -1, 15858, 15859, 15856, -1, 15858, 15856, 15851, -1, 15858, 15851, 15839, -1, 15860, 15830, 15852, -1, 15861, 15857, 15850, -1, 15862, 15858, 15839, -1, 15862, 15859, 15858, -1, 15863, 15857, 15861, -1, 15864, 15839, 15865, -1, 15864, 15866, 15859, -1, 15864, 15859, 15862, -1, 15864, 15862, 15839, -1, 15867, 15863, 15861, -1, 15868, 15866, 15864, -1, 15860, 15842, 15830, -1, 15868, 15864, 15865, -1, 15869, 15863, 15867, -1, 15870, 15840, 15853, -1, 15871, 15872, 15866, -1, 15870, 15873, 15840, -1, 15871, 15866, 15868, -1, 15871, 15868, 15865, -1, 15874, 15852, 15831, -1, 15875, 15869, 15867, -1, 15876, 15877, 15878, -1, 15876, 15865, 15877, -1, 15876, 15878, 15872, -1, 15876, 15871, 15865, -1, 15879, 15869, 15875, -1, 15876, 15872, 15871, -1, 15880, 15878, 15877, -1, 15881, 15842, 15860, -1, 15882, 15880, 15877, -1, 15883, 15880, 15882, -1, 15884, 15883, 15882, -1, 15881, 15853, 15842, -1, 15885, 15883, 15884, -1, 15790, 15860, 15852, -1, 15886, 15885, 15884, -1, 15790, 15852, 15874, -1, 15887, 15885, 15886, -1, 15794, 15873, 15870, -1, 15794, 15853, 15881, -1, 15888, 15887, 15886, -1, 15794, 15870, 15853, -1, 15889, 15887, 15888, -1, 15890, 15889, 15888, -1, 15814, 15874, 15831, -1, 15890, 15891, 15889, -1, 15814, 15831, 15824, -1, 15892, 15891, 15890, -1, 15893, 15892, 15890, -1, 15792, 15881, 15860, -1, 15894, 15892, 15893, -1, 15792, 15860, 15790, -1, 15809, 15873, 15794, -1, 15809, 15808, 15895, -1, 12352, 15894, 15893, -1, 15809, 15895, 15896, -1, 15809, 15896, 15897, -1, 15809, 15897, 15898, -1, 15809, 15898, 15899, -1, 12543, 15894, 12352, -1, 15809, 15899, 15900, -1, 15809, 15900, 15901, -1, 12542, 15894, 12543, -1, 15809, 15901, 15873, -1, 12544, 15894, 12542, -1, 15791, 15790, 15874, -1, 15902, 15875, 15798, -1, 15902, 15879, 15875, -1, 15791, 15874, 15814, -1, 15902, 15903, 15879, -1, 15904, 15905, 15903, -1, 15904, 15902, 15798, -1, 15904, 15903, 15902, -1, 15906, 15904, 15798, -1, 15906, 15905, 15904, -1, 15795, 15881, 15792, -1, 15906, 15907, 15905, -1, 15795, 15794, 15881, -1, 15815, 15814, 15824, -1, 15797, 15906, 15798, -1, 15802, 15907, 15906, -1, 15802, 15804, 15907, -1, 15802, 15906, 15797, -1, 15796, 15798, 15811, -1, 15908, 12463, 12464, -1, 15908, 12464, 15548, -1, 15909, 15548, 15547, -1, 15909, 15908, 15548, -1, 15910, 15547, 15556, -1, 15910, 15909, 15547, -1, 15911, 15556, 15555, -1, 15911, 15910, 15556, -1, 15912, 15555, 15554, -1, 15912, 15911, 15555, -1, 15913, 15554, 15553, -1, 15913, 15912, 15554, -1, 15914, 15553, 15552, -1, 15914, 15913, 15553, -1, 15582, 15914, 15552, -1, 15915, 15588, 15529, -1, 15915, 15529, 15528, -1, 15916, 15528, 15527, -1, 15916, 15915, 15528, -1, 15917, 15916, 15527, -1, 15918, 15527, 15526, -1, 15918, 15917, 15527, -1, 15919, 15526, 15525, -1, 15919, 15918, 15526, -1, 15920, 15919, 15525, -1, 15921, 15525, 15521, -1, 15921, 15920, 15525, -1, 15922, 15521, 15522, -1, 15922, 15921, 15521, -1, 15923, 15522, 15565, -1, 15923, 15922, 15522, -1, 15924, 15565, 15564, -1, 15924, 15923, 15565, -1, 15925, 15564, 15562, -1, 15925, 15924, 15564, -1, 15574, 15925, 15562, -1, 15926, 15580, 15532, -1, 15926, 15532, 15531, -1, 15927, 15531, 15530, -1, 15927, 15926, 15531, -1, 15928, 15927, 15530, -1, 15929, 15530, 15533, -1, 15929, 15928, 15530, -1, 15930, 15533, 15534, -1, 15930, 15929, 15533, -1, 15931, 15930, 15534, -1, 15932, 15534, 15540, -1, 15932, 15931, 15534, -1, 15933, 15540, 15544, -1, 15933, 15932, 15540, -1, 15934, 15544, 15545, -1, 15934, 15933, 15544, -1, 15935, 15545, 15549, -1, 15935, 15934, 15545, -1, 15936, 15549, 15546, -1, 15936, 15935, 15549, -1, 15567, 15936, 15546, -1, 15490, 15492, 15937, -1, 15937, 15543, 15938, -1, 15492, 15543, 15937, -1, 15938, 15542, 15939, -1, 15543, 15542, 15938, -1, 15939, 15541, 15940, -1, 15542, 15541, 15939, -1, 15940, 15539, 15941, -1, 15541, 15539, 15940, -1, 15941, 15538, 15942, -1, 15539, 15538, 15941, -1, 15942, 15537, 15943, -1, 15538, 15537, 15942, -1, 15537, 15536, 15943, -1, 15943, 15535, 15944, -1, 15536, 15535, 15943, -1, 15944, 15508, 15511, -1, 15535, 15508, 15944, -1, 15512, 15514, 15945, -1, 15945, 15558, 15946, -1, 15514, 15558, 15945, -1, 15946, 15560, 15947, -1, 15558, 15560, 15946, -1, 15947, 15563, 15948, -1, 15560, 15563, 15947, -1, 15948, 15561, 15949, -1, 15563, 15561, 15948, -1, 15949, 15559, 15950, -1, 15561, 15559, 15949, -1, 15950, 15557, 15951, -1, 15559, 15557, 15950, -1, 15557, 15551, 15951, -1, 15951, 15550, 15952, -1, 15551, 15550, 15951, -1, 15952, 15497, 15500, -1, 15550, 15497, 15952, -1, 15501, 15503, 15953, -1, 15953, 15524, 15954, -1, 15503, 15524, 15953, -1, 15954, 15523, 12441, -1, 15524, 15523, 15954, -1, 15523, 12442, 12441, -1, 14584, 15614, 14585, -1, 14931, 15614, 14584, -1, 15615, 14907, 14902, -1, 15615, 14916, 14907, -1, 14897, 15615, 14902, -1, 14615, 15615, 14897, -1, 14887, 15615, 14615, -1, 15617, 14887, 14881, -1, 15617, 15615, 14887, -1, 14876, 15617, 14881, -1, 14869, 15617, 14876, -1, 15618, 15617, 14869, -1, 14865, 15618, 14869, -1, 14858, 15618, 14865, -1, 14856, 15618, 14858, -1, 15589, 15618, 14856, -1, 14855, 15589, 14856, -1, 15615, 15614, 14931, -1, 15615, 14931, 14925, -1, 15615, 14925, 14916, -1, 14843, 15589, 14855, -1, 14843, 15590, 15589, -1, 14846, 15593, 15590, -1, 14846, 15590, 14843, -1, 14845, 15595, 15593, -1, 14845, 15593, 14846, -1, 14844, 15597, 15595, -1, 14844, 15595, 14845, -1, 14842, 15599, 15597, -1, 14842, 15597, 14844, -1, 14835, 15601, 15599, -1, 14835, 15602, 15601, -1, 14835, 15599, 14842, -1, 14833, 15604, 15602, -1, 14833, 15602, 14835, -1, 14828, 15606, 15604, -1, 14828, 15604, 14833, -1, 14827, 15608, 15606, -1, 14827, 15606, 14828, -1, 14822, 15610, 15608, -1, 14822, 15611, 15610, -1, 14822, 15608, 14827, -1, 14821, 15613, 15611, -1, 14821, 15611, 14822, -1, 14820, 12691, 12689, -1, 14820, 12689, 15613, -1, 14820, 15613, 14821, -1, 14825, 12693, 12691, -1, 14825, 12691, 14820, -1, 14824, 12695, 12693, -1, 14824, 12693, 14825, -1, 13216, 15620, 15619, -1, 13223, 15621, 15620, -1, 13223, 15620, 13216, -1, 13277, 15622, 15621, -1, 13277, 15621, 13223, -1, 13280, 15623, 15622, -1, 13280, 15622, 13277, -1, 13279, 15624, 15623, -1, 13279, 15623, 13280, -1, 13287, 15625, 15624, -1, 13287, 15626, 15625, -1, 13287, 15624, 13279, -1, 13285, 15627, 15626, -1, 13285, 15626, 13287, -1, 13254, 15628, 15627, -1, 13254, 15627, 13285, -1, 13230, 15629, 15628, -1, 13230, 15628, 13254, -1, 13232, 15630, 15629, -1, 13232, 15629, 13230, -1, 14623, 15631, 15630, -1, 14623, 15630, 13232, -1, 14622, 15632, 15631, -1, 14622, 15631, 14623, -1, 14621, 15634, 15632, -1, 14621, 15632, 14622, -1, 14620, 15636, 15634, -1, 14620, 15634, 14621, -1, 14585, 15614, 15636, -1, 14585, 15636, 14620, -1, 14836, 12695, 14824, -1, 14848, 12695, 14836, -1, 15637, 14872, 14878, -1, 15637, 14861, 14872, -1, 14889, 15637, 14878, -1, 14894, 15637, 14889, -1, 14900, 15637, 14894, -1, 15638, 14900, 14905, -1, 15638, 15637, 14900, -1, 14914, 15638, 14905, -1, 14918, 15638, 14914, -1, 15639, 14918, 14928, -1, 15639, 15638, 14918, -1, 14581, 15639, 14928, -1, 14591, 15639, 14581, -1, 15619, 15639, 14591, -1, 13217, 15619, 14591, -1, 13216, 15619, 13217, -1, 15637, 12695, 14848, -1, 15637, 14848, 14851, -1, 15637, 14851, 14861, -1, 13458, 12662, 13468, -1, 13452, 12662, 13458, -1, 15747, 13432, 13424, -1, 15747, 13438, 13432, -1, 13420, 15747, 13424, -1, 13415, 15747, 13420, -1, 13410, 15747, 13415, -1, 15748, 13410, 13405, -1, 15748, 15747, 13410, -1, 13396, 15748, 13405, -1, 13394, 15748, 13396, -1, 15749, 15748, 13394, -1, 13390, 15749, 13394, -1, 13386, 15749, 13390, -1, 13381, 15749, 13386, -1, 15722, 15749, 13381, -1, 13375, 15722, 13381, -1, 15747, 12662, 13452, -1, 15747, 13452, 13441, -1, 15747, 13441, 13438, -1, 13374, 15722, 13375, -1, 13374, 15723, 15722, -1, 13373, 15724, 15723, -1, 13373, 15723, 13374, -1, 13349, 15725, 15724, -1, 13349, 15724, 13373, -1, 13339, 15726, 15725, -1, 13339, 15725, 13349, -1, 13340, 15727, 15726, -1, 13340, 15726, 13339, -1, 13367, 15728, 15727, -1, 13367, 15729, 15728, -1, 13367, 15727, 13340, -1, 13257, 15730, 15729, -1, 13257, 15729, 13367, -1, 13260, 15731, 15730, -1, 13260, 15730, 13257, -1, 13259, 15733, 15731, -1, 13259, 15731, 13260, -1, 13358, 15735, 15733, -1, 13358, 15737, 15735, -1, 13358, 15733, 13259, -1, 13357, 15739, 15737, -1, 13357, 15737, 13358, -1, 13363, 15741, 15739, -1, 13363, 15739, 13357, -1, 13362, 15743, 15741, -1, 13362, 15744, 15743, -1, 13362, 15741, 13363, -1, 13361, 15746, 15744, -1, 13361, 15744, 13362, -1, 13477, 15751, 15750, -1, 13477, 15750, 13470, -1, 13476, 15754, 15751, -1, 13476, 15751, 13477, -1, 13475, 15756, 15754, -1, 13475, 15754, 13476, -1, 13474, 15758, 15756, -1, 13474, 15756, 13475, -1, 13482, 15760, 15758, -1, 13482, 15758, 13474, -1, 13265, 15762, 15760, -1, 13265, 15760, 13482, -1, 13264, 15764, 15762, -1, 13264, 15762, 13265, -1, 13263, 12646, 12645, -1, 13263, 12645, 15764, -1, 13263, 15764, 13264, -1, 13485, 12649, 12646, -1, 13485, 12646, 13263, -1, 13484, 12651, 12649, -1, 13484, 12649, 13485, -1, 13483, 12653, 12651, -1, 13483, 12651, 13484, -1, 13459, 12655, 12653, -1, 13459, 12653, 13483, -1, 13460, 12657, 12655, -1, 13460, 12655, 13459, -1, 13472, 12659, 12657, -1, 13472, 12660, 12659, -1, 13472, 12657, 13460, -1, 13468, 12662, 12660, -1, 13468, 12660, 13472, -1, 13365, 15746, 13361, -1, 13370, 15746, 13365, -1, 15765, 13388, 13401, -1, 15765, 13379, 13388, -1, 13407, 15765, 13401, -1, 13417, 15765, 13407, -1, 13422, 15765, 13417, -1, 15766, 13422, 13430, -1, 15766, 15765, 13422, -1, 13434, 15766, 13430, -1, 13443, 15766, 13434, -1, 15767, 13443, 13448, -1, 15767, 15766, 13443, -1, 13455, 15767, 13448, -1, 13463, 15767, 13455, -1, 15750, 15767, 13463, -1, 13470, 15750, 13463, -1, 15765, 15746, 13370, -1, 15765, 13370, 13379, -1, 14722, 15671, 14702, -1, 14715, 15671, 14722, -1, 15672, 14690, 14683, -1, 15672, 14693, 14690, -1, 14679, 15672, 14683, -1, 14669, 15672, 14679, -1, 14663, 15672, 14669, -1, 15674, 14663, 14658, -1, 15674, 15672, 14663, -1, 14652, 15674, 14658, -1, 14642, 15674, 14652, -1, 15675, 15674, 14642, -1, 14640, 15675, 14642, -1, 14635, 15675, 14640, -1, 14631, 15675, 14635, -1, 15665, 15675, 14631, -1, 14630, 15665, 14631, -1, 15672, 15671, 14715, -1, 15672, 14715, 14708, -1, 15672, 14708, 14693, -1, 14619, 15665, 14630, -1, 14619, 15666, 15665, -1, 14618, 15669, 15666, -1, 14618, 15666, 14619, -1, 14616, 12664, 15669, -1, 14616, 15669, 14618, -1, 14606, 12666, 12664, -1, 14606, 12664, 14616, -1, 13275, 12668, 12666, -1, 13275, 12666, 14606, -1, 13270, 12670, 12668, -1, 13270, 12668, 13275, -1, 13251, 12672, 12670, -1, 13251, 12670, 13270, -1, 13250, 12674, 12672, -1, 13250, 12676, 12674, -1, 13250, 12672, 13251, -1, 13249, 12676, 13250, -1, 13244, 12678, 12676, -1, 13244, 12676, 13249, -1, 13246, 12680, 12678, -1, 13246, 12678, 13244, -1, 13242, 12682, 12680, -1, 13242, 12683, 12682, -1, 13242, 12680, 13246, -1, 13241, 12685, 12683, -1, 13241, 12683, 13242, -1, 13273, 12687, 12685, -1, 13273, 12685, 13241, -1, 14730, 15677, 15676, -1, 14730, 15676, 14725, -1, 14728, 15678, 15677, -1, 14728, 15677, 14730, -1, 14727, 15679, 15678, -1, 14727, 15678, 14728, -1, 14736, 15681, 15679, -1, 14736, 15679, 14727, -1, 14735, 15682, 15681, -1, 14735, 15681, 14736, -1, 14742, 15684, 15682, -1, 14742, 15682, 14735, -1, 14741, 15686, 15684, -1, 14741, 15684, 14742, -1, 14740, 15688, 15686, -1, 14740, 15686, 14741, -1, 14729, 15690, 15688, -1, 14729, 15692, 15690, -1, 14729, 15688, 14740, -1, 14710, 15694, 15692, -1, 14710, 15692, 14729, -1, 14711, 15695, 15694, -1, 14711, 15694, 14710, -1, 14733, 15697, 15695, -1, 14733, 15695, 14711, -1, 14732, 15699, 15697, -1, 14732, 15697, 14733, -1, 14704, 15701, 15699, -1, 14704, 15699, 14732, -1, 14702, 15671, 15701, -1, 14702, 15701, 14704, -1, 13274, 12687, 13273, -1, 14598, 12687, 13274, -1, 15702, 14649, 14654, -1, 15702, 14638, 14649, -1, 14665, 15702, 14654, -1, 14672, 15702, 14665, -1, 14681, 15702, 14672, -1, 15703, 14681, 14686, -1, 15703, 15702, 14681, -1, 14696, 15703, 14686, -1, 14706, 15703, 14696, -1, 15704, 14706, 14717, -1, 15704, 15703, 14706, -1, 14607, 15704, 14717, -1, 14605, 15704, 14607, -1, 15676, 15704, 14605, -1, 14725, 15676, 14605, -1, 15702, 12687, 14598, -1, 15702, 14598, 14628, -1, 15702, 14628, 14638, -1, 13314, 15501, 13317, -1, 15502, 13314, 13309, -1, 15502, 15501, 13314, -1, 13302, 15502, 13309, -1, 13301, 15502, 13302, -1, 15504, 13301, 13295, -1, 15504, 15502, 13301, -1, 13282, 15504, 13295, -1, 13220, 15504, 13282, -1, 13222, 15504, 13220, -1, 15505, 13222, 14589, -1, 15505, 15504, 13222, -1, 14582, 15505, 14589, -1, 14922, 15505, 14582, -1, 14913, 15505, 14922, -1, 14904, 15505, 14913, -1, 15506, 14904, 14899, -1, 15506, 15505, 14904, -1, 14893, 15506, 14899, -1, 14883, 15506, 14893, -1, 14871, 15506, 14883, -1, 15507, 14871, 14860, -1, 15507, 15506, 14871, -1, 14850, 15507, 14860, -1, 14839, 15507, 14850, -1, 14830, 15507, 14839, -1, 14817, 15507, 14830, -1, 14811, 15507, 14817, -1, 15509, 14807, 14801, -1, 15509, 14811, 14807, -1, 15509, 15507, 14811, -1, 14796, 15509, 14801, -1, 14794, 15509, 14796, -1, 15510, 15509, 14794, -1, 14792, 15510, 14794, -1, 14789, 15510, 14792, -1, 15511, 15510, 14789, -1, 14790, 15511, 14789, -1, 15953, 13317, 15501, -1, 15953, 13319, 13317, -1, 15954, 13320, 13319, -1, 15954, 13319, 15953, -1, 12441, 13322, 13320, -1, 12441, 13320, 15954, -1, 12443, 13322, 12441, -1, 12445, 13323, 13322, -1, 12445, 13322, 12443, -1, 12447, 13325, 13323, -1, 12447, 13323, 12445, -1, 12449, 13326, 13325, -1, 12449, 13325, 12447, -1, 12451, 13283, 13326, -1, 12451, 13326, 12449, -1, 12454, 13284, 13283, -1, 12454, 13286, 13284, -1, 12454, 13283, 12451, -1, 12456, 13288, 13286, -1, 12456, 13286, 12454, -1, 15937, 14778, 14777, -1, 15937, 14777, 15490, -1, 15938, 14751, 14778, -1, 15938, 14778, 15937, -1, 15939, 14752, 14751, -1, 15939, 14751, 15938, -1, 15940, 14781, 14752, -1, 15940, 14752, 15939, -1, 15941, 14782, 14781, -1, 15941, 14781, 15940, -1, 15942, 14764, 14782, -1, 15942, 14782, 15941, -1, 15943, 14765, 14764, -1, 15943, 14764, 15942, -1, 15944, 14786, 14765, -1, 15944, 14787, 14786, -1, 15944, 14765, 15943, -1, 15511, 14790, 14787, -1, 15511, 14787, 15944, -1, 13512, 15512, 13514, -1, 13509, 15512, 13512, -1, 15513, 15512, 13509, -1, 13502, 15513, 13509, -1, 13495, 15513, 13502, -1, 15515, 13495, 13489, -1, 15515, 15513, 13495, -1, 13480, 15515, 13489, -1, 13478, 15515, 13480, -1, 13466, 15515, 13478, -1, 15516, 13466, 13456, -1, 15516, 15515, 13466, -1, 13449, 15516, 13456, -1, 13444, 15516, 13449, -1, 13435, 15516, 13444, -1, 15517, 13435, 13426, -1, 15517, 15516, 13435, -1, 13412, 15517, 13426, -1, 13402, 15517, 13412, -1, 13392, 15517, 13402, -1, 15518, 13392, 13384, -1, 15518, 15517, 13392, -1, 13378, 15518, 13384, -1, 13371, 15518, 13378, -1, 13366, 15518, 13371, -1, 13354, 15518, 13366, -1, 15519, 13343, 13337, -1, 15519, 13345, 13343, -1, 15519, 13354, 13345, -1, 15519, 15518, 13354, -1, 13335, 15519, 13337, -1, 13333, 15519, 13335, -1, 15520, 15519, 13333, -1, 13332, 15520, 13333, -1, 13330, 15520, 13332, -1, 13329, 15520, 13330, -1, 12456, 15520, 13329, -1, 13288, 12456, 13329, -1, 14773, 15490, 14777, -1, 15491, 14773, 14767, -1, 15491, 15490, 14773, -1, 14758, 15491, 14767, -1, 14754, 15491, 14758, -1, 15493, 15491, 14754, -1, 14738, 15493, 14754, -1, 14603, 15493, 14738, -1, 15494, 15493, 14603, -1, 14602, 15494, 14603, -1, 14705, 15494, 14602, -1, 14695, 15494, 14705, -1, 14685, 15494, 14695, -1, 15495, 14685, 14671, -1, 15495, 15494, 14685, -1, 14660, 15495, 14671, -1, 14648, 15495, 14660, -1, 14637, 15495, 14648, -1, 15496, 15495, 14637, -1, 14627, 15496, 14637, -1, 14624, 15496, 14627, -1, 14599, 15496, 14624, -1, 13269, 15496, 14599, -1, 13235, 15496, 13269, -1, 13227, 15496, 13235, -1, 15498, 13214, 13213, -1, 15498, 13225, 13214, -1, 15498, 13227, 13225, -1, 15498, 15496, 13227, -1, 13210, 15498, 13213, -1, 13208, 15498, 13210, -1, 15499, 15498, 13208, -1, 13528, 15499, 13208, -1, 15500, 15499, 13528, -1, 13524, 15500, 13528, -1, 15945, 13514, 15512, -1, 15945, 13504, 13514, -1, 15946, 13505, 13504, -1, 15946, 13504, 15945, -1, 15947, 13516, 13505, -1, 15947, 13505, 15946, -1, 15948, 13519, 13516, -1, 15948, 13516, 15947, -1, 15949, 13518, 13519, -1, 15949, 13519, 15948, -1, 15950, 13521, 13518, -1, 15950, 13518, 15949, -1, 15951, 13522, 13521, -1, 15951, 13521, 15950, -1, 15952, 13525, 13522, -1, 15952, 13526, 13525, -1, 15952, 13522, 15951, -1, 15500, 13524, 13526, -1, 15500, 13526, 15952, -1, 15873, 15901, 15567, -1, 15840, 15873, 15567, -1, 15566, 15820, 15840, -1, 15566, 15821, 15820, -1, 15566, 15840, 15567, -1, 15804, 15821, 15566, -1, 15907, 15804, 15566, -1, 15568, 15905, 15907, -1, 15568, 15903, 15905, -1, 15568, 15907, 15566, -1, 15879, 15903, 15568, -1, 15869, 15879, 15568, -1, 15569, 15863, 15869, -1, 15569, 15857, 15863, -1, 15569, 15869, 15568, -1, 15854, 15857, 15569, -1, 15849, 15854, 15569, -1, 15570, 15843, 15849, -1, 15570, 15833, 15843, -1, 15570, 15832, 15833, -1, 15570, 15849, 15569, -1, 15826, 15832, 15570, -1, 15817, 15826, 15570, -1, 15572, 12520, 12527, -1, 15572, 12517, 12520, -1, 15572, 12527, 15817, -1, 15572, 15817, 15570, -1, 12514, 12517, 15572, -1, 15571, 12514, 15572, -1, 15571, 12510, 12514, -1, 15571, 12506, 12510, -1, 12503, 12506, 15571, -1, 12498, 12503, 15571, -1, 12460, 12498, 15571, -1, 12460, 12483, 12498, -1, 12457, 12483, 12460, -1, 12457, 12484, 12483, -1, 12461, 12485, 12484, -1, 12461, 12484, 12457, -1, 12463, 12486, 12485, -1, 12463, 12485, 12461, -1, 15908, 12486, 12463, -1, 15909, 12487, 12486, -1, 15909, 12486, 15908, -1, 15910, 12488, 12487, -1, 15910, 12489, 12488, -1, 15910, 12487, 15909, -1, 15911, 12490, 12489, -1, 15911, 12489, 15910, -1, 15912, 12491, 12490, -1, 15912, 12490, 15911, -1, 15913, 12492, 12491, -1, 15913, 12491, 15912, -1, 15914, 12493, 12492, -1, 15914, 12494, 12493, -1, 15914, 12492, 15913, -1, 15582, 12495, 12494, -1, 15582, 12494, 15914, -1, 15926, 15803, 15800, -1, 15926, 15800, 15580, -1, 15927, 15803, 15926, -1, 15928, 15805, 15803, -1, 15928, 15803, 15927, -1, 15929, 15806, 15805, -1, 15929, 15805, 15928, -1, 15930, 15807, 15806, -1, 15930, 15806, 15929, -1, 15931, 15808, 15807, -1, 15931, 15807, 15930, -1, 15932, 15895, 15808, -1, 15932, 15808, 15931, -1, 15933, 15896, 15895, -1, 15933, 15895, 15932, -1, 15934, 15897, 15896, -1, 15934, 15896, 15933, -1, 15935, 15898, 15897, -1, 15935, 15897, 15934, -1, 15936, 15899, 15898, -1, 15936, 15900, 15899, -1, 15936, 15898, 15935, -1, 15567, 15901, 15900, -1, 15567, 15900, 15936, -1, 15588, 12602, 15586, -1, 15588, 12587, 12602, -1, 15588, 12588, 12587, -1, 12474, 12495, 15582, -1, 12475, 12474, 15582, -1, 15581, 12644, 12475, -1, 15581, 12640, 12644, -1, 15581, 12475, 15582, -1, 12637, 12640, 15581, -1, 12634, 12637, 15581, -1, 15583, 12631, 12634, -1, 15583, 12627, 12631, -1, 15583, 12634, 15581, -1, 12540, 12627, 15583, -1, 12539, 12540, 15583, -1, 15584, 12538, 12539, -1, 15584, 12537, 12538, -1, 15584, 12539, 15583, -1, 12536, 12537, 15584, -1, 12535, 12536, 15584, -1, 12534, 12535, 15584, -1, 12533, 12534, 15584, -1, 15585, 12532, 12533, -1, 15585, 12531, 12532, -1, 15585, 12530, 12531, -1, 15585, 12529, 12530, -1, 15585, 12533, 15584, -1, 12528, 12529, 15585, -1, 12524, 12528, 15585, -1, 15587, 12524, 15585, -1, 15587, 12525, 12524, -1, 15587, 12621, 12525, -1, 12618, 12621, 15587, -1, 12615, 12618, 15587, -1, 15586, 12615, 15587, -1, 15586, 12612, 12615, -1, 15586, 12610, 12612, -1, 12607, 12610, 15586, -1, 12602, 12607, 15586, -1, 12574, 12579, 15574, -1, 15573, 12564, 12574, -1, 15573, 12565, 12564, -1, 15573, 12574, 15574, -1, 12559, 12565, 15573, -1, 12556, 12559, 15573, -1, 15575, 12553, 12556, -1, 15575, 12549, 12553, -1, 15575, 12556, 15573, -1, 12547, 12549, 15575, -1, 12545, 12547, 15575, -1, 12544, 12545, 15575, -1, 15576, 15894, 12544, -1, 15576, 15892, 15894, -1, 15576, 12544, 15575, -1, 15891, 15892, 15576, -1, 15889, 15891, 15576, -1, 15887, 15889, 15576, -1, 15577, 15885, 15887, -1, 15577, 15883, 15885, -1, 15577, 15887, 15576, -1, 15880, 15883, 15577, -1, 15878, 15880, 15577, -1, 15579, 15872, 15878, -1, 15579, 15866, 15872, -1, 15579, 15878, 15577, -1, 15859, 15866, 15579, -1, 15856, 15859, 15579, -1, 15578, 15856, 15579, -1, 15578, 15848, 15856, -1, 15578, 15845, 15848, -1, 15578, 15835, 15845, -1, 15836, 15835, 15578, -1, 15799, 15836, 15578, -1, 15580, 15799, 15578, -1, 15580, 15800, 15799, -1, 15915, 12588, 15588, -1, 15915, 12589, 12588, -1, 15916, 12589, 15915, -1, 15917, 12590, 12589, -1, 15917, 12589, 15916, -1, 15918, 12591, 12590, -1, 15918, 12590, 15917, -1, 15919, 12592, 12591, -1, 15919, 12591, 15918, -1, 15920, 12593, 12592, -1, 15920, 12592, 15919, -1, 15921, 12594, 12593, -1, 15921, 12593, 15920, -1, 15922, 12595, 12594, -1, 15922, 12594, 15921, -1, 15923, 12596, 12595, -1, 15923, 12595, 15922, -1, 15924, 12597, 12596, -1, 15924, 12596, 15923, -1, 15925, 12598, 12597, -1, 15925, 12599, 12598, -1, 15925, 12597, 15924, -1, 15574, 12579, 12599, -1, 15574, 12599, 15925, -1, 15955, 15956, 15957, -1, 15955, 14494, 14495, -1, 15955, 14495, 15958, -1, 15955, 15958, 15956, -1, 15959, 15957, 15861, -1, 15960, 15957, 15959, -1, 15960, 14497, 14494, -1, 15960, 14494, 15955, -1, 15960, 15955, 15957, -1, 15961, 15850, 15846, -1, 15961, 15861, 15850, -1, 15961, 15959, 15861, -1, 15962, 12342, 12352, -1, 15963, 14502, 14497, -1, 15962, 15893, 15890, -1, 15963, 14497, 15960, -1, 15962, 12352, 15893, -1, 15963, 15960, 15959, -1, 15963, 15959, 15961, -1, 15964, 15961, 15846, -1, 15965, 12345, 12342, -1, 15965, 12360, 12345, -1, 15965, 14458, 12360, -1, 15966, 15961, 15964, -1, 15965, 12342, 15962, -1, 15966, 14525, 14502, -1, 15966, 14502, 15963, -1, 15967, 15890, 15888, -1, 15966, 15963, 15961, -1, 15967, 15962, 15890, -1, 15968, 15965, 15962, -1, 15969, 15846, 15841, -1, 15968, 14461, 14458, -1, 15969, 15964, 15846, -1, 15968, 15962, 15967, -1, 15968, 14458, 15965, -1, 15970, 15964, 15969, -1, 15971, 15888, 15886, -1, 15970, 14536, 14525, -1, 15970, 14525, 15966, -1, 15971, 15967, 15888, -1, 15970, 15966, 15964, -1, 15972, 14411, 14461, -1, 15973, 15841, 15828, -1, 15972, 15968, 15967, -1, 15973, 15969, 15841, -1, 15972, 14461, 15968, -1, 15972, 15967, 15971, -1, 15974, 14536, 15970, -1, 15975, 15886, 15884, -1, 15974, 15969, 15973, -1, 15975, 15971, 15886, -1, 15974, 14504, 14536, -1, 15974, 15970, 15969, -1, 15976, 15972, 15971, -1, 15977, 15822, 12364, -1, 15976, 15971, 15975, -1, 15977, 15828, 15822, -1, 15976, 14421, 14411, -1, 15977, 12364, 12366, -1, 15976, 14411, 15972, -1, 15978, 15884, 15882, -1, 15977, 15973, 15828, -1, 15978, 15975, 15884, -1, 15979, 15974, 15973, -1, 15979, 14504, 15974, -1, 15979, 15977, 12366, -1, 15979, 12366, 12358, -1, 15980, 14433, 14421, -1, 15979, 12358, 12357, -1, 15979, 15973, 15977, -1, 15980, 15976, 15975, -1, 15979, 14508, 14504, -1, 15980, 14421, 15976, -1, 15979, 12357, 14508, -1, 15980, 15975, 15978, -1, 15981, 15882, 15877, -1, 15981, 15978, 15882, -1, 15982, 15980, 15978, -1, 15982, 14469, 14433, -1, 15982, 15978, 15981, -1, 15982, 14433, 15980, -1, 15983, 15877, 15865, -1, 15983, 15981, 15877, -1, 15984, 14471, 14469, -1, 15984, 14469, 15982, -1, 15984, 15981, 15983, -1, 15984, 15982, 15981, -1, 15985, 15865, 15839, -1, 15985, 15983, 15865, -1, 15986, 14471, 15984, -1, 15986, 14477, 14471, -1, 15986, 15983, 15985, -1, 15986, 15984, 15983, -1, 15987, 15839, 15824, -1, 15987, 15985, 15839, -1, 15988, 15986, 15985, -1, 15988, 14480, 14477, -1, 15988, 14477, 15986, -1, 15988, 15985, 15987, -1, 15989, 15824, 15831, -1, 15989, 15987, 15824, -1, 15990, 15987, 15989, -1, 15990, 14478, 14480, -1, 15990, 15988, 15987, -1, 15990, 14480, 15988, -1, 15991, 15831, 15811, -1, 15991, 15989, 15831, -1, 15992, 15989, 15991, -1, 15992, 15990, 15989, -1, 15992, 14487, 14478, -1, 15992, 14478, 15990, -1, 15993, 15991, 15811, -1, 15993, 15811, 15798, -1, 15994, 14490, 14487, -1, 15994, 15991, 15993, -1, 15994, 14487, 15992, -1, 15994, 15992, 15991, -1, 15995, 15993, 15798, -1, 15995, 15798, 15875, -1, 15996, 14492, 14490, -1, 15996, 15993, 15995, -1, 15996, 14490, 15994, -1, 15996, 15994, 15993, -1, 15956, 15875, 15867, -1, 15956, 15995, 15875, -1, 15958, 15995, 15956, -1, 15958, 14495, 14492, -1, 15958, 14492, 15996, -1, 15958, 15996, 15995, -1, 15957, 15867, 15861, -1, 15957, 15956, 15867, -1, 15441, 15445, 15186, -1, 15182, 15441, 15186, -1, 15437, 15441, 15182, -1, 15178, 15437, 15182, -1, 15374, 12313, 12310, -1, 15374, 12310, 15184, -1, 15433, 15437, 15178, -1, 15173, 15433, 15178, -1, 15370, 15184, 15180, -1, 15370, 15374, 15184, -1, 15429, 15433, 15173, -1, 15169, 15429, 15173, -1, 15366, 15180, 15176, -1, 15425, 15429, 15169, -1, 15366, 15370, 15180, -1, 15166, 15425, 15169, -1, 15421, 15425, 15166, -1, 15362, 15176, 15174, -1, 15362, 15366, 15176, -1, 15161, 15421, 15166, -1, 15417, 15421, 15161, -1, 15158, 15417, 15161, -1, 15358, 15174, 15170, -1, 15358, 15362, 15174, -1, 15413, 15417, 15158, -1, 15154, 15413, 15158, -1, 15354, 15358, 15170, -1, 15409, 15413, 15154, -1, 15354, 15170, 15164, -1, 15150, 15409, 15154, -1, 15405, 15409, 15150, -1, 15349, 15354, 15164, -1, 15349, 15164, 15162, -1, 15146, 15405, 15150, -1, 15401, 15405, 15146, -1, 15344, 15349, 15162, -1, 15344, 15162, 15156, -1, 15142, 15401, 15146, -1, 15397, 15401, 15142, -1, 15343, 15344, 15156, -1, 15343, 15156, 15152, -1, 15138, 15397, 15142, -1, 15393, 15397, 15138, -1, 15489, 15343, 15152, -1, 15134, 15393, 15138, -1, 15489, 15152, 15148, -1, 15389, 15393, 15134, -1, 15485, 15489, 15148, -1, 15130, 15389, 15134, -1, 15485, 15148, 15144, -1, 15385, 15389, 15130, -1, 15481, 15144, 15140, -1, 15126, 15385, 15130, -1, 15481, 15485, 15144, -1, 15381, 15385, 15126, -1, 15122, 15381, 15126, -1, 15477, 15140, 15136, -1, 15477, 15481, 15140, -1, 15353, 15381, 15122, -1, 12254, 15353, 15122, -1, 15473, 15136, 15132, -1, 15473, 15477, 15136, -1, 12256, 15353, 12254, -1, 15469, 15132, 15128, -1, 15469, 15473, 15132, -1, 15465, 15128, 15124, -1, 15465, 15469, 15128, -1, 15461, 15124, 15120, -1, 15461, 15465, 15124, -1, 15457, 15120, 15118, -1, 15457, 15461, 15120, -1, 15453, 15118, 15117, -1, 15453, 15457, 15118, -1, 15449, 15117, 15115, -1, 15449, 15453, 15117, -1, 15445, 15115, 15186, -1, 15445, 15449, 15115, -1, 15997, 15998, 15999, -1, 16000, 15998, 15997, -1, 16001, 15998, 16000, -1, 15998, 16002, 15999, -1, 16002, 16003, 15999, -1, 16004, 11021, 16005, -1, 11025, 16006, 11026, -1, 11023, 16006, 11025, -1, 11021, 16006, 11023, -1, 16004, 16006, 11021, -1, 11021, 15999, 16005, -1, 16005, 15999, 16003, -1, 16007, 12200, 16008, -1, 16009, 12200, 16007, -1, 12201, 12200, 16009, -1, 12200, 16010, 16008, -1, 16010, 16011, 16008, -1, 16012, 16013, 16014, -1, 16015, 12231, 12230, -1, 16016, 12231, 16015, -1, 16013, 12231, 16016, -1, 16012, 12231, 16013, -1, 16013, 16008, 16014, -1, 16014, 16008, 16011, -1, 16017, 16018, 16019, -1, 16020, 16018, 16017, -1, 16021, 16018, 16020, -1, 16018, 16022, 16019, -1, 16022, 16023, 16019, -1, 16024, 11046, 16025, -1, 11049, 16026, 11050, -1, 11047, 16026, 11049, -1, 11046, 16026, 11047, -1, 16024, 16026, 11046, -1, 11046, 16019, 16023, -1, 11046, 16023, 16025, -1, 10999, 10997, 11038, -1, 10995, 11042, 11040, -1, 10995, 11040, 10997, -1, 11001, 11036, 11034, -1, 11001, 10999, 11036, -1, 10992, 11044, 11042, -1, 10992, 11042, 10995, -1, 11004, 11034, 11032, -1, 11004, 11001, 11034, -1, 11004, 11032, 16027, -1, 10991, 11046, 11044, -1, 10991, 11044, 10992, -1, 16028, 11046, 10991, -1, 16029, 11046, 16028, -1, 16030, 16031, 16032, -1, 16019, 11046, 16029, -1, 16033, 16034, 16031, -1, 16033, 16031, 16030, -1, 11006, 16027, 16035, -1, 16013, 16032, 16008, -1, 16013, 16030, 16032, -1, 11006, 11004, 16027, -1, 11008, 11006, 16035, -1, 11008, 16035, 16036, -1, 16037, 16038, 16034, -1, 16037, 16034, 16033, -1, 11010, 16036, 16039, -1, 16040, 11027, 16038, -1, 16040, 16038, 16037, -1, 11010, 11008, 16036, -1, 11012, 16039, 16041, -1, 16042, 11030, 11027, -1, 11012, 11010, 16039, -1, 16042, 11027, 16040, -1, 11014, 11012, 16041, -1, 11014, 16041, 16043, -1, 16044, 11032, 11030, -1, 11016, 11014, 16043, -1, 11016, 16043, 16045, -1, 16044, 11030, 16042, -1, 11018, 16045, 15999, -1, 11018, 11016, 16045, -1, 16027, 11032, 16044, -1, 11019, 11018, 15999, -1, 11020, 11019, 15999, -1, 11021, 11020, 15999, -1, 10997, 11040, 11038, -1, 10999, 11038, 11036, -1, 12245, 16046, 12246, -1, 12245, 16047, 16046, -1, 16047, 16048, 16046, -1, 16047, 16049, 16048, -1, 16049, 16050, 16048, -1, 16050, 16051, 16052, -1, 16049, 16051, 16050, -1, 16052, 16053, 16054, -1, 16051, 16053, 16052, -1, 16054, 16055, 16056, -1, 16053, 16055, 16054, -1, 16056, 16057, 16058, -1, 16055, 16057, 16056, -1, 16058, 16059, 16060, -1, 16057, 16059, 16058, -1, 16060, 16061, 16062, -1, 16059, 16061, 16060, -1, 16062, 16063, 16064, -1, 16061, 16063, 16062, -1, 15998, 16001, 16065, -1, 16064, 16066, 16001, -1, 16063, 16066, 16064, -1, 16066, 16067, 16001, -1, 16065, 16068, 16069, -1, 16001, 16068, 16065, -1, 16067, 16068, 16001, -1, 16069, 12218, 12217, -1, 16068, 12218, 16069, -1, 12215, 12216, 16070, -1, 16070, 16071, 16072, -1, 12216, 16071, 16070, -1, 16072, 11050, 16026, -1, 16071, 11050, 16072, -1, 16071, 16073, 11050, -1, 11050, 16074, 11048, -1, 16073, 16074, 11050, -1, 11048, 16075, 11045, -1, 16074, 16075, 11048, -1, 11045, 16076, 11043, -1, 16075, 16076, 11045, -1, 11043, 16077, 11041, -1, 16076, 16077, 11043, -1, 11041, 16078, 11039, -1, 16077, 16078, 11041, -1, 11039, 16079, 11037, -1, 16078, 16079, 11039, -1, 11037, 16080, 11035, -1, 16079, 16080, 11037, -1, 11035, 16081, 11033, -1, 16080, 16081, 11035, -1, 11033, 16082, 11031, -1, 16081, 16082, 11033, -1, 11031, 16083, 11028, -1, 16082, 16083, 11031, -1, 11028, 12188, 11029, -1, 16083, 12188, 11028, -1, 10993, 12187, 16084, -1, 16084, 16085, 16086, -1, 12187, 16085, 16084, -1, 16018, 16021, 16087, -1, 16086, 16088, 16021, -1, 16085, 16088, 16086, -1, 16088, 16089, 16021, -1, 16021, 16089, 16087, -1, 16087, 16090, 16091, -1, 16089, 16090, 16087, -1, 16091, 16092, 16093, -1, 16090, 16092, 16091, -1, 16093, 16094, 16095, -1, 16092, 16094, 16093, -1, 16095, 16096, 16097, -1, 16094, 16096, 16095, -1, 16097, 16098, 16099, -1, 16096, 16098, 16097, -1, 16098, 16100, 16099, -1, 16099, 11026, 16006, -1, 16099, 16101, 11026, -1, 16100, 16101, 16099, -1, 11026, 16102, 11024, -1, 16101, 16102, 11026, -1, 11024, 16103, 11022, -1, 16102, 16103, 11024, -1, 11022, 12174, 11017, -1, 16103, 12174, 11022, -1, 12176, 12140, 12177, -1, 12176, 12142, 12140, -1, 12124, 12184, 12183, -1, 16092, 16104, 16105, -1, 12126, 12183, 12182, -1, 16092, 16090, 16104, -1, 12126, 12124, 12183, -1, 12122, 12185, 12184, -1, 12122, 12184, 12124, -1, 12128, 12182, 12181, -1, 12175, 12142, 12176, -1, 12128, 12126, 12182, -1, 12119, 12186, 12185, -1, 12119, 12185, 12122, -1, 12130, 12181, 12180, -1, 12130, 12128, 12181, -1, 16094, 16105, 16106, -1, 16094, 16092, 16105, -1, 12174, 16107, 12144, -1, 12174, 12142, 12175, -1, 12118, 12187, 12186, -1, 12174, 12144, 12142, -1, 12118, 12186, 12119, -1, 12132, 12130, 12180, -1, 16096, 16108, 16109, -1, 16096, 16106, 16108, -1, 16096, 16094, 16106, -1, 16103, 16107, 12174, -1, 16110, 16088, 16085, -1, 16110, 16085, 12187, -1, 16098, 16109, 16111, -1, 16098, 16096, 16109, -1, 16110, 12187, 12118, -1, 12134, 12180, 12179, -1, 16102, 16112, 16107, -1, 16102, 16107, 16103, -1, 12134, 12132, 12180, -1, 16100, 16111, 16113, -1, 16100, 16098, 16111, -1, 16101, 16113, 16112, -1, 16101, 16100, 16113, -1, 16101, 16112, 16102, -1, 16114, 16088, 16110, -1, 12136, 12179, 12178, -1, 12136, 12134, 12179, -1, 16089, 16088, 16114, -1, 16115, 16089, 16114, -1, 12138, 12136, 12178, -1, 12177, 12138, 12178, -1, 12140, 12138, 12177, -1, 16090, 16115, 16104, -1, 16090, 16089, 16115, -1, 16055, 16116, 16117, -1, 16055, 16053, 16116, -1, 12220, 12169, 12222, -1, 12220, 12171, 12169, -1, 12220, 12173, 12171, -1, 12153, 12241, 12239, -1, 16057, 16117, 16118, -1, 16057, 16055, 16117, -1, 12155, 12239, 12237, -1, 12218, 12173, 12220, -1, 12155, 12153, 12239, -1, 16059, 16118, 16119, -1, 16059, 16057, 16118, -1, 16068, 16120, 12173, -1, 12151, 12243, 12241, -1, 12151, 12241, 12153, -1, 16068, 12173, 12218, -1, 12157, 12237, 12235, -1, 16061, 16119, 16121, -1, 12157, 12155, 12237, -1, 16061, 16059, 16119, -1, 16067, 16122, 16120, -1, 12149, 12245, 12243, -1, 16067, 16120, 16068, -1, 12149, 12243, 12151, -1, 16063, 16121, 16123, -1, 12159, 12235, 12233, -1, 16063, 16061, 16121, -1, 12159, 12157, 12235, -1, 16066, 16123, 16122, -1, 16066, 16063, 16123, -1, 16066, 16122, 16067, -1, 12147, 12245, 12149, -1, 12161, 12233, 12232, -1, 12161, 12159, 12233, -1, 16124, 16049, 16047, -1, 16124, 16047, 12245, -1, 16124, 12245, 12147, -1, 12163, 12232, 12228, -1, 12163, 12161, 12232, -1, 16125, 16049, 16124, -1, 12165, 12228, 12226, -1, 12165, 12163, 12228, -1, 16051, 16049, 16125, -1, 16126, 16051, 16125, -1, 12167, 12165, 12226, -1, 12224, 12167, 12226, -1, 16053, 16051, 16126, -1, 16053, 16126, 16127, -1, 16116, 16053, 16127, -1, 12222, 12167, 12224, -1, 12222, 12169, 12167, -1, 12192, 12112, 12194, -1, 12192, 12114, 12112, -1, 16076, 16128, 16129, -1, 16076, 16075, 16128, -1, 12096, 12209, 12207, -1, 12098, 12207, 12205, -1, 12098, 12096, 12207, -1, 12094, 12211, 12209, -1, 12094, 12209, 12096, -1, 12100, 12205, 12204, -1, 12100, 12098, 12205, -1, 12190, 12114, 12192, -1, 12091, 12216, 12214, -1, 12091, 12214, 12211, -1, 12091, 12211, 12094, -1, 12102, 12204, 12203, -1, 12102, 12100, 12204, -1, 12090, 16071, 12216, -1, 12090, 12216, 12091, -1, 16077, 16129, 16130, -1, 16077, 16076, 16129, -1, 12104, 12102, 12203, -1, 12188, 12116, 12114, -1, 12188, 12114, 12190, -1, 16078, 16131, 16132, -1, 16078, 16130, 16131, -1, 16133, 16073, 16071, -1, 16078, 16077, 16130, -1, 16133, 16071, 12090, -1, 16083, 16134, 12116, -1, 12106, 12203, 12198, -1, 16083, 12116, 12188, -1, 12106, 12104, 12203, -1, 16079, 16132, 16135, -1, 16079, 16078, 16132, -1, 16082, 16136, 16134, -1, 16082, 16134, 16083, -1, 16137, 16073, 16133, -1, 16080, 16135, 16138, -1, 16080, 16079, 16135, -1, 12108, 12198, 12196, -1, 16081, 16138, 16136, -1, 12108, 12106, 12198, -1, 16081, 16080, 16138, -1, 16081, 16136, 16082, -1, 16074, 16073, 16137, -1, 16139, 16074, 16137, -1, 12110, 12108, 12196, -1, 12194, 12110, 12196, -1, 12112, 12110, 12194, -1, 16075, 16074, 16139, -1, 16075, 16139, 16128, -1, 12173, 16120, 12172, -1, 12172, 16120, 14321, -1, 14321, 16122, 14326, -1, 16120, 16122, 14321, -1, 14326, 16123, 14304, -1, 16122, 16123, 14326, -1, 14304, 16121, 14305, -1, 16123, 16121, 14304, -1, 14305, 16119, 14312, -1, 16121, 16119, 14305, -1, 14312, 16118, 14315, -1, 16119, 16118, 14312, -1, 14315, 16117, 14318, -1, 16118, 16117, 14315, -1, 14318, 16116, 14322, -1, 16117, 16116, 14318, -1, 14322, 16127, 14325, -1, 16116, 16127, 14322, -1, 14325, 16126, 14323, -1, 16127, 16126, 14325, -1, 14323, 16125, 14319, -1, 16126, 16125, 14323, -1, 14319, 16124, 14317, -1, 16125, 16124, 14319, -1, 14317, 12147, 12146, -1, 16124, 12147, 14317, -1, 12144, 16107, 12145, -1, 12145, 16107, 14299, -1, 14299, 16112, 14301, -1, 16107, 16112, 14299, -1, 14301, 16113, 14303, -1, 16112, 16113, 14301, -1, 14303, 16111, 14282, -1, 16113, 16111, 14303, -1, 14282, 16109, 14283, -1, 16111, 16109, 14282, -1, 14283, 16108, 14288, -1, 16109, 16108, 14283, -1, 14288, 16106, 14292, -1, 16108, 16106, 14288, -1, 14292, 16105, 14295, -1, 16106, 16105, 14292, -1, 14295, 16104, 14297, -1, 16105, 16104, 14295, -1, 14297, 16115, 14296, -1, 16104, 16115, 14297, -1, 14296, 16114, 14293, -1, 16115, 16114, 14296, -1, 14293, 16110, 14290, -1, 16114, 16110, 14293, -1, 14290, 12118, 12120, -1, 16110, 12118, 14290, -1, 12116, 16134, 12117, -1, 12117, 16134, 14347, -1, 14347, 16136, 14349, -1, 16134, 16136, 14347, -1, 14349, 16138, 14351, -1, 16136, 16138, 14349, -1, 14351, 16135, 14330, -1, 16138, 16135, 14351, -1, 14330, 16132, 14331, -1, 16135, 16132, 14330, -1, 14331, 16131, 14335, -1, 16132, 16131, 14331, -1, 14335, 16130, 14338, -1, 16131, 16130, 14335, -1, 14338, 16129, 14342, -1, 16130, 16129, 14338, -1, 14342, 16128, 14345, -1, 16129, 16128, 14342, -1, 14345, 16139, 14344, -1, 16128, 16139, 14345, -1, 14344, 16137, 14341, -1, 16139, 16137, 14344, -1, 14341, 16133, 14340, -1, 16137, 16133, 14341, -1, 14340, 12090, 12092, -1, 16133, 12090, 14340, -1, 12231, 14396, 14398, -1, 14396, 16012, 14394, -1, 14394, 16012, 14392, -1, 12231, 16012, 14396, -1, 16012, 14390, 14392, -1, 16012, 14387, 14390, -1, 14387, 16014, 14385, -1, 14385, 16014, 14483, -1, 16012, 16014, 14387, -1, 16014, 14551, 14483, -1, 16014, 14548, 14551, -1, 14548, 16011, 14546, -1, 14546, 16011, 14475, -1, 16014, 16011, 14548, -1, 16011, 14383, 14475, -1, 16011, 14381, 14383, -1, 14381, 16010, 14379, -1, 14379, 16010, 14377, -1, 16011, 16010, 14381, -1, 16010, 14374, 14377, -1, 16010, 14372, 14374, -1, 14372, 12200, 14370, -1, 16010, 12200, 14372, -1, 12202, 14370, 12200, -1, 12202, 14465, 14370, -1, 12206, 14467, 14465, -1, 12206, 14465, 12202, -1, 12208, 14422, 14467, -1, 12208, 14467, 12206, -1, 12210, 14422, 12208, -1, 14412, 14422, 12210, -1, 12212, 14412, 12210, -1, 14410, 14412, 12212, -1, 12213, 14410, 12212, -1, 14462, 14410, 12213, -1, 12215, 14464, 14462, -1, 12215, 14462, 12213, -1, 16070, 14460, 14464, -1, 16070, 14464, 12215, -1, 16072, 14460, 16070, -1, 14369, 14460, 16072, -1, 16026, 14369, 16072, -1, 16065, 14507, 14402, -1, 16065, 14402, 15998, -1, 16069, 14506, 14507, -1, 16069, 14507, 16065, -1, 12217, 14535, 14506, -1, 12217, 14506, 16069, -1, 12219, 14528, 14535, -1, 12219, 14535, 12217, -1, 12221, 14527, 14528, -1, 12221, 14528, 12219, -1, 12223, 14529, 14527, -1, 12223, 14527, 12221, -1, 12225, 14501, 14529, -1, 12225, 14529, 12223, -1, 12227, 14503, 14501, -1, 12227, 14501, 12225, -1, 12229, 14499, 14503, -1, 12229, 14503, 12227, -1, 12231, 14398, 14499, -1, 12231, 14499, 12229, -1, 16026, 14367, 14369, -1, 14367, 16024, 14366, -1, 14366, 16024, 14363, -1, 16026, 16024, 14367, -1, 16024, 14361, 14363, -1, 16024, 14452, 14361, -1, 14452, 16025, 14454, -1, 14454, 16025, 14537, -1, 16024, 16025, 14452, -1, 16025, 14441, 14537, -1, 16025, 14439, 14441, -1, 14439, 16023, 14442, -1, 14442, 16023, 14354, -1, 16025, 16023, 14439, -1, 16023, 14579, 14354, -1, 16023, 14578, 14579, -1, 14578, 16022, 14577, -1, 14577, 16022, 14576, -1, 16023, 16022, 14578, -1, 16022, 14575, 14576, -1, 16022, 14574, 14575, -1, 14574, 16018, 14428, -1, 16022, 16018, 14574, -1, 16006, 14424, 14358, -1, 14424, 16004, 14420, -1, 14420, 16004, 14418, -1, 16006, 16004, 14424, -1, 16004, 14416, 14418, -1, 16004, 14415, 14416, -1, 14415, 16005, 14572, -1, 14572, 16005, 14573, -1, 16004, 16005, 14415, -1, 16005, 14559, 14573, -1, 16005, 14561, 14559, -1, 14561, 16003, 14557, -1, 14557, 16003, 14555, -1, 16005, 16003, 14561, -1, 16003, 14511, 14555, -1, 16003, 14408, 14511, -1, 14408, 16002, 14406, -1, 14406, 16002, 14404, -1, 16003, 16002, 14408, -1, 16002, 14401, 14404, -1, 16002, 14399, 14401, -1, 14399, 15998, 14402, -1, 16002, 15998, 14399, -1, 16087, 14428, 16018, -1, 16087, 14426, 14428, -1, 16091, 14430, 14426, -1, 16091, 14426, 16087, -1, 14375, 14430, 16091, -1, 16093, 14375, 16091, -1, 16095, 14360, 14375, -1, 16095, 14375, 16093, -1, 16097, 14359, 14360, -1, 16097, 14356, 14359, -1, 16097, 14360, 16095, -1, 16099, 14355, 14356, -1, 16099, 14356, 16097, -1, 14357, 14355, 16099, -1, 16006, 14358, 14357, -1, 16006, 14357, 16099, -1, 16140, 16141, 16142, -1, 16143, 16141, 16140, -1, 16142, 16141, 16144, -1, 16141, 16145, 16144, -1, 16144, 16146, 16147, -1, 16145, 16146, 16144, -1, 16147, 16148, 16149, -1, 16146, 16148, 16147, -1, 16149, 16150, 16151, -1, 16148, 16150, 16149, -1, 16151, 16152, 16153, -1, 16150, 16152, 16151, -1, 16153, 16154, 16155, -1, 16152, 16154, 16153, -1, 16155, 12082, 11168, -1, 16154, 12082, 16155, -1, 16156, 11194, 16157, -1, 11195, 11194, 16156, -1, 16157, 11190, 16158, -1, 11194, 11190, 16157, -1, 16158, 11186, 16159, -1, 11190, 11186, 16158, -1, 16159, 11171, 16160, -1, 11186, 11171, 16159, -1, 16160, 11173, 16161, -1, 11171, 11173, 16160, -1, 16161, 11206, 16162, -1, 11173, 11206, 16161, -1, 16162, 11208, 16163, -1, 11206, 11208, 16162, -1, 16163, 16164, 16165, -1, 11208, 16164, 16163, -1, 16165, 16166, 16167, -1, 16164, 16166, 16165, -1, 16167, 16168, 16169, -1, 16166, 16168, 16167, -1, 16169, 16170, 16171, -1, 16168, 16170, 16169, -1, 16171, 16172, 16173, -1, 16170, 16172, 16171, -1, 16173, 16174, 16140, -1, 16172, 16174, 16173, -1, 16174, 16143, 16140, -1, 12089, 11195, 11155, -1, 11155, 11195, 16156, -1, 16175, 16176, 16177, -1, 16175, 16178, 16176, -1, 16176, 16178, 16179, -1, 16179, 16180, 16181, -1, 16178, 16180, 16179, -1, 16180, 16182, 16181, -1, 16181, 16183, 16184, -1, 16182, 16183, 16181, -1, 16184, 16185, 16186, -1, 16183, 16185, 16184, -1, 16186, 16187, 16188, -1, 16185, 16187, 16186, -1, 16188, 16189, 16190, -1, 16187, 16189, 16188, -1, 16190, 16191, 16192, -1, 16189, 16191, 16190, -1, 16192, 16193, 16194, -1, 16191, 16193, 16192, -1, 16194, 16195, 16196, -1, 16193, 16195, 16194, -1, 16196, 16197, 16198, -1, 16195, 16197, 16196, -1, 16198, 12078, 11271, -1, 16197, 12078, 16198, -1, 11269, 11270, 16199, -1, 16199, 11270, 16200, -1, 16200, 11267, 16201, -1, 11270, 11267, 16200, -1, 16201, 11261, 16202, -1, 11267, 11261, 16201, -1, 16202, 11253, 16203, -1, 11261, 11253, 16202, -1, 16203, 11245, 16204, -1, 11253, 11245, 16203, -1, 16204, 11240, 16205, -1, 11245, 11240, 16204, -1, 16205, 11234, 16206, -1, 11240, 11234, 16205, -1, 16206, 11228, 16207, -1, 11234, 11228, 16206, -1, 16207, 11223, 16208, -1, 11228, 11223, 16207, -1, 16208, 11214, 16209, -1, 11223, 11214, 16208, -1, 16209, 11230, 16210, -1, 11214, 11230, 16209, -1, 16210, 16211, 16212, -1, 11230, 16211, 16210, -1, 16212, 16213, 16177, -1, 16211, 16213, 16212, -1, 16213, 16175, 16177, -1, 11275, 11269, 16199, -1, 12081, 11269, 11275, -1, 12077, 16214, 11116, -1, 12077, 11069, 16214, -1, 11069, 11070, 16214, -1, 16214, 11070, 16215, -1, 16215, 11061, 16216, -1, 11070, 11061, 16215, -1, 16216, 11063, 16217, -1, 11061, 11063, 16216, -1, 16217, 16218, 16219, -1, 11063, 16218, 16217, -1, 16219, 16220, 16221, -1, 16218, 16220, 16219, -1, 16221, 16222, 16223, -1, 16220, 16222, 16221, -1, 16223, 16224, 16225, -1, 16222, 16224, 16223, -1, 16225, 16226, 16227, -1, 16224, 16226, 16225, -1, 16227, 16228, 16229, -1, 16226, 16228, 16227, -1, 16229, 16230, 16231, -1, 16228, 16230, 16229, -1, 16231, 16232, 16233, -1, 16230, 16232, 16231, -1, 16233, 16234, 16235, -1, 16232, 16234, 16233, -1, 16235, 16236, 16237, -1, 16234, 16236, 16235, -1, 16236, 16238, 16237, -1, 16239, 16240, 16241, -1, 16241, 16240, 16242, -1, 16243, 16244, 11090, -1, 16242, 16244, 16243, -1, 16240, 16244, 16242, -1, 16244, 12066, 11090, -1, 16237, 16239, 16241, -1, 16238, 16239, 16237, -1, 16245, 16246, 16247, -1, 16248, 16246, 16245, -1, 12053, 16249, 11865, -1, 11865, 16249, 16250, -1, 16247, 16251, 16252, -1, 16252, 16251, 16253, -1, 16246, 16251, 16247, -1, 16250, 16254, 16255, -1, 16249, 16254, 16250, -1, 16253, 16256, 16257, -1, 16251, 16256, 16253, -1, 16257, 16258, 16259, -1, 16255, 16260, 16261, -1, 16256, 16258, 16257, -1, 16254, 16260, 16255, -1, 16259, 16262, 16263, -1, 16261, 16264, 16265, -1, 16258, 16262, 16259, -1, 16260, 16264, 16261, -1, 16263, 16266, 16267, -1, 16264, 16268, 16265, -1, 16262, 16266, 16263, -1, 16265, 16268, 16269, -1, 16267, 16270, 16271, -1, 16266, 16270, 16267, -1, 16269, 16272, 16273, -1, 16271, 16274, 16275, -1, 16268, 16276, 16269, -1, 16270, 16274, 16271, -1, 16269, 16276, 16272, -1, 16274, 16277, 16275, -1, 16276, 16278, 16272, -1, 16275, 16277, 16279, -1, 16278, 16280, 16281, -1, 16277, 16282, 16279, -1, 16276, 16283, 16278, -1, 16279, 16282, 16284, -1, 16278, 16283, 16280, -1, 16282, 16285, 16284, -1, 16284, 16285, 16286, -1, 16283, 16287, 16280, -1, 16280, 16287, 16288, -1, 16285, 16289, 16286, -1, 16286, 16289, 16290, -1, 16287, 16291, 16288, -1, 16288, 16291, 16292, -1, 16291, 16293, 16292, -1, 16293, 16294, 16292, -1, 16290, 16295, 16296, -1, 16293, 16297, 16294, -1, 16289, 16298, 16290, -1, 16290, 16298, 16295, -1, 16297, 16299, 16294, -1, 16297, 16300, 16299, -1, 16300, 16301, 16299, -1, 16298, 16302, 16295, -1, 16295, 16302, 16303, -1, 16300, 16304, 16301, -1, 16302, 16305, 16303, -1, 16304, 16306, 16301, -1, 16303, 16305, 16307, -1, 16304, 16308, 16306, -1, 16302, 16309, 16305, -1, 16309, 16310, 16305, -1, 16308, 16311, 16306, -1, 16309, 16312, 16310, -1, 16308, 16313, 16311, -1, 16312, 16314, 16310, -1, 16313, 16315, 16311, -1, 16312, 16316, 16314, -1, 16313, 16317, 16315, -1, 16316, 16318, 16314, -1, 16317, 16319, 16315, -1, 16316, 16320, 16318, -1, 16317, 16321, 16319, -1, 16320, 16322, 16318, -1, 16320, 16323, 16322, -1, 16321, 16324, 16319, -1, 16323, 11871, 16322, -1, 16321, 16248, 16324, -1, 16323, 12057, 11871, -1, 16248, 16325, 16324, -1, 16248, 16245, 16325, -1, 16326, 16327, 16328, -1, 16329, 16330, 16331, -1, 16329, 16326, 16330, -1, 16332, 16331, 16333, -1, 16332, 16329, 16331, -1, 16334, 11545, 11543, -1, 16334, 11547, 11545, -1, 16335, 16333, 16336, -1, 16334, 11548, 11547, -1, 16335, 16332, 16333, -1, 16337, 16336, 16338, -1, 16337, 16335, 16336, -1, 16339, 11541, 11539, -1, 16339, 11543, 11541, -1, 16340, 16337, 16338, -1, 16339, 16334, 11543, -1, 16341, 16338, 16342, -1, 16341, 16340, 16338, -1, 16343, 16342, 16344, -1, 16343, 16341, 16342, -1, 16345, 16344, 16346, -1, 16345, 16343, 16344, -1, 16347, 16346, 16348, -1, 16347, 16345, 16346, -1, 16349, 16348, 16350, -1, 16349, 16347, 16348, -1, 16351, 16350, 16352, -1, 16351, 16349, 16350, -1, 16353, 16352, 16354, -1, 16355, 11538, 11536, -1, 16355, 11539, 11538, -1, 16353, 16351, 16352, -1, 16355, 16339, 11539, -1, 16356, 16353, 16354, -1, 16356, 16354, 11562, -1, 16357, 16358, 16359, -1, 16357, 16360, 16358, -1, 16361, 16359, 16362, -1, 16361, 16357, 16359, -1, 16363, 16362, 16364, -1, 16363, 16361, 16362, -1, 16365, 11536, 11534, -1, 16365, 16355, 11536, -1, 16366, 16364, 16367, -1, 16366, 16363, 16364, -1, 16368, 16366, 16367, -1, 16368, 16367, 16369, -1, 16370, 16368, 16369, -1, 16371, 16372, 16373, -1, 16371, 16374, 16372, -1, 16375, 16371, 16373, -1, 16376, 16377, 16378, -1, 16376, 16379, 16377, -1, 16380, 16378, 16381, -1, 16380, 16376, 16378, -1, 16382, 16381, 16383, -1, 16382, 16380, 16381, -1, 16384, 16385, 16386, -1, 16384, 16383, 16385, -1, 16384, 16382, 16383, -1, 16387, 11608, 16388, -1, 16389, 16388, 16390, -1, 16389, 16387, 16388, -1, 16391, 16389, 16390, -1, 16391, 16390, 16392, -1, 16393, 16391, 16392, -1, 16393, 16392, 16394, -1, 16395, 16394, 16396, -1, 16395, 16393, 16394, -1, 16397, 16395, 16396, -1, 16397, 16396, 16398, -1, 16399, 16397, 16398, -1, 16399, 16398, 16400, -1, 16401, 16399, 16400, -1, 16401, 16400, 16402, -1, 16403, 16402, 16404, -1, 11648, 16405, 16406, -1, 11648, 11557, 16405, -1, 16403, 16401, 16402, -1, 11648, 11639, 11557, -1, 16407, 16403, 16404, -1, 16408, 16407, 16404, -1, 16408, 16404, 16409, -1, 16410, 16409, 16411, -1, 16410, 16408, 16409, -1, 16412, 16411, 16413, -1, 16412, 16410, 16411, -1, 16414, 16413, 16415, -1, 16414, 16412, 16413, -1, 16416, 16414, 16415, -1, 16416, 16415, 16417, -1, 16418, 16417, 16419, -1, 16418, 16416, 16417, -1, 16420, 16418, 16419, -1, 16420, 16419, 16421, -1, 16422, 16421, 16423, -1, 16422, 16420, 16421, -1, 16424, 16422, 16423, -1, 16424, 16423, 11548, -1, 16425, 16426, 16365, -1, 16425, 11528, 11530, -1, 16425, 11534, 11528, -1, 11655, 16427, 16428, -1, 11655, 16406, 16427, -1, 16425, 16365, 11534, -1, 11655, 11648, 16406, -1, 16429, 16430, 16426, -1, 16429, 16425, 11530, -1, 16429, 16431, 16432, -1, 16429, 11530, 16431, -1, 16429, 16426, 16425, -1, 16433, 16434, 16435, -1, 16433, 16326, 16329, -1, 16433, 16329, 16332, -1, 16436, 16437, 16434, -1, 16436, 16434, 16433, -1, 16436, 16433, 16332, -1, 16436, 16335, 16337, -1, 16436, 16332, 16335, -1, 16438, 16337, 16340, -1, 16438, 16439, 16437, -1, 16438, 16437, 16436, -1, 16438, 16436, 16337, -1, 16440, 16441, 16442, -1, 16440, 16343, 16345, -1, 11665, 16428, 16443, -1, 11665, 11655, 16428, -1, 16444, 11628, 16441, -1, 16444, 16441, 16440, -1, 16444, 16345, 16347, -1, 16444, 16347, 16349, -1, 16444, 16440, 16345, -1, 16445, 16349, 16351, -1, 16445, 16353, 16356, -1, 16445, 16351, 16353, -1, 16445, 11628, 16444, -1, 16445, 11629, 11628, -1, 16445, 16444, 16349, -1, 16446, 11562, 11560, -1, 16446, 16445, 16356, -1, 16446, 11629, 16445, -1, 16446, 16356, 11562, -1, 16447, 11558, 11557, -1, 16447, 11560, 11558, -1, 16447, 16446, 11560, -1, 16447, 11557, 11639, -1, 16447, 11629, 16446, -1, 16447, 11639, 11629, -1, 16448, 16443, 16449, -1, 16448, 11665, 16443, -1, 16448, 11675, 11665, -1, 16450, 16449, 16360, -1, 16450, 16360, 16357, -1, 16450, 11675, 16448, -1, 16450, 16448, 16449, -1, 16451, 16357, 16361, -1, 16451, 16450, 16357, -1, 16451, 11675, 16450, -1, 16451, 11682, 11675, -1, 16452, 16453, 16454, -1, 16452, 16455, 16372, -1, 16452, 16456, 16455, -1, 16452, 16369, 16456, -1, 16452, 16374, 16453, -1, 16452, 16454, 16370, -1, 16452, 16372, 16374, -1, 16452, 16370, 16369, -1, 16457, 16454, 16453, -1, 16457, 16370, 16454, -1, 16457, 11694, 11690, -1, 16458, 16457, 16453, -1, 16458, 16453, 16374, -1, 16458, 11694, 16457, -1, 16458, 16374, 16371, -1, 16458, 11698, 11694, -1, 16459, 16375, 16373, -1, 16459, 16379, 16460, -1, 16459, 16461, 16377, -1, 16459, 16462, 16461, -1, 16459, 16373, 16462, -1, 16459, 16463, 16375, -1, 16459, 16377, 16379, -1, 16459, 16460, 16463, -1, 16464, 16371, 16375, -1, 16464, 16458, 16371, -1, 16464, 11698, 16458, -1, 16464, 11702, 11698, -1, 16465, 16376, 16380, -1, 16465, 11623, 11620, -1, 16466, 11626, 11623, -1, 16466, 16380, 16382, -1, 16466, 11623, 16465, -1, 16466, 16465, 16380, -1, 16466, 16382, 16384, -1, 16467, 16384, 16386, -1, 16467, 16386, 16468, -1, 16467, 16466, 16384, -1, 16467, 11626, 16466, -1, 16469, 11636, 11626, -1, 16469, 16470, 11636, -1, 16469, 16468, 16470, -1, 16469, 11626, 16467, -1, 16469, 16467, 16468, -1, 16471, 16387, 16389, -1, 16471, 11609, 11608, -1, 16471, 11608, 16387, -1, 16472, 16471, 11670, -1, 16472, 11670, 11661, -1, 16472, 11613, 11609, -1, 16472, 11615, 11613, -1, 16472, 11661, 11615, -1, 16472, 11609, 16471, -1, 16473, 16389, 16391, -1, 16473, 11670, 16471, -1, 16473, 11681, 11670, -1, 16473, 16391, 16393, -1, 16473, 16471, 16389, -1, 16474, 11681, 16473, -1, 16474, 16475, 11681, -1, 16474, 16473, 16393, -1, 16474, 16393, 16395, -1, 16476, 16399, 16401, -1, 16476, 16401, 16403, -1, 16476, 16477, 16478, -1, 16479, 16477, 16476, -1, 16479, 16476, 16403, -1, 16479, 16403, 16407, -1, 16479, 16480, 16477, -1, 16481, 16414, 16416, -1, 16481, 16416, 16418, -1, 16481, 16482, 16483, -1, 11636, 16470, 16484, -1, 16485, 16422, 16424, -1, 16485, 16424, 11548, -1, 16485, 11548, 16334, -1, 16485, 16334, 16486, -1, 16487, 16429, 16432, -1, 16487, 16488, 16489, -1, 16487, 16432, 16488, -1, 16490, 16491, 16430, -1, 16490, 16429, 16487, -1, 16490, 16430, 16429, -1, 16492, 16489, 16327, -1, 16492, 16326, 16433, -1, 16492, 16327, 16326, -1, 16493, 16435, 16491, -1, 16493, 16433, 16435, -1, 16493, 16492, 16433, -1, 16494, 16343, 16440, -1, 16494, 16341, 16343, -1, 16494, 16340, 16341, -1, 16494, 16438, 16340, -1, 16495, 16439, 16438, -1, 16495, 16442, 16439, -1, 16495, 16440, 16442, -1, 16495, 16494, 16440, -1, 16495, 16438, 16494, -1, 16496, 16451, 16361, -1, 11643, 11636, 16484, -1, 16496, 16363, 16366, -1, 11643, 16497, 16498, -1, 16496, 16361, 16363, -1, 11643, 16484, 16497, -1, 16499, 16451, 16496, -1, 16499, 11682, 16451, -1, 16499, 11686, 11682, -1, 16500, 16368, 16370, -1, 16500, 16366, 16368, -1, 16500, 16370, 16457, -1, 16501, 16500, 16457, -1, 16501, 16457, 11690, -1, 16501, 11690, 11686, -1, 16502, 16464, 16375, -1, 16502, 16375, 16463, -1, 16502, 16463, 16460, -1, 16503, 16464, 16502, -1, 16503, 11702, 16464, -1, 16503, 11707, 11702, -1, 16504, 16460, 16379, -1, 16504, 16379, 16376, -1, 16504, 16376, 16465, -1, 16505, 16504, 16465, -1, 16505, 16465, 11620, -1, 16505, 11620, 11707, -1, 16506, 16397, 16399, -1, 16506, 16399, 16476, -1, 16506, 16395, 16397, -1, 16506, 16474, 16395, -1, 16507, 16476, 16478, -1, 16507, 16474, 16506, -1, 16507, 16506, 16476, -1, 16507, 16478, 16475, -1, 16507, 16475, 16474, -1, 16508, 16479, 16407, -1, 16508, 16408, 16410, -1, 16508, 16407, 16408, -1, 16509, 16479, 16508, -1, 16509, 16480, 16479, -1, 16509, 16510, 16480, -1, 16511, 16410, 16412, -1, 16511, 16414, 16481, -1, 11652, 11643, 16498, -1, 16511, 16412, 16414, -1, 11652, 16512, 11615, -1, 16513, 16481, 16483, -1, 11652, 16498, 16512, -1, 16513, 16511, 16481, -1, 16513, 16483, 16510, -1, 16514, 16481, 16418, -1, 16514, 16482, 16481, -1, 16514, 16418, 16420, -1, 16514, 16515, 16482, -1, 16516, 16485, 16486, -1, 16516, 16420, 16422, -1, 16516, 16422, 16485, -1, 16516, 16514, 16420, -1, 16516, 16515, 16514, -1, 16516, 16486, 16515, -1, 16517, 16490, 16487, -1, 16517, 16489, 16492, -1, 16517, 16493, 16491, -1, 16517, 16491, 16490, -1, 16517, 16492, 16493, -1, 16517, 16487, 16489, -1, 16518, 16366, 16500, -1, 16518, 11686, 16499, -1, 16518, 16501, 11686, -1, 16518, 16496, 16366, -1, 16518, 16500, 16501, -1, 16518, 16499, 16496, -1, 11661, 11652, 11615, -1, 16519, 16503, 16502, -1, 16519, 16502, 16460, -1, 16519, 11707, 16503, -1, 16519, 16505, 11707, -1, 16519, 16504, 16505, -1, 16519, 16460, 16504, -1, 16520, 16509, 16508, -1, 16520, 16508, 16410, -1, 16520, 16510, 16509, -1, 16520, 16511, 16513, -1, 16520, 16513, 16510, -1, 16520, 16410, 16511, -1, 16431, 11530, 16521, -1, 16431, 16521, 16522, -1, 16432, 16522, 16523, -1, 16432, 16431, 16522, -1, 16488, 16523, 16524, -1, 16488, 16432, 16523, -1, 16489, 16524, 16328, -1, 16489, 16488, 16524, -1, 16327, 16489, 16328, -1, 16326, 16328, 16330, -1, 16525, 16526, 16527, -1, 14276, 16528, 14275, -1, 16529, 16528, 14276, -1, 14258, 16528, 16529, -1, 16530, 16531, 16526, -1, 16526, 16531, 14248, -1, 16528, 16532, 14275, -1, 14275, 16532, 14259, -1, 14259, 16532, 14258, -1, 14258, 16532, 16528, -1, 14248, 16533, 14247, -1, 14247, 16533, 16534, -1, 16534, 16533, 16530, -1, 16531, 16533, 14248, -1, 16530, 16533, 16531, -1, 14259, 16535, 14275, -1, 14274, 16535, 14260, -1, 14260, 16535, 14259, -1, 14275, 16535, 14274, -1, 14260, 16536, 14274, -1, 14261, 16536, 14260, -1, 14262, 16537, 14261, -1, 14273, 16537, 14262, -1, 14274, 16537, 14273, -1, 16536, 16537, 14274, -1, 14261, 16537, 16536, -1, 16538, 16539, 16540, -1, 16540, 16539, 14262, -1, 16541, 16542, 16543, -1, 14262, 16539, 14273, -1, 16543, 16542, 16544, -1, 14273, 16539, 14272, -1, 16544, 16542, 16545, -1, 14272, 16539, 16538, -1, 16546, 16547, 16548, -1, 16548, 16547, 16538, -1, 16549, 16542, 16541, -1, 14272, 16547, 14271, -1, 16538, 16547, 14272, -1, 16546, 16550, 16547, -1, 16551, 16550, 16546, -1, 16547, 16552, 14271, -1, 14271, 16552, 14270, -1, 16553, 16554, 16555, -1, 16555, 16554, 16551, -1, 16551, 16554, 16550, -1, 16550, 16556, 16547, -1, 16547, 16556, 16552, -1, 16552, 16557, 14270, -1, 16550, 16558, 16556, -1, 16559, 16558, 16554, -1, 16554, 16558, 16550, -1, 16556, 16560, 16552, -1, 16552, 16560, 16557, -1, 16557, 16561, 14270, -1, 14270, 16561, 14269, -1, 14269, 16561, 14268, -1, 16556, 16562, 16560, -1, 16558, 16562, 16556, -1, 16560, 16563, 16557, -1, 16557, 16563, 16561, -1, 16560, 16564, 16563, -1, 16562, 16564, 16560, -1, 16565, 16564, 16566, -1, 16566, 16564, 16562, -1, 16561, 16567, 14268, -1, 16563, 16567, 16561, -1, 14268, 16567, 14267, -1, 16564, 16568, 16563, -1, 16565, 16568, 16564, -1, 16563, 16568, 16567, -1, 14263, 16569, 14264, -1, 16567, 16570, 14267, -1, 14264, 16569, 16571, -1, 14267, 16570, 14266, -1, 16565, 16572, 16568, -1, 16568, 16572, 16567, -1, 16570, 16572, 14266, -1, 16573, 16572, 16565, -1, 16569, 16574, 16571, -1, 16567, 16572, 16570, -1, 16534, 14245, 14247, -1, 16572, 16575, 14266, -1, 16573, 16575, 16572, -1, 14266, 16575, 14265, -1, 16573, 16576, 16575, -1, 16575, 16576, 14265, -1, 14265, 16576, 14263, -1, 16569, 16576, 16573, -1, 14263, 16576, 16569, -1, 16545, 16577, 16578, -1, 16578, 16577, 16553, -1, 16542, 16577, 16545, -1, 16553, 16577, 16554, -1, 16554, 16577, 16559, -1, 16574, 16579, 16580, -1, 16559, 16577, 16542, -1, 16580, 16579, 16581, -1, 16559, 16582, 16558, -1, 16566, 16582, 16559, -1, 16562, 16582, 16566, -1, 16558, 16582, 16562, -1, 16569, 16579, 16574, -1, 14254, 16583, 14255, -1, 14255, 16583, 14279, -1, 14279, 16583, 14278, -1, 16584, 16585, 16586, -1, 16586, 16585, 14253, -1, 14253, 16585, 14252, -1, 16587, 16585, 16584, -1, 16583, 16588, 14278, -1, 14256, 16588, 14254, -1, 14245, 16549, 14246, -1, 14278, 16588, 14277, -1, 14246, 16549, 16589, -1, 14254, 16588, 16583, -1, 14252, 16590, 14251, -1, 16534, 16549, 14245, -1, 16587, 16590, 16585, -1, 16585, 16590, 14252, -1, 16549, 16541, 16589, -1, 16588, 16591, 14277, -1, 14256, 16591, 16588, -1, 14251, 16592, 14250, -1, 16587, 16592, 16590, -1, 16590, 16592, 14251, -1, 16525, 16592, 16587, -1, 16591, 16593, 14277, -1, 14256, 16593, 16591, -1, 14257, 16593, 14256, -1, 14277, 16593, 14276, -1, 14250, 16527, 14249, -1, 16525, 16527, 16592, -1, 16592, 16527, 14250, -1, 14258, 16529, 14257, -1, 16593, 16529, 14276, -1, 14257, 16529, 16593, -1, 14249, 16526, 14248, -1, 16527, 16526, 14249, -1, 16530, 16526, 16525, -1, 16320, 16594, 16323, -1, 13537, 16594, 13559, -1, 16316, 16595, 16320, -1, 16312, 16595, 16316, -1, 16594, 16595, 13559, -1, 13559, 16595, 13567, -1, 16320, 16595, 16594, -1, 16596, 16246, 16597, -1, 16309, 16598, 16312, -1, 16251, 16246, 16596, -1, 16312, 16598, 16595, -1, 13567, 16598, 13573, -1, 13573, 16598, 13577, -1, 16595, 16598, 13567, -1, 16302, 16599, 16309, -1, 16600, 16599, 16302, -1, 13577, 16599, 13583, -1, 13583, 16599, 16600, -1, 16309, 16599, 16598, -1, 16246, 16248, 16597, -1, 16598, 16599, 13577, -1, 16289, 16601, 16298, -1, 16298, 16601, 16602, -1, 16602, 16601, 13722, -1, 13722, 16601, 13738, -1, 16289, 16603, 16601, -1, 16285, 16603, 16289, -1, 16601, 16603, 13738, -1, 13738, 16603, 13809, -1, 13809, 16603, 13713, -1, 16282, 16604, 16285, -1, 16277, 16604, 16282, -1, 16285, 16604, 16603, -1, 16603, 16604, 13713, -1, 13713, 16604, 13740, -1, 16274, 16605, 16277, -1, 13740, 16605, 13757, -1, 16277, 16605, 16604, -1, 16604, 16605, 13740, -1, 16270, 16606, 16274, -1, 16605, 16606, 13757, -1, 13757, 16606, 13716, -1, 13716, 16606, 13735, -1, 16274, 16606, 16605, -1, 16266, 16607, 16270, -1, 16262, 16607, 16266, -1, 16270, 16607, 16606, -1, 16606, 16607, 13735, -1, 13735, 16607, 13779, -1, 16258, 16608, 16262, -1, 13779, 16608, 13785, -1, 16262, 16608, 16607, -1, 16607, 16608, 13779, -1, 16608, 16609, 13785, -1, 16256, 16609, 16258, -1, 16251, 16609, 16256, -1, 13785, 16609, 13788, -1, 13788, 16609, 13798, -1, 16258, 16609, 16608, -1, 16251, 16610, 16609, -1, 16609, 16610, 13798, -1, 13798, 16610, 13804, -1, 13804, 16610, 16596, -1, 16596, 16610, 16251, -1, 16597, 16611, 16584, -1, 16302, 16602, 16600, -1, 16584, 16611, 16587, -1, 16248, 16611, 16597, -1, 16321, 16612, 16248, -1, 16317, 16612, 16321, -1, 16302, 16298, 16602, -1, 16248, 16612, 16611, -1, 16611, 16612, 16587, -1, 16587, 16612, 16525, -1, 16525, 16612, 16530, -1, 16313, 16613, 16317, -1, 16530, 16613, 16534, -1, 16317, 16613, 16612, -1, 16612, 16613, 16530, -1, 16308, 16614, 16313, -1, 16304, 16614, 16308, -1, 16534, 16614, 16549, -1, 16313, 16614, 16613, -1, 16613, 16614, 16534, -1, 16304, 16615, 16614, -1, 16614, 16615, 16549, -1, 16300, 16615, 16304, -1, 16549, 16615, 16542, -1, 16542, 16615, 16559, -1, 16300, 16616, 16615, -1, 16615, 16616, 16559, -1, 16297, 16616, 16300, -1, 16559, 16616, 16566, -1, 16293, 16617, 16297, -1, 16291, 16617, 16293, -1, 16616, 16617, 16566, -1, 16297, 16617, 16616, -1, 16566, 16617, 16565, -1, 16287, 16618, 16291, -1, 16617, 16618, 16565, -1, 16291, 16618, 16617, -1, 16565, 16618, 16573, -1, 16573, 16618, 16569, -1, 16619, 16620, 16283, -1, 16283, 16620, 16287, -1, 16618, 16620, 16569, -1, 16287, 16620, 16618, -1, 16569, 16620, 16579, -1, 16579, 16620, 16619, -1, 16268, 16621, 16276, -1, 16276, 16621, 16622, -1, 16622, 16621, 13834, -1, 13834, 16621, 13833, -1, 16264, 16623, 16268, -1, 13833, 16623, 13837, -1, 13837, 16623, 13845, -1, 16268, 16623, 16621, -1, 16621, 16623, 13833, -1, 16260, 16624, 16264, -1, 16254, 16624, 16260, -1, 13845, 16624, 13854, -1, 16623, 16624, 13845, -1, 16264, 16624, 16623, -1, 16254, 16625, 16624, -1, 16283, 16276, 16619, -1, 16624, 16625, 13854, -1, 16249, 16625, 16254, -1, 16619, 16276, 16622, -1, 13854, 16625, 13868, -1, 13537, 16626, 16594, -1, 12055, 16626, 13537, -1, 16323, 16627, 12057, -1, 12055, 16627, 16626, -1, 12057, 16627, 12055, -1, 16626, 16627, 16594, -1, 16594, 16627, 16323, -1, 16625, 16628, 13868, -1, 13868, 16628, 12051, -1, 16628, 16629, 12051, -1, 16249, 16629, 16625, -1, 12053, 16629, 16249, -1, 16625, 16629, 16628, -1, 12051, 16629, 12053, -1, 16630, 15191, 16269, -1, 16269, 15191, 16265, -1, 15191, 15190, 16265, -1, 16265, 15190, 16261, -1, 15208, 15206, 16253, -1, 16253, 16631, 16252, -1, 15190, 15189, 16261, -1, 15206, 16631, 16253, -1, 16261, 15189, 16255, -1, 11873, 15207, 11871, -1, 11871, 15207, 16322, -1, 15189, 15188, 16255, -1, 16255, 15188, 16250, -1, 15207, 15209, 16322, -1, 16322, 15209, 16318, -1, 15188, 15187, 16250, -1, 16250, 15187, 11865, -1, 15187, 11863, 11865, -1, 16632, 16324, 16325, -1, 15209, 15211, 16318, -1, 16631, 15205, 16633, -1, 16318, 15211, 16314, -1, 16633, 15205, 16634, -1, 16634, 15205, 16632, -1, 15206, 15205, 16631, -1, 15211, 15213, 16314, -1, 16314, 15213, 16310, -1, 15205, 15204, 16632, -1, 16632, 15204, 16324, -1, 15213, 15215, 16310, -1, 16310, 15215, 16305, -1, 16324, 15203, 16319, -1, 15204, 15203, 16324, -1, 15215, 16635, 16305, -1, 16305, 16635, 16307, -1, 16319, 15202, 16315, -1, 15203, 15202, 16319, -1, 15202, 15201, 16315, -1, 16315, 15201, 16311, -1, 15201, 15200, 16311, -1, 15215, 15217, 16635, -1, 16311, 15200, 16306, -1, 16635, 15217, 16636, -1, 16636, 15217, 16637, -1, 16637, 15217, 16638, -1, 16638, 16290, 16296, -1, 15200, 15199, 16306, -1, 16306, 15199, 16301, -1, 15217, 15219, 16638, -1, 16638, 15219, 16290, -1, 15199, 15198, 16301, -1, 16301, 15198, 16299, -1, 15219, 15221, 16290, -1, 16290, 15221, 16286, -1, 15198, 15197, 16299, -1, 15221, 15223, 16286, -1, 16299, 15197, 16294, -1, 16286, 15223, 16284, -1, 15197, 15196, 16294, -1, 16294, 15196, 16292, -1, 15223, 15222, 16284, -1, 16284, 15222, 16279, -1, 15222, 15220, 16279, -1, 15196, 15195, 16292, -1, 16292, 15195, 16288, -1, 16279, 15220, 16275, -1, 15195, 15194, 16288, -1, 16288, 15194, 16280, -1, 15220, 15218, 16275, -1, 16275, 15218, 16271, -1, 15218, 15216, 16271, -1, 16271, 15216, 16267, -1, 16280, 16639, 16281, -1, 15194, 15193, 16280, -1, 16280, 15193, 16639, -1, 16267, 15214, 16263, -1, 15216, 15214, 16267, -1, 16263, 15212, 16259, -1, 15214, 15212, 16263, -1, 16630, 16269, 16273, -1, 16259, 15210, 16257, -1, 15193, 15192, 16639, -1, 15212, 15210, 16259, -1, 16639, 15192, 16640, -1, 16640, 15192, 16641, -1, 16641, 15192, 16630, -1, 16257, 15208, 16253, -1, 15210, 15208, 16257, -1, 15192, 15191, 16630, -1, 16642, 16643, 16644, -1, 16645, 16642, 16644, -1, 13891, 16645, 16644, -1, 16646, 16645, 13891, -1, 16647, 16646, 13891, -1, 13892, 16647, 13891, -1, 13890, 13892, 13891, -1, 16648, 16649, 16650, -1, 16651, 16648, 16650, -1, 14126, 16651, 16650, -1, 16652, 16651, 14126, -1, 16653, 16652, 14126, -1, 14127, 16653, 14126, -1, 14125, 14127, 14126, -1, 16654, 16655, 16656, -1, 16657, 16654, 16656, -1, 13827, 16657, 16656, -1, 16658, 16657, 13827, -1, 16659, 16658, 13827, -1, 13828, 16659, 13827, -1, 13826, 13828, 13827, -1, 16660, 16661, 16662, -1, 16661, 16663, 16664, -1, 16665, 16666, 16667, -1, 16668, 16666, 16669, -1, 16670, 16666, 16668, -1, 16671, 16666, 16670, -1, 16672, 16666, 16671, -1, 16669, 16666, 16665, -1, 16667, 16666, 16673, -1, 16673, 16666, 16674, -1, 16674, 16666, 16675, -1, 16660, 16676, 16661, -1, 16675, 16666, 16677, -1, 16661, 16676, 16663, -1, 16677, 16666, 16678, -1, 16679, 16680, 16660, -1, 16660, 16680, 16676, -1, 16681, 16682, 16679, -1, 16679, 16682, 16680, -1, 16666, 11731, 16678, -1, 16683, 16684, 16681, -1, 16681, 16685, 16683, -1, 16684, 16686, 16681, -1, 16681, 16687, 16682, -1, 16686, 16687, 16681, -1, 16687, 16688, 16682, -1, 16688, 16689, 16682, -1, 16689, 16690, 16682, -1, 16691, 16692, 16682, -1, 16693, 16692, 16691, -1, 11718, 16692, 16694, -1, 16694, 16692, 16695, -1, 16695, 16692, 16693, -1, 11721, 16692, 11719, -1, 11719, 16692, 11718, -1, 16690, 16696, 16682, -1, 16696, 16691, 16682, -1, 11721, 11457, 16692, -1, 11731, 11457, 11729, -1, 16666, 11457, 11731, -1, 11729, 11457, 11727, -1, 16697, 16669, 16665, -1, 11727, 11457, 11725, -1, 16698, 16669, 16697, -1, 11725, 11457, 11723, -1, 11723, 11457, 11721, -1, 16699, 11444, 11443, -1, 16692, 11455, 16700, -1, 16667, 16701, 16681, -1, 11457, 11455, 16692, -1, 16681, 16701, 16685, -1, 16699, 11448, 11444, -1, 16667, 16702, 16701, -1, 16667, 16703, 16702, -1, 11453, 11450, 11455, -1, 16700, 11450, 16699, -1, 11455, 11450, 16700, -1, 16699, 11450, 11448, -1, 16667, 16704, 16703, -1, 11453, 11451, 11450, -1, 16667, 16705, 16704, -1, 16667, 16673, 16705, -1, 16706, 16707, 16691, -1, 16707, 16708, 16691, -1, 16708, 16709, 16691, -1, 16709, 16710, 16691, -1, 16710, 16711, 16691, -1, 16712, 16693, 16713, -1, 16713, 16693, 16711, -1, 16711, 16693, 16691, -1, 16712, 16714, 16693, -1, 16714, 16715, 16693, -1, 16716, 16717, 16701, -1, 16717, 16718, 16701, -1, 16718, 16719, 16701, -1, 16719, 16720, 16701, -1, 16720, 16721, 16701, -1, 16722, 16685, 16723, -1, 16723, 16685, 16721, -1, 16721, 16685, 16701, -1, 16722, 16724, 16685, -1, 16724, 16725, 16685, -1, 11730, 16726, 11731, -1, 16726, 16727, 11731, -1, 16727, 16728, 11731, -1, 16728, 16729, 11731, -1, 16729, 16730, 11731, -1, 16731, 16678, 16732, -1, 16732, 16678, 16730, -1, 16730, 16678, 11731, -1, 16731, 16733, 16678, -1, 16733, 16734, 16678, -1, 11849, 11478, 16735, -1, 16736, 16735, 16737, -1, 16736, 11849, 16735, -1, 16738, 16737, 16739, -1, 16738, 16736, 16737, -1, 16740, 16738, 16739, -1, 16741, 16742, 16743, -1, 11470, 16744, 16741, -1, 11470, 16741, 16743, -1, 16745, 16744, 11470, -1, 11837, 16745, 11470, -1, 16746, 14199, 14196, -1, 16746, 14196, 16747, -1, 16748, 16747, 16749, -1, 16748, 16746, 16747, -1, 16750, 16749, 16751, -1, 16750, 16748, 16749, -1, 16752, 16751, 16753, -1, 16752, 16750, 16751, -1, 16754, 16753, 16755, -1, 16754, 16752, 16753, -1, 16756, 16757, 16758, -1, 16756, 16755, 16757, -1, 16756, 16754, 16755, -1, 16759, 16758, 16760, -1, 16759, 16756, 16758, -1, 16761, 16760, 16762, -1, 16761, 16759, 16760, -1, 16763, 16762, 16764, -1, 16763, 16761, 16762, -1, 16765, 16764, 16766, -1, 16765, 16763, 16764, -1, 16767, 16765, 16766, -1, 16768, 16766, 16769, -1, 16768, 16767, 16766, -1, 16770, 16769, 14188, -1, 16770, 16768, 16769, -1, 14187, 16770, 14188, -1, 16771, 16740, 16739, -1, 16772, 16771, 16739, -1, 16773, 16774, 16772, -1, 16773, 16772, 16739, -1, 16775, 16774, 16773, -1, 11499, 11471, 11483, -1, 11471, 11484, 11483, -1, 11471, 11487, 11484, -1, 11471, 11488, 11487, -1, 11471, 11492, 11488, -1, 11471, 11495, 11492, -1, 11471, 11496, 11495, -1, 11477, 16776, 16777, -1, 16777, 16776, 16778, -1, 11496, 16776, 11475, -1, 11475, 16776, 11476, -1, 11476, 16776, 11477, -1, 11471, 16776, 11496, -1, 16779, 16780, 11471, -1, 11471, 16780, 16776, -1, 11835, 11465, 16781, -1, 16782, 16781, 16783, -1, 16782, 11835, 16781, -1, 16784, 16783, 16785, -1, 16784, 16782, 16783, -1, 16786, 16785, 16787, -1, 16786, 16784, 16785, -1, 16788, 16787, 16789, -1, 16788, 16786, 16787, -1, 16790, 16789, 16791, -1, 16790, 16788, 16789, -1, 16792, 16791, 16793, -1, 16792, 16790, 16791, -1, 16794, 16793, 16795, -1, 16794, 16792, 16793, -1, 16796, 16795, 16797, -1, 16796, 16794, 16795, -1, 16798, 16797, 16799, -1, 16798, 16796, 16797, -1, 16800, 16799, 16801, -1, 16800, 16798, 16799, -1, 16802, 16800, 16801, -1, 16803, 16804, 16805, -1, 11459, 16806, 16803, -1, 11459, 16803, 16805, -1, 16807, 16806, 11459, -1, 11833, 16807, 11459, -1, 16808, 14005, 14002, -1, 16808, 14002, 16809, -1, 16810, 16809, 16811, -1, 16810, 16808, 16809, -1, 16812, 16811, 16813, -1, 16812, 16810, 16811, -1, 16814, 16813, 16815, -1, 16814, 16812, 16813, -1, 16816, 16815, 16817, -1, 16816, 16814, 16815, -1, 16818, 16819, 16820, -1, 16818, 16817, 16819, -1, 16818, 16816, 16817, -1, 16821, 16820, 16822, -1, 16821, 16818, 16820, -1, 16823, 16822, 16824, -1, 16823, 16821, 16822, -1, 16825, 16824, 16826, -1, 16825, 16823, 16824, -1, 16827, 16826, 16828, -1, 16827, 16825, 16826, -1, 16829, 16827, 16828, -1, 16830, 16828, 16831, -1, 16830, 16829, 16828, -1, 16832, 16831, 13994, -1, 16832, 16830, 16831, -1, 13993, 16832, 13994, -1, 16833, 16802, 16801, -1, 16834, 16833, 16801, -1, 16835, 16836, 16834, -1, 16835, 16834, 16801, -1, 16837, 16836, 16835, -1, 16838, 16839, 16840, -1, 16839, 11460, 16840, -1, 16841, 11466, 16842, -1, 16842, 11466, 16843, -1, 16843, 11466, 16844, -1, 16844, 11466, 16839, -1, 11460, 11466, 11461, -1, 11461, 11466, 11463, -1, 16839, 11466, 11460, -1, 16841, 16845, 11466, -1, 16845, 16846, 11466, -1, 11466, 16847, 16848, -1, 16846, 16849, 11466, -1, 11466, 16850, 16847, -1, 16849, 16850, 11466, -1, 16851, 16852, 16853, -1, 16851, 16854, 16855, -1, 16851, 16853, 16854, -1, 16856, 16855, 16857, -1, 16856, 16851, 16855, -1, 16858, 16857, 16859, -1, 16858, 16856, 16857, -1, 16860, 16859, 16861, -1, 16860, 16858, 16859, -1, 16862, 16861, 16863, -1, 16862, 16860, 16861, -1, 16864, 16863, 16865, -1, 16864, 16862, 16863, -1, 16866, 16865, 16867, -1, 16866, 16864, 16865, -1, 16868, 16867, 16869, -1, 16868, 16866, 16867, -1, 16870, 16869, 16871, -1, 16870, 16868, 16869, -1, 16872, 16871, 16873, -1, 16872, 16870, 16871, -1, 16874, 16873, 16875, -1, 16874, 16872, 16873, -1, 16876, 16874, 16875, -1, 16877, 16875, 16878, -1, 16877, 16876, 16875, -1, 16879, 16877, 16878, -1, 16880, 16881, 16882, -1, 16853, 16883, 16880, -1, 16853, 16880, 16882, -1, 16884, 16883, 16853, -1, 16852, 16884, 16853, -1, 16885, 11831, 11520, -1, 16885, 16886, 16887, -1, 16885, 11520, 16886, -1, 16888, 16887, 16889, -1, 16888, 16885, 16887, -1, 16890, 16889, 16891, -1, 16890, 16888, 16889, -1, 16892, 16891, 16893, -1, 16892, 16890, 16891, -1, 16894, 16892, 16893, -1, 16895, 16893, 16896, -1, 16895, 16894, 16893, -1, 16897, 16896, 14226, -1, 16897, 16895, 16896, -1, 14225, 16897, 14226, -1, 16898, 16879, 16878, -1, 16899, 16898, 16878, -1, 16900, 16901, 16899, -1, 16900, 16899, 16878, -1, 16902, 16901, 16900, -1, 16903, 16904, 16905, -1, 16905, 16904, 16906, -1, 16906, 16904, 16907, -1, 16907, 16904, 16908, -1, 16908, 16904, 16909, -1, 16903, 16910, 16904, -1, 16910, 16911, 16904, -1, 16911, 16912, 16904, -1, 16912, 16913, 16904, -1, 16913, 16914, 16904, -1, 16915, 16916, 16914, -1, 16914, 16916, 16904, -1, 16916, 16917, 16904, -1, 16916, 16918, 16917, -1, 16919, 16920, 16921, -1, 16922, 16920, 16919, -1, 16923, 16924, 16925, -1, 16925, 16924, 16926, -1, 16926, 16924, 16927, -1, 16928, 16924, 16929, -1, 16927, 16924, 16930, -1, 16930, 16924, 16931, -1, 16931, 16924, 16932, -1, 16932, 16924, 16933, -1, 16933, 16924, 16934, -1, 16934, 16924, 16935, -1, 16935, 16924, 16936, -1, 16936, 16924, 16928, -1, 16937, 16924, 16923, -1, 16921, 16938, 16939, -1, 16939, 16938, 16940, -1, 16941, 16942, 16937, -1, 16922, 16942, 16920, -1, 16937, 16942, 16924, -1, 16924, 16942, 16929, -1, 16929, 16942, 16922, -1, 16940, 16943, 16944, -1, 16920, 16945, 16921, -1, 16921, 16945, 16938, -1, 16938, 16946, 16940, -1, 16940, 16946, 16943, -1, 16947, 16948, 16941, -1, 16941, 16948, 16942, -1, 16945, 16948, 16947, -1, 16942, 16948, 16920, -1, 16920, 16948, 16945, -1, 16943, 16949, 16944, -1, 16944, 16949, 16950, -1, 16951, 16952, 16947, -1, 16947, 16952, 16945, -1, 16945, 16952, 16938, -1, 16938, 16952, 16946, -1, 16946, 16953, 16943, -1, 16943, 16953, 16949, -1, 16949, 16954, 16950, -1, 16955, 16956, 16951, -1, 16951, 16956, 16952, -1, 16952, 16956, 16946, -1, 16946, 16956, 16953, -1, 16955, 16957, 16956, -1, 16953, 16957, 16949, -1, 16949, 16957, 16954, -1, 16956, 16957, 16953, -1, 16958, 16959, 16955, -1, 16955, 16959, 16957, -1, 16954, 16959, 16950, -1, 16957, 16959, 16954, -1, 16959, 16960, 16950, -1, 16958, 16960, 16959, -1, 16950, 16960, 16961, -1, 16962, 16963, 16958, -1, 16960, 16963, 16961, -1, 16958, 16963, 16960, -1, 16961, 16963, 16962, -1, 16961, 16964, 11672, -1, 16965, 16964, 16961, -1, 11749, 16966, 11751, -1, 11751, 16966, 11752, -1, 11752, 16966, 16965, -1, 16965, 16966, 16964, -1, 16964, 16966, 11672, -1, 11672, 16966, 11749, -1, 16967, 16968, 16969, -1, 16968, 16970, 16969, -1, 16971, 16972, 16973, -1, 16972, 16974, 16973, -1, 16972, 16975, 16974, -1, 16975, 16976, 16974, -1, 16976, 16977, 16974, -1, 16976, 16978, 16977, -1, 16978, 16979, 16977, -1, 16979, 16980, 16977, -1, 16979, 16981, 16980, -1, 16981, 16982, 16980, -1, 16982, 16983, 16980, -1, 16982, 16984, 16983, -1, 16984, 16985, 16983, -1, 16986, 16985, 16984, -1, 16986, 16987, 16985, -1, 16987, 16988, 16985, -1, 16989, 16988, 16987, -1, 16989, 16990, 16988, -1, 16990, 16991, 16988, -1, 16990, 16992, 16991, -1, 16992, 16993, 16991, -1, 16992, 16994, 16993, -1, 16995, 16937, 16923, -1, 16962, 16965, 16961, -1, 16996, 16997, 11808, -1, 11805, 16997, 11635, -1, 11807, 16997, 11805, -1, 11808, 16997, 11807, -1, 16998, 16999, 16996, -1, 11635, 16999, 17000, -1, 16997, 16999, 11635, -1, 16996, 16999, 16997, -1, 17001, 17002, 16998, -1, 16999, 17002, 17000, -1, 16998, 17002, 16999, -1, 17001, 17003, 17002, -1, 17002, 17003, 17000, -1, 17001, 17004, 17003, -1, 17003, 17004, 17000, -1, 17005, 17004, 17001, -1, 17000, 17004, 17006, -1, 17004, 17007, 17006, -1, 17005, 17007, 17004, -1, 17005, 17008, 17007, -1, 17009, 17008, 17005, -1, 17007, 17010, 17006, -1, 17009, 17011, 17008, -1, 17008, 17011, 17007, -1, 17012, 17011, 17009, -1, 17007, 17011, 17010, -1, 17006, 17013, 17014, -1, 17010, 17013, 17006, -1, 17010, 17015, 17013, -1, 17012, 17015, 17011, -1, 17011, 17015, 17010, -1, 17013, 17016, 17014, -1, 17012, 17017, 17015, -1, 17018, 17017, 17012, -1, 17015, 17019, 17013, -1, 17013, 17019, 17016, -1, 17016, 17020, 17014, -1, 17017, 17021, 17015, -1, 17018, 17021, 17017, -1, 17015, 17021, 17019, -1, 17022, 17021, 17018, -1, 17016, 17023, 17020, -1, 17019, 17023, 17016, -1, 17020, 17024, 17014, -1, 17014, 17024, 17025, -1, 17019, 17026, 17023, -1, 17021, 17026, 17019, -1, 17020, 17027, 17024, -1, 17023, 17027, 17020, -1, 17022, 17028, 17021, -1, 17029, 17028, 17022, -1, 17021, 17028, 17026, -1, 17024, 17030, 17025, -1, 17026, 17031, 17023, -1, 17023, 17031, 17027, -1, 17027, 17032, 17024, -1, 17024, 17032, 17030, -1, 17029, 17033, 17028, -1, 17028, 17033, 17026, -1, 17026, 17033, 17031, -1, 16969, 17033, 17029, -1, 17030, 17034, 17025, -1, 17027, 17035, 17032, -1, 17031, 17035, 17027, -1, 17030, 17036, 17034, -1, 17032, 17036, 17030, -1, 17031, 17037, 17035, -1, 17033, 17037, 17031, -1, 17034, 17038, 17025, -1, 17025, 17038, 17039, -1, 17032, 17040, 17036, -1, 17035, 17040, 17032, -1, 17033, 17041, 17037, -1, 16969, 17041, 17033, -1, 16970, 17041, 16969, -1, 17042, 17041, 17043, -1, 17043, 17041, 17044, -1, 17044, 17041, 17045, -1, 17045, 17041, 17046, -1, 17046, 17041, 17047, -1, 17037, 17041, 17042, -1, 17047, 17041, 17048, -1, 17048, 17041, 17049, -1, 17049, 17041, 17050, -1, 17050, 17041, 17051, -1, 17051, 17041, 16970, -1, 17036, 17052, 17034, -1, 17034, 17052, 17038, -1, 17035, 17053, 17040, -1, 17037, 17053, 17035, -1, 17054, 17053, 17042, -1, 17042, 17053, 17037, -1, 17038, 17055, 17039, -1, 17040, 17056, 17036, -1, 17036, 17056, 17052, -1, 17052, 17057, 17038, -1, 17038, 17057, 17055, -1, 17053, 17058, 17040, -1, 17054, 17058, 17053, -1, 17059, 17058, 17060, -1, 17060, 17058, 17054, -1, 17040, 17058, 17056, -1, 17056, 17058, 17059, -1, 17055, 17061, 17039, -1, 17057, 17062, 17063, -1, 17052, 17062, 17057, -1, 17063, 17062, 17059, -1, 17056, 17062, 17052, -1, 17059, 17062, 17056, -1, 17057, 17064, 17055, -1, 17063, 17064, 17057, -1, 17055, 17064, 17061, -1, 17065, 17064, 17063, -1, 17061, 17066, 17039, -1, 17064, 17067, 17061, -1, 17065, 17067, 17064, -1, 17068, 17067, 17065, -1, 17061, 17067, 17066, -1, 17066, 17069, 17039, -1, 17039, 17069, 17070, -1, 17066, 17071, 17069, -1, 17067, 17071, 17066, -1, 17068, 17071, 17067, -1, 17072, 17071, 17068, -1, 17069, 17073, 17070, -1, 17072, 17073, 17071, -1, 17071, 17073, 17069, -1, 17073, 17074, 17070, -1, 17072, 17074, 17073, -1, 16971, 17074, 17072, -1, 16971, 17075, 17074, -1, 17070, 17075, 16973, -1, 17074, 17075, 17070, -1, 16973, 17075, 16971, -1, 16994, 17076, 16993, -1, 17077, 17078, 16994, -1, 16994, 17078, 17076, -1, 17076, 17078, 16993, -1, 16993, 17078, 17079, -1, 17077, 17080, 17078, -1, 17078, 17080, 17079, -1, 17081, 17082, 17077, -1, 17077, 17082, 17080, -1, 17080, 17082, 17079, -1, 17083, 17084, 17081, -1, 17081, 17084, 17082, -1, 17082, 17084, 17079, -1, 17083, 17085, 17084, -1, 17084, 17085, 17079, -1, 17079, 17085, 17086, -1, 17087, 17088, 17083, -1, 17083, 17088, 17085, -1, 17085, 17089, 17086, -1, 17090, 17091, 17087, -1, 17087, 17091, 17088, -1, 17088, 17091, 17085, -1, 17085, 17091, 17089, -1, 17089, 17092, 17086, -1, 17091, 17092, 17089, -1, 17092, 17093, 17086, -1, 17086, 17093, 17094, -1, 17095, 17096, 17090, -1, 17090, 17096, 17091, -1, 17091, 17096, 17092, -1, 17092, 17097, 17093, -1, 17093, 17098, 17094, -1, 17099, 17100, 17095, -1, 17095, 17100, 17096, -1, 17096, 17100, 17092, -1, 17092, 17100, 17097, -1, 17097, 17101, 17093, -1, 17093, 17101, 17098, -1, 17098, 17102, 17094, -1, 17099, 17103, 17100, -1, 17097, 17103, 17101, -1, 17100, 17103, 17097, -1, 17101, 16919, 17098, -1, 17098, 16919, 17102, -1, 16928, 17104, 17099, -1, 17099, 17104, 17103, -1, 17102, 16939, 17094, -1, 17094, 16939, 16944, -1, 17103, 16922, 17101, -1, 17101, 16922, 16919, -1, 17102, 16921, 16939, -1, 16919, 16921, 17102, -1, 17104, 16929, 17103, -1, 17103, 16929, 16922, -1, 16928, 16929, 17104, -1, 16939, 16940, 16944, -1, 16715, 17105, 16693, -1, 16693, 17105, 16695, -1, 16695, 17106, 16694, -1, 17105, 17106, 16695, -1, 16694, 11716, 11718, -1, 17106, 11716, 16694, -1, 16734, 17107, 16678, -1, 16678, 17107, 16677, -1, 16677, 17108, 16675, -1, 17107, 17108, 16677, -1, 17108, 17109, 16675, -1, 16675, 17110, 16674, -1, 17109, 17110, 16675, -1, 16674, 17111, 16673, -1, 17110, 17111, 16674, -1, 17111, 17112, 16673, -1, 16673, 17113, 16705, -1, 17112, 17113, 16673, -1, 16705, 17114, 16704, -1, 17113, 17114, 16705, -1, 16704, 17115, 16703, -1, 17114, 17115, 16704, -1, 16703, 17116, 16702, -1, 17115, 17116, 16703, -1, 16702, 17117, 16701, -1, 17116, 17117, 16702, -1, 17117, 16716, 16701, -1, 16725, 17118, 16685, -1, 16685, 17118, 16683, -1, 16683, 17119, 16684, -1, 17118, 17119, 16683, -1, 17119, 17120, 16684, -1, 16684, 17121, 16686, -1, 17120, 17121, 16684, -1, 16686, 17122, 16687, -1, 17121, 17122, 16686, -1, 17122, 17123, 16687, -1, 16687, 17124, 16688, -1, 17123, 17124, 16687, -1, 16688, 17125, 16689, -1, 17124, 17125, 16688, -1, 16689, 17126, 16690, -1, 17125, 17126, 16689, -1, 16690, 17127, 16696, -1, 17126, 17127, 16690, -1, 16696, 17128, 16691, -1, 17127, 17128, 16696, -1, 17128, 16706, 16691, -1, 13986, 13985, 17129, -1, 17130, 17129, 17131, -1, 17130, 13986, 17129, -1, 17132, 17131, 17133, -1, 17132, 17130, 17131, -1, 17134, 17133, 17135, -1, 17134, 17132, 17133, -1, 17136, 17134, 17135, -1, 14218, 14217, 17137, -1, 17138, 17137, 17139, -1, 17138, 14218, 17137, -1, 17140, 17139, 17141, -1, 17140, 17138, 17139, -1, 17142, 17141, 17143, -1, 17142, 17140, 17141, -1, 17144, 17142, 17143, -1, 11715, 11714, 17145, -1, 17146, 17145, 17147, -1, 17146, 11715, 17145, -1, 17148, 17147, 17149, -1, 17148, 17146, 17147, -1, 17150, 17148, 17149, -1, 16742, 14102, 14104, -1, 14095, 16741, 14091, -1, 16741, 14089, 14091, -1, 14089, 16744, 14086, -1, 16741, 16744, 14089, -1, 16744, 14080, 14086, -1, 16744, 14075, 14080, -1, 16744, 16745, 14075, -1, 16745, 14048, 14075, -1, 16742, 16741, 14095, -1, 16742, 14095, 14102, -1, 11837, 14048, 16745, -1, 11837, 14045, 14048, -1, 11837, 11836, 14045, -1, 11836, 14037, 14045, -1, 11836, 11838, 14037, -1, 11838, 14029, 14037, -1, 11838, 11839, 14029, -1, 11840, 14028, 11839, -1, 11839, 14028, 14029, -1, 11841, 14027, 11840, -1, 11840, 14027, 14028, -1, 11842, 14070, 11841, -1, 11841, 14070, 14027, -1, 11842, 11843, 14070, -1, 11843, 14068, 14070, -1, 11843, 11844, 14068, -1, 11844, 14065, 14068, -1, 11844, 11845, 14065, -1, 11846, 14059, 11845, -1, 11845, 14059, 14065, -1, 11847, 14058, 11846, -1, 11846, 14058, 14059, -1, 11848, 14055, 11847, -1, 11847, 14055, 14058, -1, 11848, 11849, 14055, -1, 11849, 14054, 14055, -1, 11849, 16736, 14054, -1, 16738, 14063, 16736, -1, 16736, 14063, 14054, -1, 16771, 14062, 16740, -1, 16740, 14062, 16738, -1, 16738, 14062, 14063, -1, 14199, 13547, 14198, -1, 16746, 13551, 14199, -1, 14199, 13551, 13547, -1, 16746, 13588, 13551, -1, 16746, 16748, 13588, -1, 16748, 13535, 13588, -1, 16748, 16750, 13535, -1, 16750, 13533, 13535, -1, 16750, 16752, 13533, -1, 16752, 13550, 13533, -1, 16752, 16754, 13550, -1, 16754, 13543, 13550, -1, 16754, 16756, 13543, -1, 16756, 13542, 13543, -1, 16756, 16759, 13542, -1, 16759, 13541, 13542, -1, 16759, 16761, 13541, -1, 16761, 13540, 13541, -1, 16761, 16763, 13540, -1, 16763, 13555, 13540, -1, 16763, 14158, 13555, -1, 16763, 16765, 14158, -1, 16765, 14157, 14158, -1, 16765, 16767, 14157, -1, 16767, 14175, 14157, -1, 16767, 16768, 14175, -1, 16768, 14168, 14175, -1, 16768, 16770, 14168, -1, 14186, 14161, 14187, -1, 14187, 14161, 16770, -1, 16770, 14161, 14168, -1, 16771, 14067, 14062, -1, 14041, 16772, 14073, -1, 16772, 14078, 14073, -1, 14078, 16774, 14082, -1, 16772, 16774, 14078, -1, 16774, 14083, 14082, -1, 16774, 14098, 14083, -1, 16774, 16775, 14098, -1, 16775, 14100, 14098, -1, 16771, 16772, 14041, -1, 16771, 14041, 14067, -1, 16881, 13800, 13802, -1, 13792, 16880, 13787, -1, 16880, 13784, 13787, -1, 13784, 16883, 13781, -1, 16880, 16883, 13784, -1, 16883, 13774, 13781, -1, 16883, 13769, 13774, -1, 16883, 16884, 13769, -1, 16884, 13741, 13769, -1, 16881, 16880, 13792, -1, 16881, 13792, 13800, -1, 16852, 13741, 16884, -1, 16852, 13736, 13741, -1, 16852, 16851, 13736, -1, 16851, 13727, 13736, -1, 16851, 16856, 13727, -1, 16856, 13718, 13727, -1, 16856, 16858, 13718, -1, 16858, 13717, 13718, -1, 16858, 16860, 13717, -1, 16860, 13715, 13717, -1, 16860, 16862, 13715, -1, 16862, 13764, 13715, -1, 16862, 16864, 13764, -1, 16864, 13762, 13764, -1, 16864, 16866, 13762, -1, 16866, 13759, 13762, -1, 16866, 16868, 13759, -1, 16868, 13752, 13759, -1, 16868, 16870, 13752, -1, 16870, 13751, 13752, -1, 16870, 16872, 13751, -1, 16872, 13748, 13751, -1, 16872, 16874, 13748, -1, 16874, 13747, 13748, -1, 16874, 16876, 13747, -1, 16876, 13756, 13747, -1, 16876, 16877, 13756, -1, 16898, 13755, 16879, -1, 16879, 13755, 16877, -1, 16877, 13755, 13756, -1, 11825, 14262, 14235, -1, 11825, 16540, 14262, -1, 11825, 11824, 16540, -1, 11824, 16538, 16540, -1, 11824, 11826, 16538, -1, 11826, 16548, 16538, -1, 11826, 11827, 16548, -1, 11827, 16546, 16548, -1, 11827, 11828, 16546, -1, 11828, 16551, 16546, -1, 11828, 11829, 16551, -1, 11829, 16555, 16551, -1, 11829, 11830, 16555, -1, 11830, 16553, 16555, -1, 11830, 11831, 16553, -1, 11831, 16578, 16553, -1, 11831, 16885, 16578, -1, 16885, 16545, 16578, -1, 16885, 16888, 16545, -1, 16888, 16544, 16545, -1, 16888, 16890, 16544, -1, 16892, 16543, 16890, -1, 16890, 16543, 16544, -1, 16894, 16541, 16892, -1, 16892, 16541, 16543, -1, 16894, 16895, 16541, -1, 16895, 16589, 16541, -1, 16895, 16897, 16589, -1, 14224, 14246, 14225, -1, 14225, 14246, 16897, -1, 16897, 14246, 16589, -1, 16898, 13761, 13755, -1, 13731, 16899, 13767, -1, 16899, 13772, 13767, -1, 13772, 16901, 13776, -1, 16899, 16901, 13772, -1, 16901, 13777, 13776, -1, 16901, 13795, 13777, -1, 16901, 16902, 13795, -1, 16902, 13797, 13795, -1, 16898, 16899, 13731, -1, 16898, 13731, 13761, -1, 16804, 13684, 13689, -1, 13675, 16803, 13670, -1, 16803, 13668, 13670, -1, 13668, 16806, 13658, -1, 16803, 16806, 13668, -1, 16806, 13705, 13658, -1, 16806, 13702, 13705, -1, 16806, 16807, 13702, -1, 16807, 13700, 13702, -1, 16804, 16803, 13675, -1, 16804, 13675, 13684, -1, 11833, 13700, 16807, -1, 11832, 13696, 11833, -1, 11833, 13696, 13700, -1, 11832, 13694, 13696, -1, 11832, 11834, 13694, -1, 11835, 13693, 11834, -1, 11834, 13693, 13694, -1, 16782, 13664, 11835, -1, 11835, 13664, 13693, -1, 16782, 13662, 13664, -1, 16782, 16784, 13662, -1, 16784, 13881, 13662, -1, 16784, 16786, 13881, -1, 16786, 13880, 13881, -1, 16786, 16788, 13880, -1, 16788, 13879, 13880, -1, 16788, 16790, 13879, -1, 16790, 13877, 13879, -1, 16790, 16792, 13877, -1, 16792, 13873, 13877, -1, 16792, 16794, 13873, -1, 16794, 13866, 13873, -1, 16794, 16796, 13866, -1, 16796, 13864, 13866, -1, 16796, 16798, 13864, -1, 16798, 13875, 13864, -1, 16798, 16800, 13875, -1, 16800, 13871, 13875, -1, 16800, 16802, 13871, -1, 16833, 13869, 16802, -1, 16802, 13869, 13871, -1, 14005, 13913, 14004, -1, 14005, 13916, 13913, -1, 14005, 16808, 13916, -1, 16808, 13915, 13916, -1, 16808, 16810, 13915, -1, 16810, 13924, 13915, -1, 16810, 16812, 13924, -1, 16812, 13922, 13924, -1, 16812, 16814, 13922, -1, 16814, 13927, 13922, -1, 16814, 16816, 13927, -1, 16816, 13932, 13927, -1, 16816, 16818, 13932, -1, 16818, 13930, 13932, -1, 16818, 16821, 13930, -1, 16821, 13958, 13930, -1, 16821, 16823, 13958, -1, 16823, 13921, 13958, -1, 16823, 16825, 13921, -1, 16825, 13920, 13921, -1, 16827, 13919, 16825, -1, 16825, 13919, 13920, -1, 16827, 16829, 13919, -1, 16829, 13918, 13919, -1, 16829, 16830, 13918, -1, 16830, 13975, 13918, -1, 16830, 16832, 13975, -1, 13992, 13974, 13993, -1, 13993, 13974, 16832, -1, 16832, 13974, 13975, -1, 16833, 13626, 13869, -1, 16833, 13624, 13626, -1, 16834, 13632, 13630, -1, 16834, 13640, 13632, -1, 13640, 16836, 13644, -1, 16834, 16836, 13640, -1, 16836, 13650, 13644, -1, 16836, 13648, 13650, -1, 16836, 16837, 13648, -1, 16837, 13655, 13648, -1, 16833, 16834, 13630, -1, 16833, 13630, 13624, -1, 16649, 14093, 14097, -1, 16649, 14084, 14093, -1, 14084, 16648, 14077, -1, 16648, 14042, 14077, -1, 16648, 14040, 14042, -1, 16648, 14061, 14040, -1, 14061, 16651, 14053, -1, 16651, 14036, 14053, -1, 16651, 14032, 14036, -1, 16651, 14030, 14032, -1, 14030, 16652, 14024, -1, 16651, 16652, 14030, -1, 16652, 14112, 14024, -1, 16652, 14111, 14112, -1, 16652, 16653, 14111, -1, 16653, 14109, 14111, -1, 16653, 14047, 14109, -1, 16653, 14127, 14047, -1, 14127, 14046, 14047, -1, 16649, 16648, 14084, -1, 16648, 16651, 14061, -1, 13579, 11709, 14180, -1, 13580, 11710, 13579, -1, 13579, 11710, 11709, -1, 13580, 11712, 11710, -1, 13580, 13582, 11712, -1, 13582, 11714, 11712, -1, 13584, 17145, 13582, -1, 13582, 17145, 11714, -1, 13584, 17147, 17145, -1, 13584, 13585, 17147, -1, 13585, 17149, 17147, -1, 13946, 13985, 13984, -1, 13947, 17129, 13946, -1, 13946, 17129, 13985, -1, 13947, 17131, 17129, -1, 13947, 13952, 17131, -1, 13959, 17133, 13952, -1, 13952, 17133, 17131, -1, 13960, 17135, 13959, -1, 13959, 17135, 17133, -1, 16655, 13790, 13794, -1, 16655, 13778, 13790, -1, 13778, 16654, 13771, -1, 16654, 13732, 13771, -1, 16654, 13730, 13732, -1, 16654, 13754, 13730, -1, 13754, 16657, 13746, -1, 16657, 13726, 13746, -1, 16657, 13721, 13726, -1, 16657, 13719, 13721, -1, 13719, 16658, 13815, -1, 16657, 16658, 13719, -1, 16658, 13812, 13815, -1, 16658, 13811, 13812, -1, 16658, 16659, 13811, -1, 16659, 13808, 13811, -1, 16659, 13739, 13808, -1, 16659, 13828, 13739, -1, 13828, 13737, 13739, -1, 16655, 16654, 13778, -1, 16654, 16657, 13754, -1, 16643, 13651, 13653, -1, 16643, 13643, 13651, -1, 13636, 16642, 13634, -1, 13639, 16642, 13636, -1, 16642, 13629, 13634, -1, 16642, 13623, 13629, -1, 16642, 13622, 13623, -1, 13862, 16645, 13857, -1, 13622, 16645, 13862, -1, 16645, 13853, 13857, -1, 16645, 13849, 13853, -1, 13849, 16646, 13842, -1, 16645, 16646, 13849, -1, 16646, 13840, 13842, -1, 16646, 16647, 13840, -1, 16647, 13832, 13840, -1, 16647, 13892, 13832, -1, 13892, 13831, 13832, -1, 16643, 16642, 13639, -1, 16643, 13639, 13643, -1, 16642, 16645, 13622, -1, 14264, 14217, 14216, -1, 16571, 17137, 14264, -1, 14264, 17137, 14217, -1, 16571, 17139, 17137, -1, 16571, 16574, 17139, -1, 16580, 17141, 16574, -1, 16574, 17141, 17139, -1, 16581, 17143, 16580, -1, 16580, 17143, 17141, -1, 11789, 11768, 16707, -1, 11768, 11757, 16707, -1, 11747, 16708, 11757, -1, 11757, 16708, 16707, -1, 11747, 11740, 16708, -1, 11740, 11734, 16708, -1, 11821, 16709, 11734, -1, 11816, 16709, 11821, -1, 11734, 16709, 16708, -1, 11816, 11812, 16709, -1, 11812, 11744, 16709, -1, 11742, 16710, 11744, -1, 11771, 16710, 11742, -1, 11744, 16710, 16709, -1, 11771, 11767, 16710, -1, 11767, 11766, 16710, -1, 11766, 11764, 16710, -1, 11761, 16711, 11764, -1, 11760, 16711, 11761, -1, 11756, 16711, 11760, -1, 11764, 16711, 16710, -1, 11756, 11755, 16711, -1, 11755, 11750, 16711, -1, 16965, 16713, 11752, -1, 11752, 16713, 11750, -1, 11750, 16713, 16711, -1, 16965, 16962, 16713, -1, 16962, 16958, 16713, -1, 16958, 16712, 16713, -1, 16955, 16712, 16958, -1, 16951, 16712, 16955, -1, 16951, 16947, 16712, -1, 16947, 16941, 16712, -1, 16941, 16714, 16712, -1, 16937, 16714, 16941, -1, 16937, 16715, 16714, -1, 16995, 17105, 16937, -1, 16937, 17105, 16715, -1, 16923, 17106, 16995, -1, 16995, 17106, 17105, -1, 16925, 11716, 16923, -1, 16923, 11716, 17106, -1, 16926, 11717, 16925, -1, 16925, 11717, 11716, -1, 16927, 11720, 16926, -1, 16926, 11720, 11717, -1, 16930, 11722, 16927, -1, 16927, 11722, 11720, -1, 16931, 11724, 16930, -1, 16932, 11724, 16931, -1, 16930, 11724, 11722, -1, 16933, 11726, 16932, -1, 16932, 11726, 11724, -1, 16934, 11728, 16933, -1, 16935, 11728, 16934, -1, 16933, 11728, 11726, -1, 16936, 11730, 16935, -1, 16935, 11730, 11728, -1, 16936, 16726, 11730, -1, 11776, 16725, 16724, -1, 11777, 17118, 11776, -1, 11776, 17118, 16725, -1, 11779, 17119, 11777, -1, 11777, 17119, 17118, -1, 11779, 17120, 17119, -1, 11780, 17121, 11779, -1, 11779, 17121, 17120, -1, 11781, 17122, 11780, -1, 11780, 17122, 17121, -1, 11782, 17123, 11781, -1, 11781, 17123, 17122, -1, 11784, 17124, 11782, -1, 11782, 17124, 17123, -1, 11785, 17125, 11784, -1, 11784, 17125, 17124, -1, 11786, 17126, 11785, -1, 11785, 17126, 17125, -1, 11787, 17127, 11786, -1, 11786, 17127, 17126, -1, 11788, 17128, 11787, -1, 11820, 17128, 11788, -1, 11787, 17128, 17127, -1, 11789, 16706, 11820, -1, 11820, 16706, 17128, -1, 11789, 16707, 16706, -1, 17054, 16733, 16731, -1, 17042, 16733, 17054, -1, 17043, 16733, 17042, -1, 16936, 16928, 16726, -1, 16928, 17099, 16726, -1, 17095, 16727, 17099, -1, 17099, 16727, 16726, -1, 17095, 17090, 16727, -1, 17090, 17087, 16727, -1, 17087, 17083, 16727, -1, 17081, 16728, 17083, -1, 17083, 16728, 16727, -1, 17081, 17077, 16728, -1, 17077, 16994, 16728, -1, 16992, 16729, 16994, -1, 16990, 16729, 16992, -1, 16994, 16729, 16728, -1, 16990, 16989, 16729, -1, 16989, 16987, 16729, -1, 16987, 16986, 16729, -1, 16986, 16984, 16729, -1, 16982, 16730, 16984, -1, 16981, 16730, 16982, -1, 16979, 16730, 16981, -1, 16978, 16730, 16979, -1, 16984, 16730, 16729, -1, 16978, 16976, 16730, -1, 16976, 16975, 16730, -1, 16972, 16732, 16975, -1, 16971, 16732, 16972, -1, 16975, 16732, 16730, -1, 16971, 17072, 16732, -1, 17072, 17068, 16732, -1, 17068, 16731, 16732, -1, 17065, 16731, 17068, -1, 17063, 16731, 17065, -1, 17063, 17059, 16731, -1, 17059, 17060, 16731, -1, 17060, 17054, 16731, -1, 16969, 17029, 16717, -1, 17022, 16718, 17029, -1, 17029, 16718, 16717, -1, 17022, 17018, 16718, -1, 17018, 17012, 16718, -1, 17012, 17009, 16718, -1, 17005, 16719, 17009, -1, 17001, 16719, 17005, -1, 17009, 16719, 16718, -1, 17001, 16998, 16719, -1, 16998, 16996, 16719, -1, 16996, 11808, 16719, -1, 11801, 16720, 11808, -1, 11808, 16720, 16719, -1, 11801, 11798, 16720, -1, 11798, 11794, 16720, -1, 11794, 11793, 16720, -1, 11790, 16721, 11793, -1, 11783, 16721, 11790, -1, 11793, 16721, 16720, -1, 11783, 11778, 16721, -1, 11778, 11774, 16721, -1, 11737, 16723, 11774, -1, 11739, 16723, 11737, -1, 11774, 16723, 16721, -1, 11739, 11817, 16723, -1, 11817, 11814, 16723, -1, 11804, 16722, 11814, -1, 11814, 16722, 16723, -1, 11804, 11802, 16722, -1, 11802, 11797, 16722, -1, 11797, 16724, 16722, -1, 11776, 16724, 11797, -1, 17043, 16734, 16733, -1, 17044, 17107, 17043, -1, 17043, 17107, 16734, -1, 17045, 17108, 17044, -1, 17044, 17108, 17107, -1, 17045, 17109, 17108, -1, 17046, 17110, 17045, -1, 17045, 17110, 17109, -1, 17047, 17111, 17046, -1, 17046, 17111, 17110, -1, 17048, 17112, 17047, -1, 17047, 17112, 17111, -1, 17049, 17113, 17048, -1, 17048, 17113, 17112, -1, 17050, 17114, 17049, -1, 17049, 17114, 17113, -1, 17051, 17115, 17050, -1, 17050, 17115, 17114, -1, 16970, 17116, 17051, -1, 17051, 17116, 17115, -1, 16968, 17117, 16970, -1, 16967, 17117, 16968, -1, 16970, 17117, 17116, -1, 16969, 16716, 16967, -1, 16967, 16716, 17117, -1, 16969, 16717, 16716, -1, 16439, 17151, 17152, -1, 16988, 17153, 16985, -1, 17152, 17151, 17154, -1, 17155, 17153, 16988, -1, 17154, 17151, 17156, -1, 17000, 17157, 11635, -1, 17156, 17157, 17000, -1, 16334, 17158, 17159, -1, 11635, 17157, 11633, -1, 17159, 17158, 17155, -1, 17155, 17158, 17153, -1, 16441, 17160, 16442, -1, 17157, 17160, 11633, -1, 11633, 17160, 11630, -1, 17156, 17160, 17157, -1, 11630, 17160, 16441, -1, 17153, 17161, 16985, -1, 16442, 17160, 17151, -1, 17151, 17160, 17156, -1, 16334, 17162, 17158, -1, 16339, 17162, 16334, -1, 17158, 17162, 17153, -1, 17153, 17162, 17161, -1, 16985, 17163, 16983, -1, 11681, 16475, 11680, -1, 17161, 17163, 16985, -1, 16339, 17164, 17162, -1, 17162, 17164, 17161, -1, 16441, 11628, 11630, -1, 17161, 17164, 17163, -1, 17163, 17165, 16983, -1, 11674, 17166, 11672, -1, 11672, 17166, 16961, -1, 16355, 17167, 16339, -1, 17163, 17167, 17165, -1, 16339, 17167, 17164, -1, 11674, 17168, 17166, -1, 17164, 17167, 17163, -1, 17165, 17169, 16983, -1, 11680, 17168, 11674, -1, 16475, 17168, 11680, -1, 17166, 17170, 16961, -1, 16983, 17169, 16980, -1, 17167, 17171, 17165, -1, 16961, 17170, 16950, -1, 16478, 17172, 16475, -1, 16355, 17171, 17167, -1, 17165, 17171, 17169, -1, 17168, 17172, 17166, -1, 16475, 17172, 17168, -1, 17169, 17173, 16980, -1, 17166, 17172, 17170, -1, 16950, 17174, 16944, -1, 17173, 17175, 16980, -1, 17170, 17174, 16950, -1, 16980, 17175, 16977, -1, 16477, 17176, 16478, -1, 16365, 17177, 16355, -1, 16355, 17177, 17171, -1, 17170, 17176, 17174, -1, 17171, 17177, 17169, -1, 17169, 17177, 17173, -1, 17172, 17176, 17170, -1, 16478, 17176, 17172, -1, 17174, 17178, 16944, -1, 16365, 17179, 17177, -1, 16944, 17178, 17094, -1, 17173, 17179, 17175, -1, 17177, 17179, 17173, -1, 16477, 17180, 17176, -1, 16480, 17180, 16477, -1, 17175, 17181, 16977, -1, 17174, 17180, 17178, -1, 17176, 17180, 17174, -1, 17094, 17182, 17086, -1, 17181, 17183, 16977, -1, 16977, 17183, 16974, -1, 16426, 17184, 16365, -1, 17178, 17182, 17094, -1, 16365, 17184, 17179, -1, 17179, 17184, 17175, -1, 17175, 17184, 17181, -1, 17182, 17185, 17086, -1, 16426, 17186, 17184, -1, 16510, 17187, 16480, -1, 17181, 17186, 17183, -1, 16480, 17187, 17180, -1, 17180, 17187, 17178, -1, 17184, 17186, 17181, -1, 17178, 17187, 17182, -1, 17183, 17188, 16974, -1, 16510, 17189, 17187, -1, 16483, 17189, 16510, -1, 17182, 17189, 17185, -1, 17187, 17189, 17182, -1, 16974, 17190, 16973, -1, 17086, 17191, 17079, -1, 17188, 17190, 16974, -1, 16430, 17192, 16426, -1, 17185, 17191, 17086, -1, 16426, 17192, 17186, -1, 17186, 17192, 17183, -1, 17183, 17192, 17188, -1, 16483, 17193, 17189, -1, 17189, 17193, 17185, -1, 17185, 17193, 17191, -1, 16430, 17194, 17192, -1, 17188, 17194, 17190, -1, 17192, 17194, 17188, -1, 17191, 17195, 17079, -1, 17190, 17196, 16973, -1, 16482, 17197, 16483, -1, 17191, 17197, 17195, -1, 17193, 17197, 17191, -1, 16491, 17198, 16430, -1, 16483, 17197, 17193, -1, 16430, 17198, 17194, -1, 17194, 17198, 17190, -1, 17190, 17198, 17196, -1, 17079, 17199, 16993, -1, 17195, 17199, 17079, -1, 16973, 17200, 17070, -1, 17196, 17200, 16973, -1, 17197, 17201, 17195, -1, 16482, 17201, 17197, -1, 16435, 17202, 16491, -1, 17195, 17201, 17199, -1, 17199, 17203, 16993, -1, 16491, 17202, 17198, -1, 17198, 17202, 17196, -1, 17196, 17202, 17200, -1, 17200, 17204, 17070, -1, 16515, 17205, 16482, -1, 17199, 17205, 17203, -1, 17070, 17204, 17039, -1, 17201, 17205, 17199, -1, 16482, 17205, 17201, -1, 16434, 17206, 16435, -1, 16435, 17206, 17202, -1, 17203, 17207, 16993, -1, 17200, 17206, 17204, -1, 16993, 17207, 16991, -1, 17202, 17206, 17200, -1, 16515, 17208, 17205, -1, 17205, 17208, 17203, -1, 17039, 17209, 17025, -1, 17203, 17208, 17207, -1, 17204, 17209, 17039, -1, 16437, 17210, 16434, -1, 17207, 17211, 16991, -1, 16434, 17210, 17206, -1, 17206, 17210, 17204, -1, 16486, 17212, 16515, -1, 17208, 17212, 17207, -1, 17204, 17210, 17209, -1, 17207, 17212, 17211, -1, 16515, 17212, 17208, -1, 17025, 17154, 17014, -1, 17209, 17154, 17025, -1, 16991, 17213, 16988, -1, 17211, 17213, 16991, -1, 16439, 17152, 16437, -1, 16486, 17214, 17212, -1, 16437, 17152, 17210, -1, 17212, 17214, 17211, -1, 17210, 17152, 17209, -1, 17211, 17214, 17213, -1, 17209, 17152, 17154, -1, 17006, 17156, 17000, -1, 17213, 17155, 16988, -1, 17014, 17156, 17006, -1, 17154, 17156, 17014, -1, 16334, 17159, 16486, -1, 16486, 17159, 17214, -1, 17214, 17159, 17213, -1, 16442, 17151, 16439, -1, 17213, 17159, 17155, -1, 16388, 11608, 11607, -1, 16390, 16388, 11607, -1, 16392, 16390, 11607, -1, 16394, 16392, 11607, -1, 16396, 16394, 11607, -1, 16398, 16396, 11607, -1, 16400, 16398, 11607, -1, 16402, 16400, 11607, -1, 16404, 16402, 11607, -1, 11546, 16409, 16404, -1, 11546, 16411, 16409, -1, 11546, 16413, 16411, -1, 11546, 16415, 16413, -1, 11546, 16417, 16415, -1, 11546, 16419, 16417, -1, 11546, 16421, 16419, -1, 11546, 16423, 16421, -1, 11546, 16404, 11607, -1, 11548, 16423, 11546, -1, 16358, 16360, 17215, -1, 16359, 16358, 17215, -1, 16362, 16359, 17215, -1, 16364, 16362, 17215, -1, 16367, 16364, 17215, -1, 16369, 16367, 17215, -1, 16456, 16369, 17215, -1, 16455, 16456, 17215, -1, 16372, 16455, 17215, -1, 17216, 16385, 16383, -1, 17216, 16383, 16381, -1, 17216, 16381, 16378, -1, 17216, 16378, 16377, -1, 17216, 16377, 16461, -1, 17216, 16461, 16462, -1, 17216, 16462, 16373, -1, 17216, 16373, 16372, -1, 17216, 16372, 17215, -1, 16386, 16385, 17216, -1, 16521, 11530, 11529, -1, 16522, 16521, 11529, -1, 16523, 16522, 11529, -1, 16524, 16523, 11529, -1, 16328, 16524, 11529, -1, 16330, 16328, 11529, -1, 16331, 16330, 11529, -1, 16333, 16331, 11529, -1, 16336, 16333, 11529, -1, 11561, 16338, 16336, -1, 11561, 16342, 16338, -1, 11561, 16344, 16342, -1, 11561, 16346, 16344, -1, 11561, 16348, 16346, -1, 11561, 16350, 16348, -1, 11561, 16352, 16350, -1, 11561, 16354, 16352, -1, 11561, 16336, 11529, -1, 11562, 16354, 11561, -1, 17217, 17218, 11600, -1, 11600, 17218, 11602, -1, 17218, 11555, 11602, -1, 11573, 17219, 11575, -1, 11602, 11555, 11604, -1, 11604, 11553, 11606, -1, 11555, 11553, 11604, -1, 11575, 17220, 11577, -1, 11553, 11551, 11606, -1, 17219, 17220, 11575, -1, 11571, 17221, 11573, -1, 11561, 11529, 11527, -1, 11561, 11527, 11565, -1, 11573, 17221, 17219, -1, 11546, 11607, 11551, -1, 11551, 11607, 11606, -1, 11577, 17222, 11579, -1, 17220, 17222, 11577, -1, 11569, 17223, 11571, -1, 11571, 17223, 17221, -1, 11579, 17224, 11581, -1, 17222, 17224, 11579, -1, 11567, 11524, 11569, -1, 11569, 11524, 17223, -1, 17225, 17226, 17227, -1, 11581, 17228, 11590, -1, 17224, 17228, 11581, -1, 11590, 17228, 11592, -1, 17227, 17229, 17230, -1, 11565, 11525, 11567, -1, 17226, 17229, 17227, -1, 17231, 17232, 17225, -1, 11567, 11525, 11524, -1, 17225, 17232, 17226, -1, 17230, 17233, 17234, -1, 17229, 17233, 17230, -1, 17231, 17235, 17232, -1, 17236, 17237, 17215, -1, 17234, 17237, 17236, -1, 11565, 11527, 11525, -1, 17233, 17237, 17234, -1, 17228, 17238, 11592, -1, 17231, 11588, 17235, -1, 11585, 11588, 17231, -1, 11592, 17238, 11594, -1, 11583, 11588, 11585, -1, 17237, 17216, 17215, -1, 17238, 17239, 11594, -1, 11594, 17239, 11596, -1, 11583, 11586, 11588, -1, 11581, 11590, 11583, -1, 11596, 17240, 11598, -1, 17239, 17240, 11596, -1, 11583, 11590, 11586, -1, 11598, 17217, 11600, -1, 17240, 17217, 11598, -1, 14311, 11614, 11615, -1, 14311, 11615, 16512, -1, 14311, 16512, 16498, -1, 14308, 16498, 16497, -1, 14308, 14311, 16498, -1, 14309, 16497, 16484, -1, 14309, 14308, 16497, -1, 14310, 16484, 16470, -1, 14310, 14309, 16484, -1, 14314, 16470, 16468, -1, 14314, 14310, 16470, -1, 17216, 16468, 16386, -1, 14316, 14314, 16468, -1, 14316, 16468, 17216, -1, 14320, 17216, 17237, -1, 14320, 14316, 17216, -1, 14324, 17237, 17233, -1, 14324, 14320, 17237, -1, 14327, 17233, 17229, -1, 14327, 14324, 17233, -1, 14307, 17229, 17226, -1, 14307, 14327, 17229, -1, 14306, 17226, 17232, -1, 14306, 14307, 17226, -1, 14313, 17232, 17235, -1, 14313, 14306, 17232, -1, 11587, 17235, 11588, -1, 11587, 14313, 17235, -1, 11584, 11585, 17231, -1, 14337, 17231, 17225, -1, 14337, 11584, 17231, -1, 14333, 17225, 17227, -1, 14333, 14337, 17225, -1, 14334, 17227, 17230, -1, 14334, 14333, 17227, -1, 14336, 17230, 17234, -1, 14336, 14334, 17230, -1, 14339, 17234, 17236, -1, 14339, 14336, 17234, -1, 16449, 17215, 16360, -1, 14343, 17236, 17215, -1, 14343, 14339, 17236, -1, 14346, 17215, 16449, -1, 14346, 14343, 17215, -1, 14348, 16449, 16443, -1, 14348, 14346, 16449, -1, 14350, 16443, 16428, -1, 14350, 14348, 16443, -1, 14329, 16428, 16427, -1, 14329, 14350, 16428, -1, 14328, 16427, 16406, -1, 14328, 14329, 16427, -1, 14332, 16406, 16405, -1, 14332, 14328, 16406, -1, 11556, 16405, 11557, -1, 11556, 14332, 16405, -1, 14289, 11554, 11555, -1, 14289, 11555, 17218, -1, 14284, 17218, 17217, -1, 14284, 14289, 17218, -1, 14285, 17217, 17240, -1, 14285, 14284, 17217, -1, 14287, 17240, 17239, -1, 14287, 14285, 17240, -1, 14291, 17239, 17238, -1, 14291, 14287, 17239, -1, 14294, 17238, 17228, -1, 14294, 14291, 17238, -1, 14298, 17228, 17224, -1, 14298, 14294, 17228, -1, 14300, 17224, 17222, -1, 14300, 14298, 17224, -1, 14302, 17222, 17220, -1, 14302, 14300, 17222, -1, 14281, 17220, 17219, -1, 14281, 14302, 17220, -1, 14280, 17219, 17221, -1, 14280, 14281, 17219, -1, 14286, 17221, 17223, -1, 14286, 14280, 17221, -1, 11523, 17223, 11524, -1, 11523, 14286, 17223, -1, 16900, 16878, 16904, -1, 16900, 16904, 16917, -1, 17241, 14241, 14244, -1, 17241, 16889, 16887, -1, 17242, 14244, 14243, -1, 17242, 16891, 16889, -1, 17242, 17241, 14244, -1, 17242, 16889, 17241, -1, 17243, 14243, 14240, -1, 17243, 16893, 16891, -1, 17243, 16891, 17242, -1, 17243, 17242, 14243, -1, 17244, 11520, 11519, -1, 17244, 11519, 14242, -1, 17244, 14242, 14241, -1, 17244, 14241, 17241, -1, 17245, 16887, 16886, -1, 17245, 16886, 11520, -1, 17245, 17244, 17241, -1, 17245, 11520, 17244, -1, 17245, 17241, 16887, -1, 17246, 14240, 14239, -1, 17246, 14239, 14237, -1, 17246, 17243, 14240, -1, 17247, 14237, 14226, -1, 17247, 14226, 16896, -1, 17247, 16896, 16893, -1, 17247, 17243, 17246, -1, 17247, 16893, 17243, -1, 17247, 17246, 14237, -1, 17248, 16867, 17249, -1, 17248, 17249, 16905, -1, 17250, 16873, 16871, -1, 17250, 16907, 16908, -1, 17250, 16871, 17248, -1, 17250, 17248, 16907, -1, 17251, 16853, 16916, -1, 17251, 16916, 16915, -1, 17251, 16915, 16914, -1, 17251, 16914, 17252, -1, 17253, 16855, 16854, -1, 17253, 16854, 16853, -1, 17253, 17251, 17252, -1, 17253, 16853, 17251, -1, 17253, 17252, 16855, -1, 17254, 16908, 16909, -1, 17254, 16909, 16904, -1, 17254, 17250, 16908, -1, 17255, 16904, 16878, -1, 17255, 16878, 16875, -1, 17255, 16875, 16873, -1, 17255, 17254, 16904, -1, 17255, 16873, 17250, -1, 17255, 17250, 17254, -1, 17252, 16857, 16855, -1, 17252, 16914, 16913, -1, 17256, 16861, 16859, -1, 17256, 16859, 16857, -1, 17256, 16913, 16912, -1, 17256, 16912, 16911, -1, 17256, 17252, 16913, -1, 17256, 16857, 17252, -1, 17257, 16863, 16861, -1, 17257, 16911, 16910, -1, 17257, 16910, 16903, -1, 17257, 17256, 16911, -1, 17257, 16861, 17256, -1, 17249, 16867, 16865, -1, 17249, 16865, 16863, -1, 17249, 16903, 16905, -1, 17249, 17257, 16903, -1, 17249, 16863, 17257, -1, 17248, 16871, 16869, -1, 17248, 16869, 16867, -1, 17248, 16905, 16906, -1, 17248, 16906, 16907, -1, 16916, 16882, 16918, -1, 16853, 16882, 16916, -1, 11471, 16743, 16779, -1, 11470, 16743, 11471, -1, 16735, 11478, 11477, -1, 16735, 11477, 16777, -1, 16735, 16777, 16778, -1, 16737, 16735, 16778, -1, 16739, 16778, 16776, -1, 16739, 16737, 16778, -1, 17258, 16766, 16764, -1, 17258, 14205, 14204, -1, 17258, 16764, 17259, -1, 17258, 17259, 14205, -1, 17260, 14196, 14211, -1, 17260, 14211, 14215, -1, 17260, 14215, 14214, -1, 17260, 14214, 17261, -1, 17262, 16749, 16747, -1, 17262, 16747, 14196, -1, 17262, 17260, 17261, -1, 17262, 14196, 17260, -1, 17262, 17261, 16749, -1, 17263, 14204, 14203, -1, 17263, 14203, 14201, -1, 17263, 17258, 14204, -1, 17264, 14201, 14188, -1, 17264, 14188, 16769, -1, 17264, 16769, 16766, -1, 17264, 17263, 14201, -1, 17264, 16766, 17258, -1, 17264, 17258, 17263, -1, 17261, 16751, 16749, -1, 17261, 14214, 14210, -1, 17265, 16755, 16753, -1, 17265, 16753, 16751, -1, 17265, 14210, 14212, -1, 17265, 14212, 14213, -1, 17265, 17261, 14210, -1, 17265, 16751, 17261, -1, 17266, 16757, 16755, -1, 17266, 14213, 14209, -1, 17266, 14209, 14208, -1, 17266, 17265, 14213, -1, 17266, 16755, 17265, -1, 17267, 16760, 16758, -1, 17267, 16758, 16757, -1, 17267, 14208, 14207, -1, 17267, 17266, 14208, -1, 17267, 16757, 17266, -1, 17259, 16764, 16762, -1, 17259, 16762, 16760, -1, 17259, 14207, 14206, -1, 17259, 14206, 14205, -1, 17259, 16760, 17267, -1, 17259, 17267, 14207, -1, 16780, 16739, 16776, -1, 16773, 16739, 16780, -1, 16835, 16801, 16839, -1, 16835, 16839, 16838, -1, 17268, 16826, 16824, -1, 17268, 16824, 16822, -1, 17268, 17269, 14006, -1, 17268, 16822, 17269, -1, 17270, 14007, 14018, -1, 17270, 16828, 16826, -1, 17270, 17268, 14007, -1, 17270, 16826, 17268, -1, 17271, 14010, 14009, -1, 17271, 14009, 14011, -1, 17271, 14011, 17272, -1, 17273, 14002, 14010, -1, 17273, 16811, 16809, -1, 17273, 16809, 14002, -1, 17273, 17271, 17272, -1, 17273, 17272, 16811, -1, 17273, 14010, 17271, -1, 17274, 14018, 14017, -1, 17274, 14017, 14019, -1, 17274, 17270, 14018, -1, 17275, 14019, 13994, -1, 17275, 13994, 16831, -1, 17275, 16831, 16828, -1, 17275, 17270, 17274, -1, 17275, 17274, 14019, -1, 17275, 16828, 17270, -1, 17272, 14011, 14012, -1, 17272, 16813, 16811, -1, 17276, 14012, 14013, -1, 17276, 14013, 14014, -1, 17276, 16817, 16815, -1, 17276, 16815, 16813, -1, 17276, 17272, 14012, -1, 17276, 16813, 17272, -1, 17277, 14014, 14015, -1, 17277, 14015, 14016, -1, 17277, 16820, 16819, -1, 17277, 16819, 16817, -1, 17277, 17276, 14014, -1, 17277, 16817, 17276, -1, 17269, 14016, 14006, -1, 17269, 16822, 16820, -1, 17269, 16820, 17277, -1, 17269, 17277, 14016, -1, 17268, 14006, 14008, -1, 17268, 14008, 14007, -1, 17278, 16839, 16801, -1, 17278, 16801, 16799, -1, 17278, 16799, 16797, -1, 17278, 17279, 16839, -1, 17278, 16797, 17280, -1, 17278, 17280, 17279, -1, 17281, 16847, 16850, -1, 17281, 16785, 16783, -1, 17282, 16850, 16849, -1, 17282, 16849, 16846, -1, 17282, 16789, 16787, -1, 17282, 16787, 16785, -1, 17282, 17281, 16850, -1, 17282, 16785, 17281, -1, 17283, 16846, 16845, -1, 17283, 16791, 16789, -1, 17283, 16789, 17282, -1, 17283, 17282, 16846, -1, 17284, 16845, 16841, -1, 17284, 16841, 16842, -1, 17284, 16795, 16793, -1, 17284, 16793, 16791, -1, 17284, 16791, 17283, -1, 17284, 17283, 16845, -1, 17280, 16842, 16843, -1, 17280, 16797, 16795, -1, 17280, 16795, 17284, -1, 17280, 17284, 16842, -1, 17285, 11465, 11466, -1, 17285, 11466, 16848, -1, 17285, 16848, 16847, -1, 17285, 16847, 17281, -1, 17286, 16783, 16781, -1, 17286, 16781, 11465, -1, 17286, 17285, 17281, -1, 17286, 11465, 17285, -1, 17286, 17281, 16783, -1, 17279, 16843, 16844, -1, 17279, 16844, 16839, -1, 17279, 17280, 16843, -1, 11460, 16805, 16840, -1, 11459, 16805, 11460, -1, 14221, 17287, 16656, -1, 17288, 17289, 14183, -1, 14183, 17289, 16650, -1, 16633, 14221, 16656, -1, 17290, 17291, 13989, -1, 13989, 17291, 16644, -1, 16633, 16634, 14221, -1, 16631, 16633, 16656, -1, 11708, 17288, 14183, -1, 17291, 13891, 16644, -1, 17292, 13889, 13891, -1, 11711, 17288, 11708, -1, 17292, 13891, 17291, -1, 11711, 17293, 17288, -1, 17294, 13887, 13889, -1, 17294, 13889, 17292, -1, 11445, 13885, 13887, -1, 11445, 13887, 17294, -1, 11713, 17293, 11711, -1, 11713, 17295, 17293, -1, 13882, 16641, 16630, -1, 11446, 13882, 13885, -1, 11446, 13885, 11445, -1, 11447, 13882, 11446, -1, 17136, 11859, 11878, -1, 17144, 16639, 16640, -1, 17144, 16640, 16641, -1, 17144, 16641, 13882, -1, 11715, 17295, 11713, -1, 17144, 13882, 11447, -1, 17296, 17130, 17132, -1, 17144, 11447, 11449, -1, 17297, 17296, 17132, -1, 13827, 16656, 17287, -1, 17297, 17132, 17134, -1, 11452, 17144, 11449, -1, 17290, 17130, 17296, -1, 17142, 17144, 11452, -1, 17146, 17295, 11715, -1, 17290, 13986, 17130, -1, 17146, 17298, 17295, -1, 11454, 17142, 11452, -1, 17299, 17297, 17134, -1, 13825, 13827, 17287, -1, 17299, 17134, 17136, -1, 17140, 17142, 11454, -1, 14117, 17136, 11878, -1, 13825, 17287, 17300, -1, 17148, 17298, 17146, -1, 14117, 11878, 11879, -1, 11456, 17140, 11454, -1, 14117, 11879, 11874, -1, 17301, 17299, 17136, -1, 17138, 17140, 11456, -1, 17150, 17298, 17148, -1, 17138, 11456, 11458, -1, 17302, 17136, 14117, -1, 17150, 17303, 17298, -1, 17302, 17301, 17136, -1, 17150, 17304, 17303, -1, 13823, 13825, 17300, -1, 14218, 17138, 11458, -1, 17305, 17302, 14117, -1, 13823, 17300, 17306, -1, 17305, 14117, 14120, -1, 16650, 17289, 14126, -1, 13821, 17306, 17307, -1, 13821, 13823, 17306, -1, 13818, 13821, 17307, -1, 13818, 17307, 17304, -1, 13818, 17304, 17150, -1, 17308, 17305, 14120, -1, 17308, 14120, 14122, -1, 17309, 17308, 14122, -1, 11939, 16650, 11928, -1, 11940, 14183, 16650, -1, 11940, 16650, 11939, -1, 14124, 17309, 14122, -1, 16636, 17150, 16635, -1, 11850, 14183, 11940, -1, 14221, 14218, 11458, -1, 17289, 17309, 14124, -1, 16636, 13818, 17150, -1, 14126, 17289, 14124, -1, 13989, 13986, 17290, -1, 13989, 11897, 11898, -1, 16637, 13818, 16636, -1, 13989, 11898, 11900, -1, 16644, 11897, 13989, -1, 16644, 11889, 11897, -1, 16638, 13818, 16637, -1, 16634, 16632, 14221, -1, 11458, 17287, 14221, -1, 16666, 16672, 17287, -1, 17287, 16672, 17300, -1, 17300, 16671, 17306, -1, 16672, 16671, 17300, -1, 17306, 16670, 17307, -1, 16671, 16670, 17306, -1, 17307, 16668, 17304, -1, 16670, 16668, 17307, -1, 17304, 16669, 17303, -1, 16668, 16669, 17304, -1, 17303, 16698, 17298, -1, 16669, 16698, 17303, -1, 17298, 16697, 17295, -1, 16698, 16697, 17298, -1, 17295, 16665, 17293, -1, 16697, 16665, 17295, -1, 17293, 16667, 17288, -1, 16665, 16667, 17293, -1, 11458, 16666, 17287, -1, 11457, 16666, 11458, -1, 17291, 16692, 17292, -1, 17292, 16700, 17294, -1, 16692, 16700, 17292, -1, 17294, 16699, 11445, -1, 16700, 16699, 17294, -1, 16699, 11443, 11445, -1, 16682, 16692, 17291, -1, 16682, 17291, 17290, -1, 17289, 16681, 17309, -1, 17309, 16679, 17308, -1, 16681, 16679, 17309, -1, 17308, 16660, 17305, -1, 16679, 16660, 17308, -1, 17305, 16662, 17302, -1, 16660, 16662, 17305, -1, 17302, 16661, 17301, -1, 16662, 16661, 17302, -1, 17301, 16664, 17299, -1, 16661, 16664, 17301, -1, 17299, 16663, 17297, -1, 16664, 16663, 17299, -1, 17297, 16676, 17296, -1, 16663, 16676, 17297, -1, 16676, 16680, 17296, -1, 17296, 16682, 17290, -1, 16680, 16682, 17296, -1, 17288, 16681, 17289, -1, 16667, 16681, 17288, -1, 16596, 16247, 16252, -1, 13804, 16596, 16252, -1, 13803, 13804, 16252, -1, 16882, 16252, 16631, -1, 16882, 16631, 16918, -1, 16882, 13803, 16252, -1, 13802, 13803, 16882, -1, 16881, 13802, 16882, -1, 16656, 16917, 16918, -1, 16656, 16918, 16631, -1, 16900, 16917, 16656, -1, 13797, 16902, 16900, -1, 13794, 13797, 16900, -1, 16655, 16900, 16656, -1, 16655, 13794, 16900, -1, 14233, 14279, 14223, -1, 14233, 14223, 14221, -1, 14233, 14221, 14236, -1, 14238, 14236, 14221, -1, 14255, 14279, 14233, -1, 14232, 14255, 14233, -1, 14253, 14230, 14228, -1, 16632, 14228, 14238, -1, 16632, 14238, 14221, -1, 16586, 14253, 14228, -1, 16325, 14228, 16632, -1, 16325, 16586, 14228, -1, 16584, 16586, 16325, -1, 16597, 16325, 16245, -1, 16597, 16584, 16325, -1, 16596, 16597, 16245, -1, 16596, 16245, 16247, -1, 12031, 12063, 11929, -1, 12030, 12031, 11929, -1, 14105, 12030, 11929, -1, 16743, 11929, 11928, -1, 16743, 11928, 16779, -1, 16743, 14105, 11929, -1, 14104, 14105, 16743, -1, 16742, 14104, 16743, -1, 16650, 16780, 16779, -1, 16650, 16779, 11928, -1, 16773, 16780, 16650, -1, 14100, 16775, 16773, -1, 14097, 14100, 16773, -1, 16649, 16773, 16650, -1, 16649, 14097, 16773, -1, 14195, 13593, 14185, -1, 14195, 14185, 14183, -1, 14202, 14195, 14183, -1, 14200, 14202, 14183, -1, 13592, 13593, 14195, -1, 14194, 13592, 14195, -1, 14165, 14192, 14190, -1, 11850, 14190, 14200, -1, 11850, 14200, 14183, -1, 14163, 14165, 14190, -1, 11935, 14190, 11850, -1, 11935, 14163, 14190, -1, 12035, 14163, 11935, -1, 12033, 11935, 12062, -1, 12033, 12035, 11935, -1, 12031, 12033, 12062, -1, 12031, 12062, 12063, -1, 17136, 11860, 11859, -1, 11997, 11950, 12060, -1, 11997, 12061, 11860, -1, 11997, 12060, 12061, -1, 11996, 11860, 17136, -1, 11996, 11997, 11860, -1, 17135, 13960, 11996, -1, 17135, 11996, 17136, -1, 11876, 14117, 11874, -1, 12000, 14034, 14118, -1, 12000, 14118, 14117, -1, 12000, 14117, 11876, -1, 11999, 12059, 12058, -1, 11999, 11876, 12059, -1, 11999, 12000, 11876, -1, 11952, 11999, 12058, -1, 11952, 12058, 12060, -1, 11950, 11952, 12060, -1, 11960, 12065, 11892, -1, 11958, 11960, 11892, -1, 13690, 11958, 11892, -1, 16805, 11892, 11889, -1, 16805, 11889, 16840, -1, 16805, 13690, 11892, -1, 13689, 13690, 16805, -1, 16804, 13689, 16805, -1, 16644, 16838, 16840, -1, 16644, 16840, 11889, -1, 16835, 16838, 16644, -1, 13655, 16837, 16835, -1, 13653, 13655, 16835, -1, 16643, 16835, 16644, -1, 16643, 13653, 16835, -1, 14001, 13965, 13991, -1, 14001, 13991, 13989, -1, 14001, 13989, 14020, -1, 14021, 14020, 13989, -1, 13964, 13965, 14001, -1, 14000, 13964, 14001, -1, 13969, 13998, 13996, -1, 11900, 13996, 14021, -1, 11900, 14021, 13989, -1, 13968, 13969, 13996, -1, 11902, 13996, 11900, -1, 11902, 13968, 13996, -1, 11965, 13968, 11902, -1, 11963, 11902, 12064, -1, 11963, 11965, 11902, -1, 11960, 11963, 12064, -1, 11960, 12064, 12065, -1, 16619, 16278, 16281, -1, 17144, 16281, 16639, -1, 16579, 16281, 17144, -1, 16579, 16619, 16281, -1, 17143, 16581, 16579, -1, 17143, 16579, 17144, -1, 16273, 13882, 16630, -1, 13834, 13836, 13883, -1, 13834, 13883, 13882, -1, 13834, 13882, 16273, -1, 16622, 16273, 16272, -1, 16622, 13834, 16273, -1, 16619, 16622, 16272, -1, 16619, 16272, 16278, -1, 16600, 16303, 16307, -1, 17150, 16307, 16635, -1, 13583, 16307, 17150, -1, 13583, 16600, 16307, -1, 17149, 13585, 13583, -1, 17149, 13583, 17150, -1, 16296, 13818, 16638, -1, 13722, 13724, 13819, -1, 13722, 13819, 13818, -1, 13722, 13818, 16296, -1, 16602, 16296, 16295, -1, 16602, 13722, 16296, -1, 16600, 16602, 16295, -1, 16600, 16295, 16303, -1, 17310, 11441, 11440, -1, 17310, 11440, 15017, -1, 17311, 11293, 11441, -1, 17311, 11291, 11293, -1, 17311, 14593, 11291, -1, 17311, 11441, 17310, -1, 17312, 17310, 15017, -1, 17312, 15017, 15013, -1, 17313, 14587, 14593, -1, 17313, 17310, 17312, -1, 17313, 14593, 17311, -1, 17313, 17311, 17310, -1, 17314, 15013, 15010, -1, 17314, 17312, 15013, -1, 17315, 17312, 17314, -1, 17315, 17313, 17312, -1, 17315, 14924, 14587, -1, 17315, 14587, 17313, -1, 17316, 17314, 15010, -1, 17316, 15010, 15009, -1, 17317, 17314, 17316, -1, 17317, 17315, 17314, -1, 17317, 14924, 17315, -1, 17317, 14920, 14924, -1, 17318, 17316, 15009, -1, 17318, 15009, 15006, -1, 17319, 17317, 17316, -1, 17319, 14910, 14920, -1, 17319, 14920, 17317, -1, 17319, 17316, 17318, -1, 17320, 15006, 15002, -1, 17320, 17318, 15006, -1, 17321, 14910, 17319, -1, 17321, 17319, 17318, -1, 17321, 17318, 17320, -1, 17321, 14614, 14910, -1, 17322, 17320, 15002, -1, 17322, 15002, 15001, -1, 17323, 14611, 14614, -1, 17323, 14885, 14611, -1, 17323, 17321, 17320, -1, 17323, 14614, 17321, -1, 17323, 17320, 17322, -1, 17324, 15001, 14998, -1, 17324, 17322, 15001, -1, 17325, 17323, 17322, -1, 17325, 14885, 17323, -1, 17325, 17322, 17324, -1, 17326, 14998, 14994, -1, 17326, 17324, 14998, -1, 17327, 14885, 17325, -1, 17327, 14874, 14885, -1, 17327, 14863, 14874, -1, 17327, 17324, 17326, -1, 17327, 17325, 17324, -1, 17328, 17326, 14994, -1, 17328, 14994, 14991, -1, 17329, 14863, 17327, -1, 17329, 17327, 17326, -1, 17329, 17326, 17328, -1, 17330, 17328, 14991, -1, 17330, 14991, 14990, -1, 17331, 14863, 17329, -1, 17331, 17329, 17328, -1, 17331, 14854, 14863, -1, 17331, 17328, 17330, -1, 17332, 17330, 14990, -1, 17332, 14990, 14986, -1, 17333, 17330, 17332, -1, 17333, 17331, 17330, -1, 17333, 14841, 14854, -1, 17333, 14854, 17331, -1, 17334, 17332, 14986, -1, 17334, 14986, 14983, -1, 17335, 17333, 17332, -1, 17335, 17332, 17334, -1, 17335, 14832, 14841, -1, 17335, 14815, 14832, -1, 17335, 14841, 17333, -1, 17336, 17334, 14983, -1, 17336, 14983, 14979, -1, 17337, 14815, 17335, -1, 17337, 17334, 17336, -1, 17337, 17335, 17334, -1, 17338, 14979, 14978, -1, 17338, 17336, 14979, -1, 17339, 17336, 17338, -1, 17339, 14805, 14815, -1, 17339, 14815, 17337, -1, 17339, 17337, 17336, -1, 17340, 17338, 14978, -1, 17340, 14978, 14975, -1, 17341, 14805, 17339, -1, 17341, 17338, 17340, -1, 17341, 17339, 17338, -1, 17341, 14798, 14805, -1, 17342, 14975, 14971, -1, 17342, 17340, 14975, -1, 17343, 17341, 17340, -1, 17343, 17340, 17342, -1, 17343, 14798, 17341, -1, 17343, 14785, 14798, -1, 17343, 14763, 14785, -1, 17344, 14971, 14968, -1, 17344, 17342, 14971, -1, 17345, 17343, 17342, -1, 17345, 14763, 17343, -1, 17345, 17342, 17344, -1, 17346, 14968, 14967, -1, 17346, 17344, 14968, -1, 17347, 14763, 17345, -1, 17347, 14750, 14763, -1, 17347, 17345, 17344, -1, 17347, 17344, 17346, -1, 17348, 14967, 14964, -1, 17348, 17346, 14967, -1, 17349, 14775, 14750, -1, 17349, 14750, 17347, -1, 17349, 17347, 17346, -1, 17349, 17346, 17348, -1, 17350, 14964, 14960, -1, 17350, 17348, 14964, -1, 17351, 14769, 14775, -1, 17351, 14775, 17349, -1, 17351, 17349, 17348, -1, 17351, 17348, 17350, -1, 17352, 14960, 14959, -1, 17352, 17350, 14960, -1, 17353, 14760, 14769, -1, 17353, 17351, 17350, -1, 17353, 14769, 17351, -1, 17353, 17350, 17352, -1, 17354, 14959, 14956, -1, 17354, 17352, 14959, -1, 17355, 14748, 14760, -1, 17355, 17353, 17352, -1, 17355, 14760, 17353, -1, 17355, 17352, 17354, -1, 17356, 14956, 14952, -1, 17356, 17354, 14956, -1, 17357, 14724, 14748, -1, 17357, 14700, 14724, -1, 17357, 17355, 17354, -1, 17357, 14748, 17355, -1, 17357, 17354, 17356, -1, 17358, 14952, 14949, -1, 17358, 17356, 14952, -1, 17359, 17356, 17358, -1, 17359, 17357, 17356, -1, 17359, 14700, 17357, -1, 17360, 14949, 14948, -1, 17360, 17358, 14949, -1, 17361, 14700, 17359, -1, 17361, 17358, 17360, -1, 17361, 14701, 14700, -1, 17361, 14720, 14701, -1, 17361, 17359, 17358, -1, 17362, 14948, 14944, -1, 17362, 17360, 14948, -1, 17363, 17361, 17360, -1, 17363, 14720, 17361, -1, 17363, 17360, 17362, -1, 17364, 17362, 14944, -1, 17364, 14944, 14941, -1, 17365, 14720, 17363, -1, 17365, 17363, 17362, -1, 17365, 14713, 14720, -1, 17365, 17362, 17364, -1, 17366, 17364, 14941, -1, 17366, 14941, 14940, -1, 17367, 17364, 17366, -1, 17367, 14713, 17365, -1, 17367, 14698, 14713, -1, 17367, 14688, 14698, -1, 17367, 17365, 17364, -1, 17368, 17366, 14940, -1, 17368, 14940, 15036, -1, 17369, 14688, 17367, -1, 17369, 17367, 17366, -1, 17369, 17366, 17368, -1, 17370, 15036, 14935, -1, 17370, 17368, 15036, -1, 17371, 17368, 17370, -1, 17371, 14688, 17369, -1, 17371, 17369, 17368, -1, 17371, 14677, 14688, -1, 17372, 14935, 15034, -1, 17372, 17370, 14935, -1, 17373, 17371, 17370, -1, 17373, 14677, 17371, -1, 17373, 17370, 17372, -1, 17373, 14667, 14677, -1, 17374, 15034, 15033, -1, 17374, 17372, 15034, -1, 17375, 17373, 17372, -1, 17375, 14667, 17373, -1, 17375, 17372, 17374, -1, 17375, 14656, 14667, -1, 17376, 15033, 15029, -1, 17376, 17374, 15033, -1, 17377, 17375, 17374, -1, 17377, 14656, 17375, -1, 17377, 17374, 17376, -1, 17377, 14645, 14656, -1, 17378, 15029, 15026, -1, 17378, 17376, 15029, -1, 17379, 17377, 17376, -1, 17379, 14645, 17377, -1, 17379, 17376, 17378, -1, 17379, 14634, 14645, -1, 17380, 15020, 11295, -1, 17380, 15026, 15020, -1, 17380, 11295, 11297, -1, 17380, 17378, 15026, -1, 17381, 11297, 11301, -1, 17381, 11301, 11300, -1, 17381, 17379, 17378, -1, 17381, 14634, 17379, -1, 17381, 17380, 11297, -1, 17381, 17378, 17380, -1, 17381, 14617, 14634, -1, 17381, 11300, 14617, -1, 15644, 17382, 15645, -1, 17383, 17382, 15644, -1, 17384, 17385, 17386, -1, 17386, 17385, 17383, -1, 16181, 17387, 16179, -1, 17388, 17387, 17389, -1, 17389, 17387, 17384, -1, 16179, 17387, 17388, -1, 15645, 17390, 15643, -1, 17382, 17390, 15645, -1, 17385, 17391, 17383, -1, 17383, 17391, 17382, -1, 16184, 17392, 16181, -1, 16181, 17392, 17387, -1, 17384, 17392, 17385, -1, 16176, 16179, 17393, -1, 17387, 17392, 17384, -1, 15643, 17394, 15646, -1, 17390, 17394, 15643, -1, 17391, 17395, 17382, -1, 17382, 17395, 17390, -1, 16186, 17396, 16184, -1, 16184, 17396, 17392, -1, 17385, 17396, 17391, -1, 17392, 17396, 17385, -1, 15646, 17397, 15647, -1, 17394, 17397, 15646, -1, 17390, 17398, 17394, -1, 17395, 17398, 17390, -1, 17396, 17399, 17391, -1, 16188, 17399, 16186, -1, 16186, 17399, 17396, -1, 17391, 17399, 17395, -1, 15647, 17400, 15649, -1, 17397, 17400, 15647, -1, 17394, 17401, 17397, -1, 17398, 17401, 17394, -1, 16190, 17402, 16188, -1, 17395, 17402, 17398, -1, 17399, 17402, 17395, -1, 16188, 17402, 17399, -1, 15649, 17403, 15648, -1, 17400, 17403, 15649, -1, 17397, 17404, 17400, -1, 17401, 17404, 17397, -1, 16192, 17405, 16190, -1, 17398, 17405, 17401, -1, 17402, 17405, 17398, -1, 16190, 17405, 17402, -1, 15648, 17406, 15650, -1, 15650, 17406, 11279, -1, 11279, 17406, 11277, -1, 17403, 17406, 15648, -1, 16198, 11271, 11273, -1, 17400, 17407, 17403, -1, 17408, 17409, 17410, -1, 17410, 17409, 15640, -1, 17404, 17407, 17400, -1, 15640, 17409, 15641, -1, 16194, 17411, 16192, -1, 17401, 17411, 17404, -1, 17405, 17411, 17401, -1, 15641, 17386, 15642, -1, 16192, 17411, 17405, -1, 11277, 17412, 11281, -1, 17409, 17386, 15641, -1, 17406, 17412, 11277, -1, 17403, 17412, 17406, -1, 17407, 17412, 17403, -1, 17393, 17389, 17408, -1, 17404, 17413, 17407, -1, 16196, 17413, 16194, -1, 16194, 17413, 17411, -1, 17408, 17389, 17409, -1, 17411, 17413, 17404, -1, 15642, 17383, 15644, -1, 16198, 17414, 16196, -1, 16196, 17414, 17413, -1, 17386, 17383, 15642, -1, 17412, 17414, 11281, -1, 11281, 17414, 11273, -1, 17413, 17414, 17407, -1, 17407, 17414, 17412, -1, 11273, 17414, 16198, -1, 17409, 17384, 17386, -1, 17389, 17384, 17409, -1, 16179, 17388, 17393, -1, 17393, 17388, 17389, -1, 11275, 16199, 11276, -1, 11276, 17415, 11286, -1, 16199, 17415, 11276, -1, 11286, 17416, 11285, -1, 17415, 17416, 11286, -1, 11285, 17417, 11283, -1, 17416, 17417, 11285, -1, 17417, 15658, 11283, -1, 16177, 16176, 17418, -1, 17418, 17393, 17419, -1, 16176, 17393, 17418, -1, 17419, 17408, 17420, -1, 17393, 17408, 17419, -1, 17420, 17410, 15653, -1, 17408, 17410, 17420, -1, 17410, 15640, 15653, -1, 15659, 17421, 15655, -1, 17422, 17423, 17424, -1, 16208, 17425, 16207, -1, 17426, 17421, 15659, -1, 17427, 17425, 17428, -1, 16207, 17425, 17429, -1, 17430, 17431, 17426, -1, 17429, 17425, 17427, -1, 15652, 17432, 15653, -1, 15658, 17417, 15664, -1, 15653, 17432, 17420, -1, 17433, 17432, 15652, -1, 17434, 17431, 17430, -1, 16200, 17435, 16199, -1, 17415, 17435, 17416, -1, 16199, 17435, 17415, -1, 17424, 17436, 17433, -1, 17423, 17436, 17424, -1, 17416, 17435, 17434, -1, 15655, 17437, 15656, -1, 17425, 17438, 17428, -1, 16209, 17438, 16208, -1, 17428, 17438, 17423, -1, 16208, 17438, 17425, -1, 17421, 17437, 15655, -1, 17420, 17439, 17419, -1, 17431, 17440, 17426, -1, 17432, 17439, 17420, -1, 17426, 17440, 17421, -1, 17433, 17439, 17432, -1, 17436, 17439, 17433, -1, 17423, 17441, 17436, -1, 16201, 17442, 16200, -1, 17435, 17442, 17434, -1, 16210, 17441, 16209, -1, 17434, 17442, 17431, -1, 17438, 17441, 17423, -1, 16200, 17442, 17435, -1, 16209, 17441, 17438, -1, 15656, 17443, 15657, -1, 17418, 17444, 16177, -1, 17419, 17444, 17418, -1, 16177, 17444, 16212, -1, 16212, 17444, 16210, -1, 17437, 17443, 15656, -1, 17441, 17444, 17436, -1, 17436, 17444, 17439, -1, 16210, 17444, 17441, -1, 17439, 17444, 17419, -1, 17440, 17445, 17421, -1, 17421, 17445, 17437, -1, 16202, 17446, 16201, -1, 17442, 17446, 17431, -1, 17431, 17446, 17440, -1, 16201, 17446, 17442, -1, 15657, 17447, 15660, -1, 17443, 17447, 15657, -1, 17437, 17448, 17443, -1, 17445, 17448, 17437, -1, 16203, 17449, 16202, -1, 17440, 17449, 17445, -1, 16202, 17449, 17446, -1, 17446, 17449, 17440, -1, 15660, 17450, 15661, -1, 17447, 17450, 15660, -1, 17448, 17451, 17443, -1, 17443, 17451, 17447, -1, 17445, 17452, 17448, -1, 16204, 17452, 16203, -1, 17449, 17452, 17445, -1, 16203, 17452, 17449, -1, 15661, 17453, 15662, -1, 17450, 17453, 15661, -1, 17451, 17454, 17447, -1, 17447, 17454, 17450, -1, 17448, 17455, 17451, -1, 16204, 17455, 17452, -1, 16205, 17455, 16204, -1, 17452, 17455, 17448, -1, 15662, 17422, 15654, -1, 17453, 17422, 15662, -1, 17454, 17427, 17450, -1, 17450, 17427, 17453, -1, 17451, 17456, 17454, -1, 17455, 17456, 17451, -1, 16206, 17456, 16205, -1, 16205, 17456, 17455, -1, 15654, 17424, 15651, -1, 17422, 17424, 15654, -1, 17427, 17428, 17453, -1, 15664, 17430, 15663, -1, 17453, 17428, 17422, -1, 16207, 17429, 16206, -1, 17417, 17430, 15664, -1, 17456, 17429, 17454, -1, 16206, 17429, 17456, -1, 15663, 17426, 15659, -1, 17454, 17429, 17427, -1, 15651, 17433, 15652, -1, 17430, 17426, 15663, -1, 17424, 17433, 15651, -1, 17416, 17434, 17417, -1, 17428, 17423, 17422, -1, 17417, 17434, 17430, -1, 16211, 11230, 11215, -1, 17457, 17458, 15616, -1, 15616, 17458, 15635, -1, 17459, 17460, 17457, -1, 17457, 17460, 17458, -1, 15635, 17461, 15633, -1, 15633, 17461, 11258, -1, 11258, 17461, 11256, -1, 17458, 17461, 15635, -1, 16213, 17462, 16175, -1, 16175, 17462, 17463, -1, 17463, 17462, 17459, -1, 17459, 17462, 17460, -1, 11256, 17464, 11211, -1, 17458, 17464, 17461, -1, 17461, 17464, 11256, -1, 17460, 17464, 17458, -1, 16211, 17465, 16213, -1, 11211, 17465, 11215, -1, 17464, 17465, 11211, -1, 16213, 17465, 17462, -1, 17460, 17465, 17464, -1, 17462, 17465, 17460, -1, 11215, 17465, 16211, -1, 11248, 11247, 12694, -1, 12694, 11247, 17466, -1, 17466, 11255, 17467, -1, 11247, 11255, 17466, -1, 17467, 11265, 17468, -1, 11255, 11265, 17467, -1, 17468, 11269, 12081, -1, 11265, 11269, 17468, -1, 15591, 17469, 15616, -1, 15616, 17469, 17457, -1, 17457, 17470, 17459, -1, 17469, 17470, 17457, -1, 17459, 17471, 17463, -1, 17470, 17471, 17459, -1, 17463, 16178, 16175, -1, 17471, 16178, 17463, -1, 17472, 17473, 17474, -1, 17474, 17473, 17475, -1, 16189, 17476, 16191, -1, 17477, 17478, 12692, -1, 16191, 17476, 17479, -1, 17480, 17476, 17472, -1, 17479, 17476, 17480, -1, 17467, 17481, 17466, -1, 15598, 17482, 15596, -1, 17466, 17481, 17477, -1, 12690, 17483, 12688, -1, 17484, 17482, 15598, -1, 17478, 17483, 12690, -1, 17475, 17485, 17484, -1, 17473, 17485, 17475, -1, 16189, 17486, 17476, -1, 16187, 17486, 16189, -1, 17481, 17487, 17477, -1, 17477, 17487, 17478, -1, 17472, 17486, 17473, -1, 17476, 17486, 17472, -1, 12080, 17488, 12081, -1, 15596, 17489, 15594, -1, 17468, 17488, 17467, -1, 12081, 17488, 17468, -1, 17467, 17488, 17481, -1, 12688, 17490, 15612, -1, 17482, 17489, 15596, -1, 17483, 17490, 12688, -1, 17484, 17491, 17482, -1, 17485, 17491, 17484, -1, 17478, 17492, 17483, -1, 16185, 17493, 16187, -1, 17487, 17492, 17478, -1, 16187, 17493, 17486, -1, 17473, 17493, 17485, -1, 17486, 17493, 17473, -1, 12079, 17494, 12080, -1, 15594, 17495, 15592, -1, 17481, 17494, 17487, -1, 15592, 17495, 15591, -1, 12080, 17494, 17488, -1, 17488, 17494, 17481, -1, 15591, 17495, 17469, -1, 17489, 17495, 15594, -1, 15612, 17496, 15609, -1, 17490, 17496, 15612, -1, 17482, 17497, 17489, -1, 17491, 17497, 17482, -1, 16183, 17498, 16185, -1, 17492, 17499, 17483, -1, 16185, 17498, 17493, -1, 17485, 17498, 17491, -1, 17493, 17498, 17485, -1, 17483, 17499, 17490, -1, 17487, 17500, 17492, -1, 12078, 17500, 12079, -1, 17469, 17501, 17470, -1, 12079, 17500, 17494, -1, 17495, 17501, 17469, -1, 17489, 17501, 17495, -1, 17494, 17500, 17487, -1, 17497, 17501, 17489, -1, 15609, 17502, 15607, -1, 17491, 17503, 17497, -1, 16182, 17503, 16183, -1, 16183, 17503, 17498, -1, 17496, 17502, 15609, -1, 17498, 17503, 17491, -1, 17499, 17504, 17490, -1, 17501, 17505, 17470, -1, 17471, 17505, 16180, -1, 17470, 17505, 17471, -1, 16180, 17505, 16182, -1, 17490, 17504, 17496, -1, 16182, 17505, 17503, -1, 17503, 17505, 17497, -1, 17497, 17505, 17501, -1, 16197, 17506, 12078, -1, 17500, 17506, 17492, -1, 17492, 17506, 17499, -1, 12078, 17506, 17500, -1, 15607, 17507, 15605, -1, 17502, 17507, 15607, -1, 17504, 17508, 17496, -1, 17496, 17508, 17502, -1, 17506, 17509, 17499, -1, 16195, 17509, 16197, -1, 16197, 17509, 17506, -1, 17499, 17509, 17504, -1, 15605, 17474, 15603, -1, 17507, 17474, 15605, -1, 17508, 17480, 17502, -1, 17502, 17480, 17507, -1, 17509, 17510, 17504, -1, 17504, 17510, 17508, -1, 16195, 17510, 17509, -1, 16193, 17510, 16195, -1, 15603, 17475, 15600, -1, 17474, 17475, 15603, -1, 17480, 17472, 17507, -1, 17507, 17472, 17474, -1, 17510, 17479, 17508, -1, 16191, 17479, 16193, -1, 16193, 17479, 17510, -1, 17508, 17479, 17480, -1, 15600, 17484, 15598, -1, 16180, 16178, 17471, -1, 12694, 17477, 12692, -1, 17475, 17484, 15600, -1, 17466, 17477, 12694, -1, 12692, 17478, 12690, -1, 16170, 17511, 16172, -1, 17512, 17511, 17513, -1, 16172, 17511, 17512, -1, 17513, 17511, 17514, -1, 15734, 17515, 15732, -1, 15732, 17515, 11198, -1, 11198, 17515, 11196, -1, 17516, 17515, 15734, -1, 17517, 17518, 17516, -1, 17519, 17518, 17517, -1, 16166, 17520, 16168, -1, 16168, 17520, 16170, -1, 16170, 17520, 17511, -1, 17514, 17520, 17519, -1, 17511, 17520, 17514, -1, 11196, 17521, 11202, -1, 17515, 17521, 11196, -1, 17516, 17521, 17515, -1, 17518, 17521, 17516, -1, 16164, 17522, 16166, -1, 17519, 17522, 17518, -1, 16166, 17522, 17520, -1, 17520, 17522, 17519, -1, 11208, 17523, 16164, -1, 11202, 17523, 11209, -1, 11209, 17523, 11208, -1, 17521, 17523, 11202, -1, 16143, 16174, 17524, -1, 16164, 17523, 17522, -1, 17518, 17523, 17521, -1, 17522, 17523, 17518, -1, 17525, 17526, 15745, -1, 15745, 17526, 15742, -1, 15742, 17527, 15740, -1, 17526, 17527, 15742, -1, 17528, 17529, 17525, -1, 17525, 17529, 17526, -1, 15740, 17530, 15738, -1, 17527, 17530, 15740, -1, 17529, 17513, 17526, -1, 17526, 17513, 17527, -1, 17524, 17531, 17528, -1, 17528, 17531, 17529, -1, 16174, 17531, 17524, -1, 15738, 17517, 15736, -1, 17530, 17517, 15738, -1, 17513, 17514, 17527, -1, 17527, 17514, 17530, -1, 16172, 17512, 16174, -1, 17531, 17512, 17529, -1, 17529, 17512, 17513, -1, 16174, 17512, 17531, -1, 15736, 17516, 15734, -1, 17517, 17516, 15736, -1, 17514, 17519, 17530, -1, 17530, 17519, 17517, -1, 12661, 11177, 17532, -1, 17532, 11179, 17533, -1, 11177, 11179, 17532, -1, 17533, 11189, 17534, -1, 11179, 11189, 17533, -1, 17534, 11193, 12089, -1, 11189, 11193, 17534, -1, 11193, 11195, 12089, -1, 15752, 17535, 15745, -1, 17525, 17535, 17528, -1, 15745, 17535, 17525, -1, 17528, 17536, 17524, -1, 17535, 17536, 17528, -1, 17536, 17537, 17524, -1, 17524, 16141, 16143, -1, 17537, 16141, 17524, -1, 17538, 17539, 17540, -1, 17541, 17539, 17538, -1, 17542, 17543, 17541, -1, 16154, 17543, 12082, -1, 17544, 17545, 12658, -1, 17546, 17543, 17542, -1, 12082, 17543, 17546, -1, 15759, 17547, 15757, -1, 17533, 17548, 17532, -1, 17532, 17548, 17544, -1, 17549, 17547, 15759, -1, 12656, 17550, 12654, -1, 17540, 17551, 17549, -1, 17539, 17551, 17540, -1, 17545, 17550, 12656, -1, 16152, 17552, 16154, -1, 17543, 17552, 17541, -1, 17544, 17553, 17545, -1, 17541, 17552, 17539, -1, 17548, 17553, 17544, -1, 16154, 17552, 17543, -1, 15757, 17554, 15755, -1, 12088, 17555, 12089, -1, 17534, 17555, 17533, -1, 12089, 17555, 17534, -1, 17547, 17554, 15757, -1, 17533, 17555, 17548, -1, 12654, 17556, 12652, -1, 17549, 17557, 17547, -1, 17550, 17556, 12654, -1, 17551, 17557, 17549, -1, 16150, 17558, 16152, -1, 17539, 17558, 17551, -1, 16152, 17558, 17552, -1, 17552, 17558, 17539, -1, 17553, 17559, 17545, -1, 17545, 17559, 17550, -1, 15755, 17560, 15753, -1, 12087, 17561, 12088, -1, 15753, 17560, 15752, -1, 12088, 17561, 17555, -1, 17555, 17561, 17548, -1, 15752, 17560, 17535, -1, 17548, 17561, 17553, -1, 17554, 17560, 15755, -1, 12652, 17562, 12650, -1, 17547, 17563, 17554, -1, 17557, 17563, 17547, -1, 17556, 17562, 12652, -1, 16150, 17564, 17558, -1, 17559, 17565, 17550, -1, 16148, 17564, 16150, -1, 17551, 17564, 17557, -1, 17558, 17564, 17551, -1, 17550, 17565, 17556, -1, 17535, 17566, 17536, -1, 12086, 17567, 12087, -1, 17560, 17566, 17535, -1, 17563, 17566, 17554, -1, 17553, 17567, 17559, -1, 17554, 17566, 17560, -1, 17561, 17567, 17553, -1, 17557, 17568, 17563, -1, 12087, 17567, 17561, -1, 12650, 17569, 12648, -1, 16146, 17568, 16148, -1, 17564, 17568, 17557, -1, 16148, 17568, 17564, -1, 17562, 17569, 12650, -1, 17566, 17570, 17536, -1, 17537, 17570, 16145, -1, 17536, 17570, 17537, -1, 16145, 17570, 16146, -1, 17565, 17571, 17556, -1, 16146, 17570, 17568, -1, 17568, 17570, 17563, -1, 17563, 17570, 17566, -1, 17556, 17571, 17562, -1, 12085, 17572, 12086, -1, 17559, 17572, 17565, -1, 12086, 17572, 17567, -1, 17567, 17572, 17559, -1, 12648, 17573, 12647, -1, 17569, 17573, 12648, -1, 17562, 17574, 17569, -1, 17571, 17574, 17562, -1, 17572, 17575, 17565, -1, 12084, 17575, 12085, -1, 12085, 17575, 17572, -1, 17565, 17575, 17571, -1, 17573, 17538, 12647, -1, 12647, 17538, 15763, -1, 17574, 17542, 17569, -1, 17569, 17542, 17573, -1, 17575, 17576, 17571, -1, 17571, 17576, 17574, -1, 12084, 17576, 17575, -1, 12083, 17576, 12084, -1, 15763, 17540, 15761, -1, 17538, 17540, 15763, -1, 17542, 17541, 17573, -1, 17573, 17541, 17538, -1, 17576, 17546, 17574, -1, 17574, 17546, 17542, -1, 12082, 17546, 12083, -1, 12083, 17546, 17576, -1, 15761, 17549, 15759, -1, 16145, 16141, 17537, -1, 12661, 17544, 12658, -1, 17540, 17549, 15761, -1, 17532, 17544, 12661, -1, 12658, 17545, 12656, -1, 17577, 17578, 17579, -1, 15771, 17580, 15772, -1, 17581, 17582, 15776, -1, 17583, 17584, 17585, -1, 17586, 17580, 15771, -1, 17579, 17587, 17586, -1, 17585, 17584, 17581, -1, 16167, 17588, 16165, -1, 17589, 17588, 17583, -1, 16165, 17588, 17590, -1, 17578, 17587, 17579, -1, 17590, 17588, 17589, -1, 15778, 17591, 15779, -1, 17592, 17593, 17594, -1, 15779, 17591, 15781, -1, 16157, 17593, 17592, -1, 15781, 17591, 17595, -1, 17594, 17593, 17578, -1, 17582, 17591, 15778, -1, 15772, 17596, 15768, -1, 17581, 17597, 17582, -1, 17580, 17596, 15772, -1, 17584, 17597, 17581, -1, 17586, 17598, 17580, -1, 17588, 17599, 17583, -1, 17587, 17598, 17586, -1, 16169, 17599, 16167, -1, 17583, 17599, 17584, -1, 16167, 17599, 17588, -1, 17595, 17600, 17601, -1, 16158, 17602, 16157, -1, 16157, 17602, 17593, -1, 17593, 17602, 17578, -1, 17578, 17602, 17587, -1, 17582, 17600, 17591, -1, 17597, 17600, 17582, -1, 15768, 17603, 15769, -1, 16156, 16157, 17592, -1, 17591, 17600, 17595, -1, 17584, 17604, 17597, -1, 16171, 17604, 16169, -1, 17596, 17603, 15768, -1, 17599, 17604, 17584, -1, 16169, 17604, 17599, -1, 17605, 17606, 16173, -1, 17601, 17606, 17605, -1, 16173, 17606, 16171, -1, 17580, 17607, 17596, -1, 17600, 17606, 17601, -1, 17604, 17606, 17597, -1, 17597, 17606, 17600, -1, 16171, 17606, 17604, -1, 17598, 17607, 17580, -1, 17587, 17608, 17598, -1, 16159, 17608, 16158, -1, 16158, 17608, 17602, -1, 17602, 17608, 17587, -1, 15769, 17609, 15770, -1, 17603, 17609, 15769, -1, 17596, 17610, 17603, -1, 17607, 17610, 17596, -1, 16160, 17611, 16159, -1, 16159, 17611, 17608, -1, 17598, 17611, 17607, -1, 17608, 17611, 17598, -1, 15770, 17612, 15773, -1, 17609, 17612, 15770, -1, 17610, 17613, 17603, -1, 17603, 17613, 17609, -1, 17607, 17614, 17610, -1, 16161, 17614, 16160, -1, 16160, 17614, 17611, -1, 17611, 17614, 17607, -1, 15773, 17615, 15774, -1, 17612, 17615, 15773, -1, 17613, 17616, 17609, -1, 17609, 17616, 17612, -1, 17610, 17617, 17613, -1, 16161, 17617, 17614, -1, 16162, 17617, 16161, -1, 17614, 17617, 17610, -1, 15774, 17585, 15775, -1, 17615, 17585, 15774, -1, 17616, 17589, 17612, -1, 17612, 17589, 17615, -1, 17613, 17618, 17616, -1, 17617, 17618, 17613, -1, 16163, 17618, 16162, -1, 16162, 17618, 17617, -1, 15775, 17581, 15776, -1, 16173, 16140, 17605, -1, 17585, 17581, 15775, -1, 15780, 17579, 15777, -1, 17577, 17579, 15780, -1, 17589, 17583, 17615, -1, 15777, 17586, 15771, -1, 17615, 17583, 17585, -1, 16165, 17590, 16163, -1, 17618, 17590, 17616, -1, 17579, 17586, 15777, -1, 16163, 17590, 17618, -1, 17616, 17590, 17589, -1, 15776, 17582, 15778, -1, 17594, 17578, 17577, -1, 16140, 16142, 17605, -1, 17605, 17619, 17601, -1, 16142, 17619, 17605, -1, 17601, 17620, 17595, -1, 17619, 17620, 17601, -1, 17595, 17621, 15781, -1, 17620, 17621, 17595, -1, 17621, 15782, 15781, -1, 11155, 16156, 11153, -1, 11153, 17592, 11149, -1, 16156, 17592, 11153, -1, 11149, 17594, 11139, -1, 17592, 17594, 11149, -1, 11139, 17577, 11137, -1, 17594, 17577, 11139, -1, 17577, 15780, 11137, -1, 17622, 17623, 17624, -1, 15787, 17625, 15788, -1, 15788, 17625, 11158, -1, 11158, 17625, 11156, -1, 17626, 17625, 15787, -1, 15782, 17621, 15784, -1, 17627, 17628, 17626, -1, 17629, 17628, 17627, -1, 16153, 17630, 16151, -1, 16151, 17630, 17623, -1, 17624, 17630, 17629, -1, 17623, 17630, 17624, -1, 11156, 17631, 11162, -1, 17625, 17631, 11156, -1, 17626, 17631, 17625, -1, 17628, 17631, 17626, -1, 16155, 17632, 16153, -1, 16153, 17632, 17630, -1, 17629, 17632, 17628, -1, 17630, 17632, 17629, -1, 11162, 17633, 11169, -1, 17631, 17633, 11162, -1, 11169, 17633, 16155, -1, 16155, 17633, 17632, -1, 17628, 17633, 17631, -1, 17632, 17633, 17628, -1, 16155, 11168, 11169, -1, 17621, 17634, 15784, -1, 15784, 17635, 15783, -1, 17634, 17635, 15784, -1, 17620, 17636, 17621, -1, 17621, 17636, 17634, -1, 15783, 17637, 15785, -1, 17635, 17637, 15783, -1, 17636, 17622, 17634, -1, 17634, 17622, 17635, -1, 16147, 17638, 16144, -1, 16144, 17638, 16142, -1, 17619, 17638, 17620, -1, 16142, 17638, 17619, -1, 17620, 17638, 17636, -1, 15785, 17627, 15786, -1, 17637, 17627, 15785, -1, 17622, 17624, 17635, -1, 17635, 17624, 17637, -1, 16149, 17639, 16147, -1, 16147, 17639, 17638, -1, 17638, 17639, 17636, -1, 17636, 17639, 17622, -1, 15786, 17626, 15787, -1, 17627, 17626, 15786, -1, 17637, 17629, 17627, -1, 17624, 17629, 17637, -1, 16151, 17623, 16149, -1, 16149, 17623, 17639, -1, 17639, 17623, 17622, -1, 16237, 16241, 17640, -1, 16241, 17641, 17640, -1, 17640, 17642, 17643, -1, 17641, 17642, 17640, -1, 17643, 17644, 17645, -1, 17645, 17644, 15715, -1, 17642, 17644, 17643, -1, 17644, 15719, 15715, -1, 16241, 16242, 17641, -1, 16243, 11090, 11071, -1, 17644, 17646, 15719, -1, 15719, 17646, 15720, -1, 17642, 17647, 17644, -1, 17644, 17647, 17646, -1, 15720, 17648, 15721, -1, 15721, 17648, 11120, -1, 11120, 17648, 11118, -1, 17646, 17648, 15720, -1, 17641, 17649, 17642, -1, 17642, 17649, 17647, -1, 16242, 17649, 17641, -1, 11118, 17650, 11073, -1, 17647, 17650, 17646, -1, 17648, 17650, 11118, -1, 17646, 17650, 17648, -1, 16243, 17651, 16242, -1, 11073, 17651, 11071, -1, 17650, 17651, 11073, -1, 16242, 17651, 17649, -1, 17649, 17651, 17647, -1, 17647, 17651, 17650, -1, 11071, 17651, 16243, -1, 17652, 17653, 17654, -1, 17655, 17656, 15717, -1, 16225, 17653, 17652, -1, 17657, 17658, 15713, -1, 15713, 17658, 15714, -1, 17659, 17660, 17661, -1, 17661, 17660, 17655, -1, 15716, 17661, 15717, -1, 15710, 17662, 15708, -1, 17663, 17664, 17657, -1, 17656, 17662, 15710, -1, 17665, 17664, 17663, -1, 16229, 17666, 16227, -1, 17667, 17666, 17665, -1, 16227, 17666, 17653, -1, 17655, 17668, 17656, -1, 17653, 17666, 17667, -1, 17660, 17668, 17655, -1, 15714, 17669, 15718, -1, 17670, 17671, 17659, -1, 17645, 17669, 17643, -1, 15718, 17669, 17645, -1, 17659, 17671, 17660, -1, 17658, 17669, 15714, -1, 16215, 17671, 17670, -1, 15708, 17672, 15709, -1, 17664, 17673, 17657, -1, 17657, 17673, 17658, -1, 17662, 17672, 15708, -1, 17656, 17674, 17662, -1, 16231, 17675, 16229, -1, 17665, 17675, 17664, -1, 17668, 17674, 17656, -1, 16214, 16215, 17670, -1, 17666, 17675, 17665, -1, 16229, 17675, 17666, -1, 17671, 17676, 17660, -1, 17643, 17677, 17640, -1, 16216, 17676, 16215, -1, 17658, 17677, 17669, -1, 17660, 17676, 17668, -1, 17669, 17677, 17643, -1, 16215, 17676, 17671, -1, 17673, 17677, 17658, -1, 16233, 17678, 16231, -1, 16231, 17678, 17675, -1, 15709, 17679, 15706, -1, 17664, 17678, 17673, -1, 17672, 17679, 15709, -1, 17675, 17678, 17664, -1, 16237, 17680, 16235, -1, 16235, 17680, 16233, -1, 16233, 17680, 17678, -1, 17640, 17680, 16237, -1, 17677, 17680, 17640, -1, 17673, 17680, 17677, -1, 17678, 17680, 17673, -1, 17662, 17681, 17672, -1, 17674, 17681, 17662, -1, 16217, 17682, 16216, -1, 16216, 17682, 17676, -1, 17676, 17682, 17668, -1, 17668, 17682, 17674, -1, 15706, 17683, 15707, -1, 17679, 17683, 15706, -1, 17672, 17684, 17679, -1, 17681, 17684, 17672, -1, 16219, 17685, 16217, -1, 17674, 17685, 17681, -1, 17682, 17685, 17674, -1, 16217, 17685, 17682, -1, 15707, 17686, 15705, -1, 17683, 17686, 15707, -1, 17684, 17687, 17679, -1, 17679, 17687, 17683, -1, 17681, 17688, 17684, -1, 16221, 17688, 16219, -1, 16219, 17688, 17685, -1, 17685, 17688, 17681, -1, 17686, 17689, 15705, -1, 15705, 17689, 15712, -1, 17687, 17654, 17683, -1, 17683, 17654, 17686, -1, 16223, 17690, 16221, -1, 16221, 17690, 17688, -1, 17684, 17690, 17687, -1, 17688, 17690, 17684, -1, 15718, 17645, 15715, -1, 17689, 17663, 15712, -1, 15712, 17663, 15711, -1, 17654, 17667, 17686, -1, 17686, 17667, 17689, -1, 16223, 17652, 17690, -1, 16225, 17652, 16223, -1, 17690, 17652, 17687, -1, 17687, 17652, 17654, -1, 15711, 17657, 15713, -1, 17663, 17657, 15711, -1, 17661, 17655, 15717, -1, 17667, 17665, 17689, -1, 17689, 17665, 17663, -1, 15717, 17656, 15710, -1, 16227, 17653, 16225, -1, 17654, 17653, 17667, -1, 11116, 16214, 11117, -1, 11117, 17670, 11127, -1, 16214, 17670, 11117, -1, 11127, 17659, 11113, -1, 17670, 17659, 11127, -1, 11113, 17661, 11111, -1, 17659, 17661, 11113, -1, 17661, 15716, 11111, -1, 11057, 11059, 12686, -1, 12686, 11059, 17691, -1, 17691, 11066, 17692, -1, 11059, 11066, 17691, -1, 17692, 11067, 17693, -1, 11066, 11067, 17692, -1, 17693, 11069, 12077, -1, 11067, 11069, 17693, -1, 17694, 17695, 17696, -1, 17697, 17695, 17694, -1, 17691, 17698, 12686, -1, 17692, 17698, 17691, -1, 17699, 17700, 17697, -1, 12684, 17701, 12681, -1, 12069, 17700, 12070, -1, 12070, 17700, 17702, -1, 17702, 17700, 17699, -1, 17698, 17701, 12684, -1, 12665, 17703, 12663, -1, 17693, 17704, 17692, -1, 17705, 17703, 12665, -1, 17692, 17704, 17698, -1, 12681, 17706, 12679, -1, 17696, 17707, 17705, -1, 17695, 17707, 17696, -1, 17701, 17706, 12681, -1, 12068, 17708, 12069, -1, 17704, 17709, 17698, -1, 17700, 17708, 17697, -1, 17698, 17709, 17701, -1, 12069, 17708, 17700, -1, 17697, 17708, 17695, -1, 12663, 17710, 15670, -1, 12076, 17711, 17693, -1, 17693, 17711, 17704, -1, 17703, 17710, 12663, -1, 12679, 17712, 12677, -1, 12077, 12076, 17693, -1, 17705, 17713, 17703, -1, 17706, 17712, 12679, -1, 17707, 17713, 17705, -1, 12067, 17714, 12068, -1, 12068, 17714, 17708, -1, 17695, 17714, 17707, -1, 17709, 17715, 17701, -1, 17708, 17714, 17695, -1, 17701, 17715, 17706, -1, 15670, 17716, 15668, -1, 17704, 17717, 17709, -1, 15668, 17716, 17718, -1, 12075, 17717, 12076, -1, 17711, 17717, 17704, -1, 17710, 17716, 15670, -1, 12076, 17717, 17711, -1, 12677, 17719, 12675, -1, 17703, 17720, 17710, -1, 17713, 17720, 17703, -1, 17712, 17719, 12677, -1, 16244, 17721, 12066, -1, 12066, 17721, 12067, -1, 17706, 17722, 17712, -1, 12067, 17721, 17714, -1, 17707, 17721, 17713, -1, 17714, 17721, 17707, -1, 17715, 17722, 17706, -1, 17718, 17723, 17724, -1, 17710, 17723, 17716, -1, 12074, 17725, 12075, -1, 17720, 17723, 17710, -1, 17716, 17723, 17718, -1, 17709, 17725, 17715, -1, 17717, 17725, 17709, -1, 16240, 17726, 16244, -1, 12075, 17725, 17717, -1, 17713, 17726, 17720, -1, 12675, 17727, 12673, -1, 17721, 17726, 17713, -1, 16244, 17726, 17721, -1, 17728, 17729, 16240, -1, 17719, 17727, 12675, -1, 17724, 17729, 17728, -1, 16240, 17729, 17726, -1, 17720, 17729, 17723, -1, 17726, 17729, 17720, -1, 17723, 17729, 17724, -1, 17722, 17730, 17712, -1, 17712, 17730, 17719, -1, 12073, 17731, 12074, -1, 17715, 17731, 17722, -1, 12074, 17731, 17725, -1, 17725, 17731, 17715, -1, 12673, 17732, 12671, -1, 17727, 17732, 12673, -1, 17719, 17733, 17727, -1, 17730, 17733, 17719, -1, 17731, 17734, 17722, -1, 12072, 17734, 12073, -1, 12073, 17734, 17731, -1, 17722, 17734, 17730, -1, 12671, 17694, 12669, -1, 17732, 17694, 12671, -1, 17733, 17699, 17727, -1, 17727, 17699, 17732, -1, 17734, 17735, 17730, -1, 17730, 17735, 17733, -1, 12072, 17735, 17734, -1, 15668, 17718, 15667, -1, 12071, 17735, 12072, -1, 12669, 17696, 12667, -1, 17694, 17696, 12669, -1, 17699, 17697, 17732, -1, 17732, 17697, 17694, -1, 17735, 17702, 17733, -1, 17733, 17702, 17699, -1, 12070, 17702, 12071, -1, 12071, 17702, 17735, -1, 12667, 17705, 12665, -1, 17696, 17705, 12667, -1, 16240, 16239, 17728, -1, 12686, 17698, 12684, -1, 15696, 17736, 15693, -1, 17737, 17736, 15696, -1, 15673, 17738, 15700, -1, 17739, 17740, 17737, -1, 17741, 17740, 17739, -1, 16234, 17742, 16236, -1, 17743, 17742, 17744, -1, 17744, 17742, 17741, -1, 16236, 17742, 17743, -1, 15693, 17745, 15691, -1, 17736, 17745, 15693, -1, 17740, 17746, 17737, -1, 17737, 17746, 17736, -1, 16232, 17747, 16234, -1, 16234, 17747, 17742, -1, 17742, 17747, 17741, -1, 17741, 17747, 17740, -1, 15691, 17748, 15689, -1, 17745, 17748, 15691, -1, 17736, 17749, 17745, -1, 17746, 17749, 17736, -1, 16230, 17750, 16232, -1, 17747, 17750, 17740, -1, 16232, 17750, 17747, -1, 17740, 17750, 17746, -1, 15689, 17751, 15687, -1, 17748, 17751, 15689, -1, 17745, 17752, 17748, -1, 17749, 17752, 17745, -1, 16228, 17753, 16230, -1, 17746, 17753, 17749, -1, 17750, 17753, 17746, -1, 16230, 17753, 17750, -1, 15687, 17754, 15685, -1, 17751, 17754, 15687, -1, 17748, 17755, 17751, -1, 17752, 17755, 17748, -1, 16228, 17756, 17753, -1, 16226, 17756, 16228, -1, 17749, 17756, 17752, -1, 17753, 17756, 17749, -1, 15685, 17757, 15683, -1, 17754, 17757, 15685, -1, 17751, 17758, 17754, -1, 17755, 17758, 17751, -1, 16224, 17759, 16226, -1, 17752, 17759, 17755, -1, 17756, 17759, 17752, -1, 16226, 17759, 17756, -1, 15683, 17760, 15680, -1, 15680, 17760, 11053, -1, 11053, 17760, 11051, -1, 17757, 17760, 15683, -1, 17754, 17761, 17757, -1, 16218, 11063, 11064, -1, 17762, 17763, 17738, -1, 17758, 17761, 17754, -1, 17738, 17763, 15700, -1, 16222, 17764, 16224, -1, 16224, 17764, 17759, -1, 17755, 17764, 17758, -1, 15700, 17739, 15698, -1, 17759, 17764, 17755, -1, 17761, 17765, 17757, -1, 17763, 17739, 15700, -1, 11051, 17765, 11055, -1, 17760, 17765, 11051, -1, 17757, 17765, 17760, -1, 17766, 17744, 17762, -1, 16220, 17767, 16222, -1, 16222, 17767, 17764, -1, 17762, 17744, 17763, -1, 17758, 17767, 17761, -1, 17764, 17767, 17758, -1, 15698, 17737, 15696, -1, 16218, 17768, 16220, -1, 17739, 17737, 15698, -1, 11055, 17768, 11064, -1, 16220, 17768, 17767, -1, 17761, 17768, 17765, -1, 17765, 17768, 11055, -1, 17767, 17768, 17761, -1, 11064, 17768, 16218, -1, 17763, 17741, 17739, -1, 17744, 17741, 17763, -1, 16236, 17743, 16238, -1, 16238, 17743, 17766, -1, 17766, 17743, 17744, -1, 15673, 15667, 17738, -1, 17738, 17718, 17762, -1, 15667, 17718, 17738, -1, 17762, 17724, 17766, -1, 17718, 17724, 17762, -1, 17766, 17728, 16238, -1, 17724, 17728, 17766, -1, 17728, 16239, 16238, -1, 16009, 12199, 12201, -1, 16009, 16007, 12199, -1, 16007, 12197, 12199, -1, 16007, 16008, 12197, -1, 12197, 16032, 12195, -1, 16008, 16032, 12197, -1, 12195, 16031, 12193, -1, 16032, 16031, 12195, -1, 12193, 16034, 12191, -1, 16031, 16034, 12193, -1, 12191, 16038, 12189, -1, 16034, 16038, 12191, -1, 12189, 11027, 11029, -1, 16038, 11027, 12189, -1, 16000, 16064, 16001, -1, 16000, 15997, 16064, -1, 15997, 16062, 16064, -1, 15997, 15999, 16062, -1, 16062, 16045, 16060, -1, 15999, 16045, 16062, -1, 16060, 16043, 16058, -1, 16045, 16043, 16060, -1, 16058, 16041, 16056, -1, 16043, 16041, 16058, -1, 16056, 16039, 16054, -1, 16041, 16039, 16056, -1, 16054, 16036, 16052, -1, 16039, 16036, 16054, -1, 16052, 16035, 16050, -1, 16036, 16035, 16052, -1, 16050, 16027, 16048, -1, 16035, 16027, 16050, -1, 16048, 16044, 16046, -1, 16027, 16044, 16048, -1, 16046, 16042, 12246, -1, 16044, 16042, 16046, -1, 12246, 16040, 12244, -1, 16042, 16040, 12246, -1, 12244, 16037, 12242, -1, 16040, 16037, 12244, -1, 12242, 16033, 12240, -1, 16037, 16033, 12242, -1, 12240, 16030, 12238, -1, 16033, 16030, 12240, -1, 16030, 12236, 12238, -1, 16030, 16013, 12236, -1, 16013, 16016, 12236, -1, 16016, 12234, 12236, -1, 16016, 16015, 12234, -1, 16015, 12230, 12234, -1, 16020, 16086, 16021, -1, 16020, 16017, 16086, -1, 16017, 16084, 16086, -1, 16084, 16019, 10993, -1, 16017, 16019, 16084, -1, 16019, 16029, 10993, -1, 16029, 16028, 10993, -1, 16028, 10991, 10993, -1 - ] - } - } - ] - } - ] - name "wheel_respondable_fr" - contactMaterial "wheel" - boundingObject Transform { - rotation 1 0 0 1.57 - children [ - Cylinder { - height 0.149 - radius 0.165 - } - ] - } - physics DEF WHEEL_PHY Physics { - mass 3 - } - } - } - ] - } - DEF TR_JOINT_FL Transform { - translation -0.324 0 0.292 - rotation 1 0 0 0 - children [ - DEF JOINT_FL HingeJoint { - jointParameters HingeJointParameters { - axis 0 0 1 - suspensionSpringConstant 6000 - suspensionDampingConstant 150 - suspensionAxis 0 1 0 - } - device [ - RotationalMotor { - name "motor_fl" - controlPID 20 5 0 - maxTorque 500 - } - ] - endPoint DEF WHEEL_FL Solid { - rotation 0 0 1 0 - children [ - DEF LEFT_WHEEL_SHAPE Group { - children [ - DEF fl_wheel Shape { - appearance Appearance { - material Material { - } - texture ImageTexture { - url [ - "textures/asphalt.jpg" - ] - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.13554032 0.042892486 -0.069771945, -0.13278334 0.042058975 -0.07449767, -0.13335431 0.04021138 -0.074497819, -0.13218661 0.043898523 -0.074497566, -0.13925236 0.039888561 -0.064937249, -0.13869464 0.041784704 -0.064938679, -0.13666767 0.039148569 -0.069772959, -0.14164935 0.040574759 -0.059997752, -0.13611104 0.041042268 -0.069772899, -0.13389988 0.038356006 -0.074497938, -0.14817573 0.060243756 -0.016996697, -0.14594704 0.064170331 -0.020797655, -0.14825685 0.058705956 -0.020628884, 0.13666762 -0.039140821 -0.069777295, 0.13393643 -0.038219571 -0.074502245, 0.13395455 -0.038155437 -0.074502215, 0.13391796 -0.038283706 -0.074502155, 0.13389963 -0.038347721 -0.07450217, -0.14909324 0.042705834 -0.040051565, -0.14819241 0.046369255 -0.039422408, -0.1475607 0.042267174 -0.044997826, 0.13771939 -0.036958605 -0.069033593, 0.13925223 -0.039881289 -0.064941689, -0.14345326 0.073058277 0.0020038933, -0.14103131 0.077660888 4.2468309e-06, -0.14345327 0.073058575 -0.0019960552, 0.020898819 0.15135729 -0.046991527, 0.024799153 0.15215829 -0.042991549, 0.024571344 0.1508047 -0.046991751, 0.13993701 -0.036142439 -0.065544888, 0.14164935 -0.040568203 -0.06000255, -0.13753253 0.08166939 0.017004579, -0.13583022 0.085291982 0.013004795, -0.13791397 0.081879884 0.013004556, -0.13545687 0.08506763 0.017004654, 0.13861465 -0.027830034 -0.071102202, 0.13627002 -0.028814107 -0.074501604, 0.1366699 -0.026853949 -0.074501753, -0.14959304 0.045271248 -0.035819575, 0.087965667 0.11697873 0.062006518, 0.090716928 0.11485842 0.062006265, 0.089132324 0.11850455 0.058006585, 0.14205039 -0.03527382 -0.062002093, -0.14220916 0.075014353 0.0077889264, -0.13944793 0.080090821 0.0072359145, -0.14028604 0.078902602 0.0036228746, 0.14389773 -0.035803288 -0.058002234, 0.14380684 -0.041186571 -0.055083603, 0.086273596 0.12060151 0.058006689, 0.034714594 0.15428767 -0.027991667, 0.038278028 0.1525287 -0.031991601, 0.034502357 0.15342689 -0.031991526, 0.038522214 0.15338138 -0.027991652, 0.14571019 -0.038699001 -0.052290887, 0.14577833 -0.041751444 -0.050081119, 0.044107348 0.15399489 -0.014991507, 0.049138904 0.15267706 -0.012991533, 0.049019083 0.15225857 -0.016991571, 0.14669307 -0.040488541 -0.048667386, 0.047844753 0.15339336 -0.0093877614, 0.14471261 -0.032352716 -0.058002219, 0.14284754 -0.031893045 -0.062001884, -0.14857818 0.060409635 -0.012996644, -0.14742215 0.064167142 -0.0077834278, -0.14660823 0.065393388 -0.011392683, 0.081380531 0.1293118 0.047007218, 0.084499568 0.12729558 0.047007143, 0.085249811 0.12844557 0.043007016, 0.082087263 0.13048923 0.043007195, 0.14756076 -0.042262197 -0.04500252, 0.071686715 0.14096048 0.028007776, 0.076076716 0.13815221 0.030007631, 0.073297709 0.14090925 0.024417609, 0.1454449 -0.028883785 -0.058001712, 0.14356416 -0.028494149 -0.062001541, -0.15044673 0.043093204 -0.03504914, -0.14523287 0.06945318 0.0020036697, -0.14523289 0.069453388 -0.001996249, 0.14345634 -0.020061165 -0.064939141, 0.14420006 -0.02507925 -0.062001511, 0.14052579 -0.021528095 -0.069772333, 0.14993545 -0.040556341 -0.039266706, 0.14909342 -0.042701483 -0.040056452, 0.14609383 -0.025398254 -0.058001503, 0.02107586 0.15271845 -0.042991504, 0.15044667 -0.04308939 -0.035053894, 0.059181795 0.14938498 0.0094028711, 0.064662397 0.14710781 0.0092396438, 0.063410446 0.14786273 0.0056267977, 0.017213807 0.1518206 -0.046991602, 0.08516486 0.11903337 0.062006474, 0.15128353 -0.039436728 -0.03564772, 0.15161885 -0.043425471 -0.030002415, 0.060408995 0.14857736 0.013008088, 0.14168561 -0.011649013 -0.069774926, 0.13881764 -0.011382937 -0.074500799, 0.13896696 -0.0093879402 -0.074500531, 0.13863975 -0.013375521 -0.074500963, 0.030885428 0.15509966 -0.027991399, 0.030705824 0.15423155 -0.031991482, 0.13908741 -0.0073909461 -0.074500665, 0.071258783 0.14018333 0.032007858, 0.14617674 -0.018516511 -0.060001045, -0.15161888 0.043428481 -0.029997587, 0.14842112 -0.021210849 -0.054290697, 0.14740059 -0.027062029 -0.054442555, -0.15099043 0.052794695 -0.016997069, -0.15003757 0.056687415 -0.012996987, -0.14962953 0.056536794 -0.016997024, 0.15252692 -0.038276345 -0.032002062, 0.078213438 0.13125166 0.047007203, -0.14692219 0.065804809 0.0020035803, -0.14692208 0.065805018 -0.0019963235, 0.078875959 0.13245502 0.043007255, 0.14967042 -0.022891164 -0.050667137, 0.15337974 -0.038520783 -0.028002411, 0.15258627 -0.043702751 -0.025033712, 0.022819921 0.15422142 -0.037255704, 0.026890397 0.15494227 -0.031991512, 0.028930813 0.1530329 -0.037813976, -0.14851953 0.06211552 -0.0019966662, 0.068176135 0.14269152 0.02800785, -0.14982267 0.058425605 -0.0072259158, 0.14249147 -0.0053864419 -0.069032088, -0.0037086755 0.14133686 -0.071092457, -0.0022272468 0.13927013 -0.074492425, -0.0042272657 0.13922378 -0.07449232, 0.1538222 -0.041041195 -0.022250384, 0.15337832 -0.043929964 -0.020031631, -0.0062263906 0.1391488 -0.074492246, -0.10143235 0.095450014 0.074505299, -0.10005088 0.096896827 0.074505404, -0.10350899 0.097446233 0.069779575, 0.01733999 0.15318757 -0.042991564, -0.11634289 0.091936797 0.058005258, -0.11267671 0.093413651 0.062005237, -0.11411156 0.0946922 0.058005393, 0.15135479 -0.020896226 -0.047001332, 0.15215592 -0.024796903 -0.043001622, 0.1508022 -0.024568915 -0.047001481, 0.072596163 0.13778552 0.037827775, -0.15140422 0.052929968 -0.012997136, 0.076936319 0.1366891 0.033654675, 0.15396123 -0.042585731 -0.018634439, 0.15428616 -0.034713 -0.028002188, 0.15342516 -0.034500688 -0.032001898, 0.15399411 -0.044106692 -0.015002578, -0.15258631 0.043705374 -0.02502887, -0.1521437 0.046573788 -0.022798881, -0.15193456 0.045013458 -0.026405692, 0.060242847 0.14817467 0.017008185, 0.063553199 0.14596745 0.022253871, 0.06508261 0.14588246 0.018638402, 0.013518691 0.15219417 -0.046991482, 0.15271604 -0.02107349 -0.043001339, -0.14851959 0.062115312 0.0020033568, 0.15181816 -0.017211318 -0.047001138, 0.027037621 0.15581653 -0.027991474, -0.10279296 0.093983293 0.074505255, 0.15509795 -0.030883968 -0.02800186, 0.1542298 -0.030704021 -0.032001778, 0.067777634 0.14189908 0.032007888, -0.10659803 0.092871845 0.071103618, -0.10683158 0.097817183 0.064946443, -0.10899301 0.093154162 0.067647919, 0.064623684 0.14433518 0.028007984, 0.15421933 -0.02281782 -0.037265539, 0.15494052 -0.026888728 -0.032001495, 0.15303083 -0.028928638 -0.037824064, -0.11486185 0.090713352 0.062005118, -0.11850764 0.08912912 0.058004826, 0.14133295 0.0037125349 -0.071100533, 0.13926606 0.0022314489 -0.07449986, 0.13921963 0.0042314231 -0.07449998, 0.13914463 0.0062304437 -0.074499577, 0.15318535 -0.01733771 -0.043001205, 0.0215455 0.15537098 -0.033636585, 0.15510046 -0.042022705 -0.0092316568, 0.15442844 -0.044231206 -0.01001361, -0.15337825 0.043931961 -0.020026788, -0.15225747 0.049019933 -0.016997427, -0.10413218 0.092497081 0.074505135, 0.15219159 -0.013516277 -0.047000691, -0.12729834 0.084496826 0.047004715, -0.12632778 0.08835879 0.04300487, -0.12844811 0.085247397 0.043004557, 0.15468951 -0.044306308 -0.0050112605, 0.013593674 0.15356532 -0.042991385, -0.12520689 0.087565899 0.047004804, 0.15581484 -0.02703616 -0.028001666, 0.083496973 0.11147785 0.074506164, 0.085089684 0.11026701 0.074506044, 0.085258052 0.11429197 0.069040433, 0.15536907 -0.021543652 -0.033646509, 0.15356299 -0.01359123 -0.043000862, -0.11698234 0.087962061 0.062004939, 0.15565842 -0.040679514 -0.0056189299, 0.15477636 -0.04433158 -2.6524067e-06, -0.12060489 0.086270422 0.058004871, 0.064255223 0.14352861 0.032007858, -0.15399405 0.044108152 -0.014997527, -0.1526764 0.049139768 -0.012997478, -0.15339285 0.047845185 -0.0093937218, -0.1293146 0.081377894 0.047004327, -0.13049163 0.082084864 0.043004423, 0.081887275 0.11266559 0.074506342, 0.14828432 0.00066012144 -0.057999983, 0.14825763 -0.0028852224 -0.058000281, 0.14633879 -0.0027802289 -0.062000111, 0.14636366 0.00069332123 -0.062000051, -0.1409623 0.071685165 0.028003767, -0.13815406 0.076074779 0.030004159, -0.14091064 0.073296249 0.024413764, 0.15641113 -0.020240813 -0.030001253, 0.061031833 0.14589024 0.028008029, 0.057764828 0.14825478 0.022811785, 0.15326589 -0.0083672404 -0.045000419, 0.1501282 -0.011062682 -0.052843213, 0.15202543 -0.0068309307 -0.048665598, -0.00065691769 0.14828745 -0.057991758, 0.0028883368 0.14826077 -0.057991713, 0.0027835816 0.14634225 -0.061991736, 0.15479444 -0.012226462 -0.039425597, -0.00069001317 0.1463671 -0.061991796, -0.14938557 0.059181303 0.0093977898, -0.14710832 0.064661741 0.0092349648, -0.14786309 0.063410103 0.0056220293, 0.020242333 0.15641266 -0.029991224, -0.11903681 0.085161388 0.062004626, 0.15611365 -0.039305359 -0.0020022988, -0.14857823 0.060408145 0.0130032, -0.15442859 0.044232398 -0.010008544, 0.1572312 -0.022712171 -0.024249375, 0.15624484 -0.028565735 -0.024409771, 0.15760282 -0.024241596 -0.020633429, -0.14018516 0.071256846 0.032003969, 0.0083696693 0.15326831 -0.044991583, 0.011065423 0.1501312 -0.052834332, 0.0068337321 0.15202805 -0.048656687, 0.012228593 0.15479681 -0.039416313, 0.14822614 0.0042050481 -0.057999834, 0.14630614 0.0041664243 -0.061999857, -0.13125439 0.078210771 0.047004327, -0.13245757 0.078873515 0.043004245, 0.052793846 0.15098923 0.017008424, 0.056535825 0.14962831 0.017008424, 0.056686789 0.1500369 0.013008356, 0.052929252 0.15140337 0.013008207, 0.15611352 -0.039305419 0.0019975603, 0.15468942 -0.044306874 0.0050061047, -0.15400705 0.046519279 -0.0057843477, 0.022713497 0.15723258 -0.024239495, -0.14269312 0.06817463 0.028003693, 0.028566882 0.15624607 -0.024399266, -0.13778774 0.072593987 0.037824214, -0.13669115 0.076934457 0.033651426, 0.15533599 -0.041490078 0.0077823699, 0.15442854 -0.044232428 0.010008395, 0.060693756 0.14507028 0.032008052, -0.14817567 0.060241848 0.017003372, -0.14596874 0.063551903 0.022249267, -0.14588362 0.065081537 0.018633738, 0.024242699 0.15760389 -0.020623311, -0.0042018294 0.14822933 -0.057991922, -0.0041629821 0.14630947 -0.061991781, 0.14808339 0.0077475607 -0.057999656, 0.14616601 0.0076372325 -0.06199947, -0.15468945 0.044306666 -0.0050063282, 0.15471654 -0.042814732 0.011391938, -0.14190091 0.067775875 0.032003775, 0.15704651 -0.035394818 0.0019978285, 0.15704642 -0.03539452 -0.0020019412, 0.039305344 0.15611336 0.0020085573, 0.044331446 0.15477636 8.6128712e-06, 0.039305285 0.15611371 -0.0019913018, 0.15399402 -0.044108123 0.014997333, -0.14433675 0.064622045 0.028003529, 0.15788144 -0.031461805 -0.0020018816, -0.11148193 0.083492845 0.074504465, -0.11027126 0.085085362 0.074504688, -0.11429588 0.085254073 0.069038749, -0.1547765 0.044331253 2.399087e-06, 0.14072646 0.020171225 -0.069773123, 0.13814098 0.017810315 -0.074498937, 0.13787103 0.019792408 -0.074499011, -0.14353029 0.064253449 0.032003596, -0.11266977 0.081883162 0.074504659, 0.15788135 -0.031462014 0.0019979775, -0.14589189 0.061030209 0.028003439, -0.14825603 0.057763577 0.022806987, -0.007744357 0.14808646 -0.057991773, -0.0076338053 0.14616948 -0.061991796, 0.15861784 -0.027509362 -0.0020016432, -0.15099029 0.052792877 0.01700294, -0.14962943 0.056534886 0.017003223, -0.1500378 0.056685954 0.013003305, -0.15140413 0.052928448 0.013002887, 0.15906717 -0.02362138 -0.0072305799, 0.15800427 -0.029753 -0.0077885985, -0.15468952 0.044306219 0.0050113499, -0.15377374 0.047052681 0.0072340965, -0.15432629 0.045707852 0.003621012, 0.035394624 0.15704632 0.0020086914, 0.035394564 0.15704659 -0.001991421, 0.15389045 -0.041664124 0.020801023, 0.15337832 -0.043932199 0.02002643, -0.14507224 0.060691953 0.032003358, 0.044107243 0.15399319 0.015008554, 0.049019068 0.15225655 0.017008543, 0.049139038 0.15267548 0.013008371, 0.1525863 -0.043705612 0.025028735, 0.047497362 0.15221712 0.020638779, 0.15861781 -0.02750954 0.0019981265, -0.15442859 0.044231206 0.010013357, -0.15267643 0.049138159 0.013002574, 0.1594125 -0.022214442 -0.0036181211, -0.15399402 0.044106394 0.01500228, -0.15225765 0.049017996 0.017002732, 0.057131901 0.1443826 0.039430961, 0.062627882 0.14213553 0.039274693, 0.061687246 0.1436525 0.035655275, 0.15368807 -0.040105939 0.024407536, -0.15221842 0.047496051 0.020632714, 0.15161888 -0.043428779 0.029997483, -0.020167395 0.14073017 -0.069766387, -0.017806083 0.13814515 -0.074492514, -0.01978834 0.13787514 -0.074492395, -0.14438491 0.057129562 0.039426118, -0.14213789 0.062625498 0.039270177, -0.14365457 0.061685205 0.035650641, 0.031461716 0.15788117 0.0020085275, 0.03146179 0.1578815 -0.0019911677, -0.15337831 0.043929696 0.020031378, 0.058035359 0.14282018 0.043007895, 0.062185809 0.13889134 0.048670694, 0.064022496 0.13950232 0.045007944, 0.1522104 0.013307363 -0.046999365, 0.15385942 0.0096826553 -0.04299961, 0.15248886 0.0096038878 -0.04699938, -0.14282264 0.05803284 0.043003157, -0.13889408 0.062183052 0.048666477, -0.13950481 0.064020097 0.045003429, -0.15207295 0.045949817 0.024248213, 0.15965238 -0.020788074 -1.2516975e-06, 0.1581426 0.00048923492 -0.028000131, 0.15722038 -0.0033761859 -0.032000318, 0.15725587 0.00050464272 -0.031999856, 0.15810616 -0.0034246445 -0.02800034, -0.12012969 0.07048586 0.074503779, -0.11910486 0.072203934 0.074504063, -0.12259848 0.071969986 0.069778308, 0.15994798 -0.0087338686 -0.015000552, 0.15869275 -0.011548638 -0.022802234, 0.15957735 -0.0072582066 -0.018632501, 0.15934803 -0.013908744 -0.017000854, -0.13388461 0.063742936 0.058003545, -0.13063893 0.065998554 0.062003583, -0.13232225 0.066925704 0.058003619, 0.023621708 0.15906748 -0.0072202981, 0.027509287 0.15861785 -0.0019913018, 0.029753447 0.15800464 -0.0077781826, 0.16019346 -0.01251176 -0.0093970597, 0.15978292 -0.013932675 -0.013000965, -0.14155363 0.057509273 0.04700318, -0.13817064 0.06031689 0.052289516, -0.15258634 0.043702692 0.025033683, 0.070490062 0.12012556 0.074506938, 0.072208062 0.11910069 0.074506566, 0.071973786 0.12259457 0.06978105, 0.15337978 -0.038523853 0.027997747, 0.15921792 -0.023061514 0.0057833195, 0.15826592 -0.028918177 0.0056169629, -0.12698975 0.066565186 0.06764628, -0.12592009 0.071592242 0.064944878, -0.12906997 0.07107085 0.060004056, 0.063746288 0.13388121 0.058007419, 0.066001967 0.13063556 0.062007308, 0.066929042 0.13231882 0.0580073, 0.14176209 0.028153479 -0.065541342, 0.14308761 0.022537619 -0.064939663, 0.14011839 0.026455909 -0.069030121, -0.12112975 0.068753213 0.074503794, 0.14522499 0.02490899 -0.059998661, 0.15357707 0.01343739 -0.042999387, -0.1321685 0.062879801 0.062003255, -0.13537028 0.060523957 0.058003336, 0.15880939 -0.024457306 0.0093931854, 0.057511955 0.14155096 0.047007948, 0.060319826 0.13816771 0.052293882, 0.15184213 0.01700291 -0.046999142, -0.14290972 0.054051727 0.047003075, -0.14419734 0.054527462 0.043002814, -0.15161891 0.043425232 0.03000249, 0.15808213 0.0044029057 -0.027999789, 0.1571956 0.0043852031 -0.031999931, -0.13362353 0.059725642 0.062003285, 0.1525269 -0.038279712 0.031997815, 0.15044665 -0.043093264 0.035049066, 0.027509391 0.15861759 0.0020087808, 0.066569179 0.126986 0.067649737, 0.071595952 0.12591651 0.064947844, 0.071074292 0.12906656 0.060007274, -0.13677865 0.057270169 0.058003113, 0.068757385 0.12112561 0.074506789, -0.14033066 0.054475546 0.05284822, -0.14418119 0.050562143 0.047002956, -0.14548607 0.050989658 0.043002605, 0.022214502 0.15941268 -0.0036079139, -0.15044671 0.04308936 0.035054043, -0.14904533 0.045711219 0.037268892, -0.15038382 0.044588834 0.033649549, -0.13500327 0.056537747 0.062003031, 0.15428616 -0.03471607 0.027997807, 0.13696429 0.035068959 -0.071098581, 0.13527878 0.033165127 -0.074498251, 0.13478853 0.035104662 -0.074498162, 0.062883273 0.13216496 0.062007323, 0.13427043 0.037037134 -0.074497968, -0.14536764 0.047042966 0.047002509, 0.15320303 0.017184198 -0.042999178, 0.15048718 -0.040117681 0.037817746, 0.14909329 -0.042705864 0.040051475, -0.146688 0.047421336 0.043002516, -0.14909349 0.042701393 0.040056288, 0.060527146 0.13536707 0.058007658, 0.16056281 -0.0064558387 -0.00922966, 0.16049698 -0.011082381 -0.005787611, -0.14756079 0.042262286 0.04500246, 0.15138404 0.020688474 -0.046999007, 0.054054469 0.14290693 0.047007918, -0.14448644 0.045265973 0.050666109, 0.1490764 -0.041213065 0.041420996, 0.054530054 0.14419499 0.043007851, -0.12726681 0.056592375 0.074503243, -0.12644081 0.0584144 0.074503198, -0.13040195 0.057683319 0.069037229, 0.15792473 0.0083138943 -0.027999729, 0.15703957 0.0082631111 -0.031999633, -0.12806658 0.054758638 0.07450299, 0.15342513 -0.034504324 0.031998158, -0.14577827 0.041751117 0.050080955, -0.13221128 0.052258134 0.069774151, -0.13275124 0.057142615 0.065548241, 0.14756075 -0.042267203 0.044997633, -0.14348866 0.04347226 0.054289356, 0.15509804 -0.030887067 0.027998164, -0.12883995 0.052913755 0.074502975, -0.14380692 0.041186422 0.055083573, -0.14164953 0.040568054 0.060002252, 0.13900127 -0.025829613 -0.071102068, 0.14085022 -0.026804835 -0.067646652, 0.13704149 -0.024888217 -0.074501425, 0.13738483 -0.02291733 -0.074501321, 0.14096473 -0.026194692 -0.067646548, 0.148794 -0.027650744 -0.050843284, 0.14859106 -0.028722525 -0.050843433, 0.15021853 -0.027915686 -0.047001615, 0.15025352 -0.031372249 -0.045001954, -0.013304934 0.15221304 -0.046991453, -0.0096804351 0.1538617 -0.042991534, -0.0096013248 0.15249145 -0.046991631, 0.1515682 -0.028166741 -0.043001458, 0.15169646 -0.030165315 -0.041426823, 0.15273777 0.020920515 -0.042999029, 0.1527092 -0.028379083 -0.039265946, 0.14325853 -0.0058667958 -0.067645416, 0.1445145 -0.0098674297 -0.06494154, 0.13853353 0.036962628 -0.067643225, 0.14447173 -0.0040973425 -0.06554313, 0.14624259 -0.0059892535 -0.062000379, 0.14712608 -0.0080311596 -0.060000524, 0.020787776 0.15965235 8.7618828e-06, 0.14816149 -0.0060681105 -0.058000565, 0.14868599 -0.0095420182 -0.056442201, 0.14973904 -0.0061330199 -0.054441273, 0.15066895 -0.0053051412 -0.05228883, 0.059729204 0.13362002 0.062007323, 0.14117359 0.0076693892 -0.071100265, 0.14328428 0.0052093863 -0.067644835, 0.1390408 0.0082283914 -0.074499592, 0.14179368 0.010281682 -0.069770798, 0.15685974 -0.02915141 -0.020030707, 0.15786584 -0.025759429 -0.01700151, 0.15685759 -0.032485485 -0.015001833, 0.15656663 -0.030082941 -0.020803049, 0.14807245 0.028354973 -0.052286938, 0.14882652 0.022621393 -0.052841425, 0.14708208 0.023783058 -0.056440338, 0.14316775 0.0077775121 -0.067644551, 0.057273403 0.13677546 0.058007449, 0.14432448 0.01236403 -0.064937398, 0.15748942 -0.029268742 -0.015001625, 0.15748361 -0.031129271 -0.011398017, 0.15829529 -0.025831908 -0.013001502, 0.14614995 0.0079391599 -0.061999589, 0.14663272 0.014475316 -0.059999362, -0.00048781931 0.15814427 -0.02799125, 0.0033778399 0.15722224 -0.031991288, -0.0005029887 0.15725777 -0.031991228, 0.1579337 -0.029351592 -0.010012537, 0.0034262091 0.15810782 -0.02799122, 0.15422975 -0.030707568 0.031998336, 0.15519394 -0.0063573718 -0.039264843, 0.15591575 -0.010844648 -0.035822734, 0.15520129 -0.0061756372 -0.039264858, 0.054478601 0.1403276 0.052852869, 0.14806761 0.0080429614 -0.057999656, 0.14942023 0.012347937 -0.054288864, 0.0087345541 0.15994874 -0.01499112, 0.011549711 0.15869397 -0.022792593, 0.0072593391 0.15957865 -0.018623099, 0.013909534 0.15934882 -0.016991168, 0.15620863 -0.0063991249 -0.035645932, 0.15626647 -0.0047841668 -0.035645694, 0.15870368 -0.021741867 -0.015001208, 0.15895249 -0.017870933 -0.017001241, 0.15938599 -0.017911106 -0.013001025, 0.15888999 -0.021878272 -0.013001412, 0.012511969 0.16019398 -0.0093872994, 0.013933301 0.15978354 -0.01299125, 0.15845832 -0.021822035 -0.01700139, 0.14964424 0.0081284344 -0.054440379, 0.1510123 0.01098752 -0.050665244, 0.050564945 0.14417845 0.047008067, 0.050992101 0.1454837 0.043008074, 0.14972755 0.0064162612 -0.054440513, 0.1398057 0.021054 -0.071099341, 0.13757274 0.021770537 -0.074498996, 0.1372458 0.023744285 -0.074498758, 0.14973438 0.027169198 -0.048663497, 0.15712482 -0.0064368844 -0.032000378, 0.15748085 -0.008598268 -0.030000538, 0.15111931 0.0082083941 -0.050841376, 0.15125759 0.0050622225 -0.050841555, 0.15581493 -0.02703926 0.027998328, 0.15801087 -0.0064733922 -0.028000578, 0.1581413 -0.010073423 -0.026408747, 0.023061186 0.15921766 0.0057936609, 0.15739292 -0.023327976 0.022802353, 0.15645085 -0.02948004 0.022244036, 0.028917909 0.15826571 0.0056273937, 0.15256616 0.0082865655 -0.046999574, 0.15346789 0.0028488934 -0.044999883, 0.1444203 0.033639967 -0.057998121, 0.14328925 0.029853016 -0.061998576, 0.14254056 0.033244908 -0.061998323, 0.14518328 0.030177563 -0.057998434, 0.15955853 -0.014165908 -0.015000939, 0.15872996 -0.0065030456 -0.024248421, 0.15909842 -0.0057836175 -0.022248387, -0.028149828 0.14176577 -0.065535218, -0.022533923 0.14309126 -0.064932913, -0.026452154 0.14012229 -0.069023743, 0.15393688 0.0083607137 -0.042999581, 0.1546059 0.0043468177 -0.041424856, -0.024905711 0.1452283 -0.059992, 0.15793374 -0.029352754 0.01000917, 0.15685757 -0.032487184 0.014998108, 0.15780881 -0.030307114 0.0092296302, 0.15829521 -0.025833398 0.012998343, -0.013435036 0.15357926 -0.042991534, 0.15509565 0.008423537 -0.039263979, 0.15563177 0.0058493018 -0.037822112, 0.1554307 0.012071341 -0.037263587, 0.15748945 -0.02927044 0.014998108, 0.15670814 -0.030989647 0.018628478, 0.1578659 -0.025761366 0.016998619, 0.15610972 0.0084785819 -0.035645127, 0.15626802 0.013569325 -0.033644587, 0.02445659 0.1588088 0.0094033629, 0.14353307 0.028657734 -0.061998501, 0.15685965 -0.029153675 0.02002731, 0.13595164 0.041576087 -0.069768891, 0.13372467 0.038961828 -0.074497834, 0.15702535 0.008528024 -0.031999558, -0.017000601 0.15184474 -0.046991527, 0.14541623 0.029033393 -0.057998449, 0.15791066 0.0085758865 -0.027999729, 0.056541324 0.13499987 0.062007546, 0.15699397 0.015071392 -0.029999435, 0.15834337 0.012844443 -0.024247438, 0.15108785 0.022751421 -0.046998858, 0.15128563 0.025947541 -0.044998616, 0.15870373 -0.021743596 0.014998764, 0.15889004 -0.021879852 0.012998581, 0.15938592 -0.017912447 0.012998968, 0.1589524 -0.01787281 0.016998827, 0.1584582 -0.021823794 0.016998768, 0.16074431 -0.0065865219 -0.0057873726, 0.16080789 -0.0050224066 -0.0056169629, 0.15862958 0.0086145401 -0.024247676, 0.15868405 0.0069182813 -0.024407804, 0.15904583 0.011436045 -0.020631552, 0.14611723 -0.039422423 0.050841883, 0.14577834 -0.041757047 0.050076395, 0.16085055 -0.0065912306 -0.0020005405, 0.1607606 -0.0087791085 -6.8545341e-07, 0.16094583 -0.0035812557 -0.0020002425, -0.0044013858 0.15808356 -0.027991369, -0.0043835044 0.15719736 -0.031991288, 0.15244524 0.022955537 -0.042998806, 0.038278013 0.15252525 0.032008544, 0.043427005 0.15161717 0.030008242, 0.038522288 0.1533781 0.028008521, 0.15494056 -0.026892275 0.031998351, 0.15363452 0.022525162 -0.0394236, 0.15931101 0.0086514056 -0.020028532, 0.15933566 0.005510658 -0.020801127, 0.15964006 0.010014921 -0.016999602, 0.1608507 -0.0065914989 0.0019995272, 0.16062784 -0.010221481 0.0036178231, 0.16094579 -0.0035814643 0.0019996166, 0.15359282 0.023128271 -0.039263129, 0.15268475 0.028514832 -0.039262712, 0.15442024 0.024121821 -0.035820886, 0.14380698 -0.04119271 0.05507879, 0.13729931 0.041311443 -0.067642838, 0.14080274 0.039970815 -0.061997727, 0.13795543 0.044169337 -0.064935625, 0.15955861 -0.014167488 0.014998913, 0.15978289 -0.013934195 0.012999147, 0.15994796 -0.0087354481 0.01499936, 0.15934801 -0.013910651 0.016999125, 0.047045603 0.14536503 0.047008112, 0.1435747 0.037083209 -0.057997957, 0.14171153 0.036618203 -0.061998084, 0.16074438 -0.0065872073 0.0057845712, 0.16038857 -0.011655927 0.0072306097, 0.04742384 0.14668548 0.04300797, 0.16036454 -0.0073136091 0.011394113, 0.16067371 -0.0058843195 0.0077843368, 0.15995058 0.0086859465 -0.014999658, 0.16046235 0.0046945214 -0.01139611, 0.16015358 0.0032331347 -0.014999956, 0.16007474 0.010039687 -0.012999564, 0.15270855 -0.028383344 0.039265245, 0.15347795 -0.02357316 0.039421469, 0.15215589 -0.024801731 0.042998463, 0.15251018 -0.029431343 0.039265156, 0.15377948 -0.028176457 0.035645798, 0.15695623 -0.021791816 0.026408613, 0.1401594 0.042171627 -0.061997712, 0.13973603 0.046741277 -0.059997424, 0.1426473 0.040505022 -0.057997942, 0.16040188 0.008710146 -0.010010481, 0.1606636 0.0061520934 -0.0077866018, 0.16033544 0.012366593 -0.0072285235, 0.15156806 -0.02817148 0.042998388, 0.15025343 -0.031377286 0.044998214, 0.14199837 0.042724699 -0.057997644, 0.14292707 0.04528746 -0.054287046, 0.16064264 0.0087229609 -0.0057865381, 0.03471446 0.15428454 0.028008565, 0.16076219 0.0084762573 -0.0019994378, 0.16035895 0.013815135 -0.0036161244, 0.15935628 0.016286701 -0.01499933, 0.15977472 0.014026612 -0.012999386, 0.15934134 0.013985515 -0.016999274, 0.15894388 0.017947525 -0.016999036, 0.15937558 0.018004775 -0.012999058, 0.15021855 -0.027921021 0.046998337, 0.15080222 -0.024574101 0.046998337, 0.14924946 -0.029722661 0.048661351, 0.14351039 0.043179393 -0.054438502, 0.14478165 0.044315606 -0.050663456, -0.035065144 0.13696808 -0.071092963, -0.033161104 0.13528299 -0.074492455, -0.035100639 0.13479263 -0.074492589, 0.14454642 0.039573103 -0.054438516, 0.16074878 0.0087284744 -0.0019996762, 0.16076225 0.0084759891 0.0020002127, -0.037032858 0.13427463 -0.074492544, 0.13090205 0.05342117 -0.071097732, 0.12927979 0.051837742 -0.074497178, 0.12852195 0.053689122 -0.074497059, 0.13001099 0.049975395 -0.074497357, 0.1307192 0.056971997 -0.069028452, 0.13271038 0.050980151 -0.069771543, -0.017181754 0.15320536 -0.042991579, 0.15421368 0.030788243 -0.031998366, 0.15544614 0.026660115 -0.02999863, 0.15341355 0.030108362 -0.035643637, 0.15403028 0.031693369 -0.031998217, 0.15490451 0.031843126 -0.027998447, 0.14886297 -0.027669162 0.050661981, 0.14893496 -0.02188918 0.052843764, 0.14812876 -0.028064579 0.052284539, 0.14492506 0.043604732 -0.050839424, 0.14652912 0.043295145 -0.046997637, 0.14633919 0.038593441 -0.050839648, 0.16074891 0.0087281168 0.0020003319, 0.16027527 0.015259266 7.1525574e-07, 0.16035753 0.01294598 0.005785346, 0.13275103 0.054175586 -0.067642063, 0.13448587 0.053812593 -0.064938068, 0.13194393 0.058992773 -0.065539733, 0.15508306 0.030961663 -0.027998447, 0.15641826 0.025368869 -0.026406795, 0.15639666 0.029764205 -0.022246361, 0.1450651 -0.037624091 0.054440632, 0.15873039 -0.006505847 0.024245292, 0.15930307 -0.0063757598 0.020803094, 0.15875889 -0.004901588 0.024409473, 0.15848522 -0.010961324 0.024245083, 0.16064262 0.0087223947 0.0057852268, 0.16073285 0.0070242286 0.0056188703, 0.0064563602 0.16056323 -0.0092202574, 0.011082828 0.16049746 -0.0057781786, 0.16026975 0.011494368 0.0093950927, 0.1584008 0.023850858 -0.014998794, 0.15719189 0.028432995 -0.018630475, 0.15788142 0.0270769 -0.014998704, 0.14164947 -0.040574968 0.059997767, 0.15844792 0.021898299 -0.016998857, 0.15728398 0.024053544 -0.022800207, 0.15887724 0.021971703 -0.012998998, -0.020686045 0.15138659 -0.046991631, 0.15801074 -0.0064764619 0.027999401, 0.15748087 -0.0086016059 0.029999405, 0.15810624 -0.0034278035 0.027999669, 0.16040187 0.0087088346 0.010011345, 0.16059592 0.0055684745 0.0092316866, 0.16007468 0.010038227 0.013000518, 0.15884762 0.023917854 -0.010009587, 0.15797397 0.029434472 -0.0092276335, 0.15893926 0.024909288 -0.0057855844, 0.15896136 0.023448318 -0.0093950033, 0.15712489 -0.0064404309 0.031999528, 0.15653576 -0.010011137 0.033646494, 0.15722036 -0.0033796132 0.031999826, 0.15995063 0.0086841881 0.015000373, 0.15967479 0.0046580434 0.018630564, 0.16015358 0.0032314062 0.015000015, 0.15964004 0.010013103 0.017000377, 0.15620817 -0.0064031184 0.035646826, 0.15548058 -0.011403739 0.037265643, 0.15450892 -0.007007122 0.041422844, -0.008312434 0.15792626 -0.02799125, 0.15564081 -0.0056254268 0.037819803, 0.14971079 0.045043796 -0.035642952, 0.15042864 0.040333927 -0.03782022, 0.14784773 0.043676913 -0.042997703, 0.14884813 0.046355307 -0.037261471, 0.14933093 0.048002094 -0.03364262, -0.0082612634 0.15704134 -0.031991243, 0.15126401 0.043000519 -0.031997681, 0.13875641 0.056625366 -0.054437801, 0.13604197 0.056600034 -0.059996977, 0.1380512 0.060593247 -0.052285224, 0.14006202 0.05517143 -0.052839562, 0.13810278 0.055915684 -0.056438461, 0.034502372 0.1534234 0.032008573, 0.12523171 0.0656223 -0.071096808, 0.12683606 0.066862494 -0.067641348, 0.12572749 0.064667344 -0.07109721, 0.12266347 0.065986484 -0.074496403, 0.12170319 0.067741394 -0.074496344, 0.12359846 0.064217955 -0.074496493, 0.1564112 -0.020244122 0.029998869, 0.12329245 0.070785791 -0.069767207, 0.14019132 -0.026058674 0.069032401, 0.14213908 -0.026177496 0.065543458, 0.14052574 -0.021535873 0.06976983, 0.13666983 -0.026862234 0.074498489, 0.13996902 -0.027227491 0.069032356, 0.13738497 -0.022925645 0.074498832, 0.13704154 -0.024896502 0.074498609, 0.15931107 0.0086490512 0.020029515, 0.04226464 0.14755824 0.045008302, 0.15908784 0.0060727 0.022246033, 0.15863742 0.012280107 0.02280423, 0.15058896 0.045307755 -0.031997561, 0.14970437 0.04962799 -0.029997349, 0.15211548 0.043247014 -0.027997732, 0.16098507 0.00043871999 0.0019998848, 0.16098496 0.00043901801 -0.0020001531, 0.14012416 0.057183206 -0.050838739, 0.13993515 0.059807062 -0.048661888, 0.030885503 0.15509641 0.028008536, 0.1429854 0.053856045 -0.046997145, 0.15143792 0.045563042 -0.027997643, 0.15151539 0.047757208 -0.024245501, 0.045268908 0.14448363 0.050671786, 0.15862997 0.0086118579 0.024246275, 0.15792474 0.008310765 0.028000325, 0.15786983 0.013680518 0.026410788, 0.14146557 0.057730466 -0.046996817, 0.14171925 0.058961242 -0.044996843, 0.14425354 0.054383367 -0.042997137, 0.15935613 0.016285151 0.01500082, 0.15934131 0.013983548 0.017000824, 0.15977472 0.014025211 0.013000518, 0.15937558 0.018003285 0.013000906, 0.15894386 0.017945617 0.017000794, 0.15541646 0.038799763 -0.014997959, 0.15539467 0.040283203 -0.011393964, 0.15541902 0.03878966 -0.014997929, 0.1541148 0.04082796 -0.020798951, 0.1534093 0.045286983 -0.016997546, 0.158971 -0.012435883 0.020629525, 0.15212746 0.045770139 -0.024245501, 0.15316644 0.042055458 -0.024405837, 0.1525137 0.046540409 -0.020629555, 0.1579107 0.008572638 0.028000325, 0.15787047 0.031516582 -0.0019984245, 0.15789367 0.030886769 -0.0056151748, 0.15770732 0.032322347 -0.0019983947, 0.15868336 0.027213693 1.4007092e-06, 0.15469213 -0.022315562 0.035818368, 0.14273664 0.058248848 -0.042996749, 0.14477085 0.056147397 -0.039421842, 0.14251199 0.061775476 -0.039260983, 0.15128501 -0.0062021911 0.050663307, 0.15326591 -0.0083722472 0.044999525, 0.15122539 -0.0059199929 0.050843909, 0.14956541 -0.010459453 0.054286346, 0.15093717 -0.011985451 0.050663039, 0.15702537 0.0085244477 0.032000273, 0.15703963 0.0082594454 0.032000363, -0.02091819 0.15274009 -0.042991534, 0.056596488 0.12726268 0.074507058, 0.058418632 0.12643653 0.074507043, 0.057687089 0.13039806 0.069041282, 0.15699379 0.015068263 0.030000746, 0.15577906 0.012666106 0.035820305, 0.15787047 0.031516373 0.0020016134, 0.15795457 0.030016422 0.007786423, 0.15887526 0.025777757 0.0036199391, 0.15770739 0.032322079 0.0020016432, 0.1438977 -0.035809696 0.057998002, 0.14381112 0.05868718 -0.039261237, 0.14518154 0.057878733 -0.035818964, 0.14980464 -0.006141901 0.05428651, 0.14979933 -0.0044007897 0.05444248, 0.15840083 0.023849189 0.015001148, 0.15844792 0.021896452 0.017001092, 0.1588771 0.021970302 0.013001174, 0.15797105 0.028554171 0.011395901, 0.15788133 0.02707541 0.015001357, -0.036958948 0.13853708 -0.067637295, 0.15896074 0.024326235 0.0072328746, 0.15610917 0.0084744096 0.03564781, 0.15619345 0.0067489743 0.035647631, 0.15487486 0.01117 0.039423615, 0.14475147 0.059070855 -0.035642177, 0.14561668 0.060581803 -0.029996574, 0.14286783 0.063491195 -0.035641909, 0.15339425 0.046150923 -0.014997482, 0.15382741 0.04540804 -0.012997568, 0.15264782 0.049228132 -0.012997389, 0.15223449 0.049091697 -0.016997278, 0.14816138 -0.0060745478 0.057999626, 0.14825749 -0.0028916299 0.057999715, 0.14712599 -0.0080378354 0.059999555, 0.15509506 0.0084190369 0.039267123, 0.15523487 0.0052433014 0.039266825, 0.15385938 0.0096778274 0.043000519, 0.12626699 0.074026853 -0.061995849, 0.1283789 0.07030043 -0.061996102, 0.12466876 0.073759973 -0.064933926, 0.12583227 0.076663703 -0.05999577, -0.028352007 0.14807546 -0.052280322, -0.022618547 0.14882946 -0.052834108, -0.023780018 0.14708516 -0.05643335, 0.1307153 0.048103094 -0.074497327, 0.13005832 0.071231604 -0.057996184, 0.1577675 0.023753315 0.020030171, 0.15695044 0.024579734 0.02424711, 0.15775234 0.023250103 0.020631492, 0.15672739 0.029232532 0.02080512, 0.13405426 0.070244044 -0.050837919, 0.13211724 0.070745528 -0.054436937, 0.13129131 0.075421542 -0.050661623, 0.13408314 0.070189267 -0.050838009, 0.13322185 0.074815452 -0.046995848, 0.1462426 -0.0059961081 0.0619995, 0.14451447 -0.0098748207 0.064940423, 0.14633885 -0.002787143 0.061999798, 0.15393685 0.0083559752 0.043000326, 0.15346782 0.0028439462 0.045000136, 0.03070575 0.15422809 0.032008573, 0.16092388 0.0044587255 0.0020002425, 0.16092382 0.0044589937 -0.0019999146, 0.12792365 0.074997783 -0.057995915, 0.1292668 0.075956345 -0.054285303, 0.13533762 0.070916235 -0.046995997, 0.13442241 0.075480998 -0.042995974, 0.13703473 0.069154263 -0.044996172, 0.15405786 0.046349883 -0.0057844818, 0.15526654 0.041748852 -0.0077846348, 0.15484557 0.044036686 -0.0019975603, 0.15356369 0.047734499 -0.0072265565, 0.15326424 0.049152017 -0.0036141872, 0.14440772 -0.0059212744 0.065544561, 0.14329717 -0.0048818588 0.067642406, 0.15102457 0.053397417 -0.014997125, 0.1509653 0.052865922 -0.016997039, 0.14960267 0.056607336 -0.01699701, 0.15000488 0.056774408 -0.012996972, 0.15137342 0.053017706 -0.01299724, 0.15256606 0.0082812905 0.047000498, 0.054762796 0.12806237 0.074507147, 0.15212061 0.0042338073 0.048663154, 0.15248884 0.0095986128 0.047000423, -0.02716653 0.14973724 -0.048656836, 0.12928578 0.075796157 -0.054436535, 0.14708795 0.060023546 -0.024244666, 0.14798832 0.058449537 -0.02279827, 0.14685175 0.059539229 -0.026404917, 0.14585257 0.063819557 -0.022244453, 0.052262068 0.13220716 0.069778591, 0.05714637 0.13274753 0.065552413, 0.1541598 0.04638055 -0.0019975603, 0.15286134 0.050541282 2.6524067e-06, 0.027037695 0.1558134 0.028008521, 0.13655367 0.071553111 -0.042996183, 0.13768242 0.072796345 -0.037818253, 0.13741012 0.070997596 -0.041421205, 0.14247224 -0.0058420002 0.069033638, 0.14124882 -0.0061546266 0.071098208, 0.14168566 -0.011656702 0.069773406, 0.023326665 0.15739152 0.022812501, 0.029478818 0.15644953 0.022254318, 0.15118925 0.0082064569 0.050664097, 0.15007105 0.011800677 0.052845761, 0.15065916 0.0056008399 0.052286267, -0.033636853 0.14442354 -0.057992026, -0.029849559 0.14329264 -0.061992019, -0.033241525 0.14254397 -0.061991975, 0.14771985 0.060281217 -0.020025581, -0.030174509 0.14518639 -0.057991952, 0.14692394 0.062698722 -0.018628597, 0.14789779 0.061530113 -0.014996678, 0.15415978 0.046380281 0.0020026565, 0.15484548 0.044036478 0.00200212, 0.15345642 0.04830423 0.0057875216, 0.14205028 -0.035280764 0.061997935, 0.13925235 -0.03988868 0.064936951, 0.11623755 0.083945692 -0.067640573, 0.11803964 0.079232991 -0.069769785, 0.11450443 0.079305619 -0.074495688, 0.11914037 0.082389414 -0.064936325, 0.11335362 0.080942065 -0.074495673, 0.11476512 0.084631532 -0.069026962, 0.11550948 0.086874157 -0.065538034, 0.14471264 -0.032359064 0.057998136, 0.14970982 0.0081257522 0.054287538, 0.14840952 0.0131464 0.056444466, 0.14808334 0.0077412426 0.058000341, 0.15541643 0.038798124 0.015002131, 0.15382749 0.045406461 0.013002396, 0.15463464 0.040072292 0.018632472, 0.1553302 0.041164964 0.0092336535, 0.15541899 0.03878805 0.015002042, 0.15405802 0.046349317 0.0057872534, 0.15513986 0.04261446 0.0056206882, 0.15369356 0.046869695 0.0093970895, 0.14831293 0.060522884 -0.014996707, 0.15508312 0.030958533 0.028001636, 0.15586881 0.030548483 0.024411559, 0.15490453 0.031840026 0.028001726, 0.1554461 0.026656777 0.030001283, 0.14806753 0.0080365241 0.058000386, 0.11865886 0.085694075 -0.061995417, 0.12003706 0.085453331 -0.059995309, 0.11614792 0.089067847 -0.061995164, 0.11771336 0.090181977 -0.057995155, 0.14873132 0.060693353 -0.010007501, 0.14941147 0.059652269 -0.0057836175, 0.14975809 0.058232814 -0.009393096, 0.14746347 0.063849062 -0.0092255473, -0.041572168 0.13595569 -0.069763556, -0.038957596 0.13372892 -0.074492574, 0.15421367 0.030784726 0.032001734, 0.1540302 0.031689942 0.032001555, 0.15298963 0.029149055 0.03782168, 0.15483841 0.025072187 0.03364858, 0.14614995 0.0079322755 0.062000439, 0.14616606 0.0076303184 0.062000468, 0.14663278 0.01446858 0.060000986, 0.14432453 0.012356728 0.064938471, 0.15244523 0.022950768 0.043001145, 0.15411946 0.0234797 0.037267655, 0.15219371 0.027549893 0.04142493, 0.15128565 0.025942415 0.045001447, 0.052917913 0.12883571 0.074507266, 0.15273774 0.020915747 0.043000966, 0.12021573 0.086818099 -0.057995275, 0.12219863 0.085244507 -0.056436956, 0.15339433 0.046149135 0.01500237, 0.15264775 0.049226761 0.013002664, 0.15223451 0.04908976 0.017002672, 0.15340926 0.045285225 0.017002463, 0.14895453 0.060784191 -0.0057835579, 0.14864929 0.061841786 3.3676624e-06, 0.14706206 0.06524694 -0.0056132078, 0.14431626 0.007832408 0.065545231, 0.14179376 0.010273844 0.069771796, 0.14439948 0.0061077774 0.065545306, 0.15108781 0.022746235 0.047001183, 0.1513841 0.020683318 0.047001004, 0.14981928 0.021901608 0.050665081, 0.12149589 0.087742329 -0.054435909, 0.12110725 0.089793473 -0.052283689, 0.12427419 0.084954977 -0.052837878, 0.10623135 0.093297094 -0.071095243, 0.10818636 0.091022968 -0.071095541, 0.10621066 0.090111226 -0.074495092, 0.1087784 0.093409985 -0.067639813, 0.10490555 0.09162724 -0.074494943, 0.10357876 0.093124658 -0.074494854, 0.026890382 0.15493876 0.032008573, 0.10445084 0.096446365 -0.069765911, 0.14238212 0.0077272356 0.069034308, 0.13914467 0.0062222183 0.074500322, 0.14251766 0.0046009421 0.069034249, 0.13904078 0.0082200766 0.074500337, 0.13861899 -0.036646128 0.067640468, 0.13666783 -0.039148748 0.069773078, 0.13566278 0.079533428 -0.031995356, 0.13867871 0.076011628 -0.027995944, 0.13790339 0.075581789 -0.031995833, 0.13480158 0.078314781 -0.037259787, 0.13490589 0.080027848 -0.033640891, 0.13490798 0.081696332 -0.029995561, 0.14972435 0.022540689 0.050664872, 0.14875059 0.027879208 0.050845712, 0.14814217 0.023084223 0.054288298, 0.12269352 0.088607073 -0.050836772, -0.037080005 0.14357799 -0.057991907, 0.12504646 0.089018524 -0.044995025, 0.12311901 0.089446068 -0.048660144, -0.036614865 0.14171496 -0.061992034, 0.10773203 0.094614655 -0.067639753, 0.10513078 0.099652201 -0.064932421, 0.10951778 0.097104758 -0.061994612, 0.1364277 0.079981565 -0.027995676, 0.13708995 0.080275118 -0.024243742, 0.15212786 0.045767486 0.024248391, 0.15211558 0.043243915 0.028002292, 0.15374769 0.041320801 0.022247791, 0.15192705 0.047272295 0.022806257, 0.14976299 0.038640887 -0.041422978, 0.14898671 0.036927342 -0.044998065, 0.15086713 0.048466802 0.026412576, 0.13633896 -0.03743127 0.071096316, 0.15102455 0.053395808 0.015002728, 0.15137336 0.053016275 0.013002843, 0.15000485 0.056772828 0.01300317, 0.1496027 0.056605339 0.017003059, 0.15096538 0.052863926 0.01700303, 0.021790192 0.15695477 0.026418671, 0.1489546 0.060783535 0.0057881773, 0.14956215 0.059088349 0.0072345734, 0.14915565 0.060484529 0.003621906, 0.14731491 0.064412117 0.0077883005, 0.14284748 -0.031899869 0.061998203, 0.14188817 0.074347019 -0.014996052, 0.13986649 0.078499377 -0.01299569, 0.14253493 0.073851734 -0.011392146, 0.14116596 0.07409808 -0.020797044, 0.13948593 0.078288406 -0.016995609, 0.14289108 0.072401077 -0.014996022, 0.15143791 0.045559973 0.028002322, 0.14970437 0.04962483 0.030002743, 0.14873135 0.060692221 0.010014325, 0.14765629 0.062990159 0.011397988, 0.14789796 0.061528325 0.015003294, 0.1505889 0.045304209 0.032002479, 0.14905442 0.047012597 0.035822332, 0.15126395 0.042996943 0.0320023, 0.12592179 0.090937734 -0.039259344, 0.12864771 0.086954206 -0.039419979, 0.14544481 -0.028890163 0.057998255, 0.1251931 0.091938585 -0.039259195, 0.12866263 0.088733643 -0.035817206, 0.14831287 0.060521245 0.015003175, 0.14971028 0.045039684 0.035649866, 0.15077503 0.04133606 0.035649449, 0.14850585 0.045352757 0.039425373, 0.1267451 0.091532081 -0.03564021, 0.12515809 0.093690604 -0.035640329, 0.13389967 -0.038356036 0.074497908, 0.13819018 0.081014007 -0.014995694, 0.13786644 0.081961364 -0.012995511, 0.13749383 0.081736356 -0.01699546, 0.11260562 0.09889394 -0.054435328, 0.11094771 0.098386407 -0.057994619, 0.1091246 0.10281655 -0.054283738, 0.11306316 0.098370552 -0.054435477, 0.11121716 0.10274571 -0.050660193, 0.14541627 0.029027075 0.058001712, 0.14702216 0.029042929 0.054444388, 0.14518325 0.030171216 0.058001548, 0.13391796 -0.038291991 0.074497953, 0.14522496 0.024902284 0.060001448, 0.14873761 0.044746757 0.039269269, 0.1478477 0.043672085 0.043002427, 0.15017577 0.039654762 0.039268911, 0.13393636 -0.038227946 0.074497923, 0.096882299 0.10297254 -0.071094841, 0.097450167 0.10351276 -0.069768399, 0.096901059 0.10005507 -0.074494526, 0.093987301 0.10279703 -0.074494362, 0.092501327 0.10413614 -0.074494183, 0.095454067 0.10143647 -0.074494496, 0.1339546 -0.038163781 0.074497968, 0.093056381 0.10804728 -0.069025457, 0.15135477 -0.020901591 0.046998784, 0.15271613 -0.021078348 0.042998672, 0.14771979 0.060278863 0.020032197, 0.1475455 0.058888286 0.024249077, 0.14862321 0.057770371 0.020633459, 0.14629288 0.063374579 0.020807087, 0.12748848 0.092068851 -0.031994998, 0.1250259 0.095386237 -0.03199473, 0.12574868 0.095900416 -0.027994841, 0.12848546 0.091465712 -0.029995114, 0.11371559 0.099868506 -0.05083634, 0.11510336 0.098266006 -0.050836384, 0.11323427 0.10258442 -0.046994448, 0.14353304 0.028650701 0.062001452, 0.14328924 0.029846191 0.06200166, 0.14078993 0.027127117 0.067644015, 0.14308769 0.022530288 0.064942196, 0.12820737 0.09258762 -0.027994931, 0.12992142 0.090723991 -0.026403129, 0.14708833 0.060020894 0.024249107, 0.14516285 0.064466566 0.024413377, 0.14561671 0.060578436 0.030003369, 0.11480412 0.10082436 -0.046994478, 0.11425652 0.10350043 -0.042994291, 0.11821121 0.097913682 -0.044994518, 0.13417886 0.087497473 -0.014995217, 0.13361055 0.088730156 -0.012995154, 0.13578063 0.08537218 -0.012995303, 0.13541682 0.085133404 -0.01699549, 0.13325569 0.088477761 -0.016995162, 0.12879099 0.093008846 -0.024242967, 0.13127208 0.089914411 -0.022796601, 0.12799478 0.094674796 -0.022242665, 0.13887964 0.08141768 -0.0019955933, 0.13909161 0.080708921 -0.0072248578, 0.13848425 0.082024127 -0.0036121309, 0.13778225 0.083288968 4.5895576e-06, 0.1411642 0.077389002 -0.0019958317, 0.11583556 0.10173002 -0.042994335, 0.11816694 0.099794239 -0.041419655, 0.12934418 0.093408316 -0.020023853, 0.13049819 0.092897803 -0.01499486, 0.12928875 0.093820363 -0.01862669, 0.13887973 0.081417412 0.0020044744, 0.13886003 0.081240535 0.0057892501, -0.040501893 0.14265046 -0.05799216, -0.039967462 0.1408062 -0.061992154, 0.14116426 0.077388734 0.002004236, 0.11670762 0.10249549 -0.039258659, 0.1139956 0.10634762 -0.037258238, 0.11803222 0.1016084 -0.037816763, 0.14357316 0.043192148 0.054289415, 0.14652909 0.04328993 0.047002345, 0.14368188 0.04489857 0.052847505, 0.14176263 0.045840949 0.05644612, 0.14563495 0.038985044 0.052288279, 0.14264734 0.040498585 0.058002204, 0.14188837 0.074345261 0.015004009, 0.13948591 0.078286558 0.017004341, 0.14184044 0.07347694 0.0186342, 0.14289103 0.072399408 0.015003979, 0.14227557 0.074697047 0.0092355013, 0.13986656 0.078497946 0.013004392, 0.14475091 0.059066534 0.035650611, 0.14503002 0.057185948 0.037269622, 0.14537671 0.05889836 0.033650398, 0.14266725 0.062461466 0.037823528, 0.020242274 0.15640947 0.030008614, 0.11747061 0.1031656 -0.035639673, 0.11762761 0.10437331 -0.031994224, 0.14543368 0.046843708 -0.046997413, 0.14199823 0.042718261 0.058002442, 0.13973609 0.046734571 0.060002461, -0.013984635 0.15934226 -0.016991138, -0.010039017 0.16007531 -0.01299119, -0.010013983 0.15964097 -0.016991273, 0.14381059 0.058682501 0.039270043, 0.14425366 0.054378539 0.043003052, 0.14224699 0.06072554 0.041426539, -0.00043895841 0.1609849 0.0020089, 0.0035812706 0.16094592 -0.0019911975, -0.00043897331 0.16098505 -0.0019909739, 0.095111623 0.11125347 -0.061993748, 0.093282968 0.11039931 -0.065536842, 0.093417078 0.11268017 -0.061993673, 0.0035813153 0.16094568 0.0020087361, 0.094695374 0.11411467 -0.05799368, 0.097820625 0.10683519 -0.064935073, 0.098013192 0.11002159 -0.059993908, 0.13022999 0.094047278 -0.010005683, 0.13304546 0.09009707 -0.0093912482, 0.12955856 0.095061928 -0.0092236698, 0.13239171 0.091403812 -0.005781889, 0.14015941 0.042164683 0.062002406, 0.13795553 0.044161886 0.064940393, 0.14356424 -0.028501034 0.061998323, 0.1408027 0.039963961 0.062002018, 0.14273658 0.058244109 0.043003261, 0.14171931 0.058956236 0.045003325, 0.0087345093 0.15994713 0.015008897, 0.01165536 0.16038814 0.0072402805, 0.0073130131 0.16036388 0.011403337, 0.013933256 0.15978205 0.013008729, 0.096359596 0.11271289 -0.057993755, 0.10016683 0.11029917 -0.056435585, 0.10470064 0.11128062 -0.046993837, 0.10012905 0.11460018 -0.048658773, 0.10210329 0.11461222 -0.044993699, 0.10637301 0.1115872 -0.042993784, 0.10545935 0.11056188 -0.04699403, 0.10225481 0.1104787 -0.052836418, 0.14609398 -0.025404662 0.057998598, 0.13819008 0.081012309 0.015004396, 0.13749398 0.0817343 0.017004609, 0.13786644 0.081959844 0.013004541, 0.13042535 0.094188184 -0.0057817996, 0.15406917 0.035667002 -0.02799812, 0.12885617 0.0963355 -0.0056112707, 0.012434646 0.15896982 0.020639166, 0.013909578 0.15934688 0.017008901, 0.13840063 0.041635364 0.065547228, 0.15320128 0.035484761 -0.031998158, 0.13941926 0.038086474 0.065547183, 0.14146572 0.057725191 0.047003061, 0.14298548 0.053850859 0.04700315, 0.14118873 0.054690361 0.050666928, 0.13881661 0.060280293 0.05084759, 0.022313654 0.15469027 0.035828337, 0.097385749 0.11391279 -0.054434583, 0.0980905 0.11449111 -0.052282229, 0.028174415 0.15377757 0.035655916, 0.11936682 0.10483018 -0.024242133, 0.11828789 0.10496482 -0.027994215, 0.11579004 0.10876799 -0.024242014, 0.11721757 0.10810471 -0.020626068, 0.11975153 0.10434714 -0.02440235, 0.13051154 0.094250262 -0.001994729, 0.1280653 0.097548157 -0.00199458, 0.13116123 0.093368798 5.1856041e-06, 0.10564132 0.1122801 -0.042993933, 0.15181816 -0.017216623 0.046998993, 0.15318529 -0.017342508 0.042998984, 0.10607351 0.11340094 -0.039418444, 0.081242219 0.11571234 -0.071094096, 0.085266382 0.11527354 -0.067638636, 0.085220113 0.11281475 -0.071094409, 0.081887126 0.11267388 -0.074493721, 0.080260634 0.11383837 -0.074493647, 0.080371499 0.1172708 -0.069764778, 0.13654584 0.041077077 0.06903629, 0.13595164 0.041568309 0.06977348, 0.13372479 0.038953424 0.074502259, 0.13427049 0.03702876 0.074501947, 0.13791971 0.036198735 0.069036067, 0.14018899 0.057204098 0.050666839, 0.13929053 0.055470079 0.054290101, 0.11987962 0.10528034 -0.020023108, 0.11856812 0.10736409 -0.016994148, 0.12113848 0.10365266 -0.020795494, -0.014025986 0.15977541 -0.01299125, 0.13051164 0.094249994 0.0020051301, 0.1280655 0.097547859 0.0020053387, 0.13195696 0.092158347 0.0036235154, 0.082389846 0.11734664 -0.067638576, 0.085164845 0.11904031 -0.061993331, 0.080321148 0.12054759 -0.064931154, 0.13881715 0.056643993 0.054290265, 0.13604194 0.056593388 0.060003221, 0.13687269 0.061030269 0.054446101, 0.023570836 0.15347564 0.039431408, 0.1341787 0.087495923 0.015004665, 0.13541682 0.085131496 0.017004699, 0.13578068 0.085370719 0.013004661, 0.13325582 0.088475764 0.017004997, 0.1336105 0.088728756 0.013004929, 0.13042526 0.094187707 0.0057899952, 0.12928824 0.095577836 0.0077899694, 0.13266386 0.090887666 0.0072363317, 0.12036094 0.10570258 -0.014994144, 0.11889215 0.10765457 -0.012994051, -0.030106381 0.15341541 -0.035636872, -0.024119943 0.15442225 -0.035813525, -0.028512716 0.15268683 -0.039255783, 0.12252778 0.10371721 -0.011390448, 0.12319787 0.10238206 -0.014994353, 0.14673685 0.047274768 -0.04299745, -0.026658639 0.15544784 -0.029991269, 0.1364277 0.079978317 0.028004408, 0.13759847 0.079894125 0.022808194, 0.1362994 0.080822647 0.026414424, 0.13490799 0.081692904 0.030004382, 0.13867877 0.076008528 0.028003991, 0.13758098 0.07208699 0.039270759, 0.13779619 0.073850244 0.035651416, 0.13468994 0.077261269 0.039427221, -0.050976261 0.13271424 -0.069766879, -0.048098981 0.13071933 -0.074492916, -0.049971506 0.13001519 -0.074492797, 0.13442229 0.075476289 0.043003976, 0.13758591 0.072077781 0.039270699, 0.084106088 0.11979055 -0.061993197, 0.080109298 0.12366855 -0.059993193, 0.086273536 0.12060797 -0.057993338, 0.13022989 0.094046146 0.010016233, 0.12993748 0.094267458 0.011399597, 0.13049823 0.092896134 0.015005141, 0.12070049 0.1060006 -0.010004997, 0.11764497 0.10963613 -0.0072230399, 0.14425214 0.050364792 -0.046997249, 0.12177621 0.10498217 -0.007781148, 0.13566279 0.079529792 0.032004446, 0.13485552 0.079001486 0.03582406, 0.13790338 0.075578153 0.032004297, 0.1442001 -0.025086135 0.061998546, 0.13655363 0.071548343 0.043003798, 0.1370348 0.069149315 0.045003891, 0.085209593 0.12136215 -0.057993293, -0.004458949 0.16092369 0.0020087957, -0.0044590086 0.16092396 -0.0019911528, 0.083510429 0.12452134 -0.054282635, 0.12088157 0.10615951 -0.0057812333, 0.12040415 0.1068607 -0.0019941032, 0.13381596 0.054602593 0.065547839, 0.13448587 0.053805232 0.064943776, 0.13122277 0.057775557 0.067645893, 0.10159326 0.11883339 -0.035638765, 0.10159627 0.1174916 -0.039257765, 0.10117251 0.11919188 -0.035638928, 0.10569225 0.11513913 -0.035815746, 0.10491125 0.11776322 -0.029993325, 0.11519511 0.11131006 -0.014993787, 0.11585882 0.11028227 -0.01699388, 0.11307788 0.113132 -0.01699388, 0.11617191 0.11058447 -0.012994111, 0.11337943 0.11344582 -0.012993753, 0.13533771 0.07091108 0.047003835, 0.15313922 0.039469093 -0.027997971, 0.13322179 0.074810266 0.047004223, 0.13330786 0.070414454 0.052290261, 0.13521785 0.069816917 0.048666805, 0.152279 0.039254695 -0.0319978, 0.086117044 0.12265408 -0.054434091, 0.088339552 0.12106323 -0.054433987, 0.085566312 0.12491795 -0.050658956, 0.069875464 0.12291098 -0.071093813, 0.07197392 0.12260231 -0.069767445, 0.070489928 0.12013397 -0.074493319, 0.068757325 0.12113398 -0.074493304, 0.067010552 0.12210891 -0.074493334, 0.066681311 0.12604541 -0.069024444, 0.13202263 0.053870529 0.069036871, 0.12992969 0.055739999 0.071101591, 0.12852196 0.053680867 0.074502915, 0.12927994 0.051829338 0.074502841, 0.13271046 0.050972253 0.069776818, 0.12934418 0.093406051 0.020034254, 0.1285226 0.094338804 0.020808816, 0.1307421 0.090243727 0.024250776, 0.13204156 0.089393765 0.020635247, 0.14761481 -0.020207554 0.056442559, 0.10218935 0.11953008 -0.031993434, 0.10066636 0.1208156 -0.03199333, 0.10125636 0.12147775 -0.027993202, 0.086965829 0.12386295 -0.050834939, 0.09035182 0.12141523 -0.050834998, 0.15219153 -0.013521433 0.046999261, 0.15356301 -0.013596058 0.042999029, 0.087568611 0.12520945 -0.046993166, 0.070862651 0.12464687 -0.067638144, 0.071595937 0.12592381 -0.064933926, 0.10276529 0.12020382 -0.02799347, 0.10647634 0.11735973 -0.026401699, 0.12879129 0.093006283 0.024251044, 0.12717789 0.095151991 0.024415076, 0.035277247 0.14204693 0.062007964, 0.04057163 0.14164594 0.06000787, 0.035806522 0.14389446 0.058008194, 0.087798312 0.12504843 -0.046993107, 0.092998534 0.12358689 -0.04141821, 0.093460158 0.12176323 -0.044993371, 0.088361248 0.12633002 -0.042993024, 0.12088162 0.10615888 0.0057907403, 0.1173007 0.11010286 0.0057910383, 0.11813705 0.10891312 0.0094004869, 0.1204043 0.10686046 0.0020059347, 0.041991338 0.13279909 0.0745074, 0.043894336 0.13218239 0.074507385, 0.042888567 0.13553634 0.069781721, 0.12128623 0.10570696 0.0056242943, 0.10976829 0.11666507 -0.014993519, 0.1065549 0.11960724 -0.01499331, 0.10966134 0.11744356 -0.0093897283, 0.11051647 0.11623663 -0.012993693, 0.11022681 0.1159116 -0.016993642, 0.1032331 0.12075087 -0.024241298, 0.10371889 0.12078258 -0.022241116, 0.032355964 0.14470935 0.058008, 0.12820737 0.092584521 0.028005064, 0.12574862 0.095897287 0.028005242, 0.12848537 0.091462463 0.030004948, 0.15814267 0.00048607588 0.027999789, 0.088587105 0.12617177 -0.042993069, 0.12070054 0.10599944 0.01001671, 0.11889215 0.10765308 0.013005972, 0.12208667 0.10448343 0.0092370808, 0.12748861 0.092065185 0.032005072, 0.12862521 0.089770973 0.033651918, 0.0063744336 0.15930173 0.020812377, 0.010959774 0.1584838 0.024254665, 0.12502585 0.095382839 0.032005221, 0.1245081 0.062436104 -0.074496478, 0.089254037 0.12712142 -0.039257497, 0.092463255 0.1253255 -0.037815437, 0.087473512 0.12904763 -0.037256956, 0.12036082 0.10570106 0.015005797, 0.11856803 0.10736224 0.017005861, 0.14553873 0.050844222 -0.04299739, 0.12193379 0.10319731 0.018635958, 0.12319773 0.10238051 0.015005648, 0.1267447 0.091527879 0.035652429, 0.12866835 0.088024139 0.037271351, 0.12519081 0.09264189 0.037825227, 0.089837581 0.12795234 -0.035638437, 0.091453657 0.12793112 -0.031993046, 0.08682391 0.13063645 -0.033637941, 0.12792367 0.074991405 0.058004186, 0.13005827 0.071225107 0.058004037, 0.13008775 0.075745076 0.052849323, 0.13305461 0.06098941 -0.061996549, 0.12800702 0.076236725 0.056447864, 0.12583239 0.076656908 0.060004249, -0.02189748 0.15844887 -0.016991183, -0.018004164 0.15937623 -0.012991086, -0.017946512 0.15894476 -0.016991138, 0.12592126 0.090932906 0.039271772, 0.12516725 0.090855837 0.041428357, 0.066202506 0.13054097 -0.06199263, 0.066002056 0.13064232 -0.061992913, 0.066929072 0.13232532 -0.057992578, 0.066378802 0.12838882 -0.065535605, 0.071074322 0.12907305 -0.059992969, 0.05787614 0.12899655 -0.071093485, 0.054762736 0.12807068 -0.074492902, 0.057478547 0.1313571 -0.067637742, 0.057980701 0.12894964 -0.071093395, 0.056596503 0.127271 -0.074492857, 0.12630366 0.066176295 0.069037586, 0.12266332 0.065978229 0.07450363, 0.12359834 0.06420964 0.074503556, 0.12170327 0.067733049 0.074503794, 0.12640588 0.06598115 0.069037572, 0.12744787 0.068155199 0.065548778, 0.12329248 0.070777982 0.069775268, 0.11987974 0.1052779 0.020034909, 0.11637028 0.10850942 0.022809923, 0.12059301 0.10393721 0.022251546, 0.090364605 0.12870258 -0.031992972, 0.086101919 0.13214025 -0.029992685, 0.091965646 0.12865466 -0.027992964, -0.0084760189 0.16076213 0.0020089149, -0.008476153 0.16076246 -0.0019910038, 0.074798346 0.13156873 -0.050834402, 0.070155174 0.13344795 -0.05228126, 0.072118297 0.13400787 -0.048657611, 0.078213453 0.13125688 -0.046992674, 0.075107947 0.13046256 -0.052835301, 0.073112264 0.12982306 -0.056434497, 0.12626691 0.074019909 0.062004119, 0.12466893 0.073752522 0.064941987, 0.12837905 0.070293307 0.062004015, 0.06707111 0.13225338 -0.057992682, 0.090874046 0.12942803 -0.027992964, 0.040079504 0.13338858 0.074507475, 0.088684231 0.1318067 -0.024240732, 0.11936709 0.10482764 0.02425161, 0.11828791 0.10496166 0.028005749, 0.075514331 0.13282809 -0.046992585, 0.074040502 0.13445881 -0.044992611, 0.078875929 0.13245976 -0.042992815, 0.11519514 0.11130816 0.015006006, 0.11585879 0.11028048 0.017006099, 0.11617191 0.1105831 0.013006061, 0.11337933 0.11344439 0.01300633, 0.11307782 0.11313018 0.017006278, 0.10454327 0.12228209 -0.0057801902, 0.10515703 0.12150806 -0.0092223287, 0.10418908 0.12259328 -0.005610019, 0.10709615 0.12021407 6.6459179e-06, 0.10873327 0.11857197 -0.0057803988, -0.043292522 0.14653164 -0.046991795, -0.038638741 0.14976525 -0.041416839, -0.036924988 0.14898926 -0.044991776, 0.15725587 0.00050106645 0.031999975, 0.091287762 0.13001689 -0.024240881, -0.03859055 0.14634204 -0.050833613, 0.093529925 0.12837821 -0.02440092, 0.090223253 0.13147765 -0.020624787, 0.10461237 0.12236279 -0.0019932389, 0.10314794 0.12359968 -0.0019931197, 0.076192811 0.13402119 -0.042992637, 0.072905421 0.13715318 -0.039256856, 0.078180432 0.13416135 -0.039417416, 0.12275031 0.088642329 0.050668567, 0.12547831 0.084736615 0.050668359, 0.12504649 0.089013547 0.045004964, 0.12192206 0.08965838 0.050849169, 0.031896204 0.14284423 0.062007949, 0.12345432 0.085074335 0.054291666, 0.14617667 -0.018523097 0.059998959, 0.09167996 0.13057533 -0.020021766, 0.091704816 0.13105613 -0.016992748, 0.0950367 0.12800983 -0.020794302, 0.10461228 0.12236258 0.0020066202, 0.1081413 0.11921081 0.0036253035, 0.10314804 0.12359944 0.0020068884, 0.15808198 0.0043998957 0.028000116, 0.076766476 0.13502988 -0.039256975, 0.077421889 0.13577121 -0.035814613, 0.12154903 0.087774605 0.054291874, 0.11985973 0.089957118 0.054447934, 0.10976829 0.1166634 0.015006572, 0.11051638 0.11623529 0.013006419, 0.10655484 0.11960554 0.015006453, 0.11022682 0.11590981 0.017006457, 0.10883871 0.11653447 0.020636678, 0.11747035 0.1031611 0.035652965, 0.11790764 0.10266119 0.035653144, 0.11762762 0.10436967 0.032005787, 0.11389451 0.10702902 0.035825729, 0.11412038 0.10529551 0.039428681, 0.028886884 0.14544159 0.058008075, 0.10454324 0.12228149 0.0057916343, 0.10477853 0.12195072 0.0077916682, 0.092047974 0.13109922 -0.014992744, 0.091956079 0.13141149 -0.012992769, 0.096376657 0.12838179 -0.011388987, 0.097327054 0.12722924 -0.014993012, 0.088413939 0.13329834 -0.016992599, 0.088652045 0.13366267 -0.01299268, 0.12021576 0.086811662 0.058004856, 0.11771347 0.09017539 0.05800496, -0.021971166 0.15887794 -0.012991339, 0.12003717 0.085446596 0.060004726, 0.1348286 0.061727345 -0.057996646, 0.11670719 0.10249081 0.039272428, 0.11809698 0.10088632 0.039272338, 0.11425649 0.10349569 0.043005675, 0.053494349 0.13624281 -0.061992601, 0.056541294 0.1350067 -0.061992541, 0.051483691 0.13539839 -0.064930499, 0.020898744 0.1513522 0.047008336, 0.024799138 0.1521534 0.043008313, 0.021075889 0.15271363 0.043008596, 0.050582752 0.13839397 -0.059992343, 0.024571344 0.15079948 0.047008574, 0.057273507 0.13678178 -0.057992563, 0.092307672 0.13146886 -0.010003626, 0.095362499 0.12944779 -0.0077797174, 0.090299204 0.13306582 -0.0072219968, 0.11865887 0.08568716 0.062004566, 0.11614785 0.089060962 0.062004834, 0.11914033 0.082382172 0.06494537, 0.11583552 0.10172528 0.043005556, 0.11821128 0.097908616 0.045005471, 0.13627 -0.028822362 0.074498236, 0.054196194 0.13803011 -0.057992384, 0.053708658 0.13998222 -0.054281726, 0.092446163 0.13166589 -0.0057796836, 0.093606755 0.13097399 -0.0019927025, 0.08918114 0.13398746 -0.0036093295, 0.11716999 0.084611803 0.065549627, 0.11507565 0.085526705 0.067647457, 0.085705891 0.13533065 -0.014992535, 0.085068539 0.13545784 -0.01699236, 0.085292891 0.1358307 -0.012992531, 0.11480413 0.1008192 0.047005653, 0.1162914 0.098155022 0.048668563, 0.11323431 0.10257921 0.047005832, 0.054773316 0.13949969 -0.054433107, 0.055624783 0.14082626 -0.050658032, 0.05918625 0.13768542 -0.054433301, 0.092507273 0.13175279 -0.0019927323, 0.093606815 0.1309737 0.0020071268, 0.14345641 -0.020068437 0.064936712, 0.087999791 0.13482219 7.3611736e-06, -0.029763132 0.15639782 -0.022239372, -0.024052233 0.15728509 -0.022792652, -0.025367528 0.15641969 -0.026399508, 0.038929403 0.13592026 -0.071093008, 0.040079504 0.13339689 -0.074492753, 0.038159743 0.1339587 -0.074492544, 0.042888671 0.13554421 -0.069766805, 0.036962509 0.1377233 -0.069024011, 0.11559971 0.083477497 0.069038495, 0.11426768 0.083254546 0.071103185, 0.11450444 0.079297364 0.07450442, 0.1180397 0.079225063 0.06977874, 0.11376812 0.099909067 0.050669163, 0.11429621 0.098312765 0.052291662, 0.10997066 0.10279322 0.052850738, 0.078852952 0.13869876 -0.02002126, 0.074242026 0.14083397 -0.022240117, 0.075778604 0.14062548 -0.018624216, 0.077268407 0.14031908 -0.014992267, 0.079260051 0.13796726 -0.0227938, -0.043674737 0.14785007 -0.042991936, 0.081670687 0.13753322 -0.016992182, -0.040331885 0.15043065 -0.03781414, 0.092507347 0.13175243 0.0020072758, 0.089859515 0.13344419 0.00579229, 0.0394793 0.13783994 -0.067637429, 0.041781142 0.13869828 -0.064933166, 0.036146253 0.13994062 -0.065535098, 0.11265481 0.098931015 0.05429256, 0.11094758 0.098380119 0.058005348, -0.046841174 0.14543623 -0.046991959, 0.15719561 0.0043815374 0.032000154, 0.10323332 0.12074831 0.024252653, 0.10738254 0.11707401 0.024252206, 0.10430753 0.12057248 0.020810127, 0.10281564 0.121066 0.024416417, 0.10491133 0.11775982 0.030006468, 0.092446268 0.13166529 0.0057921708, 0.094723195 0.13004535 0.0056257546, 0.090939313 0.13247037 0.0094019175, 0.079169527 0.13925532 -0.014992267, -0.028431952 0.15719286 -0.018623248, 0.081880704 0.13791457 -0.012992412, 0.10276535 0.12020075 0.028006613, 0.10125645 0.12147459 0.028006673, 0.040301785 0.14071083 -0.061992049, 0.035277262 0.14205372 -0.061992154, 0.040571541 0.1416527 -0.059992105, 0.092307732 0.13146758 0.01001808, 0.028497562 0.14356083 0.062008038, 0.095775887 0.12903073 0.0092385411, 0.091956079 0.13140991 0.013007134, 0.079392761 0.13964802 -0.01000312, 0.075482607 0.1418612 -0.009221375, 0.079622269 0.13979462 -0.0057792068, 0.080778345 0.13890103 -0.0093885958, 0.10218932 0.11952648 0.032006472, 0.1006663 0.12081203 0.03200677, 0.10542396 0.116142 0.033653438, 0.10564137 0.11227539 0.043006212, 0.10181123 0.11643016 0.041429758, 0.10210337 0.11460719 0.045006424, 0.10637294 0.11158246 0.043006241, 0.10585456 0.11444861 0.037272722, 0.025401354 0.1460906 0.058008119, 0.040830493 0.14255676 -0.057992086, 0.035806462 0.14390093 -0.057991982, 0.042391479 0.14283726 -0.056433707, -0.035665482 0.15407062 -0.027991652, -0.031691715 0.15403205 -0.031991526, -0.035482988 0.15320298 -0.031991512, 0.038701877 0.14571312 -0.052280545, 0.092048004 0.13109761 0.015007257, 0.091704741 0.13105434 0.017007232, 0.095912829 0.12774265 0.018637359, 0.08865194 0.13366121 0.013007432, 0.088414028 0.13329634 0.017007411, 0.097326979 0.12722766 0.015007049, -0.031841487 0.15490603 -0.027991638, 0.10159294 0.11882898 0.0356538, 0.10143685 0.11817661 0.037826717, 0.13331454 0.064933211 -0.057996586, 0.021886125 0.14893204 0.05285345, 0.028061509 0.14812601 0.052294642, 0.079511985 0.1398572 -0.0057792962, 0.07429716 0.14270392 -0.0056088269, 0.077660978 0.141031 7.7188015e-06, 0.13156971 0.0641298 -0.0619964, 0.10859618 0.095366299 0.065550208, 0.10513094 0.09964475 0.064943433, 0.10445066 0.096438646 0.06977661, 0.10908565 0.094806135 0.065550208, 0.10951768 0.097097963 0.062005371, 0.057139724 0.1455256 -0.035637245, 0.062257886 0.14275852 -0.037814543, 0.056564808 0.14527702 -0.037256002, 0.06069383 0.14507386 -0.031992182, 0.055578157 0.14668125 -0.033637077, 0.10470061 0.11127558 0.047006235, 0.1034762 0.11053354 0.050669953, 0.10545933 0.11055675 0.04700616, 0.041265219 0.14407468 -0.054432765, 0.017213896 0.15181533 0.047008634, 0.0173399 0.15318283 0.043008432, 0.044194862 0.14390481 -0.052834585, 0.025833458 0.13900515 -0.071092844, 0.027833939 0.13861859 -0.07109277, 0.026858076 0.13667399 -0.074492514, 0.026808605 0.14085379 -0.067637056, 0.02489236 0.13704559 -0.074492335, 0.022921428 0.13738897 -0.07449244, 0.021532059 0.14052963 -0.069763333, 0.10714085 0.094087899 0.069039106, 0.10490558 0.091619045 0.07450527, 0.10855357 0.092454672 0.069039106, 0.10357879 0.093116373 0.074505106, 0.091679841 0.13057306 0.020036429, 0.094440952 0.12816578 0.022252798, 0.089306712 0.13168365 0.022811145, 0.057474986 0.14637902 -0.031991914, 0.061031863 0.14589334 -0.02799207, 0.054539531 0.14798674 -0.02999194, 0.041671976 0.14549455 -0.050833747, 0.040491238 0.14669579 -0.048656985, 0.026198402 0.14096859 -0.06763725, 0.025082737 0.14420342 -0.061991975, 0.057798952 0.1472041 -0.027991861, 0.057131231 0.14823624 -0.024239779, 0.091288015 0.13001448 0.02425307, 0.091965735 0.12865159 0.02800706, 0.08773306 0.13195673 0.026417077, 0.042071015 0.14688703 -0.046991795, 0.042264745 0.14756322 -0.044991866, 0.047045693 0.14537013 -0.046992019, 0.085705876 0.13532886 0.015007466, 0.085292876 0.13582924 0.013007522, 0.085068658 0.13545585 0.01700747, -0.056596935 0.13604516 -0.059992433, -0.053808957 0.13448942 -0.064933509, -0.058989152 0.13194761 -0.065535739, 0.065574095 0.14615032 -0.014991909, 0.064169213 0.14594805 -0.020793095, 0.060242876 0.14817655 -0.016991839, 0.065392822 0.14660877 -0.011388212, 0.066575855 0.14569676 -0.014991999, 0.060408905 0.14857876 -0.012991875, 0.058062032 0.14787394 -0.024239704, 0.062618494 0.14597189 -0.024399862, -0.047272399 0.14673927 -0.042991892, 0.058704764 0.14825788 -0.020623878, 0.09087421 0.12942472 0.028007209, 0.086101964 0.13213685 0.030007303, 0.079392806 0.13964686 0.010018498, 0.075014919 0.14220855 0.0077925622, 0.076168254 0.14130977 0.011402249, 0.077268407 0.14031747 0.015007734, 0.081880644 0.13791317 0.0130077, 0.080091164 0.13944751 0.0072391629, 0.09036462 0.12869906 0.032007098, 0.091453612 0.1279276 0.032007068, 0.087222174 0.12968946 0.035826892, 0.042768568 0.149322 -0.039255992, 0.046367094 0.14819458 -0.039416701, 0.040558442 0.14993754 -0.039256141, -0.050362274 0.14425471 -0.046992093, 0.045269132 0.14959508 -0.035813764, 0.097428352 0.11395663 0.054293409, 0.10142741 0.11041245 0.054293126, 0.098913714 0.11454073 0.050850496, 0.098013178 0.11001492 0.060006008, 0.096836656 0.11437285 0.05444923, 0.079169527 0.13925371 0.015007675, 0.081670493 0.1375314 0.017007738, 0.025082767 0.14419654 0.062007949, 0.089837343 0.12794793 0.035654545, 0.092106834 0.12632403 0.035654277, 0.0878281 0.12804961 0.039430082, 0.043048128 0.15029821 -0.035637081, 0.039438695 0.15128562 -0.035637021, 0.13172406 0.068101853 -0.057996362, 0.13001104 0.06723398 -0.061996385, 0.058545679 0.14910498 -0.01499179, 0.05653587 0.14963019 -0.016991749, 0.056686774 0.15003845 -0.012991741, 0.096359551 0.1127063 0.058006302, 0.094695464 0.11410829 0.058006287, 0.089253694 0.12711647 0.039273858, 0.092686296 0.12463585 0.03927359, 0.088361293 0.12632522 0.043006793, 0.078853056 0.1386964 0.020036817, 0.078638673 0.13803351 0.024253458, 0.080178261 0.13783151 0.02063784, -0.039467588 0.15314072 -0.027991712, -0.039252847 0.15228081 -0.031991512, 0.074862197 0.14076015 0.020811349, 0.043300658 0.15117967 -0.031991616, 0.043427065 0.15162054 -0.029991701, 0.027653441 0.14879689 -0.050833657, 0.028725266 0.14859381 -0.050833404, 0.027064979 0.1474036 -0.054432496, 0.02289407 0.1496731 -0.050657585, 0.095111683 0.11124659 0.062006146, 0.093417138 0.11267322 0.062006339, 0.097820684 0.10682777 0.06494689, 0.08858712 0.12616694 0.043006971, 0.091533527 0.1215713 0.048669875, 0.093460158 0.12175834 0.045006901, 0.043544799 0.15203169 -0.027991399, 0.041042387 0.15382341 -0.022239476, 0.020204321 0.14761153 0.056451887, 0.045011938 0.15193602 -0.026399806, 0.078515798 0.13810328 0.024253637, 0.02791813 0.15022108 -0.046991557, 0.013518766 0.15218884 0.04700838, 0.013593674 0.15356058 0.043008596, 0.031374648 0.15025598 -0.044991568, 0.058798924 0.14974952 -0.0057786703, 0.062115431 0.14851949 -0.001991868, 0.064166799 0.14742243 -0.0077787936, 0.058425248 0.14982304 -0.0072209239, 0.057130277 0.15047252 -0.0036084354, 0.093918443 0.10985029 0.065551028, 0.093158111 0.108989 0.067648798, 0.051384658 0.15172172 -0.014991716, 0.052929357 0.15140465 -0.012991697, 0.052793846 0.15099105 -0.016991571, 0.087798417 0.12504321 0.047006905, 0.087568581 0.12520432 0.047007009, 0.043742955 0.15272361 -0.02423957, 0.046572536 0.15214518 -0.022792995, 0.058837935 0.14984822 -0.0019917488, 0.055792585 0.15102375 8.2850456e-06, 0.028169066 0.15157053 -0.042991757, 0.030167475 0.15169871 -0.0414166, 0.087006032 0.12391457 0.05067037, 0.084339201 0.12468666 0.05285199, -0.00048771501 0.15814102 0.028008714, 0.0033778995 0.15721866 0.032008737, 0.0034262538 0.1581046 0.028008744, 0.089553371 0.12128106 0.052292928, 0.043930978 0.15337938 -0.020020291, 0.042586699 0.15396217 -0.018623382, 0.058837906 0.14984798 0.0020082891, 0.062115461 0.14851934 0.0020082295, 0.05791238 0.15009406 0.0057932436, 0.028381184 0.15271124 -0.039256036, 0.0058702976 0.14326224 -0.067636967, 0.011652827 0.14168954 -0.069766387, 0.0053904057 0.14249527 -0.069023699, -0.064663365 0.12573138 -0.071093693, -0.062431931 0.1245122 -0.074493229, -0.064213797 0.12360269 -0.074493349, 0.0098710954 0.14451802 -0.064932927, 0.0041010231 0.14447543 -0.06553483, 0.086154595 0.12270173 0.054293767, 0.082251057 0.12422681 0.056450635, -0.050841853 0.14554104 -0.042991936, 0.06557399 0.14614868 0.015008092, 0.066575825 0.14569506 0.015008003, 0.058798954 0.14974889 0.0057930052, 0.085209668 0.12135556 0.058006838, 0.080109328 0.12366185 0.060006812, 0.076766223 0.13502485 0.039274201, -0.060986072 0.13305792 -0.061992586, 0.073349908 0.13616613 0.041430846, 0.077732846 0.13513404 0.037274033, 0.0059926361 0.14624596 -0.06199199, 0.0080343634 0.1471293 -0.059991881, 0.044231758 0.15442911 -0.010002285, 0.042022958 0.15510103 -0.0092205405, 0.046518788 0.15400738 -0.0057783127, 0.084106132 0.1197837 0.062006518, 0.080321014 0.12054032 0.064944655, 0.076192856 0.13401639 0.043007478, 0.074040309 0.13445392 0.045007452, 0.0060712248 0.14816454 -0.057991862, 0.0095450431 0.14868903 -0.05643326, 0.058545694 0.14910319 0.015008301, -0.053853437 0.14298806 -0.046992093, 0.044298083 0.15466067 -0.0057784915, 0.040679827 0.15565872 -0.005608201, 0.083050653 0.11828044 0.0655514, 0.080371603 0.11726293 0.069777742, 0.085253537 0.11670288 0.065551519, 0.075514436 0.13282275 0.047007322, 0.076285124 0.13078782 0.050670937, 0.070945278 0.13367912 0.050851673, 0.0061358809 0.14974204 -0.054432437, 0.0053080916 0.15067178 -0.052280307, 0.15685111 0.036250353 0.0020020306, 0.15685119 0.036250442 -0.0019980371, 0.044327423 0.15476254 -0.001991421, -0.0076654255 0.14117748 -0.07109277, -0.0052056164 0.14328802 -0.067636952, -0.0082242191 0.13904494 -0.07449235, -0.04324545 0.15211692 -0.027991652, -0.04299888 0.15126577 -0.031991437, -0.010277778 0.14179766 -0.069763213, 0.081937641 0.11669508 0.069040477, 0.080260545 0.11383015 0.074506387, 0.074833155 0.13162377 0.050670877, 0.074314743 0.1302138 0.054294184, 0.029152557 0.15686068 -0.020020247, 0.025760278 0.15786687 -0.016991153, -0.00050292909 0.15725419 0.032008797, 0.032486245 0.15685835 -0.014991283, 0.030084133 0.15656784 -0.020792618, 0.044327393 0.15476239 0.0020085573, 0.041489482 0.15533555 0.0077933818, 0.045707986 0.15432602 0.0036270618, 0.0083696395 0.15326333 0.045008525, 0.01140146 0.15547836 0.037275031, -0.0077738315 0.14317158 -0.067636997, -0.012360454 0.14432812 -0.064929858, 0.0070046335 0.15450653 0.041431889, 0.074100673 0.13033566 0.054294422, 0.068957642 0.13305345 0.054450169, 0.018519744 0.14617321 0.060008079, 0.058062345 0.14787152 0.024254024, 0.056169912 0.14817062 0.026418269, 0.051384777 0.15172011 0.015008301, 0.044298232 0.1546599 0.0057934523, -0.0044013858 0.15808043 0.02800867, 0.047053024 0.15377328 0.007239908, 0.029269502 0.15749031 -0.014991403, 0.025832489 0.15829587 -0.012991369, 0.031129897 0.15748423 -0.011387512, 0.057798937 0.14720097 0.028008223, 0.054539531 0.14798352 0.030008093, 0.011982515 0.15093434 0.050672024, -0.0079357177 0.14615345 -0.061991811, -0.014472052 0.14663604 -0.059991732, 0.044231683 0.15442792 0.010019571, 0.042814046 0.1547159 0.011403009, 0.029352069 0.15793425 -0.010002151, -0.061724216 0.13483196 -0.057992592, 0.057474881 0.14637557 0.032008216, 0.056176454 0.14584646 0.035827801, 0.0063594729 0.15519595 -0.039255723, 0.0108466 0.15591782 -0.035813287, 0.0061777085 0.1552034 -0.039255798, -0.0080397576 0.14807072 -0.057991743, -0.012344956 0.14942327 -0.054281145, 0.05713965 0.1455211 0.035655364, -0.054381102 0.14425591 -0.042992145, 0.0064011216 0.15621051 -0.035636723, 0.0047862232 0.15626836 -0.035636738, 0.021742672 0.15870461 -0.014991269, 0.026858062 0.13666564 0.074507684, 0.02881828 0.13626572 0.074507713, 0.027223617 0.13996518 0.069041848, 0.02182281 0.15845907 -0.016991332, 0.017871872 0.15895304 -0.016991332, 0.017911673 0.15938666 -0.01299116, 0.021878973 0.15889058 -0.012991324, -0.0081253797 0.1496473 -0.054432556, -0.010984838 0.15101507 -0.05065757, -0.0064132959 0.14973044 -0.054432496, 0.06707117 0.13224694 0.058007374, -0.02105023 0.13980958 -0.07109262, -0.021766484 0.13757676 -0.074492365, -0.023740143 0.13724998 -0.074492469, 0.070473731 0.12395525 0.069040895, -0.01398465 0.15934035 0.017008856, -0.010014012 0.15963912 0.017008841, -0.010039046 0.160074 0.013008907, 0.066827103 0.12458825 0.071105301, 0.067010522 0.12210071 0.074506715, 0.11563163 0.077652842 -0.074495822, 0.11673483 0.075984031 -0.074495956, 0.043930888 0.15337723 0.020037487, 0.041662961 0.15388918 0.02081196, -0.014025971 0.15977401 0.013008907, 0.045951232 0.15207154 0.024254188, 0.0064385682 0.15712664 -0.031991214, 0.008599788 0.15748259 -0.029991284, -0.030886307 0.15789402 -0.0056080222, -0.024909168 0.15893969 -0.0057781041, -0.029434174 0.15797424 -0.0092202127, -0.0082055181 0.15112212 -0.050833493, 0.020064771 0.14345267 0.064945787, -0.0050595254 0.15126026 -0.050833195, 0.066202506 0.13053411 0.062007338, 0.026173711 0.14213538 0.065552905, -0.027213812 0.15868339 8.7469816e-06, 0.0064749122 0.15801218 -0.027991205, 0.010074779 0.15814278 -0.0263993, 0.15589705 0.040155888 0.00200212, 0.15589695 0.040156096 -0.0019978285, 0.043743208 0.15272099 0.024254322, 0.040104389 0.15368655 0.024418309, -0.0082840621 0.1525687 -0.046991378, -0.060590461 0.13805398 -0.052280918, -0.002846539 0.15347034 -0.044991627, 0.014166638 0.15955946 -0.014991149, 0.0065043271 0.15873137 -0.024239138, 0.0057846457 0.15909952 -0.022239119, 0.043544799 0.15202859 0.028008312, -0.004383415 0.15719381 0.032008782, -0.0083585978 0.15393916 -0.042991459, -0.0043444782 0.15460828 -0.041416541, 0.029352099 0.15793321 0.010019615, 0.032486245 0.15685666 0.015008688, 0.030306384 0.15780827 0.0092401356, 0.025832668 0.15829447 0.013008654, 0.043300673 0.15117595 0.03200841, 0.044590771 0.15038177 0.033655584, -0.0084214061 0.15509781 -0.039255798, -0.012069374 0.15543288 -0.03725557, -0.0058472455 0.1556339 -0.037813812, 0.054797307 0.13955462 0.054294676, 0.052545086 0.13941467 0.05645135, 0.029269516 0.15748864 0.015008837, 0.025760308 0.15786493 0.017008826, 0.030988574 0.15670708 0.018638939, 0.043048024 0.15029362 0.035655558, 0.040115356 0.15048507 0.037828475, 0.045713276 0.14904302 0.037274703, -0.0084765106 0.15611175 -0.035636827, 0.021532044 0.14052185 0.069778875, -0.013567582 0.15626988 -0.033636466, 0.054196239 0.1380237 0.058007836, 0.050582796 0.13838726 0.060007766, -0.0083124042 0.15792319 0.028008685, 0.042768389 0.14931709 0.03927505, 0.041210547 0.14907399 0.04143168, -0.028654248 0.14353648 -0.061992005, 0.029152483 0.15685844 0.020037785, 0.13881755 -0.011391133 0.074499324, 0.13863982 -0.013383836 0.074499279, -0.064929947 0.13331765 -0.057992473, -0.0085262209 0.15702716 -0.031991214, -0.064126343 0.13157317 -0.061992764, 0.14828429 0.00065359473 0.058000162, 0.05349423 0.13623598 0.062007502, 0.051483676 0.13539112 0.064945459, 0.042449087 0.14820164 0.043008059, -0.029030189 0.14541948 -0.057992011, -0.0085743666 0.15791225 -0.02799131, -0.015069932 0.15699545 -0.029991433, -0.01284337 0.15834469 -0.024239361, -0.022748962 0.15109044 -0.046991602, -0.025944978 0.15128803 -0.044991583, 0.021742731 0.15870291 0.015008777, 0.021822706 0.15845725 0.017008767, 0.021878928 0.1588892 0.013008788, 0.017911673 0.1593852 0.013008744, 0.017871648 0.15895128 0.017008781, 0.0065869242 0.16074455 -0.0057779402, 0.0050226301 0.16080815 -0.0056077689, 0.052823007 0.13452625 0.065552533, -0.0086133778 0.15863091 -0.024239242, -0.00691697 0.15868539 -0.024399176, -0.011434987 0.15904698 -0.020623296, 0.0065913349 0.16085055 -0.0019911528, 0.14311633 0.065173775 -0.031996489, 0.0087789446 0.16076046 8.7916851e-06, -0.022953361 0.15244758 -0.042991638, -0.022522941 0.15363678 -0.039416328, 0.041691348 0.14555612 0.050671816, 0.039419517 0.14611423 0.050852388, 0.043475464 0.14348564 0.054295108, -0.0086503327 0.15931213 -0.020020127, -0.0055095553 0.15933684 -0.020792291, 0.0065912902 0.1608505 0.0020088702, 0.010221258 0.16062766 0.0036274791, -0.023126125 0.15359497 -0.039255723, -0.041307852 0.13730305 -0.067637369, -0.044165701 0.13795921 -0.064930141, 0.041283444 0.14413133 0.054294959, 0.037620828 0.14506197 0.054450825, 0.014166698 0.15955776 0.015008926, 0.0065869689 0.16074398 0.0057936907, 0.0058837533 0.16067317 0.0077938139, -0.0086851865 0.15995154 -0.014991105, -0.0046940595 0.16046292 -0.011387214, -0.0032323897 0.16015449 -0.014991105, 0.13896675 -0.0093960464 0.074499518, 0.040830567 0.14255038 0.058008, -0.0082613081 0.15703768 0.032008663, 0.028380916 0.1527063 0.039275333, 0.029428899 0.15250793 0.039275244, -0.042168275 0.14016286 -0.061992288, -0.046737939 0.13973927 -0.059992239, -0.046539322 0.15251482 -0.020623699, -0.040826946 0.154116 -0.020792574, -0.042054027 0.15316775 -0.024399489, -0.0087095946 0.16040245 -0.010001898, -0.0061517507 0.16066396 -0.0077780187, -0.06809862 0.13172722 -0.057992727, -0.01236634 0.16033566 -0.0072201192, 0.04030171 0.14070401 0.062007695, -0.067230642 0.13001454 -0.061992735, 0.041781008 0.13869095 0.064948648, 0.028169081 0.1515657 0.043008476, 0.031374633 0.150251 0.045008272, 0.14636357 0.00068634748 0.061999977, -0.042721421 0.14200148 -0.05799228, -0.04528451 0.14292991 -0.054281369, -0.0087226331 0.16064292 -0.0057781786, -0.013815105 0.16035914 -0.0036077499, 0.039796054 0.13893825 0.065552562, 0.036642283 0.13861516 0.067650393, -0.070296988 0.12838241 -0.061992764, -0.066858947 0.12683973 -0.067637965, -0.070781976 0.12329632 -0.069764346, -0.016285956 0.15935707 -0.01499112, 0.14393541 0.065514296 -0.02799657, 0.027918205 0.15021586 0.047008365, 0.029719844 0.14924663 0.048671335, -0.045286238 0.15341014 -0.016991481, -0.043176368 0.14351338 -0.054432735, -0.039570123 0.14454949 -0.05443278, 0.14822629 0.0041985214 0.058000177, -0.044312865 0.14478457 -0.050657749, -0.0087285638 0.1607489 -0.0019910038, -0.05341728 0.1309059 -0.071093366, -0.05183354 0.12928391 -0.074492723, -0.053685084 0.12852621 -0.074492827, -0.056968123 0.130723 -0.069024295, 0.039262757 0.13707602 0.069041505, 0.037427247 0.1363349 0.071106076, 0.038159564 0.13395041 0.074507564, -0.030786499 0.15421554 -0.031991392, -0.021897465 0.15844694 0.017008871, -0.017946601 0.15894294 0.017008841, -0.01800406 0.15937465 0.013008952, 0.13908741 -0.0073992908 0.074499562, 0.027666271 0.14885998 0.050671801, -0.021971196 0.15887642 0.013008699, -0.043602049 0.14492789 -0.050833687, 0.15221047 0.013302118 0.047000676, 0.15357707 0.013432592 0.043000728, -0.0087284893 0.16074869 0.0020089149, -0.015259326 0.16027513 8.8959932e-06, -0.012946382 0.16035736 0.0057936609, -0.054171965 0.13275498 -0.067637742, -0.036250472 0.15685111 -0.001991272, -0.032322317 0.15770724 0.0020085871, -0.032322317 0.15770754 -0.0019912869, -0.030960023 0.15508461 -0.027991429, 0.0065042973 0.15872899 0.024254635, 0.0049000531 0.15875736 0.024418712, -0.0087226033 0.16064224 0.0057938248, -0.0070246458 0.16073245 0.0056274682, -0.030017123 0.15795398 0.0077935308, -0.024326563 0.15896043 0.0072403699, -0.0257781 0.15887496 0.0036274791, -0.011494949 0.1602692 0.0094034821, -0.023850039 0.15840164 -0.014991194, -0.027076215 0.15788221 -0.014991373, 0.0064749122 0.15800914 0.02800858, 0.0085997134 0.1574792 0.030008644, -0.0087095797 0.16040131 0.010019854, -0.0055690706 0.16059542 0.0092403144, -0.023917452 0.15884835 -0.010002077, -0.023448065 0.15896168 -0.0093873888, 0.0064385235 0.15712309 0.032008752, 0.010009184 0.15653393 0.033655718, -0.0086850673 0.15994981 0.015008822, -0.0046592355 0.15967369 0.018639088, -0.0032323152 0.16015273 0.015008792, -0.073756397 0.12467247 -0.06493105, 0.0064009279 0.15620613 0.035656154, 0.0056231171 0.15563852 0.037828773, -0.045407385 0.15382811 -0.012991548, -0.041748509 0.15526691 -0.007778421, -0.040282533 0.15539527 -0.011387631, -0.04504177 0.14971277 -0.035636991, -0.046353161 0.14884999 -0.037255988, -0.048000291 0.14933282 -0.033637062, -0.056622431 0.13875937 -0.054433107, -0.055168405 0.1400649 -0.052834824, -0.055912539 0.13810596 -0.056434035, -0.065618485 0.12523562 -0.071093604, 0.13136408 0.07803148 -0.046995759, -0.065982342 0.12266755 -0.074493229, -0.067737386 0.12170729 -0.074493155, -0.071228445 0.13006151 -0.057992741, 0.026054755 0.14018726 0.069041669, 0.022921503 0.13738069 0.074507743, 0.0248923 0.13703728 0.074507624, -0.0086503774 0.15930992 0.020037934, -0.0060739219 0.15908661 0.022254571, -0.012281477 0.15863591 0.02281262, -0.028554946 0.15797043 0.011403278, -0.045306087 0.15059084 -0.031991601, -0.049626574 0.14970592 -0.029991776, -0.057180583 0.14012694 -0.050834119, -0.059804469 0.13993782 -0.048657313, 0.1463062 0.0041595101 0.062000155, -0.045561373 0.15143952 -0.027991712, -0.047755927 0.15151671 -0.024239704, -0.0086134225 0.15862846 0.02425462, -0.013682052 0.1578683 0.026418537, -0.057727993 0.14146826 -0.046992242, -0.058958724 0.1417217 -0.044992268, -0.016285956 0.15935534 0.015008926, -0.038798973 0.15541729 -0.014991269, -0.038788825 0.15541986 -0.014991418, -0.036250442 0.15685087 0.0020085126, 0.14226994 0.069056422 -0.027996272, 0.1414645 0.068685621 -0.031996101, -0.045768812 0.1521287 -0.02423948, -0.0085742623 0.15790913 0.028008536, -0.031516507 0.15787056 -0.0019913316, -0.058246538 0.14273885 -0.042992145, -0.056145161 0.14477298 -0.039416969, -0.061773375 0.14251405 -0.039256468, 0.0061992258 0.15128219 0.05067198, 0.0059170425 0.15122259 0.050852597, 0.010456115 0.14956227 0.054295316, -0.0085262358 0.15702367 0.032008678, -0.015069976 0.15699214 0.030008674, 0.15184216 0.016997665 0.047000945, -0.012668088 0.15577692 0.035828426, -0.031516567 0.15787035 0.0020086169, 0.15320306 0.01717937 0.043000847, -0.058685169 0.14381334 -0.039256409, -0.057876855 0.14518347 -0.035814092, -0.040155947 0.15589699 -0.001991421, 0.0061386079 0.14980143 0.054295197, 0.0043976754 0.14979622 0.054451168, -0.023849994 0.15839994 0.015008584, -0.0270762 0.15788051 0.015008807, -0.0084764808 0.15610707 0.03565599, -0.01117228 0.15487269 0.039431527, -0.0067510158 0.15619135 0.035656065, -0.059068903 0.14475343 -0.035637274, -0.060580254 0.14561829 -0.029991984, -0.063489333 0.1428698 -0.035637558, -0.046150118 0.15339521 -0.014991462, -0.049090669 0.15223533 -0.01699166, -0.049227476 0.15264848 -0.012991518, 0.0060712844 0.14815804 0.058008328, 0.0028884858 0.14825433 0.058008343, 0.0080344081 0.14712241 0.060008034, -0.0084213912 0.15509278 0.039275423, -0.00968045 0.1538569 0.043008372, -0.0052456111 0.1552327 0.039275572, -0.0740235 0.12627041 -0.061993137, -0.076660365 0.1258356 -0.059992865, -0.023754656 0.15776619 0.02003777, -0.024581328 0.15694913 0.024254501, -0.023251519 0.15775108 0.020639107, -0.029233664 0.15672624 0.020812124, 0.13253887 0.078741461 -0.042995661, -0.070241332 0.13405707 -0.050834343, -0.070742473 0.13212019 -0.05443345, -0.07541877 0.13129392 -0.050658643, -0.070186585 0.13408589 -0.050834358, -0.074812874 0.13322434 -0.046992525, 0.0059926659 0.1462391 0.062007993, 0.0027835816 0.14633533 0.062008157, 0.0098710358 0.14451078 0.064948931, -0.0083586574 0.1539343 0.043008491, -0.0028465241 0.15346536 0.045008525, -0.074994639 0.12792689 -0.057992846, -0.075953349 0.12926978 -0.054282486, -0.070913821 0.13534018 -0.046992436, -0.075478762 0.13442454 -0.042992637, 0.12942876 0.081201226 -0.046995431, -0.069151893 0.13703728 -0.044992328, -0.046349749 0.15405819 -0.0057783574, -0.04773432 0.15356401 -0.0072206855, -0.049151883 0.15326443 -0.0036081821, -0.044036642 0.15484563 -0.0019915998, 0.0059174001 0.14440387 0.065552995, 0.0048778951 0.14329335 0.067650557, -0.053396732 0.1510255 -0.014991656, -0.056606397 0.14960364 -0.016991749, -0.056773752 0.15000549 -0.012991697, -0.052865058 0.15096632 -0.016991749, -0.05301705 0.15137398 -0.012991726, -0.079229146 0.11804366 -0.069767624, -0.077648744 0.11563572 -0.074493676, -0.079301447 0.11450857 -0.074493676, -0.075979844 0.11673906 -0.074493319, -0.0082840919 0.15256327 0.047008544, -0.0042364895 0.15211794 0.048671633, -0.0096013546 0.15248615 0.047008425, -0.075793073 0.1292887 -0.054433614, -0.060022235 0.14708918 -0.024239764, -0.058448121 0.14798972 -0.022793218, -0.059537873 0.14685312 -0.026399955, -0.063818425 0.14585373 -0.022239938, -0.046380252 0.15415975 -0.0019914955, -0.050541416 0.15286127 8.2999468e-06, 0.14051731 0.072556287 -0.027996033, 0.1397265 0.072155803 -0.031996191, -0.044036612 0.15484527 0.0020085424, -0.071550861 0.13655588 -0.042992517, -0.072794378 0.13768455 -0.037814721, -0.070995331 0.13741237 -0.04141748, -0.040156096 0.1558969 0.0020085126, 0.0058381408 0.14246836 0.069041699, 0.006150499 0.14124495 0.07110627, 0.011652783 0.14168161 0.069782183, -0.0082092434 0.15118641 0.05067192, -0.011803761 0.15006799 0.052853405, -0.005603686 0.15065619 0.052294627, -0.060280174 0.14772102 -0.020020887, -0.062697604 0.14692518 -0.018623888, -0.061529249 0.1478987 -0.014991924, -0.046380281 0.15415967 0.0020084232, -0.048304632 0.15345591 0.0057933927, -0.083942086 0.11624131 -0.067638651, -0.082385659 0.11914414 -0.064934447, -0.080937907 0.11335784 -0.074493915, -0.084627718 0.1147691 -0.069025218, -0.086870596 0.11551318 -0.06553632, -0.0081290305 0.14970654 0.054295346, -0.013149768 0.14840636 0.056451857, -0.0077444911 0.1480802 0.058008254, -0.038798928 0.15541562 0.015008494, -0.040073439 0.15463364 0.01863873, -0.03878881 0.1554181 0.015008509, -0.04116556 0.1553297 0.0092400014, -0.045407355 0.15382662 0.01300846, -0.046349779 0.15405777 0.0057932436, -0.046870127 0.15369296 0.0094030797, -0.042614862 0.15513951 0.0056271404, -0.060521975 0.1483137 -0.014991909, -0.030960128 0.15508157 0.028008595, -0.02665849 0.15544438 0.030008584, -0.030549899 0.1558674 0.024418652, -0.031841576 0.15490296 0.028008491, -0.0080398172 0.14806435 0.058008179, -0.085690618 0.11866218 -0.061993271, -0.089064494 0.11615133 -0.061993524, -0.090178907 0.11771655 -0.057993516, -0.085450098 0.12004042 -0.059993431, -0.060692862 0.14873174 -0.010002688, -0.059651867 0.14941189 -0.0057786405, -0.058232337 0.14975858 -0.0093879849, -0.063848525 0.1474638 -0.0092208385, -0.030786544 0.15421185 0.032008663, -0.031691641 0.15402845 0.032008499, -0.025074214 0.15483633 0.033655629, 0.15406902 0.035663962 0.028001815, -0.029151186 0.15298751 0.03782846, -0.0079357922 0.14614654 0.062008247, -0.0076337308 0.14616257 0.062008038, -0.014472052 0.14662936 0.060008183, -0.012360394 0.14432082 0.064945921, 0.011387125 0.13881341 0.074507624, 0.013379514 0.13863561 0.074507788, -0.022953257 0.15244281 0.043008462, -0.020918176 0.15273523 0.043008432, -0.023482099 0.15411729 0.037275121, -0.027552485 0.15219134 0.04143171, -0.025945082 0.15128312 0.045008436, -0.00065693259 0.1482811 0.058008343, -0.086814776 0.12021887 -0.057993472, 0.10749392 0.088576436 -0.074495122, -0.085241452 0.12220171 -0.056434825, -0.046150073 0.15339339 0.015008569, -0.045286253 0.15340823 0.017008558, -0.049227566 0.15264702 0.01300846, -0.049090773 0.15223345 0.017008424, 0.13057642 0.081954896 -0.042995587, -0.060783923 0.14895487 -0.0057786852, -0.061841831 0.14864913 8.225441e-06, -0.065246761 0.14706254 -0.0056086183, -0.0078360587 0.14431247 0.06555289, -0.010277838 0.14178976 0.069779038, -0.0061115623 0.14439589 0.065553054, -0.022748992 0.15108511 0.04700838, -0.020686001 0.15138137 0.047008395, -0.021904632 0.14981633 0.050672039, -0.087739423 0.12149882 -0.054434061, -0.089790583 0.12111014 -0.05228205, -0.084951907 0.12427709 -0.052835688, -0.09329313 0.10623536 -0.071094781, -0.091019154 0.10819021 -0.071094692, -0.090107232 0.10621488 -0.074494109, -0.0934062 0.10878208 -0.067638934, -0.091623276 0.10490969 -0.074494243, -0.093120649 0.10358295 -0.074494243, -0.096442476 0.10445464 -0.069765389, -0.0077311099 0.14237818 0.069041729, -0.0062263459 0.1391404 0.074507728, -0.0046049505 0.14251363 0.069042116, -0.0082241893 0.13903672 0.074507669, -0.079531685 0.13566458 -0.031992435, -0.07558012 0.13790518 -0.031992406, -0.078312993 0.13480368 -0.037256643, -0.076010182 0.13868025 -0.027992293, -0.080026209 0.13490778 -0.033637747, -0.081694633 0.13490966 -0.029992566, -0.022543743 0.1497215 0.050671905, -0.02788201 0.14874759 0.050852656, -0.023087367 0.148139 0.054295212, -0.088604122 0.1226961 -0.050834998, -0.089016035 0.12504897 -0.044993028, -0.065171972 0.14311814 -0.031992093, -0.089443386 0.12312159 -0.048658594, 0.12741686 0.084323138 -0.046995401, -0.094611093 0.10773581 -0.067639142, -0.09964855 0.1051344 -0.064932063, -0.097101405 0.10952109 -0.061994031, -0.079980031 0.13642916 -0.027992576, -0.080274001 0.13709128 -0.024240538, -0.045769066 0.1521264 0.024254113, -0.041322023 0.15374652 0.022254154, -0.047273725 0.15192574 0.022812232, -0.048468396 0.15086555 0.026418284, -0.043245435 0.152114 0.028008327, -0.053396508 0.15102372 0.015008315, -0.056773752 0.15000409 0.013008356, -0.056606352 0.14960176 0.017008424, -0.05301711 0.15137255 0.013008475, -0.052865148 0.15096432 0.017008498, -0.060783923 0.14895409 0.0057933033, -0.059088677 0.14956173 0.0072398186, -0.060484797 0.14915535 0.0036268681, -0.064412683 0.14731434 0.0077929646, -0.074346095 0.14188907 -0.014992118, -0.078287631 0.13948667 -0.016992107, -0.078498796 0.13986722 -0.012992308, -0.074097127 0.1411671 -0.020793423, -0.073851168 0.14253548 -0.011388332, -0.072400406 0.14289171 -0.014992163, -0.045561388 0.15143636 0.028008327, -0.049626559 0.14970261 0.030008227, -0.060692787 0.1487307 0.010019064, -0.062990859 0.14765573 0.011402592, -0.0615291 0.14789698 0.015008107, -0.045305967 0.1505872 0.032008469, -0.042998746 0.15126222 0.03200841, -0.04701452 0.14905244 0.035828039, 0.15320127 0.035481215 0.032002002, -0.090935692 0.12592393 -0.039257377, -0.091936752 0.12519526 -0.039257407, -0.088731587 0.12866467 -0.035814971, -0.08695206 0.12864983 -0.039417729, 0.009391889 0.13896263 0.074507758, -0.060522199 0.148312 0.015008092, -0.045041606 0.14970827 0.035655633, -0.045355007 0.14850348 0.03943114, -0.041338176 0.15077308 0.035655677, -0.091530174 0.12674707 -0.035638452, -0.093688518 0.1251601 -0.035638481, -0.081013188 0.13819081 -0.014992356, -0.081735253 0.13749471 -0.016992494, -0.081960648 0.137867 -0.012992367, 0.15313914 0.039466083 0.028002053, -0.098891065 0.1126084 -0.054434508, -0.098367721 0.11306605 -0.054434493, -0.098383293 0.1109508 -0.057993934, -0.10281353 0.10912749 -0.054283544, -0.10274304 0.11122012 -0.050659657, -0.029030129 0.14541301 0.05800806, -0.024905622 0.14522156 0.060008138, -0.029046193 0.14701906 0.05445084, -0.030174434 0.1451799 0.058008164, -0.044749036 0.1487354 0.039275169, -0.043674618 0.14784521 0.043008283, -0.039657116 0.1501734 0.039275199, -0.10296881 0.096886307 -0.071095109, -0.10350895 0.097454011 -0.069768786, -0.10005091 0.096905202 -0.074494585, -0.10279281 0.093991607 -0.074494809, -0.10413216 0.092505544 -0.074495018, -0.10143232 0.095458299 -0.074494839, -0.1080434 0.093060225 -0.069026396, -0.00068993866 0.14636025 0.062008142, -0.06028004 0.14771861 0.020037204, -0.063375771 0.14629149 0.020811737, -0.058889762 0.14754415 0.024254009, -0.057771802 0.1486221 0.020638525, -0.092067063 0.12749025 -0.031992957, -0.095384449 0.12502781 -0.031992957, -0.091464221 0.12848714 -0.029992819, -0.095898941 0.12575009 -0.027993098, -0.099865928 0.11371839 -0.050835371, -0.10258205 0.11323684 -0.046993554, -0.09826313 0.11510611 -0.05083552, -0.028654233 0.1435295 0.062007889, -0.027130976 0.14078599 0.067650467, -0.022533879 0.14308399 0.064948916, -0.029849678 0.14328584 0.062007889, -0.065512851 0.14393696 -0.02799201, -0.092586175 0.12820891 -0.027993023, -0.09072262 0.12992287 -0.026401028, -0.0042018592 0.14822289 0.058008328, 0.12853599 0.085119367 -0.042995378, -0.060022429 0.14708683 0.024254009, -0.06446816 0.14516145 0.024418056, -0.060580164 0.14561504 0.030008018, -0.10082187 0.11480668 -0.046993613, -0.10349813 0.11425874 -0.04299368, -0.097911105 0.11821374 -0.044993505, 0.13921967 0.0042230785 0.074500278, 0.13926607 0.002223134 0.074500173, -0.087496832 0.13417956 -0.014992625, -0.085371524 0.13578129 -0.012992546, -0.085132495 0.13541761 -0.016992673, -0.088477001 0.13325664 -0.016992584, -0.088729471 0.1336112 -0.012992784, -0.093007669 0.12879235 -0.024240807, -0.094673648 0.12799582 -0.022240892, -0.089913338 0.13127345 -0.022794232, 0.0073950887 0.13908327 0.074507773, -0.081417501 0.13887975 -0.0019923151, -0.077388823 0.14116439 -0.0019921809, -0.080708534 0.139092 -0.0072214305, -0.082024157 0.13848442 -0.0036090016, -0.083289072 0.13778228 7.5697899e-06, -0.013304904 0.15220779 0.047008529, -0.013435125 0.15357453 0.043008432, -0.077388868 0.14116412 0.0020076334, -0.10172774 0.11583796 -0.042993605, -0.099792048 0.11816937 -0.041418582, -0.093407214 0.12934536 -0.020021737, -0.093819246 0.1292899 -0.018624917, -0.092896938 0.13049901 -0.014992774, -0.081417665 0.13887963 0.0020077229, -0.081240833 0.13885963 0.0057924986, -0.10249345 0.11670971 -0.039257929, -0.10634559 0.11399767 -0.037257984, -0.10160632 0.11803406 -0.037815824, -0.043195188 0.14357004 0.054295108, -0.043292552 0.14652634 0.047008038, -0.044901684 0.14367869 0.052853107, -0.045844138 0.14175949 0.056451604, -0.038988039 0.14563206 0.052294344, -0.040501878 0.14264399 0.058008, -0.074346125 0.14188752 0.015007675, -0.0784989 0.13986585 0.01300776, -0.078287646 0.13948491 0.017007828, -0.074697599 0.14227498 0.009239316, -0.073478058 0.14183947 0.018638179, -0.072400331 0.14289016 0.015007973, -0.05906859 0.14474902 0.035655528, -0.057188109 0.14502794 0.03727439, -0.058900356 0.14537475 0.033655226, -0.062463671 0.14266509 0.037827939, -0.10316359 0.11747268 -0.035638794, -0.10437158 0.1176295 -0.031993389, -0.042721495 0.1419951 0.05800797, -0.046738029 0.1397326 0.060007736, -0.0586849 0.14380831 0.039274797, -0.060727879 0.14224446 0.041431069, -0.054381132 0.14425111 0.04300797, -0.11125007 0.095115274 -0.061994553, -0.11001843 0.098016381 -0.059994563, -0.10683142 0.097824425 -0.064935535, -0.11039557 0.093286544 -0.065537661, -0.11267671 0.093420446 -0.061994851, 0.15227902 0.039251 0.032002091, -0.11411153 0.094698608 -0.057994753, -0.094046697 0.1302304 -0.010003686, -0.090096608 0.13304585 -0.0093888342, -0.095061645 0.12955907 -0.009221971, -0.091403529 0.13239205 -0.0057797879, -0.042168111 0.14015576 0.062007651, -0.044165656 0.13795176 0.064945355, -0.039967418 0.14079934 0.062007859, -0.058246553 0.14273408 0.043007851, -0.05895865 0.14171675 0.045007944, -0.11270961 0.096362859 -0.057994485, -0.11029598 0.1001699 -0.056436107, -0.11127825 0.10470325 -0.046994239, -0.11055933 0.10546181 -0.046994165, -0.11047567 0.10225776 -0.05283688, -0.11459744 0.10013175 -0.048659429, -0.11460972 0.10210589 -0.044994324, -0.11158495 0.10637528 -0.042994246, -0.081013173 0.1381892 0.01500763, -0.081960663 0.13786563 0.013007671, -0.081735402 0.13749287 0.017007619, -0.094187826 0.13042554 -0.0057796836, -0.096335262 0.12885651 -0.0056096762, -0.041639134 0.13839701 0.065552711, -0.038090244 0.13941556 0.065552831, -0.078028843 0.13136658 -0.046992719, -0.057728097 0.14146301 0.047007933, -0.054693371 0.14118585 0.050671607, -0.053853542 0.14298278 0.047007963, -0.060283259 0.13881388 0.050851911, -0.1139099 0.097388744 -0.054435611, -0.11448823 0.09809351 -0.052283183, -0.10482873 0.11936814 -0.024241313, -0.10876672 0.11579138 -0.024241641, -0.1081038 0.11721855 -0.020625517, -0.1043458 0.11975276 -0.024401397, -0.10496341 0.11828944 -0.027993515, -0.094250202 0.1305117 -0.0019927919, -0.097548053 0.12806547 -0.0019929856, -0.093368962 0.13116118 7.4505806e-06, -0.11227793 0.10564354 -0.042994216, -0.11339873 0.1060757 -0.03941901, -0.0041629672 0.14630258 0.062008142, 0.11552383 0.09297049 -0.057994828, 0.1140016 0.09179911 -0.06199494, -0.11570837 0.081246048 -0.071096107, -0.11526981 0.085270107 -0.067640334, -0.11281095 0.085224122 -0.07109572, -0.11266978 0.081891477 -0.074495539, -0.11383434 0.080264777 -0.074495628, -0.11726688 0.080375373 -0.069766596, -0.041081026 0.13654199 0.069041684, -0.041572094 0.13594773 0.069778845, -0.038957655 0.13372067 0.074507639, -0.037032828 0.13426632 0.074507385, -0.03620261 0.13791582 0.069041699, -0.057207018 0.14018613 0.050671458, -0.055473387 0.13928735 0.05429484, -0.10527915 0.1198808 -0.020022362, -0.10736321 0.11856878 -0.016993478, -0.10365169 0.12113959 -0.020794541, -0.094250068 0.13051146 0.002007246, -0.097547978 0.12806517 0.0020068586, -0.069054931 0.14227143 -0.027992129, -0.068683833 0.14146611 -0.031992033, -0.092158705 0.13195655 0.0036260486, -0.11734281 0.082393467 -0.067640513, -0.11903676 0.085168153 -0.061995223, -0.12054399 0.080324739 -0.064933613, -0.056647047 0.13881397 0.054294646, -0.056596935 0.13603857 0.060007438, -0.061033547 0.13686949 0.054450363, -0.087496758 0.13417783 0.015007243, -0.088729516 0.13360974 0.013007328, -0.088476837 0.13325474 0.017007425, -0.085371643 0.13577986 0.013007462, -0.085132509 0.1354157 0.017007574, -0.09418796 0.13042501 0.0057920665, -0.095578387 0.12928781 0.0077920407, -0.090888008 0.13266361 0.0072388798, -0.10570164 0.12036172 -0.014993444, -0.1037166 0.12252846 -0.011389449, -0.1023812 0.12319863 -0.01499334, -0.10765389 0.11889294 -0.012993515, -0.017000332 0.15183938 0.047008425, -0.017181858 0.1532006 0.043008327, -0.079979986 0.13642603 0.028007448, -0.076010063 0.13867718 0.028007776, -0.079895392 0.13759732 0.022811428, -0.080824241 0.13629779 0.026417524, -0.081694573 0.13490632 0.030007482, -0.072089225 0.13757882 0.039274424, -0.072080165 0.13758373 0.039274335, -0.07385233 0.13779423 0.035654902, -0.077263415 0.13468763 0.039430425, -0.075478792 0.13441977 0.043007329, -0.11978719 0.084109426 -0.061995223, -0.12366523 0.080112636 -0.059995547, -0.12060478 0.086276799 -0.057995319, -0.094046652 0.13022926 0.01001811, -0.092896968 0.13049752 0.015007153, -0.094268069 0.12993681 0.011401698, -0.10600016 0.12070096 -0.010004163, -0.10963584 0.11764541 -0.0072225779, 0.14656109 0.066605181 -0.0019964278, -0.10498165 0.12177655 -0.0077802688, -0.07953164 0.13566104 0.032007515, -0.079003394 0.13485348 0.03582716, -0.075580046 0.13790146 0.032007575, 0.13996828 0.075083762 -0.024403781, -0.071550876 0.13655123 0.043007672, -0.069151759 0.13703215 0.045007616, -0.12135884 0.085212767 -0.057995304, -0.12451844 0.083513379 -0.054285049, -0.10615914 0.12088194 -0.0057802349, -0.10686071 0.12040445 -0.0019932538, -0.054606393 0.13381225 0.065552309, -0.053808913 0.1344822 0.064948305, -0.057779521 0.131219 0.067649856, -0.11883137 0.10159525 -0.035639673, -0.11513719 0.1056942 -0.035816208, -0.11748967 0.10159856 -0.039258897, -0.11776163 0.10491291 -0.02999422, -0.11918987 0.10117441 -0.035639912, -0.11130919 0.11519596 -0.014993668, -0.11028132 0.11585957 -0.016993642, -0.11313117 0.11307868 -0.016993761, -0.11344521 0.11338007 -0.012993753, -0.11058393 0.11617261 -0.012993559, -0.078739196 0.13254115 -0.042992592, -0.070913658 0.13533485 0.047007471, -0.070417464 0.13330489 0.052293688, -0.06981954 0.13521513 0.048670515, -0.074812904 0.13321927 0.047007278, 0.13833383 0.079311162 -0.020627588, -0.12265125 0.08611989 -0.054435968, -0.12491502 0.085568994 -0.050661162, -0.12106037 0.088342518 -0.054435968, 0.11326806 0.095705926 -0.057994753, -0.12290712 0.069879502 -0.071096659, -0.12112983 0.068761528 -0.074496195, -0.12210481 0.067014635 -0.074496418, -0.12012966 0.070494086 -0.074496195, -0.12604162 0.066685051 -0.069027871, -0.12259848 0.071977764 -0.069770202, 0.11179106 0.094478667 -0.061994702, -0.053874493 0.13201869 0.069041237, -0.055744231 0.12992549 0.071105599, -0.053685054 0.12851796 0.074507073, -0.05183357 0.12927562 0.074507266, -0.050976276 0.1327064 0.069781616, -0.081198558 0.12943131 -0.046992928, -0.093407154 0.12934297 0.020036235, -0.090245232 0.13074058 0.02425316, -0.089394957 0.13204032 0.020637661, -0.094340071 0.12852126 0.02081047, -0.11952849 0.10219088 -0.031994298, -0.12081389 0.1006681 -0.031994462, -0.1214762 0.10125786 -0.02799435, -0.12386018 0.086968541 -0.05083707, -0.12520696 0.087571144 -0.046995088, -0.12141253 0.090354681 -0.050836697, -0.12464327 0.070866466 -0.067641273, -0.12592013 0.071599662 -0.064936951, -0.12020239 0.1027669 -0.027994365, -0.1173584 0.10647765 -0.02640225, -0.093007773 0.12878984 0.024252981, -0.09515354 0.12717634 0.024416879, -0.12504594 0.08780092 -0.046995223, -0.12358455 0.093000889 -0.041419938, -0.12176083 0.093462706 -0.044994697, -0.12632778 0.088363498 -0.0429952, 0.14656106 0.066604942 0.0020035803, -0.10615918 0.12088135 0.005791679, -0.10686061 0.12040418 0.0020066649, -0.11010316 0.11730039 0.0057913661, -0.10891356 0.11813641 0.009401083, -0.10570727 0.12128577 0.0056253374, -0.11666425 0.10976914 -0.014993981, -0.11960645 0.10655579 -0.014993966, -0.11744325 0.1096617 -0.0093901157, -0.11623603 0.11051714 -0.012993872, -0.072554737 0.14051878 -0.027992293, -0.072153971 0.13972825 -0.031992197, -0.11591078 0.11022758 -0.01699394, -0.1207494 0.10323453 -0.024242327, -0.12078145 0.10372004 -0.022242293, -0.092586055 0.12820584 0.028007105, -0.091464072 0.12848359 0.030007035, -0.095898867 0.12574711 0.028006941, -0.12616941 0.08858943 -0.04299517, -0.10600004 0.12069997 0.010017633, -0.10765387 0.11889148 0.013006613, -0.10448411 0.12208611 0.0092382431, -0.092067137 0.12748677 0.032007143, -0.089772925 0.12862334 0.033654347, -0.095384464 0.12502411 0.032007217, -0.12711929 0.089256227 -0.039259449, -0.1253237 0.092465401 -0.037817374, -0.12904583 0.087475449 -0.037259325, -0.1057017 0.12036005 0.015006572, -0.10736322 0.11856693 0.01700668, -0.10319833 0.12193277 0.018636957, -0.10238117 0.12319699 0.015006691, -0.091529936 0.12674272 0.03565453, -0.0926442 0.12518859 0.03782706, -0.088026389 0.12866607 0.037273526, -0.1279503 0.089839458 -0.035640523, -0.12792927 0.09145537 -0.031994969, -0.13063446 0.086825818 -0.033640355, -0.074994698 0.12792045 0.058007166, -0.075748071 0.1300849 0.052852303, -0.076239899 0.12800384 0.05645071, -0.076660365 0.12582898 0.060006946, -0.07122843 0.13005501 0.05800727, -0.090935335 0.12591904 0.039273784, -0.09085831 0.12516502 0.041430146, -0.13053744 0.066205859 -0.06199646, -0.12838534 0.066382527 -0.065539137, -0.13063897 0.066005439 -0.061996385, -0.12906989 0.071077466 -0.059996054, -0.13232228 0.066932082 -0.057996362, -0.12899271 0.057880014 -0.071097314, -0.12894577 0.05798468 -0.071097329, -0.12726676 0.05660066 -0.074497014, -0.13135336 0.057482183 -0.067641959, -0.12806648 0.054766953 -0.074497104, -0.066180155 0.12629989 0.069041103, -0.064213827 0.12359434 0.074506909, -0.065985009 0.12640196 0.069041103, -0.06815891 0.12744418 0.065552086, -0.070781991 0.12328845 0.0697781, -0.067737296 0.12169904 0.074506953, -0.065982401 0.1226593 0.074506968, -0.035665512 0.15406755 0.028008565, -0.10527919 0.11987838 0.020035788, -0.10851084 0.11636895 0.022810087, -0.10393849 0.12059164 0.022252351, -0.12870097 0.090366274 -0.031995147, -0.12865321 0.091967076 -0.027994961, -0.13213885 0.086103439 -0.029995352, 0.14208378 0.075252265 -0.0077828467, -0.13156606 0.074801058 -0.050837621, -0.13344502 0.070158154 -0.052284881, -0.13400519 0.072120905 -0.048661023, -0.13125433 0.078215867 -0.046995729, -0.13045962 0.075110853 -0.0528384, -0.12982008 0.073115438 -0.056437582, -0.07402353 0.1262635 0.06200695, -0.073756322 0.12466517 0.064944863, -0.070296884 0.12837544 0.062007055, -0.088572323 0.10749805 -0.074494138, -0.13225013 0.067074329 -0.057996288, -0.12942648 0.090875596 -0.027994961, -0.13180538 0.088685393 -0.024243206, -0.10482906 0.11936566 0.0242524, -0.10496332 0.11828637 0.028006509, -0.081952631 0.1305787 -0.042992875, -0.13282563 0.075517118 -0.046995714, -0.13445644 0.074042797 -0.044995889, -0.13245754 0.078878313 -0.04299596, -0.11130907 0.11519417 0.015006498, -0.11028136 0.11585787 0.017006472, -0.11058393 0.11617109 0.013006508, -0.11344513 0.11337861 0.01300621, -0.11313118 0.11307675 0.017006263, -0.12228183 0.10454345 -0.0057811737, -0.12021405 0.10709602 5.7965517e-06, -0.11857168 0.10873353 -0.0057809502, -0.12150764 0.10515755 -0.0092232078, -0.12259305 0.10418919 -0.0056111068, -0.13001572 0.091289043 -0.024242967, -0.12837693 0.093531191 -0.024402872, -0.13147664 0.090224177 -0.020626962, -0.12236269 0.10461247 -0.0019942075, -0.1235995 0.10314819 -0.0019944161, -0.13401885 0.076195151 -0.0429959, -0.13715117 0.072907358 -0.039260358, 0.1448521 0.070244104 0.0020038784, -0.13415925 0.078182817 -0.03942062, 0.14485218 0.070244282 -0.0019961894, -0.088645369 0.12274733 0.050670505, -0.085077554 0.12345123 0.054293975, -0.084739536 0.12547556 0.050670743, -0.08901605 0.12504387 0.04500708, -0.08966139 0.1219191 0.050850913, -0.13057432 0.091680914 -0.020023927, -0.12800875 0.095037788 -0.020795941, -0.13105537 0.09170562 -0.016995028, -0.12236282 0.10461226 0.0020059198, -0.11921126 0.10814101 0.0036244243, -0.12359954 0.10314801 0.002005741, -0.084320486 0.12741956 -0.046992883, -0.13502774 0.076768667 -0.039260298, -0.13576925 0.077423871 -0.035817802, -0.087777793 0.12154594 0.054293707, -0.089960277 0.11985663 0.054449454, -0.11666419 0.10976744 0.015006036, -0.11960635 0.10655403 0.015005738, -0.11653584 0.10883752 0.02063638, -0.11623594 0.11051562 0.013006136, -0.11591093 0.1102258 0.017006263, -0.10316329 0.11746836 0.03565383, -0.10437141 0.11762586 0.032006502, -0.10703102 0.11389244 0.035826027, -0.10529765 0.11411801 0.039429292, -0.10266317 0.11790562 0.03565383, -0.12228182 0.10454291 0.0057906359, -0.12195131 0.10477811 0.0077907294, -0.13109834 0.092048764 -0.014994964, -0.13329755 0.088415027 -0.016995102, -0.133662 0.08865267 -0.012995094, -0.12838109 0.096377224 -0.011390969, -0.12722859 0.097327828 -0.014994532, -0.13141069 0.091956735 -0.012994945, -0.086814895 0.12021247 0.058006689, -0.085450083 0.12003371 0.060006678, -0.090178981 0.1177102 0.058006585, -0.10249305 0.11670485 0.039273202, -0.10349813 0.11425403 0.043006301, -0.10088855 0.11809468 0.039273307, -0.13623944 0.053497791 -0.061997056, -0.13500331 0.056544691 -0.061996847, -0.13539477 0.051487386 -0.064935118, -0.13677876 0.057276666 -0.057996854, -0.13839079 0.050586015 -0.059997201, -0.13146825 0.092308193 -0.010005862, -0.12944733 0.095362753 -0.0077815801, -0.035483167 0.15319952 0.032008559, -0.13306551 0.090299457 -0.0072239041, -0.085690707 0.11865532 0.062006637, -0.089064538 0.11614448 0.062006384, -0.082385749 0.11913672 0.064947516, -0.10172769 0.1158331 0.04300648, -0.097911149 0.11820871 0.045006663, -0.13802673 0.054199368 -0.057996973, -0.13997935 0.053711593 -0.05428654, -0.13166559 0.092446446 -0.0057818145, -0.13097379 0.0936068 -0.0019949526, -0.13398714 0.089181185 -0.003611818, -0.084615543 0.11716625 0.06555143, -0.085530624 0.11507171 0.067649007, -0.039467663 0.15313768 0.028008416, -0.13532977 0.085706681 -0.014995366, -0.13545699 0.085069537 -0.016995296, -0.13583013 0.085293323 -0.012995347, -0.10082188 0.11480147 0.047006354, -0.10258195 0.11323169 0.047006205, -0.098157823 0.11628857 0.048669562, -0.13949655 0.054776102 -0.054437876, -0.13768259 0.05918926 -0.054437548, -0.14082366 0.055627525 -0.050662696, -0.13175271 0.092507482 -0.0019949079, -0.13482219 0.087999761 4.7385693e-06, -0.083481446 0.11559588 0.069040447, -0.079301476 0.11450022 0.074506417, -0.079229176 0.11803576 0.069780856, -0.08325848 0.11426359 0.071104884, -0.099911928 0.11376521 0.050669968, -0.10279623 0.10996786 0.052851111, -0.098315582 0.11429328 0.052292466, -0.1386978 0.078854084 -0.020024613, -0.14083295 0.074243188 -0.022243902, -0.14062482 0.075779617 -0.018627673, -0.14031826 0.077269197 -0.014995694, -0.13796589 0.079261303 -0.022797003, -0.13753237 0.081671387 -0.016995579, -0.13175274 0.092507213 0.0020050853, -0.1309738 0.093606561 0.0020049959, -0.13344449 0.089859068 0.0057897717, -0.098934248 0.11265171 0.05429329, -0.098383203 0.11094436 0.058006287, -0.085117042 0.12853822 -0.042992845, -0.12074989 0.10323203 0.024251536, -0.1170754 0.10738117 0.024251819, -0.12057383 0.10430649 0.020809188, -0.11776158 0.10490957 0.030005723, -0.12106757 0.10281417 0.024415478, -0.13166577 0.092446029 0.005790025, -0.0042272806 0.13921559 0.074507698, -0.0022272021 0.13926184 0.074507818, -0.13004574 0.094722867 0.0056238174, -0.132471 0.090938866 0.0093995333, -0.13925454 0.079170406 -0.014995679, -0.13791411 0.081881374 -0.012995705, -0.12020224 0.10276368 0.028005823, -0.12147622 0.10125476 0.028005719, -0.13146828 0.092307001 0.010016009, -0.1290313 0.095775187 0.0092367977, 0.14305268 0.073839486 0.0020038784, 0.1430527 0.073839664 -0.0019959509, -0.13141084 0.091955364 0.013004974, -0.13964738 0.079393417 -0.010006532, -0.13979442 0.079622656 -0.0057824999, -0.13890058 0.080778837 -0.0093917996, -0.14186078 0.075482994 -0.0092250705, -0.11952849 0.10218728 0.032005593, -0.11614409 0.10542202 0.033653051, -0.12081385 0.10066447 0.032005653, 0.14736408 0.037977487 0.048665196, 0.14898656 0.036922485 0.045002192, -0.11227788 0.10563883 0.04300569, -0.11445083 0.1058524 0.037272245, -0.11643253 0.10180873 0.041428849, -0.11158496 0.10637045 0.043006018, -0.11460975 0.10210088 0.045005679, -0.13109842 0.092047274 0.015005037, -0.13329749 0.088413149 0.017004848, -0.13105537 0.091703862 0.017005175, -0.13366206 0.08865124 0.013004959, -0.12774371 0.095911711 0.018635482, -0.12722841 0.09732613 0.015005261, -0.11883093 0.10159093 0.035652831, -0.11817904 0.1014345 0.037825748, -0.1398571 0.079512358 -0.0057825595, -0.14270367 0.074297547 -0.0056127459, -0.095369965 0.10859242 0.065551117, -0.099648505 0.10512719 0.064943761, -0.096442506 0.10444683 0.069776937, 0.10561897 0.10274196 -0.05999428, -0.09480983 0.10908195 0.065551057, -0.097101435 0.10951412 0.062006041, -0.14552371 0.057141781 -0.035642266, -0.14507228 0.060695529 -0.031996682, -0.14275637 0.062260002 -0.037818834, -0.14527492 0.056566864 -0.037261054, -0.1466794 0.05558002 -0.033642307, -0.11127801 0.10469785 0.047005832, -0.11053647 0.10347325 0.050669536, -0.1105594 0.10545656 0.047005862, -0.094091892 0.10713693 0.069039941, -0.091623232 0.10490137 0.074505672, -0.092458561 0.10854968 0.06904012, -0.093120486 0.10357463 0.074505866, -0.13057432 0.091678619 0.020034045, -0.13168491 0.089305341 0.022808596, -0.12816706 0.094439626 0.022250965, -0.14637731 0.057476819 -0.031996951, -0.039252907 0.1522772 0.032008424, -0.14798522 0.054541051 -0.029997021, -0.1458919 0.061033249 -0.027996689, -0.14720254 0.057800591 -0.027996898, -0.14823496 0.057132632 -0.024244875, -0.13001595 0.091286451 0.02425085, -0.1319582 0.08773151 0.026414856, -0.12865312 0.091963947 0.028005078, -0.13532996 0.085705042 0.015004784, -0.14614958 0.065574825 -0.014996424, 0.13787098 0.019784153 0.074501127, 0.13814107 0.017801851 0.074500948, 0.14072639 0.020163357 0.069775373, -0.14569601 0.066576719 -0.01499632, 0.1444203 0.03363353 0.05800201, -0.1478727 0.058063477 -0.02424477, -0.1459706 0.062619776 -0.024404585, -0.12942657 0.090872526 0.028005034, -0.13213882 0.086100221 0.030004665, -0.13964739 0.079392284 0.010015279, -0.14131032 0.076167643 0.011398688, -0.14031835 0.077267468 0.015004158, -0.12870085 0.090362787 0.032004967, -0.12969145 0.08722043 0.035824522, -0.1279293 0.091451883 0.032005146, -0.11395988 0.097425193 0.05429253, -0.11041561 0.10142437 0.054292768, -0.11454356 0.098910689 0.050849646, -0.11001842 0.098009676 0.060005441, -0.11437602 0.096833497 0.054448232, -0.13925445 0.079168588 0.015004352, -0.12794992 0.089835346 0.03565228, -0.12805186 0.087825835 0.039427608, -0.12632629 0.092104852 0.035652459, -0.14910413 0.058546484 -0.014996842, -0.11270969 0.096356243 0.058005407, -0.092967331 0.11552685 -0.057993695, -0.12711863 0.089251488 0.039271757, -0.091795683 0.11400521 -0.061993778, -0.12463823 0.092683971 0.039271817, -0.13869776 0.07885167 0.020033374, -0.13803509 0.078637123 0.024250209, -0.13783281 0.080177069 0.020634726, -0.14076142 0.07486096 0.020807624, -0.11124992 0.095108092 0.062005267, -0.12616944 0.088584751 0.043004826, -0.12157418 0.09153071 0.048668042, -0.1217608 0.09345758 0.045005158, -0.13810483 0.078514338 0.02425006, -0.14974929 0.058799237 -0.0057836175, -0.15047258 0.057130367 -0.0036136359, -0.10985406 0.093914568 0.065550104, -0.151721 0.051385581 -0.014997259, -0.12504603 0.087795585 0.047004938, -0.14984827 0.05883795 -0.0019969791, -0.15102391 0.05579263 2.8312206e-06, -0.12391739 0.087003022 0.050668359, -0.12468977 0.084336251 0.05284965, -0.1212841 0.089550257 0.0522912, -0.14984828 0.058837771 0.0020030886, 0.13757265 0.021762282 0.074501216, -0.15009449 0.057912022 0.0057880133, -0.12270479 0.086151451 0.054291934, -0.12422997 0.082247913 0.056448251, -0.14614964 0.065573126 0.015003532, -0.14569587 0.066574901 0.015003592, -0.1497494 0.058798641 0.0057879388, -0.12135898 0.085206449 0.058004797, -0.12366523 0.080105901 0.060004428, -0.066605017 0.14656109 -0.0019919127, -0.1350272 0.076763868 0.039270997, -0.13513629 0.077730656 0.03727068, -0.13616848 0.073347449 0.041427389, 0.13907622 0.025430262 0.071099907, -0.11978728 0.08410266 0.062004671, -0.12054409 0.080317438 0.06494239, -0.075082451 0.13996965 -0.024400309, 0.14254048 0.033238173 0.062001795, -0.13401893 0.076190442 0.043004155, -0.13445635 0.07403791 0.045003951, -0.14910424 0.058544874 0.01500304, -0.11828417 0.083047062 0.065549701, -0.11726694 0.080367506 0.069775745, -0.11670667 0.085249811 0.065549701, -0.13282564 0.075511813 0.047004148, -0.13079074 0.076282293 0.050668076, -0.13368207 0.070942581 0.050848216, -0.11669903 0.081933826 0.069038615, -0.11383432 0.080256373 0.074504405, 0.14357479 0.037076771 0.05800201, -0.13162693 0.074830115 0.050667748, -0.1302169 0.074311465 0.054291099, -0.13033865 0.074097484 0.054291129, -0.079309925 0.13833508 -0.020624399, -0.13305652 0.068954527 0.054446504, -0.14787292 0.058060735 0.024248883, -0.1481723 0.056168526 0.026412979, -0.15172082 0.051383823 0.015002608, -0.095702603 0.11327124 -0.057993695, -0.09447518 0.11179462 -0.061993942, -0.14720236 0.057797372 0.028003141, -0.14798525 0.054537803 0.030002967, 0.13724568 0.023736 0.074501589, -0.14637718 0.057473123 0.032003269, -0.14584866 0.056174517 0.035822883, -0.14552316 0.057137698 0.035650522, 0.14543375 0.046838433 0.047002465, 0.1467369 0.047269791 0.043002546, -0.13225023 0.067067891 0.058003634, -0.12395926 0.070469916 0.069037825, -0.12459232 0.066823006 0.071102247, -0.12210488 0.06700635 0.074503824, -0.13053744 0.066199005 0.062003613, -0.13955773 0.054794103 0.054289907, -0.13941783 0.052541912 0.056446508, -0.13802686 0.05419293 0.058003023, -0.066605195 0.14656088 0.0020080954, -0.13839087 0.050579399 0.060002759, -0.13623945 0.053490907 0.062003031, -0.13539471 0.051480055 0.064940691, -0.13452974 0.052819341 0.06554769, -0.070244312 0.14485225 -0.0019919574, 0.11070745 0.1053063 -0.046994254, 0.1417114 0.036611408 0.062002108, -0.075251833 0.14208406 -0.0077790469, 0.12333679 0.098983049 -0.027994573, 0.12263407 0.098442435 -0.031994641, 0.14425224 0.050359458 0.047002852, 0.1455387 0.050839454 0.043002576, 0.14393538 0.065511256 0.028003544, -0.070244208 0.14485183 0.0020078868, 0.14176737 0.076067835 0.0056227148, -0.07383962 0.14305279 -0.0019921809, 0.11169474 0.10626 -0.042994171, 0.13941067 0.079894364 0.009398818, 0.10811538 0.10796595 -0.046994001, 0.12084925 0.10200521 -0.027994424, 0.12016754 0.10143873 -0.031994373, 0.14311631 0.065170139 0.032003611, -0.07383965 0.14305258 0.0020078421, -0.037980273 0.14736125 0.048671305, -0.036924958 0.14898422 0.045008332, 0.14226988 0.069053322 0.028003812, 0.085089669 0.11027539 -0.074494109, 0.083496973 0.11148611 -0.07449387, -0.10273872 0.1056222 -0.059994221, 0.10906634 0.10895613 -0.042994067, 0.14069793 0.074496776 0.022249848, -0.01978837 0.13786685 0.074507639, -0.017806113 0.1381368 0.074507698, -0.020167336 0.14072239 0.069782078, -0.033636764 0.14441705 0.058008164, 0.14146444 0.068682134 0.03200382, 0.14051728 0.072553158 0.028003931, 0.11371602 0.10804099 -0.033639282, -0.021766514 0.13756832 0.074507833, 0.13478851 0.035096377 0.074501887, 0.13527887 0.033156842 0.074501708, -0.025434524 0.13907206 0.071106195, -0.033241555 0.14253709 0.0620078, -0.037079871 0.14357159 0.058007956, -0.023740128 0.13724163 0.074507713, 0.13972652 0.072152138 0.032003999, -0.046841264 0.14543095 0.047008097, -0.047272354 0.14673445 0.043008119, 0.09194006 0.11634609 -0.057993442, 0.090717018 0.11486527 -0.061993673, 0.11334679 0.10966784 -0.029994041, -0.1053039 0.11071014 -0.046993807, -0.03661482 0.14170811 0.062007949, -0.098981619 0.12333837 -0.027993202, -0.098440617 0.12263584 -0.031993285, -0.050362185 0.14424941 0.047008052, -0.050842032 0.14553633 0.043008104, 0.089132324 0.1185109 -0.057993397, 0.087965593 0.11698574 -0.06199348, -0.065512672 0.14393374 0.02800785, -0.076068342 0.14176711 0.0056264549, -0.10625774 0.11169702 -0.042993754, -0.079895169 0.13940996 0.0094020963, -0.10796355 0.10811791 -0.046994105, 0.12558949 0.10071576 -0.0019944906, -0.10200377 0.12085071 -0.027993426, -0.10143696 0.12016922 -0.03199333, -0.065172076 0.14311454 0.032008007, -0.069054887 0.14226827 0.028007805, 0.12558939 0.10071564 0.0020054281, -0.11027129 0.085093737 -0.074495375, -0.11148193 0.08350113 -0.07449545, -0.10895377 0.10906872 -0.042994007, 0.12303515 0.10382068 -0.0019942224, -0.074498162 0.1406967 0.022253484, 0.13482863 0.061721027 0.05800344, -0.068683878 0.14146268 0.032007918, 0.072208107 0.11910897 -0.074493334, -0.072554722 0.14051566 0.028007865, 0.12303519 0.10382038 0.0020056069, -0.10803933 0.11371797 -0.033638954, -0.035100594 0.13478434 0.074507475, -0.033161029 0.13527456 0.074507654, 0.1330546 0.060982555 0.062003374, 0.13001098 0.04996714 0.074502811, 0.13071527 0.048094779 0.074502647, 0.13331449 0.064926654 0.058003694, -0.072153956 0.13972467 0.032007873, -0.1163429 0.091943294 -0.057994887, -0.11486189 0.090720326 -0.061994895, -0.10966624 0.11334836 -0.029993728, 0.11676008 0.11078337 -0.0036106706, 0.13156973 0.064122915 0.062003419, 0.13172401 0.068095356 0.058003694, 0.13136415 0.078026175 0.047004372, 0.13253886 0.078736693 0.043004304, 0.10797319 0.11687103 -0.022795051, -0.11850764 0.089135557 -0.057995304, -0.11698227 0.087968975 -0.061995178, 0.084499672 0.12730074 -0.046992972, 0.1051705 0.12023765 -0.018625289, 0.1157943 0.11186004 6.0200691e-06, 0.13001107 0.067227006 0.062003836, -0.10071568 0.12558964 -0.001993075, 0.098219052 0.12394637 -0.027993232, 0.097654253 0.12326291 -0.03199321, 0.12942882 0.08119604 0.047004521, 0.13057637 0.081950128 0.043004453, 0.085249722 0.1284503 -0.042992994, -0.10071573 0.12558937 0.0020069331, 0.081380561 0.12931713 -0.046992853, 0.095121369 0.12633923 -0.027993083, 0.094582856 0.12563527 -0.031993076, 0.12741698 0.084317744 0.047004759, 0.12853596 0.085114628 0.043004662, -0.061724246 0.13482547 0.058007509, 0.12333676 0.09897995 0.028005391, 0.058418602 0.12644485 -0.074493095, -0.11910483 0.07221216 -0.07449615, 0.082087472 0.13049391 -0.04299286, -0.10382047 0.12303519 0.0020066202, -0.10382047 0.12303525 -0.001993224, 0.12263408 0.098438799 0.032005429, -0.060986087 0.13305113 0.062007412, -0.049971417 0.13000688 0.074507207, -0.048098862 0.13071108 0.074507341, -0.064930081 0.13331136 0.058007404, 0.12084933 0.10200199 0.02800566, 0.12450804 0.062427759 0.074503452, -0.11078328 0.11676028 -0.0036101043, 0.12016746 0.10143512 0.032005668, -0.064126298 0.13156638 0.062007204, -0.06809859 0.13172075 0.058007374, 0.063746423 0.13388756 -0.057992563, 0.062883317 0.13217184 -0.061992615, -0.078028947 0.13136142 0.047007307, -0.078739136 0.13253635 0.043007299, -0.11686973 0.10797432 -0.022795424, 0.052261963 0.13221514 -0.06976372, 0.052917734 0.12884405 -0.074492782, -0.12729837 0.084502071 -0.046995223, -0.12023674 0.10517156 -0.018626049, -0.11186017 0.11579418 6.3031912e-06, 0.060527146 0.13537353 -0.057992533, 0.059729129 0.13362694 -0.061992571, -0.067230523 0.13000754 0.062007368, 0.11489691 0.10912576 0.026416063, -0.12394492 0.098220468 -0.027994618, -0.12326126 0.097656041 -0.031994715, -0.081198812 0.12942618 0.047007263, -0.081952676 0.13057393 0.043007135, 0.10002941 0.12613708 -0.0019930601, 0.10911322 0.11812925 0.0072378814, -0.12844807 0.085252076 -0.042995378, -0.12931454 0.08138299 -0.046995506, 0.10570319 0.12081769 0.011401176, 0.11334676 0.1096645 0.030006111, -0.12633777 0.095122963 -0.027994737, -0.1256336 0.094584584 -0.03199482, 0.10002936 0.12613666 0.0020070076, -0.0843205 0.12741411 0.047006965, -0.085117146 0.12853351 0.043007061, 0.096848264 0.12859547 -0.0019929409, -0.098981753 0.12333521 0.028006807, -0.12644088 0.058422744 -0.074496806, -0.1304917 0.082089543 -0.042995512, 0.072113678 0.13871658 -0.035637647, 0.076076642 0.13815561 -0.029992327, 0.041991308 0.13280743 -0.074492678, 0.043894455 0.13219064 -0.074492589, 0.09684822 0.12859532 0.0020071268, -0.098440692 0.12263215 0.03200686, -0.10200357 0.12084764 0.028006732, 0.11563163 0.077644587 0.074504346, 0.11673497 0.075975776 0.074504137, 0.11552365 0.092964113 0.058005109, -0.062432036 0.12450385 0.074506894, 0.071258754 0.14018691 -0.031992272, 0.061069667 0.13847631 -0.050834224, -0.10143687 0.12016556 0.032006428, 0.057511851 0.14155623 -0.046992064, 0.063166738 0.14118251 -0.041417181, 0.064022616 0.1395072 -0.044992328, 0.11400162 0.091792107 0.062005028, 0.071686596 0.14096379 -0.027992129, 0.11326802 0.09569934 0.058005378, -0.13388449 0.063749373 -0.057996482, -0.13216856 0.062886745 -0.061996475, 0.11335365 0.08093369 0.074504524, 0.1107076 0.10530108 0.047005773, 0.11169468 0.10625529 0.043005884, -0.13221127 0.052266002 -0.069768205, -0.12883985 0.052921951 -0.074497133, 0.077692017 0.13811049 -0.026400581, 0.058035359 0.14282492 -0.0429921, 0.054054424 0.14291215 -0.046991989, 0.11179112 0.094471693 0.062005177, -0.13537031 0.060530424 -0.057996765, -0.13362353 0.059732556 -0.061996698, -0.1091273 0.11489537 0.026416287, 0.06817615 0.14269459 -0.02799204, 0.067777574 0.1419028 -0.031992137, 0.10811546 0.10796067 0.047005862, 0.10906638 0.10895127 0.043005973, -0.12613676 0.10002947 -0.0019944608, -0.11812985 0.10911283 0.0072375089, 0.054529965 0.14419967 -0.04299207, 0.050564989 0.14418375 -0.046991825, 0.064623743 0.14433819 -0.02799198, -0.1208185 0.10570252 0.011400193, 0.064255193 0.14353204 -0.031991959, -0.10966618 0.11334506 0.03000617, 0.10783267 0.10280952 0.056449413, -0.12613684 0.10002923 0.0020054877, -0.12859546 0.096848339 -0.0019947737, 0.098218948 0.12394336 0.028006762, 0.028818235 0.13627416 -0.074492484, 0.050992116 0.14548847 -0.042992041, -0.13871457 0.0721156 -0.035641342, -0.13815399 0.076078147 -0.029995754, -0.12859535 0.096848071 0.002005294, 0.097654253 0.12325931 0.032006741, 0.10561895 0.10273528 0.06000568, 0.095121354 0.12633619 0.028006852, -0.077648729 0.1156275 0.074506581, -0.075979829 0.11673072 0.074506447, -0.092967317 0.11552042 0.058006421, 0.04742384 0.14669034 -0.042991906, 0.10621072 0.090102851 0.074505046, 0.10749392 0.088568121 0.074504897, -0.1401851 0.071260512 -0.031996161, -0.13847359 0.06107235 -0.050838396, 0.094582841 0.12563157 0.032006919, -0.14155369 0.057514578 -0.046996713, -0.14118025 0.063169062 -0.041421533, -0.13950475 0.064025074 -0.044996545, -0.091795549 0.11399817 0.062006235, -0.14096223 0.071688175 -0.027996168, 0.032355934 0.14471576 -0.057991892, 0.031896442 0.14285091 -0.061992079, -0.095702574 0.11326477 0.058006302, -0.080937818 0.11334941 0.074506402, -0.1053039 0.11070475 0.0470061, -0.10625783 0.11169225 0.043006048, 0.073058307 0.14345339 -0.0019920468, -0.13810924 0.077693522 -0.026403978, -0.14282259 0.058037609 -0.042996854, -0.14290962 0.054057062 -0.046997234, 0.02888687 0.14544806 -0.057991922, 0.028497532 0.14356771 -0.061992019, -0.094475076 0.11178759 0.062006086, -0.14269312 0.068177432 -0.027996302, -0.14190096 0.067779452 -0.03199628, 0.073058337 0.14345324 0.0020078719, -0.1079635 0.10811275 0.047006086, -0.10895395 0.10906401 0.043005973, 0.07890293 0.14028573 0.0036263168, -0.14419746 0.054532379 -0.042996958, 0.020064667 0.14346001 -0.064930037, 0.025401473 0.14609697 -0.057991922, -0.14418119 0.050567538 -0.046997264, -0.14433672 0.064625263 -0.027996525, -0.14353029 0.064257085 -0.031996459, 0.069453225 0.1452328 0.0020078719, 0.069453329 0.14523298 -0.0019919872, -0.10281271 0.10782954 0.056449667, -0.12394492 0.098217368 0.028005406, -0.14380696 0.041192591 -0.055078879, -0.14390185 0.044197738 -0.052840233, -0.14283408 0.042394698 -0.056439251, -0.14548604 0.050994396 -0.042997405, 0.011386991 0.13882172 -0.074492425, 0.0093919784 0.138971 -0.074492201, 0.013379559 0.13864389 -0.07449235, -0.14536762 0.047048151 -0.046997458, 0.065804914 0.1469219 0.0020080805, 0.065804899 0.14692211 -0.0019918978, 0.0073951185 0.13909152 -0.074492201, -0.12326126 0.097652406 0.032005429, 0.018519685 0.14617994 -0.059992, -0.10273871 0.10561553 0.060005888, -0.12633771 0.095119834 0.028005138, 0.095454216 0.10142812 0.074505597, 0.096901029 0.10004678 0.074505612, 0.097450078 0.10350499 0.069779813, -0.1457784 0.041756898 -0.050076455, -0.14668804 0.047426164 -0.04299733, 0.091940105 0.11633956 0.058006346, -0.090107188 0.10620657 0.074505821, -0.088572383 0.10748973 0.074506074, 0.021213844 0.148424 -0.054281279, -0.12563364 0.094580978 0.03200528, 0.09398742 0.10278857 0.074505657, 0.092875972 0.10659403 0.071104482, 0.092501298 0.104128 0.074505836, -0.13278331 0.0420506 0.074502468, -0.13218658 0.043890238 0.074502483, -0.13554043 0.042884737 0.069776461, -0.13925248 0.039881438 0.06494154, -0.13869469 0.041777492 0.06494309, -0.13335446 0.040203094 0.07450223, -0.13666783 0.039140731 0.069777399, -0.1338999 0.038347721 0.07450217, -0.1361118 0.041034669 0.069776356, 0.13554031 -0.042884797 -0.069776729, 0.13278329 -0.042050749 -0.074502602, 0.13335435 -0.040203094 -0.074502379, 0.1321865 -0.043890208 -0.074502394, 0.13869457 -0.041777432 -0.064943328, 0.13611102 -0.041034549 -0.069777682, 0.13278316 -0.042058975 0.074497595, 0.13218643 -0.043898553 0.074497551, 0.13554035 -0.042892635 0.069771841, 0.13869458 -0.041784674 0.064938366, 0.1333542 -0.04021138 0.074497804, 0.13611168 -0.041042507 0.069771782, -0.042691678 -0.075808853 0.064206645, -0.037533104 -0.078491002 0.064206496, -0.037533119 -0.078483939 -0.064215243, 0.07433641 -0.04520458 0.064208314, 0.077189416 -0.040138453 0.064208627, 0.07718946 -0.04013136 -0.064212888, 0.079697773 -0.034885854 -0.064212665, -0.032206848 -0.080815613 -0.064215228, -0.032206878 -0.080822706 0.064206362, -0.026736885 -0.082786322 -0.064215466, 0.079697728 -0.034893155 0.064208761, -0.083636895 0.023959041 -0.064209595, -0.083636925 0.023951828 0.064212143, -0.085050255 0.01831907 -0.064209625, 0.081850186 -0.029484838 -0.064212352, -0.026736885 -0.082793564 0.064206257, -0.02114743 -0.084387213 -0.064215526, 0.081850141 -0.029491901 0.064209163, -0.085050225 0.018312007 0.064211875, 0.083637029 -0.023952067 -0.064212084, -0.086083665 0.012597501 -0.064210013, 0.083636835 -0.0239591 0.064209476, -0.02114746 -0.084394306 0.064206108, -0.015463397 -0.085611284 -0.0642156, -0.0860838 0.012590379 0.064211369, -0.086732596 0.0068196952 -0.064210355, -0.015463501 -0.085618436 0.064205945, -0.0097105801 -0.086452931 -0.0642156, -0.086732656 0.0068125725 0.06421122, -0.086994275 0.0010112226 -0.064210877, -0.009710595 -0.086460173 0.06420587, -0.0039141923 -0.08690846 -0.064215586, -0.086994112 0.0010040998 0.064210773, -0.086867258 -0.0048015118 -0.064211145, -0.0039141923 -0.086915612 0.064205974, 0.0018995255 -0.086975843 -0.064215764, -0.086867243 -0.0048086345 0.064210504, -0.086352438 -0.010592729 -0.064211443, 0.0018996447 -0.086983025 0.064205855, 0.0077049285 -0.086654723 -0.064215779, -0.086352244 -0.010599971 0.064210221, -0.085451677 -0.016336888 -0.064211726, 0.0077050328 -0.086661845 0.064205945, 0.013475835 -0.08594653 -0.064215615, -0.085451707 -0.01634407 0.064209983, -0.084169462 -0.022007912 -0.064212054, 0.013475865 -0.085953712 0.064206064, 0.019186631 -0.084854513 -0.06421572, -0.084169418 -0.022015095 0.064209476, -0.082511365 -0.027580768 -0.064212322, 0.01918672 -0.084861666 0.06420587, 0.024811655 -0.08338353 -0.064215437, -0.082511321 -0.027587861 0.064209267, -0.080484673 -0.033030212 -0.06421262, 0.02481167 -0.083390653 0.064206213, 0.0303258 -0.081539959 -0.064215466, -0.080484554 -0.033037454 0.06420888, -0.078098699 -0.038332164 -0.064213157, 0.030325785 -0.081547141 0.064206198, 0.035704657 -0.079332441 -0.064215109, -0.07809864 -0.038339317 0.064208791, -0.075363562 -0.043463081 -0.064213216, 0.035704792 -0.079339653 0.064206332, 0.040923923 -0.076770395 -0.064215124, -0.075363547 -0.043470263 0.064208329, -0.07229197 -0.048399806 -0.064213529, 0.040923893 -0.076777488 0.06420663, 0.045960486 -0.073865533 -0.064215168, -0.072291955 -0.048406839 0.06420809, -0.068897665 -0.053120226 -0.064213812, 0.045960531 -0.073872775 0.064206764, 0.0507918 -0.070630789 -0.064214766, -0.06889756 -0.053127438 0.064207867, -0.065195531 -0.057603508 -0.064213991, 0.050791711 -0.070637912 0.064206824, 0.055396259 -0.067080498 -0.064214498, -0.065195322 -0.057610661 0.064207509, -0.061202273 -0.061829299 -0.064214334, 0.055396274 -0.06708768 0.064207062, 0.059753284 -0.063230723 -0.064214364, -0.061202094 -0.0618366 0.06420733, -0.056935564 -0.065779179 -0.064214662, 0.059753269 -0.063237816 0.064207152, 0.063843369 -0.059098333 -0.064214125, -0.05693543 -0.065786302 0.064207181, -0.0524147 -0.06943506 -0.064214617, 0.063843265 -0.059105545 0.06420736, 0.067648351 -0.054702103 -0.064213797, -0.052414551 -0.069442332 0.064206913, -0.047659546 -0.072780937 -0.064215139, 0.067648441 -0.054709226 0.064207599, 0.071151197 -0.050061524 -0.064213544, -0.047659487 -0.072788179 0.06420666, -0.042691752 -0.07580179 -0.064215139, 0.071151227 -0.050068676 0.064208031, 0.074336335 -0.045197368 -0.064213485, -0.074571967 0.060308129 -0.068649292, -0.071608767 0.063798428 -0.068649158, -0.068229824 0.060788125 -0.066575751, 0.056862995 0.071534336 -0.066574991, 0.06078434 0.06823346 -0.066575408, 0.05693537 0.065786093 -0.064207137, 0.081241891 0.081497431 -0.073838279, 0.086231142 0.076198399 -0.073838502, 0.082551703 0.072946995 -0.073019758, -0.078636318 0.070059359 -0.071878433, -0.073791564 0.068315119 -0.070419371, -0.075082749 0.066893458 -0.070419416, -0.077284217 0.071548343 -0.071878344, 0.07777521 0.078019887 -0.073019534, -0.080839738 0.07483986 -0.073019519, -0.074584559 0.074358344 -0.07187815, -0.078016013 0.077779263 -0.073019579, 0.070055455 0.078640193 -0.071877763, 0.07435447 0.074588418 -0.071878105, 0.070994303 0.071217924 -0.070419371, -0.085001379 0.084743291 -0.074331, -0.088524863 0.088255882 -0.074495152, -0.082435444 0.087241679 -0.074330673, 0.066889599 0.075086504 -0.070419043, -0.079033032 0.083641171 -0.07383813, -0.081493288 0.081245929 -0.073838085, 0.05967918 0.075076759 -0.068648517, -0.078189522 0.063233882 -0.070419818, 0.063794717 0.071612358 -0.06864877, -0.082254231 0.073282391 -0.073019594, 0.055052474 0.072937042 -0.066574991, 0.052414581 0.069442093 -0.064206794, -0.084442958 0.078175575 -0.073838308, 0.084739089 0.085005552 -0.074330822, 0.08825165 0.08852905 -0.074495226, 0.093076497 0.083441466 -0.074495479, 0.089943364 0.079478353 -0.07433106, -0.074606374 0.052766591 -0.066576049, -0.071053013 0.057462543 -0.066575855, -0.067648366 0.054709047 -0.064207599, 0.073278561 0.082258046 -0.073019117, -0.071151242 0.050068408 -0.064208031, 0.062574446 0.07871899 -0.07041876, -0.081890151 0.066226631 -0.071878508, -0.085920393 0.076548725 -0.073838487, 0.057778895 0.076548994 -0.068648458, -0.088078022 0.081540763 -0.07433109, -0.093333885 0.083153307 -0.074495435, 0.052763 0.074610084 -0.066574946, 0.047659546 0.072787941 -0.064206764, -0.078301162 0.055379629 -0.068649694, 0.076544642 0.085924596 -0.073838025, -0.085657731 0.069273233 -0.073019862, 0.065536052 0.082444578 -0.071877554, -0.089619011 0.079843819 -0.074331179, 0.060581893 0.080262512 -0.070418745, -0.082099825 0.058066249 -0.070420086, 0.055375978 0.078304887 -0.068648353, -0.077447608 0.048500478 -0.066576391, -0.07433632 0.045204282 -0.064208239, 0.079839706 0.089623123 -0.074330553, 0.08314921 0.093338072 -0.07449472, -0.089475811 0.072360963 -0.073838696, 0.050058141 0.076451182 -0.066574812, -0.085985526 0.06081441 -0.071878761, 0.068551183 0.08623755 -0.073018923, 0.063449189 0.084061265 -0.071877524, -0.081283063 0.050902218 -0.068649903, -0.093327433 0.075475663 -0.074331373, -0.09784919 0.077789187 -0.074495673, 0.058062375 0.082103699 -0.070418626, -0.089941517 0.063612163 -0.073020205, 0.048496634 0.077451259 -0.066574678, 0.042691633 0.075808734 -0.064206496, 0.052537233 0.080237359 -0.068648309, -0.085226119 0.053371519 -0.070420414, 0.071606725 0.090081096 -0.073837757, -0.080044925 0.044081718 -0.066576481, -0.07718946 0.040138334 -0.064208522, 0.066368431 0.087928414 -0.073018774, 0.060810432 0.085989505 -0.071877435, -0.089259937 0.055897444 -0.071879178, 0.050898388 0.081286639 -0.068648204, -0.081074163 0.042158306 -0.066576838, 0.055085853 0.084129751 -0.070418641, -0.084009111 0.046264619 -0.068650097, 0.07468912 0.093958855 -0.074330166, 0.077785179 0.097853333 -0.074494764, 0.069326654 0.091847658 -0.073837668, -0.093366653 0.058469087 -0.073020622, 0.063608184 0.089945555 -0.073018745, -0.085089266 0.044246018 -0.06865032, -0.088084325 0.048508942 -0.070420548, 0.044840187 0.079624087 -0.066574559, 0.053367719 0.085230023 -0.070418358, -0.082390413 0.039524168 -0.066576943, -0.079697639 0.034892887 -0.064208731, 0.057693169 0.088111401 -0.071877465, -0.097528294 0.061075151 -0.073839337, -0.093950555 0.066447556 -0.073839098, 0.072310805 0.095801234 -0.074330226, 0.072176278 0.10206088 -0.074494407, -0.089217246 0.04639253 -0.070420578, 0.066443369 0.093954504 -0.073837236, -0.092253551 0.050804645 -0.071879461, 0.047060922 0.083567202 -0.068648145, -0.086470768 0.041481435 -0.068650618, 0.05589357 0.089263827 -0.07187748, -0.083708867 0.036649078 -0.066576913, 0.060347497 0.092164993 -0.073018759, -0.10172644 0.063704044 -0.074332014, -0.10594304 0.066344529 -0.074496478, -0.10205683 0.07218042 -0.074495912, -0.097994909 0.069307715 -0.074331596, 0.069303587 0.097998708 -0.074330077, -0.093439892 0.048588216 -0.071879625, 0.049343899 0.087621301 -0.070418313, 0.058465019 0.093370587 -0.073018581, -0.096497893 0.053141952 -0.073020816, -0.090665519 0.043493629 -0.070420861, 0.063037306 0.096272975 -0.073837414, -0.084476784 0.034842223 -0.066577166, -0.081850082 0.029491812 -0.064208984, -0.08785437 0.03846392 -0.068650573, 0.051679373 0.091768205 -0.071877003, 0.061070934 0.097532243 -0.073837206, -0.097738773 0.050823361 -0.073021218, 0.065750822 0.10041714 -0.074330106, 0.066340357 0.10594726 -0.074494168, -0.10079908 0.055510521 -0.073839754, -0.0949568 0.045552164 -0.071879774, 0.054057062 0.095990032 -0.073018491, -0.088660434 0.036567658 -0.068650767, 0.063699871 0.10173056 -0.074330091, -0.092116535 0.040330082 -0.070421234, 0.034838527 0.084480435 -0.066574335, 0.03753309 0.078490913 -0.064206541, 0.032206863 0.080822617 -0.064206302, -0.10209522 0.053088784 -0.073839664, 0.039520383 0.082394093 -0.066574425, -0.10513818 0.057900012 -0.074332356, -0.10949625 0.060299814 -0.074496701, 0.056466475 0.10026845 -0.073837176, -0.099325448 0.047647655 -0.073021159, -0.085969523 0.030976057 -0.066577405, 0.036563873 0.088664114 -0.068647787, 0.041477636 0.086474389 -0.068647861, -0.09296158 0.038341671 -0.070421189, 0.058897227 0.10458457 -0.074329808, 0.060295701 0.10950047 -0.074494109, -0.096476153 0.042238623 -0.071879923, -0.10649012 0.055373877 -0.074332491, -0.11270483 0.054065406 -0.074497074, 0.038337633 0.092965364 -0.07041797, 0.043489769 0.090669572 -0.070418313, -0.10375278 0.049771458 -0.073840111, 0.030047029 0.086300939 -0.06657432, 0.026736796 0.082793295 -0.064206094, -0.090227112 0.032510042 -0.068650782, -0.097361326 0.040156156 -0.071879953, 0.040152177 0.09736523 -0.071876943, 0.045548052 0.094960809 -0.071877077, -0.10091478 0.044181675 -0.073021397, 0.028082415 0.086960077 -0.066574275, -0.10821891 0.051913738 -0.074332684, 0.031535119 0.090574741 -0.068647712, -0.094604194 0.034087211 -0.070421338, -0.10184075 0.042003572 -0.073021427, 0.041999653 0.10184452 -0.073018059, 0.047643706 0.099329442 -0.073018327, -0.10541286 0.046150982 -0.073840097, 0.0294732 0.091266543 -0.068647772, 0.033064961 0.094968796 -0.070418045, -0.09908174 0.035700232 -0.071880192, -0.10638005 0.043875754 -0.07384038, 0.025161028 0.087849855 -0.066574037, 0.021147281 0.084394217 -0.064206019, -0.1099506 0.048137426 -0.074332952, -0.11555885 0.047661126 -0.074497327, 0.043871522 0.10638413 -0.073836878, 0.049767345 0.1037567 -0.073836833, -0.10364026 0.037342608 -0.073021814, 0.030902982 0.095694125 -0.070417777, -0.11095932 0.045764148 -0.074333027, 0.034629941 0.099463463 -0.071876794, -0.10825966 0.039006978 -0.073840603, -0.11291988 0.040686041 -0.074333444, -0.11804913 0.041106641 -0.0744977, 0.026407272 0.092200369 -0.068647698, 0.022211701 0.088641614 -0.066574037, 0.04576011 0.1109634 -0.074329302, 0.051909626 0.10822305 -0.074329525, 0.047656938 0.11556292 -0.074493676, 0.054061383 0.11270902 -0.074493647, 0.11751592 0.0025706291 -0.074129909, 0.11506358 -0.0013289452 -0.073842868, 0.11258265 0.0024629235 -0.073473677, 0.12499991 0.00019717216 -0.074500039, 0.12001669 -0.001386404 -0.074335709, 0.11489566 0.0063594878 -0.073842436, 0.032365546 0.10022318 -0.071876705, 0.036223173 0.10403931 -0.073018119, 0.02768822 0.09667334 -0.070417866, 0.017015502 0.11631003 -0.074123502, 0.020452902 0.11324304 -0.073836446, 0.01630123 0.11142752 -0.073467448, 0.021333277 0.11811778 -0.074329123, 0.012843698 0.11435637 -0.073836431, 0.020195901 0.089122593 -0.066574112, 0.015463516 0.085618198 -0.064206034, 0.023311675 0.093031466 -0.068647653, -0.022077203 0.11545622 -0.074123755, -0.025377348 0.11224222 -0.073836461, -0.026469901 0.1170738 -0.074328989, -0.021128684 0.12320557 -0.074493259, -0.018591374 0.11858034 -0.074328929, -0.017824039 0.11368659 -0.073836431, -0.02115044 0.1106095 -0.073467597, 0.033854768 0.10483399 -0.073017821, -0.093732551 0.070932359 -0.07412605, 0.037837729 0.10867661 -0.073836833, 0.028998718 0.10124871 -0.071876571, -0.11185551 0.036127687 -0.074128136, -0.10715993 0.034611195 -0.07347174, 0.021196127 0.093536049 -0.068647534, -0.11062311 0.031689048 -0.073841095, 0.1089415 0.00056242943 -0.072768539, 0.11015375 -0.0012721121 -0.073023915, 0.1053088 -0.0012161136 -0.071882337, 0.024442598 0.097544551 -0.070417821, 0.10886197 0.0042023957 -0.072768301, 0.109993 0.0060881674 -0.073023483, 0.035363674 0.10950664 -0.073836744, 0.10515514 0.0058204234 -0.071881816, 0.12117168 0.0048221648 -0.074407056, 0.039466441 0.11335471 -0.074329302, 0.11984156 0.0066330731 -0.074335113, 0.12479237 0.0072057545 -0.074499846, 0.041102573 0.11805317 -0.074493393, 0.054226309 0.10009801 -0.073662922, 0.030332863 0.10590675 -0.073017806, 0.054287598 0.1042608 -0.074124232, 0.050912052 0.10182375 -0.073662817, 0.016241625 0.089927286 -0.066573963, 0.057255074 0.10690439 -0.074401543, 0.089118794 -0.020192266 -0.066580325, 0.0850503 -0.018312216 -0.064211801, 0.022224531 0.098073661 -0.070417762, 0.087846234 -0.025157511 -0.066580474, 0.05423443 0.10846791 -0.074401349, 0.093532324 -0.021192402 -0.068654016, 0.092196718 -0.026403457 -0.068654358, 0.025599435 0.10216114 -0.071876422, 0.017569408 0.10752082 -0.072762519, 0.019580111 0.10841107 -0.073017821, 0.018719032 0.10364282 -0.071876526, 0.036886051 0.11422047 -0.074329212, 0.013967037 0.10804781 -0.072762474, 0.098069936 -0.022220612 -0.070424557, 0.096669421 -0.027684391 -0.070424795, 0.034418881 0.12017217 -0.074493393, 0.011754826 0.1046617 -0.071876243, 0.012295693 0.10947677 -0.073017776, 0.03168489 0.11062714 -0.073836654, 0.018842459 0.11979878 -0.074400917, 0.02074787 0.12327036 -0.07449317, 0.017046079 0.094380677 -0.068647504, 0.090111002 -0.01516363 -0.066579953, 0.086083621 -0.012590587 -0.064211458, 0.015475333 0.12028003 -0.074400708, 0.013396516 0.11927903 -0.074328959, 0.013803527 0.12423971 -0.074493095, 0.023276314 0.10271531 -0.071876541, -0.018670857 0.10733506 -0.072762713, -0.017063498 0.10883561 -0.073017582, -0.016312867 0.10404867 -0.071876571, 0.10271144 -0.023272365 -0.071883544, 0.10124467 -0.028994858 -0.071883947, 0.026777133 0.1068612 -0.073017776, -0.022246853 0.10665125 -0.072762728, -0.023225948 0.10272685 -0.071876541, -0.024294481 0.10745278 -0.073017746, 0.033048838 0.11538929 -0.074329212, -0.089659274 0.070150316 -0.073664442, 0.090416074 -0.013224185 -0.066579878, -0.09187305 0.06722495 -0.07366465, 0.017873019 0.098959297 -0.070417807, 0.094573736 -0.015914798 -0.068653628, -0.095821351 0.074328154 -0.074403256, 0.10743697 -0.024343222 -0.073025122, 0.10590282 -0.030329019 -0.073025584, 0.024347126 0.10744098 -0.073017806, -0.097868234 0.071611524 -0.074403539, 0.027970776 0.11162418 -0.073836505, -0.10309686 0.035212129 -0.072766766, 0.094893888 -0.013879299 -0.068653613, -0.10421568 0.031747282 -0.072766796, 0.099161699 -0.016686708 -0.070424274, -0.10124472 0.029002786 -0.071880579, -0.10590273 0.030336797 -0.073022261, -0.11496888 0.038578123 -0.074405283, 0.090819716 -0.010087192 -0.06657967, 0.086732537 -0.0068126917 -0.06421122, -0.11600551 0.035338521 -0.074405611, -0.12016799 0.034422964 -0.074498028, 0.025432363 0.11222976 -0.073836461, -0.11538522 0.0330531 -0.074333817, 0.11222559 -0.025428176 -0.073844105, 0.11062311 -0.031680852 -0.073844522, 0.10471527 -0.00033420324 -0.071717113, 0.10054982 -0.0011610389 -0.070423231, 0.029174939 0.116429 -0.074329153, 0.099497348 -0.014552504 -0.07042411, 0.027626798 0.12191302 -0.074493319, 0.10611184 0.0011390448 -0.072094709, 0.10385494 -0.017476737 -0.071883187, 0.10470621 0.0014156103 -0.071716979, 0.10328235 0.0028352141 -0.071312442, 0.10460065 0.0049135983 -0.071716875, 0.026527107 0.11706075 -0.074329019, 0.095317394 -0.010586888 -0.068653524, 0.10040298 0.0055575669 -0.070422962, 0.052972689 0.095896691 -0.072893247, 0.091097653 -0.0071555972 -0.066579491, 0.1170567 -0.026523054 -0.074336991, 0.11538516 -0.033044755 -0.074337393, 0.12016803 -0.034414709 -0.074501947, 0.12190889 -0.02762273 -0.074501604, 0.10420655 -0.015241474 -0.071883067, 0.052327722 0.097868115 -0.073177442, 0.051391974 0.096753031 -0.072893277, 0.0049825907 0.091246367 -0.066574097, 0.0097105652 0.086459875 -0.064205989, 0.0039141476 0.086915314 -0.064205989, 0.10863307 -0.018280834 -0.07302478, 0.0101991 0.090811312 -0.066574022, 0.049415648 0.096185416 -0.072581798, 0.048188895 0.098387748 -0.072893128, 0.099941537 -0.01110056 -0.070423841, 0.017750636 0.10320425 -0.071711391, 0.091242597 -0.0049790442 -0.066579491, 0.086994126 -0.0010042489 -0.064210713, 0.095609292 -0.0075100064 -0.068653166, 0.0052294582 0.095764995 -0.068647534, 0.016530216 0.10482651 -0.072088793, 0.016023666 0.10348651 -0.071711361, 0.010704353 0.095308483 -0.06864737, 0.10900082 -0.015942842 -0.07302472, 0.014386982 0.10231853 -0.07130684, 0.012556836 0.10396418 -0.071711406, 0.011223555 0.099932075 -0.070417851, 0.11347501 -0.019095689 -0.073843807, 0.0054830611 0.10041079 -0.070417628, -0.017083794 0.10331672 -0.071711451, -0.015575796 0.099346757 -0.070417777, 0.10467166 -0.011625946 -0.071882755, -0.00014132261 0.091382176 -0.066574037, -0.0018996 0.086982787 -0.0642059, 0.095761269 -0.0052255988 -0.068653107, -0.018768802 0.10444894 -0.072088912, -0.018807724 0.10301676 -0.071711376, 0.10024741 -0.00787431 -0.070423648, -0.019970849 0.10137665 -0.071306899, 0.0057426989 0.10516307 -0.071876481, -0.022239432 0.10233101 -0.071711451, -0.022176281 0.098084629 -0.070417747, 0.11385925 -0.016653448 -0.073843807, -0.098810405 0.034672618 -0.071715221, 0.11835988 -0.019917876 -0.074336737, 0.12326601 -0.020743638 -0.074501291, -0.0019952059 0.09136045 -0.066574022, -0.00014813244 0.095907569 -0.068647549, 0.10948738 -0.012160987 -0.073024452, -0.098142579 0.032303631 -0.071310893, -0.10133953 0.031489134 -0.07209301, 0.091372475 -0.0010549724 -0.066579252, -0.099913627 0.031351477 -0.07171534, -0.10042338 0.0296776 -0.071715459, 0.006006822 0.11000127 -0.073017567, -0.096669495 0.027692169 -0.070421681, 0.10040693 -0.0054790974 -0.070423573, 0.0995747 0.00079157948 -0.070079952, 0.095897615 -0.0011072755 -0.068652719, 0.10499206 -0.0082471967 -0.071882844, -0.0020939857 0.09588483 -0.068647429, 0.11876062 -0.017370552 -0.074336454, 0.099492759 0.0041184723 -0.070079654, -0.0001552999 0.10056031 -0.070417613, 0.095757633 0.0053005517 -0.068652391, 0.12423545 -0.013799399 -0.074501038, 0.049439311 0.091860831 -0.071599185, 0.11436751 -0.012703121 -0.073843449, -0.0052646548 0.091230452 -0.066574022, -0.0077048838 0.086661667 -0.06420584, 0.046398103 0.093433857 -0.071598992, 0.0062745363 0.11490422 -0.073836371, 0.015785396 0.098322362 -0.070074245, -0.0021956563 0.10053656 -0.070417717, 0.10515927 -0.0057387352 -0.07188262, 0.10982245 -0.0086266696 -0.073024333, 0.012491181 0.098795176 -0.070074201, -0.00016281009 0.10531965 -0.071876436, 0.11929074 -0.013250083 -0.074336261, -0.017339081 0.098060459 -0.070074424, -0.014855057 0.094750285 -0.068647534, -0.0055253357 0.095748425 -0.0686474, -0.020605832 0.097426265 -0.070074439, -0.021150216 0.09354642 -0.068647534, -0.09414418 0.032447517 -0.070077866, -0.0080927461 0.091023117 -0.066573948, 0.10999723 -0.0060027838 -0.073024094, 0.0065445602 0.11985034 -0.074328735, -0.095175922 0.029283702 -0.070078135, 0.11471756 -0.0090113282 -0.073843211, 0.0068159103 0.12481824 -0.074493065, -0.092196867 0.026410848 -0.06865117, -0.0022995919 0.10529464 -0.071876436, 0.095426261 -0.00017160177 -0.068450898, -0.00017027557 0.110165 -0.073017716, 0.094050929 0.0016210973 -0.067853555, -0.0057934076 0.10039338 -0.070417643, 0.095378757 0.0030171871 -0.068450645, 0.11489999 -0.0062703788 -0.073843122, 0.09123908 0.00505054 -0.066578716, -0.0084934235 0.095530897 -0.068647638, 0.11965579 -0.0093993545 -0.074336022, 0.0482665 0.087660283 -0.070248395, 0.1248142 -0.0068119168 -0.074500397, -0.010371402 0.090791792 -0.066574097, -0.013476029 0.085953623 -0.064206094, -0.0024053752 0.1101388 -0.073017612, 0.045968473 0.087310255 -0.069742307, 0.045363665 0.089197248 -0.070247963, -0.00017791986 0.11507532 -0.073836312, 0.016045108 0.094071418 -0.068445668, 0.11984627 -0.0065406263 -0.074335814, -0.0060676187 0.10514486 -0.071876436, 0.014048576 0.093013614 -0.06784831, 0.012892738 0.09455505 -0.068445593, -0.0089055747 0.10016525 -0.070417628, -0.015699342 0.094129771 -0.068445548, -0.014154196 0.09027946 -0.066574007, 0.090788081 0.010375112 -0.066578507, 0.086867288 0.0048084855 -0.064210385, 0.086352304 0.010599762 -0.064210281, -0.010885164 0.095288008 -0.06864731, -0.01723817 0.092475444 -0.067848325, -0.0025125146 0.11504799 -0.073836446, -0.018835813 0.093552709 -0.068445593, -0.020152256 0.089132369 -0.066574052, -0.00018551946 0.12002882 -0.07432884, -0.00019317865 0.12500408 -0.074493095, -0.090518177 0.030213922 -0.068449169, -0.0063467324 0.10998219 -0.073017761, -0.089645877 0.028495848 -0.06785199, 0.095284328 0.010888726 -0.068652302, -0.091477051 0.027172387 -0.068449184, -0.087846339 0.025164783 -0.066577643, 0.090484098 0.00025749207 -0.066125527, -0.0093271285 0.10490602 -0.071876407, 0.090425 0.0032808781 -0.066125244, -0.011413038 0.099910587 -0.070417672, 0.099906728 0.01141715 -0.070422649, -0.0026207715 0.12000042 -0.074328899, 0.045434102 0.083414108 -0.06825465, -0.0072016269 0.12479654 -0.074493095, 0.042672187 0.084860265 -0.06825459, 0.090063676 0.015449435 -0.066578209, 0.085451752 0.016343862 -0.064209878, 0.014799789 0.089269459 -0.066120476, -0.0066297203 0.11488441 -0.073836386, 0.011808753 0.089714199 -0.066120505, -0.0097562075 0.10973221 -0.073017582, -0.015300497 0.089185119 -0.066120416, 0.10463531 0.011957347 -0.071881503, -0.011953354 0.10463929 -0.071876451, -0.018271938 0.088623941 -0.066120625, -0.019186795 0.084861457 -0.064205989, 0.089752287 0.017166436 -0.066578239, -0.085696369 0.02904734 -0.066123977, 0.094524026 0.016214222 -0.068651915, -0.086619005 0.026167631 -0.066124067, -0.0069150329 0.11982954 -0.074328706, 0.042748049 0.080259442 -0.06634903, -0.010190934 0.11462328 -0.073836371, 0.10944918 0.012507349 -0.073023185, -0.012503222 0.10945326 -0.073017702, 0.094197184 0.018016517 -0.068651646, 0.099109694 0.017000854 -0.070422396, 0.08905609 0.020474851 -0.066578105, 0.084169418 0.022014916 -0.064209476, -0.010629714 0.11955729 -0.074328929, -0.014187455 0.12419644 -0.074493095, 0.11432771 0.013064653 -0.073842034, -0.013060585 0.11433184 -0.073836371, 0.098766938 0.0188905 -0.070422158, 0.10380031 0.017805457 -0.071881264, -0.013622865 0.11925331 -0.074328944, 0.093466282 0.021488965 -0.068651646, 0.088405624 0.023122877 -0.066577777, 0.11924917 0.013626933 -0.074334979, 0.12419228 0.014191628 -0.074499384, 0.10344157 0.019784391 -0.071881071, -0.025432587 0.087771744 -0.066574007, -0.024811685 0.083390534 -0.064206153, 0.10857604 0.018624514 -0.073022693, 0.098000646 0.022531301 -0.070421994, 0.092783779 0.024267882 -0.068651527, -0.026692018 0.092118502 -0.068647638, 0.087768093 0.025436193 -0.066577673, 0.082511276 0.027587682 -0.064209357, 0.10820059 0.020694494 -0.073022619, -0.027986884 0.09658727 -0.070417881, 0.11341557 0.019454479 -0.073841736, 0.10263909 0.023597538 -0.071881056, -0.03031376 0.086207688 -0.066574231, -0.030325904 0.081546962 -0.064206094, 0.097284868 0.025445193 -0.070421815, 0.092114672 0.026695698 -0.068651184, -0.029311568 0.10115859 -0.071876675, 0.11302334 0.021616906 -0.073841676, -0.031852156 0.085651129 -0.066574514, 0.11829782 0.020291686 -0.074334413, 0.12320137 0.021132797 -0.074498951, -0.031814978 0.090476871 -0.068647623, 0.086664051 0.028976113 -0.066577539, 0.10736118 0.024682999 -0.073022366, -0.02800341 0.12182698 -0.07449317, -0.030660018 0.1058124 -0.073017985, 0.1018893 0.026649475 -0.071880639, -0.033429608 0.089892685 -0.068647817, 0.096583396 0.027990729 -0.070421726, 0.11788881 0.022547245 -0.074334279, 0.12182286 0.028007507 -0.074498653, -0.033358321 0.094865978 -0.070418, 0.086204007 0.030317336 -0.066577479, 0.080484569 0.033037335 -0.06420894, -0.035099611 0.084372342 -0.066574395, -0.035704598 0.079339385 -0.064206332, 0.090955824 0.030411065 -0.068651095, -0.032026783 0.11052871 -0.07383661, -0.035051331 0.094253689 -0.070418015, 0.11214656 0.025783181 -0.073841304, -0.034937233 0.099356025 -0.07187666, 0.10657707 0.027875304 -0.073022351, 0.10115463 0.029315591 -0.071880788, 0.090473145 0.031818539 -0.068650886, -0.036837712 0.088550568 -0.068647817, -0.037501618 0.08333239 -0.066574499, -0.033405319 0.1152865 -0.074329019, -0.034789979 0.12006524 -0.074493393, 0.095368341 0.031886309 -0.070421591, -0.036710292 0.098714471 -0.0718766, 0.11697412 0.02689293 -0.07433401, -0.036544561 0.1039269 -0.073018104, 0.11132747 0.029117703 -0.073841125, -0.038624868 0.092846394 -0.070417956, 0.10580853 0.030664116 -0.073022082, 0.094862252 0.03336221 -0.070421487, -0.039358795 0.087459147 -0.068647936, -0.039774761 0.082271487 -0.066574454, -0.040924057 0.076777428 -0.064206481, -0.038399294 0.10325587 -0.073017851, 0.084535182 0.034700036 -0.066577077, 0.099882111 0.033395439 -0.071880445, -0.038173422 0.10855913 -0.07383661, 0.11611974 0.03037104 -0.074333996, 0.12006103 0.034794152 -0.074497983, -0.040452912 0.097240597 -0.071876749, 0.11052456 0.032030761 -0.073841065, -0.041268334 0.091702133 -0.070418119, 0.099352077 0.034941077 -0.071880385, 0.088721812 0.036418259 -0.068650737, -0.041744649 0.086345881 -0.068647906, -0.040110856 0.1078583 -0.073836759, 0.10447741 0.034931719 -0.073021933, -0.039816707 0.11323214 -0.074329287, 0.11528243 0.033409357 -0.074333608, -0.041467279 0.11792564 -0.074493408, 0.10392296 0.036548525 -0.073021799, -0.042983577 0.080641448 -0.066574544, -0.042314127 0.10171437 -0.073018357, 0.093025863 0.038185 -0.070421159, -0.043221489 0.096042097 -0.071876958, 0.1091343 0.036488533 -0.073840573, -0.043769792 0.090534717 -0.070418075, 0.082267895 0.039778382 -0.066576943, 0.078098521 0.038339108 -0.064208761, -0.041837513 0.11250103 -0.074329123, 0.10855499 0.03817755 -0.073840812, -0.048013821 0.11541504 -0.074493527, -0.044325218 0.079912066 -0.066574603, -0.045960501 0.073872507 -0.06420663, 0.097428814 0.039992124 -0.071879953, -0.045112327 0.08463499 -0.068648115, 0.11383207 0.038059145 -0.074333236, -0.044200107 0.10624796 -0.073836833, 0.11792152 0.041471303 -0.0744977, 0.086342186 0.041748315 -0.068650514, -0.04520981 0.10046059 -0.073018253, 0.11322798 0.03982082 -0.0743334, -0.045841485 0.094819456 -0.071876884, 0.10191113 0.04183203 -0.073021397, -0.046520218 0.083869457 -0.068647996, 0.090530798 0.043773741 -0.070420817, -0.047300816 0.088740766 -0.070418388, 0.079908267 0.044328809 -0.066576675, 0.075363576 0.043469965 -0.064208388, -0.046102837 0.11082143 -0.074329361, 0.10645373 0.043696463 -0.073840529, -0.047225013 0.10493845 -0.073836952, -0.047950417 0.099181741 -0.073018283, 0.079156429 0.045657754 -0.0665766, 0.094815597 0.0458453 -0.071879774, -0.048776999 0.087937921 -0.070418343, 0.083865643 0.046523899 -0.068650126, -0.048273683 0.077590406 -0.066574797, -0.04953967 0.092940778 -0.071877047, 0.11103623 0.045577228 -0.074332997, 0.11541089 0.048017949 -0.074497432, -0.049257934 0.10945544 -0.074329346, 0.083076522 0.047918826 -0.068650126, -0.054409429 0.11254138 -0.074493766, -0.05008775 0.10360244 -0.073837116, -0.051085547 0.092100054 -0.071877271, 0.099177763 0.0479545 -0.073021188, 0.087934121 0.048780948 -0.070420533, -0.050664306 0.08143276 -0.06864813, -0.051818743 0.097216517 -0.073018342, 0.077297226 0.048739463 -0.066576362, 0.072292045 0.04840675 -0.06420818, 0.087106764 0.050243497 -0.070420355, -0.052243888 0.10806212 -0.074329659, -0.053435907 0.09633708 -0.073018357, 0.10359843 0.050091773 -0.073840097, 0.09209612 0.051089495 -0.071879461, -0.053122208 0.085383296 -0.070418462, -0.054128468 0.10154966 -0.073837072, 0.081125349 0.051153094 -0.068650007, -0.052993253 0.074446619 -0.066574976, -0.05079174 0.070637643 -0.064206854, 0.075930268 0.050842911 -0.066576272, -0.055817619 0.10063103 -0.073837161, 0.091229558 0.052621365 -0.071879268, -0.055636391 0.089424431 -0.071877271, 0.10805801 0.052247941 -0.07433258, 0.11253709 0.054413617 -0.074497059, -0.056458548 0.10592097 -0.074329734, 0.096333101 0.053439885 -0.073020875, -0.060633883 0.10931355 -0.074494079, -0.05561772 0.078133404 -0.068648383, 0.08506088 0.053634733 -0.070420176, -0.05822058 0.10496286 -0.07432957, 0.079690769 0.05336079 -0.068649858, -0.058196172 0.093538404 -0.0730187, 0.074442938 0.052996933 -0.066576153, 0.068897665 0.053127199 -0.064207703, -0.058315873 0.081923962 -0.070418835, 0.095426783 0.055042207 -0.073020667, 0.10062699 0.055821866 -0.073839709, -0.057084098 0.071358383 -0.06657508, -0.055396244 0.067087471 -0.064206898, 0.08908686 0.056173027 -0.071879089, -0.060790181 0.097707629 -0.07383725, 0.083556652 0.05594939 -0.070420131, -0.058184266 0.070463866 -0.066575319, -0.061075941 0.085801095 -0.07187745, 0.078129783 0.055621326 -0.068649665, 0.09968017 0.057495534 -0.073839635, -0.059910998 0.074892074 -0.068648681, 0.10495871 0.058224648 -0.074332342, 0.10930942 0.060638011 -0.074496657, -0.063406914 0.10191339 -0.074329883, -0.066667467 0.1057418 -0.074494213, 0.072365031 0.055801034 -0.066576049, -0.061065733 0.07395336 -0.068648636, 0.093185455 0.058757305 -0.073020652, -0.063885868 0.089748502 -0.073018894, 0.087511405 0.058597386 -0.07187894, 0.081919909 0.058319688 -0.070419997, -0.062817454 0.078525305 -0.07041885, 0.10397124 0.059970319 -0.074332237, 0.1057377 0.066671669 -0.074496299, -0.060995057 0.068045348 -0.066575348, -0.059753343 0.063237697 -0.064207181, 0.071354523 0.057087451 -0.066576019, 0.065195456 0.057610422 -0.064207435, -0.064028248 0.077541083 -0.070418999, 0.075948834 0.058564246 -0.068649396, -0.066733316 0.093748719 -0.073837519, 0.097338915 0.061376303 -0.073839352, -0.065790504 0.082241654 -0.071877778, 0.091537654 0.061293125 -0.073020354, -0.064015791 0.071414977 -0.068648756, 0.085797206 0.06107986 -0.07187891, -0.062760532 0.066420317 -0.066575393, -0.067058668 0.081210941 -0.071877688, 0.074888274 0.059914678 -0.06864956, -0.069606051 0.097784162 -0.074330211, 0.07963337 0.06140548 -0.070419773, -0.072491497 0.10183746 -0.074494362, 0.10152909 0.06401822 -0.074331909, -0.068817347 0.086025238 -0.073018879, -0.067121223 0.074879497 -0.070418969, 0.095617518 0.064025044 -0.073839158, 0.089744419 0.063889891 -0.073020384, -0.065868765 0.06970951 -0.06864877, 0.068476573 0.060509831 -0.066575706, -0.064714238 0.064518183 -0.066575706, -0.063843399 0.059105366 -0.06420739, -0.070143774 0.08494696 -0.073018953, 0.078521386 0.062821269 -0.070419654, 0.083402306 0.064311624 -0.071878612, -0.071884692 0.089859545 -0.073837787, 0.09973368 0.066780925 -0.074331865, -0.07029812 0.078423351 -0.071877912, 0.10183316 0.07249552 -0.074495837, 0.093744576 0.066737562 -0.073839098, -0.06906414 0.073091358 -0.070419237, 0.071867928 0.063506365 -0.068649292, -0.067918971 0.067713171 -0.068649128, 0.082237631 0.065794498 -0.071878597, -0.073270366 0.088733435 -0.073837817, 0.0872394 0.067270219 -0.073020101, -0.074979156 0.093727618 -0.074330345, 0.097780079 0.069610208 -0.074331582, -0.078087181 0.09761247 -0.074494764, 0.075354308 0.06658721 -0.07041955, -0.067056537 0.062080055 -0.066575691, -0.073532403 0.08203128 -0.073019221, 0.086021081 0.068821371 -0.073020056, -0.072332993 0.076550543 -0.071877927, 0.091127977 0.070268571 -0.073838905, -0.07121402 0.070998222 -0.070419177, 0.064514503 0.064717799 -0.066575423, 0.061202154 0.061836243 -0.064207271, -0.076424345 0.092552871 -0.074330509, -0.083437249 0.09308055 -0.074494809, 0.078920841 0.069738686 -0.071878344, 0.089855298 0.071888834 -0.073838741, -0.070377335 0.065154195 -0.068649173, 0.095050752 0.073293358 -0.074331596, 0.097608387 0.078091323 -0.074495628, -0.076809943 0.085687488 -0.073837981, 0.067709357 0.06792292 -0.068649128, -0.075660735 0.080072284 -0.073019266, 0.093723431 0.074983299 -0.074331343, -0.080116212 0.089375943 -0.074330553, 0.070055485 0.078632176 0.071886525, 0.074354425 0.074580431 0.071886182, 0.077775195 0.0780119 0.073027968, 0.073278502 0.082250029 0.073028356, 0.071606696 0.09007296 0.073847726, 0.079839781 0.089614779 0.074340314, 0.074689031 0.09395051 0.074340701, -0.081890121 0.066218406 0.071885765, -0.078636363 0.070051342 0.071886137, -0.082254142 0.073274314 0.07302779, 0.076544717 0.085916132 0.073847532, -0.085657716 0.069265246 0.073027477, -0.071608856 0.063790858 0.068656325, -0.073791564 0.068307251 0.070426852, -0.075082749 0.06688568 0.070426717, 0.072310731 0.095792949 0.07434094, 0.077785119 0.097845078 0.074505478, 0.072176352 0.10205257 0.074505746, -0.070377409 0.065146625 0.068656296, -0.067056522 0.062072575 0.066582397, -0.064714268 0.064510852 0.066582501, -0.067919046 0.067705601 0.068656638, 0.064514622 0.064710408 0.066582367, 0.068476647 0.06050241 0.066582412, 0.071867868 0.063498795 0.068656385, -0.063843355 0.059098065 0.064214066, 0.065195397 0.05760321 0.06421414, 0.067709491 0.067915171 0.068656445, 0.061202154 0.061829239 0.064214364, 0.066889495 0.075078666 0.070427194, 0.070994213 0.071210146 0.070426956, -0.078189552 0.063225955 0.070426539, 0.068551183 0.086229354 0.073028609, -0.068229839 0.060780764 0.066582352, 0.069326594 0.091839343 0.073847726, -0.067648381 0.054701865 0.064213768, 0.069303587 0.097990513 0.074340865, 0.063794717 0.071604818 0.068656921, -0.10172646 0.063695818 0.074339047, -0.097994789 0.06929943 0.074339405, -0.1020568 0.072172165 0.074503928, -0.10594326 0.066336274 0.074503794, -0.074571952 0.060300499 0.068656221, 0.065536082 0.082436413 0.071886823, 0.066368431 0.087920398 0.073028535, -0.085985497 0.060806215 0.071885586, -0.089941502 0.063604116 0.073027298, 0.066443324 0.093946248 0.07384792, -0.097528294 0.061066866 0.073846161, -0.093950465 0.066439152 0.07384637, 0.060784429 0.06822601 0.066582799, -0.071053058 0.057455122 0.066582143, 0.056935444 0.06577903 0.064214483, 0.065750852 0.10040876 0.074340984, 0.066340387 0.105939 0.074506015, -0.082099736 0.058058351 0.07042627, 0.062574401 0.078711122 0.070427373, -0.093366578 0.058460802 0.073026955, 0.063449219 0.084053218 0.071886882, -0.1051382 0.057891667 0.074338809, -0.10949625 0.060291529 0.074503347, 0.063608229 0.089937389 0.073028654, -0.078301132 0.055372119 0.068655878, 0.063699976 0.1017223 0.074341223, 0.063037232 0.09626472 0.073848039, -0.089259788 0.055889368 0.071885273, 0.059679285 0.075069159 0.068656892, -0.10649014 0.055365533 0.074338555, -0.11270471 0.05405727 0.074503019, 0.060581952 0.080254704 0.070427567, -0.1007991 0.055502236 0.073845714, 0.060810402 0.085981458 0.071886972, -0.074606419 0.05275929 0.066581756, -0.071151167 0.050061285 0.064213648, 0.061071008 0.097523928 0.073848158, -0.085226253 0.05336374 0.070425823, 0.060347423 0.092156917 0.073028877, -0.10209522 0.053080469 0.073845595, 0.056863144 0.071526766 0.066582993, 0.052414626 0.069434911 0.064214736, -0.096497938 0.053133875 0.073026612, 0.057778865 0.076541424 0.068656966, -0.10821889 0.051905364 0.074338347, 0.0580623 0.082095951 0.070427686, -0.081283033 0.050894558 0.06865567, 0.058897197 0.10457632 0.074341282, 0.060295761 0.10949215 0.074506059, -0.097738698 0.050815254 0.073026538, 0.058465019 0.093362421 0.073029175, -0.092253521 0.050796658 0.071884885, -0.10375264 0.049763143 0.073845401, 0.057693169 0.088103354 0.071887016, 0.055052489 0.072929621 0.066582948, -0.1099505 0.048129022 0.074338317, 0.055376023 0.078297287 0.068657175, -0.11555891 0.047652751 0.074502662, -0.077447623 0.048492968 0.066581622, -0.07433638 0.045197099 0.064213529, 0.056466505 0.10026029 0.073848188, -0.093439862 0.04858011 0.071884915, 0.055893496 0.089255959 0.071887121, -0.088084415 0.048501015 0.070425674, 0.055086032 0.084121823 0.070427701, -0.099325508 0.047639519 0.073026285, 0.05276297 0.074602604 0.066583082, 0.047659487 0.072780788 0.0642149, -0.11095932 0.045755982 0.074338019, 0.054057017 0.095981926 0.073029086, -0.10541289 0.046142548 0.073845103, 0.05336754 0.085222214 0.070427671, 0.052537128 0.08022967 0.068657219, -0.089217231 0.046384811 0.070425645, -0.084008932 0.046256781 0.068655327, -0.094956785 0.045544118 0.071884811, 0.051679358 0.091760188 0.071887121, -0.10637993 0.043867379 0.073845163, 0.050898448 0.081279099 0.068657279, 0.050058171 0.076443821 0.066583157, -0.10091476 0.044173479 0.073026255, -0.085089386 0.044238478 0.068655208, 0.049343973 0.087613314 0.070428029, -0.080044866 0.044074178 0.066581309, -0.077189445 0.040131032 0.064213008, 0.048496649 0.077443749 0.06658335, -0.090665579 0.04348585 0.070425436, 0.042691708 0.075801432 0.064214945, -0.11291993 0.040677756 0.074337602, -0.11804916 0.041098356 0.074502438, 0.04576008 0.11095512 0.074341848, 0.05190964 0.1082148 0.07434158, 0.054061353 0.11270064 0.074506298, 0.047656938 0.11555454 0.074506566, -0.1018406 0.041995376 0.073025987, 0.047060862 0.083559513 0.068657488, -0.096476197 0.042230427 0.071884438, -0.081074432 0.042151064 0.066581279, -0.086470872 0.041473746 0.068655059, 0.043871522 0.1063759 0.073848411, 0.049767286 0.10374847 0.073848426, 0.044840127 0.079616666 0.066583425, -0.10825965 0.038998783 0.07384479, -0.097361311 0.04014799 0.071884379, 0.041999593 0.1018365 0.073029414, 0.047643706 0.099321276 0.073029175, -0.09211649 0.040322065 0.070425302, 0.039466649 0.11334625 0.074341908, 0.041102439 0.11804497 0.074506506, -0.082390547 0.039516717 0.066581205, -0.079697669 0.034885764 0.064212725, -0.10364026 0.037334561 0.073025778, 0.040152192 0.097357124 0.071887597, 0.045548126 0.094952613 0.071887448, -0.09296152 0.038333774 0.070425138, 0.036886007 0.11421221 0.074341893, 0.034418747 0.1201638 0.07450673, -0.087854356 0.038456351 0.06865488, 0.037837684 0.10866833 0.073848903, -0.099081874 0.035692364 0.071884066, -0.088660344 0.036560029 0.06865494, 0.038337767 0.092957497 0.070428267, 0.043489829 0.090661615 0.070427999, -0.083708778 0.036641657 0.066580743, -0.094604164 0.034079283 0.070425078, 0.035363704 0.10949847 0.073848814, -0.084476799 0.034834921 0.066580847, 0.036223218 0.10403118 0.073029563, -0.081850037 0.029484689 0.06421262, -0.090227142 0.032502323 0.068654612, 0.033048883 0.11538094 0.074342057, 0.036563799 0.088656574 0.068657666, 0.041477606 0.086466789 0.068657666, -0.085969359 0.030968636 0.066580489, 0.033854663 0.10482597 0.073029548, 0.11751595 0.0025624037 0.074130282, 0.12001677 -0.0013945699 0.074335471, 0.12499994 0.00018891692 0.074499875, 0.11506364 -0.0013372004 0.073842555, 0.034629881 0.099455416 0.071887791, 0.1125825 0.0024547577 0.073473871, 0.11489572 0.0063512027 0.073843092, 0.031684846 0.11061898 0.073848799, 0.029174909 0.11642075 0.074341863, 0.027626738 0.12190473 0.074506789, 0.017015472 0.11630166 0.074136615, 0.020452946 0.11323491 0.073849007, 0.021333247 0.11810949 0.074342176, 0.034838632 0.084472984 0.066583708, 0.039520442 0.082386672 0.06658347, 0.037533 0.078483731 0.064215213, 0.032206729 0.080815524 0.064215288, 0.0163012 0.1114192 0.073480025, 0.012843773 0.11434805 0.073849097, 0.03236565 0.10021508 0.071887717, -0.022077188 0.11544794 0.07413651, -0.0185913 0.118572 0.074342176, -0.021128669 0.12319729 0.074506983, -0.017824054 0.11367834 0.073849082, -0.026469797 0.11706549 0.074342027, 0.033065021 0.094960839 0.070428297, -0.025377393 0.11223391 0.073849037, -0.02115038 0.11060125 0.073479995, 0.030332834 0.10589868 0.073029816, -0.093732581 0.070924073 0.074134171, -0.08947584 0.072352558 0.073846817, -0.093327448 0.075467348 0.074339718, 0.026527241 0.11705241 0.074342012, 0.027970761 0.11161596 0.073848873, -0.11185558 0.036119401 0.074132055, 0.030903026 0.095686257 0.070428357, -0.10715991 0.034603059 0.073475853, -0.11062308 0.031680614 0.073844358, 0.031535089 0.090567201 0.068657696, 0.12117177 0.0048137307 0.074407712, 0.12479243 0.0071974695 0.074500367, 0.11984156 0.0066247582 0.074335769, 0.028998718 0.10124061 0.071887672, 0.10894156 0.0005543232 0.07276842, 0.11015376 -0.0012802482 0.073023647, 0.1053088 -0.0012241304 0.071882054, 0.025432318 0.11222154 0.073849007, 0.10886209 0.0041942 0.07276845, 0.10999295 0.006080091 0.073024094, 0.10515513 0.0058124363 0.071882382, 0.026777104 0.10685298 0.073029637, 0.057255194 0.10689592 0.074413419, 0.054287538 0.10425249 0.074136078, 0.0542344 0.10845971 0.074413627, 0.029473245 0.091258943 0.068657875, 0.054226294 0.10008979 0.073674068, 0.030047178 0.086293459 0.066583619, 0.050912052 0.10181555 0.073674187, 0.02673687 0.082786143 0.064215466, 0.027688161 0.096665412 0.070428595, 0.018842548 0.11979035 0.074414, 0.020747811 0.12326193 0.07450676, 0.015475184 0.12027171 0.07441406, 0.013803571 0.1242314 0.074506894, 0.013396546 0.11927065 0.074342147, 0.024347171 0.10743281 0.073029742, 0.017569482 0.10751283 0.072774425, 0.018718973 0.10363477 0.071888059, 0.0195802 0.10840297 0.073029801, 0.02559948 0.10215312 0.071887925, 0.013967022 0.10803983 0.072774425, 0.012295634 0.1094687 0.073029816, 0.011754826 0.10465363 0.071888089, 0.02808243 0.086952776 0.066583753, -0.018670738 0.10732692 0.07277438, -0.017063409 0.10882738 0.073029667, -0.016312957 0.10404065 0.071888015, 0.026407182 0.092192829 0.068658024, -0.022246987 0.10664323 0.072774321, -0.02429457 0.10744482 0.073029697, -0.023225859 0.1027188 0.071887732, -0.095821261 0.07431975 0.074411526, -0.09784925 0.077780902 0.07450439, 0.023276418 0.10270727 0.071887836, -0.097868234 0.071603 0.074411228, -0.089659229 0.07014209 0.073672369, 0.024442613 0.097536713 0.07042858, 0.11705661 -0.026531339 0.074334025, 0.12016803 -0.034423053 0.074497953, 0.12190878 -0.027630985 0.074498504, 0.115385 -0.033053041 0.074333549, -0.091872945 0.067216665 0.07367225, 0.025161073 0.087842554 0.066583738, -0.11496884 0.038569808 0.07440953, 0.11222567 -0.02543655 0.073841244, 0.11062312 -0.031689048 0.073840797, 0.021147415 0.084386975 0.064215466, -0.11600555 0.035330325 0.074409381, -0.12016809 0.034414619 0.074501753, -0.11538516 0.033044815 0.074337393, 0.022224352 0.098065943 0.070428595, -0.10309687 0.035203844 0.072770238, 0.10743698 -0.024351448 0.073022187, 0.10590273 -0.030337065 0.073022097, 0.023311675 0.093023837 0.06865783, -0.10421565 0.031739116 0.072770223, -0.10590278 0.030328691 0.073025391, 0.11836006 -0.01992625 0.074334264, 0.12326598 -0.020752013 0.074498922, -0.10124482 0.02899462 0.071883723, 0.10471518 -0.00034219027 0.071717098, 0.10054968 -0.0011687577 0.070422888, 0.10271153 -0.023280501 0.071880952, 0.10124467 -0.029002875 0.071880564, 0.10330753 0.0016764104 0.071312606, 0.1187606 -0.017378867 0.074334443, 0.12423562 -0.013807774 0.07449922, 0.10606019 0.0034947991 0.072094783, 0.021196127 0.09352845 0.068658128, 0.11347507 -0.019104004 0.073841617, 0.10466816 0.0031569004 0.071717381, 0.022211671 0.088634253 0.066583753, 0.10460071 0.0049054921 0.071717292, 0.100403 0.0055498183 0.070423439, 0.098069876 -0.02222842 0.070421651, 0.096669495 -0.027692318 0.070421502, 0.052972883 0.095888436 0.072903886, 0.052327856 0.097860038 0.073188111, 0.017872915 0.098951548 0.070428565, 0.11385924 -0.016661763 0.0738419, 0.051391795 0.096745163 0.072904035, 0.020196065 0.089115083 0.066583902, 0.10863304 -0.01828894 0.073022529, 0.015463397 0.085611135 0.06421563, 0.049415752 0.09617728 0.072592258, 0.11929071 -0.013258427 0.074334726, 0.048188955 0.098379523 0.072904184, 0.093532309 -0.021200001 0.068651631, 0.092196718 -0.026411116 0.068651378, 0.017046124 0.094373018 0.068658054, 0.01775068 0.10319617 0.071722925, 0.10900089 -0.015950978 0.073022798, 0.0065446496 0.11984205 0.074342161, 0.0068158656 0.12480995 0.074506998, 0.016530186 0.10481846 0.072100669, 0.10385495 -0.017484754 0.07188113, 0.016023695 0.1034784 0.07172285, 0.11436762 -0.012711406 0.073842064, 0.016241744 0.089919865 0.066584006, 0.014386967 0.10231048 0.071318194, 0.11965594 -0.0094078481 0.07433483, 0.12481403 -0.0068201721 0.074499488, 0.006274581 0.11489585 0.073849186, 0.012556776 0.10395616 0.071722761, 0.011223599 0.099924207 0.070428655, 0.089118779 -0.020199746 0.066577643, 0.085050225 -0.018319428 0.064209804, -0.017083839 0.10330871 0.07172288, -0.015575871 0.099339038 0.070428595, 0.087846234 -0.025164872 0.06657736, -0.018840149 0.10158467 0.07131806, 0.10420652 -0.01524961 0.071881324, 0.0060068518 0.1099931 0.073029891, 0.099161774 -0.016694695 0.070422187, -0.021090955 0.10399675 0.072100386, -0.020526469 0.10268021 0.07172285, 0.10948743 -0.012169152 0.073022947, -0.00018543005 0.12002051 0.074342176, -0.00019320846 0.12499568 0.074506998, -0.022239357 0.10232297 0.071722746, -0.022176296 0.098076761 0.070428565, 0.11984631 -0.0065489113 0.074335143, -0.098810434 0.034664571 0.071718946, 0.11471765 -0.0090197027 0.073842183, 0.0057426393 0.10515505 0.071888015, -0.1006131 0.033731043 0.072096661, 0.099497423 -0.014560372 0.070422202, 0.094573557 -0.015922278 0.068651825, -0.002620697 0.11999208 0.07434234, -0.0072017461 0.12478825 0.074506968, -0.099376008 0.033008665 0.071718857, -0.00017787516 0.11506692 0.073849171, -0.098496452 0.031200349 0.07131429, 0.10467164 -0.011634111 0.071881399, -0.10042346 0.029669583 0.071718603, -0.096669465 0.027684271 0.070424527, 0.11490008 -0.0062786639 0.073842213, 0.099577606 0.00022906065 0.070079684, 0.095897555 -0.0011149347 0.068652809, 0.0054832101 0.10040289 0.070428595, 0.099514157 0.0035564005 0.070079789, 0.10982256 -0.0086348653 0.073023215, -0.0025125742 0.11503953 0.073849127, 0.095757723 0.0052928329 0.068653077, 0.049439415 0.091852754 0.071609348, 0.094893828 -0.01388678 0.068652019, 0.090110958 -0.015170962 0.066578075, 0.086083576 -0.01259768 0.064210087, -0.00017005205 0.11015686 0.07302995, 0.046398133 0.09342581 0.071609259, 0.099941537 -0.011108398 0.070422456, 0.015785307 0.098314762 0.070085078, -0.0069150329 0.11982122 0.074342147, 0.0052293688 0.095757425 0.068658128, 0.010704383 0.095300823 0.068658158, 0.012491331 0.098787248 0.070085049, -0.002405405 0.11013079 0.073029891, 0.10999712 -0.00601089 0.073023394, -0.01679258 0.098147631 0.070085272, -0.014855042 0.094742596 0.068658218, 0.10499221 -0.0082553327 0.071881533, -0.00016266108 0.10531151 0.071888149, -0.020062909 0.097531796 0.070084959, -0.021150276 0.09353888 0.068658084, 0.090416104 -0.013231635 0.066578165, -0.0066296607 0.11487609 0.073849112, -0.09432359 0.0319148 0.070081323, 0.095317394 -0.010594517 0.068652064, -0.010629773 0.11954892 0.074342221, -0.014187455 0.12418813 0.074506685, -0.095337287 0.028745145 0.070081174, 0.0049827099 0.091238886 0.066584021, 0.01019904 0.090803951 0.066583946, 0.0097104758 0.086452752 0.064215571, -0.092196733 0.026403278 0.06865418, 0.095419288 0.0011496842 0.068450838, 0.0039141029 0.08690843 0.06421572, -0.0022995472 0.10528663 0.071887985, 0.091372401 -0.001062274 0.06657891, 0.10515919 -0.0057467818 0.071881995, 0.094031885 0.0024864972 0.06785351, -0.00015549362 0.10055256 0.070428729, 0.10024752 -0.0078822672 0.070422575, 0.095327362 0.0043375492 0.068450823, 0.091239154 0.0050430298 0.066579133, 0.090819702 -0.010094464 0.066578388, -0.0063467771 0.10997412 0.073029861, 0.04826653 0.087652534 0.070258021, 0.086732566 -0.0068198144 0.064210564, 0.045968473 0.087302387 0.069751859, -0.010191068 0.11461493 0.073849082, 0.10040697 -0.0054870546 0.07042253, 0.045363784 0.089189291 0.07025829, -0.013622791 0.11924502 0.074342191, 0.016045034 0.094063878 0.06845592, -0.0021955669 0.10052863 0.070428595, 0.095609307 -0.0075177848 0.068652287, -0.00014822185 0.09589994 0.068658009, 0.014048517 0.093005985 0.067858592, 0.012892708 0.094547451 0.068456098, -0.0060676187 0.10513687 0.071888104, -0.0097562671 0.10972416 0.073029891, -0.017008558 0.093894452 0.068455935, -0.014154151 0.090272099 0.066583946, 0.09576124 -0.0052332878 0.068652436, -0.018095985 0.092303962 0.067858487, 0.091097668 -0.0071629286 0.066578463, -0.02013655 0.09327364 0.06845586, -0.020152286 0.089125097 0.066583946, -0.013060585 0.11432353 0.073849097, -0.090088531 0.031463861 0.068452463, -0.0020941049 0.0958772 0.068658248, -0.0001411587 0.091374665 0.066584066, -0.0018996298 0.086975664 0.06421569, -0.089377597 0.029319197 0.06785512, 0.091242597 -0.0049863458 0.066578761, 0.086994171 -0.0010113716 0.064210743, -0.091089904 0.028436065 0.068452254, -0.087846279 0.025157481 0.066580296, 0.090481862 0.00067007542 0.066125587, 0.086867213 0.0048013031 0.064211026, -0.0057934076 0.10038549 0.070428699, 0.090408757 0.0036931336 0.066125721, -0.0093270242 0.10489783 0.071888, 0.045434222 0.083406359 0.068263933, -0.012503251 0.1094451 0.073029727, 0.042672306 0.084852546 0.068263993, 0.11924921 0.013618618 0.074336156, 0.12419225 0.014183372 0.074500799, -0.0019952059 0.091352999 0.066583931, 0.014799848 0.089262098 0.06613034, 0.011808753 0.089706808 0.066130325, -0.0055253059 0.095740765 0.068658113, -0.015714318 0.089105695 0.066130325, -0.019186705 0.084854305 0.064215675, -0.013475955 0.085946351 0.064215586, 0.11432764 0.013056457 0.073843479, -0.018683031 0.088530749 0.066130415, -0.0089055151 0.10015738 0.070428595, -0.085560769 0.029437542 0.066127047, -0.011953294 0.10463116 0.071887806, -0.086496666 0.026562035 0.066126883, 0.10944934 0.012499064 0.073024362, 0.042748049 0.080252081 0.066358224, -0.0052647591 0.091223121 0.066584051, 0.11829771 0.02028349 0.074336559, 0.12320146 0.021124482 0.074501127, -0.0077049881 0.086654454 0.064215556, -0.0084935427 0.095523268 0.068658188, -0.011413142 0.099902779 0.07042858, 0.1046353 0.011949182 0.07188268, -0.02800341 0.12181863 0.07450664, 0.11788882 0.022538781 0.074336797, 0.12182295 0.027999133 0.074501574, 0.11341564 0.019446135 0.073843792, -0.0080927461 0.091015816 0.066584036, -0.010885119 0.095280319 0.068658024, 0.099906728 0.011409283 0.070423737, 0.11302339 0.021608621 0.073843971, 0.10857603 0.018616319 0.073024675, -0.010371432 0.090784281 0.066584021, 0.11697404 0.026884586 0.074336916, 0.095284298 0.010881156 0.06865339, 0.10820073 0.020686388 0.073024988, -0.033405364 0.1152783 0.074341938, -0.034790069 0.1200569 0.0745067, 0.10380034 0.0177975 0.071883261, 0.1121466 0.025774747 0.073844224, 0.11611986 0.030362695 0.074337155, 0.12006103 0.034785897 0.074501917, -0.032026783 0.11052054 0.073849067, 0.090787962 0.010367811 0.066579461, 0.086352289 0.01059261 0.064211279, 0.10344154 0.019776374 0.07188338, 0.09910962 0.016993016 0.070424005, -0.030660018 0.10580441 0.073029622, -0.039816633 0.11322376 0.074341848, -0.041467234 0.1179173 0.074506775, 0.1073612 0.024674863 0.073025063, 0.11132745 0.029109478 0.073844254, -0.029311508 0.10115051 0.071887806, 0.11528236 0.033401132 0.074337289, 0.098767057 0.018882662 0.07042411, -0.041837454 0.11249283 0.074341729, -0.048013896 0.11540663 0.074506462, 0.094523951 0.016206712 0.068653733, -0.038173512 0.10855094 0.073848829, 0.10263903 0.023589522 0.071883529, 0.10657702 0.027867168 0.073025167, 0.11052459 0.032022417 0.073844403, -0.027986929 0.096579343 0.070428342, 0.094197199 0.018008858 0.068653747, -0.040110931 0.10785013 0.073848754, 0.09006381 0.015441895 0.066579714, 0.085451737 0.016336709 0.064211771, -0.036544621 0.10391885 0.073029593, 0.11383213 0.03805089 0.074337646, 0.11792159 0.041462988 0.07450214, -0.046102822 0.11081317 0.07434164, 0.098000586 0.022523463 0.070424214, -0.026692048 0.092110783 0.068657905, 0.10188937 0.026641309 0.071883723, -0.038399279 0.10324782 0.073029429, 0.10580833 0.03065601 0.073025435, -0.034937263 0.099347949 0.071887717, 0.089752272 0.017159104 0.066579923, -0.044200093 0.10623971 0.073848471, 0.11322796 0.039812624 0.074337751, -0.049258068 0.10944718 0.074341729, -0.054409385 0.11253297 0.074506372, 0.10913427 0.036480218 0.073844925, -0.025432616 0.087764412 0.066583753, -0.024811655 0.083383352 0.064215407, 0.093466371 0.021481186 0.068654075, -0.036710262 0.098706365 0.071887732, 0.097284898 0.025437385 0.070424497, -0.033358335 0.09485817 0.070428371, 0.10115473 0.029307365 0.071883872, -0.042314053 0.10170615 0.073029429, 0.10855496 0.038169265 0.073844716, -0.047225043 0.10492998 0.073848501, 0.10447747 0.034923553 0.073025599, -0.052243918 0.10805383 0.07434158, 0.089056119 0.02046746 0.066579863, 0.084169477 0.022007823 0.06421189, -0.035051227 0.094245851 0.070428222, 0.092783734 0.024260253 0.068654016, -0.031814888 0.090469152 0.068657771, 0.096583351 0.02798301 0.070424542, -0.040453002 0.097232759 0.071887672, -0.045209944 0.10045254 0.073029295, 0.10392292 0.036540478 0.073025748, 0.11103626 0.045568973 0.074338034, 0.11541083 0.048009694 0.074502647, -0.05008778 0.10359418 0.073848352, 0.0998822 0.033387214 0.071884036, -0.033429608 0.089885145 0.068657756, -0.030313596 0.086200178 0.066583738, 0.088405535 0.023115486 0.066580236, -0.030326009 0.081539869 0.064215332, -0.056458563 0.10591266 0.074341461, -0.060633823 0.10930523 0.074506074, 0.092114747 0.026688069 0.068654194, -0.038624793 0.092838526 0.070428297, 0.099351972 0.03493315 0.071884155, -0.043221459 0.09603405 0.071887523, 0.10645369 0.043688089 0.073844969, -0.047950476 0.099173695 0.07302916, 0.095368445 0.031878412 0.070424646, -0.031852081 0.085643649 0.066583633, 0.087768078 0.025428742 0.06658031, 0.08251141 0.027580589 0.064212322, -0.058220655 0.10495454 0.074341401, 0.094862238 0.033354431 0.070424825, -0.054128587 0.10154149 0.073848397, 0.10191122 0.041823775 0.073026136, -0.036837786 0.088543028 0.068657756, 0.090955943 0.030403465 0.068654314, -0.041268229 0.091694087 0.070427999, 0.10805798 0.052239656 0.074338317, 0.11253719 0.054405272 0.074503109, -0.045841366 0.094811469 0.07188724, 0.09047313 0.031810969 0.068654463, 0.097428784 0.039984137 0.071884245, -0.055817753 0.10062271 0.073848426, -0.051818848 0.0972085 0.073029056, 0.086663976 0.028968722 0.066580415, -0.035099551 0.084364861 0.066583619, -0.035704717 0.079332203 0.064215139, 0.10359831 0.050083548 0.073845357, -0.039358959 0.087451637 0.068657801, 0.086203903 0.030310065 0.066580594, 0.080484673 0.033030093 0.064212635, -0.043769762 0.090526819 0.070427984, 0.093026027 0.038177133 0.070425019, -0.053436056 0.096329033 0.073029146, 0.099177822 0.047946244 0.073026344, -0.063406929 0.10190511 0.074341103, -0.066667497 0.10573339 0.074505851, 0.10495868 0.058216333 0.074338734, 0.10930936 0.060629725 0.074503511, -0.049539641 0.092932761 0.071887508, -0.037501588 0.083324939 0.06658341, 0.088721856 0.03641066 0.068654776, -0.041744605 0.086338222 0.068657488, 0.10397124 0.059961975 0.074338719, 0.1057376 0.066663325 0.07450366, -0.051085636 0.092091948 0.071887091, 0.094815627 0.045837343 0.071884871, -0.060790062 0.097699374 0.073848113, 0.10062696 0.055813581 0.073845729, -0.04730089 0.088732988 0.070427924, 0.084535167 0.034692585 0.066580996, -0.039774895 0.082264215 0.066583619, -0.040923938 0.076770186 0.064215139, -0.04877691 0.087930173 0.070427895, 0.099680245 0.05748719 0.073846102, -0.058195964 0.093530267 0.073028788, 0.090530872 0.043765813 0.070425436, -0.045112342 0.08462733 0.068657428, 0.096333161 0.053431869 0.073026836, -0.069606096 0.097775877 0.074340954, -0.072491512 0.1018292 0.074505672, 0.10152903 0.064009964 0.074338898, 0.095426813 0.055034131 0.073026776, -0.046520188 0.083861709 0.068657324, -0.055636466 0.089416295 0.071887285, 0.086342171 0.041740656 0.068655074, 0.09209612 0.051081538 0.071884885, -0.042983636 0.080633998 0.06658332, 0.097338885 0.061367989 0.073846325, -0.06673333 0.093740493 0.073847875, 0.099733636 0.06677264 0.074339077, 0.10183311 0.072487205 0.074504048, -0.044324994 0.079904377 0.066583395, -0.045960575 0.073865354 0.064214885, 0.091229558 0.052613348 0.071885109, -0.053122088 0.085375458 0.070427939, 0.082267836 0.03977111 0.066581056, 0.078098491 0.038332015 0.064212903, -0.063885882 0.089740396 0.073028743, 0.087934181 0.04877308 0.070425868, -0.074979186 0.093719304 0.074340746, -0.078087077 0.097604185 0.074505374, 0.093185499 0.058749139 0.07302697, -0.050664395 0.081425071 0.068657458, 0.095617607 0.0640167 0.073846221, -0.07642436 0.092544496 0.074340761, -0.083437368 0.093072236 0.074505225, 0.097780198 0.069601804 0.074339464, -0.061075896 0.085793018 0.071887061, 0.087106854 0.050235569 0.070425794, 0.083865598 0.04651624 0.068655416, -0.071884766 0.08985123 0.073847696, 0.089086875 0.05616498 0.071885228, -0.048273697 0.077582985 0.066583186, 0.091537535 0.061284989 0.073027134, -0.073270455 0.08872506 0.073847726, 0.093744695 0.066729218 0.073846474, -0.058315754 0.081915975 0.070427567, 0.083076537 0.047911257 0.068655431, 0.079908311 0.044321388 0.066581428, -0.068817452 0.086017102 0.073028564, 0.075363547 0.043462902 0.064213201, -0.080116197 0.089367598 0.074340403, 0.095050648 0.073285043 0.074339584, 0.097608536 0.078082949 0.07450442, -0.070143834 0.084938973 0.07302855, 0.085060835 0.053626895 0.070426181, -0.055617765 0.078125805 0.068657011, 0.087511405 0.05858925 0.071885288, 0.089744538 0.063881636 0.073027298, -0.065790534 0.082233608 0.071886703, 0.079156443 0.045650393 0.066581413, -0.076809928 0.085679233 0.073847517, 0.093723521 0.074974895 0.074339584, -0.082435355 0.087233245 0.074340373, -0.088524789 0.088247567 0.074504927, 0.091127858 0.070260316 0.073846415, -0.067058623 0.081202894 0.071886748, 0.081125364 0.051145494 0.068655685, -0.052993223 0.074439287 0.066583022, -0.05079174 0.07063055 0.064214736, 0.083556727 0.055941582 0.070426092, -0.062817454 0.078517377 0.070427448, 0.08579722 0.061071724 0.071885511, -0.073532373 0.082023203 0.07302846, 0.089855462 0.071880519 0.073846623, -0.079033226 0.083632946 0.073847413, -0.085001305 0.084734917 0.074340194, 0.087239489 0.067262113 0.073027313, 0.077297196 0.048732072 0.066581622, -0.064028308 0.077533275 0.070427343, 0.072292 0.048399568 0.064213604, -0.059910983 0.074884355 0.068656892, 0.079690665 0.053353131 0.068655759, -0.070298091 0.078415275 0.071886495, 0.081919968 0.05831185 0.070426241, -0.075660706 0.080064118 0.073028058, 0.089943305 0.079470068 0.074340031, 0.093076527 0.083433062 0.074504629, 0.086021259 0.068813235 0.073027492, -0.081493452 0.081237674 0.073847204, 0.083402425 0.064303488 0.071885675, -0.061065763 0.073945671 0.068656906, -0.057084009 0.071350783 0.066582903, 0.075930268 0.05083555 0.06658183, -0.055396274 0.067080289 0.064214706, -0.088077992 0.081532389 0.074340045, -0.093333885 0.083145052 0.074504644, 0.078129709 0.055613816 0.068655834, 0.086231291 0.076190084 0.073847041, -0.067121238 0.074871629 0.070427194, 0.082237631 0.065786451 0.071885854, -0.072332829 0.076542467 0.071886405, -0.078015953 0.077771068 0.073028088, 0.079633296 0.061397642 0.070426568, 0.074442983 0.052989483 0.066581875, -0.058184192 0.070456386 0.066582724, 0.06889756 0.053120047 0.064213827, 0.082551852 0.0729388 0.073027834, -0.089619026 0.079835415 0.074339911, 0.078521311 0.062813342 0.070426568, -0.084442958 0.078167319 0.07384716, -0.064015806 0.071407288 0.068656757, 0.075948864 0.058556646 0.068655983, -0.069064185 0.07308349 0.07042709, 0.084739089 0.084997207 0.074340388, 0.088251725 0.088520736 0.074504986, -0.074584559 0.074350268 0.071886197, 0.078920782 0.06973055 0.07188578, 0.074888304 0.059907049 0.068655983, -0.085920423 0.07654056 0.07384707, -0.080839694 0.074831724 0.07302779, 0.07236509 0.055793643 0.066582069, 0.08124201 0.081489086 0.073847145, -0.060994938 0.068037868 0.06658259, -0.059753329 0.063230455 0.064214349, 0.075354278 0.066579372 0.070426866, -0.065868691 0.069701821 0.068656743, -0.07121402 0.070990354 0.07042715, 0.071354449 0.057080269 0.066582069, 0.083149225 0.093329668 0.074505076, -0.077284172 0.071540266 0.071886107, -0.062760472 0.066412807 0.066582516, 0.042863935 -0.15911558 0.0077774823, 0.041125029 -0.15977865 0.0019908398, 0.045149982 -0.15868819 0.0019908994, 0.043184236 -0.15706974 0.024398088, 0.040456176 -0.15710104 0.027991176, 0.041952401 -0.15800217 0.020791113, 0.044381559 -0.15603763 0.027991176, 0.033646733 -0.16131639 0.0077773184, 0.030111805 -0.16192594 0.0092196465, 0.031563386 -0.16184068 0.0056074411, 0.03299877 -0.16165248 0.0019907653, 0.037073717 -0.16076684 0.0019907206, 0.033528551 -0.16075069 0.014990866, 0.027756214 -0.16184726 0.014990807, 0.029113695 -0.16117093 0.018621787, 0.039396286 -0.16000929 0.0077774227, 0.041400135 -0.15925151 0.011386991, 0.03337881 -0.16003281 0.020791084, 0.036505461 -0.15806583 0.027991042, 0.032531962 -0.15893131 0.027990878, 0.030447349 -0.16039169 0.022237524, 0.039258033 -0.15944821 0.014990881, 0.039909258 -0.15928659 0.01499103, 0.039082691 -0.15873617 0.020791128, 0.041489154 -0.15442088 0.037811115, 0.040247858 -0.15626645 0.031991199, 0.044141993 -0.1552113 0.031991333, 0.038143426 -0.14783829 0.057991818, 0.039783865 -0.15046602 0.050829262, 0.040776506 -0.14871851 0.054429203, 0.041723981 -0.14686808 0.057991728, 0.032642037 -0.15653011 0.037811041, 0.029218093 -0.15679371 0.039253056, 0.030806437 -0.15749264 0.035634503, 0.032386303 -0.15808293 0.031991169, 0.036328405 -0.15722376 0.031991184, 0.032197267 -0.15439722 0.044991329, 0.026658639 -0.15544939 0.044991344, 0.027885959 -0.15394086 0.048653036, 0.038215443 -0.15526351 0.037810907, 0.039805114 -0.15378797 0.041414499, 0.031772077 -0.15235907 0.050829038, 0.034540445 -0.14872137 0.057991594, 0.030916944 -0.14951661 0.057991728, 0.029079154 -0.15232521 0.052275822, 0.037694767 -0.153148 0.044991434, 0.038100854 -0.15304744 0.044991389, 0.037197053 -0.1511263 0.050829083, 0.029141665 -0.1425373 0.072016492, 0.025762856 -0.14318672 0.072016656, 0.028182447 -0.14555353 0.067054659, 0.038539976 -0.14315906 0.067056432, 0.03769426 -0.1460391 0.061991692, 0.041207731 -0.14508659 0.061991766, 0.031039715 -0.14497098 0.067054853, 0.030603275 -0.1476877 0.061991692, 0.034158677 -0.14690614 0.061991781, 0.032504275 -0.14180845 0.072016597, 0.035792261 -0.14387146 0.067054853, 0.035848632 -0.14100003 0.072016776, 0.042449251 -0.15763858 -0.022253275, 0.040456235 -0.15709805 -0.028008968, 0.044381469 -0.15603447 -0.028008983, 0.043729231 -0.15898484 -0.0056271106, 0.04112497 -0.15977833 -0.0020091832, 0.042281628 -0.15918109 -0.0092399567, 0.045150071 -0.15868798 -0.0020089298, 0.033333853 -0.1598146 -0.022253409, 0.029916734 -0.16071337 -0.0208112, 0.031236187 -0.15987208 -0.024417505, 0.032531843 -0.1589281 -0.028009161, 0.03650555 -0.15806276 -0.028009042, 0.033528492 -0.1607489 -0.01500921, 0.029233351 -0.16192609 -0.011403531, 0.027756214 -0.16184562 -0.015009075, 0.039030045 -0.1585198 -0.02225326, 0.04119651 -0.15851149 -0.018638, 0.033629015 -0.16123095 -0.0092399567, 0.037073731 -0.1607666 -0.0020090789, 0.0329988 -0.16165227 -0.0020091534, 0.030694351 -0.16190332 -0.007793501, 0.039258122 -0.1594466 -0.015008971, 0.039909244 -0.1592848 -0.015008956, 0.039375633 -0.15992463 -0.0092399865, 0.040186346 -0.14977345 -0.052290618, 0.038143337 -0.1478318 -0.058008373, 0.041724011 -0.14686158 -0.058008254, 0.042490155 -0.15474549 -0.035653919, 0.040247813 -0.15626281 -0.032008812, 0.040817961 -0.15417612 -0.039272755, 0.044142023 -0.15520781 -0.032008797, 0.031657815 -0.1518051 -0.052290514, 0.028605953 -0.15297869 -0.050848722, 0.029778585 -0.1512982 -0.054448023, 0.030916885 -0.1495102 -0.058008343, 0.034540445 -0.1487149 -0.058008224, 0.032197297 -0.1543923 -0.0450086, 0.028260797 -0.15631753 -0.041430071, 0.026658684 -0.15544432 -0.045008793, 0.037063181 -0.15057665 -0.052290514, 0.039166301 -0.15145943 -0.048668385, 0.03255935 -0.15612894 -0.039272964, 0.03632848 -0.15722021 -0.032008991, 0.032386288 -0.15807933 -0.032008752, 0.029854387 -0.1570822 -0.037826329, 0.037694722 -0.15314296 -0.045008734, 0.038100809 -0.15304235 -0.045008779, 0.03811869 -0.15486565 -0.039272875, 0.050489262 -0.15646133 -0.013008878, 0.047986165 -0.15754411 -0.0094031543, 0.046525344 -0.1576854 -0.013009027, 0.050489023 -0.1564627 0.012991056, 0.046525434 -0.15768683 0.012990981, 0.048849359 -0.15741184 0.007219851, 0.05226624 -0.15630955 -0.0072395802, 0.051655352 -0.15670606 -8.8214874e-06, 0.049419254 -0.15730223 -0.0057932585, 0.05442065 -0.1551376 -0.013008878, 0.05232428 -0.15648383 -8.9854002e-06, 0.050266072 -0.15710929 0.0036075115, 0.057824016 -0.15433988 -0.0072395056, 0.058317617 -0.15371522 -0.013008654, 0.060627684 -0.15326047 -0.0072393566, 0.052287072 -0.1563727 0.0057777613, 0.05442065 -0.15513909 0.012991086, 0.057888389 -0.15451208 -8.7171793e-06, 0.06202206 -0.15285006 -0.0036267787, 0.06337823 -0.15234262 -8.5234642e-06, 0.061190024 -0.1531086 0.0057778507, 0.057847217 -0.15440243 0.005777806, 0.059772715 -0.15346113 0.0093873441, 0.058317676 -0.15371668 0.012991384, 0.047825843 -0.15161446 -0.041008607, 0.046515957 -0.15250683 -0.039429635, 0.044843927 -0.15188068 -0.043008775, 0.048591688 -0.15072343 -0.043008536, 0.050217777 -0.15083918 -0.041008607, 0.048167229 -0.15302691 -0.035825968, 0.052309692 -0.14947388 -0.043008491, 0.052596927 -0.15002617 -0.041008607, 0.050346136 -0.15240884 -0.035512641, 0.054963022 -0.14917555 -0.041008428, 0.055995762 -0.14813241 -0.043008417, 0.050766811 -0.15363804 -0.030008718, 0.051040486 -0.15467584 -0.024505824, 0.048401639 -0.15582046 -0.02281104, 0.049601793 -0.15477929 -0.026417553, 0.058783025 -0.14885905 -0.037272185, 0.057598114 -0.14981219 -0.035537258, 0.0491817 -0.15616682 -0.019008905, 0.04640764 -0.15727878 -0.017008975, 0.050356254 -0.1560595 -0.017008767, 0.051731244 -0.15534079 -0.01900883, 0.06048362 -0.14917874 -0.033653319, 0.060158595 -0.15020952 -0.030008554, 0.054272786 -0.15474087 -0.017008722, 0.054267079 -0.15447316 -0.019008577, 0.062152818 -0.14939532 -0.030008554, 0.056788296 -0.15356421 -0.019008428, 0.060449302 -0.15129429 -0.02425313, 0.058526993 -0.15199742 -0.024526, 0.059325069 -0.15235707 -0.020637855, 0.058155015 -0.15332419 -0.017008573, 0.051313922 -0.15345609 -0.030008554, 0.052814931 -0.15295628 -0.029963836, 0.057443097 -0.15332055 -0.019008607, 0.048174068 -0.14946583 0.046991497, 0.045505285 -0.14890528 0.050653905, 0.044473827 -0.15060821 0.046991512, 0.044917241 -0.13837832 0.072016686, 0.041632414 -0.13940188 0.072016597, 0.0444666 -0.14160445 0.066743672, 0.049129039 -0.14685625 0.052830026, 0.047969952 -0.1439909 0.059991956, 0.046490595 -0.1470986 0.054277107, 0.051845118 -0.14823249 0.046991542, 0.048150197 -0.14393067 0.059991866, 0.046223775 -0.14284855 0.063390091, 0.054339498 -0.14500901 0.05283016, 0.055484518 -0.14690885 0.046991765, 0.056825802 -0.14405304 0.052830204, 0.047308609 -0.14141563 0.065409794, 0.048176944 -0.13727739 0.07201694, 0.053256795 -0.14212024 0.059991956, 0.057589397 -0.14214027 0.056430072, 0.058295608 -0.14012876 0.059992135, 0.055269942 -0.13849819 0.065410078, 0.052326068 -0.13963696 0.065409929, 0.053350702 -0.13734889 0.068736583, 0.051409543 -0.1360997 0.072016835, 0.049181551 -0.1561687 0.018991292, 0.047664389 -0.15639976 0.020622179, 0.046407714 -0.15728071 0.016991243, 0.050356284 -0.15606132 0.016991079, 0.051731199 -0.15534288 0.018991292, 0.048886046 -0.15541887 0.024237886, 0.054272845 -0.1547429 0.016991362, 0.054267183 -0.15447536 0.018991277, 0.051040545 -0.15467873 0.024488404, 0.056788325 -0.15356639 0.018991455, 0.058154941 -0.15332609 0.016991317, 0.050766826 -0.15364134 0.029991239, 0.050346121 -0.15241283 0.035495743, 0.047509164 -0.15283579 0.037253141, 0.049148291 -0.15329173 0.033634439, 0.060005024 -0.15173346 0.02279155, 0.058526859 -0.15200022 0.024508879, 0.047825858 -0.15161902 0.040991411, 0.044843912 -0.15188539 0.042991355, 0.048591748 -0.1507282 0.04299143, 0.050217718 -0.15084374 0.04099144, 0.061101794 -0.15061384 0.026398346, 0.060158536 -0.15021285 0.029991329, 0.052309886 -0.14947864 0.042991459, 0.052596986 -0.15003067 0.040991619, 0.062152877 -0.14939862 0.029991433, 0.054962978 -0.14918 0.040991649, 0.059467211 -0.14900345 0.035811007, 0.057598159 -0.1498161 0.035520703, 0.0577472 -0.14862186 0.039414212, 0.055995673 -0.14813715 0.042991579, 0.051316947 -0.15346858 0.029946685, 0.052815005 -0.15295967 0.029946759, 0.055777282 -0.14887753 0.040991649, 0.0058504641 -0.15496057 -0.052290857, 0.0042908639 -0.1526131 -0.058008805, 0.0079974383 -0.15246382 -0.058008596, 0.0069901496 -0.16032052 -0.035654217, 0.0044665635 -0.1613009 -0.03200908, 0.005486697 -0.15939358 -0.039273232, 0.008497864 -0.16113877 -0.032009184, -0.0029163063 -0.15504342 -0.052290887, -0.0061528981 -0.15550837 -0.050848633, -0.0046355426 -0.15413103 -0.054448158, -0.0031279624 -0.15264136 -0.058008581, 0.00058150291 -0.15267226 -0.058008522, -0.0029660612 -0.15768591 -0.045008823, -0.0085998476 -0.15747917 -0.045008942, -0.0072322488 -0.15868708 -0.041430086, 0.0026268065 -0.15504855 -0.052290857, 0.0044808388 -0.15637738 -0.048668742, -0.0029994249 -0.15945971 -0.039273143, 0.0004325062 -0.16136217 -0.032009006, -0.0036019981 -0.16132259 -0.032009214, -0.0058487207 -0.15978685 -0.037826464, 0.0026715547 -0.15769121 -0.045008838, 0.0030898303 -0.15768349 -0.045009002, 0.0027016848 -0.15946499 -0.039273202, 0.0063067973 -0.16313198 -0.022253677, 0.0044839084 -0.16216159 -0.028009221, 0.008547619 -0.16199839 -0.028009191, 0.0072553903 -0.16472954 -0.0056272745, 0.0045398027 -0.16492361 -0.0020092875, 0.0058003813 -0.16459852 -0.0092402399, 0.0087065101 -0.16475597 -0.0020093173, -0.0030642748 -0.16322508 -0.022253588, -0.006595701 -0.16334102 -0.020811319, -0.0051220953 -0.1628145 -0.024417788, -0.0036490262 -0.16218248 -0.028009176, 0.00041773915 -0.1622231 -0.02800937, -0.003082335 -0.16417953 -0.015009329, -0.0089538991 -0.16396412 -0.015009254, -0.007531777 -0.16437125 -0.011403486, 0.0027772784 -0.16323024 -0.022253543, 0.004891336 -0.16370445 -0.018638447, -0.00309138 -0.16467169 -0.0092400759, 0.00037020445 -0.1649856 -0.0020095706, -0.0037994832 -0.16494212 -0.0020093322, -0.006102249 -0.16467413 -0.0077934861, 0.002793476 -0.16418466 -0.015009344, 0.0034643114 -0.16417196 -0.01500915, 0.0028017461 -0.16467685 -0.0092400908, 0.0063828975 -0.16466445 0.0077771544, 0.0045397133 -0.16492376 0.0019906908, 0.008706525 -0.16475636 0.0019907355, 0.0071505755 -0.16274118 0.024397776, 0.004483968 -0.16216469 0.027990788, 0.0057421178 -0.16337594 0.020790756, 0.0085475445 -0.16200134 0.027990893, -0.0030930489 -0.16475898 0.0077771246, -0.0066748857 -0.16456658 0.0092194676, -0.0052409172 -0.16480649 0.0056071281, -0.0037995279 -0.16494238 0.001990512, 0.00037015975 -0.16498581 0.0019907951, -0.0030821711 -0.16418126 0.014990628, -0.0089538544 -0.16396597 0.014990687, -0.0074798018 -0.16360849 0.018621624, 0.0028032511 -0.16476411 0.0077773631, 0.0049254298 -0.16447106 0.011386693, -0.0030684173 -0.16344792 0.020790771, 0.00041770935 -0.1622262 0.027990788, -0.0036489666 -0.16218564 0.027990833, -0.0060062855 -0.16314554 0.022237211, 0.0027934313 -0.16418627 0.014990464, 0.0034643114 -0.16417366 0.014990613, 0.0027810335 -0.16345319 0.020790875, -0.0033054799 -0.14544842 0.072016358, -0.0067441314 -0.14532959 0.072016329, -0.00491184 -0.14817548 0.067054525, 0.0057186931 -0.14814579 0.067056224, 0.0042531639 -0.1507653 0.061991513, 0.0078905225 -0.15061873 0.061991453, -0.0019966513 -0.14824346 0.06705448, -0.0030267984 -0.15079486 0.061991528, 0.0006133616 -0.15082404 0.061991587, 0.00013485551 -0.14548585 0.072016314, 0.0028812438 -0.14822882 0.06705448, 0.0035752207 -0.14544207 0.072016299, 0.0060875565 -0.15978161 0.037810758, 0.0044665486 -0.16130447 0.031990856, 0.0084979236 -0.16114235 0.031990871, 0.0042906553 -0.15261951 0.057991371, 0.00530532 -0.1555464 0.050828889, 0.0066619813 -0.15406358 0.05442895, 0.0079973787 -0.15247026 0.057991371, -0.0030069202 -0.15986934 0.037810847, -0.0064039081 -0.15936437 0.039252862, -0.0050108582 -0.16039902 0.035634443, -0.0036019236 -0.16132608 0.03199093, 0.0004324615 -0.16136578 0.031990722, -0.0029660165 -0.15769085 0.044991061, -0.0070675761 -0.15628657 0.048652902, -0.008599937 -0.15748414 0.044991285, 0.0027083606 -0.1598745 0.037810624, 0.0045866817 -0.15878969 0.041414082, -0.0029268861 -0.15560925 0.050828815, 0.00058153272 -0.15267867 0.057991609, -0.0031280518 -0.15264779 0.057991356, -0.0055446774 -0.15497687 0.052275717, 0.0026715696 -0.15769616 0.044991001, 0.0030899197 -0.15768853 0.044991046, 0.0026361346 -0.15561429 0.050828815, 0.014407307 -0.16377351 -0.01300922, 0.011726037 -0.16427207 -0.0094035566, 0.010270536 -0.1640847 -0.013009384, 0.014407128 -0.16377479 0.012990803, 0.010270536 -0.16408622 0.012990788, 0.012597352 -0.16433519 0.0072194487, 0.016173631 -0.16402087 -0.0072401166, 0.015489876 -0.16427141 -9.2238188e-06, 0.013177037 -0.16435501 -0.0057936013, 0.018534735 -0.1633577 -0.013009354, 0.016191676 -0.16420385 -9.2238188e-06, 0.0140457 -0.16435561 0.0036070794, 0.022030428 -0.16333738 -0.0072401166, 0.022650406 -0.16283804 -0.01300931, 0.02500388 -0.16290879 -0.0072400123, 0.016180113 -0.16408733 0.0057772547, 0.01853472 -0.16335911 0.012990609, 0.022054851 -0.16351953 -9.2685223e-06, 0.026454642 -0.16281903 -0.0036273301, 0.027889848 -0.16262594 -9.1642141e-06, 0.025586069 -0.16288573 0.00577721, 0.022039086 -0.16340348 0.0057772696, 0.024125934 -0.16291422 0.0093867928, 0.02265051 -0.16283959 0.012990952, 0.013197973 -0.16319749 0.018990934, 0.011667475 -0.16308472 0.020621657, 0.010246158 -0.16366416 0.016990855, 0.014367044 -0.16335395 0.016990885, 0.015867516 -0.16295946 0.018990859, 0.013076633 -0.16240025 0.024237499, 0.018478811 -0.16293991 0.016990766, 0.018532693 -0.16267791 0.018990844, 0.015341967 -0.16215819 0.024487898, 0.021193117 -0.16235268 0.018990844, 0.02257894 -0.16242269 0.016990766, 0.01530616 -0.16108599 0.029990718, 0.015169337 -0.15979469 0.035495207, 0.012309298 -0.15957576 0.037252754, 0.013805851 -0.16038486 0.033634052, 0.02473703 -0.1612815 0.022790939, 0.023236617 -0.16121277 0.024508297, 0.012888968 -0.15845999 0.040991023, 0.0099224597 -0.15805617 0.042990848, 0.013833821 -0.15776196 0.042991072, 0.015393212 -0.15823621 0.040991068, 0.026055619 -0.16043416 0.026397794, 0.025225192 -0.15983325 0.029990897, 0.017736569 -0.15737075 0.042991042, 0.017893791 -0.15797305 0.040991023, 0.027350649 -0.15948331 0.029990926, 0.020389721 -0.1576702 0.040991038, 0.024820209 -0.15850025 0.035810396, 0.022817135 -0.15887666 0.035520092, 0.023228392 -0.15774572 0.039413646, 0.021628693 -0.15688339 0.042991132, 0.015880793 -0.16104001 0.029946461, 0.017454386 -0.16087705 0.029946446, 0.021250859 -0.15755659 0.040991038, 0.013707548 -0.15643817 0.046991378, 0.011230499 -0.15529785 0.050653681, 0.009845823 -0.15672857 0.046991184, 0.012999833 -0.14490396 0.072016373, 0.0095695108 -0.14517084 0.072016388, 0.011842459 -0.14794901 0.066743582, 0.015219271 -0.1541065 0.052829668, 0.014727101 -0.15105519 0.059991464, 0.012593299 -0.15375561 0.054276511, 0.017561167 -0.15605262 0.046991289, 0.014916107 -0.15103656 0.059991404, 0.013278723 -0.14955285 0.063389748, 0.02071023 -0.15346515 0.052829653, 0.021403804 -0.15557206 0.046991229, 0.023346767 -0.15308622 0.052829668, 0.014655501 -0.14839739 0.065409422, 0.016422853 -0.14455605 0.072016299, 0.020297572 -0.15040794 0.059991509, 0.024517044 -0.15139133 0.056429744, 0.025653094 -0.14958751 0.059991568, 0.023066416 -0.14732456 0.065409422, 0.019942865 -0.1477797 0.065409273, 0.021451026 -0.14577717 0.068735972, 0.019836754 -0.14412728 0.072016433, 0.012888893 -0.15845546 -0.041008964, 0.011413068 -0.15903381 -0.039429918, 0.0099223703 -0.15805128 -0.043008909, 0.013833806 -0.15775719 -0.043008894, 0.015393212 -0.15823182 -0.041009083, 0.012907431 -0.15990824 -0.035826296, 0.017736614 -0.15736604 -0.043008938, 0.017893732 -0.15796855 -0.041009113, 0.015169248 -0.15979064 -0.035513222, 0.02038987 -0.15766573 -0.041008919, 0.021628663 -0.15687859 -0.043008834, 0.015305951 -0.16108268 -0.030009165, 0.015341833 -0.16215545 -0.024506271, 0.012514576 -0.16268408 -0.022811502, 0.013916194 -0.16193596 -0.026417911, 0.024184495 -0.15820724 -0.037272751, 0.022817135 -0.15887266 -0.03553775, 0.013197839 -0.1631951 -0.019009203, 0.010246038 -0.16366214 -0.017009214, 0.014367178 -0.16335207 -0.017009273, 0.015867516 -0.16295725 -0.019009262, 0.025771499 -0.15889758 -0.033654034, 0.025225207 -0.15982997 -0.030009121, 0.018478736 -0.16293803 -0.017009124, 0.018532783 -0.16267574 -0.019009262, 0.027350664 -0.15947995 -0.030009091, 0.021192998 -0.16235057 -0.019009158, 0.025267214 -0.16095227 -0.024253666, 0.023236677 -0.16121006 -0.024526566, 0.023934796 -0.16173813 -0.020638391, 0.02257897 -0.16242081 -0.017009214, 0.015879959 -0.16102713 -0.030009106, 0.01745446 -0.16087374 -0.029964238, 0.021885499 -0.16225871 -0.019008994, 0.08809872 -0.11577797 0.072017968, 0.085336164 -0.11782905 0.072017938, 0.088543206 -0.11891168 0.067056417, 0.096835837 -0.11226031 0.067058101, 0.097323671 -0.11522204 0.061993405, 0.10007609 -0.11283955 0.061993599, 0.090864629 -0.11714706 0.067056239, 0.091650456 -0.11978415 0.061993256, 0.094514623 -0.11753732 0.061993286, 0.090811849 -0.11366215 0.072018087, 0.094669402 -0.1140945 0.067056388, 0.093474239 -0.11148292 0.072018325, 0.10438031 -0.12112722 0.037813053, 0.10406262 -0.12332836 0.031993017, 0.10711345 -0.12068823 0.031993285, 0.098509222 -0.1166482 0.057993367, 0.10112762 -0.11830398 0.050830901, 0.10126367 -0.11629882 0.054430947, 0.10131407 -0.11422026 0.057993665, 0.097324431 -0.12686604 0.037812501, 0.094353795 -0.12858933 0.039254621, 0.096088156 -0.12852979 0.035636261, 0.09776786 -0.12837601 0.031992733, 0.10094677 -0.1258916 0.031992897, 0.095998019 -0.12513754 0.044992998, 0.091915682 -0.12659696 0.048654705, 0.09146449 -0.12848857 0.044992805, 0.10179627 -0.12330669 0.037812769, 0.10258827 -0.12128758 0.041416094, 0.094730571 -0.12348565 0.050830707, 0.095646322 -0.11900717 0.057993397, 0.092726767 -0.12129584 0.057993218, 0.092289522 -0.12462351 0.052277505, 0.10040908 -0.12162656 0.044993177, 0.10073134 -0.12135983 0.044993088, 0.099083155 -0.12002108 0.050830826, 0.10765654 -0.12476033 0.0077793151, 0.10637759 -0.1261121 0.0019928962, 0.10953081 -0.12338316 0.0019929856, 0.10705709 -0.12277824 0.024399981, 0.10461274 -0.12398997 0.027992904, 0.10635173 -0.12415263 0.020793021, 0.10768786 -0.12132877 0.027993143, 0.10030687 -0.13074228 0.0077791959, 0.097386628 -0.13282514 0.0092212558, 0.098657593 -0.1321187 0.005608961, 0.099869207 -0.13132617 0.0019924343, 0.10315634 -0.12876025 0.0019925088, 0.099954963 -0.13028392 0.014992476, 0.096159577 -0.13257813 0.018623158, 0.095229939 -0.13377655 0.014992476, 0.10492015 -0.12706998 0.0077792853, 0.1063965 -0.12551779 0.011388958, 0.099508345 -0.12970221 0.020792753, 0.10147175 -0.12657338 0.027992681, 0.098267317 -0.12907735 0.027992636, 0.097022846 -0.13129729 0.022239119, 0.10455191 -0.12662449 0.014992803, 0.10506842 -0.12619641 0.014992833, 0.10408477 -0.12605903 0.020792902, 0.1066428 -0.1236093 -0.022251457, 0.10461284 -0.12398699 -0.02800715, 0.10768783 -0.12132576 -0.028006718, 0.10837977 -0.12426695 -0.0056251138, 0.10637747 -0.12611172 -0.0020071268, 0.10716067 -0.12507173 -0.00923796, 0.10953072 -0.1233829 -0.002007097, 0.099374175 -0.12952483 -0.022251815, 0.096685529 -0.13181728 -0.020809487, 0.097509295 -0.13048673 -0.024416015, 0.098267168 -0.12907404 -0.028007329, 0.10147187 -0.12657034 -0.028007135, 0.099954948 -0.13028225 -0.015007377, 0.09659566 -0.13320652 -0.011401609, 0.095229998 -0.13377494 -0.015007481, 0.10394441 -0.12588671 -0.022251591, 0.10589288 -0.12493929 -0.018636212, 0.10025437 -0.1306729 -0.0092382729, 0.10315636 -0.12876001 -0.0020073503, 0.099869296 -0.13132608 -0.002007544, 0.097902015 -0.13255194 -0.0077917874, 0.10455196 -0.12662274 -0.015007183, 0.10506839 -0.1261946 -0.015007094, 0.10486509 -0.12700251 -0.0092381686, 0.10119221 -0.11750466 -0.0522888, 0.098509252 -0.11664182 -0.05800657, 0.10131407 -0.11421388 -0.058006287, 0.10542461 -0.12098485 -0.035651967, 0.10406259 -0.12332487 -0.032006904, 0.10367119 -0.12119752 -0.039271146, 0.10711341 -0.12068465 -0.03200677, 0.094389766 -0.12303549 -0.052288935, 0.092149124 -0.12541699 -0.050847128, 0.092476621 -0.12339407 -0.054446518, 0.092726707 -0.12128934 -0.058006972, 0.095646203 -0.1190007 -0.058006853, 0.095998123 -0.12513256 -0.045007139, 0.093286797 -0.12857518 -0.041428342, 0.091464475 -0.1284835 -0.045007199, 0.09872669 -0.11958331 -0.05228889, 0.10100465 -0.1194663 -0.048666522, 0.097077608 -0.12654012 -0.039271191, 0.10094683 -0.12588799 -0.032007039, 0.097767919 -0.1283724 -0.032007381, 0.09505415 -0.12857249 -0.03782472, 0.10040912 -0.12162167 -0.045006856, 0.10073145 -0.12135491 -0.045006812, 0.10153839 -0.12298992 -0.039271206, 0.10825296 -0.11376232 0.046993554, 0.10560535 -0.11441541 0.050655857, 0.10541472 -0.11639723 0.046993434, 0.10050716 -0.10518605 0.072018638, 0.09799166 -0.10753348 0.072018564, 0.10150115 -0.10828829 0.066745698, 0.10798095 -0.1109969 0.052832097, 0.10569324 -0.10891834 0.059993908, 0.10570872 -0.11236 0.05427897, 0.11102524 -0.11105826 0.046993777, 0.10582954 -0.10878593 0.059993818, 0.10362427 -0.10864681 0.063392162, 0.11187394 -0.10707191 0.052832291, 0.11372995 -0.10828674 0.046993867, 0.1136992 -0.10513189 0.052832529, 0.10398003 -0.10688496 0.065411627, 0.10296649 -0.10277975 0.072018832, 0.10964495 -0.10493907 0.059993878, 0.11355717 -0.10307702 0.056432322, 0.11332071 -0.10095853 0.059994251, 0.10988702 -0.10080212 0.065412179, 0.10772878 -0.10310543 0.065411896, 0.1076591 -0.10059959 0.06873861, 0.10536811 -0.10031614 0.072018832, 0.10887364 -0.11584878 -0.04100664, 0.1080804 -0.11722118 -0.039427564, 0.10630241 -0.11738241 -0.043006584, 0.10917717 -0.11471385 -0.043006539, 0.1106922 -0.11411247 -0.041006505, 0.10979387 -0.11697325 -0.035823777, 0.11198469 -0.11197463 -0.043006361, 0.11248308 -0.11234769 -0.041006401, 0.11148885 -0.11547101 -0.035510749, 0.11424588 -0.11055472 -0.041006312, 0.11472364 -0.10916689 -0.043006077, 0.11240113 -0.11639604 -0.030006483, 0.11309783 -0.11721247 -0.024503633, 0.1112168 -0.11938852 -0.02280888, 0.1118466 -0.11792976 -0.026415437, 0.11754994 -0.10861212 -0.037269995, 0.1168959 -0.1099849 -0.035535231, 0.11206985 -0.11936221 -0.019006789, 0.11005294 -0.12156764 -0.017006874, 0.11308138 -0.11875582 -0.01700668, 0.11400856 -0.11751181 -0.01900661, 0.11922102 -0.10816243 -0.033651248, 0.11937504 -0.10923204 -0.03000626, 0.11603811 -0.11586857 -0.017006516, 0.11591688 -0.11562994 -0.01900661, 0.12081857 -0.10763326 -0.03000623, 0.11779407 -0.1137169 -0.019006297, 0.12010752 -0.1100834 -0.024250627, 0.11868075 -0.11155105 -0.02452369, 0.11955573 -0.11152872 -0.020635575, 0.11892112 -0.1129078 -0.017006457, 0.11281511 -0.11599475 -0.030006588, 0.11395054 -0.1148932 -0.029961735, 0.11827815 -0.11321324 -0.019006371, 0.1120698 -0.11936429 0.018993303, 0.11080278 -0.12023044 0.020624191, 0.11005308 -0.1215696 0.01699324, 0.11308144 -0.11875784 0.016993299, 0.1140085 -0.1175139 0.018993303, 0.11147779 -0.11881685 0.024240002, 0.11603814 -0.11587045 0.016993538, 0.11591682 -0.11563191 0.018993437, 0.11309776 -0.11721513 0.024490505, 0.11779398 -0.11371908 0.01899375, 0.11892113 -0.11290959 0.016993552, 0.11240116 -0.11639944 0.02999334, 0.11148879 -0.11547506 0.035497621, 0.10911638 -0.11708716 0.037255123, 0.11079098 -0.11678666 0.033636615, 0.11989681 -0.110672 0.02279377, 0.11868085 -0.11155382 0.024511144, 0.10887356 -0.11585331 0.040993273, 0.10630248 -0.11738726 0.042993426, 0.10917717 -0.11471865 0.042993426, 0.1106921 -0.11411706 0.040993631, 0.12039916 -0.10918751 0.02640076, 0.11937508 -0.10923553 0.029993862, 0.1119847 -0.11197937 0.042993769, 0.11248316 -0.11235222 0.040993527, 0.1208186 -0.10763663 0.029993877, 0.11424571 -0.11055917 0.040993661, 0.11822735 -0.10844585 0.035813421, 0.11689585 -0.1099889 0.03552264, 0.11651206 -0.10884827 0.039416596, 0.11472362 -0.10917169 0.042993754, 0.11282182 -0.11600503 0.02994889, 0.11395049 -0.11489651 0.029948875, 0.11484815 -0.10993341 0.040993676, 0.11337537 -0.11906025 -0.013006777, 0.11159003 -0.12112191 -0.0094010234, 0.11033539 -0.12188283 -0.01300697, 0.11337538 -0.11906168 0.012993202, 0.11033539 -0.12188426 0.012993008, 0.11230987 -0.12062818 0.0072217733, 0.11491051 -0.11815253 -0.0072375089, 0.11453205 -0.11877483 -6.750226e-06, 0.11277615 -0.12028205 -0.0057911277, 0.11634332 -0.11616188 -0.013006613, 0.11503841 -0.11828434 -6.7353249e-06, 0.11345525 -0.11974099 0.0036095679, 0.11906335 -0.11396655 -0.0072372258, 0.11923699 -0.11318943 -0.013006389, 0.12112097 -0.11177745 -0.0072371811, 0.11495651 -0.11820051 0.0057796836, 0.11634326 -0.11616337 0.01299341, 0.11919585 -0.11409369 -6.5267086e-06, 0.1232008 -0.10975707 -6.3031912e-06, 0.1215613 -0.1113967 0.0057801157, 0.12219906 -0.1108028 -0.0036244094, 0.11911109 -0.11401287 0.0057799816, 0.12043735 -0.11232924 0.0093896985, 0.11923712 -0.11319092 0.01299347, 0.07481049 -0.14131722 0.037811697, 0.07401073 -0.14339244 0.031991839, 0.077572614 -0.14149734 0.031992167, 0.070083573 -0.13564408 0.057992458, 0.072267517 -0.13784075 0.050829962, 0.072846606 -0.13591638 0.054429978, 0.073358372 -0.13390127 0.057992458, 0.066654488 -0.14534217 0.037811637, 0.063374892 -0.14636114 0.039253578, 0.065079063 -0.14668888 0.035635173, 0.066750646 -0.14691278 0.03199169, 0.070402727 -0.14519814 0.031991661, 0.065746114 -0.14336184 0.044991925, 0.060580447 -0.14561984 0.044991806, 0.061441347 -0.14387619 0.048653707, 0.071806192 -0.142867 0.037811756, 0.073027611 -0.14107475 0.041415051, 0.064878002 -0.14146921 0.05082956, 0.066767439 -0.1373069 0.05799222, 0.063411787 -0.13888851 0.05799222, 0.062244967 -0.14203542 0.052276462, 0.070827678 -0.14092037 0.044992089, 0.07120122 -0.14073199 0.044992164, 0.069892362 -0.13906005 0.050829649, 0.077195689 -0.14558819 0.0077782571, 0.07564795 -0.14662141 0.0019916147, 0.079329237 -0.14466262 0.0019917637, 0.077052489 -0.14352229 0.024399012, 0.074399918 -0.14416009 0.027991951, 0.076059043 -0.14470533 0.020791858, 0.077990115 -0.1422497 0.027991921, 0.068699181 -0.14978462 0.007778123, 0.06538868 -0.15116563 0.0092203468, 0.066784859 -0.15075949 0.0056079775, 0.068142548 -0.15025669 0.0019915253, 0.071918175 -0.14848644 0.001991421, 0.068458259 -0.14925942 0.014991477, 0.06424737 -0.1506516 0.018622339, 0.06307438 -0.15161312 0.014991522, 0.074013844 -0.14723101 0.0077781081, 0.07579875 -0.14604622 0.011387795, 0.068152249 -0.14859301 0.02079162, 0.070762873 -0.1459797 0.027991608, 0.067081392 -0.14770755 0.027991474, 0.065374225 -0.14959526 0.022238091, 0.073754251 -0.14671484 0.014991716, 0.074353039 -0.14641234 0.014991716, 0.073424727 -0.1460596 0.020791918, 0.060127765 -0.13247916 0.072017059, 0.056978151 -0.13386396 0.072017029, 0.059863791 -0.13563302 0.067055419, 0.069428667 -0.13099387 0.067057222, 0.069245145 -0.13398984 0.061992377, 0.072458565 -0.1322796 0.061992511, 0.062519819 -0.13442948 0.067055434, 0.062699035 -0.13717532 0.061992183, 0.065991238 -0.13562199 0.061992288, 0.063243702 -0.13102019 0.072017178, 0.066908225 -0.1322999 0.067055434, 0.066324323 -0.12948778 0.072017133, 0.072507247 -0.13707593 -0.052290007, 0.070083439 -0.13563755 -0.058007672, 0.073358417 -0.13389492 -0.058007553, 0.075859338 -0.14141071 -0.035653204, 0.074010849 -0.14338896 -0.032007933, 0.074102476 -0.14122784 -0.039272144, 0.077572554 -0.14149377 -0.032007948, 0.06464459 -0.14095441 -0.052290037, 0.061930314 -0.14277765 -0.050847918, 0.062699601 -0.14087832 -0.054447219, 0.063411757 -0.13888204 -0.058007956, 0.066767395 -0.13730034 -0.058007792, 0.065746099 -0.1433568 -0.045008168, 0.060580552 -0.14561495 -0.045008406, 0.062336698 -0.14610979 -0.041429505, 0.069640964 -0.13855386 -0.052289963, 0.071887851 -0.13894665 -0.048667714, 0.06648542 -0.14496937 -0.039272189, 0.070402801 -0.14519453 -0.032008186, 0.066750661 -0.14690921 -0.032008275, 0.064060345 -0.14650044 -0.037825659, 0.070827752 -0.14091545 -0.045008108, 0.071201324 -0.14072704 -0.045008034, 0.071624279 -0.14250061 -0.039272234, 0.076463044 -0.14424035 -0.022252515, 0.074399859 -0.14415681 -0.028008312, 0.077990159 -0.14224657 -0.028008044, 0.07801044 -0.14526814 -0.0056262165, 0.07564792 -0.14662114 -0.0020082146, 0.076642737 -0.14578146 -0.0092390478, 0.079329327 -0.14466244 -0.0020082146, 0.068060413 -0.14839023 -0.022252873, 0.064929068 -0.15002692 -0.020810783, 0.066028267 -0.14891309 -0.024417073, 0.067081466 -0.14770445 -0.02800858, 0.070762873 -0.14597648 -0.028008327, 0.068458214 -0.14925793 -0.015008524, 0.064532444 -0.15136114 -0.011402771, 0.063074529 -0.15161151 -0.015008554, 0.073325619 -0.14586028 -0.022252589, 0.075435996 -0.14537007 -0.018637389, 0.068663105 -0.14970529 -0.0092392266, 0.071918309 -0.14848623 -0.0020084232, 0.068142459 -0.1502564 -0.0020084679, 0.065951839 -0.15101406 -0.0077927113, 0.073754266 -0.14671314 -0.01500839, 0.074353039 -0.14641064 -0.015008211, 0.073975146 -0.14715293 -0.0092391968, 0.080224961 -0.13499871 0.046992287, 0.077498406 -0.13504621 0.050654665, 0.076871425 -0.1369358 0.046992332, 0.074582264 -0.12491414 0.07201758, 0.071607456 -0.12664273 0.072017238, 0.074860767 -0.12815958 0.066744506, 0.080575213 -0.13224193 0.052830905, 0.078807443 -0.12970656 0.059992775, 0.078056663 -0.13306531 0.054277733, 0.083529457 -0.13297927 0.04699254, 0.078969762 -0.12960777 0.059992641, 0.076850742 -0.1289815 0.063390955, 0.085243881 -0.12928167 0.052831113, 0.086783186 -0.13087913 0.046992794, 0.087455064 -0.12779638 0.052831218, 0.077589765 -0.12734306 0.065410495, 0.077515274 -0.12311533 0.07201767, 0.083545506 -0.12670633 0.05999276, 0.087773904 -0.12576172 0.056431174, 0.088014856 -0.12364358 0.059992895, 0.084702164 -0.12272713 0.065410793, 0.08208552 -0.12449238 0.065410659, 0.082575232 -0.12203377 0.068737283, 0.080404967 -0.12124786 0.072017744, 0.082699135 -0.14130947 0.018992186, 0.081271321 -0.14187202 0.020622984, 0.080242261 -0.14301074 0.016991928, 0.083820358 -0.14094332 0.016992077, 0.085001126 -0.13993689 0.018992156, 0.08224386 -0.14064395 0.02423881, 0.087345317 -0.13878626 0.016992345, 0.087280378 -0.13852683 0.018992111, 0.084179714 -0.1394431 0.024489403, 0.08953619 -0.13707966 0.018992364, 0.090814874 -0.13654116 0.016992316, 0.083681941 -0.13849261 0.029992208, 0.08299844 -0.13738859 0.035496593, 0.080326736 -0.13843223 0.037253946, 0.082026199 -0.13851196 0.033635423, 0.092264205 -0.13457671 0.022792488, 0.09088254 -0.1351659 0.024509728, 0.08036463 -0.13717535 0.040992185, 0.07751669 -0.13809875 0.042992055, 0.080913082 -0.13613647 0.042992264, 0.082524031 -0.13588732 0.040992305, 0.093084276 -0.13324115 0.026399463, 0.092075244 -0.13306013 0.029992431, 0.084259793 -0.13409084 0.042992339, 0.084662661 -0.13456523 0.040992677, 0.093838573 -0.13182271 0.029992446, 0.086780235 -0.1332095 0.040992469, 0.091131911 -0.1320349 0.035812125, 0.089490756 -0.1332432 0.035521477, 0.0893704 -0.13204569 0.039415181, 0.087554842 -0.13196298 0.042992577, 0.084180057 -0.13820174 0.029947475, 0.085527003 -0.13737223 0.029947475, 0.087506831 -0.13273346 0.040992483, 0.084039301 -0.14130366 -0.013008118, 0.081840008 -0.14291626 -0.0094023496, 0.080447391 -0.14337891 -0.013008267, 0.084039286 -0.14130512 0.012991846, 0.080447495 -0.14338043 0.012991786, 0.082651868 -0.14259508 0.0072205663, 0.085737988 -0.14076015 -0.0072387308, 0.085230634 -0.14128268 -8.0615282e-06, 0.083183452 -0.14236149 -0.0057924688, 0.08757779 -0.13913825 -0.013007969, 0.085833415 -0.14091724 -7.8380108e-06, 0.083965912 -0.141985 0.0036083013, 0.09071818 -0.13760331 -0.0072385371, 0.09106043 -0.13688436 -0.013007864, 0.093211338 -0.13592693 -0.007238552, 0.085772321 -0.14081728 0.0057787001, 0.08757773 -0.13913974 0.012992084, 0.09081912 -0.13775679 -7.8529119e-06, 0.095688641 -0.13441995 -7.7039003e-06, 0.093725577 -0.1356537 0.0057789236, 0.094479337 -0.13521656 -0.0036256462, 0.090754554 -0.13765907 0.0057787299, 0.092422292 -0.13631281 0.009388268, 0.091060445 -0.13688582 0.012992114, 0.080364689 -0.13717091 -0.041007742, 0.079286039 -0.13833228 -0.039428741, 0.077516764 -0.13809401 -0.043007731, 0.080913052 -0.13613182 -0.043007746, 0.082524002 -0.13588268 -0.041007847, 0.081011742 -0.13847184 -0.035825059, 0.084259734 -0.13408604 -0.043007642, 0.084662676 -0.13456064 -0.041007668, 0.082998425 -0.13738453 -0.035512075, 0.08678019 -0.13320485 -0.041007563, 0.087554857 -0.13195822 -0.043007657, 0.083681956 -0.13848922 -0.030007929, 0.084179819 -0.13944021 -0.024504915, 0.08186157 -0.14114323 -0.022810042, 0.082800165 -0.13986108 -0.026416749, 0.090433896 -0.13204637 -0.037271351, 0.089490682 -0.13323924 -0.035536453, 0.082699046 -0.14130729 -0.019007966, 0.080242172 -0.14300883 -0.017008111, 0.083820343 -0.14094141 -0.017007858, 0.085001096 -0.13993475 -0.019007817, 0.092163131 -0.13197967 -0.033652365, 0.092075378 -0.13305691 -0.030007601, 0.087345421 -0.13878432 -0.017007843, 0.087280288 -0.13852456 -0.019007728, 0.093838423 -0.13181931 -0.030007526, 0.089536056 -0.13707736 -0.019007668, 0.092600033 -0.13404968 -0.024252057, 0.090882495 -0.1351631 -0.024524868, 0.091740549 -0.13533601 -0.020636857, 0.090815052 -0.13653937 -0.017007768, 0.084175035 -0.13819024 -0.030007809, 0.085527107 -0.1373688 -0.029962972, 0.090120107 -0.13669413 -0.019007802, -0.022694305 -0.15735069 -0.041008964, -0.024261788 -0.15758625 -0.039429814, -0.025496513 -0.15629658 -0.043008804, -0.021617815 -0.15688005 -0.043008894, -0.020203114 -0.15768975 -0.041008964, -0.02299948 -0.15877131 -0.035826057, -0.017725781 -0.15736732 -0.043008879, -0.017706662 -0.15798968 -0.041009009, -0.020768225 -0.15915987 -0.035513029, -0.015205801 -0.1582498 -0.041008875, -0.013822928 -0.15775812 -0.043008834, -0.020922422 -0.16044986 -0.030009106, -0.021126062 -0.16150373 -0.024506181, -0.024000242 -0.16138986 -0.022811189, -0.022467092 -0.16097268 -0.026417688, -0.011626765 -0.15962204 -0.037272871, -0.013107777 -0.1599668 -0.035537764, -0.023447633 -0.16204023 -0.019009247, -0.026429251 -0.16183877 -0.017009035, -0.022342563 -0.16245338 -0.017009214, -0.020792142 -0.16240245 -0.019008994, -0.010233104 -0.16064826 -0.033653781, -0.0109732 -0.16143572 -0.030009106, -0.018241808 -0.16296479 -0.017009154, -0.018130839 -0.1627211 -0.019009337, -0.008823052 -0.16156757 -0.030009195, -0.015464857 -0.16299596 -0.019009158, -0.011181772 -0.16253933 -0.024253651, -0.01321882 -0.16233885 -0.024526492, -0.012655601 -0.16300905 -0.020638406, -0.014129445 -0.16337273 -0.017009214, -0.020350531 -0.16052341 -0.030009061, -0.018781319 -0.16072434 -0.029964179, -0.014769271 -0.16306064 -0.019009292, -0.023447692 -0.16204241 0.01899083, -0.024914488 -0.16159222 0.020621762, -0.026429072 -0.16184074 0.016991034, -0.022342548 -0.16245523 0.016990796, -0.020791918 -0.16240466 0.018990859, -0.023388311 -0.1612384 0.024237409, -0.018241793 -0.16296667 0.016990691, -0.018130958 -0.16272312 0.01899077, -0.021126077 -0.16150644 0.024488136, -0.015464976 -0.16299808 0.018990889, -0.014129475 -0.16337463 0.01699087, -0.020922363 -0.16045323 0.029990941, -0.02076833 -0.15916377 0.0354954, -0.023507684 -0.15831405 0.037252754, -0.022228852 -0.15943593 0.033634096, -0.011771411 -0.16274244 0.022790939, -0.013218924 -0.16234148 0.024508312, -0.022694498 -0.15735504 0.040991217, -0.025496617 -0.15630138 0.042991236, -0.021617815 -0.15688482 0.042991117, -0.020202979 -0.15769437 0.040991068, -0.010297373 -0.16220951 0.026397854, -0.0109732 -0.16143903 0.029990688, -0.01772584 -0.15737215 0.042991072, -0.017706677 -0.15799415 0.040991232, -0.0088230669 -0.16157091 0.029990748, -0.015205875 -0.15825441 0.040990978, -0.01107119 -0.16004935 0.035810411, -0.013107911 -0.15997061 0.035520047, -0.01245515 -0.15895948 0.03941375, -0.013822868 -0.15776291 0.042991042, -0.020351633 -0.16053629 0.029946178, -0.018781453 -0.1607275 0.029946387, -0.014340967 -0.15833506 0.040991083, -0.02239722 -0.16287312 -0.01300928, -0.025121957 -0.1627627 -0.0094034523, -0.02649948 -0.16225615 -0.013009131, -0.022397056 -0.16287458 0.012990624, -0.026499376 -0.16225758 0.012990907, -0.024286494 -0.16301802 0.0072194636, -0.020730093 -0.16350743 -0.0072401166, -0.021452323 -0.16359964 -9.3579292e-06, -0.023725793 -0.16316652 -0.0057935119, -0.018280804 -0.16338626 -0.01300931, -0.02075316 -0.16368985 -9.3728304e-06, -0.022878766 -0.1633603 0.0036071241, -0.014868081 -0.16414434 -0.0072401017, -0.014152586 -0.16379556 -0.01300931, -0.011873767 -0.16438821 -0.0072401166, -0.020738319 -0.16357368 0.0057772994, -0.01828067 -0.16338766 0.012990654, -0.014884636 -0.16432741 -9.3281269e-06, -0.0089971125 -0.16475478 -9.2685223e-06, -0.011300877 -0.16449535 0.0057772696, -0.010439336 -0.16462338 -0.003627345, -0.014874026 -0.16421092 0.0057772547, -0.012730598 -0.16419825 0.009386763, -0.014152482 -0.16379708 0.012990743, -0.021446213 -0.15556619 0.046991393, -0.023607358 -0.15390348 0.050653681, -0.025275931 -0.15498999 0.046991214, -0.019569278 -0.14416385 0.072016463, -0.022973016 -0.14366066 0.072016582, -0.021375343 -0.14687485 0.066743627, -0.01945363 -0.15362957 0.052829772, -0.019254386 -0.15054503 0.059991524, -0.021935731 -0.1527029 0.054276645, -0.017603606 -0.15604776 0.046991184, -0.019065931 -0.15056908 0.059991539, -0.020332053 -0.14875823 0.063389719, -0.013957456 -0.15422598 0.052829698, -0.013750315 -0.15643439 0.046991199, -0.011302814 -0.15444332 0.052829757, -0.018732756 -0.14793807 0.065409377, -0.016154766 -0.14458621 0.072016403, -0.013679475 -0.15115365 0.059991494, -0.0097847581 -0.15305126 0.056429505, -0.008275494 -0.15154558 0.059991628, -0.01029399 -0.14876354 0.065409407, -0.013440341 -0.1485123 0.065409318, -0.011524513 -0.14689559 0.068736136, -0.012731075 -0.14492795 0.072016299, -0.035587028 -0.14106625 0.072016582, -0.038912892 -0.1401853 0.072016612, -0.037760109 -0.14336747 0.067054793, -0.027389377 -0.14570412 0.067056209, -0.029401302 -0.14793178 0.061991677, -0.025822401 -0.14859825 0.061991528, -0.03493312 -0.14408249 0.067054659, -0.036505133 -0.14634079 0.061991856, -0.032962754 -0.1471791 0.061991543, -0.032241181 -0.14186844 0.072016627, -0.030174285 -0.14515367 0.067054719, -0.028877363 -0.14259121 0.072016329, -0.029619306 -0.1571303 0.037811056, -0.031538695 -0.15825412 0.031991094, -0.027572304 -0.15899321 0.031990945, -0.029777154 -0.14974782 0.05799152, -0.029439509 -0.15282702 0.050829306, -0.027786821 -0.15168339 0.054428965, -0.026130259 -0.1504271 0.05799143, -0.038505375 -0.15519196 0.037810907, -0.041704744 -0.15394363 0.039253071, -0.04057695 -0.15526256 0.035634547, -0.039409652 -0.15647981 0.031991228, -0.035485312 -0.15741616 0.031991124, -0.037980691 -0.15307742 0.044991359, -0.041666791 -0.15079555 0.048653215, -0.043427169 -0.15162218 0.044991523, -0.032934397 -0.15646887 0.037810907, -0.030861884 -0.15582907 0.041414291, -0.037479162 -0.15105653 0.050829098, -0.033406571 -0.14898014 0.057991728, -0.037016138 -0.14812464 0.057991624, -0.039890766 -0.14985746 0.052276015, -0.032485634 -0.1543369 0.044991344, -0.032076076 -0.15442261 0.044991329, -0.03205663 -0.15229946 0.050829008, -0.028778777 -0.15237719 -0.052290753, -0.029777184 -0.14974138 -0.058008492, -0.026130199 -0.15042081 -0.058008566, -0.028860152 -0.15785637 -0.035654187, -0.031538695 -0.1582506 -0.032008797, -0.030119702 -0.15661809 -0.039272785, -0.027572215 -0.1589897 -0.032008961, -0.037344411 -0.15050721 -0.052290469, -0.040603191 -0.15024036 -0.050848529, -0.038817436 -0.14923504 -0.054447785, -0.037016153 -0.14811817 -0.058008373, -0.033406481 -0.14897382 -0.058008313, -0.03798072 -0.15307227 -0.045008644, -0.043427289 -0.15161705 -0.045008466, -0.042362615 -0.15309906 -0.041429967, -0.031941339 -0.15174565 -0.052290574, -0.030429184 -0.1534538 -0.048668474, -0.038407758 -0.15479416 -0.03927283, -0.035485297 -0.15741265 -0.032008797, -0.039409772 -0.15647632 -0.032008782, -0.041258425 -0.15447921 -0.03782624, -0.032485485 -0.15433195 -0.045008898, -0.032076105 -0.15441746 -0.045008734, -0.032850921 -0.15606791 -0.03927283, -0.030151784 -0.16044542 -0.022253662, -0.031713068 -0.15909356 -0.028008938, -0.027715102 -0.15983856 -0.028008923, -0.029582262 -0.16221386 -0.0056272596, -0.032272875 -0.16179878 -0.0020090789, -0.030971929 -0.16176248 -0.0092399865, -0.028173476 -0.16256264 -0.0020091832, -0.039308846 -0.15845066 -0.022253305, -0.042777225 -0.15777805 -0.020810902, -0.04122366 -0.15759254 -0.024417579, -0.03964676 -0.15730423 -0.028008878, -0.035691112 -0.15824863 -0.028009146, -0.039538532 -0.15937728 -0.015009135, -0.04521513 -0.15786082 -0.015008822, -0.043918967 -0.15857413 -0.011403143, -0.03361477 -0.15975571 -0.022253335, -0.031659171 -0.16068837 -0.018638015, -0.039656833 -0.1598551 -0.0092399865, -0.036351889 -0.16093129 -0.0020090938, -0.040407449 -0.15996122 -0.0020091385, -0.042592719 -0.15918756 -0.007793203, -0.033811346 -0.16068977 -0.015009001, -0.033154577 -0.1608265 -0.015009031, -0.033912435 -0.16117153 -0.0092400163, -0.030418396 -0.1619561 0.0077773333, -0.032272935 -0.16179886 0.0019907355, -0.028173372 -0.16256291 0.0019907802, -0.029241726 -0.160252 0.024397999, -0.031713203 -0.1590966 0.027990863, -0.03075631 -0.16055745 0.020790935, -0.027715102 -0.15984163 0.027990878, -0.039677724 -0.15993983 0.0077774674, -0.043126732 -0.15895531 0.0092200339, -0.041782334 -0.15950832 0.005607307, -0.040407479 -0.15996149 0.0019908398, -0.03635174 -0.16093168 0.0019908994, -0.039538458 -0.15937892 0.014990866, -0.0436984 -0.15784186 0.018621877, -0.04521507 -0.1578624 0.014991134, -0.033930272 -0.16125706 0.0077773184, -0.031796083 -0.16144344 0.011386722, -0.039361954 -0.15866718 0.020791069, -0.035691127 -0.15825185 0.027991027, -0.039646819 -0.15730745 0.027990922, -0.042158604 -0.15771869 0.022237569, -0.033811286 -0.16069132 0.014990896, -0.033154353 -0.16082829 0.01499097, -0.033660129 -0.1599738 0.020791039, -0.055524692 -0.14689362 0.046991706, -0.057261482 -0.14479169 0.050654292, -0.059130102 -0.14547986 0.046991721, -0.05115734 -0.1361948 0.072016954, -0.054363683 -0.13494697 0.072016835, -0.053521171 -0.13843623 0.066744149, -0.053151011 -0.14544892 0.05283016, -0.052270323 -0.14248618 0.059991986, -0.055364668 -0.14399329 0.054277062, -0.05188559 -0.14821827 0.046991438, -0.052091971 -0.14255136 0.059991911, -0.052923277 -0.14050439 0.063390255, -0.047925398 -0.14725339 0.052829951, -0.048214987 -0.14945275 0.046991572, -0.045385584 -0.14805621 0.052829966, -0.05118154 -0.1400606 0.065409899, -0.047922239 -0.13736653 0.072016671, -0.046970382 -0.14432004 0.059991851, -0.043595731 -0.14703682 0.056429878, -0.041789383 -0.14590466 0.059991777, -0.043138117 -0.14274332 0.065409958, -0.046149656 -0.1417982 0.065409631, -0.043921918 -0.14064819 0.068736225, -0.044660494 -0.13846138 0.072016761, -0.058917359 -0.15276226 0.018991292, -0.060247138 -0.15199682 0.020622313, -0.06177932 -0.15190205 0.016991422, -0.057931885 -0.15341052 0.016991287, -0.056408927 -0.1537061 0.018991232, -0.058680445 -0.15199158 0.02423805, -0.054047585 -0.15482172 0.016991138, -0.05388549 -0.15460888 0.018991232, -0.056534559 -0.1527563 0.024488688, -0.051347464 -0.15547028 0.018991351, -0.050129309 -0.15613446 0.016991302, -0.056101575 -0.15177479 0.029991284, -0.055664465 -0.15055189 0.035495877, -0.058145925 -0.14911389 0.037253305, -0.057148889 -0.15049216 0.033634588, -0.047689617 -0.15604281 0.022791192, -0.049011514 -0.15532988 0.02450861, -0.05713971 -0.14836001 0.040991709, -0.059637055 -0.14670902 0.042991742, -0.055985391 -0.14814109 0.042991742, -0.054786146 -0.14924517 0.040991649, -0.046133831 -0.15585133 0.026398167, -0.046621263 -0.15494981 0.029991135, -0.052299321 -0.14948225 0.042991593, -0.05241929 -0.1500929 0.04099144, -0.044554472 -0.15555656 0.029991105, -0.050039023 -0.15090311 0.04099147, -0.046407521 -0.15357319 0.035810709, -0.048375607 -0.15304312 0.03552027, -0.047514245 -0.15220258 0.039414108, -0.048581302 -0.15073156 0.042991325, -0.055563793 -0.15198272 0.02994664, -0.054075196 -0.15251869 0.029946715, -0.049213767 -0.15117422 0.040991366, -0.057139739 -0.14835542 -0.041008487, -0.058720216 -0.14823627 -0.039429292, -0.0596371 -0.14670435 -0.043008387, -0.055985451 -0.14813629 -0.043008313, -0.054786235 -0.14924055 -0.041008502, -0.05775325 -0.1496726 -0.035825759, -0.05229941 -0.14947745 -0.043008581, -0.052419156 -0.15008828 -0.041008547, -0.055664331 -0.15054798 -0.035512626, -0.050038993 -0.15089849 -0.041008621, -0.048581392 -0.15072688 -0.043008491, -0.05610168 -0.15177128 -0.030008599, -0.056534588 -0.15275341 -0.02450566, -0.059311405 -0.15200296 -0.022810772, -0.057723865 -0.15193728 -0.026417255, -0.046854943 -0.15303278 -0.037272498, -0.048375458 -0.15303931 -0.035537556, -0.058917299 -0.15276009 -0.019008607, -0.061779246 -0.15190014 -0.017008498, -0.057931885 -0.15340865 -0.017008707, -0.056408867 -0.15370399 -0.019008607, -0.045724526 -0.15434328 -0.033653691, -0.046621263 -0.15494642 -0.030008748, -0.054047689 -0.15481979 -0.017008737, -0.053885505 -0.15460676 -0.0190088, -0.044554368 -0.15555331 -0.030008823, -0.05134742 -0.15546817 -0.0190088, -0.047070146 -0.15597591 -0.024253204, -0.049011379 -0.15532726 -0.024526179, -0.048611447 -0.15610582 -0.020638019, -0.050129145 -0.15613267 -0.017008811, -0.055560559 -0.15197018 -0.030008569, -0.054075181 -0.15251526 -0.029963836, -0.050683707 -0.15568563 -0.0190088, -0.058078349 -0.15380564 -0.013008714, -0.060710341 -0.15309176 -0.0094028115, -0.061940521 -0.15229145 -0.013008744, -0.058078289 -0.15380704 0.012991205, -0.061940506 -0.15229282 0.012991458, -0.059952557 -0.15352666 0.0072202235, -0.056594193 -0.15479517 -0.007239446, -0.057318881 -0.15472436 -8.7320805e-06, -0.059438854 -0.15379623 -0.0057931095, -0.054179266 -0.15522218 -0.013008729, -0.056657255 -0.1549677 -8.7618828e-06, -0.058656186 -0.15417343 0.0036077648, -0.051020876 -0.15672037 -0.0072396249, -0.050245672 -0.15653962 -0.013008907, -0.048155963 -0.15762451 -0.0072396845, -0.056616902 -0.15485781 0.0057777315, -0.054179341 -0.15522355 0.01299122, -0.051077768 -0.15689525 -8.8661909e-06, -0.045432732 -0.15862194 -9.149313e-06, -0.04762125 -0.15785646 0.0057777315, -0.046809688 -0.15817299 -0.0036270022, -0.051041305 -0.15678403 0.0057774484, -0.04894878 -0.15724853 0.0093870461, -0.050245643 -0.15654117 0.01299119, -0.066084102 -0.12961069 0.072017133, -0.069130503 -0.12801173 0.072017342, -0.068714663 -0.13137069 0.067055553, -0.059123904 -0.13595629 0.06705682, -0.06158109 -0.13768059 0.061992139, -0.05824028 -0.13912681 0.061992079, -0.066117674 -0.13269666 0.067055471, -0.068153024 -0.13454854 0.061992332, -0.064886034 -0.13615423 0.061992258, -0.063000709 -0.13113713 0.072017215, -0.061716512 -0.13480011 0.067055359, -0.05988203 -0.13259035 0.072016954, -0.061965153 -0.14215273 -0.052290246, -0.062351882 -0.13936111 -0.058007851, -0.058947667 -0.14083478 -0.058007941, -0.063263372 -0.14747655 -0.035653517, -0.065962464 -0.14726487 -0.032008186, -0.064215809 -0.14598909 -0.039272472, -0.062259942 -0.14886799 -0.032008365, -0.069899619 -0.13842356 -0.052289784, -0.073017403 -0.13743842 -0.050847769, -0.071052849 -0.13685548 -0.05444704, -0.069048211 -0.13616759 -0.058007747, -0.065719455 -0.1378049 -0.058007747, -0.071090624 -0.14078304 -0.045007914, -0.076077044 -0.13815215 -0.045007885, -0.075368702 -0.13983396 -0.041429102, -0.064907625 -0.14083338 -0.052289993, -0.063813642 -0.14283511 -0.048667908, -0.071890295 -0.14236659 -0.039272249, -0.069623634 -0.14556968 -0.03200829, -0.073241279 -0.14378357 -0.032008082, -0.074599206 -0.14142525 -0.03782557, -0.066013649 -0.14323378 -0.045008138, -0.065633446 -0.14340836 -0.045008108, -0.066756055 -0.14484483 -0.039272338, -0.065098718 -0.14971322 -0.022252873, -0.066320062 -0.14804789 -0.028008536, -0.062587991 -0.14966381 -0.02800855, -0.064936742 -0.15156412 -0.0056263804, -0.067467451 -0.15056077 -0.0020086467, -0.066190943 -0.15081489 -0.009239465, -0.063640684 -0.15221772 -0.0020085871, -0.073582098 -0.14573109 -0.022252679, -0.076813996 -0.14430332 -0.020810172, -0.075258076 -0.14446828 -0.024416685, -0.073656544 -0.14453802 -0.028008342, -0.070010394 -0.14633891 -0.028008446, -0.074012175 -0.14658323 -0.015008435, -0.079209074 -0.14384153 -0.015008122, -0.078104138 -0.14482549 -0.011402309, -0.068321213 -0.14827031 -0.022252813, -0.066622108 -0.14961469 -0.018637657, -0.074233994 -0.14702266 -0.0092392713, -0.071250901 -0.14880756 -0.0020083785, -0.074989155 -0.14695916 -0.0020083785, -0.076947466 -0.14571869 -0.0077925771, -0.068720609 -0.1491372 -0.015008479, -0.06811069 -0.1494168 -0.015008405, -0.068926483 -0.14958435 -0.0092392415, -0.063840851 -0.14659995 0.037811413, -0.065962464 -0.14726844 0.031991631, -0.062259927 -0.14887157 0.031991661, -0.062351868 -0.13936761 0.057992131, -0.062707797 -0.14244473 0.050829858, -0.060842097 -0.14169738 0.054429591, -0.058947578 -0.14084116 0.057992071, -0.072072953 -0.14273268 0.037811711, -0.074914426 -0.1408039 0.039253905, -0.074108317 -0.1423406 0.035635352, -0.073241234 -0.14378726 0.031991944, -0.06962356 -0.14557335 0.03199169, -0.071090609 -0.1407879 0.044992015, -0.074176863 -0.137743 0.048654109, -0.076076925 -0.13815719 0.044992119, -0.066925764 -0.14521739 0.037811503, -0.064762682 -0.14505491 0.041414872, -0.070152074 -0.13892931 0.050829768, -0.065719396 -0.13781142 0.05799228, -0.069048256 -0.13617405 0.057992324, -0.07223627 -0.13722378 0.052276567, -0.066013813 -0.14323863 0.044991925, -0.06563352 -0.14341331 0.044991896, -0.065141946 -0.14134774 0.050829545, -0.065694183 -0.15112698 0.0077780336, -0.067467406 -0.15056089 0.0019914657, -0.063640684 -0.15221792 0.0019914806, -0.064167544 -0.14972728 0.024398759, -0.066319913 -0.14805096 0.027991593, -0.065712273 -0.14968821 0.020791724, -0.062587947 -0.14966682 0.027991533, -0.074272752 -0.14710063 0.0077781826, -0.07741639 -0.14537326 0.0092205852, -0.076228604 -0.14621171 0.005608052, -0.074988946 -0.14695945 0.0019916296, -0.07125099 -0.14880759 0.0019915402, -0.074012175 -0.14658496 0.014991745, -0.077725798 -0.14416069 0.018622711, -0.079209015 -0.14384311 0.01499182, -0.068962559 -0.14966363 0.0077780932, -0.06692332 -0.15032047 0.011387601, -0.073681414 -0.14593035 0.020791858, -0.070010319 -0.14634219 0.027991667, -0.073656604 -0.14454123 0.027991772, -0.076197043 -0.14438325 0.022238359, -0.068720415 -0.14913887 0.014991462, -0.068110734 -0.14941829 0.014991552, -0.068413481 -0.14847291 0.020791724, -0.11375964 -0.10825562 0.046993949, -0.11441235 -0.10560822 0.050656334, -0.11639454 -0.10541755 0.046994008, -0.10518215 -0.10051143 0.072018847, -0.10752957 -0.097995996 0.072019078, -0.10828435 -0.10150507 0.066746026, -0.11099386 -0.10798413 0.05283232, -0.10891479 -0.10569674 0.059994087, -0.11235687 -0.10571188 0.054279312, -0.11105553 -0.11102796 0.046993718, -0.10878242 -0.10583287 0.059994042, -0.10864326 -0.10362786 0.063392311, -0.1070689 -0.11187705 0.052832104, -0.10828399 -0.11373284 0.046993554, -0.10512886 -0.11370221 0.052831829, -0.10688134 -0.10398376 0.065411888, -0.10277571 -0.10297069 0.072018817, -0.10493563 -0.1096485 0.059993841, -0.1030738 -0.11356035 0.056431748, -0.10095512 -0.11332408 0.059993513, -0.10079857 -0.10989076 0.065411702, -0.10310178 -0.10773256 0.065411687, -0.10059559 -0.10766304 0.068738006, -0.10031203 -0.10537243 0.072018489, -0.11585115 -0.10887149 -0.041006282, -0.11722326 -0.1080783 -0.039426923, -0.11738472 -0.1063002 -0.043006137, -0.11471607 -0.10917488 -0.043006256, -0.11411473 -0.11069006 -0.041006267, -0.11697519 -0.10979193 -0.035823494, -0.11197695 -0.11198238 -0.043006346, -0.11235002 -0.11248088 -0.041006491, -0.11547305 -0.11148679 -0.035510629, -0.11055699 -0.11424363 -0.041006595, -0.10916907 -0.11472127 -0.043006778, -0.11639765 -0.11239958 -0.030006379, -0.11721377 -0.11309662 -0.02450341, -0.11938991 -0.1112155 -0.022808477, -0.11793114 -0.11184511 -0.026414946, -0.10861416 -0.11754802 -0.037270442, -0.10998702 -0.11689395 -0.035535455, -0.1193632 -0.11206871 -0.019006312, -0.12156861 -0.11005223 -0.017006233, -0.11875667 -0.11308065 -0.017006338, -0.11751284 -0.11400753 -0.019006535, -0.10816421 -0.11921921 -0.033651739, -0.10923368 -0.1193735 -0.030006856, -0.11586939 -0.11603737 -0.017006516, -0.11563085 -0.11591592 -0.019006521, -0.10763489 -0.12081707 -0.030006766, -0.11371803 -0.11779287 -0.019006684, -0.11008482 -0.12010622 -0.024251238, -0.11155227 -0.11867955 -0.024524033, -0.11152983 -0.11955455 -0.020636067, -0.11290856 -0.11892018 -0.017006695, -0.11599632 -0.11281359 -0.030006468, -0.11489473 -0.11394891 -0.02996169, -0.11321433 -0.11827725 -0.019006595, -0.11906084 -0.11337468 -0.013006464, -0.12112239 -0.11158961 -0.009400636, -0.12188354 -0.11033478 -0.013006404, -0.11906093 -0.11337623 0.012993544, -0.12188345 -0.11033621 0.012993589, -0.12062794 -0.11231035 0.007222265, -0.11815278 -0.11491019 -0.0072372556, -0.11877473 -0.1145322 -6.5714121e-06, -0.12028241 -0.11277592 -0.0057907552, -0.11616237 -0.11634269 -0.013006628, -0.11828446 -0.11503857 -6.4224005e-06, -0.11974065 -0.1134555 0.0036099404, -0.11396691 -0.11906305 -0.0072374791, -0.11319016 -0.11923647 -0.013006747, -0.11177793 -0.12112063 -0.0072378069, -0.11820018 -0.11495697 0.0057800263, -0.11616239 -0.11634421 0.012993425, -0.11409372 -0.11919597 -7.0482492e-06, -0.11080292 -0.12219894 -0.0036250353, -0.10975698 -0.12320083 -6.9439411e-06, -0.11139637 -0.1215618 0.0057797581, -0.11401249 -0.11911142 0.0057797134, -0.11232869 -0.12043801 0.0093892664, -0.11319017 -0.11923784 0.012993261, -0.11936317 -0.11207089 0.018993542, -0.12022911 -0.11080429 0.020624653, -0.12156846 -0.11005414 0.01699388, -0.11875658 -0.11308265 0.016993552, -0.1175127 -0.11400968 0.018993571, -0.11881521 -0.11147922 0.024240226, -0.11586943 -0.1160391 0.016993463, -0.11563084 -0.11591795 0.018993333, -0.1172137 -0.1130994 0.024490654, -0.1137179 -0.11779523 0.018993273, -0.11290866 -0.11892211 0.016993284, -0.11639766 -0.11240286 0.029993467, -0.11547302 -0.11149102 0.035498075, -0.11708496 -0.10911846 0.037255533, -0.11678459 -0.11079305 0.033637032, -0.11067064 -0.11989823 0.022793233, -0.11155222 -0.11868235 0.024510533, -0.1158511 -0.10887596 0.04099384, -0.11738469 -0.10630494 0.042993747, -0.1147161 -0.10917959 0.042993851, -0.11411481 -0.11069441 0.040993713, -0.1091858 -0.12040058 0.026400179, -0.10923375 -0.11937675 0.029993147, -0.111977 -0.11198702 0.04299359, -0.11234989 -0.11248541 0.040993609, -0.10763478 -0.1208204 0.029993176, -0.11055689 -0.11424807 0.040993489, -0.10844368 -0.11822927 0.035812795, -0.10998695 -0.11689794 0.035522394, -0.10884608 -0.11651435 0.039416172, -0.10916911 -0.11472613 0.042993426, -0.11600324 -0.11282367 0.029949054, -0.11489481 -0.1139524 0.029949024, -0.10993113 -0.11485043 0.040993445, -0.12475972 -0.10765713 0.0077803433, -0.12611185 -0.10637769 0.0019939691, -0.123383 -0.10953099 0.0019935519, -0.12277671 -0.10705841 0.024400957, -0.12398852 -0.10461435 0.027994148, -0.12415138 -0.10635307 0.020794123, -0.12132718 -0.10768941 0.027994052, -0.13074173 -0.10030764 0.0077808052, -0.13282447 -0.097387224 0.0092232823, -0.1321182 -0.098657966 0.0056107342, -0.13132612 -0.09986937 0.0019941926, -0.12876007 -0.10315651 0.0019941181, -0.13028304 -0.099955767 0.014994189, -0.13377561 -0.095230818 0.014994487, -0.13257709 -0.096160591 0.018625438, -0.12706938 -0.10492074 0.0077804923, -0.1255171 -0.10639733 0.011390045, -0.12970078 -0.099509537 0.020794466, -0.12657183 -0.10147351 0.027994283, -0.12907563 -0.098268896 0.027994506, -0.13129598 -0.097024381 0.022241086, -0.12662373 -0.10455289 0.014994025, -0.12619562 -0.10506919 0.014993966, -0.12605779 -0.10408613 0.020794213, -0.1236106 -0.10664165 -0.022250399, -0.12398854 -0.10461125 -0.028005838, -0.12132727 -0.10768637 -0.028006077, -0.12426722 -0.10837951 -0.0056241304, -0.12611187 -0.10637745 -0.0020061284, -0.12507236 -0.10716033 -0.0092367977, -0.123383 -0.10953078 -0.0020060986, -0.12952599 -0.099373072 -0.022249848, -0.13181828 -0.096684515 -0.020807445, -0.13048805 -0.097508132 -0.024414077, -0.12907566 -0.098265737 -0.02800566, -0.12657173 -0.10147032 -0.028005913, -0.13028294 -0.099954218 -0.015005648, -0.13320719 -0.096595049 -0.011399627, -0.1337755 -0.095229238 -0.015005514, -0.12588778 -0.10394329 -0.022250414, -0.12494045 -0.10589188 -0.018635079, -0.13067324 -0.10025394 -0.0092365742, -0.12876014 -0.10315627 -0.0020058304, -0.13132602 -0.099869251 -0.0020057112, -0.13255247 -0.097901762 -0.0077899247, -0.12662354 -0.10455117 -0.015005901, -0.12619533 -0.10506764 -0.015005946, -0.12700282 -0.10486481 -0.0092367232, -0.11750749 -0.10118949 -0.052287892, -0.1166449 -0.098506153 -0.058005631, -0.11421713 -0.10131109 -0.05800572, -0.1209868 -0.10542265 -0.035651118, -0.12332658 -0.10406092 -0.032005832, -0.12119962 -0.10366917 -0.039270133, -0.12068631 -0.10711175 -0.03200613, -0.12303844 -0.094386846 -0.052287295, -0.12541993 -0.092146397 -0.050845206, -0.12339711 -0.092473626 -0.054444581, -0.12129234 -0.092723548 -0.058005348, -0.11900389 -0.095642954 -0.058005437, -0.125135 -0.095995635 -0.045005545, -0.1285775 -0.093284518 -0.041426495, -0.12848607 -0.091461957 -0.045005232, -0.11958648 -0.098723829 -0.052287668, -0.11946899 -0.10100207 -0.048665494, -0.12654236 -0.097075582 -0.039269626, -0.12588972 -0.1009452 -0.032005787, -0.12837422 -0.097766131 -0.032005578, -0.12857457 -0.095052153 -0.037822902, -0.1216241 -0.10040665 -0.045005858, -0.12135737 -0.1007289 -0.045005679, -0.12299198 -0.10153618 -0.03926982, -0.1157739 -0.088102877 0.072019555, -0.11782494 -0.085340291 0.072019726, -0.1189077 -0.08854717 0.067057945, -0.1122563 -0.096839964 0.067058876, -0.11521854 -0.097327203 0.061994582, -0.11283608 -0.10007966 0.061994366, -0.11714338 -0.090868562 0.067057766, -0.11978064 -0.091653913 0.061994702, -0.11753386 -0.094518185 0.061994657, -0.11365822 -0.090815961 0.072019473, -0.11409054 -0.094673306 0.067057498, -0.11147872 -0.093478501 0.072019137, -0.12112498 -0.10438254 0.037813902, -0.12332662 -0.10406452 0.031994149, -0.12068641 -0.1071153 0.031993799, -0.1166449 -0.09851259 0.057994455, -0.11830098 -0.10113037 0.050832041, -0.11629563 -0.1012668 0.054431915, -0.11421707 -0.10131738 0.057994284, -0.12686373 -0.097326666 0.037814036, -0.12858696 -0.094356149 0.03925655, -0.1285277 -0.096090257 0.035638012, -0.12837419 -0.097769737 0.031994469, -0.12588978 -0.10094869 0.031994335, -0.12513492 -0.096000731 0.044994749, -0.12659414 -0.091918468 0.048656501, -0.12848592 -0.091467112 0.044994853, -0.1233045 -0.10179853 0.037813991, -0.12128495 -0.10259059 0.041417189, -0.12348268 -0.094733417 0.050832085, -0.11900384 -0.095649481 0.057994597, -0.12129261 -0.092730075 0.057994902, -0.12462059 -0.092292398 0.05227901, -0.12162413 -0.10041159 0.044994436, -0.12135734 -0.10073391 0.04499431, -0.12001808 -0.099086225 0.050831974, -0.093267463 -0.11165607 0.072018117, -0.095881708 -0.10941929 0.072018407, -0.096223764 -0.11278659 0.067056626, -0.087894164 -0.11939135 0.067057848, -0.090673283 -0.12052563 0.061993182, -0.087738045 -0.12267885 0.061993033, -0.093986958 -0.11465731 0.067056522, -0.096383378 -0.1160098 0.06199345, -0.093555488 -0.11830217 0.061993271, -0.090600982 -0.11383048 0.072018154, -0.090164162 -0.11768728 0.067056373, -0.087883808 -0.11594129 0.072017998, -0.096781135 -0.13147384 -0.022251815, -0.09760128 -0.12957838 -0.028007507, -0.094322592 -0.13198429 -0.028007567, -0.097034797 -0.13331428 -0.0056256652, -0.099278688 -0.13177305 -0.0020075291, -0.098090902 -0.13230473 -0.0092383772, -0.095916688 -0.13423982 -0.0020076931, -0.10416564 -0.1257039 -0.022251368, -0.10699883 -0.12359262 -0.020809099, -0.10551861 -0.12409955 -0.024415657, -0.10397302 -0.12452394 -0.028007224, -0.10081881 -0.1270912 -0.028007194, -0.10477455 -0.12643883 -0.015007153, -0.10923098 -0.12260947 -0.015007049, -0.10837275 -0.1238147 -0.011401057, -0.099601895 -0.12934989 -0.022251621, -0.098244429 -0.13103884 -0.01863654, -0.10508831 -0.12681797 -0.0092381984, -0.1025773 -0.12922192 -0.0020073652, -0.10581051 -0.12658814 -0.0020071715, -0.10744363 -0.12494287 -0.0077914596, -0.10018378 -0.13010636 -0.015007451, -0.099651471 -0.13051453 -0.015007436, -0.10048403 -0.13049644 -0.0092382431, -0.092044026 -0.12480024 -0.052289337, -0.091800019 -0.12199223 -0.058007091, -0.088809043 -0.12418655 -0.058007061, -0.094494373 -0.1297015 -0.035652369, -0.097078502 -0.12889463 -0.032007217, -0.09509185 -0.12803948 -0.039271399, -0.093825489 -0.13128129 -0.032007381, -0.098949969 -0.11939886 -0.05228886, -0.10177018 -0.11774471 -0.050846606, -0.099725157 -0.11761346 -0.054446176, -0.09761788 -0.11738884 -0.058006749, -0.094737008 -0.11972582 -0.058006853, -0.10063598 -0.12143394 -0.04500702, -0.10459548 -0.11955681 -0.04142794, -0.10491182 -0.11775959 -0.045006558, -0.094619155 -0.12285918 -0.05228892, -0.093998104 -0.12505388 -0.048666924, -0.10176772 -0.12279999 -0.039271057, -0.10027063 -0.12642732 -0.032007158, -0.10340017 -0.12388086 -0.032006994, -0.10419938 -0.12127948 -0.037824467, -0.096231699 -0.12495306 -0.045007184, -0.095899835 -0.12520796 -0.045007005, -0.097313896 -0.12635863 -0.039271399, -0.097675934 -0.13271961 0.0077788979, -0.099278703 -0.13177305 0.0019924194, -0.095916584 -0.13424024 0.0019923449, -0.095875874 -0.13169479 0.024399579, -0.097601265 -0.12958148 0.027992502, -0.097373098 -0.13131291 0.020792812, -0.094322383 -0.13198736 0.027992502, -0.10514341 -0.12688524 0.0077793002, -0.10782364 -0.12450185 0.0092216134, -0.10685244 -0.12558353 0.0056093633, -0.10581039 -0.12658823 0.001992628, -0.1025773 -0.12922201 0.0019924492, -0.10477449 -0.12644053 0.01499261, -0.10923111 -0.12261105 0.014993057, -0.10785559 -0.12325093 0.018623844, -0.10053672 -0.13056567 0.0077790916, -0.098694801 -0.13165992 0.011388481, -0.10430634 -0.12587592 0.020792887, -0.1008188 -0.1270943 0.027992636, -0.10397296 -0.12452707 0.027992845, -0.10641459 -0.12380791 0.022239551, -0.1001839 -0.13010788 0.01499252, -0.099651426 -0.13051608 0.014992476, -0.099736199 -0.12952697 0.020792708, -0.094861269 -0.12871838 0.037812546, -0.097078472 -0.12889829 0.031992659, -0.093825638 -0.13128501 0.03199254, -0.091800056 -0.12199858 0.057993107, -0.09283185 -0.12491947 0.050830573, -0.090846591 -0.12460619 0.054430708, -0.088809028 -0.12419292 0.057993233, -0.10202638 -0.12311649 0.037812762, -0.10436741 -0.12060371 0.039255075, -0.10392357 -0.12228134 0.035636649, -0.10340023 -0.12388438 0.031992927, -0.10027069 -0.12643084 0.031992897, -0.10063593 -0.12143889 0.04499317, -0.10296707 -0.11778381 0.04865507, -0.10491189 -0.11776462 0.04499349, -0.097561136 -0.12668413 0.037812531, -0.095416158 -0.12700689 0.041415922, -0.099307239 -0.11983591 0.050830752, -0.094736844 -0.11973232 0.057993196, -0.09761785 -0.11739522 0.057993516, -0.1009597 -0.11770913 0.052277803, -0.096231624 -0.12495807 0.044993058, -0.095899895 -0.12521294 0.044993028, -0.094960958 -0.12330863 0.050830543, -0.086818963 -0.13085553 0.046992525, -0.088044383 -0.12841979 0.050655119, -0.090019211 -0.12867478 0.046992742, -0.080179863 -0.12139672 0.072017811, -0.083028145 -0.11946663 0.072017699, -0.082983457 -0.12305567 0.066744804, -0.084183097 -0.12997517 0.052831121, -0.082665034 -0.12728268 0.059992895, -0.086017385 -0.12806335 0.054278076, -0.083565846 -0.13295648 0.046992511, -0.08250571 -0.12738588 0.059992798, -0.082860664 -0.12520522 0.063391194, -0.079490155 -0.13289708 0.05283083, -0.080261827 -0.13497669 0.046992481, -0.077192634 -0.13424489 0.052831009, -0.081063747 -0.12516016 0.065410681, -0.07728675 -0.12325895 0.072017685, -0.077906348 -0.1302498 0.059992693, -0.075220779 -0.13364941 0.056430742, -0.073207594 -0.13294753 0.059992544, -0.073819064 -0.12956545 0.065410525, -0.076544836 -0.12797382 0.065410703, -0.074117102 -0.12734839 0.068736993, -0.074350387 -0.12505206 0.072017543, -0.091432616 -0.13582185 0.01899229, -0.092558816 -0.13477963 0.020623237, -0.094031468 -0.13434634 0.01699245, -0.090616211 -0.13667321 0.016992435, -0.089197189 -0.13730028 0.01899232, -0.091030255 -0.13512316 0.024239093, -0.087143466 -0.13891321 0.016992226, -0.08693783 -0.13874194 0.0189922, -0.089108303 -0.13634625 0.024489567, -0.084655106 -0.14014646 0.018992156, -0.083615333 -0.14106506 0.016992062, -0.088467717 -0.13548562 0.029992312, -0.087769285 -0.13439089 0.035496667, -0.089868709 -0.13243657 0.037254199, -0.089203328 -0.13400221 0.033635572, -0.081216276 -0.14151853 0.022792041, -0.082346484 -0.14052951 0.0245094, -0.08871977 -0.13192558 0.040992737, -0.090787187 -0.12976032 0.042992696, -0.087545604 -0.13196903 0.042992428, -0.086622342 -0.1333122 0.040992498, -0.079657033 -0.14167812 0.026398972, -0.079931468 -0.14069071 0.029991925, -0.08425051 -0.13409656 0.042992279, -0.084503248 -0.1346654 0.040992424, -0.078051537 -0.14174229 0.029991865, -0.082363054 -0.13598505 0.040992364, -0.079416826 -0.13939598 0.035811618, -0.081217468 -0.1384415 0.035521075, -0.080190659 -0.13781375 0.039414927, -0.08090362 -0.13614216 0.042992234, -0.087989509 -0.13580811 0.029947624, -0.086657718 -0.13666168 0.029947624, -0.081618831 -0.13643298 0.04099223, -0.090847328 -0.1370258 -0.013007775, -0.093254372 -0.13574412 -0.0094019175, -0.094275534 -0.13469014 -0.013007626, -0.090847403 -0.13702708 0.012992159, -0.094275653 -0.13469154 0.012992293, -0.092612132 -0.13633668 0.0072209388, -0.08962059 -0.1383206 -0.0072386414, -0.090310961 -0.13809043 -7.7784061e-06, -0.09217146 -0.13671389 -0.0057920814, -0.087361261 -0.13927421 -0.013007909, -0.089720219 -0.13847497 -7.8976154e-06, -0.091492489 -0.13725576 0.0036087334, -0.08461529 -0.14143795 -0.0072388947, -0.083819479 -0.14143419 -0.013007954, -0.082023308 -0.14295676 -0.007238701, -0.089656606 -0.13837677 0.0057786703, -0.087361142 -0.1392757 0.012992099, -0.08470957 -0.14159575 -8.1509352e-06, -0.07959035 -0.14453512 -8.2701445e-06, -0.081553593 -0.14330199 0.0057784021, -0.080833018 -0.14379114 -0.0036261678, -0.084649235 -0.14149526 0.0057784915, -0.082712516 -0.14241388 0.0093880147, -0.083819449 -0.14143565 0.012992069, -0.088719755 -0.13192102 -0.041007519, -0.09023416 -0.13145322 -0.039428324, -0.090787232 -0.12975553 -0.043007314, -0.087545618 -0.13196433 -0.043007314, -0.086622268 -0.13330764 -0.041007593, -0.089611024 -0.13306865 -0.035824805, -0.084250629 -0.13409188 -0.043007746, -0.084503293 -0.13466093 -0.041007653, -0.087769344 -0.13438672 -0.035511792, -0.08236295 -0.13598034 -0.041007802, -0.080903575 -0.13613728 -0.043007806, -0.088467762 -0.13548228 -0.030007586, -0.089108124 -0.13634357 -0.024504945, -0.091648296 -0.13499385 -0.022809789, -0.090086192 -0.13528302 -0.026416436, -0.07973361 -0.13876963 -0.037271574, -0.081217498 -0.1384376 -0.035536528, -0.091432691 -0.13581961 -0.019007608, -0.094031394 -0.13434443 -0.017007604, -0.090616137 -0.1366713 -0.017007649, -0.089197099 -0.13729817 -0.019007683, -0.078923181 -0.14029908 -0.033652902, -0.079931468 -0.14068732 -0.030007988, -0.087143421 -0.13891137 -0.017007902, -0.086937875 -0.13873976 -0.019007817, -0.078051597 -0.14173895 -0.030007988, -0.084655136 -0.14014432 -0.019007817, -0.080598161 -0.14159107 -0.024252608, -0.082346573 -0.14052653 -0.024525359, -0.082129836 -0.14137489 -0.020637199, -0.083615378 -0.14106312 -0.017008021, -0.087984279 -0.13579676 -0.03000778, -0.086657763 -0.1366584 -0.029962793, -0.084056601 -0.14050412 -0.019007921, 0.14424156 0.076464266 -0.022240192, 0.14415832 0.074401349 -0.027995825, 0.142248 0.077991694 -0.027995825, 0.14526832 0.078010768 -0.0056139529, 0.14662111 0.07564804 -0.0019959211, 0.14578196 0.076642931 -0.00922665, 0.14466251 0.07932955 -0.0019958317, 0.14839126 0.06806156 -0.022240609, 0.15002796 0.064930141 -0.020798475, 0.14891431 0.066029638 -0.024405181, 0.14770597 0.067083001 -0.027996361, 0.14597806 0.070764422 -0.027996153, 0.14925866 0.068459034 -0.01499626, 0.15136184 0.064532995 -0.011390805, 0.15161207 0.063075304 -0.014996499, 0.14586149 0.073326766 -0.02224049, 0.14537121 0.075437069 -0.018624961, 0.14970574 0.068663627 -0.0092273057, 0.14848632 0.071918249 -0.0019960403, 0.1502564 0.068142593 -0.0019962788, 0.15101428 0.065952152 -0.0077806711, 0.14671387 0.073755115 -0.014995962, 0.14641136 0.074353874 -0.014995933, 0.14715339 0.073975682 -0.0092270076, 0.14558753 0.077195078 0.0077906847, 0.1466212 0.075647712 0.0020042062, 0.14466262 0.079329222 0.002004236, 0.14352073 0.077051103 0.024411201, 0.14415833 0.074398339 0.02800402, 0.14470412 0.076057792 0.020804197, 0.14224817 0.077988416 0.028004289, 0.14978407 0.068698764 0.0077902675, 0.15116499 0.065388083 0.0092322826, 0.15075916 0.06678459 0.0056200027, 0.15025644 0.068142325 0.0020036995, 0.14848617 0.071918041 0.002003938, 0.14925863 0.068457335 0.01500383, 0.15161216 0.063073695 0.015003353, 0.15065053 0.064246297 0.0186342, 0.14723046 0.074013352 0.0077904463, 0.1460456 0.075798154 0.011400223, 0.14859171 0.068150908 0.02080366, 0.14597806 0.070761234 0.028003812, 0.14770605 0.067079961 0.028003663, 0.14959385 0.065372944 0.022250086, 0.14671384 0.073753357 0.015004039, 0.14641124 0.074352324 0.015004009, 0.1460584 0.073423356 0.020804077, 0.14131494 0.07480827 0.037824094, 0.14339076 0.074009001 0.032004178, 0.1414955 0.077570826 0.032004386, 0.13564079 0.070080251 0.058003947, 0.13783783 0.072264731 0.05084154, 0.1359131 0.072843462 0.05444175, 0.13389799 0.073355168 0.058004007, 0.14533985 0.066652298 0.037823379, 0.14635882 0.063372672 0.039265424, 0.1466869 0.065076977 0.035647035, 0.146911 0.066748857 0.032003641, 0.1451962 0.070400983 0.03200379, 0.14335918 0.065743595 0.045003623, 0.14561731 0.060577959 0.045003414, 0.14387339 0.06143856 0.048665196, 0.14286479 0.071804017 0.037823677, 0.1410722 0.073025137 0.041426986, 0.14146625 0.064874977 0.050841272, 0.13730352 0.066763997 0.058003813, 0.13888505 0.063408494 0.058003411, 0.1420323 0.062242091 0.052287787, 0.14091781 0.070825219 0.045003921, 0.14072947 0.071198821 0.04500401, 0.13905719 0.069889516 0.050841302, 0.13707881 0.072510242 -0.052278101, 0.13564081 0.070086688 -0.057996184, 0.13389796 0.073361546 -0.05799602, 0.14141257 0.075861335 -0.035640955, 0.14339076 0.074012578 -0.031995982, 0.14122982 0.074104637 -0.03926006, 0.14149556 0.077574402 -0.031995833, 0.1409573 0.064647496 -0.052278519, 0.14278041 0.06193313 -0.050836518, 0.1408812 0.062702626 -0.054435924, 0.13888508 0.063414961 -0.057996616, 0.13730356 0.066770405 -0.057996482, 0.14335924 0.065748572 -0.044996381, 0.14611185 0.062338948 -0.041417807, 0.14561743 0.060582906 -0.044996768, 0.13855685 0.069643974 -0.052278161, 0.13894941 0.071890622 -0.048655853, 0.1449713 0.066487551 -0.039260656, 0.14519614 0.07040453 -0.031996161, 0.14691103 0.066752493 -0.031996399, 0.14650249 0.064062387 -0.037814051, 0.14091785 0.070830226 -0.044996217, 0.14072956 0.071203768 -0.044996053, 0.14250256 0.071626395 -0.039260149, 0.13562922 0.059867531 -0.067059726, 0.13385992 0.056981921 -0.072021365, 0.13247499 0.060131729 -0.072021261, 0.13227612 0.072462052 -0.061996147, 0.13398625 0.069248587 -0.061996192, 0.13099006 0.069432348 -0.067060471, 0.13442476 0.062523127 -0.067060962, 0.13561851 0.065994561 -0.061996445, 0.13717176 0.062702298 -0.061996639, 0.13101608 0.063247651 -0.072021052, 0.13229527 0.066911697 -0.067060724, 0.12948379 0.066328257 -0.072020859, 0.13717315 0.08036685 -0.040995479, 0.13833451 0.079288155 -0.039416581, 0.13809617 0.077519 -0.04299587, 0.13613395 0.080915451 -0.042995542, 0.13588502 0.082526267 -0.040995568, 0.13847378 0.081013709 -0.035812765, 0.13408831 0.084262133 -0.042995453, 0.13456289 0.084664911 -0.040995508, 0.13738649 0.083000422 -0.035499692, 0.13320714 0.086782426 -0.040995419, 0.13196045 0.087557107 -0.0429952, 0.13849077 0.08368367 -0.029995412, 0.13944156 0.084180951 -0.024492592, 0.14114445 0.081862837 -0.022797853, 0.13986239 0.08280158 -0.026403934, 0.13204841 0.090435833 -0.037258834, 0.13324115 0.089492619 -0.035523921, 0.1413084 0.082700074 -0.018995434, 0.14300972 0.080243021 -0.016995549, 0.14094217 0.083821297 -0.0169954, 0.1399356 0.085002095 -0.018995404, 0.13198146 0.092164934 -0.033639967, 0.1330585 0.092076838 -0.029995024, 0.13878536 0.087346286 -0.016995192, 0.13852559 0.087281346 -0.018995196, 0.13182086 0.093840063 -0.029994845, 0.13707848 0.089537084 -0.018995076, 0.13405108 0.092601359 -0.024239451, 0.13516435 0.090883881 -0.02451247, 0.135337 0.091741621 -0.020624012, 0.13654006 0.090815842 -0.016995013, 0.13819183 0.0841766 -0.029995352, 0.13737039 0.085528582 -0.029950619, 0.13669509 0.09012118 -0.018995106, 0.12490995 0.074585974 -0.072020397, 0.12761594 0.073654473 -0.068738431, 0.12663861 0.071611464 -0.072020665, 0.13499589 0.080227554 -0.046995506, 0.13693313 0.076874107 -0.046995729, 0.13386554 0.07784456 -0.052836597, 0.12674281 0.077230006 -0.066749543, 0.12970309 0.078810662 -0.0599958, 0.12849611 0.075664371 -0.065411583, 0.12311116 0.077519208 -0.072020322, 0.12960431 0.078973055 -0.059995666, 0.13182984 0.078361958 -0.056435838, 0.12390555 0.081704646 -0.066749364, 0.12124355 0.080408901 -0.072020233, 0.12245704 0.083860308 -0.066749185, 0.13173942 0.080273658 -0.054278448, 0.13297656 0.083531976 -0.046995327, 0.12670293 0.083548844 -0.059995383, 0.12364015 0.088018179 -0.05999504, 0.12698945 0.087595105 -0.054277956, 0.1230949 0.085960954 -0.063395292, 0.12879017 0.084924877 -0.05427815, 0.12897444 0.087229252 -0.050655469, 0.13087636 0.086785674 -0.046995193, 0.14130837 0.082698017 0.019004613, 0.14187086 0.081270099 0.020635307, 0.14300974 0.080241054 0.0170044, 0.14094225 0.08381936 0.01700452, 0.13993573 0.084999949 0.019004703, 0.14064257 0.08224228 0.024251163, 0.13878529 0.087344408 0.017004877, 0.13852569 0.087279111 0.019004852, 0.13944152 0.084178329 0.02450189, 0.13707849 0.089534938 0.019004911, 0.13654003 0.090813935 0.017005056, 0.13849078 0.083680391 0.030004501, 0.13738666 0.082996368 0.035508811, 0.13843004 0.080324411 0.037266105, 0.13850993 0.082024246 0.033647627, 0.13457552 0.092262864 0.022805184, 0.13516447 0.09088099 0.024522394, 0.13717312 0.080362409 0.04100436, 0.13809621 0.077514321 0.043004274, 0.13613413 0.080910534 0.043004453, 0.13588507 0.082521617 0.041004479, 0.13323958 0.093082845 0.026412159, 0.1330584 0.09207356 0.030004978, 0.13408828 0.084257334 0.043004543, 0.13456292 0.084660351 0.041004509, 0.13182081 0.093836725 0.030005097, 0.13320711 0.086777866 0.041004807, 0.13203278 0.091129959 0.035824388, 0.1332411 0.089488715 0.035533816, 0.13204351 0.089368165 0.039427668, 0.13196036 0.087552398 0.043004751, 0.13820001 0.08417815 0.029959917, 0.13737039 0.085525274 0.029959947, 0.13273105 0.087504327 0.041004807, 0.14130425 0.084039986 -0.012995362, 0.14291662 0.081840277 -0.0093896687, 0.14337955 0.080448061 -0.012995631, 0.14130415 0.084038615 0.013004631, 0.14337958 0.080446601 0.013004392, 0.14259468 0.082651526 0.0072332323, 0.14076057 0.085738301 -0.0072262883, 0.14128247 0.085230529 4.6789646e-06, 0.14236169 0.083183765 -0.0057797134, 0.13913885 0.087578356 -0.012995243, 0.14091715 0.085833311 4.8279762e-06, 0.14198461 0.08396551 0.0036211312, 0.13760357 0.090718478 -0.0072257221, 0.13688493 0.091061145 -0.012994975, 0.13592726 0.093211651 -0.0072257221, 0.14081672 0.085771978 0.0057912171, 0.13913886 0.087576836 0.01300478, 0.13775663 0.09081918 5.0663948e-06, 0.1352167 0.094479412 -0.0036127269, 0.13441989 0.095688552 5.1558018e-06, 0.13565338 0.093725115 0.0057916045, 0.13765863 0.090754151 0.0057915151, 0.13631225 0.09242171 0.0094012022, 0.13688491 0.091059625 0.013004988, 0.15441871 0.041487128 0.037821919, 0.15626448 0.040246129 0.03200227, 0.15520956 0.04414013 0.032002389, 0.14783502 0.038140088 0.058002129, 0.15046312 0.039780945 0.050839722, 0.14871538 0.040773481 0.054439843, 0.14686473 0.041720748 0.058002323, 0.15652789 0.03263998 0.037821412, 0.15679136 0.029215813 0.039263427, 0.15749055 0.030804396 0.035645038, 0.15808105 0.032384574 0.032001585, 0.15722202 0.036326587 0.032001972, 0.15439476 0.032194704 0.045001656, 0.15393813 0.027883202 0.048663288, 0.15544683 0.026656151 0.045001596, 0.15526132 0.038213313 0.037821829, 0.15378548 0.039802641 0.041425139, 0.15235615 0.031769097 0.050839216, 0.1487181 0.034537166 0.05800204, 0.14951336 0.03091377 0.058001801, 0.15232202 0.029076189 0.052286074, 0.15314543 0.037692249 0.045002133, 0.15304492 0.038098335 0.045002133, 0.15112326 0.037194103 0.050839663, 0.15911505 0.042863429 0.0077887774, 0.15977836 0.041124821 0.0020021498, 0.15868805 0.045149773 0.0020022094, 0.15706828 0.04318276 0.024409324, 0.15709955 0.040454626 0.028002113, 0.15800086 0.04195109 0.020802408, 0.15603596 0.044380009 0.028002411, 0.16131574 0.033646256 0.0077883005, 0.16192536 0.030111372 0.0092304349, 0.16184035 0.031563073 0.0056180656, 0.16165236 0.03299877 0.0020016134, 0.16076671 0.037073672 0.0020020306, 0.16074964 0.033527851 0.015001804, 0.16116978 0.029112607 0.018632472, 0.16184638 0.02775532 0.015001446, 0.16000876 0.039395869 0.0077885389, 0.15925089 0.0413993 0.011398226, 0.16003151 0.033377558 0.020801902, 0.15806426 0.036503941 0.028002024, 0.1589296 0.032530338 0.028001815, 0.16039042 0.030446082 0.02224806, 0.15944742 0.039257258 0.015002161, 0.15928568 0.03990835 0.015002102, 0.15873499 0.039081424 0.02080217, 0.14554957 0.028186232 -0.067061394, 0.14318262 0.02576685 -0.072023049, 0.14253318 0.029145777 -0.072023019, 0.14508317 0.041211128 -0.061997682, 0.1460354 0.037697703 -0.061998069, 0.14315505 0.038543701 -0.067062214, 0.14496641 0.031043261 -0.06706278, 0.14690256 0.034162194 -0.061998084, 0.14768426 0.030606866 -0.061998397, 0.14180423 0.032508224 -0.072022766, 0.14386669 0.035795689 -0.067062378, 0.14099589 0.035852581 -0.072022691, 0.14977631 0.040189356 -0.052279979, 0.14783505 0.038146615 -0.057997987, 0.14686461 0.041727155 -0.057997808, 0.15474728 0.042492092 -0.035642833, 0.15626453 0.040249616 -0.03199774, 0.15417822 0.040820062 -0.039262027, 0.15520951 0.044143677 -0.031997502, 0.15180793 0.031660736 -0.052280337, 0.15298133 0.028608769 -0.050838456, 0.15130098 0.02978152 -0.054437742, 0.14951344 0.030920178 -0.057998255, 0.14871815 0.034543604 -0.05799821, 0.15439481 0.03219977 -0.044998407, 0.15544698 0.026661009 -0.044998631, 0.1563199 0.028263122 -0.041419789, 0.15057951 0.037066072 -0.052279949, 0.15146199 0.039169192 -0.04865776, 0.156131 0.032561511 -0.039262414, 0.15722206 0.036330193 -0.031998008, 0.15808104 0.03238818 -0.031998366, 0.15708412 0.029856414 -0.037816033, 0.15314533 0.037697285 -0.044998065, 0.15304494 0.038103282 -0.044997975, 0.15486765 0.038120627 -0.039262027, 0.15763976 0.042450428 -0.022242039, 0.15709956 0.040457726 -0.027997792, 0.15603608 0.044383049 -0.027997553, 0.15898508 0.043729663 -0.0056156814, 0.1597784 0.041125089 -0.0019978285, 0.15918142 0.042282164 -0.0092284679, 0.15868799 0.045150071 -0.0019977093, 0.15981568 0.033334911 -0.022242665, 0.16071446 0.029917926 -0.020800501, 0.15987346 0.031237483 -0.024407029, 0.15892975 0.032533318 -0.027998328, 0.15806416 0.03650707 -0.027997941, 0.16074973 0.03352949 -0.014998108, 0.16184637 0.027756929 -0.014998555, 0.16192666 0.029233843 -0.011392742, 0.15852077 0.039031237 -0.022242367, 0.15851264 0.041197598 -0.018626988, 0.16123126 0.033629417 -0.0092290044, 0.16076668 0.037073821 -0.0019980371, 0.16165245 0.03299883 -0.0019983053, 0.16190369 0.030694783 -0.0077825785, 0.15944743 0.039258897 -0.01499784, 0.15928562 0.039910048 -0.01499784, 0.15992503 0.03937602 -0.009228766, 0.15161671 0.047828108 -0.040997446, 0.15250894 0.046518058 -0.03941837, 0.15188293 0.044846147 -0.042997584, 0.15072572 0.048593998 -0.04299733, 0.15084137 0.050220013 -0.040997356, 0.15302882 0.048169196 -0.035814613, 0.14947613 0.052312016 -0.042997107, 0.15002836 0.052599162 -0.040997148, 0.15241097 0.050348133 -0.03550151, 0.14917785 0.054965228 -0.040997133, 0.14813471 0.055998117 -0.042997018, 0.15363963 0.050768465 -0.029997289, 0.15467714 0.051041812 -0.024494231, 0.15582167 0.048402905 -0.022799611, 0.15478067 0.049603224 -0.02640608, 0.14886095 0.058784992 -0.037260592, 0.14981411 0.057600051 -0.03552568, 0.15616767 0.049182743 -0.018997282, 0.15727957 0.046408564 -0.016997427, 0.15606028 0.050357223 -0.016997248, 0.15534179 0.051732212 -0.018997192, 0.1491807 0.060485542 -0.033641577, 0.15021105 0.0601601 -0.029996753, 0.15474178 0.054273784 -0.016997069, 0.15447427 0.054268211 -0.018997103, 0.14939681 0.062154472 -0.029996634, 0.15356518 0.056789428 -0.018996924, 0.15129551 0.060450584 -0.024241239, 0.15199877 0.058528304 -0.024514228, 0.15235822 0.059326023 -0.020626068, 0.15332499 0.058155894 -0.016996831, 0.15345772 0.051315606 -0.029997259, 0.1529579 0.052816451 -0.029952198, 0.15332159 0.057444066 -0.018996835, 0.15646189 0.050489813 -0.012997359, 0.15754446 0.047986537 -0.0093916655, 0.15768592 0.046526164 -0.012997538, 0.15646189 0.050488383 0.013002604, 0.15768588 0.046524763 0.013002545, 0.15741135 0.048848987 0.0072313845, 0.15630984 0.052266598 -0.007227838, 0.15670593 0.051655143 2.8014183e-06, 0.1573025 0.049419671 -0.0057816207, 0.15513818 0.054421306 -0.01299715, 0.15648372 0.052324265 2.8610229e-06, 0.15710892 0.050265878 0.0036190748, 0.15434031 0.057824314 -0.0072277486, 0.15371583 0.058318108 -0.012996882, 0.15326068 0.060628057 -0.0072274506, 0.15637243 0.052286834 0.0057892501, 0.15513824 0.054419816 0.013002902, 0.15451194 0.057888269 3.1590462e-06, 0.15285012 0.06202206 -0.0036147833, 0.15234238 0.063378245 3.3378601e-06, 0.15310808 0.061189622 0.0057899058, 0.15440205 0.057846904 0.0057896078, 0.15346059 0.059772104 0.0093992054, 0.15371576 0.058316767 0.013003141, 0.15616789 0.049180388 0.019002616, 0.1563984 0.047663182 0.020633459, 0.15727973 0.046406746 0.017002404, 0.15606035 0.050355196 0.017002851, 0.15534167 0.051730275 0.019002885, 0.15541726 0.048884481 0.024249285, 0.15474185 0.054271728 0.01700294, 0.15447423 0.054266036 0.019002885, 0.15467718 0.05103901 0.024500072, 0.1535652 0.056787223 0.019003183, 0.15332513 0.058153927 0.017003298, 0.15363941 0.050765246 0.030002713, 0.15241078 0.05034411 0.035506964, 0.15283363 0.047506928 0.037264138, 0.15328966 0.049146205 0.033645898, 0.151732 0.060003847 0.022803307, 0.15199885 0.058525532 0.024520576, 0.1516168 0.047823489 0.041002452, 0.15188296 0.044841349 0.043002516, 0.15072571 0.048589319 0.043002635, 0.1508414 0.050215364 0.041002601, 0.15061231 0.061100304 0.026410282, 0.15021102 0.060156763 0.030003101, 0.14947605 0.052307278 0.043002725, 0.15002835 0.052594662 0.04100281, 0.14939691 0.062151134 0.030003369, 0.1491778 0.054960698 0.041003019, 0.14900121 0.05946508 0.035822749, 0.14981392 0.057596087 0.035532176, 0.14861959 0.05774498 0.039425761, 0.14813463 0.055993259 0.043002784, 0.15346694 0.051315159 0.029958248, 0.15295784 0.052813113 0.029958248, 0.14887533 0.055774897 0.04100287, 0.13837418 0.04492116 -0.072022066, 0.14080498 0.043410808 -0.0687401, 0.13939767 0.041636199 -0.072022215, 0.14946304 0.048176616 -0.046997219, 0.15060544 0.04447636 -0.046997577, 0.14783071 0.046104997 -0.052838176, 0.14074951 0.047090858 -0.066751212, 0.14398748 0.047973216 -0.05999732, 0.14211051 0.04517433 -0.065413237, 0.1372733 0.048180848 -0.072021961, 0.1439274 0.0481534 -0.059997454, 0.14596111 0.047062397 -0.056437597, 0.13897915 0.052084804 -0.066750839, 0.13609546 0.051413685 -0.072021574, 0.13804677 0.054508567 -0.066750839, 0.14629838 0.048946321 -0.054280087, 0.14822969 0.051847667 -0.046997145, 0.14211687 0.053260148 -0.059997007, 0.14012541 0.058298945 -0.059996769, 0.14329663 0.057141095 -0.054279581, 0.13913605 0.056414545 -0.063396797, 0.1444581 0.05413717 -0.054279745, 0.1451506 0.056342781 -0.050657228, 0.14690615 0.055486977 -0.046997085, 0.08017993 0.12139657 -0.072017699, 0.083022103 0.12173116 -0.068735629, 0.083028182 0.11946648 -0.072017938, 0.086818874 0.1308552 -0.046992689, 0.090019122 0.1286746 -0.046992794, 0.086834475 0.12821791 -0.052833751, 0.080684066 0.12457386 -0.066746846, 0.082665101 0.12728244 -0.059992954, 0.082943067 0.12392411 -0.065408707, 0.077286795 0.12325868 -0.072017655, 0.082505628 0.12738585 -0.059992939, 0.084776074 0.12780073 -0.056433082, 0.076186359 0.12737432 -0.066746786, 0.074350432 0.12505192 -0.072017506, 0.073946089 0.12868801 -0.066746622, 0.083864912 0.12948397 -0.054275587, 0.083565757 0.13295645 -0.046992615, 0.077906385 0.13024956 -0.059992909, 0.073207676 0.13294747 -0.059992686, 0.076408669 0.13401943 -0.054275379, 0.073609129 0.13085741 -0.063392729, 0.079189777 0.13239497 -0.054275393, 0.078355864 0.13455111 -0.050652757, 0.080261737 0.1349766 -0.04699257, 0.090847328 0.13702703 -0.012992412, 0.093254507 0.1357449 -0.0093868077, 0.094275698 0.13469142 -0.01299265, 0.090847313 0.13702554 0.013007462, 0.094275653 0.1346899 0.013007343, 0.092612103 0.13633594 0.0072360933, 0.089620471 0.13832143 -0.0072231293, 0.090311125 0.13809022 7.5995922e-06, 0.09217155 0.13671443 -0.0057767928, 0.087361172 0.13927546 -0.012992263, 0.089720234 0.13847476 7.6293945e-06, 0.09149234 0.13725513 0.003624022, 0.084615394 0.14143854 -0.0072229505, 0.083819538 0.14143541 -0.012992293, 0.082023412 0.14295742 -0.0072229505, 0.089656293 0.13837594 0.0057943165, 0.087361187 0.13927409 0.013007879, 0.08470954 0.14159551 7.7784061e-06, 0.079590365 0.14453489 7.8678131e-06, 0.081553414 0.14330131 0.0057943761, 0.080832869 0.14379141 -0.0036100149, 0.08464925 0.14149463 0.0057943463, 0.082712635 0.14241266 0.0094039738, 0.083819389 0.14143401 0.013007909, 0.088719785 0.13192549 -0.040992782, 0.09023416 0.13145751 -0.03941378, 0.090787187 0.12976006 -0.04299283, 0.087545604 0.13196883 -0.042992756, 0.086622342 0.13331211 -0.040992633, 0.089610964 0.13307253 -0.035809889, 0.08425045 0.13409653 -0.042992562, 0.084503174 0.1346654 -0.040992618, 0.087769166 0.13439083 -0.035496697, 0.08236298 0.13598496 -0.040992424, 0.080903575 0.13614199 -0.042992502, 0.088467598 0.1354855 -0.029992402, 0.089108214 0.1363461 -0.024489552, 0.091648385 0.13499638 -0.022794724, 0.090086058 0.13528576 -0.026401132, 0.079733685 0.13877368 -0.037256196, 0.081217617 0.13844144 -0.03552115, 0.091432586 0.13582185 -0.018992484, 0.094031543 0.13434616 -0.016992629, 0.090616345 0.13667291 -0.01699248, 0.089197218 0.1373001 -0.018992424, 0.078923091 0.1403026 -0.033637181, 0.079931468 0.14069042 -0.029992238, 0.087143376 0.13891307 -0.01699239, 0.0869378 0.13874188 -0.018992424, 0.078051463 0.14174211 -0.029992193, 0.084655106 0.14014634 -0.018992335, 0.080598086 0.14159378 -0.024236709, 0.082346499 0.1405293 -0.024509609, 0.082129851 0.14137694 -0.020621479, 0.083615229 0.14106485 -0.016992152, 0.087984279 0.13579983 -0.029992461, 0.086657822 0.13666159 -0.029947802, 0.084056407 0.14050627 -0.018992096, 0.091432601 0.13581961 0.019007534, 0.092558905 0.13477716 0.020638347, 0.094031453 0.13434425 0.0170075, 0.090616301 0.13667107 0.01700756, 0.089197189 0.13729805 0.019007564, 0.09103018 0.13512015 0.024254054, 0.087143302 0.13891122 0.017007738, 0.086937889 0.13873965 0.019007623, 0.089108199 0.13634333 0.024504751, 0.084655091 0.1401442 0.019007802, 0.083615273 0.14106297 0.017007917, 0.088467672 0.13548219 0.030007541, 0.087769285 0.13438669 0.035511762, 0.089868605 0.13243213 0.037268996, 0.089203268 0.13399836 0.033650666, 0.081216335 0.14151588 0.022807837, 0.082346424 0.14052641 0.024525255, 0.08871977 0.13192108 0.04100737, 0.090787128 0.12975532 0.043007329, 0.087545663 0.13196403 0.04300727, 0.086622372 0.13330755 0.041007265, 0.079657018 0.141675 0.026414871, 0.079931512 0.14068714 0.03000769, 0.08425048 0.13409173 0.043007374, 0.084503278 0.13466075 0.0410074, 0.078051463 0.1417388 0.030007869, 0.08236298 0.13598043 0.041007414, 0.079416618 0.13939199 0.035827339, 0.081217542 0.13843751 0.035536677, 0.080190673 0.13780916 0.039430439, 0.080903605 0.13613716 0.043007687, 0.087989539 0.13580468 0.029962867, 0.086657777 0.13665816 0.029963076, 0.081618726 0.13642836 0.041007549, 0.096223742 0.11278638 -0.067056656, 0.095881656 0.10941911 -0.072018564, 0.093267426 0.11165601 -0.072018281, 0.087738067 0.12267879 -0.061993062, 0.090673283 0.12052554 -0.061993405, 0.087893859 0.11939135 -0.067057744, 0.093986556 0.11465636 -0.067057982, 0.093555436 0.11830214 -0.061993271, 0.096383348 0.11600986 -0.06199351, 0.090600923 0.11383033 -0.072018236, 0.090163544 0.11768654 -0.067057863, 0.0878838 0.11594099 -0.072018296, 0.094861358 0.12871397 0.037827075, 0.097078413 0.12889457 0.032007247, 0.093825445 0.13128147 0.032007307, 0.091799989 0.12199217 0.058006883, 0.092831984 0.12491348 0.050844729, 0.090846524 0.12459984 0.054444417, 0.088808954 0.12418652 0.058006883, 0.10202652 0.12311199 0.037826538, 0.10436748 0.12059918 0.039268672, 0.1039235 0.12227726 0.035650104, 0.10340016 0.12388083 0.032006949, 0.10027064 0.12642723 0.032007098, 0.10063601 0.12143391 0.045006782, 0.10296696 0.1177783 0.048668265, 0.10491176 0.11775967 0.045006514, 0.097561195 0.12667969 0.037826717, 0.095416188 0.12700215 0.041430056, 0.099307299 0.11982992 0.050844088, 0.094736919 0.11972579 0.058006629, 0.097617701 0.11738876 0.058006689, 0.1009596 0.11770332 0.052290976, 0.096231699 0.12495294 0.045006841, 0.095899776 0.12520778 0.04500708, 0.094960928 0.12330264 0.050844371, 0.097675934 0.13271841 0.007793963, 0.099278793 0.13177276 0.0020072758, 0.095916748 0.13423991 0.0020073652, 0.095875904 0.13169187 0.024414152, 0.09760128 0.12957838 0.028007179, 0.097373083 0.13131043 0.020807505, 0.094322518 0.13198426 0.028007329, 0.10514338 0.12688422 0.0077934861, 0.1078237 0.12450063 0.0092357993, 0.1068524 0.12558281 0.005623281, 0.10581046 0.12658787 0.0020070374, 0.10257736 0.12922171 0.0020071268, 0.10477455 0.12643877 0.01500681, 0.10785553 0.12324861 0.018637657, 0.10923079 0.12260941 0.015006661, 0.10053678 0.13056454 0.0077936351, 0.098694712 0.13165846 0.011403263, 0.10430644 0.12587333 0.020807087, 0.10081875 0.1270912 0.028006971, 0.10397303 0.12452394 0.028006881, 0.10641466 0.12380508 0.022253394, 0.10018392 0.13010627 0.015007168, 0.099651515 0.13051447 0.015007168, 0.099736258 0.12952441 0.020807177, 0.096781045 0.13147601 -0.022237033, 0.09760125 0.12958136 -0.027992874, 0.094322428 0.13198739 -0.027992755, 0.097034797 0.13331488 -0.0056107044, 0.099278867 0.13177302 -0.0019927323, 0.098090932 0.13230553 -0.0092236102, 0.095916674 0.13424012 -0.0019925535, 0.10416564 0.12570593 -0.02223745, 0.10699888 0.12359482 -0.020795226, 0.1055185 0.12410232 -0.024401814, 0.10397294 0.12452707 -0.027993202, 0.10081871 0.12709418 -0.027993113, 0.10477452 0.12644044 -0.014993131, 0.10837269 0.1238158 -0.011387318, 0.10923094 0.12261102 -0.014993191, 0.099601716 0.12935218 -0.022237152, 0.098244399 0.13104078 -0.018621773, 0.10508832 0.12681875 -0.0092238486, 0.10257736 0.12922189 -0.0019928515, 0.10581045 0.1265882 -0.0019930601, 0.10744378 0.12494349 -0.0077774227, 0.10018399 0.13010782 -0.014992774, 0.099651471 0.1305162 -0.014992714, 0.10048401 0.13049716 -0.0092236698, 0.092044041 0.12480596 -0.052275166, 0.091799989 0.12199855 -0.057993278, 0.088808879 0.12419301 -0.057993293, 0.094494253 0.12970543 -0.03563799, 0.097078353 0.12889811 -0.031992838, 0.095091805 0.12804347 -0.039257184, 0.093825519 0.13128492 -0.031992763, 0.098949865 0.11940473 -0.052275389, 0.10177009 0.11775014 -0.050833449, 0.099725202 0.11761943 -0.054432884, 0.09761782 0.11739525 -0.057993412, 0.094736993 0.11973226 -0.057993233, 0.10063601 0.12143883 -0.044993207, 0.10491186 0.11776462 -0.04499352, 0.1045955 0.1195612 -0.041414633, 0.094619349 0.12286484 -0.052275315, 0.093997911 0.12505937 -0.048652977, 0.10176782 0.12280416 -0.039257228, 0.10027064 0.12643075 -0.031993002, 0.10340016 0.12388435 -0.031992972, 0.1041995 0.12128347 -0.037810832, 0.09623155 0.12495804 -0.044992968, 0.095899791 0.12521279 -0.044993132, 0.097313821 0.12636286 -0.039257213, 0.12475967 0.107656 0.0077923834, 0.12611181 0.10637754 0.0020056367, 0.12338309 0.10953072 0.0020060241, 0.12277663 0.10705552 0.02441287, 0.1239884 0.10461119 0.028005719, 0.12415126 0.10635051 0.020805895, 0.12132721 0.10768625 0.028006077, 0.13074169 0.10030648 0.0077919662, 0.13282447 0.097386092 0.00923419, 0.13211823 0.098657161 0.0056217909, 0.131326 0.099869132 0.0020053089, 0.12876008 0.10315627 0.0020055473, 0.13028291 0.099954098 0.015005499, 0.13257697 0.096158355 0.018636078, 0.1337757 0.09522903 0.015005291, 0.12706953 0.10491958 0.0077922344, 0.12551714 0.10639593 0.011401862, 0.12970081 0.099507034 0.020805597, 0.12657179 0.10147029 0.028005451, 0.1290756 0.098265618 0.028005421, 0.1312961 0.09702161 0.022251844, 0.12662356 0.10455114 0.015005678, 0.12619534 0.10506758 0.015005678, 0.12605773 0.10408366 0.020805836, 0.12361038 0.10664397 -0.022238553, 0.12398846 0.10461426 -0.027994335, 0.12132712 0.10768941 -0.027994066, 0.12426727 0.10837996 -0.0056121051, 0.12611198 0.1063776 -0.001994133, 0.12507212 0.10716113 -0.0092248917, 0.12338299 0.10953099 -0.0019939244, 0.12952606 0.099375248 -0.022238821, 0.13181832 0.096686482 -0.020796716, 0.13048808 0.097510606 -0.024403214, 0.12907562 0.098268628 -0.027994633, 0.12657179 0.10147336 -0.027994454, 0.13028307 0.099955708 -0.014994502, 0.13320708 0.096596241 -0.011388898, 0.13377567 0.095230758 -0.01499486, 0.12588777 0.10394567 -0.022238672, 0.12494028 0.10589394 -0.018623114, 0.13067311 0.10025489 -0.0092254579, 0.12876005 0.10315651 -0.0019942522, 0.13132599 0.099869281 -0.0019944906, 0.13255236 0.097902477 -0.0077789128, 0.12662369 0.10455281 -0.014994234, 0.12619549 0.10506925 -0.014994204, 0.12700284 0.10486558 -0.0092251301, 0.12112497 0.1043781 0.037825614, 0.12332664 0.10406083 0.032005787, 0.12068638 0.10711163 0.032005817, 0.11664495 0.098506033 0.058005452, 0.11830093 0.10112461 0.050843269, 0.11629558 0.10126048 0.05444324, 0.11421721 0.10131088 0.058005556, 0.12686396 0.097322196 0.037825018, 0.12858717 0.09435153 0.039267182, 0.12852764 0.096086204 0.035648793, 0.1283742 0.097766161 0.032005429, 0.12588976 0.10094503 0.032005668, 0.12513506 0.095995516 0.045005351, 0.12848604 0.091461927 0.045005053, 0.1265942 0.091912866 0.048666865, 0.12330452 0.10179418 0.037825197, 0.1212851 0.1025857 0.041428745, 0.12348266 0.094727665 0.050842732, 0.11900383 0.095642984 0.058005258, 0.12129265 0.092723459 0.058005214, 0.12462057 0.092286587 0.052289516, 0.12162417 0.10040659 0.04500556, 0.12135726 0.10072884 0.045005739, 0.12001809 0.099080414 0.050843149, 0.11890781 0.088546872 -0.067058101, 0.11782484 0.085340142 -0.072019905, 0.11577396 0.088102549 -0.072019741, 0.11283609 0.10007951 -0.061994448, 0.11521855 0.097327173 -0.061994582, 0.11225647 0.096839696 -0.06705898, 0.11714266 0.090867817 -0.067059323, 0.11753373 0.094518036 -0.061994702, 0.11978063 0.091654003 -0.06199491, 0.11365812 0.090815842 -0.072019577, 0.11408985 0.094672531 -0.067059189, 0.11147869 0.093478262 -0.072019488, 0.11750767 0.10119513 -0.052276567, 0.11664495 0.098512471 -0.05799447, 0.11421721 0.10131723 -0.0579945, 0.12098688 0.10542655 -0.035639405, 0.12332658 0.10406446 -0.031994402, 0.1211995 0.10367331 -0.039258495, 0.12068644 0.10711518 -0.031994194, 0.12303841 0.094392657 -0.052276716, 0.12541991 0.092152029 -0.050834939, 0.12339713 0.092479557 -0.054434478, 0.12129249 0.092729986 -0.057994872, 0.11900386 0.09564954 -0.057994738, 0.12513499 0.096000612 -0.044994712, 0.12848598 0.091466933 -0.04499504, 0.12857735 0.093289018 -0.041416198, 0.1195863 0.0987297 -0.052276596, 0.11946899 0.1010074 -0.048654199, 0.1265422 0.097079813 -0.039258748, 0.12588972 0.1009486 -0.031994432, 0.1283742 0.097769707 -0.031994611, 0.12857468 0.095056206 -0.037812233, 0.12162422 0.1004115 -0.044994682, 0.12135723 0.10073397 -0.044994488, 0.12299182 0.10154039 -0.03925842, 0.1193631 0.11206874 0.019006163, 0.12022918 0.1108017 0.020637006, 0.12156849 0.11005196 0.017006159, 0.11875668 0.1130805 0.017006278, 0.11751269 0.11400747 0.019006252, 0.11881529 0.11147627 0.024252892, 0.11586949 0.1160371 0.017006427, 0.11563076 0.11591578 0.019006312, 0.11721368 0.11309639 0.02450335, 0.11371787 0.11779299 0.01900661, 0.11290857 0.11892006 0.017006636, 0.11639756 0.11239931 0.030006051, 0.11547308 0.11148676 0.035510391, 0.11708489 0.10911408 0.037267655, 0.11678462 0.11078903 0.033649325, 0.11067061 0.11989555 0.022806704, 0.1115523 0.11867929 0.024523973, 0.11585107 0.10887146 0.041005969, 0.11738479 0.10630003 0.043005884, 0.11471607 0.10917455 0.043006003, 0.11411473 0.11068988 0.041006058, 0.10918593 0.12039754 0.02641356, 0.10923365 0.11937335 0.030006409, 0.11197688 0.1119822 0.043006092, 0.11234985 0.11248076 0.041006178, 0.10763481 0.12081692 0.030006647, 0.11055689 0.11424357 0.041006356, 0.10844365 0.11822522 0.035825908, 0.10998699 0.11689383 0.035535485, 0.10884605 0.11650988 0.039429307, 0.10916911 0.11472106 0.043006271, 0.11600322 0.11282012 0.029961646, 0.11489476 0.1139487 0.029961705, 0.10993116 0.11484584 0.041006267, 0.11906101 0.11337596 -0.012993783, 0.12112227 0.11159045 -0.00938797, 0.12188348 0.11033601 -0.012994081, 0.11906092 0.11337456 0.013006389, 0.12188351 0.11033458 0.013006002, 0.1206277 0.11230972 0.0072350204, 0.11815277 0.11491093 -0.0072244704, 0.1187747 0.11453196 6.2584877e-06, 0.12028247 0.11277664 -0.0057782233, 0.1161626 0.1163438 -0.012993515, 0.11828433 0.11503828 6.4373016e-06, 0.11974074 0.11345485 0.0036226213, 0.11396679 0.11906382 -0.0072242022, 0.11319005 0.11923775 -0.012993485, 0.11177771 0.12112135 -0.0072240531, 0.11820009 0.1149562 0.0057928562, 0.11616258 0.11634228 0.013006359, 0.11409369 0.11919576 6.6161156e-06, 0.10975698 0.12320068 6.7949295e-06, 0.11139633 0.12156105 0.0057932138, 0.11080295 0.12219915 -0.003611207, 0.11401258 0.11911052 0.0057930946, 0.11232872 0.12043682 0.0094026029, 0.11318995 0.11923632 0.013006598, 0.11585104 0.10887599 -0.040994093, 0.11722329 0.10808283 -0.039414763, 0.11738484 0.10630468 -0.042994305, 0.11471602 0.10917944 -0.042994022, 0.11411472 0.11069447 -0.040994108, 0.11697531 0.10979584 -0.035811126, 0.11197689 0.11198691 -0.042993769, 0.11234991 0.11248538 -0.040993884, 0.11547299 0.11149085 -0.035498083, 0.11055693 0.1142481 -0.040993765, 0.10916916 0.11472589 -0.042993784, 0.11639749 0.11240268 -0.029993892, 0.11721376 0.1130991 -0.024490803, 0.11938974 0.11121815 -0.022796035, 0.11793104 0.11184791 -0.026402444, 0.10861419 0.11755204 -0.037257195, 0.10998693 0.11689791 -0.035522223, 0.11936314 0.11207077 -0.018993706, 0.12156849 0.1100539 -0.01699385, 0.11875676 0.11308238 -0.016993731, 0.11751272 0.11400965 -0.018993795, 0.10816416 0.11922285 -0.033638567, 0.10923371 0.1193766 -0.029993385, 0.11586945 0.11603898 -0.016993523, 0.11563079 0.1159178 -0.018993586, 0.10763474 0.12082031 -0.029993296, 0.11371791 0.11779514 -0.018993467, 0.11008446 0.12010902 -0.024237931, 0.11155234 0.11868206 -0.024510771, 0.11152978 0.11955673 -0.020622671, 0.11290848 0.11892194 -0.016993254, 0.11599638 0.11281669 -0.029993773, 0.1148947 0.11395213 -0.02994886, 0.11321424 0.11827913 -0.018993437, 0.10518198 0.10051122 -0.07201916, 0.10802741 0.10020509 -0.06873703, 0.10752939 0.097995758 -0.07201916, 0.11375964 0.10825554 -0.04699403, 0.11639443 0.1054174 -0.046994209, 0.1131878 0.10568073 -0.052834928, 0.1063807 0.10349667 -0.066748068, 0.10891482 0.10569656 -0.059994236, 0.10843834 0.10236058 -0.065409943, 0.10277574 0.10297054 -0.072018817, 0.10878243 0.10583282 -0.059994221, 0.11108805 0.10573229 -0.056434155, 0.10261881 0.10722777 -0.066747874, 0.10031192 0.10537219 -0.072018817, 0.10072701 0.10900715 -0.0667478, 0.11057441 0.10757598 -0.054276779, 0.11105564 0.11102769 -0.046993852, 0.10493562 0.10964826 -0.059993893, 0.10095508 0.11332402 -0.059993863, 0.10431446 0.11365676 -0.054276571, 0.10088134 0.11119699 -0.063393697, 0.10666426 0.11145428 -0.05427663, 0.10633114 0.11374179 -0.050653994, 0.10828397 0.1137327 -0.046993777, 0.14106221 -0.035591215 0.072022483, 0.14018108 -0.038917005 0.072022289, 0.14336367 -0.037763983 0.067060784, 0.1457002 -0.027393311 0.067062944, 0.14792828 -0.029404521 0.061998323, 0.14859492 -0.025825888 0.061998397, 0.14407854 -0.034936994 0.067060828, 0.1463373 -0.036508679 0.061997771, 0.14717564 -0.032966197 0.061997905, 0.14186436 -0.032245308 0.072022706, 0.14514978 -0.030177981 0.06706126, 0.14258692 -0.028881371 0.072022736, 0.15238006 -0.028775841 -0.052283898, 0.14974464 -0.02977398 -0.058001801, 0.15042396 -0.0261271 -0.058001444, 0.15785836 -0.028858215 -0.035646886, 0.15825228 -0.031536758 -0.032001927, 0.15662007 -0.030117542 -0.039265975, 0.15899144 -0.027570575 -0.032001555, 0.1505101 -0.037341475 -0.052284375, 0.15024324 -0.0406003 -0.050842196, 0.14923786 -0.038814425 -0.05444178, 0.1481213 -0.037012935 -0.058002174, 0.14897683 -0.033403277 -0.058001935, 0.15307477 -0.037978232 -0.045002431, 0.15161955 -0.043424755 -0.045002595, 0.1531011 -0.042360306 -0.041423619, 0.15174851 -0.031938225 -0.052283883, 0.15345638 -0.030426621 -0.04866156, 0.15479627 -0.038405746 -0.039266363, 0.15741444 -0.035483599 -0.032001987, 0.15647803 -0.039407969 -0.032002285, 0.15448126 -0.041256309 -0.037819922, 0.1543344 -0.032483071 -0.045001835, 0.15441994 -0.032073498 -0.04500182, 0.1560699 -0.032848686 -0.039265916, 0.16044658 -0.030150652 -0.022246167, 0.15909505 -0.031711459 -0.028002053, 0.15984008 -0.027713627 -0.02800177, 0.16221406 -0.029581994 -0.0056197643, 0.16179873 -0.032272846 -0.0020019412, 0.16176271 -0.030971318 -0.0092326105, 0.16256264 -0.028173327 -0.0020017326, 0.15845187 -0.039307594 -0.022246569, 0.15777919 -0.042776257 -0.02080451, 0.15759386 -0.041222274 -0.024411052, 0.15730572 -0.039645255 -0.028002501, 0.15825009 -0.035689622 -0.028002068, 0.15937814 -0.039537698 -0.01500231, 0.15786146 -0.045214206 -0.015002653, 0.15857476 -0.043918461 -0.011396766, 0.15975682 -0.033613682 -0.022246301, 0.16068941 -0.031658113 -0.018630922, 0.15985548 -0.03965649 -0.0092331171, 0.16093159 -0.03635177 -0.00200212, 0.15996127 -0.0404073 -0.002002418, 0.159188 -0.042592287 -0.0077868402, 0.16069052 -0.033810467 -0.015001953, 0.16082743 -0.033153683 -0.015001982, 0.16117187 -0.033912152 -0.0092330277, 0.15712804 -0.029621571 0.037818015, 0.15825236 -0.031540364 0.031998158, 0.15899134 -0.027574122 0.031998381, 0.14974467 -0.029780507 0.05799827, 0.15282413 -0.02944243 0.050836012, 0.15168022 -0.027789861 0.054435819, 0.15042377 -0.026133418 0.057998359, 0.15518968 -0.03850767 0.037817344, 0.15394151 -0.041707039 0.039259493, 0.15526041 -0.040578932 0.035641074, 0.156478 -0.039411485 0.031997785, 0.15741451 -0.035487056 0.031997874, 0.15307473 -0.037983179 0.044997752, 0.15079272 -0.041669637 0.048659563, 0.15161952 -0.043429762 0.044997543, 0.1564666 -0.032936573 0.037817821, 0.15582655 -0.030864269 0.041421235, 0.15105367 -0.037482113 0.050835386, 0.14897692 -0.033409745 0.057998106, 0.14812121 -0.037019342 0.057997972, 0.14985438 -0.039893597 0.052282184, 0.15433435 -0.032487988 0.044998094, 0.15441999 -0.032078445 0.04499808, 0.15229654 -0.03205952 0.050835758, 0.16195561 -0.030418873 0.0077846348, 0.16179873 -0.032273024 0.0019981265, 0.16256273 -0.028173566 0.0019982755, 0.16025065 -0.029243231 0.024405271, 0.15909509 -0.031714737 0.027998149, 0.16055621 -0.030757487 0.020798326, 0.15983996 -0.027716666 0.027998269, 0.1599392 -0.039678186 0.007784158, 0.15895462 -0.043127418 0.009226203, 0.15950803 -0.041782767 0.0056140423, 0.15996137 -0.040407568 0.0019976497, 0.16093153 -0.036351979 0.0019977987, 0.15937801 -0.039539248 0.014997631, 0.15784092 -0.043699592 0.01862824, 0.15786144 -0.045215994 0.014997393, 0.16125637 -0.033930898 0.007784456, 0.16144295 -0.031796873 0.011394173, 0.158666 -0.039363146 0.020797819, 0.15825014 -0.035692692 0.027997762, 0.15730575 -0.039648414 0.027997658, 0.1577173 -0.042159885 0.022244126, 0.16069052 -0.033812076 0.014997929, 0.16082744 -0.033155411 0.014998019, 0.15997258 -0.033661425 0.020798117, 0.14415975 -0.019565463 -0.072025895, 0.14569445 -0.021981001 -0.068743899, 0.14365666 -0.022969186 -0.072025999, 0.15556356 -0.021443725 -0.047001228, 0.15498722 -0.025273204 -0.047001496, 0.15319359 -0.022601902 -0.052842051, 0.14724129 -0.018641353 -0.066755071, 0.15054151 -0.019251108 -0.06000106, 0.14763597 -0.020958364 -0.065416813, 0.14458211 -0.016150832 -0.072025344, 0.15056555 -0.019062579 -0.060001031, 0.15192463 -0.020927995 -0.056441277, 0.14781298 -0.013373613 -0.066754684, 0.14492375 -0.012727171 -0.072025448, 0.1480245 -0.010785252 -0.066754416, 0.15304597 -0.019377053 -0.054284021, 0.15604506 -0.017601043 -0.047001272, 0.15115014 -0.013676167 -0.060000896, 0.1515421 -0.0082722306 -0.060000539, 0.15389709 -0.010691464 -0.054283619, 0.14983313 -0.0095405877 -0.063400537, 0.15364026 -0.013901889 -0.054283455, 0.15522115 -0.012215078 -0.050661057, 0.15643173 -0.013747752 -0.047000825, 0.15735278 -0.022692114 -0.041001469, 0.15758827 -0.024259657 -0.039422482, 0.15629882 -0.025494307 -0.043001488, 0.15688236 -0.021615535 -0.043001294, 0.157692 -0.02020067 -0.041001156, 0.15877315 -0.022997528 -0.035818577, 0.15736963 -0.017723411 -0.043001235, 0.1579919 -0.017704427 -0.041001111, 0.15916185 -0.020766348 -0.035505399, 0.15825211 -0.015203565 -0.041000918, 0.15776031 -0.013820559 -0.043000907, 0.16045135 -0.020920813 -0.030001253, 0.16150497 -0.021124691 -0.024498403, 0.16139115 -0.023998886 -0.02280356, 0.16097392 -0.022465676 -0.026410073, 0.15962413 -0.011624753 -0.037264496, 0.15996863 -0.01310575 -0.035529658, 0.16204131 -0.0234465 -0.019001365, 0.16183965 -0.026428312 -0.017001539, 0.16245429 -0.022341818 -0.017001331, 0.16240345 -0.020790994 -0.019001335, 0.16065007 -0.010231286 -0.03364563, 0.16143739 -0.010971546 -0.030000806, 0.16296573 -0.018240929 -0.017001003, 0.1627221 -0.018129855 -0.019001096, 0.16156898 -0.0088214874 -0.030000538, 0.1629971 -0.015463829 -0.019000858, 0.16254058 -0.01118049 -0.024245262, 0.16234013 -0.013217509 -0.024518073, 0.16301008 -0.012654603 -0.020629972, 0.16337356 -0.014128536 -0.017001092, 0.16052498 -0.020348966 -0.030001312, 0.16072568 -0.018779695 -0.02995646, 0.16306148 -0.014768183 -0.019000828, 0.16204138 -0.023448676 0.018998563, 0.16159104 -0.024915814 0.020629436, 0.1618396 -0.02643016 0.016998619, 0.16245419 -0.022343576 0.016998678, 0.16240355 -0.020793229 0.018998772, 0.16123693 -0.023389816 0.024245322, 0.16296566 -0.018242836 0.016998917, 0.16272204 -0.018131942 0.018998861, 0.16150492 -0.021127492 0.024496049, 0.16299704 -0.015466124 0.01899904, 0.16337362 -0.014130473 0.016999125, 0.16045149 -0.0209243 0.02999866, 0.15916173 -0.020770282 0.035503119, 0.15831178 -0.023509949 0.037260324, 0.1594339 -0.022230864 0.033641905, 0.16274111 -0.011772752 0.022799253, 0.1623401 -0.01322031 0.024516582, 0.15735288 -0.022696763 0.040998593, 0.15629883 -0.025498986 0.042998478, 0.15688236 -0.021620333 0.042998582, 0.15769212 -0.020205289 0.040998667, 0.16220811 -0.010298878 0.026406318, 0.16143742 -0.010974944 0.029999197, 0.15736954 -0.01772809 0.04299897, 0.1579919 -0.017709017 0.040998951, 0.16156903 -0.0088249147 0.029999465, 0.15825216 -0.015208095 0.040998995, 0.16004723 -0.011073232 0.035818905, 0.15996863 -0.013109863 0.035528332, 0.15895726 -0.01245746 0.039421991, 0.15776031 -0.013825297 0.042999133, 0.1605345 -0.020353526 0.029954016, 0.16072571 -0.018782914 0.029954165, 0.15833288 -0.014343411 0.040999055, 0.1628738 -0.022396624 -0.013001382, 0.16276312 -0.025121659 -0.0093957484, 0.16225676 -0.026498795 -0.013001621, 0.1628737 -0.022397965 0.012998581, 0.16225676 -0.026500165 0.012998253, 0.16301762 -0.024286836 0.0072272122, 0.16350785 -0.020729661 -0.00723207, 0.16359952 -0.021452308 -1.2516975e-06, 0.16316687 -0.02372545 -0.0057858229, 0.163387 -0.018280029 -0.013001144, 0.16368967 -0.020753235 -1.2814999e-06, 0.16335985 -0.022879153 0.0036150813, 0.16414465 -0.014867723 -0.0072316825, 0.16379622 -0.014151931 -0.013000786, 0.16438846 -0.011873424 -0.0072317123, 0.16357325 -0.020738751 0.0057852566, 0.1633869 -0.0182814 0.012998849, 0.16432738 -0.0148848 -9.8347664e-07, 0.16462351 -0.010439157 -0.0036187768, 0.16475457 -0.0089971423 -5.6624413e-07, 0.16449493 -0.01130119 0.0057857037, 0.16421041 -0.014874458 0.0057856143, 0.16419753 -0.012731165 0.0093951225, 0.16379616 -0.014153242 0.012999117, 0.16377391 0.014407814 -0.012999386, 0.16427247 0.011726379 -0.0093937218, 0.16408531 0.010271251 -0.012999624, 0.16377403 0.014406323 0.013000757, 0.16408531 0.010269821 0.013000429, 0.1643347 0.012596965 0.0072293878, 0.16402122 0.016173869 -0.0072298944, 0.1642713 0.015489876 8.6426735e-07, 0.1643554 0.013177454 -0.0057836175, 0.16335827 0.018535346 -0.012999028, 0.16420363 0.016191483 6.8545341e-07, 0.16435513 0.014045477 0.0036172271, 0.16333777 0.022030652 -0.0072297156, 0.16283871 0.022651047 -0.012998849, 0.16290919 0.025004268 -0.007229507, 0.16408683 0.016179591 0.0057872534, 0.16335838 0.018533856 0.013000935, 0.1635194 0.022054762 1.1324883e-06, 0.16262592 0.027889758 1.3411045e-06, 0.16288552 0.025585651 0.0057877302, 0.162819 0.026454747 -0.0036165714, 0.16340306 0.022038758 0.0057876408, 0.16291356 0.024125457 0.0093972385, 0.16283864 0.022649646 0.013001263, 0.15845762 0.012891263 -0.040999606, 0.15903591 0.011415452 -0.039420292, 0.15805364 0.00992468 -0.042999566, 0.15775937 0.013836145 -0.042999402, 0.15823396 0.015395612 -0.040999264, 0.15991038 0.012909383 -0.03581655, 0.15736844 0.017738879 -0.042998999, 0.1579708 0.017896056 -0.040998951, 0.15979268 0.01517123 -0.035503417, 0.15766788 0.020392209 -0.040998966, 0.15688081 0.021631002 -0.04299885, 0.16108419 0.015307605 -0.029999226, 0.1621567 0.015343249 -0.024496168, 0.16268533 0.012515634 -0.022801638, 0.16193739 0.013917774 -0.026408076, 0.15820909 0.024186552 -0.037262484, 0.15887465 0.022819251 -0.035527706, 0.16319622 0.013199091 -0.018999279, 0.16366294 0.010247052 -0.016999424, 0.16335286 0.014367968 -0.016999334, 0.16295832 0.015868545 -0.018999308, 0.15889928 0.025773346 -0.033643603, 0.15983149 0.025226593 -0.02999872, 0.16293901 0.018479645 -0.016999036, 0.16267677 0.018533885 -0.018998921, 0.15948148 0.027352184 -0.02999866, 0.16235155 0.02119422 -0.018998921, 0.16095361 0.025268465 -0.024243206, 0.1612114 0.023237973 -0.024516135, 0.16173913 0.023935795 -0.020628035, 0.16242161 0.0225797 -0.016998678, 0.16102859 0.015881509 -0.029999107, 0.16087539 0.017455995 -0.029954225, 0.16225974 0.021886557 -0.018998981, 0.16319631 0.013196766 0.019000679, 0.16308355 0.011666209 0.020631552, 0.16366298 0.010245234 0.017000437, 0.16335298 0.014365971 0.017000765, 0.16295829 0.015866429 0.019000769, 0.16239871 0.013075262 0.024247199, 0.16293897 0.018477917 0.017000943, 0.16267671 0.01853171 0.019000918, 0.1621567 0.015340418 0.024498016, 0.1623517 0.021191955 0.019001186, 0.16242161 0.022577733 0.017001301, 0.16108415 0.015304297 0.030000836, 0.1597926 0.015167236 0.035504997, 0.1595735 0.012307107 0.037262231, 0.16038296 0.013803899 0.033644021, 0.16128027 0.02473563 0.02280131, 0.16121137 0.023235172 0.02451849, 0.15845768 0.012886554 0.041000634, 0.15805371 0.0099198818 0.04300043, 0.1577594 0.013831317 0.043000549, 0.15823402 0.015390933 0.041000754, 0.16043259 0.026054025 0.026408374, 0.15983143 0.025223255 0.030001372, 0.15736844 0.01773423 0.043000847, 0.15797068 0.017891556 0.041000724, 0.15948154 0.027348876 0.030001253, 0.15766808 0.020387441 0.041000962, 0.1584982 0.024818182 0.035820901, 0.15887456 0.022815228 0.035529971, 0.15774336 0.023226231 0.039423823, 0.15688087 0.021626174 0.043001115, 0.16103812 0.015879095 0.029956222, 0.16087535 0.017452657 0.029956281, 0.15755425 0.021248668 0.041001171, 0.14489987 0.013003767 -0.072024047, 0.14693373 0.010990351 -0.068741918, 0.14516677 0.0095734894 -0.072024032, 0.15643543 0.013710141 -0.046999261, 0.15672582 0.0098484159 -0.046999544, 0.15438287 0.012053728 -0.052840173, 0.14769851 0.014590472 -0.066753253, 0.15105164 0.014730334 -0.059999242, 0.14859895 0.012419373 -0.065415025, 0.14455186 0.016426802 -0.072023615, 0.15103319 0.01491937 -0.059999198, 0.15277316 0.013403177 -0.05643937, 0.14708379 0.019853145 -0.066752687, 0.14412323 0.019840479 -0.072023496, 0.14671402 0.022423804 -0.066752583, 0.15352114 0.015164882 -0.054281861, 0.15604973 0.017563641 -0.046998978, 0.15040463 0.020300835 -0.059998974, 0.14958411 0.025656551 -0.059998617, 0.15241835 0.02382198 -0.054281637, 0.14820032 0.024039507 -0.063398764, 0.15288217 0.02063489 -0.054281592, 0.15404816 0.022631198 -0.050659105, 0.15556933 0.021406323 -0.046998844, 0.14817162 -0.0049083233 -0.067063227, 0.14532547 -0.0067402124 -0.072024912, 0.1454442 -0.0033015013 -0.072024807, 0.15061525 0.0078939795 -0.061999545, 0.15076175 0.0042566061 -0.061999813, 0.14814186 0.0057222843 -0.067064241, 0.14823872 -0.0019930005 -0.067064583, 0.15082045 0.00061684847 -0.061999977, 0.15079151 -0.0030234754 -0.062000275, 0.14548178 0.00013884902 -0.072024852, 0.14822417 0.0028849244 -0.067064166, 0.14543793 0.0035791993 -0.072024405, 0.15496342 0.0058534443 -0.052281827, 0.15261626 0.0042938292 -0.05799979, 0.15246689 0.0080006719 -0.057999745, 0.16032253 0.0069921911 -0.035644874, 0.16130266 0.0044683814 -0.031999812, 0.15939559 0.0054887533 -0.039263904, 0.16114053 0.0084996819 -0.031999707, 0.15504637 -0.0029134452 -0.052282274, 0.15551127 -0.0061500072 -0.050840393, 0.15413401 -0.004632622 -0.054439664, 0.15264444 -0.0031247139 -0.058000207, 0.15267548 0.00058469176 -0.058000177, 0.1576882 -0.0029635429 -0.045000196, 0.15748163 -0.0085974336 -0.045000508, 0.15868932 -0.0072299242 -0.041421697, 0.15505154 0.0026297271 -0.052281797, 0.15638003 0.0044836104 -0.048659623, 0.15946163 -0.0029973388 -0.039264426, 0.1613639 0.00043413043 -0.03200008, 0.16132432 -0.0036002696 -0.032000497, 0.15978901 -0.00584656 -0.037818015, 0.15769356 0.0026741028 -0.044999927, 0.15768601 0.0030923188 -0.044999942, 0.159467 0.0027036667 -0.039264098, 0.16313326 0.0063079298 -0.022244096, 0.16216296 0.0044856071 -0.027999789, 0.16199972 0.0085490644 -0.027999759, 0.1647298 0.007255584 -0.0056176782, 0.16492352 0.0045399666 -0.0019997954, 0.16459903 0.0058007836 -0.0092308223, 0.16475615 0.0087066591 -0.0019996166, 0.16322631 -0.0030632913 -0.022244513, 0.16334219 -0.0065946877 -0.020802408, 0.16281576 -0.005120784 -0.024409205, 0.16218396 -0.003647387 -0.028000444, 0.16222444 0.00041931868 -0.028000027, 0.16418028 -0.0030813515 -0.015000194, 0.16396494 -0.0089531839 -0.015000522, 0.16437185 -0.0075311065 -0.011394799, 0.1632314 0.0027783811 -0.022244066, 0.16370541 0.0048922896 -0.018628865, 0.16467202 -0.0030909777 -0.0092312098, 0.16498558 0.00037044287 -0.0020001829, 0.16494228 -0.0037994385 -0.0020002425, 0.16467454 -0.0061017573 -0.0077848732, 0.16418552 0.0027941167 -0.015000045, 0.16417256 0.0034651458 -0.014999956, 0.16467728 0.0028022528 -0.0092307925, 0.1597794 0.0060853362 0.03782022, 0.16130258 0.0044647455 0.032000214, 0.16114052 0.0084961951 0.032000482, 0.15261616 0.0042875111 0.058000267, 0.15554334 0.0053022504 0.050838113, 0.15406045 0.0066588223 0.054437861, 0.15246697 0.0079941452 0.05800049, 0.1598669 -0.0030092299 0.037819326, 0.15936199 -0.0064061284 0.03926149, 0.16039702 -0.0050129294 0.03564322, 0.16132438 -0.0036037564 0.031999618, 0.16136386 0.00043061376 0.031999975, 0.15768833 -0.0029685795 0.044999734, 0.15628384 -0.0070704222 0.048661411, 0.15748163 -0.0086024404 0.044999525, 0.15987231 0.0027062595 0.037819922, 0.15878713 0.004584223 0.04142338, 0.15560614 -0.0029298067 0.050837427, 0.15267552 0.00057831407 0.057999969, 0.15264447 -0.0031312406 0.057999894, 0.15497372 -0.0055476129 0.052284002, 0.15769355 0.0026690364 0.045000136, 0.15768585 0.0030875206 0.045000225, 0.15561141 0.002633363 0.050837755, 0.16466373 0.0063823462 0.0077867508, 0.16492358 0.0045396686 0.0020000339, 0.16475609 0.0087064803 0.0020003319, 0.16273952 0.0071491599 0.024407327, 0.16216309 0.0044823885 0.028000116, 0.1633746 0.0057408214 0.020800143, 0.16199972 0.0085458755 0.028000355, 0.16475827 -0.0030935109 0.007786274, 0.16456604 -0.0066753328 0.0092281401, 0.16480622 -0.0052411854 0.0056159496, 0.16494222 -0.0037996769 0.0019995868, 0.16498558 0.00037014484 0.0019999146, 0.16418028 -0.0030830801 0.014999777, 0.16396491 -0.0089547038 0.01499936, 0.1636073 -0.0074810088 0.018630236, 0.16476354 0.0028027296 0.007786572, 0.16447052 0.004924804 0.011396199, 0.16344658 -0.0030696988 0.020799786, 0.16222447 0.00041615963 0.027999938, 0.16218401 -0.0036504865 0.027999669, 0.16314431 -0.0060074925 0.022246152, 0.16418549 0.002792567 0.014999986, 0.16417268 0.0034633577 0.014999956, 0.16345182 0.0027796626 0.020800173, 0.15276112 -0.058918357 0.018996671, 0.15199549 -0.060248464 0.020627558, 0.15190108 -0.061780334 0.016996458, 0.15340951 -0.057932884 0.016996711, 0.15370511 -0.056409955 0.018996909, 0.15198994 -0.058681965 0.024243325, 0.15482064 -0.054048777 0.01699698, 0.15460779 -0.053886533 0.018996894, 0.15275477 -0.056536138 0.024493977, 0.15546907 -0.051348597 0.018997148, 0.15613344 -0.050130248 0.016997129, 0.15177293 -0.056103438 0.029996514, 0.15054987 -0.055666357 0.035501122, 0.14911166 -0.058148235 0.037258267, 0.15049021 -0.057150871 0.033639967, 0.15604141 -0.047690809 0.022797361, 0.15532838 -0.049012989 0.024514586, 0.14835769 -0.057141989 0.040996701, 0.14670658 -0.059639633 0.0429966, 0.14813857 -0.055987865 0.042996794, 0.14924279 -0.054788649 0.040996894, 0.15584971 -0.046135366 0.026404291, 0.15494786 -0.046622962 0.029997304, 0.14947963 -0.052301854 0.042996898, 0.15009052 -0.05242148 0.040996984, 0.15555479 -0.044556111 0.029997483, 0.15090072 -0.050041229 0.040997148, 0.15357104 -0.046409547 0.035816684, 0.15304112 -0.048377603 0.035526052, 0.15220037 -0.047516495 0.039419919, 0.15072912 -0.048583865 0.042997181, 0.15198089 -0.055565506 0.029952124, 0.15251687 -0.054077089 0.029952109, 0.15117188 -0.049216032 0.040997237, 0.15380636 -0.058077902 -0.013003439, 0.15309221 -0.060710013 -0.0093975067, 0.15229194 -0.061939865 -0.013003603, 0.1538064 -0.058079273 0.012996629, 0.15229212 -0.061941355 0.01299639, 0.15352626 -0.059952796 0.007225275, 0.15479538 -0.056593835 -0.0072340518, 0.1547242 -0.057318836 -3.3080578e-06, 0.15379642 -0.059438527 -0.0057876408, 0.15522271 -0.054178685 -0.013003185, 0.15496774 -0.056657463 -3.2484531e-06, 0.15417308 -0.058656514 0.0036129951, 0.15672071 -0.051020533 -0.0072337389, 0.15654022 -0.050245106 -0.013002962, 0.15762474 -0.048155516 -0.0072335601, 0.15485744 -0.0566172 0.0057831109, 0.15522259 -0.054180115 0.012996852, 0.15689509 -0.051077843 -2.9504299e-06, 0.15862179 -0.045432955 -2.682209e-06, 0.15785617 -0.047621578 0.0057839155, 0.15817308 -0.046809524 -0.0036206841, 0.15678349 -0.051041692 0.0057835281, 0.1572479 -0.04894942 0.0093930662, 0.15654022 -0.050246507 0.012997121, 0.14835767 -0.057137549 -0.041003287, 0.14823844 -0.058718026 -0.0394243, 0.14670664 -0.059634894 -0.0430035, 0.14813863 -0.055983216 -0.04300341, 0.14924276 -0.054784089 -0.041003197, 0.14967449 -0.057751209 -0.035820603, 0.14947961 -0.052297026 -0.043002933, 0.15009049 -0.052416921 -0.041003168, 0.15054983 -0.055662453 -0.035507277, 0.15090089 -0.050036848 -0.041002959, 0.15072905 -0.048578978 -0.043002814, 0.15177296 -0.0561001 -0.030003265, 0.15275469 -0.056533247 -0.024500385, 0.1520042 -0.059310019 -0.022805557, 0.15193863 -0.057722509 -0.026412085, 0.15303475 -0.046853006 -0.037266538, 0.15304111 -0.04837355 -0.03553161, 0.1527611 -0.058916211 -0.019003212, 0.15190095 -0.061778337 -0.017003655, 0.15340956 -0.057931095 -0.017003298, 0.15370509 -0.056407928 -0.019003198, 0.15434521 -0.045722812 -0.033647627, 0.154948 -0.046619713 -0.030002818, 0.15482056 -0.05404672 -0.017003179, 0.15460774 -0.053884327 -0.019003004, 0.15555489 -0.044552892 -0.030002683, 0.15546897 -0.051346451 -0.0190029, 0.15597723 -0.047068805 -0.024247274, 0.15532839 -0.049010217 -0.024520129, 0.15610686 -0.048610389 -0.020632103, 0.15613335 -0.050128251 -0.017002776, 0.15197185 -0.05555886 -0.03000325, 0.15251684 -0.054073721 -0.029958457, 0.15568674 -0.050682515 -0.019002795, 0.1361907 -0.051153272 -0.07202743, 0.13714966 -0.053849816 -0.068745717, 0.13494278 -0.054359674 -0.072027549, 0.14689091 -0.055522144 -0.047003135, 0.14547706 -0.059127539 -0.047003463, 0.14432283 -0.056123883 -0.052844062, 0.13940081 -0.05093804 -0.06675674, 0.1424828 -0.052267164 -0.060003072, 0.1392701 -0.053285062 -0.065418705, 0.13736248 -0.047918409 -0.0720274, 0.14254798 -0.052088648 -0.060003057, 0.14345789 -0.05420962 -0.056443185, 0.1411303 -0.045929879 -0.066756397, 0.13845722 -0.044656605 -0.072027072, 0.14191252 -0.043453425 -0.066756338, 0.14489625 -0.052946955 -0.054285869, 0.14821553 -0.051883042 -0.047002971, 0.14431654 -0.046967238 -0.060002789, 0.14590123 -0.041786134 -0.060002491, 0.1476588 -0.044668645 -0.054285422, 0.14395273 -0.042642474 -0.063402414, 0.14669405 -0.047741443 -0.054285482, 0.14861074 -0.046448797 -0.050663099, 0.14944986 -0.04821232 -0.047002733, 0.14971435 -0.065097481 -0.022248104, 0.14804946 -0.066318452 -0.028004065, 0.14966537 -0.062586486 -0.028003529, 0.15156439 -0.06493637 -0.0056218505, 0.15056075 -0.067467302 -0.0020038188, 0.15081513 -0.066190362 -0.0092347562, 0.15221773 -0.063640594 -0.0020038486, 0.1457323 -0.07358098 -0.022248417, 0.1443045 -0.076812863 -0.020806238, 0.14446957 -0.075256735 -0.024412915, 0.14453956 -0.073655069 -0.028004035, 0.14634037 -0.070008695 -0.028004125, 0.146584 -0.074011207 -0.015004262, 0.14384222 -0.079208046 -0.015004426, 0.14482608 -0.078103513 -0.011398822, 0.14827138 -0.068320066 -0.022248313, 0.14961575 -0.066621095 -0.01863277, 0.14702317 -0.074233532 -0.0092352182, 0.14880744 -0.071250796 -0.002003938, 0.14695932 -0.074989051 -0.0020042658, 0.14571904 -0.076947063 -0.0077887475, 0.14913808 -0.068719804 -0.015004039, 0.14941758 -0.0681099 -0.015003815, 0.14958476 -0.068926007 -0.0092348605, 0.14215565 -0.061962098 -0.052285612, 0.13936417 -0.062348694 -0.058003515, 0.14083789 -0.058944345 -0.05800344, 0.14747852 -0.06326142 -0.035648778, 0.14726663 -0.065960497 -0.032003671, 0.14599103 -0.064213723 -0.039267883, 0.14886983 -0.062258303 -0.032003552, 0.13842653 -0.069896549 -0.052286148, 0.13744119 -0.073014587 -0.050844252, 0.13685857 -0.071049809 -0.054443404, 0.13617073 -0.069044948 -0.058003962, 0.13780814 -0.065716296 -0.058003902, 0.14078531 -0.071088254 -0.045003995, 0.13983615 -0.075366348 -0.04142566, 0.13815466 -0.076074451 -0.045004457, 0.14083646 -0.064904779 -0.052285746, 0.14283766 -0.063810796 -0.048663303, 0.14236864 -0.071888119 -0.039268106, 0.14557151 -0.069621891 -0.03200388, 0.14378536 -0.073239535 -0.032004103, 0.14142725 -0.074597239 -0.037821844, 0.14323619 -0.06601122 -0.045003831, 0.14341085 -0.065631062 -0.045003876, 0.14484698 -0.066753924 -0.039268002, 0.15112627 -0.065694779 0.0077827573, 0.15056089 -0.06746763 0.0019960999, 0.15221773 -0.063640803 0.0019963682, 0.14972587 -0.064169139 0.024403498, 0.14804944 -0.066321522 0.027996123, 0.14968684 -0.065713406 0.020796284, 0.14966534 -0.062589496 0.027996421, 0.14710018 -0.074273348 0.0077821463, 0.1453727 -0.077416986 0.0092244744, 0.14621139 -0.076228976 0.005611971, 0.14695917 -0.07498917 0.0019955486, 0.14880744 -0.071251065 0.0019958466, 0.14658403 -0.074013054 0.014995664, 0.14384228 -0.079209864 0.014995366, 0.14415979 -0.077726811 0.018626362, 0.14966309 -0.068963051 0.0077826232, 0.15031984 -0.066924036 0.011392191, 0.1459291 -0.073682696 0.020795852, 0.1463405 -0.070011914 0.02799584, 0.14453958 -0.073658258 0.027995691, 0.14438188 -0.076198369 0.022242293, 0.14913803 -0.068721294 0.014995903, 0.14941742 -0.068111539 0.014996186, 0.14847159 -0.068414807 0.02079621, 0.14659764 -0.063843161 0.037816152, 0.14726669 -0.065964133 0.03199622, 0.14886971 -0.062261701 0.031996444, 0.13936403 -0.062355161 0.057996556, 0.14244151 -0.062710792 0.050834149, 0.14169428 -0.060845286 0.054434136, 0.14083785 -0.058950782 0.05799672, 0.14273046 -0.072075158 0.037815616, 0.14080168 -0.074916661 0.039257526, 0.14233854 -0.074110359 0.035639271, 0.1437854 -0.073243082 0.031995773, 0.14557149 -0.069625407 0.031996042, 0.14078531 -0.071093172 0.044995889, 0.13815463 -0.076079428 0.044995755, 0.13774018 -0.074179441 0.048657581, 0.14521512 -0.06692782 0.037816003, 0.14505245 -0.064765185 0.041419417, 0.1389264 -0.070154905 0.050833583, 0.13780823 -0.065722734 0.057996169, 0.13617079 -0.069051474 0.057996199, 0.13722083 -0.072239369 0.052280352, 0.14323618 -0.066016227 0.044996306, 0.1434108 -0.065636039 0.044996351, 0.14134492 -0.065145046 0.050833777, 0.12960647 -0.06608808 0.072020859, 0.1280075 -0.069134653 0.072020784, 0.13136673 -0.068718582 0.067058936, 0.13595256 -0.059127986 0.067061052, 0.13767713 -0.061584592 0.06199652, 0.13912319 -0.058243722 0.061996594, 0.13269284 -0.066121519 0.067059234, 0.13454498 -0.068156421 0.061996013, 0.13615082 -0.064889431 0.061996281, 0.13113312 -0.063004822 0.072021067, 0.13479622 -0.061720341 0.067059472, 0.13258627 -0.059886128 0.072021082, 0.13192315 -0.08871752 -0.04100512, 0.1314553 -0.090231895 -0.039425999, 0.12975787 -0.090784878 -0.043005258, 0.13196649 -0.087543398 -0.04300496, 0.13330987 -0.086620063 -0.041005135, 0.13307054 -0.089608908 -0.035822213, 0.13409422 -0.084248185 -0.043004826, 0.13466305 -0.084500819 -0.041005015, 0.13438883 -0.087767333 -0.035509229, 0.13598268 -0.082360715 -0.041004807, 0.13613962 -0.080901384 -0.043004707, 0.13548395 -0.088466138 -0.030005068, 0.13634476 -0.089106977 -0.024502009, 0.13499504 -0.091647118 -0.022807404, 0.13528441 -0.090084702 -0.026413858, 0.13877176 -0.079731673 -0.037268326, 0.1384394 -0.08121556 -0.035533413, 0.13582075 -0.091431618 -0.019005239, 0.13434529 -0.094030529 -0.017005444, 0.13667217 -0.090615392 -0.01700519, 0.13729917 -0.089196146 -0.01900515, 0.14030081 -0.078921288 -0.033649519, 0.14068894 -0.079929918 -0.030004501, 0.1389122 -0.087142497 -0.017005011, 0.13874076 -0.086936772 -0.019004926, 0.1417405 -0.078050077 -0.030004546, 0.14014527 -0.084654152 -0.019004732, 0.14159243 -0.080596834 -0.024248973, 0.14052798 -0.082345158 -0.024522096, 0.14137582 -0.082128763 -0.020633861, 0.14106397 -0.083614439 -0.017004743, 0.13579826 -0.087982684 -0.030005053, 0.13665992 -0.086656094 -0.029960126, 0.14050528 -0.084055394 -0.019004777, 0.13702646 -0.090846807 -0.013005197, 0.13574456 -0.09325403 -0.0093996376, 0.13469066 -0.094275087 -0.013005465, 0.13702644 -0.090848178 0.012994871, 0.13469067 -0.094276488 0.012994587, 0.13633633 -0.092612505 0.0072232187, 0.13832091 -0.089620024 -0.0072359741, 0.13809031 -0.09031114 -5.1707029e-06, 0.13671403 -0.092171192 -0.0057897121, 0.13927492 -0.087360531 -0.013004988, 0.13847491 -0.089720249 -5.3048134e-06, 0.13725552 -0.091492742 0.0036112517, 0.14143828 -0.084615082 -0.007235691, 0.14143476 -0.083818853 -0.013004884, 0.14295706 -0.082023025 -0.0072354823, 0.1383764 -0.08965683 0.0057815015, 0.13927495 -0.087362021 0.012995034, 0.14159554 -0.084709555 -4.8428774e-06, 0.14379132 -0.080832958 -0.0036227256, 0.14453512 -0.079590589 -4.4852495e-06, 0.14330159 -0.081553787 0.005781889, 0.14149486 -0.084649593 0.0057815462, 0.14241326 -0.082713127 0.0093913823, 0.14143476 -0.083820343 0.012995139, 0.13582079 -0.091433883 0.018994898, 0.13477843 -0.092560142 0.020625696, 0.13434537 -0.094032556 0.01699467, 0.13667218 -0.090617299 0.016994879, 0.13729925 -0.089198291 0.018994987, 0.1351217 -0.091031671 0.024241477, 0.13891211 -0.087144405 0.016995117, 0.1387409 -0.086938918 0.018995166, 0.13634479 -0.089109808 0.024492189, 0.14014535 -0.084656298 0.01899524, 0.14106406 -0.083616406 0.01699543, 0.13548389 -0.088469446 0.02999486, 0.13438877 -0.087771297 0.035499334, 0.13243426 -0.089870751 0.037256509, 0.13400026 -0.089205295 0.033638135, 0.14151715 -0.081217647 0.022795215, 0.14052786 -0.0823479 0.024512768, 0.13192326 -0.08872214 0.040994912, 0.12975778 -0.090789586 0.042994961, 0.13196656 -0.087548256 0.042994902, 0.13330993 -0.086624682 0.040994927, 0.14167659 -0.079658568 0.026402459, 0.14068894 -0.079933256 0.029995471, 0.13409421 -0.084252983 0.042995036, 0.13466306 -0.084505469 0.040995359, 0.1417405 -0.078053266 0.029995605, 0.13598262 -0.082365274 0.040995225, 0.13939393 -0.079418719 0.035814941, 0.13843951 -0.081219584 0.035524458, 0.13781144 -0.080193073 0.039418355, 0.13613963 -0.080906153 0.042995393, 0.13580629 -0.087991327 0.029950336, 0.13666001 -0.086659431 0.029950291, 0.13643062 -0.081621081 0.040995255, 0.1308527 -0.086821616 0.046995044, 0.1284167 -0.088047445 0.050657362, 0.12867209 -0.090021968 0.046994954, 0.1213927 -0.080184072 0.072019964, 0.11946258 -0.08303234 0.072019741, 0.12305185 -0.082987249 0.066747174, 0.12997209 -0.084185958 0.052833617, 0.12727918 -0.082668573 0.059995279, 0.12806006 -0.08602038 0.05428037, 0.13295378 -0.083568513 0.046995386, 0.12738256 -0.08250922 0.059995338, 0.12520163 -0.082864374 0.063393429, 0.13289413 -0.079493165 0.052833915, 0.13497409 -0.080264509 0.046995431, 0.13424186 -0.077195555 0.052834034, 0.12515622 -0.081067502 0.065413132, 0.12325463 -0.077290744 0.072020113, 0.13024627 -0.077909738 0.059995517, 0.13364612 -0.075223923 0.056434065, 0.13294412 -0.073211133 0.05999583, 0.12956168 -0.073822737 0.065413684, 0.1279701 -0.076548547 0.065413311, 0.12734464 -0.074121028 0.068739876, 0.12504785 -0.07435444 0.072020233, 0.13271905 -0.097676516 0.0077809244, 0.13177295 -0.099278837 0.0019941926, 0.13423993 -0.095916897 0.0019944906, 0.13169317 -0.095877409 0.024401531, 0.12957996 -0.097602993 0.027994484, 0.13131157 -0.097374469 0.020794675, 0.13198583 -0.094324112 0.027994618, 0.12688483 -0.10514408 0.0077806711, 0.12450123 -0.10782444 0.009222731, 0.12558305 -0.10685277 0.005610317, 0.12658803 -0.10581067 0.0019939542, 0.12922175 -0.10257748 0.0019941926, 0.12643957 -0.10477543 0.014993921, 0.12261026 -0.10923186 0.014993638, 0.12324968 -0.1078566 0.018624693, 0.13056526 -0.1005373 0.0077809095, 0.13165914 -0.098695368 0.011390373, 0.12587455 -0.10430753 0.020794183, 0.12709264 -0.10082039 0.027994245, 0.12452553 -0.10397449 0.027993977, 0.12380645 -0.10641578 0.022240683, 0.13010709 -0.10018477 0.014994189, 0.13051529 -0.09965238 0.014994264, 0.12952572 -0.099737644 0.020794332, 0.13147499 -0.096779883 -0.022249892, 0.12957983 -0.097599775 -0.028005451, 0.13198574 -0.094320893 -0.028005421, 0.13331448 -0.097034544 -0.0056236088, 0.13177305 -0.099278718 -0.002005741, 0.13230513 -0.09809044 -0.009236604, 0.13423997 -0.095916629 -0.0020054579, 0.12570475 -0.10416439 -0.022250339, 0.12359372 -0.10699773 -0.02080819, 0.12410089 -0.10551733 -0.024414614, 0.1245255 -0.10397133 -0.028005868, 0.12709267 -0.10081729 -0.028005883, 0.12643959 -0.10477367 -0.015005961, 0.12381516 -0.10837218 -0.011400491, 0.12261027 -0.10923016 -0.015006095, 0.12935092 -0.099600524 -0.022249982, 0.13103975 -0.098243505 -0.018634841, 0.12681833 -0.10508791 -0.009237051, 0.12922181 -0.10257727 -0.0020058602, 0.12658805 -0.1058104 -0.0020060837, 0.12494318 -0.10744339 -0.0077902377, 0.13010699 -0.10018304 -0.015005633, 0.13051526 -0.099650651 -0.015005678, 0.13049679 -0.10048366 -0.0092366338, 0.12480307 -0.092041105 -0.052287444, 0.12199545 -0.091796905 -0.058005124, 0.12418969 -0.088805795 -0.058005065, 0.12970343 -0.094492286 -0.035650492, 0.12889637 -0.097076744 -0.032005519, 0.12804143 -0.095089793 -0.039269611, 0.13128312 -0.093823791 -0.032005504, 0.11940177 -0.098946989 -0.052287787, 0.11774737 -0.10176748 -0.050845832, 0.11761647 -0.099722326 -0.054444999, 0.11739194 -0.097614646 -0.058005452, 0.1197291 -0.094733745 -0.058005437, 0.12143646 -0.10063365 -0.045005739, 0.11955912 -0.10459316 -0.04142715, 0.11776204 -0.10490936 -0.045005947, 0.12286192 -0.094616324 -0.052287459, 0.12505649 -0.093995273 -0.048665121, 0.12280202 -0.10176569 -0.039270028, 0.12642908 -0.10026902 -0.032005697, 0.12388256 -0.10339844 -0.032005966, 0.1212814 -0.10419735 -0.037823364, 0.12495551 -0.096229166 -0.045005441, 0.12521034 -0.095897406 -0.045005336, 0.12636068 -0.097311795 -0.039269567, 0.11165187 -0.093271405 0.072019175, 0.10941507 -0.095885754 0.072019175, 0.11278266 -0.096227527 0.067057431, 0.11938761 -0.087897897 0.067059547, 0.12052213 -0.090676636 0.061994761, 0.12267542 -0.087741554 0.061995119, 0.11465329 -0.093990803 0.067057565, 0.11600623 -0.09638676 0.061994553, 0.11829866 -0.093558908 0.061994612, 0.11382626 -0.09060505 0.072019517, 0.11768335 -0.090167999 0.067057908, 0.1159371 -0.087888002 0.072019622, 0.12871617 -0.094863594 0.037814453, 0.12889633 -0.097080231 0.031994492, 0.1312831 -0.093827397 0.03199473, 0.12199537 -0.091803312 0.057994798, 0.12491642 -0.09283486 0.05083245, 0.12460308 -0.090849727 0.054432392, 0.12418978 -0.088812351 0.057995006, 0.12311424 -0.10202855 0.037813976, 0.12060145 -0.10436973 0.039255753, 0.12227921 -0.10392568 0.035637408, 0.12388256 -0.10340199 0.031994119, 0.12642899 -0.10027248 0.031994283, 0.12143643 -0.10063866 0.044994339, 0.11778101 -0.10296977 0.048655942, 0.11776204 -0.10491437 0.044994116, 0.12668195 -0.097563446 0.037814036, 0.12700455 -0.095418721 0.041417673, 0.11983299 -0.09931016 0.050831825, 0.11972903 -0.094740242 0.057994783, 0.11739187 -0.097621083 0.05799453, 0.11770621 -0.1009627 0.052278697, 0.12495551 -0.096234232 0.044994563, 0.12521033 -0.095902264 0.044994682, 0.12330556 -0.094963819 0.050832212, -0.013197958 0.16319516 0.019009128, -0.01166752 0.1630823 0.020640001, -0.010246217 0.16366199 0.017009109, -0.014367104 0.1633518 0.01700902, -0.015867516 0.16295734 0.019009113, -0.013076693 0.16239727 0.024255618, -0.018478841 0.16293788 0.01700899, -0.018532827 0.16267565 0.019009277, -0.015341952 0.1621553 0.024506286, -0.021193117 0.16235054 0.019009113, -0.022578925 0.16242051 0.017009169, -0.015306056 0.16108251 0.030008867, -0.015169203 0.15979066 0.035513267, -0.012309298 0.15957132 0.037270501, -0.013805807 0.16038093 0.033652067, -0.024737 0.16127884 0.022808999, -0.023236692 0.16120979 0.024526373, -0.012888968 0.15845531 0.04100877, -0.0099224448 0.15805116 0.0430087, -0.013833955 0.15775698 0.043008685, -0.015393287 0.15823171 0.041008726, -0.02605556 0.160431 0.02641578, -0.025225207 0.1598298 0.030008808, -0.017736658 0.15736595 0.043008566, -0.017893746 0.15796837 0.041008741, -0.027350545 0.15947974 0.030008629, -0.02038984 0.15766576 0.041008785, -0.024820253 0.15849623 0.035828203, -0.022817165 0.1588726 0.035537869, -0.023228467 0.15774116 0.039431438, -0.021628827 0.15687856 0.043008745, -0.015880868 0.16103652 0.029964313, -0.017454386 0.16087347 0.029964343, -0.021250948 0.15755191 0.041008741, -0.014407292 0.16377467 -0.012990862, -0.011725977 0.16427287 -0.0093850493, -0.010270551 0.16408598 -0.012990981, -0.014407292 0.16377318 0.013009176, -0.010270536 0.16408464 0.013009116, -0.012597322 0.16433442 0.0072377771, -0.016173616 0.16402158 -0.0072217137, -0.015490055 0.16427135 9.059906e-06, -0.013177335 0.16435584 -0.0057752579, -0.018534809 0.16335899 -0.012990832, -0.016191572 0.16420364 9.0301037e-06, -0.014045745 0.16435483 0.0036254376, -0.022030413 0.16333801 -0.0072216839, -0.02265048 0.16283935 -0.012990907, -0.025003895 0.16290954 -0.0072218329, -0.016180128 0.16408649 0.005795598, -0.018534824 0.16335756 0.013009056, -0.022054806 0.16351932 9.1195107e-06, -0.027889863 0.16262573 9.1046095e-06, -0.025586009 0.16288513 0.0057956129, -0.026454613 0.16281924 -0.0036089569, -0.02203919 0.16340271 0.0057956427, -0.024126023 0.1629132 0.0094051361, -0.02265045 0.16283786 0.013009056, -0.012889013 0.15845993 -0.040991291, -0.011413157 0.15903822 -0.039412096, -0.0099223703 0.15805584 -0.042991325, -0.01383394 0.15776178 -0.042991325, -0.015393272 0.15823621 -0.040991232, -0.01290758 0.15991229 -0.03580831, -0.017736748 0.15737072 -0.042991325, -0.017893791 0.15797296 -0.040991217, -0.015169263 0.1597946 -0.035495296, -0.020389989 0.15767029 -0.040991455, -0.021628797 0.15688318 -0.042991295, -0.015305921 0.16108581 -0.02999115, -0.015342027 0.16215804 -0.024488017, -0.012514502 0.16268659 -0.02279301, -0.013916373 0.16193876 -0.026399806, -0.024184451 0.15821132 -0.037254974, -0.022817314 0.15887663 -0.035520047, -0.013197958 0.16319725 -0.018990904, -0.010246173 0.16366389 -0.01699093, -0.014367059 0.16335365 -0.016990989, -0.015867427 0.16295934 -0.018991053, -0.025771514 0.15890104 -0.033636093, -0.025225013 0.15983298 -0.029991195, -0.01847887 0.16293979 -0.0169909, -0.018532723 0.16267782 -0.018991023, -0.027350649 0.15948313 -0.02999115, -0.021193132 0.16235274 -0.018990979, -0.025267303 0.16095492 -0.024235681, -0.023236647 0.16121262 -0.024508461, -0.023934737 0.16174027 -0.020620227, -0.022578865 0.16242233 -0.016991004, -0.015879944 0.16103026 -0.02999115, -0.01745449 0.16087696 -0.029946193, -0.021885693 0.1622608 -0.018990844, -0.012999788 0.14490381 -0.072016522, -0.010986522 0.14693746 -0.068734273, -0.0095696449 0.14517063 -0.072016537, -0.013707578 0.15643799 -0.046991393, -0.0098458529 0.15672851 -0.046991199, -0.012050837 0.15438578 -0.052832276, -0.014586821 0.14770228 -0.066745535, -0.014727011 0.15105489 -0.059991613, -0.012415662 0.14860266 -0.06540741, -0.016422957 0.14455596 -0.072016522, -0.014916182 0.15103644 -0.059991583, -0.013400033 0.15277633 -0.056431621, -0.019849524 0.14708751 -0.066745505, -0.019836619 0.14412701 -0.072016492, -0.022420034 0.14671767 -0.066745594, -0.015161812 0.15352416 -0.054274261, -0.017561048 0.15605241 -0.046991423, -0.020297617 0.15040767 -0.059991613, -0.025653198 0.14958742 -0.059991553, -0.023819029 0.15242127 -0.05427447, -0.02403605 0.14820364 -0.06339182, -0.020632029 0.15288517 -0.054274336, -0.022628486 0.15405107 -0.05065167, -0.021403939 0.155572 -0.046991527, 0.0049119294 0.14817524 -0.067054644, 0.0067441463 0.14532927 -0.072016329, 0.0033053607 0.14544827 -0.072016373, -0.0078906119 0.15061879 -0.061991632, -0.0042532682 0.1507653 -0.061991602, -0.0057187527 0.14814571 -0.067056, 0.0019966811 0.14824241 -0.067056015, -0.0006134063 0.15082395 -0.061991572, 0.0030267686 0.1507948 -0.061991677, -0.00013482571 0.14548573 -0.072016522, -0.0028813481 0.14822781 -0.067056119, -0.0035752505 0.14544186 -0.072016373, -0.005850479 0.15496635 -0.052273631, -0.0042905807 0.1526193 -0.057991564, -0.0079974085 0.15247014 -0.057991683, -0.0069901496 0.16032436 -0.03563644, -0.0044665039 0.16130435 -0.031990901, -0.0054867119 0.1593976 -0.039255247, -0.0084979981 0.16114232 -0.03199099, 0.0029163361 0.15504929 -0.052273661, 0.0061527789 0.15551409 -0.050831243, 0.0046356767 0.15413699 -0.054430693, 0.0031279922 0.15264761 -0.057991534, -0.00058159232 0.1526787 -0.057991683, 0.0029660314 0.15769082 -0.044991121, 0.008599937 0.15748405 -0.04499124, 0.0072321892 0.15869147 -0.041412383, -0.0026268661 0.15505448 -0.052273363, -0.004480958 0.15638274 -0.048651233, 0.0029994398 0.15946364 -0.039255321, -0.00043238699 0.1613656 -0.031991124, 0.0036019832 0.16132602 -0.031991199, 0.0058486313 0.15979099 -0.037808746, -0.0026716143 0.15769607 -0.0449913, -0.003090024 0.15768844 -0.044991165, -0.0027015954 0.15946901 -0.039255261, -0.0063828677 0.16466326 0.0077955425, -0.0045399368 0.16492346 0.0020091385, -0.0087065548 0.16475594 0.0020090789, -0.0071506053 0.16273811 0.024416134, -0.0044839978 0.16216141 0.028008878, -0.0057421327 0.16337344 0.020809039, -0.0085474104 0.16199812 0.028008848, 0.0030931383 0.16475779 0.0077956319, 0.0066748261 0.16456538 0.0092379749, 0.0052408874 0.16480586 0.005625546, 0.0037995577 0.1649422 0.0020090044, -0.00037029386 0.16498548 0.0020093024, 0.0030822754 0.16417938 0.015009031, 0.0074798763 0.16360629 0.018639907, 0.0089538395 0.16396406 0.015009031, -0.0028033108 0.16476291 0.0077955574, -0.0049254894 0.16446978 0.011405095, 0.0030682981 0.16344556 0.020809144, -0.00041763484 0.16222295 0.028008878, 0.0036488324 0.16218245 0.028009027, 0.006006062 0.16314298 0.022255525, -0.0027933419 0.16418442 0.015009135, -0.0034642369 0.16417179 0.015009165, -0.0027810037 0.1634506 0.020809248, -0.0063068867 0.1631344 -0.022235155, -0.0044841021 0.16216463 -0.027991116, -0.0085474402 0.16200119 -0.027991131, -0.0072554648 0.16473001 -0.0056089461, -0.0045398921 0.16492367 -0.0019907504, -0.0058004111 0.16459954 -0.0092218667, -0.0087066889 0.16475621 -0.0019908845, 0.0030642748 0.16322741 -0.022235259, 0.0065956265 0.16334322 -0.020792946, 0.0051221848 0.16281709 -0.024399653, 0.0036487877 0.16218552 -0.027990907, -0.00041770935 0.16222602 -0.027990937, 0.0030821413 0.16418111 -0.014990941, 0.0089538842 0.1639657 -0.014990911, 0.007531777 0.16437247 -0.011385098, -0.0027772784 0.16323242 -0.022235453, -0.0048913807 0.16370648 -0.018619999, 0.00309138 0.1646724 -0.009221673, -0.00037023425 0.1649856 -0.0019908398, 0.0037995726 0.16494235 -0.0019908249, 0.0061020851 0.16467491 -0.0077751577, -0.0027935803 0.16418636 -0.01499097, -0.0034643561 0.16417348 -0.014990926, -0.002801761 0.16467759 -0.0092219561, -0.006087631 0.15977716 0.037828535, -0.004466638 0.16130096 0.032009006, -0.0084979236 0.16113877 0.032008842, -0.0042907596 0.15261292 0.058008224, -0.0053052306 0.1555405 0.050846308, -0.0066619664 0.15405732 0.054446086, -0.007997334 0.15246364 0.058008537, 0.0030070096 0.15986472 0.03782858, 0.0064039081 0.15935969 0.039270744, 0.0050109327 0.16039497 0.03565225, 0.0036020428 0.16132247 0.032008991, -0.0004324764 0.16136217 0.032008961, 0.0029660463 0.15768588 0.045008793, 0.0085999221 0.15747905 0.045008928, 0.0070676059 0.15628105 0.048670441, -0.0027085245 0.15987 0.037828565, -0.0045865774 0.15878478 0.041431725, 0.0029268265 0.15560329 0.050846398, -0.00058159232 0.15267229 0.058008417, 0.0031279773 0.15264112 0.058008552, 0.0055449158 0.15497079 0.052293032, -0.0026716292 0.15769112 0.045008764, -0.0030899346 0.1576834 0.045008734, -0.0026362985 0.15560845 0.050846338, -0.049181566 0.15616655 0.019008577, -0.047664478 0.1563971 0.020639658, -0.0464077 0.15727875 0.017008692, -0.050356403 0.15605921 0.017008677, -0.051731363 0.15534079 0.019008592, -0.048885912 0.15541586 0.024255216, -0.05427289 0.15474069 0.017008647, -0.054267064 0.15447313 0.019008622, -0.051040486 0.15467575 0.02450572, -0.056788355 0.15356413 0.019008458, -0.058154911 0.15332401 0.017008454, -0.050766826 0.15363789 0.03000845, -0.050346151 0.15240872 0.03551282, -0.047509015 0.15283138 0.037270173, -0.049148113 0.15328771 0.03365165, -0.060005218 0.15173081 0.022808403, -0.058526993 0.15199727 0.024525747, -0.047825918 0.1516144 0.041008309, -0.044843987 0.15188038 0.043008298, -0.048591793 0.15072328 0.043008283, -0.050217643 0.15083909 0.04100813, -0.061101973 0.1506108 0.026415363, -0.060158491 0.15020934 0.030008242, -0.052309752 0.14947352 0.043008238, -0.052597061 0.15002602 0.041008398, -0.062152818 0.14939508 0.030008316, -0.054962993 0.14917541 0.041008234, -0.059467092 0.14899927 0.035827816, -0.057598025 0.14981198 0.035537228, -0.057747185 0.14861733 0.039430946, -0.055995703 0.14813221 0.043008029, -0.051316977 0.15346509 0.029963851, -0.052814931 0.1529561 0.029963896, -0.055777267 0.14887294 0.041008145, -0.044917181 0.13837811 -0.07201694, -0.043407053 0.14080882 -0.068734571, -0.041632235 0.13940158 -0.072016791, -0.048174188 0.14946553 -0.046991751, -0.044473812 0.15060812 -0.046991572, -0.046102121 0.14783353 -0.052832648, -0.047087222 0.14075333 -0.066745952, -0.047970071 0.14399081 -0.059991971, -0.045170784 0.14211428 -0.065407768, -0.04817687 0.1372771 -0.072017133, -0.048150241 0.14393055 -0.059991971, -0.047059387 0.14596424 -0.056432039, -0.052081034 0.13898286 -0.066745996, -0.051409706 0.13609949 -0.07201691, -0.054504871 0.13805032 -0.066746145, -0.048943326 0.14630127 -0.054274559, -0.051845118 0.14823219 -0.04699184, -0.053256869 0.14212012 -0.059992194, -0.058295608 0.14012867 -0.059992164, -0.05713819 0.14329961 -0.054274902, -0.056411117 0.1391395 -0.063392147, -0.054134205 0.14446107 -0.054274708, -0.056340098 0.14515337 -0.050652236, -0.055484593 0.14690858 -0.046991765, -0.050489172 0.15646255 -0.012991324, -0.047986135 0.15754494 -0.0093854517, -0.046525359 0.15768647 -0.012991264, -0.050489113 0.15646106 0.013008609, -0.046525478 0.15768522 0.013008758, -0.048849463 0.15741098 0.0072374493, -0.052266225 0.15631017 -0.0072221011, -0.051655367 0.15670586 8.6575747e-06, -0.049419269 0.1573028 -0.005775556, -0.054420635 0.15513891 -0.012991503, -0.05232431 0.15648368 8.687377e-06, -0.050266176 0.15710869 0.0036251694, -0.05782409 0.15434062 -0.0072223544, -0.058317587 0.1537163 -0.012991428, -0.060627654 0.15326113 -0.0072224587, -0.052287251 0.15637207 0.0057951063, -0.054420725 0.15513742 0.01300846, -0.057888448 0.15451196 8.59797e-06, -0.06337826 0.15234235 8.4340572e-06, -0.061189964 0.15310776 0.005795002, -0.062022105 0.15285033 -0.0036095679, -0.057847202 0.15440166 0.005795151, -0.059772685 0.15345997 0.0094044805, -0.058317587 0.15371501 0.013008624, -0.047825933 0.15161899 -0.04099156, -0.046515852 0.15251112 -0.039412498, -0.044843942 0.15188524 -0.042991668, -0.048591748 0.15072805 -0.042991579, -0.050217748 0.15084365 -0.04099156, -0.048167229 0.15303084 -0.035808697, -0.052309766 0.14947832 -0.042991713, -0.052597031 0.15003061 -0.040991724, -0.050346181 0.15241274 -0.03549552, -0.054963067 0.14918 -0.040991887, -0.055995673 0.14813697 -0.042991772, -0.050766796 0.15364119 -0.029991597, -0.05104056 0.15467858 -0.024488404, -0.048401609 0.15582299 -0.022793695, -0.049601927 0.15478209 -0.02640003, -0.058783054 0.14886302 -0.03725554, -0.057598114 0.1498161 -0.035520673, -0.049181744 0.15616888 -0.018991172, -0.046407729 0.15728045 -0.016991392, -0.050356418 0.15606117 -0.016991407, -0.051731333 0.15534282 -0.018991336, -0.060483798 0.14918256 -0.0336366, -0.06015864 0.15021265 -0.029991806, -0.05427292 0.15474278 -0.016991347, -0.054267049 0.15447518 -0.018991545, -0.062152848 0.14939842 -0.029991761, -0.056788296 0.15356627 -0.018991515, -0.060449362 0.15129685 -0.024236053, -0.058526948 0.15200001 -0.024508938, -0.059324861 0.1523591 -0.020620763, -0.05815509 0.15332592 -0.016991496, -0.051313981 0.15345931 -0.029991582, -0.052814931 0.15295944 -0.029946715, -0.057443142 0.15332264 -0.01899147, -0.041489229 0.1544165 0.037828401, -0.040247783 0.15626276 0.032008648, -0.044142082 0.15520769 0.032008722, -0.038143486 0.14783165 0.058008209, -0.039783895 0.15046006 0.050846204, -0.040776625 0.14871219 0.054445833, -0.041723996 0.14686146 0.058008224, -0.032642141 0.1565257 0.037828296, -0.029217869 0.15678924 0.03927055, -0.030806512 0.1574885 0.03565222, -0.032386377 0.15807918 0.032008663, -0.03632845 0.15722013 0.032008782, -0.032197282 0.1543923 0.045008525, -0.027886003 0.15393528 0.048670337, -0.026658699 0.15544432 0.045008674, -0.038215429 0.15525901 0.037828192, -0.039805129 0.15378299 0.041431516, -0.031772166 0.15235329 0.050846115, -0.034540445 0.14871478 0.058008343, -0.030916989 0.14951026 0.058008358, -0.02907899 0.15231913 0.052292898, -0.037694752 0.15314278 0.04500854, -0.038100913 0.15304232 0.045008659, -0.037197009 0.15112036 0.050845847, -0.04286392 0.15911439 0.0077953488, -0.041125 0.15977824 0.0020088255, -0.045149967 0.15868783 0.0020086467, -0.043184251 0.15706676 0.024415568, -0.04045628 0.15709803 0.028008625, -0.041952461 0.1579996 0.02080895, -0.044381529 0.15603435 0.028008565, -0.033646643 0.1613152 0.0077954978, -0.030111879 0.16192469 0.0092377365, -0.031563416 0.16184002 0.0056253225, -0.03299886 0.16165215 0.0020087808, -0.037073821 0.16076645 0.0020089, -0.033528671 0.16074893 0.015008897, -0.029113591 0.16116855 0.018639818, -0.027756199 0.16184554 0.015008852, -0.039396301 0.16000822 0.0077954829, -0.041400164 0.1592502 0.011404887, -0.03337881 0.16003022 0.02080898, -0.036505669 0.15806273 0.028008714, -0.032531947 0.15892813 0.02800864, -0.030447364 0.16038901 0.022255436, -0.039258257 0.15944666 0.015008777, -0.039909333 0.1592848 0.015008762, -0.039082706 0.15873361 0.020808905, -0.042449281 0.15764087 -0.022235677, -0.040456355 0.15710112 -0.027991295, -0.044381633 0.15603766 -0.027991325, -0.04372938 0.15898544 -0.0056092888, -0.04112494 0.1597783 -0.0019911975, -0.042281672 0.15918183 -0.0092220753, -0.045149878 0.15868798 -0.0019911975, -0.033333793 0.15981668 -0.022235513, -0.029916793 0.16071555 -0.020793244, -0.031236231 0.15987471 -0.024399757, -0.032532007 0.15893114 -0.02799125, -0.03650561 0.15806589 -0.027991176, -0.033528596 0.16075066 -0.014991134, -0.029233366 0.16192716 -0.011385158, -0.027756214 0.1618472 -0.014991164, -0.039029941 0.15852189 -0.022235498, -0.041196749 0.15851367 -0.018620402, -0.033628955 0.1612317 -0.0092219412, -0.037073791 0.16076669 -0.0019911379, -0.03299886 0.16165239 -0.0019909889, -0.030694455 0.16190413 -0.0077753216, -0.039258182 0.15944824 -0.014991164, -0.039909154 0.15928632 -0.014991298, -0.039375603 0.15992531 -0.0092221051, -0.04018645 0.14977938 -0.052273929, -0.038143486 0.14783818 -0.057991907, -0.041724056 0.14686805 -0.057991832, -0.04249014 0.15474939 -0.035636589, -0.040247858 0.1562663 -0.031991333, -0.040818065 0.15418044 -0.039255634, -0.044141993 0.15521118 -0.031991318, -0.031657726 0.15181077 -0.052273601, -0.028605849 0.15298405 -0.050831437, -0.029778659 0.15130404 -0.054431051, -0.030917048 0.14951664 -0.057991624, -0.03454037 0.14872128 -0.057991713, -0.032197326 0.15439728 -0.044991434, -0.028260902 0.15632215 -0.041412532, -0.026658639 0.15544942 -0.044991374, -0.037063226 0.15058252 -0.052273646, -0.039166331 0.15146479 -0.048651531, -0.03255932 0.15613312 -0.039255485, -0.036328495 0.15722379 -0.031991318, -0.032386348 0.15808278 -0.031991139, -0.029854476 0.15708619 -0.037808746, -0.037694693 0.15314788 -0.044991493, -0.038100824 0.15304735 -0.044991612, -0.038118646 0.15486971 -0.039255485, -0.028182447 0.1455532 -0.067054898, -0.025762931 0.14318651 -0.072016641, -0.029141754 0.14253721 -0.072016567, -0.041207716 0.14508659 -0.061991975, -0.037694126 0.14603886 -0.061991975, -0.038539827 0.14315882 -0.067056417, -0.031039685 0.14497009 -0.067056373, -0.034158751 0.14690614 -0.061991826, -0.030603305 0.14768767 -0.061991841, -0.032504335 0.14180821 -0.072016597, -0.035792023 0.14387047 -0.067056343, -0.035848618 0.14099988 -0.072016805, 0.022694275 0.15735519 -0.040991426, 0.024261817 0.15759042 -0.039412141, 0.025496498 0.15630123 -0.042991444, 0.021617681 0.15688473 -0.042991161, 0.020202935 0.15769434 -0.040991411, 0.022999495 0.15877518 -0.035808206, 0.017725617 0.15737206 -0.042991102, 0.017706543 0.15799412 -0.040991277, 0.020768225 0.15916383 -0.035495311, 0.01520586 0.15825438 -0.040991426, 0.013822764 0.15776268 -0.04299134, 0.020922333 0.16045299 -0.029991224, 0.021125957 0.16150633 -0.024488106, 0.024000153 0.16139233 -0.022793263, 0.022467077 0.16097531 -0.026399866, 0.01162672 0.1596261 -0.037254944, 0.013107747 0.15997067 -0.035520121, 0.023447469 0.16204244 -0.018991038, 0.026429117 0.16184074 -0.01699093, 0.022342548 0.16245511 -0.01699093, 0.020791978 0.16240448 -0.018990889, 0.01023306 0.16065189 -0.033635974, 0.01097323 0.16143882 -0.029991075, 0.018241748 0.16296649 -0.01699093, 0.018130779 0.16272318 -0.018990934, 0.0088232011 0.16157061 -0.029991075, 0.015464917 0.16299808 -0.018990904, 0.011181742 0.16254199 -0.024235502, 0.013218835 0.16234139 -0.024508432, 0.01265572 0.16301122 -0.020620137, 0.014129415 0.16337445 -0.01699093, 0.020350471 0.1605266 -0.02999106, 0.018781245 0.16072741 -0.029946208, 0.014769256 0.16306245 -0.018990904, 0.019569412 0.14416352 -0.072016567, 0.021984771 0.14569831 -0.068734273, 0.022972956 0.14366052 -0.072016448, 0.021446139 0.15556616 -0.046991378, 0.025275916 0.15498981 -0.046991408, 0.022604719 0.15319651 -0.052832365, 0.018644944 0.14724502 -0.066745803, 0.019254312 0.15054488 -0.059991732, 0.020962015 0.14763975 -0.065407529, 0.016154721 0.14458606 -0.072016582, 0.019065902 0.15056878 -0.059991568, 0.020931125 0.15192774 -0.056431487, 0.013377473 0.14781672 -0.066745624, 0.01273109 0.14492762 -0.072016552, 0.010788977 0.14802828 -0.066745579, 0.019380033 0.15304893 -0.054274395, 0.017603606 0.15604758 -0.046991363, 0.013679445 0.15115342 -0.059991732, 0.0082754642 0.15154541 -0.059991524, 0.010694474 0.15389997 -0.054274186, 0.0095441639 0.14983648 -0.06339179, 0.013904795 0.15364316 -0.054274276, 0.012217864 0.15522394 -0.050651774, 0.013750225 0.15643421 -0.046991244, 0.023447603 0.16204023 0.019009098, 0.024914488 0.16158956 0.020639896, 0.026429057 0.16183862 0.017008975, 0.022342607 0.16245317 0.017009139, 0.020791948 0.16240248 0.019009054, 0.023388132 0.16123548 0.024255648, 0.018241763 0.16296455 0.017009124, 0.018130884 0.16272098 0.019008934, 0.021125913 0.16150358 0.024506211, 0.015464887 0.16299593 0.019008979, 0.014129415 0.16337261 0.017009169, 0.020922452 0.16044962 0.030008867, 0.020768255 0.15915975 0.035513178, 0.023507819 0.15830958 0.037270382, 0.022228822 0.15943187 0.033651993, 0.01177147 0.16273972 0.022809193, 0.013218865 0.16233858 0.024526492, 0.022694349 0.15735063 0.041008681, 0.025496617 0.1562964 0.043008715, 0.021617725 0.15687993 0.04300867, 0.020202935 0.15768981 0.041008711, 0.010297373 0.16220641 0.02641587, 0.010973096 0.16143566 0.030008912, 0.017725721 0.15736732 0.043008655, 0.017706543 0.15798956 0.041008636, 0.0088230819 0.16156727 0.030008897, 0.01520583 0.15824983 0.0410088, 0.01107116 0.1600453 0.035828441, 0.013107896 0.15996659 0.035537869, 0.012455225 0.15895498 0.039431468, 0.013822764 0.15775791 0.04300864, 0.020351797 0.16053271 0.029964387, 0.018781289 0.16072416 0.029964313, 0.014340892 0.15833056 0.041008681, 0.022397161 0.16287428 -0.012991086, 0.025122046 0.16276354 -0.0093851686, 0.026499361 0.16225737 -0.012991101, 0.02239719 0.16287282 0.013008937, 0.02649945 0.16225594 0.013008937, 0.024286389 0.16301739 0.0072377026, 0.020729974 0.16350818 -0.0072218925, 0.021452263 0.16359946 8.9555979e-06, 0.023725674 0.16316721 -0.0057751685, 0.018280625 0.1633876 -0.012990952, 0.020753235 0.16368952 8.9406967e-06, 0.022878781 0.16335967 0.0036255568, 0.014868006 0.16414511 -0.0072216243, 0.014152423 0.16379687 -0.012990952, 0.011873782 0.16438884 -0.007221818, 0.020738408 0.16357279 0.0057955831, 0.018280566 0.1633862 0.013009027, 0.014884651 0.16432735 9.1642141e-06, 0.010439247 0.16462386 -0.0036088526, 0.0089969188 0.16475451 9.1046095e-06, 0.011300802 0.16449466 0.005795911, 0.014873862 0.16421011 0.005795598, 0.012730584 0.16419694 0.0094051659, 0.014152452 0.16379541 0.013009086, -0.15380642 0.058079064 -0.012996957, -0.15309215 0.060710758 -0.0093909353, -0.15229207 0.061941236 -0.012996644, -0.1538063 0.058077633 0.013003185, -0.15229191 0.061939657 0.013003334, -0.15352617 0.059951991 0.0072320104, -0.15479538 0.056594551 -0.0072277933, -0.15472429 0.057318658 3.0696392e-06, -0.15379651 0.059439242 -0.0057810843, -0.15522283 0.054179966 -0.012997165, -0.15496765 0.056657046 3.0994415e-06, -0.15417314 0.058655858 0.0036197156, -0.15672068 0.051021338 -0.0072280467, -0.15654027 0.050246358 -0.012997389, -0.15762483 0.048156202 -0.0072280467, -0.15485744 0.056616336 0.0057896972, -0.15522276 0.054178536 0.013002947, -0.15689513 0.051077634 2.7418137e-06, -0.15862186 0.045432657 2.6226044e-06, -0.15785621 0.047620803 0.005789116, -0.15817311 0.046809942 -0.0036156774, -0.15678354 0.051041067 0.0057892501, -0.15724795 0.048948228 0.0093988329, -0.15654023 0.050244927 0.013002649, -0.14835776 0.05714196 -0.040997177, -0.14823848 0.058722436 -0.039417744, -0.14670664 0.059639394 -0.042996764, -0.14813849 0.055987656 -0.042996854, -0.14924286 0.05478853 -0.040997073, -0.14967449 0.057755202 -0.035814077, -0.14947978 0.052301645 -0.042997211, -0.15009053 0.052421361 -0.040997148, -0.15055002 0.055666417 -0.035500914, -0.15090087 0.050041258 -0.040997267, -0.15072905 0.048583478 -0.042997286, -0.15177284 0.05610314 -0.029997036, -0.15275477 0.056535929 -0.024493948, -0.15200424 0.059312612 -0.022798955, -0.15193857 0.057725132 -0.026405632, -0.15303494 0.046857059 -0.037261382, -0.15304124 0.048377484 -0.035526186, -0.15276116 0.058918327 -0.01899685, -0.15190096 0.061780095 -0.016996816, -0.15340951 0.057932615 -0.016996816, -0.15370496 0.056409836 -0.018996894, -0.15434511 0.045726359 -0.033642262, -0.15494794 0.046622783 -0.029997662, -0.15482065 0.054048568 -0.016996935, -0.15460795 0.053886563 -0.018997073, -0.15555486 0.044555992 -0.029997572, -0.15546915 0.051348537 -0.018997177, -0.15597722 0.047071487 -0.024241969, -0.15532851 0.04901275 -0.024514779, -0.15610686 0.048612684 -0.020626485, -0.15613344 0.050130129 -0.016997233, -0.15197198 0.055562139 -0.029996991, -0.15251672 0.054076821 -0.029952213, -0.1556868 0.050684631 -0.018997207, -0.15276118 0.058916271 0.019003123, -0.15199552 0.060245872 0.02063413, -0.15190093 0.061778218 0.017003268, -0.15340948 0.057930797 0.017003268, -0.15370503 0.056407839 0.019003242, -0.15199 0.058678985 0.024249986, -0.15482074 0.05404669 0.01700303, -0.15460767 0.053884208 0.019002885, -0.15275472 0.056533128 0.024500445, -0.15546903 0.051346302 0.01900278, -0.15613341 0.050128222 0.017002687, -0.15177289 0.056099832 0.030003086, -0.15054989 0.055662334 0.035507292, -0.14911164 0.058143884 0.037264794, -0.15049022 0.057146847 0.03364642, -0.15604144 0.047688216 0.022802696, -0.15532841 0.049009889 0.024519891, -0.14835766 0.057137311 0.041003048, -0.14670651 0.059634537 0.043003246, -0.14813863 0.055983037 0.043002993, -0.14924282 0.054783851 0.041003048, -0.15584984 0.046132267 0.026409566, -0.15494797 0.046619385 0.03000246, -0.14947976 0.052296907 0.043002844, -0.1500905 0.052416742 0.04100278, -0.15555495 0.044552624 0.03000237, -0.15090078 0.050036609 0.041002825, -0.15357091 0.046405494 0.0358219, -0.15304121 0.04837358 0.035531804, -0.15220022 0.047511905 0.039425135, -0.15072902 0.04857868 0.04300265, -0.15198094 0.055562109 0.029958263, -0.15251681 0.054073513 0.029958457, -0.15117185 0.049211472 0.041002691, -0.13619065 0.05116117 -0.072021782, -0.13714963 0.053857356 -0.068739519, -0.13494295 0.054367542 -0.072021604, -0.14689097 0.05552721 -0.0469971, -0.14547718 0.059132576 -0.046996832, -0.14432278 0.056129843 -0.052837789, -0.13940078 0.050945461 -0.066751063, -0.14248279 0.052273631 -0.059997052, -0.13927002 0.053292245 -0.065412715, -0.13736242 0.047926188 -0.072021961, -0.14254808 0.052095175 -0.059997261, -0.1434581 0.054215997 -0.056436971, -0.14113034 0.04593727 -0.06675145, -0.13845737 0.044664472 -0.072022229, -0.14191251 0.043460697 -0.066751525, -0.14489628 0.052952945 -0.054279745, -0.14821553 0.051888168 -0.046997175, -0.14431655 0.046973854 -0.059997395, -0.14590123 0.041792601 -0.059997812, -0.14765902 0.044674605 -0.054280475, -0.1439528 0.042649359 -0.063397497, -0.14669393 0.047747254 -0.054279998, -0.14861073 0.04645431 -0.050657704, -0.14944987 0.048217416 -0.046997502, -0.13136683 0.068718523 -0.067059055, -0.12800764 0.069134414 -0.072020724, -0.12960652 0.066087902 -0.072020918, -0.13912325 0.058243901 -0.061996669, -0.1376771 0.061584473 -0.061996579, -0.13595247 0.059127718 -0.067061096, -0.13269216 0.066120952 -0.067060664, -0.13615084 0.064889371 -0.06199646, -0.1345451 0.068156391 -0.061996251, -0.13113312 0.063004702 -0.072021157, -0.1347955 0.061719865 -0.067060903, -0.13258633 0.059885919 -0.072021082, -0.14215575 0.06196788 -0.052278668, -0.13936429 0.062355012 -0.057996571, -0.140838 0.058950752 -0.05799678, -0.14747852 0.063265383 -0.03564176, -0.14726672 0.065964073 -0.031996503, -0.14599112 0.064217865 -0.039260581, -0.14886975 0.062261641 -0.031996638, -0.13842668 0.069902688 -0.052278161, -0.13744128 0.073020071 -0.050836027, -0.13685851 0.0710558 -0.054435506, -0.13617073 0.069051355 -0.057996273, -0.1378082 0.065722615 -0.057996422, -0.14078526 0.071093112 -0.044996127, -0.13815473 0.076079458 -0.044995829, -0.13983621 0.075370997 -0.041417152, -0.14083622 0.064910561 -0.052278593, -0.14283781 0.063816309 -0.048656255, -0.1423687 0.071892202 -0.039260104, -0.14557154 0.069625318 -0.031996205, -0.14378537 0.073243022 -0.031996086, -0.14142725 0.074601382 -0.037813529, -0.14323629 0.066016257 -0.044996411, -0.14341086 0.065636039 -0.044996455, -0.14484714 0.066758215 -0.039260447, -0.14971444 0.065099776 -0.022240758, -0.14804937 0.066321462 -0.02799648, -0.14966528 0.062589467 -0.027996659, -0.15156434 0.064936787 -0.0056144893, -0.15056077 0.067467451 -0.0019962639, -0.15081523 0.066191226 -0.0092273504, -0.15221782 0.063640833 -0.0019964278, -0.14573224 0.073583215 -0.022240326, -0.14430445 0.076815099 -0.020797893, -0.14446969 0.075259358 -0.0244046, -0.14453962 0.073658079 -0.027995914, -0.14634046 0.070011795 -0.027996391, -0.14658396 0.074012846 -0.014996156, -0.14384234 0.079209745 -0.014995754, -0.14482616 0.078104705 -0.011389911, -0.14827155 0.068322331 -0.022240534, -0.14961572 0.066623151 -0.018625572, -0.14702316 0.074234158 -0.0092269182, -0.14880764 0.071250975 -0.0019959062, -0.14695929 0.07498917 -0.0019959062, -0.14571916 0.076947778 -0.0077800006, -0.14913811 0.068721503 -0.014996246, -0.14941764 0.068111539 -0.01499626, -0.14958471 0.068926781 -0.0092270672, -0.1465977 0.06383878 0.037823275, -0.14726667 0.065960467 0.032003552, -0.14886972 0.062258065 0.032003582, -0.13936415 0.062348694 0.058003396, -0.14244165 0.062704951 0.050841123, -0.14169422 0.060839057 0.054440841, -0.140838 0.058944315 0.058003396, -0.14273047 0.072070718 0.037823737, -0.14080168 0.074912071 0.039266035, -0.14233863 0.074106306 0.035647511, -0.14378537 0.073239535 0.032004058, -0.1455715 0.069621891 0.03200385, -0.14078549 0.071088314 0.045003876, -0.13774042 0.074174047 0.048665851, -0.13815476 0.076074362 0.045004323, -0.14521518 0.066923499 0.037823498, -0.1450524 0.064760357 0.041426867, -0.13892646 0.070149004 0.050841331, -0.13780813 0.065716267 0.058003739, -0.13617069 0.069044858 0.058003798, -0.13722074 0.072233438 0.052288368, -0.14323625 0.066011131 0.045003667, -0.14341088 0.065630972 0.045003638, -0.14134482 0.065138996 0.050841168, -0.1511264 0.065693617 0.0077901483, -0.15056093 0.067467302 0.0020036101, -0.1522177 0.063640505 0.0020034909, -0.14972585 0.064166129 0.024410516, -0.14804944 0.066318393 0.028003693, -0.14968702 0.065711111 0.020803735, -0.14966537 0.062586397 0.028003454, -0.14710005 0.074272156 0.0077905208, -0.14537278 0.077415705 0.009232983, -0.14621148 0.076228201 0.0056205541, -0.14695932 0.074988931 0.0020041764, -0.14880754 0.071250916 0.0020038337, -0.14658406 0.074011207 0.015003994, -0.14384229 0.079207987 0.015004292, -0.1441597 0.077724665 0.018635035, -0.14966321 0.068961889 0.0077902377, -0.15031989 0.066922694 0.011399627, -0.14592907 0.073680192 0.020804226, -0.14634041 0.070008725 0.028003797, -0.14453959 0.07365492 0.02800405, -0.14438185 0.076195687 0.022250786, -0.14913806 0.068719774 0.015003666, -0.14941742 0.068109691 0.01500383, -0.14847174 0.068412244 0.020803809, -0.12139267 0.080183953 -0.072019994, -0.1217275 0.083025783 -0.068737864, -0.11946248 0.083032101 -0.072020039, -0.13085268 0.086821347 -0.046995342, -0.12867209 0.090021789 -0.046995088, -0.12821512 0.086837471 -0.052835986, -0.1245701 0.080687881 -0.066749528, -0.12727916 0.082668334 -0.059995532, -0.12392034 0.082946688 -0.065411031, -0.12325479 0.077290773 -0.072020292, -0.12738256 0.082508951 -0.059995562, -0.12779769 0.084779143 -0.056435406, -0.1273707 0.076190025 -0.066749617, -0.12504797 0.07435441 -0.072020382, -0.12868443 0.073949635 -0.066749796, -0.12948102 0.083867818 -0.054278091, -0.13295381 0.083568275 -0.046995342, -0.13024637 0.077909648 -0.059995756, -0.13294424 0.073210925 -0.059996039, -0.13401623 0.076411724 -0.054278627, -0.13085398 0.07361263 -0.063395768, -0.13239194 0.079192728 -0.054278374, -0.13454831 0.07835871 -0.050656006, -0.13497405 0.080264211 -0.04699558, -0.13192321 0.088721961 -0.040995285, -0.1314552 0.090236336 -0.039415851, -0.12975785 0.090789437 -0.042994976, -0.13196659 0.087548167 -0.042995125, -0.13330992 0.086624563 -0.040995345, -0.13307056 0.089612961 -0.035812259, -0.13409421 0.084252775 -0.042995304, -0.13466315 0.084505409 -0.040995419, -0.13438872 0.087771147 -0.035499141, -0.13598263 0.082365125 -0.040995479, -0.13613968 0.080905914 -0.042995423, -0.13548388 0.088469207 -0.029995263, -0.13634482 0.08910954 -0.0244921, -0.13499501 0.091649622 -0.022797242, -0.13528448 0.090087444 -0.02640368, -0.13877174 0.079735756 -0.037259504, -0.13843967 0.081219524 -0.035524383, -0.13582076 0.091433644 -0.018994883, -0.13434546 0.094032407 -0.016994819, -0.13667217 0.09061718 -0.016995043, -0.13729928 0.089198291 -0.018995002, -0.14030068 0.078924924 -0.033640623, -0.14068887 0.079933017 -0.029995561, -0.13891214 0.087144285 -0.016995206, -0.13874084 0.086938888 -0.018995345, -0.14174059 0.078053147 -0.029995829, -0.14014533 0.084656239 -0.018995419, -0.14159238 0.080599427 -0.024240166, -0.14052799 0.08234784 -0.024512798, -0.14137594 0.082130849 -0.020624653, -0.14106411 0.083616227 -0.016995385, -0.13579814 0.087985903 -0.029995099, -0.13666005 0.086659133 -0.029950395, -0.14050524 0.084057391 -0.018995434, -0.13582069 0.091431707 0.01900509, -0.13477834 0.092557579 0.020635918, -0.13434538 0.09403047 0.017005295, -0.13667218 0.090615243 0.017004952, -0.13729912 0.089196086 0.019004926, -0.13512164 0.09102872 0.024251625, -0.13891214 0.087142318 0.017004922, -0.13874067 0.086936831 0.019004822, -0.13634476 0.089106709 0.024502173, -0.14014529 0.084654033 0.019004747, -0.14106397 0.0836142 0.017004624, -0.1354838 0.088465929 0.030004844, -0.13438891 0.087767243 0.035509065, -0.13243428 0.08986643 0.037266627, -0.13400024 0.089201272 0.033648163, -0.14151733 0.081215054 0.022804663, -0.14052799 0.082344919 0.024521872, -0.13192326 0.088717401 0.041004911, -0.12975802 0.090784699 0.043005005, -0.13196646 0.087543249 0.043004811, -0.13330984 0.086620003 0.041004777, -0.14167662 0.079655528 0.026411384, -0.14068879 0.079929709 0.030004412, -0.13409427 0.084247977 0.043004721, -0.13466321 0.084500968 0.041004539, -0.14174046 0.07804963 0.030004188, -0.13598254 0.082360655 0.041004583, -0.13939413 0.079414815 0.035823852, -0.13843964 0.081215531 0.035533413, -0.13781148 0.080188453 0.039427266, -0.13613971 0.080901235 0.043004379, -0.13580626 0.087987751 0.029960215, -0.13666004 0.086655855 0.029960081, -0.13643065 0.081616431 0.041004434, -0.13702646 0.090848029 -0.01299496, -0.13574439 0.093254805 -0.0093891621, -0.1346906 0.094276279 -0.012994915, -0.13702632 0.090846479 0.013004974, -0.13469069 0.094274998 0.013005272, -0.13633649 0.0926117 0.0072338581, -0.13832107 0.089620858 -0.007225886, -0.13809025 0.090310872 4.8726797e-06, -0.13671404 0.092171937 -0.0057792962, -0.13927495 0.087361991 -0.012995183, -0.13847493 0.08972016 4.9620867e-06, -0.13725561 0.091492176 0.0036214739, -0.14143838 0.084615767 -0.0072262138, -0.14143473 0.083820075 -0.012995452, -0.14295714 0.08202368 -0.0072263032, -0.13837628 0.089655846 0.0057913959, -0.13927492 0.087360442 0.01300481, -0.14159574 0.084709466 4.6789646e-06, -0.14379129 0.080833107 -0.0036137253, -0.14453503 0.079590201 4.4554472e-06, -0.14330147 0.081553072 0.0057909191, -0.14149487 0.084648907 0.0057912171, -0.1424133 0.082711995 0.0094005018, -0.1414348 0.083818644 0.013004646, -0.12871608 0.094859123 0.037825167, -0.12889645 0.097076654 0.032005444, -0.13128319 0.093823701 0.032005265, -0.12199543 0.091796786 0.058005139, -0.12491658 0.092829049 0.050842926, -0.12460303 0.09084335 0.054442704, -0.12418972 0.088805765 0.05800502, -0.12311424 0.10202435 0.037825406, -0.12060152 0.10436523 0.039267674, -0.12227926 0.10392156 0.035649374, -0.12388261 0.10339838 0.032005891, -0.12642898 0.1002689 0.032005683, -0.12143636 0.10063344 0.04500559, -0.11778103 0.10296431 0.048667535, -0.11776215 0.10490927 0.045005843, -0.12668195 0.097558856 0.037825122, -0.12700459 0.095413715 0.041428357, -0.11983301 0.099304318 0.050843179, -0.11972903 0.094733626 0.058005258, -0.11739194 0.097614497 0.058005363, -0.1177063 0.10095671 0.052290127, -0.12495546 0.096229047 0.045005262, -0.12521048 0.095897317 0.045005426, -0.1233056 0.094957948 0.050842732, -0.11278272 0.096227467 -0.067057446, -0.10941517 0.095885664 -0.07201916, -0.11165194 0.093271285 -0.072019458, -0.12267555 0.087741435 -0.061995, -0.1205221 0.090676606 -0.06199488, -0.11938745 0.087897509 -0.06705977, -0.11465275 0.093990058 -0.067059204, -0.11829863 0.093558878 -0.061994791, -0.11600621 0.09638676 -0.061994523, -0.11382629 0.090604812 -0.072019488, -0.11768277 0.090167165 -0.067059368, -0.11593707 0.087887764 -0.072019711, -0.12480304 0.092046976 -0.052277192, -0.12199539 0.091803133 -0.057994917, -0.12418973 0.088812113 -0.05799529, -0.12970351 0.094496161 -0.03564015, -0.12889639 0.097080171 -0.031994626, -0.12804143 0.095093876 -0.039258882, -0.13128319 0.093827277 -0.031994835, -0.11940187 0.09895277 -0.052276552, -0.11774746 0.1017729 -0.050834432, -0.11761646 0.099728316 -0.054433897, -0.117392 0.097621053 -0.057994753, -0.11972889 0.094740003 -0.057994932, -0.12143652 0.1006386 -0.044994444, -0.11776215 0.10491437 -0.044994131, -0.119559 0.10459769 -0.041415453, -0.12286198 0.094622165 -0.052276731, -0.12505662 0.094000727 -0.048654675, -0.12280206 0.10176983 -0.039258435, -0.12642896 0.10027242 -0.031994462, -0.12388259 0.10340199 -0.031994224, -0.12128153 0.10420138 -0.037811786, -0.12495561 0.096234113 -0.044994727, -0.12521045 0.095902264 -0.044994727, -0.12636079 0.097315907 -0.039258718, -0.13271905 0.097675443 0.0077918917, -0.13177291 0.099278599 0.0020054728, -0.13423994 0.095916539 0.0020050257, -0.1316933 0.095874429 0.024412274, -0.12957995 0.097599745 0.028005451, -0.13131166 0.097371966 0.020805493, -0.13198577 0.094320923 0.028005093, -0.12688482 0.10514298 0.0077921897, -0.12450126 0.10782316 0.0092346817, -0.12558314 0.10685208 0.0056221783, -0.12658809 0.10581031 0.0020056218, -0.12922171 0.10257718 0.0020055771, -0.1264396 0.10477358 0.015005738, -0.12324974 0.10785437 0.018636867, -0.1226103 0.10922995 0.01500605, -0.13056526 0.1005362 0.0077920109, -0.13165908 0.098694026 0.0114014, -0.12587459 0.10430506 0.020805702, -0.12709267 0.10081726 0.028005436, -0.12452561 0.10397139 0.028005764, -0.12380658 0.10641333 0.022252455, -0.13010705 0.10018316 0.01500535, -0.13051526 0.099650651 0.015005395, -0.1295256 0.099735051 0.020805597, -0.13147497 0.096782058 -0.022239029, -0.12957995 0.097602844 -0.027994812, -0.13198589 0.094324052 -0.027994871, -0.13331445 0.097035199 -0.0056125224, -0.13177297 0.099278808 -0.0019945651, -0.13230503 0.098091364 -0.0092255026, -0.1342399 0.095916867 -0.0019947886, -0.1257049 0.10416678 -0.022238657, -0.12359366 0.1069999 -0.020796195, -0.12410089 0.10551992 -0.024402902, -0.12452559 0.10397449 -0.02799426, -0.12709254 0.10082015 -0.027994424, -0.12643966 0.10477525 -0.014994115, -0.12261015 0.10923171 -0.014993906, -0.12381513 0.10837322 -0.011388123, -0.12935111 0.099602848 -0.022239015, -0.13103974 0.098245472 -0.018623739, -0.12681836 0.1050888 -0.0092250407, -0.12922183 0.10257754 -0.0019943565, -0.12658811 0.10581061 -0.0019942224, -0.12494312 0.1074442 -0.0077783018, -0.13010713 0.10018486 -0.014994517, -0.13051529 0.099652261 -0.014994487, -0.1304968 0.10048437 -0.0092253983, -0.074582145 0.12491381 -0.072017565, -0.073650688 0.1276195 -0.068735227, -0.071607456 0.12664264 -0.07201758, -0.080224827 0.13499847 -0.046992525, -0.076871648 0.13693577 -0.046992451, -0.077841476 0.13386852 -0.052833363, -0.077226445 0.12674665 -0.066746742, -0.078807458 0.12970635 -0.059992954, -0.07566084 0.12849978 -0.065408558, -0.077515125 0.12311509 -0.07201767, -0.078969851 0.12960759 -0.059992939, -0.078358859 0.13183308 -0.056432828, -0.081701115 0.12390926 -0.06674701, -0.080404937 0.12124768 -0.072017819, -0.083856612 0.12246072 -0.066746995, -0.080270648 0.13174233 -0.054275528, -0.083529472 0.13297918 -0.046992555, -0.08354567 0.12670621 -0.059992909, -0.088014901 0.12364343 -0.059993237, -0.08759205 0.12699249 -0.054275766, -0.085957542 0.12309846 -0.063393161, -0.084921822 0.12879318 -0.054275662, -0.087226465 0.1289773 -0.05065304, -0.086783111 0.13087896 -0.046992794, -0.080364704 0.13717535 -0.040992379, -0.079286084 0.13833663 -0.039413199, -0.077516884 0.1380986 -0.042992502, -0.080913067 0.13613626 -0.042992517, -0.082524076 0.13588732 -0.040992513, -0.081011817 0.13847587 -0.035809442, -0.084259897 0.13409069 -0.042992562, -0.084662676 0.13456517 -0.040992677, -0.082998529 0.13738838 -0.035496622, -0.086780265 0.13320944 -0.040992603, -0.087554827 0.13196275 -0.042992741, -0.08368203 0.13849238 -0.029992446, -0.08417961 0.13944283 -0.024489284, -0.081861705 0.14114577 -0.022794217, -0.082800135 0.13986379 -0.026400954, -0.090433866 0.13205034 -0.037256524, -0.089490727 0.13324305 -0.035521567, -0.08269909 0.14130935 -0.018992171, -0.080242276 0.14301059 -0.016992182, -0.083820432 0.14094302 -0.016992107, -0.085001156 0.13993677 -0.01899229, -0.092163265 0.13198325 -0.033637673, -0.092075363 0.13306004 -0.029992715, -0.087345421 0.13878611 -0.016992345, -0.087280214 0.13852665 -0.018992364, -0.093838558 0.13182241 -0.029992729, -0.089536026 0.13707948 -0.018992439, -0.092600226 0.13405246 -0.024237096, -0.090882629 0.13516572 -0.024509802, -0.091740429 0.13533813 -0.020621806, -0.090814978 0.13654098 -0.016992435, -0.084175006 0.1381934 -0.029992372, -0.085527048 0.13737202 -0.029947639, -0.090120271 0.13669619 -0.018992275, -0.084039316 0.14130476 -0.012992308, -0.081840023 0.14291704 -0.0093863159, -0.080447391 0.14338019 -0.012992248, -0.08403945 0.14130351 0.013007909, -0.080447301 0.1433787 0.013007849, -0.082651868 0.14259431 0.0072367638, -0.085738137 0.14076093 -0.0072230101, -0.085230693 0.14128247 7.7337027e-06, -0.083183289 0.14236194 -0.0057763606, -0.08757776 0.13913944 -0.012992308, -0.085833415 0.14091703 7.8380108e-06, -0.083965868 0.14198434 0.0036242455, -0.09071818 0.137604 -0.0072232783, -0.0910604 0.13688564 -0.012992665, -0.093211278 0.13592759 -0.0072234422, -0.085772485 0.14081657 0.0057944208, -0.087577745 0.13913816 0.013007715, -0.090819255 0.13775665 7.674098e-06, -0.094479248 0.13521683 -0.0036104321, -0.095688611 0.13441977 7.3313713e-06, -0.093725562 0.13565299 0.0057939142, -0.090754554 0.13765824 0.0057941824, -0.092422396 0.13631165 0.0094035864, -0.091060355 0.13688409 0.013007462, -0.082699224 0.14130732 0.019007817, -0.081271321 0.14186949 0.020638764, -0.080242202 0.14300865 0.017008066, -0.083820328 0.1409412 0.017007917, -0.085001096 0.1399346 0.019007772, -0.08224383 0.14064091 0.024254456, -0.087345436 0.13878417 0.017007709, -0.087280273 0.13852459 0.019007728, -0.084179819 0.13944003 0.0245049, -0.089536056 0.13707727 0.019007489, -0.090814933 0.13653901 0.017007574, -0.083681971 0.13848913 0.030007571, -0.082998484 0.13738438 0.035511851, -0.080326721 0.13842773 0.03726925, -0.082026273 0.13850799 0.03365086, -0.092264235 0.13457415 0.022807539, -0.09088245 0.13516289 0.024524868, -0.080364764 0.13717088 0.041007787, -0.077516645 0.13809359 0.043007642, -0.080913141 0.13613161 0.043007478, -0.082524106 0.13588265 0.041007593, -0.093084246 0.13323814 0.026414216, -0.092075214 0.13305661 0.030007154, -0.084259823 0.13408601 0.043007359, -0.084662706 0.13456061 0.041007534, -0.093838573 0.13181919 0.030007273, -0.08678025 0.13320482 0.041007325, -0.091132089 0.13203081 0.035826817, -0.089490712 0.133239 0.035536423, -0.08937034 0.1320411 0.039430037, -0.087554842 0.13195792 0.04300721, -0.084179997 0.13819817 0.029963061, -0.085527092 0.13736874 0.029963031, -0.087506726 0.13272876 0.04100728, -0.076463163 0.14424273 -0.022236392, -0.074399859 0.14415979 -0.027992085, -0.077989966 0.14224955 -0.027992219, -0.07801038 0.14526868 -0.005610019, -0.07564801 0.14662126 -0.0019918978, -0.076642856 0.14578232 -0.0092228651, -0.079329401 0.14466265 -0.0019919127, -0.068060324 0.1483925 -0.022236049, -0.064929098 0.15002903 -0.020793736, -0.066028178 0.14891559 -0.024400383, -0.067081437 0.14770758 -0.027991951, -0.070762977 0.14597964 -0.027991846, -0.068458304 0.14925948 -0.014991805, -0.064532474 0.15136233 -0.011385843, -0.063074395 0.15161297 -0.014991522, -0.073325738 0.14586255 -0.022236243, -0.07543613 0.14537221 -0.018620968, -0.06866321 0.14970624 -0.0092226714, -0.07191813 0.14848626 -0.0019917488, -0.068142369 0.15025645 -0.0019916296, -0.065951809 0.15101463 -0.0077759326, -0.073754296 0.14671475 -0.014991939, -0.074353173 0.14641222 -0.014991894, -0.07397522 0.14715385 -0.0092226267, -0.072507292 0.13708171 -0.05227457, -0.070083499 0.13564396 -0.057992384, -0.073358297 0.13390127 -0.057992503, -0.075859278 0.14141455 -0.035637274, -0.074010924 0.14339253 -0.031991988, -0.074102551 0.14123192 -0.039256379, -0.077572718 0.14149725 -0.031992182, -0.06464453 0.14096025 -0.052274138, -0.061930522 0.14278322 -0.050831914, -0.062699601 0.14088416 -0.054431424, -0.063411728 0.13888827 -0.057992339, -0.066767454 0.13730678 -0.057992458, -0.065746143 0.14336172 -0.044992134, -0.062336773 0.14611417 -0.041413099, -0.060580418 0.14561978 -0.044991866, -0.069641218 0.13855985 -0.052274287, -0.071887866 0.13895214 -0.048652187, -0.066485599 0.14497358 -0.039255932, -0.070402831 0.14519787 -0.031991869, -0.066750675 0.14691269 -0.031991765, -0.064060465 0.14650455 -0.037809357, -0.070827752 0.14092031 -0.044992149, -0.07120119 0.14073196 -0.044992253, -0.071624339 0.14250466 -0.039256096, -0.05986385 0.13563299 -0.067055479, -0.056978151 0.13386387 -0.072017089, -0.060127854 0.13247907 -0.072017178, -0.072458595 0.13227957 -0.061992511, -0.069245115 0.13398969 -0.061992526, -0.069428682 0.13099375 -0.067057014, -0.062519312 0.13442859 -0.067057028, -0.065991312 0.13562179 -0.061992526, -0.06269899 0.13717511 -0.061992615, -0.063243672 0.13101995 -0.072017118, -0.066908047 0.13229892 -0.067057028, -0.066324428 0.12948775 -0.072017252, -0.07481055 0.14131278 0.03782776, -0.074010894 0.14338893 0.032008052, -0.077572629 0.14149374 0.032007933, -0.070083499 0.13563749 0.058007672, -0.072267652 0.13783497 0.05084525, -0.072846487 0.13590991 0.054445058, -0.073358402 0.1338948 0.058007479, -0.066654444 0.14533758 0.037827715, -0.063374832 0.14635652 0.039269939, -0.065079078 0.14668491 0.035651654, -0.06675069 0.14690918 0.032008126, -0.070402816 0.1451945 0.032008007, -0.065746158 0.14335671 0.045007855, -0.061441272 0.14387062 0.048669696, -0.060580567 0.14561489 0.045008227, -0.071806267 0.14286256 0.037827641, -0.073027655 0.14106968 0.041430891, -0.064878002 0.14146334 0.050845399, -0.066767469 0.13730031 0.058007747, -0.063411757 0.13888174 0.058007881, -0.062244922 0.1420294 0.052292362, -0.070827752 0.14091539 0.045007721, -0.071201414 0.14072704 0.04500787, -0.069892481 0.13905424 0.05084531, -0.077195719 0.14558712 0.0077944547, -0.075648069 0.14662108 0.0020080209, -0.079329371 0.14466241 0.0020078868, -0.077052489 0.1435194 0.024415031, -0.074399844 0.14415678 0.028007969, -0.076058969 0.14470291 0.020808086, -0.07799004 0.14224648 0.028007835, -0.068699256 0.1497837 0.0077948719, -0.065388769 0.15116441 0.0092372596, -0.066785008 0.15075886 0.0056246519, -0.068142563 0.15025637 0.0020084381, -0.071918219 0.14848599 0.0020081103, -0.068458244 0.14925775 0.015008286, -0.06307447 0.15161145 0.015008166, -0.064247519 0.15064943 0.018639326, -0.074013934 0.14723003 0.0077944994, -0.075798675 0.14604491 0.011404201, -0.068152398 0.14859051 0.020808309, -0.070762873 0.14597633 0.028008103, -0.067081317 0.14770433 0.028008178, -0.06537427 0.14959249 0.022254869, -0.073754147 0.14671302 0.015007958, -0.074353084 0.14641052 0.015008256, -0.073424712 0.1460571 0.020808235, -0.11206973 0.11936206 0.019006744, -0.11080296 0.1202279 0.020637602, -0.11005306 0.12156752 0.017006591, -0.1130815 0.11875567 0.017006651, -0.11400858 0.11751172 0.019006595, -0.11147772 0.11881375 0.02425316, -0.1160382 0.11586839 0.017006427, -0.11591686 0.11562982 0.019006506, -0.11309791 0.11721218 0.024503678, -0.11779405 0.11371696 0.019006401, -0.11892113 0.11290756 0.017006099, -0.1124012 0.11639577 0.030006468, -0.11148903 0.11547101 0.035510659, -0.10911639 0.11708274 0.037268206, -0.11079104 0.1167827 0.033649623, -0.11989684 0.11066931 0.022806168, -0.11868091 0.11155087 0.024523541, -0.1088737 0.11584878 0.041006461, -0.1063025 0.11738223 0.043006495, -0.10917695 0.11471346 0.043006331, -0.11069247 0.11411256 0.041006178, -0.12039909 0.10918438 0.026413113, -0.11937515 0.10923192 0.030005932, -0.11198471 0.11197445 0.043006286, -0.11248313 0.11234754 0.041006193, -0.12081863 0.10763299 0.030005813, -0.11424583 0.11055461 0.041005969, -0.11822721 0.10844168 0.035825625, -0.11689602 0.10998484 0.035535127, -0.11651208 0.10884374 0.039428711, -0.11472362 0.10916653 0.043005958, -0.11282188 0.11600155 0.029961944, -0.11395051 0.11489299 0.02996169, -0.1148482 0.10992882 0.041005999, -0.1133754 0.1190615 -0.012993425, -0.11159012 0.12112266 -0.0093874782, -0.11033539 0.12188429 -0.01299338, -0.11337546 0.11906025 0.013006523, -0.11033535 0.12188271 0.013006702, -0.11230992 0.12062743 0.0072352886, -0.11491054 0.11815321 -0.0072243065, -0.11453202 0.11877456 6.6012144e-06, -0.11277629 0.12028265 -0.0057776421, -0.11634322 0.11616313 -0.012993574, -0.11503837 0.11828423 6.5863132e-06, -0.11345527 0.1197404 0.0036229938, -0.11906332 0.11396718 -0.0072244257, -0.11923712 0.11319065 -0.012993678, -0.12112111 0.11177817 -0.0072246045, -0.11495654 0.11819974 0.0057929605, -0.1163432 0.11616161 0.013006479, -0.11919592 0.11409357 6.4522028e-06, -0.12320067 0.10975686 6.005168e-06, -0.1215615 0.11139601 0.0057926178, -0.12219904 0.11080298 -0.0036120266, -0.11911106 0.11401206 0.0057929009, -0.12043743 0.11232799 0.0094021857, -0.11923721 0.11318928 0.013006181, -0.10887371 0.11585322 -0.040993541, -0.10808037 0.11722559 -0.039414287, -0.10630265 0.11738721 -0.042993665, -0.10917708 0.11471829 -0.042993769, -0.11069223 0.11411697 -0.040993646, -0.10979393 0.11697713 -0.035810664, -0.11198486 0.11197931 -0.042993903, -0.11248298 0.11235213 -0.040993914, -0.11148895 0.11547497 -0.035497665, -0.11424577 0.11055925 -0.040993914, -0.11472364 0.10917154 -0.042993978, -0.11240102 0.11639917 -0.029993594, -0.11309803 0.11721507 -0.024490595, -0.11121677 0.11939108 -0.022795573, -0.11184657 0.11793232 -0.026402235, -0.11755009 0.10861617 -0.037257671, -0.11689602 0.10998893 -0.035522521, -0.11206977 0.11936429 -0.018993348, -0.11005321 0.12156948 -0.01699321, -0.11308165 0.11875761 -0.016993463, -0.11400858 0.11751378 -0.018993512, -0.11922091 0.10816592 -0.033639044, -0.11937506 0.10923517 -0.029993996, -0.11603829 0.11587027 -0.016993582, -0.11591676 0.11563188 -0.018993482, -0.12081887 0.10763645 -0.029994026, -0.11779401 0.11371908 -0.018993691, -0.12010764 0.11008596 -0.024238437, -0.118681 0.11155367 -0.024511173, -0.11955574 0.11153084 -0.020623088, -0.11892119 0.11290941 -0.016993895, -0.1128152 0.115998 -0.029993564, -0.11395049 0.11489624 -0.029948741, -0.11827819 0.11321536 -0.018994004, -0.10050735 0.10518593 -0.072018743, -0.10020147 0.10803109 -0.06873624, -0.097991794 0.10753331 -0.072018579, -0.10825279 0.11376223 -0.046993822, -0.10541476 0.11639699 -0.046993494, -0.10567783 0.11319068 -0.052834556, -0.10349302 0.10638443 -0.066747919, -0.10569324 0.10891807 -0.059993997, -0.10235697 0.10844204 -0.065409645, -0.10296662 0.10277981 -0.072018877, -0.10582966 0.10878569 -0.059994012, -0.10572904 0.11109126 -0.056433916, -0.10722429 0.10262251 -0.066748187, -0.10536818 0.10031602 -0.072018996, -0.1090035 0.10073069 -0.066748247, -0.10757303 0.11057761 -0.0542766, -0.1110252 0.11105812 -0.046993837, -0.10964495 0.10493895 -0.059994385, -0.1133208 0.10095832 -0.05999437, -0.1136537 0.10431758 -0.054277182, -0.11119369 0.1008848 -0.063394144, -0.11145122 0.10666737 -0.054276839, -0.11373909 0.10633385 -0.050654545, -0.11373004 0.10828653 -0.046993986, -0.10119219 0.11751047 -0.052275643, -0.098509252 0.11664808 -0.057993621, -0.10131419 0.11422026 -0.057993591, -0.10542458 0.12098867 -0.035638422, -0.10406272 0.12332845 -0.03199324, -0.10367121 0.12120157 -0.039257482, -0.10711351 0.12068817 -0.031993344, -0.094389603 0.1230413 -0.052275196, -0.092149243 0.12542269 -0.050833195, -0.092476651 0.12340003 -0.054432675, -0.092726767 0.12129581 -0.057993293, -0.095646262 0.1190072 -0.057993501, -0.095998034 0.12513742 -0.044992983, -0.093286887 0.1285798 -0.041413993, -0.091464549 0.12848845 -0.04499279, -0.098726779 0.11958927 -0.052275315, -0.10100478 0.11947179 -0.04865326, -0.097077623 0.12654436 -0.039257124, -0.10094695 0.12589157 -0.031993002, -0.097767904 0.12837595 -0.031992853, -0.095054165 0.12857649 -0.03781037, -0.10040906 0.12162656 -0.044993341, -0.10073142 0.12135983 -0.044993132, -0.10153823 0.12299404 -0.039257422, -0.088543236 0.11891133 -0.067056313, -0.085336164 0.11782876 -0.072017998, -0.088098779 0.11577779 -0.072018161, -0.10007608 0.11283949 -0.061993733, -0.097323671 0.11522198 -0.061993495, -0.096835896 0.11226013 -0.067058131, -0.090864256 0.11714631 -0.067057863, -0.094514489 0.11753714 -0.06199342, -0.091650411 0.11978397 -0.061993405, -0.090811849 0.11366203 -0.072018266, -0.094668955 0.11409354 -0.067058057, -0.093474314 0.1114828 -0.072018281, -0.10664274 0.12361154 -0.022237435, -0.10461277 0.12399006 -0.027993158, -0.1076878 0.12132871 -0.027993247, -0.10837975 0.12426755 -0.0056110024, -0.10637754 0.12611195 -0.001993075, -0.10716073 0.12507284 -0.0092239976, -0.10953096 0.12338316 -0.0019931495, -0.099374145 0.12952715 -0.022237167, -0.09668532 0.13181931 -0.020794719, -0.097509354 0.13048938 -0.024401307, -0.098267317 0.12907714 -0.027992919, -0.10147184 0.12657335 -0.027993158, -0.099955142 0.13028389 -0.014992759, -0.095229983 0.13377637 -0.014992625, -0.09659569 0.13320765 -0.011386737, -0.10394439 0.12588897 -0.022237256, -0.10589297 0.12494129 -0.018622205, -0.10025436 0.13067374 -0.0092236698, -0.10315634 0.12876013 -0.0019930601, -0.099869207 0.13132614 -0.0019928217, -0.097902045 0.13255277 -0.0077769309, -0.10455187 0.12662446 -0.014992967, -0.10506842 0.12619618 -0.014993101, -0.10486513 0.12700331 -0.0092239827, -0.10765652 0.12475926 0.0077934414, -0.10637765 0.12611169 0.0020069927, -0.10953079 0.1233829 0.0020065606, -0.10705701 0.12277514 0.024413764, -0.10461271 0.12398687 0.028006688, -0.10635173 0.12415016 0.020807013, -0.10768792 0.12132558 0.028006732, -0.10030696 0.1307413 0.0077936053, -0.097386628 0.13282394 0.0092360526, -0.098657474 0.13211799 0.0056236982, -0.099869207 0.1313259 0.0020071715, -0.1031563 0.12875995 0.0020071417, -0.099954948 0.13028213 0.015007049, -0.095230013 0.13377467 0.015007406, -0.096159443 0.13257584 0.018638209, -0.10492022 0.12706891 0.0077934265, -0.10639662 0.12551653 0.011403009, -0.099508405 0.12969953 0.02080743, -0.1014719 0.12657028 0.028006896, -0.098267302 0.12907404 0.028007179, -0.097023025 0.13129476 0.022253901, -0.10455197 0.12662274 0.01500693, -0.1050684 0.12619457 0.0150069, -0.1040847 0.12605658 0.020807043, -0.10438049 0.1211229 0.037826747, -0.10406257 0.12332469 0.03200689, -0.10711351 0.12068462 0.0320068, -0.098509401 0.11664176 0.058006629, -0.10112758 0.1182979 0.050844237, -0.10126366 0.11629245 0.054444134, -0.10131422 0.11421394 0.058006302, -0.097324461 0.1268616 0.037826732, -0.094353721 0.1285848 0.039268956, -0.096088231 0.1285257 0.035650492, -0.097767904 0.12837237 0.032006979, -0.10094692 0.1258879 0.032007158, -0.095998079 0.12513253 0.045006871, -0.091464505 0.12848347 0.04500711, -0.091915578 0.12659144 0.048668906, -0.10179636 0.12330225 0.037826508, -0.10258827 0.12128267 0.041429758, -0.094730511 0.12347978 0.050844535, -0.095646337 0.11900067 0.058006659, -0.092726633 0.12128928 0.058006793, -0.092289448 0.12461758 0.052291468, -0.10040905 0.12162152 0.045006737, -0.10073128 0.12135458 0.045006782, -0.09908323 0.12001514 0.050844207, -0.14946318 -0.048176885 0.046997212, -0.14890233 -0.045508385 0.050659567, -0.15060563 -0.044476628 0.046997562, -0.13837421 -0.044921339 0.072021991, -0.13939779 -0.041636407 0.072022237, -0.14160067 -0.04447037 0.066749327, -0.1468533 -0.049131989 0.052835479, -0.14398749 -0.047973394 0.059997164, -0.14709531 -0.04649362 0.054282613, -0.14822961 -0.051847816 0.046996966, -0.14392737 -0.048153639 0.059997149, -0.14284492 -0.046227425 0.063395545, -0.14500608 -0.054342538 0.052835345, -0.14690624 -0.055487365 0.046996742, -0.14405002 -0.056828767 0.052835256, -0.14141211 -0.047312409 0.065415002, -0.13727331 -0.048181057 0.072021767, -0.14211687 -0.053260446 0.05999697, -0.14213699 -0.05759269 0.056435071, -0.14012541 -0.058299124 0.059996665, -0.13849451 -0.055273771 0.065414779, -0.13963322 -0.052329779 0.065414578, -0.13734503 -0.053354621 0.068741061, -0.13609561 -0.051413774 0.072021663, -0.15616767 -0.049182743 0.018997133, -0.15639834 -0.047665805 0.020627998, -0.15727971 -0.046408772 0.016997248, -0.15606028 -0.050357342 0.016997188, -0.15534186 -0.051732421 0.018997177, -0.1554172 -0.048887402 0.024244018, -0.15474173 -0.054274052 0.016996965, -0.15447414 -0.054268152 0.018996701, -0.1546772 -0.05104202 0.024494238, -0.15356509 -0.056789517 0.018996879, -0.15332501 -0.058156043 0.016996711, -0.15363955 -0.050768763 0.029996939, -0.15241085 -0.050348282 0.035501435, -0.15283364 -0.047511309 0.037258908, -0.15328974 -0.049150229 0.033640452, -0.15173213 -0.06000644 0.022796743, -0.15199873 -0.058528513 0.024514027, -0.15161669 -0.047828138 0.040997215, -0.15188293 -0.044846445 0.042997263, -0.15072575 -0.048594207 0.042997144, -0.15084133 -0.050220042 0.040996976, -0.15061206 -0.061103553 0.026403554, -0.15021111 -0.060160249 0.029996596, -0.14947604 -0.052312195 0.042996913, -0.15002841 -0.052599311 0.040996909, -0.14939687 -0.062154621 0.029996529, -0.14917788 -0.054965407 0.040996864, -0.14900133 -0.059469074 0.035816155, -0.14981416 -0.057600051 0.035525635, -0.1486197 -0.05774954 0.03941939, -0.14813478 -0.055998206 0.04299669, -0.15346685 -0.051318794 0.029952511, -0.1529578 -0.052816659 0.029952325, -0.14887518 -0.055779517 0.040996872, -0.15646195 -0.050488383 -0.013002872, -0.15754457 -0.047985703 -0.0093969554, -0.15768594 -0.046524882 -0.013002723, -0.156462 -0.050489962 0.01299715, -0.15768602 -0.046526283 0.01299715, -0.1574114 -0.048849761 0.0072259158, -0.15630987 -0.052265882 -0.0072337091, -0.15670592 -0.051655501 -3.144145e-06, -0.15730248 -0.049419105 -0.0057871938, -0.15513822 -0.054420084 -0.01300326, -0.15648364 -0.052324533 -3.1143427e-06, -0.15710898 -0.050266385 0.0036135763, -0.15434012 -0.057823807 -0.0072340965, -0.15371579 -0.058317125 -0.013003424, -0.15326078 -0.060627252 -0.007234171, -0.15637232 -0.052287489 0.0057836026, -0.1551383 -0.054421365 0.012996688, -0.15451203 -0.057888508 -3.4272671e-06, -0.15234241 -0.063378274 -3.5017729e-06, -0.15310813 -0.061190367 0.0057830662, -0.15285009 -0.062021852 -0.003621608, -0.15440206 -0.0578475 0.0057831854, -0.15346053 -0.059773296 0.0093925297, -0.15371576 -0.058318496 0.012996599, -0.15161678 -0.047823608 -0.041002899, -0.1525089 -0.046513557 -0.03942354, -0.15188283 -0.044841588 -0.043002546, -0.1507258 -0.048589438 -0.043002769, -0.15084127 -0.050215483 -0.041002974, -0.15302899 -0.048165083 -0.035819992, -0.14947611 -0.052307367 -0.043003201, -0.15002833 -0.052594662 -0.041003183, -0.15241086 -0.050344229 -0.035507023, -0.14917779 -0.054960698 -0.041003197, -0.1481348 -0.055993348 -0.043003306, -0.15363967 -0.050765187 -0.030002877, -0.15467717 -0.051039129 -0.024500072, -0.15582161 -0.048400372 -0.022804916, -0.15478073 -0.049600452 -0.026411593, -0.1488611 -0.058780909 -0.037267044, -0.1498141 -0.057596087 -0.035532087, -0.15616781 -0.049180597 -0.019002765, -0.15727974 -0.046406835 -0.017002657, -0.15606034 -0.050355494 -0.017002836, -0.15534176 -0.051730216 -0.019003019, -0.14918062 -0.060482025 -0.033648327, -0.15021117 -0.060156941 -0.030003473, -0.15474173 -0.054272056 -0.017003149, -0.15447429 -0.054265946 -0.019003123, -0.14939703 -0.062151253 -0.030003443, -0.1535653 -0.056787342 -0.019003168, -0.15129554 -0.060447961 -0.024247974, -0.15199889 -0.058525711 -0.024520636, -0.152358 -0.059324026 -0.020632625, -0.15332511 -0.058154136 -0.017003506, -0.15345767 -0.051312327 -0.030002877, -0.1529579 -0.052813292 -0.029958218, -0.15332156 -0.05744198 -0.019003198, -0.15441871 -0.041491568 0.037817433, -0.15626451 -0.040249616 0.031997614, -0.15520947 -0.044143796 0.031997554, -0.14783505 -0.038146853 0.057997778, -0.15046304 -0.039786845 0.050835438, -0.14871538 -0.040779829 0.054435179, -0.14686477 -0.041727185 0.057997622, -0.15652788 -0.032644302 0.037817962, -0.15679151 -0.029220253 0.039260194, -0.15749058 -0.030808508 0.0356417, -0.15808114 -0.0323883 0.031998098, -0.157222 -0.036330163 0.031997852, -0.15439476 -0.0321998 0.044998132, -0.15544683 -0.026661247 0.044998549, -0.15393811 -0.027888685 0.04866007, -0.15526122 -0.038217783 0.037817627, -0.15378548 -0.039807528 0.04142075, -0.15235603 -0.031774998 0.05083584, -0.14871809 -0.034543693 0.057998128, -0.14951336 -0.030920327 0.05799827, -0.15232208 -0.02908206 0.052282706, -0.15314546 -0.037697285 0.044997923, -0.15304494 -0.038103342 0.044997878, -0.15112314 -0.037200004 0.050835416, -0.15911508 -0.042864561 0.0077839792, -0.15977846 -0.041125178 0.0019974113, -0.15868783 -0.045150191 0.0019973218, -0.15706824 -0.043185622 0.024404459, -0.1570995 -0.040457845 0.027997553, -0.15800086 -0.041953653 0.02079761, -0.15603599 -0.044383228 0.027997531, -0.16131586 -0.033647299 0.007784605, -0.16192526 -0.030112416 0.0092270672, -0.16184032 -0.031563699 0.0056144446, -0.16165224 -0.032998919 0.0019981414, -0.16076669 -0.03707388 0.001997605, -0.16074982 -0.033529431 0.014997914, -0.16116983 -0.029114753 0.018629074, -0.1618465 -0.027757049 0.014998466, -0.16000867 -0.039397061 0.0077841878, -0.1592509 -0.04140076 0.011393636, -0.16003148 -0.033380032 0.020798102, -0.15806428 -0.03650713 0.027997889, -0.15892971 -0.032533497 0.027998172, -0.16039047 -0.030448675 0.022244781, -0.15944736 -0.039259076 0.014997795, -0.15928569 -0.039910167 0.014997646, -0.15873477 -0.039084077 0.020797774, -0.14253333 -0.029145896 0.072022863, -0.14318258 -0.025767148 0.072022997, -0.14554957 -0.0281865 0.067061283, -0.14315511 -0.03854382 0.067062274, -0.14603552 -0.037697762 0.061997786, -0.14508298 -0.041211337 0.061997585, -0.14496729 -0.0310435 0.067061037, -0.14768425 -0.030606717 0.061998338, -0.14690274 -0.034162283 0.061998136, -0.14180425 -0.032508373 0.072022572, -0.14386751 -0.035796195 0.067060933, -0.14099586 -0.03585279 0.07202252, -0.14977641 -0.040183455 -0.052284494, -0.147835 -0.038140297 -0.058002338, -0.1468648 -0.041720778 -0.058002472, -0.15474749 -0.042488009 -0.035647616, -0.15626454 -0.040246069 -0.03200224, -0.15417831 -0.040815949 -0.039266542, -0.1552095 -0.04414022 -0.032002509, -0.15180787 -0.031654924 -0.052283853, -0.15298134 -0.028603226 -0.050841615, -0.15130109 -0.029775679 -0.054441139, -0.1495136 -0.03091383 -0.05800198, -0.14871815 -0.034537256 -0.058002189, -0.15439481 -0.032194883 -0.045002058, -0.15544693 -0.026656151 -0.045001596, -0.15631989 -0.028258562 -0.041422874, -0.15057933 -0.03706035 -0.052284196, -0.15146217 -0.039163679 -0.048662156, -0.1561311 -0.032557219 -0.03926608, -0.15722191 -0.036326647 -0.032002047, -0.15808104 -0.032384634 -0.032002062, -0.15708409 -0.02985239 -0.037819177, -0.15314545 -0.03769213 -0.045002192, -0.15304491 -0.038098395 -0.045002222, -0.15486771 -0.038116574 -0.039266303, -0.15763967 -0.042448252 -0.022246778, -0.15709949 -0.040454775 -0.028002456, -0.15603611 -0.044380039 -0.028002575, -0.15898521 -0.043729037 -0.0056205094, -0.15977837 -0.041125059 -0.0020024329, -0.15918154 -0.04228127 -0.0092333704, -0.15868801 -0.045149893 -0.0020027012, -0.15981574 -0.033332676 -0.02224648, -0.16071448 -0.02991581 -0.020803869, -0.15987349 -0.031235009 -0.024410352, -0.15892969 -0.032530427 -0.0280018, -0.15806423 -0.03650403 -0.028002217, -0.16074984 -0.033527821 -0.015002012, -0.16192676 -0.029232711 -0.011395887, -0.16184649 -0.027755439 -0.015001625, -0.1585208 -0.039028943 -0.022246674, -0.15851243 -0.041195512 -0.018631473, -0.16123143 -0.033628553 -0.0092328191, -0.16076668 -0.037073672 -0.0020022243, -0.16165227 -0.032998681 -0.0020019859, -0.16190371 -0.030694127 -0.0077861547, -0.15944739 -0.039257199 -0.01500228, -0.15928568 -0.03990835 -0.015002266, -0.15992498 -0.039375365 -0.0092331618, -0.13717313 -0.080362499 -0.041004539, -0.13833447 -0.079283774 -0.039425448, -0.13809617 -0.077514499 -0.043004513, -0.13613401 -0.080910832 -0.043004677, -0.13588494 -0.082521915 -0.041004658, -0.13847369 -0.081009805 -0.0358219, -0.13408838 -0.084257513 -0.043004841, -0.13456303 -0.08466047 -0.041004941, -0.13738655 -0.082996458 -0.035508826, -0.13320722 -0.086777925 -0.041004941, -0.13196048 -0.087552607 -0.043005109, -0.13849086 -0.083680481 -0.030004829, -0.13944162 -0.084178418 -0.024501964, -0.1411446 -0.081860274 -0.022806868, -0.13986249 -0.082798749 -0.026413426, -0.13204837 -0.090431809 -0.037268981, -0.1332411 -0.089488834 -0.03553386, -0.14130838 -0.082698137 -0.019004628, -0.14300965 -0.080241382 -0.017004684, -0.14094231 -0.083819687 -0.017004818, -0.13993576 -0.085000068 -0.019004747, -0.13198154 -0.092161328 -0.033650264, -0.13305844 -0.092073768 -0.030005231, -0.13878521 -0.087344646 -0.017004952, -0.13852571 -0.087279171 -0.019004896, -0.13182095 -0.093836904 -0.030005366, -0.13707842 -0.089534938 -0.019005135, -0.13405105 -0.092598826 -0.024249598, -0.13516442 -0.090881109 -0.024522498, -0.13533711 -0.091739506 -0.020634457, -0.13654007 -0.090814114 -0.017005235, -0.13819189 -0.08417353 -0.030004784, -0.13737056 -0.085525483 -0.029960096, -0.13669516 -0.090119064 -0.019005179, -0.14130843 -0.082700223 0.01899536, -0.14187089 -0.081272602 0.020626351, -0.14300953 -0.08024317 0.01699537, -0.14094228 -0.083821505 0.016995341, -0.13993558 -0.085002363 0.018995099, -0.14064249 -0.08224538 0.024241887, -0.13878529 -0.087346584 0.016995072, -0.13852566 -0.087281287 0.018995032, -0.13944155 -0.084181219 0.024492443, -0.13707846 -0.089537114 0.01899495, -0.13654032 -0.090816021 0.016994908, -0.13849092 -0.083683759 0.029995218, -0.13738647 -0.083000571 0.035499491, -0.13843 -0.080328882 0.037257187, -0.13850994 -0.082028151 0.033638462, -0.13457537 -0.092265576 0.022794925, -0.13516435 -0.09088394 0.024512224, -0.13717307 -0.080367029 0.040995441, -0.1380963 -0.077519149 0.042995378, -0.136134 -0.08091566 0.042995207, -0.13588494 -0.082526356 0.04099524, -0.13323963 -0.093085885 0.026401713, -0.1330584 -0.092077017 0.029994659, -0.13408834 -0.084262311 0.042995058, -0.13456294 -0.08466509 0.04099527, -0.13182092 -0.093840271 0.029994726, -0.13320731 -0.086782455 0.040994942, -0.1320329 -0.091134161 0.035814308, -0.13324112 -0.089492708 0.035523988, -0.13204336 -0.089372665 0.039417647, -0.13196041 -0.087557405 0.042994931, -0.13820001 -0.084181726 0.029950626, -0.1373706 -0.085528761 0.029950619, -0.13273099 -0.087508947 0.040995017, -0.14130425 -0.084038645 -0.013004854, -0.14291659 -0.081839442 -0.0093988478, -0.14337955 -0.08044675 -0.013004631, -0.14130421 -0.084040135 0.012995094, -0.14337952 -0.0804483 0.012995467, -0.14259487 -0.082652301 0.0072241277, -0.14076059 -0.085737675 -0.0072357655, -0.14128251 -0.085230798 -4.8577785e-06, -0.1423617 -0.08318308 -0.005789116, -0.13913888 -0.087577075 -0.013005093, -0.14091727 -0.08583352 -4.8428774e-06, -0.1419847 -0.083966196 0.0036116689, -0.13760349 -0.090717882 -0.0072359294, -0.13688493 -0.091059804 -0.013005167, -0.13592722 -0.093211055 -0.0072361082, -0.14081684 -0.085772723 0.0057816356, -0.13913889 -0.087578565 0.012995139, -0.13775657 -0.090819269 -5.0514936e-06, -0.13441986 -0.09568879 -5.4389238e-06, -0.13565335 -0.093726039 0.005781278, -0.13521671 -0.094479144 -0.0036234111, -0.13765857 -0.090754867 0.0057813376, -0.13631228 -0.092422903 0.0093908012, -0.13688493 -0.091061234 0.012994811, -0.13499603 -0.080227703 0.046995483, -0.13504311 -0.077501416 0.050657928, -0.13693312 -0.076874375 0.046995558, -0.12490977 -0.074586332 0.072020493, -0.1266387 -0.071611553 0.072020471, -0.12815556 -0.074864686 0.066747509, -0.13223918 -0.080578059 0.052833728, -0.12970294 -0.07881093 0.059995465, -0.13306206 -0.078059912 0.054280832, -0.13297677 -0.083532155 0.046995275, -0.12960424 -0.078973234 0.059995495, -0.12897775 -0.076854467 0.063393757, -0.12927866 -0.08524701 0.052833505, -0.13087639 -0.086785883 0.046995088, -0.12779351 -0.087458193 0.052833438, -0.12733936 -0.077593327 0.065413542, -0.12311128 -0.077519357 0.072020181, -0.12670293 -0.083548963 0.059995279, -0.12575842 -0.087777138 0.056433126, -0.12364022 -0.088018388 0.059995033, -0.12272336 -0.0847058 0.065412931, -0.12448868 -0.082089186 0.06541308, -0.12202986 -0.082579225 0.068739332, -0.12124354 -0.080408961 0.072019875, -0.13247502 -0.060131818 0.072021231, -0.13385984 -0.056982249 0.072021253, -0.13562918 -0.05986762 0.067059539, -0.13099006 -0.069432527 0.067060597, -0.13398626 -0.069248557 0.061995946, -0.13227615 -0.072462082 0.061995775, -0.13442573 -0.062523633 0.067059405, -0.13717169 -0.062702328 0.061996602, -0.13561854 -0.065994859 0.061996311, -0.13101602 -0.063247889 0.072021045, -0.13229609 -0.066912144 0.067059241, -0.12948376 -0.066328466 0.072020806, -0.14131491 -0.07481268 0.037815459, -0.14339063 -0.074012667 0.031995773, -0.14149565 -0.077574402 0.031995781, -0.13564074 -0.070086926 0.057996079, -0.13783783 -0.072270542 0.050833657, -0.1359133 -0.072849691 0.054433547, -0.13389805 -0.073361546 0.057995953, -0.14533977 -0.066656649 0.037815884, -0.14635864 -0.063377142 0.039258331, -0.14668688 -0.06508106 0.035639726, -0.14691092 -0.066752523 0.031996302, -0.14519617 -0.070404559 0.031996027, -0.14335909 -0.065748602 0.044996276, -0.14387339 -0.061444074 0.048658304, -0.1456175 -0.060582936 0.044996507, -0.14286476 -0.071808487 0.037815593, -0.14107212 -0.073030084 0.041418821, -0.14146614 -0.064880967 0.050833881, -0.13730355 -0.066770613 0.05799637, -0.13888511 -0.063415051 0.05799643, -0.14203244 -0.062247902 0.052280866, -0.1409179 -0.070830286 0.044996038, -0.14072952 -0.071203887 0.044995986, -0.13905722 -0.069895387 0.050833553, -0.14558753 -0.07719627 0.0077820271, -0.14662111 -0.075648129 0.0019957274, -0.14466259 -0.079329461 0.0019953549, -0.14352083 -0.077054024 0.024402678, -0.14415838 -0.074401617 0.027995713, -0.14470407 -0.076060385 0.020795695, -0.14224814 -0.077991635 0.02799549, -0.1497843 -0.068699718 0.0077825636, -0.15116496 -0.065389276 0.0092250556, -0.1507591 -0.066785276 0.0056126863, -0.15025644 -0.068142593 0.0019959658, -0.14848621 -0.071918309 0.0019959062, -0.14925858 -0.068459094 0.014996082, -0.1506505 -0.064248443 0.018627092, -0.15161221 -0.063075423 0.014996305, -0.1472306 -0.074014544 0.0077823251, -0.14604573 -0.075799465 0.011391714, -0.14859176 -0.06815362 0.02079618, -0.14597818 -0.070764363 0.027995989, -0.14770596 -0.067083061 0.027996153, -0.14959377 -0.065375566 0.022242948, -0.14671382 -0.073755115 0.014995694, -0.14641149 -0.074353933 0.01499562, -0.14605838 -0.073425949 0.020795986, -0.14424159 -0.076461941 -0.02224876, -0.14415844 -0.074398369 -0.028004184, -0.14224818 -0.077988565 -0.028004497, -0.14526838 -0.078010112 -0.0056224465, -0.14662123 -0.075647712 -0.0020042211, -0.14578201 -0.076642364 -0.0092353374, -0.14466253 -0.079329491 -0.0020044297, -0.1483912 -0.068059236 -0.022248298, -0.15002793 -0.064928055 -0.020805806, -0.14891443 -0.066026986 -0.024412423, -0.14770617 -0.067079902 -0.028003886, -0.14597794 -0.070761383 -0.02800405, -0.14925872 -0.068457335 -0.01500386, -0.15136187 -0.064531833 -0.011397868, -0.15161225 -0.063073725 -0.015003711, -0.1458614 -0.073324531 -0.022248641, -0.14537136 -0.075435042 -0.018633366, -0.14970556 -0.068663001 -0.0092348754, -0.14848615 -0.07191819 -0.0020040572, -0.15025648 -0.068142444 -0.0020039678, -0.15101439 -0.065951437 -0.0077880621, -0.14671384 -0.073753506 -0.015004188, -0.14641131 -0.074352324 -0.015004247, -0.14715326 -0.073974729 -0.0092349499, -0.13707888 -0.072504312 -0.052286416, -0.1356408 -0.07008031 -0.058004066, -0.13389802 -0.073355168 -0.0580042, -0.1414126 -0.075857282 -0.035649434, -0.14339082 -0.074009001 -0.032004148, -0.14122985 -0.074100465 -0.039268389, -0.14149544 -0.077571005 -0.032004431, -0.14095715 -0.064641774 -0.052285746, -0.14278053 -0.061927646 -0.050843358, -0.1408812 -0.062696666 -0.054442957, -0.13888523 -0.063408583 -0.058003604, -0.13730338 -0.066764146 -0.058003813, -0.14335911 -0.065743625 -0.045003727, -0.14611202 -0.062334448 -0.041424826, -0.14561732 -0.060577959 -0.045003414, -0.13855687 -0.069638133 -0.052286148, -0.13894942 -0.071885228 -0.048663929, -0.14497146 -0.066483349 -0.039267838, -0.14519636 -0.070400983 -0.032003924, -0.14691103 -0.066749036 -0.032003671, -0.14650248 -0.064058393 -0.037821427, -0.14091781 -0.070825279 -0.045004085, -0.1407295 -0.071198791 -0.04500407, -0.1425028 -0.071622074 -0.039268136, -0.14106229 0.03558293 0.072026446, -0.14018102 0.038908809 0.072026655, -0.14336389 0.037756294 0.067065135, -0.1457002 0.027385533 0.067065865, -0.14792824 0.029397696 0.062001601, -0.14859478 0.025818765 0.062001467, -0.14407857 0.034929246 0.067064852, -0.14633714 0.036501616 0.062001809, -0.14717552 0.032959253 0.062001809, -0.1418643 0.032237172 0.072026342, -0.14514975 0.030170172 0.067064628, -0.14258696 0.028873205 0.072026029, -0.15712798 0.029617041 0.037821367, -0.15825228 0.031536847 0.032001644, -0.15899137 0.027570456 0.03200151, -0.14974459 0.029773951 0.058001578, -0.15282407 0.029436409 0.05083929, -0.15168019 0.027783483 0.054439023, -0.15042391 0.026126951 0.058001399, -0.15518966 0.03850323 0.037821606, -0.15394153 0.041702539 0.039264277, -0.15526059 0.040575027 0.035645619, -0.15647803 0.039407879 0.032002121, -0.15741444 0.035483509 0.032001987, -0.15307485 0.037978172 0.045002207, -0.15079272 0.041664153 0.048664093, -0.1516196 0.043424696 0.045002371, -0.15646653 0.032932073 0.037821472, -0.15582673 0.030859321 0.041424677, -0.15105353 0.037476182 0.050839573, -0.14897701 0.033403277 0.058001801, -0.14812131 0.037012815 0.058002159, -0.14985444 0.039887726 0.052286565, -0.15433449 0.032482982 0.04500173, -0.15441993 0.032073319 0.04500182, -0.15229639 0.03205362 0.050839245, -0.1523802 0.028781801 -0.052280664, -0.14974469 0.029780358 -0.057998285, -0.15042387 0.026133478 -0.057998776, -0.15785833 0.028862 -0.035643637, -0.15825239 0.031540334 -0.031998232, -0.15662025 0.030121773 -0.039262474, -0.15899144 0.027574062 -0.031998649, -0.15051006 0.037347257 -0.052280024, -0.15024319 0.040605813 -0.050837755, -0.14923798 0.038820446 -0.054437295, -0.14812136 0.037019312 -0.057998016, -0.14897691 0.033409595 -0.057998121, -0.1530748 0.037983179 -0.044998035, -0.15161951 0.043429583 -0.044997558, -0.15310124 0.042364657 -0.041418985, -0.15174852 0.031944036 -0.052280471, -0.15345642 0.030431956 -0.048658133, -0.15479621 0.038409919 -0.039262161, -0.15741441 0.035486996 -0.031998008, -0.15647812 0.039411396 -0.031997889, -0.15448138 0.041260332 -0.037815392, -0.15433425 0.032487899 -0.044998392, -0.15441997 0.032078385 -0.044998214, -0.15606992 0.032852858 -0.039262205, -0.16044666 0.030153155 -0.022242695, -0.1590952 0.031714678 -0.027998492, -0.15983999 0.027716577 -0.027998492, -0.16221413 0.029582649 -0.0056164265, -0.16179879 0.032272965 -0.0019981861, -0.16176274 0.030972123 -0.0092291534, -0.16256279 0.028173625 -0.0019984692, -0.15845193 0.039309889 -0.022242159, -0.15777913 0.042778432 -0.020799711, -0.15759385 0.041224927 -0.024406403, -0.15730569 0.039648324 -0.027997732, -0.15825021 0.035692662 -0.027998015, -0.15937816 0.039539337 -0.01499781, -0.15786155 0.045215935 -0.014997557, -0.15857475 0.043919593 -0.011391863, -0.15975679 0.033615917 -0.022242665, -0.16068932 0.031660169 -0.018627346, -0.1598555 0.039657325 -0.0092287809, -0.16093153 0.03635183 -0.0019982457, -0.15996127 0.040407419 -0.0019978732, -0.15918793 0.042592973 -0.0077819526, -0.16069064 0.033812046 -0.014998198, -0.16082749 0.033155322 -0.014998302, -0.16117182 0.033912867 -0.009229064, -0.16195562 0.030417711 0.0077880621, -0.16179882 0.032272786 0.0020015985, -0.16256273 0.028173208 0.0020016134, -0.16025069 0.029240191 0.024408564, -0.15909511 0.031711578 0.028001741, -0.16055627 0.030754894 0.020801678, -0.15984 0.027713418 0.028001457, -0.15993933 0.039677143 0.0077887475, -0.15895478 0.043126285 0.0092312247, -0.15950808 0.041781992 0.0056186318, -0.15996125 0.040407181 0.0020020157, -0.16093151 0.036351562 0.0020019263, -0.1593781 0.039537668 0.015002012, -0.15784085 0.043697387 0.018633336, -0.15786152 0.045214176 0.015002504, -0.16125628 0.033929646 0.0077881664, -0.16144291 0.031795532 0.011397615, -0.15866597 0.039360493 0.020802185, -0.15825021 0.035689682 0.028001979, -0.15730575 0.039645135 0.028001994, -0.15771751 0.042157382 0.022248894, -0.16069064 0.033810377 0.015001833, -0.16082735 0.033153504 0.015001848, -0.15997265 0.033658981 0.020801902, -0.157353 0.022696614 -0.040998921, -0.15758838 0.024264067 -0.039419621, -0.15629892 0.025498986 -0.042998686, -0.15688244 0.021620125 -0.042999014, -0.15769191 0.0202052 -0.040998995, -0.15877315 0.023001522 -0.035816044, -0.15736961 0.017727971 -0.042999014, -0.15799177 0.017708749 -0.040999293, -0.15916179 0.020770252 -0.03550303, -0.15825212 0.015207976 -0.040999323, -0.15776043 0.013825119 -0.042999431, -0.16045146 0.020923942 -0.029999033, -0.16150488 0.021127313 -0.024496123, -0.16139121 0.024001479 -0.022800982, -0.16097397 0.022468328 -0.026407614, -0.1596242 0.011628777 -0.037263229, -0.15996867 0.013109833 -0.035528213, -0.16204134 0.023448616 -0.018998757, -0.16183962 0.02643007 -0.016998693, -0.16245437 0.022343427 -0.016998887, -0.1624036 0.02079308 -0.018998921, -0.16065012 0.010234922 -0.033644527, -0.16143732 0.010974765 -0.029999435, -0.16296583 0.018242717 -0.016999081, -0.16272205 0.018131912 -0.01899901, -0.16156903 0.0088247359 -0.029999599, -0.16299716 0.015465975 -0.018999204, -0.16254057 0.011183023 -0.024243921, -0.16234009 0.013220042 -0.024516657, -0.16301008 0.012656838 -0.020628497, -0.16337368 0.014130324 -0.01699917, -0.16052505 0.020352125 -0.029998839, -0.16072579 0.018782914 -0.02995424, -0.16306153 0.014770269 -0.018999264, -0.16287376 0.022397667 -0.012998909, -0.16276304 0.025122374 -0.0093928874, -0.16225675 0.026499927 -0.012998641, -0.16287376 0.022396326 0.013001189, -0.16225681 0.026498556 0.013001382, -0.16301778 0.024286121 0.0072300136, -0.1635078 0.020730436 -0.0072296858, -0.16359951 0.021452248 1.1026859e-06, -0.16316696 0.023726076 -0.0057830364, -0.16338688 0.018281311 -0.012999058, -0.16368982 0.020752966 9.8347664e-07, -0.16335991 0.022878557 0.0036175549, -0.16414477 0.014868468 -0.0072300136, -0.16379617 0.014153063 -0.012999371, -0.16438854 0.01187399 -0.0072302818, -0.16357329 0.020737946 0.0057877004, -0.1633869 0.018279791 0.013000891, -0.1643274 0.014884561 5.8114529e-07, -0.16462363 0.010439366 -0.0036176294, -0.16475455 0.0089969337 4.0233135e-07, -0.16449502 0.011300504 0.0057871342, -0.16421038 0.014873624 0.0057871789, -0.16419753 0.012729973 0.0093966872, -0.16379616 0.014151633 0.013000816, -0.16204146 0.02344656 0.019001171, -0.1615908 0.024913281 0.020632267, -0.16183963 0.026428163 0.01700142, -0.16245435 0.022341549 0.017001346, -0.1624034 0.020790815 0.019001156, -0.16123696 0.023386836 0.024247929, -0.16296582 0.01824078 0.017000973, -0.16272205 0.018129855 0.019001067, -0.16150494 0.021124423 0.024498388, -0.16299699 0.015463799 0.019000635, -0.16337365 0.014128387 0.017000809, -0.16045146 0.020920515 0.030001104, -0.1591617 0.02076605 0.035505474, -0.15831174 0.023505509 0.037262827, -0.15943393 0.02222693 0.033644348, -0.16274121 0.01177007 0.022800729, -0.16234009 0.01321727 0.024518028, -0.15735279 0.022692084 0.041001171, -0.15629885 0.025494099 0.043001428, -0.15688244 0.021615326 0.04300116, -0.15769209 0.020200729 0.041001156, -0.16220801 0.010295719 0.02640745, -0.16143733 0.010971367 0.030000314, -0.1573696 0.017723233 0.043000832, -0.15799171 0.017704248 0.041000903, -0.16156909 0.0088213682 0.030000493, -0.15825209 0.015203446 0.041000828, -0.16004743 0.011069357 0.035820141, -0.15996867 0.01310578 0.035529628, -0.15895729 0.01245299 0.039423361, -0.1577604 0.01382035 0.043000698, -0.16053459 0.02034992 0.029956505, -0.16072573 0.018779576 0.029956475, -0.15833287 0.014338702 0.041000813, -0.15556353 0.021443516 0.047001213, -0.15390049 0.023604453 0.050663635, -0.15498734 0.025273114 0.047001347, -0.14415973 0.019565225 0.072025418, -0.1436566 0.022968948 0.072025813, -0.14687102 0.021371305 0.066753022, -0.15362647 0.019450456 0.052839488, -0.15054156 0.019251049 0.060001105, -0.15269966 0.021932542 0.054286391, -0.15604502 0.017600834 0.047000825, -0.15056559 0.019062459 0.060000896, -0.14875461 0.020328343 0.063399374, -0.15422305 0.01395449 0.052838981, -0.15643172 0.013747573 0.047000811, -0.15444036 0.0112997 0.052838907, -0.14793426 0.018728971 0.065418608, -0.14458212 0.016150504 0.072025269, -0.15115026 0.013676047 0.060000725, -0.15304807 0.00978145 0.05643855, -0.15154213 0.0082720518 0.060000457, -0.14876001 0.010290265 0.065418519, -0.14850867 0.013436645 0.065418407, -0.14689147 0.011520535 0.068744749, -0.14492375 0.012726992 0.072025374, -0.16377406 -0.014406532 -0.01300104, -0.16427244 -0.011725634 -0.0093949884, -0.16408534 -0.01026991 -0.013000727, -0.16377421 -0.014408082 0.012998983, -0.16408537 -0.01027137 0.012999296, -0.16433485 -0.01259774 0.0072280616, -0.16402113 -0.016173214 -0.0072317868, -0.1642713 -0.015489995 -9.6857548e-07, -0.16435544 -0.013176918 -0.0057850629, -0.16335833 -0.018534005 -0.01300104, -0.16420369 -0.016191632 -9.8347664e-07, -0.16435525 -0.014046103 0.0036156923, -0.16333771 -0.022030085 -0.007232219, -0.16283871 -0.022649854 -0.013001353, -0.16290921 -0.025003403 -0.0072324425, -0.16408691 -0.016180456 0.0057855546, -0.16335832 -0.018535614 0.012998968, -0.16351928 -0.02205497 -1.3411045e-06, -0.16281907 -0.026454538 -0.0036194921, -0.16262583 -0.027889878 -1.6838312e-06, -0.16288549 -0.025586367 0.005784899, -0.16340311 -0.022039562 0.0057851076, -0.16291368 -0.02412647 0.0093945563, -0.16283861 -0.022651285 0.012998834, -0.15845762 -0.012886673 -0.041000947, -0.15903595 -0.011410981 -0.039421558, -0.15805352 -0.0099201798 -0.043000817, -0.15775943 -0.013831615 -0.043000907, -0.15823406 -0.015391082 -0.041001141, -0.15991028 -0.012905449 -0.035818011, -0.15736848 -0.017734379 -0.043001235, -0.15797067 -0.017891556 -0.04100123, -0.15979271 -0.015167296 -0.035505146, -0.15766811 -0.020387471 -0.041001186, -0.15688089 -0.021626413 -0.043001309, -0.16108423 -0.015304446 -0.030001, -0.16215669 -0.015340626 -0.024497926, -0.16268536 -0.012513101 -0.022803023, -0.16193736 -0.013914913 -0.026409701, -0.15820937 -0.02418232 -0.037265286, -0.15887475 -0.022815108 -0.03553021, -0.16319616 -0.013197035 -0.019000754, -0.1636631 -0.010245323 -0.017000735, -0.16335292 -0.014366329 -0.017000899, -0.16295844 -0.015866399 -0.019000769, -0.15889932 -0.02576974 -0.033646435, -0.15983152 -0.025223553 -0.030001655, -0.16293898 -0.018477976 -0.017001197, -0.16267668 -0.01853174 -0.019001275, -0.15948151 -0.027349025 -0.030001581, -0.16235161 -0.021191984 -0.01900135, -0.16095352 -0.025265813 -0.024245963, -0.16121151 -0.023235291 -0.024518669, -0.16173922 -0.023933768 -0.020630687, -0.16242158 -0.022577941 -0.017001212, -0.16102855 -0.01587835 -0.030001044, -0.16087544 -0.017452806 -0.029956296, -0.16225965 -0.021884531 -0.01900129, -0.15643555 -0.013710231 0.046999186, -0.15529492 -0.011233568 0.050661631, -0.15672599 -0.0098485947 0.046999358, -0.14489996 -0.013003975 0.072023749, -0.14516677 -0.0095736682 0.072023906, -0.14794518 -0.011846453 0.066751026, -0.15410353 -0.01522249 0.052837513, -0.15105179 -0.014730394 0.059999079, -0.15375239 -0.012596428 0.054284275, -0.15605003 -0.017563641 0.04699897, -0.15103333 -0.014919549 0.059999354, -0.14954923 -0.013282478 0.063397437, -0.15346199 -0.020713359 0.052837059, -0.1555694 -0.021406442 0.046998687, -0.15308322 -0.023349941 0.052836992, -0.14839369 -0.014659137 0.065416954, -0.14455184 -0.01642707 0.072023615, -0.15040445 -0.020301104 0.059998974, -0.15138817 -0.024520218 0.056436814, -0.14958425 -0.02565676 0.059998617, -0.14732081 -0.023070067 0.065416537, -0.14777604 -0.019946694 0.065416485, -0.14577317 -0.021454841 0.068742916, -0.14412321 -0.019840688 0.072023399, -0.16319628 -0.013199002 0.018999159, -0.16308369 -0.011668682 0.02063027, -0.16366306 -0.010247171 0.016999409, -0.16335283 -0.014368087 0.0169992, -0.16295838 -0.015868574 0.018999085, -0.16239874 -0.013078123 0.024245918, -0.16293895 -0.018479884 0.016998813, -0.1626768 -0.018533796 0.018998906, -0.16215669 -0.015343487 0.024496242, -0.16235162 -0.02119419 0.018998712, -0.1624216 -0.022579968 0.016998798, -0.16108423 -0.015307754 0.029999003, -0.15979268 -0.015171289 0.035503455, -0.15957355 -0.012311459 0.037260979, -0.16038296 -0.013807774 0.033642322, -0.16128013 -0.024738401 0.022798628, -0.16121142 -0.023238212 0.024515986, -0.15845767 -0.012891233 0.040999062, -0.15805352 -0.0099250078 0.042999394, -0.15775934 -0.013836235 0.042999141, -0.15823396 -0.015395701 0.040998995, -0.16043268 -0.026057035 0.026405528, -0.1598314 -0.025226861 0.029998556, -0.15736824 -0.017739236 0.042998925, -0.15797076 -0.017896086 0.040998839, -0.15948148 -0.027352363 0.02999831, -0.15766792 -0.020392209 0.040998727, -0.15849812 -0.024822235 0.035818025, -0.15887469 -0.022819191 0.035527602, -0.1577433 -0.023230761 0.039421536, -0.1568808 -0.021631181 0.04299853, -0.16103829 -0.015882552 0.029954493, -0.16087522 -0.017456263 0.029954225, -0.15755436 -0.021253258 0.040998757, -0.16313322 -0.0063057244 -0.022244826, -0.16216312 -0.0044825375 -0.028000325, -0.16199972 -0.0085460842 -0.028000623, -0.1647298 -0.0072550774 -0.0056185871, -0.16492347 -0.0045398474 -0.0020004213, -0.16459891 -0.0057999194 -0.0092313141, -0.1647561 -0.0087063909 -0.0020004511, -0.16322623 0.0030653775 -0.022244304, -0.16334207 0.0065966547 -0.020801663, -0.16281578 0.0051234663 -0.02440843, -0.16218391 0.0036503971 -0.027999863, -0.16222453 -0.00041612983 -0.028000027, -0.16418023 0.003082931 -0.014999866, -0.16396494 0.008954674 -0.014999628, -0.16437185 0.0075322688 -0.011393741, -0.16323151 -0.0027761161 -0.022244602, -0.1637053 -0.0048903227 -0.018629342, -0.16467208 0.0030917227 -0.0092307627, -0.1649857 -0.00037020445 -0.0020001978, -0.16494228 0.0037996173 -0.0019999295, -0.16467458 0.0061024129 -0.0077840686, -0.16418539 -0.002792716 -0.015000284, -0.16417266 -0.0034634769 -0.015000299, -0.1646772 -0.0028014183 -0.0092311203, -0.15496337 -0.0058476329 -0.052282602, -0.15261623 -0.0042875111 -0.058000296, -0.15246703 -0.0079942644 -0.058000639, -0.16032265 -0.0069881678 -0.035645545, -0.16130272 -0.0044648051 -0.032000288, -0.15939552 -0.00548473 -0.039264485, -0.16114056 -0.0084961355 -0.032000631, -0.15504637 0.0029192865 -0.052281976, -0.1555113 0.0061555803 -0.050839633, -0.1541339 0.0046386123 -0.054439276, -0.15264446 0.0031312108 -0.057999969, -0.15267549 -0.00057831407 -0.058000222, -0.15768832 0.0029685497 -0.044999793, -0.15868935 0.0072344542 -0.041420743, -0.15748163 0.0086023808 -0.044999704, -0.15505156 -0.0026238859 -0.052282318, -0.1563801 -0.0044781864 -0.048660204, -0.15946168 0.0030014217 -0.039263934, -0.16136396 -0.00043061376 -0.032000124, -0.16132431 0.0036038458 -0.031999826, -0.159789 0.0058507025 -0.037817389, -0.1576938 -0.0026690662 -0.045000136, -0.15768602 -0.003087461 -0.04500033, -0.15946698 -0.002699554 -0.039264411, -0.16466378 -0.0063833892 0.0077860355, -0.1649237 -0.0045399666 0.0019995421, -0.16475615 -0.0087067187 0.0019993335, -0.16273972 -0.0071520805 0.024406478, -0.16216306 -0.0044856966 0.02799952, -0.16337483 -0.0057434142 0.020799622, -0.16199973 -0.008548975 0.027999312, -0.16475835 0.0030924976 0.0077866167, -0.16456604 0.0066742599 0.0092291087, -0.16480634 0.0052404702 0.0056167841, -0.16494212 0.0037993193 0.0020001978, -0.16498549 -0.00037050247 0.001999706, -0.16418023 0.0030812919 0.015000179, -0.16396512 0.0089531243 0.015000448, -0.16360727 0.0074789226 0.01863113, -0.16476369 -0.0028038621 0.0077860802, -0.16447049 -0.0049260855 0.011395544, -0.16344661 0.0030671954 0.020800054, -0.16222458 -0.00041922927 0.027999714, -0.16218394 0.0036472976 0.028000161, -0.1631442 0.0060048699 0.022246748, -0.1641853 -0.0027944744 0.014999643, -0.16417259 -0.003465265 0.014999673, -0.16345176 -0.0027823746 0.020799831, -0.15977944 -0.0060897768 0.03781949, -0.16130266 -0.0044684112 0.031999812, -0.16114059 -0.0084997118 0.031999633, -0.15261626 -0.004294008 0.057999723, -0.15554331 -0.005308181 0.050837383, -0.15406051 -0.0066651404 0.054437205, -0.15246709 -0.0080006123 0.057999551, -0.15986699 0.0030047894 0.037819713, -0.15936211 0.0064017177 0.039262012, -0.16039713 0.0050087869 0.035643816, -0.16132441 0.0036001503 0.032000184, -0.16136402 -0.00043419003 0.032000005, -0.15768827 0.0029635727 0.045000121, -0.15748161 0.0085973144 0.045000523, -0.15628371 0.0070648789 0.048662096, -0.15987246 -0.0027107 0.037819415, -0.15878725 -0.0045890808 0.04142262, -0.155606 0.0029238164 0.050837778, -0.15267551 -0.00058478117 0.057999916, -0.15264443 0.0031247437 0.05800017, -0.15497382 0.0055418909 0.052284651, -0.15769356 -0.0026742518 0.044999756, -0.15768597 -0.0030924678 0.044999786, -0.15561132 -0.0026392341 0.050837263, -0.14544433 0.0033013821 0.072024755, -0.14532539 0.0067399442 0.072025053, -0.1481716 0.0049080551 0.067063116, -0.14814189 -0.0057225823 0.067064166, -0.1507618 -0.0042567253 0.061999612, -0.15061536 -0.0078939497 0.061999433, -0.14823946 0.0019927621 0.067062944, -0.15079139 0.0030232668 0.062000088, -0.15082064 -0.00061690807 0.061999977, -0.1454818 -0.00013905764 0.072024517, -0.14822489 -0.0028850734 0.067062519, -0.14543796 -0.0035793185 0.072024114, 0.06509836 0.14971566 -0.022236049, 0.066320047 0.14805096 -0.027991921, 0.062587947 0.14966688 -0.027991638, 0.064936742 0.1515646 -0.0056096315, 0.067467332 0.15056089 -0.0019915402, 0.066190973 0.15081561 -0.0092224479, 0.063640684 0.15221789 -0.00199157, 0.073581964 0.14573342 -0.022236273, 0.076814041 0.14430541 -0.020794094, 0.075257927 0.1444709 -0.024400666, 0.073656559 0.14454114 -0.02799207, 0.070010245 0.14634204 -0.027991861, 0.074012101 0.14658478 -0.01499182, 0.078104109 0.1448265 -0.011386156, 0.079208955 0.14384302 -0.014991999, 0.068321273 0.14827248 -0.022236228, 0.066622153 0.14961672 -0.018620759, 0.0742338 0.1470235 -0.0092227757, 0.071251079 0.14880759 -0.0019917488, 0.074989036 0.14695939 -0.0019918382, 0.076947317 0.14571947 -0.007776171, 0.068720534 0.14913884 -0.01499176, 0.068110615 0.14941832 -0.01499182, 0.068926454 0.14958519 -0.0092225373, 0.061965019 0.14215854 -0.052274302, 0.062351838 0.13936731 -0.057992339, 0.058947474 0.1408411 -0.05799228, 0.063263342 0.14748064 -0.035636917, 0.06596227 0.14726847 -0.03199181, 0.064215809 0.14599308 -0.039256096, 0.062259912 0.14887151 -0.03199178, 0.069899648 0.13842943 -0.052274302, 0.073017269 0.13744402 -0.050832197, 0.07105276 0.13686159 -0.05443196, 0.069048136 0.1361739 -0.057992309, 0.06571947 0.13781127 -0.057992399, 0.071090668 0.14078784 -0.044992194, 0.075368598 0.13983837 -0.041413486, 0.07607685 0.13815722 -0.044992328, 0.06490761 0.14083937 -0.052274346, 0.063813746 0.14284045 -0.048652127, 0.071890175 0.14237067 -0.0392562, 0.069623649 0.14557326 -0.031992108, 0.073241279 0.14378715 -0.031992048, 0.074599296 0.14142922 -0.037809625, 0.066013709 0.14323869 -0.044992134, 0.065633297 0.14341339 -0.044992089, 0.06675607 0.14484903 -0.039256096, 0.068714902 0.13137043 -0.067055717, 0.069130749 0.12801135 -0.072017491, 0.066084117 0.12961054 -0.072017342, 0.058240294 0.13912657 -0.061992377, 0.061581075 0.13768053 -0.061992183, 0.059123933 0.13595611 -0.067056909, 0.066117272 0.13269588 -0.067056984, 0.064885795 0.13615423 -0.061992571, 0.068152934 0.13454849 -0.061992571, 0.063000724 0.13113695 -0.072017312, 0.061716124 0.13479918 -0.067056939, 0.059881881 0.13259023 -0.072017103, 0.063840851 0.14659536 0.037827924, 0.065962285 0.14726496 0.032008156, 0.062259942 0.14886788 0.032008305, 0.062351912 0.13936096 0.058007836, 0.062707812 0.14243865 0.050845608, 0.060842156 0.14169109 0.054445446, 0.058947474 0.14083463 0.058007881, 0.072072893 0.14272818 0.037827611, 0.074914247 0.14079946 0.039269641, 0.074108258 0.14233664 0.035651371, 0.073241323 0.14378342 0.032007962, 0.06962359 0.14556965 0.032008052, 0.071090698 0.14078283 0.045007825, 0.074176788 0.13773757 0.048669443, 0.07607697 0.13815203 0.04500781, 0.066925824 0.1452128 0.037827879, 0.064762726 0.14505005 0.041431054, 0.070151925 0.1389235 0.050845355, 0.065719381 0.13780493 0.058007732, 0.069048181 0.13616756 0.058007613, 0.0722363 0.13721782 0.052292109, 0.066013664 0.1432336 0.045008019, 0.065633476 0.1434083 0.045007914, 0.065141991 0.14134195 0.05084534, 0.065694198 0.15112594 0.0077948868, 0.067467302 0.15056071 0.0020082295, 0.063640594 0.1522176 0.0020084083, 0.064167574 0.14972436 0.024415255, 0.066319957 0.14804792 0.028008074, 0.065712154 0.14968577 0.020808339, 0.062587947 0.14966372 0.028008193, 0.074272677 0.1470997 0.0077946484, 0.07741639 0.14537212 0.0092368126, 0.076228574 0.14621094 0.0056245029, 0.07498908 0.14695916 0.0020080209, 0.07125099 0.14880741 0.0020081401, 0.074012145 0.14658311 0.015007943, 0.079208896 0.14384145 0.015008003, 0.077725664 0.14415866 0.0186387, 0.068962559 0.14966252 0.007794857, 0.06692335 0.15031916 0.011404276, 0.073681444 0.1459277 0.02080822, 0.07001023 0.14633888 0.028007984, 0.073656648 0.14453784 0.028008074, 0.076196924 0.14438063 0.022254646, 0.068720564 0.14913717 0.015008271, 0.068110675 0.14941669 0.015008271, 0.068413407 0.14847037 0.020808488, 0.030418336 0.16195521 0.007795468, 0.03227289 0.16179869 0.0020088702, 0.028173357 0.16256264 0.0020089895, 0.029241681 0.16024911 0.024415821, 0.031713098 0.15909362 0.028008863, 0.030756265 0.16055501 0.02080895, 0.027715117 0.15983847 0.028008923, 0.039677709 0.15993869 0.0077952892, 0.043126747 0.15895417 0.0092376173, 0.041782349 0.15950751 0.005625248, 0.040407404 0.15996113 0.0020089149, 0.036351621 0.16093135 0.0020088255, 0.039538458 0.15937713 0.015008882, 0.04369846 0.15783972 0.01863952, 0.045214966 0.15786073 0.015008807, 0.033930242 0.16125578 0.0077955276, 0.031796053 0.16144231 0.011405066, 0.03936176 0.15866464 0.020809025, 0.035691097 0.15824857 0.02800867, 0.0396467 0.15730411 0.028008759, 0.042158589 0.15771607 0.022255421, 0.033811256 0.16068974 0.015008956, 0.033154428 0.16082656 0.015008852, 0.033660084 0.15997127 0.020808905, 0.029619336 0.15712583 0.03782852, 0.03153871 0.15825045 0.032008782, 0.02757214 0.15898976 0.032008752, 0.029777125 0.14974132 0.058008343, 0.029439479 0.15282109 0.050846189, 0.027786672 0.15167713 0.054445982, 0.026130304 0.15042058 0.058008417, 0.03850542 0.15518737 0.037828326, 0.041704804 0.15393922 0.039270535, 0.040576905 0.15525854 0.03565219, 0.039409742 0.15647614 0.032008708, 0.035485208 0.15741259 0.032008722, 0.037980676 0.15307209 0.04500851, 0.043427095 0.15161708 0.045008421, 0.041666865 0.15078998 0.048670173, 0.032934308 0.15646455 0.037828431, 0.030861884 0.15582421 0.04143168, 0.037479073 0.15105066 0.050845921, 0.033406526 0.14897358 0.058008358, 0.037016243 0.14811814 0.058008343, 0.039890677 0.14985156 0.052292705, 0.03248553 0.15433186 0.045008749, 0.032076001 0.15441748 0.045008644, 0.03205651 0.15229356 0.050846025, 0.037760004 0.14336729 -0.067055032, 0.038912967 0.14018497 -0.072016776, 0.035587013 0.14106613 -0.072016597, 0.025822282 0.14859822 -0.061991826, 0.029401183 0.14793169 -0.061991766, 0.027389392 0.14570391 -0.067056343, 0.034932882 0.14408147 -0.067056447, 0.032962635 0.1471791 -0.061991826, 0.036505103 0.1463407 -0.061991885, 0.032241255 0.14186817 -0.072016641, 0.030174032 0.14515269 -0.067056358, 0.028877512 0.14259091 -0.072016716, 0.028778702 0.152383 -0.052273631, 0.029777154 0.14974785 -0.057991728, 0.026130214 0.15042701 -0.057991654, 0.028860137 0.15786037 -0.0356365, 0.03153865 0.15825415 -0.031991214, 0.030119702 0.15662217 -0.039255425, 0.027572259 0.15899321 -0.031991184, 0.037344217 0.15051299 -0.052273616, 0.040603027 0.15024596 -0.050831661, 0.03881751 0.14924091 -0.054431126, 0.037016034 0.14812464 -0.057991862, 0.033406422 0.1489802 -0.057991788, 0.037980646 0.1530773 -0.044991583, 0.043427289 0.15162206 -0.044991538, 0.042362615 0.15310353 -0.041412711, 0.03194119 0.15175158 -0.052273706, 0.030429244 0.15345901 -0.048651278, 0.038407743 0.15479833 -0.039255619, 0.035485283 0.15741619 -0.031991094, 0.039409727 0.15647981 -0.031991288, 0.04125838 0.15448335 -0.03780897, 0.032485455 0.15433699 -0.044991389, 0.032075942 0.15442252 -0.044991419, 0.032850817 0.15607217 -0.039255455, 0.030151859 0.16044757 -0.022235453, 0.031713039 0.15909666 -0.027991161, 0.027715117 0.15984163 -0.027991191, 0.029582188 0.16221446 -0.0056090057, 0.032272741 0.16179898 -0.0019909143, 0.030971721 0.1617634 -0.009221971, 0.028173268 0.16256291 -0.0019909292, 0.039308786 0.15845302 -0.022235513, 0.042777285 0.15778029 -0.020793259, 0.041223556 0.15759525 -0.024399877, 0.039646789 0.15730727 -0.027991295, 0.035691187 0.1582517 -0.027991325, 0.039538398 0.15937889 -0.014991075, 0.045215115 0.15786237 -0.014991179, 0.043918982 0.15857533 -0.011385426, 0.033614799 0.15975797 -0.022235498, 0.031659216 0.16069043 -0.018620208, 0.039656892 0.1598559 -0.0092218816, 0.03635174 0.16093156 -0.0019909143, 0.040407524 0.15996131 -0.0019911826, 0.04259266 0.15918833 -0.0077756792, 0.033811137 0.16069141 -0.014991209, 0.033154383 0.1608282 -0.014991075, 0.03391248 0.16117221 -0.0092219859, 0.057139635 0.14835995 -0.040991798, 0.058720276 0.14824063 -0.039412767, 0.059637129 0.14670891 -0.042991906, 0.055985391 0.14814079 -0.042991787, 0.054786205 0.14924514 -0.040991694, 0.057753175 0.14967656 -0.035808846, 0.052299306 0.14948204 -0.042991877, 0.052419201 0.15009272 -0.040991694, 0.055664256 0.15055192 -0.035495967, 0.050039008 0.15090296 -0.040991873, 0.048581243 0.15073141 -0.042991683, 0.056101575 0.15177447 -0.029991642, 0.056534559 0.15275601 -0.024488598, 0.059311241 0.15200552 -0.022793815, 0.05772391 0.15193996 -0.026400372, 0.046854913 0.15303689 -0.037255421, 0.048375532 0.15304312 -0.03552033, 0.058917299 0.15276217 -0.01899156, 0.06177935 0.15190166 -0.016991556, 0.057931721 0.15341038 -0.016991541, 0.056408852 0.15370622 -0.01899156, 0.045724541 0.15434691 -0.033636361, 0.046621203 0.15494946 -0.029991537, 0.054047823 0.15482143 -0.016991362, 0.053885445 0.15460882 -0.018991366, 0.044554442 0.15555632 -0.029991359, 0.051347449 0.1554701 -0.018991351, 0.047070205 0.15597838 -0.02423583, 0.049011379 0.15532973 -0.024508744, 0.048611522 0.15610796 -0.020620599, 0.05012925 0.15613425 -0.016991392, 0.055560499 0.15197331 -0.029991552, 0.054075226 0.15251848 -0.029946655, 0.050683603 0.15568787 -0.018991336, 0.058078364 0.15380695 -0.012991518, 0.060710356 0.15309253 -0.0093856156, 0.061940461 0.15229264 -0.012991577, 0.058078393 0.15380549 0.013008446, 0.061940432 0.15229121 0.013008386, 0.059952408 0.15352586 0.007237196, 0.056594372 0.15479574 -0.0072223842, 0.057318702 0.15472415 8.5532665e-06, 0.059438914 0.15379679 -0.0057758689, 0.054179296 0.15522334 -0.012991518, 0.05665724 0.15496761 8.5234642e-06, 0.058656275 0.15417287 0.0036249161, 0.051020935 0.15672112 -0.0072220564, 0.050245717 0.15654084 -0.012991324, 0.048155874 0.15762523 -0.0072220862, 0.056616873 0.15485707 0.0057950318, 0.054179341 0.15522188 0.013008565, 0.051077679 0.15689513 8.7916851e-06, 0.046809703 0.15817326 -0.0036093593, 0.045432791 0.15862173 8.7022781e-06, 0.047621176 0.15785578 0.0057950914, 0.051041305 0.15678316 0.0057952404, 0.048948765 0.15724733 0.0094047785, 0.050245747 0.15653944 0.013008654, 0.051157221 0.13619459 -0.07201691, 0.053853616 0.13715342 -0.068734825, 0.054363579 0.13494679 -0.072017133, 0.055524796 0.14689353 -0.046991795, 0.059130087 0.14547959 -0.046991885, 0.056126848 0.1443257 -0.052832678, 0.05094184 0.13940448 -0.066746205, 0.052270263 0.14248586 -0.059991926, 0.053288653 0.13927355 -0.065407887, 0.047922254 0.13736629 -0.072017014, 0.052091867 0.14255124 -0.05999212, 0.054212779 0.14346111 -0.056432039, 0.045933396 0.14113399 -0.066745967, 0.044660509 0.13846123 -0.072016835, 0.043457016 0.14191619 -0.066745922, 0.052950099 0.14489928 -0.054274693, 0.05188553 0.1482181 -0.046991825, 0.046970472 0.14431983 -0.059992, 0.041789323 0.14590442 -0.059991837, 0.044671595 0.14766186 -0.054274768, 0.042645961 0.14395624 -0.063391939, 0.047744244 0.14669707 -0.054274708, 0.046451494 0.14861351 -0.050652012, 0.048214883 0.14945245 -0.046991661, 0.05891721 0.15276006 0.019008428, 0.060247123 0.1519942 0.020639449, 0.061779246 0.15189984 0.017008513, 0.057931811 0.1534085 0.017008483, 0.056408852 0.15370396 0.019008487, 0.058680534 0.15198854 0.024255216, 0.054047748 0.15481943 0.017008692, 0.05388546 0.15460667 0.019008592, 0.056534484 0.15275341 0.024505511, 0.05134742 0.15546805 0.019008771, 0.05012925 0.15613228 0.017008796, 0.056101575 0.15177113 0.030008405, 0.055664301 0.15054786 0.035512641, 0.058146074 0.14910942 0.03726992, 0.057148948 0.1504882 0.033651561, 0.047689527 0.15604004 0.022808641, 0.049011379 0.15532687 0.024526015, 0.057139665 0.14835539 0.041008279, 0.05963704 0.14670414 0.043007955, 0.055985361 0.14813611 0.043008104, 0.05478628 0.14924049 0.041008115, 0.046133801 0.15584821 0.026415646, 0.046621114 0.1549463 0.03000851, 0.052299455 0.14947712 0.043008253, 0.052419186 0.15008819 0.041008279, 0.044554472 0.15555304 0.030008629, 0.050039023 0.15089846 0.041008294, 0.046407521 0.15356901 0.035827994, 0.048375562 0.15303916 0.035537437, 0.0475142 0.15219805 0.039431185, 0.048581213 0.15072671 0.043008313, 0.055563837 0.15197903 0.029963747, 0.054075226 0.15251508 0.029963776, 0.049213737 0.15116969 0.041008443, -0.11253719 -0.054413706 0.07449697, -0.1285221 -0.053689212 0.074497044, -0.12450811 -0.062436193 0.0744965, -0.12896097 -0.057422876 0.074496716, -0.11541091 -0.048018128 0.074497312, -0.13025977 -0.054412216 0.074496917, -0.12927978 -0.051837832 0.074497044, 0.11488701 0.082025141 0.074504673, 0.11295079 0.084671348 0.074504822, -0.13001096 -0.049975634 0.074497037, -0.11792151 -0.041471422 0.074497677, -0.13071528 -0.048103034 0.074497245, -0.13355285 -0.045737088 0.074497476, -0.13245448 -0.048826724 0.074497283, 0.11095345 0.087272018 0.074504778, 0.071496651 -0.12172535 0.074493125, 0.067737341 -0.12170744 0.074493185, 0.068650365 -0.12335324 0.074493185, 0.10889642 0.089825481 0.074504957, -0.13457885 -0.042622745 0.074497536, 0.060398519 -0.1275968 0.074492723, 0.062432036 -0.12451226 0.074492887, 0.057418615 -0.12896514 0.074492872, 0.063345745 -0.12615958 0.074492976, -0.13372466 -0.038961768 0.074497618, -0.12006111 -0.034794211 0.074498042, 0.074304476 -0.12003195 0.074493229, 0.075979814 -0.11673918 0.074493408, 0.077072293 -0.11827374 0.074493378, -0.13553251 -0.039485514 0.074497752, -0.13427043 -0.037037164 0.074497871, -0.13478851 -0.035104692 0.074497953, 0.053684905 -0.12852615 0.074492738, 0.05440785 -0.13026398 0.074492723, -0.12182292 -0.028007478 0.074498266, 0.084675744 -0.11295503 0.074493662, 0.080937818 -0.11335781 0.074493617, 0.082029432 -0.11489132 0.074493632, 0.10498023 0.094372541 0.074505359, 0.10275982 0.096785575 0.074505314, -0.13527869 -0.033165246 0.074498087, -0.13783348 -0.030496478 0.07449834, -0.13708797 -0.033689469 0.074497968, 0.10048413 0.099145979 0.074505657, 0.098153949 0.10145327 0.074505702, 0.045732975 -0.13355696 0.074492663, 0.048098862 -0.13071945 0.074492604, 0.042618588 -0.13458315 0.07449235, 0.048822418 -0.13245869 0.074492723, 0.088572353 -0.10749814 0.074494094, -0.1385044 -0.027286798 0.07449846, 0.08727622 -0.11095774 0.074493885, 0.089829609 -0.10890076 0.07449396, -0.1372458 -0.023744434 0.074498735, -0.12320139 -0.021132857 0.07449878, -0.13910085 -0.024062455 0.074498653, -0.1375725 -0.021770716 0.074498743, 0.038957566 -0.13372889 0.074492574, 0.039481252 -0.13553664 0.07449244, -0.13787104 -0.019792587 0.074498758, -0.12419235 -0.014191657 0.074499212, 0.096789643 -0.1027641 0.074494123, 0.093120515 -0.1035831 0.074494183, 0.094376802 -0.10498449 0.074494094, 0.093753248 0.10553321 0.074506015, 0.091276795 0.10768238 0.074506059, -0.13814104 -0.017810345 0.074498914, 0.033685401 -0.13709232 0.074492455, 0.033161029 -0.13528299 0.074492455, 0.030492052 -0.13783768 0.074492306, 0.027282596 -0.13850859 0.074492201, -0.1403809 -0.014872164 0.07449922, -0.13999766 -0.018128723 0.074499063, 0.10005096 -0.096905321 0.074494615, 0.088751003 0.10977334 0.074506223, 0.09915027 -0.10048839 0.074494317, 0.10145742 -0.09815833 0.07449472, 0.08617726 0.11180508 0.074506149, -0.14068836 -0.011607736 0.074499302, -0.13904075 -0.0082286 0.074499533, -0.12479241 -0.0072058141 0.074499808, 0.023740113 -0.13725001 0.074492425, 0.024058282 -0.13910499 0.074492261, 0.10768642 -0.091280878 0.074494958, 0.10413222 -0.092505634 0.07449469, 0.10553737 -0.093757391 0.074494734, -0.14091972 -0.0083369315 0.074499585, -0.13914463 -0.0062306225 0.074499607, -0.12499982 -0.00019738078 0.074499905, -0.13921979 -0.0042314231 0.074499793, 0.081347376 0.1153667 0.074506372, 0.078645781 0.11722493 0.074506417, 0.018124551 -0.1400018 0.074492022, 0.017806053 -0.13814518 0.074492335, 0.014868051 -0.140385 0.074492157, -0.13926607 -0.0022314191 0.074499883, 0.011603415 -0.14069244 0.074492052, 0.11027138 -0.085093915 0.074495167, 0.10977738 -0.088755101 0.074495047, 0.11180916 -0.086181521 0.074495256, 0.075901777 0.11901999 0.07450667, -0.1411629 0.00093880296 0.074500069, -0.14114669 -0.0023399293 0.074499816, 0.07311672 0.1207509 0.07450667, -0.14110288 0.0042173266 0.074500367, 0.0082241893 -0.13904512 0.074492171, 0.0083326548 -0.14092389 0.074491993, -0.13908744 0.007390976 0.074500255, 0.11722924 -0.078649968 0.074495658, 0.11383431 -0.080264807 0.074495345, 0.11537091 -0.081351519 0.074495479, -0.12481403 0.006811738 0.074500352, -0.14096671 0.0074934959 0.074500382, 0.065982386 -0.12266773 0.074493229, 0.060633928 -0.10931367 0.074493855, 0.064213827 -0.12360269 0.074493095, -0.13896677 0.0093877614 0.074500322, -0.13881758 0.011382729 0.074500673, -0.12423562 0.013799459 0.074500784, 0.066667482 -0.10574186 0.074493974, 0.077648565 -0.11563578 0.074493453, 0.067918479 0.12374941 0.074506983, 0.065025777 0.1252934 0.074507043, -0.13863984 0.013375491 0.074500762, 0.0544094 -0.11254138 0.074493676, 0.062098056 0.12676981 0.074507013, -0.14016971 0.016738325 0.074500971, -0.14052075 0.01347816 0.074500777, 0.072491378 -0.10183752 0.074494317, 0.079301357 -0.11450869 0.074493662, 0.059136808 0.12817803 0.074507073, -0.13974285 0.019989282 0.074501112, 0.051833555 -0.12928411 0.074492618, 0.048013926 -0.11541519 0.074493438, 0.049971402 -0.13001516 0.074492633, -0.13738495 0.0229173 0.074501365, -0.12326619 0.020743608 0.074501216, -0.13924091 0.023229688 0.074501351, 0.078087211 -0.09761256 0.074494451, 0.090107098 -0.10621503 0.074494004, -0.13704157 0.024888217 0.074501514, 0.041467071 -0.11792579 0.074493468, -0.12190892 0.027622521 0.074501589, -0.13666998 0.026853859 0.074501544, 0.053635314 0.13057566 0.074507445, 0.050587937 0.13178617 0.07450743, -0.13627002 0.028813958 0.074501604, 0.0023358017 -0.14115089 0.074491963, 0.0022272617 -0.13927028 0.074492291, -0.0009431541 -0.14116701 0.074492007, 0.08343716 -0.09308067 0.074494779, 0.091623232 -0.10490972 0.074494123, 0.037032932 -0.13427475 0.074492306, 0.034789979 -0.12006527 0.074493244, 0.035100639 -0.13479283 0.074492365, 0.047513276 0.13292557 0.07450749, -0.13741368 0.032326967 0.074501768, -0.13812743 0.029126555 0.074501529, 0.044413 0.13399336 0.074507356, -0.0042215288 -0.14110708 0.074491993, 0.11902413 -0.075905859 0.074495971, 0.1191048 -0.072212309 0.074496001, 0.12075496 -0.073121011 0.074496076, 0.088524759 -0.088255972 0.074495062, -0.13662574 0.035509914 0.074502006, 0.10143235 -0.095458359 0.074494749, 0.028003365 -0.1218271 0.074493185, -0.13395463 0.038155317 0.07450214, -0.13393633 0.038219422 0.074502096, -0.13391806 0.038283616 0.074502125, -0.13576405 0.038673669 0.07450214, -0.0073950887 -0.13909167 0.074492201, -0.0074977875 -0.14097071 0.074491978, 0.10279287 -0.093991607 0.07449463, 0.0933339 -0.083153278 0.074495405, 0.021128803 -0.12320569 0.074493185, 0.021766469 -0.13757682 0.074492365, 0.019788355 -0.13787526 0.07449232, 0.038677812 0.13575974 0.07450743, 0.035514176 0.13662151 0.074507594, 0.12375341 -0.067922592 0.074496239, 0.12529755 -0.065029919 0.074496418, 0.12210484 -0.067014694 0.07449615, 0.09784919 -0.077789336 0.074495479, 0.032331094 0.13740963 0.074507758, 0.11148188 -0.08350116 0.074495405, -0.13292983 0.047509193 0.074502796, -0.13399743 0.044408858 0.074502453, 0.014187485 -0.12419656 0.074493065, 0.029130891 0.13812342 0.074507624, -0.013379544 -0.13864407 0.074492127, -0.016742423 -0.14017385 0.074492261, -0.013482362 -0.14052492 0.074492037, -0.13179033 0.050583839 0.074502751, 0.10205677 -0.072180569 0.074495941, 0.11266963 -0.081891418 0.074495494, 0.0062263459 -0.1391488 0.074492201, 0.0072016567 -0.1247966 0.074492827, 0.0042272359 -0.1392239 0.074492276, -0.019993529 -0.13974723 0.074492186, 0.12644075 -0.058422804 0.074496686, -0.1305798 0.053631067 0.074502885, 0.12677409 -0.062102199 0.074496672, 0.12818226 -0.05914101 0.074496672, 0.02323398 0.13923666 0.074507669, 0.019993499 0.13973883 0.074507818, 0.10594325 -0.066344649 0.074496418, 0.1201297 -0.070494115 0.074496031, 0.00019299984 -0.12500405 0.074492902, -0.022921547 -0.13738915 0.074492246, -0.023233861 -0.13924503 0.074492216, 0.016742393 0.14016554 0.074507743, 0.13057978 -0.053639472 0.074496865, 0.13179031 -0.050592184 0.074497163, 0.12883991 -0.052921951 0.074496865, -0.12677409 0.062093884 0.074503422, -0.12818219 0.059132576 0.074503288, 0.12112978 -0.068761528 0.07449609, 0.10949633 -0.060300022 0.074496627, 0.013482288 0.14051667 0.074507788, -0.0093920529 -0.13897121 0.074492276, -0.0068160444 -0.12481824 0.074493036, -0.01138705 -0.13882178 0.074492186, -0.12529764 0.065021485 0.074503571, -0.028818235 -0.13627419 0.074492425, -0.032331258 -0.13741782 0.074492142, -0.029130936 -0.13813165 0.074492127, 0.13292976 -0.047517627 0.074497357, 0.13399747 -0.044417262 0.074497506, -0.035514176 -0.13662997 0.074492499, 0.11270471 -0.054065585 0.074497133, 0.12726673 -0.05660072 0.074496806, -0.1237535 0.067914188 0.074503824, -0.013803616 -0.12423977 0.074493095, -0.038159639 -0.13395888 0.074492618, -0.038677797 -0.13576815 0.074492455, 0.0074977428 0.14096257 0.074507922, 0.004221648 0.14109862 0.074507773, 0.11555871 -0.047661155 0.074497312, 0.12806655 -0.054766983 0.07449694, -0.020747751 -0.12327036 0.074493051, -0.02489233 -0.13704574 0.074492335, -0.026858121 -0.13667402 0.07449241, 0.1357639 -0.038681895 0.074497908, 0.13662572 -0.035518289 0.074497908, 0.0009431541 0.14115861 0.074507818, 0.11804904 -0.041106641 0.074497551, -0.11902414 0.075897545 0.074504405, -0.12075493 0.073112518 0.074504063, -0.027626678 -0.12191311 0.074493095, -0.0023357719 0.14114243 0.074507818, -0.043894425 -0.13219067 0.074492648, -0.047513366 -0.13293397 0.074492604, -0.044413105 -0.1340017 0.074492663, 0.13741377 -0.03233546 0.074498072, 0.13812761 -0.029135048 0.074498206, -0.050587982 -0.13179451 0.074492574, -0.040079519 -0.13339707 0.07449241, -0.034418806 -0.12017229 0.0744932, -0.041991383 -0.13280746 0.074492604, -0.11722925 0.078641504 0.074504435, -0.052917898 -0.12884399 0.074492753, -0.053635299 -0.13058421 0.074492648, 0.13924088 -0.023238093 0.074498564, 0.13974296 -0.019997716 0.074498788, -0.11537084 0.081343114 0.07450451, -0.041102499 -0.11805347 0.074493378, -0.0083326697 0.14091566 0.074507847, -0.011603564 0.14068413 0.074507803, -0.058418646 -0.12644497 0.074492946, -0.062098116 -0.12677836 0.074492887, -0.059136778 -0.12818637 0.074492946, 0.14016965 -0.0167467 0.074499056, 0.14052072 -0.013486505 0.07449922, -0.065025762 -0.12530187 0.074492872, -0.014868036 0.14037663 0.074507773, -0.054763079 -0.12807062 0.074492723, -0.047656953 -0.11556298 0.074493498, -0.056596503 -0.12727103 0.074492812, -0.10977753 0.088746786 0.074504986, -0.11180925 0.086173177 0.074504882, -0.067010552 -0.122109 0.074493214, -0.067918405 -0.12375766 0.07449314, -0.018124491 0.1399934 0.074507788, -0.054061368 -0.11270905 0.074493662, 0.14096667 -0.0075018406 0.074499533, 0.14110288 -0.0042257607 0.074499965, -0.10768664 0.091272682 0.074505076, -0.10553738 0.093749076 0.074505135, -0.072208308 -0.119109 0.074493311, -0.075901709 -0.11902845 0.074493401, -0.073116869 -0.12075916 0.074493267, -0.060295776 -0.10950041 0.074493691, -0.068757206 -0.1211341 0.074493237, -0.070490077 -0.120134 0.074493229, -0.024058282 0.13909674 0.074507818, -0.027282685 0.13850036 0.074507758, 0.14116281 -0.00094732642 0.074499905, 0.14114663 0.0023315847 0.074500173, -0.078645848 -0.11723346 0.07449346, -0.08026062 -0.11383846 0.074493684, -0.081347361 -0.11537513 0.07449346, -0.030492082 0.13782936 0.074507684, -0.066340297 -0.10594741 0.074494094, 0.1409198 0.0083284974 0.074500501, 0.14068832 0.011599243 0.074500695, -0.099150315 0.10047987 0.074505612, -0.10145758 0.098149866 0.074505478, -0.033685341 0.13708383 0.074507698, -0.096789762 0.10275578 0.074505672, -0.081887431 -0.11267385 0.074493758, -0.072176322 -0.10206094 0.074494138, -0.083496958 -0.11148629 0.074493669, -0.085089736 -0.11027548 0.074493811, -0.088750951 -0.10978165 0.074493818, -0.086177349 -0.1118134 0.074493729, 0.14038067 0.014863968 0.074500903, 0.1399976 0.018120438 0.074500933, -0.094376817 0.10497606 0.074505687, -0.091276579 -0.10769066 0.074493855, -0.077785067 -0.097853541 0.074494615, -0.039481312 0.13552839 0.074507609, -0.042618513 0.13457477 0.074507475, -0.092501283 -0.10413638 0.074494079, -0.093753353 -0.10554171 0.074494071, 0.13910073 0.02405417 0.074501306, 0.13850456 0.027278394 0.074501529, -0.083149157 -0.093338192 0.07449466, -0.093987413 -0.10279703 0.074494347, -0.095454179 -0.10143647 0.074494295, -0.045732856 0.1335485 0.074507415, -0.096901052 -0.10005513 0.074494407, -0.10048414 -0.099154532 0.074494503, -0.098154083 -0.10146159 0.074494168, 0.13783336 0.030487955 0.074501872, 0.13708802 0.033681124 0.074501872, -0.1027598 -0.09679395 0.074494421, -0.087276191 0.11094946 0.074506104, -0.089829698 0.10889238 0.074506149, -0.048822552 0.13245031 0.074507311, -0.084675699 0.11294654 0.074506372, -0.08825171 -0.08852905 0.074495092, -0.082029298 0.1148828 0.074506402, -0.10357868 -0.093124658 0.074494638, -0.057418793 0.12895676 0.074507236, -0.05440791 0.13025561 0.074507192, -0.10498035 -0.094380945 0.074494682, 0.13553251 0.039477229 0.074502125, 0.13457888 0.04261452 0.074502379, -0.060398519 0.12758842 0.074507073, -0.074304581 0.12002358 0.074506715, -0.077072352 0.11826545 0.074506611, -0.093076482 -0.083441526 0.074495308, -0.06334573 0.12615114 0.074507043, -0.10490543 -0.091627389 0.074494854, -0.10621074 -0.090111256 0.074495159, -0.07149674 0.12171701 0.074506924, -0.068650261 0.12334478 0.074506953, -0.10749386 -0.088576525 0.074495003, -0.11095362 -0.087280363 0.074495099, -0.10889666 -0.089833945 0.074494995, 0.13355277 0.045728743 0.074502617, 0.1324545 0.048818231 0.074502662, -0.097608365 -0.078091323 0.074495599, -0.11295081 -0.084679812 0.074495278, -0.11335371 -0.080941975 0.074495375, -0.11488701 -0.082033634 0.074495547, -0.10183317 -0.07249552 0.074495882, -0.11450447 -0.079305679 0.074495524, 0.13025981 0.054403752 0.074503034, 0.12896094 0.057414532 0.074503019, -0.11563166 -0.077652872 0.074495472, -0.10573775 -0.066671699 0.074496128, -0.11673507 -0.075984091 0.07449574, -0.12002789 -0.074308753 0.074495986, -0.11826961 -0.077076554 0.074495845, 0.12759238 0.060394436 0.074503362, 0.12615523 0.063341498 0.074503511, -0.12172128 -0.071500987 0.074495852, -0.12170313 -0.067741573 0.074496195, -0.12334912 -0.068654418 0.074496038, -0.10930938 -0.0606381 0.074496701, -0.12266345 -0.065986693 0.074496143, 0.123349 0.068646163 0.074503809, 0.12172113 0.071492523 0.074503943, -0.12359837 -0.064218014 0.074496418, -0.12759259 -0.060402632 0.074496664, -0.12615538 -0.063349843 0.074496366, 0.12002768 0.074300408 0.074504182, 0.1182695 0.07706818 0.074504346, -0.060398519 0.12759671 -0.074492916, -0.057418853 0.1289652 -0.074492827, 0.077648655 -0.11562756 -0.074506596, 0.072491422 -0.10182914 -0.07450591, 0.079301342 -0.1145004 -0.074506566, 0.066667557 -0.10573351 -0.07450591, -0.054407954 0.13026392 -0.074492827, 0.080937907 -0.11334953 -0.074506313, 0.084675595 -0.11294663 -0.074506491, 0.082029313 -0.11488277 -0.074506462, 0.078087196 -0.097604424 -0.074505404, -0.12334898 -0.068646222 -0.074503794, -0.12170318 -0.067733228 -0.074503794, -0.12172131 -0.071492672 -0.074503943, -0.048822448 0.13245857 -0.074492544, -0.045732915 0.13355675 -0.074492544, -0.12759255 -0.060394347 -0.074503466, -0.12450811 -0.062427878 -0.074503452, -0.12615538 -0.063341647 -0.074503496, -0.12896097 -0.057414621 -0.074503228, 0.088572294 -0.10748976 -0.074506089, 0.087276116 -0.11094937 -0.074506313, 0.089829683 -0.10889241 -0.074506253, -0.1200279 -0.074300408 -0.074504197, -0.11673513 -0.075975716 -0.074504301, -0.11826973 -0.07706815 -0.074504539, 0.090107054 -0.10620654 -0.074506134, 0.083437175 -0.093072355 -0.074505433, -0.042618692 0.134583 -0.074492663, -0.13025977 -0.054403871 -0.074503154, -0.12852211 -0.053680897 -0.074503109, 0.091623232 -0.10490134 -0.07450591, -0.11488706 -0.08202517 -0.074504703, -0.1133537 -0.08093372 -0.074504599, -0.11295067 -0.084671617 -0.074504897, 0.093120471 -0.10357466 -0.074506029, -0.039481416 0.13553661 -0.074492455, 0.088524804 -0.088247627 -0.074505076, -0.13355276 -0.045728832 -0.074502707, -0.13071547 -0.048094898 -0.074502707, -0.13245459 -0.04881826 -0.074502796, -0.1345789 -0.04261449 -0.074502438, -0.10749388 -0.08856824 -0.074504867, 0.096789613 -0.10275578 -0.074505836, 0.094376773 -0.10497606 -0.074506134, -0.11095361 -0.087272078 -0.074504942, -0.10889651 -0.08982566 -0.074505076, -0.033685356 0.1370922 -0.074492455, -0.030492142 0.13783759 -0.074492395, 0.10005087 -0.096896917 -0.074505478, 0.099150375 -0.10048005 -0.074505836, 0.10145743 -0.098149955 -0.074505463, -0.13372476 -0.038953364 -0.074502349, -0.13553244 -0.039477229 -0.074502349, 0.093333781 -0.083145022 -0.074504793, 0.10143223 -0.095449865 -0.074505448, -0.10498019 -0.09437266 -0.074505359, -0.10357885 -0.093116373 -0.07450515, -0.1027599 -0.096785516 -0.074505463, -0.027282566 0.13850874 -0.07449241, 0.10279284 -0.093983293 -0.074505299, 0.10413213 -0.09249723 -0.074505284, -0.024058387 0.13910493 -0.074492171, -0.13783361 -0.030488074 -0.074501753, -0.13527872 -0.033156842 -0.074502066, -0.13708808 -0.033681154 -0.074502081, -0.13850443 -0.027278423 -0.074501708, -0.096900985 -0.10004675 -0.074505866, 0.097849265 -0.077780992 -0.074504465, -0.10048409 -0.099146158 -0.074505821, -0.098154038 -0.10145339 -0.074505851, 0.10768647 -0.091272622 -0.074505091, 0.10553743 -0.093749076 -0.074505299, -0.13910072 -0.024054199 -0.074501291, -0.13724582 -0.023736089 -0.074501529, -0.093753383 -0.10553333 -0.07450594, -0.092501163 -0.10412812 -0.074505925, -0.091276824 -0.10768238 -0.074506089, -0.018124625 0.1400018 -0.074492112, -0.014868051 0.14038494 -0.074492201, 0.11027133 -0.085085571 -0.074504897, 0.1097775 -0.088746846 -0.074505135, 0.11180925 -0.086173177 -0.074504852, -0.14038098 -0.014863819 -0.074501023, -0.13814104 -0.01780194 -0.074501202, -0.13999759 -0.018120527 -0.074501157, 0.10205686 -0.072172225 -0.074504286, 0.11148199 -0.083493024 -0.074504837, -0.1406884 -0.011599213 -0.074500665, -0.011603609 0.14069241 -0.074492112, -0.085089669 -0.11026713 -0.074506268, 0.11266977 -0.081883222 -0.074504703, -0.088750929 -0.1097734 -0.074506253, -0.086177394 -0.11180511 -0.074506417, 0.10594316 -0.066336274 -0.074503824, 0.11383432 -0.080256552 -0.074504554, -0.14091976 -0.008328557 -0.07450068, -0.1390408 -0.0082202256 -0.074500665, -0.008332625 0.14092392 -0.07449241, -0.081347346 -0.11536676 -0.074506596, -0.080260545 -0.11383015 -0.074506536, -0.078645766 -0.11722511 -0.074506566, -0.12266348 -0.065978259 -0.074504003, -0.10930943 -0.060629785 -0.074503511, -0.12359846 -0.064209729 -0.07450366, 0.11722901 -0.078641534 -0.07450445, 0.1153708 -0.081343144 -0.074504539, -0.10573769 -0.066663355 -0.074503884, -0.11563165 -0.077644616 -0.07450442, 0.11910486 -0.072203934 -0.074504122, 0.11902419 -0.075897545 -0.074504316, -0.0023357868 0.14115095 -0.074492142, 0.000943169 0.14116693 -0.074492216, 0.120755 -0.073112696 -0.074504256, 0.12012967 -0.07048583 -0.074503943, -0.11253721 -0.054405361 -0.074503228, 0.10949631 -0.060291678 -0.074503496, 0.0042216331 0.14110687 -0.07449235, -0.10183318 -0.072487235 -0.074504063, -0.11450449 -0.079297364 -0.074504539, 0.12112978 -0.068753272 -0.074503869, 0.12210485 -0.067006379 -0.074503854, 0.11270478 -0.054057211 -0.074503064, 0.0074977875 0.14097089 -0.074492261, -0.12927988 -0.051829457 -0.074503109, -0.11541088 -0.048009843 -0.07450287, -0.13001093 -0.049967319 -0.07450299, -0.097608432 -0.078083009 -0.074504614, 0.12529762 -0.065021634 -0.074503586, 0.12375349 -0.067914188 -0.074503854, -0.10621069 -0.090102971 -0.074505106, -0.11792156 -0.041463077 -0.074502513, 0.12644073 -0.058414459 -0.074503392, 0.12677404 -0.062093824 -0.074503452, 0.013482273 0.14052486 -0.07449238, 0.016742408 0.1401737 -0.074492246, -0.14116286 0.00094714761 -0.074500084, -0.13926628 -0.0022230744 -0.074500203, -0.14114663 -0.0023317039 -0.074500129, -0.093076572 -0.083433121 -0.074504793, 0.1281822 -0.059132576 -0.074503437, -0.10490553 -0.091619134 -0.074505299, -0.12006107 -0.034785956 -0.0745022, 0.11555874 -0.047652751 -0.074502751, 0.12726676 -0.056592435 -0.074503303, -0.1342704 -0.037028879 -0.0745022, -0.13478865 -0.035096407 -0.074501976, 0.019993529 0.13974717 -0.074492365, 0.1280665 -0.054758757 -0.074503124, -0.14110279 0.0042257309 -0.074500054, -0.072208196 -0.11910078 -0.07450673, 0.11804913 -0.041098356 -0.074502409, 0.12883991 -0.052913636 -0.074503064, -0.075901717 -0.1190201 -0.07450676, -0.073116854 -0.12075093 -0.074506804, -0.088251695 -0.088520765 -0.074505061, 0.023233861 0.139245 -0.074492201, -0.095454037 -0.10142815 -0.074505672, -0.121823 -0.027999282 -0.074501634, 0.13179027 -0.05058381 -0.074502856, 0.13057983 -0.053631216 -0.074503019, -0.1390875 0.0073991418 -0.074499652, -0.1409667 0.007501781 -0.074499637, -0.083149269 -0.093329847 -0.074505404, -0.09398748 -0.10278872 -0.07450588, -0.12320139 -0.021124542 -0.07450138, -0.13757265 -0.021762311 -0.074501336, 0.13292976 -0.047509164 -0.074502721, -0.13787104 -0.019784153 -0.074501261, 0.029130787 0.13813177 -0.07449238, 0.032331213 0.13741791 -0.074492201, 0.1339974 -0.044408977 -0.074502707, -0.067010447 -0.12210074 -0.074506953, -0.065025896 -0.12529355 -0.074507102, -0.06791845 -0.12374941 -0.074506968, 0.035514086 0.13662973 -0.074492514, -0.077785209 -0.097845167 -0.074505478, -0.083497092 -0.11147791 -0.074506342, -0.1241924 -0.014183342 -0.074501023, 0.038677886 0.13576806 -0.074492455, -0.14052083 0.013486505 -0.074499413, -0.14016958 0.016746551 -0.074499115, -0.13863981 0.013383746 -0.074499398, -0.072176248 -0.10205278 -0.074505866, -0.08188723 -0.11266568 -0.074506477, -0.13914464 -0.0062222183 -0.074500293, -0.12479253 -0.0071974397 -0.074500397, -0.13921976 -0.0042231381 -0.074500263, 0.13662572 -0.035509914 -0.074502081, 0.13576394 -0.038673609 -0.07450217, -0.139743 0.019997656 -0.074498951, -0.058418646 -0.12643656 -0.074507177, -0.062098056 -0.12677002 -0.074507177, -0.059136882 -0.12817809 -0.074507236, 0.13741362 -0.032327026 -0.074501917, -0.066340342 -0.10593909 -0.074506015, 0.04441306 0.13400152 -0.074492738, 0.047513321 0.13293391 -0.074492574, -0.070489943 -0.12012574 -0.074506983, -0.12499984 -0.00018900633 -0.074500069, 0.13812767 -0.029126763 -0.074501589, -0.13924101 0.023238152 -0.074499011, -0.13738492 0.022925615 -0.074498996, 0.050587997 0.13179445 -0.074492767, -0.052917883 -0.12883574 -0.074507266, -0.050587997 -0.13178617 -0.074507415, -0.053635418 -0.13057575 -0.074507385, -0.06029579 -0.10949212 -0.074506372, -0.068757385 -0.12112564 -0.074506834, 0.053635374 0.13058394 -0.074492827, -0.13896687 0.0093961358 -0.074499428, -0.124814 0.0068200231 -0.07449986, -0.13881774 0.011391133 -0.074499324, -0.13812761 0.029135019 -0.074498519, -0.13741378 0.03233543 -0.074498296, -0.13627003 0.028822273 -0.074498504, -0.047513425 -0.13292566 -0.07450752, -0.04389438 -0.13218245 -0.074507535, -0.04441309 -0.13399345 -0.074507549, 0.1397429 -0.019989431 -0.074501306, 0.13924085 -0.023229688 -0.07450138, -0.1366258 0.035518169 -0.074498028, -0.054061398 -0.11270067 -0.074506596, -0.056596488 -0.12726253 -0.074507222, -0.12423553 0.013807744 -0.074499324, 0.14016971 -0.016738355 -0.074501082, 0.059136763 0.12818632 -0.074492887, 0.062098101 0.12677816 -0.074493051, -0.13395463 0.038163602 -0.074498102, -0.13576396 0.038681924 -0.074497923, 0.14052066 -0.01347816 -0.074501038, -0.047656983 -0.11555454 -0.074506596, 0.065025643 0.12530178 -0.07449317, -0.05476284 -0.12806234 -0.074507117, -0.1232661 0.020752072 -0.074498922, -0.13704154 0.024896532 -0.074498788, -0.13666987 0.026862144 -0.074498549, -0.038159594 -0.13395047 -0.074507535, -0.035514101 -0.13662162 -0.074507862, -0.038677856 -0.13575998 -0.074507877, 0.06791839 0.12375769 -0.07449314, -0.041102573 -0.118045 -0.074506864, -0.041991353 -0.13279918 -0.074507385, -0.12190893 0.027630925 -0.074498519, -0.13399743 0.044417262 -0.074497536, -0.13292976 0.047517508 -0.074497461, -0.02881822 -0.13626584 -0.074507713, -0.032331228 -0.13740954 -0.074507892, -0.029130936 -0.13812339 -0.074507996, 0.14110282 -0.0042173564 -0.074500322, 0.14096671 -0.0074935853 -0.074500546, -0.13179037 0.050592184 -0.074497223, -0.040079698 -0.13338861 -0.07450749, -0.034418955 -0.12016383 -0.074506834, -0.1339363 0.038227707 -0.074497923, -0.13391808 0.038291901 -0.074498072, 0.14116287 -0.00093898177 -0.074500233, -0.13057978 0.053639442 -0.074497074, -0.022921428 -0.13738072 -0.074507892, -0.019993559 -0.13973883 -0.074507922, -0.023233861 -0.13923681 -0.074508026, 0.073116779 0.12075907 -0.074493334, 0.075901762 0.1190283 -0.074493557, -0.027626708 -0.12190473 -0.074507073, 0.14114669 0.0023398995 -0.074500084, -0.026858076 -0.13666576 -0.074507833, -0.12818217 0.05914101 -0.074496835, -0.1267741 0.062102169 -0.074496463, -0.016742438 -0.14016557 -0.074507877, -0.013379544 -0.13863569 -0.074507937, -0.013482377 -0.14051655 -0.074507892, -0.12529765 0.0650298 -0.074496388, -0.020747826 -0.12326202 -0.074507058, -0.02489236 -0.13703734 -0.074507743, 0.078645855 0.11723334 -0.074493617, 0.081347391 0.11537495 -0.074493662, -0.12375352 0.067922592 -0.074496388, -0.013803616 -0.12423143 -0.074507147, -0.011387035 -0.13881353 -0.074507833, 0.14068824 0.011607587 -0.074499413, 0.14091983 0.0083367825 -0.074499607, -0.0073951185 -0.13908336 -0.074508011, -0.0042216331 -0.14109871 -0.074507937, -0.0074978024 -0.14096257 -0.074507937, 0.14038081 0.014872253 -0.074499264, 0.086177319 0.11181334 -0.074493736, 0.088750958 0.10978165 -0.074494138, -0.12075491 0.073120862 -0.074496105, -0.1190242 0.075905919 -0.074495971, -0.0093920678 -0.13896275 -0.074507907, -0.0068159699 -0.12481001 -0.074507147, 0.0022272617 -0.13926196 -0.074507907, -0.00094312429 -0.1411587 -0.074507982, 0.0023358166 -0.14114264 -0.074508011, 0.13999763 0.018128693 -0.0744991, -0.11722922 0.078649819 -0.074495837, -0.11537094 0.081351459 -0.074495494, 0.00019316375 -0.1249958 -0.074507192, 0.0042271912 -0.13921565 -0.074507847, 0.091276765 0.10769069 -0.074494138, 0.093753353 0.10554147 -0.074494198, 0.0082242787 -0.1390368 -0.074507907, 0.011603549 -0.14068422 -0.074508011, 0.0083326399 -0.14091569 -0.074507877, 0.0062263459 -0.13914046 -0.074507907, 0.0072016418 -0.12478831 -0.074507073, 0.13850445 0.027286768 -0.074498534, 0.13910091 0.024062425 -0.074498788, -0.11180928 0.086181492 -0.074495211, -0.10977754 0.088755101 -0.074495062, 0.014867991 -0.14037681 -0.074507967, 0.017806083 -0.13813689 -0.074507847, 0.01812461 -0.13999361 -0.074507877, 0.13783342 0.03049624 -0.074498355, -0.10768659 0.091280848 -0.074494928, 0.014187455 -0.12418813 -0.074507192, 0.019788384 -0.13786691 -0.074507847, 0.098154038 0.10146156 -0.074494362, 0.10048403 0.099154472 -0.074494466, -0.10553734 0.093757391 -0.074494839, 0.13708799 0.033689469 -0.074498177, 0.023740143 -0.13724172 -0.074507907, 0.027282596 -0.13850036 -0.074507862, 0.024058282 -0.13909671 -0.074507996, 0.10275984 0.096793741 -0.074494496, 0.021766469 -0.13756838 -0.074507877, 0.021128684 -0.12319735 -0.074507073, 0.10498023 0.094380915 -0.074494854, -0.10145745 0.098158121 -0.074494526, -0.09915027 0.10048819 -0.074494541, 0.033161059 -0.13527471 -0.074507952, 0.030492067 -0.1378293 -0.074507847, 0.033685163 -0.13708389 -0.074507698, 0.13457888 0.042622775 -0.074497849, 0.13553242 0.039485604 -0.074497849, -0.096789673 0.10276398 -0.074494153, 0.028003484 -0.12181887 -0.074507073, 0.035100669 -0.1347844 -0.074507684, -0.094376802 0.10498425 -0.074494153, 0.1335527 0.045737058 -0.074497551, 0.038957581 -0.13372058 -0.074507684, 0.042618588 -0.13457483 -0.074507684, 0.039481357 -0.13552842 -0.074507862, 0.037032887 -0.13426641 -0.074507669, 0.034789935 -0.12005687 -0.074506909, 0.10889643 0.089833915 -0.074495137, 0.11095358 0.087280393 -0.074495181, 0.13245453 0.048826635 -0.074497327, -0.089829668 0.10890076 -0.074494168, -0.08727625 0.11095771 -0.074493885, 0.11295074 0.084679872 -0.07449539, 0.048098832 -0.13071111 -0.074507326, 0.045732856 -0.13354859 -0.07450752, 0.048822567 -0.1324504 -0.074507535, 0.11488698 0.082033604 -0.074495524, 0.041467041 -0.11791742 -0.074506685, 0.12896095 0.057422817 -0.07449685, 0.13025971 0.054412127 -0.074497133, 0.049971342 -0.13000694 -0.074507281, -0.08467567 0.11295488 -0.074493691, 0.12759241 0.060402662 -0.074496716, -0.082029253 0.11489105 -0.074493662, 0.11826953 0.077076465 -0.074495852, 0.12002766 0.074308693 -0.074496165, 0.12615529 0.063349754 -0.074496612, 0.12172119 0.071500868 -0.074496165, 0.051833615 -0.1292758 -0.074507296, 0.048013881 -0.11540684 -0.074506551, 0.053685009 -0.12851793 -0.074507326, 0.123349 0.068654358 -0.07449618, 0.05741863 -0.12895685 -0.074507251, 0.054407865 -0.13025564 -0.074507385, 0.054409504 -0.11253306 -0.074506268, -0.077072397 0.11827379 -0.074493393, -0.074304551 0.12003189 -0.074493363, 0.060398445 -0.12758842 -0.074507222, 0.062431917 -0.12450391 -0.074507102, 0.063345701 -0.12615117 -0.074507207, 0.064213887 -0.12359437 -0.074506924, -0.07149674 0.12172535 -0.074493363, -0.068650305 0.12335312 -0.07449317, 0.060633868 -0.10930532 -0.074506283, 0.065982446 -0.12265933 -0.074506998, 0.067737311 -0.12169898 -0.074506909, 0.0714968 -0.12171713 -0.074506938, 0.068650305 -0.12334496 -0.074506894, -0.063345596 0.12615937 -0.074493051, 0.075979874 -0.11673093 -0.074506566, 0.074304506 -0.12002361 -0.074506924, 0.077072278 -0.11826542 -0.074506775, 0.02721104 -0.13986295 0.074316084, 0.027115881 -0.14112666 0.073800012, 0.028269649 -0.14084876 0.073829547, 0.027782455 -0.13972205 0.074323699, 0.029964417 -0.14144737 0.073142946, 0.030786812 -0.14104855 0.073334336, 0.029903546 -0.14051101 0.073829293, 0.029126808 -0.14140078 0.073334515, 0.029550597 -0.14164066 0.073042735, 0.028727695 -0.14180991 0.073042855, 0.028146416 -0.14194748 0.073022082, 0.026981786 -0.14221507 0.072980508, 0.032474339 -0.13850728 0.074371338, 0.034039304 -0.13813776 0.074369773, 0.034465432 -0.13909733 0.074014023, 0.034002379 -0.14038223 0.073273346, 0.034941077 -0.13992864 0.073450506, 0.035393223 -0.14054012 0.07279022, 0.032534018 -0.13980588 0.073894158, 0.033530504 -0.1406031 0.073180497, 0.031562969 -0.14014763 0.073829368, 0.029030964 -0.13989067 0.074193954, 0.026066288 -0.14013773 0.074300408, 0.025531739 -0.1403431 0.074268937, 0.024458289 -0.14074576 0.074199557, 0.024800435 -0.14165282 0.07374008, 0.024232641 -0.13994598 0.07441783, 0.026400954 -0.14231166 0.07299298, 0.025238395 -0.14249772 0.073017851, 0.031515494 -0.13886157 0.074340418, 0.031034812 -0.13903573 0.074323669, 0.030212119 -0.13921684 0.074323684, 0.030663535 -0.13954198 0.074193791, 0.029819727 -0.13944378 0.074284613, 0.028198227 -0.13978058 0.074284479, 0.042699262 -0.13593709 0.074316218, 0.043251097 -0.13573271 0.074323669, 0.043861508 -0.13679808 0.073829487, 0.04561244 -0.13720304 0.073143184, 0.046385214 -0.13671476 0.073334739, 0.045447215 -0.13627943 0.073829591, 0.044775128 -0.13725042 0.073334783, 0.045223102 -0.13744146 0.073042914, 0.04442434 -0.13770181 0.073042914, 0.043862045 -0.13790363 0.073022231, 0.042746171 -0.1372034 0.073800355, 0.042734668 -0.13829979 0.072980672, 0.047777563 -0.13400054 0.074371487, 0.049291357 -0.13345811 0.074370027, 0.049822226 -0.13436395 0.074014381, 0.049505875 -0.13569254 0.073273703, 0.0503878 -0.13513657 0.073450699, 0.050905541 -0.13569361 0.072790354, 0.04798238 -0.13528422 0.073894367, 0.049061716 -0.13596478 0.073180705, 0.047055572 -0.13573241 0.073829606, 0.044510886 -0.13576069 0.074194148, 0.041592404 -0.13633814 0.074300751, 0.041084126 -0.1366021 0.074269384, 0.040062681 -0.13712233 0.074199677, 0.040504128 -0.13798544 0.073740155, 0.039748758 -0.13635272 0.074418202, 0.042168438 -0.13846084 0.072993249, 0.041033939 -0.13877589 0.073017955, 0.04686448 -0.13445982 0.074340537, 0.046406224 -0.13468677 0.074323788, 0.045609176 -0.13495877 0.074323654, 0.046094 -0.13523132 0.074193984, 0.04524456 -0.13522831 0.074284792, 0.043671116 -0.1357446 0.074284643, -0.0045925379 -0.14241156 0.074315906, -0.0049666166 -0.14362231 0.073799714, -0.0037800968 -0.14360818 0.073829025, -0.0040043443 -0.14240116 0.07432349, -0.0022610575 -0.14456871 0.073142752, -0.0013702959 -0.14436299 0.073334292, -0.0021119565 -0.1436424 0.073829174, -0.0030671805 -0.144337 0.073334381, -0.0027073771 -0.1446653 0.073042527, -0.0035474151 -0.14464703 0.073042378, -0.0041447133 -0.14465174 0.073021963, -0.0053396523 -0.14465338 0.072980389, 0.00084029138 -0.14226103 0.07437101, 0.0024482459 -0.14224893 0.074369356, 0.0026501864 -0.14327934 0.07401377, 0.0019129217 -0.14442891 0.073272899, 0.0029287487 -0.14419538 0.073450267, 0.0032336265 -0.14489231 0.072789744, 0.0006096065 -0.14354023 0.073893905, 0.0014036447 -0.14453924 0.07318002, -0.00041329861 -0.14365724 0.073829234, -0.0028244853 -0.14284346 0.074193731, -0.0057697594 -0.14242473 0.074300274, -0.0063367188 -0.14250591 0.074268997, -0.0074727535 -0.14265963 0.074199483, -0.0073411763 -0.14362028 0.073739797, -0.0075149387 -0.14182949 0.074417889, -0.0059273243 -0.14461848 0.07299298, -0.0071020275 -0.14454126 0.073017523, -0.0001732558 -0.1423929 0.074340165, -0.00068078935 -0.14245573 0.074323446, -0.0015231073 -0.14244932 0.074323565, -0.0011554211 -0.14286667 0.074193835, -0.0019561052 -0.14258319 0.074284315, -0.0036118031 -0.14255092 0.074284121, 0.011380807 -0.14203036 0.074315861, 0.011964276 -0.14195409 0.074323401, 0.012322277 -0.1431284 0.073829159, 0.013939217 -0.143913 0.073142767, 0.014801413 -0.14360887 0.073334321, 0.013983622 -0.14297569 0.0738291, 0.013112217 -0.14377269 0.073334366, 0.013506487 -0.14405876 0.073042616, 0.012669846 -0.14413473 0.073042527, 0.01207678 -0.14420632 0.073021889, 0.011144802 -0.14327529 0.073799804, 0.01088956 -0.1443418 0.072980329, 0.016762689 -0.14127237 0.074371219, 0.018359229 -0.14108038 0.074369356, 0.018675253 -0.14208177 0.074013874, 0.018071324 -0.14330664 0.073273227, 0.019054636 -0.14296079 0.073450342, 0.01943551 -0.14361915 0.072789952, 0.01667659 -0.14256936 0.073894039, 0.017577559 -0.14347312 0.073180348, 0.015673295 -0.14280024 0.073829263, 0.013186127 -0.14226159 0.074193701, 0.010212362 -0.14217514 0.074300274, 0.0096582323 -0.14231941 0.074268967, 0.0085465312 -0.14259923 0.074199408, 0.0087849051 -0.14353901 0.073739767, 0.0084116757 -0.14177907 0.074417874, 0.01030159 -0.14437276 0.072992891, 0.0091254711 -0.14442751 0.073017806, 0.015770197 -0.14151701 0.074340373, 0.01527302 -0.14163631 0.074323535, 0.014435306 -0.1417242 0.07432355, 0.014847428 -0.14209771 0.074193746, 0.014019981 -0.14190578 0.074284166, 0.012371063 -0.14205906 0.074284181, 0.085198775 -0.11420617 0.074317545, 0.085661307 -0.11538586 0.073801368, 0.086580262 -0.11463502 0.073830888, 0.085652411 -0.11383122 0.074324995, 0.088366687 -0.11443907 0.07314463, 0.088934973 -0.11372283 0.073335886, 0.087905616 -0.11362177 0.073830768, 0.087592021 -0.11476046 0.07333602, 0.088078037 -0.11479264 0.073044136, 0.087409973 -0.11530235 0.07304433, 0.086945966 -0.11567834 0.073023498, 0.086012706 -0.11642483 0.072982058, 0.089352652 -0.11070117 0.074372828, 0.090602234 -0.10968915 0.074371368, 0.091402531 -0.11036882 0.0740159, 0.091542944 -0.11172733 0.07327491, 0.092191666 -0.11091134 0.073452145, 0.092864409 -0.11126614 0.07279174, 0.089969829 -0.11184508 0.073895693, 0.091213629 -0.11213106 0.073181957, 0.089243129 -0.1125744 0.073830843, 0.086850539 -0.11344144 0.074195325, 0.08428663 -0.11495045 0.074301869, 0.083893999 -0.11536753 0.074270651, 0.083101705 -0.11619583 0.074200764, 0.083803609 -0.11686462 0.073741332, 0.082551301 -0.11557323 0.074419275, 0.085531428 -0.1167638 0.07299459, 0.084564641 -0.11743578 0.073019043, 0.088642344 -0.11143622 0.074341968, 0.08828494 -0.11180186 0.074325234, 0.08762233 -0.11232185 0.074324965, 0.088169992 -0.11241892 0.074195445, 0.087367207 -0.11269653 0.074285954, 0.086052448 -0.11370352 0.07428585, 0.097449586 -0.10394886 0.074318036, 0.09662661 -0.1047906 0.07430245, 0.098041326 -0.10506934 0.073802114, 0.098870471 -0.10422042 0.073831305, 0.097858459 -0.10352546 0.074325651, 0.10062382 -0.10382551 0.073145077, 0.10110809 -0.10305026 0.073336586, 0.10007405 -0.10306498 0.073831528, 0.099889934 -0.10423172 0.073336571, 0.10037653 -0.10420939 0.073044851, 0.099769667 -0.10479054 0.073044911, 0.099350631 -0.10521623 0.073024273, 0.098506778 -0.10606235 0.072982684, 0.10118501 -0.1000008 0.074373305, 0.10231327 -0.098855227 0.074371815, 0.10318482 -0.099441051 0.074016243, 0.10347638 -0.1007753 0.07327567, 0.10402963 -0.099891901 0.073452801, 0.10473788 -0.10016894 0.072792307, 0.10192631 -0.10106841 0.073896319, 0.10319424 -0.10121325 0.073182866, 0.10128586 -0.10187447 0.073831514, 0.099005342 -0.10300401 0.074195862, 0.096283287 -0.10524896 0.074271008, 0.095588461 -0.10616079 0.074201599, 0.096360803 -0.10674688 0.073741689, 0.09497194 -0.10560372 0.074419856, 0.098066568 -0.10645318 0.07299526, 0.097181126 -0.1072292 0.073019803, 0.10056143 -0.10081071 0.074342668, 0.10024704 -0.10121399 0.074325874, 0.099646866 -0.101805 0.074325621, 0.10020201 -0.10184008 0.074196041, 0.099435493 -0.10220587 0.074286416, 0.098241791 -0.10335386 0.074286506, 0.057650343 -0.13030139 0.074316829, 0.058901787 -0.13102695 0.073829859, 0.05817613 -0.13003692 0.074324131, 0.06068702 -0.13123339 0.073143601, 0.061400414 -0.13066155 0.073335066, 0.060419455 -0.13033399 0.073829845, 0.059860259 -0.13137424 0.073334977, 0.06032677 -0.13151389 0.073043227, 0.059562162 -0.13186198 0.073043287, 0.059026033 -0.13212544 0.073022395, 0.057838827 -0.13155442 0.073800489, 0.057950139 -0.13264546 0.07298106, 0.062480032 -0.12780854 0.07437171, 0.063923463 -0.12709996 0.07437031, 0.064552546 -0.12794086 0.074014634, 0.064386979 -0.12929639 0.073273927, 0.065201133 -0.1286453 0.073451161, 0.065777943 -0.12914085 0.072790593, 0.062827155 -0.1290611 0.07389465, 0.063976079 -0.12961671 0.073181063, 0.061956316 -0.12961036 0.0738298, 0.059430927 -0.12992346 0.074194357, 0.056595519 -0.13082406 0.074300945, 0.056120008 -0.13114336 0.074269548, 0.055163234 -0.1317746 0.074200138, 0.055698663 -0.1325829 0.073740363, 0.054764986 -0.13104495 0.074418426, 0.057405442 -0.13286886 0.072993562, 0.056313425 -0.13330898 0.073018268, 0.06162402 -0.12836713 0.074340999, 0.061194077 -0.12864399 0.07432425, 0.060432345 -0.12900358 0.074324176, 0.060944766 -0.12922019 0.074194446, 0.060100421 -0.12931219 0.074284986, 0.058594555 -0.13000154 0.074284852, 0.071876481 -0.12302732 0.074317157, 0.070886821 -0.12366471 0.074301288, 0.072204143 -0.12425148 0.073800936, 0.072369128 -0.12270546 0.074324548, 0.073201388 -0.12360826 0.073830202, 0.074998423 -0.12361342 0.073143944, 0.075643316 -0.12296546 0.073335379, 0.074631959 -0.12274981 0.073830396, 0.074192673 -0.12384617 0.073335409, 0.074672028 -0.12393266 0.073043719, 0.073951185 -0.12436411 0.073043495, 0.073447779 -0.12468603 0.073022991, 0.072436869 -0.125323 0.072981477, 0.076396689 -0.12000933 0.074372292, 0.077751771 -0.11914387 0.074370787, 0.078470886 -0.11990866 0.074015126, 0.078458279 -0.12127438 0.0732743, 0.079194307 -0.12053615 0.073451579, 0.079823181 -0.12096405 0.07279098, 0.07688193 -0.12121534 0.073895022, 0.078085765 -0.12163863 0.073181435, 0.076078117 -0.12185863 0.073830202, 0.073603615 -0.12245253 0.074194878, 0.070450008 -0.12403524 0.074270025, 0.069569841 -0.12476978 0.074200451, 0.070192322 -0.12551296 0.073740825, 0.069092587 -0.12408933 0.074418917, 0.071920663 -0.12560612 0.072993934, 0.070884764 -0.12616575 0.073018715, 0.075608581 -0.12066039 0.07434155, 0.075212389 -0.12098363 0.074324861, 0.074495837 -0.12142622 0.074324533, 0.075029269 -0.121584 0.074194908, 0.074200392 -0.12176996 0.074285433, 0.07278128 -0.12262359 0.074285343, -0.020508289 -0.14100191 0.074315965, -0.021679595 -0.14088318 0.074300408, -0.021015406 -0.14216316 0.073799953, -0.019834802 -0.14228192 0.073829144, -0.019922361 -0.14105749 0.074323505, -0.01843293 -0.1434066 0.073142841, -0.017524824 -0.14330187 0.073334351, -0.018181115 -0.14250273 0.0738291, -0.019208074 -0.14308599 0.073334381, -0.018887132 -0.14345261 0.073042557, -0.019719958 -0.14334041 0.073042646, -0.020314068 -0.14327818 0.073022142, -0.021501616 -0.14314619 0.072980568, -0.015092671 -0.14146066 0.07437107, -0.013493553 -0.14162874 0.074369609, -0.01340811 -0.14267534 0.074013859, -0.01426959 -0.14373493 0.073273063, -0.01323387 -0.14361677 0.073450327, -0.013008997 -0.14434329 0.072789699, -0.015465111 -0.14270601 0.0738938, -0.014788002 -0.14378756 0.073180273, -0.016494781 -0.14270774 0.073829234, -0.018799707 -0.14162913 0.07419388, -0.022252187 -0.14090046 0.074269146, -0.023398027 -0.14092594 0.074199513, -0.023374841 -0.14189529 0.073739931, -0.023347229 -0.14009634 0.074418098, -0.022081658 -0.14304557 0.07299298, -0.023240507 -0.14283714 0.073017851, -0.016114622 -0.14147818 0.074340388, -0.016625986 -0.14148396 0.074323416, -0.017462268 -0.14138305 0.07432355, -0.017143607 -0.14183909 0.074193612, -0.017907575 -0.14146766 0.0742843, -0.019549221 -0.14125019 0.074284032, -0.036166176 -0.13781911 0.074316248, -0.03731674 -0.13756993 0.074300796, -0.036800057 -0.13891625 0.073800147, -0.035640106 -0.13916668 0.073829353, -0.035590082 -0.13793999 0.074323669, -0.034373075 -0.14044112 0.07314305, -0.033458889 -0.14043874 0.073334441, -0.034021467 -0.13957113 0.073829249, -0.035107255 -0.14003572 0.073334381, -0.034829676 -0.14043584 0.073042691, -0.035644501 -0.14023116 0.073042884, -0.036227882 -0.14010292 0.073022142, -0.037393287 -0.13983873 0.072980776, -0.030835956 -0.13888127 0.074371219, -0.029265568 -0.13922736 0.074369669, -0.029297993 -0.14027703 0.074013844, -0.030272663 -0.1412335 0.073273391, -0.029230192 -0.14123207 0.073450431, -0.02908805 -0.14197922 0.072789922, -0.031345472 -0.14007711 0.073894247, -0.030793652 -0.14122775 0.073180497, -0.032368883 -0.13996369 0.073829427, -0.034538403 -0.13863379 0.074194118, -0.037887529 -0.13752311 0.074269176, -0.03902933 -0.13742003 0.074199811, -0.03911458 -0.13838595 0.073740155, -0.038885653 -0.13660145 0.074418098, -0.037958518 -0.13967374 0.072993204, -0.039086565 -0.13933694 0.073017865, -0.031853467 -0.13878423 0.074340403, -0.032362148 -0.13873264 0.074323699, -0.033181861 -0.13853893 0.074323729, -0.032916233 -0.13902777 0.07419391, -0.033633932 -0.13857311 0.074284241, -0.035240889 -0.13817325 0.074284375, -0.051368997 -0.13290313 0.074316546, -0.050810322 -0.13308772 0.074323982, -0.050997183 -0.13430119 0.073829681, -0.049880803 -0.13570955 0.073143333, -0.048972189 -0.13580957 0.073334828, -0.049434036 -0.13488445 0.073829621, -0.050565094 -0.13522455 0.073334828, -0.050333887 -0.13565332 0.073043123, -0.051120713 -0.1353586 0.073043168, -0.051686227 -0.13516584 0.07302241, -0.052121937 -0.13392252 0.073800325, -0.052814648 -0.13477254 0.07298094, -0.04619132 -0.13455555 0.074371412, -0.044669643 -0.13507521 0.074369803, -0.04481931 -0.13611454 0.074014381, -0.045894921 -0.13695607 0.073273346, -0.044858888 -0.13707134 0.07345067, -0.04480134 -0.13782963 0.072790191, -0.046831518 -0.13568684 0.073894322, -0.046412066 -0.13689202 0.073180676, -0.047835663 -0.13545942 0.073829621, -0.049842745 -0.13389486 0.074194282, -0.052484676 -0.13252687 0.074301004, -0.05304651 -0.1324164 0.074269563, -0.05416958 -0.13218611 0.074200004, -0.054362431 -0.13313618 0.073740363, -0.053935096 -0.13138887 0.074418277, -0.053357676 -0.13454559 0.072993636, -0.054441065 -0.13408452 0.073018327, -0.04719162 -0.13434535 0.074340835, -0.04769136 -0.13423714 0.074323907, -0.048484161 -0.13395271 0.074323982, -0.048274964 -0.1344682 0.074194238, -0.048937127 -0.13393614 0.074284628, -0.050489396 -0.13335872 0.074284807, -0.065925926 -0.1263161 0.074316867, -0.066788301 -0.12724477 0.073800705, -0.065713093 -0.12774667 0.073829986, -0.065391317 -0.126562 0.074324451, -0.064761505 -0.12927124 0.073143706, -0.063869551 -0.12947246 0.073335044, -0.064225093 -0.12850127 0.073829889, -0.06538707 -0.12871277 0.073335141, -0.065205231 -0.12916458 0.073043391, -0.065954134 -0.12878385 0.073043264, -0.06649451 -0.12852883 0.073022895, -0.067571849 -0.12801191 0.072981454, -0.060965821 -0.12853771 0.07437174, -0.059511974 -0.12922457 0.074370056, -0.059777126 -0.13024044 0.074014395, -0.060940191 -0.13095632 0.073273845, -0.059923515 -0.13118672 0.073451087, -0.059951141 -0.13194683 0.072790653, -0.06172885 -0.12959021 0.073894762, -0.061446652 -0.13083479 0.073180936, -0.062701076 -0.1292519 0.073829927, -0.064520389 -0.12747246 0.07419467, -0.066992432 -0.12581715 0.074301377, -0.067538589 -0.12564442 0.074269995, -0.068628639 -0.12528998 0.074200593, -0.068926796 -0.12621251 0.073740713, -0.068306476 -0.12452385 0.074418716, -0.068086028 -0.12772539 0.072993815, -0.069111146 -0.12714604 0.073018678, -0.061936319 -0.12821671 0.074341029, -0.062420815 -0.12805325 0.074324362, -0.06317696 -0.12768191 0.074324317, -0.063026533 -0.12821764 0.07419461, -0.063624948 -0.12761483 0.07428512, -0.065102875 -0.12686729 0.07428509, -0.1039446 -0.097453803 0.074318446, -0.10478637 -0.096630871 0.074302845, -0.10506514 -0.098045677 0.073802426, -0.10421634 -0.098874569 0.073831692, -0.10352141 -0.097862661 0.074325994, -0.10382132 -0.10062802 0.07314527, -0.10304614 -0.10111231 0.073336795, -0.10306089 -0.10007837 0.073831551, -0.10422746 -0.099894166 0.073336855, -0.10420521 -0.10038063 0.073044993, -0.10478631 -0.099773675 0.073044971, -0.10521199 -0.099354744 0.0730244, -0.10605805 -0.09851113 0.072983064, -0.099996671 -0.10118914 0.07437326, -0.098850988 -0.10231751 0.074371658, -0.099436946 -0.10318896 0.07401596, -0.10077127 -0.10348049 0.073275402, -0.099887609 -0.1040338 0.073452376, -0.10016488 -0.10474202 0.07279212, -0.10106425 -0.10193053 0.073896199, -0.10120918 -0.10319847 0.073182531, -0.1018702 -0.10128999 0.073831402, -0.10299987 -0.099009573 0.074196197, -0.10524469 -0.09628734 0.074271597, -0.10615664 -0.095592737 0.074202031, -0.10674274 -0.096365124 0.073742382, -0.10559954 -0.094975978 0.074420407, -0.10644898 -0.098070651 0.072995484, -0.10722502 -0.097185254 0.07302019, -0.1008066 -0.10056573 0.074342556, -0.10120983 -0.10025132 0.074325815, -0.10180089 -0.099651188 0.07432583, -0.10183606 -0.10020629 0.074196085, -0.10220174 -0.099439591 0.074286558, -0.10334964 -0.098246008 0.07428664, -0.11420201 -0.085203022 0.074319109, -0.11538169 -0.085665435 0.073803015, -0.11463089 -0.086584389 0.073832251, -0.11382715 -0.085656524 0.074326783, -0.11443486 -0.088370979 0.073145933, -0.11371865 -0.08893913 0.073337458, -0.11361763 -0.087909907 0.073832266, -0.11475623 -0.087596208 0.073337443, -0.11478853 -0.088082284 0.073045835, -0.11529807 -0.087414116 0.07304579, -0.11567432 -0.086950094 0.07302513, -0.1164206 -0.086016804 0.07298369, -0.11069696 -0.089356929 0.074373923, -0.10968498 -0.090606481 0.074372299, -0.1103647 -0.091406882 0.07401672, -0.11172333 -0.091547042 0.073276035, -0.11090734 -0.09219566 0.073453143, -0.111262 -0.092868537 0.072792746, -0.11184098 -0.089974105 0.073896892, -0.11212695 -0.091217875 0.073183268, -0.11257017 -0.089247376 0.073832184, -0.11343728 -0.086854845 0.074196935, -0.1149462 -0.084290862 0.074303485, -0.11536328 -0.083898306 0.074272305, -0.11619169 -0.083105892 0.07420285, -0.11686049 -0.083807856 0.073743045, -0.11556898 -0.082555592 0.074421152, -0.1167597 -0.085535526 0.072996363, -0.11743157 -0.084568858 0.073020965, -0.11143204 -0.088646591 0.074343458, -0.11179759 -0.088289171 0.07432656, -0.11231761 -0.087626457 0.0743265, -0.11241482 -0.088174284 0.074196756, -0.11269239 -0.087371528 0.074287243, -0.11369949 -0.086056679 0.074287541, -0.092380054 -0.10847923 0.074317858, -0.09330871 -0.10775557 0.074302219, -0.093427435 -0.10919276 0.073801801, -0.091913588 -0.10883805 0.074325226, -0.092490911 -0.10992151 0.073831104, -0.091902383 -0.1116195 0.073144637, -0.091077656 -0.11201414 0.073336087, -0.091208316 -0.11098811 0.073830917, -0.092388049 -0.11093587 0.073336221, -0.092311442 -0.1114167 0.073044397, -0.092956759 -0.11087883 0.073044494, -0.093426697 -0.11051017 0.073023841, -0.094362162 -0.10976633 0.072982475, -0.088038646 -0.11174896 0.07437285, -0.086774074 -0.11274207 0.074371211, -0.087258607 -0.1136736 0.074015364, -0.088551857 -0.11411259 0.073274776, -0.087611996 -0.11456364 0.073451996, -0.087808207 -0.11529833 0.07279142, -0.089016549 -0.11260524 0.073895678, -0.089018598 -0.11388144 0.07318195, -0.089889444 -0.112059 0.073830962, -0.091267057 -0.1099194 0.074195638, -0.093802698 -0.1074656 0.074270949, -0.094786659 -0.10687724 0.07420142, -0.095282726 -0.10771051 0.073741809, -0.094301917 -0.10620221 0.074419692, -0.094799712 -0.10937268 0.072994925, -0.095669948 -0.10857967 0.073019579, -0.088913456 -0.11122 0.074342117, -0.089349478 -0.11095285 0.074325182, -0.090003796 -0.11042261 0.074325196, -0.089976639 -0.11097831 0.074195512, -0.090425834 -0.11025745 0.074286066, -0.091700256 -0.1091997 0.074286193, -0.07965406 -0.11814031 0.074317329, -0.079602547 -0.11958596 0.073830523, -0.079150327 -0.11844471 0.074324816, -0.078827538 -0.12120751 0.073144071, -0.077963956 -0.1215072 0.073335707, -0.078208417 -0.1205025 0.073830567, -0.079386629 -0.12058246 0.073335685, -0.079256549 -0.12105194 0.073043875, -0.079958245 -0.12058961 0.073043965, -0.080466583 -0.12027571 0.073023215, -0.080614708 -0.11896673 0.073801145, -0.081479259 -0.1196413 0.072981842, -0.074973643 -0.12090355 0.07437215, -0.073605761 -0.12174892 0.074370742, -0.073983103 -0.12272868 0.074015051, -0.075219072 -0.1233097 0.073274195, -0.074234523 -0.12365267 0.073451504, -0.074347034 -0.12440491 0.072790891, -0.075849839 -0.12186384 0.07389494, -0.075708933 -0.12313223 0.073181413, -0.07677798 -0.12141883 0.073830165, -0.078386627 -0.11944696 0.074195139, -0.08065778 -0.11752522 0.07430163, -0.081181072 -0.11729255 0.074270457, -0.082224622 -0.11681816 0.074200913, -0.082624227 -0.11770162 0.073741212, -0.081818759 -0.11609295 0.074419312, -0.081958301 -0.11929908 0.072994456, -0.082911797 -0.11860862 0.073019043, -0.075901911 -0.12047601 0.07434158, -0.076365203 -0.12025926 0.074324831, -0.077074938 -0.11980554 0.07432472, -0.076985627 -0.1203548 0.074194826, -0.07751289 -0.11968866 0.074285634, -0.078897774 -0.11878031 0.074285507, 0.13029711 0.057646304 0.074327052, 0.13155031 0.057834715 0.073810935, 0.13102272 0.058897644 0.07384041, 0.13003257 0.058171839 0.074334711, 0.13122919 0.060682893 0.0731543, 0.13247503 0.060123682 0.072027832, 0.13101606 0.063239604 0.072027907, 0.13065749 0.061396122 0.073345706, 0.13032995 0.060415238 0.073840678, 0.1313702 0.059856057 0.07334584, 0.13150989 0.060322791 0.073054001, 0.13185792 0.059558064 0.07305409, 0.13212134 0.05902192 0.073033497, 0.13264124 0.057946026 0.072991818, 0.1278044 0.06247586 0.074382469, 0.12709576 0.063919365 0.074380979, 0.12793657 0.064548343 0.074025407, 0.12929222 0.064382792 0.073285028, 0.12864111 0.065196812 0.073462039, 0.12913658 0.065773904 0.072801635, 0.12905699 0.062823087 0.073905483, 0.12961258 0.063971907 0.073191896, 0.12948383 0.06632027 0.072028175, 0.12960626 0.061952263 0.073840693, 0.12991926 0.059426546 0.07420522, 0.13081986 0.056591332 0.074311376, 0.13113916 0.056115717 0.074280083, 0.13177042 0.055158883 0.07421051, 0.13257869 0.055694401 0.073750943, 0.13104081 0.054760814 0.074428767, 0.1338599 0.056973934 0.072027698, 0.13286473 0.05740127 0.073004335, 0.13330485 0.056309402 0.073028848, 0.12836288 0.061619818 0.074351713, 0.12863992 0.06118989 0.074334905, 0.12899941 0.060428143 0.074334741, 0.12921607 0.060940564 0.074205086, 0.129308 0.060096055 0.074295551, 0.12999718 0.058590353 0.074295387, 0.12302309 0.071872413 0.074327931, 0.12360397 0.073197126 0.073841408, 0.12270138 0.072364986 0.074335441, 0.12360929 0.074994385 0.073155031, 0.12490982 0.074577987 0.072028726, 0.12311113 0.077511162 0.072028667, 0.12296121 0.075639158 0.073346511, 0.12274548 0.074627668 0.073841348, 0.12384194 0.07418856 0.073346347, 0.12392844 0.074667841 0.073054984, 0.12436 0.073946953 0.073054805, 0.12468173 0.073443741 0.073034033, 0.12424731 0.0722 0.073811948, 0.12531894 0.072432786 0.072992429, 0.12000521 0.076392531 0.074383333, 0.11913945 0.077747613 0.074381843, 0.11990449 0.078466803 0.074026331, 0.12127018 0.078454137 0.073285595, 0.12053204 0.079190075 0.073462814, 0.1209598 0.079819113 0.072802499, 0.12121107 0.076877832 0.073906228, 0.12163453 0.078081548 0.073192731, 0.12124372 0.080400765 0.072029084, 0.12185447 0.076073885 0.073841333, 0.12244813 0.073599428 0.074205905, 0.12366064 0.070882559 0.074312255, 0.12403113 0.070445806 0.074280903, 0.12476547 0.069565713 0.074211404, 0.12550876 0.070188314 0.073751822, 0.12408522 0.06908834 0.074429512, 0.12663862 0.071603298 0.072028324, 0.12560192 0.07191655 0.073004961, 0.12616143 0.070880681 0.073029652, 0.12065622 0.07560429 0.074352369, 0.12097943 0.075208127 0.074335575, 0.12142192 0.07449162 0.074335456, 0.12157975 0.075025141 0.07420592, 0.12176575 0.074196249 0.074296281, 0.12261926 0.072777063 0.074296325, 0.13985889 0.027206898 0.074325517, 0.14013362 0.026062131 0.074309617, 0.1411224 0.027111918 0.073809296, 0.14084467 0.028265446 0.073838636, 0.13971797 0.027778119 0.074333131, 0.14144322 0.029960126 0.073152617, 0.14253326 0.029137582 0.072026059, 0.14180426 0.032500118 0.072026297, 0.14104447 0.030782789 0.073343977, 0.14050682 0.029899299 0.073839024, 0.14139651 0.02912271 0.073344097, 0.1416366 0.029546559 0.073052183, 0.1418059 0.028723538 0.073052153, 0.14194325 0.028142244 0.0730315, 0.14221086 0.026977599 0.07299003, 0.13850322 0.032470196 0.074380875, 0.13813356 0.034035116 0.074379459, 0.13909324 0.03446126 0.074023753, 0.1403781 0.03399834 0.073282972, 0.13992445 0.034936786 0.073460206, 0.14053594 0.035389125 0.072799727, 0.13980158 0.03252998 0.073903769, 0.14059883 0.033526421 0.073190272, 0.14099592 0.035844475 0.072026551, 0.14014341 0.031558692 0.073839024, 0.13988656 0.029026777 0.074203357, 0.140339 0.025527596 0.074278206, 0.14074144 0.024454266 0.074208796, 0.14164869 0.024796426 0.073749065, 0.13994175 0.024228483 0.074426904, 0.14318258 0.025758833 0.07202591, 0.14230749 0.026396811 0.073002681, 0.14249364 0.025234252 0.073026985, 0.13885728 0.031511307 0.074350163, 0.13903143 0.031030506 0.074333251, 0.13921262 0.030208021 0.074333102, 0.13953774 0.030659348 0.074203417, 0.13943955 0.029815584 0.074293911, 0.13977647 0.028194189 0.074293777, 0.13593259 0.042694986 0.074326307, 0.13633402 0.041588217 0.07431066, 0.13719912 0.042741925 0.07381022, 0.13679381 0.043857276 0.073839799, 0.1357286 0.043247074 0.074333817, 0.1371989 0.045608371 0.073153436, 0.13837413 0.044912994 0.072027013, 0.13727325 0.048172742 0.072027162, 0.13671052 0.046381086 0.073344842, 0.13627529 0.045442998 0.073839694, 0.13724628 0.044770986 0.073344812, 0.13743742 0.045219034 0.073053226, 0.13769773 0.044420153 0.073053315, 0.13789932 0.043857783 0.073032543, 0.13829559 0.042730451 0.072990939, 0.13399634 0.047773361 0.074381649, 0.13345376 0.04928717 0.074380234, 0.13435973 0.049818158 0.074024782, 0.13568841 0.049501747 0.07328397, 0.13513242 0.050383627 0.073461309, 0.1356895 0.050901562 0.072800785, 0.13527992 0.047978193 0.073904574, 0.1359605 0.049057722 0.073191032, 0.13609564 0.051405549 0.07202746, 0.13572823 0.04705137 0.073839828, 0.13575634 0.044506729 0.074204162, 0.13659799 0.041079938 0.074279234, 0.13711813 0.040058494 0.07420972, 0.13798122 0.040500164 0.073749781, 0.13634855 0.039744675 0.074427933, 0.13939764 0.041628182 0.072026908, 0.1384567 0.042164296 0.073003352, 0.13877168 0.0410299 0.073027954, 0.13445571 0.046860158 0.074350834, 0.13468243 0.046402037 0.074334115, 0.13495448 0.045604974 0.074333921, 0.13522716 0.046089828 0.074204206, 0.13522398 0.045240462 0.074294835, 0.13574038 0.043666929 0.074294567, 0.079653814 0.11813211 0.074330583, 0.080614686 0.11895838 0.073814288, 0.079602569 0.11957771 0.073843941, 0.079150289 0.11843634 0.074337929, 0.078827456 0.12119913 0.073157787, 0.080179885 0.12138847 0.0720312, 0.07728675 0.12325063 0.072031423, 0.077963918 0.121499 0.073349148, 0.078208253 0.12049416 0.073843986, 0.079386726 0.12057412 0.073349163, 0.079256788 0.12104356 0.073057368, 0.079958141 0.12058136 0.073057339, 0.080466509 0.12026748 0.073036686, 0.081479341 0.11963305 0.072995245, 0.074973702 0.12089512 0.074385598, 0.07360591 0.12174034 0.074384332, 0.073983029 0.12272042 0.074028715, 0.075218916 0.12330145 0.073288053, 0.07423453 0.12364432 0.073465139, 0.074347243 0.12439644 0.072804794, 0.075849533 0.12185559 0.073908597, 0.075708672 0.123124 0.073195368, 0.074350402 0.12504381 0.072031468, 0.07677795 0.12141055 0.073843986, 0.078386649 0.11943859 0.074208319, 0.08065775 0.11751693 0.074314803, 0.081181079 0.11728415 0.07428351, 0.082224622 0.1168099 0.074214041, 0.082624033 0.11769336 0.073754475, 0.081818759 0.11608467 0.074432105, 0.083028167 0.11945844 0.07203117, 0.081958249 0.11929074 0.073007628, 0.082911775 0.11860022 0.073032409, 0.075902045 0.12046751 0.074354976, 0.076365307 0.12025082 0.074338093, 0.07707493 0.1197972 0.074338317, 0.076985717 0.12034622 0.074208438, 0.077512845 0.11968032 0.074299023, 0.078897581 0.11877185 0.074298829, 0.092380106 0.10847089 0.074329987, 0.093427524 0.10918438 0.073813885, 0.092490911 0.10991308 0.073843375, 0.0919137 0.10882968 0.074337557, 0.091902345 0.11161128 0.073157191, 0.093267441 0.11164778 0.072030738, 0.090601012 0.11382228 0.072030783, 0.091077626 0.1120058 0.073348597, 0.0912081 0.11098 0.0738433, 0.092388004 0.11092749 0.073348537, 0.092311338 0.11140844 0.073056892, 0.092956901 0.11087048 0.073056847, 0.093426809 0.11050174 0.07303609, 0.094362065 0.10975799 0.072994679, 0.088038698 0.11174062 0.074385196, 0.086774021 0.11273357 0.074383855, 0.087258488 0.11366522 0.074028224, 0.088551983 0.11410424 0.073287517, 0.087611884 0.11455533 0.073464885, 0.087808222 0.11529008 0.072804302, 0.089016601 0.1125969 0.073908359, 0.089018703 0.11387303 0.073194772, 0.087883726 0.11593288 0.072031051, 0.089889377 0.11205059 0.073843345, 0.091267154 0.10991102 0.074207991, 0.093308851 0.1077472 0.074314445, 0.093802691 0.10745716 0.074282885, 0.094786644 0.10686913 0.074213341, 0.09528254 0.10770226 0.073753774, 0.094302058 0.10619393 0.074431613, 0.095881686 0.10941103 0.072030619, 0.094799593 0.10936427 0.073007122, 0.09567 0.10857132 0.073031679, 0.088913262 0.11121184 0.074354455, 0.089349374 0.1109446 0.074337572, 0.090003669 0.1104143 0.074337631, 0.089976594 0.11097002 0.074207976, 0.090425849 0.11024907 0.074298307, 0.091700211 0.10919136 0.074298427, 0.11420199 0.085194588 0.074328586, 0.11382698 0.085648179 0.074336171, 0.11463077 0.086576164 0.073841989, 0.11443481 0.088362604 0.07315591, 0.11577396 0.088094562 0.072029293, 0.11365817 0.090807796 0.072029591, 0.11371875 0.088930756 0.07334727, 0.11361761 0.087901562 0.073842123, 0.11475632 0.087587953 0.073347241, 0.11478853 0.088073969 0.07305558, 0.11529809 0.087405801 0.073055446, 0.11567406 0.086941808 0.073034763, 0.11538167 0.085657269 0.073812678, 0.11642049 0.086008638 0.072993264, 0.11069688 0.089348495 0.074384049, 0.10968488 0.090598017 0.074382558, 0.11036471 0.091398418 0.074027017, 0.11172311 0.091538757 0.073286191, 0.11090711 0.092187434 0.073463514, 0.11126201 0.092860371 0.07280305, 0.11184093 0.089965671 0.073906854, 0.11212689 0.091209352 0.073193386, 0.11147876 0.093470275 0.072029591, 0.11257011 0.089238971 0.073842183, 0.11343729 0.086846411 0.074206576, 0.11494628 0.084282488 0.074313089, 0.11536321 0.083889902 0.074281722, 0.11619166 0.083097577 0.074212134, 0.11686064 0.083799362 0.073752493, 0.11556903 0.082547098 0.074430272, 0.11782494 0.085332066 0.072029293, 0.11675967 0.085527331 0.073005646, 0.1174317 0.084560603 0.073030576, 0.11143196 0.088638276 0.074353203, 0.1117975 0.088280708 0.074336469, 0.11231761 0.087618113 0.074336305, 0.11241476 0.08816582 0.074206784, 0.11269237 0.087363094 0.074297115, 0.11369941 0.086048394 0.074297234, 0.10394464 0.097445518 0.074329361, 0.10478635 0.096622407 0.074313655, 0.10506523 0.098037213 0.073813319, 0.10421619 0.098866343 0.073842749, 0.10352123 0.097854227 0.074336872, 0.10382135 0.10061961 0.073156416, 0.10518202 0.10050318 0.072029978, 0.10277575 0.10296246 0.072030246, 0.10304618 0.10110402 0.07334803, 0.10306095 0.10006994 0.073842824, 0.10422753 0.099885762 0.073347852, 0.10420516 0.10037237 0.073056236, 0.10478632 0.099765509 0.073056117, 0.10521202 0.099346519 0.073035613, 0.1060582 0.098502696 0.072994128, 0.099996477 0.10118076 0.074384764, 0.09885104 0.1023092 0.074383214, 0.09943679 0.10318062 0.074027687, 0.10077094 0.10347223 0.073286936, 0.099887595 0.10402539 0.073464096, 0.10016479 0.10473374 0.072803721, 0.10106422 0.10192227 0.073907495, 0.10120921 0.10319012 0.073194146, 0.10031202 0.10536405 0.07203041, 0.10187024 0.1012817 0.073842764, 0.10299984 0.099001318 0.074207202, 0.10524471 0.096279055 0.074282363, 0.10615662 0.095584393 0.074212804, 0.10674267 0.096356779 0.073753029, 0.10559955 0.094967723 0.074431106, 0.10752943 0.097987711 0.072029814, 0.10644895 0.098062396 0.073006555, 0.10722506 0.097176969 0.073031068, 0.10080647 0.10055727 0.074353814, 0.10120988 0.10024288 0.074336872, 0.10180087 0.099642813 0.074337006, 0.101836 0.10019785 0.074207336, 0.10220179 0.099431247 0.074297786, 0.10334966 0.098237634 0.074297711, 0.13781479 -0.036170244 0.074321777, 0.13756576 -0.037320912 0.074306235, 0.13891213 -0.036804259 0.073805854, 0.13916245 -0.035644323 0.073835194, 0.13793571 -0.035594374 0.074329346, 0.14043689 -0.034377098 0.07314904, 0.14043452 -0.033463061 0.073340565, 0.13956694 -0.034025639 0.073835254, 0.14003164 -0.035111487 0.073340327, 0.14043167 -0.034833699 0.073048696, 0.14022715 -0.035648674 0.073048756, 0.14009877 -0.036232084 0.073028058, 0.13983437 -0.037397265 0.072986528, 0.13887721 -0.030840158 0.074377298, 0.13922316 -0.029269725 0.074375749, 0.14027271 -0.029302061 0.074020192, 0.14122929 -0.030276835 0.07327944, 0.14122786 -0.029234469 0.07345666, 0.14197491 -0.029092133 0.072796255, 0.14007305 -0.031349689 0.073899955, 0.14122367 -0.030797839 0.073186636, 0.13995947 -0.032372981 0.073835284, 0.13862942 -0.034542501 0.074199796, 0.13751887 -0.037891746 0.074274868, 0.13741583 -0.039033413 0.074205384, 0.13838163 -0.039118767 0.073745638, 0.13659723 -0.038889706 0.074423477, 0.13966966 -0.037962645 0.072998911, 0.13933279 -0.039090663 0.073023617, 0.13878022 -0.03185761 0.074346468, 0.13872859 -0.032366455 0.07432954, 0.13853475 -0.033186138 0.07432963, 0.13902368 -0.03292051 0.07419984, 0.13856903 -0.03363803 0.074290305, 0.13816898 -0.035245031 0.074290246, 0.14099765 -0.020512551 0.074322745, 0.14227778 -0.019838899 0.073835939, 0.14105324 -0.019926727 0.074330389, 0.14340249 -0.018437207 0.073150009, 0.14415981 -0.019573539 0.072023436, 0.14458212 -0.016158789 0.072023556, 0.1432977 -0.017528951 0.073341236, 0.14249846 -0.018185258 0.073836192, 0.14308196 -0.019212127 0.073341191, 0.14344831 -0.018891364 0.073049575, 0.14333622 -0.019723982 0.07304959, 0.14327405 -0.02031818 0.073028818, 0.14215904 -0.021019667 0.073806792, 0.1431419 -0.021505743 0.072987258, 0.14145637 -0.015096784 0.074378043, 0.14162442 -0.0134978 0.074376747, 0.14267105 -0.013412476 0.074021086, 0.14373091 -0.014273733 0.07328029, 0.14361249 -0.013237894 0.073457703, 0.14433907 -0.013013065 0.072797194, 0.14270175 -0.015469372 0.073900938, 0.14378335 -0.014792144 0.07318756, 0.14492379 -0.012735218 0.072023764, 0.14270356 -0.016498953 0.073836401, 0.14162475 -0.018803775 0.074200779, 0.14087901 -0.021683812 0.074306995, 0.14089626 -0.022256285 0.074275628, 0.14092176 -0.023402333 0.074206054, 0.14189096 -0.023378909 0.073746413, 0.14009222 -0.023351192 0.074424475, 0.14365655 -0.022977263 0.072023183, 0.1430413 -0.022085845 0.072999805, 0.14283298 -0.02324459 0.073024392, 0.14147404 -0.016118944 0.074347422, 0.14147966 -0.016630203 0.074330613, 0.14137881 -0.017466396 0.074330404, 0.14183487 -0.01714775 0.074200779, 0.14146344 -0.017911702 0.074291214, 0.14124595 -0.019553423 0.074291274, 0.14202589 0.011376679 0.074324518, 0.1432711 0.011140674 0.073808342, 0.14312425 0.012318105 0.073837817, 0.14194998 0.011960119 0.074332133, 0.14390866 0.013935089 0.073151514, 0.14489989 0.01299578 0.072025284, 0.14455184 0.016418785 0.072025284, 0.14360462 0.014797062 0.073343188, 0.14297156 0.013979375 0.073837921, 0.14376867 0.013108134 0.073343024, 0.14405453 0.013502479 0.073051468, 0.14413065 0.012665749 0.073051304, 0.14420216 0.012072712 0.073030651, 0.1443377 0.010885358 0.072989106, 0.14126818 0.016758561 0.074379906, 0.14107622 0.018354982 0.074378461, 0.14207759 0.018671006 0.074022859, 0.14330244 0.018067122 0.073282138, 0.14295666 0.019050598 0.073459402, 0.14361507 0.019431472 0.072799012, 0.14256518 0.016672641 0.073902875, 0.14346904 0.017573476 0.073189288, 0.14412312 0.019832462 0.072025567, 0.14279607 0.015669227 0.073838174, 0.14225735 0.013182044 0.074202344, 0.14217095 0.010208309 0.074308857, 0.14231527 0.0096538961 0.074277475, 0.14259498 0.0085424185 0.074207991, 0.14353485 0.0087808073 0.073748201, 0.14177501 0.0084075332 0.074426174, 0.14516674 0.0095654428 0.072025105, 0.14436859 0.010297477 0.073001638, 0.14442338 0.0091213882 0.07302621, 0.14151274 0.015766084 0.074349269, 0.14163212 0.015268773 0.074332356, 0.14171997 0.014431179 0.074332267, 0.14209358 0.014843255 0.074202582, 0.14190157 0.014015764 0.074293166, 0.14205477 0.012366861 0.074292958, 0.14240728 -0.0045967698 0.074323669, 0.14242044 -0.0057739317 0.074307859, 0.14361821 -0.0049707592 0.073807642, 0.14360385 -0.0037840903 0.073836893, 0.142397 -0.0040085316 0.074331164, 0.14456463 -0.0022651255 0.073150635, 0.14544435 -0.0033097267 0.072024316, 0.14548177 0.000130862 0.072024569, 0.14435899 -0.0013745427 0.073342279, 0.14363822 -0.0021161437 0.073836952, 0.1443329 -0.0030712783 0.07334213, 0.14466111 -0.0027114153 0.073050424, 0.14464299 -0.0035515726 0.073050454, 0.14464766 -0.0041488111 0.073029742, 0.14464933 -0.0053437352 0.072988018, 0.1422568 0.00083613396 0.074379027, 0.14224473 0.0024440289 0.074377596, 0.14327519 0.0026459992 0.07402198, 0.14442465 0.0019087195 0.073281258, 0.14419135 0.0029246509 0.073458523, 0.14488818 0.0032295287 0.072797984, 0.14353597 0.00060552359 0.073901847, 0.14453502 0.0013995171 0.073188424, 0.14543797 0.0035710931 0.072024703, 0.14365312 -0.00041744113 0.073837236, 0.1428393 -0.0028286874 0.074201554, 0.14250176 -0.0063409507 0.074276567, 0.14265536 -0.0074769557 0.074206933, 0.14361592 -0.0073451996 0.073747471, 0.14182542 -0.0075191259 0.074425295, 0.14532551 -0.0067481995 0.072024122, 0.14461435 -0.0059315264 0.073000729, 0.14453703 -0.0071062148 0.073025301, 0.14238866 -0.00017753243 0.074348286, 0.14245152 -0.00068494678 0.074331447, 0.14244503 -0.0015273094 0.074331403, 0.14286248 -0.0011594892 0.074201733, 0.14257905 -0.0019603372 0.074291945, 0.14254674 -0.0036160648 0.074292079, 0.13289894 -0.051373184 0.074320957, 0.13252269 -0.052488655 0.074305534, 0.13391843 -0.052126169 0.073804975, 0.13429688 -0.0510014 0.073834389, 0.13308354 -0.05081445 0.074328542, 0.13570546 -0.049885094 0.073148176, 0.13619055 -0.051161289 0.072021544, 0.13736244 -0.047926426 0.072021931, 0.13580532 -0.048976332 0.07333979, 0.13488014 -0.049438298 0.073834419, 0.13522027 -0.050569266 0.073339552, 0.13564911 -0.050338089 0.073047951, 0.13535441 -0.05112493 0.073047742, 0.13516155 -0.05169031 0.073027104, 0.13476844 -0.052818686 0.072985619, 0.13455144 -0.046195537 0.074376464, 0.13507099 -0.044673771 0.074374959, 0.13611029 -0.044823468 0.074019298, 0.13695192 -0.045899063 0.073278666, 0.13706708 -0.044863135 0.073455811, 0.13782544 -0.044805437 0.072795376, 0.13568257 -0.046835631 0.073899209, 0.13688777 -0.046416163 0.073185757, 0.13845727 -0.044664621 0.072021872, 0.13545521 -0.047839791 0.073834613, 0.13389066 -0.049846977 0.074198961, 0.13241206 -0.053050727 0.074274093, 0.13218193 -0.054173648 0.074204534, 0.13313214 -0.054366678 0.073744774, 0.13138461 -0.053939372 0.074422687, 0.1349428 -0.054367691 0.072021499, 0.13454141 -0.053361952 0.072998077, 0.13408037 -0.054445267 0.073022708, 0.13434108 -0.047195733 0.074345514, 0.13423289 -0.047695547 0.074328661, 0.13394855 -0.048488438 0.074328542, 0.13446401 -0.048279196 0.074198917, 0.13393191 -0.048941314 0.074289352, 0.13335441 -0.050493389 0.074289396, 0.12631182 -0.065930128 0.074320167, 0.12581293 -0.066996485 0.074304596, 0.12724052 -0.066792488 0.073804215, 0.12774253 -0.06571734 0.073833451, 0.12655765 -0.065395534 0.074327856, 0.12926711 -0.064765513 0.073147178, 0.12946826 -0.063873798 0.073338777, 0.12849717 -0.06422931 0.073833644, 0.12870863 -0.065391272 0.073338479, 0.12916039 -0.065209419 0.073047027, 0.12877955 -0.065958411 0.073047072, 0.12852477 -0.066498637 0.073026389, 0.12800774 -0.067575872 0.072984755, 0.12853357 -0.060969979 0.074375421, 0.12922046 -0.059516132 0.074374154, 0.1302364 -0.059781283 0.074018583, 0.13095219 -0.060944289 0.073277667, 0.13118264 -0.059927642 0.073454991, 0.13194272 -0.059955329 0.072794542, 0.12958586 -0.061732829 0.073898494, 0.13083059 -0.061450809 0.073184878, 0.12924773 -0.062705308 0.073833585, 0.1274682 -0.064524651 0.074198291, 0.12564021 -0.067542553 0.07427305, 0.12528569 -0.068632782 0.074203685, 0.12620832 -0.068930805 0.07374391, 0.12451965 -0.068310648 0.074421763, 0.12772128 -0.06809023 0.072997287, 0.12714176 -0.069115192 0.073021963, 0.12821247 -0.061940402 0.074344829, 0.12804908 -0.062425077 0.074327826, 0.12767777 -0.063180983 0.074327841, 0.12821347 -0.063030809 0.074198112, 0.12761058 -0.06362921 0.074288532, 0.12686296 -0.065106988 0.074288741, 0.11813629 -0.07965818 0.074319437, 0.11896269 -0.080619007 0.073803291, 0.11958183 -0.079606712 0.073832721, 0.11844055 -0.079154432 0.074326858, 0.12120326 -0.078831643 0.073146567, 0.12150306 -0.077967942 0.073337972, 0.12049821 -0.078212589 0.073832899, 0.1205783 -0.079390913 0.073337823, 0.1210476 -0.079260886 0.073046237, 0.12058541 -0.079962403 0.073046193, 0.12027149 -0.080470651 0.073025361, 0.11963722 -0.081483394 0.072983816, 0.12089942 -0.074977875 0.074374884, 0.12174466 -0.073610008 0.074373186, 0.12272453 -0.073987246 0.074017867, 0.12330569 -0.075223088 0.073276937, 0.12364854 -0.074238598 0.073454127, 0.12440068 -0.074351221 0.072793677, 0.12185976 -0.075853676 0.073897645, 0.1231281 -0.075712949 0.073184013, 0.12141463 -0.076782167 0.073832631, 0.11944272 -0.078390896 0.074197218, 0.11752103 -0.080661833 0.074303865, 0.11728828 -0.081185192 0.074272424, 0.11681402 -0.082228839 0.074202836, 0.11769745 -0.08262828 0.073743045, 0.11608885 -0.081822902 0.074421108, 0.11929493 -0.081962377 0.072996393, 0.11860435 -0.082915932 0.073021159, 0.12047169 -0.075906277 0.074343845, 0.12025505 -0.076369464 0.07432729, 0.11980142 -0.077079207 0.074327067, 0.12035042 -0.0769898 0.074197412, 0.11968438 -0.077517122 0.074287966, 0.11877625 -0.078901976 0.074287906, 0.10847491 -0.092384309 0.074318826, 0.10775131 -0.093312949 0.074302971, 0.1091885 -0.093431681 0.073802695, 0.10991736 -0.092495114 0.07383202, 0.10883373 -0.091917843 0.074326113, 0.11161548 -0.091906577 0.073145926, 0.11200991 -0.091081798 0.073337227, 0.1109841 -0.091212302 0.073832229, 0.11093159 -0.092392176 0.073337212, 0.11141269 -0.092315584 0.073045388, 0.11087461 -0.092960924 0.073045433, 0.11050595 -0.093430907 0.073024914, 0.10976213 -0.094366163 0.072983384, 0.11174479 -0.088042915 0.07437405, 0.11273775 -0.086778134 0.074372455, 0.11366932 -0.08726269 0.074016988, 0.1141085 -0.088555932 0.073276207, 0.11455943 -0.087616116 0.073453575, 0.1152942 -0.087812275 0.072793007, 0.11260109 -0.089020789 0.073897004, 0.11387713 -0.089022845 0.073183283, 0.11205485 -0.089893609 0.073832139, 0.10991512 -0.091271192 0.074196637, 0.10746144 -0.093806952 0.074271753, 0.10687323 -0.094790787 0.074202061, 0.10770646 -0.095286787 0.073742464, 0.10619807 -0.09430626 0.074420482, 0.10936829 -0.09480384 0.072995916, 0.10857555 -0.095674157 0.073020339, 0.11121579 -0.088917613 0.074343249, 0.11094858 -0.089353561 0.074326351, 0.11041844 -0.090007961 0.074326366, 0.11097415 -0.08998087 0.074196801, 0.11025326 -0.090430051 0.074287042, 0.10919547 -0.091704398 0.074286997, -0.011380777 0.14202192 0.074331895, -0.011144772 0.14326701 0.073815823, -0.012322277 0.14312005 0.073845133, -0.011964306 0.14194572 0.074339435, -0.013939276 0.14390466 0.073159024, -0.012999907 0.14489573 0.07203263, -0.016422927 0.14454776 0.072032645, -0.014801398 0.14360061 0.073350355, -0.013983756 0.14296725 0.073845133, -0.013112321 0.14376447 0.073350325, -0.013506636 0.14405051 0.07305862, -0.012669906 0.14412653 0.073058635, -0.012076765 0.14419806 0.073038101, -0.0108895 0.14433357 0.072996467, -0.016762704 0.14126402 0.074386999, -0.01835911 0.14107201 0.074385285, -0.018675238 0.14207333 0.074029699, -0.018071279 0.14329824 0.07328929, -0.019054785 0.14295262 0.073466405, -0.019435644 0.14361084 0.072806001, -0.016676664 0.14256114 0.073909819, -0.017577574 0.1434648 0.073196396, -0.019836724 0.14411902 0.072032467, -0.01567328 0.14279196 0.073845148, -0.013186172 0.14225313 0.07420969, -0.010212377 0.1421667 0.074316323, -0.0096582919 0.14231116 0.074284777, -0.0085466206 0.14259091 0.074215561, -0.0087848902 0.1435307 0.073755875, -0.0084117502 0.14177078 0.074433759, -0.0095695257 0.14516252 0.072032645, -0.01030159 0.14436451 0.073009178, -0.0091256946 0.14441916 0.073033795, -0.015770391 0.14150861 0.074356198, -0.015273035 0.14162785 0.074339405, -0.014435455 0.14171588 0.074339464, -0.014847592 0.14208943 0.07420963, -0.014020085 0.14189732 0.074300021, -0.012371078 0.14205071 0.074300215, 0.0045925677 0.14240319 0.074331909, 0.0057697296 0.1424163 0.074316114, 0.0049666613 0.14361393 0.073815823, 0.0037800074 0.14359975 0.073845327, 0.00400424 0.14239281 0.07433933, 0.0022610724 0.14456043 0.073159158, 0.0033055544 0.14544019 0.072032735, -0.00013494492 0.14547771 0.072032616, 0.0013702959 0.14435479 0.073350608, 0.0021119118 0.14363408 0.073845193, 0.0030670315 0.14432862 0.07335037, 0.0027072579 0.14465702 0.073058784, 0.0035473108 0.14463887 0.073058799, 0.004144609 0.14464343 0.073038012, 0.0053395331 0.14464527 0.072996587, -0.00084035099 0.14225268 0.074386939, -0.0024482459 0.14224058 0.074385479, -0.0026503205 0.14327103 0.074029788, -0.0019128919 0.14442056 0.073289275, -0.0029288232 0.14418709 0.073466286, -0.0032336116 0.14488393 0.072806165, -0.00060966611 0.14353186 0.073910087, -0.0014036298 0.14453089 0.073196471, -0.0035753101 0.14543378 0.072032571, 0.00041329861 0.14364889 0.073845267, 0.0028244704 0.14283511 0.074209645, 0.0063367039 0.14249766 0.074284896, 0.0074727535 0.14265117 0.074215367, 0.0073411465 0.14361176 0.073755771, 0.0075148791 0.14182106 0.074433684, 0.0067441165 0.14532131 0.07203269, 0.0059273243 0.14461011 0.073009118, 0.0071020126 0.14453286 0.073033854, 0.0001731813 0.1423845 0.074356392, 0.00068083405 0.14244735 0.074339554, 0.0015229732 0.14244089 0.074339345, 0.0011553019 0.14285842 0.074209824, 0.0019560903 0.14257482 0.074300066, 0.0036118478 0.14254257 0.07430014, -0.042699188 0.13592842 0.074331433, -0.042746142 0.1371949 0.073815614, -0.043861493 0.13678956 0.07384482, -0.043251261 0.13572448 0.074338987, -0.045612544 0.13719466 0.073158637, -0.044917226 0.13837007 0.072032213, -0.048176929 0.13726905 0.072032258, -0.046385303 0.13670641 0.073350012, -0.045447379 0.13627109 0.073844954, -0.044775099 0.13724217 0.073350042, -0.045223147 0.13743323 0.073058411, -0.044424415 0.13769346 0.073058292, -0.043862149 0.13789532 0.073037788, -0.042734623 0.13829145 0.072996348, -0.047777563 0.13399205 0.074386626, -0.049291357 0.1334497 0.074384943, -0.04982233 0.13435552 0.074029401, -0.049505979 0.13568413 0.073288843, -0.05038783 0.13512823 0.073465958, -0.050905794 0.13568538 0.072805583, -0.047982275 0.13527572 0.073909402, -0.049061835 0.1359565 0.073195994, -0.051409781 0.13609147 0.072032228, -0.047055513 0.13572401 0.073844671, -0.044510826 0.13575229 0.074209228, -0.041592389 0.13632983 0.074315876, -0.041084096 0.13659382 0.074284673, -0.040062651 0.13711399 0.074215174, -0.040504187 0.13797712 0.073755428, -0.039748773 0.13634443 0.074433416, -0.041632295 0.1393936 0.072032139, -0.042168468 0.13845256 0.073008776, -0.041034013 0.1387676 0.073033392, -0.046864569 0.13445142 0.074355736, -0.046406299 0.13467839 0.074338928, -0.045609087 0.13495037 0.074339062, -0.046093985 0.13522282 0.074209303, -0.045244619 0.1352199 0.074299544, -0.043671012 0.13573614 0.074299663, -0.02721113 0.13985458 0.074331865, -0.028269753 0.14084053 0.073844984, -0.0277825 0.1397137 0.074339256, -0.029964238 0.14143899 0.073158845, -0.029141665 0.14252892 0.072032452, -0.03250432 0.14180022 0.072032332, -0.030786827 0.1410403 0.073350117, -0.029903427 0.14050263 0.07384491, -0.029126853 0.14139244 0.073350355, -0.029550672 0.14163253 0.073058575, -0.02872777 0.14180169 0.073058829, -0.028146386 0.14193913 0.073038012, -0.027115971 0.1411182 0.073815808, -0.026981816 0.14220682 0.072996512, -0.032474369 0.13849902 0.074386835, -0.034039348 0.13812941 0.074385002, -0.034465536 0.13908905 0.074029565, -0.034002408 0.14037389 0.073288977, -0.034941077 0.13992032 0.073466241, -0.035393164 0.14053166 0.072805777, -0.032534108 0.13979757 0.073909715, -0.033530578 0.14059469 0.073196143, -0.035848692 0.14099184 0.072032347, -0.031562924 0.14013922 0.073845029, -0.029031068 0.13988218 0.07420972, -0.026066452 0.14012948 0.07431598, -0.025531679 0.14033484 0.074284762, -0.024458244 0.14073738 0.074215278, -0.024800584 0.1416446 0.073755637, -0.024232805 0.13993761 0.07443352, -0.025762886 0.14317828 0.072032496, -0.026401117 0.14230332 0.073009014, -0.025238529 0.14248931 0.073033571, -0.031515464 0.13885313 0.07435596, -0.031034783 0.13902733 0.074339107, -0.030212253 0.13920847 0.074339271, -0.03066355 0.13953367 0.074209377, -0.029819861 0.13943547 0.074300006, -0.028198317 0.1397723 0.074300155, 0.020508215 0.14099351 0.074331924, 0.02167958 0.14087477 0.074316129, 0.021015421 0.14215478 0.073815778, 0.019834846 0.1422736 0.073845133, 0.019922465 0.14104915 0.074339092, 0.018432811 0.1433984 0.07315889, 0.019569248 0.14415559 0.072032556, 0.016154736 0.14457816 0.072032705, 0.017524809 0.14329365 0.073350295, 0.018180981 0.14249447 0.073845088, 0.019207865 0.14307782 0.073350236, 0.018887132 0.14344427 0.073058814, 0.019719914 0.14333215 0.07305862, 0.020313889 0.14326999 0.073038116, 0.021501511 0.14313778 0.072996482, 0.015092611 0.14145228 0.074386999, 0.013493553 0.14162022 0.0743853, 0.013408259 0.14266682 0.074029773, 0.014269665 0.14372665 0.073289275, 0.013233796 0.14360845 0.073466316, 0.013008997 0.14433491 0.072806001, 0.01546523 0.14269766 0.073910087, 0.014787927 0.14377928 0.073196337, 0.01273112 0.14491954 0.072032601, 0.016494721 0.14269936 0.073845208, 0.018799648 0.14162067 0.074209675, 0.022251979 0.14089206 0.074284807, 0.023398057 0.14091754 0.074215412, 0.0233749 0.14188674 0.073755786, 0.02334702 0.14008808 0.074433699, 0.022972941 0.14365238 0.072032586, 0.022081584 0.1430372 0.073009044, 0.023240447 0.14282882 0.07303375, 0.016114667 0.14146978 0.074356243, 0.016626045 0.14147556 0.074339435, 0.017462149 0.14137483 0.074339226, 0.017143592 0.14183065 0.074209705, 0.017907545 0.14145926 0.074300081, 0.019549236 0.14124188 0.074300066, 0.036166057 0.13781068 0.074331492, 0.036800146 0.13890788 0.073815688, 0.035640135 0.13915822 0.073845014, 0.035590142 0.1379315 0.074339136, 0.034372881 0.1404328 0.073158771, 0.035586998 0.14105812 0.072032347, 0.032241136 0.14186016 0.072032347, 0.033458844 0.14043054 0.073350176, 0.034021333 0.13956282 0.073844925, 0.035107329 0.14002746 0.073350206, 0.034829572 0.14042753 0.073058441, 0.035644472 0.14022291 0.073058471, 0.036227852 0.14009455 0.073037922, 0.037393212 0.13983035 0.072996333, 0.030835792 0.13887283 0.074386716, 0.029265627 0.13921881 0.0743853, 0.029298022 0.14026853 0.074029773, 0.030272707 0.14122519 0.073289067, 0.029230207 0.14122367 0.073466167, 0.029088005 0.14197075 0.072805792, 0.031345397 0.14006877 0.073909715, 0.030793652 0.14121944 0.073196307, 0.028877392 0.14258286 0.072032496, 0.03236866 0.1399554 0.073844999, 0.034538403 0.13862532 0.074209496, 0.037316769 0.13756165 0.074315995, 0.037887514 0.13751474 0.074284673, 0.039029166 0.13741171 0.074215069, 0.039114535 0.13837761 0.073755488, 0.038885608 0.13659319 0.074433208, 0.038913161 0.14017689 0.072032347, 0.037958309 0.13966542 0.073008806, 0.03908655 0.13932869 0.073033541, 0.031853363 0.138776 0.074355975, 0.032362074 0.13872439 0.074339285, 0.033181906 0.13853061 0.074339002, 0.032916233 0.1390194 0.074209467, 0.033633843 0.13856477 0.074300036, 0.035240933 0.13816485 0.074300006, -0.13289903 0.051364809 0.074326828, -0.13391845 0.052117705 0.073810741, -0.13429694 0.050993055 0.073840126, -0.13308351 0.050806046 0.074334279, -0.13570532 0.04987669 0.073153645, -0.13619065 0.051153153 0.072027296, -0.13736245 0.047918051 0.072027102, -0.13580544 0.048968017 0.07334511, -0.13488011 0.049429953 0.073839918, -0.13522035 0.050560981 0.073345259, -0.13564892 0.050329775 0.073053539, -0.13535443 0.051116616 0.073053494, -0.13516164 0.051681966 0.073032886, -0.13476859 0.052810431 0.072991535, -0.13455145 0.046187073 0.074381545, -0.13507093 0.044665337 0.074379936, -0.13611038 0.044815123 0.074024305, -0.13695194 0.045890838 0.073283836, -0.13706712 0.044854611 0.073460862, -0.13782543 0.044797182 0.072800457, -0.13568264 0.046827435 0.07390438, -0.1368878 0.046407878 0.073190883, -0.13845736 0.044656366 0.072026879, -0.13545531 0.047831535 0.073840007, -0.13389066 0.049838573 0.074204415, -0.13252263 0.05248028 0.074311152, -0.13241221 0.053042382 0.074280038, -0.13218194 0.054165244 0.074210554, -0.13313217 0.054358363 0.073750868, -0.13138463 0.053930938 0.074428692, -0.13494292 0.054359496 0.07202746, -0.13454129 0.053353608 0.073004022, -0.13408037 0.054436922 0.073028818, -0.13434112 0.047187388 0.074350819, -0.13423291 0.047687113 0.07433413, -0.13394865 0.048480123 0.074334174, -0.13446397 0.048270732 0.074204311, -0.13393198 0.04893297 0.074294955, -0.13335453 0.050485164 0.074294999, -0.12686303 0.065098703 0.074295774, -0.12746827 0.064516187 0.074205339, -0.12761056 0.063620925 0.074295774, -0.12655774 0.06538713 0.074334919, -0.12774263 0.065708786 0.073840827, -0.12631181 0.065921724 0.074327528, -0.12581308 0.06698817 0.074312121, -0.12724058 0.066784143 0.073811576, -0.12926711 0.064757258 0.073154479, -0.12960652 0.066079974 0.07202822, -0.13113312 0.062996477 0.072028011, -0.12946823 0.063865364 0.07334584, -0.12849712 0.064220846 0.073840737, -0.12870859 0.065382957 0.073346049, -0.12916049 0.065201104 0.073054358, -0.12877949 0.065950096 0.073054388, -0.12852472 0.066490263 0.073033586, -0.12800787 0.067567647 0.072992459, -0.13095227 0.060935915 0.073284596, -0.13118276 0.059919387 0.073461756, -0.13023654 0.059772849 0.074025244, -0.13194278 0.059947073 0.072801262, -0.12958609 0.061724603 0.073905259, -0.13083072 0.061442673 0.073191866, -0.13258626 0.059877872 0.072027802, -0.1292477 0.062696904 0.073840752, -0.1256402 0.067534387 0.074280724, -0.12528582 0.068624467 0.074211419, -0.12620838 0.068922549 0.073751599, -0.12451965 0.068302184 0.074429512, -0.12800761 0.069126397 0.072028294, -0.12772126 0.068082005 0.073004708, -0.12714191 0.069106966 0.073029637, -0.12855363 0.061125696 0.07436195, -0.12922037 0.059507757 0.0743808, -0.1282126 0.061932087 0.074351877, -0.12857124 0.062193096 0.074220121, -0.12804908 0.062416673 0.07433486, -0.12767778 0.063172698 0.07433486, -0.1282136 0.063022524 0.07420513, -0.11813635 0.079649717 0.074328363, -0.11896271 0.080610752 0.073812351, -0.11958186 0.079598367 0.073841706, -0.11844052 0.079146087 0.074335828, -0.12120342 0.078823388 0.073155329, -0.12139256 0.080175877 0.072028995, -0.12325475 0.077282637 0.072028935, -0.12150331 0.077959836 0.073346764, -0.1204983 0.078204155 0.073841482, -0.12057835 0.079382598 0.073346823, -0.12104775 0.079252541 0.073055014, -0.12058534 0.079954118 0.073055148, -0.1202717 0.080462486 0.073034421, -0.11963725 0.081475079 0.072993129, -0.12089927 0.074969381 0.074383095, -0.12174459 0.073601574 0.074381456, -0.12272456 0.073978782 0.074026123, -0.12330566 0.075214744 0.073285222, -0.12364857 0.074230313 0.073462412, -0.12440063 0.074342996 0.072802037, -0.1218598 0.075845361 0.073906153, -0.12312801 0.075704575 0.073192418, -0.12504803 0.074346244 0.072028771, -0.12141469 0.076773852 0.073841512, -0.11944287 0.078382462 0.074206308, -0.11752114 0.080653548 0.074312687, -0.11728841 0.081176877 0.07428129, -0.11681403 0.082220525 0.07421194, -0.11769742 0.082619995 0.073752373, -0.1160889 0.081814617 0.074430227, -0.11946261 0.083024144 0.072029158, -0.11929503 0.081954122 0.073005661, -0.11860453 0.082907796 0.073030472, -0.1204716 0.075897872 0.074352413, -0.12025507 0.07636106 0.07433559, -0.11980139 0.077070802 0.074335888, -0.12035048 0.076981544 0.074206084, -0.11968459 0.077508628 0.074296579, -0.11877622 0.078893512 0.074296549, -0.10847503 0.092375934 0.074329153, -0.10918854 0.093423307 0.073812976, -0.10991734 0.092486739 0.073842451, -0.1088338 0.091909468 0.074336648, -0.11161543 0.091898173 0.073155895, -0.111652 0.093263239 0.072029576, -0.11382636 0.090596735 0.072029635, -0.11200996 0.091073573 0.07334742, -0.11098406 0.091203958 0.073842436, -0.11093161 0.092383921 0.073347479, -0.11141261 0.09230721 0.073055863, -0.11087476 0.092952669 0.073055908, -0.11050589 0.093422592 0.073035225, -0.10976218 0.094357818 0.072993934, -0.11174479 0.08803457 0.074383929, -0.11273783 0.086769819 0.074382231, -0.11366932 0.087254405 0.074026719, -0.11410841 0.088547558 0.073286057, -0.1145594 0.087607712 0.073463276, -0.11529425 0.0878039 0.072802886, -0.11260101 0.089012474 0.073906839, -0.11387722 0.08901459 0.073193356, -0.11593705 0.087879688 0.072029442, -0.11205475 0.089885175 0.073842287, -0.10991511 0.091262907 0.074206784, -0.10775138 0.093304634 0.074313521, -0.10746139 0.093798518 0.074282303, -0.10687332 0.094782382 0.0742127, -0.1077064 0.095278352 0.073752999, -0.10619816 0.094297886 0.074430972, -0.10941522 0.095877618 0.072029918, -0.10936834 0.094795525 0.073006257, -0.10857551 0.095665753 0.073031113, -0.11121589 0.088909149 0.074353054, -0.11094873 0.089345247 0.074336261, -0.11041841 0.089999527 0.074336365, -0.1109741 0.089972496 0.074206784, -0.11025308 0.090421677 0.074297234, -0.10919547 0.091695994 0.074297309, -0.072781205 0.12261507 0.074299172, -0.073603511 0.12244409 0.074208632, -0.074200362 0.12176165 0.074298874, -0.072369248 0.12269709 0.074338317, -0.073201343 0.12359989 0.07384412, -0.071876571 0.1230188 0.074330688, -0.07088688 0.12365648 0.07431519, -0.072204083 0.12424317 0.07381472, -0.074998602 0.12360516 0.073157698, -0.074582085 0.12490574 0.072031409, -0.077515155 0.12310711 0.072031468, -0.075643241 0.12295705 0.073349312, -0.074631914 0.12274143 0.07384412, -0.074192777 0.12383783 0.073349386, -0.074671999 0.12392426 0.073057532, -0.073951036 0.12435573 0.073057652, -0.073447704 0.1246776 0.07303682, -0.072436929 0.12531471 0.072995618, -0.078458354 0.12126616 0.07328783, -0.079194337 0.1205278 0.073465079, -0.07847099 0.11990044 0.074028656, -0.079823375 0.1209558 0.072804794, -0.076881915 0.12120697 0.073908731, -0.07808584 0.12163046 0.07319513, -0.080404997 0.12123957 0.072031349, -0.076078117 0.12185019 0.073844016, -0.070449963 0.12402683 0.074283943, -0.069569945 0.12476128 0.074214607, -0.070192397 0.12550455 0.073754877, -0.06909278 0.12408102 0.07443276, -0.071607366 0.12663451 0.072031438, -0.071920753 0.12559775 0.073008046, -0.070884869 0.12615746 0.073032975, -0.0763264 0.12015066 0.074365005, -0.077751786 0.11913532 0.074384093, -0.075608686 0.12065184 0.074355036, -0.075773448 0.12106392 0.074223489, -0.075212255 0.12097526 0.074338138, -0.074495882 0.12141785 0.074338287, -0.075029135 0.12157562 0.074208498, -0.057650462 0.13029301 0.074331194, -0.058901772 0.13101873 0.073844597, -0.058175936 0.13002837 0.074338704, -0.060687199 0.13122517 0.073158249, -0.060127705 0.13247094 0.07203187, -0.063243717 0.13101181 0.07203187, -0.061400414 0.13065341 0.073349714, -0.060419545 0.13032565 0.073844463, -0.059860349 0.1313661 0.073349684, -0.060326979 0.1315057 0.073057935, -0.059562236 0.13185379 0.073058054, -0.059026062 0.13211721 0.073037371, -0.057838842 0.13154617 0.073815197, -0.057950318 0.13263717 0.072995901, -0.062480003 0.12780023 0.07438609, -0.063923404 0.12709156 0.074384451, -0.064552501 0.1279324 0.074028954, -0.064387038 0.12928808 0.073288411, -0.065201059 0.1286369 0.073465601, -0.065777972 0.12913248 0.072805166, -0.0628272 0.12905285 0.073909149, -0.063976035 0.12960848 0.073195592, -0.066324443 0.12947965 0.072031692, -0.06195645 0.12960213 0.073844343, -0.059430987 0.12991509 0.074209049, -0.056595474 0.13081574 0.074315667, -0.056119874 0.13113481 0.074284315, -0.055163085 0.1317662 0.074214801, -0.055698618 0.1325745 0.073755249, -0.054765061 0.13103667 0.074433029, -0.056978106 0.13385576 0.072032019, -0.057405502 0.13286057 0.073008388, -0.056313574 0.13330069 0.07303305, -0.061624005 0.12835872 0.074355498, -0.061194107 0.1286357 0.074338749, -0.060432479 0.12899524 0.074338764, -0.0609449 0.12921175 0.074208841, -0.060100332 0.12930375 0.074299276, -0.058594584 0.12999308 0.074299544, -0.097449556 0.10394037 0.074329793, -0.098041371 0.10506099 0.073813856, -0.098870426 0.10421196 0.073842883, -0.097858354 0.10351709 0.074337423, -0.10062368 0.10381722 0.073156789, -0.10050735 0.10517785 0.072030321, -0.10296647 0.10277158 0.072030231, -0.1011081 0.10304189 0.073348209, -0.1000741 0.10305661 0.073842973, -0.099889949 0.10422331 0.073348135, -0.10037649 0.10420108 0.073056459, -0.099769875 0.10478234 0.073056579, -0.099350646 0.10520783 0.073035866, -0.098506689 0.10605407 0.072994411, -0.10118502 0.099992365 0.074384764, -0.1023133 0.098846823 0.074383095, -0.10318482 0.099432707 0.074027494, -0.10347636 0.10076696 0.073286965, -0.10402963 0.099883437 0.073463961, -0.10473776 0.10016063 0.072803482, -0.10192636 0.10106003 0.073907673, -0.10319413 0.10120502 0.073194042, -0.10536832 0.10030788 0.072030187, -0.10128586 0.10186604 0.073842898, -0.099005356 0.1029956 0.074207664, -0.09662661 0.10478216 0.074314281, -0.096283257 0.10524067 0.074282899, -0.095588475 0.10615239 0.074213386, -0.096360907 0.1067386 0.073753729, -0.094971806 0.10559526 0.074431717, -0.097991809 0.10752523 0.072030485, -0.098066494 0.1064449 0.073007047, -0.097181126 0.10722092 0.073031709, -0.10056153 0.10080233 0.074354038, -0.10024714 0.10120565 0.07433714, -0.099646956 0.1017966 0.074337155, -0.1002021 0.10183185 0.074207425, -0.099435538 0.10219759 0.074297994, -0.098241851 0.10334545 0.074298084, -0.085198879 0.11419785 0.074330404, -0.084286794 0.11494195 0.074314773, -0.085661456 0.11537763 0.073814467, -0.086580247 0.11462668 0.073843732, -0.085652307 0.11382273 0.074337721, -0.088366687 0.11443079 0.073157325, -0.088098675 0.11576983 0.072030783, -0.090811819 0.11365399 0.072030738, -0.088934869 0.11371464 0.073348835, -0.087905705 0.1136134 0.073843583, -0.087592021 0.11475205 0.073348671, -0.088077962 0.11478439 0.073057011, -0.087410048 0.11529401 0.073057264, -0.086945891 0.11566997 0.073036462, -0.086012676 0.11641651 0.072995186, -0.089352727 0.11069283 0.074385047, -0.090602234 0.10968083 0.074383497, -0.091402605 0.11036056 0.07402797, -0.091542855 0.11171904 0.073287562, -0.092191517 0.11090297 0.073464572, -0.092864513 0.11125788 0.072804272, -0.089969829 0.11183658 0.07390824, -0.091213569 0.11212277 0.073194608, -0.093474254 0.11147463 0.072030842, -0.089243069 0.11256596 0.073843479, -0.086850688 0.11343321 0.074208096, -0.083894089 0.11535913 0.074283332, -0.08310169 0.11618748 0.074213788, -0.083803698 0.1168564 0.073754385, -0.082551315 0.11556488 0.074432299, -0.085336208 0.11782083 0.072031111, -0.085531428 0.11675549 0.073007643, -0.084564686 0.1174275 0.073032439, -0.088642284 0.1114279 0.074354485, -0.08828494 0.11179352 0.074337691, -0.0876223 0.11231354 0.074337736, -0.088170126 0.11241052 0.074208066, -0.087367266 0.11268824 0.074298471, -0.086052746 0.11369529 0.074298561, -0.13593267 -0.042703509 0.074321665, -0.13633394 -0.04159677 0.074306019, -0.13719901 -0.042750388 0.073805273, -0.13679379 -0.043865681 0.07383474, -0.13572852 -0.043255419 0.074328937, -0.13719878 -0.045616746 0.073148385, -0.13671049 -0.046389401 0.073339753, -0.13627526 -0.045451432 0.07383471, -0.13724646 -0.044779301 0.073339865, -0.13743727 -0.045227408 0.073048025, -0.13769773 -0.044428498 0.073048145, -0.13789952 -0.043866098 0.073027611, -0.13829561 -0.042738795 0.07298626, -0.13399635 -0.047781795 0.074376456, -0.1334537 -0.049295485 0.074374624, -0.13435975 -0.049826473 0.07401906, -0.13568839 -0.049510211 0.073278479, -0.13513231 -0.050392002 0.073455416, -0.13568942 -0.050909877 0.072795153, -0.13527992 -0.047986448 0.073899314, -0.13596067 -0.049065828 0.073185541, -0.13572833 -0.047059655 0.07383462, -0.13575646 -0.044515014 0.074199289, -0.13659804 -0.041088402 0.0742746, -0.1371181 -0.040066808 0.074205175, -0.13798138 -0.040508389 0.073745437, -0.13634874 -0.03975293 0.074423537, -0.13845688 -0.042172581 0.07299874, -0.13877176 -0.041038126 0.073023297, -0.13445552 -0.046868622 0.074345544, -0.13468264 -0.046410322 0.074328922, -0.13495463 -0.045613199 0.074328683, -0.1352272 -0.046098143 0.074199319, -0.13522404 -0.045248747 0.074289545, -0.13574037 -0.043675274 0.074289814, -0.13985884 -0.027215183 0.074322298, -0.14112253 -0.027120084 0.07380648, -0.14084461 -0.02827388 0.073835582, -0.13971785 -0.027786702 0.074329868, -0.14144325 -0.029968441 0.073149443, -0.14104444 -0.030791014 0.073340558, -0.14050679 -0.029907793 0.073835529, -0.14139655 -0.029131025 0.073340788, -0.14163673 -0.029554784 0.073048934, -0.1418058 -0.028731883 0.073048979, -0.14194341 -0.028150529 0.07302855, -0.14221093 -0.026986003 0.072987057, -0.13850319 -0.032478511 0.074377172, -0.13813365 -0.034043431 0.074375629, -0.13909326 -0.034469604 0.074020028, -0.14037803 -0.034006625 0.073279262, -0.13992438 -0.034945041 0.073456429, -0.14053601 -0.035397381 0.072796054, -0.13980168 -0.032538295 0.073899969, -0.14059894 -0.033534676 0.073186465, -0.14014353 -0.031567097 0.073835589, -0.1398866 -0.029035211 0.074200064, -0.14013362 -0.026070505 0.074306943, -0.14033909 -0.025535792 0.074275509, -0.1407415 -0.02446261 0.074206106, -0.14164868 -0.024804741 0.073746338, -0.13994178 -0.024237007 0.074424386, -0.14230764 -0.026405215 0.072999477, -0.14249346 -0.025242656 0.073024333, -0.13885731 -0.031519711 0.074346446, -0.13903159 -0.03103891 0.074329823, -0.13921252 -0.030216336 0.074329704, -0.13953775 -0.030667722 0.074200027, -0.13943949 -0.029823899 0.074290588, -0.13977644 -0.028202564 0.074290618, -0.12302307 -0.071880758 0.074319907, -0.12424731 -0.072208345 0.073803909, -0.12360395 -0.073205471 0.073833153, -0.12270127 -0.07237345 0.074327275, -0.12360936 -0.075002581 0.073146738, -0.12296126 -0.075647414 0.073338017, -0.12274554 -0.074635923 0.073832929, -0.12384186 -0.074196815 0.07333827, -0.12392851 -0.074676096 0.073046505, -0.12435991 -0.073955327 0.073046394, -0.12468161 -0.073452085 0.073025949, -0.12531897 -0.072441101 0.072984569, -0.12000518 -0.076400936 0.074374825, -0.11913951 -0.077756017 0.074373208, -0.11990455 -0.078475118 0.074017346, -0.12127016 -0.078462332 0.073276833, -0.12053201 -0.07919848 0.073453978, -0.12095995 -0.079827189 0.072793446, -0.12121117 -0.076886088 0.073897533, -0.12163457 -0.078089982 0.073184028, -0.12185455 -0.076082289 0.073832862, -0.12244806 -0.073607743 0.074197657, -0.12366073 -0.070890933 0.074304253, -0.12403104 -0.07045421 0.074273124, -0.12476555 -0.069574088 0.074203551, -0.12550864 -0.070196629 0.073743723, -0.12408528 -0.069096684 0.074421719, -0.12560195 -0.071924895 0.072997048, -0.12616144 -0.070888877 0.073021747, -0.12065614 -0.075612843 0.074343935, -0.12097941 -0.075216621 0.074327305, -0.12142206 -0.074499905 0.074327037, -0.12157983 -0.075033396 0.074197479, -0.12176579 -0.074204504 0.074288055, -0.12261927 -0.072785467 0.074288085, -0.1302972 -0.05765456 0.074320629, -0.1308198 -0.056599617 0.074305102, -0.13155049 -0.05784297 0.07380458, -0.1310228 -0.05890581 0.073833801, -0.13003266 -0.058180213 0.074328132, -0.13122937 -0.060691148 0.07314761, -0.13065755 -0.061404526 0.073338978, -0.13032988 -0.060423583 0.073833875, -0.13137011 -0.059864461 0.073338956, -0.1315098 -0.060331047 0.073047355, -0.13185796 -0.059566289 0.07304728, -0.13212138 -0.059030294 0.073026627, -0.13264126 -0.057954311 0.072985262, -0.12780432 -0.062484115 0.074375495, -0.12709582 -0.06392765 0.074373752, -0.12793663 -0.064556658 0.074018106, -0.12929225 -0.064391136 0.073277526, -0.12864114 -0.065205246 0.073454648, -0.12913662 -0.065782249 0.072794184, -0.12905695 -0.062831372 0.073898442, -0.12961265 -0.063980222 0.073184699, -0.12960628 -0.061960518 0.07383357, -0.12991939 -0.05943498 0.074198402, -0.13113901 -0.056124181 0.07427381, -0.13177039 -0.055167228 0.0742044, -0.13257867 -0.055702746 0.073744632, -0.13104077 -0.054769367 0.074422739, -0.13286467 -0.057409644 0.072997682, -0.1333048 -0.056317568 0.073022746, -0.12836301 -0.061628193 0.074344873, -0.12863991 -0.061198294 0.074328005, -0.12899937 -0.060436606 0.074327826, -0.1292159 -0.060949117 0.074198343, -0.12930802 -0.060104549 0.074288636, -0.12999743 -0.058598787 0.074288949, -0.13781488 0.036161959 0.074325889, -0.13756579 0.037312478 0.074310482, -0.1389122 0.036795855 0.073809892, -0.13916242 0.035636038 0.073839262, -0.13793573 0.035585999 0.074333429, -0.14043696 0.034368962 0.073152915, -0.14043464 0.033454567 0.073344186, -0.13956685 0.034017265 0.073839128, -0.14003164 0.035103291 0.073344186, -0.1404317 0.034825325 0.07305257, -0.14022715 0.03564027 0.073052526, -0.14009868 0.03622362 0.073031917, -0.13983458 0.03738898 0.072990566, -0.13887708 0.030831635 0.074380845, -0.13922314 0.02926144 0.074379027, -0.14027262 0.029293805 0.074023396, -0.14122951 0.03026855 0.073282912, -0.14122787 0.029225975 0.073460013, -0.14197513 0.029083937 0.072799638, -0.14007306 0.031341374 0.07390362, -0.14122346 0.030789435 0.073190019, -0.13995951 0.032364577 0.073838875, -0.13862941 0.034534156 0.07420364, -0.13751888 0.037883341 0.074279174, -0.13741593 0.039025038 0.074209645, -0.1383817 0.039110392 0.07374993, -0.13659729 0.038881332 0.074427918, -0.13966957 0.037954211 0.073003232, -0.1393327 0.039082319 0.073027983, -0.13878015 0.031849146 0.074350104, -0.13872845 0.032357991 0.074333191, -0.13853487 0.033177763 0.074333444, -0.13902359 0.032912135 0.074203685, -0.13856913 0.033629745 0.074294165, -0.13816905 0.035236746 0.074294224, -0.14099771 0.020504177 0.074325114, -0.14105323 0.019918293 0.074332692, -0.14227784 0.019830436 0.073838316, -0.14340246 0.018428802 0.073151916, -0.14329785 0.017520636 0.073343381, -0.14249858 0.018176943 0.073838174, -0.14308193 0.019203842 0.073343478, -0.14344841 0.018883049 0.073051848, -0.14333616 0.019715637 0.073051728, -0.14327413 0.020309865 0.07303115, -0.14215896 0.021011323 0.07380899, -0.14314196 0.021497458 0.07298971, -0.14145647 0.015088528 0.074379921, -0.14162454 0.013489366 0.074378222, -0.14267099 0.013403922 0.074022673, -0.14373079 0.014265478 0.073282011, -0.14361259 0.013229668 0.073459096, -0.14433916 0.013004959 0.07279861, -0.14270186 0.015461087 0.073902644, -0.14378339 0.014783829 0.073189169, -0.14270353 0.016490549 0.073838003, -0.14162494 0.01879552 0.074202791, -0.14087898 0.021675378 0.074309506, -0.14089632 0.022247791 0.07427828, -0.14092179 0.023393929 0.074208766, -0.14189105 0.023370653 0.07374908, -0.14009225 0.023342907 0.074426912, -0.14304133 0.022077501 0.073002376, -0.14283295 0.023236364 0.073027082, -0.14147413 0.01611048 0.074349269, -0.14147958 0.016621798 0.074332416, -0.141379 0.017458051 0.074332513, -0.14183503 0.017139435 0.074202836, -0.14146358 0.017903388 0.074293211, -0.14124602 0.019545138 0.074293278, -0.14202607 -0.011384904 0.074323356, -0.14327115 -0.011148959 0.073807321, -0.14312425 -0.012326479 0.073836543, -0.14194994 -0.011968374 0.074330702, -0.14390868 -0.013943404 0.073150091, -0.14360468 -0.014805615 0.073341563, -0.14297152 -0.013987869 0.073836401, -0.14376855 -0.01311639 0.073341548, -0.14405456 -0.013510793 0.073049866, -0.14413068 -0.012674004 0.073049992, -0.14420232 -0.012080967 0.073029332, -0.1443377 -0.010893703 0.072987966, -0.14126806 -0.016766965 0.074378066, -0.14107618 -0.018363416 0.074376397, -0.14207751 -0.01867941 0.074020699, -0.14330244 -0.018075526 0.073280066, -0.14295676 -0.019058824 0.073457323, -0.14361501 -0.019439787 0.072796695, -0.14256521 -0.016680896 0.073900953, -0.14346911 -0.017581969 0.073187329, -0.14279598 -0.015677512 0.073836476, -0.14225742 -0.013190418 0.074200884, -0.14217097 -0.010216653 0.074307635, -0.14231524 -0.0096624494 0.074276425, -0.14259508 -0.0085507929 0.074207105, -0.14353479 -0.0087892115 0.073747359, -0.14177501 -0.0084160268 0.074425295, -0.14436862 -0.010305882 0.073000565, -0.14442337 -0.0091296732 0.073025122, -0.14151277 -0.015774429 0.074347422, -0.14163211 -0.015277207 0.074330591, -0.14171994 -0.014439553 0.074330561, -0.1420936 -0.014851719 0.074200936, -0.14190155 -0.014024228 0.074291274, -0.14205481 -0.012375265 0.074291676, -0.14240724 0.0045883954 0.07432425, -0.14239699 0.0040000677 0.074331671, -0.14360398 0.0037757754 0.073837392, -0.14456448 0.0022569001 0.073150896, -0.14435896 0.0013660789 0.073342539, -0.14363831 0.0021077693 0.073837355, -0.14433272 0.0030629337 0.073342532, -0.14466105 0.0027032197 0.073050745, -0.14464286 0.0035430789 0.073050715, -0.14464775 0.0041405261 0.073030137, -0.14361817 0.0049624741 0.073808156, -0.14464934 0.0053353906 0.072988711, -0.14225668 -0.00084456801 0.074378937, -0.14224482 -0.0024524033 0.074377351, -0.14327517 -0.0026544333 0.074021608, -0.14442468 -0.0019170642 0.073281184, -0.14419131 -0.0029330254 0.073458135, -0.14488816 -0.0032377243 0.072797716, -0.14353612 -0.00061383843 0.073901959, -0.14453505 -0.0014079213 0.07318829, -0.14365311 0.00040909648 0.073837265, -0.14283919 0.0028202534 0.074201889, -0.14242052 0.0057657659 0.074308544, -0.14250177 0.0063326359 0.074277222, -0.14265543 0.007468611 0.07420776, -0.14361596 0.0073369741 0.073748246, -0.14182551 0.0075107217 0.074426159, -0.14461434 0.0059231818 0.073001511, -0.14453696 0.0070978999 0.073026247, -0.14238872 0.00016912818 0.074348256, -0.14245147 0.00067657232 0.074331462, -0.1424451 0.0015188158 0.07433141, -0.14286233 0.0011510551 0.074201591, -0.14257896 0.0019518137 0.074292272, -0.14254668 0.0036075711 0.074292198, 0.065925956 0.1263077 0.074331135, 0.066992387 0.12580872 0.074315414, 0.066788316 0.12723637 0.073815033, 0.065713108 0.12773842 0.073844299, 0.065391392 0.12655365 0.074338436, 0.064761385 0.12926301 0.073158145, 0.066083953 0.12960255 0.072031811, 0.063000664 0.13112894 0.072031885, 0.063869655 0.12946421 0.07334964, 0.064225107 0.12849304 0.073844284, 0.065386966 0.1287044 0.073349297, 0.065205336 0.12915623 0.073057801, 0.065954119 0.12877551 0.07305792, 0.06649445 0.12852064 0.073037207, 0.067571789 0.1280036 0.072995692, 0.060965851 0.1285294 0.074386269, 0.05951196 0.12921616 0.074384719, 0.059777051 0.13023224 0.074029163, 0.060940146 0.13094801 0.07328856, 0.059923425 0.13117853 0.073465735, 0.059951186 0.13193855 0.072805345, 0.061728805 0.12958187 0.073909134, 0.061446831 0.13082641 0.07319577, 0.059881955 0.13258216 0.072031885, 0.062701061 0.12924349 0.073844388, 0.064520434 0.12746403 0.074208856, 0.067538589 0.12563604 0.074283957, 0.068628624 0.12528154 0.074214324, 0.068926752 0.12620419 0.073754907, 0.068306372 0.12451556 0.07443279, 0.06913057 0.12800333 0.072031647, 0.068086162 0.12771699 0.07300818, 0.069111004 0.12713769 0.073032841, 0.061936259 0.12820837 0.074355379, 0.06242086 0.12804496 0.074338689, 0.063176796 0.1276736 0.07433857, 0.063026711 0.12820905 0.074208871, 0.063625053 0.12760636 0.074299321, 0.065102816 0.12685886 0.074299306, 0.028182521 -0.14554605 -0.067071095, 0.025762901 -0.14317855 -0.072032571, 0.02914165 -0.14252934 -0.072032586, 0.041207701 -0.14507976 -0.062008083, 0.037694126 -0.14603204 -0.062008351, 0.038539961 -0.14315149 -0.067072406, 0.031039536 -0.14496258 -0.06707263, 0.034158722 -0.14689925 -0.062008336, 0.030603394 -0.14768085 -0.062008336, 0.032504246 -0.14180031 -0.072032467, 0.035791874 -0.14386302 -0.067072406, 0.035848513 -0.14099199 -0.072032422, 0.044917166 -0.13837031 -0.072032288, 0.043406963 -0.1408014 -0.068750203, 0.041632324 -0.13939387 -0.072032571, 0.048174024 -0.14946064 -0.047008321, 0.044473797 -0.15060306 -0.04700847, 0.046102017 -0.14782763 -0.052849114, 0.047087073 -0.140746 -0.066761822, 0.047969833 -0.14398423 -0.060008183, 0.04517065 -0.14210695 -0.065423667, 0.048176885 -0.13726935 -0.072032124, 0.048150063 -0.14392397 -0.060008109, 0.047059283 -0.14595792 -0.05644837, 0.052080914 -0.1389755 -0.066761538, 0.051409662 -0.13609159 -0.072032258, 0.054504842 -0.13804308 -0.066761687, 0.048943341 -0.14629528 -0.05429101, 0.051845118 -0.14822721 -0.047008306, 0.053256899 -0.14211369 -0.060008019, 0.058295652 -0.14012206 -0.060007885, 0.05713819 -0.14329377 -0.05429101, 0.056411073 -0.13913265 -0.063407823, 0.05413419 -0.14445522 -0.05429104, 0.05633992 -0.14514783 -0.050668538, 0.055484578 -0.14690369 -0.047008157, -0.0049120337 -0.14816797 -0.067071453, -0.0067441165 -0.14532164 -0.072032765, -0.0033055395 -0.14544034 -0.072032779, 0.0078905225 -0.15061185 -0.062008411, 0.0042531192 -0.15075845 -0.06200856, 0.0057186037 -0.1481382 -0.067072749, -0.0019966811 -0.14823502 -0.067072764, 0.00061346591 -0.15081722 -0.062008426, -0.0030267984 -0.15078801 -0.062008545, 0.00013490021 -0.14547786 -0.072032869, 0.0028811842 -0.14822051 -0.067072675, 0.0035752654 -0.14543402 -0.072032869, 0.012999907 -0.14489597 -0.072032824, 0.010986418 -0.14693004 -0.068750739, 0.0095695257 -0.14516282 -0.072032794, 0.013707548 -0.15643293 -0.047008976, 0.0098459125 -0.15672344 -0.047008798, 0.012050807 -0.15437984 -0.052849531, 0.014586717 -0.14769495 -0.066762239, 0.014726952 -0.15104845 -0.0600086, 0.012415439 -0.14859527 -0.065424025, 0.016422838 -0.144548 -0.072032705, 0.014916077 -0.15102994 -0.060008511, 0.013399988 -0.15276998 -0.056448758, 0.019849434 -0.14708015 -0.066762015, 0.01983659 -0.14411917 -0.072032645, 0.022420019 -0.14671037 -0.066762179, 0.015161783 -0.15351832 -0.054291442, 0.017561108 -0.15604749 -0.047008902, 0.020297676 -0.15040135 -0.060008585, 0.025653198 -0.14958093 -0.060008481, 0.023818985 -0.15241536 -0.054291531, 0.02403608 -0.14819685 -0.063408449, 0.020631894 -0.15287915 -0.054291457, 0.022628412 -0.15404549 -0.050668985, 0.021403819 -0.1555669 -0.047008678, 0.088543117 -0.11890402 -0.067069635, 0.085336193 -0.11782107 -0.072031081, 0.088098735 -0.11576995 -0.07203114, 0.10007606 -0.1128327 -0.062006429, 0.097323731 -0.11521506 -0.062006578, 0.096835971 -0.11225283 -0.067070767, 0.090864211 -0.11713901 -0.06707105, 0.094514653 -0.11753047 -0.062006518, 0.09165059 -0.1197772 -0.062006652, 0.090811774 -0.11365417 -0.072030932, 0.094668925 -0.11408627 -0.067070737, 0.093474224 -0.11147475 -0.072030902, 0.10050716 -0.105178 -0.072030544, 0.10020126 -0.10802361 -0.068748593, 0.097991765 -0.10752544 -0.072030529, 0.1082529 -0.11375704 -0.047006562, 0.1054147 -0.11639202 -0.047006518, 0.10567786 -0.11318487 -0.052847236, 0.10349302 -0.10637718 -0.066759869, 0.10569328 -0.10891166 -0.060006201, 0.10235685 -0.10843465 -0.065421894, 0.10296656 -0.10277185 -0.072030246, 0.10582952 -0.10877922 -0.060006157, 0.10572907 -0.111085 -0.056446388, 0.10722417 -0.10261503 -0.066759631, 0.10536814 -0.10030797 -0.072030276, 0.10900345 -0.10072333 -0.066759378, 0.10757293 -0.11057159 -0.054289147, 0.1110252 -0.11105305 -0.04700616, 0.10964496 -0.10493237 -0.060005918, 0.11332068 -0.10095176 -0.06000568, 0.11365378 -0.10431159 -0.054288745, 0.11119357 -0.10087797 -0.063405678, 0.11145122 -0.10666135 -0.054288715, 0.11373906 -0.10632843 -0.050666392, 0.11372997 -0.10828146 -0.04700616, 0.059863746 -0.13562551 -0.067070693, 0.056978121 -0.13385591 -0.072032094, 0.06012775 -0.13247105 -0.072031915, 0.072458655 -0.13227275 -0.062007472, 0.069245055 -0.13398287 -0.062007472, 0.069428667 -0.13098636 -0.067071795, 0.062519342 -0.13442123 -0.067071989, 0.065991223 -0.13561505 -0.062007591, 0.06269896 -0.13716826 -0.0620078, 0.063243657 -0.13101208 -0.0720319, 0.066907972 -0.13229162 -0.067071751, 0.066324353 -0.12947986 -0.07203193, 0.074582189 -0.12490594 -0.072031617, 0.073650688 -0.12761211 -0.068749681, 0.071607426 -0.12663475 -0.072031692, 0.080224827 -0.13499343 -0.047007561, 0.076871574 -0.13693064 -0.047007784, 0.077841595 -0.13386256 -0.05284825, 0.077226236 -0.12673908 -0.066761062, 0.078807458 -0.12969983 -0.060007393, 0.075660795 -0.12849247 -0.065423176, 0.077515289 -0.12310722 -0.072031453, 0.078969732 -0.12960109 -0.060007289, 0.078358784 -0.13182667 -0.056447536, 0.0817011 -0.12390199 -0.066760704, 0.080404952 -0.12123972 -0.072031334, 0.083856583 -0.12245348 -0.066760749, 0.080270723 -0.13173643 -0.054290116, 0.083529428 -0.13297406 -0.047007516, 0.083545521 -0.12669969 -0.06000717, 0.088014975 -0.12363699 -0.060007155, 0.087592006 -0.12698647 -0.054289967, 0.085957453 -0.12309149 -0.06340687, 0.084921837 -0.12878716 -0.054289967, 0.087226465 -0.12897173 -0.050667614, 0.086783201 -0.13087392 -0.047007397, -0.019569308 -0.14415574 -0.07203266, -0.021984771 -0.14569086 -0.068750754, -0.022973046 -0.14365259 -0.07203269, -0.021446377 -0.15556094 -0.047008708, -0.025275916 -0.15498486 -0.047008678, -0.022604853 -0.15319061 -0.052849323, -0.018645078 -0.14723766 -0.066761941, -0.019254327 -0.15053838 -0.060008347, -0.020962119 -0.14763242 -0.06542398, -0.016154736 -0.14457819 -0.072032794, -0.019066006 -0.15056241 -0.060008481, -0.020931154 -0.15192148 -0.056448668, -0.013377503 -0.14780933 -0.066762134, -0.012731045 -0.14491987 -0.072032735, -0.010789007 -0.14802095 -0.066762194, -0.019380048 -0.153043 -0.054291278, -0.01760368 -0.15604267 -0.047008798, -0.0136794 -0.15114707 -0.060008451, -0.0082755685 -0.15153894 -0.06000863, -0.010694429 -0.15389407 -0.054291502, -0.0095441192 -0.14982975 -0.063408524, -0.01390484 -0.15363729 -0.054291368, -0.012217879 -0.15521842 -0.050669119, -0.013750389 -0.15642917 -0.047008738, -0.03775999 -0.14336008 -0.067071095, -0.038912967 -0.14017734 -0.072032362, -0.035587102 -0.14105824 -0.072032511, -0.025822401 -0.1485914 -0.062008351, -0.029401153 -0.1479249 -0.062008306, -0.027389467 -0.14569655 -0.06707269, -0.034932911 -0.14407402 -0.067072496, -0.032962769 -0.14717218 -0.062008306, -0.036505193 -0.1463339 -0.062008202, -0.032241166 -0.1418604 -0.072032467, -0.030173942 -0.14514551 -0.067072541, -0.028877512 -0.1425831 -0.072032645, -0.05115734 -0.13618681 -0.072032079, -0.053853661 -0.13714603 -0.068750218, -0.054363757 -0.13493887 -0.072032154, -0.055524737 -0.14688852 -0.047008187, -0.059129983 -0.14547467 -0.047008127, -0.056126937 -0.14431986 -0.052848831, -0.050941661 -0.13939717 -0.066761672, -0.052270323 -0.14247948 -0.060007915, -0.053288624 -0.1392664 -0.065423489, -0.047922298 -0.1373584 -0.072032258, -0.052091986 -0.14254469 -0.060007989, -0.054212794 -0.14345485 -0.056448042, -0.045933485 -0.14112669 -0.066761851, -0.044660404 -0.13845327 -0.072032303, -0.043457046 -0.14190891 -0.066761971, -0.052950099 -0.14489335 -0.054290995, -0.05188553 -0.14821306 -0.047008514, -0.046970427 -0.1443134 -0.060008109, -0.041789383 -0.14589792 -0.060008198, -0.044671625 -0.14765587 -0.054291025, -0.042645961 -0.14394921 -0.063408077, -0.047744334 -0.14669099 -0.05429104, -0.046451613 -0.14860806 -0.050668761, -0.048214942 -0.14944735 -0.047008321, -0.068714678 -0.13136318 -0.067070276, -0.069130555 -0.12800366 -0.072031707, -0.066084176 -0.12960252 -0.07203193, -0.058240443 -0.13911983 -0.062007949, -0.061581045 -0.13767371 -0.062007681, -0.059123933 -0.13594872 -0.067071974, -0.066117406 -0.1326884 -0.067071825, -0.064885989 -0.13614732 -0.062007725, -0.068153024 -0.13454166 -0.062007472, -0.063000605 -0.13112924 -0.072031915, -0.061716184 -0.13479182 -0.06707187, -0.05988203 -0.13258234 -0.072031975, -0.10518201 -0.10050333 -0.072030187, -0.10802749 -0.1001977 -0.068748042, -0.10752949 -0.09798789 -0.072030067, -0.11375965 -0.10825044 -0.047006175, -0.11639448 -0.10541224 -0.047005981, -0.11318783 -0.1056748 -0.0528467, -0.10638061 -0.10348934 -0.066759631, -0.10891487 -0.10568994 -0.060006171, -0.10843843 -0.10235339 -0.065421507, -0.10277574 -0.10296273 -0.072030291, -0.10878241 -0.10582617 -0.060006097, -0.11108799 -0.10572609 -0.056446105, -0.10261878 -0.10722053 -0.066759869, -0.10031205 -0.10536438 -0.072030514, -0.10072713 -0.10899979 -0.066760048, -0.11057445 -0.10756999 -0.054288894, -0.11105557 -0.11102274 -0.047006115, -0.10493587 -0.10964173 -0.060006067, -0.10095516 -0.11331749 -0.060006276, -0.10431458 -0.1136508 -0.054289192, -0.10088149 -0.11119011 -0.063406438, -0.10666427 -0.11144832 -0.054289043, -0.10633117 -0.11373642 -0.050666779, -0.10828394 -0.11372757 -0.047006413, -0.11890781 -0.088539541 -0.067067876, -0.11782499 -0.085332274 -0.072029278, -0.1157738 -0.088094771 -0.07202968, -0.11283612 -0.10007277 -0.062005684, -0.11521851 -0.097320408 -0.062005535, -0.11225651 -0.096832305 -0.067069814, -0.11714272 -0.090860516 -0.067069516, -0.11753394 -0.094511211 -0.062005341, -0.11978069 -0.091646999 -0.062005132, -0.11365825 -0.090807885 -0.072029635, -0.11408992 -0.094665259 -0.067069858, -0.11147885 -0.093470424 -0.072029769, -0.096223876 -0.11277896 -0.067069396, -0.095881701 -0.10941124 -0.072030708, -0.09326756 -0.11164796 -0.072030917, -0.087737963 -0.12267205 -0.062006921, -0.090673164 -0.12051868 -0.062006786, -0.087894008 -0.11938381 -0.067071125, -0.093986526 -0.11464909 -0.067070723, -0.093555555 -0.11829534 -0.062006682, -0.096383452 -0.11600289 -0.062006518, -0.090600938 -0.11382243 -0.072030962, -0.090163723 -0.11767909 -0.067070946, -0.08788377 -0.11593315 -0.072030991, -0.08017984 -0.12138858 -0.072031438, -0.083022088 -0.12172368 -0.068749443, -0.083028287 -0.11945856 -0.072031289, -0.086818904 -0.13085011 -0.047007367, -0.090019315 -0.12866953 -0.047007114, -0.08683446 -0.12821203 -0.052848101, -0.08068423 -0.12456641 -0.066760644, -0.08266522 -0.12727594 -0.060007155, -0.082943127 -0.12391672 -0.065422639, -0.07728681 -0.12325081 -0.072031632, -0.082505763 -0.12737921 -0.060007155, -0.084775999 -0.12779447 -0.056447327, -0.076186344 -0.12736693 -0.066761047, -0.074350446 -0.12504396 -0.072031632, -0.073946029 -0.12868065 -0.066760913, -0.083864897 -0.12947795 -0.054289982, -0.083565652 -0.13295132 -0.047007605, -0.077906236 -0.13024312 -0.060007364, -0.073207632 -0.13294083 -0.060007542, -0.076408848 -0.13401344 -0.054290265, -0.073609278 -0.13085043 -0.063407317, -0.079189882 -0.13238904 -0.054290101, -0.078355864 -0.13454568 -0.050667971, -0.080261827 -0.13497153 -0.04700768, 0.13562924 0.059859902 0.067066282, 0.13099001 0.069424808 0.067068264, 0.13398634 0.069241673 0.062003791, 0.13227589 0.072455198 0.06200394, 0.13442568 0.062515765 0.067066357, 0.13717166 0.062695444 0.062003389, 0.13561846 0.065987766 0.062003627, 0.13229589 0.066904426 0.06706658, 0.13499592 0.080222309 0.047004282, 0.13504322 0.077495426 0.0506666, 0.13693334 0.076868802 0.047004253, 0.12815569 0.074856907 0.066755891, 0.13223912 0.080572248 0.052842736, 0.12970312 0.078803986 0.060004428, 0.13306217 0.078053653 0.05428943, 0.13297662 0.08352679 0.04700458, 0.12960434 0.078966349 0.060004339, 0.12897778 0.076847106 0.063402325, 0.1292787 0.085241109 0.052843094, 0.13087645 0.086780459 0.0470047, 0.12779346 0.087452143 0.052843243, 0.12733927 0.077585965 0.065422088, 0.12670304 0.083542109 0.060004681, 0.12575842 0.08777076 0.056442991, 0.12364013 0.088011473 0.06000489, 0.12272336 0.084698498 0.065422416, 0.12448865 0.082081765 0.065422371, 0.1220299 0.082571298 0.068748593, 0.14554958 0.028178632 0.067064404, 0.14315519 0.038536131 0.067066506, 0.14603543 0.037690908 0.062002033, 0.14508319 0.041204244 0.062002316, 0.14496726 0.031035811 0.067064732, 0.14768432 0.030599803 0.062001631, 0.14690262 0.03415522 0.062001735, 0.14386743 0.035788387 0.067064866, 0.14946306 0.048171401 0.047002673, 0.1489024 0.045502454 0.050664842, 0.15060554 0.044471055 0.047002286, 0.14160059 0.04446274 0.066754177, 0.14685322 0.049126118 0.052841067, 0.14398737 0.04796657 0.060002774, 0.14709529 0.046487391 0.054287821, 0.14822964 0.051842391 0.047002703, 0.14392729 0.048146784 0.06000258, 0.14284497 0.046220124 0.063400641, 0.14500614 0.054336488 0.052841306, 0.14690623 0.055481791 0.04700309, 0.14405011 0.056822747 0.052841425, 0.141412 0.047304958 0.065420181, 0.14211692 0.053253442 0.060002998, 0.14213683 0.057586342 0.056441456, 0.1401253 0.05829224 0.060003221, 0.13849455 0.055266231 0.065420777, 0.13963316 0.052322477 0.065420523, 0.13734499 0.053346843 0.068746954, 0.086818919 0.13085005 0.047007218, 0.08804442 0.12841374 0.050669521, 0.090019226 0.12866935 0.047007114, 0.082983434 0.12304807 0.066758662, 0.084182963 0.12996921 0.052845657, 0.082665086 0.12727574 0.060006961, 0.086017251 0.12805703 0.054292247, 0.083565757 0.13295111 0.047007337, 0.082505748 0.12737918 0.060007066, 0.082860753 0.12519789 0.063405216, 0.079490215 0.13289118 0.052845716, 0.080261722 0.13497132 0.047007501, 0.077192515 0.13423899 0.05284597, 0.081063822 0.12515268 0.065424711, 0.077906311 0.13024291 0.060007274, 0.075220793 0.13364303 0.056445584, 0.073207602 0.13294086 0.060007468, 0.073819041 0.129558 0.065425053, 0.076544881 0.1279664 0.065424755, 0.074117005 0.12734064 0.068751127, 0.096223712 0.1127789 0.067069262, 0.087893993 0.11938366 0.06707105, 0.090673134 0.12051871 0.062006697, 0.087738097 0.12267187 0.062006861, 0.093986899 0.11464962 0.067069396, 0.096383408 0.11600283 0.062006548, 0.09355548 0.11829522 0.062006637, 0.09016411 0.1176796 0.067069262, 0.11890776 0.088539392 0.067067891, 0.11225654 0.096832067 0.067069724, 0.11521852 0.097320288 0.06200543, 0.11283609 0.10007265 0.062005579, 0.11714324 0.090860933 0.067067966, 0.11978063 0.091646999 0.062005073, 0.11753388 0.094511122 0.062005132, 0.11409052 0.094665647 0.067068279, 0.11375968 0.10825029 0.047005832, 0.11441235 0.10560241 0.050668299, 0.11639442 0.10541213 0.047005832, 0.10828449 0.10149738 0.0667575, 0.11099389 0.10797802 0.052844271, 0.10891479 0.10568982 0.060006052, 0.11235672 0.10570559 0.05429107, 0.11105558 0.11102253 0.0470061, 0.10878241 0.10582599 0.060005844, 0.1086432 0.10362065 0.063403904, 0.1070689 0.11187097 0.052844539, 0.10828395 0.11372736 0.047006339, 0.10512879 0.11369625 0.052844629, 0.10688126 0.10397637 0.065423474, 0.10493568 0.10964146 0.060005993, 0.10307382 0.11355394 0.056444436, 0.10095508 0.11331728 0.060006261, 0.10079847 0.10988337 0.065423861, 0.10310169 0.1077252 0.065423757, 0.10059558 0.10765532 0.068749949, 0.14336373 -0.037756354 -0.06706509, 0.14018103 -0.038908929 -0.072026789, 0.14106217 -0.035583109 -0.072026655, 0.14859483 -0.025818825 -0.062001526, 0.14792837 -0.029397726 -0.062001705, 0.14570023 -0.027385682 -0.067066059, 0.1440777 -0.034929156 -0.067066431, 0.14717561 -0.032959342 -0.062002018, 0.14633715 -0.036501676 -0.062002122, 0.14186424 -0.032237202 -0.072026312, 0.14514895 -0.030170262 -0.067066312, 0.14258704 -0.028873354 -0.072026268, 0.15556355 -0.021449029 0.046998829, 0.15390056 -0.023610353 0.050660878, 0.15498732 -0.025278598 0.046998486, 0.146871 -0.021378934 0.066750512, 0.15362647 -0.019456536 0.052837133, 0.15054168 -0.019257903 0.059998736, 0.15269977 -0.02193886 0.054284006, 0.15604515 -0.017606467 0.046998933, 0.15056562 -0.019069403 0.05999893, 0.14875449 -0.020335585 0.06339702, 0.15422291 -0.01396054 0.052837625, 0.15643167 -0.013752967 0.046999231, 0.15444028 -0.0113056 0.052837744, 0.14793424 -0.018736362 0.065416604, 0.15115021 -0.013682842 0.059999242, 0.1530481 -0.0097878873 0.056437656, 0.15154207 -0.0082788765 0.059999332, 0.14875992 -0.010297626 0.065417215, 0.1485087 -0.013444155 0.065416902, 0.14689167 -0.011528403 0.068743393, 0.1564355 0.013704836 0.047000825, 0.15529492 0.011227697 0.05066289, 0.15672588 0.0098431408 0.047000572, 0.14794514 0.011838704 0.066752195, 0.15410349 0.01521644 0.05283916, 0.15105174 0.014723629 0.060000747, 0.15375237 0.012590021 0.054285988, 0.15604991 0.017558247 0.047000974, 0.1510331 0.014912814 0.060000703, 0.14954925 0.013275266 0.063398868, 0.15346208 0.020707339 0.052839577, 0.15556942 0.021400958 0.047001213, 0.15308325 0.023343921 0.052839652, 0.14839363 0.014651805 0.065418407, 0.15040448 0.02029416 0.060001105, 0.15138812 0.02451393 0.056439534, 0.14958423 0.025649667 0.060001433, 0.14732076 0.023062676 0.065418944, 0.14777598 0.019939184 0.065418795, 0.14577317 0.021447003 0.06874527, 0.14817157 -0.0049157441 0.067062512, 0.1481418 0.0057149231 0.067064732, 0.15076178 0.0042496324 0.0620002, 0.15061525 0.0078870058 0.062000468, 0.14823943 -0.0020006895 0.067062885, 0.15079136 -0.0030302405 0.061999768, 0.15082054 0.00060987473 0.061999992, 0.14822501 0.0028773248 0.067063019, 0.14689106 -0.055527449 0.046996772, 0.14478874 -0.057264358 0.050658956, 0.14547715 -0.059132695 0.046996608, 0.13843228 -0.05352509 0.066748723, 0.1454459 -0.053153783 0.052835375, 0.14248273 -0.05227375 0.059997007, 0.14399007 -0.055367887 0.05428195, 0.14821544 -0.051888287 0.046996921, 0.14254795 -0.052095354 0.059997022, 0.14050078 -0.052926928 0.063395232, 0.14725034 -0.047928333 0.052835718, 0.14944987 -0.048217684 0.046997204, 0.14805311 -0.045388579 0.052835718, 0.14005676 -0.051185161 0.06541492, 0.14431658 -0.046974033 0.05999741, 0.14703363 -0.04359898 0.056435615, 0.14590119 -0.04179275 0.059997484, 0.14273946 -0.043141723 0.065415308, 0.14179458 -0.046153456 0.06541504, 0.14064436 -0.043925941 0.068741545, 0.13136688 -0.068711042 -0.067066744, 0.12800747 -0.069126487 -0.072028533, 0.1296065 -0.066080093 -0.072028235, 0.13912322 -0.058236927 -0.062003404, 0.13767703 -0.061577708 -0.062003449, 0.13595244 -0.059120327 -0.067067698, 0.13269211 -0.06611371 -0.067068011, 0.13615078 -0.064882576 -0.062003493, 0.13454512 -0.068149596 -0.062003762, 0.13113303 -0.062996686 -0.072027951, 0.13479552 -0.061712533 -0.067067802, 0.1325862 -0.059877932 -0.072028041, 0.12139258 -0.080175936 -0.072029069, 0.12172754 -0.083018363 -0.068747163, 0.11946249 -0.083024204 -0.072029188, 0.13085271 -0.086816341 -0.047004893, 0.12867205 -0.090016812 -0.047005132, 0.12821487 -0.08683151 -0.052845806, 0.12457012 -0.08068043 -0.06675835, 0.12727916 -0.082661837 -0.060004726, 0.12392046 -0.082939446 -0.065420285, 0.12325473 -0.077282786 -0.07202889, 0.12738246 -0.082502484 -0.060004801, 0.1277976 -0.084772795 -0.056444854, 0.1273707 -0.076182604 -0.066758275, 0.12504795 -0.074346393 -0.072028905, 0.1286843 -0.073942333 -0.066758037, 0.1294809 -0.083861887 -0.054287538, 0.1329539 -0.083563298 -0.047004834, 0.13024628 -0.077903092 -0.060004458, 0.13294414 -0.073204488 -0.060004085, 0.13401626 -0.076405734 -0.054287121, 0.13085388 -0.073605657 -0.063404277, 0.13239202 -0.079186767 -0.054287314, 0.13454828 -0.078353047 -0.050664678, 0.13497414 -0.080259293 -0.047004506, 0.11278263 -0.096220076 -0.06706816, 0.10941502 -0.095877767 -0.072029874, 0.11165196 -0.093263417 -0.072029933, 0.12267542 -0.08773455 -0.062005013, 0.12052205 -0.090669721 -0.062005147, 0.11938755 -0.087890178 -0.067069322, 0.11465281 -0.093982816 -0.067069694, 0.11829868 -0.093552113 -0.062005222, 0.11600624 -0.096379846 -0.06200552, 0.11382622 -0.090596855 -0.07202971, 0.11768275 -0.090159982 -0.067069322, 0.1159371 -0.087879956 -0.072029665, -0.013707533 0.15643275 0.047008768, -0.011230603 0.15529206 0.050670862, -0.0098459274 0.15672323 0.047008678, -0.011842534 0.1479412 0.066759944, -0.015219405 0.15410066 0.052847043, -0.014727041 0.15104824 0.060008511, -0.012593135 0.15374932 0.054293692, -0.017561033 0.15604714 0.0470085, -0.014916047 0.15102974 0.060008422, -0.013278827 0.14954564 0.063406646, -0.02071017 0.1534591 0.052847043, -0.02140376 0.15556669 0.047008693, -0.023346856 0.1530804 0.052846774, -0.014655426 0.14839002 0.065425932, -0.020297647 0.15040103 0.060008317, -0.024517119 0.15138492 0.056446567, -0.025653228 0.14958075 0.060008243, -0.023066342 0.1473172 0.065426007, -0.01994288 0.14777225 0.065425918, -0.021450967 0.14576936 0.068752185, 0.0049119294 0.14816785 0.067071229, -0.0057186484 0.14813796 0.067072675, -0.0042532831 0.15075839 0.062008232, -0.0078905225 0.15061188 0.062008366, 0.0019966811 0.14823574 0.067071259, 0.0030267686 0.15078789 0.062008396, -0.0006134212 0.15081716 0.062008366, -0.0028812736 0.14822108 0.067071229, -0.048174143 0.14946032 0.047008231, -0.045505419 0.14889944 0.050670519, -0.044473782 0.15060279 0.04700835, -0.044466585 0.14159673 0.066759631, -0.049129009 0.14685032 0.052846387, -0.047969863 0.14398402 0.060007885, -0.046490639 0.14709222 0.054293364, -0.051845074 0.14822695 0.047008291, -0.048150241 0.14392382 0.060007885, -0.046223626 0.14284131 0.063406095, -0.054339617 0.14500299 0.052846581, -0.055484593 0.1469034 0.047008112, -0.056825861 0.14404711 0.052846432, -0.047308713 0.14140835 0.065425709, -0.053256884 0.14211348 0.060007885, -0.057589427 0.1421338 0.056445971, -0.058295697 0.14012185 0.060007691, -0.055270001 0.13849083 0.065425694, -0.052326232 0.13962963 0.065425515, -0.053350672 0.13734117 0.068751797, -0.028182551 0.14554584 0.06707108, -0.038539991 0.14315131 0.06707257, -0.037694126 0.14603204 0.062008157, -0.041207746 0.14507964 0.062008053, -0.031039804 0.14496332 0.067071065, -0.030603439 0.14768088 0.062008351, -0.034158647 0.14689919 0.062008128, -0.035792246 0.14386368 0.067070842, 0.021446228 0.15556076 0.047008663, 0.023607269 0.15389767 0.050670996, 0.025275826 0.15498462 0.047008693, 0.021375224 0.14686725 0.066759989, 0.019453526 0.15362352 0.052846983, 0.019254372 0.15053812 0.060008407, 0.021935686 0.15269664 0.054293633, 0.01760371 0.15604234 0.047008708, 0.019066006 0.15056211 0.060008407, 0.020332009 0.1487509 0.063406423, 0.013957471 0.15421996 0.052846864, 0.013750196 0.15642899 0.047008678, 0.011302784 0.15443736 0.052846849, 0.018732712 0.14793059 0.065425977, 0.013679355 0.15114683 0.060008451, 0.0097846836 0.15304497 0.056446701, 0.0082755536 0.15153864 0.060008481, 0.010294005 0.14875627 0.065426052, 0.013440385 0.148505 0.065425962, 0.011524469 0.14688772 0.068752319, 0.037759975 0.14335981 0.067071006, 0.027389333 0.14569628 0.067072526, 0.029401004 0.1479249 0.062008277, 0.025822341 0.14859134 0.062008262, 0.03493306 0.14407462 0.067070857, 0.036505088 0.14633381 0.062008098, 0.032962754 0.14717215 0.062008172, 0.030174196 0.14514604 0.067070946, -0.14689101 0.055521935 0.047003135, -0.1447887 0.057258636 0.050665483, -0.14547716 0.059127271 0.047003284, -0.13843226 0.053517312 0.066754729, -0.14544605 0.053147972 0.052841514, -0.14248271 0.052266955 0.060002789, -0.14399014 0.055361569 0.054288447, -0.14821546 0.051882863 0.047002807, -0.14254794 0.05208841 0.060002819, -0.14050072 0.052919567 0.063401163, -0.1472505 0.047922432 0.052840963, -0.14944987 0.048212171 0.047002643, -0.14805317 0.045382649 0.052840948, -0.14005674 0.05117774 0.065420419, -0.14431657 0.046967208 0.060002759, -0.14703347 0.043592513 0.056440577, -0.14590132 0.041786045 0.060002312, -0.14273976 0.043134451 0.065420195, -0.14179453 0.046145976 0.065420389, -0.14064434 0.043918014 0.068746522, -0.13136676 0.068710864 0.067066699, -0.13595246 0.059120148 0.067067668, -0.1376771 0.061577588 0.062003449, -0.13912319 0.058236927 0.06200327, -0.13269298 0.066113949 0.06706652, -0.13454515 0.068149596 0.062003732, -0.13615078 0.064882457 0.062003464, -0.13479619 0.061712652 0.067066401, -0.1308527 0.086816221 0.047004789, -0.12841669 0.088041544 0.050667331, -0.12867212 0.090016663 0.047004923, -0.12305185 0.082979441 0.066756442, -0.12997213 0.084179997 0.052843139, -0.12727924 0.082661748 0.060004592, -0.12806018 0.086014152 0.054289922, -0.13295397 0.083563119 0.047004774, -0.12738255 0.082502276 0.060004458, -0.12520154 0.082857043 0.063402668, -0.13289419 0.079487175 0.052842945, -0.13497408 0.080259025 0.047004417, -0.13424192 0.077189565 0.052842602, -0.12515628 0.081060082 0.065422222, -0.13024645 0.077902913 0.060004458, -0.13364619 0.075217545 0.056442305, -0.13294421 0.073204339 0.060003966, -0.12956165 0.073815376 0.065421864, -0.12797011 0.076541066 0.065422013, -0.12734464 0.074113131 0.06874828, -0.11278272 0.096219927 0.067068264, -0.11938755 0.087890059 0.067069322, -0.12052207 0.090669632 0.062005028, -0.12267555 0.087734431 0.062004864, -0.11465336 0.093983084 0.067068338, -0.11600626 0.096379846 0.062005326, -0.11829862 0.093551964 0.062005058, -0.11768341 0.090160251 0.067068011, -0.080224842 0.13499323 0.047007531, -0.077498421 0.13504028 0.050669715, -0.076871455 0.13693041 0.04700768, -0.074860781 0.12815195 0.066759005, -0.080575168 0.13223615 0.052845731, -0.078807533 0.1296998 0.060007378, -0.078056693 0.133059 0.054292604, -0.083529472 0.13297394 0.047007307, -0.078969836 0.12960097 0.060007259, -0.076850697 0.12897414 0.063405216, -0.08524397 0.12927574 0.052845642, -0.086783186 0.13087365 0.047007322, -0.087455362 0.12779051 0.052845508, -0.077589676 0.12733561 0.06542474, -0.083545685 0.12669957 0.06000711, -0.087774009 0.12575519 0.056445122, -0.088014886 0.12363669 0.060006708, -0.084702104 0.12271965 0.065424651, -0.082085535 0.12448502 0.065424606, -0.082575306 0.12202585 0.068750918, -0.059863746 0.13562545 0.067070514, -0.069428667 0.13098609 0.067071766, -0.069245085 0.13398287 0.062007323, -0.07245858 0.13227266 0.062007308, -0.062519759 0.13442168 0.067070261, -0.062698871 0.13716808 0.062007621, -0.065991342 0.13561502 0.062007412, -0.066908389 0.13229218 0.06707032, -0.10825287 0.11375687 0.047006413, -0.10560529 0.11440948 0.050668806, -0.10541494 0.11639184 0.047006354, -0.10150115 0.10828048 0.066757858, -0.10798098 0.11099091 0.052844569, -0.10569331 0.10891151 0.060005903, -0.10570873 0.11235365 0.054291546, -0.11102535 0.11105281 0.04700622, -0.10582963 0.10877904 0.060006037, -0.10362415 0.10863951 0.063404366, -0.11187398 0.10706595 0.052844316, -0.11373007 0.10828128 0.047006115, -0.11369935 0.10512605 0.052844197, -0.10397995 0.10687768 0.065423712, -0.1096451 0.10493231 0.060005918, -0.11355725 0.10307071 0.056443781, -0.11332084 0.10095167 0.060005635, -0.10988703 0.10079485 0.065423429, -0.10772887 0.10309803 0.065423489, -0.10765928 0.10059175 0.068749845, -0.088543206 0.11890393 0.06706959, -0.09683603 0.11225262 0.067070737, -0.097323745 0.11521497 0.062006429, -0.10007605 0.11283261 0.06200625, -0.090864733 0.11713946 0.067069322, -0.091650546 0.11977714 0.062006623, -0.094514623 0.11753035 0.062006533, -0.094669342 0.11408657 0.067069232, -0.13837412 -0.044913322 -0.072027072, -0.14080502 -0.043403327 -0.068744957, -0.13939771 -0.041628391 -0.072026879, -0.14946315 -0.04817155 -0.047002792, -0.1506056 -0.044471234 -0.047002465, -0.14783067 -0.046099156 -0.052843317, -0.1407495 -0.047083437 -0.066756621, -0.14398742 -0.047966748 -0.060002714, -0.1421105 -0.045167148 -0.065418229, -0.13727324 -0.04817304 -0.07202737, -0.14392728 -0.048146874 -0.060002774, -0.1459612 -0.047056049 -0.056442648, -0.13897923 -0.052077383 -0.06675671, -0.13609557 -0.051405758 -0.072027296, -0.13804677 -0.054501235 -0.066756964, -0.14629839 -0.04894051 -0.054285616, -0.14822972 -0.051842541 -0.047002986, -0.1421171 -0.053253591 -0.060002953, -0.14012544 -0.058292568 -0.06000334, -0.14329655 -0.057135224 -0.054286271, -0.13913618 -0.05640766 -0.063403293, -0.14445819 -0.05413121 -0.054285839, -0.14515065 -0.056337297 -0.050663501, -0.14690611 -0.05548206 -0.047003254, -0.14554982 -0.028178841 -0.067064479, -0.14318255 -0.025758982 -0.072026104, -0.14253333 -0.02913785 -0.072026268, -0.14508332 -0.041204304 -0.06200242, -0.14603546 -0.037690789 -0.062002197, -0.14315522 -0.038536251 -0.06706658, -0.14496629 -0.031035841 -0.067066163, -0.14690273 -0.034155339 -0.062001824, -0.14768426 -0.030599922 -0.062001705, -0.14180425 -0.032500386 -0.072026387, -0.14386675 -0.035788387 -0.067066371, -0.14099588 -0.035844684 -0.072026551, -0.12490976 -0.074578255 -0.072028697, -0.12761596 -0.073646992 -0.068746641, -0.12663864 -0.071603537 -0.072028548, -0.13499594 -0.080222428 -0.047004536, -0.13693316 -0.076869071 -0.047004372, -0.13386542 -0.077838689 -0.05284524, -0.12674284 -0.077222556 -0.066758126, -0.12970304 -0.078804225 -0.060004652, -0.12849617 -0.075657189 -0.065419987, -0.12311131 -0.077511281 -0.072028935, -0.12960444 -0.078966409 -0.060004428, -0.13182996 -0.078355551 -0.056444407, -0.12390557 -0.081697285 -0.066758499, -0.12124369 -0.080400914 -0.072029248, -0.12245713 -0.083852977 -0.066758484, -0.13173936 -0.080267727 -0.054287374, -0.1329767 -0.08352679 -0.047004849, -0.12670305 -0.083542258 -0.060004577, -0.12364016 -0.088011712 -0.060004979, -0.12698956 -0.087589085 -0.054287896, -0.1230949 -0.08595407 -0.063404739, -0.12879032 -0.084918916 -0.054287717, -0.12897459 -0.087223738 -0.050665081, -0.13087639 -0.086780638 -0.047004938, -0.13562931 -0.059860051 -0.067066401, -0.13385984 -0.056974202 -0.072027788, -0.13247509 -0.060123891 -0.072027832, -0.13227606 -0.072455138 -0.062003851, -0.13398641 -0.069241583 -0.062003836, -0.13098992 -0.069425046 -0.067068428, -0.13442492 -0.062515736 -0.067067891, -0.13561854 -0.065987736 -0.062003732, -0.13717164 -0.062695473 -0.062003508, -0.13101603 -0.063239872 -0.072028175, -0.13229528 -0.066904336 -0.06706816, -0.12948376 -0.066320509 -0.072028205, -0.14336357 0.037763715 -0.067060873, -0.14018105 0.038916886 -0.072022438, -0.14106216 0.035590947 -0.072022706, -0.14859481 0.025825709 -0.061998725, -0.14792827 0.029404461 -0.061998412, -0.14570014 0.027393043 -0.067062885, -0.14407796 0.034936756 -0.067062482, -0.14717571 0.032966107 -0.061998263, -0.14633724 0.03650856 -0.061998099, -0.14186428 0.032245189 -0.072022751, -0.14514907 0.030177593 -0.067062691, -0.1425871 0.028881311 -0.0720229, -0.1441597 0.019573212 -0.072023481, -0.14569463 0.021988362 -0.068741351, -0.14365661 0.022976965 -0.072023377, -0.15556344 0.021448761 -0.046998963, -0.15498734 0.02527827 -0.046998665, -0.15319377 0.022607714 -0.052839607, -0.14724137 0.018648565 -0.066752747, -0.15054169 0.019257784 -0.059998974, -0.14763618 0.020965725 -0.065414518, -0.14458214 0.01615873 -0.072023734, -0.15056559 0.019069165 -0.059999034, -0.15192461 0.020934194 -0.056438982, -0.14781308 0.013381094 -0.066753238, -0.14492375 0.012735099 -0.072023764, -0.14802462 0.010792613 -0.066753283, -0.15304598 0.019382954 -0.054281607, -0.15604508 0.017606139 -0.046999097, -0.15115017 0.013682693 -0.059999391, -0.15154211 0.0082787275 -0.059999585, -0.1538972 0.010697424 -0.054282248, -0.14983328 0.0095478296 -0.063399583, -0.15364024 0.01390776 -0.054282054, -0.15522112 0.012220591 -0.050659716, -0.15643179 0.013752759 -0.046999291, -0.1448999 -0.012995958 -0.072025433, -0.14693382 -0.010982841 -0.06874308, -0.14516683 -0.0095656812 -0.072025016, -0.15643542 -0.013705045 -0.047000855, -0.15672581 -0.0098433793 -0.047000676, -0.15438287 -0.012047976 -0.052841514, -0.14769873 -0.014583021 -0.066754699, -0.15105172 -0.014723778 -0.060000896, -0.14859904 -0.012411982 -0.065416425, -0.1445519 -0.016418904 -0.072025388, -0.15103315 -0.014912784 -0.060001016, -0.15277314 -0.013396919 -0.056440771, -0.14708376 -0.019845933 -0.066755131, -0.14412321 -0.01983273 -0.072025657, -0.14671411 -0.022416413 -0.066755012, -0.15352122 -0.015158802 -0.054283664, -0.15604983 -0.017558545 -0.047001004, -0.15040463 -0.020294368 -0.060001194, -0.14958414 -0.025650024 -0.060001448, -0.15241835 -0.023816139 -0.054284245, -0.14820042 -0.024032593 -0.063401327, -0.15288225 -0.020629078 -0.054283932, -0.15404819 -0.022625715 -0.050661564, -0.15556958 -0.021401107 -0.047001243, -0.14817162 0.0049156547 -0.067062676, -0.14532548 0.0067479908 -0.072024032, -0.14544429 0.0033094883 -0.072024375, -0.15061532 -0.0078870356 -0.062000528, -0.15076178 -0.0042499006 -0.062000364, -0.14814195 -0.0057150126 -0.067064703, -0.14823873 0.0020003617 -0.067064241, -0.15082063 -0.00060981512 -0.062000141, -0.15079147 0.0030302405 -0.061999857, -0.14548177 -0.00013107061 -0.072024569, -0.14822425 -0.0028775036 -0.067064643, -0.14543793 -0.0035713017 -0.072024956, 0.068714797 0.131363 0.06707032, 0.059124097 0.13594857 0.067072019, 0.061581045 0.13767362 0.062007576, 0.058240458 0.13911963 0.06200783, 0.066117749 0.132689 0.067070425, 0.068152905 0.1345416 0.062007457, 0.064885899 0.13614726 0.062007606, 0.061716512 0.13479239 0.067070588, 0.028727561 -0.14180183 -0.073058516, 0.0281775 -0.14199528 -0.072975934, 0.029126793 -0.14139247 -0.07335031, 0.028269604 -0.14084041 -0.073845133, 0.029903352 -0.1405026 -0.073845118, 0.030663505 -0.13953361 -0.074209601, 0.031562924 -0.14013919 -0.073845118, 0.029819727 -0.13943541 -0.074300006, 0.030212089 -0.1392085 -0.07433933, 0.031034648 -0.13902733 -0.074339181, 0.031482771 -0.13877881 -0.074375302, 0.033952117 -0.13789877 -0.07443431, 0.032470733 -0.13966271 -0.073985204, 0.031513557 -0.13924825 -0.074242532, 0.029550701 -0.14163265 -0.07305868, 0.029964283 -0.1414392 -0.073159009, 0.030786842 -0.14104033 -0.073350117, 0.025964022 -0.13986927 -0.074386239, 0.024292886 -0.14017403 -0.074385002, 0.025651738 -0.14063832 -0.074174121, 0.024609759 -0.14117315 -0.074026868, 0.024990618 -0.14204705 -0.073457494, 0.026169345 -0.14036402 -0.074237898, 0.027182549 -0.14125696 -0.073724911, 0.027072951 -0.14237002 -0.072804704, 0.025366962 -0.14268762 -0.072800547, 0.029030994 -0.13988236 -0.074209616, 0.034265816 -0.13867006 -0.074217543, 0.033441812 -0.14042524 -0.073357776, 0.033867627 -0.14013869 -0.07349965, 0.034710333 -0.1395438 -0.073758021, 0.035244435 -0.14034817 -0.073035374, 0.033640787 -0.14077884 -0.072997972, 0.034175903 -0.14063734 -0.073010534, 0.027246222 -0.13993332 -0.074308053, 0.02778244 -0.13971376 -0.074339345, 0.028198361 -0.13977236 -0.074299991, 0.044424266 -0.1376937 -0.073058292, 0.043899313 -0.13794756 -0.072975531, 0.044775024 -0.13724229 -0.073349938, 0.043861508 -0.13678974 -0.073844969, 0.04544732 -0.13627115 -0.073844939, 0.046093956 -0.13522306 -0.074209332, 0.045244545 -0.13521987 -0.074299604, 0.047055617 -0.13572425 -0.073844984, 0.045609072 -0.13495043 -0.074339077, 0.04640618 -0.13467845 -0.074339151, 0.046823621 -0.13438129 -0.074375212, 0.049178854 -0.13323036 -0.074434027, 0.047904372 -0.13514894 -0.073984936, 0.046906695 -0.13484427 -0.074242055, 0.045223102 -0.13743332 -0.073058307, 0.04561235 -0.1371949 -0.073158771, 0.046385303 -0.13670647 -0.073349997, 0.041461676 -0.13608277 -0.074385926, 0.03983511 -0.13657263 -0.074384749, 0.04123728 -0.1368818 -0.074173823, 0.040261731 -0.13753 -0.074026585, 0.040738121 -0.13835564 -0.073457405, 0.041721046 -0.13655132 -0.074237749, 0.04282777 -0.13732529 -0.073724836, 0.042843536 -0.13844377 -0.072804496, 0.041183949 -0.13895023 -0.072800547, 0.044510767 -0.13575235 -0.074209273, 0.049576938 -0.1339615 -0.074217305, 0.048954666 -0.13579795 -0.073357657, 0.049345762 -0.13546553 -0.073499426, 0.050116643 -0.13478008 -0.073757604, 0.050737217 -0.1355195 -0.073035061, 0.049191967 -0.13612714 -0.072997898, 0.04970789 -0.13592663 -0.073010311, 0.042742923 -0.13600278 -0.074307978, 0.043251052 -0.13572448 -0.074339166, 0.043671012 -0.13573617 -0.074299842, -0.0035474151 -0.14463899 -0.07305862, -0.0041267723 -0.14470533 -0.072976008, -0.0030671358 -0.1443288 -0.073350325, -0.0037799925 -0.1435999 -0.073845357, -0.002112031 -0.14363417 -0.073845133, -0.0011553764 -0.14285833 -0.074209765, -0.00041331351 -0.14364898 -0.073845327, -0.0019560754 -0.14257488 -0.074300155, -0.0015230775 -0.14244103 -0.074339584, -0.00068080425 -0.1424475 -0.074339539, -0.0001886338 -0.14230487 -0.074375659, 0.0024145544 -0.14199638 -0.074434459, 0.00057786703 -0.14338642 -0.073985562, -0.00026313961 -0.1427694 -0.074242562, -0.0027071983 -0.14465722 -0.073058799, -0.0022610575 -0.14456069 -0.073159128, -0.0013703853 -0.14435479 -0.073350385, -0.0058116764 -0.14213988 -0.074386314, -0.0075086802 -0.14206511 -0.074385211, -0.0062873513 -0.14282009 -0.074174151, -0.0074222088 -0.14310968 -0.074026838, -0.0072453022 -0.14404634 -0.073457628, -0.005721733 -0.14266783 -0.074238151, -0.0049325228 -0.14376378 -0.073725104, -0.0052870214 -0.1448248 -0.072804958, -0.0070209205 -0.14475471 -0.072800651, -0.0028246045 -0.1428352 -0.074209526, 0.0025486946 -0.14281803 -0.074217707, 0.0013548732 -0.14434591 -0.073358163, 0.0018337965 -0.14416122 -0.073499978, 0.0027879179 -0.14376882 -0.073758259, 0.0031294227 -0.14467195 -0.073035523, 0.0014701933 -0.14473501 -0.072998315, 0.0020235479 -0.14471605 -0.073010907, -0.0045758933 -0.14248756 -0.074308217, -0.0040043294 -0.14239284 -0.074339464, -0.0036119074 -0.14254257 -0.07430017, 0.012669861 -0.14412662 -0.073058665, 0.012101501 -0.14425734 -0.072976038, 0.012322292 -0.14312008 -0.073845387, 0.013112321 -0.1437645 -0.0733504, 0.013983622 -0.14296731 -0.073845312, 0.014847457 -0.14208946 -0.074209616, 0.014019951 -0.14189744 -0.07430017, 0.015673295 -0.1427919 -0.073845267, 0.014435306 -0.14171576 -0.074339464, 0.015273005 -0.14162794 -0.074339435, 0.015746072 -0.14143121 -0.074375585, 0.018298373 -0.14083329 -0.074434429, 0.016628936 -0.14242008 -0.073985398, 0.015724108 -0.14190111 -0.074242562, 0.013506591 -0.14405072 -0.07305862, 0.013939232 -0.14390481 -0.073159054, 0.014801234 -0.14360052 -0.073350385, 0.010139987 -0.14189675 -0.074386209, 0.0084452927 -0.14201263 -0.074385151, 0.0097434074 -0.14262587 -0.074174121, 0.008648023 -0.14304069 -0.074026838, 0.0089287609 -0.1439518 -0.073457405, 0.010288447 -0.14241144 -0.074238107, 0.011195302 -0.14341211 -0.07372506, 0.010961935 -0.1445061 -0.072805002, 0.0092309862 -0.14463058 -0.072800681, 0.013186187 -0.14225331 -0.07420978, 0.018523782 -0.14163467 -0.074217603, 0.017508328 -0.14328644 -0.073357984, 0.017963707 -0.14304939 -0.073499754, 0.018867686 -0.14255264 -0.073758274, 0.019308418 -0.14341184 -0.073035568, 0.017666548 -0.14366019 -0.072998255, 0.018214151 -0.14357957 -0.073010862, 0.011406809 -0.142104 -0.074308202, 0.011964247 -0.14194575 -0.074339449, 0.012370959 -0.14205062 -0.074300155, 0.087410092 -0.11529428 -0.073056981, 0.086998329 -0.11570725 -0.072974324, 0.086580351 -0.11462682 -0.073843673, 0.08759205 -0.1147522 -0.073348716, 0.087905735 -0.11361349 -0.073843658, 0.088170066 -0.11241069 -0.074207857, 0.087367326 -0.11268833 -0.074298441, 0.08762233 -0.1123136 -0.074337915, 0.089243069 -0.11256608 -0.073843613, 0.08828488 -0.11179364 -0.07433784, 0.088580742 -0.11137524 -0.074373931, 0.090423703 -0.10951099 -0.074432641, 0.08985433 -0.11174279 -0.073983669, 0.088812143 -0.11178482 -0.074240729, 0.088078052 -0.11478463 -0.073057011, 0.088366777 -0.11443093 -0.073157266, 0.088934898 -0.11371467 -0.073348716, 0.08408162 -0.11475202 -0.07438466, 0.08270818 -0.11575168 -0.074383602, 0.0841337 -0.11558035 -0.074172616, 0.083426982 -0.11651441 -0.074025184, 0.08414951 -0.11713645 -0.073456049, 0.08448115 -0.11510879 -0.074236572, 0.085781425 -0.11547357 -0.073723495, 0.086165771 -0.11652416 -0.072803244, 0.084766373 -0.1175504 -0.072799131, 0.086850494 -0.11343309 -0.074208111, 0.091041103 -0.11006975 -0.074215874, 0.091059998 -0.11200854 -0.073356196, 0.091319308 -0.11156541 -0.07349813, 0.091820419 -0.11066383 -0.073756292, 0.092650577 -0.11115694 -0.073033616, 0.091392651 -0.1122407 -0.072996512, 0.091813385 -0.11188105 -0.073008895, 0.0852644 -0.11425334 -0.074306682, 0.085652351 -0.11382285 -0.074337766, 0.086052582 -0.11369538 -0.074298546, 0.099769637 -0.1047824 -0.073056534, 0.099406719 -0.10523891 -0.072973981, 0.098870367 -0.10421211 -0.073843196, 0.099889919 -0.1042234 -0.073348299, 0.10007413 -0.1030567 -0.073843092, 0.10020204 -0.10183182 -0.074207529, 0.099435598 -0.10219774 -0.074298024, 0.10128574 -0.10186613 -0.073843062, 0.099646956 -0.10179669 -0.074337363, 0.1002471 -0.10120583 -0.074337214, 0.10049431 -0.10075694 -0.07437329, 0.10211697 -0.098698199 -0.074431926, 0.10180096 -0.1009796 -0.073983043, 0.10077004 -0.10113806 -0.074240208, 0.10037652 -0.10420123 -0.073056564, 0.10062373 -0.10381737 -0.073156819, 0.10110815 -0.10304201 -0.073348328, 0.096401557 -0.10461637 -0.074384168, 0.095148712 -0.10576349 -0.07438311, 0.096546113 -0.10543364 -0.074172109, 0.095948383 -0.1064409 -0.074024886, 0.096735835 -0.10697815 -0.073455513, 0.096838564 -0.10492614 -0.074235976, 0.098171428 -0.10514304 -0.073722765, 0.098670855 -0.10614383 -0.072802842, 0.097395316 -0.1073204 -0.072798729, 0.099005327 -0.1029956 -0.074207485, 0.10279267 -0.099184066 -0.074215278, 0.10302886 -0.10110867 -0.073355719, 0.1032369 -0.10063934 -0.073497489, 0.10363403 -0.099687368 -0.073755667, 0.10451406 -0.10008439 -0.073033169, 0.10338543 -0.1013023 -0.072995842, 0.10376318 -0.10089764 -0.073008418, 0.097521231 -0.10398844 -0.07430616, 0.097858474 -0.1035172 -0.074337468, 0.098241866 -0.10334554 -0.074297935, 0.059562221 -0.13185397 -0.073058069, 0.059068903 -0.13216501 -0.072975278, 0.058901757 -0.1310187 -0.073844552, 0.059860274 -0.13136607 -0.073349625, 0.060419321 -0.13032573 -0.073844597, 0.060944736 -0.12921172 -0.074208841, 0.060100302 -0.1293039 -0.074299484, 0.061956361 -0.12960216 -0.073844627, 0.06043236 -0.12899536 -0.074338809, 0.061194003 -0.12863579 -0.074338689, 0.061575636 -0.12829381 -0.07437472, 0.063786998 -0.12688625 -0.07443364, 0.062735543 -0.12893564 -0.073984593, 0.061709985 -0.12874448 -0.074241757, 0.060326874 -0.13150585 -0.073057964, 0.060687065 -0.13122532 -0.073158294, 0.061400309 -0.13065338 -0.073349565, 0.05643779 -0.13058475 -0.074385732, 0.054876387 -0.13125372 -0.0743846, 0.056304336 -0.13140392 -0.07417357, 0.055407509 -0.13215727 -0.074026421, 0.055973321 -0.13292438 -0.073456913, 0.056748092 -0.13102156 -0.074237436, 0.057934403 -0.13166645 -0.073724344, 0.058075488 -0.13277623 -0.072804123, 0.056482837 -0.13346538 -0.072800115, 0.059430853 -0.12991509 -0.07420893, 0.06426467 -0.12756836 -0.074216843, 0.063851714 -0.12946293 -0.073357165, 0.064203382 -0.12908882 -0.073499098, 0.06489253 -0.12832114 -0.073757306, 0.065592036 -0.12898657 -0.073034927, 0.064124465 -0.12976333 -0.072997525, 0.064614683 -0.12950644 -0.073009908, 0.057702005 -0.1303618 -0.074307784, 0.058176011 -0.13002849 -0.074338883, 0.058594465 -0.12999314 -0.074299529, 0.073951006 -0.12435597 -0.073057503, 0.073495701 -0.12472025 -0.072974995, 0.073201284 -0.12359992 -0.073844239, 0.074192658 -0.12383783 -0.073349446, 0.07463178 -0.12274137 -0.073844135, 0.075029209 -0.12157568 -0.074208379, 0.074200377 -0.12176171 -0.074298918, 0.076078221 -0.12185037 -0.07384406, 0.074495807 -0.12141797 -0.074338287, 0.0752123 -0.12097517 -0.074338272, 0.075553298 -0.12059277 -0.074374482, 0.077593252 -0.11894649 -0.074433237, 0.076777592 -0.12110054 -0.073984101, 0.075737208 -0.12102556 -0.074241221, 0.074672043 -0.12392455 -0.073057562, 0.074998677 -0.1236054 -0.073158026, 0.075643286 -0.12295717 -0.073349342, 0.070704341 -0.12344468 -0.074385032, 0.069227517 -0.12428415 -0.074384257, 0.070663363 -0.12427363 -0.074173167, 0.069856524 -0.12512267 -0.074025914, 0.07050468 -0.12582159 -0.073456556, 0.071061358 -0.12384385 -0.074237123, 0.072312623 -0.12435195 -0.073723853, 0.072576955 -0.12543887 -0.072803631, 0.071071491 -0.12630203 -0.072799638, 0.073603511 -0.12244409 -0.074208587, 0.078144118 -0.11957079 -0.0742165, 0.077946097 -0.12149978 -0.073356837, 0.078253329 -0.12108845 -0.073498607, 0.078852221 -0.12024865 -0.073756948, 0.07962203 -0.12083149 -0.073034242, 0.078250751 -0.12176779 -0.072996974, 0.078709021 -0.12145743 -0.0730097, 0.071935669 -0.12308162 -0.074307144, 0.072369158 -0.1226972 -0.074338391, 0.072781116 -0.12261519 -0.074299127, -0.019719958 -0.14333233 -0.073058605, -0.020303071 -0.14333329 -0.072975948, -0.019834772 -0.14227375 -0.073845163, -0.019208059 -0.14307767 -0.0733504, -0.018181011 -0.14249441 -0.073845267, -0.017143622 -0.14183083 -0.074209616, -0.017907545 -0.14145938 -0.074300081, -0.017462239 -0.14137465 -0.074339464, -0.016494855 -0.14269939 -0.073845357, -0.016625956 -0.14147559 -0.074339479, -0.016121045 -0.14138904 -0.07437554, -0.013499752 -0.1413739 -0.074434489, -0.015480414 -0.14254948 -0.073985487, -0.016247019 -0.14184216 -0.074242488, -0.018887132 -0.14344451 -0.073058784, -0.018432871 -0.14339855 -0.073158994, -0.017524734 -0.14329371 -0.07335037, -0.021690175 -0.14059544 -0.074386179, -0.023368239 -0.14033103 -0.074385077, -0.022239029 -0.14121801 -0.074174136, -0.023399219 -0.14137876 -0.074026823, -0.023328304 -0.14232937 -0.073457465, -0.021659896 -0.14113018 -0.074238047, -0.020998314 -0.14230773 -0.07372506, -0.021469429 -0.1433222 -0.072804749, -0.023184687 -0.14305845 -0.072800696, -0.018799543 -0.14162084 -0.074209794, -0.013458312 -0.14220527 -0.074217662, -0.014815792 -0.14358988 -0.073358029, -0.014319107 -0.14346004 -0.073499858, -0.013327152 -0.14317688 -0.073758289, -0.013088733 -0.14411259 -0.073035449, -0.014744654 -0.14398944 -0.072998241, -0.014192775 -0.14403263 -0.073010832, -0.020501241 -0.14107925 -0.074308217, -0.019922495 -0.14104912 -0.074339405, -0.01954931 -0.14124197 -0.074300095, -0.035644546 -0.14022312 -0.073058531, -0.036224112 -0.14015877 -0.07297571, -0.035107359 -0.14002746 -0.073350027, -0.035640165 -0.13915834 -0.073844939, -0.034021452 -0.13956288 -0.073845208, -0.032916233 -0.13901946 -0.074209407, -0.03236863 -0.13995537 -0.073845178, -0.033633769 -0.13856494 -0.074299991, -0.033181906 -0.13853061 -0.07433933, -0.032362223 -0.13872448 -0.074339345, -0.031850621 -0.13869488 -0.07437548, -0.029244125 -0.13897341 -0.074434251, -0.031344041 -0.13991982 -0.073985144, -0.032026544 -0.13913119 -0.074242339, -0.034829557 -0.14042771 -0.07305856, -0.034373045 -0.14043292 -0.073158756, -0.033458903 -0.14043051 -0.073349983, -0.037295967 -0.13728291 -0.074385956, -0.038933828 -0.13683233 -0.074385002, -0.037911147 -0.13784 -0.074173823, -0.039081961 -0.13786998 -0.07402651, -0.039117873 -0.13882247 -0.073457226, -0.03732577 -0.13781759 -0.074237898, -0.036800295 -0.13906166 -0.073724851, -0.037381858 -0.14001712 -0.07280457, -0.039056703 -0.13956305 -0.072800413, -0.034538463 -0.13862529 -0.074209571, -0.02929607 -0.13980427 -0.074217543, -0.030800089 -0.14102817 -0.073357925, -0.030291989 -0.1409547 -0.07349968, -0.029274553 -0.14078444 -0.073758081, -0.029142454 -0.14174083 -0.073035598, -0.030774057 -0.14143318 -0.072998106, -0.030230507 -0.14153796 -0.073010713, -0.036168635 -0.13789678 -0.074307978, -0.035590202 -0.13793159 -0.074339241, -0.035240889 -0.13816497 -0.074299976, -0.051120743 -0.13535058 -0.073058218, -0.051689476 -0.13522175 -0.072975472, -0.050565079 -0.13521621 -0.073350027, -0.050997302 -0.13429284 -0.073844776, -0.049434185 -0.1348761 -0.07384491, -0.048274934 -0.13445979 -0.074209258, -0.048937261 -0.13392773 -0.074299783, -0.048484161 -0.1339443 -0.074339062, -0.047835693 -0.13545117 -0.073844939, -0.047691509 -0.13422877 -0.074339196, -0.047179669 -0.13425663 -0.074375182, -0.044620842 -0.13482532 -0.074434072, -0.046813384 -0.13553065 -0.073984936, -0.04740338 -0.13467047 -0.074242085, -0.050333902 -0.13564515 -0.073058262, -0.049880862 -0.13570136 -0.073158681, -0.048972219 -0.13580132 -0.073350042, -0.052432641 -0.13224384 -0.074385732, -0.054009885 -0.13161269 -0.074384585, -0.053106308 -0.13272861 -0.074173674, -0.054273218 -0.13262719 -0.074026152, -0.054415628 -0.13356978 -0.073456913, -0.052522168 -0.13277197 -0.07423766, -0.052139476 -0.134067 -0.073724389, -0.052824229 -0.13495138 -0.072804287, -0.054437563 -0.13431254 -0.072800204, -0.049842775 -0.13388667 -0.074209273, -0.044765413 -0.13564527 -0.074217275, -0.04639703 -0.13669291 -0.073357522, -0.045883909 -0.13667694 -0.073499411, -0.044853777 -0.13662151 -0.073757857, -0.044829473 -0.13758677 -0.073035195, -0.046416476 -0.13709822 -0.072997838, -0.045888096 -0.13726318 -0.073010415, -0.051381052 -0.13298011 -0.074307665, -0.050810263 -0.13307953 -0.074338987, -0.050489277 -0.13335046 -0.074299842, -0.065954268 -0.12877575 -0.073057637, -0.066505089 -0.12858397 -0.072975144, -0.065386996 -0.12870452 -0.07334958, -0.065713122 -0.12773845 -0.073844373, -0.064225078 -0.12849307 -0.073844373, -0.063026637 -0.12820923 -0.0742089, -0.062701106 -0.12924364 -0.073844507, -0.063624963 -0.12760654 -0.074299306, -0.063176915 -0.1276736 -0.074338645, -0.062420934 -0.12804493 -0.074338615, -0.061915681 -0.12812996 -0.074374765, -0.059436351 -0.12898162 -0.074433669, -0.061694115 -0.12943703 -0.073984519, -0.062184006 -0.12851629 -0.074241802, -0.065205365 -0.12915647 -0.073057711, -0.06476137 -0.12926316 -0.07315816, -0.06386967 -0.12946415 -0.073349535, -0.066910163 -0.12554157 -0.074385375, -0.068406597 -0.12473792 -0.074384138, -0.067633763 -0.12594786 -0.074173346, -0.068781883 -0.12571669 -0.074025869, -0.069028825 -0.12663731 -0.07345663, -0.067058101 -0.12605646 -0.074237123, -0.066822767 -0.12738618 -0.073724315, -0.067602322 -0.12818834 -0.072803929, -0.069133878 -0.12737295 -0.072799891, -0.064520463 -0.12746423 -0.0742089, -0.059671879 -0.12978017 -0.074217007, -0.061410382 -0.13063854 -0.073357284, -0.060898796 -0.13068011 -0.073499188, -0.059868947 -0.13074031 -0.073757455, -0.059952855 -0.13170221 -0.073034897, -0.061475143 -0.1310392 -0.072997585, -0.060968652 -0.13126215 -0.073009968, -0.065947667 -0.12639105 -0.074307367, -0.065391466 -0.12655368 -0.074338466, -0.065102786 -0.12685886 -0.074299321, -0.10478631 -0.099765718 -0.07305631, -0.10524292 -0.099402845 -0.07297352, -0.10421631 -0.098866224 -0.073842809, -0.10422751 -0.099885941 -0.073347911, -0.10306099 -0.10007003 -0.073842779, -0.10183591 -0.10019803 -0.07420738, -0.10220176 -0.099431366 -0.074297771, -0.10180078 -0.099642843 -0.074337065, -0.10187031 -0.1012817 -0.073842958, -0.10121 -0.10024297 -0.074337363, -0.100761 -0.10049012 -0.07437326, -0.098702312 -0.10211274 -0.074432224, -0.10098384 -0.10179678 -0.073983058, -0.10114214 -0.10076588 -0.074240133, -0.10420534 -0.10037243 -0.073056236, -0.1038214 -0.10061985 -0.0731567, -0.10304612 -0.10110417 -0.073347971, -0.10462047 -0.09639743 -0.074383721, -0.10576756 -0.0951446 -0.074382499, -0.10543771 -0.096541941 -0.074171826, -0.10644509 -0.095944315 -0.074024156, -0.10698229 -0.096731722 -0.073454991, -0.10493016 -0.096834511 -0.074235603, -0.10514721 -0.09816739 -0.073722556, -0.10614789 -0.098666877 -0.072802261, -0.1073243 -0.097391337 -0.072798073, -0.10299967 -0.099001288 -0.074207261, -0.099188268 -0.10278869 -0.074215531, -0.10111292 -0.10302475 -0.073355675, -0.10064355 -0.10323301 -0.073497683, -0.09969148 -0.10362992 -0.073756173, -0.1000884 -0.10451034 -0.073033318, -0.10130626 -0.10338154 -0.07299608, -0.10090169 -0.10375929 -0.073008448, -0.10399266 -0.097517073 -0.074305654, -0.10352132 -0.097854346 -0.074336916, -0.10334964 -0.098237634 -0.074297741, -0.11529809 -0.087406009 -0.073055446, -0.11571114 -0.08699435 -0.072972611, -0.11463086 -0.086576223 -0.073842108, -0.11475629 -0.087587982 -0.073347151, -0.11361769 -0.087901652 -0.073842064, -0.11241487 -0.088165969 -0.074206606, -0.11269236 -0.087363183 -0.074297085, -0.11231758 -0.087618202 -0.074336395, -0.11257023 -0.089238912 -0.073842272, -0.11179766 -0.088280797 -0.07433641, -0.11137933 -0.088576645 -0.074372664, -0.10951513 -0.090419412 -0.074431375, -0.11174704 -0.089850157 -0.073982388, -0.11178869 -0.08880806 -0.074239433, -0.11478849 -0.088074207 -0.07305558, -0.11443485 -0.088362873 -0.073156014, -0.11371881 -0.088930815 -0.07334727, -0.11475608 -0.084077537 -0.074382856, -0.1157558 -0.082704067 -0.074381977, -0.1155846 -0.084129632 -0.074170887, -0.11651848 -0.083422899 -0.074023634, -0.11714071 -0.084145367 -0.073454231, -0.11511287 -0.084477127 -0.074234933, -0.11547785 -0.085777283 -0.073721975, -0.11652805 -0.086161852 -0.072801471, -0.11755437 -0.084762454 -0.072797373, -0.11343735 -0.086846441 -0.074206531, -0.11007375 -0.091036916 -0.074214697, -0.11201264 -0.09105587 -0.073355004, -0.11156967 -0.09131524 -0.073496953, -0.11066797 -0.091816545 -0.073755205, -0.1111608 -0.092646748 -0.073032677, -0.11224473 -0.091388822 -0.072995245, -0.11188516 -0.091809511 -0.073007643, -0.11425751 -0.085260421 -0.074305162, -0.11382703 -0.085648298 -0.074336231, -0.11369947 -0.086048454 -0.074296966, -0.092956841 -0.11087072 -0.073056906, -0.093451068 -0.11056128 -0.07297422, -0.092490926 -0.10991323 -0.073843405, -0.092388064 -0.11092749 -0.073348537, -0.09120822 -0.11097991 -0.07384336, -0.089976683 -0.11096999 -0.074207813, -0.090425879 -0.1102491 -0.074298352, -0.089889377 -0.11205071 -0.073843643, -0.090003699 -0.11041436 -0.07433781, -0.089349389 -0.1109446 -0.07433781, -0.088875681 -0.11113989 -0.074373856, -0.086648121 -0.11252186 -0.07443288, -0.088950709 -0.11246336 -0.07398358, -0.089223534 -0.11145663 -0.074240535, -0.092311412 -0.11140862 -0.073056892, -0.091902331 -0.11161143 -0.073157281, -0.091077805 -0.11200583 -0.073348582, -0.093169153 -0.10750502 -0.074384362, -0.094449162 -0.10638857 -0.074383065, -0.093965024 -0.10774016 -0.074172124, -0.095032886 -0.10725906 -0.074024811, -0.09547852 -0.10810164 -0.073455438, -0.093427896 -0.10797399 -0.074236035, -0.093494251 -0.10932291 -0.073723182, -0.094432816 -0.10993132 -0.072802916, -0.09574458 -0.10879561 -0.072798848, -0.091267094 -0.10991108 -0.074208021, -0.087055475 -0.1132479 -0.074216112, -0.088941455 -0.11369807 -0.073356286, -0.088451788 -0.11385232 -0.073498383, -0.087461323 -0.11414018 -0.073756546, -0.087757215 -0.11505941 -0.073033839, -0.08909364 -0.1140742 -0.072996557, -0.088649511 -0.11440426 -0.073009104, -0.092419729 -0.10854745 -0.074306458, -0.09191373 -0.10882968 -0.074337736, -0.091700241 -0.10919142 -0.074298471, -0.079958245 -0.12058154 -0.073057383, -0.080484107 -0.12032932 -0.072974607, -0.079602346 -0.11957777 -0.07384406, -0.079386741 -0.12057424 -0.073348984, -0.078208447 -0.12049428 -0.073844045, -0.076985672 -0.12034628 -0.074208409, -0.077513009 -0.11968026 -0.074298978, -0.076777965 -0.12141064 -0.07384409, -0.07707496 -0.1197972 -0.074338302, -0.076365232 -0.12025094 -0.074338228, -0.075872645 -0.12039202 -0.074374482, -0.073504373 -0.12151584 -0.074433446, -0.075799048 -0.12171555 -0.07398425, -0.076182857 -0.12074563 -0.074241325, -0.079256594 -0.12104377 -0.073057368, -0.0788275 -0.12119931 -0.073157907, -0.077963978 -0.12149894 -0.073349133, -0.080546066 -0.11726075 -0.074384958, -0.081943169 -0.11629456 -0.074383661, -0.081310704 -0.11758345 -0.074172691, -0.082425654 -0.1172249 -0.074025467, -0.082774311 -0.11811218 -0.073456109, -0.080750868 -0.11775565 -0.074236736, -0.080665603 -0.11910343 -0.073723584, -0.081530109 -0.11981329 -0.072803363, -0.082961112 -0.11883152 -0.07279934, -0.078386709 -0.11943859 -0.074208379, -0.073827922 -0.12228292 -0.074216411, -0.075651705 -0.12294134 -0.073356986, -0.075147912 -0.1230399 -0.073498636, -0.074131161 -0.12321511 -0.073756948, -0.074322388 -0.12416163 -0.073034436, -0.075760752 -0.1233322 -0.072997138, -0.075282365 -0.12361056 -0.073009714, -0.079684764 -0.11821252 -0.074306801, -0.079150304 -0.1184364 -0.074338064, -0.078897685 -0.11877203 -0.074298769, 0.13185795 0.059566289 -0.073047385, 0.13216901 0.059072942 -0.072964534, 0.13102274 0.05890587 -0.073833928, 0.13137007 0.059864461 -0.073338911, 0.13032973 0.060423642 -0.073833987, 0.12921581 0.060948938 -0.074198186, 0.12930791 0.060104549 -0.07428886, 0.1289994 0.060436547 -0.074328139, 0.12960617 0.061960489 -0.073833853, 0.12863988 0.061198235 -0.074328199, 0.12829767 0.061579764 -0.074364185, 0.12689048 0.063791275 -0.074422926, 0.12893961 0.062739581 -0.073973835, 0.12874857 0.061714202 -0.07423082, 0.13150984 0.060330868 -0.073047161, 0.13122919 0.060691059 -0.073147774, 0.13065742 0.061404467 -0.073339015, 0.13058886 0.056441933 -0.074375331, 0.13125788 0.054880559 -0.074374095, 0.13140801 0.056308478 -0.074163109, 0.13216151 0.055411637 -0.074015781, 0.13292857 0.055977434 -0.073446348, 0.13102557 0.056752205 -0.07422699, 0.13167065 0.057938546 -0.073713899, 0.13278012 0.058079451 -0.072793394, 0.1334693 0.056486815 -0.07278958, 0.12991923 0.05943498 -0.07419841, 0.12757246 0.064268738 -0.074206054, 0.12946691 0.063855827 -0.073346332, 0.12909284 0.064207345 -0.073488265, 0.12832524 0.064896554 -0.073746458, 0.12899056 0.065596044 -0.073023751, 0.12976742 0.064128458 -0.072986752, 0.12951031 0.064618677 -0.072999015, 0.13036597 0.057706267 -0.07429713, 0.13003255 0.058180153 -0.074328333, 0.12999727 0.058598608 -0.074289039, 0.12436 0.073955059 -0.073046565, 0.12472422 0.073499769 -0.072963849, 0.12384197 0.074196726 -0.07333824, 0.12360395 0.073205411 -0.073833227, 0.12274544 0.074635893 -0.073833182, 0.12157993 0.075033337 -0.074197486, 0.12176587 0.074204504 -0.074288145, 0.12185444 0.0760822 -0.073833153, 0.12142204 0.074499875 -0.074327514, 0.1209794 0.075216472 -0.074327335, 0.1205968 0.075557262 -0.07436344, 0.11895068 0.077597439 -0.074422285, 0.12110467 0.076781809 -0.073972985, 0.12102972 0.07574138 -0.074230313, 0.12392849 0.074675947 -0.073046446, 0.1236092 0.075002491 -0.073146954, 0.12296124 0.075647324 -0.073338047, 0.12344863 0.070708483 -0.074374393, 0.12428841 0.069231749 -0.074373245, 0.1242777 0.070667416 -0.074162334, 0.12512675 0.069860697 -0.074014917, 0.12582576 0.070508808 -0.073445618, 0.12384793 0.071065545 -0.074226201, 0.12435603 0.072316885 -0.073712915, 0.12544292 0.072580874 -0.072792634, 0.12630603 0.071075529 -0.072788745, 0.12244821 0.073607624 -0.07419765, 0.11957496 0.078148186 -0.074205458, 0.12150371 0.077950031 -0.073345572, 0.1210926 0.078257471 -0.073487639, 0.12025265 0.078856498 -0.073745564, 0.12083553 0.079625845 -0.073023185, 0.12177166 0.07825464 -0.072985873, 0.12146139 0.07871297 -0.0729983, 0.12308566 0.071939677 -0.074296296, 0.12270136 0.07237336 -0.074327543, 0.1226193 0.072785288 -0.074288189, 0.14180587 0.028731614 -0.073049128, 0.14199927 0.028181583 -0.072966307, 0.14084463 0.028273761 -0.073835745, 0.14139661 0.029130936 -0.073340818, 0.14050682 0.029907584 -0.073835611, 0.13953772 0.030667633 -0.074200019, 0.13943957 0.029823959 -0.074290514, 0.13921261 0.030216247 -0.074329719, 0.14014341 0.031567007 -0.073835582, 0.13903147 0.031038821 -0.074329749, 0.13878298 0.031486928 -0.074365765, 0.13790295 0.03395614 -0.074424535, 0.13966677 0.032474905 -0.073975503, 0.13925238 0.031517684 -0.074232817, 0.14163652 0.029554665 -0.073048934, 0.14144307 0.029968351 -0.073149279, 0.14104445 0.030790985 -0.073340669, 0.13987336 0.025968224 -0.074376822, 0.14017811 0.024297237 -0.074375868, 0.14064226 0.025655746 -0.074164703, 0.14117718 0.024613738 -0.074017569, 0.14205106 0.024994731 -0.073448107, 0.14036812 0.026173472 -0.07422848, 0.141261 0.027186632 -0.073715493, 0.1423741 0.027076989 -0.072795257, 0.14269155 0.025370926 -0.072791189, 0.13988639 0.02903527 -0.074200004, 0.13867407 0.034269989 -0.074207664, 0.14042926 0.033445954 -0.073348075, 0.14014266 0.03387183 -0.073490068, 0.13954781 0.03471452 -0.073748216, 0.14035214 0.035248339 -0.073025614, 0.14078283 0.033644766 -0.072988346, 0.14064139 0.034179866 -0.073000744, 0.1399374 0.02725029 -0.07429871, 0.13971773 0.027786583 -0.074330062, 0.13977653 0.028202474 -0.074290648, 0.13769764 0.044428289 -0.073048279, 0.13795148 0.043903291 -0.072965473, 0.13724637 0.044779241 -0.073339775, 0.13679382 0.043865651 -0.073834866, 0.13627526 0.045451343 -0.073834792, 0.13522719 0.046098232 -0.074199215, 0.13522398 0.045248717 -0.07428959, 0.13572827 0.047059596 -0.073834866, 0.13495451 0.045613229 -0.074329078, 0.13468255 0.046410292 -0.074328944, 0.13438535 0.046827734 -0.074365124, 0.13323446 0.049183011 -0.074423909, 0.135153 0.047908485 -0.073974788, 0.13484837 0.046910793 -0.074231923, 0.13743739 0.04522711 -0.073048115, 0.13719885 0.045616508 -0.073148385, 0.13671058 0.046389371 -0.07333976, 0.13608676 0.041465759 -0.074375957, 0.13657688 0.039839268 -0.074375063, 0.13688587 0.041241378 -0.074163765, 0.13753405 0.040265858 -0.074016735, 0.13835983 0.040742218 -0.073447198, 0.13655543 0.041725218 -0.07422787, 0.13732922 0.042831928 -0.073714763, 0.13844764 0.042847514 -0.072794303, 0.13895413 0.041187882 -0.072790369, 0.13575649 0.044514954 -0.074199215, 0.13396563 0.04958114 -0.074206904, 0.13580213 0.048958659 -0.073347226, 0.13546954 0.049349785 -0.073489189, 0.13478403 0.050120652 -0.073747337, 0.13552345 0.050741255 -0.07302469, 0.13613106 0.049195915 -0.072987571, 0.13593048 0.049711823 -0.072999924, 0.13600682 0.04274708 -0.07429795, 0.13572858 0.043255329 -0.074329138, 0.13574035 0.043675274 -0.074289799, 0.079958186 0.12058932 -0.073043868, 0.080484033 0.12033725 -0.072961107, 0.079602495 0.11958593 -0.073830634, 0.079386741 0.1205824 -0.073335603, 0.078208253 0.12050256 -0.073830709, 0.076985508 0.12035474 -0.074194938, 0.076777995 0.12141877 -0.073830351, 0.07751286 0.11968854 -0.074285522, 0.077074856 0.11980566 -0.074324906, 0.076365188 0.1202592 -0.074324876, 0.075872719 0.12040019 -0.074360996, 0.073504433 0.12152395 -0.074419752, 0.075799003 0.12172377 -0.073970601, 0.076182753 0.12075388 -0.074227676, 0.079256698 0.12105164 -0.073043928, 0.078827426 0.12120739 -0.073144227, 0.077963933 0.12150723 -0.073335513, 0.080546051 0.11726892 -0.074371666, 0.081943169 0.11630273 -0.074370757, 0.08131066 0.11759168 -0.074159592, 0.082425654 0.1172331 -0.074012429, 0.082774311 0.11812031 -0.073442906, 0.080750778 0.11776394 -0.074223429, 0.080665678 0.11911166 -0.073710352, 0.081530079 0.11982119 -0.072790071, 0.082961038 0.11883935 -0.072786167, 0.07838656 0.1194469 -0.074194953, 0.073827848 0.12229115 -0.074202806, 0.075651571 0.12294957 -0.073343053, 0.075147718 0.12304807 -0.073485047, 0.074131221 0.1232233 -0.073743209, 0.074322298 0.12416953 -0.073020473, 0.075760871 0.1233401 -0.072983265, 0.075282305 0.12361842 -0.072995722, 0.079684749 0.11822072 -0.074293762, 0.079150245 0.11844456 -0.074324951, 0.078897581 0.11878034 -0.074285507, 0.092956856 0.11087859 -0.073044404, 0.093451083 0.11056924 -0.072961658, 0.092387974 0.11093572 -0.073336184, 0.092490926 0.10992134 -0.073831245, 0.0912081 0.11098814 -0.073830992, 0.089976579 0.11097828 -0.074195519, 0.089889362 0.11205891 -0.073830977, 0.090425923 0.11025727 -0.074286073, 0.090003818 0.11042252 -0.074325308, 0.089349434 0.11095276 -0.074325323, 0.088875666 0.11114818 -0.074361503, 0.086648121 0.11253011 -0.074420512, 0.088950574 0.11247173 -0.073971048, 0.089223519 0.11146474 -0.074228287, 0.092311442 0.11141652 -0.073044434, 0.091902256 0.11161953 -0.073144823, 0.0910777 0.11201409 -0.07333605, 0.093169108 0.10751325 -0.074372172, 0.094449282 0.10639668 -0.074371263, 0.093965068 0.10774845 -0.074160159, 0.095032901 0.10726726 -0.074012831, 0.095478535 0.10811001 -0.073443457, 0.093427911 0.10798225 -0.074223965, 0.093494266 0.1093311 -0.073711053, 0.094432831 0.10993928 -0.072790697, 0.095744595 0.10880342 -0.072786555, 0.091267109 0.10991937 -0.074195653, 0.08705543 0.11325625 -0.074203432, 0.08894138 0.11370632 -0.073343635, 0.088451877 0.11386049 -0.073485479, 0.087461308 0.11414847 -0.073743895, 0.087757304 0.11506718 -0.073021144, 0.089093685 0.11408216 -0.072983772, 0.088649407 0.11441219 -0.072996408, 0.092419714 0.10855556 -0.074294209, 0.091913566 0.10883805 -0.074325532, 0.091700196 0.10919967 -0.074286029, 0.11529817 0.087413907 -0.07304582, 0.11571115 0.087002248 -0.072963163, 0.1146308 0.086584449 -0.073832437, 0.11475636 0.087596148 -0.073337466, 0.11361761 0.087909907 -0.073832408, 0.11241475 0.088174075 -0.074196771, 0.1126923 0.087371409 -0.074287295, 0.11257014 0.089247227 -0.073832169, 0.11231762 0.087626427 -0.074326664, 0.11179753 0.088289082 -0.074326515, 0.11137925 0.08858484 -0.07436274, 0.10951503 0.090427786 -0.074421421, 0.11174701 0.089858383 -0.073972508, 0.11178878 0.088816196 -0.074229583, 0.11478844 0.088082105 -0.073045596, 0.11443467 0.0883708 -0.07314612, 0.11371881 0.088938981 -0.073337287, 0.11475609 0.084085792 -0.074373618, 0.1157558 0.082712322 -0.074372575, 0.11558452 0.084137797 -0.074161425, 0.11651841 0.083431274 -0.074014127, 0.11714058 0.084153444 -0.073444694, 0.11511289 0.084485263 -0.074225441, 0.1154777 0.085785568 -0.073712319, 0.11652811 0.08616972 -0.072791919, 0.11755434 0.084770352 -0.072787851, 0.11343731 0.086854696 -0.07419692, 0.1100737 0.091045022 -0.074204564, 0.11201251 0.091064125 -0.073345035, 0.1115696 0.091323435 -0.073486641, 0.11066793 0.091824561 -0.073745072, 0.11116105 0.092654556 -0.073022395, 0.11224464 0.091396749 -0.072985008, 0.1118851 0.091817409 -0.0729976, 0.1142575 0.085268527 -0.074295536, 0.11382703 0.085656554 -0.074326888, 0.11369941 0.086056799 -0.07428737, 0.10478634 0.099773616 -0.073044986, 0.10524288 0.099410772 -0.072962329, 0.10422751 0.099894047 -0.073336646, 0.10421611 0.098874629 -0.073831663, 0.1030609 0.10007828 -0.073831901, 0.10183601 0.10020626 -0.0741961, 0.10220173 0.099439561 -0.074286625, 0.10187027 0.10128993 -0.073831752, 0.1018008 0.099651039 -0.074325874, 0.10120985 0.10025114 -0.074325904, 0.10076098 0.10049835 -0.074362114, 0.098702222 0.10212097 -0.07442084, 0.10098366 0.10180515 -0.073971793, 0.10114203 0.10077423 -0.074228898, 0.10420525 0.10038042 -0.07304503, 0.10382147 0.10062772 -0.073145404, 0.10304612 0.10111228 -0.073336706, 0.10462034 0.096405745 -0.074372843, 0.10576758 0.095152766 -0.0743718, 0.10543773 0.096550196 -0.074160814, 0.10644497 0.09595257 -0.074013412, 0.10698226 0.096739978 -0.073444054, 0.10493016 0.096842617 -0.074224591, 0.10514726 0.098175496 -0.073711514, 0.10614793 0.098674923 -0.072791219, 0.10732433 0.097399324 -0.072787285, 0.10299979 0.099009514 -0.074196219, 0.099188238 0.10279688 -0.074204057, 0.10111275 0.10303301 -0.073344216, 0.10064346 0.10324118 -0.073485985, 0.09969157 0.10363805 -0.073744461, 0.10008834 0.1045182 -0.07302168, 0.10130623 0.10338935 -0.072984427, 0.10090178 0.10376728 -0.072997004, 0.10399254 0.097525328 -0.074294701, 0.10352121 0.097862571 -0.074326098, 0.1033497 0.098245829 -0.074286729, 0.14022715 -0.035640508 -0.073052615, 0.14016278 -0.036220014 -0.072970092, 0.13916241 -0.035636097 -0.073839277, 0.14003152 -0.035103202 -0.073344335, 0.13956703 -0.034017473 -0.073839232, 0.13902359 -0.032912135 -0.074203625, 0.13995947 -0.032364666 -0.073839217, 0.13856895 -0.033629686 -0.07429412, 0.13853475 -0.033177704 -0.074333355, 0.13872857 -0.032358021 -0.0743334, 0.13869902 -0.031846583 -0.074369475, 0.13897756 -0.029239893 -0.074428305, 0.13992395 -0.031339794 -0.073978961, 0.13913523 -0.032022446 -0.074236229, 0.14043169 -0.034825653 -0.07305263, 0.14043695 -0.034369022 -0.073152974, 0.14043458 -0.033454686 -0.073344216, 0.13728692 -0.037291914 -0.074380338, 0.13683635 -0.03892976 -0.074379295, 0.13784418 -0.037907094 -0.074168384, 0.13787401 -0.039077818 -0.074021056, 0.13882662 -0.03911373 -0.073451743, 0.13782178 -0.037321568 -0.074232265, 0.13906589 -0.036796272 -0.073719114, 0.14002113 -0.037377864 -0.072798833, 0.13956693 -0.039052635 -0.072794721, 0.13862951 -0.034534305 -0.07420373, 0.13980854 -0.029291987 -0.074211523, 0.14103225 -0.030795842 -0.073351651, 0.14095894 -0.030287862 -0.073493451, 0.14078848 -0.029270381 -0.073751956, 0.14174482 -0.029138356 -0.073029131, 0.14143717 -0.030770123 -0.072991878, 0.1415419 -0.030226558 -0.073004514, 0.13790098 -0.036164492 -0.074302435, 0.13793573 -0.035586089 -0.074333578, 0.13816907 -0.035236746 -0.07429418, 0.14333625 -0.019715875 -0.07305178, 0.14333719 -0.020299077 -0.072969049, 0.14227772 -0.019830644 -0.073838413, 0.14308195 -0.019203812 -0.07334356, 0.14249852 -0.018177003 -0.073838279, 0.14183488 -0.017139494 -0.074202627, 0.1414635 -0.017903477 -0.074293271, 0.14270365 -0.016490668 -0.07383801, 0.14137895 -0.017458111 -0.074332535, 0.14147969 -0.016621977 -0.074332431, 0.14139298 -0.016116887 -0.074368477, 0.141378 -0.013495535 -0.074427322, 0.14255354 -0.015476257 -0.073978245, 0.14184628 -0.016242921 -0.074235588, 0.14344829 -0.018883228 -0.073051661, 0.14340234 -0.018428922 -0.073152035, 0.14329784 -0.017520756 -0.073343441, 0.14059947 -0.021685958 -0.074379563, 0.14033526 -0.023364156 -0.07437855, 0.14122203 -0.022234976 -0.074167356, 0.14138283 -0.023395061 -0.074020222, 0.14233354 -0.023324192 -0.073450789, 0.14113432 -0.021655768 -0.074231401, 0.14231162 -0.020994246 -0.07371819, 0.14332613 -0.021465451 -0.072797835, 0.14306234 -0.023180574 -0.072794035, 0.1416249 -0.01879555 -0.074202701, 0.14220951 -0.013454169 -0.074210376, 0.143594 -0.014811575 -0.073350787, 0.14346424 -0.014314979 -0.073492616, 0.14318098 -0.013323069 -0.073750958, 0.14411648 -0.013084799 -0.073028192, 0.14399351 -0.014740616 -0.072991133, 0.14403655 -0.014188707 -0.073003516, 0.14108342 -0.020497084 -0.074301526, 0.14105317 -0.019918442 -0.074332684, 0.14124602 -0.019545108 -0.074293345, 0.1441306 0.012673765 -0.073049977, 0.14426127 0.012105465 -0.072967127, 0.14312427 0.01232627 -0.073836774, 0.14376871 0.01311639 -0.073341638, 0.14297152 0.01398778 -0.073836535, 0.14209354 0.0148516 -0.074200973, 0.14279605 0.015677541 -0.073836312, 0.14190155 0.014024049 -0.074291319, 0.14171986 0.014439434 -0.074330807, 0.14163208 0.015277237 -0.074330688, 0.14143519 0.0157502 -0.074366719, 0.14083721 0.018302381 -0.074425414, 0.14242412 0.016633034 -0.073976427, 0.14190523 0.015728176 -0.074233621, 0.14405458 0.013510585 -0.073049903, 0.14390871 0.013943195 -0.073150158, 0.14360453 0.014805466 -0.073341534, 0.14190091 0.010144085 -0.074377581, 0.14201671 0.0084492862 -0.074376643, 0.14263001 0.0097475648 -0.074165672, 0.14304487 0.0086522996 -0.074018374, 0.14395592 0.0089328885 -0.073448986, 0.14241557 0.010292649 -0.07422933, 0.1434163 0.011199534 -0.073716551, 0.14451009 0.010965884 -0.072796121, 0.14463453 0.0092351139 -0.072792232, 0.14225736 0.013190299 -0.074200928, 0.14163886 0.018527925 -0.074208677, 0.14329062 0.0175125 -0.073349029, 0.14305358 0.01796782 -0.073490858, 0.14255665 0.018871933 -0.07374908, 0.14341572 0.019312203 -0.073026434, 0.14366417 0.017670691 -0.0729893, 0.14358351 0.018218189 -0.073001638, 0.14210808 0.011411011 -0.074299768, 0.14194998 0.011968404 -0.074330777, 0.14205475 0.012375176 -0.074291527, 0.14464284 -0.0035433471 -0.073050693, 0.14470923 -0.0041227937 -0.072968066, 0.14360398 -0.0037758052 -0.073837638, 0.1443329 -0.0030631721 -0.073342592, 0.1436383 -0.0021079183 -0.073837444, 0.1428625 -0.0011512041 -0.074201703, 0.14257912 -0.0019519329 -0.074292421, 0.14365311 -0.00040918589 -0.073837385, 0.14244512 -0.001518935 -0.074331507, 0.14245154 -0.00067663193 -0.074331596, 0.14230891 -0.00018459558 -0.074367672, 0.14200053 0.0024186075 -0.074426413, 0.14339048 0.00058200955 -0.07397747, 0.14277348 -0.00025898218 -0.07423456, 0.14466105 -0.0027033091 -0.073050886, 0.14456457 -0.0022570789 -0.073151201, 0.14435895 -0.0013663173 -0.073342457, 0.14214404 -0.005807519 -0.074378565, 0.1420693 -0.0075046122 -0.07437773, 0.14282416 -0.0062832534 -0.074166656, 0.14311372 -0.0074180961 -0.074019164, 0.14405054 -0.0072411597 -0.073449925, 0.14267209 -0.0057175756 -0.074230328, 0.143768 -0.0049285591 -0.073717311, 0.14482875 -0.0052830577 -0.07279706, 0.14475866 -0.007016927 -0.072793201, 0.14283924 -0.0028204024 -0.074201941, 0.14282222 0.0025529861 -0.074209601, 0.14435005 0.0013588667 -0.073349938, 0.1441654 0.001837939 -0.073491693, 0.14377286 0.0027919412 -0.073749915, 0.14467572 0.0031335354 -0.073027372, 0.14473888 0.0014742911 -0.072990134, 0.14472 0.0020273924 -0.073002681, 0.14249165 -0.0045718551 -0.074300572, 0.14239696 -0.0040002167 -0.07433185, 0.14254664 -0.0036076903 -0.074292198, 0.13535438 -0.051116765 -0.073053598, 0.13522567 -0.051685601 -0.072970897, 0.13429686 -0.050993174 -0.073840231, 0.1352203 -0.05056107 -0.07334514, 0.13488017 -0.049429953 -0.073840022, 0.13446407 -0.048270881 -0.074204609, 0.13545528 -0.047831565 -0.073840007, 0.13393198 -0.048933089 -0.074294969, 0.13394861 -0.048480242 -0.074334234, 0.1342328 -0.047687262 -0.074334189, 0.13426073 -0.047175556 -0.074370354, 0.13482931 -0.04461658 -0.074429095, 0.13553475 -0.046809435 -0.073980033, 0.13467453 -0.047399193 -0.074237168, 0.13564906 -0.050330013 -0.073053464, 0.13570535 -0.049876958 -0.073153853, 0.1358054 -0.048968107 -0.07334502, 0.1322479 -0.052428633 -0.074381188, 0.13161686 -0.054005712 -0.074380234, 0.13273281 -0.053102255 -0.074169189, 0.13263118 -0.054269016 -0.074021935, 0.13357386 -0.054411501 -0.073452517, 0.13277604 -0.05251804 -0.074232996, 0.13407107 -0.05213517 -0.073719904, 0.13495515 -0.052820116 -0.072799623, 0.13431653 -0.054433733 -0.072795674, 0.13389075 -0.049838722 -0.074204564, 0.13564926 -0.04476136 -0.074212268, 0.13669699 -0.046392828 -0.073352426, 0.13668092 -0.045879751 -0.073494509, 0.13662569 -0.044849753 -0.073752776, 0.13759074 -0.044825613 -0.073030055, 0.13710216 -0.046412557 -0.072992802, 0.1372671 -0.045884132 -0.073005259, 0.13298427 -0.051377118 -0.074303105, 0.13308358 -0.050806135 -0.074334338, 0.13335449 -0.050485253 -0.074295014, 0.12877959 -0.065950185 -0.073054343, 0.12858792 -0.066501021 -0.072971642, 0.12870857 -0.065382868 -0.073346004, 0.12774265 -0.065709025 -0.073840931, 0.12849727 -0.064221054 -0.073840842, 0.12821351 -0.063022584 -0.074205428, 0.12924771 -0.062697142 -0.073840827, 0.12761056 -0.063620925 -0.07429561, 0.12767766 -0.063172609 -0.074335232, 0.12804908 -0.062416643 -0.074335024, 0.12813404 -0.061911374 -0.074371055, 0.12898563 -0.059432209 -0.07442987, 0.12944114 -0.061690122 -0.073980734, 0.1285203 -0.062180012 -0.074237958, 0.12916043 -0.065201342 -0.073054135, 0.12926714 -0.064757437 -0.073154464, 0.12946838 -0.063865632 -0.073345914, 0.12554574 -0.066905946 -0.074381888, 0.12474205 -0.068402559 -0.074380964, 0.12595206 -0.067629606 -0.074170038, 0.12572068 -0.068777889 -0.074022889, 0.1266413 -0.069024891 -0.073453382, 0.12606061 -0.067054063 -0.074233845, 0.12739034 -0.066818625 -0.073720828, 0.12819225 -0.067598313 -0.072800517, 0.12737681 -0.069130033 -0.072796658, 0.12746833 -0.064516425 -0.074205399, 0.12978414 -0.059667617 -0.074213192, 0.1306427 -0.061406374 -0.073353544, 0.13068424 -0.060894698 -0.073495254, 0.13074438 -0.059864789 -0.073753431, 0.13170618 -0.059948981 -0.073030919, 0.13104317 -0.061471313 -0.072993577, 0.13126615 -0.060964614 -0.073006064, 0.12639524 -0.06594348 -0.07430391, 0.12655784 -0.065387249 -0.074334994, 0.12686303 -0.065098733 -0.074295893, 0.12058535 -0.079954326 -0.073055193, 0.12033316 -0.080480188 -0.072972298, 0.11958182 -0.079598457 -0.073841661, 0.12057827 -0.079382628 -0.073346704, 0.12049821 -0.078204274 -0.073841676, 0.12035049 -0.076981515 -0.074206084, 0.12141469 -0.076773793 -0.073841661, 0.11968438 -0.077508807 -0.07429646, 0.1198013 -0.077070832 -0.074335977, 0.12025496 -0.07636115 -0.074335828, 0.12039603 -0.075868458 -0.074371755, 0.12151991 -0.073500305 -0.074430689, 0.12171951 -0.075794846 -0.073981613, 0.12074979 -0.076178759 -0.074238867, 0.12104766 -0.07925275 -0.073055133, 0.12120344 -0.078823566 -0.073155433, 0.12150317 -0.077959776 -0.07334666, 0.11726478 -0.080541879 -0.074382752, 0.1162986 -0.081939101 -0.074381933, 0.11758757 -0.081306607 -0.074170634, 0.117229 -0.082421571 -0.074023515, 0.11811638 -0.082770139 -0.073454112, 0.11775985 -0.08074674 -0.074234545, 0.11910763 -0.080661654 -0.073721647, 0.11981721 -0.08152625 -0.072801247, 0.11883529 -0.08295691 -0.072797343, 0.11944273 -0.078382641 -0.074206173, 0.12228698 -0.07382372 -0.074213862, 0.12294537 -0.075647473 -0.07335414, 0.12304391 -0.075143725 -0.073496059, 0.12321909 -0.074127138 -0.073754266, 0.12416546 -0.074318409 -0.073031723, 0.1233362 -0.075756907 -0.072994426, 0.1236145 -0.075278521 -0.073007077, 0.1182166 -0.079680532 -0.074304774, 0.11844037 -0.079146028 -0.074335873, 0.1187762 -0.078893512 -0.074296653, 0.11087462 -0.092952758 -0.073055819, 0.11056516 -0.093447 -0.072973162, 0.1109315 -0.092383891 -0.073347524, 0.10991724 -0.092486888 -0.073842481, 0.11098409 -0.091203928 -0.073842332, 0.1109741 -0.089972526 -0.07420671, 0.11025323 -0.090421766 -0.074297324, 0.1120548 -0.089885205 -0.073842362, 0.1104185 -0.089999795 -0.074336633, 0.11094874 -0.089345396 -0.074336588, 0.11114411 -0.088871509 -0.074372694, 0.11252587 -0.086643934 -0.074431449, 0.11246747 -0.08894664 -0.073982313, 0.1114608 -0.089219362 -0.074239478, 0.1114127 -0.092307478 -0.073055729, 0.1116154 -0.091898382 -0.073156208, 0.11200991 -0.091073513 -0.073347539, 0.10750918 -0.093164921 -0.074383587, 0.10639265 -0.094445258 -0.074382558, 0.10774434 -0.093960941 -0.074171349, 0.10726327 -0.095028788 -0.074024126, 0.10810573 -0.095474422 -0.073454872, 0.10797817 -0.093423873 -0.07423538, 0.10932687 -0.093490183 -0.073722288, 0.10993534 -0.094428867 -0.072801903, 0.10879938 -0.095740616 -0.072798058, 0.10991529 -0.091263086 -0.074206784, 0.11325206 -0.087051362 -0.074214682, 0.11370209 -0.088937432 -0.073355034, 0.11385642 -0.088447869 -0.073496744, 0.11414436 -0.087457299 -0.073754966, 0.11506331 -0.087753236 -0.073032349, 0.1140781 -0.089089781 -0.072995067, 0.11440836 -0.088645518 -0.073007628, 0.10855152 -0.09241572 -0.074305534, 0.10883386 -0.091909677 -0.074336573, 0.1091956 -0.091696113 -0.074297488, -0.012669817 0.14413455 -0.073042601, -0.012101501 0.14426523 -0.07295984, -0.012322322 0.14312834 -0.073829159, -0.013112217 0.14377272 -0.073334381, -0.013983801 0.14297554 -0.073829308, -0.014847457 0.14209765 -0.074193627, -0.014020115 0.14190552 -0.074284226, -0.014435425 0.14172408 -0.07432358, -0.015673339 0.14280009 -0.073829472, -0.01527296 0.1416361 -0.074323669, -0.015746132 0.14143947 -0.074359789, -0.018298388 0.14084142 -0.074418694, -0.016628861 0.14242825 -0.073969454, -0.015724152 0.14190933 -0.074226558, -0.013506621 0.14405861 -0.073042601, -0.013939261 0.1439127 -0.073143065, -0.014801338 0.14360869 -0.073334336, -0.010140166 0.1419051 -0.074370414, -0.0084451586 0.14202076 -0.074369192, -0.0097434223 0.14263421 -0.074158221, -0.0086481869 0.14304903 -0.074010879, -0.0089289695 0.14396012 -0.073441595, -0.010288551 0.14241964 -0.074222162, -0.011195347 0.14342031 -0.073708981, -0.010962009 0.14451414 -0.072788686, -0.0092310309 0.14463842 -0.072784558, -0.013186157 0.14226136 -0.074193701, -0.018523917 0.14164296 -0.074201912, -0.017508492 0.14329469 -0.073341966, -0.017963931 0.14305773 -0.073483855, -0.01886785 0.14256087 -0.073742151, -0.019308418 0.14341959 -0.073019356, -0.017666534 0.14366817 -0.072982103, -0.018214166 0.14358744 -0.072994709, -0.011406869 0.14211231 -0.074292377, -0.011964455 0.14195403 -0.074323654, -0.012371063 0.14205882 -0.074284151, 0.0035472363 0.14464685 -0.073042557, 0.0041266382 0.14471313 -0.072959751, 0.0037799627 0.143608 -0.073829234, 0.0030670911 0.14433682 -0.073334202, 0.0021119863 0.14364231 -0.073829353, 0.0011553019 0.1428667 -0.07419382, 0.0019560754 0.14258307 -0.074284345, 0.0015229583 0.14244923 -0.074323595, 0.0004132688 0.14365715 -0.073829323, 0.00068078935 0.14245573 -0.074323595, 0.00018857419 0.14231312 -0.07435967, -0.0024144948 0.1420047 -0.074418694, -0.00057794154 0.14339456 -0.073969468, 0.0002630353 0.14277765 -0.074226469, 0.0027072579 0.14466503 -0.073042542, 0.0022610277 0.14456859 -0.073142871, 0.0013703108 0.14436305 -0.073334321, 0.0058115125 0.14214823 -0.074370369, 0.0075086653 0.14207345 -0.074369222, 0.0062873513 0.1428282 -0.074158221, 0.0074221045 0.14311793 -0.074010909, 0.0072453171 0.14405453 -0.073441401, 0.0057215095 0.14267623 -0.074222326, 0.0049325377 0.14377207 -0.073708996, 0.0052870363 0.1448327 -0.072788611, 0.0070208609 0.14476267 -0.072784483, 0.002824381 0.14284343 -0.074193627, -0.0025488883 0.14282632 -0.074201703, -0.001354903 0.14435396 -0.073341742, -0.0018338859 0.14416933 -0.073483735, -0.002787903 0.14377689 -0.073742136, -0.0031294078 0.14467978 -0.07301943, -0.0014703423 0.14474291 -0.072982013, -0.0020234436 0.14472395 -0.072994709, 0.0045759231 0.14249587 -0.074292317, 0.0040042549 0.14240107 -0.074323669, 0.0036117882 0.1425508 -0.074284226, -0.044424236 0.1377016 -0.07304284, -0.043899313 0.13795561 -0.072960228, -0.044775113 0.13725051 -0.073334739, -0.043861508 0.13679793 -0.073829502, -0.04544729 0.13627931 -0.073829666, -0.046093985 0.13523129 -0.074194238, -0.047055483 0.13573229 -0.073829651, -0.04524456 0.13522825 -0.074284732, -0.045609102 0.13495868 -0.074323937, -0.046406209 0.13468662 -0.074324042, -0.046823576 0.13438955 -0.074360147, -0.049178869 0.13323858 -0.074419186, -0.047904268 0.13515714 -0.073969901, -0.046906695 0.13485241 -0.074226916, -0.045223102 0.13744131 -0.073043078, -0.045612544 0.1372028 -0.073143229, -0.046385318 0.1367147 -0.073334664, -0.041461676 0.13609099 -0.074370563, -0.039835259 0.136581 -0.074369445, -0.041237324 0.13689014 -0.074158564, -0.040261939 0.13753825 -0.074011058, -0.04073818 0.13836384 -0.073441744, -0.041721061 0.13655949 -0.074222475, -0.04282777 0.13733333 -0.073709384, -0.042843685 0.13845167 -0.07278882, -0.041183889 0.13895807 -0.072784781, -0.044510841 0.13576049 -0.074194014, -0.049576879 0.13396978 -0.074202225, -0.048954606 0.13580608 -0.073342338, -0.049345687 0.13547367 -0.073484331, -0.050116554 0.13478824 -0.073742732, -0.050737277 0.13552758 -0.073019862, -0.049192041 0.1361351 -0.072982445, -0.049708039 0.13593453 -0.072995037, -0.042742908 0.13601103 -0.07429269, -0.043251321 0.1357328 -0.074323893, -0.043671057 0.13574451 -0.074284717, -0.028727695 0.14180973 -0.073042646, -0.028177649 0.14200324 -0.072959885, -0.029126897 0.14140067 -0.073334336, -0.028269678 0.14084879 -0.073829412, -0.029903501 0.14051089 -0.073829517, -0.03066358 0.13954198 -0.074193865, -0.029819861 0.13944381 -0.074284405, -0.031562909 0.14014748 -0.073829472, -0.030212283 0.13921681 -0.074323818, -0.031034738 0.13903561 -0.074323833, -0.03148286 0.13878715 -0.074359834, -0.033952117 0.13790712 -0.074418858, -0.032470748 0.139671 -0.073969483, -0.031513661 0.13925648 -0.074226782, -0.029550657 0.14164048 -0.073042735, -0.029964238 0.1414471 -0.07314305, -0.030786812 0.14104849 -0.073334605, -0.025964171 0.13987756 -0.074370414, -0.024292991 0.14018226 -0.074369341, -0.025651664 0.1406464 -0.074158415, -0.024609745 0.14118138 -0.074010983, -0.024990678 0.14205509 -0.073441684, -0.026169375 0.14037231 -0.074222282, -0.027182534 0.14126509 -0.073709115, -0.027073041 0.14237812 -0.072788626, -0.025366962 0.14269549 -0.072784647, -0.029031113 0.13989064 -0.07419385, -0.034265801 0.13867825 -0.074201941, -0.033441931 0.14043343 -0.073342189, -0.033867776 0.140147 -0.073484033, -0.034710318 0.13955188 -0.073742434, -0.035244435 0.14035606 -0.073019624, -0.033640891 0.14078686 -0.072982356, -0.034175947 0.14064521 -0.072994828, -0.027246237 0.13994145 -0.074292421, -0.027782455 0.13972196 -0.074323818, -0.028198436 0.13978058 -0.0742843, 0.019719914 0.14334026 -0.073042646, 0.020302892 0.14334124 -0.072959766, 0.019834772 0.14228189 -0.073829457, 0.01920791 0.14308602 -0.073334336, 0.018181041 0.14250264 -0.073829308, 0.017143548 0.141839 -0.074193776, 0.017907515 0.14146766 -0.074284136, 0.017462194 0.14138302 -0.074323699, 0.016494691 0.14270765 -0.073829308, 0.016625926 0.14148384 -0.07432355, 0.016121 0.14139712 -0.074359715, 0.013499558 0.14138222 -0.074418604, 0.015480369 0.14255765 -0.073969513, 0.016247004 0.14185041 -0.074226543, 0.018887118 0.14345247 -0.073042557, 0.0184329 0.14340636 -0.073143125, 0.017524794 0.1433019 -0.073334336, 0.02169013 0.14060369 -0.074370489, 0.023368165 0.14033937 -0.074369401, 0.022239 0.14122632 -0.074158415, 0.023399174 0.14138699 -0.074010864, 0.02332817 0.14233768 -0.073441535, 0.021659732 0.14113861 -0.074222267, 0.020998478 0.14231583 -0.073709011, 0.021469429 0.1433301 -0.072788656, 0.023184538 0.14306629 -0.072784632, 0.018799677 0.14162895 -0.074193761, 0.013458237 0.14221358 -0.074201792, 0.014815703 0.14359802 -0.073341921, 0.014319092 0.14346823 -0.073483735, 0.013327181 0.14318514 -0.073742211, 0.013088793 0.1441204 -0.073019385, 0.014744565 0.14399734 -0.072982118, 0.014192745 0.1440405 -0.072994769, 0.020501122 0.14108753 -0.074292421, 0.019922495 0.14105737 -0.074323565, 0.01954931 0.14125007 -0.074284315, 0.035644561 0.14023101 -0.07304284, 0.036224037 0.14016673 -0.072960123, 0.035107315 0.14003563 -0.073334455, 0.03564015 0.13916656 -0.073829442, 0.034021407 0.13957098 -0.073829338, 0.032916158 0.13902771 -0.07419385, 0.03236866 0.13996363 -0.073829398, 0.033633709 0.13857317 -0.074284419, 0.033181846 0.1385389 -0.074323818, 0.032362178 0.13873273 -0.074323639, 0.031850591 0.13870317 -0.074359849, 0.029244065 0.13898179 -0.074418843, 0.031343922 0.13992819 -0.073969573, 0.032026634 0.13913938 -0.074226826, 0.034829482 0.14043567 -0.073042721, 0.03437303 0.14044091 -0.07314311, 0.033458859 0.14043862 -0.073334411, 0.037295893 0.13729113 -0.074370444, 0.038933828 0.13684058 -0.074369416, 0.037911072 0.13784832 -0.07415846, 0.039081946 0.13787806 -0.074011087, 0.039117798 0.13883075 -0.073441893, 0.03732568 0.13782594 -0.074222401, 0.036800236 0.13906989 -0.073709324, 0.037381947 0.14002511 -0.07278882, 0.039056629 0.13957098 -0.072784796, 0.034538448 0.13863358 -0.074193925, 0.029295981 0.13981259 -0.074201927, 0.030799866 0.14103642 -0.073342144, 0.030291781 0.14096311 -0.073483959, 0.029274613 0.14079261 -0.073742434, 0.029142439 0.14174882 -0.073019654, 0.030774131 0.14144108 -0.072982147, 0.030230597 0.14154571 -0.072994843, 0.03616859 0.13790506 -0.07429269, 0.035590112 0.13793984 -0.074323848, 0.035240799 0.13817322 -0.074284568, -0.13535452 0.051124841 -0.073047787, -0.13522561 0.05169338 -0.072965026, -0.13429695 0.05100137 -0.073834375, -0.13522041 0.050569385 -0.073339611, -0.13488023 0.049438328 -0.073834538, -0.13446398 0.048279017 -0.074198931, -0.13545518 0.047839761 -0.073834747, -0.13393177 0.048941165 -0.074289441, -0.13394852 0.048488319 -0.074328631, -0.13423277 0.047695488 -0.074328959, -0.13426077 0.047183841 -0.074364975, -0.13482948 0.044624865 -0.074423999, -0.1355347 0.046817571 -0.07397455, -0.13467455 0.047407538 -0.074231863, -0.135649 0.050337911 -0.073047802, -0.13570532 0.049884856 -0.073148265, -0.13580541 0.048976362 -0.073339626, -0.13224792 0.052436858 -0.074375331, -0.13161685 0.054013997 -0.074374139, -0.13273275 0.053110421 -0.074163154, -0.13263138 0.054277331 -0.074015737, -0.13357387 0.054419696 -0.073446393, -0.13277614 0.052526444 -0.07422711, -0.13407119 0.052143484 -0.073714167, -0.13495524 0.052828103 -0.072793916, -0.13431641 0.054441571 -0.072789595, -0.13389073 0.049846947 -0.074198917, -0.13564928 0.044769526 -0.074207142, -0.13669695 0.046400964 -0.07334739, -0.13668092 0.045887947 -0.073489264, -0.13662559 0.04485786 -0.07374759, -0.13759081 0.044833541 -0.073024988, -0.13710235 0.046420455 -0.072987571, -0.13726717 0.045892 -0.073000222, -0.13298421 0.051385224 -0.074297592, -0.1330837 0.05081442 -0.074328706, -0.13335453 0.050493419 -0.074289382, -0.1287798 0.065958321 -0.073046997, -0.12858799 0.066508919 -0.072964251, -0.12774263 0.065717161 -0.073833585, -0.12870871 0.065391123 -0.073338538, -0.12849712 0.06422922 -0.073833883, -0.12821341 0.063030601 -0.074198142, -0.12761047 0.06362918 -0.074288622, -0.12767783 0.063181043 -0.074327841, -0.1292477 0.062705159 -0.073833868, -0.12804905 0.062424928 -0.074328065, -0.12813406 0.0619196 -0.07436417, -0.12898564 0.059440345 -0.074423134, -0.12944107 0.061698288 -0.073973864, -0.12852032 0.062188268 -0.074231058, -0.12916055 0.065209359 -0.073046982, -0.12926716 0.064765334 -0.07314755, -0.12946837 0.063873798 -0.073338866, -0.12554586 0.066914231 -0.074374437, -0.12474221 0.068410754 -0.07437335, -0.12595198 0.06763792 -0.074162498, -0.12572069 0.068786085 -0.074015111, -0.12664138 0.069032967 -0.073445648, -0.12606058 0.067062199 -0.07422635, -0.12739033 0.066826791 -0.073713169, -0.12819228 0.067606211 -0.072792828, -0.12737682 0.069137931 -0.072788715, -0.12746826 0.064524531 -0.074198321, -0.12978423 0.059675962 -0.074206337, -0.1306427 0.06141448 -0.073346481, -0.1306843 0.060902894 -0.073488429, -0.13074446 0.059873015 -0.073746815, -0.1317063 0.059956968 -0.073024005, -0.13104306 0.061479121 -0.072986752, -0.13126625 0.060972542 -0.072999373, -0.12639512 0.065951735 -0.074296683, -0.12655775 0.065395474 -0.074328065, -0.12686305 0.065106958 -0.074288458, -0.12058552 0.079962254 -0.073046222, -0.12033331 0.080488145 -0.072963357, -0.12057814 0.079390764 -0.073337883, -0.11958186 0.079606652 -0.073832855, -0.1204983 0.07821244 -0.073832825, -0.12035048 0.07698983 -0.074197456, -0.11968447 0.077517033 -0.074287802, -0.11980145 0.077079028 -0.074327111, -0.12141472 0.076782018 -0.073832989, -0.12025513 0.076369464 -0.074327216, -0.12039614 0.075876802 -0.07436347, -0.12151989 0.073508501 -0.074422449, -0.12171979 0.07580319 -0.07397303, -0.12074988 0.076186925 -0.07423006, -0.12104762 0.079260617 -0.073046222, -0.12120338 0.078831494 -0.073146567, -0.12150326 0.077968001 -0.073337898, -0.11726475 0.080550075 -0.074373707, -0.11629863 0.081947386 -0.074372649, -0.11758748 0.081314743 -0.074161649, -0.117229 0.082429796 -0.074014306, -0.1181163 0.082778364 -0.073444873, -0.11775976 0.080754936 -0.074225679, -0.1191075 0.080669791 -0.073712513, -0.11981736 0.081534088 -0.072792336, -0.1188354 0.082965016 -0.07278803, -0.11944273 0.078390718 -0.074197382, -0.12228703 0.073831916 -0.074205652, -0.12294543 0.075655639 -0.073345542, -0.12304395 0.075151891 -0.07348761, -0.12321922 0.074135393 -0.073745936, -0.12416545 0.074326366 -0.073023304, -0.12333636 0.075764865 -0.072985798, -0.12361437 0.075286269 -0.072998509, -0.11821665 0.079688787 -0.074295864, -0.11844055 0.079154372 -0.074327126, -0.11877608 0.078901678 -0.074287817, -0.11087473 0.092960775 -0.073045403, -0.11056525 0.093454957 -0.072962597, -0.11093162 0.092392176 -0.073337197, -0.10991728 0.092495084 -0.073832169, -0.11098418 0.091212243 -0.073831975, -0.11097409 0.089980721 -0.074196607, -0.11205499 0.08989349 -0.073832303, -0.11025316 0.090429991 -0.074287221, -0.11041839 0.090007871 -0.07432656, -0.11094867 0.089353532 -0.074326634, -0.11114399 0.088879824 -0.074362695, -0.11252598 0.08665213 -0.074421629, -0.11246744 0.088954777 -0.073972419, -0.1114607 0.089227617 -0.074229598, -0.11141273 0.092315465 -0.073045418, -0.11161542 0.091906339 -0.073145881, -0.11200997 0.091081828 -0.073337168, -0.10750927 0.093173265 -0.074373335, -0.10639265 0.094453394 -0.07437177, -0.10774432 0.093969077 -0.074161127, -0.1072633 0.095037103 -0.074013606, -0.10810588 0.095482647 -0.073444247, -0.10797822 0.093432009 -0.074224845, -0.10932691 0.093498439 -0.073711887, -0.1099353 0.094436735 -0.072791487, -0.10879943 0.095748603 -0.0727873, -0.10991526 0.091271192 -0.074196666, -0.11325206 0.087059587 -0.074204743, -0.11370222 0.088945627 -0.073344946, -0.11385641 0.088455975 -0.073486894, -0.11414441 0.087465465 -0.073745281, -0.11506341 0.087761164 -0.073022723, -0.11407816 0.089097649 -0.072985277, -0.11440839 0.088653475 -0.072997749, -0.1085515 0.092423886 -0.074295118, -0.10883397 0.091917962 -0.074326411, -0.10919552 0.091704309 -0.074287012, -0.0739512 0.12436393 -0.073043704, -0.073495761 0.12472826 -0.072960839, -0.073201224 0.12360817 -0.073830262, -0.074192747 0.12384599 -0.07333529, -0.0746319 0.1227496 -0.073830396, -0.075029179 0.121584 -0.074194893, -0.074200407 0.12176991 -0.074285462, -0.074495837 0.12142614 -0.074324757, -0.076078072 0.12185854 -0.07383056, -0.075212449 0.12098351 -0.074324831, -0.075553223 0.12060094 -0.074361041, -0.077593252 0.11895478 -0.074419931, -0.076777592 0.1211088 -0.073970541, -0.075737327 0.12103373 -0.07422772, -0.074672058 0.12393242 -0.073043719, -0.074998543 0.12361333 -0.073144108, -0.07564339 0.12296534 -0.073335528, -0.07070443 0.12345284 -0.074371278, -0.069227651 0.12429255 -0.074370414, -0.070663512 0.12428194 -0.074159205, -0.069856629 0.12513083 -0.074011773, -0.07050465 0.12582976 -0.07344234, -0.071061432 0.1238521 -0.07422331, -0.072312668 0.12436011 -0.07370995, -0.07257694 0.12544686 -0.072789729, -0.071071595 0.12631002 -0.072785497, -0.073603481 0.12245226 -0.074194863, -0.078144059 0.11957905 -0.074202895, -0.077946022 0.12150776 -0.073343039, -0.078253314 0.12109667 -0.073485211, -0.078852326 0.12025678 -0.073743492, -0.079621971 0.12083954 -0.073020741, -0.078250557 0.12177563 -0.072983354, -0.078708991 0.12146538 -0.072995871, -0.071935639 0.12308979 -0.074293509, -0.072369248 0.12270543 -0.074324712, -0.072781235 0.12262347 -0.074285269, -0.059562325 0.1318619 -0.073043302, -0.059069067 0.13217297 -0.072960436, -0.059860319 0.13137421 -0.073334977, -0.058901757 0.13102686 -0.073829904, -0.060419515 0.13033405 -0.073829934, -0.060944706 0.1292201 -0.074194491, -0.060100421 0.12931219 -0.074285105, -0.061956361 0.12961039 -0.073830068, -0.060432389 0.12900352 -0.07432428, -0.061194047 0.12864396 -0.07432422, -0.061575532 0.12830201 -0.074360371, -0.063787237 0.12689453 -0.074419528, -0.062735453 0.12894374 -0.073970094, -0.061710089 0.12875271 -0.074227363, -0.060326949 0.1315138 -0.073043227, -0.060687229 0.13123333 -0.073143691, -0.061400369 0.13066155 -0.073335081, -0.05643791 0.13059303 -0.074370921, -0.054876462 0.13126203 -0.074369848, -0.056304291 0.13141215 -0.074158832, -0.055407494 0.13216555 -0.074011639, -0.055973411 0.13293272 -0.073441967, -0.056748062 0.13102978 -0.074222744, -0.057934493 0.13167477 -0.073709458, -0.058075532 0.13278416 -0.072789252, -0.056482881 0.13347331 -0.072785184, -0.059430957 0.12992331 -0.074194491, -0.06426461 0.12757644 -0.074202567, -0.063851878 0.12947112 -0.07334277, -0.064203352 0.12909693 -0.073484585, -0.064892516 0.12832952 -0.073742896, -0.06559214 0.12899461 -0.073020309, -0.064124554 0.12977135 -0.072982982, -0.064614892 0.1295144 -0.072995454, -0.057702214 0.13037011 -0.074292988, -0.058176041 0.13003668 -0.07432422, -0.058594525 0.1300014 -0.074284941, -0.099769667 0.10479033 -0.073044792, -0.099406868 0.10524675 -0.072961912, -0.098870456 0.1042203 -0.073831543, -0.099889919 0.10423151 -0.073336571, -0.1000742 0.10306495 -0.073831603, -0.10020217 0.10184017 -0.074196085, -0.10128586 0.10187435 -0.073831528, -0.099435523 0.10220587 -0.074286446, -0.099646986 0.101805 -0.0743258, -0.10024716 0.10121396 -0.07432583, -0.10049431 0.1007652 -0.074362084, -0.102117 0.098706275 -0.074421063, -0.10180113 0.10098788 -0.073971674, -0.10077 0.10114622 -0.074228853, -0.10037661 0.10420915 -0.073044881, -0.10062376 0.10382533 -0.0731453, -0.10110822 0.1030502 -0.073336557, -0.096401528 0.10462454 -0.074372545, -0.095148742 0.10577178 -0.074371308, -0.096546128 0.10544184 -0.074160323, -0.095948368 0.10644916 -0.07401292, -0.096735865 0.1069864 -0.073443696, -0.096838504 0.10493428 -0.074224219, -0.098171487 0.10515127 -0.073711127, -0.098671034 0.10615191 -0.072790742, -0.097395316 0.10732827 -0.072786629, -0.099005371 0.10300389 -0.074195981, -0.10279289 0.099192441 -0.074204117, -0.10302882 0.1011169 -0.073344409, -0.10323699 0.10064772 -0.073486105, -0.10363407 0.099695563 -0.07374455, -0.10451408 0.10009223 -0.073021933, -0.10338549 0.10131007 -0.072984412, -0.10376331 0.10090563 -0.072997004, -0.09752126 0.1039966 -0.074294478, -0.097858295 0.10352534 -0.074325636, -0.098241836 0.10335389 -0.074286491, -0.087410107 0.11530221 -0.073044211, -0.086998403 0.11571524 -0.072961375, -0.086580411 0.11463502 -0.073830828, -0.087592006 0.11476037 -0.073336065, -0.08790575 0.11362171 -0.073830917, -0.088170201 0.11241895 -0.0741954, -0.087367401 0.11269653 -0.07428579, -0.089243159 0.11257422 -0.073831007, -0.087622374 0.11232185 -0.074325234, -0.08828494 0.11180177 -0.074325174, -0.088580742 0.11138332 -0.074361458, -0.090423673 0.10951918 -0.074420422, -0.089854285 0.11175099 -0.073971018, -0.088812053 0.11179295 -0.074228346, -0.088078156 0.11479262 -0.07304424, -0.088366702 0.11443886 -0.073144525, -0.088935018 0.11372286 -0.07333611, -0.08408156 0.11476028 -0.074371874, -0.08270821 0.11576 -0.074370787, -0.084133804 0.11558858 -0.074159727, -0.083427057 0.11652261 -0.074012503, -0.084149405 0.11714467 -0.073442921, -0.084481299 0.11511707 -0.074223727, -0.085781544 0.11548188 -0.073710486, -0.08616583 0.11653206 -0.07279028, -0.084766358 0.11755836 -0.072786167, -0.086850598 0.11344141 -0.074195355, -0.091041103 0.11007798 -0.074203491, -0.091059893 0.11201674 -0.073343784, -0.091319412 0.11157364 -0.073485568, -0.091820613 0.11067221 -0.073743954, -0.092650592 0.1111649 -0.073021248, -0.09139289 0.11224875 -0.072983861, -0.0918134 0.11188906 -0.072996184, -0.085264415 0.11426169 -0.074293986, -0.085652381 0.11383104 -0.074325204, -0.086052656 0.11370349 -0.074285865, -0.13769774 -0.044420213 -0.073053151, -0.1379514 -0.043895394 -0.072970316, -0.13679379 -0.043857396 -0.073839754, -0.13724644 -0.044771075 -0.073344767, -0.13627526 -0.045443147 -0.073839858, -0.13522717 -0.046089917 -0.074204296, -0.1352239 -0.045240492 -0.074294969, -0.13495465 -0.045605004 -0.074333951, -0.13572833 -0.0470514 -0.073839903, -0.13468264 -0.046402067 -0.074334145, -0.13438542 -0.046819389 -0.074370369, -0.13323441 -0.049174786 -0.074429318, -0.13515301 -0.047900259 -0.073980153, -0.13484842 -0.046902597 -0.074237019, -0.13743742 -0.045219213 -0.07305336, -0.13719882 -0.04560861 -0.073153615, -0.13671045 -0.046381235 -0.073344931, -0.13608682 -0.041457534 -0.074380726, -0.13657679 -0.039831072 -0.074379504, -0.13688594 -0.041233152 -0.074168369, -0.13753408 -0.040257722 -0.074021056, -0.1383599 -0.040734082 -0.073451757, -0.13655554 -0.041716903 -0.074232399, -0.13732919 -0.042823792 -0.073719308, -0.13844757 -0.042839766 -0.072799146, -0.1389541 -0.041180015 -0.072795033, -0.13575646 -0.044506818 -0.074204251, -0.13396566 -0.049572825 -0.074212492, -0.13580205 -0.048950404 -0.073352799, -0.13546966 -0.049341559 -0.073494568, -0.13478413 -0.050112456 -0.07375297, -0.1355235 -0.050733209 -0.073030502, -0.13613103 -0.049187958 -0.072992906, -0.13593043 -0.049703956 -0.073005527, -0.13600689 -0.042738765 -0.074302718, -0.1357287 -0.043247074 -0.074333966, -0.13574031 -0.043667048 -0.074294701, -0.14180581 -0.028723717 -0.073052317, -0.14199939 -0.028173715 -0.072969362, -0.1408447 -0.028265536 -0.073838919, -0.14139654 -0.02912268 -0.073343962, -0.14050683 -0.029899269 -0.073839024, -0.13953787 -0.030659318 -0.074203312, -0.14014338 -0.031558782 -0.073839039, -0.13943955 -0.029815614 -0.074293941, -0.13921262 -0.030208111 -0.074333236, -0.13903165 -0.031030566 -0.074333325, -0.13878289 -0.031478792 -0.074369401, -0.13790305 -0.033947974 -0.074428454, -0.13966674 -0.03246671 -0.073979318, -0.13925239 -0.03150937 -0.074236333, -0.14163667 -0.029546767 -0.073052227, -0.14144327 -0.029960245 -0.073152632, -0.14104442 -0.030782789 -0.073344067, -0.13987343 -0.025959969 -0.074379712, -0.14017819 -0.024288744 -0.074378535, -0.14064236 -0.025647521 -0.074167505, -0.14117727 -0.024605453 -0.074020207, -0.14205103 -0.024986565 -0.073450893, -0.1403681 -0.026165217 -0.074231654, -0.14126101 -0.027178407 -0.073718384, -0.14237407 -0.027069092 -0.072798312, -0.14269157 -0.025362968 -0.072794259, -0.1398866 -0.029026896 -0.074203312, -0.1386741 -0.034261763 -0.074211642, -0.14042923 -0.033437729 -0.073351949, -0.14014286 -0.033863544 -0.073493704, -0.13954778 -0.034706235 -0.073751971, -0.14035228 -0.035240412 -0.073029533, -0.14078283 -0.033636868 -0.072992146, -0.14064132 -0.034172118 -0.073004574, -0.13993745 -0.027242124 -0.074301764, -0.13971776 -0.027778357 -0.074333072, -0.13977645 -0.028194189 -0.074293867, -0.12435994 -0.073947102 -0.073054731, -0.1247243 -0.073491812 -0.07297191, -0.12360395 -0.073197126 -0.073841482, -0.12384197 -0.07418859 -0.073346421, -0.12274554 -0.074627757 -0.073841646, -0.12157972 -0.075025141 -0.07420598, -0.12185445 -0.076073885 -0.073841363, -0.12176588 -0.074196309 -0.0742964, -0.12142201 -0.074491739 -0.07433565, -0.12097947 -0.075208306 -0.07433565, -0.12059687 -0.075549155 -0.074371785, -0.11895071 -0.077589214 -0.074430838, -0.12110478 -0.076773494 -0.073981583, -0.12102976 -0.075733185 -0.074238673, -0.12392858 -0.07466805 -0.073054716, -0.12360919 -0.074994534 -0.073155209, -0.12296125 -0.075639248 -0.073346689, -0.12344876 -0.070700139 -0.074382156, -0.12428834 -0.069223553 -0.074381173, -0.12427768 -0.07065925 -0.074170113, -0.12512678 -0.069852412 -0.07402271, -0.12582575 -0.070500672 -0.073453575, -0.12384802 -0.07105726 -0.07423389, -0.12435606 -0.072308719 -0.073721066, -0.12544298 -0.072573066 -0.072800756, -0.12630618 -0.071067482 -0.072796494, -0.12244824 -0.073599398 -0.074205965, -0.11957493 -0.07814005 -0.074214101, -0.12150386 -0.077941924 -0.073354334, -0.12109265 -0.078249246 -0.073496163, -0.1202528 -0.078848094 -0.073754549, -0.1208356 -0.079617888 -0.073031962, -0.12177175 -0.078246713 -0.07299462, -0.12146141 -0.078705072 -0.073007107, -0.12308577 -0.071931392 -0.074304476, -0.12270127 -0.072365135 -0.074335665, -0.12261933 -0.072777152 -0.074296385, -0.13185789 -0.059558243 -0.073054105, -0.13216899 -0.059064895 -0.072971314, -0.1313702 -0.059856206 -0.073345736, -0.13102289 -0.058897644 -0.073840722, -0.1303298 -0.060415328 -0.073840767, -0.12921603 -0.060940683 -0.074205205, -0.129308 -0.060096174 -0.074295789, -0.12960625 -0.061952353 -0.073840857, -0.12899941 -0.060428351 -0.074334934, -0.12863986 -0.06118995 -0.074334949, -0.12829779 -0.061571479 -0.07437101, -0.1268905 -0.06378293 -0.074430242, -0.12893961 -0.062731355 -0.073980808, -0.12874849 -0.061705917 -0.074237898, -0.13150969 -0.060323 -0.073053971, -0.1312293 -0.060682952 -0.073154211, -0.13065746 -0.061396271 -0.073345691, -0.13058889 -0.056433827 -0.074381322, -0.13125798 -0.054872185 -0.074380189, -0.13140814 -0.056300282 -0.074169219, -0.13216139 -0.055403501 -0.074021891, -0.13292873 -0.055969298 -0.073452607, -0.13102572 -0.05674395 -0.074233234, -0.13167059 -0.05793047 -0.073720291, -0.13278018 -0.058071554 -0.072800174, -0.13346931 -0.056478947 -0.072795868, -0.12991929 -0.059426665 -0.074205041, -0.1275724 -0.064260572 -0.074213266, -0.12946692 -0.06384781 -0.073353633, -0.12909292 -0.064199209 -0.073495358, -0.1283253 -0.064888388 -0.073753819, -0.12899038 -0.065588176 -0.073031157, -0.12976727 -0.064120591 -0.072993815, -0.12951039 -0.064610809 -0.073006362, -0.13036598 -0.057697862 -0.074303493, -0.13003249 -0.058172017 -0.074334934, -0.12999725 -0.058590442 -0.074295476, -0.14022717 0.035648406 -0.073048607, -0.14016272 0.036228031 -0.072965801, -0.13916235 0.035644263 -0.073835358, -0.14003156 0.035111398 -0.073340401, -0.13956681 0.03402558 -0.073835477, -0.1390236 0.03292042 -0.07419987, -0.13856913 0.033637941 -0.074290216, -0.13995938 0.032372862 -0.073835373, -0.13853489 0.033186048 -0.074329659, -0.13872857 0.032366365 -0.074329704, -0.13869901 0.031854749 -0.074365959, -0.13897763 0.029248238 -0.074424893, -0.1399239 0.03134802 -0.073975682, -0.13913517 0.032030702 -0.074232787, -0.14043164 0.034833491 -0.073048607, -0.14043677 0.034376889 -0.07314904, -0.14043461 0.033462942 -0.073340565, -0.13728701 0.03730014 -0.074376106, -0.13683641 0.038937896 -0.074374899, -0.1378442 0.03791514 -0.074164018, -0.13787407 0.039086014 -0.07401669, -0.13882662 0.039121926 -0.073447302, -0.13782173 0.037329853 -0.074228004, -0.13906583 0.036804408 -0.073715001, -0.14002115 0.037385821 -0.072794706, -0.13956703 0.039060622 -0.07279034, -0.13862938 0.034542471 -0.074199811, -0.13980864 0.029300153 -0.074207962, -0.14103229 0.030804068 -0.073348388, -0.14095885 0.030295998 -0.073490009, -0.1407885 0.029278725 -0.073748574, -0.14174473 0.029146314 -0.073025852, -0.1414371 0.030777931 -0.072988391, -0.14154172 0.030234396 -0.073001042, -0.13790098 0.036172658 -0.074298233, -0.13793576 0.035594285 -0.074329481, -0.13816905 0.035245001 -0.07429029, -0.14333616 0.019723743 -0.07304965, -0.14333725 0.020307004 -0.072966829, -0.14227785 0.019838959 -0.073836297, -0.14308181 0.019212008 -0.073341236, -0.14249861 0.018185288 -0.073836342, -0.14183497 0.017147809 -0.07420069, -0.14146361 0.017911732 -0.074291244, -0.14270355 0.016498864 -0.073836416, -0.14137894 0.017466426 -0.074330494, -0.1414796 0.016630083 -0.074330613, -0.14139305 0.016125113 -0.074366674, -0.14137803 0.01350379 -0.074425742, -0.14255366 0.015484661 -0.073976502, -0.14184628 0.016251087 -0.074233592, -0.14344846 0.018891215 -0.07304962, -0.14340231 0.018436939 -0.073150009, -0.14329785 0.017528892 -0.073341459, -0.14059961 0.021694303 -0.074377134, -0.14033523 0.023372293 -0.074375853, -0.14122216 0.022243083 -0.074165002, -0.1413828 0.023403317 -0.074017555, -0.14233355 0.023332357 -0.073448136, -0.14113429 0.021664023 -0.074228793, -0.14231171 0.021002591 -0.07371591, -0.14332619 0.021473467 -0.07279554, -0.1430624 0.023188561 -0.072791412, -0.14162493 0.018803865 -0.074200496, -0.14220953 0.013462305 -0.074208871, -0.143594 0.014819831 -0.073349252, -0.14346413 0.014323235 -0.073490903, -0.14318115 0.013331234 -0.073749334, -0.14411645 0.013092697 -0.073027, -0.14399341 0.014748603 -0.072989434, -0.14403655 0.014196634 -0.073001876, -0.14108337 0.020505279 -0.074299127, -0.14105333 0.019926637 -0.074330479, -0.14124596 0.019553423 -0.074291214, -0.14413068 -0.012665838 -0.073051333, -0.14426127 -0.012097627 -0.072968572, -0.1437688 -0.013108104 -0.073343083, -0.14312422 -0.012318254 -0.073837832, -0.14297137 -0.013979673 -0.07383801, -0.14209369 -0.014843345 -0.074202448, -0.14190167 -0.014015853 -0.074293092, -0.14171995 -0.014431149 -0.074332312, -0.1427962 -0.015669167 -0.073838204, -0.14163215 -0.015268892 -0.074332505, -0.14143537 -0.015742004 -0.074368477, -0.14083731 -0.018294305 -0.07442756, -0.1424243 -0.016624629 -0.07397835, -0.14190517 -0.015720069 -0.074235409, -0.14405468 -0.013502777 -0.073051453, -0.14390862 -0.013935387 -0.073151857, -0.14360468 -0.014797211 -0.073343143, -0.14190094 -0.010135889 -0.074378833, -0.14201672 -0.0084410906 -0.074377671, -0.14263001 -0.0097393394 -0.074166834, -0.14304501 -0.008643955 -0.074019462, -0.14395602 -0.0089246631 -0.073449925, -0.14241561 -0.010284394 -0.074230462, -0.14341629 -0.011191219 -0.073717564, -0.14451016 -0.010957927 -0.072797269, -0.14463459 -0.0092271268 -0.072793201, -0.1422573 -0.013182282 -0.074202359, -0.14163874 -0.018519729 -0.074210733, -0.14329068 -0.017504245 -0.073351011, -0.14305353 -0.017959565 -0.073492974, -0.14255674 -0.018863589 -0.073751345, -0.14341581 -0.019304246 -0.07302855, -0.14366429 -0.017662495 -0.072991267, -0.14358358 -0.018210322 -0.073003665, -0.14210807 -0.011402726 -0.074300826, -0.14194988 -0.011960208 -0.074332282, -0.14205486 -0.012366891 -0.074292973, -0.14464287 0.0035512447 -0.073050559, -0.14470911 0.0041306913 -0.072967678, -0.1443328 0.0030711889 -0.073342189, -0.14360395 0.0037841797 -0.073837042, -0.1436381 0.0021159053 -0.073837101, -0.1428626 0.0011594892 -0.074201658, -0.14257899 0.0019601583 -0.074292123, -0.14365317 0.00041747093 -0.07383731, -0.14244507 0.0015271604 -0.074331507, -0.14245166 0.00068482757 -0.074331462, -0.142309 0.00019267201 -0.074367717, -0.1420005 -0.0024104118 -0.074426696, -0.14339054 -0.00057375431 -0.073977515, -0.14277345 0.00026726723 -0.074234262, -0.14466111 0.0027112961 -0.073050335, -0.14456455 0.0022650063 -0.073150948, -0.14435896 0.0013744831 -0.07334213, -0.14214405 0.0058156252 -0.074378133, -0.14206921 0.0075128675 -0.074376866, -0.14282431 0.0062915087 -0.074165776, -0.14311381 0.0074263513 -0.074018434, -0.14405049 0.0072494149 -0.073448941, -0.14267208 0.0057256818 -0.074229807, -0.1437678 0.0049366057 -0.073716804, -0.14482881 0.0052909553 -0.072796419, -0.14475876 0.0070247948 -0.072792277, -0.14283919 0.0028284788 -0.074201718, -0.14282222 -0.0025447309 -0.074209824, -0.14435016 -0.0013506711 -0.073349848, -0.14416526 -0.0018297732 -0.073492005, -0.14377299 -0.0027837157 -0.073750198, -0.14467588 -0.0031255186 -0.07302773, -0.14473896 -0.0014663339 -0.072990328, -0.1447202 -0.0020194054 -0.073002785, -0.14249173 0.0045801401 -0.074299991, -0.14239697 0.0040083528 -0.074331358, -0.14254674 0.0036159158 -0.074292049, 0.065954313 0.12878367 -0.073043421, 0.066504985 0.12859187 -0.072960794, 0.06538704 0.12871271 -0.073335037, 0.065713122 0.12774661 -0.073830336, 0.064225107 0.12850127 -0.073830143, 0.063026592 0.12821752 -0.074194565, 0.063625067 0.12761465 -0.074285224, 0.062701061 0.12925175 -0.073829994, 0.063176781 0.12768188 -0.074324399, 0.062420726 0.12805319 -0.074324399, 0.061915472 0.12813824 -0.074360535, 0.059436262 0.12898979 -0.074419424, 0.06169413 0.1294452 -0.073970094, 0.062184036 0.12852454 -0.074227214, 0.065205261 0.12916446 -0.073043376, 0.064761311 0.12927112 -0.073143706, 0.063869655 0.12947235 -0.073335037, 0.066910014 0.12554988 -0.074371263, 0.068406552 0.12474626 -0.074370444, 0.067633748 0.1259563 -0.07415916, 0.068781853 0.12572488 -0.074011818, 0.069028899 0.12664548 -0.073442355, 0.067058131 0.12606457 -0.074223071, 0.066822767 0.12739429 -0.073709741, 0.067602322 0.12819621 -0.07278955, 0.069133908 0.12738082 -0.072785556, 0.064520463 0.12747237 -0.074194655, 0.059671879 0.12978837 -0.074202433, 0.061410502 0.13064668 -0.073342919, 0.060898826 0.13068816 -0.073484406, 0.059868932 0.13074863 -0.073742852, 0.059952885 0.13171008 -0.07302025, 0.061475277 0.13104704 -0.072982877, 0.060968593 0.13127008 -0.072995439, 0.065947667 0.12639919 -0.074293375, 0.065391406 0.12656191 -0.074324504, 0.06510289 0.12686718 -0.074285224, 0.051368952 0.13289487 0.074331358, 0.052484483 0.1325185 0.074315652, 0.052121848 0.13391423 0.073815227, 0.050997242 0.13429272 0.073844716, 0.050810307 0.13307932 0.074338883, 0.049880907 0.13570115 0.073158532, 0.051157221 0.13618657 0.072032154, 0.047922179 0.13735834 0.072032198, 0.04897216 0.13580117 0.073350012, 0.049434066 0.13487589 0.07384485, 0.050565168 0.13521621 0.073349908, 0.050333917 0.13564488 0.073058277, 0.051120788 0.13535029 0.073058382, 0.051686138 0.13515741 0.073037624, 0.052814439 0.13476443 0.072996229, 0.04619126 0.13454723 0.074386507, 0.044669539 0.13506687 0.074385062, 0.044819295 0.13610619 0.074029624, 0.045894966 0.13694778 0.073288903, 0.044858888 0.13706291 0.073465854, 0.04480131 0.13782138 0.072805658, 0.046831548 0.13567838 0.073909417, 0.046411887 0.13688377 0.07319583, 0.044660494 0.13845319 0.072032318, 0.047835618 0.13545105 0.073844805, 0.049842834 0.13388652 0.074209228, 0.05304651 0.13240793 0.074284285, 0.054169536 0.13217783 0.074214891, 0.054362521 0.1331279 0.07375522, 0.05393517 0.13138041 0.074433133, 0.054363504 0.13493875 0.072032198, 0.053357765 0.13453719 0.073008627, 0.054441124 0.13407627 0.073033065, 0.047191545 0.13433689 0.074355811, 0.047691464 0.13422856 0.074338734, 0.048484206 0.13394433 0.074338943, 0.048275039 0.13445979 0.074209213, 0.048937127 0.13392773 0.074299723, 0.050489292 0.13335034 0.074299678, -0.071606621 -0.090081155 0.073837683, -0.079839706 -0.089623302 0.074330658, -0.07468912 -0.093958855 0.074330285, 0.067056581 -0.062080115 0.066575378, 0.064714119 -0.064518213 0.066575289, 0.070377484 -0.065154612 0.068649232, -0.076544717 -0.085924476 0.073837891, -0.072310865 -0.095801264 0.074329972, -0.064514384 -0.064717919 0.066575348, -0.071867913 -0.063506514 0.068649262, -0.06770955 -0.067923009 0.068649024, -0.068476632 -0.06050989 0.066575438, 0.078189448 -0.063233942 0.070419461, 0.075082615 -0.066893607 0.070419431, 0.078636304 -0.070059627 0.07187824, 0.081890166 -0.066226721 0.071878523, -0.066889644 -0.075086653 0.070418835, -0.07435441 -0.074588686 0.071877867, -0.07005547 -0.078640491 0.071877986, 0.068229645 -0.060788184 0.066575423, 0.071608737 -0.063798636 0.068649292, -0.070994273 -0.071217954 0.070419058, -0.068551302 -0.086237729 0.073018894, -0.073278591 -0.082258254 0.073019043, -0.069326609 -0.091847658 0.073837489, 0.10172643 -0.063704103 0.07433185, 0.097994611 -0.069307685 0.074331582, -0.069303647 -0.097998887 0.074329898, 0.074571818 -0.060308248 0.068649426, -0.063794732 -0.071612597 0.068648711, 0.085985601 -0.060814589 0.071878746, 0.085657761 -0.069273442 0.073019579, 0.089941621 -0.063612461 0.07302025, -0.065536097 -0.082444727 0.071877703, 0.097528055 -0.061075121 0.073839203, 0.093950331 -0.066447526 0.073838949, -0.066368312 -0.087928683 0.073018804, 0.071053013 -0.057462573 0.066575617, -0.066443473 -0.093954533 0.073837489, 0.08209981 -0.058066338 0.070419699, -0.060784459 -0.06823352 0.066575095, -0.065750957 -0.1004172 0.074329838, 0.093366578 -0.058469206 0.073020399, -0.062574461 -0.078719079 0.070418552, 0.10513818 -0.057900161 0.074332148, 0.078301236 -0.055379868 0.06864962, -0.063449368 -0.084061414 0.07187745, 0.089259952 -0.055897623 0.071879029, -0.063608184 -0.089945674 0.07301864, -0.063699916 -0.10173061 0.074329689, 0.10649016 -0.055374026 0.074332476, -0.063037261 -0.096273035 0.073837295, 0.1007989 -0.055510551 0.073839456, -0.059679285 -0.075076938 0.068648607, 0.074606434 -0.052766711 0.066575944, -0.060581893 -0.080262512 0.070418671, 0.085226163 -0.053371608 0.070420012, -0.060810551 -0.085989654 0.07187745, 0.10209522 -0.053088754 0.07383962, 0.096497849 -0.05314222 0.073020667, -0.061071008 -0.097532272 0.07383728, -0.060347363 -0.092165232 0.073018566, 0.10821897 -0.051913887 0.074332625, -0.056863174 -0.071534336 0.066574857, 0.081283018 -0.050902367 0.068649977, -0.057778984 -0.076549172 0.068648547, 0.097738728 -0.050823599 0.073020831, -0.058062375 -0.082103789 0.070418373, 0.092253566 -0.050804913 0.071879208, -0.058897287 -0.1045846 0.074329615, 0.10375276 -0.049771637 0.073839843, -0.058464974 -0.093370676 0.073018536, 0.10995057 -0.048137426 0.074332848, -0.057693183 -0.088111639 0.071877256, 0.077447399 -0.048500478 0.066576138, -0.055052549 -0.072937131 0.066574752, 0.093439862 -0.048588365 0.071879581, -0.055376023 -0.078305155 0.068648398, 0.088084504 -0.048508912 0.070420295, -0.05646649 -0.10026851 0.073836967, 0.099325478 -0.047647715 0.07302098, -0.055893511 -0.089264125 0.071877107, -0.055085942 -0.084129751 0.070418343, 0.11095929 -0.045764327 0.074332938, 0.10541284 -0.046150982 0.073840246, -0.052762941 -0.074610054 0.066574693, -0.054056957 -0.09599027 0.07301861, 0.089217171 -0.046392649 0.070420295, -0.053367659 -0.085230231 0.070418358, 0.084008887 -0.046264648 0.068650216, -0.052537307 -0.080237448 0.068648338, 0.094956875 -0.045552343 0.071879581, 0.10637996 -0.043875754 0.073840126, -0.051679373 -0.091768384 0.071877137, 0.10091485 -0.044181883 0.073021367, -0.050898403 -0.081286937 0.068648189, -0.050058112 -0.076451331 0.066574588, 0.085089356 -0.044246167 0.068650261, 0.080044821 -0.044081658 0.066576451, 0.090665638 -0.043493837 0.070420608, -0.049343973 -0.087621272 0.070418134, 0.11292012 -0.040686071 0.074333265, -0.048496664 -0.077451229 0.066574588, 0.10184073 -0.042003781 0.073021397, -0.04576008 -0.11096343 0.074329212, -0.0519097 -0.10822314 0.074329317, 0.096476227 -0.042238712 0.07187964, -0.047060892 -0.083567411 0.068648085, 0.081074119 -0.042158484 0.066576645, 0.086470678 -0.041481465 0.068650439, 0.10825975 -0.039007097 0.073840454, -0.043871611 -0.1063841 0.073836729, -0.0497673 -0.10375679 0.073836729, 0.097361282 -0.040156305 0.071879804, -0.044840336 -0.079624027 0.066574559, 0.092116386 -0.040330052 0.070420757, 0.082390487 -0.039524168 0.06657657, -0.041999593 -0.10184473 0.07301797, -0.047643766 -0.099329621 0.073018149, 0.10364018 -0.037342906 0.073021695, -0.03946656 -0.11335471 0.074329093, 0.09296149 -0.038341701 0.070420951, 0.087854207 -0.038464129 0.068650469, -0.040152177 -0.097365528 0.071876705, -0.045548186 -0.094960958 0.071876839, -0.036886007 -0.11422056 0.074329138, 0.099081755 -0.03570053 0.071880206, -0.037837744 -0.10867664 0.073836625, 0.088660419 -0.036567986 0.068650648, 0.083708793 -0.036649138 0.066576898, 0.094604179 -0.034087181 0.070421189, -0.038337767 -0.092965394 0.070417911, -0.043489903 -0.090669721 0.070417941, 0.08447665 -0.034842342 0.066576853, -0.035363808 -0.10950667 0.073836491, 0.090227023 -0.032510191 0.068650991, -0.036223143 -0.10403952 0.07301788, 0.085969448 -0.030976057 0.066577286, -0.033048943 -0.11538926 0.074328974, -0.036563903 -0.088664234 0.068647772, -0.041477636 -0.086474657 0.068647966, -0.11751598 -0.0025707483 0.074129879, -0.11506365 0.0013287961 0.073842838, -0.12001678 0.001386255 0.07433562, -0.1125827 -0.0024629831 0.073473632, -0.11489567 -0.0063595176 0.073842347, -0.033854887 -0.10483417 0.073017791, -0.034630015 -0.099463642 0.071876556, -0.017015412 -0.11631009 0.074123517, -0.020452946 -0.1132431 0.073836386, -0.021333367 -0.11811787 0.074328899, -0.031684995 -0.11062708 0.073836446, -0.029174849 -0.11642927 0.074329183, -0.016301244 -0.11142752 0.073467746, -0.012843683 -0.1143564 0.073836267, -0.034838662 -0.084480405 0.066574231, -0.039520487 -0.082394153 0.06657441, 0.022077173 -0.1154564 0.074123695, 0.018591285 -0.11858046 0.074328855, 0.026469678 -0.1170738 0.074328974, 0.017823979 -0.11368665 0.073836192, 0.025377467 -0.11224234 0.073836431, 0.021150321 -0.11060956 0.073467612, -0.03236565 -0.10022339 0.0718766, -0.033065096 -0.094968796 0.070417628, 0.093732506 -0.070932448 0.074126139, 0.089475736 -0.072360992 0.073838666, 0.093327314 -0.075475752 0.074331343, -0.030332968 -0.1059069 0.073017791, -0.026527271 -0.11706093 0.074328899, 0.11185554 -0.036127687 0.074128091, -0.027970895 -0.11162418 0.073836446, 0.10715991 -0.034611255 0.073471978, -0.12117186 -0.0048220754 0.074407205, -0.030903012 -0.095694304 0.070417717, -0.11984162 -0.0066332221 0.074334964, -0.10894157 -0.00056257844 0.072768241, -0.11015369 0.0012719929 0.073023692, -0.1053088 0.001215905 0.071882173, -0.031535149 -0.09057489 0.068647683, -0.10886194 -0.0042025149 0.072768092, -0.10999289 -0.0060883164 0.07302323, -0.028998792 -0.10124898 0.071876377, -0.10515514 -0.0058207214 0.071881652, -0.057255045 -0.10690436 0.074401289, -0.054287508 -0.10426077 0.074124202, -0.025432333 -0.11222991 0.07383655, -0.054234445 -0.10846803 0.074401379, -0.026777208 -0.10686138 0.073017716, -0.054226384 -0.10009804 0.073662892, -0.02947323 -0.0912669 0.068647608, -0.050912142 -0.10182381 0.073662817, -0.030047238 -0.086300939 0.066574037, -0.018842593 -0.11979875 0.074400619, -0.015475422 -0.12027997 0.074400634, -0.013396502 -0.11927909 0.074328929, -0.027688324 -0.09667325 0.070417538, -0.017569527 -0.10752097 0.072762355, -0.019580275 -0.10841128 0.073017865, -0.018718913 -0.10364312 0.071876377, -0.013966992 -0.10804799 0.07276234, -0.012295589 -0.10947695 0.073017463, -0.024347216 -0.1074411 0.073017612, -0.011754856 -0.10466197 0.071876436, 0.018670976 -0.10733533 0.072762251, 0.017063379 -0.10883582 0.073017523, 0.016312778 -0.10404879 0.071876407, -0.025599465 -0.10216138 0.071876436, 0.022246793 -0.10665134 0.072762355, 0.024294525 -0.10745314 0.073017463, 0.023225963 -0.10272697 0.071876377, -0.028082445 -0.086960167 0.066573963, 0.09582147 -0.074328184 0.074403048, -0.026407138 -0.092200667 0.068647623, 0.097868159 -0.071611524 0.074403405, 0.089659274 -0.070150435 0.073664576, -0.023276269 -0.10271558 0.071876541, 0.091872945 -0.067225039 0.073664665, 0.11496882 -0.038578242 0.074405164, -0.024442628 -0.097544581 0.070417434, 0.1160055 -0.035338581 0.074405387, -0.025161117 -0.087849915 0.066574007, 0.10309681 -0.035212129 0.072766244, 0.10421573 -0.031747431 0.072766617, -0.11705664 0.026523083 0.074336886, -0.11222562 0.025428206 0.073844209, -0.022224471 -0.098073721 0.070417374, -0.10471523 0.00033402443 0.071717098, -0.10054998 0.0011610687 0.070423141, -0.023311689 -0.093031645 0.068647638, -0.10611182 -0.0011392534 0.072094649, -0.10743682 0.024342895 0.073025033, -0.10470627 -0.0014157593 0.071716964, -0.11835986 0.019917876 0.074336693, -0.10328236 -0.0028354228 0.071312234, -0.021196082 -0.093536288 0.068647712, -0.10271145 0.023272187 0.07188338, -0.10460062 -0.0049137175 0.0717168, -0.100403 -0.0055576861 0.070422843, -0.052972734 -0.095897019 0.072893366, -0.02221185 -0.088641524 0.066573858, -0.1187605 0.017370492 0.074336469, -0.052327842 -0.097868323 0.073177293, -0.11347511 0.019095719 0.073843747, -0.051391914 -0.096753329 0.072893202, -0.017873064 -0.098959386 0.070417404, -0.098069832 0.022220463 0.070424244, -0.049415693 -0.096185684 0.0725815, -0.020195946 -0.089122623 0.066573918, -0.048189044 -0.098387957 0.072893202, -0.11385925 0.016653478 0.07384342, -0.017750606 -0.10320449 0.071711212, -0.10863298 0.018280685 0.073024765, -0.017046109 -0.094380826 0.068647414, -0.015525788 -0.10215208 0.071306631, -0.0065447688 -0.11985031 0.07432875, -0.11929075 0.013249993 0.074336231, -0.014190882 -0.10516909 0.072088808, -0.093532354 0.021192193 0.068654031, -0.014292419 -0.10373995 0.071711212, -0.10900092 0.015942693 0.073024541, -0.012556925 -0.10396436 0.071711227, -0.011223614 -0.099932164 0.070417389, -0.10385495 0.017476469 0.071883082, 0.01708366 -0.10331681 0.071711406, 0.015575767 -0.099346846 0.070417449, -0.016241744 -0.089927346 0.066573888, 0.018768832 -0.10444906 0.072088838, -0.0062746704 -0.11490422 0.073836163, 0.018807724 -0.10301706 0.071711197, -0.1143674 0.012702852 0.073843449, -0.11965592 0.0093993843 0.074335992, -0.089118853 0.020192236 0.066580147, -0.006006822 -0.11000142 0.073017493, 0.01997079 -0.10137686 0.071306884, 0.022239313 -0.1023311 0.071711227, -0.10420668 0.015241325 0.071882933, 0.022176325 -0.098084658 0.070417523, 0.098810315 -0.034672827 0.071715087, 0.00018545985 -0.12002888 0.07432887, 0.10061297 -0.033739299 0.072092772, -0.099161625 0.016686708 0.070423976, -0.10948752 0.012160778 0.073024392, -0.0057426542 -0.10516328 0.071876347, 0.099375814 -0.033016741 0.07171534, -0.11984633 0.0065404773 0.074335948, -0.11471771 0.0090113282 0.073843136, 0.0026206821 -0.12000027 0.074328691, 0.098496318 -0.031208515 0.071310624, 0.10042354 -0.029677808 0.071715325, -0.099497348 0.014552474 0.070423886, 0.00017781556 -0.11507529 0.073836282, -0.099574715 -0.00079169869 0.070079461, -0.094573691 0.015914589 0.068653628, -0.09589757 0.0011069775 0.068652749, -0.099492595 -0.0041185617 0.070079342, -0.095757544 -0.0053006709 0.068652421, -0.0054832548 -0.10041091 0.070417464, -0.10467181 0.011625767 0.071882874, -0.049439296 -0.091861159 0.071598977, -0.11490013 0.0062704086 0.073842943, 0.002512455 -0.11504793 0.073836237, -0.046398103 -0.093434066 0.071598962, -0.1098226 0.0086265206 0.073024288, 0.00017014146 -0.11016521 0.073017493, -0.016332731 -0.098233163 0.070074171, -0.094893903 0.013879091 0.068653569, -0.013041347 -0.098724097 0.070074067, -0.010704353 -0.095308632 0.068647325, 0.006915018 -0.1198296 0.074328735, -0.090111092 0.01516366 0.06657964, -0.005229488 -0.095765233 0.068647251, 0.017338917 -0.098060548 0.070074067, 0.014855087 -0.094750345 0.068647474, -0.099941596 0.011100382 0.070423543, 0.0024053454 -0.11013904 0.073017478, 0.020605907 -0.097426474 0.070074156, 0.021150231 -0.093546659 0.068647534, 0.00016273558 -0.10531995 0.071876287, 0.094323412 -0.031922758 0.070077807, -0.10999733 0.0060026646 0.073024109, 0.0066296458 -0.11488444 0.073836207, 0.095337391 -0.028753102 0.070077926, -0.10499224 0.0082469881 0.07188274, -0.095426202 0.00017142296 0.068450645, 0.010629624 -0.11955732 0.074328825, -0.090416059 0.013224065 0.066579565, -0.091372445 0.001054883 0.066579059, -0.0049826801 -0.091246456 0.066573918, -0.010199264 -0.090811342 0.066573933, -0.094050899 -0.0016212761 0.067853421, -0.095317394 0.010586679 0.068653286, 0.0022995472 -0.10529491 0.071876258, -0.095378786 -0.0030174553 0.068450451, -0.091239169 -0.0050504506 0.066578731, 0.00015535951 -0.10056043 0.070417419, -0.0482665 -0.087660402 0.070248351, -0.10515919 0.0057384372 0.071882516, 0.0063468218 -0.10998237 0.073017418, -0.045968503 -0.087310284 0.069742098, -0.1002474 0.007874161 0.070423588, -0.045363903 -0.089197248 0.070248082, 0.010190964 -0.11462325 0.073836237, -0.090819776 0.010087162 0.066579491, -0.014733672 -0.094285935 0.068445534, 0.013622791 -0.11925343 0.074328661, 0.0021956414 -0.1005365 0.070417389, -0.013184533 -0.093140095 0.06784834, -0.011574924 -0.094725579 0.068445385, -0.10040708 0.0054791868 0.070423469, 0.00014817715 -0.095907807 0.068647504, 0.015699252 -0.09412995 0.068445548, 0.01415424 -0.09027952 0.066573918, -0.095609263 0.0075098872 0.068653077, 0.0060674399 -0.10514495 0.071876243, 0.017238393 -0.092475802 0.067848325, 0.0097561628 -0.10973248 0.073017672, 0.018835798 -0.093552738 0.068445548, 0.020152092 -0.089132398 0.066573858, 0.09008871 -0.03147164 0.068448961, 0.013060644 -0.11433202 0.073836327, -0.095761433 0.0052255392 0.068653047, 0.00209409 -0.095885068 0.068647459, -0.091097653 0.007155478 0.066579223, 0.089377597 -0.029327065 0.067851961, 0.091089785 -0.028443813 0.068449169, 0.0001412183 -0.091382176 0.066573933, -0.090483993 -0.00025758147 0.066125453, -0.090425014 -0.0032808781 0.066125125, 0.0057934523 -0.10039359 0.070417374, -0.045434147 -0.083414167 0.068254605, -0.091242626 0.0049789846 0.066579118, 0.0093271583 -0.10490614 0.071876287, -0.042672276 -0.084860265 0.06825453, 0.012503311 -0.10945362 0.073017508, -0.014385328 -0.08933723 0.066120267, 0.0019952953 -0.091360629 0.066573828, -0.011392236 -0.089768022 0.066120237, -0.11924914 -0.013626993 0.074334711, 0.015300423 -0.089185119 0.066120416, 0.018271804 -0.088623971 0.066120267, 0.0055253357 -0.095748603 0.068647236, 0.0089056343 -0.10016552 0.070417494, 0.085560679 -0.029444993 0.066123858, 0.086496785 -0.026569486 0.066124111, 0.011953369 -0.10463944 0.071876332, -0.11432771 -0.013064772 0.073841855, -0.042748198 -0.080259532 0.066349238, 0.0052646548 -0.091230631 0.066573992, 0.0084936321 -0.095531106 0.068647295, -0.1094493 -0.012507379 0.073022947, -0.11829794 -0.020291865 0.074334204, 0.011413097 -0.099910736 0.070417464, -0.10463551 -0.011957347 0.071881413, 0.0080926865 -0.091023296 0.066573963, -0.11788886 -0.022547245 0.074334122, 0.010885015 -0.095288068 0.068647519, -0.11341549 -0.019454688 0.073841631, -0.099906772 -0.011417121 0.070422605, 0.010371372 -0.090791851 0.066573918, -0.11302352 -0.021617055 0.073841512, -0.10857613 -0.018624634 0.073022634, -0.11697409 -0.02689296 0.074333936, 0.033405244 -0.11528653 0.074329019, -0.095284268 -0.010888934 0.068652138, -0.10820065 -0.020694762 0.073022678, -0.10380061 -0.017805547 0.071881101, 0.032026544 -0.1105288 0.073836416, -0.1121466 -0.025783092 0.073841229, -0.11611973 -0.03037113 0.074333705, -0.0907882 -0.010375142 0.066578344, 0.030660048 -0.10581279 0.073017791, -0.10344173 -0.0197846 0.071880996, 0.039816603 -0.11323217 0.074329153, -0.099109694 -0.017000884 0.070422187, -0.10736129 -0.024683297 0.073022366, 0.029311538 -0.1011588 0.071876526, -0.11132756 -0.029117733 0.073840827, -0.11528244 -0.033409506 0.074333638, 0.041837439 -0.1125012 0.074329138, -0.098767042 -0.01889056 0.07042183, 0.038173363 -0.10855931 0.07383652, -0.094524205 -0.016214401 0.06865187, -0.10263894 -0.023597687 0.071880788, 0.027986869 -0.0965873 0.070417523, -0.10657708 -0.027875394 0.073022157, 0.040110782 -0.10785833 0.073836684, -0.11052462 -0.032030821 0.073840782, 0.036544561 -0.10392714 0.073017806, -0.094197348 -0.018016666 0.068651766, 0.046102807 -0.11082146 0.074329212, -0.090063676 -0.015449435 0.066578016, 0.026692048 -0.09211874 0.068647593, -0.11383223 -0.038059235 0.074333243, 0.038399249 -0.10325614 0.07301794, -0.098000795 -0.02253136 0.070421785, 0.034937203 -0.099356145 0.07187663, -0.10188939 -0.026649624 0.071880639, 0.044200063 -0.10624808 0.073836699, -0.1058085 -0.030664206 0.073021919, -0.089752302 -0.017166615 0.066577867, 0.049257934 -0.10945547 0.074329361, -0.11322793 -0.03982091 0.074333459, 0.025432467 -0.087771773 0.066574007, 0.036710352 -0.098714799 0.071876809, -0.10913426 -0.036488652 0.073840551, 0.033358395 -0.094866127 0.070417628, -0.093466416 -0.021489084 0.068651497, -0.097284958 -0.025445223 0.070421755, 0.042314082 -0.10171458 0.073018, -0.10115477 -0.029315591 0.071880445, 0.047225043 -0.10493839 0.073836878, -0.10855503 -0.03817758 0.073840581, 0.052243903 -0.10806224 0.07432954, 0.035051331 -0.094253719 0.070417717, -0.10447742 -0.034931809 0.07302171, 0.031814888 -0.090477109 0.068647623, -0.089056015 -0.020475149 0.066577643, -0.092783809 -0.024268091 0.068651348, 0.040452898 -0.097240835 0.071876884, -0.096583411 -0.027990729 0.070421264, 0.045210063 -0.10046089 0.073018119, -0.10392275 -0.036548853 0.07302165, 0.050087735 -0.10360262 0.073836699, 0.033429787 -0.089893073 0.068647772, -0.1110363 -0.045577407 0.074333042, 0.030313611 -0.086207598 0.066574082, -0.099882126 -0.033395529 0.071880326, 0.056458503 -0.10592112 0.07432963, -0.088405564 -0.023122996 0.066577643, 0.038624838 -0.092846483 0.070417911, -0.092114761 -0.026695877 0.068651289, 0.043221489 -0.096042424 0.071876705, -0.099352151 -0.034941196 0.071880206, 0.047950447 -0.09918192 0.073018238, -0.10645359 -0.043696553 0.073840149, 0.031852081 -0.0856511 0.066574022, -0.095368415 -0.031886429 0.070421308, 0.058220685 -0.10496303 0.074329585, -0.087768197 -0.025436103 0.066577524, 0.054128453 -0.10154986 0.073836878, 0.036837667 -0.088550895 0.068647832, -0.094862252 -0.033362269 0.070421115, -0.10191128 -0.041832119 0.073021233, 0.041268378 -0.091702223 0.07041797, 0.045841411 -0.094819725 0.071876794, -0.090956032 -0.030411184 0.06865114, 0.055817664 -0.10063118 0.073837012, -0.10805805 -0.052247971 0.074332513, 0.051818714 -0.097216785 0.073018253, -0.090473101 -0.031818926 0.068650886, -0.097428918 -0.039992273 0.071879953, 0.035099462 -0.084372401 0.066574052, -0.086664021 -0.028976291 0.066577271, 0.03935878 -0.087459266 0.068647817, 0.043769851 -0.090534687 0.070417881, -0.10359845 -0.050091863 0.073839881, -0.086204007 -0.030317396 0.066577271, 0.053435877 -0.096337378 0.073018327, -0.093025997 -0.038185149 0.07042098, 0.0634069 -0.10191339 0.074329838, 0.049539626 -0.092940956 0.071876958, -0.099177778 -0.047954649 0.07302101, 0.037501648 -0.083332509 0.066574186, -0.10495869 -0.058224648 0.074332237, 0.041744664 -0.08634609 0.068647847, -0.088721886 -0.036418408 0.068650663, 0.051085755 -0.092100263 0.071876973, -0.10397122 -0.059970587 0.074332073, 0.060790017 -0.097707629 0.073837176, 0.047300816 -0.088740945 0.07041797, -0.094815657 -0.045845568 0.071879521, 0.03977491 -0.082271695 0.06657435, -0.10062692 -0.055821925 0.073839635, 0.048777044 -0.087938219 0.070418134, -0.084535331 -0.034700096 0.066577032, -0.099680215 -0.057495505 0.073839538, 0.058196142 -0.093538553 0.073018387, 0.045112267 -0.084635198 0.068648085, -0.090530843 -0.043773711 0.070420519, 0.069606081 -0.09778437 0.074330077, -0.096333131 -0.053440154 0.073020637, 0.046520233 -0.083869576 0.068648055, 0.055636406 -0.08942458 0.071877331, -0.10152902 -0.06401819 0.074331895, -0.095426917 -0.055042326 0.073020592, 0.042983547 -0.080641538 0.066574439, -0.08634226 -0.041748554 0.06865038, 0.066733435 -0.093748719 0.073837459, -0.092096001 -0.051089764 0.071879238, 0.044325083 -0.079912007 0.066574425, -0.097338855 -0.061376274 0.073839277, 0.053122178 -0.085383415 0.070418388, -0.099733636 -0.066781014 0.074331723, 0.063885748 -0.089748681 0.073018819, -0.091229603 -0.052621573 0.071879417, -0.082267866 -0.03977859 0.066576555, 0.074979231 -0.093727589 0.074330121, -0.087934196 -0.048780978 0.070420355, 0.05066447 -0.081433207 0.068648413, -0.093185335 -0.058757573 0.073020294, 0.07642445 -0.09255293 0.074330375, -0.095617697 -0.064025044 0.07383915, 0.061075822 -0.085801274 0.071877331, -0.097780049 -0.069610208 0.074331455, 0.071884766 -0.089859605 0.073837772, -0.087106973 -0.050243586 0.070420235, -0.083865628 -0.046524167 0.068650171, 0.048273638 -0.077590436 0.066574588, -0.089086905 -0.056173265 0.071878776, 0.07327041 -0.088733435 0.073837712, -0.091537654 -0.061293215 0.073020339, 0.058315903 -0.081923902 0.070418388, 0.068817362 -0.086025417 0.073018894, -0.093744703 -0.066737592 0.073839076, -0.083076686 -0.047918975 0.068650067, -0.079908207 -0.044328898 0.066576496, 0.080116361 -0.089376122 0.074330598, 0.070143864 -0.084947258 0.073018849, -0.095050842 -0.073293269 0.07433138, 0.05561775 -0.078133553 0.068648264, -0.085060924 -0.053634793 0.070420086, 0.065790445 -0.082241774 0.07187748, -0.087511435 -0.058597505 0.071878865, 0.076809958 -0.085687608 0.073837683, -0.089744508 -0.063889921 0.073020041, 0.082435265 -0.08724165 0.074330717, -0.079156503 -0.045657843 0.066576362, 0.067058578 -0.08121106 0.071877703, -0.093723424 -0.074983358 0.074331298, 0.052993283 -0.074446738 0.066574723, -0.091128007 -0.070268601 0.073838696, 0.062817395 -0.078525394 0.070418701, -0.081125274 -0.051153362 0.068649977, 0.073532358 -0.082031429 0.073018998, -0.083556652 -0.05594939 0.070419788, 0.079033226 -0.08364135 0.073837921, -0.085797206 -0.061080068 0.071878687, 0.085001349 -0.084743351 0.074330792, -0.089855343 -0.071888894 0.073838577, 0.064028189 -0.077541173 0.070418701, -0.087239534 -0.067270398 0.073019922, 0.059910879 -0.074892133 0.068648458, -0.077297345 -0.048739582 0.066576034, 0.070298091 -0.07842353 0.071877673, -0.07969068 -0.053360909 0.068649843, 0.075660795 -0.080072403 0.073019087, -0.081920013 -0.058319867 0.070419788, 0.081493378 -0.081246138 0.073838085, -0.089943431 -0.079478353 0.074331068, 0.061065808 -0.073953629 0.068648502, -0.08602114 -0.068821579 0.073019773, 0.057083875 -0.071358413 0.066574931, -0.083402276 -0.064311773 0.071878627, 0.088078037 -0.081540883 0.07433103, -0.075930268 -0.050843 0.06657593, 0.067121372 -0.074879616 0.070418879, -0.078129798 -0.055621505 0.068649709, 0.072332948 -0.076550752 0.071877778, -0.086231351 -0.076198399 0.073838457, 0.078016028 -0.077779442 0.073019251, -0.082237706 -0.065794647 0.071878523, 0.058184355 -0.070464015 0.066574827, -0.079633296 -0.061405629 0.070419714, 0.089618921 -0.079843938 0.074331015, -0.074443057 -0.052997053 0.066575974, 0.084442973 -0.078175753 0.073838413, -0.082551852 -0.072947234 0.073019698, 0.064015657 -0.071415126 0.068648785, 0.069064185 -0.073091418 0.070418939, -0.078521192 -0.062821269 0.070419654, -0.075948879 -0.058564484 0.068649411, 0.074584529 -0.074358463 0.071877912, -0.084739037 -0.085005552 0.074330807, 0.085920423 -0.076548845 0.073838368, 0.080839649 -0.074840099 0.073019519, -0.078920797 -0.069738895 0.07187824, 0.060995087 -0.068045348 0.066575035, -0.074888259 -0.059914976 0.068649158, -0.072365031 -0.055800974 0.066575706, 0.065868735 -0.069709778 0.068648919, -0.081241921 -0.081497371 0.073838189, 0.07121405 -0.070998281 0.070419207, -0.075354517 -0.066587269 0.070419237, -0.071354568 -0.0570876 0.066575825, 0.082254082 -0.073282689 0.073019564, -0.07777527 -0.078020155 0.073019311, 0.077284113 -0.071548522 0.071878135, 0.062760592 -0.066420376 0.066575274, 0.067919061 -0.06771341 0.068648949, 0.073791593 -0.068315178 0.070419282, 0.055524632 0.14688826 0.047008067, 0.057261527 0.14478576 0.05067037, 0.059130028 0.14547443 0.047008023, 0.053521171 0.13842845 0.066759422, 0.053151056 0.14544293 0.052846387, 0.052270323 0.14247933 0.06000793, 0.055364549 0.143987 0.05429326, 0.051885471 0.14821285 0.047008052, 0.052091911 0.14254463 0.060007915, 0.052923247 0.14049691 0.06340602, 0.047925413 0.14724749 0.052846655, 0.048214868 0.14944717 0.047008261, 0.045385584 0.14805013 0.052846611, 0.05118145 0.14005321 0.065425456, 0.046970591 0.1443131 0.060008064, 0.043595776 0.14703038 0.056446299, 0.041789234 0.14589778 0.060008153, 0.043138117 0.14273581 0.065425918, 0.046149597 0.14179081 0.065425664, 0.043921977 0.14064032 0.06875205, 0.051120698 0.13535851 -0.073043063, 0.051689476 0.13522956 -0.072960392, 0.050997168 0.13430104 -0.073829919, 0.050565138 0.13522449 -0.073334917, 0.049434081 0.13488427 -0.073829919, 0.048274994 0.13446808 -0.074194252, 0.048937127 0.13393608 -0.074284703, 0.047835767 0.13545936 -0.073829666, 0.048484221 0.13395262 -0.074324012, 0.047691375 0.13423687 -0.074324086, 0.047179714 0.13426477 -0.074360132, 0.044620663 0.13483363 -0.074418917, 0.046813369 0.13553891 -0.073969707, 0.047403499 0.13467875 -0.074227065, 0.050333872 0.13565302 -0.073043048, 0.049880892 0.1357092 -0.073143288, 0.048972115 0.13580942 -0.073334664, 0.052432686 0.13225201 -0.074370816, 0.054009855 0.13162094 -0.074369863, 0.053106278 0.13273689 -0.074158803, 0.054273099 0.13263541 -0.074011326, 0.05441545 0.13357797 -0.073441982, 0.052522182 0.1327801 -0.074222788, 0.052139312 0.13407516 -0.073709503, 0.052824214 0.13495925 -0.072789073, 0.054437608 0.13432044 -0.072785184, 0.049842834 0.13389486 -0.074194342, 0.044765383 0.1356535 -0.074202046, 0.046396896 0.13670108 -0.073342323, 0.045883924 0.13668495 -0.073484331, 0.044853702 0.13662973 -0.073742554, 0.044829518 0.13759467 -0.073019743, 0.046416596 0.13710609 -0.072982609, 0.045888066 0.13727114 -0.072995067, 0.051381096 0.13298833 -0.074292898, 0.050810218 0.13308769 -0.074324042, 0.050489306 0.13335872 -0.074284732, 0.081493318 -0.081237793 -0.073847219, 0.075660855 -0.080064446 -0.073028296, 0.078015938 -0.077771246 -0.073028192, -0.070055425 -0.078632414 -0.071886703, -0.074354351 -0.074580669 -0.071886435, -0.070994258 -0.071210176 -0.070427239, 0.074571833 -0.060300618 -0.068656191, 0.06822972 -0.060780734 -0.06658259, 0.071052998 -0.057455152 -0.066582307, 0.071608707 -0.063790977 -0.068656415, -0.066889524 -0.075078726 -0.070427507, 0.078636274 -0.070051491 -0.071886137, 0.073791534 -0.068307191 -0.070427015, 0.075082541 -0.06688565 -0.070426926, 0.077284187 -0.071540475 -0.071886241, -0.05967924 -0.075069398 -0.068656981, -0.063794717 -0.071604967 -0.068656772, -0.060784489 -0.068226069 -0.066582933, 0.080839694 -0.074831992 -0.073028043, 0.074584648 -0.074350506 -0.071886495, -0.056863099 -0.071527004 -0.066583171, -0.055052549 -0.072929591 -0.066583186, -0.084739134 -0.084997267 -0.074340433, 0.085001335 -0.084734976 -0.074340492, 0.082435191 -0.087233365 -0.074340478, 0.079033181 -0.083633035 -0.073847413, -0.089943409 -0.079470038 -0.074339926, -0.086231336 -0.076190203 -0.073847204, -0.081241921 -0.081489235 -0.073847368, -0.073278546 -0.082250118 -0.073028445, 0.078189388 -0.063226044 -0.070426956, -0.077775314 -0.078012019 -0.073028192, 0.082254082 -0.073274404 -0.073027819, -0.062574476 -0.078711152 -0.070427597, 0.084442899 -0.078167439 -0.07384716, 0.074606493 -0.052759379 -0.066582173, -0.057778969 -0.076541513 -0.068657055, -0.052762821 -0.074602753 -0.066583261, 0.081890151 -0.066218644 -0.071885884, -0.076544777 -0.085916281 -0.073847517, 0.085920364 -0.07654053 -0.073847175, -0.065536082 -0.08243677 -0.071886808, 0.088077962 -0.081532389 -0.07434018, -0.060581952 -0.080254704 -0.070427701, 0.078301236 -0.055372268 -0.068656087, -0.055375889 -0.078297526 -0.068657234, 0.085657731 -0.069265306 -0.073027849, -0.079839692 -0.089614987 -0.074340641, 0.089619011 -0.079835594 -0.07434012, -0.050058216 -0.076443791 -0.066583395, 0.08209978 -0.05805853 -0.070426568, -0.068551213 -0.086229473 -0.073028624, 0.077447474 -0.048493057 -0.066581786, -0.063449323 -0.084053397 -0.071887001, 0.089475721 -0.072352618 -0.073846981, -0.0580623 -0.082095951 -0.070427984, 0.085985497 -0.060806453 -0.071885794, -0.048496678 -0.077443808 -0.066583514, -0.052537218 -0.080229759 -0.06865716, 0.081282884 -0.050894707 -0.068655729, -0.071606681 -0.0900729 -0.073847711, 0.093327299 -0.075467348 -0.074339882, -0.066368371 -0.087920576 -0.073028699, 0.089941546 -0.063604206 -0.073027357, -0.060810462 -0.085981578 -0.07188727, 0.085226119 -0.05336386 -0.070426375, -0.050898463 -0.081279337 -0.068657324, 0.080044821 -0.044074386 -0.066581711, -0.055085927 -0.084121913 -0.070428088, -0.074689284 -0.09395054 -0.074340895, 0.089260012 -0.055889606 -0.071885526, -0.069326654 -0.091839433 -0.073847756, 0.081074253 -0.042151093 -0.066581368, -0.063608214 -0.089937478 -0.073028967, 0.084009051 -0.046257168 -0.068655357, -0.044840217 -0.079616725 -0.066583574, -0.053367555 -0.085222304 -0.070428118, -0.057693154 -0.088103652 -0.071887165, 0.093366563 -0.05846113 -0.073027059, -0.072310895 -0.095792979 -0.07434088, 0.085089311 -0.044238597 -0.068655357, 0.088084534 -0.048501045 -0.070425957, -0.066443428 -0.093946278 -0.073848099, -0.047060892 -0.083559752 -0.068657354, 0.082390413 -0.039516687 -0.066581398, 0.09752813 -0.061066866 -0.073846161, -0.055893511 -0.089256108 -0.071887314, 0.093950406 -0.066439182 -0.073846564, -0.060347423 -0.092157125 -0.073028907, 0.089217231 -0.046384811 -0.070425779, 0.092253566 -0.050796807 -0.071885034, -0.069303647 -0.097990662 -0.074340999, -0.049343973 -0.087613493 -0.070428222, 0.086470693 -0.041473776 -0.068655103, -0.058465108 -0.0933626 -0.073028997, 0.083708778 -0.036641687 -0.066581175, -0.063037351 -0.09626472 -0.073848218, 0.10172643 -0.063695818 -0.074339077, 0.09799473 -0.069299459 -0.074339315, 0.093439832 -0.048580319 -0.071884915, -0.051679373 -0.091760278 -0.071887478, 0.096497715 -0.053133965 -0.073026702, -0.061071038 -0.097523987 -0.073848173, -0.065750927 -0.10040894 -0.074341372, 0.090665594 -0.04348582 -0.070425719, 0.084476694 -0.034834892 -0.066581085, 0.087854326 -0.03845647 -0.068654865, -0.054056987 -0.095982164 -0.073029101, -0.063699931 -0.10172233 -0.074341252, 0.097738773 -0.050815523 -0.073026657, 0.10079895 -0.055502325 -0.073846012, -0.034838617 -0.084472984 -0.066583827, 0.094956785 -0.045544267 -0.071884781, -0.039520532 -0.082386762 -0.066583782, 0.088660389 -0.036560267 -0.06865482, -0.056466535 -0.1002602 -0.073848516, 0.092116311 -0.040322036 -0.070425659, -0.036563903 -0.088656694 -0.068657711, -0.041477636 -0.086467057 -0.068657592, 0.10209528 -0.053080529 -0.073845759, 0.10513805 -0.057891726 -0.074338913, -0.058897227 -0.10457638 -0.074341476, 0.099325538 -0.047639728 -0.073026493, 0.085969344 -0.030968726 -0.066580951, -0.038337722 -0.092957616 -0.070428625, -0.043489933 -0.090661705 -0.070428401, -0.030047178 -0.086293608 -0.066583797, 0.092961445 -0.038333833 -0.070425332, 0.096476197 -0.042230725 -0.071884796, 0.10649014 -0.055365711 -0.074338779, -0.040152267 -0.097357422 -0.071887791, -0.045548186 -0.094952852 -0.071887583, 0.10375278 -0.049763262 -0.073845595, -0.028082415 -0.086952746 -0.066584051, 0.090227038 -0.032502502 -0.068654507, -0.031535298 -0.090567142 -0.068657801, 0.097361296 -0.040148258 -0.071884468, -0.041999593 -0.10183659 -0.073029459, -0.047643676 -0.099321485 -0.073029503, 0.10091484 -0.044173717 -0.073026299, 0.10821906 -0.051905513 -0.074338481, -0.029473245 -0.091259152 -0.068657845, 0.094604224 -0.034079462 -0.070425138, -0.03306517 -0.094960928 -0.070428506, 0.10184057 -0.041995525 -0.07302615, -0.025161237 -0.087842554 -0.066584036, -0.043871567 -0.10637587 -0.073848799, -0.049767345 -0.10374859 -0.07384859, 0.10541283 -0.046142697 -0.073845476, -0.030903086 -0.095686346 -0.07042858, 0.099081814 -0.035692483 -0.071884394, -0.034630015 -0.099455595 -0.071887821, 0.10637997 -0.043867588 -0.073845342, 0.10995057 -0.04812929 -0.074338228, -0.026407167 -0.092193127 -0.068657979, 0.10364021 -0.037334681 -0.073025808, -0.022211805 -0.088634253 -0.066584259, -0.045759976 -0.1109553 -0.074341893, -0.0519097 -0.10821483 -0.07434161, 0.11095934 -0.045755982 -0.074338034, 0.10825975 -0.038998872 -0.073844925, -0.03236562 -0.10021535 -0.071887925, 0.11291999 -0.040677816 -0.074337929, -0.036223292 -0.10403138 -0.073029622, -0.02768831 -0.096665531 -0.070428595, -0.020196006 -0.089115232 -0.06658408, -0.11751607 -0.0025624633 -0.074130133, -0.11258258 -0.0024547875 -0.073473945, -0.11489567 -0.0063512027 -0.073843077, -0.11506356 0.0013370812 -0.073842764, -0.12001677 0.0013945103 -0.074335441, -0.023311645 -0.093023956 -0.068657935, -0.033854693 -0.10482615 -0.073029563, -0.037837908 -0.10866833 -0.073848978, -0.017015427 -0.11630183 -0.07413657, -0.020452842 -0.11323491 -0.073849201, -0.0163012 -0.1114192 -0.073480099, -0.021333486 -0.11810955 -0.074342191, -0.012843698 -0.11434814 -0.073849142, -0.028998747 -0.10124084 -0.07188794, -0.021196157 -0.093528599 -0.06865795, 0.022077143 -0.11544797 -0.074136645, 0.025377333 -0.112234 -0.073849022, 0.026469693 -0.11706561 -0.074342191, 0.018591315 -0.11857209 -0.074342281, 0.017824054 -0.11367837 -0.073849156, 0.02115038 -0.11060134 -0.073480099, -0.024442673 -0.097536802 -0.070428804, 0.093732506 -0.070924103 -0.074134126, -0.035363764 -0.10949841 -0.073848963, -0.03946656 -0.11334643 -0.074341938, 0.11185555 -0.03611958 -0.07413213, 0.10715982 -0.034603029 -0.073475659, -0.030332968 -0.10589883 -0.073029682, -0.10894148 -0.0005543828 -0.072768718, -0.11015368 0.0012799799 -0.073023751, -0.1053088 0.0012239814 -0.071882024, -0.016241744 -0.089919925 -0.066584259, -0.10886188 -0.0041944981 -0.072768793, -0.022224516 -0.098065913 -0.07042864, -0.1051551 -0.0058126748 -0.071882352, -0.10999294 -0.0060802996 -0.073024109, -0.12117167 -0.0048138499 -0.074407771, -0.11984152 -0.0066249669 -0.074336007, -0.02559942 -0.10215324 -0.071887881, -0.089118809 0.020199537 -0.06657809, -0.054226354 -0.10008982 -0.073674142, -0.036886051 -0.11421224 -0.074342057, -0.054287523 -0.10425249 -0.074135944, -0.093532264 0.021199763 -0.068651557, -0.03168495 -0.11061898 -0.073849037, -0.050912187 -0.10181555 -0.073674276, -0.057255134 -0.10689598 -0.074413449, -0.017046124 -0.094373167 -0.068658024, -0.098069951 0.022228301 -0.070421934, -0.054234371 -0.10845986 -0.074413627, -0.023276359 -0.10270756 -0.071888074, -0.017569587 -0.10751286 -0.072774544, -0.019580215 -0.10840306 -0.073029906, -0.090111077 0.015170813 -0.066578299, -0.018718943 -0.10363507 -0.071888089, -0.026777297 -0.10685322 -0.073029757, -0.013967052 -0.10803992 -0.072774753, -0.011754856 -0.10465387 -0.071888044, -0.012295648 -0.10946888 -0.07303001, -0.10271147 0.023280144 -0.071881026, -0.033048913 -0.11538103 -0.074342072, -0.018842578 -0.11979043 -0.074414328, -0.015475258 -0.12027192 -0.074414343, -0.013396546 -0.11927071 -0.07434231, -0.090416178 0.013231575 -0.066578344, -0.017873138 -0.098951519 -0.070428744, -0.094573691 0.01592207 -0.068652064, -0.024347141 -0.10743299 -0.073029846, 0.018670797 -0.1073271 -0.072774619, 0.017063424 -0.10882756 -0.073029876, 0.016312838 -0.10404089 -0.071888, 0.022246793 -0.10664326 -0.072774589, 0.024294525 -0.10744485 -0.073029861, -0.10743693 0.02435106 -0.073022649, -0.027970806 -0.11161587 -0.073849037, 0.023225963 -0.10271895 -0.071887895, 0.089659289 -0.07014221 -0.073672399, -0.094893932 0.01388675 -0.068651944, 0.091873094 -0.067216814 -0.073672295, -0.09916167 0.016694516 -0.070422277, 0.095821276 -0.074319839 -0.074411526, 0.09786813 -0.071603179 -0.074411511, -0.025432393 -0.1122216 -0.073848948, -0.090819806 0.010094553 -0.066578478, 0.10309687 -0.035204023 -0.07277061, -0.029174834 -0.11642092 -0.074342117, -0.11222553 0.025436372 -0.073841304, 0.10421576 -0.031739295 -0.072770342, 0.11496887 -0.038569897 -0.074409634, -0.099497423 0.014560431 -0.070422411, -0.10385497 0.017484516 -0.071881309, 0.1160055 -0.035330325 -0.074409604, -0.10471532 0.00034213066 -0.071717262, -0.10054977 0.0011687875 -0.070423231, -0.026527241 -0.11705256 -0.074342221, -0.095317498 0.010594338 -0.068652093, -0.091097757 0.0071628988 -0.066578716, -0.10611196 -0.0011311173 -0.072094649, -0.10470642 -0.0014076829 -0.071717247, -0.11705668 0.026531309 -0.074334115, -0.1032823 -0.0028274655 -0.071312651, -0.0049825758 -0.091239005 -0.066584349, -0.10460068 -0.0049056113 -0.071717471, -0.10420664 0.015249282 -0.07188122, -0.010199279 -0.090803891 -0.066584244, -0.10040306 -0.0055497587 -0.070423529, -0.10863304 0.01828891 -0.073022664, -0.052972764 -0.095888734 -0.072904035, -0.099941581 0.011108279 -0.07042262, -0.052327886 -0.097860098 -0.07318829, -0.051391914 -0.096745223 -0.072903931, -0.091242552 0.004986316 -0.066578686, -0.0052294582 -0.095757574 -0.068658203, -0.095609352 0.0075174868 -0.068652198, -0.010704324 -0.095301032 -0.068658099, -0.049415693 -0.096177429 -0.072592512, -0.048188969 -0.098379821 -0.072904333, -0.109001 0.015950829 -0.073023006, -0.0054831952 -0.1004031 -0.070428923, -0.011223629 -0.099924386 -0.070428878, -0.017750561 -0.1031965 -0.071722955, -0.11347505 0.019103944 -0.073841706, -0.015525937 -0.10214403 -0.071318403, -0.10467185 0.011633933 -0.071881637, 0.0001412183 -0.091374755 -0.066584229, -0.014292344 -0.10373193 -0.071723133, -0.014190912 -0.10516086 -0.072100595, -0.095761329 0.0052331686 -0.068652451, -0.012557015 -0.10395622 -0.071723029, -0.10024741 0.0078820586 -0.070422888, -0.0057426095 -0.10515526 -0.071888164, 0.017083809 -0.10330889 -0.071723014, 0.015575647 -0.099339038 -0.070428759, -0.11385931 0.016661674 -0.073841944, 0.001995191 -0.091353148 -0.066584289, -0.11835989 0.01992619 -0.074334398, 0.018768802 -0.10444102 -0.07210061, 0.00014814734 -0.095900208 -0.068658188, 0.018807635 -0.10300899 -0.071722776, 0.019970775 -0.10136881 -0.071318373, -0.10948743 0.012168914 -0.073023006, 0.022239327 -0.10232303 -0.071722984, 0.02217631 -0.098076791 -0.070428669, -0.09137252 0.0010622442 -0.066579148, 0.098810375 -0.03466481 -0.07171905, -0.0060068667 -0.10999328 -0.073030114, -0.10040703 0.0054870248 -0.070423067, -0.1049922 0.0082550049 -0.07188186, 0.098142624 -0.032295883 -0.071314439, 0.0020940155 -0.095877379 -0.068658069, 0.099913538 -0.031343549 -0.071718916, 0.00015538931 -0.10055262 -0.070428744, 0.10133962 -0.031481236 -0.072096467, -0.11876051 0.017378807 -0.074334666, 0.10042346 -0.029669672 -0.071718752, -0.11436751 0.012711346 -0.073842198, 0.0052645057 -0.091223061 -0.06658417, -0.09957473 -0.00078392029 -0.070079744, -0.09589763 0.0011147857 -0.06865266, -0.0062745512 -0.11489603 -0.073849231, -0.099492714 -0.0041107535 -0.070080161, -0.10515909 0.0057465434 -0.071882039, 0.0021956414 -0.10052869 -0.070428774, -0.095757723 -0.0052930415 -0.068653062, -0.049439326 -0.091853052 -0.071609482, 0.00016264617 -0.10531175 -0.071888193, -0.10982269 0.0086348355 -0.073023513, -0.046398208 -0.093426019 -0.071609586, -0.11929066 0.013258338 -0.074334949, 0.0055253357 -0.095740944 -0.068658113, -0.016332775 -0.098225236 -0.070085377, -0.013041258 -0.098716348 -0.070085362, 0.0080927163 -0.091015905 -0.066584125, -0.10999732 0.0060108006 -0.073023543, -0.0065447241 -0.11984214 -0.074342191, -0.11471772 0.0090195835 -0.073842302, 0.017338917 -0.09805274 -0.070085317, 0.014855072 -0.094742864 -0.068658054, 0.0022994727 -0.10528684 -0.071888164, 0.020605832 -0.097418606 -0.070085093, 0.021150261 -0.09353897 -0.068658099, 0.00017021596 -0.11015704 -0.073030084, 0.09414427 -0.032439798 -0.070081666, 0.0057934076 -0.10038573 -0.070428759, 0.095175698 -0.029275835 -0.070081428, -0.11490005 0.0062786043 -0.073842555, -0.11965589 0.0094075501 -0.074334949, 0.0084935129 -0.095523447 -0.068658203, -0.095426157 0.00017902255 -0.068450958, 0.010371506 -0.090784371 -0.066584185, 0.0024053454 -0.11013091 -0.07303004, -0.094050884 -0.0016136765 -0.067853704, -0.095378757 -0.0030097961 -0.068451002, 0.00017783046 -0.11506698 -0.073849216, -0.09123908 -0.0050431192 -0.066579461, -0.11984627 0.0065487623 -0.074335307, -0.048266485 -0.087652624 -0.070258006, 0.0060674995 -0.10513699 -0.071888104, -0.045968473 -0.087302417 -0.069752082, 0.0089055896 -0.10015762 -0.070428923, -0.045363694 -0.08918947 -0.070258141, -0.014733583 -0.094278395 -0.068456024, -0.090788066 -0.010367841 -0.066579774, 0.010885045 -0.095280558 -0.068658113, -0.013184592 -0.093132555 -0.067858756, 0.0025124848 -0.11503974 -0.073849186, -0.011574969 -0.094718009 -0.068456188, 0.00018541515 -0.12002054 -0.074342206, 0.015699327 -0.09412238 -0.068456143, 0.014154151 -0.090272069 -0.066584364, 0.017238155 -0.092468113 -0.067858741, 0.0063468516 -0.10997432 -0.073030084, -0.095284268 -0.010881484 -0.068653524, 0.018835783 -0.093545139 -0.068456098, 0.020152271 -0.089125007 -0.066584095, 0.090518102 -0.030206591 -0.068452463, 0.0093270242 -0.1048981 -0.071888179, 0.011413202 -0.099902868 -0.070428953, -0.099906728 -0.011409223 -0.070423931, 0.089645907 -0.028488368 -0.06785512, 0.0026207417 -0.11999202 -0.074342296, 0.091477036 -0.027164936 -0.068452433, -0.090063795 -0.015442044 -0.066579893, -0.090484113 -0.00025013089 -0.066125497, -0.090424985 -0.0032735169 -0.066125751, 0.0066296309 -0.11487606 -0.073849246, -0.045434102 -0.083406627 -0.068264067, 0.009756133 -0.10972437 -0.073030025, -0.042672306 -0.084852666 -0.068263918, -0.10463533 -0.01194945 -0.071882978, 0.01195325 -0.10463136 -0.071888179, -0.089752346 -0.017159194 -0.066580027, -0.014385387 -0.089329839 -0.066130504, -0.09452419 -0.016206831 -0.068653643, -0.011392206 -0.089760691 -0.066130534, 0.0069149286 -0.11982131 -0.074342296, 0.015300393 -0.089177668 -0.066130534, 0.018271863 -0.088616639 -0.066130519, 0.010191038 -0.11461499 -0.073849261, -0.10944934 -0.012499183 -0.073024422, 0.085696459 -0.029040068 -0.066127226, 0.012503266 -0.10944545 -0.073029995, 0.086619139 -0.026160389 -0.066126898, -0.094197169 -0.018008947 -0.068653852, -0.042748109 -0.08025223 -0.066358149, -0.099109709 -0.016993165 -0.070424169, -0.089055985 -0.020467639 -0.066580296, 0.010629743 -0.11954904 -0.074342206, -0.11432768 -0.013056457 -0.073843643, 0.013060585 -0.11432368 -0.073849291, -0.098767057 -0.018882662 -0.070424303, -0.10380055 -0.017797559 -0.071883291, -0.09346658 -0.021481305 -0.068653926, 0.013622746 -0.11924517 -0.074342266, -0.08840555 -0.023115605 -0.06658034, -0.11924921 -0.013618648 -0.074336231, -0.1034416 -0.019776523 -0.071883455, 0.025432467 -0.087764472 -0.06658408, -0.10857601 -0.018616587 -0.073024854, -0.09800072 -0.022523433 -0.070424557, -0.092783764 -0.024260432 -0.068654105, -0.087768003 -0.025428861 -0.066580489, 0.026691884 -0.092110932 -0.06865783, -0.1082007 -0.020686567 -0.073025003, -0.11341545 -0.019446403 -0.073844045, -0.10263894 -0.02358973 -0.0718835, 0.027986884 -0.096579522 -0.070428684, -0.097285092 -0.025437295 -0.070424661, 0.030313641 -0.086200297 -0.066583917, -0.092114642 -0.026688337 -0.068654269, -0.1130235 -0.021608621 -0.073843941, 0.029311478 -0.10115075 -0.071887851, -0.11829777 -0.02028361 -0.074336603, 0.031852067 -0.085643798 -0.066584051, -0.086664066 -0.028968811 -0.066580832, -0.10736118 -0.024675071 -0.073025286, 0.031814888 -0.090469301 -0.068657681, -0.10188948 -0.026641428 -0.071883902, -0.096583292 -0.02798295 -0.070424795, 0.030659959 -0.10580444 -0.073029861, -0.11788876 -0.02253899 -0.074336886, 0.033429548 -0.089885205 -0.068657875, -0.086204022 -0.030310005 -0.066580892, 0.033358335 -0.094858289 -0.070428416, -0.090955809 -0.030403435 -0.068654582, 0.035099462 -0.08436501 -0.066583648, 0.032026708 -0.11052066 -0.073848978, -0.11214651 -0.025774986 -0.073844299, -0.10657696 -0.027867347 -0.073025316, 0.035051286 -0.09424594 -0.070428535, 0.034937218 -0.099348128 -0.071887895, -0.10115473 -0.029307544 -0.071883842, -0.09047316 -0.031811178 -0.068654448, 0.036837757 -0.088543236 -0.068657652, -0.095368341 -0.031878561 -0.070425063, 0.037501618 -0.083324999 -0.066583753, 0.033405244 -0.1152783 -0.074342087, -0.11697409 -0.026884764 -0.074337244, -0.11132745 -0.029109538 -0.073844358, 0.036710367 -0.098706692 -0.071887672, -0.10580856 -0.030656099 -0.07302551, 0.036544532 -0.103919 -0.073029533, -0.094862342 -0.033354491 -0.070425004, 0.038624734 -0.092838645 -0.070428506, 0.039358914 -0.087451696 -0.068657711, -0.084535331 -0.034692556 -0.066581115, -0.099882245 -0.033387363 -0.071884111, 0.03977482 -0.082264155 -0.066583693, -0.11611976 -0.030362815 -0.074337348, 0.038399339 -0.10324809 -0.073029593, -0.11052458 -0.032022476 -0.073844478, 0.038173452 -0.108551 -0.073848978, -0.099352002 -0.03493318 -0.071884334, 0.040452957 -0.097232789 -0.071887702, -0.088721871 -0.036410809 -0.068654776, 0.041268304 -0.091694266 -0.070428446, -0.10447738 -0.034923732 -0.073025659, 0.041744635 -0.086338341 -0.068657473, -0.11528252 -0.033401191 -0.074337393, 0.040110722 -0.10785007 -0.073848888, -0.10392289 -0.036540627 -0.073025897, 0.039816543 -0.11322382 -0.074341893, -0.093025804 -0.038177252 -0.070425272, 0.042983592 -0.080634177 -0.066583753, -0.10913424 -0.036480457 -0.073844895, 0.042314008 -0.10170639 -0.073029578, -0.082267955 -0.03977114 -0.066581324, 0.043221384 -0.096034169 -0.071887538, -0.10855511 -0.038169265 -0.073844761, 0.043769792 -0.090526879 -0.070428297, 0.041837409 -0.11249292 -0.074341878, -0.097428858 -0.039984256 -0.071884438, 0.044325083 -0.079904616 -0.066583559, -0.11383229 -0.03805092 -0.07433781, 0.045112327 -0.084627539 -0.068657428, -0.086342216 -0.041740924 -0.068655327, 0.044200093 -0.10623977 -0.073848665, -0.11322799 -0.039812535 -0.074337825, -0.10191116 -0.041824073 -0.073026121, 0.045209944 -0.10045278 -0.073029444, 0.04584153 -0.094811767 -0.071887657, -0.090530768 -0.043765962 -0.070425764, -0.079908296 -0.044321418 -0.066581711, 0.046520188 -0.083861828 -0.068657517, 0.047300786 -0.088733077 -0.070428208, -0.1064536 -0.043688297 -0.073845193, 0.046102837 -0.11081326 -0.074341923, 0.047225028 -0.10493004 -0.073848709, -0.079156473 -0.045650482 -0.066581726, -0.094815463 -0.045837492 -0.071884811, 0.047950447 -0.099173874 -0.073029473, -0.083865643 -0.046516418 -0.068655565, 0.048777059 -0.087930322 -0.070428103, -0.11103623 -0.045569032 -0.074338153, 0.048273608 -0.077583015 -0.066583514, -0.083076492 -0.047911406 -0.068655595, 0.049539641 -0.09293288 -0.071887389, 0.049257934 -0.10944721 -0.07434155, -0.099177808 -0.047946513 -0.073026493, 0.05008769 -0.10359424 -0.073848546, -0.08793433 -0.04877308 -0.070425883, 0.051085725 -0.092092037 -0.071887448, -0.07729733 -0.048732072 -0.06658186, -0.087106898 -0.050235748 -0.070426062, 0.050664276 -0.081425309 -0.068657339, 0.051818714 -0.097208649 -0.07302919, -0.10359837 -0.050083637 -0.07384564, -0.092096046 -0.051081747 -0.071885303, 0.052243769 -0.10805386 -0.07434161, -0.08112523 -0.051145822 -0.06865564, 0.053435981 -0.096329272 -0.073029235, 0.053122178 -0.085375458 -0.070428073, -0.075930327 -0.05083558 -0.066581935, 0.054128453 -0.10154155 -0.073848516, -0.091229707 -0.052613407 -0.071885213, -0.10805801 -0.052239716 -0.074338466, 0.052993193 -0.074439287 -0.066583425, -0.096333101 -0.053431958 -0.073026791, 0.055817768 -0.10062292 -0.07384856, 0.055636346 -0.089416504 -0.071887314, 0.056458503 -0.10591274 -0.074341491, -0.085060969 -0.053626835 -0.070426226, -0.07969074 -0.05335322 -0.068655789, -0.074442953 -0.052989662 -0.066582158, 0.055617601 -0.078125954 -0.068657115, 0.05822055 -0.1049546 -0.074341625, -0.095426783 -0.05503422 -0.073027015, 0.058196232 -0.093530446 -0.073029011, -0.10062693 -0.055813611 -0.073845819, 0.058315828 -0.081916064 -0.070427835, -0.089086905 -0.056165248 -0.071885601, -0.083556727 -0.055941612 -0.070426464, 0.057083935 -0.071350902 -0.066583231, -0.078129724 -0.055613965 -0.068655863, 0.060790032 -0.097699374 -0.073848277, -0.09968026 -0.05748716 -0.073845997, 0.058184236 -0.070456564 -0.066583082, -0.10495874 -0.058216453 -0.074338689, 0.061075985 -0.085793257 -0.071887195, -0.072365016 -0.055793732 -0.066582292, -0.093185455 -0.058749348 -0.073027119, 0.059911042 -0.074884534 -0.068657041, 0.063406914 -0.1019052 -0.074341401, -0.087511525 -0.058589309 -0.071885481, -0.081919983 -0.058311939 -0.070426568, 0.061065674 -0.07394591 -0.068656817, -0.10397109 -0.059962183 -0.074338913, 0.063885719 -0.089740515 -0.073028862, -0.071354553 -0.057080209 -0.066582322, 0.062817395 -0.078517407 -0.070427611, -0.075948879 -0.058556914 -0.068656117, 0.060995013 -0.068037897 -0.066582963, -0.09733893 -0.061368078 -0.073846251, 0.064028159 -0.077533245 -0.070427686, -0.09153761 -0.061285198 -0.073027298, 0.066733405 -0.093740493 -0.073848084, -0.085797191 -0.061072081 -0.071885705, 0.0657904 -0.082233667 -0.071886733, -0.074888319 -0.059907228 -0.068656057, 0.064015746 -0.071407497 -0.068656847, -0.079633474 -0.061397523 -0.070426688, 0.062760487 -0.066412896 -0.066582903, -0.101529 -0.064009994 -0.074339196, 0.067058578 -0.081203103 -0.071886629, -0.095617726 -0.06401673 -0.073846325, 0.069606066 -0.097776055 -0.074341029, -0.089744493 -0.063881963 -0.073027298, 0.068817317 -0.086017191 -0.073028728, -0.068476453 -0.060502589 -0.066582531, 0.067121312 -0.074871719 -0.070427522, -0.078521207 -0.062813371 -0.070426717, -0.08340247 -0.064303637 -0.071885824, 0.065868646 -0.069702059 -0.068656743, -0.099733651 -0.06677267 -0.07433939, 0.064714208 -0.064510822 -0.066582769, -0.09374465 -0.066729277 -0.073846564, 0.070143849 -0.084939182 -0.073028594, -0.071867913 -0.063498944 -0.068656415, 0.071884736 -0.08985129 -0.07384783, -0.082237676 -0.06578666 -0.071886063, 0.07029812 -0.078415513 -0.071886614, -0.087239563 -0.067262411 -0.073027581, 0.069064051 -0.07308349 -0.070427358, -0.097780138 -0.069601923 -0.074339464, 0.067918941 -0.06770578 -0.068656445, -0.075354397 -0.066579461 -0.070427001, 0.073270351 -0.08872515 -0.073847756, 0.074979216 -0.093719274 -0.07434094, -0.086021349 -0.068813354 -0.073027551, -0.091127932 -0.070260346 -0.073846683, 0.067056477 -0.062072605 -0.066582605, -0.064514488 -0.064710557 -0.06658271, 0.073532358 -0.082023352 -0.073028505, 0.072332785 -0.076542646 -0.071886465, -0.078920856 -0.069730729 -0.071886092, -0.089855269 -0.071880668 -0.073846906, 0.07121402 -0.070990413 -0.070427299, -0.095050633 -0.073285073 -0.074339762, 0.076424435 -0.092544556 -0.074340791, -0.067709625 -0.06791532 -0.068656638, -0.082551837 -0.072938979 -0.07302776, 0.07037732 -0.065146863 -0.06865643, -0.093723342 -0.074975044 -0.074339777, 0.076809853 -0.085679322 -0.073847592, 0.080116317 -0.089367777 -0.074340716, 0.14817563 -0.060242116 -0.017003506, 0.14594691 -0.064168066 -0.020804778, 0.14825682 -0.058703691 -0.020635471, 0.14819229 -0.046364874 -0.039427549, 0.14345323 -0.073058546 0.0019958764, 0.14103121 -0.077661008 -4.4703484e-06, 0.14345324 -0.073058397 -0.0020040572, -0.13771948 0.036966324 -0.069029525, -0.020898804 -0.15135223 -0.04700841, -0.024799228 -0.15215355 -0.043008626, -0.024571449 -0.15079972 -0.047008529, -0.13993712 0.03614983 -0.06554085, 0.13753243 -0.081671566 0.016995355, 0.13583024 -0.085293651 0.012995109, 0.13791399 -0.081881642 0.012995318, 0.13545687 -0.085069686 0.016995296, 0.14959307 -0.045267284 -0.035824776, -0.1386148 0.027837813 -0.071099013, 0.14523305 -0.069453269 -0.0020040423, -0.087965623 -0.11698583 0.061993472, -0.090716943 -0.11486533 0.061993577, -0.089132398 -0.11851093 0.057993233, -0.14205036 0.035280734 -0.06199801, 0.1422091 -0.075015277 0.0077805221, 0.13944784 -0.080091566 0.0072268695, 0.14028598 -0.078903317 0.0036139935, -0.14389776 0.035809636 -0.057998031, -0.08627376 -0.12060806 0.057993263, -0.03471452 -0.15428466 -0.028008789, -0.038278088 -0.15252522 -0.032008618, -0.034502432 -0.15342334 -0.032008871, -0.038522378 -0.15337825 -0.02800864, -0.044107422 -0.15399325 -0.015008599, -0.049138993 -0.15267569 -0.013008922, -0.049019083 -0.15225679 -0.017008588, -0.1457102 0.038704872 -0.052286565, -0.047844782 -0.15339252 -0.0094048381, -0.1466931 0.040493906 -0.04866302, 0.14857818 -0.060408324 -0.013003454, 0.14742208 -0.064166427 -0.0077905506, 0.14660813 -0.065392166 -0.01139991, -0.14471266 0.032359093 -0.0579983, -0.14284751 0.03189972 -0.061998218, -0.081380606 -0.12931728 0.046992794, -0.084499642 -0.12730113 0.046992928, -0.085249662 -0.12845045 0.042992681, -0.082087442 -0.13049409 0.042992443, -0.071686625 -0.14096382 0.02799198, -0.076076508 -0.13815573 0.029992074, -0.073297828 -0.14091223 0.024401933, -0.1454449 0.028890163 -0.057998598, -0.14356428 0.028501004 -0.061998516, 0.14523301 -0.069453537 0.0019959658, -0.14345627 0.020068347 -0.064936787, -0.14420015 0.025086075 -0.061998591, -0.14052573 0.021535844 -0.069769919, -0.14993553 0.040560514 -0.039262161, -0.021075994 -0.15271378 -0.043008596, -0.14609396 0.025404632 -0.057998821, -0.059181809 -0.14938611 0.0093859881, -0.064662367 -0.14710891 0.0092229694, -0.063410431 -0.14786345 0.0056101233, 0.1469221 -0.065804899 -0.002003774, -0.017213911 -0.15181556 -0.047008395, -0.085164882 -0.11904031 0.061993301, -0.1512835 0.039440691 -0.035643339, -0.06040895 -0.14857906 0.012991577, -0.14168581 0.011656672 -0.0697736, -0.030885577 -0.1550965 -0.028008744, -0.03070581 -0.15422809 -0.032008722, -0.071258888 -0.14018688 0.031992152, 0.15099025 -0.052793056 -0.017003134, 0.1500378 -0.056686163 -0.01300326, 0.14962941 -0.056535065 -0.017003417, -0.14617673 0.018523037 -0.059999213, -0.14842099 0.02121675 -0.054288417, -0.14740075 0.027068108 -0.054439321, -0.078213438 -0.13125706 0.046992645, 0.14692196 -0.065805048 0.0019962192, -0.078876004 -0.13246 0.042992428, -0.15252689 0.038279653 -0.031997994, -0.14967056 0.022896677 -0.050664529, -0.022819981 -0.15421742 -0.037272975, -0.026890501 -0.15493879 -0.032008767, -0.028930843 -0.15302894 -0.037831143, -0.1533796 0.038523793 -0.027998045, 0.14982274 -0.05842486 -0.0072325319, -0.068176016 -0.14269468 0.027991965, -0.14249153 0.0053942502 -0.069031283, -0.15382229 0.041043639 -0.022245765, 0.0037085414 -0.14132905 -0.071108446, 0.10350902 -0.097454071 0.069768757, -0.017339885 -0.15318304 -0.043008626, 0.11634287 -0.091943353 0.057994798, 0.11267671 -0.093420625 0.061994776, 0.11411153 -0.094698578 0.057994813, 0.15140408 -0.052928746 -0.013003051, -0.072596222 -0.13778996 0.037812307, -0.1513547 0.020901293 -0.046998933, -0.15215597 0.024801433 -0.042998582, -0.15080211 0.024573982 -0.046998858, -0.076936379 -0.13669297 0.033639491, -0.15396126 0.042587757 -0.018629685, 0.15214385 -0.046571285 -0.022804201, 0.15193453 -0.045010656 -0.026410803, -0.15428624 0.03471598 -0.027998209, -0.15342505 0.034504235 -0.031998187, -0.060242876 -0.14817679 0.016991556, -0.063553169 -0.14597005 0.02223739, -0.065082535 -0.14588469 0.018622011, -0.013518766 -0.15218908 -0.047008574, 0.14851946 -0.06211558 0.0019962639, -0.15271616 0.02107814 -0.042998835, 0.1485194 -0.062115312 -0.0020034164, -0.15181813 0.017216563 -0.046999261, -0.027037621 -0.15581337 -0.028008714, -0.15509805 0.030887097 -0.027998313, -0.15422978 0.030707568 -0.031998411, -0.067777693 -0.1419028 0.031992048, 0.10659802 -0.09288013 0.071093351, 0.10683146 -0.097824574 0.064935461, 0.10899296 -0.093162 0.06763728, -0.064623758 -0.14433834 0.027991891, 0.11486183 -0.090720445 0.06199491, -0.15421948 0.022822082 -0.037263095, -0.15494052 0.026892215 -0.031998485, -0.1530308 0.02893275 -0.03782095, 0.11850771 -0.089135647 0.057995081, -0.14133312 -0.0037046075 -0.071100727, -0.021545604 -0.15536737 -0.033654049, -0.15318525 0.01734221 -0.042999104, 0.1522575 -0.049018055 -0.017002791, 0.12729836 -0.08450231 0.046995237, 0.12632774 -0.088363886 0.042994902, 0.12844796 -0.085252225 0.042995125, -0.15510067 0.04202348 -0.0092268586, -0.013593674 -0.15356076 -0.0430087, 0.12520696 -0.087571412 0.046995193, -0.15219161 0.013521343 -0.046999201, -0.085257933 -0.11429995 0.069027692, -0.15581502 0.027039111 -0.027998745, -0.15536922 0.021547258 -0.033644035, 0.11698228 -0.087969065 0.061994925, -0.15356304 0.013595909 -0.042999431, 0.12060475 -0.086276919 0.057995275, -0.064255327 -0.14353204 0.03199181, -0.15565842 0.040680051 -0.0056144148, 0.15267649 -0.049138427 -0.013002977, 0.15339276 -0.047844321 -0.0093989819, 0.12931462 -0.081383318 0.046995327, 0.13049175 -0.082089901 0.042995065, -0.14828415 -0.00065380335 -0.058000162, -0.14825769 0.0028916597 -0.05799982, -0.14633888 0.0027871132 -0.062000036, 0.14096226 -0.071688265 0.027995914, 0.13815396 -0.076078296 0.029995486, 0.14091074 -0.073299289 0.024405688, -0.14636369 -0.00068643689 -0.062000066, -0.061031803 -0.14589342 0.027991563, -0.15641104 0.020243794 -0.029998958, -0.057765022 -0.14825737 0.02279523, -0.15326585 0.0083721876 -0.044999719, -0.15012811 0.011068404 -0.052842036, -0.1520253 0.0068363547 -0.048664868, 0.00065696239 -0.14828113 -0.058008373, -0.0028884411 -0.14825439 -0.058008507, -0.0027837157 -0.14633539 -0.062008321, 0.00068981946 -0.14636022 -0.062008247, 0.14938556 -0.059182584 0.0093911141, 0.14710835 -0.064662933 0.0092276782, 0.14786308 -0.063410819 0.0056147873, 0.11903679 -0.085168332 0.061995268, -0.020242482 -0.15640947 -0.030008778, -0.15479457 0.012230933 -0.0394243, 0.14857818 -0.060409695 0.012996584, -0.15611349 0.039305419 -0.0019978434, -0.15723123 0.022714764 -0.024246901, -0.15624487 0.028568357 -0.024406508, 0.1401851 -0.071260512 0.031995997, -0.0083697587 -0.15326351 -0.04500863, -0.011065632 -0.15012527 -0.052851155, -0.0068336874 -0.15202272 -0.0486736, -0.15760285 0.024243861 -0.020630747, -0.14822617 -0.0041986406 -0.058000401, -0.012228608 -0.15479237 -0.039433539, -0.14630613 -0.0041595697 -0.06200029, 0.13125442 -0.078216195 0.046995491, 0.13245755 -0.078878433 0.042995363, -0.05279395 -0.15099126 0.016991496, -0.056686744 -0.15003857 0.012991682, -0.052929401 -0.15140486 0.012991399, -0.056536034 -0.14963034 0.016991496, 0.15400709 -0.046518534 -0.0057896078, -0.15611367 0.03930521 0.0020020306, 0.14269313 -0.068177551 0.027996108, -0.022713616 -0.15722984 -0.024256825, -0.028567016 -0.15624341 -0.024416909, -0.15704648 0.035394669 -0.0019979924, 0.13778776 -0.072598457 0.037815884, 0.13669097 -0.07693845 0.033642694, -0.15533607 0.041489035 0.0077869445, -0.06069389 -0.14507398 0.031991914, 0.14817566 -0.060243994 0.016996577, 0.14596879 -0.063554674 0.022242054, 0.1458836 -0.065083623 0.018626422, -0.024242744 -0.15760177 -0.02064088, 0.0042017698 -0.14822292 -0.058008373, 0.0041628182 -0.14630264 -0.062008202, -0.1480833 -0.0077412426 -0.058000371, -0.14616624 -0.0076302588 -0.062000498, -0.15471654 0.042813331 0.011396825, 0.14190087 -0.067779452 0.031996086, -0.15704642 0.03539449 0.0020018965, 0.14433677 -0.064625323 0.027996197, -0.039305329 -0.15611371 0.0019911379, -0.044331402 -0.15477657 -8.6724758e-06, -0.039305359 -0.15611348 -0.0020088553, 0.11429587 -0.085261881 0.069029182, -0.15788141 0.031461924 -0.00199835, -0.035394624 -0.15704638 -0.0020088702, -0.1407263 -0.020163476 -0.069775447, 0.14353031 -0.064257115 0.031996295, 0.14589174 -0.061033338 0.0279966, -0.15788144 0.031461686 0.0020016879, 0.14825596 -0.057766259 0.022800341, 0.0077443719 -0.1480802 -0.058008328, 0.007633701 -0.14616269 -0.062008232, 0.1509902 -0.052794904 0.016997069, 0.15003772 -0.056687564 0.012996778, 0.15140408 -0.052930176 0.012996972, 0.14962934 -0.056536943 0.016996726, -0.15861781 0.027509451 -0.0019984692, 0.15377365 -0.047053486 0.0072287619, 0.15432626 -0.045708477 0.003616035, -0.15906718 0.023622006 -0.0072279125, -0.15800437 0.029753804 -0.0077853054, -0.035394698 -0.15704656 0.001990959, 0.14507218 -0.060695618 0.031996757, -0.044107452 -0.15399489 0.014991149, -0.049019143 -0.15225872 0.016991481, -0.049139142 -0.15267697 0.012991369, -0.15389058 0.041661561 0.020805776, -0.047497377 -0.15221965 0.020621762, -0.031461865 -0.15788114 -0.0020089447, 0.15267636 -0.049139798 0.012997076, -0.15861778 0.027509212 0.002001375, -0.15941247 0.022214651 -0.0036156029, 0.15225758 -0.049020082 0.016997114, -0.057131872 -0.14438725 0.039414793, -0.062627882 -0.14214012 0.039258793, -0.061687276 -0.14365661 0.035639226, 0.15221843 -0.047498554 0.020627588, -0.15368813 0.040102988 0.024412051, 0.020167395 -0.14072248 -0.069782123, 0.14438491 -0.057134122 0.039419696, 0.14213775 -0.062630087 0.039263219, 0.14365448 -0.061689317 0.035643756, -0.031461805 -0.15788153 0.0019909889, -0.058035269 -0.14282522 0.042991817, -0.062185824 -0.13889691 0.048655331, -0.064022645 -0.13950732 0.044992089, 0.14282265 -0.058037698 0.04299657, 0.13889411 -0.062188596 0.048659578, 0.13950479 -0.064025104 0.0449965, -0.15221034 -0.013302326 -0.047000647, -0.15385936 -0.009678036 -0.043000579, -0.1524889 -0.009598732 -0.047000602, 0.15207297 -0.045952797 0.024243057, -0.15965241 0.020787865 9.5367432e-07, -0.15814261 -0.00048616529 -0.028000191, -0.15810604 0.0034276247 -0.027999967, -0.15722051 0.0033797622 -0.031999782, 0.12259845 -0.071977824 0.069770083, -0.027509525 -0.15861765 -0.0020089298, -0.1572559 -0.00050121546 -0.03200011, 0.13388447 -0.063749641 0.057996437, 0.130639 -0.066005528 0.061996311, 0.13232218 -0.066932201 0.057996079, -0.15994792 0.0087353885 -0.014999598, -0.15934797 0.013910443 -0.016999379, -0.1586926 0.011550963 -0.022800922, -0.15957753 0.0072603822 -0.018631712, -0.023621693 -0.15906692 -0.0072380304, -0.029753506 -0.15800396 -0.0077957809, -0.16019347 0.012512565 -0.009395808, -0.15978302 0.013934046 -0.01299943, 0.14155357 -0.057514638 0.046996683, 0.13817063 -0.060322762 0.052282795, -0.07197395 -0.1226024 0.069767311, -0.15337965 0.038520634 0.028001904, -0.15921795 0.023060799 0.0057861209, -0.063746139 -0.13388789 0.057992369, -0.066002026 -0.13064244 0.061992556, -0.066928834 -0.13232556 0.057992503, 0.12698993 -0.066573143 0.067638919, 0.12592007 -0.071599633 0.064936891, 0.12906989 -0.071077734 0.059996128, -0.15826614 0.028917581 0.0056200325, -0.14176203 -0.028146207 -0.065544546, -0.14308782 -0.022530317 -0.064942122, -0.14011861 -0.02644828 -0.069032952, 0.13216843 -0.062886775 0.061996341, -0.14522512 -0.024902433 -0.060001418, -0.15357699 -0.013432741 -0.043000922, 0.1353703 -0.060530543 0.057996556, -0.05751203 -0.14155638 0.046992019, -0.060319841 -0.1381737 0.052278399, -0.15880944 0.024456024 0.0093957633, 0.14290954 -0.054057091 0.046996772, 0.14419729 -0.054532349 0.042996779, -0.15184227 -0.016997814 -0.04700093, 0.13362361 -0.059732586 0.061996683, -0.15808201 -0.0043998957 -0.02800034, -0.1571957 -0.0043816864 -0.032000363, -0.027509376 -0.15861794 0.001990959, 0.13677855 -0.057276756 0.05799669, -0.15252692 0.038276255 0.032002002, -0.066569135 -0.12699375 0.067635566, -0.071595967 -0.12592384 0.064933784, -0.071074396 -0.12907338 0.059992626, 0.14033067 -0.054481506 0.052841932, 0.14418119 -0.050567687 0.04699713, 0.14548612 -0.050994635 0.042996898, -0.022214606 -0.15941235 -0.0036257803, 0.14904523 -0.045715511 0.037263796, 0.15038383 -0.044592798 0.033644632, 0.13500324 -0.056544721 0.061996758, -0.15428627 0.03471303 0.02800183, -0.062883347 -0.13217193 0.061992556, -0.1369642 -0.0350613 -0.07110253, 0.1453677 -0.04704842 0.046997339, 0.14668812 -0.047426343 0.042997345, -0.15320314 -0.01717937 -0.043001071, -0.1504872 0.040113151 0.037822276, -0.060527116 -0.13537356 0.057992429, -0.054054379 -0.14291233 0.046991885, -0.05453001 -0.14419994 0.042991832, -0.16056278 0.0064567626 -0.0092287511, -0.16049713 0.011082977 -0.0057863146, 0.14448647 -0.045271814 0.050661489, -0.15138404 -0.020683497 -0.047001138, 0.130402 -0.057691127 0.069030657, -0.14907634 0.041208118 0.04142563, -0.15792476 -0.0083107352 -0.028000608, -0.1570396 -0.0082594752 -0.032000393, 0.13221121 -0.052266061 0.069768384, -0.15342511 0.034500599 0.032001942, 0.13275124 -0.057150066 0.065541849, 0.14348873 -0.043478668 0.054284602, -0.15509808 0.030884027 0.028001606, -0.13900141 0.025837541 -0.071099281, -0.1408502 0.026812226 -0.067643613, -0.14096498 0.026202112 -0.067643628, -0.14879407 0.027656287 -0.050840467, -0.14859106 0.028728127 -0.05084008, -0.15021855 0.027920812 -0.046998397, -0.15025349 0.031377107 -0.044998243, 0.013304755 -0.15220788 -0.047008574, 0.0096803904 -0.15385711 -0.04300876, 0.0096012503 -0.15248626 -0.047008619, -0.15156825 0.02817142 -0.042998388, -0.15169661 0.030169815 -0.04142344, -0.15270922 0.028383285 -0.039262876, -0.15273777 -0.020915985 -0.043001235, -0.1432585 0.0058740377 -0.067644641, -0.14451437 0.0098746419 -0.064940423, -0.14447178 0.004104495 -0.065542653, -0.14624265 0.0059960485 -0.061999664, -0.14712586 0.0080375671 -0.059999824, -0.02078785 -0.15965244 -9.0152025e-06, -0.14816146 0.0060745478 -0.057999641, -0.14868586 0.0095481873 -0.056441233, -0.1385335 -0.036955208 -0.067647174, -0.14973904 0.006138891 -0.054440439, -0.059729174 -0.13362703 0.061992586, -0.15066899 0.0053109527 -0.052288368, -0.14117372 -0.0076615214 -0.07110092, -0.14328434 -0.0052019358 -0.067645416, -0.14179382 -0.010273993 -0.069771722, -0.15685974 0.029153496 -0.020027339, -0.15656678 0.030085206 -0.020799592, -0.157866 0.025761157 -0.01699841, -0.15685771 0.032487065 -0.014998242, -0.14316779 -0.0077700913 -0.067645639, -0.1443245 -0.012356818 -0.064938575, -0.15748945 0.029270321 -0.01499854, -0.057273433 -0.13678187 0.057992458, -0.15829527 0.025833398 -0.012998655, -0.15748376 0.031130522 -0.011394531, -0.14615004 -0.0079322159 -0.062000573, 0.0004876703 -0.15814102 -0.028008848, -0.0033779144 -0.15721866 -0.032009006, 0.0005029887 -0.15725422 -0.032008946, -0.14663279 -0.014468729 -0.060000762, -0.14807254 -0.028349161 -0.052290261, -0.14882638 -0.022615612 -0.052843899, -0.14708211 -0.023776919 -0.05644308, -0.15793374 0.029352635 -0.010009259, -0.0034261942 -0.15810478 -0.028008938, -0.15519403 0.0063615143 -0.039264128, -0.15591595 0.010848641 -0.035821512, -0.054478675 -0.14033359 0.052837089, -0.15520152 0.0061798096 -0.039264038, -0.14806752 -0.0080367327 -0.05800052, -0.15422982 0.030704051 0.032001778, -0.0087346286 -0.15994722 -0.015009105, -0.011549801 -0.15869141 -0.02281031, -0.007259503 -0.15957633 -0.018640876, -0.013909593 -0.15934703 -0.017008975, -0.14942031 -0.012341887 -0.05429031, -0.1562086 0.006403029 -0.035645261, -0.15626654 0.0047882199 -0.035645261, -0.15870389 0.021743596 -0.014998913, -0.15938604 0.017912418 -0.012998998, -0.15888995 0.021879613 -0.012998939, -0.012512162 -0.16019309 -0.0094053, -0.013933256 -0.15978232 -0.013009086, -0.15845822 0.021823704 -0.016998887, -0.15895246 0.017872572 -0.016999155, -0.050565004 -0.14418402 0.046992049, -0.050992206 -0.14548856 0.042991713, -0.14964435 -0.0081225336 -0.054441363, -0.14972761 -0.0064103305 -0.054441169, -0.15101229 -0.010982066 -0.050666451, -0.13980564 -0.021046281 -0.071101665, -0.1571248 0.0064403713 -0.031999663, -0.15748085 0.0086013675 -0.029999569, -0.15111929 -0.0082027614 -0.05084233, -0.15125744 -0.0050568283 -0.050842151, -0.14973448 -0.027163774 -0.048666701, -0.15801075 0.0064764917 -0.027999833, -0.15814148 0.010076165 -0.02640757, -0.023061275 -0.15921834 0.0057759434, -0.15581481 0.027036011 0.028001323, -0.15256619 -0.0082815289 -0.047000408, -0.028917983 -0.15826637 0.0056096166, -0.15346767 -0.002844125 -0.045000359, -0.15955848 0.014167428 -0.014999211, -0.15739286 0.023325205 0.022805005, -0.15645078 0.029477388 0.022247434, -0.15872994 0.006505549 -0.024247885, -0.14442036 -0.033633679 -0.058002174, -0.14518328 -0.030171126 -0.058001846, -0.14328925 -0.029846162 -0.06200175, -0.15909843 0.0057858229 -0.022247642, 0.028149799 -0.14175856 -0.065550908, 0.022533864 -0.14308402 -0.064948991, 0.026452124 -0.14011464 -0.069039479, -0.14254045 -0.033238292 -0.062001944, -0.15393686 -0.0083561838 -0.043000594, -0.15460597 -0.004342258 -0.041425303, 0.024905711 -0.14522186 -0.060008183, -0.15793362 0.029351473 0.010012493, -0.15829529 0.025831759 0.013001382, -0.15685761 0.032485485 0.015001699, -0.15780868 0.030305862 0.0092329681, -0.15509565 -0.0084193349 -0.039264902, -0.15543075 -0.012067378 -0.037264884, 0.013435036 -0.15357471 -0.043008775, -0.15563188 -0.0058450699 -0.037822887, -0.15748951 0.029268682 0.015001595, -0.15670827 0.030987561 0.018631876, -0.157866 0.02575928 0.017001435, -0.15610962 -0.0084745288 -0.035646021, -0.15626805 -0.013565749 -0.033645913, -0.14353319 -0.02865085 -0.06200175, -0.024456665 -0.15880987 0.0093854368, -0.15685979 0.029151261 0.020030513, 0.017000467 -0.15183964 -0.047008589, -0.15702543 -0.0085245073 -0.032000586, -0.14541614 -0.029027104 -0.058001652, -0.13595177 -0.041568369 -0.069773555, -0.056541428 -0.13500673 0.061992526, -0.15791063 -0.008572787 -0.028000608, -0.15699403 -0.015068293 -0.030001014, -0.15834337 -0.01284191 -0.024248734, -0.15108779 -0.022746384 -0.047001317, -0.1512855 -0.025942475 -0.045001388, -0.15870383 0.021741837 0.015000969, -0.15938585 0.017910749 0.013000995, -0.15895237 0.017870635 0.017000914, -0.15845829 0.021821767 0.017001182, -0.15888993 0.021878153 0.013001084, -0.16074429 0.0065871775 -0.0057868063, -0.16080776 0.005022943 -0.0056165457, -0.15862961 -0.0086120367 -0.02424857, -0.15904592 -0.011433929 -0.020632818, -0.15868425 -0.0069155991 -0.024408355, 0.0044015199 -0.1580807 -0.028008997, 0.0043834299 -0.15719384 -0.032008976, -0.16085066 0.0065913498 -0.0019997209, -0.1609458 0.0035814047 -0.0019999146, -0.16076067 0.0087788403 2.682209e-07, -0.15244515 -0.022951007 -0.043001458, -0.15363458 -0.022520602 -0.039426133, -0.038278103 -0.15252873 0.031991243, -0.04342705 -0.15162075 0.029991329, -0.038522333 -0.15338132 0.027991384, -0.15931107 -0.0086493194 -0.020029604, -0.1596403 -0.010013044 -0.01700066, -0.14611723 0.039416552 0.050846457, -0.15933575 -0.0055084229 -0.020801648, -0.15494052 0.026888669 0.032001406, -0.16085067 0.0065911412 0.0020002574, -0.16094573 0.0035811663 0.002000019, -0.16062805 0.010220945 0.0036191195, -0.15359296 -0.023124039 -0.039265737, -0.15268487 -0.0285106 -0.039266214, -0.15442041 -0.024117917 -0.035823479, -0.13729942 -0.041304022 -0.067647412, -0.14080279 -0.039963931 -0.062002391, -0.13795549 -0.044162005 -0.064940512, -0.15955861 0.014165759 0.015000612, -0.15994793 0.0087337196 0.015000388, -0.15934783 0.013908476 0.017000794, -0.15978283 0.013932437 0.013000622, -0.047045752 -0.1453703 0.046991736, -0.04742381 -0.14669055 0.042991593, -0.16074452 0.0065864921 0.005785197, -0.1606738 0.0058831275 0.0077851415, -0.16036445 0.007312268 0.011394829, -0.16038859 0.011655033 0.0072319806, -0.15995067 -0.0086842179 -0.015000686, -0.14357488 -0.037076712 -0.058002174, -0.16046248 -0.0046934485 -0.011396468, -0.16015363 -0.0032315552 -0.015000269, -0.16007493 -0.010038435 -0.013000548, -0.14171153 -0.036611348 -0.062002257, -0.15270849 0.028378755 0.039268225, -0.15251009 0.029426754 0.039268494, -0.15377952 0.028172344 0.035648838, -0.15347779 0.023568481 0.039424106, -0.15215585 0.024796754 0.04300119, -0.14015941 -0.042164773 -0.062002376, -0.13973609 -0.046734929 -0.06000267, -0.14264722 -0.040498674 -0.058002502, -0.15695626 0.021788776 0.026411206, -0.16040191 -0.0087089837 -0.010011345, -0.16066366 -0.006151408 -0.0077873021, -0.16033545 -0.012365997 -0.0072297603, -0.15156819 0.028166682 0.043001428, -0.1502535 0.03137213 0.04500179, -0.14199838 -0.042718232 -0.058002666, -0.14292715 -0.045281589 -0.054292127, -0.034714714 -0.15428758 0.027991235, -0.16064255 -0.0087223053 -0.0057875812, -0.16076235 -0.0084760189 -0.0020006746, -0.16035895 -0.013814926 -0.0036174059, -0.15935624 -0.016285151 -0.015001014, -0.15894395 -0.017945647 -0.017001018, -0.15937562 -0.018003434 -0.013001174, -0.15934154 -0.013983786 -0.017000839, -0.15977469 -0.01402542 -0.013000995, -0.15021846 0.027915418 0.047001451, -0.15080221 0.024568677 0.047001407, -0.14924939 0.029717058 0.048664838, 0.035065114 -0.13696024 -0.071108192, -0.14351042 -0.043173343 -0.05444321, -0.14454636 -0.039567024 -0.054443225, -0.14478174 -0.044310063 -0.050668389, -0.16074876 -0.0087284446 -0.0020005107, -0.13090202 -0.053413272 -0.071103543, -0.13271035 -0.050972432 -0.069777042, 0.017181814 -0.15320083 -0.04300876, -0.13071921 -0.056964427 -0.06903486, -0.15421386 -0.030784667 -0.032001853, -0.15403028 -0.031689942 -0.032001764, -0.15490466 -0.031840086 -0.028001979, -0.15341364 -0.030104399 -0.035647273, -0.1554461 -0.026656955 -0.030001596, -0.14886288 0.027663499 0.050665259, -0.14893489 0.021883219 0.052846223, -0.14812873 0.028058529 0.052287817, -0.1449251 -0.043599159 -0.050844163, -0.14652914 -0.043290049 -0.047002494, -0.14633939 -0.038587987 -0.050843984, -0.16074887 -0.0087285638 0.0019993037, -0.16027537 -0.015259415 -8.6426735e-07, -0.16035768 -0.012946695 0.0057840645, -0.16098507 -0.000438869 -0.0020001531, -0.1607624 -0.0084761679 0.0019994527, -0.13275114 -0.054168224 -0.067648172, -0.13448587 -0.053805292 -0.064943954, -0.13194393 -0.058985502 -0.065546304, -0.15508324 -0.030958444 -0.028001979, -0.15641822 -0.025366277 -0.026409596, -0.15639682 -0.02976203 -0.022249773, -0.15873046 0.006502986 0.024246022, -0.1584852 0.010958344 0.02424632, -0.1593031 0.0063731372 0.020803705, -0.15875873 0.0048985481 0.024410024, -0.16064249 -0.00872311 0.0057841837, -0.1602698 -0.01149565 0.0093937516, -0.14506501 0.037617624 0.05444482, -0.1607329 -0.0070248544 0.0056181401, -0.0064563006 -0.1605626 -0.0092380047, -0.011082724 -0.16049698 -0.00579606, -0.15840079 -0.023849159 -0.015001625, -0.15887724 -0.021970391 -0.013001427, -0.15844797 -0.02189666 -0.017001361, -0.15728405 -0.024050981 -0.022802889, -0.15719193 -0.028430879 -0.018633798, -0.15788133 -0.02707544 -0.015001625, -0.15801062 0.0064732432 0.028000295, -0.15810627 0.0034246743 0.027999982, 0.02068603 -0.15138152 -0.047008604, -0.157481 0.0085981488 0.030000284, -0.16040185 -0.0087101758 0.010010257, -0.16007477 -0.010039985 0.012999177, -0.16059604 -0.005569756 0.009231016, -0.15884773 -0.023916632 -0.010012344, -0.15893935 -0.024908751 -0.0057884008, -0.1589613 -0.023447514 -0.0093975812, -0.15797397 -0.029433578 -0.0092308074, -0.15712489 0.0064367354 0.032000229, -0.1572205 0.0033760965 0.032000259, -0.15653589 0.010007322 0.033647671, -0.15995069 -0.0086859465 0.014999375, -0.15967473 -0.0046602786 0.018629923, -0.16015363 -0.0032331944 0.014999643, -0.15964021 -0.01001507 0.016999379, -0.1562081 0.0063989758 0.035647526, -0.15564075 0.0056206882 0.037820309, -0.15450899 0.0070022345 0.041423574, 0.0083122849 -0.15792319 -0.028008893, 0.0082612634 -0.15703794 -0.032008752, -0.15548056 0.011399359 0.037267089, -0.14971086 -0.045039922 -0.035648018, -0.15042867 -0.040329874 -0.03782478, -0.14784752 -0.043672383 -0.043002635, -0.14884809 -0.046351284 -0.037266672, -0.14933102 -0.047998577 -0.03364794, -0.15126406 -0.042996943 -0.032002568, -0.13875657 -0.056619406 -0.05444409, -0.14006214 -0.05516547 -0.052845642, -0.13810287 -0.055909425 -0.056444719, -0.13604198 -0.056593567 -0.060003251, -0.034502402 -0.15342692 0.031991348, -0.13805102 -0.060587496 -0.052292064, -0.12523156 -0.065614581 -0.071104288, -0.12683593 -0.066855073 -0.067648754, -0.12572744 -0.064659536 -0.071104184, -0.12329246 -0.070778131 -0.06977506, -0.15641108 0.020240545 0.03000091, -0.14019135 0.026050836 0.069035351, -0.13996916 0.027219772 0.069035456, -0.14213915 0.026169986 0.065546468, -0.14052571 0.021528035 0.069772452, -0.042264655 -0.14756337 0.044991747, -0.1593111 -0.0086515546 0.020028427, -0.15908797 -0.0060752332 0.022245467, -0.15863745 -0.012282729 0.022803143, -0.15058899 -0.045304179 -0.032002583, -0.15211554 -0.043243885 -0.028002441, -0.14970446 -0.049625039 -0.030002952, -0.14012422 -0.057177812 -0.050845087, -0.14298542 -0.053851128 -0.04700312, -0.030885428 -0.15509963 0.027991131, -0.1399352 -0.059801608 -0.048668385, -0.15143801 -0.045559973 -0.02800265, -0.15151553 -0.047754705 -0.02425079, -0.045268938 -0.14448944 0.050655738, -0.15862992 -0.0086147785 0.024245337, -0.1579248 -0.0083140433 0.027999327, -0.16098501 -0.00043907762 0.0019997507, -0.15786979 -0.013683587 0.026409075, -0.14146586 -0.05772537 -0.04700321, -0.14425358 -0.054378808 -0.043003201, -0.14171934 -0.058956355 -0.045003355, -0.15935621 -0.01628685 0.014998928, -0.15977465 -0.014026761 0.012999132, -0.15937553 -0.018004954 0.012998849, -0.15894401 -0.017947614 0.016999021, -0.15934157 -0.013985723 0.016999021, -0.1554165 -0.038798094 -0.015002191, -0.15340932 -0.045285404 -0.017002687, -0.15539475 -0.040281981 -0.011398509, -0.15541895 -0.038787991 -0.015002221, -0.15411489 -0.040825903 -0.020803645, -0.15212734 -0.045767546 -0.024250716, -0.15251374 -0.046538264 -0.020634845, -0.1589711 0.012433439 0.020631, -0.15316649 -0.042052716 -0.024410605, -0.15791081 -0.0085758567 0.027999446, -0.15787041 -0.031516314 -0.0020018518, -0.15868348 -0.027213931 -1.6540289e-06, -0.15789384 -0.030886024 -0.0056185424, -0.1577075 -0.032322228 -0.0020019263, -0.14273667 -0.058244377 -0.043003321, -0.16092394 -0.0044588447 -0.0020002127, -0.14251204 -0.061771363 -0.039268032, -0.15469238 0.022311628 0.035820931, -0.1447707 -0.056142986 -0.039428055, -0.15128505 0.0061963499 0.050664112, -0.153266 0.008367151 0.045000494, -0.15122549 0.0059140921 0.05084464, -0.14956541 0.010453105 0.054287627, -0.15093732 0.01197964 0.050664395, 0.020918339 -0.15273556 -0.04300867, -0.1570254 -0.0085281134 0.03199935, -0.15703966 -0.0082631111 0.031999379, -0.15699382 -0.01507169 0.029999048, -0.15577905 -0.0126701 0.03581892, -0.15787047 -0.031516761 0.0019980222, -0.15887514 -0.025778443 0.0036170185, -0.057687148 -0.13040581 0.069026858, -0.15770744 -0.032322556 0.0019980073, -0.15795454 -0.030017644 0.007782951, -0.14381127 -0.058683097 -0.039267689, -0.14518149 -0.057874829 -0.035825416, -0.14980458 0.0061354339 0.054287359, -0.14979951 0.004394412 0.054443032, -0.14389774 0.035803139 0.058001965, -0.15840086 -0.023850828 0.014998466, -0.15887722 -0.021971881 0.012998596, -0.15896086 -0.024326921 0.0072300583, -0.15797119 -0.028555542 0.011392862, -0.15788132 -0.027077109 0.014998257, 0.036958784 -0.13852981 -0.067652687, -0.15844801 -0.021898389 0.016998708, -0.15610921 -0.0084785223 0.035646781, -0.15619335 -0.0067531765 0.035646826, -0.15487491 -0.0111745 0.039422363, -0.14475141 -0.059066892 -0.035648763, -0.14286795 -0.063487321 -0.035649166, -0.14561674 -0.060578644 -0.030003369, -0.1533944 -0.046149135 -0.015002757, -0.15264782 -0.04922685 -0.013003007, -0.15382738 -0.045406789 -0.013002679, -0.15223449 -0.049089968 -0.017002717, -0.1481615 0.0060681105 0.058000356, -0.14825758 0.0028851926 0.05800014, -0.14712594 0.0080308914 0.060000345, -0.15509501 -0.0084236562 0.039266154, -0.15523501 -0.0052477419 0.039266542, -0.15385938 -0.0096829534 0.04299926, -0.12626696 -0.074020058 -0.062004298, -0.13005833 -0.071225256 -0.058004156, -0.12837897 -0.070293456 -0.062003911, -0.12466899 -0.073752701 -0.064942211, -0.12583238 -0.076657087 -0.060004279, -0.15776752 -0.023755848 0.020027548, -0.15672749 -0.029234767 0.020802006, -0.15695052 -0.024582773 0.024244457, 0.028351963 -0.14806965 -0.052296966, 0.022618547 -0.14882362 -0.052851006, 0.023779899 -0.14707887 -0.056449905, -0.15775234 -0.023252815 0.02062887, -0.13405435 -0.070238471 -0.050845698, -0.13211715 -0.070739537 -0.0544447, -0.13129127 -0.075416058 -0.050670102, -0.13322204 -0.074810356 -0.047004282, -0.13408311 -0.070183903 -0.050845787, -0.14624263 0.0059891641 0.062000118, -0.14451441 0.0098674297 0.064941548, -0.14633885 0.0027801692 0.062000103, -0.15393698 -0.0083609521 0.042999506, -0.15346785 -0.002848953 0.044999883, -0.030705765 -0.15423167 0.031991541, -0.12792374 -0.074991405 -0.05800429, -0.12926677 -0.075950503 -0.054293856, -0.13533756 -0.070911229 -0.047003999, -0.16092388 -0.0044591427 0.0019996166, -0.13703483 -0.069149464 -0.04500401, -0.13442233 -0.075476497 -0.043004304, -0.15405792 -0.046349436 -0.0057897121, -0.15526649 -0.041748226 -0.0077893585, -0.15356372 -0.047733903 -0.0072318912, -0.15326424 -0.049151778 -0.0036194921, -0.15484554 -0.044036537 -0.0020026863, -0.1444076 0.0059137046 0.065545306, -0.14329726 0.0048740804 0.067643054, -0.1510247 -0.053395718 -0.01500313, -0.15096541 -0.052864134 -0.017003074, -0.15000492 -0.056773126 -0.013003141, -0.1513734 -0.053016543 -0.013003141, -0.14960274 -0.056605458 -0.017003179, -0.15256613 -0.0082867444 0.046999477, -0.15212068 -0.0042390823 0.048662744, -0.1524888 -0.0096040368 0.046999432, 0.027166381 -0.14973173 -0.048673555, -0.12928592 -0.075790256 -0.054445162, -0.14708798 -0.060020864 -0.024251431, -0.14685176 -0.059536487 -0.026411653, -0.14585273 -0.063817203 -0.022251591, -0.14798854 -0.058446944 -0.022804722, -0.15415974 -0.046380132 -0.0020027161, -0.052261874 -0.13221517 0.06976372, -0.15286136 -0.050541401 -2.9653311e-06, -0.05714643 -0.13275486 0.065537751, -0.13655354 -0.071548492 -0.04300414, -0.13768245 -0.072792172 -0.037826553, -0.13741027 -0.070993096 -0.041429117, -0.027037606 -0.15581653 0.027991176, -0.14247218 0.005834192 0.069034182, -0.14124885 0.0061463118 0.071099021, -0.14168575 0.011648864 0.069774844, -0.15118928 -0.0082122087 0.050663128, -0.15065928 -0.0056065619 0.052285828, -0.023326576 -0.15739417 0.022794887, -0.029478639 -0.15645236 0.022236869, -0.15007094 -0.011806667 0.05284442, 0.033636823 -0.1444172 -0.058008209, 0.029849604 -0.14328581 -0.062008083, 0.03324151 -0.14253718 -0.062008023, 0.03017436 -0.14518008 -0.058008283, -0.14771985 -0.060279042 -0.02003248, -0.14692408 -0.062696606 -0.01863566, -0.1478979 -0.061528444 -0.015003383, -0.15415981 -0.04638046 0.0019973516, -0.15345626 -0.048305035 0.005782038, -0.1548456 -0.044036686 0.0019973218, -0.11623766 -0.08393833 -0.067649722, -0.11914049 -0.082382143 -0.064945549, -0.11803967 -0.079225183 -0.069778785, -0.1147652 -0.084623843 -0.06903629, -0.14205049 0.03527382 0.062001824, -0.11550936 -0.086866766 -0.065547794, -0.14970991 -0.0081322193 0.054286711, -0.14808339 -0.0077476203 0.057999536, -0.14840961 -0.013152927 0.056442745, -0.1447127 0.032352686 0.058001831, -0.15541656 -0.038799822 0.014997825, -0.15382752 -0.0454081 0.012997329, -0.15463458 -0.040074438 0.018627912, -0.15541904 -0.03878966 0.014997751, -0.15533029 -0.041166067 0.0092290044, -0.15405795 -0.046350121 0.005782187, -0.15369369 -0.046870679 0.0093917847, -0.15513989 -0.042615235 0.0056161135, -0.14831282 -0.060521215 -0.015003562, -0.15508294 -0.030961692 0.027998134, -0.15544619 -0.026660323 0.029998392, -0.15586884 -0.030551374 0.024408072, -0.15490444 -0.031843275 0.027998164, -0.14806753 -0.0080430806 0.057999358, -0.11865881 -0.08568722 -0.062004894, -0.12003715 -0.085446715 -0.060004771, -0.11614791 -0.089060992 -0.062005147, -0.11771327 -0.090175688 -0.058005139, -0.14873143 -0.0606924 -0.010014325, -0.14746346 -0.063848197 -0.0092325956, 0.041572183 -0.13594794 -0.069778904, -0.14941151 -0.059651583 -0.0057904273, -0.14975825 -0.05823195 -0.0093993843, -0.15421382 -0.030788213 0.031998381, -0.15403023 -0.031693488 0.031998083, -0.15298975 -0.029153436 0.037818372, -0.1548384 -0.025076091 0.03364554, -0.14615002 -0.0079391599 0.06199941, -0.14663287 -0.014475435 0.059999123, -0.14432438 -0.012364089 0.064937152, -0.14616615 -0.0076372921 0.061999485, -0.1524452 -0.022955865 0.042998351, -0.15219368 -0.02755487 0.041421659, -0.1512856 -0.025947601 0.044998512, -0.15411936 -0.02348423 0.037265241, -0.15273781 -0.020920753 0.042998768, -0.12021565 -0.086811781 -0.058005109, -0.12219866 -0.085238338 -0.056446418, -0.15339428 -0.046150953 0.014997348, -0.15223455 -0.049091786 0.016997293, -0.1534092 -0.0452874 0.016997516, -0.15264794 -0.04922834 0.012997136, -0.14895448 -0.060783774 -0.0057903975, -0.14706226 -0.065246284 -0.0056203902, -0.14864938 -0.061841965 -3.5911798e-06, -0.14431627 -0.0078398883 0.065544315, -0.14179376 -0.010281622 0.069770634, -0.1443997 -0.0061150789 0.065544732, -0.15108791 -0.022751629 0.04699865, -0.1498193 -0.021907389 0.050662391, -0.15138394 -0.020688802 0.046998791, -0.12149586 -0.087736428 -0.054445788, -0.12427436 -0.084949017 -0.052847415, -0.12110721 -0.089787602 -0.052293628, -0.10623147 -0.093289196 -0.071105763, -0.10818627 -0.091015249 -0.071105629, -0.10877849 -0.093402535 -0.067650318, -0.026890472 -0.1549423 0.031991214, -0.10445078 -0.096438587 -0.069776475, -0.14238206 -0.0077350736 0.069033451, -0.14251761 -0.0046088696 0.069033511, -0.13566276 -0.079529822 -0.032004476, -0.13480155 -0.078310877 -0.037268698, -0.13490602 -0.080024302 -0.033649787, -0.13490804 -0.081693143 -0.030004561, -0.13861907 0.036638439 0.067644611, -0.13790333 -0.075578392 -0.032004431, -0.13867852 -0.076008648 -0.028004348, -0.14972435 -0.02254653 0.050662294, -0.1481422 -0.023090571 0.054285578, -0.14875057 -0.027885109 0.050842568, -0.12269342 -0.0886015 -0.05084689, 0.037079886 -0.14357159 -0.058008, 0.036614731 -0.14170808 -0.062008023, -0.12504642 -0.089013517 -0.045005053, -0.12311904 -0.089440852 -0.048670322, -0.10773204 -0.094607323 -0.067650363, -0.10951766 -0.097098023 -0.062005579, -0.10513088 -0.09964484 -0.064943492, -0.13642775 -0.079978526 -0.028004512, -0.13708991 -0.080272734 -0.024252579, -0.15212771 -0.045770496 0.024243042, -0.15192705 -0.047275007 0.022801027, -0.15086719 -0.048469931 0.026407152, -0.15374774 -0.041323423 0.022243321, -0.15211558 -0.043247074 0.027997516, -0.1510247 -0.053397268 0.014996961, -0.14960267 -0.056607425 0.016996935, -0.15096538 -0.052866101 0.01699701, -0.15137337 -0.053017884 0.012996808, -0.14976296 -0.038636297 -0.041427135, -0.14898674 -0.036922455 -0.045002133, -0.15000494 -0.056774497 0.012996867, -0.021790355 -0.15695783 0.026401073, -0.14895461 -0.060784221 0.0057813823, -0.14956209 -0.059089214 0.0072280765, -0.14915574 -0.060485154 0.0036151111, -0.14731486 -0.06441322 0.0077811629, -0.13633893 0.037423134 0.071100488, -0.14188834 -0.07434544 -0.015004188, -0.14253481 -0.073850572 -0.011400446, -0.14289096 -0.072399557 -0.015003979, -0.14116597 -0.074095994 -0.020805389, -0.13948599 -0.078286618 -0.01700449, -0.14284758 0.031892896 0.062001526, -0.13986656 -0.078498036 -0.013004452, -0.15143806 -0.045563072 0.02799724, -0.14970443 -0.049628347 0.029997103, -0.14873144 -0.060693413 0.01000762, -0.14765652 -0.062991351 0.011390939, -0.14789794 -0.061530083 0.014996529, -0.15058893 -0.045307785 0.031997345, -0.14905444 -0.047016561 0.03581699, -0.15126394 -0.043000579 0.031997569, -0.12592186 -0.090933591 -0.039269418, -0.12864767 -0.086949855 -0.039429724, -0.12866274 -0.088729739 -0.03582707, -0.12519306 -0.091934562 -0.039269596, -0.14544494 0.028883696 0.058001727, -0.14831272 -0.060522974 0.014996514, -0.14971018 -0.045043737 0.035644718, -0.14850572 -0.045357317 0.039420418, -0.15077499 -0.041340232 0.035644963, -0.12674509 -0.091528118 -0.035650507, -0.12515813 -0.0936867 -0.035650626, -0.13819014 -0.081012547 -0.015004501, -0.13749391 -0.081734568 -0.017004505, -0.13786659 -0.081959993 -0.01300469, -0.11260556 -0.09888801 -0.054446459, -0.11094771 -0.098380148 -0.058005646, -0.10912459 -0.10281068 -0.054295376, -0.11121733 -0.10274026 -0.050671577, -0.11306325 -0.098364681 -0.05444625, -0.1454162 -0.029033542 0.057998464, -0.1470222 -0.029049367 0.054441057, -0.14518327 -0.030177653 0.057998367, -0.14522509 -0.024909139 0.05999846, -0.1487378 -0.044751227 0.039264314, -0.14784756 -0.043677121 0.042997383, -0.15017563 -0.039659351 0.039264604, -0.096882433 -0.10296476 -0.071106255, -0.093056425 -0.10803962 -0.06903778, -0.097450122 -0.1035051 -0.069780007, -0.14771985 -0.060281336 0.020025656, -0.14629282 -0.063377231 0.020800024, -0.14754559 -0.058891267 0.024242342, -0.1486233 -0.057772964 0.020627022, -0.12748869 -0.092065334 -0.032005221, -0.12502599 -0.095382601 -0.032005265, -0.12574856 -0.095897377 -0.02800566, -0.12848547 -0.091462493 -0.030005172, -0.15135482 0.020896047 0.047001228, -0.15271619 0.021073401 0.043001086, -0.11371548 -0.099863082 -0.050847292, -0.1132341 -0.10257933 -0.047005877, -0.11510338 -0.098260522 -0.050847262, -0.14353305 -0.028657794 0.061998382, -0.14328933 -0.029853165 0.061998181, -0.1407901 -0.027134776 0.067641057, -0.1430878 -0.022537529 0.064939626, -0.12820745 -0.09258461 -0.028005347, -0.1299215 -0.090721339 -0.026413232, -0.1470882 -0.060023814 0.024242274, -0.14516306 -0.064469546 0.024406321, -0.1456168 -0.060581893 0.02999644, -0.11480424 -0.10081935 -0.047005668, -0.11425649 -0.1034959 -0.043005973, -0.11821128 -0.097908705 -0.0450055, -0.13417883 -0.087495953 -0.015004888, -0.13541667 -0.085131764 -0.017004967, -0.1332559 -0.088476032 -0.017005011, -0.1357808 -0.085371017 -0.013004854, -0.13361052 -0.088728845 -0.013005331, -0.12879097 -0.093006432 -0.024253309, -0.13127206 -0.089912176 -0.022806615, -0.12799489 -0.094672501 -0.022253186, -0.1388797 -0.081417412 -0.002004534, -0.1411643 -0.077388853 -0.0020044744, -0.1390917 -0.080708206 -0.0072336793, -0.13848439 -0.082023889 -0.003621459, -0.13778229 -0.083289236 -4.6491623e-06, -0.11583558 -0.10172528 -0.043005735, -0.11816728 -0.099789679 -0.041430652, -0.12934445 -0.093406141 -0.020034358, -0.1304982 -0.092896253 -0.015005246, -0.12928884 -0.093818367 -0.018637359, -0.13887972 -0.08141765 0.0019952804, 0.040501773 -0.14264393 -0.058008, 0.039967313 -0.14079931 -0.062007934, -0.1388602 -0.08124122 0.0057801306, -0.14116421 -0.077389002 0.0019955784, -0.11670773 -0.1024915 -0.039270043, -0.1139956 -0.10634357 -0.037270114, -0.11803223 -0.10160434 -0.037827998, -0.14357327 -0.043198377 0.054284498, -0.14652923 -0.043295264 0.046997547, -0.14368173 -0.044904709 0.052842543, -0.14176269 -0.045847446 0.056440987, -0.14264719 -0.040505111 0.057997666, -0.14563499 -0.038991034 0.052284069, -0.14188831 -0.07434696 0.014995664, -0.14184046 -0.073479235 0.018626079, -0.14289096 -0.072401106 0.014995903, -0.1422756 -0.07469824 0.0092271417, -0.13986658 -0.078499466 0.012995586, -0.13948579 -0.078288645 0.016995654, -0.14475101 -0.059070498 0.035644032, -0.14266723 -0.062465996 0.037816547, -0.14503002 -0.057190269 0.037263244, -0.14537671 -0.058902383 0.0336437, -0.020242229 -0.1564129 0.029990971, -0.11747065 -0.10316157 -0.035651103, -0.11762767 -0.10436988 -0.032005876, -0.14199826 -0.042724729 0.057997577, -0.13973595 -0.046741605 0.05999738, 0.013984606 -0.15934056 -0.01700905, 0.010038987 -0.16007406 -0.013009146, 0.010013983 -0.15963933 -0.01700902, -0.14543377 -0.046838611 -0.047002658, -0.14381044 -0.058687031 0.039263442, -0.14224692 -0.060730278 0.041419916, -0.14425364 -0.054383546 0.042996764, 0.0004388839 -0.16098514 0.0019908994, -0.0035813004 -0.16094598 0.0019908398, -0.0035814345 -0.16094565 -0.0020090491, -0.095111698 -0.11124659 -0.062006339, -0.093417078 -0.11267337 -0.062006325, -0.094695285 -0.11410829 -0.058006525, -0.097820744 -0.10682774 -0.064946979, -0.093283117 -0.11039206 -0.065549046, 0.000438869 -0.16098505 -0.002009064, -0.098013058 -0.11001521 -0.060006171, -0.13022989 -0.094046205 -0.010016233, -0.13239181 -0.091403157 -0.0057922155, -0.13304545 -0.090096265 -0.009401381, -0.1295587 -0.095061034 -0.0092345476, -0.14015937 -0.042171746 0.0619976, -0.13795549 -0.044169545 0.06493523, -0.14080271 -0.039970845 0.06199757, -0.1427367 -0.058249086 0.04299657, -0.14171933 -0.058961213 0.044996679, -0.0087346286 -0.15994877 0.014990985, -0.011655614 -0.16038889 0.0072223991, -0.0073129833 -0.1603651 0.011385426, -0.14356434 0.02849406 0.062001511, -0.096359834 -0.11270642 -0.058006316, -0.01393342 -0.15978363 0.012990981, -0.10016683 -0.11029291 -0.056447804, -0.10470061 -0.11127561 -0.047006309, -0.10225485 -0.11047268 -0.052848756, -0.10012908 -0.11459485 -0.048671558, -0.10210347 -0.11460724 -0.045006484, -0.10545933 -0.11055687 -0.047006324, -0.10637283 -0.1115827 -0.043006346, -0.13819005 -0.081014127 0.014995337, -0.13786657 -0.081961423 0.012995362, -0.13749394 -0.081736475 0.016995296, -0.13042532 -0.094187558 -0.0057922006, -0.14609396 0.025398254 0.058001354, -0.12885629 -0.096334845 -0.0056221634, -0.012434721 -0.15897235 0.02062121, -0.013909653 -0.15934896 0.016991168, -0.15406904 -0.035664111 -0.028002188, -0.13840081 -0.041642636 0.065542601, -0.13941929 -0.038093925 0.065542877, -0.14146569 -0.057730705 0.04699678, -0.13881671 -0.060286105 0.050840765, -0.14298542 -0.053856164 0.046996951, -0.15320133 -0.035481304 -0.032002091, -0.14118874 -0.054696143 0.050660521, -0.097385734 -0.11390692 -0.054447144, -0.0980905 -0.11448526 -0.052295074, -0.02231364 -0.15469438 0.035811082, -0.11936678 -0.10482755 -0.024254009, -0.11828789 -0.10496172 -0.028006122, -0.11579011 -0.10876533 -0.024254113, -0.028174475 -0.15378159 0.035638556, -0.11975154 -0.10434464 -0.024414048, -0.11721738 -0.10810271 -0.020638153, -0.1305117 -0.094250172 -0.0020052791, -0.13116127 -0.093368918 -5.3048134e-06, -0.1280655 -0.097547978 -0.0020054579, -0.10564119 -0.11227572 -0.04300651, -0.1060735 -0.11339664 -0.03943108, -0.081242159 -0.1157046 -0.071107253, -0.085220009 -0.11280686 -0.071106941, -0.085266277 -0.11526611 -0.06765154, -0.15181804 0.017211139 0.047000945, -0.080371588 -0.11726305 -0.069777742, -0.15318522 0.017337441 0.043000862, -0.13654588 -0.041084975 0.069031574, -0.13595173 -0.041576147 0.069768786, -0.13791963 -0.036206514 0.069031924, -0.14018899 -0.057209909 0.050660446, -0.13929051 -0.055476457 0.054283917, -0.11987978 -0.10527804 -0.020034939, -0.12113848 -0.1036506 -0.020807073, -0.11856803 -0.10736236 -0.017006218, -0.13051166 -0.094250292 0.0019945055, -0.13195695 -0.092158914 0.0036131889, -0.12806539 -0.097548157 0.0019944459, 0.014025912 -0.15977415 -0.013008967, -0.082389742 -0.11733934 -0.067651734, -0.085164741 -0.11903349 -0.062006697, -0.080320954 -0.12054041 -0.064944685, -0.13881707 -0.056650251 0.054283917, -0.13687274 -0.061036676 0.054439418, -0.13604191 -0.056600362 0.05999703, -0.023570821 -0.15348017 0.039414167, -0.13417885 -0.087497592 0.014995009, -0.1357806 -0.085372508 0.012995154, -0.13361065 -0.088730216 0.012994811, -0.13325585 -0.088477939 0.016995057, -0.13541682 -0.085133672 0.016995236, -0.1304255 -0.094188273 0.005779475, -0.132664 -0.090888411 0.0072263181, -0.12928826 -0.09557882 0.0077794194, 0.030106351 -0.15341154 -0.035654142, 0.024119839 -0.15441838 -0.035830796, 0.028512627 -0.15268275 -0.039272934, -0.12036102 -0.10570103 -0.015005961, -0.11889224 -0.10765329 -0.013006076, 0.026658535 -0.15544465 -0.030008808, -0.12252782 -0.10371602 -0.011402264, -0.12319784 -0.1023806 -0.015005723, -0.1364276 -0.079981714 0.027995326, -0.13759857 -0.079896688 0.022799261, -0.13629937 -0.080825955 0.026405253, -0.13490799 -0.081696481 0.02999533, -0.14673705 -0.04726997 -0.043002829, -0.1386787 -0.076011717 0.027995527, -0.13758105 -0.072091371 0.039262623, -0.13779628 -0.073854357 0.035643339, -0.13469005 -0.077265799 0.039418496, 0.050976276 -0.1327064 -0.069781765, -0.13758595 -0.072082222 0.03926269, -0.13442224 -0.075481296 0.042995505, -0.084106028 -0.11978391 -0.062006727, -0.08627373 -0.12060162 -0.058007047, -0.080109462 -0.1236622 -0.060006887, -0.13022999 -0.094047427 0.010005772, -0.13049833 -0.092897892 0.014994636, -0.12993756 -0.094268739 0.011389256, -0.12070051 -0.10599968 -0.010016978, -0.11764494 -0.10963547 -0.0072353482, -0.14425218 -0.050359726 -0.047002926, -0.12177625 -0.1049813 -0.0077929348, -0.13566276 -0.079533458 0.031995267, -0.1379033 -0.075581878 0.031995676, -0.13485557 -0.079005569 0.035815105, -0.13655356 -0.07155332 0.04299584, -0.1370348 -0.069154322 0.04499615, -0.14420015 0.025079161 0.062001452, 0.0044588596 -0.16092399 0.0019910038, 0.0044588447 -0.16092378 -0.0020091385, -0.085209548 -0.12135568 -0.058007047, -0.083510354 -0.12451547 -0.054296553, -0.12088174 -0.10615876 -0.0057930797, -0.12040432 -0.10686055 -0.0020060837, -0.13381591 -0.054610103 0.065541729, -0.13122272 -0.057783395 0.067639314, -0.13448581 -0.053812623 0.064937674, -0.1015933 -0.11882943 -0.035652205, -0.10159647 -0.11748758 -0.039271012, -0.10117252 -0.11918798 -0.035652056, -0.10569225 -0.11513501 -0.035828575, -0.10491137 -0.11775985 -0.030006602, -0.11519505 -0.11130828 -0.015006319, -0.11307797 -0.11313036 -0.017006382, -0.1133794 -0.11344463 -0.013006419, -0.11617196 -0.11058319 -0.013006404, -0.1158589 -0.11028063 -0.017006323, -0.13533773 -0.070916504 0.046996102, -0.13330784 -0.070420444 0.052282251, -0.13521793 -0.069822311 0.048659198, -0.15313938 -0.039466023 -0.028002232, -0.13322189 -0.074815631 0.046995819, -0.086117089 -0.12264809 -0.054447666, -0.088339463 -0.12105739 -0.054447621, -0.085566357 -0.12491232 -0.050672829, -0.15227906 -0.039251059 -0.032002136, -0.069875658 -0.12290311 -0.071107566, -0.066681236 -0.12603775 -0.069038749, -0.071973935 -0.12259457 -0.069781169, -0.13202274 -0.053878486 0.069030829, -0.1327104 -0.050980181 0.06977129, -0.12992951 -0.055748224 0.071095265, -0.12934434 -0.093408436 0.020023778, -0.12852252 -0.094341338 0.020798296, -0.1320415 -0.089396268 0.020625263, -0.13074207 -0.090246588 0.02424074, 0.0084760487 -0.16076213 -0.0020090044, -0.10218921 -0.11952668 -0.032006845, -0.10066633 -0.12081212 -0.032006815, -0.10125652 -0.12147471 -0.028006911, -0.14761475 0.020201147 0.056444675, -0.086965829 -0.12385741 -0.050848767, -0.087568656 -0.1252045 -0.047007158, -0.090351865 -0.12140983 -0.050848648, -0.070862755 -0.12463945 -0.067652076, -0.071596056 -0.12591651 -0.064948052, -0.1521917 0.013516098 0.047000557, -0.15356308 0.0135912 0.043000534, -0.1027654 -0.12020093 -0.028006718, -0.10647635 -0.11735696 -0.026414871, -0.12879135 -0.093009412 0.024240434, -0.127178 -0.095155001 0.024404466, -0.087798387 -0.12504345 -0.047007158, -0.092998564 -0.12358242 -0.041431978, -0.093460292 -0.12175819 -0.045006886, -0.035277262 -0.14205399 0.061992064, -0.04057157 -0.14165297 0.059991837, -0.035806447 -0.1439009 0.057991922, -0.088361323 -0.12632543 -0.043007165, -0.12088183 -0.10615951 0.0057787299, -0.12040423 -0.10686076 0.0019937903, -0.11730081 -0.11010367 0.0057785064, -0.12128618 -0.10570765 0.0056125671, -0.042888731 -0.13554421 0.069766596, -0.11813705 -0.10891432 0.0093884021, -0.10976836 -0.11666331 -0.015006602, -0.10655487 -0.11960557 -0.01500687, -0.10966143 -0.11744273 -0.0094029158, -0.11022668 -0.11590984 -0.01700671, -0.1105165 -0.11623532 -0.013006598, -0.03235586 -0.14471593 0.057991818, -0.10323314 -0.12074831 -0.024254829, -0.10371889 -0.12078032 -0.022254765, -0.12820736 -0.092587709 0.027994752, -0.12574869 -0.095900416 0.027994491, -0.12848543 -0.09146595 0.029994771, -0.08858712 -0.12616712 -0.043007195, -0.15814263 -0.00048926473 0.027999952, -0.12070052 -0.10600066 0.010004982, -0.12208669 -0.10448471 0.0092255175, -0.11889225 -0.10765463 0.012993932, -0.12748861 -0.09206903 0.031994656, -0.12502596 -0.095386207 0.031994566, -0.0063744485 -0.15930432 0.020794496, -0.010959804 -0.15848669 0.024236843, -0.12862523 -0.089774936 0.033642136, -0.089254171 -0.12711713 -0.039271563, -0.087473422 -0.12904367 -0.037271395, -0.092463255 -0.12532151 -0.037829429, -0.12036103 -0.10570264 0.014993995, -0.12193388 -0.1031993 0.01862438, -0.12319781 -0.10238212 0.01499407, -0.11856808 -0.10736436 0.01699388, -0.12674466 -0.091531903 0.035642214, -0.1455387 -0.050839543 -0.043002918, -0.12519082 -0.092646241 0.037814744, -0.12866831 -0.088028699 0.037261479, -0.089837536 -0.1279484 -0.035652593, -0.086824015 -0.1306327 -0.033652633, -0.091453761 -0.12792754 -0.032007143, -0.12792352 -0.074997872 0.057995781, -0.13008788 -0.075750977 0.052840829, -0.12800705 -0.076243192 0.056439258, -0.12583247 -0.076663911 0.059995681, -0.13005832 -0.071231693 0.057996064, 0.02189742 -0.15844709 -0.017009065, 0.01800403 -0.15937492 -0.013008967, 0.017946556 -0.15894309 -0.01700893, -0.12592128 -0.090937436 0.039261736, -0.13305451 -0.060982645 -0.062003568, -0.12516728 -0.090860665 0.041417986, -0.066202447 -0.13053408 -0.062007368, -0.071074322 -0.12906677 -0.060007438, -0.066378832 -0.12838161 -0.065550163, -0.066002011 -0.13063562 -0.062007397, -0.066928774 -0.13231915 -0.058007509, -0.057876155 -0.12898862 -0.071107656, -0.057478592 -0.13134956 -0.067652315, -0.05798085 -0.1289418 -0.071107924, -0.1263037 -0.066184044 0.069030248, -0.12640589 -0.065988809 0.069030225, -0.12744787 -0.06816265 0.065541282, -0.12329245 -0.07078591 0.069767281, -0.11987957 -0.10528043 0.020022929, -0.11637023 -0.10851219 0.022797644, -0.12059294 -0.10393986 0.022239745, -0.090364605 -0.12869918 -0.032007262, -0.086101875 -0.13213712 -0.030007586, -0.09196566 -0.12865168 -0.028007448, -0.074798405 -0.13156316 -0.050849244, -0.078213423 -0.13125184 -0.047007486, -0.075107902 -0.13045681 -0.052849829, -0.07311219 -0.1298168 -0.056449011, -0.070155263 -0.13344207 -0.052296206, -0.072118208 -0.13400245 -0.048672572, 0.0084760785 -0.16076249 0.0019907802, -0.12626696 -0.074026823 0.061995797, -0.12837899 -0.07030043 0.061996102, -0.12466889 -0.073760122 0.064933658, -0.067071036 -0.13224703 -0.058007494, -0.09087418 -0.12942505 -0.028007463, -0.088684201 -0.13180405 -0.024255529, -0.1193672 -0.10483062 0.024240047, -0.11828788 -0.10496488 0.027993992, -0.075514436 -0.13282302 -0.047007531, -0.078875929 -0.13245517 -0.043007672, -0.074040368 -0.13445392 -0.045007601, -0.11519521 -0.11130995 0.014993787, -0.11585891 -0.11028251 0.016993865, -0.11617197 -0.11058477 0.012993693, -0.11307789 -0.11313212 0.016993612, -0.1133794 -0.11344597 0.012993485, -0.10454328 -0.12228137 -0.005793944, -0.10515723 -0.12150738 -0.0092358887, -0.10418899 -0.12259272 -0.0056236535, -0.10709627 -0.12021419 -6.7204237e-06, -0.10873331 -0.11857152 -0.0057937056, -0.091287762 -0.13001442 -0.02425538, -0.09352988 -0.12837562 -0.024415255, -0.090223148 -0.13147563 -0.020639554, 0.043292552 -0.14652663 -0.047008216, 0.038638577 -0.14976069 -0.041433528, 0.036924839 -0.14898428 -0.045008495, 0.03859064 -0.14633659 -0.050850049, -0.10461244 -0.12236258 -0.0020069182, -0.10314809 -0.12359944 -0.0020070523, -0.15725601 -0.00050476193 0.031999871, -0.076192945 -0.13401654 -0.043007731, -0.078180507 -0.134157 -0.039432317, -0.072905302 -0.1371491 -0.039272159, -0.031896412 -0.14285102 0.061992034, -0.12275031 -0.08864814 0.05065871, -0.12504646 -0.089018703 0.044995025, -0.12192208 -0.08966431 0.050839156, -0.12345435 -0.085080594 0.054282233, -0.12547849 -0.084742397 0.050659031, -0.091679871 -0.13057327 -0.020036474, -0.095036641 -0.12800768 -0.020808399, -0.091704726 -0.13105446 -0.017007574, -0.10461241 -0.12236288 0.0019930005, -0.14617671 0.018516183 0.060001105, -0.10814132 -0.11921152 0.0036117733, -0.103148 -0.12359971 0.0019928217, -0.076766416 -0.13502577 -0.039271846, -0.077421933 -0.13576719 -0.035829827, -0.15808213 -0.0044030249 0.027999699, -0.12154903 -0.087781042 0.054281898, -0.11985988 -0.089963406 0.054437794, -0.10976836 -0.11666512 0.014993399, -0.11022674 -0.11591181 0.016993538, -0.11051649 -0.11623693 0.012993455, -0.028886974 -0.14544815 0.057991922, -0.10655479 -0.11960724 0.014993086, -0.10883878 -0.11653692 0.020623803, -0.11747032 -0.10316539 0.035641328, -0.11762767 -0.10437328 0.031994082, -0.1138946 -0.10703292 0.035813645, -0.11790773 -0.10266539 0.035641633, -0.11412035 -0.10530007 0.039416946, -0.10454324 -0.12228221 0.0057780147, -0.10477851 -0.12195194 0.0077780336, -0.09204796 -0.13109764 -0.015007496, -0.088414177 -0.13329649 -0.017007336, -0.096376613 -0.1283806 -0.011403531, -0.097327039 -0.12722769 -0.015007168, -0.088652134 -0.13366133 -0.013007671, -0.091956109 -0.13141018 -0.013007462, -0.12021565 -0.086818218 0.057995155, -0.11771335 -0.090182066 0.057994962, -0.12003725 -0.085453361 0.059995189, 0.021971181 -0.15887666 -0.013009176, -0.11670715 -0.10249525 0.039260931, -0.118097 -0.10089082 0.039261036, -0.1142565 -0.10350066 0.042994156, -0.1348287 -0.061720967 -0.05800347, -0.053494394 -0.13623595 -0.062007874, -0.051483735 -0.13539118 -0.064945534, -0.050582603 -0.13838762 -0.060007915, -0.057273418 -0.13677552 -0.058007792, -0.056541234 -0.1349999 -0.062007532, -0.020898923 -0.15135753 0.046991423, -0.024571329 -0.15080491 0.046991587, -0.024799228 -0.15215835 0.042991355, -0.021075875 -0.15271863 0.04299134, -0.092307776 -0.13146773 -0.010018259, -0.09536241 -0.12944716 -0.0077942014, -0.090298995 -0.13306525 -0.0072367787, -0.118659 -0.085694164 0.061995201, -0.11914042 -0.082389534 0.064936258, -0.11614788 -0.089067966 0.061994873, -0.11583575 -0.10173014 0.042994253, -0.11821128 -0.097913831 0.044994555, -0.054196313 -0.13802361 -0.058007762, -0.053708643 -0.13997635 -0.054297462, -0.092446223 -0.13166526 -0.0057943314, -0.09360674 -0.13097364 -0.0020074397, -0.0891812 -0.13398716 -0.00362432, -0.11717001 -0.084619135 0.065540127, -0.11507571 -0.085534543 0.067637883, -0.085705876 -0.13532892 -0.015007764, -0.085068733 -0.13545606 -0.017007664, -0.085292861 -0.13582957 -0.013007745, -0.11480426 -0.10082445 0.046994336, -0.11323436 -0.10258448 0.046994172, -0.11629123 -0.098160654 0.048657276, -0.054773256 -0.13949376 -0.054448664, 0.029762998 -0.15639564 -0.022256941, 0.024052218 -0.15728277 -0.02281028, 0.025367558 -0.15641695 -0.026416898, -0.055624798 -0.14082077 -0.050673649, -0.05918619 -0.13767952 -0.054448545, -0.092507437 -0.13175252 -0.0020074546, -0.087999806 -0.13482243 -7.7039003e-06, -0.038929477 -0.13591242 -0.071108237, -0.036962524 -0.13771561 -0.069039226, -0.042888671 -0.13553646 -0.06978184, -0.1434563 0.020060956 0.064939037, -0.1155997 -0.083485365 0.06902916, -0.11803971 -0.079232991 0.069769695, -0.11426761 -0.083262652 0.071093939, -0.11376803 -0.099914968 0.05065801, -0.11429629 -0.098318756 0.052280664, -0.10997074 -0.10279921 0.05283922, -0.078852937 -0.13869661 -0.020036697, -0.081670567 -0.13753152 -0.017007709, -0.07926023 -0.13796461 -0.022809491, -0.074242055 -0.14083183 -0.022255749, 0.043674603 -0.1478453 -0.043008402, -0.075778499 -0.1406236 -0.018639967, -0.077268407 -0.14031753 -0.015008062, -0.092507362 -0.13175276 0.0019925386, -0.089859471 -0.13344505 0.00577721, -0.09360683 -0.13097394 0.0019925386, 0.040331945 -0.15042669 -0.037830964, -0.039479345 -0.13783258 -0.067652896, -0.041781053 -0.13869107 -0.064948663, -0.036146179 -0.13993335 -0.065550908, -0.11265493 -0.098937333 0.054281391, -0.11094771 -0.098386467 0.057994522, -0.10323338 -0.12075126 0.024238899, -0.10430762 -0.12057498 0.02079688, -0.1028156 -0.12106895 0.02440308, 0.046841234 -0.14543107 -0.047008276, -0.10491127 -0.11776331 0.029993296, -0.10738252 -0.11707696 0.024239227, -0.15719572 -0.0043852329 0.031999782, -0.092446357 -0.13166609 0.0057772845, -0.090939522 -0.13247156 0.0093869567, 0.028431982 -0.15719089 -0.018640861, -0.09472321 -0.1300461 0.0056112409, -0.079169452 -0.1392538 -0.015007898, -0.081880644 -0.13791338 -0.01300779, -0.10276532 -0.12020394 0.027993143, -0.10125643 -0.12147778 0.027993098, -0.04030177 -0.14070392 -0.06200774, -0.035277292 -0.14204699 -0.062007949, -0.040571585 -0.14164624 -0.06000796, -0.092307612 -0.13146901 0.010003522, -0.091956154 -0.13141155 0.012992591, -0.028497532 -0.14356783 0.06199187, -0.095775887 -0.1290319 0.0092241317, -0.07939288 -0.13964689 -0.010018781, -0.075482622 -0.14186043 -0.0092371404, -0.079622269 -0.13979399 -0.0057949275, -0.080778405 -0.13890019 -0.0094041377, -0.10218926 -0.11953023 0.031993225, -0.1006664 -0.12081558 0.031993076, -0.10542402 -0.11614603 0.033640519, -0.025401264 -0.14609727 0.057991892, -0.1056412 -0.11228037 0.042993687, -0.106373 -0.11158741 0.042993657, -0.10585462 -0.11445296 0.037260018, -0.10181133 -0.11643511 0.041416764, -0.10210337 -0.11461228 0.044993483, -0.040830538 -0.14255032 -0.058008134, -0.035806522 -0.1438944 -0.058008268, -0.038701996 -0.14570734 -0.052296743, 0.035665467 -0.15406749 -0.028008848, 0.031841531 -0.15490311 -0.02800867, 0.031691656 -0.15402845 -0.032008693, -0.042391434 -0.14283097 -0.056449547, -0.092048049 -0.13109934 0.014992565, -0.091704696 -0.13105634 0.016992435, -0.095912978 -0.12774485 0.018622994, -0.088414207 -0.13329849 0.016992509, -0.088652119 -0.1336627 0.012992412, 0.035483077 -0.15319961 -0.032008588, -0.097327173 -0.1272293 0.014992803, -0.10159302 -0.11883295 0.035640746, -0.10143682 -0.11818099 0.037813365, -0.02188617 -0.14893794 0.05283688, -0.028061479 -0.14813194 0.052277878, -0.13331456 -0.064926773 -0.058003768, -0.079512075 -0.13985655 -0.0057949722, -0.074297249 -0.14270329 -0.0056248456, -0.077660859 -0.14103121 -8.0317259e-06, -0.13156982 -0.064122975 -0.062003493, -0.10859618 -0.095373631 0.065539412, -0.10951772 -0.097104907 0.061994404, -0.10513084 -0.099652201 0.064932331, -0.10445081 -0.096446455 0.069765784, -0.10908581 -0.094813555 0.065539792, -0.057139874 -0.14552173 -0.035653889, -0.056564778 -0.145273 -0.037272409, -0.055578306 -0.14667761 -0.033653513, -0.06225808 -0.14275435 -0.037830561, -0.06069386 -0.14507034 -0.032008141, -0.10470078 -0.11128092 0.046993852, -0.10545935 -0.11056226 0.046993688, -0.10347624 -0.1105395 0.050657526, -0.017213881 -0.15182081 0.046991438, -0.017339885 -0.15318787 0.04299134, -0.041265264 -0.14406869 -0.054448977, -0.044194773 -0.14389893 -0.052850768, -0.025833622 -0.13899738 -0.071108416, -0.027833998 -0.13861084 -0.071108356, -0.026808679 -0.14084649 -0.067652985, -0.021532074 -0.14052182 -0.069778934, -0.10714073 -0.094095886 0.069028646, -0.1085536 -0.09246251 0.069028795, -0.091679886 -0.13057548 0.020021632, -0.089306712 -0.13168651 0.022796392, -0.094440877 -0.12816834 0.022238627, -0.057474971 -0.14637551 -0.032008246, -0.054539591 -0.14798367 -0.030008331, -0.061031714 -0.1458903 -0.028008297, -0.041672125 -0.14548895 -0.050849974, -0.040491238 -0.14669049 -0.048673466, -0.026198342 -0.14096129 -0.067652971, -0.025082618 -0.14419669 -0.062008113, -0.057799041 -0.14720097 -0.028008252, -0.057131246 -0.14823362 -0.024256349, -0.091287941 -0.13001758 0.024238572, -0.087733224 -0.13195974 0.026402622, -0.091965556 -0.12865469 0.027992666, -0.042071134 -0.14688209 -0.047008142, -0.04226476 -0.1475583 -0.045008391, -0.047045603 -0.14536524 -0.047008142, -0.085705698 -0.13533068 0.014992312, -0.085292876 -0.13583106 0.012992337, -0.085068807 -0.13545796 0.016992494, 0.056596816 -0.13603863 -0.060007572, 0.053808898 -0.13448218 -0.064948484, 0.058989137 -0.13194039 -0.065550327, -0.065573931 -0.1461488 -0.015008405, -0.064169317 -0.14594582 -0.020809457, -0.060242966 -0.14817476 -0.017008275, -0.065392897 -0.14660761 -0.011404485, -0.066575885 -0.14569509 -0.01500833, -0.06040892 -0.14857754 -0.013008535, -0.058062077 -0.1478714 -0.024256378, -0.058704823 -0.14825583 -0.020640567, -0.062618613 -0.14596921 -0.024416238, 0.047272295 -0.14673474 -0.043008342, -0.090874046 -0.12942809 0.027992591, -0.086101994 -0.13214049 0.029992446, -0.079392821 -0.13964808 0.010002956, -0.075014859 -0.14220974 0.0077767372, -0.076168403 -0.14131105 0.011386454, -0.077268437 -0.14031911 0.014992088, -0.080091357 -0.13944834 0.0072236061, -0.081880614 -0.13791478 0.012992233, -0.090364575 -0.12870273 0.031992689, -0.091453597 -0.12793118 0.031992927, 0.050362363 -0.14424971 -0.047008246, -0.087222278 -0.12969339 0.035812482, -0.042768598 -0.14931792 -0.039272815, -0.040558293 -0.14993358 -0.039272815, -0.045269251 -0.14959124 -0.035830662, -0.046367109 -0.14819011 -0.039433286, -0.097428285 -0.1139628 0.054280736, -0.098013133 -0.11002189 0.059993818, -0.10142745 -0.11041865 0.054280676, -0.098913766 -0.11454651 0.050837792, -0.096836656 -0.11437908 0.054436423, -0.025082693 -0.14420366 0.0619919, -0.079169556 -0.13925537 0.014992133, -0.081670627 -0.1375334 0.016992137, -0.089837328 -0.12795189 0.03564024, -0.092106894 -0.12632814 0.035640314, -0.087828219 -0.12805411 0.039415777, -0.043048203 -0.15029415 -0.035653993, -0.03943871 -0.15128163 -0.035653859, -0.058545724 -0.1491034 -0.015008405, -0.056686804 -0.15003708 -0.013008356, -0.056535974 -0.14962849 -0.017008498, -0.13172401 -0.068095565 -0.058003828, -0.13001105 -0.067227125 -0.062003896, -0.096359633 -0.11271298 0.057993792, -0.09469533 -0.11411476 0.057993643, -0.089253664 -0.12712088 0.039259613, -0.09268631 -0.12464035 0.039259776, -0.088361129 -0.12633029 0.042992815, -0.078853086 -0.13869885 0.020021141, -0.074862152 -0.14076266 0.020795658, -0.078638569 -0.1380364 0.024237961, -0.080178186 -0.13783419 0.020622537, 0.039467603 -0.15313771 -0.02800867, -0.043300703 -0.15117604 -0.032008588, 0.039252967 -0.15227726 -0.032008633, -0.04342711 -0.15161726 -0.030008584, -0.027653471 -0.14879134 -0.050850093, -0.028725281 -0.14858836 -0.050850034, -0.027065098 -0.14739767 -0.054449126, -0.02289395 -0.14966768 -0.050674289, -0.095111832 -0.1112535 0.061993711, -0.09341719 -0.11268026 0.061993539, -0.097820833 -0.10683513 0.064934917, -0.08858718 -0.12617189 0.042992935, -0.091533579 -0.12157688 0.048656136, -0.093460202 -0.12176329 0.044993088, -0.043544859 -0.15202862 -0.028008685, -0.045012012 -0.15193319 -0.026416779, -0.02020438 -0.14761794 0.056435227, -0.041042402 -0.15382105 -0.022256568, -0.078515843 -0.13810617 0.02423811, -0.013518751 -0.15219432 0.046991453, -0.013593659 -0.1535655 0.042991281, -0.027918324 -0.15021595 -0.04700844, -0.031374648 -0.150251 -0.04500857, -0.058799058 -0.14974877 -0.0057952851, -0.058425307 -0.14982235 -0.0072377324, -0.057130128 -0.15047237 -0.0036251992, -0.064166754 -0.14742169 -0.0077952147, -0.062115431 -0.14851946 -0.0020084381, -0.093918331 -0.10985795 0.065538734, -0.093158156 -0.10899675 0.067636579, -0.051384643 -0.1517202 -0.015008718, -0.052929252 -0.15140352 -0.013008654, -0.052793831 -0.15098935 -0.017008737, -0.087798372 -0.12504867 0.046992913, -0.0875687 -0.12520963 0.046992943, -0.043743044 -0.15272093 -0.024256781, -0.046572685 -0.15214264 -0.022809967, -0.058837816 -0.1498481 -0.0020085275, -0.055792645 -0.15102383 -8.6128712e-06, -0.02816917 -0.15156588 -0.043008506, -0.030167535 -0.15169424 -0.041433662, -0.15685113 -0.036250323 -0.0020020306, -0.087005951 -0.12392035 0.050656766, -0.084339119 -0.12469268 0.052838102, -0.089553311 -0.12128699 0.052279457, 0.00048772991 -0.15814424 0.027991012, -0.0033778399 -0.15722233 0.031991273, -0.0034261495 -0.15810788 0.027991027, -0.043931007 -0.15337732 -0.02003774, -0.04258664 -0.15396017 -0.018640637, -0.058837906 -0.14984834 0.0019914508, -0.057912275 -0.15009487 0.0057763308, -0.062115461 -0.14851964 0.001991421, -0.028381139 -0.15270716 -0.039272979, 0.06466338 -0.1257236 -0.071107671, -0.0058704317 -0.14325482 -0.067653105, -0.011652753 -0.14168185 -0.069782153, -0.0053902864 -0.1424877 -0.069039568, -0.0098710805 -0.1445109 -0.064948916, -0.0041009635 -0.14446828 -0.065551132, -0.086154796 -0.12270805 0.05427999, -0.082251094 -0.12423334 0.056436613, 0.050841868 -0.14553639 -0.043008283, -0.065574035 -0.14615047 0.014991656, -0.066575766 -0.14569679 0.01499179, -0.058799028 -0.14974946 0.005776301, -0.085209511 -0.12136218 0.057993241, -0.080109373 -0.1236687 0.059992984, -0.076766193 -0.13502949 0.039259091, -0.073349923 -0.13617101 0.041415706, -0.077732846 -0.13513836 0.037258819, 0.060986057 -0.13305113 -0.062007502, -0.0059927255 -0.14623919 -0.062008202, -0.008034423 -0.14712274 -0.060008183, -0.044231802 -0.15442798 -0.010019526, -0.046518847 -0.15400669 -0.0057955086, -0.042023078 -0.1551002 -0.0092379451, -0.084105998 -0.11979073 0.061993219, -0.080321155 -0.12054759 0.064931132, -0.076192901 -0.13402125 0.042992413, -0.074040368 -0.13445878 0.044992417, -0.0060713291 -0.14815816 -0.058008328, -0.0095451474 -0.14868274 -0.05644992, -0.058545679 -0.14910498 0.014991537, 0.053853437 -0.14298287 -0.047008112, -0.044298321 -0.15465975 -0.0057956576, -0.040679812 -0.15565827 -0.005625546, -0.083050653 -0.11828792 0.065538399, -0.080371447 -0.11727098 0.069764592, -0.085253492 -0.11671028 0.065538384, -0.075514436 -0.1328283 0.046992466, -0.076285109 -0.13079366 0.050656289, -0.070945546 -0.13368502 0.050836816, -0.0061359406 -0.14973614 -0.054449216, -0.0053081065 -0.150666 -0.05229716, -0.044327393 -0.15476251 -0.0020087361, -0.15685116 -0.036250561 0.0019979924, 0.04324545 -0.15211403 -0.028008744, 0.0076655447 -0.14116961 -0.071108669, 0.0052057058 -0.14328068 -0.06765309, 0.010277703 -0.14178988 -0.069779202, -0.08193779 -0.11670294 0.069027394, 0.042998701 -0.15126225 -0.032008588, 0.00050289929 -0.15725777 0.031991288, -0.074833006 -0.13162982 0.050656289, -0.074314699 -0.13022009 0.054279521, -0.029152587 -0.15685862 -0.020037904, -0.025760457 -0.15786502 -0.017008886, -0.032486275 -0.15685672 -0.015008941, -0.030084148 -0.15656558 -0.020809993, -0.044327408 -0.15476269 0.0019911528, -0.04570812 -0.15432662 0.0036099553, -0.0083696842 -0.15326843 0.044991389, -0.011401519 -0.15548271 0.037257582, -0.041489482 -0.15533659 0.0077759624, 0.0077737868 -0.1431641 -0.067653149, -0.0070046484 -0.15451145 0.04141441, 0.01236029 -0.14432088 -0.06494613, -0.074100658 -0.13034201 0.054279849, -0.068957821 -0.13305974 0.054435357, -0.018519759 -0.14618003 0.059991688, -0.05806227 -0.14787444 0.024237409, -0.056170002 -0.14817366 0.026401669, -0.051384807 -0.15172184 0.014991343, -0.044298187 -0.15466073 0.0057761371, 0.0044013113 -0.15808365 0.027991012, -0.1558969 -0.040156007 -0.0020022839, -0.047053039 -0.15377414 0.0072226673, -0.029269606 -0.15748861 -0.015008897, -0.025832579 -0.15829471 -0.013009012, -0.01198265 -0.15094015 0.05065529, -0.031129956 -0.15748313 -0.011405051, -0.057798982 -0.1472041 0.027991608, -0.054539517 -0.14798698 0.029991701, 0.0079357177 -0.14614657 -0.062008306, 0.014471933 -0.14662939 -0.060008183, -0.044231847 -0.15442914 0.010002092, -0.042814106 -0.15471718 0.011385813, -0.029352143 -0.15793332 -0.010019764, -0.057475016 -0.14637914 0.031991854, 0.061724186 -0.13482553 -0.058007687, -0.056176424 -0.14585069 0.035811394, -0.0063594431 -0.1551919 -0.039273039, -0.0061777383 -0.15519935 -0.039273024, -0.010846689 -0.15591392 -0.035830945, 0.0080397874 -0.14806443 -0.058008492, 0.012344867 -0.14941734 -0.054297999, -0.057139561 -0.14552528 0.035639167, 0.054381058 -0.14425138 -0.043008015, -0.0064010173 -0.1562067 -0.035654306, -0.0047861338 -0.15626445 -0.035654336, -0.027223766 -0.13997298 0.069026381, -0.02174288 -0.15870291 -0.015008941, -0.017911717 -0.15938538 -0.013009146, -0.021878988 -0.15888923 -0.013008997, -0.017871752 -0.15895149 -0.01700902, -0.021822751 -0.15845746 -0.01700905, 0.0081254542 -0.14964136 -0.05444923, 0.0064132512 -0.14972454 -0.05444935, 0.010984778 -0.15100947 -0.050674245, -0.067071185 -0.13225359 0.057992548, 0.021050185 -0.13980189 -0.071108371, -0.070473827 -0.12396315 0.069026902, 0.013984591 -0.15934253 0.016991049, 0.010013968 -0.15964121 0.016991124, 0.010039061 -0.16007566 0.012991041, -0.066827074 -0.12459654 0.071091719, 0.014025912 -0.15977553 0.012991041, -0.043931022 -0.15337965 0.02002041, -0.045951292 -0.15207434 0.02423726, -0.041663036 -0.15389171 0.02079466, -0.0064384639 -0.15712324 -0.032008782, 0.030886292 -0.15789342 -0.0056256801, 0.024908945 -0.15893909 -0.0057958364, 0.02943413 -0.15797353 -0.0092380643, -0.0085998476 -0.15747938 -0.030008733, -0.020064741 -0.14346012 0.064929813, 0.0082055926 -0.1511167 -0.050850287, -0.026173741 -0.14214286 0.065536976, 0.0050595999 -0.1512548 -0.050850302, -0.066202357 -0.13054106 0.061992645, 0.027213693 -0.15868351 -8.9555979e-06, -0.0064748824 -0.15800923 -0.028008923, -0.010074869 -0.15813991 -0.026417062, 0.060590237 -0.13804808 -0.05229637, -0.043743283 -0.15272406 0.024237156, -0.040104434 -0.15368956 0.024401203, 0.0082841516 -0.15256369 -0.047008529, 0.0028464496 -0.15346542 -0.045008719, -0.15589704 -0.040156156 0.0019977093, -0.014166728 -0.15955779 -0.015009075, -0.0065043569 -0.15872875 -0.024257123, -0.00578475 -0.15909725 -0.02225703, 0.0043834746 -0.15719748 0.031991228, -0.043544829 -0.15203178 0.027991384, 0.0083584934 -0.15393451 -0.043008626, 0.0043445528 -0.15460378 -0.041433886, -0.029352188 -0.15793437 0.010002077, -0.025832653 -0.15829602 0.012991026, -0.032486334 -0.15685835 0.014991209, -0.030306429 -0.15780938 0.009222433, -0.043300688 -0.15117958 0.031991541, -0.044590786 -0.1503858 0.033638805, 0.0084214658 -0.1550937 -0.039273202, 0.01206924 -0.15542865 -0.037273049, 0.0058472157 -0.15562987 -0.037831306, -0.054797322 -0.13956079 0.054279149, -0.052545145 -0.13942108 0.056435823, -0.029269487 -0.15749049 0.01499106, -0.025760338 -0.15786701 0.016991049, -0.030988559 -0.15670922 0.01862143, -0.043048084 -0.15029779 0.03563872, -0.045713425 -0.14904734 0.037258148, -0.021531954 -0.14052975 0.069763437, -0.040115416 -0.15048951 0.037811622, 0.0084764957 -0.15610775 -0.035654187, 0.013567448 -0.15626618 -0.033654079, 0.0083122402 -0.15792635 0.027990982, -0.054196388 -0.13803011 0.057992324, -0.050582647 -0.13839412 0.059992209, -0.042768225 -0.14932162 0.039258242, -0.041210607 -0.14907885 0.041414991, 0.028654099 -0.14352959 -0.062008113, -0.029152602 -0.15686098 0.020020217, 0.064929947 -0.13331139 -0.058007494, 0.064126372 -0.13156644 -0.062007412, 0.0085262209 -0.15702367 -0.032008693, -0.053494364 -0.13624284 0.061992332, -0.14828427 -0.00066012144 0.057999879, -0.051483735 -0.13539845 0.064930186, -0.042449057 -0.1482068 0.042991549, 0.029030204 -0.1454131 -0.058008149, 0.0085743219 -0.15790927 -0.028008953, 0.015069887 -0.15699238 -0.030008793, 0.012843236 -0.15834212 -0.024257004, 0.022749007 -0.15108538 -0.047008619, 0.025945023 -0.1512832 -0.04500851, -0.021742776 -0.15870464 0.014990881, -0.017911658 -0.15938693 0.012990966, -0.017871797 -0.1589534 0.016991153, -0.021822825 -0.15845928 0.016991079, -0.021878958 -0.15889069 0.012991086, -0.0065868795 -0.16074404 -0.0057959706, -0.0050226897 -0.16080758 -0.0056257695, -0.052822977 -0.13453364 0.065537363, 0.0086134076 -0.1586282 -0.024257094, 0.011434957 -0.15904483 -0.020641059, 0.0069168508 -0.15868282 -0.024416924, -0.0065912604 -0.16085058 -0.0020091087, -0.1431164 -0.065170318 -0.032003537, -0.0087789446 -0.16076067 -9.1791153e-06, 0.022953257 -0.15244287 -0.0430087, 0.022523016 -0.15363249 -0.039433345, -0.041691318 -0.14556193 0.050655425, -0.039419591 -0.1461201 0.050836027, -0.043475494 -0.1434918 0.054279044, 0.0086503327 -0.15931004 -0.020038113, 0.0055095404 -0.15933466 -0.020810246, -0.0065913498 -0.16085073 0.0019910634, -0.010221213 -0.16062838 0.0036095083, 0.02312611 -0.15359077 -0.039273053, 0.041307732 -0.13729575 -0.067652732, 0.04416573 -0.13795191 -0.064945653, -0.041283444 -0.14413768 0.054278836, -0.037620857 -0.14506826 0.054434583, -0.014166638 -0.15955949 0.014990807, -0.0065868497 -0.16074479 0.0057757497, -0.0058837682 -0.16067433 0.0077758133, 0.0086850077 -0.15994987 -0.01500909, 0.004693985 -0.16046181 -0.011405215, 0.0032322407 -0.16015282 -0.01500909, -0.040830538 -0.14255685 0.057992116, 0.0082612038 -0.1570414 0.031991199, -0.028381079 -0.15271088 0.039258346, -0.029429018 -0.1525124 0.039258257, 0.042168155 -0.14015594 -0.06200783, 0.046738088 -0.13973278 -0.060007975, 0.046539351 -0.15251261 -0.020640552, 0.040826797 -0.15411371 -0.020809919, 0.042054027 -0.15316516 -0.024416685, 0.008709535 -0.16040137 -0.010019884, 0.0061516762 -0.16066316 -0.0077959299, 0.06809862 -0.1317209 -0.058007449, 0.067230552 -0.13000751 -0.062007502, 0.012366265 -0.16033506 -0.0072381943, -0.04030174 -0.14071095 0.0619919, -0.041781038 -0.13869843 0.064933047, -0.028169036 -0.15157074 0.042991415, -0.031374633 -0.15025607 0.044991434, -0.14636377 -0.00069335103 0.061999992, 0.042721465 -0.14199519 -0.058008, 0.04528448 -0.14292401 -0.05429773, 0.0087226182 -0.16064236 -0.0057959557, 0.013815045 -0.16035888 -0.0036256015, -0.039796039 -0.13894561 0.065537363, -0.036642238 -0.13862294 0.067634791, -0.14393535 -0.065511256 -0.028003931, 0.070296809 -0.12837547 -0.062007234, 0.066858873 -0.1268324 -0.067652225, 0.070781916 -0.12328851 -0.069778189, 0.016286001 -0.15935546 -0.015008956, -0.027918354 -0.15022132 0.046991423, -0.0297198 -0.14925218 0.04865475, 0.043176398 -0.14350745 -0.054448783, 0.044312805 -0.144779 -0.050674021, 0.045286134 -0.15340847 -0.017008722, 0.039569959 -0.14454359 -0.054449067, -0.14822629 -0.0042049885 0.057999797, 0.0087282807 -0.16074869 -0.0020090044, 0.053417236 -0.13089812 -0.071107775, 0.056968153 -0.13071525 -0.069038972, -0.039262772 -0.13708371 0.069026232, -0.037427068 -0.13634306 0.071090877, 0.030786395 -0.15421194 -0.032008812, 0.021897376 -0.15844908 0.016991064, 0.017946616 -0.15894499 0.016991034, 0.018004104 -0.15937632 0.012991041, -0.02766636 -0.14886591 0.050655395, 0.021971002 -0.15887803 0.012991056, -0.15221033 -0.013307542 0.046999201, 0.043601945 -0.14492232 -0.050849959, -0.153577 -0.01343748 0.042999089, 0.0087283999 -0.16074899 0.0019908249, 0.015259251 -0.16027537 -9.1642141e-06, 0.012946337 -0.16035795 0.0057758093, 0.05417186 -0.13274744 -0.067652553, 0.030960038 -0.1550816 -0.028008863, -0.0065044612 -0.158732 0.024236888, -0.0049000531 -0.1587604 0.02440086, 0.0087226182 -0.16064304 0.0057757944, 0.011494905 -0.16027042 0.0093854219, 0.0070245713 -0.16073316 0.0056094676, 0.030017033 -0.15795514 0.0077758878, 0.024326533 -0.15896127 0.007222414, 0.02577804 -0.15887552 0.0036096573, 0.023849994 -0.15840003 -0.015008822, 0.027076155 -0.15788051 -0.015008897, -0.0064748824 -0.15801242 0.027991101, -0.0085997432 -0.15748268 0.02999115, 0.0087095797 -0.16040254 0.010001823, 0.0055691749 -0.16059655 0.0092224777, 0.023917153 -0.158847 -0.010019794, 0.02344805 -0.15896088 -0.009405151, -0.0064386725 -0.15712667 0.03199105, -0.010009244 -0.15653777 0.033638269, 0.0086850077 -0.15995148 0.014991015, 0.0046591461 -0.1596759 0.01862134, 0.0032324493 -0.16015458 0.014990956, -0.0064010471 -0.15621009 0.035638556, 0.073756292 -0.1246652 -0.064944893, -0.005623132 -0.1556429 0.037811175, 0.045041889 -0.14970887 -0.035653889, 0.046353221 -0.14884606 -0.037272498, 0.045407414 -0.15382683 -0.013008773, 0.041748554 -0.15526608 -0.0077956319, 0.040282503 -0.15539405 -0.011404976, 0.048000306 -0.14932925 -0.033653662, 0.056622371 -0.13875353 -0.054448649, 0.05516848 -0.14005911 -0.052850574, 0.055912554 -0.13809961 -0.056449383, 0.065618351 -0.12522769 -0.071107715, 0.071228504 -0.13005516 -0.058007479, -0.02605471 -0.14019507 0.069025993, -0.13136421 -0.078026384 -0.047004387, 0.0086503476 -0.15931225 0.020020053, 0.0060739517 -0.15908936 0.02223666, 0.012281448 -0.15863869 0.022794858, 0.028554797 -0.15797168 0.011385635, 0.045306116 -0.15058729 -0.032008588, 0.04962647 -0.14970276 -0.03000848, 0.057180539 -0.1401214 -0.050849661, 0.059804484 -0.13993254 -0.048673019, 0.045561567 -0.15143654 -0.028008759, 0.047756001 -0.15151411 -0.024256557, -0.14630614 -0.0041664541 0.061999738, 0.0086132437 -0.15863147 0.024237007, 0.013682067 -0.15787137 0.026400983, 0.057728037 -0.14146322 -0.047007978, 0.058958754 -0.14171675 -0.045008078, 0.016286016 -0.15935707 0.01499106, 0.038798898 -0.15541568 -0.015008777, 0.038788825 -0.15541828 -0.015008911, 0.036250383 -0.15685132 0.0019910932, 0.032322362 -0.15770763 0.0019910485, 0.032322198 -0.15770736 -0.002009064, 0.036250368 -0.15685105 -0.0020087659, 0.045768842 -0.15212598 -0.024256557, -0.14226983 -0.069053352 -0.028004065, -0.14146453 -0.068682134 -0.032003939, 0.0085743368 -0.15791243 0.027991146, 0.031516567 -0.15787041 -0.0020090044, 0.058246538 -0.14273435 -0.043008089, 0.056145132 -0.14476874 -0.039432973, 0.0617733 -0.14251 -0.039272517, -0.0061993301 -0.15128803 0.050655127, -0.010456234 -0.14956856 0.054278463, -0.0059171021 -0.1512284 0.050835729, 0.0085261166 -0.15702724 0.031991079, 0.015069962 -0.15699577 0.02999109, 0.012668118 -0.15578118 0.035810918, 0.031516507 -0.15787062 0.0019909889, -0.15184213 -0.017003179 0.046999089, -0.1532032 -0.017184138 0.042998984, 0.058685124 -0.14380914 -0.039272472, 0.05787684 -0.14517951 -0.035830244, -0.0061386675 -0.14980778 0.054278597, -0.0043976605 -0.14980248 0.054434255, 0.023849934 -0.15840167 0.014990836, 0.02707617 -0.15788221 0.014990985, 0.0084763616 -0.15611127 0.035638601, 0.011172161 -0.15487713 0.039414138, 0.0067511946 -0.15619549 0.035638601, 0.059068799 -0.14474955 -0.035653695, 0.063489333 -0.1428659 -0.035653368, 0.060580134 -0.14561504 -0.030008301, 0.046149909 -0.15339348 -0.015008569, 0.049227476 -0.15264729 -0.013008669, 0.049090773 -0.1522336 -0.017008513, -0.0060713887 -0.14816475 0.057991639, -0.0080344081 -0.14712945 0.059991896, -0.0028884262 -0.14826089 0.057991743, 0.0084213465 -0.15509728 0.039258033, 0.0096803904 -0.15386185 0.042991132, 0.0052455366 -0.15523723 0.039258093, 0.07402344 -0.12626362 -0.062007189, 0.076660499 -0.12582919 -0.060007125, 0.023754507 -0.15776855 0.020020232, 0.02923353 -0.15672877 0.020794898, 0.024581283 -0.15695202 0.024236932, 0.02325131 -0.15775359 0.020621344, 0.070241243 -0.1340515 -0.050849333, 0.07541889 -0.13128859 -0.050673217, 0.074812979 -0.13321927 -0.047007546, -0.13253891 -0.078736812 -0.043004572, 0.070186645 -0.13408035 -0.050849348, 0.070742503 -0.13211423 -0.054448336, -0.0059926063 -0.14624605 0.061991721, -0.002783671 -0.14634225 0.061991662, -0.0098711103 -0.14451817 0.064932942, 0.0083585382 -0.15393928 0.042991415, 0.0028464347 -0.1534704 0.044991344, 0.074994668 -0.12792063 -0.058007389, 0.075953439 -0.12926385 -0.054296896, 0.070913628 -0.13533512 -0.047007531, 0.075478792 -0.13441998 -0.043007702, 0.069151804 -0.13703221 -0.045007765, -0.12942883 -0.081196159 -0.047004506, 0.046349674 -0.15405756 -0.0057955384, 0.047734246 -0.15356347 -0.007237792, 0.049151912 -0.15326414 -0.003625378, 0.044036567 -0.15484548 -0.0020087361, -0.0059174895 -0.14441133 0.065536782, -0.00487791 -0.1433011 0.067634761, 0.053396627 -0.15102389 -0.015008494, 0.056606367 -0.14960185 -0.017008483, 0.056773737 -0.15000421 -0.013008446, 0.079229176 -0.11803597 -0.069780871, 0.053017095 -0.1513727 -0.013008475, 0.052865028 -0.15096447 -0.017008483, 0.0082840323 -0.15256882 0.046991482, 0.0042364448 -0.15212348 0.048654467, 0.0096012354 -0.15249157 0.046991453, 0.075793102 -0.1292828 -0.054447979, 0.06002222 -0.14708662 -0.024256513, 0.058448151 -0.14798713 -0.022809833, 0.059537873 -0.14685035 -0.02641651, 0.06381838 -0.14585158 -0.022256047, 0.046380267 -0.15415978 -0.0020088255, 0.050541431 -0.15286145 -8.7320805e-06, 0.071550727 -0.13655117 -0.043007806, 0.072794273 -0.13768053 -0.037829995, 0.070995331 -0.13740802 -0.041432753, 0.040156022 -0.15589702 0.0019911081, -0.14051737 -0.072553217 -0.02800408, -0.13972656 -0.072152168 -0.032004148, -0.0058382154 -0.14247632 0.069025889, -0.0061505735 -0.14125308 0.071090639, -0.011652842 -0.14168954 0.069766313, 0.0082092285 -0.15119222 0.050655097, 0.011803627 -0.15007389 0.052836463, 0.040156156 -0.15589702 -0.0020087808, 0.0056036562 -0.15066221 0.052277654, 0.06028007 -0.14771882 -0.020037502, 0.062697664 -0.14692309 -0.01864019, 0.061529249 -0.14789727 -0.015008375, 0.046380371 -0.15416008 0.0019912273, 0.048304752 -0.15345678 0.0057761073, 0.044036523 -0.15484568 0.0019912273, 0.083941951 -0.11623386 -0.067651525, 0.082385778 -0.11913693 -0.064947575, 0.084627569 -0.11476129 -0.069038004, 0.086870432 -0.11550593 -0.065549448, 0.0081290454 -0.14971295 0.054278463, 0.013149559 -0.14841288 0.056435317, 0.0077444166 -0.14808664 0.057991728, 0.038798973 -0.15541735 0.014991105, 0.04007338 -0.15463576 0.018621504, 0.038788676 -0.15541977 0.014991179, 0.041165456 -0.15533081 0.0092225671, 0.045407414 -0.1538282 0.01299122, 0.046349674 -0.15405834 0.0057763159, 0.046870098 -0.1536943 0.0093858689, 0.042614833 -0.15514028 0.0056095868, 0.060522214 -0.14831212 -0.015008494, 0.030959994 -0.15508479 0.027991191, 0.026658595 -0.15544793 0.029991329, 0.030549943 -0.15587035 0.024401024, 0.031841457 -0.15490612 0.027991295, 0.0080397427 -0.1480709 0.057991683, 0.085690603 -0.11865538 -0.062006712, 0.085450098 -0.12003392 -0.060006753, 0.089064494 -0.11614454 -0.062006533, 0.090178803 -0.11771017 -0.058006704, 0.060692877 -0.14873073 -0.010019317, 0.059651881 -0.14941126 -0.0057953596, 0.058232293 -0.14975768 -0.0094046891, 0.063848555 -0.14746311 -0.0092376024, 0.030786484 -0.15421557 0.031991288, 0.031691596 -0.15403199 0.031991214, 0.029151291 -0.15299204 0.037811518, -0.15406898 -0.035667211 0.027997866, 0.025074139 -0.15484029 0.033638373, 0.0079355389 -0.14615345 0.061991781, 0.0076337457 -0.14616957 0.061991677, 0.014472008 -0.14663631 0.059991732, 0.012360305 -0.14432812 0.064929768, 0.022953317 -0.1524477 0.04299131, 0.02348192 -0.15412155 0.037257746, 0.027552351 -0.15219632 0.041414693, 0.025945008 -0.15128815 0.044991493, 0.020918235 -0.15274039 0.04299137, 0.00065690279 -0.14828742 0.057991594, 0.08681491 -0.1202125 -0.058006868, 0.085241437 -0.12219545 -0.056448609, 0.046150029 -0.15339524 0.014991239, 0.049090818 -0.15223551 0.016991436, 0.045286223 -0.15341032 0.016991496, 0.049227476 -0.1526486 0.012991369, -0.13057633 -0.081950277 -0.043004677, 0.060783982 -0.14895427 -0.005795449, 0.065246776 -0.14706188 -0.0056250393, 0.06184186 -0.14864939 -8.4638596e-06, 0.0078360289 -0.14431983 0.065536976, 0.010277748 -0.14179772 0.069763154, 0.0061114281 -0.14440328 0.065537065, 0.022748902 -0.15109059 0.046991453, 0.021904558 -0.14982221 0.050655335, 0.020685986 -0.15138677 0.046991438, 0.087739259 -0.1214928 -0.054447711, 0.089790508 -0.12110436 -0.052295506, 0.084951892 -0.1242713 -0.052849695, 0.09329322 -0.10622758 -0.071106628, 0.091019168 -0.10818249 -0.071106791, 0.093406215 -0.10877478 -0.067651242, 0.096442476 -0.10444701 -0.069777057, 0.0077311546 -0.14238605 0.069025815, 0.0046049654 -0.14252153 0.069026068, 0.079531506 -0.13566095 -0.032007575, 0.075580046 -0.13790148 -0.032007918, 0.078312844 -0.13479957 -0.037271753, 0.076010078 -0.13867718 -0.02800788, 0.08002606 -0.13490403 -0.033652753, 0.081694663 -0.13490638 -0.030007601, 0.02254355 -0.14972731 0.050655171, 0.023087353 -0.14814535 0.054278523, 0.02788198 -0.1487534 0.050835729, 0.065172076 -0.14311457 -0.032008156, 0.088604197 -0.12269074 -0.050848633, 0.089443579 -0.12311637 -0.04867205, 0.089016065 -0.12504414 -0.045007035, -0.12741695 -0.084318131 -0.047004893, 0.094611034 -0.10772833 -0.067651093, 0.099648565 -0.10512727 -0.06494391, 0.097101361 -0.10951424 -0.062006339, 0.079980001 -0.13642615 -0.028007776, 0.080274001 -0.13708863 -0.024255753, 0.045768932 -0.15212929 0.02423729, 0.047273546 -0.15192837 0.022795245, 0.048468277 -0.15086862 0.026401535, 0.041321993 -0.15374896 0.022237197, 0.04324542 -0.15211716 0.027991444, 0.053396598 -0.15102556 0.014991373, 0.056606367 -0.14960372 0.016991511, 0.052864999 -0.15096655 0.016991392, 0.053017035 -0.15137428 0.012991562, 0.056773812 -0.1500057 0.012991488, 0.060784012 -0.14895499 0.0057764649, 0.059088647 -0.14956251 0.0072229654, 0.060484871 -0.14915603 0.0036101043, 0.064412594 -0.1473155 0.0077764243, 0.074346066 -0.14188761 -0.015008107, 0.078287423 -0.13948497 -0.017007977, 0.078498781 -0.13986599 -0.013007954, 0.074097022 -0.14116487 -0.020809203, 0.073851183 -0.14253432 -0.01140435, 0.072400182 -0.14289007 -0.015007973, 0.045561373 -0.15143952 0.027991384, 0.049626619 -0.14970624 0.029991329, 0.060692787 -0.14873189 0.010002553, 0.062990785 -0.14765707 0.011386111, 0.061529204 -0.1478987 0.014991507, 0.045306042 -0.15059093 0.031991571, 0.047014594 -0.14905646 0.035811305, 0.042998731 -0.15126577 0.031991437, -0.15320131 -0.03548491 0.031997964, 0.090935662 -0.12591976 -0.03927137, 0.091936588 -0.12519109 -0.039271563, 0.086951897 -0.12864542 -0.039432123, 0.088731632 -0.12866071 -0.035829321, 0.060522124 -0.14831376 0.014991626, 0.045041576 -0.14971232 0.035638869, 0.045355022 -0.14850807 0.0394146, 0.041338161 -0.1507771 0.035638779, 0.0915301 -0.12674314 -0.035652503, 0.093688622 -0.1251561 -0.035652429, 0.081013262 -0.13818926 -0.015007943, 0.081735432 -0.13749307 -0.017007887, 0.081960693 -0.13786581 -0.013007849, -0.15313934 -0.039469182 0.027997658, 0.09889102 -0.11260253 -0.054447278, 0.098367706 -0.11306006 -0.054447085, 0.098383322 -0.11094454 -0.058006302, 0.10281365 -0.10912159 -0.054295674, 0.10274297 -0.11121449 -0.05067198, 0.029030189 -0.14541957 0.057991743, 0.029046208 -0.14702541 0.054434523, 0.030174345 -0.14518648 0.057991773, 0.024905756 -0.14522853 0.059991896, 0.044749036 -0.14874005 0.039258301, 0.043674648 -0.14785019 0.042991579, 0.039657041 -0.1501779 0.039258257, 0.10296866 -0.096878409 -0.071106121, 0.10804348 -0.093052506 -0.069036826, 0.10350886 -0.097446263 -0.069779769, 0.00068984926 -0.14636713 0.061991736, 0.060280129 -0.14772108 0.020020664, 0.057771638 -0.14862451 0.020622, 0.063375846 -0.14629409 0.020795286, 0.058889836 -0.14754707 0.024237558, 0.092066988 -0.12748685 -0.032007277, 0.095384434 -0.12502423 -0.032007158, 0.095898837 -0.12574717 -0.028007194, 0.091464087 -0.12848395 -0.030007318, 0.099865749 -0.11371276 -0.050848261, 0.098263189 -0.11510059 -0.050848171, 0.10258189 -0.11323181 -0.047006458, 0.028654233 -0.14353663 0.061991841, 0.029849574 -0.14329275 0.06199193, 0.027130947 -0.14079371 0.067634746, 0.065512806 -0.14393392 -0.028008208, 0.022533894 -0.14309135 0.064932913, 0.0042018741 -0.14822942 0.057991713, 0.092586085 -0.12820578 -0.028007209, 0.090722665 -0.12992007 -0.026415527, -0.12853594 -0.085114807 -0.04300496, 0.060022488 -0.14708978 0.024237469, 0.064467937 -0.14516437 0.02440162, 0.060580119 -0.1456185 0.029991671, 0.10082181 -0.1148017 -0.047006533, 0.097911134 -0.11820868 -0.045006737, 0.10349815 -0.11425424 -0.04300648, 0.087496713 -0.13417792 -0.015007675, 0.085371524 -0.1357801 -0.013007686, 0.085132554 -0.13541591 -0.017007619, 0.088729441 -0.13360998 -0.013007686, 0.088476792 -0.13325489 -0.01700756, 0.093007624 -0.12878972 -0.024255276, 0.089913234 -0.13127074 -0.022808954, 0.094673604 -0.1279937 -0.022255242, 0.081417486 -0.1388796 -0.0020077527, 0.077388778 -0.14116406 -0.0020079613, 0.080708608 -0.13909128 -0.0072370619, 0.082023904 -0.13848424 -0.0036243498, 0.083288968 -0.13778234 -7.8827143e-06, 0.10172759 -0.11583328 -0.043006495, 0.099791989 -0.11816484 -0.041431814, 0.013304785 -0.15221325 0.046991363, 0.013435021 -0.15357947 0.042991176, 0.093407184 -0.12934324 -0.020036459, 0.092896938 -0.13049743 -0.015007436, 0.093819365 -0.1292879 -0.018639341, 0.081417531 -0.13887978 0.0019919872, 0.081240892 -0.13886049 0.0057767779, 0.077388823 -0.14116442 0.0019919574, 0.10249346 -0.1167056 -0.039270863, 0.10160641 -0.11803031 -0.037829041, 0.10634553 -0.11399359 -0.037270635, 0.043195203 -0.14357641 0.05427891, 0.040501863 -0.14265057 0.057992086, 0.038988039 -0.1456379 0.052277982, 0.043292508 -0.14653194 0.046991751, 0.044901639 -0.14368477 0.052836865, 0.045844033 -0.14176577 0.056435809, 0.07434614 -0.14188924 0.014991939, 0.078287438 -0.13948685 0.016992107, 0.073478013 -0.1418415 0.01862219, 0.072400317 -0.14289194 0.01499182, 0.074697673 -0.1422762 0.0092234313, 0.078498751 -0.1398674 0.012992084, 0.059068516 -0.14475295 0.035639241, 0.062463745 -0.14266941 0.037811935, 0.057187989 -0.14503223 0.037258342, 0.058900312 -0.14537874 0.03363879, 0.10316366 -0.11746883 -0.035651907, 0.1043714 -0.1176258 -0.032006696, 0.042721435 -0.14200154 0.057992041, 0.046737999 -0.13973945 0.059992239, 0.058684841 -0.14381289 0.039258718, 0.06072779 -0.14224944 0.0414152, 0.054381087 -0.14425614 0.042991757, 0.11124998 -0.09510833 -0.06200546, 0.10683142 -0.097817153 -0.064946532, 0.11039563 -0.093279272 -0.065548316, 0.11267669 -0.093413651 -0.062005326, 0.11411144 -0.094692051 -0.058005437, 0.1100184 -0.098009825 -0.060005501, 0.094046861 -0.13022938 -0.010018244, 0.090096623 -0.13304505 -0.0094038248, -0.15227902 -0.039254695 0.031997748, 0.091403484 -0.13239142 -0.0057945102, 0.095061451 -0.12955815 -0.009236455, 0.042168275 -0.14016289 0.061991841, 0.039967328 -0.14080632 0.061992124, 0.044165671 -0.13795912 0.064930186, 0.058246583 -0.14273909 0.042991817, 0.058958769 -0.14172176 0.044992089, 0.1127097 -0.096356452 -0.058005497, 0.11029603 -0.10016367 -0.056447163, 0.11127809 -0.10469806 -0.047006056, 0.11158483 -0.10637045 -0.043006063, 0.11055949 -0.1054568 -0.047005981, 0.1145974 -0.1001263 -0.048670679, 0.1146097 -0.10210094 -0.045005843, 0.11047567 -0.10225192 -0.052848443, 0.081013188 -0.13819093 0.014992177, 0.081735358 -0.13749492 0.016992286, 0.081960753 -0.13786736 0.012992188, 0.094187871 -0.13042501 -0.0057943761, 0.096335202 -0.12885585 -0.0056239665, 0.041639119 -0.13840452 0.065537289, 0.038090095 -0.13942292 0.065537304, 0.078028932 -0.13136166 -0.047007337, 0.057727844 -0.14146832 0.046992093, 0.060283214 -0.13881978 0.050836399, 0.053853408 -0.14298815 0.046992004, 0.054693207 -0.14119175 0.050655678, 0.11390983 -0.097382754 -0.05444628, 0.11448823 -0.098087698 -0.05229421, 0.10482883 -0.11936563 -0.024254829, 0.10496329 -0.11828631 -0.028006732, 0.10876662 -0.11578888 -0.024254501, 0.10810368 -0.11721638 -0.020638749, 0.10434589 -0.11975038 -0.024414718, 0.094250277 -0.13051155 -0.0020074397, 0.093368933 -0.13116142 -7.4356794e-06, 0.097548053 -0.12806529 -0.0020073205, 0.0041630864 -0.1463097 0.061991826, 0.1122779 -0.10563892 -0.043006152, -0.11552374 -0.092964143 -0.058005124, -0.11400169 -0.091792196 -0.062005118, 0.11339882 -0.1060715 -0.039430797, 0.11570834 -0.081238329 -0.071105137, 0.11726689 -0.080367625 -0.069775656, 0.11281081 -0.085216314 -0.071105435, 0.11526974 -0.085262507 -0.067649916, 0.041080996 -0.13654983 0.069026306, 0.036202595 -0.13792372 0.069026262, 0.041572183 -0.13595572 0.069763526, 0.057206944 -0.14019191 0.050655708, 0.055473283 -0.13929379 0.054279298, 0.10527909 -0.11987853 -0.020035788, 0.10736322 -0.11856705 -0.01700668, 0.10365163 -0.12113747 -0.020808205, 0.069054917 -0.14226839 -0.028008193, 0.094250128 -0.13051173 0.0019927025, 0.092158705 -0.13195729 0.0036111474, 0.097548082 -0.12806562 0.0019926578, 0.068683982 -0.14146289 -0.032007918, 0.1173429 -0.082386196 -0.067649707, 0.12054402 -0.080317557 -0.064942554, 0.11903684 -0.085161299 -0.06200473, 0.056647167 -0.13882017 0.054279059, 0.061033383 -0.13687578 0.054435089, 0.056596786 -0.13604531 0.059992239, 0.087496907 -0.13417974 0.014992461, 0.088476956 -0.13325676 0.01699239, 0.085132614 -0.13541794 0.016992301, 0.085371614 -0.13578165 0.012992278, 0.088729411 -0.13361129 0.012992501, 0.09418793 -0.13042578 0.0057774484, 0.090888038 -0.13266426 0.0072239041, 0.095578298 -0.12928885 0.0077775121, 0.10570189 -0.12036017 -0.015006959, 0.10765387 -0.11889175 -0.013006806, 0.10371651 -0.12252736 -0.011403278, 0.10238135 -0.12319714 -0.015006885, 0.079980046 -0.13642925 0.027992234, 0.079895303 -0.13759989 0.02279596, 0.080824316 -0.13630095 0.026402354, 0.017000437 -0.15184486 0.046991482, 0.017181784 -0.15320569 0.042991221, 0.081694707 -0.13490978 0.029992208, 0.076010168 -0.13868022 0.027992055, 0.072089165 -0.1375832 0.039259136, 0.072079942 -0.13758817 0.039259002, 0.073852271 -0.13779828 0.035639614, 0.07726343 -0.13469216 0.039415255, 0.075478792 -0.13442484 0.042992264, 0.11978723 -0.08410269 -0.0620047, 0.12366532 -0.080106229 -0.060004696, 0.12060471 -0.086270511 -0.058005035, -0.14656091 -0.066605121 -0.0020037144, 0.094046772 -0.13023055 0.010003626, 0.092896894 -0.13049915 0.01499261, 0.094268113 -0.12993822 0.011387095, 0.10600005 -0.12069994 -0.010017648, 0.10963583 -0.11764464 -0.0072357506, 0.10498169 -0.1217759 -0.0077937543, 0.07953161 -0.13566455 0.031992331, 0.075580165 -0.13790527 0.031992272, 0.079003558 -0.13485765 0.03581205, -0.13996829 -0.075081229 -0.024412379, 0.071550772 -0.13655603 0.042992339, 0.069151878 -0.13703731 0.044992343, 0.1213588 -0.085206449 -0.058004797, 0.12451835 -0.083507508 -0.054294348, 0.10615912 -0.12088126 -0.0057938397, 0.10686049 -0.12040418 -0.0020066649, 0.054606408 -0.13381967 0.065537289, 0.057779402 -0.13122657 0.067635208, 0.053808898 -0.1344896 0.064933345, 0.1188314 -0.10159135 -0.035651267, 0.11513714 -0.10569021 -0.035828128, 0.11748959 -0.10159439 -0.039270237, 0.11776154 -0.10490978 -0.030005977, 0.11918992 -0.10117057 -0.035651132, 0.11130917 -0.11519444 -0.015006468, 0.11313099 -0.1130769 -0.017006457, 0.11344519 -0.11337885 -0.013006389, 0.11058392 -0.11617136 -0.013006404, 0.11028139 -0.11585799 -0.017006546, 0.078739136 -0.1325365 -0.043007642, 0.070913583 -0.13534036 0.046992451, 0.07041733 -0.13331085 0.052278727, 0.069819644 -0.13522068 0.04865548, 0.074812934 -0.13322455 0.046992511, -0.1383339 -0.079308927 -0.020636454, 0.1226511 -0.08611396 -0.054445773, 0.12491512 -0.0855636 -0.050670698, 0.12106028 -0.088336527 -0.054445848, 0.12290706 -0.069871724 -0.071104437, -0.1132682 -0.09569943 -0.058005556, -0.11179113 -0.094471723 -0.062005311, 0.12604153 -0.066677332 -0.069035366, 0.12259848 -0.071970046 -0.069778383, 0.053874463 -0.13202658 0.069026604, 0.050976396 -0.13271427 0.069766641, 0.055744305 -0.12993386 0.071091279, 0.081198663 -0.12942627 -0.047007352, 0.093407139 -0.12934554 0.020021692, 0.090245277 -0.13074353 0.024238363, 0.089395031 -0.1320428 0.020622954, 0.094339952 -0.12852377 0.02079618, 0.11952834 -0.10218751 -0.032005742, 0.12081385 -0.10066456 -0.032005802, 0.1214762 -0.10125488 -0.028005764, 0.1238602 -0.086963147 -0.050846726, 0.12520684 -0.087566108 -0.047005042, 0.12141253 -0.090349168 -0.050846905, 0.12464318 -0.070858926 -0.067649141, 0.12592012 -0.07159242 -0.064944968, 0.1202023 -0.1027638 -0.028005868, 0.11735837 -0.10647491 -0.02641426, 0.093007863 -0.12879285 0.024238601, 0.095153525 -0.12717938 0.024402663, -0.14656091 -0.06660527 0.0019961596, 0.12504593 -0.087795764 -0.047004879, 0.12358458 -0.092996329 -0.041430295, 0.12176074 -0.093457639 -0.045005262, 0.12632765 -0.088358998 -0.04300487, 0.10615917 -0.12088209 0.0057778955, 0.10686056 -0.12040448 0.0019931048, 0.11010318 -0.1173012 0.0057782829, 0.10891366 -0.11813763 0.009387657, 0.10570726 -0.1212866 0.0056117475, 0.11666432 -0.10976756 -0.015006289, 0.11744311 -0.10966092 -0.009402439, 0.11623603 -0.11051592 -0.01300627, 0.11591068 -0.11022589 -0.017006159, 0.072554827 -0.14051592 -0.028007925, 0.072153911 -0.13972464 -0.032007962, 0.11960648 -0.10655415 -0.015006021, 0.1207495 -0.10323194 -0.02425389, 0.12078145 -0.10371783 -0.022253796, 0.09258613 -0.12820894 0.027992576, 0.091464043 -0.12848723 0.029992595, 0.095898822 -0.12575024 0.02799283, 0.12616934 -0.0885849 -0.043005094, 0.10600017 -0.12070122 0.010003969, 0.10765384 -0.11889306 0.012993276, -0.14485207 -0.070244253 -0.0020040423, 0.1044841 -0.12208733 0.0092243552, 0.092066973 -0.12749028 0.031992689, 0.095384434 -0.12502775 0.031992927, 0.08977294 -0.12862718 0.033639923, 0.12711921 -0.089252114 -0.039269537, 0.12904567 -0.087471306 -0.03726922, 0.1253235 -0.092461348 -0.037827671, 0.10570185 -0.1203618 0.014993116, 0.10736321 -0.11856902 0.016993329, 0.10319822 -0.12193501 0.018623382, 0.10238127 -0.12319881 0.014993072, 0.091529846 -0.12674671 0.035640195, 0.088026404 -0.1286706 0.037259281, 0.092644155 -0.125193 0.037812918, 0.12795034 -0.089835614 -0.035650507, 0.13063449 -0.086822152 -0.033650085, 0.12792914 -0.091451794 -0.03200525, 0.074994668 -0.12792695 0.057992741, 0.075748146 -0.13009086 0.052837789, 0.076239884 -0.1280103 0.056436539, 0.076660395 -0.12583584 0.059992909, 0.071228489 -0.13006163 0.057992697, 0.090935275 -0.1259236 0.039259627, 0.090858266 -0.12516975 0.041416153, 0.13053758 -0.066199154 -0.062003791, 0.13063903 -0.065998673 -0.062003776, 0.13232222 -0.066925794 -0.058004111, 0.12838528 -0.066375226 -0.06554687, 0.12906982 -0.071070999 -0.060003921, 0.12899271 -0.057872295 -0.071103901, 0.13135321 -0.057474852 -0.067648321, 0.12894575 -0.057976991 -0.071103781, 0.066180289 -0.12630767 0.069026724, 0.068158925 -0.12745166 0.06553793, 0.070781976 -0.12329647 0.069764137, 0.065984994 -0.12640992 0.069026932, 0.10527924 -0.11988091 0.020022303, 0.10851085 -0.11637163 0.022797227, 0.035665542 -0.15407076 0.027991235, 0.10393855 -0.12059438 0.02223894, 0.1287009 -0.090362847 -0.03200525, 0.13213871 -0.08610037 -0.030004933, 0.12865323 -0.091964126 -0.028005198, -0.14208378 -0.075251579 -0.0077912211, 0.13156584 -0.074795544 -0.050845936, 0.13344498 -0.070152283 -0.05229257, 0.13400516 -0.07211563 -0.048669368, 0.13125433 -0.07821095 -0.047004461, 0.13045973 -0.075105071 -0.052846923, 0.12981988 -0.073109031 -0.056445777, 0.074023396 -0.12627062 0.061992854, 0.070296764 -0.12838247 0.061992809, 0.073756397 -0.12467256 0.064930737, 0.13225028 -0.067067921 -0.058003843, 0.12942645 -0.090872496 -0.028005108, 0.13180538 -0.08868283 -0.024253055, 0.10482897 -0.11936852 0.024239063, 0.10496326 -0.11828944 0.027993396, 0.081952542 -0.13057408 -0.043007672, 0.13282557 -0.075511992 -0.047004402, 0.13245763 -0.078873873 -0.043004453, 0.13445634 -0.07403785 -0.045004278, 0.11130914 -0.11519602 0.014993384, 0.11344522 -0.11338031 0.012993664, 0.11313096 -0.1130788 0.016993597, 0.11028129 -0.1158599 0.016993538, 0.11058383 -0.11617285 0.012993559, 0.12228182 -0.10454291 -0.005792886, 0.11857174 -0.10873297 -0.0057931095, 0.12150754 -0.10515666 -0.0092351586, 0.12021409 -0.10709634 -6.0796738e-06, 0.12259313 -0.10418868 -0.0056225955, 0.13001569 -0.09128648 -0.024253264, 0.13147667 -0.09022215 -0.020637259, 0.12837698 -0.093528748 -0.024413407, 0.12236261 -0.10461229 -0.0020060241, 0.12359956 -0.10314801 -0.0020058602, 0.13401869 -0.076190531 -0.043004319, 0.13715121 -0.072903395 -0.039268434, 0.13415915 -0.078178346 -0.039429277, -0.14485215 -0.070244491 0.0019959509, 0.088645205 -0.12275323 0.050656736, 0.08901599 -0.125049 0.044992998, 0.08966136 -0.12192503 0.050837517, 0.085077479 -0.1234574 0.054280177, 0.084739387 -0.12548134 0.050656587, 0.1305742 -0.091679007 -0.020034164, 0.13105527 -0.091703832 -0.01700522, 0.12800869 -0.095035493 -0.02080673, 0.12236278 -0.10461259 0.0019938499, 0.11921109 -0.10814142 0.0036124736, 0.12359953 -0.10314825 0.0019940883, 0.084320575 -0.12741452 -0.047007293, 0.13502778 -0.076764524 -0.039268807, 0.1357692 -0.077419907 -0.035826474, 0.087777764 -0.12155226 0.054280266, 0.089960277 -0.11986297 0.054436043, 0.11666428 -0.10976923 0.014993712, 0.11653581 -0.10884005 0.020624116, 0.11591063 -0.11022764 0.016993895, 0.11623602 -0.11051735 0.012993798, 0.11960639 -0.1065557 0.014993951, 0.10316314 -0.11747226 0.035640508, 0.10437149 -0.11762953 0.031993285, 0.107031 -0.11389661 0.035813123, 0.10529763 -0.11412266 0.039416641, 0.10266317 -0.1179097 0.035640553, 0.12228186 -0.10454354 0.0057787746, 0.12195131 -0.10477906 0.0077789575, 0.13109845 -0.092047185 -0.015005171, 0.13366191 -0.088651359 -0.013005063, 0.13141064 -0.091955423 -0.013005331, -0.14305274 -0.073839456 -0.0020042658, 0.13329744 -0.088413298 -0.017005011, 0.12838118 -0.096376151 -0.011401549, 0.12722836 -0.097326279 -0.015005708, 0.08681491 -0.12021899 0.057993203, 0.090178758 -0.11771658 0.057993516, 0.085449919 -0.12004048 0.059993252, 0.10249303 -0.11670938 0.039260253, 0.10349819 -0.11425897 0.042993546, 0.10088855 -0.11809933 0.039260224, 0.035483062 -0.1532031 0.031991482, 0.13623938 -0.053490967 -0.062003151, 0.13500333 -0.056537896 -0.062003255, 0.13539469 -0.051480085 -0.064940959, 0.13839072 -0.050579458 -0.060003057, 0.13677867 -0.057270288 -0.058003396, 0.13146833 -0.09230715 -0.010016248, 0.13306548 -0.090298742 -0.0072341263, 0.12944745 -0.095362127 -0.0077923387, 0.085690558 -0.1186623 0.061993271, 0.082385808 -0.11914414 0.064934224, 0.089064464 -0.11615136 0.06199339, 0.10172759 -0.11583811 0.042993397, 0.097911194 -0.11821386 0.044993356, 0.13802685 -0.05419293 -0.058003157, 0.1399793 -0.053705722 -0.054292634, 0.13166554 -0.09244591 -0.0057923496, 0.13398714 -0.089180946 -0.0036219358, 0.13097383 -0.09360674 -0.0020053834, 0.084615424 -0.1171737 0.065538362, 0.085530594 -0.11507952 0.067636117, 0.039467618 -0.15314087 0.02799128, 0.13532972 -0.085705042 -0.015004843, 0.1358301 -0.08529219 -0.013004795, 0.13545687 -0.085067898 -0.017004997, 0.10082184 -0.11480686 0.046993554, 0.098158002 -0.11629418 0.048656523, 0.10258184 -0.11323702 0.046993494, 0.13949655 -0.05477035 -0.054443941, 0.13768247 -0.059183359 -0.054444224, 0.14082348 -0.055622071 -0.050668925, 0.13175255 -0.092507184 -0.0020052791, 0.13482228 -0.08799988 -4.902482e-06, 0.13097383 -0.093606979 0.0019946694, 0.083481371 -0.11560357 0.069027379, 0.083258599 -0.11427173 0.071092144, 0.079229057 -0.11804363 0.069767609, 0.099911958 -0.11377105 0.050657347, 0.10279617 -0.10997361 0.052838892, 0.098315686 -0.11429924 0.052279696, 0.13869768 -0.078851849 -0.020033449, 0.13796595 -0.079258978 -0.022806019, 0.14083274 -0.074240834 -0.022252157, 0.13753247 -0.081669778 -0.017004743, 0.14062457 -0.07577756 -0.018636331, 0.14031842 -0.077267647 -0.015004441, 0.13175265 -0.092507511 0.001994729, 0.13344458 -0.089859962 0.0057795793, 0.098934382 -0.11265805 0.054280728, 0.098383203 -0.11095083 0.057993889, 0.12074977 -0.10323507 0.024240062, 0.11776161 -0.10491315 0.029993907, 0.11707531 -0.10738403 0.024239704, 0.12057376 -0.10430881 0.020797655, 0.12106748 -0.102817 0.024404034, 0.085117087 -0.12853366 -0.043007314, 0.13166569 -0.092446625 0.0057795346, 0.13247091 -0.090940028 0.009389326, 0.13004579 -0.094723582 0.0056131333, 0.13925458 -0.079168797 -0.015004501, 0.13791397 -0.081880093 -0.01300469, 0.12020227 -0.1027669 0.027994037, -0.14305282 -0.073839694 0.0019955933, 0.12147617 -0.10125798 0.02799423, 0.13146824 -0.092308223 0.010005847, 0.13141081 -0.091956943 0.012994707, 0.12903127 -0.095776439 0.0092259496, 0.13964742 -0.079392314 -0.010015339, 0.13979429 -0.07962203 -0.0057914704, 0.13890053 -0.080778033 -0.0094007701, 0.14186077 -0.07548207 -0.0092334449, 0.11952838 -0.10219106 0.031994238, -0.14736405 -0.03798309 0.048660971, -0.14898673 -0.036927551 0.044997931, 0.11614397 -0.10542604 0.03364113, 0.12081394 -0.10066813 0.031994313, 0.11227787 -0.10564375 0.042994007, 0.11643267 -0.10181367 0.041417435, 0.11460976 -0.102106 0.04499422, 0.11158483 -0.1063754 0.042993948, 0.11445083 -0.10585672 0.037260503, 0.1310984 -0.092048943 0.014994651, 0.13105536 -0.091705799 0.016994774, 0.12774371 -0.095914036 0.018624842, 0.1272285 -0.097327948 0.014994502, 0.133662 -0.088652819 0.012994945, 0.13329738 -0.088415146 0.016994983, 0.1188309 -0.10159498 0.035641655, 0.11817892 -0.10143897 0.037814528, -0.10561903 -0.10273543 -0.060005784, 0.13985696 -0.079511702 -0.0057913363, 0.14270379 -0.074296921 -0.0056210458, 0.095370024 -0.10859996 0.065538675, 0.097101361 -0.10952118 0.061993822, 0.09964852 -0.10513452 0.064932063, 0.09644255 -0.10445479 0.069765434, 0.0948098 -0.10908952 0.065538883, 0.14552361 -0.057137817 -0.035648793, 0.14527491 -0.056562752 -0.037267342, 0.14667945 -0.055576473 -0.033648521, 0.14507219 -0.060691953 -0.032003492, 0.14275634 -0.062255919 -0.037825882, 0.11127815 -0.10470331 0.04699406, 0.11053646 -0.10347912 0.050657824, 0.11055936 -0.10546201 0.04699403, 0.094091922 -0.10714477 0.069027841, 0.092458516 -0.10855764 0.069027901, 0.13057415 -0.091681182 0.020023718, 0.12816696 -0.094442129 0.022240385, 0.13168496 -0.089308023 0.022798702, 0.14637724 -0.057473302 -0.032003313, 0.14798528 -0.054538071 -0.030003101, 0.039252877 -0.15228084 0.031991363, 0.1458919 -0.061030328 -0.028003439, 0.14720252 -0.057797432 -0.02800341, 0.14823484 -0.057129949 -0.024251461, 0.13001598 -0.091289431 0.024240673, 0.1286532 -0.091967225 0.027994677, 0.1319582 -0.087734729 0.026404738, 0.13532974 -0.085706741 0.014994904, -0.14072633 -0.020171434 0.069773175, 0.14614952 -0.065573215 -0.015003905, 0.14569591 -0.066575021 -0.01500386, 0.14787257 -0.058060795 -0.024251461, 0.14597066 -0.062617183 -0.024411634, -0.14442021 -0.033639938 0.057998121, 0.12942646 -0.090875685 0.027994707, 0.13213879 -0.086103678 0.029995114, 0.13964747 -0.079393625 0.010006234, 0.14131036 -0.076168895 0.011390045, 0.14031838 -0.077269256 0.014995381, 0.12870091 -0.090366453 0.031994924, 0.12969133 -0.087224454 0.035814866, 0.1279292 -0.09145543 0.03199473, 0.11395974 -0.09743157 0.054281637, 0.11041555 -0.10143062 0.054281294, 0.11454359 -0.09891665 0.050838694, 0.11437604 -0.096839726 0.054437339, 0.11001836 -0.09801653 0.059994444, 0.13925447 -0.079170376 0.014995456, 0.12795 -0.089839399 0.035642162, 0.12805168 -0.087830335 0.039417952, 0.12632616 -0.092108935 0.035642192, 0.14910407 -0.058544934 -0.015003204, 0.1127097 -0.096362919 0.057994649, 0.092967242 -0.11552048 -0.058006495, 0.12711863 -0.089255869 0.039261818, 0.091795608 -0.1139982 -0.062006354, 0.12463805 -0.09268859 0.039261654, 0.13869782 -0.078854263 0.020024449, 0.13803501 -0.078640133 0.024241433, 0.13783275 -0.080179542 0.02062583, 0.14076133 -0.074863523 0.02079922, 0.11124997 -0.095115215 0.061994478, 0.12616932 -0.088589728 0.042994961, 0.12157415 -0.091536373 0.048657849, 0.12176076 -0.093462706 0.044994652, 0.13810459 -0.078517228 0.024241433, 0.14974929 -0.058798641 -0.0057902783, 0.15047257 -0.057130098 -0.0036201626, 0.10985418 -0.093922079 0.065539524, 0.151721 -0.051383942 -0.015002921, 0.12504588 -0.087801158 0.046995059, 0.14984822 -0.058837771 -0.0020034015, 0.15102386 -0.055792928 -3.2484531e-06, 0.12391743 -0.087008893 0.050658628, 0.12128404 -0.089556366 0.052281097, 0.12468977 -0.08434236 0.052840382, 0.14984819 -0.05883801 0.0019965768, 0.15009455 -0.057912678 0.0057814717, 0.12270488 -0.086157709 0.054282114, 0.12423001 -0.08225435 0.056439042, 0.14614949 -0.065574914 0.014996216, 0.14569598 -0.066576868 0.014996082, 0.1497491 -0.058799297 0.0057814568, 0.066605136 -0.14656106 -0.002008155, 0.12135889 -0.085212857 0.05799517, 0.12366529 -0.080112755 0.059995472, 0.13502711 -0.076768398 0.039262474, 0.13513611 -0.077735007 0.037262008, 0.13616839 -0.073352367 0.041419223, -0.13907622 -0.025438637 0.071097136, 0.075082526 -0.13996702 -0.024415985, 0.11978714 -0.084109455 0.061995193, 0.12054388 -0.080324709 0.06493327, 0.13401881 -0.076195329 0.042995617, -0.14254048 -0.033245027 0.061998039, 0.13445638 -0.074043036 0.044995755, 0.14910401 -0.058546424 0.014996573, 0.11828415 -0.083054364 0.065540165, 0.11726697 -0.080375493 0.06976667, 0.11670654 -0.085257232 0.065540135, 0.13282548 -0.075517178 0.046995744, 0.13079068 -0.076288074 0.050659418, 0.13368215 -0.070948303 0.050840303, 0.11669905 -0.081941694 0.069029331, -0.14357495 -0.037083179 0.057997897, 0.13162678 -0.074835986 0.050659448, 0.13021691 -0.074317813 0.054282859, 0.13033865 -0.074103773 0.054282799, 0.079309985 -0.13833281 -0.020639896, 0.13305654 -0.068960845 0.054439083, 0.14787303 -0.058063865 0.024242342, 0.14817224 -0.056171626 0.02640672, 0.15172097 -0.051385671 0.014997125, 0.14720252 -0.057800621 0.027996689, 0.095702693 -0.11326492 -0.05800654, 0.09447512 -0.11178774 -0.062006339, 0.14798528 -0.054541349 0.029996663, 0.14637734 -0.057476878 0.031996563, 0.1458485 -0.05617848 0.035816371, 0.14552316 -0.057141602 0.035644084, -0.14543355 -0.046843916 0.046997391, -0.14673701 -0.047274798 0.042997241, 0.1322502 -0.067074329 0.057996139, 0.12395915 -0.070477605 0.069029897, 0.12459235 -0.066831201 0.071094841, 0.13053742 -0.066205949 0.061996296, 0.1395577 -0.05480057 0.054283947, 0.13941783 -0.052548319 0.056440651, 0.13802689 -0.054199427 0.057996944, 0.13839068 -0.050586164 0.059997112, 0.13623932 -0.053497761 0.061997056, 0.13539475 -0.051487356 0.064935029, 0.066605166 -0.14656118 0.00199157, 0.13452992 -0.052826941 0.065541878, 0.070244208 -0.14485198 -0.0020081848, -0.11070757 -0.10530114 -0.047005951, -0.14171159 -0.036618382 0.061998054, 0.075251848 -0.14208335 -0.0077948868, -0.1233367 -0.098980099 -0.028005794, -0.12263414 -0.098438859 -0.032005489, -0.14425218 -0.050364971 0.046997301, -0.14553869 -0.050844193 0.04299695, -0.14393538 -0.065514445 0.027996086, 0.070244268 -0.14485225 0.0019918382, -0.14176752 -0.07606855 0.0056141019, 0.07383956 -0.1430527 -0.0020081103, -0.11169472 -0.10625547 -0.043006122, -0.13941056 -0.079895645 0.009389773, -0.10811539 -0.10796094 -0.0470061, -0.1208494 -0.1020022 -0.028005883, -0.12016742 -0.10143515 -0.032005608, -0.14311627 -0.065173864 0.031996161, 0.07383956 -0.14305305 0.001991719, 0.037980154 -0.14736691 0.048654765, 0.036924824 -0.14898914 0.044991642, -0.14226994 -0.069056422 0.027995907, 0.10273871 -0.10561568 -0.060005933, -0.10906643 -0.10895151 -0.043006286, -0.14069803 -0.074499458 0.022241399, 0.020167381 -0.14073023 0.069766268, 0.033636883 -0.14442366 0.057991803, -0.14146453 -0.068685621 0.031996056, -0.14051741 -0.072556376 0.027995832, -0.11371605 -0.10803735 -0.033651412, 0.025434539 -0.13908035 0.071090594, 0.033241466 -0.14254397 0.061991856, 0.037079871 -0.14357817 0.057991967, 0.046841189 -0.14543635 0.046991974, -0.13972655 -0.072155803 0.031995915, 0.047272265 -0.14673945 0.042991504, -0.091940135 -0.11633971 -0.058006674, -0.090717003 -0.11485845 -0.062006369, -0.11334686 -0.10966465 -0.030006066, 0.10530382 -0.11070508 -0.047006279, 0.036614716 -0.14171505 0.061992034, 0.098981798 -0.12333533 -0.02800712, 0.098440588 -0.12263229 -0.032006934, 0.050362334 -0.14425492 0.046991721, 0.050841928 -0.14554125 0.042991593, 0.065512747 -0.14393696 0.027991921, -0.089132369 -0.11850461 -0.058006898, -0.087965712 -0.11697885 -0.062006548, 0.076068297 -0.1417678 0.0056105703, 0.10625753 -0.11169234 -0.043006405, 0.079895079 -0.13941118 0.0093864799, 0.10796347 -0.10811284 -0.047006026, 0.10200365 -0.12084785 -0.028006911, 0.10143703 -0.12016565 -0.0320068, 0.065172061 -0.14311823 0.031992048, 0.069054887 -0.14227149 0.027991906, -0.12558946 -0.10071582 0.0019942224, -0.12558939 -0.10071567 -0.0020058006, 0.10895382 -0.10906419 -0.043006137, 0.074498028 -0.14069924 0.022237748, -0.13482881 -0.061727524 0.057996497, 0.068683878 -0.14146629 0.031992033, 0.072554693 -0.1405189 0.027992159, -0.12303527 -0.10382059 0.0019941628, -0.12303527 -0.10382044 -0.0020059049, 0.1080392 -0.11371425 -0.033651859, -0.13305452 -0.060989439 0.061996572, -0.13331455 -0.06493333 0.057996288, 0.072154015 -0.13972831 0.031992182, 0.11634284 -0.091936946 -0.058005169, 0.11486192 -0.09071359 -0.062005147, 0.10966621 -0.11334524 -0.030006334, -0.11676019 -0.11078298 -0.0036229342, -0.13156982 -0.064129859 0.061996408, -0.13172407 -0.068101883 0.057996251, -0.13136426 -0.07803157 0.046995528, -0.13253896 -0.07874155 0.04299552, -0.10797313 -0.11686856 -0.022807926, 0.11850782 -0.08912918 -0.058005095, 0.1169824 -0.0879623 -0.062005073, -0.084499612 -0.12729573 -0.047007218, -0.10517049 -0.12023553 -0.018638849, -0.11579412 -0.11186033 -6.3478947e-06, -0.13001105 -0.067234129 0.061995976, -0.098218888 -0.12394354 -0.028007135, -0.097654253 -0.12325943 -0.032006964, -0.12942883 -0.081201315 0.046995319, -0.13057625 -0.081955075 0.042995267, -0.085249707 -0.12844577 -0.043007508, -0.081380531 -0.12931213 -0.047007263, 0.10071565 -0.12558973 0.0019928217, 0.10071565 -0.1255894 -0.0020070821, -0.095121488 -0.12633622 -0.028007209, -0.094582722 -0.12563184 -0.032007158, 0.10382049 -0.12303519 -0.0020071417, -0.12741706 -0.084323287 0.04699529, -0.12853608 -0.085119575 0.042995133, 0.06172429 -0.13483202 0.057992384, -0.12333676 -0.098983139 0.027994312, -0.082087398 -0.13048944 -0.043007419, 0.10382044 -0.1230354 0.0019929558, -0.12263414 -0.098442465 0.031994499, 0.060986102 -0.13305807 0.061992511, 0.064929932 -0.13331789 0.057992503, -0.12084934 -0.1020053 0.027994037, 0.11078313 -0.11675999 -0.0036233217, -0.12016749 -0.10143882 0.031994365, 0.064126268 -0.1315732 0.061992764, 0.06809856 -0.13172728 0.057992503, -0.063746348 -0.13388136 -0.058007583, -0.062883288 -0.13216513 -0.062007397, 0.078028947 -0.13136688 0.046992525, 0.078739196 -0.13254127 0.042992368, -0.052262083 -0.13220727 -0.069778636, 0.11686981 -0.10797209 -0.022807598, 0.12729833 -0.084497064 -0.047004879, 0.12023652 -0.10516948 -0.018637866, 0.11186025 -0.11579436 -6.6608191e-06, -0.060527354 -0.13536704 -0.058007628, -0.059729233 -0.13362011 -0.062007472, 0.067230508 -0.13001445 0.061992586, -0.11489709 -0.10912889 0.026403621, 0.12394492 -0.098217547 -0.02800554, 0.12326118 -0.097652465 -0.032005563, 0.081198633 -0.12943152 0.046992719, 0.081952602 -0.13057894 0.042992547, -0.10002936 -0.12613678 -0.0020070523, -0.10911319 -0.11813009 0.0072247386, 0.12844802 -0.085247368 -0.043004975, 0.12931463 -0.081378013 -0.04700458, -0.10570318 -0.12081909 0.011387661, -0.11334686 -0.10966802 0.029993743, 0.12633775 -0.095119894 -0.02800554, 0.12563348 -0.094581097 -0.032005519, -0.10002936 -0.12613699 0.0019929111, 0.084320515 -0.12741968 0.046992883, 0.085117102 -0.12853849 0.042992696, -0.09684822 -0.12859532 -0.002007246, 0.098981574 -0.12333834 0.027992994, 0.13049167 -0.082085162 -0.043004662, -0.072113708 -0.13871264 -0.035653293, -0.076076582 -0.13815236 -0.030007854, -0.096848279 -0.12859556 0.0019926429, 0.098440722 -0.12263599 0.031992927, 0.10200359 -0.12085086 0.027993023, -0.11552355 -0.09297061 0.057994738, -0.071258828 -0.14018345 -0.032007873, -0.061069712 -0.13847083 -0.050849468, 0.10143702 -0.12016928 0.031993315, -0.057512015 -0.14155099 -0.047007844, -0.063166797 -0.14117801 -0.041432962, -0.064022556 -0.13950247 -0.045007974, -0.1140016 -0.09179914 0.06199462, -0.071686715 -0.14096066 -0.028007865, -0.11326806 -0.095705867 0.057994679, 0.1338845 -0.063743114 -0.058003664, 0.13216843 -0.062879831 -0.062003449, -0.11070752 -0.10530654 0.046994045, -0.11169473 -0.10626021 0.042993955, 0.13221115 -0.052258193 -0.069774032, -0.077691987 -0.13810781 -0.026415899, -0.058035284 -0.14282045 -0.043008149, -0.054054514 -0.14290708 -0.047008023, -0.11179112 -0.094478637 0.061994642, 0.13537025 -0.060524017 -0.0580035, 0.13362345 -0.059725672 -0.062003329, -0.068176061 -0.14269158 -0.028008237, 0.10912725 -0.1148985 0.026403651, -0.067777693 -0.14189923 -0.032007918, -0.10811536 -0.10796618 0.046993956, -0.10906643 -0.10895637 0.042993575, 0.12613669 -0.10002923 -0.0020056814, 0.11812976 -0.10911363 0.0072253197, -0.054529995 -0.14419511 -0.043008253, -0.050565183 -0.14417866 -0.047008127, 0.12081838 -0.10570383 0.011388481, -0.064623758 -0.14433515 -0.028008237, -0.064255252 -0.14352852 -0.032007933, 0.10966629 -0.1133486 0.029993385, -0.10783273 -0.10281596 0.056437813, 0.12613681 -0.10002947 0.0019942373, 0.12859541 -0.09684819 -0.0020055175, -0.098218992 -0.12394664 0.027992934, -0.050992027 -0.14548388 -0.043008044, 0.13871451 -0.072111577 -0.035649478, 0.13815413 -0.076075017 -0.030004323, 0.12859552 -0.096848518 0.001994431, -0.097654313 -0.12326297 0.031992957, -0.10561907 -0.10274202 0.059994124, -0.09512125 -0.12633941 0.027992889, 0.092967227 -0.11552691 0.05799365, -0.047423825 -0.14668584 -0.043008357, 0.14018503 -0.071256936 -0.032004088, 0.13847364 -0.061067015 -0.050845057, -0.094582841 -0.12563542 0.031992957, 0.14155361 -0.057509392 -0.047003224, 0.14118017 -0.063164562 -0.04142867, 0.13950469 -0.064020097 -0.045003623, 0.091795698 -0.11400521 0.061993554, 0.1409622 -0.071685076 -0.028004095, -0.032355979 -0.14470944 -0.05800809, -0.031896472 -0.14284411 -0.062008008, 0.095702529 -0.1132713 0.057993606, 0.10530381 -0.11071032 0.046993703, 0.1062576 -0.11169708 0.04299362, -0.073058292 -0.14345321 -0.0020082295, 0.13810906 -0.077690631 -0.026412472, 0.14282261 -0.058033019 -0.04300341, 0.14290966 -0.054051846 -0.047003165, -0.028887019 -0.14544168 -0.058008134, -0.028497651 -0.1435608 -0.062008142, 0.09447518 -0.11179468 0.061993793, 0.14269312 -0.068174511 -0.028003871, 0.141901 -0.067776024 -0.032003984, -0.073058471 -0.14345339 0.0019918829, 0.10796346 -0.10811809 0.046993926, 0.10895376 -0.10906884 0.04299368, -0.078902856 -0.14028642 0.0036105961, 0.14419745 -0.05452764 -0.043003142, -0.020064667 -0.14345282 -0.06494613, -0.025401369 -0.14609069 -0.058008298, 0.14418127 -0.05056259 -0.047002748, 0.14433667 -0.064622134 -0.028003797, 0.14353029 -0.064253569 -0.032003611, -0.069453284 -0.14523324 0.0019917786, -0.069453284 -0.14523289 -0.0020081401, 0.10281263 -0.1078358 0.056437582, 0.12394491 -0.098220587 0.027994454, 0.14390188 -0.044191986 -0.052844912, 0.14283413 -0.042388409 -0.056444034, 0.14548613 -0.050989866 -0.043002933, 0.14536762 -0.047043055 -0.047002599, -0.065804958 -0.1469222 0.0019915253, -0.065804958 -0.1469219 -0.0020083785, 0.12326123 -0.097656131 0.031994566, -0.018519774 -0.14617339 -0.060008317, 0.1027386 -0.10562232 0.059994161, 0.12633777 -0.095122993 0.027994543, -0.097450025 -0.10351303 0.069768362, 0.14668806 -0.047421545 -0.043002859, -0.091940112 -0.11634615 0.05799339, -0.021213681 -0.14841816 -0.054297864, 0.12563349 -0.094584614 0.03199473, -0.092876002 -0.10660216 0.071092449, 0.056254119 0.15177453 0.024505809, 0.053793043 0.15152982 0.029963657, 0.058638245 0.15178615 0.019008517, 0.05613032 0.1527313 0.019008458, 0.053607062 0.15363511 0.019008473, 0.051069379 0.15449721 0.019008592, 0.0487317 0.15435061 0.024526104, 0.046339452 0.15396273 0.03000848, 0.048091054 0.15204585 0.035537869, 0.049751133 0.14989358 0.041008413, 0.052131265 0.14908263 0.041008279, 0.054497942 0.14823383 0.041008085, 0.056851029 0.1473473 0.041008115, 0.055379361 0.14955202 0.035513043, 0.054471508 0.15242341 0.024505854, 0.050577208 0.15375951 0.024506092, 0.053668097 0.15017471 0.035513252, 0.050243303 0.15274352 0.029963851, 0.049831316 0.15149096 0.035513058, 0.048091143 0.15204975 -0.035520792, 0.049751163 0.14989802 -0.040991858, 0.046339557 0.15396601 -0.029991522, 0.054497972 0.14823842 -0.040991887, 0.056850955 0.14735198 -0.040991932, 0.052131116 0.14908722 -0.040991962, 0.053793013 0.15153304 -0.02994673, 0.055379272 0.14955607 -0.035496369, 0.05863829 0.15178818 -0.018991619, 0.056254014 0.15177745 -0.024488851, 0.051069304 0.15449929 -0.018991351, 0.053607166 0.15363723 -0.018991634, 0.056130201 0.15273347 -0.01899147, 0.048731685 0.15435347 -0.024509147, 0.053665951 0.15017259 -0.035520777, 0.049829334 0.15148887 -0.035520807, 0.054470211 0.1524229 -0.024509102, 0.050240263 0.15273762 -0.029991567, 0.050576136 0.15375885 -0.024508983, -0.16115323 -0.015171319 0.024496704, -0.15986511 -0.017282873 0.029954106, -0.16219762 -0.013027847 0.018999174, -0.16196118 -0.015697479 0.018999189, -0.16168074 -0.018362969 0.018998787, -0.16135629 -0.021023452 0.018998817, -0.15882307 -0.025053859 0.029998392, -0.16021031 -0.02306658 0.024516314, -0.1566378 -0.020215541 0.040998779, -0.15785635 -0.022644371 0.035528034, -0.15693973 -0.017719239 0.040998861, -0.15720177 -0.015218645 0.040998936, -0.15742427 -0.012713999 0.040999293, -0.15877184 -0.014996052 0.035503872, -0.16096438 -0.017058998 0.024496526, -0.1604785 -0.021147192 0.024496123, -0.15859008 -0.016808003 0.035503805, -0.15941842 -0.021007866 0.029954031, -0.15811154 -0.020835817 0.035503529, -0.1588231 -0.025050581 -0.030001521, -0.15785621 -0.022640467 -0.035530686, -0.1566378 -0.020210862 -0.041001201, -0.15720187 -0.015214056 -0.041001007, -0.15742426 -0.012709528 -0.041000783, -0.15693979 -0.017714649 -0.041001037, -0.15986505 -0.017279625 -0.029956341, -0.1587718 -0.014991969 -0.035505518, -0.16219774 -0.013025552 -0.019000769, -0.16115327 -0.015168577 -0.024498299, -0.1613563 -0.021021247 -0.01900132, -0.16168061 -0.018360943 -0.019001126, -0.1619612 -0.015695304 -0.019000858, -0.16021042 -0.023063838 -0.024519041, -0.15858386 -0.016803294 -0.035530254, -0.15810527 -0.020831078 -0.035530582, -0.16096081 -0.017055929 -0.024518818, -0.15940882 -0.021003246 -0.030001193, -0.16047485 -0.021144062 -0.024518847, -0.16048856 0.02106902 0.024498522, -0.15970227 0.018723518 0.02995643, -0.16102986 0.023391247 0.01900129, -0.16139318 0.02073577 0.019001156, -0.16171294 0.018074721 0.019000828, -0.16198874 0.015408844 0.01900062, -0.1613261 0.013161868 0.024518445, -0.16041572 0.010915697 0.030000627, -0.15893684 0.013049543 0.035530075, -0.15720853 0.015146494 0.041000783, -0.15694721 0.017647177 0.041000947, -0.15664642 0.020143598 0.041000992, -0.15630586 0.022634983 0.041001111, -0.15812744 0.020709813 0.035505846, -0.16072443 0.019186646 0.024498507, -0.16116044 0.015092701 0.02449812, -0.15835363 0.018902957 0.035505816, -0.16009592 0.014992863 0.029956207, -0.15878324 0.014869511 0.035505578, -0.15893701 0.013053685 -0.035528407, -0.15720843 0.015151024 -0.040999219, -0.16041575 0.010918945 -0.029999435, -0.15664649 0.020148188 -0.040998921, -0.15630576 0.022639394 -0.040998921, -0.15694728 0.017651826 -0.040999174, -0.15970226 0.018726945 -0.02995421, -0.15812744 0.020713985 -0.035503507, -0.16102977 0.023393273 -0.018998742, -0.16048843 0.021071643 -0.024496183, -0.16198875 0.01541093 -0.018999144, -0.16171297 0.018076748 -0.01899913, -0.1613933 0.020737916 -0.018998861, -0.16132604 0.013164729 -0.024516806, -0.15834746 0.018906295 -0.035528064, -0.15877703 0.014873028 -0.035528526, -0.16072066 0.019188911 -0.024516627, -0.16008615 0.014995098 -0.029999197, -0.16115674 0.015095294 -0.024516895, -0.13861209 -0.083590865 0.024492659, -0.1365355 -0.084934443 0.029950574, -0.14048305 -0.08211261 0.018995225, -0.13625558 -0.088951588 0.018994913, -0.13770227 -0.086695135 0.01899527, -0.13911143 -0.084415436 0.018995263, -0.13222492 -0.091483682 0.029994808, -0.13433698 -0.090295106 0.0245125, -0.1323556 -0.086176246 0.040995091, -0.13239944 -0.088893414 0.035524383, -0.13631892 -0.079758942 0.040995538, -0.13503194 -0.081918985 0.040995285, -0.13371092 -0.084058344 0.040995121, -0.13654271 -0.082399666 0.035500124, -0.13762289 -0.085209727 0.02449251, -0.13541141 -0.088682085 0.02449248, -0.13559297 -0.08395344 0.035499923, -0.13451692 -0.088096678 0.029950343, -0.13341407 -0.087374747 0.035499714, -0.13222483 -0.091480404 -0.030005261, -0.13239932 -0.08888936 -0.035534292, -0.13235562 -0.086171895 -0.041004971, -0.13371065 -0.084053874 -0.041004881, -0.13503192 -0.081914604 -0.041004702, -0.13631894 -0.079754412 -0.041004658, -0.13653554 -0.084931046 -0.029959962, -0.13654281 -0.082395673 -0.035509318, -0.14048298 -0.082110673 -0.019004613, -0.13861197 -0.083588094 -0.024501994, -0.13911155 -0.08441335 -0.019004673, -0.13770227 -0.086693168 -0.019004896, -0.13625577 -0.088949382 -0.01900509, -0.13433704 -0.090292305 -0.024522692, -0.13558777 -0.083946049 -0.03553398, -0.1334088 -0.087367266 -0.035534203, -0.13762005 -0.085204959 -0.024522334, -0.13450873 -0.088088036 -0.030004919, -0.13540839 -0.088677436 -0.024522677, -0.14926639 -0.059763819 -0.030003458, -0.14886001 -0.057199061 -0.035532326, -0.1482127 -0.05455929 -0.041003138, -0.15064864 -0.047420859 -0.041002795, -0.14987463 -0.049813151 -0.041002944, -0.14906254 -0.052192897 -0.041003212, -0.15201153 -0.052419633 -0.029958308, -0.1514547 -0.04994604 -0.035507679, -0.15523244 -0.048791379 -0.0190029, -0.1537371 -0.050648212 -0.02450034, -0.15263286 -0.056399435 -0.019003212, -0.15354109 -0.053877771 -0.019003019, -0.15440767 -0.051341653 -0.019002989, -0.15106112 -0.058135748 -0.024521053, -0.15086836 -0.051670283 -0.035532191, -0.14950539 -0.055490434 -0.035532311, -0.15312956 -0.052445322 -0.024520487, -0.15073815 -0.055948377 -0.030003071, -0.15174627 -0.056322902 -0.024520785, -0.15373707 -0.050650984 0.024494447, -0.15201163 -0.05242309 0.029952317, -0.15523247 -0.048793465 0.018997237, -0.15440781 -0.051343769 0.018997163, -0.15354115 -0.053879887 0.018996909, -0.15263289 -0.056401581 0.018996701, -0.14926636 -0.059767246 0.029996447, -0.151061 -0.05813843 0.024514385, -0.14821272 -0.05456388 0.040996723, -0.14886002 -0.057203054 0.035526037, -0.14906257 -0.052197427 0.040997036, -0.14987443 -0.04981783 0.040997185, -0.1506488 -0.047425568 0.040997386, -0.15145451 -0.049950093 0.035501897, -0.15313306 -0.052449197 0.024494611, -0.15174949 -0.056326896 0.024494268, -0.1508743 -0.051676303 0.035501935, -0.15074718 -0.055955052 0.029952221, -0.14951131 -0.055496663 0.035501577, -0.11861108 0.10855457 -0.0299941, -0.11612432 0.10930178 -0.035523236, -0.11346532 0.10986394 -0.040993869, -0.10991018 0.11342031 -0.040993869, -0.10809076 0.11515579 -0.040993661, -0.11170207 0.1116564 -0.040993914, -0.1131853 0.11421448 -0.02994892, -0.11071539 0.11478618 -0.035498396, -0.11131321 0.11869028 -0.018993497, -0.1123378 0.11653772 -0.024490878, -0.11703986 0.11304715 -0.018993944, -0.11516212 0.11495966 -0.018993586, -0.11325312 0.11684078 -0.018993586, -0.11792251 0.11087793 -0.024511412, -0.11201441 0.11350995 -0.035522923, -0.11486493 0.11062434 -0.035523236, -0.11369321 0.1152105 -0.024511382, -0.11581206 0.1115362 -0.029993877, -0.11658658 0.1122818 -0.024511397, -0.11233769 0.1165348 0.024503902, -0.11318529 0.1142112 0.029961556, -0.11131346 0.11868829 0.019006699, -0.11325309 0.11683875 0.019006431, -0.11516209 0.11495745 0.019006342, -0.11704011 0.11304522 0.019006297, -0.11861113 0.10855129 0.030005768, -0.11792244 0.11087507 0.02452381, -0.11346549 0.10985938 0.041006133, -0.11612435 0.10929769 0.035535365, -0.11170208 0.11165187 0.041006178, -0.10991038 0.11341593 0.041006386, -0.1080907 0.11515141 0.041006342, -0.11071537 0.11478207 0.035511166, -0.11369574 0.11521029 0.024503782, -0.1165892 0.11228156 0.024503723, -0.11201873 0.1135104 0.035511062, -0.11581896 0.11153948 0.029961467, -0.11486939 0.11062476 0.035510883, -0.083589345 0.13861054 0.024505138, -0.08493267 0.13653371 0.029962897, -0.082111567 0.14048201 0.019007757, -0.084414378 0.13911051 0.019007787, -0.086694047 0.13770121 0.019007832, -0.088950425 0.13625467 0.019007534, -0.091481894 0.1322231 0.030007064, -0.090293646 0.13433558 0.024525046, -0.086174041 0.13235331 0.041007355, -0.088891432 0.13239738 0.035536647, -0.084056064 0.13370833 0.04100737, -0.081916675 0.13502958 0.041007563, -0.079756543 0.13631657 0.0410074, -0.08239767 0.13654068 0.035512462, -0.085208237 0.13762146 0.024505064, -0.088680834 0.13541004 0.02450487, -0.083951399 0.13559097 0.035512179, -0.08809489 0.13451508 0.029962867, -0.087372765 0.13341224 0.035512224, -0.091481909 0.13222644 -0.029992715, -0.088891432 0.13240138 -0.035521865, -0.086173981 0.13235781 -0.040992722, -0.081916705 0.13503411 -0.040992647, -0.079756647 0.13632107 -0.040992454, -0.08405596 0.13371298 -0.040992692, -0.0849327 0.13653705 -0.029947683, -0.082397655 0.13654467 -0.03549692, -0.082111657 0.14048409 -0.018992081, -0.083589554 0.13861346 -0.024489611, -0.088950381 0.13625672 -0.018992573, -0.086694032 0.13770342 -0.018992335, -0.084414378 0.13911265 -0.01899235, -0.090293676 0.13433826 -0.024509996, -0.083948031 0.13558951 -0.035521731, -0.087369189 0.13341054 -0.035521746, -0.08520633 0.13762119 -0.024510011, -0.088089556 0.13451022 -0.029992715, -0.088678628 0.1354095 -0.02451013, -0.13545291 0.088615477 0.024502292, -0.13576227 0.086161643 0.02996023, -0.1349332 0.09094286 0.01900509, -0.13641277 0.088707954 0.019004926, -0.13785549 0.086449295 0.019004866, -0.13926077 0.084166944 0.019004762, -0.13963832 0.081854969 0.024522066, -0.13979268 0.079436123 0.030004188, -0.13753426 0.080717206 0.035533711, -0.13506708 0.081856459 0.041004494, -0.13374668 0.083996296 0.041004568, -0.13239259 0.086114943 0.041004643, -0.13100471 0.088211626 0.041004747, -0.13348146 0.087267786 0.035509795, -0.1364823 0.087022126 0.024502307, -0.13865134 0.083522797 0.024502009, -0.13446921 0.085737884 0.035509452, -0.13773543 0.082970768 0.029960081, -0.13660625 0.082290262 0.035509229, -0.13753432 0.08072108 -0.035524726, -0.13506705 0.08186093 -0.040995568, -0.13979256 0.079439551 -0.02999568, -0.13239256 0.086119443 -0.04099527, -0.1310048 0.088216305 -0.040995285, -0.1337468 0.084000885 -0.040995434, -0.13576235 0.086164981 -0.029950485, -0.13348126 0.087271661 -0.035499841, -0.13493328 0.090944976 -0.018995062, -0.13545285 0.088618428 -0.024492532, -0.13926065 0.08416903 -0.018995345, -0.13785543 0.086451292 -0.018995196, -0.13641293 0.088710368 -0.018995136, -0.13963833 0.0818578 -0.024513096, -0.13446388 0.08573854 -0.035524383, -0.13660075 0.082290947 -0.035524592, -0.13647915 0.087022871 -0.024512798, -0.13772707 0.082969129 -0.029995471, -0.13864836 0.08352384 -0.024512991, -0.15177597 0.056252599 0.024500638, -0.15153165 0.053791285 0.029958501, -0.15178728 0.058637291 0.019003242, -0.1527323 0.056129068 0.019003034, -0.1536362 0.053605974 0.019002914, -0.15449832 0.051068276 0.019002929, -0.15435208 0.048730254 0.024520248, -0.15396437 0.046337813 0.03000243, -0.15204783 0.048089117 0.035531938, -0.14989592 0.049748868 0.041002601, -0.14908493 0.052128881 0.041002914, -0.1482361 0.054495633 0.041002929, -0.14734955 0.056848556 0.041003197, -0.14955416 0.055377305 0.035507873, -0.15242493 0.054470122 0.024500415, -0.15376087 0.050575793 0.024500161, -0.15017678 0.053666025 0.035507694, -0.1527452 0.0502415 0.029958144, -0.15149297 0.049829334 0.035507545, -0.15204762 0.048092961 -0.035526589, -0.14989592 0.049753457 -0.040997267, -0.15396439 0.046341062 -0.029997677, -0.14823598 0.054500222 -0.040997207, -0.14734973 0.056853265 -0.040996954, -0.14908504 0.052133501 -0.040997282, -0.15153161 0.053794682 -0.029952124, -0.14955394 0.055381238 -0.035501584, -0.1517873 0.058639348 -0.018996611, -0.151776 0.05625546 -0.024494275, -0.15449835 0.051070362 -0.018997222, -0.15363622 0.053608298 -0.018997177, -0.15273242 0.056131393 -0.018996939, -0.15435214 0.048732996 -0.024514884, -0.1501708 0.053667814 -0.035526276, -0.15148698 0.049831331 -0.03552641, -0.15242161 0.054471523 -0.024514511, -0.15273616 0.050241917 -0.029997259, -0.15375762 0.050577581 -0.024514839, 0.021070272 0.160487 0.024506375, 0.018725336 0.15970072 0.029964134, 0.023392335 0.16102868 0.019008979, 0.020736903 0.16139209 0.019008964, 0.018075705 0.16171181 0.019008905, 0.015409902 0.16198748 0.019009113, 0.013163283 0.16132459 0.024526551, 0.010917395 0.16041392 0.030008838, 0.013051599 0.15893498 0.035538122, 0.015148893 0.15720603 0.041008666, 0.017649531 0.15694502 0.041008592, 0.020145983 0.15664414 0.041008562, 0.022637203 0.15630355 0.041008621, 0.020711899 0.15812552 0.035513476, 0.019188091 0.16072279 0.024506316, 0.015094265 0.16115886 0.02450648, 0.018905044 0.15835163 0.035513461, 0.014994502 0.16009408 0.029964313, 0.014871538 0.15878126 0.035513535, 0.013051614 0.15893897 -0.035520345, 0.015148714 0.15721071 -0.04099147, 0.010917306 0.16041726 -0.02999106, 0.020145893 0.15664867 -0.040991426, 0.022637159 0.15630814 -0.040991515, 0.017649561 0.15694958 -0.040991262, 0.018725306 0.15970409 -0.029946432, 0.020711958 0.15812939 -0.035495967, 0.02339226 0.16103086 -0.018991113, 0.021070376 0.16048971 -0.024488464, 0.015409857 0.16198975 -0.018991023, 0.018075675 0.16171396 -0.018990889, 0.020736814 0.16139436 -0.018991083, 0.013163298 0.16132715 -0.02450861, 0.018904179 0.15834942 -0.03552039, 0.014870971 0.15877897 -0.035520256, 0.019187674 0.16072208 -0.024508819, 0.014993593 0.16008762 -0.02999121, 0.015093848 0.16115806 -0.024508595, -0.059765533 0.14926794 -0.029991776, -0.057201013 0.14886212 -0.035520881, -0.0545616 0.148215 -0.040991873, -0.047423169 0.15065086 -0.040991694, -0.049815416 0.14987671 -0.040991887, -0.052195057 0.1490646 -0.040991783, -0.052421182 0.15201306 -0.02994673, -0.049948141 0.15145665 -0.035496101, -0.04879269 0.15523344 -0.018991351, -0.050649643 0.15373856 -0.024488717, -0.056400508 0.15263391 -0.018991515, -0.053878829 0.15354213 -0.01899156, -0.051342636 0.15440863 -0.018991306, -0.058137074 0.15106243 -0.024509028, -0.051672146 0.15087023 -0.035520777, -0.055492446 0.14950734 -0.035520971, -0.052446768 0.15313101 -0.024509355, -0.055949882 0.15073976 -0.029991701, -0.056324124 0.15174755 -0.024509355, -0.050649568 0.15373561 0.024505958, -0.052421257 0.15200976 0.029963896, -0.048792452 0.15523121 0.019008502, -0.051342607 0.15440655 0.019008592, -0.053878859 0.15353999 0.019008517, -0.056400403 0.15263167 0.019008413, -0.059765518 0.14926469 0.030008197, -0.058136806 0.15105936 0.024525955, -0.054561585 0.14821041 0.041008085, -0.057200983 0.14885801 0.03553766, -0.052194953 0.14906016 0.041008338, -0.049815431 0.14987227 0.041008264, -0.047423229 0.15064639 0.041008383, -0.04994823 0.15145266 0.035513207, -0.05244793 0.15313151 0.024505958, -0.056325421 0.15174803 0.024505988, -0.051674291 0.15087235 0.035513207, -0.055953294 0.15074545 0.029963702, -0.055494756 0.14950937 0.035513029, -0.025052294 0.15882471 -0.029991195, -0.022642344 0.15785828 -0.035520539, -0.020213246 0.15664005 -0.04099144, -0.015216306 0.15720412 -0.04099144, -0.012711793 0.15742648 -0.04099147, -0.017716885 0.15694189 -0.040991411, -0.017281279 0.15986669 -0.029946327, -0.01499404 0.15877375 -0.035495713, -0.013026655 0.16219866 -0.018990993, -0.015169814 0.16115445 -0.024488315, -0.021022469 0.16135743 -0.018991008, -0.018362045 0.16168171 -0.018991023, -0.015696481 0.16196221 -0.018991083, -0.02306515 0.16021162 -0.024508744, -0.016805381 0.15858591 -0.03552033, -0.020832926 0.1581071 -0.035520479, -0.01705727 0.16096219 -0.024508759, -0.021004811 0.15941036 -0.02999118, -0.021145329 0.16047621 -0.02450864, -0.015169889 0.16115174 0.02450648, -0.01728119 0.15986329 0.029964209, -0.013026685 0.16219661 0.019008964, -0.015696451 0.16196018 0.019008934, -0.018361896 0.16167948 0.019009084, -0.021022364 0.16135514 0.019008905, -0.02505222 0.15882131 0.030008644, -0.023065105 0.16020879 0.024526566, -0.020213217 0.15663561 0.041008651, -0.022642329 0.15785417 0.035538092, -0.017716989 0.15693733 0.041008785, -0.015216336 0.15719956 0.041008845, -0.012711629 0.15742183 0.041008607, -0.014994025 0.15876967 0.035513654, -0.017057553 0.16096282 0.02450639, -0.021145746 0.16047704 0.024506301, -0.016805917 0.1585882 0.035513625, -0.021006018 0.15941659 0.029964045, -0.020833895 0.15810958 0.03551349, 0.1354529 -0.088618606 0.024492413, 0.13576216 -0.086165071 0.029950336, 0.13493343 -0.090945065 0.018994868, 0.13926066 -0.08416912 0.018995211, 0.1378556 -0.086451381 0.018995196, 0.1364129 -0.088710338 0.018994868, 0.13979264 -0.079439849 0.029995501, 0.13963841 -0.081858099 0.024513006, 0.13506711 -0.081861079 0.040995225, 0.13753435 -0.080721378 0.035524786, 0.13100472 -0.088216275 0.040994883, 0.13239253 -0.086119413 0.040995061, 0.13374667 -0.084000856 0.040995181, 0.13348123 -0.08727175 0.035499856, 0.13648221 -0.087024987 0.024492472, 0.13865145 -0.083525866 0.024492696, 0.13446906 -0.085742027 0.035500035, 0.13773541 -0.082974285 0.029950514, 0.13660629 -0.082294434 0.035500079, 0.13979268 -0.079436451 -0.030004486, 0.13753431 -0.080717325 -0.035533726, 0.13506708 -0.081856519 -0.041004658, 0.13374674 -0.083996415 -0.041004688, 0.13239251 -0.086114973 -0.041004956, 0.13100483 -0.088211685 -0.041005224, 0.13576221 -0.086161703 -0.029960141, 0.13348135 -0.087267756 -0.035509676, 0.13493328 -0.090942949 -0.019005105, 0.13545293 -0.088615745 -0.024502352, 0.13641281 -0.088708073 -0.019004971, 0.1378555 -0.086449236 -0.019004971, 0.13926063 -0.084167004 -0.019004896, 0.13963833 -0.081855148 -0.024522305, 0.13446373 -0.085734457 -0.035534009, 0.13660073 -0.082286984 -0.03553386, 0.13647923 -0.087020367 -0.024522483, 0.13772705 -0.082965881 -0.030004829, 0.13864821 -0.083521158 -0.024522245, 0.15396437 -0.046337962 -0.030002728, 0.15204769 -0.048089147 -0.035531968, 0.14989595 -0.049748987 -0.041002944, 0.14908487 -0.05212903 -0.041002899, 0.14823601 -0.054495662 -0.041003287, 0.14734969 -0.056848764 -0.041003242, 0.15153149 -0.053791523 -0.029958293, 0.1495541 -0.055377394 -0.035507932, 0.15178709 -0.058637291 -0.019003287, 0.15177591 -0.056252807 -0.02450037, 0.1527323 -0.056129247 -0.019003183, 0.15363608 -0.053605974 -0.019003004, 0.15449825 -0.051068425 -0.019002825, 0.15435208 -0.048730493 -0.024520352, 0.15017062 -0.053663969 -0.03553234, 0.15148695 -0.049827397 -0.035532191, 0.15242144 -0.0544689 -0.024520576, 0.15273604 -0.050238639 -0.030002907, 0.15375745 -0.050574809 -0.024520591, 0.1517759 -0.056255609 0.024494365, 0.1515315 -0.053794742 0.029952183, 0.15178718 -0.058639348 0.018996537, 0.15449822 -0.051070452 0.018997163, 0.15363611 -0.053608179 0.018996909, 0.1527324 -0.056131512 0.018996716, 0.15396444 -0.046341211 0.029997289, 0.15435211 -0.048733205 0.024514735, 0.14989588 -0.049753368 0.040997073, 0.15204774 -0.04809323 0.035526499, 0.14734966 -0.056853205 0.040996745, 0.14823605 -0.054500252 0.040996835, 0.14908488 -0.052133501 0.040996909, 0.14955406 -0.055381298 0.03550151, 0.15242493 -0.054473013 0.02449435, 0.15376085 -0.050578952 0.024494663, 0.1501766 -0.053670019 0.035501733, 0.15274517 -0.050245076 0.029952496, 0.15149312 -0.049833506 0.035502017, 0.16115321 0.015168399 0.024498254, 0.15986511 0.017279357 0.029956251, 0.16219769 0.013025612 0.019000679, 0.16135633 0.021021158 0.019001096, 0.16168073 0.018360764 0.019000858, 0.16196115 0.015695333 0.019000798, 0.15882318 0.025050372 0.030001372, 0.16021039 0.02306354 0.024518877, 0.15663773 0.020210892 0.041000903, 0.15785629 0.022640377 0.035530597, 0.1574242 0.012709409 0.041000485, 0.15720175 0.015213966 0.041000754, 0.15693967 0.017714649 0.041000873, 0.15877165 0.014991999 0.035505444, 0.16096431 0.017056018 0.024498254, 0.16047855 0.021144181 0.024498552, 0.15859018 0.01680392 0.035505712, 0.15941846 0.02100426 0.029956371, 0.1581115 0.020831883 0.035505831, 0.15882306 0.025053769 -0.029998779, 0.15785618 0.022644401 -0.035528123, 0.15663771 0.020215482 -0.040998921, 0.15693973 0.01771915 -0.040999219, 0.15720187 0.015218496 -0.040999219, 0.15742415 0.012713909 -0.040999547, 0.15986513 0.017282724 -0.029954284, 0.15877168 0.014996022 -0.035503864, 0.16219768 0.013027877 -0.018999487, 0.1611532 0.0151712 -0.024496615, 0.1619612 0.01569742 -0.018999279, 0.16168065 0.01836291 -0.0189991, 0.16135621 0.021023452 -0.018998832, 0.16021028 0.023066491 -0.024516433, 0.15858391 0.016807258 -0.035528377, 0.15810518 0.020835072 -0.035528123, 0.16096079 0.017058432 -0.024516642, 0.15940878 0.021006346 -0.029999048, 0.16047499 0.021146536 -0.024516463, 0.16048823 -0.021071881 0.024496168, 0.15970238 -0.018727213 0.029954225, 0.16102985 -0.023393393 0.018998653, 0.16198865 -0.01541099 0.01899901, 0.16171287 -0.018076837 0.018998861, 0.16139318 -0.020738006 0.018998742, 0.16041557 -0.010919154 0.029999286, 0.16132599 -0.013164878 0.024516732, 0.15720837 -0.015151083 0.040999055, 0.15893683 -0.013053685 0.035528541, 0.15630582 -0.022639483 0.040998653, 0.15664639 -0.020148158 0.040998727, 0.15694723 -0.017651826 0.040998697, 0.15812746 -0.020714045 0.035503581, 0.16072422 -0.019189537 0.024496347, 0.16116026 -0.015095681 0.024496585, 0.15835369 -0.01890707 0.035503656, 0.16009574 -0.01499638 0.029954344, 0.15878329 -0.014873654 0.035503894, 0.16041565 -0.010915726 -0.030000642, 0.15893708 -0.013049811 -0.035529986, 0.15720837 -0.015146554 -0.041001096, 0.15694718 -0.017647386 -0.041001037, 0.15664653 -0.020143747 -0.041001409, 0.15630583 -0.022634894 -0.041001558, 0.15970232 -0.018723726 -0.029956341, 0.15812746 -0.020710051 -0.035505831, 0.16102979 -0.023391306 -0.019001365, 0.16048834 -0.021069169 -0.024498522, 0.16139325 -0.0207358 -0.019001186, 0.16171299 -0.018074811 -0.019001126, 0.16198859 -0.015408784 -0.019000769, 0.16132598 -0.013161927 -0.024518371, 0.15834744 -0.018902332 -0.035530239, 0.15877692 -0.014869004 -0.03553009, 0.16072072 -0.019186318 -0.024518698, 0.16008611 -0.014992088 -0.030001044, 0.16115682 -0.015092641 -0.02451849, 0.10855304 0.11861271 -0.029993415, 0.10929981 0.11612624 -0.035522819, 0.10986166 0.11346754 -0.04099372, 0.11341821 0.10991246 -0.040993944, 0.11515357 0.10809299 -0.040994197, 0.11165412 0.11170423 -0.04099384, 0.11421293 0.11318687 -0.02994895, 0.11478411 0.1107173 -0.035498559, 0.11868922 0.11131445 -0.018993706, 0.11653636 0.11233896 -0.024491221, 0.11304612 0.11704111 -0.018993556, 0.11495864 0.11516324 -0.018993765, 0.11683975 0.11325413 -0.018994004, 0.11087666 0.11792383 -0.02451095, 0.11350796 0.11201632 -0.035522908, 0.11062239 0.11486685 -0.035522804, 0.11520928 0.11369458 -0.024511248, 0.1115346 0.11581355 -0.029993653, 0.11228044 0.11658779 -0.02451098, 0.11653632 0.11233622 0.024503589, 0.11421287 0.1131835 0.029961646, 0.11868922 0.11131224 0.019006133, 0.11683978 0.11325204 0.019006312, 0.11495854 0.11516118 0.019006401, 0.11304621 0.11703891 0.01900661, 0.10855302 0.11860928 0.030006498, 0.11087663 0.11792105 0.024524152, 0.1098616 0.1134631 0.041006297, 0.10929975 0.11612225 0.035535723, 0.11165407 0.1116997 0.041006118, 0.11341819 0.10990804 0.041005939, 0.11515357 0.10808846 0.04100588, 0.11478415 0.1107133 0.035510927, 0.11521176 0.11369431 0.024503678, 0.11228298 0.11658767 0.024503767, 0.1135124 0.1120168 0.035510957, 0.11154121 0.11581722 0.029961705, 0.11062683 0.11486739 0.035511166, 0.088617086 0.13545141 0.02450493, 0.086163223 0.13576049 0.029962838, 0.090943962 0.13493219 0.019007504, 0.088709161 0.13641182 0.019007534, 0.086450279 0.13785446 0.019007534, 0.084168062 0.13925964 0.019007683, 0.081856504 0.13963693 0.024525404, 0.079438016 0.13979092 0.03000769, 0.080719277 0.1375322 0.035536855, 0.081858784 0.1350646 0.041007593, 0.083998606 0.13374442 0.041007385, 0.086117148 0.13239032 0.041007236, 0.088213921 0.13100252 0.041007295, 0.087269709 0.13347936 0.03551212, 0.087023526 0.13648075 0.024505019, 0.083524212 0.13864979 0.024505019, 0.085739985 0.1344671 0.035512298, 0.082972541 0.1377337 0.029962897, 0.082292348 0.13660425 0.035512388, 0.080719247 0.13753629 -0.035521612, 0.08185865 0.13506934 -0.040992469, 0.079438016 0.1397942 -0.029992133, 0.086117133 0.13239476 -0.040992737, 0.088213921 0.13100699 -0.040992856, 0.08399865 0.13374907 -0.040992633, 0.086163327 0.13576382 -0.029947713, 0.087269828 0.13348335 -0.035497174, 0.090943933 0.13493428 -0.018992573, 0.088617206 0.13545412 -0.02448988, 0.084168032 0.13926175 -0.018992305, 0.086450398 0.13785654 -0.018992335, 0.088709161 0.13641396 -0.018992573, 0.08185643 0.13963968 -0.024509996, 0.085736528 0.13446578 -0.03552191, 0.08228904 0.13660285 -0.035521626, 0.087021589 0.13648048 -0.024509937, 0.082967654 0.13772866 -0.029992417, 0.083522364 0.13864952 -0.024509758, 0.15373711 0.050648093 0.024500132, 0.15201154 0.052419454 0.029958278, 0.15523238 0.04879126 0.019002855, 0.15263283 0.056399375 0.019003093, 0.15354112 0.053877711 0.019002944, 0.15440767 0.051341593 0.019002914, 0.14926639 0.059763819 0.03000322, 0.15106101 0.058135539 0.024520755, 0.14821275 0.054559261 0.041002929, 0.14886016 0.057198942 0.035532534, 0.15064859 0.047420859 0.041002393, 0.1498746 0.049813181 0.041002661, 0.14906247 0.052192897 0.04100281, 0.15145446 0.0499461 0.03550753, 0.15313296 0.052446246 0.024500459, 0.1517496 0.056323826 0.024500638, 0.15087439 0.05167219 0.035507709, 0.15074712 0.055951715 0.029958338, 0.14951126 0.055492699 0.035507768, 0.14926638 0.059767097 -0.029996812, 0.14886004 0.057203054 -0.035526037, 0.14821279 0.05456382 -0.040997103, 0.14906262 0.052197218 -0.040997207, 0.14987458 0.049817711 -0.040997401, 0.15064865 0.047425389 -0.04099752, 0.15201154 0.052422732 -0.029952198, 0.15145449 0.049950093 -0.035501927, 0.15523237 0.048793554 -0.018997282, 0.15373722 0.050650775 -0.024494648, 0.15440769 0.051343679 -0.018997192, 0.15354097 0.053879887 -0.018996894, 0.15263289 0.056401461 -0.018997163, 0.15106104 0.058138311 -0.024514437, 0.15086836 0.051674068 -0.035526514, 0.14950529 0.055494428 -0.035526037, 0.1531295 0.052448064 -0.024514675, 0.15073806 0.055951536 -0.029996932, 0.15174624 0.056325495 -0.024514437, 0.13861211 0.083587855 0.02450189, 0.13653541 0.084930897 0.029960155, 0.14048295 0.082110584 0.019004464, 0.13911161 0.084413171 0.019004613, 0.13770223 0.086693019 0.019004852, 0.13625573 0.088949263 0.019004881, 0.13222492 0.091480136 0.030004948, 0.13433687 0.090292126 0.024522692, 0.13235562 0.086171836 0.041004628, 0.13239951 0.088889301 0.035534292, 0.13371064 0.084053755 0.041004628, 0.13503197 0.081914395 0.04100439, 0.13631888 0.079754382 0.041004419, 0.13654278 0.082395643 0.035509348, 0.13762298 0.085206568 0.024502128, 0.13541126 0.088679165 0.024502397, 0.13559289 0.083949417 0.035509348, 0.1345167 0.088093311 0.029960126, 0.1334141 0.087370664 0.035509676, 0.13222493 0.091483474 -0.029995054, 0.13239945 0.088893265 -0.03552413, 0.13235559 0.086176246 -0.04099527, 0.13503195 0.081918925 -0.040995523, 0.13631883 0.079758853 -0.040995583, 0.13371071 0.084058195 -0.040995479, 0.13653539 0.084934235 -0.029950589, 0.13654272 0.082399577 -0.035500109, 0.14048302 0.082112551 -0.018995464, 0.13861211 0.083590627 -0.024492681, 0.13625568 0.088951528 -0.018995196, 0.13770232 0.086695105 -0.018995255, 0.13911153 0.084415376 -0.018995255, 0.13433696 0.090294778 -0.024512619, 0.13558763 0.083949864 -0.035524577, 0.13340871 0.0873712 -0.035524428, 0.13761976 0.085207582 -0.024512798, 0.1345087 0.088091135 -0.029995054, 0.13540834 0.088679999 -0.024512619, -0.079438016 -0.13979104 -0.030007973, -0.080719322 -0.13753226 -0.035537049, -0.081858873 -0.13506481 -0.041007712, -0.083998635 -0.13374451 -0.041007608, -0.086117163 -0.13239041 -0.041007489, -0.088214159 -0.13100249 -0.041007474, -0.086163238 -0.13576061 -0.029962778, -0.087269798 -0.13347942 -0.035512164, -0.090943947 -0.13493228 -0.019007593, -0.088617086 -0.13545161 -0.02450493, -0.088709205 -0.13641188 -0.019007683, -0.086450264 -0.13785455 -0.019007742, -0.084168047 -0.13925964 -0.019007728, -0.081856534 -0.13963708 -0.024525449, -0.085736483 -0.13446194 -0.035536811, -0.082289055 -0.13659883 -0.035537079, -0.087021708 -0.13647795 -0.0245253, -0.08296746 -0.13772559 -0.030007944, -0.083522379 -0.13864702 -0.024525404, -0.088617072 -0.13545436 0.024489805, -0.086163417 -0.13576394 0.029947624, -0.090943888 -0.13493443 0.018992275, -0.084167957 -0.1392619 0.018991962, -0.086450443 -0.13785651 0.018992215, -0.088709146 -0.13641399 0.01899235, -0.079437986 -0.13979435 0.029992029, -0.081856504 -0.13963994 0.024509773, -0.081858784 -0.1350694 0.040992364, -0.080719247 -0.13753644 0.035521656, -0.08821404 -0.13100711 0.040992454, -0.086117253 -0.13239479 0.040992409, -0.08399868 -0.13374916 0.040992498, -0.087269694 -0.1334835 0.035497189, -0.087023526 -0.13648367 0.024489745, -0.083524331 -0.13865271 0.024489626, -0.08574 -0.13447115 0.035497323, -0.082972601 -0.13773721 0.02994746, -0.082292363 -0.1366083 0.035497054, -0.11653642 -0.1123392 0.024491042, -0.11421291 -0.11318704 0.029948883, -0.11868912 -0.11131448 0.018993735, -0.11304609 -0.1170412 0.018993497, -0.11495866 -0.11516318 0.018993482, -0.11683972 -0.1132541 0.018993661, -0.1085531 -0.11861297 0.029993236, -0.1108766 -0.11792406 0.024510995, -0.10986165 -0.11346769 0.040993564, -0.10929969 -0.11612633 0.035522737, -0.11515356 -0.10809317 0.040993862, -0.11341833 -0.10991251 0.040993758, -0.11165421 -0.11170417 0.040993579, -0.11478415 -0.11071733 0.035498559, -0.11521184 -0.11369729 0.024491027, -0.11228313 -0.11659047 0.024490938, -0.11351253 -0.11202091 0.035498537, -0.11154123 -0.11582074 0.029948726, -0.11062691 -0.1148715 0.035498291, -0.10855316 -0.11860955 -0.030006692, -0.1092997 -0.11612245 -0.035535887, -0.1098617 -0.11346307 -0.041006505, -0.11165413 -0.11169967 -0.041006431, -0.11341815 -0.10990816 -0.041006371, -0.11515357 -0.10808855 -0.041006282, -0.11421284 -0.11318371 -0.029961646, -0.11478414 -0.11071333 -0.035511017, -0.11868915 -0.11131227 -0.019006163, -0.11653629 -0.1123364 -0.024503589, -0.11683975 -0.11325201 -0.019006371, -0.11495867 -0.11516112 -0.019006491, -0.11304627 -0.11703891 -0.019006506, -0.11087669 -0.1179212 -0.024524212, -0.11350799 -0.11201239 -0.035535485, -0.11062236 -0.11486289 -0.035535648, -0.11520928 -0.11369199 -0.024524018, -0.11153468 -0.11581033 -0.030006468, -0.11228038 -0.11658531 -0.024524167, -0.046339557 -0.15396285 -0.03000851, -0.048091218 -0.15204579 -0.035537794, -0.049751177 -0.1498937 -0.041008547, -0.05213128 -0.14908263 -0.041008383, -0.054497942 -0.14823386 -0.041008547, -0.056851029 -0.14734742 -0.041008279, -0.053793058 -0.15152994 -0.029963627, -0.055379331 -0.14955208 -0.035512969, -0.058638304 -0.15178618 -0.019008547, -0.056254253 -0.15177462 -0.024505898, -0.056130454 -0.15273136 -0.019008532, -0.053607017 -0.15363523 -0.019008711, -0.0510692 -0.1544973 -0.019008741, -0.048731625 -0.15435079 -0.024526268, -0.05366601 -0.15016869 -0.03553766, -0.049829289 -0.15148503 -0.03553775, -0.054470271 -0.15242016 -0.024526194, -0.050240248 -0.15273443 -0.030008793, -0.050576165 -0.15375623 -0.024526328, -0.056254148 -0.15177757 0.024488822, -0.053793028 -0.15153337 0.029946879, -0.058638275 -0.15178832 0.018991321, -0.051069334 -0.15449944 0.018991485, -0.053607196 -0.15363732 0.018991262, -0.056130379 -0.15273345 0.018991426, -0.046339482 -0.15396628 0.029991373, -0.048731759 -0.15435356 0.024508923, -0.049751133 -0.14989823 0.04099153, -0.048091277 -0.15204978 0.035520777, -0.056851029 -0.14735192 0.040991664, -0.054497972 -0.14823848 0.040991679, -0.05213128 -0.14908722 0.0409915, -0.055379391 -0.14955601 0.035496145, -0.054471537 -0.15242627 0.024488881, -0.050577283 -0.15376243 0.024488747, -0.053668126 -0.15017873 0.035496354, -0.050243244 -0.15274695 0.029946789, -0.049831212 -0.15149504 0.035496175, -0.021070436 -0.16048983 0.024488419, -0.018725395 -0.15970415 0.029946163, -0.02339223 -0.16103095 0.018990993, -0.015409857 -0.16198975 0.018990919, -0.018075719 -0.16171399 0.018990874, -0.020736828 -0.16139439 0.018990904, -0.01091744 -0.16041744 0.029990911, -0.013163328 -0.16132742 0.024508536, -0.015148789 -0.15721065 0.040991053, -0.013051629 -0.15893894 0.03552039, -0.022637248 -0.15630808 0.040991351, -0.020145953 -0.1566487 0.040991157, -0.017649651 -0.15694961 0.040991187, -0.020712018 -0.15812957 0.035495803, -0.019188046 -0.16072577 0.024488375, -0.015094221 -0.16116187 0.024488419, -0.018905029 -0.15835574 0.035495743, -0.014994591 -0.16009754 0.029946163, -0.014871687 -0.15878525 0.035495803, -0.010917366 -0.16041413 -0.030009151, -0.013051629 -0.15893492 -0.035538003, -0.015148774 -0.15720618 -0.041009113, -0.017649576 -0.15694511 -0.041009024, -0.020146027 -0.15664425 -0.041009024, -0.022637397 -0.15630352 -0.041008994, -0.018725365 -0.15970087 -0.029964253, -0.020711929 -0.15812558 -0.03551358, -0.023392305 -0.1610288 -0.019009009, -0.021070316 -0.16048709 -0.024506286, -0.020736933 -0.16139212 -0.019008979, -0.018075839 -0.16171172 -0.019009203, -0.015409842 -0.16198772 -0.019009233, -0.013163269 -0.1613248 -0.024526671, -0.018904328 -0.15834552 -0.035538226, -0.014871046 -0.15877497 -0.035538062, -0.019187719 -0.16071942 -0.0245267, -0.014993683 -0.16008446 -0.030009106, -0.015093952 -0.16115549 -0.024526492, 0.091482013 -0.13222334 -0.030007526, 0.088891327 -0.13239747 -0.035536692, 0.086174056 -0.13235331 -0.041007489, 0.084056109 -0.1337086 -0.041007712, 0.081916675 -0.13502964 -0.041007578, 0.079756573 -0.13631657 -0.041007772, 0.084932551 -0.1365338 -0.029962748, 0.082397565 -0.13654077 -0.035512358, 0.082111627 -0.1404821 -0.019007877, 0.083589315 -0.13861072 -0.024505049, 0.084414259 -0.13911054 -0.019007832, 0.086694017 -0.13770121 -0.019007862, 0.088950381 -0.1362547 -0.019007698, 0.090293616 -0.13433561 -0.024525121, 0.083948016 -0.13558564 -0.03553696, 0.087369204 -0.13340682 -0.035536706, 0.085206285 -0.13761863 -0.024525389, 0.088089436 -0.13450709 -0.030007496, 0.088678733 -0.135407 -0.024525255, 0.083589405 -0.13861361 0.024489596, 0.084932625 -0.1365371 0.029947579, 0.082111627 -0.14048421 0.018992081, 0.088950381 -0.13625675 0.01899232, 0.086694136 -0.1377033 0.01899226, 0.084414214 -0.13911256 0.018992171, 0.091481924 -0.13222665 0.029992342, 0.090293601 -0.13433829 0.024509996, 0.086173952 -0.13235781 0.040992364, 0.088891327 -0.13240147 0.03552185, 0.079756632 -0.13632122 0.04099226, 0.081916615 -0.13503411 0.04099232, 0.08405596 -0.13371304 0.040992454, 0.082397535 -0.13654479 0.035497189, 0.085208163 -0.13762438 0.024489626, 0.088680699 -0.13541275 0.024489999, 0.083951324 -0.13559499 0.035497129, 0.088094816 -0.13451853 0.029947549, 0.087372586 -0.133416 0.035497218, 0.11233762 -0.1165379 0.024490923, 0.11318527 -0.11421472 0.029948801, 0.1113133 -0.11869031 0.018993258, 0.11703987 -0.11304721 0.018993571, 0.11516216 -0.11495963 0.018993437, 0.11325292 -0.11684075 0.018993542, 0.11861111 -0.10855475 0.029993787, 0.11792253 -0.11087805 0.024511397, 0.11346543 -0.10986397 0.04099375, 0.11612424 -0.10930166 0.035523266, 0.10809073 -0.11515579 0.040993303, 0.10991034 -0.11342064 0.040993631, 0.11170195 -0.11165643 0.040993676, 0.11071528 -0.11478606 0.035498261, 0.11369573 -0.11521327 0.024490938, 0.11658907 -0.11228436 0.024491102, 0.11201881 -0.11351454 0.035498351, 0.11581899 -0.11154309 0.029949114, 0.11486949 -0.11062893 0.035498664, 0.1186112 -0.10855165 -0.030006126, 0.1161243 -0.10929778 -0.03553541, 0.11346537 -0.10985941 -0.041006312, 0.111702 -0.11165181 -0.041006476, 0.10991026 -0.11341599 -0.041006371, 0.1080907 -0.11515135 -0.041006505, 0.11318526 -0.11421138 -0.02996169, 0.11071534 -0.11478224 -0.035511225, 0.1113134 -0.11868832 -0.019006699, 0.11233759 -0.11653504 -0.024503797, 0.11325312 -0.11683887 -0.01900658, 0.11516218 -0.11495754 -0.019006476, 0.11703996 -0.11304516 -0.019006282, 0.11792265 -0.11087528 -0.024523705, 0.11201434 -0.11350593 -0.035535604, 0.11486481 -0.11062038 -0.035535529, 0.11369328 -0.11520797 -0.024524108, 0.11581199 -0.11153308 -0.030006304, 0.11658657 -0.11227924 -0.024524048, 0.02505222 -0.15882155 -0.030008972, 0.022642523 -0.15785438 -0.035538211, 0.020213217 -0.15663561 -0.04100889, 0.0177169 -0.15693742 -0.041008905, 0.015216157 -0.15719956 -0.04100889, 0.012711644 -0.15742189 -0.041009009, 0.01728119 -0.15986359 -0.029964209, 0.014993995 -0.15876988 -0.035513729, 0.013026625 -0.16219667 -0.019009024, 0.015169963 -0.16115198 -0.02450645, 0.015696421 -0.16196018 -0.019008979, 0.018361941 -0.16167974 -0.019009158, 0.021022424 -0.16135526 -0.019009188, 0.023065105 -0.16020912 -0.024526626, 0.016805142 -0.15858191 -0.035538152, 0.020833075 -0.15810326 -0.035537958, 0.017057121 -0.16095945 -0.024526581, 0.021004751 -0.15940723 -0.030009121, 0.021145329 -0.16047364 -0.024526641, 0.015169829 -0.1611546 0.024488524, 0.017281219 -0.15986687 0.029946268, 0.013026848 -0.16219884 0.01899083, 0.02102235 -0.1613574 0.018990904, 0.018361881 -0.16168171 0.018990844, 0.015696362 -0.16196224 0.018990949, 0.025052041 -0.15882468 0.029991105, 0.023065135 -0.16021189 0.024508581, 0.020213068 -0.15664014 0.040991202, 0.022642344 -0.15785837 0.035520449, 0.012711674 -0.15742645 0.040991187, 0.015216261 -0.15720421 0.040991113, 0.017716989 -0.15694207 0.040991083, 0.014993995 -0.15877381 0.035495743, 0.017057583 -0.16096592 0.02448833, 0.021145821 -0.16047993 0.024488434, 0.016806006 -0.15859231 0.035495847, 0.021006018 -0.15942019 0.029946357, 0.020833954 -0.15811366 0.035495743, 0.050649434 -0.15373862 0.024488792, 0.052421182 -0.15201318 0.029946908, 0.048792526 -0.15523347 0.018991247, 0.056400627 -0.15263408 0.018991426, 0.053878844 -0.15354204 0.018991411, 0.051342562 -0.15440878 0.018991202, 0.059765592 -0.14926824 0.029991418, 0.05813688 -0.15106249 0.024509132, 0.054561585 -0.14821494 0.040991619, 0.057201013 -0.14886218 0.035520837, 0.047423124 -0.15065095 0.04099147, 0.049815431 -0.14987686 0.0409915, 0.052195057 -0.14906475 0.04099147, 0.049948066 -0.15145656 0.035496175, 0.052447885 -0.15313455 0.024488926, 0.056325421 -0.1517511 0.024488881, 0.051674157 -0.15087634 0.035496354, 0.055953324 -0.150749 0.029946744, 0.055494592 -0.14951336 0.035496324, 0.059765473 -0.14926484 -0.03000851, 0.057201028 -0.14885813 -0.03553769, 0.054561526 -0.14821035 -0.041008577, 0.052195087 -0.14906025 -0.041008726, 0.049815357 -0.14987236 -0.041008264, 0.047423124 -0.15064639 -0.041008472, 0.052421123 -0.15200993 -0.029963836, 0.049948081 -0.1514526 -0.035513192, 0.048792526 -0.15523148 -0.019008771, 0.050649509 -0.15373591 -0.024505883, 0.051342711 -0.15440667 -0.019008756, 0.053878888 -0.15354002 -0.019008845, 0.056400388 -0.15263191 -0.019008517, 0.05813688 -0.15105963 -0.024526045, 0.051672101 -0.15086642 -0.03553769, 0.055492416 -0.14950344 -0.035537586, 0.052446663 -0.15312827 -0.024526313, 0.055949956 -0.1507366 -0.030008554, 0.056324169 -0.1517449 -0.024526224 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 0, 3, 1, -1, 4, 5, 6, -1, 7, 5, 4, -1, 8, 2, 9, -1, 8, 9, 6, -1, 8, 5, 0, -1, 8, 0, 2, -1, 8, 6, 5, -1, 10, 11, 12, -1, 13, 14, 15, -1, 13, 16, 14, -1, 13, 17, 16, -1, 18, 19, 20, -1, 21, 13, 15, -1, 22, 13, 21, -1, 23, 24, 25, -1, 26, 27, 28, -1, 29, 22, 21, -1, 30, 22, 29, -1, 31, 32, 33, -1, 31, 34, 32, -1, 35, 36, 37, -1, 38, 19, 18, -1, 39, 40, 41, -1, 42, 30, 29, -1, 43, 44, 45, -1, 43, 45, 24, -1, 46, 47, 30, -1, 48, 39, 41, -1, 46, 30, 42, -1, 43, 24, 23, -1, 49, 50, 51, -1, 49, 52, 50, -1, 53, 54, 47, -1, 53, 47, 46, -1, 55, 56, 57, -1, 58, 54, 53, -1, 59, 56, 55, -1, 60, 42, 61, -1, 60, 46, 42, -1, 62, 63, 64, -1, 65, 66, 67, -1, 65, 67, 68, -1, 69, 54, 58, -1, 70, 71, 72, -1, 73, 61, 74, -1, 73, 60, 61, -1, 75, 38, 18, -1, 76, 23, 25, -1, 76, 25, 77, -1, 78, 79, 80, -1, 81, 82, 69, -1, 83, 74, 79, -1, 83, 73, 74, -1, 84, 27, 26, -1, 85, 82, 81, -1, 86, 87, 88, -1, 89, 84, 26, -1, 90, 39, 48, -1, 91, 85, 81, -1, 92, 85, 91, -1, 93, 87, 86, -1, 94, 95, 96, -1, 94, 97, 95, -1, 98, 49, 51, -1, 98, 51, 99, -1, 100, 94, 96, -1, 101, 71, 70, -1, 102, 79, 78, -1, 102, 83, 79, -1, 103, 38, 75, -1, 104, 83, 102, -1, 104, 105, 83, -1, 106, 107, 108, -1, 109, 92, 91, -1, 110, 65, 68, -1, 111, 77, 112, -1, 110, 68, 113, -1, 111, 76, 77, -1, 114, 105, 104, -1, 115, 92, 109, -1, 115, 116, 92, -1, 117, 118, 119, -1, 120, 111, 112, -1, 121, 101, 70, -1, 122, 63, 62, -1, 123, 94, 100, -1, 124, 125, 126, -1, 127, 128, 116, -1, 127, 116, 115, -1, 129, 124, 126, -1, 130, 131, 132, -1, 133, 84, 89, -1, 134, 135, 136, -1, 137, 138, 139, -1, 140, 71, 101, -1, 141, 107, 106, -1, 140, 142, 71, -1, 143, 128, 127, -1, 144, 109, 145, -1, 144, 115, 109, -1, 146, 128, 143, -1, 147, 148, 149, -1, 147, 149, 103, -1, 150, 151, 152, -1, 153, 133, 89, -1, 154, 138, 137, -1, 155, 111, 120, -1, 156, 154, 137, -1, 157, 98, 99, -1, 157, 99, 118, -1, 158, 130, 132, -1, 159, 145, 160, -1, 159, 144, 145, -1, 161, 101, 121, -1, 162, 158, 132, -1, 162, 132, 163, -1, 162, 163, 164, -1, 165, 161, 121, -1, 166, 167, 168, -1, 169, 135, 134, -1, 170, 169, 134, -1, 171, 172, 173, -1, 174, 171, 173, -1, 175, 154, 156, -1, 176, 118, 117, -1, 176, 157, 118, -1, 177, 178, 146, -1, 179, 180, 148, -1, 179, 148, 147, -1, 181, 158, 162, -1, 182, 175, 156, -1, 183, 184, 185, -1, 186, 178, 177, -1, 187, 133, 153, -1, 183, 188, 184, -1, 189, 160, 167, -1, 189, 159, 160, -1, 190, 191, 192, -1, 193, 167, 166, -1, 193, 189, 167, -1, 194, 175, 182, -1, 195, 169, 170, -1, 196, 186, 177, -1, 197, 186, 196, -1, 198, 195, 170, -1, 199, 161, 165, -1, 200, 201, 180, -1, 200, 180, 179, -1, 202, 201, 200, -1, 203, 183, 185, -1, 203, 185, 204, -1, 205, 190, 192, -1, 206, 207, 208, -1, 206, 208, 209, -1, 210, 211, 212, -1, 213, 189, 193, -1, 214, 199, 165, -1, 215, 151, 150, -1, 216, 217, 218, -1, 216, 182, 217, -1, 216, 194, 182, -1, 219, 220, 221, -1, 222, 194, 216, -1, 219, 221, 223, -1, 224, 225, 226, -1, 227, 157, 176, -1, 228, 195, 198, -1, 229, 197, 196, -1, 230, 225, 224, -1, 231, 202, 200, -1, 232, 233, 189, -1, 232, 189, 213, -1, 234, 233, 232, -1, 235, 211, 210, -1, 236, 187, 153, -1, 236, 153, 237, -1, 236, 237, 238, -1, 239, 187, 236, -1, 240, 209, 241, -1, 240, 206, 209, -1, 242, 203, 204, -1, 242, 204, 243, -1, 244, 245, 246, -1, 244, 246, 247, -1, 248, 249, 197, -1, 248, 197, 229, -1, 250, 202, 231, -1, 251, 157, 227, -1, 252, 235, 210, -1, 251, 253, 157, -1, 254, 255, 211, -1, 256, 257, 249, -1, 254, 211, 235, -1, 256, 249, 248, -1, 258, 199, 214, -1, 259, 260, 261, -1, 262, 253, 251, -1, 263, 219, 223, -1, 263, 223, 264, -1, 265, 240, 241, -1, 265, 241, 266, -1, 267, 250, 231, -1, 268, 257, 256, -1, 269, 235, 252, -1, 270, 229, 271, -1, 270, 248, 229, -1, 272, 273, 274, -1, 275, 257, 268, -1, 276, 269, 252, -1, 277, 270, 271, -1, 278, 279, 280, -1, 281, 250, 267, -1, 282, 283, 284, -1, 285, 269, 276, -1, 286, 278, 280, -1, 287, 270, 277, -1, 288, 285, 276, -1, 289, 260, 259, -1, 290, 263, 264, -1, 290, 264, 291, -1, 292, 287, 277, -1, 293, 294, 295, -1, 293, 295, 296, -1, 297, 292, 298, -1, 299, 300, 301, -1, 299, 301, 281, -1, 302, 272, 274, -1, 302, 274, 303, -1, 304, 305, 275, -1, 306, 285, 288, -1, 307, 308, 309, -1, 310, 305, 304, -1, 311, 308, 307, -1, 312, 287, 292, -1, 313, 300, 299, -1, 313, 314, 300, -1, 315, 292, 297, -1, 315, 312, 292, -1, 316, 317, 314, -1, 316, 314, 313, -1, 318, 319, 320, -1, 321, 310, 304, -1, 322, 317, 316, -1, 323, 310, 321, -1, 324, 325, 326, -1, 327, 328, 329, -1, 330, 303, 331, -1, 330, 302, 303, -1, 332, 322, 316, -1, 333, 334, 335, -1, 333, 335, 319, -1, 333, 319, 318, -1, 336, 337, 338, -1, 339, 340, 341, -1, 339, 328, 327, -1, 339, 341, 328, -1, 342, 322, 332, -1, 343, 312, 315, -1, 344, 345, 346, -1, 344, 347, 345, -1, 348, 349, 350, -1, 351, 352, 353, -1, 351, 354, 352, -1, 355, 356, 357, -1, 358, 359, 360, -1, 361, 362, 351, -1, 363, 364, 340, -1, 363, 340, 339, -1, 365, 342, 332, -1, 366, 367, 368, -1, 369, 323, 321, -1, 370, 371, 312, -1, 370, 312, 343, -1, 372, 373, 374, -1, 375, 376, 377, -1, 378, 379, 380, -1, 381, 348, 350, -1, 382, 379, 378, -1, 383, 337, 336, -1, 384, 356, 355, -1, 385, 384, 355, -1, 386, 371, 370, -1, 387, 334, 333, -1, 387, 388, 334, -1, 389, 383, 336, -1, 390, 339, 391, -1, 390, 363, 339, -1, 392, 342, 365, -1, 393, 346, 394, -1, 393, 344, 346, -1, 395, 384, 385, -1, 396, 397, 323, -1, 398, 331, 359, -1, 396, 323, 369, -1, 398, 330, 331, -1, 399, 400, 401, -1, 402, 395, 385, -1, 403, 366, 368, -1, 404, 364, 363, -1, 405, 390, 391, -1, 405, 391, 406, -1, 407, 398, 359, -1, 407, 359, 358, -1, 408, 409, 410, -1, 408, 410, 392, -1, 411, 395, 402, -1, 412, 396, 369, -1, 413, 414, 415, -1, 416, 376, 375, -1, 417, 413, 415, -1, 418, 405, 406, -1, 419, 383, 389, -1, 420, 421, 397, -1, 418, 406, 422, -1, 423, 409, 408, -1, 420, 397, 396, -1, 423, 422, 409, -1, 424, 416, 375, -1, 425, 426, 361, -1, 427, 422, 423, -1, 427, 418, 422, -1, 425, 361, 351, -1, 428, 419, 389, -1, 429, 387, 333, -1, 430, 418, 427, -1, 431, 421, 420, -1, 429, 333, 432, -1, 433, 434, 435, -1, 436, 394, 437, -1, 436, 393, 394, -1, 438, 433, 435, -1, 439, 396, 412, -1, 440, 430, 427, -1, 441, 435, 442, -1, 441, 438, 435, -1, 443, 421, 431, -1, 444, 430, 440, -1, 445, 439, 412, -1, 446, 438, 441, -1, 447, 444, 440, -1, 448, 444, 447, -1, 449, 35, 37, -1, 449, 450, 35, -1, 449, 451, 452, -1, 449, 37, 451, -1, 449, 452, 80, -1, 453, 450, 449, -1, 453, 449, 80, -1, 453, 79, 450, -1, 453, 80, 79, -1, 454, 455, 105, -1, 454, 114, 139, -1, 454, 105, 114, -1, 456, 457, 455, -1, 456, 139, 138, -1, 458, 459, 460, -1, 456, 454, 139, -1, 456, 455, 454, -1, 461, 462, 457, -1, 463, 419, 428, -1, 461, 457, 456, -1, 461, 456, 138, -1, 464, 138, 166, -1, 464, 166, 168, -1, 464, 462, 461, -1, 464, 168, 462, -1, 464, 461, 138, -1, 465, 94, 123, -1, 465, 466, 94, -1, 467, 413, 417, -1, 465, 123, 468, -1, 469, 466, 465, -1, 469, 465, 468, -1, 469, 208, 207, -1, 469, 470, 466, -1, 469, 468, 208, -1, 471, 398, 407, -1, 472, 470, 469, -1, 472, 469, 207, -1, 472, 473, 470, -1, 474, 207, 475, -1, 474, 475, 218, -1, 474, 218, 217, -1, 474, 217, 473, -1, 474, 473, 472, -1, 474, 472, 207, -1, 476, 416, 424, -1, 477, 171, 174, -1, 477, 478, 171, -1, 477, 174, 479, -1, 477, 479, 480, -1, 481, 234, 482, -1, 481, 483, 484, -1, 481, 484, 233, -1, 481, 233, 234, -1, 485, 486, 487, -1, 488, 477, 480, -1, 489, 476, 424, -1, 488, 478, 477, -1, 488, 266, 478, -1, 488, 480, 490, -1, 491, 492, 483, -1, 491, 482, 493, -1, 491, 481, 482, -1, 491, 483, 481, -1, 494, 490, 495, -1, 494, 265, 266, -1, 494, 266, 488, -1, 494, 488, 490, -1, 496, 497, 498, -1, 499, 297, 298, -1, 496, 500, 497, -1, 499, 298, 492, -1, 499, 493, 297, -1, 499, 492, 491, -1, 501, 439, 445, -1, 499, 491, 493, -1, 502, 503, 222, -1, 502, 216, 504, -1, 505, 388, 387, -1, 502, 222, 216, -1, 506, 495, 507, -1, 508, 509, 510, -1, 506, 265, 494, -1, 508, 511, 509, -1, 506, 494, 495, -1, 512, 504, 513, -1, 512, 503, 502, -1, 512, 502, 504, -1, 514, 515, 516, -1, 514, 516, 517, -1, 518, 519, 508, -1, 514, 517, 493, -1, 514, 493, 482, -1, 514, 482, 520, -1, 514, 520, 515, -1, 521, 507, 522, -1, 521, 506, 507, -1, 523, 432, 524, -1, 523, 429, 432, -1, 521, 525, 265, -1, 521, 265, 506, -1, 526, 379, 282, -1, 526, 527, 528, -1, 526, 284, 527, -1, 529, 486, 485, -1, 526, 528, 380, -1, 526, 380, 379, -1, 526, 282, 284, -1, 530, 531, 503, -1, 530, 513, 345, -1, 530, 345, 347, -1, 530, 503, 512, -1, 530, 512, 513, -1, 532, 522, 338, -1, 532, 533, 525, -1, 534, 501, 445, -1, 532, 525, 521, -1, 532, 521, 522, -1, 535, 536, 531, -1, 537, 398, 471, -1, 538, 534, 539, -1, 535, 530, 347, -1, 535, 531, 530, -1, 537, 540, 398, -1, 541, 542, 533, -1, 541, 338, 337, -1, 543, 544, 545, -1, 541, 532, 338, -1, 541, 533, 532, -1, 543, 546, 544, -1, 547, 516, 515, -1, 547, 362, 516, -1, 547, 351, 362, -1, 547, 354, 351, -1, 547, 515, 354, -1, 548, 352, 536, -1, 548, 536, 535, -1, 548, 347, 549, -1, 548, 549, 353, -1, 548, 535, 347, -1, 548, 353, 352, -1, 550, 551, 552, -1, 553, 554, 542, -1, 555, 551, 550, -1, 553, 542, 541, -1, 553, 541, 337, -1, 556, 557, 558, -1, 556, 558, 371, -1, 556, 386, 559, -1, 556, 371, 386, -1, 560, 459, 458, -1, 561, 562, 554, -1, 561, 554, 553, -1, 561, 337, 563, -1, 561, 553, 337, -1, 564, 565, 557, -1, 564, 556, 559, -1, 564, 559, 566, -1, 564, 557, 556, -1, 567, 437, 562, -1, 567, 562, 561, -1, 567, 561, 563, -1, 567, 563, 568, -1, 569, 540, 537, -1, 570, 378, 544, -1, 570, 544, 546, -1, 570, 382, 378, -1, 571, 539, 565, -1, 571, 564, 566, -1, 571, 538, 539, -1, 571, 565, 564, -1, 572, 417, 573, -1, 571, 566, 538, -1, 574, 567, 568, -1, 575, 560, 458, -1, 574, 437, 567, -1, 572, 467, 417, -1, 574, 436, 437, -1, 576, 487, 382, -1, 576, 570, 546, -1, 576, 485, 487, -1, 576, 382, 570, -1, 576, 546, 485, -1, 577, 574, 568, -1, 578, 476, 489, -1, 577, 568, 579, -1, 577, 579, 580, -1, 577, 436, 574, -1, 581, 428, 486, -1, 581, 486, 529, -1, 581, 463, 428, -1, 581, 529, 582, -1, 583, 559, 584, -1, 583, 584, 585, -1, 583, 566, 559, -1, 583, 586, 587, -1, 583, 587, 566, -1, 583, 585, 586, -1, 588, 425, 589, -1, 588, 426, 425, -1, 590, 591, 436, -1, 590, 577, 580, -1, 590, 580, 592, -1, 593, 594, 443, -1, 590, 436, 577, -1, 595, 588, 589, -1, 595, 596, 426, -1, 595, 426, 588, -1, 595, 589, 597, -1, 598, 498, 599, -1, 600, 463, 581, -1, 598, 496, 498, -1, 600, 581, 582, -1, 601, 602, 603, -1, 604, 501, 534, -1, 600, 605, 463, -1, 606, 591, 590, -1, 606, 607, 591, -1, 606, 592, 608, -1, 606, 590, 592, -1, 609, 610, 596, -1, 609, 596, 595, -1, 609, 597, 611, -1, 609, 595, 597, -1, 612, 600, 582, -1, 612, 613, 614, -1, 612, 605, 600, -1, 612, 614, 605, -1, 612, 582, 613, -1, 615, 594, 593, -1, 616, 467, 572, -1, 616, 617, 467, -1, 616, 572, 618, -1, 619, 585, 620, -1, 619, 620, 621, -1, 619, 622, 586, -1, 623, 523, 524, -1, 619, 621, 622, -1, 619, 586, 585, -1, 624, 545, 625, -1, 626, 627, 610, -1, 624, 543, 545, -1, 626, 610, 609, -1, 623, 524, 628, -1, 626, 609, 611, -1, 626, 629, 627, -1, 626, 611, 630, -1, 626, 630, 629, -1, 631, 606, 608, -1, 631, 632, 633, -1, 631, 633, 607, -1, 631, 608, 634, -1, 631, 607, 606, -1, 635, 636, 637, -1, 635, 638, 639, -1, 635, 639, 636, -1, 640, 604, 534, -1, 641, 618, 642, -1, 641, 616, 618, -1, 641, 643, 617, -1, 640, 534, 538, -1, 641, 617, 616, -1, 644, 645, 632, -1, 644, 631, 634, -1, 644, 634, 646, -1, 644, 632, 631, -1, 647, 638, 635, -1, 647, 635, 637, -1, 647, 648, 638, -1, 649, 642, 650, -1, 649, 643, 641, -1, 649, 641, 642, -1, 651, 644, 646, -1, 652, 601, 603, -1, 651, 653, 645, -1, 651, 646, 654, -1, 651, 645, 644, -1, 655, 656, 657, -1, 655, 658, 659, -1, 655, 657, 658, -1, 655, 659, 656, -1, 660, 648, 647, -1, 660, 637, 661, -1, 660, 647, 637, -1, 660, 662, 648, -1, 663, 643, 649, -1, 663, 650, 664, -1, 665, 666, 667, -1, 663, 649, 650, -1, 663, 668, 643, -1, 669, 651, 654, -1, 669, 670, 653, -1, 669, 653, 651, -1, 671, 665, 667, -1, 672, 673, 674, -1, 672, 675, 673, -1, 672, 674, 676, -1, 672, 677, 675, -1, 678, 560, 575, -1, 679, 680, 681, -1, 679, 682, 683, -1, 679, 681, 682, -1, 684, 685, 686, -1, 684, 660, 661, -1, 684, 662, 660, -1, 684, 661, 685, -1, 684, 686, 662, -1, 687, 688, 689, -1, 687, 664, 688, -1, 687, 668, 663, -1, 687, 663, 664, -1, 687, 689, 668, -1, 690, 669, 654, -1, 690, 654, 691, -1, 690, 691, 692, -1, 690, 670, 669, -1, 693, 672, 676, -1, 693, 694, 677, -1, 693, 676, 695, -1, 693, 695, 694, -1, 693, 677, 672, -1, 696, 697, 680, -1, 696, 679, 683, -1, 696, 680, 679, -1, 696, 698, 697, -1, 699, 615, 593, -1, 696, 683, 698, -1, 700, 701, 702, -1, 700, 703, 701, -1, 704, 690, 692, -1, 704, 705, 670, -1, 706, 707, 518, -1, 704, 692, 708, -1, 704, 670, 690, -1, 709, 710, 711, -1, 706, 518, 508, -1, 712, 615, 699, -1, 709, 713, 714, -1, 709, 715, 713, -1, 716, 678, 575, -1, 709, 714, 710, -1, 717, 718, 703, -1, 717, 702, 719, -1, 717, 703, 700, -1, 717, 700, 702, -1, 720, 704, 708, -1, 720, 721, 705, -1, 720, 705, 704, -1, 720, 708, 722, -1, 723, 711, 724, -1, 723, 709, 711, -1, 723, 715, 709, -1, 723, 725, 726, -1, 723, 726, 715, -1, 723, 724, 725, -1, 727, 728, 718, -1, 727, 718, 717, -1, 727, 717, 719, -1, 727, 719, 729, -1, 730, 721, 720, -1, 730, 731, 732, -1, 730, 732, 721, -1, 730, 720, 722, -1, 730, 722, 733, -1, 734, 727, 729, -1, 643, 625, 617, -1, 734, 728, 727, -1, 734, 735, 728, -1, 643, 624, 625, -1, 734, 736, 735, -1, 737, 598, 599, -1, 734, 729, 738, -1, 734, 738, 736, -1, 739, 740, 741, -1, 739, 741, 742, -1, 739, 742, 743, -1, 737, 599, 744, -1, 739, 745, 740, -1, 746, 747, 748, -1, 746, 749, 750, -1, 746, 750, 747, -1, 751, 601, 652, -1, 752, 753, 754, -1, 752, 755, 756, -1, 752, 757, 755, -1, 758, 604, 640, -1, 752, 756, 759, -1, 752, 759, 753, -1, 752, 754, 757, -1, 760, 761, 762, -1, 760, 763, 764, -1, 760, 762, 765, -1, 760, 766, 763, -1, 760, 765, 766, -1, 760, 764, 761, -1, 767, 731, 730, -1, 768, 623, 628, -1, 767, 769, 731, -1, 767, 730, 733, -1, 767, 733, 770, -1, 771, 743, 772, -1, 771, 745, 739, -1, 657, 634, 608, -1, 771, 773, 745, -1, 771, 739, 743, -1, 774, 597, 775, -1, 776, 748, 777, -1, 776, 746, 748, -1, 778, 751, 652, -1, 776, 779, 749, -1, 776, 749, 746, -1, 780, 772, 781, -1, 774, 611, 597, -1, 780, 773, 771, -1, 780, 771, 772, -1, 782, 623, 768, -1, 783, 784, 769, -1, 783, 769, 767, -1, 783, 767, 770, -1, 783, 770, 785, -1, 786, 779, 776, -1, 786, 777, 787, -1, 621, 620, 627, -1, 786, 788, 779, -1, 786, 776, 777, -1, 789, 790, 791, -1, 621, 627, 629, -1, 789, 792, 793, -1, 789, 791, 792, -1, 789, 793, 790, -1, 794, 795, 796, -1, 794, 796, 797, -1, 794, 797, 798, -1, 799, 622, 621, -1, 794, 798, 795, -1, 800, 801, 773, -1, 800, 781, 802, -1, 800, 780, 781, -1, 800, 773, 780, -1, 800, 802, 801, -1, 803, 783, 785, -1, 803, 784, 783, -1, 804, 805, 806, -1, 804, 807, 805, -1, 808, 604, 758, -1, 809, 810, 788, -1, 809, 788, 786, -1, 809, 786, 787, -1, 808, 639, 604, -1, 809, 787, 811, -1, 812, 813, 814, -1, 812, 815, 816, -1, 812, 816, 813, -1, 817, 818, 784, -1, 819, 678, 716, -1, 817, 784, 803, -1, 817, 803, 785, -1, 820, 821, 822, -1, 817, 785, 823, -1, 817, 823, 824, -1, 825, 826, 827, -1, 825, 828, 826, -1, 825, 807, 804, -1, 825, 804, 806, -1, 825, 827, 807, -1, 829, 712, 699, -1, 825, 806, 828, -1, 830, 831, 810, -1, 830, 810, 809, -1, 830, 809, 811, -1, 832, 812, 814, -1, 832, 814, 833, -1, 832, 815, 812, -1, 656, 634, 657, -1, 834, 835, 836, -1, 834, 837, 838, -1, 839, 665, 671, -1, 834, 840, 837, -1, 834, 836, 840, -1, 841, 842, 818, -1, 841, 817, 824, -1, 841, 818, 817, -1, 636, 639, 808, -1, 841, 824, 843, -1, 844, 845, 831, -1, 844, 831, 830, -1, 844, 811, 846, -1, 844, 846, 845, -1, 844, 830, 811, -1, 847, 848, 798, -1, 847, 849, 848, -1, 847, 850, 849, -1, 847, 798, 850, -1, 851, 832, 833, -1, 851, 815, 832, -1, 851, 833, 852, -1, 681, 614, 613, -1, 851, 853, 815, -1, 854, 842, 841, -1, 854, 855, 842, -1, 854, 841, 843, -1, 854, 843, 856, -1, 680, 614, 681, -1, 857, 858, 859, -1, 857, 859, 860, -1, 861, 862, 863, -1, 677, 864, 675, -1, 857, 865, 858, -1, 866, 867, 868, -1, 866, 868, 835, -1, 866, 838, 869, -1, 866, 835, 834, -1, 866, 834, 838, -1, 866, 869, 867, -1, 870, 871, 872, -1, 870, 873, 871, -1, 870, 872, 874, -1, 875, 851, 852, -1, 875, 853, 851, -1, 875, 876, 853, -1, 875, 852, 877, -1, 878, 879, 855, -1, 878, 854, 856, -1, 880, 751, 778, -1, 881, 775, 882, -1, 878, 855, 854, -1, 881, 774, 775, -1, 883, 860, 884, -1, 883, 857, 860, -1, 883, 865, 857, -1, 885, 874, 886, -1, 885, 887, 873, -1, 885, 870, 874, -1, 885, 873, 870, -1, 888, 889, 848, -1, 888, 890, 889, -1, 888, 848, 891, -1, 888, 891, 892, -1, 893, 877, 894, -1, 893, 876, 875, -1, 893, 875, 877, -1, 895, 896, 897, -1, 895, 898, 899, -1, 895, 899, 849, -1, 895, 897, 898, -1, 895, 849, 896, -1, 900, 878, 856, -1, 901, 820, 822, -1, 900, 902, 879, -1, 900, 879, 878, -1, 900, 856, 903, -1, 904, 862, 861, -1, 905, 872, 871, -1, 905, 865, 883, -1, 905, 883, 884, -1, 905, 871, 865, -1, 905, 884, 872, -1, 906, 907, 908, -1, 906, 908, 909, -1, 910, 822, 911, -1, 910, 901, 822, -1, 912, 888, 892, -1, 912, 892, 913, -1, 914, 880, 778, -1, 912, 890, 888, -1, 915, 886, 916, -1, 915, 916, 917, -1, 915, 917, 887, -1, 915, 887, 885, -1, 915, 885, 886, -1, 653, 881, 882, -1, 918, 876, 893, -1, 918, 919, 920, -1, 918, 893, 894, -1, 918, 894, 919, -1, 918, 920, 876, -1, 921, 914, 922, -1, 923, 900, 903, -1, 923, 903, 924, -1, 923, 925, 902, -1, 923, 902, 900, -1, 926, 927, 928, -1, 929, 897, 907, -1, 926, 930, 927, -1, 929, 906, 909, -1, 929, 909, 931, -1, 929, 931, 932, -1, 929, 907, 906, -1, 933, 934, 890, -1, 933, 913, 935, -1, 933, 890, 912, -1, 933, 912, 913, -1, 936, 937, 712, -1, 938, 939, 940, -1, 936, 712, 829, -1, 938, 941, 939, -1, 938, 940, 942, -1, 938, 942, 943, -1, 938, 943, 944, -1, 945, 936, 829, -1, 946, 925, 923, -1, 946, 923, 924, -1, 946, 924, 947, -1, 946, 948, 925, -1, 949, 950, 951, -1, 949, 952, 950, -1, 949, 951, 953, -1, 949, 953, 952, -1, 954, 933, 935, -1, 954, 955, 934, -1, 954, 935, 956, -1, 954, 934, 933, -1, 954, 956, 955, -1, 957, 897, 929, -1, 957, 929, 932, -1, 957, 898, 897, -1, 958, 959, 960, -1, 958, 961, 959, -1, 962, 946, 947, -1, 962, 948, 946, -1, 963, 964, 941, -1, 963, 944, 965, -1, 963, 965, 966, -1, 701, 703, 799, -1, 963, 938, 944, -1, 963, 941, 938, -1, 967, 968, 969, -1, 967, 969, 898, -1, 701, 799, 621, -1, 967, 957, 932, -1, 967, 932, 970, -1, 971, 671, 972, -1, 967, 898, 957, -1, 971, 839, 671, -1, 973, 974, 975, -1, 973, 975, 976, -1, 973, 958, 960, -1, 973, 961, 958, -1, 973, 960, 974, -1, 973, 976, 961, -1, 977, 978, 948, -1, 977, 947, 979, -1, 977, 979, 980, -1, 977, 962, 947, -1, 977, 948, 962, -1, 981, 982, 983, -1, 981, 983, 984, -1, 985, 901, 910, -1, 981, 986, 982, -1, 987, 963, 966, -1, 987, 964, 963, -1, 987, 988, 964, -1, 989, 950, 990, -1, 989, 990, 991, -1, 989, 991, 992, -1, 989, 992, 950, -1, 993, 967, 970, -1, 713, 659, 658, -1, 993, 968, 967, -1, 993, 994, 968, -1, 993, 970, 995, -1, 993, 995, 994, -1, 996, 977, 980, -1, 996, 980, 997, -1, 996, 998, 978, -1, 996, 978, 977, -1, 999, 1000, 986, -1, 999, 1001, 1000, -1, 999, 986, 981, -1, 999, 981, 984, -1, 1002, 988, 987, -1, 1002, 966, 1003, -1, 1002, 987, 966, -1, 1002, 1004, 988, -1, 1005, 1006, 1007, -1, 1005, 1008, 1006, -1, 670, 881, 653, -1, 1005, 1009, 1010, -1, 1011, 880, 914, -1, 1005, 1007, 1009, -1, 1005, 1010, 1012, -1, 1013, 1014, 1015, -1, 1013, 997, 1016, -1, 1013, 996, 997, -1, 1017, 1018, 937, -1, 1013, 1016, 1014, -1, 1013, 1015, 998, -1, 1013, 998, 996, -1, 1019, 1020, 1021, -1, 1019, 1021, 1022, -1, 1017, 937, 936, -1, 1019, 1022, 1023, -1, 1019, 1023, 1024, -1, 1025, 1001, 999, -1, 1025, 999, 984, -1, 1025, 984, 1026, -1, 1025, 1027, 1001, -1, 1025, 1026, 1027, -1, 1028, 1004, 1002, -1, 1029, 926, 928, -1, 1028, 1030, 1004, -1, 1028, 1002, 1003, -1, 1028, 1003, 1031, -1, 1029, 928, 1032, -1, 1028, 1031, 1030, -1, 1033, 1008, 1005, -1, 1033, 1034, 1035, -1, 1033, 1005, 1012, -1, 1033, 1035, 1008, -1, 1033, 1012, 1034, -1, 1036, 1020, 1019, -1, 1036, 1019, 1024, -1, 1036, 1037, 1020, -1, 1036, 1024, 1037, -1, 1038, 1039, 1040, -1, 1038, 992, 1041, -1, 688, 1042, 1043, -1, 1038, 1041, 1044, -1, 688, 1043, 689, -1, 1038, 1040, 992, -1, 1045, 1018, 1017, -1, 1046, 990, 1047, -1, 1046, 1047, 1048, -1, 1046, 1048, 1049, -1, 1046, 1050, 990, -1, 1051, 914, 921, -1, 1046, 1049, 1050, -1, 1052, 1053, 1054, -1, 1052, 1054, 1055, -1, 1051, 1011, 914, -1, 1056, 936, 945, -1, 1057, 1058, 1059, -1, 1057, 1060, 1061, -1, 1057, 1059, 1062, -1, 1057, 1062, 1060, -1, 1057, 1061, 1058, -1, 1063, 1038, 1044, -1, 1063, 1044, 1064, -1, 1063, 1039, 1038, -1, 1065, 1048, 1053, -1, 1065, 1053, 1052, -1, 1065, 1055, 1066, -1, 1065, 1066, 1067, -1, 1065, 1052, 1055, -1, 1068, 1063, 1064, -1, 1068, 1064, 1069, -1, 1068, 1070, 1039, -1, 1068, 1039, 1063, -1, 1071, 1072, 1030, -1, 1073, 1056, 945, -1, 1071, 1030, 1074, -1, 1071, 1075, 1072, -1, 1076, 1048, 1065, -1, 1076, 1049, 1048, -1, 1076, 1065, 1067, -1, 1077, 1068, 1069, -1, 1077, 1070, 1068, -1, 1077, 1078, 1070, -1, 1077, 1069, 1079, -1, 1080, 1075, 1071, -1, 1080, 1074, 1081, -1, 1082, 1018, 1045, -1, 1080, 1071, 1074, -1, 1083, 1084, 1058, -1, 1083, 1085, 1084, -1, 1083, 1061, 1085, -1, 715, 659, 713, -1, 1083, 1058, 1061, -1, 1086, 1087, 1088, -1, 1086, 1089, 1087, -1, 1086, 1088, 1090, -1, 1091, 1092, 1093, -1, 1094, 1082, 1045, -1, 1091, 1095, 1092, -1, 1096, 1097, 1098, -1, 1096, 1098, 1078, -1, 1096, 1079, 1097, -1, 1096, 1078, 1077, -1, 1099, 1094, 1045, -1, 1096, 1077, 1079, -1, 1100, 1101, 1102, -1, 1100, 1103, 1104, -1, 1100, 1105, 1103, -1, 1100, 1102, 1105, -1, 1106, 1099, 1045, -1, 1100, 1104, 1107, -1, 1100, 1107, 1101, -1, 1108, 637, 1109, -1, 1110, 1049, 1076, -1, 1110, 1111, 1112, -1, 1108, 661, 637, -1, 1110, 1112, 1049, -1, 1110, 1067, 1113, -1, 1110, 1076, 1067, -1, 1114, 1075, 1080, -1, 1114, 1080, 1081, -1, 1114, 1115, 1116, -1, 1114, 1081, 1115, -1, 1114, 1117, 1075, -1, 1118, 1086, 1090, -1, 1118, 1089, 1086, -1, 1118, 1119, 1089, -1, 1118, 1090, 1120, -1, 1121, 1095, 1091, -1, 1121, 1093, 1122, -1, 1121, 1122, 1123, -1, 1121, 1124, 1095, -1, 1121, 1123, 1124, -1, 1121, 1091, 1093, -1, 1125, 1114, 1116, -1, 1125, 1117, 1114, -1, 1125, 1126, 1117, -1, 1127, 1128, 1129, -1, 1127, 1111, 1110, -1, 1127, 1129, 1111, -1, 1127, 1113, 1128, -1, 1127, 1110, 1113, -1, 1130, 1118, 1120, -1, 1130, 1120, 1131, -1, 1130, 1132, 1119, -1, 1130, 1119, 1118, -1, 1133, 1134, 1135, -1, 1133, 1135, 1136, -1, 1133, 1137, 1134, -1, 1133, 1136, 1137, -1, 1138, 1126, 1125, -1, 1138, 1139, 1126, -1, 1138, 1116, 1140, -1, 1138, 1125, 1116, -1, 1141, 1142, 1143, -1, 698, 714, 697, -1, 1141, 1143, 1144, -1, 1141, 1145, 1142, -1, 1146, 1132, 1130, -1, 1146, 1147, 1132, -1, 1146, 1130, 1131, -1, 1148, 1139, 1138, -1, 1148, 1138, 1140, -1, 1148, 1149, 1139, -1, 1148, 1140, 1150, -1, 1148, 1150, 1149, -1, 1151, 1144, 1152, -1, 1151, 1145, 1141, -1, 1153, 1032, 1154, -1, 1151, 1141, 1144, -1, 1151, 1155, 1145, -1, 1151, 1152, 1155, -1, 1153, 1029, 1032, -1, 1156, 1146, 1131, -1, 1156, 1131, 1157, -1, 1156, 1158, 1147, -1, 1156, 1147, 1146, -1, 1159, 1160, 1161, -1, 741, 1042, 688, -1, 1159, 1161, 1162, -1, 1159, 1163, 1160, -1, 741, 740, 1042, -1, 1159, 1164, 1163, -1, 1165, 1166, 1167, -1, 1165, 1167, 1168, -1, 1165, 1168, 1169, -1, 1165, 1170, 1166, -1, 1165, 1169, 1170, -1, 1171, 1172, 1173, -1, 1171, 1173, 1129, -1, 1171, 1129, 1174, -1, 1175, 1011, 1051, -1, 1176, 1157, 1177, -1, 1176, 1156, 1157, -1, 1176, 1177, 1158, -1, 1176, 1158, 1156, -1, 1178, 741, 688, -1, 1179, 1159, 1162, -1, 1179, 1162, 1180, -1, 1181, 1182, 1183, -1, 1179, 1164, 1159, -1, 1184, 1171, 1174, -1, 710, 714, 698, -1, 1184, 1185, 1172, -1, 1184, 1172, 1171, -1, 1184, 1174, 1186, -1, 1187, 1188, 1189, -1, 1190, 1191, 1192, -1, 1187, 1193, 1188, -1, 1190, 1192, 1194, -1, 1190, 1195, 1191, -1, 1190, 1196, 1195, -1, 1197, 1198, 1149, -1, 1197, 1149, 1199, -1, 1197, 1200, 1198, -1, 1201, 1180, 1202, -1, 1203, 1056, 1073, -1, 1201, 1164, 1179, -1, 1201, 1179, 1180, -1, 1201, 1204, 1164, -1, 1205, 1185, 1184, -1, 1205, 1184, 1186, -1, 1205, 1186, 1206, -1, 1207, 1208, 1209, -1, 1207, 1210, 1208, -1, 1211, 1190, 1194, -1, 1211, 1196, 1190, -1, 1211, 1212, 1196, -1, 1213, 1214, 1215, -1, 1213, 1216, 1217, -1, 1213, 1218, 1214, -1, 1219, 1203, 1073, -1, 1213, 1217, 1218, -1, 1220, 1221, 1166, -1, 1220, 1222, 1221, -1, 1220, 1166, 1170, -1, 1220, 1170, 1222, -1, 1223, 1200, 1197, -1, 1223, 1197, 1199, -1, 1224, 683, 682, -1, 1223, 1199, 1225, -1, 1226, 1227, 1207, -1, 1228, 1201, 1202, -1, 1224, 682, 1229, -1, 1228, 1230, 1204, -1, 1228, 1204, 1201, -1, 1231, 1185, 1205, -1, 1231, 1232, 1185, -1, 1231, 1233, 1232, -1, 685, 1219, 686, -1, 1231, 1205, 1206, -1, 1231, 1206, 1234, -1, 1235, 1011, 1175, -1, 1236, 1194, 1237, -1, 1236, 1211, 1194, -1, 1236, 1237, 1212, -1, 1235, 1238, 1011, -1, 1236, 1212, 1211, -1, 1239, 1240, 1241, -1, 1239, 1241, 1242, -1, 1239, 1243, 1240, -1, 1244, 1223, 1225, -1, 1244, 1200, 1223, -1, 1244, 1225, 1245, -1, 1244, 1246, 1200, -1, 1247, 1216, 1213, -1, 1248, 1109, 1249, -1, 1247, 1250, 1216, -1, 1247, 1213, 1215, -1, 1248, 1108, 1109, -1, 1247, 1215, 1250, -1, 1251, 1252, 1253, -1, 1251, 1254, 1255, -1, 1251, 1253, 1254, -1, 1251, 1255, 1256, -1, 1257, 1228, 1202, -1, 1257, 1202, 1258, -1, 1257, 1258, 1259, -1, 1257, 1259, 1260, -1, 1257, 1261, 1230, -1, 1257, 1260, 1261, -1, 1257, 1230, 1228, -1, 1262, 1231, 1234, -1, 1262, 1263, 1233, -1, 1262, 1233, 1231, -1, 1264, 1243, 1239, -1, 1264, 1242, 1265, -1, 1264, 1239, 1242, -1, 1264, 1266, 1243, -1, 1267, 1182, 1181, -1, 1268, 1244, 1245, -1, 1268, 1245, 1269, -1, 1268, 1246, 1244, -1, 1268, 1270, 1246, -1, 1271, 1272, 1252, -1, 1271, 1256, 1273, -1, 1271, 1251, 1256, -1, 1271, 1252, 1251, -1, 1274, 1262, 1234, -1, 1274, 1263, 1262, -1, 1274, 1275, 1263, -1, 1274, 1276, 1275, -1, 1274, 1234, 1276, -1, 1277, 1238, 1235, -1, 1278, 1279, 1280, -1, 1278, 1281, 1279, -1, 1278, 1282, 1281, -1, 1278, 1280, 1282, -1, 1283, 1269, 1284, -1, 1283, 1270, 1268, -1, 1283, 1268, 1269, -1, 1283, 1285, 1270, -1, 1286, 1266, 1264, -1, 1286, 1265, 1287, -1, 747, 694, 695, -1, 1288, 1289, 1290, -1, 1286, 1291, 1292, -1, 1286, 1292, 1266, -1, 1286, 1264, 1265, -1, 1293, 741, 1178, -1, 1294, 1289, 1288, -1, 1295, 1296, 1297, -1, 1295, 1297, 1298, -1, 1295, 1299, 1296, -1, 1300, 1301, 1302, -1, 1303, 1304, 1305, -1, 1300, 1302, 1306, -1, 1300, 1307, 1301, -1, 1308, 1273, 1309, -1, 1308, 1272, 1271, -1, 1308, 1310, 1272, -1, 1308, 1271, 1273, -1, 1311, 1284, 1312, -1, 1311, 1312, 1313, -1, 1311, 1283, 1284, -1, 1311, 1285, 1283, -1, 1311, 1313, 1285, -1, 1314, 1287, 1315, -1, 1316, 1293, 1178, -1, 1314, 1317, 1291, -1, 1314, 1286, 1287, -1, 1314, 1291, 1286, -1, 1318, 1319, 1320, -1, 1318, 1320, 1299, -1, 1318, 1298, 1319, -1, 1318, 1299, 1295, -1, 1318, 1295, 1298, -1, 1321, 1203, 1219, -1, 1322, 1307, 1300, -1, 1322, 1323, 1307, -1, 1322, 1300, 1306, -1, 1324, 1308, 1309, -1, 1325, 1189, 1326, -1, 1324, 1310, 1308, -1, 1324, 1309, 1327, -1, 1325, 1187, 1189, -1, 1328, 1314, 1315, -1, 1328, 1317, 1314, -1, 1328, 1329, 1317, -1, 1328, 1315, 1329, -1, 1330, 1331, 1275, -1, 1330, 1275, 1332, -1, 1333, 1334, 1335, -1, 1333, 1336, 1334, -1, 1333, 1337, 1336, -1, 1338, 1339, 1340, -1, 1338, 1341, 1339, -1, 1338, 1342, 1341, -1, 1338, 1340, 1342, -1, 1343, 1322, 1306, -1, 1344, 1224, 1229, -1, 1343, 1306, 1345, -1, 1343, 1323, 1322, -1, 1343, 1345, 1346, -1, 1343, 1346, 1347, -1, 1343, 1347, 1323, -1, 1344, 1229, 1348, -1, 1349, 1350, 1310, -1, 1349, 1327, 1351, -1, 1349, 1324, 1327, -1, 1349, 1310, 1324, -1, 1352, 1353, 1354, -1, 1352, 1355, 1356, -1, 1352, 1354, 1355, -1, 1352, 1356, 1357, -1, 1358, 1332, 1359, -1, 1358, 1359, 1360, -1, 1358, 1360, 1361, -1, 1358, 1362, 1331, -1, 1358, 1361, 1362, -1, 1358, 1331, 1330, -1, 1358, 1330, 1332, -1, 1363, 1313, 1364, -1, 1363, 1365, 1366, -1, 1363, 1366, 1313, -1, 1367, 1219, 685, -1, 1368, 1335, 1369, -1, 1368, 1369, 1370, -1, 1368, 1337, 1333, -1, 1367, 1321, 1219, -1, 1368, 1333, 1335, -1, 1371, 1350, 1349, -1, 1371, 1372, 1350, -1, 1373, 1249, 1374, -1, 1371, 1351, 1375, -1, 1371, 1349, 1351, -1, 1376, 1352, 1357, -1, 1376, 1377, 1353, -1, 1373, 1248, 1249, -1, 1376, 1353, 1352, -1, 1376, 1357, 1377, -1, 1378, 1379, 1337, -1, 1378, 1368, 1370, -1, 1378, 1337, 1368, -1, 1380, 1364, 1381, -1, 1380, 1363, 1364, -1, 1380, 1365, 1363, -1, 1382, 1383, 1384, -1, 1385, 1386, 1387, -1, 1385, 1387, 1372, -1, 1385, 1375, 1388, -1, 1385, 1372, 1371, -1, 1385, 1371, 1375, -1, 1389, 1390, 1391, -1, 1389, 1392, 1390, -1, 1393, 1394, 1395, -1, 1389, 1396, 1392, -1, 1397, 1398, 1399, -1, 1397, 1399, 1400, -1, 1397, 1400, 1401, -1, 1397, 1401, 1398, -1, 1402, 1370, 1403, -1, 1402, 1403, 1379, -1, 1404, 1382, 1384, -1, 1402, 1379, 1378, -1, 1402, 1378, 1370, -1, 1405, 1381, 1406, -1, 1405, 1380, 1381, -1, 1405, 1365, 1380, -1, 1405, 1407, 1365, -1, 1408, 729, 719, -1, 1409, 1385, 1388, -1, 1409, 1386, 1385, -1, 1410, 1396, 1389, -1, 1410, 1389, 1391, -1, 1410, 1391, 1411, -1, 1410, 1412, 1396, -1, 1413, 1414, 1407, -1, 1413, 1405, 1406, -1, 1415, 1416, 1226, -1, 1413, 1407, 1405, -1, 1413, 1406, 1417, -1, 754, 1418, 757, -1, 1419, 1420, 1386, -1, 1415, 1226, 1207, -1, 1419, 1409, 1388, -1, 1419, 1388, 1421, -1, 1419, 1386, 1409, -1, 1422, 1411, 1423, -1, 1422, 1412, 1410, -1, 1422, 1410, 1411, -1, 1424, 1293, 1316, -1, 1422, 1425, 1426, -1, 1422, 1426, 1412, -1, 1427, 1428, 1414, -1, 1427, 1417, 1429, -1, 1427, 1413, 1417, -1, 1427, 1414, 1413, -1, 1430, 1419, 1421, -1, 1430, 1431, 1420, -1, 1430, 1421, 1432, -1, 1430, 1420, 1419, -1, 1433, 1434, 1435, -1, 1436, 747, 695, -1, 1433, 1435, 1437, -1, 1433, 1437, 1438, -1, 1439, 1440, 1441, -1, 1442, 1429, 1443, -1, 1442, 1427, 1429, -1, 1442, 1443, 1428, -1, 1442, 1428, 1427, -1, 1444, 1445, 1446, -1, 1444, 1447, 1445, -1, 1444, 1448, 1447, -1, 1449, 1450, 1451, -1, 1449, 1452, 1453, -1, 1449, 1451, 1452, -1, 1449, 1453, 1450, -1, 1454, 1455, 1456, -1, 1454, 1457, 1455, -1, 1454, 1458, 1459, -1, 1454, 1459, 1460, -1, 1454, 1456, 1458, -1, 1454, 1460, 1457, -1, 1461, 1422, 1423, -1, 1461, 1423, 1462, -1, 1461, 1463, 1425, -1, 1461, 1425, 1422, -1, 1464, 1430, 1432, -1, 1464, 1431, 1430, -1, 1464, 1432, 1465, -1, 779, 1424, 1316, -1, 1464, 1466, 1431, -1, 1467, 1326, 1468, -1, 1469, 1470, 1471, -1, 1467, 1325, 1326, -1, 1469, 1472, 1473, -1, 1469, 1473, 1474, -1, 1469, 1474, 1470, -1, 1475, 1434, 1433, -1, 1475, 1433, 1438, -1, 1475, 1476, 1477, -1, 1475, 1438, 1476, -1, 1475, 1477, 1434, -1, 1478, 1470, 1448, -1, 1478, 1444, 1446, -1, 1478, 1448, 1444, -1, 1478, 1446, 1470, -1, 1479, 1466, 1464, -1, 1480, 1393, 1395, -1, 1479, 1465, 1481, -1, 1479, 1464, 1465, -1, 1482, 1462, 1483, -1, 1482, 1463, 1461, -1, 1482, 1483, 1463, -1, 1482, 1461, 1462, -1, 1484, 1471, 1485, -1, 1484, 1472, 1469, -1, 1484, 1469, 1471, -1, 1484, 1486, 1472, -1, 1487, 1488, 1489, -1, 773, 1344, 1348, -1, 1487, 1489, 1490, -1, 1487, 1490, 1491, -1, 1487, 1491, 1488, -1, 1492, 1493, 1494, -1, 773, 1348, 745, -1, 1492, 1495, 1496, -1, 1492, 1496, 1493, -1, 1497, 1498, 1499, -1, 1500, 729, 1408, -1, 1501, 1479, 1481, -1, 1497, 1499, 1502, -1, 1501, 1503, 1466, -1, 1501, 1466, 1479, -1, 1501, 1481, 1504, -1, 1505, 1494, 1506, -1, 1505, 1492, 1494, -1, 1505, 1495, 1492, -1, 1507, 1485, 1508, -1, 1507, 1509, 1486, -1, 1507, 1484, 1485, -1, 813, 1373, 1374, -1, 1507, 1486, 1484, -1, 813, 1374, 735, -1, 1510, 1511, 1512, -1, 1510, 1512, 1513, -1, 1514, 1382, 1404, -1, 813, 735, 736, -1, 1510, 1515, 1511, -1, 1516, 1321, 1367, -1, 1517, 1518, 1519, -1, 1517, 1503, 1501, -1, 1517, 1501, 1504, -1, 1517, 1519, 1503, -1, 1517, 1504, 1518, -1, 1520, 1505, 1506, -1, 1520, 1521, 1495, -1, 1520, 1506, 1522, -1, 1523, 1500, 1408, -1, 1520, 1495, 1505, -1, 1524, 1507, 1508, -1, 1524, 1508, 1525, -1, 1524, 1509, 1507, -1, 1524, 1525, 1509, -1, 1526, 1510, 1513, -1, 1526, 1513, 1527, -1, 1526, 1515, 1510, -1, 1528, 1529, 1530, -1, 816, 1373, 813, -1, 1528, 1531, 1529, -1, 1528, 1532, 1531, -1, 1528, 1530, 1532, -1, 1533, 1534, 1535, -1, 1533, 1536, 1537, -1, 1533, 1535, 1536, -1, 1538, 1514, 1404, -1, 1539, 1540, 1521, -1, 1539, 1520, 1522, -1, 1539, 1522, 1540, -1, 1539, 1521, 1520, -1, 1541, 1519, 1518, -1, 1541, 1542, 1543, -1, 1541, 1543, 1544, -1, 1541, 1544, 1519, -1, 1541, 1518, 1545, -1, 1541, 1545, 1546, -1, 1541, 1546, 1542, -1, 1547, 1527, 1548, -1, 1549, 1440, 1439, -1, 1547, 1526, 1527, -1, 1547, 1515, 1526, -1, 1547, 1550, 1515, -1, 1551, 747, 1436, -1, 1552, 1553, 1534, -1, 1552, 1534, 1533, -1, 1552, 1537, 1554, -1, 1552, 1533, 1537, -1, 1555, 1556, 1557, -1, 1558, 1559, 1560, -1, 1555, 1557, 1561, -1, 1558, 1562, 1559, -1, 1555, 1563, 1556, -1, 1564, 1543, 1542, -1, 1564, 1565, 1543, -1, 1564, 1542, 1566, -1, 1567, 1548, 1568, -1, 788, 1424, 779, -1, 1567, 1547, 1548, -1, 1567, 1550, 1547, -1, 1567, 1569, 1550, -1, 1570, 1571, 1553, -1, 763, 1572, 764, -1, 1570, 1552, 1554, -1, 1570, 1553, 1552, -1, 1573, 1563, 1555, -1, 1573, 1555, 1561, -1, 1573, 1561, 1574, -1, 1575, 1564, 1566, -1, 1575, 1576, 1565, -1, 1575, 1566, 1577, -1, 1575, 1565, 1564, -1, 1578, 1569, 1567, -1, 1578, 1567, 1568, -1, 1578, 1568, 1579, -1, 1580, 1545, 1581, -1, 1580, 1546, 1545, -1, 1580, 1582, 1546, -1, 1580, 1581, 1582, -1, 1583, 1584, 1571, -1, 790, 722, 791, -1, 1583, 1554, 1585, -1, 790, 733, 722, -1, 1583, 1570, 1554, -1, 1583, 1571, 1570, -1, 1586, 1587, 1588, -1, 1586, 1573, 1574, -1, 1586, 1574, 1587, -1, 1586, 1563, 1573, -1, 1586, 1588, 1563, -1, 805, 725, 724, -1, 1589, 1590, 1576, -1, 1591, 1321, 1516, -1, 1589, 1575, 1577, -1, 1589, 1576, 1575, -1, 1589, 1577, 1592, -1, 1593, 1594, 1595, -1, 1591, 761, 1321, -1, 1596, 1597, 1598, -1, 1596, 1599, 1597, -1, 1596, 1598, 1600, -1, 1601, 1602, 1603, -1, 1601, 1569, 1578, -1, 807, 725, 805, -1, 1601, 1578, 1579, -1, 1601, 1603, 1604, -1, 1601, 1579, 1602, -1, 1601, 1604, 1569, -1, 748, 747, 1551, -1, 1605, 1606, 1584, -1, 1605, 1583, 1585, -1, 1605, 1584, 1583, -1, 1605, 1585, 1607, -1, 1608, 1609, 1610, -1, 1608, 1610, 1611, -1, 1608, 1612, 1609, -1, 1613, 1498, 1497, -1, 1608, 1614, 1612, -1, 1613, 1615, 1498, -1, 1616, 1589, 1592, -1, 1616, 1592, 1617, -1, 1616, 1590, 1589, -1, 1618, 1619, 1599, -1, 1618, 1600, 1620, -1, 1618, 1596, 1600, -1, 1618, 1599, 1596, -1, 1621, 1622, 1606, -1, 1623, 1613, 1497, -1, 1624, 1500, 1523, -1, 1621, 1605, 1607, -1, 1621, 1607, 1622, -1, 1621, 1606, 1605, -1, 1625, 1626, 1627, -1, 1625, 1627, 1628, -1, 1625, 1629, 1626, -1, 1630, 1590, 1616, -1, 1630, 1616, 1617, -1, 1630, 1631, 1590, -1, 1630, 1617, 1632, -1, 1633, 1614, 1608, -1, 1633, 1608, 1611, -1, 1634, 1594, 1593, -1, 1633, 1635, 1614, -1, 1636, 1625, 1628, -1, 1636, 1628, 1637, -1, 1636, 1629, 1625, -1, 1638, 1618, 1620, -1, 1638, 1619, 1618, -1, 1638, 1639, 1640, -1, 1638, 1640, 1619, -1, 1638, 1620, 1639, -1, 1641, 1631, 1630, -1, 1641, 1630, 1632, -1, 1642, 1514, 1538, -1, 1641, 1643, 1631, -1, 1641, 1644, 1643, -1, 1641, 1632, 1644, -1, 1645, 1611, 1646, -1, 1645, 1635, 1633, -1, 1645, 1633, 1611, -1, 1645, 1647, 1648, -1, 1645, 1648, 1635, -1, 1649, 1637, 1650, -1, 762, 761, 1591, -1, 1649, 1636, 1637, -1, 1649, 1629, 1636, -1, 1649, 1651, 1629, -1, 1652, 1653, 1654, -1, 1652, 1655, 1656, -1, 1652, 1656, 1653, -1, 1657, 1642, 1538, -1, 1658, 1640, 1659, -1, 1658, 1660, 1640, -1, 1661, 1662, 1663, -1, 784, 1624, 1523, -1, 1658, 1659, 1664, -1, 1665, 1666, 1667, -1, 1665, 1668, 1669, -1, 1665, 1667, 1670, -1, 1665, 1670, 1643, -1, 1665, 1643, 1644, -1, 1665, 1644, 1668, -1, 1661, 1671, 1662, -1, 1665, 1669, 1666, -1, 1672, 1673, 1651, -1, 1674, 1551, 1436, -1, 1672, 1650, 1673, -1, 1672, 1651, 1649, -1, 1675, 1657, 1676, -1, 1672, 1649, 1650, -1, 1677, 1678, 1679, -1, 1674, 1436, 1680, -1, 1677, 1646, 1678, -1, 1677, 1647, 1645, -1, 1677, 1679, 1647, -1, 1677, 1645, 1646, -1, 1681, 1682, 1683, -1, 1681, 1684, 1685, -1, 1681, 1685, 1682, -1, 1686, 1687, 1688, -1, 1686, 1689, 1687, -1, 1686, 1688, 1690, -1, 1691, 1654, 1692, -1, 1691, 1693, 1655, -1, 1691, 1692, 1693, -1, 1691, 1652, 1654, -1, 1691, 1655, 1652, -1, 1694, 1660, 1658, -1, 1695, 1560, 1696, -1, 1694, 1697, 1660, -1, 1695, 1558, 1560, -1, 1694, 1658, 1664, -1, 1698, 1699, 1700, -1, 1698, 1701, 1699, -1, 1698, 1702, 1703, -1, 1698, 1700, 1702, -1, 1698, 1703, 1704, -1, 1705, 1681, 1683, -1, 1705, 1706, 1707, -1, 1705, 1684, 1681, -1, 1705, 1683, 1708, -1, 1705, 1708, 1706, -1, 1705, 1707, 1684, -1, 1709, 1667, 1666, -1, 1709, 1710, 1667, -1, 1709, 1666, 1711, -1, 1712, 1689, 1686, -1, 1712, 1713, 1689, -1, 1712, 1686, 1690, -1, 1712, 1690, 1714, -1, 1715, 1697, 1694, -1, 1715, 1694, 1664, -1, 1715, 1664, 1716, -1, 1717, 1698, 1704, -1, 1717, 1704, 1718, -1, 1717, 1701, 1698, -1, 1717, 1718, 1701, -1, 1719, 1712, 1714, -1, 1719, 1713, 1712, -1, 1719, 1714, 1720, -1, 1721, 1722, 1710, -1, 1721, 1709, 1711, -1, 1721, 1710, 1709, -1, 1721, 1711, 1723, -1, 1724, 1725, 1726, -1, 1724, 1726, 1697, -1, 1724, 1697, 1715, -1, 1724, 1715, 1716, -1, 1724, 1716, 1725, -1, 1727, 1669, 1668, -1, 1727, 1728, 1729, -1, 1730, 1731, 1732, -1, 1727, 1668, 1728, -1, 1727, 1729, 1669, -1, 1733, 1734, 1735, -1, 1733, 1736, 1737, -1, 1733, 1737, 1734, -1, 1733, 1738, 1736, -1, 1733, 1735, 1738, -1, 1739, 1740, 1713, -1, 1739, 1713, 1719, -1, 1739, 1719, 1720, -1, 1741, 1613, 1623, -1, 1739, 1742, 1740, -1, 1739, 1720, 1742, -1, 1743, 1721, 1723, -1, 1743, 1722, 1721, -1, 1743, 1723, 1744, -1, 1745, 1746, 1747, -1, 1745, 1747, 1748, -1, 1745, 1749, 1750, -1, 1745, 1750, 1746, -1, 1751, 1722, 1743, -1, 1751, 1743, 1744, -1, 1751, 1752, 1722, -1, 1751, 1744, 1753, -1, 1754, 1755, 1725, -1, 1754, 1725, 1756, -1, 1757, 1741, 1623, -1, 1754, 1758, 1755, -1, 818, 1624, 784, -1, 1759, 1760, 1761, -1, 1759, 1762, 1760, -1, 1759, 1761, 1763, -1, 1764, 1745, 1748, -1, 1764, 1749, 1745, -1, 1764, 1765, 1749, -1, 1766, 1642, 1657, -1, 1767, 1751, 1753, -1, 802, 797, 801, -1, 1767, 1752, 1751, -1, 1767, 1768, 1752, -1, 1767, 1753, 1769, -1, 1770, 1758, 1754, -1, 1770, 1754, 1756, -1, 1770, 1756, 1771, -1, 1772, 1680, 1773, -1, 1774, 1775, 1776, -1, 1772, 1674, 1680, -1, 1774, 1735, 1775, -1, 1774, 1776, 1738, -1, 1774, 1738, 1735, -1, 1777, 1762, 1759, -1, 1777, 1763, 1778, -1, 1777, 1759, 1763, -1, 1779, 1768, 1767, -1, 1779, 1767, 1769, -1, 1779, 1780, 1768, -1, 1779, 1769, 1781, -1, 1782, 1783, 1784, -1, 1785, 1663, 1786, -1, 1782, 1784, 1765, -1, 1782, 1765, 1764, -1, 1782, 1764, 1748, -1, 1782, 1748, 1787, -1, 1788, 50, 1789, -1, 1788, 1770, 1771, -1, 1788, 1771, 50, -1, 1785, 1661, 1663, -1, 1788, 1789, 1758, -1, 1788, 1758, 1770, -1, 1790, 1791, 1792, -1, 858, 753, 759, -1, 1790, 1793, 28, -1, 1790, 1792, 1793, -1, 1794, 1778, 1795, -1, 1794, 1796, 1762, -1, 1794, 1762, 1777, -1, 1794, 1777, 1778, -1, 1797, 1780, 1779, -1, 798, 797, 802, -1, 1797, 1779, 1781, -1, 1797, 1798, 1799, -1, 1797, 1799, 1780, -1, 1800, 52, 1801, -1, 1800, 1789, 52, -1, 1802, 1766, 1657, -1, 1800, 1803, 1789, -1, 1804, 71, 1783, -1, 1804, 1782, 1787, -1, 1804, 1783, 1782, -1, 1802, 1657, 1675, -1, 1804, 72, 71, -1, 1804, 1787, 72, -1, 1805, 1791, 1790, -1, 1805, 1790, 28, -1, 1806, 1696, 1807, -1, 1805, 28, 27, -1, 1805, 1808, 1791, -1, 1809, 1810, 1811, -1, 1806, 1695, 1696, -1, 1809, 1811, 1812, -1, 1809, 1812, 1813, -1, 1814, 1796, 1794, -1, 1814, 1794, 1795, -1, 835, 793, 792, -1, 1814, 1795, 1815, -1, 835, 792, 836, -1, 1814, 1815, 1796, -1, 1816, 57, 56, -1, 1816, 1817, 1818, -1, 1816, 56, 1817, -1, 1816, 1818, 57, -1, 1819, 1781, 1820, -1, 1819, 1797, 1781, -1, 1819, 1798, 1797, -1, 1821, 1803, 1800, -1, 1821, 1800, 1801, -1, 1821, 1822, 1803, -1, 1823, 1809, 1813, -1, 1823, 1810, 1809, -1, 1823, 1813, 1824, -1, 1825, 1805, 27, -1, 1825, 1826, 1808, -1, 1825, 1808, 1805, -1, 1827, 1820, 1828, -1, 1829, 1830, 1831, -1, 1827, 1832, 1798, -1, 1827, 1798, 1819, -1, 1827, 1819, 1820, -1, 826, 840, 827, -1, 1833, 1821, 1801, -1, 1833, 1801, 1834, -1, 1833, 1834, 55, -1, 1833, 1822, 1821, -1, 1833, 57, 1822, -1, 1833, 55, 57, -1, 1835, 1836, 1810, -1, 1835, 1824, 1837, -1, 1835, 1810, 1823, -1, 1835, 1823, 1824, -1, 1838, 1825, 27, -1, 1838, 27, 117, -1, 1838, 119, 1826, -1, 1838, 1826, 1825, -1, 1838, 117, 119, -1, 1839, 1840, 1841, -1, 1842, 1843, 1844, -1, 1839, 1845, 1840, -1, 1839, 1841, 1846, -1, 1847, 1832, 1827, -1, 1847, 1827, 1828, -1, 1847, 1828, 1848, -1, 1847, 48, 1832, -1, 1849, 1741, 1757, -1, 1850, 150, 152, -1, 1850, 93, 150, -1, 1850, 152, 1851, -1, 1850, 1851, 87, -1, 1850, 87, 93, -1, 1852, 1835, 1837, -1, 1852, 1836, 1835, -1, 1852, 88, 1836, -1, 1852, 1837, 86, -1, 1852, 86, 88, -1, 1853, 1848, 1854, -1, 1853, 1847, 1848, -1, 1853, 48, 1847, -1, 859, 858, 759, -1, 1855, 142, 140, -1, 1856, 1730, 1732, -1, 848, 889, 795, -1, 1855, 140, 1857, -1, 1855, 113, 1858, -1, 1855, 1858, 142, -1, 1859, 221, 220, -1, 1859, 1845, 1839, -1, 848, 795, 798, -1, 1859, 1839, 1846, -1, 1859, 1860, 1845, -1, 1859, 1846, 221, -1, 1861, 59, 55, -1, 1861, 55, 1862, -1, 1861, 1863, 59, -1, 1864, 1854, 1865, -1, 1864, 1853, 1854, -1, 865, 1773, 858, -1, 1864, 48, 1853, -1, 865, 1772, 1773, -1, 1864, 90, 48, -1, 1866, 113, 1855, -1, 1866, 1855, 1857, -1, 1866, 1857, 1867, -1, 1868, 1860, 1859, -1, 837, 840, 826, -1, 1868, 1859, 220, -1, 1868, 1869, 1860, -1, 1870, 245, 150, -1, 1870, 150, 93, -1, 1871, 1849, 1757, -1, 1870, 246, 245, -1, 1870, 93, 246, -1, 1872, 1863, 1861, -1, 1872, 1862, 1873, -1, 1872, 1861, 1862, -1, 1874, 1864, 1865, -1, 1874, 90, 1864, -1, 1874, 1865, 1875, -1, 1874, 1876, 90, -1, 1877, 113, 1866, -1, 1877, 110, 113, -1, 1877, 1866, 1867, -1, 1877, 1878, 110, -1, 1877, 1867, 1879, -1, 1880, 1868, 220, -1, 1880, 1869, 1868, -1, 1880, 220, 1881, -1, 1880, 1881, 238, -1, 1882, 806, 1883, -1, 1880, 237, 1869, -1, 1880, 238, 237, -1, 1884, 1872, 1873, -1, 1884, 1863, 1872, -1, 1884, 1873, 274, -1, 1882, 828, 806, -1, 1884, 273, 1863, -1, 1884, 274, 273, -1, 1885, 1886, 124, -1, 1885, 129, 1887, -1, 1888, 1786, 1889, -1, 1885, 1887, 1890, -1, 1885, 124, 129, -1, 1891, 1874, 1875, -1, 1891, 1875, 1892, -1, 1891, 1892, 205, -1, 1891, 192, 1876, -1, 1888, 1785, 1786, -1, 1891, 1876, 1874, -1, 1891, 205, 192, -1, 1893, 1878, 1877, -1, 1893, 1894, 1878, -1, 1893, 1877, 1879, -1, 1895, 262, 1896, -1, 1897, 1830, 1829, -1, 1895, 1898, 1899, -1, 1895, 1899, 253, -1, 1895, 253, 262, -1, 1900, 272, 1901, -1, 1900, 273, 272, -1, 1900, 1902, 273, -1, 1903, 1807, 1904, -1, 1905, 291, 1886, -1, 1905, 1890, 1906, -1, 1903, 1806, 1807, -1, 1905, 1885, 1890, -1, 1905, 1886, 1885, -1, 1903, 1904, 1907, -1, 1908, 401, 1894, -1, 1908, 1894, 1893, -1, 1908, 1909, 401, -1, 1910, 1766, 1802, -1, 1908, 1879, 1909, -1, 1908, 1893, 1879, -1, 1911, 215, 1912, -1, 1911, 214, 151, -1, 1911, 151, 215, -1, 1913, 308, 244, -1, 1913, 244, 247, -1, 1913, 309, 308, -1, 1913, 247, 309, -1, 1914, 1900, 1901, -1, 1914, 1902, 1900, -1, 1915, 1897, 1829, -1, 1914, 1916, 1902, -1, 1917, 1898, 1895, -1, 1917, 1896, 1918, -1, 1917, 1919, 1898, -1, 1917, 1895, 1896, -1, 1920, 1912, 1921, -1, 1922, 1806, 1903, -1, 1920, 1911, 1912, -1, 1920, 214, 1911, -1, 1923, 1906, 1924, -1, 1923, 291, 1905, -1, 1923, 1905, 1906, -1, 1923, 290, 291, -1, 1925, 1901, 1926, -1, 1925, 1926, 307, -1, 1925, 1914, 1901, -1, 1925, 1916, 1914, -1, 1925, 309, 1916, -1, 1925, 307, 309, -1, 1927, 1919, 1917, -1, 1927, 358, 360, -1, 1927, 1918, 358, -1, 1927, 1917, 1918, -1, 1927, 360, 1919, -1, 1928, 1730, 1856, -1, 1929, 1921, 1930, -1, 1929, 258, 214, -1, 1929, 214, 1920, -1, 1929, 1920, 1921, -1, 1931, 239, 236, -1, 1931, 1932, 239, -1, 1931, 236, 1933, -1, 1934, 1924, 1935, -1, 1934, 1923, 1924, -1, 1934, 290, 1923, -1, 1936, 318, 320, -1, 1936, 1930, 318, -1, 1936, 1929, 1930, -1, 1936, 258, 1929, -1, 1936, 320, 258, -1, 1937, 1849, 1871, -1, 1938, 1931, 1933, -1, 1938, 1932, 1931, -1, 1938, 1933, 1939, -1, 1940, 1918, 1896, -1, 1941, 1942, 1943, -1, 1940, 1896, 1944, -1, 1940, 1944, 1945, -1, 1940, 1946, 1947, -1, 1940, 1947, 1918, -1, 1940, 1945, 1946, -1, 1948, 1935, 1949, -1, 1948, 1934, 1935, -1, 1948, 290, 1934, -1, 1948, 1950, 290, -1, 1951, 401, 1909, -1, 1951, 1909, 377, -1, 1952, 551, 324, -1, 1952, 1953, 1954, -1, 1952, 326, 1953, -1, 1952, 1954, 552, -1, 1952, 552, 551, -1, 1952, 324, 326, -1, 1955, 400, 399, -1, 1956, 1957, 1958, -1, 1955, 399, 1959, -1, 1955, 1959, 1960, -1, 1955, 1960, 403, -1, 1955, 368, 400, -1, 939, 1961, 940, -1, 1955, 403, 368, -1, 939, 1962, 1961, -1, 1963, 307, 1964, -1, 1956, 1958, 1965, -1, 1963, 311, 307, -1, 1963, 1966, 311, -1, 1967, 1932, 1938, -1, 1967, 1968, 1932, -1, 1967, 1938, 1939, -1, 1969, 1970, 1971, -1, 1967, 1939, 497, -1, 1967, 497, 500, -1, 1972, 1949, 460, -1, 1973, 1766, 1910, -1, 896, 849, 850, -1, 1972, 1948, 1949, -1, 1972, 1950, 1948, -1, 1972, 1974, 1950, -1, 1975, 399, 401, -1, 1973, 1976, 1766, -1, 1975, 376, 399, -1, 1975, 401, 1951, -1, 1975, 1951, 377, -1, 1975, 377, 376, -1, 1977, 1970, 1969, -1, 1978, 1979, 1968, -1, 1978, 1967, 500, -1, 1978, 1968, 1967, -1, 1980, 1883, 1981, -1, 1982, 1963, 1964, -1, 1980, 1882, 1883, -1, 1982, 1964, 1983, -1, 1982, 1966, 1963, -1, 1984, 460, 459, -1, 1985, 1730, 1928, -1, 1984, 1974, 1972, -1, 1984, 1972, 460, -1, 1984, 1986, 1974, -1, 1987, 511, 508, -1, 1987, 1945, 511, -1, 1987, 519, 1946, -1, 1987, 1946, 1945, -1, 1987, 508, 519, -1, 1988, 500, 1989, -1, 1988, 1989, 510, -1, 1988, 510, 509, -1, 1988, 509, 1979, -1, 1988, 1978, 500, -1, 1988, 1979, 1978, -1, 1990, 603, 602, -1, 1990, 1983, 603, -1, 1990, 1966, 1982, -1, 1990, 1982, 1983, -1, 1991, 1897, 1915, -1, 1990, 602, 1966, -1, 1992, 1984, 459, -1, 1992, 1986, 1984, -1, 1992, 1993, 1986, -1, 1994, 540, 569, -1, 1994, 1995, 1996, -1, 1994, 569, 1997, -1, 1994, 1996, 540, -1, 1998, 602, 601, -1, 1998, 1999, 602, -1, 2000, 1993, 1992, -1, 2000, 459, 2001, -1, 2000, 1992, 459, -1, 2000, 2002, 1993, -1, 2003, 505, 2004, -1, 2003, 388, 505, -1, 2003, 489, 388, -1, 2005, 1997, 2006, -1, 2005, 1995, 1994, -1, 2005, 1994, 1997, -1, 2005, 2007, 1995, -1, 2008, 1999, 1998, -1, 2008, 601, 2009, -1, 2008, 1998, 601, -1, 2008, 2010, 1999, -1, 2011, 2000, 2001, -1, 2011, 2002, 2000, -1, 2012, 1976, 1973, -1, 2011, 2001, 2013, -1, 2011, 744, 2002, -1, 2014, 2004, 2015, -1, 2014, 2003, 2004, -1, 2014, 489, 2003, -1, 2016, 1991, 1915, -1, 2017, 2009, 2018, -1, 2017, 2010, 2008, -1, 2017, 2008, 2009, -1, 2019, 550, 927, -1, 2019, 927, 930, -1, 2019, 555, 550, -1, 2020, 2006, 921, -1, 2020, 2007, 2005, -1, 2021, 2022, 920, -1, 2020, 922, 2007, -1, 2020, 2005, 2006, -1, 2020, 921, 922, -1, 2023, 1928, 1856, -1, 2024, 737, 744, -1, 2023, 1856, 2025, -1, 2024, 2011, 2013, -1, 2024, 744, 2011, -1, 2026, 877, 852, -1, 2027, 2015, 2028, -1, 2027, 489, 2014, -1, 2027, 2014, 2015, -1, 2027, 578, 489, -1, 2029, 2018, 768, -1, 2029, 768, 628, -1, 2029, 2017, 2018, -1, 2029, 2010, 2017, -1, 2029, 628, 2010, -1, 2030, 863, 555, -1, 2030, 930, 861, -1, 2030, 861, 863, -1, 2030, 2019, 930, -1, 2030, 555, 2019, -1, 2031, 2013, 2032, -1, 2031, 2032, 2033, -1, 2031, 2024, 2013, -1, 2031, 737, 2024, -1, 2034, 716, 862, -1, 2034, 904, 2035, -1, 2034, 819, 716, -1, 2034, 862, 904, -1, 2036, 2037, 2006, -1, 2036, 2006, 1997, -1, 2036, 1997, 2038, -1, 2036, 2038, 2039, -1, 2036, 2039, 2040, -1, 2036, 2040, 2037, -1, 2041, 706, 2042, -1, 2041, 707, 706, -1, 2043, 2028, 910, -1, 2043, 911, 578, -1, 2043, 910, 911, -1, 2043, 578, 2027, -1, 2043, 2027, 2028, -1, 2044, 737, 2031, -1, 2044, 2045, 737, -1, 2044, 2033, 2046, -1, 2044, 2031, 2033, -1, 2047, 2042, 1188, -1, 2048, 845, 846, -1, 2047, 2041, 2042, -1, 2047, 707, 2041, -1, 2047, 2049, 707, -1, 2050, 819, 2034, -1, 2050, 2034, 2035, -1, 2050, 2051, 819, -1, 2052, 768, 2053, -1, 2052, 782, 768, -1, 2052, 2054, 782, -1, 2055, 2056, 2045, -1, 2055, 2045, 2044, -1, 2055, 2046, 1183, -1, 2055, 2044, 2046, -1, 2057, 1188, 1193, -1, 2057, 2058, 2049, -1, 2057, 2049, 2047, -1, 2057, 2047, 1188, -1, 2059, 2035, 1290, -1, 2059, 2051, 2050, -1, 2059, 1289, 2051, -1, 2059, 1290, 1289, -1, 2059, 2050, 2035, -1, 934, 1981, 890, -1, 2060, 1154, 839, -1, 2060, 971, 2061, -1, 2060, 839, 971, -1, 2062, 2053, 2063, -1, 934, 1980, 1981, -1, 2062, 2052, 2053, -1, 2062, 2054, 2052, -1, 2064, 1210, 1207, -1, 2064, 2039, 1210, -1, 2064, 1207, 1227, -1, 2064, 2040, 2039, -1, 2064, 1227, 2040, -1, 2065, 2057, 1193, -1, 2065, 1193, 2066, -1, 2065, 2066, 1209, -1, 2065, 1209, 1208, -1, 2065, 1208, 2058, -1, 2065, 2058, 2057, -1, 2067, 2068, 2069, -1, 2070, 2021, 920, -1, 2067, 2069, 2056, -1, 2067, 1183, 1182, -1, 2067, 2056, 2055, -1, 2067, 2055, 1183, -1, 2071, 1384, 1383, -1, 2071, 2063, 1384, -1, 2071, 2062, 2063, -1, 2071, 2054, 2062, -1, 2071, 1383, 2054, -1, 2072, 1991, 2016, -1, 2073, 1238, 1277, -1, 2073, 1277, 1559, -1, 2073, 2074, 1238, -1, 2075, 1154, 2060, -1, 2075, 1153, 1154, -1, 2075, 2060, 2061, -1, 2075, 2061, 2076, -1, 2077, 2078, 2079, -1, 2080, 2081, 2068, -1, 2080, 2068, 2067, -1, 2082, 2023, 2025, -1, 2080, 2067, 1182, -1, 2080, 1182, 2083, -1, 2084, 1383, 1382, -1, 2082, 2025, 2085, -1, 2084, 2086, 1383, -1, 919, 2070, 920, -1, 2087, 2088, 2074, -1, 2087, 2073, 1559, -1, 2089, 877, 2026, -1, 2087, 2074, 2073, -1, 2090, 2076, 2091, -1, 2090, 1153, 2075, -1, 2090, 2075, 2076, -1, 2092, 1468, 2081, -1, 2092, 2081, 2080, -1, 2092, 2080, 2083, -1, 2092, 2083, 2093, -1, 2094, 2084, 1382, -1, 2094, 1382, 2095, -1, 2094, 2086, 2084, -1, 2096, 2097, 2098, -1, 2099, 1441, 1440, -1, 2099, 1267, 1181, -1, 2099, 1181, 1441, -1, 2100, 845, 2048, -1, 2099, 1440, 1267, -1, 2101, 2088, 2087, -1, 2101, 1559, 1562, -1, 2101, 2102, 2088, -1, 2101, 2087, 1559, -1, 2103, 2078, 2077, -1, 2104, 2090, 2091, -1, 2104, 2105, 1153, -1, 2106, 2089, 2026, -1, 2104, 1153, 2090, -1, 2104, 2091, 2107, -1, 2108, 2092, 2093, -1, 2108, 1468, 2092, -1, 2109, 1303, 1305, -1, 2109, 2110, 2111, -1, 2109, 1305, 2110, -1, 2109, 2111, 2112, -1, 2113, 2094, 2095, -1, 2113, 1480, 1395, -1, 2113, 2086, 2094, -1, 2113, 2095, 2114, -1, 2113, 2114, 2115, -1, 2113, 2115, 1480, -1, 2113, 1395, 2086, -1, 2116, 1288, 1662, -1, 2117, 2118, 2119, -1, 2116, 1294, 1288, -1, 2120, 2070, 919, -1, 2116, 1662, 1671, -1, 2121, 1676, 2102, -1, 2121, 2101, 1562, -1, 2121, 2102, 2101, -1, 2121, 1562, 1675, -1, 2117, 2119, 2122, -1, 2121, 1675, 1676, -1, 2123, 1502, 2105, -1, 2123, 1497, 1502, -1, 2124, 856, 2125, -1, 2123, 2107, 1497, -1, 2124, 903, 856, -1, 2123, 2105, 2104, -1, 2123, 2104, 2107, -1, 2126, 1467, 1468, -1, 2126, 2108, 2093, -1, 959, 867, 869, -1, 2126, 1468, 2108, -1, 2126, 2093, 2127, -1, 2126, 2127, 2128, -1, 2129, 1732, 1731, -1, 2129, 2109, 2112, -1, 2129, 1731, 1303, -1, 2130, 2131, 2132, -1, 2129, 1303, 2109, -1, 2129, 2112, 1732, -1, 2133, 2116, 1671, -1, 2133, 1671, 1593, -1, 2133, 1595, 1294, -1, 2133, 1593, 1595, -1, 2133, 1294, 2116, -1, 961, 867, 959, -1, 2134, 1415, 2135, -1, 2134, 1416, 1415, -1, 2136, 2126, 2128, -1, 2136, 1467, 2126, -1, 2136, 2137, 1467, -1, 2138, 2139, 2140, -1, 2136, 2128, 2141, -1, 2142, 1549, 1439, -1, 2142, 1634, 2143, -1, 2142, 1439, 1594, -1, 2142, 1594, 1634, -1, 2144, 2145, 1416, -1, 2144, 2135, 1831, -1, 909, 908, 845, -1, 2144, 1416, 2134, -1, 2144, 2134, 2135, -1, 2146, 2137, 2136, -1, 2146, 2136, 2141, -1, 909, 845, 2100, -1, 2146, 2147, 2137, -1, 2146, 2141, 1958, -1, 2148, 2142, 2143, -1, 2148, 1549, 2142, -1, 2148, 2143, 1971, -1, 2148, 1971, 1970, -1, 2148, 1970, 2149, -1, 2148, 2149, 1549, -1, 2150, 2151, 2145, -1, 2150, 1831, 1830, -1, 2150, 2145, 2144, -1, 2150, 2144, 1831, -1, 2152, 2147, 2146, -1, 2152, 2153, 2154, -1, 2152, 2154, 2147, -1, 2155, 2096, 2098, -1, 2152, 1958, 1957, -1, 2152, 2146, 1958, -1, 2156, 1904, 2151, -1, 2156, 2151, 2150, -1, 2156, 1830, 2157, -1, 2156, 2157, 1907, -1, 2156, 2150, 1830, -1, 2156, 1907, 1904, -1, 2158, 2159, 2160, -1, 2161, 1613, 2162, -1, 2161, 2162, 2163, -1, 2158, 2160, 2103, -1, 2161, 1889, 1615, -1, 2161, 1615, 1613, -1, 2164, 2165, 2166, -1, 2164, 2166, 1730, -1, 2164, 1730, 1985, -1, 2167, 2098, 2097, -1, 2167, 1842, 1844, -1, 2168, 886, 874, -1, 2167, 2097, 1842, -1, 2167, 2169, 2170, -1, 2167, 1844, 2169, -1, 2167, 2170, 2098, -1, 2171, 2082, 2085, -1, 2172, 1941, 1943, -1, 2172, 1976, 2012, -1, 2171, 2085, 2096, -1, 2172, 2012, 2173, -1, 2172, 2174, 1941, -1, 2172, 2173, 2174, -1, 2172, 1943, 1976, -1, 2175, 2176, 2153, -1, 2175, 2153, 2152, -1, 2175, 2152, 1957, -1, 2175, 1957, 2177, -1, 2178, 2139, 2138, -1, 2179, 2161, 2163, -1, 2179, 2163, 2180, -1, 2179, 1889, 2161, -1, 2179, 1888, 1889, -1, 2181, 2165, 2164, -1, 2181, 2164, 1985, -1, 2181, 1871, 2165, -1, 2181, 1985, 2182, -1, 2183, 2089, 2106, -1, 2184, 2180, 2185, -1, 2184, 1888, 2179, -1, 2184, 2179, 2180, -1, 2186, 2175, 2177, -1, 2186, 2176, 2175, -1, 2186, 2016, 2176, -1, 2186, 2177, 2187, -1, 2188, 1871, 2181, -1, 2188, 2181, 2182, -1, 2188, 2182, 2189, -1, 2188, 1937, 1871, -1, 2190, 1956, 1965, -1, 2190, 2119, 2118, -1, 2190, 1965, 2119, -1, 2190, 2118, 1956, -1, 2191, 2160, 2192, -1, 2191, 2192, 2078, -1, 948, 2183, 2106, -1, 2191, 2078, 2103, -1, 2193, 2131, 2130, -1, 2191, 2103, 2160, -1, 2194, 2048, 2195, -1, 2196, 2185, 2077, -1, 2196, 1888, 2184, -1, 2196, 2079, 1888, -1, 2196, 2184, 2185, -1, 2196, 2077, 2079, -1, 2197, 2186, 2187, -1, 2194, 2100, 2048, -1, 2197, 2016, 2186, -1, 2198, 1977, 1969, -1, 2198, 1969, 2132, -1, 2199, 2188, 2189, -1, 2199, 2200, 1937, -1, 2199, 2189, 2201, -1, 2199, 1937, 2188, -1, 2202, 1903, 2203, -1, 2202, 2204, 1922, -1, 2202, 1922, 1903, -1, 2205, 2072, 2016, -1, 2205, 2016, 2197, -1, 2205, 2197, 2187, -1, 2205, 2187, 2206, -1, 2207, 2124, 2125, -1, 2205, 2206, 2208, -1, 2209, 1977, 2198, -1, 2209, 2198, 2132, -1, 2209, 2131, 2138, -1, 2209, 2132, 2131, -1, 2207, 2125, 2210, -1, 2209, 2140, 1977, -1, 2209, 2138, 2140, -1, 2211, 2212, 2200, -1, 2211, 2200, 2199, -1, 2213, 2193, 2130, -1, 2211, 2199, 2201, -1, 2214, 2203, 2215, -1, 2214, 2204, 2202, -1, 2214, 2202, 2203, -1, 2216, 2139, 2178, -1, 2216, 2178, 2217, -1, 2216, 2117, 2122, -1, 2216, 2122, 2139, -1, 2218, 2208, 2219, -1, 2218, 2072, 2205, -1, 2218, 2220, 2072, -1, 2218, 2205, 2208, -1, 2221, 2222, 2212, -1, 2221, 2211, 2201, -1, 2221, 2223, 2222, -1, 2221, 2201, 2223, -1, 2221, 2212, 2211, -1, 2224, 2103, 2225, -1, 2224, 2225, 2226, -1, 2224, 2226, 2158, -1, 2224, 2158, 2103, -1, 2227, 2204, 2214, -1, 2227, 2215, 2228, -1, 2227, 2214, 2215, -1, 2227, 2229, 2204, -1, 2230, 2219, 2231, -1, 2230, 2232, 2220, -1, 2230, 2218, 2219, -1, 2230, 2220, 2218, -1, 2233, 2171, 2096, -1, 2233, 2155, 2234, -1, 2233, 2096, 2155, -1, 2235, 2236, 2237, -1, 2235, 2237, 2117, -1, 2235, 2117, 2216, -1, 2235, 2238, 2236, -1, 2239, 886, 2168, -1, 2235, 2217, 2238, -1, 2235, 2216, 2217, -1, 2240, 2241, 2242, -1, 2240, 2243, 2241, -1, 2240, 2242, 2244, -1, 2245, 2227, 2228, -1, 2245, 2228, 2246, -1, 2245, 2229, 2227, -1, 2245, 2247, 2229, -1, 2248, 2232, 2230, -1, 956, 952, 955, -1, 2248, 2249, 2232, -1, 2248, 2230, 2231, -1, 2250, 2233, 2234, -1, 2250, 2234, 2251, -1, 2250, 2171, 2233, -1, 2252, 2240, 2244, -1, 2252, 2243, 2240, -1, 2252, 2244, 2253, -1, 2254, 2239, 2168, -1, 2252, 2255, 2243, -1, 2256, 2158, 2257, -1, 2256, 2257, 2258, -1, 978, 2183, 948, -1, 2256, 2259, 2159, -1, 2256, 2159, 2158, -1, 2260, 2247, 2245, -1, 2260, 2245, 2246, -1, 2260, 2246, 2261, -1, 2262, 2263, 2264, -1, 2262, 2265, 2263, -1, 2262, 2264, 2266, -1, 2267, 2268, 2269, -1, 2262, 2266, 2226, -1, 2267, 2270, 2268, -1, 2262, 2226, 2265, -1, 950, 952, 956, -1, 2271, 2248, 2231, -1, 2271, 2249, 2248, -1, 2271, 2272, 2249, -1, 2271, 2231, 2273, -1, 2274, 2242, 2241, -1, 2274, 2171, 2250, -1, 2274, 2250, 2251, -1, 2265, 2226, 2225, -1, 2274, 2241, 2171, -1, 2274, 2251, 2242, -1, 2275, 2276, 2277, -1, 2275, 2277, 2278, -1, 2279, 2259, 2256, -1, 2279, 2258, 2280, -1, 2279, 2256, 2258, -1, 2281, 2195, 2282, -1, 2279, 2283, 2259, -1, 2284, 2252, 2253, -1, 2284, 2255, 2252, -1, 2284, 2285, 2286, -1, 2284, 2286, 2255, -1, 2281, 2194, 2195, -1, 2284, 2253, 2285, -1, 2287, 2193, 2213, -1, 2288, 2260, 2261, -1, 2288, 2261, 2289, -1, 2288, 2290, 2247, -1, 2288, 2289, 2290, -1, 2288, 2247, 2260, -1, 2291, 2272, 2271, -1, 2291, 2273, 2292, -1, 2291, 2293, 2272, -1, 2291, 2271, 2273, -1, 2294, 2263, 2276, -1, 2294, 2275, 2278, -1, 2294, 2278, 2295, -1, 2294, 2295, 2296, -1, 2294, 2276, 2275, -1, 2297, 2280, 2298, -1, 2297, 2283, 2279, -1, 2297, 2279, 2280, -1, 2299, 2267, 2269, -1, 2299, 2300, 2267, -1, 2299, 2269, 2301, -1, 2299, 2301, 2302, -1, 2299, 2302, 2303, -1, 2304, 2293, 2291, -1, 2304, 2292, 2305, -1, 1000, 2207, 2210, -1, 2304, 2306, 2293, -1, 1000, 2210, 986, -1, 2304, 2291, 2292, -1, 2307, 2308, 2309, -1, 2307, 2309, 2310, -1, 2307, 2311, 2308, -1, 2307, 2310, 2311, -1, 2312, 2283, 2297, -1, 2312, 2298, 2313, -1, 2312, 2297, 2298, -1, 2312, 2314, 2283, -1, 2312, 2313, 2314, -1, 2315, 2264, 2263, -1, 2315, 2263, 2294, -1, 2315, 2294, 2296, -1, 2316, 2317, 2318, -1, 2316, 2318, 2319, -1, 2320, 2304, 2305, -1, 2320, 2306, 2304, -1, 2321, 2300, 2299, -1, 2321, 2322, 2323, -1, 2321, 2324, 2300, -1, 2321, 2299, 2303, -1, 1022, 916, 886, -1, 2321, 2303, 2322, -1, 1022, 1021, 916, -1, 2325, 2315, 2296, -1, 2325, 2326, 2327, -1, 2325, 2327, 2264, -1, 2325, 2264, 2315, -1, 2325, 2296, 2328, -1, 2329, 2319, 2330, -1, 2329, 2317, 2316, -1, 2329, 2331, 2317, -1, 2332, 974, 960, -1, 2329, 2330, 2333, -1, 2329, 2316, 2319, -1, 2329, 2333, 2331, -1, 2334, 2335, 2306, -1, 2334, 2320, 2305, -1, 2334, 2305, 2336, -1, 2334, 2336, 2337, -1, 2334, 2306, 2320, -1, 2338, 2339, 2290, -1, 2340, 2341, 2342, -1, 2340, 2342, 2343, -1, 2340, 2343, 2344, -1, 2345, 2246, 2228, -1, 2346, 2321, 2323, -1, 1006, 2347, 1007, -1, 2346, 2348, 2324, -1, 2346, 2324, 2321, -1, 2349, 2350, 2311, -1, 2349, 2311, 2351, -1, 2349, 2352, 2350, -1, 2353, 2239, 2254, -1, 2349, 2351, 2352, -1, 2354, 2326, 2325, -1, 2354, 2355, 2326, -1, 2354, 2356, 2355, -1, 2354, 2328, 2356, -1, 2354, 2325, 2328, -1, 2357, 2334, 2337, -1, 2357, 2335, 2334, -1, 2357, 2337, 2358, -1, 2357, 2359, 2335, -1, 2360, 2340, 2344, -1, 2360, 2361, 2341, -1, 2360, 2362, 2361, -1, 2360, 2341, 2340, -1, 975, 982, 976, -1, 2363, 2348, 2346, -1, 2363, 2323, 2364, -1, 2363, 2346, 2323, -1, 2363, 2365, 2348, -1, 2366, 2367, 2368, -1, 2366, 2369, 2367, -1, 2366, 2370, 2371, -1, 2366, 2368, 2370, -1, 2366, 2371, 2372, -1, 2373, 2374, 2375, -1, 2373, 2358, 2376, -1, 2373, 2376, 2374, -1, 992, 951, 950, -1, 2373, 2375, 2359, -1, 2373, 2357, 2358, -1, 992, 1040, 951, -1, 2373, 2359, 2357, -1, 2377, 2378, 2379, -1, 2377, 2380, 2378, -1, 2377, 2379, 2381, -1, 2377, 2381, 2382, -1, 2383, 2384, 2385, -1, 2383, 2385, 2362, -1, 2383, 2362, 2360, -1, 2383, 2360, 2344, -1, 2383, 2344, 2384, -1, 2386, 2363, 2364, -1, 2386, 2387, 2365, -1, 2388, 2222, 2223, -1, 2386, 2364, 2389, -1, 2386, 2389, 2387, -1, 2386, 2365, 2363, -1, 2390, 2353, 2254, -1, 2391, 2369, 2366, -1, 2391, 2392, 2393, -1, 2391, 2366, 2372, -1, 2391, 2393, 2369, -1, 2391, 2372, 2392, -1, 2394, 2395, 2380, -1, 2394, 2377, 2382, -1, 2394, 2382, 2395, -1, 983, 982, 975, -1, 2394, 2380, 2377, -1, 2396, 2397, 2350, -1, 2396, 2350, 2398, -1, 2396, 2398, 2399, -1, 2396, 2400, 2397, -1, 2401, 2402, 2403, -1, 2401, 2351, 2404, -1, 2401, 2404, 2402, -1, 2401, 2403, 2405, -1, 2401, 2405, 2351, -1, 2406, 2407, 2408, -1, 2406, 2408, 2409, -1, 2410, 2411, 2412, -1, 2410, 2413, 2411, -1, 2410, 2412, 2414, -1, 2410, 2414, 2415, -1, 2410, 2415, 2413, -1, 2416, 2400, 2396, -1, 2283, 2287, 2213, -1, 2416, 2399, 2417, -1, 2416, 2396, 2399, -1, 2283, 2213, 2259, -1, 1020, 2282, 1021, -1, 2418, 2409, 2419, -1, 2418, 2419, 2420, -1, 2418, 2407, 2406, -1, 2418, 2406, 2409, -1, 1020, 2281, 2282, -1, 2418, 2402, 2407, -1, 2421, 2422, 2400, -1, 2421, 2416, 2417, -1, 2421, 2417, 2423, -1, 2424, 974, 2332, -1, 2421, 2400, 2416, -1, 2425, 2387, 2426, -1, 2425, 2427, 2428, -1, 2429, 2338, 2290, -1, 2425, 2428, 2387, -1, 2430, 2403, 2402, -1, 2430, 2418, 2420, -1, 2430, 2402, 2418, -1, 2431, 2421, 2423, -1, 2431, 2423, 2432, -1, 2431, 2422, 2421, -1, 2431, 2433, 2422, -1, 2434, 2427, 2425, -1, 2434, 2426, 2435, -1, 2434, 2425, 2426, -1, 2436, 2412, 2411, -1, 2436, 2437, 2438, -1, 2439, 2424, 2332, -1, 2436, 2411, 2437, -1, 2436, 2438, 2412, -1, 2440, 2441, 2442, -1, 2440, 2442, 2443, -1, 2440, 2443, 2444, -1, 2445, 2446, 2447, -1, 2289, 2429, 2290, -1, 2445, 2447, 2448, -1, 2449, 2433, 2431, -1, 2449, 2432, 2450, -1, 2449, 2451, 2433, -1, 2449, 2431, 2432, -1, 2449, 2450, 2451, -1, 2452, 2453, 2454, -1, 2452, 2455, 2456, -1, 2452, 2457, 2455, -1, 2452, 2454, 2457, -1, 2452, 2456, 2458, -1, 2459, 2246, 2345, -1, 2452, 2458, 2453, -1, 2460, 2420, 2461, -1, 2460, 2403, 2430, -1, 2460, 2462, 2463, -1, 2460, 2463, 2403, -1, 2460, 2430, 2420, -1, 2464, 2434, 2435, -1, 2464, 2435, 2465, -1, 2464, 2427, 2434, -1, 2464, 2466, 2427, -1, 2464, 2465, 2467, -1, 2468, 2444, 2469, -1, 2468, 2440, 2444, -1, 2468, 2470, 2441, -1, 2468, 2441, 2440, -1, 2471, 2472, 2473, -1, 2471, 2448, 2474, -1, 2475, 2222, 2388, -1, 2471, 2474, 2472, -1, 2471, 2473, 2446, -1, 2471, 2445, 2448, -1, 2471, 2446, 2445, -1, 2476, 2477, 2466, -1, 2476, 2464, 2467, -1, 2478, 2459, 2345, -1, 2479, 2353, 2390, -1, 2476, 2466, 2464, -1, 2480, 2461, 2481, -1, 2480, 2462, 2460, -1, 2480, 2482, 2462, -1, 2480, 2460, 2461, -1, 2480, 2481, 2482, -1, 2483, 2469, 2484, -1, 2483, 2485, 2470, -1, 2486, 2487, 1015, -1, 2483, 2468, 2469, -1, 2483, 2470, 2468, -1, 2488, 2489, 2490, -1, 2488, 2490, 2491, -1, 2488, 2492, 2489, -1, 2488, 2491, 2492, -1, 2493, 2467, 2494, -1, 2493, 2476, 2467, -1, 2493, 2495, 2477, -1, 2493, 2477, 2476, -1, 2496, 2429, 2289, -1, 2497, 2498, 2499, -1, 2497, 2499, 2500, -1, 2497, 2500, 2501, -1, 2502, 2231, 2503, -1, 2497, 2504, 2498, -1, 2505, 2483, 2484, -1, 2505, 2506, 2485, -1, 2505, 2485, 2483, -1, 2502, 2273, 2231, -1, 2507, 2494, 2508, -1, 2507, 2508, 2509, -1, 2507, 2495, 2493, -1, 2507, 2493, 2494, -1, 2507, 2509, 2495, -1, 2510, 2497, 2501, -1, 2510, 2504, 2497, -1, 2318, 2236, 2238, -1, 2510, 2511, 2504, -1, 2510, 2501, 2511, -1, 2512, 2484, 2513, -1, 2512, 2514, 2506, -1, 2512, 2505, 2484, -1, 2512, 2506, 2505, -1, 2515, 2516, 2517, -1, 2515, 2517, 2518, -1, 2515, 2519, 2516, -1, 2515, 2520, 2519, -1, 2521, 2522, 2523, -1, 2317, 2236, 2318, -1, 2521, 2524, 2522, -1, 2521, 2523, 2525, -1, 2521, 2525, 2526, -1, 2521, 2526, 2524, -1, 2527, 2528, 2529, -1, 2527, 2529, 2482, -1, 2527, 2482, 2530, -1, 2531, 2513, 2532, -1, 2531, 2532, 2514, -1, 2531, 2512, 2513, -1, 2531, 2514, 2512, -1, 2533, 2518, 2534, -1, 2533, 2520, 2515, -1, 2533, 2515, 2518, -1, 2535, 2530, 2536, -1, 2278, 2277, 2222, -1, 2535, 2527, 2530, -1, 2535, 2528, 2527, -1, 2535, 2537, 2528, -1, 2538, 2539, 2540, -1, 2538, 2541, 2542, -1, 2543, 2424, 2439, -1, 2538, 2540, 2541, -1, 2278, 2222, 2475, -1, 2538, 2542, 2544, -1, 2545, 2546, 2509, -1, 2545, 2509, 2547, -1, 2545, 2548, 2546, -1, 2549, 2534, 2550, -1, 2549, 2520, 2533, -1, 2549, 2533, 2534, -1, 2549, 2551, 2520, -1, 2552, 2537, 2535, -1, 2552, 2536, 2553, -1, 2552, 2535, 2536, -1, 2554, 2555, 2539, -1, 2554, 2539, 2538, -1, 2554, 2538, 2544, -1, 2556, 2557, 2558, -1, 2556, 2559, 2560, -1, 2556, 2561, 2557, -1, 2556, 2558, 2559, -1, 2562, 2523, 2522, -1, 2562, 2563, 2564, -1, 2562, 2522, 2563, -1, 2562, 2564, 2523, -1, 2565, 2545, 2547, -1, 1014, 2486, 1015, -1, 2565, 2548, 2545, -1, 2565, 2547, 2566, -1, 2567, 2568, 2551, -1, 2569, 2253, 2244, -1, 2567, 2551, 2549, -1, 2567, 2549, 2550, -1, 2570, 2571, 2572, -1, 2570, 2537, 2552, -1, 2570, 2553, 2573, -1, 2570, 2552, 2553, -1, 2570, 2572, 2537, -1, 2574, 2575, 2555, -1, 2574, 2544, 2575, -1, 1039, 2543, 2439, -1, 2574, 2555, 2554, -1, 2574, 2554, 2544, -1, 2576, 2577, 2578, -1, 2576, 2579, 2580, -1, 2576, 2580, 2577, -1, 2581, 2548, 2565, -1, 2581, 2565, 2566, -1, 2581, 2566, 2582, -1, 2581, 2583, 2548, -1, 2584, 2585, 2561, -1, 2584, 2556, 2560, -1, 2586, 2459, 2478, -1, 2584, 2560, 2585, -1, 2584, 2561, 2556, -1, 2587, 965, 2588, -1, 2589, 2590, 2591, -1, 2589, 2592, 2593, -1, 2587, 966, 965, -1, 2589, 2593, 2594, -1, 2589, 2591, 2592, -1, 2595, 2567, 2550, -1, 2595, 2550, 2596, -1, 2595, 2596, 2597, -1, 2595, 2597, 2598, -1, 2595, 2599, 2568, -1, 2595, 2568, 2567, -1, 2595, 2598, 2599, -1, 2600, 2570, 2573, -1, 2600, 2601, 2571, -1, 2600, 2571, 2570, -1, 2602, 2578, 2603, -1, 2602, 2604, 2579, -1, 2602, 2579, 2576, -1, 2306, 2586, 2478, -1, 2602, 2576, 2578, -1, 2605, 2582, 2606, -1, 2607, 2475, 2388, -1, 2605, 2583, 2581, -1, 2605, 2581, 2582, -1, 2607, 2388, 2608, -1, 2605, 2609, 2583, -1, 2610, 2590, 2589, -1, 2610, 2611, 2590, -1, 2610, 2594, 2612, -1, 2610, 2589, 2594, -1, 2613, 2614, 2601, -1, 2613, 2601, 2600, -1, 2613, 2615, 2614, -1, 2613, 2573, 2615, -1, 2613, 2600, 2573, -1, 2616, 2617, 2618, -1, 2616, 2619, 2617, -1, 1030, 2390, 1004, -1, 2616, 2618, 2620, -1, 2616, 2620, 2619, -1, 2621, 2605, 2606, -1, 1030, 2479, 2390, -1, 2621, 2609, 2605, -1, 2621, 2606, 2622, -1, 2621, 2623, 2609, -1, 1072, 2479, 1030, -1, 2624, 2604, 2602, -1, 2624, 2625, 2626, -1, 2624, 2626, 2604, -1, 2624, 2603, 2627, -1, 2628, 2503, 2629, -1, 2624, 2602, 2603, -1, 2628, 2502, 2503, -1, 2630, 2631, 2632, -1, 2630, 2632, 2633, -1, 2630, 2633, 2634, -1, 2635, 2636, 2637, -1, 2635, 2637, 2638, -1, 1050, 991, 990, -1, 2635, 2638, 2639, -1, 2640, 2612, 2641, -1, 2640, 2642, 2611, -1, 2640, 2610, 2612, -1, 2640, 2611, 2610, -1, 2643, 2621, 2622, -1, 2643, 2644, 2623, -1, 2643, 2623, 2621, -1, 2643, 2622, 2645, -1, 2643, 2645, 2644, -1, 2646, 2627, 2647, -1, 2646, 2624, 2627, -1, 2648, 994, 995, -1, 2646, 2649, 2625, -1, 2646, 2625, 2624, -1, 2650, 2651, 2652, -1, 2650, 2631, 2630, -1, 2650, 2652, 2631, -1, 1037, 2653, 1020, -1, 2650, 2630, 2634, -1, 2650, 2634, 2651, -1, 2654, 2655, 2636, -1, 2654, 2636, 2635, -1, 2654, 2635, 2639, -1, 2656, 2642, 2640, -1, 2656, 2641, 2657, -1, 2656, 2640, 2641, -1, 2658, 2646, 2647, -1, 2658, 2659, 2649, -1, 2658, 2649, 2646, -1, 2658, 2647, 2659, -1, 2660, 2661, 2614, -1, 2660, 2614, 2662, -1, 2663, 2664, 2665, -1, 2663, 2666, 2664, -1, 2663, 2665, 2667, -1, 1070, 2543, 1039, -1, 2668, 2669, 2670, -1, 2668, 2671, 2672, -1, 2668, 2672, 2669, -1, 2673, 2253, 2569, -1, 2668, 2670, 2671, -1, 2674, 2654, 2639, -1, 2674, 2675, 2676, -1, 2674, 2676, 2655, -1, 2674, 2639, 2677, -1, 2674, 2677, 2675, -1, 2678, 2653, 1037, -1, 2674, 2655, 2654, -1, 2678, 1060, 2653, -1, 2679, 2656, 2657, -1, 2679, 2642, 2656, -1, 2679, 2657, 2680, -1, 2679, 2681, 2642, -1, 2682, 2587, 2588, -1, 2683, 2684, 2685, -1, 2683, 2686, 2684, -1, 2683, 2685, 2687, -1, 2683, 2688, 2686, -1, 2682, 2588, 2689, -1, 2690, 2662, 2691, -1, 2313, 2310, 2314, -1, 2690, 2691, 2692, -1, 2690, 2692, 2693, -1, 2690, 2694, 2661, -1, 2690, 2693, 2694, -1, 2690, 2661, 2660, -1, 2690, 2660, 2662, -1, 2695, 2673, 2569, -1, 2696, 2697, 2698, -1, 2696, 2698, 2644, -1, 2696, 2644, 2699, -1, 2700, 2666, 2663, -1, 2700, 2663, 2667, -1, 2335, 2586, 2306, -1, 2700, 2667, 2701, -1, 2700, 2701, 2702, -1, 2703, 2679, 2680, -1, 2703, 2680, 2704, -1, 2703, 2705, 2681, -1, 2703, 2681, 2679, -1, 2706, 2688, 2683, -1, 2706, 2707, 2688, -1, 2706, 2683, 2687, -1, 2706, 2687, 2707, -1, 2708, 2709, 2666, -1, 2708, 2666, 2700, -1, 1061, 1060, 2678, -1, 2708, 2700, 2702, -1, 2710, 2696, 2699, -1, 2710, 2699, 2711, -1, 2710, 2697, 2696, -1, 2712, 2713, 2714, -1, 2712, 2714, 2705, -1, 2712, 2705, 2703, -1, 2311, 2310, 2313, -1, 2712, 2704, 2715, -1, 2712, 2703, 2704, -1, 2716, 994, 2648, -1, 2717, 2718, 2719, -1, 2717, 2719, 2720, -1, 2717, 2721, 2718, -1, 2722, 2723, 2724, -1, 2722, 2724, 2725, -1, 2726, 2608, 2727, -1, 2722, 2725, 2728, -1, 2726, 2607, 2608, -1, 2722, 2728, 2723, -1, 2729, 2709, 2708, -1, 2729, 2730, 2709, -1, 2729, 2702, 2730, -1, 2729, 2708, 2702, -1, 2731, 2732, 2697, -1, 2731, 2697, 2710, -1, 2731, 2711, 2733, -1, 2731, 2710, 2711, -1, 2734, 2713, 2712, -1, 2734, 2712, 2715, -1, 2735, 2717, 2720, -1, 2735, 2720, 2736, -1, 2735, 2721, 2717, -1, 2735, 2737, 2721, -1, 2738, 2739, 2732, -1, 2738, 2733, 2740, -1, 2738, 2731, 2733, -1, 2738, 2732, 2731, -1, 2741, 2734, 2715, -1, 2741, 2742, 2713, -1, 2741, 2715, 2743, -1, 2741, 2713, 2734, -1, 2361, 2629, 2341, -1, 2744, 2735, 2736, -1, 2744, 2736, 2745, -1, 1055, 994, 2716, -1, 2744, 2746, 2747, -1, 2744, 2747, 2737, -1, 2361, 2628, 2629, -1, 2744, 2737, 2735, -1, 1055, 1054, 994, -1, 2748, 2739, 2738, -1, 2748, 2738, 2740, -1, 2748, 2740, 2749, -1, 2748, 2750, 2739, -1, 2751, 2752, 2742, -1, 2751, 2741, 2743, -1, 2751, 2743, 2753, -1, 2751, 2742, 2741, -1, 1092, 1027, 1026, -1, 2754, 2755, 2756, -1, 2754, 2756, 2757, -1, 2754, 2758, 2755, -1, 2759, 2750, 2748, -1, 2759, 2748, 2749, -1, 2759, 2760, 2750, -1, 2759, 2749, 2760, -1, 2761, 2762, 2763, -1, 2761, 2764, 2762, -1, 2761, 2763, 2765, -1, 2766, 2767, 2768, -1, 2766, 2769, 2767, -1, 1095, 1027, 1092, -1, 2766, 2768, 2770, -1, 2766, 2770, 2769, -1, 2771, 2772, 2773, -1, 2379, 2378, 2285, -1, 2771, 2774, 2775, -1, 2379, 2285, 2253, -1, 2771, 2775, 2776, -1, 2771, 2777, 2772, -1, 2771, 2776, 2777, -1, 2778, 2330, 2319, -1, 2771, 2773, 2774, -1, 2779, 2744, 2745, -1, 2779, 2745, 2780, -1, 2779, 2746, 2744, -1, 2779, 2781, 2746, -1, 2782, 2783, 2752, -1, 2782, 2752, 2751, -1, 2782, 2753, 2784, -1, 1058, 2785, 1059, -1, 2782, 2751, 2753, -1, 2786, 2787, 2788, -1, 2786, 2789, 2790, -1, 2786, 2790, 2791, -1, 2786, 2791, 2787, -1, 2792, 2793, 2794, -1, 2792, 2794, 2758, -1, 2792, 2754, 2757, -1, 2792, 2758, 2754, -1, 2367, 2795, 2368, -1, 2792, 2757, 2793, -1, 2796, 2765, 2787, -1, 2796, 2761, 2765, -1, 2796, 2787, 2764, -1, 1087, 2682, 2689, -1, 2796, 2764, 2761, -1, 1087, 2689, 1035, -1, 2797, 2783, 2782, -1, 2797, 2784, 2798, -1, 2797, 2782, 2784, -1, 2799, 2780, 2800, -1, 2799, 2781, 2779, -1, 2801, 2673, 2695, -1, 2799, 2800, 2781, -1, 2799, 2779, 2780, -1, 2802, 2788, 2803, -1, 2333, 2342, 2331, -1, 2802, 2789, 2786, -1, 2802, 2804, 2789, -1, 2802, 2786, 2788, -1, 2805, 2806, 2807, -1, 2805, 2808, 2809, -1, 2805, 2807, 2808, -1, 2805, 2809, 2806, -1, 2810, 2811, 2812, -1, 2810, 2813, 2814, -1, 2810, 2812, 2813, -1, 2815, 2783, 2797, -1, 2815, 2797, 2798, -1, 2815, 2816, 2783, -1, 2815, 2798, 2817, -1, 2818, 2810, 2814, -1, 2818, 2814, 2819, -1, 2818, 2811, 2810, -1, 2820, 2803, 2821, -1, 2820, 2802, 2803, -1, 2820, 2804, 2802, -1, 2350, 2397, 2308, -1, 2822, 2716, 2648, -1, 2820, 2823, 2804, -1, 2822, 2648, 2824, -1, 2825, 2826, 2827, -1, 2350, 2308, 2311, -1, 2825, 2828, 2829, -1, 2825, 2827, 2828, -1, 2830, 2816, 2815, -1, 2830, 2815, 2817, -1, 2830, 2831, 2816, -1, 2830, 2817, 2832, -1, 2830, 2832, 2831, -1, 2833, 2834, 2811, -1, 2833, 2811, 2818, -1, 2833, 2819, 2835, -1, 2836, 2801, 2695, -1, 2833, 2818, 2819, -1, 2837, 2820, 2821, -1, 2837, 2821, 2838, -1, 2837, 2838, 2823, -1, 2837, 2823, 2820, -1, 2839, 2825, 2829, -1, 2839, 2829, 2840, -1, 2343, 2342, 2333, -1, 2839, 2826, 2825, -1, 2841, 2842, 2843, -1, 2841, 2844, 2842, -1, 2841, 2843, 2845, -1, 2841, 2845, 2844, -1, 2846, 2847, 2848, -1, 2846, 2848, 2849, -1, 2846, 2850, 2847, -1, 2851, 2833, 2835, -1, 2851, 2835, 2852, -1, 2851, 2834, 2833, -1, 2851, 2852, 2834, -1, 2853, 2854, 2855, -1, 2853, 2856, 2857, -1, 2853, 2857, 2831, -1, 2853, 2831, 2832, -1, 2853, 2832, 2854, -1, 2853, 2858, 2856, -1, 2853, 2855, 2858, -1, 2859, 2860, 2826, -1, 2859, 2839, 2840, -1, 2859, 2826, 2839, -1, 2859, 2840, 2861, -1, 2862, 2850, 2846, -1, 2862, 2849, 2863, -1, 2380, 2727, 2378, -1, 2862, 2846, 2849, -1, 2380, 2726, 2727, -1, 2862, 2864, 2850, -1, 2865, 2866, 2867, -1, 2865, 2868, 2866, -1, 2865, 2867, 2869, -1, 2870, 2871, 2856, -1, 2872, 2330, 2778, -1, 2870, 2856, 2858, -1, 2870, 2858, 2873, -1, 2874, 2861, 2875, -1, 2874, 2860, 2859, -1, 2874, 2876, 2860, -1, 2874, 2859, 2861, -1, 2877, 2864, 2862, -1, 2877, 2862, 2863, -1, 2877, 2878, 2864, -1, 2879, 2865, 2869, -1, 2879, 2868, 2865, -1, 2879, 2869, 2880, -1, 2881, 2871, 2870, -1, 2881, 2882, 2871, -1, 2881, 2870, 2873, -1, 2881, 2873, 2883, -1, 2884, 2874, 2875, -1, 2884, 2875, 2885, -1, 2886, 2872, 2778, -1, 2884, 2876, 2874, -1, 2887, 2855, 2854, -1, 2887, 2888, 2889, -1, 2887, 2854, 2888, -1, 2887, 2889, 2855, -1, 2890, 2878, 2877, -1, 2890, 2863, 2891, -1, 2890, 2892, 2878, -1, 2890, 2877, 2863, -1, 2893, 2894, 2868, -1, 2893, 2868, 2879, -1, 2893, 2879, 2880, -1, 2893, 2880, 2895, -1, 2893, 2895, 2894, -1, 2896, 2882, 2881, -1, 2896, 2881, 2883, -1, 2896, 2883, 2897, -1, 2898, 2899, 2900, -1, 2898, 2885, 2901, -1, 2898, 2876, 2884, -1, 2898, 2900, 2876, -1, 2898, 2884, 2885, -1, 2898, 2901, 2899, -1, 2902, 2890, 2891, -1, 2902, 2891, 2903, -1, 2902, 2892, 2890, -1, 2902, 2904, 2892, -1, 2905, 2906, 2907, -1, 2905, 2907, 2908, -1, 2905, 2909, 2906, -1, 2905, 2910, 2909, -1, 2911, 2882, 2896, -1, 2911, 2912, 2882, -1, 2911, 2896, 2897, -1, 2911, 2897, 2913, -1, 2914, 2903, 2915, -1, 2914, 2902, 2903, -1, 2916, 2801, 2836, -1, 2914, 2915, 2904, -1, 2914, 2904, 2902, -1, 2917, 2918, 2919, -1, 2917, 2920, 2918, -1, 2917, 2919, 2921, -1, 1136, 1084, 1085, -1, 2922, 2911, 2913, -1, 2923, 2924, 2375, -1, 2922, 2912, 2911, -1, 2922, 2925, 2912, -1, 2922, 2913, 2926, -1, 2927, 2928, 2910, -1, 2927, 2910, 2905, -1, 2927, 2905, 2908, -1, 2929, 2920, 2917, -1, 2929, 2921, 2930, -1, 2929, 2917, 2921, -1, 2931, 2922, 2926, -1, 2931, 2932, 2925, -1, 2933, 2824, 2934, -1, 2931, 2935, 2932, -1, 2931, 2925, 2922, -1, 2931, 2926, 2935, -1, 2936, 2937, 2938, -1, 2933, 2822, 2824, -1, 2936, 2938, 2928, -1, 2936, 2908, 2939, -1, 2936, 2927, 2908, -1, 2936, 2928, 2927, -1, 2940, 2941, 2920, -1, 2940, 2930, 2942, -1, 1097, 2943, 2944, -1, 2940, 2929, 2930, -1, 1097, 2944, 1098, -1, 2940, 2920, 2929, -1, 2945, 2946, 2947, -1, 2945, 2948, 2946, -1, 2945, 2947, 2949, -1, 2950, 2951, 2952, -1, 2950, 2953, 2951, -1, 2950, 2954, 2955, -1, 2950, 2955, 2932, -1, 2950, 2932, 2935, -1, 2950, 2952, 2954, -1, 2950, 2935, 2953, -1, 2956, 2940, 2942, -1, 2956, 2941, 2940, -1, 2956, 2957, 2941, -1, 2956, 2942, 2957, -1, 2958, 24, 2937, -1, 2958, 2939, 2959, -1, 2958, 2959, 24, -1, 2958, 2936, 2939, -1, 2958, 2937, 2936, -1, 2960, 2961, 2962, -1, 2963, 1035, 1034, -1, 2963, 1087, 1035, -1, 2960, 2964, 2965, -1, 2960, 2965, 2961, -1, 2966, 2967, 2968, -1, 2966, 2969, 2970, -1, 2966, 2968, 2969, -1, 2971, 2949, 2972, -1, 2971, 2948, 2945, -1, 2971, 2972, 2973, -1, 2971, 2945, 2949, -1, 2971, 2973, 2948, -1, 2974, 2960, 2962, -1, 2974, 2975, 2976, -1, 2974, 2962, 2977, -1, 2974, 2977, 2975, -1, 2974, 2976, 2964, -1, 2974, 2964, 2960, -1, 2978, 2952, 2979, -1, 2978, 2980, 2954, -1, 1142, 1145, 2785, -1, 2978, 2954, 2952, -1, 2981, 2966, 2970, -1, 2982, 2872, 2886, -1, 1142, 2785, 1058, -1, 2981, 2970, 2983, -1, 2981, 2984, 2967, -1, 2981, 2967, 2966, -1, 2985, 2983, 2986, -1, 2985, 2984, 2981, -1, 2985, 2981, 2983, -1, 2987, 2979, 2988, -1, 2987, 2978, 2979, -1, 2987, 2980, 2978, -1, 2987, 2989, 2980, -1, 2990, 2953, 32, -1, 2990, 34, 2951, -1, 2990, 2951, 2953, -1, 2990, 32, 34, -1, 2991, 62, 64, -1, 2991, 10, 62, -1, 2992, 2993, 2994, -1, 2991, 64, 2995, -1, 2991, 2995, 11, -1, 2991, 11, 10, -1, 2996, 1122, 1093, -1, 2997, 2985, 2986, -1, 2997, 2986, 12, -1, 2997, 2998, 2984, -1, 2997, 2984, 2985, -1, 2997, 12, 2998, -1, 2999, 2988, 3000, -1, 2374, 2923, 2375, -1, 2999, 2987, 2988, -1, 2999, 2989, 2987, -1, 1135, 1084, 1136, -1, 3001, 33, 44, -1, 3001, 43, 3002, -1, 3001, 3002, 3003, -1, 3001, 44, 43, -1, 3004, 3000, 3005, -1, 3004, 2989, 2999, -1, 1088, 1087, 2963, -1, 3004, 2999, 3000, -1, 3004, 3006, 2989, -1, 3007, 3008, 3009, -1, 3007, 3010, 3008, -1, 3007, 3009, 3011, -1, 2400, 2982, 2886, -1, 3012, 31, 33, -1, 3012, 33, 3001, -1, 3012, 3001, 3003, -1, 3013, 3004, 3005, -1, 3013, 3005, 3014, -1, 3013, 3006, 3004, -1, 3013, 3015, 3006, -1, 3016, 62, 10, -1, 3016, 10, 108, -1, 3016, 107, 62, -1, 3016, 108, 107, -1, 3017, 3007, 3011, -1, 3017, 3010, 3007, -1, 1160, 1163, 2943, -1, 3017, 3011, 136, -1, 3018, 2323, 2322, -1, 1160, 2943, 1097, -1, 3019, 3014, 184, -1, 3018, 2322, 3020, -1, 3019, 3015, 3013, -1, 3019, 3021, 3015, -1, 3019, 3013, 3014, -1, 3022, 3012, 3003, -1, 3022, 3023, 3024, -1, 3022, 3024, 31, -1, 3022, 3003, 3025, -1, 3022, 31, 3012, -1, 3026, 3017, 136, -1, 3026, 163, 3010, -1, 3026, 136, 135, -1, 3026, 3010, 3017, -1, 3027, 3021, 3019, -1, 3027, 3019, 184, -1, 3027, 3028, 3029, -1, 3027, 3029, 3021, -1, 3030, 211, 3023, -1, 3030, 3022, 3025, -1, 3030, 3023, 3022, -1, 3030, 212, 211, -1, 3030, 3025, 212, -1, 3031, 120, 63, -1, 3031, 122, 3032, -1, 3031, 63, 122, -1, 3033, 163, 3026, -1, 3033, 135, 164, -1, 3033, 3026, 135, -1, 3033, 164, 163, -1, 3034, 141, 106, -1, 3034, 180, 201, -1, 3034, 106, 180, -1, 3034, 201, 141, -1, 2387, 2916, 2836, -1, 1155, 2933, 2934, -1, 3035, 3027, 184, -1, 2387, 2836, 2365, -1, 3035, 3028, 3027, -1, 1155, 2934, 1145, -1, 3035, 184, 188, -1, 2428, 2916, 2387, -1, 3036, 3031, 3032, -1, 3036, 3032, 3037, -1, 3036, 120, 3031, -1, 3038, 188, 3039, -1, 3038, 3035, 188, -1, 3038, 3040, 3028, -1, 3038, 3028, 3035, -1, 3041, 120, 3036, -1, 3042, 2992, 2994, -1, 3041, 3037, 3043, -1, 3041, 3036, 3037, -1, 3041, 155, 120, -1, 3044, 3038, 3039, -1, 3044, 3039, 3045, -1, 3044, 3040, 3038, -1, 3044, 198, 3040, -1, 3046, 261, 3047, -1, 2405, 2352, 2351, -1, 3046, 3047, 225, -1, 3046, 225, 230, -1, 3046, 259, 261, -1, 3046, 230, 259, -1, 3048, 3041, 3043, -1, 3048, 155, 3041, -1, 3048, 3043, 224, -1, 3048, 226, 155, -1, 3048, 224, 226, -1, 3049, 3044, 3045, -1, 3049, 3045, 3050, -1, 3049, 198, 3044, -1, 3051, 2355, 2356, -1, 3052, 243, 3053, -1, 3052, 3053, 255, -1, 3052, 254, 3054, -1, 3055, 2994, 1124, -1, 3052, 255, 254, -1, 3055, 1124, 1123, -1, 3056, 3050, 3057, -1, 2395, 3058, 2380, -1, 3056, 3049, 3050, -1, 3055, 3042, 2994, -1, 3056, 228, 198, -1, 3056, 198, 3049, -1, 3059, 1122, 2996, -1, 3060, 243, 3052, -1, 3060, 3054, 3061, -1, 3060, 3052, 3054, -1, 3062, 295, 294, -1, 3062, 230, 295, -1, 3062, 294, 259, -1, 3062, 259, 230, -1, 3063, 3057, 3064, -1, 3063, 3065, 228, -1, 3063, 228, 3056, -1, 3063, 3056, 3057, -1, 3066, 243, 3060, -1, 2422, 2982, 2400, -1, 3066, 3067, 242, -1, 3066, 3060, 3061, -1, 3066, 242, 243, -1, 3066, 3061, 3068, -1, 3069, 286, 280, -1, 3069, 3064, 3070, -1, 3069, 3070, 286, -1, 3069, 3063, 3064, -1, 3069, 280, 3065, -1, 3071, 3059, 2996, -1, 3069, 3065, 3063, -1, 3072, 3073, 3067, -1, 3072, 3066, 3068, -1, 3072, 3067, 3066, -1, 3074, 3072, 3068, -1, 3075, 3058, 2395, -1, 3074, 374, 3073, -1, 3074, 3076, 374, -1, 3074, 3073, 3072, -1, 3075, 2413, 3058, -1, 3074, 3068, 3076, -1, 3077, 260, 289, -1, 3077, 288, 260, -1, 3077, 289, 3078, -1, 3079, 293, 296, -1, 3079, 314, 317, -1, 3079, 296, 314, -1, 3079, 317, 293, -1, 3080, 3018, 3020, -1, 3080, 3020, 3081, -1, 3082, 288, 3077, -1, 3082, 3078, 3083, -1, 3082, 3077, 3078, -1, 3084, 3042, 3055, -1, 3085, 306, 288, -1, 3085, 3083, 3086, -1, 3085, 288, 3082, -1, 3085, 3082, 3083, -1, 3087, 327, 329, -1, 3087, 3085, 3086, -1, 3087, 3086, 327, -1, 3088, 1097, 3089, -1, 3087, 329, 306, -1, 3087, 306, 3085, -1, 3090, 374, 3076, -1, 3088, 1160, 1097, -1, 3090, 3076, 357, -1, 3091, 372, 3092, -1, 3091, 3092, 3093, -1, 3091, 3093, 381, -1, 3091, 350, 373, -1, 3091, 381, 350, -1, 3091, 373, 372, -1, 3094, 356, 372, -1, 3094, 374, 3090, -1, 3094, 3090, 357, -1, 3094, 357, 356, -1, 3094, 372, 374, -1, 2411, 2413, 3075, -1, 3095, 364, 404, -1, 3095, 402, 364, -1, 3095, 404, 3096, -1, 3097, 3095, 3096, -1, 3098, 2355, 3051, -1, 3097, 402, 3095, -1, 3097, 3096, 3099, -1, 1107, 1195, 1101, -1, 3100, 402, 3097, -1, 3100, 3097, 3099, -1, 3100, 411, 402, -1, 3100, 3099, 3101, -1, 3102, 3101, 441, -1, 3102, 442, 411, -1, 3102, 411, 3100, -1, 3102, 441, 442, -1, 3102, 3100, 3101, -1, 3103, 3098, 3051, -1, 2409, 2355, 3098, -1, 2409, 2408, 2355, -1, 2447, 2385, 2384, -1, 3104, 1131, 1120, -1, 2446, 2385, 2447, -1, 3105, 3059, 3071, -1, 2412, 3106, 2414, -1, 1164, 3105, 3071, -1, 2442, 3080, 3081, -1, 3107, 1116, 1115, -1, 3107, 1115, 3108, -1, 2442, 3081, 2393, -1, 1149, 1134, 1137, -1, 1149, 1137, 1139, -1, 1198, 1134, 1149, -1, 3109, 3089, 3110, -1, 3109, 3088, 3089, -1, 3111, 1129, 1128, -1, 3112, 3098, 3103, -1, 1152, 3113, 1155, -1, 1191, 1195, 1107, -1, 3114, 3112, 3103, -1, 3115, 1131, 3104, -1, 3116, 3113, 1152, -1, 3116, 1169, 3113, -1, 3117, 3115, 3104, -1, 1204, 3105, 1164, -1, 1170, 1169, 3116, -1, 3118, 3108, 3119, -1, 3118, 3107, 3108, -1, 3120, 1129, 3111, -1, 1232, 3110, 1185, -1, 1232, 3109, 3110, -1, 2490, 2438, 2437, -1, 3121, 3112, 3114, -1, 2450, 3122, 3123, -1, 2450, 3123, 2451, -1, 3124, 3120, 3111, -1, 1253, 3125, 3126, -1, 3127, 2393, 2392, -1, 3127, 2442, 2393, -1, 1254, 1253, 3126, -1, 3128, 3115, 3117, -1, 1174, 1129, 3120, -1, 2498, 3121, 3114, -1, 2499, 3106, 2412, -1, 2499, 2498, 3106, -1, 1166, 3129, 1167, -1, 3130, 3131, 3132, -1, 3133, 2474, 2448, -1, 1217, 3128, 3117, -1, 2489, 2438, 2490, -1, 2443, 2442, 3127, -1, 1240, 3118, 3119, -1, 1240, 3119, 1177, -1, 2516, 3122, 2450, -1, 3134, 3120, 3124, -1, 2516, 2519, 3122, -1, 3135, 3134, 3124, -1, 2504, 3121, 2498, -1, 3136, 1177, 1157, -1, 3136, 1240, 1177, -1, 3137, 3130, 3132, -1, 1216, 3128, 1217, -1, 3138, 3139, 1261, -1, 3140, 2473, 2472, -1, 3140, 3132, 2473, -1, 3140, 3137, 3132, -1, 3141, 2474, 3133, -1, 3142, 3141, 3133, -1, 1237, 1218, 1212, -1, 3143, 3137, 3140, -1, 3144, 3134, 3135, -1, 3145, 2450, 3146, -1, 3145, 2516, 2450, -1, 1260, 3138, 1261, -1, 2458, 2540, 2453, -1, 1214, 1218, 1237, -1, 1299, 3144, 3135, -1, 1296, 3129, 1166, -1, 1296, 1299, 3129, -1, 3147, 1192, 3148, -1, 3147, 1194, 1192, -1, 3149, 1240, 3136, -1, 3150, 2484, 2469, -1, 1279, 1221, 1222, -1, 3151, 3141, 3142, -1, 1279, 1222, 1280, -1, 2520, 3151, 3142, -1, 3152, 2465, 3153, -1, 1241, 1240, 3149, -1, 3152, 2467, 2465, -1, 2509, 2491, 2495, -1, 2509, 2492, 2491, -1, 2546, 2492, 2509, -1, 1320, 3144, 1299, -1, 3154, 3146, 3155, -1, 3154, 3145, 3146, -1, 3156, 3148, 3157, -1, 3156, 3147, 3148, -1, 3158, 2482, 2481, -1, 2511, 3159, 2504, -1, 2541, 2540, 2458, -1, 3160, 2484, 3150, -1, 3161, 3159, 2511, -1, 3161, 2524, 3159, -1, 3162, 3160, 3150, -1, 3163, 1269, 1245, -1, 2551, 3151, 2520, -1, 2522, 2524, 3161, -1, 3164, 3152, 3153, -1, 3164, 3153, 3165, -1, 3166, 2482, 3158, -1, 2572, 3154, 3155, -1, 1334, 1336, 1250, -1, 2572, 3155, 2537, -1, 1334, 1250, 1215, -1, 1310, 3156, 3157, -1, 1310, 3157, 1272, -1, 1339, 1287, 1265, -1, 3167, 3166, 3158, -1, 3168, 1269, 3163, -1, 2591, 3169, 3170, -1, 1313, 1281, 1282, -1, 2592, 2591, 3170, -1, 1313, 1282, 1285, -1, 3171, 3160, 3162, -1, 2530, 2482, 3166, -1, 1366, 1281, 1313, -1, 3172, 3168, 3163, -1, 1319, 1301, 1320, -1, 2523, 3173, 2525, -1, 2557, 3171, 3162, -1, 3174, 1275, 1276, -1, 1341, 1287, 1339, -1, 1302, 1301, 1319, -1, 2580, 3164, 3165, -1, 2580, 3165, 2532, -1, 3175, 3166, 3167, -1, 1353, 3176, 1354, -1, 3177, 3175, 3167, -1, 3178, 3168, 3172, -1, 3179, 2580, 2532, -1, 3179, 2532, 2513, -1, 2561, 3171, 2557, -1, 3180, 3181, 2599, -1, 1329, 3178, 3172, -1, 3182, 1275, 3174, -1, 3183, 3184, 1362, -1, 3185, 3182, 3174, -1, 2575, 2558, 2555, -1, 3186, 3175, 3177, -1, 1401, 1342, 1340, -1, 2598, 3180, 2599, -1, 2559, 2558, 2575, -1, 1392, 3178, 1329, -1, 2631, 3186, 3177, -1, 1332, 1275, 3182, -1, 2632, 3173, 2523, -1, 2632, 2631, 3173, -1, 3187, 2542, 3188, -1, 1361, 3183, 1362, -1, 3187, 2544, 2542, -1, 3189, 2580, 3179, -1, 3190, 1392, 1329, -1, 3190, 1329, 1315, -1, 3191, 3182, 3185, -1, 3192, 3191, 3185, -1, 2620, 2564, 2563, -1, 2620, 2563, 2619, -1, 1400, 1342, 1401, -1, 3193, 1306, 3194, -1, 3193, 1345, 1306, -1, 2577, 2580, 3189, -1, 2652, 3186, 2631, -1, 1403, 3195, 1379, -1, 3196, 3188, 3197, -1, 3196, 3187, 3188, -1, 3198, 1388, 1375, -1, 3199, 3195, 1403, -1, 3200, 1392, 3190, -1, 3201, 3191, 3192, -1, 1434, 3201, 3192, -1, 3202, 2606, 2582, -1, 3203, 1369, 3204, -1, 3203, 1370, 1369, -1, 1435, 1346, 1345, -1, 1435, 1434, 1346, -1, 1398, 1401, 3195, -1, 1398, 3195, 3199, -1, 3205, 3194, 3206, -1, 3205, 3193, 3194, -1, 1390, 1392, 3200, -1, 2665, 2664, 2585, -1, 2665, 2585, 2560, -1, 2642, 3197, 2611, -1, 2642, 3196, 3197, -1, 1447, 1377, 1357, -1, 1448, 1377, 1447, -1, 3207, 1388, 3198, -1, 2669, 2627, 2603, -1, 3208, 2606, 3202, -1, 3209, 3207, 3198, -1, 1477, 3201, 1434, -1, 2644, 2618, 2617, -1, 2644, 2617, 2623, -1, 3210, 3204, 3211, -1, 2698, 2618, 2644, -1, 3210, 3203, 3204, -1, 2651, 2637, 2652, -1, 3212, 3206, 3213, -1, 3212, 3205, 3206, -1, 3214, 2614, 2615, -1, 2672, 2627, 2669, -1, 2638, 2637, 2651, -1, 3215, 1417, 1406, -1, 1452, 3216, 1453, -1, 2688, 3217, 2686, -1, 3218, 3207, 3209, -1, 3219, 3202, 3220, -1, 3219, 3208, 3202, -1, 1493, 1399, 1398, -1, 1493, 1496, 1399, -1, 1472, 3218, 3209, -1, 1466, 3211, 1431, -1, 1466, 3210, 3211, -1, 3221, 1417, 3215, -1, 1512, 3213, 1428, -1, 1512, 1428, 1443, -1, 1512, 3212, 3213, -1, 3222, 2614, 3214, -1, 3223, 3224, 2694, -1, 3225, 3222, 3214, -1, 3226, 3221, 3215, -1, 1511, 3212, 1512, -1, 1486, 3218, 1472, -1, 1456, 3227, 1458, -1, 2728, 2671, 2670, -1, 1488, 1423, 1411, -1, 1488, 1411, 1489, -1, 2718, 3219, 3220, -1, 2718, 3220, 2659, -1, 1476, 1459, 1477, -1, 2662, 2614, 3222, -1, 2693, 3223, 2694, -1, 1470, 1474, 1448, -1, 3228, 2718, 2659, -1, 3229, 3221, 3226, -1, 3228, 2659, 2647, -1, 3230, 3222, 3225, -1, 1460, 1459, 1476, -1, 3231, 3230, 3225, -1, 1483, 3229, 3226, -1, 2725, 2671, 2728, -1, 3232, 1446, 1445, -1, 3232, 1445, 3233, -1, 3234, 2677, 2639, -1, 3234, 2639, 3235, -1, 2730, 3236, 2709, -1, 3237, 1451, 1450, -1, 3237, 1450, 3238, -1, 1535, 3229, 1483, -1, 3239, 2715, 2704, -1, 3240, 3236, 2730, -1, 3241, 2718, 3228, -1, 3242, 3232, 3233, -1, 3242, 3233, 3243, -1, 3244, 3230, 3231, -1, 2758, 3244, 3231, -1, 3245, 1535, 1483, -1, 3245, 1483, 1462, -1, 1556, 1451, 3237, -1, 3246, 2701, 3247, -1, 3246, 2702, 2701, -1, 2755, 2758, 2675, -1, 2755, 2675, 2677, -1, 2723, 2728, 3236, -1, 2723, 3236, 3240, -1, 1531, 1490, 1529, -1, 3248, 3234, 3235, -1, 1531, 1491, 1490, -1, 3248, 3235, 3249, -1, 3250, 1522, 1506, -1, 1540, 3251, 1521, -1, 2719, 2718, 3241, -1, 2762, 2707, 2687, -1, 2764, 2707, 2762, -1, 3252, 2715, 3239, -1, 1557, 1556, 3237, -1, 3253, 3252, 3239, -1, 1563, 3243, 1556, -1, 2794, 3244, 2758, -1, 1563, 3242, 3243, -1, 3254, 3251, 1540, -1, 3255, 1535, 3245, -1, 3256, 3247, 3257, -1, 3256, 3246, 3247, -1, 3258, 1522, 3250, -1, 1530, 1529, 3251, -1, 1530, 3251, 3254, -1, 3259, 3248, 3249, -1, 3259, 3249, 3260, -1, 3261, 3258, 3250, -1, 1536, 1535, 3255, -1, 3262, 2740, 2733, -1, 2767, 3263, 2768, -1, 3264, 3252, 3253, -1, 3265, 1525, 1508, -1, 3266, 1525, 3265, -1, 1599, 3267, 1597, -1, 1599, 3268, 3267, -1, 2813, 2724, 2723, -1, 2813, 2812, 2724, -1, 2789, 3264, 3253, -1, 3269, 3258, 3261, -1, 2783, 3256, 3257, -1, 2783, 3257, 2752, -1, 3270, 2740, 3262, -1, 2828, 3259, 3260, -1, 1576, 3269, 3261, -1, 2828, 2750, 2760, -1, 2828, 3260, 2750, -1, 3271, 3270, 3262, -1, 2827, 3259, 2828, -1, 3272, 3273, 1604, -1, 3274, 1568, 1548, -1, 2804, 3264, 2789, -1, 1627, 1626, 1532, -1, 1627, 1532, 1530, -1, 2772, 3275, 2773, -1, 3276, 3266, 3265, -1, 2806, 2736, 2807, -1, 2806, 2745, 2736, -1, 1614, 1582, 1581, -1, 2793, 2774, 2794, -1, 1587, 3277, 1588, -1, 1590, 3269, 1576, -1, 2787, 2791, 2764, -1, 1603, 3272, 1604, -1, 3278, 3270, 3271, -1, 3279, 3277, 1587, -1, 3279, 3280, 3281, -1, 3279, 3281, 3277, -1, 3282, 1568, 3274, -1, 3283, 3266, 3276, -1, 2775, 2774, 2793, -1, 2800, 3278, 3271, -1, 3284, 3282, 3274, -1, 3285, 2763, 3286, -1, 3285, 2765, 2763, -1, 1635, 1582, 1614, -1, 3287, 1603, 1602, -1, 3288, 1585, 1554, -1, 3288, 1554, 3289, -1, 3290, 2770, 3291, -1, 3290, 2769, 2770, -1, 1609, 3266, 3283, -1, 1609, 1612, 3292, -1, 1609, 3292, 3266, -1, 3293, 3280, 3279, -1, 3293, 1687, 3280, -1, 3294, 3293, 3279, -1, 2847, 3278, 2800, -1, 3295, 3282, 3284, -1, 3296, 3285, 3286, -1, 3296, 3286, 3297, -1, 1622, 3295, 3284, -1, 3298, 2800, 2780, -1, 3299, 3276, 3300, -1, 3298, 2847, 2800, -1, 3299, 3283, 3276, -1, 2866, 2769, 3290, -1, 3301, 3288, 3289, -1, 3301, 3289, 3302, -1, 2845, 2809, 2808, -1, 2845, 2808, 2844, -1, 3303, 2835, 2819, -1, 2852, 3304, 2834, -1, 3305, 3293, 3294, -1, 3306, 3305, 3294, -1, 1685, 3295, 1622, -1, 2867, 2866, 3290, -1, 2868, 3297, 2866, -1, 2868, 3296, 3297, -1, 3307, 3299, 3300, -1, 3308, 3304, 2852, -1, 3307, 3300, 3309, -1, 3310, 2847, 3298, -1, 3311, 1622, 1607, -1, 3311, 1685, 1622, -1, 3312, 2835, 3303, -1, 1693, 3302, 1655, -1, 1693, 3301, 3302, -1, 2842, 2844, 3304, -1, 2842, 3304, 3308, -1, 1688, 1687, 3293, -1, 3313, 3312, 3303, -1, 3314, 1650, 1637, -1, 2848, 2847, 3310, -1, 1699, 3315, 1700, -1, 3316, 3305, 3306, -1, 1673, 1656, 1651, -1, 3317, 2838, 2821, -1, 3318, 2838, 3317, -1, 1726, 3316, 3306, -1, 1653, 1656, 1673, -1, 3319, 3312, 3313, -1, 1713, 3307, 3309, -1, 1713, 3309, 1689, -1, 3320, 1650, 3314, -1, 3321, 1685, 3311, -1, 3322, 3320, 3314, -1, 2882, 3319, 3313, -1, 1659, 1640, 1639, -1, 3323, 3324, 2900, -1, 3325, 2875, 2861, -1, 3326, 3316, 1726, -1, 3327, 3328, 1707, -1, 2919, 2843, 2842, -1, 2919, 2918, 2843, -1, 3329, 3318, 3317, -1, 1682, 1685, 3321, -1, 2910, 2889, 2888, -1, 2895, 3330, 2894, -1, 2912, 3319, 2882, -1, 3331, 3320, 3322, -1, 2899, 3323, 2900, -1, 1706, 3327, 1707, -1, 3332, 3333, 3334, -1, 3332, 3334, 3330, -1, 3332, 3330, 2895, -1, 1722, 3331, 3322, -1, 3335, 2875, 3325, -1, 3336, 3318, 3329, -1, 3337, 1639, 3338, -1, 3337, 1659, 1639, -1, 3339, 3335, 3325, -1, 2928, 2889, 2910, -1, 3340, 2899, 2901, -1, 3341, 2863, 3342, -1, 3341, 2891, 2863, -1, 1725, 3326, 1726, -1, 1755, 3326, 1725, -1, 3343, 1679, 1678, -1, 2906, 3318, 3336, -1, 2906, 2909, 3344, -1, 2906, 3344, 3318, -1, 1761, 1692, 1654, -1, 1761, 1760, 1692, -1, 3345, 2968, 3333, -1, 3345, 3333, 3332, -1, 1752, 3331, 1722, -1, 3346, 3345, 3332, -1, 1742, 1734, 1740, -1, 3347, 3338, 3348, -1, 3347, 3337, 3338, -1, 3349, 3335, 3339, -1, 1735, 1734, 1742, -1, 2915, 3349, 3339, -1, 3350, 3336, 3329, -1, 3350, 3329, 3351, -1, 3352, 1679, 3343, -1, 1765, 1729, 1728, -1, 1765, 1728, 1749, -1, 3353, 3341, 3342, -1, 3353, 3342, 3354, -1, 1746, 1679, 3352, -1, 1746, 1750, 3355, -1, 1746, 3355, 1679, -1, 3356, 3345, 3346, -1, 3357, 1718, 1704, -1, 1738, 1811, 1736, -1, 3358, 3347, 3348, -1, 3358, 3348, 1718, -1, 3359, 3356, 3346, -1, 2965, 3349, 2915, -1, 3360, 3351, 3361, -1, 3360, 3350, 3351, -1, 3362, 3343, 3363, -1, 3362, 3352, 3343, -1, 3364, 2915, 2903, -1, 3364, 2965, 2915, -1, 2973, 3354, 2948, -1, 2973, 3353, 3354, -1, 2969, 2968, 3345, -1, 3365, 2942, 2930, -1, 3366, 3367, 3368, -1, 3366, 3368, 7, -1, 3369, 3356, 3359, -1, 2957, 2946, 2941, -1, 1840, 3370, 3371, -1, 1840, 3372, 3370, -1, 3373, 3369, 3359, -1, 1818, 1776, 1775, -1, 2947, 2946, 2957, -1, 3374, 3363, 3375, -1, 3374, 3362, 3363, -1, 2984, 3361, 2967, -1, 2984, 3360, 3361, -1, 3376, 1840, 3371, -1, 3377, 2942, 3365, -1, 3378, 3358, 1718, -1, 3378, 1718, 3357, -1, 3379, 2965, 3364, -1, 3380, 3377, 3365, -1, 1812, 1811, 1738, -1, 3381, 3382, 3383, -1, 3384, 3373, 3367, -1, 3384, 3367, 3366, -1, 3385, 3369, 3373, -1, 3386, 1795, 1778, -1, 3387, 3388, 2976, -1, 1817, 1776, 1818, -1, 3389, 3358, 3378, -1, 3389, 1792, 3358, -1, 2961, 2965, 3379, -1, 3390, 3377, 3380, -1, 1793, 1792, 3389, -1, 1836, 3375, 1810, -1, 1836, 3374, 3375, -1, 2975, 3387, 2976, -1, 3391, 3381, 3383, -1, 2989, 3390, 3380, -1, 3392, 3383, 1796, -1, 3392, 1796, 1815, -1, 3392, 3391, 3383, -1, 40, 1795, 3386, -1, 20, 3385, 3373, -1, 20, 3373, 3384, -1, 52, 1789, 50, -1, 19, 3385, 20, -1, 41, 40, 3386, -1, 25, 24, 2959, -1, 3393, 3391, 3392, -1, 66, 1820, 1781, -1, 66, 1781, 67, -1, 3009, 2972, 2949, -1, 3009, 3008, 2972, -1, 3006, 3390, 2989, -1, 1841, 1840, 3376, -1, 12, 11, 2998, -1, 3394, 3395, 3396, -1, 3397, 3398, 448, -1, 3399, 3394, 3396, -1, 3400, 3398, 3397, -1, 3401, 3399, 3400, -1, 3402, 3396, 3398, -1, 3402, 3399, 3396, -1, 3402, 3398, 3400, -1, 3402, 3400, 3399, -1, 3403, 3404, 3405, -1, 3403, 3406, 3404, -1, 22, 3407, 13, -1, 30, 3407, 22, -1, 3408, 3405, 17, -1, 3408, 17, 13, -1, 3408, 3407, 3403, -1, 3408, 3403, 3405, -1, 3408, 13, 3407, -1, 3409, 3410, 3411, -1, 937, 3412, 712, -1, 3413, 3409, 3411, -1, 1018, 3412, 937, -1, 1082, 3413, 1018, -1, 3414, 3411, 3412, -1, 3414, 3413, 3411, -1, 3414, 3412, 1018, -1, 3414, 1018, 3413, -1, 3415, 3416, 3417, -1, 3418, 3419, 3420, -1, 3420, 3419, 3421, -1, 3422, 3423, 3424, -1, 3416, 3423, 3422, -1, 3419, 3425, 3421, -1, 3426, 3427, 3428, -1, 3421, 3425, 3429, -1, 3424, 3430, 3431, -1, 3423, 3430, 3424, -1, 3425, 3432, 3429, -1, 3427, 3433, 3428, -1, 3429, 3432, 3434, -1, 3428, 3433, 3435, -1, 3432, 3436, 3434, -1, 3431, 3437, 3438, -1, 3430, 3437, 3431, -1, 3433, 3439, 3435, -1, 3435, 3439, 3440, -1, 3438, 3441, 3442, -1, 3437, 3441, 3438, -1, 3439, 3443, 3440, -1, 3440, 3443, 3444, -1, 3442, 3445, 3446, -1, 3441, 3445, 3442, -1, 3443, 3447, 3444, -1, 3444, 3447, 3448, -1, 3445, 3449, 3446, -1, 3446, 3449, 3450, -1, 3447, 3451, 3448, -1, 3448, 3451, 3452, -1, 3449, 3453, 3450, -1, 3450, 3453, 3454, -1, 3451, 3455, 3452, -1, 3452, 3455, 3456, -1, 3453, 3457, 3454, -1, 3454, 3457, 3458, -1, 3455, 3459, 3456, -1, 3456, 3459, 3460, -1, 3457, 3461, 3458, -1, 3458, 3461, 3462, -1, 3459, 3463, 3460, -1, 3460, 3463, 3464, -1, 3461, 3465, 3462, -1, 3462, 3465, 3466, -1, 3463, 3467, 3464, -1, 3464, 3467, 3468, -1, 3465, 3469, 3466, -1, 3466, 3469, 3470, -1, 3467, 3471, 3468, -1, 3468, 3471, 3472, -1, 3469, 3473, 3470, -1, 3470, 3473, 3474, -1, 3471, 3475, 3472, -1, 3472, 3475, 3476, -1, 3473, 3477, 3474, -1, 3474, 3477, 3478, -1, 3475, 3479, 3476, -1, 3476, 3479, 3480, -1, 3477, 3481, 3478, -1, 3478, 3481, 3482, -1, 3479, 3483, 3480, -1, 3480, 3483, 3484, -1, 3481, 3485, 3482, -1, 3482, 3485, 3486, -1, 3483, 3487, 3484, -1, 3484, 3487, 3488, -1, 3485, 3489, 3486, -1, 3486, 3489, 3490, -1, 3487, 3491, 3488, -1, 3488, 3491, 3492, -1, 3489, 3493, 3490, -1, 3490, 3493, 3494, -1, 3491, 3495, 3492, -1, 3492, 3495, 3496, -1, 3493, 3497, 3494, -1, 3494, 3497, 3498, -1, 3495, 3499, 3496, -1, 3496, 3499, 3500, -1, 3497, 3501, 3498, -1, 3498, 3501, 3502, -1, 3500, 3503, 3504, -1, 3499, 3503, 3500, -1, 3501, 3505, 3502, -1, 3502, 3505, 3506, -1, 3504, 3507, 3508, -1, 3503, 3507, 3504, -1, 3505, 3509, 3506, -1, 3506, 3509, 3510, -1, 3508, 3415, 3417, -1, 3507, 3415, 3508, -1, 3509, 3418, 3510, -1, 3510, 3418, 3420, -1, 3417, 3416, 3422, -1, 3511, 3512, 3513, -1, 3514, 3515, 3516, -1, 3517, 3518, 3519, -1, 3520, 3521, 3522, -1, 3520, 3523, 3521, -1, 3517, 3519, 3524, -1, 3525, 3526, 3523, -1, 3525, 3527, 3526, -1, 3528, 3529, 3530, -1, 3531, 3532, 3533, -1, 3528, 3530, 3534, -1, 3531, 3533, 3535, -1, 3531, 3535, 3536, -1, 3537, 3515, 3514, -1, 3538, 3522, 3512, -1, 3537, 3539, 3515, -1, 3538, 3512, 3511, -1, 3540, 3523, 3520, -1, 3540, 3525, 3523, -1, 3541, 3514, 3542, -1, 3543, 3536, 3527, -1, 3543, 3527, 3525, -1, 3544, 3545, 3546, -1, 3544, 3547, 3518, -1, 3544, 3518, 3517, -1, 3544, 3546, 3547, -1, 3548, 3549, 3550, -1, 3551, 3529, 3528, -1, 3548, 3550, 3552, -1, 3551, 3524, 3529, -1, 3553, 3539, 3537, -1, 3554, 3522, 3538, -1, 3554, 3520, 3522, -1, 3553, 3534, 3539, -1, 3555, 3543, 3525, -1, 3555, 3525, 3540, -1, 3556, 3514, 3541, -1, 3557, 3558, 3532, -1, 3557, 3536, 3543, -1, 3557, 3531, 3536, -1, 3556, 3537, 3514, -1, 3557, 3543, 3555, -1, 3559, 3541, 3542, -1, 3557, 3532, 3531, -1, 3559, 3542, 3560, -1, 3561, 3549, 3548, -1, 3562, 3524, 3551, -1, 3561, 3511, 3549, -1, 3563, 3540, 3520, -1, 3562, 3517, 3524, -1, 3563, 3520, 3554, -1, 3564, 3534, 3553, -1, 3564, 3528, 3534, -1, 3565, 3558, 3557, -1, 3565, 3557, 3555, -1, 3566, 3553, 3537, -1, 3567, 3538, 3511, -1, 3566, 3537, 3556, -1, 3567, 3511, 3561, -1, 3568, 3556, 3541, -1, 3569, 3552, 3570, -1, 3569, 3548, 3552, -1, 3568, 3541, 3559, -1, 3571, 3544, 3517, -1, 3571, 3572, 3545, -1, 3573, 3555, 3540, -1, 3571, 3545, 3544, -1, 3573, 3540, 3563, -1, 3571, 3517, 3562, -1, 3574, 3559, 3560, -1, 3575, 3538, 3567, -1, 3575, 3554, 3538, -1, 3576, 3551, 3528, -1, 3576, 3528, 3564, -1, 3577, 3564, 3553, -1, 3577, 3553, 3566, -1, 3578, 3548, 3569, -1, 3578, 3561, 3548, -1, 3579, 3580, 3558, -1, 3581, 3566, 3556, -1, 3579, 3555, 3573, -1, 3581, 3556, 3568, -1, 3579, 3558, 3565, -1, 3579, 3565, 3555, -1, 3582, 3563, 3554, -1, 3583, 3560, 3584, -1, 3583, 3574, 3560, -1, 3582, 3554, 3575, -1, 3585, 3559, 3574, -1, 3585, 3568, 3559, -1, 3586, 3567, 3561, -1, 3586, 3561, 3578, -1, 3587, 3562, 3551, -1, 3588, 3569, 3570, -1, 3587, 3551, 3576, -1, 3588, 3570, 3589, -1, 3590, 3576, 3564, -1, 3590, 3564, 3577, -1, 3591, 3577, 3566, -1, 3591, 3566, 3581, -1, 3592, 3575, 3567, -1, 3592, 3567, 3586, -1, 3593, 3574, 3583, -1, 3593, 3585, 3574, -1, 3594, 3588, 3589, -1, 3595, 3568, 3585, -1, 3595, 3581, 3568, -1, 3596, 3578, 3569, -1, 3596, 3569, 3588, -1, 3597, 3571, 3562, -1, 3597, 3572, 3571, -1, 3597, 3562, 3587, -1, 3597, 3598, 3572, -1, 3599, 3587, 3576, -1, 3600, 3575, 3592, -1, 3600, 3582, 3575, -1, 3599, 3576, 3590, -1, 3601, 3590, 3577, -1, 3602, 3596, 3588, -1, 3602, 3588, 3594, -1, 3601, 3577, 3591, -1, 3603, 3578, 3596, -1, 3604, 3583, 3584, -1, 3605, 3585, 3593, -1, 3603, 3586, 3578, -1, 3605, 3595, 3585, -1, 3606, 3594, 3589, -1, 3606, 3589, 3607, -1, 3608, 3591, 3581, -1, 3608, 3581, 3595, -1, 3609, 3582, 3600, -1, 3609, 3610, 3582, -1, 3611, 3597, 3587, -1, 3611, 3587, 3599, -1, 3611, 3612, 3598, -1, 3611, 3598, 3597, -1, 3613, 3603, 3596, -1, 3613, 3596, 3602, -1, 3614, 3599, 3590, -1, 3614, 3590, 3601, -1, 3615, 3586, 3603, -1, 3616, 3593, 3583, -1, 3615, 3592, 3586, -1, 3617, 3594, 3606, -1, 3616, 3583, 3604, -1, 3618, 3608, 3595, -1, 3618, 3595, 3605, -1, 3617, 3602, 3594, -1, 3619, 3606, 3607, -1, 3620, 3601, 3591, -1, 3620, 3591, 3608, -1, 3621, 3622, 3623, -1, 3621, 3624, 3610, -1, 3621, 3610, 3609, -1, 3625, 3611, 3599, -1, 3621, 3623, 3624, -1, 3625, 3599, 3614, -1, 3625, 3612, 3611, -1, 3626, 3603, 3613, -1, 3626, 3615, 3603, -1, 3627, 3605, 3593, -1, 3627, 3593, 3616, -1, 3628, 3620, 3608, -1, 3629, 3592, 3615, -1, 3629, 3600, 3592, -1, 3628, 3608, 3618, -1, 3630, 3602, 3617, -1, 3631, 3601, 3620, -1, 3630, 3613, 3602, -1, 3631, 3614, 3601, -1, 3632, 3619, 3607, -1, 3632, 3607, 3633, -1, 3634, 3606, 3619, -1, 3635, 3605, 3627, -1, 3634, 3617, 3606, -1, 3635, 3618, 3605, -1, 3636, 3620, 3628, -1, 3636, 3631, 3620, -1, 3637, 3615, 3626, -1, 3638, 3612, 3625, -1, 3637, 3629, 3615, -1, 3638, 3614, 3631, -1, 3638, 3631, 3636, -1, 3638, 3639, 3612, -1, 3640, 3609, 3600, -1, 3638, 3625, 3614, -1, 3640, 3600, 3629, -1, 3641, 3626, 3613, -1, 3641, 3613, 3630, -1, 3642, 3618, 3635, -1, 3643, 3619, 3632, -1, 3643, 3634, 3619, -1, 3642, 3628, 3618, -1, 3644, 3639, 3638, -1, 3644, 3638, 3636, -1, 3645, 3630, 3617, -1, 3645, 3617, 3634, -1, 3646, 3647, 3648, -1, 3649, 3629, 3637, -1, 3649, 3640, 3629, -1, 3646, 3650, 3647, -1, 3651, 3652, 3622, -1, 3651, 3609, 3640, -1, 3653, 3636, 3628, -1, 3651, 3621, 3609, -1, 3653, 3628, 3642, -1, 3651, 3622, 3621, -1, 3654, 3626, 3641, -1, 3654, 3637, 3626, -1, 3655, 3632, 3633, -1, 3656, 3657, 3650, -1, 3658, 3634, 3643, -1, 3656, 3650, 3646, -1, 3659, 3644, 3636, -1, 3659, 3639, 3644, -1, 3658, 3645, 3634, -1, 3659, 3636, 3653, -1, 3659, 3660, 3639, -1, 3661, 3630, 3645, -1, 3661, 3641, 3630, -1, 3662, 3663, 3652, -1, 3664, 3665, 3657, -1, 3662, 3652, 3651, -1, 3662, 3640, 3649, -1, 3662, 3651, 3640, -1, 3664, 3657, 3656, -1, 3666, 3649, 3637, -1, 3666, 3637, 3654, -1, 3667, 3648, 3668, -1, 3667, 3646, 3648, -1, 3669, 3632, 3655, -1, 3669, 3643, 3632, -1, 3670, 3645, 3658, -1, 3671, 3665, 3664, -1, 3670, 3661, 3645, -1, 3671, 3672, 3665, -1, 3673, 3654, 3641, -1, 3673, 3641, 3661, -1, 3674, 3667, 3668, -1, 3675, 3663, 3662, -1, 3675, 3662, 3649, -1, 3676, 3656, 3646, -1, 3675, 3649, 3666, -1, 3677, 3658, 3643, -1, 3676, 3646, 3667, -1, 3677, 3643, 3669, -1, 3678, 3673, 3661, -1, 3679, 3680, 3672, -1, 3679, 3672, 3671, -1, 3678, 3661, 3670, -1, 3681, 3666, 3654, -1, 3681, 3654, 3673, -1, 3682, 3667, 3674, -1, 3682, 3676, 3667, -1, 3683, 3664, 3656, -1, 3684, 3670, 3658, -1, 3684, 3658, 3677, -1, 3683, 3656, 3676, -1, 3685, 3681, 3673, -1, 3686, 3668, 3687, -1, 3685, 3673, 3678, -1, 3688, 3663, 3675, -1, 3688, 3689, 3663, -1, 3686, 3674, 3668, -1, 3688, 3666, 3681, -1, 3688, 3675, 3666, -1, 3690, 3691, 3680, -1, 3692, 3678, 3670, -1, 3690, 3680, 3679, -1, 3692, 3670, 3684, -1, 3693, 3683, 3676, -1, 3693, 3676, 3682, -1, 3694, 3689, 3688, -1, 3694, 3681, 3685, -1, 3694, 3688, 3681, -1, 3695, 3671, 3664, -1, 3696, 3678, 3692, -1, 3695, 3664, 3683, -1, 3696, 3685, 3678, -1, 3697, 3698, 3689, -1, 3697, 3689, 3694, -1, 3699, 3682, 3674, -1, 3697, 3694, 3685, -1, 3697, 3685, 3696, -1, 3699, 3674, 3686, -1, 3700, 3686, 3687, -1, 3701, 3702, 3691, -1, 3701, 3703, 3704, -1, 3701, 3704, 3702, -1, 3705, 3706, 3707, -1, 3701, 3691, 3690, -1, 3705, 3708, 3709, -1, 3705, 3707, 3710, -1, 3711, 3695, 3683, -1, 3705, 3709, 3706, -1, 3711, 3683, 3693, -1, 3712, 3679, 3671, -1, 3712, 3671, 3695, -1, 3713, 3682, 3699, -1, 3714, 3715, 3716, -1, 3714, 3717, 3715, -1, 3713, 3693, 3682, -1, 3714, 3716, 3718, -1, 3719, 3687, 3720, -1, 3719, 3700, 3687, -1, 3721, 3686, 3700, -1, 3721, 3699, 3686, -1, 3722, 3723, 3724, -1, 3722, 3724, 3725, -1, 3722, 3726, 3727, -1, 3722, 3727, 3728, -1, 3729, 3712, 3695, -1, 3722, 3728, 3723, -1, 3722, 3725, 3726, -1, 3729, 3695, 3711, -1, 3730, 3610, 3624, -1, 3731, 3679, 3712, -1, 3730, 3579, 3573, -1, 3731, 3690, 3679, -1, 3732, 3711, 3693, -1, 3732, 3693, 3713, -1, 3733, 3696, 3734, -1, 3735, 3721, 3700, -1, 3733, 3697, 3696, -1, 3733, 3734, 3736, -1, 3737, 3738, 3739, -1, 3737, 3707, 3706, -1, 3735, 3700, 3719, -1, 3740, 3713, 3699, -1, 3737, 3706, 3738, -1, 3741, 3742, 3710, -1, 3740, 3699, 3721, -1, 3741, 3710, 3707, -1, 3741, 3707, 3737, -1, 3743, 3712, 3729, -1, 3743, 3731, 3712, -1, 3741, 3744, 3742, -1, 3745, 3705, 3710, -1, 3745, 3708, 3705, -1, 3746, 3701, 3690, -1, 3745, 3710, 3747, -1, 3746, 3690, 3731, -1, 3745, 3748, 3708, -1, 3745, 3747, 3748, -1, 3746, 3703, 3701, -1, 3746, 3749, 3703, -1, 3750, 3653, 3642, -1, 3751, 3711, 3732, -1, 3750, 3659, 3653, -1, 3750, 3752, 3659, -1, 3751, 3729, 3711, -1, 3753, 3680, 3691, -1, 3754, 3719, 3720, -1, 3753, 3752, 3750, -1, 3755, 3660, 3659, -1, 3755, 3659, 3752, -1, 3756, 3434, 3757, -1, 3758, 3721, 3735, -1, 3756, 3759, 3434, -1, 3760, 3755, 3752, -1, 3760, 3752, 3753, -1, 3758, 3740, 3721, -1, 3760, 3753, 3691, -1, 3760, 3691, 3702, -1, 3760, 3660, 3755, -1, 3760, 3704, 3660, -1, 3761, 3762, 3759, -1, 3760, 3702, 3704, -1, 3763, 3732, 3713, -1, 3764, 3765, 3766, -1, 3764, 3716, 3715, -1, 3764, 3715, 3765, -1, 3763, 3713, 3740, -1, 3761, 3759, 3756, -1, 3767, 3731, 3743, -1, 3768, 3716, 3764, -1, 3767, 3749, 3746, -1, 3769, 3770, 3762, -1, 3767, 3771, 3749, -1, 3768, 3772, 3773, -1, 3767, 3746, 3731, -1, 3768, 3773, 3718, -1, 3768, 3718, 3716, -1, 3774, 3743, 3729, -1, 3774, 3729, 3751, -1, 3775, 3776, 3717, -1, 3775, 3717, 3714, -1, 3769, 3762, 3761, -1, 3777, 3735, 3719, -1, 3778, 3757, 3779, -1, 3780, 3718, 3781, -1, 3780, 3714, 3718, -1, 3778, 3756, 3757, -1, 3780, 3781, 3782, -1, 3777, 3719, 3754, -1, 3780, 3776, 3775, -1, 3780, 3782, 3776, -1, 3780, 3775, 3714, -1, 3783, 3740, 3758, -1, 3784, 3785, 3786, -1, 3787, 3770, 3769, -1, 3783, 3763, 3740, -1, 3787, 3788, 3770, -1, 3784, 3727, 3785, -1, 3784, 3728, 3727, -1, 3789, 3732, 3763, -1, 3789, 3751, 3732, -1, 3790, 3791, 3792, -1, 3790, 3723, 3728, -1, 3790, 3792, 3723, -1, 3790, 3728, 3784, -1, 3793, 3767, 3743, -1, 3794, 3730, 3573, -1, 3793, 3743, 3774, -1, 3795, 3778, 3779, -1, 3793, 3771, 3767, -1, 3794, 3573, 3563, -1, 3796, 3794, 3563, -1, 3797, 3758, 3735, -1, 3796, 3730, 3794, -1, 3797, 3735, 3777, -1, 3796, 3563, 3582, -1, 3796, 3610, 3730, -1, 3798, 3756, 3778, -1, 3796, 3582, 3610, -1, 3798, 3761, 3756, -1, 3799, 3579, 3730, -1, 3800, 3788, 3787, -1, 3800, 3801, 3788, -1, 3799, 3580, 3579, -1, 3802, 3763, 3783, -1, 3802, 3789, 3763, -1, 3803, 3623, 3580, -1, 3803, 3580, 3799, -1, 3803, 3799, 3730, -1, 3803, 3624, 3623, -1, 3803, 3730, 3624, -1, 3804, 3793, 3774, -1, 3805, 3734, 3696, -1, 3806, 3778, 3795, -1, 3804, 3774, 3751, -1, 3805, 3692, 3684, -1, 3806, 3798, 3778, -1, 3804, 3751, 3789, -1, 3805, 3696, 3692, -1, 3807, 3734, 3805, -1, 3808, 3769, 3761, -1, 3807, 3809, 3810, -1, 3807, 3810, 3736, -1, 3808, 3761, 3798, -1, 3807, 3736, 3734, -1, 3766, 3758, 3797, -1, 3811, 3698, 3697, -1, 3766, 3783, 3758, -1, 3812, 3779, 3813, -1, 3811, 3697, 3733, -1, 3814, 3815, 3698, -1, 3812, 3795, 3779, -1, 3814, 3811, 3733, -1, 3814, 3698, 3811, -1, 3816, 3789, 3802, -1, 3814, 3736, 3817, -1, 3818, 3819, 3801, -1, 3814, 3817, 3815, -1, 3816, 3804, 3789, -1, 3814, 3733, 3736, -1, 3820, 3739, 3821, -1, 3822, 3793, 3804, -1, 3818, 3801, 3800, -1, 3822, 3771, 3793, -1, 3820, 3737, 3739, -1, 3823, 3798, 3806, -1, 3822, 3824, 3771, -1, 3823, 3808, 3798, -1, 3825, 3737, 3820, -1, 3826, 3769, 3808, -1, 3825, 3820, 3827, -1, 3825, 3741, 3737, -1, 3825, 3827, 3741, -1, 3826, 3787, 3769, -1, 3765, 3802, 3783, -1, 3765, 3783, 3766, -1, 3828, 3741, 3827, -1, 3829, 3741, 3828, -1, 3830, 3822, 3804, -1, 3829, 3744, 3741, -1, 3831, 3795, 3812, -1, 3831, 3806, 3795, -1, 3830, 3804, 3816, -1, 3829, 3832, 3744, -1, 3830, 3824, 3822, -1, 3833, 3642, 3635, -1, 3833, 3750, 3642, -1, 3834, 3812, 3813, -1, 3835, 3836, 3819, -1, 3835, 3837, 3836, -1, 3835, 3838, 3837, -1, 3835, 3819, 3818, -1, 3715, 3816, 3802, -1, 3839, 3808, 3823, -1, 3715, 3802, 3765, -1, 3840, 3750, 3833, -1, 3840, 3833, 3841, -1, 3839, 3826, 3808, -1, 3840, 3841, 3753, -1, 3840, 3753, 3750, -1, 3842, 3843, 3844, -1, 3845, 3787, 3826, -1, 3842, 3846, 3843, -1, 3847, 3753, 3841, -1, 3845, 3800, 3787, -1, 3848, 3672, 3680, -1, 3849, 3823, 3806, -1, 3848, 3680, 3753, -1, 3848, 3753, 3847, -1, 3849, 3806, 3831, -1, 3850, 3764, 3766, -1, 3850, 3766, 3797, -1, 3851, 3813, 3852, -1, 3717, 3824, 3830, -1, 3717, 3776, 3824, -1, 3851, 3834, 3813, -1, 3717, 3816, 3715, -1, 3717, 3830, 3816, -1, 3853, 3831, 3812, -1, 3854, 3846, 3842, -1, 3855, 3764, 3850, -1, 3855, 3850, 3856, -1, 3855, 3856, 3768, -1, 3853, 3812, 3834, -1, 3854, 3857, 3846, -1, 3855, 3768, 3764, -1, 3858, 3845, 3826, -1, 3859, 3768, 3856, -1, 3858, 3826, 3839, -1, 3860, 3861, 3772, -1, 3862, 3818, 3800, -1, 3860, 3772, 3768, -1, 3860, 3768, 3859, -1, 3863, 3857, 3854, -1, 3863, 3861, 3857, -1, 3864, 3784, 3786, -1, 3864, 3786, 3865, -1, 3862, 3800, 3845, -1, 3866, 3839, 3823, -1, 3866, 3823, 3849, -1, 3867, 3844, 3868, -1, 3869, 3853, 3834, -1, 3869, 3834, 3851, -1, 3867, 3842, 3844, -1, 3870, 3784, 3864, -1, 3870, 3790, 3784, -1, 3870, 3871, 3790, -1, 3870, 3864, 3871, -1, 3872, 3849, 3831, -1, 3873, 3790, 3871, -1, 3872, 3831, 3853, -1, 3874, 3772, 3861, -1, 3875, 3876, 3791, -1, 3874, 3861, 3863, -1, 3877, 3862, 3845, -1, 3875, 3790, 3873, -1, 3875, 3791, 3790, -1, 3877, 3845, 3858, -1, 3878, 3684, 3677, -1, 3878, 3805, 3684, -1, 3879, 3835, 3818, -1, 3879, 3880, 3838, -1, 3881, 3867, 3868, -1, 3879, 3838, 3835, -1, 3879, 3818, 3862, -1, 3882, 3854, 3842, -1, 3883, 3839, 3866, -1, 3882, 3842, 3867, -1, 3884, 3805, 3878, -1, 3883, 3858, 3839, -1, 3885, 3807, 3805, -1, 3886, 3851, 3852, -1, 3885, 3884, 3887, -1, 3885, 3805, 3884, -1, 3888, 3807, 3885, -1, 3888, 3809, 3807, -1, 3889, 3773, 3772, -1, 3888, 3890, 3809, -1, 3888, 3885, 3887, -1, 3889, 3772, 3874, -1, 3891, 3872, 3853, -1, 3892, 3821, 3893, -1, 3891, 3853, 3869, -1, 3892, 3820, 3821, -1, 3894, 3866, 3849, -1, 3892, 3827, 3820, -1, 3895, 3882, 3867, -1, 3892, 3828, 3827, -1, 3895, 3867, 3881, -1, 3894, 3849, 3872, -1, 3896, 3879, 3862, -1, 3897, 3829, 3828, -1, 3897, 3832, 3829, -1, 3896, 3862, 3877, -1, 3898, 3863, 3854, -1, 3897, 3899, 3832, -1, 3896, 3880, 3879, -1, 3897, 3828, 3892, -1, 3898, 3854, 3882, -1, 3896, 3900, 3880, -1, 3901, 3635, 3627, -1, 3902, 3877, 3858, -1, 3901, 3841, 3833, -1, 3903, 3868, 3904, -1, 3902, 3858, 3883, -1, 3901, 3833, 3635, -1, 3901, 3847, 3841, -1, 3905, 3847, 3901, -1, 3893, 3869, 3851, -1, 3903, 3881, 3868, -1, 3905, 3672, 3848, -1, 3893, 3851, 3886, -1, 3905, 3665, 3672, -1, 3906, 3718, 3773, -1, 3905, 3848, 3847, -1, 3906, 3773, 3889, -1, 3907, 3856, 3850, -1, 3908, 3882, 3895, -1, 3907, 3850, 3797, -1, 3909, 3894, 3872, -1, 3907, 3859, 3856, -1, 3907, 3797, 3777, -1, 3909, 3872, 3891, -1, 3910, 3866, 3894, -1, 3911, 3857, 3861, -1, 3910, 3883, 3866, -1, 3908, 3898, 3882, -1, 3911, 3859, 3907, -1, 3912, 3874, 3863, -1, 3911, 3860, 3859, -1, 3911, 3861, 3860, -1, 3912, 3863, 3898, -1, 3913, 3896, 3877, -1, 3913, 3900, 3896, -1, 3914, 3871, 3864, -1, 3914, 3864, 3865, -1, 3913, 3877, 3902, -1, 3914, 3865, 3915, -1, 3821, 3891, 3869, -1, 3821, 3869, 3893, -1, 3916, 3895, 3881, -1, 3914, 3873, 3871, -1, 3916, 3881, 3903, -1, 3917, 3873, 3914, -1, 3917, 3918, 3876, -1, 3917, 3876, 3875, -1, 3917, 3875, 3873, -1, 3919, 3677, 3669, -1, 3920, 3903, 3904, -1, 3919, 3878, 3677, -1, 3921, 3894, 3909, -1, 3919, 3884, 3878, -1, 3921, 3910, 3894, -1, 3922, 3781, 3718, -1, 3923, 3888, 3887, -1, 3922, 3782, 3781, -1, 3923, 3884, 3919, -1, 3924, 3902, 3883, -1, 3922, 3718, 3906, -1, 3922, 3925, 3782, -1, 3923, 3926, 3890, -1, 3924, 3883, 3910, -1, 3927, 3912, 3898, -1, 3927, 3898, 3908, -1, 3923, 3887, 3884, -1, 3923, 3890, 3888, -1, 3928, 3893, 3886, -1, 3928, 3892, 3893, -1, 3929, 3889, 3874, -1, 3929, 3874, 3912, -1, 3930, 3892, 3928, -1, 3739, 3891, 3821, -1, 3931, 3908, 3895, -1, 3739, 3909, 3891, -1, 3931, 3895, 3916, -1, 3932, 3897, 3892, -1, 3933, 3910, 3921, -1, 3932, 3892, 3930, -1, 3933, 3924, 3910, -1, 3932, 3934, 3899, -1, 3932, 3899, 3897, -1, 3935, 3903, 3920, -1, 3936, 3900, 3913, -1, 3935, 3916, 3903, -1, 3936, 3902, 3924, -1, 3937, 3627, 3616, -1, 3936, 3938, 3900, -1, 3936, 3913, 3902, -1, 3937, 3901, 3627, -1, 3939, 3904, 3940, -1, 3939, 3920, 3904, -1, 3941, 3929, 3912, -1, 3942, 3901, 3937, -1, 3941, 3912, 3927, -1, 3943, 3665, 3905, -1, 3738, 3909, 3739, -1, 3943, 3657, 3665, -1, 3738, 3921, 3909, -1, 3943, 3905, 3901, -1, 3943, 3901, 3942, -1, 3944, 3906, 3889, -1, 3944, 3889, 3929, -1, 3945, 3777, 3754, -1, 3946, 3938, 3936, -1, 3945, 3907, 3777, -1, 3946, 3924, 3933, -1, 3946, 3936, 3924, -1, 3947, 3927, 3908, -1, 3947, 3908, 3931, -1, 3948, 3907, 3945, -1, 3949, 3911, 3907, -1, 3949, 3907, 3948, -1, 3950, 3931, 3916, -1, 3950, 3916, 3935, -1, 3949, 3857, 3911, -1, 3949, 3846, 3857, -1, 3951, 3915, 3952, -1, 3706, 3921, 3738, -1, 3706, 3933, 3921, -1, 3951, 3914, 3915, -1, 3953, 3954, 3955, -1, 3956, 3935, 3920, -1, 3956, 3920, 3939, -1, 3957, 3914, 3951, -1, 3953, 3934, 3954, -1, 3958, 3944, 3929, -1, 3958, 3929, 3941, -1, 3959, 3918, 3917, -1, 3959, 3960, 3918, -1, 3959, 3914, 3957, -1, 3959, 3917, 3914, -1, 3961, 3922, 3906, -1, 3961, 3925, 3922, -1, 3961, 3962, 3925, -1, 3961, 3906, 3944, -1, 3963, 3669, 3655, -1, 3709, 3938, 3946, -1, 3963, 3919, 3669, -1, 3709, 3708, 3938, -1, 3963, 3923, 3919, -1, 3952, 3939, 3940, -1, 3709, 3946, 3933, -1, 3709, 3933, 3706, -1, 3964, 3941, 3927, -1, 3965, 3923, 3963, -1, 3966, 3899, 3934, -1, 3967, 3926, 3923, -1, 3964, 3927, 3947, -1, 3967, 3923, 3965, -1, 3967, 3968, 3926, -1, 3966, 3934, 3953, -1, 3969, 3928, 3886, -1, 3969, 3930, 3928, -1, 3970, 3947, 3931, -1, 3970, 3931, 3950, -1, 3969, 3886, 3852, -1, 3971, 3852, 3954, -1, 3971, 3969, 3852, -1, 3972, 3950, 3935, -1, 3971, 3932, 3930, -1, 3971, 3934, 3932, -1, 3971, 3930, 3969, -1, 3973, 3832, 3899, -1, 3971, 3954, 3934, -1, 3972, 3935, 3956, -1, 3973, 3899, 3966, -1, 3974, 3944, 3958, -1, 3975, 3937, 3616, -1, 3974, 3961, 3944, -1, 3975, 3942, 3937, -1, 3974, 3962, 3961, -1, 3975, 3616, 3604, -1, 3974, 3976, 3962, -1, 3977, 3650, 3657, -1, 3977, 3657, 3943, -1, 3978, 3955, 3979, -1, 3915, 3956, 3939, -1, 3977, 3943, 3942, -1, 3915, 3939, 3952, -1, 3977, 3942, 3975, -1, 3978, 3953, 3955, -1, 3980, 3754, 3720, -1, 3980, 3945, 3754, -1, 3980, 3948, 3945, -1, 3981, 3941, 3964, -1, 3982, 3720, 3843, -1, 3982, 3843, 3846, -1, 3981, 3958, 3941, -1, 3982, 3949, 3948, -1, 3983, 3964, 3947, -1, 3982, 3846, 3949, -1, 3982, 3980, 3720, -1, 3982, 3948, 3980, -1, 3984, 3957, 3951, -1, 3983, 3947, 3970, -1, 3984, 3952, 3940, -1, 3985, 3744, 3832, -1, 3986, 3970, 3950, -1, 3984, 3951, 3952, -1, 3985, 3832, 3973, -1, 3986, 3950, 3972, -1, 3987, 3988, 3960, -1, 3987, 3940, 3988, -1, 3987, 3984, 3940, -1, 3987, 3960, 3959, -1, 3989, 3978, 3979, -1, 3987, 3959, 3957, -1, 3987, 3957, 3984, -1, 3865, 3972, 3956, -1, 3990, 3655, 3633, -1, 3990, 3633, 3426, -1, 3991, 3953, 3978, -1, 3990, 3963, 3655, -1, 3990, 3965, 3963, -1, 3865, 3956, 3915, -1, 3992, 3965, 3990, -1, 3992, 3990, 3426, -1, 3993, 3976, 3974, -1, 3992, 3426, 3968, -1, 3993, 3958, 3981, -1, 3992, 3967, 3965, -1, 3991, 3966, 3953, -1, 3992, 3968, 3967, -1, 3994, 3584, 3647, -1, 3993, 3974, 3958, -1, 3994, 3650, 3977, -1, 3994, 3975, 3604, -1, 3995, 3981, 3964, -1, 3994, 3647, 3650, -1, 3994, 3604, 3584, -1, 3994, 3977, 3975, -1, 3996, 3744, 3985, -1, 3995, 3964, 3983, -1, 3997, 3983, 3970, -1, 3997, 3970, 3986, -1, 3996, 3742, 3744, -1, 3998, 3991, 3978, -1, 3998, 3978, 3989, -1, 3999, 3973, 3966, -1, 3999, 3966, 3991, -1, 3786, 3986, 3972, -1, 3786, 3972, 3865, -1, 4000, 3979, 4001, -1, 4002, 3976, 3993, -1, 4002, 3981, 3995, -1, 4000, 3989, 3979, -1, 4002, 3993, 3981, -1, 4002, 4003, 3976, -1, 4004, 3710, 3742, -1, 4005, 3995, 3983, -1, 4005, 3983, 3997, -1, 4004, 3742, 3996, -1, 4006, 3999, 3991, -1, 4006, 3991, 3998, -1, 4007, 3985, 3973, -1, 4007, 3973, 3999, -1, 3785, 3986, 3786, -1, 3785, 3997, 3986, -1, 4008, 3995, 4005, -1, 4009, 3998, 3989, -1, 4009, 3989, 4000, -1, 4008, 4002, 3995, -1, 4008, 4003, 4002, -1, 4010, 4000, 4001, -1, 4011, 3710, 4004, -1, 3727, 4005, 3997, -1, 4011, 3747, 3710, -1, 4011, 4012, 3748, -1, 3727, 3997, 3785, -1, 4011, 3748, 3747, -1, 4013, 3999, 4006, -1, 4013, 4007, 3999, -1, 4014, 3960, 3988, -1, 4014, 3988, 4015, -1, 4016, 3985, 4007, -1, 4016, 3996, 3985, -1, 4017, 4006, 3998, -1, 4017, 3998, 4009, -1, 3726, 4005, 3727, -1, 3726, 4008, 4005, -1, 3726, 4003, 4008, -1, 3726, 3725, 4003, -1, 4018, 4009, 4000, -1, 4018, 4000, 4010, -1, 4019, 3918, 3960, -1, 4019, 3960, 4014, -1, 4020, 4001, 4021, -1, 4020, 4010, 4001, -1, 4022, 4016, 4007, -1, 4022, 4007, 4013, -1, 4023, 3876, 3918, -1, 4024, 4004, 3996, -1, 4024, 3996, 4016, -1, 4023, 3918, 4019, -1, 4025, 4013, 4006, -1, 4025, 4006, 4017, -1, 4026, 4015, 4027, -1, 4026, 4014, 4015, -1, 4028, 4017, 4009, -1, 4028, 4009, 4018, -1, 4029, 4018, 4010, -1, 4030, 3791, 3876, -1, 4029, 4010, 4020, -1, 4030, 3876, 4023, -1, 4031, 4016, 4022, -1, 4031, 4024, 4016, -1, 4032, 4026, 4027, -1, 4033, 4011, 4004, -1, 4033, 4004, 4024, -1, 4033, 4012, 4011, -1, 4033, 4034, 4012, -1, 4035, 4014, 4026, -1, 4035, 4019, 4014, -1, 4036, 4020, 4021, -1, 4037, 4022, 4013, -1, 3724, 4038, 3725, -1, 4037, 4013, 4025, -1, 4039, 3792, 3791, -1, 4040, 4025, 4017, -1, 4040, 4017, 4028, -1, 4039, 3791, 4030, -1, 4041, 4035, 4026, -1, 4041, 4026, 4032, -1, 4042, 4028, 4018, -1, 4042, 4018, 4029, -1, 4043, 4033, 4024, -1, 4043, 4044, 4034, -1, 4043, 4024, 4031, -1, 4043, 4034, 4033, -1, 4045, 4023, 4019, -1, 4045, 4019, 4035, -1, 4046, 4021, 4047, -1, 4048, 4032, 4027, -1, 4046, 4036, 4021, -1, 4048, 4027, 4049, -1, 4050, 4020, 4036, -1, 4050, 4029, 4020, -1, 4051, 3723, 3792, -1, 4051, 3792, 4039, -1, 4052, 4035, 4041, -1, 4053, 4031, 4022, -1, 4052, 4045, 4035, -1, 4053, 4022, 4037, -1, 4054, 4023, 4045, -1, 4055, 4025, 4040, -1, 4055, 4037, 4025, -1, 4054, 4030, 4023, -1, 4056, 4040, 4028, -1, 4056, 4028, 4042, -1, 4057, 4036, 4046, -1, 4058, 4032, 4048, -1, 4057, 4050, 4036, -1, 4058, 4041, 4032, -1, 4059, 4048, 4049, -1, 4060, 3724, 3723, -1, 4060, 3723, 4051, -1, 4060, 4038, 3724, -1, 4060, 4061, 4038, -1, 4062, 4042, 4029, -1, 4063, 4045, 4052, -1, 4062, 4029, 4050, -1, 4063, 4054, 4045, -1, 4064, 4044, 4043, -1, 4064, 4031, 4053, -1, 4064, 4043, 4031, -1, 4065, 4039, 4030, -1, 4066, 4053, 4037, -1, 4065, 4030, 4054, -1, 4066, 4064, 4053, -1, 4066, 4037, 4055, -1, 4067, 4052, 4041, -1, 4068, 4055, 4040, -1, 4067, 4041, 4058, -1, 4068, 4040, 4056, -1, 4069, 4050, 4057, -1, 4070, 4058, 4048, -1, 4070, 4048, 4059, -1, 4069, 4062, 4050, -1, 4071, 4049, 4072, -1, 4071, 4059, 4049, -1, 4073, 4065, 4054, -1, 4073, 4054, 4063, -1, 4074, 4046, 4047, -1, 4075, 4042, 4062, -1, 4076, 4051, 4039, -1, 4075, 4056, 4042, -1, 4077, 4044, 4064, -1, 4076, 4039, 4065, -1, 4077, 4064, 4066, -1, 4077, 4078, 4044, -1, 4079, 4063, 4052, -1, 4079, 4052, 4067, -1, 4080, 4055, 4068, -1, 4080, 4066, 4055, -1, 4081, 4058, 4070, -1, 4082, 4075, 4062, -1, 4081, 4067, 4058, -1, 4082, 4062, 4069, -1, 4083, 4046, 4074, -1, 4084, 4070, 4059, -1, 4084, 4059, 4071, -1, 4083, 4057, 4046, -1, 4085, 4065, 4073, -1, 4086, 4056, 4075, -1, 4085, 4076, 4065, -1, 4087, 4060, 4051, -1, 4086, 4068, 4056, -1, 4087, 4061, 4060, -1, 4087, 4051, 4076, -1, 4088, 4066, 4080, -1, 4088, 4077, 4066, -1, 4088, 4078, 4077, -1, 4087, 4089, 4061, -1, 4090, 4075, 4082, -1, 4091, 4071, 4072, -1, 4090, 4086, 4075, -1, 4092, 4073, 4063, -1, 4093, 4069, 4057, -1, 4092, 4063, 4079, -1, 4094, 4079, 4067, -1, 4093, 4057, 4083, -1, 4094, 4067, 4081, -1, 4095, 4080, 4068, -1, 4095, 4068, 4086, -1, 4096, 4081, 4070, -1, 4097, 4047, 4098, -1, 4097, 4074, 4047, -1, 4096, 4070, 4084, -1, 4099, 4087, 4076, -1, 4099, 4076, 4085, -1, 4099, 4089, 4087, -1, 4100, 4095, 4086, -1, 4100, 4086, 4090, -1, 4099, 4101, 4089, -1, 4102, 4072, 4103, -1, 4102, 4091, 4072, -1, 4104, 4082, 4069, -1, 4104, 4069, 4093, -1, 4105, 4071, 4091, -1, 4105, 4084, 4071, -1, 4106, 4088, 4080, -1, 4106, 4080, 4095, -1, 4106, 4078, 4088, -1, 4107, 4085, 4073, -1, 4106, 4108, 4078, -1, 4107, 4073, 4092, -1, 4109, 4074, 4097, -1, 4109, 4083, 4074, -1, 4110, 4079, 4094, -1, 4110, 4092, 4079, -1, 4111, 4106, 4095, -1, 4111, 4095, 4100, -1, 4112, 4081, 4096, -1, 4112, 4094, 4081, -1, 4111, 4108, 4106, -1, 4113, 4090, 4082, -1, 4113, 4082, 4104, -1, 4114, 4091, 4102, -1, 4114, 4105, 4091, -1, 4115, 4093, 4083, -1, 4115, 4083, 4109, -1, 4116, 4096, 4084, -1, 4117, 4098, 4118, -1, 4116, 4084, 4105, -1, 4117, 4097, 4098, -1, 4119, 4099, 4085, -1, 4119, 4085, 4107, -1, 4119, 4101, 4099, -1, 4120, 4100, 4090, -1, 4121, 4092, 4110, -1, 4120, 4090, 4113, -1, 4121, 4107, 4092, -1, 4122, 4094, 4112, -1, 4123, 4117, 4118, -1, 4122, 4110, 4094, -1, 4124, 4104, 4093, -1, 4125, 4116, 4105, -1, 4124, 4093, 4115, -1, 4125, 4105, 4114, -1, 4126, 4097, 4117, -1, 4126, 4109, 4097, -1, 4127, 4102, 4103, -1, 4128, 4096, 4116, -1, 4129, 4100, 4120, -1, 4129, 4130, 4108, -1, 4128, 4112, 4096, -1, 4129, 4111, 4100, -1, 4129, 4108, 4111, -1, 4131, 4119, 4107, -1, 4132, 4126, 4117, -1, 4131, 4101, 4119, -1, 4131, 4107, 4121, -1, 4131, 4133, 4101, -1, 4134, 4110, 4122, -1, 4132, 4117, 4123, -1, 4134, 4121, 4110, -1, 4135, 4116, 4125, -1, 4136, 4113, 4104, -1, 4135, 4128, 4116, -1, 4136, 4104, 4124, -1, 4137, 4109, 4126, -1, 4138, 4114, 4102, -1, 4137, 4115, 4109, -1, 4138, 4102, 4127, -1, 4139, 4112, 4128, -1, 4140, 4118, 4141, -1, 4139, 4122, 4112, -1, 4140, 4123, 4118, -1, 4142, 4126, 4132, -1, 4143, 4131, 4121, -1, 4143, 4133, 4131, -1, 4143, 4121, 4134, -1, 4142, 4137, 4126, -1, 4144, 4139, 4128, -1, 4145, 4113, 4136, -1, 4144, 4128, 4135, -1, 4145, 4120, 4113, -1, 4146, 4124, 4115, -1, 4147, 4125, 4114, -1, 4147, 4114, 4138, -1, 4146, 4115, 4137, -1, 4148, 4134, 4122, -1, 4149, 4132, 4123, -1, 4148, 4122, 4139, -1, 4149, 4123, 4140, -1, 4150, 4127, 4103, -1, 4150, 4103, 4151, -1, 4152, 4140, 4141, -1, 4153, 4139, 4144, -1, 4154, 4137, 4142, -1, 4154, 4146, 4137, -1, 4153, 4148, 4139, -1, 4155, 4135, 4125, -1, 4155, 4125, 4147, -1, 4156, 4120, 4145, -1, 4156, 4157, 4130, -1, 4156, 4130, 4129, -1, 4156, 4129, 4120, -1, 4158, 4133, 4143, -1, 4158, 4134, 4148, -1, 4159, 4136, 4124, -1, 4158, 4143, 4134, -1, 4159, 4124, 4146, -1, 4158, 4148, 4153, -1, 4158, 4160, 4133, -1, 4161, 4127, 4150, -1, 4162, 4142, 4132, -1, 4161, 4138, 4127, -1, 4163, 4158, 4153, -1, 4162, 4132, 4149, -1, 4163, 4160, 4158, -1, 4164, 4149, 4140, -1, 4165, 4144, 4135, -1, 4165, 4135, 4155, -1, 4164, 4140, 4152, -1, 4166, 4141, 4167, -1, 4166, 4152, 4141, -1, 4168, 4147, 4138, -1, 4169, 4146, 4154, -1, 4168, 4138, 4161, -1, 4169, 4159, 4146, -1, 4170, 4145, 4136, -1, 4170, 4136, 4159, -1, 4171, 4151, 4172, -1, 4171, 4150, 4151, -1, 4173, 4154, 4142, -1, 4174, 4153, 4144, -1, 4173, 4142, 4162, -1, 4174, 4144, 4165, -1, 4175, 4162, 4149, -1, 4175, 4149, 4164, -1, 4176, 4171, 4172, -1, 4177, 4147, 4168, -1, 4177, 4155, 4147, -1, 4178, 4164, 4152, -1, 4178, 4152, 4166, -1, 4179, 4170, 4159, -1, 4179, 4159, 4169, -1, 4180, 4150, 4171, -1, 4180, 4161, 4150, -1, 4181, 4145, 4170, -1, 4181, 4157, 4156, -1, 4181, 4170, 4179, -1, 4181, 4182, 4157, -1, 4183, 4163, 4153, -1, 4183, 4160, 4163, -1, 4183, 4153, 4174, -1, 4181, 4156, 4145, -1, 4183, 4184, 4160, -1, 4185, 4166, 4167, -1, 4186, 4180, 4171, -1, 4187, 4169, 4154, -1, 4187, 4154, 4173, -1, 4186, 4171, 4176, -1, 4188, 4165, 4155, -1, 4189, 4162, 4175, -1, 4188, 4155, 4177, -1, 4189, 4173, 4162, -1, 4190, 4164, 4178, -1, 4190, 4175, 4164, -1, 4191, 4161, 4180, -1, 4191, 4168, 4161, -1, 4192, 4193, 4182, -1, 4194, 4172, 4195, -1, 4192, 4181, 4179, -1, 4192, 4182, 4181, -1, 4194, 4176, 4172, -1, 4196, 4167, 4197, -1, 4196, 4185, 4167, -1, 4198, 4180, 4186, -1, 4198, 4191, 4180, -1, 4199, 4178, 4166, -1, 4199, 4166, 4185, -1, 4200, 4174, 4165, -1, 4200, 4165, 4188, -1, 4201, 4179, 4169, -1, 4201, 4169, 4187, -1, 4202, 4168, 4191, -1, 4202, 4177, 4168, -1, 4203, 4173, 4189, -1, 4203, 4187, 4173, -1, 4204, 4176, 4194, -1, 4205, 4189, 4175, -1, 4205, 4175, 4190, -1, 4204, 4186, 4176, -1, 4206, 4194, 4195, -1, 4207, 4191, 4198, -1, 4207, 4202, 4191, -1, 4208, 4185, 4196, -1, 4208, 4199, 4185, -1, 4209, 4184, 4183, -1, 4210, 4178, 4199, -1, 4209, 4174, 4200, -1, 4210, 4190, 4178, -1, 4209, 4211, 4184, -1, 4209, 4183, 4174, -1, 4212, 4192, 4179, -1, 4213, 4188, 4177, -1, 4212, 4179, 4201, -1, 4212, 4193, 4192, -1, 4213, 4177, 4202, -1, 4214, 4198, 4186, -1, 4215, 4201, 4187, -1, 4215, 4187, 4203, -1, 4214, 4186, 4204, -1, 4216, 4203, 4189, -1, 4217, 4194, 4206, -1, 4216, 4189, 4205, -1, 4217, 4204, 4194, -1, 4218, 4196, 4197, -1, 4219, 4206, 4195, -1, 4219, 4195, 4220, -1, 4221, 4202, 4207, -1, 4222, 4199, 4208, -1, 4221, 4213, 4202, -1, 4222, 4210, 4199, -1, 4223, 4190, 4210, -1, 4224, 4188, 4213, -1, 4223, 4205, 4190, -1, 4225, 4193, 4212, -1, 4224, 4200, 4188, -1, 4225, 4212, 4201, -1, 4225, 4201, 4215, -1, 4226, 4207, 4198, -1, 4225, 4227, 4193, -1, 4228, 4203, 4216, -1, 4226, 4198, 4214, -1, 4228, 4225, 4215, -1, 4229, 4214, 4204, -1, 4228, 4215, 4203, -1, 4229, 4204, 4217, -1, 4230, 4208, 4196, -1, 4231, 4206, 4219, -1, 4230, 4196, 4218, -1, 4231, 4217, 4206, -1, 4232, 4210, 4222, -1, 4232, 4223, 4210, -1, 4233, 4213, 4221, -1, 4234, 4216, 4205, -1, 4233, 4224, 4213, -1, 4234, 4205, 4223, -1, 4235, 4209, 4200, -1, 4235, 4211, 4209, -1, 4236, 4227, 4225, -1, 4235, 4200, 4224, -1, 4236, 4225, 4228, -1, 4235, 4237, 4211, -1, 4238, 4222, 4208, -1, 4239, 4219, 4220, -1, 4240, 4221, 4207, -1, 4238, 4208, 4230, -1, 4241, 4223, 4232, -1, 4241, 4234, 4223, -1, 4240, 4207, 4226, -1, 4242, 4214, 4229, -1, 4242, 4226, 4214, -1, 4243, 4228, 4216, -1, 4243, 4216, 4234, -1, 4244, 4229, 4217, -1, 4245, 4197, 4246, -1, 4244, 4217, 4231, -1, 4245, 4218, 4197, -1, 4247, 4248, 4237, -1, 4247, 4237, 4235, -1, 4247, 4224, 4233, -1, 4249, 4232, 4222, -1, 4247, 4235, 4224, -1, 3513, 4220, 3550, -1, 3513, 4239, 4220, -1, 4249, 4222, 4238, -1, 4250, 4234, 4241, -1, 4250, 4243, 4234, -1, 4251, 4231, 4219, -1, 4251, 4219, 4239, -1, 4252, 4228, 4243, -1, 4252, 4236, 4228, -1, 4252, 4253, 4227, -1, 4252, 4227, 4236, -1, 4254, 4233, 4221, -1, 4255, 4218, 4245, -1, 4254, 4221, 4240, -1, 4255, 4230, 4218, -1, 4254, 4247, 4233, -1, 4256, 4240, 4226, -1, 3519, 4241, 4232, -1, 4256, 4226, 4242, -1, 3519, 4232, 4249, -1, 3526, 4242, 4229, -1, 4257, 4243, 4250, -1, 3526, 4229, 4244, -1, 4257, 4252, 4243, -1, 4257, 4253, 4252, -1, 3530, 4238, 4230, -1, 3530, 4230, 4255, -1, 3512, 4239, 3513, -1, 3512, 4251, 4239, -1, 3521, 4231, 4251, -1, 3521, 4244, 4231, -1, 3515, 4246, 3516, -1, 3515, 4245, 4246, -1, 4258, 4248, 4247, -1, 4258, 4247, 4254, -1, 3518, 4250, 4241, -1, 3518, 4241, 3519, -1, 3535, 4254, 4240, -1, 3535, 4240, 4256, -1, 3529, 4249, 4238, -1, 3529, 4238, 3530, -1, 3527, 4242, 3526, -1, 3527, 4256, 4242, -1, 3549, 3513, 3550, -1, 3539, 4255, 4245, -1, 3522, 3521, 4251, -1, 3539, 4245, 3515, -1, 3547, 4257, 4250, -1, 3547, 4250, 3518, -1, 3522, 4251, 3512, -1, 3547, 4253, 4257, -1, 3523, 4244, 3521, -1, 3547, 3546, 4253, -1, 3524, 3519, 4249, -1, 3523, 3526, 4244, -1, 3533, 3532, 4248, -1, 3524, 4249, 3529, -1, 3533, 4258, 4254, -1, 3533, 4248, 4258, -1, 3533, 4254, 3535, -1, 3534, 3530, 4255, -1, 3534, 4255, 3539, -1, 3536, 3535, 4256, -1, 3536, 4256, 3527, -1, 3511, 3513, 3549, -1, 3514, 3516, 3542, -1, 4259, 4260, 4261, -1, 4259, 4261, 4262, -1, 4263, 4264, 4265, -1, 4266, 4267, 4268, -1, 4263, 4269, 4264, -1, 4266, 4268, 4270, -1, 4271, 4272, 4273, -1, 4274, 4275, 4276, -1, 4271, 4277, 4272, -1, 4274, 4265, 4275, -1, 4278, 4279, 4280, -1, 4278, 4280, 4277, -1, 4281, 4282, 4283, -1, 4278, 4284, 4279, -1, 4281, 4285, 4282, -1, 4281, 4283, 4286, -1, 4281, 4287, 4285, -1, 4288, 4260, 4259, -1, 4288, 4289, 4260, -1, 4290, 4267, 4266, -1, 4291, 4269, 4263, -1, 4290, 4273, 4267, -1, 4291, 4262, 4269, -1, 4292, 4278, 4277, -1, 4293, 4263, 4265, -1, 4292, 4277, 4271, -1, 4292, 4284, 4278, -1, 4292, 4294, 4284, -1, 4293, 4265, 4274, -1, 4295, 4274, 4276, -1, 4296, 4289, 4288, -1, 4297, 4298, 4299, -1, 4296, 4286, 4289, -1, 4297, 4299, 4300, -1, 4301, 4273, 4290, -1, 4302, 4262, 4291, -1, 4301, 4271, 4273, -1, 4302, 4259, 4262, -1, 4303, 4291, 4263, -1, 4304, 4266, 4270, -1, 4303, 4263, 4293, -1, 4304, 4270, 4305, -1, 4306, 4293, 4274, -1, 4306, 4274, 4295, -1, 4307, 4298, 4297, -1, 4307, 4308, 4298, -1, 4309, 4281, 4286, -1, 4309, 4286, 4296, -1, 4309, 4287, 4281, -1, 4310, 4292, 4271, -1, 4309, 4311, 4287, -1, 4310, 4271, 4301, -1, 4310, 4294, 4292, -1, 4312, 4276, 4313, -1, 4314, 4290, 4266, -1, 4312, 4295, 4276, -1, 4314, 4266, 4304, -1, 4315, 4288, 4259, -1, 4316, 4308, 4307, -1, 4315, 4259, 4302, -1, 4317, 4302, 4291, -1, 4317, 4291, 4303, -1, 4316, 4305, 4308, -1, 4318, 4300, 4319, -1, 4318, 4297, 4300, -1, 4320, 4303, 4293, -1, 4320, 4293, 4306, -1, 4321, 4301, 4290, -1, 4321, 4290, 4314, -1, 4322, 4312, 4313, -1, 4323, 4306, 4295, -1, 4324, 4304, 4305, -1, 4323, 4295, 4312, -1, 4324, 4305, 4316, -1, 4325, 4296, 4288, -1, 4326, 4319, 4327, -1, 4325, 4288, 4315, -1, 4326, 4318, 4319, -1, 4328, 4302, 4317, -1, 4329, 4307, 4297, -1, 4329, 4297, 4318, -1, 4328, 4315, 4302, -1, 4330, 4317, 4303, -1, 4330, 4303, 4320, -1, 4331, 4332, 4294, -1, 4331, 4310, 4301, -1, 4331, 4294, 4310, -1, 4331, 4301, 4321, -1, 4333, 4323, 4312, -1, 4334, 4314, 4304, -1, 4333, 4312, 4322, -1, 4334, 4304, 4324, -1, 4335, 4320, 4306, -1, 4336, 4329, 4318, -1, 4335, 4306, 4323, -1, 4336, 4318, 4326, -1, 4337, 4309, 4296, -1, 4337, 4311, 4309, -1, 4337, 4296, 4325, -1, 4337, 4338, 4311, -1, 4339, 4316, 4307, -1, 4340, 4325, 4315, -1, 4339, 4307, 4329, -1, 4340, 4315, 4328, -1, 4341, 4326, 4327, -1, 4342, 4328, 4317, -1, 4343, 4314, 4334, -1, 4342, 4317, 4330, -1, 4343, 4321, 4314, -1, 4344, 4313, 4345, -1, 4346, 4329, 4336, -1, 4344, 4322, 4313, -1, 4346, 4339, 4329, -1, 4347, 4323, 4333, -1, 4348, 4316, 4339, -1, 4347, 4335, 4323, -1, 4348, 4324, 4316, -1, 4349, 4326, 4341, -1, 4350, 4330, 4320, -1, 4350, 4320, 4335, -1, 4351, 4337, 4325, -1, 4351, 4325, 4340, -1, 4349, 4336, 4326, -1, 4351, 4338, 4337, -1, 4352, 4341, 4327, -1, 4353, 4328, 4342, -1, 4353, 4340, 4328, -1, 4352, 4327, 4354, -1, 4355, 4321, 4343, -1, 4355, 4356, 4332, -1, 4357, 4333, 4322, -1, 4355, 4332, 4331, -1, 4355, 4331, 4321, -1, 4357, 4322, 4344, -1, 4358, 4339, 4346, -1, 4359, 4335, 4347, -1, 4358, 4348, 4339, -1, 4359, 4350, 4335, -1, 4360, 4324, 4348, -1, 4361, 4342, 4330, -1, 4360, 4334, 4324, -1, 4361, 4330, 4350, -1, 4362, 4346, 4336, -1, 4362, 4336, 4349, -1, 4363, 4351, 4340, -1, 4363, 4340, 4353, -1, 4363, 4364, 4338, -1, 4363, 4338, 4351, -1, 4365, 4352, 4354, -1, 4366, 4333, 4357, -1, 4366, 4347, 4333, -1, 4367, 4341, 4352, -1, 4368, 4350, 4359, -1, 4367, 4349, 4341, -1, 4368, 4361, 4350, -1, 4369, 4353, 4342, -1, 4370, 4360, 4348, -1, 4370, 4348, 4358, -1, 4369, 4342, 4361, -1, 4371, 4343, 4334, -1, 4371, 4334, 4360, -1, 4372, 4358, 4346, -1, 4372, 4346, 4362, -1, 4373, 4347, 4366, -1, 4373, 4359, 4347, -1, 4374, 4352, 4365, -1, 4375, 4361, 4368, -1, 4375, 4369, 4361, -1, 4374, 4367, 4352, -1, 4376, 4353, 4369, -1, 4376, 4364, 4363, -1, 4377, 4362, 4349, -1, 4376, 4363, 4353, -1, 4377, 4349, 4367, -1, 4378, 4360, 4370, -1, 4378, 4371, 4360, -1, 4379, 4368, 4359, -1, 4379, 4359, 4373, -1, 4380, 4355, 4343, -1, 4380, 4356, 4355, -1, 4380, 4343, 4371, -1, 4380, 4381, 4356, -1, 4382, 4369, 4375, -1, 4382, 4376, 4369, -1, 4382, 4364, 4376, -1, 4383, 4358, 4372, -1, 4383, 4370, 4358, -1, 4382, 4384, 4364, -1, 4385, 4365, 4354, -1, 4385, 4354, 4386, -1, 4387, 4388, 4389, -1, 4387, 4389, 4390, -1, 4391, 4367, 4374, -1, 4391, 4377, 4367, -1, 4392, 4368, 4379, -1, 4393, 4372, 4362, -1, 4393, 4362, 4377, -1, 4392, 4375, 4368, -1, 4394, 4371, 4378, -1, 4394, 4380, 4371, -1, 4394, 4381, 4380, -1, 4395, 4378, 4370, -1, 4395, 4370, 4383, -1, 4396, 4388, 4387, -1, 4396, 4397, 4388, -1, 4398, 4382, 4375, -1, 4398, 4384, 4382, -1, 4399, 4365, 4385, -1, 4398, 4375, 4392, -1, 4399, 4374, 4365, -1, 4400, 4393, 4377, -1, 4400, 4377, 4391, -1, 4401, 4402, 4397, -1, 4401, 4397, 4396, -1, 4403, 4383, 4372, -1, 4403, 4372, 4393, -1, 4404, 4390, 4405, -1, 4404, 4387, 4390, -1, 4406, 4407, 4381, -1, 4406, 4378, 4395, -1, 4406, 4394, 4378, -1, 4406, 4381, 4394, -1, 4408, 4374, 4399, -1, 4408, 4391, 4374, -1, 4409, 4410, 4402, -1, 4409, 4402, 4401, -1, 4411, 4393, 4400, -1, 4412, 4405, 4413, -1, 4411, 4403, 4393, -1, 4412, 4404, 4405, -1, 4414, 4395, 4383, -1, 4414, 4383, 4403, -1, 4415, 4387, 4404, -1, 4415, 4396, 4387, -1, 4416, 4391, 4408, -1, 4416, 4400, 4391, -1, 4417, 4414, 4403, -1, 4418, 4419, 4410, -1, 4417, 4403, 4411, -1, 4418, 4410, 4409, -1, 4420, 4395, 4414, -1, 4420, 4406, 4395, -1, 4420, 4407, 4406, -1, 4421, 4411, 4400, -1, 4421, 4400, 4416, -1, 4422, 4404, 4412, -1, 4422, 4415, 4404, -1, 4423, 4420, 4414, -1, 4424, 4401, 4396, -1, 4423, 4414, 4417, -1, 4424, 4396, 4415, -1, 4423, 4407, 4420, -1, 4423, 4425, 4407, -1, 4426, 4417, 4411, -1, 4427, 4412, 4413, -1, 4428, 4429, 4419, -1, 4426, 4411, 4421, -1, 4428, 4419, 4418, -1, 4430, 4423, 4417, -1, 4430, 4417, 4426, -1, 4430, 4425, 4423, -1, 4431, 4415, 4422, -1, 4431, 4424, 4415, -1, 4432, 4433, 4434, -1, 4432, 4435, 4433, -1, 4436, 4401, 4424, -1, 4436, 4409, 4401, -1, 4437, 4432, 4438, -1, 4437, 4435, 4432, -1, 4439, 4422, 4412, -1, 4439, 4412, 4427, -1, 4440, 4413, 4441, -1, 4440, 4427, 4413, -1, 4442, 4443, 4444, -1, 4445, 4446, 4429, -1, 4445, 4447, 4446, -1, 4445, 4429, 4428, -1, 4445, 4448, 4447, -1, 4449, 4442, 4450, -1, 4449, 4443, 4442, -1, 4451, 4436, 4424, -1, 4451, 4424, 4431, -1, 4452, 4453, 4454, -1, 4452, 4455, 4453, -1, 4452, 4454, 4456, -1, 4457, 4409, 4436, -1, 4452, 4456, 4458, -1, 4457, 4418, 4409, -1, 4459, 4452, 4458, -1, 4460, 4422, 4439, -1, 4460, 4431, 4422, -1, 4459, 4455, 4452, -1, 4461, 4462, 4463, -1, 4461, 4298, 4308, -1, 4464, 4440, 4441, -1, 4465, 4439, 4427, -1, 4465, 4427, 4440, -1, 4466, 4399, 4385, -1, 4467, 4457, 4436, -1, 4467, 4436, 4451, -1, 4468, 4466, 4469, -1, 4468, 4399, 4466, -1, 4470, 4418, 4457, -1, 4471, 4434, 4472, -1, 4470, 4428, 4418, -1, 4471, 4438, 4432, -1, 4471, 4472, 4473, -1, 4471, 4473, 4438, -1, 4471, 4432, 4434, -1, 4474, 4451, 4431, -1, 4475, 4476, 4435, -1, 4474, 4431, 4460, -1, 4475, 4435, 4437, -1, 4475, 4477, 4476, -1, 4478, 4465, 4440, -1, 4478, 4440, 4464, -1, 4479, 4437, 4438, -1, 4479, 4475, 4437, -1, 4479, 4438, 4480, -1, 4479, 4480, 4481, -1, 4482, 4439, 4465, -1, 4482, 4460, 4439, -1, 4483, 4484, 4344, -1, 4483, 4344, 4345, -1, 4485, 4389, 4388, -1, 4485, 4345, 4389, -1, 4485, 4484, 4483, -1, 4486, 4470, 4457, -1, 4485, 4483, 4345, -1, 4487, 4366, 4357, -1, 4486, 4457, 4467, -1, 4488, 4445, 4428, -1, 4488, 4448, 4445, -1, 4487, 4344, 4484, -1, 4487, 4357, 4344, -1, 4488, 4428, 4470, -1, 4489, 4485, 4388, -1, 4488, 4490, 4448, -1, 4491, 4467, 4451, -1, 4489, 4397, 4402, -1, 4489, 4484, 4485, -1, 4489, 4487, 4484, -1, 4489, 4388, 4397, -1, 4491, 4451, 4474, -1, 4492, 4442, 4444, -1, 4492, 4444, 4493, -1, 4444, 4464, 4441, -1, 4444, 4441, 4493, -1, 4494, 4493, 4495, -1, 4494, 4450, 4442, -1, 4494, 4495, 4496, -1, 4497, 4465, 4478, -1, 4494, 4442, 4492, -1, 4497, 4482, 4465, -1, 4494, 4492, 4493, -1, 4494, 4496, 4450, -1, 4498, 4443, 4449, -1, 4498, 4499, 4500, -1, 4501, 4460, 4482, -1, 4498, 4500, 4443, -1, 4501, 4474, 4460, -1, 4502, 4450, 4503, -1, 4502, 4503, 4504, -1, 4505, 4470, 4486, -1, 4502, 4449, 4450, -1, 4502, 4498, 4449, -1, 4505, 4488, 4470, -1, 4506, 4507, 4455, -1, 4505, 4490, 4488, -1, 4506, 4508, 4507, -1, 4506, 4455, 4459, -1, 4509, 4467, 4491, -1, 4509, 4486, 4467, -1, 4510, 4459, 4458, -1, 4510, 4511, 4512, -1, 4510, 4458, 4511, -1, 4443, 4478, 4464, -1, 4443, 4464, 4444, -1, 4510, 4506, 4459, -1, 4513, 4463, 4514, -1, 4515, 4501, 4482, -1, 4513, 4461, 4463, -1, 4515, 4482, 4497, -1, 4516, 4461, 4513, -1, 4516, 4298, 4461, -1, 4516, 4514, 4299, -1, 4516, 4299, 4298, -1, 4516, 4513, 4514, -1, 4517, 4270, 4462, -1, 4518, 4491, 4474, -1, 4517, 4462, 4461, -1, 4519, 4520, 4521, -1, 4518, 4474, 4501, -1, 4519, 4522, 4520, -1, 4523, 4517, 4461, -1, 4523, 4270, 4517, -1, 4523, 4461, 4308, -1, 4524, 4505, 4486, -1, 4523, 4305, 4270, -1, 4523, 4308, 4305, -1, 4524, 4490, 4505, -1, 4524, 4486, 4509, -1, 4525, 4385, 4386, -1, 4526, 4527, 4522, -1, 4524, 4528, 4490, -1, 4525, 4466, 4385, -1, 4529, 4525, 4386, -1, 4500, 4497, 4478, -1, 4529, 4469, 4466, -1, 4500, 4478, 4443, -1, 4529, 4386, 4530, -1, 4529, 4530, 4531, -1, 4529, 4531, 4469, -1, 4526, 4522, 4519, -1, 4529, 4466, 4525, -1, 4532, 4518, 4501, -1, 4533, 4416, 4408, -1, 4534, 4535, 4527, -1, 4532, 4501, 4515, -1, 4533, 4399, 4468, -1, 4533, 4408, 4399, -1, 4536, 4509, 4491, -1, 4537, 4533, 4468, -1, 4534, 4527, 4526, -1, 4536, 4491, 4518, -1, 4537, 4469, 4538, -1, 4539, 4521, 4540, -1, 4537, 4538, 4541, -1, 4537, 4468, 4469, -1, 4542, 4477, 4475, -1, 4539, 4519, 4521, -1, 4542, 4543, 4477, -1, 4544, 4545, 4535, -1, 4544, 4535, 4534, -1, 4499, 4515, 4497, -1, 4546, 4542, 4475, -1, 4499, 4497, 4500, -1, 4547, 4540, 4548, -1, 4549, 4546, 4475, -1, 4547, 4539, 4540, -1, 4550, 4536, 4518, -1, 4550, 4518, 4532, -1, 4549, 4475, 4479, -1, 4551, 4526, 4519, -1, 4552, 4546, 4549, -1, 4553, 4524, 4509, -1, 4553, 4528, 4524, -1, 4553, 4509, 4536, -1, 4554, 4549, 4479, -1, 4551, 4519, 4539, -1, 4554, 4552, 4549, -1, 4554, 4479, 4481, -1, 4554, 4481, 4555, -1, 4556, 4557, 4545, -1, 4558, 4373, 4366, -1, 4558, 4366, 4487, -1, 4556, 4545, 4544, -1, 4559, 4558, 4487, -1, 4560, 4532, 4515, -1, 4560, 4515, 4499, -1, 4561, 4539, 4547, -1, 4559, 4487, 4489, -1, 4561, 4551, 4539, -1, 4562, 4558, 4559, -1, 4562, 4559, 4489, -1, 4563, 4528, 4553, -1, 4564, 4526, 4551, -1, 4563, 4536, 4550, -1, 4564, 4534, 4526, -1, 4563, 4565, 4528, -1, 4563, 4553, 4536, -1, 4566, 4562, 4489, -1, 4567, 4547, 4548, -1, 4568, 4402, 4410, -1, 4568, 4566, 4489, -1, 4569, 4570, 4557, -1, 4568, 4489, 4402, -1, 4571, 4550, 4532, -1, 4572, 4560, 4499, -1, 4569, 4557, 4556, -1, 4571, 4532, 4560, -1, 4572, 4499, 4498, -1, 4573, 4551, 4561, -1, 4574, 4495, 4575, -1, 4574, 4496, 4495, -1, 4576, 4572, 4498, -1, 4573, 4564, 4551, -1, 4576, 4498, 4502, -1, 4577, 4534, 4564, -1, 4578, 4572, 4576, -1, 4577, 4544, 4534, -1, 4579, 4547, 4567, -1, 4580, 4550, 4571, -1, 4580, 4563, 4550, -1, 4581, 4576, 4502, -1, 4579, 4561, 4547, -1, 4580, 4565, 4563, -1, 4581, 4578, 4576, -1, 4582, 4548, 4583, -1, 4584, 4496, 4574, -1, 4585, 4504, 4586, -1, 4585, 4502, 4504, -1, 4582, 4567, 4548, -1, 4585, 4581, 4502, -1, 4587, 4588, 3436, -1, 4589, 4590, 4508, -1, 4587, 4570, 4569, -1, 4584, 4450, 4496, -1, 4589, 4508, 4506, -1, 4587, 4591, 4570, -1, 4587, 3436, 4591, -1, 4592, 4589, 4506, -1, 4593, 4577, 4564, -1, 4593, 4564, 4573, -1, 4594, 4503, 4450, -1, 4595, 4556, 4544, -1, 4594, 4450, 4584, -1, 4596, 4506, 4510, -1, 4595, 4544, 4577, -1, 4597, 4592, 4506, -1, 4598, 4561, 4579, -1, 4599, 4575, 4600, -1, 4597, 4506, 4596, -1, 4599, 4574, 4575, -1, 4601, 4510, 4512, -1, 4601, 4512, 4602, -1, 4598, 4573, 4561, -1, 4601, 4596, 4510, -1, 4603, 4582, 4583, -1, 4601, 4597, 4596, -1, 4604, 4421, 4416, -1, 4604, 4416, 4533, -1, 4605, 4579, 4567, -1, 4605, 4567, 4582, -1, 4606, 4504, 4503, -1, 4606, 4503, 4594, -1, 4607, 4604, 4533, -1, 4607, 4533, 4537, -1, 4608, 4577, 4593, -1, 4608, 4595, 4577, -1, 4609, 4569, 4556, -1, 4610, 4600, 4611, -1, 4610, 4599, 4600, -1, 4612, 4604, 4607, -1, 4609, 4556, 4595, -1, 4613, 4574, 4599, -1, 4614, 4607, 4537, -1, 4615, 4573, 4598, -1, 4615, 4593, 4573, -1, 4614, 4612, 4607, -1, 4616, 4614, 4537, -1, 4613, 4584, 4574, -1, 4616, 4537, 4541, -1, 4616, 4541, 4617, -1, 4618, 4582, 4603, -1, 4619, 4543, 4542, -1, 4618, 4605, 4582, -1, 4619, 4542, 4546, -1, 4619, 4620, 4543, -1, 4621, 4586, 4504, -1, 4621, 4504, 4606, -1, 4622, 4619, 4546, -1, 4623, 4598, 4579, -1, 4622, 4546, 4552, -1, 4622, 4552, 4554, -1, 4623, 4579, 4605, -1, 4624, 4599, 4610, -1, 4622, 4554, 4555, -1, 4622, 4555, 4625, -1, 4624, 4613, 4599, -1, 4626, 4379, 4373, -1, 4627, 4595, 4608, -1, 4627, 4609, 4595, -1, 4626, 4562, 4566, -1, 4628, 4629, 4588, -1, 4626, 4558, 4562, -1, 4628, 4587, 4569, -1, 4628, 4588, 4587, -1, 4630, 4584, 4613, -1, 4626, 4373, 4558, -1, 4628, 4569, 4609, -1, 4631, 4626, 4566, -1, 4632, 4593, 4615, -1, 4630, 4594, 4584, -1, 4631, 4410, 4419, -1, 4631, 4568, 4410, -1, 4631, 4566, 4568, -1, 4633, 4571, 4560, -1, 4632, 4608, 4593, -1, 4634, 4610, 4611, -1, 4433, 4583, 4434, -1, 4635, 4636, 4586, -1, 4433, 4603, 4583, -1, 4635, 4586, 4621, -1, 4633, 4572, 4578, -1, 4633, 4578, 4581, -1, 4633, 4560, 4572, -1, 4637, 4633, 4581, -1, 4637, 4586, 4636, -1, 4638, 4630, 4613, -1, 4637, 4585, 4586, -1, 4639, 4623, 4605, -1, 4638, 4613, 4624, -1, 4637, 4581, 4585, -1, 4640, 4641, 4590, -1, 4640, 4590, 4589, -1, 4639, 4605, 4618, -1, 4642, 4615, 4598, -1, 4643, 4606, 4594, -1, 4640, 4589, 4592, -1, 4643, 4594, 4630, -1, 4644, 4602, 4645, -1, 4642, 4598, 4623, -1, 4644, 4640, 4592, -1, 4644, 4592, 4597, -1, 4644, 4601, 4602, -1, 4646, 4609, 4627, -1, 4644, 4597, 4601, -1, 4646, 4628, 4609, -1, 4647, 4624, 4610, -1, 4646, 4629, 4628, -1, 4648, 4426, 4421, -1, 4647, 4610, 4634, -1, 4649, 4627, 4608, -1, 4649, 4608, 4632, -1, 4650, 4634, 4611, -1, 4648, 4421, 4604, -1, 4650, 4611, 4651, -1, 4648, 4604, 4612, -1, 4648, 4612, 4614, -1, 4652, 4616, 4617, -1, 4652, 4648, 4614, -1, 4653, 4654, 4636, -1, 4435, 4603, 4433, -1, 4653, 4655, 4654, -1, 4652, 4617, 4656, -1, 4435, 4618, 4603, -1, 4653, 4636, 4635, -1, 4652, 4614, 4616, -1, 4657, 4619, 4622, -1, 4653, 4658, 4655, -1, 4659, 4643, 4630, -1, 4657, 4620, 4619, -1, 4659, 4630, 4638, -1, 4657, 4660, 4620, -1, 4661, 4623, 4639, -1, 4661, 4642, 4623, -1, 4662, 4657, 4622, -1, 4663, 4621, 4606, -1, 4664, 4632, 4615, -1, 4663, 4606, 4643, -1, 4664, 4615, 4642, -1, 4665, 4625, 4666, -1, 4665, 4622, 4625, -1, 4667, 4646, 4627, -1, 4665, 4662, 4622, -1, 4667, 4629, 4646, -1, 4668, 4638, 4624, -1, 4669, 4379, 4626, -1, 4667, 4670, 4629, -1, 4669, 4392, 4379, -1, 4667, 4627, 4649, -1, 4668, 4624, 4647, -1, 4671, 4669, 4626, -1, 4476, 4618, 4435, -1, 4476, 4639, 4618, -1, 4672, 4634, 4650, -1, 4672, 4647, 4634, -1, 4673, 4664, 4642, -1, 4674, 4671, 4626, -1, 4674, 4626, 4631, -1, 4675, 4650, 4651, -1, 4673, 4642, 4661, -1, 4674, 4631, 4419, -1, 4674, 4419, 4429, -1, 4676, 4580, 4571, -1, 4677, 4663, 4643, -1, 4677, 4643, 4659, -1, 4678, 4649, 4632, -1, 4676, 4571, 4633, -1, 4678, 4632, 4664, -1, 4679, 4635, 4621, -1, 4679, 4621, 4663, -1, 4680, 4676, 4633, -1, 4681, 4633, 4637, -1, 4682, 4659, 4638, -1, 4681, 4636, 4654, -1, 4682, 4638, 4668, -1, 4681, 4680, 4633, -1, 4477, 4639, 4476, -1, 4681, 4637, 4636, -1, 4477, 4661, 4639, -1, 4683, 4668, 4647, -1, 4684, 4685, 4641, -1, 4686, 4664, 4673, -1, 4684, 4640, 4644, -1, 4684, 4641, 4640, -1, 4686, 4678, 4664, -1, 4683, 4647, 4672, -1, 4687, 4684, 4644, -1, 4688, 4649, 4678, -1, 4688, 4667, 4649, -1, 4689, 4645, 4690, -1, 4688, 4670, 4667, -1, 4691, 4672, 4650, -1, 4689, 4644, 4645, -1, 4689, 4687, 4644, -1, 4691, 4650, 4675, -1, 4692, 4430, 4426, -1, 4693, 4679, 4663, -1, 4693, 4663, 4677, -1, 4692, 4426, 4648, -1, 4694, 4653, 4635, -1, 4694, 4658, 4653, -1, 4543, 4673, 4661, -1, 4694, 4635, 4679, -1, 4543, 4661, 4477, -1, 4694, 4695, 4658, -1, 4696, 4692, 4648, -1, 4697, 4698, 4670, -1, 4699, 4648, 4652, -1, 4453, 4651, 4454, -1, 4699, 4652, 4656, -1, 4697, 4670, 4688, -1, 4699, 4656, 4700, -1, 4699, 4696, 4648, -1, 4697, 4678, 4686, -1, 4697, 4688, 4678, -1, 4453, 4675, 4651, -1, 4701, 4702, 4698, -1, 4701, 4657, 4662, -1, 4701, 4660, 4657, -1, 4703, 4677, 4659, -1, 4701, 4698, 4660, -1, 4703, 4659, 4682, -1, 4704, 4702, 4701, -1, 4704, 4665, 4666, -1, 4704, 4662, 4665, -1, 4704, 4701, 4662, -1, 4704, 4666, 4702, -1, 4705, 4682, 4668, -1, 4706, 4669, 4671, -1, 4706, 4392, 4669, -1, 4620, 4686, 4673, -1, 4705, 4668, 4683, -1, 4620, 4673, 4543, -1, 4706, 4398, 4392, -1, 4707, 4683, 4672, -1, 4708, 4671, 4674, -1, 4709, 4472, 4710, -1, 4708, 4674, 4429, -1, 4709, 4473, 4472, -1, 4708, 4706, 4671, -1, 4707, 4672, 4691, -1, 4708, 4429, 4446, -1, 4711, 4694, 4679, -1, 4712, 4565, 4580, -1, 4711, 4679, 4693, -1, 4711, 4695, 4694, -1, 4712, 4676, 4680, -1, 4455, 4675, 4453, -1, 4455, 4691, 4675, -1, 4712, 4580, 4676, -1, 4713, 4565, 4712, -1, 4713, 4654, 4655, -1, 4713, 4681, 4654, -1, 4660, 4698, 4697, -1, 4713, 4680, 4681, -1, 4713, 4655, 4565, -1, 4660, 4697, 4686, -1, 4713, 4712, 4680, -1, 4714, 4693, 4677, -1, 4715, 4684, 4687, -1, 4660, 4686, 4620, -1, 4714, 4677, 4703, -1, 4715, 4685, 4684, -1, 4715, 4716, 4717, -1, 4715, 4717, 4685, -1, 4718, 4438, 4473, -1, 4719, 4715, 4687, -1, 4720, 4703, 4682, -1, 4719, 4689, 4690, -1, 4720, 4682, 4705, -1, 4719, 4687, 4689, -1, 4718, 4473, 4709, -1, 4719, 4690, 4716, -1, 4719, 4716, 4715, -1, 4721, 4425, 4430, -1, 4722, 4705, 4683, -1, 4721, 4692, 4696, -1, 4721, 4430, 4692, -1, 4722, 4683, 4707, -1, 4723, 4721, 4696, -1, 4723, 4700, 3427, -1, 4723, 3427, 4425, -1, 4507, 4691, 4455, -1, 4723, 4425, 4721, -1, 4507, 4707, 4691, -1, 4723, 4699, 4700, -1, 4723, 4696, 4699, -1, 4724, 4438, 4718, -1, 4725, 4384, 4398, -1, 4724, 4480, 4438, -1, 4725, 4446, 4447, -1, 4725, 4398, 4706, -1, 4725, 4706, 4708, -1, 4725, 4708, 4446, -1, 4726, 4693, 4714, -1, 4725, 4447, 4384, -1, 4726, 4695, 4711, -1, 4727, 4710, 4728, -1, 4726, 4729, 4695, -1, 4726, 4711, 4693, -1, 4727, 4709, 4710, -1, 4730, 4714, 4703, -1, 4730, 4703, 4720, -1, 4731, 4720, 4705, -1, 4732, 4480, 4724, -1, 4731, 4705, 4722, -1, 4732, 4481, 4480, -1, 4456, 4454, 4733, -1, 4734, 4727, 4728, -1, 4734, 4728, 4735, -1, 4508, 4722, 4707, -1, 4508, 4707, 4507, -1, 4736, 4709, 4727, -1, 4736, 4718, 4709, -1, 4737, 4729, 4726, -1, 4737, 4726, 4714, -1, 4737, 4714, 4730, -1, 4738, 4720, 4731, -1, 4738, 4730, 4720, -1, 4739, 4481, 4732, -1, 4739, 4555, 4481, -1, 4590, 4731, 4722, -1, 4740, 4736, 4727, -1, 4590, 4722, 4508, -1, 4740, 4727, 4734, -1, 4741, 4724, 4718, -1, 4742, 4730, 4738, -1, 4742, 4737, 4730, -1, 4741, 4718, 4736, -1, 4742, 4717, 4729, -1, 4742, 4729, 4737, -1, 4743, 4734, 4735, -1, 4641, 4738, 4731, -1, 4744, 4555, 4739, -1, 4641, 4731, 4590, -1, 4744, 4625, 4555, -1, 4745, 4736, 4740, -1, 4746, 4733, 4747, -1, 4745, 4741, 4736, -1, 4746, 4456, 4733, -1, 4748, 4724, 4741, -1, 4748, 4732, 4724, -1, 4749, 4740, 4734, -1, 4685, 4742, 4738, -1, 4749, 4734, 4743, -1, 4685, 4738, 4641, -1, 4685, 4717, 4742, -1, 4750, 4735, 4751, -1, 4750, 4743, 4735, -1, 4752, 4458, 4456, -1, 4753, 4754, 4702, -1, 4752, 4456, 4746, -1, 4753, 4666, 4625, -1, 4753, 4702, 4666, -1, 4753, 4625, 4744, -1, 4755, 4741, 4745, -1, 4755, 4748, 4741, -1, 4756, 4739, 4732, -1, 4757, 4511, 4458, -1, 4756, 4732, 4748, -1, 4757, 4458, 4752, -1, 4758, 4747, 4759, -1, 4760, 4745, 4740, -1, 4758, 4746, 4747, -1, 4760, 4740, 4749, -1, 4761, 4749, 4743, -1, 4761, 4743, 4750, -1, 4762, 4512, 4511, -1, 4763, 4750, 4751, -1, 4762, 4511, 4757, -1, 4764, 4748, 4755, -1, 4764, 4756, 4748, -1, 4765, 4759, 4766, -1, 4767, 4739, 4756, -1, 4765, 4758, 4759, -1, 4767, 4744, 4739, -1, 4768, 4746, 4758, -1, 4769, 4745, 4760, -1, 4768, 4752, 4746, -1, 4769, 4755, 4745, -1, 4770, 4749, 4761, -1, 4770, 4760, 4749, -1, 4771, 4761, 4750, -1, 4771, 4750, 4763, -1, 4772, 4602, 4512, -1, 4772, 4512, 4762, -1, 4773, 4756, 4764, -1, 4773, 4767, 4756, -1, 4774, 4758, 4765, -1, 4775, 4776, 4754, -1, 4774, 4768, 4758, -1, 4775, 4754, 4753, -1, 4775, 4753, 4744, -1, 4777, 4752, 4768, -1, 4775, 4744, 4767, -1, 4778, 4751, 4779, -1, 4777, 4757, 4752, -1, 4778, 4763, 4751, -1, 4780, 4765, 4766, -1, 4781, 4764, 4755, -1, 4781, 4755, 4769, -1, 4782, 4645, 4602, -1, 4782, 4602, 4772, -1, 4783, 4769, 4760, -1, 4784, 4768, 4774, -1, 4783, 4760, 4770, -1, 4784, 4777, 4768, -1, 4785, 4770, 4761, -1, 4786, 4762, 4757, -1, 4785, 4761, 4771, -1, 4786, 4757, 4777, -1, 4787, 4767, 4773, -1, 4787, 4775, 4767, -1, 4788, 4774, 4765, -1, 4787, 4776, 4775, -1, 4789, 4778, 4779, -1, 4788, 4765, 4780, -1, 4790, 4780, 4766, -1, 4790, 4766, 4791, -1, 4792, 4763, 4778, -1, 4793, 4690, 4645, -1, 4792, 4771, 4763, -1, 4793, 4794, 4716, -1, 4795, 4764, 4781, -1, 4793, 4716, 4690, -1, 4793, 4645, 4782, -1, 4795, 4773, 4764, -1, 4796, 4786, 4777, -1, 4796, 4777, 4784, -1, 4797, 4781, 4769, -1, 4798, 4762, 4786, -1, 4797, 4769, 4783, -1, 4799, 4770, 4785, -1, 4798, 4772, 4762, -1, 4800, 4784, 4774, -1, 4799, 4783, 4770, -1, 4801, 4778, 4789, -1, 4800, 4774, 4788, -1, 4802, 4788, 4780, -1, 4801, 4792, 4778, -1, 4803, 4771, 4792, -1, 4802, 4780, 4790, -1, 4804, 4790, 4791, -1, 4803, 4785, 4771, -1, 4805, 4806, 4776, -1, 4805, 4773, 4795, -1, 4807, 4798, 4786, -1, 4807, 4786, 4796, -1, 4805, 4776, 4787, -1, 4805, 4787, 4773, -1, 4808, 4795, 4781, -1, 4809, 4772, 4798, -1, 4809, 4782, 4772, -1, 4808, 4781, 4797, -1, 4810, 4797, 4783, -1, 4810, 4783, 4799, -1, 4811, 4796, 4784, -1, 4811, 4784, 4800, -1, 4812, 4800, 4788, -1, 4813, 4792, 4801, -1, 4812, 4788, 4802, -1, 4813, 4803, 4792, -1, 4814, 4779, 4815, -1, 4816, 4802, 4790, -1, 4816, 4790, 4804, -1, 4814, 4789, 4779, -1, 4817, 4799, 4785, -1, 4818, 4809, 4798, -1, 4817, 4785, 4803, -1, 4818, 4798, 4807, -1, 4819, 4793, 4782, -1, 4820, 4805, 4795, -1, 4819, 4782, 4809, -1, 4819, 4794, 4793, -1, 4820, 4806, 4805, -1, 4820, 4795, 4808, -1, 4819, 4821, 4794, -1, 4822, 4791, 4823, -1, 4824, 4797, 4810, -1, 4824, 4808, 4797, -1, 4822, 4804, 4791, -1, 4825, 4807, 4796, -1, 4826, 4803, 4813, -1, 4825, 4796, 4811, -1, 4826, 4817, 4803, -1, 4827, 4811, 4800, -1, 4827, 4800, 4812, -1, 4828, 4789, 4814, -1, 4828, 4801, 4789, -1, 4829, 4812, 4802, -1, 4829, 4802, 4816, -1, 4830, 4799, 4817, -1, 4831, 4819, 4809, -1, 4830, 4810, 4799, -1, 4831, 4809, 4818, -1, 4832, 4833, 4806, -1, 4832, 4806, 4820, -1, 4831, 4821, 4819, -1, 4832, 4820, 4808, -1, 4832, 4808, 4824, -1, 4834, 4822, 4823, -1, 4835, 4830, 4817, -1, 4835, 4817, 4826, -1, 4836, 4804, 4822, -1, 4837, 4813, 4801, -1, 4836, 4816, 4804, -1, 4838, 4818, 4807, -1, 4838, 4807, 4825, -1, 4837, 4801, 4828, -1, 4839, 4824, 4810, -1, 4840, 4825, 4811, -1, 4839, 4810, 4830, -1, 4840, 4811, 4827, -1, 4841, 4815, 4842, -1, 4841, 4814, 4815, -1, 4843, 4827, 4812, -1, 4843, 4812, 4829, -1, 4844, 4830, 4835, -1, 4844, 4839, 4830, -1, 4845, 4813, 4837, -1, 4846, 4836, 4822, -1, 4845, 4826, 4813, -1, 4846, 4822, 4834, -1, 4847, 4816, 4836, -1, 4847, 4829, 4816, -1, 4848, 4833, 4832, -1, 4849, 4831, 4818, -1, 4848, 4832, 4824, -1, 4849, 4850, 4821, -1, 4848, 4824, 4839, -1, 4849, 4818, 4838, -1, 4849, 4821, 4831, -1, 4851, 4828, 4814, -1, 4852, 4825, 4840, -1, 4851, 4814, 4841, -1, 4852, 4838, 4825, -1, 4853, 4854, 4833, -1, 4855, 4840, 4827, -1, 4853, 4839, 4844, -1, 4853, 4848, 4839, -1, 4853, 4833, 4848, -1, 4855, 4827, 4843, -1, 4856, 4826, 4845, -1, 4857, 4847, 4836, -1, 4856, 4835, 4826, -1, 4857, 4836, 4846, -1, 4858, 4837, 4828, -1, 4858, 4828, 4851, -1, 4859, 4823, 4860, -1, 4859, 4834, 4823, -1, 4861, 4842, 4862, -1, 4863, 4843, 4829, -1, 4861, 4841, 4842, -1, 4863, 4829, 4847, -1, 4864, 4838, 4852, -1, 4864, 4849, 4838, -1, 4865, 4844, 4835, -1, 4865, 4835, 4856, -1, 4864, 4850, 4849, -1, 4866, 4852, 4840, -1, 4867, 4862, 4868, -1, 4867, 4861, 4862, -1, 4866, 4840, 4855, -1, 4869, 4863, 4847, -1, 4869, 4847, 4857, -1, 4870, 4845, 4837, -1, 4870, 4837, 4858, -1, 4871, 4834, 4859, -1, 4871, 4846, 4834, -1, 4872, 4841, 4861, -1, 4872, 4851, 4841, -1, 4873, 4855, 4843, -1, 4873, 4843, 4863, -1, 4874, 4844, 4865, -1, 4875, 4864, 4852, -1, 4874, 4854, 4853, -1, 4875, 4852, 4866, -1, 4874, 4853, 4844, -1, 4875, 4850, 4864, -1, 4875, 4876, 4850, -1, 4877, 4863, 4869, -1, 4877, 4873, 4863, -1, 4878, 4872, 4861, -1, 4878, 4861, 4867, -1, 4879, 4857, 4846, -1, 4880, 4856, 4845, -1, 4880, 4845, 4870, -1, 4879, 4846, 4871, -1, 4881, 4855, 4873, -1, 4881, 4866, 4855, -1, 4882, 4858, 4851, -1, 4882, 4851, 4872, -1, 4883, 4859, 4860, -1, 4883, 4860, 4884, -1, 4885, 4867, 4868, -1, 4886, 4882, 4872, -1, 4886, 4872, 4878, -1, 4887, 4873, 4877, -1, 4887, 4881, 4873, -1, 4888, 4869, 4857, -1, 4889, 4856, 4880, -1, 4888, 4857, 4879, -1, 4889, 4865, 4856, -1, 4890, 4858, 4882, -1, 4891, 4875, 4866, -1, 4891, 4866, 4881, -1, 4891, 4876, 4875, -1, 4890, 4870, 4858, -1, 4892, 4878, 4867, -1, 4893, 4859, 4883, -1, 4893, 4871, 4859, -1, 4892, 4867, 4885, -1, 4894, 4868, 4895, -1, 4896, 4891, 4881, -1, 4894, 4885, 4868, -1, 4896, 4881, 4887, -1, 4896, 4876, 4891, -1, 4896, 4897, 4876, -1, 4898, 4890, 4882, -1, 4898, 4882, 4886, -1, 4899, 4869, 4888, -1, 4900, 4901, 4854, -1, 4899, 4877, 4869, -1, 4900, 4874, 4865, -1, 4900, 4854, 4874, -1, 4900, 4865, 4889, -1, 4902, 4879, 4871, -1, 4902, 4871, 4893, -1, 4903, 4880, 4870, -1, 4904, 4884, 4905, -1, 4903, 4870, 4890, -1, 4904, 4883, 4884, -1, 4906, 4878, 4892, -1, 4907, 4887, 4877, -1, 4907, 4877, 4899, -1, 4906, 4886, 4878, -1, 4908, 4885, 4894, -1, 4909, 4905, 4910, -1, 4908, 4892, 4885, -1, 4911, 4894, 4895, -1, 4909, 4904, 4905, -1, 4912, 4888, 4879, -1, 4913, 4890, 4898, -1, 4912, 4879, 4902, -1, 4913, 4903, 4890, -1, 4914, 4889, 4880, -1, 4915, 4893, 4883, -1, 4914, 4880, 4903, -1, 4915, 4883, 4904, -1, 4916, 4898, 4886, -1, 4916, 4886, 4906, -1, 4917, 4896, 4887, -1, 4918, 4906, 4892, -1, 4917, 4897, 4896, -1, 4917, 4887, 4907, -1, 4918, 4892, 4908, -1, 4919, 4904, 4909, -1, 4919, 4915, 4904, -1, 4920, 4908, 4894, -1, 4920, 4894, 4911, -1, 4921, 4899, 4888, -1, 4921, 4888, 4912, -1, 4922, 4903, 4913, -1, 4922, 4914, 4903, -1, 4923, 4901, 4900, -1, 4924, 4902, 4893, -1, 4923, 4900, 4889, -1, 4923, 4889, 4914, -1, 4924, 4893, 4915, -1, 4923, 4925, 4901, -1, 4926, 4909, 4910, -1, 4927, 4895, 4928, -1, 4927, 4911, 4895, -1, 4929, 4915, 4919, -1, 4930, 4898, 4916, -1, 4930, 4913, 4898, -1, 4929, 4924, 4915, -1, 4931, 4907, 4899, -1, 4932, 4916, 4906, -1, 4932, 4906, 4918, -1, 4931, 4899, 4921, -1, 4933, 4908, 4920, -1, 4934, 4902, 4924, -1, 4933, 4918, 4908, -1, 4934, 4912, 4902, -1, 4935, 4914, 4922, -1, 4935, 4923, 4914, -1, 4936, 4909, 4926, -1, 4935, 4925, 4923, -1, 4936, 4919, 4909, -1, 4937, 4927, 4928, -1, 4938, 4910, 4939, -1, 4938, 4926, 4910, -1, 4940, 4920, 4911, -1, 4940, 4911, 4927, -1, 4941, 4924, 4929, -1, 4941, 4934, 4924, -1, 4942, 4922, 4913, -1, 4942, 4913, 4930, -1, 4943, 4944, 4897, -1, 4943, 4917, 4907, -1, 4943, 4907, 4931, -1, 4943, 4897, 4917, -1, 4945, 4930, 4916, -1, 4946, 4921, 4912, -1, 4945, 4916, 4932, -1, 4946, 4912, 4934, -1, 4947, 4932, 4918, -1, 4947, 4918, 4933, -1, 4948, 4919, 4936, -1, 4948, 4929, 4919, -1, 4949, 4927, 4937, -1, 4950, 4936, 4926, -1, 4949, 4940, 4927, -1, 4950, 4926, 4938, -1, 4951, 4938, 4939, -1, 4952, 4933, 4920, -1, 4952, 4920, 4940, -1, 4953, 4935, 4922, -1, 4954, 4934, 4941, -1, 4953, 4922, 4942, -1, 4953, 4925, 4935, -1, 4954, 4946, 4934, -1, 4953, 4955, 4925, -1, 4956, 4921, 4946, -1, 4956, 4931, 4921, -1, 4957, 4930, 4945, -1, 4957, 4942, 4930, -1, 4958, 4941, 4929, -1, 4958, 4929, 4948, -1, 4959, 4945, 4932, -1, 4959, 4932, 4947, -1, 4960, 4948, 4936, -1, 4961, 4928, 4962, -1, 4961, 4937, 4928, -1, 4960, 4936, 4950, -1, 4963, 4940, 4949, -1, 4963, 4952, 4940, -1, 4964, 4950, 4938, -1, 4964, 4938, 4951, -1, 4965, 4947, 4933, -1, 4966, 4956, 4946, -1, 4966, 4946, 4954, -1, 4965, 4933, 4952, -1, 4967, 4931, 4956, -1, 4967, 4943, 4931, -1, 4968, 4955, 4953, -1, 4968, 4942, 4957, -1, 4967, 4969, 4944, -1, 4968, 4953, 4942, -1, 4967, 4944, 4943, -1, 4970, 4951, 4939, -1, 4970, 4939, 4971, -1, 4972, 4957, 4945, -1, 4972, 4945, 4959, -1, 4973, 4949, 4937, -1, 4974, 4941, 4958, -1, 4974, 4954, 4941, -1, 4973, 4937, 4961, -1, 4975, 4965, 4952, -1, 4976, 4948, 4960, -1, 4976, 4958, 4948, -1, 4975, 4952, 4963, -1, 4977, 4950, 4964, -1, 4977, 4960, 4950, -1, 4978, 4947, 4965, -1, 4978, 4959, 4947, -1, 4979, 4955, 4968, -1, 4980, 4956, 4966, -1, 4980, 4967, 4956, -1, 4979, 4957, 4972, -1, 4980, 4969, 4967, -1, 4979, 4981, 4955, -1, 4979, 4968, 4957, -1, 4982, 4949, 4973, -1, 4983, 4970, 4971, -1, 4982, 4963, 4949, -1, 4984, 4965, 4975, -1, 4985, 4951, 4970, -1, 4985, 4964, 4951, -1, 4984, 4978, 4965, -1, 4986, 4966, 4954, -1, 4987, 4972, 4959, -1, 4987, 4959, 4978, -1, 4986, 4954, 4974, -1, 4988, 4974, 4958, -1, 4988, 4958, 4976, -1, 4989, 4962, 4990, -1, 4989, 4961, 4962, -1, 4991, 4976, 4960, -1, 4992, 4975, 4963, -1, 4992, 4963, 4982, -1, 4991, 4960, 4977, -1, 4993, 4987, 4978, -1, 4993, 4978, 4984, -1, 4994, 4970, 4983, -1, 4994, 4985, 4970, -1, 4995, 4977, 4964, -1, 4996, 4972, 4987, -1, 4996, 4979, 4972, -1, 4995, 4964, 4985, -1, 4996, 4981, 4979, -1, 4997, 4961, 4989, -1, 4998, 4980, 4966, -1, 4998, 4999, 4969, -1, 4998, 4969, 4980, -1, 4998, 4966, 4986, -1, 4997, 4973, 4961, -1, 5000, 4984, 4975, -1, 5001, 4986, 4974, -1, 5000, 4975, 4992, -1, 5001, 4974, 4988, -1, 5002, 4988, 4976, -1, 5003, 4996, 4987, -1, 5003, 4987, 4993, -1, 5002, 4976, 4991, -1, 5003, 4981, 4996, -1, 5003, 4285, 4981, -1, 4463, 4971, 4514, -1, 4261, 4982, 4973, -1, 4463, 4983, 4971, -1, 4268, 4995, 4985, -1, 4261, 4973, 4997, -1, 4264, 4990, 5004, -1, 4268, 4985, 4994, -1, 4264, 4989, 4990, -1, 5005, 4991, 4977, -1, 4283, 4993, 4984, -1, 4283, 4984, 5000, -1, 5005, 4977, 4995, -1, 5006, 4998, 4986, -1, 5006, 4999, 4998, -1, 5006, 4986, 5001, -1, 4260, 4982, 4261, -1, 4260, 4992, 4982, -1, 4280, 5001, 4988, -1, 4280, 4988, 5002, -1, 4462, 4983, 4463, -1, 4269, 4989, 4264, -1, 4269, 4997, 4989, -1, 4462, 4994, 4983, -1, 4267, 5005, 4995, -1, 4282, 5003, 4993, -1, 4282, 4993, 4283, -1, 4267, 4995, 4268, -1, 4282, 4285, 5003, -1, 4289, 5000, 4992, -1, 4289, 4992, 4260, -1, 4272, 4991, 5005, -1, 4272, 5002, 4991, -1, 4279, 5006, 5001, -1, 4279, 4999, 5006, -1, 4262, 4997, 4269, -1, 4279, 5001, 4280, -1, 4262, 4261, 4997, -1, 4279, 4284, 4999, -1, 4270, 4994, 4462, -1, 4265, 5004, 4275, -1, 4270, 4268, 4994, -1, 4265, 4264, 5004, -1, 4273, 5005, 4267, -1, 4273, 4272, 5005, -1, 4286, 4283, 5000, -1, 4286, 5000, 4289, -1, 4277, 4280, 5002, -1, 4277, 5002, 4272, -1, 5007, 5008, 5009, -1, 5010, 5011, 5012, -1, 5013, 5011, 5010, -1, 5014, 5015, 5016, -1, 5014, 5016, 5017, -1, 5014, 5017, 5018, -1, 5019, 5020, 5015, -1, 5019, 5021, 5020, -1, 5019, 5015, 5014, -1, 5022, 5018, 5008, -1, 5022, 5007, 5023, -1, 5022, 5014, 5018, -1, 5022, 5008, 5007, -1, 5024, 5025, 5026, -1, 5024, 5026, 5027, -1, 5024, 5027, 5021, -1, 5024, 5021, 5019, -1, 5028, 5023, 5029, -1, 5028, 5022, 5023, -1, 5028, 5014, 5022, -1, 5028, 5019, 5014, -1, 5030, 5029, 5012, -1, 5030, 5011, 5025, -1, 5030, 5024, 5019, -1, 5030, 5028, 5029, -1, 5030, 5019, 5028, -1, 5030, 5012, 5011, -1, 5030, 5025, 5024, -1, 5031, 5032, 5033, -1, 5034, 5035, 5036, -1, 5037, 5034, 5036, -1, 5038, 5039, 5040, -1, 5038, 5040, 5041, -1, 5038, 5041, 5042, -1, 5043, 5044, 5039, -1, 5043, 5045, 5044, -1, 5043, 5039, 5038, -1, 5046, 5042, 5032, -1, 5046, 5031, 5047, -1, 5046, 5038, 5042, -1, 5046, 5032, 5031, -1, 5048, 5049, 5050, -1, 5048, 5050, 5051, -1, 5048, 5051, 5045, -1, 5048, 5045, 5043, -1, 5052, 5047, 5053, -1, 5052, 5046, 5047, -1, 5052, 5038, 5046, -1, 5052, 5043, 5038, -1, 5054, 5053, 5035, -1, 5054, 5034, 5049, -1, 5054, 5048, 5043, -1, 5054, 5052, 5053, -1, 5054, 5043, 5052, -1, 5054, 5035, 5034, -1, 5054, 5049, 5048, -1, 5055, 5056, 5057, -1, 5058, 5059, 5060, -1, 5061, 5057, 5062, -1, 5061, 5062, 5063, -1, 5061, 5064, 5055, -1, 5061, 5055, 5057, -1, 5065, 5063, 5059, -1, 5065, 5058, 5066, -1, 5065, 5066, 5064, -1, 5065, 5061, 5063, -1, 5065, 5059, 5058, -1, 5065, 5064, 5061, -1, 5067, 5068, 5069, -1, 5070, 5071, 5072, -1, 5073, 5071, 5070, -1, 5074, 5075, 5076, -1, 5074, 5076, 5077, -1, 5074, 5077, 5078, -1, 5079, 5080, 5081, -1, 5079, 5081, 5075, -1, 5079, 5075, 5074, -1, 5082, 5078, 5068, -1, 5082, 5067, 5083, -1, 5082, 5068, 5067, -1, 5082, 5074, 5078, -1, 5084, 5085, 5086, -1, 5084, 5086, 5087, -1, 5084, 5087, 5080, -1, 5084, 5080, 5079, -1, 5088, 5083, 5089, -1, 5088, 5082, 5083, -1, 5088, 5074, 5082, -1, 5088, 5079, 5074, -1, 5090, 5089, 5072, -1, 5090, 5071, 5085, -1, 5090, 5088, 5089, -1, 5090, 5084, 5079, -1, 5090, 5079, 5088, -1, 5090, 5072, 5071, -1, 5090, 5085, 5084, -1, 5091, 5092, 5093, -1, 5094, 5095, 5096, -1, 5097, 5095, 5094, -1, 5098, 5099, 5100, -1, 5098, 5100, 5101, -1, 5098, 5101, 5102, -1, 5103, 5104, 5105, -1, 5103, 5105, 5099, -1, 5103, 5099, 5098, -1, 5106, 5102, 5092, -1, 5106, 5091, 5107, -1, 5106, 5092, 5091, -1, 5106, 5098, 5102, -1, 5108, 5109, 5110, -1, 5108, 5110, 5111, -1, 5108, 5111, 5104, -1, 5108, 5104, 5103, -1, 5112, 5107, 5113, -1, 5112, 5106, 5107, -1, 5112, 5098, 5106, -1, 5112, 5103, 5098, -1, 5114, 5113, 5096, -1, 5114, 5095, 5109, -1, 5114, 5112, 5113, -1, 5114, 5108, 5103, -1, 5114, 5103, 5112, -1, 5114, 5096, 5095, -1, 5114, 5109, 5108, -1, 5115, 5116, 5117, -1, 5118, 5119, 5120, -1, 5121, 5122, 5123, -1, 5121, 5123, 5116, -1, 5121, 5115, 5124, -1, 5121, 5116, 5115, -1, 5125, 5126, 5122, -1, 5125, 5122, 5121, -1, 5127, 5124, 5128, -1, 5127, 5128, 5129, -1, 5127, 5121, 5124, -1, 5130, 5131, 5118, -1, 5130, 5120, 5126, -1, 5130, 5118, 5120, -1, 5130, 5126, 5125, -1, 5132, 5129, 5133, -1, 5132, 5133, 5134, -1, 5132, 5134, 5135, -1, 5132, 5127, 5129, -1, 5132, 5125, 5121, -1, 5132, 5121, 5127, -1, 5136, 5135, 5137, -1, 5136, 5137, 5138, -1, 5136, 5138, 5131, -1, 5136, 5132, 5135, -1, 5136, 5131, 5130, -1, 5136, 5130, 5125, -1, 5136, 5125, 5132, -1, 5139, 5140, 5141, -1, 5139, 5141, 5142, -1, 5143, 5139, 5142, -1, 5144, 5140, 5139, -1, 5145, 5143, 5142, -1, 5146, 5143, 5145, -1, 5147, 5144, 5139, -1, 5148, 5145, 5149, -1, 5148, 5146, 5145, -1, 5150, 5144, 5147, -1, 5151, 5152, 5153, -1, 5154, 5155, 5148, -1, 5154, 5148, 5149, -1, 5156, 5157, 5152, -1, 5158, 5157, 5156, -1, 5159, 5158, 5156, -1, 5160, 5155, 5154, -1, 5161, 5155, 5160, -1, 5162, 5159, 5163, -1, 5162, 5158, 5159, -1, 5164, 5161, 5160, -1, 5165, 5162, 5163, -1, 5166, 5167, 5161, -1, 5166, 5161, 5164, -1, 5168, 5167, 5166, -1, 5169, 5162, 5165, -1, 5151, 5156, 5152, -1, 5170, 5147, 5171, -1, 5170, 5171, 5151, -1, 5170, 5153, 5150, -1, 5170, 5151, 5153, -1, 5170, 5150, 5147, -1, 5172, 5165, 5167, -1, 5172, 5168, 5169, -1, 5172, 5169, 5165, -1, 5172, 5167, 5168, -1, 5173, 5174, 5175, -1, 5176, 5177, 5178, -1, 5179, 5180, 5181, -1, 5179, 5181, 5174, -1, 5179, 5173, 5182, -1, 5179, 5174, 5173, -1, 5183, 5184, 5180, -1, 5183, 5180, 5179, -1, 5185, 5182, 5186, -1, 5185, 5186, 5187, -1, 5185, 5179, 5182, -1, 5188, 5189, 5176, -1, 5188, 5178, 5184, -1, 5188, 5184, 5183, -1, 5188, 5176, 5178, -1, 5190, 5187, 5191, -1, 5190, 5191, 5192, -1, 5190, 5192, 5193, -1, 5190, 5185, 5187, -1, 5190, 5179, 5185, -1, 5190, 5183, 5179, -1, 5194, 5193, 5195, -1, 5194, 5195, 5196, -1, 5194, 5196, 5189, -1, 5194, 5189, 5188, -1, 5194, 5190, 5193, -1, 5194, 5188, 5183, -1, 5194, 5183, 5190, -1, 5197, 5198, 5199, -1, 5197, 5199, 5200, -1, 5201, 5197, 5200, -1, 5202, 5198, 5197, -1, 5203, 5201, 5200, -1, 5204, 5201, 5203, -1, 5205, 5202, 5197, -1, 5206, 5204, 5203, -1, 5207, 5206, 5203, -1, 5208, 5202, 5205, -1, 5209, 5210, 5211, -1, 5209, 5211, 5208, -1, 5212, 5213, 5206, -1, 5212, 5206, 5207, -1, 5214, 5215, 5210, -1, 5216, 5215, 5214, -1, 5217, 5216, 5214, -1, 5218, 5213, 5212, -1, 5219, 5213, 5218, -1, 5220, 5217, 5221, -1, 5220, 5216, 5217, -1, 5222, 5219, 5218, -1, 5223, 5220, 5221, -1, 5224, 5225, 5219, -1, 5224, 5219, 5222, -1, 5226, 5225, 5224, -1, 5227, 5220, 5223, -1, 5209, 5214, 5210, -1, 5228, 5205, 5229, -1, 5228, 5229, 5209, -1, 5228, 5208, 5205, -1, 5228, 5209, 5208, -1, 5230, 5223, 5225, -1, 5230, 5226, 5227, -1, 5230, 5227, 5223, -1, 5230, 5225, 5226, -1, 5231, 5232, 5233, -1, 5234, 5235, 5236, -1, 5237, 5235, 5234, -1, 5238, 5239, 5240, -1, 5238, 5240, 5241, -1, 5238, 5241, 5242, -1, 5243, 5244, 5239, -1, 5243, 5245, 5244, -1, 5243, 5239, 5238, -1, 5246, 5242, 5232, -1, 5246, 5231, 5247, -1, 5246, 5238, 5242, -1, 5246, 5232, 5231, -1, 5248, 5249, 5250, -1, 5248, 5250, 5251, -1, 5248, 5251, 5245, -1, 5248, 5245, 5243, -1, 5252, 5247, 5253, -1, 5252, 5246, 5247, -1, 5252, 5238, 5246, -1, 5252, 5243, 5238, -1, 5254, 5253, 5236, -1, 5254, 5235, 5249, -1, 5254, 5248, 5243, -1, 5254, 5252, 5253, -1, 5254, 5243, 5252, -1, 5254, 5236, 5235, -1, 5254, 5249, 5248, -1, 5255, 5256, 5257, -1, 5258, 5259, 5260, -1, 5261, 5259, 5258, -1, 5262, 5263, 5264, -1, 5262, 5264, 5265, -1, 5262, 5265, 5266, -1, 5267, 5268, 5263, -1, 5267, 5269, 5268, -1, 5267, 5263, 5262, -1, 5270, 5266, 5256, -1, 5270, 5255, 5271, -1, 5270, 5262, 5266, -1, 5270, 5256, 5255, -1, 5272, 5273, 5274, -1, 5272, 5274, 5275, -1, 5272, 5275, 5269, -1, 5272, 5269, 5267, -1, 5276, 5271, 5277, -1, 5276, 5270, 5271, -1, 5276, 5262, 5270, -1, 5276, 5267, 5262, -1, 5278, 5277, 5260, -1, 5278, 5259, 5273, -1, 5278, 5272, 5267, -1, 5278, 5276, 5277, -1, 5278, 5267, 5276, -1, 5278, 5260, 5259, -1, 5278, 5273, 5272, -1, 5279, 5280, 5281, -1, 5282, 5283, 5284, -1, 5285, 5283, 5282, -1, 5286, 5287, 5288, -1, 5286, 5288, 5289, -1, 5286, 5289, 5290, -1, 5291, 5292, 5287, -1, 5291, 5293, 5292, -1, 5291, 5287, 5286, -1, 5294, 5290, 5280, -1, 5294, 5279, 5295, -1, 5294, 5286, 5290, -1, 5294, 5280, 5279, -1, 5296, 5297, 5298, -1, 5296, 5298, 5299, -1, 5296, 5299, 5293, -1, 5296, 5293, 5291, -1, 5300, 5295, 5301, -1, 5300, 5294, 5295, -1, 5300, 5286, 5294, -1, 5300, 5291, 5286, -1, 5302, 5301, 5284, -1, 5302, 5283, 5297, -1, 5302, 5296, 5291, -1, 5302, 5300, 5301, -1, 5302, 5291, 5300, -1, 5302, 5284, 5283, -1, 5302, 5297, 5296, -1, 5303, 5304, 5305, -1, 5306, 5307, 5308, -1, 5309, 5305, 5310, -1, 5309, 5310, 5311, -1, 5309, 5312, 5303, -1, 5309, 5303, 5305, -1, 5313, 5311, 5307, -1, 5313, 5306, 5314, -1, 5313, 5314, 5312, -1, 5313, 5309, 5311, -1, 5313, 5307, 5306, -1, 5313, 5312, 5309, -1, 5315, 5316, 5317, -1, 5318, 5319, 5320, -1, 5321, 5318, 5320, -1, 5322, 5323, 5324, -1, 5322, 5324, 5325, -1, 5322, 5325, 5326, -1, 5327, 5328, 5329, -1, 5327, 5329, 5323, -1, 5327, 5323, 5322, -1, 5330, 5326, 5316, -1, 5330, 5315, 5331, -1, 5330, 5316, 5315, -1, 5330, 5322, 5326, -1, 5332, 5333, 5334, -1, 5332, 5334, 5335, -1, 5332, 5335, 5328, -1, 5332, 5328, 5327, -1, 5336, 5331, 5337, -1, 5336, 5330, 5331, -1, 5336, 5322, 5330, -1, 5336, 5327, 5322, -1, 5338, 5337, 5319, -1, 5338, 5318, 5333, -1, 5338, 5336, 5337, -1, 5338, 5332, 5327, -1, 5338, 5327, 5336, -1, 5338, 5319, 5318, -1, 5338, 5333, 5332, -1, 5339, 5340, 5341, -1, 5342, 5343, 5344, -1, 5345, 5346, 5347, -1, 5345, 5347, 5340, -1, 5345, 5339, 5348, -1, 5345, 5340, 5339, -1, 5349, 5350, 5346, -1, 5349, 5346, 5345, -1, 5351, 5348, 5352, -1, 5351, 5352, 5353, -1, 5351, 5345, 5348, -1, 5354, 5355, 5342, -1, 5354, 5344, 5350, -1, 5354, 5342, 5344, -1, 5354, 5350, 5349, -1, 5356, 5353, 5357, -1, 5356, 5357, 5358, -1, 5356, 5358, 5359, -1, 5356, 5351, 5353, -1, 5356, 5349, 5345, -1, 5356, 5345, 5351, -1, 5360, 5359, 5361, -1, 5360, 5361, 5362, -1, 5360, 5362, 5355, -1, 5360, 5356, 5359, -1, 5360, 5355, 5354, -1, 5360, 5354, 5349, -1, 5360, 5349, 5356, -1, 5363, 5364, 5365, -1, 5363, 5365, 5366, -1, 5367, 5363, 5366, -1, 5368, 5364, 5363, -1, 5369, 5367, 5366, -1, 5370, 5367, 5369, -1, 5371, 5368, 5363, -1, 5372, 5370, 5369, -1, 5373, 5372, 5369, -1, 5374, 5368, 5371, -1, 5375, 5376, 5377, -1, 5375, 5377, 5374, -1, 5378, 5379, 5372, -1, 5378, 5372, 5373, -1, 5380, 5381, 5376, -1, 5382, 5381, 5380, -1, 5383, 5382, 5380, -1, 5384, 5379, 5378, -1, 5385, 5379, 5384, -1, 5386, 5383, 5387, -1, 5386, 5382, 5383, -1, 5388, 5385, 5384, -1, 5389, 5386, 5387, -1, 5390, 5391, 5385, -1, 5390, 5385, 5388, -1, 5392, 5391, 5390, -1, 5393, 5386, 5389, -1, 5375, 5380, 5376, -1, 5394, 5371, 5395, -1, 5394, 5395, 5375, -1, 5394, 5374, 5371, -1, 5394, 5375, 5374, -1, 5396, 5389, 5391, -1, 5396, 5392, 5393, -1, 5396, 5393, 5389, -1, 5396, 5391, 5392, -1, 5397, 5398, 5399, -1, 5400, 5401, 5402, -1, 5403, 5404, 5405, -1, 5403, 5405, 5398, -1, 5403, 5397, 5406, -1, 5403, 5398, 5397, -1, 5407, 5408, 5404, -1, 5407, 5404, 5403, -1, 5409, 5406, 5410, -1, 5409, 5410, 5411, -1, 5409, 5403, 5406, -1, 5412, 5413, 5400, -1, 5412, 5402, 5408, -1, 5412, 5408, 5407, -1, 5412, 5400, 5402, -1, 5414, 5411, 5415, -1, 5414, 5415, 5416, -1, 5414, 5416, 5417, -1, 5414, 5409, 5411, -1, 5414, 5403, 5409, -1, 5414, 5407, 5403, -1, 5418, 5417, 5419, -1, 5418, 5419, 5420, -1, 5418, 5420, 5413, -1, 5418, 5413, 5412, -1, 5418, 5414, 5417, -1, 5418, 5412, 5407, -1, 5418, 5407, 5414, -1, 5421, 5422, 5423, -1, 5421, 5423, 5424, -1, 5425, 5421, 5424, -1, 5426, 5422, 5421, -1, 5427, 5425, 5424, -1, 5428, 5425, 5427, -1, 5429, 5426, 5421, -1, 5430, 5427, 5431, -1, 5430, 5428, 5427, -1, 5432, 5426, 5429, -1, 5433, 5434, 5435, -1, 5436, 5437, 5430, -1, 5436, 5430, 5431, -1, 5438, 5439, 5434, -1, 5440, 5439, 5438, -1, 5441, 5440, 5438, -1, 5442, 5437, 5436, -1, 5443, 5437, 5442, -1, 5444, 5441, 5445, -1, 5444, 5440, 5441, -1, 5446, 5443, 5442, -1, 5447, 5444, 5445, -1, 5448, 5449, 5443, -1, 5448, 5443, 5446, -1, 5450, 5449, 5448, -1, 5451, 5444, 5447, -1, 5433, 5438, 5434, -1, 5452, 5429, 5453, -1, 5452, 5453, 5433, -1, 5452, 5435, 5432, -1, 5452, 5433, 5435, -1, 5452, 5432, 5429, -1, 5454, 5447, 5449, -1, 5454, 5450, 5451, -1, 5454, 5451, 5447, -1, 5454, 5449, 5450, -1, 5455, 5456, 5457, -1, 5458, 5459, 5460, -1, 5461, 5457, 5462, -1, 5461, 5462, 5463, -1, 5461, 5464, 5455, -1, 5461, 5455, 5457, -1, 5465, 5463, 5459, -1, 5465, 5458, 5466, -1, 5465, 5466, 5464, -1, 5465, 5461, 5463, -1, 5465, 5459, 5458, -1, 5465, 5464, 5461, -1, 5467, 5468, 5469, -1, 5470, 5471, 5472, -1, 5473, 5470, 5472, -1, 5474, 5475, 5476, -1, 5474, 5476, 5477, -1, 5474, 5477, 5478, -1, 5479, 5480, 5481, -1, 5479, 5481, 5475, -1, 5479, 5475, 5474, -1, 5482, 5478, 5468, -1, 5482, 5467, 5483, -1, 5482, 5468, 5467, -1, 5482, 5474, 5478, -1, 5484, 5485, 5486, -1, 5484, 5486, 5487, -1, 5484, 5487, 5480, -1, 5484, 5480, 5479, -1, 5488, 5483, 5489, -1, 5488, 5482, 5483, -1, 5488, 5474, 5482, -1, 5488, 5479, 5474, -1, 5490, 5489, 5471, -1, 5490, 5470, 5485, -1, 5490, 5488, 5489, -1, 5490, 5484, 5479, -1, 5490, 5479, 5488, -1, 5490, 5471, 5470, -1, 5490, 5485, 5484, -1, 5491, 5492, 5493, -1, 5494, 5495, 5496, -1, 5497, 5495, 5494, -1, 5498, 5499, 5500, -1, 5498, 5500, 5501, -1, 5498, 5501, 5502, -1, 5503, 5504, 5505, -1, 5503, 5505, 5499, -1, 5503, 5499, 5498, -1, 5506, 5502, 5492, -1, 5506, 5491, 5507, -1, 5506, 5492, 5491, -1, 5506, 5498, 5502, -1, 5508, 5509, 5510, -1, 5508, 5510, 5511, -1, 5508, 5511, 5504, -1, 5508, 5504, 5503, -1, 5512, 5507, 5513, -1, 5512, 5506, 5507, -1, 5512, 5498, 5506, -1, 5512, 5503, 5498, -1, 5514, 5513, 5496, -1, 5514, 5495, 5509, -1, 5514, 5512, 5513, -1, 5514, 5508, 5503, -1, 5514, 5503, 5512, -1, 5514, 5496, 5495, -1, 5514, 5509, 5508, -1, 5515, 5516, 5517, -1, 5518, 5519, 5520, -1, 5521, 5519, 5518, -1, 5522, 5523, 5524, -1, 5522, 5524, 5525, -1, 5522, 5525, 5526, -1, 5527, 5528, 5529, -1, 5527, 5529, 5523, -1, 5527, 5523, 5522, -1, 5530, 5526, 5516, -1, 5530, 5515, 5531, -1, 5530, 5516, 5515, -1, 5530, 5522, 5526, -1, 5532, 5533, 5534, -1, 5532, 5534, 5535, -1, 5532, 5535, 5528, -1, 5532, 5528, 5527, -1, 5536, 5531, 5537, -1, 5536, 5530, 5531, -1, 5536, 5522, 5530, -1, 5536, 5527, 5522, -1, 5538, 5537, 5520, -1, 5538, 5519, 5533, -1, 5538, 5536, 5537, -1, 5538, 5532, 5527, -1, 5538, 5527, 5536, -1, 5538, 5520, 5519, -1, 5538, 5533, 5532, -1, 5539, 5540, 5541, -1, 5542, 5543, 5544, -1, 5545, 5543, 5542, -1, 5546, 5547, 5548, -1, 5546, 5548, 5549, -1, 5546, 5549, 5550, -1, 5551, 5552, 5553, -1, 5551, 5553, 5547, -1, 5551, 5547, 5546, -1, 5554, 5550, 5540, -1, 5554, 5539, 5555, -1, 5554, 5540, 5539, -1, 5554, 5546, 5550, -1, 5556, 5557, 5558, -1, 5556, 5558, 5559, -1, 5556, 5559, 5552, -1, 5556, 5552, 5551, -1, 5560, 5555, 5561, -1, 5560, 5554, 5555, -1, 5560, 5546, 5554, -1, 5560, 5551, 5546, -1, 5562, 5561, 5544, -1, 5562, 5543, 5557, -1, 5562, 5560, 5561, -1, 5562, 5556, 5551, -1, 5562, 5551, 5560, -1, 5562, 5544, 5543, -1, 5562, 5557, 5556, -1, 5563, 5564, 5565, -1, 5566, 5567, 5568, -1, 5569, 5570, 5571, -1, 5569, 5571, 5564, -1, 5569, 5563, 5572, -1, 5569, 5564, 5563, -1, 5573, 5574, 5570, -1, 5573, 5570, 5569, -1, 5575, 5572, 5576, -1, 5575, 5576, 5577, -1, 5575, 5569, 5572, -1, 5578, 5579, 5566, -1, 5578, 5568, 5574, -1, 5578, 5574, 5573, -1, 5578, 5566, 5568, -1, 5580, 5577, 5581, -1, 5580, 5581, 5582, -1, 5580, 5582, 5583, -1, 5580, 5575, 5577, -1, 5580, 5569, 5575, -1, 5580, 5573, 5569, -1, 5584, 5583, 5585, -1, 5584, 5585, 5586, -1, 5584, 5586, 5579, -1, 5584, 5579, 5578, -1, 5584, 5580, 5583, -1, 5584, 5578, 5573, -1, 5584, 5573, 5580, -1, 5587, 5588, 5589, -1, 5587, 5589, 5590, -1, 5591, 5587, 5590, -1, 5592, 5588, 5587, -1, 5593, 5591, 5590, -1, 5594, 5591, 5593, -1, 5595, 5592, 5587, -1, 5596, 5593, 5597, -1, 5596, 5594, 5593, -1, 5598, 5592, 5595, -1, 5599, 5600, 5601, -1, 5602, 5603, 5596, -1, 5602, 5596, 5597, -1, 5604, 5605, 5600, -1, 5606, 5605, 5604, -1, 5607, 5606, 5604, -1, 5608, 5603, 5602, -1, 5609, 5603, 5608, -1, 5610, 5607, 5611, -1, 5610, 5606, 5607, -1, 5612, 5609, 5608, -1, 5613, 5610, 5611, -1, 5614, 5615, 5609, -1, 5614, 5609, 5612, -1, 5616, 5615, 5614, -1, 5617, 5610, 5613, -1, 5599, 5604, 5600, -1, 5618, 5595, 5619, -1, 5618, 5619, 5599, -1, 5618, 5601, 5598, -1, 5618, 5599, 5601, -1, 5618, 5598, 5595, -1, 5620, 5613, 5615, -1, 5620, 5616, 5617, -1, 5620, 5617, 5613, -1, 5620, 5615, 5616, -1, 5621, 5622, 5623, -1, 5621, 5623, 5624, -1, 5625, 5621, 5624, -1, 5626, 5622, 5621, -1, 5627, 5625, 5624, -1, 5628, 5625, 5627, -1, 5629, 5626, 5621, -1, 5630, 5628, 5627, -1, 5631, 5630, 5627, -1, 5632, 5626, 5629, -1, 5633, 5634, 5635, -1, 5633, 5635, 5632, -1, 5636, 5637, 5630, -1, 5636, 5630, 5631, -1, 5638, 5639, 5634, -1, 5640, 5639, 5638, -1, 5641, 5640, 5638, -1, 5642, 5637, 5636, -1, 5643, 5637, 5642, -1, 5644, 5641, 5645, -1, 5644, 5640, 5641, -1, 5646, 5643, 5642, -1, 5647, 5644, 5645, -1, 5648, 5649, 5643, -1, 5648, 5643, 5646, -1, 5650, 5649, 5648, -1, 5651, 5644, 5647, -1, 5633, 5638, 5634, -1, 5652, 5629, 5653, -1, 5652, 5653, 5633, -1, 5652, 5632, 5629, -1, 5652, 5633, 5632, -1, 5654, 5647, 5649, -1, 5654, 5650, 5651, -1, 5654, 5651, 5647, -1, 5654, 5649, 5650, -1, 5655, 5656, 5657, -1, 5658, 5659, 5660, -1, 5661, 5662, 5663, -1, 5661, 5663, 5656, -1, 5661, 5655, 5664, -1, 5661, 5656, 5655, -1, 5665, 5666, 5662, -1, 5665, 5662, 5661, -1, 5667, 5664, 5668, -1, 5667, 5668, 5669, -1, 5667, 5661, 5664, -1, 5670, 5671, 5658, -1, 5670, 5660, 5666, -1, 5670, 5666, 5665, -1, 5670, 5658, 5660, -1, 5672, 5673, 5674, -1, 5672, 5669, 5675, -1, 5672, 5675, 5673, -1, 5672, 5667, 5669, -1, 5672, 5661, 5667, -1, 5672, 5665, 5661, -1, 5676, 5674, 5677, -1, 5676, 5677, 5678, -1, 5676, 5678, 5671, -1, 5676, 5665, 5672, -1, 5676, 5672, 5674, -1, 5676, 5671, 5670, -1, 5676, 5670, 5665, -1, 5679, 5680, 5681, -1, 5682, 5683, 5684, -1, 5685, 5682, 5684, -1, 5686, 5687, 5688, -1, 5686, 5688, 5689, -1, 5686, 5689, 5690, -1, 5691, 5692, 5687, -1, 5691, 5693, 5692, -1, 5691, 5687, 5686, -1, 5694, 5690, 5680, -1, 5694, 5679, 5695, -1, 5694, 5686, 5690, -1, 5694, 5680, 5679, -1, 5696, 5697, 5698, -1, 5696, 5698, 5699, -1, 5696, 5699, 5693, -1, 5696, 5693, 5691, -1, 5700, 5695, 5701, -1, 5700, 5694, 5695, -1, 5700, 5686, 5694, -1, 5700, 5691, 5686, -1, 5702, 5701, 5683, -1, 5702, 5682, 5697, -1, 5702, 5696, 5691, -1, 5702, 5700, 5701, -1, 5702, 5691, 5700, -1, 5702, 5683, 5682, -1, 5702, 5697, 5696, -1, 5703, 5704, 5705, -1, 5706, 5707, 5708, -1, 5709, 5707, 5706, -1, 5710, 5711, 5712, -1, 5710, 5712, 5713, -1, 5710, 5713, 5714, -1, 5715, 5716, 5717, -1, 5715, 5717, 5711, -1, 5715, 5711, 5710, -1, 5718, 5714, 5704, -1, 5718, 5703, 5719, -1, 5718, 5704, 5703, -1, 5718, 5710, 5714, -1, 5720, 5721, 5722, -1, 5720, 5722, 5723, -1, 5720, 5723, 5716, -1, 5720, 5716, 5715, -1, 5724, 5719, 5725, -1, 5724, 5718, 5719, -1, 5724, 5710, 5718, -1, 5724, 5715, 5710, -1, 5726, 5725, 5708, -1, 5726, 5707, 5721, -1, 5726, 5724, 5725, -1, 5726, 5720, 5715, -1, 5726, 5715, 5724, -1, 5726, 5708, 5707, -1, 5726, 5721, 5720, -1, 5727, 5728, 5729, -1, 5730, 5731, 5732, -1, 5733, 5729, 5734, -1, 5733, 5734, 5735, -1, 5733, 5736, 5727, -1, 5733, 5727, 5729, -1, 5737, 5735, 5731, -1, 5737, 5730, 5738, -1, 5737, 5738, 5736, -1, 5737, 5733, 5735, -1, 5737, 5731, 5730, -1, 5737, 5736, 5733, -1, 5739, 5740, 5741, -1, 5742, 5743, 5744, -1, 5745, 5743, 5742, -1, 5746, 5747, 5748, -1, 5746, 5748, 5749, -1, 5746, 5749, 5750, -1, 5751, 5752, 5747, -1, 5751, 5753, 5752, -1, 5751, 5747, 5746, -1, 5754, 5750, 5740, -1, 5754, 5739, 5755, -1, 5754, 5746, 5750, -1, 5754, 5740, 5739, -1, 5756, 5757, 5758, -1, 5756, 5758, 5759, -1, 5756, 5759, 5753, -1, 5756, 5753, 5751, -1, 5760, 5755, 5761, -1, 5760, 5754, 5755, -1, 5760, 5746, 5754, -1, 5760, 5751, 5746, -1, 5762, 5761, 5744, -1, 5762, 5743, 5757, -1, 5762, 5756, 5751, -1, 5762, 5760, 5761, -1, 5762, 5751, 5760, -1, 5762, 5744, 5743, -1, 5762, 5757, 5756, -1, 5763, 5764, 5765, -1, 5766, 5767, 5768, -1, 5769, 5767, 5766, -1, 5770, 5771, 5772, -1, 5770, 5772, 5773, -1, 5770, 5773, 5774, -1, 5775, 5776, 5777, -1, 5775, 5777, 5771, -1, 5775, 5771, 5770, -1, 5778, 5774, 5764, -1, 5778, 5763, 5779, -1, 5778, 5764, 5763, -1, 5778, 5770, 5774, -1, 5780, 5781, 5782, -1, 5780, 5782, 5783, -1, 5780, 5783, 5776, -1, 5780, 5776, 5775, -1, 5784, 5779, 5785, -1, 5784, 5778, 5779, -1, 5784, 5770, 5778, -1, 5784, 5775, 5770, -1, 5786, 5785, 5768, -1, 5786, 5767, 5781, -1, 5786, 5784, 5785, -1, 5786, 5780, 5775, -1, 5786, 5775, 5784, -1, 5786, 5768, 5767, -1, 5786, 5781, 5780, -1, 5787, 5788, 5789, -1, 5790, 5791, 5792, -1, 5793, 5794, 5795, -1, 5793, 5795, 5788, -1, 5793, 5787, 5796, -1, 5793, 5788, 5787, -1, 5797, 5798, 5794, -1, 5797, 5794, 5793, -1, 5799, 5796, 5800, -1, 5799, 5800, 5801, -1, 5799, 5793, 5796, -1, 5802, 5803, 5790, -1, 5802, 5792, 5798, -1, 5802, 5798, 5797, -1, 5802, 5790, 5792, -1, 5804, 5801, 5805, -1, 5804, 5805, 5806, -1, 5804, 5806, 5807, -1, 5804, 5799, 5801, -1, 5804, 5793, 5799, -1, 5804, 5797, 5793, -1, 5808, 5807, 5809, -1, 5808, 5809, 5810, -1, 5808, 5810, 5803, -1, 5808, 5803, 5802, -1, 5808, 5804, 5807, -1, 5808, 5802, 5797, -1, 5808, 5797, 5804, -1, 5811, 5812, 5813, -1, 5811, 5813, 5814, -1, 5815, 5811, 5814, -1, 5816, 5812, 5811, -1, 5817, 5815, 5814, -1, 5818, 5815, 5817, -1, 5819, 5816, 5811, -1, 5820, 5818, 5817, -1, 5821, 5820, 5817, -1, 5822, 5816, 5819, -1, 5823, 5824, 5825, -1, 5823, 5825, 5822, -1, 5826, 5827, 5820, -1, 5826, 5820, 5821, -1, 5828, 5829, 5824, -1, 5830, 5829, 5828, -1, 5831, 5830, 5828, -1, 5832, 5827, 5826, -1, 5833, 5827, 5832, -1, 5834, 5831, 5835, -1, 5834, 5830, 5831, -1, 5836, 5833, 5832, -1, 5837, 5834, 5835, -1, 5838, 5839, 5833, -1, 5838, 5833, 5836, -1, 5840, 5839, 5838, -1, 5841, 5834, 5837, -1, 5823, 5828, 5824, -1, 5842, 5819, 5843, -1, 5842, 5843, 5823, -1, 5842, 5822, 5819, -1, 5842, 5823, 5822, -1, 5844, 5837, 5839, -1, 5844, 5840, 5841, -1, 5844, 5841, 5837, -1, 5844, 5839, 5840, -1, 5845, 5846, 5847, -1, 5848, 5849, 5850, -1, 5851, 5852, 5853, -1, 5851, 5853, 5846, -1, 5851, 5845, 5854, -1, 5851, 5846, 5845, -1, 5855, 5856, 5852, -1, 5855, 5852, 5851, -1, 5857, 5854, 5858, -1, 5857, 5858, 5859, -1, 5857, 5851, 5854, -1, 5860, 5861, 5848, -1, 5860, 5850, 5856, -1, 5860, 5856, 5855, -1, 5860, 5848, 5850, -1, 5862, 5863, 5864, -1, 5862, 5859, 5865, -1, 5862, 5865, 5863, -1, 5862, 5857, 5859, -1, 5862, 5851, 5857, -1, 5862, 5855, 5851, -1, 5866, 5864, 5867, -1, 5866, 5867, 5868, -1, 5866, 5868, 5861, -1, 5866, 5855, 5862, -1, 5866, 5862, 5864, -1, 5866, 5861, 5860, -1, 5866, 5860, 5855, -1, 5869, 5870, 5871, -1, 5869, 5871, 5872, -1, 5873, 5869, 5872, -1, 5874, 5870, 5869, -1, 5875, 5873, 5872, -1, 5876, 5873, 5875, -1, 5877, 5874, 5869, -1, 5878, 5875, 5879, -1, 5878, 5876, 5875, -1, 5880, 5874, 5877, -1, 5881, 5882, 5883, -1, 5884, 5885, 5878, -1, 5884, 5878, 5879, -1, 5886, 5887, 5882, -1, 5888, 5887, 5886, -1, 5889, 5888, 5886, -1, 5890, 5885, 5884, -1, 5891, 5885, 5890, -1, 5892, 5889, 5893, -1, 5892, 5888, 5889, -1, 5894, 5891, 5890, -1, 5895, 5892, 5893, -1, 5896, 5897, 5891, -1, 5896, 5891, 5894, -1, 5898, 5897, 5896, -1, 5899, 5892, 5895, -1, 5881, 5886, 5882, -1, 5900, 5877, 5901, -1, 5900, 5901, 5881, -1, 5900, 5883, 5880, -1, 5900, 5881, 5883, -1, 5900, 5880, 5877, -1, 5902, 5895, 5897, -1, 5902, 5898, 5899, -1, 5902, 5899, 5895, -1, 5902, 5897, 5898, -1, 5903, 5904, 5905, -1, 5903, 5905, 5906, -1, 5907, 5903, 5906, -1, 5908, 5904, 5903, -1, 5909, 5907, 5906, -1, 5910, 5907, 5909, -1, 5911, 5908, 5903, -1, 5912, 5909, 5913, -1, 5912, 5910, 5909, -1, 5914, 5908, 5911, -1, 5915, 5916, 5917, -1, 5918, 5919, 5912, -1, 5918, 5912, 5913, -1, 5920, 5921, 5916, -1, 5922, 5921, 5920, -1, 5923, 5922, 5920, -1, 5924, 5919, 5918, -1, 5925, 5919, 5924, -1, 5926, 5923, 5927, -1, 5926, 5922, 5923, -1, 5928, 5925, 5924, -1, 5929, 5926, 5927, -1, 5930, 5931, 5925, -1, 5930, 5925, 5928, -1, 5932, 5931, 5930, -1, 5933, 5926, 5929, -1, 5915, 5920, 5916, -1, 5934, 5911, 5935, -1, 5934, 5935, 5915, -1, 5934, 5917, 5914, -1, 5934, 5915, 5917, -1, 5934, 5914, 5911, -1, 5936, 5929, 5931, -1, 5936, 5932, 5933, -1, 5936, 5933, 5929, -1, 5936, 5931, 5932, -1, 5937, 5938, 5939, -1, 5937, 5939, 5940, -1, 5941, 5937, 5940, -1, 5942, 5938, 5937, -1, 5943, 5941, 5940, -1, 5944, 5941, 5943, -1, 5945, 5942, 5937, -1, 5946, 5944, 5943, -1, 5947, 5946, 5943, -1, 5948, 5942, 5945, -1, 5949, 5950, 5951, -1, 5949, 5951, 5948, -1, 5952, 5953, 5946, -1, 5952, 5946, 5947, -1, 5954, 5955, 5950, -1, 5956, 5955, 5954, -1, 5957, 5956, 5954, -1, 5958, 5953, 5952, -1, 5959, 5953, 5958, -1, 5960, 5957, 5961, -1, 5960, 5956, 5957, -1, 5962, 5959, 5958, -1, 5963, 5960, 5961, -1, 5964, 5965, 5959, -1, 5964, 5959, 5962, -1, 5966, 5965, 5964, -1, 5967, 5960, 5963, -1, 5949, 5954, 5950, -1, 5968, 5945, 5969, -1, 5968, 5969, 5949, -1, 5968, 5948, 5945, -1, 5968, 5949, 5948, -1, 5970, 5963, 5965, -1, 5970, 5966, 5967, -1, 5970, 5967, 5963, -1, 5970, 5965, 5966, -1, 5971, 5972, 5973, -1, 5974, 5975, 5976, -1, 5977, 5978, 5979, -1, 5977, 5979, 5972, -1, 5977, 5971, 5980, -1, 5977, 5972, 5971, -1, 5981, 5982, 5978, -1, 5981, 5978, 5977, -1, 5983, 5980, 5984, -1, 5983, 5984, 5985, -1, 5983, 5977, 5980, -1, 5986, 5987, 5974, -1, 5986, 5976, 5982, -1, 5986, 5982, 5981, -1, 5986, 5974, 5976, -1, 5988, 5989, 5990, -1, 5988, 5985, 5991, -1, 5988, 5991, 5989, -1, 5988, 5983, 5985, -1, 5988, 5977, 5983, -1, 5988, 5981, 5977, -1, 5992, 5990, 5993, -1, 5992, 5993, 5994, -1, 5992, 5994, 5987, -1, 5992, 5981, 5988, -1, 5992, 5988, 5990, -1, 5992, 5987, 5986, -1, 5992, 5986, 5981, -1, 5995, 5996, 5997, -1, 5998, 5999, 6000, -1, 6001, 6002, 6003, -1, 6001, 6003, 5996, -1, 6001, 5995, 6004, -1, 6001, 5996, 5995, -1, 6005, 6006, 6002, -1, 6005, 6002, 6001, -1, 6007, 6004, 6008, -1, 6007, 6008, 6009, -1, 6007, 6001, 6004, -1, 6010, 6011, 5998, -1, 6010, 6000, 6006, -1, 6010, 6006, 6005, -1, 6010, 5998, 6000, -1, 6012, 6009, 6013, -1, 6012, 6013, 6014, -1, 6012, 6014, 6015, -1, 6012, 6007, 6009, -1, 6012, 6001, 6007, -1, 6012, 6005, 6001, -1, 6016, 6015, 6017, -1, 6016, 6017, 6018, -1, 6016, 6018, 6011, -1, 6016, 6011, 6010, -1, 6016, 6012, 6015, -1, 6016, 6010, 6005, -1, 6016, 6005, 6012, -1, 6019, 6020, 6021, -1, 6022, 6023, 6024, -1, 6025, 6021, 6026, -1, 6025, 6026, 6027, -1, 6025, 6028, 6019, -1, 6025, 6019, 6021, -1, 6029, 6027, 6023, -1, 6029, 6022, 6030, -1, 6029, 6030, 6028, -1, 6029, 6025, 6027, -1, 6029, 6023, 6022, -1, 6029, 6028, 6025, -1, 6031, 6032, 6033, -1, 6034, 6035, 6036, -1, 6037, 6034, 6036, -1, 6038, 6039, 6040, -1, 6038, 6040, 6041, -1, 6038, 6041, 6042, -1, 6043, 6044, 6045, -1, 6043, 6045, 6039, -1, 6043, 6039, 6038, -1, 6046, 6042, 6032, -1, 6046, 6031, 6047, -1, 6046, 6032, 6031, -1, 6046, 6038, 6042, -1, 6048, 6049, 6050, -1, 6048, 6050, 6051, -1, 6048, 6051, 6044, -1, 6048, 6044, 6043, -1, 6052, 6047, 6053, -1, 6052, 6046, 6047, -1, 6052, 6038, 6046, -1, 6052, 6043, 6038, -1, 6054, 6053, 6035, -1, 6054, 6034, 6049, -1, 6054, 6052, 6053, -1, 6054, 6048, 6043, -1, 6054, 6043, 6052, -1, 6054, 6035, 6034, -1, 6054, 6049, 6048, -1, 6055, 6056, 6057, -1, 6058, 6059, 6060, -1, 6061, 6059, 6058, -1, 6062, 6063, 6064, -1, 6062, 6064, 6065, -1, 6062, 6065, 6066, -1, 6067, 6068, 6063, -1, 6067, 6069, 6068, -1, 6067, 6063, 6062, -1, 6070, 6066, 6056, -1, 6070, 6055, 6071, -1, 6070, 6062, 6066, -1, 6070, 6056, 6055, -1, 6072, 6073, 6074, -1, 6072, 6074, 6075, -1, 6072, 6075, 6069, -1, 6072, 6069, 6067, -1, 6076, 6071, 6077, -1, 6076, 6070, 6071, -1, 6076, 6062, 6070, -1, 6076, 6067, 6062, -1, 6078, 6077, 6060, -1, 6078, 6059, 6073, -1, 6078, 6072, 6067, -1, 6078, 6076, 6077, -1, 6078, 6067, 6076, -1, 6078, 6060, 6059, -1, 6078, 6073, 6072, -1, 6079, 6080, 6081, -1, 6082, 6083, 6084, -1, 6085, 6083, 6082, -1, 6086, 6087, 6088, -1, 6086, 6088, 6089, -1, 6086, 6089, 6090, -1, 6091, 6092, 6087, -1, 6091, 6093, 6092, -1, 6091, 6087, 6086, -1, 6094, 6090, 6080, -1, 6094, 6079, 6095, -1, 6094, 6086, 6090, -1, 6094, 6080, 6079, -1, 6096, 6097, 6098, -1, 6096, 6098, 6099, -1, 6096, 6099, 6093, -1, 6096, 6093, 6091, -1, 6100, 6095, 6101, -1, 6100, 6094, 6095, -1, 6100, 6086, 6094, -1, 6100, 6091, 6086, -1, 6102, 6101, 6084, -1, 6102, 6083, 6097, -1, 6102, 6096, 6091, -1, 6102, 6100, 6101, -1, 6102, 6091, 6100, -1, 6102, 6084, 6083, -1, 6102, 6097, 6096, -1, 6103, 6104, 6105, -1, 6106, 6107, 6108, -1, 6109, 6107, 6106, -1, 6110, 6111, 6112, -1, 6110, 6112, 6113, -1, 6110, 6113, 6114, -1, 6115, 6116, 6117, -1, 6115, 6117, 6111, -1, 6115, 6111, 6110, -1, 6118, 6114, 6104, -1, 6118, 6103, 6119, -1, 6118, 6104, 6103, -1, 6118, 6110, 6114, -1, 6120, 6121, 6122, -1, 6120, 6122, 6123, -1, 6120, 6123, 6116, -1, 6120, 6116, 6115, -1, 6124, 6119, 6125, -1, 6124, 6118, 6119, -1, 6124, 6110, 6118, -1, 6124, 6115, 6110, -1, 6126, 6125, 6108, -1, 6126, 6107, 6121, -1, 6126, 6124, 6125, -1, 6126, 6120, 6115, -1, 6126, 6115, 6124, -1, 6126, 6108, 6107, -1, 6126, 6121, 6120, -1, 6127, 6128, 6129, -1, 6130, 6131, 6132, -1, 6133, 6134, 6135, -1, 6133, 6135, 6128, -1, 6133, 6127, 6136, -1, 6133, 6128, 6127, -1, 6137, 6138, 6134, -1, 6137, 6134, 6133, -1, 6139, 6136, 6140, -1, 6139, 6140, 6141, -1, 6139, 6133, 6136, -1, 6142, 6143, 6130, -1, 6142, 6132, 6138, -1, 6142, 6138, 6137, -1, 6142, 6130, 6132, -1, 6144, 6141, 6145, -1, 6144, 6145, 6146, -1, 6144, 6146, 6147, -1, 6144, 6139, 6141, -1, 6144, 6133, 6139, -1, 6144, 6137, 6133, -1, 6148, 6147, 6149, -1, 6148, 6149, 6150, -1, 6148, 6150, 6143, -1, 6148, 6143, 6142, -1, 6148, 6144, 6147, -1, 6148, 6142, 6137, -1, 6148, 6137, 6144, -1, 6151, 6152, 6153, -1, 6151, 6153, 6154, -1, 6155, 6151, 6154, -1, 6156, 6152, 6151, -1, 6157, 6155, 6154, -1, 6158, 6155, 6157, -1, 6159, 6156, 6151, -1, 6160, 6158, 6157, -1, 6161, 6160, 6157, -1, 6162, 6156, 6159, -1, 6163, 6164, 6165, -1, 6163, 6165, 6162, -1, 6166, 6167, 6160, -1, 6166, 6160, 6161, -1, 6168, 6169, 6164, -1, 6170, 6169, 6168, -1, 6171, 6170, 6168, -1, 6172, 6167, 6166, -1, 6173, 6167, 6172, -1, 6174, 6171, 6175, -1, 6174, 6170, 6171, -1, 6176, 6173, 6172, -1, 6177, 6174, 6175, -1, 6178, 6179, 6173, -1, 6178, 6173, 6176, -1, 6180, 6179, 6178, -1, 6181, 6174, 6177, -1, 6163, 6168, 6164, -1, 6182, 6159, 6183, -1, 6182, 6183, 6163, -1, 6182, 6162, 6159, -1, 6182, 6163, 6162, -1, 6184, 6177, 6179, -1, 6184, 6180, 6181, -1, 6184, 6181, 6177, -1, 6184, 6179, 6180, -1, 6185, 6186, 6187, -1, 6185, 6187, 6188, -1, 6189, 6185, 6188, -1, 6190, 6186, 6185, -1, 6191, 6189, 6188, -1, 6192, 6189, 6191, -1, 6193, 6190, 6185, -1, 6194, 6191, 6195, -1, 6194, 6192, 6191, -1, 6196, 6190, 6193, -1, 6197, 6198, 6199, -1, 6200, 6201, 6194, -1, 6200, 6194, 6195, -1, 6202, 6203, 6198, -1, 6204, 6203, 6202, -1, 6205, 6204, 6202, -1, 6206, 6201, 6200, -1, 6207, 6201, 6206, -1, 6208, 6205, 6209, -1, 6208, 6204, 6205, -1, 6210, 6207, 6206, -1, 6211, 6208, 6209, -1, 6212, 6213, 6207, -1, 6212, 6207, 6210, -1, 6214, 6213, 6212, -1, 6215, 6208, 6211, -1, 6197, 6202, 6198, -1, 6216, 6193, 6217, -1, 6216, 6217, 6197, -1, 6216, 6199, 6196, -1, 6216, 6197, 6199, -1, 6216, 6196, 6193, -1, 6218, 6211, 6213, -1, 6218, 6214, 6215, -1, 6218, 6215, 6211, -1, 6218, 6213, 6214, -1, 6219, 6220, 6221, -1, 6222, 6223, 6224, -1, 6225, 6226, 6227, -1, 6225, 6227, 6220, -1, 6225, 6219, 6228, -1, 6225, 6220, 6219, -1, 6229, 6230, 6226, -1, 6229, 6226, 6225, -1, 6231, 6228, 6232, -1, 6231, 6232, 6233, -1, 6231, 6225, 6228, -1, 6234, 6235, 6222, -1, 6234, 6224, 6230, -1, 6234, 6230, 6229, -1, 6234, 6222, 6224, -1, 6236, 6237, 6238, -1, 6236, 6233, 6239, -1, 6236, 6239, 6237, -1, 6236, 6231, 6233, -1, 6236, 6225, 6231, -1, 6236, 6229, 6225, -1, 6240, 6238, 6241, -1, 6240, 6241, 6242, -1, 6240, 6242, 6235, -1, 6240, 6229, 6236, -1, 6240, 6236, 6238, -1, 6240, 6235, 6234, -1, 6240, 6234, 6229, -1, 6243, 6244, 6245, -1, 6246, 6247, 6248, -1, 6249, 6245, 6250, -1, 6249, 6250, 6251, -1, 6249, 6252, 6243, -1, 6249, 6243, 6245, -1, 6253, 6251, 6247, -1, 6253, 6246, 6254, -1, 6253, 6254, 6252, -1, 6253, 6249, 6251, -1, 6253, 6247, 6246, -1, 6253, 6252, 6249, -1, 6255, 6256, 6257, -1, 6258, 6259, 6260, -1, 6261, 6259, 6258, -1, 6262, 6263, 6264, -1, 6262, 6264, 6265, -1, 6262, 6265, 6266, -1, 6267, 6268, 6263, -1, 6267, 6269, 6268, -1, 6267, 6263, 6262, -1, 6270, 6266, 6256, -1, 6270, 6255, 6271, -1, 6270, 6262, 6266, -1, 6270, 6256, 6255, -1, 6272, 6273, 6274, -1, 6272, 6274, 6275, -1, 6272, 6275, 6269, -1, 6272, 6269, 6267, -1, 6276, 6271, 6277, -1, 6276, 6270, 6271, -1, 6276, 6262, 6270, -1, 6276, 6267, 6262, -1, 6278, 6277, 6260, -1, 6278, 6259, 6273, -1, 6278, 6272, 6267, -1, 6278, 6276, 6277, -1, 6278, 6267, 6276, -1, 6278, 6260, 6259, -1, 6278, 6273, 6272, -1, 6279, 6280, 6281, -1, 6282, 6283, 6284, -1, 6285, 6283, 6282, -1, 6286, 6287, 6288, -1, 6286, 6288, 6289, -1, 6286, 6289, 6290, -1, 6291, 6292, 6287, -1, 6291, 6293, 6292, -1, 6291, 6287, 6286, -1, 6294, 6290, 6280, -1, 6294, 6279, 6295, -1, 6294, 6286, 6290, -1, 6294, 6280, 6279, -1, 6296, 6297, 6298, -1, 6296, 6298, 6299, -1, 6296, 6299, 6293, -1, 6296, 6293, 6291, -1, 6300, 6295, 6301, -1, 6300, 6294, 6295, -1, 6300, 6286, 6294, -1, 6300, 6291, 6286, -1, 6302, 6301, 6284, -1, 6302, 6283, 6297, -1, 6302, 6296, 6291, -1, 6302, 6300, 6301, -1, 6302, 6291, 6300, -1, 6302, 6284, 6283, -1, 6302, 6297, 6296, -1, 6303, 6304, 6305, -1, 6306, 6307, 6308, -1, 6309, 6306, 6308, -1, 6310, 6311, 6312, -1, 6310, 6312, 6313, -1, 6310, 6313, 6314, -1, 6315, 6316, 6317, -1, 6315, 6317, 6311, -1, 6315, 6311, 6310, -1, 6318, 6314, 6304, -1, 6318, 6303, 6319, -1, 6318, 6304, 6303, -1, 6318, 6310, 6314, -1, 6320, 6321, 6322, -1, 6320, 6322, 6323, -1, 6320, 6323, 6316, -1, 6320, 6316, 6315, -1, 6324, 6319, 6325, -1, 6324, 6318, 6319, -1, 6324, 6310, 6318, -1, 6324, 6315, 6310, -1, 6326, 6325, 6307, -1, 6326, 6306, 6321, -1, 6326, 6324, 6325, -1, 6326, 6320, 6315, -1, 6326, 6315, 6324, -1, 6326, 6307, 6306, -1, 6326, 6321, 6320, -1, 6327, 6328, 6329, -1, 6330, 6331, 6332, -1, 6333, 6331, 6330, -1, 6334, 6335, 6336, -1, 6334, 6336, 6337, -1, 6334, 6337, 6338, -1, 6339, 6340, 6341, -1, 6339, 6341, 6335, -1, 6339, 6335, 6334, -1, 6342, 6338, 6328, -1, 6342, 6327, 6343, -1, 6342, 6328, 6327, -1, 6342, 6334, 6338, -1, 6344, 6345, 6346, -1, 6344, 6346, 6347, -1, 6344, 6347, 6340, -1, 6344, 6340, 6339, -1, 6348, 6343, 6349, -1, 6348, 6342, 6343, -1, 6348, 6334, 6342, -1, 6348, 6339, 6334, -1, 6350, 6349, 6332, -1, 6350, 6331, 6345, -1, 6350, 6348, 6349, -1, 6350, 6344, 6339, -1, 6350, 6339, 6348, -1, 6350, 6332, 6331, -1, 6350, 6345, 6344, -1, 6351, 6352, 6353, -1, 6354, 6355, 6356, -1, 6357, 6358, 6359, -1, 6357, 6359, 6352, -1, 6357, 6351, 6360, -1, 6357, 6352, 6351, -1, 6361, 6362, 6358, -1, 6361, 6358, 6357, -1, 6363, 6360, 6364, -1, 6363, 6364, 6365, -1, 6363, 6357, 6360, -1, 6366, 6367, 6354, -1, 6366, 6356, 6362, -1, 6366, 6362, 6361, -1, 6366, 6354, 6356, -1, 6368, 6365, 6369, -1, 6368, 6369, 6370, -1, 6368, 6370, 6371, -1, 6368, 6363, 6365, -1, 6368, 6357, 6363, -1, 6368, 6361, 6357, -1, 6372, 6371, 6373, -1, 6372, 6373, 6374, -1, 6372, 6374, 6367, -1, 6372, 6367, 6366, -1, 6372, 6368, 6371, -1, 6372, 6366, 6361, -1, 6372, 6361, 6368, -1, 6375, 6376, 6377, -1, 6375, 6377, 6378, -1, 6379, 6375, 6378, -1, 6380, 6376, 6375, -1, 6381, 6379, 6378, -1, 6382, 6379, 6381, -1, 6383, 6380, 6375, -1, 6384, 6381, 6385, -1, 6384, 6382, 6381, -1, 6386, 6380, 6383, -1, 6387, 6388, 6389, -1, 6390, 6391, 6384, -1, 6390, 6384, 6385, -1, 6392, 6393, 6388, -1, 6394, 6393, 6392, -1, 6395, 6394, 6392, -1, 6396, 6391, 6390, -1, 6397, 6391, 6396, -1, 6398, 6395, 6399, -1, 6398, 6394, 6395, -1, 6400, 6397, 6396, -1, 6401, 6398, 6399, -1, 6402, 6403, 6397, -1, 6402, 6397, 6400, -1, 6404, 6403, 6402, -1, 6405, 6398, 6401, -1, 6387, 6392, 6388, -1, 6406, 6383, 6407, -1, 6406, 6407, 6387, -1, 6406, 6389, 6386, -1, 6406, 6387, 6389, -1, 6406, 6386, 6383, -1, 6408, 6401, 6403, -1, 6408, 6404, 6405, -1, 6408, 6405, 6401, -1, 6408, 6403, 6404, -1, 6409, 6410, 6411, -1, 6412, 6413, 6414, -1, 6415, 6416, 6417, -1, 6415, 6417, 6410, -1, 6415, 6409, 6418, -1, 6415, 6410, 6409, -1, 6419, 6420, 6416, -1, 6419, 6416, 6415, -1, 6421, 6418, 6422, -1, 6421, 6422, 6423, -1, 6421, 6415, 6418, -1, 6424, 6425, 6412, -1, 6424, 6414, 6420, -1, 6424, 6412, 6414, -1, 6424, 6420, 6419, -1, 6426, 6423, 6427, -1, 6426, 6427, 6428, -1, 6426, 6428, 6429, -1, 6426, 6421, 6423, -1, 6426, 6419, 6415, -1, 6426, 6415, 6421, -1, 6430, 6429, 6431, -1, 6430, 6431, 6432, -1, 6430, 6432, 6425, -1, 6430, 6426, 6429, -1, 6430, 6425, 6424, -1, 6430, 6424, 6419, -1, 6430, 6419, 6426, -1, 6433, 6434, 6435, -1, 6433, 6435, 6436, -1, 6437, 6433, 6436, -1, 6438, 6434, 6433, -1, 6439, 6437, 6436, -1, 6440, 6437, 6439, -1, 6441, 6438, 6433, -1, 6442, 6440, 6439, -1, 6443, 6442, 6439, -1, 6444, 6438, 6441, -1, 6445, 6446, 6447, -1, 6445, 6447, 6444, -1, 6448, 6449, 6442, -1, 6448, 6442, 6443, -1, 6450, 6451, 6446, -1, 6452, 6451, 6450, -1, 6453, 6452, 6450, -1, 6454, 6449, 6448, -1, 6455, 6449, 6454, -1, 6456, 6453, 6457, -1, 6456, 6452, 6453, -1, 6458, 6455, 6454, -1, 6459, 6456, 6457, -1, 6460, 6461, 6455, -1, 6460, 6455, 6458, -1, 6462, 6461, 6460, -1, 6463, 6456, 6459, -1, 6445, 6450, 6446, -1, 6464, 6441, 6465, -1, 6464, 6465, 6445, -1, 6464, 6444, 6441, -1, 6464, 6445, 6444, -1, 6466, 6459, 6461, -1, 6466, 6462, 6463, -1, 6466, 6463, 6459, -1, 6466, 6461, 6462, -1, 6467, 6468, 6469, -1, 6470, 6471, 6472, -1, 6473, 6471, 6470, -1, 6474, 6475, 6476, -1, 6474, 6476, 6477, -1, 6474, 6477, 6478, -1, 6479, 6480, 6475, -1, 6479, 6481, 6480, -1, 6479, 6475, 6474, -1, 6482, 6478, 6468, -1, 6482, 6467, 6483, -1, 6482, 6474, 6478, -1, 6482, 6468, 6467, -1, 6484, 6485, 6486, -1, 6484, 6486, 6487, -1, 6484, 6487, 6481, -1, 6484, 6481, 6479, -1, 6488, 6483, 6489, -1, 6488, 6482, 6483, -1, 6488, 6474, 6482, -1, 6488, 6479, 6474, -1, 6490, 6489, 6472, -1, 6490, 6471, 6485, -1, 6490, 6484, 6479, -1, 6490, 6488, 6489, -1, 6490, 6479, 6488, -1, 6490, 6472, 6471, -1, 6490, 6485, 6484, -1, 6491, 6492, 6493, -1, 6494, 6495, 6496, -1, 6497, 6495, 6494, -1, 6498, 6499, 6500, -1, 6498, 6500, 6501, -1, 6498, 6501, 6502, -1, 6503, 6504, 6505, -1, 6503, 6505, 6499, -1, 6503, 6499, 6498, -1, 6506, 6502, 6492, -1, 6506, 6491, 6507, -1, 6506, 6492, 6491, -1, 6506, 6498, 6502, -1, 6508, 6509, 6510, -1, 6508, 6510, 6511, -1, 6508, 6511, 6504, -1, 6508, 6504, 6503, -1, 6512, 6507, 6513, -1, 6512, 6506, 6507, -1, 6512, 6498, 6506, -1, 6512, 6503, 6498, -1, 6514, 6513, 6496, -1, 6514, 6495, 6509, -1, 6514, 6512, 6513, -1, 6514, 6508, 6503, -1, 6514, 6503, 6512, -1, 6514, 6496, 6495, -1, 6514, 6509, 6508, -1, 6515, 6516, 6517, -1, 6518, 6519, 6520, -1, 6521, 6519, 6518, -1, 6522, 6523, 6524, -1, 6522, 6524, 6525, -1, 6522, 6525, 6526, -1, 6527, 6528, 6529, -1, 6527, 6529, 6523, -1, 6527, 6523, 6522, -1, 6530, 6526, 6516, -1, 6530, 6515, 6531, -1, 6530, 6516, 6515, -1, 6530, 6522, 6526, -1, 6532, 6533, 6534, -1, 6532, 6534, 6535, -1, 6532, 6535, 6528, -1, 6532, 6528, 6527, -1, 6536, 6531, 6537, -1, 6536, 6530, 6531, -1, 6536, 6522, 6530, -1, 6536, 6527, 6522, -1, 6538, 6537, 6520, -1, 6538, 6519, 6533, -1, 6538, 6536, 6537, -1, 6538, 6532, 6527, -1, 6538, 6527, 6536, -1, 6538, 6520, 6519, -1, 6538, 6533, 6532, -1, 6539, 6540, 6541, -1, 6542, 6543, 6544, -1, 6545, 6541, 6546, -1, 6545, 6546, 6547, -1, 6545, 6548, 6539, -1, 6545, 6539, 6541, -1, 6549, 6547, 6543, -1, 6549, 6542, 6550, -1, 6549, 6550, 6548, -1, 6549, 6545, 6547, -1, 6549, 6543, 6542, -1, 6549, 6548, 6545, -1, 6551, 6552, 6553, -1, 6554, 6555, 6556, -1, 6557, 6554, 6556, -1, 6558, 6559, 6560, -1, 6558, 6560, 6561, -1, 6558, 6561, 6562, -1, 6563, 6564, 6565, -1, 6563, 6565, 6559, -1, 6563, 6559, 6558, -1, 6566, 6562, 6552, -1, 6566, 6551, 6567, -1, 6566, 6552, 6551, -1, 6566, 6558, 6562, -1, 6568, 6569, 6570, -1, 6568, 6570, 6571, -1, 6568, 6571, 6564, -1, 6568, 6564, 6563, -1, 6572, 6567, 6573, -1, 6572, 6566, 6567, -1, 6572, 6558, 6566, -1, 6572, 6563, 6558, -1, 6574, 6573, 6555, -1, 6574, 6554, 6569, -1, 6574, 6572, 6573, -1, 6574, 6568, 6563, -1, 6574, 6563, 6572, -1, 6574, 6555, 6554, -1, 6574, 6569, 6568, -1, 6575, 6576, 6577, -1, 6578, 6579, 6580, -1, 6581, 6577, 6582, -1, 6581, 6582, 6583, -1, 6581, 6584, 6575, -1, 6581, 6575, 6577, -1, 6585, 6583, 6579, -1, 6585, 6578, 6586, -1, 6585, 6586, 6584, -1, 6585, 6581, 6583, -1, 6585, 6579, 6578, -1, 6585, 6584, 6581, -1, 6587, 6588, 6589, -1, 6590, 6591, 6592, -1, 6593, 6591, 6590, -1, 6594, 6595, 6596, -1, 6594, 6596, 6597, -1, 6594, 6597, 6598, -1, 6599, 6600, 6595, -1, 6599, 6601, 6600, -1, 6599, 6595, 6594, -1, 6602, 6598, 6588, -1, 6602, 6587, 6603, -1, 6602, 6594, 6598, -1, 6602, 6588, 6587, -1, 6604, 6605, 6606, -1, 6604, 6606, 6607, -1, 6604, 6607, 6601, -1, 6604, 6601, 6599, -1, 6608, 6603, 6609, -1, 6608, 6602, 6603, -1, 6608, 6594, 6602, -1, 6608, 6599, 6594, -1, 6610, 6609, 6592, -1, 6610, 6591, 6605, -1, 6610, 6604, 6599, -1, 6610, 6608, 6609, -1, 6610, 6599, 6608, -1, 6610, 6592, 6591, -1, 6610, 6605, 6604, -1, 6611, 6612, 6613, -1, 6614, 6615, 6616, -1, 6617, 6615, 6614, -1, 6618, 6619, 6620, -1, 6618, 6620, 6621, -1, 6618, 6621, 6622, -1, 6623, 6624, 6625, -1, 6623, 6625, 6619, -1, 6623, 6619, 6618, -1, 6626, 6622, 6612, -1, 6626, 6611, 6627, -1, 6626, 6612, 6611, -1, 6626, 6618, 6622, -1, 6628, 6629, 6630, -1, 6628, 6630, 6631, -1, 6628, 6631, 6624, -1, 6628, 6624, 6623, -1, 6632, 6627, 6633, -1, 6632, 6626, 6627, -1, 6632, 6618, 6626, -1, 6632, 6623, 6618, -1, 6634, 6633, 6616, -1, 6634, 6615, 6629, -1, 6634, 6632, 6633, -1, 6634, 6628, 6623, -1, 6634, 6623, 6632, -1, 6634, 6616, 6615, -1, 6634, 6629, 6628, -1, 6635, 6636, 6637, -1, 6638, 6639, 6640, -1, 6641, 6639, 6638, -1, 6642, 6643, 6644, -1, 6642, 6644, 6645, -1, 6642, 6645, 6646, -1, 6647, 6648, 6643, -1, 6647, 6649, 6648, -1, 6647, 6643, 6642, -1, 6650, 6646, 6636, -1, 6650, 6635, 6651, -1, 6650, 6642, 6646, -1, 6650, 6636, 6635, -1, 6652, 6653, 6654, -1, 6652, 6654, 6655, -1, 6652, 6655, 6649, -1, 6652, 6649, 6647, -1, 6656, 6651, 6657, -1, 6656, 6650, 6651, -1, 6656, 6642, 6650, -1, 6656, 6647, 6642, -1, 6658, 6657, 6640, -1, 6658, 6639, 6653, -1, 6658, 6652, 6647, -1, 6658, 6656, 6657, -1, 6658, 6647, 6656, -1, 6658, 6640, 6639, -1, 6658, 6653, 6652, -1, 6659, 6660, 6661, -1, 6662, 6663, 6664, -1, 6665, 6662, 6664, -1, 6666, 6667, 6668, -1, 6666, 6668, 6669, -1, 6666, 6669, 6670, -1, 6671, 6672, 6673, -1, 6671, 6673, 6667, -1, 6671, 6667, 6666, -1, 6674, 6670, 6660, -1, 6674, 6659, 6675, -1, 6674, 6660, 6659, -1, 6674, 6666, 6670, -1, 6676, 6677, 6678, -1, 6676, 6678, 6679, -1, 6676, 6679, 6672, -1, 6676, 6672, 6671, -1, 6680, 6675, 6681, -1, 6680, 6674, 6675, -1, 6680, 6666, 6674, -1, 6680, 6671, 6666, -1, 6682, 6681, 6663, -1, 6682, 6662, 6677, -1, 6682, 6680, 6681, -1, 6682, 6676, 6671, -1, 6682, 6671, 6680, -1, 6682, 6663, 6662, -1, 6682, 6677, 6676, -1, 6683, 6684, 6685, -1, 6686, 6687, 6688, -1, 6689, 6690, 6691, -1, 6689, 6691, 6684, -1, 6689, 6683, 6692, -1, 6689, 6684, 6683, -1, 6693, 6694, 6690, -1, 6693, 6690, 6689, -1, 6695, 6692, 6696, -1, 6695, 6696, 6697, -1, 6695, 6689, 6692, -1, 6698, 6699, 6686, -1, 6698, 6688, 6694, -1, 6698, 6694, 6693, -1, 6698, 6686, 6688, -1, 6700, 6697, 6701, -1, 6700, 6701, 6702, -1, 6700, 6702, 6703, -1, 6700, 6695, 6697, -1, 6700, 6689, 6695, -1, 6700, 6693, 6689, -1, 6704, 6703, 6705, -1, 6704, 6705, 6706, -1, 6704, 6706, 6699, -1, 6704, 6699, 6698, -1, 6704, 6700, 6703, -1, 6704, 6698, 6693, -1, 6704, 6693, 6700, -1, 6707, 6708, 6709, -1, 6707, 6709, 6710, -1, 6711, 6707, 6710, -1, 6712, 6708, 6707, -1, 6713, 6711, 6710, -1, 6714, 6711, 6713, -1, 6715, 6712, 6707, -1, 6716, 6714, 6713, -1, 6717, 6716, 6713, -1, 6718, 6712, 6715, -1, 6719, 6720, 6721, -1, 6719, 6721, 6718, -1, 6722, 6723, 6716, -1, 6722, 6716, 6717, -1, 6724, 6725, 6720, -1, 6726, 6725, 6724, -1, 6727, 6726, 6724, -1, 6728, 6723, 6722, -1, 6729, 6723, 6728, -1, 6730, 6727, 6731, -1, 6730, 6726, 6727, -1, 6732, 6729, 6728, -1, 6733, 6730, 6731, -1, 6734, 6735, 6729, -1, 6734, 6729, 6732, -1, 6736, 6735, 6734, -1, 6737, 6730, 6733, -1, 6719, 6724, 6720, -1, 6738, 6715, 6739, -1, 6738, 6739, 6719, -1, 6738, 6718, 6715, -1, 6738, 6719, 6718, -1, 6740, 6733, 6735, -1, 6740, 6736, 6737, -1, 6740, 6737, 6733, -1, 6740, 6735, 6736, -1, 6741, 6742, 6743, -1, 6744, 6745, 6746, -1, 6747, 6748, 6749, -1, 6747, 6749, 6742, -1, 6747, 6741, 6750, -1, 6747, 6742, 6741, -1, 6751, 6752, 6748, -1, 6751, 6748, 6747, -1, 6753, 6750, 6754, -1, 6753, 6754, 6755, -1, 6753, 6747, 6750, -1, 6756, 6757, 6744, -1, 6756, 6746, 6752, -1, 6756, 6752, 6751, -1, 6756, 6744, 6746, -1, 6758, 6759, 6760, -1, 6758, 6755, 6761, -1, 6758, 6761, 6759, -1, 6758, 6753, 6755, -1, 6758, 6747, 6753, -1, 6758, 6751, 6747, -1, 6762, 6760, 6763, -1, 6762, 6763, 6764, -1, 6762, 6764, 6757, -1, 6762, 6751, 6758, -1, 6762, 6758, 6760, -1, 6762, 6757, 6756, -1, 6762, 6756, 6751, -1, 6765, 6766, 6767, -1, 6765, 6767, 6768, -1, 6769, 6765, 6768, -1, 6770, 6766, 6765, -1, 6771, 6769, 6768, -1, 6772, 6769, 6771, -1, 6773, 6770, 6765, -1, 6774, 6771, 6775, -1, 6774, 6772, 6771, -1, 6776, 6770, 6773, -1, 6777, 6778, 6779, -1, 6780, 6781, 6774, -1, 6780, 6774, 6775, -1, 6782, 6783, 6778, -1, 6784, 6783, 6782, -1, 6785, 6784, 6782, -1, 6786, 6781, 6780, -1, 6787, 6781, 6786, -1, 6788, 6785, 6789, -1, 6788, 6784, 6785, -1, 6790, 6787, 6786, -1, 6791, 6788, 6789, -1, 6792, 6793, 6787, -1, 6792, 6787, 6790, -1, 6794, 6793, 6792, -1, 6795, 6788, 6791, -1, 6777, 6782, 6778, -1, 6796, 6773, 6797, -1, 6796, 6797, 6777, -1, 6796, 6779, 6776, -1, 6796, 6777, 6779, -1, 6796, 6776, 6773, -1, 6798, 6791, 6793, -1, 6798, 6794, 6795, -1, 6798, 6795, 6791, -1, 6798, 6793, 6794, -1, 6799, 6800, 6801, -1, 6802, 6803, 6804, -1, 6805, 6803, 6802, -1, 6806, 6807, 6808, -1, 6806, 6808, 6809, -1, 6806, 6809, 6810, -1, 6811, 6812, 6813, -1, 6811, 6813, 6807, -1, 6811, 6807, 6806, -1, 6814, 6810, 6800, -1, 6814, 6799, 6815, -1, 6814, 6800, 6799, -1, 6814, 6806, 6810, -1, 6816, 6817, 6818, -1, 6816, 6818, 6819, -1, 6816, 6819, 6812, -1, 6816, 6812, 6811, -1, 6820, 6815, 6821, -1, 6820, 6814, 6815, -1, 6820, 6806, 6814, -1, 6820, 6811, 6806, -1, 6822, 6821, 6804, -1, 6822, 6803, 6817, -1, 6822, 6820, 6821, -1, 6822, 6816, 6811, -1, 6822, 6811, 6820, -1, 6822, 6804, 6803, -1, 6822, 6817, 6816, -1, 6823, 6824, 6825, -1, 6826, 6827, 6828, -1, 6829, 6827, 6826, -1, 6830, 6831, 6832, -1, 6830, 6832, 6833, -1, 6830, 6833, 6834, -1, 6835, 6836, 6831, -1, 6835, 6837, 6836, -1, 6835, 6831, 6830, -1, 6838, 6834, 6824, -1, 6838, 6823, 6839, -1, 6838, 6830, 6834, -1, 6838, 6824, 6823, -1, 6840, 6841, 6842, -1, 6840, 6842, 6843, -1, 6840, 6843, 6837, -1, 6840, 6837, 6835, -1, 6844, 6839, 6845, -1, 6844, 6838, 6839, -1, 6844, 6830, 6838, -1, 6844, 6835, 6830, -1, 6846, 6845, 6828, -1, 6846, 6827, 6841, -1, 6846, 6840, 6835, -1, 6846, 6844, 6845, -1, 6846, 6835, 6844, -1, 6846, 6828, 6827, -1, 6846, 6841, 6840, -1, 6847, 6848, 6849, -1, 6850, 6851, 6852, -1, 6853, 6850, 6852, -1, 6854, 6855, 6856, -1, 6854, 6856, 6857, -1, 6854, 6857, 6858, -1, 6859, 6860, 6855, -1, 6859, 6861, 6860, -1, 6859, 6855, 6854, -1, 6862, 6858, 6848, -1, 6862, 6847, 6863, -1, 6862, 6854, 6858, -1, 6862, 6848, 6847, -1, 6864, 6865, 6866, -1, 6864, 6866, 6867, -1, 6864, 6867, 6861, -1, 6864, 6861, 6859, -1, 6868, 6863, 6869, -1, 6868, 6862, 6863, -1, 6868, 6854, 6862, -1, 6868, 6859, 6854, -1, 6870, 6869, 6851, -1, 6870, 6850, 6865, -1, 6870, 6864, 6859, -1, 6870, 6868, 6869, -1, 6870, 6859, 6868, -1, 6870, 6851, 6850, -1, 6870, 6865, 6864, -1, 6871, 6872, 6873, -1, 6874, 6875, 6876, -1, 6877, 6875, 6874, -1, 6878, 6879, 6880, -1, 6878, 6880, 6881, -1, 6878, 6881, 6882, -1, 6883, 6884, 6885, -1, 6883, 6885, 6879, -1, 6883, 6879, 6878, -1, 6886, 6882, 6872, -1, 6886, 6871, 6887, -1, 6886, 6872, 6871, -1, 6886, 6878, 6882, -1, 6888, 6889, 6890, -1, 6888, 6890, 6891, -1, 6888, 6891, 6884, -1, 6888, 6884, 6883, -1, 6892, 6887, 6893, -1, 6892, 6886, 6887, -1, 6892, 6878, 6886, -1, 6892, 6883, 6878, -1, 6894, 6893, 6876, -1, 6894, 6875, 6889, -1, 6894, 6892, 6893, -1, 6894, 6888, 6883, -1, 6894, 6883, 6892, -1, 6894, 6876, 6875, -1, 6894, 6889, 6888, -1, 6895, 6896, 6897, -1, 6898, 6899, 6900, -1, 6901, 6902, 6903, -1, 6901, 6903, 6895, -1, 6901, 6897, 6904, -1, 6901, 6895, 6897, -1, 6905, 6906, 6900, -1, 6905, 6899, 6902, -1, 6905, 6904, 6906, -1, 6905, 6901, 6904, -1, 6905, 6902, 6901, -1, 6905, 6900, 6899, -1, 6907, 6908, 6909, -1, 6907, 6909, 6910, -1, 6911, 6907, 6910, -1, 6912, 6908, 6907, -1, 6913, 6911, 6910, -1, 6914, 6911, 6913, -1, 6915, 6912, 6907, -1, 6916, 6913, 6917, -1, 6916, 6914, 6913, -1, 6918, 6912, 6915, -1, 6919, 6920, 6921, -1, 6922, 6923, 6916, -1, 6922, 6916, 6917, -1, 6924, 6925, 6920, -1, 6926, 6925, 6924, -1, 6927, 6926, 6924, -1, 6928, 6923, 6922, -1, 6929, 6923, 6928, -1, 6930, 6927, 6931, -1, 6930, 6926, 6927, -1, 6932, 6929, 6928, -1, 6933, 6930, 6931, -1, 6934, 6935, 6929, -1, 6934, 6929, 6932, -1, 6936, 6935, 6934, -1, 6937, 6930, 6933, -1, 6919, 6924, 6920, -1, 6938, 6915, 6939, -1, 6938, 6939, 6919, -1, 6938, 6921, 6918, -1, 6938, 6919, 6921, -1, 6938, 6918, 6915, -1, 6940, 6933, 6935, -1, 6940, 6936, 6937, -1, 6940, 6937, 6933, -1, 6940, 6935, 6936, -1, 6941, 6942, 6943, -1, 6944, 6945, 6946, -1, 6947, 6948, 6949, -1, 6947, 6949, 6942, -1, 6947, 6941, 6950, -1, 6947, 6942, 6941, -1, 6951, 6952, 6948, -1, 6951, 6948, 6947, -1, 6953, 6950, 6954, -1, 6953, 6954, 6955, -1, 6953, 6947, 6950, -1, 6956, 6957, 6944, -1, 6956, 6946, 6952, -1, 6956, 6952, 6951, -1, 6956, 6944, 6946, -1, 6958, 6959, 6960, -1, 6958, 6955, 6961, -1, 6958, 6961, 6959, -1, 6958, 6953, 6955, -1, 6958, 6947, 6953, -1, 6958, 6951, 6947, -1, 6962, 6960, 6963, -1, 6962, 6963, 6964, -1, 6962, 6964, 6957, -1, 6962, 6951, 6958, -1, 6962, 6958, 6960, -1, 6962, 6957, 6956, -1, 6962, 6956, 6951, -1, 6965, 6966, 6967, -1, 6965, 6967, 6968, -1, 6969, 6965, 6968, -1, 6970, 6966, 6965, -1, 6971, 6969, 6968, -1, 6972, 6969, 6971, -1, 6973, 6970, 6965, -1, 6974, 6972, 6971, -1, 6975, 6974, 6971, -1, 6976, 6970, 6973, -1, 6977, 6978, 6979, -1, 6977, 6979, 6976, -1, 6980, 6981, 6974, -1, 6980, 6974, 6975, -1, 6982, 6983, 6978, -1, 6984, 6983, 6982, -1, 6985, 6984, 6982, -1, 6986, 6981, 6980, -1, 6987, 6981, 6986, -1, 6988, 6985, 6989, -1, 6988, 6984, 6985, -1, 6990, 6987, 6986, -1, 6991, 6988, 6989, -1, 6992, 6993, 6987, -1, 6992, 6987, 6990, -1, 6994, 6993, 6992, -1, 6995, 6988, 6991, -1, 6977, 6982, 6978, -1, 6996, 6973, 6997, -1, 6996, 6997, 6977, -1, 6996, 6976, 6973, -1, 6996, 6977, 6976, -1, 6998, 6991, 6993, -1, 6998, 6994, 6995, -1, 6998, 6995, 6991, -1, 6998, 6993, 6994, -1, 6999, 7000, 7001, -1, 7002, 7003, 7004, -1, 7005, 7006, 7007, -1, 7005, 7007, 7000, -1, 7005, 6999, 7008, -1, 7005, 7000, 6999, -1, 7009, 7010, 7006, -1, 7009, 7006, 7005, -1, 7011, 7008, 7012, -1, 7011, 7012, 7013, -1, 7011, 7005, 7008, -1, 7014, 7015, 7002, -1, 7014, 7004, 7010, -1, 7014, 7002, 7004, -1, 7014, 7010, 7009, -1, 7016, 7013, 7017, -1, 7016, 7017, 7018, -1, 7016, 7018, 7019, -1, 7016, 7011, 7013, -1, 7016, 7009, 7005, -1, 7016, 7005, 7011, -1, 7020, 7019, 7021, -1, 7020, 7021, 7022, -1, 7020, 7022, 7015, -1, 7020, 7016, 7019, -1, 7020, 7015, 7014, -1, 7020, 7014, 7009, -1, 7020, 7009, 7016, -1, 7023, 7024, 7025, -1, 7026, 7027, 7028, -1, 7029, 7026, 7028, -1, 7030, 7031, 7032, -1, 7030, 7032, 7033, -1, 7030, 7033, 7034, -1, 7035, 7036, 7037, -1, 7035, 7037, 7031, -1, 7035, 7031, 7030, -1, 7038, 7034, 7024, -1, 7038, 7023, 7039, -1, 7038, 7024, 7023, -1, 7038, 7030, 7034, -1, 7040, 7041, 7042, -1, 7040, 7042, 7043, -1, 7040, 7043, 7036, -1, 7040, 7036, 7035, -1, 7044, 7039, 7045, -1, 7044, 7038, 7039, -1, 7044, 7030, 7038, -1, 7044, 7035, 7030, -1, 7046, 7045, 7027, -1, 7046, 7026, 7041, -1, 7046, 7044, 7045, -1, 7046, 7040, 7035, -1, 7046, 7035, 7044, -1, 7046, 7027, 7026, -1, 7046, 7041, 7040, -1, 7047, 7048, 7049, -1, 7050, 7051, 7052, -1, 7053, 7051, 7050, -1, 7054, 7055, 7056, -1, 7054, 7056, 7057, -1, 7054, 7057, 7058, -1, 7059, 7060, 7061, -1, 7059, 7061, 7055, -1, 7059, 7055, 7054, -1, 7062, 7058, 7048, -1, 7062, 7047, 7063, -1, 7062, 7048, 7047, -1, 7062, 7054, 7058, -1, 7064, 7065, 7066, -1, 7064, 7066, 7067, -1, 7064, 7067, 7060, -1, 7064, 7060, 7059, -1, 7068, 7063, 7069, -1, 7068, 7062, 7063, -1, 7068, 7054, 7062, -1, 7068, 7059, 7054, -1, 7070, 7069, 7052, -1, 7070, 7051, 7065, -1, 7070, 7068, 7069, -1, 7070, 7064, 7059, -1, 7070, 7059, 7068, -1, 7070, 7052, 7051, -1, 7070, 7065, 7064, -1, 7071, 7072, 7073, -1, 7074, 7075, 7076, -1, 7077, 7078, 7079, -1, 7077, 7079, 7071, -1, 7077, 7073, 7080, -1, 7077, 7071, 7073, -1, 7081, 7082, 7076, -1, 7081, 7075, 7078, -1, 7081, 7080, 7082, -1, 7081, 7077, 7080, -1, 7081, 7078, 7077, -1, 7081, 7076, 7075, -1, 7083, 7084, 7085, -1, 7086, 7087, 7088, -1, 7089, 7087, 7086, -1, 7090, 7091, 7092, -1, 7090, 7092, 7093, -1, 7090, 7093, 7094, -1, 7095, 7096, 7091, -1, 7095, 7097, 7096, -1, 7095, 7091, 7090, -1, 7098, 7094, 7084, -1, 7098, 7083, 7099, -1, 7098, 7090, 7094, -1, 7098, 7084, 7083, -1, 7100, 7101, 7102, -1, 7100, 7102, 7103, -1, 7100, 7103, 7097, -1, 7100, 7097, 7095, -1, 7104, 7099, 7105, -1, 7104, 7098, 7099, -1, 7104, 7090, 7098, -1, 7104, 7095, 7090, -1, 7106, 7105, 7088, -1, 7106, 7087, 7101, -1, 7106, 7100, 7095, -1, 7106, 7104, 7105, -1, 7106, 7095, 7104, -1, 7106, 7088, 7087, -1, 7106, 7101, 7100, -1, 7107, 7108, 7109, -1, 7110, 7111, 7112, -1, 7113, 7111, 7110, -1, 7114, 7115, 7116, -1, 7114, 7116, 7117, -1, 7114, 7117, 7118, -1, 7119, 7120, 7115, -1, 7119, 7121, 7120, -1, 7119, 7115, 7114, -1, 7122, 7118, 7108, -1, 7122, 7107, 7123, -1, 7122, 7114, 7118, -1, 7122, 7108, 7107, -1, 7124, 7125, 7126, -1, 7124, 7126, 7127, -1, 7124, 7127, 7121, -1, 7124, 7121, 7119, -1, 7128, 7123, 7129, -1, 7128, 7122, 7123, -1, 7128, 7114, 7122, -1, 7128, 7119, 7114, -1, 7130, 7129, 7112, -1, 7130, 7111, 7125, -1, 7130, 7124, 7119, -1, 7130, 7128, 7129, -1, 7130, 7119, 7128, -1, 7130, 7112, 7111, -1, 7130, 7125, 7124, -1, 7131, 7132, 7133, -1, 7131, 7133, 7134, -1, 7135, 7131, 7134, -1, 7136, 7132, 7131, -1, 7137, 7135, 7134, -1, 7138, 7135, 7137, -1, 7139, 7136, 7131, -1, 7140, 7137, 7141, -1, 7140, 7138, 7137, -1, 7142, 7136, 7139, -1, 7143, 7144, 7145, -1, 7146, 7147, 7140, -1, 7146, 7140, 7141, -1, 7148, 7149, 7144, -1, 7150, 7149, 7148, -1, 7151, 7150, 7148, -1, 7152, 7147, 7146, -1, 7153, 7147, 7152, -1, 7154, 7151, 7155, -1, 7154, 7150, 7151, -1, 7156, 7153, 7152, -1, 7157, 7154, 7155, -1, 7158, 7159, 7153, -1, 7158, 7153, 7156, -1, 7160, 7159, 7158, -1, 7161, 7154, 7157, -1, 7143, 7148, 7144, -1, 7162, 7139, 7163, -1, 7162, 7163, 7143, -1, 7162, 7145, 7142, -1, 7162, 7143, 7145, -1, 7162, 7142, 7139, -1, 7164, 7157, 7159, -1, 7164, 7160, 7161, -1, 7164, 7161, 7157, -1, 7164, 7159, 7160, -1, 7165, 7166, 7167, -1, 7168, 7169, 7170, -1, 7171, 7172, 7173, -1, 7171, 7173, 7166, -1, 7171, 7165, 7174, -1, 7171, 7166, 7165, -1, 7175, 7176, 7172, -1, 7175, 7172, 7171, -1, 7177, 7174, 7178, -1, 7177, 7178, 7179, -1, 7177, 7171, 7174, -1, 7180, 7181, 7168, -1, 7180, 7170, 7176, -1, 7180, 7168, 7170, -1, 7180, 7176, 7175, -1, 7182, 7179, 7183, -1, 7182, 7183, 7184, -1, 7182, 7184, 7185, -1, 7182, 7177, 7179, -1, 7182, 7175, 7171, -1, 7182, 7171, 7177, -1, 7186, 7185, 7187, -1, 7186, 7187, 7188, -1, 7186, 7188, 7181, -1, 7186, 7182, 7185, -1, 7186, 7181, 7180, -1, 7186, 7180, 7175, -1, 7186, 7175, 7182, -1, 7189, 7190, 7191, -1, 7189, 7191, 7192, -1, 7193, 7189, 7192, -1, 7194, 7190, 7189, -1, 7195, 7193, 7192, -1, 7196, 7193, 7195, -1, 7197, 7194, 7189, -1, 7198, 7196, 7195, -1, 7199, 7198, 7195, -1, 7200, 7194, 7197, -1, 7201, 7202, 7203, -1, 7201, 7203, 7200, -1, 7204, 7205, 7198, -1, 7204, 7198, 7199, -1, 7206, 7207, 7202, -1, 7208, 7207, 7206, -1, 7209, 7208, 7206, -1, 7210, 7205, 7204, -1, 7211, 7205, 7210, -1, 7212, 7209, 7213, -1, 7212, 7208, 7209, -1, 7214, 7211, 7210, -1, 7215, 7212, 7213, -1, 7216, 7217, 7211, -1, 7216, 7211, 7214, -1, 7218, 7217, 7216, -1, 7219, 7212, 7215, -1, 7201, 7206, 7202, -1, 7220, 7197, 7221, -1, 7220, 7221, 7201, -1, 7220, 7200, 7197, -1, 7220, 7201, 7200, -1, 7222, 7215, 7217, -1, 7222, 7218, 7219, -1, 7222, 7219, 7215, -1, 7222, 7217, 7218, -1, 7223, 7224, 7225, -1, 7226, 7227, 7228, -1, 7229, 7230, 7231, -1, 7229, 7231, 7224, -1, 7229, 7223, 7232, -1, 7229, 7224, 7223, -1, 7233, 7234, 7230, -1, 7233, 7230, 7229, -1, 7235, 7232, 7236, -1, 7235, 7236, 7237, -1, 7235, 7229, 7232, -1, 7238, 7239, 7226, -1, 7238, 7228, 7234, -1, 7238, 7234, 7233, -1, 7238, 7226, 7228, -1, 7240, 7241, 7242, -1, 7240, 7237, 7243, -1, 7240, 7243, 7241, -1, 7240, 7235, 7237, -1, 7240, 7229, 7235, -1, 7240, 7233, 7229, -1, 7244, 7242, 7245, -1, 7244, 7245, 7246, -1, 7244, 7246, 7239, -1, 7244, 7233, 7240, -1, 7244, 7240, 7242, -1, 7244, 7239, 7238, -1, 7244, 7238, 7233, -1, 7247, 7248, 7249, -1, 7250, 7251, 7252, -1, 7253, 7254, 7255, -1, 7253, 7255, 7248, -1, 7253, 7247, 7256, -1, 7253, 7248, 7247, -1, 7257, 7258, 7254, -1, 7257, 7254, 7253, -1, 7259, 7256, 7260, -1, 7259, 7260, 7261, -1, 7259, 7253, 7256, -1, 7262, 7263, 7250, -1, 7262, 7252, 7258, -1, 7262, 7258, 7257, -1, 7262, 7250, 7252, -1, 7264, 7265, 7266, -1, 7264, 7261, 7267, -1, 7264, 7267, 7265, -1, 7264, 7259, 7261, -1, 7264, 7253, 7259, -1, 7264, 7257, 7253, -1, 7268, 7266, 7269, -1, 7268, 7269, 7270, -1, 7268, 7270, 7263, -1, 7268, 7257, 7264, -1, 7268, 7264, 7266, -1, 7268, 7263, 7262, -1, 7268, 7262, 7257, -1, 7271, 7272, 7273, -1, 7274, 7275, 7276, -1, 7277, 7278, 7279, -1, 7277, 7279, 7272, -1, 7277, 7271, 7280, -1, 7277, 7272, 7271, -1, 7281, 7282, 7278, -1, 7281, 7278, 7277, -1, 7283, 7280, 7284, -1, 7283, 7284, 7285, -1, 7283, 7277, 7280, -1, 7286, 7287, 7274, -1, 7286, 7276, 7282, -1, 7286, 7282, 7281, -1, 7286, 7274, 7276, -1, 7288, 7289, 7290, -1, 7288, 7285, 7291, -1, 7288, 7291, 7289, -1, 7288, 7283, 7285, -1, 7288, 7277, 7283, -1, 7288, 7281, 7277, -1, 7292, 7290, 7293, -1, 7292, 7293, 7294, -1, 7292, 7294, 7287, -1, 7292, 7281, 7288, -1, 7292, 7288, 7290, -1, 7292, 7287, 7286, -1, 7292, 7286, 7281, -1, 7295, 7296, 7297, -1, 7295, 7297, 7298, -1, 7299, 7295, 7298, -1, 7300, 7296, 7295, -1, 7301, 7299, 7298, -1, 7302, 7299, 7301, -1, 7303, 7300, 7295, -1, 7304, 7301, 7305, -1, 7304, 7302, 7301, -1, 7306, 7300, 7303, -1, 7307, 7308, 7309, -1, 7310, 7311, 7304, -1, 7310, 7304, 7305, -1, 7312, 7313, 7308, -1, 7314, 7313, 7312, -1, 7315, 7314, 7312, -1, 7316, 7311, 7310, -1, 7317, 7311, 7316, -1, 7318, 7315, 7319, -1, 7318, 7314, 7315, -1, 7320, 7317, 7316, -1, 7321, 7318, 7319, -1, 7322, 7323, 7317, -1, 7322, 7317, 7320, -1, 7324, 7323, 7322, -1, 7325, 7318, 7321, -1, 7307, 7312, 7308, -1, 7326, 7303, 7327, -1, 7326, 7327, 7307, -1, 7326, 7309, 7306, -1, 7326, 7307, 7309, -1, 7326, 7306, 7303, -1, 7328, 7321, 7323, -1, 7328, 7324, 7325, -1, 7328, 7325, 7321, -1, 7328, 7323, 7324, -1, 7329, 7330, 7331, -1, 7329, 7331, 7332, -1, 7333, 7329, 7332, -1, 7334, 7330, 7329, -1, 7335, 7333, 7332, -1, 7336, 7333, 7335, -1, 7337, 7334, 7329, -1, 7338, 7336, 7335, -1, 7339, 7338, 7335, -1, 7340, 7334, 7337, -1, 7341, 7342, 7343, -1, 7341, 7343, 7340, -1, 7344, 7345, 7338, -1, 7344, 7338, 7339, -1, 7346, 7347, 7342, -1, 7348, 7347, 7346, -1, 7349, 7348, 7346, -1, 7350, 7345, 7344, -1, 7351, 7345, 7350, -1, 7352, 7349, 7353, -1, 7352, 7348, 7349, -1, 7354, 7351, 7350, -1, 7355, 7352, 7353, -1, 7356, 7357, 7351, -1, 7356, 7351, 7354, -1, 7358, 7357, 7356, -1, 7359, 7352, 7355, -1, 7341, 7346, 7342, -1, 7360, 7337, 7361, -1, 7360, 7361, 7341, -1, 7360, 7340, 7337, -1, 7360, 7341, 7340, -1, 7362, 7355, 7357, -1, 7362, 7358, 7359, -1, 7362, 7359, 7355, -1, 7362, 7357, 7358, -1, 7363, 7364, 7365, -1, 7366, 7367, 7368, -1, 7369, 7370, 7371, -1, 7369, 7371, 7363, -1, 7369, 7365, 7372, -1, 7369, 7363, 7365, -1, 7373, 7374, 7368, -1, 7373, 7367, 7370, -1, 7373, 7372, 7374, -1, 7373, 7369, 7372, -1, 7373, 7370, 7369, -1, 7373, 7368, 7367, -1, 7375, 7376, 7377, -1, 7378, 7379, 7380, -1, 7381, 7378, 7380, -1, 7382, 7383, 7384, -1, 7382, 7384, 7385, -1, 7382, 7385, 7386, -1, 7387, 7388, 7389, -1, 7387, 7389, 7383, -1, 7387, 7383, 7382, -1, 7390, 7386, 7376, -1, 7390, 7375, 7391, -1, 7390, 7376, 7375, -1, 7390, 7382, 7386, -1, 7392, 7393, 7394, -1, 7392, 7394, 7395, -1, 7392, 7395, 7388, -1, 7392, 7388, 7387, -1, 7396, 7391, 7397, -1, 7396, 7390, 7391, -1, 7396, 7382, 7390, -1, 7396, 7387, 7382, -1, 7398, 7397, 7379, -1, 7398, 7378, 7393, -1, 7398, 7396, 7397, -1, 7398, 7392, 7387, -1, 7398, 7387, 7396, -1, 7398, 7379, 7378, -1, 7398, 7393, 7392, -1, 7399, 7400, 7401, -1, 7402, 7403, 7404, -1, 7405, 7403, 7402, -1, 7406, 7407, 7408, -1, 7406, 7408, 7409, -1, 7406, 7409, 7410, -1, 7411, 7412, 7413, -1, 7411, 7413, 7407, -1, 7411, 7407, 7406, -1, 7414, 7410, 7400, -1, 7414, 7399, 7415, -1, 7414, 7400, 7399, -1, 7414, 7406, 7410, -1, 7416, 7417, 7418, -1, 7416, 7418, 7419, -1, 7416, 7419, 7412, -1, 7416, 7412, 7411, -1, 7420, 7415, 7421, -1, 7420, 7414, 7415, -1, 7420, 7406, 7414, -1, 7420, 7411, 7406, -1, 7422, 7421, 7404, -1, 7422, 7403, 7417, -1, 7422, 7420, 7421, -1, 7422, 7416, 7411, -1, 7422, 7411, 7420, -1, 7422, 7404, 7403, -1, 7422, 7417, 7416, -1, 7423, 7424, 7425, -1, 7426, 7427, 7428, -1, 7429, 7427, 7426, -1, 7430, 7431, 7432, -1, 7430, 7432, 7433, -1, 7430, 7433, 7434, -1, 7435, 7436, 7437, -1, 7435, 7437, 7431, -1, 7435, 7431, 7430, -1, 7438, 7434, 7424, -1, 7438, 7423, 7439, -1, 7438, 7424, 7423, -1, 7438, 7430, 7434, -1, 7440, 7441, 7442, -1, 7440, 7442, 7443, -1, 7440, 7443, 7436, -1, 7440, 7436, 7435, -1, 7444, 7439, 7445, -1, 7444, 7438, 7439, -1, 7444, 7430, 7438, -1, 7444, 7435, 7430, -1, 7446, 7445, 7428, -1, 7446, 7427, 7441, -1, 7446, 7444, 7445, -1, 7446, 7440, 7435, -1, 7446, 7435, 7444, -1, 7446, 7428, 7427, -1, 7446, 7441, 7440, -1, 7447, 7448, 7449, -1, 7450, 7451, 7452, -1, 7453, 7451, 7450, -1, 7454, 7455, 7456, -1, 7454, 7456, 7457, -1, 7454, 7457, 7458, -1, 7459, 7460, 7455, -1, 7459, 7461, 7460, -1, 7459, 7455, 7454, -1, 7462, 7458, 7448, -1, 7462, 7447, 7463, -1, 7462, 7454, 7458, -1, 7462, 7448, 7447, -1, 7464, 7465, 7466, -1, 7464, 7466, 7467, -1, 7464, 7467, 7461, -1, 7464, 7461, 7459, -1, 7468, 7463, 7469, -1, 7468, 7462, 7463, -1, 7468, 7454, 7462, -1, 7468, 7459, 7454, -1, 7470, 7469, 7452, -1, 7470, 7451, 7465, -1, 7470, 7464, 7459, -1, 7470, 7468, 7469, -1, 7470, 7459, 7468, -1, 7470, 7452, 7451, -1, 7470, 7465, 7464, -1, 7471, 7472, 7473, -1, 7474, 7475, 7476, -1, 7477, 7475, 7474, -1, 7478, 7479, 7480, -1, 7478, 7480, 7481, -1, 7478, 7481, 7482, -1, 7483, 7484, 7485, -1, 7483, 7485, 7479, -1, 7483, 7479, 7478, -1, 7486, 7482, 7472, -1, 7486, 7471, 7487, -1, 7486, 7472, 7471, -1, 7486, 7478, 7482, -1, 7488, 7489, 7490, -1, 7488, 7490, 7491, -1, 7488, 7491, 7484, -1, 7488, 7484, 7483, -1, 7492, 7487, 7493, -1, 7492, 7486, 7487, -1, 7492, 7478, 7486, -1, 7492, 7483, 7478, -1, 7494, 7493, 7476, -1, 7494, 7475, 7489, -1, 7494, 7492, 7493, -1, 7494, 7488, 7483, -1, 7494, 7483, 7492, -1, 7494, 7476, 7475, -1, 7494, 7489, 7488, -1, 7495, 7496, 7497, -1, 7498, 7499, 7500, -1, 7501, 7499, 7498, -1, 7502, 7503, 7504, -1, 7502, 7504, 7505, -1, 7502, 7505, 7506, -1, 7507, 7508, 7509, -1, 7507, 7509, 7503, -1, 7507, 7503, 7502, -1, 7510, 7506, 7496, -1, 7510, 7495, 7511, -1, 7510, 7496, 7495, -1, 7510, 7502, 7506, -1, 7512, 7513, 7514, -1, 7512, 7514, 7515, -1, 7512, 7515, 7508, -1, 7512, 7508, 7507, -1, 7516, 7511, 7517, -1, 7516, 7510, 7511, -1, 7516, 7502, 7510, -1, 7516, 7507, 7502, -1, 7518, 7517, 7500, -1, 7518, 7499, 7513, -1, 7518, 7516, 7517, -1, 7518, 7512, 7507, -1, 7518, 7507, 7516, -1, 7518, 7500, 7499, -1, 7518, 7513, 7512, -1, 7519, 7520, 7521, -1, 7522, 7523, 7524, -1, 7525, 7522, 7524, -1, 7526, 7527, 7528, -1, 7526, 7528, 7529, -1, 7526, 7529, 7530, -1, 7531, 7532, 7527, -1, 7531, 7533, 7532, -1, 7531, 7527, 7526, -1, 7534, 7530, 7520, -1, 7534, 7519, 7535, -1, 7534, 7526, 7530, -1, 7534, 7520, 7519, -1, 7536, 7537, 7538, -1, 7536, 7538, 7539, -1, 7536, 7539, 7533, -1, 7536, 7533, 7531, -1, 7540, 7535, 7541, -1, 7540, 7534, 7535, -1, 7540, 7526, 7534, -1, 7540, 7531, 7526, -1, 7542, 7541, 7523, -1, 7542, 7522, 7537, -1, 7542, 7536, 7531, -1, 7542, 7540, 7541, -1, 7542, 7531, 7540, -1, 7542, 7523, 7522, -1, 7542, 7537, 7536, -1, 7543, 7544, 7545, -1, 7546, 7547, 7548, -1, 7549, 7550, 7551, -1, 7549, 7551, 7543, -1, 7549, 7545, 7552, -1, 7549, 7543, 7545, -1, 7553, 7554, 7548, -1, 7553, 7547, 7550, -1, 7553, 7552, 7554, -1, 7553, 7549, 7552, -1, 7553, 7550, 7549, -1, 7553, 7548, 7547, -1, 7555, 7556, 7557, -1, 7558, 7559, 7560, -1, 7561, 7559, 7558, -1, 7562, 7563, 7564, -1, 7562, 7564, 7565, -1, 7562, 7565, 7566, -1, 7567, 7568, 7563, -1, 7567, 7569, 7568, -1, 7567, 7563, 7562, -1, 7570, 7566, 7556, -1, 7570, 7555, 7571, -1, 7570, 7562, 7566, -1, 7570, 7556, 7555, -1, 7572, 7573, 7574, -1, 7572, 7574, 7575, -1, 7572, 7575, 7569, -1, 7572, 7569, 7567, -1, 7576, 7571, 7577, -1, 7576, 7570, 7571, -1, 7576, 7562, 7570, -1, 7576, 7567, 7562, -1, 7578, 7577, 7560, -1, 7578, 7559, 7573, -1, 7578, 7572, 7567, -1, 7578, 7576, 7577, -1, 7578, 7567, 7576, -1, 7578, 7560, 7559, -1, 7578, 7573, 7572, -1, 7579, 7580, 7581, -1, 7579, 7581, 7582, -1, 7583, 7579, 7582, -1, 7584, 7580, 7579, -1, 7585, 7583, 7582, -1, 7586, 7583, 7585, -1, 7587, 7584, 7579, -1, 7588, 7586, 7585, -1, 7589, 7588, 7585, -1, 7590, 7584, 7587, -1, 7591, 7592, 7593, -1, 7591, 7593, 7590, -1, 7594, 7595, 7588, -1, 7594, 7588, 7589, -1, 7596, 7597, 7592, -1, 7598, 7597, 7596, -1, 7599, 7598, 7596, -1, 7600, 7595, 7594, -1, 7601, 7595, 7600, -1, 7602, 7599, 7603, -1, 7602, 7598, 7599, -1, 7604, 7601, 7600, -1, 7605, 7602, 7603, -1, 7606, 7607, 7601, -1, 7606, 7601, 7604, -1, 7608, 7607, 7606, -1, 7609, 7602, 7605, -1, 7591, 7596, 7592, -1, 7610, 7587, 7611, -1, 7610, 7611, 7591, -1, 7610, 7590, 7587, -1, 7610, 7591, 7590, -1, 7612, 7605, 7607, -1, 7612, 7608, 7609, -1, 7612, 7609, 7605, -1, 7612, 7607, 7608, -1, 7613, 7614, 7615, -1, 7616, 7617, 7618, -1, 7619, 7620, 7621, -1, 7619, 7621, 7614, -1, 7619, 7613, 7622, -1, 7619, 7614, 7613, -1, 7623, 7624, 7620, -1, 7623, 7620, 7619, -1, 7625, 7622, 7626, -1, 7625, 7626, 7627, -1, 7625, 7619, 7622, -1, 7628, 7629, 7616, -1, 7628, 7618, 7624, -1, 7628, 7624, 7623, -1, 7628, 7616, 7618, -1, 7630, 7631, 7632, -1, 7630, 7627, 7633, -1, 7630, 7633, 7631, -1, 7630, 7625, 7627, -1, 7630, 7619, 7625, -1, 7630, 7623, 7619, -1, 7634, 7632, 7635, -1, 7634, 7635, 7636, -1, 7634, 7636, 7629, -1, 7634, 7623, 7630, -1, 7634, 7630, 7632, -1, 7634, 7629, 7628, -1, 7634, 7628, 7623, -1, 7637, 7638, 7639, -1, 7637, 7639, 7640, -1, 7641, 7637, 7640, -1, 7642, 7638, 7637, -1, 7643, 7641, 7640, -1, 7644, 7641, 7643, -1, 7645, 7642, 7637, -1, 7646, 7643, 7647, -1, 7646, 7644, 7643, -1, 7648, 7642, 7645, -1, 7649, 7650, 7651, -1, 7652, 7653, 7646, -1, 7652, 7646, 7647, -1, 7654, 7655, 7650, -1, 7656, 7655, 7654, -1, 7657, 7656, 7654, -1, 7658, 7653, 7652, -1, 7659, 7653, 7658, -1, 7660, 7657, 7661, -1, 7660, 7656, 7657, -1, 7662, 7659, 7658, -1, 7663, 7660, 7661, -1, 7664, 7665, 7659, -1, 7664, 7659, 7662, -1, 7666, 7665, 7664, -1, 7667, 7660, 7663, -1, 7649, 7654, 7650, -1, 7668, 7645, 7669, -1, 7668, 7669, 7649, -1, 7668, 7651, 7648, -1, 7668, 7649, 7651, -1, 7668, 7648, 7645, -1, 7670, 7663, 7665, -1, 7670, 7666, 7667, -1, 7670, 7667, 7663, -1, 7670, 7665, 7666, -1, 7671, 7672, 7673, -1, 7674, 7675, 7676, -1, 7677, 7678, 7679, -1, 7677, 7679, 7672, -1, 7677, 7671, 7680, -1, 7677, 7672, 7671, -1, 7681, 7682, 7678, -1, 7681, 7678, 7677, -1, 7683, 7680, 7684, -1, 7683, 7684, 7685, -1, 7683, 7677, 7680, -1, 7686, 7687, 7674, -1, 7686, 7676, 7682, -1, 7686, 7682, 7681, -1, 7686, 7674, 7676, -1, 7688, 7689, 7690, -1, 7688, 7685, 7691, -1, 7688, 7691, 7689, -1, 7688, 7683, 7685, -1, 7688, 7677, 7683, -1, 7688, 7681, 7677, -1, 7692, 7690, 7693, -1, 7692, 7693, 7694, -1, 7692, 7694, 7687, -1, 7692, 7681, 7688, -1, 7692, 7688, 7690, -1, 7692, 7687, 7686, -1, 7692, 7686, 7681, -1, 7695, 7696, 7697, -1, 7698, 7699, 7700, -1, 7701, 7697, 7702, -1, 7701, 7702, 7703, -1, 7701, 7704, 7695, -1, 7701, 7695, 7697, -1, 7705, 7703, 7699, -1, 7705, 7698, 7706, -1, 7705, 7706, 7704, -1, 7705, 7701, 7703, -1, 7705, 7704, 7701, -1, 7705, 7699, 7698, -1, 7707, 7708, 7709, -1, 7710, 7711, 7712, -1, 7713, 7711, 7710, -1, 7714, 7715, 7716, -1, 7714, 7716, 7717, -1, 7714, 7717, 7718, -1, 7719, 7720, 7715, -1, 7719, 7721, 7720, -1, 7719, 7715, 7714, -1, 7722, 7718, 7708, -1, 7722, 7707, 7723, -1, 7722, 7714, 7718, -1, 7722, 7708, 7707, -1, 7724, 7725, 7726, -1, 7724, 7726, 7727, -1, 7724, 7727, 7721, -1, 7724, 7721, 7719, -1, 7728, 7723, 7729, -1, 7728, 7722, 7723, -1, 7728, 7714, 7722, -1, 7728, 7719, 7714, -1, 7730, 7729, 7712, -1, 7730, 7711, 7725, -1, 7730, 7724, 7719, -1, 7730, 7728, 7729, -1, 7730, 7719, 7728, -1, 7730, 7712, 7711, -1, 7730, 7725, 7724, -1, 7731, 7732, 7733, -1, 7734, 7735, 7736, -1, 7737, 7735, 7734, -1, 7738, 7739, 7740, -1, 7738, 7740, 7741, -1, 7738, 7741, 7742, -1, 7743, 7744, 7739, -1, 7743, 7745, 7744, -1, 7743, 7739, 7738, -1, 7746, 7742, 7732, -1, 7746, 7731, 7747, -1, 7746, 7738, 7742, -1, 7746, 7732, 7731, -1, 7748, 7749, 7750, -1, 7748, 7750, 7751, -1, 7748, 7751, 7745, -1, 7748, 7745, 7743, -1, 7752, 7747, 7753, -1, 7752, 7746, 7747, -1, 7752, 7738, 7746, -1, 7752, 7743, 7738, -1, 7754, 7753, 7736, -1, 7754, 7735, 7749, -1, 7754, 7748, 7743, -1, 7754, 7752, 7753, -1, 7754, 7743, 7752, -1, 7754, 7736, 7735, -1, 7754, 7749, 7748, -1, 7755, 7756, 7757, -1, 7758, 7759, 7760, -1, 7761, 7758, 7760, -1, 7762, 7763, 7764, -1, 7762, 7764, 7765, -1, 7762, 7765, 7766, -1, 7767, 7768, 7769, -1, 7767, 7769, 7763, -1, 7767, 7763, 7762, -1, 7770, 7766, 7756, -1, 7770, 7755, 7771, -1, 7770, 7756, 7755, -1, 7770, 7762, 7766, -1, 7772, 7773, 7774, -1, 7772, 7774, 7775, -1, 7772, 7775, 7768, -1, 7772, 7768, 7767, -1, 7776, 7771, 7777, -1, 7776, 7770, 7771, -1, 7776, 7762, 7770, -1, 7776, 7767, 7762, -1, 7778, 7777, 7759, -1, 7778, 7758, 7773, -1, 7778, 7776, 7777, -1, 7778, 7772, 7767, -1, 7778, 7767, 7776, -1, 7778, 7759, 7758, -1, 7778, 7773, 7772, -1, 7779, 7780, 7781, -1, 7782, 7783, 7784, -1, 7785, 7783, 7782, -1, 7786, 7787, 7788, -1, 7786, 7788, 7789, -1, 7786, 7789, 7790, -1, 7791, 7792, 7793, -1, 7791, 7793, 7787, -1, 7791, 7787, 7786, -1, 7794, 7790, 7780, -1, 7794, 7779, 7795, -1, 7794, 7780, 7779, -1, 7794, 7786, 7790, -1, 7796, 7797, 7798, -1, 7796, 7798, 7799, -1, 7796, 7799, 7792, -1, 7796, 7792, 7791, -1, 7800, 7795, 7801, -1, 7800, 7794, 7795, -1, 7800, 7786, 7794, -1, 7800, 7791, 7786, -1, 7802, 7801, 7784, -1, 7802, 7783, 7797, -1, 7802, 7800, 7801, -1, 7802, 7796, 7791, -1, 7802, 7791, 7800, -1, 7802, 7784, 7783, -1, 7802, 7797, 7796, -1, 7803, 7804, 7805, -1, 7806, 7807, 7808, -1, 7809, 7810, 7811, -1, 7809, 7811, 7804, -1, 7809, 7803, 7812, -1, 7809, 7804, 7803, -1, 7813, 7814, 7810, -1, 7813, 7810, 7809, -1, 7815, 7812, 7816, -1, 7815, 7816, 7817, -1, 7815, 7809, 7812, -1, 7818, 7819, 7806, -1, 7818, 7808, 7814, -1, 7818, 7814, 7813, -1, 7818, 7806, 7808, -1, 7820, 7821, 7822, -1, 7820, 7817, 7823, -1, 7820, 7823, 7821, -1, 7820, 7815, 7817, -1, 7820, 7809, 7815, -1, 7820, 7813, 7809, -1, 7824, 7822, 7825, -1, 7824, 7825, 7826, -1, 7824, 7826, 7819, -1, 7824, 7813, 7820, -1, 7824, 7820, 7822, -1, 7824, 7819, 7818, -1, 7824, 7818, 7813, -1, 7827, 7828, 7829, -1, 7827, 7829, 7830, -1, 7831, 7827, 7830, -1, 7832, 7828, 7827, -1, 7833, 7831, 7830, -1, 7834, 7831, 7833, -1, 7835, 7832, 7827, -1, 7836, 7833, 7837, -1, 7836, 7834, 7833, -1, 7838, 7832, 7835, -1, 7839, 7840, 7841, -1, 7842, 7843, 7836, -1, 7842, 7836, 7837, -1, 7844, 7845, 7840, -1, 7846, 7845, 7844, -1, 7847, 7846, 7844, -1, 7848, 7843, 7842, -1, 7849, 7843, 7848, -1, 7850, 7847, 7851, -1, 7850, 7846, 7847, -1, 7852, 7849, 7848, -1, 7853, 7850, 7851, -1, 7854, 7855, 7849, -1, 7854, 7849, 7852, -1, 7856, 7855, 7854, -1, 7857, 7850, 7853, -1, 7839, 7844, 7840, -1, 7858, 7835, 7859, -1, 7858, 7859, 7839, -1, 7858, 7841, 7838, -1, 7858, 7839, 7841, -1, 7858, 7838, 7835, -1, 7860, 7853, 7855, -1, 7860, 7856, 7857, -1, 7860, 7857, 7853, -1, 7860, 7855, 7856, -1, 7861, 7862, 7863, -1, 7861, 7863, 7864, -1, 7865, 7861, 7864, -1, 7866, 7862, 7861, -1, 7867, 7865, 7864, -1, 7868, 7865, 7867, -1, 7869, 7866, 7861, -1, 7870, 7868, 7867, -1, 7871, 7870, 7867, -1, 7872, 7866, 7869, -1, 7873, 7874, 7875, -1, 7873, 7875, 7872, -1, 7876, 7877, 7870, -1, 7876, 7870, 7871, -1, 7878, 7879, 7874, -1, 7880, 7879, 7878, -1, 7881, 7880, 7878, -1, 7882, 7877, 7876, -1, 7883, 7877, 7882, -1, 7884, 7881, 7885, -1, 7884, 7880, 7881, -1, 7886, 7883, 7882, -1, 7887, 7884, 7885, -1, 7888, 7889, 7883, -1, 7888, 7883, 7886, -1, 7890, 7889, 7888, -1, 7891, 7884, 7887, -1, 7873, 7878, 7874, -1, 7892, 7869, 7893, -1, 7892, 7893, 7873, -1, 7892, 7872, 7869, -1, 7892, 7873, 7872, -1, 7894, 7887, 7889, -1, 7894, 7890, 7891, -1, 7894, 7891, 7887, -1, 7894, 7889, 7890, -1, 7895, 7896, 7897, -1, 7898, 7899, 7900, -1, 7901, 7902, 7903, -1, 7901, 7903, 7896, -1, 7901, 7895, 7904, -1, 7901, 7896, 7895, -1, 7905, 7906, 7902, -1, 7905, 7902, 7901, -1, 7907, 7904, 7908, -1, 7907, 7908, 7909, -1, 7907, 7901, 7904, -1, 7910, 7911, 7898, -1, 7910, 7900, 7906, -1, 7910, 7898, 7900, -1, 7910, 7906, 7905, -1, 7912, 7909, 7913, -1, 7912, 7913, 7914, -1, 7912, 7914, 7915, -1, 7912, 7907, 7909, -1, 7912, 7905, 7901, -1, 7912, 7901, 7907, -1, 7916, 7915, 7917, -1, 7916, 7917, 7918, -1, 7916, 7918, 7911, -1, 7916, 7912, 7915, -1, 7916, 7911, 7910, -1, 7916, 7910, 7905, -1, 7916, 7905, 7912, -1, 7919, 7920, 7921, -1, 7922, 7923, 7924, -1, 7925, 7926, 7927, -1, 7925, 7927, 7920, -1, 7925, 7919, 7928, -1, 7925, 7920, 7919, -1, 7929, 7930, 7926, -1, 7929, 7926, 7925, -1, 7931, 7928, 7932, -1, 7931, 7932, 7933, -1, 7931, 7925, 7928, -1, 7934, 7935, 7922, -1, 7934, 7924, 7930, -1, 7934, 7930, 7929, -1, 7934, 7922, 7924, -1, 7936, 7937, 7938, -1, 7936, 7933, 7939, -1, 7936, 7939, 7937, -1, 7936, 7931, 7933, -1, 7936, 7925, 7931, -1, 7936, 7929, 7925, -1, 7940, 7938, 7941, -1, 7940, 7941, 7942, -1, 7940, 7942, 7935, -1, 7940, 7929, 7936, -1, 7940, 7936, 7938, -1, 7940, 7935, 7934, -1, 7940, 7934, 7929, -1, 7943, 7944, 7945, -1, 7943, 7945, 7946, -1, 7947, 7943, 7946, -1, 7948, 7944, 7943, -1, 7949, 7947, 7946, -1, 7950, 7947, 7949, -1, 7951, 7948, 7943, -1, 7952, 7949, 7953, -1, 7952, 7950, 7949, -1, 7954, 7948, 7951, -1, 7955, 7956, 7957, -1, 7958, 7959, 7952, -1, 7958, 7952, 7953, -1, 7960, 7961, 7956, -1, 7962, 7961, 7960, -1, 7963, 7962, 7960, -1, 7964, 7959, 7958, -1, 7965, 7959, 7964, -1, 7966, 7963, 7967, -1, 7966, 7962, 7963, -1, 7968, 7965, 7964, -1, 7969, 7966, 7967, -1, 7970, 7971, 7965, -1, 7970, 7965, 7968, -1, 7972, 7971, 7970, -1, 7973, 7966, 7969, -1, 7955, 7960, 7956, -1, 7974, 7951, 7975, -1, 7974, 7975, 7955, -1, 7974, 7957, 7954, -1, 7974, 7955, 7957, -1, 7974, 7954, 7951, -1, 7976, 7969, 7971, -1, 7976, 7972, 7973, -1, 7976, 7973, 7969, -1, 7976, 7971, 7972, -1, 7977, 7978, 7979, -1, 7977, 7979, 7980, -1, 7981, 7977, 7980, -1, 7982, 7978, 7977, -1, 7983, 7981, 7980, -1, 7984, 7981, 7983, -1, 7985, 7982, 7977, -1, 7986, 7984, 7983, -1, 7987, 7986, 7983, -1, 7988, 7982, 7985, -1, 7989, 7990, 7991, -1, 7989, 7991, 7988, -1, 7992, 7993, 7986, -1, 7992, 7986, 7987, -1, 7994, 7995, 7990, -1, 7996, 7995, 7994, -1, 7997, 7996, 7994, -1, 7998, 7993, 7992, -1, 7999, 7993, 7998, -1, 8000, 7997, 8001, -1, 8000, 7996, 7997, -1, 8002, 7999, 7998, -1, 8003, 8000, 8001, -1, 8004, 8005, 7999, -1, 8004, 7999, 8002, -1, 8006, 8005, 8004, -1, 8007, 8000, 8003, -1, 7989, 7994, 7990, -1, 8008, 7985, 8009, -1, 8008, 8009, 7989, -1, 8008, 7988, 7985, -1, 8008, 7989, 7988, -1, 8010, 8003, 8005, -1, 8010, 8006, 8007, -1, 8010, 8007, 8003, -1, 8010, 8005, 8006, -1, 8011, 8012, 8013, -1, 8014, 8015, 8016, -1, 8017, 8018, 8019, -1, 8017, 8019, 8012, -1, 8017, 8011, 8020, -1, 8017, 8012, 8011, -1, 8021, 8022, 8018, -1, 8021, 8018, 8017, -1, 8023, 8020, 8024, -1, 8023, 8024, 8025, -1, 8023, 8017, 8020, -1, 8026, 8027, 8014, -1, 8026, 8016, 8022, -1, 8026, 8022, 8021, -1, 8026, 8014, 8016, -1, 8028, 8029, 8030, -1, 8028, 8025, 8031, -1, 8028, 8031, 8029, -1, 8028, 8023, 8025, -1, 8028, 8017, 8023, -1, 8028, 8021, 8017, -1, 8032, 8030, 8033, -1, 8032, 8033, 8034, -1, 8032, 8034, 8027, -1, 8032, 8021, 8028, -1, 8032, 8028, 8030, -1, 8032, 8027, 8026, -1, 8032, 8026, 8021, -1, 8035, 8036, 8037, -1, 8038, 8039, 8040, -1, 8041, 8042, 8043, -1, 8041, 8043, 8035, -1, 8041, 8037, 8044, -1, 8041, 8035, 8037, -1, 8045, 8046, 8040, -1, 8045, 8039, 8042, -1, 8045, 8044, 8046, -1, 8045, 8041, 8044, -1, 8045, 8042, 8041, -1, 8045, 8040, 8039, -1, 8047, 8048, 8049, -1, 8050, 8051, 8052, -1, 8053, 8051, 8050, -1, 8054, 8055, 8056, -1, 8054, 8056, 8057, -1, 8054, 8057, 8058, -1, 8059, 8060, 8055, -1, 8059, 8061, 8060, -1, 8059, 8055, 8054, -1, 8062, 8058, 8048, -1, 8062, 8047, 8063, -1, 8062, 8054, 8058, -1, 8062, 8048, 8047, -1, 8064, 8065, 8066, -1, 8064, 8066, 8067, -1, 8064, 8067, 8061, -1, 8064, 8061, 8059, -1, 8068, 8063, 8069, -1, 8068, 8062, 8063, -1, 8068, 8054, 8062, -1, 8068, 8059, 8054, -1, 8070, 8069, 8052, -1, 8070, 8051, 8065, -1, 8070, 8064, 8059, -1, 8070, 8068, 8069, -1, 8070, 8059, 8068, -1, 8070, 8052, 8051, -1, 8070, 8065, 8064, -1, 8071, 8072, 8073, -1, 8074, 8075, 8076, -1, 8077, 8075, 8074, -1, 8078, 8079, 8080, -1, 8078, 8080, 8081, -1, 8078, 8081, 8082, -1, 8083, 8084, 8079, -1, 8083, 8085, 8084, -1, 8083, 8079, 8078, -1, 8086, 8082, 8072, -1, 8086, 8071, 8087, -1, 8086, 8078, 8082, -1, 8086, 8072, 8071, -1, 8088, 8089, 8090, -1, 8088, 8090, 8091, -1, 8088, 8091, 8085, -1, 8088, 8085, 8083, -1, 8092, 8087, 8093, -1, 8092, 8086, 8087, -1, 8092, 8078, 8086, -1, 8092, 8083, 8078, -1, 8094, 8093, 8076, -1, 8094, 8075, 8089, -1, 8094, 8088, 8083, -1, 8094, 8092, 8093, -1, 8094, 8083, 8092, -1, 8094, 8076, 8075, -1, 8094, 8089, 8088, -1, 8095, 8096, 8097, -1, 8098, 8099, 8100, -1, 8101, 8098, 8100, -1, 8102, 8103, 8104, -1, 8102, 8104, 8105, -1, 8102, 8105, 8106, -1, 8107, 8108, 8109, -1, 8107, 8109, 8103, -1, 8107, 8103, 8102, -1, 8110, 8106, 8096, -1, 8110, 8095, 8111, -1, 8110, 8096, 8095, -1, 8110, 8102, 8106, -1, 8112, 8113, 8114, -1, 8112, 8114, 8115, -1, 8112, 8115, 8108, -1, 8112, 8108, 8107, -1, 8116, 8111, 8117, -1, 8116, 8110, 8111, -1, 8116, 8102, 8110, -1, 8116, 8107, 8102, -1, 8118, 8117, 8099, -1, 8118, 8098, 8113, -1, 8118, 8116, 8117, -1, 8118, 8112, 8107, -1, 8118, 8107, 8116, -1, 8118, 8099, 8098, -1, 8118, 8113, 8112, -1, 8119, 8120, 8121, -1, 8122, 8123, 8124, -1, 8125, 8123, 8122, -1, 8126, 8127, 8128, -1, 8126, 8128, 8129, -1, 8126, 8129, 8130, -1, 8131, 8132, 8127, -1, 8131, 8133, 8132, -1, 8131, 8127, 8126, -1, 8134, 8130, 8120, -1, 8134, 8119, 8135, -1, 8134, 8126, 8130, -1, 8134, 8120, 8119, -1, 8136, 8137, 8138, -1, 8136, 8138, 8139, -1, 8136, 8139, 8133, -1, 8136, 8133, 8131, -1, 8140, 8135, 8141, -1, 8140, 8134, 8135, -1, 8140, 8126, 8134, -1, 8140, 8131, 8126, -1, 8142, 8141, 8124, -1, 8142, 8123, 8137, -1, 8142, 8136, 8131, -1, 8142, 8140, 8141, -1, 8142, 8131, 8140, -1, 8142, 8124, 8123, -1, 8142, 8137, 8136, -1, 8143, 8144, 8145, -1, 8143, 8145, 8146, -1, 8147, 8143, 8146, -1, 8148, 8144, 8143, -1, 8149, 8147, 8146, -1, 8150, 8147, 8149, -1, 8151, 8148, 8143, -1, 8152, 8150, 8149, -1, 8153, 8152, 8149, -1, 8154, 8148, 8151, -1, 8155, 8156, 8157, -1, 8155, 8157, 8154, -1, 8158, 8159, 8152, -1, 8158, 8152, 8153, -1, 8160, 8161, 8156, -1, 8162, 8161, 8160, -1, 8163, 8162, 8160, -1, 8164, 8159, 8158, -1, 8165, 8159, 8164, -1, 8166, 8163, 8167, -1, 8166, 8162, 8163, -1, 8168, 8165, 8164, -1, 8169, 8166, 8167, -1, 8170, 8171, 8165, -1, 8170, 8165, 8168, -1, 8172, 8171, 8170, -1, 8173, 8166, 8169, -1, 8155, 8160, 8156, -1, 8174, 8151, 8175, -1, 8174, 8175, 8155, -1, 8174, 8154, 8151, -1, 8174, 8155, 8154, -1, 8176, 8169, 8171, -1, 8176, 8172, 8173, -1, 8176, 8173, 8169, -1, 8176, 8171, 8172, -1, 8177, 8178, 8179, -1, 8180, 8181, 8182, -1, 8183, 8184, 8185, -1, 8183, 8185, 8178, -1, 8183, 8177, 8186, -1, 8183, 8178, 8177, -1, 8187, 8188, 8184, -1, 8187, 8184, 8183, -1, 8189, 8186, 8190, -1, 8189, 8190, 8191, -1, 8189, 8183, 8186, -1, 8192, 8193, 8180, -1, 8192, 8182, 8188, -1, 8192, 8188, 8187, -1, 8192, 8180, 8182, -1, 8194, 8195, 8196, -1, 8194, 8191, 8197, -1, 8194, 8197, 8195, -1, 8194, 8189, 8191, -1, 8194, 8183, 8189, -1, 8194, 8187, 8183, -1, 8198, 8196, 8199, -1, 8198, 8199, 8200, -1, 8198, 8200, 8193, -1, 8198, 8187, 8194, -1, 8198, 8194, 8196, -1, 8198, 8193, 8192, -1, 8198, 8192, 8187, -1, 8201, 8202, 8203, -1, 8201, 8203, 8204, -1, 8205, 8201, 8204, -1, 8206, 8202, 8201, -1, 8207, 8205, 8204, -1, 8208, 8205, 8207, -1, 8209, 8206, 8201, -1, 8210, 8207, 8211, -1, 8210, 8208, 8207, -1, 8212, 8206, 8209, -1, 8213, 8214, 8215, -1, 8216, 8217, 8210, -1, 8216, 8210, 8211, -1, 8218, 8219, 8214, -1, 8220, 8219, 8218, -1, 8221, 8220, 8218, -1, 8222, 8217, 8216, -1, 8223, 8217, 8222, -1, 8224, 8221, 8225, -1, 8224, 8220, 8221, -1, 8226, 8223, 8222, -1, 8227, 8224, 8225, -1, 8228, 8229, 8223, -1, 8228, 8223, 8226, -1, 8230, 8229, 8228, -1, 8231, 8224, 8227, -1, 8213, 8218, 8214, -1, 8232, 8209, 8233, -1, 8232, 8233, 8213, -1, 8232, 8215, 8212, -1, 8232, 8213, 8215, -1, 8232, 8212, 8209, -1, 8234, 8227, 8229, -1, 8234, 8230, 8231, -1, 8234, 8231, 8227, -1, 8234, 8229, 8230, -1, 8235, 8236, 8237, -1, 8238, 8239, 8240, -1, 8241, 8242, 8243, -1, 8241, 8243, 8236, -1, 8241, 8235, 8244, -1, 8241, 8236, 8235, -1, 8245, 8246, 8242, -1, 8245, 8242, 8241, -1, 8247, 8244, 8248, -1, 8247, 8248, 8249, -1, 8247, 8241, 8244, -1, 8250, 8251, 8238, -1, 8250, 8240, 8246, -1, 8250, 8246, 8245, -1, 8250, 8238, 8240, -1, 8252, 8253, 8254, -1, 8252, 8249, 8255, -1, 8252, 8255, 8253, -1, 8252, 8247, 8249, -1, 8252, 8241, 8247, -1, 8252, 8245, 8241, -1, 8256, 8254, 8257, -1, 8256, 8257, 8258, -1, 8256, 8258, 8251, -1, 8256, 8245, 8252, -1, 8256, 8252, 8254, -1, 8256, 8251, 8250, -1, 8256, 8250, 8245, -1, 8259, 8260, 8261, -1, 8262, 8263, 8264, -1, 8265, 8263, 8262, -1, 8266, 8267, 8268, -1, 8266, 8268, 8269, -1, 8266, 8269, 8270, -1, 8271, 8272, 8267, -1, 8271, 8273, 8272, -1, 8271, 8267, 8266, -1, 8274, 8270, 8260, -1, 8274, 8259, 8275, -1, 8274, 8266, 8270, -1, 8274, 8260, 8259, -1, 8276, 8277, 8278, -1, 8276, 8278, 8279, -1, 8276, 8279, 8273, -1, 8276, 8273, 8271, -1, 8280, 8275, 8281, -1, 8280, 8274, 8275, -1, 8280, 8266, 8274, -1, 8280, 8271, 8266, -1, 8282, 8281, 8264, -1, 8282, 8263, 8277, -1, 8282, 8276, 8271, -1, 8282, 8280, 8281, -1, 8282, 8271, 8280, -1, 8282, 8264, 8263, -1, 8282, 8277, 8276, -1, 8283, 8284, 8285, -1, 8286, 8287, 8288, -1, 8289, 8287, 8286, -1, 8290, 8291, 8292, -1, 8290, 8292, 8293, -1, 8290, 8293, 8294, -1, 8295, 8296, 8297, -1, 8295, 8297, 8291, -1, 8295, 8291, 8290, -1, 8298, 8294, 8284, -1, 8298, 8283, 8299, -1, 8298, 8284, 8283, -1, 8298, 8290, 8294, -1, 8300, 8301, 8302, -1, 8300, 8302, 8303, -1, 8300, 8303, 8296, -1, 8300, 8296, 8295, -1, 8304, 8299, 8305, -1, 8304, 8298, 8299, -1, 8304, 8290, 8298, -1, 8304, 8295, 8290, -1, 8306, 8305, 8288, -1, 8306, 8287, 8301, -1, 8306, 8304, 8305, -1, 8306, 8300, 8295, -1, 8306, 8295, 8304, -1, 8306, 8288, 8287, -1, 8306, 8301, 8300, -1, 8307, 8308, 8309, -1, 8310, 8311, 8312, -1, 8313, 8311, 8310, -1, 8314, 8315, 8316, -1, 8314, 8316, 8317, -1, 8314, 8317, 8318, -1, 8319, 8320, 8315, -1, 8319, 8321, 8320, -1, 8319, 8315, 8314, -1, 8322, 8318, 8308, -1, 8322, 8307, 8323, -1, 8322, 8314, 8318, -1, 8322, 8308, 8307, -1, 8324, 8325, 8326, -1, 8324, 8326, 8327, -1, 8324, 8327, 8321, -1, 8324, 8321, 8319, -1, 8328, 8323, 8329, -1, 8328, 8322, 8323, -1, 8328, 8314, 8322, -1, 8328, 8319, 8314, -1, 8330, 8329, 8312, -1, 8330, 8311, 8325, -1, 8330, 8324, 8319, -1, 8330, 8328, 8329, -1, 8330, 8319, 8328, -1, 8330, 8312, 8311, -1, 8330, 8325, 8324, -1, 8331, 8332, 8333, -1, 8334, 8335, 8336, -1, 8337, 8334, 8336, -1, 8338, 8339, 8340, -1, 8338, 8340, 8341, -1, 8338, 8341, 8342, -1, 8343, 8344, 8339, -1, 8343, 8345, 8344, -1, 8343, 8339, 8338, -1, 8346, 8342, 8332, -1, 8346, 8331, 8347, -1, 8346, 8338, 8342, -1, 8346, 8332, 8331, -1, 8348, 8349, 8350, -1, 8348, 8350, 8351, -1, 8348, 8351, 8345, -1, 8348, 8345, 8343, -1, 8352, 8347, 8353, -1, 8352, 8346, 8347, -1, 8352, 8338, 8346, -1, 8352, 8343, 8338, -1, 8354, 8353, 8335, -1, 8354, 8334, 8349, -1, 8354, 8348, 8343, -1, 8354, 8352, 8353, -1, 8354, 8343, 8352, -1, 8354, 8335, 8334, -1, 8354, 8349, 8348, -1, 8355, 8356, 8357, -1, 8358, 8359, 8360, -1, 8361, 8357, 8362, -1, 8361, 8362, 8363, -1, 8361, 8364, 8355, -1, 8361, 8355, 8357, -1, 8365, 8363, 8359, -1, 8365, 8358, 8366, -1, 8365, 8366, 8364, -1, 8365, 8361, 8363, -1, 8365, 8359, 8358, -1, 8365, 8364, 8361, -1, 8367, 8368, 8369, -1, 8367, 8369, 8370, -1, 8371, 8367, 8370, -1, 8372, 8368, 8367, -1, 8373, 8371, 8370, -1, 8374, 8371, 8373, -1, 8375, 8372, 8367, -1, 8376, 8373, 8377, -1, 8376, 8374, 8373, -1, 8378, 8372, 8375, -1, 8379, 8380, 8381, -1, 8382, 8383, 8376, -1, 8382, 8376, 8377, -1, 8384, 8385, 8380, -1, 8386, 8385, 8384, -1, 8387, 8386, 8384, -1, 8388, 8383, 8382, -1, 8389, 8383, 8388, -1, 8390, 8387, 8391, -1, 8390, 8386, 8387, -1, 8392, 8389, 8388, -1, 8393, 8390, 8391, -1, 8394, 8395, 8389, -1, 8394, 8389, 8392, -1, 8396, 8395, 8394, -1, 8397, 8390, 8393, -1, 8379, 8384, 8380, -1, 8398, 8375, 8399, -1, 8398, 8399, 8379, -1, 8398, 8381, 8378, -1, 8398, 8379, 8381, -1, 8398, 8378, 8375, -1, 8400, 8393, 8395, -1, 8400, 8396, 8397, -1, 8400, 8397, 8393, -1, 8400, 8395, 8396, -1, 8401, 8402, 8403, -1, 8404, 8405, 8406, -1, 8407, 8408, 8409, -1, 8407, 8409, 8402, -1, 8407, 8401, 8410, -1, 8407, 8402, 8401, -1, 8411, 8412, 8408, -1, 8411, 8408, 8407, -1, 8413, 8410, 8414, -1, 8413, 8414, 8415, -1, 8413, 8407, 8410, -1, 8416, 8417, 8404, -1, 8416, 8406, 8412, -1, 8416, 8404, 8406, -1, 8416, 8412, 8411, -1, 8418, 8415, 8419, -1, 8418, 8419, 8420, -1, 8418, 8420, 8421, -1, 8418, 8413, 8415, -1, 8418, 8411, 8407, -1, 8418, 8407, 8413, -1, 8422, 8421, 8423, -1, 8422, 8423, 8424, -1, 8422, 8424, 8417, -1, 8422, 8418, 8421, -1, 8422, 8417, 8416, -1, 8422, 8416, 8411, -1, 8422, 8411, 8418, -1, 8425, 8426, 8427, -1, 8425, 8427, 8428, -1, 8429, 8425, 8428, -1, 8430, 8426, 8425, -1, 8431, 8429, 8428, -1, 8432, 8429, 8431, -1, 8433, 8430, 8425, -1, 8434, 8432, 8431, -1, 8435, 8434, 8431, -1, 8436, 8430, 8433, -1, 8437, 8438, 8439, -1, 8437, 8439, 8436, -1, 8440, 8441, 8434, -1, 8440, 8434, 8435, -1, 8442, 8443, 8438, -1, 8444, 8443, 8442, -1, 8445, 8444, 8442, -1, 8446, 8441, 8440, -1, 8447, 8441, 8446, -1, 8448, 8445, 8449, -1, 8448, 8444, 8445, -1, 8450, 8447, 8446, -1, 8451, 8448, 8449, -1, 8452, 8453, 8447, -1, 8452, 8447, 8450, -1, 8454, 8453, 8452, -1, 8455, 8448, 8451, -1, 8437, 8442, 8438, -1, 8456, 8433, 8457, -1, 8456, 8457, 8437, -1, 8456, 8436, 8433, -1, 8456, 8437, 8436, -1, 8458, 8451, 8453, -1, 8458, 8454, 8455, -1, 8458, 8455, 8451, -1, 8458, 8453, 8454, -1, 8459, 8460, 8461, -1, 8462, 8463, 8464, -1, 8465, 8466, 8467, -1, 8465, 8467, 8460, -1, 8465, 8459, 8468, -1, 8465, 8460, 8459, -1, 8469, 8470, 8466, -1, 8469, 8466, 8465, -1, 8471, 8468, 8472, -1, 8471, 8472, 8473, -1, 8471, 8465, 8468, -1, 8474, 8475, 8462, -1, 8474, 8464, 8470, -1, 8474, 8470, 8469, -1, 8474, 8462, 8464, -1, 8476, 8473, 8477, -1, 8476, 8477, 8478, -1, 8476, 8478, 8479, -1, 8476, 8471, 8473, -1, 8476, 8465, 8471, -1, 8476, 8469, 8465, -1, 8480, 8479, 8481, -1, 8480, 8481, 8482, -1, 8480, 8482, 8475, -1, 8480, 8475, 8474, -1, 8480, 8476, 8479, -1, 8480, 8474, 8469, -1, 8480, 8469, 8476, -1, 8483, 8484, 8485, -1, 8486, 8487, 8488, -1, 8489, 8487, 8486, -1, 8490, 8491, 8492, -1, 8490, 8492, 8493, -1, 8490, 8493, 8494, -1, 8495, 8496, 8491, -1, 8495, 8497, 8496, -1, 8495, 8491, 8490, -1, 8498, 8494, 8484, -1, 8498, 8483, 8499, -1, 8498, 8490, 8494, -1, 8498, 8484, 8483, -1, 8500, 8501, 8502, -1, 8500, 8502, 8503, -1, 8500, 8503, 8497, -1, 8500, 8497, 8495, -1, 8504, 8499, 8505, -1, 8504, 8498, 8499, -1, 8504, 8490, 8498, -1, 8504, 8495, 8490, -1, 8506, 8505, 8488, -1, 8506, 8487, 8501, -1, 8506, 8500, 8495, -1, 8506, 8504, 8505, -1, 8506, 8495, 8504, -1, 8506, 8488, 8487, -1, 8506, 8501, 8500, -1, 8507, 8508, 8509, -1, 8510, 8511, 8512, -1, 8513, 8511, 8510, -1, 8514, 8515, 8516, -1, 8514, 8516, 8517, -1, 8514, 8517, 8518, -1, 8519, 8520, 8521, -1, 8519, 8521, 8515, -1, 8519, 8515, 8514, -1, 8522, 8518, 8508, -1, 8522, 8507, 8523, -1, 8522, 8508, 8507, -1, 8522, 8514, 8518, -1, 8524, 8525, 8526, -1, 8524, 8526, 8527, -1, 8524, 8527, 8520, -1, 8524, 8520, 8519, -1, 8528, 8523, 8529, -1, 8528, 8522, 8523, -1, 8528, 8514, 8522, -1, 8528, 8519, 8514, -1, 8530, 8529, 8512, -1, 8530, 8511, 8525, -1, 8530, 8528, 8529, -1, 8530, 8524, 8519, -1, 8530, 8519, 8528, -1, 8530, 8512, 8511, -1, 8530, 8525, 8524, -1, 8531, 8532, 8533, -1, 8534, 8535, 8536, -1, 8537, 8535, 8534, -1, 8538, 8539, 8540, -1, 8538, 8540, 8541, -1, 8538, 8541, 8542, -1, 8543, 8544, 8545, -1, 8543, 8545, 8539, -1, 8543, 8539, 8538, -1, 8546, 8542, 8532, -1, 8546, 8531, 8547, -1, 8546, 8532, 8531, -1, 8546, 8538, 8542, -1, 8548, 8549, 8550, -1, 8548, 8550, 8551, -1, 8548, 8551, 8544, -1, 8548, 8544, 8543, -1, 8552, 8547, 8553, -1, 8552, 8546, 8547, -1, 8552, 8538, 8546, -1, 8552, 8543, 8538, -1, 8554, 8553, 8536, -1, 8554, 8535, 8549, -1, 8554, 8552, 8553, -1, 8554, 8548, 8543, -1, 8554, 8543, 8552, -1, 8554, 8536, 8535, -1, 8554, 8549, 8548, -1, 8555, 8556, 8557, -1, 8558, 8559, 8560, -1, 8561, 8557, 8562, -1, 8561, 8562, 8563, -1, 8561, 8564, 8555, -1, 8561, 8555, 8557, -1, 8565, 8563, 8559, -1, 8565, 8558, 8566, -1, 8565, 8566, 8564, -1, 8565, 8561, 8563, -1, 8565, 8559, 8558, -1, 8565, 8564, 8561, -1, 8567, 8568, 8569, -1, 8570, 8571, 8572, -1, 8573, 8570, 8572, -1, 8574, 8575, 8576, -1, 8574, 8576, 8577, -1, 8574, 8577, 8578, -1, 8579, 8580, 8581, -1, 8579, 8581, 8575, -1, 8579, 8575, 8574, -1, 8582, 8578, 8568, -1, 8582, 8567, 8583, -1, 8582, 8568, 8567, -1, 8582, 8574, 8578, -1, 8584, 8585, 8586, -1, 8584, 8586, 8587, -1, 8584, 8587, 8580, -1, 8584, 8580, 8579, -1, 8588, 8583, 8589, -1, 8588, 8582, 8583, -1, 8588, 8574, 8582, -1, 8588, 8579, 8574, -1, 8590, 8589, 8571, -1, 8590, 8570, 8585, -1, 8590, 8588, 8589, -1, 8590, 8584, 8579, -1, 8590, 8579, 8588, -1, 8590, 8571, 8570, -1, 8590, 8585, 8584, -1, 8591, 8592, 8593, -1, 8591, 8593, 8594, -1, 8595, 8591, 8594, -1, 8596, 8592, 8591, -1, 8597, 8595, 8594, -1, 8598, 8595, 8597, -1, 8599, 8596, 8591, -1, 8600, 8598, 8597, -1, 8601, 8600, 8597, -1, 8602, 8596, 8599, -1, 8603, 8604, 8605, -1, 8603, 8605, 8602, -1, 8606, 8607, 8600, -1, 8606, 8600, 8601, -1, 8608, 8609, 8604, -1, 8610, 8609, 8608, -1, 8611, 8610, 8608, -1, 8612, 8607, 8606, -1, 8613, 8607, 8612, -1, 8614, 8611, 8615, -1, 8614, 8610, 8611, -1, 8616, 8613, 8612, -1, 8617, 8614, 8615, -1, 8618, 8619, 8613, -1, 8618, 8613, 8616, -1, 8620, 8619, 8618, -1, 8621, 8614, 8617, -1, 8603, 8608, 8604, -1, 8622, 8599, 8623, -1, 8622, 8623, 8603, -1, 8622, 8602, 8599, -1, 8622, 8603, 8602, -1, 8624, 8617, 8619, -1, 8624, 8620, 8621, -1, 8624, 8621, 8617, -1, 8624, 8619, 8620, -1, 8625, 8626, 8627, -1, 8628, 8629, 8630, -1, 8631, 8632, 8633, -1, 8631, 8633, 8626, -1, 8631, 8625, 8634, -1, 8631, 8626, 8625, -1, 8635, 8636, 8632, -1, 8635, 8632, 8631, -1, 8637, 8634, 8638, -1, 8637, 8638, 8639, -1, 8637, 8631, 8634, -1, 8640, 8641, 8628, -1, 8640, 8630, 8636, -1, 8640, 8636, 8635, -1, 8640, 8628, 8630, -1, 8642, 8643, 8644, -1, 8642, 8639, 8645, -1, 8642, 8645, 8643, -1, 8642, 8637, 8639, -1, 8642, 8631, 8637, -1, 8642, 8635, 8631, -1, 8646, 8644, 8647, -1, 8646, 8647, 8648, -1, 8646, 8648, 8641, -1, 8646, 8635, 8642, -1, 8646, 8642, 8644, -1, 8646, 8641, 8640, -1, 8646, 8640, 8635, -1, 8649, 8650, 8651, -1, 8649, 8651, 8652, -1, 8653, 8649, 8652, -1, 8654, 8650, 8649, -1, 8655, 8653, 8652, -1, 8656, 8653, 8655, -1, 8657, 8654, 8649, -1, 8658, 8655, 8659, -1, 8658, 8656, 8655, -1, 8660, 8654, 8657, -1, 8661, 8662, 8663, -1, 8664, 8665, 8658, -1, 8664, 8658, 8659, -1, 8666, 8667, 8662, -1, 8668, 8667, 8666, -1, 8669, 8668, 8666, -1, 8670, 8665, 8664, -1, 8671, 8665, 8670, -1, 8672, 8669, 8673, -1, 8672, 8668, 8669, -1, 8674, 8671, 8670, -1, 8675, 8672, 8673, -1, 8676, 8677, 8671, -1, 8676, 8671, 8674, -1, 8678, 8677, 8676, -1, 8679, 8672, 8675, -1, 8661, 8666, 8662, -1, 8680, 8657, 8681, -1, 8680, 8681, 8661, -1, 8680, 8663, 8660, -1, 8680, 8661, 8663, -1, 8680, 8660, 8657, -1, 8682, 8675, 8677, -1, 8682, 8678, 8679, -1, 8682, 8679, 8675, -1, 8682, 8677, 8678, -1, 8683, 8684, 8685, -1, 8686, 8687, 8688, -1, 8689, 8690, 8691, -1, 8689, 8691, 8684, -1, 8689, 8683, 8692, -1, 8689, 8684, 8683, -1, 8693, 8694, 8690, -1, 8693, 8690, 8689, -1, 8695, 8692, 8696, -1, 8695, 8696, 8697, -1, 8695, 8689, 8692, -1, 8698, 8699, 8686, -1, 8698, 8688, 8694, -1, 8698, 8694, 8693, -1, 8698, 8686, 8688, -1, 8700, 8701, 8702, -1, 8700, 8697, 8703, -1, 8700, 8703, 8701, -1, 8700, 8695, 8697, -1, 8700, 8689, 8695, -1, 8700, 8693, 8689, -1, 8704, 8702, 8705, -1, 8704, 8705, 8706, -1, 8704, 8706, 8699, -1, 8704, 8693, 8700, -1, 8704, 8700, 8702, -1, 8704, 8699, 8698, -1, 8704, 8698, 8693, -1, 8707, 8708, 8709, -1, 8710, 8711, 8712, -1, 8713, 8714, 8715, -1, 8713, 8715, 8707, -1, 8713, 8709, 8716, -1, 8713, 8707, 8709, -1, 8717, 8718, 8712, -1, 8717, 8711, 8714, -1, 8717, 8716, 8718, -1, 8717, 8713, 8716, -1, 8717, 8714, 8713, -1, 8717, 8712, 8711, -1, 8719, 8720, 8721, -1, 8722, 8723, 8724, -1, 8725, 8723, 8722, -1, 8726, 8727, 8728, -1, 8726, 8728, 8729, -1, 8726, 8729, 8730, -1, 8731, 8732, 8727, -1, 8731, 8733, 8732, -1, 8731, 8727, 8726, -1, 8734, 8730, 8720, -1, 8734, 8719, 8735, -1, 8734, 8726, 8730, -1, 8734, 8720, 8719, -1, 8736, 8737, 8738, -1, 8736, 8738, 8739, -1, 8736, 8739, 8733, -1, 8736, 8733, 8731, -1, 8740, 8735, 8741, -1, 8740, 8734, 8735, -1, 8740, 8726, 8734, -1, 8740, 8731, 8726, -1, 8742, 8741, 8724, -1, 8742, 8723, 8737, -1, 8742, 8736, 8731, -1, 8742, 8740, 8741, -1, 8742, 8731, 8740, -1, 8742, 8724, 8723, -1, 8742, 8737, 8736, -1, 8743, 8744, 8745, -1, 8746, 8747, 8748, -1, 8749, 8747, 8746, -1, 8750, 8751, 8752, -1, 8750, 8752, 8753, -1, 8750, 8753, 8754, -1, 8755, 8756, 8757, -1, 8755, 8757, 8751, -1, 8755, 8751, 8750, -1, 8758, 8754, 8744, -1, 8758, 8743, 8759, -1, 8758, 8744, 8743, -1, 8758, 8750, 8754, -1, 8760, 8761, 8762, -1, 8760, 8762, 8763, -1, 8760, 8763, 8756, -1, 8760, 8756, 8755, -1, 8764, 8759, 8765, -1, 8764, 8758, 8759, -1, 8764, 8750, 8758, -1, 8764, 8755, 8750, -1, 8766, 8765, 8748, -1, 8766, 8747, 8761, -1, 8766, 8764, 8765, -1, 8766, 8760, 8755, -1, 8766, 8755, 8764, -1, 8766, 8748, 8747, -1, 8766, 8761, 8760, -1, 8767, 8768, 8769, -1, 8770, 8771, 8772, -1, 8773, 8771, 8770, -1, 8774, 8775, 8776, -1, 8774, 8776, 8777, -1, 8774, 8777, 8778, -1, 8779, 8780, 8775, -1, 8779, 8781, 8780, -1, 8779, 8775, 8774, -1, 8782, 8778, 8768, -1, 8782, 8767, 8783, -1, 8782, 8774, 8778, -1, 8782, 8768, 8767, -1, 8784, 8785, 8786, -1, 8784, 8786, 8787, -1, 8784, 8787, 8781, -1, 8784, 8781, 8779, -1, 8788, 8783, 8789, -1, 8788, 8782, 8783, -1, 8788, 8774, 8782, -1, 8788, 8779, 8774, -1, 8790, 8789, 8772, -1, 8790, 8771, 8785, -1, 8790, 8784, 8779, -1, 8790, 8788, 8789, -1, 8790, 8779, 8788, -1, 8790, 8772, 8771, -1, 8790, 8785, 8784, -1, 8791, 8792, 8793, -1, 8794, 8795, 8796, -1, 8797, 8794, 8796, -1, 8798, 8799, 8800, -1, 8798, 8800, 8801, -1, 8798, 8801, 8802, -1, 8803, 8804, 8799, -1, 8803, 8805, 8804, -1, 8803, 8799, 8798, -1, 8806, 8802, 8792, -1, 8806, 8791, 8807, -1, 8806, 8798, 8802, -1, 8806, 8792, 8791, -1, 8808, 8809, 8810, -1, 8808, 8810, 8811, -1, 8808, 8811, 8805, -1, 8808, 8805, 8803, -1, 8812, 8807, 8813, -1, 8812, 8806, 8807, -1, 8812, 8798, 8806, -1, 8812, 8803, 8798, -1, 8814, 8813, 8795, -1, 8814, 8794, 8809, -1, 8814, 8808, 8803, -1, 8814, 8812, 8813, -1, 8814, 8803, 8812, -1, 8814, 8795, 8794, -1, 8814, 8809, 8808, -1, 8815, 8816, 8817, -1, 8815, 8817, 8818, -1, 8819, 8815, 8818, -1, 8820, 8816, 8815, -1, 8821, 8819, 8818, -1, 8822, 8819, 8821, -1, 8823, 8820, 8815, -1, 8824, 8822, 8821, -1, 8825, 8824, 8821, -1, 8826, 8820, 8823, -1, 8827, 8828, 8829, -1, 8827, 8829, 8826, -1, 8830, 8831, 8824, -1, 8830, 8824, 8825, -1, 8832, 8833, 8828, -1, 8834, 8833, 8832, -1, 8835, 8834, 8832, -1, 8836, 8831, 8830, -1, 8837, 8831, 8836, -1, 8838, 8835, 8839, -1, 8838, 8834, 8835, -1, 8840, 8837, 8836, -1, 8841, 8838, 8839, -1, 8842, 8843, 8837, -1, 8842, 8837, 8840, -1, 8844, 8843, 8842, -1, 8845, 8838, 8841, -1, 8827, 8832, 8828, -1, 8846, 8823, 8847, -1, 8846, 8847, 8827, -1, 8846, 8826, 8823, -1, 8846, 8827, 8826, -1, 8848, 8841, 8843, -1, 8848, 8844, 8845, -1, 8848, 8845, 8841, -1, 8848, 8843, 8844, -1, 8849, 8850, 8851, -1, 8852, 8853, 8854, -1, 8855, 8856, 8857, -1, 8855, 8857, 8850, -1, 8855, 8849, 8858, -1, 8855, 8850, 8849, -1, 8859, 8860, 8856, -1, 8859, 8856, 8855, -1, 8861, 8858, 8862, -1, 8861, 8862, 8863, -1, 8861, 8855, 8858, -1, 8864, 8865, 8852, -1, 8864, 8854, 8860, -1, 8864, 8860, 8859, -1, 8864, 8852, 8854, -1, 8866, 8867, 8868, -1, 8866, 8863, 8869, -1, 8866, 8869, 8867, -1, 8866, 8861, 8863, -1, 8866, 8855, 8861, -1, 8866, 8859, 8855, -1, 8870, 8868, 8871, -1, 8870, 8871, 8872, -1, 8870, 8872, 8865, -1, 8870, 8859, 8866, -1, 8870, 8866, 8868, -1, 8870, 8865, 8864, -1, 8870, 8864, 8859, -1, 8873, 8874, 8875, -1, 8876, 8877, 8878, -1, 8879, 8880, 8881, -1, 8879, 8881, 8874, -1, 8879, 8873, 8882, -1, 8879, 8874, 8873, -1, 8883, 8884, 8880, -1, 8883, 8880, 8879, -1, 8885, 8882, 8886, -1, 8885, 8886, 8887, -1, 8885, 8879, 8882, -1, 8888, 8889, 8876, -1, 8888, 8878, 8884, -1, 8888, 8884, 8883, -1, 8888, 8876, 8878, -1, 8890, 8891, 8892, -1, 8890, 8887, 8893, -1, 8890, 8893, 8891, -1, 8890, 8885, 8887, -1, 8890, 8879, 8885, -1, 8890, 8883, 8879, -1, 8894, 8892, 8895, -1, 8894, 8895, 8896, -1, 8894, 8896, 8889, -1, 8894, 8883, 8890, -1, 8894, 8890, 8892, -1, 8894, 8889, 8888, -1, 8894, 8888, 8883, -1, 8897, 8898, 8899, -1, 8897, 8899, 8900, -1, 8901, 8897, 8900, -1, 8902, 8898, 8897, -1, 8903, 8901, 8900, -1, 8904, 8901, 8903, -1, 8905, 8902, 8897, -1, 8906, 8903, 8907, -1, 8906, 8904, 8903, -1, 8908, 8902, 8905, -1, 8909, 8910, 8911, -1, 8912, 8913, 8906, -1, 8912, 8906, 8907, -1, 8914, 8915, 8910, -1, 8916, 8915, 8914, -1, 8917, 8916, 8914, -1, 8918, 8913, 8912, -1, 8919, 8913, 8918, -1, 8920, 8917, 8921, -1, 8920, 8916, 8917, -1, 8922, 8919, 8918, -1, 8923, 8920, 8921, -1, 8924, 8925, 8919, -1, 8924, 8919, 8922, -1, 8926, 8925, 8924, -1, 8927, 8920, 8923, -1, 8909, 8914, 8910, -1, 8928, 8905, 8929, -1, 8928, 8929, 8909, -1, 8928, 8911, 8908, -1, 8928, 8909, 8911, -1, 8928, 8908, 8905, -1, 8930, 8923, 8925, -1, 8930, 8926, 8927, -1, 8930, 8927, 8923, -1, 8930, 8925, 8926, -1, 8931, 8932, 8933, -1, 8934, 8935, 8936, -1, 8937, 8934, 8936, -1, 8938, 8939, 8940, -1, 8938, 8940, 8941, -1, 8938, 8941, 8942, -1, 8943, 8944, 8945, -1, 8943, 8945, 8939, -1, 8943, 8939, 8938, -1, 8946, 8942, 8932, -1, 8946, 8931, 8947, -1, 8946, 8932, 8931, -1, 8946, 8938, 8942, -1, 8948, 8949, 8950, -1, 8948, 8950, 8951, -1, 8948, 8951, 8944, -1, 8948, 8944, 8943, -1, 8952, 8947, 8953, -1, 8952, 8946, 8947, -1, 8952, 8938, 8946, -1, 8952, 8943, 8938, -1, 8954, 8953, 8935, -1, 8954, 8934, 8949, -1, 8954, 8952, 8953, -1, 8954, 8948, 8943, -1, 8954, 8943, 8952, -1, 8954, 8935, 8934, -1, 8954, 8949, 8948, -1, 8955, 8956, 8957, -1, 8958, 8959, 8960, -1, 8961, 8959, 8958, -1, 8962, 8963, 8964, -1, 8962, 8964, 8965, -1, 8962, 8965, 8966, -1, 8967, 8968, 8969, -1, 8967, 8969, 8963, -1, 8967, 8963, 8962, -1, 8970, 8966, 8956, -1, 8970, 8955, 8971, -1, 8970, 8956, 8955, -1, 8970, 8962, 8966, -1, 8972, 8973, 8974, -1, 8972, 8974, 8975, -1, 8972, 8975, 8968, -1, 8972, 8968, 8967, -1, 8976, 8971, 8977, -1, 8976, 8970, 8971, -1, 8976, 8962, 8970, -1, 8976, 8967, 8962, -1, 8978, 8977, 8960, -1, 8978, 8959, 8973, -1, 8978, 8976, 8977, -1, 8978, 8972, 8967, -1, 8978, 8967, 8976, -1, 8978, 8960, 8959, -1, 8978, 8973, 8972, -1, 8979, 8980, 8981, -1, 8982, 8983, 8984, -1, 8985, 8983, 8982, -1, 8986, 8987, 8988, -1, 8986, 8988, 8989, -1, 8986, 8989, 8990, -1, 8991, 8992, 8993, -1, 8991, 8993, 8987, -1, 8991, 8987, 8986, -1, 8994, 8990, 8980, -1, 8994, 8979, 8995, -1, 8994, 8980, 8979, -1, 8994, 8986, 8990, -1, 8996, 8997, 8998, -1, 8996, 8998, 8999, -1, 8996, 8999, 8992, -1, 8996, 8992, 8991, -1, 9000, 8995, 9001, -1, 9000, 8994, 8995, -1, 9000, 8986, 8994, -1, 9000, 8991, 8986, -1, 9002, 9001, 8984, -1, 9002, 8983, 8997, -1, 9002, 9000, 9001, -1, 9002, 8996, 8991, -1, 9002, 8991, 9000, -1, 9002, 8984, 8983, -1, 9002, 8997, 8996, -1, 9003, 9004, 9005, -1, 9006, 9007, 9008, -1, 9009, 9007, 9006, -1, 9010, 9011, 9012, -1, 9010, 9012, 9013, -1, 9010, 9013, 9014, -1, 9015, 9016, 9017, -1, 9015, 9017, 9011, -1, 9015, 9011, 9010, -1, 9018, 9014, 9004, -1, 9018, 9003, 9019, -1, 9018, 9004, 9003, -1, 9018, 9010, 9014, -1, 9020, 9021, 9022, -1, 9020, 9022, 9023, -1, 9020, 9023, 9016, -1, 9020, 9016, 9015, -1, 9024, 9019, 9025, -1, 9024, 9018, 9019, -1, 9024, 9010, 9018, -1, 9024, 9015, 9010, -1, 9026, 9025, 9008, -1, 9026, 9007, 9021, -1, 9026, 9024, 9025, -1, 9026, 9020, 9015, -1, 9026, 9015, 9024, -1, 9026, 9008, 9007, -1, 9026, 9021, 9020, -1, 9027, 9028, 9029, -1, 9030, 9031, 9032, -1, 9033, 9034, 9035, -1, 9033, 9035, 9027, -1, 9033, 9029, 9036, -1, 9033, 9027, 9029, -1, 9037, 9038, 9032, -1, 9037, 9031, 9034, -1, 9037, 9036, 9038, -1, 9037, 9033, 9036, -1, 9037, 9034, 9033, -1, 9037, 9032, 9031, -1, 9039, 9040, 9041, -1, 9039, 9041, 9042, -1, 9043, 9039, 9042, -1, 9044, 9040, 9039, -1, 9045, 9043, 9042, -1, 9046, 9043, 9045, -1, 9047, 9044, 9039, -1, 9048, 9045, 9049, -1, 9048, 9046, 9045, -1, 9050, 9044, 9047, -1, 9051, 9052, 9053, -1, 9054, 9055, 9048, -1, 9054, 9048, 9049, -1, 9056, 9057, 9052, -1, 9058, 9057, 9056, -1, 9059, 9058, 9056, -1, 9060, 9055, 9054, -1, 9061, 9055, 9060, -1, 9062, 9059, 9063, -1, 9062, 9058, 9059, -1, 9064, 9061, 9060, -1, 9065, 9062, 9063, -1, 9066, 9067, 9061, -1, 9066, 9061, 9064, -1, 9068, 9067, 9066, -1, 9069, 9062, 9065, -1, 9051, 9056, 9052, -1, 9070, 9047, 9071, -1, 9070, 9071, 9051, -1, 9070, 9053, 9050, -1, 9070, 9051, 9053, -1, 9070, 9050, 9047, -1, 9072, 9065, 9067, -1, 9072, 9068, 9069, -1, 9072, 9069, 9065, -1, 9072, 9067, 9068, -1, 9073, 9074, 9075, -1, 9076, 9077, 9078, -1, 9079, 9080, 9081, -1, 9079, 9081, 9074, -1, 9079, 9073, 9082, -1, 9079, 9074, 9073, -1, 9083, 9084, 9080, -1, 9083, 9080, 9079, -1, 9085, 9082, 9086, -1, 9085, 9086, 9087, -1, 9085, 9079, 9082, -1, 9088, 9089, 9076, -1, 9088, 9078, 9084, -1, 9088, 9084, 9083, -1, 9088, 9076, 9078, -1, 9090, 9091, 9092, -1, 9090, 9087, 9093, -1, 9090, 9093, 9091, -1, 9090, 9085, 9087, -1, 9090, 9079, 9085, -1, 9090, 9083, 9079, -1, 9094, 9092, 9095, -1, 9094, 9095, 9096, -1, 9094, 9096, 9089, -1, 9094, 9083, 9090, -1, 9094, 9090, 9092, -1, 9094, 9089, 9088, -1, 9094, 9088, 9083, -1, 9097, 9098, 9099, -1, 9097, 9099, 9100, -1, 9101, 9097, 9100, -1, 9102, 9098, 9097, -1, 9103, 9101, 9100, -1, 9104, 9101, 9103, -1, 9105, 9102, 9097, -1, 9106, 9104, 9103, -1, 9107, 9106, 9103, -1, 9108, 9102, 9105, -1, 9109, 9110, 9111, -1, 9109, 9111, 9108, -1, 9112, 9113, 9106, -1, 9112, 9106, 9107, -1, 9114, 9115, 9110, -1, 9116, 9115, 9114, -1, 9117, 9116, 9114, -1, 9118, 9113, 9112, -1, 9119, 9113, 9118, -1, 9120, 9117, 9121, -1, 9120, 9116, 9117, -1, 9122, 9119, 9118, -1, 9123, 9120, 9121, -1, 9124, 9125, 9119, -1, 9124, 9119, 9122, -1, 9126, 9125, 9124, -1, 9127, 9120, 9123, -1, 9109, 9114, 9110, -1, 9128, 9105, 9129, -1, 9128, 9129, 9109, -1, 9128, 9108, 9105, -1, 9128, 9109, 9108, -1, 9130, 9123, 9125, -1, 9130, 9126, 9127, -1, 9130, 9127, 9123, -1, 9130, 9125, 9126, -1, 9131, 9132, 9133, -1, 9134, 9135, 9136, -1, 9137, 9138, 9139, -1, 9137, 9139, 9132, -1, 9137, 9131, 9140, -1, 9137, 9132, 9131, -1, 9141, 9142, 9138, -1, 9141, 9138, 9137, -1, 9143, 9140, 9144, -1, 9143, 9144, 9145, -1, 9143, 9137, 9140, -1, 9146, 9147, 9134, -1, 9146, 9136, 9142, -1, 9146, 9134, 9136, -1, 9146, 9142, 9141, -1, 9148, 9145, 9149, -1, 9148, 9149, 9150, -1, 9148, 9150, 9151, -1, 9148, 9143, 9145, -1, 9148, 9141, 9137, -1, 9148, 9137, 9143, -1, 9152, 9151, 9153, -1, 9152, 9153, 9154, -1, 9152, 9154, 9147, -1, 9152, 9148, 9151, -1, 9152, 9147, 9146, -1, 9152, 9146, 9141, -1, 9152, 9141, 9148, -1, 9155, 9156, 9157, -1, 9158, 9159, 9160, -1, 9161, 9162, 9163, -1, 9161, 9163, 9156, -1, 9161, 9155, 9164, -1, 9161, 9156, 9155, -1, 9165, 9166, 9162, -1, 9165, 9162, 9161, -1, 9167, 9164, 9168, -1, 9167, 9168, 9169, -1, 9167, 9161, 9164, -1, 9170, 9171, 9158, -1, 9170, 9160, 9166, -1, 9170, 9166, 9165, -1, 9170, 9158, 9160, -1, 9172, 9173, 9174, -1, 9172, 9169, 9175, -1, 9172, 9175, 9173, -1, 9172, 9167, 9169, -1, 9172, 9161, 9167, -1, 9172, 9165, 9161, -1, 9176, 9174, 9177, -1, 9176, 9177, 9178, -1, 9176, 9178, 9171, -1, 9176, 9165, 9172, -1, 9176, 9172, 9174, -1, 9176, 9171, 9170, -1, 9176, 9170, 9165, -1, 9179, 9180, 9181, -1, 9179, 9181, 9182, -1, 9183, 9179, 9182, -1, 9184, 9180, 9179, -1, 9185, 9183, 9182, -1, 9186, 9183, 9185, -1, 9187, 9184, 9179, -1, 9188, 9185, 9189, -1, 9188, 9186, 9185, -1, 9190, 9184, 9187, -1, 9191, 9192, 9193, -1, 9194, 9195, 9188, -1, 9194, 9188, 9189, -1, 9196, 9197, 9192, -1, 9198, 9197, 9196, -1, 9199, 9198, 9196, -1, 9200, 9195, 9194, -1, 9201, 9195, 9200, -1, 9202, 9199, 9203, -1, 9202, 9198, 9199, -1, 9204, 9201, 9200, -1, 9205, 9202, 9203, -1, 9206, 9207, 9201, -1, 9206, 9201, 9204, -1, 9208, 9207, 9206, -1, 9209, 9202, 9205, -1, 9191, 9196, 9192, -1, 9210, 9187, 9211, -1, 9210, 9211, 9191, -1, 9210, 9193, 9190, -1, 9210, 9191, 9193, -1, 9210, 9190, 9187, -1, 9212, 9205, 9207, -1, 9212, 9208, 9209, -1, 9212, 9209, 9205, -1, 9212, 9207, 9208, -1, 9213, 9214, 9215, -1, 9213, 9215, 9216, -1, 9217, 9213, 9216, -1, 9218, 9214, 9213, -1, 9219, 9217, 9216, -1, 9220, 9217, 9219, -1, 9221, 9218, 9213, -1, 9222, 9220, 9219, -1, 9223, 9222, 9219, -1, 9224, 9218, 9221, -1, 9225, 9226, 9227, -1, 9225, 9227, 9224, -1, 9228, 9229, 9222, -1, 9228, 9222, 9223, -1, 9230, 9231, 9226, -1, 9232, 9231, 9230, -1, 9233, 9232, 9230, -1, 9234, 9229, 9228, -1, 9235, 9229, 9234, -1, 9236, 9233, 9237, -1, 9236, 9232, 9233, -1, 9238, 9235, 9234, -1, 9239, 9236, 9237, -1, 9240, 9241, 9235, -1, 9240, 9235, 9238, -1, 9242, 9241, 9240, -1, 9243, 9236, 9239, -1, 9225, 9230, 9226, -1, 9244, 9221, 9245, -1, 9244, 9245, 9225, -1, 9244, 9224, 9221, -1, 9244, 9225, 9224, -1, 9246, 9239, 9241, -1, 9246, 9242, 9243, -1, 9246, 9243, 9239, -1, 9246, 9241, 9242, -1, 9247, 9248, 9249, -1, 9250, 9251, 9252, -1, 9253, 9254, 9255, -1, 9253, 9255, 9248, -1, 9253, 9247, 9256, -1, 9253, 9248, 9247, -1, 9257, 9258, 9254, -1, 9257, 9254, 9253, -1, 9259, 9256, 9260, -1, 9259, 9260, 9261, -1, 9259, 9253, 9256, -1, 9262, 9263, 9250, -1, 9262, 9252, 9258, -1, 9262, 9258, 9257, -1, 9262, 9250, 9252, -1, 9264, 9265, 9266, -1, 9264, 9261, 9267, -1, 9264, 9267, 9265, -1, 9264, 9259, 9261, -1, 9264, 9253, 9259, -1, 9264, 9257, 9253, -1, 9268, 9266, 9269, -1, 9268, 9269, 9270, -1, 9268, 9270, 9263, -1, 9268, 9257, 9264, -1, 9268, 9264, 9266, -1, 9268, 9263, 9262, -1, 9268, 9262, 9257, -1, 9271, 9272, 9273, -1, 9274, 9275, 9276, -1, 9277, 9278, 9279, -1, 9277, 9279, 9271, -1, 9277, 9273, 9280, -1, 9277, 9271, 9273, -1, 9281, 9282, 9276, -1, 9281, 9275, 9278, -1, 9281, 9280, 9282, -1, 9281, 9277, 9280, -1, 9281, 9278, 9277, -1, 9281, 9276, 9275, -1, 9283, 9284, 9285, -1, 9286, 9287, 9288, -1, 9289, 9287, 9286, -1, 9290, 9291, 9292, -1, 9290, 9292, 9293, -1, 9290, 9293, 9294, -1, 9295, 9296, 9291, -1, 9295, 9297, 9296, -1, 9295, 9291, 9290, -1, 9298, 9294, 9284, -1, 9298, 9283, 9299, -1, 9298, 9290, 9294, -1, 9298, 9284, 9283, -1, 9300, 9301, 9302, -1, 9300, 9302, 9303, -1, 9300, 9303, 9297, -1, 9300, 9297, 9295, -1, 9304, 9299, 9305, -1, 9304, 9298, 9299, -1, 9304, 9290, 9298, -1, 9304, 9295, 9290, -1, 9306, 9305, 9288, -1, 9306, 9287, 9301, -1, 9306, 9300, 9295, -1, 9306, 9304, 9305, -1, 9306, 9295, 9304, -1, 9306, 9288, 9287, -1, 9306, 9301, 9300, -1, 9307, 9308, 9309, -1, 9310, 9311, 9312, -1, 9313, 9311, 9310, -1, 9314, 9315, 9316, -1, 9314, 9316, 9317, -1, 9314, 9317, 9318, -1, 9319, 9320, 9315, -1, 9319, 9321, 9320, -1, 9319, 9315, 9314, -1, 9322, 9318, 9308, -1, 9322, 9307, 9323, -1, 9322, 9314, 9318, -1, 9322, 9308, 9307, -1, 9324, 9325, 9326, -1, 9324, 9326, 9327, -1, 9324, 9327, 9321, -1, 9324, 9321, 9319, -1, 9328, 9323, 9329, -1, 9328, 9322, 9323, -1, 9328, 9314, 9322, -1, 9328, 9319, 9314, -1, 9330, 9329, 9312, -1, 9330, 9311, 9325, -1, 9330, 9324, 9319, -1, 9330, 9328, 9329, -1, 9330, 9319, 9328, -1, 9330, 9312, 9311, -1, 9330, 9325, 9324, -1, 9331, 9332, 9333, -1, 9334, 9335, 9336, -1, 9337, 9334, 9336, -1, 9338, 9339, 9340, -1, 9338, 9340, 9341, -1, 9338, 9341, 9342, -1, 9343, 9344, 9345, -1, 9343, 9345, 9339, -1, 9343, 9339, 9338, -1, 9346, 9342, 9332, -1, 9346, 9331, 9347, -1, 9346, 9332, 9331, -1, 9346, 9338, 9342, -1, 9348, 9349, 9350, -1, 9348, 9350, 9351, -1, 9348, 9351, 9344, -1, 9348, 9344, 9343, -1, 9352, 9347, 9353, -1, 9352, 9346, 9347, -1, 9352, 9338, 9346, -1, 9352, 9343, 9338, -1, 9354, 9353, 9335, -1, 9354, 9334, 9349, -1, 9354, 9352, 9353, -1, 9354, 9348, 9343, -1, 9354, 9343, 9352, -1, 9354, 9335, 9334, -1, 9354, 9349, 9348, -1, 9355, 9356, 9357, -1, 9358, 9359, 9360, -1, 9361, 9359, 9358, -1, 9362, 9363, 9364, -1, 9362, 9364, 9365, -1, 9362, 9365, 9366, -1, 9367, 9368, 9363, -1, 9367, 9369, 9368, -1, 9367, 9363, 9362, -1, 9370, 9366, 9356, -1, 9370, 9355, 9371, -1, 9370, 9362, 9366, -1, 9370, 9356, 9355, -1, 9372, 9373, 9374, -1, 9372, 9374, 9375, -1, 9372, 9375, 9369, -1, 9372, 9369, 9367, -1, 9376, 9371, 9377, -1, 9376, 9370, 9371, -1, 9376, 9362, 9370, -1, 9376, 9367, 9362, -1, 9378, 9377, 9360, -1, 9378, 9359, 9373, -1, 9378, 9372, 9367, -1, 9378, 9376, 9377, -1, 9378, 9367, 9376, -1, 9378, 9360, 9359, -1, 9378, 9373, 9372, -1, 9379, 9380, 9381, -1, 9382, 9383, 9384, -1, 9385, 9386, 9387, -1, 9385, 9387, 9380, -1, 9385, 9379, 9388, -1, 9385, 9380, 9379, -1, 9389, 9390, 9386, -1, 9389, 9386, 9385, -1, 9391, 9388, 9392, -1, 9391, 9392, 9393, -1, 9391, 9385, 9388, -1, 9394, 9395, 9382, -1, 9394, 9384, 9390, -1, 9394, 9390, 9389, -1, 9394, 9382, 9384, -1, 9396, 9397, 9398, -1, 9396, 9393, 9399, -1, 9396, 9399, 9397, -1, 9396, 9391, 9393, -1, 9396, 9385, 9391, -1, 9396, 9389, 9385, -1, 9400, 9398, 9401, -1, 9400, 9401, 9402, -1, 9400, 9402, 9395, -1, 9400, 9389, 9396, -1, 9400, 9396, 9398, -1, 9400, 9395, 9394, -1, 9400, 9394, 9389, -1, 9403, 9404, 9405, -1, 9403, 9405, 9406, -1, 9407, 9403, 9406, -1, 9408, 9404, 9403, -1, 9409, 9407, 9406, -1, 9410, 9407, 9409, -1, 9411, 9408, 9403, -1, 9412, 9409, 9413, -1, 9412, 9410, 9409, -1, 9414, 9408, 9411, -1, 9415, 9416, 9417, -1, 9418, 9419, 9412, -1, 9418, 9412, 9413, -1, 9420, 9421, 9416, -1, 9422, 9421, 9420, -1, 9423, 9422, 9420, -1, 9424, 9419, 9418, -1, 9425, 9419, 9424, -1, 9426, 9423, 9427, -1, 9426, 9422, 9423, -1, 9428, 9425, 9424, -1, 9429, 9426, 9427, -1, 9430, 9431, 9425, -1, 9430, 9425, 9428, -1, 9432, 9431, 9430, -1, 9433, 9426, 9429, -1, 9415, 9420, 9416, -1, 9434, 9411, 9435, -1, 9434, 9435, 9415, -1, 9434, 9417, 9414, -1, 9434, 9415, 9417, -1, 9434, 9414, 9411, -1, 9436, 9429, 9431, -1, 9436, 9432, 9433, -1, 9436, 9433, 9429, -1, 9436, 9431, 9432, -1, 9437, 9438, 9439, -1, 9437, 9439, 9440, -1, 9441, 9437, 9440, -1, 9442, 9438, 9437, -1, 9443, 9441, 9440, -1, 9444, 9441, 9443, -1, 9445, 9442, 9437, -1, 9446, 9444, 9443, -1, 9447, 9446, 9443, -1, 9448, 9442, 9445, -1, 9449, 9450, 9451, -1, 9449, 9451, 9448, -1, 9452, 9453, 9446, -1, 9452, 9446, 9447, -1, 9454, 9455, 9450, -1, 9456, 9455, 9454, -1, 9457, 9456, 9454, -1, 9458, 9453, 9452, -1, 9459, 9453, 9458, -1, 9460, 9457, 9461, -1, 9460, 9456, 9457, -1, 9462, 9459, 9458, -1, 9463, 9460, 9461, -1, 9464, 9465, 9459, -1, 9464, 9459, 9462, -1, 9466, 9465, 9464, -1, 9467, 9460, 9463, -1, 9449, 9454, 9450, -1, 9468, 9445, 9469, -1, 9468, 9469, 9449, -1, 9468, 9448, 9445, -1, 9468, 9449, 9448, -1, 9470, 9463, 9465, -1, 9470, 9466, 9467, -1, 9470, 9467, 9463, -1, 9470, 9465, 9466, -1, 9471, 9472, 9473, -1, 9474, 9475, 9476, -1, 9477, 9478, 9479, -1, 9477, 9479, 9472, -1, 9477, 9471, 9480, -1, 9477, 9472, 9471, -1, 9481, 9482, 9478, -1, 9481, 9478, 9477, -1, 9483, 9480, 9484, -1, 9483, 9484, 9485, -1, 9483, 9477, 9480, -1, 9486, 9487, 9474, -1, 9486, 9476, 9482, -1, 9486, 9474, 9476, -1, 9486, 9482, 9481, -1, 9488, 9485, 9489, -1, 9488, 9489, 9490, -1, 9488, 9490, 9491, -1, 9488, 9483, 9485, -1, 9488, 9481, 9477, -1, 9488, 9477, 9483, -1, 9492, 9491, 9493, -1, 9492, 9493, 9494, -1, 9492, 9494, 9487, -1, 9492, 9488, 9491, -1, 9492, 9487, 9486, -1, 9492, 9486, 9481, -1, 9492, 9481, 9488, -1, 9495, 9496, 9497, -1, 9498, 9499, 9500, -1, 9501, 9498, 9500, -1, 9502, 9503, 9504, -1, 9502, 9504, 9505, -1, 9502, 9505, 9506, -1, 9507, 9508, 9509, -1, 9507, 9509, 9503, -1, 9507, 9503, 9502, -1, 9510, 9506, 9496, -1, 9510, 9495, 9511, -1, 9510, 9496, 9495, -1, 9510, 9502, 9506, -1, 9512, 9513, 9514, -1, 9512, 9514, 9515, -1, 9512, 9515, 9508, -1, 9512, 9508, 9507, -1, 9516, 9511, 9517, -1, 9516, 9510, 9511, -1, 9516, 9502, 9510, -1, 9516, 9507, 9502, -1, 9518, 9517, 9499, -1, 9518, 9498, 9513, -1, 9518, 9516, 9517, -1, 9518, 9512, 9507, -1, 9518, 9507, 9516, -1, 9518, 9499, 9498, -1, 9518, 9513, 9512, -1, 9519, 9520, 9521, -1, 9522, 9523, 9524, -1, 9525, 9526, 9527, -1, 9525, 9527, 9519, -1, 9525, 9521, 9528, -1, 9525, 9519, 9521, -1, 9529, 9530, 9524, -1, 9529, 9523, 9526, -1, 9529, 9528, 9530, -1, 9529, 9525, 9528, -1, 9529, 9526, 9525, -1, 9529, 9524, 9523, -1, 9531, 9532, 9533, -1, 9534, 9535, 9536, -1, 9537, 9535, 9534, -1, 9538, 9539, 9540, -1, 9538, 9540, 9541, -1, 9538, 9541, 9542, -1, 9543, 9544, 9539, -1, 9543, 9545, 9544, -1, 9543, 9539, 9538, -1, 9546, 9542, 9532, -1, 9546, 9531, 9547, -1, 9546, 9538, 9542, -1, 9546, 9532, 9531, -1, 9548, 9549, 9550, -1, 9548, 9550, 9551, -1, 9548, 9551, 9545, -1, 9548, 9545, 9543, -1, 9552, 9547, 9553, -1, 9552, 9546, 9547, -1, 9552, 9538, 9546, -1, 9552, 9543, 9538, -1, 9554, 9553, 9536, -1, 9554, 9535, 9549, -1, 9554, 9548, 9543, -1, 9554, 9552, 9553, -1, 9554, 9543, 9552, -1, 9554, 9536, 9535, -1, 9554, 9549, 9548, -1, 9555, 9556, 9557, -1, 9558, 9559, 9560, -1, 9561, 9559, 9558, -1, 9562, 9563, 9564, -1, 9562, 9564, 9565, -1, 9562, 9565, 9566, -1, 9567, 9568, 9569, -1, 9567, 9569, 9563, -1, 9567, 9563, 9562, -1, 9570, 9566, 9556, -1, 9570, 9555, 9571, -1, 9570, 9556, 9555, -1, 9570, 9562, 9566, -1, 9572, 9573, 9574, -1, 9572, 9574, 9575, -1, 9572, 9575, 9568, -1, 9572, 9568, 9567, -1, 9576, 9571, 9577, -1, 9576, 9570, 9571, -1, 9576, 9562, 9570, -1, 9576, 9567, 9562, -1, 9578, 9577, 9560, -1, 9578, 9559, 9573, -1, 9578, 9576, 9577, -1, 9578, 9572, 9567, -1, 9578, 9567, 9576, -1, 9578, 9560, 9559, -1, 9578, 9573, 9572, -1, 9579, 9580, 9581, -1, 9582, 9583, 9584, -1, 9585, 9583, 9582, -1, 9586, 9587, 9588, -1, 9586, 9588, 9589, -1, 9586, 9589, 9590, -1, 9591, 9592, 9587, -1, 9591, 9593, 9592, -1, 9591, 9587, 9586, -1, 9594, 9590, 9580, -1, 9594, 9579, 9595, -1, 9594, 9586, 9590, -1, 9594, 9580, 9579, -1, 9596, 9597, 9598, -1, 9596, 9598, 9599, -1, 9596, 9599, 9593, -1, 9596, 9593, 9591, -1, 9600, 9595, 9601, -1, 9600, 9594, 9595, -1, 9600, 9586, 9594, -1, 9600, 9591, 9586, -1, 9602, 9601, 9584, -1, 9602, 9583, 9597, -1, 9602, 9596, 9591, -1, 9602, 9600, 9601, -1, 9602, 9591, 9600, -1, 9602, 9584, 9583, -1, 9602, 9597, 9596, -1, 9603, 9604, 9605, -1, 9606, 9607, 9608, -1, 9609, 9610, 9611, -1, 9609, 9611, 9604, -1, 9609, 9603, 9612, -1, 9609, 9604, 9603, -1, 9613, 9614, 9610, -1, 9613, 9610, 9609, -1, 9615, 9612, 9616, -1, 9615, 9616, 9617, -1, 9615, 9609, 9612, -1, 9618, 9619, 9606, -1, 9618, 9608, 9614, -1, 9618, 9614, 9613, -1, 9618, 9606, 9608, -1, 9620, 9621, 9622, -1, 9620, 9617, 9623, -1, 9620, 9623, 9621, -1, 9620, 9615, 9617, -1, 9620, 9609, 9615, -1, 9620, 9613, 9609, -1, 9624, 9622, 9625, -1, 9624, 9625, 9626, -1, 9624, 9626, 9619, -1, 9624, 9613, 9620, -1, 9624, 9620, 9622, -1, 9624, 9619, 9618, -1, 9624, 9618, 9613, -1, 9627, 9628, 9629, -1, 9627, 9629, 9630, -1, 9631, 9627, 9630, -1, 9632, 9628, 9627, -1, 9633, 9631, 9630, -1, 9634, 9631, 9633, -1, 9635, 9632, 9627, -1, 9636, 9633, 9637, -1, 9636, 9634, 9633, -1, 9638, 9632, 9635, -1, 9639, 9640, 9641, -1, 9642, 9643, 9636, -1, 9642, 9636, 9637, -1, 9644, 9645, 9640, -1, 9646, 9645, 9644, -1, 9647, 9646, 9644, -1, 9648, 9643, 9642, -1, 9649, 9643, 9648, -1, 9650, 9647, 9651, -1, 9650, 9646, 9647, -1, 9652, 9649, 9648, -1, 9653, 9650, 9651, -1, 9654, 9655, 9649, -1, 9654, 9649, 9652, -1, 9656, 9655, 9654, -1, 9657, 9650, 9653, -1, 9639, 9644, 9640, -1, 9658, 9635, 9659, -1, 9658, 9659, 9639, -1, 9658, 9641, 9638, -1, 9658, 9639, 9641, -1, 9658, 9638, 9635, -1, 9660, 9653, 9655, -1, 9660, 9656, 9657, -1, 9660, 9657, 9653, -1, 9660, 9655, 9656, -1, 9661, 9662, 9663, -1, 9664, 9665, 9666, -1, 9667, 9668, 9669, -1, 9667, 9669, 9662, -1, 9667, 9661, 9670, -1, 9667, 9662, 9661, -1, 9671, 9672, 9668, -1, 9671, 9668, 9667, -1, 9673, 9670, 9674, -1, 9673, 9674, 9675, -1, 9673, 9667, 9670, -1, 9676, 9677, 9664, -1, 9676, 9666, 9672, -1, 9676, 9664, 9666, -1, 9676, 9672, 9671, -1, 9678, 9675, 9679, -1, 9678, 9679, 9680, -1, 9678, 9680, 9681, -1, 9678, 9673, 9675, -1, 9678, 9671, 9667, -1, 9678, 9667, 9673, -1, 9682, 9681, 9683, -1, 9682, 9683, 9684, -1, 9682, 9684, 9677, -1, 9682, 9678, 9681, -1, 9682, 9677, 9676, -1, 9682, 9676, 9671, -1, 9682, 9671, 9678, -1, 9685, 9686, 9687, -1, 9685, 9687, 9688, -1, 9689, 9685, 9688, -1, 9690, 9686, 9685, -1, 9691, 9689, 9688, -1, 9692, 9689, 9691, -1, 9693, 9690, 9685, -1, 9694, 9692, 9691, -1, 9695, 9694, 9691, -1, 9696, 9690, 9693, -1, 9697, 9698, 9699, -1, 9697, 9699, 9696, -1, 9700, 9701, 9694, -1, 9700, 9694, 9695, -1, 9702, 9703, 9698, -1, 9704, 9703, 9702, -1, 9705, 9704, 9702, -1, 9706, 9701, 9700, -1, 9707, 9701, 9706, -1, 9708, 9705, 9709, -1, 9708, 9704, 9705, -1, 9710, 9707, 9706, -1, 9711, 9708, 9709, -1, 9712, 9713, 9707, -1, 9712, 9707, 9710, -1, 9714, 9713, 9712, -1, 9715, 9708, 9711, -1, 9697, 9702, 9698, -1, 9716, 9693, 9717, -1, 9716, 9717, 9697, -1, 9716, 9696, 9693, -1, 9716, 9697, 9696, -1, 9718, 9711, 9713, -1, 9718, 9714, 9715, -1, 9718, 9715, 9711, -1, 9718, 9713, 9714, -1, 9719, 9720, 9721, -1, 9722, 9723, 9724, -1, 9725, 9723, 9722, -1, 9726, 9727, 9728, -1, 9726, 9728, 9729, -1, 9726, 9729, 9730, -1, 9731, 9732, 9733, -1, 9731, 9733, 9727, -1, 9731, 9727, 9726, -1, 9734, 9730, 9720, -1, 9734, 9719, 9735, -1, 9734, 9720, 9719, -1, 9734, 9726, 9730, -1, 9736, 9737, 9738, -1, 9736, 9738, 9739, -1, 9736, 9739, 9732, -1, 9736, 9732, 9731, -1, 9740, 9735, 9741, -1, 9740, 9734, 9735, -1, 9740, 9726, 9734, -1, 9740, 9731, 9726, -1, 9742, 9741, 9724, -1, 9742, 9723, 9737, -1, 9742, 9740, 9741, -1, 9742, 9736, 9731, -1, 9742, 9731, 9740, -1, 9742, 9724, 9723, -1, 9742, 9737, 9736, -1, 9743, 9744, 9745, -1, 9746, 9747, 9748, -1, 9749, 9747, 9746, -1, 9750, 9751, 9752, -1, 9750, 9752, 9753, -1, 9750, 9753, 9754, -1, 9755, 9756, 9757, -1, 9755, 9757, 9751, -1, 9755, 9751, 9750, -1, 9758, 9754, 9744, -1, 9758, 9743, 9759, -1, 9758, 9744, 9743, -1, 9758, 9750, 9754, -1, 9760, 9761, 9762, -1, 9760, 9762, 9763, -1, 9760, 9763, 9756, -1, 9760, 9756, 9755, -1, 9764, 9759, 9765, -1, 9764, 9758, 9759, -1, 9764, 9750, 9758, -1, 9764, 9755, 9750, -1, 9766, 9765, 9748, -1, 9766, 9747, 9761, -1, 9766, 9764, 9765, -1, 9766, 9760, 9755, -1, 9766, 9755, 9764, -1, 9766, 9748, 9747, -1, 9766, 9761, 9760, -1, 9767, 9768, 9769, -1, 9770, 9771, 9772, -1, 9773, 9774, 9775, -1, 9773, 9775, 9767, -1, 9773, 9769, 9776, -1, 9773, 9767, 9769, -1, 9777, 9778, 9772, -1, 9777, 9771, 9774, -1, 9777, 9776, 9778, -1, 9777, 9773, 9776, -1, 9777, 9774, 9773, -1, 9777, 9772, 9771, -1, 9779, 9780, 9781, -1, 9782, 9783, 9784, -1, 9785, 9782, 9784, -1, 9786, 9787, 9788, -1, 9786, 9788, 9789, -1, 9786, 9789, 9790, -1, 9791, 9792, 9793, -1, 9791, 9793, 9787, -1, 9791, 9787, 9786, -1, 9794, 9790, 9780, -1, 9794, 9779, 9795, -1, 9794, 9780, 9779, -1, 9794, 9786, 9790, -1, 9796, 9797, 9798, -1, 9796, 9798, 9799, -1, 9796, 9799, 9792, -1, 9796, 9792, 9791, -1, 9800, 9795, 9801, -1, 9800, 9794, 9795, -1, 9800, 9786, 9794, -1, 9800, 9791, 9786, -1, 9802, 9801, 9783, -1, 9802, 9782, 9797, -1, 9802, 9800, 9801, -1, 9802, 9796, 9791, -1, 9802, 9791, 9800, -1, 9802, 9783, 9782, -1, 9802, 9797, 9796, -1, 9803, 9804, 9805, -1, 9806, 9807, 9808, -1, 9809, 9807, 9806, -1, 9810, 9811, 9812, -1, 9810, 9812, 9813, -1, 9810, 9813, 9814, -1, 9815, 9816, 9811, -1, 9815, 9817, 9816, -1, 9815, 9811, 9810, -1, 9818, 9814, 9804, -1, 9818, 9803, 9819, -1, 9818, 9810, 9814, -1, 9818, 9804, 9803, -1, 9820, 9821, 9822, -1, 9820, 9822, 9823, -1, 9820, 9823, 9817, -1, 9820, 9817, 9815, -1, 9824, 9819, 9825, -1, 9824, 9818, 9819, -1, 9824, 9810, 9818, -1, 9824, 9815, 9810, -1, 9826, 9825, 9808, -1, 9826, 9807, 9821, -1, 9826, 9820, 9815, -1, 9826, 9824, 9825, -1, 9826, 9815, 9824, -1, 9826, 9808, 9807, -1, 9826, 9821, 9820, -1, 9827, 9828, 9829, -1, 9827, 9829, 9830, -1, 9831, 9827, 9830, -1, 9832, 9828, 9827, -1, 9833, 9831, 9830, -1, 9834, 9831, 9833, -1, 9835, 9832, 9827, -1, 9836, 9834, 9833, -1, 9837, 9836, 9833, -1, 9838, 9832, 9835, -1, 9839, 9840, 9841, -1, 9839, 9841, 9838, -1, 9842, 9843, 9836, -1, 9842, 9836, 9837, -1, 9844, 9845, 9840, -1, 9846, 9845, 9844, -1, 9847, 9846, 9844, -1, 9848, 9843, 9842, -1, 9849, 9843, 9848, -1, 9850, 9847, 9851, -1, 9850, 9846, 9847, -1, 9852, 9849, 9848, -1, 9853, 9850, 9851, -1, 9854, 9855, 9849, -1, 9854, 9849, 9852, -1, 9856, 9855, 9854, -1, 9857, 9850, 9853, -1, 9839, 9844, 9840, -1, 9858, 9835, 9859, -1, 9858, 9859, 9839, -1, 9858, 9838, 9835, -1, 9858, 9839, 9838, -1, 9860, 9853, 9855, -1, 9860, 9856, 9857, -1, 9860, 9857, 9853, -1, 9860, 9855, 9856, -1, 9861, 9862, 9863, -1, 9864, 9865, 9866, -1, 9867, 9868, 9869, -1, 9867, 9869, 9862, -1, 9867, 9861, 9870, -1, 9867, 9862, 9861, -1, 9871, 9872, 9868, -1, 9871, 9868, 9867, -1, 9873, 9870, 9874, -1, 9873, 9874, 9875, -1, 9873, 9867, 9870, -1, 9876, 9877, 9864, -1, 9876, 9866, 9872, -1, 9876, 9872, 9871, -1, 9876, 9864, 9866, -1, 9878, 9879, 9880, -1, 9878, 9875, 9881, -1, 9878, 9881, 9879, -1, 9878, 9873, 9875, -1, 9878, 9867, 9873, -1, 9878, 9871, 9867, -1, 9882, 9880, 9883, -1, 9882, 9883, 9884, -1, 9882, 9884, 9877, -1, 9882, 9871, 9878, -1, 9882, 9878, 9880, -1, 9882, 9877, 9876, -1, 9882, 9876, 9871, -1, 9885, 9886, 9887, -1, 9885, 9887, 9888, -1, 9889, 9885, 9888, -1, 9890, 9886, 9885, -1, 9891, 9889, 9888, -1, 9892, 9889, 9891, -1, 9893, 9890, 9885, -1, 9894, 9891, 9895, -1, 9894, 9892, 9891, -1, 9896, 9890, 9893, -1, 9897, 9898, 9899, -1, 9900, 9901, 9894, -1, 9900, 9894, 9895, -1, 9902, 9903, 9898, -1, 9904, 9903, 9902, -1, 9905, 9904, 9902, -1, 9906, 9901, 9900, -1, 9907, 9901, 9906, -1, 9908, 9905, 9909, -1, 9908, 9904, 9905, -1, 9910, 9907, 9906, -1, 9911, 9908, 9909, -1, 9912, 9913, 9907, -1, 9912, 9907, 9910, -1, 9914, 9913, 9912, -1, 9915, 9908, 9911, -1, 9897, 9902, 9898, -1, 9916, 9893, 9917, -1, 9916, 9917, 9897, -1, 9916, 9899, 9896, -1, 9916, 9897, 9899, -1, 9916, 9896, 9893, -1, 9918, 9911, 9913, -1, 9918, 9914, 9915, -1, 9918, 9915, 9911, -1, 9918, 9913, 9914, -1, 9919, 9920, 9921, -1, 9922, 9923, 9924, -1, 9925, 9926, 9927, -1, 9925, 9927, 9920, -1, 9925, 9919, 9928, -1, 9925, 9920, 9919, -1, 9929, 9930, 9926, -1, 9929, 9926, 9925, -1, 9931, 9928, 9932, -1, 9931, 9932, 9933, -1, 9931, 9925, 9928, -1, 9934, 9935, 9922, -1, 9934, 9924, 9930, -1, 9934, 9930, 9929, -1, 9934, 9922, 9924, -1, 9936, 9937, 9938, -1, 9936, 9933, 9939, -1, 9936, 9939, 9937, -1, 9936, 9931, 9933, -1, 9936, 9925, 9931, -1, 9936, 9929, 9925, -1, 9940, 9938, 9941, -1, 9940, 9941, 9942, -1, 9940, 9942, 9935, -1, 9940, 9929, 9936, -1, 9940, 9936, 9938, -1, 9940, 9935, 9934, -1, 9940, 9934, 9929, -1, 9943, 9944, 9945, -1, 9946, 9947, 9948, -1, 9949, 9947, 9946, -1, 9950, 9951, 9952, -1, 9950, 9952, 9953, -1, 9950, 9953, 9954, -1, 9955, 9956, 9957, -1, 9955, 9957, 9951, -1, 9955, 9951, 9950, -1, 9958, 9954, 9944, -1, 9958, 9943, 9959, -1, 9958, 9944, 9943, -1, 9958, 9950, 9954, -1, 9960, 9961, 9962, -1, 9960, 9962, 9963, -1, 9960, 9963, 9956, -1, 9960, 9956, 9955, -1, 9964, 9959, 9965, -1, 9964, 9958, 9959, -1, 9964, 9950, 9958, -1, 9964, 9955, 9950, -1, 9966, 9965, 9948, -1, 9966, 9947, 9961, -1, 9966, 9964, 9965, -1, 9966, 9960, 9955, -1, 9966, 9955, 9964, -1, 9966, 9948, 9947, -1, 9966, 9961, 9960, -1, 9967, 9968, 9969, -1, 9970, 9971, 9972, -1, 9973, 9974, 9975, -1, 9973, 9975, 9967, -1, 9973, 9969, 9976, -1, 9973, 9967, 9969, -1, 9977, 9978, 9972, -1, 9977, 9971, 9974, -1, 9977, 9976, 9978, -1, 9977, 9973, 9976, -1, 9977, 9974, 9973, -1, 9977, 9972, 9971, -1, 9979, 9980, 9981, -1, 9982, 9983, 9984, -1, 9985, 9983, 9982, -1, 9986, 9987, 9988, -1, 9986, 9988, 9989, -1, 9986, 9989, 9990, -1, 9991, 9992, 9987, -1, 9991, 9993, 9992, -1, 9991, 9987, 9986, -1, 9994, 9990, 9980, -1, 9994, 9979, 9995, -1, 9994, 9986, 9990, -1, 9994, 9980, 9979, -1, 9996, 9997, 9998, -1, 9996, 9998, 9999, -1, 9996, 9999, 9993, -1, 9996, 9993, 9991, -1, 10000, 9995, 10001, -1, 10000, 9994, 9995, -1, 10000, 9986, 9994, -1, 10000, 9991, 9986, -1, 10002, 10001, 9984, -1, 10002, 9983, 9997, -1, 10002, 9996, 9991, -1, 10002, 10000, 10001, -1, 10002, 9991, 10000, -1, 10002, 9984, 9983, -1, 10002, 9997, 9996, -1, 10003, 10004, 10005, -1, 10006, 10007, 10008, -1, 10009, 10007, 10006, -1, 10010, 10011, 10012, -1, 10010, 10012, 10013, -1, 10010, 10013, 10014, -1, 10015, 10016, 10011, -1, 10015, 10017, 10016, -1, 10015, 10011, 10010, -1, 10018, 10014, 10004, -1, 10018, 10003, 10019, -1, 10018, 10010, 10014, -1, 10018, 10004, 10003, -1, 10020, 10021, 10022, -1, 10020, 10022, 10023, -1, 10020, 10023, 10017, -1, 10020, 10017, 10015, -1, 10024, 10019, 10025, -1, 10024, 10018, 10019, -1, 10024, 10010, 10018, -1, 10024, 10015, 10010, -1, 10026, 10025, 10008, -1, 10026, 10007, 10021, -1, 10026, 10020, 10015, -1, 10026, 10024, 10025, -1, 10026, 10015, 10024, -1, 10026, 10008, 10007, -1, 10026, 10021, 10020, -1, 10027, 10028, 10029, -1, 10030, 10031, 10032, -1, 10033, 10030, 10032, -1, 10034, 10035, 10036, -1, 10034, 10036, 10037, -1, 10034, 10037, 10038, -1, 10039, 10040, 10035, -1, 10039, 10041, 10040, -1, 10039, 10035, 10034, -1, 10042, 10038, 10028, -1, 10042, 10027, 10043, -1, 10042, 10034, 10038, -1, 10042, 10028, 10027, -1, 10044, 10045, 10046, -1, 10044, 10046, 10047, -1, 10044, 10047, 10041, -1, 10044, 10041, 10039, -1, 10048, 10043, 10049, -1, 10048, 10042, 10043, -1, 10048, 10034, 10042, -1, 10048, 10039, 10034, -1, 10050, 10049, 10031, -1, 10050, 10030, 10045, -1, 10050, 10044, 10039, -1, 10050, 10048, 10049, -1, 10050, 10039, 10048, -1, 10050, 10031, 10030, -1, 10050, 10045, 10044, -1, 10051, 10052, 10053, -1, 10054, 10055, 10056, -1, 10057, 10058, 10059, -1, 10057, 10059, 10052, -1, 10057, 10051, 10060, -1, 10057, 10052, 10051, -1, 10061, 10062, 10058, -1, 10061, 10058, 10057, -1, 10063, 10060, 10064, -1, 10063, 10064, 10065, -1, 10063, 10057, 10060, -1, 10066, 10067, 10054, -1, 10066, 10056, 10062, -1, 10066, 10062, 10061, -1, 10066, 10054, 10056, -1, 10068, 10065, 10069, -1, 10068, 10069, 10070, -1, 10068, 10070, 10071, -1, 10068, 10063, 10065, -1, 10068, 10057, 10063, -1, 10068, 10061, 10057, -1, 10072, 10071, 10073, -1, 10072, 10073, 10074, -1, 10072, 10074, 10067, -1, 10072, 10067, 10066, -1, 10072, 10068, 10071, -1, 10072, 10066, 10061, -1, 10072, 10061, 10068, -1, 10075, 10076, 10077, -1, 10075, 10077, 10078, -1, 10079, 10075, 10078, -1, 10080, 10076, 10075, -1, 10081, 10079, 10078, -1, 10082, 10079, 10081, -1, 10083, 10080, 10075, -1, 10084, 10082, 10081, -1, 10085, 10084, 10081, -1, 10086, 10080, 10083, -1, 10087, 10088, 10089, -1, 10087, 10089, 10086, -1, 10090, 10091, 10084, -1, 10090, 10084, 10085, -1, 10092, 10093, 10088, -1, 10094, 10093, 10092, -1, 10095, 10094, 10092, -1, 10096, 10091, 10090, -1, 10097, 10091, 10096, -1, 10098, 10095, 10099, -1, 10098, 10094, 10095, -1, 10100, 10097, 10096, -1, 10101, 10098, 10099, -1, 10102, 10103, 10097, -1, 10102, 10097, 10100, -1, 10104, 10103, 10102, -1, 10105, 10098, 10101, -1, 10087, 10092, 10088, -1, 10106, 10083, 10107, -1, 10106, 10107, 10087, -1, 10106, 10086, 10083, -1, 10106, 10087, 10086, -1, 10108, 10101, 10103, -1, 10108, 10104, 10105, -1, 10108, 10105, 10101, -1, 10108, 10103, 10104, -1, 10109, 10110, 10111, -1, 10112, 10113, 10114, -1, 10115, 10116, 10117, -1, 10115, 10117, 10110, -1, 10115, 10109, 10118, -1, 10115, 10110, 10109, -1, 10119, 10120, 10116, -1, 10119, 10116, 10115, -1, 10121, 10118, 10122, -1, 10121, 10122, 10123, -1, 10121, 10115, 10118, -1, 10124, 10125, 10112, -1, 10124, 10114, 10120, -1, 10124, 10120, 10119, -1, 10124, 10112, 10114, -1, 10126, 10127, 10128, -1, 10126, 10123, 10129, -1, 10126, 10129, 10127, -1, 10126, 10121, 10123, -1, 10126, 10115, 10121, -1, 10126, 10119, 10115, -1, 10130, 10128, 10131, -1, 10130, 10131, 10132, -1, 10130, 10132, 10125, -1, 10130, 10119, 10126, -1, 10130, 10126, 10128, -1, 10130, 10125, 10124, -1, 10130, 10124, 10119, -1, 10133, 10134, 10135, -1, 10133, 10135, 10136, -1, 10137, 10133, 10136, -1, 10138, 10134, 10133, -1, 10139, 10137, 10136, -1, 10140, 10137, 10139, -1, 10141, 10138, 10133, -1, 10142, 10139, 10143, -1, 10142, 10140, 10139, -1, 10144, 10138, 10141, -1, 10145, 10146, 10147, -1, 10148, 10149, 10142, -1, 10148, 10142, 10143, -1, 10150, 10151, 10146, -1, 10152, 10151, 10150, -1, 10153, 10152, 10150, -1, 10154, 10149, 10148, -1, 10155, 10149, 10154, -1, 10156, 10153, 10157, -1, 10156, 10152, 10153, -1, 10158, 10155, 10154, -1, 10159, 10156, 10157, -1, 10160, 10161, 10155, -1, 10160, 10155, 10158, -1, 10162, 10161, 10160, -1, 10163, 10156, 10159, -1, 10145, 10150, 10146, -1, 10164, 10141, 10165, -1, 10164, 10165, 10145, -1, 10164, 10147, 10144, -1, 10164, 10145, 10147, -1, 10164, 10144, 10141, -1, 10166, 10159, 10161, -1, 10166, 10162, 10163, -1, 10166, 10163, 10159, -1, 10166, 10161, 10162, -1, 10167, 10168, 10169, -1, 10170, 10171, 10172, -1, 10173, 10170, 10172, -1, 10174, 10175, 10176, -1, 10174, 10176, 10177, -1, 10174, 10177, 10178, -1, 10179, 10180, 10175, -1, 10179, 10181, 10180, -1, 10179, 10175, 10174, -1, 10182, 10178, 10168, -1, 10182, 10167, 10183, -1, 10182, 10174, 10178, -1, 10182, 10168, 10167, -1, 10184, 10185, 10186, -1, 10184, 10186, 10187, -1, 10184, 10187, 10181, -1, 10184, 10181, 10179, -1, 10188, 10183, 10189, -1, 10188, 10182, 10183, -1, 10188, 10174, 10182, -1, 10188, 10179, 10174, -1, 10190, 10189, 10171, -1, 10190, 10170, 10185, -1, 10190, 10184, 10179, -1, 10190, 10188, 10189, -1, 10190, 10179, 10188, -1, 10190, 10171, 10170, -1, 10190, 10185, 10184, -1, 10191, 10192, 10193, -1, 10194, 10195, 10196, -1, 10197, 10195, 10194, -1, 10198, 10199, 10200, -1, 10198, 10200, 10201, -1, 10198, 10201, 10202, -1, 10203, 10204, 10205, -1, 10203, 10205, 10199, -1, 10203, 10199, 10198, -1, 10206, 10202, 10192, -1, 10206, 10191, 10207, -1, 10206, 10192, 10191, -1, 10206, 10198, 10202, -1, 10208, 10209, 10210, -1, 10208, 10210, 10211, -1, 10208, 10211, 10204, -1, 10208, 10204, 10203, -1, 10212, 10207, 10213, -1, 10212, 10206, 10207, -1, 10212, 10198, 10206, -1, 10212, 10203, 10198, -1, 10214, 10213, 10196, -1, 10214, 10195, 10209, -1, 10214, 10212, 10213, -1, 10214, 10208, 10203, -1, 10214, 10203, 10212, -1, 10214, 10196, 10195, -1, 10214, 10209, 10208, -1, 10215, 10216, 10217, -1, 10218, 10219, 10220, -1, 10221, 10217, 10222, -1, 10221, 10222, 10223, -1, 10221, 10224, 10215, -1, 10221, 10215, 10217, -1, 10225, 10223, 10219, -1, 10225, 10218, 10226, -1, 10225, 10226, 10224, -1, 10225, 10221, 10223, -1, 10225, 10219, 10218, -1, 10225, 10224, 10221, -1, 10227, 10228, 10229, -1, 10230, 10231, 10232, -1, 10233, 10231, 10230, -1, 10234, 10235, 10236, -1, 10234, 10236, 10237, -1, 10234, 10237, 10238, -1, 10239, 10240, 10235, -1, 10239, 10241, 10240, -1, 10239, 10235, 10234, -1, 10242, 10238, 10228, -1, 10242, 10227, 10243, -1, 10242, 10234, 10238, -1, 10242, 10228, 10227, -1, 10244, 10245, 10246, -1, 10244, 10246, 10247, -1, 10244, 10247, 10241, -1, 10244, 10241, 10239, -1, 10248, 10243, 10249, -1, 10248, 10242, 10243, -1, 10248, 10234, 10242, -1, 10248, 10239, 10234, -1, 10250, 10249, 10232, -1, 10250, 10231, 10245, -1, 10250, 10244, 10239, -1, 10250, 10248, 10249, -1, 10250, 10239, 10248, -1, 10250, 10232, 10231, -1, 10250, 10245, 10244, -1, 10251, 10252, 10253, -1, 10254, 10255, 10256, -1, 10257, 10255, 10254, -1, 10258, 10259, 10260, -1, 10258, 10260, 10261, -1, 10258, 10261, 10262, -1, 10263, 10264, 10265, -1, 10263, 10265, 10259, -1, 10263, 10259, 10258, -1, 10266, 10262, 10252, -1, 10266, 10251, 10267, -1, 10266, 10252, 10251, -1, 10266, 10258, 10262, -1, 10268, 10269, 10270, -1, 10268, 10270, 10271, -1, 10268, 10271, 10264, -1, 10268, 10264, 10263, -1, 10272, 10267, 10273, -1, 10272, 10266, 10267, -1, 10272, 10258, 10266, -1, 10272, 10263, 10258, -1, 10274, 10273, 10256, -1, 10274, 10255, 10269, -1, 10274, 10272, 10273, -1, 10274, 10268, 10263, -1, 10274, 10263, 10272, -1, 10274, 10256, 10255, -1, 10274, 10269, 10268, -1, 10275, 10276, 10277, -1, 10275, 10277, 10278, -1, 10279, 10275, 10278, -1, 10280, 10276, 10275, -1, 10281, 10279, 10278, -1, 10282, 10279, 10281, -1, 10283, 10280, 10275, -1, 10284, 10281, 10285, -1, 10284, 10282, 10281, -1, 10286, 10280, 10283, -1, 10287, 10288, 10289, -1, 10290, 10291, 10284, -1, 10290, 10284, 10285, -1, 10292, 10293, 10288, -1, 10294, 10293, 10292, -1, 10295, 10294, 10292, -1, 10296, 10291, 10290, -1, 10297, 10291, 10296, -1, 10298, 10295, 10299, -1, 10298, 10294, 10295, -1, 10300, 10297, 10296, -1, 10301, 10298, 10299, -1, 10302, 10303, 10297, -1, 10302, 10297, 10300, -1, 10304, 10303, 10302, -1, 10305, 10298, 10301, -1, 10287, 10292, 10288, -1, 10306, 10283, 10307, -1, 10306, 10307, 10287, -1, 10306, 10289, 10286, -1, 10306, 10287, 10289, -1, 10306, 10286, 10283, -1, 10308, 10301, 10303, -1, 10308, 10304, 10305, -1, 10308, 10305, 10301, -1, 10308, 10303, 10304, -1, 10309, 10310, 10311, -1, 10309, 10311, 10312, -1, 10313, 10309, 10312, -1, 10314, 10310, 10309, -1, 10315, 10313, 10312, -1, 10316, 10313, 10315, -1, 10317, 10314, 10309, -1, 10318, 10316, 10315, -1, 10319, 10318, 10315, -1, 10320, 10314, 10317, -1, 10321, 10322, 10323, -1, 10321, 10323, 10320, -1, 10324, 10325, 10318, -1, 10324, 10318, 10319, -1, 10326, 10327, 10322, -1, 10328, 10327, 10326, -1, 10329, 10328, 10326, -1, 10330, 10325, 10324, -1, 10331, 10325, 10330, -1, 10332, 10329, 10333, -1, 10332, 10328, 10329, -1, 10334, 10331, 10330, -1, 10335, 10332, 10333, -1, 10336, 10337, 10331, -1, 10336, 10331, 10334, -1, 10338, 10337, 10336, -1, 10339, 10332, 10335, -1, 10321, 10326, 10322, -1, 10340, 10317, 10341, -1, 10340, 10341, 10321, -1, 10340, 10320, 10317, -1, 10340, 10321, 10320, -1, 10342, 10335, 10337, -1, 10342, 10338, 10339, -1, 10342, 10339, 10335, -1, 10342, 10337, 10338, -1, 10343, 10344, 10345, -1, 10346, 10347, 10348, -1, 10349, 10350, 10351, -1, 10349, 10351, 10344, -1, 10349, 10343, 10352, -1, 10349, 10344, 10343, -1, 10353, 10354, 10350, -1, 10353, 10350, 10349, -1, 10355, 10352, 10356, -1, 10355, 10356, 10357, -1, 10355, 10349, 10352, -1, 10358, 10359, 10346, -1, 10358, 10348, 10354, -1, 10358, 10354, 10353, -1, 10358, 10346, 10348, -1, 10360, 10361, 10362, -1, 10360, 10357, 10363, -1, 10360, 10363, 10361, -1, 10360, 10355, 10357, -1, 10360, 10349, 10355, -1, 10360, 10353, 10349, -1, 10364, 10362, 10365, -1, 10364, 10365, 10366, -1, 10364, 10366, 10359, -1, 10364, 10353, 10360, -1, 10364, 10360, 10362, -1, 10364, 10359, 10358, -1, 10364, 10358, 10353, -1, 10367, 10368, 10369, -1, 10370, 10371, 10372, -1, 10373, 10374, 10375, -1, 10373, 10375, 10368, -1, 10373, 10367, 10376, -1, 10373, 10368, 10367, -1, 10377, 10378, 10374, -1, 10377, 10374, 10373, -1, 10379, 10376, 10380, -1, 10379, 10380, 10381, -1, 10379, 10373, 10376, -1, 10382, 10383, 10370, -1, 10382, 10372, 10378, -1, 10382, 10378, 10377, -1, 10382, 10370, 10372, -1, 10384, 10381, 10385, -1, 10384, 10385, 10386, -1, 10384, 10386, 10387, -1, 10384, 10379, 10381, -1, 10384, 10373, 10379, -1, 10384, 10377, 10373, -1, 10388, 10387, 10389, -1, 10388, 10389, 10390, -1, 10388, 10390, 10383, -1, 10388, 10383, 10382, -1, 10388, 10384, 10387, -1, 10388, 10382, 10377, -1, 10388, 10377, 10384, -1, 10391, 10392, 10393, -1, 10394, 10395, 10396, -1, 10397, 10393, 10398, -1, 10397, 10398, 10399, -1, 10397, 10400, 10391, -1, 10397, 10391, 10393, -1, 10401, 10399, 10395, -1, 10401, 10394, 10402, -1, 10401, 10402, 10400, -1, 10401, 10397, 10399, -1, 10401, 10395, 10394, -1, 10401, 10400, 10397, -1, 10403, 10404, 10405, -1, 10406, 10407, 10408, -1, 10409, 10406, 10408, -1, 10410, 10411, 10412, -1, 10410, 10412, 10413, -1, 10410, 10413, 10414, -1, 10415, 10416, 10417, -1, 10415, 10417, 10411, -1, 10415, 10411, 10410, -1, 10418, 10414, 10404, -1, 10418, 10403, 10419, -1, 10418, 10404, 10403, -1, 10418, 10410, 10414, -1, 10420, 10421, 10422, -1, 10420, 10422, 10423, -1, 10420, 10423, 10416, -1, 10420, 10416, 10415, -1, 10424, 10419, 10425, -1, 10424, 10418, 10419, -1, 10424, 10410, 10418, -1, 10424, 10415, 10410, -1, 10426, 10425, 10407, -1, 10426, 10406, 10421, -1, 10426, 10424, 10425, -1, 10426, 10420, 10415, -1, 10426, 10415, 10424, -1, 10426, 10407, 10406, -1, 10426, 10421, 10420, -1, 10427, 10428, 10429, -1, 10430, 10431, 10432, -1, 10433, 10431, 10430, -1, 10434, 10435, 10436, -1, 10434, 10436, 10437, -1, 10434, 10437, 10438, -1, 10439, 10440, 10441, -1, 10439, 10441, 10435, -1, 10439, 10435, 10434, -1, 10442, 10438, 10428, -1, 10442, 10427, 10443, -1, 10442, 10428, 10427, -1, 10442, 10434, 10438, -1, 10444, 10445, 10446, -1, 10444, 10446, 10447, -1, 10444, 10447, 10440, -1, 10444, 10440, 10439, -1, 10448, 10443, 10449, -1, 10448, 10442, 10443, -1, 10448, 10434, 10442, -1, 10448, 10439, 10434, -1, 10450, 10449, 10432, -1, 10450, 10431, 10445, -1, 10450, 10448, 10449, -1, 10450, 10444, 10439, -1, 10450, 10439, 10448, -1, 10450, 10432, 10431, -1, 10450, 10445, 10444, -1, 10451, 10452, 10453, -1, 10454, 10455, 10456, -1, 10457, 10455, 10454, -1, 10458, 10459, 10460, -1, 10458, 10460, 10461, -1, 10458, 10461, 10462, -1, 10463, 10464, 10465, -1, 10463, 10465, 10459, -1, 10463, 10459, 10458, -1, 10466, 10462, 10452, -1, 10466, 10451, 10467, -1, 10466, 10452, 10451, -1, 10466, 10458, 10462, -1, 10468, 10469, 10470, -1, 10468, 10470, 10471, -1, 10468, 10471, 10464, -1, 10468, 10464, 10463, -1, 10472, 10467, 10473, -1, 10472, 10466, 10467, -1, 10472, 10458, 10466, -1, 10472, 10463, 10458, -1, 10474, 10473, 10456, -1, 10474, 10455, 10469, -1, 10474, 10472, 10473, -1, 10474, 10468, 10463, -1, 10474, 10463, 10472, -1, 10474, 10456, 10455, -1, 10474, 10469, 10468, -1, 10475, 10476, 10477, -1, 10478, 10479, 10480, -1, 10481, 10479, 10478, -1, 10482, 10483, 10484, -1, 10482, 10484, 10485, -1, 10482, 10485, 10486, -1, 10487, 10488, 10489, -1, 10487, 10489, 10483, -1, 10487, 10483, 10482, -1, 10490, 10486, 10476, -1, 10490, 10475, 10491, -1, 10490, 10476, 10475, -1, 10490, 10482, 10486, -1, 10492, 10493, 10494, -1, 10492, 10494, 10495, -1, 10492, 10495, 10488, -1, 10492, 10488, 10487, -1, 10496, 10491, 10497, -1, 10496, 10490, 10491, -1, 10496, 10482, 10490, -1, 10496, 10487, 10482, -1, 10498, 10497, 10480, -1, 10498, 10479, 10493, -1, 10498, 10496, 10497, -1, 10498, 10492, 10487, -1, 10498, 10487, 10496, -1, 10498, 10480, 10479, -1, 10498, 10493, 10492, -1, 10499, 10500, 10501, -1, 10502, 10503, 10504, -1, 10505, 10501, 10506, -1, 10505, 10506, 10507, -1, 10505, 10508, 10499, -1, 10505, 10499, 10501, -1, 10509, 10507, 10503, -1, 10509, 10502, 10510, -1, 10509, 10510, 10508, -1, 10509, 10505, 10507, -1, 10509, 10503, 10502, -1, 10509, 10508, 10505, -1, 10511, 10512, 10513, -1, 10514, 10515, 10516, -1, 10517, 10514, 10516, -1, 10518, 10519, 10520, -1, 10518, 10520, 10521, -1, 10518, 10521, 10522, -1, 10523, 10524, 10525, -1, 10523, 10525, 10519, -1, 10523, 10519, 10518, -1, 10526, 10522, 10512, -1, 10526, 10511, 10527, -1, 10526, 10512, 10511, -1, 10526, 10518, 10522, -1, 10528, 10529, 10530, -1, 10528, 10530, 10531, -1, 10528, 10531, 10524, -1, 10528, 10524, 10523, -1, 10532, 10527, 10533, -1, 10532, 10526, 10527, -1, 10532, 10518, 10526, -1, 10532, 10523, 10518, -1, 10534, 10533, 10515, -1, 10534, 10514, 10529, -1, 10534, 10532, 10533, -1, 10534, 10528, 10523, -1, 10534, 10523, 10532, -1, 10534, 10515, 10514, -1, 10534, 10529, 10528, -1, 10535, 10536, 10537, -1, 10538, 10539, 10540, -1, 10541, 10539, 10538, -1, 10542, 10543, 10544, -1, 10542, 10544, 10545, -1, 10542, 10545, 10546, -1, 10547, 10548, 10543, -1, 10547, 10549, 10548, -1, 10547, 10543, 10542, -1, 10550, 10546, 10536, -1, 10550, 10535, 10551, -1, 10550, 10542, 10546, -1, 10550, 10536, 10535, -1, 10552, 10553, 10554, -1, 10552, 10554, 10555, -1, 10552, 10555, 10549, -1, 10552, 10549, 10547, -1, 10556, 10551, 10557, -1, 10556, 10550, 10551, -1, 10556, 10542, 10550, -1, 10556, 10547, 10542, -1, 10558, 10557, 10540, -1, 10558, 10539, 10553, -1, 10558, 10552, 10547, -1, 10558, 10556, 10557, -1, 10558, 10547, 10556, -1, 10558, 10540, 10539, -1, 10558, 10553, 10552, -1, 10559, 10560, 10561, -1, 10562, 10563, 10564, -1, 10565, 10563, 10562, -1, 10566, 10567, 10568, -1, 10566, 10568, 10569, -1, 10566, 10569, 10570, -1, 10571, 10572, 10567, -1, 10571, 10573, 10572, -1, 10571, 10567, 10566, -1, 10574, 10570, 10560, -1, 10574, 10559, 10575, -1, 10574, 10566, 10570, -1, 10574, 10560, 10559, -1, 10576, 10577, 10578, -1, 10576, 10578, 10579, -1, 10576, 10579, 10573, -1, 10576, 10573, 10571, -1, 10580, 10575, 10581, -1, 10580, 10574, 10575, -1, 10580, 10566, 10574, -1, 10580, 10571, 10566, -1, 10582, 10581, 10564, -1, 10582, 10563, 10577, -1, 10582, 10576, 10571, -1, 10582, 10580, 10581, -1, 10582, 10571, 10580, -1, 10582, 10564, 10563, -1, 10582, 10577, 10576, -1, 10583, 10584, 10585, -1, 10586, 10587, 10588, -1, 10589, 10587, 10586, -1, 10590, 10591, 10592, -1, 10590, 10592, 10593, -1, 10590, 10593, 10594, -1, 10595, 10596, 10597, -1, 10595, 10597, 10591, -1, 10595, 10591, 10590, -1, 10598, 10594, 10584, -1, 10598, 10583, 10599, -1, 10598, 10584, 10583, -1, 10598, 10590, 10594, -1, 10600, 10601, 10602, -1, 10600, 10602, 10603, -1, 10600, 10603, 10596, -1, 10600, 10596, 10595, -1, 10604, 10599, 10605, -1, 10604, 10598, 10599, -1, 10604, 10590, 10598, -1, 10604, 10595, 10590, -1, 10606, 10605, 10588, -1, 10606, 10587, 10601, -1, 10606, 10604, 10605, -1, 10606, 10600, 10595, -1, 10606, 10595, 10604, -1, 10606, 10588, 10587, -1, 10606, 10601, 10600, -1, 10607, 10608, 10609, -1, 10607, 10609, 10610, -1, 10611, 10607, 10610, -1, 10612, 10608, 10607, -1, 10613, 10611, 10610, -1, 10614, 10611, 10613, -1, 10615, 10612, 10607, -1, 10616, 10613, 10617, -1, 10616, 10614, 10613, -1, 10618, 10612, 10615, -1, 10619, 10620, 10621, -1, 10622, 10623, 10616, -1, 10622, 10616, 10617, -1, 10624, 10625, 10620, -1, 10626, 10625, 10624, -1, 10627, 10626, 10624, -1, 10628, 10623, 10622, -1, 10629, 10623, 10628, -1, 10630, 10627, 10631, -1, 10630, 10626, 10627, -1, 10632, 10629, 10628, -1, 10633, 10630, 10631, -1, 10634, 10635, 10629, -1, 10634, 10629, 10632, -1, 10636, 10635, 10634, -1, 10637, 10630, 10633, -1, 10619, 10624, 10620, -1, 10638, 10615, 10639, -1, 10638, 10639, 10619, -1, 10638, 10621, 10618, -1, 10638, 10619, 10621, -1, 10638, 10618, 10615, -1, 10640, 10633, 10635, -1, 10640, 10636, 10637, -1, 10640, 10637, 10633, -1, 10640, 10635, 10636, -1, 10641, 10642, 10643, -1, 10644, 10645, 10646, -1, 10647, 10648, 10649, -1, 10647, 10649, 10642, -1, 10647, 10641, 10650, -1, 10647, 10642, 10641, -1, 10651, 10652, 10648, -1, 10651, 10648, 10647, -1, 10653, 10650, 10654, -1, 10653, 10654, 10655, -1, 10653, 10647, 10650, -1, 10656, 10657, 10644, -1, 10656, 10646, 10652, -1, 10656, 10644, 10646, -1, 10656, 10652, 10651, -1, 10658, 10655, 10659, -1, 10658, 10659, 10660, -1, 10658, 10660, 10661, -1, 10658, 10653, 10655, -1, 10658, 10651, 10647, -1, 10658, 10647, 10653, -1, 10662, 10661, 10663, -1, 10662, 10663, 10664, -1, 10662, 10664, 10657, -1, 10662, 10658, 10661, -1, 10662, 10657, 10656, -1, 10662, 10656, 10651, -1, 10662, 10651, 10658, -1, 10665, 10666, 10667, -1, 10665, 10667, 10668, -1, 10669, 10665, 10668, -1, 10670, 10666, 10665, -1, 10671, 10669, 10668, -1, 10672, 10669, 10671, -1, 10673, 10670, 10665, -1, 10674, 10672, 10671, -1, 10675, 10674, 10671, -1, 10676, 10670, 10673, -1, 10677, 10678, 10679, -1, 10677, 10679, 10676, -1, 10680, 10681, 10674, -1, 10680, 10674, 10675, -1, 10682, 10683, 10678, -1, 10684, 10683, 10682, -1, 10685, 10684, 10682, -1, 10686, 10681, 10680, -1, 10687, 10681, 10686, -1, 10688, 10685, 10689, -1, 10688, 10684, 10685, -1, 10690, 10687, 10686, -1, 10691, 10688, 10689, -1, 10692, 10693, 10687, -1, 10692, 10687, 10690, -1, 10694, 10693, 10692, -1, 10695, 10688, 10691, -1, 10677, 10682, 10678, -1, 10696, 10673, 10697, -1, 10696, 10697, 10677, -1, 10696, 10676, 10673, -1, 10696, 10677, 10676, -1, 10698, 10691, 10693, -1, 10698, 10694, 10695, -1, 10698, 10695, 10691, -1, 10698, 10693, 10694, -1, 10699, 10700, 10701, -1, 10702, 10703, 10704, -1, 10705, 10706, 10707, -1, 10705, 10707, 10700, -1, 10705, 10699, 10708, -1, 10705, 10700, 10699, -1, 10709, 10710, 10706, -1, 10709, 10706, 10705, -1, 10711, 10708, 10712, -1, 10711, 10712, 10713, -1, 10711, 10705, 10708, -1, 10714, 10715, 10702, -1, 10714, 10704, 10710, -1, 10714, 10710, 10709, -1, 10714, 10702, 10704, -1, 10716, 10713, 10717, -1, 10716, 10717, 10718, -1, 10716, 10718, 10719, -1, 10716, 10711, 10713, -1, 10716, 10705, 10711, -1, 10716, 10709, 10705, -1, 10720, 10719, 10721, -1, 10720, 10721, 10722, -1, 10720, 10722, 10715, -1, 10720, 10715, 10714, -1, 10720, 10716, 10719, -1, 10720, 10714, 10709, -1, 10720, 10709, 10716, -1, 10723, 10724, 10725, -1, 10726, 10727, 10728, -1, 10729, 10730, 10731, -1, 10729, 10731, 10724, -1, 10729, 10723, 10732, -1, 10729, 10724, 10723, -1, 10733, 10734, 10730, -1, 10733, 10730, 10729, -1, 10735, 10732, 10736, -1, 10735, 10736, 10737, -1, 10735, 10729, 10732, -1, 10738, 10739, 10726, -1, 10738, 10728, 10734, -1, 10738, 10726, 10728, -1, 10738, 10734, 10733, -1, 10740, 10737, 10741, -1, 10740, 10741, 10742, -1, 10740, 10742, 10743, -1, 10740, 10735, 10737, -1, 10740, 10733, 10729, -1, 10740, 10729, 10735, -1, 10744, 10743, 10745, -1, 10744, 10745, 10746, -1, 10744, 10746, 10739, -1, 10744, 10740, 10743, -1, 10744, 10739, 10738, -1, 10744, 10738, 10733, -1, 10744, 10733, 10740, -1, 10747, 10748, 10749, -1, 10747, 10749, 10750, -1, 10751, 10747, 10750, -1, 10752, 10748, 10747, -1, 10753, 10751, 10750, -1, 10754, 10751, 10753, -1, 10755, 10752, 10747, -1, 10756, 10753, 10757, -1, 10756, 10754, 10753, -1, 10758, 10752, 10755, -1, 10759, 10760, 10761, -1, 10762, 10763, 10756, -1, 10762, 10756, 10757, -1, 10764, 10765, 10760, -1, 10766, 10765, 10764, -1, 10767, 10766, 10764, -1, 10768, 10763, 10762, -1, 10769, 10763, 10768, -1, 10770, 10767, 10771, -1, 10770, 10766, 10767, -1, 10772, 10769, 10768, -1, 10773, 10770, 10771, -1, 10774, 10775, 10769, -1, 10774, 10769, 10772, -1, 10776, 10775, 10774, -1, 10777, 10770, 10773, -1, 10759, 10764, 10760, -1, 10778, 10755, 10779, -1, 10778, 10779, 10759, -1, 10778, 10761, 10758, -1, 10778, 10759, 10761, -1, 10778, 10758, 10755, -1, 10780, 10773, 10775, -1, 10780, 10776, 10777, -1, 10780, 10777, 10773, -1, 10780, 10775, 10776, -1, 10781, 10782, 10783, -1, 10784, 10785, 10786, -1, 10787, 10788, 10789, -1, 10787, 10789, 10782, -1, 10787, 10781, 10790, -1, 10787, 10782, 10781, -1, 10791, 10792, 10788, -1, 10791, 10788, 10787, -1, 10793, 10790, 10794, -1, 10793, 10794, 10795, -1, 10793, 10787, 10790, -1, 10796, 10797, 10784, -1, 10796, 10786, 10792, -1, 10796, 10792, 10791, -1, 10796, 10784, 10786, -1, 10798, 10795, 10799, -1, 10798, 10799, 10800, -1, 10798, 10800, 10801, -1, 10798, 10793, 10795, -1, 10798, 10787, 10793, -1, 10798, 10791, 10787, -1, 10802, 10801, 10803, -1, 10802, 10803, 10804, -1, 10802, 10804, 10797, -1, 10802, 10797, 10796, -1, 10802, 10798, 10801, -1, 10802, 10796, 10791, -1, 10802, 10791, 10798, -1, 10805, 10806, 10807, -1, 10805, 10807, 10808, -1, 10809, 10805, 10808, -1, 10810, 10806, 10805, -1, 10811, 10809, 10808, -1, 10812, 10809, 10811, -1, 10813, 10810, 10805, -1, 10814, 10812, 10811, -1, 10815, 10814, 10811, -1, 10816, 10810, 10813, -1, 10817, 10818, 10819, -1, 10817, 10819, 10816, -1, 10820, 10821, 10814, -1, 10820, 10814, 10815, -1, 10822, 10823, 10818, -1, 10824, 10823, 10822, -1, 10825, 10824, 10822, -1, 10826, 10821, 10820, -1, 10827, 10821, 10826, -1, 10828, 10825, 10829, -1, 10828, 10824, 10825, -1, 10830, 10827, 10826, -1, 10831, 10828, 10829, -1, 10832, 10833, 10827, -1, 10832, 10827, 10830, -1, 10834, 10833, 10832, -1, 10835, 10828, 10831, -1, 10817, 10822, 10818, -1, 10836, 10813, 10837, -1, 10836, 10837, 10817, -1, 10836, 10816, 10813, -1, 10836, 10817, 10816, -1, 10838, 10831, 10833, -1, 10838, 10834, 10835, -1, 10838, 10835, 10831, -1, 10838, 10833, 10834, -1, 10839, 10840, 10841, -1, 10842, 10843, 10844, -1, 10845, 10843, 10842, -1, 10846, 10847, 10848, -1, 10846, 10848, 10849, -1, 10846, 10849, 10850, -1, 10851, 10852, 10847, -1, 10851, 10853, 10852, -1, 10851, 10847, 10846, -1, 10854, 10850, 10840, -1, 10854, 10839, 10855, -1, 10854, 10846, 10850, -1, 10854, 10840, 10839, -1, 10856, 10857, 10858, -1, 10856, 10858, 10859, -1, 10856, 10859, 10853, -1, 10856, 10853, 10851, -1, 10860, 10855, 10861, -1, 10860, 10854, 10855, -1, 10860, 10846, 10854, -1, 10860, 10851, 10846, -1, 10862, 10861, 10844, -1, 10862, 10843, 10857, -1, 10862, 10856, 10851, -1, 10862, 10860, 10861, -1, 10862, 10851, 10860, -1, 10862, 10844, 10843, -1, 10862, 10857, 10856, -1, 10863, 10864, 10865, -1, 10866, 10867, 10868, -1, 10869, 10867, 10866, -1, 10870, 10871, 10872, -1, 10870, 10872, 10873, -1, 10870, 10873, 10874, -1, 10875, 10876, 10877, -1, 10875, 10877, 10871, -1, 10875, 10871, 10870, -1, 10878, 10874, 10864, -1, 10878, 10863, 10879, -1, 10878, 10864, 10863, -1, 10878, 10870, 10874, -1, 10880, 10881, 10882, -1, 10880, 10882, 10883, -1, 10880, 10883, 10876, -1, 10880, 10876, 10875, -1, 10884, 10879, 10885, -1, 10884, 10878, 10879, -1, 10884, 10870, 10878, -1, 10884, 10875, 10870, -1, 10886, 10885, 10868, -1, 10886, 10867, 10881, -1, 10886, 10884, 10885, -1, 10886, 10880, 10875, -1, 10886, 10875, 10884, -1, 10886, 10868, 10867, -1, 10886, 10881, 10880, -1, 10887, 10888, 10889, -1, 10890, 10891, 10892, -1, 10893, 10891, 10890, -1, 10894, 10895, 10896, -1, 10894, 10896, 10897, -1, 10894, 10897, 10898, -1, 10899, 10900, 10895, -1, 10899, 10901, 10900, -1, 10899, 10895, 10894, -1, 10902, 10898, 10888, -1, 10902, 10887, 10903, -1, 10902, 10894, 10898, -1, 10902, 10888, 10887, -1, 10904, 10905, 10906, -1, 10904, 10906, 10907, -1, 10904, 10907, 10901, -1, 10904, 10901, 10899, -1, 10908, 10903, 10909, -1, 10908, 10902, 10903, -1, 10908, 10894, 10902, -1, 10908, 10899, 10894, -1, 10910, 10909, 10892, -1, 10910, 10891, 10905, -1, 10910, 10904, 10899, -1, 10910, 10908, 10909, -1, 10910, 10899, 10908, -1, 10910, 10892, 10891, -1, 10910, 10905, 10904, -1, 10911, 10912, 10913, -1, 10914, 10915, 10916, -1, 10917, 10914, 10916, -1, 10918, 10919, 10920, -1, 10918, 10920, 10921, -1, 10918, 10921, 10922, -1, 10923, 10924, 10919, -1, 10923, 10925, 10924, -1, 10923, 10919, 10918, -1, 10926, 10922, 10912, -1, 10926, 10911, 10927, -1, 10926, 10918, 10922, -1, 10926, 10912, 10911, -1, 10928, 10929, 10930, -1, 10928, 10930, 10931, -1, 10928, 10931, 10925, -1, 10928, 10925, 10923, -1, 10932, 10927, 10933, -1, 10932, 10926, 10927, -1, 10932, 10918, 10926, -1, 10932, 10923, 10918, -1, 10934, 10933, 10915, -1, 10934, 10914, 10929, -1, 10934, 10928, 10923, -1, 10934, 10932, 10933, -1, 10934, 10923, 10932, -1, 10934, 10915, 10914, -1, 10934, 10929, 10928, -1, 10935, 10936, 10937, -1, 10938, 10939, 10940, -1, 10941, 10937, 10942, -1, 10941, 10942, 10943, -1, 10941, 10944, 10935, -1, 10941, 10935, 10937, -1, 10945, 10943, 10939, -1, 10945, 10938, 10946, -1, 10945, 10946, 10944, -1, 10945, 10941, 10943, -1, 10945, 10939, 10938, -1, 10945, 10944, 10941, -1, 10947, 10948, 10949, -1, 10950, 10951, 10952, -1, 10953, 10951, 10950, -1, 10954, 10955, 10956, -1, 10954, 10956, 10957, -1, 10954, 10957, 10958, -1, 10959, 10960, 10961, -1, 10959, 10961, 10955, -1, 10959, 10955, 10954, -1, 10962, 10958, 10948, -1, 10962, 10947, 10963, -1, 10962, 10948, 10947, -1, 10962, 10954, 10958, -1, 10964, 10965, 10966, -1, 10964, 10966, 10967, -1, 10964, 10967, 10960, -1, 10964, 10960, 10959, -1, 10968, 10963, 10969, -1, 10968, 10962, 10963, -1, 10968, 10954, 10962, -1, 10968, 10959, 10954, -1, 10970, 10969, 10952, -1, 10970, 10951, 10965, -1, 10970, 10968, 10969, -1, 10970, 10964, 10959, -1, 10970, 10959, 10968, -1, 10970, 10952, 10951, -1, 10970, 10965, 10964, -1, 10971, 10972, 10973, -1, 10974, 10975, 10976, -1, 10977, 10975, 10974, -1, 10978, 10979, 10980, -1, 10978, 10980, 10981, -1, 10978, 10981, 10982, -1, 10983, 10984, 10985, -1, 10983, 10985, 10979, -1, 10983, 10979, 10978, -1, 10986, 10982, 10972, -1, 10986, 10971, 10987, -1, 10986, 10972, 10971, -1, 10986, 10978, 10982, -1, 10988, 10989, 10990, -1, 10988, 10990, 10991, -1, 10988, 10991, 10984, -1, 10988, 10984, 10983, -1, 10992, 10987, 10993, -1, 10992, 10986, 10987, -1, 10992, 10978, 10986, -1, 10992, 10983, 10978, -1, 10994, 10993, 10976, -1, 10994, 10975, 10989, -1, 10994, 10992, 10993, -1, 10994, 10988, 10983, -1, 10994, 10983, 10992, -1, 10994, 10976, 10975, -1, 10994, 10989, 10988, -1, 10995, 10996, 10997, -1, 10998, 10999, 11000, -1, 11001, 11002, 11003, -1, 11001, 11003, 10995, -1, 11001, 10997, 11004, -1, 11001, 10995, 10997, -1, 11005, 11006, 11000, -1, 11005, 10999, 11002, -1, 11005, 11004, 11006, -1, 11005, 11001, 11004, -1, 11005, 11002, 11001, -1, 11005, 11000, 10999, -1, 11007, 11008, 11009, -1, 11010, 11011, 11012, -1, 11013, 11010, 11012, -1, 11014, 11015, 11016, -1, 11014, 11016, 11017, -1, 11014, 11017, 11018, -1, 11019, 11020, 11021, -1, 11019, 11021, 11015, -1, 11019, 11015, 11014, -1, 11022, 11018, 11008, -1, 11022, 11007, 11023, -1, 11022, 11008, 11007, -1, 11022, 11014, 11018, -1, 11024, 11025, 11026, -1, 11024, 11026, 11027, -1, 11024, 11027, 11020, -1, 11024, 11020, 11019, -1, 11028, 11023, 11029, -1, 11028, 11022, 11023, -1, 11028, 11014, 11022, -1, 11028, 11019, 11014, -1, 11030, 11029, 11011, -1, 11030, 11010, 11025, -1, 11030, 11028, 11029, -1, 11030, 11024, 11019, -1, 11030, 11019, 11028, -1, 11030, 11011, 11010, -1, 11030, 11025, 11024, -1, 11031, 11032, 11033, -1, 11034, 11035, 11036, -1, 11037, 11035, 11034, -1, 11038, 11039, 11040, -1, 11038, 11040, 11041, -1, 11038, 11041, 11042, -1, 11043, 11044, 11039, -1, 11043, 11045, 11044, -1, 11043, 11039, 11038, -1, 11046, 11042, 11032, -1, 11046, 11031, 11047, -1, 11046, 11038, 11042, -1, 11046, 11032, 11031, -1, 11048, 11049, 11050, -1, 11048, 11050, 11051, -1, 11048, 11051, 11045, -1, 11048, 11045, 11043, -1, 11052, 11047, 11053, -1, 11052, 11046, 11047, -1, 11052, 11038, 11046, -1, 11052, 11043, 11038, -1, 11054, 11053, 11036, -1, 11054, 11035, 11049, -1, 11054, 11048, 11043, -1, 11054, 11052, 11053, -1, 11054, 11043, 11052, -1, 11054, 11036, 11035, -1, 11054, 11049, 11048, -1, 11055, 11056, 11057, -1, 11058, 11059, 11060, -1, 11061, 11059, 11058, -1, 11062, 11063, 11064, -1, 11062, 11064, 11065, -1, 11062, 11065, 11066, -1, 11067, 11068, 11069, -1, 11067, 11069, 11063, -1, 11067, 11063, 11062, -1, 11070, 11066, 11056, -1, 11070, 11055, 11071, -1, 11070, 11056, 11055, -1, 11070, 11062, 11066, -1, 11072, 11073, 11074, -1, 11072, 11074, 11075, -1, 11072, 11075, 11068, -1, 11072, 11068, 11067, -1, 11076, 11071, 11077, -1, 11076, 11070, 11071, -1, 11076, 11062, 11070, -1, 11076, 11067, 11062, -1, 11078, 11077, 11060, -1, 11078, 11059, 11073, -1, 11078, 11076, 11077, -1, 11078, 11072, 11067, -1, 11078, 11067, 11076, -1, 11078, 11060, 11059, -1, 11078, 11073, 11072, -1, 11079, 11080, 11081, -1, 11082, 11083, 11084, -1, 11085, 11082, 11084, -1, 11086, 11087, 11088, -1, 11086, 11088, 11089, -1, 11086, 11089, 11090, -1, 11091, 11092, 11087, -1, 11091, 11093, 11092, -1, 11091, 11087, 11086, -1, 11094, 11090, 11080, -1, 11094, 11079, 11095, -1, 11094, 11086, 11090, -1, 11094, 11080, 11079, -1, 11096, 11097, 11098, -1, 11096, 11098, 11099, -1, 11096, 11099, 11093, -1, 11096, 11093, 11091, -1, 11100, 11095, 11101, -1, 11100, 11094, 11095, -1, 11100, 11086, 11094, -1, 11100, 11091, 11086, -1, 11102, 11101, 11083, -1, 11102, 11082, 11097, -1, 11102, 11096, 11091, -1, 11102, 11100, 11101, -1, 11102, 11091, 11100, -1, 11102, 11083, 11082, -1, 11102, 11097, 11096, -1, 11103, 11104, 11105, -1, 11106, 11107, 11108, -1, 11109, 11110, 11111, -1, 11109, 11111, 11103, -1, 11109, 11105, 11112, -1, 11109, 11103, 11105, -1, 11113, 11114, 11108, -1, 11113, 11107, 11110, -1, 11113, 11112, 11114, -1, 11113, 11109, 11112, -1, 11113, 11110, 11109, -1, 11113, 11108, 11107, -1, 11115, 11116, 11117, -1, 11118, 11119, 11120, -1, 11121, 11119, 11118, -1, 11122, 11123, 11124, -1, 11122, 11124, 11125, -1, 11122, 11125, 11126, -1, 11127, 11128, 11123, -1, 11127, 11129, 11128, -1, 11127, 11123, 11122, -1, 11130, 11126, 11116, -1, 11130, 11115, 11131, -1, 11130, 11122, 11126, -1, 11130, 11116, 11115, -1, 11132, 11133, 11134, -1, 11132, 11134, 11135, -1, 11132, 11135, 11129, -1, 11132, 11129, 11127, -1, 11136, 11131, 11137, -1, 11136, 11130, 11131, -1, 11136, 11122, 11130, -1, 11136, 11127, 11122, -1, 11138, 11137, 11120, -1, 11138, 11119, 11133, -1, 11138, 11132, 11127, -1, 11138, 11136, 11137, -1, 11138, 11127, 11136, -1, 11138, 11120, 11119, -1, 11138, 11133, 11132, -1, 11139, 11140, 11141, -1, 11142, 11143, 11144, -1, 11145, 11143, 11142, -1, 11146, 11147, 11148, -1, 11146, 11148, 11149, -1, 11146, 11149, 11150, -1, 11151, 11152, 11147, -1, 11151, 11153, 11152, -1, 11151, 11147, 11146, -1, 11154, 11150, 11140, -1, 11154, 11139, 11155, -1, 11154, 11146, 11150, -1, 11154, 11140, 11139, -1, 11156, 11157, 11158, -1, 11156, 11158, 11159, -1, 11156, 11159, 11153, -1, 11156, 11153, 11151, -1, 11160, 11155, 11161, -1, 11160, 11154, 11155, -1, 11160, 11146, 11154, -1, 11160, 11151, 11146, -1, 11162, 11161, 11144, -1, 11162, 11143, 11157, -1, 11162, 11156, 11151, -1, 11162, 11160, 11161, -1, 11162, 11151, 11160, -1, 11162, 11144, 11143, -1, 11162, 11157, 11156, -1, 11163, 11164, 11165, -1, 11163, 11165, 11166, -1, 11167, 11163, 11166, -1, 11168, 11164, 11163, -1, 11169, 11167, 11166, -1, 11170, 11167, 11169, -1, 11171, 11168, 11163, -1, 11172, 11169, 11173, -1, 11172, 11170, 11169, -1, 11174, 11168, 11171, -1, 11175, 11176, 11177, -1, 11178, 11179, 11172, -1, 11178, 11172, 11173, -1, 11180, 11181, 11176, -1, 11182, 11181, 11180, -1, 11183, 11182, 11180, -1, 11184, 11179, 11178, -1, 11185, 11179, 11184, -1, 11186, 11183, 11187, -1, 11186, 11182, 11183, -1, 11188, 11185, 11184, -1, 11189, 11186, 11187, -1, 11190, 11191, 11185, -1, 11190, 11185, 11188, -1, 11192, 11191, 11190, -1, 11193, 11186, 11189, -1, 11175, 11180, 11176, -1, 11194, 11171, 11195, -1, 11194, 11195, 11175, -1, 11194, 11177, 11174, -1, 11194, 11175, 11177, -1, 11194, 11174, 11171, -1, 11196, 11189, 11191, -1, 11196, 11192, 11193, -1, 11196, 11193, 11189, -1, 11196, 11191, 11192, -1, 11197, 11198, 11199, -1, 11200, 11201, 11202, -1, 11203, 11204, 11205, -1, 11203, 11205, 11198, -1, 11203, 11197, 11206, -1, 11203, 11198, 11197, -1, 11207, 11208, 11204, -1, 11207, 11204, 11203, -1, 11209, 11206, 11210, -1, 11209, 11210, 11211, -1, 11209, 11203, 11206, -1, 11212, 11213, 11200, -1, 11212, 11202, 11208, -1, 11212, 11200, 11202, -1, 11212, 11208, 11207, -1, 11214, 11211, 11215, -1, 11214, 11215, 11216, -1, 11214, 11216, 11217, -1, 11214, 11209, 11211, -1, 11214, 11207, 11203, -1, 11214, 11203, 11209, -1, 11218, 11217, 11219, -1, 11218, 11219, 11220, -1, 11218, 11220, 11213, -1, 11218, 11214, 11217, -1, 11218, 11213, 11212, -1, 11218, 11212, 11207, -1, 11218, 11207, 11214, -1, 11221, 11222, 11223, -1, 11224, 11225, 11226, -1, 11227, 11228, 11229, -1, 11227, 11229, 11222, -1, 11227, 11221, 11230, -1, 11227, 11222, 11221, -1, 11231, 11232, 11228, -1, 11231, 11228, 11227, -1, 11233, 11230, 11234, -1, 11233, 11234, 11235, -1, 11233, 11227, 11230, -1, 11236, 11237, 11224, -1, 11236, 11226, 11232, -1, 11236, 11232, 11231, -1, 11236, 11224, 11226, -1, 11238, 11239, 11240, -1, 11238, 11235, 11241, -1, 11238, 11241, 11239, -1, 11238, 11233, 11235, -1, 11238, 11227, 11233, -1, 11238, 11231, 11227, -1, 11242, 11240, 11243, -1, 11242, 11243, 11244, -1, 11242, 11244, 11237, -1, 11242, 11231, 11238, -1, 11242, 11238, 11240, -1, 11242, 11237, 11236, -1, 11242, 11236, 11231, -1, 11245, 11246, 11247, -1, 11245, 11247, 11248, -1, 11249, 11245, 11248, -1, 11250, 11246, 11245, -1, 11251, 11249, 11248, -1, 11252, 11249, 11251, -1, 11253, 11250, 11245, -1, 11254, 11252, 11251, -1, 11255, 11254, 11251, -1, 11256, 11250, 11253, -1, 11257, 11258, 11259, -1, 11257, 11259, 11256, -1, 11260, 11261, 11254, -1, 11260, 11254, 11255, -1, 11262, 11263, 11258, -1, 11264, 11263, 11262, -1, 11265, 11264, 11262, -1, 11266, 11261, 11260, -1, 11267, 11261, 11266, -1, 11268, 11265, 11269, -1, 11268, 11264, 11265, -1, 11270, 11267, 11266, -1, 11271, 11268, 11269, -1, 11272, 11273, 11267, -1, 11272, 11267, 11270, -1, 11274, 11273, 11272, -1, 11275, 11268, 11271, -1, 11257, 11262, 11258, -1, 11276, 11253, 11277, -1, 11276, 11277, 11257, -1, 11276, 11256, 11253, -1, 11276, 11257, 11256, -1, 11278, 11271, 11273, -1, 11278, 11274, 11275, -1, 11278, 11275, 11271, -1, 11278, 11273, 11274, -1, 11279, 11280, 11281, -1, 11281, 11280, 11282, -1, 11283, 11280, 11279, -1, 11280, 11284, 11282, -1, 1603, 3287, 4895, -1, 11283, 11285, 11280, -1, 11286, 11287, 3287, -1, 11283, 11288, 11285, -1, 3287, 4928, 4895, -1, 11283, 11289, 11288, -1, 11289, 11290, 11288, -1, 11290, 11291, 11292, -1, 3287, 3328, 4928, -1, 11293, 3328, 11287, -1, 11287, 3328, 3287, -1, 11294, 11295, 11296, -1, 11293, 11297, 3328, -1, 3328, 3327, 4928, -1, 3327, 4962, 4928, -1, 11290, 11298, 11291, -1, 11299, 11300, 11301, -1, 11302, 11300, 11299, -1, 3327, 1706, 4962, -1, 11290, 11303, 11298, -1, 11304, 11303, 11289, -1, 11289, 11303, 11290, -1, 1706, 1708, 4962, -1, 11305, 11306, 11294, -1, 11307, 11306, 11305, -1, 11294, 11306, 11295, -1, 11303, 11308, 11298, -1, 11304, 11309, 11303, -1, 1708, 4990, 4962, -1, 11304, 11310, 11309, -1, 11301, 11311, 11312, -1, 11300, 11311, 11301, -1, 11313, 11310, 11304, -1, 11314, 11315, 11316, -1, 11317, 11318, 1708, -1, 11313, 11319, 11310, -1, 11319, 11320, 11321, -1, 11318, 3382, 1708, -1, 11322, 3382, 11318, -1, 1708, 3382, 4990, -1, 11322, 11323, 3382, -1, 11324, 11325, 11326, -1, 11327, 11325, 11324, -1, 4990, 3381, 5004, -1, 3382, 3381, 4990, -1, 11314, 11328, 11315, -1, 11319, 11329, 11320, -1, 11330, 11328, 11314, -1, 11331, 11328, 11330, -1, 3381, 3391, 5004, -1, 11313, 11332, 11319, -1, 11319, 11332, 11329, -1, 11333, 11332, 11313, -1, 3391, 3393, 5004, -1, 11332, 11334, 11329, -1, 11333, 11335, 11332, -1, 3393, 4275, 5004, -1, 11325, 11336, 11326, -1, 11326, 11336, 11337, -1, 11333, 11338, 11335, -1, 11339, 11338, 11333, -1, 11340, 11341, 11342, -1, 11343, 11344, 3393, -1, 11339, 11345, 11338, -1, 11346, 11347, 11348, -1, 11347, 11349, 11348, -1, 11345, 11350, 11351, -1, 3393, 191, 4275, -1, 11340, 11352, 11341, -1, 11344, 191, 3393, -1, 11353, 191, 11344, -1, 11354, 11352, 11340, -1, 11355, 11352, 11354, -1, 11353, 11356, 191, -1, 4275, 190, 4276, -1, 191, 190, 4275, -1, 11345, 11357, 11350, -1, 190, 205, 4276, -1, 11345, 11358, 11357, -1, 11339, 11358, 11345, -1, 11359, 11358, 11339, -1, 11349, 11360, 11361, -1, 11347, 11360, 11349, -1, 11362, 11363, 11364, -1, 4276, 1892, 4313, -1, 205, 1892, 4276, -1, 11358, 11365, 11357, -1, 11359, 11366, 11358, -1, 11367, 11368, 11359, -1, 11359, 11368, 11366, -1, 11369, 11370, 1892, -1, 11371, 11372, 11373, -1, 11367, 11374, 11368, -1, 11372, 11375, 11373, -1, 11362, 11376, 11363, -1, 11377, 11376, 11362, -1, 11378, 11376, 11377, -1, 1892, 367, 4313, -1, 11379, 367, 11370, -1, 11370, 367, 1892, -1, 11374, 11380, 11381, -1, 11379, 11382, 367, -1, 367, 366, 4313, -1, 4313, 366, 4345, -1, 11374, 11383, 11380, -1, 11375, 11384, 11385, -1, 11372, 11384, 11375, -1, 366, 403, 4345, -1, 11367, 11386, 11374, -1, 11387, 11388, 11389, -1, 11374, 11386, 11383, -1, 11390, 11386, 11367, -1, 4345, 1960, 4389, -1, 403, 1960, 4345, -1, 11386, 11391, 11383, -1, 11392, 11393, 11394, -1, 11295, 11393, 11392, -1, 11390, 11395, 11386, -1, 11390, 11396, 11395, -1, 11397, 11396, 11390, -1, 11306, 11398, 11295, -1, 11399, 11398, 11306, -1, 11400, 11401, 1960, -1, 11397, 11402, 11396, -1, 11295, 11398, 11393, -1, 11394, 11403, 11300, -1, 1960, 821, 4389, -1, 11393, 11403, 11394, -1, 11401, 821, 1960, -1, 11404, 821, 11401, -1, 11402, 11405, 11406, -1, 11300, 11403, 11311, -1, 11399, 11407, 11398, -1, 11408, 11407, 11399, -1, 11315, 11407, 11408, -1, 11404, 11409, 821, -1, 4389, 820, 4390, -1, 821, 820, 4389, -1, 11402, 11410, 11405, -1, 11411, 11412, 11413, -1, 11311, 11412, 11411, -1, 820, 901, 4390, -1, 11397, 11414, 11402, -1, 11402, 11414, 11410, -1, 11403, 11412, 11311, -1, 11415, 11414, 11397, -1, 4390, 985, 4405, -1, 901, 985, 4390, -1, 11414, 11416, 11410, -1, 11328, 11417, 11315, -1, 11418, 11417, 11328, -1, 11415, 11419, 11414, -1, 11315, 11417, 11407, -1, 11412, 11420, 11413, -1, 11413, 11420, 11325, -1, 11421, 11422, 11415, -1, 11325, 11420, 11336, -1, 11415, 11422, 11419, -1, 11423, 11424, 985, -1, 11421, 11425, 11422, -1, 11426, 11427, 11428, -1, 11418, 11429, 11417, -1, 11430, 11429, 11418, -1, 11341, 11429, 11430, -1, 985, 1394, 4405, -1, 11424, 1394, 985, -1, 11431, 11432, 11433, -1, 11336, 11432, 11431, -1, 11434, 1394, 11424, -1, 11425, 11435, 11436, -1, 11420, 11432, 11336, -1, 11434, 11437, 1394, -1, 4405, 1393, 4413, -1, 1394, 1393, 4405, -1, 11427, 11438, 11428, -1, 1393, 1480, 4413, -1, 11439, 11440, 11387, -1, 11441, 11440, 11439, -1, 11387, 11440, 11388, -1, 11341, 11442, 11429, -1, 11425, 11443, 11435, -1, 11352, 11442, 11341, -1, 11444, 11442, 11352, -1, 11433, 11445, 11347, -1, 11425, 11446, 11443, -1, 11432, 11445, 11433, -1, 4530, 11446, 11421, -1, 11347, 11445, 11360, -1, 11421, 11446, 11425, -1, 4530, 11447, 11446, -1, 4530, 11448, 11447, -1, 4530, 3401, 11448, -1, 1480, 2115, 4413, -1, 4413, 2115, 4441, -1, 11446, 11449, 11443, -1, 11427, 11450, 11438, -1, 11438, 11450, 11451, -1, 11452, 11453, 11444, -1, 11363, 11453, 11452, -1, 4530, 3399, 3401, -1, 11444, 11453, 11442, -1, 4530, 3394, 3399, -1, 4386, 3394, 4530, -1, 11445, 11454, 11360, -1, 11455, 11454, 11456, -1, 11360, 11454, 11455, -1, 11457, 11458, 2115, -1, 11459, 11460, 11461, -1, 4386, 3395, 3394, -1, 2115, 1942, 4441, -1, 11363, 11462, 11453, -1, 11463, 1942, 11458, -1, 11458, 1942, 2115, -1, 11464, 11462, 11376, -1, 11376, 11462, 11363, -1, 3395, 11465, 11466, -1, 11456, 11467, 11372, -1, 4441, 1941, 4493, -1, 11454, 11467, 11456, -1, 11372, 11467, 11384, -1, 1942, 1941, 4441, -1, 11463, 11468, 1942, -1, 11469, 11470, 11471, -1, 1941, 2174, 4493, -1, 3395, 11472, 11465, -1, 11464, 11473, 11462, -1, 4386, 446, 3395, -1, 3395, 446, 11472, -1, 11474, 11473, 11464, -1, 11388, 11473, 11474, -1, 4354, 446, 4386, -1, 4493, 2173, 4495, -1, 2174, 2173, 4493, -1, 11475, 11476, 11477, -1, 11384, 11476, 11475, -1, 11467, 11476, 11384, -1, 11469, 11478, 11470, -1, 4354, 438, 446, -1, 11460, 11479, 11461, -1, 446, 11480, 11472, -1, 11481, 11479, 11460, -1, 11482, 11479, 11481, -1, 4327, 433, 4354, -1, 4354, 433, 438, -1, 4327, 434, 433, -1, 11483, 11484, 2173, -1, 11388, 11485, 11473, -1, 11486, 11485, 11440, -1, 11440, 11485, 11388, -1, 11427, 11487, 11450, -1, 11477, 11487, 11427, -1, 11476, 11487, 11477, -1, 11469, 11488, 11478, -1, 11478, 11488, 11489, -1, 11490, 2339, 11484, -1, 11491, 11492, 11493, -1, 2173, 2339, 4495, -1, 11484, 2339, 2173, -1, 434, 11494, 11495, -1, 4495, 2338, 4575, -1, 11496, 11497, 11486, -1, 2339, 2338, 4495, -1, 11461, 11497, 11496, -1, 11486, 11497, 11485, -1, 11490, 11498, 2339, -1, 2338, 2429, 4575, -1, 11499, 11500, 11501, -1, 11450, 11500, 11499, -1, 11487, 11500, 11450, -1, 434, 11502, 11494, -1, 4319, 3093, 4327, -1, 11503, 11504, 11505, -1, 4327, 3093, 434, -1, 434, 3093, 11502, -1, 11506, 3410, 11492, -1, 11507, 3410, 11506, -1, 11492, 3410, 11493, -1, 11503, 11508, 11504, -1, 4575, 2496, 4600, -1, 2429, 2496, 4575, -1, 11461, 11509, 11497, -1, 11479, 11509, 11461, -1, 11510, 11509, 11479, -1, 4319, 381, 3093, -1, 3093, 11511, 11502, -1, 11501, 11512, 11469, -1, 11500, 11512, 11501, -1, 11469, 11512, 11488, -1, 4319, 348, 381, -1, 4300, 348, 4319, -1, 11503, 11513, 11508, -1, 11508, 11513, 11514, -1, 4300, 349, 348, -1, 11515, 11516, 2496, -1, 11510, 11517, 11509, -1, 11518, 11517, 11510, -1, 11493, 11517, 11518, -1, 11512, 11519, 11488, -1, 11520, 11519, 11521, -1, 11488, 11519, 11520, -1, 2496, 2924, 4600, -1, 11516, 2924, 2496, -1, 11522, 11523, 1106, -1, 11516, 11524, 2924, -1, 2924, 2923, 4600, -1, 4600, 2923, 4611, -1, 11493, 11525, 11517, -1, 349, 11526, 11527, -1, 3409, 11525, 3410, -1, 3410, 11525, 11493, -1, 11503, 11528, 11513, -1, 11524, 11529, 2924, -1, 11521, 11528, 11503, -1, 11519, 11528, 11521, -1, 2923, 2374, 4611, -1, 11530, 11531, 11532, -1, 11523, 1572, 1106, -1, 11533, 1572, 11523, -1, 11534, 1572, 11533, -1, 11530, 11535, 11531, -1, 3409, 4520, 11525, -1, 3413, 4520, 3409, -1, 1082, 4520, 3413, -1, 1094, 4520, 1082, -1, 1099, 4520, 1094, -1, 4299, 3070, 4300, -1, 1106, 4520, 1099, -1, 4300, 3070, 349, -1, 11536, 11537, 11538, -1, 2374, 2376, 4611, -1, 11513, 11537, 11536, -1, 11528, 11537, 11513, -1, 4611, 2376, 4651, -1, 3070, 11539, 349, -1, 349, 11539, 11526, -1, 11535, 11540, 11541, -1, 11530, 11540, 11535, -1, 4299, 286, 3070, -1, 4299, 278, 286, -1, 4514, 278, 4299, -1, 11542, 11543, 765, -1, 3070, 11544, 11539, -1, 1106, 4521, 4520, -1, 1572, 4521, 1106, -1, 763, 4521, 1572, -1, 4514, 279, 278, -1, 11538, 11545, 11530, -1, 11546, 11547, 2376, -1, 11537, 11545, 11538, -1, 11530, 11545, 11540, -1, 11548, 11549, 11550, -1, 2376, 3131, 4651, -1, 11547, 3131, 2376, -1, 11551, 2022, 11543, -1, 11552, 2022, 11551, -1, 11543, 2022, 765, -1, 11548, 11553, 11549, -1, 11547, 11554, 3131, -1, 765, 4540, 766, -1, 4651, 3130, 4454, -1, 763, 4540, 4521, -1, 766, 4540, 763, -1, 3131, 3130, 4651, -1, 11555, 11556, 11557, -1, 11540, 11556, 11555, -1, 11545, 11556, 11540, -1, 279, 11558, 11559, -1, 3130, 3137, 4454, -1, 11548, 11560, 11553, -1, 11553, 11560, 11561, -1, 11554, 11562, 3131, -1, 4971, 181, 4514, -1, 4514, 181, 279, -1, 2021, 4548, 2022, -1, 2022, 4548, 765, -1, 4454, 3143, 4733, -1, 765, 4548, 4540, -1, 3137, 3143, 4454, -1, 11557, 11563, 11548, -1, 4971, 158, 181, -1, 11548, 11563, 11560, -1, 11556, 11563, 11557, -1, 11564, 11565, 2120, -1, 279, 11566, 11558, -1, 181, 11566, 279, -1, 4939, 130, 4971, -1, 4971, 130, 158, -1, 181, 11567, 11566, -1, 11568, 11569, 11570, -1, 4939, 131, 130, -1, 2070, 4583, 2021, -1, 2120, 4583, 2070, -1, 2021, 4583, 4548, -1, 11563, 11571, 11560, -1, 11572, 11571, 11573, -1, 11560, 11571, 11572, -1, 11574, 11575, 3143, -1, 11576, 2487, 11565, -1, 11577, 2487, 11576, -1, 11565, 2487, 2120, -1, 11568, 11578, 11569, -1, 11575, 3181, 3143, -1, 3143, 3181, 4733, -1, 3181, 3180, 4733, -1, 4733, 3180, 4747, -1, 11578, 11579, 11580, -1, 11568, 11579, 11578, -1, 2486, 4434, 2487, -1, 2120, 4434, 4583, -1, 2487, 4434, 2120, -1, 11575, 11581, 3181, -1, 3180, 2598, 4747, -1, 11573, 11582, 11568, -1, 11571, 11582, 11573, -1, 11568, 11582, 11579, -1, 4910, 2977, 4939, -1, 4939, 2977, 131, -1, 4747, 2597, 4759, -1, 11583, 11584, 1016, -1, 2598, 2597, 4747, -1, 131, 11585, 11586, -1, 4910, 2975, 2977, -1, 11581, 11587, 3181, -1, 1014, 4472, 2486, -1, 4910, 3387, 2975, -1, 1016, 4472, 1014, -1, 2486, 4472, 4434, -1, 4905, 3387, 4910, -1, 2977, 11588, 131, -1, 11589, 11590, 11591, -1, 131, 11588, 11585, -1, 11579, 11590, 11589, -1, 11582, 11590, 11579, -1, 4905, 3388, 3387, -1, 11592, 11593, 11594, -1, 11595, 2993, 11584, -1, 11596, 2993, 11595, -1, 2977, 11597, 11588, -1, 11584, 2993, 1016, -1, 11592, 11598, 11593, -1, 2597, 3224, 4759, -1, 2992, 4710, 2993, -1, 1016, 4710, 4472, -1, 2993, 4710, 1016, -1, 3224, 3223, 4759, -1, 11591, 11599, 11592, -1, 4759, 3223, 4766, -1, 11590, 11599, 11591, -1, 3223, 2693, 4766, -1, 11600, 11601, 2597, -1, 2597, 11601, 3224, -1, 11592, 11602, 11598, -1, 11599, 11602, 11592, -1, 11598, 11602, 11603, -1, 4884, 3340, 4905, -1, 4905, 3340, 3388, -1, 2693, 2692, 4766, -1, 4766, 2692, 4791, -1, 11604, 11605, 3084, -1, 4884, 2899, 3340, -1, 4860, 3323, 4884, -1, 3042, 4728, 2992, -1, 4884, 3323, 2899, -1, 3084, 4728, 3042, -1, 2992, 4728, 4710, -1, 11599, 11606, 11602, -1, 11607, 11606, 11608, -1, 11602, 11606, 11607, -1, 4860, 3324, 3323, -1, 11601, 11609, 3224, -1, 2692, 3275, 4791, -1, 4791, 2772, 4823, -1, 3275, 2772, 4791, -1, 11610, 11611, 11612, -1, 2772, 2777, 4823, -1, 4823, 2776, 4860, -1, 4860, 2776, 3324, -1, 2777, 2776, 4823, -1, 11605, 3139, 3084, -1, 11613, 3139, 11605, -1, 11614, 3139, 11613, -1, 11610, 11615, 11611, -1, 3388, 11616, 11617, -1, 11609, 11618, 3224, -1, 3084, 4735, 4728, -1, 3139, 4735, 3084, -1, 3138, 4735, 3139, -1, 3340, 11619, 3388, -1, 3388, 11619, 11616, -1, 11606, 11620, 11608, -1, 3340, 11621, 11619, -1, 11608, 11620, 11610, -1, 11620, 11622, 11610, -1, 2692, 11623, 3275, -1, 11610, 11622, 11615, -1, 11624, 11623, 2692, -1, 11615, 11622, 11625, -1, 11626, 11627, 1259, -1, 11623, 11628, 3275, -1, 1260, 4751, 3138, -1, 1259, 4751, 1260, -1, 3324, 11629, 11630, -1, 3138, 4751, 4735, -1, 11620, 11631, 11622, -1, 11628, 11632, 3275, -1, 11622, 11631, 11633, -1, 11631, 11634, 11633, -1, 2776, 11635, 3324, -1, 3324, 11635, 11629, -1, 2776, 11636, 11635, -1, 11637, 11638, 11639, -1, 11640, 3184, 11627, -1, 11641, 3184, 11640, -1, 11627, 3184, 1259, -1, 1259, 4779, 4751, -1, 3184, 4779, 1259, -1, 11631, 11642, 11634, -1, 11634, 11642, 11637, -1, 3184, 3183, 4779, -1, 11637, 11643, 11638, -1, 11642, 11644, 11637, -1, 11637, 11644, 11643, -1, 11643, 11644, 11645, -1, 1361, 4815, 3183, -1, 1360, 4815, 1361, -1, 3183, 4815, 4779, -1, 11642, 11646, 11644, -1, 11646, 11647, 11644, -1, 11648, 11649, 1360, -1, 11646, 11650, 11647, -1, 1360, 4842, 4815, -1, 11650, 11651, 11652, -1, 11646, 11651, 11650, -1, 11652, 11653, 11654, -1, 11655, 3227, 11649, -1, 11656, 3227, 11655, -1, 1360, 3227, 4842, -1, 11649, 3227, 1360, -1, 3227, 1456, 4842, -1, 11652, 11657, 11653, -1, 11651, 11658, 11652, -1, 11652, 11658, 11657, -1, 11658, 11659, 11657, -1, 1456, 4862, 4842, -1, 1455, 4862, 1456, -1, 11651, 11660, 11658, -1, 1455, 1457, 4862, -1, 11660, 11661, 11658, -1, 11662, 11663, 1457, -1, 11660, 11664, 11661, -1, 1457, 4868, 4862, -1, 11660, 11279, 11664, -1, 11664, 11279, 11281, -1, 11281, 11665, 11666, -1, 1457, 3273, 4868, -1, 11663, 3273, 1457, -1, 11667, 3273, 11663, -1, 11667, 11668, 3273, -1, 3273, 3272, 4868, -1, 11281, 11282, 11665, -1, 3272, 4895, 4868, -1, 1603, 4895, 3272, -1, 11669, 11670, 1843, -1, 11671, 11672, 11673, -1, 11674, 11672, 11671, -1, 4133, 2111, 4101, -1, 11670, 2111, 1843, -1, 1843, 2111, 4133, -1, 11670, 11675, 2111, -1, 11672, 11676, 11673, -1, 2111, 2110, 4101, -1, 11676, 11677, 11678, -1, 2110, 1305, 4101, -1, 11672, 11679, 11676, -1, 11680, 11681, 11682, -1, 1305, 4089, 4101, -1, 1305, 1304, 4089, -1, 11683, 11684, 1304, -1, 11685, 11686, 11687, -1, 11688, 11686, 11685, -1, 11677, 11689, 11690, -1, 11676, 11689, 11677, -1, 11679, 11689, 11676, -1, 11689, 11691, 11690, -1, 11692, 11693, 11694, -1, 11682, 11693, 11692, -1, 11679, 11695, 11689, -1, 11681, 11693, 11682, -1, 11679, 11696, 11695, -1, 11684, 11697, 1304, -1, 11698, 11699, 11688, -1, 11696, 11700, 11695, -1, 11688, 11699, 11686, -1, 11697, 972, 1304, -1, 4089, 972, 4061, -1, 1304, 972, 4089, -1, 11701, 11702, 11703, -1, 11696, 11704, 11700, -1, 11697, 11705, 972, -1, 972, 671, 4061, -1, 11696, 11706, 11704, -1, 11707, 11708, 11709, -1, 11710, 11708, 11707, -1, 4061, 667, 4038, -1, 11702, 11711, 11703, -1, 671, 667, 4061, -1, 11704, 11712, 11713, -1, 11714, 11711, 11715, -1, 11703, 11711, 11714, -1, 667, 666, 4038, -1, 11716, 11717, 666, -1, 11712, 11718, 11719, -1, 11704, 11718, 11712, -1, 11706, 11718, 11704, -1, 11718, 11720, 11719, -1, 11710, 11721, 11708, -1, 11722, 11721, 11710, -1, 11723, 11724, 11706, -1, 11725, 11726, 11727, -1, 11706, 11724, 11718, -1, 11717, 11728, 666, -1, 11723, 11729, 11724, -1, 666, 1954, 4038, -1, 11728, 1954, 666, -1, 4038, 1954, 3725, -1, 11723, 11730, 11729, -1, 11728, 11731, 1954, -1, 11732, 11733, 11734, -1, 11732, 11735, 11733, -1, 1954, 1953, 3725, -1, 11726, 11736, 11727, -1, 11723, 11737, 11730, -1, 11738, 11736, 11739, -1, 11727, 11736, 11738, -1, 3725, 326, 4003, -1, 1953, 326, 3725, -1, 11730, 11740, 11741, -1, 326, 325, 4003, -1, 11742, 11743, 11735, -1, 11735, 11743, 11733, -1, 11744, 11745, 11746, -1, 11747, 11748, 325, -1, 11740, 11749, 11750, -1, 11737, 11749, 11730, -1, 11730, 11749, 11740, -1, 11749, 11751, 11750, -1, 11752, 11753, 11754, -1, 11755, 11756, 11737, -1, 11737, 11756, 11749, -1, 11752, 11757, 11753, -1, 11748, 11758, 325, -1, 11745, 11759, 11746, -1, 11755, 11760, 11756, -1, 4003, 1887, 3976, -1, 11761, 11759, 11762, -1, 325, 1887, 4003, -1, 11746, 11759, 11761, -1, 11758, 1887, 325, -1, 11763, 11764, 11755, -1, 11755, 11764, 11760, -1, 11765, 11766, 11757, -1, 11758, 11767, 1887, -1, 11757, 11766, 11753, -1, 11768, 11769, 11770, -1, 1887, 129, 3976, -1, 3976, 126, 3962, -1, 129, 126, 3976, -1, 11771, 11772, 11681, -1, 11773, 11772, 11771, -1, 11764, 11774, 11775, -1, 126, 125, 3962, -1, 11693, 11776, 11777, -1, 11774, 11778, 11779, -1, 11763, 11778, 11764, -1, 11764, 11778, 11774, -1, 11780, 11781, 125, -1, 11681, 11776, 11693, -1, 11772, 11776, 11681, -1, 11778, 11782, 11779, -1, 11763, 11783, 11778, -1, 11686, 11784, 11773, -1, 11699, 11784, 11686, -1, 11785, 11783, 11763, -1, 11781, 11786, 125, -1, 11773, 11784, 11772, -1, 11777, 11787, 11788, -1, 11785, 11789, 11783, -1, 125, 3376, 3962, -1, 11786, 3376, 125, -1, 3962, 3376, 3925, -1, 11785, 11790, 11789, -1, 11791, 11790, 11785, -1, 11776, 11787, 11777, -1, 11786, 11792, 3376, -1, 11788, 11787, 11702, -1, 11793, 11794, 11699, -1, 11795, 11794, 11793, -1, 11699, 11794, 11784, -1, 3376, 3371, 3925, -1, 3925, 3370, 3782, -1, 3371, 3370, 3925, -1, 11702, 11796, 11711, -1, 11787, 11796, 11702, -1, 11790, 11797, 11798, -1, 3370, 3372, 3782, -1, 11711, 11796, 11799, -1, 11708, 11800, 11795, -1, 11797, 11801, 11802, -1, 11795, 11800, 11794, -1, 11721, 11800, 11708, -1, 11791, 11801, 11790, -1, 11790, 11801, 11797, -1, 11803, 11804, 3372, -1, 11805, 11806, 11807, -1, 11796, 11808, 11799, -1, 11801, 11809, 11802, -1, 11810, 11808, 11726, -1, 11799, 11808, 11810, -1, 11721, 11811, 11800, -1, 11812, 11813, 11791, -1, 11791, 11813, 11801, -1, 11814, 11811, 11721, -1, 11815, 11811, 11814, -1, 11804, 11816, 3372, -1, 11812, 11817, 11813, -1, 11805, 11818, 11806, -1, 3782, 1703, 3776, -1, 3372, 1703, 3782, -1, 11816, 1703, 3372, -1, 11769, 11819, 11770, -1, 11820, 11821, 11812, -1, 11822, 11819, 11823, -1, 11770, 11819, 11822, -1, 11812, 11821, 11817, -1, 11726, 11824, 11736, -1, 11816, 11825, 1703, -1, 11736, 11824, 11826, -1, 1703, 1702, 3776, -1, 11808, 11824, 11726, -1, 11733, 11827, 11815, -1, 11743, 11827, 11733, -1, 11815, 11827, 11811, -1, 3776, 1700, 3824, -1, 1702, 1700, 3776, -1, 11821, 11828, 11829, -1, 1700, 3315, 3824, -1, 11818, 11830, 11806, -1, 11831, 11830, 11818, -1, 11824, 11832, 11826, -1, 11833, 11832, 11745, -1, 11826, 11832, 11833, -1, 11820, 3406, 11821, -1, 11821, 3406, 11828, -1, 11743, 11834, 11827, -1, 11835, 11834, 11743, -1, 11828, 3406, 11836, -1, 11837, 11834, 11835, -1, 11838, 11839, 3315, -1, 3406, 11840, 11836, -1, 3837, 3404, 11820, -1, 11820, 3404, 3406, -1, 11841, 11842, 11843, -1, 3837, 3405, 3404, -1, 11839, 11844, 3315, -1, 11844, 1598, 3315, -1, 11832, 11845, 11745, -1, 3824, 1598, 3771, -1, 3315, 1598, 3824, -1, 11745, 11845, 11759, -1, 3837, 17, 3405, -1, 11759, 11845, 11846, -1, 3837, 16, 17, -1, 11753, 11847, 11837, -1, 11837, 11847, 11834, -1, 3837, 14, 16, -1, 3838, 15, 3837, -1, 3837, 15, 14, -1, 11766, 11847, 11753, -1, 11844, 11848, 1598, -1, 11849, 11850, 11851, -1, 1598, 1597, 3771, -1, 11845, 11852, 11846, -1, 3771, 3267, 3749, -1, 1597, 3267, 3771, -1, 11853, 11852, 11769, -1, 11846, 11852, 11853, -1, 11854, 11855, 11766, -1, 11856, 11855, 11854, -1, 11766, 11855, 11847, -1, 15, 11857, 11858, -1, 3267, 3268, 3749, -1, 11850, 11859, 11851, -1, 11841, 11860, 11842, -1, 11861, 11860, 11862, -1, 11842, 11860, 11861, -1, 3838, 36, 15, -1, 15, 36, 11857, -1, 11857, 36, 11863, -1, 11769, 11864, 11819, -1, 11852, 11864, 11769, -1, 11865, 11866, 3268, -1, 3880, 37, 3838, -1, 11819, 11864, 11867, -1, 11830, 11868, 11806, -1, 3838, 37, 36, -1, 11806, 11868, 11856, -1, 36, 11869, 11863, -1, 11856, 11868, 11855, -1, 11870, 11871, 11859, -1, 3880, 451, 37, -1, 11859, 11871, 11851, -1, 11866, 11872, 3268, -1, 11873, 11874, 11875, -1, 3268, 3238, 3749, -1, 3749, 3238, 3703, -1, 11872, 3238, 3268, -1, 3900, 452, 3880, -1, 3880, 452, 451, -1, 11864, 11876, 11867, -1, 3238, 1450, 3703, -1, 11877, 11876, 11841, -1, 11867, 11876, 11877, -1, 11872, 11878, 3238, -1, 11879, 11880, 11830, -1, 11881, 11880, 11879, -1, 11830, 11880, 11868, -1, 3703, 1453, 3704, -1, 1450, 1453, 3703, -1, 11882, 11883, 11884, -1, 1453, 3216, 3704, -1, 11885, 11886, 11887, -1, 452, 11888, 11889, -1, 11874, 11886, 11885, -1, 11873, 11886, 11874, -1, 11883, 11890, 11884, -1, 11841, 11891, 11860, -1, 11860, 11891, 11892, -1, 11876, 11891, 11841, -1, 11881, 11893, 11880, -1, 11851, 11893, 11881, -1, 11871, 11893, 11851, -1, 3900, 97, 452, -1, 452, 97, 11888, -1, 11888, 97, 11894, -1, 11895, 11896, 3216, -1, 11890, 11897, 11884, -1, 3938, 95, 3900, -1, 11898, 11897, 11890, -1, 3900, 95, 97, -1, 97, 11899, 11894, -1, 3938, 96, 95, -1, 11891, 11900, 11892, -1, 11896, 11901, 3216, -1, 11902, 11900, 11873, -1, 11892, 11900, 11902, -1, 3704, 1356, 3660, -1, 11871, 11903, 11893, -1, 3216, 1356, 3704, -1, 11901, 1356, 3216, -1, 11904, 11903, 11871, -1, 11905, 11903, 11904, -1, 11906, 11907, 11908, -1, 3708, 100, 3938, -1, 3938, 100, 96, -1, 1356, 1355, 3660, -1, 11901, 11909, 1356, -1, 11873, 11910, 11886, -1, 1355, 1354, 3660, -1, 11886, 11910, 11911, -1, 11900, 11910, 11873, -1, 3660, 1354, 3639, -1, 11905, 11912, 11903, -1, 11897, 11912, 11884, -1, 11884, 11912, 11905, -1, 11913, 11914, 3, -1, 1354, 3176, 3639, -1, 11906, 11915, 11907, -1, 11916, 11915, 11917, -1, 11907, 11915, 11916, -1, 100, 11918, 11919, -1, 11914, 11920, 3, -1, 11921, 11922, 11906, -1, 11911, 11922, 11921, -1, 11910, 11922, 11911, -1, 11897, 3815, 11912, -1, 11923, 3815, 11897, -1, 11924, 3815, 11923, -1, 100, 172, 11918, -1, 9, 3815, 11924, -1, 3708, 172, 100, -1, 2, 3815, 9, -1, 172, 11925, 11918, -1, 1, 3815, 2, -1, 3708, 173, 172, -1, 3748, 173, 3708, -1, 11920, 3291, 3, -1, 11926, 3291, 11920, -1, 11927, 11928, 11929, -1, 11930, 11931, 3176, -1, 11922, 11932, 11906, -1, 172, 11933, 11925, -1, 11906, 11932, 11915, -1, 11915, 11932, 11934, -1, 3748, 174, 173, -1, 3, 3698, 1, -1, 3291, 3698, 3, -1, 1, 3698, 3815, -1, 11935, 11936, 3263, -1, 11937, 11938, 11939, -1, 3639, 1255, 3612, -1, 11928, 11938, 11937, -1, 11927, 11938, 11928, -1, 3176, 1255, 3639, -1, 4012, 479, 3748, -1, 11936, 11940, 3263, -1, 3748, 479, 174, -1, 11932, 11941, 11934, -1, 11942, 11941, 11927, -1, 11934, 11941, 11942, -1, 3176, 11943, 1255, -1, 11931, 11943, 3176, -1, 1255, 1254, 3612, -1, 2770, 3689, 3291, -1, 2768, 3689, 2770, -1, 3291, 3689, 3698, -1, 3612, 3126, 3598, -1, 1254, 3126, 3612, -1, 11943, 11944, 1255, -1, 11940, 2685, 3263, -1, 11945, 2685, 11940, -1, 3126, 3125, 3598, -1, 11927, 11946, 11938, -1, 11941, 11946, 11927, -1, 11938, 11946, 11947, -1, 479, 11948, 11949, -1, 2768, 3663, 3689, -1, 4012, 283, 479, -1, 479, 283, 11948, -1, 3263, 3663, 2768, -1, 2685, 3663, 3263, -1, 11950, 11951, 11952, -1, 283, 11953, 11948, -1, 4012, 284, 283, -1, 4034, 284, 4012, -1, 11954, 11955, 3125, -1, 11956, 11957, 3217, -1, 11958, 11959, 11950, -1, 11947, 11959, 11958, -1, 11946, 11959, 11947, -1, 2685, 3652, 3663, -1, 2684, 3652, 2685, -1, 2686, 3652, 2684, -1, 4034, 527, 284, -1, 11950, 11960, 11951, -1, 11961, 11960, 11962, -1, 11951, 11960, 11961, -1, 283, 11963, 11953, -1, 11957, 11964, 3217, -1, 3598, 1104, 3572, -1, 3125, 1104, 3598, -1, 4044, 528, 4034, -1, 4034, 528, 527, -1, 11964, 2593, 3217, -1, 1104, 1103, 3572, -1, 11965, 2593, 11964, -1, 11960, 11966, 11967, -1, 11959, 11966, 11950, -1, 3125, 11968, 1104, -1, 11950, 11966, 11960, -1, 11955, 11968, 3125, -1, 2686, 3622, 3652, -1, 2593, 3622, 3217, -1, 3572, 1105, 3545, -1, 3217, 3622, 2686, -1, 1103, 1105, 3572, -1, 11968, 11969, 1104, -1, 11970, 11971, 11972, -1, 1105, 1102, 3545, -1, 11973, 11974, 11970, -1, 528, 11975, 11976, -1, 11967, 11974, 11973, -1, 11966, 11974, 11967, -1, 4044, 414, 528, -1, 528, 414, 11975, -1, 2593, 3623, 3622, -1, 4078, 415, 4044, -1, 2592, 3623, 2593, -1, 3170, 3623, 2592, -1, 4044, 415, 414, -1, 11977, 11978, 3169, -1, 11979, 11980, 11981, -1, 11971, 11980, 11979, -1, 414, 11982, 11975, -1, 11970, 11980, 11971, -1, 11978, 11983, 3169, -1, 4078, 417, 415, -1, 11980, 11984, 11985, -1, 11974, 11984, 11970, -1, 3545, 1010, 3546, -1, 1102, 1010, 3545, -1, 11970, 11984, 11980, -1, 3170, 3580, 3623, -1, 3169, 3580, 3170, -1, 4108, 573, 4078, -1, 4078, 573, 417, -1, 11986, 11987, 1102, -1, 1010, 1009, 3546, -1, 11983, 2456, 3169, -1, 11988, 2456, 11983, -1, 414, 11989, 11982, -1, 3169, 2456, 3580, -1, 1009, 1007, 3546, -1, 3546, 1007, 4253, -1, 11990, 11991, 11992, -1, 1102, 11993, 1010, -1, 11987, 11993, 1102, -1, 11994, 11995, 11990, -1, 11985, 11995, 11994, -1, 1007, 2347, 4253, -1, 11984, 11995, 11985, -1, 11993, 11996, 1010, -1, 2456, 3558, 3580, -1, 4108, 864, 573, -1, 2455, 3558, 2456, -1, 2457, 3558, 2455, -1, 4130, 675, 4108, -1, 11997, 11998, 2454, -1, 4108, 675, 864, -1, 11990, 11999, 11991, -1, 12000, 11999, 12001, -1, 4130, 673, 675, -1, 11991, 11999, 12000, -1, 573, 12002, 12003, -1, 11998, 12004, 2454, -1, 864, 12002, 573, -1, 4253, 942, 4227, -1, 2347, 942, 4253, -1, 11995, 12005, 11990, -1, 11990, 12005, 11999, -1, 11999, 12005, 12006, -1, 4157, 674, 4130, -1, 4130, 674, 673, -1, 2457, 3532, 3558, -1, 2454, 3532, 2457, -1, 942, 940, 4227, -1, 4227, 1961, 4193, -1, 940, 1961, 4227, -1, 12007, 2371, 12004, -1, 2454, 2371, 3532, -1, 12004, 2371, 2454, -1, 1961, 1962, 4193, -1, 864, 12008, 12002, -1, 12009, 12010, 12011, -1, 4157, 1418, 674, -1, 12012, 12013, 12009, -1, 12006, 12013, 12012, -1, 4182, 757, 4157, -1, 12005, 12013, 12006, -1, 4157, 757, 1418, -1, 4182, 755, 757, -1, 2370, 4248, 2371, -1, 2371, 4248, 3532, -1, 4193, 756, 4182, -1, 4182, 756, 755, -1, 1962, 756, 4193, -1, 2370, 2368, 4248, -1, 12014, 12015, 2347, -1, 864, 12016, 12008, -1, 12017, 12018, 2795, -1, 2347, 12019, 942, -1, 12015, 12019, 2347, -1, 12009, 12020, 12010, -1, 12021, 12020, 12022, -1, 12010, 12020, 12021, -1, 12019, 12023, 942, -1, 12013, 12024, 12009, -1, 12009, 12024, 12020, -1, 2795, 4237, 2368, -1, 2368, 4237, 4248, -1, 674, 12025, 12026, -1, 1418, 12025, 674, -1, 12024, 12027, 12020, -1, 12018, 12028, 2795, -1, 1418, 12029, 12025, -1, 12030, 2301, 12028, -1, 12031, 12032, 1962, -1, 12028, 2301, 2795, -1, 2795, 2301, 4237, -1, 1418, 12033, 12029, -1, 12032, 12034, 1962, -1, 1962, 12034, 756, -1, 12035, 12036, 12037, -1, 12027, 12036, 12035, -1, 12034, 12038, 756, -1, 12024, 12036, 12027, -1, 2301, 4211, 4237, -1, 2301, 2269, 4211, -1, 12037, 12039, 12040, -1, 2269, 2268, 4211, -1, 12036, 12041, 12037, -1, 2270, 4184, 2268, -1, 2268, 4184, 4211, -1, 12042, 12043, 2270, -1, 12044, 12045, 12046, -1, 12039, 12045, 12044, -1, 12037, 12045, 12039, -1, 12041, 12045, 12037, -1, 12041, 12047, 12045, -1, 12043, 12048, 2270, -1, 12048, 2170, 2270, -1, 2270, 2170, 4184, -1, 12048, 12049, 2170, -1, 12041, 12050, 12047, -1, 12047, 12050, 12051, -1, 2170, 4160, 4184, -1, 12050, 12052, 12051, -1, 2170, 2169, 4160, -1, 12052, 12053, 12054, -1, 2169, 1844, 4160, -1, 12050, 11674, 12052, -1, 1843, 4133, 1844, -1, 1844, 4133, 4160, -1, 12055, 11669, 1843, -1, 11674, 12056, 12052, -1, 12052, 12056, 12053, -1, 12053, 12056, 12057, -1, 12056, 12058, 12057, -1, 11674, 11671, 12056, -1, 12059, 12060, 12061, -1, 12059, 12061, 12062, -1, 12063, 5055, 5064, -1, 12063, 5064, 12064, -1, 12063, 12064, 12065, -1, 12066, 12065, 12061, -1, 12066, 12063, 12065, -1, 12067, 5055, 12063, -1, 12067, 12063, 12066, -1, 12068, 5055, 12067, -1, 12068, 12067, 12066, -1, 12068, 12066, 12061, -1, 12069, 12068, 12061, -1, 12069, 12061, 12060, -1, 12069, 12070, 5055, -1, 12069, 12060, 12070, -1, 12069, 5055, 12068, -1, 12071, 12072, 11346, -1, 12071, 12073, 12072, -1, 12071, 11346, 11348, -1, 12074, 12075, 12073, -1, 12074, 12076, 12075, -1, 12077, 12073, 12071, -1, 12077, 12074, 12073, -1, 12078, 5066, 12076, -1, 12078, 5064, 5066, -1, 12078, 12074, 12077, -1, 12078, 12076, 12074, -1, 12079, 12078, 12077, -1, 12064, 12078, 12079, -1, 12064, 5064, 12078, -1, 12064, 12079, 12065, -1, 12061, 12065, 12080, -1, 12081, 11349, 11361, -1, 12082, 12083, 12084, -1, 12082, 12085, 12083, -1, 12082, 11361, 12085, -1, 12082, 12084, 12060, -1, 12082, 12081, 11361, -1, 12082, 12060, 12081, -1, 12070, 5056, 5055, -1, 12086, 12087, 5056, -1, 12086, 12084, 12087, -1, 12086, 12060, 12084, -1, 12086, 5056, 12070, -1, 12086, 12070, 12060, -1, 12088, 12077, 12071, -1, 12088, 12079, 12077, -1, 12088, 12071, 11348, -1, 12089, 12079, 12088, -1, 12089, 12088, 11348, -1, 12090, 12089, 11348, -1, 12091, 12065, 12079, -1, 12091, 12079, 12089, -1, 12091, 12089, 12090, -1, 12092, 11348, 11349, -1, 12092, 12080, 12065, -1, 12092, 12090, 11348, -1, 12092, 12091, 12090, -1, 12092, 12065, 12091, -1, 12093, 12092, 11349, -1, 12093, 12061, 12080, -1, 12093, 12080, 12092, -1, 12062, 12093, 11349, -1, 12062, 12061, 12093, -1, 12059, 11349, 12081, -1, 12059, 12062, 11349, -1, 12059, 12081, 12060, -1, 12094, 12095, 11326, -1, 12094, 12096, 12095, -1, 12097, 5176, 5189, -1, 12097, 5189, 12098, -1, 12097, 12098, 12099, -1, 12100, 12099, 12096, -1, 12100, 12097, 12099, -1, 12101, 5176, 12097, -1, 12101, 12097, 12100, -1, 12102, 5176, 12101, -1, 12102, 12101, 12100, -1, 12102, 12100, 12096, -1, 12103, 12102, 12096, -1, 12103, 12096, 12104, -1, 12103, 12105, 5176, -1, 12103, 12104, 12105, -1, 12103, 5176, 12102, -1, 12106, 12107, 11327, -1, 12106, 12108, 12107, -1, 12106, 11327, 11324, -1, 12109, 12110, 12108, -1, 12109, 12111, 12110, -1, 12112, 12109, 12108, -1, 12112, 12108, 12106, -1, 12113, 5189, 5196, -1, 12113, 5196, 12111, -1, 12113, 12109, 12112, -1, 12113, 12111, 12109, -1, 12114, 12113, 12112, -1, 12098, 5189, 12113, -1, 12098, 12113, 12114, -1, 12098, 12114, 12099, -1, 12096, 12099, 12115, -1, 12116, 11326, 11337, -1, 12117, 12118, 12119, -1, 12117, 12120, 12118, -1, 12117, 11337, 12120, -1, 12117, 12119, 12104, -1, 12117, 12116, 11337, -1, 12117, 12104, 12116, -1, 12105, 5177, 5176, -1, 12121, 12122, 5177, -1, 12121, 12119, 12122, -1, 12121, 5177, 12105, -1, 12121, 12104, 12119, -1, 12121, 12105, 12104, -1, 12123, 12112, 12106, -1, 12123, 12114, 12112, -1, 12123, 12106, 11324, -1, 12124, 12114, 12123, -1, 12124, 12123, 11324, -1, 12125, 12124, 11324, -1, 12126, 12099, 12114, -1, 12126, 12114, 12124, -1, 12126, 12124, 12125, -1, 12127, 11324, 11326, -1, 12127, 12115, 12099, -1, 12127, 12125, 11324, -1, 12127, 12099, 12126, -1, 12127, 12126, 12125, -1, 12128, 12127, 11326, -1, 12128, 12096, 12115, -1, 12128, 12115, 12127, -1, 12095, 12128, 11326, -1, 12095, 12096, 12128, -1, 12094, 11326, 12116, -1, 12094, 12104, 12096, -1, 12094, 12116, 12104, -1, 12129, 12130, 12131, -1, 12129, 12132, 11438, -1, 12129, 12131, 12132, -1, 12133, 5303, 5312, -1, 12133, 5312, 12134, -1, 12133, 12134, 12135, -1, 12136, 12135, 12131, -1, 12136, 12133, 12135, -1, 12137, 5303, 12133, -1, 12137, 12133, 12136, -1, 12138, 5303, 12137, -1, 12138, 12137, 12136, -1, 12138, 12136, 12131, -1, 12139, 12138, 12131, -1, 12139, 12131, 12130, -1, 12139, 12140, 5303, -1, 12139, 12130, 12140, -1, 12139, 5303, 12138, -1, 12141, 12142, 11426, -1, 12141, 12143, 12142, -1, 12141, 11426, 11428, -1, 12144, 12145, 12143, -1, 12144, 12146, 12145, -1, 12147, 12143, 12141, -1, 12147, 12144, 12143, -1, 12148, 5314, 12146, -1, 12148, 5312, 5314, -1, 12148, 12144, 12147, -1, 12148, 12146, 12144, -1, 12149, 12148, 12147, -1, 12134, 12148, 12149, -1, 12134, 5312, 12148, -1, 12134, 12149, 12135, -1, 12131, 12135, 12150, -1, 12151, 11438, 11451, -1, 12152, 12153, 12154, -1, 12152, 12155, 12153, -1, 12152, 11451, 12155, -1, 12152, 12154, 12130, -1, 12152, 12151, 11451, -1, 12152, 12130, 12151, -1, 12140, 5304, 5303, -1, 12156, 12157, 5304, -1, 12156, 12154, 12157, -1, 12156, 12130, 12154, -1, 12156, 5304, 12140, -1, 12156, 12140, 12130, -1, 12158, 12147, 12141, -1, 12158, 12149, 12147, -1, 12158, 12141, 11428, -1, 12159, 12149, 12158, -1, 12159, 12158, 11428, -1, 12160, 12159, 11428, -1, 12161, 12135, 12149, -1, 12161, 12149, 12159, -1, 12161, 12159, 12160, -1, 12162, 11428, 11438, -1, 12162, 12150, 12135, -1, 12162, 12160, 11428, -1, 12162, 12161, 12160, -1, 12162, 12135, 12161, -1, 12163, 12131, 12150, -1, 12163, 12150, 12162, -1, 12163, 12162, 11438, -1, 12132, 12163, 11438, -1, 12132, 12131, 12163, -1, 12129, 11438, 12151, -1, 12129, 12151, 12130, -1, 12164, 12165, 11375, -1, 12164, 12166, 12165, -1, 12167, 5400, 5413, -1, 12167, 5413, 12168, -1, 12167, 12168, 12169, -1, 12170, 12169, 12166, -1, 12170, 12167, 12169, -1, 12171, 5400, 12167, -1, 12171, 12167, 12170, -1, 12172, 5400, 12171, -1, 12172, 12171, 12170, -1, 12172, 12170, 12166, -1, 12173, 12172, 12166, -1, 12173, 12166, 12174, -1, 12173, 12175, 5400, -1, 12173, 12174, 12175, -1, 12173, 5400, 12172, -1, 12176, 12177, 11371, -1, 12176, 12178, 12177, -1, 12176, 11371, 11373, -1, 12179, 12180, 12178, -1, 12179, 12181, 12180, -1, 12182, 12179, 12178, -1, 12182, 12178, 12176, -1, 12183, 5413, 5420, -1, 12183, 5420, 12181, -1, 12183, 12179, 12182, -1, 12183, 12181, 12179, -1, 12184, 12183, 12182, -1, 12168, 5413, 12183, -1, 12168, 12184, 12169, -1, 12168, 12183, 12184, -1, 12166, 12169, 12185, -1, 12186, 11375, 11385, -1, 12187, 12188, 12189, -1, 12187, 12190, 12188, -1, 12187, 11385, 12190, -1, 12187, 12189, 12174, -1, 12187, 12186, 11385, -1, 12187, 12174, 12186, -1, 12175, 5401, 5400, -1, 12191, 12192, 5401, -1, 12191, 12189, 12192, -1, 12191, 12174, 12189, -1, 12191, 5401, 12175, -1, 12191, 12175, 12174, -1, 12193, 12182, 12176, -1, 12193, 12184, 12182, -1, 12193, 12176, 11373, -1, 12194, 12184, 12193, -1, 12194, 12193, 11373, -1, 12195, 12194, 11373, -1, 12196, 12169, 12184, -1, 12196, 12184, 12194, -1, 12196, 12194, 12195, -1, 12197, 11373, 11375, -1, 12197, 12185, 12169, -1, 12197, 12195, 11373, -1, 12197, 12169, 12196, -1, 12197, 12196, 12195, -1, 12198, 12197, 11375, -1, 12198, 12166, 12185, -1, 12198, 12185, 12197, -1, 12165, 12198, 11375, -1, 12165, 12166, 12198, -1, 12164, 11375, 12186, -1, 12164, 12174, 12166, -1, 12164, 12186, 12174, -1, 12199, 12200, 12201, -1, 12199, 12202, 11314, -1, 12199, 12201, 12202, -1, 12203, 5455, 5464, -1, 12203, 5464, 12204, -1, 12203, 12204, 12205, -1, 12206, 12205, 12201, -1, 12206, 12203, 12205, -1, 12207, 5455, 12203, -1, 12207, 12203, 12206, -1, 12208, 5455, 12207, -1, 12208, 12207, 12206, -1, 12208, 12206, 12201, -1, 12209, 12208, 12201, -1, 12209, 12201, 12200, -1, 12209, 12210, 5455, -1, 12209, 12200, 12210, -1, 12209, 5455, 12208, -1, 12211, 12212, 11331, -1, 12211, 12213, 12212, -1, 12211, 11331, 11330, -1, 12214, 12215, 12213, -1, 12214, 12216, 12215, -1, 12217, 12213, 12211, -1, 12217, 12214, 12213, -1, 12218, 5466, 12216, -1, 12218, 5464, 5466, -1, 12218, 12214, 12217, -1, 12218, 12216, 12214, -1, 12219, 12218, 12217, -1, 12204, 12218, 12219, -1, 12204, 5464, 12218, -1, 12204, 12219, 12205, -1, 12201, 12205, 12220, -1, 12221, 11314, 11316, -1, 12222, 12223, 12224, -1, 12222, 12225, 12223, -1, 12222, 11316, 12225, -1, 12222, 12224, 12200, -1, 12222, 12221, 11316, -1, 12222, 12200, 12221, -1, 12210, 5456, 5455, -1, 12226, 12227, 5456, -1, 12226, 12224, 12227, -1, 12226, 12200, 12224, -1, 12226, 5456, 12210, -1, 12226, 12210, 12200, -1, 12228, 12217, 12211, -1, 12228, 12219, 12217, -1, 12228, 12211, 11330, -1, 12229, 12219, 12228, -1, 12229, 12228, 11330, -1, 12230, 12229, 11330, -1, 12231, 12205, 12219, -1, 12231, 12219, 12229, -1, 12231, 12229, 12230, -1, 12232, 11330, 11314, -1, 12232, 12220, 12205, -1, 12232, 12230, 11330, -1, 12232, 12231, 12230, -1, 12232, 12205, 12231, -1, 12233, 12201, 12220, -1, 12233, 12220, 12232, -1, 12233, 12232, 11314, -1, 12202, 12233, 11314, -1, 12202, 12201, 12233, -1, 12199, 11314, 12221, -1, 12199, 12221, 12200, -1, 12234, 12235, 12236, -1, 12234, 12237, 12238, -1, 12234, 12238, 11340, -1, 12239, 5566, 5579, -1, 12239, 5579, 12240, -1, 12239, 12240, 12241, -1, 12242, 12241, 12237, -1, 12242, 12239, 12241, -1, 12243, 5566, 12239, -1, 12243, 12239, 12242, -1, 12244, 5566, 12243, -1, 12244, 12243, 12242, -1, 12244, 12242, 12237, -1, 12245, 12244, 12237, -1, 12245, 12237, 12236, -1, 12245, 12246, 5566, -1, 12245, 12236, 12246, -1, 12245, 5566, 12244, -1, 12247, 12248, 11355, -1, 12247, 12249, 12248, -1, 12247, 11355, 11354, -1, 12250, 12251, 12249, -1, 12250, 12252, 12251, -1, 12253, 12250, 12249, -1, 12253, 12249, 12247, -1, 12254, 5579, 5586, -1, 12254, 5586, 12252, -1, 12254, 12250, 12253, -1, 12254, 12252, 12250, -1, 12255, 12254, 12253, -1, 12240, 5579, 12254, -1, 12240, 12255, 12241, -1, 12240, 12254, 12255, -1, 12237, 12241, 12256, -1, 12235, 11340, 11342, -1, 12257, 12258, 12259, -1, 12257, 12260, 12258, -1, 12257, 11342, 12260, -1, 12257, 12259, 12236, -1, 12257, 12235, 11342, -1, 12257, 12236, 12235, -1, 12246, 5567, 5566, -1, 12261, 12262, 5567, -1, 12261, 12259, 12262, -1, 12261, 12236, 12259, -1, 12261, 5567, 12246, -1, 12261, 12246, 12236, -1, 12263, 12253, 12247, -1, 12263, 12255, 12253, -1, 12263, 12247, 11354, -1, 12264, 12255, 12263, -1, 12264, 12263, 11354, -1, 12265, 12264, 11354, -1, 12266, 12241, 12255, -1, 12266, 12255, 12264, -1, 12266, 12264, 12265, -1, 12267, 11354, 11340, -1, 12267, 12256, 12241, -1, 12267, 12265, 11354, -1, 12267, 12241, 12266, -1, 12267, 12266, 12265, -1, 12268, 12237, 12256, -1, 12268, 12256, 12267, -1, 12268, 12267, 11340, -1, 12238, 12237, 12268, -1, 12238, 12268, 11340, -1, 12234, 11340, 12235, -1, 12234, 12236, 12237, -1, 12269, 12270, 12271, -1, 12269, 12271, 11301, -1, 12272, 5727, 5736, -1, 12272, 5736, 12273, -1, 12272, 12273, 12274, -1, 12275, 12274, 12270, -1, 12275, 12272, 12274, -1, 12276, 5727, 12272, -1, 12276, 12272, 12275, -1, 12277, 5727, 12276, -1, 12277, 12276, 12275, -1, 12277, 12275, 12270, -1, 12278, 12277, 12270, -1, 12278, 12270, 12279, -1, 12278, 12280, 5727, -1, 12278, 12279, 12280, -1, 12278, 5727, 12277, -1, 12281, 12282, 11302, -1, 12281, 12283, 12282, -1, 12281, 11302, 11299, -1, 12284, 12285, 12283, -1, 12284, 12286, 12285, -1, 12287, 12284, 12283, -1, 12287, 12283, 12281, -1, 12288, 5736, 5738, -1, 12288, 5738, 12286, -1, 12288, 12284, 12287, -1, 12288, 12286, 12284, -1, 12289, 12288, 12287, -1, 12273, 5736, 12288, -1, 12273, 12289, 12274, -1, 12273, 12288, 12289, -1, 12270, 12274, 12290, -1, 12291, 11301, 11312, -1, 12292, 12293, 12294, -1, 12292, 12295, 12293, -1, 12292, 11312, 12295, -1, 12292, 12294, 12279, -1, 12292, 12291, 11312, -1, 12292, 12279, 12291, -1, 12280, 5728, 5727, -1, 12296, 12297, 5728, -1, 12296, 12294, 12297, -1, 12296, 12279, 12294, -1, 12296, 5728, 12280, -1, 12296, 12280, 12279, -1, 12298, 12287, 12281, -1, 12298, 12289, 12287, -1, 12298, 12281, 11299, -1, 12299, 12289, 12298, -1, 12299, 12298, 11299, -1, 12300, 12299, 11299, -1, 12301, 12274, 12289, -1, 12301, 12289, 12299, -1, 12301, 12299, 12300, -1, 12302, 11299, 11301, -1, 12302, 12290, 12274, -1, 12302, 12300, 11299, -1, 12302, 12274, 12301, -1, 12302, 12301, 12300, -1, 12303, 12270, 12290, -1, 12303, 12290, 12302, -1, 12303, 12302, 11301, -1, 12271, 12270, 12303, -1, 12271, 12303, 11301, -1, 12269, 11301, 12291, -1, 12269, 12279, 12270, -1, 12269, 12291, 12279, -1, 12304, 12305, 12306, -1, 12304, 12307, 11294, -1, 12304, 12308, 12307, -1, 12309, 5790, 5803, -1, 12309, 5803, 12310, -1, 12309, 12310, 12311, -1, 12312, 12311, 12308, -1, 12312, 12309, 12311, -1, 12313, 5790, 12309, -1, 12313, 12309, 12312, -1, 12314, 5790, 12313, -1, 12314, 12313, 12312, -1, 12314, 12312, 12308, -1, 12315, 12314, 12308, -1, 12315, 12308, 12306, -1, 12315, 12316, 5790, -1, 12315, 12306, 12316, -1, 12315, 5790, 12314, -1, 12317, 12318, 11307, -1, 12317, 12319, 12318, -1, 12317, 11307, 11305, -1, 12320, 12321, 12319, -1, 12320, 12322, 12321, -1, 12323, 12320, 12319, -1, 12323, 12319, 12317, -1, 12324, 5803, 5810, -1, 12324, 5810, 12322, -1, 12324, 12320, 12323, -1, 12324, 12322, 12320, -1, 12325, 12324, 12323, -1, 12310, 5803, 12324, -1, 12310, 12324, 12325, -1, 12310, 12325, 12311, -1, 12308, 12311, 12326, -1, 12305, 11294, 11296, -1, 12327, 12328, 12329, -1, 12327, 12330, 12328, -1, 12327, 11296, 12330, -1, 12327, 12329, 12306, -1, 12327, 12305, 11296, -1, 12327, 12306, 12305, -1, 12316, 5791, 5790, -1, 12331, 12332, 5791, -1, 12331, 12329, 12332, -1, 12331, 12306, 12329, -1, 12331, 5791, 12316, -1, 12331, 12316, 12306, -1, 12333, 12323, 12317, -1, 12333, 12325, 12323, -1, 12333, 12317, 11305, -1, 12334, 12325, 12333, -1, 12334, 12333, 11305, -1, 12335, 12334, 11305, -1, 12336, 12311, 12325, -1, 12336, 12325, 12334, -1, 12336, 12334, 12335, -1, 12337, 11305, 11294, -1, 12337, 12326, 12311, -1, 12337, 12335, 11305, -1, 12337, 12311, 12336, -1, 12337, 12336, 12335, -1, 12338, 12337, 11294, -1, 12338, 12308, 12326, -1, 12338, 12326, 12337, -1, 12307, 12338, 11294, -1, 12307, 12308, 12338, -1, 12304, 11294, 12305, -1, 12304, 12306, 12308, -1, 12339, 12340, 12341, -1, 12339, 12341, 12342, -1, 12339, 12342, 12343, -1, 12344, 5998, 6011, -1, 12344, 6011, 12345, -1, 12344, 12345, 12346, -1, 12347, 12346, 12342, -1, 12347, 12344, 12346, -1, 12348, 5998, 12344, -1, 12348, 12344, 12347, -1, 12349, 5998, 12348, -1, 12349, 12348, 12347, -1, 12349, 12347, 12342, -1, 12350, 12349, 12342, -1, 12350, 12342, 12341, -1, 12350, 12351, 5998, -1, 12350, 12341, 12351, -1, 12350, 5998, 12349, -1, 12352, 12353, 11471, -1, 12352, 12354, 12353, -1, 12352, 11471, 11470, -1, 12355, 12356, 12354, -1, 12355, 12357, 12356, -1, 12358, 12354, 12352, -1, 12358, 12355, 12354, -1, 12359, 6018, 12357, -1, 12359, 6011, 6018, -1, 12359, 12355, 12358, -1, 12359, 12357, 12355, -1, 12360, 12359, 12358, -1, 12345, 6011, 12359, -1, 12345, 12359, 12360, -1, 12345, 12360, 12346, -1, 12342, 12346, 12361, -1, 12340, 11478, 11489, -1, 12362, 12363, 12364, -1, 12362, 12365, 12363, -1, 12362, 11489, 12365, -1, 12362, 12364, 12341, -1, 12362, 12340, 11489, -1, 12362, 12341, 12340, -1, 12351, 5999, 5998, -1, 12366, 12367, 5999, -1, 12366, 12364, 12367, -1, 12366, 12341, 12364, -1, 12366, 5999, 12351, -1, 12366, 12351, 12341, -1, 12368, 12358, 12352, -1, 12368, 12360, 12358, -1, 12368, 12352, 11470, -1, 12369, 12360, 12368, -1, 12369, 12368, 11470, -1, 12370, 12369, 11470, -1, 12371, 12346, 12360, -1, 12371, 12360, 12369, -1, 12371, 12369, 12370, -1, 12372, 11470, 11478, -1, 12372, 12361, 12346, -1, 12372, 12370, 11470, -1, 12372, 12371, 12370, -1, 12372, 12346, 12371, -1, 12373, 12372, 11478, -1, 12373, 12342, 12361, -1, 12373, 12361, 12372, -1, 12343, 12373, 11478, -1, 12343, 12342, 12373, -1, 12339, 11478, 12340, -1, 12339, 12343, 11478, -1, 12374, 12375, 12376, -1, 12374, 12376, 12377, -1, 12374, 12377, 12378, -1, 12379, 6019, 6028, -1, 12379, 6028, 12380, -1, 12379, 12380, 12381, -1, 12382, 12381, 12377, -1, 12382, 12379, 12381, -1, 12383, 6019, 12379, -1, 12383, 12379, 12382, -1, 12384, 6019, 12383, -1, 12384, 12383, 12382, -1, 12384, 12382, 12377, -1, 12385, 12384, 12377, -1, 12385, 12377, 12376, -1, 12385, 12386, 6019, -1, 12385, 12376, 12386, -1, 12385, 6019, 12384, -1, 12387, 12388, 11505, -1, 12387, 12389, 12388, -1, 12387, 11505, 11504, -1, 12390, 12391, 12389, -1, 12390, 12392, 12391, -1, 12393, 12389, 12387, -1, 12393, 12390, 12389, -1, 12394, 6030, 12392, -1, 12394, 6028, 6030, -1, 12394, 12390, 12393, -1, 12394, 12392, 12390, -1, 12395, 12394, 12393, -1, 12380, 12394, 12395, -1, 12380, 6028, 12394, -1, 12380, 12395, 12381, -1, 12377, 12381, 12396, -1, 12375, 11508, 11514, -1, 12397, 12398, 12399, -1, 12397, 12400, 12398, -1, 12397, 11514, 12400, -1, 12397, 12399, 12376, -1, 12397, 12375, 11514, -1, 12397, 12376, 12375, -1, 12386, 6020, 6019, -1, 12401, 12402, 6020, -1, 12401, 12399, 12402, -1, 12401, 12376, 12399, -1, 12401, 6020, 12386, -1, 12401, 12386, 12376, -1, 12403, 12393, 12387, -1, 12403, 12395, 12393, -1, 12403, 12387, 11504, -1, 12404, 12395, 12403, -1, 12404, 12403, 11504, -1, 12405, 12404, 11504, -1, 12406, 12381, 12395, -1, 12406, 12395, 12404, -1, 12406, 12404, 12405, -1, 12407, 11504, 11508, -1, 12407, 12396, 12381, -1, 12407, 12405, 11504, -1, 12407, 12406, 12405, -1, 12407, 12381, 12406, -1, 12408, 12407, 11508, -1, 12408, 12377, 12396, -1, 12408, 12396, 12407, -1, 12378, 12408, 11508, -1, 12378, 12377, 12408, -1, 12374, 11508, 12375, -1, 12374, 12378, 11508, -1, 12409, 12410, 11535, -1, 12409, 12411, 12410, -1, 12412, 6130, 6143, -1, 12412, 6143, 12413, -1, 12412, 12413, 12414, -1, 12415, 12414, 12411, -1, 12415, 12412, 12414, -1, 12416, 6130, 12412, -1, 12416, 12412, 12415, -1, 12417, 6130, 12416, -1, 12417, 12416, 12415, -1, 12417, 12415, 12411, -1, 12418, 12417, 12411, -1, 12418, 12411, 12419, -1, 12418, 12420, 6130, -1, 12418, 12419, 12420, -1, 12418, 6130, 12417, -1, 12421, 12422, 11532, -1, 12421, 12423, 12422, -1, 12421, 11532, 11531, -1, 12424, 12425, 12423, -1, 12424, 12426, 12425, -1, 12427, 12423, 12421, -1, 12427, 12424, 12423, -1, 12428, 6150, 12426, -1, 12428, 6143, 6150, -1, 12428, 12424, 12427, -1, 12428, 12426, 12424, -1, 12429, 12428, 12427, -1, 12413, 6143, 12428, -1, 12413, 12428, 12429, -1, 12413, 12429, 12414, -1, 12411, 12414, 12430, -1, 12431, 11535, 11541, -1, 12432, 12433, 12434, -1, 12432, 12435, 12433, -1, 12432, 11541, 12435, -1, 12432, 12434, 12419, -1, 12432, 12431, 11541, -1, 12432, 12419, 12431, -1, 12420, 6131, 6130, -1, 12436, 12437, 6131, -1, 12436, 12434, 12437, -1, 12436, 12419, 12434, -1, 12436, 6131, 12420, -1, 12436, 12420, 12419, -1, 12438, 12427, 12421, -1, 12438, 12429, 12427, -1, 12438, 12421, 11531, -1, 12439, 12429, 12438, -1, 12439, 12438, 11531, -1, 12440, 12439, 11531, -1, 12441, 12414, 12429, -1, 12441, 12429, 12439, -1, 12441, 12439, 12440, -1, 12442, 11531, 11535, -1, 12442, 12430, 12414, -1, 12442, 12440, 11531, -1, 12442, 12441, 12440, -1, 12442, 12414, 12441, -1, 12443, 12411, 12430, -1, 12443, 12430, 12442, -1, 12443, 12442, 11535, -1, 12410, 12443, 11535, -1, 12410, 12411, 12443, -1, 12409, 11535, 12431, -1, 12409, 12431, 12419, -1, 12409, 12419, 12411, -1, 12444, 12445, 12446, -1, 12444, 12447, 11553, -1, 12444, 12446, 12447, -1, 12448, 6243, 6252, -1, 12448, 6252, 12449, -1, 12448, 12449, 12450, -1, 12451, 12450, 12446, -1, 12451, 12448, 12450, -1, 12452, 6243, 12448, -1, 12452, 12448, 12451, -1, 12453, 6243, 12452, -1, 12453, 12452, 12451, -1, 12453, 12451, 12446, -1, 12454, 12453, 12446, -1, 12454, 12446, 12445, -1, 12454, 12455, 6243, -1, 12454, 12445, 12455, -1, 12454, 6243, 12453, -1, 12456, 12457, 11550, -1, 12456, 12458, 12457, -1, 12456, 11550, 11549, -1, 12459, 12460, 12458, -1, 12459, 12461, 12460, -1, 12462, 12458, 12456, -1, 12462, 12459, 12458, -1, 12463, 6254, 12461, -1, 12463, 6252, 6254, -1, 12463, 12459, 12462, -1, 12463, 12461, 12459, -1, 12464, 12463, 12462, -1, 12449, 6252, 12463, -1, 12449, 12463, 12464, -1, 12449, 12464, 12450, -1, 12446, 12450, 12465, -1, 12466, 11553, 11561, -1, 12467, 12468, 12469, -1, 12467, 12470, 12468, -1, 12467, 11561, 12470, -1, 12467, 12469, 12445, -1, 12467, 12466, 11561, -1, 12467, 12445, 12466, -1, 12455, 6244, 6243, -1, 12471, 12472, 6244, -1, 12471, 12469, 12472, -1, 12471, 12445, 12469, -1, 12471, 6244, 12455, -1, 12471, 12455, 12445, -1, 12473, 12462, 12456, -1, 12473, 12464, 12462, -1, 12473, 12456, 11549, -1, 12474, 12464, 12473, -1, 12474, 12473, 11549, -1, 12475, 12474, 11549, -1, 12476, 12450, 12464, -1, 12476, 12464, 12474, -1, 12476, 12474, 12475, -1, 12477, 11549, 11553, -1, 12477, 12465, 12450, -1, 12477, 12475, 11549, -1, 12477, 12476, 12475, -1, 12477, 12450, 12476, -1, 12478, 12446, 12465, -1, 12478, 12465, 12477, -1, 12478, 12477, 11553, -1, 12447, 12478, 11553, -1, 12447, 12446, 12478, -1, 12444, 11553, 12466, -1, 12444, 12466, 12445, -1, 12479, 12480, 12481, -1, 12479, 12481, 12482, -1, 12479, 12482, 12483, -1, 12484, 6354, 6367, -1, 12484, 6367, 12485, -1, 12484, 12485, 12486, -1, 12487, 12486, 12482, -1, 12487, 12484, 12486, -1, 12488, 6354, 12484, -1, 12488, 12484, 12487, -1, 12489, 6354, 12488, -1, 12489, 12488, 12487, -1, 12489, 12487, 12482, -1, 12490, 12489, 12482, -1, 12490, 12482, 12481, -1, 12490, 12491, 6354, -1, 12490, 12481, 12491, -1, 12490, 6354, 12489, -1, 12492, 12493, 11612, -1, 12492, 12494, 12493, -1, 12492, 11612, 11611, -1, 12495, 12496, 12494, -1, 12495, 12497, 12496, -1, 12498, 12494, 12492, -1, 12498, 12495, 12494, -1, 12499, 6374, 12497, -1, 12499, 6367, 6374, -1, 12499, 12495, 12498, -1, 12499, 12497, 12495, -1, 12500, 12499, 12498, -1, 12485, 6367, 12499, -1, 12485, 12499, 12500, -1, 12485, 12500, 12486, -1, 12482, 12486, 12501, -1, 12480, 11615, 11625, -1, 12502, 12503, 12504, -1, 12502, 12505, 12503, -1, 12502, 11625, 12505, -1, 12502, 12504, 12481, -1, 12502, 12480, 11625, -1, 12502, 12481, 12480, -1, 12491, 6355, 6354, -1, 12506, 12507, 6355, -1, 12506, 12504, 12507, -1, 12506, 12481, 12504, -1, 12506, 6355, 12491, -1, 12506, 12491, 12481, -1, 12508, 12498, 12492, -1, 12508, 12500, 12498, -1, 12508, 12492, 11611, -1, 12509, 12500, 12508, -1, 12509, 12508, 11611, -1, 12510, 12509, 11611, -1, 12511, 12486, 12500, -1, 12511, 12500, 12509, -1, 12511, 12509, 12510, -1, 12512, 11611, 11615, -1, 12512, 12501, 12486, -1, 12512, 12510, 11611, -1, 12512, 12511, 12510, -1, 12512, 12486, 12511, -1, 12513, 12512, 11615, -1, 12513, 12482, 12501, -1, 12513, 12501, 12512, -1, 12483, 12513, 11615, -1, 12483, 12482, 12513, -1, 12479, 11615, 12480, -1, 12479, 12483, 11615, -1, 12514, 12515, 12516, -1, 12514, 12516, 12517, -1, 12518, 6539, 6548, -1, 12518, 6548, 12519, -1, 12518, 12519, 12520, -1, 12521, 12520, 12516, -1, 12521, 12518, 12520, -1, 12522, 6539, 12518, -1, 12522, 12518, 12521, -1, 12523, 6539, 12522, -1, 12523, 12522, 12521, -1, 12523, 12521, 12516, -1, 12524, 12523, 12516, -1, 12524, 12516, 12515, -1, 12524, 12525, 6539, -1, 12524, 12515, 12525, -1, 12524, 6539, 12523, -1, 12526, 12527, 11639, -1, 12526, 12528, 12527, -1, 12526, 11639, 11638, -1, 12529, 12530, 12528, -1, 12529, 12531, 12530, -1, 12532, 12528, 12526, -1, 12532, 12529, 12528, -1, 12533, 6550, 12531, -1, 12533, 6548, 6550, -1, 12533, 12529, 12532, -1, 12533, 12531, 12529, -1, 12534, 12533, 12532, -1, 12519, 6548, 12533, -1, 12519, 12533, 12534, -1, 12519, 12534, 12520, -1, 12516, 12520, 12535, -1, 12536, 11643, 11645, -1, 12537, 12538, 12539, -1, 12537, 12540, 12538, -1, 12537, 11645, 12540, -1, 12537, 12539, 12515, -1, 12537, 12536, 11645, -1, 12537, 12515, 12536, -1, 12525, 6540, 6539, -1, 12541, 12542, 6540, -1, 12541, 12539, 12542, -1, 12541, 12515, 12539, -1, 12541, 6540, 12525, -1, 12541, 12525, 12515, -1, 12543, 12532, 12526, -1, 12543, 12534, 12532, -1, 12543, 12526, 11638, -1, 12544, 12534, 12543, -1, 12544, 12543, 11638, -1, 12545, 12544, 11638, -1, 12546, 12520, 12534, -1, 12546, 12534, 12544, -1, 12546, 12544, 12545, -1, 12547, 11638, 11643, -1, 12547, 12535, 12520, -1, 12547, 12545, 11638, -1, 12547, 12546, 12545, -1, 12547, 12520, 12546, -1, 12548, 12547, 11643, -1, 12548, 12516, 12535, -1, 12548, 12535, 12547, -1, 12517, 12548, 11643, -1, 12517, 12516, 12548, -1, 12514, 11643, 12536, -1, 12514, 12517, 11643, -1, 12514, 12536, 12515, -1, 12549, 12550, 12551, -1, 12549, 12552, 11598, -1, 12549, 12553, 12552, -1, 12554, 6575, 6584, -1, 12554, 6584, 12555, -1, 12554, 12555, 12556, -1, 12557, 12556, 12553, -1, 12557, 12554, 12556, -1, 12558, 6575, 12554, -1, 12558, 12554, 12557, -1, 12559, 6575, 12558, -1, 12559, 12558, 12557, -1, 12559, 12557, 12553, -1, 12560, 12559, 12553, -1, 12560, 12553, 12551, -1, 12560, 12561, 6575, -1, 12560, 12551, 12561, -1, 12560, 6575, 12559, -1, 12562, 12563, 11594, -1, 12562, 12564, 12563, -1, 12562, 11594, 11593, -1, 12565, 12566, 12564, -1, 12565, 12567, 12566, -1, 12568, 12565, 12564, -1, 12568, 12564, 12562, -1, 12569, 6584, 6586, -1, 12569, 6586, 12567, -1, 12569, 12565, 12568, -1, 12569, 12567, 12565, -1, 12570, 12569, 12568, -1, 12555, 6584, 12569, -1, 12555, 12569, 12570, -1, 12555, 12570, 12556, -1, 12553, 12556, 12571, -1, 12550, 11598, 11603, -1, 12572, 12573, 12574, -1, 12572, 12575, 12573, -1, 12572, 11603, 12575, -1, 12572, 12574, 12551, -1, 12572, 12550, 11603, -1, 12572, 12551, 12550, -1, 12561, 6576, 6575, -1, 12576, 12577, 6576, -1, 12576, 12574, 12577, -1, 12576, 6576, 12561, -1, 12576, 12551, 12574, -1, 12576, 12561, 12551, -1, 12578, 12568, 12562, -1, 12578, 12570, 12568, -1, 12578, 12562, 11593, -1, 12579, 12570, 12578, -1, 12579, 12578, 11593, -1, 12580, 12579, 11593, -1, 12581, 12556, 12570, -1, 12581, 12570, 12579, -1, 12581, 12579, 12580, -1, 12582, 11593, 11598, -1, 12582, 12571, 12556, -1, 12582, 12580, 11593, -1, 12582, 12556, 12581, -1, 12582, 12581, 12580, -1, 12583, 12582, 11598, -1, 12583, 12553, 12571, -1, 12583, 12571, 12582, -1, 12552, 12583, 11598, -1, 12552, 12553, 12583, -1, 12549, 11598, 12550, -1, 12549, 12551, 12553, -1, 12584, 12585, 12586, -1, 12584, 12586, 11578, -1, 12587, 6686, 6699, -1, 12587, 6699, 12588, -1, 12587, 12588, 12589, -1, 12590, 12589, 12585, -1, 12590, 12587, 12589, -1, 12591, 6686, 12587, -1, 12591, 12587, 12590, -1, 12592, 6686, 12591, -1, 12592, 12591, 12590, -1, 12592, 12590, 12585, -1, 12593, 12592, 12585, -1, 12593, 12585, 12594, -1, 12593, 12595, 6686, -1, 12593, 12594, 12595, -1, 12593, 6686, 12592, -1, 12596, 12597, 11570, -1, 12596, 12598, 12597, -1, 12596, 11570, 11569, -1, 12599, 12600, 12598, -1, 12599, 12601, 12600, -1, 12602, 12599, 12598, -1, 12602, 12598, 12596, -1, 12603, 6699, 6706, -1, 12603, 6706, 12601, -1, 12603, 12599, 12602, -1, 12603, 12601, 12599, -1, 12604, 12603, 12602, -1, 12588, 6699, 12603, -1, 12588, 12604, 12589, -1, 12588, 12603, 12604, -1, 12585, 12589, 12605, -1, 12606, 11578, 11580, -1, 12607, 12608, 12609, -1, 12607, 12610, 12608, -1, 12607, 11580, 12610, -1, 12607, 12609, 12594, -1, 12607, 12606, 11580, -1, 12607, 12594, 12606, -1, 12595, 6687, 6686, -1, 12611, 12612, 6687, -1, 12611, 12609, 12612, -1, 12611, 12594, 12609, -1, 12611, 6687, 12595, -1, 12611, 12595, 12594, -1, 12613, 12602, 12596, -1, 12613, 12604, 12602, -1, 12613, 12596, 11569, -1, 12614, 12604, 12613, -1, 12614, 12613, 11569, -1, 12615, 12614, 11569, -1, 12616, 12589, 12604, -1, 12616, 12604, 12614, -1, 12616, 12614, 12615, -1, 12617, 11569, 11578, -1, 12617, 12605, 12589, -1, 12617, 12615, 11569, -1, 12617, 12589, 12616, -1, 12617, 12616, 12615, -1, 12618, 12585, 12605, -1, 12618, 12605, 12617, -1, 12618, 12617, 11578, -1, 12586, 12585, 12618, -1, 12586, 12618, 11578, -1, 12584, 11578, 12606, -1, 12584, 12594, 12585, -1, 12584, 12606, 12594, -1, 12619, 12620, 12621, -1, 12619, 12622, 11649, -1, 12619, 12621, 12622, -1, 12623, 12624, 12625, -1, 12623, 12625, 12626, -1, 12623, 12626, 12627, -1, 12628, 12627, 12621, -1, 12628, 12623, 12627, -1, 12629, 12624, 12623, -1, 12629, 12623, 12628, -1, 12630, 12624, 12629, -1, 12630, 12629, 12628, -1, 12630, 12628, 12621, -1, 12631, 12630, 12621, -1, 12631, 12621, 12620, -1, 12631, 12632, 12624, -1, 12631, 12620, 12632, -1, 12631, 12624, 12630, -1, 12633, 12634, 11656, -1, 12633, 12635, 12634, -1, 12633, 11656, 11655, -1, 12636, 12637, 12635, -1, 12636, 12638, 12637, -1, 12639, 12635, 12633, -1, 12639, 12636, 12635, -1, 12640, 12641, 12638, -1, 12640, 12625, 12641, -1, 12640, 12636, 12639, -1, 12640, 12638, 12636, -1, 12642, 12640, 12639, -1, 12626, 12640, 12642, -1, 12626, 12625, 12640, -1, 12626, 12642, 12627, -1, 12621, 12627, 12643, -1, 12644, 11649, 11648, -1, 12645, 12646, 12647, -1, 12645, 12648, 12646, -1, 12645, 11648, 12648, -1, 12645, 12647, 12620, -1, 12645, 12644, 11648, -1, 12645, 12620, 12644, -1, 12632, 12649, 12624, -1, 12650, 12651, 12649, -1, 12650, 12647, 12651, -1, 12650, 12620, 12647, -1, 12650, 12649, 12632, -1, 12650, 12632, 12620, -1, 12652, 12639, 12633, -1, 12652, 12642, 12639, -1, 12652, 12633, 11655, -1, 12653, 12642, 12652, -1, 12653, 12652, 11655, -1, 12654, 12653, 11655, -1, 12655, 12627, 12642, -1, 12655, 12642, 12653, -1, 12655, 12653, 12654, -1, 12656, 11655, 11649, -1, 12656, 12643, 12627, -1, 12656, 12654, 11655, -1, 12656, 12655, 12654, -1, 12656, 12627, 12655, -1, 12657, 12621, 12643, -1, 12657, 12643, 12656, -1, 12657, 12656, 11649, -1, 12622, 12657, 11649, -1, 12622, 12621, 12657, -1, 12619, 11649, 12644, -1, 12619, 12644, 12620, -1, 12658, 12659, 12660, -1, 12658, 12660, 11663, -1, 12661, 12662, 12663, -1, 12661, 12663, 12664, -1, 12661, 12664, 12665, -1, 12666, 12665, 12659, -1, 12666, 12661, 12665, -1, 12667, 12662, 12661, -1, 12667, 12661, 12666, -1, 12668, 12662, 12667, -1, 12668, 12667, 12666, -1, 12668, 12666, 12659, -1, 12669, 12668, 12659, -1, 12669, 12659, 12670, -1, 12669, 12671, 12662, -1, 12669, 12670, 12671, -1, 12669, 12662, 12668, -1, 12672, 12673, 11668, -1, 12672, 12674, 12673, -1, 12672, 11668, 11667, -1, 12675, 12676, 12674, -1, 12675, 12677, 12676, -1, 12678, 12675, 12674, -1, 12678, 12674, 12672, -1, 12679, 12663, 12680, -1, 12679, 12680, 12677, -1, 12679, 12675, 12678, -1, 12679, 12677, 12675, -1, 12681, 12679, 12678, -1, 12664, 12663, 12679, -1, 12664, 12679, 12681, -1, 12664, 12681, 12665, -1, 12659, 12665, 12682, -1, 12683, 11663, 11662, -1, 12684, 12685, 12686, -1, 12684, 12687, 12685, -1, 12684, 11662, 12687, -1, 12684, 12686, 12670, -1, 12684, 12683, 11662, -1, 12684, 12670, 12683, -1, 12671, 12688, 12662, -1, 12689, 12690, 12688, -1, 12689, 12686, 12690, -1, 12689, 12688, 12671, -1, 12689, 12670, 12686, -1, 12689, 12671, 12670, -1, 12691, 12678, 12672, -1, 12691, 12681, 12678, -1, 12691, 12672, 11667, -1, 12692, 12681, 12691, -1, 12692, 12691, 11667, -1, 12693, 12692, 11667, -1, 12694, 12665, 12681, -1, 12694, 12681, 12692, -1, 12694, 12692, 12693, -1, 12695, 11667, 11663, -1, 12695, 12682, 12665, -1, 12695, 12693, 11667, -1, 12695, 12665, 12694, -1, 12695, 12694, 12693, -1, 12696, 12659, 12682, -1, 12696, 12682, 12695, -1, 12696, 12695, 11663, -1, 12660, 12659, 12696, -1, 12660, 12696, 11663, -1, 12658, 11663, 12683, -1, 12658, 12670, 12659, -1, 12658, 12683, 12670, -1, 12697, 12698, 12699, -1, 12697, 12699, 12700, -1, 12697, 12700, 12701, -1, 12702, 12703, 12704, -1, 12702, 12704, 12705, -1, 12702, 12705, 12706, -1, 12707, 12706, 12700, -1, 12707, 12702, 12706, -1, 12708, 12703, 12702, -1, 12708, 12702, 12707, -1, 12709, 12703, 12708, -1, 12709, 12708, 12707, -1, 12709, 12707, 12700, -1, 12710, 12709, 12700, -1, 12710, 12700, 12699, -1, 12710, 12711, 12703, -1, 12710, 12699, 12711, -1, 12710, 12703, 12709, -1, 12712, 12713, 11614, -1, 12712, 12714, 12713, -1, 12712, 11614, 11613, -1, 12715, 12716, 12714, -1, 12715, 12717, 12716, -1, 12718, 12714, 12712, -1, 12718, 12715, 12714, -1, 12719, 12720, 12717, -1, 12719, 12704, 12720, -1, 12719, 12715, 12718, -1, 12719, 12717, 12715, -1, 12721, 12719, 12718, -1, 12705, 12719, 12721, -1, 12705, 12704, 12719, -1, 12705, 12721, 12706, -1, 12700, 12706, 12722, -1, 12698, 11605, 11604, -1, 12723, 12724, 12725, -1, 12723, 12726, 12724, -1, 12723, 11604, 12726, -1, 12723, 12725, 12699, -1, 12723, 12698, 11604, -1, 12723, 12699, 12698, -1, 12711, 12727, 12703, -1, 12728, 12729, 12727, -1, 12728, 12725, 12729, -1, 12728, 12699, 12725, -1, 12728, 12727, 12711, -1, 12728, 12711, 12699, -1, 12730, 12718, 12712, -1, 12730, 12721, 12718, -1, 12730, 12712, 11613, -1, 12731, 12721, 12730, -1, 12731, 12730, 11613, -1, 12732, 12731, 11613, -1, 12733, 12706, 12721, -1, 12733, 12721, 12731, -1, 12733, 12731, 12732, -1, 12734, 11613, 11605, -1, 12734, 12722, 12706, -1, 12734, 12732, 11613, -1, 12734, 12733, 12732, -1, 12734, 12706, 12733, -1, 12735, 12734, 11605, -1, 12735, 12700, 12722, -1, 12735, 12722, 12734, -1, 12701, 12735, 11605, -1, 12701, 12700, 12735, -1, 12697, 11605, 12698, -1, 12697, 12701, 11605, -1, 12736, 12737, 12738, -1, 12736, 12739, 12740, -1, 12736, 12740, 11627, -1, 12741, 12742, 12743, -1, 12741, 12743, 12744, -1, 12741, 12744, 12745, -1, 12746, 12745, 12739, -1, 12746, 12741, 12745, -1, 12747, 12742, 12741, -1, 12747, 12741, 12746, -1, 12748, 12742, 12747, -1, 12748, 12747, 12746, -1, 12748, 12746, 12739, -1, 12749, 12748, 12739, -1, 12749, 12739, 12738, -1, 12749, 12750, 12742, -1, 12749, 12738, 12750, -1, 12749, 12742, 12748, -1, 12751, 12752, 11641, -1, 12751, 12753, 12752, -1, 12751, 11641, 11640, -1, 12754, 12755, 12753, -1, 12754, 12756, 12755, -1, 12757, 12754, 12753, -1, 12757, 12753, 12751, -1, 12758, 12743, 12759, -1, 12758, 12759, 12756, -1, 12758, 12754, 12757, -1, 12758, 12756, 12754, -1, 12760, 12758, 12757, -1, 12744, 12743, 12758, -1, 12744, 12760, 12745, -1, 12744, 12758, 12760, -1, 12739, 12745, 12761, -1, 12737, 11627, 11626, -1, 12762, 12763, 12764, -1, 12762, 12765, 12763, -1, 12762, 11626, 12765, -1, 12762, 12764, 12738, -1, 12762, 12737, 11626, -1, 12762, 12738, 12737, -1, 12750, 12766, 12742, -1, 12767, 12768, 12766, -1, 12767, 12764, 12768, -1, 12767, 12738, 12764, -1, 12767, 12766, 12750, -1, 12767, 12750, 12738, -1, 12769, 12757, 12751, -1, 12769, 12760, 12757, -1, 12769, 12751, 11640, -1, 12770, 12760, 12769, -1, 12770, 12769, 11640, -1, 12771, 12770, 11640, -1, 12772, 12745, 12760, -1, 12772, 12760, 12770, -1, 12772, 12770, 12771, -1, 12773, 11640, 11627, -1, 12773, 12761, 12745, -1, 12773, 12771, 11640, -1, 12773, 12745, 12772, -1, 12773, 12772, 12771, -1, 12774, 12739, 12761, -1, 12774, 12761, 12773, -1, 12774, 12773, 11627, -1, 12740, 12739, 12774, -1, 12740, 12774, 11627, -1, 12736, 11627, 12737, -1, 12736, 12738, 12739, -1, 12775, 12776, 12777, -1, 12775, 12778, 11370, -1, 12775, 12777, 12778, -1, 12779, 12780, 12781, -1, 12779, 12781, 12782, -1, 12779, 12782, 12783, -1, 12784, 12783, 12777, -1, 12784, 12779, 12783, -1, 12785, 12780, 12779, -1, 12785, 12779, 12784, -1, 12786, 12780, 12785, -1, 12786, 12785, 12784, -1, 12786, 12784, 12777, -1, 12787, 12786, 12777, -1, 12787, 12777, 12776, -1, 12787, 12788, 12780, -1, 12787, 12776, 12788, -1, 12787, 12780, 12786, -1, 12789, 12790, 11382, -1, 12789, 12791, 12790, -1, 12789, 11382, 11379, -1, 12792, 12793, 12791, -1, 12792, 12794, 12793, -1, 12795, 12791, 12789, -1, 12795, 12792, 12791, -1, 12796, 12797, 12794, -1, 12796, 12781, 12797, -1, 12796, 12792, 12795, -1, 12796, 12794, 12792, -1, 12798, 12796, 12795, -1, 12782, 12796, 12798, -1, 12782, 12781, 12796, -1, 12782, 12798, 12783, -1, 12777, 12783, 12799, -1, 12800, 11370, 11369, -1, 12801, 12802, 12803, -1, 12801, 12804, 12802, -1, 12801, 11369, 12804, -1, 12801, 12803, 12776, -1, 12801, 12800, 11369, -1, 12801, 12776, 12800, -1, 12788, 12805, 12780, -1, 12806, 12807, 12805, -1, 12806, 12803, 12807, -1, 12806, 12776, 12803, -1, 12806, 12805, 12788, -1, 12806, 12788, 12776, -1, 12808, 12795, 12789, -1, 12808, 12798, 12795, -1, 12808, 12789, 11379, -1, 12809, 12798, 12808, -1, 12809, 12808, 11379, -1, 12810, 12809, 11379, -1, 12811, 12783, 12798, -1, 12811, 12798, 12809, -1, 12811, 12809, 12810, -1, 12812, 11379, 11370, -1, 12812, 12799, 12783, -1, 12812, 12810, 11379, -1, 12812, 12811, 12810, -1, 12812, 12783, 12811, -1, 12813, 12777, 12799, -1, 12813, 12799, 12812, -1, 12813, 12812, 11370, -1, 12778, 12813, 11370, -1, 12778, 12777, 12813, -1, 12775, 11370, 12800, -1, 12775, 12800, 12776, -1, 12814, 12815, 12816, -1, 12814, 12816, 12817, -1, 12818, 12819, 12820, -1, 12818, 12820, 12821, -1, 12818, 12821, 12822, -1, 12823, 12822, 12816, -1, 12823, 12818, 12822, -1, 12824, 12819, 12818, -1, 12824, 12818, 12823, -1, 12825, 12819, 12824, -1, 12825, 12824, 12823, -1, 12825, 12823, 12816, -1, 12826, 12825, 12816, -1, 12826, 12816, 12815, -1, 12826, 12827, 12819, -1, 12826, 12815, 12827, -1, 12826, 12819, 12825, -1, 12828, 12829, 11356, -1, 12828, 12830, 12829, -1, 12828, 11356, 11353, -1, 12831, 12832, 12830, -1, 12831, 12833, 12832, -1, 12834, 12830, 12828, -1, 12834, 12831, 12830, -1, 12835, 12836, 12833, -1, 12835, 12820, 12836, -1, 12835, 12831, 12834, -1, 12835, 12833, 12831, -1, 12837, 12835, 12834, -1, 12821, 12820, 12835, -1, 12821, 12835, 12837, -1, 12821, 12837, 12822, -1, 12816, 12822, 12838, -1, 12839, 11344, 11343, -1, 12840, 12841, 12842, -1, 12840, 12843, 12841, -1, 12840, 11343, 12843, -1, 12840, 12842, 12815, -1, 12840, 12839, 11343, -1, 12840, 12815, 12839, -1, 12827, 12844, 12819, -1, 12845, 12846, 12844, -1, 12845, 12842, 12846, -1, 12845, 12815, 12842, -1, 12845, 12844, 12827, -1, 12845, 12827, 12815, -1, 12847, 12834, 12828, -1, 12847, 12837, 12834, -1, 12847, 12828, 11353, -1, 12848, 12837, 12847, -1, 12848, 12847, 11353, -1, 12849, 12848, 11353, -1, 12850, 12822, 12837, -1, 12850, 12837, 12848, -1, 12850, 12848, 12849, -1, 12851, 11353, 11344, -1, 12851, 12838, 12822, -1, 12851, 12849, 11353, -1, 12851, 12850, 12849, -1, 12851, 12822, 12850, -1, 12852, 12851, 11344, -1, 12852, 12816, 12838, -1, 12852, 12838, 12851, -1, 12817, 12852, 11344, -1, 12817, 12816, 12852, -1, 12814, 11344, 12839, -1, 12814, 12817, 11344, -1, 12814, 12839, 12815, -1, 12853, 12854, 11287, -1, 12853, 12855, 12854, -1, 12856, 12857, 12858, -1, 12856, 12858, 12859, -1, 12856, 12859, 12860, -1, 12861, 12860, 12855, -1, 12861, 12856, 12860, -1, 12862, 12857, 12856, -1, 12862, 12856, 12861, -1, 12863, 12857, 12862, -1, 12863, 12862, 12861, -1, 12863, 12861, 12855, -1, 12864, 12863, 12855, -1, 12864, 12855, 12865, -1, 12864, 12866, 12857, -1, 12864, 12865, 12866, -1, 12864, 12857, 12863, -1, 12867, 12868, 11297, -1, 12867, 12869, 12868, -1, 12867, 11297, 11293, -1, 12870, 12871, 12869, -1, 12870, 12872, 12871, -1, 12873, 12870, 12869, -1, 12873, 12869, 12867, -1, 12874, 12858, 12875, -1, 12874, 12875, 12872, -1, 12874, 12870, 12873, -1, 12874, 12872, 12870, -1, 12876, 12874, 12873, -1, 12859, 12858, 12874, -1, 12859, 12876, 12860, -1, 12859, 12874, 12876, -1, 12855, 12860, 12877, -1, 12878, 11287, 11286, -1, 12879, 12880, 12881, -1, 12879, 12882, 12880, -1, 12879, 11286, 12882, -1, 12879, 12881, 12865, -1, 12879, 12878, 11286, -1, 12879, 12865, 12878, -1, 12866, 12883, 12857, -1, 12884, 12885, 12883, -1, 12884, 12881, 12885, -1, 12884, 12883, 12866, -1, 12884, 12865, 12881, -1, 12884, 12866, 12865, -1, 12886, 12873, 12867, -1, 12886, 12876, 12873, -1, 12886, 12867, 11293, -1, 12887, 12876, 12886, -1, 12887, 12886, 11293, -1, 12888, 12887, 11293, -1, 12889, 12860, 12876, -1, 12889, 12876, 12887, -1, 12889, 12887, 12888, -1, 12890, 11293, 11287, -1, 12890, 12877, 12860, -1, 12890, 12888, 11293, -1, 12890, 12860, 12889, -1, 12890, 12889, 12888, -1, 12891, 12890, 11287, -1, 12891, 12855, 12877, -1, 12891, 12877, 12890, -1, 12854, 12891, 11287, -1, 12854, 12855, 12891, -1, 12853, 11287, 12878, -1, 12853, 12865, 12855, -1, 12853, 12878, 12865, -1, 12892, 12893, 12894, -1, 12892, 12895, 12896, -1, 12892, 12896, 11318, -1, 12897, 12898, 12899, -1, 12897, 12899, 12900, -1, 12897, 12900, 12901, -1, 12902, 12901, 12895, -1, 12902, 12897, 12901, -1, 12903, 12898, 12897, -1, 12903, 12897, 12902, -1, 12904, 12898, 12903, -1, 12904, 12903, 12902, -1, 12904, 12902, 12895, -1, 12905, 12904, 12895, -1, 12905, 12895, 12894, -1, 12905, 12906, 12898, -1, 12905, 12894, 12906, -1, 12905, 12898, 12904, -1, 12907, 12908, 11323, -1, 12907, 12909, 12908, -1, 12907, 11323, 11322, -1, 12910, 12911, 12909, -1, 12910, 12912, 12911, -1, 12913, 12910, 12909, -1, 12913, 12909, 12907, -1, 12914, 12899, 12915, -1, 12914, 12915, 12912, -1, 12914, 12910, 12913, -1, 12914, 12912, 12910, -1, 12916, 12914, 12913, -1, 12900, 12899, 12914, -1, 12900, 12914, 12916, -1, 12900, 12916, 12901, -1, 12895, 12901, 12917, -1, 12893, 11318, 11317, -1, 12918, 12919, 12920, -1, 12918, 12921, 12919, -1, 12918, 11317, 12921, -1, 12918, 12920, 12894, -1, 12918, 12893, 11317, -1, 12918, 12894, 12893, -1, 12906, 12922, 12898, -1, 12923, 12924, 12922, -1, 12923, 12920, 12924, -1, 12923, 12922, 12906, -1, 12923, 12894, 12920, -1, 12923, 12906, 12894, -1, 12925, 12913, 12907, -1, 12925, 12916, 12913, -1, 12925, 12907, 11322, -1, 12926, 12916, 12925, -1, 12926, 12925, 11322, -1, 12927, 12926, 11322, -1, 12928, 12901, 12916, -1, 12928, 12916, 12926, -1, 12928, 12926, 12927, -1, 12929, 11322, 11318, -1, 12929, 12917, 12901, -1, 12929, 12927, 11322, -1, 12929, 12901, 12928, -1, 12929, 12928, 12927, -1, 12930, 12895, 12917, -1, 12930, 12917, 12929, -1, 12930, 12929, 11318, -1, 12896, 12895, 12930, -1, 12896, 12930, 11318, -1, 12892, 11318, 12893, -1, 12892, 12894, 12895, -1, 12931, 12932, 12933, -1, 12931, 12933, 12934, -1, 12931, 12934, 12935, -1, 12936, 7695, 7704, -1, 12936, 7704, 12937, -1, 12936, 12937, 12938, -1, 12939, 12938, 12934, -1, 12939, 12936, 12938, -1, 12940, 7695, 12936, -1, 12940, 12936, 12939, -1, 12941, 7695, 12940, -1, 12941, 12940, 12939, -1, 12941, 12939, 12934, -1, 12942, 12941, 12934, -1, 12942, 12934, 12933, -1, 12942, 12943, 7695, -1, 12942, 12933, 12943, -1, 12942, 7695, 12941, -1, 12944, 12945, 11534, -1, 12944, 12946, 12945, -1, 12944, 11534, 11533, -1, 12947, 12948, 12946, -1, 12947, 12949, 12948, -1, 12950, 12946, 12944, -1, 12950, 12947, 12946, -1, 12951, 7706, 12949, -1, 12951, 7704, 7706, -1, 12951, 12947, 12950, -1, 12951, 12949, 12947, -1, 12952, 12951, 12950, -1, 12937, 7704, 12951, -1, 12937, 12951, 12952, -1, 12937, 12952, 12938, -1, 12934, 12938, 12953, -1, 12932, 11523, 11522, -1, 12954, 12955, 12956, -1, 12954, 12957, 12955, -1, 12954, 11522, 12957, -1, 12954, 12956, 12933, -1, 12954, 12932, 11522, -1, 12954, 12933, 12932, -1, 12943, 7696, 7695, -1, 12958, 12959, 7696, -1, 12958, 12956, 12959, -1, 12958, 12933, 12956, -1, 12958, 7696, 12943, -1, 12958, 12943, 12933, -1, 12960, 12950, 12944, -1, 12960, 12952, 12950, -1, 12960, 12944, 11533, -1, 12961, 12952, 12960, -1, 12961, 12960, 11533, -1, 12962, 12961, 11533, -1, 12963, 12938, 12952, -1, 12963, 12952, 12961, -1, 12963, 12961, 12962, -1, 12964, 11533, 11523, -1, 12964, 12953, 12938, -1, 12964, 12962, 11533, -1, 12964, 12963, 12962, -1, 12964, 12938, 12963, -1, 12965, 12964, 11523, -1, 12965, 12934, 12953, -1, 12965, 12953, 12964, -1, 12935, 12965, 11523, -1, 12935, 12934, 12965, -1, 12931, 11523, 12932, -1, 12931, 12935, 11523, -1, 12966, 12967, 12968, -1, 12966, 12968, 11543, -1, 12969, 12970, 12971, -1, 12969, 12971, 12972, -1, 12969, 12972, 12973, -1, 12974, 12973, 12967, -1, 12974, 12969, 12973, -1, 12975, 12970, 12969, -1, 12975, 12969, 12974, -1, 12976, 12970, 12975, -1, 12976, 12975, 12974, -1, 12976, 12974, 12967, -1, 12977, 12976, 12967, -1, 12977, 12967, 12978, -1, 12977, 12979, 12970, -1, 12977, 12978, 12979, -1, 12977, 12970, 12976, -1, 12980, 12981, 11552, -1, 12980, 12982, 12981, -1, 12980, 11552, 11551, -1, 12983, 12984, 12982, -1, 12983, 12985, 12984, -1, 12986, 12983, 12982, -1, 12986, 12982, 12980, -1, 12987, 12971, 12988, -1, 12987, 12988, 12985, -1, 12987, 12983, 12986, -1, 12987, 12985, 12983, -1, 12989, 12987, 12986, -1, 12972, 12971, 12987, -1, 12972, 12989, 12973, -1, 12972, 12987, 12989, -1, 12967, 12973, 12990, -1, 12991, 11543, 11542, -1, 12992, 12993, 12994, -1, 12992, 12995, 12993, -1, 12992, 11542, 12995, -1, 12992, 12994, 12978, -1, 12992, 12991, 11542, -1, 12992, 12978, 12991, -1, 12979, 12996, 12970, -1, 12997, 12998, 12996, -1, 12997, 12994, 12998, -1, 12997, 12978, 12994, -1, 12997, 12996, 12979, -1, 12997, 12979, 12978, -1, 12999, 12986, 12980, -1, 12999, 12989, 12986, -1, 12999, 12980, 11551, -1, 13000, 12989, 12999, -1, 13000, 12999, 11551, -1, 13001, 13000, 11551, -1, 13002, 12973, 12989, -1, 13002, 12989, 13000, -1, 13002, 13000, 13001, -1, 13003, 11551, 11543, -1, 13003, 12990, 12973, -1, 13003, 13001, 11551, -1, 13003, 12973, 13002, -1, 13003, 13002, 13001, -1, 13004, 12967, 12990, -1, 13004, 12990, 13003, -1, 13004, 13003, 11543, -1, 12968, 12967, 13004, -1, 12968, 13004, 11543, -1, 12966, 11543, 12991, -1, 12966, 12978, 12967, -1, 12966, 12991, 12978, -1, 13005, 13006, 13007, -1, 13005, 13008, 11584, -1, 13005, 13007, 13008, -1, 13009, 13010, 13011, -1, 13009, 13011, 13012, -1, 13009, 13012, 13013, -1, 13014, 13013, 13007, -1, 13014, 13009, 13013, -1, 13015, 13010, 13009, -1, 13015, 13009, 13014, -1, 13016, 13010, 13015, -1, 13016, 13015, 13014, -1, 13016, 13014, 13007, -1, 13017, 13016, 13007, -1, 13017, 13007, 13006, -1, 13017, 13018, 13010, -1, 13017, 13006, 13018, -1, 13017, 13010, 13016, -1, 13019, 13020, 11596, -1, 13019, 13021, 13020, -1, 13019, 11596, 11595, -1, 13022, 13023, 13021, -1, 13022, 13024, 13023, -1, 13025, 13021, 13019, -1, 13025, 13022, 13021, -1, 13026, 13027, 13024, -1, 13026, 13011, 13027, -1, 13026, 13022, 13025, -1, 13026, 13024, 13022, -1, 13028, 13026, 13025, -1, 13012, 13011, 13026, -1, 13012, 13026, 13028, -1, 13012, 13028, 13013, -1, 13007, 13013, 13029, -1, 13030, 11584, 11583, -1, 13031, 13032, 13033, -1, 13031, 13034, 13032, -1, 13031, 11583, 13034, -1, 13031, 13033, 13006, -1, 13031, 13030, 11583, -1, 13031, 13006, 13030, -1, 13018, 13035, 13010, -1, 13036, 13037, 13035, -1, 13036, 13033, 13037, -1, 13036, 13006, 13033, -1, 13036, 13035, 13018, -1, 13036, 13018, 13006, -1, 13038, 13025, 13019, -1, 13038, 13028, 13025, -1, 13038, 13019, 11595, -1, 13039, 13028, 13038, -1, 13039, 13038, 11595, -1, 13040, 13039, 11595, -1, 13041, 13013, 13028, -1, 13041, 13028, 13039, -1, 13041, 13039, 13040, -1, 13042, 11595, 11584, -1, 13042, 13029, 13013, -1, 13042, 13040, 11595, -1, 13042, 13041, 13040, -1, 13042, 13013, 13041, -1, 13043, 13007, 13029, -1, 13043, 13029, 13042, -1, 13043, 13042, 11584, -1, 13008, 13043, 11584, -1, 13008, 13007, 13043, -1, 13005, 11584, 13030, -1, 13005, 13030, 13006, -1, 13044, 13045, 13046, -1, 13044, 13047, 13048, -1, 13044, 13048, 11565, -1, 13049, 13050, 13051, -1, 13049, 13051, 13052, -1, 13049, 13052, 13053, -1, 13054, 13053, 13047, -1, 13054, 13049, 13053, -1, 13055, 13050, 13049, -1, 13055, 13049, 13054, -1, 13056, 13050, 13055, -1, 13056, 13055, 13054, -1, 13056, 13054, 13047, -1, 13057, 13056, 13047, -1, 13057, 13047, 13046, -1, 13057, 13058, 13050, -1, 13057, 13046, 13058, -1, 13057, 13050, 13056, -1, 13059, 13060, 11577, -1, 13059, 13061, 13060, -1, 13059, 11577, 11576, -1, 13062, 13063, 13061, -1, 13062, 13064, 13063, -1, 13065, 13062, 13061, -1, 13065, 13061, 13059, -1, 13066, 13051, 13067, -1, 13066, 13067, 13064, -1, 13066, 13062, 13065, -1, 13066, 13064, 13062, -1, 13068, 13066, 13065, -1, 13052, 13051, 13066, -1, 13052, 13066, 13068, -1, 13052, 13068, 13053, -1, 13047, 13053, 13069, -1, 13045, 11565, 11564, -1, 13070, 13071, 13072, -1, 13070, 13073, 13071, -1, 13070, 11564, 13073, -1, 13070, 13072, 13046, -1, 13070, 13045, 11564, -1, 13070, 13046, 13045, -1, 13058, 13074, 13050, -1, 13075, 13076, 13074, -1, 13075, 13072, 13076, -1, 13075, 13046, 13072, -1, 13075, 13074, 13058, -1, 13075, 13058, 13046, -1, 13077, 13065, 13059, -1, 13077, 13068, 13065, -1, 13077, 13059, 11576, -1, 13078, 13068, 13077, -1, 13078, 13077, 11576, -1, 13079, 13078, 11576, -1, 13080, 13053, 13068, -1, 13080, 13068, 13078, -1, 13080, 13078, 13079, -1, 13081, 11576, 11565, -1, 13081, 13069, 13053, -1, 13081, 13079, 11576, -1, 13081, 13053, 13080, -1, 13081, 13080, 13079, -1, 13082, 13047, 13069, -1, 13082, 13069, 13081, -1, 13082, 13081, 11565, -1, 13048, 13047, 13082, -1, 13048, 13082, 11565, -1, 13044, 11565, 13045, -1, 13044, 13046, 13047, -1, 13083, 13084, 13085, -1, 13083, 13085, 13086, -1, 13083, 13086, 13087, -1, 13088, 13089, 13090, -1, 13088, 13090, 13091, -1, 13088, 13091, 13092, -1, 13093, 13092, 13086, -1, 13093, 13088, 13092, -1, 13094, 13089, 13088, -1, 13094, 13088, 13093, -1, 13095, 13089, 13094, -1, 13095, 13094, 13093, -1, 13095, 13093, 13086, -1, 13096, 13095, 13086, -1, 13096, 13086, 13085, -1, 13096, 13097, 13089, -1, 13096, 13085, 13097, -1, 13096, 13089, 13095, -1, 13098, 13099, 11507, -1, 13098, 13100, 13099, -1, 13098, 11507, 11506, -1, 13101, 13102, 13100, -1, 13101, 13103, 13102, -1, 13104, 13100, 13098, -1, 13104, 13101, 13100, -1, 13105, 13106, 13103, -1, 13105, 13090, 13106, -1, 13105, 13101, 13104, -1, 13105, 13103, 13101, -1, 13107, 13105, 13104, -1, 13091, 13105, 13107, -1, 13091, 13090, 13105, -1, 13091, 13107, 13092, -1, 13086, 13092, 13108, -1, 13084, 11492, 11491, -1, 13109, 13110, 13111, -1, 13109, 13112, 13110, -1, 13109, 11491, 13112, -1, 13109, 13111, 13085, -1, 13109, 13084, 11491, -1, 13109, 13085, 13084, -1, 13097, 13113, 13089, -1, 13114, 13115, 13113, -1, 13114, 13111, 13115, -1, 13114, 13085, 13111, -1, 13114, 13113, 13097, -1, 13114, 13097, 13085, -1, 13116, 13104, 13098, -1, 13116, 13107, 13104, -1, 13116, 13098, 11506, -1, 13117, 13107, 13116, -1, 13117, 13116, 11506, -1, 13118, 13117, 11506, -1, 13119, 13092, 13107, -1, 13119, 13107, 13117, -1, 13119, 13117, 13118, -1, 13120, 11506, 11492, -1, 13120, 13108, 13092, -1, 13120, 13118, 11506, -1, 13120, 13119, 13118, -1, 13120, 13092, 13119, -1, 13121, 13120, 11492, -1, 13121, 13086, 13108, -1, 13121, 13108, 13120, -1, 13087, 13121, 11492, -1, 13087, 13086, 13121, -1, 13083, 11492, 13084, -1, 13083, 13087, 11492, -1, 13122, 13123, 13124, -1, 13122, 13124, 13125, -1, 13122, 13125, 13126, -1, 13127, 8355, 8364, -1, 13127, 8364, 13128, -1, 13127, 13128, 13129, -1, 13130, 13129, 13125, -1, 13130, 13127, 13129, -1, 13131, 8355, 13127, -1, 13131, 13127, 13130, -1, 13132, 8355, 13131, -1, 13132, 13131, 13130, -1, 13132, 13130, 13125, -1, 13133, 13132, 13125, -1, 13133, 13125, 13124, -1, 13133, 13134, 8355, -1, 13133, 13124, 13134, -1, 13133, 8355, 13132, -1, 13135, 13136, 11482, -1, 13135, 13137, 13136, -1, 13135, 11482, 11481, -1, 13138, 13139, 13137, -1, 13138, 13140, 13139, -1, 13141, 13137, 13135, -1, 13141, 13138, 13137, -1, 13142, 8366, 13140, -1, 13142, 8364, 8366, -1, 13142, 13138, 13141, -1, 13142, 13140, 13138, -1, 13143, 13142, 13141, -1, 13128, 8364, 13142, -1, 13128, 13142, 13143, -1, 13128, 13143, 13129, -1, 13125, 13129, 13144, -1, 13123, 11460, 11459, -1, 13145, 13146, 13147, -1, 13145, 13148, 13146, -1, 13145, 11459, 13148, -1, 13145, 13147, 13124, -1, 13145, 13123, 11459, -1, 13145, 13124, 13123, -1, 13134, 8356, 8355, -1, 13149, 13150, 8356, -1, 13149, 13147, 13150, -1, 13149, 13124, 13147, -1, 13149, 8356, 13134, -1, 13149, 13134, 13124, -1, 13151, 13141, 13135, -1, 13151, 13143, 13141, -1, 13151, 13135, 11481, -1, 13152, 13143, 13151, -1, 13152, 13151, 11481, -1, 13153, 13152, 11481, -1, 13154, 13129, 13143, -1, 13154, 13143, 13152, -1, 13154, 13152, 13153, -1, 13155, 11481, 11460, -1, 13155, 13144, 13129, -1, 13155, 13153, 11481, -1, 13155, 13154, 13153, -1, 13155, 13129, 13154, -1, 13156, 13155, 11460, -1, 13156, 13125, 13144, -1, 13156, 13144, 13155, -1, 13126, 13156, 11460, -1, 13126, 13125, 13156, -1, 13122, 11460, 13123, -1, 13122, 13126, 11460, -1, 13157, 13158, 13159, -1, 13157, 13160, 11387, -1, 13157, 13159, 13160, -1, 13161, 8462, 8475, -1, 13161, 8475, 13162, -1, 13161, 13162, 13163, -1, 13164, 13163, 13159, -1, 13164, 13161, 13163, -1, 13165, 8462, 13161, -1, 13165, 13161, 13164, -1, 13166, 8462, 13165, -1, 13166, 13165, 13164, -1, 13166, 13164, 13159, -1, 13167, 13166, 13159, -1, 13167, 13159, 13158, -1, 13167, 13168, 8462, -1, 13167, 13158, 13168, -1, 13167, 8462, 13166, -1, 13169, 13170, 11441, -1, 13169, 13171, 13170, -1, 13169, 11441, 11439, -1, 13172, 13173, 13171, -1, 13172, 13174, 13173, -1, 13175, 13171, 13169, -1, 13175, 13172, 13171, -1, 13176, 8482, 13174, -1, 13176, 8475, 8482, -1, 13176, 13172, 13175, -1, 13176, 13174, 13172, -1, 13177, 13176, 13175, -1, 13162, 13176, 13177, -1, 13162, 8475, 13176, -1, 13162, 13177, 13163, -1, 13159, 13163, 13178, -1, 13179, 11387, 11389, -1, 13180, 13181, 13182, -1, 13180, 13183, 13181, -1, 13180, 11389, 13183, -1, 13180, 13182, 13158, -1, 13180, 13179, 11389, -1, 13180, 13158, 13179, -1, 13168, 8463, 8462, -1, 13184, 13185, 8463, -1, 13184, 13182, 13185, -1, 13184, 13158, 13182, -1, 13184, 8463, 13168, -1, 13184, 13168, 13158, -1, 13186, 13175, 13169, -1, 13186, 13177, 13175, -1, 13186, 13169, 11439, -1, 13187, 13177, 13186, -1, 13187, 13186, 11439, -1, 13188, 13187, 11439, -1, 13189, 13163, 13177, -1, 13189, 13177, 13187, -1, 13189, 13187, 13188, -1, 13190, 11439, 11387, -1, 13190, 13178, 13163, -1, 13190, 13188, 11439, -1, 13190, 13189, 13188, -1, 13190, 13163, 13189, -1, 13191, 13159, 13178, -1, 13191, 13178, 13190, -1, 13191, 13190, 11387, -1, 13160, 13191, 11387, -1, 13160, 13159, 13191, -1, 13157, 11387, 13179, -1, 13157, 13179, 13158, -1, 13192, 13193, 13194, -1, 13192, 13195, 13196, -1, 13192, 13196, 11362, -1, 13197, 8555, 8564, -1, 13197, 8564, 13198, -1, 13197, 13198, 13199, -1, 13200, 13199, 13195, -1, 13200, 13197, 13199, -1, 13201, 8555, 13197, -1, 13201, 13197, 13200, -1, 13202, 8555, 13201, -1, 13202, 13201, 13200, -1, 13202, 13200, 13195, -1, 13203, 13202, 13195, -1, 13203, 13195, 13194, -1, 13203, 13204, 8555, -1, 13203, 13194, 13204, -1, 13203, 8555, 13202, -1, 13205, 13206, 11378, -1, 13205, 13207, 13206, -1, 13205, 11378, 11377, -1, 13208, 13209, 13207, -1, 13208, 13210, 13209, -1, 13211, 13208, 13207, -1, 13211, 13207, 13205, -1, 13212, 8564, 8566, -1, 13212, 8566, 13210, -1, 13212, 13208, 13211, -1, 13212, 13210, 13208, -1, 13213, 13212, 13211, -1, 13198, 8564, 13212, -1, 13198, 13212, 13213, -1, 13198, 13213, 13199, -1, 13195, 13199, 13214, -1, 13193, 11362, 11364, -1, 13215, 13216, 13217, -1, 13215, 13218, 13216, -1, 13215, 11364, 13218, -1, 13215, 13217, 13194, -1, 13215, 13193, 11364, -1, 13215, 13194, 13193, -1, 13204, 8556, 8555, -1, 13219, 13220, 8556, -1, 13219, 13217, 13220, -1, 13219, 8556, 13204, -1, 13219, 13194, 13217, -1, 13219, 13204, 13194, -1, 13221, 13211, 13205, -1, 13221, 13213, 13211, -1, 13221, 13205, 11377, -1, 13222, 13213, 13221, -1, 13222, 13221, 11377, -1, 13223, 13222, 11377, -1, 13224, 13199, 13213, -1, 13224, 13213, 13222, -1, 13224, 13222, 13223, -1, 13225, 11377, 11362, -1, 13225, 13214, 13199, -1, 13225, 13223, 11377, -1, 13225, 13199, 13224, -1, 13225, 13224, 13223, -1, 13226, 13195, 13214, -1, 13226, 13214, 13225, -1, 13226, 13225, 11362, -1, 13196, 13195, 13226, -1, 13196, 13226, 11362, -1, 13192, 11362, 13193, -1, 13192, 13194, 13195, -1, 13227, 13228, 13229, -1, 13227, 13230, 11547, -1, 13227, 13229, 13230, -1, 13231, 13232, 13233, -1, 13231, 13233, 13234, -1, 13231, 13234, 13235, -1, 13236, 13235, 13229, -1, 13236, 13231, 13235, -1, 13237, 13232, 13231, -1, 13237, 13231, 13236, -1, 13238, 13232, 13237, -1, 13238, 13237, 13236, -1, 13238, 13236, 13229, -1, 13239, 13238, 13229, -1, 13239, 13229, 13228, -1, 13239, 13240, 13232, -1, 13239, 13228, 13240, -1, 13239, 13232, 13238, -1, 13241, 13242, 11562, -1, 13241, 13243, 13242, -1, 13241, 11562, 11554, -1, 13244, 13245, 13243, -1, 13244, 13246, 13245, -1, 13247, 13243, 13241, -1, 13247, 13244, 13243, -1, 13248, 13249, 13246, -1, 13248, 13233, 13249, -1, 13248, 13244, 13247, -1, 13248, 13246, 13244, -1, 13250, 13248, 13247, -1, 13234, 13233, 13248, -1, 13234, 13248, 13250, -1, 13234, 13250, 13235, -1, 13229, 13235, 13251, -1, 13252, 11547, 11546, -1, 13253, 13254, 13255, -1, 13253, 13256, 13254, -1, 13253, 11546, 13256, -1, 13253, 13255, 13228, -1, 13253, 13252, 11546, -1, 13253, 13228, 13252, -1, 13240, 13257, 13232, -1, 13258, 13259, 13257, -1, 13258, 13255, 13259, -1, 13258, 13228, 13255, -1, 13258, 13257, 13240, -1, 13258, 13240, 13228, -1, 13260, 13247, 13241, -1, 13260, 13250, 13247, -1, 13260, 13241, 11554, -1, 13261, 13250, 13260, -1, 13261, 13260, 11554, -1, 13262, 13261, 11554, -1, 13263, 13235, 13250, -1, 13263, 13250, 13261, -1, 13263, 13261, 13262, -1, 13264, 11554, 11547, -1, 13264, 13251, 13235, -1, 13264, 13262, 11554, -1, 13264, 13263, 13262, -1, 13264, 13235, 13263, -1, 13265, 13229, 13251, -1, 13265, 13251, 13264, -1, 13265, 13264, 11547, -1, 13230, 13265, 11547, -1, 13230, 13229, 13265, -1, 13227, 11547, 13252, -1, 13227, 13252, 13228, -1, 13266, 13267, 13268, -1, 13266, 13268, 13269, -1, 13266, 13269, 13270, -1, 13271, 13272, 13273, -1, 13271, 13273, 13274, -1, 13271, 13274, 13275, -1, 13276, 13275, 13269, -1, 13276, 13271, 13275, -1, 13277, 13272, 13271, -1, 13277, 13271, 13276, -1, 13278, 13272, 13277, -1, 13278, 13277, 13276, -1, 13278, 13276, 13269, -1, 13279, 13278, 13269, -1, 13279, 13269, 13268, -1, 13279, 13280, 13272, -1, 13279, 13268, 13280, -1, 13279, 13272, 13278, -1, 13281, 13282, 11529, -1, 13281, 13283, 13282, -1, 13281, 11529, 11524, -1, 13284, 13285, 13283, -1, 13284, 13286, 13285, -1, 13287, 13283, 13281, -1, 13287, 13284, 13283, -1, 13288, 13289, 13286, -1, 13288, 13273, 13289, -1, 13288, 13284, 13287, -1, 13288, 13286, 13284, -1, 13290, 13288, 13287, -1, 13274, 13288, 13290, -1, 13274, 13273, 13288, -1, 13274, 13290, 13275, -1, 13269, 13275, 13291, -1, 13267, 11516, 11515, -1, 13292, 13293, 13294, -1, 13292, 13295, 13293, -1, 13292, 11515, 13295, -1, 13292, 13294, 13268, -1, 13292, 13267, 11515, -1, 13292, 13268, 13267, -1, 13280, 13296, 13272, -1, 13297, 13298, 13296, -1, 13297, 13294, 13298, -1, 13297, 13268, 13294, -1, 13297, 13296, 13280, -1, 13297, 13280, 13268, -1, 13299, 13287, 13281, -1, 13299, 13290, 13287, -1, 13299, 13281, 11524, -1, 13300, 13290, 13299, -1, 13300, 13299, 11524, -1, 13301, 13300, 11524, -1, 13302, 13275, 13290, -1, 13302, 13290, 13300, -1, 13302, 13300, 13301, -1, 13303, 11524, 11516, -1, 13303, 13291, 13275, -1, 13303, 13301, 11524, -1, 13303, 13302, 13301, -1, 13303, 13275, 13302, -1, 13304, 13303, 11516, -1, 13304, 13269, 13291, -1, 13304, 13291, 13303, -1, 13270, 13304, 11516, -1, 13270, 13269, 13304, -1, 13266, 11516, 13267, -1, 13266, 13270, 11516, -1, 13305, 13306, 13307, -1, 13305, 13308, 11601, -1, 13305, 13307, 13308, -1, 13309, 13310, 13311, -1, 13309, 13311, 13312, -1, 13309, 13312, 13313, -1, 13314, 13313, 13307, -1, 13314, 13309, 13313, -1, 13315, 13310, 13309, -1, 13315, 13309, 13314, -1, 13316, 13310, 13315, -1, 13316, 13315, 13314, -1, 13316, 13314, 13307, -1, 13317, 13316, 13307, -1, 13317, 13307, 13306, -1, 13317, 13318, 13310, -1, 13317, 13306, 13318, -1, 13317, 13310, 13316, -1, 13319, 13320, 11618, -1, 13319, 13321, 13320, -1, 13319, 11618, 11609, -1, 13322, 13323, 13321, -1, 13322, 13324, 13323, -1, 13325, 13321, 13319, -1, 13325, 13322, 13321, -1, 13326, 13327, 13324, -1, 13326, 13311, 13327, -1, 13326, 13322, 13325, -1, 13326, 13324, 13322, -1, 13328, 13326, 13325, -1, 13312, 13311, 13326, -1, 13312, 13326, 13328, -1, 13312, 13328, 13313, -1, 13307, 13313, 13329, -1, 13330, 11601, 11600, -1, 13331, 13332, 13333, -1, 13331, 13334, 13332, -1, 13331, 11600, 13334, -1, 13331, 13333, 13306, -1, 13331, 13330, 11600, -1, 13331, 13306, 13330, -1, 13318, 13335, 13310, -1, 13336, 13337, 13335, -1, 13336, 13333, 13337, -1, 13336, 13306, 13333, -1, 13336, 13335, 13318, -1, 13336, 13318, 13306, -1, 13338, 13325, 13319, -1, 13338, 13328, 13325, -1, 13338, 13319, 11609, -1, 13339, 13328, 13338, -1, 13339, 13338, 11609, -1, 13340, 13339, 11609, -1, 13341, 13313, 13328, -1, 13341, 13328, 13339, -1, 13341, 13339, 13340, -1, 13342, 11609, 11601, -1, 13342, 13329, 13313, -1, 13342, 13340, 11609, -1, 13342, 13341, 13340, -1, 13342, 13313, 13341, -1, 13343, 13307, 13329, -1, 13343, 13329, 13342, -1, 13343, 13342, 11601, -1, 13308, 13343, 11601, -1, 13308, 13307, 13343, -1, 13305, 11601, 13330, -1, 13305, 13330, 13306, -1, 13344, 13345, 13346, -1, 13344, 13346, 11575, -1, 13347, 13348, 13349, -1, 13347, 13349, 13350, -1, 13347, 13350, 13351, -1, 13352, 13351, 13345, -1, 13352, 13347, 13351, -1, 13353, 13348, 13347, -1, 13353, 13347, 13352, -1, 13354, 13348, 13353, -1, 13354, 13353, 13352, -1, 13354, 13352, 13345, -1, 13355, 13354, 13345, -1, 13355, 13345, 13356, -1, 13355, 13357, 13348, -1, 13355, 13356, 13357, -1, 13355, 13348, 13354, -1, 13358, 13359, 11587, -1, 13358, 13360, 13359, -1, 13358, 11587, 11581, -1, 13361, 13362, 13360, -1, 13361, 13363, 13362, -1, 13364, 13361, 13360, -1, 13364, 13360, 13358, -1, 13365, 13349, 13366, -1, 13365, 13366, 13363, -1, 13365, 13361, 13364, -1, 13365, 13363, 13361, -1, 13367, 13365, 13364, -1, 13350, 13349, 13365, -1, 13350, 13367, 13351, -1, 13350, 13365, 13367, -1, 13345, 13351, 13368, -1, 13369, 11575, 11574, -1, 13370, 13371, 13372, -1, 13370, 13373, 13371, -1, 13370, 11574, 13373, -1, 13370, 13372, 13356, -1, 13370, 13369, 11574, -1, 13370, 13356, 13369, -1, 13357, 13374, 13348, -1, 13375, 13376, 13374, -1, 13375, 13372, 13376, -1, 13375, 13356, 13372, -1, 13375, 13374, 13357, -1, 13375, 13357, 13356, -1, 13377, 13364, 13358, -1, 13377, 13367, 13364, -1, 13377, 13358, 11581, -1, 13378, 13367, 13377, -1, 13378, 13377, 11581, -1, 13379, 13378, 11581, -1, 13380, 13351, 13367, -1, 13380, 13367, 13378, -1, 13380, 13378, 13379, -1, 13381, 11581, 11575, -1, 13381, 13368, 13351, -1, 13381, 13379, 11581, -1, 13381, 13351, 13380, -1, 13381, 13380, 13379, -1, 13382, 13345, 13368, -1, 13382, 13368, 13381, -1, 13382, 13381, 11575, -1, 13346, 13345, 13382, -1, 13346, 13382, 11575, -1, 13344, 11575, 13369, -1, 13344, 13356, 13345, -1, 13344, 13369, 13356, -1, 13383, 13384, 13385, -1, 13383, 13385, 13386, -1, 13383, 13386, 13387, -1, 13388, 13389, 13390, -1, 13388, 13390, 13391, -1, 13388, 13391, 13392, -1, 13393, 13392, 13386, -1, 13393, 13388, 13392, -1, 13394, 13389, 13388, -1, 13394, 13388, 13393, -1, 13395, 13389, 13394, -1, 13395, 13394, 13393, -1, 13395, 13393, 13386, -1, 13396, 13395, 13386, -1, 13396, 13386, 13385, -1, 13396, 13397, 13389, -1, 13396, 13385, 13397, -1, 13396, 13389, 13395, -1, 13398, 13399, 11498, -1, 13398, 13400, 13399, -1, 13398, 11498, 11490, -1, 13401, 13402, 13400, -1, 13401, 13403, 13402, -1, 13404, 13400, 13398, -1, 13404, 13401, 13400, -1, 13405, 13406, 13403, -1, 13405, 13390, 13406, -1, 13405, 13401, 13404, -1, 13405, 13403, 13401, -1, 13407, 13405, 13404, -1, 13391, 13390, 13405, -1, 13391, 13405, 13407, -1, 13391, 13407, 13392, -1, 13386, 13392, 13408, -1, 13384, 11484, 11483, -1, 13409, 13410, 13411, -1, 13409, 13412, 13410, -1, 13409, 11483, 13412, -1, 13409, 13411, 13385, -1, 13409, 13384, 11483, -1, 13409, 13385, 13384, -1, 13397, 13413, 13389, -1, 13414, 13415, 13413, -1, 13414, 13411, 13415, -1, 13414, 13385, 13411, -1, 13414, 13413, 13397, -1, 13414, 13397, 13385, -1, 13416, 13404, 13398, -1, 13416, 13407, 13404, -1, 13416, 13398, 11490, -1, 13417, 13407, 13416, -1, 13417, 13416, 11490, -1, 13418, 13417, 11490, -1, 13419, 13392, 13407, -1, 13419, 13407, 13417, -1, 13419, 13417, 13418, -1, 13420, 11490, 11484, -1, 13420, 13408, 13392, -1, 13420, 13418, 11490, -1, 13420, 13419, 13418, -1, 13420, 13392, 13419, -1, 13421, 13420, 11484, -1, 13421, 13386, 13408, -1, 13421, 13408, 13420, -1, 13387, 13421, 11484, -1, 13387, 13386, 13421, -1, 13383, 11484, 13384, -1, 13383, 13387, 11484, -1, 13422, 13423, 13424, -1, 13422, 13424, 13425, -1, 13426, 13427, 13428, -1, 13426, 13428, 13429, -1, 13426, 13429, 13430, -1, 13431, 13430, 13424, -1, 13431, 13426, 13430, -1, 13432, 13427, 13426, -1, 13432, 13426, 13431, -1, 13433, 13427, 13432, -1, 13433, 13432, 13431, -1, 13433, 13431, 13424, -1, 13434, 13433, 13424, -1, 13434, 13424, 13423, -1, 13434, 13435, 13427, -1, 13434, 13423, 13435, -1, 13434, 13427, 13433, -1, 13436, 13437, 11468, -1, 13436, 13438, 13437, -1, 13436, 11468, 11463, -1, 13439, 13440, 13438, -1, 13439, 13441, 13440, -1, 13442, 13438, 13436, -1, 13442, 13439, 13438, -1, 13443, 13444, 13441, -1, 13443, 13428, 13444, -1, 13443, 13439, 13442, -1, 13443, 13441, 13439, -1, 13445, 13443, 13442, -1, 13429, 13443, 13445, -1, 13429, 13428, 13443, -1, 13429, 13445, 13430, -1, 13424, 13430, 13446, -1, 13447, 11458, 11457, -1, 13448, 13449, 13450, -1, 13448, 13451, 13449, -1, 13448, 11457, 13451, -1, 13448, 13450, 13423, -1, 13448, 13447, 11457, -1, 13448, 13423, 13447, -1, 13435, 13452, 13427, -1, 13453, 13454, 13452, -1, 13453, 13450, 13454, -1, 13453, 13423, 13450, -1, 13453, 13452, 13435, -1, 13453, 13435, 13423, -1, 13455, 13442, 13436, -1, 13455, 13445, 13442, -1, 13455, 13436, 11463, -1, 13456, 13445, 13455, -1, 13456, 13455, 11463, -1, 13457, 13456, 11463, -1, 13458, 13430, 13445, -1, 13458, 13445, 13456, -1, 13458, 13456, 13457, -1, 13459, 11463, 11458, -1, 13459, 13446, 13430, -1, 13459, 13457, 11463, -1, 13459, 13458, 13457, -1, 13459, 13430, 13458, -1, 13460, 13459, 11458, -1, 13460, 13424, 13446, -1, 13460, 13446, 13459, -1, 13425, 13460, 11458, -1, 13425, 13424, 13460, -1, 13422, 11458, 13447, -1, 13422, 13425, 11458, -1, 13422, 13447, 13423, -1, 13461, 13462, 13463, -1, 13461, 13464, 11472, -1, 13461, 13463, 13464, -1, 13465, 13466, 13467, -1, 13465, 13467, 13468, -1, 13465, 13468, 13469, -1, 13470, 13469, 13463, -1, 13470, 13465, 13469, -1, 13471, 13466, 13465, -1, 13471, 13465, 13470, -1, 13472, 13466, 13471, -1, 13472, 13471, 13470, -1, 13472, 13470, 13463, -1, 13473, 13472, 13463, -1, 13473, 13463, 13462, -1, 13473, 13474, 13466, -1, 13473, 13462, 13474, -1, 13473, 13466, 13472, -1, 13475, 13476, 11466, -1, 13475, 13477, 13476, -1, 13475, 11466, 11465, -1, 13478, 13479, 13477, -1, 13478, 13480, 13479, -1, 13481, 13477, 13475, -1, 13481, 13478, 13477, -1, 13482, 13483, 13480, -1, 13482, 13467, 13483, -1, 13482, 13478, 13481, -1, 13482, 13480, 13478, -1, 13484, 13482, 13481, -1, 13468, 13482, 13484, -1, 13468, 13467, 13482, -1, 13468, 13484, 13469, -1, 13463, 13469, 13485, -1, 13486, 11472, 11480, -1, 13487, 13488, 13489, -1, 13487, 13490, 13488, -1, 13487, 11480, 13490, -1, 13487, 13489, 13462, -1, 13487, 13486, 11480, -1, 13487, 13462, 13486, -1, 13474, 13491, 13466, -1, 13492, 13493, 13491, -1, 13492, 13489, 13493, -1, 13492, 13462, 13489, -1, 13492, 13491, 13474, -1, 13492, 13474, 13462, -1, 13494, 13481, 13475, -1, 13494, 13484, 13481, -1, 13494, 13475, 11465, -1, 13495, 13484, 13494, -1, 13495, 13494, 11465, -1, 13496, 13495, 11465, -1, 13497, 13469, 13484, -1, 13497, 13484, 13495, -1, 13497, 13495, 13496, -1, 13498, 11465, 11472, -1, 13498, 13485, 13469, -1, 13498, 13496, 11465, -1, 13498, 13497, 13496, -1, 13498, 13469, 13497, -1, 13499, 13463, 13485, -1, 13499, 13485, 13498, -1, 13499, 13498, 11472, -1, 13464, 13499, 11472, -1, 13464, 13463, 13499, -1, 13461, 11472, 13486, -1, 13461, 13486, 13462, -1, 13500, 13501, 13502, -1, 13503, 13500, 11502, -1, 13503, 13504, 13500, -1, 13505, 11502, 13506, -1, 13505, 13503, 11502, -1, 13505, 13506, 13507, -1, 13505, 13507, 13504, -1, 13505, 13504, 13503, -1, 13508, 13509, 13510, -1, 13508, 13511, 13512, -1, 13508, 13510, 13511, -1, 13513, 13512, 13504, -1, 13513, 13508, 13512, -1, 13514, 13509, 13508, -1, 13514, 13508, 13513, -1, 13515, 13513, 13504, -1, 13515, 13514, 13513, -1, 13515, 13509, 13514, -1, 13516, 13515, 13504, -1, 13516, 13509, 13515, -1, 13516, 13504, 13507, -1, 13516, 13517, 13509, -1, 13516, 13507, 13517, -1, 13518, 13519, 13520, -1, 13518, 13521, 13519, -1, 13522, 13518, 13520, -1, 13523, 13524, 13521, -1, 13523, 13510, 13524, -1, 13523, 13521, 13518, -1, 13523, 13518, 13522, -1, 13525, 13523, 13522, -1, 13511, 13510, 13523, -1, 13511, 13525, 13512, -1, 13511, 13523, 13525, -1, 13504, 13512, 13501, -1, 13506, 11502, 11511, -1, 13526, 13527, 13528, -1, 13526, 13529, 13527, -1, 13526, 11511, 13529, -1, 13526, 13528, 13507, -1, 13526, 13506, 11511, -1, 13526, 13507, 13506, -1, 13517, 13530, 13509, -1, 13531, 13532, 13530, -1, 13531, 13528, 13532, -1, 13531, 13507, 13528, -1, 13531, 13530, 13517, -1, 13531, 13517, 13507, -1, 13533, 13534, 11495, -1, 13533, 13520, 13534, -1, 13533, 11495, 11494, -1, 13533, 13522, 13520, -1, 13535, 13533, 11494, -1, 13536, 13525, 13522, -1, 13536, 13522, 13533, -1, 13536, 13533, 13535, -1, 13537, 13535, 11494, -1, 13537, 13536, 13535, -1, 13538, 13537, 11494, -1, 13539, 13512, 13525, -1, 13539, 13525, 13536, -1, 13539, 13536, 13537, -1, 13539, 13537, 13538, -1, 13502, 11494, 11502, -1, 13502, 13538, 11494, -1, 13502, 13501, 13512, -1, 13502, 13512, 13539, -1, 13502, 13539, 13538, -1, 13500, 13502, 11502, -1, 13500, 13504, 13501, -1, 13540, 13541, 13542, -1, 13540, 13543, 11539, -1, 13540, 13542, 13543, -1, 13544, 13545, 13546, -1, 13544, 13546, 13547, -1, 13544, 13547, 13548, -1, 13549, 13548, 13542, -1, 13549, 13544, 13548, -1, 13550, 13545, 13544, -1, 13550, 13544, 13549, -1, 13551, 13545, 13550, -1, 13551, 13550, 13549, -1, 13551, 13549, 13542, -1, 13552, 13551, 13542, -1, 13552, 13542, 13541, -1, 13552, 13553, 13545, -1, 13552, 13541, 13553, -1, 13552, 13545, 13551, -1, 13554, 13555, 11527, -1, 13554, 13556, 13555, -1, 13554, 11527, 11526, -1, 13557, 13558, 13556, -1, 13557, 13559, 13558, -1, 13560, 13556, 13554, -1, 13560, 13557, 13556, -1, 13561, 13562, 13559, -1, 13561, 13546, 13562, -1, 13561, 13557, 13560, -1, 13561, 13559, 13557, -1, 13563, 13561, 13560, -1, 13547, 13561, 13563, -1, 13547, 13546, 13561, -1, 13547, 13563, 13548, -1, 13542, 13548, 13564, -1, 13565, 11539, 11544, -1, 13566, 13567, 13568, -1, 13566, 13569, 13567, -1, 13566, 11544, 13569, -1, 13566, 13568, 13541, -1, 13566, 13565, 11544, -1, 13566, 13541, 13565, -1, 13553, 13570, 13545, -1, 13571, 13572, 13570, -1, 13571, 13568, 13572, -1, 13571, 13541, 13568, -1, 13571, 13570, 13553, -1, 13571, 13553, 13541, -1, 13573, 13560, 13554, -1, 13573, 13563, 13560, -1, 13573, 13554, 11526, -1, 13574, 13563, 13573, -1, 13574, 13573, 11526, -1, 13575, 13574, 11526, -1, 13576, 13548, 13563, -1, 13576, 13563, 13574, -1, 13576, 13574, 13575, -1, 13577, 11526, 11539, -1, 13577, 13564, 13548, -1, 13577, 13575, 11526, -1, 13577, 13576, 13575, -1, 13577, 13548, 13576, -1, 13578, 13542, 13564, -1, 13578, 13564, 13577, -1, 13578, 13577, 11539, -1, 13543, 13578, 11539, -1, 13543, 13542, 13578, -1, 13540, 11539, 13565, -1, 13540, 13565, 13541, -1, 13579, 13580, 13581, -1, 13579, 13582, 11566, -1, 13579, 13581, 13582, -1, 13583, 13584, 13585, -1, 13583, 13585, 13586, -1, 13583, 13586, 13587, -1, 13588, 13587, 13581, -1, 13588, 13583, 13587, -1, 13589, 13584, 13583, -1, 13589, 13583, 13588, -1, 13590, 13584, 13589, -1, 13590, 13589, 13588, -1, 13590, 13588, 13581, -1, 13591, 13590, 13581, -1, 13591, 13581, 13580, -1, 13591, 13592, 13584, -1, 13591, 13580, 13592, -1, 13591, 13584, 13590, -1, 13593, 13594, 11559, -1, 13593, 13595, 13594, -1, 13593, 11559, 11558, -1, 13596, 13597, 13595, -1, 13596, 13598, 13597, -1, 13599, 13595, 13593, -1, 13599, 13596, 13595, -1, 13600, 13601, 13598, -1, 13600, 13585, 13601, -1, 13600, 13596, 13599, -1, 13600, 13598, 13596, -1, 13602, 13600, 13599, -1, 13586, 13600, 13602, -1, 13586, 13585, 13600, -1, 13586, 13602, 13587, -1, 13581, 13587, 13603, -1, 13604, 11566, 11567, -1, 13605, 13606, 13607, -1, 13605, 13608, 13606, -1, 13605, 11567, 13608, -1, 13605, 13607, 13580, -1, 13605, 13604, 11567, -1, 13605, 13580, 13604, -1, 13592, 13609, 13584, -1, 13610, 13611, 13609, -1, 13610, 13607, 13611, -1, 13610, 13580, 13607, -1, 13610, 13609, 13592, -1, 13610, 13592, 13580, -1, 13612, 13599, 13593, -1, 13612, 13602, 13599, -1, 13612, 13593, 11558, -1, 13613, 13602, 13612, -1, 13613, 13612, 11558, -1, 13614, 13613, 11558, -1, 13615, 13587, 13602, -1, 13615, 13602, 13613, -1, 13615, 13613, 13614, -1, 13616, 11558, 11566, -1, 13616, 13603, 13587, -1, 13616, 13614, 11558, -1, 13616, 13615, 13614, -1, 13616, 13587, 13615, -1, 13617, 13581, 13603, -1, 13617, 13603, 13616, -1, 13617, 13616, 11566, -1, 13582, 13617, 11566, -1, 13582, 13581, 13617, -1, 13579, 11566, 13604, -1, 13579, 13604, 13580, -1, 13618, 13619, 13620, -1, 13621, 13618, 11635, -1, 13621, 13622, 13618, -1, 13623, 11635, 13624, -1, 13623, 13621, 11635, -1, 13623, 13624, 13625, -1, 13623, 13625, 13622, -1, 13623, 13622, 13621, -1, 13626, 13627, 13628, -1, 13626, 13629, 13630, -1, 13626, 13628, 13629, -1, 13631, 13630, 13622, -1, 13631, 13626, 13630, -1, 13632, 13627, 13626, -1, 13632, 13626, 13631, -1, 13633, 13631, 13622, -1, 13633, 13632, 13631, -1, 13633, 13627, 13632, -1, 13634, 13633, 13622, -1, 13634, 13627, 13633, -1, 13634, 13622, 13625, -1, 13634, 13635, 13627, -1, 13634, 13625, 13635, -1, 13636, 13637, 13638, -1, 13636, 13639, 13637, -1, 13640, 13636, 13638, -1, 13641, 13642, 13639, -1, 13641, 13628, 13642, -1, 13641, 13639, 13636, -1, 13641, 13636, 13640, -1, 13643, 13641, 13640, -1, 13629, 13628, 13641, -1, 13629, 13643, 13630, -1, 13629, 13641, 13643, -1, 13622, 13630, 13619, -1, 13624, 11635, 11636, -1, 13644, 13645, 13646, -1, 13644, 13647, 13645, -1, 13644, 11636, 13647, -1, 13644, 13646, 13625, -1, 13644, 13624, 11636, -1, 13644, 13625, 13624, -1, 13635, 13648, 13627, -1, 13649, 13650, 13648, -1, 13649, 13646, 13650, -1, 13649, 13625, 13646, -1, 13649, 13648, 13635, -1, 13649, 13635, 13625, -1, 13651, 13652, 11630, -1, 13651, 13638, 13652, -1, 13651, 11630, 11629, -1, 13651, 13640, 13638, -1, 13653, 13651, 11629, -1, 13654, 13643, 13640, -1, 13654, 13640, 13651, -1, 13654, 13651, 13653, -1, 13655, 13653, 11629, -1, 13655, 13654, 13653, -1, 13656, 13655, 11629, -1, 13657, 13630, 13643, -1, 13657, 13643, 13654, -1, 13657, 13654, 13655, -1, 13657, 13655, 13656, -1, 13620, 11629, 11635, -1, 13620, 13656, 11629, -1, 13620, 13619, 13630, -1, 13620, 13630, 13657, -1, 13620, 13657, 13656, -1, 13618, 13620, 11635, -1, 13618, 13622, 13619, -1, 13658, 13659, 13660, -1, 13658, 13660, 11623, -1, 13661, 13662, 13663, -1, 13661, 13663, 13664, -1, 13661, 13664, 13665, -1, 13666, 13665, 13659, -1, 13666, 13661, 13665, -1, 13667, 13662, 13661, -1, 13667, 13661, 13666, -1, 13668, 13662, 13667, -1, 13668, 13667, 13666, -1, 13668, 13666, 13659, -1, 13669, 13668, 13659, -1, 13669, 13659, 13670, -1, 13669, 13671, 13662, -1, 13669, 13670, 13671, -1, 13669, 13662, 13668, -1, 13672, 13673, 11632, -1, 13672, 13674, 13673, -1, 13672, 11632, 11628, -1, 13675, 13676, 13674, -1, 13675, 13677, 13676, -1, 13678, 13675, 13674, -1, 13678, 13674, 13672, -1, 13679, 13663, 13680, -1, 13679, 13680, 13677, -1, 13679, 13675, 13678, -1, 13679, 13677, 13675, -1, 13681, 13679, 13678, -1, 13664, 13663, 13679, -1, 13664, 13681, 13665, -1, 13664, 13679, 13681, -1, 13659, 13665, 13682, -1, 13683, 11623, 11624, -1, 13684, 13685, 13686, -1, 13684, 13687, 13685, -1, 13684, 11624, 13687, -1, 13684, 13686, 13670, -1, 13684, 13683, 11624, -1, 13684, 13670, 13683, -1, 13671, 13688, 13662, -1, 13689, 13690, 13688, -1, 13689, 13686, 13690, -1, 13689, 13670, 13686, -1, 13689, 13688, 13671, -1, 13689, 13671, 13670, -1, 13691, 13678, 13672, -1, 13691, 13681, 13678, -1, 13691, 13672, 11628, -1, 13692, 13681, 13691, -1, 13692, 13691, 11628, -1, 13693, 13692, 11628, -1, 13694, 13665, 13681, -1, 13694, 13681, 13692, -1, 13694, 13692, 13693, -1, 13695, 11628, 11623, -1, 13695, 13682, 13665, -1, 13695, 13693, 11628, -1, 13695, 13665, 13694, -1, 13695, 13694, 13693, -1, 13696, 13659, 13682, -1, 13696, 13682, 13695, -1, 13696, 13695, 11623, -1, 13660, 13659, 13696, -1, 13660, 13696, 11623, -1, 13658, 11623, 13683, -1, 13658, 13670, 13659, -1, 13658, 13683, 13670, -1, 13697, 13698, 13699, -1, 13697, 13699, 13700, -1, 13701, 13702, 13703, -1, 13701, 13703, 13704, -1, 13701, 13704, 13705, -1, 13706, 13705, 13699, -1, 13706, 13701, 13705, -1, 13707, 13702, 13701, -1, 13707, 13701, 13706, -1, 13708, 13702, 13707, -1, 13708, 13707, 13706, -1, 13708, 13706, 13699, -1, 13709, 13708, 13699, -1, 13709, 13699, 13698, -1, 13709, 13710, 13702, -1, 13709, 13698, 13710, -1, 13709, 13702, 13708, -1, 13711, 13712, 11586, -1, 13711, 13713, 13712, -1, 13711, 11586, 11585, -1, 13714, 13715, 13713, -1, 13714, 13716, 13715, -1, 13717, 13713, 13711, -1, 13717, 13714, 13713, -1, 13718, 13719, 13716, -1, 13718, 13703, 13719, -1, 13718, 13714, 13717, -1, 13718, 13716, 13714, -1, 13720, 13718, 13717, -1, 13704, 13718, 13720, -1, 13704, 13703, 13718, -1, 13704, 13720, 13705, -1, 13699, 13705, 13721, -1, 13722, 11588, 11597, -1, 13723, 13724, 13725, -1, 13723, 13726, 13724, -1, 13723, 11597, 13726, -1, 13723, 13725, 13698, -1, 13723, 13722, 11597, -1, 13723, 13698, 13722, -1, 13710, 13727, 13702, -1, 13728, 13729, 13727, -1, 13728, 13725, 13729, -1, 13728, 13698, 13725, -1, 13728, 13727, 13710, -1, 13728, 13710, 13698, -1, 13730, 13717, 13711, -1, 13730, 13720, 13717, -1, 13730, 13711, 11585, -1, 13731, 13720, 13730, -1, 13731, 13730, 11585, -1, 13732, 13731, 11585, -1, 13733, 13705, 13720, -1, 13733, 13720, 13731, -1, 13733, 13731, 13732, -1, 13734, 11585, 11588, -1, 13734, 13721, 13705, -1, 13734, 13732, 11585, -1, 13734, 13733, 13732, -1, 13734, 13705, 13733, -1, 13735, 13734, 11588, -1, 13735, 13699, 13721, -1, 13735, 13721, 13734, -1, 13700, 13735, 11588, -1, 13700, 13699, 13735, -1, 13697, 11588, 13722, -1, 13697, 13700, 11588, -1, 13697, 13722, 13698, -1, 13736, 13737, 13738, -1, 13736, 13739, 13740, -1, 13736, 13740, 11619, -1, 13741, 13742, 13743, -1, 13741, 13743, 13744, -1, 13741, 13744, 13745, -1, 13746, 13745, 13739, -1, 13746, 13741, 13745, -1, 13747, 13742, 13741, -1, 13747, 13741, 13746, -1, 13748, 13742, 13747, -1, 13748, 13747, 13746, -1, 13748, 13746, 13739, -1, 13749, 13748, 13739, -1, 13749, 13739, 13738, -1, 13749, 13750, 13742, -1, 13749, 13738, 13750, -1, 13749, 13742, 13748, -1, 13751, 13752, 11617, -1, 13751, 13753, 13752, -1, 13751, 11617, 11616, -1, 13754, 13755, 13753, -1, 13754, 13756, 13755, -1, 13757, 13754, 13753, -1, 13757, 13753, 13751, -1, 13758, 13743, 13759, -1, 13758, 13759, 13756, -1, 13758, 13754, 13757, -1, 13758, 13756, 13754, -1, 13760, 13758, 13757, -1, 13744, 13743, 13758, -1, 13744, 13758, 13760, -1, 13744, 13760, 13745, -1, 13739, 13745, 13761, -1, 13737, 11619, 11621, -1, 13762, 13763, 13764, -1, 13762, 13765, 13763, -1, 13762, 11621, 13765, -1, 13762, 13764, 13738, -1, 13762, 13737, 11621, -1, 13762, 13738, 13737, -1, 13750, 13766, 13742, -1, 13767, 13768, 13766, -1, 13767, 13764, 13768, -1, 13767, 13766, 13750, -1, 13767, 13738, 13764, -1, 13767, 13750, 13738, -1, 13769, 13757, 13751, -1, 13769, 13760, 13757, -1, 13769, 13751, 11616, -1, 13770, 13760, 13769, -1, 13770, 13769, 11616, -1, 13771, 13770, 11616, -1, 13772, 13745, 13760, -1, 13772, 13760, 13770, -1, 13772, 13770, 13771, -1, 13773, 11616, 11619, -1, 13773, 13761, 13745, -1, 13773, 13771, 11616, -1, 13773, 13745, 13772, -1, 13773, 13772, 13771, -1, 13774, 13739, 13761, -1, 13774, 13761, 13773, -1, 13774, 13773, 11619, -1, 13740, 13739, 13774, -1, 13740, 13774, 11619, -1, 13736, 11619, 13737, -1, 13736, 13738, 13739, -1, 13775, 13776, 13777, -1, 13775, 13777, 13778, -1, 13775, 13778, 13779, -1, 13780, 10054, 10067, -1, 13780, 10067, 13781, -1, 13780, 13781, 13782, -1, 13783, 13782, 13778, -1, 13783, 13780, 13782, -1, 13784, 10054, 13780, -1, 13784, 13780, 13783, -1, 13785, 10054, 13784, -1, 13785, 13784, 13783, -1, 13785, 13783, 13778, -1, 13786, 13785, 13778, -1, 13786, 13778, 13777, -1, 13786, 13787, 10054, -1, 13786, 13777, 13787, -1, 13786, 10054, 13785, -1, 13788, 13789, 11292, -1, 13788, 13790, 13789, -1, 13788, 11292, 11291, -1, 13791, 13792, 13790, -1, 13791, 13793, 13792, -1, 13794, 13790, 13788, -1, 13794, 13791, 13790, -1, 13795, 10074, 13793, -1, 13795, 10067, 10074, -1, 13795, 13791, 13794, -1, 13795, 13793, 13791, -1, 13796, 13795, 13794, -1, 13781, 10067, 13795, -1, 13781, 13795, 13796, -1, 13781, 13796, 13782, -1, 13778, 13782, 13797, -1, 13776, 11298, 11308, -1, 13798, 13799, 13800, -1, 13798, 13801, 13799, -1, 13798, 11308, 13801, -1, 13798, 13800, 13777, -1, 13798, 13776, 11308, -1, 13798, 13777, 13776, -1, 13787, 10055, 10054, -1, 13802, 13803, 10055, -1, 13802, 13800, 13803, -1, 13802, 13777, 13800, -1, 13802, 10055, 13787, -1, 13802, 13787, 13777, -1, 13804, 13794, 13788, -1, 13804, 13796, 13794, -1, 13804, 13788, 11291, -1, 13805, 13796, 13804, -1, 13805, 13804, 11291, -1, 13806, 13805, 11291, -1, 13807, 13782, 13796, -1, 13807, 13796, 13805, -1, 13807, 13805, 13806, -1, 13808, 11291, 11298, -1, 13808, 13797, 13782, -1, 13808, 13806, 11291, -1, 13808, 13807, 13806, -1, 13808, 13782, 13807, -1, 13809, 13808, 11298, -1, 13809, 13778, 13797, -1, 13809, 13797, 13808, -1, 13779, 13809, 11298, -1, 13779, 13778, 13809, -1, 13775, 11298, 13776, -1, 13775, 13779, 11298, -1, 13810, 13811, 13812, -1, 13810, 13813, 11329, -1, 13810, 13812, 13813, -1, 13814, 10215, 10224, -1, 13814, 10224, 13815, -1, 13814, 13815, 13816, -1, 13817, 13816, 13812, -1, 13817, 13814, 13816, -1, 13818, 10215, 13814, -1, 13818, 13814, 13817, -1, 13819, 10215, 13818, -1, 13819, 13818, 13817, -1, 13819, 13817, 13812, -1, 13820, 13819, 13812, -1, 13820, 13812, 13811, -1, 13820, 13821, 10215, -1, 13820, 13811, 13821, -1, 13820, 10215, 13819, -1, 13822, 13823, 11321, -1, 13822, 13824, 13823, -1, 13822, 11321, 11320, -1, 13825, 13826, 13824, -1, 13825, 13827, 13826, -1, 13828, 13824, 13822, -1, 13828, 13825, 13824, -1, 13829, 10226, 13827, -1, 13829, 10224, 10226, -1, 13829, 13825, 13828, -1, 13829, 13827, 13825, -1, 13830, 13829, 13828, -1, 13815, 10224, 13829, -1, 13815, 13829, 13830, -1, 13815, 13830, 13816, -1, 13812, 13816, 13831, -1, 13832, 11329, 11334, -1, 13833, 13834, 13835, -1, 13833, 13836, 13834, -1, 13833, 11334, 13836, -1, 13833, 13835, 13811, -1, 13833, 13832, 11334, -1, 13833, 13811, 13832, -1, 13821, 10216, 10215, -1, 13837, 13838, 10216, -1, 13837, 13835, 13838, -1, 13837, 13811, 13835, -1, 13837, 10216, 13821, -1, 13837, 13821, 13811, -1, 13839, 13828, 13822, -1, 13839, 13830, 13828, -1, 13839, 13822, 11320, -1, 13840, 13830, 13839, -1, 13840, 13839, 11320, -1, 13841, 13840, 11320, -1, 13842, 13816, 13830, -1, 13842, 13830, 13840, -1, 13842, 13840, 13841, -1, 13843, 11320, 11329, -1, 13843, 13831, 13816, -1, 13843, 13841, 11320, -1, 13843, 13842, 13841, -1, 13843, 13816, 13842, -1, 13844, 13812, 13831, -1, 13844, 13831, 13843, -1, 13844, 13843, 11329, -1, 13813, 13844, 11329, -1, 13813, 13812, 13844, -1, 13810, 11329, 13832, -1, 13810, 13832, 13811, -1, 13845, 13846, 13847, -1, 13845, 13847, 13848, -1, 13849, 10370, 10383, -1, 13849, 10383, 13850, -1, 13849, 13850, 13851, -1, 13852, 13851, 13847, -1, 13852, 13849, 13851, -1, 13853, 10370, 13849, -1, 13853, 13849, 13852, -1, 13854, 10370, 13853, -1, 13854, 13853, 13852, -1, 13854, 13852, 13847, -1, 13855, 13854, 13847, -1, 13855, 13847, 13846, -1, 13855, 13856, 10370, -1, 13855, 13846, 13856, -1, 13855, 10370, 13854, -1, 13857, 13858, 11654, -1, 13857, 13859, 13858, -1, 13857, 11654, 11653, -1, 13860, 13861, 13859, -1, 13860, 13862, 13861, -1, 13863, 13859, 13857, -1, 13863, 13860, 13859, -1, 13864, 10390, 13862, -1, 13864, 10383, 10390, -1, 13864, 13860, 13863, -1, 13864, 13862, 13860, -1, 13865, 13864, 13863, -1, 13850, 13864, 13865, -1, 13850, 10383, 13864, -1, 13850, 13865, 13851, -1, 13847, 13851, 13866, -1, 13867, 11657, 11659, -1, 13868, 13869, 13870, -1, 13868, 13871, 13869, -1, 13868, 11659, 13871, -1, 13868, 13870, 13846, -1, 13868, 13867, 11659, -1, 13868, 13846, 13867, -1, 13856, 10371, 10370, -1, 13872, 13873, 10371, -1, 13872, 13870, 13873, -1, 13872, 13846, 13870, -1, 13872, 10371, 13856, -1, 13872, 13856, 13846, -1, 13874, 13863, 13857, -1, 13874, 13865, 13863, -1, 13874, 13857, 11653, -1, 13875, 13865, 13874, -1, 13875, 13874, 11653, -1, 13876, 13875, 11653, -1, 13877, 13851, 13865, -1, 13877, 13865, 13875, -1, 13877, 13875, 13876, -1, 13878, 11653, 11657, -1, 13878, 13866, 13851, -1, 13878, 13876, 11653, -1, 13878, 13877, 13876, -1, 13878, 13851, 13877, -1, 13879, 13878, 11657, -1, 13879, 13847, 13866, -1, 13879, 13866, 13878, -1, 13848, 13879, 11657, -1, 13848, 13847, 13879, -1, 13845, 11657, 13867, -1, 13845, 13848, 11657, -1, 13845, 13867, 13846, -1, 13880, 13881, 13882, -1, 13880, 13883, 13884, -1, 13880, 13884, 11282, -1, 13885, 10391, 10400, -1, 13885, 10400, 13886, -1, 13885, 13886, 13887, -1, 13888, 13887, 13883, -1, 13888, 13885, 13887, -1, 13889, 10391, 13885, -1, 13889, 13885, 13888, -1, 13890, 10391, 13889, -1, 13890, 13889, 13888, -1, 13890, 13888, 13883, -1, 13891, 13890, 13883, -1, 13891, 13883, 13882, -1, 13891, 13892, 10391, -1, 13891, 13882, 13892, -1, 13891, 10391, 13890, -1, 13893, 13894, 11666, -1, 13893, 13895, 13894, -1, 13893, 11666, 11665, -1, 13896, 13897, 13895, -1, 13896, 13898, 13897, -1, 13899, 13896, 13895, -1, 13899, 13895, 13893, -1, 13900, 10400, 10402, -1, 13900, 10402, 13898, -1, 13900, 13896, 13899, -1, 13900, 13898, 13896, -1, 13901, 13900, 13899, -1, 13886, 10400, 13900, -1, 13886, 13900, 13901, -1, 13886, 13901, 13887, -1, 13883, 13887, 13902, -1, 13881, 11282, 11284, -1, 13903, 13904, 13905, -1, 13903, 13906, 13904, -1, 13903, 11284, 13906, -1, 13903, 13905, 13882, -1, 13903, 13881, 11284, -1, 13903, 13882, 13881, -1, 13892, 10392, 10391, -1, 13907, 13908, 10392, -1, 13907, 13905, 13908, -1, 13907, 13882, 13905, -1, 13907, 10392, 13892, -1, 13907, 13892, 13882, -1, 13909, 13899, 13893, -1, 13909, 13901, 13899, -1, 13909, 13893, 11665, -1, 13910, 13901, 13909, -1, 13910, 13909, 11665, -1, 13911, 13910, 11665, -1, 13912, 13887, 13901, -1, 13912, 13901, 13910, -1, 13912, 13910, 13911, -1, 13913, 11665, 11282, -1, 13913, 13902, 13887, -1, 13913, 13911, 11665, -1, 13913, 13887, 13912, -1, 13913, 13912, 13911, -1, 13914, 13883, 13902, -1, 13914, 13902, 13913, -1, 13914, 13913, 11282, -1, 13884, 13883, 13914, -1, 13884, 13914, 11282, -1, 13880, 11282, 13881, -1, 13880, 13882, 13883, -1, 13915, 13916, 13917, -1, 13915, 13918, 13919, -1, 13915, 13919, 11443, -1, 13920, 10499, 10508, -1, 13920, 10508, 13921, -1, 13920, 13921, 13922, -1, 13923, 13922, 13918, -1, 13923, 13920, 13922, -1, 13924, 10499, 13920, -1, 13924, 13920, 13923, -1, 13925, 10499, 13924, -1, 13925, 13924, 13923, -1, 13925, 13923, 13918, -1, 13926, 13925, 13918, -1, 13926, 13918, 13917, -1, 13926, 13927, 10499, -1, 13926, 13917, 13927, -1, 13926, 10499, 13925, -1, 13928, 13929, 11436, -1, 13928, 13930, 13929, -1, 13928, 11436, 11435, -1, 13931, 13932, 13930, -1, 13931, 13933, 13932, -1, 13934, 13931, 13930, -1, 13934, 13930, 13928, -1, 13935, 10508, 10510, -1, 13935, 10510, 13933, -1, 13935, 13931, 13934, -1, 13935, 13933, 13931, -1, 13936, 13935, 13934, -1, 13921, 10508, 13935, -1, 13921, 13935, 13936, -1, 13921, 13936, 13922, -1, 13918, 13922, 13937, -1, 13916, 11443, 11449, -1, 13938, 13939, 13940, -1, 13938, 13941, 13939, -1, 13938, 11449, 13941, -1, 13938, 13940, 13917, -1, 13938, 13916, 11449, -1, 13938, 13917, 13916, -1, 13927, 10500, 10499, -1, 13942, 13943, 10500, -1, 13942, 13940, 13943, -1, 13942, 10500, 13927, -1, 13942, 13917, 13940, -1, 13942, 13927, 13917, -1, 13944, 13934, 13928, -1, 13944, 13936, 13934, -1, 13944, 13928, 11435, -1, 13945, 13936, 13944, -1, 13945, 13944, 11435, -1, 13946, 13945, 11435, -1, 13947, 13922, 13936, -1, 13947, 13936, 13945, -1, 13947, 13945, 13946, -1, 13948, 11435, 11443, -1, 13948, 13937, 13922, -1, 13948, 13946, 11435, -1, 13948, 13922, 13947, -1, 13948, 13947, 13946, -1, 13949, 13918, 13937, -1, 13949, 13937, 13948, -1, 13949, 13948, 11443, -1, 13919, 13918, 13949, -1, 13919, 13949, 11443, -1, 13915, 11443, 13916, -1, 13915, 13917, 13918, -1, 13950, 13951, 11410, -1, 13950, 13952, 13951, -1, 13953, 10702, 10715, -1, 13953, 10715, 13954, -1, 13953, 13954, 13955, -1, 13956, 13955, 13952, -1, 13956, 13953, 13955, -1, 13957, 10702, 13953, -1, 13957, 13953, 13956, -1, 13958, 10702, 13957, -1, 13958, 13957, 13956, -1, 13958, 13956, 13952, -1, 13959, 13958, 13952, -1, 13959, 13952, 13960, -1, 13959, 13961, 10702, -1, 13959, 13960, 13961, -1, 13959, 10702, 13958, -1, 13962, 13963, 11406, -1, 13962, 13964, 13963, -1, 13962, 11406, 11405, -1, 13965, 13966, 13964, -1, 13965, 13967, 13966, -1, 13968, 13965, 13964, -1, 13968, 13964, 13962, -1, 13969, 10715, 10722, -1, 13969, 10722, 13967, -1, 13969, 13965, 13968, -1, 13969, 13967, 13965, -1, 13970, 13969, 13968, -1, 13954, 10715, 13969, -1, 13954, 13969, 13970, -1, 13954, 13970, 13955, -1, 13952, 13955, 13971, -1, 13972, 11410, 11416, -1, 13973, 13974, 13975, -1, 13973, 13976, 13974, -1, 13973, 11416, 13976, -1, 13973, 13975, 13960, -1, 13973, 13972, 11416, -1, 13973, 13960, 13972, -1, 13961, 10703, 10702, -1, 13977, 13978, 10703, -1, 13977, 13975, 13978, -1, 13977, 10703, 13961, -1, 13977, 13960, 13975, -1, 13977, 13961, 13960, -1, 13979, 13968, 13962, -1, 13979, 13970, 13968, -1, 13979, 13962, 11405, -1, 13980, 13970, 13979, -1, 13980, 13979, 11405, -1, 13981, 13980, 11405, -1, 13982, 13955, 13970, -1, 13982, 13970, 13980, -1, 13982, 13980, 13981, -1, 13983, 11405, 11410, -1, 13983, 13971, 13955, -1, 13983, 13981, 11405, -1, 13983, 13955, 13982, -1, 13983, 13982, 13981, -1, 13984, 13983, 11410, -1, 13984, 13952, 13971, -1, 13984, 13971, 13983, -1, 13951, 13984, 11410, -1, 13951, 13952, 13984, -1, 13950, 11410, 13972, -1, 13950, 13960, 13952, -1, 13950, 13972, 13960, -1, 13985, 13986, 13987, -1, 13985, 13988, 11357, -1, 13985, 13987, 13988, -1, 13989, 10784, 10797, -1, 13989, 10797, 13990, -1, 13989, 13990, 13991, -1, 13992, 13991, 13987, -1, 13992, 13989, 13991, -1, 13993, 10784, 13989, -1, 13993, 13989, 13992, -1, 13994, 10784, 13993, -1, 13994, 13993, 13992, -1, 13994, 13992, 13987, -1, 13995, 13994, 13987, -1, 13995, 13987, 13986, -1, 13995, 13996, 10784, -1, 13995, 13986, 13996, -1, 13995, 10784, 13994, -1, 13997, 13998, 11351, -1, 13997, 13999, 13998, -1, 13997, 11351, 11350, -1, 14000, 14001, 13999, -1, 14000, 14002, 14001, -1, 14003, 13999, 13997, -1, 14003, 14000, 13999, -1, 14004, 10804, 14002, -1, 14004, 10797, 10804, -1, 14004, 14000, 14003, -1, 14004, 14002, 14000, -1, 14005, 14004, 14003, -1, 13990, 14004, 14005, -1, 13990, 10797, 14004, -1, 13990, 14005, 13991, -1, 13987, 13991, 14006, -1, 14007, 11357, 11365, -1, 14008, 14009, 14010, -1, 14008, 14011, 14009, -1, 14008, 11365, 14011, -1, 14008, 14010, 13986, -1, 14008, 14007, 11365, -1, 14008, 13986, 14007, -1, 13996, 10785, 10784, -1, 14012, 14013, 10785, -1, 14012, 14010, 14013, -1, 14012, 13986, 14010, -1, 14012, 10785, 13996, -1, 14012, 13996, 13986, -1, 14014, 14003, 13997, -1, 14014, 14005, 14003, -1, 14014, 13997, 11350, -1, 14015, 14005, 14014, -1, 14015, 14014, 11350, -1, 14016, 14015, 11350, -1, 14017, 13991, 14005, -1, 14017, 14005, 14015, -1, 14017, 14015, 14016, -1, 14018, 11350, 11357, -1, 14018, 14006, 13991, -1, 14018, 14016, 11350, -1, 14018, 14017, 14016, -1, 14018, 13991, 14017, -1, 14019, 13987, 14006, -1, 14019, 14006, 14018, -1, 14019, 14018, 11357, -1, 13988, 14019, 11357, -1, 13988, 13987, 14019, -1, 13985, 11357, 14007, -1, 13985, 14007, 13986, -1, 14020, 14021, 11383, -1, 14020, 14022, 14021, -1, 14023, 10935, 10944, -1, 14023, 10944, 14024, -1, 14023, 14024, 14025, -1, 14026, 14025, 14022, -1, 14026, 14023, 14025, -1, 14027, 10935, 14023, -1, 14027, 14023, 14026, -1, 14028, 10935, 14027, -1, 14028, 14027, 14026, -1, 14028, 14026, 14022, -1, 14029, 14028, 14022, -1, 14029, 14022, 14030, -1, 14029, 14031, 10935, -1, 14029, 14030, 14031, -1, 14029, 10935, 14028, -1, 14032, 14033, 11381, -1, 14032, 14034, 14033, -1, 14032, 11381, 11380, -1, 14035, 14036, 14034, -1, 14035, 14037, 14036, -1, 14038, 14035, 14034, -1, 14038, 14034, 14032, -1, 14039, 10944, 10946, -1, 14039, 10946, 14037, -1, 14039, 14035, 14038, -1, 14039, 14037, 14035, -1, 14040, 14039, 14038, -1, 14024, 10944, 14039, -1, 14024, 14039, 14040, -1, 14024, 14040, 14025, -1, 14022, 14025, 14041, -1, 14042, 11383, 11391, -1, 14043, 14044, 14045, -1, 14043, 14046, 14044, -1, 14043, 11391, 14046, -1, 14043, 14045, 14030, -1, 14043, 14042, 11391, -1, 14043, 14030, 14042, -1, 14031, 10936, 10935, -1, 14047, 14048, 10936, -1, 14047, 14045, 14048, -1, 14047, 10936, 14031, -1, 14047, 14030, 14045, -1, 14047, 14031, 14030, -1, 14049, 14038, 14032, -1, 14049, 14040, 14038, -1, 14049, 14032, 11380, -1, 14050, 14040, 14049, -1, 14050, 14049, 11380, -1, 14051, 14050, 11380, -1, 14052, 14025, 14040, -1, 14052, 14040, 14050, -1, 14052, 14050, 14051, -1, 14053, 11380, 11383, -1, 14053, 14041, 14025, -1, 14053, 14051, 11380, -1, 14053, 14025, 14052, -1, 14053, 14052, 14051, -1, 14054, 14053, 11383, -1, 14054, 14022, 14041, -1, 14054, 14041, 14053, -1, 14021, 14054, 11383, -1, 14021, 14022, 14054, -1, 14020, 11383, 14042, -1, 14020, 14030, 14022, -1, 14020, 14042, 14030, -1, 14055, 14056, 14057, -1, 14055, 14058, 14059, -1, 14055, 14059, 11401, -1, 14060, 14061, 14062, -1, 14060, 14062, 14063, -1, 14060, 14063, 14064, -1, 14065, 14064, 14058, -1, 14065, 14060, 14064, -1, 14066, 14061, 14060, -1, 14066, 14060, 14065, -1, 14067, 14061, 14066, -1, 14067, 14066, 14065, -1, 14067, 14065, 14058, -1, 14068, 14067, 14058, -1, 14068, 14058, 14057, -1, 14068, 14069, 14061, -1, 14068, 14057, 14069, -1, 14068, 14061, 14067, -1, 14070, 14071, 11409, -1, 14070, 14072, 14071, -1, 14070, 11409, 11404, -1, 14073, 14074, 14072, -1, 14073, 14075, 14074, -1, 14076, 14073, 14072, -1, 14076, 14072, 14070, -1, 14077, 14062, 14078, -1, 14077, 14078, 14075, -1, 14077, 14073, 14076, -1, 14077, 14075, 14073, -1, 14079, 14077, 14076, -1, 14063, 14062, 14077, -1, 14063, 14077, 14079, -1, 14063, 14079, 14064, -1, 14058, 14064, 14080, -1, 14056, 11401, 11400, -1, 14081, 14082, 14083, -1, 14081, 14084, 14082, -1, 14081, 11400, 14084, -1, 14081, 14083, 14057, -1, 14081, 14056, 11400, -1, 14081, 14057, 14056, -1, 14069, 14085, 14061, -1, 14086, 14087, 14085, -1, 14086, 14083, 14087, -1, 14086, 14085, 14069, -1, 14086, 14057, 14083, -1, 14086, 14069, 14057, -1, 14088, 14076, 14070, -1, 14088, 14079, 14076, -1, 14088, 14070, 11404, -1, 14089, 14079, 14088, -1, 14089, 14088, 11404, -1, 14090, 14089, 11404, -1, 14091, 14064, 14079, -1, 14091, 14079, 14089, -1, 14091, 14089, 14090, -1, 14092, 11404, 11401, -1, 14092, 14080, 14064, -1, 14092, 14090, 11404, -1, 14092, 14064, 14091, -1, 14092, 14091, 14090, -1, 14093, 14058, 14080, -1, 14093, 14080, 14092, -1, 14093, 14092, 11401, -1, 14059, 14058, 14093, -1, 14059, 14093, 11401, -1, 14055, 11401, 14056, -1, 14055, 14057, 14058, -1, 14094, 14095, 14096, -1, 14097, 14098, 14099, -1, 14100, 14101, 14102, -1, 14100, 14102, 14094, -1, 14100, 14096, 14103, -1, 14100, 14094, 14096, -1, 14104, 14105, 14099, -1, 14104, 14098, 14101, -1, 14104, 14103, 14105, -1, 14104, 14100, 14103, -1, 14104, 14101, 14100, -1, 14104, 14099, 14098, -1, 14106, 14107, 14108, -1, 14109, 14110, 14111, -1, 14112, 14113, 14114, -1, 14112, 14114, 14107, -1, 14112, 14106, 14115, -1, 14112, 14107, 14106, -1, 14116, 14117, 14113, -1, 14116, 14113, 14112, -1, 14118, 14115, 14119, -1, 14118, 14119, 14120, -1, 14118, 14112, 14115, -1, 14121, 14122, 14109, -1, 14121, 14111, 14117, -1, 14121, 14117, 14116, -1, 14121, 14109, 14111, -1, 14123, 14124, 14125, -1, 14123, 14120, 14126, -1, 14123, 14126, 14124, -1, 14123, 14118, 14120, -1, 14123, 14112, 14118, -1, 14123, 14116, 14112, -1, 14127, 14125, 14128, -1, 14127, 14128, 14129, -1, 14127, 14129, 14122, -1, 14127, 14116, 14123, -1, 14127, 14123, 14125, -1, 14127, 14122, 14121, -1, 14127, 14121, 14116, -1, 14130, 14131, 14132, -1, 14133, 14134, 14135, -1, 14136, 14137, 14138, -1, 14136, 14138, 14130, -1, 14136, 14132, 14139, -1, 14136, 14130, 14132, -1, 14140, 14141, 14135, -1, 14140, 14134, 14137, -1, 14140, 14139, 14141, -1, 14140, 14136, 14139, -1, 14140, 14137, 14136, -1, 14140, 14135, 14134, -1, 14142, 14143, 14144, -1, 14145, 14146, 14147, -1, 14148, 14149, 14150, -1, 14148, 14150, 14143, -1, 14148, 14142, 14151, -1, 14148, 14143, 14142, -1, 14152, 14153, 14149, -1, 14152, 14149, 14148, -1, 14154, 14151, 14155, -1, 14154, 14155, 14156, -1, 14154, 14148, 14151, -1, 14157, 14158, 14145, -1, 14157, 14147, 14153, -1, 14157, 14153, 14152, -1, 14157, 14145, 14147, -1, 14159, 14160, 14161, -1, 14159, 14156, 14162, -1, 14159, 14162, 14160, -1, 14159, 14154, 14156, -1, 14159, 14148, 14154, -1, 14159, 14152, 14148, -1, 14163, 14161, 14164, -1, 14163, 14164, 14165, -1, 14163, 14165, 14158, -1, 14163, 14152, 14159, -1, 14163, 14159, 14161, -1, 14163, 14158, 14157, -1, 14163, 14157, 14152, -1, 14166, 14167, 14168, -1, 14169, 14170, 14171, -1, 14172, 14173, 14174, -1, 14172, 14174, 14166, -1, 14172, 14168, 14175, -1, 14172, 14166, 14168, -1, 14176, 14177, 14171, -1, 14176, 14170, 14173, -1, 14176, 14175, 14177, -1, 14176, 14172, 14175, -1, 14176, 14173, 14172, -1, 14176, 14171, 14170, -1, 14178, 14179, 14180, -1, 14181, 14182, 14183, -1, 14184, 14185, 14186, -1, 14184, 14186, 14179, -1, 14184, 14178, 14187, -1, 14184, 14179, 14178, -1, 14188, 14189, 14185, -1, 14188, 14185, 14184, -1, 14190, 14187, 14191, -1, 14190, 14191, 14192, -1, 14190, 14184, 14187, -1, 14193, 14194, 14181, -1, 14193, 14183, 14189, -1, 14193, 14189, 14188, -1, 14193, 14181, 14183, -1, 14195, 14196, 14197, -1, 14195, 14192, 14198, -1, 14195, 14198, 14196, -1, 14195, 14190, 14192, -1, 14195, 14184, 14190, -1, 14195, 14188, 14184, -1, 14199, 14197, 14200, -1, 14199, 14200, 14201, -1, 14199, 14201, 14194, -1, 14199, 14188, 14195, -1, 14199, 14195, 14197, -1, 14199, 14194, 14193, -1, 14199, 14193, 14188, -1, 14202, 14203, 14204, -1, 14205, 14206, 14207, -1, 14208, 14209, 14210, -1, 14208, 14210, 14202, -1, 14208, 14204, 14211, -1, 14208, 14202, 14204, -1, 14212, 14213, 14207, -1, 14212, 14206, 14209, -1, 14212, 14211, 14213, -1, 14212, 14208, 14211, -1, 14212, 14209, 14208, -1, 14212, 14207, 14206, -1, 14214, 14215, 14216, -1, 14217, 14218, 14219, -1, 14220, 14221, 14222, -1, 14220, 14222, 14215, -1, 14220, 14214, 14223, -1, 14220, 14215, 14214, -1, 14224, 14225, 14221, -1, 14224, 14221, 14220, -1, 14226, 14223, 14227, -1, 14226, 14227, 14228, -1, 14226, 14220, 14223, -1, 14229, 14230, 14217, -1, 14229, 14219, 14225, -1, 14229, 14225, 14224, -1, 14229, 14217, 14219, -1, 14231, 14232, 14233, -1, 14231, 14228, 14234, -1, 14231, 14234, 14232, -1, 14231, 14226, 14228, -1, 14231, 14220, 14226, -1, 14231, 14224, 14220, -1, 14235, 14233, 14236, -1, 14235, 14236, 14237, -1, 14235, 14237, 14230, -1, 14235, 14224, 14231, -1, 14235, 14231, 14233, -1, 14235, 14230, 14229, -1, 14235, 14229, 14224, -1, 14238, 14239, 14240, -1, 14241, 14242, 14243, -1, 14244, 14245, 14246, -1, 14244, 14246, 14239, -1, 14244, 14238, 14247, -1, 14244, 14239, 14238, -1, 14248, 14249, 14245, -1, 14248, 14245, 14244, -1, 14250, 14247, 14251, -1, 14250, 14251, 14252, -1, 14250, 14244, 14247, -1, 14253, 14254, 14241, -1, 14253, 14243, 14249, -1, 14253, 14249, 14248, -1, 14253, 14241, 14243, -1, 14255, 14256, 14257, -1, 14255, 14252, 14258, -1, 14255, 14258, 14256, -1, 14255, 14250, 14252, -1, 14255, 14244, 14250, -1, 14255, 14248, 14244, -1, 14259, 14257, 14260, -1, 14259, 14260, 14261, -1, 14259, 14261, 14254, -1, 14259, 14248, 14255, -1, 14259, 14255, 14257, -1, 14259, 14254, 14253, -1, 14259, 14253, 14248, -1, 14262, 14263, 14264, -1, 14265, 14266, 14267, -1, 14268, 14269, 14270, -1, 14268, 14270, 14262, -1, 14268, 14264, 14271, -1, 14268, 14262, 14264, -1, 14272, 14273, 14267, -1, 14272, 14266, 14269, -1, 14272, 14271, 14273, -1, 14272, 14268, 14271, -1, 14272, 14269, 14268, -1, 14272, 14267, 14266, -1, 14274, 14275, 14276, -1, 14277, 14278, 14279, -1, 14280, 14281, 14282, -1, 14280, 14282, 14275, -1, 14280, 14274, 14283, -1, 14280, 14275, 14274, -1, 14284, 14285, 14281, -1, 14284, 14281, 14280, -1, 14286, 14283, 14287, -1, 14286, 14287, 14288, -1, 14286, 14280, 14283, -1, 14289, 14290, 14277, -1, 14289, 14279, 14285, -1, 14289, 14285, 14284, -1, 14289, 14277, 14279, -1, 14291, 14292, 14293, -1, 14291, 14288, 14294, -1, 14291, 14294, 14292, -1, 14291, 14286, 14288, -1, 14291, 14280, 14286, -1, 14291, 14284, 14280, -1, 14295, 14293, 14296, -1, 14295, 14296, 14297, -1, 14295, 14297, 14290, -1, 14295, 14284, 14291, -1, 14295, 14291, 14293, -1, 14295, 14290, 14289, -1, 14295, 14289, 14284, -1, 14298, 14299, 14300, -1, 14301, 14302, 14303, -1, 14304, 14305, 14306, -1, 14304, 14306, 14298, -1, 14304, 14300, 14307, -1, 14304, 14298, 14300, -1, 14308, 14309, 14303, -1, 14308, 14302, 14305, -1, 14308, 14307, 14309, -1, 14308, 14304, 14307, -1, 14308, 14305, 14304, -1, 14308, 14303, 14302, -1, 14310, 14311, 14312, -1, 14313, 14314, 14315, -1, 14316, 14317, 14318, -1, 14316, 14318, 14311, -1, 14316, 14310, 14319, -1, 14316, 14311, 14310, -1, 14320, 14321, 14317, -1, 14320, 14317, 14316, -1, 14322, 14319, 14323, -1, 14322, 14323, 14324, -1, 14322, 14316, 14319, -1, 14325, 14326, 14313, -1, 14325, 14315, 14321, -1, 14325, 14321, 14320, -1, 14325, 14313, 14315, -1, 14327, 14328, 14329, -1, 14327, 14324, 14330, -1, 14327, 14330, 14328, -1, 14327, 14322, 14324, -1, 14327, 14316, 14322, -1, 14327, 14320, 14316, -1, 14331, 14329, 14332, -1, 14331, 14332, 14333, -1, 14331, 14333, 14326, -1, 14331, 14320, 14327, -1, 14331, 14327, 14329, -1, 14331, 14326, 14325, -1, 14331, 14325, 14320, -1, 14334, 14335, 14336, -1, 14337, 14338, 14339, -1, 14340, 14341, 14342, -1, 14340, 14342, 14334, -1, 14340, 14336, 14343, -1, 14340, 14334, 14336, -1, 14344, 14345, 14339, -1, 14344, 14338, 14341, -1, 14344, 14343, 14345, -1, 14344, 14340, 14343, -1, 14344, 14341, 14340, -1, 14344, 14339, 14338, -1, 14346, 14347, 14348, -1, 14349, 14350, 14351, -1, 14352, 14353, 14354, -1, 14352, 14354, 14346, -1, 14352, 14348, 14355, -1, 14352, 14346, 14348, -1, 14356, 14357, 14351, -1, 14356, 14350, 14353, -1, 14356, 14355, 14357, -1, 14356, 14352, 14355, -1, 14356, 14353, 14352, -1, 14356, 14351, 14350, -1, 14358, 14359, 14360, -1, 14361, 14362, 14363, -1, 14364, 14365, 14366, -1, 14364, 14366, 14359, -1, 14364, 14358, 14367, -1, 14364, 14359, 14358, -1, 14368, 14369, 14365, -1, 14368, 14365, 14364, -1, 14370, 14367, 14371, -1, 14370, 14371, 14372, -1, 14370, 14364, 14367, -1, 14373, 14374, 14361, -1, 14373, 14363, 14369, -1, 14373, 14369, 14368, -1, 14373, 14361, 14363, -1, 14375, 14376, 14377, -1, 14375, 14372, 14378, -1, 14375, 14378, 14376, -1, 14375, 14370, 14372, -1, 14375, 14364, 14370, -1, 14375, 14368, 14364, -1, 14379, 14377, 14380, -1, 14379, 14380, 14381, -1, 14379, 14381, 14374, -1, 14379, 14368, 14375, -1, 14379, 14375, 14377, -1, 14379, 14374, 14373, -1, 14379, 14373, 14368, -1, 12624, 12649, 14382, -1, 14383, 14384, 14385, -1, 14386, 14382, 14387, -1, 14386, 14387, 14388, -1, 14386, 12625, 12624, -1, 14386, 12624, 14382, -1, 14389, 14388, 14384, -1, 14389, 14383, 12641, -1, 14389, 12641, 12625, -1, 14389, 14386, 14388, -1, 14389, 14384, 14383, -1, 14389, 12625, 14386, -1, 14390, 14391, 14392, -1, 12662, 12688, 14393, -1, 14394, 14395, 14396, -1, 14394, 14396, 14391, -1, 14394, 14390, 14397, -1, 14394, 14391, 14390, -1, 14398, 14399, 14395, -1, 14398, 14395, 14394, -1, 14400, 14397, 14401, -1, 14400, 14401, 14402, -1, 14400, 14394, 14397, -1, 14403, 12663, 12662, -1, 14403, 14393, 14399, -1, 14403, 14399, 14398, -1, 14403, 12662, 14393, -1, 14404, 14402, 14405, -1, 14404, 14405, 14406, -1, 14404, 14406, 14407, -1, 14404, 14400, 14402, -1, 14404, 14394, 14400, -1, 14404, 14398, 14394, -1, 14408, 14407, 14409, -1, 14408, 14409, 12680, -1, 14408, 12680, 12663, -1, 14408, 12663, 14403, -1, 14408, 14404, 14407, -1, 14408, 14403, 14398, -1, 14408, 14398, 14404, -1, 12703, 12727, 14410, -1, 14411, 14412, 14413, -1, 14414, 14410, 14415, -1, 14414, 14415, 14416, -1, 14414, 12704, 12703, -1, 14414, 12703, 14410, -1, 14417, 14416, 14412, -1, 14417, 14411, 12720, -1, 14417, 12720, 12704, -1, 14417, 14414, 14416, -1, 14417, 14412, 14411, -1, 14417, 12704, 14414, -1, 14418, 14419, 14420, -1, 12742, 12766, 14421, -1, 14422, 14423, 14424, -1, 14422, 14424, 14419, -1, 14422, 14418, 14425, -1, 14422, 14419, 14418, -1, 14426, 14427, 14423, -1, 14426, 14423, 14422, -1, 14428, 14425, 14429, -1, 14428, 14429, 14430, -1, 14428, 14422, 14425, -1, 14431, 12743, 12742, -1, 14431, 14421, 14427, -1, 14431, 14427, 14426, -1, 14431, 12742, 14421, -1, 14432, 14430, 14433, -1, 14432, 14433, 14434, -1, 14432, 14434, 14435, -1, 14432, 14428, 14430, -1, 14432, 14422, 14428, -1, 14432, 14426, 14422, -1, 14436, 14435, 14437, -1, 14436, 14437, 12759, -1, 14436, 12759, 12743, -1, 14436, 12743, 14431, -1, 14436, 14432, 14435, -1, 14436, 14431, 14426, -1, 14436, 14426, 14432, -1, 14438, 14439, 14440, -1, 12780, 12805, 14441, -1, 14442, 14443, 14444, -1, 14442, 14444, 14439, -1, 14442, 14438, 14445, -1, 14442, 14439, 14438, -1, 14446, 14447, 14443, -1, 14446, 14443, 14442, -1, 14448, 14445, 14449, -1, 14448, 14449, 14450, -1, 14448, 14442, 14445, -1, 14451, 12781, 12780, -1, 14451, 14441, 14447, -1, 14451, 14447, 14446, -1, 14451, 12780, 14441, -1, 14452, 14450, 14453, -1, 14452, 14453, 14454, -1, 14452, 14454, 14455, -1, 14452, 14448, 14450, -1, 14452, 14442, 14448, -1, 14452, 14446, 14442, -1, 14456, 14455, 14457, -1, 14456, 14457, 12797, -1, 14456, 12797, 12781, -1, 14456, 12781, 14451, -1, 14456, 14452, 14455, -1, 14456, 14451, 14446, -1, 14456, 14446, 14452, -1, 12819, 12844, 14458, -1, 14459, 14460, 14461, -1, 14462, 14458, 14463, -1, 14462, 14463, 14464, -1, 14462, 12820, 12819, -1, 14462, 12819, 14458, -1, 14465, 14464, 14460, -1, 14465, 14459, 12836, -1, 14465, 12836, 12820, -1, 14465, 14462, 14464, -1, 14465, 12820, 14462, -1, 14465, 14460, 14459, -1, 12857, 12883, 14466, -1, 14467, 14468, 14469, -1, 14470, 14466, 14471, -1, 14470, 14471, 14472, -1, 14470, 12858, 12857, -1, 14470, 12857, 14466, -1, 14473, 14472, 14468, -1, 14473, 14467, 12875, -1, 14473, 12875, 12858, -1, 14473, 14470, 14472, -1, 14473, 14468, 14467, -1, 14473, 12858, 14470, -1, 14474, 14475, 14476, -1, 12898, 12922, 14477, -1, 14478, 14479, 14480, -1, 14478, 14480, 14475, -1, 14478, 14474, 14481, -1, 14478, 14475, 14474, -1, 14482, 14483, 14479, -1, 14482, 14479, 14478, -1, 14484, 14481, 14485, -1, 14484, 14485, 14486, -1, 14484, 14478, 14481, -1, 14487, 12899, 12898, -1, 14487, 14477, 14483, -1, 14487, 14483, 14482, -1, 14487, 12898, 14477, -1, 14488, 14486, 14489, -1, 14488, 14489, 14490, -1, 14488, 14490, 14491, -1, 14488, 14484, 14486, -1, 14488, 14478, 14484, -1, 14488, 14482, 14478, -1, 14492, 14491, 14493, -1, 14492, 14493, 12915, -1, 14492, 12915, 12899, -1, 14492, 12899, 14487, -1, 14492, 14488, 14491, -1, 14492, 14487, 14482, -1, 14492, 14482, 14488, -1, 14494, 14495, 14496, -1, 14497, 14498, 14499, -1, 14500, 14501, 14502, -1, 14500, 14502, 14494, -1, 14500, 14496, 14503, -1, 14500, 14494, 14496, -1, 14504, 14505, 14499, -1, 14504, 14498, 14501, -1, 14504, 14503, 14505, -1, 14504, 14500, 14503, -1, 14504, 14501, 14500, -1, 14504, 14499, 14498, -1, 14506, 14507, 14508, -1, 12970, 12996, 14509, -1, 14510, 14511, 14512, -1, 14510, 14512, 14507, -1, 14510, 14506, 14513, -1, 14510, 14507, 14506, -1, 14514, 14515, 14511, -1, 14514, 14511, 14510, -1, 14516, 14513, 14517, -1, 14516, 14517, 14518, -1, 14516, 14510, 14513, -1, 14519, 12971, 12970, -1, 14519, 14509, 14515, -1, 14519, 14515, 14514, -1, 14519, 12970, 14509, -1, 14520, 14518, 14521, -1, 14520, 14521, 14522, -1, 14520, 14522, 14523, -1, 14520, 14516, 14518, -1, 14520, 14510, 14516, -1, 14520, 14514, 14510, -1, 14524, 14523, 14525, -1, 14524, 14525, 12988, -1, 14524, 12988, 12971, -1, 14524, 12971, 14519, -1, 14524, 14520, 14523, -1, 14524, 14519, 14514, -1, 14524, 14514, 14520, -1, 14526, 14527, 14528, -1, 13010, 13035, 14529, -1, 14530, 14531, 14532, -1, 14530, 14532, 14527, -1, 14530, 14526, 14533, -1, 14530, 14527, 14526, -1, 14534, 14535, 14531, -1, 14534, 14531, 14530, -1, 14536, 14533, 14537, -1, 14536, 14537, 14538, -1, 14536, 14530, 14533, -1, 14539, 13011, 13010, -1, 14539, 14529, 14535, -1, 14539, 14535, 14534, -1, 14539, 13010, 14529, -1, 14540, 14538, 14541, -1, 14540, 14541, 14542, -1, 14540, 14542, 14543, -1, 14540, 14536, 14538, -1, 14540, 14530, 14536, -1, 14540, 14534, 14530, -1, 14544, 14543, 14545, -1, 14544, 14545, 13027, -1, 14544, 13027, 13011, -1, 14544, 13011, 14539, -1, 14544, 14540, 14543, -1, 14544, 14539, 14534, -1, 14544, 14534, 14540, -1, 13050, 13074, 14546, -1, 14547, 14548, 14549, -1, 14550, 14546, 14551, -1, 14550, 14551, 14552, -1, 14550, 13051, 13050, -1, 14550, 13050, 14546, -1, 14553, 14552, 14548, -1, 14553, 14547, 13067, -1, 14553, 13067, 13051, -1, 14553, 14550, 14552, -1, 14553, 14548, 14547, -1, 14553, 13051, 14550, -1, 14554, 14555, 14556, -1, 13089, 13113, 14557, -1, 14558, 14559, 14560, -1, 14558, 14560, 14555, -1, 14558, 14554, 14561, -1, 14558, 14555, 14554, -1, 14562, 14563, 14559, -1, 14562, 14559, 14558, -1, 14564, 14561, 14565, -1, 14564, 14565, 14566, -1, 14564, 14558, 14561, -1, 14567, 13090, 13089, -1, 14567, 14557, 14563, -1, 14567, 14563, 14562, -1, 14567, 13089, 14557, -1, 14568, 14566, 14569, -1, 14568, 14569, 14570, -1, 14568, 14570, 14571, -1, 14568, 14564, 14566, -1, 14568, 14558, 14564, -1, 14568, 14562, 14558, -1, 14572, 14571, 14573, -1, 14572, 14573, 13106, -1, 14572, 13106, 13090, -1, 14572, 13090, 14567, -1, 14572, 14568, 14571, -1, 14572, 14567, 14562, -1, 14572, 14562, 14568, -1, 14574, 14575, 14576, -1, 14577, 14578, 14579, -1, 14580, 14581, 14582, -1, 14580, 14582, 14574, -1, 14580, 14576, 14583, -1, 14580, 14574, 14576, -1, 14584, 14585, 14579, -1, 14584, 14578, 14581, -1, 14584, 14583, 14585, -1, 14584, 14580, 14583, -1, 14584, 14581, 14580, -1, 14584, 14579, 14578, -1, 14586, 14587, 14588, -1, 14589, 14590, 14591, -1, 14592, 14593, 14594, -1, 14592, 14594, 14587, -1, 14592, 14586, 14595, -1, 14592, 14587, 14586, -1, 14596, 14597, 14593, -1, 14596, 14593, 14592, -1, 14598, 14595, 14599, -1, 14598, 14599, 14600, -1, 14598, 14592, 14595, -1, 14601, 14602, 14589, -1, 14601, 14591, 14597, -1, 14601, 14597, 14596, -1, 14601, 14589, 14591, -1, 14603, 14604, 14605, -1, 14603, 14600, 14606, -1, 14603, 14606, 14604, -1, 14603, 14598, 14600, -1, 14603, 14592, 14598, -1, 14603, 14596, 14592, -1, 14607, 14605, 14608, -1, 14607, 14608, 14609, -1, 14607, 14609, 14602, -1, 14607, 14596, 14603, -1, 14607, 14603, 14605, -1, 14607, 14602, 14601, -1, 14607, 14601, 14596, -1, 14610, 14611, 14612, -1, 14613, 14614, 14615, -1, 14616, 14617, 14618, -1, 14616, 14618, 14610, -1, 14616, 14612, 14619, -1, 14616, 14610, 14612, -1, 14620, 14621, 14615, -1, 14620, 14614, 14617, -1, 14620, 14619, 14621, -1, 14620, 14616, 14619, -1, 14620, 14617, 14616, -1, 14620, 14615, 14614, -1, 14622, 14623, 14624, -1, 13232, 13257, 14625, -1, 14626, 14627, 14628, -1, 14626, 14628, 14623, -1, 14626, 14622, 14629, -1, 14626, 14623, 14622, -1, 14630, 14631, 14627, -1, 14630, 14627, 14626, -1, 14632, 14629, 14633, -1, 14632, 14633, 14634, -1, 14632, 14626, 14629, -1, 14635, 13233, 13232, -1, 14635, 14625, 14631, -1, 14635, 14631, 14630, -1, 14635, 13232, 14625, -1, 14636, 14634, 14637, -1, 14636, 14637, 14638, -1, 14636, 14638, 14639, -1, 14636, 14632, 14634, -1, 14636, 14626, 14632, -1, 14636, 14630, 14626, -1, 14640, 14639, 14641, -1, 14640, 14641, 13249, -1, 14640, 13249, 13233, -1, 14640, 13233, 14635, -1, 14640, 14636, 14639, -1, 14640, 14635, 14630, -1, 14640, 14630, 14636, -1, 13272, 13296, 14642, -1, 14643, 14644, 14645, -1, 14646, 14642, 14647, -1, 14646, 14647, 14648, -1, 14646, 13273, 13272, -1, 14646, 13272, 14642, -1, 14649, 14648, 14644, -1, 14649, 14643, 13289, -1, 14649, 13289, 13273, -1, 14649, 14646, 14648, -1, 14649, 13273, 14646, -1, 14649, 14644, 14643, -1, 14650, 14651, 14652, -1, 13310, 13335, 14653, -1, 14654, 14655, 14656, -1, 14654, 14656, 14651, -1, 14654, 14650, 14657, -1, 14654, 14651, 14650, -1, 14658, 14659, 14655, -1, 14658, 14655, 14654, -1, 14660, 14657, 14661, -1, 14660, 14661, 14662, -1, 14660, 14654, 14657, -1, 14663, 13311, 13310, -1, 14663, 14653, 14659, -1, 14663, 14659, 14658, -1, 14663, 13310, 14653, -1, 14664, 14662, 14665, -1, 14664, 14665, 14666, -1, 14664, 14666, 14667, -1, 14664, 14660, 14662, -1, 14664, 14654, 14660, -1, 14664, 14658, 14654, -1, 14668, 14667, 14669, -1, 14668, 14669, 13327, -1, 14668, 13327, 13311, -1, 14668, 13311, 14663, -1, 14668, 14664, 14667, -1, 14668, 14663, 14658, -1, 14668, 14658, 14664, -1, 13348, 13374, 14670, -1, 14671, 14672, 14673, -1, 14674, 14670, 14675, -1, 14674, 14675, 14676, -1, 14674, 13349, 13348, -1, 14674, 13348, 14670, -1, 14677, 14676, 14672, -1, 14677, 14671, 13366, -1, 14677, 13366, 13349, -1, 14677, 14674, 14676, -1, 14677, 14672, 14671, -1, 14677, 13349, 14674, -1, 14678, 14679, 14680, -1, 13389, 13413, 14681, -1, 14682, 14683, 14684, -1, 14682, 14684, 14679, -1, 14682, 14678, 14685, -1, 14682, 14679, 14678, -1, 14686, 14687, 14683, -1, 14686, 14683, 14682, -1, 14688, 14685, 14689, -1, 14688, 14689, 14690, -1, 14688, 14682, 14685, -1, 14691, 13390, 13389, -1, 14691, 14681, 14687, -1, 14691, 14687, 14686, -1, 14691, 13389, 14681, -1, 14692, 14690, 14693, -1, 14692, 14693, 14694, -1, 14692, 14694, 14695, -1, 14692, 14688, 14690, -1, 14692, 14682, 14688, -1, 14692, 14686, 14682, -1, 14696, 14695, 14697, -1, 14696, 14697, 13406, -1, 14696, 13406, 13390, -1, 14696, 13390, 14691, -1, 14696, 14692, 14695, -1, 14696, 14691, 14686, -1, 14696, 14686, 14692, -1, 13427, 13452, 14698, -1, 14699, 14700, 14701, -1, 14702, 14698, 14703, -1, 14702, 14703, 14704, -1, 14702, 13428, 13427, -1, 14702, 13427, 14698, -1, 14705, 14704, 14700, -1, 14705, 14699, 13444, -1, 14705, 13444, 13428, -1, 14705, 14702, 14704, -1, 14705, 14700, 14699, -1, 14705, 13428, 14702, -1, 14706, 14707, 14708, -1, 13466, 13491, 14709, -1, 14710, 14711, 14712, -1, 14710, 14712, 14707, -1, 14710, 14706, 14713, -1, 14710, 14707, 14706, -1, 14714, 14715, 14711, -1, 14714, 14711, 14710, -1, 14716, 14713, 14717, -1, 14716, 14717, 14718, -1, 14716, 14710, 14713, -1, 14719, 13467, 13466, -1, 14719, 14709, 14715, -1, 14719, 14715, 14714, -1, 14719, 13466, 14709, -1, 14720, 14718, 14721, -1, 14720, 14721, 14722, -1, 14720, 14722, 14723, -1, 14720, 14716, 14718, -1, 14720, 14710, 14716, -1, 14720, 14714, 14710, -1, 14724, 14723, 14725, -1, 14724, 14725, 13483, -1, 14724, 13483, 13467, -1, 14724, 13467, 14719, -1, 14724, 14720, 14723, -1, 14724, 14719, 14714, -1, 14724, 14714, 14720, -1, 13509, 13530, 14726, -1, 14727, 14728, 14729, -1, 14730, 14726, 14731, -1, 14730, 14731, 14732, -1, 14730, 13510, 13509, -1, 14730, 13509, 14726, -1, 14733, 14732, 14728, -1, 14733, 14727, 13524, -1, 14733, 13524, 13510, -1, 14733, 14730, 14732, -1, 14733, 14728, 14727, -1, 14733, 13510, 14730, -1, 14734, 14735, 14736, -1, 13545, 13570, 14737, -1, 14738, 14739, 14740, -1, 14738, 14740, 14735, -1, 14738, 14734, 14741, -1, 14738, 14735, 14734, -1, 14742, 14743, 14739, -1, 14742, 14739, 14738, -1, 14744, 14741, 14745, -1, 14744, 14745, 14746, -1, 14744, 14738, 14741, -1, 14747, 13546, 13545, -1, 14747, 14737, 14743, -1, 14747, 14743, 14742, -1, 14747, 13545, 14737, -1, 14748, 14746, 14749, -1, 14748, 14749, 14750, -1, 14748, 14750, 14751, -1, 14748, 14744, 14746, -1, 14748, 14738, 14744, -1, 14748, 14742, 14738, -1, 14752, 14751, 14753, -1, 14752, 14753, 13562, -1, 14752, 13562, 13546, -1, 14752, 13546, 14747, -1, 14752, 14748, 14751, -1, 14752, 14747, 14742, -1, 14752, 14742, 14748, -1, 13584, 13609, 14754, -1, 14755, 14756, 14757, -1, 14758, 14754, 14759, -1, 14758, 14759, 14760, -1, 14758, 13585, 13584, -1, 14758, 13584, 14754, -1, 14761, 14760, 14756, -1, 14761, 14755, 13601, -1, 14761, 13601, 13585, -1, 14761, 14758, 14760, -1, 14761, 14756, 14755, -1, 14761, 13585, 14758, -1, 14762, 14763, 14764, -1, 13627, 13648, 14765, -1, 14766, 14767, 14768, -1, 14766, 14768, 14763, -1, 14766, 14762, 14769, -1, 14766, 14763, 14762, -1, 14770, 14771, 14767, -1, 14770, 14767, 14766, -1, 14772, 14769, 14773, -1, 14772, 14773, 14774, -1, 14772, 14766, 14769, -1, 14775, 13628, 13627, -1, 14775, 14765, 14771, -1, 14775, 14771, 14770, -1, 14775, 13627, 14765, -1, 14776, 14774, 14777, -1, 14776, 14777, 14778, -1, 14776, 14778, 14779, -1, 14776, 14772, 14774, -1, 14776, 14766, 14772, -1, 14776, 14770, 14766, -1, 14780, 14779, 14781, -1, 14780, 14781, 13642, -1, 14780, 13642, 13628, -1, 14780, 13628, 14775, -1, 14780, 14776, 14779, -1, 14780, 14775, 14770, -1, 14780, 14770, 14776, -1, 13662, 13688, 14782, -1, 14783, 14784, 14785, -1, 14786, 14782, 14787, -1, 14786, 14787, 14788, -1, 14786, 13663, 13662, -1, 14786, 13662, 14782, -1, 14789, 14788, 14784, -1, 14789, 14783, 13680, -1, 14789, 13680, 13663, -1, 14789, 14786, 14788, -1, 14789, 14784, 14783, -1, 14789, 13663, 14786, -1, 14790, 14791, 14792, -1, 13702, 13727, 14793, -1, 14794, 14795, 14796, -1, 14794, 14796, 14791, -1, 14794, 14790, 14797, -1, 14794, 14791, 14790, -1, 14798, 14799, 14795, -1, 14798, 14795, 14794, -1, 14800, 14797, 14801, -1, 14800, 14801, 14802, -1, 14800, 14794, 14797, -1, 14803, 13703, 13702, -1, 14803, 14793, 14799, -1, 14803, 14799, 14798, -1, 14803, 13702, 14793, -1, 14804, 14802, 14805, -1, 14804, 14805, 14806, -1, 14804, 14806, 14807, -1, 14804, 14800, 14802, -1, 14804, 14794, 14800, -1, 14804, 14798, 14794, -1, 14808, 14807, 14809, -1, 14808, 14809, 13719, -1, 14808, 13719, 13703, -1, 14808, 13703, 14803, -1, 14808, 14804, 14807, -1, 14808, 14803, 14798, -1, 14808, 14798, 14804, -1, 13742, 13766, 14810, -1, 14811, 14812, 14813, -1, 14814, 14810, 14815, -1, 14814, 14815, 14816, -1, 14814, 13743, 13742, -1, 14814, 13742, 14810, -1, 14817, 14816, 14812, -1, 14817, 14811, 13759, -1, 14817, 13759, 13743, -1, 14817, 14814, 14816, -1, 14817, 14812, 14811, -1, 14817, 13743, 14814, -1, 14818, 14819, 14820, -1, 14821, 14822, 14823, -1, 14824, 14825, 14826, -1, 14824, 14826, 14819, -1, 14824, 14818, 14827, -1, 14824, 14819, 14818, -1, 14828, 14829, 14825, -1, 14828, 14825, 14824, -1, 14830, 14827, 14831, -1, 14830, 14831, 14832, -1, 14830, 14824, 14827, -1, 14833, 14834, 14821, -1, 14833, 14823, 14829, -1, 14833, 14829, 14828, -1, 14833, 14821, 14823, -1, 14835, 14836, 14837, -1, 14835, 14832, 14838, -1, 14835, 14838, 14836, -1, 14835, 14830, 14832, -1, 14835, 14824, 14830, -1, 14835, 14828, 14824, -1, 14839, 14837, 14840, -1, 14839, 14840, 14841, -1, 14839, 14841, 14834, -1, 14839, 14828, 14835, -1, 14839, 14835, 14837, -1, 14839, 14834, 14833, -1, 14839, 14833, 14828, -1, 14842, 14843, 14844, -1, 14845, 14846, 14847, -1, 14848, 14849, 14850, -1, 14848, 14850, 14842, -1, 14848, 14844, 14851, -1, 14848, 14842, 14844, -1, 14852, 14853, 14847, -1, 14852, 14846, 14849, -1, 14852, 14851, 14853, -1, 14852, 14848, 14851, -1, 14852, 14849, 14848, -1, 14852, 14847, 14846, -1, 14854, 14855, 14856, -1, 14857, 14858, 14859, -1, 14860, 14861, 14862, -1, 14860, 14862, 14855, -1, 14860, 14854, 14863, -1, 14860, 14855, 14854, -1, 14864, 14865, 14861, -1, 14864, 14861, 14860, -1, 14866, 14863, 14867, -1, 14866, 14867, 14868, -1, 14866, 14860, 14863, -1, 14869, 14870, 14857, -1, 14869, 14859, 14865, -1, 14869, 14865, 14864, -1, 14869, 14857, 14859, -1, 14871, 14872, 14873, -1, 14871, 14868, 14874, -1, 14871, 14874, 14872, -1, 14871, 14866, 14868, -1, 14871, 14860, 14866, -1, 14871, 14864, 14860, -1, 14875, 14873, 14876, -1, 14875, 14876, 14877, -1, 14875, 14877, 14870, -1, 14875, 14864, 14871, -1, 14875, 14871, 14873, -1, 14875, 14870, 14869, -1, 14875, 14869, 14864, -1, 14878, 14879, 14880, -1, 14881, 14882, 14883, -1, 14884, 14885, 14886, -1, 14884, 14886, 14878, -1, 14884, 14880, 14887, -1, 14884, 14878, 14880, -1, 14888, 14889, 14883, -1, 14888, 14882, 14885, -1, 14888, 14887, 14889, -1, 14888, 14884, 14887, -1, 14888, 14885, 14884, -1, 14888, 14883, 14882, -1, 14890, 14891, 14892, -1, 14893, 14894, 14895, -1, 14896, 14897, 14898, -1, 14896, 14898, 14890, -1, 14896, 14892, 14899, -1, 14896, 14890, 14892, -1, 14900, 14901, 14895, -1, 14900, 14894, 14897, -1, 14900, 14899, 14901, -1, 14900, 14896, 14899, -1, 14900, 14897, 14896, -1, 14900, 14895, 14894, -1, 14902, 14903, 14904, -1, 14905, 14906, 14907, -1, 14908, 14909, 14910, -1, 14908, 14910, 14903, -1, 14908, 14902, 14911, -1, 14908, 14903, 14902, -1, 14912, 14913, 14909, -1, 14912, 14909, 14908, -1, 14914, 14911, 14915, -1, 14914, 14915, 14916, -1, 14914, 14908, 14911, -1, 14917, 14918, 14905, -1, 14917, 14907, 14913, -1, 14917, 14913, 14912, -1, 14917, 14905, 14907, -1, 14919, 14920, 14921, -1, 14919, 14916, 14922, -1, 14919, 14922, 14920, -1, 14919, 14914, 14916, -1, 14919, 14908, 14914, -1, 14919, 14912, 14908, -1, 14923, 14921, 14924, -1, 14923, 14924, 14925, -1, 14923, 14925, 14918, -1, 14923, 14912, 14919, -1, 14923, 14919, 14921, -1, 14923, 14918, 14917, -1, 14923, 14917, 14912, -1, 14926, 14927, 14928, -1, 14929, 14930, 14931, -1, 14932, 14933, 14934, -1, 14932, 14934, 14927, -1, 14932, 14926, 14935, -1, 14932, 14927, 14926, -1, 14936, 14937, 14933, -1, 14936, 14933, 14932, -1, 14938, 14935, 14939, -1, 14938, 14939, 14940, -1, 14938, 14932, 14935, -1, 14941, 14942, 14929, -1, 14941, 14931, 14937, -1, 14941, 14937, 14936, -1, 14941, 14929, 14931, -1, 14943, 14944, 14945, -1, 14943, 14940, 14946, -1, 14943, 14946, 14944, -1, 14943, 14938, 14940, -1, 14943, 14932, 14938, -1, 14943, 14936, 14932, -1, 14947, 14945, 14948, -1, 14947, 14948, 14949, -1, 14947, 14949, 14942, -1, 14947, 14936, 14943, -1, 14947, 14943, 14945, -1, 14947, 14942, 14941, -1, 14947, 14941, 14936, -1, 14950, 14951, 14952, -1, 14953, 14954, 14955, -1, 14956, 14957, 14958, -1, 14956, 14958, 14950, -1, 14956, 14952, 14959, -1, 14956, 14950, 14952, -1, 14960, 14961, 14955, -1, 14960, 14954, 14957, -1, 14960, 14959, 14961, -1, 14960, 14956, 14959, -1, 14960, 14957, 14956, -1, 14960, 14955, 14954, -1, 14061, 14085, 14962, -1, 14963, 14964, 14965, -1, 14966, 14962, 14967, -1, 14966, 14967, 14968, -1, 14966, 14062, 14061, -1, 14966, 14061, 14962, -1, 14969, 14968, 14964, -1, 14969, 14963, 14078, -1, 14969, 14078, 14062, -1, 14969, 14966, 14968, -1, 14969, 14964, 14963, -1, 14969, 14062, 14966, -1, 14970, 14096, 14971, -1, 14972, 14973, 14974, -1, 14972, 14970, 14973, -1, 14975, 14976, 14974, -1, 14975, 14977, 14978, -1, 14975, 14974, 14977, -1, 14979, 14978, 12000, -1, 14979, 14975, 14978, -1, 14980, 12001, 14981, -1, 14980, 12000, 12001, -1, 14980, 14981, 14982, -1, 14980, 14979, 12000, -1, 14983, 14979, 14980, -1, 14983, 14975, 14979, -1, 14983, 14980, 14982, -1, 14983, 14982, 14976, -1, 14983, 14976, 14975, -1, 14984, 14096, 14970, -1, 14984, 14970, 14972, -1, 14985, 14103, 14096, -1, 14985, 14984, 14972, -1, 14985, 14986, 14103, -1, 14985, 14974, 14986, -1, 14985, 14972, 14974, -1, 14985, 14096, 14984, -1, 14987, 14988, 11992, -1, 14987, 11992, 11991, -1, 14989, 14990, 14988, -1, 14989, 14991, 14990, -1, 14989, 14988, 14987, -1, 14992, 14989, 14987, -1, 14993, 14989, 14992, -1, 14993, 14991, 14989, -1, 14994, 14096, 14095, -1, 14994, 14995, 14991, -1, 14994, 14095, 14995, -1, 14994, 14991, 14993, -1, 14974, 14973, 14996, -1, 14976, 14986, 14974, -1, 14982, 14981, 14997, -1, 14998, 14103, 14986, -1, 14998, 14986, 14976, -1, 14998, 14976, 14982, -1, 14999, 15000, 15001, -1, 14999, 14997, 15000, -1, 14999, 14982, 14997, -1, 14999, 14998, 14982, -1, 15002, 14103, 14998, -1, 15003, 15001, 14105, -1, 15003, 14105, 14103, -1, 15003, 14999, 15001, -1, 15003, 14998, 14999, -1, 15003, 14103, 15002, -1, 15003, 15002, 14998, -1, 15004, 14992, 14987, -1, 15004, 14973, 14993, -1, 15004, 14987, 11991, -1, 15004, 14993, 14992, -1, 15005, 14973, 15004, -1, 15005, 15004, 11991, -1, 15006, 14996, 14973, -1, 15006, 14973, 15005, -1, 15006, 15005, 11991, -1, 14977, 11991, 12000, -1, 14977, 14996, 15006, -1, 14977, 14974, 14996, -1, 14977, 15006, 11991, -1, 14978, 14977, 12000, -1, 14971, 14993, 14973, -1, 14971, 14994, 14993, -1, 14971, 14096, 14994, -1, 14970, 14971, 14973, -1, 15007, 14106, 15008, -1, 15009, 15010, 15011, -1, 15009, 15007, 15010, -1, 15012, 15011, 15013, -1, 15012, 15014, 15011, -1, 15012, 15013, 15015, -1, 15016, 15015, 12021, -1, 15016, 15012, 15015, -1, 15017, 15016, 12021, -1, 15017, 12021, 12022, -1, 15017, 12022, 15018, -1, 15017, 15018, 15019, -1, 15020, 15012, 15016, -1, 15020, 15017, 15019, -1, 15020, 15016, 15017, -1, 15020, 15019, 15014, -1, 15020, 15014, 15012, -1, 15021, 14106, 15007, -1, 15021, 15007, 15009, -1, 15022, 15021, 15009, -1, 15022, 14115, 14106, -1, 15022, 15023, 14115, -1, 15022, 15011, 15023, -1, 15022, 15009, 15011, -1, 15022, 14106, 15021, -1, 15024, 15025, 12011, -1, 15024, 12011, 12010, -1, 15026, 15027, 15025, -1, 15026, 15028, 15027, -1, 15026, 15025, 15024, -1, 15029, 15026, 15024, -1, 15030, 15026, 15029, -1, 15030, 15028, 15026, -1, 15031, 15032, 15028, -1, 15031, 14108, 15032, -1, 15031, 14106, 14108, -1, 15031, 15028, 15030, -1, 15011, 15010, 15033, -1, 15014, 15023, 15011, -1, 15019, 15018, 15034, -1, 15035, 14115, 15023, -1, 15035, 15023, 15014, -1, 15035, 15014, 15019, -1, 15036, 15037, 15038, -1, 15036, 15034, 15037, -1, 15036, 15019, 15034, -1, 15036, 15035, 15019, -1, 15039, 14115, 15035, -1, 15040, 15038, 14119, -1, 15040, 14119, 14115, -1, 15040, 15036, 15038, -1, 15040, 15035, 15036, -1, 15040, 14115, 15039, -1, 15040, 15039, 15035, -1, 15041, 15029, 15024, -1, 15041, 15010, 15030, -1, 15041, 15024, 12010, -1, 15041, 15030, 15029, -1, 15042, 15010, 15041, -1, 15042, 15041, 12010, -1, 15043, 15033, 15010, -1, 15043, 15010, 15042, -1, 15043, 15042, 12010, -1, 15013, 12010, 12021, -1, 15013, 15011, 15033, -1, 15013, 15033, 15043, -1, 15013, 15043, 12010, -1, 15015, 15013, 12021, -1, 15008, 15030, 15010, -1, 15008, 15031, 15030, -1, 15008, 14106, 15031, -1, 15007, 15008, 15010, -1, 15044, 14132, 15045, -1, 15046, 15047, 15048, -1, 15046, 15044, 15047, -1, 15049, 15050, 15048, -1, 15049, 15051, 15052, -1, 15049, 15048, 15051, -1, 15053, 15052, 11961, -1, 15053, 15049, 15052, -1, 15054, 11962, 15055, -1, 15054, 11961, 11962, -1, 15054, 15055, 15056, -1, 15054, 15053, 11961, -1, 15057, 15053, 15054, -1, 15057, 15049, 15053, -1, 15057, 15054, 15056, -1, 15057, 15056, 15050, -1, 15057, 15050, 15049, -1, 15058, 14132, 15044, -1, 15058, 15044, 15046, -1, 15059, 14139, 14132, -1, 15059, 15058, 15046, -1, 15059, 15060, 14139, -1, 15059, 15048, 15060, -1, 15059, 15046, 15048, -1, 15059, 14132, 15058, -1, 15061, 15062, 11952, -1, 15061, 11952, 11951, -1, 15063, 15064, 15062, -1, 15063, 15065, 15064, -1, 15063, 15062, 15061, -1, 15066, 15063, 15061, -1, 15067, 15063, 15066, -1, 15067, 15065, 15063, -1, 15068, 14132, 14131, -1, 15068, 15069, 15065, -1, 15068, 14131, 15069, -1, 15068, 15065, 15067, -1, 15048, 15047, 15070, -1, 15050, 15060, 15048, -1, 15056, 15055, 15071, -1, 15072, 14139, 15060, -1, 15072, 15060, 15050, -1, 15072, 15050, 15056, -1, 15073, 15074, 15075, -1, 15073, 15071, 15074, -1, 15073, 15056, 15071, -1, 15073, 15072, 15056, -1, 15076, 14139, 15072, -1, 15077, 15075, 14141, -1, 15077, 14141, 14139, -1, 15077, 15073, 15075, -1, 15077, 15072, 15073, -1, 15077, 14139, 15076, -1, 15077, 15076, 15072, -1, 15078, 15066, 15061, -1, 15078, 15047, 15067, -1, 15078, 15061, 11951, -1, 15078, 15067, 15066, -1, 15079, 15047, 15078, -1, 15079, 15078, 11951, -1, 15080, 15070, 15047, -1, 15080, 15047, 15079, -1, 15080, 15079, 11951, -1, 15051, 11951, 11961, -1, 15051, 15070, 15080, -1, 15051, 15048, 15070, -1, 15051, 15080, 11951, -1, 15052, 15051, 11961, -1, 15045, 15067, 15047, -1, 15045, 15068, 15067, -1, 15045, 14132, 15068, -1, 15044, 15045, 15047, -1, 15081, 15082, 15083, -1, 15081, 14142, 15082, -1, 15084, 15083, 15085, -1, 15084, 15081, 15083, -1, 15086, 15085, 15087, -1, 15086, 15088, 15085, -1, 15086, 15087, 15089, -1, 15090, 15089, 11979, -1, 15090, 15086, 15089, -1, 15091, 15090, 11979, -1, 15091, 11979, 11981, -1, 15091, 11981, 15092, -1, 15091, 15092, 15093, -1, 15094, 15086, 15090, -1, 15094, 15091, 15093, -1, 15094, 15090, 15091, -1, 15094, 15093, 15088, -1, 15094, 15088, 15086, -1, 15095, 14142, 15081, -1, 15095, 15081, 15084, -1, 15096, 15095, 15084, -1, 15096, 14151, 14142, -1, 15096, 15097, 14151, -1, 15096, 15085, 15097, -1, 15096, 15084, 15085, -1, 15096, 14142, 15095, -1, 15098, 15099, 11972, -1, 15098, 11972, 11971, -1, 15100, 15101, 15099, -1, 15100, 15102, 15101, -1, 15100, 15099, 15098, -1, 15103, 15100, 15098, -1, 15104, 15100, 15103, -1, 15104, 15102, 15100, -1, 15105, 15106, 15102, -1, 15105, 14144, 15106, -1, 15105, 14142, 14144, -1, 15105, 15102, 15104, -1, 15085, 15083, 15107, -1, 15088, 15097, 15085, -1, 15093, 15092, 15108, -1, 15109, 14151, 15097, -1, 15109, 15097, 15088, -1, 15109, 15088, 15093, -1, 15110, 15111, 15112, -1, 15110, 15108, 15111, -1, 15110, 15093, 15108, -1, 15110, 15109, 15093, -1, 15113, 14151, 15109, -1, 15114, 15112, 14155, -1, 15114, 14155, 14151, -1, 15114, 15110, 15112, -1, 15114, 15109, 15110, -1, 15114, 14151, 15113, -1, 15114, 15113, 15109, -1, 15115, 15103, 15098, -1, 15115, 15098, 11971, -1, 15115, 15083, 15104, -1, 15115, 15104, 15103, -1, 15116, 15115, 11971, -1, 15116, 15083, 15115, -1, 15117, 15107, 15083, -1, 15117, 15116, 11971, -1, 15117, 15083, 15116, -1, 15087, 11971, 11979, -1, 15087, 15085, 15107, -1, 15087, 15107, 15117, -1, 15087, 15117, 11971, -1, 15089, 15087, 11979, -1, 15082, 15104, 15083, -1, 15082, 15105, 15104, -1, 15082, 14142, 15105, -1, 15118, 15119, 15120, -1, 15118, 14168, 15119, -1, 15121, 15120, 15122, -1, 15121, 15118, 15120, -1, 15123, 15124, 15125, -1, 15123, 15126, 15122, -1, 15123, 15122, 15124, -1, 15127, 15125, 11690, -1, 15127, 15123, 15125, -1, 15128, 11691, 15129, -1, 15128, 11690, 11691, -1, 15128, 15129, 15130, -1, 15128, 15127, 11690, -1, 15131, 15127, 15128, -1, 15131, 15123, 15127, -1, 15131, 15128, 15130, -1, 15131, 15130, 15126, -1, 15131, 15126, 15123, -1, 15132, 14168, 15118, -1, 15132, 15118, 15121, -1, 15133, 14175, 14168, -1, 15133, 15132, 15121, -1, 15133, 15134, 14175, -1, 15133, 15122, 15134, -1, 15133, 15121, 15122, -1, 15133, 14168, 15132, -1, 15135, 15136, 11678, -1, 15135, 11678, 11677, -1, 15137, 15138, 15136, -1, 15137, 15139, 15138, -1, 15137, 15136, 15135, -1, 15140, 15137, 15135, -1, 15141, 15137, 15140, -1, 15141, 15139, 15137, -1, 15142, 14168, 14167, -1, 15142, 15143, 15139, -1, 15142, 14167, 15143, -1, 15142, 15139, 15141, -1, 15122, 15120, 15144, -1, 15126, 15134, 15122, -1, 15130, 15129, 15145, -1, 15146, 14175, 15134, -1, 15146, 15134, 15126, -1, 15146, 15126, 15130, -1, 15147, 15148, 15149, -1, 15147, 15145, 15148, -1, 15147, 15130, 15145, -1, 15147, 15146, 15130, -1, 15150, 14175, 15146, -1, 15151, 15149, 14177, -1, 15151, 14177, 14175, -1, 15151, 15147, 15149, -1, 15151, 15146, 15147, -1, 15151, 14175, 15150, -1, 15151, 15150, 15146, -1, 15152, 15140, 15135, -1, 15152, 15120, 15141, -1, 15152, 15135, 11677, -1, 15152, 15141, 15140, -1, 15153, 15120, 15152, -1, 15153, 15152, 11677, -1, 15154, 15144, 15120, -1, 15154, 15120, 15153, -1, 15154, 15153, 11677, -1, 15124, 11677, 11690, -1, 15124, 15122, 15144, -1, 15124, 15144, 15154, -1, 15124, 15154, 11677, -1, 15125, 15124, 11690, -1, 15119, 15141, 15120, -1, 15119, 15142, 15141, -1, 15119, 14168, 15142, -1, 15155, 15156, 15157, -1, 15155, 14178, 15156, -1, 15158, 15157, 15159, -1, 15158, 15155, 15157, -1, 15160, 15159, 15161, -1, 15160, 15162, 15159, -1, 15160, 15161, 15163, -1, 15164, 15163, 11719, -1, 15164, 15160, 15163, -1, 15165, 15164, 11719, -1, 15165, 11719, 11720, -1, 15165, 11720, 15166, -1, 15165, 15166, 15167, -1, 15168, 15160, 15164, -1, 15168, 15165, 15167, -1, 15168, 15164, 15165, -1, 15168, 15167, 15162, -1, 15168, 15162, 15160, -1, 15169, 14178, 15155, -1, 15169, 15155, 15158, -1, 15170, 15169, 15158, -1, 15170, 14187, 14178, -1, 15170, 15171, 14187, -1, 15170, 15159, 15171, -1, 15170, 15158, 15159, -1, 15170, 14178, 15169, -1, 15172, 15173, 11713, -1, 15172, 11713, 11712, -1, 15174, 15175, 15173, -1, 15174, 15176, 15175, -1, 15174, 15173, 15172, -1, 15177, 15174, 15172, -1, 15178, 15174, 15177, -1, 15178, 15176, 15174, -1, 15179, 15180, 15176, -1, 15179, 14180, 15180, -1, 15179, 14178, 14180, -1, 15179, 15176, 15178, -1, 15159, 15157, 15181, -1, 15162, 15171, 15159, -1, 15167, 15166, 15182, -1, 15183, 14187, 15171, -1, 15183, 15171, 15162, -1, 15183, 15162, 15167, -1, 15184, 15185, 15186, -1, 15184, 15182, 15185, -1, 15184, 15167, 15182, -1, 15184, 15183, 15167, -1, 15187, 14187, 15183, -1, 15188, 15186, 14191, -1, 15188, 14191, 14187, -1, 15188, 15184, 15186, -1, 15188, 15183, 15184, -1, 15188, 14187, 15187, -1, 15188, 15187, 15183, -1, 15189, 15177, 15172, -1, 15189, 15172, 11712, -1, 15189, 15157, 15178, -1, 15189, 15178, 15177, -1, 15190, 15189, 11712, -1, 15190, 15157, 15189, -1, 15191, 15181, 15157, -1, 15191, 15190, 11712, -1, 15191, 15157, 15190, -1, 15161, 11712, 11719, -1, 15161, 15159, 15181, -1, 15161, 15181, 15191, -1, 15161, 15191, 11712, -1, 15163, 15161, 11719, -1, 15156, 15178, 15157, -1, 15156, 15179, 15178, -1, 15156, 14178, 15179, -1, 15192, 15193, 15194, -1, 15192, 14204, 15193, -1, 15195, 15194, 15196, -1, 15195, 15192, 15194, -1, 15197, 15196, 15198, -1, 15197, 15199, 15196, -1, 15197, 15198, 15200, -1, 15201, 15200, 12044, -1, 15201, 15197, 15200, -1, 15202, 15201, 12044, -1, 15202, 12044, 12046, -1, 15202, 12046, 15203, -1, 15202, 15203, 15204, -1, 15205, 15197, 15201, -1, 15205, 15202, 15204, -1, 15205, 15201, 15202, -1, 15205, 15204, 15199, -1, 15205, 15199, 15197, -1, 15206, 14204, 15192, -1, 15206, 15192, 15195, -1, 15207, 15206, 15195, -1, 15207, 14211, 14204, -1, 15207, 15208, 14211, -1, 15207, 15196, 15208, -1, 15207, 15195, 15196, -1, 15207, 14204, 15206, -1, 15209, 15210, 12040, -1, 15209, 12040, 12039, -1, 15211, 15212, 15210, -1, 15211, 15213, 15212, -1, 15211, 15210, 15209, -1, 15214, 15211, 15209, -1, 15215, 15211, 15214, -1, 15215, 15213, 15211, -1, 15216, 15217, 15213, -1, 15216, 14203, 15217, -1, 15216, 14204, 14203, -1, 15216, 15213, 15215, -1, 15196, 15194, 15218, -1, 15199, 15208, 15196, -1, 15204, 15203, 15219, -1, 15220, 14211, 15208, -1, 15220, 15208, 15199, -1, 15220, 15199, 15204, -1, 15221, 15222, 15223, -1, 15221, 15219, 15222, -1, 15221, 15204, 15219, -1, 15221, 15220, 15204, -1, 15224, 14211, 15220, -1, 15225, 15223, 14213, -1, 15225, 14213, 14211, -1, 15225, 15221, 15223, -1, 15225, 15220, 15221, -1, 15225, 14211, 15224, -1, 15225, 15224, 15220, -1, 15226, 15214, 15209, -1, 15226, 15209, 12039, -1, 15226, 15194, 15215, -1, 15226, 15215, 15214, -1, 15227, 15226, 12039, -1, 15227, 15194, 15226, -1, 15228, 15218, 15194, -1, 15228, 15227, 12039, -1, 15228, 15194, 15227, -1, 15198, 12039, 12044, -1, 15198, 15196, 15218, -1, 15198, 15218, 15228, -1, 15198, 15228, 12039, -1, 15200, 15198, 12044, -1, 15193, 15215, 15194, -1, 15193, 15216, 15215, -1, 15193, 14204, 15216, -1, 15229, 15230, 15231, -1, 15229, 14214, 15230, -1, 15232, 15231, 15233, -1, 15232, 15229, 15231, -1, 15234, 15233, 15235, -1, 15234, 15236, 15233, -1, 15234, 15235, 15237, -1, 15238, 15237, 12057, -1, 15238, 15234, 15237, -1, 15239, 15238, 12057, -1, 15239, 12057, 12058, -1, 15239, 12058, 15240, -1, 15239, 15240, 15241, -1, 15242, 15234, 15238, -1, 15242, 15239, 15241, -1, 15242, 15238, 15239, -1, 15242, 15241, 15236, -1, 15242, 15236, 15234, -1, 15243, 14214, 15229, -1, 15243, 15229, 15232, -1, 15244, 15243, 15232, -1, 15244, 14223, 14214, -1, 15244, 15245, 14223, -1, 15244, 15233, 15245, -1, 15244, 15232, 15233, -1, 15244, 14214, 15243, -1, 15246, 15247, 12054, -1, 15246, 12054, 12053, -1, 15248, 15249, 15247, -1, 15248, 15250, 15249, -1, 15248, 15247, 15246, -1, 15251, 15248, 15246, -1, 15252, 15248, 15251, -1, 15252, 15250, 15248, -1, 15253, 15254, 15250, -1, 15253, 14216, 15254, -1, 15253, 14214, 14216, -1, 15253, 15250, 15252, -1, 15233, 15231, 15255, -1, 15236, 15245, 15233, -1, 15241, 15240, 15256, -1, 15257, 14223, 15245, -1, 15257, 15245, 15236, -1, 15257, 15236, 15241, -1, 15258, 15259, 15260, -1, 15258, 15256, 15259, -1, 15258, 15241, 15256, -1, 15258, 15257, 15241, -1, 15261, 14223, 15257, -1, 15262, 15260, 14227, -1, 15262, 14227, 14223, -1, 15262, 15258, 15260, -1, 15262, 15257, 15258, -1, 15262, 14223, 15261, -1, 15262, 15261, 15257, -1, 15263, 15251, 15246, -1, 15263, 15246, 12053, -1, 15263, 15231, 15252, -1, 15263, 15252, 15251, -1, 15264, 15263, 12053, -1, 15264, 15231, 15263, -1, 15265, 15255, 15231, -1, 15265, 15264, 12053, -1, 15265, 15231, 15264, -1, 15235, 12053, 12057, -1, 15235, 15233, 15255, -1, 15235, 15255, 15265, -1, 15235, 15265, 12053, -1, 15237, 15235, 12057, -1, 15230, 15252, 15231, -1, 15230, 15253, 15252, -1, 15230, 14214, 15253, -1, 15266, 15267, 15268, -1, 15266, 14238, 15267, -1, 15269, 15268, 15270, -1, 15269, 15266, 15268, -1, 15271, 15272, 15273, -1, 15271, 15274, 15270, -1, 15271, 15270, 15272, -1, 15275, 15273, 11937, -1, 15275, 15271, 15273, -1, 15276, 11939, 15277, -1, 15276, 11937, 11939, -1, 15276, 15277, 15278, -1, 15276, 15275, 11937, -1, 15279, 15275, 15276, -1, 15279, 15271, 15275, -1, 15279, 15276, 15278, -1, 15279, 15278, 15274, -1, 15279, 15274, 15271, -1, 15280, 14238, 15266, -1, 15280, 15266, 15269, -1, 15281, 14247, 14238, -1, 15281, 15280, 15269, -1, 15281, 15282, 14247, -1, 15281, 15270, 15282, -1, 15281, 15269, 15270, -1, 15281, 14238, 15280, -1, 15283, 15284, 11929, -1, 15283, 11929, 11928, -1, 15285, 15286, 15284, -1, 15285, 15287, 15286, -1, 15285, 15284, 15283, -1, 15288, 15285, 15283, -1, 15289, 15285, 15288, -1, 15289, 15287, 15285, -1, 15290, 14238, 14240, -1, 15290, 15291, 15287, -1, 15290, 14240, 15291, -1, 15290, 15287, 15289, -1, 15270, 15268, 15292, -1, 15274, 15282, 15270, -1, 15278, 15277, 15293, -1, 15294, 14247, 15282, -1, 15294, 15282, 15274, -1, 15294, 15274, 15278, -1, 15295, 15296, 15297, -1, 15295, 15293, 15296, -1, 15295, 15278, 15293, -1, 15295, 15294, 15278, -1, 15298, 14247, 15294, -1, 15299, 15297, 14251, -1, 15299, 14251, 14247, -1, 15299, 15295, 15297, -1, 15299, 15294, 15295, -1, 15299, 14247, 15298, -1, 15299, 15298, 15294, -1, 15300, 15288, 15283, -1, 15300, 15268, 15289, -1, 15300, 15283, 11928, -1, 15300, 15289, 15288, -1, 15301, 15268, 15300, -1, 15301, 15300, 11928, -1, 15302, 15292, 15268, -1, 15302, 15268, 15301, -1, 15302, 15301, 11928, -1, 15272, 11928, 11937, -1, 15272, 15270, 15292, -1, 15272, 15292, 15302, -1, 15272, 15302, 11928, -1, 15273, 15272, 11937, -1, 15267, 15289, 15268, -1, 15267, 15290, 15289, -1, 15267, 14238, 15290, -1, 15303, 14264, 15304, -1, 15305, 15306, 15307, -1, 15305, 15303, 15306, -1, 15308, 15309, 15307, -1, 15308, 15310, 15311, -1, 15308, 15307, 15310, -1, 15312, 15311, 11916, -1, 15312, 15308, 15311, -1, 15313, 11917, 15314, -1, 15313, 11916, 11917, -1, 15313, 15314, 15315, -1, 15313, 15312, 11916, -1, 15316, 15312, 15313, -1, 15316, 15308, 15312, -1, 15316, 15313, 15315, -1, 15316, 15315, 15309, -1, 15316, 15309, 15308, -1, 15317, 14264, 15303, -1, 15317, 15303, 15305, -1, 15318, 14271, 14264, -1, 15318, 15317, 15305, -1, 15318, 15319, 14271, -1, 15318, 15307, 15319, -1, 15318, 15305, 15307, -1, 15318, 14264, 15317, -1, 15320, 15321, 11908, -1, 15320, 11908, 11907, -1, 15322, 15323, 15321, -1, 15322, 15324, 15323, -1, 15322, 15321, 15320, -1, 15325, 15322, 15320, -1, 15326, 15322, 15325, -1, 15326, 15324, 15322, -1, 15327, 14264, 14263, -1, 15327, 15328, 15324, -1, 15327, 14263, 15328, -1, 15327, 15324, 15326, -1, 15307, 15306, 15329, -1, 15309, 15319, 15307, -1, 15315, 15314, 15330, -1, 15331, 14271, 15319, -1, 15331, 15319, 15309, -1, 15331, 15309, 15315, -1, 15332, 15333, 15334, -1, 15332, 15330, 15333, -1, 15332, 15315, 15330, -1, 15332, 15331, 15315, -1, 15335, 14271, 15331, -1, 15336, 15334, 14273, -1, 15336, 14273, 14271, -1, 15336, 15332, 15334, -1, 15336, 15331, 15332, -1, 15336, 14271, 15335, -1, 15336, 15335, 15331, -1, 15337, 15325, 15320, -1, 15337, 15306, 15326, -1, 15337, 15320, 11907, -1, 15337, 15326, 15325, -1, 15338, 15306, 15337, -1, 15338, 15337, 11907, -1, 15339, 15329, 15306, -1, 15339, 15306, 15338, -1, 15339, 15338, 11907, -1, 15310, 11907, 11916, -1, 15310, 15329, 15339, -1, 15310, 15307, 15329, -1, 15310, 15339, 11907, -1, 15311, 15310, 11916, -1, 15304, 15326, 15306, -1, 15304, 15327, 15326, -1, 15304, 14264, 15327, -1, 15303, 15304, 15306, -1, 15340, 14274, 15341, -1, 15342, 15343, 15344, -1, 15342, 15340, 15343, -1, 15345, 15346, 15347, -1, 15345, 15348, 15344, -1, 15345, 15344, 15346, -1, 15349, 15347, 11885, -1, 15349, 15345, 15347, -1, 15350, 11887, 15351, -1, 15350, 11885, 11887, -1, 15350, 15351, 15352, -1, 15350, 15349, 11885, -1, 15353, 15349, 15350, -1, 15353, 15345, 15349, -1, 15353, 15350, 15352, -1, 15353, 15352, 15348, -1, 15353, 15348, 15345, -1, 15354, 14274, 15340, -1, 15354, 15340, 15342, -1, 15355, 14283, 14274, -1, 15355, 15354, 15342, -1, 15355, 15356, 14283, -1, 15355, 15344, 15356, -1, 15355, 15342, 15344, -1, 15355, 14274, 15354, -1, 15357, 15358, 11875, -1, 15357, 11875, 11874, -1, 15359, 15360, 15358, -1, 15359, 15361, 15360, -1, 15359, 15358, 15357, -1, 15362, 15359, 15357, -1, 15363, 15359, 15362, -1, 15363, 15361, 15359, -1, 15364, 14274, 14276, -1, 15364, 15365, 15361, -1, 15364, 14276, 15365, -1, 15364, 15361, 15363, -1, 15344, 15343, 15366, -1, 15348, 15356, 15344, -1, 15352, 15351, 15367, -1, 15368, 14283, 15356, -1, 15368, 15356, 15348, -1, 15368, 15348, 15352, -1, 15369, 15370, 15371, -1, 15369, 15367, 15370, -1, 15369, 15352, 15367, -1, 15369, 15368, 15352, -1, 15372, 14283, 15368, -1, 15373, 15371, 14287, -1, 15373, 14287, 14283, -1, 15373, 15369, 15371, -1, 15373, 15368, 15369, -1, 15373, 14283, 15372, -1, 15373, 15372, 15368, -1, 15374, 15362, 15357, -1, 15374, 15343, 15363, -1, 15374, 15357, 11874, -1, 15374, 15363, 15362, -1, 15375, 15343, 15374, -1, 15375, 15374, 11874, -1, 15376, 15366, 15343, -1, 15376, 15343, 15375, -1, 15376, 15375, 11874, -1, 15346, 11874, 11885, -1, 15346, 15344, 15366, -1, 15346, 15366, 15376, -1, 15346, 15376, 11874, -1, 15347, 15346, 11885, -1, 15341, 15363, 15343, -1, 15341, 15364, 15363, -1, 15341, 14274, 15364, -1, 15340, 15341, 15343, -1, 15377, 14300, 15378, -1, 15379, 15380, 15381, -1, 15379, 15377, 15380, -1, 15382, 15383, 15381, -1, 15382, 15384, 15385, -1, 15382, 15381, 15384, -1, 15386, 15385, 11861, -1, 15386, 15382, 15385, -1, 15387, 11862, 15388, -1, 15387, 11861, 11862, -1, 15387, 15388, 15389, -1, 15387, 15386, 11861, -1, 15390, 15386, 15387, -1, 15390, 15382, 15386, -1, 15390, 15387, 15389, -1, 15390, 15389, 15383, -1, 15390, 15383, 15382, -1, 15391, 14300, 15377, -1, 15391, 15377, 15379, -1, 15392, 14307, 14300, -1, 15392, 15391, 15379, -1, 15392, 15393, 14307, -1, 15392, 15381, 15393, -1, 15392, 15379, 15381, -1, 15392, 14300, 15391, -1, 15394, 15395, 11843, -1, 15394, 11843, 11842, -1, 15396, 15397, 15395, -1, 15396, 15398, 15397, -1, 15396, 15395, 15394, -1, 15399, 15396, 15394, -1, 15400, 15396, 15399, -1, 15400, 15398, 15396, -1, 15401, 14300, 14299, -1, 15401, 15402, 15398, -1, 15401, 14299, 15402, -1, 15401, 15398, 15400, -1, 15381, 15380, 15403, -1, 15383, 15393, 15381, -1, 15389, 15388, 15404, -1, 15405, 14307, 15393, -1, 15405, 15393, 15383, -1, 15405, 15383, 15389, -1, 15406, 15407, 15408, -1, 15406, 15404, 15407, -1, 15406, 15389, 15404, -1, 15406, 15405, 15389, -1, 15409, 14307, 15405, -1, 15410, 15408, 14309, -1, 15410, 14309, 14307, -1, 15410, 15406, 15408, -1, 15410, 15405, 15406, -1, 15410, 14307, 15409, -1, 15410, 15409, 15405, -1, 15411, 15399, 15394, -1, 15411, 15380, 15400, -1, 15411, 15394, 11842, -1, 15411, 15400, 15399, -1, 15412, 15380, 15411, -1, 15412, 15411, 11842, -1, 15413, 15403, 15380, -1, 15413, 15380, 15412, -1, 15413, 15412, 11842, -1, 15384, 11842, 11861, -1, 15384, 15403, 15413, -1, 15384, 15381, 15403, -1, 15384, 15413, 11842, -1, 15385, 15384, 11861, -1, 15378, 15400, 15380, -1, 15378, 15401, 15400, -1, 15378, 14300, 15401, -1, 15377, 15378, 15380, -1, 15414, 15415, 15416, -1, 15414, 14310, 15415, -1, 15417, 15416, 15418, -1, 15417, 15414, 15416, -1, 15419, 15420, 15421, -1, 15419, 15422, 15418, -1, 15419, 15418, 15420, -1, 15423, 15421, 11738, -1, 15423, 15419, 15421, -1, 15424, 11739, 15425, -1, 15424, 11738, 11739, -1, 15424, 15425, 15426, -1, 15424, 15423, 11738, -1, 15427, 15423, 15424, -1, 15427, 15419, 15423, -1, 15427, 15424, 15426, -1, 15427, 15426, 15422, -1, 15427, 15422, 15419, -1, 15428, 14310, 15414, -1, 15428, 15414, 15417, -1, 15429, 14319, 14310, -1, 15429, 15428, 15417, -1, 15429, 15430, 14319, -1, 15429, 15418, 15430, -1, 15429, 15417, 15418, -1, 15429, 14310, 15428, -1, 15431, 15432, 11725, -1, 15431, 11725, 11727, -1, 15433, 15434, 15432, -1, 15433, 15435, 15434, -1, 15433, 15432, 15431, -1, 15436, 15433, 15431, -1, 15437, 15433, 15436, -1, 15437, 15435, 15433, -1, 15438, 14310, 14312, -1, 15438, 15439, 15435, -1, 15438, 14312, 15439, -1, 15438, 15435, 15437, -1, 15418, 15416, 15440, -1, 15422, 15430, 15418, -1, 15426, 15425, 15441, -1, 15442, 14319, 15430, -1, 15442, 15430, 15422, -1, 15442, 15422, 15426, -1, 15443, 15444, 15445, -1, 15443, 15441, 15444, -1, 15443, 15426, 15441, -1, 15443, 15442, 15426, -1, 15446, 14319, 15442, -1, 15447, 15445, 14323, -1, 15447, 14323, 14319, -1, 15447, 15443, 15445, -1, 15447, 15442, 15443, -1, 15447, 14319, 15446, -1, 15447, 15446, 15442, -1, 15448, 15436, 15431, -1, 15448, 15416, 15437, -1, 15448, 15431, 11727, -1, 15448, 15437, 15436, -1, 15449, 15416, 15448, -1, 15449, 15448, 11727, -1, 15450, 15440, 15416, -1, 15450, 15416, 15449, -1, 15450, 15449, 11727, -1, 15420, 11727, 11738, -1, 15420, 15418, 15440, -1, 15420, 15440, 15450, -1, 15420, 15450, 11727, -1, 15421, 15420, 11738, -1, 15415, 15437, 15416, -1, 15415, 15438, 15437, -1, 15415, 14310, 15438, -1, 15451, 15452, 15453, -1, 15451, 14336, 15452, -1, 15454, 15453, 15455, -1, 15454, 15451, 15453, -1, 15456, 15457, 15458, -1, 15456, 15459, 15455, -1, 15456, 15455, 15457, -1, 15460, 15458, 11714, -1, 15460, 15456, 15458, -1, 15461, 11715, 15462, -1, 15461, 11714, 11715, -1, 15461, 15462, 15463, -1, 15461, 15460, 11714, -1, 15464, 15460, 15461, -1, 15464, 15456, 15460, -1, 15464, 15461, 15463, -1, 15464, 15463, 15459, -1, 15464, 15459, 15456, -1, 15465, 14336, 15451, -1, 15465, 15451, 15454, -1, 15466, 14343, 14336, -1, 15466, 15465, 15454, -1, 15466, 15467, 14343, -1, 15466, 15455, 15467, -1, 15466, 15454, 15455, -1, 15466, 14336, 15465, -1, 15468, 15469, 11701, -1, 15468, 11701, 11703, -1, 15470, 15471, 15469, -1, 15470, 15472, 15471, -1, 15470, 15469, 15468, -1, 15473, 15470, 15468, -1, 15474, 15470, 15473, -1, 15474, 15472, 15470, -1, 15475, 14336, 14335, -1, 15475, 15476, 15472, -1, 15475, 14335, 15476, -1, 15475, 15472, 15474, -1, 15455, 15453, 15477, -1, 15459, 15467, 15455, -1, 15463, 15462, 15478, -1, 15479, 14343, 15467, -1, 15479, 15467, 15459, -1, 15479, 15459, 15463, -1, 15480, 15481, 15482, -1, 15480, 15478, 15481, -1, 15480, 15463, 15478, -1, 15480, 15479, 15463, -1, 15483, 14343, 15479, -1, 15484, 15482, 14345, -1, 15484, 14345, 14343, -1, 15484, 15480, 15482, -1, 15484, 15479, 15480, -1, 15484, 14343, 15483, -1, 15484, 15483, 15479, -1, 15485, 15473, 15468, -1, 15485, 15453, 15474, -1, 15485, 15468, 11703, -1, 15485, 15474, 15473, -1, 15486, 15453, 15485, -1, 15486, 15485, 11703, -1, 15487, 15477, 15453, -1, 15487, 15453, 15486, -1, 15487, 15486, 11703, -1, 15457, 11703, 11714, -1, 15457, 15455, 15477, -1, 15457, 15477, 15487, -1, 15457, 15487, 11703, -1, 15458, 15457, 11714, -1, 15452, 15474, 15453, -1, 15452, 15475, 15474, -1, 15452, 14336, 15475, -1, 15488, 15489, 15490, -1, 15488, 14348, 15489, -1, 15491, 15490, 15492, -1, 15491, 15488, 15490, -1, 15493, 15492, 15494, -1, 15493, 15495, 15492, -1, 15493, 15494, 15496, -1, 15497, 15496, 11761, -1, 15497, 15493, 15496, -1, 15498, 15497, 11761, -1, 15498, 11761, 11762, -1, 15498, 11762, 15499, -1, 15498, 15499, 15500, -1, 15501, 15493, 15497, -1, 15501, 15498, 15500, -1, 15501, 15497, 15498, -1, 15501, 15500, 15495, -1, 15501, 15495, 15493, -1, 15502, 14348, 15488, -1, 15502, 15488, 15491, -1, 15503, 15502, 15491, -1, 15503, 14355, 14348, -1, 15503, 15504, 14355, -1, 15503, 15492, 15504, -1, 15503, 15491, 15492, -1, 15503, 14348, 15502, -1, 15505, 15506, 11744, -1, 15505, 11744, 11746, -1, 15507, 15508, 15506, -1, 15507, 15509, 15508, -1, 15507, 15506, 15505, -1, 15510, 15507, 15505, -1, 15511, 15507, 15510, -1, 15511, 15509, 15507, -1, 15512, 15513, 15509, -1, 15512, 14347, 15513, -1, 15512, 14348, 14347, -1, 15512, 15509, 15511, -1, 15492, 15490, 15514, -1, 15495, 15504, 15492, -1, 15500, 15499, 15515, -1, 15516, 14355, 15504, -1, 15516, 15504, 15495, -1, 15516, 15495, 15500, -1, 15517, 15518, 15519, -1, 15517, 15515, 15518, -1, 15517, 15500, 15515, -1, 15517, 15516, 15500, -1, 15520, 14355, 15516, -1, 15521, 15519, 14357, -1, 15521, 14357, 14355, -1, 15521, 15517, 15519, -1, 15521, 15516, 15517, -1, 15521, 14355, 15520, -1, 15521, 15520, 15516, -1, 15522, 15510, 15505, -1, 15522, 15505, 11746, -1, 15522, 15490, 15511, -1, 15522, 15511, 15510, -1, 15523, 15522, 11746, -1, 15523, 15490, 15522, -1, 15524, 15514, 15490, -1, 15524, 15523, 11746, -1, 15524, 15490, 15523, -1, 15494, 11746, 11761, -1, 15494, 15492, 15514, -1, 15494, 15514, 15524, -1, 15494, 15524, 11746, -1, 15496, 15494, 11761, -1, 15489, 15511, 15490, -1, 15489, 15512, 15511, -1, 15489, 14348, 15512, -1, 15525, 15526, 15527, -1, 15525, 14358, 15526, -1, 15528, 15527, 15529, -1, 15528, 15525, 15527, -1, 15530, 15529, 15531, -1, 15530, 15532, 15529, -1, 15530, 15531, 15533, -1, 15534, 15533, 11822, -1, 15534, 15530, 15533, -1, 15535, 15534, 11822, -1, 15535, 11822, 11823, -1, 15535, 11823, 15536, -1, 15535, 15536, 15537, -1, 15538, 15530, 15534, -1, 15538, 15535, 15537, -1, 15538, 15534, 15535, -1, 15538, 15537, 15532, -1, 15538, 15532, 15530, -1, 15539, 14358, 15525, -1, 15539, 15525, 15528, -1, 15540, 15539, 15528, -1, 15540, 14367, 14358, -1, 15540, 15541, 14367, -1, 15540, 15529, 15541, -1, 15540, 15528, 15529, -1, 15540, 14358, 15539, -1, 15542, 15543, 11768, -1, 15542, 11768, 11770, -1, 15544, 15545, 15543, -1, 15544, 15546, 15545, -1, 15544, 15543, 15542, -1, 15547, 15544, 15542, -1, 15548, 15544, 15547, -1, 15548, 15546, 15544, -1, 15549, 15550, 15546, -1, 15549, 14360, 15550, -1, 15549, 14358, 14360, -1, 15549, 15546, 15548, -1, 15529, 15527, 15551, -1, 15532, 15541, 15529, -1, 15537, 15536, 15552, -1, 15553, 14367, 15541, -1, 15553, 15541, 15532, -1, 15553, 15532, 15537, -1, 15554, 15555, 15556, -1, 15554, 15552, 15555, -1, 15554, 15537, 15552, -1, 15554, 15553, 15537, -1, 15557, 14367, 15553, -1, 15558, 15556, 14371, -1, 15558, 14371, 14367, -1, 15558, 15554, 15556, -1, 15558, 15553, 15554, -1, 15558, 14367, 15557, -1, 15558, 15557, 15553, -1, 15559, 15547, 15542, -1, 15559, 15542, 11770, -1, 15559, 15527, 15548, -1, 15559, 15548, 15547, -1, 15560, 15559, 11770, -1, 15560, 15527, 15559, -1, 15561, 15551, 15527, -1, 15561, 15560, 11770, -1, 15561, 15527, 15560, -1, 15531, 11770, 11822, -1, 15531, 15529, 15551, -1, 15531, 15551, 15561, -1, 15531, 15561, 11770, -1, 15533, 15531, 11822, -1, 15526, 15548, 15527, -1, 15526, 15549, 15548, -1, 15526, 14358, 15549, -1, 15562, 15563, 15564, -1, 15562, 6897, 15563, -1, 15565, 15564, 15566, -1, 15565, 15562, 15564, -1, 15567, 15568, 15569, -1, 15567, 15570, 15566, -1, 15567, 15566, 15568, -1, 15571, 15569, 12029, -1, 15571, 15567, 15569, -1, 15572, 12033, 15573, -1, 15572, 12029, 12033, -1, 15572, 15573, 15574, -1, 15572, 15571, 12029, -1, 15575, 15571, 15572, -1, 15575, 15567, 15571, -1, 15575, 15572, 15574, -1, 15575, 15574, 15570, -1, 15575, 15570, 15567, -1, 15576, 6897, 15562, -1, 15576, 15562, 15565, -1, 15577, 6904, 6897, -1, 15577, 15576, 15565, -1, 15577, 15578, 6904, -1, 15577, 15566, 15578, -1, 15577, 15565, 15566, -1, 15577, 6897, 15576, -1, 15579, 15580, 12026, -1, 15579, 12026, 12025, -1, 15581, 15582, 15580, -1, 15581, 15583, 15582, -1, 15581, 15580, 15579, -1, 15584, 15581, 15579, -1, 15585, 15581, 15584, -1, 15585, 15583, 15581, -1, 15586, 6897, 6896, -1, 15586, 15587, 15583, -1, 15586, 6896, 15587, -1, 15586, 15583, 15585, -1, 15566, 15564, 15588, -1, 15570, 15578, 15566, -1, 15574, 15573, 15589, -1, 15590, 6904, 15578, -1, 15590, 15578, 15570, -1, 15590, 15570, 15574, -1, 15591, 15592, 15593, -1, 15591, 15589, 15592, -1, 15591, 15574, 15589, -1, 15591, 15590, 15574, -1, 15594, 6904, 15590, -1, 15595, 15593, 6906, -1, 15595, 6906, 6904, -1, 15595, 15591, 15593, -1, 15595, 15590, 15591, -1, 15595, 6904, 15594, -1, 15595, 15594, 15590, -1, 15596, 15584, 15579, -1, 15596, 15564, 15585, -1, 15596, 15579, 12025, -1, 15596, 15585, 15584, -1, 15597, 15564, 15596, -1, 15597, 15596, 12025, -1, 15598, 15588, 15564, -1, 15598, 15564, 15597, -1, 15598, 15597, 12025, -1, 15568, 12025, 12029, -1, 15568, 15566, 15588, -1, 15568, 15588, 15598, -1, 15568, 15598, 12025, -1, 15569, 15568, 12029, -1, 15563, 15585, 15564, -1, 15563, 15586, 15585, -1, 15563, 6897, 15586, -1, 15599, 6941, 15600, -1, 15601, 15602, 15603, -1, 15601, 15599, 15602, -1, 15604, 15603, 15605, -1, 15604, 15606, 15603, -1, 15604, 15605, 15607, -1, 15608, 15607, 12032, -1, 15608, 15604, 15607, -1, 15609, 15608, 12032, -1, 15609, 12032, 12031, -1, 15609, 12031, 15610, -1, 15609, 15610, 15611, -1, 15612, 15604, 15608, -1, 15612, 15609, 15611, -1, 15612, 15608, 15609, -1, 15612, 15611, 15606, -1, 15612, 15606, 15604, -1, 15613, 6941, 15599, -1, 15613, 15599, 15601, -1, 15614, 15613, 15601, -1, 15614, 6950, 6941, -1, 15614, 15615, 6950, -1, 15614, 15603, 15615, -1, 15614, 15601, 15603, -1, 15614, 6941, 15613, -1, 15616, 15617, 12038, -1, 15616, 12038, 12034, -1, 15618, 15619, 15617, -1, 15618, 15620, 15619, -1, 15618, 15617, 15616, -1, 15621, 15618, 15616, -1, 15622, 15618, 15621, -1, 15622, 15620, 15618, -1, 15623, 15624, 15620, -1, 15623, 6943, 15624, -1, 15623, 6941, 6943, -1, 15623, 15620, 15622, -1, 15603, 15602, 15625, -1, 15606, 15615, 15603, -1, 15611, 15610, 15626, -1, 15627, 6950, 15615, -1, 15627, 15615, 15606, -1, 15627, 15606, 15611, -1, 15628, 15629, 15630, -1, 15628, 15626, 15629, -1, 15628, 15611, 15626, -1, 15628, 15627, 15611, -1, 15631, 6950, 15627, -1, 15632, 15630, 6954, -1, 15632, 6954, 6950, -1, 15632, 15628, 15630, -1, 15632, 15627, 15628, -1, 15632, 6950, 15631, -1, 15632, 15631, 15627, -1, 15633, 15621, 15616, -1, 15633, 15602, 15622, -1, 15633, 15616, 12034, -1, 15633, 15622, 15621, -1, 15634, 15602, 15633, -1, 15634, 15633, 12034, -1, 15635, 15625, 15602, -1, 15635, 15602, 15634, -1, 15635, 15634, 12034, -1, 15605, 12034, 12032, -1, 15605, 15603, 15625, -1, 15605, 15625, 15635, -1, 15605, 15635, 12034, -1, 15607, 15605, 12032, -1, 15600, 15622, 15602, -1, 15600, 15623, 15622, -1, 15600, 6941, 15623, -1, 15599, 15600, 15602, -1, 15636, 15637, 15638, -1, 15636, 7073, 15637, -1, 15639, 15638, 15640, -1, 15639, 15636, 15638, -1, 15641, 15642, 15643, -1, 15641, 15644, 15640, -1, 15641, 15640, 15642, -1, 15645, 15643, 11982, -1, 15645, 15641, 15643, -1, 15646, 11989, 15647, -1, 15646, 11982, 11989, -1, 15646, 15647, 15648, -1, 15646, 15645, 11982, -1, 15649, 15645, 15646, -1, 15649, 15641, 15645, -1, 15649, 15646, 15648, -1, 15649, 15648, 15644, -1, 15649, 15644, 15641, -1, 15650, 7073, 15636, -1, 15650, 15636, 15639, -1, 15651, 7080, 7073, -1, 15651, 15650, 15639, -1, 15651, 15652, 7080, -1, 15651, 15640, 15652, -1, 15651, 15639, 15640, -1, 15651, 7073, 15650, -1, 15653, 15654, 11976, -1, 15653, 11976, 11975, -1, 15655, 15656, 15654, -1, 15655, 15657, 15656, -1, 15655, 15654, 15653, -1, 15658, 15655, 15653, -1, 15659, 15655, 15658, -1, 15659, 15657, 15655, -1, 15660, 7073, 7072, -1, 15660, 15661, 15657, -1, 15660, 7072, 15661, -1, 15660, 15657, 15659, -1, 15640, 15638, 15662, -1, 15644, 15652, 15640, -1, 15648, 15647, 15663, -1, 15664, 7080, 15652, -1, 15664, 15652, 15644, -1, 15664, 15644, 15648, -1, 15665, 15666, 15667, -1, 15665, 15663, 15666, -1, 15665, 15648, 15663, -1, 15665, 15664, 15648, -1, 15668, 7080, 15664, -1, 15669, 15667, 7082, -1, 15669, 7082, 7080, -1, 15669, 15665, 15667, -1, 15669, 15664, 15665, -1, 15669, 7080, 15668, -1, 15669, 15668, 15664, -1, 15670, 15658, 15653, -1, 15670, 15638, 15659, -1, 15670, 15653, 11975, -1, 15670, 15659, 15658, -1, 15671, 15638, 15670, -1, 15671, 15670, 11975, -1, 15672, 15662, 15638, -1, 15672, 15638, 15671, -1, 15672, 15671, 11975, -1, 15642, 11975, 11982, -1, 15642, 15640, 15662, -1, 15642, 15662, 15672, -1, 15642, 15672, 11975, -1, 15643, 15642, 11982, -1, 15637, 15659, 15638, -1, 15637, 15660, 15659, -1, 15637, 7073, 15660, -1, 15673, 7223, 15674, -1, 15675, 15676, 15677, -1, 15675, 15673, 15676, -1, 15678, 15677, 15679, -1, 15678, 15680, 15677, -1, 15678, 15679, 15681, -1, 15682, 15681, 12008, -1, 15682, 15678, 15681, -1, 15683, 15682, 12008, -1, 15683, 12008, 12016, -1, 15683, 12016, 15684, -1, 15683, 15684, 15685, -1, 15686, 15678, 15682, -1, 15686, 15683, 15685, -1, 15686, 15682, 15683, -1, 15686, 15685, 15680, -1, 15686, 15680, 15678, -1, 15687, 7223, 15673, -1, 15687, 15673, 15675, -1, 15688, 15687, 15675, -1, 15688, 7232, 7223, -1, 15688, 15689, 7232, -1, 15688, 15677, 15689, -1, 15688, 15675, 15677, -1, 15688, 7223, 15687, -1, 15690, 15691, 12003, -1, 15690, 12003, 12002, -1, 15692, 15693, 15691, -1, 15692, 15694, 15693, -1, 15692, 15691, 15690, -1, 15695, 15692, 15690, -1, 15696, 15692, 15695, -1, 15696, 15694, 15692, -1, 15697, 15698, 15694, -1, 15697, 7225, 15698, -1, 15697, 7223, 7225, -1, 15697, 15694, 15696, -1, 15677, 15676, 15699, -1, 15680, 15689, 15677, -1, 15685, 15684, 15700, -1, 15701, 7232, 15689, -1, 15701, 15689, 15680, -1, 15701, 15680, 15685, -1, 15702, 15703, 15704, -1, 15702, 15700, 15703, -1, 15702, 15685, 15700, -1, 15702, 15701, 15685, -1, 15705, 7232, 15701, -1, 15706, 15704, 7236, -1, 15706, 7236, 7232, -1, 15706, 15702, 15704, -1, 15706, 15701, 15702, -1, 15706, 7232, 15705, -1, 15706, 15705, 15701, -1, 15707, 15695, 15690, -1, 15707, 15676, 15696, -1, 15707, 15690, 12002, -1, 15707, 15696, 15695, -1, 15708, 15676, 15707, -1, 15708, 15707, 12002, -1, 15709, 15699, 15676, -1, 15709, 15676, 15708, -1, 15709, 15708, 12002, -1, 15679, 12002, 12008, -1, 15679, 15677, 15699, -1, 15679, 15699, 15709, -1, 15679, 15709, 12002, -1, 15681, 15679, 12008, -1, 15674, 15696, 15676, -1, 15674, 15697, 15696, -1, 15674, 7223, 15697, -1, 15673, 15674, 15676, -1, 15710, 15711, 15712, -1, 15710, 7247, 15711, -1, 15713, 15712, 15714, -1, 15713, 15710, 15712, -1, 15715, 15716, 15714, -1, 15715, 15717, 15718, -1, 15715, 15714, 15717, -1, 15719, 15718, 11931, -1, 15719, 15715, 15718, -1, 15720, 11930, 15721, -1, 15720, 11931, 11930, -1, 15720, 15721, 15722, -1, 15720, 15719, 11931, -1, 15723, 15719, 15720, -1, 15723, 15715, 15719, -1, 15723, 15720, 15722, -1, 15723, 15722, 15716, -1, 15723, 15716, 15715, -1, 15724, 7247, 15710, -1, 15724, 15710, 15713, -1, 15725, 7256, 7247, -1, 15725, 15724, 15713, -1, 15725, 15726, 7256, -1, 15725, 15714, 15726, -1, 15725, 15713, 15714, -1, 15725, 7247, 15724, -1, 15727, 15728, 11944, -1, 15727, 11944, 11943, -1, 15729, 15730, 15728, -1, 15729, 15731, 15730, -1, 15729, 15728, 15727, -1, 15732, 15729, 15727, -1, 15733, 15729, 15732, -1, 15733, 15731, 15729, -1, 15734, 7247, 7249, -1, 15734, 15735, 15731, -1, 15734, 7249, 15735, -1, 15734, 15731, 15733, -1, 15714, 15712, 15736, -1, 15716, 15726, 15714, -1, 15722, 15721, 15737, -1, 15738, 7256, 15726, -1, 15738, 15726, 15716, -1, 15738, 15716, 15722, -1, 15739, 15740, 15741, -1, 15739, 15737, 15740, -1, 15739, 15722, 15737, -1, 15739, 15738, 15722, -1, 15742, 7256, 15738, -1, 15743, 15741, 7260, -1, 15743, 7260, 7256, -1, 15743, 15739, 15741, -1, 15743, 15738, 15739, -1, 15743, 7256, 15742, -1, 15743, 15742, 15738, -1, 15744, 15732, 15727, -1, 15744, 15712, 15733, -1, 15744, 15727, 11943, -1, 15744, 15733, 15732, -1, 15745, 15712, 15744, -1, 15745, 15744, 11943, -1, 15746, 15736, 15712, -1, 15746, 15712, 15745, -1, 15746, 15745, 11943, -1, 15717, 11943, 11931, -1, 15717, 15736, 15746, -1, 15717, 15714, 15736, -1, 15717, 15746, 11943, -1, 15718, 15717, 11931, -1, 15711, 15733, 15712, -1, 15711, 15734, 15733, -1, 15711, 7247, 15734, -1, 15747, 7365, 15748, -1, 15749, 15750, 15751, -1, 15749, 15747, 15750, -1, 15752, 15753, 15751, -1, 15752, 15754, 15755, -1, 15752, 15751, 15754, -1, 15756, 15755, 11955, -1, 15756, 15752, 15755, -1, 15757, 11954, 15758, -1, 15757, 11955, 11954, -1, 15757, 15758, 15759, -1, 15757, 15756, 11955, -1, 15760, 15756, 15757, -1, 15760, 15752, 15756, -1, 15760, 15757, 15759, -1, 15760, 15759, 15753, -1, 15760, 15753, 15752, -1, 15761, 7365, 15747, -1, 15761, 15747, 15749, -1, 15762, 7372, 7365, -1, 15762, 15761, 15749, -1, 15762, 15763, 7372, -1, 15762, 15751, 15763, -1, 15762, 15749, 15751, -1, 15762, 7365, 15761, -1, 15764, 15765, 11969, -1, 15764, 11969, 11968, -1, 15766, 15767, 15765, -1, 15766, 15768, 15767, -1, 15766, 15765, 15764, -1, 15769, 15766, 15764, -1, 15770, 15766, 15769, -1, 15770, 15768, 15766, -1, 15771, 7365, 7364, -1, 15771, 15772, 15768, -1, 15771, 7364, 15772, -1, 15771, 15768, 15770, -1, 15751, 15750, 15773, -1, 15753, 15763, 15751, -1, 15759, 15758, 15774, -1, 15775, 7372, 15763, -1, 15775, 15763, 15753, -1, 15775, 15753, 15759, -1, 15776, 15777, 15778, -1, 15776, 15774, 15777, -1, 15776, 15759, 15774, -1, 15776, 15775, 15759, -1, 15779, 7372, 15775, -1, 15780, 15778, 7374, -1, 15780, 7374, 7372, -1, 15780, 15776, 15778, -1, 15780, 15775, 15776, -1, 15780, 7372, 15779, -1, 15780, 15779, 15775, -1, 15781, 15769, 15764, -1, 15781, 15750, 15770, -1, 15781, 15764, 11968, -1, 15781, 15770, 15769, -1, 15782, 15750, 15781, -1, 15782, 15781, 11968, -1, 15783, 15773, 15750, -1, 15783, 15750, 15782, -1, 15783, 15782, 11968, -1, 15754, 11968, 11955, -1, 15754, 15773, 15783, -1, 15754, 15751, 15773, -1, 15754, 15783, 11968, -1, 15755, 15754, 11955, -1, 15748, 15770, 15750, -1, 15748, 15771, 15770, -1, 15748, 7365, 15771, -1, 15747, 15748, 15750, -1, 15784, 15785, 15786, -1, 15784, 7545, 15785, -1, 15787, 15786, 15788, -1, 15787, 15784, 15786, -1, 15789, 15788, 15790, -1, 15789, 15791, 15788, -1, 15789, 15790, 15792, -1, 15793, 15792, 12015, -1, 15793, 15789, 15792, -1, 15794, 15793, 12015, -1, 15794, 12015, 12014, -1, 15794, 12014, 15795, -1, 15794, 15795, 15796, -1, 15797, 15789, 15793, -1, 15797, 15794, 15796, -1, 15797, 15793, 15794, -1, 15797, 15796, 15791, -1, 15797, 15791, 15789, -1, 15798, 7545, 15784, -1, 15798, 15784, 15787, -1, 15799, 15798, 15787, -1, 15799, 7552, 7545, -1, 15799, 15800, 7552, -1, 15799, 15788, 15800, -1, 15799, 15787, 15788, -1, 15799, 7545, 15798, -1, 15801, 15802, 12023, -1, 15801, 12023, 12019, -1, 15803, 15804, 15802, -1, 15803, 15805, 15804, -1, 15803, 15802, 15801, -1, 15806, 15803, 15801, -1, 15807, 15803, 15806, -1, 15807, 15805, 15803, -1, 15808, 15809, 15805, -1, 15808, 7544, 15809, -1, 15808, 7545, 7544, -1, 15808, 15805, 15807, -1, 15788, 15786, 15810, -1, 15791, 15800, 15788, -1, 15796, 15795, 15811, -1, 15812, 7552, 15800, -1, 15812, 15800, 15791, -1, 15812, 15791, 15796, -1, 15813, 15814, 15815, -1, 15813, 15811, 15814, -1, 15813, 15796, 15811, -1, 15813, 15812, 15796, -1, 15816, 7552, 15812, -1, 15817, 15815, 7554, -1, 15817, 7554, 7552, -1, 15817, 15813, 15815, -1, 15817, 15812, 15813, -1, 15817, 7552, 15816, -1, 15817, 15816, 15812, -1, 15818, 15806, 15801, -1, 15818, 15801, 12019, -1, 15818, 15786, 15807, -1, 15818, 15807, 15806, -1, 15819, 15818, 12019, -1, 15819, 15786, 15818, -1, 15820, 15810, 15786, -1, 15820, 15819, 12019, -1, 15820, 15786, 15819, -1, 15790, 12019, 12015, -1, 15790, 15788, 15810, -1, 15790, 15810, 15820, -1, 15790, 15820, 12019, -1, 15792, 15790, 12015, -1, 15785, 15807, 15786, -1, 15785, 15808, 15807, -1, 15785, 7545, 15808, -1, 15821, 7671, 15822, -1, 15823, 15824, 15825, -1, 15823, 15821, 15824, -1, 15826, 15825, 15827, -1, 15826, 15828, 15825, -1, 15826, 15827, 15829, -1, 15830, 15829, 11987, -1, 15830, 15826, 15829, -1, 15831, 15830, 11987, -1, 15831, 11987, 11986, -1, 15831, 11986, 15832, -1, 15831, 15832, 15833, -1, 15834, 15826, 15830, -1, 15834, 15831, 15833, -1, 15834, 15830, 15831, -1, 15834, 15833, 15828, -1, 15834, 15828, 15826, -1, 15835, 7671, 15821, -1, 15835, 15821, 15823, -1, 15836, 15835, 15823, -1, 15836, 7680, 7671, -1, 15836, 15837, 7680, -1, 15836, 15825, 15837, -1, 15836, 15823, 15825, -1, 15836, 7671, 15835, -1, 15838, 15839, 11996, -1, 15838, 11996, 11993, -1, 15840, 15841, 15839, -1, 15840, 15842, 15841, -1, 15840, 15839, 15838, -1, 15843, 15840, 15838, -1, 15844, 15840, 15843, -1, 15844, 15842, 15840, -1, 15845, 15846, 15842, -1, 15845, 7673, 15846, -1, 15845, 7671, 7673, -1, 15845, 15842, 15844, -1, 15825, 15824, 15847, -1, 15828, 15837, 15825, -1, 15833, 15832, 15848, -1, 15849, 7680, 15837, -1, 15849, 15837, 15828, -1, 15849, 15828, 15833, -1, 15850, 15851, 15852, -1, 15850, 15848, 15851, -1, 15850, 15833, 15848, -1, 15850, 15849, 15833, -1, 15853, 7680, 15849, -1, 15854, 15852, 7684, -1, 15854, 7684, 7680, -1, 15854, 15850, 15852, -1, 15854, 15849, 15850, -1, 15854, 7680, 15853, -1, 15854, 15853, 15849, -1, 15855, 15843, 15838, -1, 15855, 15824, 15844, -1, 15855, 15838, 11993, -1, 15855, 15844, 15843, -1, 15856, 15824, 15855, -1, 15856, 15855, 11993, -1, 15857, 15847, 15824, -1, 15857, 15824, 15856, -1, 15857, 15856, 11993, -1, 15827, 11993, 11987, -1, 15827, 15825, 15847, -1, 15827, 15847, 15857, -1, 15827, 15857, 11993, -1, 15829, 15827, 11987, -1, 15822, 15844, 15824, -1, 15822, 15845, 15844, -1, 15822, 7671, 15845, -1, 15821, 15822, 15824, -1, 15858, 15859, 15860, -1, 15858, 14496, 15859, -1, 15861, 15860, 15862, -1, 15861, 15858, 15860, -1, 15863, 15864, 15862, -1, 15863, 15865, 15866, -1, 15863, 15862, 15865, -1, 15867, 15866, 11863, -1, 15867, 15863, 15866, -1, 15868, 11869, 15869, -1, 15868, 11863, 11869, -1, 15868, 15869, 15870, -1, 15868, 15867, 11863, -1, 15871, 15867, 15868, -1, 15871, 15863, 15867, -1, 15871, 15868, 15870, -1, 15871, 15870, 15864, -1, 15871, 15864, 15863, -1, 15872, 14496, 15858, -1, 15872, 15858, 15861, -1, 15873, 14503, 14496, -1, 15873, 15872, 15861, -1, 15873, 15874, 14503, -1, 15873, 15862, 15874, -1, 15873, 15861, 15862, -1, 15873, 14496, 15872, -1, 15875, 15876, 11858, -1, 15875, 11858, 11857, -1, 15877, 15878, 15876, -1, 15877, 15879, 15878, -1, 15877, 15876, 15875, -1, 15880, 15877, 15875, -1, 15881, 15877, 15880, -1, 15881, 15879, 15877, -1, 15882, 14496, 14495, -1, 15882, 15883, 15879, -1, 15882, 14495, 15883, -1, 15882, 15879, 15881, -1, 15862, 15860, 15884, -1, 15864, 15874, 15862, -1, 15870, 15869, 15885, -1, 15886, 14503, 15874, -1, 15886, 15874, 15864, -1, 15886, 15864, 15870, -1, 15887, 15888, 15889, -1, 15887, 15885, 15888, -1, 15887, 15870, 15885, -1, 15887, 15886, 15870, -1, 15890, 14503, 15886, -1, 15891, 15889, 14505, -1, 15891, 14505, 14503, -1, 15891, 15887, 15889, -1, 15891, 15886, 15887, -1, 15891, 14503, 15890, -1, 15891, 15890, 15886, -1, 15892, 15880, 15875, -1, 15892, 15860, 15881, -1, 15892, 15875, 11857, -1, 15892, 15881, 15880, -1, 15893, 15860, 15892, -1, 15893, 15892, 11857, -1, 15894, 15884, 15860, -1, 15894, 15860, 15893, -1, 15894, 15893, 11857, -1, 15865, 11857, 11863, -1, 15865, 15884, 15894, -1, 15865, 15862, 15884, -1, 15865, 15894, 11857, -1, 15866, 15865, 11863, -1, 15859, 15881, 15860, -1, 15859, 15882, 15881, -1, 15859, 14496, 15882, -1, 15895, 15896, 15897, -1, 15895, 7803, 15896, -1, 15898, 15897, 15899, -1, 15898, 15895, 15897, -1, 15900, 15899, 15901, -1, 15900, 15902, 15899, -1, 15900, 15901, 15903, -1, 15904, 15903, 11894, -1, 15904, 15900, 15903, -1, 15905, 15904, 11894, -1, 15905, 11894, 11899, -1, 15905, 11899, 15906, -1, 15905, 15906, 15907, -1, 15908, 15900, 15904, -1, 15908, 15905, 15907, -1, 15908, 15904, 15905, -1, 15908, 15907, 15902, -1, 15908, 15902, 15900, -1, 15909, 7803, 15895, -1, 15909, 15895, 15898, -1, 15910, 15909, 15898, -1, 15910, 7812, 7803, -1, 15910, 15911, 7812, -1, 15910, 15899, 15911, -1, 15910, 15898, 15899, -1, 15910, 7803, 15909, -1, 15912, 15913, 11889, -1, 15912, 11889, 11888, -1, 15914, 15915, 15913, -1, 15914, 15916, 15915, -1, 15914, 15913, 15912, -1, 15917, 15914, 15912, -1, 15918, 15914, 15917, -1, 15918, 15916, 15914, -1, 15919, 15920, 15916, -1, 15919, 7805, 15920, -1, 15919, 7803, 7805, -1, 15919, 15916, 15918, -1, 15899, 15897, 15921, -1, 15902, 15911, 15899, -1, 15907, 15906, 15922, -1, 15923, 7812, 15911, -1, 15923, 15911, 15902, -1, 15923, 15902, 15907, -1, 15924, 15925, 15926, -1, 15924, 15922, 15925, -1, 15924, 15907, 15922, -1, 15924, 15923, 15907, -1, 15927, 7812, 15923, -1, 15928, 15926, 7816, -1, 15928, 7816, 7812, -1, 15928, 15924, 15926, -1, 15928, 15923, 15924, -1, 15928, 7812, 15927, -1, 15928, 15927, 15923, -1, 15929, 15917, 15912, -1, 15929, 15912, 11888, -1, 15929, 15897, 15918, -1, 15929, 15918, 15917, -1, 15930, 15929, 11888, -1, 15930, 15897, 15929, -1, 15931, 15921, 15897, -1, 15931, 15930, 11888, -1, 15931, 15897, 15930, -1, 15901, 11888, 11894, -1, 15901, 15899, 15921, -1, 15901, 15921, 15931, -1, 15901, 15931, 11888, -1, 15903, 15901, 11894, -1, 15896, 15918, 15897, -1, 15896, 15919, 15918, -1, 15896, 7803, 15919, -1, 15932, 15933, 15934, -1, 15932, 8011, 15933, -1, 15935, 15934, 15936, -1, 15935, 15932, 15934, -1, 15937, 15938, 15936, -1, 15937, 15939, 15940, -1, 15937, 15936, 15939, -1, 15941, 15940, 11953, -1, 15941, 15937, 15940, -1, 15942, 11963, 15943, -1, 15942, 11953, 11963, -1, 15942, 15943, 15944, -1, 15942, 15941, 11953, -1, 15945, 15941, 15942, -1, 15945, 15937, 15941, -1, 15945, 15942, 15944, -1, 15945, 15944, 15938, -1, 15945, 15938, 15937, -1, 15946, 8011, 15932, -1, 15946, 15932, 15935, -1, 15947, 8020, 8011, -1, 15947, 15946, 15935, -1, 15947, 15948, 8020, -1, 15947, 15936, 15948, -1, 15947, 15935, 15936, -1, 15947, 8011, 15946, -1, 15949, 15950, 11949, -1, 15949, 11949, 11948, -1, 15951, 15952, 15950, -1, 15951, 15953, 15952, -1, 15951, 15950, 15949, -1, 15954, 15951, 15949, -1, 15955, 15951, 15954, -1, 15955, 15953, 15951, -1, 15956, 8011, 8013, -1, 15956, 15957, 15953, -1, 15956, 8013, 15957, -1, 15956, 15953, 15955, -1, 15936, 15934, 15958, -1, 15938, 15948, 15936, -1, 15944, 15943, 15959, -1, 15960, 8020, 15948, -1, 15960, 15948, 15938, -1, 15960, 15938, 15944, -1, 15961, 15962, 15963, -1, 15961, 15959, 15962, -1, 15961, 15944, 15959, -1, 15961, 15960, 15944, -1, 15964, 8020, 15960, -1, 15965, 15963, 8024, -1, 15965, 8024, 8020, -1, 15965, 15961, 15963, -1, 15965, 15960, 15961, -1, 15965, 8020, 15964, -1, 15965, 15964, 15960, -1, 15966, 15954, 15949, -1, 15966, 15934, 15955, -1, 15966, 15949, 11948, -1, 15966, 15955, 15954, -1, 15967, 15934, 15966, -1, 15967, 15966, 11948, -1, 15968, 15958, 15934, -1, 15968, 15934, 15967, -1, 15968, 15967, 11948, -1, 15939, 11948, 11953, -1, 15939, 15958, 15968, -1, 15939, 15936, 15958, -1, 15939, 15968, 11948, -1, 15940, 15939, 11953, -1, 15933, 15955, 15934, -1, 15933, 15956, 15955, -1, 15933, 8011, 15956, -1, 15969, 15970, 15971, -1, 15969, 8037, 15970, -1, 15972, 15971, 15973, -1, 15972, 15969, 15971, -1, 15974, 15973, 15975, -1, 15974, 15976, 15973, -1, 15974, 15975, 15977, -1, 15978, 15977, 11925, -1, 15978, 15974, 15977, -1, 15979, 15978, 11925, -1, 15979, 11925, 11933, -1, 15979, 11933, 15980, -1, 15979, 15980, 15981, -1, 15982, 15974, 15978, -1, 15982, 15979, 15981, -1, 15982, 15978, 15979, -1, 15982, 15981, 15976, -1, 15982, 15976, 15974, -1, 15983, 8037, 15969, -1, 15983, 15969, 15972, -1, 15984, 15983, 15972, -1, 15984, 8044, 8037, -1, 15984, 15985, 8044, -1, 15984, 15973, 15985, -1, 15984, 15972, 15973, -1, 15984, 8037, 15983, -1, 15986, 15987, 11919, -1, 15986, 11919, 11918, -1, 15988, 15989, 15987, -1, 15988, 15990, 15989, -1, 15988, 15987, 15986, -1, 15991, 15988, 15986, -1, 15992, 15988, 15991, -1, 15992, 15990, 15988, -1, 15993, 15994, 15990, -1, 15993, 8036, 15994, -1, 15993, 8037, 8036, -1, 15993, 15990, 15992, -1, 15973, 15971, 15995, -1, 15976, 15985, 15973, -1, 15981, 15980, 15996, -1, 15997, 8044, 15985, -1, 15997, 15985, 15976, -1, 15997, 15976, 15981, -1, 15998, 15999, 16000, -1, 15998, 15996, 15999, -1, 15998, 15981, 15996, -1, 15998, 15997, 15981, -1, 16001, 8044, 15997, -1, 16002, 16000, 8046, -1, 16002, 8046, 8044, -1, 16002, 15998, 16000, -1, 16002, 15997, 15998, -1, 16002, 8044, 16001, -1, 16002, 16001, 15997, -1, 16003, 15991, 15986, -1, 16003, 15986, 11918, -1, 16003, 15971, 15992, -1, 16003, 15992, 15991, -1, 16004, 16003, 11918, -1, 16004, 15971, 16003, -1, 16005, 15995, 15971, -1, 16005, 16004, 11918, -1, 16005, 15971, 16004, -1, 15975, 11918, 11925, -1, 15975, 15973, 15995, -1, 15975, 15995, 16005, -1, 15975, 16005, 11918, -1, 15977, 15975, 11925, -1, 15970, 15992, 15971, -1, 15970, 15993, 15992, -1, 15970, 8037, 15993, -1, 16006, 16007, 16008, -1, 16006, 8235, 16007, -1, 16009, 16008, 16010, -1, 16009, 16006, 16008, -1, 16011, 16012, 16010, -1, 16011, 16013, 16014, -1, 16011, 16010, 16013, -1, 16015, 16014, 11836, -1, 16015, 16011, 16014, -1, 16016, 11840, 16017, -1, 16016, 11836, 11840, -1, 16016, 16017, 16018, -1, 16016, 16015, 11836, -1, 16019, 16015, 16016, -1, 16019, 16011, 16015, -1, 16019, 16016, 16018, -1, 16019, 16018, 16012, -1, 16019, 16012, 16011, -1, 16020, 8235, 16006, -1, 16020, 16006, 16009, -1, 16021, 8244, 8235, -1, 16021, 16020, 16009, -1, 16021, 16022, 8244, -1, 16021, 16010, 16022, -1, 16021, 16009, 16010, -1, 16021, 8235, 16020, -1, 16023, 16024, 11829, -1, 16023, 11829, 11828, -1, 16025, 16026, 16024, -1, 16025, 16027, 16026, -1, 16025, 16024, 16023, -1, 16028, 16025, 16023, -1, 16029, 16025, 16028, -1, 16029, 16027, 16025, -1, 16030, 8235, 8237, -1, 16030, 16031, 16027, -1, 16030, 8237, 16031, -1, 16030, 16027, 16029, -1, 16010, 16008, 16032, -1, 16012, 16022, 16010, -1, 16018, 16017, 16033, -1, 16034, 8244, 16022, -1, 16034, 16022, 16012, -1, 16034, 16012, 16018, -1, 16035, 16036, 16037, -1, 16035, 16033, 16036, -1, 16035, 16018, 16033, -1, 16035, 16034, 16018, -1, 16038, 8244, 16034, -1, 16039, 16037, 8248, -1, 16039, 8248, 8244, -1, 16039, 16035, 16037, -1, 16039, 16034, 16035, -1, 16039, 8244, 16038, -1, 16039, 16038, 16034, -1, 16040, 16028, 16023, -1, 16040, 16008, 16029, -1, 16040, 16023, 11828, -1, 16040, 16029, 16028, -1, 16041, 16008, 16040, -1, 16041, 16040, 11828, -1, 16042, 16032, 16008, -1, 16042, 16008, 16041, -1, 16042, 16041, 11828, -1, 16013, 11828, 11836, -1, 16013, 16032, 16042, -1, 16013, 16010, 16032, -1, 16013, 16042, 11828, -1, 16014, 16013, 11836, -1, 16007, 16029, 16008, -1, 16007, 16030, 16029, -1, 16007, 8235, 16030, -1, 16043, 14576, 16044, -1, 16045, 16046, 16047, -1, 16045, 16043, 16046, -1, 16048, 16049, 16047, -1, 16048, 16050, 16051, -1, 16048, 16047, 16050, -1, 16052, 16051, 11802, -1, 16052, 16048, 16051, -1, 16053, 11809, 16054, -1, 16053, 11802, 11809, -1, 16053, 16054, 16055, -1, 16053, 16052, 11802, -1, 16056, 16052, 16053, -1, 16056, 16048, 16052, -1, 16056, 16053, 16055, -1, 16056, 16055, 16049, -1, 16056, 16049, 16048, -1, 16057, 14576, 16043, -1, 16057, 16043, 16045, -1, 16058, 14583, 14576, -1, 16058, 16057, 16045, -1, 16058, 16059, 14583, -1, 16058, 16047, 16059, -1, 16058, 16045, 16047, -1, 16058, 14576, 16057, -1, 16060, 16061, 11798, -1, 16060, 11798, 11797, -1, 16062, 16063, 16061, -1, 16062, 16064, 16063, -1, 16062, 16061, 16060, -1, 16065, 16062, 16060, -1, 16066, 16062, 16065, -1, 16066, 16064, 16062, -1, 16067, 14576, 14575, -1, 16067, 16068, 16064, -1, 16067, 14575, 16068, -1, 16067, 16064, 16066, -1, 16047, 16046, 16069, -1, 16049, 16059, 16047, -1, 16055, 16054, 16070, -1, 16071, 14583, 16059, -1, 16071, 16059, 16049, -1, 16071, 16049, 16055, -1, 16072, 16073, 16074, -1, 16072, 16070, 16073, -1, 16072, 16055, 16070, -1, 16072, 16071, 16055, -1, 16075, 14583, 16071, -1, 16076, 16074, 14585, -1, 16076, 14585, 14583, -1, 16076, 16072, 16074, -1, 16076, 16071, 16072, -1, 16076, 14583, 16075, -1, 16076, 16075, 16071, -1, 16077, 16065, 16060, -1, 16077, 16046, 16066, -1, 16077, 16060, 11797, -1, 16077, 16066, 16065, -1, 16078, 16046, 16077, -1, 16078, 16077, 11797, -1, 16079, 16069, 16046, -1, 16079, 16046, 16078, -1, 16079, 16078, 11797, -1, 16050, 11797, 11802, -1, 16050, 16069, 16079, -1, 16050, 16047, 16069, -1, 16050, 16079, 11797, -1, 16051, 16050, 11802, -1, 16044, 16066, 16046, -1, 16044, 16067, 16066, -1, 16044, 14576, 16067, -1, 16043, 16044, 16046, -1, 16080, 16081, 16082, -1, 16080, 14586, 16081, -1, 16083, 16082, 16084, -1, 16083, 16080, 16082, -1, 16085, 16086, 16084, -1, 16085, 16087, 16088, -1, 16085, 16084, 16087, -1, 16089, 16088, 11779, -1, 16089, 16085, 16088, -1, 16090, 11782, 16091, -1, 16090, 11779, 11782, -1, 16090, 16091, 16092, -1, 16090, 16089, 11779, -1, 16093, 16089, 16090, -1, 16093, 16085, 16089, -1, 16093, 16090, 16092, -1, 16093, 16092, 16086, -1, 16093, 16086, 16085, -1, 16094, 14586, 16080, -1, 16094, 16080, 16083, -1, 16095, 14595, 14586, -1, 16095, 16094, 16083, -1, 16095, 16096, 14595, -1, 16095, 16084, 16096, -1, 16095, 16083, 16084, -1, 16095, 14586, 16094, -1, 16097, 16098, 11775, -1, 16097, 11775, 11774, -1, 16099, 16100, 16098, -1, 16099, 16101, 16100, -1, 16099, 16098, 16097, -1, 16102, 16099, 16097, -1, 16103, 16099, 16102, -1, 16103, 16101, 16099, -1, 16104, 14586, 14588, -1, 16104, 16105, 16101, -1, 16104, 14588, 16105, -1, 16104, 16101, 16103, -1, 16084, 16082, 16106, -1, 16086, 16096, 16084, -1, 16092, 16091, 16107, -1, 16108, 14595, 16096, -1, 16108, 16096, 16086, -1, 16108, 16086, 16092, -1, 16109, 16110, 16111, -1, 16109, 16107, 16110, -1, 16109, 16092, 16107, -1, 16109, 16108, 16092, -1, 16112, 14595, 16108, -1, 16113, 16111, 14599, -1, 16113, 14599, 14595, -1, 16113, 16109, 16111, -1, 16113, 16108, 16109, -1, 16113, 14595, 16112, -1, 16113, 16112, 16108, -1, 16114, 16102, 16097, -1, 16114, 16082, 16103, -1, 16114, 16097, 11774, -1, 16114, 16103, 16102, -1, 16115, 16082, 16114, -1, 16115, 16114, 11774, -1, 16116, 16106, 16082, -1, 16116, 16082, 16115, -1, 16116, 16115, 11774, -1, 16087, 11774, 11779, -1, 16087, 16106, 16116, -1, 16087, 16084, 16106, -1, 16087, 16116, 11774, -1, 16088, 16087, 11779, -1, 16081, 16103, 16082, -1, 16081, 16104, 16103, -1, 16081, 14586, 16104, -1, 16117, 14612, 16118, -1, 16119, 16120, 16121, -1, 16119, 16117, 16120, -1, 16122, 16121, 16123, -1, 16122, 16124, 16121, -1, 16122, 16123, 16125, -1, 16126, 16125, 11750, -1, 16126, 16122, 16125, -1, 16127, 16126, 11750, -1, 16127, 11750, 11751, -1, 16127, 11751, 16128, -1, 16127, 16128, 16129, -1, 16130, 16122, 16126, -1, 16130, 16127, 16129, -1, 16130, 16126, 16127, -1, 16130, 16129, 16124, -1, 16130, 16124, 16122, -1, 16131, 14612, 16117, -1, 16131, 16117, 16119, -1, 16132, 16131, 16119, -1, 16132, 14619, 14612, -1, 16132, 16133, 14619, -1, 16132, 16121, 16133, -1, 16132, 16119, 16121, -1, 16132, 14612, 16131, -1, 16134, 16135, 11741, -1, 16134, 11741, 11740, -1, 16136, 16137, 16135, -1, 16136, 16138, 16137, -1, 16136, 16135, 16134, -1, 16139, 16136, 16134, -1, 16140, 16136, 16139, -1, 16140, 16138, 16136, -1, 16141, 16142, 16138, -1, 16141, 14611, 16142, -1, 16141, 14612, 14611, -1, 16141, 16138, 16140, -1, 16121, 16120, 16143, -1, 16124, 16133, 16121, -1, 16129, 16128, 16144, -1, 16145, 14619, 16133, -1, 16145, 16133, 16124, -1, 16145, 16124, 16129, -1, 16146, 16147, 16148, -1, 16146, 16144, 16147, -1, 16146, 16129, 16144, -1, 16146, 16145, 16129, -1, 16149, 14619, 16145, -1, 16150, 16148, 14621, -1, 16150, 14621, 14619, -1, 16150, 16146, 16148, -1, 16150, 16145, 16146, -1, 16150, 14619, 16149, -1, 16150, 16149, 16145, -1, 16151, 16139, 16134, -1, 16151, 16120, 16140, -1, 16151, 16134, 11740, -1, 16151, 16140, 16139, -1, 16152, 16120, 16151, -1, 16152, 16151, 11740, -1, 16153, 16143, 16120, -1, 16153, 16120, 16152, -1, 16153, 16152, 11740, -1, 16123, 11740, 11750, -1, 16123, 16121, 16143, -1, 16123, 16143, 16153, -1, 16123, 16153, 11740, -1, 16125, 16123, 11750, -1, 16118, 16140, 16120, -1, 16118, 16141, 16140, -1, 16118, 14612, 16141, -1, 16117, 16118, 16120, -1, 16154, 16155, 16156, -1, 16154, 8683, 16155, -1, 16157, 16156, 16158, -1, 16157, 16154, 16156, -1, 16159, 16160, 16161, -1, 16159, 16162, 16158, -1, 16159, 16158, 16160, -1, 16163, 16161, 11748, -1, 16163, 16159, 16161, -1, 16164, 11747, 16165, -1, 16164, 11748, 11747, -1, 16164, 16165, 16166, -1, 16164, 16163, 11748, -1, 16167, 16163, 16164, -1, 16167, 16159, 16163, -1, 16167, 16164, 16166, -1, 16167, 16166, 16162, -1, 16167, 16162, 16159, -1, 16168, 8683, 16154, -1, 16168, 16154, 16157, -1, 16169, 8692, 8683, -1, 16169, 16168, 16157, -1, 16169, 16170, 8692, -1, 16169, 16158, 16170, -1, 16169, 16157, 16158, -1, 16169, 8683, 16168, -1, 16171, 16172, 11767, -1, 16171, 11767, 11758, -1, 16173, 16174, 16172, -1, 16173, 16175, 16174, -1, 16173, 16172, 16171, -1, 16176, 16173, 16171, -1, 16177, 16173, 16176, -1, 16177, 16175, 16173, -1, 16178, 8683, 8685, -1, 16178, 16179, 16175, -1, 16178, 8685, 16179, -1, 16178, 16175, 16177, -1, 16158, 16156, 16180, -1, 16162, 16170, 16158, -1, 16166, 16165, 16181, -1, 16182, 8692, 16170, -1, 16182, 16170, 16162, -1, 16182, 16162, 16166, -1, 16183, 16184, 16185, -1, 16183, 16181, 16184, -1, 16183, 16166, 16181, -1, 16183, 16182, 16166, -1, 16186, 8692, 16182, -1, 16187, 16185, 8696, -1, 16187, 8696, 8692, -1, 16187, 16183, 16185, -1, 16187, 16182, 16183, -1, 16187, 8692, 16186, -1, 16187, 16186, 16182, -1, 16188, 16176, 16171, -1, 16188, 16156, 16177, -1, 16188, 16171, 11758, -1, 16188, 16177, 16176, -1, 16189, 16156, 16188, -1, 16189, 16188, 11758, -1, 16190, 16180, 16156, -1, 16190, 16156, 16189, -1, 16190, 16189, 11758, -1, 16160, 11758, 11748, -1, 16160, 16158, 16180, -1, 16160, 16180, 16190, -1, 16160, 16190, 11758, -1, 16161, 16160, 11748, -1, 16155, 16177, 16156, -1, 16155, 16178, 16177, -1, 16155, 8683, 16178, -1, 16191, 16192, 16193, -1, 16191, 8709, 16192, -1, 16194, 16193, 16195, -1, 16194, 16191, 16193, -1, 16196, 16197, 16198, -1, 16196, 16199, 16195, -1, 16196, 16195, 16197, -1, 16200, 16198, 11781, -1, 16200, 16196, 16198, -1, 16201, 11780, 16202, -1, 16201, 11781, 11780, -1, 16201, 16202, 16203, -1, 16201, 16200, 11781, -1, 16204, 16200, 16201, -1, 16204, 16196, 16200, -1, 16204, 16201, 16203, -1, 16204, 16203, 16199, -1, 16204, 16199, 16196, -1, 16205, 8709, 16191, -1, 16205, 16191, 16194, -1, 16206, 8716, 8709, -1, 16206, 16205, 16194, -1, 16206, 16207, 8716, -1, 16206, 16195, 16207, -1, 16206, 16194, 16195, -1, 16206, 8709, 16205, -1, 16208, 16209, 11792, -1, 16208, 11792, 11786, -1, 16210, 16211, 16209, -1, 16210, 16212, 16211, -1, 16210, 16209, 16208, -1, 16213, 16210, 16208, -1, 16214, 16210, 16213, -1, 16214, 16212, 16210, -1, 16215, 8709, 8708, -1, 16215, 16216, 16212, -1, 16215, 8708, 16216, -1, 16215, 16212, 16214, -1, 16195, 16193, 16217, -1, 16199, 16207, 16195, -1, 16203, 16202, 16218, -1, 16219, 8716, 16207, -1, 16219, 16207, 16199, -1, 16219, 16199, 16203, -1, 16220, 16221, 16222, -1, 16220, 16218, 16221, -1, 16220, 16203, 16218, -1, 16220, 16219, 16203, -1, 16223, 8716, 16219, -1, 16224, 16222, 8718, -1, 16224, 8718, 8716, -1, 16224, 16220, 16222, -1, 16224, 16219, 16220, -1, 16224, 8716, 16223, -1, 16224, 16223, 16219, -1, 16225, 16213, 16208, -1, 16225, 16193, 16214, -1, 16225, 16208, 11786, -1, 16225, 16214, 16213, -1, 16226, 16193, 16225, -1, 16226, 16225, 11786, -1, 16227, 16217, 16193, -1, 16227, 16193, 16226, -1, 16227, 16226, 11786, -1, 16197, 11786, 11781, -1, 16197, 16195, 16217, -1, 16197, 16217, 16227, -1, 16197, 16227, 11786, -1, 16198, 16197, 11781, -1, 16192, 16214, 16193, -1, 16192, 16215, 16214, -1, 16192, 8709, 16215, -1, 16228, 8849, 16229, -1, 16230, 16231, 16232, -1, 16230, 16228, 16231, -1, 16233, 16234, 16232, -1, 16233, 16235, 16236, -1, 16233, 16232, 16235, -1, 16237, 16236, 11684, -1, 16237, 16233, 16236, -1, 16238, 11683, 16239, -1, 16238, 11684, 11683, -1, 16238, 16239, 16240, -1, 16238, 16237, 11684, -1, 16241, 16237, 16238, -1, 16241, 16233, 16237, -1, 16241, 16238, 16240, -1, 16241, 16240, 16234, -1, 16241, 16234, 16233, -1, 16242, 8849, 16228, -1, 16242, 16228, 16230, -1, 16243, 8858, 8849, -1, 16243, 16242, 16230, -1, 16243, 16244, 8858, -1, 16243, 16232, 16244, -1, 16243, 16230, 16232, -1, 16243, 8849, 16242, -1, 16245, 16246, 11705, -1, 16245, 11705, 11697, -1, 16247, 16248, 16246, -1, 16247, 16249, 16248, -1, 16247, 16246, 16245, -1, 16250, 16247, 16245, -1, 16251, 16247, 16250, -1, 16251, 16249, 16247, -1, 16252, 8849, 8851, -1, 16252, 16253, 16249, -1, 16252, 8851, 16253, -1, 16252, 16249, 16251, -1, 16232, 16231, 16254, -1, 16234, 16244, 16232, -1, 16240, 16239, 16255, -1, 16256, 8858, 16244, -1, 16256, 16244, 16234, -1, 16256, 16234, 16240, -1, 16257, 16258, 16259, -1, 16257, 16255, 16258, -1, 16257, 16240, 16255, -1, 16257, 16256, 16240, -1, 16260, 8858, 16256, -1, 16261, 16259, 8862, -1, 16261, 8862, 8858, -1, 16261, 16257, 16259, -1, 16261, 16256, 16257, -1, 16261, 8858, 16260, -1, 16261, 16260, 16256, -1, 16262, 16250, 16245, -1, 16262, 16231, 16251, -1, 16262, 16245, 11697, -1, 16262, 16251, 16250, -1, 16263, 16231, 16262, -1, 16263, 16262, 11697, -1, 16264, 16254, 16231, -1, 16264, 16231, 16263, -1, 16264, 16263, 11697, -1, 16235, 11697, 11684, -1, 16235, 16254, 16264, -1, 16235, 16232, 16254, -1, 16235, 16264, 11697, -1, 16236, 16235, 11684, -1, 16229, 16251, 16231, -1, 16229, 16252, 16251, -1, 16229, 8849, 16252, -1, 16228, 16229, 16231, -1, 16265, 9029, 16266, -1, 16267, 16268, 16269, -1, 16267, 16265, 16268, -1, 16270, 16269, 16271, -1, 16270, 16272, 16269, -1, 16270, 16271, 16273, -1, 16274, 16273, 11717, -1, 16274, 16270, 16273, -1, 16275, 16274, 11717, -1, 16275, 11717, 11716, -1, 16275, 11716, 16276, -1, 16275, 16276, 16277, -1, 16278, 16270, 16274, -1, 16278, 16275, 16277, -1, 16278, 16274, 16275, -1, 16278, 16277, 16272, -1, 16278, 16272, 16270, -1, 16279, 9029, 16265, -1, 16279, 16265, 16267, -1, 16280, 16279, 16267, -1, 16280, 9036, 9029, -1, 16280, 16281, 9036, -1, 16280, 16269, 16281, -1, 16280, 16267, 16269, -1, 16280, 9029, 16279, -1, 16282, 16283, 11731, -1, 16282, 11731, 11728, -1, 16284, 16285, 16283, -1, 16284, 16286, 16285, -1, 16284, 16283, 16282, -1, 16287, 16284, 16282, -1, 16288, 16284, 16287, -1, 16288, 16286, 16284, -1, 16289, 16290, 16286, -1, 16289, 9028, 16290, -1, 16289, 9029, 9028, -1, 16289, 16286, 16288, -1, 16269, 16268, 16291, -1, 16272, 16281, 16269, -1, 16277, 16276, 16292, -1, 16293, 9036, 16281, -1, 16293, 16281, 16272, -1, 16293, 16272, 16277, -1, 16294, 16295, 16296, -1, 16294, 16292, 16295, -1, 16294, 16277, 16292, -1, 16294, 16293, 16277, -1, 16297, 9036, 16293, -1, 16298, 16296, 9038, -1, 16298, 9038, 9036, -1, 16298, 16294, 16296, -1, 16298, 16293, 16294, -1, 16298, 9036, 16297, -1, 16298, 16297, 16293, -1, 16299, 16287, 16282, -1, 16299, 16268, 16288, -1, 16299, 16282, 11728, -1, 16299, 16288, 16287, -1, 16300, 16268, 16299, -1, 16300, 16299, 11728, -1, 16301, 16291, 16268, -1, 16301, 16268, 16300, -1, 16301, 16300, 11728, -1, 16271, 11728, 11717, -1, 16271, 16269, 16291, -1, 16271, 16291, 16301, -1, 16271, 16301, 11728, -1, 16273, 16271, 11717, -1, 16266, 16288, 16268, -1, 16266, 16289, 16288, -1, 16266, 9029, 16289, -1, 16265, 16266, 16268, -1, 16302, 16303, 16304, -1, 16302, 9073, 16303, -1, 16305, 16304, 16306, -1, 16305, 16302, 16304, -1, 16307, 16308, 16309, -1, 16307, 16310, 16306, -1, 16307, 16306, 16308, -1, 16311, 16309, 11804, -1, 16311, 16307, 16309, -1, 16312, 11803, 16313, -1, 16312, 11804, 11803, -1, 16312, 16313, 16314, -1, 16312, 16311, 11804, -1, 16315, 16311, 16312, -1, 16315, 16307, 16311, -1, 16315, 16312, 16314, -1, 16315, 16314, 16310, -1, 16315, 16310, 16307, -1, 16316, 9073, 16302, -1, 16316, 16302, 16305, -1, 16317, 9082, 9073, -1, 16317, 16316, 16305, -1, 16317, 16318, 9082, -1, 16317, 16306, 16318, -1, 16317, 16305, 16306, -1, 16317, 9073, 16316, -1, 16319, 16320, 11825, -1, 16319, 11825, 11816, -1, 16321, 16322, 16320, -1, 16321, 16323, 16322, -1, 16321, 16320, 16319, -1, 16324, 16321, 16319, -1, 16325, 16321, 16324, -1, 16325, 16323, 16321, -1, 16326, 9073, 9075, -1, 16326, 16327, 16323, -1, 16326, 9075, 16327, -1, 16326, 16323, 16325, -1, 16306, 16304, 16328, -1, 16310, 16318, 16306, -1, 16314, 16313, 16329, -1, 16330, 9082, 16318, -1, 16330, 16318, 16310, -1, 16330, 16310, 16314, -1, 16331, 16332, 16333, -1, 16331, 16329, 16332, -1, 16331, 16314, 16329, -1, 16331, 16330, 16314, -1, 16334, 9082, 16330, -1, 16335, 16333, 9086, -1, 16335, 9086, 9082, -1, 16335, 16331, 16333, -1, 16335, 16330, 16331, -1, 16335, 9082, 16334, -1, 16335, 16334, 16330, -1, 16336, 16324, 16319, -1, 16336, 16304, 16325, -1, 16336, 16319, 11816, -1, 16336, 16325, 16324, -1, 16337, 16304, 16336, -1, 16337, 16336, 11816, -1, 16338, 16328, 16304, -1, 16338, 16304, 16337, -1, 16338, 16337, 11816, -1, 16308, 11816, 11804, -1, 16308, 16306, 16328, -1, 16308, 16328, 16338, -1, 16308, 16338, 11816, -1, 16309, 16308, 11804, -1, 16303, 16325, 16304, -1, 16303, 16326, 16325, -1, 16303, 9073, 16326, -1, 16339, 11105, 16340, -1, 16341, 16342, 16343, -1, 16341, 16339, 16342, -1, 16344, 16345, 16343, -1, 16344, 16346, 16347, -1, 16344, 16343, 16346, -1, 16348, 16347, 11839, -1, 16348, 16344, 16347, -1, 16349, 11838, 16350, -1, 16349, 11839, 11838, -1, 16349, 16350, 16351, -1, 16349, 16348, 11839, -1, 16352, 16348, 16349, -1, 16352, 16344, 16348, -1, 16352, 16349, 16351, -1, 16352, 16351, 16345, -1, 16352, 16345, 16344, -1, 16353, 11105, 16339, -1, 16353, 16339, 16341, -1, 16354, 11112, 11105, -1, 16354, 16353, 16341, -1, 16354, 16355, 11112, -1, 16354, 16343, 16355, -1, 16354, 16341, 16343, -1, 16354, 11105, 16353, -1, 16356, 16357, 11848, -1, 16356, 11848, 11844, -1, 16358, 16359, 16357, -1, 16358, 16360, 16359, -1, 16358, 16357, 16356, -1, 16361, 16358, 16356, -1, 16362, 16358, 16361, -1, 16362, 16360, 16358, -1, 16363, 11105, 11104, -1, 16363, 16364, 16360, -1, 16363, 11104, 16364, -1, 16363, 16360, 16362, -1, 16343, 16342, 16365, -1, 16345, 16355, 16343, -1, 16351, 16350, 16366, -1, 16367, 11112, 16355, -1, 16367, 16355, 16345, -1, 16367, 16345, 16351, -1, 16368, 16369, 16370, -1, 16368, 16366, 16369, -1, 16368, 16351, 16366, -1, 16368, 16367, 16351, -1, 16371, 11112, 16367, -1, 16372, 16370, 11114, -1, 16372, 11114, 11112, -1, 16372, 16368, 16370, -1, 16372, 16367, 16368, -1, 16372, 11112, 16371, -1, 16372, 16371, 16367, -1, 16373, 16361, 16356, -1, 16373, 16342, 16362, -1, 16373, 16356, 11844, -1, 16373, 16362, 16361, -1, 16374, 16342, 16373, -1, 16374, 16373, 11844, -1, 16375, 16365, 16342, -1, 16375, 16342, 16374, -1, 16375, 16374, 11844, -1, 16346, 11844, 11839, -1, 16346, 16365, 16375, -1, 16346, 16343, 16365, -1, 16346, 16375, 11844, -1, 16347, 16346, 11839, -1, 16340, 16362, 16342, -1, 16340, 16363, 16362, -1, 16340, 11105, 16363, -1, 16339, 16340, 16342, -1, 16376, 16377, 16378, -1, 16376, 9247, 16377, -1, 16379, 16378, 16380, -1, 16379, 16376, 16378, -1, 16381, 16382, 16380, -1, 16381, 16383, 16384, -1, 16381, 16380, 16383, -1, 16385, 16384, 11914, -1, 16385, 16381, 16384, -1, 16386, 11913, 16387, -1, 16386, 11914, 11913, -1, 16386, 16387, 16388, -1, 16386, 16385, 11914, -1, 16389, 16385, 16386, -1, 16389, 16381, 16385, -1, 16389, 16386, 16388, -1, 16389, 16388, 16382, -1, 16389, 16382, 16381, -1, 16390, 9247, 16376, -1, 16390, 16376, 16379, -1, 16391, 9256, 9247, -1, 16391, 16390, 16379, -1, 16391, 16392, 9256, -1, 16391, 16380, 16392, -1, 16391, 16379, 16380, -1, 16391, 9247, 16390, -1, 16393, 16394, 11926, -1, 16393, 11926, 11920, -1, 16395, 16396, 16394, -1, 16395, 16397, 16396, -1, 16395, 16394, 16393, -1, 16398, 16395, 16393, -1, 16399, 16395, 16398, -1, 16399, 16397, 16395, -1, 16400, 9247, 9249, -1, 16400, 16401, 16397, -1, 16400, 9249, 16401, -1, 16400, 16397, 16399, -1, 16380, 16378, 16402, -1, 16382, 16392, 16380, -1, 16388, 16387, 16403, -1, 16404, 9256, 16392, -1, 16404, 16392, 16382, -1, 16404, 16382, 16388, -1, 16405, 16406, 16407, -1, 16405, 16403, 16406, -1, 16405, 16388, 16403, -1, 16405, 16404, 16388, -1, 16408, 9256, 16404, -1, 16409, 16407, 9260, -1, 16409, 9260, 9256, -1, 16409, 16405, 16407, -1, 16409, 16404, 16405, -1, 16409, 9256, 16408, -1, 16409, 16408, 16404, -1, 16410, 16398, 16393, -1, 16410, 16378, 16399, -1, 16410, 16393, 11920, -1, 16410, 16399, 16398, -1, 16411, 16378, 16410, -1, 16411, 16410, 11920, -1, 16412, 16402, 16378, -1, 16412, 16378, 16411, -1, 16412, 16411, 11920, -1, 16383, 11920, 11914, -1, 16383, 16402, 16412, -1, 16383, 16380, 16402, -1, 16383, 16412, 11920, -1, 16384, 16383, 11914, -1, 16377, 16399, 16378, -1, 16377, 16400, 16399, -1, 16377, 9247, 16400, -1, 16413, 16414, 16415, -1, 16413, 9273, 16414, -1, 16416, 16415, 16417, -1, 16416, 16413, 16415, -1, 16418, 16419, 16420, -1, 16418, 16421, 16417, -1, 16418, 16417, 16419, -1, 16422, 16420, 11936, -1, 16422, 16418, 16420, -1, 16423, 11935, 16424, -1, 16423, 11936, 11935, -1, 16423, 16424, 16425, -1, 16423, 16422, 11936, -1, 16426, 16422, 16423, -1, 16426, 16418, 16422, -1, 16426, 16423, 16425, -1, 16426, 16425, 16421, -1, 16426, 16421, 16418, -1, 16427, 9273, 16413, -1, 16427, 16413, 16416, -1, 16428, 9280, 9273, -1, 16428, 16427, 16416, -1, 16428, 16429, 9280, -1, 16428, 16417, 16429, -1, 16428, 16416, 16417, -1, 16428, 9273, 16427, -1, 16430, 16431, 11945, -1, 16430, 11945, 11940, -1, 16432, 16433, 16431, -1, 16432, 16434, 16433, -1, 16432, 16431, 16430, -1, 16435, 16432, 16430, -1, 16436, 16432, 16435, -1, 16436, 16434, 16432, -1, 16437, 9273, 9272, -1, 16437, 16438, 16434, -1, 16437, 9272, 16438, -1, 16437, 16434, 16436, -1, 16417, 16415, 16439, -1, 16421, 16429, 16417, -1, 16425, 16424, 16440, -1, 16441, 9280, 16429, -1, 16441, 16429, 16421, -1, 16441, 16421, 16425, -1, 16442, 16443, 16444, -1, 16442, 16440, 16443, -1, 16442, 16425, 16440, -1, 16442, 16441, 16425, -1, 16445, 9280, 16441, -1, 16446, 16444, 9282, -1, 16446, 9282, 9280, -1, 16446, 16442, 16444, -1, 16446, 16441, 16442, -1, 16446, 9280, 16445, -1, 16446, 16445, 16441, -1, 16447, 16435, 16430, -1, 16447, 16415, 16436, -1, 16447, 16430, 11940, -1, 16447, 16436, 16435, -1, 16448, 16415, 16447, -1, 16448, 16447, 11940, -1, 16449, 16439, 16415, -1, 16449, 16415, 16448, -1, 16449, 16448, 11940, -1, 16419, 11940, 11936, -1, 16419, 16417, 16439, -1, 16419, 16439, 16449, -1, 16419, 16449, 11940, -1, 16420, 16419, 11936, -1, 16414, 16436, 16415, -1, 16414, 16437, 16436, -1, 16414, 9273, 16437, -1, 16450, 9379, 16451, -1, 16452, 16453, 16454, -1, 16452, 16450, 16453, -1, 16455, 16456, 16457, -1, 16455, 16458, 16454, -1, 16455, 16454, 16456, -1, 16459, 16457, 11957, -1, 16459, 16455, 16457, -1, 16460, 11956, 16461, -1, 16460, 11957, 11956, -1, 16460, 16461, 16462, -1, 16460, 16459, 11957, -1, 16463, 16459, 16460, -1, 16463, 16455, 16459, -1, 16463, 16460, 16462, -1, 16463, 16462, 16458, -1, 16463, 16458, 16455, -1, 16464, 9379, 16450, -1, 16464, 16450, 16452, -1, 16465, 9388, 9379, -1, 16465, 16464, 16452, -1, 16465, 16466, 9388, -1, 16465, 16454, 16466, -1, 16465, 16452, 16454, -1, 16465, 9379, 16464, -1, 16467, 16468, 11965, -1, 16467, 11965, 11964, -1, 16469, 16470, 16468, -1, 16469, 16471, 16470, -1, 16469, 16468, 16467, -1, 16472, 16469, 16467, -1, 16473, 16469, 16472, -1, 16473, 16471, 16469, -1, 16474, 9379, 9381, -1, 16474, 16475, 16471, -1, 16474, 9381, 16475, -1, 16474, 16471, 16473, -1, 16454, 16453, 16476, -1, 16458, 16466, 16454, -1, 16462, 16461, 16477, -1, 16478, 9388, 16466, -1, 16478, 16466, 16458, -1, 16478, 16458, 16462, -1, 16479, 16480, 16481, -1, 16479, 16477, 16480, -1, 16479, 16462, 16477, -1, 16479, 16478, 16462, -1, 16482, 9388, 16478, -1, 16483, 16481, 9392, -1, 16483, 9392, 9388, -1, 16483, 16479, 16481, -1, 16483, 16478, 16479, -1, 16483, 9388, 16482, -1, 16483, 16482, 16478, -1, 16484, 16472, 16467, -1, 16484, 16453, 16473, -1, 16484, 16467, 11964, -1, 16484, 16473, 16472, -1, 16485, 16453, 16484, -1, 16485, 16484, 11964, -1, 16486, 16476, 16453, -1, 16486, 16453, 16485, -1, 16486, 16485, 11964, -1, 16456, 11964, 11957, -1, 16456, 16454, 16476, -1, 16456, 16476, 16486, -1, 16456, 16486, 11964, -1, 16457, 16456, 11957, -1, 16451, 16473, 16453, -1, 16451, 16474, 16473, -1, 16451, 9379, 16474, -1, 16450, 16451, 16453, -1, 16487, 9521, 16488, -1, 16489, 16490, 16491, -1, 16489, 16487, 16490, -1, 16492, 16493, 16491, -1, 16492, 16494, 16495, -1, 16492, 16491, 16494, -1, 16496, 16495, 11978, -1, 16496, 16492, 16495, -1, 16497, 11977, 16498, -1, 16497, 11978, 11977, -1, 16497, 16498, 16499, -1, 16497, 16496, 11978, -1, 16500, 16496, 16497, -1, 16500, 16492, 16496, -1, 16500, 16497, 16499, -1, 16500, 16499, 16493, -1, 16500, 16493, 16492, -1, 16501, 9521, 16487, -1, 16501, 16487, 16489, -1, 16502, 9528, 9521, -1, 16502, 16501, 16489, -1, 16502, 16503, 9528, -1, 16502, 16491, 16503, -1, 16502, 16489, 16491, -1, 16502, 9521, 16501, -1, 16504, 16505, 11988, -1, 16504, 11988, 11983, -1, 16506, 16507, 16505, -1, 16506, 16508, 16507, -1, 16506, 16505, 16504, -1, 16509, 16506, 16504, -1, 16510, 16506, 16509, -1, 16510, 16508, 16506, -1, 16511, 9521, 9520, -1, 16511, 16512, 16508, -1, 16511, 9520, 16512, -1, 16511, 16508, 16510, -1, 16491, 16490, 16513, -1, 16493, 16503, 16491, -1, 16499, 16498, 16514, -1, 16515, 9528, 16503, -1, 16515, 16503, 16493, -1, 16515, 16493, 16499, -1, 16516, 16517, 16518, -1, 16516, 16514, 16517, -1, 16516, 16499, 16514, -1, 16516, 16515, 16499, -1, 16519, 9528, 16515, -1, 16520, 16518, 9530, -1, 16520, 9530, 9528, -1, 16520, 16516, 16518, -1, 16520, 16515, 16516, -1, 16520, 9528, 16519, -1, 16520, 16519, 16515, -1, 16521, 16509, 16504, -1, 16521, 16490, 16510, -1, 16521, 16504, 11983, -1, 16521, 16510, 16509, -1, 16522, 16490, 16521, -1, 16522, 16521, 11983, -1, 16523, 16513, 16490, -1, 16523, 16490, 16522, -1, 16523, 16522, 11983, -1, 16494, 11983, 11978, -1, 16494, 16513, 16523, -1, 16494, 16491, 16513, -1, 16494, 16523, 11983, -1, 16495, 16494, 11978, -1, 16488, 16510, 16490, -1, 16488, 16511, 16510, -1, 16488, 9521, 16511, -1, 16487, 16488, 16490, -1, 16524, 16525, 16526, -1, 16524, 9603, 16525, -1, 16527, 16526, 16528, -1, 16527, 16524, 16526, -1, 16529, 16530, 16531, -1, 16529, 16532, 16528, -1, 16529, 16528, 16530, -1, 16533, 16531, 12043, -1, 16533, 16529, 16531, -1, 16534, 12042, 16535, -1, 16534, 12043, 12042, -1, 16534, 16535, 16536, -1, 16534, 16533, 12043, -1, 16537, 16533, 16534, -1, 16537, 16529, 16533, -1, 16537, 16534, 16536, -1, 16537, 16536, 16532, -1, 16537, 16532, 16529, -1, 16538, 9603, 16524, -1, 16538, 16524, 16527, -1, 16539, 9612, 9603, -1, 16539, 16538, 16527, -1, 16539, 16540, 9612, -1, 16539, 16528, 16540, -1, 16539, 16527, 16528, -1, 16539, 9603, 16538, -1, 16541, 16542, 12049, -1, 16541, 12049, 12048, -1, 16543, 16544, 16542, -1, 16543, 16545, 16544, -1, 16543, 16542, 16541, -1, 16546, 16543, 16541, -1, 16547, 16543, 16546, -1, 16547, 16545, 16543, -1, 16548, 9603, 9605, -1, 16548, 16549, 16545, -1, 16548, 9605, 16549, -1, 16548, 16545, 16547, -1, 16528, 16526, 16550, -1, 16532, 16540, 16528, -1, 16536, 16535, 16551, -1, 16552, 9612, 16540, -1, 16552, 16540, 16532, -1, 16552, 16532, 16536, -1, 16553, 16554, 16555, -1, 16553, 16551, 16554, -1, 16553, 16536, 16551, -1, 16553, 16552, 16536, -1, 16556, 9612, 16552, -1, 16557, 16555, 9616, -1, 16557, 9616, 9612, -1, 16557, 16553, 16555, -1, 16557, 16552, 16553, -1, 16557, 9612, 16556, -1, 16557, 16556, 16552, -1, 16558, 16546, 16541, -1, 16558, 16526, 16547, -1, 16558, 16541, 12048, -1, 16558, 16547, 16546, -1, 16559, 16526, 16558, -1, 16559, 16558, 12048, -1, 16560, 16550, 16526, -1, 16560, 16526, 16559, -1, 16560, 16559, 12048, -1, 16530, 12048, 12043, -1, 16530, 16528, 16550, -1, 16530, 16550, 16560, -1, 16530, 16560, 12048, -1, 16531, 16530, 12043, -1, 16525, 16547, 16526, -1, 16525, 16548, 16547, -1, 16525, 9603, 16548, -1, 16561, 9769, 16562, -1, 16563, 16564, 16565, -1, 16563, 16561, 16564, -1, 16566, 16565, 16567, -1, 16566, 16568, 16565, -1, 16566, 16567, 16569, -1, 16570, 16569, 11669, -1, 16570, 16566, 16569, -1, 16571, 16570, 11669, -1, 16571, 11669, 12055, -1, 16571, 12055, 16572, -1, 16571, 16572, 16573, -1, 16574, 16566, 16570, -1, 16574, 16571, 16573, -1, 16574, 16570, 16571, -1, 16574, 16573, 16568, -1, 16574, 16568, 16566, -1, 16575, 9769, 16561, -1, 16575, 16561, 16563, -1, 16576, 16575, 16563, -1, 16576, 9776, 9769, -1, 16576, 16577, 9776, -1, 16576, 16565, 16577, -1, 16576, 16563, 16565, -1, 16576, 9769, 16575, -1, 16578, 16579, 11675, -1, 16578, 11675, 11670, -1, 16580, 16581, 16579, -1, 16580, 16582, 16581, -1, 16580, 16579, 16578, -1, 16583, 16580, 16578, -1, 16584, 16580, 16583, -1, 16584, 16582, 16580, -1, 16585, 16586, 16582, -1, 16585, 9768, 16586, -1, 16585, 9769, 9768, -1, 16585, 16582, 16584, -1, 16565, 16564, 16587, -1, 16568, 16577, 16565, -1, 16573, 16572, 16588, -1, 16589, 9776, 16577, -1, 16589, 16577, 16568, -1, 16589, 16568, 16573, -1, 16590, 16591, 16592, -1, 16590, 16588, 16591, -1, 16590, 16573, 16588, -1, 16590, 16589, 16573, -1, 16593, 9776, 16589, -1, 16594, 16592, 9778, -1, 16594, 9778, 9776, -1, 16594, 16590, 16592, -1, 16594, 16589, 16590, -1, 16594, 9776, 16593, -1, 16594, 16593, 16589, -1, 16595, 16583, 16578, -1, 16595, 16564, 16584, -1, 16595, 16578, 11670, -1, 16595, 16584, 16583, -1, 16596, 16564, 16595, -1, 16596, 16595, 11670, -1, 16597, 16587, 16564, -1, 16597, 16564, 16596, -1, 16597, 16596, 11670, -1, 16567, 11670, 11669, -1, 16567, 16565, 16587, -1, 16567, 16587, 16597, -1, 16567, 16597, 11670, -1, 16569, 16567, 11669, -1, 16562, 16584, 16564, -1, 16562, 16585, 16584, -1, 16562, 9769, 16585, -1, 16561, 16562, 16564, -1, 16598, 16599, 16600, -1, 16598, 9919, 16599, -1, 16601, 16600, 16602, -1, 16601, 16598, 16600, -1, 16603, 16604, 16602, -1, 16603, 16605, 16606, -1, 16603, 16602, 16605, -1, 16607, 16606, 11998, -1, 16607, 16603, 16606, -1, 16608, 11997, 16609, -1, 16608, 11998, 11997, -1, 16608, 16609, 16610, -1, 16608, 16607, 11998, -1, 16611, 16607, 16608, -1, 16611, 16603, 16607, -1, 16611, 16608, 16610, -1, 16611, 16610, 16604, -1, 16611, 16604, 16603, -1, 16612, 9919, 16598, -1, 16612, 16598, 16601, -1, 16613, 9928, 9919, -1, 16613, 16612, 16601, -1, 16613, 16614, 9928, -1, 16613, 16602, 16614, -1, 16613, 16601, 16602, -1, 16613, 9919, 16612, -1, 16615, 16616, 12007, -1, 16615, 12007, 12004, -1, 16617, 16618, 16616, -1, 16617, 16619, 16618, -1, 16617, 16616, 16615, -1, 16620, 16617, 16615, -1, 16621, 16617, 16620, -1, 16621, 16619, 16617, -1, 16622, 9919, 9921, -1, 16622, 16623, 16619, -1, 16622, 9921, 16623, -1, 16622, 16619, 16621, -1, 16602, 16600, 16624, -1, 16604, 16614, 16602, -1, 16610, 16609, 16625, -1, 16626, 9928, 16614, -1, 16626, 16614, 16604, -1, 16626, 16604, 16610, -1, 16627, 16628, 16629, -1, 16627, 16625, 16628, -1, 16627, 16610, 16625, -1, 16627, 16626, 16610, -1, 16630, 9928, 16626, -1, 16631, 16629, 9932, -1, 16631, 9932, 9928, -1, 16631, 16627, 16629, -1, 16631, 16626, 16627, -1, 16631, 9928, 16630, -1, 16631, 16630, 16626, -1, 16632, 16620, 16615, -1, 16632, 16600, 16621, -1, 16632, 16615, 12004, -1, 16632, 16621, 16620, -1, 16633, 16600, 16632, -1, 16633, 16632, 12004, -1, 16634, 16624, 16600, -1, 16634, 16600, 16633, -1, 16634, 16633, 12004, -1, 16605, 12004, 11998, -1, 16605, 16624, 16634, -1, 16605, 16602, 16624, -1, 16605, 16634, 12004, -1, 16606, 16605, 11998, -1, 16599, 16621, 16600, -1, 16599, 16622, 16621, -1, 16599, 9919, 16622, -1, 16635, 16636, 16637, -1, 16635, 9969, 16636, -1, 16638, 16637, 16639, -1, 16638, 16635, 16637, -1, 16640, 16639, 16641, -1, 16640, 16642, 16639, -1, 16640, 16641, 16643, -1, 16644, 16643, 12018, -1, 16644, 16640, 16643, -1, 16645, 16644, 12018, -1, 16645, 12018, 12017, -1, 16645, 12017, 16646, -1, 16645, 16646, 16647, -1, 16648, 16640, 16644, -1, 16648, 16645, 16647, -1, 16648, 16644, 16645, -1, 16648, 16647, 16642, -1, 16648, 16642, 16640, -1, 16649, 9969, 16635, -1, 16649, 16635, 16638, -1, 16650, 16649, 16638, -1, 16650, 9976, 9969, -1, 16650, 16651, 9976, -1, 16650, 16639, 16651, -1, 16650, 16638, 16639, -1, 16650, 9969, 16649, -1, 16652, 16653, 12030, -1, 16652, 12030, 12028, -1, 16654, 16655, 16653, -1, 16654, 16656, 16655, -1, 16654, 16653, 16652, -1, 16657, 16654, 16652, -1, 16658, 16654, 16657, -1, 16658, 16656, 16654, -1, 16659, 16660, 16656, -1, 16659, 9968, 16660, -1, 16659, 9969, 9968, -1, 16659, 16656, 16658, -1, 16639, 16637, 16661, -1, 16642, 16651, 16639, -1, 16647, 16646, 16662, -1, 16663, 9976, 16651, -1, 16663, 16651, 16642, -1, 16663, 16642, 16647, -1, 16664, 16665, 16666, -1, 16664, 16662, 16665, -1, 16664, 16647, 16662, -1, 16664, 16663, 16647, -1, 16667, 9976, 16663, -1, 16668, 16666, 9978, -1, 16668, 9978, 9976, -1, 16668, 16664, 16666, -1, 16668, 16663, 16664, -1, 16668, 9976, 16667, -1, 16668, 16667, 16663, -1, 16669, 16657, 16652, -1, 16669, 16652, 12028, -1, 16669, 16637, 16658, -1, 16669, 16658, 16657, -1, 16670, 16669, 12028, -1, 16670, 16637, 16669, -1, 16671, 16661, 16637, -1, 16671, 16670, 12028, -1, 16671, 16637, 16670, -1, 16641, 12028, 12018, -1, 16641, 16639, 16661, -1, 16641, 16661, 16671, -1, 16641, 16671, 12028, -1, 16643, 16641, 12018, -1, 16636, 16658, 16637, -1, 16636, 16659, 16658, -1, 16636, 9969, 16659, -1, 16672, 16673, 16674, -1, 16672, 14818, 16673, -1, 16675, 16674, 16676, -1, 16675, 16672, 16674, -1, 16677, 16678, 16679, -1, 16677, 16680, 16676, -1, 16677, 16676, 16678, -1, 16681, 16679, 11707, -1, 16681, 16677, 16679, -1, 16682, 11709, 16683, -1, 16682, 11707, 11709, -1, 16682, 16683, 16684, -1, 16682, 16681, 11707, -1, 16685, 16681, 16682, -1, 16685, 16677, 16681, -1, 16685, 16682, 16684, -1, 16685, 16684, 16680, -1, 16685, 16680, 16677, -1, 16686, 14818, 16672, -1, 16686, 16672, 16675, -1, 16687, 14827, 14818, -1, 16687, 16686, 16675, -1, 16687, 16688, 14827, -1, 16687, 16676, 16688, -1, 16687, 16675, 16676, -1, 16687, 14818, 16686, -1, 16689, 16690, 11722, -1, 16689, 11722, 11710, -1, 16691, 16692, 16690, -1, 16691, 16693, 16692, -1, 16691, 16690, 16689, -1, 16694, 16691, 16689, -1, 16695, 16691, 16694, -1, 16695, 16693, 16691, -1, 16696, 14818, 14820, -1, 16696, 16697, 16693, -1, 16696, 14820, 16697, -1, 16696, 16693, 16695, -1, 16676, 16674, 16698, -1, 16680, 16688, 16676, -1, 16684, 16683, 16699, -1, 16700, 14827, 16688, -1, 16700, 16688, 16680, -1, 16700, 16680, 16684, -1, 16701, 16702, 16703, -1, 16701, 16699, 16702, -1, 16701, 16684, 16699, -1, 16701, 16700, 16684, -1, 16704, 14827, 16700, -1, 16705, 16703, 14831, -1, 16705, 14831, 14827, -1, 16705, 16701, 16703, -1, 16705, 16700, 16701, -1, 16705, 14827, 16704, -1, 16705, 16704, 16700, -1, 16706, 16694, 16689, -1, 16706, 16674, 16695, -1, 16706, 16689, 11710, -1, 16706, 16695, 16694, -1, 16707, 16674, 16706, -1, 16707, 16706, 11710, -1, 16708, 16698, 16674, -1, 16708, 16674, 16707, -1, 16708, 16707, 11710, -1, 16678, 11710, 11707, -1, 16678, 16676, 16698, -1, 16678, 16698, 16708, -1, 16678, 16708, 11710, -1, 16679, 16678, 11707, -1, 16673, 16695, 16674, -1, 16673, 16696, 16695, -1, 16673, 14818, 16696, -1, 16709, 16710, 16711, -1, 16709, 14844, 16710, -1, 16712, 16711, 16713, -1, 16712, 16709, 16711, -1, 16714, 16715, 16713, -1, 16714, 16716, 16717, -1, 16714, 16713, 16716, -1, 16718, 16717, 11732, -1, 16718, 16714, 16717, -1, 16719, 11734, 16720, -1, 16719, 11732, 11734, -1, 16719, 16720, 16721, -1, 16719, 16718, 11732, -1, 16722, 16718, 16719, -1, 16722, 16714, 16718, -1, 16722, 16719, 16721, -1, 16722, 16721, 16715, -1, 16722, 16715, 16714, -1, 16723, 14844, 16709, -1, 16723, 16709, 16712, -1, 16724, 14851, 14844, -1, 16724, 16723, 16712, -1, 16724, 16725, 14851, -1, 16724, 16713, 16725, -1, 16724, 16712, 16713, -1, 16724, 14844, 16723, -1, 16726, 16727, 11742, -1, 16726, 11742, 11735, -1, 16728, 16729, 16727, -1, 16728, 16730, 16729, -1, 16728, 16727, 16726, -1, 16731, 16728, 16726, -1, 16732, 16728, 16731, -1, 16732, 16730, 16728, -1, 16733, 14844, 14843, -1, 16733, 16734, 16730, -1, 16733, 14843, 16734, -1, 16733, 16730, 16732, -1, 16713, 16711, 16735, -1, 16715, 16725, 16713, -1, 16721, 16720, 16736, -1, 16737, 14851, 16725, -1, 16737, 16725, 16715, -1, 16737, 16715, 16721, -1, 16738, 16739, 16740, -1, 16738, 16736, 16739, -1, 16738, 16721, 16736, -1, 16738, 16737, 16721, -1, 16741, 14851, 16737, -1, 16742, 16740, 14853, -1, 16742, 14853, 14851, -1, 16742, 16738, 16740, -1, 16742, 16737, 16738, -1, 16742, 14851, 16741, -1, 16742, 16741, 16737, -1, 16743, 16731, 16726, -1, 16743, 16711, 16732, -1, 16743, 16726, 11735, -1, 16743, 16732, 16731, -1, 16744, 16711, 16743, -1, 16744, 16743, 11735, -1, 16745, 16735, 16711, -1, 16745, 16711, 16744, -1, 16745, 16744, 11735, -1, 16716, 11735, 11732, -1, 16716, 16735, 16745, -1, 16716, 16713, 16735, -1, 16716, 16745, 11735, -1, 16717, 16716, 11732, -1, 16710, 16732, 16711, -1, 16710, 16733, 16732, -1, 16710, 14844, 16733, -1, 16746, 16747, 16748, -1, 16746, 14854, 16747, -1, 16749, 16748, 16750, -1, 16749, 16746, 16748, -1, 16751, 16752, 16750, -1, 16751, 16753, 16754, -1, 16751, 16750, 16753, -1, 16755, 16754, 11692, -1, 16755, 16751, 16754, -1, 16756, 11694, 16757, -1, 16756, 11692, 11694, -1, 16756, 16757, 16758, -1, 16756, 16755, 11692, -1, 16759, 16755, 16756, -1, 16759, 16751, 16755, -1, 16759, 16756, 16758, -1, 16759, 16758, 16752, -1, 16759, 16752, 16751, -1, 16760, 14854, 16746, -1, 16760, 16746, 16749, -1, 16761, 14863, 14854, -1, 16761, 16760, 16749, -1, 16761, 16762, 14863, -1, 16761, 16750, 16762, -1, 16761, 16749, 16750, -1, 16761, 14854, 16760, -1, 16763, 16764, 11680, -1, 16763, 11680, 11682, -1, 16765, 16766, 16764, -1, 16765, 16767, 16766, -1, 16765, 16764, 16763, -1, 16768, 16765, 16763, -1, 16769, 16765, 16768, -1, 16769, 16767, 16765, -1, 16770, 14854, 14856, -1, 16770, 16771, 16767, -1, 16770, 14856, 16771, -1, 16770, 16767, 16769, -1, 16750, 16748, 16772, -1, 16752, 16762, 16750, -1, 16758, 16757, 16773, -1, 16774, 14863, 16762, -1, 16774, 16762, 16752, -1, 16774, 16752, 16758, -1, 16775, 16776, 16777, -1, 16775, 16773, 16776, -1, 16775, 16758, 16773, -1, 16775, 16774, 16758, -1, 16778, 14863, 16774, -1, 16779, 16777, 14867, -1, 16779, 14867, 14863, -1, 16779, 16775, 16777, -1, 16779, 16774, 16775, -1, 16779, 14863, 16778, -1, 16779, 16778, 16774, -1, 16780, 16768, 16763, -1, 16780, 16748, 16769, -1, 16780, 16763, 11682, -1, 16780, 16769, 16768, -1, 16781, 16748, 16780, -1, 16781, 16780, 11682, -1, 16782, 16772, 16748, -1, 16782, 16748, 16781, -1, 16782, 16781, 11682, -1, 16753, 11682, 11692, -1, 16753, 16772, 16782, -1, 16753, 16750, 16772, -1, 16753, 16782, 11682, -1, 16754, 16753, 11692, -1, 16747, 16769, 16748, -1, 16747, 16770, 16769, -1, 16747, 14854, 16770, -1, 16783, 14880, 16784, -1, 16785, 16786, 16787, -1, 16785, 16783, 16786, -1, 16788, 16787, 16789, -1, 16788, 16790, 16787, -1, 16788, 16789, 16791, -1, 16792, 16791, 11685, -1, 16792, 16788, 16791, -1, 16793, 16792, 11685, -1, 16793, 11685, 11687, -1, 16793, 11687, 16794, -1, 16793, 16794, 16795, -1, 16796, 16788, 16792, -1, 16796, 16793, 16795, -1, 16796, 16792, 16793, -1, 16796, 16795, 16790, -1, 16796, 16790, 16788, -1, 16797, 14880, 16783, -1, 16797, 16783, 16785, -1, 16798, 16797, 16785, -1, 16798, 14887, 14880, -1, 16798, 16799, 14887, -1, 16798, 16787, 16799, -1, 16798, 16785, 16787, -1, 16798, 14880, 16797, -1, 16800, 16801, 11698, -1, 16800, 11698, 11688, -1, 16802, 16803, 16801, -1, 16802, 16804, 16803, -1, 16802, 16801, 16800, -1, 16805, 16802, 16800, -1, 16806, 16802, 16805, -1, 16806, 16804, 16802, -1, 16807, 16808, 16804, -1, 16807, 14879, 16808, -1, 16807, 14880, 14879, -1, 16807, 16804, 16806, -1, 16787, 16786, 16809, -1, 16790, 16799, 16787, -1, 16795, 16794, 16810, -1, 16811, 14887, 16799, -1, 16811, 16799, 16790, -1, 16811, 16790, 16795, -1, 16812, 16813, 16814, -1, 16812, 16810, 16813, -1, 16812, 16795, 16810, -1, 16812, 16811, 16795, -1, 16815, 14887, 16811, -1, 16816, 16814, 14889, -1, 16816, 14889, 14887, -1, 16816, 16812, 16814, -1, 16816, 16811, 16812, -1, 16816, 14887, 16815, -1, 16816, 16815, 16811, -1, 16817, 16805, 16800, -1, 16817, 16786, 16806, -1, 16817, 16800, 11688, -1, 16817, 16806, 16805, -1, 16818, 16786, 16817, -1, 16818, 16817, 11688, -1, 16819, 16809, 16786, -1, 16819, 16786, 16818, -1, 16819, 16818, 11688, -1, 16789, 11688, 11685, -1, 16789, 16787, 16809, -1, 16789, 16809, 16819, -1, 16789, 16819, 11688, -1, 16791, 16789, 11685, -1, 16784, 16806, 16786, -1, 16784, 16807, 16806, -1, 16784, 14880, 16807, -1, 16783, 16784, 16786, -1, 16820, 16821, 16822, -1, 16820, 14892, 16821, -1, 16823, 16822, 16824, -1, 16823, 16820, 16822, -1, 16825, 16824, 16826, -1, 16825, 16827, 16824, -1, 16825, 16826, 16828, -1, 16829, 16828, 11883, -1, 16829, 16825, 16828, -1, 16830, 16829, 11883, -1, 16830, 11883, 11882, -1, 16830, 11882, 16831, -1, 16830, 16831, 16832, -1, 16833, 16825, 16829, -1, 16833, 16830, 16832, -1, 16833, 16829, 16830, -1, 16833, 16832, 16827, -1, 16833, 16827, 16825, -1, 16834, 14892, 16820, -1, 16834, 16820, 16823, -1, 16835, 16834, 16823, -1, 16835, 14899, 14892, -1, 16835, 16836, 14899, -1, 16835, 16824, 16836, -1, 16835, 16823, 16824, -1, 16835, 14892, 16834, -1, 16837, 16838, 11898, -1, 16837, 11898, 11890, -1, 16839, 16840, 16838, -1, 16839, 16841, 16840, -1, 16839, 16838, 16837, -1, 16842, 16839, 16837, -1, 16843, 16839, 16842, -1, 16843, 16841, 16839, -1, 16844, 16845, 16841, -1, 16844, 14891, 16845, -1, 16844, 14892, 14891, -1, 16844, 16841, 16843, -1, 16824, 16822, 16846, -1, 16827, 16836, 16824, -1, 16832, 16831, 16847, -1, 16848, 14899, 16836, -1, 16848, 16836, 16827, -1, 16848, 16827, 16832, -1, 16849, 16850, 16851, -1, 16849, 16847, 16850, -1, 16849, 16832, 16847, -1, 16849, 16848, 16832, -1, 16852, 14899, 16848, -1, 16853, 16851, 14901, -1, 16853, 14901, 14899, -1, 16853, 16849, 16851, -1, 16853, 16848, 16849, -1, 16853, 14899, 16852, -1, 16853, 16852, 16848, -1, 16854, 16842, 16837, -1, 16854, 16837, 11890, -1, 16854, 16822, 16843, -1, 16854, 16843, 16842, -1, 16855, 16854, 11890, -1, 16855, 16822, 16854, -1, 16856, 16846, 16822, -1, 16856, 16855, 11890, -1, 16856, 16822, 16855, -1, 16826, 11890, 11883, -1, 16826, 16824, 16846, -1, 16826, 16846, 16856, -1, 16826, 16856, 11890, -1, 16828, 16826, 11883, -1, 16821, 16843, 16822, -1, 16821, 16844, 16843, -1, 16821, 14892, 16844, -1, 16857, 16858, 16859, -1, 16857, 14902, 16858, -1, 16860, 16859, 16861, -1, 16860, 16857, 16859, -1, 16862, 16861, 16863, -1, 16862, 16864, 16861, -1, 16862, 16863, 16865, -1, 16866, 16865, 11850, -1, 16866, 16862, 16865, -1, 16867, 16866, 11850, -1, 16867, 11850, 11849, -1, 16867, 11849, 16868, -1, 16867, 16868, 16869, -1, 16870, 16862, 16866, -1, 16870, 16867, 16869, -1, 16870, 16866, 16867, -1, 16870, 16869, 16864, -1, 16870, 16864, 16862, -1, 16871, 14902, 16857, -1, 16871, 16857, 16860, -1, 16872, 16871, 16860, -1, 16872, 14911, 14902, -1, 16872, 16873, 14911, -1, 16872, 16861, 16873, -1, 16872, 16860, 16861, -1, 16872, 14902, 16871, -1, 16874, 16875, 11870, -1, 16874, 11870, 11859, -1, 16876, 16877, 16875, -1, 16876, 16878, 16877, -1, 16876, 16875, 16874, -1, 16879, 16876, 16874, -1, 16880, 16876, 16879, -1, 16880, 16878, 16876, -1, 16881, 16882, 16878, -1, 16881, 14904, 16882, -1, 16881, 14902, 14904, -1, 16881, 16878, 16880, -1, 16861, 16859, 16883, -1, 16864, 16873, 16861, -1, 16869, 16868, 16884, -1, 16885, 14911, 16873, -1, 16885, 16873, 16864, -1, 16885, 16864, 16869, -1, 16886, 16887, 16888, -1, 16886, 16884, 16887, -1, 16886, 16869, 16884, -1, 16886, 16885, 16869, -1, 16889, 14911, 16885, -1, 16890, 16888, 14915, -1, 16890, 14915, 14911, -1, 16890, 16886, 16888, -1, 16890, 16885, 16886, -1, 16890, 14911, 16889, -1, 16890, 16889, 16885, -1, 16891, 16879, 16874, -1, 16891, 16874, 11859, -1, 16891, 16859, 16880, -1, 16891, 16880, 16879, -1, 16892, 16891, 11859, -1, 16892, 16859, 16891, -1, 16893, 16883, 16859, -1, 16893, 16892, 11859, -1, 16893, 16859, 16892, -1, 16863, 11859, 11850, -1, 16863, 16861, 16883, -1, 16863, 16883, 16893, -1, 16863, 16893, 11859, -1, 16865, 16863, 11850, -1, 16858, 16880, 16859, -1, 16858, 16881, 16880, -1, 16858, 14902, 16881, -1, 16894, 14926, 16895, -1, 16896, 16897, 16898, -1, 16896, 16894, 16897, -1, 16899, 16900, 16901, -1, 16899, 16902, 16898, -1, 16899, 16898, 16900, -1, 16903, 16901, 11752, -1, 16903, 16899, 16901, -1, 16904, 11754, 16905, -1, 16904, 11752, 11754, -1, 16904, 16905, 16906, -1, 16904, 16903, 11752, -1, 16907, 16903, 16904, -1, 16907, 16899, 16903, -1, 16907, 16904, 16906, -1, 16907, 16906, 16902, -1, 16907, 16902, 16899, -1, 16908, 14926, 16894, -1, 16908, 16894, 16896, -1, 16909, 14935, 14926, -1, 16909, 16908, 16896, -1, 16909, 16910, 14935, -1, 16909, 16898, 16910, -1, 16909, 16896, 16898, -1, 16909, 14926, 16908, -1, 16911, 16912, 11765, -1, 16911, 11765, 11757, -1, 16913, 16914, 16912, -1, 16913, 16915, 16914, -1, 16913, 16912, 16911, -1, 16916, 16913, 16911, -1, 16917, 16913, 16916, -1, 16917, 16915, 16913, -1, 16918, 14926, 14928, -1, 16918, 16919, 16915, -1, 16918, 14928, 16919, -1, 16918, 16915, 16917, -1, 16898, 16897, 16920, -1, 16902, 16910, 16898, -1, 16906, 16905, 16921, -1, 16922, 14935, 16910, -1, 16922, 16910, 16902, -1, 16922, 16902, 16906, -1, 16923, 16924, 16925, -1, 16923, 16921, 16924, -1, 16923, 16906, 16921, -1, 16923, 16922, 16906, -1, 16926, 14935, 16922, -1, 16927, 16925, 14939, -1, 16927, 14939, 14935, -1, 16927, 16923, 16925, -1, 16927, 16922, 16923, -1, 16927, 14935, 16926, -1, 16927, 16926, 16922, -1, 16928, 16916, 16911, -1, 16928, 16897, 16917, -1, 16928, 16911, 11757, -1, 16928, 16917, 16916, -1, 16929, 16897, 16928, -1, 16929, 16928, 11757, -1, 16930, 16920, 16897, -1, 16930, 16897, 16929, -1, 16930, 16929, 11757, -1, 16900, 11757, 11752, -1, 16900, 16898, 16920, -1, 16900, 16920, 16930, -1, 16900, 16930, 11757, -1, 16901, 16900, 11752, -1, 16895, 16917, 16897, -1, 16895, 16918, 16917, -1, 16895, 14926, 16918, -1, 16894, 16895, 16897, -1, 16931, 14952, 16932, -1, 16933, 16934, 16935, -1, 16933, 16931, 16934, -1, 16936, 16935, 16937, -1, 16936, 16938, 16935, -1, 16936, 16937, 16939, -1, 16940, 16939, 11805, -1, 16940, 16936, 16939, -1, 16941, 16940, 11805, -1, 16941, 11805, 11807, -1, 16941, 11807, 16942, -1, 16941, 16942, 16943, -1, 16944, 16936, 16940, -1, 16944, 16941, 16943, -1, 16944, 16940, 16941, -1, 16944, 16943, 16938, -1, 16944, 16938, 16936, -1, 16945, 14952, 16931, -1, 16945, 16931, 16933, -1, 16946, 16945, 16933, -1, 16946, 14959, 14952, -1, 16946, 16947, 14959, -1, 16946, 16935, 16947, -1, 16946, 16933, 16935, -1, 16946, 14952, 16945, -1, 16948, 16949, 11831, -1, 16948, 11831, 11818, -1, 16950, 16951, 16949, -1, 16950, 16952, 16951, -1, 16950, 16949, 16948, -1, 16953, 16950, 16948, -1, 16954, 16950, 16953, -1, 16954, 16952, 16950, -1, 16955, 16956, 16952, -1, 16955, 14951, 16956, -1, 16955, 14952, 14951, -1, 16955, 16952, 16954, -1, 16935, 16934, 16957, -1, 16938, 16947, 16935, -1, 16943, 16942, 16958, -1, 16959, 14959, 16947, -1, 16959, 16947, 16938, -1, 16959, 16938, 16943, -1, 16960, 16961, 16962, -1, 16960, 16958, 16961, -1, 16960, 16943, 16958, -1, 16960, 16959, 16943, -1, 16963, 14959, 16959, -1, 16964, 16962, 14961, -1, 16964, 14961, 14959, -1, 16964, 16960, 16962, -1, 16964, 16959, 16960, -1, 16964, 14959, 16963, -1, 16964, 16963, 16959, -1, 16965, 16953, 16948, -1, 16965, 16934, 16954, -1, 16965, 16948, 11818, -1, 16965, 16954, 16953, -1, 16966, 16934, 16965, -1, 16966, 16965, 11818, -1, 16967, 16957, 16934, -1, 16967, 16934, 16966, -1, 16967, 16966, 11818, -1, 16937, 11818, 11805, -1, 16937, 16935, 16957, -1, 16937, 16957, 16967, -1, 16937, 16967, 11818, -1, 16939, 16937, 11805, -1, 16932, 16954, 16934, -1, 16932, 16955, 16954, -1, 16932, 14952, 16955, -1, 16931, 16932, 16934, -1, 16968, 10997, 16969, -1, 16970, 16971, 16972, -1, 16970, 16968, 16971, -1, 16973, 16972, 16974, -1, 16973, 16975, 16972, -1, 16973, 16974, 16976, -1, 16977, 16976, 11896, -1, 16977, 16973, 16976, -1, 16978, 16977, 11896, -1, 16978, 11896, 11895, -1, 16978, 11895, 16979, -1, 16978, 16979, 16980, -1, 16981, 16973, 16977, -1, 16981, 16978, 16980, -1, 16981, 16977, 16978, -1, 16981, 16980, 16975, -1, 16981, 16975, 16973, -1, 16982, 10997, 16968, -1, 16982, 16968, 16970, -1, 16983, 16982, 16970, -1, 16983, 11004, 10997, -1, 16983, 16984, 11004, -1, 16983, 16972, 16984, -1, 16983, 16970, 16972, -1, 16983, 10997, 16982, -1, 16985, 16986, 11909, -1, 16985, 11909, 11901, -1, 16987, 16988, 16986, -1, 16987, 16989, 16988, -1, 16987, 16986, 16985, -1, 16990, 16987, 16985, -1, 16991, 16987, 16990, -1, 16991, 16989, 16987, -1, 16992, 16993, 16989, -1, 16992, 10996, 16993, -1, 16992, 10997, 10996, -1, 16992, 16989, 16991, -1, 16972, 16971, 16994, -1, 16975, 16984, 16972, -1, 16980, 16979, 16995, -1, 16996, 11004, 16984, -1, 16996, 16984, 16975, -1, 16996, 16975, 16980, -1, 16997, 16998, 16999, -1, 16997, 16995, 16998, -1, 16997, 16980, 16995, -1, 16997, 16996, 16980, -1, 17000, 11004, 16996, -1, 17001, 16999, 11006, -1, 17001, 11006, 11004, -1, 17001, 16997, 16999, -1, 17001, 16996, 16997, -1, 17001, 11004, 17000, -1, 17001, 17000, 16996, -1, 17002, 16990, 16985, -1, 17002, 16971, 16991, -1, 17002, 16985, 11901, -1, 17002, 16991, 16990, -1, 17003, 16971, 17002, -1, 17003, 17002, 11901, -1, 17004, 16994, 16971, -1, 17004, 16971, 17003, -1, 17004, 17003, 11901, -1, 16974, 11901, 11896, -1, 16974, 16972, 16994, -1, 16974, 16994, 17004, -1, 16974, 17004, 11901, -1, 16976, 16974, 11896, -1, 16969, 16991, 16971, -1, 16969, 16992, 16991, -1, 16969, 10997, 16992, -1, 16968, 16969, 16971, -1, 17005, 17006, 17007, -1, 17005, 17008, 17009, -1, 17005, 17009, 11424, -1, 17010, 17011, 17012, -1, 17010, 17012, 17013, -1, 17010, 17013, 17014, -1, 17015, 17014, 17008, -1, 17015, 17010, 17014, -1, 17016, 17011, 17010, -1, 17016, 17010, 17015, -1, 17017, 17011, 17016, -1, 17017, 17016, 17015, -1, 17017, 17015, 17008, -1, 17018, 17017, 17008, -1, 17018, 17008, 17007, -1, 17018, 17019, 17011, -1, 17018, 17007, 17019, -1, 17018, 17011, 17017, -1, 17020, 17021, 11437, -1, 17020, 17022, 17021, -1, 17020, 11437, 11434, -1, 17023, 17024, 17022, -1, 17023, 17025, 17024, -1, 17026, 17023, 17022, -1, 17026, 17022, 17020, -1, 17027, 17012, 17028, -1, 17027, 17028, 17025, -1, 17027, 17023, 17026, -1, 17027, 17025, 17023, -1, 17029, 17027, 17026, -1, 17013, 17012, 17027, -1, 17013, 17027, 17029, -1, 17013, 17029, 17014, -1, 17008, 17014, 17030, -1, 17006, 11424, 11423, -1, 17031, 17032, 17033, -1, 17031, 17034, 17032, -1, 17031, 11423, 17034, -1, 17031, 17033, 17007, -1, 17031, 17006, 11423, -1, 17031, 17007, 17006, -1, 17019, 17035, 17011, -1, 17036, 17037, 17035, -1, 17036, 17033, 17037, -1, 17036, 17007, 17033, -1, 17036, 17035, 17019, -1, 17036, 17019, 17007, -1, 17038, 17026, 17020, -1, 17038, 17029, 17026, -1, 17038, 17020, 11434, -1, 17039, 17029, 17038, -1, 17039, 17038, 11434, -1, 17040, 17039, 11434, -1, 17041, 17014, 17029, -1, 17041, 17029, 17039, -1, 17041, 17039, 17040, -1, 17042, 11434, 11424, -1, 17042, 17030, 17014, -1, 17042, 17040, 11434, -1, 17042, 17014, 17041, -1, 17042, 17041, 17040, -1, 17043, 17008, 17030, -1, 17043, 17030, 17042, -1, 17043, 17042, 11424, -1, 17009, 17008, 17043, -1, 17009, 17043, 11424, -1, 17005, 11424, 17006, -1, 17005, 17007, 17008, -1, 17044, 17045, 17046, -1, 17047, 17048, 17049, -1, 17047, 3501, 17048, -1, 17044, 17050, 17045, -1, 17051, 11599, 11590, -1, 17051, 17046, 11599, -1, 11421, 4531, 4530, -1, 17052, 17053, 17054, -1, 17052, 3495, 3491, -1, 17052, 3491, 17055, -1, 17056, 17057, 17058, -1, 17056, 17058, 17059, -1, 17052, 17055, 17053, -1, 17060, 17061, 17062, -1, 17063, 17049, 17064, -1, 17063, 17047, 17049, -1, 17063, 3501, 17047, -1, 17060, 17065, 17061, -1, 17063, 3505, 3501, -1, 17066, 17050, 17044, -1, 17066, 17067, 17050, -1, 17068, 17046, 17051, -1, 17068, 17044, 17046, -1, 17069, 17070, 11473, -1, 17069, 11473, 11485, -1, 17071, 17051, 11590, -1, 17072, 17064, 17057, -1, 17072, 17057, 17056, -1, 17073, 17054, 17065, -1, 17074, 17075, 17076, -1, 17073, 17065, 17060, -1, 17074, 17059, 17075, -1, 17077, 17067, 17066, -1, 17077, 17062, 17067, -1, 17078, 17070, 17069, -1, 17078, 17079, 17070, -1, 17080, 17044, 17068, -1, 17080, 17066, 17044, -1, 17081, 17063, 17064, -1, 17082, 17068, 17051, -1, 17081, 17064, 17072, -1, 17081, 3505, 17063, -1, 17083, 17059, 17074, -1, 17083, 17056, 17059, -1, 17082, 17051, 17071, -1, 17084, 3499, 3495, -1, 17084, 17054, 17073, -1, 17084, 17052, 17054, -1, 17084, 3495, 17052, -1, 17085, 17071, 11590, -1, 17086, 17076, 17079, -1, 17085, 11590, 11582, -1, 17086, 17079, 17078, -1, 17087, 17060, 17062, -1, 17088, 11485, 11497, -1, 17088, 17069, 11485, -1, 17087, 17062, 17077, -1, 17089, 17072, 17056, -1, 17089, 17056, 17083, -1, 17090, 17066, 17080, -1, 17090, 17077, 17066, -1, 17091, 17076, 17086, -1, 17092, 17080, 17068, -1, 17091, 17074, 17076, -1, 17092, 17068, 17082, -1, 17093, 17085, 11582, -1, 17094, 11497, 11509, -1, 17095, 17082, 17071, -1, 17094, 17088, 11497, -1, 17095, 17071, 17085, -1, 17096, 17078, 17069, -1, 17096, 17069, 17088, -1, 17097, 17073, 17060, -1, 17097, 17060, 17087, -1, 17098, 3509, 3505, -1, 17098, 17081, 17072, -1, 17098, 3505, 17081, -1, 17098, 17072, 17089, -1, 17099, 17087, 17077, -1, 17099, 17077, 17090, -1, 17100, 17083, 17074, -1, 17101, 17090, 17080, -1, 17100, 17074, 17091, -1, 17101, 17080, 17092, -1, 17102, 17096, 17088, -1, 17102, 17088, 17094, -1, 17103, 17078, 17096, -1, 17104, 17085, 17093, -1, 17104, 17095, 17085, -1, 17105, 17092, 17082, -1, 17103, 17086, 17078, -1, 17105, 17082, 17095, -1, 17106, 17094, 11509, -1, 17107, 3503, 3499, -1, 17107, 3499, 17084, -1, 17107, 17084, 17073, -1, 17107, 17073, 17097, -1, 17108, 17083, 17100, -1, 17108, 17089, 17083, -1, 17109, 17097, 17087, -1, 17109, 17087, 17099, -1, 17110, 17103, 17096, -1, 17111, 17099, 17090, -1, 17110, 17096, 17102, -1, 17111, 17090, 17101, -1, 17112, 17086, 17103, -1, 17113, 11582, 11571, -1, 17112, 17091, 17086, -1, 17113, 17093, 11582, -1, 17114, 17102, 17094, -1, 17115, 17105, 17095, -1, 17115, 17095, 17104, -1, 17114, 17094, 17106, -1, 17116, 17106, 11509, -1, 17117, 17092, 17105, -1, 17117, 17101, 17092, -1, 17116, 11509, 11517, -1, 17118, 17098, 17089, -1, 17118, 3418, 3509, -1, 17119, 3503, 17107, -1, 17119, 17097, 17109, -1, 17118, 17089, 17108, -1, 17119, 17107, 17097, -1, 17118, 3509, 17098, -1, 17120, 17112, 17103, -1, 17121, 17109, 17099, -1, 17121, 17099, 17111, -1, 17120, 17103, 17110, -1, 17122, 17091, 17112, -1, 17123, 17104, 17093, -1, 17123, 17093, 17113, -1, 17122, 17100, 17091, -1, 17124, 17102, 17114, -1, 17124, 17110, 17102, -1, 17125, 17105, 17115, -1, 17125, 17117, 17105, -1, 17126, 17111, 17101, -1, 17127, 17116, 11517, -1, 17126, 17101, 17117, -1, 17126, 17121, 17111, -1, 17128, 17114, 17106, -1, 17129, 3507, 3503, -1, 17128, 17106, 17116, -1, 17129, 3503, 17119, -1, 17129, 17109, 17121, -1, 17129, 17119, 17109, -1, 17130, 17115, 17104, -1, 17131, 17112, 17120, -1, 17130, 17104, 17123, -1, 17132, 17117, 17125, -1, 17131, 17122, 17112, -1, 17132, 17126, 17117, -1, 17133, 17108, 17100, -1, 17133, 17122, 17131, -1, 17134, 17121, 17126, -1, 17133, 17100, 17122, -1, 17135, 17110, 17124, -1, 17134, 17129, 17121, -1, 17135, 17120, 17110, -1, 17136, 17116, 17127, -1, 17136, 17128, 17116, -1, 17137, 17115, 17130, -1, 17137, 17125, 17115, -1, 17138, 17124, 17114, -1, 17139, 17126, 17132, -1, 17139, 17134, 17126, -1, 17138, 17114, 17128, -1, 17140, 17129, 17134, -1, 17141, 17133, 17131, -1, 17140, 3507, 17129, -1, 17142, 17133, 17141, -1, 17142, 3418, 17118, -1, 17142, 17118, 17108, -1, 17142, 17108, 17133, -1, 17142, 3419, 3418, -1, 17143, 17120, 17135, -1, 17143, 17131, 17120, -1, 17144, 17132, 17125, -1, 17144, 17125, 17137, -1, 17145, 17127, 11517, -1, 17146, 17134, 17139, -1, 17145, 11517, 11525, -1, 17146, 17140, 17134, -1, 17146, 3507, 17140, -1, 17146, 3415, 3507, -1, 17147, 17128, 17136, -1, 17147, 17138, 17128, -1, 17148, 17149, 11563, -1, 17150, 17124, 17138, -1, 17148, 11563, 11556, -1, 17150, 17135, 17124, -1, 17151, 17139, 17132, -1, 17152, 17142, 17141, -1, 17151, 17132, 17144, -1, 17152, 3419, 17142, -1, 17153, 17141, 17131, -1, 17153, 17131, 17143, -1, 17154, 17127, 17145, -1, 17154, 17136, 17127, -1, 17155, 17156, 17149, -1, 17155, 17149, 17148, -1, 17157, 17138, 17147, -1, 17158, 17139, 17151, -1, 17158, 17146, 17139, -1, 17157, 17150, 17138, -1, 17158, 3415, 17146, -1, 17159, 17143, 17135, -1, 17159, 17135, 17150, -1, 17160, 17152, 17141, -1, 17161, 17162, 17156, -1, 17160, 3425, 3419, -1, 17160, 17141, 17153, -1, 17160, 3419, 17152, -1, 17161, 17156, 17155, -1, 17163, 17147, 17136, -1, 17164, 11556, 11545, -1, 17164, 17148, 11556, -1, 17163, 17136, 17154, -1, 17165, 17159, 17150, -1, 17165, 17150, 17157, -1, 17166, 17153, 17143, -1, 17166, 17143, 17159, -1, 17167, 17162, 17161, -1, 17166, 17159, 17165, -1, 17167, 17168, 17162, -1, 17169, 11545, 11537, -1, 17170, 17157, 17147, -1, 17169, 17164, 11545, -1, 17170, 17147, 17163, -1, 17171, 17148, 17164, -1, 17172, 17166, 17165, -1, 17171, 17155, 17148, -1, 17173, 17160, 17153, -1, 17173, 17166, 17172, -1, 17173, 3425, 17160, -1, 17173, 17153, 17166, -1, 17174, 17165, 17157, -1, 17175, 17176, 17168, -1, 17175, 17168, 17167, -1, 17174, 17157, 17170, -1, 17177, 17173, 17172, -1, 17177, 3425, 17173, -1, 17178, 17171, 17164, -1, 17177, 3432, 3425, -1, 17179, 17172, 17165, -1, 17178, 17164, 17169, -1, 17180, 17161, 17155, -1, 17179, 17165, 17174, -1, 17181, 17177, 17172, -1, 17180, 17155, 17171, -1, 17181, 17172, 17179, -1, 17181, 3432, 17177, -1, 17182, 17169, 11537, -1, 17183, 17184, 17176, -1, 17183, 17176, 17175, -1, 17185, 17186, 17187, -1, 17185, 17187, 11367, -1, 17188, 17185, 17189, -1, 17190, 17180, 17171, -1, 17190, 17171, 17178, -1, 17188, 17186, 17185, -1, 17191, 17167, 17161, -1, 17191, 17161, 17180, -1, 17192, 17193, 17194, -1, 17195, 17178, 17169, -1, 17195, 17169, 17182, -1, 17196, 11537, 11528, -1, 17197, 17192, 17198, -1, 17197, 17193, 17192, -1, 17196, 17182, 11537, -1, 17199, 17200, 17184, -1, 17201, 17202, 11454, -1, 17199, 3416, 17200, -1, 17199, 17184, 17183, -1, 17201, 11454, 17203, -1, 17201, 17204, 17202, -1, 17199, 3423, 3416, -1, 17201, 17203, 17205, -1, 17206, 17204, 17201, -1, 17207, 17180, 17190, -1, 17207, 17191, 17180, -1, 17206, 17201, 17205, -1, 17208, 17175, 17167, -1, 17209, 17070, 17079, -1, 17208, 17167, 17191, -1, 17209, 17210, 17211, -1, 17212, 17178, 17195, -1, 17212, 17190, 17178, -1, 17213, 17196, 11528, -1, 17214, 17154, 17145, -1, 17215, 17195, 17182, -1, 17216, 17214, 4527, -1, 17216, 17154, 17214, -1, 17215, 17182, 17196, -1, 17217, 11367, 11359, -1, 17217, 17189, 17185, -1, 17218, 17191, 17207, -1, 17217, 11359, 17219, -1, 17218, 17208, 17191, -1, 17217, 17219, 17189, -1, 17217, 17185, 11367, -1, 17220, 17221, 17186, -1, 17220, 17186, 17188, -1, 17220, 17222, 17221, -1, 17223, 17175, 17208, -1, 17224, 17188, 17189, -1, 17223, 17183, 17175, -1, 17224, 17189, 17225, -1, 17226, 17207, 17190, -1, 17224, 17220, 17188, -1, 17226, 17190, 17212, -1, 17224, 17225, 17227, -1, 17228, 17113, 11571, -1, 17228, 17229, 17113, -1, 17230, 17215, 17196, -1, 17230, 17196, 17213, -1, 17231, 11563, 17149, -1, 17231, 17149, 17156, -1, 17231, 11571, 11563, -1, 17231, 17228, 11571, -1, 17231, 17229, 17228, -1, 17232, 17195, 17215, -1, 17233, 17130, 17123, -1, 17232, 17212, 17195, -1, 17233, 17113, 17229, -1, 17233, 17123, 17113, -1, 17234, 17208, 17218, -1, 17235, 17156, 17162, -1, 17235, 17231, 17156, -1, 17234, 17223, 17208, -1, 17235, 17229, 17231, -1, 17235, 17233, 17229, -1, 17236, 17199, 17183, -1, 17236, 3423, 17199, -1, 17237, 17194, 11519, -1, 17236, 17183, 17223, -1, 17236, 3430, 3423, -1, 17237, 17192, 17194, -1, 17238, 11512, 17239, -1, 17240, 17207, 17226, -1, 17238, 11519, 11512, -1, 17238, 17198, 17192, -1, 17238, 17237, 11519, -1, 17238, 17192, 17237, -1, 17238, 17239, 17198, -1, 17240, 17218, 17207, -1, 17241, 17193, 17197, -1, 17241, 17242, 17193, -1, 17194, 17213, 11528, -1, 17194, 11528, 11519, -1, 17241, 17243, 17242, -1, 17244, 17198, 17245, -1, 17246, 17215, 17230, -1, 17244, 17245, 17247, -1, 17246, 17232, 17215, -1, 17244, 17241, 17197, -1, 17244, 17197, 17198, -1, 17248, 17249, 17204, -1, 17248, 17250, 17249, -1, 17251, 17226, 17212, -1, 17248, 17204, 17206, -1, 17251, 17212, 17232, -1, 17252, 17206, 17205, -1, 17252, 17253, 17254, -1, 17252, 17205, 17253, -1, 17255, 17223, 17234, -1, 17255, 3430, 17236, -1, 17255, 17236, 17223, -1, 17252, 17248, 17206, -1, 17256, 17211, 11462, -1, 17257, 17234, 17218, -1, 17256, 17209, 17211, -1, 17257, 17218, 17240, -1, 17258, 17256, 11462, -1, 17258, 17209, 17256, -1, 17258, 11473, 17070, -1, 17193, 17230, 17213, -1, 17258, 11462, 11473, -1, 17193, 17213, 17194, -1, 17258, 17070, 17209, -1, 17259, 17075, 17210, -1, 17259, 17210, 17209, -1, 17260, 17251, 17232, -1, 17261, 17259, 17209, -1, 17260, 17232, 17246, -1, 17261, 17076, 17075, -1, 17261, 17075, 17259, -1, 17261, 17209, 17079, -1, 17261, 17079, 17076, -1, 17262, 17145, 11525, -1, 17263, 17240, 17226, -1, 17263, 17226, 17251, -1, 17262, 17214, 17145, -1, 17264, 17214, 17262, -1, 17264, 17262, 11525, -1, 17264, 4527, 17214, -1, 17264, 11525, 4520, -1, 17265, 17255, 17234, -1, 17264, 4520, 4522, -1, 17265, 17234, 17257, -1, 17264, 4522, 4527, -1, 17265, 3430, 17255, -1, 17266, 17170, 17163, -1, 17266, 17163, 17154, -1, 17265, 3437, 3430, -1, 17266, 17154, 17216, -1, 17242, 17246, 17230, -1, 17242, 17230, 17193, -1, 17267, 17266, 17216, -1, 17268, 4531, 11421, -1, 17267, 17216, 4527, -1, 17267, 4527, 4535, -1, 17269, 4469, 4531, -1, 17270, 17251, 17260, -1, 17267, 4535, 4545, -1, 17270, 17263, 17251, -1, 17271, 17222, 17220, -1, 17271, 17272, 17222, -1, 17269, 4531, 17268, -1, 17273, 17257, 17240, -1, 17273, 17240, 17263, -1, 17274, 17220, 17224, -1, 17275, 4538, 4469, -1, 17274, 17271, 17220, -1, 17275, 4469, 17269, -1, 17276, 17271, 17274, -1, 17276, 17274, 17224, -1, 17277, 11421, 11415, -1, 17243, 17246, 17242, -1, 17243, 17260, 17246, -1, 17277, 17268, 11421, -1, 17278, 17276, 17224, -1, 17279, 17263, 17270, -1, 17280, 4541, 4538, -1, 17279, 17273, 17263, -1, 17281, 17278, 17224, -1, 17281, 17224, 17227, -1, 17281, 17227, 17282, -1, 17283, 17130, 17233, -1, 17284, 17265, 17257, -1, 17283, 17137, 17130, -1, 17280, 4538, 17275, -1, 17284, 17257, 17273, -1, 17285, 11415, 11397, -1, 17284, 3437, 17265, -1, 17285, 17277, 11415, -1, 17286, 17233, 17235, -1, 17286, 17283, 17233, -1, 17287, 17268, 17277, -1, 17287, 17269, 17268, -1, 17288, 17283, 17286, -1, 17288, 17286, 17235, -1, 17289, 17260, 17243, -1, 17290, 4617, 4541, -1, 17289, 17270, 17260, -1, 17291, 17288, 17235, -1, 17290, 4541, 17280, -1, 17292, 17284, 17273, -1, 17292, 17273, 17279, -1, 17292, 3441, 3437, -1, 17293, 17291, 17235, -1, 17294, 17287, 17277, -1, 17292, 3437, 17284, -1, 17293, 17235, 17162, -1, 17293, 17162, 17168, -1, 17295, 17289, 17243, -1, 17294, 17277, 17285, -1, 17296, 17275, 17269, -1, 17295, 17243, 17241, -1, 17297, 17270, 17289, -1, 17297, 17279, 17270, -1, 17296, 17269, 17287, -1, 17298, 17295, 17241, -1, 17299, 17239, 11512, -1, 17300, 17285, 11397, -1, 17299, 11512, 11500, -1, 17301, 17241, 17244, -1, 17302, 4656, 4617, -1, 17303, 17298, 17241, -1, 17302, 4617, 17290, -1, 17303, 17241, 17301, -1, 17304, 17296, 17287, -1, 17305, 17301, 17244, -1, 17305, 17303, 17301, -1, 17304, 17287, 17294, -1, 17305, 17244, 17247, -1, 17305, 17247, 17306, -1, 17307, 17275, 17296, -1, 17308, 17309, 17250, -1, 17310, 17279, 17297, -1, 17308, 17250, 17248, -1, 17310, 17292, 17279, -1, 17310, 3441, 17292, -1, 17307, 17280, 17275, -1, 17311, 17308, 17248, -1, 17311, 17248, 17252, -1, 17312, 17198, 17239, -1, 17313, 17308, 17311, -1, 17314, 17294, 17285, -1, 17312, 17239, 17299, -1, 17314, 17285, 17300, -1, 17313, 17311, 17252, -1, 17315, 11397, 11390, -1, 17315, 17300, 11397, -1, 17316, 4700, 4656, -1, 17317, 17245, 17198, -1, 17318, 17313, 17252, -1, 17316, 3427, 4700, -1, 17316, 3433, 3427, -1, 17316, 4656, 17302, -1, 17319, 17252, 17254, -1, 17320, 17307, 17296, -1, 17317, 17198, 17312, -1, 17319, 17254, 17321, -1, 17319, 17318, 17252, -1, 17320, 17296, 17304, -1, 17322, 17174, 17170, -1, 17323, 11500, 11487, -1, 17322, 17170, 17266, -1, 17323, 17299, 11500, -1, 17324, 17322, 17266, -1, 17324, 17266, 17267, -1, 17325, 17290, 17280, -1, 17325, 17280, 17307, -1, 17326, 17304, 17294, -1, 17326, 17294, 17314, -1, 17327, 17247, 17245, -1, 17327, 17245, 17317, -1, 17328, 17322, 17324, -1, 17329, 17315, 11390, -1, 17330, 17314, 17300, -1, 17331, 17323, 11487, -1, 17332, 17324, 17267, -1, 17330, 17300, 17315, -1, 17331, 11487, 11476, -1, 17332, 17328, 17324, -1, 17333, 17332, 17267, -1, 17333, 17267, 4545, -1, 17333, 4545, 4557, -1, 17334, 17307, 17320, -1, 17335, 17312, 17299, -1, 17335, 17299, 17323, -1, 17334, 17325, 17307, -1, 17336, 17276, 17278, -1, 17336, 17272, 17271, -1, 17336, 17271, 17276, -1, 17337, 17302, 17290, -1, 17336, 17338, 17272, -1, 17337, 17290, 17325, -1, 17339, 17282, 17340, -1, 17339, 17281, 17282, -1, 17339, 17278, 17281, -1, 17341, 17247, 17327, -1, 17339, 17336, 17278, -1, 17342, 17320, 17304, -1, 17343, 17144, 17137, -1, 17343, 17137, 17283, -1, 17342, 17304, 17326, -1, 17343, 17283, 17288, -1, 17343, 17288, 17291, -1, 17341, 17306, 17247, -1, 17344, 17330, 17315, -1, 17345, 17335, 17323, -1, 17346, 17343, 17291, -1, 17344, 17315, 17329, -1, 17346, 17291, 17293, -1, 17345, 17323, 17331, -1, 17346, 17168, 17176, -1, 17346, 17293, 17168, -1, 17347, 17326, 17314, -1, 17348, 17317, 17312, -1, 17349, 17297, 17289, -1, 17349, 17289, 17295, -1, 17347, 17314, 17330, -1, 17350, 17337, 17325, -1, 17349, 17295, 17298, -1, 17348, 17312, 17335, -1, 17351, 17306, 17352, -1, 17350, 17325, 17334, -1, 17353, 17331, 11476, -1, 17354, 3439, 3433, -1, 17351, 17349, 17298, -1, 17354, 17316, 17302, -1, 17351, 17298, 17303, -1, 17354, 3433, 17316, -1, 17351, 17303, 17305, -1, 17351, 17305, 17306, -1, 17354, 17302, 17337, -1, 17355, 17352, 17306, -1, 17355, 17306, 17341, -1, 17356, 17357, 17309, -1, 17356, 17308, 17313, -1, 17358, 17320, 17342, -1, 17358, 17334, 17320, -1, 17356, 17309, 17308, -1, 17359, 17348, 17335, -1, 17356, 17313, 17318, -1, 17359, 17335, 17345, -1, 17187, 11390, 11367, -1, 17360, 17356, 17318, -1, 17360, 17321, 17361, -1, 17360, 17319, 17321, -1, 17362, 17327, 17317, -1, 17360, 17318, 17319, -1, 17187, 17329, 11390, -1, 17363, 17179, 17174, -1, 17362, 17317, 17348, -1, 17364, 17330, 17344, -1, 17363, 17322, 17328, -1, 17365, 17345, 17331, -1, 17363, 17174, 17322, -1, 17364, 17347, 17330, -1, 17363, 17328, 17332, -1, 17365, 17331, 17353, -1, 17366, 17333, 4557, -1, 17366, 17363, 17332, -1, 17367, 17342, 17326, -1, 17366, 4557, 4570, -1, 17366, 17332, 17333, -1, 17368, 17338, 17336, -1, 17367, 17326, 17347, -1, 17369, 17353, 11476, -1, 17369, 11476, 11467, -1, 17370, 3439, 17354, -1, 17368, 17371, 17338, -1, 17370, 17337, 17350, -1, 17372, 17373, 17352, -1, 17370, 17354, 17337, -1, 17372, 3445, 17373, -1, 17372, 17352, 17355, -1, 17374, 17368, 17336, -1, 17375, 17350, 17334, -1, 17372, 3449, 3445, -1, 17375, 17334, 17358, -1, 17376, 17362, 17348, -1, 17376, 17348, 17359, -1, 17377, 17336, 17339, -1, 17186, 17344, 17329, -1, 17377, 17374, 17336, -1, 17186, 17329, 17187, -1, 17377, 17339, 17340, -1, 17377, 17340, 17378, -1, 17379, 17341, 17327, -1, 17380, 17151, 17144, -1, 17379, 17327, 17362, -1, 17380, 17144, 17343, -1, 17381, 17347, 17364, -1, 17382, 17359, 17345, -1, 17383, 17380, 17343, -1, 17381, 17367, 17347, -1, 17382, 17345, 17365, -1, 17384, 17342, 17367, -1, 17385, 17346, 17176, -1, 17384, 17358, 17342, -1, 17385, 17343, 17346, -1, 17386, 17353, 17369, -1, 17385, 17176, 17184, -1, 17387, 17350, 17375, -1, 17385, 17383, 17343, -1, 17387, 3443, 3439, -1, 17388, 17349, 17351, -1, 17387, 3439, 17370, -1, 17386, 17365, 17353, -1, 17387, 17370, 17350, -1, 17388, 17310, 17297, -1, 17389, 17369, 11467, -1, 17388, 17297, 17349, -1, 17221, 17344, 17186, -1, 17390, 17379, 17362, -1, 17390, 17362, 17376, -1, 17221, 17364, 17344, -1, 17391, 17388, 17351, -1, 17392, 17391, 17351, -1, 17393, 17367, 17381, -1, 17392, 17351, 17352, -1, 17393, 17384, 17367, -1, 17394, 17355, 17341, -1, 17392, 17352, 17373, -1, 17394, 17341, 17379, -1, 17395, 17396, 17357, -1, 17397, 17358, 17384, -1, 17395, 17357, 17356, -1, 17398, 17376, 17359, -1, 17397, 17384, 17393, -1, 17397, 17375, 17358, -1, 17398, 17359, 17382, -1, 17399, 17395, 17356, -1, 17400, 17382, 17365, -1, 17401, 17361, 17402, -1, 17401, 17360, 17361, -1, 17400, 17365, 17386, -1, 17401, 17399, 17356, -1, 17401, 17356, 17360, -1, 17222, 17364, 17221, -1, 17403, 17181, 17179, -1, 17222, 17381, 17364, -1, 17404, 17386, 17369, -1, 17403, 17179, 17363, -1, 17405, 17397, 17393, -1, 17404, 17369, 17389, -1, 17406, 17394, 17379, -1, 17407, 3443, 17387, -1, 17406, 17379, 17390, -1, 17407, 17375, 17397, -1, 17408, 17403, 17363, -1, 17407, 17387, 17375, -1, 17409, 17363, 17366, -1, 17407, 17397, 17405, -1, 17409, 17366, 4570, -1, 17410, 17372, 17355, -1, 17409, 17408, 17363, -1, 17410, 3449, 17372, -1, 17410, 17355, 17394, -1, 17409, 4570, 4591, -1, 17410, 3453, 3449, -1, 17411, 17371, 17368, -1, 17202, 11467, 11454, -1, 17411, 17368, 17374, -1, 17411, 3447, 17371, -1, 17412, 3451, 3447, -1, 17202, 17389, 11467, -1, 17412, 17378, 3451, -1, 17272, 17381, 17222, -1, 17412, 3447, 17411, -1, 17412, 17377, 17378, -1, 17413, 17406, 17390, -1, 17412, 17374, 17377, -1, 17272, 17393, 17381, -1, 17413, 17390, 17376, -1, 17412, 17411, 17374, -1, 17413, 17376, 17398, -1, 17414, 17151, 17380, -1, 17415, 3447, 3443, -1, 17414, 17158, 17151, -1, 17414, 17380, 17383, -1, 17415, 3443, 17407, -1, 17415, 17407, 17405, -1, 17416, 17398, 17382, -1, 17417, 17385, 17184, -1, 17416, 17382, 17400, -1, 17417, 17383, 17385, -1, 17418, 17400, 17386, -1, 17417, 17184, 17200, -1, 17417, 17414, 17383, -1, 17419, 3441, 17310, -1, 17419, 17310, 17388, -1, 17418, 17386, 17404, -1, 17419, 17388, 17391, -1, 17338, 17405, 17393, -1, 17420, 17410, 17394, -1, 17419, 3445, 3441, -1, 17338, 17393, 17272, -1, 17421, 17391, 17392, -1, 17421, 17373, 3445, -1, 17421, 17392, 17373, -1, 17420, 17394, 17406, -1, 17421, 3445, 17419, -1, 17422, 11359, 11339, -1, 17420, 3453, 17410, -1, 17421, 17419, 17391, -1, 17204, 17389, 17202, -1, 17422, 17219, 11359, -1, 17204, 17404, 17389, -1, 17423, 17396, 17395, -1, 17423, 17395, 17399, -1, 17423, 3461, 17396, -1, 17424, 17402, 3465, -1, 17424, 17423, 17399, -1, 17424, 17399, 17401, -1, 17424, 17401, 17402, -1, 17425, 17420, 17406, -1, 17424, 3465, 3461, -1, 17425, 17406, 17413, -1, 17424, 3461, 17423, -1, 17426, 17413, 17398, -1, 17427, 3432, 17181, -1, 17371, 3447, 17415, -1, 17427, 17403, 17408, -1, 17371, 17415, 17405, -1, 17427, 17181, 17403, -1, 17426, 17398, 17416, -1, 17371, 17405, 17338, -1, 17428, 3432, 17427, -1, 17429, 17400, 17418, -1, 17428, 17427, 17408, -1, 17429, 17416, 17400, -1, 17428, 4591, 3436, -1, 17428, 3436, 3432, -1, 17428, 17408, 17409, -1, 17428, 17409, 4591, -1, 17430, 17189, 17219, -1, 17431, 17158, 17414, -1, 17431, 3415, 17158, -1, 17430, 17219, 17422, -1, 17249, 17404, 17204, -1, 17431, 17200, 3416, -1, 17249, 17418, 17404, -1, 17431, 17414, 17417, -1, 17431, 17417, 17200, -1, 17431, 3416, 3415, -1, 17432, 3453, 17420, -1, 17432, 17420, 17425, -1, 17432, 3457, 3453, -1, 17433, 17413, 17426, -1, 17434, 17225, 17189, -1, 17434, 17189, 17430, -1, 17433, 17425, 17413, -1, 17435, 11339, 11333, -1, 17436, 17416, 17429, -1, 17435, 17422, 11339, -1, 17436, 17426, 17416, -1, 17203, 11454, 11445, -1, 17250, 17429, 17418, -1, 17250, 17418, 17249, -1, 17437, 17225, 17434, -1, 17437, 17227, 17225, -1, 17438, 17432, 17425, -1, 17438, 3457, 17432, -1, 17439, 17435, 11333, -1, 17438, 17425, 17433, -1, 17439, 11333, 11313, -1, 17440, 17433, 17426, -1, 17440, 17426, 17436, -1, 17441, 17422, 17435, -1, 17441, 17430, 17422, -1, 17309, 17436, 17429, -1, 17442, 17227, 17437, -1, 17309, 17429, 17250, -1, 17442, 17282, 17227, -1, 17443, 3457, 17438, -1, 17443, 17433, 17440, -1, 17443, 17438, 17433, -1, 17444, 17441, 17435, -1, 17443, 3461, 3457, -1, 17444, 17435, 17439, -1, 17445, 17434, 17430, -1, 17445, 17430, 17441, -1, 17357, 17436, 17309, -1, 17357, 17440, 17436, -1, 17446, 17439, 11313, -1, 17447, 11445, 11432, -1, 17448, 17340, 17282, -1, 17447, 17203, 11445, -1, 17448, 17282, 17442, -1, 17449, 17441, 17444, -1, 17449, 17445, 17441, -1, 17450, 17437, 17434, -1, 17396, 17440, 17357, -1, 17396, 17443, 17440, -1, 17396, 3461, 17443, -1, 17450, 17434, 17445, -1, 17451, 17203, 17447, -1, 17451, 17205, 17203, -1, 17452, 17439, 17446, -1, 17452, 17444, 17439, -1, 17453, 11313, 11304, -1, 17453, 17446, 11313, -1, 17454, 3455, 3451, -1, 17454, 3451, 17378, -1, 17454, 17340, 17448, -1, 17455, 17253, 17205, -1, 17454, 17378, 17340, -1, 17455, 17205, 17451, -1, 17456, 17445, 17449, -1, 17456, 17450, 17445, -1, 17457, 17447, 11432, -1, 17457, 11432, 11420, -1, 17458, 17442, 17437, -1, 17458, 17437, 17450, -1, 17459, 17449, 17444, -1, 17459, 17444, 17452, -1, 17460, 17254, 17253, -1, 17461, 17452, 17446, -1, 17460, 17253, 17455, -1, 17461, 17446, 17453, -1, 17462, 17453, 11304, -1, 17463, 11420, 11412, -1, 17463, 17457, 11420, -1, 17464, 17450, 17456, -1, 17465, 17451, 17447, -1, 17464, 17458, 17450, -1, 17466, 17448, 17442, -1, 17465, 17447, 17457, -1, 17466, 17458, 17464, -1, 17466, 17442, 17458, -1, 17467, 17449, 17459, -1, 17467, 17456, 17449, -1, 17468, 17321, 17254, -1, 17468, 17254, 17460, -1, 17469, 17452, 17461, -1, 17469, 17459, 17452, -1, 17470, 17465, 17457, -1, 17470, 17457, 17463, -1, 17471, 17461, 17453, -1, 17471, 17453, 17462, -1, 17472, 17451, 17465, -1, 17472, 17455, 17451, -1, 17473, 17466, 17464, -1, 17474, 17463, 11412, -1, 17475, 3459, 3455, -1, 17475, 17448, 17466, -1, 17475, 17454, 17448, -1, 17475, 17466, 17473, -1, 17475, 3455, 17454, -1, 17476, 17321, 17468, -1, 17477, 11304, 11289, -1, 17476, 17361, 17321, -1, 17477, 17462, 11304, -1, 17478, 17472, 17465, -1, 17479, 17464, 17456, -1, 17478, 17465, 17470, -1, 17479, 17456, 17467, -1, 17480, 17460, 17455, -1, 17480, 17455, 17472, -1, 17481, 17467, 17459, -1, 17481, 17459, 17469, -1, 17482, 17470, 17463, -1, 17482, 17463, 17474, -1, 17483, 17469, 17461, -1, 17483, 17461, 17471, -1, 17484, 3459, 17475, -1, 17485, 11412, 11403, -1, 17484, 17475, 17473, -1, 17485, 17474, 11412, -1, 17486, 17477, 11289, -1, 17487, 17402, 17361, -1, 17487, 3465, 17402, -1, 17487, 17361, 17476, -1, 17487, 3469, 3465, -1, 17488, 17480, 17472, -1, 17489, 17471, 17462, -1, 17488, 17472, 17478, -1, 17489, 17462, 17477, -1, 17490, 17468, 17460, -1, 17490, 17460, 17480, -1, 17491, 17473, 17464, -1, 17491, 17464, 17479, -1, 17492, 17491, 17479, -1, 17492, 17479, 17467, -1, 17493, 17470, 17482, -1, 17492, 17467, 17481, -1, 17493, 17478, 17470, -1, 17494, 17469, 17483, -1, 17495, 17482, 17474, -1, 17494, 17481, 17469, -1, 17496, 17477, 17486, -1, 17495, 17474, 17485, -1, 17496, 17489, 17477, -1, 17497, 17485, 11403, -1, 17498, 17490, 17480, -1, 17499, 17471, 17489, -1, 17498, 17480, 17488, -1, 17500, 17476, 17468, -1, 17499, 17483, 17471, -1, 17501, 17484, 17473, -1, 17500, 17468, 17490, -1, 17501, 3463, 3459, -1, 17500, 17490, 17498, -1, 17501, 3459, 17484, -1, 17501, 17473, 17491, -1, 17502, 17491, 17492, -1, 17503, 17488, 17478, -1, 17503, 17478, 17493, -1, 17502, 17501, 17491, -1, 17504, 17492, 17481, -1, 17505, 17482, 17495, -1, 17504, 17481, 17494, -1, 17506, 17489, 17496, -1, 17505, 17493, 17482, -1, 17507, 17495, 17485, -1, 17507, 17485, 17497, -1, 17506, 17499, 17489, -1, 17508, 17500, 17498, -1, 17509, 11289, 11283, -1, 17509, 17486, 11289, -1, 17510, 17487, 17476, -1, 17510, 3469, 17487, -1, 17510, 17476, 17500, -1, 17511, 17494, 17483, -1, 17510, 17500, 17508, -1, 17511, 17483, 17499, -1, 17510, 3473, 3469, -1, 17512, 17497, 11403, -1, 17512, 11403, 11393, -1, 17513, 3463, 17501, -1, 17513, 17501, 17502, -1, 17514, 17498, 17488, -1, 17514, 17488, 17503, -1, 17515, 17492, 17504, -1, 17515, 17502, 17492, -1, 17516, 17503, 17493, -1, 17516, 17493, 17505, -1, 17517, 17499, 17506, -1, 17517, 17511, 17499, -1, 17518, 17505, 17495, -1, 17518, 17495, 17507, -1, 17519, 17496, 17486, -1, 17519, 17486, 17509, -1, 17520, 17510, 17508, -1, 17520, 3473, 17510, -1, 17521, 17504, 17494, -1, 17522, 17512, 11393, -1, 17521, 17494, 17511, -1, 17523, 3467, 3463, -1, 17523, 17513, 17502, -1, 17523, 17502, 17515, -1, 17524, 17497, 17512, -1, 17523, 3463, 17513, -1, 17524, 17507, 17497, -1, 17525, 17508, 17498, -1, 17526, 17511, 17517, -1, 17525, 17498, 17514, -1, 17526, 17521, 17511, -1, 17527, 17506, 17496, -1, 17527, 17496, 17519, -1, 17528, 17525, 17514, -1, 17528, 17514, 17503, -1, 17528, 17503, 17516, -1, 17529, 17516, 17505, -1, 17530, 17504, 17521, -1, 17530, 17515, 17504, -1, 17529, 17505, 17518, -1, 17531, 17524, 17512, -1, 17532, 11283, 11279, -1, 17532, 17509, 11283, -1, 17531, 17512, 17522, -1, 17533, 17518, 17507, -1, 17534, 17530, 17521, -1, 17534, 17521, 17526, -1, 17533, 17507, 17524, -1, 17535, 17517, 17506, -1, 17536, 17520, 17508, -1, 17536, 17508, 17525, -1, 17536, 3477, 3473, -1, 17535, 17506, 17527, -1, 17536, 3473, 17520, -1, 17537, 3467, 17523, -1, 17538, 17536, 17525, -1, 17537, 17523, 17515, -1, 17537, 17515, 17530, -1, 17538, 17525, 17528, -1, 17539, 17528, 17516, -1, 17540, 17519, 17509, -1, 17540, 17509, 17532, -1, 17539, 17516, 17529, -1, 17541, 3467, 17537, -1, 17541, 3471, 3467, -1, 17542, 17524, 17531, -1, 17541, 17530, 17534, -1, 17541, 17537, 17530, -1, 17542, 17533, 17524, -1, 17543, 17517, 17535, -1, 17543, 17526, 17517, -1, 17544, 11393, 11398, -1, 17544, 17522, 11393, -1, 17545, 17518, 17533, -1, 17545, 17529, 17518, -1, 17546, 17519, 17540, -1, 17546, 17527, 17519, -1, 17547, 17536, 17538, -1, 17547, 3477, 17536, -1, 17548, 11279, 11660, -1, 17548, 17532, 11279, -1, 17549, 17538, 17528, -1, 17549, 17528, 17539, -1, 17550, 17526, 17543, -1, 17550, 17534, 17526, -1, 17551, 17545, 17533, -1, 17552, 11660, 11651, -1, 17551, 17533, 17542, -1, 17553, 17531, 17522, -1, 17552, 17548, 11660, -1, 17553, 17522, 17544, -1, 17554, 17529, 17545, -1, 17555, 17535, 17527, -1, 17554, 17539, 17529, -1, 17555, 17527, 17546, -1, 17556, 17547, 17538, -1, 17556, 17538, 17549, -1, 17557, 17540, 17532, -1, 17557, 17532, 17548, -1, 17556, 3477, 17547, -1, 17556, 3481, 3477, -1, 17558, 17554, 17545, -1, 17559, 3471, 17541, -1, 17559, 17541, 17534, -1, 17558, 17545, 17551, -1, 17559, 17534, 17550, -1, 17560, 17557, 17548, -1, 17561, 17542, 17531, -1, 17561, 17531, 17553, -1, 17560, 17548, 17552, -1, 17562, 17549, 17539, -1, 17562, 17539, 17554, -1, 17563, 17543, 17535, -1, 17563, 17535, 17555, -1, 17564, 17544, 11398, -1, 17564, 11398, 11407, -1, 17565, 17540, 17557, -1, 17566, 17562, 17554, -1, 17566, 17554, 17558, -1, 17565, 17546, 17540, -1, 17567, 17551, 17542, -1, 17568, 17552, 11651, -1, 17567, 17542, 17561, -1, 17569, 17565, 17557, -1, 17569, 17557, 17560, -1, 17570, 17556, 17549, -1, 17570, 17549, 17562, -1, 17570, 3481, 17556, -1, 17571, 17550, 17543, -1, 17571, 17543, 17563, -1, 17572, 17553, 17544, -1, 17573, 17555, 17546, -1, 17572, 17544, 17564, -1, 17573, 17546, 17565, -1, 17574, 17570, 17562, -1, 17574, 17562, 17566, -1, 17575, 17560, 17552, -1, 17575, 17552, 17568, -1, 17574, 3481, 17570, -1, 17574, 3485, 3481, -1, 17576, 17558, 17551, -1, 17576, 17551, 17567, -1, 17577, 17568, 11651, -1, 17577, 11651, 11646, -1, 17578, 17561, 17553, -1, 17579, 17573, 17565, -1, 17578, 17553, 17572, -1, 17579, 17565, 17569, -1, 17580, 17559, 17550, -1, 17580, 3475, 3471, -1, 17580, 17550, 17571, -1, 17580, 3471, 17559, -1, 17581, 11407, 11417, -1, 17581, 17564, 11407, -1, 17582, 17563, 17555, -1, 17583, 17566, 17558, -1, 17583, 17558, 17576, -1, 17582, 17555, 17573, -1, 17584, 17569, 17560, -1, 17585, 11417, 11429, -1, 17584, 17560, 17575, -1, 17586, 17575, 17568, -1, 17585, 17581, 11417, -1, 17586, 17568, 17577, -1, 17587, 17561, 17578, -1, 17587, 17567, 17561, -1, 17588, 17577, 11646, -1, 17589, 17564, 17581, -1, 17590, 17573, 17579, -1, 17589, 17572, 17564, -1, 17590, 17582, 17573, -1, 17591, 17563, 17582, -1, 17591, 17571, 17563, -1, 17592, 17574, 17566, -1, 17592, 3485, 17574, -1, 17592, 17566, 17583, -1, 17593, 17569, 17584, -1, 17594, 17589, 17581, -1, 17593, 17579, 17569, -1, 17594, 17581, 17585, -1, 17595, 17584, 17575, -1, 17595, 17575, 17586, -1, 17596, 17576, 17567, -1, 17596, 17567, 17587, -1, 17597, 17578, 17572, -1, 17598, 17586, 17577, -1, 17597, 17572, 17589, -1, 17598, 17577, 17588, -1, 17599, 17582, 17590, -1, 17599, 17591, 17582, -1, 17600, 3479, 3475, -1, 17600, 17580, 17571, -1, 17601, 17585, 11429, -1, 17600, 17571, 17591, -1, 17602, 17597, 17589, -1, 17600, 3475, 17580, -1, 17602, 17589, 17594, -1, 17603, 11646, 11642, -1, 17603, 17588, 11646, -1, 17604, 17583, 17576, -1, 17605, 17590, 17579, -1, 17604, 17576, 17596, -1, 17605, 17579, 17593, -1, 17606, 17578, 17597, -1, 17606, 17587, 17578, -1, 17607, 17584, 17595, -1, 17607, 17593, 17584, -1, 17608, 17594, 17585, -1, 17608, 17585, 17601, -1, 17609, 17595, 17586, -1, 17609, 17586, 17598, -1, 17610, 17601, 11429, -1, 17611, 17591, 17599, -1, 17611, 3479, 17600, -1, 17610, 11429, 11442, -1, 17611, 17600, 17591, -1, 17612, 17606, 17597, -1, 17612, 17597, 17602, -1, 17613, 17603, 11642, -1, 17614, 17592, 17583, -1, 17614, 17583, 17604, -1, 17615, 17598, 17588, -1, 17614, 3489, 3485, -1, 17614, 3485, 17592, -1, 17615, 17588, 17603, -1, 17616, 17596, 17587, -1, 17616, 17587, 17606, -1, 17617, 17590, 17605, -1, 17617, 17599, 17590, -1, 17618, 17602, 17594, -1, 17618, 17594, 17608, -1, 17619, 17605, 17593, -1, 17619, 17593, 17607, -1, 17620, 17608, 17601, -1, 17621, 17607, 17595, -1, 17620, 17601, 17610, -1, 17621, 17595, 17609, -1, 17622, 17610, 11442, -1, 17623, 17603, 17613, -1, 17624, 17606, 17612, -1, 17623, 17615, 17603, -1, 17624, 17616, 17606, -1, 17625, 17609, 17598, -1, 17626, 17596, 17616, -1, 17625, 17598, 17615, -1, 17626, 17616, 17624, -1, 17627, 3483, 3479, -1, 17627, 3479, 17611, -1, 17626, 17604, 17596, -1, 17628, 17612, 17602, -1, 17627, 17611, 17599, -1, 17628, 17602, 17618, -1, 17627, 17599, 17617, -1, 17629, 17617, 17605, -1, 17629, 17605, 17619, -1, 17630, 17618, 17608, -1, 17630, 17608, 17620, -1, 17631, 17607, 17621, -1, 17631, 17619, 17607, -1, 17632, 17620, 17610, -1, 17632, 17610, 17622, -1, 17633, 11642, 11631, -1, 17633, 17613, 11642, -1, 17634, 17626, 17624, -1, 17635, 17625, 17615, -1, 17636, 17614, 17604, -1, 17636, 17604, 17626, -1, 17635, 17615, 17623, -1, 17636, 3489, 17614, -1, 17636, 17626, 17634, -1, 17637, 17621, 17609, -1, 17637, 17609, 17625, -1, 17636, 3493, 3489, -1, 17638, 17622, 11442, -1, 17638, 11442, 11453, -1, 17639, 17627, 17617, -1, 17640, 17624, 17612, -1, 17640, 17612, 17628, -1, 17639, 17617, 17629, -1, 17639, 3483, 17627, -1, 17641, 17629, 17619, -1, 17642, 17618, 17630, -1, 17642, 17628, 17618, -1, 17641, 17619, 17631, -1, 17643, 17623, 17613, -1, 17644, 17620, 17632, -1, 17643, 17613, 17633, -1, 17644, 17630, 17620, -1, 17645, 17637, 17625, -1, 17646, 17636, 17634, -1, 17645, 17625, 17635, -1, 17646, 3493, 17636, -1, 17647, 17631, 17621, -1, 17647, 17621, 17637, -1, 17648, 17638, 11453, -1, 17649, 3487, 3483, -1, 17650, 17632, 17622, -1, 17649, 17629, 17641, -1, 17650, 17622, 17638, -1, 17649, 17639, 17629, -1, 17649, 3483, 17639, -1, 17651, 17623, 17643, -1, 17652, 17634, 17624, -1, 17652, 17624, 17640, -1, 17651, 17635, 17623, -1, 17653, 17652, 17640, -1, 17653, 17628, 17642, -1, 17654, 17637, 17645, -1, 17653, 17640, 17628, -1, 17654, 17647, 17637, -1, 17655, 17631, 17647, -1, 17656, 17642, 17630, -1, 17656, 17630, 17644, -1, 17655, 17641, 17631, -1, 17655, 17647, 17654, -1, 17657, 17633, 11631, -1, 17658, 17650, 17638, -1, 17657, 11631, 11620, -1, 17658, 17638, 17648, -1, 17659, 17644, 17632, -1, 17659, 17632, 17650, -1, 17660, 17645, 17635, -1, 17660, 17635, 17651, -1, 17661, 17646, 17634, -1, 17661, 17634, 17652, -1, 17661, 3493, 17646, -1, 17662, 17655, 17654, -1, 17661, 3497, 3493, -1, 17663, 3487, 17649, -1, 17663, 17649, 17641, -1, 17663, 17641, 17655, -1, 17664, 17661, 17652, -1, 17663, 17655, 17662, -1, 17664, 17652, 17653, -1, 17665, 17643, 17633, -1, 17666, 17642, 17656, -1, 17666, 17653, 17642, -1, 17665, 17633, 17657, -1, 17211, 11453, 11462, -1, 17667, 17654, 17645, -1, 17211, 17648, 11453, -1, 17667, 17645, 17660, -1, 17668, 3491, 3487, -1, 17669, 17650, 17658, -1, 17668, 3487, 17663, -1, 17668, 17663, 17662, -1, 17670, 17651, 17643, -1, 17669, 17659, 17650, -1, 17671, 17644, 17659, -1, 17670, 17643, 17665, -1, 17671, 17656, 17644, -1, 17672, 3497, 17661, -1, 17045, 11620, 11606, -1, 17672, 17661, 17664, -1, 17673, 17664, 17653, -1, 17045, 17657, 11620, -1, 17673, 17653, 17666, -1, 17053, 17662, 17654, -1, 17053, 17654, 17667, -1, 17210, 17648, 17211, -1, 17061, 17651, 17670, -1, 17210, 17658, 17648, -1, 17058, 17659, 17669, -1, 17058, 17671, 17659, -1, 17061, 17660, 17651, -1, 17674, 17656, 17671, -1, 17050, 17665, 17657, -1, 17050, 17657, 17045, -1, 17674, 17666, 17656, -1, 17048, 17672, 17664, -1, 17055, 3491, 17668, -1, 17048, 17664, 17673, -1, 17055, 17662, 17053, -1, 17055, 17668, 17662, -1, 17048, 3501, 3497, -1, 17048, 3497, 17672, -1, 17075, 17669, 17658, -1, 17065, 17667, 17660, -1, 17075, 17658, 17210, -1, 17065, 17660, 17061, -1, 17067, 17665, 17050, -1, 17057, 17674, 17671, -1, 17067, 17670, 17665, -1, 17057, 17671, 17058, -1, 17049, 17673, 17666, -1, 17049, 17048, 17673, -1, 17049, 17666, 17674, -1, 17046, 17045, 11606, -1, 17046, 11606, 11599, -1, 17054, 17667, 17065, -1, 17054, 17053, 17667, -1, 17059, 17058, 17669, -1, 17059, 17669, 17075, -1, 17062, 17061, 17670, -1, 17064, 17049, 17674, -1, 17064, 17674, 17057, -1, 17062, 17670, 17067, -1, 17675, 17676, 17677, -1, 17011, 17035, 17678, -1, 17679, 17680, 17681, -1, 17679, 17681, 17676, -1, 17679, 17675, 17682, -1, 17679, 17676, 17675, -1, 17683, 17684, 17680, -1, 17683, 17680, 17679, -1, 17685, 17682, 17686, -1, 17685, 17686, 17687, -1, 17685, 17679, 17682, -1, 17688, 17012, 17011, -1, 17688, 17678, 17684, -1, 17688, 17684, 17683, -1, 17688, 17011, 17678, -1, 17689, 17687, 17690, -1, 17689, 17690, 17691, -1, 17689, 17691, 17692, -1, 17689, 17685, 17687, -1, 17689, 17679, 17685, -1, 17689, 17683, 17679, -1, 17693, 17692, 17694, -1, 17693, 17694, 17028, -1, 17693, 17028, 17012, -1, 17693, 17012, 17688, -1, 17693, 17689, 17692, -1, 17693, 17688, 17683, -1, 17693, 17683, 17689, -1, 17695, 17696, 17697, -1, 17695, 11221, 17696, -1, 17698, 17697, 17699, -1, 17698, 17695, 17697, -1, 17700, 17699, 17701, -1, 17700, 17702, 17699, -1, 17700, 17701, 17703, -1, 17704, 17703, 11866, -1, 17704, 17700, 17703, -1, 17705, 17704, 11866, -1, 17705, 11866, 11865, -1, 17705, 11865, 17706, -1, 17705, 17706, 17707, -1, 17708, 17700, 17704, -1, 17708, 17705, 17707, -1, 17708, 17704, 17705, -1, 17708, 17707, 17702, -1, 17708, 17702, 17700, -1, 17709, 11221, 17695, -1, 17709, 17695, 17698, -1, 17710, 17709, 17698, -1, 17710, 11230, 11221, -1, 17710, 17711, 11230, -1, 17710, 17699, 17711, -1, 17710, 17698, 17699, -1, 17710, 11221, 17709, -1, 17712, 17713, 11878, -1, 17712, 11878, 11872, -1, 17714, 17715, 17713, -1, 17714, 17716, 17715, -1, 17714, 17713, 17712, -1, 17717, 17714, 17712, -1, 17718, 17714, 17717, -1, 17718, 17716, 17714, -1, 17719, 17720, 17716, -1, 17719, 11223, 17720, -1, 17719, 11221, 11223, -1, 17719, 17716, 17718, -1, 17699, 17697, 17721, -1, 17702, 17711, 17699, -1, 17707, 17706, 17722, -1, 17723, 11230, 17711, -1, 17723, 17711, 17702, -1, 17723, 17702, 17707, -1, 17724, 17725, 17726, -1, 17724, 17722, 17725, -1, 17724, 17707, 17722, -1, 17724, 17723, 17707, -1, 17727, 11230, 17723, -1, 17728, 17726, 11234, -1, 17728, 11234, 11230, -1, 17728, 17724, 17726, -1, 17728, 17723, 17724, -1, 17728, 11230, 17727, -1, 17728, 17727, 17723, -1, 17729, 17717, 17712, -1, 17729, 17712, 11872, -1, 17729, 17697, 17718, -1, 17729, 17718, 17717, -1, 17730, 17729, 11872, -1, 17730, 17697, 17729, -1, 17731, 17721, 17697, -1, 17731, 17730, 11872, -1, 17731, 17697, 17730, -1, 17701, 11872, 11866, -1, 17701, 17699, 17721, -1, 17701, 17721, 17731, -1, 17701, 17731, 11872, -1, 17703, 17701, 11866, -1, 17696, 17718, 17697, -1, 17696, 17719, 17718, -1, 17696, 11221, 17719, -1, 17732, 17733, 17734, -1, 17735, 17736, 17737, -1, 17738, 17739, 17740, -1, 17738, 17741, 17739, -1, 17735, 17737, 17742, -1, 17743, 17744, 17745, -1, 17743, 17746, 17744, -1, 17747, 17748, 17749, -1, 17750, 17734, 17751, -1, 17747, 17749, 17752, -1, 17753, 17752, 3500, -1, 17750, 17751, 17746, -1, 17754, 11824, 11808, -1, 17755, 17756, 17757, -1, 17755, 17757, 17732, -1, 17754, 17758, 17759, -1, 17755, 11706, 17756, -1, 17754, 11808, 17758, -1, 17754, 17759, 17760, -1, 17761, 17736, 17735, -1, 17762, 17745, 17741, -1, 17761, 17763, 17736, -1, 17762, 17741, 17738, -1, 17764, 17746, 17743, -1, 17765, 17748, 17747, -1, 17764, 17750, 17746, -1, 17766, 17734, 17750, -1, 17766, 17732, 17734, -1, 17765, 17742, 17748, -1, 17767, 17740, 3502, -1, 17768, 17752, 17753, -1, 17768, 17747, 17752, -1, 17769, 17753, 3500, -1, 17767, 3502, 3506, -1, 11912, 3815, 3817, -1, 17769, 3500, 3504, -1, 17770, 17745, 17762, -1, 17770, 17743, 17745, -1, 17771, 17763, 17761, -1, 17771, 17760, 17763, -1, 17772, 17750, 17764, -1, 17773, 17735, 17742, -1, 17772, 17766, 17750, -1, 17774, 11706, 17755, -1, 17774, 11723, 11706, -1, 17773, 17742, 17765, -1, 17774, 17732, 17766, -1, 17774, 17755, 17732, -1, 17775, 17765, 17747, -1, 17776, 17738, 17740, -1, 17775, 17747, 17768, -1, 17776, 17740, 17767, -1, 17777, 17753, 17769, -1, 17778, 17764, 17743, -1, 17778, 17743, 17770, -1, 17777, 17768, 17753, -1, 17779, 11824, 17754, -1, 17779, 17754, 17760, -1, 17780, 11723, 17774, -1, 17779, 11832, 11824, -1, 17780, 17766, 17772, -1, 17780, 17774, 17766, -1, 17779, 17760, 17771, -1, 17781, 17769, 3504, -1, 17782, 17762, 17738, -1, 17783, 17761, 17735, -1, 17783, 17735, 17773, -1, 17782, 17738, 17776, -1, 17784, 17767, 3506, -1, 17784, 3506, 3510, -1, 17785, 17773, 17765, -1, 17785, 17765, 17775, -1, 17786, 17764, 17778, -1, 17786, 17772, 17764, -1, 17787, 17775, 17768, -1, 17787, 17768, 17777, -1, 17788, 17770, 17762, -1, 17789, 3504, 3508, -1, 17788, 17762, 17782, -1, 17789, 17781, 3504, -1, 17790, 17777, 17769, -1, 17790, 17769, 17781, -1, 17791, 17767, 17784, -1, 17791, 17776, 17767, -1, 17792, 17771, 17761, -1, 17793, 11737, 11723, -1, 17792, 17761, 17783, -1, 17793, 17780, 17772, -1, 17793, 17772, 17786, -1, 17793, 11723, 17780, -1, 17794, 17773, 17785, -1, 17794, 17783, 17773, -1, 17795, 17770, 17788, -1, 17795, 17778, 17770, -1, 17796, 17785, 17775, -1, 17796, 17775, 17787, -1, 17797, 17782, 17776, -1, 17797, 17776, 17791, -1, 17798, 17790, 17781, -1, 17798, 17781, 17789, -1, 17799, 3510, 3420, -1, 17799, 17784, 3510, -1, 17800, 17787, 17777, -1, 17800, 17777, 17790, -1, 17801, 17779, 17771, -1, 17801, 11832, 17779, -1, 17801, 17771, 17792, -1, 17802, 17782, 17797, -1, 17801, 11845, 11832, -1, 17802, 17788, 17782, -1, 17803, 17792, 17783, -1, 17803, 17783, 17794, -1, 17804, 17799, 3420, -1, 17805, 17794, 17785, -1, 17805, 17785, 17796, -1, 17806, 17791, 17784, -1, 17806, 17784, 17799, -1, 17807, 17789, 3508, -1, 17808, 17790, 17798, -1, 17808, 17800, 17790, -1, 17809, 17796, 17787, -1, 17809, 17787, 17800, -1, 17810, 17795, 17788, -1, 17810, 17788, 17802, -1, 17811, 17801, 17792, -1, 17812, 17799, 17804, -1, 17811, 11845, 17801, -1, 17811, 17792, 17803, -1, 17812, 17806, 17799, -1, 17811, 11852, 11845, -1, 17813, 17791, 17806, -1, 17814, 17794, 17805, -1, 17814, 17803, 17794, -1, 17813, 17797, 17791, -1, 17815, 17798, 17789, -1, 17816, 17804, 3420, -1, 17815, 17789, 17807, -1, 17816, 3420, 3421, -1, 17817, 17795, 17810, -1, 17818, 17809, 17800, -1, 17818, 17800, 17808, -1, 17817, 17819, 17795, -1, 17820, 17805, 17796, -1, 17821, 17806, 17812, -1, 17820, 17796, 17809, -1, 17821, 17813, 17806, -1, 17822, 17797, 17813, -1, 17823, 17803, 17814, -1, 17823, 17811, 17803, -1, 17822, 17802, 17797, -1, 17823, 11852, 17811, -1, 17824, 17808, 17798, -1, 17825, 17804, 17816, -1, 17824, 17798, 17815, -1, 17825, 17812, 17804, -1, 17826, 17820, 17809, -1, 17827, 17816, 3421, -1, 17826, 17809, 17818, -1, 17828, 17805, 17820, -1, 17828, 17814, 17805, -1, 17829, 17830, 17819, -1, 17829, 11763, 11755, -1, 17829, 11755, 17830, -1, 17829, 17819, 17817, -1, 17831, 17822, 17813, -1, 17832, 17808, 17824, -1, 17831, 17813, 17821, -1, 17832, 17818, 17808, -1, 17833, 17802, 17822, -1, 17834, 17820, 17826, -1, 17833, 17810, 17802, -1, 17834, 17828, 17820, -1, 17835, 11852, 17823, -1, 17836, 17812, 17825, -1, 17835, 17814, 17828, -1, 17835, 11864, 11852, -1, 17835, 17823, 17814, -1, 17836, 17821, 17812, -1, 17837, 17827, 3421, -1, 17837, 3421, 3429, -1, 17838, 17816, 17827, -1, 17839, 17826, 17818, -1, 17838, 17825, 17816, -1, 17839, 17818, 17832, -1, 17840, 17828, 17834, -1, 17840, 11864, 17835, -1, 17840, 17835, 17828, -1, 17841, 17833, 17822, -1, 17841, 17822, 17831, -1, 17842, 17810, 17833, -1, 17842, 17817, 17810, -1, 17843, 3417, 3422, -1, 17844, 17831, 17821, -1, 17844, 17821, 17836, -1, 17843, 17845, 3417, -1, 17846, 17838, 17827, -1, 17846, 17827, 17837, -1, 17847, 17826, 17839, -1, 17847, 17834, 17826, -1, 17848, 17836, 17825, -1, 17848, 17825, 17838, -1, 17849, 17850, 17845, -1, 17849, 17845, 17843, -1, 17851, 17833, 17841, -1, 17851, 17842, 17833, -1, 17852, 11785, 11763, -1, 17853, 17834, 17847, -1, 17853, 17840, 17834, -1, 17853, 11864, 17840, -1, 17852, 17829, 17817, -1, 17852, 17817, 17842, -1, 17853, 11876, 11864, -1, 17852, 11763, 17829, -1, 17854, 17831, 17844, -1, 17854, 17841, 17831, -1, 17855, 17837, 3429, -1, 17856, 17857, 17850, -1, 17856, 17850, 17849, -1, 17858, 3422, 3424, -1, 17859, 17838, 17846, -1, 17858, 17843, 3422, -1, 17859, 17848, 17838, -1, 17860, 17836, 17848, -1, 17860, 17844, 17836, -1, 17861, 11791, 11785, -1, 17862, 17863, 17857, -1, 17861, 11785, 17852, -1, 17862, 17857, 17856, -1, 17861, 17842, 17851, -1, 17861, 17852, 17842, -1, 17864, 17851, 17841, -1, 17864, 17841, 17854, -1, 17865, 17858, 3424, -1, 17866, 17837, 17855, -1, 17867, 17849, 17843, -1, 17866, 17846, 17837, -1, 17867, 17843, 17858, -1, 17868, 17860, 17848, -1, 17868, 17848, 17859, -1, 17869, 17870, 17863, -1, 17869, 17863, 17862, -1, 17871, 17854, 17844, -1, 17871, 17844, 17860, -1, 17872, 11791, 17861, -1, 17872, 17851, 17864, -1, 17873, 17867, 17858, -1, 17873, 17858, 17865, -1, 17872, 17861, 17851, -1, 17874, 17846, 17866, -1, 17875, 17856, 17849, -1, 17875, 17849, 17867, -1, 17874, 17859, 17846, -1, 17876, 17871, 17860, -1, 17877, 3424, 3431, -1, 17877, 17865, 3424, -1, 17876, 17860, 17868, -1, 17878, 17879, 17870, -1, 17878, 17870, 17869, -1, 17880, 17854, 17871, -1, 17880, 17864, 17854, -1, 17881, 17875, 17867, -1, 17881, 17867, 17873, -1, 17882, 17859, 17874, -1, 17883, 17862, 17856, -1, 17882, 17868, 17859, -1, 17883, 17856, 17875, -1, 17884, 17880, 17871, -1, 17884, 17871, 17876, -1, 17885, 17872, 17864, -1, 17885, 17864, 17880, -1, 17885, 11812, 11791, -1, 17886, 17873, 17865, -1, 17885, 11791, 17872, -1, 17886, 17865, 17877, -1, 17887, 17876, 17868, -1, 17887, 17868, 17882, -1, 17888, 17877, 3431, -1, 17889, 17890, 17879, -1, 17889, 11891, 17890, -1, 17889, 17879, 17878, -1, 17891, 17880, 17884, -1, 17889, 11900, 11891, -1, 17891, 11812, 17885, -1, 17891, 17885, 17880, -1, 17892, 17876, 17887, -1, 17893, 17883, 17875, -1, 17893, 17875, 17881, -1, 17892, 17884, 17876, -1, 17894, 11820, 11812, -1, 17894, 11812, 17891, -1, 17894, 17891, 17884, -1, 17895, 17862, 17883, -1, 17895, 17869, 17862, -1, 17894, 17884, 17892, -1, 17896, 17873, 17886, -1, 17896, 17881, 17873, -1, 17897, 17888, 3431, -1, 17898, 17899, 17900, -1, 17897, 3431, 3438, -1, 17898, 17901, 17899, -1, 17898, 11868, 17902, -1, 17898, 17902, 17901, -1, 17903, 17877, 17888, -1, 17903, 17886, 17877, -1, 17904, 17883, 17893, -1, 17904, 17895, 17883, -1, 17905, 17869, 17895, -1, 17906, 17907, 17908, -1, 17906, 17909, 17907, -1, 17905, 17878, 17869, -1, 17906, 17908, 17910, -1, 17911, 17881, 17896, -1, 17911, 17893, 17881, -1, 17912, 17888, 17897, -1, 17912, 17903, 17888, -1, 17913, 17914, 17915, -1, 17913, 17915, 11995, -1, 17913, 17916, 17917, -1, 17913, 17917, 17918, -1, 17913, 17918, 17914, -1, 17913, 11995, 17916, -1, 17919, 17896, 17886, -1, 17920, 17819, 17830, -1, 17919, 17886, 17903, -1, 17920, 17793, 17786, -1, 17921, 17895, 17904, -1, 17921, 17905, 17895, -1, 17922, 17889, 17878, -1, 17922, 11900, 17889, -1, 17922, 17878, 17905, -1, 17922, 11910, 11900, -1, 17923, 17892, 17924, -1, 17925, 17904, 17893, -1, 17923, 17894, 17892, -1, 17925, 17893, 17911, -1, 17923, 17924, 3819, -1, 17926, 17899, 17901, -1, 17926, 17927, 17928, -1, 17929, 17897, 3438, -1, 17926, 17901, 17927, -1, 17930, 17900, 17899, -1, 17930, 17899, 17926, -1, 17931, 17903, 17912, -1, 17930, 17932, 17933, -1, 17931, 17919, 17903, -1, 17930, 17933, 17900, -1, 17934, 17900, 17935, -1, 17934, 17935, 11855, -1, 17934, 11868, 17898, -1, 17936, 17911, 17896, -1, 17934, 11855, 11868, -1, 17934, 17898, 17900, -1, 17937, 3968, 3426, -1, 17938, 17853, 17847, -1, 17936, 17896, 17919, -1, 17938, 17847, 17839, -1, 17937, 3426, 3428, -1, 17939, 17905, 17921, -1, 17938, 17940, 17853, -1, 17939, 17922, 17905, -1, 17939, 11910, 17922, -1, 17941, 3926, 3968, -1, 17939, 11922, 11910, -1, 17942, 17921, 17904, -1, 17943, 17870, 17879, -1, 17942, 17904, 17925, -1, 17941, 3968, 17937, -1, 17943, 17940, 17938, -1, 17944, 17853, 17940, -1, 17944, 11876, 17853, -1, 17945, 17912, 17897, -1, 17946, 3890, 3926, -1, 17947, 17940, 17943, -1, 17947, 17944, 17940, -1, 17947, 17879, 17890, -1, 17946, 3926, 17941, -1, 17945, 17897, 17929, -1, 17947, 17943, 17879, -1, 17947, 11876, 17944, -1, 17947, 17890, 11891, -1, 17948, 17919, 17931, -1, 17947, 11891, 11876, -1, 17948, 17936, 17919, -1, 17949, 17908, 17907, -1, 17949, 17907, 17950, -1, 17951, 3428, 3435, -1, 17951, 17937, 3428, -1, 17949, 17950, 17952, -1, 17953, 17925, 17911, -1, 17953, 17911, 17936, -1, 17954, 17955, 17956, -1, 17957, 3809, 3890, -1, 17954, 17908, 17949, -1, 17954, 17910, 17908, -1, 17954, 17956, 17910, -1, 17958, 17939, 17921, -1, 17959, 11941, 17909, -1, 17958, 17921, 17942, -1, 17959, 17909, 17906, -1, 17958, 11922, 17939, -1, 17957, 3890, 17946, -1, 17960, 11941, 17959, -1, 17960, 17910, 17961, -1, 17962, 17951, 3435, -1, 17963, 17931, 17912, -1, 17960, 17906, 17910, -1, 17963, 17912, 17945, -1, 17960, 17961, 11946, -1, 17960, 17959, 17906, -1, 17960, 11946, 11941, -1, 17964, 17937, 17951, -1, 17965, 17953, 17936, -1, 17966, 17917, 17967, -1, 17964, 17941, 17937, -1, 17965, 17936, 17948, -1, 17966, 17967, 17968, -1, 17966, 17918, 17917, -1, 17969, 17970, 17914, -1, 17971, 3810, 3809, -1, 17972, 17942, 17925, -1, 17972, 17925, 17953, -1, 17969, 17914, 17918, -1, 17969, 17973, 17970, -1, 17969, 17918, 17966, -1, 17971, 3809, 17957, -1, 17974, 17786, 17778, -1, 17974, 17920, 17786, -1, 17975, 17951, 17962, -1, 17975, 17964, 17951, -1, 17976, 17974, 17778, -1, 17976, 17819, 17920, -1, 17976, 17920, 17974, -1, 17976, 17778, 17795, -1, 17952, 17948, 17931, -1, 17976, 17795, 17819, -1, 17952, 17931, 17963, -1, 17977, 17941, 17964, -1, 17978, 17793, 17920, -1, 17978, 11737, 17793, -1, 17979, 17920, 17830, -1, 17980, 17953, 17965, -1, 17979, 11737, 17978, -1, 17979, 11755, 11737, -1, 17977, 17946, 17941, -1, 17980, 17972, 17953, -1, 17979, 17978, 17920, -1, 17981, 3435, 3440, -1, 17979, 17830, 11755, -1, 17982, 17887, 17882, -1, 17983, 17958, 17942, -1, 17983, 11922, 17958, -1, 17982, 17892, 17887, -1, 17981, 17962, 3435, -1, 17983, 17942, 17972, -1, 17982, 17924, 17892, -1, 17984, 3736, 3810, -1, 17983, 11932, 11922, -1, 17985, 17924, 17982, -1, 17984, 3810, 17971, -1, 17985, 3788, 3801, -1, 17985, 3819, 17924, -1, 17985, 3801, 3819, -1, 17986, 11820, 17894, -1, 17987, 17964, 17975, -1, 17986, 17894, 17923, -1, 17987, 17977, 17964, -1, 17950, 17965, 17948, -1, 17988, 17946, 17977, -1, 17989, 3837, 11820, -1, 17950, 17948, 17952, -1, 17989, 17986, 17923, -1, 17989, 11820, 17986, -1, 17989, 3819, 3836, -1, 17989, 17923, 3819, -1, 17989, 3836, 3837, -1, 17988, 17957, 17946, -1, 17990, 17928, 17991, -1, 17990, 17926, 17928, -1, 17992, 17972, 17980, -1, 17993, 17962, 17981, -1, 17992, 17983, 17972, -1, 17992, 11932, 17983, -1, 17993, 17975, 17962, -1, 17994, 17981, 3440, -1, 17995, 17996, 17930, -1, 17995, 17990, 17996, -1, 17907, 17980, 17965, -1, 17995, 17930, 17926, -1, 17997, 3817, 3736, -1, 17907, 17965, 17950, -1, 17995, 17926, 17990, -1, 17997, 11912, 3817, -1, 17997, 3736, 17984, -1, 17998, 17930, 17996, -1, 17999, 3442, 3446, -1, 18000, 17930, 17998, -1, 18001, 17977, 17987, -1, 17999, 18002, 3442, -1, 18000, 18003, 17932, -1, 18001, 17988, 17977, -1, 18000, 17932, 17930, -1, 18004, 17957, 17988, -1, 18005, 17839, 17832, -1, 18005, 17938, 17839, -1, 18004, 17971, 17957, -1, 18006, 17975, 17993, -1, 17909, 17980, 17907, -1, 17909, 11932, 17992, -1, 17909, 11941, 11932, -1, 18006, 17987, 17975, -1, 18007, 18005, 18008, -1, 17909, 17992, 17980, -1, 18007, 17938, 18005, -1, 18009, 3440, 3444, -1, 18009, 17994, 3440, -1, 18007, 17943, 17938, -1, 18010, 18002, 17999, -1, 18011, 17993, 17981, -1, 18010, 18012, 18002, -1, 18011, 17981, 17994, -1, 18013, 18007, 18008, -1, 18013, 17943, 18007, -1, 18014, 17863, 17870, -1, 18015, 17988, 18001, -1, 18014, 17943, 18013, -1, 18014, 17870, 17943, -1, 18015, 18004, 17988, -1, 18016, 18017, 18012, -1, 18018, 17952, 17963, -1, 18018, 17949, 17952, -1, 18019, 17971, 18004, -1, 18019, 17984, 17971, -1, 18020, 17949, 18018, -1, 18016, 18012, 18010, -1, 18021, 18001, 17987, -1, 18021, 17987, 18006, -1, 18022, 3446, 3450, -1, 18022, 17999, 3446, -1, 18023, 17949, 18020, -1, 18024, 17954, 17949, -1, 18025, 18011, 17994, -1, 18024, 17949, 18023, -1, 18026, 18017, 17955, -1, 18026, 17955, 17954, -1, 18026, 17954, 18024, -1, 18026, 18024, 18023, -1, 18025, 17994, 18009, -1, 18027, 17993, 18011, -1, 18028, 17955, 18017, -1, 18029, 17968, 18030, -1, 18027, 18006, 17993, -1, 18028, 18017, 18016, -1, 18029, 17966, 17968, -1, 18031, 18004, 18015, -1, 18031, 18019, 18004, -1, 18032, 18022, 3450, -1, 18033, 17997, 17984, -1, 18034, 17969, 17966, -1, 18033, 11912, 17997, -1, 18035, 18010, 17999, -1, 18034, 18036, 17969, -1, 18035, 17999, 18022, -1, 18034, 18029, 18036, -1, 18033, 11903, 11912, -1, 18034, 17966, 18029, -1, 18033, 17984, 18019, -1, 18037, 17969, 18036, -1, 18038, 18015, 18001, -1, 18039, 17973, 17969, -1, 18038, 18001, 18021, -1, 18039, 18040, 17973, -1, 18039, 17969, 18037, -1, 18041, 18009, 3444, -1, 18042, 17882, 17874, -1, 18043, 17956, 17955, -1, 18042, 17982, 17882, -1, 18044, 18027, 18011, -1, 18043, 17955, 18028, -1, 18044, 18011, 18025, -1, 18045, 18006, 18027, -1, 18046, 17982, 18042, -1, 18047, 18035, 18022, -1, 18047, 18022, 18032, -1, 18045, 18021, 18006, -1, 18048, 17982, 18046, -1, 18049, 18016, 18010, -1, 18050, 17985, 17982, -1, 18051, 11903, 18033, -1, 18049, 18010, 18035, -1, 18051, 18033, 18019, -1, 18050, 17982, 18048, -1, 18051, 18019, 18031, -1, 18051, 11893, 11903, -1, 18052, 3788, 17985, -1, 18052, 3770, 3788, -1, 18053, 18031, 18015, -1, 18054, 3450, 3454, -1, 18052, 17985, 18050, -1, 18053, 18015, 18038, -1, 18052, 18050, 18048, -1, 18054, 18032, 3450, -1, 18055, 17996, 17990, -1, 18056, 18025, 18009, -1, 18055, 17991, 18056, -1, 18057, 17956, 18043, -1, 18056, 18009, 18041, -1, 18055, 17990, 17991, -1, 18055, 17998, 17996, -1, 18057, 17910, 17956, -1, 18058, 17998, 18055, -1, 18059, 18027, 18044, -1, 18060, 18049, 18035, -1, 18058, 18000, 17998, -1, 18060, 18035, 18047, -1, 18058, 18003, 18000, -1, 18058, 18061, 18003, -1, 18059, 18045, 18027, -1, 18062, 17832, 17824, -1, 18062, 18008, 18005, -1, 18063, 18028, 18016, -1, 18064, 18038, 18021, -1, 18063, 18016, 18049, -1, 18062, 18013, 18008, -1, 18064, 18021, 18045, -1, 18062, 18005, 17832, -1, 18065, 18013, 18062, -1, 18065, 17857, 17863, -1, 18066, 11893, 18051, -1, 18066, 18031, 18053, -1, 18065, 17863, 18014, -1, 18065, 18014, 18013, -1, 18066, 18051, 18031, -1, 18067, 18047, 18032, -1, 17991, 18025, 18056, -1, 18067, 18032, 18054, -1, 18068, 18018, 17963, -1, 18068, 18020, 18018, -1, 17991, 18044, 18025, -1, 18068, 17963, 17945, -1, 18069, 18012, 18017, -1, 18070, 18054, 3454, -1, 18071, 18045, 18059, -1, 18069, 18023, 18020, -1, 18071, 18064, 18045, -1, 18069, 18020, 18068, -1, 18069, 18017, 18026, -1, 18072, 17961, 17910, -1, 18069, 18026, 18023, -1, 18072, 11946, 17961, -1, 18073, 18053, 18038, -1, 18072, 17910, 18057, -1, 18073, 18038, 18064, -1, 18072, 11959, 11946, -1, 18074, 18030, 18075, -1, 18076, 18049, 18060, -1, 18074, 18037, 18036, -1, 18074, 18029, 18030, -1, 18074, 18036, 18029, -1, 18077, 18037, 18074, -1, 18076, 18063, 18049, -1, 18077, 18078, 18040, -1, 18079, 18043, 18028, -1, 18077, 18040, 18039, -1, 18079, 18028, 18063, -1, 18077, 18039, 18037, -1, 17928, 18059, 18044, -1, 18080, 18042, 17874, -1, 18080, 17874, 17866, -1, 18080, 18046, 18042, -1, 18081, 18060, 18047, -1, 17928, 18044, 17991, -1, 18081, 18047, 18067, -1, 18082, 18046, 18080, -1, 18083, 18073, 18064, -1, 18082, 3762, 3770, -1, 18082, 18048, 18046, -1, 18083, 18064, 18071, -1, 18084, 11893, 18066, -1, 18085, 18067, 18054, -1, 18082, 3770, 18052, -1, 18085, 18054, 18070, -1, 18082, 18052, 18048, -1, 18084, 18053, 18073, -1, 18086, 18055, 18056, -1, 18084, 11880, 11893, -1, 18084, 18066, 18053, -1, 18087, 3454, 3458, -1, 18086, 18056, 18041, -1, 18087, 18070, 3454, -1, 18088, 18079, 18063, -1, 18088, 18063, 18076, -1, 18089, 18055, 18086, -1, 18090, 18058, 18055, -1, 17927, 18059, 17928, -1, 18090, 18061, 18058, -1, 17927, 18071, 18059, -1, 18091, 18057, 18043, -1, 18090, 18055, 18089, -1, 18091, 18043, 18079, -1, 18090, 18092, 18061, -1, 18093, 18073, 18083, -1, 18093, 18084, 18073, -1, 18094, 17824, 17815, -1, 18094, 18062, 17824, -1, 18093, 11880, 18084, -1, 18095, 18076, 18060, -1, 18095, 18060, 18081, -1, 18096, 18062, 18094, -1, 18097, 18081, 18067, -1, 18098, 17850, 17857, -1, 17901, 18083, 18071, -1, 18097, 18067, 18085, -1, 18098, 17857, 18065, -1, 17901, 18071, 17927, -1, 18098, 18065, 18062, -1, 18098, 18062, 18096, -1, 18099, 18069, 18068, -1, 18099, 18068, 17945, -1, 18099, 17945, 17929, -1, 18100, 3448, 3452, -1, 18100, 18092, 3448, -1, 18101, 18085, 18070, -1, 18101, 18070, 18087, -1, 18102, 18069, 18099, -1, 18103, 18079, 18088, -1, 18103, 18091, 18079, -1, 18104, 18069, 18102, -1, 18104, 18012, 18069, -1, 18105, 18072, 18057, -1, 18104, 18002, 18012, -1, 18105, 11959, 18072, -1, 18105, 18057, 18091, -1, 18106, 18075, 18107, -1, 18105, 11966, 11959, -1, 17902, 18093, 18083, -1, 18106, 18074, 18075, -1, 17902, 11868, 11880, -1, 17902, 18083, 17901, -1, 18107, 18087, 3458, -1, 17902, 11880, 18093, -1, 18108, 18074, 18106, -1, 18109, 18088, 18076, -1, 18110, 18061, 18092, -1, 18110, 18092, 18100, -1, 18109, 18076, 18095, -1, 18111, 18078, 18077, -1, 18111, 18112, 18078, -1, 18111, 18074, 18108, -1, 18111, 18077, 18074, -1, 18113, 18082, 18080, -1, 18114, 18095, 18081, -1, 18114, 18081, 18097, -1, 18113, 17866, 17855, -1, 18113, 18080, 17866, -1, 18115, 18097, 18085, -1, 18116, 18003, 18061, -1, 18115, 18085, 18101, -1, 18117, 18082, 18113, -1, 18116, 18061, 18110, -1, 18118, 18091, 18103, -1, 18118, 18105, 18091, -1, 18119, 3759, 3762, -1, 18118, 11966, 18105, -1, 18119, 18082, 18117, -1, 18119, 3762, 18082, -1, 18120, 3452, 3456, -1, 18118, 11974, 11966, -1, 18121, 18041, 3444, -1, 18075, 18101, 18087, -1, 18121, 18086, 18041, -1, 18075, 18087, 18107, -1, 18121, 18089, 18086, -1, 18120, 18100, 3452, -1, 18122, 18121, 3444, -1, 18122, 3444, 3448, -1, 18122, 18090, 18089, -1, 18122, 18092, 18090, -1, 18122, 3448, 18092, -1, 18122, 18089, 18121, -1, 18123, 18088, 18109, -1, 18123, 18103, 18088, -1, 18124, 18094, 17815, -1, 18125, 18109, 18095, -1, 18124, 18096, 18094, -1, 18124, 17815, 17807, -1, 18126, 17845, 17850, -1, 18126, 18096, 18124, -1, 18126, 17850, 18098, -1, 18127, 17932, 18003, -1, 18126, 18098, 18096, -1, 18125, 18095, 18114, -1, 18127, 18003, 18116, -1, 18128, 18114, 18097, -1, 18128, 18097, 18115, -1, 18129, 18120, 3456, -1, 18130, 3438, 3442, -1, 18130, 17929, 3438, -1, 18130, 18099, 17929, -1, 18130, 18102, 18099, -1, 18131, 18100, 18120, -1, 18132, 18130, 3442, -1, 18030, 18115, 18101, -1, 18132, 18104, 18102, -1, 18132, 18002, 18104, -1, 18132, 3442, 18002, -1, 18132, 18102, 18130, -1, 18030, 18101, 18075, -1, 18133, 18118, 18103, -1, 18131, 18110, 18100, -1, 18133, 18103, 18123, -1, 18134, 18108, 18106, -1, 18134, 18107, 3458, -1, 18133, 11974, 18118, -1, 18134, 18106, 18107, -1, 18135, 3458, 3462, -1, 18135, 3462, 18112, -1, 18135, 18134, 3458, -1, 18136, 18109, 18125, -1, 18135, 18112, 18111, -1, 18136, 18123, 18109, -1, 18135, 18111, 18108, -1, 18137, 17933, 17932, -1, 18135, 18108, 18134, -1, 18138, 3429, 3434, -1, 18138, 17855, 3429, -1, 18137, 17932, 18127, -1, 18139, 18125, 18114, -1, 18138, 18117, 18113, -1, 18139, 18114, 18128, -1, 18138, 18113, 17855, -1, 18140, 18119, 18117, -1, 18140, 3434, 3759, -1, 18141, 18120, 18129, -1, 18140, 18117, 18138, -1, 18140, 3759, 18119, -1, 18140, 18138, 3434, -1, 18141, 18131, 18120, -1, 18142, 18126, 18124, -1, 18142, 3508, 3417, -1, 18143, 18116, 18110, -1, 18142, 17845, 18126, -1, 18142, 17807, 3508, -1, 18143, 18110, 18131, -1, 18142, 3417, 17845, -1, 18142, 18124, 17807, -1, 17968, 18128, 18115, -1, 17968, 18115, 18030, -1, 18144, 18129, 3456, -1, 18144, 3456, 3460, -1, 18145, 18133, 18123, -1, 18145, 18123, 18136, -1, 18145, 11974, 18133, -1, 18146, 17933, 18137, -1, 18145, 11984, 11974, -1, 18146, 17900, 17933, -1, 18147, 18125, 18139, -1, 18148, 18143, 18131, -1, 18148, 18131, 18141, -1, 18147, 18136, 18125, -1, 18149, 18116, 18143, -1, 18149, 18127, 18116, -1, 17967, 18128, 17968, -1, 17967, 18139, 18128, -1, 18150, 18141, 18129, -1, 18151, 18145, 18136, -1, 18151, 18136, 18147, -1, 18150, 18129, 18144, -1, 18151, 11984, 18145, -1, 18152, 18144, 3460, -1, 18153, 17935, 17900, -1, 18153, 11855, 17935, -1, 18153, 17900, 18146, -1, 18153, 11847, 11855, -1, 18154, 18143, 18148, -1, 17917, 18147, 18139, -1, 17917, 18139, 17967, -1, 18154, 18149, 18143, -1, 18155, 3462, 3466, -1, 18156, 18137, 18127, -1, 18156, 18127, 18149, -1, 18155, 18112, 3462, -1, 18157, 18141, 18150, -1, 18157, 18148, 18141, -1, 18158, 18144, 18152, -1, 17916, 18151, 18147, -1, 18158, 18150, 18144, -1, 17916, 18147, 17917, -1, 17916, 11984, 18151, -1, 17916, 11995, 11984, -1, 18159, 18152, 3460, -1, 18159, 3460, 3464, -1, 18160, 18078, 18112, -1, 18161, 18149, 18154, -1, 18160, 18112, 18155, -1, 18161, 18156, 18149, -1, 18162, 18137, 18156, -1, 18162, 18146, 18137, -1, 18163, 18154, 18148, -1, 18164, 18040, 18078, -1, 18163, 18148, 18157, -1, 18164, 18078, 18160, -1, 18165, 18150, 18158, -1, 18166, 3466, 3470, -1, 18165, 18157, 18150, -1, 18166, 18155, 3466, -1, 18167, 18152, 18159, -1, 18167, 18158, 18152, -1, 18168, 18162, 18156, -1, 18168, 18156, 18161, -1, 18169, 17973, 18040, -1, 18169, 18040, 18164, -1, 18170, 18146, 18162, -1, 18170, 18153, 18146, -1, 18170, 11847, 18153, -1, 18170, 11834, 11847, -1, 18171, 18166, 3470, -1, 18172, 18159, 3464, -1, 18173, 18161, 18154, -1, 18174, 18160, 18155, -1, 18173, 18154, 18163, -1, 18174, 18155, 18166, -1, 18175, 18163, 18157, -1, 18175, 18157, 18165, -1, 17915, 12005, 11995, -1, 18176, 18165, 18158, -1, 18177, 17973, 18169, -1, 18177, 17970, 17973, -1, 18176, 18158, 18167, -1, 18178, 18170, 18162, -1, 18179, 18174, 18166, -1, 18178, 18162, 18168, -1, 18178, 11827, 11834, -1, 18179, 18166, 18171, -1, 18178, 11834, 18170, -1, 18180, 3464, 3468, -1, 18180, 18172, 3464, -1, 18181, 18160, 18174, -1, 18182, 18159, 18172, -1, 18181, 18164, 18160, -1, 18183, 18171, 3470, -1, 18182, 18167, 18159, -1, 18183, 3470, 3474, -1, 18184, 17914, 17970, -1, 18185, 18168, 18161, -1, 18185, 18161, 18173, -1, 18184, 17970, 18177, -1, 18186, 18163, 18175, -1, 18186, 18173, 18163, -1, 18187, 18174, 18179, -1, 18187, 18181, 18174, -1, 18188, 18169, 18164, -1, 18189, 18175, 18165, -1, 18189, 18165, 18176, -1, 18190, 18182, 18172, -1, 18188, 18164, 18181, -1, 18191, 18179, 18171, -1, 18190, 18172, 18180, -1, 18191, 18171, 18183, -1, 18192, 18167, 18182, -1, 18193, 18183, 3474, -1, 18192, 18176, 18167, -1, 18194, 12013, 12005, -1, 18195, 18168, 18185, -1, 18194, 17915, 17914, -1, 18195, 18178, 18168, -1, 18194, 12005, 17915, -1, 18195, 11827, 18178, -1, 18194, 17914, 18184, -1, 18196, 18173, 18186, -1, 18197, 18181, 18187, -1, 18197, 18188, 18181, -1, 18196, 18185, 18173, -1, 18198, 18175, 18189, -1, 18199, 18177, 18169, -1, 18198, 18186, 18175, -1, 18199, 18169, 18188, -1, 18200, 18192, 18182, -1, 18200, 18182, 18190, -1, 18201, 18187, 18179, -1, 18201, 18179, 18191, -1, 18202, 18191, 18183, -1, 18203, 18180, 3468, -1, 18202, 18183, 18193, -1, 18204, 18189, 18176, -1, 18205, 18193, 3474, -1, 18204, 18176, 18192, -1, 18205, 3474, 3478, -1, 18206, 11827, 18195, -1, 18206, 18195, 18185, -1, 18207, 18188, 18197, -1, 18206, 18185, 18196, -1, 18207, 18199, 18188, -1, 18206, 11811, 11827, -1, 18208, 18186, 18198, -1, 18209, 18184, 18177, -1, 18209, 18177, 18199, -1, 18208, 18196, 18186, -1, 18210, 18192, 18200, -1, 18210, 18204, 18192, -1, 18211, 18197, 18187, -1, 18211, 18187, 18201, -1, 18212, 18190, 18180, -1, 18212, 18180, 18203, -1, 18213, 18201, 18191, -1, 18213, 18191, 18202, -1, 18214, 18198, 18189, -1, 18215, 18202, 18193, -1, 18215, 18193, 18205, -1, 18214, 18189, 18204, -1, 18216, 18206, 18196, -1, 18216, 11811, 18206, -1, 18216, 18196, 18208, -1, 18217, 18199, 18207, -1, 18217, 18209, 18199, -1, 18218, 18214, 18204, -1, 18218, 18204, 18210, -1, 18219, 12024, 12013, -1, 18219, 12013, 18194, -1, 18219, 18194, 18184, -1, 18220, 18200, 18190, -1, 18219, 18184, 18209, -1, 18220, 18190, 18212, -1, 18221, 18205, 3478, -1, 18222, 18208, 18198, -1, 18222, 18198, 18214, -1, 18223, 18197, 18211, -1, 18223, 18207, 18197, -1, 18224, 3468, 3472, -1, 18225, 18201, 18213, -1, 18225, 18211, 18201, -1, 18224, 18203, 3468, -1, 18226, 18214, 18218, -1, 18227, 18213, 18202, -1, 18226, 18222, 18214, -1, 18227, 18202, 18215, -1, 18228, 12036, 12024, -1, 18228, 12024, 18219, -1, 18229, 18200, 18220, -1, 18228, 18219, 18209, -1, 18228, 18209, 18217, -1, 18230, 3478, 3482, -1, 18229, 18210, 18200, -1, 18231, 11811, 18216, -1, 18230, 18221, 3478, -1, 18231, 18208, 18222, -1, 18231, 18216, 18208, -1, 18231, 11800, 11811, -1, 18232, 18215, 18205, -1, 18232, 18205, 18221, -1, 18233, 18203, 18224, -1, 18233, 18212, 18203, -1, 18234, 18217, 18207, -1, 18235, 18222, 18226, -1, 18234, 18207, 18223, -1, 18235, 18231, 18222, -1, 18235, 11800, 18231, -1, 18236, 18210, 18229, -1, 18236, 18218, 18210, -1, 18237, 18223, 18211, -1, 18237, 18211, 18225, -1, 18238, 18225, 18213, -1, 18239, 18212, 18233, -1, 18238, 18213, 18227, -1, 18239, 18220, 18212, -1, 18240, 3472, 3476, -1, 18240, 18224, 3472, -1, 18241, 18221, 18230, -1, 18241, 18232, 18221, -1, 18242, 18227, 18215, -1, 18243, 18226, 18218, -1, 18242, 18215, 18232, -1, 18243, 18218, 18236, -1, 18244, 18217, 18234, -1, 18244, 12036, 18228, -1, 18244, 18228, 18217, -1, 18245, 18234, 18223, -1, 18246, 18240, 3476, -1, 18247, 18229, 18220, -1, 18245, 18223, 18237, -1, 18248, 18237, 18225, -1, 18247, 18220, 18239, -1, 18248, 18225, 18238, -1, 18249, 18224, 18240, -1, 18249, 18233, 18224, -1, 18250, 18242, 18232, -1, 18250, 18232, 18241, -1, 18251, 18235, 18226, -1, 18251, 11794, 11800, -1, 18251, 11800, 18235, -1, 18251, 18226, 18243, -1, 18252, 18230, 3482, -1, 18253, 18249, 18240, -1, 18254, 18238, 18227, -1, 18253, 18240, 18246, -1, 18254, 18227, 18242, -1, 18255, 12041, 12036, -1, 18256, 18236, 18229, -1, 18255, 12036, 18244, -1, 18255, 18234, 18245, -1, 18256, 18229, 18247, -1, 18255, 18244, 18234, -1, 18257, 18237, 18248, -1, 18257, 18245, 18237, -1, 18258, 18239, 18233, -1, 18258, 18233, 18249, -1, 18259, 18242, 18250, -1, 18259, 18254, 18242, -1, 18260, 3476, 3480, -1, 18260, 18246, 3476, -1, 18261, 18258, 18249, -1, 18261, 18249, 18253, -1, 18262, 18241, 18230, -1, 18262, 18230, 18252, -1, 18263, 18248, 18238, -1, 18264, 18236, 18256, -1, 18263, 18238, 18254, -1, 18264, 18243, 18236, -1, 18265, 18247, 18239, -1, 18266, 18255, 18245, -1, 18266, 18245, 18257, -1, 18266, 12041, 18255, -1, 18265, 18239, 18258, -1, 18267, 18253, 18246, -1, 18268, 18254, 18259, -1, 18267, 18246, 18260, -1, 18268, 18263, 18254, -1, 18269, 18241, 18262, -1, 18270, 18260, 3480, -1, 18269, 18250, 18241, -1, 18271, 18257, 18248, -1, 18271, 18248, 18263, -1, 18272, 18258, 18261, -1, 18272, 18265, 18258, -1, 18273, 18251, 18243, -1, 18274, 18252, 3482, -1, 18274, 3482, 3486, -1, 18273, 11784, 11794, -1, 18273, 11794, 18251, -1, 18273, 18243, 18264, -1, 18275, 18256, 18247, -1, 18276, 18271, 18263, -1, 18276, 18263, 18268, -1, 18275, 18247, 18265, -1, 18277, 18259, 18250, -1, 18277, 18250, 18269, -1, 18278, 12050, 12041, -1, 18278, 12041, 18266, -1, 18279, 18253, 18267, -1, 18278, 18257, 18271, -1, 18279, 18261, 18253, -1, 18278, 18266, 18257, -1, 18280, 18267, 18260, -1, 18280, 18260, 18270, -1, 18281, 3480, 3484, -1, 18282, 18252, 18274, -1, 18282, 18262, 18252, -1, 18281, 18270, 3480, -1, 18283, 12050, 18278, -1, 18284, 18265, 18272, -1, 18283, 18271, 18276, -1, 18284, 18275, 18265, -1, 18283, 18278, 18271, -1, 18285, 18259, 18277, -1, 18285, 18268, 18259, -1, 18286, 18256, 18275, -1, 18286, 18264, 18256, -1, 18287, 18262, 18282, -1, 18287, 18269, 18262, -1, 18288, 18272, 18261, -1, 18288, 18261, 18279, -1, 18289, 18267, 18280, -1, 18289, 18279, 18267, -1, 18290, 3486, 3490, -1, 18290, 18274, 3486, -1, 18291, 18280, 18270, -1, 18292, 18276, 18268, -1, 18292, 18268, 18285, -1, 18291, 18270, 18281, -1, 18293, 18286, 18275, -1, 18293, 18275, 18284, -1, 18294, 18290, 3490, -1, 18295, 18273, 18264, -1, 18295, 11784, 18273, -1, 18296, 18277, 18269, -1, 18296, 18269, 18287, -1, 18295, 11772, 11784, -1, 18295, 18264, 18286, -1, 18297, 18281, 3484, -1, 18298, 18284, 18272, -1, 18298, 18272, 18288, -1, 18299, 18282, 18274, -1, 18299, 18274, 18290, -1, 18300, 11674, 12050, -1, 18301, 18288, 18279, -1, 18300, 12050, 18283, -1, 18301, 18279, 18289, -1, 18300, 18276, 18292, -1, 18300, 18283, 18276, -1, 18302, 18280, 18291, -1, 18302, 18289, 18280, -1, 18303, 18290, 18294, -1, 18303, 18299, 18290, -1, 18304, 18295, 18286, -1, 18304, 18286, 18293, -1, 18305, 18277, 18296, -1, 18305, 18285, 18277, -1, 18304, 11772, 18295, -1, 18304, 11776, 11772, -1, 18306, 3484, 3488, -1, 18306, 18297, 3484, -1, 18307, 18282, 18299, -1, 18307, 18287, 18282, -1, 18308, 18291, 18281, -1, 18308, 18281, 18297, -1, 18309, 3490, 3494, -1, 18309, 18294, 3490, -1, 18310, 18293, 18284, -1, 18310, 18284, 18298, -1, 18311, 18299, 18303, -1, 18312, 18298, 18288, -1, 18312, 18288, 18301, -1, 18311, 18307, 18299, -1, 18313, 18285, 18305, -1, 18314, 18301, 18289, -1, 18314, 18289, 18302, -1, 18313, 18292, 18285, -1, 18315, 18287, 18307, -1, 18315, 18296, 18287, -1, 18316, 18297, 18306, -1, 18317, 18294, 18309, -1, 18316, 18308, 18297, -1, 18318, 18302, 18291, -1, 18318, 18291, 18308, -1, 18317, 18303, 18294, -1, 18319, 18309, 3494, -1, 18320, 18304, 18293, -1, 18320, 18293, 18310, -1, 18320, 11776, 18304, -1, 18321, 18315, 18307, -1, 18321, 18307, 18311, -1, 18322, 18298, 18312, -1, 18322, 18310, 18298, -1, 18323, 18300, 18292, -1, 18323, 11672, 11674, -1, 18323, 18292, 18313, -1, 18324, 18312, 18301, -1, 18323, 11674, 18300, -1, 18325, 18305, 18296, -1, 18324, 18301, 18314, -1, 18325, 18296, 18315, -1, 18326, 18306, 3488, -1, 18327, 18311, 18303, -1, 18328, 18318, 18308, -1, 18327, 18303, 18317, -1, 18328, 18308, 18316, -1, 18329, 18302, 18318, -1, 18330, 18317, 18309, -1, 18330, 18309, 18319, -1, 18329, 18314, 18302, -1, 18331, 11776, 18320, -1, 18331, 18310, 18322, -1, 18332, 18319, 3494, -1, 18331, 11787, 11776, -1, 18332, 3494, 3498, -1, 18331, 18320, 18310, -1, 18333, 18312, 18324, -1, 18334, 18325, 18315, -1, 18334, 18315, 18321, -1, 18333, 18322, 18312, -1, 18335, 18316, 18306, -1, 18336, 18305, 18325, -1, 18335, 18306, 18326, -1, 18336, 18313, 18305, -1, 18337, 18318, 18328, -1, 18337, 18329, 18318, -1, 18338, 18321, 18311, -1, 18338, 18311, 18327, -1, 18339, 18324, 18314, -1, 18339, 18314, 18329, -1, 18340, 18327, 18317, -1, 18340, 18317, 18330, -1, 18341, 18331, 18322, -1, 18341, 11787, 18331, -1, 18342, 18319, 18332, -1, 18341, 18322, 18333, -1, 18342, 18330, 18319, -1, 18343, 18316, 18335, -1, 18343, 18328, 18316, -1, 18344, 18325, 18334, -1, 18344, 18336, 18325, -1, 18345, 11679, 11672, -1, 18346, 18339, 18329, -1, 18346, 18329, 18337, -1, 18345, 18323, 18313, -1, 18345, 18313, 18336, -1, 18345, 11672, 18323, -1, 18347, 18333, 18324, -1, 18347, 18324, 18339, -1, 18348, 18332, 3498, -1, 18349, 18326, 3488, -1, 18349, 3488, 3492, -1, 18350, 18334, 18321, -1, 18350, 18321, 18338, -1, 18351, 18327, 18340, -1, 18352, 18328, 18343, -1, 18352, 18337, 18328, -1, 18351, 18338, 18327, -1, 18353, 18339, 18346, -1, 18353, 18347, 18339, -1, 18354, 18340, 18330, -1, 18354, 18330, 18342, -1, 18355, 11787, 18341, -1, 18355, 18333, 18347, -1, 18356, 11696, 11679, -1, 18355, 18341, 18333, -1, 18356, 11679, 18345, -1, 18355, 11796, 11787, -1, 18356, 18336, 18344, -1, 18356, 18345, 18336, -1, 18357, 18326, 18349, -1, 18357, 18335, 18326, -1, 17739, 3498, 3502, -1, 17739, 18348, 3498, -1, 18358, 18346, 18337, -1, 18359, 18332, 18348, -1, 18358, 18337, 18352, -1, 18359, 18342, 18332, -1, 18360, 18347, 18353, -1, 18360, 18355, 18347, -1, 18361, 18344, 18334, -1, 18360, 11796, 18355, -1, 18361, 18334, 18350, -1, 17737, 18335, 18357, -1, 17733, 18350, 18338, -1, 17733, 18338, 18351, -1, 17737, 18343, 18335, -1, 17749, 18349, 3492, -1, 17751, 18351, 18340, -1, 17751, 18340, 18354, -1, 17749, 3492, 3496, -1, 17759, 18353, 18346, -1, 17759, 18346, 18358, -1, 17741, 18348, 17739, -1, 17741, 18359, 18348, -1, 17736, 18352, 18343, -1, 17736, 18343, 17737, -1, 17744, 18354, 18342, -1, 17744, 18342, 18359, -1, 18362, 11696, 18356, -1, 18362, 18344, 18361, -1, 18362, 18356, 18344, -1, 17748, 18357, 18349, -1, 17748, 18349, 17749, -1, 17757, 18361, 18350, -1, 17757, 18350, 17733, -1, 17758, 18360, 18353, -1, 17758, 11796, 18360, -1, 17758, 18353, 17759, -1, 17734, 18351, 17751, -1, 17758, 11808, 11796, -1, 17734, 17733, 18351, -1, 17763, 18358, 18352, -1, 17763, 18352, 17736, -1, 17740, 17739, 3502, -1, 17745, 17744, 18359, -1, 17742, 17737, 18357, -1, 17742, 18357, 17748, -1, 17745, 18359, 17741, -1, 17746, 18354, 17744, -1, 17752, 3496, 3500, -1, 17746, 17751, 18354, -1, 17752, 17749, 3496, -1, 17756, 18362, 18361, -1, 17756, 11706, 11696, -1, 17760, 17759, 18358, -1, 17756, 11696, 18362, -1, 17760, 18358, 17763, -1, 17756, 18361, 17757, -1, 17732, 17757, 17733, -1, 4338, 4364, 3542, -1, 4999, 4284, 4195, -1, 3560, 4384, 3584, -1, 4195, 4284, 4220, -1, 4364, 4384, 3560, -1, 4284, 4294, 4220, -1, 3584, 4447, 3647, -1, 4220, 4294, 3550, -1, 4384, 4447, 3584, -1, 3436, 4588, 3434, -1, 3434, 4588, 3757, -1, 4294, 4332, 3550, -1, 3647, 4448, 3648, -1, 3550, 4332, 3552, -1, 4447, 4448, 3647, -1, 4588, 4629, 3757, -1, 3757, 4629, 3779, -1, 4332, 4356, 3552, -1, 3552, 4356, 3570, -1, 3648, 4490, 3668, -1, 4448, 4490, 3648, -1, 4629, 4670, 3779, -1, 3779, 4670, 3813, -1, 4356, 4381, 3570, -1, 3570, 4381, 3589, -1, 3668, 4528, 3687, -1, 4490, 4528, 3668, -1, 4670, 4698, 3813, -1, 3813, 4698, 3852, -1, 4381, 4407, 3589, -1, 3589, 4407, 3607, -1, 3687, 4565, 3720, -1, 4528, 4565, 3687, -1, 4698, 4702, 3852, -1, 3852, 4702, 3954, -1, 4407, 4425, 3607, -1, 3607, 4425, 3633, -1, 4565, 4655, 3720, -1, 3720, 4655, 3843, -1, 4425, 3427, 3633, -1, 4702, 4754, 3954, -1, 3633, 3427, 3426, -1, 3954, 4754, 3955, -1, 4655, 4658, 3843, -1, 3843, 4658, 3844, -1, 4754, 4776, 3955, -1, 3955, 4776, 3979, -1, 4658, 4695, 3844, -1, 3844, 4695, 3868, -1, 4776, 4806, 3979, -1, 3979, 4806, 4001, -1, 4695, 4729, 3868, -1, 3868, 4729, 3904, -1, 4806, 4833, 4001, -1, 4001, 4833, 4021, -1, 4729, 4717, 3904, -1, 3904, 4717, 3940, -1, 4833, 4854, 4021, -1, 4021, 4854, 4047, -1, 4717, 4716, 3940, -1, 3940, 4716, 3988, -1, 4854, 4901, 4047, -1, 4047, 4901, 4098, -1, 4716, 4794, 3988, -1, 3988, 4794, 4015, -1, 4901, 4925, 4098, -1, 4098, 4925, 4118, -1, 4794, 4821, 4015, -1, 4015, 4821, 4027, -1, 4925, 4955, 4118, -1, 4118, 4955, 4141, -1, 4821, 4850, 4027, -1, 4027, 4850, 4049, -1, 4955, 4981, 4141, -1, 4141, 4981, 4167, -1, 4850, 4876, 4049, -1, 4049, 4876, 4072, -1, 4981, 4285, 4167, -1, 4167, 4285, 4197, -1, 4876, 4897, 4072, -1, 4072, 4897, 4103, -1, 4197, 4287, 4246, -1, 4285, 4287, 4197, -1, 4897, 4944, 4103, -1, 4103, 4944, 4151, -1, 4246, 4311, 3516, -1, 4287, 4311, 4246, -1, 4944, 4969, 4151, -1, 4151, 4969, 4172, -1, 3516, 4338, 3542, -1, 4311, 4338, 3516, -1, 4969, 4999, 4172, -1, 3542, 4364, 3560, -1, 4172, 4999, 4195, -1, 57, 11192, 1822, -1, 11193, 11192, 57, -1, 1822, 11190, 1803, -1, 11192, 11190, 1822, -1, 1803, 11188, 1789, -1, 11190, 11188, 1803, -1, 1789, 11184, 1758, -1, 11188, 11184, 1789, -1, 1758, 11178, 1755, -1, 11184, 11178, 1758, -1, 1755, 11173, 3326, -1, 11178, 11173, 1755, -1, 1726, 11243, 1697, -1, 11244, 11243, 1726, -1, 1697, 11240, 1660, -1, 11243, 11240, 1697, -1, 1660, 11239, 1640, -1, 11240, 11239, 1660, -1, 11125, 1664, 1659, -1, 11125, 11124, 1664, -1, 1664, 11123, 1716, -1, 11124, 11123, 1664, -1, 11123, 1725, 1716, -1, 11123, 11128, 1725, -1, 1725, 11129, 1756, -1, 11128, 11129, 1725, -1, 1756, 11135, 1771, -1, 11129, 11135, 1756, -1, 1771, 11134, 50, -1, 11135, 11134, 1771, -1, 52, 11148, 1801, -1, 11149, 11148, 52, -1, 1801, 11147, 1834, -1, 11148, 11147, 1801, -1, 1834, 11152, 55, -1, 11147, 11152, 1834, -1, 55, 11153, 1862, -1, 11152, 11153, 55, -1, 1862, 11159, 1873, -1, 11153, 11159, 1862, -1, 1873, 11158, 274, -1, 11159, 11158, 1873, -1, 272, 11064, 1901, -1, 11065, 11064, 272, -1, 1901, 11063, 1926, -1, 11064, 11063, 1901, -1, 1926, 11069, 307, -1, 11063, 11069, 1926, -1, 307, 11068, 1964, -1, 11069, 11068, 307, -1, 1964, 11075, 1983, -1, 11068, 11075, 1964, -1, 1983, 11074, 603, -1, 11075, 11074, 1983, -1, 601, 11088, 2009, -1, 11089, 11088, 601, -1, 2009, 11087, 2018, -1, 11088, 11087, 2009, -1, 2018, 11092, 768, -1, 11087, 11092, 2018, -1, 768, 11093, 2053, -1, 11092, 11093, 768, -1, 2053, 11099, 2063, -1, 11093, 11099, 2053, -1, 2063, 11098, 1384, -1, 11099, 11098, 2063, -1, 1382, 14698, 2095, -1, 14703, 14698, 1382, -1, 2114, 11457, 2115, -1, 2114, 13451, 11457, -1, 2114, 13449, 13451, -1, 2095, 13452, 2114, -1, 14698, 13452, 2095, -1, 2114, 13450, 13449, -1, 13452, 13454, 2114, -1, 2114, 13454, 13450, -1, 17021, 1395, 11437, -1, 17022, 1395, 17021, -1, 17024, 1395, 17022, -1, 17025, 1395, 17024, -1, 11437, 1395, 1394, -1, 17025, 17028, 1395, -1, 17028, 17694, 1395, -1, 17694, 2086, 1395, -1, 17694, 17692, 2086, -1, 17692, 1383, 2086, -1, 17692, 17691, 1383, -1, 17691, 2054, 1383, -1, 17691, 17690, 2054, -1, 2054, 17687, 782, -1, 17690, 17687, 2054, -1, 17687, 623, 782, -1, 17687, 17686, 623, -1, 628, 11274, 2010, -1, 11275, 11274, 628, -1, 2010, 11272, 1999, -1, 11274, 11272, 2010, -1, 1999, 11270, 602, -1, 11272, 11270, 1999, -1, 602, 11266, 1966, -1, 11270, 11266, 602, -1, 1966, 11260, 311, -1, 11266, 11260, 1966, -1, 311, 11255, 308, -1, 11260, 11255, 311, -1, 309, 11219, 1916, -1, 11220, 11219, 309, -1, 1916, 11217, 1902, -1, 11219, 11217, 1916, -1, 1902, 11216, 273, -1, 11217, 11216, 1902, -1, 273, 11215, 1863, -1, 11216, 11215, 273, -1, 1863, 11211, 59, -1, 11215, 11211, 1863, -1, 59, 11210, 56, -1, 11211, 11210, 59, -1, 1640, 11241, 1619, -1, 11239, 11241, 1640, -1, 1619, 11235, 1599, -1, 11241, 11235, 1619, -1, 1599, 11865, 3268, -1, 1599, 17706, 11865, -1, 1599, 17722, 17706, -1, 11235, 11234, 1599, -1, 1599, 17725, 17722, -1, 11234, 17726, 1599, -1, 1599, 17726, 17725, -1, 11848, 1600, 1598, -1, 16357, 1600, 11848, -1, 16359, 1600, 16357, -1, 16360, 1600, 16359, -1, 16364, 1600, 16360, -1, 11104, 1600, 16364, -1, 1600, 11103, 1620, -1, 11104, 11103, 1600, -1, 11103, 1639, 1620, -1, 11103, 11111, 1639, -1, 18363, 18364, 18365, -1, 82, 18366, 69, -1, 6, 11923, 11897, -1, 18367, 18368, 18369, -1, 6, 11924, 11923, -1, 6, 9, 11924, -1, 18370, 6, 11897, -1, 4, 6, 18370, -1, 18371, 18372, 18373, -1, 18374, 4, 18370, -1, 18375, 18376, 18377, -1, 7, 4, 18374, -1, 18375, 18378, 18376, -1, 18379, 18366, 82, -1, 18380, 11884, 11905, -1, 18381, 18367, 18369, -1, 18382, 18383, 18384, -1, 18385, 7, 18374, -1, 18386, 18387, 18388, -1, 18386, 18388, 18368, -1, 18386, 18368, 18367, -1, 18389, 3366, 7, -1, 18390, 18382, 18384, -1, 18389, 7, 18385, -1, 18391, 18392, 18393, -1, 18391, 18394, 18392, -1, 18395, 18396, 18397, -1, 18398, 3384, 3366, -1, 18398, 3366, 18389, -1, 18399, 18396, 18395, -1, 18400, 3384, 18398, -1, 18401, 18402, 18403, -1, 18404, 18385, 18405, -1, 18406, 18407, 18408, -1, 18404, 18389, 18385, -1, 18406, 18408, 18409, -1, 20, 3384, 18400, -1, 18410, 18411, 18412, -1, 85, 18379, 82, -1, 18413, 18405, 18414, -1, 18413, 18404, 18405, -1, 18415, 18367, 18381, -1, 18416, 18417, 18418, -1, 18419, 18, 20, -1, 18420, 18372, 18371, -1, 18421, 18414, 18417, -1, 18421, 18413, 18414, -1, 75, 18, 18419, -1, 18422, 18423, 18424, -1, 18425, 18415, 18381, -1, 18426, 18420, 18371, -1, 18427, 18382, 18390, -1, 18428, 75, 18419, -1, 18429, 18423, 18422, -1, 103, 75, 18428, -1, 18430, 11881, 11879, -1, 18430, 11851, 11881, -1, 18431, 18393, 18432, -1, 18431, 18391, 18393, -1, 11830, 18430, 11879, -1, 18433, 18411, 18410, -1, 92, 18379, 85, -1, 18434, 18435, 18436, -1, 18437, 18417, 18416, -1, 18437, 18421, 18417, -1, 18438, 18421, 18437, -1, 18438, 18439, 18421, -1, 18440, 18406, 18409, -1, 18441, 18415, 18425, -1, 18440, 18409, 18442, -1, 18443, 103, 18428, -1, 18444, 18439, 18438, -1, 18445, 18446, 18447, -1, 18448, 103, 18443, -1, 18448, 147, 103, -1, 18449, 18402, 18401, -1, 18450, 18433, 18410, -1, 18451, 18430, 11830, -1, 18452, 179, 147, -1, 18452, 147, 18448, -1, 18453, 11960, 11967, -1, 11444, 11352, 18454, -1, 11973, 18453, 11967, -1, 18455, 18420, 18426, -1, 18456, 18457, 18458, -1, 18459, 18435, 18434, -1, 18460, 18411, 18433, -1, 18461, 18462, 18463, -1, 18460, 18464, 18411, -1, 18465, 179, 18452, -1, 116, 18466, 18467, -1, 18468, 18443, 18469, -1, 116, 18467, 92, -1, 18468, 18448, 18443, -1, 18470, 18471, 18472, -1, 200, 179, 18465, -1, 18473, 18455, 18426, -1, 18474, 18441, 18425, -1, 18475, 18462, 18461, -1, 18474, 18425, 18476, -1, 18477, 18475, 18461, -1, 18478, 18432, 18446, -1, 11452, 11444, 18454, -1, 18478, 18431, 18432, -1, 18479, 18469, 18480, -1, 18481, 18433, 18450, -1, 18479, 18468, 18469, -1, 18482, 11452, 18454, -1, 18482, 18454, 18483, -1, 18482, 18483, 18484, -1, 18485, 18481, 18450, -1, 18486, 18457, 18456, -1, 18487, 18488, 18489, -1, 18490, 18486, 18456, -1, 18491, 11806, 11856, -1, 11854, 18491, 11856, -1, 18492, 18478, 18446, -1, 18493, 18475, 18477, -1, 18492, 18446, 18445, -1, 128, 18494, 18466, -1, 128, 18466, 116, -1, 11363, 11452, 18482, -1, 18495, 18496, 18497, -1, 18498, 231, 200, -1, 18499, 18455, 18473, -1, 18495, 18500, 18496, -1, 18501, 18493, 18477, -1, 267, 231, 18498, -1, 11591, 11592, 18502, -1, 18503, 18480, 18488, -1, 18503, 18479, 18480, -1, 18504, 18488, 18487, -1, 18504, 18503, 18488, -1, 18505, 18486, 18490, -1, 18506, 18493, 18501, -1, 18507, 18505, 18490, -1, 18508, 18481, 18485, -1, 18509, 267, 18498, -1, 281, 267, 18509, -1, 146, 18510, 18494, -1, 146, 18494, 128, -1, 18511, 18510, 146, -1, 18512, 18497, 18513, -1, 18512, 18495, 18497, -1, 11589, 11591, 18502, -1, 18514, 18515, 18516, -1, 18517, 18518, 18519, -1, 18514, 18516, 18520, -1, 18521, 18508, 18485, -1, 18522, 18503, 18504, -1, 18523, 18471, 18470, -1, 18524, 18525, 18526, -1, 18527, 18528, 18529, -1, 18524, 18501, 18525, -1, 18524, 18506, 18501, -1, 18527, 18529, 18530, -1, 18531, 18532, 18533, -1, 18534, 18505, 18507, -1, 18535, 18478, 18492, -1, 18536, 18506, 18524, -1, 18537, 18532, 18531, -1, 18538, 281, 18509, -1, 178, 18511, 146, -1, 18539, 18540, 18503, -1, 18539, 18503, 18522, -1, 18541, 18518, 18517, -1, 18542, 18473, 18543, -1, 18542, 18499, 18473, -1, 18542, 18543, 18544, -1, 18545, 18540, 18539, -1, 18546, 18514, 18520, -1, 18547, 18499, 18542, -1, 18546, 18520, 18548, -1, 18549, 18513, 18550, -1, 18551, 18552, 18553, -1, 18549, 18512, 18513, -1, 18551, 18554, 18552, -1, 18555, 18511, 178, -1, 18556, 281, 18538, -1, 18557, 18541, 18517, -1, 18556, 299, 281, -1, 18558, 18478, 18535, -1, 18558, 18559, 18478, -1, 18560, 18556, 18538, -1, 18561, 18562, 18518, -1, 18561, 18518, 18541, -1, 18563, 299, 18556, -1, 18564, 18508, 18521, -1, 18563, 313, 299, -1, 18565, 18566, 18567, -1, 18568, 18559, 18558, -1, 18569, 18527, 18530, -1, 18569, 18530, 18570, -1, 186, 18555, 178, -1, 18571, 18546, 18548, -1, 18571, 18548, 18572, -1, 18573, 313, 18563, -1, 18574, 18541, 18557, -1, 18575, 18556, 18560, -1, 18576, 18574, 18557, -1, 18577, 18578, 18579, -1, 316, 313, 18573, -1, 11464, 11376, 18580, -1, 18581, 18575, 18560, -1, 18582, 18577, 18579, -1, 197, 18555, 186, -1, 18583, 11753, 11837, -1, 18584, 18574, 18576, -1, 11474, 11464, 18580, -1, 18585, 18584, 18576, -1, 18586, 18575, 18581, -1, 18587, 18566, 18565, -1, 18588, 18570, 18589, -1, 18588, 18569, 18570, -1, 18590, 18591, 18592, -1, 18590, 18593, 18591, -1, 18594, 18586, 18581, -1, 249, 18595, 18596, -1, 249, 18596, 197, -1, 18597, 18594, 18598, -1, 18599, 18577, 18582, -1, 18600, 18584, 18585, -1, 18601, 18602, 18603, -1, 18604, 332, 316, -1, 365, 332, 18604, -1, 18605, 18602, 18601, -1, 18606, 18599, 18582, -1, 257, 18607, 18595, -1, 257, 18595, 249, -1, 18608, 18586, 18594, -1, 18609, 18608, 18594, -1, 18609, 18594, 18597, -1, 275, 18607, 257, -1, 275, 18610, 18607, -1, 18611, 18612, 18613, -1, 18614, 18610, 275, -1, 18615, 365, 18604, -1, 18616, 11980, 11985, -1, 392, 365, 18615, -1, 18617, 18618, 18619, -1, 18620, 18599, 18606, -1, 305, 18614, 275, -1, 18621, 18622, 18623, -1, 18621, 18623, 18612, -1, 18621, 18612, 18611, -1, 18624, 18625, 18626, -1, 18624, 18626, 18618, -1, 18627, 18628, 18629, -1, 18624, 18618, 18617, -1, 18630, 18614, 305, -1, 18631, 18608, 18609, -1, 18632, 18633, 18634, -1, 11486, 11440, 18635, -1, 18636, 18620, 18606, -1, 18632, 18634, 18637, -1, 18638, 18639, 18640, -1, 18641, 18642, 18643, -1, 18641, 18643, 18644, -1, 18645, 18636, 18646, -1, 18647, 18648, 18641, -1, 18649, 18650, 18625, -1, 18649, 18625, 18624, -1, 310, 18630, 305, -1, 11573, 11568, 18651, -1, 18652, 392, 18615, -1, 18653, 18608, 18631, -1, 18654, 18655, 18656, -1, 18657, 18658, 18659, -1, 18653, 18660, 18608, -1, 11496, 11486, 18635, -1, 18661, 18662, 18663, -1, 18664, 18639, 18638, -1, 18665, 18662, 18661, -1, 18666, 18628, 18627, -1, 18667, 18664, 18638, -1, 18668, 18622, 18621, -1, 18668, 18669, 18622, -1, 18670, 18660, 18653, -1, 18671, 18624, 18672, -1, 18671, 18649, 18624, -1, 18673, 18666, 18627, -1, 323, 18630, 310, -1, 18674, 18664, 18667, -1, 18675, 18637, 18676, -1, 18675, 18632, 18637, -1, 18677, 18620, 18636, -1, 18678, 18674, 18667, -1, 18679, 392, 18652, -1, 18680, 18681, 18682, -1, 18679, 408, 392, -1, 18683, 18650, 18649, -1, 11572, 11573, 18651, -1, 18684, 18672, 18685, -1, 18684, 18671, 18672, -1, 18686, 18636, 18645, -1, 397, 18687, 18688, -1, 18686, 18677, 18636, -1, 397, 18688, 323, -1, 18689, 18674, 18678, -1, 18690, 18679, 18652, -1, 18691, 18655, 18654, -1, 18692, 11733, 11815, -1, 11814, 18692, 11815, -1, 18693, 18684, 18685, -1, 18693, 18685, 18694, -1, 421, 18694, 18687, -1, 18695, 18666, 18673, -1, 421, 18687, 397, -1, 18696, 408, 18679, -1, 18696, 423, 408, -1, 18697, 18691, 18654, -1, 443, 18694, 421, -1, 443, 18693, 18694, -1, 18698, 18621, 18699, -1, 18700, 18647, 18641, -1, 18700, 18701, 18647, -1, 18702, 18693, 443, -1, 18703, 18695, 18673, -1, 18698, 18668, 18621, -1, 11510, 11479, 18704, -1, 18705, 423, 18696, -1, 18706, 18675, 18676, -1, 11518, 11510, 18704, -1, 18706, 18676, 18707, -1, 594, 18702, 443, -1, 18708, 11518, 18704, -1, 18709, 18679, 18690, -1, 18708, 18704, 18710, -1, 18711, 18702, 594, -1, 427, 423, 18705, -1, 11493, 11518, 18708, -1, 18712, 18709, 18690, -1, 615, 18711, 594, -1, 712, 18711, 615, -1, 18713, 18714, 18380, -1, 18713, 11904, 11871, -1, 18713, 11905, 11904, -1, 18713, 11871, 18418, -1, 18713, 18380, 11905, -1, 18715, 18713, 18418, -1, 18715, 18417, 18714, -1, 18715, 18714, 18713, -1, 18715, 18418, 18417, -1, 18716, 18717, 18439, -1, 18716, 18439, 18444, -1, 18716, 18444, 18463, -1, 18718, 18717, 18716, -1, 18718, 18719, 18717, -1, 18718, 18716, 18463, -1, 18718, 18463, 18462, -1, 18720, 18721, 18722, -1, 18723, 18724, 18719, -1, 18723, 18719, 18718, -1, 18723, 18718, 18462, -1, 18725, 18489, 18724, -1, 18725, 18462, 18487, -1, 18725, 18723, 18462, -1, 18725, 18724, 18723, -1, 18726, 18695, 18703, -1, 18725, 18487, 18489, -1, 18727, 18430, 18451, -1, 18727, 18728, 18430, -1, 18727, 18451, 18729, -1, 18730, 18516, 18515, -1, 18730, 18727, 18729, -1, 18730, 18731, 18728, -1, 18730, 18729, 18516, -1, 18730, 18728, 18727, -1, 18732, 18677, 18686, -1, 18733, 18730, 18515, -1, 18733, 18734, 18731, -1, 18735, 18692, 11814, -1, 18733, 18731, 18730, -1, 18736, 18526, 18525, -1, 18736, 18734, 18733, -1, 18736, 18525, 18734, -1, 18737, 18691, 18697, -1, 18736, 18733, 18515, -1, 18736, 18515, 18738, -1, 18736, 18738, 18526, -1, 18739, 18740, 18491, -1, 18739, 11854, 11766, -1, 18739, 11766, 18741, -1, 18739, 18491, 11854, -1, 18742, 18743, 18540, -1, 18742, 18545, 18744, -1, 18742, 18540, 18545, -1, 18742, 18745, 18743, -1, 18746, 18739, 18741, -1, 18746, 18740, 18739, -1, 18746, 18572, 18740, -1, 18746, 18741, 18747, -1, 18748, 18742, 18744, -1, 18749, 18737, 18697, -1, 18748, 18744, 18750, -1, 18748, 18745, 18742, -1, 18748, 18751, 18745, -1, 18752, 18571, 18572, -1, 18752, 18572, 18746, -1, 18753, 18754, 18755, -1, 18752, 18747, 18756, -1, 18757, 18758, 18759, -1, 18752, 18746, 18747, -1, 18760, 18750, 18597, -1, 18753, 18761, 18754, -1, 18760, 18597, 18598, -1, 18760, 18748, 18750, -1, 18760, 18751, 18748, -1, 18760, 18598, 18751, -1, 18762, 18763, 18536, -1, 18764, 18669, 18668, -1, 18762, 18524, 18765, -1, 18762, 18536, 18524, -1, 18766, 18571, 18752, -1, 18767, 18709, 18712, -1, 18768, 18769, 18770, -1, 18766, 18752, 18756, -1, 18768, 18771, 18769, -1, 18766, 18756, 18772, -1, 18773, 18763, 18762, -1, 18773, 18765, 18774, -1, 18773, 18762, 18765, -1, 18775, 18776, 18777, -1, 18775, 18777, 18750, -1, 18778, 18779, 18768, -1, 18775, 18744, 18780, -1, 18775, 18780, 18781, -1, 18782, 18699, 18783, -1, 18775, 18750, 18744, -1, 18775, 18781, 18776, -1, 18782, 18698, 18699, -1, 18784, 18571, 18766, -1, 18784, 18785, 18571, -1, 18784, 18772, 18786, -1, 18784, 18766, 18772, -1, 18787, 18663, 18662, -1, 18787, 18662, 18583, -1, 18787, 11835, 11743, -1, 18787, 11837, 11835, -1, 18787, 11743, 18663, -1, 18787, 18583, 11837, -1, 18788, 18789, 18763, -1, 18788, 18763, 18773, -1, 18788, 18634, 18633, -1, 18788, 18773, 18774, -1, 18788, 18774, 18634, -1, 18790, 18785, 18784, -1, 18790, 18791, 18785, -1, 18792, 18758, 18757, -1, 18790, 18786, 18629, -1, 18790, 18784, 18786, -1, 18793, 18794, 18789, -1, 18795, 18677, 18732, -1, 18793, 18788, 18633, -1, 18796, 18767, 18712, -1, 18793, 18789, 18788, -1, 18797, 18791, 18790, -1, 18795, 18798, 18677, -1, 18797, 18629, 18628, -1, 18797, 18799, 18791, -1, 18797, 18790, 18629, -1, 18800, 18648, 18776, -1, 18800, 18781, 18642, -1, 18800, 18641, 18648, -1, 18801, 18796, 18802, -1, 18800, 18642, 18641, -1, 18800, 18776, 18781, -1, 18803, 18793, 18633, -1, 18803, 18643, 18794, -1, 18804, 18805, 18806, -1, 18803, 18794, 18793, -1, 18803, 18633, 18807, -1, 18808, 18809, 18810, -1, 18803, 18807, 18644, -1, 18803, 18644, 18643, -1, 18804, 18806, 18811, -1, 18812, 18797, 18628, -1, 18812, 18799, 18797, -1, 18812, 18813, 18799, -1, 18814, 18809, 18808, -1, 18815, 18670, 18816, -1, 18815, 18817, 18818, -1, 18815, 18818, 18660, -1, 18815, 18660, 18670, -1, 18819, 18813, 18812, -1, 18819, 18628, 18820, -1, 18821, 18721, 18720, -1, 18819, 18822, 18813, -1, 18819, 18812, 18628, -1, 18823, 18815, 18816, -1, 18823, 18824, 18817, -1, 18823, 18817, 18815, -1, 18823, 18816, 18825, -1, 18826, 18822, 18819, -1, 18826, 18820, 18827, -1, 18826, 18707, 18822, -1, 18826, 18819, 18820, -1, 18828, 18665, 18661, -1, 18829, 18798, 18795, -1, 18828, 18806, 18805, -1, 18828, 18661, 18806, -1, 18830, 18824, 18823, -1, 18830, 18823, 18825, -1, 18831, 18821, 18720, -1, 18830, 18801, 18802, -1, 18830, 18802, 18824, -1, 18830, 18825, 18801, -1, 18832, 18706, 18707, -1, 18832, 18707, 18826, -1, 18832, 18826, 18827, -1, 18833, 18665, 18828, -1, 18833, 18828, 18805, -1, 18834, 11814, 11721, -1, 18833, 18757, 18759, -1, 18835, 18737, 18749, -1, 18833, 18805, 18757, -1, 18833, 18759, 18665, -1, 18834, 18735, 11814, -1, 18836, 18706, 18832, -1, 18836, 18827, 18837, -1, 18836, 18837, 18838, -1, 18836, 18832, 18827, -1, 18839, 18726, 18703, -1, 18839, 18703, 18758, -1, 18839, 18758, 18792, -1, 18839, 18792, 18840, -1, 18841, 18842, 18843, -1, 18841, 18843, 18844, -1, 18841, 18844, 18825, -1, 18841, 18816, 18845, -1, 18841, 18845, 18842, -1, 18841, 18825, 18816, -1, 18846, 18701, 18700, -1, 18846, 18700, 18847, -1, 18848, 18706, 18836, -1, 18848, 18836, 18838, -1, 18848, 18838, 18849, -1, 18848, 18850, 18706, -1, 18851, 18755, 18852, -1, 18851, 18753, 18755, -1, 18853, 18846, 18847, -1, 18853, 18847, 18854, -1, 18853, 18701, 18846, -1, 18853, 18855, 18701, -1, 18856, 18839, 18840, -1, 18856, 18857, 18726, -1, 18856, 18726, 18839, -1, 18858, 18859, 18860, -1, 18861, 18849, 18862, -1, 18863, 440, 427, -1, 18861, 18864, 18850, -1, 18861, 18850, 18848, -1, 18861, 18848, 18849, -1, 18865, 18767, 18796, -1, 18866, 18853, 18854, -1, 18866, 18855, 18853, -1, 18866, 18854, 18867, -1, 18866, 18868, 18855, -1, 18869, 18870, 18871, -1, 18869, 18857, 18856, -1, 18869, 18871, 18857, -1, 18869, 18856, 18840, -1, 18869, 18840, 18870, -1, 18872, 18873, 18735, -1, 18872, 18735, 18834, -1, 18872, 18834, 18874, -1, 18875, 18876, 18877, -1, 18875, 18843, 18842, -1, 18875, 18878, 18876, -1, 18879, 18783, 18880, -1, 18875, 18877, 18843, -1, 18875, 18842, 18878, -1, 18881, 18867, 18882, -1, 18879, 18782, 18783, -1, 18881, 18882, 18883, -1, 447, 440, 18863, -1, 18881, 18883, 18884, -1, 18881, 18868, 18866, -1, 18881, 18866, 18867, -1, 18881, 18884, 18868, -1, 18885, 18864, 18861, -1, 18886, 18804, 18811, -1, 18885, 18887, 18888, -1, 18885, 18888, 18864, -1, 18885, 18862, 18889, -1, 18885, 18861, 18862, -1, 18886, 18811, 18890, -1, 18891, 18892, 18893, -1, 18891, 18893, 18894, -1, 18891, 18894, 18895, -1, 18896, 18874, 18897, -1, 18896, 18872, 18874, -1, 18896, 18898, 18873, -1, 18896, 18873, 18872, -1, 18899, 18865, 18796, -1, 18900, 18885, 18889, -1, 18900, 18901, 18887, -1, 18900, 18887, 18885, -1, 18900, 18889, 18902, -1, 18899, 18796, 18801, -1, 18903, 18892, 18891, -1, 18903, 18891, 18895, -1, 18903, 18904, 18892, -1, 18905, 18897, 18906, -1, 18907, 18858, 18860, -1, 18905, 18898, 18896, -1, 18905, 18896, 18897, -1, 18908, 18900, 18902, -1, 18908, 18901, 18900, -1, 18908, 18909, 18901, -1, 18908, 18902, 18910, -1, 18911, 18912, 18913, -1, 18911, 18914, 18912, -1, 18911, 18915, 18914, -1, 18911, 18913, 18915, -1, 18916, 18895, 18917, -1, 18916, 18904, 18903, -1, 18916, 18918, 18904, -1, 18919, 11999, 12006, -1, 18916, 18903, 18895, -1, 18920, 18921, 18898, -1, 18920, 18905, 18906, -1, 18920, 18906, 18922, -1, 18920, 18898, 18905, -1, 18923, 18908, 18910, -1, 12012, 18919, 12006, -1, 18923, 18909, 18908, -1, 18924, 18925, 11795, -1, 18924, 11793, 11699, -1, 18926, 18821, 18831, -1, 18924, 11795, 11793, -1, 18924, 11699, 18927, -1, 18928, 18929, 18930, -1, 18928, 18931, 18929, -1, 18928, 18932, 18931, -1, 18933, 18934, 18935, -1, 18933, 18918, 18916, -1, 18933, 18916, 18917, -1, 18933, 18917, 18934, -1, 18933, 18935, 18918, -1, 18936, 18922, 18937, -1, 18936, 18937, 18938, -1, 18936, 18920, 18922, -1, 18936, 18921, 18920, -1, 18936, 18938, 18921, -1, 18939, 18940, 18941, -1, 18942, 18867, 18854, -1, 18939, 18943, 18909, -1, 18939, 18909, 18923, -1, 18939, 18923, 18910, -1, 18939, 18910, 18940, -1, 18944, 18945, 18925, -1, 18944, 18925, 18924, -1, 18944, 18927, 18946, -1, 18944, 18946, 18945, -1, 18944, 18924, 18927, -1, 18947, 18932, 18928, -1, 18947, 18948, 18932, -1, 18947, 18930, 18949, -1, 18947, 18949, 18948, -1, 18947, 18928, 18930, -1, 18950, 18951, 18952, -1, 18950, 18952, 18953, -1, 18954, 18941, 18955, -1, 18956, 447, 18863, -1, 18954, 18939, 18941, -1, 18954, 18957, 18943, -1, 18958, 18959, 18778, -1, 18954, 18943, 18939, -1, 18958, 18778, 18768, -1, 18960, 18961, 18962, -1, 18960, 18962, 18963, -1, 18960, 18964, 18965, -1, 18960, 18963, 18964, -1, 18966, 18951, 18950, -1, 18966, 18953, 18967, -1, 18968, 18926, 18831, -1, 18966, 18950, 18953, -1, 448, 447, 18956, -1, 18966, 18969, 18951, -1, 18970, 18955, 18971, -1, 18970, 18972, 18957, -1, 18970, 18954, 18955, -1, 18970, 18957, 18954, -1, 18973, 18974, 18975, -1, 18973, 18975, 18961, -1, 18973, 18960, 18965, -1, 18973, 18961, 18960, -1, 18973, 18976, 18974, -1, 18973, 18965, 18976, -1, 18977, 18967, 18978, -1, 18977, 18969, 18966, -1, 18977, 18966, 18967, -1, 18977, 18979, 18969, -1, 18980, 18981, 18982, -1, 18980, 18982, 18972, -1, 18980, 18971, 18983, -1, 18980, 18970, 18971, -1, 18980, 18972, 18970, -1, 18984, 18978, 18985, -1, 18984, 18985, 18986, -1, 18987, 18852, 18988, -1, 18984, 18986, 18989, -1, 18987, 18851, 18852, -1, 18984, 18979, 18977, -1, 18984, 18989, 18979, -1, 18984, 18977, 18978, -1, 18990, 18991, 18992, -1, 18898, 18886, 18890, -1, 18990, 18992, 18993, -1, 18990, 18993, 18994, -1, 18990, 18995, 18991, -1, 18996, 18997, 18998, -1, 18898, 18890, 18873, -1, 18996, 18998, 18999, -1, 19000, 18858, 18907, -1, 18996, 18999, 19001, -1, 19002, 19003, 19004, -1, 19002, 11771, 11681, -1, 19002, 11773, 11771, -1, 19002, 11681, 19005, -1, 19002, 19004, 11773, -1, 19002, 19005, 19003, -1, 19006, 18865, 18899, -1, 19007, 11422, 19008, -1, 19007, 19009, 19010, -1, 19007, 19010, 11414, -1, 19007, 11419, 11422, -1, 19007, 11414, 11419, -1, 19007, 19008, 19009, -1, 19011, 18879, 18880, -1, 19012, 19013, 18981, -1, 19012, 18980, 18983, -1, 19012, 18981, 18980, -1, 19012, 18983, 19014, -1, 19015, 19016, 18995, -1, 19015, 18990, 18994, -1, 19015, 18995, 18990, -1, 19015, 18994, 19017, -1, 19018, 19019, 18997, -1, 19018, 18997, 18996, -1, 19018, 18996, 19001, -1, 19020, 19000, 18907, -1, 18914, 18889, 18862, -1, 19018, 19001, 19021, -1, 19022, 19017, 19023, -1, 19024, 18879, 19011, -1, 19022, 19015, 19017, -1, 19022, 19016, 19015, -1, 19025, 19013, 19012, -1, 19025, 19026, 19013, -1, 19025, 19012, 19014, -1, 19027, 18867, 18942, -1, 19025, 19014, 19028, -1, 19029, 19030, 19019, -1, 19029, 19019, 19018, -1, 19029, 19021, 19031, -1, 19029, 19018, 19021, -1, 19032, 19033, 19034, -1, 19032, 19034, 19035, -1, 19032, 19036, 19033, -1, 19032, 19035, 19036, -1, 19037, 19038, 19039, -1, 19037, 19039, 19040, -1, 18876, 18884, 18883, -1, 19037, 19040, 19041, -1, 19037, 19041, 19038, -1, 19042, 19016, 19022, -1, 18876, 18878, 18884, -1, 19042, 19023, 19043, -1, 19042, 19022, 19023, -1, 19044, 18877, 18876, -1, 19042, 19045, 19016, -1, 19042, 19043, 19045, -1, 19046, 19026, 19025, -1, 19046, 19025, 19028, -1, 19047, 19048, 19049, -1, 19047, 19049, 19050, -1, 19051, 19029, 19031, -1, 19052, 19027, 18942, -1, 19051, 19030, 19029, -1, 19051, 19031, 19053, -1, 19054, 18865, 19006, -1, 19051, 19055, 19030, -1, 19056, 19057, 19058, -1, 19054, 18893, 18865, -1, 19056, 19059, 19060, -1, 19056, 19060, 19057, -1, 19061, 18926, 18968, -1, 19062, 19046, 19028, -1, 19062, 19026, 19046, -1, 19062, 19063, 19026, -1, 19062, 19028, 19064, -1, 19062, 19064, 19065, -1, 19066, 19067, 19048, -1, 11557, 11548, 19068, -1, 19066, 19047, 19050, -1, 19066, 19048, 19047, -1, 19066, 19069, 19070, -1, 19066, 19070, 19067, -1, 19066, 19050, 19069, -1, 19071, 19051, 19053, -1, 19071, 19055, 19051, -1, 19071, 19072, 19055, -1, 19073, 19056, 19058, -1, 19073, 19058, 19074, -1, 19075, 448, 18956, -1, 19073, 19059, 19056, -1, 19076, 19077, 19078, -1, 19076, 19079, 19080, -1, 19076, 19078, 19079, -1, 19081, 18919, 12012, -1, 19076, 19082, 19077, -1, 19083, 19084, 19063, -1, 19083, 19062, 19065, -1, 18915, 18889, 18914, -1, 19083, 19063, 19062, -1, 19083, 19065, 19085, -1, 19086, 19071, 19053, -1, 19086, 19087, 19088, -1, 19086, 19053, 19087, -1, 19086, 19088, 19072, -1, 18894, 18893, 19054, -1, 19086, 19072, 19071, -1, 19089, 19090, 19091, -1, 19089, 19038, 19092, -1, 19089, 19092, 19090, -1, 19089, 19091, 19038, -1, 19093, 19074, 19094, -1, 19093, 19073, 19074, -1, 19093, 19095, 19059, -1, 19093, 19059, 19073, -1, 18931, 18871, 18870, -1, 19096, 19097, 19084, -1, 19096, 19083, 19085, -1, 19096, 19084, 19083, -1, 19096, 19085, 19098, -1, 19099, 19100, 19101, -1, 19099, 19101, 19102, -1, 19099, 19102, 19103, -1, 19104, 19105, 19106, -1, 18932, 18871, 18931, -1, 19104, 19080, 19105, -1, 19104, 19076, 19080, -1, 19107, 19108, 19109, -1, 19104, 19106, 19110, -1, 18925, 11708, 11795, -1, 19104, 19110, 19082, -1, 19104, 19082, 19076, -1, 19111, 19112, 19113, -1, 19111, 19113, 19114, -1, 19111, 19115, 19112, -1, 19116, 19117, 19095, -1, 19116, 19093, 19094, -1, 19116, 19095, 19093, -1, 19116, 19094, 19118, -1, 19119, 19120, 19097, -1, 19119, 19096, 19098, -1, 19121, 19000, 19020, -1, 19119, 19097, 19096, -1, 19122, 19099, 19103, -1, 19122, 19103, 19123, -1, 19122, 19100, 19099, -1, 19124, 19115, 19111, -1, 19125, 19027, 19052, -1, 19124, 19126, 19115, -1, 19124, 19111, 19114, -1, 19124, 19114, 19127, -1, 19128, 19129, 19091, -1, 19128, 19091, 19130, -1, 19128, 19130, 19131, -1, 19128, 19132, 19129, -1, 19133, 19116, 19118, -1, 19133, 19117, 19116, -1, 19133, 19118, 19134, -1, 19135, 19090, 19136, -1, 19135, 19137, 19138, -1, 19135, 19138, 19090, -1, 19135, 19139, 19137, -1, 11555, 11557, 19068, -1, 19135, 19136, 19139, -1, 19140, 19141, 19120, -1, 19140, 19098, 19142, -1, 19140, 19120, 19119, -1, 19143, 19108, 19107, -1, 19140, 19119, 19098, -1, 19144, 19113, 19112, -1, 19144, 19100, 19122, -1, 19144, 19123, 19113, -1, 19144, 19112, 19100, -1, 19144, 19122, 19123, -1, 19145, 19146, 19147, -1, 19145, 19148, 19146, -1, 19149, 19128, 19131, -1, 19150, 11555, 19068, -1, 19149, 19131, 19151, -1, 19150, 19068, 19152, -1, 19149, 19132, 19128, -1, 19153, 19154, 19155, -1, 19156, 19121, 19020, -1, 19153, 19155, 19126, -1, 19153, 19126, 19124, -1, 19153, 19127, 19154, -1, 19153, 19124, 19127, -1, 19157, 19158, 19159, -1, 19157, 19133, 19134, -1, 19157, 19134, 19158, -1, 19157, 19159, 19117, -1, 19157, 19117, 19133, -1, 18909, 19125, 19052, -1, 19160, 19161, 19141, -1, 19162, 19156, 19163, -1, 19160, 19142, 19164, -1, 19165, 19166, 19167, -1, 19160, 19141, 19140, -1, 19165, 19168, 19166, -1, 19160, 19140, 19142, -1, 19169, 19145, 19147, -1, 19169, 19147, 19170, -1, 19169, 19170, 19171, -1, 19169, 19148, 19145, -1, 19169, 19139, 19148, -1, 19172, 19151, 19173, -1, 19172, 19174, 19132, -1, 19172, 19149, 19151, -1, 19172, 19132, 19149, -1, 19175, 19176, 19177, -1, 19175, 11788, 11702, -1, 19175, 11702, 19178, -1, 19179, 448, 19075, -1, 19175, 19178, 19180, -1, 19179, 3397, 448, -1, 19175, 19177, 11788, -1, 19181, 19182, 19161, -1, 19181, 19160, 19164, -1, 19181, 19164, 19183, -1, 19181, 19161, 19160, -1, 19184, 19179, 19075, -1, 19185, 19186, 19187, -1, 19185, 19187, 19188, -1, 19185, 19188, 19189, -1, 19185, 19189, 19186, -1, 19190, 19191, 19192, -1, 19190, 19172, 19173, -1, 19190, 19173, 19191, -1, 19190, 19174, 19172, -1, 19190, 19192, 19174, -1, 19193, 19169, 19171, -1, 19193, 19137, 19139, -1, 19193, 19139, 19169, -1, 19194, 19195, 19196, -1, 19194, 19196, 19197, -1, 19198, 19181, 19183, -1, 19198, 19182, 19181, -1, 19199, 19176, 19175, -1, 19199, 19200, 19176, -1, 19199, 19180, 19201, -1, 19199, 19175, 19180, -1, 19199, 19201, 19202, -1, 19203, 19137, 19193, -1, 19203, 19193, 19171, -1, 18952, 19044, 18876, -1, 19203, 19171, 19204, -1, 19205, 12012, 12009, -1, 19203, 19206, 19207, -1, 19203, 19207, 19137, -1, 19208, 19194, 19197, -1, 19208, 19209, 19210, -1, 19208, 19195, 19194, -1, 18952, 18951, 19044, -1, 19208, 19210, 19211, -1, 19205, 19081, 12012, -1, 19208, 19197, 19209, -1, 19208, 19211, 19195, -1, 19212, 19198, 19183, -1, 19212, 19183, 19213, -1, 19212, 19213, 19214, -1, 19212, 19215, 19182, -1, 19212, 19182, 19198, -1, 19216, 19217, 19218, -1, 11540, 11555, 19150, -1, 19216, 19219, 19217, -1, 19216, 19220, 19219, -1, 19221, 19222, 19200, -1, 19221, 19199, 19202, -1, 19221, 19200, 19199, -1, 19223, 19224, 19225, -1, 19223, 19186, 19226, -1, 19223, 19225, 19186, -1, 19223, 19226, 19224, -1, 19227, 19228, 19229, -1, 19227, 19203, 19204, -1, 18962, 18913, 18912, -1, 19227, 19229, 19206, -1, 19227, 19204, 19228, -1, 19227, 19206, 19203, -1, 19230, 19214, 19231, -1, 19230, 19232, 19215, -1, 19230, 19212, 19214, -1, 19230, 19215, 19212, -1, 19233, 19216, 19218, -1, 19233, 19220, 19216, -1, 19233, 19234, 19235, -1, 19233, 19235, 19220, -1, 19236, 19222, 19221, -1, 19236, 19237, 19222, -1, 19236, 19202, 19238, -1, 19236, 19221, 19202, -1, 19239, 19240, 11799, -1, 19239, 19241, 19240, -1, 19242, 19121, 19156, -1, 19239, 11810, 11726, -1, 19239, 11799, 11810, -1, 19239, 11726, 19243, -1, 18943, 19125, 18909, -1, 19244, 19232, 19230, -1, 19244, 19231, 11358, -1, 19244, 11358, 11366, -1, 19244, 19245, 19232, -1, 19244, 19230, 19231, -1, 19244, 11366, 19245, -1, 19246, 19247, 19248, -1, 19246, 19248, 19249, -1, 19250, 3397, 19179, -1, 19246, 19251, 19247, -1, 19246, 19252, 19251, -1, 19253, 19254, 19234, -1, 19253, 19255, 19254, -1, 19250, 3400, 3397, -1, 19253, 19234, 19233, -1, 19253, 19218, 19255, -1, 19253, 19233, 19218, -1, 19256, 19237, 19236, -1, 19257, 19167, 19258, -1, 19256, 19236, 19238, -1, 19257, 19165, 19167, -1, 19256, 19259, 19237, -1, 19256, 19238, 19260, -1, 19256, 19260, 19259, -1, 19261, 19239, 19243, -1, 19261, 19262, 19241, -1, 19261, 19241, 19239, -1, 19261, 19263, 19262, -1, 19261, 19243, 19263, -1, 19264, 19249, 19265, -1, 19264, 19252, 19246, -1, 19264, 19265, 19252, -1, 19264, 19246, 19249, -1, 19266, 19225, 19267, -1, 19266, 19267, 19268, -1, 19266, 19269, 19225, -1, 19266, 19270, 19269, -1, 19271, 19272, 19273, -1, 19271, 19273, 19226, -1, 19271, 19226, 19274, -1, 18937, 19275, 19276, -1, 19271, 19274, 19277, -1, 18937, 19276, 18938, -1, 19271, 19277, 19272, -1, 19278, 19242, 19156, -1, 19279, 19280, 19281, -1, 19279, 19281, 19282, -1, 19283, 3400, 19250, -1, 19278, 19156, 19162, -1, 19284, 19285, 19286, -1, 19284, 19286, 19287, -1, 19284, 19287, 19288, -1, 19289, 19179, 19184, -1, 19284, 19288, 19290, -1, 19284, 19290, 19285, -1, 19291, 19268, 19292, -1, 19291, 19266, 19268, -1, 19291, 19270, 19266, -1, 19293, 19280, 19279, -1, 19293, 19282, 19294, -1, 19293, 19294, 19295, -1, 19293, 19277, 19280, -1, 19293, 19279, 19282, -1, 19296, 19292, 19297, -1, 19296, 19291, 19292, -1, 19296, 19298, 19270, -1, 19296, 19270, 19291, -1, 19299, 19300, 19259, -1, 19299, 19301, 19300, -1, 19299, 19259, 19302, -1, 19303, 19289, 19184, -1, 19304, 19293, 19295, -1, 19304, 19272, 19277, -1, 19304, 19277, 19293, -1, 19305, 19296, 19297, -1, 19305, 19297, 19306, -1, 19305, 19298, 19296, -1, 19305, 19307, 19298, -1, 19308, 19299, 19302, -1, 19308, 19301, 19299, -1, 19308, 19302, 19309, -1, 19310, 19288, 19311, -1, 19310, 19311, 19312, -1, 19310, 19290, 19288, -1, 19310, 19312, 19290, -1, 3401, 3400, 19283, -1, 19313, 19314, 19315, -1, 19313, 19315, 19316, -1, 19313, 19317, 19314, -1, 18961, 18913, 18962, -1, 19318, 19319, 19320, -1, 19318, 19321, 19319, -1, 19322, 19306, 19323, -1, 19322, 19324, 19307, -1, 19322, 19323, 19324, -1, 19322, 19305, 19306, -1, 19322, 19307, 19305, -1, 11448, 3401, 19283, -1, 19325, 19326, 19327, -1, 19325, 19327, 11736, -1, 19325, 11833, 11745, -1, 19325, 11826, 11833, -1, 19325, 11736, 11826, -1, 11447, 11448, 19283, -1, 19325, 11745, 19326, -1, 19328, 19295, 19329, -1, 19328, 19330, 19331, -1, 19328, 19331, 19272, -1, 19328, 19272, 19304, -1, 11446, 11447, 19283, -1, 19328, 19304, 19295, -1, 19332, 19333, 19334, -1, 19332, 19335, 19301, -1, 19336, 18917, 18895, -1, 19332, 19301, 19308, -1, 19332, 19308, 19309, -1, 19332, 19309, 19333, -1, 19336, 18895, 19337, -1, 19338, 19317, 19313, -1, 19338, 19313, 19316, -1, 19338, 19316, 19339, -1, 19338, 19340, 19317, -1, 19341, 19318, 19320, -1, 19341, 19342, 19343, -1, 19341, 19344, 19321, -1, 19341, 19343, 19344, -1, 19341, 19321, 19318, -1, 19341, 19320, 19342, -1, 19345, 19346, 19335, -1, 19345, 19332, 19334, -1, 19345, 19335, 19332, -1, 19347, 19348, 19349, -1, 19347, 19330, 19328, -1, 19347, 19349, 19330, -1, 19347, 19329, 19348, -1, 19347, 19328, 19329, -1, 19350, 19338, 19339, -1, 19350, 19339, 19351, -1, 19350, 19340, 19338, -1, 19350, 19352, 19340, -1, 19353, 19354, 19355, -1, 19353, 19356, 19354, -1, 19353, 19357, 19356, -1, 19353, 19355, 19357, -1, 19358, 19359, 19346, -1, 19358, 19346, 19345, -1, 19358, 19345, 19334, -1, 19358, 19334, 19360, -1, 19361, 19362, 19363, -1, 18949, 18963, 18948, -1, 19361, 19363, 19364, -1, 19361, 19364, 19365, -1, 19366, 19352, 19350, -1, 19366, 19350, 19351, -1, 19366, 19367, 19352, -1, 19368, 19359, 19358, -1, 19368, 19369, 19359, -1, 19368, 19360, 19370, -1, 19368, 19370, 19369, -1, 19368, 19358, 19360, -1, 19371, 19361, 19365, -1, 19371, 19362, 19361, -1, 19372, 19258, 19373, -1, 19371, 19374, 19375, -1, 19371, 19375, 19362, -1, 19371, 19365, 19374, -1, 19372, 19257, 19258, -1, 19376, 19367, 19366, -1, 19376, 19366, 19351, -1, 19376, 19351, 19377, -1, 19376, 19378, 19367, -1, 19379, 19380, 19381, -1, 19379, 19381, 19382, -1, 19379, 19383, 19384, -1, 19379, 19384, 19380, -1, 19385, 19386, 19387, -1, 19385, 19387, 19388, -1, 18992, 19275, 18937, -1, 19385, 19389, 19390, -1, 19385, 19390, 19386, -1, 19385, 19388, 19389, -1, 18992, 18991, 19275, -1, 19391, 19349, 19392, -1, 19391, 19393, 19394, -1, 19391, 19394, 19349, -1, 19395, 19242, 19278, -1, 19396, 19376, 19377, -1, 19396, 19377, 19397, -1, 19396, 19378, 19376, -1, 19396, 19397, 19378, -1, 19398, 19382, 19399, -1, 19400, 19401, 19402, -1, 19398, 19383, 19379, -1, 19398, 19379, 19382, -1, 19403, 18992, 18937, -1, 19404, 19392, 19405, -1, 19404, 19393, 19391, -1, 19404, 19406, 19393, -1, 19404, 19391, 19392, -1, 19407, 19408, 19409, -1, 18964, 18963, 18949, -1, 19410, 19411, 19412, -1, 19410, 19413, 19414, -1, 19407, 19409, 19415, -1, 19410, 19416, 19413, -1, 19410, 19414, 19411, -1, 19417, 19418, 19419, -1, 19417, 19419, 19369, -1, 19417, 19369, 19420, -1, 19421, 19399, 19422, -1, 19421, 19423, 19383, -1, 19421, 19398, 19399, -1, 19421, 19383, 19398, -1, 19424, 19406, 19404, -1, 19424, 19405, 19425, -1, 19426, 19427, 19428, -1, 19429, 19289, 19303, -1, 19424, 19404, 19405, -1, 19430, 19416, 19410, -1, 19426, 19431, 19427, -1, 19430, 19410, 19412, -1, 19430, 19432, 19416, -1, 19433, 19434, 19435, -1, 19433, 19435, 19436, -1, 19433, 19437, 19434, -1, 19433, 19438, 19437, -1, 19439, 19390, 19389, -1, 19439, 19440, 19441, -1, 19439, 19441, 19390, -1, 19439, 19389, 19440, -1, 19442, 19418, 19417, -1, 19443, 19429, 19303, -1, 19442, 19420, 19444, -1, 19445, 19446, 19426, -1, 19442, 19417, 19420, -1, 19447, 18930, 18929, -1, 19448, 19449, 19423, -1, 19448, 19421, 19422, -1, 19448, 19423, 19421, -1, 19450, 19425, 19451, -1, 19450, 19424, 19425, -1, 19450, 19452, 19406, -1, 19447, 18929, 19453, -1, 19450, 19406, 19424, -1, 19450, 19454, 19452, -1, 19455, 19412, 19456, -1, 19455, 19432, 19430, -1, 19457, 19242, 19395, -1, 18934, 19443, 18935, -1, 19455, 19456, 19432, -1, 19455, 19430, 19412, -1, 19458, 19459, 19460, -1, 19457, 19461, 19242, -1, 19458, 19462, 19459, -1, 19458, 19460, 19463, -1, 19464, 19465, 19418, -1, 19464, 19418, 19442, -1, 19464, 19442, 19444, -1, 19464, 19444, 19466, -1, 19467, 19433, 19436, -1, 19467, 19436, 19468, -1, 19467, 19438, 19433, -1, 19467, 19468, 19438, -1, 19469, 19470, 11853, -1, 19469, 19471, 19470, -1, 19469, 11853, 11769, -1, 19472, 19336, 19337, -1, 19469, 11769, 19473, -1, 19472, 19337, 19474, -1, 19475, 19422, 19476, -1, 19475, 19476, 11303, -1, 19475, 11303, 11309, -1, 19475, 19477, 19449, -1, 19475, 19449, 19448, -1, 19475, 19448, 19422, -1, 19475, 11309, 19477, -1, 19478, 19450, 19451, -1, 19478, 19454, 19450, -1, 19478, 19479, 19454, -1, 19480, 19462, 19458, -1, 19480, 19458, 19463, -1, 19480, 19481, 19462, -1, 19480, 19463, 19482, -1, 19483, 19484, 19465, -1, 19483, 19466, 19485, -1, 19486, 19401, 19400, -1, 19483, 19464, 19466, -1, 19483, 19465, 19464, -1, 19487, 19469, 19473, -1, 19487, 19471, 19469, -1, 19487, 19488, 19471, -1, 19487, 19473, 19489, -1, 19490, 19478, 19451, -1, 19490, 19451, 19491, -1, 19490, 19491, 19492, -1, 19490, 19492, 19479, -1, 19490, 19479, 19478, -1, 19493, 19461, 19457, -1, 19494, 19495, 19496, -1, 19494, 19496, 19497, -1, 19494, 19497, 19498, -1, 19494, 19498, 19495, -1, 19499, 19500, 19484, -1, 19499, 19484, 19483, -1, 19499, 19483, 19485, -1, 19499, 19485, 19501, -1, 19502, 19503, 19504, -1, 19505, 19480, 19482, -1, 19505, 19481, 19480, -1, 19505, 19482, 19506, -1, 19507, 19503, 19502, -1, 19505, 19508, 19509, -1, 19505, 19509, 19481, -1, 18999, 18945, 18946, -1, 19510, 19511, 19512, -1, 19510, 19512, 19513, -1, 19514, 18992, 19403, -1, 19510, 19515, 19511, -1, 19516, 19517, 19518, -1, 19519, 12020, 12027, -1, 19516, 19520, 19517, -1, 19516, 19518, 19521, -1, 19522, 19523, 19488, -1, 19522, 19487, 19489, -1, 19522, 19488, 19487, -1, 19522, 19489, 19524, -1, 19525, 19526, 19500, -1, 19525, 19501, 19527, -1, 19525, 19527, 19526, -1, 19525, 19499, 19501, -1, 19525, 19500, 19499, -1, 19528, 19505, 19506, -1, 19528, 19506, 19529, -1, 19528, 19508, 19505, -1, 19530, 19514, 19403, -1, 19528, 19531, 19508, -1, 19532, 19533, 19515, -1, 19532, 19534, 19533, -1, 19532, 19515, 19510, -1, 19532, 19513, 19534, -1, 19532, 19510, 19513, -1, 19535, 19536, 19520, -1, 19535, 19520, 19516, -1, 19537, 19429, 19443, -1, 19535, 19516, 19521, -1, 19538, 19415, 19539, -1, 19540, 19523, 19522, -1, 19540, 19522, 19524, -1, 19540, 19524, 19541, -1, 19542, 19528, 19529, -1, 19538, 19407, 19415, -1, 19542, 19531, 19528, -1, 19542, 19543, 19531, -1, 19542, 19529, 19543, -1, 19544, 19492, 19545, -1, 19544, 19546, 19492, -1, 19547, 19548, 19549, -1, 19547, 19550, 19548, -1, 19547, 19551, 19550, -1, 19552, 19553, 19554, -1, 19552, 19554, 19555, -1, 19552, 19555, 19556, -1, 19552, 19556, 19553, -1, 19557, 19558, 19559, -1, 19557, 19559, 19536, -1, 19560, 19447, 19453, -1, 19557, 19561, 19558, -1, 19557, 19536, 19535, -1, 19557, 19521, 19561, -1, 19557, 19535, 19521, -1, 19562, 19563, 19523, -1, 19562, 19523, 19540, -1, 19562, 19540, 19541, -1, 19562, 19541, 19564, -1, 19560, 19453, 19565, -1, 19566, 11877, 11841, -1, 19566, 11867, 11877, -1, 19566, 11841, 19567, -1, 19566, 19568, 11867, -1, 19569, 11285, 19570, -1, 19569, 19544, 19545, -1, 19569, 19546, 19544, -1, 19569, 19545, 19571, -1, 19569, 19571, 11280, -1, 19569, 11280, 11285, -1, 19569, 19570, 19546, -1, 19572, 19526, 19573, -1, 19572, 19574, 19526, -1, 19572, 19575, 19574, -1, 19576, 19538, 19539, -1, 19577, 19578, 19579, -1, 19577, 19549, 19578, -1, 19577, 19551, 19547, -1, 19580, 19443, 18934, -1, 19577, 19547, 19549, -1, 19581, 19564, 19582, -1, 19581, 19563, 19562, -1, 19581, 19562, 19564, -1, 19581, 19583, 19563, -1, 19580, 19537, 19443, -1, 19584, 19585, 19568, -1, 19584, 19568, 19566, -1, 19584, 19566, 19567, -1, 19586, 19472, 19474, -1, 19584, 19567, 19585, -1, 19586, 19474, 19587, -1, 19588, 19577, 19579, -1, 19588, 19551, 19577, -1, 19588, 19589, 19551, -1, 19590, 19573, 19591, -1, 19590, 19572, 19573, -1, 19590, 19575, 19572, -1, 19592, 19593, 19594, -1, 19595, 19596, 19597, -1, 19592, 19594, 19583, -1, 19592, 19581, 19582, -1, 19592, 19583, 19581, -1, 19592, 19582, 19598, -1, 19599, 19600, 19601, -1, 19599, 19602, 19600, -1, 11538, 11530, 19603, -1, 19599, 19601, 19604, -1, 19605, 19606, 19607, -1, 19605, 19608, 19606, -1, 19605, 19607, 19609, -1, 19605, 19609, 19608, -1, 19610, 19595, 19597, -1, 19611, 19589, 19588, -1, 19611, 19612, 19589, -1, 19611, 19579, 19612, -1, 19611, 19588, 19579, -1, 19613, 19590, 19591, -1, 19613, 19591, 19614, -1, 19613, 19615, 19575, -1, 19613, 19575, 19590, -1, 19616, 19593, 19592, -1, 19616, 19592, 19598, -1, 19617, 18978, 18967, -1, 19618, 19602, 19599, -1, 19618, 19599, 19604, -1, 19618, 19619, 19602, -1, 19618, 19604, 19620, -1, 19621, 19614, 19622, -1, 19623, 19624, 19445, -1, 19621, 19613, 19614, -1, 19621, 19615, 19613, -1, 19623, 19445, 19426, -1, 19621, 19625, 19615, -1, 19626, 19598, 19627, -1, 19626, 19628, 19593, -1, 19004, 11686, 11773, -1, 19626, 19593, 19616, -1, 19626, 19616, 19598, -1, 19629, 19630, 19631, -1, 19629, 19631, 19619, -1, 19629, 19618, 19620, -1, 19629, 19619, 19618, -1, 19629, 19620, 19632, -1, 19633, 19625, 19621, -1, 19634, 19514, 19530, -1, 19633, 19622, 19635, -1, 19633, 19621, 19622, -1, 19633, 19636, 19625, -1, 19637, 19628, 19626, -1, 19637, 19627, 19638, -1, 19637, 19639, 19628, -1, 19637, 19626, 19627, -1, 19640, 19641, 19642, -1, 19640, 19642, 19643, -1, 19640, 19644, 19641, -1, 19645, 19646, 19647, -1, 19648, 19633, 19635, -1, 19649, 18999, 18946, -1, 19648, 19635, 19650, -1, 19648, 19636, 19633, -1, 19648, 19650, 19636, -1, 19651, 19652, 19653, -1, 19651, 19653, 19654, -1, 19651, 19654, 19655, -1, 19656, 19657, 19658, -1, 19656, 11892, 11902, -1, 19656, 11902, 19657, -1, 19656, 19658, 11892, -1, 19659, 11664, 19660, -1, 19659, 19661, 19662, -1, 19659, 19662, 11658, -1, 19659, 11661, 11664, -1, 19659, 11658, 11661, -1, 19659, 19660, 19661, -1, 19663, 19630, 19629, -1, 19663, 19629, 19632, -1, 19663, 19632, 19664, -1, 19663, 19665, 19630, -1, 19666, 19638, 19667, -1, 19666, 19639, 19637, -1, 19666, 19637, 19638, -1, 19666, 19668, 19639, -1, 19669, 19670, 19671, -1, 19669, 19671, 19672, -1, 19019, 19634, 19530, -1, 19669, 19673, 19674, -1, 19675, 19538, 19576, -1, 19669, 19672, 19673, -1, 19676, 19644, 19640, -1, 19676, 19677, 19644, -1, 19676, 19640, 19643, -1, 19676, 19678, 19677, -1, 19676, 19643, 19678, -1, 19679, 19673, 19652, -1, 19679, 19652, 19651, -1, 19679, 19651, 19655, -1, 19679, 19655, 19673, -1, 19680, 19666, 19667, -1, 19680, 19668, 19666, -1, 11536, 11538, 19603, -1, 19680, 19667, 19681, -1, 19682, 19683, 19665, -1, 19682, 19664, 19683, -1, 19682, 19665, 19663, -1, 19682, 19663, 19664, -1, 19684, 19669, 19674, -1, 19684, 19685, 19670, -1, 19684, 19674, 19686, -1, 19684, 19670, 19669, -1, 19687, 19688, 19689, -1, 19687, 19690, 19688, -1, 19687, 19689, 19691, -1, 19687, 19691, 19690, -1, 19692, 19693, 19694, -1, 19016, 19560, 19565, -1, 19692, 19695, 19696, -1, 19692, 19696, 19693, -1, 19697, 19698, 19668, -1, 19697, 19681, 19699, -1, 19700, 19701, 19702, -1, 19016, 19565, 18995, -1, 19697, 19668, 19680, -1, 19700, 19702, 19703, -1, 19697, 19680, 19681, -1, 19704, 19694, 19705, -1, 19704, 19692, 19694, -1, 19704, 19695, 19692, -1, 19706, 18978, 19617, -1, 19707, 19708, 19685, -1, 19707, 19685, 19684, -1, 19707, 19684, 19686, -1, 19707, 19686, 19709, -1, 19710, 19595, 19610, -1, 19711, 19712, 19713, -1, 19057, 18989, 18986, -1, 19711, 19714, 19715, -1, 19711, 19715, 19712, -1, 19057, 19586, 19587, -1, 19716, 19717, 19698, -1, 19057, 19587, 18989, -1, 19716, 19699, 19718, -1, 19716, 19697, 19699, -1, 19716, 19718, 19717, -1, 19716, 19698, 19697, -1, 19719, 19704, 19705, -1, 19720, 19537, 19580, -1, 19719, 19695, 19704, -1, 19719, 19721, 19695, -1, 19719, 19705, 19722, -1, 19723, 19707, 19709, -1, 19723, 19724, 19708, -1, 19723, 19708, 19707, -1, 19723, 19709, 19724, -1, 19725, 19706, 19617, -1, 19726, 19714, 19711, -1, 19726, 19711, 19713, -1, 19726, 19713, 19727, -1, 19728, 19729, 19730, -1, 19731, 19710, 19610, -1, 19728, 19732, 19733, -1, 19060, 19586, 19057, -1, 19728, 19730, 19732, -1, 19728, 19733, 19729, -1, 19734, 19735, 19736, -1, 19734, 19737, 19735, -1, 19734, 19736, 19738, -1, 19739, 19722, 19740, -1, 19739, 19740, 19721, -1, 19739, 19719, 19722, -1, 19739, 19721, 19719, -1, 19741, 19718, 19742, -1, 19741, 19743, 19744, -1, 19741, 19744, 19717, -1, 19741, 19742, 19745, -1, 19741, 19746, 19743, -1, 19741, 19717, 19718, -1, 19741, 19745, 19746, -1, 19747, 19714, 19726, -1, 19747, 19727, 19748, -1, 19747, 19749, 19714, -1, 19747, 19726, 19727, -1, 19750, 19646, 19645, -1, 19751, 19752, 19737, -1, 19751, 19738, 19753, -1, 19751, 19734, 19738, -1, 19751, 19737, 19734, -1, 19754, 18999, 19649, -1, 19755, 19756, 19757, -1, 19755, 19758, 19759, -1, 19755, 19759, 19756, -1, 19760, 19761, 19762, -1, 19760, 19762, 19763, -1, 19764, 19765, 19743, -1, 19764, 19743, 19746, -1, 19764, 19746, 19766, -1, 19767, 19749, 19747, -1, 19767, 19768, 19749, -1, 19767, 19748, 19769, -1, 19767, 19747, 19748, -1, 19770, 19752, 19751, -1, 19030, 19634, 19019, -1, 19770, 19771, 19752, -1, 19770, 19751, 19753, -1, 11422, 11425, 19008, -1, 19772, 19755, 19757, -1, 19772, 19758, 19755, -1, 19772, 19757, 19773, -1, 19774, 19765, 19764, -1, 19774, 19764, 19766, -1, 19774, 19775, 19765, -1, 19774, 19766, 19776, -1, 19777, 19767, 19769, -1, 19777, 19768, 19767, -1, 19777, 19769, 19778, -1, 19779, 19742, 19780, -1, 19779, 19745, 19742, -1, 19779, 19780, 19781, -1, 19779, 19781, 19745, -1, 19782, 19770, 19753, -1, 19782, 19753, 19783, -1, 19782, 19771, 19770, -1, 19036, 18971, 19033, -1, 19782, 19784, 19771, -1, 19036, 18983, 18971, -1, 19785, 19758, 19772, -1, 19786, 19787, 19788, -1, 19785, 19789, 19790, -1, 19785, 19773, 19789, -1, 19785, 19772, 19773, -1, 19785, 19790, 19758, -1, 19791, 19776, 19792, -1, 19791, 19775, 19774, -1, 19791, 19774, 19776, -1, 19049, 18974, 18976, -1, 19793, 11921, 11906, -1, 19793, 11906, 19794, -1, 19793, 19795, 11921, -1, 19796, 19537, 19720, -1, 19797, 19768, 19777, -1, 19797, 11647, 19798, -1, 19797, 19799, 11647, -1, 19796, 19009, 19537, -1, 19797, 19777, 19778, -1, 19797, 19778, 19799, -1, 19797, 19798, 19768, -1, 19048, 18974, 19049, -1, 19800, 19801, 19784, -1, 19800, 19783, 19802, -1, 19800, 19782, 19783, -1, 19800, 19784, 19782, -1, 19803, 19804, 19805, -1, 19803, 19805, 19806, -1, 19807, 19701, 19700, -1, 19803, 19806, 19808, -1, 19803, 19808, 19809, -1, 19810, 19792, 19811, -1, 19001, 18999, 19754, -1, 19810, 19812, 19775, -1, 19807, 19813, 19701, -1, 19810, 19775, 19791, -1, 19810, 19791, 19792, -1, 19814, 19815, 19795, -1, 19814, 19794, 19816, -1, 19814, 19793, 19794, -1, 19814, 19795, 19793, -1, 19817, 19801, 19800, -1, 19817, 19800, 19802, -1, 19817, 19818, 19801, -1, 19817, 19802, 19818, -1, 19819, 19820, 19821, -1, 19822, 19807, 19700, -1, 19819, 19823, 19824, -1, 19825, 19706, 19725, -1, 19819, 19824, 19820, -1, 19826, 19811, 19827, -1, 19826, 19810, 19811, -1, 19826, 19812, 19810, -1, 19828, 19787, 19786, -1, 19826, 19829, 19812, -1, 19830, 19804, 19803, -1, 19830, 19803, 19809, -1, 19830, 19831, 19804, -1, 19832, 19821, 19833, -1, 19832, 19819, 19821, -1, 19832, 19823, 19819, -1, 19834, 19814, 19816, -1, 19834, 19835, 19836, -1, 19834, 19815, 19814, -1, 19834, 19836, 19815, -1, 19834, 19816, 19835, -1, 19837, 19827, 19838, -1, 19839, 19710, 19731, -1, 19837, 19826, 19827, -1, 19837, 19838, 19840, -1, 19837, 19829, 19826, -1, 19837, 19840, 19829, -1, 19841, 19830, 19809, -1, 19841, 19831, 19830, -1, 19841, 19809, 19842, -1, 19841, 19843, 19844, -1, 19841, 19844, 19831, -1, 19845, 19832, 19833, -1, 19845, 19833, 19846, -1, 19845, 19847, 19823, -1, 19848, 19839, 19731, -1, 19845, 19823, 19832, -1, 19010, 19009, 19796, -1, 19849, 19850, 19851, -1, 19849, 19851, 19852, -1, 19849, 19852, 19853, -1, 19854, 19855, 19856, -1, 19857, 19858, 19859, -1, 19026, 19825, 19725, -1, 19854, 19860, 19836, -1, 19854, 19836, 19855, -1, 19861, 19840, 19838, -1, 19861, 19862, 19863, -1, 19861, 19864, 19862, -1, 19861, 19865, 19864, -1, 19861, 19838, 19865, -1, 19857, 19859, 19866, -1, 19861, 19863, 19867, -1, 19861, 19867, 19840, -1, 19868, 19869, 19847, -1, 19868, 19845, 19846, -1, 19868, 19847, 19845, -1, 19870, 19848, 19871, -1, 19868, 19846, 19869, -1, 19872, 19754, 19649, -1, 19873, 19874, 19875, -1, 19873, 19842, 19874, -1, 19872, 19649, 19876, -1, 19873, 19841, 19842, -1, 19873, 19843, 19841, -1, 19873, 19875, 19843, -1, 19877, 19878, 19879, -1, 19877, 19879, 19880, -1, 19877, 19881, 19878, -1, 19882, 19883, 19884, -1, 19882, 19885, 19883, -1, 19882, 19886, 19885, -1, 19887, 19849, 19853, -1, 19887, 19888, 19850, -1, 19887, 19889, 19888, -1, 19887, 19853, 19889, -1, 19887, 19850, 19849, -1, 19890, 19760, 19763, -1, 19890, 19763, 19891, -1, 19892, 19860, 19854, -1, 19892, 19893, 19860, -1, 19892, 19854, 19856, -1, 19894, 19895, 11934, -1, 19894, 19896, 19895, -1, 19894, 11942, 11927, -1, 19894, 11934, 11942, -1, 19894, 11927, 19897, -1, 19898, 19877, 19880, -1, 19898, 11633, 19899, -1, 19898, 19881, 19877, -1, 19898, 19880, 11622, -1, 19898, 11622, 11633, -1, 19898, 19899, 19881, -1, 19900, 19863, 19862, -1, 19900, 19862, 19901, -1, 19900, 19902, 19863, -1, 19903, 19882, 19884, -1, 19903, 19884, 19904, -1, 19903, 19886, 19882, -1, 19903, 19905, 19886, -1, 19906, 19856, 19907, -1, 19906, 19893, 19892, -1, 19906, 19892, 19856, -1, 19908, 19894, 19897, -1, 19908, 19909, 19896, -1, 19908, 19896, 19894, -1, 19908, 19897, 19909, -1, 19910, 19903, 19904, -1, 19910, 19904, 19911, -1, 19910, 19905, 19903, -1, 19912, 19902, 19900, -1, 19912, 19900, 19901, -1, 19912, 19901, 19913, -1, 19912, 19914, 19902, -1, 19915, 19907, 19916, -1, 19915, 19917, 19893, -1, 19915, 19893, 19906, -1, 19915, 19916, 19917, -1, 19915, 19906, 19907, -1, 19918, 19919, 19920, -1, 19921, 19922, 19923, -1, 19918, 19920, 19864, -1, 19918, 19864, 19865, -1, 19918, 19865, 19919, -1, 19924, 19925, 19926, -1, 19924, 19927, 19928, -1, 19924, 19928, 19925, -1, 19924, 19926, 19929, -1, 19924, 19929, 19927, -1, 19930, 19905, 19910, -1, 19930, 19911, 19931, -1, 19930, 19931, 19932, -1, 19933, 19807, 19822, -1, 19930, 19932, 19905, -1, 19930, 19910, 19911, -1, 19934, 19914, 19912, -1, 19934, 19912, 19913, -1, 19934, 19913, 19935, -1, 19936, 19937, 19938, -1, 19936, 19938, 19939, -1, 19936, 19940, 19937, -1, 19936, 19941, 19940, -1, 19942, 19914, 19934, -1, 19942, 19943, 19914, -1, 19942, 19934, 19935, -1, 19944, 19933, 19822, -1, 19942, 19935, 19945, -1, 19946, 19916, 19947, -1, 19946, 19948, 19949, -1, 19946, 19949, 19916, -1, 19950, 19951, 19952, -1, 19950, 19953, 19954, -1, 19955, 19839, 19848, -1, 19063, 19825, 19026, -1, 19950, 19952, 19953, -1, 19956, 19941, 19936, -1, 19956, 19936, 19939, -1, 19956, 19957, 19941, -1, 19958, 19942, 19945, -1, 19958, 19943, 19942, -1, 19958, 19959, 19943, -1, 19958, 19945, 19960, -1, 19961, 19947, 19962, -1, 19961, 19946, 19947, -1, 19043, 19041, 19045, -1, 19961, 19948, 19946, -1, 19963, 19964, 19929, -1, 19963, 19926, 19965, -1, 19966, 19876, 19967, -1, 19963, 19929, 19926, -1, 19963, 19965, 19964, -1, 19966, 19872, 19876, -1, 19968, 19951, 19950, -1, 19968, 19950, 19954, -1, 19968, 19954, 19969, -1, 19970, 19959, 19958, -1, 19970, 19958, 19960, -1, 19970, 19971, 19959, -1, 19970, 19960, 19972, -1, 19973, 19939, 19974, -1, 19973, 19956, 19939, -1, 19973, 19975, 19976, -1, 19973, 19976, 19957, -1, 19973, 19957, 19956, -1, 19977, 19857, 19866, -1, 19978, 19962, 18392, -1, 19977, 19866, 19979, -1, 19978, 19948, 19961, -1, 19978, 19980, 19948, -1, 19978, 19961, 19962, -1, 19978, 18392, 19980, -1, 19981, 19982, 19983, -1, 19981, 19984, 18373, -1, 19981, 19983, 19984, -1, 19985, 19969, 19986, -1, 19101, 19003, 19005, -1, 19985, 19987, 19951, -1, 19985, 19968, 19969, -1, 19985, 19951, 19968, -1, 19988, 19971, 19970, -1, 19988, 19970, 19972, -1, 19988, 19989, 19990, -1, 19988, 19990, 19971, -1, 19038, 19041, 19043, -1, 19991, 19980, 18394, -1, 19991, 19992, 19980, -1, 19993, 19848, 19870, -1, 19991, 18394, 19994, -1, 19993, 19955, 19848, -1, 19995, 19973, 19974, -1, 19995, 19975, 19973, -1, 19995, 18412, 18411, -1, 19995, 19974, 18412, -1, 19995, 18411, 19975, -1, 19996, 19891, 19997, -1, 19998, 19982, 19981, -1, 19998, 19999, 19982, -1, 19996, 19890, 19891, -1, 19998, 19981, 18373, -1, 19998, 18373, 18372, -1, 20000, 20001, 20002, -1, 20000, 20003, 20001, -1, 20000, 20004, 20003, -1, 20005, 19986, 20006, -1, 20005, 19985, 19986, -1, 20005, 19987, 19985, -1, 20005, 20006, 19987, -1, 19082, 19034, 19077, -1, 20007, 18397, 18396, -1, 20007, 18396, 20008, -1, 19082, 19035, 19034, -1, 20007, 20009, 18397, -1, 20007, 20008, 20009, -1, 20010, 19988, 19972, -1, 20010, 19972, 20011, -1, 20010, 19989, 19988, -1, 20012, 19992, 19991, -1, 20012, 20013, 19992, -1, 20012, 19991, 19994, -1, 20014, 20002, 20015, -1, 20014, 20000, 20002, -1, 20014, 20004, 20000, -1, 20016, 20017, 19999, -1, 20018, 19069, 19050, -1, 20016, 19998, 18372, -1, 20016, 19999, 19998, -1, 20019, 20011, 20020, -1, 20019, 19989, 20010, -1, 20019, 20021, 19989, -1, 20019, 20010, 20011, -1, 20022, 20023, 20024, -1, 20025, 18395, 18397, -1, 19070, 19078, 19067, -1, 20025, 18397, 20013, -1, 20025, 20012, 19994, -1, 20025, 20013, 20012, -1, 20025, 19994, 20026, -1, 20025, 20026, 18395, -1, 20027, 20015, 20028, -1, 20027, 20004, 20014, -1, 20027, 20029, 20004, -1, 20027, 20014, 20015, -1, 20030, 20017, 20016, -1, 20030, 18445, 18447, -1, 20030, 18447, 20017, -1, 20030, 18372, 18445, -1, 20031, 12045, 12047, -1, 20030, 20016, 18372, -1, 20032, 20033, 20034, -1, 20032, 20035, 20033, -1, 20032, 20034, 20036, -1, 20037, 20020, 20038, -1, 20039, 19933, 19944, -1, 20037, 20021, 20019, -1, 20037, 18390, 20021, -1, 20037, 20019, 20020, -1, 20040, 18429, 18470, -1, 20040, 18470, 18472, -1, 20040, 18472, 20041, -1, 20040, 20041, 18423, -1, 20040, 18423, 18429, -1, 20042, 20029, 20027, -1, 20042, 20028, 18422, -1, 20042, 20027, 20028, -1, 20042, 18422, 18424, -1, 20042, 18424, 20029, -1, 20043, 20038, 20044, -1, 20043, 20037, 20038, -1, 20043, 18390, 20037, -1, 20045, 18464, 18460, -1, 20045, 18460, 20046, -1, 19102, 19101, 19005, -1, 20045, 18442, 20047, -1, 20045, 20047, 18464, -1, 20048, 19921, 19923, -1, 19091, 19039, 19038, -1, 20049, 18529, 18528, -1, 20049, 20050, 20035, -1, 20049, 20035, 20032, -1, 20049, 20032, 20036, -1, 20049, 20036, 18529, -1, 19091, 19129, 19039, -1, 20051, 18399, 18395, -1, 20051, 20052, 18399, -1, 20051, 18395, 20053, -1, 20054, 20044, 20055, -1, 20054, 20043, 20044, -1, 20054, 18427, 18390, -1, 20054, 18390, 20043, -1, 19100, 19967, 19101, -1, 20056, 20046, 20057, -1, 20056, 18442, 20045, -1, 19100, 19966, 19967, -1, 20056, 20045, 20046, -1, 20058, 20059, 20050, -1, 20058, 20050, 20049, -1, 20058, 20049, 18528, -1, 20060, 18470, 18429, -1, 20060, 18429, 18552, -1, 19079, 19078, 19070, -1, 20060, 18552, 18554, -1, 20060, 18554, 18470, -1, 20061, 20039, 19944, -1, 20062, 20051, 20053, -1, 20062, 20052, 20051, -1, 20062, 20053, 20063, -1, 20064, 18427, 20054, -1, 20064, 20055, 20065, -1, 20064, 20054, 20055, -1, 20064, 20066, 18427, -1, 20067, 18440, 18442, -1, 20067, 20068, 18440, -1, 20067, 18442, 20056, -1, 20067, 20057, 20069, -1, 20067, 20056, 20057, -1, 20070, 18528, 20071, -1, 20070, 20071, 18544, -1, 20070, 20058, 18528, -1, 20070, 20059, 20058, -1, 20070, 18543, 20059, -1, 20070, 18544, 18543, -1, 20072, 18578, 20052, -1, 20072, 20052, 20062, -1, 20073, 19069, 20018, -1, 20072, 20062, 20063, -1, 20072, 18579, 18578, -1, 20072, 20063, 18579, -1, 20074, 19977, 19979, -1, 20075, 18453, 11973, -1, 20075, 20076, 18453, -1, 20075, 11973, 11970, -1, 20075, 11970, 20077, -1, 20078, 20065, 11579, -1, 20078, 11579, 11589, -1, 20074, 19979, 20079, -1, 20078, 18502, 20066, -1, 20078, 20066, 20064, -1, 20078, 20064, 20065, -1, 20080, 20023, 20022, -1, 20078, 11589, 18502, -1, 20081, 20082, 20068, -1, 20081, 20068, 20067, -1, 20081, 20067, 20069, -1, 20083, 18559, 18568, -1, 20083, 18568, 20084, -1, 20083, 20085, 20086, -1, 20083, 20086, 18559, -1, 20087, 20088, 18578, -1, 20087, 18578, 18577, -1, 20089, 19997, 20090, -1, 20087, 18577, 20091, -1, 20092, 20075, 20077, -1, 20089, 19996, 19997, -1, 20092, 18589, 20076, -1, 20089, 20090, 20093, -1, 20092, 20076, 20075, -1, 20092, 20077, 20094, -1, 20095, 20081, 20069, -1, 20095, 18682, 20082, -1, 20095, 20069, 20096, -1, 20097, 19955, 19993, -1, 20095, 20096, 18682, -1, 20095, 20082, 20081, -1, 20098, 18471, 18523, -1, 20098, 18521, 18471, -1, 20098, 18523, 20099, -1, 20100, 18603, 18602, -1, 20100, 18553, 18603, -1, 20100, 18551, 18553, -1, 20100, 18602, 18551, -1, 20101, 20088, 20087, -1, 20102, 20080, 20022, -1, 20103, 20073, 20018, -1, 20101, 20104, 20088, -1, 20101, 20087, 20091, -1, 20105, 20085, 20083, -1, 20105, 20084, 20106, -1, 20105, 20083, 20084, -1, 20107, 19996, 20089, -1, 20105, 20108, 20085, -1, 20109, 18521, 20098, -1, 20109, 20098, 20099, -1, 20109, 20099, 20110, -1, 20111, 20092, 20094, -1, 20111, 18589, 20092, -1, 20111, 18588, 18589, -1, 20111, 20094, 20112, -1, 20113, 20104, 20101, -1, 20113, 18603, 20104, -1, 20113, 20101, 20091, -1, 20113, 18601, 18603, -1, 20113, 20091, 20114, -1, 20113, 20114, 18601, -1, 20115, 20105, 20106, -1, 20115, 18645, 18646, -1, 20115, 20108, 20105, -1, 20115, 20106, 18645, -1, 20115, 18646, 20108, -1, 20116, 18521, 20109, -1, 20116, 18564, 18521, -1, 20117, 19921, 20048, -1, 20116, 20109, 20110, -1, 20116, 20110, 20118, -1, 20119, 18547, 18542, -1, 20119, 18542, 20120, -1, 20119, 20121, 18547, -1, 20122, 20111, 20112, -1, 20122, 18588, 20111, -1, 20122, 20112, 20123, -1, 20124, 20118, 18611, -1, 20124, 18611, 18613, -1, 20124, 18613, 18564, -1, 20124, 18564, 20116, -1, 20124, 20116, 20118, -1, 20125, 20039, 20061, -1, 20126, 20119, 20120, -1, 20126, 20120, 20127, -1, 11521, 11503, 20128, -1, 20126, 20121, 20119, -1, 20129, 20106, 20084, -1, 20129, 20130, 20131, -1, 20129, 20131, 20106, -1, 20129, 20132, 20130, -1, 20129, 20084, 20133, -1, 20129, 20133, 20132, -1, 20134, 20135, 18588, -1, 20134, 18588, 20122, -1, 20134, 20123, 20136, -1, 20134, 20122, 20123, -1, 20137, 20096, 18656, -1, 20137, 18682, 20096, -1, 20138, 11985, 11994, -1, 20138, 18810, 18809, -1, 20138, 11990, 18810, -1, 20138, 18616, 11985, -1, 20138, 18809, 18616, -1, 20138, 11994, 11990, -1, 20139, 11572, 18651, -1, 20140, 20141, 20142, -1, 20139, 11560, 11572, -1, 20139, 18651, 18681, -1, 20139, 18681, 18680, -1, 19177, 11777, 11788, -1, 20139, 18680, 20143, -1, 20140, 20142, 20144, -1, 19177, 11693, 11777, -1, 20139, 20143, 11560, -1, 20145, 20146, 18605, -1, 20145, 18601, 20147, -1, 20145, 18605, 18601, -1, 20148, 20126, 20127, -1, 20149, 20150, 20151, -1, 20148, 20121, 20126, -1, 20148, 20127, 18754, -1, 20148, 20152, 20121, -1, 20153, 19955, 20097, -1, 20148, 18754, 18761, -1, 20154, 20135, 20134, -1, 20154, 20134, 20136, -1, 20153, 20155, 19955, -1, 20154, 20156, 20135, -1, 20154, 20136, 18722, -1, 20157, 20137, 18656, -1, 20157, 18682, 20137, -1, 20157, 18680, 18682, -1, 20157, 18656, 18655, -1, 20158, 20150, 20149, -1, 20157, 18655, 18680, -1, 19136, 19090, 19092, -1, 20159, 20148, 18761, -1, 20159, 20152, 20148, -1, 20159, 20160, 20152, -1, 20161, 19921, 20117, -1, 20162, 20146, 20145, -1, 20162, 20145, 20147, -1, 20162, 20147, 20163, -1, 20164, 20165, 20156, -1, 20166, 20073, 20103, -1, 20164, 20154, 18722, -1, 20164, 20156, 20154, -1, 20164, 18722, 18721, -1, 20167, 18771, 18768, -1, 20167, 18779, 20130, -1, 20167, 20130, 20132, -1, 20167, 20132, 18771, -1, 20167, 18768, 18779, -1, 20168, 18761, 20169, -1, 20168, 20169, 18770, -1, 20168, 18770, 18769, -1, 20168, 20160, 20159, -1, 20170, 20080, 20102, -1, 20168, 18769, 20160, -1, 20168, 20159, 18761, -1, 20171, 18860, 18859, -1, 20171, 18859, 20146, -1, 20171, 20146, 20162, -1, 20171, 20163, 18860, -1, 20171, 20162, 20163, -1, 20172, 20173, 20165, -1, 20172, 20165, 20164, -1, 20172, 20164, 18721, -1, 20174, 18798, 18829, -1, 20174, 18829, 20175, -1, 20174, 20176, 20177, -1, 20174, 20177, 18798, -1, 20178, 20179, 18859, -1, 20178, 18859, 18858, -1, 20180, 20172, 18721, -1, 20180, 18721, 20181, -1, 20180, 20182, 20173, -1, 20180, 20173, 20172, -1, 20183, 18749, 18669, -1, 20183, 18764, 20184, -1, 20183, 18669, 18764, -1, 20185, 20174, 20175, -1, 20185, 20176, 20174, -1, 20185, 20175, 20186, -1, 20185, 20187, 20176, -1, 20188, 20189, 20179, -1, 20188, 20179, 20178, -1, 19132, 20166, 20103, -1, 20188, 20178, 18858, -1, 20190, 20155, 20153, -1, 20188, 18858, 20191, -1, 20192, 20181, 20193, -1, 20192, 20182, 20180, -1, 20192, 18988, 20182, -1, 20192, 20180, 20181, -1, 20194, 20170, 20102, -1, 20195, 20183, 20184, -1, 20195, 18749, 20183, -1, 20195, 20184, 20196, -1, 20197, 20189, 20188, -1, 20197, 20191, 20198, -1, 20197, 20188, 20191, -1, 20199, 18808, 19166, -1, 20199, 18814, 18808, -1, 20199, 19166, 19168, -1, 20200, 20186, 19162, -1, 20200, 20185, 20186, -1, 20201, 20048, 20202, -1, 20200, 20187, 20185, -1, 20200, 19162, 19163, -1, 20201, 20117, 20048, -1, 11396, 11402, 19159, -1, 20200, 19163, 20187, -1, 20203, 18987, 18988, -1, 20203, 18988, 20192, -1, 20203, 20192, 20193, -1, 20204, 18835, 18749, -1, 20204, 18749, 20195, -1, 20205, 19118, 19094, -1, 20204, 20195, 20196, -1, 20204, 20196, 20206, -1, 20207, 18880, 20189, -1, 20207, 20198, 19011, -1, 20207, 20197, 20198, -1, 20207, 20189, 20197, -1, 20207, 19011, 18880, -1, 20208, 19107, 19109, -1, 20208, 20199, 19168, -1, 20208, 19168, 19107, -1, 20208, 19109, 18814, -1, 20208, 18814, 20199, -1, 20209, 20193, 20210, -1, 20209, 20210, 20211, -1, 20209, 20203, 20193, -1, 20209, 18987, 20203, -1, 20212, 19108, 19143, -1, 20212, 19061, 18968, -1, 20212, 19143, 20213, -1, 20212, 18968, 19108, -1, 20214, 20215, 20216, -1, 20214, 20216, 20217, -1, 20214, 20217, 20186, -1, 20214, 20175, 20218, -1, 20214, 20218, 20215, -1, 20214, 20186, 20175, -1, 20219, 18959, 18958, -1, 20219, 18958, 20220, -1, 20221, 20204, 20206, -1, 20221, 19150, 19152, -1, 20221, 18835, 20204, -1, 20221, 20206, 19150, -1, 20221, 19152, 18835, -1, 20222, 18987, 20209, -1, 20222, 20211, 20223, -1, 20222, 20209, 20211, -1, 20222, 20224, 18987, -1, 20225, 20220, 19409, -1, 20225, 20219, 20220, -1, 20226, 19088, 19087, -1, 20225, 20227, 18959, -1, 20225, 18959, 20219, -1, 20228, 20229, 19061, -1, 20228, 19061, 20212, -1, 20228, 20212, 20213, -1, 20230, 19011, 20231, -1, 20230, 19024, 19011, -1, 20230, 20232, 19024, -1, 20233, 20223, 19402, -1, 20233, 20234, 20224, -1, 20233, 20222, 20223, -1, 20233, 20224, 20222, -1, 20235, 19409, 19408, -1, 20235, 20236, 20227, -1, 20235, 20225, 19409, -1, 20235, 20227, 20225, -1, 20237, 19503, 20229, -1, 20237, 19504, 19503, -1, 20237, 20229, 20228, -1, 20237, 20213, 19504, -1, 20237, 20228, 20213, -1, 20238, 19373, 19081, -1, 20238, 19205, 20239, -1, 20238, 19081, 19205, -1, 20240, 20231, 20241, -1, 19174, 20166, 19132, -1, 20240, 20232, 20230, -1, 20240, 20230, 20231, -1, 20242, 20216, 20215, -1, 20242, 19446, 20216, -1, 20242, 19426, 19446, -1, 20242, 20215, 19431, -1, 20242, 19431, 19426, -1, 20243, 20236, 20235, -1, 20243, 20235, 19408, -1, 20243, 19428, 19427, -1, 20243, 19427, 20236, -1, 20243, 19408, 20244, -1, 11395, 11396, 19159, -1, 20243, 20244, 19428, -1, 20245, 19402, 19401, -1, 20245, 20246, 20247, -1, 20245, 20247, 20234, -1, 20245, 20233, 19402, -1, 20245, 20234, 20233, -1, 20248, 20232, 20240, -1, 20248, 20240, 20241, -1, 20248, 20241, 19597, -1, 20249, 20170, 20194, -1, 20248, 19597, 19596, -1, 20248, 19596, 20232, -1, 20250, 19493, 19762, -1, 20250, 20251, 19461, -1, 20250, 19461, 19493, -1, 20252, 19373, 20238, -1, 20252, 20239, 20253, -1, 20252, 19372, 19373, -1, 20252, 20238, 20239, -1, 20254, 20255, 20256, -1, 20257, 20258, 20246, -1, 20257, 20246, 20245, -1, 20259, 20201, 20202, -1, 20257, 20245, 19401, -1, 20259, 20202, 20260, -1, 20257, 19401, 20261, -1, 20262, 19596, 19595, -1, 19158, 11395, 19159, -1, 20262, 20263, 19596, -1, 20264, 20250, 19762, -1, 20264, 20265, 20251, -1, 20266, 19118, 20205, -1, 20264, 20251, 20250, -1, 20267, 20253, 20268, -1, 20267, 19372, 20252, -1, 20267, 20252, 20253, -1, 20269, 19576, 20258, -1, 20269, 20258, 20257, -1, 20269, 20257, 20261, -1, 20269, 20261, 20270, -1, 20271, 19595, 20272, -1, 20273, 19088, 20226, -1, 20271, 20263, 20262, -1, 20271, 20262, 19595, -1, 20274, 20275, 20276, -1, 20277, 19400, 19647, -1, 20277, 19647, 19646, -1, 20277, 19486, 19400, -1, 20277, 19646, 19486, -1, 20278, 20264, 19762, -1, 20278, 19762, 19761, -1, 20278, 20279, 20265, -1, 20278, 20265, 20264, -1, 20280, 19372, 20267, -1, 20280, 20267, 20268, -1, 20280, 20268, 20281, -1, 20282, 20255, 20254, -1, 20280, 20283, 19372, -1, 20284, 20266, 20205, -1, 20285, 20269, 20270, -1, 20285, 19576, 20269, -1, 20285, 19675, 19576, -1, 20286, 12035, 12037, -1, 20286, 12027, 12035, -1, 20286, 12037, 20287, -1, 20286, 19519, 12027, -1, 20288, 11536, 19603, -1, 20288, 20271, 20272, -1, 20288, 20263, 20271, -1, 20288, 20272, 20289, -1, 20288, 20289, 11513, -1, 20288, 11513, 11536, -1, 20288, 19603, 20263, -1, 20290, 19859, 19858, -1, 20291, 20292, 20293, -1, 20290, 19507, 19502, -1, 11386, 11395, 19158, -1, 20290, 19502, 19859, -1, 20294, 20278, 19761, -1, 20294, 19761, 19870, -1, 20291, 20293, 20295, -1, 20294, 19871, 20279, -1, 20296, 19142, 19098, -1, 20294, 20279, 20278, -1, 20294, 19870, 19871, -1, 20297, 20281, 19700, -1, 20297, 19700, 19703, -1, 20297, 20283, 20280, -1, 20297, 20280, 20281, -1, 20296, 19098, 20298, -1, 20297, 19703, 20283, -1, 20299, 20300, 20301, -1, 19196, 19106, 19105, -1, 20299, 19675, 20285, -1, 20299, 20285, 20270, -1, 20299, 20270, 20300, -1, 20302, 19519, 20286, -1, 20302, 19923, 19922, -1, 20302, 19922, 19519, -1, 20302, 20287, 19923, -1, 20302, 20286, 20287, -1, 20303, 19788, 19507, -1, 20303, 19786, 19788, -1, 20303, 19507, 20290, -1, 20303, 19858, 19786, -1, 19195, 19106, 19196, -1, 20303, 20290, 19858, -1, 20304, 19624, 19623, -1, 20304, 19623, 20305, -1, 20306, 20301, 20307, -1, 20306, 20308, 19675, -1, 20309, 20310, 20311, -1, 20306, 19675, 20299, -1, 20306, 20299, 20301, -1, 20312, 19645, 19787, -1, 20312, 19750, 19645, -1, 20312, 19828, 20313, -1, 20312, 19787, 19828, -1, 20314, 20304, 20305, -1, 20314, 20315, 19624, -1, 19147, 19088, 20273, -1, 20314, 19624, 20304, -1, 20314, 20305, 20024, -1, 20316, 20307, 20142, -1, 20316, 20317, 20308, -1, 20316, 20306, 20307, -1, 19147, 19146, 19088, -1, 20316, 20308, 20306, -1, 20318, 20312, 20313, -1, 20318, 20313, 20151, -1, 20318, 20151, 20150, -1, 20318, 19750, 20312, -1, 20318, 20150, 20319, -1, 20318, 20319, 19750, -1, 20320, 20315, 20314, -1, 20320, 20321, 20315, -1, 20320, 20314, 20024, -1, 20320, 20024, 20023, -1, 20322, 20323, 20324, -1, 20322, 20324, 20317, -1, 20322, 20142, 20141, -1, 20322, 20316, 20142, -1, 20322, 20317, 20316, -1, 20325, 20320, 20023, -1, 20326, 20274, 20276, -1, 20325, 20090, 20321, -1, 20325, 20093, 20090, -1, 20325, 20023, 20327, -1, 20325, 20327, 20093, -1, 20325, 20321, 20320, -1, 20328, 19807, 20329, -1, 20330, 20331, 20332, -1, 20328, 20329, 20333, -1, 20330, 20332, 20282, -1, 20328, 19813, 19807, -1, 20328, 20079, 19813, -1, 20334, 20335, 20336, -1, 20334, 20336, 19921, -1, 20334, 19921, 20161, -1, 20337, 20275, 20031, -1, 20337, 12051, 12052, -1, 20337, 12047, 12051, -1, 20337, 12052, 20276, -1, 20338, 20260, 20274, -1, 20337, 20276, 20275, -1, 20337, 20031, 12047, -1, 20338, 20259, 20260, -1, 20339, 20190, 11488, -1, 20339, 11520, 11521, -1, 20340, 19127, 19114, -1, 20339, 11488, 11520, -1, 20339, 20128, 20155, -1, 20339, 11521, 20128, -1, 20339, 20155, 20190, -1, 20341, 20342, 20323, -1, 20341, 20323, 20322, -1, 20341, 20322, 20141, -1, 20341, 20141, 20343, -1, 20344, 20310, 20309, -1, 20345, 20328, 20333, -1, 20345, 20074, 20079, -1, 20345, 20333, 20346, -1, 20345, 20079, 20328, -1, 20347, 20335, 20334, -1, 20347, 20061, 20335, -1, 20347, 20161, 20348, -1, 20347, 20334, 20161, -1, 20349, 20346, 20350, -1, 20351, 20266, 20284, -1, 20349, 20074, 20345, -1, 20349, 20345, 20346, -1, 20352, 20194, 20342, -1, 20352, 20342, 20341, -1, 20352, 20341, 20343, -1, 20352, 20343, 20353, -1, 20354, 20125, 20061, -1, 20354, 20347, 20348, -1, 20354, 20348, 20355, -1, 20354, 20061, 20347, -1, 20356, 20140, 20144, -1, 20356, 20293, 20292, -1, 20356, 20292, 20140, -1, 20356, 20144, 20293, -1, 19182, 20351, 20284, -1, 20357, 20332, 20358, -1, 20359, 20360, 20361, -1, 20357, 20358, 20255, -1, 20357, 20282, 20332, -1, 20359, 20361, 20362, -1, 20357, 20255, 20282, -1, 20363, 20349, 20350, -1, 20363, 20350, 20254, -1, 20363, 20074, 20349, -1, 20363, 20254, 20256, -1, 20364, 20226, 20365, -1, 20363, 20256, 20074, -1, 20366, 20352, 20353, -1, 20366, 20194, 20352, -1, 20364, 20273, 20226, -1, 20367, 20149, 20361, -1, 20367, 20158, 20149, -1, 20368, 20125, 20354, -1, 20368, 20369, 20125, -1, 20368, 20354, 20355, -1, 20368, 20355, 20370, -1, 20371, 20372, 20107, -1, 20371, 20089, 20373, -1, 20371, 20107, 20089, -1, 20374, 20249, 20194, -1, 20374, 20194, 20366, -1, 20374, 20366, 20353, -1, 20374, 20353, 20375, -1, 20374, 20375, 20376, -1, 20377, 20367, 20361, -1, 20378, 20296, 20298, -1, 20377, 20360, 20309, -1, 20377, 20361, 20360, -1, 20377, 20311, 20158, -1, 20377, 20309, 20311, -1, 20377, 20158, 20367, -1, 20378, 20298, 20379, -1, 20380, 20381, 20369, -1, 20380, 20368, 20370, -1, 20380, 20369, 20368, -1, 20382, 20371, 20373, -1, 20382, 20373, 20383, -1, 20382, 20372, 20371, -1, 20384, 20310, 20344, -1, 20384, 20344, 20385, -1, 20384, 20291, 20295, -1, 20384, 20295, 20310, -1, 20386, 20249, 20374, -1, 20386, 20376, 20387, -1, 20386, 20388, 20249, -1, 20386, 20374, 20376, -1, 20389, 20381, 20380, -1, 20389, 20390, 20391, -1, 20389, 20391, 20381, -1, 20389, 20380, 20370, -1, 20389, 20370, 20390, -1, 20392, 20393, 20330, -1, 20392, 20282, 20394, -1, 20392, 20330, 20282, -1, 20392, 20394, 20393, -1, 20395, 20396, 20372, -1, 20395, 20382, 20383, -1, 20395, 20383, 20397, -1, 20395, 20372, 20382, -1, 20398, 20388, 20386, -1, 20398, 20386, 20387, -1, 20398, 20387, 20399, -1, 20398, 20400, 20388, -1, 20401, 20274, 20326, -1, 20401, 20326, 20402, -1, 20401, 20338, 20274, -1, 20403, 20404, 20405, -1, 20403, 20385, 20404, -1, 20403, 20405, 20406, -1, 20403, 20406, 20291, -1, 20403, 20384, 20385, -1, 20403, 20291, 20384, -1, 20407, 20408, 20409, -1, 20410, 19127, 20340, -1, 20407, 20411, 20412, -1, 20407, 20412, 20408, -1, 20413, 20397, 20414, -1, 20413, 20396, 20395, -1, 20413, 20415, 20396, -1, 20413, 20395, 20397, -1, 20416, 20398, 20399, -1, 20416, 20400, 20398, -1, 20416, 20417, 20400, -1, 19191, 19189, 19192, -1, 20418, 20402, 20419, -1, 20418, 20401, 20402, -1, 20418, 20338, 20401, -1, 20420, 20409, 20421, -1, 20420, 20422, 20411, -1, 20423, 20410, 20340, -1, 20420, 20411, 20407, -1, 20420, 20407, 20409, -1, 20424, 20331, 20330, -1, 20424, 20330, 20425, -1, 20424, 20425, 20426, -1, 20424, 20427, 20331, -1, 20428, 20415, 20413, -1, 20428, 20414, 20429, -1, 19215, 20351, 19182, -1, 20428, 20413, 20414, -1, 20430, 20431, 20432, -1, 20433, 11671, 11673, -1, 20430, 20432, 20434, -1, 20433, 12056, 11671, -1, 20430, 20434, 20393, -1, 20430, 20435, 20431, -1, 20430, 20393, 20435, -1, 20436, 20417, 20416, -1, 20436, 20416, 20399, -1, 19186, 19189, 19191, -1, 20436, 20437, 20417, -1, 20436, 20399, 20438, -1, 20439, 20338, 20418, -1, 20439, 20419, 20408, -1, 20439, 20412, 20338, -1, 20439, 20418, 20419, -1, 20439, 20408, 20412, -1, 20440, 20441, 20442, -1, 20440, 20442, 20443, -1, 20435, 20393, 20394, -1, 20444, 20426, 20445, -1, 20444, 20424, 20426, -1, 20444, 20427, 20424, -1, 20446, 20422, 20420, -1, 20446, 20421, 20447, -1, 20446, 20447, 20448, -1, 20446, 20448, 20422, -1, 20449, 20359, 20362, -1, 20450, 20365, 20451, -1, 20446, 20420, 20421, -1, 20450, 20364, 20365, -1, 20452, 20429, 20453, -1, 20452, 20454, 20415, -1, 20452, 20453, 20454, -1, 20452, 20428, 20429, -1, 20452, 20415, 20428, -1, 20455, 20437, 20436, -1, 20455, 20438, 20456, -1, 20449, 20362, 20457, -1, 20455, 20436, 20438, -1, 20455, 20458, 20437, -1, 20459, 20431, 20441, -1, 20459, 20441, 20440, -1, 20459, 20440, 20443, -1, 20459, 20443, 20460, -1, 20459, 20460, 20461, -1, 20462, 20445, 20463, -1, 20462, 20444, 20445, -1, 20462, 20427, 20444, -1, 20462, 20464, 20427, -1, 20465, 20466, 20433, -1, 20465, 11673, 11676, -1, 20465, 11676, 20467, -1, 20465, 20467, 20468, -1, 20465, 20433, 11673, -1, 20469, 20455, 20456, -1, 19235, 20379, 19220, -1, 20469, 20456, 20470, -1, 20469, 20458, 20455, -1, 19235, 20378, 20379, -1, 20469, 20471, 20458, -1, 20472, 20473, 20474, -1, 20472, 20474, 20475, -1, 20472, 20475, 20476, -1, 20472, 20476, 20473, -1, 20477, 20463, 20478, -1, 20477, 20462, 20463, -1, 20477, 20479, 20464, -1, 20477, 20478, 20479, -1, 20477, 20464, 20462, -1, 20480, 20432, 20431, -1, 20480, 20459, 20461, -1, 20480, 20431, 20459, -1, 20481, 20482, 20483, -1, 20481, 20483, 20484, -1, 20485, 20469, 20470, -1, 20485, 20471, 20469, -1, 20486, 20465, 20468, -1, 20486, 20466, 20465, -1, 20486, 20487, 20466, -1, 20486, 20488, 20489, -1, 20486, 20468, 20488, -1, 20490, 20491, 20492, -1, 19247, 19251, 19154, -1, 20490, 20492, 20432, -1, 19247, 19154, 19127, -1, 20490, 20461, 20493, -1, 20490, 20432, 20480, -1, 20490, 20480, 20461, -1, 20494, 20482, 20481, -1, 20494, 20481, 20484, -1, 20494, 20495, 20496, -1, 20497, 19209, 19197, -1, 20494, 20496, 20498, -1, 20494, 20498, 20482, -1, 20494, 20484, 20495, -1, 20499, 20500, 20471, -1, 20499, 20470, 20501, -1, 20499, 20501, 20502, -1, 20499, 20485, 20470, -1, 11501, 11469, 20454, -1, 20499, 20471, 20485, -1, 20503, 20504, 20505, -1, 20503, 20505, 20506, -1, 20503, 20507, 20504, -1, 20508, 20414, 20397, -1, 20509, 20487, 20486, -1, 19240, 11711, 11799, -1, 20509, 20510, 20487, -1, 20509, 20486, 20489, -1, 20511, 20512, 20513, -1, 20511, 20476, 20514, -1, 20511, 20513, 20476, -1, 20511, 20514, 20512, -1, 20515, 20410, 20423, -1, 20516, 20490, 20493, -1, 20516, 20517, 20518, -1, 20516, 20518, 20491, -1, 20516, 20491, 20490, -1, 20516, 20493, 20517, -1, 20519, 20502, 20520, -1, 20519, 20521, 20500, -1, 20519, 20499, 20502, -1, 20519, 20500, 20499, -1, 20522, 20503, 20506, -1, 20522, 20523, 20524, -1, 20522, 20507, 20503, -1, 19210, 19219, 19211, -1, 20522, 20524, 20507, -1, 20525, 20489, 20526, -1, 20525, 20527, 20510, -1, 20525, 20510, 20509, -1, 20525, 20509, 20489, -1, 20528, 20529, 11695, -1, 20528, 20530, 20529, -1, 20528, 11700, 11704, -1, 20528, 11695, 11700, -1, 20528, 11704, 20531, -1, 20532, 20520, 11384, -1, 20532, 11384, 11475, -1, 20532, 20533, 20521, -1, 20532, 20519, 20520, -1, 19225, 19187, 19186, -1, 20532, 20521, 20519, -1, 20532, 11475, 20533, -1, 20534, 20535, 20536, -1, 19225, 19269, 19187, -1, 20534, 20537, 20535, -1, 20534, 20536, 20538, -1, 20534, 20538, 20539, -1, 20540, 20522, 20506, -1, 20540, 20541, 20523, -1, 20540, 20506, 20542, -1, 20543, 20391, 20390, -1, 20540, 20542, 20541, -1, 20540, 20523, 20522, -1, 20544, 20526, 20545, -1, 20544, 20545, 20546, -1, 20544, 20525, 20526, -1, 20544, 20527, 20525, -1, 20544, 20546, 20527, -1, 20547, 20515, 20423, -1, 20548, 20530, 20528, -1, 20548, 20549, 20550, -1, 20548, 20528, 20531, -1, 20548, 20550, 20530, -1, 20548, 20531, 20549, -1, 20551, 20537, 20534, -1, 20551, 20552, 20537, -1, 20551, 20534, 20539, -1, 20551, 20539, 20552, -1, 20553, 20513, 20554, -1, 20553, 20554, 20555, -1, 19217, 19219, 19210, -1, 20553, 20556, 20513, -1, 20553, 20557, 20556, -1, 20558, 20559, 20560, -1, 20558, 20514, 20561, -1, 20558, 20561, 20562, -1, 20558, 20560, 20514, -1, 20558, 20562, 20559, -1, 20563, 20564, 20565, -1, 20563, 20565, 20566, -1, 20567, 20568, 20569, -1, 20567, 20570, 20568, -1, 20567, 20571, 20572, -1, 20567, 20572, 20570, -1, 20567, 20569, 20571, -1, 20573, 20555, 20574, -1, 20464, 20449, 20457, -1, 20573, 20557, 20553, -1, 20464, 20457, 20427, -1, 20573, 20553, 20555, -1, 19252, 20450, 20451, -1, 20575, 20562, 20564, -1, 20575, 20566, 20576, -1, 20575, 20576, 20577, -1, 20575, 20563, 20566, -1, 20575, 20564, 20563, -1, 19252, 20451, 19251, -1, 20578, 20574, 20579, -1, 20578, 20580, 20557, -1, 20581, 19209, 20497, -1, 20578, 20573, 20574, -1, 20578, 20557, 20573, -1, 20582, 20546, 20583, -1, 11499, 11501, 20454, -1, 20582, 20584, 20546, -1, 20582, 20585, 20584, -1, 20586, 20562, 20575, -1, 20586, 20575, 20577, -1, 20586, 20559, 20562, -1, 20587, 20580, 20578, -1, 20587, 20579, 20588, -1, 20587, 20589, 20580, -1, 20587, 20578, 20579, -1, 20590, 20583, 20591, -1, 20590, 20582, 20583, -1, 20590, 20585, 20582, -1, 20592, 20593, 20594, -1, 20592, 20569, 20568, -1, 20592, 20594, 20569, -1, 20595, 20581, 20497, -1, 20592, 20568, 20593, -1, 20596, 20597, 20598, -1, 20596, 20598, 20599, -1, 20596, 20599, 20600, -1, 20601, 20602, 20603, -1, 20453, 11499, 20454, -1, 20601, 20604, 20602, -1, 20605, 20588, 20606, -1, 20605, 20606, 20607, -1, 20605, 20607, 20589, -1, 20605, 20587, 20588, -1, 20605, 20589, 20587, -1, 20608, 20609, 20610, -1, 20608, 20610, 11718, -1, 20608, 11729, 11730, -1, 20608, 11724, 11729, -1, 20608, 11718, 11724, -1, 20611, 20414, 20508, -1, 20608, 11730, 20609, -1, 20612, 20613, 20559, -1, 20612, 20577, 20614, -1, 20612, 20559, 20586, -1, 20612, 20586, 20577, -1, 20612, 20615, 20613, -1, 20616, 20591, 20617, -1, 20616, 20585, 20590, -1, 20616, 20617, 20618, -1, 20616, 20619, 20585, -1, 20616, 20590, 20591, -1, 20620, 20621, 20597, -1, 20620, 20596, 20600, -1, 20620, 20597, 20596, -1, 20620, 20600, 20622, -1, 20623, 20624, 20625, -1, 20623, 20601, 20603, -1, 20626, 20391, 20543, -1, 20623, 20627, 20604, -1, 20623, 20603, 20624, -1, 20623, 20625, 20627, -1, 20623, 20604, 20601, -1, 20628, 20611, 20508, -1, 20629, 20619, 20616, -1, 20629, 20616, 20618, -1, 20629, 20630, 20619, -1, 20631, 20515, 20547, -1, 20632, 20612, 20614, -1, 20632, 20633, 20634, -1, 20632, 20614, 20633, -1, 20632, 20615, 20612, -1, 20632, 20634, 20615, -1, 20635, 20636, 20621, -1, 20635, 20622, 20637, -1, 20635, 20621, 20620, -1, 11368, 11374, 19245, -1, 20635, 20620, 20622, -1, 20638, 20639, 20640, -1, 20638, 20641, 20639, -1, 20638, 20640, 20642, -1, 20638, 20642, 20641, -1, 20643, 20630, 20629, -1, 20643, 20629, 20618, -1, 20643, 20644, 20630, -1, 20643, 20618, 20645, -1, 11450, 11499, 20453, -1, 20646, 20647, 20648, -1, 20646, 20648, 20649, -1, 20646, 20649, 20650, -1, 20651, 20652, 20636, -1, 20651, 20635, 20637, -1, 20653, 20399, 20654, -1, 20651, 20636, 20635, -1, 20655, 20656, 20644, -1, 20655, 20643, 20645, -1, 20655, 20645, 20657, -1, 20653, 20438, 20399, -1, 20655, 20657, 20656, -1, 20655, 20644, 20643, -1, 20658, 20646, 20650, -1, 20658, 20659, 20660, -1, 20483, 20405, 20404, -1, 20658, 20647, 20646, -1, 20658, 20660, 20647, -1, 20658, 20650, 20659, -1, 20661, 20662, 20652, -1, 20661, 20651, 20637, -1, 20661, 20637, 20663, -1, 20661, 20652, 20651, -1, 20664, 20665, 20666, -1, 20664, 20666, 20667, -1, 20664, 20667, 20668, -1, 20664, 20668, 20669, -1, 20670, 20671, 20672, -1, 20482, 20405, 20483, -1, 20670, 20672, 20673, -1, 20670, 20673, 20674, -1, 20670, 20674, 20675, -1, 20670, 20675, 20671, -1, 20676, 20634, 20677, -1, 20676, 20678, 20679, -1, 20676, 20679, 20634, -1, 20680, 20681, 20662, -1, 20680, 20661, 20663, -1, 20680, 20663, 20681, -1, 20680, 20662, 20661, -1, 20682, 20664, 20669, -1, 20682, 20665, 20664, -1, 20682, 20669, 20683, -1, 20684, 20677, 20685, -1, 20443, 20391, 20626, -1, 20684, 20676, 20677, -1, 20684, 20678, 20676, -1, 20684, 20686, 20678, -1, 20443, 20442, 20391, -1, 20687, 20688, 20689, -1, 20687, 20690, 20691, -1, 20687, 20692, 20688, -1, 20687, 20689, 20690, -1, 20693, 20694, 20656, -1, 20695, 20581, 20595, -1, 20693, 20696, 20694, -1, 20693, 20656, 20697, -1, 20698, 20665, 20682, -1, 20698, 20699, 20665, -1, 20698, 20682, 20683, -1, 20698, 20683, 20700, -1, 20701, 20685, 20702, -1, 20701, 20686, 20684, -1, 20701, 20684, 20685, -1, 20703, 20687, 20691, -1, 20703, 20704, 20692, -1, 20703, 20692, 20687, -1, 20705, 20706, 20707, -1, 20705, 20708, 20709, -1, 20705, 20710, 20708, -1, 20705, 20707, 20710, -1, 20711, 20712, 20671, -1, 11366, 11368, 19245, -1, 20711, 20675, 20713, -1, 20711, 20713, 20712, -1, 20711, 20671, 20675, -1, 20714, 20696, 20693, -1, 20714, 20693, 20697, -1, 20714, 20697, 20715, -1, 20716, 20717, 20699, -1, 20716, 20698, 20700, -1, 20716, 20699, 20698, -1, 20718, 20421, 20409, -1, 20719, 20686, 20701, -1, 20719, 20701, 20702, -1, 20719, 20702, 20720, -1, 20719, 20721, 20686, -1, 20719, 20722, 20721, -1, 20723, 20704, 20703, -1, 20723, 20703, 20691, -1, 20723, 20724, 20704, -1, 20723, 20691, 20724, -1, 19270, 20695, 20595, -1, 20725, 20726, 20727, -1, 20725, 20727, 20728, -1, 20725, 20729, 20726, -1, 20730, 20696, 20714, -1, 20730, 20731, 20696, -1, 20730, 20714, 20715, -1, 20730, 20715, 20732, -1, 20733, 20611, 20628, -1, 20734, 20706, 20705, -1, 20734, 20705, 20709, -1, 20735, 19201, 20736, -1, 20734, 20737, 20706, -1, 20734, 20709, 20737, -1, 20738, 11760, 11764, -1, 20735, 19202, 19201, -1, 20738, 11764, 20739, -1, 20738, 20740, 11760, -1, 20738, 20741, 20740, -1, 20742, 11336, 11431, -1, 20742, 20743, 20717, -1, 20742, 11431, 20743, -1, 20742, 20716, 20700, -1, 20742, 20717, 20716, -1, 20742, 20700, 20744, -1, 20742, 20744, 11336, -1, 20745, 20722, 20719, -1, 20745, 20746, 20722, -1, 20745, 20719, 20720, -1, 20471, 20733, 20628, -1, 20747, 20725, 20728, -1, 20747, 20728, 20748, -1, 20747, 20729, 20725, -1, 20747, 20749, 20729, -1, 20750, 20626, 20543, -1, 20751, 20730, 20732, -1, 20751, 20731, 20730, -1, 20751, 20752, 20731, -1, 20751, 20732, 20753, -1, 20750, 20543, 20754, -1, 20755, 20739, 20756, -1, 20755, 20738, 20739, -1, 20755, 20741, 20738, -1, 20755, 20757, 20741, -1, 20758, 20720, 20759, -1, 20758, 20745, 20720, -1, 20758, 20746, 20745, -1, 20758, 20760, 20746, -1, 20758, 20759, 20760, -1, 20761, 20762, 20763, -1, 19259, 20547, 19237, -1, 20761, 20764, 20765, -1, 20761, 20763, 20764, -1, 19259, 20631, 20547, -1, 20761, 20765, 20762, -1, 20766, 20752, 20751, -1, 20766, 20767, 20752, -1, 20766, 20753, 20768, -1, 20766, 20751, 20753, -1, 19300, 20631, 19259, -1, 20769, 20748, 20770, -1, 20769, 20749, 20747, -1, 20769, 20747, 20748, -1, 20769, 20771, 20772, -1, 20769, 20772, 20749, -1, 20773, 20774, 20775, -1, 20776, 20654, 20777, -1, 20773, 20775, 20778, -1, 20776, 20653, 20654, -1, 20773, 20779, 20774, -1, 20780, 20781, 20782, -1, 20780, 20783, 20784, -1, 20780, 20782, 20783, -1, 19273, 19224, 19226, -1, 20785, 20756, 20786, -1, 20785, 20757, 20755, -1, 20785, 20787, 20757, -1, 20785, 20755, 20756, -1, 20788, 19229, 19228, -1, 20789, 20790, 20767, -1, 20789, 20766, 20768, -1, 20789, 20767, 20766, -1, 20789, 20768, 20791, -1, 20789, 20791, 20790, -1, 20792, 20770, 20793, -1, 20792, 20769, 20770, -1, 20792, 20771, 20769, -1, 20792, 20794, 20771, -1, 20795, 20796, 20779, -1, 20795, 20797, 20796, -1, 20795, 20773, 20778, -1, 20795, 20778, 20797, -1, 19265, 20798, 19252, -1, 20795, 20779, 20773, -1, 20799, 20800, 20781, -1, 20799, 20781, 20780, -1, 20799, 20780, 20784, -1, 20801, 20786, 20802, -1, 20801, 20787, 20785, -1, 20801, 20785, 20786, -1, 20803, 20793, 20804, -1, 20803, 20792, 20793, -1, 20803, 20794, 20792, -1, 20803, 20804, 20794, -1, 20805, 20760, 20806, -1, 20805, 20807, 20760, -1, 20808, 20809, 20810, -1, 20808, 20811, 20809, -1, 20808, 20810, 20812, -1, 19298, 20695, 19270, -1, 20813, 20814, 20815, -1, 20813, 20815, 20816, -1, 20813, 20817, 20814, -1, 20813, 20816, 20817, -1, 20818, 20421, 20718, -1, 20819, 20820, 20821, -1, 20819, 20821, 20800, -1, 20819, 20800, 20799, -1, 20819, 20799, 20784, -1, 20819, 20784, 20822, -1, 20823, 19287, 20798, -1, 20819, 20822, 20820, -1, 20823, 20798, 19265, -1, 20824, 20802, 20825, -1, 20824, 20801, 20802, -1, 20824, 20826, 20787, -1, 20824, 20787, 20801, -1, 20827, 11789, 11790, -1, 20827, 11783, 11789, -1, 20828, 20736, 20829, -1, 20827, 11790, 20830, -1, 20827, 20831, 11783, -1, 20478, 20475, 20479, -1, 20828, 20735, 20736, -1, 20832, 20807, 20805, -1, 20832, 11411, 20833, -1, 20832, 20805, 20806, -1, 20832, 20806, 20834, -1, 20832, 20834, 11311, -1, 20832, 11311, 11411, -1, 20835, 20818, 20718, -1, 20832, 20833, 20807, -1, 20836, 20837, 20838, -1, 20836, 20838, 20790, -1, 20836, 20790, 20839, -1, 20840, 20841, 20842, -1, 20840, 20808, 20812, -1, 20840, 20812, 20841, -1, 20840, 20811, 20808, -1, 20843, 20825, 20844, -1, 20843, 20824, 20825, -1, 20843, 20845, 20826, -1, 20843, 20826, 20824, -1, 20500, 20733, 20471, -1, 20846, 20847, 20831, -1, 20846, 20827, 20830, -1, 20846, 20830, 20847, -1, 20846, 20831, 20827, -1, 20848, 20811, 20840, -1, 20848, 20849, 20811, -1, 20848, 20840, 20842, -1, 20850, 20837, 20836, -1, 20850, 20836, 20839, -1, 20850, 20839, 20851, -1, 19288, 19287, 20823, -1, 20852, 19229, 20788, -1, 20853, 20845, 20843, -1, 20476, 20475, 20478, -1, 20853, 20854, 20855, -1, 20853, 20855, 20845, -1, 20853, 20843, 20844, -1, 20853, 20844, 20856, -1, 20857, 20858, 20859, -1, 20857, 20859, 20860, -1, 20857, 20861, 20858, -1, 20862, 20863, 20864, -1, 20862, 20864, 20865, -1, 20866, 20754, 20867, -1, 20862, 20865, 20868, -1, 20866, 20750, 20754, -1, 20862, 20868, 20863, -1, 20869, 20849, 20848, -1, 20869, 20842, 20870, -1, 20869, 20848, 20842, -1, 20869, 20870, 20849, -1, 20871, 20837, 20850, -1, 20871, 20872, 20837, -1, 20871, 20850, 20851, -1, 20871, 20851, 20873, -1, 20874, 20853, 20856, -1, 20874, 20854, 20853, -1, 20875, 20861, 20857, -1, 20875, 20860, 20876, -1, 20875, 20857, 20860, -1, 20877, 20852, 20788, -1, 20875, 20878, 20861, -1, 20879, 20871, 20873, -1, 20879, 20873, 20880, -1, 20879, 20881, 20872, -1, 20879, 20872, 20871, -1, 20882, 20854, 20874, -1, 20882, 20856, 20883, -1, 20882, 20884, 20854, -1, 20882, 20874, 20856, -1, 20524, 20776, 20777, -1, 20885, 20875, 20876, -1, 20524, 20777, 20507, -1, 20885, 20876, 20886, -1, 19282, 19229, 20852, -1, 20885, 20887, 20888, -1, 20885, 20888, 20878, -1, 20885, 20878, 20875, -1, 20889, 20890, 20881, -1, 19282, 19281, 19229, -1, 20889, 20880, 20891, -1, 20889, 20879, 20880, -1, 19319, 19254, 19255, -1, 20889, 20881, 20879, -1, 20892, 20883, 20893, -1, 20892, 20884, 20882, -1, 20892, 20894, 20884, -1, 20892, 20882, 20883, -1, 20895, 20896, 20897, -1, 20895, 20897, 20898, -1, 20895, 20899, 20896, -1, 20900, 20889, 20891, -1, 20900, 20891, 20901, -1, 20900, 20901, 20890, -1, 20900, 20890, 20889, -1, 20902, 20903, 20904, -1, 20902, 20905, 20903, -1, 20902, 20906, 20905, -1, 20907, 11817, 20908, -1, 20907, 20908, 20909, -1, 19321, 19254, 19319, -1, 20907, 11813, 11817, -1, 20536, 20447, 20421, -1, 20907, 20909, 11813, -1, 20536, 20535, 20447, -1, 20910, 20911, 20912, -1, 20910, 11394, 20913, -1, 20910, 20912, 11295, -1, 20910, 11392, 11394, -1, 20910, 11295, 11392, -1, 20910, 20913, 20911, -1, 20914, 20887, 20885, -1, 20914, 20886, 20915, -1, 20916, 20495, 20484, -1, 20914, 20885, 20886, -1, 20914, 20917, 20887, -1, 20918, 20893, 20919, -1, 20918, 20920, 20894, -1, 20918, 20894, 20892, -1, 19290, 20921, 19285, -1, 20918, 20892, 20893, -1, 20922, 20923, 20924, -1, 20922, 20925, 20926, -1, 20922, 20926, 20927, -1, 20922, 20927, 20923, -1, 20928, 20929, 20899, -1, 20529, 11689, 11695, -1, 20928, 20895, 20898, -1, 20928, 20899, 20895, -1, 20928, 20898, 20930, -1, 20928, 20930, 20929, -1, 20931, 20904, 20923, -1, 20931, 20923, 20906, -1, 19314, 20828, 20829, -1, 20931, 20902, 20904, -1, 20931, 20906, 20902, -1, 19314, 20829, 19262, -1, 20932, 20920, 20918, -1, 20932, 20919, 20933, -1, 20932, 20918, 20919, -1, 20934, 20915, 20935, -1, 20936, 20818, 20835, -1, 20934, 20914, 20915, -1, 20934, 20935, 20917, -1, 20934, 20917, 20914, -1, 20937, 20938, 20925, -1, 20937, 20924, 20939, -1, 20937, 20922, 20924, -1, 20937, 20925, 20922, -1, 20940, 20941, 20942, -1, 20496, 20504, 20498, -1, 20940, 20942, 20943, -1, 20940, 20944, 20941, -1, 20940, 20943, 20944, -1, 20945, 20946, 20947, -1, 20945, 20948, 20946, -1, 20945, 20947, 20949, -1, 20950, 20932, 20933, -1, 20950, 20933, 20951, -1, 20950, 20952, 20920, -1, 20950, 20920, 20932, -1, 20953, 20949, 20954, -1, 20953, 20945, 20949, -1, 20953, 20948, 20945, -1, 20955, 20939, 20956, -1, 20955, 20937, 20939, -1, 20955, 20957, 20938, -1, 20513, 20556, 20473, -1, 20955, 20938, 20937, -1, 20958, 20852, 20877, -1, 20513, 20473, 20476, -1, 20959, 20960, 20961, -1, 20959, 20962, 20963, -1, 20959, 20963, 20960, -1, 20964, 20952, 20950, -1, 20964, 20951, 20965, -1, 20964, 20966, 20952, -1, 20964, 20965, 20966, -1, 20964, 20950, 20951, -1, 20967, 20953, 20954, -1, 20967, 20968, 20948, -1, 20967, 20954, 20969, -1, 20967, 20948, 20953, -1, 20970, 20936, 20835, -1, 20971, 20955, 20956, -1, 20971, 20972, 20957, -1, 20971, 20956, 20972, -1, 20971, 20957, 20955, -1, 20973, 20959, 20961, -1, 20973, 20962, 20959, -1, 20505, 20504, 20496, -1, 20973, 20961, 20974, -1, 20975, 20976, 20977, -1, 20975, 20978, 20979, -1, 20975, 20977, 20978, -1, 20975, 20979, 20976, -1, 20980, 20981, 20982, -1, 20980, 20982, 20983, -1, 20980, 20984, 20981, -1, 20985, 20969, 20986, -1, 20985, 20967, 20969, -1, 20985, 20968, 20967, -1, 20985, 20986, 20968, -1, 20987, 20988, 20989, -1, 20990, 20958, 20877, -1, 20987, 20991, 20988, -1, 20987, 20992, 20993, -1, 20987, 20993, 20966, -1, 20987, 20965, 20991, -1, 20987, 20966, 20965, -1, 20987, 20989, 20992, -1, 20994, 20962, 20973, -1, 20994, 20974, 20995, -1, 20994, 20996, 20962, -1, 20994, 20973, 20974, -1, 20537, 20867, 20535, -1, 20997, 20983, 20998, -1, 20997, 20999, 20984, -1, 20997, 20980, 20983, -1, 20537, 20866, 20867, -1, 20997, 20984, 20980, -1, 21000, 20495, 20916, -1, 21001, 21002, 21003, -1, 21001, 21003, 21004, -1, 21001, 21005, 21002, -1, 21006, 20989, 21007, -1, 21006, 21008, 20992, -1, 21006, 20992, 20989, -1, 21009, 20994, 20995, -1, 21009, 21010, 20996, -1, 21009, 20995, 21011, -1, 21009, 20996, 20994, -1, 21012, 20999, 20997, -1, 21012, 20997, 20998, -1, 21012, 21013, 20999, -1, 21014, 21004, 21015, -1, 21014, 21001, 21004, -1, 21014, 21005, 21001, -1, 21016, 21007, 21017, -1, 21016, 21006, 21007, -1, 21016, 21018, 21008, -1, 21016, 21008, 21006, -1, 21019, 21011, 21020, -1, 21019, 21009, 21011, -1, 21019, 21010, 21009, -1, 21021, 21000, 20916, -1, 21022, 21023, 20988, -1, 21022, 20988, 20991, -1, 21022, 20991, 21024, -1, 21022, 21024, 21023, -1, 21025, 21013, 21012, -1, 21025, 21012, 20998, -1, 21025, 21026, 21013, -1, 21025, 20998, 21027, -1, 21028, 21014, 21015, -1, 21028, 21029, 21005, -1, 21028, 21015, 21030, -1, 21028, 21030, 21029, -1, 21028, 21005, 21014, -1, 21031, 21016, 21017, -1, 21031, 21017, 21032, -1, 21031, 21018, 21016, -1, 21031, 21033, 21018, -1, 21034, 21035, 11408, -1, 21034, 21019, 21020, -1, 21034, 21020, 21035, -1, 21034, 21036, 21010, -1, 21034, 21010, 21019, -1, 21034, 11408, 21036, -1, 21037, 21027, 21038, -1, 21037, 21039, 21026, -1, 21037, 21025, 21027, -1, 21037, 21026, 21025, -1, 21040, 21041, 21042, -1, 21040, 21043, 21041, -1, 21040, 21042, 21044, -1, 21040, 21044, 21045, -1, 21046, 21032, 21047, -1, 21046, 21031, 21032, -1, 21046, 21033, 21031, -1, 21048, 21039, 21037, -1, 21048, 21038, 21049, -1, 21048, 21037, 21038, -1, 21048, 21049, 21039, -1, 21050, 21051, 21052, -1, 21050, 21053, 21054, -1, 21050, 21052, 21053, -1, 21055, 20936, 20970, -1, 19354, 19312, 19311, -1, 21056, 21047, 21057, -1, 11477, 11427, 20533, -1, 21056, 21058, 21033, -1, 21056, 21046, 21047, -1, 21056, 21033, 21046, -1, 21059, 21060, 21043, -1, 21059, 21043, 21040, -1, 21059, 21040, 21045, -1, 21061, 21051, 21050, -1, 21061, 21050, 21054, -1, 21062, 20958, 20990, -1, 21061, 21054, 21063, -1, 21064, 21065, 21066, -1, 21064, 21057, 21065, -1, 21064, 21066, 21058, -1, 21064, 21058, 21056, -1, 21064, 21056, 21057, -1, 21067, 21068, 21069, -1, 21067, 21069, 21060, -1, 21067, 21059, 21045, -1, 21067, 21060, 21059, -1, 21067, 21045, 21070, -1, 21071, 21061, 21063, -1, 19323, 21072, 21073, -1, 19323, 21073, 19324, -1, 21071, 21074, 21051, -1, 21071, 21063, 21075, -1, 21071, 21051, 21061, -1, 21076, 21077, 21078, -1, 21076, 21079, 21080, -1, 21076, 21080, 21077, -1, 21081, 21066, 21065, -1, 21081, 21082, 21083, -1, 21081, 21083, 21084, -1, 21081, 21084, 21066, -1, 21081, 21065, 21085, -1, 21081, 21085, 21086, -1, 21081, 21086, 21082, -1, 21087, 21075, 21088, -1, 21087, 21074, 21071, -1, 21087, 21088, 21074, -1, 21089, 19314, 19262, -1, 21087, 21071, 21075, -1, 21090, 18368, 21068, -1, 21090, 21091, 18368, -1, 21090, 21067, 21070, -1, 21089, 19262, 19263, -1, 21090, 21068, 21067, -1, 21090, 21070, 21091, -1, 21092, 21093, 21094, -1, 21092, 21094, 21095, -1, 21092, 21096, 21093, -1, 21097, 21098, 21099, -1, 21097, 21100, 21101, -1, 21097, 21101, 21098, -1, 21102, 21078, 21103, -1, 21102, 21103, 21104, -1, 21102, 21076, 21078, -1, 21102, 21079, 21076, -1, 21102, 21104, 21079, -1, 21105, 21096, 21092, -1, 21105, 11430, 21106, -1, 21105, 21095, 11341, -1, 21105, 11341, 11430, -1, 21105, 21106, 21096, -1, 21105, 21092, 21095, -1, 21107, 21083, 21082, -1, 19363, 19362, 20921, -1, 21107, 21108, 21083, -1, 19363, 20921, 19290, -1, 21107, 21082, 21109, -1, 21110, 21099, 21111, -1, 21112, 21000, 21021, -1, 21110, 21113, 21100, -1, 21110, 21097, 21099, -1, 21110, 21100, 21097, -1, 21114, 21111, 21115, -1, 21114, 21110, 21111, -1, 21114, 21113, 21110, -1, 21116, 21117, 21108, -1, 21116, 21107, 21109, -1, 21116, 21108, 21107, -1, 21116, 21109, 21118, -1, 21119, 21085, 18376, -1, 21119, 18376, 18378, -1, 21119, 21086, 21085, -1, 11338, 11345, 21120, -1, 21119, 18378, 21086, -1, 21121, 18364, 18363, -1, 21121, 18363, 18401, -1, 21121, 18401, 18403, -1, 21121, 18403, 21122, -1, 21121, 21122, 18364, -1, 21123, 21124, 21113, -1, 21123, 21115, 18365, -1, 21123, 21114, 21115, -1, 21123, 18365, 21124, -1, 21125, 19342, 19320, -1, 21123, 21113, 21114, -1, 21126, 21118, 21127, -1, 11475, 11477, 20533, -1, 21126, 21116, 21118, -1, 21126, 21117, 21116, -1, 21128, 18377, 18387, -1, 19356, 19312, 19354, -1, 21128, 18387, 18386, -1, 21128, 18386, 21129, -1, 21128, 21129, 21130, -1, 21131, 21127, 21132, -1, 21131, 21126, 21127, -1, 19315, 19314, 21089, -1, 21131, 21117, 21126, -1, 21131, 21133, 21117, -1, 21134, 21135, 21136, -1, 21134, 21136, 21137, -1, 21134, 21138, 21135, -1, 21139, 18375, 18377, -1, 21139, 21128, 21130, -1, 21139, 18377, 21128, -1, 21140, 21132, 21141, -1, 20557, 21112, 21021, -1, 21140, 21142, 21133, -1, 21140, 21131, 21132, -1, 21140, 21133, 21131, -1, 21143, 18436, 18435, -1, 21143, 18363, 18436, -1, 21143, 18401, 18363, -1, 21143, 18435, 18401, -1, 21144, 21138, 21134, -1, 21144, 21137, 18458, -1, 21144, 21134, 21137, -1, 19380, 21072, 19323, -1, 21145, 20489, 20488, -1, 19380, 19384, 21072, -1, 21146, 21141, 18496, -1, 21145, 20488, 21147, -1, 21146, 21148, 21142, -1, 21146, 21142, 21140, -1, 21146, 21140, 21141, -1, 21149, 21150, 21151, -1, 21149, 21151, 18375, -1, 21149, 21130, 21152, -1, 21149, 21139, 21130, -1, 21149, 18375, 21139, -1, 21153, 21138, 21144, -1, 21153, 18483, 21138, -1, 21153, 21144, 18458, -1, 21153, 18458, 18457, -1, 21154, 21155, 21156, -1, 21154, 21156, 21148, -1, 21154, 21148, 21146, -1, 21154, 21146, 18496, -1, 21157, 18518, 21150, -1, 21157, 21150, 21149, -1, 21157, 21149, 21152, -1, 21157, 21152, 18519, -1, 21157, 18519, 18518, -1, 21158, 18449, 21159, -1, 21158, 18402, 18449, -1, 21158, 18476, 18402, -1, 21160, 21153, 18457, -1, 21160, 18457, 18484, -1, 21160, 18483, 21153, -1, 21160, 18484, 18483, -1, 21161, 18434, 18494, -1, 21161, 18494, 18510, -1, 21161, 18510, 18459, -1, 20546, 21055, 20970, -1, 19375, 20990, 19362, -1, 21161, 18459, 18434, -1, 20546, 20970, 20527, -1, 19375, 21062, 20990, -1, 21162, 21154, 18496, -1, 21162, 18496, 18500, -1, 21162, 21155, 21154, -1, 21163, 18476, 21158, -1, 21163, 21159, 21164, -1, 20584, 21055, 20546, -1, 21163, 21158, 21159, -1, 21165, 21166, 21155, -1, 21165, 18500, 21167, -1, 21165, 21155, 21162, -1, 21165, 21162, 18500, -1, 11335, 11338, 21120, -1, 21168, 18476, 21163, -1, 21168, 21164, 21169, -1, 21168, 18474, 18476, -1, 21168, 21163, 21164, -1, 21170, 18507, 21166, -1, 21170, 21167, 21171, -1, 21170, 21165, 21167, -1, 21170, 21166, 21165, -1, 20560, 20512, 20514, -1, 21172, 18537, 18565, -1, 21172, 18532, 18537, -1, 21172, 18567, 21173, -1, 21172, 21173, 18532, -1, 21172, 18565, 18567, -1, 21174, 21168, 21169, -1, 21174, 21169, 18531, -1, 21174, 18474, 21168, -1, 21174, 18531, 18533, -1, 21175, 20518, 20517, -1, 21174, 18533, 18474, -1, 21176, 18507, 21170, -1, 21176, 21171, 21177, -1, 21176, 21170, 21171, -1, 21178, 18550, 21179, -1, 21178, 21179, 18562, -1, 21178, 18562, 18561, -1, 21178, 18561, 21180, -1, 21181, 21120, 19344, -1, 21181, 19344, 19343, -1, 20552, 21182, 20537, -1, 21181, 11335, 21120, -1, 21183, 21177, 21184, -1, 21183, 21176, 21177, -1, 21183, 18534, 18507, -1, 21183, 18507, 21176, -1, 21185, 18550, 21178, -1, 21186, 19342, 21125, -1, 21185, 21180, 21187, -1, 21185, 21178, 21180, -1, 21188, 18537, 18591, -1, 21188, 18593, 18565, -1, 21188, 18565, 18537, -1, 21188, 18591, 18593, -1, 21189, 18534, 21183, -1, 21189, 21184, 21190, -1, 21189, 21191, 18534, -1, 21189, 21183, 21184, -1, 21192, 21193, 18549, -1, 20580, 21112, 20557, -1, 21192, 21185, 21187, -1, 21192, 18549, 18550, -1, 21192, 21187, 21194, -1, 21192, 18550, 21185, -1, 21195, 21191, 21189, -1, 21195, 21190, 11388, -1, 21195, 11388, 11474, -1, 21196, 21186, 21125, -1, 21195, 18580, 21191, -1, 21195, 21189, 21190, -1, 21195, 11474, 18580, -1, 21197, 21193, 21192, -1, 21197, 21192, 21194, -1, 21197, 21198, 21193, -1, 21199, 21197, 21194, -1, 21200, 21182, 20552, -1, 21199, 21201, 18659, -1, 21200, 20570, 21182, -1, 21199, 21194, 21201, -1, 21199, 21198, 21197, -1, 21199, 18659, 21198, -1, 21202, 18566, 18587, -1, 21202, 18587, 21203, -1, 21202, 18585, 18566, -1, 21204, 18590, 18592, -1, 21204, 18592, 18607, -1, 21204, 18610, 18590, -1, 21204, 18607, 18610, -1, 21205, 21202, 21203, -1, 21206, 21147, 21207, -1, 21206, 21145, 21147, -1, 21205, 21203, 21208, -1, 21205, 18585, 21202, -1, 11332, 11335, 21181, -1, 21209, 21205, 21208, -1, 21209, 18585, 21205, -1, 21209, 18600, 18585, -1, 21209, 21208, 21210, -1, 21211, 18600, 21209, -1, 21211, 18617, 18619, -1, 21211, 21210, 18617, -1, 21211, 21209, 21210, -1, 21212, 19323, 21213, -1, 21211, 18619, 18600, -1, 21212, 19380, 19323, -1, 21214, 18659, 21201, -1, 21214, 21201, 18640, -1, 21215, 18657, 21216, -1, 21215, 21216, 11461, -1, 21215, 11461, 11496, -1, 21215, 18658, 18657, -1, 21215, 18635, 18658, -1, 21215, 11496, 18635, -1, 21217, 18659, 21214, -1, 21217, 21214, 18640, -1, 21217, 18640, 18639, -1, 21217, 18657, 18659, -1, 21217, 18639, 18657, -1, 21218, 18650, 18683, -1, 21218, 18678, 18650, -1, 21218, 18683, 21219, -1, 21220, 18678, 21218, -1, 20568, 20570, 21200, -1, 21220, 21219, 21221, -1, 21220, 21218, 21219, -1, 21222, 18689, 18678, -1, 21222, 18678, 21220, -1, 21222, 21221, 21223, -1, 21224, 20518, 21175, -1, 19326, 19413, 19327, -1, 21222, 21220, 21221, -1, 21225, 18708, 18710, -1, 21225, 18689, 21222, -1, 21225, 21223, 18708, -1, 21225, 21222, 21223, -1, 21225, 18710, 18689, -1, 21226, 21224, 21175, -1, 20566, 20565, 20518, -1, 20566, 20518, 21224, -1, 20602, 20541, 20542, -1, 21227, 19351, 19339, -1, 20604, 20541, 20602, -1, 21228, 21186, 21196, -1, 20569, 21229, 20571, -1, 19383, 21228, 21196, -1, 21230, 19334, 19333, -1, 20598, 21206, 21207, -1, 20598, 21207, 20550, -1, 21230, 19333, 21231, -1, 19369, 19355, 19359, -1, 19369, 19357, 19355, -1, 19419, 19357, 19369, -1, 21232, 21212, 21213, -1, 21232, 21213, 21233, -1, 21234, 19349, 19348, -1, 21235, 21224, 21226, -1, 19374, 21236, 19375, -1, 19414, 19413, 19326, -1, 21237, 21235, 21226, -1, 21238, 19351, 21227, -1, 21239, 19388, 21236, -1, 21239, 21236, 19374, -1, 21240, 21238, 21227, -1, 19423, 21228, 19383, -1, 19389, 19388, 21239, -1, 21241, 21230, 21231, -1, 21241, 21231, 21242, -1, 21243, 19349, 21234, -1, 19452, 21233, 19406, -1, 19452, 21232, 21233, -1, 20640, 20594, 20593, -1, 21244, 21235, 21237, -1, 20606, 21245, 21246, -1, 20606, 21246, 20607, -1, 21247, 21243, 21234, -1, 19470, 11759, 11846, -1, 21248, 20550, 20549, -1, 11853, 19470, 11846, -1, 21248, 20598, 20550, -1, 21249, 21238, 21240, -1, 19392, 19349, 21243, -1, 20647, 21244, 21237, -1, 20648, 20647, 21229, -1, 20648, 21229, 20569, -1, 19390, 21250, 19386, -1, 11456, 11372, 21251, -1, 21252, 20624, 20603, -1, 19437, 21249, 21240, -1, 20639, 20594, 20640, -1, 20599, 20598, 21248, -1, 19459, 21241, 21242, -1, 19459, 21242, 19397, -1, 20667, 20666, 21245, -1, 21253, 21243, 21247, -1, 20667, 21245, 20606, -1, 21254, 21253, 21247, -1, 20660, 21244, 20647, -1, 21255, 19397, 19377, -1, 21255, 19459, 19397, -1, 11455, 11456, 21251, -1, 19438, 21249, 19437, -1, 11310, 11319, 19477, -1, 21256, 21251, 20627, -1, 21256, 20627, 20625, -1, 21256, 11455, 21251, -1, 21257, 20624, 21252, -1, 21258, 21257, 21252, -1, 19456, 19434, 19432, -1, 11360, 11455, 21256, -1, 21259, 20667, 20606, -1, 21260, 21253, 21254, -1, 21259, 20606, 21261, -1, 11309, 11310, 19477, -1, 19435, 19434, 19456, -1, 20609, 20688, 20610, -1, 19515, 21260, 21254, -1, 19511, 19515, 21250, -1, 19511, 21250, 19390, -1, 21262, 19412, 19411, -1, 21262, 19411, 21263, -1, 21264, 19459, 21255, -1, 21265, 20637, 20622, -1, 19498, 19440, 19495, -1, 21266, 21257, 21258, -1, 19498, 19441, 19440, -1, 20665, 21266, 21258, -1, 19460, 19459, 21264, -1, 21267, 20617, 21268, -1, 21267, 20618, 20617, -1, 20656, 20642, 20644, -1, 20656, 20641, 20642, -1, 20694, 20641, 20656, -1, 19533, 21260, 19515, -1, 21269, 21259, 21261, -1, 21269, 21261, 21270, -1, 21271, 20634, 20633, -1, 21272, 21263, 21273, -1, 21272, 21262, 21263, -1, 20659, 21274, 20660, -1, 20689, 20688, 20609, -1, 21275, 20637, 21265, -1, 21276, 21274, 20659, -1, 21276, 20674, 21274, -1, 21277, 21275, 21265, -1, 20699, 21266, 20665, -1, 20675, 20674, 21276, -1, 21278, 21268, 21279, -1, 21278, 21267, 21268, -1, 21280, 20634, 21271, -1, 19548, 19468, 19436, -1, 20721, 21270, 20686, -1, 20721, 21269, 21270, -1, 19548, 19550, 19468, -1, 19523, 21273, 19488, -1, 19523, 21272, 21273, -1, 19556, 19506, 19482, -1, 21281, 21280, 21271, -1, 21282, 19485, 19466, -1, 21282, 19466, 21283, -1, 20740, 11749, 11756, -1, 19526, 19496, 19500, -1, 19526, 19497, 19496, -1, 11760, 20740, 11756, -1, 21284, 21275, 21277, -1, 20677, 20634, 21280, -1, 19574, 19497, 19526, -1, 19534, 19517, 19533, -1, 20671, 21285, 20672, -1, 20707, 21284, 21277, -1, 21286, 19492, 19491, -1, 19555, 19506, 19556, -1, 19518, 19517, 19534, -1, 20726, 21279, 20681, -1, 20726, 21278, 21279, -1, 21287, 21280, 21281, -1, 19568, 11819, 11867, -1, 21288, 21287, 21281, -1, 21289, 21283, 21290, -1, 21289, 21282, 21283, -1, 21291, 20681, 20663, -1, 21291, 20726, 20681, -1, 20706, 21284, 20707, -1, 11433, 11347, 20743, -1, 21292, 19492, 21286, -1, 11288, 11290, 19570, -1, 21293, 21292, 21286, -1, 20724, 20710, 20704, -1, 21294, 21287, 21288, -1, 19608, 19554, 19553, -1, 11431, 11433, 20743, -1, 20708, 20710, 20724, -1, 20779, 21294, 21288, -1, 19600, 21289, 21290, -1, 19600, 21290, 19543, -1, 20774, 20779, 21285, -1, 19545, 19492, 21292, -1, 20774, 21285, 20671, -1, 11285, 11288, 19570, -1, 21295, 20691, 20690, -1, 21295, 20690, 21296, -1, 21297, 20726, 21291, -1, 21298, 19600, 19543, -1, 21298, 19543, 19529, -1, 21299, 21292, 21293, -1, 21300, 21299, 21293, -1, 20763, 20713, 20764, -1, 20763, 20712, 20713, -1, 19609, 19554, 19608, -1, 20727, 20726, 21297, -1, 21301, 19561, 19521, -1, 21301, 19521, 21302, -1, 20796, 21294, 20779, -1, 19612, 21303, 19589, -1, 21304, 21295, 21296, -1, 21304, 21296, 21305, -1, 21306, 19598, 19582, -1, 21307, 21303, 19612, -1, 21308, 19600, 21298, -1, 21309, 21299, 21300, -1, 19644, 21309, 21300, -1, 21310, 19578, 21311, -1, 21310, 19579, 19578, -1, 19641, 19644, 19558, -1, 19641, 19558, 19561, -1, 19606, 21303, 21307, -1, 19606, 19608, 21303, -1, 21312, 21301, 21302, -1, 21312, 21302, 21313, -1, 19601, 19600, 21308, -1, 20810, 20809, 20737, -1, 20810, 20737, 20709, -1, 20787, 21304, 21305, -1, 20787, 21305, 20757, -1, 19653, 19585, 19567, -1, 19652, 19585, 19653, -1, 21314, 19598, 21306, -1, 20817, 20770, 20748, -1, 21315, 21314, 21306, -1, 21316, 20753, 20732, -1, 19677, 21309, 19644, -1, 21316, 20732, 21317, -1, 20790, 20765, 20767, -1, 20790, 20762, 20765, -1, 20838, 20762, 20790, -1, 21318, 21311, 21319, -1, 21318, 21310, 21311, -1, 21320, 21316, 21317, -1, 20797, 20782, 20796, -1, 21321, 21312, 21313, -1, 21321, 21313, 21322, -1, 21323, 20760, 20759, -1, 20816, 20770, 20817, -1, 20783, 20782, 20797, -1, 21324, 19622, 19614, -1, 19658, 11860, 11892, -1, 20831, 11778, 11783, -1, 21325, 21314, 21315, -1, 21326, 21316, 21320, -1, 19693, 19607, 19606, -1, 19693, 19696, 19607, -1, 19670, 21325, 21315, -1, 19668, 21319, 19639, -1, 19668, 21318, 21319, -1, 20804, 21326, 21320, -1, 21327, 19622, 21324, -1, 21328, 20760, 21323, -1, 19712, 21321, 21322, -1, 19712, 19636, 19650, -1, 19712, 21322, 19636, -1, 11413, 11325, 20833, -1, 21329, 21328, 21323, -1, 21330, 21327, 21324, -1, 19715, 21321, 19712, -1, 19685, 21325, 19670, -1, 20865, 20815, 20814, -1, 11664, 11281, 19660, -1, 19688, 19620, 19689, -1, 19688, 19632, 19620, -1, 20858, 21326, 20804, -1, 20806, 20760, 21328, -1, 19678, 19661, 19677, -1, 11411, 11413, 20833, -1, 19673, 19672, 19652, -1, 21331, 20804, 20793, -1, 21331, 20858, 20804, -1, 21332, 21327, 21330, -1, 21333, 21328, 21329, -1, 21334, 21333, 21329, -1, 19662, 19661, 19678, -1, 19683, 21332, 21330, -1, 20864, 20815, 20865, -1, 21335, 19654, 21336, -1, 21335, 19655, 19654, -1, 21337, 20822, 20784, -1, 21337, 20784, 21338, -1, 21339, 11902, 11873, -1, 21339, 19657, 11902, -1, 20870, 21340, 20849, -1, 21341, 20856, 20844, -1, 19735, 21332, 19683, -1, 21342, 21340, 20870, -1, 21343, 20858, 21331, -1, 21344, 21335, 21336, -1, 21344, 21336, 21345, -1, 21346, 21333, 21334, -1, 21347, 19683, 19664, -1, 20899, 21346, 21334, -1, 21347, 19735, 19683, -1, 21348, 20842, 20841, -1, 19759, 19657, 21339, -1, 21348, 20841, 21349, -1, 20896, 20820, 20822, -1, 20896, 20899, 20820, -1, 20868, 20865, 21340, -1, 20868, 21340, 21342, -1, 21350, 21337, 21338, -1, 21350, 21338, 21351, -1, 19729, 19691, 19730, -1, 19729, 19690, 19691, -1, 21352, 19722, 19705, -1, 20859, 20858, 21343, -1, 19740, 21353, 19721, -1, 20905, 20847, 20830, -1, 20906, 20847, 20905, -1, 21354, 20856, 21341, -1, 19756, 19759, 21339, -1, 21355, 21354, 21341, -1, 20929, 21346, 20899, -1, 19758, 21345, 19759, -1, 19758, 21344, 21345, -1, 21356, 21353, 19740, -1, 21357, 19735, 21347, -1, 21358, 21349, 21359, -1, 21358, 21348, 21349, -1, 21360, 19722, 21352, -1, 19732, 21353, 21356, -1, 19732, 19730, 21353, -1, 21361, 21351, 21362, -1, 21361, 21350, 21351, -1, 21363, 21360, 21352, -1, 19736, 19735, 21357, -1, 21364, 20880, 20873, -1, 20909, 11801, 11813, -1, 21365, 21354, 21355, -1, 21366, 19724, 19709, -1, 21367, 19724, 21366, -1, 19795, 11911, 11921, -1, 19795, 11886, 11911, -1, 20947, 20946, 20863, -1, 20947, 20863, 20868, -1, 20925, 21365, 21355, -1, 21368, 21360, 21363, -1, 20920, 21358, 21359, -1, 20920, 21359, 20894, -1, 21369, 20880, 21364, -1, 20960, 21362, 20890, -1, 20960, 21361, 21362, -1, 20960, 20890, 20901, -1, 19775, 21368, 21363, -1, 21370, 21369, 21364, -1, 20963, 21361, 20960, -1, 11650, 11652, 19798, -1, 21371, 19769, 19748, -1, 20938, 21365, 20925, -1, 19820, 19733, 19732, -1, 19820, 19824, 19733, -1, 11394, 11300, 20913, -1, 21372, 21367, 21366, -1, 20943, 20876, 20944, -1, 20943, 20886, 20876, -1, 19804, 19781, 19780, -1, 20930, 20911, 20929, -1, 19789, 21373, 19790, -1, 20923, 20927, 20906, -1, 19812, 21368, 19775, -1, 11647, 11650, 19798, -1, 21374, 21369, 21370, -1, 21375, 21373, 19789, -1, 21375, 21376, 21377, -1, 21375, 21377, 21373, -1, 21378, 19769, 21371, -1, 20912, 20911, 20930, -1, 21379, 21367, 21372, -1, 20935, 21374, 21370, -1, 21380, 21378, 21371, -1, 21381, 20904, 20903, -1, 21381, 20903, 21382, -1, 19831, 19781, 19804, -1, 11644, 11647, 19799, -1, 21383, 19783, 19753, -1, 21383, 19753, 21384, -1, 21385, 20908, 11817, -1, 21385, 11817, 11821, -1, 19806, 19805, 21386, -1, 19806, 21386, 21367, -1, 19806, 21367, 21379, -1, 21387, 21376, 21375, -1, 21387, 19885, 21376, -1, 21388, 21387, 21375, -1, 20981, 21374, 20935, -1, 21389, 21378, 21380, -1, 21390, 21382, 21391, -1, 21390, 21381, 21382, -1, 19818, 21389, 21380, -1, 21392, 21379, 21372, -1, 21393, 20935, 20915, -1, 21393, 20981, 20935, -1, 21392, 21372, 21394, -1, 21002, 20908, 21385, -1, 21395, 21383, 21384, -1, 21395, 21384, 21396, -1, 20977, 20942, 20941, -1, 20977, 20941, 20978, -1, 21397, 20969, 20954, -1, 20986, 21398, 20968, -1, 21399, 21387, 21388, -1, 21003, 21002, 21385, -1, 21400, 21399, 21388, -1, 19878, 21389, 19818, -1, 21005, 21391, 21002, -1, 21005, 21390, 21391, -1, 21401, 21398, 20986, -1, 21402, 21392, 21394, -1, 21402, 21394, 21403, -1, 21404, 20981, 21393, -1, 21405, 19878, 19818, -1, 21405, 19818, 19802, -1, 21406, 20969, 21397, -1, 19888, 21396, 19850, -1, 19888, 21395, 21396, -1, 20979, 20978, 21398, -1, 20979, 21398, 21401, -1, 19883, 19885, 21387, -1, 21407, 21406, 21397, -1, 21408, 19846, 19833, -1, 20982, 20981, 21404, -1, 19895, 11915, 11934, -1, 21409, 21399, 21400, -1, 19869, 19851, 19847, -1, 21410, 20972, 20956, -1, 21411, 20972, 21410, -1, 19917, 21409, 21400, -1, 19852, 19851, 19869, -1, 21412, 21406, 21407, -1, 19905, 21402, 21403, -1, 19905, 21403, 19886, -1, 21413, 19846, 21408, -1, 21414, 19878, 21405, -1, 21018, 21412, 21407, -1, 21415, 21413, 21408, -1, 19855, 19836, 19835, -1, 11399, 11306, 21036, -1, 21416, 21011, 20995, -1, 21417, 21409, 19917, -1, 11634, 11637, 19899, -1, 21053, 21052, 20976, -1, 21053, 20976, 20979, -1, 21418, 21411, 21410, -1, 19879, 19878, 21414, -1, 21043, 21023, 21024, -1, 21030, 21419, 21029, -1, 21033, 21412, 21018, -1, 21420, 21413, 21415, -1, 11408, 11399, 21036, -1, 11633, 11634, 19899, -1, 21421, 21422, 21423, -1, 21421, 21423, 21419, -1, 21421, 21419, 21030, -1, 19914, 21420, 21415, -1, 21424, 21011, 21416, -1, 21425, 21411, 21418, -1, 21426, 19835, 21427, -1, 21426, 19855, 19835, -1, 21428, 21424, 21416, -1, 21060, 21023, 21043, -1, 11315, 11408, 21035, -1, 21429, 20998, 21430, -1, 21429, 21027, 20998, -1, 19916, 21417, 19917, -1, 19949, 21417, 19916, -1, 21042, 21411, 21425, -1, 21431, 19875, 19874, -1, 21042, 21041, 21432, -1, 21042, 21432, 21411, -1, 19953, 19952, 19889, -1, 21433, 21101, 21422, -1, 19953, 19889, 19853, -1, 21433, 21422, 21421, -1, 19943, 21420, 19914, -1, 21434, 21433, 21421, -1, 19931, 19925, 19932, -1, 21435, 21426, 21427, -1, 21435, 21427, 21436, -1, 21437, 21424, 21428, -1, 21049, 21437, 21428, -1, 19926, 19925, 19931, -1, 21438, 21418, 21439, -1, 21438, 21425, 21418, -1, 21440, 19875, 21431, -1, 19957, 19920, 19919, -1, 19957, 19919, 19941, -1, 21441, 21430, 21442, -1, 21441, 21429, 21430, -1, 19937, 19875, 21440, -1, 19937, 19940, 21443, -1, 19937, 21443, 19875, -1, 21444, 21433, 21434, -1, 21445, 19909, 19897, -1, 19929, 20003, 19927, -1, 21446, 21436, 19909, -1, 21447, 21444, 21434, -1, 21446, 21435, 21436, -1, 21093, 21437, 21049, -1, 21448, 21439, 21449, -1, 21448, 21438, 21439, -1, 21450, 21431, 21451, -1, 21450, 21440, 21431, -1, 21452, 21049, 21038, -1, 21452, 21093, 21049, -1, 21104, 21442, 21079, -1, 21104, 21441, 21442, -1, 21098, 21101, 21433, -1, 21453, 21075, 21063, -1, 47, 21454, 21455, -1, 47, 21455, 30, -1, 21456, 21444, 21447, -1, 21088, 21080, 21074, -1, 20033, 11947, 11958, -1, 20033, 11938, 11947, -1, 21457, 21456, 21447, -1, 21077, 21080, 21088, -1, 20009, 19964, 19965, -1, 21458, 21450, 21451, -1, 21458, 21451, 21459, -1, 21113, 21449, 21100, -1, 21113, 21448, 21449, -1, 21460, 21075, 21453, -1, 11950, 20033, 11958, -1, 21461, 21446, 19909, -1, 21462, 21093, 21452, -1, 21461, 19909, 21445, -1, 21463, 21460, 21453, -1, 20001, 20003, 19929, -1, 54, 21454, 47, -1, 54, 21457, 21454, -1, 11608, 11610, 21464, -1, 21465, 21456, 21457, -1, 21466, 19986, 19969, -1, 11418, 11328, 21106, -1, 20008, 19964, 20009, -1, 21467, 21446, 21461, -1, 21467, 19983, 21446, -1, 21094, 21093, 21462, -1, 21468, 21460, 21463, -1, 19984, 19983, 21467, -1, 20029, 21458, 21459, -1, 20029, 21459, 20004, -1, 11430, 11418, 21106, -1, 11607, 11608, 21464, -1, 21117, 21468, 21463, -1, 21469, 21464, 19987, -1, 21469, 11607, 21464, -1, 21469, 19987, 20006, -1, 18383, 19986, 21466, -1, 69, 21457, 54, -1, 69, 21465, 21457, -1, 18366, 21465, 69, -1, 18394, 19980, 18392, -1, 18384, 18383, 21466, -1, 18369, 18368, 21091, -1, 11602, 11607, 21469, -1, 18407, 20011, 19972, -1, 18407, 19972, 18408, -1, 21136, 21103, 21078, -1, 21136, 21135, 21103, -1, 21133, 21468, 21117, -1, 20034, 20033, 11950, -1, 18365, 18364, 21124, -1, 11409, 822, 821, -1, 14071, 822, 11409, -1, 14072, 822, 14071, -1, 14074, 822, 14072, -1, 14075, 822, 14074, -1, 14078, 822, 14075, -1, 822, 14963, 911, -1, 14078, 14963, 822, -1, 14963, 578, 911, -1, 14963, 14965, 578, -1, 11013, 388, 489, -1, 11013, 11012, 388, -1, 388, 11011, 334, -1, 11012, 11011, 388, -1, 11011, 335, 334, -1, 11011, 11029, 335, -1, 11029, 319, 335, -1, 11029, 11023, 319, -1, 319, 11007, 320, -1, 11023, 11007, 319, -1, 320, 11009, 258, -1, 11007, 11009, 320, -1, 214, 11034, 151, -1, 11037, 11034, 214, -1, 151, 11036, 152, -1, 11034, 11036, 151, -1, 152, 11053, 1851, -1, 11036, 11053, 152, -1, 1851, 11047, 87, -1, 11053, 11047, 1851, -1, 87, 11031, 88, -1, 11047, 11031, 87, -1, 88, 11033, 1836, -1, 11031, 11033, 88, -1, 1810, 10950, 1811, -1, 10953, 10950, 1810, -1, 1811, 10952, 1736, -1, 10950, 10952, 1811, -1, 1736, 10969, 1737, -1, 10952, 10969, 1736, -1, 1737, 10963, 1734, -1, 10969, 10963, 1737, -1, 1734, 10947, 1740, -1, 10963, 10947, 1734, -1, 1740, 10949, 1713, -1, 10947, 10949, 1740, -1, 1689, 10974, 1687, -1, 10977, 10974, 1689, -1, 1687, 10976, 3280, -1, 10974, 10976, 1687, -1, 3280, 10993, 3281, -1, 10976, 10993, 3280, -1, 3281, 10987, 3277, -1, 10993, 10987, 3281, -1, 3277, 10971, 1588, -1, 10987, 10971, 3277, -1, 1588, 10973, 1563, -1, 10971, 10973, 1588, -1, 1556, 11000, 1451, -1, 10998, 11000, 1556, -1, 1452, 11895, 3216, -1, 1452, 16979, 11895, -1, 1452, 16995, 16979, -1, 1451, 11006, 1452, -1, 11000, 11006, 1451, -1, 1452, 16998, 16995, -1, 11006, 16999, 1452, -1, 1452, 16999, 16998, -1, 2015, 17684, 2028, -1, 17680, 17684, 2015, -1, 2028, 17678, 910, -1, 17684, 17678, 2028, -1, 910, 11423, 985, -1, 910, 17034, 11423, -1, 910, 17032, 17034, -1, 17678, 17035, 910, -1, 910, 17033, 17032, -1, 17035, 17037, 910, -1, 910, 17037, 17033, -1, 387, 17676, 505, -1, 17677, 17676, 387, -1, 505, 17681, 2004, -1, 17676, 17681, 505, -1, 2004, 17680, 2015, -1, 17681, 17680, 2004, -1, 1921, 11259, 1930, -1, 11256, 11259, 1921, -1, 1930, 11258, 318, -1, 11259, 11258, 1930, -1, 318, 11263, 333, -1, 11258, 11263, 318, -1, 150, 11246, 215, -1, 11247, 11246, 150, -1, 215, 11250, 1912, -1, 11246, 11250, 215, -1, 1912, 11256, 1921, -1, 11250, 11256, 1912, -1, 1824, 11208, 1837, -1, 11204, 11208, 1824, -1, 1837, 11202, 86, -1, 11208, 11202, 1837, -1, 86, 11201, 93, -1, 11202, 11201, 86, -1, 1738, 11198, 1812, -1, 11199, 11198, 1738, -1, 1812, 11205, 1813, -1, 11198, 11205, 1812, -1, 1813, 11204, 1824, -1, 11205, 11204, 1813, -1, 1714, 11177, 1720, -1, 11174, 11177, 1714, -1, 1720, 11176, 1742, -1, 11177, 11176, 1720, -1, 1742, 11181, 1735, -1, 11176, 11181, 1742, -1, 3293, 11164, 1688, -1, 11165, 11164, 3293, -1, 1688, 11168, 1690, -1, 11164, 11168, 1688, -1, 1690, 11174, 1714, -1, 11168, 11174, 1690, -1, 11228, 1574, 1561, -1, 11228, 11232, 1574, -1, 1574, 11226, 1587, -1, 11232, 11226, 1574, -1, 11226, 3279, 1587, -1, 11226, 11225, 3279, -1, 11878, 3237, 3238, -1, 17713, 3237, 11878, -1, 17715, 3237, 17713, -1, 17716, 3237, 17715, -1, 17720, 3237, 17716, -1, 17720, 11223, 3237, -1, 11223, 11222, 3237, -1, 11222, 1557, 3237, -1, 11222, 11229, 1557, -1, 11229, 1561, 1557, -1, 11229, 11228, 1561, -1, 11381, 19245, 11374, -1, 14033, 19245, 11381, -1, 14034, 19245, 14033, -1, 14036, 19245, 14034, -1, 14037, 19245, 14036, -1, 10946, 19245, 14037, -1, 19245, 10938, 19232, -1, 10946, 10938, 19245, -1, 10938, 19215, 19232, -1, 10938, 10940, 19215, -1, 10917, 19161, 19182, -1, 10917, 10916, 19161, -1, 19161, 10915, 19141, -1, 10916, 10915, 19161, -1, 10915, 19120, 19141, -1, 10915, 10933, 19120, -1, 10933, 19097, 19120, -1, 10933, 10927, 19097, -1, 19097, 10911, 19084, -1, 10927, 10911, 19097, -1, 19084, 10913, 19063, -1, 10911, 10913, 19084, -1, 19026, 10890, 19013, -1, 10893, 10890, 19026, -1, 19013, 10892, 18981, -1, 10890, 10892, 19013, -1, 18981, 10909, 18982, -1, 10892, 10909, 18981, -1, 18982, 10903, 18972, -1, 10909, 10903, 18982, -1, 18972, 10887, 18957, -1, 10903, 10887, 18972, -1, 18957, 10889, 18943, -1, 10887, 10889, 18957, -1, 18909, 10842, 18901, -1, 10845, 10842, 18909, -1, 18901, 10844, 18887, -1, 10842, 10844, 18901, -1, 18887, 10861, 18888, -1, 10844, 10861, 18887, -1, 18888, 10855, 18864, -1, 10861, 10855, 18888, -1, 18864, 10839, 18850, -1, 10855, 10839, 18864, -1, 18850, 10841, 18706, -1, 10839, 10841, 18850, -1, 18707, 10866, 18822, -1, 10869, 10866, 18707, -1, 18822, 10868, 18813, -1, 10866, 10868, 18822, -1, 18813, 10885, 18799, -1, 10868, 10885, 18813, -1, 18799, 10879, 18791, -1, 10885, 10879, 18799, -1, 18791, 10863, 18785, -1, 10879, 10863, 18791, -1, 18785, 10865, 18571, -1, 10863, 10865, 18785, -1, 18572, 14955, 18740, -1, 14953, 14955, 18572, -1, 18491, 11807, 11806, -1, 18491, 16942, 11807, -1, 18491, 16958, 16942, -1, 18740, 14961, 18491, -1, 14955, 14961, 18740, -1, 18491, 16961, 16958, -1, 14961, 16962, 18491, -1, 18491, 16962, 16961, -1, 19213, 10792, 19214, -1, 10788, 10792, 19213, -1, 19214, 10786, 19231, -1, 10792, 10786, 19214, -1, 19231, 11365, 11358, -1, 19231, 14011, 11365, -1, 19231, 14009, 14011, -1, 10786, 10785, 19231, -1, 19231, 14010, 14009, -1, 10785, 14013, 19231, -1, 19231, 14013, 14010, -1, 19142, 10782, 19164, -1, 10783, 10782, 19142, -1, 19164, 10789, 19183, -1, 10782, 10789, 19164, -1, 19183, 10788, 19213, -1, 10789, 10788, 19183, -1, 19064, 10819, 19065, -1, 10816, 10819, 19064, -1, 19065, 10818, 19085, -1, 10819, 10818, 19065, -1, 19085, 10823, 19098, -1, 10818, 10823, 19085, -1, 18983, 10806, 19014, -1, 10807, 10806, 18983, -1, 19014, 10810, 19028, -1, 10806, 10810, 19014, -1, 19028, 10816, 19064, -1, 10810, 10816, 19028, -1, 18940, 10734, 18941, -1, 10730, 10734, 18940, -1, 18941, 10728, 18955, -1, 10734, 10728, 18941, -1, 18955, 10727, 18971, -1, 10728, 10727, 18955, -1, 18889, 10724, 18902, -1, 10725, 10724, 18889, -1, 18902, 10731, 18910, -1, 10724, 10731, 18902, -1, 18910, 10730, 18940, -1, 10731, 10730, 18910, -1, 18837, 10761, 18838, -1, 10758, 10761, 18837, -1, 18838, 10760, 18849, -1, 10761, 10760, 18838, -1, 18849, 10765, 18862, -1, 10760, 10765, 18849, -1, 18628, 10748, 18820, -1, 10749, 10748, 18628, -1, 18820, 10752, 18827, -1, 10748, 10752, 18820, -1, 18827, 10758, 18837, -1, 10752, 10758, 18827, -1, 14933, 18772, 18756, -1, 14933, 14937, 18772, -1, 18772, 14931, 18786, -1, 14937, 14931, 18772, -1, 14931, 18629, 18786, -1, 14931, 14930, 18629, -1, 11765, 18741, 11766, -1, 16912, 18741, 11765, -1, 16914, 18741, 16912, -1, 16915, 18741, 16914, -1, 16919, 18741, 16915, -1, 16919, 14928, 18741, -1, 14928, 14927, 18741, -1, 14927, 18747, 18741, -1, 14927, 14934, 18747, -1, 14934, 18756, 18747, -1, 14934, 14933, 18756, -1, 13998, 21120, 11351, -1, 13999, 21120, 13998, -1, 14001, 21120, 13999, -1, 14002, 21120, 14001, -1, 11351, 21120, 11345, -1, 14002, 10804, 21120, -1, 10804, 10803, 21120, -1, 10803, 19344, 21120, -1, 10803, 10801, 19344, -1, 10801, 19321, 19344, -1, 10801, 10800, 19321, -1, 10800, 19254, 19321, -1, 10800, 10799, 19254, -1, 19254, 10795, 19234, -1, 10799, 10795, 19254, -1, 10795, 19235, 19234, -1, 10795, 10794, 19235, -1, 19220, 10834, 19219, -1, 10835, 10834, 19220, -1, 19219, 10832, 19211, -1, 10834, 10832, 19219, -1, 19211, 10830, 19195, -1, 10832, 10830, 19211, -1, 19195, 10826, 19106, -1, 10830, 10826, 19195, -1, 19106, 10820, 19110, -1, 10826, 10820, 19106, -1, 19110, 10815, 19082, -1, 10820, 10815, 19110, -1, 19077, 10745, 19078, -1, 10746, 10745, 19077, -1, 19078, 10743, 19067, -1, 10745, 10743, 19078, -1, 19067, 10742, 19048, -1, 10743, 10742, 19067, -1, 19048, 10741, 18974, -1, 10742, 10741, 19048, -1, 18974, 10737, 18975, -1, 10741, 10737, 18974, -1, 18975, 10736, 18961, -1, 10737, 10736, 18975, -1, 18962, 10776, 18963, -1, 10777, 10776, 18962, -1, 18963, 10774, 18948, -1, 10776, 10774, 18963, -1, 18948, 10772, 18932, -1, 10774, 10772, 18948, -1, 18932, 10768, 18871, -1, 10772, 10768, 18932, -1, 18871, 10762, 18857, -1, 10768, 10762, 18871, -1, 18857, 10757, 18726, -1, 10762, 10757, 18857, -1, 18703, 14948, 18758, -1, 14949, 14948, 18703, -1, 18758, 14945, 18759, -1, 14948, 14945, 18758, -1, 18759, 14944, 18665, -1, 14945, 14944, 18759, -1, 18665, 14946, 18662, -1, 14944, 14946, 18665, -1, 18662, 14940, 18583, -1, 14946, 14940, 18662, -1, 18583, 11754, 11753, -1, 18583, 16905, 11754, -1, 18583, 16921, 16905, -1, 14940, 14939, 18583, -1, 18583, 16924, 16921, -1, 14939, 16925, 18583, -1, 18583, 16925, 16924, -1, 19342, 10217, 19343, -1, 10222, 10217, 19342, -1, 21181, 11334, 11332, -1, 21181, 13836, 11334, -1, 21181, 13834, 13836, -1, 19343, 10216, 21181, -1, 10217, 10216, 19343, -1, 21181, 13835, 13834, -1, 10216, 13838, 21181, -1, 21181, 13838, 13835, -1, 19218, 10181, 19255, -1, 10180, 10181, 19218, -1, 19255, 10187, 19319, -1, 10181, 10187, 19255, -1, 19319, 10186, 19320, -1, 10187, 10186, 19319, -1, 19209, 10176, 19210, -1, 10177, 10176, 19209, -1, 19210, 10175, 19217, -1, 10176, 10175, 19210, -1, 19217, 10180, 19218, -1, 10175, 10180, 19217, -1, 19080, 10204, 19105, -1, 10205, 10204, 19080, -1, 19105, 10211, 19196, -1, 10204, 10211, 19105, -1, 19196, 10210, 19197, -1, 10211, 10210, 19196, -1, 19069, 10200, 19070, -1, 10201, 10200, 19069, -1, 19070, 10199, 19079, -1, 10200, 10199, 19070, -1, 19079, 10205, 19080, -1, 10199, 10205, 19079, -1, 18965, 10264, 18976, -1, 10265, 10264, 18965, -1, 18976, 10271, 19049, -1, 10264, 10271, 18976, -1, 19049, 10270, 19050, -1, 10271, 10270, 19049, -1, 18930, 10260, 18949, -1, 10261, 10260, 18930, -1, 18949, 10259, 18964, -1, 10260, 10259, 18949, -1, 18964, 10265, 18965, -1, 10259, 10265, 18964, -1, 18840, 10241, 18870, -1, 10240, 10241, 18840, -1, 18870, 10247, 18931, -1, 10241, 10247, 18870, -1, 18931, 10246, 18929, -1, 10247, 10246, 18931, -1, 10237, 18757, 18805, -1, 10237, 10236, 18757, -1, 18757, 10235, 18792, -1, 10236, 10235, 18757, -1, 10235, 18840, 18792, -1, 10235, 10240, 18840, -1, 11742, 18663, 11743, -1, 16727, 18663, 11742, -1, 16729, 18663, 16727, -1, 16730, 18663, 16729, -1, 16734, 18663, 16730, -1, 14843, 18663, 16734, -1, 18663, 14842, 18661, -1, 14843, 14842, 18663, -1, 14842, 18806, 18661, -1, 14842, 14850, 18806, -1, 13963, 19159, 11406, -1, 13964, 19159, 13963, -1, 13966, 19159, 13964, -1, 13967, 19159, 13966, -1, 11406, 19159, 11402, -1, 13967, 10722, 19159, -1, 10722, 10721, 19159, -1, 10721, 19117, 19159, -1, 10721, 10719, 19117, -1, 10719, 19095, 19117, -1, 10719, 10718, 19095, -1, 10718, 19059, 19095, -1, 10718, 10717, 19059, -1, 19059, 10713, 19060, -1, 10717, 10713, 19059, -1, 10713, 19586, 19060, -1, 10713, 10712, 19586, -1, 19587, 10694, 18989, -1, 10695, 10694, 19587, -1, 18989, 10692, 18979, -1, 10694, 10692, 18989, -1, 18979, 10690, 18969, -1, 10692, 10690, 18979, -1, 18969, 10686, 18951, -1, 10690, 10686, 18969, -1, 18951, 10680, 19044, -1, 10686, 10680, 18951, -1, 19044, 10675, 18877, -1, 10680, 10675, 19044, -1, 18878, 10663, 18884, -1, 10664, 10663, 18878, -1, 18884, 10661, 18868, -1, 10663, 10661, 18884, -1, 18868, 10660, 18855, -1, 10661, 10660, 18868, -1, 18855, 10659, 18701, -1, 10660, 10659, 18855, -1, 18701, 10655, 18647, -1, 10659, 10655, 18701, -1, 18647, 10654, 18648, -1, 10655, 10654, 18647, -1, 18642, 10636, 18643, -1, 10637, 10636, 18642, -1, 18643, 10634, 18794, -1, 10636, 10634, 18643, -1, 18794, 10632, 18789, -1, 10634, 10632, 18794, -1, 18789, 10628, 18763, -1, 10632, 10628, 18789, -1, 18763, 10622, 18536, -1, 10628, 10622, 18763, -1, 18536, 10617, 18506, -1, 10622, 10617, 18536, -1, 18501, 14924, 18525, -1, 14925, 14924, 18501, -1, 18525, 14921, 18734, -1, 14924, 14921, 18525, -1, 18734, 14920, 18731, -1, 14921, 14920, 18734, -1, 18731, 14922, 18728, -1, 14920, 14922, 18731, -1, 18728, 14916, 18430, -1, 14922, 14916, 18728, -1, 18430, 11849, 11851, -1, 18430, 16868, 11849, -1, 18430, 16884, 16868, -1, 14916, 14915, 18430, -1, 18430, 16887, 16884, -1, 14915, 16888, 18430, -1, 18430, 16888, 16887, -1, 19118, 10937, 19134, -1, 10942, 10937, 19118, -1, 19158, 11391, 11386, -1, 19158, 14046, 11391, -1, 19158, 14044, 14046, -1, 19134, 10936, 19158, -1, 10937, 10936, 19134, -1, 19158, 14045, 14044, -1, 10936, 14048, 19158, -1, 19158, 14048, 14045, -1, 19057, 10925, 19058, -1, 10924, 10925, 19057, -1, 19058, 10931, 19074, -1, 10925, 10931, 19058, -1, 19074, 10930, 19094, -1, 10931, 10930, 19074, -1, 18978, 10920, 18985, -1, 10921, 10920, 18978, -1, 18985, 10919, 18986, -1, 10920, 10919, 18985, -1, 18986, 10924, 19057, -1, 10919, 10924, 18986, -1, 18876, 10901, 18952, -1, 10900, 10901, 18876, -1, 18952, 10907, 18953, -1, 10901, 10907, 18952, -1, 18953, 10906, 18967, -1, 10907, 10906, 18953, -1, 18867, 10896, 18882, -1, 10897, 10896, 18867, -1, 18882, 10895, 18883, -1, 10896, 10895, 18882, -1, 18883, 10900, 18876, -1, 10895, 10900, 18883, -1, 18641, 10853, 18700, -1, 10852, 10853, 18641, -1, 18700, 10859, 18847, -1, 10853, 10859, 18700, -1, 18847, 10858, 18854, -1, 10859, 10858, 18847, -1, 18633, 10848, 18807, -1, 10849, 10848, 18633, -1, 18807, 10847, 18644, -1, 10848, 10847, 18807, -1, 18644, 10852, 18641, -1, 10847, 10852, 18644, -1, 18524, 10876, 18765, -1, 10877, 10876, 18524, -1, 18765, 10883, 18774, -1, 10876, 10883, 18765, -1, 18774, 10882, 18634, -1, 10883, 10882, 18774, -1, 10873, 18738, 18515, -1, 10873, 10872, 18738, -1, 18738, 10871, 18526, -1, 10872, 10871, 18738, -1, 10871, 18524, 18526, -1, 10871, 10877, 18524, -1, 11831, 18451, 11830, -1, 16949, 18451, 11831, -1, 16951, 18451, 16949, -1, 16952, 18451, 16951, -1, 16956, 18451, 16952, -1, 14951, 18451, 16956, -1, 18451, 14950, 18729, -1, 14951, 14950, 18451, -1, 14950, 18516, 18729, -1, 14950, 14958, 18516, -1, 11436, 19008, 11425, -1, 13929, 19008, 11436, -1, 13930, 19008, 13929, -1, 13932, 19008, 13930, -1, 13933, 19008, 13932, -1, 10510, 19008, 13933, -1, 19008, 10502, 19009, -1, 10510, 10502, 19008, -1, 10502, 19537, 19009, -1, 10502, 10504, 19537, -1, 10517, 18935, 19443, -1, 10517, 10516, 18935, -1, 18935, 10515, 18918, -1, 10516, 10515, 18935, -1, 10515, 18904, 18918, -1, 10515, 10533, 18904, -1, 10533, 18892, 18904, -1, 10533, 10527, 18892, -1, 18892, 10511, 18893, -1, 10527, 10511, 18892, -1, 18893, 10513, 18865, -1, 10511, 10513, 18893, -1, 18796, 10586, 18802, -1, 10589, 10586, 18796, -1, 18802, 10588, 18824, -1, 10586, 10588, 18802, -1, 18824, 10605, 18817, -1, 10588, 10605, 18824, -1, 18817, 10599, 18818, -1, 10605, 10599, 18817, -1, 18818, 10583, 18660, -1, 10599, 10583, 18818, -1, 18660, 10585, 18608, -1, 10583, 10585, 18660, -1, 18594, 10562, 18598, -1, 10565, 10562, 18594, -1, 18598, 10564, 18751, -1, 10562, 10564, 18598, -1, 18751, 10581, 18745, -1, 10564, 10581, 18751, -1, 18745, 10575, 18743, -1, 10581, 10575, 18745, -1, 18743, 10559, 18540, -1, 10575, 10559, 18743, -1, 18540, 10561, 18503, -1, 10559, 10561, 18540, -1, 18488, 10538, 18489, -1, 10541, 10538, 18488, -1, 18489, 10540, 18724, -1, 10538, 10540, 18489, -1, 18724, 10557, 18719, -1, 10540, 10557, 18724, -1, 18719, 10551, 18717, -1, 10557, 10551, 18719, -1, 18717, 10535, 18439, -1, 10551, 10535, 18717, -1, 18439, 10537, 18421, -1, 10535, 10537, 18439, -1, 18417, 14895, 18714, -1, 14893, 14895, 18417, -1, 18380, 11882, 11884, -1, 18380, 16831, 11882, -1, 18380, 16847, 16831, -1, 18714, 14901, 18380, -1, 14895, 14901, 18714, -1, 18380, 16850, 16847, -1, 14901, 16851, 18380, -1, 18380, 16851, 16850, -1, 19720, 10710, 19796, -1, 10706, 10710, 19720, -1, 19796, 10704, 19010, -1, 10710, 10704, 19796, -1, 19010, 11416, 11414, -1, 19010, 13976, 11416, -1, 19010, 13974, 13976, -1, 10704, 10703, 19010, -1, 19010, 13975, 13974, -1, 10703, 13978, 19010, -1, 19010, 13978, 13975, -1, 18917, 10700, 18934, -1, 10701, 10700, 18917, -1, 18934, 10707, 19580, -1, 10700, 10707, 18934, -1, 19580, 10706, 19720, -1, 10707, 10706, 19580, -1, 19006, 10679, 19054, -1, 10676, 10679, 19006, -1, 19054, 10678, 18894, -1, 10679, 10678, 19054, -1, 18894, 10683, 18895, -1, 10678, 10683, 18894, -1, 18825, 10666, 18801, -1, 10667, 10666, 18825, -1, 18801, 10670, 18899, -1, 10666, 10670, 18801, -1, 18899, 10676, 19006, -1, 10670, 10676, 18899, -1, 18631, 10652, 18653, -1, 10648, 10652, 18631, -1, 18653, 10646, 18670, -1, 10652, 10646, 18653, -1, 18670, 10645, 18816, -1, 10646, 10645, 18670, -1, 18750, 10642, 18597, -1, 10643, 10642, 18750, -1, 18597, 10649, 18609, -1, 10642, 10649, 18597, -1, 18609, 10648, 18631, -1, 10649, 10648, 18609, -1, 18522, 10621, 18539, -1, 10618, 10621, 18522, -1, 18539, 10620, 18545, -1, 10621, 10620, 18539, -1, 18545, 10625, 18744, -1, 10620, 10625, 18545, -1, 18462, 10608, 18487, -1, 10609, 10608, 18462, -1, 18487, 10612, 18504, -1, 10608, 10612, 18487, -1, 18504, 10618, 18522, -1, 10612, 10618, 18504, -1, 14909, 18438, 18437, -1, 14909, 14913, 18438, -1, 18438, 14907, 18444, -1, 14913, 14907, 18438, -1, 14907, 18463, 18444, -1, 14907, 14906, 18463, -1, 11870, 18418, 11871, -1, 16875, 18418, 11870, -1, 16877, 18418, 16875, -1, 16878, 18418, 16877, -1, 16882, 18418, 16878, -1, 16882, 14904, 18418, -1, 14904, 14903, 18418, -1, 14903, 18416, 18418, -1, 14903, 14910, 18416, -1, 14910, 18437, 18416, -1, 14910, 14909, 18437, -1, 11666, 19660, 11281, -1, 13894, 19660, 11666, -1, 13895, 19660, 13894, -1, 13897, 19660, 13895, -1, 13898, 19660, 13897, -1, 10402, 19660, 13898, -1, 19660, 10394, 19661, -1, 10402, 10394, 19660, -1, 10394, 19677, 19661, -1, 10394, 10396, 19677, -1, 10409, 19558, 19644, -1, 10409, 10408, 19558, -1, 19558, 10407, 19559, -1, 10408, 10407, 19558, -1, 10407, 19536, 19559, -1, 10407, 10425, 19536, -1, 10425, 19520, 19536, -1, 10425, 10419, 19520, -1, 19520, 10403, 19517, -1, 10419, 10403, 19520, -1, 19517, 10405, 19533, -1, 10403, 10405, 19517, -1, 19515, 10430, 21250, -1, 10433, 10430, 19515, -1, 21250, 10432, 19386, -1, 10430, 10432, 21250, -1, 19386, 10449, 19387, -1, 10432, 10449, 19386, -1, 19387, 10443, 19388, -1, 10449, 10443, 19387, -1, 19388, 10427, 21236, -1, 10443, 10427, 19388, -1, 21236, 10429, 19375, -1, 10427, 10429, 21236, -1, 19362, 10454, 20921, -1, 10457, 10454, 19362, -1, 20921, 10456, 19285, -1, 10454, 10456, 20921, -1, 19285, 10473, 19286, -1, 10456, 10473, 19285, -1, 19286, 10467, 19287, -1, 10473, 10467, 19286, -1, 19287, 10451, 20798, -1, 10467, 10451, 19287, -1, 20798, 10453, 19252, -1, 10451, 10453, 20798, -1, 19251, 10478, 19154, -1, 10481, 10478, 19251, -1, 19154, 10480, 19155, -1, 10478, 10480, 19154, -1, 19155, 10497, 19126, -1, 10480, 10497, 19155, -1, 19126, 10491, 19115, -1, 10497, 10491, 19126, -1, 19115, 10475, 19112, -1, 10491, 10475, 19115, -1, 19112, 10477, 19100, -1, 10475, 10477, 19112, -1, 19101, 14883, 19003, -1, 14881, 14883, 19101, -1, 19004, 11687, 11686, -1, 19004, 16794, 11687, -1, 19004, 16810, 16794, -1, 19003, 14889, 19004, -1, 14883, 14889, 19003, -1, 19004, 16813, 16810, -1, 14889, 16814, 19004, -1, 19004, 16814, 16813, -1, 19643, 10378, 19678, -1, 10374, 10378, 19643, -1, 19678, 10372, 19662, -1, 10378, 10372, 19678, -1, 19662, 11659, 11658, -1, 19662, 13871, 11659, -1, 19662, 13869, 13871, -1, 10372, 10371, 19662, -1, 19662, 13870, 13869, -1, 10371, 13873, 19662, -1, 19662, 13873, 13870, -1, 19561, 10368, 19641, -1, 10369, 10368, 19561, -1, 19641, 10375, 19642, -1, 10368, 10375, 19641, -1, 19642, 10374, 19643, -1, 10375, 10374, 19642, -1, 19513, 10323, 19534, -1, 10320, 10323, 19513, -1, 19534, 10322, 19518, -1, 10323, 10322, 19534, -1, 19518, 10327, 19521, -1, 10322, 10327, 19518, -1, 19390, 10310, 19511, -1, 10311, 10310, 19390, -1, 19511, 10314, 19512, -1, 10310, 10314, 19511, -1, 19512, 10320, 19513, -1, 10314, 10320, 19512, -1, 19365, 10354, 19374, -1, 10350, 10354, 19365, -1, 19374, 10348, 21239, -1, 10354, 10348, 19374, -1, 21239, 10347, 19389, -1, 10348, 10347, 21239, -1, 19290, 10344, 19363, -1, 10345, 10344, 19290, -1, 19363, 10351, 19364, -1, 10344, 10351, 19363, -1, 19364, 10350, 19365, -1, 10351, 10350, 19364, -1, 19249, 10289, 19265, -1, 10286, 10289, 19249, -1, 19265, 10288, 20823, -1, 10289, 10288, 19265, -1, 20823, 10293, 19288, -1, 10288, 10293, 20823, -1, 19127, 10276, 19247, -1, 10277, 10276, 19127, -1, 19247, 10280, 19248, -1, 10276, 10280, 19247, -1, 19248, 10286, 19249, -1, 10280, 10286, 19248, -1, 14861, 19123, 19103, -1, 14861, 14865, 19123, -1, 19123, 14859, 19113, -1, 14865, 14859, 19123, -1, 14859, 19114, 19113, -1, 14859, 14858, 19114, -1, 11680, 19005, 11681, -1, 16764, 19005, 11680, -1, 16766, 19005, 16764, -1, 16767, 19005, 16766, -1, 16771, 19005, 16767, -1, 16771, 14856, 19005, -1, 14856, 14855, 19005, -1, 14855, 19102, 19005, -1, 14855, 14862, 19102, -1, 14862, 19103, 19102, -1, 14862, 14861, 19103, -1, 13858, 19798, 11654, -1, 13859, 19798, 13858, -1, 13861, 19798, 13859, -1, 13862, 19798, 13861, -1, 11654, 19798, 11652, -1, 13862, 10390, 19798, -1, 10390, 10389, 19798, -1, 10389, 19768, 19798, -1, 10389, 10387, 19768, -1, 10387, 19749, 19768, -1, 10387, 10386, 19749, -1, 10386, 19714, 19749, -1, 10386, 10385, 19714, -1, 19714, 10381, 19715, -1, 10385, 10381, 19714, -1, 10381, 21321, 19715, -1, 10381, 10380, 21321, -1, 21322, 10338, 19636, -1, 10339, 10338, 21322, -1, 19636, 10336, 19625, -1, 10338, 10336, 19636, -1, 19625, 10334, 19615, -1, 10336, 10334, 19625, -1, 19615, 10330, 19575, -1, 10334, 10330, 19615, -1, 19575, 10324, 19574, -1, 10330, 10324, 19575, -1, 19574, 10319, 19497, -1, 10324, 10319, 19574, -1, 19496, 10365, 19500, -1, 10366, 10365, 19496, -1, 19500, 10362, 19484, -1, 10365, 10362, 19500, -1, 19484, 10361, 19465, -1, 10362, 10361, 19484, -1, 19465, 10363, 19418, -1, 10361, 10363, 19465, -1, 19418, 10357, 19419, -1, 10363, 10357, 19418, -1, 19419, 10356, 19357, -1, 10357, 10356, 19419, -1, 19355, 10304, 19359, -1, 10305, 10304, 19355, -1, 19359, 10302, 19346, -1, 10304, 10302, 19359, -1, 19346, 10300, 19335, -1, 10302, 10300, 19346, -1, 19335, 10296, 19301, -1, 10300, 10296, 19335, -1, 19301, 10290, 19300, -1, 10296, 10290, 19301, -1, 19300, 10285, 20631, -1, 10290, 10285, 19300, -1, 20547, 14876, 19237, -1, 14877, 14876, 20547, -1, 19237, 14873, 19222, -1, 14876, 14873, 19237, -1, 19222, 14872, 19200, -1, 14873, 14872, 19222, -1, 19200, 14874, 19176, -1, 14872, 14874, 19200, -1, 19176, 14868, 19177, -1, 14874, 14868, 19176, -1, 19177, 11694, 11693, -1, 19177, 16757, 11694, -1, 19177, 16773, 16757, -1, 14868, 14867, 19177, -1, 19177, 16776, 16773, -1, 14867, 16777, 19177, -1, 19177, 16777, 16776, -1, 19769, 6541, 19778, -1, 6546, 6541, 19769, -1, 19799, 11645, 11644, -1, 19799, 12540, 11645, -1, 19799, 12538, 12540, -1, 19778, 6540, 19799, -1, 6541, 6540, 19778, -1, 19799, 12539, 12538, -1, 6540, 12542, 19799, -1, 19799, 12542, 12539, -1, 19712, 6564, 19713, -1, 6565, 6564, 19712, -1, 19713, 6571, 19727, -1, 6564, 6571, 19713, -1, 19727, 6570, 19748, -1, 6571, 6570, 19727, -1, 19622, 6560, 19635, -1, 6561, 6560, 19622, -1, 19635, 6559, 19650, -1, 6560, 6559, 19635, -1, 19650, 6565, 19712, -1, 6559, 6565, 19650, -1, 19526, 6481, 19573, -1, 6480, 6481, 19526, -1, 19573, 6487, 19591, -1, 6481, 6487, 19573, -1, 19591, 6486, 19614, -1, 6487, 6486, 19591, -1, 19485, 6476, 19501, -1, 6477, 6476, 19485, -1, 19501, 6475, 19527, -1, 6476, 6475, 19501, -1, 19527, 6480, 19526, -1, 6475, 6480, 19527, -1, 19369, 6504, 19420, -1, 6505, 6504, 19369, -1, 19420, 6511, 19444, -1, 6504, 6511, 19420, -1, 19444, 6510, 19466, -1, 6511, 6510, 19444, -1, 19334, 6500, 19360, -1, 6501, 6500, 19334, -1, 19360, 6499, 19370, -1, 6500, 6499, 19360, -1, 19370, 6505, 19369, -1, 6499, 6505, 19370, -1, 19259, 6528, 19302, -1, 6529, 6528, 19259, -1, 19302, 6535, 19309, -1, 6528, 6535, 19302, -1, 19309, 6534, 19333, -1, 6535, 6534, 19309, -1, 6525, 19238, 19202, -1, 6525, 6524, 19238, -1, 19238, 6523, 19260, -1, 6524, 6523, 19238, -1, 6523, 19259, 19260, -1, 6523, 6529, 19259, -1, 11701, 19178, 11702, -1, 15469, 19178, 11701, -1, 15471, 19178, 15469, -1, 15472, 19178, 15471, -1, 15476, 19178, 15472, -1, 14335, 19178, 15476, -1, 19178, 14334, 19180, -1, 14335, 14334, 19178, -1, 14334, 19201, 19180, -1, 14334, 14342, 19201, -1, 11321, 19477, 11319, -1, 13823, 19477, 11321, -1, 13824, 19477, 13823, -1, 13826, 19477, 13824, -1, 13827, 19477, 13826, -1, 10226, 19477, 13827, -1, 19477, 10218, 19449, -1, 10226, 10218, 19477, -1, 10218, 19423, 19449, -1, 10218, 10220, 19423, -1, 10173, 19384, 19383, -1, 10173, 10172, 19384, -1, 19384, 10171, 21072, -1, 10172, 10171, 19384, -1, 10171, 21073, 21072, -1, 10171, 10189, 21073, -1, 10189, 19324, 21073, -1, 10189, 10183, 19324, -1, 19324, 10167, 19307, -1, 10183, 10167, 19324, -1, 19307, 10169, 19298, -1, 10167, 10169, 19307, -1, 19270, 10194, 19269, -1, 10197, 10194, 19270, -1, 19269, 10196, 19187, -1, 10194, 10196, 19269, -1, 19187, 10213, 19188, -1, 10196, 10213, 19187, -1, 19188, 10207, 19189, -1, 10213, 10207, 19188, -1, 19189, 10191, 19192, -1, 10207, 10191, 19189, -1, 19192, 10193, 19174, -1, 10191, 10193, 19192, -1, 19132, 10254, 19129, -1, 10257, 10254, 19132, -1, 19129, 10256, 19039, -1, 10254, 10256, 19129, -1, 19039, 10273, 19040, -1, 10256, 10273, 19039, -1, 19040, 10267, 19041, -1, 10273, 10267, 19040, -1, 19041, 10251, 19045, -1, 10267, 10251, 19041, -1, 19045, 10253, 19016, -1, 10251, 10253, 19045, -1, 18995, 10230, 18991, -1, 10233, 10230, 18995, -1, 18991, 10232, 19275, -1, 10230, 10232, 18991, -1, 19275, 10249, 19276, -1, 10232, 10249, 19275, -1, 19276, 10243, 18938, -1, 10249, 10243, 19276, -1, 18938, 10227, 18921, -1, 10243, 10227, 18938, -1, 18921, 10229, 18898, -1, 10227, 10229, 18921, -1, 18873, 14847, 18735, -1, 14845, 14847, 18873, -1, 18692, 11734, 11733, -1, 18692, 16720, 11734, -1, 18692, 16736, 16720, -1, 18735, 14853, 18692, -1, 14847, 14853, 18735, -1, 18692, 16739, 16736, -1, 14853, 16740, 18692, -1, 18692, 16740, 16739, -1, 19399, 10062, 19422, -1, 10058, 10062, 19399, -1, 19422, 10056, 19476, -1, 10062, 10056, 19422, -1, 19476, 11308, 11303, -1, 19476, 13801, 11308, -1, 19476, 13799, 13801, -1, 10056, 10055, 19476, -1, 19476, 13800, 13799, -1, 10055, 13803, 19476, -1, 19476, 13803, 13800, -1, 19380, 10052, 19381, -1, 10053, 10052, 19380, -1, 19381, 10059, 19382, -1, 10052, 10059, 19381, -1, 19382, 10058, 19399, -1, 10059, 10058, 19382, -1, 19292, 10089, 19297, -1, 10086, 10089, 19292, -1, 19297, 10088, 19306, -1, 10089, 10088, 19297, -1, 19306, 10093, 19323, -1, 10088, 10093, 19306, -1, 19225, 10076, 19267, -1, 10077, 10076, 19225, -1, 19267, 10080, 19268, -1, 10076, 10080, 19267, -1, 19268, 10086, 19292, -1, 10080, 10086, 19268, -1, 19151, 10120, 19173, -1, 10116, 10120, 19151, -1, 19173, 10114, 19191, -1, 10120, 10114, 19173, -1, 19191, 10113, 19186, -1, 10114, 10113, 19191, -1, 19091, 10110, 19130, -1, 10111, 10110, 19091, -1, 19130, 10117, 19131, -1, 10110, 10117, 19130, -1, 19131, 10116, 19151, -1, 10117, 10116, 19131, -1, 19017, 10147, 19023, -1, 10144, 10147, 19017, -1, 19023, 10146, 19043, -1, 10147, 10146, 19023, -1, 19043, 10151, 19038, -1, 10146, 10151, 19043, -1, 18992, 10134, 18993, -1, 10135, 10134, 18992, -1, 18993, 10138, 18994, -1, 10134, 10138, 18993, -1, 18994, 10144, 19017, -1, 10138, 10144, 18994, -1, 14825, 18906, 18897, -1, 14825, 14829, 18906, -1, 18906, 14823, 18922, -1, 14829, 14823, 18906, -1, 14823, 18937, 18922, -1, 14823, 14822, 18937, -1, 11722, 18834, 11721, -1, 16690, 18834, 11722, -1, 16692, 18834, 16690, -1, 16693, 18834, 16692, -1, 16697, 18834, 16693, -1, 16697, 14820, 18834, -1, 14820, 14819, 18834, -1, 14819, 18874, 18834, -1, 14819, 14826, 18874, -1, 14826, 18897, 18874, -1, 14826, 14825, 18897, -1, 13789, 19570, 11292, -1, 13790, 19570, 13789, -1, 13792, 19570, 13790, -1, 13793, 19570, 13792, -1, 11292, 19570, 11290, -1, 13793, 10074, 19570, -1, 10074, 10073, 19570, -1, 10073, 19546, 19570, -1, 10073, 10071, 19546, -1, 10071, 19492, 19546, -1, 10071, 10070, 19492, -1, 10070, 19479, 19492, -1, 10070, 10069, 19479, -1, 19479, 10065, 19454, -1, 10069, 10065, 19479, -1, 10065, 19452, 19454, -1, 10065, 10064, 19452, -1, 19406, 10104, 19393, -1, 10105, 10104, 19406, -1, 19393, 10102, 19394, -1, 10104, 10102, 19393, -1, 19394, 10100, 19349, -1, 10102, 10100, 19394, -1, 19349, 10096, 19330, -1, 10100, 10096, 19349, -1, 19330, 10090, 19331, -1, 10096, 10090, 19330, -1, 19331, 10085, 19272, -1, 10090, 10085, 19331, -1, 19277, 10131, 19280, -1, 10132, 10131, 19277, -1, 19280, 10128, 19281, -1, 10131, 10128, 19280, -1, 19281, 10127, 19229, -1, 10128, 10127, 19281, -1, 19229, 10129, 19206, -1, 10127, 10129, 19229, -1, 19206, 10123, 19207, -1, 10129, 10123, 19206, -1, 19207, 10122, 19137, -1, 10123, 10122, 19207, -1, 19139, 10162, 19148, -1, 10163, 10162, 19139, -1, 19148, 10160, 19146, -1, 10162, 10160, 19148, -1, 19146, 10158, 19088, -1, 10160, 10158, 19146, -1, 19088, 10154, 19072, -1, 10158, 10154, 19088, -1, 19072, 10148, 19055, -1, 10154, 10148, 19072, -1, 19055, 10143, 19030, -1, 10148, 10143, 19055, -1, 19019, 14840, 18997, -1, 14841, 14840, 19019, -1, 18997, 14837, 18998, -1, 14840, 14837, 18997, -1, 18998, 14836, 18999, -1, 14837, 14836, 18998, -1, 18999, 14838, 18945, -1, 14836, 14838, 18999, -1, 18945, 14832, 18925, -1, 14838, 14832, 18945, -1, 18925, 11709, 11708, -1, 18925, 16683, 11709, -1, 18925, 16699, 16683, -1, 14832, 14831, 18925, -1, 18925, 16702, 16699, -1, 14831, 16703, 18925, -1, 18925, 16703, 16702, -1, 21292, 10393, 19545, -1, 10398, 10393, 21292, -1, 19571, 11284, 11280, -1, 19571, 13906, 11284, -1, 19571, 13904, 13906, -1, 19545, 10392, 19571, -1, 10393, 10392, 19545, -1, 19571, 13905, 13904, -1, 10392, 13908, 19571, -1, 19571, 13908, 13905, -1, 19425, 10416, 19451, -1, 10417, 10416, 19425, -1, 19451, 10423, 19491, -1, 10416, 10423, 19451, -1, 19491, 10422, 21286, -1, 10423, 10422, 19491, -1, 21243, 10412, 19392, -1, 10413, 10412, 21243, -1, 19392, 10411, 19405, -1, 10412, 10411, 19392, -1, 19405, 10417, 19425, -1, 10411, 10417, 19405, -1, 19295, 10440, 19329, -1, 10441, 10440, 19295, -1, 19329, 10447, 19348, -1, 10440, 10447, 19329, -1, 19348, 10446, 21234, -1, 10447, 10446, 19348, -1, 20852, 10436, 19282, -1, 10437, 10436, 20852, -1, 19282, 10435, 19294, -1, 10436, 10435, 19282, -1, 19294, 10441, 19295, -1, 10435, 10441, 19294, -1, 19171, 10464, 19204, -1, 10465, 10464, 19171, -1, 19204, 10471, 19228, -1, 10464, 10471, 19204, -1, 19228, 10470, 20788, -1, 10471, 10470, 19228, -1, 20273, 10460, 19147, -1, 10461, 10460, 20273, -1, 19147, 10459, 19170, -1, 10460, 10459, 19147, -1, 19170, 10465, 19171, -1, 10459, 10465, 19170, -1, 19031, 10488, 19053, -1, 10489, 10488, 19031, -1, 19053, 10495, 19087, -1, 10488, 10495, 19053, -1, 19087, 10494, 20226, -1, 10495, 10494, 19087, -1, 10485, 19001, 19754, -1, 10485, 10484, 19001, -1, 19001, 10483, 19021, -1, 10484, 10483, 19001, -1, 10483, 19031, 19021, -1, 10483, 10489, 19031, -1, 11698, 18927, 11699, -1, 16801, 18927, 11698, -1, 16803, 18927, 16801, -1, 16804, 18927, 16803, -1, 16808, 18927, 16804, -1, 14879, 18927, 16808, -1, 18927, 14878, 18946, -1, 14879, 14878, 18927, -1, 14878, 19649, 18946, -1, 14878, 14886, 19649, -1, 11617, 2976, 3388, -1, 13752, 2976, 11617, -1, 13753, 2976, 13752, -1, 13755, 2976, 13753, -1, 13756, 2976, 13755, -1, 13759, 2976, 13756, -1, 2976, 14811, 2964, -1, 13759, 14811, 2976, -1, 14811, 2965, 2964, -1, 14811, 14813, 2965, -1, 10033, 2904, 2915, -1, 10033, 10032, 2904, -1, 2904, 10031, 2892, -1, 10032, 10031, 2904, -1, 10031, 2878, 2892, -1, 10031, 10049, 2878, -1, 10049, 2864, 2878, -1, 10049, 10043, 2864, -1, 2864, 10027, 2850, -1, 10043, 10027, 2864, -1, 2850, 10029, 2847, -1, 10027, 10029, 2850, -1, 2800, 10006, 2781, -1, 10009, 10006, 2800, -1, 2781, 10008, 2746, -1, 10006, 10008, 2781, -1, 2746, 10025, 2747, -1, 10008, 10025, 2746, -1, 2747, 10019, 2737, -1, 10025, 10019, 2747, -1, 2737, 10003, 2721, -1, 10019, 10003, 2737, -1, 2721, 10005, 2718, -1, 10003, 10005, 2721, -1, 2659, 9982, 2649, -1, 9985, 9982, 2659, -1, 2649, 9984, 2625, -1, 9982, 9984, 2649, -1, 2625, 10001, 2626, -1, 9984, 10001, 2625, -1, 2626, 9995, 2604, -1, 10001, 9995, 2626, -1, 2604, 9979, 2579, -1, 9995, 9979, 2604, -1, 2579, 9981, 2580, -1, 9979, 9981, 2579, -1, 2532, 9946, 2514, -1, 9949, 9946, 2532, -1, 2514, 9948, 2506, -1, 9946, 9948, 2514, -1, 2506, 9965, 2485, -1, 9948, 9965, 2506, -1, 2485, 9959, 2470, -1, 9965, 9959, 2485, -1, 2470, 9943, 2441, -1, 9959, 9943, 2470, -1, 2441, 9945, 2442, -1, 9943, 9945, 2441, -1, 2393, 9972, 2369, -1, 9970, 9972, 2393, -1, 2367, 12017, 2795, -1, 2367, 16646, 12017, -1, 2367, 16662, 16646, -1, 2369, 9978, 2367, -1, 9972, 9978, 2369, -1, 2367, 16665, 16662, -1, 9978, 16666, 2367, -1, 2367, 16666, 16665, -1, 3379, 14799, 2961, -1, 14795, 14799, 3379, -1, 2961, 14793, 2962, -1, 14799, 14793, 2961, -1, 2962, 11597, 2977, -1, 2962, 13726, 11597, -1, 2962, 13724, 13726, -1, 14793, 13727, 2962, -1, 2962, 13725, 13724, -1, 13727, 13729, 2962, -1, 2962, 13729, 13725, -1, 2891, 14791, 2903, -1, 14792, 14791, 2891, -1, 2903, 14796, 3364, -1, 14791, 14796, 2903, -1, 3364, 14795, 3379, -1, 14796, 14795, 3364, -1, 3310, 9841, 2848, -1, 9838, 9841, 3310, -1, 2848, 9840, 2849, -1, 9841, 9840, 2848, -1, 2849, 9845, 2863, -1, 9840, 9845, 2849, -1, 2745, 9828, 2780, -1, 9829, 9828, 2745, -1, 2780, 9832, 3298, -1, 9828, 9832, 2780, -1, 3298, 9838, 3310, -1, 9832, 9838, 3298, -1, 3241, 9872, 2719, -1, 9868, 9872, 3241, -1, 2719, 9866, 2720, -1, 9872, 9866, 2719, -1, 2720, 9865, 2736, -1, 9866, 9865, 2720, -1, 2627, 9862, 2647, -1, 9863, 9862, 2627, -1, 2647, 9869, 3228, -1, 9862, 9869, 2647, -1, 3228, 9868, 3241, -1, 9869, 9868, 3228, -1, 3189, 9899, 2577, -1, 9896, 9899, 3189, -1, 2577, 9898, 2578, -1, 9899, 9898, 2577, -1, 2578, 9903, 2603, -1, 9898, 9903, 2578, -1, 2484, 9886, 2513, -1, 9887, 9886, 2484, -1, 2513, 9890, 3179, -1, 9886, 9890, 2513, -1, 3179, 9896, 3189, -1, 9890, 9896, 3179, -1, 9926, 2443, 3127, -1, 9926, 9930, 2443, -1, 2443, 9924, 2444, -1, 9930, 9924, 2443, -1, 9924, 2469, 2444, -1, 9924, 9923, 2469, -1, 12007, 2372, 2371, -1, 16616, 2372, 12007, -1, 16618, 2372, 16616, -1, 16619, 2372, 16618, -1, 16623, 2372, 16619, -1, 16623, 9921, 2372, -1, 9921, 9920, 2372, -1, 9920, 2392, 2372, -1, 9920, 9927, 2392, -1, 9927, 3127, 2392, -1, 9927, 9926, 3127, -1, 13712, 132, 11586, -1, 13713, 132, 13712, -1, 13715, 132, 13713, -1, 13716, 132, 13715, -1, 11586, 132, 131, -1, 13716, 13719, 132, -1, 13719, 14809, 132, -1, 14809, 163, 132, -1, 14809, 14807, 163, -1, 14807, 3010, 163, -1, 14807, 14806, 3010, -1, 14806, 3008, 3010, -1, 14806, 14805, 3008, -1, 3008, 14802, 2972, -1, 14805, 14802, 3008, -1, 14802, 2973, 2972, -1, 14802, 14801, 2973, -1, 2948, 9856, 2946, -1, 9857, 9856, 2948, -1, 2946, 9854, 2941, -1, 9856, 9854, 2946, -1, 2941, 9852, 2920, -1, 9854, 9852, 2941, -1, 2920, 9848, 2918, -1, 9852, 9848, 2920, -1, 2918, 9842, 2843, -1, 9848, 9842, 2918, -1, 2843, 9837, 2845, -1, 9842, 9837, 2843, -1, 2844, 9883, 3304, -1, 9884, 9883, 2844, -1, 3304, 9880, 2834, -1, 9883, 9880, 3304, -1, 2834, 9879, 2811, -1, 9880, 9879, 2834, -1, 2811, 9881, 2812, -1, 9879, 9881, 2811, -1, 2812, 9875, 2724, -1, 9881, 9875, 2812, -1, 2724, 9874, 2725, -1, 9875, 9874, 2724, -1, 2728, 9914, 3236, -1, 9915, 9914, 2728, -1, 3236, 9912, 2709, -1, 9914, 9912, 3236, -1, 2709, 9910, 2666, -1, 9912, 9910, 2709, -1, 2666, 9906, 2664, -1, 9910, 9906, 2666, -1, 2664, 9900, 2585, -1, 9906, 9900, 2664, -1, 2585, 9895, 2561, -1, 9900, 9895, 2585, -1, 2557, 9941, 2558, -1, 9942, 9941, 2557, -1, 2558, 9938, 2555, -1, 9941, 9938, 2558, -1, 2555, 9937, 2539, -1, 9938, 9937, 2555, -1, 2539, 9939, 2540, -1, 9937, 9939, 2539, -1, 2540, 9933, 2453, -1, 9939, 9933, 2540, -1, 2453, 11997, 2454, -1, 2453, 16609, 11997, -1, 2453, 16625, 16609, -1, 9933, 9932, 2453, -1, 2453, 16628, 16625, -1, 9932, 16629, 2453, -1, 2453, 16629, 16628, -1, 135, 14754, 164, -1, 14759, 14754, 135, -1, 162, 11567, 181, -1, 162, 13608, 11567, -1, 162, 13606, 13608, -1, 164, 13609, 162, -1, 14754, 13609, 164, -1, 162, 13607, 13606, -1, 13609, 13611, 162, -1, 162, 13611, 13607, -1, 2949, 9508, 3009, -1, 9509, 9508, 2949, -1, 3009, 9515, 3011, -1, 9508, 9515, 3009, -1, 3011, 9514, 136, -1, 9515, 9514, 3011, -1, 2942, 9504, 2957, -1, 9505, 9504, 2942, -1, 2957, 9503, 2947, -1, 9504, 9503, 2957, -1, 2947, 9509, 2949, -1, 9503, 9509, 2947, -1, 2842, 9568, 2919, -1, 9569, 9568, 2842, -1, 2919, 9575, 2921, -1, 9568, 9575, 2919, -1, 2921, 9574, 2930, -1, 9575, 9574, 2921, -1, 2835, 9564, 2852, -1, 9565, 9564, 2835, -1, 2852, 9563, 3308, -1, 9564, 9563, 2852, -1, 3308, 9569, 2842, -1, 9563, 9569, 3308, -1, 2723, 9593, 2813, -1, 9592, 9593, 2723, -1, 2813, 9599, 2814, -1, 9593, 9599, 2813, -1, 2814, 9598, 2819, -1, 9599, 9598, 2814, -1, 2702, 9588, 2730, -1, 9589, 9588, 2702, -1, 2730, 9587, 3240, -1, 9588, 9587, 2730, -1, 3240, 9592, 2723, -1, 9587, 9592, 3240, -1, 2560, 9545, 2665, -1, 9544, 9545, 2560, -1, 2665, 9551, 2667, -1, 9545, 9551, 2665, -1, 2667, 9550, 2701, -1, 9551, 9550, 2667, -1, 9541, 2575, 2544, -1, 9541, 9540, 2575, -1, 2575, 9539, 2559, -1, 9540, 9539, 2575, -1, 9539, 2560, 2559, -1, 9539, 9544, 2560, -1, 11988, 2458, 2456, -1, 16505, 2458, 11988, -1, 16507, 2458, 16505, -1, 16508, 2458, 16507, -1, 16512, 2458, 16508, -1, 9520, 2458, 16512, -1, 2458, 9519, 2541, -1, 9520, 9519, 2458, -1, 9519, 2542, 2541, -1, 9519, 9527, 2542, -1, 11632, 2773, 3275, -1, 13673, 2773, 11632, -1, 13674, 2773, 13673, -1, 13676, 2773, 13674, -1, 13677, 2773, 13676, -1, 13680, 2773, 13677, -1, 2773, 14783, 2774, -1, 13680, 14783, 2773, -1, 14783, 2794, 2774, -1, 14783, 14785, 2794, -1, 9785, 2675, 2758, -1, 9785, 9784, 2675, -1, 2675, 9783, 2676, -1, 9784, 9783, 2675, -1, 9783, 2655, 2676, -1, 9783, 9801, 2655, -1, 9801, 2636, 2655, -1, 9801, 9795, 2636, -1, 2636, 9779, 2637, -1, 9795, 9779, 2636, -1, 2637, 9781, 2652, -1, 9779, 9781, 2637, -1, 2631, 9806, 3173, -1, 9809, 9806, 2631, -1, 3173, 9808, 2525, -1, 9806, 9808, 3173, -1, 2525, 9825, 2526, -1, 9808, 9825, 2525, -1, 2526, 9819, 2524, -1, 9825, 9819, 2526, -1, 2524, 9803, 3159, -1, 9819, 9803, 2524, -1, 3159, 9805, 2504, -1, 9803, 9805, 3159, -1, 2498, 9722, 3106, -1, 9725, 9722, 2498, -1, 3106, 9724, 2414, -1, 9722, 9724, 3106, -1, 2414, 9741, 2415, -1, 9724, 9741, 2414, -1, 2415, 9735, 2413, -1, 9741, 9735, 2415, -1, 2413, 9719, 3058, -1, 9735, 9719, 2413, -1, 3058, 9721, 2380, -1, 9719, 9721, 3058, -1, 2378, 9746, 2285, -1, 9749, 9746, 2378, -1, 2285, 9748, 2286, -1, 9746, 9748, 2285, -1, 2286, 9765, 2255, -1, 9748, 9765, 2286, -1, 2255, 9759, 2243, -1, 9765, 9759, 2255, -1, 2243, 9743, 2241, -1, 9759, 9743, 2243, -1, 2241, 9745, 2171, -1, 9743, 9745, 2241, -1, 2096, 9772, 2097, -1, 9770, 9772, 2096, -1, 1842, 12055, 1843, -1, 1842, 16572, 12055, -1, 1842, 16588, 16572, -1, 2097, 9778, 1842, -1, 9772, 9778, 2097, -1, 1842, 16591, 16588, -1, 9778, 16592, 1842, -1, 1842, 16592, 16591, -1, 2757, 14771, 2793, -1, 14767, 14771, 2757, -1, 2793, 14765, 2775, -1, 14771, 14765, 2793, -1, 2775, 11636, 2776, -1, 2775, 13647, 11636, -1, 2775, 13645, 13647, -1, 14765, 13648, 2775, -1, 2775, 13646, 13645, -1, 13648, 13650, 2775, -1, 2775, 13650, 13646, -1, 2677, 14763, 2755, -1, 14764, 14763, 2677, -1, 2755, 14768, 2756, -1, 14763, 14768, 2755, -1, 2756, 14767, 2757, -1, 14768, 14767, 2756, -1, 2634, 9699, 2651, -1, 9696, 9699, 2634, -1, 2651, 9698, 2638, -1, 9699, 9698, 2651, -1, 2638, 9703, 2639, -1, 9698, 9703, 2638, -1, 2523, 9686, 2632, -1, 9687, 9686, 2523, -1, 2632, 9690, 2633, -1, 9686, 9690, 2632, -1, 2633, 9696, 2634, -1, 9690, 9696, 2633, -1, 2501, 9672, 2511, -1, 9668, 9672, 2501, -1, 2511, 9666, 3161, -1, 9672, 9666, 2511, -1, 3161, 9665, 2522, -1, 9666, 9665, 3161, -1, 2412, 9662, 2499, -1, 9663, 9662, 2412, -1, 2499, 9669, 2500, -1, 9662, 9669, 2499, -1, 2500, 9668, 2501, -1, 9669, 9668, 2500, -1, 2382, 9641, 2395, -1, 9638, 9641, 2382, -1, 2395, 9640, 3075, -1, 9641, 9640, 2395, -1, 3075, 9645, 2411, -1, 9640, 9645, 3075, -1, 2253, 9628, 2379, -1, 9629, 9628, 2253, -1, 2379, 9632, 2381, -1, 9628, 9632, 2379, -1, 2381, 9638, 2382, -1, 9632, 9638, 2381, -1, 9610, 2251, 2234, -1, 9610, 9614, 2251, -1, 2251, 9608, 2242, -1, 9614, 9608, 2251, -1, 9608, 2244, 2242, -1, 9608, 9607, 2244, -1, 12049, 2098, 2170, -1, 16542, 2098, 12049, -1, 16544, 2098, 16542, -1, 16545, 2098, 16544, -1, 16549, 2098, 16545, -1, 16549, 9605, 2098, -1, 9605, 9604, 2098, -1, 9604, 2155, 2098, -1, 9604, 9611, 2155, -1, 9611, 2234, 2155, -1, 9611, 9610, 2234, -1, 13652, 2900, 11630, -1, 13638, 2900, 13652, -1, 13637, 2900, 13638, -1, 13639, 2900, 13637, -1, 11630, 2900, 3324, -1, 13639, 13642, 2900, -1, 13642, 14781, 2900, -1, 14781, 2876, 2900, -1, 14781, 14779, 2876, -1, 14779, 2860, 2876, -1, 14779, 14778, 2860, -1, 14778, 2826, 2860, -1, 14778, 14777, 2826, -1, 2826, 14774, 2827, -1, 14777, 14774, 2826, -1, 14774, 3259, 2827, -1, 14774, 14773, 3259, -1, 3260, 9714, 2750, -1, 9715, 9714, 3260, -1, 2750, 9712, 2739, -1, 9714, 9712, 2750, -1, 2739, 9710, 2732, -1, 9712, 9710, 2739, -1, 2732, 9706, 2697, -1, 9710, 9706, 2732, -1, 2697, 9700, 2698, -1, 9706, 9700, 2697, -1, 2698, 9695, 2618, -1, 9700, 9695, 2698, -1, 2617, 9683, 2623, -1, 9684, 9683, 2617, -1, 2623, 9681, 2609, -1, 9683, 9681, 2623, -1, 2609, 9680, 2583, -1, 9681, 9680, 2609, -1, 2583, 9679, 2548, -1, 9680, 9679, 2583, -1, 2548, 9675, 2546, -1, 9679, 9675, 2548, -1, 2546, 9674, 2492, -1, 9675, 9674, 2546, -1, 2491, 9656, 2495, -1, 9657, 9656, 2491, -1, 2495, 9654, 2477, -1, 9656, 9654, 2495, -1, 2477, 9652, 2466, -1, 9654, 9652, 2477, -1, 2466, 9648, 2427, -1, 9652, 9648, 2466, -1, 2427, 9642, 2428, -1, 9648, 9642, 2427, -1, 2428, 9637, 2916, -1, 9642, 9637, 2428, -1, 2836, 9625, 2365, -1, 9626, 9625, 2836, -1, 2365, 9622, 2348, -1, 9625, 9622, 2365, -1, 2348, 9621, 2324, -1, 9622, 9621, 2348, -1, 2324, 9623, 2300, -1, 9621, 9623, 2324, -1, 2300, 9617, 2267, -1, 9623, 9617, 2300, -1, 2267, 12042, 2270, -1, 2267, 16535, 12042, -1, 2267, 16551, 16535, -1, 9617, 9616, 2267, -1, 2267, 16554, 16551, -1, 9616, 16555, 2267, -1, 2267, 16555, 16554, -1, 2875, 14810, 2885, -1, 14815, 14810, 2875, -1, 2901, 11621, 3340, -1, 2901, 13765, 11621, -1, 2901, 13763, 13765, -1, 2885, 13766, 2901, -1, 14810, 13766, 2885, -1, 2901, 13764, 13763, -1, 13766, 13768, 2901, -1, 2901, 13768, 13764, -1, 2828, 10041, 2829, -1, 10040, 10041, 2828, -1, 2829, 10047, 2840, -1, 10041, 10047, 2829, -1, 2840, 10046, 2861, -1, 10047, 10046, 2840, -1, 2740, 10036, 2749, -1, 10037, 10036, 2740, -1, 2749, 10035, 2760, -1, 10036, 10035, 2749, -1, 2760, 10040, 2828, -1, 10035, 10040, 2760, -1, 2644, 10017, 2699, -1, 10016, 10017, 2644, -1, 2699, 10023, 2711, -1, 10017, 10023, 2699, -1, 2711, 10022, 2733, -1, 10023, 10022, 2711, -1, 2606, 10012, 2622, -1, 10013, 10012, 2606, -1, 2622, 10011, 2645, -1, 10012, 10011, 2622, -1, 2645, 10016, 2644, -1, 10011, 10016, 2645, -1, 2509, 9993, 2547, -1, 9992, 9993, 2509, -1, 2547, 9999, 2566, -1, 9993, 9999, 2547, -1, 2566, 9998, 2582, -1, 9999, 9998, 2566, -1, 2467, 9988, 2494, -1, 9989, 9988, 2467, -1, 2494, 9987, 2508, -1, 9988, 9987, 2494, -1, 2508, 9992, 2509, -1, 9987, 9992, 2508, -1, 2387, 9956, 2426, -1, 9957, 9956, 2387, -1, 2426, 9963, 2435, -1, 9956, 9963, 2426, -1, 2435, 9962, 2465, -1, 9963, 9962, 2435, -1, 9953, 2364, 2323, -1, 9953, 9952, 2364, -1, 2364, 9951, 2389, -1, 9952, 9951, 2364, -1, 9951, 2387, 2389, -1, 9951, 9957, 2387, -1, 12030, 2302, 2301, -1, 16653, 2302, 12030, -1, 16655, 2302, 16653, -1, 16656, 2302, 16655, -1, 16660, 2302, 16656, -1, 9968, 2302, 16660, -1, 2302, 9967, 2303, -1, 9968, 9967, 2302, -1, 9967, 2322, 2303, -1, 9967, 9975, 2322, -1, 11559, 280, 279, -1, 13594, 280, 11559, -1, 13595, 280, 13594, -1, 13597, 280, 13595, -1, 13598, 280, 13597, -1, 13601, 280, 13598, -1, 280, 14755, 3065, -1, 13601, 14755, 280, -1, 14755, 228, 3065, -1, 14755, 14757, 228, -1, 9501, 3040, 198, -1, 9501, 9500, 3040, -1, 3040, 9499, 3028, -1, 9500, 9499, 3040, -1, 9499, 3029, 3028, -1, 9499, 9517, 3029, -1, 9517, 3021, 3029, -1, 9517, 9511, 3021, -1, 3021, 9495, 3015, -1, 9511, 9495, 3021, -1, 3015, 9497, 3006, -1, 9495, 9497, 3015, -1, 2989, 9558, 2980, -1, 9561, 9558, 2989, -1, 2980, 9560, 2954, -1, 9558, 9560, 2980, -1, 2954, 9577, 2955, -1, 9560, 9577, 2954, -1, 2955, 9571, 2932, -1, 9577, 9571, 2955, -1, 2932, 9555, 2925, -1, 9571, 9555, 2932, -1, 2925, 9557, 2912, -1, 9555, 9557, 2925, -1, 2882, 9582, 2871, -1, 9585, 9582, 2882, -1, 2871, 9584, 2856, -1, 9582, 9584, 2871, -1, 2856, 9601, 2857, -1, 9584, 9601, 2856, -1, 2857, 9595, 2831, -1, 9601, 9595, 2857, -1, 2831, 9579, 2816, -1, 9595, 9579, 2831, -1, 2816, 9581, 2783, -1, 9579, 9581, 2816, -1, 2752, 9534, 2742, -1, 9537, 9534, 2752, -1, 2742, 9536, 2713, -1, 9534, 9536, 2742, -1, 2713, 9553, 2714, -1, 9536, 9553, 2713, -1, 2714, 9547, 2705, -1, 9553, 9547, 2714, -1, 2705, 9531, 2681, -1, 9547, 9531, 2705, -1, 2681, 9533, 2642, -1, 9531, 9533, 2681, -1, 2611, 9524, 2590, -1, 9522, 9524, 2611, -1, 2591, 11977, 3169, -1, 2591, 16498, 11977, -1, 2591, 16514, 16498, -1, 2590, 9530, 2591, -1, 9524, 9530, 2590, -1, 2591, 16517, 16514, -1, 9530, 16518, 2591, -1, 2591, 16518, 16517, -1, 3050, 14743, 3057, -1, 14739, 14743, 3050, -1, 3057, 14737, 3064, -1, 14743, 14737, 3057, -1, 3064, 11544, 3070, -1, 3064, 13569, 11544, -1, 3064, 13567, 13569, -1, 14737, 13570, 3064, -1, 3064, 13568, 13567, -1, 13570, 13572, 3064, -1, 3064, 13572, 13568, -1, 188, 14735, 3039, -1, 14736, 14735, 188, -1, 3039, 14740, 3045, -1, 14735, 14740, 3039, -1, 3045, 14739, 3050, -1, 14740, 14739, 3045, -1, 3000, 9451, 3005, -1, 9448, 9451, 3000, -1, 3005, 9450, 3014, -1, 9451, 9450, 3005, -1, 3014, 9455, 184, -1, 9450, 9455, 3014, -1, 2952, 9438, 2979, -1, 9439, 9438, 2952, -1, 2979, 9442, 2988, -1, 9438, 9442, 2979, -1, 2988, 9448, 3000, -1, 9442, 9448, 2988, -1, 2897, 9482, 2913, -1, 9478, 9482, 2897, -1, 2913, 9476, 2926, -1, 9482, 9476, 2913, -1, 2926, 9475, 2935, -1, 9476, 9475, 2926, -1, 2858, 9472, 2873, -1, 9473, 9472, 2858, -1, 2873, 9479, 2883, -1, 9472, 9479, 2873, -1, 2883, 9478, 2897, -1, 9479, 9478, 2883, -1, 2784, 9417, 2798, -1, 9414, 9417, 2784, -1, 2798, 9416, 2817, -1, 9417, 9416, 2798, -1, 2817, 9421, 2832, -1, 9416, 9421, 2817, -1, 2715, 9404, 2743, -1, 9405, 9404, 2715, -1, 2743, 9408, 2753, -1, 9404, 9408, 2743, -1, 2753, 9414, 2784, -1, 9408, 9414, 2753, -1, 9386, 2657, 2641, -1, 9386, 9390, 2657, -1, 2657, 9384, 2680, -1, 9390, 9384, 2657, -1, 9384, 2704, 2680, -1, 9384, 9383, 2704, -1, 11965, 2594, 2593, -1, 16468, 2594, 11965, -1, 16470, 2594, 16468, -1, 16471, 2594, 16470, -1, 16475, 2594, 16471, -1, 16475, 9381, 2594, -1, 9381, 9380, 2594, -1, 9380, 2612, 2594, -1, 9380, 9387, 2612, -1, 9387, 2641, 2612, -1, 9387, 9386, 2641, -1, 13555, 350, 11527, -1, 13556, 350, 13555, -1, 13558, 350, 13556, -1, 13559, 350, 13558, -1, 11527, 350, 349, -1, 13559, 13562, 350, -1, 13562, 14753, 350, -1, 14753, 373, 350, -1, 14753, 14751, 373, -1, 14751, 374, 373, -1, 14751, 14750, 374, -1, 14750, 3073, 374, -1, 14750, 14749, 3073, -1, 3073, 14746, 3067, -1, 14749, 14746, 3073, -1, 14746, 242, 3067, -1, 14746, 14745, 242, -1, 243, 9466, 3053, -1, 9467, 9466, 243, -1, 3053, 9464, 255, -1, 9466, 9464, 3053, -1, 255, 9462, 211, -1, 9464, 9462, 255, -1, 211, 9458, 3023, -1, 9462, 9458, 211, -1, 3023, 9452, 3024, -1, 9458, 9452, 3023, -1, 3024, 9447, 31, -1, 9452, 9447, 3024, -1, 33, 9493, 44, -1, 9494, 9493, 33, -1, 44, 9491, 45, -1, 9493, 9491, 44, -1, 45, 9490, 24, -1, 9491, 9490, 45, -1, 24, 9489, 2937, -1, 9490, 9489, 24, -1, 2937, 9485, 2938, -1, 9489, 9485, 2937, -1, 2938, 9484, 2928, -1, 9485, 9484, 2938, -1, 2910, 9432, 2909, -1, 9433, 9432, 2910, -1, 2909, 9430, 3344, -1, 9432, 9430, 2909, -1, 3344, 9428, 3318, -1, 9430, 9428, 3344, -1, 3318, 9424, 2838, -1, 9428, 9424, 3318, -1, 2838, 9418, 2823, -1, 9424, 9418, 2838, -1, 2823, 9413, 2804, -1, 9418, 9413, 2823, -1, 2789, 9401, 2790, -1, 9402, 9401, 2789, -1, 2790, 9398, 2791, -1, 9401, 9398, 2790, -1, 2791, 9397, 2764, -1, 9398, 9397, 2791, -1, 2764, 9399, 2707, -1, 9397, 9399, 2764, -1, 2707, 9393, 2688, -1, 9399, 9393, 2707, -1, 2688, 11956, 3217, -1, 2688, 16461, 11956, -1, 2688, 16477, 16461, -1, 9393, 9392, 2688, -1, 2688, 16480, 16477, -1, 9392, 16481, 2688, -1, 2688, 16481, 16480, -1, 356, 14726, 372, -1, 14731, 14726, 356, -1, 3092, 11511, 3093, -1, 3092, 13529, 11511, -1, 3092, 13527, 13529, -1, 372, 13530, 3092, -1, 14726, 13530, 372, -1, 3092, 13528, 13527, -1, 13530, 13532, 3092, -1, 3092, 13532, 13528, -1, 3061, 9344, 3068, -1, 9345, 9344, 3061, -1, 3068, 9351, 3076, -1, 9344, 9351, 3068, -1, 3076, 9350, 357, -1, 9351, 9350, 3076, -1, 235, 9340, 254, -1, 9341, 9340, 235, -1, 254, 9339, 3054, -1, 9340, 9339, 254, -1, 3054, 9345, 3061, -1, 9339, 9345, 3054, -1, 3003, 9369, 3025, -1, 9368, 9369, 3003, -1, 3025, 9375, 212, -1, 9369, 9375, 3025, -1, 212, 9374, 210, -1, 9375, 9374, 212, -1, 23, 9364, 43, -1, 9365, 9364, 23, -1, 43, 9363, 3002, -1, 9364, 9363, 43, -1, 3002, 9368, 3003, -1, 9363, 9368, 3002, -1, 2908, 9321, 2939, -1, 9320, 9321, 2908, -1, 2939, 9327, 2959, -1, 9321, 9327, 2939, -1, 2959, 9326, 25, -1, 9327, 9326, 2959, -1, 3336, 9316, 2906, -1, 9317, 9316, 3336, -1, 2906, 9315, 2907, -1, 9316, 9315, 2906, -1, 2907, 9320, 2908, -1, 9315, 9320, 2907, -1, 2803, 9297, 2821, -1, 9296, 9297, 2803, -1, 2821, 9303, 3317, -1, 9297, 9303, 2821, -1, 3317, 9302, 3329, -1, 9303, 9302, 3317, -1, 9293, 2787, 2765, -1, 9293, 9292, 2787, -1, 2787, 9291, 2788, -1, 9292, 9291, 2787, -1, 9291, 2803, 2788, -1, 9291, 9296, 2803, -1, 11945, 2687, 2685, -1, 16431, 2687, 11945, -1, 16433, 2687, 16431, -1, 16434, 2687, 16433, -1, 16438, 2687, 16434, -1, 9272, 2687, 16438, -1, 2687, 9271, 2762, -1, 9272, 9271, 2687, -1, 9271, 2763, 2762, -1, 9271, 9279, 2763, -1, 11495, 435, 434, -1, 13534, 435, 11495, -1, 13520, 435, 13534, -1, 13519, 435, 13520, -1, 13521, 435, 13519, -1, 13524, 435, 13521, -1, 435, 14727, 442, -1, 13524, 14727, 435, -1, 14727, 411, 442, -1, 14727, 14729, 411, -1, 9337, 364, 402, -1, 9337, 9336, 364, -1, 364, 9335, 340, -1, 9336, 9335, 364, -1, 9335, 341, 340, -1, 9335, 9353, 341, -1, 9353, 328, 341, -1, 9353, 9347, 328, -1, 328, 9331, 329, -1, 9347, 9331, 328, -1, 329, 9333, 306, -1, 9331, 9333, 329, -1, 288, 9358, 260, -1, 9361, 9358, 288, -1, 260, 9360, 261, -1, 9358, 9360, 260, -1, 261, 9377, 3047, -1, 9360, 9377, 261, -1, 3047, 9371, 225, -1, 9377, 9371, 3047, -1, 225, 9355, 226, -1, 9371, 9355, 225, -1, 226, 9357, 155, -1, 9355, 9357, 226, -1, 120, 9310, 63, -1, 9313, 9310, 120, -1, 63, 9312, 64, -1, 9310, 9312, 63, -1, 64, 9329, 2995, -1, 9312, 9329, 64, -1, 2995, 9323, 11, -1, 9329, 9323, 2995, -1, 11, 9307, 2998, -1, 9323, 9307, 11, -1, 2998, 9309, 2984, -1, 9307, 9309, 2998, -1, 2967, 9286, 2968, -1, 9289, 9286, 2967, -1, 2968, 9288, 3333, -1, 9286, 9288, 2968, -1, 3333, 9305, 3334, -1, 9288, 9305, 3333, -1, 3334, 9299, 3330, -1, 9305, 9299, 3334, -1, 3330, 9283, 2894, -1, 9299, 9283, 3330, -1, 2894, 9285, 2868, -1, 9283, 9285, 2894, -1, 2866, 9276, 2769, -1, 9274, 9276, 2866, -1, 2767, 11935, 3263, -1, 2767, 16424, 11935, -1, 2767, 16440, 16424, -1, 2769, 9282, 2767, -1, 9276, 9282, 2769, -1, 2767, 16443, 16440, -1, 9282, 16444, 2767, -1, 2767, 16444, 16443, -1, 3099, 14715, 3101, -1, 14711, 14715, 3099, -1, 3101, 14709, 441, -1, 14715, 14709, 3101, -1, 441, 11480, 446, -1, 441, 13490, 11480, -1, 441, 13488, 13490, -1, 14709, 13491, 441, -1, 441, 13489, 13488, -1, 13491, 13493, 441, -1, 441, 13493, 13489, -1, 363, 14707, 404, -1, 14708, 14707, 363, -1, 404, 14712, 3096, -1, 14707, 14712, 404, -1, 3096, 14711, 3099, -1, 14712, 14711, 3096, -1, 3083, 9227, 3086, -1, 9224, 9227, 3083, -1, 3086, 9226, 327, -1, 9227, 9226, 3086, -1, 327, 9231, 339, -1, 9226, 9231, 327, -1, 259, 9214, 289, -1, 9215, 9214, 259, -1, 289, 9218, 3078, -1, 9214, 9218, 289, -1, 3078, 9224, 3083, -1, 9218, 9224, 3078, -1, 3037, 9166, 3043, -1, 9162, 9166, 3037, -1, 3043, 9160, 224, -1, 9166, 9160, 3043, -1, 224, 9159, 230, -1, 9160, 9159, 224, -1, 62, 9156, 122, -1, 9157, 9156, 62, -1, 122, 9163, 3032, -1, 9156, 9163, 122, -1, 3032, 9162, 3037, -1, 9163, 9162, 3032, -1, 2983, 9193, 2986, -1, 9190, 9193, 2983, -1, 2986, 9192, 12, -1, 9193, 9192, 2986, -1, 12, 9197, 10, -1, 9192, 9197, 12, -1, 3345, 9180, 2969, -1, 9181, 9180, 3345, -1, 2969, 9184, 2970, -1, 9180, 9184, 2969, -1, 2970, 9190, 2983, -1, 9184, 9190, 2970, -1, 9254, 2880, 2869, -1, 9254, 9258, 2880, -1, 2880, 9252, 2895, -1, 9258, 9252, 2880, -1, 9252, 3332, 2895, -1, 9252, 9251, 3332, -1, 11926, 3290, 3291, -1, 16394, 3290, 11926, -1, 16396, 3290, 16394, -1, 16397, 3290, 16396, -1, 16401, 3290, 16397, -1, 16401, 9249, 3290, -1, 9249, 9248, 3290, -1, 9248, 2867, 3290, -1, 9248, 9255, 2867, -1, 9255, 2869, 2867, -1, 9255, 9254, 2869, -1, 13476, 3396, 11466, -1, 13477, 3396, 13476, -1, 13479, 3396, 13477, -1, 13480, 3396, 13479, -1, 11466, 3396, 3395, -1, 13480, 13483, 3396, -1, 13483, 14725, 3396, -1, 14725, 3398, 3396, -1, 14725, 14723, 3398, -1, 14723, 448, 3398, -1, 14723, 14722, 448, -1, 14722, 444, 448, -1, 14722, 14721, 444, -1, 444, 14718, 430, -1, 14721, 14718, 444, -1, 14718, 418, 430, -1, 14718, 14717, 418, -1, 422, 9242, 409, -1, 9243, 9242, 422, -1, 409, 9240, 410, -1, 9242, 9240, 409, -1, 410, 9238, 392, -1, 9240, 9238, 410, -1, 392, 9234, 342, -1, 9238, 9234, 392, -1, 342, 9228, 322, -1, 9234, 9228, 342, -1, 322, 9223, 317, -1, 9228, 9223, 322, -1, 314, 9177, 300, -1, 9178, 9177, 314, -1, 300, 9174, 301, -1, 9177, 9174, 300, -1, 301, 9173, 281, -1, 9174, 9173, 301, -1, 281, 9175, 250, -1, 9173, 9175, 281, -1, 250, 9169, 202, -1, 9175, 9169, 250, -1, 202, 9168, 201, -1, 9169, 9168, 202, -1, 180, 9208, 148, -1, 9209, 9208, 180, -1, 148, 9206, 149, -1, 9208, 9206, 148, -1, 149, 9204, 103, -1, 9206, 9204, 149, -1, 103, 9200, 38, -1, 9204, 9200, 103, -1, 38, 9194, 19, -1, 9200, 9194, 38, -1, 19, 9189, 3385, -1, 9194, 9189, 19, -1, 3373, 9269, 3367, -1, 9270, 9269, 3373, -1, 3367, 9266, 3368, -1, 9269, 9266, 3367, -1, 3368, 9265, 7, -1, 9266, 9265, 3368, -1, 7, 9267, 5, -1, 9265, 9267, 7, -1, 5, 9261, 0, -1, 9267, 9261, 5, -1, 0, 11913, 3, -1, 0, 16387, 11913, -1, 0, 16403, 16387, -1, 9261, 9260, 0, -1, 0, 16406, 16403, -1, 9260, 16407, 0, -1, 0, 16407, 16406, -1, 19179, 10501, 19250, -1, 10506, 10501, 19179, -1, 19283, 11449, 11446, -1, 19283, 13941, 11449, -1, 19283, 13939, 13941, -1, 19250, 10500, 19283, -1, 10501, 10500, 19250, -1, 19283, 13940, 13939, -1, 10500, 13943, 19283, -1, 19283, 13943, 13940, -1, 427, 10524, 18863, -1, 10525, 10524, 427, -1, 18863, 10531, 18956, -1, 10524, 10531, 18863, -1, 18956, 10530, 19075, -1, 10531, 10530, 18956, -1, 18679, 10520, 18696, -1, 10521, 10520, 18679, -1, 18696, 10519, 18705, -1, 10520, 10519, 18696, -1, 18705, 10525, 427, -1, 10519, 10525, 18705, -1, 316, 10596, 18604, -1, 10597, 10596, 316, -1, 18604, 10603, 18615, -1, 10596, 10603, 18604, -1, 18615, 10602, 18652, -1, 10603, 10602, 18615, -1, 18556, 10592, 18563, -1, 10593, 10592, 18556, -1, 18563, 10591, 18573, -1, 10592, 10591, 18563, -1, 18573, 10597, 316, -1, 10591, 10597, 18573, -1, 200, 10573, 18498, -1, 10572, 10573, 200, -1, 18498, 10579, 18509, -1, 10573, 10579, 18498, -1, 18509, 10578, 18538, -1, 10579, 10578, 18509, -1, 18448, 10568, 18452, -1, 10569, 10568, 18448, -1, 18452, 10567, 18465, -1, 10568, 10567, 18452, -1, 18465, 10572, 200, -1, 10567, 10572, 18465, -1, 20, 10549, 18419, -1, 10548, 10549, 20, -1, 18419, 10555, 18428, -1, 10549, 10555, 18419, -1, 18428, 10554, 18443, -1, 10555, 10554, 18428, -1, 10545, 18398, 18389, -1, 10545, 10544, 18398, -1, 18398, 10543, 18400, -1, 10544, 10543, 18398, -1, 10543, 20, 18400, -1, 10543, 10548, 20, -1, 11898, 18370, 11897, -1, 16838, 18370, 11898, -1, 16840, 18370, 16838, -1, 16841, 18370, 16840, -1, 16845, 18370, 16841, -1, 14891, 18370, 16845, -1, 18370, 14890, 18374, -1, 14891, 14890, 18370, -1, 14890, 18385, 18374, -1, 14890, 14898, 18385, -1, 11468, 1943, 1942, -1, 13437, 1943, 11468, -1, 13438, 1943, 13437, -1, 13440, 1943, 13438, -1, 13441, 1943, 13440, -1, 13444, 1943, 13441, -1, 1943, 14699, 1976, -1, 13444, 14699, 1943, -1, 14699, 1766, 1976, -1, 14699, 14701, 1766, -1, 11085, 1676, 1657, -1, 11085, 11084, 1676, -1, 1676, 11083, 2102, -1, 11084, 11083, 1676, -1, 11083, 2088, 2102, -1, 11083, 11101, 2088, -1, 11101, 2074, 2088, -1, 11101, 11095, 2074, -1, 2074, 11079, 1238, -1, 11095, 11079, 2074, -1, 1238, 11081, 1011, -1, 11079, 11081, 1238, -1, 914, 11058, 922, -1, 11061, 11058, 914, -1, 922, 11060, 2007, -1, 11058, 11060, 922, -1, 2007, 11077, 1995, -1, 11060, 11077, 2007, -1, 1995, 11071, 1996, -1, 11077, 11071, 1995, -1, 1996, 11055, 540, -1, 11071, 11055, 1996, -1, 540, 11057, 398, -1, 11055, 11057, 540, -1, 359, 11142, 360, -1, 11145, 11142, 359, -1, 360, 11144, 1919, -1, 11142, 11144, 360, -1, 1919, 11161, 1898, -1, 11144, 11161, 1919, -1, 1898, 11155, 1899, -1, 11161, 11155, 1898, -1, 1899, 11139, 253, -1, 11155, 11139, 1899, -1, 253, 11141, 157, -1, 11139, 11141, 253, -1, 118, 11118, 119, -1, 11121, 11118, 118, -1, 119, 11120, 1826, -1, 11118, 11120, 119, -1, 1826, 11137, 1808, -1, 11120, 11137, 1826, -1, 1808, 11131, 1791, -1, 11137, 11131, 1808, -1, 1791, 11115, 1792, -1, 11131, 11115, 1791, -1, 1792, 11117, 3358, -1, 11115, 11117, 1792, -1, 1718, 11108, 1701, -1, 11106, 11108, 1718, -1, 1699, 11838, 3315, -1, 1699, 16350, 11838, -1, 1699, 16366, 16350, -1, 1701, 11114, 1699, -1, 11108, 11114, 1701, -1, 1699, 16369, 16366, -1, 11114, 16370, 1699, -1, 1699, 16370, 16369, -1, 1910, 14687, 1973, -1, 14683, 14687, 1910, -1, 1973, 14681, 2012, -1, 14687, 14681, 1973, -1, 2012, 11483, 2173, -1, 2012, 13412, 11483, -1, 2012, 13410, 13412, -1, 14681, 13413, 2012, -1, 2012, 13411, 13410, -1, 13413, 13415, 2012, -1, 2012, 13415, 13411, -1, 1562, 14679, 1675, -1, 14680, 14679, 1562, -1, 1675, 14684, 1802, -1, 14679, 14684, 1675, -1, 1802, 14683, 1910, -1, 14684, 14683, 1802, -1, 1175, 9111, 1235, -1, 9108, 9111, 1175, -1, 1235, 9110, 1277, -1, 9111, 9110, 1235, -1, 1277, 9115, 1559, -1, 9110, 9115, 1277, -1, 2006, 9098, 921, -1, 9099, 9098, 2006, -1, 921, 9102, 1051, -1, 9098, 9102, 921, -1, 1051, 9108, 1175, -1, 9102, 9108, 1051, -1, 471, 9142, 537, -1, 9138, 9142, 471, -1, 537, 9136, 569, -1, 9142, 9136, 537, -1, 569, 9135, 1997, -1, 9136, 9135, 569, -1, 1918, 9132, 358, -1, 9133, 9132, 1918, -1, 358, 9139, 407, -1, 9132, 9139, 358, -1, 407, 9138, 471, -1, 9139, 9138, 407, -1, 227, 9053, 251, -1, 9050, 9053, 227, -1, 251, 9052, 262, -1, 9053, 9052, 251, -1, 262, 9057, 1896, -1, 9052, 9057, 262, -1, 27, 9040, 117, -1, 9041, 9040, 27, -1, 117, 9044, 176, -1, 9040, 9044, 117, -1, 176, 9050, 227, -1, 9044, 9050, 176, -1, 9080, 3389, 3378, -1, 9080, 9084, 3389, -1, 3389, 9078, 1793, -1, 9084, 9078, 3389, -1, 9078, 28, 1793, -1, 9078, 9077, 28, -1, 11825, 1704, 1703, -1, 16320, 1704, 11825, -1, 16322, 1704, 16320, -1, 16323, 1704, 16322, -1, 16327, 1704, 16323, -1, 16327, 9075, 1704, -1, 9075, 9074, 1704, -1, 9074, 3357, 1704, -1, 9074, 9081, 3357, -1, 9081, 3378, 3357, -1, 9081, 9080, 3378, -1, 13399, 2290, 11498, -1, 13400, 2290, 13399, -1, 13402, 2290, 13400, -1, 13403, 2290, 13402, -1, 11498, 2290, 2339, -1, 13403, 13406, 2290, -1, 13406, 14697, 2290, -1, 14697, 2247, 2290, -1, 14697, 14695, 2247, -1, 14695, 2229, 2247, -1, 14695, 14694, 2229, -1, 14694, 2204, 2229, -1, 14694, 14693, 2204, -1, 2204, 14690, 1922, -1, 14693, 14690, 2204, -1, 14690, 1806, 1922, -1, 14690, 14689, 1806, -1, 1807, 9126, 1904, -1, 9127, 9126, 1807, -1, 1904, 9124, 2151, -1, 9126, 9124, 1904, -1, 2151, 9122, 2145, -1, 9124, 9122, 2151, -1, 2145, 9118, 1416, -1, 9122, 9118, 2145, -1, 1416, 9112, 1226, -1, 9118, 9112, 1416, -1, 1226, 9107, 1227, -1, 9112, 9107, 1226, -1, 1210, 9153, 1208, -1, 9154, 9153, 1210, -1, 1208, 9151, 2058, -1, 9153, 9151, 1208, -1, 2058, 9150, 2049, -1, 9151, 9150, 2058, -1, 2049, 9149, 707, -1, 9150, 9149, 2049, -1, 707, 9145, 518, -1, 9149, 9145, 707, -1, 518, 9144, 519, -1, 9145, 9144, 518, -1, 511, 9068, 509, -1, 9069, 9068, 511, -1, 509, 9066, 1979, -1, 9068, 9066, 509, -1, 1979, 9064, 1968, -1, 9066, 9064, 1979, -1, 1968, 9060, 1932, -1, 9064, 9060, 1968, -1, 1932, 9054, 239, -1, 9060, 9054, 1932, -1, 239, 9049, 187, -1, 9054, 9049, 239, -1, 153, 9095, 237, -1, 9096, 9095, 153, -1, 237, 9092, 1869, -1, 9095, 9092, 237, -1, 1869, 9091, 1860, -1, 9092, 9091, 1869, -1, 1860, 9093, 1845, -1, 9091, 9093, 1860, -1, 1845, 9087, 1840, -1, 9093, 9087, 1845, -1, 1840, 11803, 3372, -1, 1840, 16313, 11803, -1, 1840, 16329, 16313, -1, 9087, 9086, 1840, -1, 1840, 16332, 16329, -1, 9086, 16333, 1840, -1, 1840, 16333, 16332, -1, 2246, 14642, 2261, -1, 14647, 14642, 2246, -1, 2289, 11515, 2496, -1, 2289, 13295, 11515, -1, 2289, 13293, 13295, -1, 2261, 13296, 2289, -1, 14642, 13296, 2261, -1, 2289, 13294, 13293, -1, 13296, 13298, 2289, -1, 2289, 13298, 13294, -1, 1903, 8805, 2203, -1, 8804, 8805, 1903, -1, 2203, 8811, 2215, -1, 8805, 8811, 2203, -1, 2215, 8810, 2228, -1, 8811, 8810, 2215, -1, 1830, 8800, 2157, -1, 8801, 8800, 1830, -1, 2157, 8799, 1907, -1, 8800, 8799, 2157, -1, 1907, 8804, 1903, -1, 8799, 8804, 1907, -1, 1207, 8756, 1415, -1, 8757, 8756, 1207, -1, 1415, 8763, 2135, -1, 8756, 8763, 1415, -1, 2135, 8762, 1831, -1, 8763, 8762, 2135, -1, 1193, 8752, 2066, -1, 8753, 8752, 1193, -1, 2066, 8751, 1209, -1, 8752, 8751, 2066, -1, 1209, 8757, 1207, -1, 8751, 8757, 1209, -1, 508, 8781, 706, -1, 8780, 8781, 508, -1, 706, 8787, 2042, -1, 8781, 8787, 706, -1, 2042, 8786, 1188, -1, 8787, 8786, 2042, -1, 500, 8776, 1989, -1, 8777, 8776, 500, -1, 1989, 8775, 510, -1, 8776, 8775, 1989, -1, 510, 8780, 508, -1, 8775, 8780, 510, -1, 236, 8733, 1933, -1, 8732, 8733, 236, -1, 1933, 8739, 1939, -1, 8733, 8739, 1933, -1, 1939, 8738, 497, -1, 8739, 8738, 1939, -1, 8729, 1881, 220, -1, 8729, 8728, 1881, -1, 1881, 8727, 238, -1, 8728, 8727, 1881, -1, 8727, 236, 238, -1, 8727, 8732, 236, -1, 11792, 1841, 3376, -1, 16209, 1841, 11792, -1, 16211, 1841, 16209, -1, 16212, 1841, 16211, -1, 16216, 1841, 16212, -1, 8708, 1841, 16216, -1, 1841, 8707, 1846, -1, 8708, 8707, 1841, -1, 8707, 221, 1846, -1, 8707, 8715, 221, -1, 11587, 2599, 3181, -1, 13359, 2599, 11587, -1, 13360, 2599, 13359, -1, 13362, 2599, 13360, -1, 13363, 2599, 13362, -1, 13366, 2599, 13363, -1, 2599, 14671, 2568, -1, 13366, 14671, 2599, -1, 14671, 2551, 2568, -1, 14671, 14673, 2551, -1, 8937, 2519, 2520, -1, 8937, 8936, 2519, -1, 2519, 8935, 3122, -1, 8936, 8935, 2519, -1, 8935, 3123, 3122, -1, 8935, 8953, 3123, -1, 8953, 2451, 3123, -1, 8953, 8947, 2451, -1, 2451, 8931, 2433, -1, 8947, 8931, 2451, -1, 2433, 8933, 2422, -1, 8931, 8933, 2433, -1, 2400, 8958, 2397, -1, 8961, 8958, 2400, -1, 2397, 8960, 2308, -1, 8958, 8960, 2397, -1, 2308, 8977, 2309, -1, 8960, 8977, 2308, -1, 2309, 8971, 2310, -1, 8977, 8971, 2309, -1, 2310, 8955, 2314, -1, 8971, 8955, 2310, -1, 2314, 8957, 2283, -1, 8955, 8957, 2314, -1, 2259, 8982, 2159, -1, 8985, 8982, 2259, -1, 2159, 8984, 2160, -1, 8982, 8984, 2159, -1, 2160, 9001, 2192, -1, 8984, 9001, 2160, -1, 2192, 8995, 2078, -1, 9001, 8995, 2192, -1, 2078, 8979, 2079, -1, 8995, 8979, 2078, -1, 2079, 8981, 1888, -1, 8979, 8981, 2079, -1, 1889, 9006, 1615, -1, 9009, 9006, 1889, -1, 1615, 9008, 1498, -1, 9006, 9008, 1615, -1, 1498, 9025, 1499, -1, 9008, 9025, 1498, -1, 1499, 9019, 1502, -1, 9025, 9019, 1499, -1, 1502, 9003, 2105, -1, 9019, 9003, 1502, -1, 2105, 9005, 1153, -1, 9003, 9005, 2105, -1, 1154, 9032, 839, -1, 9030, 9032, 1154, -1, 665, 11716, 666, -1, 665, 16276, 11716, -1, 665, 16292, 16276, -1, 839, 9038, 665, -1, 9032, 9038, 839, -1, 665, 16295, 16292, -1, 9038, 16296, 665, -1, 665, 16296, 16295, -1, 2534, 14659, 2550, -1, 14655, 14659, 2534, -1, 2550, 14653, 2596, -1, 14659, 14653, 2550, -1, 2596, 11600, 2597, -1, 2596, 13334, 11600, -1, 2596, 13332, 13334, -1, 14653, 13335, 2596, -1, 2596, 13333, 13332, -1, 13335, 13337, 2596, -1, 2596, 13337, 13333, -1, 2516, 14651, 2517, -1, 14652, 14651, 2516, -1, 2517, 14656, 2518, -1, 14651, 14656, 2517, -1, 2518, 14655, 2534, -1, 14656, 14655, 2518, -1, 2417, 8829, 2423, -1, 8826, 8829, 2417, -1, 2423, 8828, 2432, -1, 8829, 8828, 2423, -1, 2432, 8833, 2450, -1, 8828, 8833, 2432, -1, 2350, 8816, 2398, -1, 8817, 8816, 2350, -1, 2398, 8820, 2399, -1, 8816, 8820, 2398, -1, 2399, 8826, 2417, -1, 8820, 8826, 2399, -1, 2280, 8884, 2298, -1, 8880, 8884, 2280, -1, 2298, 8878, 2313, -1, 8884, 8878, 2298, -1, 2313, 8877, 2311, -1, 8878, 8877, 2313, -1, 2158, 8874, 2257, -1, 8875, 8874, 2158, -1, 2257, 8881, 2258, -1, 8874, 8881, 2257, -1, 2258, 8880, 2280, -1, 8881, 8880, 2258, -1, 2180, 8911, 2185, -1, 8908, 8911, 2180, -1, 2185, 8910, 2077, -1, 8911, 8910, 2185, -1, 2077, 8915, 2103, -1, 8910, 8915, 2077, -1, 1613, 8898, 2162, -1, 8899, 8898, 1613, -1, 2162, 8902, 2163, -1, 8898, 8902, 2162, -1, 2163, 8908, 2180, -1, 8902, 8908, 2163, -1, 8856, 2091, 2076, -1, 8856, 8860, 2091, -1, 2091, 8854, 2107, -1, 8860, 8854, 2091, -1, 8854, 1497, 2107, -1, 8854, 8853, 1497, -1, 11705, 971, 972, -1, 16246, 971, 11705, -1, 16248, 971, 16246, -1, 16249, 971, 16248, -1, 16253, 971, 16249, -1, 16253, 8851, 971, -1, 8851, 8850, 971, -1, 8850, 2061, 971, -1, 8850, 8857, 2061, -1, 8857, 2076, 2061, -1, 8857, 8856, 2076, -1, 13320, 2694, 11618, -1, 13321, 2694, 13320, -1, 13323, 2694, 13321, -1, 13324, 2694, 13323, -1, 11618, 2694, 3224, -1, 13324, 13327, 2694, -1, 13327, 14669, 2694, -1, 14669, 2661, 2694, -1, 14669, 14667, 2661, -1, 14667, 2614, 2661, -1, 14667, 14666, 2614, -1, 14666, 2601, 2614, -1, 14666, 14665, 2601, -1, 2601, 14662, 2571, -1, 14665, 14662, 2601, -1, 14662, 2572, 2571, -1, 14662, 14661, 2572, -1, 2537, 8844, 2528, -1, 8845, 8844, 2537, -1, 2528, 8842, 2529, -1, 8844, 8842, 2528, -1, 2529, 8840, 2482, -1, 8842, 8840, 2529, -1, 2482, 8836, 2462, -1, 8840, 8836, 2482, -1, 2462, 8830, 2463, -1, 8836, 8830, 2462, -1, 2463, 8825, 2403, -1, 8830, 8825, 2463, -1, 2402, 8895, 2407, -1, 8896, 8895, 2402, -1, 2407, 8892, 2408, -1, 8895, 8892, 2407, -1, 2408, 8891, 2355, -1, 8892, 8891, 2408, -1, 2355, 8893, 2326, -1, 8891, 8893, 2355, -1, 2326, 8887, 2327, -1, 8893, 8887, 2326, -1, 2327, 8886, 2264, -1, 8887, 8886, 2327, -1, 2263, 8926, 2276, -1, 8927, 8926, 2263, -1, 2276, 8924, 2277, -1, 8926, 8924, 2276, -1, 2277, 8922, 2222, -1, 8924, 8922, 2277, -1, 2222, 8918, 2212, -1, 8922, 8918, 2222, -1, 2212, 8912, 2200, -1, 8918, 8912, 2212, -1, 2200, 8907, 1937, -1, 8912, 8907, 2200, -1, 1871, 8871, 2165, -1, 8872, 8871, 1871, -1, 2165, 8868, 2166, -1, 8871, 8868, 2165, -1, 2166, 8867, 1730, -1, 8868, 8867, 2166, -1, 1730, 8869, 1731, -1, 8867, 8869, 1730, -1, 1731, 8863, 1303, -1, 8869, 8863, 1731, -1, 1303, 11683, 1304, -1, 1303, 16239, 11683, -1, 1303, 16255, 16239, -1, 8863, 8862, 1303, -1, 1303, 16258, 16255, -1, 8862, 16259, 1303, -1, 1303, 16259, 16258, -1, 3222, 14782, 2662, -1, 14787, 14782, 3222, -1, 2691, 11624, 2692, -1, 2691, 13687, 11624, -1, 2691, 13685, 13687, -1, 2662, 13688, 2691, -1, 14782, 13688, 2662, -1, 2691, 13686, 13685, -1, 13688, 13690, 2691, -1, 2691, 13690, 13686, -1, 2553, 9792, 2573, -1, 9793, 9792, 2553, -1, 2573, 9799, 2615, -1, 9792, 9799, 2573, -1, 2615, 9798, 3214, -1, 9799, 9798, 2615, -1, 3166, 9788, 2530, -1, 9789, 9788, 3166, -1, 2530, 9787, 2536, -1, 9788, 9787, 2530, -1, 2536, 9793, 2553, -1, 9787, 9793, 2536, -1, 2420, 9817, 2461, -1, 9816, 9817, 2420, -1, 2461, 9823, 2481, -1, 9817, 9823, 2461, -1, 2481, 9822, 3158, -1, 9823, 9822, 2481, -1, 3098, 9812, 2409, -1, 9813, 9812, 3098, -1, 2409, 9811, 2419, -1, 9812, 9811, 2409, -1, 2419, 9816, 2420, -1, 9811, 9816, 2419, -1, 2296, 9732, 2328, -1, 9733, 9732, 2296, -1, 2328, 9739, 2356, -1, 9732, 9739, 2328, -1, 2356, 9738, 3051, -1, 9739, 9738, 2356, -1, 2475, 9728, 2278, -1, 9729, 9728, 2475, -1, 2278, 9727, 2295, -1, 9728, 9727, 2278, -1, 2295, 9733, 2296, -1, 9727, 9733, 2295, -1, 2189, 9756, 2201, -1, 9757, 9756, 2189, -1, 2201, 9763, 2223, -1, 9756, 9763, 2201, -1, 2223, 9762, 2388, -1, 9763, 9762, 2223, -1, 9753, 1985, 1928, -1, 9753, 9752, 1985, -1, 1985, 9751, 2182, -1, 9752, 9751, 1985, -1, 9751, 2189, 2182, -1, 9751, 9757, 2189, -1, 11675, 2112, 2111, -1, 16579, 2112, 11675, -1, 16581, 2112, 16579, -1, 16582, 2112, 16581, -1, 16586, 2112, 16582, -1, 9768, 2112, 16586, -1, 2112, 9767, 1732, -1, 9768, 9767, 2112, -1, 9767, 1856, 1732, -1, 9767, 9775, 1856, -1, 11529, 2375, 2924, -1, 13282, 2375, 11529, -1, 13283, 2375, 13282, -1, 13285, 2375, 13283, -1, 13286, 2375, 13285, -1, 13289, 2375, 13286, -1, 2375, 14643, 2359, -1, 13289, 14643, 2375, -1, 14643, 2335, 2359, -1, 14643, 14645, 2335, -1, 8797, 2293, 2306, -1, 8797, 8796, 2293, -1, 2293, 8795, 2272, -1, 8796, 8795, 2293, -1, 8795, 2249, 2272, -1, 8795, 8813, 2249, -1, 8813, 2232, 2249, -1, 8813, 8807, 2232, -1, 2232, 8791, 2220, -1, 8807, 8791, 2232, -1, 2220, 8793, 2072, -1, 8791, 8793, 2220, -1, 2016, 8746, 2176, -1, 8749, 8746, 2016, -1, 2176, 8748, 2153, -1, 8746, 8748, 2176, -1, 2153, 8765, 2154, -1, 8748, 8765, 2153, -1, 2154, 8759, 2147, -1, 8765, 8759, 2154, -1, 2147, 8743, 2137, -1, 8759, 8743, 2147, -1, 2137, 8745, 1467, -1, 8743, 8745, 2137, -1, 1468, 8770, 2081, -1, 8773, 8770, 1468, -1, 2081, 8772, 2068, -1, 8770, 8772, 2081, -1, 2068, 8789, 2069, -1, 8772, 8789, 2068, -1, 2069, 8783, 2056, -1, 8789, 8783, 2069, -1, 2056, 8767, 2045, -1, 8783, 8767, 2056, -1, 2045, 8769, 737, -1, 8767, 8769, 2045, -1, 744, 8722, 2002, -1, 8725, 8722, 744, -1, 2002, 8724, 1993, -1, 8722, 8724, 2002, -1, 1993, 8741, 1986, -1, 8724, 8741, 1993, -1, 1986, 8735, 1974, -1, 8741, 8735, 1986, -1, 1974, 8719, 1950, -1, 8735, 8719, 1974, -1, 1950, 8721, 290, -1, 8719, 8721, 1950, -1, 291, 8712, 1886, -1, 8710, 8712, 291, -1, 124, 11780, 125, -1, 124, 16202, 11780, -1, 124, 16218, 16202, -1, 1886, 8718, 124, -1, 8712, 8718, 1886, -1, 124, 16221, 16218, -1, 8718, 16222, 124, -1, 124, 16222, 16221, -1, 2336, 14631, 2337, -1, 14627, 14631, 2336, -1, 2337, 14625, 2358, -1, 14631, 14625, 2337, -1, 2358, 11546, 2376, -1, 2358, 13256, 11546, -1, 2358, 13254, 13256, -1, 14625, 13257, 2358, -1, 2358, 13255, 13254, -1, 13257, 13259, 2358, -1, 2358, 13259, 13255, -1, 2273, 14623, 2292, -1, 14624, 14623, 2273, -1, 2292, 14628, 2305, -1, 14623, 14628, 2292, -1, 2305, 14627, 2336, -1, 14628, 14627, 2305, -1, 2206, 8605, 2208, -1, 8602, 8605, 2206, -1, 2208, 8604, 2219, -1, 8605, 8604, 2208, -1, 2219, 8609, 2231, -1, 8604, 8609, 2219, -1, 1957, 8592, 2177, -1, 8593, 8592, 1957, -1, 2177, 8596, 2187, -1, 8592, 8596, 2177, -1, 2187, 8602, 2206, -1, 8596, 8602, 2187, -1, 2127, 8636, 2128, -1, 8632, 8636, 2127, -1, 2128, 8630, 2141, -1, 8636, 8630, 2128, -1, 2141, 8629, 1958, -1, 8630, 8629, 2141, -1, 1182, 8626, 2083, -1, 8627, 8626, 1182, -1, 2083, 8633, 2093, -1, 8626, 8633, 2083, -1, 2093, 8632, 2127, -1, 8633, 8632, 2093, -1, 2032, 8663, 2033, -1, 8660, 8663, 2032, -1, 2033, 8662, 2046, -1, 8663, 8662, 2033, -1, 2046, 8667, 1183, -1, 8662, 8667, 2046, -1, 459, 8650, 2001, -1, 8651, 8650, 459, -1, 2001, 8654, 2013, -1, 8650, 8654, 2001, -1, 2013, 8660, 2032, -1, 8654, 8660, 2013, -1, 8690, 1935, 1924, -1, 8690, 8694, 1935, -1, 1935, 8688, 1949, -1, 8694, 8688, 1935, -1, 8688, 460, 1949, -1, 8688, 8687, 460, -1, 11767, 1890, 1887, -1, 16172, 1890, 11767, -1, 16174, 1890, 16172, -1, 16175, 1890, 16174, -1, 16179, 1890, 16175, -1, 16179, 8685, 1890, -1, 8685, 8684, 1890, -1, 8684, 1906, 1890, -1, 8684, 8691, 1906, -1, 8691, 1924, 1906, -1, 8691, 8690, 1924, -1, 13242, 3132, 11562, -1, 13243, 3132, 13242, -1, 13245, 3132, 13243, -1, 13246, 3132, 13245, -1, 11562, 3132, 3131, -1, 13246, 13249, 3132, -1, 13249, 14641, 3132, -1, 14641, 2473, 3132, -1, 14641, 14639, 2473, -1, 14639, 2446, 2473, -1, 14639, 14638, 2446, -1, 14638, 2385, 2446, -1, 14638, 14637, 2385, -1, 2385, 14634, 2362, -1, 14637, 14634, 2385, -1, 14634, 2361, 2362, -1, 14634, 14633, 2361, -1, 2341, 8620, 2342, -1, 8621, 8620, 2341, -1, 2342, 8618, 2331, -1, 8620, 8618, 2342, -1, 2331, 8616, 2317, -1, 8618, 8616, 2331, -1, 2317, 8612, 2236, -1, 8616, 8612, 2317, -1, 2236, 8606, 2237, -1, 8612, 8606, 2236, -1, 2237, 8601, 2117, -1, 8606, 8601, 2237, -1, 2122, 8647, 2139, -1, 8648, 8647, 2122, -1, 2139, 8644, 2140, -1, 8647, 8644, 2139, -1, 2140, 8643, 1977, -1, 8644, 8643, 2140, -1, 1977, 8645, 1970, -1, 8643, 8645, 1977, -1, 1970, 8639, 2149, -1, 8645, 8639, 1970, -1, 2149, 8638, 1549, -1, 8639, 8638, 2149, -1, 1439, 8678, 1594, -1, 8679, 8678, 1439, -1, 1594, 8676, 1595, -1, 8678, 8676, 1594, -1, 1595, 8674, 1294, -1, 8676, 8674, 1595, -1, 1294, 8670, 1289, -1, 8674, 8670, 1294, -1, 1289, 8664, 2051, -1, 8670, 8664, 1289, -1, 2051, 8659, 819, -1, 8664, 8659, 2051, -1, 716, 8705, 862, -1, 8706, 8705, 716, -1, 862, 8702, 863, -1, 8705, 8702, 862, -1, 863, 8701, 555, -1, 8702, 8701, 863, -1, 555, 8703, 551, -1, 8701, 8703, 555, -1, 551, 8697, 324, -1, 8703, 8697, 551, -1, 324, 11747, 325, -1, 324, 16165, 11747, -1, 324, 16181, 16165, -1, 8697, 8696, 324, -1, 324, 16184, 16181, -1, 8696, 16185, 324, -1, 324, 16185, 16184, -1, 2474, 14670, 2472, -1, 14675, 14670, 2474, -1, 3140, 11574, 3143, -1, 3140, 13373, 11574, -1, 3140, 13371, 13373, -1, 2472, 13374, 3140, -1, 14670, 13374, 2472, -1, 3140, 13372, 13371, -1, 13374, 13376, 3140, -1, 3140, 13376, 13372, -1, 2344, 8944, 2384, -1, 8945, 8944, 2344, -1, 2384, 8951, 2447, -1, 8944, 8951, 2384, -1, 2447, 8950, 2448, -1, 8951, 8950, 2447, -1, 2330, 8940, 2333, -1, 8941, 8940, 2330, -1, 2333, 8939, 2343, -1, 8940, 8939, 2333, -1, 2343, 8945, 2344, -1, 8939, 8945, 2343, -1, 2217, 8968, 2238, -1, 8969, 8968, 2217, -1, 2238, 8975, 2318, -1, 8968, 8975, 2238, -1, 2318, 8974, 2319, -1, 8975, 8974, 2318, -1, 2131, 8964, 2138, -1, 8965, 8964, 2131, -1, 2138, 8963, 2178, -1, 8964, 8963, 2138, -1, 2178, 8969, 2217, -1, 8963, 8969, 2178, -1, 2143, 8992, 1971, -1, 8993, 8992, 2143, -1, 1971, 8999, 1969, -1, 8992, 8999, 1971, -1, 1969, 8998, 2132, -1, 8999, 8998, 1969, -1, 1671, 8988, 1593, -1, 8989, 8988, 1671, -1, 1593, 8987, 1634, -1, 8988, 8987, 1593, -1, 1634, 8993, 2143, -1, 8987, 8993, 1634, -1, 2035, 9016, 1290, -1, 9017, 9016, 2035, -1, 1290, 9023, 1288, -1, 9016, 9023, 1290, -1, 1288, 9022, 1662, -1, 9023, 9022, 1288, -1, 9013, 861, 930, -1, 9013, 9012, 861, -1, 861, 9011, 904, -1, 9012, 9011, 861, -1, 9011, 2035, 904, -1, 9011, 9017, 2035, -1, 11731, 552, 1954, -1, 16283, 552, 11731, -1, 16285, 552, 16283, -1, 16286, 552, 16285, -1, 16290, 552, 16286, -1, 9028, 552, 16290, -1, 552, 9027, 550, -1, 9028, 9027, 552, -1, 9027, 927, 550, -1, 9027, 9035, 927, -1, 11378, 18580, 11376, -1, 13206, 18580, 11378, -1, 13207, 18580, 13206, -1, 13209, 18580, 13207, -1, 13210, 18580, 13209, -1, 8566, 18580, 13210, -1, 18580, 8558, 21191, -1, 8566, 8558, 18580, -1, 8558, 18534, 21191, -1, 8558, 8560, 18534, -1, 8573, 21166, 18507, -1, 8573, 8572, 21166, -1, 21166, 8571, 21155, -1, 8572, 8571, 21166, -1, 8571, 21156, 21155, -1, 8571, 8589, 21156, -1, 8589, 21148, 21156, -1, 8589, 8583, 21148, -1, 21148, 8567, 21142, -1, 8583, 8567, 21148, -1, 21142, 8569, 21133, -1, 8567, 8569, 21142, -1, 21117, 8486, 21108, -1, 8489, 8486, 21117, -1, 21108, 8488, 21083, -1, 8486, 8488, 21108, -1, 21083, 8505, 21084, -1, 8488, 8505, 21083, -1, 21084, 8499, 21066, -1, 8505, 8499, 21084, -1, 21066, 8483, 21058, -1, 8499, 8483, 21066, -1, 21058, 8485, 21033, -1, 8483, 8485, 21058, -1, 21018, 8510, 21008, -1, 8513, 8510, 21018, -1, 21008, 8512, 20992, -1, 8510, 8512, 21008, -1, 20992, 8529, 20993, -1, 8512, 8529, 20992, -1, 20993, 8523, 20966, -1, 8529, 8523, 20993, -1, 20966, 8507, 20952, -1, 8523, 8507, 20966, -1, 20952, 8509, 20920, -1, 8507, 8509, 20952, -1, 20894, 8534, 20884, -1, 8537, 8534, 20894, -1, 20884, 8536, 20854, -1, 8534, 8536, 20884, -1, 20854, 8553, 20855, -1, 8536, 8553, 20854, -1, 20855, 8547, 20845, -1, 8553, 8547, 20855, -1, 20845, 8531, 20826, -1, 8547, 8531, 20845, -1, 20826, 8533, 20787, -1, 8531, 8533, 20826, -1, 20757, 14615, 20741, -1, 14613, 14615, 20757, -1, 20740, 11751, 11749, -1, 20740, 16128, 11751, -1, 20740, 16144, 16128, -1, 20741, 14621, 20740, -1, 14615, 14621, 20741, -1, 20740, 16147, 16144, -1, 14621, 16148, 20740, -1, 20740, 16148, 16147, -1, 21177, 8470, 21184, -1, 8466, 8470, 21177, -1, 21184, 8464, 21190, -1, 8470, 8464, 21184, -1, 21190, 11389, 11388, -1, 21190, 13183, 11389, -1, 21190, 13181, 13183, -1, 8464, 8463, 21190, -1, 21190, 13182, 13181, -1, 8463, 13185, 21190, -1, 21190, 13185, 13182, -1, 18500, 8460, 21167, -1, 8461, 8460, 18500, -1, 21167, 8467, 21171, -1, 8460, 8467, 21167, -1, 21171, 8466, 21177, -1, 8467, 8466, 21171, -1, 21127, 8439, 21132, -1, 8436, 8439, 21127, -1, 21132, 8438, 21141, -1, 8439, 8438, 21132, -1, 21141, 8443, 18496, -1, 8438, 8443, 21141, -1, 21082, 8426, 21109, -1, 8427, 8426, 21082, -1, 21109, 8430, 21118, -1, 8426, 8430, 21109, -1, 21118, 8436, 21127, -1, 8430, 8436, 21118, -1, 21032, 8412, 21047, -1, 8408, 8412, 21032, -1, 21047, 8406, 21057, -1, 8412, 8406, 21047, -1, 21057, 8405, 21065, -1, 8406, 8405, 21057, -1, 20989, 8402, 21007, -1, 8403, 8402, 20989, -1, 21007, 8409, 21017, -1, 8402, 8409, 21007, -1, 21017, 8408, 21032, -1, 8409, 8408, 21017, -1, 20919, 8381, 20933, -1, 8378, 8381, 20919, -1, 20933, 8380, 20951, -1, 8381, 8380, 20933, -1, 20951, 8385, 20965, -1, 8380, 8385, 20951, -1, 20856, 8368, 20883, -1, 8369, 8368, 20856, -1, 20883, 8372, 20893, -1, 8368, 8372, 20883, -1, 20893, 8378, 20919, -1, 8372, 8378, 20893, -1, 14593, 20802, 20786, -1, 14593, 14597, 20802, -1, 20802, 14591, 20825, -1, 14597, 14591, 20802, -1, 14591, 20844, 20825, -1, 14591, 14590, 20844, -1, 11775, 20739, 11764, -1, 16098, 20739, 11775, -1, 16100, 20739, 16098, -1, 16101, 20739, 16100, -1, 16105, 20739, 16101, -1, 16105, 14588, 20739, -1, 14588, 14587, 20739, -1, 14587, 20756, 20739, -1, 14587, 14594, 20756, -1, 14594, 20786, 20756, -1, 14594, 14593, 20786, -1, 13170, 18635, 11441, -1, 13171, 18635, 13170, -1, 13173, 18635, 13171, -1, 13174, 18635, 13173, -1, 11441, 18635, 11440, -1, 13174, 8482, 18635, -1, 8482, 8481, 18635, -1, 8481, 18658, 18635, -1, 8481, 8479, 18658, -1, 8479, 18659, 18658, -1, 8479, 8478, 18659, -1, 8478, 21198, 18659, -1, 8478, 8477, 21198, -1, 21198, 8473, 21193, -1, 8477, 8473, 21198, -1, 8473, 18549, 21193, -1, 8473, 8472, 18549, -1, 18550, 8454, 21179, -1, 8455, 8454, 18550, -1, 21179, 8452, 18562, -1, 8454, 8452, 21179, -1, 18562, 8450, 18518, -1, 8452, 8450, 18562, -1, 18518, 8446, 21150, -1, 8450, 8446, 18518, -1, 21150, 8440, 21151, -1, 8446, 8440, 21150, -1, 21151, 8435, 18375, -1, 8440, 8435, 21151, -1, 18377, 8423, 18387, -1, 8424, 8423, 18377, -1, 18387, 8421, 18388, -1, 8423, 8421, 18387, -1, 18388, 8420, 18368, -1, 8421, 8420, 18388, -1, 18368, 8419, 21068, -1, 8420, 8419, 18368, -1, 21068, 8415, 21069, -1, 8419, 8415, 21068, -1, 21069, 8414, 21060, -1, 8415, 8414, 21069, -1, 21043, 8396, 21041, -1, 8397, 8396, 21043, -1, 21041, 8394, 21432, -1, 8396, 8394, 21041, -1, 21432, 8392, 21411, -1, 8394, 8392, 21432, -1, 21411, 8388, 20972, -1, 8392, 8388, 21411, -1, 20972, 8382, 20957, -1, 8388, 8382, 20972, -1, 20957, 8377, 20938, -1, 8382, 8377, 20957, -1, 20925, 14608, 20926, -1, 14609, 14608, 20925, -1, 20926, 14605, 20927, -1, 14608, 14605, 20926, -1, 20927, 14604, 20906, -1, 14605, 14604, 20927, -1, 20906, 14606, 20847, -1, 14604, 14606, 20906, -1, 20847, 14600, 20831, -1, 14606, 14600, 20847, -1, 20831, 11782, 11778, -1, 20831, 16091, 11782, -1, 20831, 16107, 16091, -1, 14600, 14599, 20831, -1, 20831, 16110, 16107, -1, 14599, 16111, 20831, -1, 20831, 16111, 16110, -1, 18639, 8357, 18657, -1, 8362, 8357, 18639, -1, 21216, 11459, 11461, -1, 21216, 13148, 11459, -1, 21216, 13146, 13148, -1, 18657, 8356, 21216, -1, 8357, 8356, 18657, -1, 21216, 13147, 13146, -1, 8356, 13150, 21216, -1, 21216, 13150, 13147, -1, 21187, 8345, 21194, -1, 8344, 8345, 21187, -1, 21194, 8351, 21201, -1, 8345, 8351, 21194, -1, 21201, 8350, 18640, -1, 8351, 8350, 21201, -1, 18541, 8340, 18561, -1, 8341, 8340, 18541, -1, 18561, 8339, 21180, -1, 8340, 8339, 18561, -1, 21180, 8344, 21187, -1, 8339, 8344, 21180, -1, 21130, 8321, 21152, -1, 8320, 8321, 21130, -1, 21152, 8327, 18519, -1, 8321, 8327, 21152, -1, 18519, 8326, 18517, -1, 8327, 8326, 18519, -1, 18367, 8316, 18386, -1, 8317, 8316, 18367, -1, 18386, 8315, 21129, -1, 8316, 8315, 18386, -1, 21129, 8320, 21130, -1, 8315, 8320, 21129, -1, 21045, 8273, 21070, -1, 8272, 8273, 21045, -1, 21070, 8279, 21091, -1, 8273, 8279, 21070, -1, 21091, 8278, 18369, -1, 8279, 8278, 21091, -1, 21425, 8268, 21042, -1, 8269, 8268, 21425, -1, 21042, 8267, 21044, -1, 8268, 8267, 21042, -1, 21044, 8272, 21045, -1, 8267, 8272, 21044, -1, 20939, 8296, 20956, -1, 8297, 8296, 20939, -1, 20956, 8303, 21410, -1, 8296, 8303, 20956, -1, 21410, 8302, 21418, -1, 8303, 8302, 21410, -1, 8293, 20923, 20904, -1, 8293, 8292, 20923, -1, 20923, 8291, 20924, -1, 8292, 8291, 20923, -1, 8291, 20939, 20924, -1, 8291, 8297, 20939, -1, 11798, 20830, 11790, -1, 16061, 20830, 11798, -1, 16063, 20830, 16061, -1, 16064, 20830, 16063, -1, 16068, 20830, 16064, -1, 14575, 20830, 16068, -1, 20830, 14574, 20905, -1, 14575, 14574, 20830, -1, 14574, 20903, 20905, -1, 14574, 14582, 20903, -1, 11482, 18704, 11479, -1, 13136, 18704, 11482, -1, 13137, 18704, 13136, -1, 13139, 18704, 13137, -1, 13140, 18704, 13139, -1, 8366, 18704, 13140, -1, 18704, 8358, 18710, -1, 8366, 8358, 18704, -1, 8358, 18689, 18710, -1, 8358, 8360, 18689, -1, 8337, 18650, 18678, -1, 8337, 8336, 18650, -1, 18650, 8335, 18625, -1, 8336, 8335, 18650, -1, 8335, 18626, 18625, -1, 8335, 8353, 18626, -1, 8353, 18618, 18626, -1, 8353, 8347, 18618, -1, 18618, 8331, 18619, -1, 8347, 8331, 18618, -1, 18619, 8333, 18600, -1, 8331, 8333, 18619, -1, 18585, 8310, 18566, -1, 8313, 8310, 18585, -1, 18566, 8312, 18567, -1, 8310, 8312, 18566, -1, 18567, 8329, 21173, -1, 8312, 8329, 18567, -1, 21173, 8323, 18532, -1, 8329, 8323, 21173, -1, 18532, 8307, 18533, -1, 8323, 8307, 18532, -1, 18533, 8309, 18474, -1, 8307, 8309, 18533, -1, 18476, 8262, 18402, -1, 8265, 8262, 18476, -1, 18402, 8264, 18403, -1, 8262, 8264, 18402, -1, 18403, 8281, 21122, -1, 8264, 8281, 18403, -1, 21122, 8275, 18364, -1, 8281, 8275, 21122, -1, 18364, 8259, 21124, -1, 8275, 8259, 18364, -1, 21124, 8261, 21113, -1, 8259, 8261, 21124, -1, 21100, 8286, 21101, -1, 8289, 8286, 21100, -1, 21101, 8288, 21422, -1, 8286, 8288, 21101, -1, 21422, 8305, 21423, -1, 8288, 8305, 21422, -1, 21423, 8299, 21419, -1, 8305, 8299, 21423, -1, 21419, 8283, 21029, -1, 8299, 8283, 21419, -1, 21029, 8285, 21005, -1, 8283, 8285, 21029, -1, 21002, 14579, 20908, -1, 14577, 14579, 21002, -1, 20909, 11809, 11801, -1, 20909, 16054, 11809, -1, 20909, 16070, 16054, -1, 20908, 14585, 20909, -1, 14579, 14585, 20908, -1, 20909, 16073, 16070, -1, 14585, 16074, 20909, -1, 20909, 16074, 16073, -1, 21221, 14563, 21223, -1, 14559, 14563, 21221, -1, 21223, 14557, 18708, -1, 14563, 14557, 21223, -1, 18708, 11491, 11493, -1, 18708, 13112, 11491, -1, 18708, 13110, 13112, -1, 14557, 13113, 18708, -1, 18708, 13111, 13110, -1, 13113, 13115, 18708, -1, 18708, 13115, 13111, -1, 18649, 14555, 18683, -1, 14556, 14555, 18649, -1, 18683, 14560, 21219, -1, 14555, 14560, 18683, -1, 21219, 14559, 21221, -1, 14560, 14559, 21219, -1, 21208, 8157, 21210, -1, 8154, 8157, 21208, -1, 21210, 8156, 18617, -1, 8157, 8156, 21210, -1, 18617, 8161, 18624, -1, 8156, 8161, 18617, -1, 18565, 8144, 18587, -1, 8145, 8144, 18565, -1, 18587, 8148, 21203, -1, 8144, 8148, 18587, -1, 21203, 8154, 21208, -1, 8148, 8154, 21203, -1, 21164, 8188, 21169, -1, 8184, 8188, 21164, -1, 21169, 8182, 18531, -1, 8188, 8182, 21169, -1, 18531, 8181, 18537, -1, 8182, 8181, 18531, -1, 18401, 8178, 18449, -1, 8179, 8178, 18401, -1, 18449, 8185, 21159, -1, 8178, 8185, 18449, -1, 21159, 8184, 21164, -1, 8185, 8184, 21159, -1, 21111, 8215, 21115, -1, 8212, 8215, 21111, -1, 21115, 8214, 18365, -1, 8215, 8214, 21115, -1, 18365, 8219, 18363, -1, 8214, 8219, 18365, -1, 21433, 8202, 21098, -1, 8203, 8202, 21433, -1, 21098, 8206, 21099, -1, 8202, 8206, 21098, -1, 21099, 8212, 21111, -1, 8206, 8212, 21099, -1, 8242, 21015, 21004, -1, 8242, 8246, 21015, -1, 21015, 8240, 21030, -1, 8246, 8240, 21015, -1, 8240, 21421, 21030, -1, 8240, 8239, 21421, -1, 11829, 21385, 11821, -1, 16024, 21385, 11829, -1, 16026, 21385, 16024, -1, 16027, 21385, 16026, -1, 16031, 21385, 16027, -1, 16031, 8237, 21385, -1, 8237, 8236, 21385, -1, 8236, 21003, 21385, -1, 8236, 8243, 21003, -1, 8243, 21004, 21003, -1, 8243, 8242, 21004, -1, 13099, 3411, 11507, -1, 13100, 3411, 13099, -1, 13102, 3411, 13100, -1, 13103, 3411, 13102, -1, 11507, 3411, 3410, -1, 13103, 13106, 3411, -1, 13106, 14573, 3411, -1, 14573, 3412, 3411, -1, 14573, 14571, 3412, -1, 14571, 712, 3412, -1, 14571, 14570, 712, -1, 14570, 18711, 712, -1, 14570, 14569, 18711, -1, 18711, 14566, 18702, -1, 14569, 14566, 18711, -1, 14566, 18693, 18702, -1, 14566, 14565, 18693, -1, 18694, 8172, 18687, -1, 8173, 8172, 18694, -1, 18687, 8170, 18688, -1, 8172, 8170, 18687, -1, 18688, 8168, 323, -1, 8170, 8168, 18688, -1, 323, 8164, 18630, -1, 8168, 8164, 323, -1, 18630, 8158, 18614, -1, 8164, 8158, 18630, -1, 18614, 8153, 18610, -1, 8158, 8153, 18614, -1, 18607, 8199, 18595, -1, 8200, 8199, 18607, -1, 18595, 8196, 18596, -1, 8199, 8196, 18595, -1, 18596, 8195, 197, -1, 8196, 8195, 18596, -1, 197, 8197, 18555, -1, 8195, 8197, 197, -1, 18555, 8191, 18511, -1, 8197, 8191, 18555, -1, 18511, 8190, 18510, -1, 8191, 8190, 18511, -1, 18494, 8230, 18466, -1, 8231, 8230, 18494, -1, 18466, 8228, 18467, -1, 8230, 8228, 18466, -1, 18467, 8226, 92, -1, 8228, 8226, 18467, -1, 92, 8222, 18379, -1, 8226, 8222, 92, -1, 18379, 8216, 18366, -1, 8222, 8216, 18379, -1, 18366, 8211, 21465, -1, 8216, 8211, 18366, -1, 21457, 8257, 21454, -1, 8258, 8257, 21457, -1, 21454, 8254, 21455, -1, 8257, 8254, 21454, -1, 21455, 8253, 30, -1, 8254, 8253, 21455, -1, 30, 8255, 3407, -1, 8253, 8255, 30, -1, 3407, 8249, 3403, -1, 8255, 8249, 3407, -1, 3403, 11840, 3406, -1, 3403, 16017, 11840, -1, 3403, 16033, 16017, -1, 8249, 8248, 3403, -1, 3403, 16036, 16033, -1, 8248, 16037, 3403, -1, 3403, 16037, 16036, -1, 936, 7697, 1017, -1, 7702, 7697, 936, -1, 1045, 11522, 1106, -1, 1045, 12957, 11522, -1, 1045, 12955, 12957, -1, 1017, 7696, 1045, -1, 7697, 7696, 1017, -1, 1045, 12956, 12955, -1, 7696, 12959, 1045, -1, 1045, 12959, 12956, -1, 443, 7768, 593, -1, 7769, 7768, 443, -1, 593, 7775, 699, -1, 7768, 7775, 593, -1, 699, 7774, 829, -1, 7775, 7774, 699, -1, 396, 7764, 420, -1, 7765, 7764, 396, -1, 420, 7763, 431, -1, 7764, 7763, 420, -1, 431, 7769, 443, -1, 7763, 7769, 431, -1, 275, 7792, 304, -1, 7793, 7792, 275, -1, 304, 7799, 321, -1, 7792, 7799, 304, -1, 321, 7798, 369, -1, 7799, 7798, 321, -1, 248, 7788, 256, -1, 7789, 7788, 248, -1, 256, 7787, 268, -1, 7788, 7787, 256, -1, 268, 7793, 275, -1, 7787, 7793, 268, -1, 146, 7745, 177, -1, 7744, 7745, 146, -1, 177, 7751, 196, -1, 7745, 7751, 177, -1, 196, 7750, 229, -1, 7751, 7750, 196, -1, 115, 7740, 127, -1, 7741, 7740, 115, -1, 127, 7739, 143, -1, 7740, 7739, 127, -1, 143, 7744, 146, -1, 7739, 7744, 143, -1, 69, 7721, 81, -1, 7720, 7721, 69, -1, 81, 7727, 91, -1, 7721, 7727, 81, -1, 91, 7726, 109, -1, 7727, 7726, 91, -1, 7717, 53, 46, -1, 7717, 7716, 53, -1, 53, 7715, 58, -1, 7716, 7715, 53, -1, 7715, 69, 58, -1, 7715, 7720, 69, -1, 11858, 21, 15, -1, 15876, 21, 11858, -1, 15878, 21, 15876, -1, 15879, 21, 15878, -1, 15883, 21, 15879, -1, 14495, 21, 15883, -1, 21, 14494, 29, -1, 14495, 14494, 21, -1, 14494, 42, 29, -1, 14494, 14502, 42, -1, 11577, 1015, 2487, -1, 13060, 1015, 11577, -1, 13061, 1015, 13060, -1, 13063, 1015, 13061, -1, 13064, 1015, 13063, -1, 13067, 1015, 13064, -1, 1015, 14547, 998, -1, 13067, 14547, 1015, -1, 14547, 978, 998, -1, 14547, 14549, 978, -1, 8101, 925, 948, -1, 8101, 8100, 925, -1, 925, 8099, 902, -1, 8100, 8099, 925, -1, 8099, 879, 902, -1, 8099, 8117, 879, -1, 8117, 855, 879, -1, 8117, 8111, 855, -1, 855, 8095, 842, -1, 8111, 8095, 855, -1, 842, 8097, 818, -1, 8095, 8097, 842, -1, 784, 8122, 769, -1, 8125, 8122, 784, -1, 769, 8124, 731, -1, 8122, 8124, 769, -1, 731, 8141, 732, -1, 8124, 8141, 731, -1, 732, 8135, 721, -1, 8141, 8135, 732, -1, 721, 8119, 705, -1, 8135, 8119, 721, -1, 705, 8121, 670, -1, 8119, 8121, 705, -1, 653, 8074, 645, -1, 8077, 8074, 653, -1, 645, 8076, 632, -1, 8074, 8076, 645, -1, 632, 8093, 633, -1, 8076, 8093, 632, -1, 633, 8087, 607, -1, 8093, 8087, 633, -1, 607, 8071, 591, -1, 8087, 8071, 607, -1, 591, 8073, 436, -1, 8071, 8073, 591, -1, 437, 8050, 562, -1, 8053, 8050, 437, -1, 562, 8052, 554, -1, 8050, 8052, 562, -1, 554, 8069, 542, -1, 8052, 8069, 554, -1, 542, 8063, 533, -1, 8069, 8063, 542, -1, 533, 8047, 525, -1, 8063, 8047, 533, -1, 525, 8049, 265, -1, 8047, 8049, 525, -1, 266, 8040, 478, -1, 8038, 8040, 266, -1, 171, 11933, 172, -1, 171, 15980, 11933, -1, 171, 15996, 15980, -1, 478, 8046, 171, -1, 8040, 8046, 478, -1, 171, 15999, 15996, -1, 8046, 16000, 171, -1, 171, 16000, 15999, -1, 979, 14535, 980, -1, 14531, 14535, 979, -1, 980, 14529, 997, -1, 14535, 14529, 980, -1, 997, 11583, 1016, -1, 997, 13034, 11583, -1, 997, 13032, 13034, -1, 14529, 13035, 997, -1, 997, 13033, 13032, -1, 13035, 13037, 997, -1, 997, 13037, 13033, -1, 903, 14527, 924, -1, 14528, 14527, 903, -1, 924, 14532, 947, -1, 14527, 14532, 924, -1, 947, 14531, 979, -1, 14532, 14531, 947, -1, 823, 7991, 824, -1, 7988, 7991, 823, -1, 824, 7990, 843, -1, 7991, 7990, 824, -1, 843, 7995, 856, -1, 7990, 7995, 843, -1, 733, 7978, 770, -1, 7979, 7978, 733, -1, 770, 7982, 785, -1, 7978, 7982, 770, -1, 785, 7988, 823, -1, 7982, 7988, 785, -1, 691, 7930, 692, -1, 7926, 7930, 691, -1, 692, 7924, 708, -1, 7930, 7924, 692, -1, 708, 7923, 722, -1, 7924, 7923, 708, -1, 634, 7920, 646, -1, 7921, 7920, 634, -1, 646, 7927, 654, -1, 7920, 7927, 646, -1, 654, 7926, 691, -1, 7927, 7926, 654, -1, 579, 7957, 580, -1, 7954, 7957, 579, -1, 580, 7956, 592, -1, 7957, 7956, 580, -1, 592, 7961, 608, -1, 7956, 7961, 592, -1, 337, 7944, 563, -1, 7945, 7944, 337, -1, 563, 7948, 568, -1, 7944, 7948, 563, -1, 568, 7954, 579, -1, 7948, 7954, 568, -1, 8018, 507, 495, -1, 8018, 8022, 507, -1, 507, 8016, 522, -1, 8022, 8016, 507, -1, 8016, 338, 522, -1, 8016, 8015, 338, -1, 11949, 480, 479, -1, 15950, 480, 11949, -1, 15952, 480, 15950, -1, 15953, 480, 15952, -1, 15957, 480, 15953, -1, 15957, 8013, 480, -1, 8013, 8012, 480, -1, 8012, 490, 480, -1, 8012, 8019, 490, -1, 8019, 495, 490, -1, 8019, 8018, 495, -1, 13020, 2994, 11596, -1, 13021, 2994, 13020, -1, 13023, 2994, 13021, -1, 13024, 2994, 13023, -1, 11596, 2994, 2993, -1, 13024, 13027, 2994, -1, 13027, 14545, 2994, -1, 14545, 1124, 2994, -1, 14545, 14543, 1124, -1, 14543, 1095, 1124, -1, 14543, 14542, 1095, -1, 14542, 1027, 1095, -1, 14542, 14541, 1027, -1, 1027, 14538, 1001, -1, 14541, 14538, 1027, -1, 14538, 1000, 1001, -1, 14538, 14537, 1000, -1, 986, 8006, 982, -1, 8007, 8006, 986, -1, 982, 8004, 976, -1, 8006, 8004, 982, -1, 976, 8002, 961, -1, 8004, 8002, 976, -1, 961, 7998, 867, -1, 8002, 7998, 961, -1, 867, 7992, 868, -1, 7998, 7992, 867, -1, 868, 7987, 835, -1, 7992, 7987, 868, -1, 836, 7941, 840, -1, 7942, 7941, 836, -1, 840, 7938, 827, -1, 7941, 7938, 840, -1, 827, 7937, 807, -1, 7938, 7937, 827, -1, 807, 7939, 725, -1, 7937, 7939, 807, -1, 725, 7933, 726, -1, 7939, 7933, 725, -1, 726, 7932, 715, -1, 7933, 7932, 726, -1, 713, 7972, 714, -1, 7973, 7972, 713, -1, 714, 7970, 697, -1, 7972, 7970, 714, -1, 697, 7968, 680, -1, 7970, 7968, 697, -1, 680, 7964, 614, -1, 7968, 7964, 680, -1, 614, 7958, 605, -1, 7964, 7958, 614, -1, 605, 7953, 463, -1, 7958, 7953, 605, -1, 428, 8033, 486, -1, 8034, 8033, 428, -1, 486, 8030, 487, -1, 8033, 8030, 486, -1, 487, 8029, 382, -1, 8030, 8029, 487, -1, 382, 8031, 379, -1, 8029, 8031, 382, -1, 379, 8025, 282, -1, 8031, 8025, 379, -1, 282, 11963, 283, -1, 282, 15943, 11963, -1, 282, 15959, 15943, -1, 8025, 8024, 282, -1, 282, 15962, 15959, -1, 8024, 15963, 282, -1, 282, 15963, 15962, -1, 1122, 14410, 1123, -1, 14415, 14410, 1122, -1, 3055, 11604, 3084, -1, 3055, 12726, 11604, -1, 3055, 12724, 12726, -1, 1123, 12727, 3055, -1, 14410, 12727, 1123, -1, 3055, 12725, 12724, -1, 12727, 12729, 3055, -1, 3055, 12729, 12725, -1, 984, 7036, 1026, -1, 7037, 7036, 984, -1, 1026, 7043, 1092, -1, 7036, 7043, 1026, -1, 1092, 7042, 1093, -1, 7043, 7042, 1092, -1, 974, 7032, 975, -1, 7033, 7032, 974, -1, 975, 7031, 983, -1, 7032, 7031, 975, -1, 983, 7037, 984, -1, 7031, 7037, 983, -1, 838, 7060, 869, -1, 7061, 7060, 838, -1, 869, 7067, 959, -1, 7060, 7067, 869, -1, 959, 7066, 960, -1, 7067, 7066, 959, -1, 828, 7056, 826, -1, 7057, 7056, 828, -1, 826, 7055, 837, -1, 7056, 7055, 826, -1, 837, 7061, 838, -1, 7055, 7061, 837, -1, 711, 7121, 724, -1, 7120, 7121, 711, -1, 724, 7127, 805, -1, 7121, 7127, 724, -1, 805, 7126, 806, -1, 7127, 7126, 805, -1, 683, 7116, 698, -1, 7117, 7116, 683, -1, 698, 7115, 710, -1, 7116, 7115, 698, -1, 710, 7120, 711, -1, 7115, 7120, 710, -1, 582, 7097, 613, -1, 7096, 7097, 582, -1, 613, 7103, 681, -1, 7097, 7103, 613, -1, 681, 7102, 682, -1, 7103, 7102, 681, -1, 7093, 485, 546, -1, 7093, 7092, 485, -1, 485, 7091, 529, -1, 7092, 7091, 485, -1, 7091, 582, 529, -1, 7091, 7096, 582, -1, 11976, 380, 528, -1, 15654, 380, 11976, -1, 15656, 380, 15654, -1, 15657, 380, 15656, -1, 15661, 380, 15657, -1, 7072, 380, 15661, -1, 380, 7071, 378, -1, 7072, 7071, 380, -1, 7071, 544, 378, -1, 7071, 7079, 544, -1, 12981, 920, 11552, -1, 12982, 920, 12981, -1, 12984, 920, 12982, -1, 12985, 920, 12984, -1, 11552, 920, 2022, -1, 12985, 12988, 920, -1, 12988, 14525, 920, -1, 14525, 876, 920, -1, 14525, 14523, 876, -1, 14523, 853, 876, -1, 14523, 14522, 853, -1, 14522, 815, 853, -1, 14522, 14521, 815, -1, 815, 14518, 816, -1, 14521, 14518, 815, -1, 14518, 1373, 816, -1, 14518, 14517, 1373, -1, 1374, 7890, 735, -1, 7891, 7890, 1374, -1, 735, 7888, 728, -1, 7890, 7888, 735, -1, 728, 7886, 718, -1, 7888, 7886, 728, -1, 718, 7882, 703, -1, 7886, 7882, 718, -1, 703, 7876, 799, -1, 7882, 7876, 703, -1, 799, 7871, 622, -1, 7876, 7871, 799, -1, 620, 7917, 627, -1, 7918, 7917, 620, -1, 627, 7915, 610, -1, 7917, 7915, 627, -1, 610, 7914, 596, -1, 7915, 7914, 610, -1, 596, 7913, 426, -1, 7914, 7913, 596, -1, 426, 7909, 361, -1, 7913, 7909, 426, -1, 361, 7908, 362, -1, 7909, 7908, 361, -1, 354, 7856, 352, -1, 7857, 7856, 354, -1, 352, 7854, 536, -1, 7856, 7854, 352, -1, 536, 7852, 531, -1, 7854, 7852, 536, -1, 531, 7848, 503, -1, 7852, 7848, 531, -1, 503, 7842, 222, -1, 7848, 7842, 503, -1, 222, 7837, 194, -1, 7842, 7837, 222, -1, 182, 7825, 217, -1, 7826, 7825, 182, -1, 217, 7822, 473, -1, 7825, 7822, 217, -1, 473, 7821, 470, -1, 7822, 7821, 473, -1, 470, 7823, 466, -1, 7821, 7823, 470, -1, 466, 7817, 94, -1, 7823, 7817, 466, -1, 94, 11899, 97, -1, 94, 15906, 11899, -1, 94, 15922, 15906, -1, 7817, 7816, 94, -1, 94, 15925, 15922, -1, 7816, 15926, 94, -1, 94, 15926, 15925, -1, 877, 14546, 894, -1, 14551, 14546, 877, -1, 919, 11564, 2120, -1, 919, 13073, 11564, -1, 919, 13071, 13073, -1, 894, 13074, 919, -1, 14546, 13074, 894, -1, 919, 13072, 13071, -1, 13074, 13076, 919, -1, 919, 13076, 13072, -1, 813, 8108, 814, -1, 8109, 8108, 813, -1, 814, 8115, 833, -1, 8108, 8115, 814, -1, 833, 8114, 852, -1, 8115, 8114, 833, -1, 729, 8104, 738, -1, 8105, 8104, 729, -1, 738, 8103, 736, -1, 8104, 8103, 738, -1, 736, 8109, 813, -1, 8103, 8109, 736, -1, 621, 8133, 701, -1, 8132, 8133, 621, -1, 701, 8139, 702, -1, 8133, 8139, 701, -1, 702, 8138, 719, -1, 8139, 8138, 702, -1, 611, 8128, 630, -1, 8129, 8128, 611, -1, 630, 8127, 629, -1, 8128, 8127, 630, -1, 629, 8132, 621, -1, 8127, 8132, 629, -1, 351, 8085, 425, -1, 8084, 8085, 351, -1, 425, 8091, 589, -1, 8085, 8091, 425, -1, 589, 8090, 597, -1, 8091, 8090, 589, -1, 347, 8080, 549, -1, 8081, 8080, 347, -1, 549, 8079, 353, -1, 8080, 8079, 549, -1, 353, 8084, 351, -1, 8079, 8084, 353, -1, 216, 8061, 504, -1, 8060, 8061, 216, -1, 504, 8067, 513, -1, 8061, 8067, 504, -1, 513, 8066, 345, -1, 8067, 8066, 513, -1, 8057, 475, 207, -1, 8057, 8056, 475, -1, 475, 8055, 218, -1, 8056, 8055, 475, -1, 8055, 216, 218, -1, 8055, 8060, 216, -1, 11919, 123, 100, -1, 15987, 123, 11919, -1, 15989, 123, 15987, -1, 15990, 123, 15989, -1, 15994, 123, 15990, -1, 8036, 123, 15994, -1, 123, 8035, 468, -1, 8036, 8035, 123, -1, 8035, 208, 468, -1, 8035, 8043, 208, -1, 11534, 764, 1572, -1, 12945, 764, 11534, -1, 12946, 764, 12945, -1, 12948, 764, 12946, -1, 12949, 764, 12948, -1, 7706, 764, 12949, -1, 764, 7698, 761, -1, 7706, 7698, 764, -1, 7698, 1321, 761, -1, 7698, 7700, 1321, -1, 7761, 686, 1219, -1, 7761, 7760, 686, -1, 686, 7759, 662, -1, 7760, 7759, 686, -1, 7759, 648, 662, -1, 7759, 7777, 648, -1, 7777, 638, 648, -1, 7777, 7771, 638, -1, 638, 7755, 639, -1, 7771, 7755, 638, -1, 639, 7757, 604, -1, 7755, 7757, 639, -1, 534, 7782, 539, -1, 7785, 7782, 534, -1, 539, 7784, 565, -1, 7782, 7784, 539, -1, 565, 7801, 557, -1, 7784, 7801, 565, -1, 557, 7795, 558, -1, 7801, 7795, 557, -1, 558, 7779, 371, -1, 7795, 7779, 558, -1, 371, 7781, 312, -1, 7779, 7781, 371, -1, 292, 7734, 298, -1, 7737, 7734, 292, -1, 298, 7736, 492, -1, 7734, 7736, 298, -1, 492, 7753, 483, -1, 7736, 7753, 492, -1, 483, 7747, 484, -1, 7753, 7747, 483, -1, 484, 7731, 233, -1, 7747, 7731, 484, -1, 233, 7733, 189, -1, 7731, 7733, 233, -1, 167, 7710, 168, -1, 7713, 7710, 167, -1, 168, 7712, 462, -1, 7710, 7712, 168, -1, 462, 7729, 457, -1, 7712, 7729, 462, -1, 457, 7723, 455, -1, 7729, 7723, 457, -1, 455, 7707, 105, -1, 7723, 7707, 455, -1, 105, 7709, 83, -1, 7707, 7709, 105, -1, 79, 14499, 450, -1, 14497, 14499, 79, -1, 35, 11869, 36, -1, 35, 15869, 11869, -1, 35, 15885, 15869, -1, 450, 14505, 35, -1, 14499, 14505, 450, -1, 35, 15888, 15885, -1, 14505, 15889, 35, -1, 35, 15889, 15888, -1, 1516, 14515, 1591, -1, 14511, 14515, 1516, -1, 1591, 14509, 762, -1, 14515, 14509, 1591, -1, 762, 11542, 765, -1, 762, 12995, 11542, -1, 762, 12993, 12995, -1, 14509, 12996, 762, -1, 762, 12994, 12993, -1, 12996, 12998, 762, -1, 762, 12998, 12994, -1, 661, 14507, 685, -1, 14508, 14507, 661, -1, 685, 14512, 1367, -1, 14507, 14512, 685, -1, 1367, 14511, 1516, -1, 14512, 14511, 1367, -1, 758, 7875, 808, -1, 7872, 7875, 758, -1, 808, 7874, 636, -1, 7875, 7874, 808, -1, 636, 7879, 637, -1, 7874, 7879, 636, -1, 566, 7862, 538, -1, 7863, 7862, 566, -1, 538, 7866, 640, -1, 7862, 7866, 538, -1, 640, 7872, 758, -1, 7866, 7872, 640, -1, 343, 7906, 370, -1, 7902, 7906, 343, -1, 370, 7900, 386, -1, 7906, 7900, 370, -1, 386, 7899, 559, -1, 7900, 7899, 386, -1, 493, 7896, 297, -1, 7897, 7896, 493, -1, 297, 7903, 315, -1, 7896, 7903, 297, -1, 315, 7902, 343, -1, 7903, 7902, 315, -1, 213, 7841, 232, -1, 7838, 7841, 213, -1, 232, 7840, 234, -1, 7841, 7840, 232, -1, 234, 7845, 482, -1, 7840, 7845, 234, -1, 138, 7828, 166, -1, 7829, 7828, 138, -1, 166, 7832, 193, -1, 7828, 7832, 166, -1, 193, 7838, 213, -1, 7832, 7838, 193, -1, 7810, 104, 102, -1, 7810, 7814, 104, -1, 104, 7808, 114, -1, 7814, 7808, 104, -1, 7808, 139, 114, -1, 7808, 7807, 139, -1, 11889, 80, 452, -1, 15913, 80, 11889, -1, 15915, 80, 15913, -1, 15916, 80, 15915, -1, 15920, 80, 15916, -1, 15920, 7805, 80, -1, 7805, 7804, 80, -1, 7804, 78, 80, -1, 7804, 7811, 78, -1, 7811, 102, 78, -1, 7811, 7810, 102, -1, 12908, 3383, 11323, -1, 12909, 3383, 12908, -1, 12911, 3383, 12909, -1, 12912, 3383, 12911, -1, 11323, 3383, 3382, -1, 12912, 12915, 3383, -1, 12915, 14493, 3383, -1, 14493, 1796, 3383, -1, 14493, 14491, 1796, -1, 14491, 1762, 1796, -1, 14491, 14490, 1762, -1, 14490, 1760, 1762, -1, 14490, 14489, 1760, -1, 1760, 14486, 1692, -1, 14489, 14486, 1760, -1, 14486, 1693, 1692, -1, 14486, 14485, 1693, -1, 1655, 7608, 1656, -1, 7609, 7608, 1655, -1, 1656, 7606, 1651, -1, 7608, 7606, 1656, -1, 1651, 7604, 1629, -1, 7606, 7604, 1651, -1, 1629, 7600, 1626, -1, 7604, 7600, 1629, -1, 1626, 7594, 1532, -1, 7600, 7594, 1626, -1, 1532, 7589, 1531, -1, 7594, 7589, 1532, -1, 1529, 7635, 3251, -1, 7636, 7635, 1529, -1, 3251, 7632, 1521, -1, 7635, 7632, 3251, -1, 1521, 7631, 1495, -1, 7632, 7631, 1521, -1, 1495, 7633, 1496, -1, 7631, 7633, 1495, -1, 1496, 7627, 1399, -1, 7633, 7627, 1496, -1, 1399, 7626, 1400, -1, 7627, 7626, 1399, -1, 1401, 7666, 3195, -1, 7667, 7666, 1401, -1, 3195, 7664, 1379, -1, 7666, 7664, 3195, -1, 1379, 7662, 1337, -1, 7664, 7662, 1379, -1, 1337, 7658, 1336, -1, 7662, 7658, 1337, -1, 1336, 7652, 1250, -1, 7658, 7652, 1336, -1, 1250, 7647, 1216, -1, 7652, 7647, 1250, -1, 1217, 7693, 1218, -1, 7694, 7693, 1217, -1, 1218, 7690, 1212, -1, 7693, 7690, 1218, -1, 1212, 7689, 1196, -1, 7690, 7689, 1212, -1, 1196, 7691, 1195, -1, 7689, 7691, 1196, -1, 1195, 7685, 1101, -1, 7691, 7685, 1195, -1, 1101, 11986, 1102, -1, 1101, 15832, 11986, -1, 1101, 15848, 15832, -1, 7685, 7684, 1101, -1, 1101, 15851, 15848, -1, 7684, 15852, 1101, -1, 1101, 15852, 15851, -1, 1795, 14458, 1815, -1, 14463, 14458, 1795, -1, 3392, 11343, 3393, -1, 3392, 12843, 11343, -1, 3392, 12841, 12843, -1, 1815, 12844, 3392, -1, 14458, 12844, 1815, -1, 3392, 12842, 12841, -1, 12844, 12846, 3392, -1, 3392, 12846, 12842, -1, 1654, 7388, 1761, -1, 7389, 7388, 1654, -1, 1761, 7395, 1763, -1, 7388, 7395, 1761, -1, 1763, 7394, 1778, -1, 7395, 7394, 1763, -1, 1650, 7384, 1673, -1, 7385, 7384, 1650, -1, 1673, 7383, 1653, -1, 7384, 7383, 1673, -1, 1653, 7389, 1654, -1, 7383, 7389, 1653, -1, 1530, 7412, 1627, -1, 7413, 7412, 1530, -1, 1627, 7419, 1628, -1, 7412, 7419, 1627, -1, 1628, 7418, 1637, -1, 7419, 7418, 1628, -1, 1522, 7408, 1540, -1, 7409, 7408, 1522, -1, 1540, 7407, 3254, -1, 7408, 7407, 1540, -1, 3254, 7413, 1530, -1, 7407, 7413, 3254, -1, 1398, 7436, 1493, -1, 7437, 7436, 1398, -1, 1493, 7443, 1494, -1, 7436, 7443, 1493, -1, 1494, 7442, 1506, -1, 7443, 7442, 1494, -1, 1370, 7432, 1403, -1, 7433, 7432, 1370, -1, 1403, 7431, 3199, -1, 7432, 7431, 1403, -1, 3199, 7437, 1398, -1, 7431, 7437, 3199, -1, 1215, 7461, 1334, -1, 7460, 7461, 1215, -1, 1334, 7467, 1335, -1, 7461, 7467, 1334, -1, 1335, 7466, 1369, -1, 7467, 7466, 1335, -1, 7457, 1237, 1194, -1, 7457, 7456, 1237, -1, 1237, 7455, 1214, -1, 7456, 7455, 1237, -1, 7455, 1215, 1214, -1, 7455, 7460, 1215, -1, 11969, 1107, 1104, -1, 15765, 1107, 11969, -1, 15767, 1107, 15765, -1, 15768, 1107, 15767, -1, 15772, 1107, 15768, -1, 7364, 1107, 15772, -1, 1107, 7363, 1191, -1, 7364, 7363, 1107, -1, 7363, 1192, 1191, -1, 7363, 7371, 1192, -1, 11297, 1707, 3328, -1, 12868, 1707, 11297, -1, 12869, 1707, 12868, -1, 12871, 1707, 12869, -1, 12872, 1707, 12871, -1, 12875, 1707, 12872, -1, 1707, 14467, 1684, -1, 12875, 14467, 1707, -1, 14467, 1685, 1684, -1, 14467, 14469, 1685, -1, 7525, 1606, 1622, -1, 7525, 7524, 1606, -1, 1606, 7523, 1584, -1, 7524, 7523, 1606, -1, 7523, 1571, 1584, -1, 7523, 7541, 1571, -1, 7541, 1553, 1571, -1, 7541, 7535, 1553, -1, 1553, 7519, 1534, -1, 7535, 7519, 1553, -1, 1534, 7521, 1535, -1, 7519, 7521, 1534, -1, 1483, 7474, 1463, -1, 7477, 7474, 1483, -1, 1463, 7476, 1425, -1, 7474, 7476, 1463, -1, 1425, 7493, 1426, -1, 7476, 7493, 1425, -1, 1426, 7487, 1412, -1, 7493, 7487, 1426, -1, 1412, 7471, 1396, -1, 7487, 7471, 1412, -1, 1396, 7473, 1392, -1, 7471, 7473, 1396, -1, 1329, 7498, 1317, -1, 7501, 7498, 1329, -1, 1317, 7500, 1291, -1, 7498, 7500, 1317, -1, 1291, 7517, 1292, -1, 7500, 7517, 1291, -1, 1292, 7511, 1266, -1, 7517, 7511, 1292, -1, 1266, 7495, 1243, -1, 7511, 7495, 1266, -1, 1243, 7497, 1240, -1, 7495, 7497, 1243, -1, 1177, 7558, 1158, -1, 7561, 7558, 1177, -1, 1158, 7560, 1147, -1, 7558, 7560, 1158, -1, 1147, 7577, 1132, -1, 7560, 7577, 1147, -1, 1132, 7571, 1119, -1, 7577, 7571, 1132, -1, 1119, 7555, 1089, -1, 7571, 7555, 1119, -1, 1089, 7557, 1087, -1, 7555, 7557, 1089, -1, 1035, 7548, 1008, -1, 7546, 7548, 1035, -1, 1006, 12014, 2347, -1, 1006, 15795, 12014, -1, 1006, 15811, 15795, -1, 1008, 7554, 1006, -1, 7548, 7554, 1008, -1, 1006, 15814, 15811, -1, 7554, 15815, 1006, -1, 1006, 15815, 15814, -1, 3321, 14483, 1682, -1, 14479, 14483, 3321, -1, 1682, 14477, 1683, -1, 14483, 14477, 1682, -1, 1683, 11317, 1708, -1, 1683, 12921, 11317, -1, 1683, 12919, 12921, -1, 14477, 12922, 1683, -1, 1683, 12920, 12919, -1, 12922, 12924, 1683, -1, 1683, 12924, 12920, -1, 1585, 14475, 1607, -1, 14476, 14475, 1585, -1, 1607, 14480, 3311, -1, 14475, 14480, 1607, -1, 3311, 14479, 3321, -1, 14480, 14479, 3311, -1, 3255, 7593, 1536, -1, 7590, 7593, 3255, -1, 1536, 7592, 1537, -1, 7593, 7592, 1536, -1, 1537, 7597, 1554, -1, 7592, 7597, 1537, -1, 1423, 7580, 1462, -1, 7581, 7580, 1423, -1, 1462, 7584, 3245, -1, 7580, 7584, 1462, -1, 3245, 7590, 3255, -1, 7584, 7590, 3245, -1, 3200, 7624, 1390, -1, 7620, 7624, 3200, -1, 1390, 7618, 1391, -1, 7624, 7618, 1390, -1, 1391, 7617, 1411, -1, 7618, 7617, 1391, -1, 1287, 7614, 1315, -1, 7615, 7614, 1287, -1, 1315, 7621, 3190, -1, 7614, 7621, 1315, -1, 3190, 7620, 3200, -1, 7621, 7620, 3190, -1, 3149, 7651, 1241, -1, 7648, 7651, 3149, -1, 1241, 7650, 1242, -1, 7651, 7650, 1241, -1, 1242, 7655, 1265, -1, 7650, 7655, 1242, -1, 1131, 7638, 1157, -1, 7639, 7638, 1131, -1, 1157, 7642, 3136, -1, 7638, 7642, 1157, -1, 3136, 7648, 3149, -1, 7642, 7648, 3136, -1, 7678, 1088, 2963, -1, 7678, 7682, 1088, -1, 1088, 7676, 1090, -1, 7682, 7676, 1088, -1, 7676, 1120, 1090, -1, 7676, 7675, 1120, -1, 11996, 1012, 1010, -1, 15839, 1012, 11996, -1, 15841, 1012, 15839, -1, 15842, 1012, 15841, -1, 15846, 1012, 15842, -1, 15846, 7673, 1012, -1, 7673, 7672, 1012, -1, 7672, 1034, 1012, -1, 7672, 7679, 1034, -1, 7679, 2963, 1034, -1, 7679, 7678, 2963, -1, 11356, 192, 191, -1, 12829, 192, 11356, -1, 12830, 192, 12829, -1, 12832, 192, 12830, -1, 12833, 192, 12832, -1, 12836, 192, 12833, -1, 192, 14459, 1876, -1, 12836, 14459, 192, -1, 14459, 90, 1876, -1, 14459, 14461, 90, -1, 7381, 1832, 48, -1, 7381, 7380, 1832, -1, 1832, 7379, 1798, -1, 7380, 7379, 1832, -1, 7379, 1799, 1798, -1, 7379, 7397, 1799, -1, 7397, 1780, 1799, -1, 7397, 7391, 1780, -1, 1780, 7375, 1768, -1, 7391, 7375, 1780, -1, 1768, 7377, 1752, -1, 7375, 7377, 1768, -1, 1722, 7402, 1710, -1, 7405, 7402, 1722, -1, 1710, 7404, 1667, -1, 7402, 7404, 1710, -1, 1667, 7421, 1670, -1, 7404, 7421, 1667, -1, 1670, 7415, 1643, -1, 7421, 7415, 1670, -1, 1643, 7399, 1631, -1, 7415, 7399, 1643, -1, 1631, 7401, 1590, -1, 7399, 7401, 1631, -1, 1576, 7426, 1565, -1, 7429, 7426, 1576, -1, 1565, 7428, 1543, -1, 7426, 7428, 1565, -1, 1543, 7445, 1544, -1, 7428, 7445, 1543, -1, 1544, 7439, 1519, -1, 7445, 7439, 1544, -1, 1519, 7423, 1503, -1, 7439, 7423, 1519, -1, 1503, 7425, 1466, -1, 7423, 7425, 1503, -1, 1431, 7450, 1420, -1, 7453, 7450, 1431, -1, 1420, 7452, 1386, -1, 7450, 7452, 1420, -1, 1386, 7469, 1387, -1, 7452, 7469, 1386, -1, 1387, 7463, 1372, -1, 7469, 7463, 1387, -1, 1372, 7447, 1350, -1, 7463, 7447, 1372, -1, 1350, 7449, 1310, -1, 7447, 7449, 1350, -1, 1272, 7368, 1252, -1, 7366, 7368, 1272, -1, 1253, 11954, 3125, -1, 1253, 15758, 11954, -1, 1253, 15774, 15758, -1, 1252, 7374, 1253, -1, 7368, 7374, 1252, -1, 1253, 15777, 15774, -1, 7374, 15778, 1253, -1, 1253, 15778, 15777, -1, 1854, 14447, 1865, -1, 14443, 14447, 1854, -1, 1865, 14441, 1875, -1, 14447, 14441, 1865, -1, 1875, 11369, 1892, -1, 1875, 12804, 11369, -1, 1875, 12802, 12804, -1, 14441, 12805, 1875, -1, 1875, 12803, 12802, -1, 12805, 12807, 1875, -1, 1875, 12807, 12803, -1, 1820, 14439, 1828, -1, 14440, 14439, 1820, -1, 1828, 14444, 1848, -1, 14439, 14444, 1828, -1, 1848, 14443, 1854, -1, 14444, 14443, 1848, -1, 1744, 7343, 1753, -1, 7340, 7343, 1744, -1, 1753, 7342, 1769, -1, 7343, 7342, 1753, -1, 1769, 7347, 1781, -1, 7342, 7347, 1769, -1, 1666, 7330, 1711, -1, 7331, 7330, 1666, -1, 1711, 7334, 1723, -1, 7330, 7334, 1711, -1, 1723, 7340, 1744, -1, 7334, 7340, 1723, -1, 1592, 7282, 1617, -1, 7278, 7282, 1592, -1, 1617, 7276, 1632, -1, 7282, 7276, 1617, -1, 1632, 7275, 1644, -1, 7276, 7275, 1632, -1, 1542, 7272, 1566, -1, 7273, 7272, 1542, -1, 1566, 7279, 1577, -1, 7272, 7279, 1566, -1, 1577, 7278, 1592, -1, 7279, 7278, 1577, -1, 1465, 7309, 1481, -1, 7306, 7309, 1465, -1, 1481, 7308, 1504, -1, 7309, 7308, 1481, -1, 1504, 7313, 1518, -1, 7308, 7313, 1504, -1, 1388, 7296, 1421, -1, 7297, 7296, 1388, -1, 1421, 7300, 1432, -1, 7296, 7300, 1421, -1, 1432, 7306, 1465, -1, 7300, 7306, 1432, -1, 7254, 1327, 1309, -1, 7254, 7258, 1327, -1, 1327, 7252, 1351, -1, 7258, 7252, 1327, -1, 7252, 1375, 1351, -1, 7252, 7251, 1375, -1, 11944, 1256, 1255, -1, 15728, 1256, 11944, -1, 15730, 1256, 15728, -1, 15731, 1256, 15730, -1, 15735, 1256, 15731, -1, 15735, 7249, 1256, -1, 7249, 7248, 1256, -1, 7248, 1273, 1256, -1, 7248, 7255, 1273, -1, 7255, 1309, 1273, -1, 7255, 7254, 1309, -1, 12790, 368, 11382, -1, 12791, 368, 12790, -1, 12793, 368, 12791, -1, 12794, 368, 12793, -1, 11382, 368, 367, -1, 12794, 12797, 368, -1, 12797, 14457, 368, -1, 14457, 400, 368, -1, 14457, 14455, 400, -1, 14455, 401, 400, -1, 14455, 14454, 401, -1, 14454, 1894, 401, -1, 14454, 14453, 1894, -1, 1894, 14450, 1878, -1, 14453, 14450, 1894, -1, 14450, 110, 1878, -1, 14450, 14449, 110, -1, 113, 7358, 1858, -1, 7359, 7358, 113, -1, 1858, 7356, 142, -1, 7358, 7356, 1858, -1, 142, 7354, 71, -1, 7356, 7354, 142, -1, 71, 7350, 1783, -1, 7354, 7350, 71, -1, 1783, 7344, 1784, -1, 7350, 7344, 1783, -1, 1784, 7339, 1765, -1, 7344, 7339, 1784, -1, 1749, 7293, 1750, -1, 7294, 7293, 1749, -1, 1750, 7290, 3355, -1, 7293, 7290, 1750, -1, 3355, 7289, 1679, -1, 7290, 7289, 3355, -1, 1679, 7291, 1647, -1, 7289, 7291, 1679, -1, 1647, 7285, 1648, -1, 7291, 7285, 1647, -1, 1648, 7284, 1635, -1, 7285, 7284, 1648, -1, 1614, 7324, 1612, -1, 7325, 7324, 1614, -1, 1612, 7322, 3292, -1, 7324, 7322, 1612, -1, 3292, 7320, 3266, -1, 7322, 7320, 3292, -1, 3266, 7316, 1525, -1, 7320, 7316, 3266, -1, 1525, 7310, 1509, -1, 7316, 7310, 1525, -1, 1509, 7305, 1486, -1, 7310, 7305, 1509, -1, 1472, 7269, 1473, -1, 7270, 7269, 1472, -1, 1473, 7266, 1474, -1, 7269, 7266, 1473, -1, 1474, 7265, 1448, -1, 7266, 7265, 1474, -1, 1448, 7267, 1377, -1, 7265, 7267, 1448, -1, 1377, 7261, 1353, -1, 7267, 7261, 1377, -1, 1353, 11930, 3176, -1, 1353, 15721, 11930, -1, 1353, 15737, 15721, -1, 7261, 7260, 1353, -1, 1353, 15740, 15737, -1, 7260, 15741, 1353, -1, 1353, 15741, 15740, -1, 376, 14962, 399, -1, 14967, 14962, 376, -1, 1959, 11400, 1960, -1, 1959, 14084, 11400, -1, 1959, 14082, 14084, -1, 399, 14085, 1959, -1, 14962, 14085, 399, -1, 1959, 14083, 14082, -1, 14085, 14087, 1959, -1, 1959, 14087, 14083, -1, 1867, 11020, 1879, -1, 11021, 11020, 1867, -1, 1879, 11027, 1909, -1, 11020, 11027, 1879, -1, 1909, 11026, 377, -1, 11027, 11026, 1909, -1, 101, 11016, 140, -1, 11017, 11016, 101, -1, 140, 11015, 1857, -1, 11016, 11015, 140, -1, 1857, 11021, 1867, -1, 11015, 11021, 1857, -1, 1748, 11045, 1787, -1, 11044, 11045, 1748, -1, 1787, 11051, 72, -1, 11045, 11051, 1787, -1, 72, 11050, 70, -1, 11051, 11050, 72, -1, 3352, 11040, 1746, -1, 11041, 11040, 3352, -1, 1746, 11039, 1747, -1, 11040, 11039, 1746, -1, 1747, 11044, 1748, -1, 11039, 11044, 1747, -1, 1611, 10960, 1646, -1, 10961, 10960, 1611, -1, 1646, 10967, 1678, -1, 10960, 10967, 1646, -1, 1678, 10966, 3343, -1, 10967, 10966, 1678, -1, 3283, 10956, 1609, -1, 10957, 10956, 3283, -1, 1609, 10955, 1610, -1, 10956, 10955, 1609, -1, 1610, 10961, 1611, -1, 10955, 10961, 1610, -1, 1485, 10984, 1508, -1, 10985, 10984, 1485, -1, 1508, 10991, 3265, -1, 10984, 10991, 1508, -1, 3265, 10990, 3276, -1, 10991, 10990, 3265, -1, 10981, 1470, 1446, -1, 10981, 10980, 1470, -1, 1470, 10979, 1471, -1, 10980, 10979, 1470, -1, 10979, 1485, 1471, -1, 10979, 10985, 1485, -1, 11909, 1357, 1356, -1, 16986, 1357, 11909, -1, 16988, 1357, 16986, -1, 16989, 1357, 16988, -1, 16993, 1357, 16989, -1, 10996, 1357, 16993, -1, 1357, 10995, 1447, -1, 10996, 10995, 1357, -1, 10995, 1445, 1447, -1, 10995, 11003, 1445, -1, 12752, 1362, 11641, -1, 12753, 1362, 12752, -1, 12755, 1362, 12753, -1, 12756, 1362, 12755, -1, 11641, 1362, 3184, -1, 12756, 12759, 1362, -1, 12759, 14437, 1362, -1, 14437, 1331, 1362, -1, 14437, 14435, 1331, -1, 14435, 1275, 1331, -1, 14435, 14434, 1275, -1, 14434, 1263, 1275, -1, 14434, 14433, 1263, -1, 1263, 14430, 1233, -1, 14433, 14430, 1263, -1, 14430, 1232, 1233, -1, 14430, 14429, 1232, -1, 1185, 7218, 1172, -1, 7219, 7218, 1185, -1, 1172, 7216, 1173, -1, 7218, 7216, 1172, -1, 1173, 7214, 1129, -1, 7216, 7214, 1173, -1, 1129, 7210, 1111, -1, 7214, 7210, 1129, -1, 1111, 7204, 1112, -1, 7210, 7204, 1111, -1, 1112, 7199, 1049, -1, 7204, 7199, 1112, -1, 1048, 7187, 1053, -1, 7188, 7187, 1048, -1, 1053, 7185, 1054, -1, 7187, 7185, 1053, -1, 1054, 7184, 994, -1, 7185, 7184, 1054, -1, 994, 7183, 968, -1, 7184, 7183, 994, -1, 968, 7179, 969, -1, 7183, 7179, 968, -1, 969, 7178, 898, -1, 7179, 7178, 969, -1, 897, 7160, 907, -1, 7161, 7160, 897, -1, 907, 7158, 908, -1, 7160, 7158, 907, -1, 908, 7156, 845, -1, 7158, 7156, 908, -1, 845, 7152, 831, -1, 7156, 7152, 845, -1, 831, 7146, 810, -1, 7152, 7146, 831, -1, 810, 7141, 788, -1, 7146, 7141, 810, -1, 779, 7245, 749, -1, 7246, 7245, 779, -1, 749, 7242, 750, -1, 7245, 7242, 749, -1, 750, 7241, 747, -1, 7242, 7241, 750, -1, 747, 7243, 694, -1, 7241, 7243, 747, -1, 694, 7237, 677, -1, 7243, 7237, 694, -1, 677, 12016, 864, -1, 677, 15684, 12016, -1, 677, 15700, 15684, -1, 7237, 7236, 677, -1, 677, 15703, 15700, -1, 7236, 15704, 677, -1, 677, 15704, 15703, -1, 3182, 14382, 1332, -1, 14387, 14382, 3182, -1, 1359, 11648, 1360, -1, 1359, 12648, 11648, -1, 1359, 12646, 12648, -1, 1332, 12649, 1359, -1, 14382, 12649, 1332, -1, 1359, 12647, 12646, -1, 12649, 12651, 1359, -1, 1359, 12651, 12647, -1, 1206, 6861, 1234, -1, 6860, 6861, 1206, -1, 1234, 6867, 1276, -1, 6861, 6867, 1234, -1, 1276, 6866, 3174, -1, 6867, 6866, 1276, -1, 3120, 6856, 1174, -1, 6857, 6856, 3120, -1, 1174, 6855, 1186, -1, 6856, 6855, 1174, -1, 1186, 6860, 1206, -1, 6855, 6860, 1186, -1, 1067, 6837, 1113, -1, 6836, 6837, 1067, -1, 1113, 6843, 1128, -1, 6837, 6843, 1113, -1, 1128, 6842, 3111, -1, 6843, 6842, 1128, -1, 2716, 6832, 1055, -1, 6833, 6832, 2716, -1, 1055, 6831, 1066, -1, 6832, 6831, 1055, -1, 1066, 6836, 1067, -1, 6831, 6836, 1066, -1, 932, 6812, 970, -1, 6813, 6812, 932, -1, 970, 6819, 995, -1, 6812, 6819, 970, -1, 995, 6818, 2648, -1, 6819, 6818, 995, -1, 2100, 6808, 909, -1, 6809, 6808, 2100, -1, 909, 6807, 931, -1, 6808, 6807, 909, -1, 931, 6813, 932, -1, 6807, 6813, 931, -1, 787, 6884, 811, -1, 6885, 6884, 787, -1, 811, 6891, 846, -1, 6884, 6891, 811, -1, 846, 6890, 2048, -1, 6891, 6890, 846, -1, 6881, 748, 1551, -1, 6881, 6880, 748, -1, 748, 6879, 777, -1, 6880, 6879, 748, -1, 6879, 787, 777, -1, 6879, 6885, 787, -1, 12026, 676, 674, -1, 15580, 676, 12026, -1, 15582, 676, 15580, -1, 15583, 676, 15582, -1, 15587, 676, 15583, -1, 6896, 676, 15587, -1, 676, 6895, 695, -1, 6896, 6895, 676, -1, 6895, 1436, 695, -1, 6895, 6903, 1436, -1, 11614, 1261, 3139, -1, 12713, 1261, 11614, -1, 12714, 1261, 12713, -1, 12716, 1261, 12714, -1, 12717, 1261, 12716, -1, 12720, 1261, 12717, -1, 1261, 14411, 1230, -1, 12720, 14411, 1261, -1, 14411, 1204, 1230, -1, 14411, 14413, 1204, -1, 7029, 1163, 1164, -1, 7029, 7028, 1163, -1, 1163, 7027, 2943, -1, 7028, 7027, 1163, -1, 7027, 2944, 2943, -1, 7027, 7045, 2944, -1, 7045, 1098, 2944, -1, 7045, 7039, 1098, -1, 1098, 7023, 1078, -1, 7039, 7023, 1098, -1, 1078, 7025, 1070, -1, 7023, 7025, 1078, -1, 1039, 7050, 1040, -1, 7053, 7050, 1039, -1, 1040, 7052, 951, -1, 7050, 7052, 1040, -1, 951, 7069, 953, -1, 7052, 7069, 951, -1, 953, 7063, 952, -1, 7069, 7063, 953, -1, 952, 7047, 955, -1, 7063, 7047, 952, -1, 955, 7049, 934, -1, 7047, 7049, 955, -1, 890, 7110, 889, -1, 7113, 7110, 890, -1, 889, 7112, 795, -1, 7110, 7112, 889, -1, 795, 7129, 796, -1, 7112, 7129, 795, -1, 796, 7123, 797, -1, 7129, 7123, 796, -1, 797, 7107, 801, -1, 7123, 7107, 797, -1, 801, 7109, 773, -1, 7107, 7109, 801, -1, 745, 7086, 740, -1, 7089, 7086, 745, -1, 740, 7088, 1042, -1, 7086, 7088, 740, -1, 1042, 7105, 1043, -1, 7088, 7105, 1042, -1, 1043, 7099, 689, -1, 7105, 7099, 1043, -1, 689, 7083, 668, -1, 7099, 7083, 689, -1, 668, 7085, 643, -1, 7083, 7085, 668, -1, 617, 7076, 467, -1, 7074, 7076, 617, -1, 413, 11989, 414, -1, 413, 15647, 11989, -1, 413, 15663, 15647, -1, 467, 7082, 413, -1, 7076, 7082, 467, -1, 413, 15666, 15663, -1, 7082, 15667, 413, -1, 413, 15667, 15666, -1, 1180, 14427, 1202, -1, 14423, 14427, 1180, -1, 1202, 14421, 1258, -1, 14427, 14421, 1202, -1, 1258, 11626, 1259, -1, 1258, 12765, 11626, -1, 1258, 12763, 12765, -1, 14421, 12766, 1258, -1, 1258, 12764, 12763, -1, 12766, 12768, 1258, -1, 1258, 12768, 12764, -1, 1160, 14419, 1161, -1, 14420, 14419, 1160, -1, 1161, 14424, 1162, -1, 14419, 14424, 1161, -1, 1162, 14423, 1180, -1, 14424, 14423, 1162, -1, 1064, 7203, 1069, -1, 7200, 7203, 1064, -1, 1069, 7202, 1079, -1, 7203, 7202, 1069, -1, 1079, 7207, 1097, -1, 7202, 7207, 1079, -1, 992, 7190, 1041, -1, 7191, 7190, 992, -1, 1041, 7194, 1044, -1, 7190, 7194, 1041, -1, 1044, 7200, 1064, -1, 7194, 7200, 1044, -1, 913, 7176, 935, -1, 7172, 7176, 913, -1, 935, 7170, 956, -1, 7176, 7170, 935, -1, 956, 7169, 950, -1, 7170, 7169, 956, -1, 848, 7166, 891, -1, 7167, 7166, 848, -1, 891, 7173, 892, -1, 7166, 7173, 891, -1, 892, 7172, 913, -1, 7173, 7172, 892, -1, 772, 7145, 781, -1, 7142, 7145, 772, -1, 781, 7144, 802, -1, 7145, 7144, 781, -1, 802, 7149, 798, -1, 7144, 7149, 802, -1, 741, 7132, 742, -1, 7133, 7132, 741, -1, 742, 7136, 743, -1, 7132, 7136, 742, -1, 743, 7142, 772, -1, 7136, 7142, 743, -1, 7230, 650, 642, -1, 7230, 7234, 650, -1, 650, 7228, 664, -1, 7234, 7228, 650, -1, 7228, 688, 664, -1, 7228, 7227, 688, -1, 12003, 572, 573, -1, 15691, 572, 12003, -1, 15693, 572, 15691, -1, 15694, 572, 15693, -1, 15698, 572, 15694, -1, 15698, 7225, 572, -1, 7225, 7224, 572, -1, 7224, 618, 572, -1, 7224, 7231, 618, -1, 7231, 642, 618, -1, 7231, 7230, 642, -1, 12673, 1604, 11668, -1, 12674, 1604, 12673, -1, 12676, 1604, 12674, -1, 12677, 1604, 12676, -1, 11668, 1604, 3273, -1, 12677, 12680, 1604, -1, 12680, 14409, 1604, -1, 14409, 1569, 1604, -1, 14409, 14407, 1569, -1, 14407, 1550, 1569, -1, 14407, 14406, 1550, -1, 14406, 1515, 1550, -1, 14406, 14405, 1515, -1, 1515, 14402, 1511, -1, 14405, 14402, 1515, -1, 14402, 3212, 1511, -1, 14402, 14401, 3212, -1, 3213, 6994, 1428, -1, 6995, 6994, 3213, -1, 1428, 6992, 1414, -1, 6994, 6992, 1428, -1, 1414, 6990, 1407, -1, 6992, 6990, 1414, -1, 1407, 6986, 1365, -1, 6990, 6986, 1407, -1, 1365, 6980, 1366, -1, 6986, 6980, 1365, -1, 1366, 6975, 1281, -1, 6980, 6975, 1366, -1, 1282, 7021, 1285, -1, 7022, 7021, 1282, -1, 1285, 7019, 1270, -1, 7021, 7019, 1285, -1, 1270, 7018, 1246, -1, 7019, 7018, 1270, -1, 1246, 7017, 1200, -1, 7018, 7017, 1246, -1, 1200, 7013, 1198, -1, 7017, 7013, 1200, -1, 1198, 7012, 1134, -1, 7013, 7012, 1198, -1, 1137, 6936, 1139, -1, 6937, 6936, 1137, -1, 1139, 6934, 1126, -1, 6936, 6934, 1139, -1, 1126, 6932, 1117, -1, 6934, 6932, 1126, -1, 1117, 6928, 1075, -1, 6932, 6928, 1117, -1, 1075, 6922, 1072, -1, 6928, 6922, 1075, -1, 1072, 6917, 2479, -1, 6922, 6917, 1072, -1, 2390, 6963, 1004, -1, 6964, 6963, 2390, -1, 1004, 6960, 988, -1, 6963, 6960, 1004, -1, 988, 6959, 964, -1, 6960, 6959, 988, -1, 964, 6961, 941, -1, 6959, 6961, 964, -1, 941, 6955, 939, -1, 6961, 6955, 941, -1, 939, 12031, 1962, -1, 939, 15610, 12031, -1, 939, 15626, 15610, -1, 6955, 6954, 939, -1, 939, 15629, 15626, -1, 6954, 15630, 939, -1, 939, 15630, 15629, -1, 1568, 14466, 1579, -1, 14471, 14466, 1568, -1, 1602, 11286, 3287, -1, 1602, 12882, 11286, -1, 1602, 12880, 12882, -1, 1579, 12883, 1602, -1, 14466, 12883, 1579, -1, 1602, 12881, 12880, -1, 12883, 12885, 1602, -1, 1602, 12885, 12881, -1, 1512, 7533, 1513, -1, 7532, 7533, 1512, -1, 1513, 7539, 1527, -1, 7533, 7539, 1513, -1, 1527, 7538, 1548, -1, 7539, 7538, 1527, -1, 1417, 7528, 1429, -1, 7529, 7528, 1417, -1, 1429, 7527, 1443, -1, 7528, 7527, 1429, -1, 1443, 7532, 1512, -1, 7527, 7532, 1443, -1, 1313, 7484, 1364, -1, 7485, 7484, 1313, -1, 1364, 7491, 1381, -1, 7484, 7491, 1364, -1, 1381, 7490, 1406, -1, 7491, 7490, 1381, -1, 1269, 7480, 1284, -1, 7481, 7480, 1269, -1, 1284, 7479, 1312, -1, 7480, 7479, 1284, -1, 1312, 7485, 1313, -1, 7479, 7485, 1312, -1, 1149, 7508, 1199, -1, 7509, 7508, 1149, -1, 1199, 7515, 1225, -1, 7508, 7515, 1199, -1, 1225, 7514, 1245, -1, 7515, 7514, 1225, -1, 1116, 7504, 1140, -1, 7505, 7504, 1116, -1, 1140, 7503, 1150, -1, 7504, 7503, 1140, -1, 1150, 7509, 1149, -1, 7503, 7509, 1150, -1, 1030, 7569, 1074, -1, 7568, 7569, 1030, -1, 1074, 7575, 1081, -1, 7569, 7575, 1074, -1, 1081, 7574, 1115, -1, 7575, 7574, 1081, -1, 7565, 1003, 966, -1, 7565, 7564, 1003, -1, 1003, 7563, 1031, -1, 7564, 7563, 1003, -1, 7563, 1030, 1031, -1, 7563, 7568, 1030, -1, 12023, 943, 942, -1, 15802, 943, 12023, -1, 15804, 943, 15802, -1, 15805, 943, 15804, -1, 15809, 943, 15805, -1, 7544, 943, 15809, -1, 943, 7543, 944, -1, 7544, 7543, 943, -1, 7543, 965, 944, -1, 7543, 7551, 965, -1, 11656, 1458, 3227, -1, 12634, 1458, 11656, -1, 12635, 1458, 12634, -1, 12637, 1458, 12635, -1, 12638, 1458, 12637, -1, 12641, 1458, 12638, -1, 1458, 14383, 1459, -1, 12641, 14383, 1458, -1, 14383, 1477, 1459, -1, 14383, 14385, 1477, -1, 6853, 1346, 1434, -1, 6853, 6852, 1346, -1, 1346, 6851, 1347, -1, 6852, 6851, 1346, -1, 6851, 1323, 1347, -1, 6851, 6869, 1323, -1, 6869, 1307, 1323, -1, 6869, 6863, 1307, -1, 1307, 6847, 1301, -1, 6863, 6847, 1307, -1, 1301, 6849, 1320, -1, 6847, 6849, 1301, -1, 1299, 6826, 3129, -1, 6829, 6826, 1299, -1, 3129, 6828, 1167, -1, 6826, 6828, 3129, -1, 1167, 6845, 1168, -1, 6828, 6845, 1167, -1, 1168, 6839, 1169, -1, 6845, 6839, 1168, -1, 1169, 6823, 3113, -1, 6839, 6823, 1169, -1, 3113, 6825, 1155, -1, 6823, 6825, 3113, -1, 1145, 6802, 2785, -1, 6805, 6802, 1145, -1, 2785, 6804, 1059, -1, 6802, 6804, 2785, -1, 1059, 6821, 1062, -1, 6804, 6821, 1059, -1, 1062, 6815, 1060, -1, 6821, 6815, 1062, -1, 1060, 6799, 2653, -1, 6815, 6799, 1060, -1, 2653, 6801, 1020, -1, 6799, 6801, 2653, -1, 1021, 6874, 916, -1, 6877, 6874, 1021, -1, 916, 6876, 917, -1, 6874, 6876, 916, -1, 917, 6893, 887, -1, 6876, 6893, 917, -1, 887, 6887, 873, -1, 6893, 6887, 887, -1, 873, 6871, 871, -1, 6887, 6871, 873, -1, 871, 6873, 865, -1, 6871, 6873, 871, -1, 858, 6900, 753, -1, 6898, 6900, 858, -1, 754, 12033, 1418, -1, 754, 15573, 12033, -1, 754, 15589, 15573, -1, 753, 6906, 754, -1, 6900, 6906, 753, -1, 754, 15592, 15589, -1, 6906, 15593, 754, -1, 754, 15593, 15592, -1, 1438, 14399, 1476, -1, 14395, 14399, 1438, -1, 1476, 14393, 1460, -1, 14399, 14393, 1476, -1, 1460, 11662, 1457, -1, 1460, 12687, 11662, -1, 1460, 12685, 12687, -1, 14393, 12688, 1460, -1, 1460, 12686, 12685, -1, 12688, 12690, 1460, -1, 1460, 12690, 12686, -1, 1345, 14391, 1435, -1, 14392, 14391, 1345, -1, 1435, 14396, 1437, -1, 14391, 14396, 1435, -1, 1437, 14395, 1438, -1, 14396, 14395, 1437, -1, 1298, 6979, 1319, -1, 6976, 6979, 1298, -1, 1319, 6978, 1302, -1, 6979, 6978, 1319, -1, 1302, 6983, 1306, -1, 6978, 6983, 1302, -1, 1166, 6966, 1296, -1, 6967, 6966, 1166, -1, 1296, 6970, 1297, -1, 6966, 6970, 1296, -1, 1297, 6976, 1298, -1, 6970, 6976, 1297, -1, 1144, 7010, 1152, -1, 7006, 7010, 1144, -1, 1152, 7004, 3116, -1, 7010, 7004, 1152, -1, 3116, 7003, 1170, -1, 7004, 7003, 3116, -1, 1058, 7000, 1142, -1, 7001, 7000, 1058, -1, 1142, 7007, 1143, -1, 7000, 7007, 1142, -1, 1143, 7006, 1144, -1, 7007, 7006, 1143, -1, 1024, 6921, 1037, -1, 6918, 6921, 1024, -1, 1037, 6920, 2678, -1, 6921, 6920, 1037, -1, 2678, 6925, 1061, -1, 6920, 6925, 2678, -1, 886, 6908, 1022, -1, 6909, 6908, 886, -1, 1022, 6912, 1023, -1, 6908, 6912, 1022, -1, 1023, 6918, 1024, -1, 6912, 6918, 1023, -1, 6948, 884, 860, -1, 6948, 6952, 884, -1, 884, 6946, 872, -1, 6952, 6946, 884, -1, 6946, 874, 872, -1, 6946, 6945, 874, -1, 12038, 759, 756, -1, 15617, 759, 12038, -1, 15619, 759, 15617, -1, 15620, 759, 15619, -1, 15624, 759, 15620, -1, 15624, 6943, 759, -1, 6943, 6942, 759, -1, 6942, 859, 759, -1, 6942, 6949, 859, -1, 6949, 860, 859, -1, 6949, 6948, 860, -1, 12597, 18651, 11570, -1, 12598, 18651, 12597, -1, 12600, 18651, 12598, -1, 12601, 18651, 12600, -1, 11570, 18651, 11568, -1, 12601, 6706, 18651, -1, 6706, 6705, 18651, -1, 6705, 18681, 18651, -1, 6705, 6703, 18681, -1, 6703, 18682, 18681, -1, 6703, 6702, 18682, -1, 6702, 20082, 18682, -1, 6702, 6701, 20082, -1, 20082, 6697, 20068, -1, 6701, 6697, 20082, -1, 6697, 18440, 20068, -1, 6697, 6696, 18440, -1, 18442, 6736, 20047, -1, 6737, 6736, 18442, -1, 20047, 6734, 18464, -1, 6736, 6734, 20047, -1, 18464, 6732, 18411, -1, 6734, 6732, 18464, -1, 18411, 6728, 19975, -1, 6732, 6728, 18411, -1, 19975, 6722, 19976, -1, 6728, 6722, 19975, -1, 19976, 6717, 19957, -1, 6722, 6717, 19976, -1, 19941, 6763, 19940, -1, 6764, 6763, 19941, -1, 19940, 6760, 21443, -1, 6763, 6760, 19940, -1, 21443, 6759, 19875, -1, 6760, 6759, 21443, -1, 19875, 6761, 19843, -1, 6759, 6761, 19875, -1, 19843, 6755, 19844, -1, 6761, 6755, 19843, -1, 19844, 6754, 19831, -1, 6755, 6754, 19844, -1, 19804, 6794, 19805, -1, 6795, 6794, 19804, -1, 19805, 6792, 21386, -1, 6794, 6792, 19805, -1, 21386, 6790, 21367, -1, 6792, 6790, 21386, -1, 21367, 6786, 19724, -1, 6790, 6786, 21367, -1, 19724, 6780, 19708, -1, 6786, 6780, 19724, -1, 19708, 6775, 19685, -1, 6780, 6775, 19708, -1, 19670, 14380, 19671, -1, 14381, 14380, 19670, -1, 19671, 14377, 19672, -1, 14380, 14377, 19671, -1, 19672, 14376, 19652, -1, 14377, 14376, 19672, -1, 19652, 14378, 19585, -1, 14376, 14378, 19652, -1, 19585, 14372, 19568, -1, 14378, 14372, 19585, -1, 19568, 11823, 11819, -1, 19568, 15536, 11823, -1, 19568, 15552, 15536, -1, 14372, 14371, 19568, -1, 19568, 15555, 15552, -1, 14371, 15556, 19568, -1, 19568, 15556, 15555, -1, 18655, 6245, 18680, -1, 6250, 6245, 18655, -1, 20143, 11561, 11560, -1, 20143, 12470, 11561, -1, 20143, 12468, 12470, -1, 18680, 6244, 20143, -1, 6245, 6244, 18680, -1, 20143, 12469, 12468, -1, 6244, 12472, 20143, -1, 20143, 12472, 12469, -1, 20057, 6316, 20069, -1, 6317, 6316, 20057, -1, 20069, 6323, 20096, -1, 6316, 6323, 20069, -1, 20096, 6322, 18656, -1, 6323, 6322, 20096, -1, 18433, 6312, 18460, -1, 6313, 6312, 18433, -1, 18460, 6311, 20046, -1, 6312, 6311, 18460, -1, 20046, 6317, 20057, -1, 6311, 6317, 20046, -1, 19939, 6340, 19974, -1, 6341, 6340, 19939, -1, 19974, 6347, 18412, -1, 6340, 6347, 19974, -1, 18412, 6346, 18410, -1, 6347, 6346, 18412, -1, 21440, 6336, 19937, -1, 6337, 6336, 21440, -1, 19937, 6335, 19938, -1, 6336, 6335, 19937, -1, 19938, 6341, 19939, -1, 6335, 6341, 19938, -1, 19809, 6293, 19842, -1, 6292, 6293, 19809, -1, 19842, 6299, 19874, -1, 6293, 6299, 19842, -1, 19874, 6298, 21431, -1, 6299, 6298, 19874, -1, 21379, 6288, 19806, -1, 6289, 6288, 21379, -1, 19806, 6287, 19808, -1, 6288, 6287, 19806, -1, 19808, 6292, 19809, -1, 6287, 6292, 19808, -1, 19686, 6269, 19709, -1, 6268, 6269, 19686, -1, 19709, 6275, 21366, -1, 6269, 6275, 19709, -1, 21366, 6274, 21372, -1, 6275, 6274, 21366, -1, 6265, 19673, 19655, -1, 6265, 6264, 19673, -1, 19673, 6263, 19674, -1, 6264, 6263, 19673, -1, 6263, 19686, 19674, -1, 6263, 6268, 19686, -1, 11843, 19567, 11841, -1, 15395, 19567, 11843, -1, 15397, 19567, 15395, -1, 15398, 19567, 15397, -1, 15402, 19567, 15398, -1, 14299, 19567, 15402, -1, 19567, 14298, 19653, -1, 14299, 14298, 19567, -1, 14298, 19654, 19653, -1, 14298, 14306, 19654, -1, 11594, 18502, 11592, -1, 12563, 18502, 11594, -1, 12564, 18502, 12563, -1, 12566, 18502, 12564, -1, 12567, 18502, 12566, -1, 6586, 18502, 12567, -1, 18502, 6578, 20066, -1, 6586, 6578, 18502, -1, 6578, 18427, 20066, -1, 6578, 6580, 18427, -1, 6665, 20021, 18390, -1, 6665, 6664, 20021, -1, 20021, 6663, 19989, -1, 6664, 6663, 20021, -1, 6663, 19990, 19989, -1, 6663, 6681, 19990, -1, 6681, 19971, 19990, -1, 6681, 6675, 19971, -1, 19971, 6659, 19959, -1, 6675, 6659, 19971, -1, 19959, 6661, 19943, -1, 6659, 6661, 19959, -1, 19914, 6638, 19902, -1, 6641, 6638, 19914, -1, 19902, 6640, 19863, -1, 6638, 6640, 19902, -1, 19863, 6657, 19867, -1, 6640, 6657, 19863, -1, 19867, 6651, 19840, -1, 6657, 6651, 19867, -1, 19840, 6635, 19829, -1, 6651, 6635, 19840, -1, 19829, 6637, 19812, -1, 6635, 6637, 19829, -1, 19775, 6590, 19765, -1, 6593, 6590, 19775, -1, 19765, 6592, 19743, -1, 6590, 6592, 19765, -1, 19743, 6609, 19744, -1, 6592, 6609, 19743, -1, 19744, 6603, 19717, -1, 6609, 6603, 19744, -1, 19717, 6587, 19698, -1, 6603, 6587, 19717, -1, 19698, 6589, 19668, -1, 6587, 6589, 19698, -1, 19639, 6614, 19628, -1, 6617, 6614, 19639, -1, 19628, 6616, 19593, -1, 6614, 6616, 19628, -1, 19593, 6633, 19594, -1, 6616, 6633, 19593, -1, 19594, 6627, 19583, -1, 6633, 6627, 19594, -1, 19583, 6611, 19563, -1, 6627, 6611, 19583, -1, 19563, 6613, 19523, -1, 6611, 6613, 19563, -1, 19488, 14351, 19471, -1, 14349, 14351, 19488, -1, 19470, 11762, 11759, -1, 19470, 15499, 11762, -1, 19470, 15515, 15499, -1, 19471, 14357, 19470, -1, 14351, 14357, 19471, -1, 19470, 15518, 15515, -1, 14357, 15519, 19470, -1, 19470, 15519, 15518, -1, 20044, 6694, 20055, -1, 6690, 6694, 20044, -1, 20055, 6688, 20065, -1, 6694, 6688, 20055, -1, 20065, 11580, 11579, -1, 20065, 12610, 11580, -1, 20065, 12608, 12610, -1, 6688, 6687, 20065, -1, 20065, 12609, 12608, -1, 6687, 12612, 20065, -1, 20065, 12612, 12609, -1, 20011, 6684, 20020, -1, 6685, 6684, 20011, -1, 20020, 6691, 20038, -1, 6684, 6691, 20020, -1, 20038, 6690, 20044, -1, 6691, 6690, 20038, -1, 19935, 6721, 19945, -1, 6718, 6721, 19935, -1, 19945, 6720, 19960, -1, 6721, 6720, 19945, -1, 19960, 6725, 19972, -1, 6720, 6725, 19960, -1, 19862, 6708, 19901, -1, 6709, 6708, 19862, -1, 19901, 6712, 19913, -1, 6708, 6712, 19901, -1, 19913, 6718, 19935, -1, 6712, 6718, 19913, -1, 19792, 6752, 19811, -1, 6748, 6752, 19792, -1, 19811, 6746, 19827, -1, 6752, 6746, 19811, -1, 19827, 6745, 19838, -1, 6746, 6745, 19827, -1, 19746, 6742, 19766, -1, 6743, 6742, 19746, -1, 19766, 6749, 19776, -1, 6742, 6749, 19766, -1, 19776, 6748, 19792, -1, 6749, 6748, 19776, -1, 19667, 6779, 19681, -1, 6776, 6779, 19667, -1, 19681, 6778, 19699, -1, 6779, 6778, 19681, -1, 19699, 6783, 19718, -1, 6778, 6783, 19699, -1, 19598, 6766, 19627, -1, 6767, 6766, 19598, -1, 19627, 6770, 19638, -1, 6766, 6770, 19627, -1, 19638, 6776, 19667, -1, 6770, 6776, 19638, -1, 14365, 19541, 19524, -1, 14365, 14369, 19541, -1, 19541, 14363, 19564, -1, 14369, 14363, 19541, -1, 14363, 19582, 19564, -1, 14363, 14362, 19582, -1, 11768, 19473, 11769, -1, 15543, 19473, 11768, -1, 15545, 19473, 15543, -1, 15546, 19473, 15545, -1, 15550, 19473, 15546, -1, 15550, 14360, 19473, -1, 14360, 14359, 19473, -1, 14359, 19489, 19473, -1, 14359, 14366, 19489, -1, 14366, 19524, 19489, -1, 14366, 14365, 19524, -1, 11639, 19899, 11637, -1, 12527, 19899, 11639, -1, 12528, 19899, 12527, -1, 12530, 19899, 12528, -1, 12531, 19899, 12530, -1, 6550, 19899, 12531, -1, 19899, 6542, 19881, -1, 6550, 6542, 19899, -1, 6542, 19878, 19881, -1, 6542, 6544, 19878, -1, 6557, 19801, 19818, -1, 6557, 6556, 19801, -1, 19801, 6555, 19784, -1, 6556, 6555, 19801, -1, 6555, 19771, 19784, -1, 6555, 6573, 19771, -1, 6573, 19752, 19771, -1, 6573, 6567, 19752, -1, 19752, 6551, 19737, -1, 6567, 6551, 19752, -1, 19737, 6553, 19735, -1, 6551, 6553, 19737, -1, 19683, 6470, 19665, -1, 6473, 6470, 19683, -1, 19665, 6472, 19630, -1, 6470, 6472, 19665, -1, 19630, 6489, 19631, -1, 6472, 6489, 19630, -1, 19631, 6483, 19619, -1, 6489, 6483, 19631, -1, 19619, 6467, 19602, -1, 6483, 6467, 19619, -1, 19602, 6469, 19600, -1, 6467, 6469, 19602, -1, 19543, 6494, 19531, -1, 6497, 6494, 19543, -1, 19531, 6496, 19508, -1, 6494, 6496, 19531, -1, 19508, 6513, 19509, -1, 6496, 6513, 19508, -1, 19509, 6507, 19481, -1, 6513, 6507, 19509, -1, 19481, 6491, 19462, -1, 6507, 6491, 19481, -1, 19462, 6493, 19459, -1, 6491, 6493, 19462, -1, 19397, 6518, 19378, -1, 6521, 6518, 19397, -1, 19378, 6520, 19367, -1, 6518, 6520, 19378, -1, 19367, 6537, 19352, -1, 6520, 6537, 19367, -1, 19352, 6531, 19340, -1, 6537, 6531, 19352, -1, 19340, 6515, 19317, -1, 6531, 6515, 19340, -1, 19317, 6517, 19314, -1, 6515, 6517, 19317, -1, 19262, 14339, 19241, -1, 14337, 14339, 19262, -1, 19240, 11715, 11711, -1, 19240, 15462, 11715, -1, 19240, 15478, 15462, -1, 19241, 14345, 19240, -1, 14339, 14345, 19241, -1, 19240, 15481, 15478, -1, 14345, 15482, 19240, -1, 19240, 15482, 15481, -1, 21414, 6362, 19879, -1, 6358, 6362, 21414, -1, 19879, 6356, 19880, -1, 6362, 6356, 19879, -1, 19880, 11625, 11622, -1, 19880, 12505, 11625, -1, 19880, 12503, 12505, -1, 6356, 6355, 19880, -1, 19880, 12504, 12503, -1, 6355, 12507, 19880, -1, 19880, 12507, 12504, -1, 19783, 6352, 19802, -1, 6353, 6352, 19783, -1, 19802, 6359, 21405, -1, 6352, 6359, 19802, -1, 21405, 6358, 21414, -1, 6359, 6358, 21405, -1, 21357, 6447, 19736, -1, 6444, 6447, 21357, -1, 19736, 6446, 19738, -1, 6447, 6446, 19736, -1, 19738, 6451, 19753, -1, 6446, 6451, 19738, -1, 19632, 6434, 19664, -1, 6435, 6434, 19632, -1, 19664, 6438, 21347, -1, 6434, 6438, 19664, -1, 21347, 6444, 21357, -1, 6438, 6444, 21347, -1, 21308, 6420, 19601, -1, 6416, 6420, 21308, -1, 19601, 6414, 19604, -1, 6420, 6414, 19601, -1, 19604, 6413, 19620, -1, 6414, 6413, 19604, -1, 19506, 6410, 19529, -1, 6411, 6410, 19506, -1, 19529, 6417, 21298, -1, 6410, 6417, 19529, -1, 21298, 6416, 21308, -1, 6417, 6416, 21298, -1, 21264, 6389, 19460, -1, 6386, 6389, 21264, -1, 19460, 6388, 19463, -1, 6389, 6388, 19460, -1, 19463, 6393, 19482, -1, 6388, 6393, 19463, -1, 19351, 6376, 19377, -1, 6377, 6376, 19351, -1, 19377, 6380, 21255, -1, 6376, 6380, 19377, -1, 21255, 6386, 21264, -1, 6380, 6386, 21255, -1, 14317, 19315, 21089, -1, 14317, 14321, 19315, -1, 19315, 14315, 19316, -1, 14321, 14315, 19315, -1, 14315, 19339, 19316, -1, 14315, 14314, 19339, -1, 11725, 19243, 11726, -1, 15432, 19243, 11725, -1, 15434, 19243, 15432, -1, 15435, 19243, 15434, -1, 15439, 19243, 15435, -1, 15439, 14312, 19243, -1, 14312, 14311, 19243, -1, 14311, 19263, 19243, -1, 14311, 14318, 19263, -1, 14318, 21089, 19263, -1, 14318, 14317, 21089, -1, 12493, 21464, 11612, -1, 12494, 21464, 12493, -1, 12496, 21464, 12494, -1, 12497, 21464, 12496, -1, 11612, 21464, 11610, -1, 12497, 6374, 21464, -1, 6374, 6373, 21464, -1, 6373, 19987, 21464, -1, 6373, 6371, 19987, -1, 6371, 19951, 19987, -1, 6371, 6370, 19951, -1, 6370, 19952, 19951, -1, 6370, 6369, 19952, -1, 19952, 6365, 19889, -1, 6369, 6365, 19952, -1, 6365, 19888, 19889, -1, 6365, 6364, 19888, -1, 19850, 6462, 19851, -1, 6463, 6462, 19850, -1, 19851, 6460, 19847, -1, 6462, 6460, 19851, -1, 19847, 6458, 19823, -1, 6460, 6458, 19847, -1, 19823, 6454, 19824, -1, 6458, 6454, 19823, -1, 19824, 6448, 19733, -1, 6454, 6448, 19824, -1, 19733, 6443, 19729, -1, 6448, 6443, 19733, -1, 19730, 6431, 21353, -1, 6432, 6431, 19730, -1, 21353, 6429, 19721, -1, 6431, 6429, 21353, -1, 19721, 6428, 19695, -1, 6429, 6428, 19721, -1, 19695, 6427, 19696, -1, 6428, 6427, 19695, -1, 19696, 6423, 19607, -1, 6427, 6423, 19696, -1, 19607, 6422, 19609, -1, 6423, 6422, 19607, -1, 19608, 6404, 21303, -1, 6405, 6404, 19608, -1, 21303, 6402, 19589, -1, 6404, 6402, 21303, -1, 19589, 6400, 19551, -1, 6402, 6400, 19589, -1, 19551, 6396, 19550, -1, 6400, 6396, 19551, -1, 19550, 6390, 19468, -1, 6396, 6390, 19550, -1, 19468, 6385, 19438, -1, 6390, 6385, 19468, -1, 19437, 14332, 19434, -1, 14333, 14332, 19437, -1, 19434, 14329, 19432, -1, 14332, 14329, 19434, -1, 19432, 14328, 19416, -1, 14329, 14328, 19432, -1, 19416, 14330, 19413, -1, 14328, 14330, 19416, -1, 19413, 14324, 19327, -1, 14330, 14324, 19413, -1, 19327, 11739, 11736, -1, 19327, 15425, 11739, -1, 19327, 15441, 15425, -1, 14324, 14323, 19327, -1, 19327, 15444, 15441, -1, 14323, 15445, 19327, -1, 19327, 15445, 15444, -1, 19986, 6577, 20006, -1, 6582, 6577, 19986, -1, 21469, 11603, 11602, -1, 21469, 12575, 11603, -1, 21469, 12573, 12575, -1, 20006, 6576, 21469, -1, 6577, 6576, 20006, -1, 21469, 12574, 12573, -1, 6576, 12577, 21469, -1, 21469, 12577, 12574, -1, 19853, 6672, 19953, -1, 6673, 6672, 19853, -1, 19953, 6679, 19954, -1, 6672, 6679, 19953, -1, 19954, 6678, 19969, -1, 6679, 6678, 19954, -1, 19846, 6668, 19869, -1, 6669, 6668, 19846, -1, 19869, 6667, 19852, -1, 6668, 6667, 19869, -1, 19852, 6673, 19853, -1, 6667, 6673, 19852, -1, 19732, 6649, 19820, -1, 6648, 6649, 19732, -1, 19820, 6655, 19821, -1, 6649, 6655, 19820, -1, 19821, 6654, 19833, -1, 6655, 6654, 19821, -1, 19722, 6644, 19740, -1, 6645, 6644, 19722, -1, 19740, 6643, 21356, -1, 6644, 6643, 19740, -1, 21356, 6648, 19732, -1, 6643, 6648, 21356, -1, 19606, 6601, 19693, -1, 6600, 6601, 19606, -1, 19693, 6607, 19694, -1, 6601, 6607, 19693, -1, 19694, 6606, 19705, -1, 6607, 6606, 19694, -1, 19579, 6596, 19612, -1, 6597, 6596, 19579, -1, 19612, 6595, 21307, -1, 6596, 6595, 19612, -1, 21307, 6600, 19606, -1, 6595, 6600, 21307, -1, 19436, 6624, 19548, -1, 6625, 6624, 19436, -1, 19548, 6631, 19549, -1, 6624, 6631, 19548, -1, 19549, 6630, 19578, -1, 6631, 6630, 19549, -1, 6621, 19456, 19412, -1, 6621, 6620, 19456, -1, 19456, 6619, 19435, -1, 6620, 6619, 19456, -1, 6619, 19436, 19435, -1, 6619, 6625, 19436, -1, 11744, 19326, 11745, -1, 15506, 19326, 11744, -1, 15508, 19326, 15506, -1, 15509, 19326, 15508, -1, 15513, 19326, 15509, -1, 14347, 19326, 15513, -1, 19326, 14346, 19414, -1, 14347, 14346, 19326, -1, 14346, 19411, 19414, -1, 14346, 14354, 19411, -1, 11550, 19068, 11548, -1, 12457, 19068, 11550, -1, 12458, 19068, 12457, -1, 12460, 19068, 12458, -1, 12461, 19068, 12460, -1, 6254, 19068, 12461, -1, 19068, 6246, 19152, -1, 6254, 6246, 19068, -1, 6246, 18835, 19152, -1, 6246, 6248, 18835, -1, 6309, 18669, 18749, -1, 6309, 6308, 18669, -1, 18669, 6307, 18622, -1, 6308, 6307, 18669, -1, 6307, 18623, 18622, -1, 6307, 6325, 18623, -1, 6325, 18612, 18623, -1, 6325, 6319, 18612, -1, 18612, 6303, 18613, -1, 6319, 6303, 18612, -1, 18613, 6305, 18564, -1, 6303, 6305, 18613, -1, 18521, 6330, 18471, -1, 6333, 6330, 18521, -1, 18471, 6332, 18472, -1, 6330, 6332, 18471, -1, 18472, 6349, 20041, -1, 6332, 6349, 18472, -1, 20041, 6343, 18423, -1, 6349, 6343, 20041, -1, 18423, 6327, 18424, -1, 6343, 6327, 18423, -1, 18424, 6329, 20029, -1, 6327, 6329, 18424, -1, 20004, 6282, 20003, -1, 6285, 6282, 20004, -1, 20003, 6284, 19927, -1, 6282, 6284, 20003, -1, 19927, 6301, 19928, -1, 6284, 6301, 19927, -1, 19928, 6295, 19925, -1, 6301, 6295, 19928, -1, 19925, 6279, 19932, -1, 6295, 6279, 19925, -1, 19932, 6281, 19905, -1, 6279, 6281, 19932, -1, 19886, 6258, 19885, -1, 6261, 6258, 19886, -1, 19885, 6260, 21376, -1, 6258, 6260, 19885, -1, 21376, 6277, 21377, -1, 6260, 6277, 21376, -1, 21377, 6271, 21373, -1, 6277, 6271, 21377, -1, 21373, 6255, 19790, -1, 6271, 6255, 21373, -1, 19790, 6257, 19758, -1, 6255, 6257, 19790, -1, 19759, 14303, 19657, -1, 14301, 14303, 19759, -1, 19658, 11862, 11860, -1, 19658, 15388, 11862, -1, 19658, 15404, 15388, -1, 19657, 14309, 19658, -1, 14303, 14309, 19657, -1, 19658, 15407, 15404, -1, 14309, 15408, 19658, -1, 19658, 15408, 15407, -1, 20196, 6138, 20206, -1, 6134, 6138, 20196, -1, 20206, 6132, 19150, -1, 6138, 6132, 20206, -1, 19150, 11541, 11540, -1, 19150, 12435, 11541, -1, 19150, 12433, 12435, -1, 6132, 6131, 19150, -1, 19150, 12434, 12433, -1, 6131, 12437, 19150, -1, 19150, 12437, 12434, -1, 18668, 6128, 18764, -1, 6129, 6128, 18668, -1, 18764, 6135, 20184, -1, 6128, 6135, 18764, -1, 20184, 6134, 20196, -1, 6135, 6134, 20184, -1, 20110, 6165, 20118, -1, 6162, 6165, 20110, -1, 20118, 6164, 18611, -1, 6165, 6164, 20118, -1, 18611, 6169, 18621, -1, 6164, 6169, 18611, -1, 18470, 6152, 18523, -1, 6153, 6152, 18470, -1, 18523, 6156, 20099, -1, 6152, 6156, 18523, -1, 20099, 6162, 20110, -1, 6156, 6162, 20099, -1, 20015, 6230, 20028, -1, 6226, 6230, 20015, -1, 20028, 6224, 18422, -1, 6230, 6224, 20028, -1, 18422, 6223, 18429, -1, 6224, 6223, 18422, -1, 19929, 6220, 20001, -1, 6221, 6220, 19929, -1, 20001, 6227, 20002, -1, 6220, 6227, 20001, -1, 20002, 6226, 20015, -1, 6227, 6226, 20002, -1, 19904, 6199, 19911, -1, 6196, 6199, 19904, -1, 19911, 6198, 19931, -1, 6199, 6198, 19911, -1, 19931, 6203, 19926, -1, 6198, 6203, 19931, -1, 21387, 6186, 19883, -1, 6187, 6186, 21387, -1, 19883, 6190, 19884, -1, 6186, 6190, 19883, -1, 19884, 6196, 19904, -1, 6190, 6196, 19884, -1, 14281, 19773, 19757, -1, 14281, 14285, 19773, -1, 19773, 14279, 19789, -1, 14285, 14279, 19773, -1, 14279, 21375, 19789, -1, 14279, 14278, 21375, -1, 11875, 21339, 11873, -1, 15358, 21339, 11875, -1, 15360, 21339, 15358, -1, 15361, 21339, 15360, -1, 15365, 21339, 15361, -1, 15365, 14276, 21339, -1, 14276, 14275, 21339, -1, 14275, 19756, 21339, -1, 14275, 14282, 19756, -1, 14282, 19757, 19756, -1, 14282, 14281, 19757, -1, 12422, 19603, 11532, -1, 12423, 19603, 12422, -1, 12425, 19603, 12423, -1, 12426, 19603, 12425, -1, 11532, 19603, 11530, -1, 12426, 6150, 19603, -1, 6150, 6149, 19603, -1, 6149, 20263, 19603, -1, 6149, 6147, 20263, -1, 6147, 19596, 20263, -1, 6147, 6146, 19596, -1, 6146, 20232, 19596, -1, 6146, 6145, 20232, -1, 20232, 6141, 19024, -1, 6145, 6141, 20232, -1, 6141, 18879, 19024, -1, 6141, 6140, 18879, -1, 18880, 6180, 20189, -1, 6181, 6180, 18880, -1, 20189, 6178, 20179, -1, 6180, 6178, 20189, -1, 20179, 6176, 18859, -1, 6178, 6176, 20179, -1, 18859, 6172, 20146, -1, 6176, 6172, 18859, -1, 20146, 6166, 18605, -1, 6172, 6166, 20146, -1, 18605, 6161, 18602, -1, 6166, 6161, 18605, -1, 18603, 6241, 20104, -1, 6242, 6241, 18603, -1, 20104, 6238, 20088, -1, 6241, 6238, 20104, -1, 20088, 6237, 18578, -1, 6238, 6237, 20088, -1, 18578, 6239, 20052, -1, 6237, 6239, 18578, -1, 20052, 6233, 18399, -1, 6239, 6233, 20052, -1, 18399, 6232, 18396, -1, 6233, 6232, 18399, -1, 18397, 6214, 20013, -1, 6215, 6214, 18397, -1, 20013, 6212, 19992, -1, 6214, 6212, 20013, -1, 19992, 6210, 19980, -1, 6212, 6210, 19992, -1, 19980, 6206, 19948, -1, 6210, 6206, 19980, -1, 19948, 6200, 19949, -1, 6206, 6200, 19948, -1, 19949, 6195, 21417, -1, 6200, 6195, 19949, -1, 19917, 14296, 19893, -1, 14297, 14296, 19917, -1, 19893, 14293, 19860, -1, 14296, 14293, 19893, -1, 19860, 14292, 19836, -1, 14293, 14292, 19860, -1, 19836, 14294, 19815, -1, 14292, 14294, 19836, -1, 19815, 14288, 19795, -1, 14294, 14288, 19815, -1, 19795, 11887, 11886, -1, 19795, 15351, 11887, -1, 19795, 15367, 15351, -1, 14288, 14287, 19795, -1, 19795, 15370, 15367, -1, 14287, 15371, 19795, -1, 19795, 15371, 15370, -1, 19595, 6021, 20272, -1, 6026, 6021, 19595, -1, 20289, 11514, 11513, -1, 20289, 12400, 11514, -1, 20289, 12398, 12400, -1, 20272, 6020, 20289, -1, 6021, 6020, 20272, -1, 20289, 12399, 12398, -1, 6020, 12402, 20289, -1, 20289, 12402, 12399, -1, 19011, 6044, 20231, -1, 6045, 6044, 19011, -1, 20231, 6051, 20241, -1, 6044, 6051, 20231, -1, 20241, 6050, 19597, -1, 6051, 6050, 20241, -1, 18858, 6040, 20191, -1, 6041, 6040, 18858, -1, 20191, 6039, 20198, -1, 6040, 6039, 20191, -1, 20198, 6045, 19011, -1, 6039, 6045, 20198, -1, 18601, 6116, 20147, -1, 6117, 6116, 18601, -1, 20147, 6123, 20163, -1, 6116, 6123, 20147, -1, 20163, 6122, 18860, -1, 6123, 6122, 20163, -1, 18577, 6112, 20091, -1, 6113, 6112, 18577, -1, 20091, 6111, 20114, -1, 6112, 6111, 20091, -1, 20114, 6117, 18601, -1, 6111, 6117, 20114, -1, 18395, 6093, 20053, -1, 6092, 6093, 18395, -1, 20053, 6099, 20063, -1, 6093, 6099, 20053, -1, 20063, 6098, 18579, -1, 6099, 6098, 20063, -1, 18394, 6088, 19994, -1, 6089, 6088, 18394, -1, 19994, 6087, 20026, -1, 6088, 6087, 19994, -1, 20026, 6092, 18395, -1, 6087, 6092, 20026, -1, 19916, 6069, 19947, -1, 6068, 6069, 19916, -1, 19947, 6075, 19962, -1, 6069, 6075, 19947, -1, 19962, 6074, 18392, -1, 6075, 6074, 19962, -1, 6065, 19856, 19855, -1, 6065, 6064, 19856, -1, 19856, 6063, 19907, -1, 6064, 6063, 19856, -1, 6063, 19916, 19907, -1, 6063, 6068, 19916, -1, 11908, 19794, 11906, -1, 15321, 19794, 11908, -1, 15323, 19794, 15321, -1, 15324, 19794, 15323, -1, 15328, 19794, 15324, -1, 14263, 19794, 15328, -1, 19794, 14262, 19816, -1, 14263, 14262, 19794, -1, 14262, 19835, 19816, -1, 14262, 14270, 19835, -1, 11505, 20128, 11503, -1, 12388, 20128, 11505, -1, 12389, 20128, 12388, -1, 12391, 20128, 12389, -1, 12392, 20128, 12391, -1, 6030, 20128, 12392, -1, 20128, 6022, 20155, -1, 6030, 6022, 20128, -1, 6022, 19955, 20155, -1, 6022, 6024, 19955, -1, 6037, 19871, 19848, -1, 6037, 6036, 19871, -1, 19871, 6035, 20279, -1, 6036, 6035, 19871, -1, 6035, 20265, 20279, -1, 6035, 6053, 20265, -1, 6053, 20251, 20265, -1, 6053, 6047, 20251, -1, 20251, 6031, 19461, -1, 6047, 6031, 20251, -1, 19461, 6033, 19242, -1, 6031, 6033, 19461, -1, 19156, 6106, 19163, -1, 6109, 6106, 19156, -1, 19163, 6108, 20187, -1, 6106, 6108, 19163, -1, 20187, 6125, 20176, -1, 6108, 6125, 20187, -1, 20176, 6119, 20177, -1, 6125, 6119, 20176, -1, 20177, 6103, 18798, -1, 6119, 6103, 20177, -1, 18798, 6105, 18677, -1, 6103, 6105, 18798, -1, 18636, 6082, 18646, -1, 6085, 6082, 18636, -1, 18646, 6084, 20108, -1, 6082, 6084, 18646, -1, 20108, 6101, 20085, -1, 6084, 6101, 20108, -1, 20085, 6095, 20086, -1, 6101, 6095, 20085, -1, 20086, 6079, 18559, -1, 6095, 6079, 20086, -1, 18559, 6081, 18478, -1, 6079, 6081, 18559, -1, 18446, 6058, 18447, -1, 6061, 6058, 18446, -1, 18447, 6060, 20017, -1, 6058, 6060, 18447, -1, 20017, 6077, 19999, -1, 6060, 6077, 20017, -1, 19999, 6071, 19982, -1, 6077, 6071, 19999, -1, 19982, 6055, 19983, -1, 6071, 6055, 19982, -1, 19983, 6057, 21446, -1, 6055, 6057, 19983, -1, 19909, 14267, 19896, -1, 14265, 14267, 19909, -1, 19895, 11917, 11915, -1, 19895, 15314, 11917, -1, 19895, 15330, 15314, -1, 19896, 14273, 19895, -1, 14267, 14273, 19896, -1, 19895, 15333, 15330, -1, 14273, 15334, 19895, -1, 19895, 15334, 15333, -1, 20097, 6006, 20153, -1, 6002, 6006, 20097, -1, 20153, 6000, 20190, -1, 6006, 6000, 20153, -1, 20190, 11489, 11488, -1, 20190, 12365, 11489, -1, 20190, 12363, 12365, -1, 6000, 5999, 20190, -1, 20190, 12364, 12363, -1, 5999, 12367, 20190, -1, 20190, 12367, 12364, -1, 19761, 5996, 19870, -1, 5997, 5996, 19761, -1, 19870, 6003, 19993, -1, 5996, 6003, 19870, -1, 19993, 6002, 20097, -1, 6003, 6002, 19993, -1, 19395, 5951, 19457, -1, 5948, 5951, 19395, -1, 19457, 5950, 19493, -1, 5951, 5950, 19457, -1, 19493, 5955, 19762, -1, 5950, 5955, 19493, -1, 20186, 5938, 19162, -1, 5939, 5938, 20186, -1, 19162, 5942, 19278, -1, 5938, 5942, 19162, -1, 19278, 5948, 19395, -1, 5942, 5948, 19278, -1, 18732, 5982, 18795, -1, 5978, 5982, 18732, -1, 18795, 5976, 18829, -1, 5982, 5976, 18795, -1, 18829, 5975, 20175, -1, 5976, 5975, 18829, -1, 20106, 5972, 18645, -1, 5973, 5972, 20106, -1, 18645, 5979, 18686, -1, 5972, 5979, 18645, -1, 18686, 5978, 18732, -1, 5979, 5978, 18686, -1, 18535, 5917, 18558, -1, 5914, 5917, 18535, -1, 18558, 5916, 18568, -1, 5917, 5916, 18558, -1, 18568, 5921, 20084, -1, 5916, 5921, 18568, -1, 18372, 5904, 18445, -1, 5905, 5904, 18372, -1, 18445, 5908, 18492, -1, 5904, 5908, 18445, -1, 18492, 5914, 18535, -1, 5908, 5914, 18492, -1, 14245, 21467, 21461, -1, 14245, 14249, 21467, -1, 21467, 14243, 19984, -1, 14249, 14243, 21467, -1, 14243, 18373, 19984, -1, 14243, 14242, 18373, -1, 11929, 19897, 11927, -1, 15284, 19897, 11929, -1, 15286, 19897, 15284, -1, 15287, 19897, 15286, -1, 15291, 19897, 15287, -1, 15291, 14240, 19897, -1, 14240, 14239, 19897, -1, 14239, 21445, 19897, -1, 14239, 14246, 21445, -1, 14246, 21461, 21445, -1, 14246, 14245, 21461, -1, 12353, 20454, 11471, -1, 12354, 20454, 12353, -1, 12356, 20454, 12354, -1, 12357, 20454, 12356, -1, 11471, 20454, 11469, -1, 12357, 6018, 20454, -1, 6018, 6017, 20454, -1, 6017, 20415, 20454, -1, 6017, 6015, 20415, -1, 6015, 20396, 20415, -1, 6015, 6014, 20396, -1, 6014, 20372, 20396, -1, 6014, 6013, 20372, -1, 20372, 6009, 20107, -1, 6013, 6009, 20372, -1, 6009, 19996, 20107, -1, 6009, 6008, 19996, -1, 19997, 5966, 20090, -1, 5967, 5966, 19997, -1, 20090, 5964, 20321, -1, 5966, 5964, 20090, -1, 20321, 5962, 20315, -1, 5964, 5962, 20321, -1, 20315, 5958, 19624, -1, 5962, 5958, 20315, -1, 19624, 5952, 19445, -1, 5958, 5952, 19624, -1, 19445, 5947, 19446, -1, 5952, 5947, 19445, -1, 19431, 5993, 19427, -1, 5994, 5993, 19431, -1, 19427, 5990, 20236, -1, 5993, 5990, 19427, -1, 20236, 5989, 20227, -1, 5990, 5989, 20236, -1, 20227, 5991, 18959, -1, 5989, 5991, 20227, -1, 18959, 5985, 18778, -1, 5991, 5985, 18959, -1, 18778, 5984, 18779, -1, 5985, 5984, 18778, -1, 18771, 5932, 18769, -1, 5933, 5932, 18771, -1, 18769, 5930, 20160, -1, 5932, 5930, 18769, -1, 20160, 5928, 20152, -1, 5930, 5928, 20160, -1, 20152, 5924, 20121, -1, 5928, 5924, 20152, -1, 20121, 5918, 18547, -1, 5924, 5918, 20121, -1, 18547, 5913, 18499, -1, 5918, 5913, 18547, -1, 18473, 14260, 18543, -1, 14261, 14260, 18473, -1, 18543, 14257, 20059, -1, 14260, 14257, 18543, -1, 20059, 14256, 20050, -1, 14257, 14256, 20059, -1, 20050, 14258, 20035, -1, 14256, 14258, 20050, -1, 20035, 14252, 20033, -1, 14258, 14252, 20035, -1, 20033, 11939, 11938, -1, 20033, 15277, 11939, -1, 20033, 15293, 15277, -1, 14252, 14251, 20033, -1, 20033, 15296, 15293, -1, 14251, 15297, 20033, -1, 20033, 15297, 15296, -1, 20414, 5305, 20429, -1, 5310, 5305, 20414, -1, 20453, 11451, 11450, -1, 20453, 12155, 11451, -1, 20453, 12153, 12155, -1, 20429, 5304, 20453, -1, 5305, 5304, 20429, -1, 20453, 12154, 12153, -1, 5304, 12157, 20453, -1, 20453, 12157, 12154, -1, 20089, 5328, 20373, -1, 5329, 5328, 20089, -1, 20373, 5335, 20383, -1, 5328, 5335, 20373, -1, 20383, 5334, 20397, -1, 5335, 5334, 20383, -1, 20023, 5324, 20327, -1, 5325, 5324, 20023, -1, 20327, 5323, 20093, -1, 5324, 5323, 20327, -1, 20093, 5329, 20089, -1, 5323, 5329, 20093, -1, 19426, 5293, 19623, -1, 5292, 5293, 19426, -1, 19623, 5299, 20305, -1, 5293, 5299, 19623, -1, 20305, 5298, 20024, -1, 5299, 5298, 20305, -1, 19408, 5288, 20244, -1, 5289, 5288, 19408, -1, 20244, 5287, 19428, -1, 5288, 5287, 20244, -1, 19428, 5292, 19426, -1, 5287, 5292, 19428, -1, 18768, 5269, 18958, -1, 5268, 5269, 18768, -1, 18958, 5275, 20220, -1, 5269, 5275, 18958, -1, 20220, 5274, 19409, -1, 5275, 5274, 20220, -1, 18761, 5264, 20169, -1, 5265, 5264, 18761, -1, 20169, 5263, 18770, -1, 5264, 5263, 20169, -1, 18770, 5268, 18768, -1, 5263, 5268, 18770, -1, 18542, 5245, 20120, -1, 5244, 5245, 18542, -1, 20120, 5251, 20127, -1, 5245, 5251, 20120, -1, 20127, 5250, 18754, -1, 5251, 5250, 20127, -1, 5241, 20071, 18528, -1, 5241, 5240, 20071, -1, 20071, 5239, 18544, -1, 5240, 5239, 20071, -1, 5239, 18542, 18544, -1, 5239, 5244, 18542, -1, 11952, 20034, 11950, -1, 15062, 20034, 11952, -1, 15064, 20034, 15062, -1, 15065, 20034, 15064, -1, 15069, 20034, 15065, -1, 14131, 20034, 15069, -1, 20034, 14130, 20036, -1, 14131, 14130, 20034, -1, 14130, 18529, 20036, -1, 14130, 14138, 18529, -1, 12318, 21036, 11307, -1, 12319, 21036, 12318, -1, 12321, 21036, 12319, -1, 12322, 21036, 12321, -1, 11307, 21036, 11306, -1, 12322, 5810, 21036, -1, 5810, 5809, 21036, -1, 5809, 21010, 21036, -1, 5809, 5807, 21010, -1, 5807, 20996, 21010, -1, 5807, 5806, 20996, -1, 5806, 20962, 20996, -1, 5806, 5805, 20962, -1, 20962, 5801, 20963, -1, 5805, 5801, 20962, -1, 5801, 21361, 20963, -1, 5801, 5800, 21361, -1, 21362, 5840, 20890, -1, 5841, 5840, 21362, -1, 20890, 5838, 20881, -1, 5840, 5838, 20890, -1, 20881, 5836, 20872, -1, 5838, 5836, 20881, -1, 20872, 5832, 20837, -1, 5836, 5832, 20872, -1, 20837, 5826, 20838, -1, 5832, 5826, 20837, -1, 20838, 5821, 20762, -1, 5826, 5821, 20838, -1, 20765, 5867, 20767, -1, 5868, 5867, 20765, -1, 20767, 5864, 20752, -1, 5867, 5864, 20767, -1, 20752, 5863, 20731, -1, 5864, 5863, 20752, -1, 20731, 5865, 20696, -1, 5863, 5865, 20731, -1, 20696, 5859, 20694, -1, 5865, 5859, 20696, -1, 20694, 5858, 20641, -1, 5859, 5858, 20694, -1, 20642, 5898, 20644, -1, 5899, 5898, 20642, -1, 20644, 5896, 20630, -1, 5898, 5896, 20644, -1, 20630, 5894, 20619, -1, 5896, 5894, 20630, -1, 20619, 5890, 20585, -1, 5894, 5890, 20619, -1, 20585, 5884, 20584, -1, 5890, 5884, 20585, -1, 20584, 5879, 21055, -1, 5884, 5879, 20584, -1, 20970, 14236, 20527, -1, 14237, 14236, 20970, -1, 20527, 14233, 20510, -1, 14236, 14233, 20527, -1, 20510, 14232, 20487, -1, 14233, 14232, 20510, -1, 20487, 14234, 20466, -1, 14232, 14234, 20487, -1, 20466, 14228, 20433, -1, 14234, 14228, 20466, -1, 20433, 12058, 12056, -1, 20433, 15240, 12058, -1, 20433, 15256, 15240, -1, 14228, 14227, 20433, -1, 20433, 15259, 15256, -1, 14227, 15260, 20433, -1, 20433, 15260, 15259, -1, 21011, 5457, 21020, -1, 5462, 5457, 21011, -1, 21035, 11316, 11315, -1, 21035, 12225, 11316, -1, 21035, 12223, 12225, -1, 21020, 5456, 21035, -1, 5457, 5456, 21020, -1, 21035, 12224, 12223, -1, 5456, 12227, 21035, -1, 21035, 12227, 12224, -1, 20960, 5480, 20961, -1, 5481, 5480, 20960, -1, 20961, 5487, 20974, -1, 5480, 5487, 20961, -1, 20974, 5486, 20995, -1, 5487, 5486, 20974, -1, 20880, 5476, 20891, -1, 5477, 5476, 20880, -1, 20891, 5475, 20901, -1, 5476, 5475, 20891, -1, 20901, 5481, 20960, -1, 5475, 5481, 20901, -1, 20790, 5504, 20839, -1, 5505, 5504, 20790, -1, 20839, 5511, 20851, -1, 5504, 5511, 20839, -1, 20851, 5510, 20873, -1, 5511, 5510, 20851, -1, 20753, 5500, 20768, -1, 5501, 5500, 20753, -1, 20768, 5499, 20791, -1, 5500, 5499, 20768, -1, 20791, 5505, 20790, -1, 5499, 5505, 20791, -1, 20656, 5528, 20697, -1, 5529, 5528, 20656, -1, 20697, 5535, 20715, -1, 5528, 5535, 20697, -1, 20715, 5534, 20732, -1, 5535, 5534, 20715, -1, 20618, 5524, 20645, -1, 5525, 5524, 20618, -1, 20645, 5523, 20657, -1, 5524, 5523, 20645, -1, 20657, 5529, 20656, -1, 5523, 5529, 20657, -1, 20546, 5552, 20583, -1, 5553, 5552, 20546, -1, 20583, 5559, 20591, -1, 5552, 5559, 20583, -1, 20591, 5558, 20617, -1, 5559, 5558, 20591, -1, 5549, 20526, 20489, -1, 5549, 5548, 20526, -1, 20526, 5547, 20545, -1, 5548, 5547, 20526, -1, 5547, 20546, 20545, -1, 5547, 5553, 20546, -1, 11678, 20467, 11676, -1, 15136, 20467, 11678, -1, 15138, 20467, 15136, -1, 15139, 20467, 15138, -1, 15143, 20467, 15139, -1, 14167, 20467, 15143, -1, 20467, 14166, 20468, -1, 14167, 14166, 20467, -1, 14166, 20488, 20468, -1, 14166, 14174, 20488, -1, 11302, 20913, 11300, -1, 12282, 20913, 11302, -1, 12283, 20913, 12282, -1, 12285, 20913, 12283, -1, 12286, 20913, 12285, -1, 5738, 20913, 12286, -1, 20913, 5730, 20911, -1, 5738, 5730, 20913, -1, 5730, 20929, 20911, -1, 5730, 5732, 20929, -1, 5685, 20820, 20899, -1, 5685, 5684, 20820, -1, 20820, 5683, 20821, -1, 5684, 5683, 20820, -1, 5683, 20800, 20821, -1, 5683, 5701, 20800, -1, 5701, 20781, 20800, -1, 5701, 5695, 20781, -1, 20781, 5679, 20782, -1, 5695, 5679, 20781, -1, 20782, 5681, 20796, -1, 5679, 5681, 20782, -1, 20779, 5706, 21285, -1, 5709, 5706, 20779, -1, 21285, 5708, 20672, -1, 5706, 5708, 21285, -1, 20672, 5725, 20673, -1, 5708, 5725, 20672, -1, 20673, 5719, 20674, -1, 5725, 5719, 20673, -1, 20674, 5703, 21274, -1, 5719, 5703, 20674, -1, 21274, 5705, 20660, -1, 5703, 5705, 21274, -1, 20647, 5766, 21229, -1, 5769, 5766, 20647, -1, 21229, 5768, 20571, -1, 5766, 5768, 21229, -1, 20571, 5785, 20572, -1, 5768, 5785, 20571, -1, 20572, 5779, 20570, -1, 5785, 5779, 20572, -1, 20570, 5763, 21182, -1, 5779, 5763, 20570, -1, 21182, 5765, 20537, -1, 5763, 5765, 21182, -1, 20535, 5742, 20447, -1, 5745, 5742, 20535, -1, 20447, 5744, 20448, -1, 5742, 5744, 20447, -1, 20448, 5761, 20422, -1, 5744, 5761, 20448, -1, 20422, 5755, 20411, -1, 5761, 5755, 20422, -1, 20411, 5739, 20412, -1, 5755, 5739, 20411, -1, 20412, 5741, 20338, -1, 5739, 5741, 20412, -1, 20274, 14207, 20275, -1, 14205, 14207, 20274, -1, 20031, 12046, 12045, -1, 20031, 15203, 12046, -1, 20031, 15219, 15203, -1, 20275, 14213, 20031, -1, 14207, 14213, 20275, -1, 20031, 15222, 15219, -1, 14213, 15223, 20031, -1, 20031, 15223, 15222, -1, 20898, 5798, 20930, -1, 5794, 5798, 20898, -1, 20930, 5792, 20912, -1, 5798, 5792, 20930, -1, 20912, 11296, 11295, -1, 20912, 12330, 11296, -1, 20912, 12328, 12330, -1, 5792, 5791, 20912, -1, 20912, 12329, 12328, -1, 5791, 12332, 20912, -1, 20912, 12332, 12329, -1, 20822, 5788, 20896, -1, 5789, 5788, 20822, -1, 20896, 5795, 20897, -1, 5788, 5795, 20896, -1, 20897, 5794, 20898, -1, 5795, 5794, 20897, -1, 20778, 5825, 20797, -1, 5822, 5825, 20778, -1, 20797, 5824, 20783, -1, 5825, 5824, 20797, -1, 20783, 5829, 20784, -1, 5824, 5829, 20783, -1, 20671, 5812, 20774, -1, 5813, 5812, 20671, -1, 20774, 5816, 20775, -1, 5812, 5816, 20774, -1, 20775, 5822, 20778, -1, 5816, 5822, 20775, -1, 20650, 5856, 20659, -1, 5852, 5856, 20650, -1, 20659, 5850, 21276, -1, 5856, 5850, 20659, -1, 21276, 5849, 20675, -1, 5850, 5849, 21276, -1, 20569, 5846, 20648, -1, 5847, 5846, 20569, -1, 20648, 5853, 20649, -1, 5846, 5853, 20648, -1, 20649, 5852, 20650, -1, 5853, 5852, 20649, -1, 20539, 5883, 20552, -1, 5880, 5883, 20539, -1, 20552, 5882, 21200, -1, 5883, 5882, 20552, -1, 21200, 5887, 20568, -1, 5882, 5887, 21200, -1, 20421, 5870, 20536, -1, 5871, 5870, 20421, -1, 20536, 5874, 20538, -1, 5870, 5874, 20536, -1, 20538, 5880, 20539, -1, 5874, 5880, 20538, -1, 14221, 20419, 20402, -1, 14221, 14225, 20419, -1, 20419, 14219, 20408, -1, 14225, 14219, 20419, -1, 14219, 20409, 20408, -1, 14219, 14218, 20409, -1, 12054, 20276, 12052, -1, 15247, 20276, 12054, -1, 15249, 20276, 15247, -1, 15250, 20276, 15249, -1, 15254, 20276, 15250, -1, 15254, 14216, 20276, -1, 14216, 14215, 20276, -1, 14215, 20326, 20276, -1, 14215, 14222, 20326, -1, 14222, 20402, 20326, -1, 14222, 14221, 20402, -1, 12248, 18454, 11355, -1, 12249, 18454, 12248, -1, 12251, 18454, 12249, -1, 12252, 18454, 12251, -1, 11355, 18454, 11352, -1, 12252, 5586, 18454, -1, 5586, 5585, 18454, -1, 5585, 18483, 18454, -1, 5585, 5583, 18483, -1, 5583, 21138, 18483, -1, 5583, 5582, 21138, -1, 5582, 21135, 21138, -1, 5582, 5581, 21135, -1, 21135, 5577, 21103, -1, 5581, 5577, 21135, -1, 5577, 21104, 21103, -1, 5577, 5576, 21104, -1, 21079, 5650, 21080, -1, 5651, 5650, 21079, -1, 21080, 5648, 21074, -1, 5650, 5648, 21080, -1, 21074, 5646, 21051, -1, 5648, 5646, 21074, -1, 21051, 5642, 21052, -1, 5646, 5642, 21051, -1, 21052, 5636, 20976, -1, 5642, 5636, 21052, -1, 20976, 5631, 20977, -1, 5636, 5631, 20976, -1, 20978, 5677, 21398, -1, 5678, 5677, 20978, -1, 21398, 5674, 20968, -1, 5677, 5674, 21398, -1, 20968, 5673, 20948, -1, 5674, 5673, 20968, -1, 20948, 5675, 20946, -1, 5673, 5675, 20948, -1, 20946, 5669, 20863, -1, 5675, 5669, 20946, -1, 20863, 5668, 20864, -1, 5669, 5668, 20863, -1, 20865, 5616, 21340, -1, 5617, 5616, 20865, -1, 21340, 5614, 20849, -1, 5616, 5614, 21340, -1, 20849, 5612, 20811, -1, 5614, 5612, 20849, -1, 20811, 5608, 20809, -1, 5612, 5608, 20811, -1, 20809, 5602, 20737, -1, 5608, 5602, 20809, -1, 20737, 5597, 20706, -1, 5602, 5597, 20737, -1, 20707, 14200, 20710, -1, 14201, 14200, 20707, -1, 20710, 14197, 20704, -1, 14200, 14197, 20710, -1, 20704, 14196, 20692, -1, 14197, 14196, 20704, -1, 20692, 14198, 20688, -1, 14196, 14198, 20692, -1, 20688, 14192, 20610, -1, 14198, 14192, 20688, -1, 20610, 11720, 11718, -1, 20610, 15166, 11720, -1, 20610, 15182, 15166, -1, 14192, 14191, 20610, -1, 20610, 15185, 15182, -1, 14191, 15186, 20610, -1, 20610, 15186, 15185, -1, 18457, 8557, 18484, -1, 8562, 8557, 18457, -1, 18482, 11364, 11363, -1, 18482, 13218, 11364, -1, 18482, 13216, 13218, -1, 18484, 8556, 18482, -1, 8557, 8556, 18484, -1, 18482, 13217, 13216, -1, 8556, 13220, 18482, -1, 18482, 13220, 13217, -1, 21078, 8580, 21136, -1, 8581, 8580, 21078, -1, 21136, 8587, 21137, -1, 8580, 8587, 21136, -1, 21137, 8586, 18458, -1, 8587, 8586, 21137, -1, 21075, 8576, 21088, -1, 8577, 8576, 21075, -1, 21088, 8575, 21077, -1, 8576, 8575, 21088, -1, 21077, 8581, 21078, -1, 8575, 8581, 21077, -1, 20979, 8497, 21053, -1, 8496, 8497, 20979, -1, 21053, 8503, 21054, -1, 8497, 8503, 21053, -1, 21054, 8502, 21063, -1, 8503, 8502, 21054, -1, 20969, 8492, 20986, -1, 8493, 8492, 20969, -1, 20986, 8491, 21401, -1, 8492, 8491, 20986, -1, 21401, 8496, 20979, -1, 8491, 8496, 21401, -1, 20868, 8520, 20947, -1, 8521, 8520, 20868, -1, 20947, 8527, 20949, -1, 8520, 8527, 20947, -1, 20949, 8526, 20954, -1, 8527, 8526, 20949, -1, 20842, 8516, 20870, -1, 8517, 8516, 20842, -1, 20870, 8515, 21342, -1, 8516, 8515, 20870, -1, 21342, 8521, 20868, -1, 8515, 8521, 21342, -1, 20709, 8544, 20810, -1, 8545, 8544, 20709, -1, 20810, 8551, 20812, -1, 8544, 8551, 20810, -1, 20812, 8550, 20841, -1, 8551, 8550, 20812, -1, 8541, 20724, 20691, -1, 8541, 8540, 20724, -1, 20724, 8539, 20708, -1, 8540, 8539, 20724, -1, 8539, 20709, 20708, -1, 8539, 8545, 20709, -1, 11741, 20609, 11730, -1, 16135, 20609, 11741, -1, 16137, 20609, 16135, -1, 16138, 20609, 16137, -1, 16142, 20609, 16138, -1, 14611, 20609, 16142, -1, 20609, 14610, 20689, -1, 14611, 14610, 20609, -1, 14610, 20690, 20689, -1, 14610, 14618, 20690, -1, 11331, 21106, 11328, -1, 12212, 21106, 11331, -1, 12213, 21106, 12212, -1, 12215, 21106, 12213, -1, 12216, 21106, 12215, -1, 5466, 21106, 12216, -1, 21106, 5458, 21096, -1, 5466, 5458, 21106, -1, 5458, 21093, 21096, -1, 5458, 5460, 21093, -1, 5473, 21039, 21049, -1, 5473, 5472, 21039, -1, 21039, 5471, 21026, -1, 5472, 5471, 21039, -1, 5471, 21013, 21026, -1, 5471, 5489, 21013, -1, 5489, 20999, 21013, -1, 5489, 5483, 20999, -1, 20999, 5467, 20984, -1, 5483, 5467, 20999, -1, 20984, 5469, 20981, -1, 5467, 5469, 20984, -1, 20935, 5494, 20917, -1, 5497, 5494, 20935, -1, 20917, 5496, 20887, -1, 5494, 5496, 20917, -1, 20887, 5513, 20888, -1, 5496, 5513, 20887, -1, 20888, 5507, 20878, -1, 5513, 5507, 20888, -1, 20878, 5491, 20861, -1, 5507, 5491, 20878, -1, 20861, 5493, 20858, -1, 5491, 5493, 20861, -1, 20804, 5518, 20794, -1, 5521, 5518, 20804, -1, 20794, 5520, 20771, -1, 5518, 5520, 20794, -1, 20771, 5537, 20772, -1, 5520, 5537, 20771, -1, 20772, 5531, 20749, -1, 5537, 5531, 20772, -1, 20749, 5515, 20729, -1, 5531, 5515, 20749, -1, 20729, 5517, 20726, -1, 5515, 5517, 20729, -1, 20681, 5542, 20662, -1, 5545, 5542, 20681, -1, 20662, 5544, 20652, -1, 5542, 5544, 20662, -1, 20652, 5561, 20636, -1, 5544, 5561, 20652, -1, 20636, 5555, 20621, -1, 5561, 5555, 20636, -1, 20621, 5539, 20597, -1, 5555, 5539, 20621, -1, 20597, 5541, 20598, -1, 5539, 5541, 20597, -1, 20550, 14171, 20530, -1, 14169, 14171, 20550, -1, 20529, 11691, 11689, -1, 20529, 15129, 11691, -1, 20529, 15145, 15129, -1, 20530, 14177, 20529, -1, 14171, 14177, 20530, -1, 20529, 15148, 15145, -1, 14177, 15149, 20529, -1, 20529, 15149, 15148, -1, 21462, 5574, 21094, -1, 5570, 5574, 21462, -1, 21094, 5568, 21095, -1, 5574, 5568, 21094, -1, 21095, 11342, 11341, -1, 21095, 12260, 11342, -1, 21095, 12258, 12260, -1, 5568, 5567, 21095, -1, 21095, 12259, 12258, -1, 5567, 12262, 21095, -1, 21095, 12262, 12259, -1, 21027, 5564, 21038, -1, 5565, 5564, 21027, -1, 21038, 5571, 21452, -1, 5564, 5571, 21038, -1, 21452, 5570, 21462, -1, 5571, 5570, 21452, -1, 21404, 5635, 20982, -1, 5632, 5635, 21404, -1, 20982, 5634, 20983, -1, 5635, 5634, 20982, -1, 20983, 5639, 20998, -1, 5634, 5639, 20983, -1, 20886, 5622, 20915, -1, 5623, 5622, 20886, -1, 20915, 5626, 21393, -1, 5622, 5626, 20915, -1, 21393, 5632, 21404, -1, 5626, 5632, 21393, -1, 21343, 5666, 20859, -1, 5662, 5666, 21343, -1, 20859, 5660, 20860, -1, 5666, 5660, 20859, -1, 20860, 5659, 20876, -1, 5660, 5659, 20860, -1, 20770, 5656, 20793, -1, 5657, 5656, 20770, -1, 20793, 5663, 21331, -1, 5656, 5663, 20793, -1, 21331, 5662, 21343, -1, 5663, 5662, 21331, -1, 21297, 5601, 20727, -1, 5598, 5601, 21297, -1, 20727, 5600, 20728, -1, 5601, 5600, 20727, -1, 20728, 5605, 20748, -1, 5600, 5605, 20728, -1, 20637, 5588, 20663, -1, 5589, 5588, 20637, -1, 20663, 5592, 21291, -1, 5588, 5592, 20663, -1, 21291, 5598, 21297, -1, 5592, 5598, 21291, -1, 14185, 20599, 21248, -1, 14185, 14189, 20599, -1, 20599, 14183, 20600, -1, 14189, 14183, 20599, -1, 14183, 20622, 20600, -1, 14183, 14182, 20622, -1, 11713, 20531, 11704, -1, 15173, 20531, 11713, -1, 15175, 20531, 15173, -1, 15176, 20531, 15175, -1, 15180, 20531, 15176, -1, 15180, 14180, 20531, -1, 14180, 14179, 20531, -1, 14179, 20549, 20531, -1, 14179, 14186, 20549, -1, 14186, 21248, 20549, -1, 14186, 14185, 21248, -1, 12177, 21251, 11371, -1, 12178, 21251, 12177, -1, 12180, 21251, 12178, -1, 12181, 21251, 12180, -1, 11371, 21251, 11372, -1, 12181, 5420, 21251, -1, 5420, 5419, 21251, -1, 5419, 20627, 21251, -1, 5419, 5417, 20627, -1, 5417, 20604, 20627, -1, 5417, 5416, 20604, -1, 5416, 20541, 20604, -1, 5416, 5415, 20541, -1, 20541, 5411, 20523, -1, 5415, 5411, 20541, -1, 5411, 20524, 20523, -1, 5411, 5410, 20524, -1, 20507, 5392, 20504, -1, 5393, 5392, 20507, -1, 20504, 5390, 20498, -1, 5392, 5390, 20504, -1, 20498, 5388, 20482, -1, 5390, 5388, 20498, -1, 20482, 5384, 20405, -1, 5388, 5384, 20482, -1, 20405, 5378, 20406, -1, 5384, 5378, 20405, -1, 20406, 5373, 20291, -1, 5378, 5373, 20406, -1, 20295, 5361, 20310, -1, 5362, 5361, 20295, -1, 20310, 5359, 20311, -1, 5361, 5359, 20310, -1, 20311, 5358, 20158, -1, 5359, 5358, 20311, -1, 20158, 5357, 20150, -1, 5358, 5357, 20158, -1, 20150, 5353, 20319, -1, 5357, 5353, 20150, -1, 20319, 5352, 19750, -1, 5353, 5352, 20319, -1, 19645, 5450, 19787, -1, 5451, 5450, 19645, -1, 19787, 5448, 19788, -1, 5450, 5448, 19787, -1, 19788, 5446, 19507, -1, 5448, 5446, 19788, -1, 19507, 5442, 19503, -1, 5446, 5442, 19507, -1, 19503, 5436, 20229, -1, 5442, 5436, 19503, -1, 20229, 5431, 19061, -1, 5436, 5431, 20229, -1, 18968, 14164, 19108, -1, 14165, 14164, 18968, -1, 19108, 14161, 19109, -1, 14164, 14161, 19108, -1, 19109, 14160, 18814, -1, 14161, 14160, 19109, -1, 18814, 14162, 18809, -1, 14160, 14162, 18814, -1, 18809, 14156, 18616, -1, 14162, 14156, 18809, -1, 18616, 11981, 11980, -1, 18616, 15092, 11981, -1, 18616, 15108, 15092, -1, 14156, 14155, 18616, -1, 18616, 15111, 15108, -1, 14155, 15112, 18616, -1, 18616, 15112, 15111, -1, 20624, 5057, 20625, -1, 5062, 5057, 20624, -1, 21256, 11361, 11360, -1, 21256, 12085, 11361, -1, 21256, 12083, 12085, -1, 20625, 5056, 21256, -1, 5057, 5056, 20625, -1, 21256, 12084, 12083, -1, 5056, 12087, 21256, -1, 21256, 12087, 12084, -1, 20506, 5045, 20542, -1, 5044, 5045, 20506, -1, 20542, 5051, 20602, -1, 5045, 5051, 20542, -1, 20602, 5050, 20603, -1, 5051, 5050, 20602, -1, 20495, 5040, 20496, -1, 5041, 5040, 20495, -1, 20496, 5039, 20505, -1, 5040, 5039, 20496, -1, 20505, 5044, 20506, -1, 5039, 5044, 20505, -1, 20385, 5021, 20404, -1, 5020, 5021, 20385, -1, 20404, 5027, 20483, -1, 5021, 5027, 20404, -1, 20483, 5026, 20484, -1, 5027, 5026, 20483, -1, 20360, 5016, 20309, -1, 5017, 5016, 20360, -1, 20309, 5015, 20344, -1, 5016, 5015, 20309, -1, 20344, 5020, 20385, -1, 5015, 5020, 20344, -1, 20313, 5080, 20151, -1, 5081, 5080, 20313, -1, 20151, 5087, 20149, -1, 5080, 5087, 20151, -1, 20149, 5086, 20361, -1, 5087, 5086, 20149, -1, 19858, 5076, 19786, -1, 5077, 5076, 19858, -1, 19786, 5075, 19828, -1, 5076, 5075, 19786, -1, 19828, 5081, 20313, -1, 5075, 5081, 19828, -1, 20213, 5104, 19504, -1, 5105, 5104, 20213, -1, 19504, 5111, 19502, -1, 5104, 5111, 19504, -1, 19502, 5110, 19859, -1, 5111, 5110, 19502, -1, 5101, 19107, 19168, -1, 5101, 5100, 19107, -1, 19107, 5099, 19143, -1, 5100, 5099, 19107, -1, 5099, 20213, 19143, -1, 5099, 5105, 20213, -1, 11992, 18810, 11990, -1, 14988, 18810, 11992, -1, 14990, 18810, 14988, -1, 14991, 18810, 14990, -1, 14995, 18810, 14991, -1, 14095, 18810, 14995, -1, 18810, 14094, 18808, -1, 14095, 14094, 18810, -1, 14094, 19166, 18808, -1, 14094, 14102, 19166, -1, 11426, 20533, 11427, -1, 12142, 20533, 11426, -1, 12143, 20533, 12142, -1, 12145, 20533, 12143, -1, 12146, 20533, 12145, -1, 5314, 20533, 12146, -1, 20533, 5306, 20521, -1, 5314, 5306, 20533, -1, 5306, 20500, 20521, -1, 5306, 5308, 20500, -1, 5321, 20458, 20471, -1, 5321, 5320, 20458, -1, 20458, 5319, 20437, -1, 5320, 5319, 20458, -1, 5319, 20417, 20437, -1, 5319, 5337, 20417, -1, 5337, 20400, 20417, -1, 5337, 5331, 20400, -1, 20400, 5315, 20388, -1, 5331, 5315, 20400, -1, 20388, 5317, 20249, -1, 5315, 5317, 20388, -1, 20194, 5282, 20342, -1, 5285, 5282, 20194, -1, 20342, 5284, 20323, -1, 5282, 5284, 20342, -1, 20323, 5301, 20324, -1, 5284, 5301, 20323, -1, 20324, 5295, 20317, -1, 5301, 5295, 20324, -1, 20317, 5279, 20308, -1, 5295, 5279, 20317, -1, 20308, 5281, 19675, -1, 5279, 5281, 20308, -1, 19576, 5258, 20258, -1, 5261, 5258, 19576, -1, 20258, 5260, 20246, -1, 5258, 5260, 20258, -1, 20246, 5277, 20247, -1, 5260, 5277, 20246, -1, 20247, 5271, 20234, -1, 5277, 5271, 20247, -1, 20234, 5255, 20224, -1, 5271, 5255, 20234, -1, 20224, 5257, 18987, -1, 5255, 5257, 20224, -1, 18988, 5234, 20182, -1, 5237, 5234, 18988, -1, 20182, 5236, 20173, -1, 5234, 5236, 20182, -1, 20173, 5253, 20165, -1, 5236, 5253, 20173, -1, 20165, 5247, 20156, -1, 5253, 5247, 20165, -1, 20156, 5231, 20135, -1, 5247, 5231, 20156, -1, 20135, 5233, 18588, -1, 5231, 5233, 20135, -1, 18589, 14135, 20076, -1, 14133, 14135, 18589, -1, 18453, 11962, 11960, -1, 18453, 15055, 11962, -1, 18453, 15071, 15055, -1, 20076, 14141, 18453, -1, 14135, 14141, 20076, -1, 18453, 15074, 15071, -1, 14141, 15075, 18453, -1, 18453, 15075, 15074, -1, 20501, 5408, 20502, -1, 5404, 5408, 20501, -1, 20502, 5402, 20520, -1, 5408, 5402, 20502, -1, 20520, 11385, 11384, -1, 20520, 12190, 11385, -1, 20520, 12188, 12190, -1, 5402, 5401, 20520, -1, 20520, 12189, 12188, -1, 5401, 12192, 20520, -1, 20520, 12192, 12189, -1, 20438, 5398, 20456, -1, 5399, 5398, 20438, -1, 20456, 5405, 20470, -1, 5398, 5405, 20456, -1, 20470, 5404, 20501, -1, 5405, 5404, 20470, -1, 20375, 5377, 20376, -1, 5374, 5377, 20375, -1, 20376, 5376, 20387, -1, 5377, 5376, 20376, -1, 20387, 5381, 20399, -1, 5376, 5381, 20387, -1, 20141, 5364, 20343, -1, 5365, 5364, 20141, -1, 20343, 5368, 20353, -1, 5364, 5368, 20343, -1, 20353, 5374, 20375, -1, 5368, 5374, 20353, -1, 20300, 5350, 20301, -1, 5346, 5350, 20300, -1, 20301, 5344, 20307, -1, 5350, 5344, 20301, -1, 20307, 5343, 20142, -1, 5344, 5343, 20307, -1, 19401, 5340, 20261, -1, 5341, 5340, 19401, -1, 20261, 5347, 20270, -1, 5340, 5347, 20261, -1, 20270, 5346, 20300, -1, 5347, 5346, 20270, -1, 20210, 5435, 20211, -1, 5432, 5435, 20210, -1, 20211, 5434, 20223, -1, 5435, 5434, 20211, -1, 20223, 5439, 19402, -1, 5434, 5439, 20223, -1, 18721, 5422, 20181, -1, 5423, 5422, 18721, -1, 20181, 5426, 20193, -1, 5422, 5426, 20181, -1, 20193, 5432, 20210, -1, 5426, 5432, 20193, -1, 14149, 20123, 20112, -1, 14149, 14153, 20123, -1, 20123, 14147, 20136, -1, 14153, 14147, 20123, -1, 14147, 18722, 20136, -1, 14147, 14146, 18722, -1, 11972, 20077, 11970, -1, 15099, 20077, 11972, -1, 15101, 20077, 15099, -1, 15102, 20077, 15101, -1, 15106, 20077, 15102, -1, 15106, 14144, 20077, -1, 14144, 14143, 20077, -1, 14143, 20094, 20077, -1, 14143, 14150, 20094, -1, 14150, 20112, 20094, -1, 14150, 14149, 20112, -1, 12107, 20833, 11327, -1, 12108, 20833, 12107, -1, 12110, 20833, 12108, -1, 12111, 20833, 12110, -1, 11327, 20833, 11325, -1, 12111, 5196, 20833, -1, 5196, 5195, 20833, -1, 5195, 20807, 20833, -1, 5195, 5193, 20807, -1, 5193, 20760, 20807, -1, 5193, 5192, 20760, -1, 5192, 20746, 20760, -1, 5192, 5191, 20746, -1, 20746, 5187, 20722, -1, 5191, 5187, 20746, -1, 5187, 20721, 20722, -1, 5187, 5186, 20721, -1, 20686, 5226, 20678, -1, 5227, 5226, 20686, -1, 20678, 5224, 20679, -1, 5226, 5224, 20678, -1, 20679, 5222, 20634, -1, 5224, 5222, 20679, -1, 20634, 5218, 20615, -1, 5222, 5218, 20634, -1, 20615, 5212, 20613, -1, 5218, 5212, 20615, -1, 20613, 5207, 20559, -1, 5212, 5207, 20613, -1, 20562, 5137, 20564, -1, 5138, 5137, 20562, -1, 20564, 5135, 20565, -1, 5137, 5135, 20564, -1, 20565, 5134, 20518, -1, 5135, 5134, 20565, -1, 20518, 5133, 20491, -1, 5134, 5133, 20518, -1, 20491, 5129, 20492, -1, 5133, 5129, 20491, -1, 20492, 5128, 20432, -1, 5129, 5128, 20492, -1, 20431, 5168, 20441, -1, 5169, 5168, 20431, -1, 20441, 5166, 20442, -1, 5168, 5166, 20441, -1, 20442, 5164, 20391, -1, 5166, 5164, 20442, -1, 20391, 5160, 20381, -1, 5164, 5160, 20391, -1, 20381, 5154, 20369, -1, 5160, 5154, 20381, -1, 20369, 5149, 20125, -1, 5154, 5149, 20369, -1, 20061, 14128, 20335, -1, 14129, 14128, 20061, -1, 20335, 14125, 20336, -1, 14128, 14125, 20335, -1, 20336, 14124, 19921, -1, 14125, 14124, 20336, -1, 19921, 14126, 19922, -1, 14124, 14126, 19921, -1, 19922, 14120, 19519, -1, 14126, 14120, 19922, -1, 19519, 12022, 12020, -1, 19519, 15018, 12022, -1, 19519, 15034, 15018, -1, 14120, 14119, 19519, -1, 19519, 15037, 15034, -1, 14119, 15038, 19519, -1, 19519, 15038, 15037, -1, 21328, 5729, 20806, -1, 5734, 5729, 21328, -1, 20834, 11312, 11311, -1, 20834, 12295, 11312, -1, 20834, 12293, 12295, -1, 20806, 5728, 20834, -1, 5729, 5728, 20806, -1, 20834, 12294, 12293, -1, 5728, 12297, 20834, -1, 20834, 12297, 12294, -1, 20702, 5693, 20720, -1, 5692, 5693, 20702, -1, 20720, 5699, 20759, -1, 5693, 5699, 20720, -1, 20759, 5698, 21323, -1, 5699, 5698, 20759, -1, 21280, 5688, 20677, -1, 5689, 5688, 21280, -1, 20677, 5687, 20685, -1, 5688, 5687, 20677, -1, 20685, 5692, 20702, -1, 5687, 5692, 20685, -1, 20577, 5716, 20614, -1, 5717, 5716, 20577, -1, 20614, 5723, 20633, -1, 5716, 5723, 20614, -1, 20633, 5722, 21271, -1, 5723, 5722, 20633, -1, 21224, 5712, 20566, -1, 5713, 5712, 21224, -1, 20566, 5711, 20576, -1, 5712, 5711, 20566, -1, 20576, 5717, 20577, -1, 5711, 5717, 20576, -1, 20461, 5776, 20493, -1, 5777, 5776, 20461, -1, 20493, 5783, 20517, -1, 5776, 5783, 20493, -1, 20517, 5782, 21175, -1, 5783, 5782, 20517, -1, 20626, 5772, 20443, -1, 5773, 5772, 20626, -1, 20443, 5771, 20460, -1, 5772, 5771, 20443, -1, 20460, 5777, 20461, -1, 5771, 5777, 20460, -1, 20355, 5753, 20370, -1, 5752, 5753, 20355, -1, 20370, 5759, 20390, -1, 5753, 5759, 20370, -1, 20390, 5758, 20543, -1, 5759, 5758, 20390, -1, 5749, 20161, 20117, -1, 5749, 5748, 20161, -1, 20161, 5747, 20348, -1, 5748, 5747, 20161, -1, 5747, 20355, 20348, -1, 5747, 5752, 20355, -1, 12040, 20287, 12037, -1, 15210, 20287, 12040, -1, 15212, 20287, 15210, -1, 15213, 20287, 15212, -1, 15217, 20287, 15213, -1, 14203, 20287, 15217, -1, 20287, 14202, 19923, -1, 14203, 14202, 20287, -1, 14202, 20048, 19923, -1, 14202, 14210, 20048, -1, 11346, 20743, 11347, -1, 12072, 20743, 11346, -1, 12073, 20743, 12072, -1, 12075, 20743, 12073, -1, 12076, 20743, 12075, -1, 5066, 20743, 12076, -1, 20743, 5058, 20717, -1, 5066, 5058, 20743, -1, 5058, 20699, 20717, -1, 5058, 5060, 20699, -1, 5037, 20666, 20665, -1, 5037, 5036, 20666, -1, 20666, 5035, 21245, -1, 5036, 5035, 20666, -1, 5035, 21246, 21245, -1, 5035, 5053, 21246, -1, 5053, 20607, 21246, -1, 5053, 5047, 20607, -1, 20607, 5031, 20589, -1, 5047, 5031, 20607, -1, 20589, 5033, 20580, -1, 5031, 5033, 20589, -1, 20557, 5010, 20556, -1, 5013, 5010, 20557, -1, 20556, 5012, 20473, -1, 5010, 5012, 20556, -1, 20473, 5029, 20474, -1, 5012, 5029, 20473, -1, 20474, 5023, 20475, -1, 5029, 5023, 20474, -1, 20475, 5007, 20479, -1, 5023, 5007, 20475, -1, 20479, 5009, 20464, -1, 5007, 5009, 20479, -1, 20427, 5070, 20331, -1, 5073, 5070, 20427, -1, 20331, 5072, 20332, -1, 5070, 5072, 20331, -1, 20332, 5089, 20358, -1, 5072, 5089, 20332, -1, 20358, 5083, 20255, -1, 5089, 5083, 20358, -1, 20255, 5067, 20256, -1, 5083, 5067, 20255, -1, 20256, 5069, 20074, -1, 5067, 5069, 20256, -1, 20079, 5094, 19813, -1, 5097, 5094, 20079, -1, 19813, 5096, 19701, -1, 5094, 5096, 19813, -1, 19701, 5113, 19702, -1, 5096, 5113, 19701, -1, 19702, 5107, 19703, -1, 5113, 5107, 19702, -1, 19703, 5091, 20283, -1, 5107, 5091, 19703, -1, 20283, 5093, 19372, -1, 5091, 5093, 20283, -1, 19373, 14099, 19081, -1, 14097, 14099, 19373, -1, 18919, 12001, 11999, -1, 18919, 14981, 12001, -1, 18919, 14997, 14981, -1, 19081, 14105, 18919, -1, 14099, 14105, 19081, -1, 18919, 15000, 14997, -1, 14105, 15001, 18919, -1, 18919, 15001, 15000, -1, 20683, 5184, 20700, -1, 5180, 5184, 20683, -1, 20700, 5178, 20744, -1, 5184, 5178, 20700, -1, 20744, 11337, 11336, -1, 20744, 12120, 11337, -1, 20744, 12118, 12120, -1, 5178, 5177, 20744, -1, 20744, 12119, 12118, -1, 5177, 12122, 20744, -1, 20744, 12122, 12119, -1, 20667, 5174, 20668, -1, 5175, 5174, 20667, -1, 20668, 5181, 20669, -1, 5174, 5181, 20668, -1, 20669, 5180, 20683, -1, 5181, 5180, 20669, -1, 20574, 5211, 20579, -1, 5208, 5211, 20574, -1, 20579, 5210, 20588, -1, 5211, 5210, 20579, -1, 20588, 5215, 20606, -1, 5210, 5215, 20588, -1, 20513, 5198, 20554, -1, 5199, 5198, 20513, -1, 20554, 5202, 20555, -1, 5198, 5202, 20554, -1, 20555, 5208, 20574, -1, 5202, 5208, 20555, -1, 20445, 5126, 20463, -1, 5122, 5126, 20445, -1, 20463, 5120, 20478, -1, 5126, 5120, 20463, -1, 20478, 5119, 20476, -1, 5120, 5119, 20478, -1, 20330, 5116, 20425, -1, 5117, 5116, 20330, -1, 20425, 5123, 20426, -1, 5116, 5123, 20425, -1, 20426, 5122, 20445, -1, 5123, 5122, 20426, -1, 20346, 5153, 20350, -1, 5150, 5153, 20346, -1, 20350, 5152, 20254, -1, 5153, 5152, 20350, -1, 20254, 5157, 20282, -1, 5152, 5157, 20254, -1, 19807, 5140, 20329, -1, 5141, 5140, 19807, -1, 20329, 5144, 20333, -1, 5140, 5144, 20329, -1, 20333, 5150, 20346, -1, 5144, 5150, 20333, -1, 14113, 20268, 20253, -1, 14113, 14117, 20268, -1, 20268, 14111, 20281, -1, 14117, 14111, 20268, -1, 14111, 19700, 20281, -1, 14111, 14110, 19700, -1, 12011, 19205, 12009, -1, 15025, 19205, 12011, -1, 15027, 19205, 15025, -1, 15028, 19205, 15027, -1, 15032, 19205, 15028, -1, 15032, 14108, 19205, -1, 14108, 14107, 19205, -1, 14107, 20239, 19205, -1, 14107, 14114, 20239, -1, 14114, 20253, 20239, -1, 14114, 14113, 20253, -1, 1639, 11110, 3338, -1, 11111, 11110, 1639, -1, 3338, 11107, 3348, -1, 11110, 11107, 3338, -1, 3348, 11106, 1718, -1, 11107, 11106, 3348, -1, 3358, 11117, 3347, -1, 3347, 11116, 3337, -1, 11117, 11116, 3347, -1, 3337, 11126, 1659, -1, 11116, 11126, 3337, -1, 11126, 11125, 1659, -1, 50, 11133, 51, -1, 11134, 11133, 50, -1, 51, 11119, 99, -1, 11133, 11119, 51, -1, 99, 11121, 118, -1, 11119, 11121, 99, -1, 11141, 98, 157, -1, 11141, 11140, 98, -1, 11140, 49, 98, -1, 11140, 11150, 49, -1, 11150, 52, 49, -1, 11150, 11149, 52, -1, 274, 11157, 303, -1, 11158, 11157, 274, -1, 303, 11143, 331, -1, 11157, 11143, 303, -1, 331, 11145, 359, -1, 11143, 11145, 331, -1, 11057, 330, 398, -1, 11057, 11056, 330, -1, 11056, 302, 330, -1, 11056, 11066, 302, -1, 11066, 272, 302, -1, 11066, 11065, 272, -1, 603, 11073, 652, -1, 11074, 11073, 603, -1, 652, 11059, 778, -1, 11073, 11059, 652, -1, 778, 11061, 914, -1, 11059, 11061, 778, -1, 11081, 880, 1011, -1, 11081, 11080, 880, -1, 11080, 751, 880, -1, 11080, 11090, 751, -1, 11090, 601, 751, -1, 11090, 11089, 601, -1, 1384, 11097, 1404, -1, 11098, 11097, 1384, -1, 1404, 11082, 1538, -1, 11097, 11082, 1404, -1, 1538, 11085, 1657, -1, 11082, 11085, 1538, -1, 1766, 14701, 1642, -1, 1642, 14700, 1514, -1, 14701, 14700, 1642, -1, 1514, 14704, 1382, -1, 14700, 14704, 1514, -1, 14704, 14703, 1382, -1, 11225, 3294, 3279, -1, 11225, 11224, 3294, -1, 11224, 3306, 3294, -1, 3306, 11237, 1726, -1, 11224, 11237, 3306, -1, 11237, 11244, 1726, -1, 3326, 11169, 3316, -1, 11173, 11169, 3326, -1, 3316, 11166, 3305, -1, 11169, 11166, 3316, -1, 3305, 11165, 3293, -1, 11166, 11165, 3305, -1, 11181, 1775, 1735, -1, 11181, 11182, 1775, -1, 11182, 1818, 1775, -1, 11182, 11186, 1818, -1, 11186, 57, 1818, -1, 11186, 11193, 57, -1, 56, 11206, 1817, -1, 11210, 11206, 56, -1, 1817, 11197, 1776, -1, 11206, 11197, 1817, -1, 1776, 11199, 1738, -1, 11197, 11199, 1776, -1, 11201, 246, 93, -1, 11201, 11200, 246, -1, 11200, 247, 246, -1, 11200, 11213, 247, -1, 11213, 309, 247, -1, 11213, 11220, 309, -1, 308, 11251, 244, -1, 11255, 11251, 308, -1, 244, 11248, 245, -1, 11251, 11248, 244, -1, 245, 11247, 150, -1, 11248, 11247, 245, -1, 11263, 432, 333, -1, 11263, 11264, 432, -1, 11264, 524, 432, -1, 524, 11268, 628, -1, 11264, 11268, 524, -1, 11268, 11275, 628, -1, 623, 17682, 523, -1, 17686, 17682, 623, -1, 523, 17675, 429, -1, 17682, 17675, 523, -1, 429, 17677, 387, -1, 17675, 17677, 429, -1, 5141, 19933, 5142, -1, 19807, 19933, 5141, -1, 5142, 20039, 5145, -1, 19933, 20039, 5142, -1, 5145, 20125, 5149, -1, 20039, 20125, 5145, -1, 14129, 20061, 14122, -1, 14122, 19944, 14109, -1, 20061, 19944, 14122, -1, 14109, 19822, 14110, -1, 19944, 19822, 14109, -1, 19822, 19700, 14110, -1, 5117, 20393, 5115, -1, 20330, 20393, 5117, -1, 5115, 20434, 5124, -1, 20393, 20434, 5115, -1, 5124, 20432, 5128, -1, 20434, 20432, 5124, -1, 5169, 20431, 5162, -1, 5162, 20435, 5158, -1, 20431, 20435, 5162, -1, 5158, 20394, 5157, -1, 20435, 20394, 5158, -1, 20394, 20282, 5157, -1, 5199, 20512, 5200, -1, 20513, 20512, 5199, -1, 5200, 20560, 5203, -1, 20512, 20560, 5200, -1, 5203, 20559, 5207, -1, 20560, 20559, 5203, -1, 5138, 20562, 5131, -1, 5131, 20561, 5118, -1, 20562, 20561, 5131, -1, 5118, 20514, 5119, -1, 20561, 20514, 5118, -1, 20514, 20476, 5119, -1, 5175, 21259, 5173, -1, 20667, 21259, 5175, -1, 5173, 21269, 5182, -1, 21259, 21269, 5173, -1, 5182, 20721, 5186, -1, 21269, 20721, 5182, -1, 5227, 20686, 5220, -1, 5220, 21270, 5216, -1, 20686, 21270, 5220, -1, 5216, 21261, 5215, -1, 21270, 21261, 5216, -1, 21261, 20606, 5215, -1, 19168, 5102, 5101, -1, 19168, 19165, 5102, -1, 19165, 5092, 5102, -1, 19165, 19257, 5092, -1, 19257, 5093, 5092, -1, 19257, 19372, 5093, -1, 14097, 19258, 14098, -1, 19373, 19258, 14097, -1, 14098, 19167, 14101, -1, 19258, 19167, 14098, -1, 14101, 19166, 14102, -1, 19167, 19166, 14101, -1, 19858, 5078, 5077, -1, 19858, 19857, 5078, -1, 19857, 5068, 5078, -1, 19857, 19977, 5068, -1, 19977, 5069, 5068, -1, 19977, 20074, 5069, -1, 5097, 19979, 5095, -1, 20079, 19979, 5097, -1, 5095, 19866, 5109, -1, 19979, 19866, 5095, -1, 5109, 19859, 5110, -1, 19866, 19859, 5109, -1, 20360, 5018, 5017, -1, 20360, 20359, 5018, -1, 20359, 5008, 5018, -1, 20359, 20449, 5008, -1, 20449, 5009, 5008, -1, 20449, 20464, 5009, -1, 5073, 20457, 5071, -1, 20427, 20457, 5073, -1, 5071, 20362, 5085, -1, 20457, 20362, 5071, -1, 5085, 20361, 5086, -1, 20362, 20361, 5085, -1, 20495, 5042, 5041, -1, 20495, 21000, 5042, -1, 21000, 5032, 5042, -1, 21000, 21112, 5032, -1, 21112, 5033, 5032, -1, 21112, 20580, 5033, -1, 5013, 21021, 5011, -1, 20557, 21021, 5013, -1, 5011, 20916, 5025, -1, 21021, 20916, 5011, -1, 5025, 20484, 5026, -1, 20916, 20484, 5025, -1, 20624, 5063, 5062, -1, 20624, 21257, 5063, -1, 21257, 5059, 5063, -1, 21257, 21266, 5059, -1, 21266, 5060, 5059, -1, 21266, 20699, 5060, -1, 5037, 21258, 5034, -1, 20665, 21258, 5037, -1, 5034, 21252, 5049, -1, 21258, 21252, 5034, -1, 5049, 20603, 5050, -1, 21252, 20603, 5049, -1, 20117, 5750, 5749, -1, 20117, 20201, 5750, -1, 20201, 5740, 5750, -1, 20201, 20259, 5740, -1, 20338, 5741, 20259, -1, 20259, 5741, 5740, -1, 14205, 20260, 14206, -1, 20274, 20260, 14205, -1, 14206, 20202, 14209, -1, 20260, 20202, 14206, -1, 14209, 20048, 14210, -1, 20202, 20048, 14209, -1, 20626, 5774, 5773, -1, 20626, 20750, 5774, -1, 20750, 5764, 5774, -1, 20750, 20866, 5764, -1, 20537, 5765, 20866, -1, 20866, 5765, 5764, -1, 5745, 20867, 5743, -1, 20535, 20867, 5745, -1, 5743, 20754, 5757, -1, 20867, 20754, 5743, -1, 5757, 20543, 5758, -1, 20754, 20543, 5757, -1, 21224, 5714, 5713, -1, 21224, 21235, 5714, -1, 21235, 5704, 5714, -1, 21235, 21244, 5704, -1, 21244, 5705, 5704, -1, 21244, 20660, 5705, -1, 5769, 21237, 5767, -1, 20647, 21237, 5769, -1, 5767, 21226, 5781, -1, 21237, 21226, 5767, -1, 5781, 21175, 5782, -1, 21226, 21175, 5781, -1, 21280, 5690, 5689, -1, 21280, 21287, 5690, -1, 21287, 5680, 5690, -1, 21287, 21294, 5680, -1, 20796, 5681, 21294, -1, 21294, 5681, 5680, -1, 5709, 21288, 5707, -1, 20779, 21288, 5709, -1, 5707, 21281, 5721, -1, 21288, 21281, 5707, -1, 5721, 21271, 5722, -1, 21281, 21271, 5721, -1, 21328, 5735, 5734, -1, 21328, 21333, 5735, -1, 21333, 5731, 5735, -1, 21333, 21346, 5731, -1, 21346, 5732, 5731, -1, 21346, 20929, 5732, -1, 5685, 21334, 5682, -1, 20899, 21334, 5685, -1, 5682, 21329, 5697, -1, 21334, 21329, 5682, -1, 5697, 21323, 5698, -1, 21329, 21323, 5697, -1, 5423, 18821, 5424, -1, 18721, 18821, 5423, -1, 5424, 18926, 5427, -1, 18821, 18926, 5424, -1, 5427, 19061, 5431, -1, 18926, 19061, 5427, -1, 14165, 18968, 14158, -1, 14158, 18831, 14145, -1, 18968, 18831, 14158, -1, 14145, 18720, 14146, -1, 18831, 18720, 14145, -1, 18720, 18722, 14146, -1, 5341, 19486, 5339, -1, 19401, 19486, 5341, -1, 5339, 19646, 5348, -1, 19486, 19646, 5339, -1, 5348, 19750, 5352, -1, 19646, 19750, 5348, -1, 5451, 19645, 5444, -1, 5444, 19647, 5440, -1, 19645, 19647, 5444, -1, 5440, 19400, 5439, -1, 19647, 19400, 5440, -1, 19400, 19402, 5439, -1, 5365, 20140, 5366, -1, 20141, 20140, 5365, -1, 5366, 20292, 5369, -1, 20140, 20292, 5366, -1, 5369, 20291, 5373, -1, 20292, 20291, 5369, -1, 5362, 20295, 5355, -1, 5355, 20293, 5342, -1, 20295, 20293, 5355, -1, 5342, 20144, 5343, -1, 20293, 20144, 5342, -1, 20144, 20142, 5343, -1, 5399, 20653, 5397, -1, 20438, 20653, 5399, -1, 5397, 20776, 5406, -1, 20653, 20776, 5397, -1, 5406, 20524, 5410, -1, 20776, 20524, 5406, -1, 5393, 20507, 5386, -1, 5386, 20777, 5382, -1, 20507, 20777, 5386, -1, 5382, 20654, 5381, -1, 20777, 20654, 5382, -1, 20654, 20399, 5381, -1, 18528, 5242, 5241, -1, 18528, 18527, 5242, -1, 18527, 5232, 5242, -1, 18527, 18569, 5232, -1, 18569, 5233, 5232, -1, 18569, 18588, 5233, -1, 14133, 18570, 14134, -1, 18589, 18570, 14133, -1, 14134, 18530, 14137, -1, 18570, 18530, 14134, -1, 14137, 18529, 14138, -1, 18530, 18529, 14137, -1, 18761, 5266, 5265, -1, 18761, 18753, 5266, -1, 18753, 5256, 5266, -1, 18753, 18851, 5256, -1, 18851, 5257, 5256, -1, 18851, 18987, 5257, -1, 5237, 18852, 5235, -1, 18988, 18852, 5237, -1, 5235, 18755, 5249, -1, 18852, 18755, 5235, -1, 5249, 18754, 5250, -1, 18755, 18754, 5249, -1, 19408, 5290, 5289, -1, 19408, 19407, 5290, -1, 19407, 5280, 5290, -1, 19407, 19538, 5280, -1, 19538, 5281, 5280, -1, 19538, 19675, 5281, -1, 5261, 19539, 5259, -1, 19576, 19539, 5261, -1, 5259, 19415, 5273, -1, 19539, 19415, 5259, -1, 5273, 19409, 5274, -1, 19415, 19409, 5273, -1, 20023, 5326, 5325, -1, 20023, 20080, 5326, -1, 20080, 5316, 5326, -1, 20080, 20170, 5316, -1, 20170, 5317, 5316, -1, 20170, 20249, 5317, -1, 5285, 20102, 5283, -1, 20194, 20102, 5285, -1, 5283, 20022, 5297, -1, 20102, 20022, 5283, -1, 5297, 20024, 5298, -1, 20022, 20024, 5297, -1, 20414, 5311, 5310, -1, 20414, 20611, 5311, -1, 20611, 5307, 5311, -1, 20611, 20733, 5307, -1, 20733, 5308, 5307, -1, 20733, 20500, 5308, -1, 5321, 20628, 5318, -1, 20471, 20628, 5321, -1, 5318, 20508, 5333, -1, 20628, 20508, 5318, -1, 5333, 20397, 5334, -1, 20508, 20397, 5333, -1, 20637, 21275, 5589, -1, 21275, 5590, 5589, -1, 21275, 21284, 5590, -1, 21284, 5593, 5590, -1, 21284, 20706, 5593, -1, 20706, 5597, 5593, -1, 14182, 21265, 20622, -1, 14181, 21265, 14182, -1, 14194, 21277, 14181, -1, 14181, 21277, 21265, -1, 14201, 20707, 14194, -1, 14194, 20707, 21277, -1, 20770, 20816, 5657, -1, 20816, 5655, 5657, -1, 20816, 20815, 5655, -1, 20815, 5664, 5655, -1, 20815, 20864, 5664, -1, 20864, 5668, 5664, -1, 5605, 20817, 20748, -1, 5606, 20817, 5605, -1, 5610, 20814, 5606, -1, 5606, 20814, 20817, -1, 5617, 20865, 5610, -1, 5610, 20865, 20814, -1, 20886, 20943, 5623, -1, 20943, 5624, 5623, -1, 20943, 20942, 5624, -1, 20942, 5627, 5624, -1, 20942, 20977, 5627, -1, 20977, 5631, 5627, -1, 5659, 20944, 20876, -1, 5658, 20944, 5659, -1, 5671, 20941, 5658, -1, 5658, 20941, 20944, -1, 5678, 20978, 5671, -1, 5671, 20978, 20941, -1, 21027, 21429, 5565, -1, 21429, 5563, 5565, -1, 21429, 21441, 5563, -1, 21441, 5572, 5563, -1, 21441, 21104, 5572, -1, 21104, 5576, 5572, -1, 5639, 21430, 20998, -1, 5640, 21430, 5639, -1, 5644, 21442, 5640, -1, 5640, 21442, 21430, -1, 5651, 21079, 5644, -1, 5644, 21079, 21442, -1, 21145, 5550, 20489, -1, 20489, 5550, 5549, -1, 21206, 5540, 21145, -1, 21145, 5540, 5550, -1, 20598, 5541, 21206, -1, 21206, 5541, 5540, -1, 14173, 20488, 14174, -1, 14170, 21147, 14173, -1, 14173, 21147, 20488, -1, 14169, 21207, 14170, -1, 14170, 21207, 21147, -1, 14169, 20550, 21207, -1, 21267, 5526, 20618, -1, 20618, 5526, 5525, -1, 21278, 5516, 21267, -1, 21267, 5516, 5526, -1, 20726, 5517, 21278, -1, 21278, 5517, 5516, -1, 5557, 20617, 5558, -1, 5543, 21268, 5557, -1, 5557, 21268, 20617, -1, 5545, 21279, 5543, -1, 5543, 21279, 21268, -1, 5545, 20681, 21279, -1, 21316, 5502, 20753, -1, 20753, 5502, 5501, -1, 21326, 5492, 21316, -1, 21316, 5492, 5502, -1, 20858, 5493, 21326, -1, 21326, 5493, 5492, -1, 5533, 20732, 5534, -1, 5519, 21317, 5533, -1, 5533, 21317, 20732, -1, 5521, 21320, 5519, -1, 5519, 21320, 21317, -1, 5521, 20804, 21320, -1, 21369, 5478, 20880, -1, 20880, 5478, 5477, -1, 21374, 5468, 21369, -1, 21369, 5468, 5478, -1, 20981, 5469, 21374, -1, 21374, 5469, 5468, -1, 5509, 20873, 5510, -1, 5495, 21364, 5509, -1, 5509, 21364, 20873, -1, 5497, 21370, 5495, -1, 5495, 21370, 21364, -1, 5497, 20935, 21370, -1, 21424, 5463, 21011, -1, 21011, 5463, 5462, -1, 21437, 5459, 21424, -1, 21424, 5459, 5463, -1, 21093, 5460, 21437, -1, 21437, 5460, 5459, -1, 5485, 20995, 5486, -1, 5470, 21416, 5485, -1, 5485, 21416, 20995, -1, 5473, 21428, 5470, -1, 5470, 21428, 21416, -1, 5473, 21049, 21428, -1, 20691, 8542, 8541, -1, 21295, 8542, 20691, -1, 21304, 8532, 21295, -1, 21295, 8532, 8542, -1, 20787, 8533, 21304, -1, 21304, 8533, 8532, -1, 14617, 20690, 14618, -1, 14614, 21296, 14617, -1, 14617, 21296, 20690, -1, 14613, 21305, 14614, -1, 14614, 21305, 21296, -1, 14613, 20757, 21305, -1, 20842, 8518, 8517, -1, 21348, 8518, 20842, -1, 21358, 8508, 21348, -1, 21348, 8508, 8518, -1, 20920, 8509, 21358, -1, 21358, 8509, 8508, -1, 8549, 20841, 8550, -1, 8535, 21349, 8549, -1, 8549, 21349, 20841, -1, 8537, 21359, 8535, -1, 8535, 21359, 21349, -1, 8537, 20894, 21359, -1, 20969, 8494, 8493, -1, 21406, 8494, 20969, -1, 21412, 8484, 21406, -1, 21406, 8484, 8494, -1, 21033, 8485, 21412, -1, 21412, 8485, 8484, -1, 8525, 20954, 8526, -1, 8511, 21397, 8525, -1, 8525, 21397, 20954, -1, 8513, 21407, 8511, -1, 8511, 21407, 21397, -1, 8513, 21018, 21407, -1, 21075, 8578, 8577, -1, 21460, 8578, 21075, -1, 21468, 8568, 21460, -1, 21460, 8568, 8578, -1, 21133, 8569, 21468, -1, 21468, 8569, 8568, -1, 8501, 21063, 8502, -1, 8487, 21453, 8501, -1, 8501, 21453, 21063, -1, 8489, 21463, 8487, -1, 8487, 21463, 21453, -1, 8489, 21117, 21463, -1, 18457, 8563, 8562, -1, 18486, 8563, 18457, -1, 18505, 8559, 18486, -1, 18486, 8559, 8563, -1, 18534, 8560, 18505, -1, 18505, 8560, 8559, -1, 8585, 18458, 8586, -1, 8570, 18456, 8585, -1, 8585, 18456, 18458, -1, 8573, 18490, 8570, -1, 8570, 18490, 18456, -1, 8573, 18507, 18490, -1, 20421, 20818, 5871, -1, 20818, 5872, 5871, -1, 20818, 20936, 5872, -1, 20936, 5875, 5872, -1, 20936, 21055, 5875, -1, 21055, 5879, 5875, -1, 14218, 20718, 20409, -1, 14217, 20718, 14218, -1, 14230, 20835, 14217, -1, 14217, 20835, 20718, -1, 14237, 20970, 14230, -1, 14230, 20970, 20835, -1, 20569, 20594, 5847, -1, 20594, 5845, 5847, -1, 20594, 20639, 5845, -1, 20639, 5854, 5845, -1, 20639, 20641, 5854, -1, 20641, 5858, 5854, -1, 5887, 20593, 20568, -1, 5888, 20593, 5887, -1, 5892, 20640, 5888, -1, 5888, 20640, 20593, -1, 5899, 20642, 5892, -1, 5892, 20642, 20640, -1, 20671, 20712, 5813, -1, 20712, 5814, 5813, -1, 20712, 20763, 5814, -1, 20763, 5817, 5814, -1, 20763, 20762, 5817, -1, 20762, 5821, 5817, -1, 5849, 20713, 20675, -1, 5848, 20713, 5849, -1, 5861, 20764, 5848, -1, 5848, 20764, 20713, -1, 5868, 20765, 5861, -1, 5861, 20765, 20764, -1, 20822, 21337, 5789, -1, 21337, 5787, 5789, -1, 21337, 21350, 5787, -1, 21350, 5796, 5787, -1, 21350, 21361, 5796, -1, 21361, 5800, 5796, -1, 5829, 21338, 20784, -1, 5830, 21338, 5829, -1, 5834, 21351, 5830, -1, 5830, 21351, 21338, -1, 5841, 21362, 5834, -1, 5834, 21362, 21351, -1, 5905, 18420, 5906, -1, 18372, 18420, 5905, -1, 5906, 18455, 5909, -1, 18420, 18455, 5906, -1, 5909, 18499, 5913, -1, 18455, 18499, 5909, -1, 14261, 18473, 14254, -1, 14254, 18426, 14241, -1, 18473, 18426, 14254, -1, 14241, 18371, 14242, -1, 18426, 18371, 14241, -1, 18371, 18373, 14242, -1, 5973, 20131, 5971, -1, 20106, 20131, 5973, -1, 5971, 20130, 5980, -1, 20131, 20130, 5971, -1, 5980, 18779, 5984, -1, 20130, 18779, 5980, -1, 5933, 18771, 5926, -1, 5926, 20132, 5922, -1, 18771, 20132, 5926, -1, 5922, 20133, 5921, -1, 20132, 20133, 5922, -1, 20133, 20084, 5921, -1, 5939, 20217, 5940, -1, 20186, 20217, 5939, -1, 5940, 20216, 5943, -1, 20217, 20216, 5940, -1, 5943, 19446, 5947, -1, 20216, 19446, 5943, -1, 5994, 19431, 5987, -1, 5987, 20215, 5974, -1, 19431, 20215, 5987, -1, 5974, 20218, 5975, -1, 20215, 20218, 5974, -1, 20218, 20175, 5975, -1, 5997, 19760, 5995, -1, 19761, 19760, 5997, -1, 5995, 19890, 6004, -1, 19760, 19890, 5995, -1, 6004, 19996, 6008, -1, 19890, 19996, 6004, -1, 5967, 19997, 5960, -1, 5960, 19891, 5956, -1, 19997, 19891, 5960, -1, 5956, 19763, 5955, -1, 19891, 19763, 5956, -1, 19763, 19762, 5955, -1, 6065, 19855, 6066, -1, 6066, 21426, 6056, -1, 19855, 21426, 6066, -1, 6056, 21435, 6057, -1, 21426, 21435, 6056, -1, 21435, 21446, 6057, -1, 14265, 21436, 14266, -1, 19909, 21436, 14265, -1, 14266, 21427, 14269, -1, 21436, 21427, 14266, -1, 14269, 19835, 14270, -1, 21427, 19835, 14269, -1, 18394, 6090, 6089, -1, 18394, 18391, 6090, -1, 18391, 6080, 6090, -1, 18391, 18431, 6080, -1, 18431, 6081, 6080, -1, 18431, 18478, 6081, -1, 6061, 18432, 6059, -1, 18446, 18432, 6061, -1, 6059, 18393, 6073, -1, 18432, 18393, 6059, -1, 6073, 18392, 6074, -1, 18393, 18392, 6073, -1, 18577, 6114, 6113, -1, 18577, 18599, 6114, -1, 18599, 6104, 6114, -1, 18599, 18620, 6104, -1, 18620, 6105, 6104, -1, 18620, 18677, 6105, -1, 6085, 18606, 6083, -1, 18636, 18606, 6085, -1, 6083, 18582, 6097, -1, 18606, 18582, 6083, -1, 6097, 18579, 6098, -1, 18582, 18579, 6097, -1, 18858, 6042, 6041, -1, 18858, 19000, 6042, -1, 19000, 6032, 6042, -1, 19000, 19121, 6032, -1, 19121, 6033, 6032, -1, 19121, 19242, 6033, -1, 6109, 19020, 6107, -1, 19156, 19020, 6109, -1, 6107, 18907, 6121, -1, 19020, 18907, 6107, -1, 6121, 18860, 6122, -1, 18907, 18860, 6121, -1, 6026, 19595, 6027, -1, 6027, 19710, 6023, -1, 19595, 19710, 6027, -1, 6023, 19839, 6024, -1, 19710, 19839, 6023, -1, 19839, 19955, 6024, -1, 6037, 19731, 6034, -1, 19848, 19731, 6037, -1, 6034, 19610, 6049, -1, 19731, 19610, 6034, -1, 6049, 19597, 6050, -1, 19610, 19597, 6049, -1, 6187, 21399, 6188, -1, 21387, 21399, 6187, -1, 6188, 21409, 6191, -1, 21399, 21409, 6188, -1, 6191, 21417, 6195, -1, 21409, 21417, 6191, -1, 14297, 19917, 14290, -1, 19917, 21400, 14290, -1, 21400, 14277, 14290, -1, 21400, 21388, 14277, -1, 21388, 14278, 14277, -1, 21388, 21375, 14278, -1, 6221, 19964, 6219, -1, 19929, 19964, 6221, -1, 6219, 20008, 6228, -1, 19964, 20008, 6219, -1, 6228, 18396, 6232, -1, 20008, 18396, 6228, -1, 18397, 6208, 6215, -1, 18397, 20009, 6208, -1, 20009, 6204, 6208, -1, 20009, 19965, 6204, -1, 19965, 6203, 6204, -1, 19965, 19926, 6203, -1, 6153, 18554, 6154, -1, 18470, 18554, 6153, -1, 6154, 18551, 6157, -1, 18554, 18551, 6154, -1, 6157, 18602, 6161, -1, 18551, 18602, 6157, -1, 18603, 6235, 6242, -1, 18603, 18553, 6235, -1, 18553, 6222, 6235, -1, 18553, 18552, 6222, -1, 18552, 6223, 6222, -1, 18552, 18429, 6223, -1, 6129, 18698, 6127, -1, 18668, 18698, 6129, -1, 6127, 18782, 6136, -1, 18698, 18782, 6127, -1, 6136, 18879, 6140, -1, 18782, 18879, 6136, -1, 6181, 18880, 6174, -1, 18880, 18783, 6174, -1, 18783, 6170, 6174, -1, 18783, 18699, 6170, -1, 18699, 6169, 6170, -1, 18699, 18621, 6169, -1, 6265, 19655, 6266, -1, 6266, 21335, 6256, -1, 19655, 21335, 6266, -1, 6256, 21344, 6257, -1, 21335, 21344, 6256, -1, 21344, 19758, 6257, -1, 14301, 21345, 14302, -1, 19759, 21345, 14301, -1, 14302, 21336, 14305, -1, 21345, 21336, 14302, -1, 14305, 19654, 14306, -1, 21336, 19654, 14305, -1, 6289, 21379, 6290, -1, 6290, 21392, 6280, -1, 21379, 21392, 6290, -1, 6280, 21402, 6281, -1, 21392, 21402, 6280, -1, 21402, 19905, 6281, -1, 6261, 21403, 6259, -1, 19886, 21403, 6261, -1, 6259, 21394, 6273, -1, 21403, 21394, 6259, -1, 6273, 21372, 6274, -1, 21394, 21372, 6273, -1, 6337, 21440, 6338, -1, 6338, 21450, 6328, -1, 21440, 21450, 6338, -1, 6328, 21458, 6329, -1, 21450, 21458, 6328, -1, 21458, 20029, 6329, -1, 6285, 21459, 6283, -1, 20004, 21459, 6285, -1, 6283, 21451, 6297, -1, 21459, 21451, 6283, -1, 6297, 21431, 6298, -1, 21451, 21431, 6297, -1, 6313, 18433, 6314, -1, 6314, 18481, 6304, -1, 18433, 18481, 6314, -1, 6304, 18508, 6305, -1, 18481, 18508, 6304, -1, 18508, 18564, 6305, -1, 6333, 18485, 6331, -1, 18521, 18485, 6333, -1, 6331, 18450, 6345, -1, 18485, 18450, 6331, -1, 6345, 18410, 6346, -1, 18450, 18410, 6345, -1, 6250, 18655, 6251, -1, 6251, 18691, 6247, -1, 18655, 18691, 6251, -1, 6247, 18737, 6248, -1, 18691, 18737, 6247, -1, 18737, 18835, 6248, -1, 6309, 18697, 6306, -1, 18749, 18697, 6309, -1, 6306, 18654, 6321, -1, 18697, 18654, 6306, -1, 6321, 18656, 6322, -1, 18654, 18656, 6321, -1, 6621, 19412, 6622, -1, 6622, 21262, 6612, -1, 19412, 21262, 6622, -1, 6612, 21272, 6613, -1, 21262, 21272, 6612, -1, 21272, 19523, 6613, -1, 14349, 21273, 14350, -1, 19488, 21273, 14349, -1, 14350, 21263, 14353, -1, 21273, 21263, 14350, -1, 14353, 19411, 14354, -1, 21263, 19411, 14353, -1, 6597, 19579, 6598, -1, 6598, 21310, 6588, -1, 19579, 21310, 6598, -1, 6588, 21318, 6589, -1, 21310, 21318, 6588, -1, 21318, 19668, 6589, -1, 6617, 21319, 6615, -1, 19639, 21319, 6617, -1, 6615, 21311, 6629, -1, 21319, 21311, 6615, -1, 6629, 19578, 6630, -1, 21311, 19578, 6629, -1, 6645, 19722, 6646, -1, 6646, 21360, 6636, -1, 19722, 21360, 6646, -1, 6636, 21368, 6637, -1, 21360, 21368, 6636, -1, 21368, 19812, 6637, -1, 6593, 21363, 6591, -1, 19775, 21363, 6593, -1, 6591, 21352, 6605, -1, 21363, 21352, 6591, -1, 6605, 19705, 6606, -1, 21352, 19705, 6605, -1, 6669, 19846, 6670, -1, 6670, 21413, 6660, -1, 19846, 21413, 6670, -1, 6660, 21420, 6661, -1, 21413, 21420, 6660, -1, 21420, 19943, 6661, -1, 6641, 21415, 6639, -1, 19914, 21415, 6641, -1, 6639, 21408, 6653, -1, 21415, 21408, 6639, -1, 6653, 19833, 6654, -1, 21408, 19833, 6653, -1, 6582, 19986, 6583, -1, 6583, 18383, 6579, -1, 19986, 18383, 6583, -1, 6579, 18382, 6580, -1, 18383, 18382, 6579, -1, 18382, 18427, 6580, -1, 6665, 18384, 6662, -1, 18390, 18384, 6665, -1, 6662, 21466, 6677, -1, 18384, 21466, 6662, -1, 6677, 19969, 6678, -1, 21466, 19969, 6677, -1, 6377, 21238, 6378, -1, 19351, 21238, 6377, -1, 6378, 21249, 6381, -1, 21238, 21249, 6378, -1, 6381, 19438, 6385, -1, 21249, 19438, 6381, -1, 19437, 14326, 14333, -1, 19437, 21240, 14326, -1, 21240, 14313, 14326, -1, 21240, 21227, 14313, -1, 21227, 14314, 14313, -1, 21227, 19339, 14314, -1, 6411, 19555, 6409, -1, 19506, 19555, 6411, -1, 6409, 19554, 6418, -1, 19555, 19554, 6409, -1, 6418, 19609, 6422, -1, 19554, 19609, 6418, -1, 19608, 6398, 6405, -1, 19608, 19553, 6398, -1, 19553, 6394, 6398, -1, 19553, 19556, 6394, -1, 19556, 6393, 6394, -1, 19556, 19482, 6393, -1, 6435, 19688, 6436, -1, 19632, 19688, 6435, -1, 6436, 19690, 6439, -1, 19688, 19690, 6436, -1, 6439, 19729, 6443, -1, 19690, 19729, 6439, -1, 19730, 6425, 6432, -1, 19730, 19691, 6425, -1, 19691, 6412, 6425, -1, 19691, 19689, 6412, -1, 19689, 6413, 6412, -1, 19689, 19620, 6413, -1, 6353, 21383, 6351, -1, 19783, 21383, 6353, -1, 6351, 21395, 6360, -1, 21383, 21395, 6351, -1, 6360, 19888, 6364, -1, 21395, 19888, 6360, -1, 19850, 6456, 6463, -1, 19850, 21396, 6456, -1, 21396, 6452, 6456, -1, 21396, 21384, 6452, -1, 21384, 6451, 6452, -1, 21384, 19753, 6451, -1, 6525, 19202, 6526, -1, 6526, 20735, 6516, -1, 19202, 20735, 6526, -1, 6516, 20828, 6517, -1, 20735, 20828, 6516, -1, 20828, 19314, 6517, -1, 14337, 20829, 14338, -1, 19262, 20829, 14337, -1, 14338, 20736, 14341, -1, 20829, 20736, 14338, -1, 14341, 19201, 14342, -1, 20736, 19201, 14341, -1, 6501, 19334, 6502, -1, 6502, 21230, 6492, -1, 19334, 21230, 6502, -1, 6492, 21241, 6493, -1, 21230, 21241, 6492, -1, 21241, 19459, 6493, -1, 6521, 21242, 6519, -1, 19397, 21242, 6521, -1, 6519, 21231, 6533, -1, 21242, 21231, 6519, -1, 6533, 19333, 6534, -1, 21231, 19333, 6533, -1, 6477, 19485, 6478, -1, 6478, 21282, 6468, -1, 19485, 21282, 6478, -1, 6468, 21289, 6469, -1, 21282, 21289, 6468, -1, 21289, 19600, 6469, -1, 6497, 21290, 6495, -1, 19543, 21290, 6497, -1, 6495, 21283, 6509, -1, 21290, 21283, 6495, -1, 6509, 19466, 6510, -1, 21283, 19466, 6509, -1, 6561, 19622, 6562, -1, 6562, 21327, 6552, -1, 19622, 21327, 6562, -1, 6552, 21332, 6553, -1, 21327, 21332, 6552, -1, 21332, 19735, 6553, -1, 6473, 21330, 6471, -1, 19683, 21330, 6473, -1, 6471, 21324, 6485, -1, 21330, 21324, 6471, -1, 6485, 19614, 6486, -1, 21324, 19614, 6485, -1, 6546, 19769, 6547, -1, 6547, 21378, 6543, -1, 19769, 21378, 6547, -1, 6543, 21389, 6544, -1, 21378, 21389, 6543, -1, 21389, 19878, 6544, -1, 6557, 21380, 6554, -1, 19818, 21380, 6557, -1, 6554, 21371, 6569, -1, 21380, 21371, 6554, -1, 6569, 19748, 6570, -1, 21371, 19748, 6569, -1, 6767, 21314, 6768, -1, 19598, 21314, 6767, -1, 6768, 21325, 6771, -1, 21314, 21325, 6768, -1, 6771, 19685, 6775, -1, 21325, 19685, 6771, -1, 19670, 14374, 14381, -1, 19670, 21315, 14374, -1, 21315, 14361, 14374, -1, 21315, 21306, 14361, -1, 21306, 14362, 14361, -1, 21306, 19582, 14362, -1, 6743, 19745, 6741, -1, 19746, 19745, 6743, -1, 6741, 19781, 6750, -1, 19745, 19781, 6741, -1, 6750, 19831, 6754, -1, 19781, 19831, 6750, -1, 19804, 6788, 6795, -1, 19804, 19780, 6788, -1, 19780, 6784, 6788, -1, 19780, 19742, 6784, -1, 19742, 6783, 6784, -1, 19742, 19718, 6783, -1, 6709, 19864, 6710, -1, 19862, 19864, 6709, -1, 6710, 19920, 6713, -1, 19864, 19920, 6710, -1, 6713, 19957, 6717, -1, 19920, 19957, 6713, -1, 19941, 6757, 6764, -1, 19941, 19919, 6757, -1, 19919, 6744, 6757, -1, 19919, 19865, 6744, -1, 19865, 6745, 6744, -1, 19865, 19838, 6745, -1, 6685, 18407, 6683, -1, 20011, 18407, 6685, -1, 6683, 18406, 6692, -1, 18407, 18406, 6683, -1, 6692, 18440, 6696, -1, 18406, 18440, 6692, -1, 18442, 6730, 6737, -1, 18442, 18409, 6730, -1, 18409, 6726, 6730, -1, 18409, 18408, 6726, -1, 18408, 6725, 6726, -1, 18408, 19972, 6725, -1, 6945, 2168, 874, -1, 6945, 6944, 2168, -1, 6944, 2254, 2168, -1, 6944, 6957, 2254, -1, 6957, 2390, 2254, -1, 6957, 6964, 2390, -1, 2479, 6913, 2353, -1, 6917, 6913, 2479, -1, 2353, 6910, 2239, -1, 6913, 6910, 2353, -1, 2239, 6909, 886, -1, 6910, 6909, 2239, -1, 6925, 1085, 1061, -1, 6925, 6926, 1085, -1, 6926, 1136, 1085, -1, 6926, 6930, 1136, -1, 6930, 1137, 1136, -1, 6930, 6937, 1137, -1, 1134, 7008, 1135, -1, 7012, 7008, 1134, -1, 1135, 6999, 1084, -1, 7008, 6999, 1135, -1, 1084, 7001, 1058, -1, 6999, 7001, 1084, -1, 7003, 1222, 1170, -1, 7003, 7002, 1222, -1, 7002, 1280, 1222, -1, 7002, 7015, 1280, -1, 7015, 1282, 1280, -1, 7015, 7022, 1282, -1, 1281, 6971, 1279, -1, 6975, 6971, 1281, -1, 1279, 6968, 1221, -1, 6971, 6968, 1279, -1, 1221, 6967, 1166, -1, 6968, 6967, 1221, -1, 6983, 3194, 1306, -1, 6983, 6984, 3194, -1, 6984, 3206, 3194, -1, 6984, 6988, 3206, -1, 6988, 3213, 3206, -1, 6988, 6995, 3213, -1, 3212, 14397, 3205, -1, 14401, 14397, 3212, -1, 3205, 14390, 3193, -1, 14397, 14390, 3205, -1, 3193, 14392, 1345, -1, 14390, 14392, 3193, -1, 6903, 6902, 1436, -1, 6902, 1680, 1436, -1, 6902, 6899, 1680, -1, 6899, 1773, 1680, -1, 6899, 6898, 1773, -1, 6898, 858, 1773, -1, 1674, 6882, 1551, -1, 1551, 6882, 6881, -1, 1772, 6872, 1674, -1, 1674, 6872, 6882, -1, 865, 6873, 1772, -1, 1772, 6873, 6872, -1, 6890, 6889, 2048, -1, 6889, 2195, 2048, -1, 6889, 6875, 2195, -1, 6875, 2282, 2195, -1, 6875, 6877, 2282, -1, 6877, 1021, 2282, -1, 2194, 6810, 2100, -1, 2100, 6810, 6809, -1, 2281, 6800, 2194, -1, 2194, 6800, 6810, -1, 1020, 6801, 2281, -1, 2281, 6801, 6800, -1, 6818, 6817, 2648, -1, 6817, 2824, 2648, -1, 6817, 6803, 2824, -1, 6803, 2934, 2824, -1, 6803, 6805, 2934, -1, 6805, 1145, 2934, -1, 2822, 6834, 2716, -1, 2716, 6834, 6833, -1, 2933, 6824, 2822, -1, 2822, 6824, 6834, -1, 1155, 6825, 2933, -1, 2933, 6825, 6824, -1, 6842, 6841, 3111, -1, 6841, 3124, 3111, -1, 6841, 6827, 3124, -1, 6827, 3135, 3124, -1, 3135, 6829, 1299, -1, 6827, 6829, 3135, -1, 3134, 6858, 3120, -1, 3120, 6858, 6857, -1, 3144, 6848, 3134, -1, 3134, 6848, 6858, -1, 1320, 6849, 3144, -1, 3144, 6849, 6848, -1, 6866, 6865, 3174, -1, 6865, 3185, 3174, -1, 6865, 6850, 3185, -1, 6850, 3192, 3185, -1, 6850, 6853, 3192, -1, 6853, 1434, 3192, -1, 3191, 14388, 3182, -1, 3182, 14388, 14387, -1, 3201, 14384, 3191, -1, 3191, 14384, 14388, -1, 1477, 14385, 3201, -1, 3201, 14385, 14384, -1, 965, 7550, 2588, -1, 7551, 7550, 965, -1, 2588, 7547, 2689, -1, 7550, 7547, 2588, -1, 2689, 7546, 1035, -1, 7547, 7546, 2689, -1, 1087, 7557, 2682, -1, 2682, 7556, 2587, -1, 7557, 7556, 2682, -1, 2587, 7566, 966, -1, 7556, 7566, 2587, -1, 7566, 7565, 966, -1, 1115, 7573, 3108, -1, 7574, 7573, 1115, -1, 3108, 7559, 3119, -1, 7573, 7559, 3108, -1, 3119, 7561, 1177, -1, 7559, 7561, 3119, -1, 1240, 7497, 3118, -1, 3118, 7496, 3107, -1, 7497, 7496, 3118, -1, 3107, 7506, 1116, -1, 7496, 7506, 3107, -1, 7506, 7505, 1116, -1, 1245, 7513, 3163, -1, 7514, 7513, 1245, -1, 3163, 7499, 3172, -1, 7513, 7499, 3163, -1, 3172, 7501, 1329, -1, 7499, 7501, 3172, -1, 1392, 7473, 3178, -1, 3178, 7472, 3168, -1, 7473, 7472, 3178, -1, 3168, 7482, 1269, -1, 7472, 7482, 3168, -1, 7482, 7481, 1269, -1, 1406, 7489, 3215, -1, 7490, 7489, 1406, -1, 3215, 7475, 3226, -1, 7489, 7475, 3215, -1, 3226, 7477, 1483, -1, 7475, 7477, 3226, -1, 1535, 7521, 3229, -1, 3229, 7520, 3221, -1, 7521, 7520, 3229, -1, 3221, 7530, 1417, -1, 7520, 7530, 3221, -1, 7530, 7529, 1417, -1, 1548, 7537, 3274, -1, 7538, 7537, 1548, -1, 3274, 7522, 3284, -1, 7537, 7522, 3274, -1, 3284, 7525, 1622, -1, 7522, 7525, 3284, -1, 1685, 14469, 3295, -1, 3295, 14468, 3282, -1, 14469, 14468, 3295, -1, 3282, 14472, 1568, -1, 14468, 14472, 3282, -1, 14472, 14471, 1568, -1, 7227, 1178, 688, -1, 7226, 1178, 7227, -1, 7239, 1316, 7226, -1, 7226, 1316, 1178, -1, 7246, 779, 7239, -1, 7239, 779, 1316, -1, 1293, 7133, 741, -1, 1424, 7134, 1293, -1, 1293, 7134, 7133, -1, 788, 7137, 1424, -1, 1424, 7137, 7134, -1, 788, 7141, 7137, -1, 7149, 850, 798, -1, 7150, 850, 7149, -1, 7154, 896, 7150, -1, 7150, 896, 850, -1, 7161, 897, 7154, -1, 7154, 897, 896, -1, 849, 7167, 848, -1, 899, 7165, 849, -1, 849, 7165, 7167, -1, 898, 7174, 899, -1, 899, 7174, 7165, -1, 898, 7178, 7174, -1, 7169, 990, 950, -1, 7168, 990, 7169, -1, 7181, 1047, 7168, -1, 7168, 1047, 990, -1, 7188, 1048, 7181, -1, 7181, 1048, 1047, -1, 991, 7191, 992, -1, 1050, 7192, 991, -1, 991, 7192, 7191, -1, 1049, 7195, 1050, -1, 1050, 7195, 7192, -1, 1049, 7199, 7195, -1, 7207, 3089, 1097, -1, 7208, 3089, 7207, -1, 7212, 3110, 7208, -1, 7208, 3110, 3089, -1, 7219, 1185, 7212, -1, 7212, 1185, 3110, -1, 3088, 14420, 1160, -1, 3109, 14418, 3088, -1, 3088, 14418, 14420, -1, 1232, 14425, 3109, -1, 3109, 14425, 14418, -1, 1232, 14429, 14425, -1, 7079, 7078, 544, -1, 7078, 545, 544, -1, 7078, 7075, 545, -1, 7075, 625, 545, -1, 7075, 7074, 625, -1, 7074, 617, 625, -1, 543, 7094, 546, -1, 546, 7094, 7093, -1, 624, 7084, 543, -1, 543, 7084, 7094, -1, 643, 7085, 624, -1, 624, 7085, 7084, -1, 7102, 7101, 682, -1, 7101, 1229, 682, -1, 7101, 7087, 1229, -1, 7087, 1348, 1229, -1, 7087, 7089, 1348, -1, 7089, 745, 1348, -1, 1224, 7118, 683, -1, 683, 7118, 7117, -1, 1344, 7108, 1224, -1, 1224, 7108, 7118, -1, 773, 7109, 1344, -1, 1344, 7109, 7108, -1, 7126, 7125, 806, -1, 7125, 1883, 806, -1, 7125, 7111, 1883, -1, 7111, 1981, 1883, -1, 7111, 7113, 1981, -1, 7113, 890, 1981, -1, 1882, 7058, 828, -1, 828, 7058, 7057, -1, 1980, 7048, 1882, -1, 1882, 7048, 7058, -1, 934, 7049, 1980, -1, 1980, 7049, 7048, -1, 7066, 7065, 960, -1, 7065, 2332, 960, -1, 7065, 7051, 2332, -1, 7051, 2439, 2332, -1, 7051, 7053, 2439, -1, 7053, 1039, 2439, -1, 2424, 7034, 974, -1, 974, 7034, 7033, -1, 2543, 7024, 2424, -1, 2424, 7024, 7034, -1, 1070, 7025, 2543, -1, 2543, 7025, 7024, -1, 7042, 7041, 1093, -1, 7041, 2996, 1093, -1, 7041, 7026, 2996, -1, 7026, 3071, 2996, -1, 7026, 7029, 3071, -1, 7029, 1164, 3071, -1, 3059, 14416, 1122, -1, 1122, 14416, 14415, -1, 3105, 14412, 3059, -1, 3059, 14412, 14416, -1, 1204, 14413, 3105, -1, 3105, 14413, 14412, -1, 1445, 11002, 3233, -1, 11003, 11002, 1445, -1, 3233, 10999, 3243, -1, 11002, 10999, 3233, -1, 3243, 10998, 1556, -1, 10999, 10998, 3243, -1, 1563, 10973, 3242, -1, 3242, 10972, 3232, -1, 10973, 10972, 3242, -1, 3232, 10982, 1446, -1, 10972, 10982, 3232, -1, 10982, 10981, 1446, -1, 3276, 10989, 3300, -1, 10990, 10989, 3276, -1, 3300, 10975, 3309, -1, 10989, 10975, 3300, -1, 3309, 10977, 1689, -1, 10975, 10977, 3309, -1, 1713, 10949, 3307, -1, 3307, 10948, 3299, -1, 10949, 10948, 3307, -1, 3299, 10958, 3283, -1, 10948, 10958, 3299, -1, 10958, 10957, 3283, -1, 3343, 10965, 3363, -1, 10966, 10965, 3343, -1, 3363, 10951, 3375, -1, 10965, 10951, 3363, -1, 3375, 10953, 1810, -1, 10951, 10953, 3375, -1, 1836, 11033, 3374, -1, 3374, 11032, 3362, -1, 11033, 11032, 3374, -1, 3362, 11042, 3352, -1, 11032, 11042, 3362, -1, 11042, 11041, 3352, -1, 70, 11049, 121, -1, 11050, 11049, 70, -1, 121, 11035, 165, -1, 11049, 11035, 121, -1, 165, 11037, 214, -1, 11035, 11037, 165, -1, 258, 11009, 199, -1, 199, 11008, 161, -1, 11009, 11008, 199, -1, 161, 11018, 101, -1, 11008, 11018, 161, -1, 11018, 11017, 101, -1, 377, 11025, 375, -1, 11026, 11025, 377, -1, 375, 11010, 424, -1, 11025, 11010, 375, -1, 424, 11013, 489, -1, 11010, 11013, 424, -1, 578, 14965, 476, -1, 476, 14964, 416, -1, 14965, 14964, 476, -1, 416, 14968, 376, -1, 14964, 14968, 416, -1, 14968, 14967, 376, -1, 7251, 3198, 1375, -1, 7251, 7250, 3198, -1, 7250, 3209, 3198, -1, 7250, 7263, 3209, -1, 7263, 1472, 3209, -1, 7263, 7270, 1472, -1, 1486, 7301, 3218, -1, 7305, 7301, 1486, -1, 3218, 7298, 3207, -1, 7301, 7298, 3218, -1, 3207, 7297, 1388, -1, 7298, 7297, 3207, -1, 7313, 1545, 1518, -1, 7313, 7314, 1545, -1, 7314, 1581, 1545, -1, 7314, 7318, 1581, -1, 7318, 1614, 1581, -1, 7318, 7325, 1614, -1, 1635, 7280, 1582, -1, 7284, 7280, 1635, -1, 1582, 7271, 1546, -1, 7280, 7271, 1582, -1, 1546, 7273, 1542, -1, 7271, 7273, 1546, -1, 7275, 1668, 1644, -1, 7275, 7274, 1668, -1, 7274, 1728, 1668, -1, 7274, 7287, 1728, -1, 7287, 1749, 1728, -1, 7287, 7294, 1749, -1, 1765, 7335, 1729, -1, 7339, 7335, 1765, -1, 1729, 7332, 1669, -1, 7335, 7332, 1729, -1, 1669, 7331, 1666, -1, 7332, 7331, 1669, -1, 7347, 67, 1781, -1, 7347, 7348, 67, -1, 7348, 68, 67, -1, 7348, 7352, 68, -1, 7352, 113, 68, -1, 7352, 7359, 113, -1, 110, 14445, 65, -1, 14449, 14445, 110, -1, 65, 14438, 66, -1, 14445, 14438, 65, -1, 66, 14440, 1820, -1, 14438, 14440, 66, -1, 1192, 7370, 3148, -1, 7371, 7370, 1192, -1, 3148, 7367, 3157, -1, 7370, 7367, 3148, -1, 3157, 7366, 1272, -1, 7367, 7366, 3157, -1, 1310, 7449, 3156, -1, 3156, 7448, 3147, -1, 7449, 7448, 3156, -1, 3147, 7458, 1194, -1, 7448, 7458, 3147, -1, 7458, 7457, 1194, -1, 1369, 7465, 3204, -1, 7466, 7465, 1369, -1, 3204, 7451, 3211, -1, 7465, 7451, 3204, -1, 3211, 7453, 1431, -1, 7451, 7453, 3211, -1, 1466, 7425, 3210, -1, 3210, 7424, 3203, -1, 7425, 7424, 3210, -1, 3203, 7434, 1370, -1, 7424, 7434, 3203, -1, 7434, 7433, 1370, -1, 1506, 7441, 3250, -1, 7442, 7441, 1506, -1, 3250, 7427, 3261, -1, 7441, 7427, 3250, -1, 3261, 7429, 1576, -1, 7427, 7429, 3261, -1, 1590, 7401, 3269, -1, 3269, 7400, 3258, -1, 7401, 7400, 3269, -1, 3258, 7410, 1522, -1, 7400, 7410, 3258, -1, 7410, 7409, 1522, -1, 1637, 7417, 3314, -1, 7418, 7417, 1637, -1, 3314, 7403, 3322, -1, 7417, 7403, 3314, -1, 3322, 7405, 1722, -1, 7403, 7405, 3322, -1, 1752, 7377, 3331, -1, 3331, 7376, 3320, -1, 7377, 7376, 3331, -1, 3320, 7386, 1650, -1, 7376, 7386, 3320, -1, 7386, 7385, 1650, -1, 1778, 7393, 3386, -1, 7394, 7393, 1778, -1, 3386, 7378, 41, -1, 7393, 7378, 3386, -1, 41, 7381, 48, -1, 7378, 7381, 41, -1, 90, 14461, 39, -1, 39, 14460, 40, -1, 14461, 14460, 39, -1, 40, 14464, 1795, -1, 14460, 14464, 40, -1, 14464, 14463, 1795, -1, 7675, 3104, 1120, -1, 7675, 7674, 3104, -1, 7674, 3117, 3104, -1, 7674, 7687, 3117, -1, 7687, 1217, 3117, -1, 7687, 7694, 1217, -1, 1216, 7643, 3128, -1, 7647, 7643, 1216, -1, 3128, 7640, 3115, -1, 7643, 7640, 3128, -1, 3115, 7639, 1131, -1, 7640, 7639, 3115, -1, 7655, 1339, 1265, -1, 7655, 7656, 1339, -1, 7656, 1340, 1339, -1, 7656, 7660, 1340, -1, 7660, 1401, 1340, -1, 7660, 7667, 1401, -1, 1400, 7622, 1342, -1, 7626, 7622, 1400, -1, 1342, 7613, 1341, -1, 7622, 7613, 1342, -1, 1341, 7615, 1287, -1, 7613, 7615, 1341, -1, 7617, 1489, 1411, -1, 7617, 7616, 1489, -1, 7616, 1490, 1489, -1, 7616, 7629, 1490, -1, 7629, 1529, 1490, -1, 7629, 7636, 1529, -1, 1531, 7585, 1491, -1, 7589, 7585, 1531, -1, 1491, 7582, 1488, -1, 7585, 7582, 1491, -1, 1488, 7581, 1423, -1, 7582, 7581, 1488, -1, 7597, 3289, 1554, -1, 7597, 7598, 3289, -1, 7598, 3302, 3289, -1, 7598, 7602, 3302, -1, 7602, 1655, 3302, -1, 7602, 7609, 1655, -1, 1693, 14481, 3301, -1, 14485, 14481, 1693, -1, 3301, 14474, 3288, -1, 14481, 14474, 3301, -1, 3288, 14476, 1585, -1, 14474, 14476, 3288, -1, 7807, 137, 139, -1, 7806, 137, 7807, -1, 7819, 156, 7806, -1, 7806, 156, 137, -1, 7826, 182, 7819, -1, 7819, 182, 156, -1, 154, 7829, 138, -1, 175, 7830, 154, -1, 154, 7830, 7829, -1, 194, 7833, 175, -1, 175, 7833, 7830, -1, 194, 7837, 7833, -1, 7845, 520, 482, -1, 7846, 520, 7845, -1, 7850, 515, 7846, -1, 7846, 515, 520, -1, 7857, 354, 7850, -1, 7850, 354, 515, -1, 517, 7897, 493, -1, 516, 7895, 517, -1, 517, 7895, 7897, -1, 362, 7904, 516, -1, 516, 7904, 7895, -1, 362, 7908, 7904, -1, 7899, 584, 559, -1, 7898, 584, 7899, -1, 7911, 585, 7898, -1, 7898, 585, 584, -1, 7918, 620, 7911, -1, 7911, 620, 585, -1, 587, 7863, 566, -1, 586, 7864, 587, -1, 587, 7864, 7863, -1, 622, 7867, 586, -1, 586, 7867, 7864, -1, 622, 7871, 7867, -1, 7879, 1109, 637, -1, 7880, 1109, 7879, -1, 7884, 1249, 7880, -1, 7880, 1249, 1109, -1, 7891, 1374, 7884, -1, 7884, 1374, 1249, -1, 1108, 14508, 661, -1, 1248, 14506, 1108, -1, 1108, 14506, 14508, -1, 1373, 14513, 1248, -1, 1248, 14513, 14506, -1, 1373, 14517, 14513, -1, 60, 7718, 46, -1, 46, 7718, 7717, -1, 73, 7708, 60, -1, 60, 7708, 7718, -1, 83, 7709, 73, -1, 73, 7709, 7708, -1, 14501, 42, 14502, -1, 14498, 61, 14501, -1, 14501, 61, 42, -1, 14497, 74, 14498, -1, 14498, 74, 61, -1, 14497, 79, 74, -1, 144, 7742, 115, -1, 115, 7742, 7741, -1, 159, 7732, 144, -1, 144, 7732, 7742, -1, 189, 7733, 159, -1, 159, 7733, 7732, -1, 7726, 7725, 109, -1, 7725, 145, 109, -1, 7725, 7711, 145, -1, 7711, 160, 145, -1, 7711, 7713, 160, -1, 7713, 167, 160, -1, 270, 7790, 248, -1, 248, 7790, 7789, -1, 287, 7780, 270, -1, 270, 7780, 7790, -1, 312, 7781, 287, -1, 287, 7781, 7780, -1, 7750, 7749, 229, -1, 7749, 271, 229, -1, 7749, 7735, 271, -1, 7735, 277, 271, -1, 7735, 7737, 277, -1, 7737, 292, 277, -1, 439, 7766, 396, -1, 396, 7766, 7765, -1, 501, 7756, 439, -1, 439, 7756, 7766, -1, 604, 7757, 501, -1, 501, 7757, 7756, -1, 7798, 7797, 369, -1, 7797, 412, 369, -1, 7797, 7783, 412, -1, 7783, 445, 412, -1, 7783, 7785, 445, -1, 7785, 534, 445, -1, 1056, 7703, 936, -1, 936, 7703, 7702, -1, 1203, 7699, 1056, -1, 1056, 7699, 7703, -1, 1321, 7700, 1203, -1, 1203, 7700, 7699, -1, 7773, 829, 7774, -1, 7758, 945, 7773, -1, 7773, 945, 829, -1, 7761, 1073, 7758, -1, 7758, 1073, 945, -1, 7761, 1219, 1073, -1, 8043, 8042, 208, -1, 8042, 209, 208, -1, 8042, 8039, 209, -1, 8039, 241, 209, -1, 8039, 8038, 241, -1, 8038, 266, 241, -1, 207, 8058, 8057, -1, 206, 8058, 207, -1, 240, 8048, 206, -1, 206, 8048, 8058, -1, 265, 8049, 240, -1, 240, 8049, 8048, -1, 8066, 8065, 345, -1, 8065, 346, 345, -1, 8065, 8051, 346, -1, 8051, 394, 346, -1, 8051, 8053, 394, -1, 8053, 437, 394, -1, 347, 8082, 8081, -1, 344, 8082, 347, -1, 393, 8072, 344, -1, 344, 8072, 8082, -1, 436, 8073, 393, -1, 393, 8073, 8072, -1, 8090, 8089, 597, -1, 8089, 775, 597, -1, 8089, 8075, 775, -1, 8075, 882, 775, -1, 8075, 8077, 882, -1, 8077, 653, 882, -1, 611, 8130, 8129, -1, 774, 8130, 611, -1, 881, 8120, 774, -1, 774, 8120, 8130, -1, 670, 8121, 881, -1, 881, 8121, 8120, -1, 8138, 8137, 719, -1, 8137, 1408, 719, -1, 8137, 8123, 1408, -1, 8123, 1523, 1408, -1, 8123, 8125, 1523, -1, 8125, 784, 1523, -1, 729, 8106, 8105, -1, 1500, 8106, 729, -1, 1624, 8096, 1500, -1, 1500, 8096, 8106, -1, 818, 8097, 1624, -1, 1624, 8097, 8096, -1, 8114, 8113, 852, -1, 8113, 2026, 852, -1, 8113, 8098, 2026, -1, 8098, 2106, 2026, -1, 8098, 8101, 2106, -1, 8101, 948, 2106, -1, 877, 14552, 14551, -1, 2089, 14552, 877, -1, 2183, 14548, 2089, -1, 2089, 14548, 14552, -1, 978, 14549, 2183, -1, 2183, 14549, 14548, -1, 8014, 336, 8015, -1, 8015, 336, 338, -1, 8027, 389, 8014, -1, 8014, 389, 336, -1, 8034, 428, 8027, -1, 8027, 428, 389, -1, 383, 7945, 337, -1, 419, 7946, 383, -1, 383, 7946, 7945, -1, 463, 7949, 419, -1, 419, 7949, 7946, -1, 463, 7953, 7949, -1, 7962, 657, 7961, -1, 7961, 657, 608, -1, 7966, 658, 7962, -1, 7962, 658, 657, -1, 7973, 713, 7966, -1, 7966, 713, 658, -1, 656, 7921, 634, -1, 659, 7919, 656, -1, 656, 7919, 7921, -1, 715, 7928, 659, -1, 659, 7928, 7919, -1, 715, 7932, 7928, -1, 7922, 791, 7923, -1, 7923, 791, 722, -1, 7935, 792, 7922, -1, 7922, 792, 791, -1, 7942, 836, 7935, -1, 7935, 836, 792, -1, 790, 7979, 733, -1, 793, 7980, 790, -1, 790, 7980, 7979, -1, 835, 7983, 793, -1, 793, 7983, 7980, -1, 835, 7987, 7983, -1, 7996, 2125, 7995, -1, 7995, 2125, 856, -1, 8000, 2210, 7996, -1, 7996, 2210, 2125, -1, 8007, 986, 8000, -1, 8000, 986, 2210, -1, 2124, 14528, 903, -1, 2207, 14526, 2124, -1, 2124, 14526, 14528, -1, 1000, 14533, 2207, -1, 2207, 14533, 14526, -1, 1000, 14537, 14533, -1, 8238, 21434, 8239, -1, 8239, 21434, 21421, -1, 8251, 21447, 8238, -1, 8238, 21447, 21434, -1, 8258, 21457, 8251, -1, 8251, 21457, 21447, -1, 21433, 21444, 8203, -1, 21444, 8204, 8203, -1, 21444, 21456, 8204, -1, 21465, 8207, 21456, -1, 21456, 8207, 8204, -1, 21465, 8211, 8207, -1, 8220, 18436, 8219, -1, 8219, 18436, 18363, -1, 8224, 18434, 8220, -1, 8220, 18434, 18436, -1, 8231, 18494, 8224, -1, 8224, 18494, 18434, -1, 18401, 18435, 8179, -1, 18435, 8177, 8179, -1, 18435, 18459, 8177, -1, 18459, 8186, 8177, -1, 18459, 18510, 8186, -1, 18510, 8190, 8186, -1, 8180, 18591, 8181, -1, 8181, 18591, 18537, -1, 8193, 18592, 8180, -1, 8180, 18592, 18591, -1, 8200, 18607, 8193, -1, 8193, 18607, 18592, -1, 18565, 18593, 8145, -1, 18593, 8146, 8145, -1, 18593, 18590, 8146, -1, 18590, 8149, 8146, -1, 18590, 18610, 8149, -1, 18610, 8153, 8149, -1, 8162, 18672, 8161, -1, 8161, 18672, 18624, -1, 8166, 18685, 8162, -1, 8162, 18685, 18672, -1, 8173, 18694, 8166, -1, 8166, 18694, 18685, -1, 18649, 18671, 14556, -1, 18671, 14554, 14556, -1, 18671, 18684, 14554, -1, 18693, 14561, 18684, -1, 18684, 14561, 14554, -1, 18693, 14565, 14561, -1, 21381, 8294, 20904, -1, 20904, 8294, 8293, -1, 21390, 8284, 21381, -1, 21381, 8284, 8294, -1, 21005, 8285, 21390, -1, 21390, 8285, 8284, -1, 14581, 20903, 14582, -1, 14578, 21382, 14581, -1, 14581, 21382, 20903, -1, 14577, 21391, 14578, -1, 14578, 21391, 21382, -1, 14577, 21002, 21391, -1, 21438, 8270, 21425, -1, 21425, 8270, 8269, -1, 21448, 8260, 21438, -1, 21438, 8260, 8270, -1, 21113, 8261, 21448, -1, 21448, 8261, 8260, -1, 8301, 21418, 8302, -1, 8287, 21439, 8301, -1, 8301, 21439, 21418, -1, 8289, 21449, 8287, -1, 8287, 21449, 21439, -1, 8289, 21100, 21449, -1, 18415, 8318, 18367, -1, 18367, 8318, 8317, -1, 18441, 8308, 18415, -1, 18415, 8308, 8318, -1, 18474, 8309, 18441, -1, 18441, 8309, 8308, -1, 8277, 18369, 8278, -1, 8263, 18381, 8277, -1, 8277, 18381, 18369, -1, 8265, 18425, 8263, -1, 8263, 18425, 18381, -1, 8265, 18476, 18425, -1, 18574, 8342, 18541, -1, 18541, 8342, 8341, -1, 18584, 8332, 18574, -1, 18574, 8332, 8342, -1, 18600, 8333, 18584, -1, 18584, 8333, 8332, -1, 8325, 18517, 8326, -1, 8311, 18557, 8325, -1, 8325, 18557, 18517, -1, 8313, 18576, 8311, -1, 8311, 18576, 18557, -1, 8313, 18585, 18576, -1, 18664, 8363, 18639, -1, 18639, 8363, 8362, -1, 18674, 8359, 18664, -1, 18664, 8359, 8363, -1, 18689, 8360, 18674, -1, 18674, 8360, 8359, -1, 8349, 18640, 8350, -1, 8334, 18638, 8349, -1, 8349, 18638, 18640, -1, 8337, 18667, 8334, -1, 8334, 18667, 18638, -1, 8337, 18678, 18667, -1, 20856, 21354, 8369, -1, 21354, 8370, 8369, -1, 21354, 21365, 8370, -1, 21365, 8373, 8370, -1, 21365, 20938, 8373, -1, 20938, 8377, 8373, -1, 14589, 21341, 14590, -1, 14590, 21341, 20844, -1, 14602, 21355, 14589, -1, 14589, 21355, 21341, -1, 14609, 20925, 14602, -1, 14602, 20925, 21355, -1, 20989, 20988, 8403, -1, 20988, 8401, 8403, -1, 20988, 21023, 8401, -1, 21023, 8410, 8401, -1, 21023, 21060, 8410, -1, 21060, 8414, 8410, -1, 8386, 20991, 8385, -1, 8385, 20991, 20965, -1, 8390, 21024, 8386, -1, 8386, 21024, 20991, -1, 8397, 21043, 8390, -1, 8390, 21043, 21024, -1, 21082, 21086, 8427, -1, 21086, 8428, 8427, -1, 21086, 18378, 8428, -1, 18378, 8431, 8428, -1, 18378, 18375, 8431, -1, 18375, 8435, 8431, -1, 8404, 21085, 8405, -1, 8405, 21085, 21065, -1, 8417, 18376, 8404, -1, 8404, 18376, 21085, -1, 8424, 18377, 8417, -1, 8417, 18377, 18376, -1, 18500, 18495, 8461, -1, 18495, 8459, 8461, -1, 18495, 18512, 8459, -1, 18512, 8468, 8459, -1, 18512, 18549, 8468, -1, 18549, 8472, 8468, -1, 8444, 18497, 8443, -1, 8443, 18497, 18496, -1, 8448, 18513, 8444, -1, 8444, 18513, 18497, -1, 8455, 18550, 8448, -1, 8448, 18550, 18513, -1, 927, 9034, 928, -1, 9035, 9034, 927, -1, 928, 9031, 1032, -1, 9034, 9031, 928, -1, 1032, 9030, 1154, -1, 9031, 9030, 1032, -1, 9005, 1029, 1153, -1, 9005, 9004, 1029, -1, 9004, 926, 1029, -1, 9004, 9014, 926, -1, 9014, 930, 926, -1, 9014, 9013, 930, -1, 1662, 9021, 1663, -1, 9022, 9021, 1662, -1, 1663, 9007, 1786, -1, 9021, 9007, 1663, -1, 1786, 9009, 1889, -1, 9007, 9009, 1786, -1, 8981, 1785, 1888, -1, 8981, 8980, 1785, -1, 8980, 1661, 1785, -1, 8980, 8990, 1661, -1, 8990, 1671, 1661, -1, 8990, 8989, 1671, -1, 2132, 8997, 2130, -1, 8998, 8997, 2132, -1, 2130, 8983, 2213, -1, 8997, 8983, 2130, -1, 2213, 8985, 2259, -1, 8983, 8985, 2213, -1, 8957, 2287, 2283, -1, 8957, 8956, 2287, -1, 8956, 2193, 2287, -1, 8956, 8966, 2193, -1, 8966, 2131, 2193, -1, 8966, 8965, 2131, -1, 2319, 8973, 2778, -1, 8974, 8973, 2319, -1, 2778, 8959, 2886, -1, 8973, 8959, 2778, -1, 2886, 8961, 2400, -1, 8959, 8961, 2886, -1, 8933, 2982, 2422, -1, 8933, 8932, 2982, -1, 8932, 2872, 2982, -1, 8932, 8942, 2872, -1, 8942, 2330, 2872, -1, 8942, 8941, 2330, -1, 2448, 8949, 3133, -1, 8950, 8949, 2448, -1, 3133, 8934, 3142, -1, 8949, 8934, 3133, -1, 3142, 8937, 2520, -1, 8934, 8937, 3142, -1, 14673, 3151, 2551, -1, 14673, 14672, 3151, -1, 14672, 3141, 3151, -1, 14672, 14676, 3141, -1, 14676, 2474, 3141, -1, 14676, 14675, 2474, -1, 460, 8687, 458, -1, 458, 8686, 575, -1, 8687, 8686, 458, -1, 575, 8699, 716, -1, 8686, 8699, 575, -1, 8699, 8706, 716, -1, 819, 8655, 678, -1, 8659, 8655, 819, -1, 678, 8652, 560, -1, 8655, 8652, 678, -1, 560, 8651, 459, -1, 8652, 8651, 560, -1, 1183, 8667, 1181, -1, 1181, 8668, 1441, -1, 8667, 8668, 1181, -1, 1441, 8672, 1439, -1, 8668, 8672, 1441, -1, 8672, 8679, 1439, -1, 1549, 8634, 1440, -1, 8638, 8634, 1549, -1, 1440, 8625, 1267, -1, 8634, 8625, 1440, -1, 1267, 8627, 1182, -1, 8625, 8627, 1267, -1, 1958, 8629, 1965, -1, 1965, 8628, 2119, -1, 8629, 8628, 1965, -1, 2119, 8641, 2122, -1, 8628, 8641, 2119, -1, 8641, 8648, 2122, -1, 2117, 8597, 2118, -1, 8601, 8597, 2117, -1, 2118, 8594, 1956, -1, 8597, 8594, 2118, -1, 1956, 8593, 1957, -1, 8594, 8593, 1956, -1, 2231, 8609, 2503, -1, 2503, 8610, 2629, -1, 8609, 8610, 2503, -1, 2629, 8614, 2341, -1, 8610, 8614, 2629, -1, 8614, 8621, 2341, -1, 2361, 14629, 2628, -1, 14633, 14629, 2361, -1, 2628, 14622, 2502, -1, 14629, 14622, 2628, -1, 2502, 14624, 2273, -1, 14622, 14624, 2502, -1, 221, 8714, 223, -1, 8715, 8714, 221, -1, 223, 8711, 264, -1, 8714, 8711, 223, -1, 264, 8710, 291, -1, 8711, 8710, 264, -1, 8721, 263, 290, -1, 8721, 8720, 263, -1, 8720, 219, 263, -1, 8720, 8730, 219, -1, 8730, 220, 219, -1, 8730, 8729, 220, -1, 497, 8737, 498, -1, 8738, 8737, 497, -1, 498, 8723, 599, -1, 8737, 8723, 498, -1, 599, 8725, 744, -1, 8723, 8725, 599, -1, 8769, 598, 737, -1, 8769, 8768, 598, -1, 8768, 496, 598, -1, 8768, 8778, 496, -1, 8778, 500, 496, -1, 8778, 8777, 500, -1, 1188, 8785, 1189, -1, 8786, 8785, 1188, -1, 1189, 8771, 1326, -1, 8785, 8771, 1189, -1, 1326, 8773, 1468, -1, 8771, 8773, 1326, -1, 8745, 1325, 1467, -1, 8745, 8744, 1325, -1, 8744, 1187, 1325, -1, 8744, 8754, 1187, -1, 8754, 1193, 1187, -1, 8754, 8753, 1193, -1, 1831, 8761, 1829, -1, 8762, 8761, 1831, -1, 1829, 8747, 1915, -1, 8761, 8747, 1829, -1, 1915, 8749, 2016, -1, 8747, 8749, 1915, -1, 8793, 1991, 2072, -1, 8793, 8792, 1991, -1, 8792, 1897, 1991, -1, 8792, 8802, 1897, -1, 8802, 1830, 1897, -1, 8802, 8801, 1830, -1, 2228, 8809, 2345, -1, 8810, 8809, 2228, -1, 2345, 8794, 2478, -1, 8809, 8794, 2345, -1, 2478, 8797, 2306, -1, 8794, 8797, 2478, -1, 14645, 2586, 2335, -1, 14645, 14644, 2586, -1, 14644, 2459, 2586, -1, 14644, 14648, 2459, -1, 14648, 2246, 2459, -1, 14648, 14647, 2246, -1, 1856, 9774, 2025, -1, 9775, 9774, 1856, -1, 2025, 9771, 2085, -1, 9774, 9771, 2025, -1, 2085, 9770, 2096, -1, 9771, 9770, 2085, -1, 9745, 2082, 2171, -1, 9745, 9744, 2082, -1, 9744, 2023, 2082, -1, 9744, 9754, 2023, -1, 9754, 1928, 2023, -1, 9754, 9753, 1928, -1, 2388, 9761, 2608, -1, 9762, 9761, 2388, -1, 2608, 9747, 2727, -1, 9761, 9747, 2608, -1, 2727, 9749, 2378, -1, 9747, 9749, 2727, -1, 9721, 2726, 2380, -1, 9721, 9720, 2726, -1, 9720, 2607, 2726, -1, 9720, 9730, 2607, -1, 9730, 2475, 2607, -1, 9730, 9729, 2475, -1, 3051, 9737, 3103, -1, 9738, 9737, 3051, -1, 3103, 9723, 3114, -1, 9737, 9723, 3103, -1, 3114, 9725, 2498, -1, 9723, 9725, 3114, -1, 9805, 3121, 2504, -1, 9805, 9804, 3121, -1, 9804, 3112, 3121, -1, 9804, 9814, 3112, -1, 9814, 3098, 3112, -1, 9814, 9813, 3098, -1, 3158, 9821, 3167, -1, 9822, 9821, 3158, -1, 3167, 9807, 3177, -1, 9821, 9807, 3167, -1, 3177, 9809, 2631, -1, 9807, 9809, 3177, -1, 9781, 3186, 2652, -1, 9781, 9780, 3186, -1, 9780, 3175, 3186, -1, 9780, 9790, 3175, -1, 9790, 3166, 3175, -1, 9790, 9789, 3166, -1, 3214, 9797, 3225, -1, 9798, 9797, 3214, -1, 3225, 9782, 3231, -1, 9797, 9782, 3225, -1, 3231, 9785, 2758, -1, 9782, 9785, 3231, -1, 14785, 3244, 2794, -1, 14785, 14784, 3244, -1, 14784, 3230, 3244, -1, 14784, 14788, 3230, -1, 14788, 3222, 3230, -1, 14788, 14787, 3222, -1, 1497, 8853, 1623, -1, 1623, 8852, 1757, -1, 8853, 8852, 1623, -1, 1757, 8865, 1871, -1, 8852, 8865, 1757, -1, 8865, 8872, 1871, -1, 1937, 8903, 1849, -1, 8907, 8903, 1937, -1, 1849, 8900, 1741, -1, 8903, 8900, 1849, -1, 1741, 8899, 1613, -1, 8900, 8899, 1741, -1, 2103, 8915, 2225, -1, 2225, 8916, 2265, -1, 8915, 8916, 2225, -1, 2265, 8920, 2263, -1, 8916, 8920, 2265, -1, 8920, 8927, 2263, -1, 2264, 8882, 2266, -1, 8886, 8882, 2264, -1, 2266, 8873, 2226, -1, 8882, 8873, 2266, -1, 2226, 8875, 2158, -1, 8873, 8875, 2226, -1, 2311, 8877, 2351, -1, 2351, 8876, 2404, -1, 8877, 8876, 2351, -1, 2404, 8889, 2402, -1, 8876, 8889, 2404, -1, 8889, 8896, 2402, -1, 2403, 8821, 2405, -1, 8825, 8821, 2403, -1, 2405, 8818, 2352, -1, 8821, 8818, 2405, -1, 2352, 8817, 2350, -1, 8818, 8817, 2352, -1, 2450, 8833, 3146, -1, 3146, 8834, 3155, -1, 8833, 8834, 3146, -1, 3155, 8838, 2537, -1, 8834, 8838, 3155, -1, 8838, 8845, 2537, -1, 2572, 14657, 3154, -1, 14661, 14657, 2572, -1, 3154, 14650, 3145, -1, 14657, 14650, 3154, -1, 3145, 14652, 2516, -1, 14650, 14652, 3145, -1, 28, 9077, 26, -1, 26, 9076, 89, -1, 9077, 9076, 26, -1, 89, 9089, 153, -1, 9076, 9089, 89, -1, 9089, 9096, 153, -1, 187, 9045, 133, -1, 9049, 9045, 187, -1, 133, 9042, 84, -1, 9045, 9042, 133, -1, 84, 9041, 27, -1, 9042, 9041, 84, -1, 1896, 9057, 1944, -1, 1944, 9058, 1945, -1, 9057, 9058, 1944, -1, 1945, 9062, 511, -1, 9058, 9062, 1945, -1, 9062, 9069, 511, -1, 519, 9140, 1946, -1, 9144, 9140, 519, -1, 1946, 9131, 1947, -1, 9140, 9131, 1946, -1, 1947, 9133, 1918, -1, 9131, 9133, 1947, -1, 1997, 9135, 2038, -1, 2038, 9134, 2039, -1, 9135, 9134, 2038, -1, 2039, 9147, 1210, -1, 9134, 9147, 2039, -1, 9147, 9154, 1210, -1, 1227, 9103, 2040, -1, 9107, 9103, 1227, -1, 2040, 9100, 2037, -1, 9103, 9100, 2040, -1, 2037, 9099, 2006, -1, 9100, 9099, 2037, -1, 1559, 9115, 1560, -1, 1560, 9116, 1696, -1, 9115, 9116, 1560, -1, 1696, 9120, 1807, -1, 9116, 9120, 1696, -1, 9120, 9127, 1807, -1, 1806, 14685, 1695, -1, 14689, 14685, 1806, -1, 1695, 14678, 1558, -1, 14685, 14678, 1695, -1, 1558, 14680, 1562, -1, 14678, 14680, 1558, -1, 10536, 18413, 10537, -1, 10537, 18413, 18421, -1, 10546, 18404, 10536, -1, 10536, 18404, 18413, -1, 10545, 18389, 10546, -1, 10546, 18389, 18404, -1, 18414, 14893, 18417, -1, 18405, 14894, 18414, -1, 18414, 14894, 14893, -1, 18385, 14897, 18405, -1, 18405, 14897, 14894, -1, 18385, 14898, 14897, -1, 10560, 18479, 10561, -1, 10561, 18479, 18503, -1, 10570, 18468, 10560, -1, 10560, 18468, 18479, -1, 10569, 18448, 10570, -1, 10570, 18448, 18468, -1, 18488, 18480, 10541, -1, 18480, 10539, 10541, -1, 18480, 18469, 10539, -1, 18469, 10553, 10539, -1, 18469, 18443, 10553, -1, 18443, 10554, 10553, -1, 10584, 18586, 10585, -1, 10585, 18586, 18608, -1, 10594, 18575, 10584, -1, 10584, 18575, 18586, -1, 10593, 18556, 10594, -1, 10594, 18556, 18575, -1, 18594, 18581, 10565, -1, 18581, 10563, 10565, -1, 18581, 18560, 10563, -1, 18560, 10577, 10563, -1, 18560, 18538, 10577, -1, 18538, 10578, 10577, -1, 10512, 18767, 10513, -1, 10513, 18767, 18865, -1, 10522, 18709, 10512, -1, 10512, 18709, 18767, -1, 10521, 18679, 10522, -1, 10522, 18679, 18709, -1, 18796, 18712, 10589, -1, 18712, 10587, 10589, -1, 18712, 18690, 10587, -1, 18690, 10601, 10587, -1, 18690, 18652, 10601, -1, 18652, 10602, 10601, -1, 10503, 19429, 10504, -1, 10504, 19429, 19537, -1, 10507, 19289, 10503, -1, 10503, 19289, 19429, -1, 10506, 19179, 10507, -1, 10507, 19179, 19289, -1, 19303, 10517, 19443, -1, 19184, 10514, 19303, -1, 19303, 10514, 10517, -1, 19075, 10529, 19184, -1, 19184, 10529, 10514, -1, 19075, 10530, 10529, -1, 3373, 9263, 9270, -1, 3359, 9263, 3373, -1, 3346, 9250, 3359, -1, 3359, 9250, 9263, -1, 3332, 9251, 3346, -1, 3346, 9251, 9250, -1, 9185, 3385, 9189, -1, 9185, 3369, 3385, -1, 9185, 9182, 3369, -1, 9182, 3356, 3369, -1, 9182, 9181, 3356, -1, 9181, 3345, 3356, -1, 180, 9202, 9209, -1, 106, 9202, 180, -1, 108, 9198, 106, -1, 106, 9198, 9202, -1, 10, 9197, 108, -1, 108, 9197, 9198, -1, 9168, 9164, 201, -1, 9164, 141, 201, -1, 9164, 9155, 141, -1, 9155, 107, 141, -1, 9155, 9157, 107, -1, 9157, 62, 107, -1, 314, 9171, 9178, -1, 296, 9171, 314, -1, 295, 9158, 296, -1, 296, 9158, 9171, -1, 230, 9159, 295, -1, 295, 9159, 9158, -1, 9223, 9219, 317, -1, 9219, 293, 317, -1, 9219, 9216, 293, -1, 9216, 294, 293, -1, 9216, 9215, 294, -1, 9215, 259, 294, -1, 422, 9236, 9243, -1, 406, 9236, 422, -1, 391, 9232, 406, -1, 406, 9232, 9236, -1, 339, 9231, 391, -1, 391, 9231, 9232, -1, 14713, 418, 14717, -1, 14713, 405, 418, -1, 14713, 14706, 405, -1, 14706, 390, 405, -1, 14706, 14708, 390, -1, 14708, 363, 390, -1, 3297, 9274, 2866, -1, 3286, 9275, 3297, -1, 3297, 9275, 9274, -1, 2763, 9278, 3286, -1, 3286, 9278, 9275, -1, 2763, 9279, 9278, -1, 9285, 3296, 2868, -1, 9284, 3296, 9285, -1, 9294, 3285, 9284, -1, 9284, 3285, 3296, -1, 9293, 2765, 9294, -1, 9294, 2765, 3285, -1, 3361, 9289, 2967, -1, 3351, 9287, 3361, -1, 3361, 9287, 9289, -1, 3329, 9301, 3351, -1, 3351, 9301, 9287, -1, 3329, 9302, 9301, -1, 9309, 3360, 2984, -1, 9308, 3360, 9309, -1, 9318, 3350, 9308, -1, 9308, 3350, 3360, -1, 9317, 3336, 9318, -1, 9318, 3336, 3350, -1, 112, 9313, 120, -1, 77, 9311, 112, -1, 112, 9311, 9313, -1, 25, 9325, 77, -1, 77, 9325, 9311, -1, 25, 9326, 9325, -1, 9357, 111, 155, -1, 9356, 111, 9357, -1, 9366, 76, 9356, -1, 9356, 76, 111, -1, 9365, 23, 9366, -1, 9366, 23, 76, -1, 276, 9361, 288, -1, 252, 9359, 276, -1, 276, 9359, 9361, -1, 210, 9373, 252, -1, 252, 9373, 9359, -1, 210, 9374, 9373, -1, 9333, 285, 306, -1, 9332, 285, 9333, -1, 9342, 269, 9332, -1, 9332, 269, 285, -1, 9341, 235, 9342, -1, 9342, 235, 269, -1, 385, 9337, 402, -1, 355, 9334, 385, -1, 385, 9334, 9337, -1, 357, 9349, 355, -1, 355, 9349, 9334, -1, 357, 9350, 9349, -1, 14729, 395, 411, -1, 14728, 395, 14729, -1, 14732, 384, 14728, -1, 14728, 384, 395, -1, 14731, 356, 14732, -1, 14732, 356, 384, -1, 2789, 9395, 9402, -1, 3253, 9395, 2789, -1, 3239, 9382, 3253, -1, 3253, 9382, 9395, -1, 2704, 9383, 3239, -1, 3239, 9383, 9382, -1, 9413, 9409, 2804, -1, 9409, 3264, 2804, -1, 9409, 9406, 3264, -1, 9406, 3252, 3264, -1, 9406, 9405, 3252, -1, 9405, 2715, 3252, -1, 2910, 9426, 9433, -1, 2888, 9426, 2910, -1, 2854, 9422, 2888, -1, 2888, 9422, 9426, -1, 2832, 9421, 2854, -1, 2854, 9421, 9422, -1, 9484, 9480, 2928, -1, 9480, 2889, 2928, -1, 9480, 9471, 2889, -1, 9471, 2855, 2889, -1, 9471, 9473, 2855, -1, 9473, 2858, 2855, -1, 33, 9487, 9494, -1, 32, 9487, 33, -1, 2953, 9474, 32, -1, 32, 9474, 9487, -1, 2935, 9475, 2953, -1, 2953, 9475, 9474, -1, 9447, 9443, 31, -1, 9443, 34, 31, -1, 9443, 9440, 34, -1, 9440, 2951, 34, -1, 9440, 9439, 2951, -1, 9439, 2952, 2951, -1, 243, 9460, 9467, -1, 204, 9460, 243, -1, 185, 9456, 204, -1, 204, 9456, 9460, -1, 184, 9455, 185, -1, 185, 9455, 9456, -1, 14745, 14741, 242, -1, 14741, 203, 242, -1, 14741, 14734, 203, -1, 14734, 183, 203, -1, 14734, 14736, 183, -1, 14736, 188, 183, -1, 3197, 9522, 2611, -1, 3188, 9523, 3197, -1, 3197, 9523, 9522, -1, 2542, 9526, 3188, -1, 3188, 9526, 9523, -1, 2542, 9527, 9526, -1, 9533, 3196, 2642, -1, 9532, 3196, 9533, -1, 9542, 3187, 9532, -1, 9532, 3187, 3196, -1, 9541, 2544, 9542, -1, 9542, 2544, 3187, -1, 3257, 9537, 2752, -1, 3247, 9535, 3257, -1, 3257, 9535, 9537, -1, 2701, 9549, 3247, -1, 3247, 9549, 9535, -1, 2701, 9550, 9549, -1, 9581, 3256, 2783, -1, 9580, 3256, 9581, -1, 9590, 3246, 9580, -1, 9580, 3246, 3256, -1, 9589, 2702, 9590, -1, 9590, 2702, 3246, -1, 3313, 9585, 2882, -1, 3303, 9583, 3313, -1, 3313, 9583, 9585, -1, 2819, 9597, 3303, -1, 3303, 9597, 9583, -1, 2819, 9598, 9597, -1, 9557, 3319, 2912, -1, 9556, 3319, 9557, -1, 9566, 3312, 9556, -1, 9556, 3312, 3319, -1, 9565, 2835, 9566, -1, 9566, 2835, 3312, -1, 3380, 9561, 2989, -1, 3365, 9559, 3380, -1, 3380, 9559, 9561, -1, 2930, 9573, 3365, -1, 3365, 9573, 9559, -1, 2930, 9574, 9573, -1, 9497, 3390, 3006, -1, 9496, 3390, 9497, -1, 9506, 3377, 9496, -1, 9496, 3377, 3390, -1, 9505, 2942, 9506, -1, 9506, 2942, 3377, -1, 170, 9501, 198, -1, 134, 9498, 170, -1, 170, 9498, 9501, -1, 136, 9513, 134, -1, 134, 9513, 9498, -1, 136, 9514, 9513, -1, 14757, 195, 228, -1, 14756, 195, 14757, -1, 14760, 169, 14756, -1, 14756, 169, 195, -1, 14759, 135, 14760, -1, 14760, 135, 169, -1, 3081, 9970, 2393, -1, 3020, 9971, 3081, -1, 3081, 9971, 9970, -1, 2322, 9974, 3020, -1, 3020, 9974, 9971, -1, 2322, 9975, 9974, -1, 9944, 3080, 9945, -1, 9945, 3080, 2442, -1, 9954, 3018, 9944, -1, 9944, 3018, 3080, -1, 9953, 2323, 9954, -1, 9954, 2323, 3018, -1, 3165, 9949, 2532, -1, 3153, 9947, 3165, -1, 3165, 9947, 9949, -1, 2465, 9961, 3153, -1, 3153, 9961, 9947, -1, 2465, 9962, 9961, -1, 9980, 3164, 9981, -1, 9981, 3164, 2580, -1, 9990, 3152, 9980, -1, 9980, 3152, 3164, -1, 9989, 2467, 9990, -1, 9990, 2467, 3152, -1, 3220, 9985, 2659, -1, 3202, 9983, 3220, -1, 3220, 9983, 9985, -1, 2582, 9997, 3202, -1, 3202, 9997, 9983, -1, 2582, 9998, 9997, -1, 10004, 3219, 10005, -1, 10005, 3219, 2718, -1, 10014, 3208, 10004, -1, 10004, 3208, 3219, -1, 10013, 2606, 10014, -1, 10014, 2606, 3208, -1, 3271, 10009, 2800, -1, 3262, 10007, 3271, -1, 3271, 10007, 10009, -1, 2733, 10021, 3262, -1, 3262, 10021, 10007, -1, 2733, 10022, 10021, -1, 10028, 3278, 10029, -1, 10029, 3278, 2847, -1, 10038, 3270, 10028, -1, 10028, 3270, 3278, -1, 10037, 2740, 10038, -1, 10038, 2740, 3270, -1, 3339, 10033, 2915, -1, 3325, 10030, 3339, -1, 3339, 10030, 10033, -1, 2861, 10045, 3325, -1, 3325, 10045, 10030, -1, 2861, 10046, 10045, -1, 14812, 3349, 14813, -1, 14813, 3349, 2965, -1, 14816, 3335, 14812, -1, 14812, 3335, 3349, -1, 14815, 2875, 14816, -1, 14816, 2875, 3335, -1, 2836, 9619, 9626, -1, 2695, 9619, 2836, -1, 2569, 9606, 2695, -1, 2695, 9606, 9619, -1, 2244, 9607, 2569, -1, 2569, 9607, 9606, -1, 9637, 9633, 2916, -1, 9633, 2801, 2916, -1, 9633, 9630, 2801, -1, 9630, 2673, 2801, -1, 2673, 9629, 2253, -1, 9630, 9629, 2673, -1, 2491, 9650, 9657, -1, 2490, 9650, 2491, -1, 2437, 9646, 2490, -1, 2490, 9646, 9650, -1, 2411, 9645, 2437, -1, 2437, 9645, 9646, -1, 9674, 9670, 2492, -1, 9670, 2489, 2492, -1, 9670, 9661, 2489, -1, 9661, 2438, 2489, -1, 9661, 9663, 2438, -1, 9663, 2412, 2438, -1, 2617, 9677, 9684, -1, 2619, 9677, 2617, -1, 2563, 9664, 2619, -1, 2619, 9664, 9677, -1, 2522, 9665, 2563, -1, 2563, 9665, 9664, -1, 9695, 9691, 2618, -1, 9691, 2620, 2618, -1, 9691, 9688, 2620, -1, 9688, 2564, 2620, -1, 2564, 9687, 2523, -1, 9688, 9687, 2564, -1, 3260, 9708, 9715, -1, 3249, 9708, 3260, -1, 3235, 9704, 3249, -1, 3249, 9704, 9708, -1, 2639, 9703, 3235, -1, 3235, 9703, 9704, -1, 14773, 14769, 3259, -1, 14769, 3248, 3259, -1, 14769, 14762, 3248, -1, 14762, 3234, 3248, -1, 3234, 14764, 2677, -1, 14762, 14764, 3234, -1, 2557, 9935, 9942, -1, 3162, 9935, 2557, -1, 3150, 9922, 3162, -1, 3162, 9922, 9935, -1, 2469, 9923, 3150, -1, 3150, 9923, 9922, -1, 9895, 9891, 2561, -1, 9891, 3171, 2561, -1, 9891, 9888, 3171, -1, 9888, 3160, 3171, -1, 9888, 9887, 3160, -1, 9887, 2484, 3160, -1, 2728, 9908, 9915, -1, 2670, 9908, 2728, -1, 2669, 9904, 2670, -1, 2670, 9904, 9908, -1, 2603, 9903, 2669, -1, 2669, 9903, 9904, -1, 9874, 9870, 2725, -1, 9870, 2671, 2725, -1, 9870, 9861, 2671, -1, 9861, 2672, 2671, -1, 9861, 9863, 2672, -1, 9863, 2627, 2672, -1, 2844, 9877, 9884, -1, 2808, 9877, 2844, -1, 2807, 9864, 2808, -1, 2808, 9864, 9877, -1, 2736, 9865, 2807, -1, 2807, 9865, 9864, -1, 9837, 9833, 2845, -1, 9833, 2809, 2845, -1, 9833, 9830, 2809, -1, 9830, 2806, 2809, -1, 9830, 9829, 2806, -1, 9829, 2745, 2806, -1, 2948, 9850, 9857, -1, 3354, 9850, 2948, -1, 3342, 9846, 3354, -1, 3354, 9846, 9850, -1, 2863, 9845, 3342, -1, 3342, 9845, 9846, -1, 14801, 14797, 2973, -1, 14797, 3353, 2973, -1, 14797, 14790, 3353, -1, 14790, 3341, 3353, -1, 14790, 14792, 3341, -1, 14792, 2891, 3341, -1, 10476, 19966, 10477, -1, 10477, 19966, 19100, -1, 10486, 19872, 10476, -1, 10476, 19872, 19966, -1, 10485, 19754, 10486, -1, 10486, 19754, 19872, -1, 19101, 19967, 14881, -1, 19967, 14882, 14881, -1, 19967, 19876, 14882, -1, 19876, 14885, 14882, -1, 19876, 19649, 14885, -1, 19649, 14886, 14885, -1, 10452, 20450, 10453, -1, 10453, 20450, 19252, -1, 10462, 20364, 10452, -1, 10452, 20364, 20450, -1, 10461, 20273, 10462, -1, 10462, 20273, 20364, -1, 19251, 20451, 10481, -1, 20451, 10479, 10481, -1, 20451, 20365, 10479, -1, 20365, 10493, 10479, -1, 20365, 20226, 10493, -1, 20226, 10494, 10493, -1, 10428, 21062, 10429, -1, 10429, 21062, 19375, -1, 10438, 20958, 10428, -1, 10428, 20958, 21062, -1, 10437, 20852, 10438, -1, 10438, 20852, 20958, -1, 19362, 20990, 10457, -1, 20990, 10455, 10457, -1, 20990, 20877, 10455, -1, 20877, 10469, 10455, -1, 20877, 20788, 10469, -1, 20788, 10470, 10469, -1, 10404, 21260, 10405, -1, 10405, 21260, 19533, -1, 10414, 21253, 10404, -1, 10404, 21253, 21260, -1, 10413, 21243, 10414, -1, 10414, 21243, 21253, -1, 19515, 21254, 10433, -1, 21254, 10431, 10433, -1, 21254, 21247, 10431, -1, 21247, 10445, 10431, -1, 21247, 21234, 10445, -1, 21234, 10446, 10445, -1, 10395, 21309, 10396, -1, 10396, 21309, 19677, -1, 10399, 21299, 10395, -1, 10395, 21299, 21309, -1, 10398, 21292, 10399, -1, 10399, 21292, 21299, -1, 19644, 21300, 10409, -1, 21300, 10406, 10409, -1, 21300, 21293, 10406, -1, 21293, 10421, 10406, -1, 21293, 21286, 10421, -1, 21286, 10422, 10421, -1, 10139, 19030, 10143, -1, 10136, 19634, 10139, -1, 10139, 19634, 19030, -1, 10135, 19514, 10136, -1, 10136, 19514, 19634, -1, 10135, 18992, 19514, -1, 19019, 14834, 14841, -1, 19530, 14834, 19019, -1, 19403, 14821, 19530, -1, 19530, 14821, 14834, -1, 18937, 14822, 19403, -1, 19403, 14822, 14821, -1, 10118, 19137, 10122, -1, 10109, 19138, 10118, -1, 10118, 19138, 19137, -1, 10111, 19090, 10109, -1, 10109, 19090, 19138, -1, 10111, 19091, 19090, -1, 19139, 10156, 10163, -1, 19136, 10156, 19139, -1, 19092, 10152, 19136, -1, 19136, 10152, 10156, -1, 19038, 10151, 19092, -1, 19092, 10151, 10152, -1, 10081, 19272, 10085, -1, 10078, 19273, 10081, -1, 10081, 19273, 19272, -1, 10077, 19224, 10078, -1, 10078, 19224, 19273, -1, 10077, 19225, 19224, -1, 19277, 10125, 10132, -1, 19274, 10125, 19277, -1, 19226, 10112, 19274, -1, 19274, 10112, 10125, -1, 19186, 10113, 19226, -1, 19226, 10113, 10112, -1, 10060, 19452, 10064, -1, 10051, 21232, 10060, -1, 10060, 21232, 19452, -1, 10053, 21212, 10051, -1, 10051, 21212, 21232, -1, 10053, 19380, 21212, -1, 19406, 10098, 10105, -1, 21233, 10098, 19406, -1, 21213, 10094, 21233, -1, 21233, 10094, 10098, -1, 19323, 10093, 21213, -1, 21213, 10093, 10094, -1, 10229, 18886, 18898, -1, 10228, 18886, 10229, -1, 10238, 18804, 10228, -1, 10228, 18804, 18886, -1, 10237, 18805, 10238, -1, 10238, 18805, 18804, -1, 18873, 18890, 14845, -1, 18890, 14846, 14845, -1, 18890, 18811, 14846, -1, 18811, 14849, 14846, -1, 18811, 18806, 14849, -1, 18806, 14850, 14849, -1, 10253, 19560, 19016, -1, 10252, 19560, 10253, -1, 10262, 19447, 10252, -1, 10252, 19447, 19560, -1, 10261, 18930, 10262, -1, 10262, 18930, 19447, -1, 18995, 19565, 10233, -1, 19565, 10231, 10233, -1, 19565, 19453, 10231, -1, 19453, 10245, 10231, -1, 19453, 18929, 10245, -1, 18929, 10246, 10245, -1, 10193, 20166, 19174, -1, 10192, 20166, 10193, -1, 10202, 20073, 10192, -1, 10192, 20073, 20166, -1, 10201, 19069, 10202, -1, 10202, 19069, 20073, -1, 19132, 20103, 10257, -1, 20103, 10255, 10257, -1, 20103, 20018, 10255, -1, 20018, 10269, 10255, -1, 20018, 19050, 10269, -1, 19050, 10270, 10269, -1, 10169, 20695, 19298, -1, 10168, 20695, 10169, -1, 10178, 20581, 10168, -1, 10168, 20581, 20695, -1, 10177, 19209, 10178, -1, 10178, 19209, 20581, -1, 19270, 20595, 10197, -1, 20595, 10195, 10197, -1, 20595, 20497, 10195, -1, 20497, 10209, 10195, -1, 20497, 19197, 10209, -1, 19197, 10210, 10209, -1, 10220, 21228, 19423, -1, 10219, 21228, 10220, -1, 10223, 21186, 10219, -1, 10219, 21186, 21228, -1, 10222, 19342, 10223, -1, 10223, 19342, 21186, -1, 19383, 21196, 10173, -1, 21196, 10170, 10173, -1, 21196, 21125, 10170, -1, 21125, 10185, 10170, -1, 21125, 19320, 10185, -1, 19320, 10186, 10185, -1, 10277, 20410, 10278, -1, 19127, 20410, 10277, -1, 10278, 20515, 10281, -1, 20410, 20515, 10278, -1, 10281, 20631, 10285, -1, 20515, 20631, 10281, -1, 20547, 14870, 14877, -1, 20547, 20423, 14870, -1, 20423, 14857, 14870, -1, 20423, 20340, 14857, -1, 19114, 14858, 20340, -1, 20340, 14858, 14857, -1, 10345, 19312, 10343, -1, 19290, 19312, 10345, -1, 10343, 19356, 10352, -1, 19312, 19356, 10343, -1, 10352, 19357, 10356, -1, 19356, 19357, 10352, -1, 19355, 10298, 10305, -1, 19355, 19354, 10298, -1, 19354, 10294, 10298, -1, 19354, 19311, 10294, -1, 19311, 10293, 10294, -1, 19311, 19288, 10293, -1, 10311, 19441, 10312, -1, 19390, 19441, 10311, -1, 10312, 19498, 10315, -1, 19441, 19498, 10312, -1, 10315, 19497, 10319, -1, 19498, 19497, 10315, -1, 19496, 10359, 10366, -1, 19496, 19495, 10359, -1, 19495, 10346, 10359, -1, 19495, 19440, 10346, -1, 19389, 10347, 19440, -1, 19440, 10347, 10346, -1, 10369, 21301, 10367, -1, 19561, 21301, 10369, -1, 10367, 21312, 10376, -1, 21301, 21312, 10367, -1, 10376, 21321, 10380, -1, 21312, 21321, 10376, -1, 21322, 10332, 10339, -1, 21322, 21313, 10332, -1, 21313, 10328, 10332, -1, 21313, 21302, 10328, -1, 19521, 10327, 21302, -1, 21302, 10327, 10328, -1, 10613, 18506, 10617, -1, 10610, 18493, 10613, -1, 10613, 18493, 18506, -1, 10609, 18475, 10610, -1, 10610, 18475, 18493, -1, 10609, 18462, 18475, -1, 18477, 14918, 18501, -1, 18501, 14918, 14925, -1, 18461, 14905, 18477, -1, 18477, 14905, 14918, -1, 18463, 14906, 18461, -1, 18461, 14906, 14905, -1, 10650, 18648, 10654, -1, 10641, 18776, 10650, -1, 10650, 18776, 18648, -1, 10643, 18777, 10641, -1, 10641, 18777, 18776, -1, 10643, 18750, 18777, -1, 18781, 10630, 18642, -1, 18642, 10630, 10637, -1, 18780, 10626, 18781, -1, 18781, 10626, 10630, -1, 18744, 10625, 18780, -1, 18780, 10625, 10626, -1, 10671, 18877, 10675, -1, 10668, 18843, 10671, -1, 10671, 18843, 18877, -1, 10667, 18844, 10668, -1, 10668, 18844, 18843, -1, 10667, 18825, 18844, -1, 18842, 10657, 18878, -1, 18878, 10657, 10664, -1, 18845, 10644, 18842, -1, 18842, 10644, 10657, -1, 18816, 10645, 18845, -1, 18845, 10645, 10644, -1, 10708, 19586, 10712, -1, 10699, 19472, 10708, -1, 10708, 19472, 19586, -1, 10701, 19336, 10699, -1, 10699, 19336, 19472, -1, 10701, 18917, 19336, -1, 19474, 10688, 19587, -1, 19587, 10688, 10695, -1, 19337, 10684, 19474, -1, 19474, 10684, 10688, -1, 18895, 10683, 19337, -1, 19337, 10683, 10684, -1, 10864, 18546, 10865, -1, 10865, 18546, 18571, -1, 10874, 18514, 10864, -1, 10864, 18514, 18546, -1, 10873, 18515, 10874, -1, 10874, 18515, 18514, -1, 18572, 18548, 14953, -1, 18548, 14954, 14953, -1, 18548, 18520, 14954, -1, 18520, 14957, 14954, -1, 18520, 18516, 14957, -1, 18516, 14958, 14957, -1, 10840, 18675, 10841, -1, 10841, 18675, 18706, -1, 10850, 18632, 10840, -1, 10840, 18632, 18675, -1, 10849, 18633, 10850, -1, 10850, 18633, 18632, -1, 18707, 18676, 10869, -1, 18676, 10867, 10869, -1, 18676, 18637, 10867, -1, 18637, 10881, 10867, -1, 18637, 18634, 10881, -1, 18634, 10882, 10881, -1, 10888, 19125, 10889, -1, 10889, 19125, 18943, -1, 10898, 19027, 10888, -1, 10888, 19027, 19125, -1, 10897, 18867, 10898, -1, 10898, 18867, 19027, -1, 18909, 19052, 10845, -1, 19052, 10843, 10845, -1, 19052, 18942, 10843, -1, 18942, 10857, 10843, -1, 18942, 18854, 10857, -1, 18854, 10858, 10857, -1, 10912, 19825, 10913, -1, 10913, 19825, 19063, -1, 10922, 19706, 10912, -1, 10912, 19706, 19825, -1, 10921, 18978, 10922, -1, 10922, 18978, 19706, -1, 19026, 19725, 10893, -1, 19725, 10891, 10893, -1, 19725, 19617, 10891, -1, 19617, 10905, 10891, -1, 19617, 18967, 10905, -1, 18967, 10906, 10905, -1, 10939, 20351, 10940, -1, 10940, 20351, 19215, -1, 10943, 20266, 10939, -1, 10939, 20266, 20351, -1, 10942, 19118, 10943, -1, 10943, 19118, 20266, -1, 19182, 20284, 10917, -1, 20284, 10914, 10917, -1, 20284, 20205, 10914, -1, 20205, 10929, 10914, -1, 20205, 19094, 10929, -1, 19094, 10930, 10929, -1, 10753, 18726, 10757, -1, 10750, 18695, 10753, -1, 10753, 18695, 18726, -1, 10749, 18666, 10750, -1, 10750, 18666, 18695, -1, 10749, 18628, 18666, -1, 18703, 14942, 14949, -1, 18673, 14942, 18703, -1, 18627, 14929, 18673, -1, 18673, 14929, 14942, -1, 18629, 14930, 18627, -1, 18627, 14930, 14929, -1, 10732, 18961, 10736, -1, 10723, 18913, 10732, -1, 10732, 18913, 18961, -1, 10725, 18915, 10723, -1, 10723, 18915, 18913, -1, 10725, 18889, 18915, -1, 18962, 10770, 10777, -1, 18912, 10770, 18962, -1, 18914, 10766, 18912, -1, 18912, 10766, 10770, -1, 18862, 10765, 18914, -1, 18914, 10765, 10766, -1, 10811, 19082, 10815, -1, 10808, 19035, 10811, -1, 10811, 19035, 19082, -1, 10807, 19036, 10808, -1, 10808, 19036, 19035, -1, 10807, 18983, 19036, -1, 19077, 10739, 10746, -1, 19034, 10739, 19077, -1, 19033, 10726, 19034, -1, 19034, 10726, 10739, -1, 18971, 10727, 19033, -1, 19033, 10727, 10726, -1, 10790, 19235, 10794, -1, 10781, 20378, 10790, -1, 10790, 20378, 19235, -1, 10783, 20296, 10781, -1, 10781, 20296, 20378, -1, 10783, 19142, 20296, -1, 19220, 10828, 10835, -1, 20379, 10828, 19220, -1, 20298, 10824, 20379, -1, 20379, 10824, 10828, -1, 19098, 10823, 20298, -1, 20298, 10823, 10824, -1, 11277, 21470, 21471, -1, 11277, 11253, 21470, -1, 11253, 21472, 21470, -1, 11253, 11245, 21472, -1, 11245, 21473, 21472, -1, 11245, 11249, 21473, -1, 11249, 21474, 21473, -1, 11249, 11252, 21474, -1, 11252, 21475, 21474, -1, 11252, 11254, 21475, -1, 21475, 11261, 21476, -1, 11254, 11261, 21475, -1, 21476, 11267, 21477, -1, 11261, 11267, 21476, -1, 21477, 11273, 21478, -1, 11267, 11273, 21477, -1, 21478, 11271, 21479, -1, 11273, 11271, 21478, -1, 21479, 11269, 21480, -1, 11271, 11269, 21479, -1, 21480, 11265, 21481, -1, 11269, 11265, 21480, -1, 21481, 11262, 21482, -1, 11265, 11262, 21481, -1, 11262, 21483, 21482, -1, 11262, 11257, 21483, -1, 11257, 21471, 21483, -1, 11257, 11277, 21471, -1, 21470, 21472, 21473, -1, 21481, 21482, 21483, -1, 21484, 21471, 21470, -1, 21484, 21473, 21474, -1, 21484, 21470, 21473, -1, 21485, 21474, 21475, -1, 21485, 21475, 21476, -1, 21485, 21484, 21474, -1, 21485, 21471, 21484, -1, 21486, 21480, 21481, -1, 21486, 21483, 21471, -1, 21486, 21481, 21483, -1, 21487, 21476, 21477, -1, 21487, 21477, 21478, -1, 21487, 21471, 21485, -1, 21487, 21485, 21476, -1, 21488, 21479, 21480, -1, 21488, 21478, 21479, -1, 21488, 21480, 21486, -1, 21488, 21471, 21487, -1, 21488, 21487, 21478, -1, 21488, 21486, 21471, -1, 11172, 21489, 21490, -1, 11172, 11179, 21489, -1, 11179, 21491, 21489, -1, 11179, 11185, 21491, -1, 11163, 21492, 21493, -1, 11163, 11167, 21492, -1, 11167, 21494, 21492, -1, 11167, 11170, 21494, -1, 11170, 21490, 21494, -1, 11170, 11172, 21490, -1, 11195, 11171, 21495, -1, 21495, 11171, 21496, -1, 21496, 11163, 21493, -1, 11171, 11163, 21496, -1, 11180, 11175, 21497, -1, 21497, 11175, 21498, -1, 21498, 11195, 21495, -1, 11175, 11195, 21498, -1, 21499, 11187, 21500, -1, 11189, 11187, 21499, -1, 21500, 11183, 21501, -1, 11187, 11183, 21500, -1, 21501, 11180, 21497, -1, 11183, 11180, 21501, -1, 11185, 21502, 21491, -1, 11185, 11191, 21502, -1, 11191, 21499, 21502, -1, 11191, 11189, 21499, -1, 21496, 21493, 21492, -1, 21501, 21497, 21498, -1, 21503, 21492, 21494, -1, 21503, 21495, 21496, -1, 21503, 21496, 21492, -1, 21504, 21494, 21490, -1, 21504, 21490, 21489, -1, 21504, 21503, 21494, -1, 21504, 21495, 21503, -1, 21505, 21500, 21501, -1, 21505, 21498, 21495, -1, 21505, 21501, 21498, -1, 21506, 21489, 21491, -1, 21506, 21491, 21502, -1, 21506, 21495, 21504, -1, 21506, 21504, 21489, -1, 21507, 21502, 21499, -1, 21507, 21499, 21500, -1, 21507, 21500, 21505, -1, 21507, 21495, 21506, -1, 21507, 21506, 21502, -1, 21507, 21505, 21495, -1, 10837, 21508, 21509, -1, 10837, 10813, 21508, -1, 10813, 21510, 21508, -1, 10813, 10805, 21510, -1, 10805, 21511, 21510, -1, 10805, 10809, 21511, -1, 10809, 21512, 21511, -1, 10809, 10812, 21512, -1, 10812, 21513, 21512, -1, 10812, 10814, 21513, -1, 21514, 21515, 10827, -1, 21515, 10821, 10827, -1, 21515, 21513, 10821, -1, 21513, 10814, 10821, -1, 21516, 21517, 10831, -1, 21517, 10833, 10831, -1, 21517, 21514, 10833, -1, 21514, 10827, 10833, -1, 21516, 10829, 21518, -1, 10831, 10829, 21516, -1, 21518, 10825, 21519, -1, 10829, 10825, 21518, -1, 21519, 10822, 21520, -1, 10825, 10822, 21519, -1, 10822, 21521, 21520, -1, 10822, 10817, 21521, -1, 10817, 21509, 21521, -1, 10817, 10837, 21509, -1, 21508, 21510, 21511, -1, 21519, 21520, 21521, -1, 21522, 21509, 21508, -1, 21522, 21511, 21512, -1, 21522, 21508, 21511, -1, 21523, 21512, 21513, -1, 21523, 21513, 21515, -1, 21523, 21522, 21512, -1, 21523, 21509, 21522, -1, 21524, 21518, 21519, -1, 21524, 21521, 21509, -1, 21524, 21519, 21521, -1, 21525, 21515, 21514, -1, 21525, 21514, 21517, -1, 21525, 21509, 21523, -1, 21525, 21523, 21515, -1, 21526, 21516, 21518, -1, 21526, 21517, 21516, -1, 21526, 21518, 21524, -1, 21526, 21509, 21525, -1, 21526, 21525, 21517, -1, 21526, 21524, 21509, -1, 21527, 10763, 10769, -1, 21528, 10763, 21527, -1, 21529, 10756, 21528, -1, 21528, 10756, 10763, -1, 10747, 21530, 21531, -1, 21530, 10751, 21532, -1, 10747, 10751, 21530, -1, 21532, 10754, 21529, -1, 10751, 10754, 21532, -1, 10754, 10756, 21529, -1, 10779, 10755, 21533, -1, 21533, 10755, 21534, -1, 21534, 10747, 21531, -1, 10755, 10747, 21534, -1, 10764, 10759, 21535, -1, 21535, 10759, 21536, -1, 21536, 10779, 21533, -1, 10759, 10779, 21536, -1, 10773, 10771, 21537, -1, 10771, 21538, 21537, -1, 10771, 10767, 21538, -1, 10767, 21539, 21538, -1, 10767, 10764, 21539, -1, 10764, 21535, 21539, -1, 21537, 10775, 10773, -1, 21540, 10775, 21537, -1, 21527, 10769, 21540, -1, 21540, 10769, 10775, -1, 21534, 21531, 21530, -1, 21539, 21535, 21536, -1, 21541, 21530, 21532, -1, 21541, 21533, 21534, -1, 21541, 21534, 21530, -1, 21542, 21532, 21529, -1, 21542, 21529, 21528, -1, 21542, 21541, 21532, -1, 21542, 21533, 21541, -1, 21543, 21538, 21539, -1, 21543, 21536, 21533, -1, 21543, 21539, 21536, -1, 21544, 21528, 21527, -1, 21544, 21527, 21540, -1, 21544, 21533, 21542, -1, 21544, 21542, 21528, -1, 21545, 21540, 21537, -1, 21545, 21537, 21538, -1, 21545, 21538, 21543, -1, 21545, 21533, 21544, -1, 21545, 21544, 21540, -1, 21545, 21543, 21533, -1, 10697, 21546, 21547, -1, 10697, 10673, 21546, -1, 10673, 21548, 21546, -1, 10673, 10665, 21548, -1, 10665, 21549, 21548, -1, 10665, 10669, 21549, -1, 10669, 21550, 21549, -1, 10669, 10672, 21550, -1, 10672, 21551, 21550, -1, 10672, 10674, 21551, -1, 21551, 10681, 21552, -1, 10674, 10681, 21551, -1, 21552, 10687, 21553, -1, 10681, 10687, 21552, -1, 21553, 10693, 21554, -1, 10687, 10693, 21553, -1, 21554, 10691, 21555, -1, 10693, 10691, 21554, -1, 21555, 10689, 21556, -1, 10691, 10689, 21555, -1, 21556, 10685, 21557, -1, 10689, 10685, 21556, -1, 21557, 10682, 21558, -1, 10685, 10682, 21557, -1, 10682, 21559, 21558, -1, 10682, 10677, 21559, -1, 10677, 21547, 21559, -1, 10677, 10697, 21547, -1, 21546, 21548, 21549, -1, 21557, 21558, 21559, -1, 21560, 21547, 21546, -1, 21560, 21549, 21550, -1, 21560, 21546, 21549, -1, 21561, 21550, 21551, -1, 21561, 21551, 21552, -1, 21561, 21560, 21550, -1, 21561, 21547, 21560, -1, 21562, 21556, 21557, -1, 21562, 21559, 21547, -1, 21562, 21557, 21559, -1, 21563, 21552, 21553, -1, 21563, 21553, 21554, -1, 21563, 21547, 21561, -1, 21563, 21561, 21552, -1, 21564, 21555, 21556, -1, 21564, 21554, 21555, -1, 21564, 21556, 21562, -1, 21564, 21547, 21563, -1, 21564, 21563, 21554, -1, 21564, 21562, 21547, -1, 10616, 21565, 21566, -1, 10616, 10623, 21565, -1, 10623, 21567, 21565, -1, 10623, 10629, 21567, -1, 10607, 21568, 21569, -1, 10607, 10611, 21568, -1, 10611, 21570, 21568, -1, 10611, 10614, 21570, -1, 10614, 21566, 21570, -1, 10614, 10616, 21566, -1, 10639, 10615, 21571, -1, 21571, 10615, 21572, -1, 21572, 10607, 21569, -1, 10615, 10607, 21572, -1, 10624, 10619, 21573, -1, 21573, 10619, 21574, -1, 21574, 10639, 21571, -1, 10619, 10639, 21574, -1, 10633, 10631, 21575, -1, 10631, 21576, 21575, -1, 10631, 10627, 21576, -1, 10627, 21577, 21576, -1, 10627, 10624, 21577, -1, 10624, 21573, 21577, -1, 10629, 21578, 21567, -1, 10629, 10635, 21578, -1, 10635, 21575, 21578, -1, 10635, 10633, 21575, -1, 21572, 21569, 21568, -1, 21577, 21573, 21574, -1, 21579, 21568, 21570, -1, 21579, 21571, 21572, -1, 21579, 21572, 21568, -1, 21580, 21570, 21566, -1, 21580, 21566, 21565, -1, 21580, 21579, 21570, -1, 21580, 21571, 21579, -1, 21581, 21576, 21577, -1, 21581, 21574, 21571, -1, 21581, 21577, 21574, -1, 21582, 21565, 21567, -1, 21582, 21567, 21578, -1, 21582, 21571, 21580, -1, 21582, 21580, 21565, -1, 21583, 21578, 21575, -1, 21583, 21575, 21576, -1, 21583, 21576, 21581, -1, 21583, 21571, 21582, -1, 21583, 21582, 21578, -1, 21583, 21581, 21571, -1, 10341, 21584, 21585, -1, 10341, 10317, 21584, -1, 10317, 21586, 21584, -1, 10317, 10309, 21586, -1, 21587, 10316, 10318, -1, 21587, 21588, 10316, -1, 21588, 10313, 10316, -1, 21588, 21589, 10313, -1, 21589, 10309, 10313, -1, 21589, 21586, 10309, -1, 21590, 21591, 10331, -1, 21591, 10325, 10331, -1, 21591, 21587, 10325, -1, 21587, 10318, 10325, -1, 21592, 21593, 10335, -1, 21593, 10337, 10335, -1, 21593, 21590, 10337, -1, 21590, 10331, 10337, -1, 21594, 21595, 10326, -1, 10326, 21595, 10329, -1, 10329, 21596, 10333, -1, 21595, 21596, 10329, -1, 10333, 21592, 10335, -1, 21596, 21592, 10333, -1, 10326, 21597, 21594, -1, 10326, 10321, 21597, -1, 10321, 21585, 21597, -1, 10321, 10341, 21585, -1, 21584, 21586, 21589, -1, 21595, 21594, 21597, -1, 21598, 21585, 21584, -1, 21598, 21589, 21588, -1, 21598, 21584, 21589, -1, 21599, 21588, 21587, -1, 21599, 21587, 21591, -1, 21599, 21598, 21588, -1, 21599, 21585, 21598, -1, 21600, 21596, 21595, -1, 21600, 21597, 21585, -1, 21600, 21595, 21597, -1, 21601, 21591, 21590, -1, 21601, 21590, 21593, -1, 21601, 21585, 21599, -1, 21601, 21599, 21591, -1, 21602, 21592, 21596, -1, 21602, 21593, 21592, -1, 21602, 21596, 21600, -1, 21602, 21585, 21601, -1, 21602, 21601, 21593, -1, 21602, 21600, 21585, -1, 21603, 10291, 10297, -1, 21604, 10291, 21603, -1, 21605, 10284, 21604, -1, 21604, 10284, 10291, -1, 21605, 10282, 10284, -1, 21605, 21606, 10282, -1, 21606, 10279, 10282, -1, 21606, 21607, 10279, -1, 21607, 10275, 10279, -1, 21607, 21608, 10275, -1, 10307, 10283, 21609, -1, 21609, 10283, 21610, -1, 21610, 10275, 21608, -1, 10283, 10275, 21610, -1, 10292, 10287, 21611, -1, 21611, 10287, 21612, -1, 21612, 10307, 21609, -1, 10287, 10307, 21612, -1, 21611, 21613, 10292, -1, 10292, 21613, 10295, -1, 10295, 21614, 10299, -1, 21613, 21614, 10295, -1, 10299, 21615, 10301, -1, 21614, 21615, 10299, -1, 21615, 10303, 10301, -1, 21616, 10303, 21615, -1, 21603, 10297, 21616, -1, 21616, 10297, 10303, -1, 21610, 21608, 21607, -1, 21613, 21611, 21612, -1, 21617, 21607, 21606, -1, 21617, 21609, 21610, -1, 21617, 21610, 21607, -1, 21618, 21606, 21605, -1, 21618, 21605, 21604, -1, 21618, 21617, 21606, -1, 21618, 21609, 21617, -1, 21619, 21614, 21613, -1, 21619, 21612, 21609, -1, 21619, 21613, 21612, -1, 21620, 21604, 21603, -1, 21620, 21603, 21616, -1, 21620, 21609, 21618, -1, 21620, 21618, 21604, -1, 21621, 21616, 21615, -1, 21621, 21615, 21614, -1, 21621, 21614, 21619, -1, 21621, 21609, 21620, -1, 21621, 21620, 21616, -1, 21621, 21619, 21609, -1, 21622, 10149, 10155, -1, 21623, 10149, 21622, -1, 21624, 10142, 21623, -1, 21623, 10142, 10149, -1, 21625, 10133, 21626, -1, 21626, 10137, 21627, -1, 10133, 10137, 21626, -1, 21627, 10140, 21624, -1, 10137, 10140, 21627, -1, 10140, 10142, 21624, -1, 10165, 10141, 21628, -1, 21628, 10141, 21629, -1, 21629, 10133, 21625, -1, 10141, 10133, 21629, -1, 10150, 10145, 21630, -1, 21630, 10145, 21631, -1, 21631, 10165, 21628, -1, 10145, 10165, 21631, -1, 10157, 21632, 10159, -1, 10153, 21633, 10157, -1, 10157, 21633, 21632, -1, 10150, 21634, 10153, -1, 10153, 21634, 21633, -1, 10150, 21630, 21634, -1, 21632, 10161, 10159, -1, 21635, 10161, 21632, -1, 21622, 10155, 21635, -1, 21635, 10155, 10161, -1, 21629, 21625, 21626, -1, 21634, 21630, 21631, -1, 21636, 21626, 21627, -1, 21636, 21628, 21629, -1, 21636, 21629, 21626, -1, 21637, 21627, 21624, -1, 21637, 21624, 21623, -1, 21637, 21636, 21627, -1, 21637, 21628, 21636, -1, 21638, 21633, 21634, -1, 21638, 21631, 21628, -1, 21638, 21634, 21631, -1, 21639, 21623, 21622, -1, 21639, 21622, 21635, -1, 21639, 21628, 21637, -1, 21639, 21637, 21623, -1, 21640, 21635, 21632, -1, 21640, 21632, 21633, -1, 21640, 21633, 21638, -1, 21640, 21628, 21639, -1, 21640, 21639, 21635, -1, 21640, 21638, 21628, -1, 10107, 21641, 21642, -1, 10107, 10083, 21641, -1, 10083, 21643, 21641, -1, 10083, 10075, 21643, -1, 21643, 10075, 21644, -1, 21644, 10079, 21645, -1, 10075, 10079, 21644, -1, 21645, 10082, 21646, -1, 10079, 10082, 21645, -1, 10082, 10084, 21646, -1, 21647, 21648, 10097, -1, 21648, 10091, 10097, -1, 21648, 21646, 10091, -1, 21646, 10084, 10091, -1, 21649, 21650, 10101, -1, 21650, 10103, 10101, -1, 21650, 21647, 10103, -1, 21647, 10097, 10103, -1, 21649, 10099, 21651, -1, 10101, 10099, 21649, -1, 21651, 10095, 21652, -1, 10099, 10095, 21651, -1, 21652, 10092, 21653, -1, 10095, 10092, 21652, -1, 10092, 21654, 21653, -1, 10092, 10087, 21654, -1, 10087, 21642, 21654, -1, 10087, 10107, 21642, -1, 21641, 21643, 21644, -1, 21652, 21653, 21654, -1, 21655, 21642, 21641, -1, 21655, 21644, 21645, -1, 21655, 21641, 21644, -1, 21656, 21645, 21646, -1, 21656, 21646, 21648, -1, 21656, 21655, 21645, -1, 21656, 21642, 21655, -1, 21657, 21651, 21652, -1, 21657, 21654, 21642, -1, 21657, 21652, 21654, -1, 21658, 21648, 21647, -1, 21658, 21647, 21650, -1, 21658, 21642, 21656, -1, 21658, 21656, 21648, -1, 21659, 21649, 21651, -1, 21659, 21650, 21649, -1, 21659, 21651, 21657, -1, 21659, 21642, 21658, -1, 21659, 21658, 21650, -1, 21659, 21657, 21642, -1, 21660, 9901, 9907, -1, 21661, 9901, 21660, -1, 21662, 9894, 21661, -1, 21661, 9894, 9901, -1, 9885, 21663, 21664, -1, 9885, 9889, 21663, -1, 9889, 21665, 21663, -1, 9889, 9892, 21665, -1, 9892, 21662, 21665, -1, 9892, 9894, 21662, -1, 9917, 9893, 21666, -1, 21666, 9893, 21667, -1, 21667, 9885, 21664, -1, 9893, 9885, 21667, -1, 9902, 9897, 21668, -1, 21668, 9897, 21669, -1, 21669, 9917, 21666, -1, 9897, 9917, 21669, -1, 9911, 9909, 21670, -1, 9909, 21671, 21670, -1, 9909, 9905, 21671, -1, 9905, 21672, 21671, -1, 9905, 9902, 21672, -1, 9902, 21668, 21672, -1, 21670, 9913, 9911, -1, 21673, 9913, 21670, -1, 21660, 9907, 21673, -1, 21673, 9907, 9913, -1, 21667, 21664, 21663, -1, 21672, 21668, 21669, -1, 21674, 21663, 21665, -1, 21674, 21666, 21667, -1, 21674, 21667, 21663, -1, 21675, 21665, 21662, -1, 21675, 21662, 21661, -1, 21675, 21674, 21665, -1, 21675, 21666, 21674, -1, 21676, 21671, 21672, -1, 21676, 21669, 21666, -1, 21676, 21672, 21669, -1, 21677, 21661, 21660, -1, 21677, 21660, 21673, -1, 21677, 21666, 21675, -1, 21677, 21675, 21661, -1, 21678, 21673, 21670, -1, 21678, 21670, 21671, -1, 21678, 21671, 21676, -1, 21678, 21666, 21677, -1, 21678, 21677, 21673, -1, 21678, 21676, 21666, -1, 9859, 21679, 21680, -1, 9859, 9835, 21679, -1, 9835, 21681, 21679, -1, 9835, 9827, 21681, -1, 9827, 21682, 21681, -1, 9827, 9831, 21682, -1, 9831, 21683, 21682, -1, 9831, 9834, 21683, -1, 9834, 21684, 21683, -1, 9834, 9836, 21684, -1, 21685, 21686, 9849, -1, 21686, 9843, 9849, -1, 21686, 21684, 9843, -1, 21684, 9836, 9843, -1, 21687, 21688, 9853, -1, 21688, 9855, 9853, -1, 21688, 21685, 9855, -1, 21685, 9849, 9855, -1, 21687, 9851, 21689, -1, 9853, 9851, 21687, -1, 21689, 9847, 21690, -1, 9851, 9847, 21689, -1, 21690, 9844, 21691, -1, 9847, 9844, 21690, -1, 9844, 21692, 21691, -1, 9844, 9839, 21692, -1, 9839, 21680, 21692, -1, 9839, 9859, 21680, -1, 21679, 21681, 21682, -1, 21690, 21691, 21692, -1, 21693, 21680, 21679, -1, 21693, 21682, 21683, -1, 21693, 21679, 21682, -1, 21694, 21683, 21684, -1, 21694, 21684, 21686, -1, 21694, 21693, 21683, -1, 21694, 21680, 21693, -1, 21695, 21689, 21690, -1, 21695, 21692, 21680, -1, 21695, 21690, 21692, -1, 21696, 21686, 21685, -1, 21696, 21685, 21688, -1, 21696, 21680, 21694, -1, 21696, 21694, 21686, -1, 21697, 21687, 21689, -1, 21697, 21688, 21687, -1, 21697, 21689, 21695, -1, 21697, 21680, 21696, -1, 21697, 21696, 21688, -1, 21697, 21695, 21680, -1, 9717, 21698, 21699, -1, 9717, 9693, 21698, -1, 9693, 21700, 21698, -1, 9693, 9685, 21700, -1, 9685, 21701, 21700, -1, 9685, 9689, 21701, -1, 9689, 21702, 21701, -1, 9689, 9692, 21702, -1, 9692, 21703, 21702, -1, 9692, 9694, 21703, -1, 21704, 21705, 9707, -1, 21705, 9701, 9707, -1, 21705, 21703, 9701, -1, 21703, 9694, 9701, -1, 21706, 21707, 9711, -1, 21707, 9713, 9711, -1, 21707, 21704, 9713, -1, 21704, 9707, 9713, -1, 21706, 9709, 21708, -1, 9711, 9709, 21706, -1, 21708, 9705, 21709, -1, 9709, 9705, 21708, -1, 21709, 9702, 21710, -1, 9705, 9702, 21709, -1, 9702, 21711, 21710, -1, 9702, 9697, 21711, -1, 9697, 21699, 21711, -1, 9697, 9717, 21699, -1, 21698, 21700, 21701, -1, 21709, 21710, 21711, -1, 21712, 21699, 21698, -1, 21712, 21701, 21702, -1, 21712, 21698, 21701, -1, 21713, 21702, 21703, -1, 21713, 21703, 21705, -1, 21713, 21712, 21702, -1, 21713, 21699, 21712, -1, 21714, 21708, 21709, -1, 21714, 21711, 21699, -1, 21714, 21709, 21711, -1, 21715, 21705, 21704, -1, 21715, 21704, 21707, -1, 21715, 21699, 21713, -1, 21715, 21713, 21705, -1, 21716, 21706, 21708, -1, 21716, 21707, 21706, -1, 21716, 21708, 21714, -1, 21716, 21699, 21715, -1, 21716, 21715, 21707, -1, 21716, 21714, 21699, -1, 21717, 9643, 9649, -1, 21718, 9643, 21717, -1, 21719, 9636, 21718, -1, 21718, 9636, 9643, -1, 9627, 21720, 21721, -1, 9627, 9631, 21720, -1, 9631, 21722, 21720, -1, 9631, 9634, 21722, -1, 9634, 21719, 21722, -1, 9634, 9636, 21719, -1, 9659, 9635, 21723, -1, 21723, 9635, 21724, -1, 21724, 9627, 21721, -1, 9635, 9627, 21724, -1, 9644, 9639, 21725, -1, 21725, 9639, 21726, -1, 21726, 9659, 21723, -1, 9639, 9659, 21726, -1, 9653, 9651, 21727, -1, 9651, 21728, 21727, -1, 9651, 9647, 21728, -1, 9647, 21729, 21728, -1, 9647, 9644, 21729, -1, 9644, 21725, 21729, -1, 21727, 9655, 9653, -1, 21730, 9655, 21727, -1, 21717, 9649, 21730, -1, 21730, 9649, 9655, -1, 21724, 21721, 21720, -1, 21729, 21725, 21726, -1, 21731, 21720, 21722, -1, 21731, 21723, 21724, -1, 21731, 21724, 21720, -1, 21732, 21722, 21719, -1, 21732, 21719, 21718, -1, 21732, 21731, 21722, -1, 21732, 21723, 21731, -1, 21733, 21728, 21729, -1, 21733, 21726, 21723, -1, 21733, 21729, 21726, -1, 21734, 21718, 21717, -1, 21734, 21717, 21730, -1, 21734, 21723, 21732, -1, 21734, 21732, 21718, -1, 21735, 21730, 21727, -1, 21735, 21727, 21728, -1, 21735, 21728, 21733, -1, 21735, 21723, 21734, -1, 21735, 21734, 21730, -1, 21735, 21733, 21723, -1, 9469, 21736, 21737, -1, 9469, 9445, 21736, -1, 9445, 21738, 21736, -1, 9445, 9437, 21738, -1, 9437, 21739, 21738, -1, 9437, 9441, 21739, -1, 9441, 21740, 21739, -1, 9441, 9444, 21740, -1, 9444, 21741, 21740, -1, 9444, 9446, 21741, -1, 21741, 9453, 21742, -1, 9446, 9453, 21741, -1, 21742, 9459, 21743, -1, 9453, 9459, 21742, -1, 21743, 9465, 21744, -1, 9459, 9465, 21743, -1, 21744, 9463, 21745, -1, 9465, 9463, 21744, -1, 21745, 9461, 21746, -1, 9463, 9461, 21745, -1, 21746, 9457, 21747, -1, 9461, 9457, 21746, -1, 21747, 9454, 21748, -1, 9457, 9454, 21747, -1, 9454, 21749, 21748, -1, 9454, 9449, 21749, -1, 9449, 21737, 21749, -1, 9449, 9469, 21737, -1, 21736, 21738, 21739, -1, 21747, 21748, 21749, -1, 21750, 21737, 21736, -1, 21750, 21739, 21740, -1, 21750, 21736, 21739, -1, 21751, 21740, 21741, -1, 21751, 21741, 21742, -1, 21751, 21750, 21740, -1, 21751, 21737, 21750, -1, 21752, 21746, 21747, -1, 21752, 21749, 21737, -1, 21752, 21747, 21749, -1, 21753, 21742, 21743, -1, 21753, 21743, 21744, -1, 21753, 21737, 21751, -1, 21753, 21751, 21742, -1, 21754, 21745, 21746, -1, 21754, 21744, 21745, -1, 21754, 21746, 21752, -1, 21754, 21737, 21753, -1, 21754, 21753, 21744, -1, 21754, 21752, 21737, -1, 9412, 21755, 21756, -1, 9412, 9419, 21755, -1, 9419, 21757, 21755, -1, 9419, 9425, 21757, -1, 9403, 21758, 21759, -1, 9403, 9407, 21758, -1, 9407, 21760, 21758, -1, 9407, 9410, 21760, -1, 9410, 21756, 21760, -1, 9410, 9412, 21756, -1, 9435, 9411, 21761, -1, 21761, 9411, 21762, -1, 21762, 9403, 21759, -1, 9411, 9403, 21762, -1, 9420, 9415, 21763, -1, 21763, 9415, 21764, -1, 21764, 9435, 21761, -1, 9415, 9435, 21764, -1, 9429, 9427, 21765, -1, 9427, 21766, 21765, -1, 9427, 9423, 21766, -1, 9423, 21767, 21766, -1, 9423, 9420, 21767, -1, 9420, 21763, 21767, -1, 9425, 21768, 21757, -1, 9425, 9431, 21768, -1, 9431, 21765, 21768, -1, 9431, 9429, 21765, -1, 21762, 21759, 21758, -1, 21767, 21763, 21764, -1, 21769, 21758, 21760, -1, 21769, 21761, 21762, -1, 21769, 21762, 21758, -1, 21770, 21760, 21756, -1, 21770, 21756, 21755, -1, 21770, 21769, 21760, -1, 21770, 21761, 21769, -1, 21771, 21766, 21767, -1, 21771, 21764, 21761, -1, 21771, 21767, 21764, -1, 21772, 21755, 21757, -1, 21772, 21757, 21768, -1, 21772, 21761, 21770, -1, 21772, 21770, 21755, -1, 21773, 21768, 21765, -1, 21773, 21765, 21766, -1, 21773, 21766, 21771, -1, 21773, 21761, 21772, -1, 21773, 21772, 21768, -1, 21773, 21771, 21761, -1, 9245, 21774, 21775, -1, 9245, 9221, 21774, -1, 9221, 21776, 21774, -1, 9221, 9213, 21776, -1, 9213, 21777, 21776, -1, 9213, 9217, 21777, -1, 9217, 21778, 21777, -1, 9217, 9220, 21778, -1, 9220, 21779, 21778, -1, 9220, 9222, 21779, -1, 21779, 9229, 21780, -1, 9222, 9229, 21779, -1, 21780, 9235, 21781, -1, 9229, 9235, 21780, -1, 21781, 9241, 21782, -1, 9235, 9241, 21781, -1, 21782, 9239, 21783, -1, 9241, 9239, 21782, -1, 21783, 9237, 21784, -1, 9239, 9237, 21783, -1, 21784, 9233, 21785, -1, 9237, 9233, 21784, -1, 21785, 9230, 21786, -1, 9233, 9230, 21785, -1, 9230, 21787, 21786, -1, 9230, 9225, 21787, -1, 9225, 21775, 21787, -1, 9225, 9245, 21775, -1, 21774, 21776, 21777, -1, 21785, 21786, 21787, -1, 21788, 21775, 21774, -1, 21788, 21777, 21778, -1, 21788, 21774, 21777, -1, 21789, 21778, 21779, -1, 21789, 21779, 21780, -1, 21789, 21788, 21778, -1, 21789, 21775, 21788, -1, 21790, 21784, 21785, -1, 21790, 21787, 21775, -1, 21790, 21785, 21787, -1, 21791, 21780, 21781, -1, 21791, 21781, 21782, -1, 21791, 21775, 21789, -1, 21791, 21789, 21780, -1, 21792, 21783, 21784, -1, 21792, 21782, 21783, -1, 21792, 21784, 21790, -1, 21792, 21775, 21791, -1, 21792, 21791, 21782, -1, 21792, 21790, 21775, -1, 9188, 21793, 21794, -1, 9188, 9195, 21793, -1, 9195, 21795, 21793, -1, 9195, 9201, 21795, -1, 9179, 21796, 21797, -1, 9179, 9183, 21796, -1, 9183, 21798, 21796, -1, 9183, 9186, 21798, -1, 9186, 21794, 21798, -1, 9186, 9188, 21794, -1, 9211, 9187, 21799, -1, 21799, 9187, 21800, -1, 21800, 9179, 21797, -1, 9187, 9179, 21800, -1, 9196, 9191, 21801, -1, 21801, 9191, 21802, -1, 21802, 9211, 21799, -1, 9191, 9211, 21802, -1, 9205, 9203, 21803, -1, 9203, 21804, 21803, -1, 9203, 9199, 21804, -1, 9199, 21805, 21804, -1, 9199, 9196, 21805, -1, 9196, 21801, 21805, -1, 9201, 21806, 21795, -1, 9201, 9207, 21806, -1, 9207, 21803, 21806, -1, 9207, 9205, 21803, -1, 21800, 21797, 21796, -1, 21805, 21801, 21802, -1, 21807, 21796, 21798, -1, 21807, 21799, 21800, -1, 21807, 21800, 21796, -1, 21808, 21798, 21794, -1, 21808, 21794, 21793, -1, 21808, 21807, 21798, -1, 21808, 21799, 21807, -1, 21809, 21804, 21805, -1, 21809, 21802, 21799, -1, 21809, 21805, 21802, -1, 21810, 21793, 21795, -1, 21810, 21795, 21806, -1, 21810, 21799, 21808, -1, 21810, 21808, 21793, -1, 21811, 21806, 21803, -1, 21811, 21803, 21804, -1, 21811, 21804, 21809, -1, 21811, 21799, 21810, -1, 21811, 21810, 21806, -1, 21811, 21809, 21799, -1, 9129, 21812, 21813, -1, 9129, 9105, 21812, -1, 9105, 21814, 21812, -1, 9105, 9097, 21814, -1, 9097, 21815, 21814, -1, 9097, 9101, 21815, -1, 9101, 21816, 21815, -1, 9101, 9104, 21816, -1, 9104, 21817, 21816, -1, 9104, 9106, 21817, -1, 21817, 9113, 21818, -1, 9106, 9113, 21817, -1, 21818, 9119, 21819, -1, 9113, 9119, 21818, -1, 21819, 9125, 21820, -1, 9119, 9125, 21819, -1, 21820, 9123, 21821, -1, 9125, 9123, 21820, -1, 21821, 9121, 21822, -1, 9123, 9121, 21821, -1, 21822, 9117, 21823, -1, 9121, 9117, 21822, -1, 21823, 9114, 21824, -1, 9117, 9114, 21823, -1, 9114, 21825, 21824, -1, 9114, 9109, 21825, -1, 9109, 21813, 21825, -1, 9109, 9129, 21813, -1, 21812, 21814, 21815, -1, 21823, 21824, 21825, -1, 21826, 21813, 21812, -1, 21826, 21815, 21816, -1, 21826, 21812, 21815, -1, 21827, 21816, 21817, -1, 21827, 21817, 21818, -1, 21827, 21826, 21816, -1, 21827, 21813, 21826, -1, 21828, 21822, 21823, -1, 21828, 21825, 21813, -1, 21828, 21823, 21825, -1, 21829, 21818, 21819, -1, 21829, 21819, 21820, -1, 21829, 21813, 21827, -1, 21829, 21827, 21818, -1, 21830, 21821, 21822, -1, 21830, 21820, 21821, -1, 21830, 21822, 21828, -1, 21830, 21813, 21829, -1, 21830, 21829, 21820, -1, 21830, 21828, 21813, -1, 9048, 21831, 21832, -1, 9048, 9055, 21831, -1, 9055, 21833, 21831, -1, 9055, 9061, 21833, -1, 9039, 21834, 21835, -1, 9039, 9043, 21834, -1, 9043, 21836, 21834, -1, 9043, 9046, 21836, -1, 9046, 21832, 21836, -1, 9046, 9048, 21832, -1, 9071, 9047, 21837, -1, 21837, 9047, 21838, -1, 21838, 9039, 21835, -1, 9047, 9039, 21838, -1, 9056, 9051, 21839, -1, 21839, 9051, 21840, -1, 21840, 9071, 21837, -1, 9051, 9071, 21840, -1, 21841, 9063, 21842, -1, 9065, 9063, 21841, -1, 21842, 9059, 21843, -1, 9063, 9059, 21842, -1, 21843, 9056, 21839, -1, 9059, 9056, 21843, -1, 9061, 21844, 21833, -1, 9061, 9067, 21844, -1, 9067, 21841, 21844, -1, 9067, 9065, 21841, -1, 21838, 21835, 21834, -1, 21843, 21839, 21840, -1, 21845, 21834, 21836, -1, 21845, 21837, 21838, -1, 21845, 21838, 21834, -1, 21846, 21836, 21832, -1, 21846, 21832, 21831, -1, 21846, 21845, 21836, -1, 21846, 21837, 21845, -1, 21847, 21842, 21843, -1, 21847, 21840, 21837, -1, 21847, 21843, 21840, -1, 21848, 21831, 21833, -1, 21848, 21833, 21844, -1, 21848, 21837, 21846, -1, 21848, 21846, 21831, -1, 21849, 21844, 21841, -1, 21849, 21841, 21842, -1, 21849, 21842, 21847, -1, 21849, 21837, 21848, -1, 21849, 21848, 21844, -1, 21849, 21847, 21837, -1, 21850, 8913, 8919, -1, 21851, 8913, 21850, -1, 21852, 8906, 21851, -1, 21851, 8906, 8913, -1, 21853, 8897, 21854, -1, 21854, 8901, 21855, -1, 8897, 8901, 21854, -1, 21855, 8904, 21852, -1, 8901, 8904, 21855, -1, 8904, 8906, 21852, -1, 8929, 8905, 21856, -1, 21856, 8905, 21857, -1, 21857, 8897, 21853, -1, 8905, 8897, 21857, -1, 8914, 8909, 21858, -1, 21858, 8909, 21859, -1, 21859, 8929, 21856, -1, 8909, 8929, 21859, -1, 21860, 8921, 21861, -1, 8923, 8921, 21860, -1, 21861, 8917, 21862, -1, 8921, 8917, 21861, -1, 21862, 8914, 21858, -1, 8917, 8914, 21862, -1, 21860, 8925, 8923, -1, 21863, 8925, 21860, -1, 21850, 8919, 21863, -1, 21863, 8919, 8925, -1, 21857, 21853, 21854, -1, 21862, 21858, 21859, -1, 21864, 21854, 21855, -1, 21864, 21856, 21857, -1, 21864, 21857, 21854, -1, 21865, 21855, 21852, -1, 21865, 21852, 21851, -1, 21865, 21864, 21855, -1, 21865, 21856, 21864, -1, 21866, 21861, 21862, -1, 21866, 21859, 21856, -1, 21866, 21862, 21859, -1, 21867, 21851, 21850, -1, 21867, 21850, 21863, -1, 21867, 21856, 21865, -1, 21867, 21865, 21851, -1, 21868, 21863, 21860, -1, 21868, 21860, 21861, -1, 21868, 21861, 21866, -1, 21868, 21856, 21867, -1, 21868, 21867, 21863, -1, 21868, 21866, 21856, -1, 8847, 21869, 21870, -1, 8847, 8823, 21869, -1, 8823, 21871, 21869, -1, 8823, 8815, 21871, -1, 21871, 8815, 21872, -1, 21872, 8819, 21873, -1, 8815, 8819, 21872, -1, 21873, 8822, 21874, -1, 8819, 8822, 21873, -1, 8822, 8824, 21874, -1, 21875, 21876, 8837, -1, 21876, 8831, 8837, -1, 21876, 21874, 8831, -1, 21874, 8824, 8831, -1, 21877, 21878, 8841, -1, 21878, 8843, 8841, -1, 21878, 21875, 8843, -1, 21875, 8837, 8843, -1, 21877, 8839, 21879, -1, 8841, 8839, 21877, -1, 21879, 8835, 21880, -1, 8839, 8835, 21879, -1, 21880, 8832, 21881, -1, 8835, 8832, 21880, -1, 8832, 21882, 21881, -1, 8832, 8827, 21882, -1, 8827, 21870, 21882, -1, 8827, 8847, 21870, -1, 21869, 21871, 21872, -1, 21880, 21881, 21882, -1, 21883, 21870, 21869, -1, 21883, 21872, 21873, -1, 21883, 21869, 21872, -1, 21884, 21873, 21874, -1, 21884, 21874, 21876, -1, 21884, 21883, 21873, -1, 21884, 21870, 21883, -1, 21885, 21879, 21880, -1, 21885, 21882, 21870, -1, 21885, 21880, 21882, -1, 21886, 21876, 21875, -1, 21886, 21875, 21878, -1, 21886, 21870, 21884, -1, 21886, 21884, 21876, -1, 21887, 21877, 21879, -1, 21887, 21878, 21877, -1, 21887, 21879, 21885, -1, 21887, 21870, 21886, -1, 21887, 21886, 21878, -1, 21887, 21885, 21870, -1, 21888, 8665, 8671, -1, 21889, 8665, 21888, -1, 21890, 8658, 21889, -1, 21889, 8658, 8665, -1, 8649, 21891, 21892, -1, 21891, 8653, 21893, -1, 8649, 8653, 21891, -1, 21893, 8656, 21890, -1, 8653, 8656, 21893, -1, 8656, 8658, 21890, -1, 8681, 8657, 21894, -1, 21894, 8657, 21895, -1, 21895, 8649, 21892, -1, 8657, 8649, 21895, -1, 8666, 8661, 21896, -1, 21896, 8661, 21897, -1, 21897, 8681, 21894, -1, 8661, 8681, 21897, -1, 21898, 8673, 21899, -1, 8675, 8673, 21898, -1, 21899, 8669, 21900, -1, 8673, 8669, 21899, -1, 21900, 8666, 21896, -1, 8669, 8666, 21900, -1, 21898, 8677, 8675, -1, 21901, 8677, 21898, -1, 21888, 8671, 21901, -1, 21901, 8671, 8677, -1, 21895, 21892, 21891, -1, 21900, 21896, 21897, -1, 21902, 21891, 21893, -1, 21902, 21894, 21895, -1, 21902, 21895, 21891, -1, 21903, 21893, 21890, -1, 21903, 21890, 21889, -1, 21903, 21902, 21893, -1, 21903, 21894, 21902, -1, 21904, 21899, 21900, -1, 21904, 21897, 21894, -1, 21904, 21900, 21897, -1, 21905, 21889, 21888, -1, 21905, 21888, 21901, -1, 21905, 21894, 21903, -1, 21905, 21903, 21889, -1, 21906, 21901, 21898, -1, 21906, 21898, 21899, -1, 21906, 21899, 21904, -1, 21906, 21894, 21905, -1, 21906, 21905, 21901, -1, 21906, 21904, 21894, -1, 8623, 21907, 21908, -1, 8623, 8599, 21907, -1, 8599, 21909, 21907, -1, 8599, 8591, 21909, -1, 8591, 21910, 21909, -1, 8591, 8595, 21910, -1, 8595, 21911, 21910, -1, 8595, 8598, 21911, -1, 8598, 21912, 21911, -1, 8598, 8600, 21912, -1, 21913, 21914, 8613, -1, 21914, 8607, 8613, -1, 21914, 21912, 8607, -1, 21912, 8600, 8607, -1, 21915, 21916, 8617, -1, 21916, 8619, 8617, -1, 21916, 21913, 8619, -1, 21913, 8613, 8619, -1, 21915, 8615, 21917, -1, 8617, 8615, 21915, -1, 21917, 8611, 21918, -1, 8615, 8611, 21917, -1, 21918, 8608, 21919, -1, 8611, 8608, 21918, -1, 8608, 21920, 21919, -1, 8608, 8603, 21920, -1, 8603, 21908, 21920, -1, 8603, 8623, 21908, -1, 21907, 21909, 21910, -1, 21918, 21919, 21920, -1, 21921, 21908, 21907, -1, 21921, 21910, 21911, -1, 21921, 21907, 21910, -1, 21922, 21911, 21912, -1, 21922, 21912, 21914, -1, 21922, 21921, 21911, -1, 21922, 21908, 21921, -1, 21923, 21917, 21918, -1, 21923, 21920, 21908, -1, 21923, 21918, 21920, -1, 21924, 21914, 21913, -1, 21924, 21913, 21916, -1, 21924, 21908, 21922, -1, 21924, 21922, 21914, -1, 21925, 21915, 21917, -1, 21925, 21916, 21915, -1, 21925, 21917, 21923, -1, 21925, 21908, 21924, -1, 21925, 21924, 21916, -1, 21925, 21923, 21908, -1, 8457, 21926, 21927, -1, 8457, 8433, 21926, -1, 8433, 21928, 21926, -1, 8433, 8425, 21928, -1, 21929, 8432, 8434, -1, 21929, 21930, 8432, -1, 21930, 8429, 8432, -1, 21930, 21931, 8429, -1, 21931, 8425, 8429, -1, 21931, 21928, 8425, -1, 21932, 21933, 8447, -1, 8447, 21933, 8441, -1, 8441, 21929, 8434, -1, 21933, 21929, 8441, -1, 21934, 21935, 8451, -1, 8451, 21935, 8453, -1, 8453, 21932, 8447, -1, 21935, 21932, 8453, -1, 21936, 21937, 8442, -1, 8442, 21937, 8445, -1, 8445, 21938, 8449, -1, 21937, 21938, 8445, -1, 8449, 21934, 8451, -1, 21938, 21934, 8449, -1, 8442, 21939, 21936, -1, 8442, 8437, 21939, -1, 8437, 21927, 21939, -1, 8437, 8457, 21927, -1, 21926, 21928, 21931, -1, 21937, 21936, 21939, -1, 21940, 21927, 21926, -1, 21940, 21931, 21930, -1, 21940, 21926, 21931, -1, 21941, 21930, 21929, -1, 21941, 21929, 21933, -1, 21941, 21940, 21930, -1, 21941, 21927, 21940, -1, 21942, 21938, 21937, -1, 21942, 21939, 21927, -1, 21942, 21937, 21939, -1, 21943, 21933, 21932, -1, 21943, 21932, 21935, -1, 21943, 21927, 21941, -1, 21943, 21941, 21933, -1, 21944, 21934, 21938, -1, 21944, 21935, 21934, -1, 21944, 21938, 21942, -1, 21944, 21927, 21943, -1, 21944, 21943, 21935, -1, 21944, 21942, 21927, -1, 21945, 8383, 8389, -1, 21945, 21946, 8383, -1, 21946, 8376, 8383, -1, 21946, 21947, 8376, -1, 21947, 8374, 8376, -1, 21947, 21948, 8374, -1, 21948, 8371, 8374, -1, 21948, 21949, 8371, -1, 21949, 8367, 8371, -1, 21949, 21950, 8367, -1, 8399, 8375, 21951, -1, 21951, 8375, 21952, -1, 21952, 8367, 21950, -1, 8375, 8367, 21952, -1, 8384, 8379, 21953, -1, 21953, 8379, 21954, -1, 21954, 8399, 21951, -1, 8379, 8399, 21954, -1, 21953, 21955, 8384, -1, 21955, 8387, 8384, -1, 21955, 21956, 8387, -1, 21956, 8391, 8387, -1, 21956, 21957, 8391, -1, 21957, 8393, 8391, -1, 21957, 8395, 8393, -1, 21957, 21958, 8395, -1, 21958, 8389, 8395, -1, 21958, 21945, 8389, -1, 21952, 21950, 21949, -1, 21955, 21953, 21954, -1, 21959, 21949, 21948, -1, 21959, 21951, 21952, -1, 21959, 21952, 21949, -1, 21960, 21948, 21947, -1, 21960, 21947, 21946, -1, 21960, 21959, 21948, -1, 21960, 21951, 21959, -1, 21961, 21956, 21955, -1, 21961, 21954, 21951, -1, 21961, 21955, 21954, -1, 21962, 21946, 21945, -1, 21962, 21945, 21958, -1, 21962, 21951, 21960, -1, 21962, 21960, 21946, -1, 21963, 21958, 21957, -1, 21963, 21957, 21956, -1, 21963, 21956, 21961, -1, 21963, 21951, 21962, -1, 21963, 21962, 21958, -1, 21963, 21961, 21951, -1, 21964, 8217, 8223, -1, 21964, 21965, 8217, -1, 21965, 8210, 8217, -1, 21965, 21966, 8210, -1, 21966, 8208, 8210, -1, 21966, 21967, 8208, -1, 21967, 8205, 8208, -1, 21967, 21968, 8205, -1, 21968, 8201, 8205, -1, 21968, 21969, 8201, -1, 8233, 8209, 21970, -1, 21970, 8209, 21971, -1, 21971, 8201, 21969, -1, 8209, 8201, 21971, -1, 8218, 8213, 21972, -1, 21972, 8213, 21973, -1, 21973, 8233, 21970, -1, 8213, 8233, 21973, -1, 21972, 21974, 8218, -1, 21974, 8221, 8218, -1, 21974, 21975, 8221, -1, 21975, 8225, 8221, -1, 21975, 21976, 8225, -1, 21976, 8227, 8225, -1, 21976, 8229, 8227, -1, 21976, 21977, 8229, -1, 21977, 8223, 8229, -1, 21977, 21964, 8223, -1, 21971, 21969, 21968, -1, 21974, 21972, 21973, -1, 21978, 21968, 21967, -1, 21978, 21970, 21971, -1, 21978, 21971, 21968, -1, 21979, 21967, 21966, -1, 21979, 21966, 21965, -1, 21979, 21978, 21967, -1, 21979, 21970, 21978, -1, 21980, 21975, 21974, -1, 21980, 21973, 21970, -1, 21980, 21974, 21973, -1, 21981, 21965, 21964, -1, 21981, 21964, 21977, -1, 21981, 21970, 21979, -1, 21981, 21979, 21965, -1, 21982, 21977, 21976, -1, 21982, 21976, 21975, -1, 21982, 21975, 21980, -1, 21982, 21970, 21981, -1, 21982, 21981, 21977, -1, 21982, 21980, 21970, -1, 8175, 21983, 21984, -1, 8175, 8151, 21983, -1, 8151, 21985, 21983, -1, 8151, 8143, 21985, -1, 21986, 8150, 8152, -1, 21986, 21987, 8150, -1, 21987, 8147, 8150, -1, 21987, 21988, 8147, -1, 21988, 8143, 8147, -1, 21988, 21985, 8143, -1, 21989, 21990, 8165, -1, 8165, 21990, 8159, -1, 8159, 21986, 8152, -1, 21990, 21986, 8159, -1, 21991, 21992, 8169, -1, 8169, 21992, 8171, -1, 8171, 21989, 8165, -1, 21992, 21989, 8171, -1, 21993, 21994, 8160, -1, 8160, 21994, 8163, -1, 8163, 21995, 8167, -1, 21994, 21995, 8163, -1, 8167, 21991, 8169, -1, 21995, 21991, 8167, -1, 8160, 21996, 21993, -1, 8160, 8155, 21996, -1, 8155, 21984, 21996, -1, 8155, 8175, 21984, -1, 21983, 21985, 21988, -1, 21994, 21993, 21996, -1, 21997, 21984, 21983, -1, 21997, 21988, 21987, -1, 21997, 21983, 21988, -1, 21998, 21987, 21986, -1, 21998, 21986, 21990, -1, 21998, 21997, 21987, -1, 21998, 21984, 21997, -1, 21999, 21995, 21994, -1, 21999, 21996, 21984, -1, 21999, 21994, 21996, -1, 22000, 21990, 21989, -1, 22000, 21989, 21992, -1, 22000, 21984, 21998, -1, 22000, 21998, 21990, -1, 22001, 21991, 21995, -1, 22001, 21992, 21991, -1, 22001, 21995, 21999, -1, 22001, 21984, 22000, -1, 22001, 22000, 21992, -1, 22001, 21999, 21984, -1, 8009, 22002, 22003, -1, 8009, 7985, 22002, -1, 7985, 22004, 22002, -1, 7985, 7977, 22004, -1, 22005, 7984, 7986, -1, 22005, 22006, 7984, -1, 22006, 7981, 7984, -1, 22006, 22007, 7981, -1, 22007, 7977, 7981, -1, 22007, 22004, 7977, -1, 22008, 22009, 7999, -1, 22009, 7993, 7999, -1, 22009, 22005, 7993, -1, 22005, 7986, 7993, -1, 22010, 22011, 8003, -1, 22011, 8005, 8003, -1, 22011, 22008, 8005, -1, 22008, 7999, 8005, -1, 22012, 22013, 7994, -1, 7994, 22013, 7997, -1, 7997, 22014, 8001, -1, 22013, 22014, 7997, -1, 8001, 22010, 8003, -1, 22014, 22010, 8001, -1, 7994, 22015, 22012, -1, 7994, 7989, 22015, -1, 7989, 22003, 22015, -1, 7989, 8009, 22003, -1, 22002, 22004, 22007, -1, 22013, 22012, 22015, -1, 22016, 22003, 22002, -1, 22016, 22007, 22006, -1, 22016, 22002, 22007, -1, 22017, 22006, 22005, -1, 22017, 22005, 22009, -1, 22017, 22016, 22006, -1, 22017, 22003, 22016, -1, 22018, 22014, 22013, -1, 22018, 22015, 22003, -1, 22018, 22013, 22015, -1, 22019, 22009, 22008, -1, 22019, 22008, 22011, -1, 22019, 22003, 22017, -1, 22019, 22017, 22009, -1, 22020, 22010, 22014, -1, 22020, 22011, 22010, -1, 22020, 22014, 22018, -1, 22020, 22003, 22019, -1, 22020, 22019, 22011, -1, 22020, 22018, 22003, -1, 22021, 7959, 7965, -1, 22022, 7959, 22021, -1, 22023, 7952, 22022, -1, 22022, 7952, 7959, -1, 7952, 22023, 7950, -1, 7950, 22024, 7947, -1, 22023, 22024, 7950, -1, 22024, 22025, 7947, -1, 22025, 7943, 7947, -1, 22025, 22026, 7943, -1, 7975, 7951, 22027, -1, 22027, 7951, 22028, -1, 22028, 7943, 22026, -1, 7951, 7943, 22028, -1, 7960, 7955, 22029, -1, 22029, 7955, 22030, -1, 22030, 7975, 22027, -1, 7955, 7975, 22030, -1, 22029, 22031, 7960, -1, 22031, 7963, 7960, -1, 22031, 22032, 7963, -1, 22032, 7967, 7963, -1, 22032, 22033, 7967, -1, 22033, 7969, 7967, -1, 22033, 7971, 7969, -1, 22034, 7971, 22033, -1, 22021, 7965, 22034, -1, 22034, 7965, 7971, -1, 22028, 22026, 22025, -1, 22031, 22029, 22030, -1, 22035, 22025, 22024, -1, 22035, 22027, 22028, -1, 22035, 22028, 22025, -1, 22036, 22024, 22023, -1, 22036, 22023, 22022, -1, 22036, 22035, 22024, -1, 22036, 22027, 22035, -1, 22037, 22032, 22031, -1, 22037, 22030, 22027, -1, 22037, 22031, 22030, -1, 22038, 22022, 22021, -1, 22038, 22021, 22034, -1, 22038, 22027, 22036, -1, 22038, 22036, 22022, -1, 22039, 22034, 22033, -1, 22039, 22033, 22032, -1, 22039, 22032, 22037, -1, 22039, 22027, 22038, -1, 22039, 22038, 22034, -1, 22039, 22037, 22027, -1, 7893, 22040, 22041, -1, 7893, 7869, 22040, -1, 7869, 22042, 22040, -1, 7869, 7861, 22042, -1, 22043, 7868, 7870, -1, 22043, 22044, 7868, -1, 22044, 7865, 7868, -1, 22044, 22045, 7865, -1, 22045, 7861, 7865, -1, 22045, 22042, 7861, -1, 22046, 22047, 7883, -1, 7883, 22047, 7877, -1, 7877, 22043, 7870, -1, 22047, 22043, 7877, -1, 22048, 22049, 7887, -1, 7887, 22049, 7889, -1, 7889, 22046, 7883, -1, 22049, 22046, 7889, -1, 22050, 22051, 7878, -1, 7878, 22051, 7881, -1, 7881, 22052, 7885, -1, 22051, 22052, 7881, -1, 7885, 22048, 7887, -1, 22052, 22048, 7885, -1, 7878, 22053, 22050, -1, 7878, 7873, 22053, -1, 7873, 22041, 22053, -1, 7873, 7893, 22041, -1, 22040, 22042, 22045, -1, 22051, 22050, 22053, -1, 22054, 22041, 22040, -1, 22054, 22045, 22044, -1, 22054, 22040, 22045, -1, 22055, 22044, 22043, -1, 22055, 22043, 22047, -1, 22055, 22054, 22044, -1, 22055, 22041, 22054, -1, 22056, 22052, 22051, -1, 22056, 22053, 22041, -1, 22056, 22051, 22053, -1, 22057, 22047, 22046, -1, 22057, 22046, 22049, -1, 22057, 22041, 22055, -1, 22057, 22055, 22047, -1, 22058, 22048, 22052, -1, 22058, 22049, 22048, -1, 22058, 22052, 22056, -1, 22058, 22041, 22057, -1, 22058, 22057, 22049, -1, 22058, 22056, 22041, -1, 22059, 7843, 7849, -1, 22059, 22060, 7843, -1, 22060, 7836, 7843, -1, 22060, 22061, 7836, -1, 22061, 7834, 7836, -1, 22061, 22062, 7834, -1, 22062, 7831, 7834, -1, 22062, 22063, 7831, -1, 22063, 7827, 7831, -1, 22063, 22064, 7827, -1, 7859, 7835, 22065, -1, 22065, 7835, 22066, -1, 22066, 7827, 22064, -1, 7835, 7827, 22066, -1, 7844, 7839, 22067, -1, 22067, 7839, 22068, -1, 22068, 7859, 22065, -1, 7839, 7859, 22068, -1, 22067, 22069, 7844, -1, 22069, 7847, 7844, -1, 22069, 22070, 7847, -1, 22070, 7851, 7847, -1, 22070, 22071, 7851, -1, 22071, 7853, 7851, -1, 22071, 7855, 7853, -1, 22071, 22072, 7855, -1, 22072, 7849, 7855, -1, 22072, 22059, 7849, -1, 22066, 22064, 22063, -1, 22069, 22067, 22068, -1, 22073, 22063, 22062, -1, 22073, 22065, 22066, -1, 22073, 22066, 22063, -1, 22074, 22062, 22061, -1, 22074, 22061, 22060, -1, 22074, 22073, 22062, -1, 22074, 22065, 22073, -1, 22075, 22070, 22069, -1, 22075, 22068, 22065, -1, 22075, 22069, 22068, -1, 22076, 22060, 22059, -1, 22076, 22059, 22072, -1, 22076, 22065, 22074, -1, 22076, 22074, 22060, -1, 22077, 22072, 22071, -1, 22077, 22071, 22070, -1, 22077, 22070, 22075, -1, 22077, 22065, 22076, -1, 22077, 22076, 22072, -1, 22077, 22075, 22065, -1, 22078, 7653, 7659, -1, 22079, 7653, 22078, -1, 22080, 7646, 22079, -1, 22079, 7646, 7653, -1, 7637, 22081, 22082, -1, 7637, 7641, 22081, -1, 7641, 22083, 22081, -1, 7641, 7644, 22083, -1, 7644, 22080, 22083, -1, 7644, 7646, 22080, -1, 7669, 7645, 22084, -1, 22084, 7645, 22085, -1, 22085, 7637, 22082, -1, 7645, 7637, 22085, -1, 7654, 7649, 22086, -1, 22086, 7649, 22087, -1, 22087, 7669, 22084, -1, 7649, 7669, 22087, -1, 22088, 7661, 22089, -1, 7663, 7661, 22088, -1, 22089, 7657, 22090, -1, 7661, 7657, 22089, -1, 22090, 7654, 22086, -1, 7657, 7654, 22090, -1, 22088, 7665, 7663, -1, 22091, 7665, 22088, -1, 22078, 7659, 22091, -1, 22091, 7659, 7665, -1, 22085, 22082, 22081, -1, 22090, 22086, 22087, -1, 22092, 22081, 22083, -1, 22092, 22084, 22085, -1, 22092, 22085, 22081, -1, 22093, 22083, 22080, -1, 22093, 22080, 22079, -1, 22093, 22092, 22083, -1, 22093, 22084, 22092, -1, 22094, 22089, 22090, -1, 22094, 22087, 22084, -1, 22094, 22090, 22087, -1, 22095, 22079, 22078, -1, 22095, 22078, 22091, -1, 22095, 22084, 22093, -1, 22095, 22093, 22079, -1, 22096, 22091, 22088, -1, 22096, 22088, 22089, -1, 22096, 22089, 22094, -1, 22096, 22084, 22095, -1, 22096, 22095, 22091, -1, 22096, 22094, 22084, -1, 7611, 22097, 22098, -1, 7611, 7587, 22097, -1, 7587, 22099, 22097, -1, 7587, 7579, 22099, -1, 7579, 22100, 22099, -1, 7579, 7583, 22100, -1, 7583, 22101, 22100, -1, 7583, 7586, 22101, -1, 7586, 22102, 22101, -1, 7586, 7588, 22102, -1, 22103, 22104, 7601, -1, 22104, 7595, 7601, -1, 22104, 22102, 7595, -1, 22102, 7588, 7595, -1, 22105, 22106, 7605, -1, 22106, 7607, 7605, -1, 22106, 22103, 7607, -1, 22103, 7601, 7607, -1, 22105, 7603, 22107, -1, 7605, 7603, 22105, -1, 22107, 7599, 22108, -1, 7603, 7599, 22107, -1, 22108, 7596, 22109, -1, 7599, 7596, 22108, -1, 7596, 22110, 22109, -1, 7596, 7591, 22110, -1, 7591, 22098, 22110, -1, 7591, 7611, 22098, -1, 22097, 22099, 22100, -1, 22108, 22109, 22110, -1, 22111, 22098, 22097, -1, 22111, 22100, 22101, -1, 22111, 22097, 22100, -1, 22112, 22101, 22102, -1, 22112, 22102, 22104, -1, 22112, 22111, 22101, -1, 22112, 22098, 22111, -1, 22113, 22107, 22108, -1, 22113, 22110, 22098, -1, 22113, 22108, 22110, -1, 22114, 22104, 22103, -1, 22114, 22103, 22106, -1, 22114, 22098, 22112, -1, 22114, 22112, 22104, -1, 22115, 22105, 22107, -1, 22115, 22106, 22105, -1, 22115, 22107, 22113, -1, 22115, 22098, 22114, -1, 22115, 22114, 22106, -1, 22115, 22113, 22098, -1, 7361, 22116, 22117, -1, 7361, 7337, 22116, -1, 7337, 22118, 22116, -1, 7337, 7329, 22118, -1, 7329, 22119, 22118, -1, 7329, 7333, 22119, -1, 7333, 22120, 22119, -1, 7333, 7336, 22120, -1, 7336, 22121, 22120, -1, 7336, 7338, 22121, -1, 22121, 7345, 22122, -1, 7338, 7345, 22121, -1, 22122, 7351, 22123, -1, 7345, 7351, 22122, -1, 22123, 7357, 22124, -1, 7351, 7357, 22123, -1, 22124, 7355, 22125, -1, 7357, 7355, 22124, -1, 22125, 7353, 22126, -1, 7355, 7353, 22125, -1, 22126, 7349, 22127, -1, 7353, 7349, 22126, -1, 22127, 7346, 22128, -1, 7349, 7346, 22127, -1, 7346, 22129, 22128, -1, 7346, 7341, 22129, -1, 7341, 22117, 22129, -1, 7341, 7361, 22117, -1, 22116, 22118, 22119, -1, 22127, 22128, 22129, -1, 22130, 22117, 22116, -1, 22130, 22119, 22120, -1, 22130, 22116, 22119, -1, 22131, 22120, 22121, -1, 22131, 22121, 22122, -1, 22131, 22130, 22120, -1, 22131, 22117, 22130, -1, 22132, 22126, 22127, -1, 22132, 22129, 22117, -1, 22132, 22127, 22129, -1, 22133, 22122, 22123, -1, 22133, 22123, 22124, -1, 22133, 22117, 22131, -1, 22133, 22131, 22122, -1, 22134, 22125, 22126, -1, 22134, 22124, 22125, -1, 22134, 22126, 22132, -1, 22134, 22117, 22133, -1, 22134, 22133, 22124, -1, 22134, 22132, 22117, -1, 7304, 22135, 22136, -1, 7304, 7311, 22135, -1, 7311, 22137, 22135, -1, 7311, 7317, 22137, -1, 7295, 22138, 22139, -1, 7295, 7299, 22138, -1, 7299, 22140, 22138, -1, 7299, 7302, 22140, -1, 7302, 22136, 22140, -1, 7302, 7304, 22136, -1, 7327, 7303, 22141, -1, 22141, 7303, 22142, -1, 22142, 7295, 22139, -1, 7303, 7295, 22142, -1, 7312, 7307, 22143, -1, 22143, 7307, 22144, -1, 22144, 7327, 22141, -1, 7307, 7327, 22144, -1, 22145, 7319, 22146, -1, 7321, 7319, 22145, -1, 22146, 7315, 22147, -1, 7319, 7315, 22146, -1, 22147, 7312, 22143, -1, 7315, 7312, 22147, -1, 7317, 22148, 22137, -1, 7317, 7323, 22148, -1, 7323, 22145, 22148, -1, 7323, 7321, 22145, -1, 22142, 22139, 22138, -1, 22147, 22143, 22144, -1, 22149, 22138, 22140, -1, 22149, 22141, 22142, -1, 22149, 22142, 22138, -1, 22150, 22140, 22136, -1, 22150, 22136, 22135, -1, 22150, 22149, 22140, -1, 22150, 22141, 22149, -1, 22151, 22146, 22147, -1, 22151, 22144, 22141, -1, 22151, 22147, 22144, -1, 22152, 22135, 22137, -1, 22152, 22137, 22148, -1, 22152, 22141, 22150, -1, 22152, 22150, 22135, -1, 22153, 22148, 22145, -1, 22153, 22145, 22146, -1, 22153, 22146, 22151, -1, 22153, 22141, 22152, -1, 22153, 22152, 22148, -1, 22153, 22151, 22141, -1, 7221, 22154, 22155, -1, 7221, 7197, 22154, -1, 7197, 22156, 22154, -1, 7197, 7189, 22156, -1, 7198, 22157, 7196, -1, 7196, 22158, 7193, -1, 22157, 22158, 7196, -1, 7193, 22159, 7189, -1, 22158, 22159, 7193, -1, 22159, 22156, 7189, -1, 22160, 22161, 7211, -1, 22161, 7205, 7211, -1, 22161, 22157, 7205, -1, 22157, 7198, 7205, -1, 22162, 22163, 7215, -1, 22163, 7217, 7215, -1, 22163, 22160, 7217, -1, 22160, 7211, 7217, -1, 22164, 22165, 7206, -1, 7206, 22165, 7209, -1, 7209, 22166, 7213, -1, 22165, 22166, 7209, -1, 7213, 22162, 7215, -1, 22166, 22162, 7213, -1, 7206, 22167, 22164, -1, 7206, 7201, 22167, -1, 7201, 22155, 22167, -1, 7201, 7221, 22155, -1, 22154, 22156, 22159, -1, 22165, 22164, 22167, -1, 22168, 22155, 22154, -1, 22168, 22159, 22158, -1, 22168, 22154, 22159, -1, 22169, 22158, 22157, -1, 22169, 22157, 22161, -1, 22169, 22168, 22158, -1, 22169, 22155, 22168, -1, 22170, 22166, 22165, -1, 22170, 22167, 22155, -1, 22170, 22165, 22167, -1, 22171, 22161, 22160, -1, 22171, 22160, 22163, -1, 22171, 22155, 22169, -1, 22171, 22169, 22161, -1, 22172, 22162, 22166, -1, 22172, 22163, 22162, -1, 22172, 22166, 22170, -1, 22172, 22155, 22171, -1, 22172, 22171, 22163, -1, 22172, 22170, 22155, -1, 22173, 7147, 7153, -1, 22174, 7147, 22173, -1, 22175, 7140, 22174, -1, 22174, 7140, 7147, -1, 7140, 22175, 7138, -1, 7138, 22176, 7135, -1, 22175, 22176, 7138, -1, 7135, 22177, 7131, -1, 22176, 22177, 7135, -1, 22177, 22178, 7131, -1, 7163, 7139, 22179, -1, 22179, 7139, 22180, -1, 22180, 7131, 22178, -1, 7139, 7131, 22180, -1, 7148, 7143, 22181, -1, 22181, 7143, 22182, -1, 22182, 7163, 22179, -1, 7143, 7163, 22182, -1, 22183, 7148, 22181, -1, 22184, 7151, 22183, -1, 22183, 7151, 7148, -1, 22185, 7155, 22184, -1, 22184, 7155, 7151, -1, 22185, 7157, 7155, -1, 22185, 7159, 7157, -1, 22186, 7159, 22185, -1, 22173, 7153, 22186, -1, 22186, 7153, 7159, -1, 22180, 22178, 22177, -1, 22183, 22181, 22182, -1, 22187, 22177, 22176, -1, 22187, 22179, 22180, -1, 22187, 22180, 22177, -1, 22188, 22176, 22175, -1, 22188, 22175, 22174, -1, 22188, 22187, 22176, -1, 22188, 22179, 22187, -1, 22189, 22184, 22183, -1, 22189, 22182, 22179, -1, 22189, 22183, 22182, -1, 22190, 22174, 22173, -1, 22190, 22173, 22186, -1, 22190, 22179, 22188, -1, 22190, 22188, 22174, -1, 22191, 22186, 22185, -1, 22191, 22185, 22184, -1, 22191, 22184, 22189, -1, 22191, 22179, 22190, -1, 22191, 22190, 22186, -1, 22191, 22189, 22179, -1, 6997, 22192, 22193, -1, 6997, 6973, 22192, -1, 6973, 22194, 22192, -1, 6973, 6965, 22194, -1, 6965, 22195, 22194, -1, 6965, 6969, 22195, -1, 6969, 22196, 22195, -1, 6969, 6972, 22196, -1, 6972, 22197, 22196, -1, 6972, 6974, 22197, -1, 22198, 22199, 6987, -1, 22199, 6981, 6987, -1, 22199, 22197, 6981, -1, 22197, 6974, 6981, -1, 22200, 22201, 6991, -1, 22201, 6993, 6991, -1, 22201, 22198, 6993, -1, 22198, 6987, 6993, -1, 22200, 6989, 22202, -1, 6991, 6989, 22200, -1, 22202, 6985, 22203, -1, 6989, 6985, 22202, -1, 22203, 6982, 22204, -1, 6985, 6982, 22203, -1, 6982, 22205, 22204, -1, 6982, 6977, 22205, -1, 6977, 22193, 22205, -1, 6977, 6997, 22193, -1, 22192, 22194, 22195, -1, 22203, 22204, 22205, -1, 22206, 22193, 22192, -1, 22206, 22195, 22196, -1, 22206, 22192, 22195, -1, 22207, 22196, 22197, -1, 22207, 22197, 22199, -1, 22207, 22206, 22196, -1, 22207, 22193, 22206, -1, 22208, 22202, 22203, -1, 22208, 22205, 22193, -1, 22208, 22203, 22205, -1, 22209, 22199, 22198, -1, 22209, 22198, 22201, -1, 22209, 22193, 22207, -1, 22209, 22207, 22199, -1, 22210, 22200, 22202, -1, 22210, 22201, 22200, -1, 22210, 22202, 22208, -1, 22210, 22193, 22209, -1, 22210, 22209, 22201, -1, 22210, 22208, 22193, -1, 22211, 6923, 6929, -1, 22212, 6923, 22211, -1, 22213, 6916, 22212, -1, 22212, 6916, 6923, -1, 6907, 22214, 22215, -1, 6907, 6911, 22214, -1, 6911, 22216, 22214, -1, 6911, 6914, 22216, -1, 6914, 22213, 22216, -1, 6914, 6916, 22213, -1, 6939, 6915, 22217, -1, 22217, 6915, 22218, -1, 22218, 6907, 22215, -1, 6915, 6907, 22218, -1, 6924, 6919, 22219, -1, 22219, 6919, 22220, -1, 22220, 6939, 22217, -1, 6919, 6939, 22220, -1, 22221, 6931, 22222, -1, 6933, 6931, 22221, -1, 22222, 6927, 22223, -1, 6931, 6927, 22222, -1, 22223, 6924, 22219, -1, 6927, 6924, 22223, -1, 22221, 6935, 6933, -1, 22224, 6935, 22221, -1, 22211, 6929, 22224, -1, 22224, 6929, 6935, -1, 22218, 22215, 22214, -1, 22223, 22219, 22220, -1, 22225, 22214, 22216, -1, 22225, 22217, 22218, -1, 22225, 22218, 22214, -1, 22226, 22216, 22213, -1, 22226, 22213, 22212, -1, 22226, 22225, 22216, -1, 22226, 22217, 22225, -1, 22227, 22222, 22223, -1, 22227, 22220, 22217, -1, 22227, 22223, 22220, -1, 22228, 22212, 22211, -1, 22228, 22211, 22224, -1, 22228, 22217, 22226, -1, 22228, 22226, 22212, -1, 22229, 22224, 22221, -1, 22229, 22221, 22222, -1, 22229, 22222, 22227, -1, 22229, 22217, 22228, -1, 22229, 22228, 22224, -1, 22229, 22227, 22217, -1, 22230, 6781, 6787, -1, 22230, 22231, 6781, -1, 22231, 6774, 6781, -1, 22231, 22232, 6774, -1, 22232, 6772, 6774, -1, 22232, 22233, 6772, -1, 22233, 6769, 6772, -1, 22233, 22234, 6769, -1, 22234, 6765, 6769, -1, 22234, 22235, 6765, -1, 6797, 6773, 22236, -1, 22236, 6773, 22237, -1, 22237, 6765, 22235, -1, 6773, 6765, 22237, -1, 6782, 6777, 22238, -1, 22238, 6777, 22239, -1, 22239, 6797, 22236, -1, 6777, 6797, 22239, -1, 22238, 22240, 6782, -1, 6782, 22240, 6785, -1, 6785, 22241, 6789, -1, 22240, 22241, 6785, -1, 6789, 22242, 6791, -1, 22241, 22242, 6789, -1, 22242, 6793, 6791, -1, 22242, 22243, 6793, -1, 22243, 6787, 6793, -1, 22243, 22230, 6787, -1, 22237, 22235, 22234, -1, 22240, 22238, 22239, -1, 22244, 22234, 22233, -1, 22244, 22236, 22237, -1, 22244, 22237, 22234, -1, 22245, 22233, 22232, -1, 22245, 22232, 22231, -1, 22245, 22244, 22233, -1, 22245, 22236, 22244, -1, 22246, 22241, 22240, -1, 22246, 22239, 22236, -1, 22246, 22240, 22239, -1, 22247, 22231, 22230, -1, 22247, 22230, 22243, -1, 22247, 22236, 22245, -1, 22247, 22245, 22231, -1, 22248, 22243, 22242, -1, 22248, 22242, 22241, -1, 22248, 22241, 22246, -1, 22248, 22236, 22247, -1, 22248, 22247, 22243, -1, 22248, 22246, 22236, -1, 6739, 22249, 22250, -1, 6739, 6715, 22249, -1, 6715, 22251, 22249, -1, 6715, 6707, 22251, -1, 22252, 6714, 6716, -1, 22252, 22253, 6714, -1, 22253, 6711, 6714, -1, 22253, 22254, 6711, -1, 22254, 6707, 6711, -1, 22254, 22251, 6707, -1, 22255, 22256, 6729, -1, 6729, 22256, 6723, -1, 6723, 22252, 6716, -1, 22256, 22252, 6723, -1, 22257, 22258, 6733, -1, 6733, 22258, 6735, -1, 6735, 22255, 6729, -1, 22258, 22255, 6735, -1, 22259, 22260, 6724, -1, 6724, 22260, 6727, -1, 6727, 22261, 6731, -1, 22260, 22261, 6727, -1, 6731, 22257, 6733, -1, 22261, 22257, 6731, -1, 6724, 22262, 22259, -1, 6724, 6719, 22262, -1, 6719, 22250, 22262, -1, 6719, 6739, 22250, -1, 22249, 22251, 22254, -1, 22260, 22259, 22262, -1, 22263, 22250, 22249, -1, 22263, 22254, 22253, -1, 22263, 22249, 22254, -1, 22264, 22253, 22252, -1, 22264, 22252, 22256, -1, 22264, 22263, 22253, -1, 22264, 22250, 22263, -1, 22265, 22261, 22260, -1, 22265, 22262, 22250, -1, 22265, 22260, 22262, -1, 22266, 22256, 22255, -1, 22266, 22255, 22258, -1, 22266, 22250, 22264, -1, 22266, 22264, 22256, -1, 22267, 22257, 22261, -1, 22267, 22258, 22257, -1, 22267, 22261, 22265, -1, 22267, 22250, 22266, -1, 22267, 22266, 22258, -1, 22267, 22265, 22250, -1, 6465, 22268, 22269, -1, 6465, 6441, 22268, -1, 6441, 22270, 22268, -1, 6441, 6433, 22270, -1, 22271, 6440, 6442, -1, 22271, 22272, 6440, -1, 22272, 6437, 6440, -1, 22272, 22273, 6437, -1, 22273, 6433, 6437, -1, 22273, 22270, 6433, -1, 22274, 22275, 6455, -1, 22275, 6449, 6455, -1, 22275, 22271, 6449, -1, 22271, 6442, 6449, -1, 22276, 22277, 6459, -1, 22277, 6461, 6459, -1, 22277, 22274, 6461, -1, 22274, 6455, 6461, -1, 22278, 22279, 6450, -1, 6450, 22279, 6453, -1, 6453, 22280, 6457, -1, 22279, 22280, 6453, -1, 6457, 22276, 6459, -1, 22280, 22276, 6457, -1, 6450, 22281, 22278, -1, 6450, 6445, 22281, -1, 6445, 22269, 22281, -1, 6445, 6465, 22269, -1, 22268, 22270, 22273, -1, 22279, 22278, 22281, -1, 22282, 22269, 22268, -1, 22282, 22273, 22272, -1, 22282, 22268, 22273, -1, 22283, 22272, 22271, -1, 22283, 22271, 22275, -1, 22283, 22282, 22272, -1, 22283, 22269, 22282, -1, 22284, 22280, 22279, -1, 22284, 22281, 22269, -1, 22284, 22279, 22281, -1, 22285, 22275, 22274, -1, 22285, 22274, 22277, -1, 22285, 22269, 22283, -1, 22285, 22283, 22275, -1, 22286, 22276, 22280, -1, 22286, 22277, 22276, -1, 22286, 22280, 22284, -1, 22286, 22269, 22285, -1, 22286, 22285, 22277, -1, 22286, 22284, 22269, -1, 22287, 6391, 6397, -1, 22288, 6391, 22287, -1, 22289, 6384, 22288, -1, 22288, 6384, 6391, -1, 22289, 6382, 6384, -1, 22289, 22290, 6382, -1, 22290, 6379, 6382, -1, 22290, 22291, 6379, -1, 22291, 6375, 6379, -1, 22291, 22292, 6375, -1, 6407, 6383, 22293, -1, 22293, 6383, 22294, -1, 22294, 6375, 22292, -1, 6383, 6375, 22294, -1, 6392, 6387, 22295, -1, 22295, 6387, 22296, -1, 22296, 6407, 22293, -1, 6387, 6407, 22296, -1, 22295, 22297, 6392, -1, 6392, 22297, 6395, -1, 6395, 22298, 6399, -1, 22297, 22298, 6395, -1, 6399, 22299, 6401, -1, 22298, 22299, 6399, -1, 22299, 6403, 6401, -1, 22300, 6403, 22299, -1, 22287, 6397, 22300, -1, 22300, 6397, 6403, -1, 22294, 22292, 22291, -1, 22297, 22295, 22296, -1, 22301, 22291, 22290, -1, 22301, 22293, 22294, -1, 22301, 22294, 22291, -1, 22302, 22290, 22289, -1, 22302, 22289, 22288, -1, 22302, 22301, 22290, -1, 22302, 22293, 22301, -1, 22303, 22298, 22297, -1, 22303, 22296, 22293, -1, 22303, 22297, 22296, -1, 22304, 22288, 22287, -1, 22304, 22287, 22300, -1, 22304, 22293, 22302, -1, 22304, 22302, 22288, -1, 22305, 22300, 22299, -1, 22305, 22299, 22298, -1, 22305, 22298, 22303, -1, 22305, 22293, 22304, -1, 22305, 22304, 22300, -1, 22305, 22303, 22293, -1, 22306, 6201, 6207, -1, 22306, 22307, 6201, -1, 22307, 6194, 6201, -1, 22307, 22308, 6194, -1, 22308, 6192, 6194, -1, 22308, 22309, 6192, -1, 22309, 6189, 6192, -1, 22309, 22310, 6189, -1, 22310, 6185, 6189, -1, 22310, 22311, 6185, -1, 6217, 6193, 22312, -1, 22312, 6193, 22313, -1, 22313, 6185, 22311, -1, 6193, 6185, 22313, -1, 6202, 6197, 22314, -1, 22314, 6197, 22315, -1, 22315, 6217, 22312, -1, 6197, 6217, 22315, -1, 22314, 22316, 6202, -1, 6202, 22316, 6205, -1, 6205, 22317, 6209, -1, 22316, 22317, 6205, -1, 6209, 22318, 6211, -1, 22317, 22318, 6209, -1, 22318, 6213, 6211, -1, 22318, 22319, 6213, -1, 22319, 6207, 6213, -1, 22319, 22306, 6207, -1, 22313, 22311, 22310, -1, 22316, 22314, 22315, -1, 22320, 22310, 22309, -1, 22320, 22312, 22313, -1, 22320, 22313, 22310, -1, 22321, 22309, 22308, -1, 22321, 22308, 22307, -1, 22321, 22320, 22309, -1, 22321, 22312, 22320, -1, 22322, 22317, 22316, -1, 22322, 22315, 22312, -1, 22322, 22316, 22315, -1, 22323, 22307, 22306, -1, 22323, 22306, 22319, -1, 22323, 22312, 22321, -1, 22323, 22321, 22307, -1, 22324, 22319, 22318, -1, 22324, 22318, 22317, -1, 22324, 22317, 22322, -1, 22324, 22312, 22323, -1, 22324, 22323, 22319, -1, 22324, 22322, 22312, -1, 6183, 22325, 22326, -1, 6183, 6159, 22325, -1, 6159, 22327, 22325, -1, 6159, 6151, 22327, -1, 22328, 6158, 6160, -1, 22328, 22329, 6158, -1, 22329, 6155, 6158, -1, 22329, 22330, 6155, -1, 22330, 6151, 6155, -1, 22330, 22327, 6151, -1, 22331, 22332, 6173, -1, 6173, 22332, 6167, -1, 6167, 22328, 6160, -1, 22332, 22328, 6167, -1, 22333, 22334, 6177, -1, 6177, 22334, 6179, -1, 6179, 22331, 6173, -1, 22334, 22331, 6179, -1, 22335, 22336, 6168, -1, 6168, 22336, 6171, -1, 6171, 22337, 6175, -1, 22336, 22337, 6171, -1, 6175, 22333, 6177, -1, 22337, 22333, 6175, -1, 6168, 22338, 22335, -1, 6168, 6163, 22338, -1, 6163, 22326, 22338, -1, 6163, 6183, 22326, -1, 22325, 22327, 22330, -1, 22336, 22335, 22338, -1, 22339, 22326, 22325, -1, 22339, 22330, 22329, -1, 22339, 22325, 22330, -1, 22340, 22329, 22328, -1, 22340, 22328, 22332, -1, 22340, 22339, 22329, -1, 22340, 22326, 22339, -1, 22341, 22337, 22336, -1, 22341, 22338, 22326, -1, 22341, 22336, 22338, -1, 22342, 22332, 22331, -1, 22342, 22331, 22334, -1, 22342, 22326, 22340, -1, 22342, 22340, 22332, -1, 22343, 22333, 22337, -1, 22343, 22334, 22333, -1, 22343, 22337, 22341, -1, 22343, 22326, 22342, -1, 22343, 22342, 22334, -1, 22343, 22341, 22326, -1, 5969, 22344, 22345, -1, 5969, 5945, 22344, -1, 5945, 22346, 22344, -1, 5945, 5937, 22346, -1, 22347, 5944, 5946, -1, 22347, 22348, 5944, -1, 22348, 5941, 5944, -1, 22348, 22349, 5941, -1, 22349, 5937, 5941, -1, 22349, 22346, 5937, -1, 22350, 22351, 5959, -1, 5959, 22351, 5953, -1, 5953, 22347, 5946, -1, 22351, 22347, 5953, -1, 22352, 22353, 5963, -1, 5963, 22353, 5965, -1, 5965, 22350, 5959, -1, 22353, 22350, 5965, -1, 22354, 22355, 5954, -1, 5954, 22355, 5957, -1, 5957, 22356, 5961, -1, 22355, 22356, 5957, -1, 5961, 22352, 5963, -1, 22356, 22352, 5961, -1, 5954, 22357, 22354, -1, 5954, 5949, 22357, -1, 5949, 22345, 22357, -1, 5949, 5969, 22345, -1, 22344, 22346, 22349, -1, 22355, 22354, 22357, -1, 22358, 22345, 22344, -1, 22358, 22349, 22348, -1, 22358, 22344, 22349, -1, 22359, 22348, 22347, -1, 22359, 22347, 22351, -1, 22359, 22358, 22348, -1, 22359, 22345, 22358, -1, 22360, 22356, 22355, -1, 22360, 22357, 22345, -1, 22360, 22355, 22357, -1, 22361, 22351, 22350, -1, 22361, 22350, 22353, -1, 22361, 22345, 22359, -1, 22361, 22359, 22351, -1, 22362, 22352, 22356, -1, 22362, 22353, 22352, -1, 22362, 22356, 22360, -1, 22362, 22345, 22361, -1, 22362, 22361, 22353, -1, 22362, 22360, 22345, -1, 22363, 5919, 5925, -1, 22363, 22364, 5919, -1, 22364, 5912, 5919, -1, 22364, 22365, 5912, -1, 22365, 5910, 5912, -1, 22365, 22366, 5910, -1, 22366, 5907, 5910, -1, 22366, 22367, 5907, -1, 22367, 5903, 5907, -1, 22367, 22368, 5903, -1, 5935, 5911, 22369, -1, 22369, 5911, 22370, -1, 22370, 5903, 22368, -1, 5911, 5903, 22370, -1, 5920, 5915, 22371, -1, 22371, 5915, 22372, -1, 22372, 5935, 22369, -1, 5915, 5935, 22372, -1, 22371, 22373, 5920, -1, 5920, 22373, 5923, -1, 5923, 22374, 5927, -1, 22373, 22374, 5923, -1, 5927, 22375, 5929, -1, 22374, 22375, 5927, -1, 22375, 5931, 5929, -1, 22375, 22376, 5931, -1, 22376, 5925, 5931, -1, 22376, 22363, 5925, -1, 22370, 22368, 22367, -1, 22373, 22371, 22372, -1, 22377, 22367, 22366, -1, 22377, 22369, 22370, -1, 22377, 22370, 22367, -1, 22378, 22366, 22365, -1, 22378, 22365, 22364, -1, 22378, 22377, 22366, -1, 22378, 22369, 22377, -1, 22379, 22374, 22373, -1, 22379, 22372, 22369, -1, 22379, 22373, 22372, -1, 22380, 22364, 22363, -1, 22380, 22363, 22376, -1, 22380, 22369, 22378, -1, 22380, 22378, 22364, -1, 22381, 22376, 22375, -1, 22381, 22375, 22374, -1, 22381, 22374, 22379, -1, 22381, 22369, 22380, -1, 22381, 22380, 22376, -1, 22381, 22379, 22369, -1, 22382, 5885, 5891, -1, 22383, 5885, 22382, -1, 22384, 5878, 22383, -1, 22383, 5878, 5885, -1, 22384, 5876, 5878, -1, 22384, 22385, 5876, -1, 22385, 5873, 5876, -1, 22385, 22386, 5873, -1, 22386, 5869, 5873, -1, 22386, 22387, 5869, -1, 5901, 5877, 22388, -1, 22388, 5877, 22389, -1, 22389, 5869, 22387, -1, 5877, 5869, 22389, -1, 5886, 5881, 22390, -1, 22390, 5881, 22391, -1, 22391, 5901, 22388, -1, 5881, 5901, 22391, -1, 22390, 22392, 5886, -1, 22392, 5889, 5886, -1, 22392, 22393, 5889, -1, 22393, 5893, 5889, -1, 22393, 22394, 5893, -1, 22394, 5895, 5893, -1, 22394, 5897, 5895, -1, 22395, 5897, 22394, -1, 22382, 5891, 22395, -1, 22395, 5891, 5897, -1, 22389, 22387, 22386, -1, 22392, 22390, 22391, -1, 22396, 22386, 22385, -1, 22396, 22388, 22389, -1, 22396, 22389, 22386, -1, 22397, 22385, 22384, -1, 22397, 22384, 22383, -1, 22397, 22396, 22385, -1, 22397, 22388, 22396, -1, 22398, 22393, 22392, -1, 22398, 22391, 22388, -1, 22398, 22392, 22391, -1, 22399, 22383, 22382, -1, 22399, 22382, 22395, -1, 22399, 22388, 22397, -1, 22399, 22397, 22383, -1, 22400, 22395, 22394, -1, 22400, 22394, 22393, -1, 22400, 22393, 22398, -1, 22400, 22388, 22399, -1, 22400, 22399, 22395, -1, 22400, 22398, 22388, -1, 5843, 22401, 22402, -1, 5843, 5819, 22401, -1, 5819, 22403, 22401, -1, 5819, 5811, 22403, -1, 22404, 5818, 5820, -1, 22404, 22405, 5818, -1, 22405, 5815, 5818, -1, 22405, 22406, 5815, -1, 22406, 5811, 5815, -1, 22406, 22403, 5811, -1, 22407, 22408, 5833, -1, 22408, 5827, 5833, -1, 22408, 22404, 5827, -1, 22404, 5820, 5827, -1, 22409, 22410, 5837, -1, 22410, 5839, 5837, -1, 22410, 22407, 5839, -1, 22407, 5833, 5839, -1, 22411, 22412, 5828, -1, 5828, 22412, 5831, -1, 5831, 22413, 5835, -1, 22412, 22413, 5831, -1, 5835, 22409, 5837, -1, 22413, 22409, 5835, -1, 5828, 22414, 22411, -1, 5828, 5823, 22414, -1, 5823, 22402, 22414, -1, 5823, 5843, 22402, -1, 22401, 22403, 22406, -1, 22412, 22411, 22414, -1, 22415, 22402, 22401, -1, 22415, 22406, 22405, -1, 22415, 22401, 22406, -1, 22416, 22405, 22404, -1, 22416, 22404, 22408, -1, 22416, 22415, 22405, -1, 22416, 22402, 22415, -1, 22417, 22413, 22412, -1, 22417, 22414, 22402, -1, 22417, 22412, 22414, -1, 22418, 22408, 22407, -1, 22418, 22407, 22410, -1, 22418, 22402, 22416, -1, 22418, 22416, 22408, -1, 22419, 22409, 22413, -1, 22419, 22410, 22409, -1, 22419, 22413, 22417, -1, 22419, 22402, 22418, -1, 22419, 22418, 22410, -1, 22419, 22417, 22402, -1, 5653, 22420, 22421, -1, 5653, 5629, 22420, -1, 5629, 22422, 22420, -1, 5629, 5621, 22422, -1, 22423, 5628, 5630, -1, 22423, 22424, 5628, -1, 22424, 5625, 5628, -1, 22424, 22425, 5625, -1, 22425, 5621, 5625, -1, 22425, 22422, 5621, -1, 22426, 22427, 5643, -1, 22427, 5637, 5643, -1, 22427, 22423, 5637, -1, 22423, 5630, 5637, -1, 22428, 22429, 5647, -1, 22429, 5649, 5647, -1, 22429, 22426, 5649, -1, 22426, 5643, 5649, -1, 22430, 22431, 5638, -1, 5638, 22431, 5641, -1, 5641, 22432, 5645, -1, 22431, 22432, 5641, -1, 5645, 22428, 5647, -1, 22432, 22428, 5645, -1, 5638, 22433, 22430, -1, 5638, 5633, 22433, -1, 5633, 22421, 22433, -1, 5633, 5653, 22421, -1, 22420, 22422, 22425, -1, 22431, 22430, 22433, -1, 22434, 22421, 22420, -1, 22434, 22425, 22424, -1, 22434, 22420, 22425, -1, 22435, 22424, 22423, -1, 22435, 22423, 22427, -1, 22435, 22434, 22424, -1, 22435, 22421, 22434, -1, 22436, 22432, 22431, -1, 22436, 22433, 22421, -1, 22436, 22431, 22433, -1, 22437, 22427, 22426, -1, 22437, 22426, 22429, -1, 22437, 22421, 22435, -1, 22437, 22435, 22427, -1, 22438, 22428, 22432, -1, 22438, 22429, 22428, -1, 22438, 22432, 22436, -1, 22438, 22421, 22437, -1, 22438, 22437, 22429, -1, 22438, 22436, 22421, -1, 22439, 5603, 5609, -1, 22440, 5603, 22439, -1, 22441, 5596, 22440, -1, 22440, 5596, 5603, -1, 22441, 5594, 5596, -1, 22441, 22442, 5594, -1, 22442, 5591, 5594, -1, 22442, 22443, 5591, -1, 22443, 5587, 5591, -1, 22443, 22444, 5587, -1, 5619, 5595, 22445, -1, 22445, 5595, 22446, -1, 22446, 5587, 22444, -1, 5595, 5587, 22446, -1, 5604, 5599, 22447, -1, 22447, 5599, 22448, -1, 22448, 5619, 22445, -1, 5599, 5619, 22448, -1, 22447, 22449, 5604, -1, 22449, 5607, 5604, -1, 22449, 22450, 5607, -1, 22450, 5611, 5607, -1, 22450, 22451, 5611, -1, 22451, 5613, 5611, -1, 22451, 5615, 5613, -1, 22452, 5615, 22451, -1, 22439, 5609, 22452, -1, 22452, 5609, 5615, -1, 22446, 22444, 22443, -1, 22449, 22447, 22448, -1, 22453, 22443, 22442, -1, 22453, 22445, 22446, -1, 22453, 22446, 22443, -1, 22454, 22442, 22441, -1, 22454, 22441, 22440, -1, 22454, 22453, 22442, -1, 22454, 22445, 22453, -1, 22455, 22450, 22449, -1, 22455, 22448, 22445, -1, 22455, 22449, 22448, -1, 22456, 22440, 22439, -1, 22456, 22439, 22452, -1, 22456, 22445, 22454, -1, 22456, 22454, 22440, -1, 22457, 22452, 22451, -1, 22457, 22451, 22450, -1, 22457, 22450, 22455, -1, 22457, 22445, 22456, -1, 22457, 22456, 22452, -1, 22457, 22455, 22445, -1, 22458, 5437, 5443, -1, 22459, 5437, 22458, -1, 22460, 5430, 22459, -1, 22459, 5430, 5437, -1, 5430, 22460, 5428, -1, 5428, 22461, 5425, -1, 22460, 22461, 5428, -1, 22461, 22462, 5425, -1, 22462, 5421, 5425, -1, 22462, 22463, 5421, -1, 5453, 5429, 22464, -1, 22464, 5429, 22465, -1, 22465, 5421, 22463, -1, 5429, 5421, 22465, -1, 5438, 5433, 22466, -1, 22466, 5433, 22467, -1, 22467, 5453, 22464, -1, 5433, 5453, 22467, -1, 22466, 22468, 5438, -1, 5438, 22468, 5441, -1, 5441, 22469, 5445, -1, 22468, 22469, 5441, -1, 5445, 22470, 5447, -1, 22469, 22470, 5445, -1, 22470, 5449, 5447, -1, 22471, 5449, 22470, -1, 22458, 5443, 22471, -1, 22471, 5443, 5449, -1, 22465, 22463, 22462, -1, 22468, 22466, 22467, -1, 22472, 22462, 22461, -1, 22472, 22464, 22465, -1, 22472, 22465, 22462, -1, 22473, 22461, 22460, -1, 22473, 22460, 22459, -1, 22473, 22472, 22461, -1, 22473, 22464, 22472, -1, 22474, 22469, 22468, -1, 22474, 22467, 22464, -1, 22474, 22468, 22467, -1, 22475, 22459, 22458, -1, 22475, 22458, 22471, -1, 22475, 22464, 22473, -1, 22475, 22473, 22459, -1, 22476, 22471, 22470, -1, 22476, 22470, 22469, -1, 22476, 22469, 22474, -1, 22476, 22464, 22475, -1, 22476, 22475, 22471, -1, 22476, 22474, 22464, -1, 5395, 22477, 22478, -1, 5395, 5371, 22477, -1, 5371, 22479, 22477, -1, 5371, 5363, 22479, -1, 22480, 5370, 5372, -1, 22480, 22481, 5370, -1, 22481, 5367, 5370, -1, 22481, 22482, 5367, -1, 22482, 5363, 5367, -1, 22482, 22479, 5363, -1, 22483, 22484, 5385, -1, 22484, 5379, 5385, -1, 22484, 22480, 5379, -1, 22480, 5372, 5379, -1, 22485, 22486, 5389, -1, 22486, 5391, 5389, -1, 22486, 22483, 5391, -1, 22483, 5385, 5391, -1, 22487, 22488, 5380, -1, 5380, 22488, 5383, -1, 5383, 22489, 5387, -1, 22488, 22489, 5383, -1, 5387, 22485, 5389, -1, 22489, 22485, 5387, -1, 5380, 22490, 22487, -1, 5380, 5375, 22490, -1, 5375, 22478, 22490, -1, 5375, 5395, 22478, -1, 22477, 22479, 22482, -1, 22488, 22487, 22490, -1, 22491, 22478, 22477, -1, 22491, 22482, 22481, -1, 22491, 22477, 22482, -1, 22492, 22481, 22480, -1, 22492, 22480, 22484, -1, 22492, 22491, 22481, -1, 22492, 22478, 22491, -1, 22493, 22489, 22488, -1, 22493, 22490, 22478, -1, 22493, 22488, 22490, -1, 22494, 22484, 22483, -1, 22494, 22483, 22486, -1, 22494, 22478, 22492, -1, 22494, 22492, 22484, -1, 22495, 22485, 22489, -1, 22495, 22486, 22485, -1, 22495, 22489, 22493, -1, 22495, 22478, 22494, -1, 22495, 22494, 22486, -1, 22495, 22493, 22478, -1, 5229, 22496, 22497, -1, 5229, 5205, 22496, -1, 5205, 22498, 22496, -1, 5205, 5197, 22498, -1, 5206, 22499, 5204, -1, 5204, 22500, 5201, -1, 22499, 22500, 5204, -1, 5201, 22501, 5197, -1, 22500, 22501, 5201, -1, 22501, 22498, 5197, -1, 22502, 22503, 5219, -1, 22503, 5213, 5219, -1, 22503, 22499, 5213, -1, 22499, 5206, 5213, -1, 22504, 22505, 5223, -1, 22505, 5225, 5223, -1, 22505, 22502, 5225, -1, 22502, 5219, 5225, -1, 22506, 22507, 5214, -1, 5214, 22507, 5217, -1, 5217, 22508, 5221, -1, 22507, 22508, 5217, -1, 5221, 22504, 5223, -1, 22508, 22504, 5221, -1, 5214, 22509, 22506, -1, 5214, 5209, 22509, -1, 5209, 22497, 22509, -1, 5209, 5229, 22497, -1, 22496, 22498, 22501, -1, 22507, 22506, 22509, -1, 22510, 22497, 22496, -1, 22510, 22501, 22500, -1, 22510, 22496, 22501, -1, 22511, 22500, 22499, -1, 22511, 22499, 22503, -1, 22511, 22510, 22500, -1, 22511, 22497, 22510, -1, 22512, 22508, 22507, -1, 22512, 22509, 22497, -1, 22512, 22507, 22509, -1, 22513, 22503, 22502, -1, 22513, 22502, 22505, -1, 22513, 22497, 22511, -1, 22513, 22511, 22503, -1, 22514, 22504, 22508, -1, 22514, 22505, 22504, -1, 22514, 22508, 22512, -1, 22514, 22497, 22513, -1, 22514, 22513, 22505, -1, 22514, 22512, 22497, -1, 22515, 5155, 5161, -1, 22516, 5155, 22515, -1, 22517, 5148, 22516, -1, 22516, 5148, 5155, -1, 5148, 22517, 5146, -1, 5146, 22518, 5143, -1, 22517, 22518, 5146, -1, 5143, 22519, 5139, -1, 22518, 22519, 5143, -1, 22519, 22520, 5139, -1, 5171, 5147, 22521, -1, 22521, 5147, 22522, -1, 22522, 5139, 22520, -1, 5147, 5139, 22522, -1, 5156, 5151, 22523, -1, 22523, 5151, 22524, -1, 22524, 5171, 22521, -1, 5151, 5171, 22524, -1, 22523, 22525, 5156, -1, 5156, 22525, 5159, -1, 5159, 22526, 5163, -1, 22525, 22526, 5159, -1, 5163, 22527, 5165, -1, 22526, 22527, 5163, -1, 22527, 5167, 5165, -1, 22528, 5167, 22527, -1, 22515, 5161, 22528, -1, 22528, 5161, 5167, -1, 22522, 22520, 22519, -1, 22525, 22523, 22524, -1, 22529, 22519, 22518, -1, 22529, 22521, 22522, -1, 22529, 22522, 22519, -1, 22530, 22518, 22517, -1, 22530, 22517, 22516, -1, 22530, 22529, 22518, -1, 22530, 22521, 22529, -1, 22531, 22526, 22525, -1, 22531, 22524, 22521, -1, 22531, 22525, 22524, -1, 22532, 22516, 22515, -1, 22532, 22515, 22528, -1, 22532, 22521, 22530, -1, 22532, 22530, 22516, -1, 22533, 22528, 22527, -1, 22533, 22527, 22526, -1, 22533, 22526, 22531, -1, 22533, 22521, 22532, -1, 22533, 22532, 22528, -1, 22533, 22531, 22521, -1 - ] - } - } - DEF fl_hub Shape { - appearance Appearance { - material Material { - } - texture ImageTexture { - url [ - "textures/metal.jpg" - ] - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.072857857 -0.043728992 -0.050280035, -0.075672284 -0.038655207 -0.050279707, -0.072794572 -0.043690741 -0.050068542, -0.072879434 -0.043741748 -0.050502479, 0.043453261 -0.072391272 -0.04960309, 0.038497895 -0.075356662 -0.049722388, 0.038411647 -0.075187773 -0.049603373, -0.075694874 -0.038666353 -0.050502315, -0.075606674 -0.038621455 -0.050068468, 0.043550938 -0.072553813 -0.049722344, -0.075002491 -0.038312703 -0.049527273, -0.077442378 -0.03310512 -0.049527109, -0.074804172 -0.038211435 -0.049502209, 0.038569987 -0.075497568 -0.049880803, -0.077237815 -0.033017546 -0.04950203, 0.043632329 -0.072689459 -0.049880639, 0.038624331 -0.075603783 -0.05007045, 0.043693706 -0.072791576 -0.050070152, -0.077636838 -0.033188045 -0.049600974, 0.043731675 -0.072854966 -0.050281733, 0.038657919 -0.075669616 -0.050281882, -0.075190604 -0.03840895 -0.049601197, -0.077811033 -0.03326273 -0.049720138, 0.038669258 -0.075691909 -0.050504237, 0.043744668 -0.072876588 -0.050504297, -0.075359493 -0.038495228 -0.049720466, 0.038214251 -0.074801415 -0.049504369, 0.033107907 -0.077439502 -0.049529701, 0.033020452 -0.077234909 -0.049504653, 0.03831552 -0.074999422 -0.049529254, -0.075500354 -0.038567245 -0.049878597, -0.077956587 -0.033324853 -0.049878508, -0.078066096 -0.033371776 -0.050068066, 0.033190861 -0.077633709 -0.049603403, -0.078157216 -0.033410683 -0.050501883, -0.078134209 -0.033400744 -0.050279588, 0.033265576 -0.077808157 -0.049722806, -0.07952112 -0.027743012 -0.04952684, 0.033327788 -0.077953666 -0.049881101, -0.079311192 -0.027669653 -0.049501821, 0.081714272 -0.02340208 -0.050501451, 0.079926401 -0.028923705 -0.050501719, 0.081690013 -0.023395047 -0.050279111, 0.033374533 -0.07806319 -0.050070539, -0.079720691 -0.02781269 -0.049600646, 0.033403754 -0.078131303 -0.050282046, 0.033413529 -0.07815437 -0.050504461, -0.079899713 -0.027875111 -0.04971981, 0.027745917 -0.079518288 -0.049529716, 0.027672574 -0.079308182 -0.049504533, -0.080049291 -0.02792725 -0.049878299, 0.027815402 -0.07971783 -0.049603596, -0.080161765 -0.027966529 -0.050067678, -0.08025527 -0.027999148 -0.050501704, -0.080231503 -0.027990848 -0.050279453, 0.027877912 -0.079896674 -0.049723029, -0.08122921 -0.02225168 -0.049526513, 0.027930066 -0.080046341 -0.049881279, -0.081014693 -0.022192821 -0.049501196, 0.027969226 -0.080158696 -0.050070554, -0.081433088 -0.02230759 -0.049600407, 0.027993768 -0.08022882 -0.0502823, 0.028001994 -0.08025229 -0.050504699, -0.081616119 -0.022357628 -0.049719542, 0.022254556 -0.081226364 -0.049529746, 0.022195637 -0.081011787 -0.049504831, -0.081768721 -0.022399411 -0.049877957, 0.022310302 -0.081430182 -0.049603581, -0.08188349 -0.022430882 -0.05006741, -0.081978962 -0.022457063 -0.050501317, -0.081954971 -0.022450343 -0.050278962, 0.022360429 -0.081612974 -0.049722806, -0.082558557 -0.016656309 -0.049526021, 0.022402048 -0.081765786 -0.049881294, -0.082340464 -0.01661256 -0.049501091, -0.082765609 -0.016698346 -0.049600065, 0.022433683 -0.081880644 -0.050070718, 0.022459835 -0.08197616 -0.050504625, 0.022453219 -0.081951872 -0.050282091, -0.082951576 -0.016735688 -0.049719229, 0.016659334 -0.082555711 -0.049529731, -0.08310698 -0.01676701 -0.049877554, 0.016615272 -0.082337469 -0.049504846, 0.016700983 -0.082762778 -0.049603745, -0.083223611 -0.016790822 -0.050067022, -0.083320543 -0.016810328 -0.050501049, -0.083295956 -0.016805321 -0.050278395, 0.016738608 -0.082948744 -0.049722984, -0.083502769 -0.01098381 -0.049525797, 0.016769946 -0.083104014 -0.04988125, -0.083282381 -0.010954663 -0.049500808, 0.01679346 -0.083220646 -0.050071031, -0.083712459 -0.011011198 -0.049599618, 0.016813025 -0.083317712 -0.050504759, 0.016808212 -0.083293155 -0.050282344, -0.08390063 -0.011036053 -0.049719006, 0.010986343 -0.083500043 -0.049529657, 0.010957345 -0.08327949 -0.049504817, -0.084057286 -0.011056677 -0.049877122, 0.011014 -0.083709568 -0.049603775, -0.084175602 -0.011072129 -0.050066739, -0.084248841 -0.01108171 -0.050278187, 0.011038646 -0.083897486 -0.04972288, -0.08427377 -0.011085063 -0.050500661, -0.084058121 -0.0052597523 -0.049525529, -0.083835959 -0.0052457601 -0.049500361, 0.011059389 -0.084054545 -0.04988122, 0.01107499 -0.084172681 -0.050070912, -0.084269047 -0.0052728504 -0.04959923, 0.011084571 -0.08424601 -0.050282285, 0.011087924 -0.084270954 -0.050504863, -0.084458113 -0.0052847862 -0.049718603, 0.0052623302 -0.0840552 -0.049530059, 0.0052485317 -0.083832979 -0.049504787, -0.084616214 -0.0052945614 -0.049876899, 0.0052755028 -0.084266037 -0.04960382, -0.084735096 -0.0053019673 -0.050066397, -0.08483398 -0.0053081661 -0.050500378, -0.084809065 -0.0053066462 -0.050278068, 0.0052873939 -0.084455371 -0.049723119, -0.084221199 0.0004889667 -0.049525172, -0.08399874 0.0004877001 -0.049500242, 0.0052973032 -0.084613219 -0.049881324, 0.0053047836 -0.084732234 -0.050070927, -0.084432602 0.00049030781 -0.049599141, 0.0053094625 -0.084806085 -0.050282419, -0.084622309 0.00049136579 -0.049718156, 0.005311057 -0.084830999 -0.050504938, -0.00048628449 -0.084218308 -0.049529806, -0.00048495829 -0.083995789 -0.049504772, -0.084780619 0.00049223006 -0.049876541, -0.00048732758 -0.084429726 -0.049604014, -0.084899813 0.00049296021 -0.050066113, -0.084998682 0.00049357116 -0.050500214, -0.084973618 0.00049333274 -0.050277621, -0.00048853457 -0.084619433 -0.049723148, -0.083991691 0.0062352717 -0.049524978, -0.083769754 0.0062188059 -0.049499884, -0.00048953295 -0.084777579 -0.049881309, -0.0004901886 -0.084896713 -0.050070897, -0.084202468 0.0062509626 -0.049598634, -0.00049051642 -0.084970549 -0.050282344, -0.00049065053 -0.084995762 -0.050504968, -0.084391624 0.0062649995 -0.049717963, -0.0062325746 -0.083988756 -0.049529836, -0.084549576 0.0062766224 -0.049876228, -0.0062160194 -0.083766982 -0.049504906, -0.0062481314 -0.084199592 -0.04960382, -0.084668219 0.006285578 -0.050065786, -0.084767058 0.0062928647 -0.050499707, -0.084742054 0.0062909424 -0.050277203, -0.006262213 -0.084388852 -0.049722984, -0.083370507 0.011952519 -0.049524501, -0.083150372 0.011921212 -0.049499512, -0.0062738955 -0.084546536 -0.049881265, -0.083579689 0.011982501 -0.04959847, -0.0062827617 -0.084665298 -0.050070912, -0.0062900037 -0.084764108 -0.050504968, -0.0062880963 -0.084739119 -0.0502823, -0.083767399 0.012009442 -0.04971768, -0.011949867 -0.083367839 -0.049529865, -0.083924159 0.012031913 -0.049875796, -0.011918068 -0.083147347 -0.049504936, -0.011979803 -0.083577037 -0.049603805, -0.084042087 0.012048826 -0.050065458, -0.084140271 0.012062877 -0.050499484, -0.084115282 0.012059405 -0.050277025, -0.012006581 -0.083764747 -0.049722999, -0.082360804 0.017614156 -0.049524218, -0.082143173 0.01756753 -0.049499094, -0.080966815 0.023193404 -0.049523786, -0.012029126 -0.083921343 -0.049881309, -0.012046024 -0.08403942 -0.050070927, -0.082567319 0.017658368 -0.049598187, -0.081170142 0.023251638 -0.049597815, -0.012060106 -0.084137395 -0.050504729, -0.01205647 -0.084112495 -0.050282344, -0.082752869 0.017697915 -0.049717411, -0.081352293 0.023304 -0.049716935, -0.017611295 -0.082357958 -0.049529627, -0.017564788 -0.082140416 -0.049504891, -0.082907692 0.017730966 -0.049875513, -0.081504494 0.023347452 -0.049875274, -0.017655477 -0.082564503 -0.04960376, -0.083024174 0.017756015 -0.050065294, -0.081619129 0.023380324 -0.050064832, -0.017695099 -0.082750097 -0.049723044, -0.017728284 -0.082904786 -0.049881428, -0.083096415 0.017771527 -0.050276652, -0.081690162 0.023400798 -0.050276354, -0.081714198 0.023407668 -0.050498754, -0.083120972 0.017776698 -0.050499082, -0.017753214 -0.083021253 -0.050070986, -0.017773867 -0.083118096 -0.050504863, -0.017768815 -0.083093479 -0.05028224, -0.023190916 -0.080963969 -0.049529836, -0.023129642 -0.080749944 -0.049504668, -0.023249134 -0.081167161 -0.04960376, -0.023301229 -0.081349418 -0.049722865, -0.02334483 -0.081501633 -0.049881339, -0.023377642 -0.081616178 -0.050070956, -0.080752999 0.023132369 -0.049498975, -0.023397952 -0.081687361 -0.050282255, -0.023404911 -0.081711233 -0.05050464, -0.028662026 -0.079192683 -0.049529642, -0.028586254 -0.078983501 -0.049504608, -0.028733969 -0.079391465 -0.049603567, -0.028798461 -0.079569742 -0.04972288, 0.08096683 -0.02318798 -0.049526572, 0.079195529 -0.02865912 -0.049526811, 0.080752864 -0.023126557 -0.049501583, -0.028852567 -0.079718471 -0.049881145, 0.078986153 -0.028583556 -0.049501657, -0.028893009 -0.079830736 -0.050070733, 0.079394177 -0.028731018 -0.049600631, 0.081169978 -0.023246095 -0.049600422, -0.028918251 -0.079900056 -0.050282151, -0.028926656 -0.07992363 -0.050504461, 0.081352249 -0.023298234 -0.049719676, 0.079572439 -0.028795555 -0.049719945, -0.033999711 -0.077052042 -0.049529463, 0.079721242 -0.028849453 -0.049878225, -0.033909917 -0.076848567 -0.049504578, 0.081504628 -0.023341864 -0.049877897, -0.034085035 -0.077245459 -0.049603477, 0.079833344 -0.028889954 -0.050067946, 0.081619039 -0.023374736 -0.05006741, 0.079902828 -0.028915137 -0.050279304, -0.034161612 -0.077419072 -0.049722716, 0.077054784 -0.033996835 -0.049527004, 0.076851338 -0.033906966 -0.049502045, -0.034225494 -0.077563703 -0.049881011, 0.077248156 -0.034082249 -0.049600869, -0.034273505 -0.077672809 -0.050070465, -0.034313589 -0.077763304 -0.050504565, -0.034303457 -0.077740446 -0.050281957, 0.077421784 -0.034158677 -0.049720213, 0.077566609 -0.034222677 -0.049878672, -0.039178863 -0.074552283 -0.049529418, -0.039075419 -0.07435514 -0.049504235, -0.039277196 -0.074739382 -0.049603298, 0.077675551 -0.034270763 -0.050068185, 0.077743188 -0.034300685 -0.050279453, 0.07776615 -0.034310743 -0.050501898, -0.039365411 -0.074907035 -0.049722731, 0.074555054 -0.039176062 -0.049527451, 0.074357927 -0.039072409 -0.049502388, -0.039439186 -0.07504721 -0.049880728, 0.074742064 -0.039274305 -0.049601242, -0.0394945 -0.075152874 -0.050070405, 0.074909925 -0.039362416 -0.049720421, -0.039540604 -0.075240478 -0.050504163, -0.039528891 -0.075218216 -0.050281942, 0.075050265 -0.039436266 -0.049878731, -0.044175372 -0.071704686 -0.04952915, -0.044058755 -0.071515352 -0.049504116, -0.044286206 -0.071884662 -0.049603179, 0.07515581 -0.039491609 -0.050068364, 0.075221047 -0.039525971 -0.050279826, 0.075243294 -0.039537668 -0.05050236, -0.044385597 -0.07204625 -0.049722314, 0.071707502 -0.044172511 -0.049527705, 0.071518153 -0.04405576 -0.049502775, -0.044468656 -0.072180957 -0.049880609, -0.044531271 -0.072282404 -0.050070167, 0.071887568 -0.044283271 -0.0496016, -0.044583216 -0.072366685 -0.050504044, -0.044570073 -0.072345212 -0.050281808, 0.072048947 -0.044382781 -0.049720854, -0.048965916 -0.068522945 -0.04952918, 0.072183684 -0.044465885 -0.049879238, -0.048836514 -0.068341866 -0.049503922, 0.072285056 -0.044528261 -0.050068632, -0.049088731 -0.068694904 -0.04960303, 0.072348207 -0.044567049 -0.050280228, 0.072369441 -0.044580266 -0.050502509, -0.04919906 -0.068849266 -0.049722105, 0.068525702 -0.048962891 -0.049527839, 0.068344593 -0.048833668 -0.049502745, -0.049290985 -0.068978041 -0.049880475, 0.068697602 -0.049085811 -0.049601838, -0.04936026 -0.069074988 -0.050070062, -0.049417913 -0.069155484 -0.050503999, -0.049403444 -0.069135055 -0.050281644, 0.068851963 -0.049196079 -0.049721256, 0.068980753 -0.049288109 -0.049879342, -0.053528205 -0.065021589 -0.049528778, -0.053386614 -0.064849928 -0.049503669, 0.069077715 -0.04935734 -0.050068855, -0.053662539 -0.065184996 -0.049602702, 0.069137856 -0.049400479 -0.050280422, 0.069158271 -0.049415097 -0.050502807, -0.053782865 -0.065331221 -0.049721956, 0.06502445 -0.05352518 -0.049528182, -0.053883642 -0.065453485 -0.049880266, 0.064852759 -0.053383797 -0.049503431, 0.065187633 -0.053659603 -0.049602121, -0.05395934 -0.06554541 -0.050069809, -0.054006279 -0.065602526 -0.050281286, 0.065334097 -0.053780124 -0.049721465, -0.054022223 -0.065621957 -0.050503775, -0.05784066 -0.061217219 -0.049528539, -0.057687938 -0.061055526 -0.049503475, 0.065456256 -0.05388087 -0.049879685, 0.065548137 -0.053956389 -0.050069228, -0.057986021 -0.061370835 -0.049602568, 0.065605357 -0.054003358 -0.050280765, 0.065624744 -0.054019347 -0.050503045, 0.06121996 -0.05783774 -0.049528643, -0.058116093 -0.06150873 -0.049721658, -0.058224842 -0.061623782 -0.049880132, 0.061058298 -0.057685062 -0.049503431, 0.061373547 -0.057983041 -0.049602449, -0.058306783 -0.061710253 -0.050069645, -0.058357537 -0.061764047 -0.050281182, 0.061511412 -0.058113322 -0.049721539, -0.058374703 -0.061782226 -0.050503537, -0.061883703 -0.057127222 -0.04952845, 0.061626539 -0.058221832 -0.049880043, -0.061720282 -0.056976289 -0.049503535, 0.061713234 -0.058303699 -0.050069422, -0.062039003 -0.057270572 -0.049602315, 0.061766893 -0.058354452 -0.050280988, -0.062178403 -0.057399303 -0.049721539, 0.061785191 -0.058371782 -0.050503358, 0.057129949 -0.061880797 -0.049528569, -0.062294573 -0.057506695 -0.049879655, 0.05697903 -0.061717361 -0.049503669, 0.057273373 -0.062036112 -0.049602658, -0.062382296 -0.057587489 -0.050069347, -0.062455088 -0.057654619 -0.050503165, -0.06243661 -0.057637751 -0.050280854, 0.057402223 -0.062175557 -0.049721763, -0.06563817 -0.052770942 -0.049528167, 0.057509527 -0.062291831 -0.049880132, -0.06546472 -0.052631602 -0.049503013, 0.057590261 -0.06237933 -0.05006972, -0.065802753 -0.052903444 -0.049602166, 0.057640374 -0.062433645 -0.050281271, -0.065950826 -0.053022131 -0.04972133, 0.057657465 -0.062452018 -0.050503567, 0.052773893 -0.065635234 -0.049529105, -0.066074073 -0.053121388 -0.049879536, 0.052634224 -0.065461785 -0.049503803, 0.052906245 -0.065800026 -0.049602821, -0.066166863 -0.053196117 -0.050069138, 0.053025126 -0.065947846 -0.049722046, -0.066244036 -0.053258166 -0.050503209, -0.06622459 -0.05324243 -0.050280809, 0.053124249 -0.066071048 -0.049880281, -0.069086537 -0.048168704 -0.049527839, -0.068903968 -0.048041508 -0.049502715, -0.069259778 -0.048289701 -0.049602062, 0.053198829 -0.066164017 -0.050069869, 0.053260997 -0.06624122 -0.05050391, 0.053245232 -0.066221684 -0.050281405, -0.06941542 -0.048398048 -0.049720913, 0.048171371 -0.069083586 -0.04952918, 0.048044115 -0.068901107 -0.049504012, -0.069545269 -0.048488617 -0.049879208, 0.048292324 -0.069257066 -0.049603075, -0.069643095 -0.04855673 -0.050068989, -0.069724381 -0.048613369 -0.050502837, -0.069703639 -0.048599064 -0.050280333, 0.048400804 -0.069412619 -0.049722299, -0.07221292 -0.04334183 -0.049527586, 0.048491374 -0.069542348 -0.049880549, -0.07202211 -0.043227196 -0.049502537, -0.072393969 -0.043450713 -0.049601555, 0.048559412 -0.069640145 -0.050070047, 0.048616186 -0.069721282 -0.050504044, 0.048601791 -0.069700927 -0.050281525, -0.072556615 -0.043548018 -0.049720705, 0.043344602 -0.072209895 -0.049529225, 0.043229997 -0.072019234 -0.049504057, -0.072692439 -0.043629557 -0.049879193, 0.027930096 -0.080051959 0.049871877, 0.033327788 -0.077959314 0.0498721, 0.027877897 -0.079902679 0.049713746, -0.07806617 -0.033377513 0.050064072, -0.075606629 -0.038626984 0.050063848, -0.077956662 -0.03333059 0.049874336, 0.033265471 -0.077813759 0.049713805, -0.075500488 -0.038572773 0.049874321, 0.033374563 -0.078068942 0.050061688, 0.027969271 -0.080164447 0.050061569, -0.075694889 -0.038672119 0.050497726, -0.075672522 -0.038660541 0.050275177, -0.078157187 -0.033416316 0.050497919, -0.078134328 -0.033406571 0.05027549, 0.033413455 -0.078160018 0.05049555, 0.033403605 -0.078136906 0.050272837, 0.028001994 -0.080258071 0.050495386, 0.027993709 -0.08023423 0.050272867, -0.074804485 -0.038216934 0.049497858, -0.07221289 -0.04334718 0.049522623, -0.072021931 -0.043232709 0.049497545, 0.033107847 -0.077444866 0.049520537, 0.03831546 -0.075005054 0.049520895, 0.033020422 -0.077240437 0.049495459, -0.075002432 -0.038318217 0.049522817, 0.038214251 -0.074806839 0.049495742, -0.075190827 -0.038414285 0.049596906, -0.072394028 -0.043456078 0.049596593, 0.038411722 -0.07519339 0.049594805, 0.033190995 -0.077639282 0.04959476, -0.072556779 -0.04355368 0.049715757, 0.038498029 -0.075362325 0.04971385, -0.075359702 -0.038500905 0.049716011, 0.038570017 -0.07550332 0.049872309, -0.072692603 -0.043635249 0.049874038, -0.072794646 -0.043696553 0.050063416, 0.038624182 -0.075609475 0.050061941, -0.07285808 -0.04373455 0.050274819, 0.038657933 -0.075675294 0.05027318, -0.072879389 -0.043747455 0.050497338, 0.038669318 -0.075697601 0.050495595, -0.069086656 -0.048174158 0.049522355, -0.068904117 -0.048046932 0.049497023, 0.043344468 -0.072215423 0.049521029, 0.043229952 -0.072024763 0.049495697, -0.069259971 -0.048295066 0.04959628, 0.043453217 -0.072396666 0.049595073, -0.06941542 -0.04840377 0.04971534, 0.043550834 -0.072559357 0.049714208, -0.069545478 -0.04849419 0.049873888, 0.043632373 -0.072695151 0.049872443, -0.06964314 -0.048562363 0.050063223, 0.043693602 -0.072797239 0.050062135, -0.069703639 -0.048604682 0.050274611, 0.043731689 -0.072860777 0.050273433, -0.069724277 -0.048618972 0.050497308, 0.043744639 -0.07288219 0.050495744, -0.06563808 -0.05277653 0.049521953, 0.048171327 -0.069088981 0.049521074, -0.065464675 -0.052637234 0.049496904, -0.065802917 -0.052908868 0.049595982, 0.04804416 -0.068906695 0.04949604, 0.048292369 -0.069262505 0.049595252, -0.065950513 -0.053028032 0.049715221, 0.048400894 -0.069418103 0.049714327, -0.066074178 -0.053127021 0.049873531, 0.048491403 -0.069548145 0.049872637, -0.066166952 -0.053201899 0.050063103, 0.048559517 -0.069646016 0.050062075, -0.066224664 -0.053248167 0.050274417, 0.048616141 -0.069727078 0.050496086, 0.048601881 -0.069706574 0.050273284, -0.066244066 -0.053263858 0.050496981, -0.061883837 -0.057132825 0.049521685, 0.052773893 -0.065640852 0.049521342, -0.061720341 -0.056981817 0.049496531, -0.062039077 -0.057276204 0.049595684, 0.052634403 -0.065467462 0.049496189, 0.05290629 -0.065805569 0.049595356, -0.062178478 -0.057404876 0.049714893, 0.053024948 -0.065953195 0.049714297, -0.062294498 -0.057512194 0.049873516, 0.053124204 -0.066076875 0.04987286, -0.062382355 -0.057593182 0.050062895, 0.053198919 -0.066169605 0.050062358, -0.062436461 -0.057643324 0.050274149, -0.062454864 -0.057660386 0.050496757, 0.053261101 -0.066246912 0.050496325, 0.053245232 -0.066227362 0.050273702, -0.057840914 -0.061222702 0.04952164, 0.057130098 -0.061886534 0.049521551, -0.05768773 -0.061061025 0.049496353, 0.056979075 -0.061722845 0.049496397, -0.057985783 -0.061376452 0.049595624, 0.057273507 -0.062041655 0.049595475, -0.058116093 -0.061514348 0.049714625, 0.057402149 -0.062181145 0.049714655, -0.058224797 -0.061629504 0.04987289, 0.057509437 -0.062297314 0.049872801, -0.05830659 -0.061716095 0.050062642, 0.057590306 -0.062385052 0.050062552, -0.058374718 -0.061787933 0.050496444, -0.058357567 -0.061769783 0.050273821, 0.057657406 -0.062457755 0.05049634, 0.057640463 -0.062439337 0.05027397, -0.05352807 -0.065027088 0.049521342, -0.053386644 -0.064855322 0.049496293, 0.06122008 -0.057843357 0.04952167, 0.061058253 -0.057690576 0.049496576, -0.05366239 -0.065190434 0.049595281, 0.061373726 -0.057988688 0.049595729, -0.053782895 -0.065337062 0.049714535, 0.061511561 -0.058118954 0.049714938, -0.053883493 -0.065459222 0.049872831, 0.061626494 -0.058227673 0.049873054, -0.053959325 -0.065551117 0.050062522, 0.061713308 -0.058309466 0.05006282, -0.054006383 -0.065608233 0.050273702, -0.054022253 -0.065627605 0.05049631, 0.061785206 -0.058377534 0.050496489, 0.061766863 -0.058360249 0.050273925, -0.048965961 -0.068528414 0.049521133, -0.04883647 -0.068347588 0.04949601, 0.06502448 -0.053530797 0.049522102, -0.049088821 -0.068700492 0.049595028, 0.064852625 -0.053389326 0.049496934, 0.065187603 -0.05366528 0.049595952, -0.04919894 -0.068854868 0.049714267, 0.065334141 -0.053785741 0.049714953, -0.049291059 -0.068983704 0.049872547, 0.065456361 -0.053886458 0.049873516, -0.049360365 -0.069080546 0.050062358, 0.065548271 -0.053962156 0.050063163, -0.049403399 -0.069140688 0.050273508, 0.065605432 -0.054009095 0.050274432, -0.049417973 -0.069161162 0.050496161, 0.065624744 -0.054025054 0.050496757, 0.068525732 -0.048968628 0.049522191, 0.068344474 -0.048839211 0.049497128, -0.044175401 -0.071710244 0.049520969, -0.044058681 -0.071520939 0.049495935, -0.044286266 -0.07189022 0.049595103, 0.068697706 -0.049091414 0.049596339, -0.044385716 -0.072051808 0.049714148, 0.068851933 -0.049201921 0.0497154, -0.044468775 -0.072186664 0.049872428, 0.068980843 -0.049293846 0.049873769, -0.044531107 -0.072288066 0.05006218, 0.069077849 -0.049363166 0.050063282, -0.044570059 -0.072351024 0.050273299, -0.04458335 -0.072372362 0.050495937, 0.069158345 -0.04942067 0.050497308, 0.069137886 -0.049405962 0.050274551, -0.039178953 -0.074557617 0.049520865, 0.071707517 -0.044178009 0.049522519, 0.071518064 -0.044061288 0.049497381, -0.039075449 -0.074360758 0.049495667, -0.039277226 -0.074744985 0.049594879, 0.071887448 -0.044288918 0.049596623, -0.039365381 -0.074912876 0.049713954, 0.072048977 -0.044388384 0.049715564, -0.039439112 -0.075053021 0.049872085, 0.072183684 -0.044471562 0.049873829, -0.039494485 -0.075158477 0.050061956, 0.072285131 -0.044533998 0.05006364, -0.039540589 -0.075246066 0.05049555, -0.039528906 -0.075223908 0.050273016, 0.072369486 -0.044586018 0.050497264, 0.072348177 -0.0445728 0.050274774, 0.074554965 -0.039181575 0.049522907, 0.074358121 -0.039078057 0.049497634, -0.033999681 -0.077057645 0.049520552, -0.033909962 -0.07685405 0.049495637, -0.034084961 -0.077250957 0.049594685, 0.074742049 -0.039279908 0.049596876, -0.034161776 -0.077424526 0.049713984, 0.074909955 -0.039368093 0.049715847, -0.034225509 -0.077569455 0.049872085, 0.07505013 -0.039441854 0.049874276, -0.034273639 -0.077678442 0.050061822, 0.075155586 -0.039497241 0.050063923, -0.0343135 -0.077769011 0.050495505, -0.034303442 -0.077746183 0.050273001, 0.075243205 -0.039543226 0.050497636, 0.075220987 -0.039531633 0.050275117, 0.077054784 -0.034002379 0.049522996, 0.076851293 -0.033912554 0.049497902, -0.028661951 -0.079198226 0.049520642, -0.028586343 -0.078989029 0.04949519, -0.028734103 -0.079396784 0.049594551, 0.077248171 -0.034087718 0.049597293, 0.078986064 -0.028588861 0.049498245, 0.08096686 -0.023193434 0.049523681, 0.080752894 -0.023132175 0.049498439, -0.028798461 -0.07957536 0.049713597, 0.077421665 -0.034164265 0.04971607, -0.028852493 -0.079724118 0.049871907, 0.077566549 -0.034228235 0.04987447, -0.028892949 -0.079836309 0.050061747, 0.077675611 -0.034276396 0.050064176, -0.028926685 -0.079929411 0.050495431, -0.028918162 -0.079905823 0.050272837, 0.079926625 -0.028929532 0.050498217, 0.081714302 -0.023407608 0.050498649, 0.081690073 -0.023400784 0.050276071, 0.077766269 -0.034316242 0.050497919, 0.077743232 -0.034306243 0.05027549, -0.080966815 0.023187965 0.049526155, -0.08236064 0.017608538 0.049526036, -0.080753073 0.023126826 0.049501181, -0.023190841 -0.080969602 0.049520329, -0.023129508 -0.080755681 0.049495474, -0.082143202 0.017562091 0.049500823, 0.079195425 -0.028664649 0.049523517, -0.082567424 0.01765275 0.049600229, -0.023249045 -0.081172705 0.049594417, -0.081170052 0.023246214 0.049600229, 0.079394221 -0.028736502 0.049597487, 0.081170097 -0.023251638 0.049597725, -0.023301199 -0.081355035 0.049713627, -0.081352353 0.023298264 0.049719349, -0.082752869 0.017692372 0.04971914, 0.07957238 -0.028801218 0.049716488, 0.081352353 -0.023304045 0.049716905, -0.082907706 0.017725497 0.049877539, -0.0233448 -0.081507415 0.049871787, -0.081504658 0.023341849 0.049877718, -0.083024129 0.017750353 0.050067291, -0.023377568 -0.081621796 0.050061584, 0.079721242 -0.02885507 0.049874902, 0.081504613 -0.023347557 0.049875155, -0.081619248 0.023374721 0.050067544, -0.083120927 0.017771035 0.05050084, -0.083096504 0.017765671 0.05027853, -0.081714422 0.023401946 0.050501212, -0.081690341 0.023395106 0.050278604, -0.023397967 -0.081692904 0.050272733, -0.023404866 -0.081717014 0.050495341, 0.079833344 -0.028895676 0.050064519, 0.081619084 -0.023380414 0.050064772, -0.017611459 -0.082363486 0.049520224, -0.083370537 0.011946917 0.049525589, -0.083150268 0.011915326 0.049500689, 0.079902947 -0.028920785 0.050275654, -0.017564923 -0.082145631 0.049495086, -0.083579659 0.011977062 0.049599797, -0.017655656 -0.082569987 0.049594343, -0.083767533 0.012003824 0.049718738, -0.017695427 -0.082755417 0.049713567, -0.017728329 -0.082910404 0.049871787, -0.083924115 0.012026235 0.049877167, -0.084042192 0.012043178 0.050066873, -0.017753229 -0.083026946 0.050061509, -0.084115386 0.012053683 0.050277814, -0.017768696 -0.083099067 0.050272644, -0.084140226 0.012057245 0.050500587, -0.083991632 0.0062296987 0.049525261, -0.017774001 -0.083123654 0.050495371, -0.011949837 -0.083373085 0.049520269, -0.083769739 0.0062132627 0.049500272, -0.011918202 -0.083153039 0.049495354, -0.084202573 0.0062454343 0.049599394, -0.011979699 -0.083582431 0.049594313, -0.08439146 0.0062593818 0.049718603, -0.012006745 -0.08377026 0.049713448, -0.084549442 0.0062710643 0.049876824, -0.012029186 -0.083926812 0.049871579, -0.084668159 0.006279856 0.050066426, -0.012046114 -0.084045008 0.050061315, -0.084742025 0.0062852204 0.05027765, -0.084767118 0.0062871426 0.050500154, -0.01205647 -0.084118202 0.050272614, -0.012060091 -0.084143072 0.050495252, -0.08422111 0.00048342347 0.049524948, -0.083998725 0.00048220158 0.049500033, -0.0062325299 -0.083994374 0.049520344, -0.0062160939 -0.083772466 0.049495354, -0.084432572 0.00048474967 0.049599156, -0.006248042 -0.084205166 0.049594298, -0.084622204 0.00048570335 0.049718142, -0.0062622726 -0.084394321 0.049713597, -0.084780499 0.00048656762 0.049876407, -0.0062737912 -0.084552363 0.049871564, -0.084899709 0.00048731267 0.050066158, -0.0062827319 -0.084671244 0.05006139, -0.084973678 0.0004877001 0.050277323, -0.084998727 0.0004876703 0.050500035, -0.006289959 -0.084769994 0.050495148, -0.0062880814 -0.084744871 0.050272554, -0.084058031 -0.0052652359 0.049524695, -0.00048607588 -0.084224001 0.049520314, -0.08383581 -0.005251199 0.049499437, -0.084269091 -0.0052783191 0.049598768, -0.00048488379 -0.084001273 0.049495161, -0.00048737228 -0.08443521 0.049594373, -0.084458098 -0.0052902699 0.049717769, -0.00048846006 -0.084624961 0.049713463, -0.084616303 -0.0053000897 0.049876034, -0.00048935413 -0.08478336 0.049871594, -0.08473517 -0.0053076744 0.050066024, -0.0004901588 -0.084902257 0.050061181, -0.084808946 -0.0053121448 0.050276861, -0.00049051642 -0.085001588 0.050494999, -0.00049048662 -0.084976375 0.050272658, -0.084833965 -0.005313918 0.050499499, -0.083503067 -0.010989189 0.049524322, -0.083282292 -0.010960177 0.049499288, 0.0052624196 -0.084060758 0.049520314, 0.0052483231 -0.083838567 0.04949531, -0.083712608 -0.011016697 0.049598366, 0.0052754879 -0.084271654 0.049594209, -0.083900303 -0.011041626 0.049717695, 0.0052874237 -0.084460974 0.049713433, -0.084057495 -0.011062294 0.049875975, 0.0052973628 -0.084619045 0.049871683, -0.084175542 -0.011077911 0.050065354, 0.0053046942 -0.084737882 0.05006133, -0.084249005 -0.011087447 0.050276667, 0.0053093433 -0.084811717 0.050272703, -0.084273785 -0.011090711 0.050499335, 0.0053109825 -0.084836826 0.050495267, -0.082558423 -0.016662061 0.049523979, -0.082340479 -0.016618073 0.04949896, 0.010986477 -0.083505675 0.049520299, 0.010957405 -0.083285064 0.049495071, 0.011014104 -0.083715335 0.049594447, -0.082765788 -0.016703859 0.049598023, -0.082951561 -0.016741499 0.049717098, 0.011038661 -0.083903208 0.049713448, -0.083106846 -0.016772792 0.049875528, 0.011059374 -0.084060177 0.049871534, -0.083223477 -0.01679641 0.050065368, 0.01107493 -0.084178343 0.050061405, -0.083295926 -0.016811088 0.050276294, 0.011084571 -0.084251776 0.050272703, -0.083320692 -0.016815916 0.050498918, 0.01108779 -0.084276661 0.050495058, 0.016659126 -0.08256118 0.049520358, -0.08122924 -0.022257119 0.049523756, -0.081014574 -0.022198379 0.049498633, 0.016615108 -0.082343042 0.04949525, -0.081433252 -0.022313103 0.04959783, 0.016700983 -0.082768321 0.049594507, -0.081615955 -0.022363067 0.049717084, 0.016738579 -0.082954377 0.049713463, -0.081768721 -0.022405177 0.049875125, 0.016769826 -0.083109617 0.049871683, -0.08188346 -0.022436619 0.050064921, -0.081954718 -0.022456229 0.050275981, 0.01679334 -0.083226368 0.050061524, 0.016808063 -0.083298847 0.050272778, -0.081979111 -0.022462815 0.050498754, 0.01681298 -0.083323494 0.050495178, -0.079521134 -0.02774848 0.049523532, 0.022254422 -0.081231683 0.049520418, -0.079311088 -0.02767536 0.049498305, 0.022195533 -0.081017241 0.049495339, -0.079720706 -0.027818203 0.049597442, 0.022310406 -0.08143571 0.049594402, -0.079899848 -0.027880803 0.049716592, 0.02236034 -0.081618711 0.049713537, -0.080049351 -0.027932987 0.049874902, 0.022402197 -0.081771374 0.049871862, -0.08016181 -0.027972221 0.050064564, 0.022433683 -0.08188647 0.050061241, -0.080255315 -0.028004929 0.050498396, -0.080231473 -0.027996495 0.050275758, 0.022459865 -0.081981897 0.050495386, 0.022453219 -0.081957623 0.050272703, -0.077442363 -0.033110604 0.04952307, -0.077237844 -0.033023074 0.049498066, 0.027745679 -0.079523757 0.049520522, -0.077636689 -0.033193916 0.049597248, 0.02767238 -0.079313517 0.049495384, 0.02781558 -0.079723313 0.049594611, -0.077811137 -0.033268258 0.049716309, 0.04711172 0.071944267 0.063620269, 0.051812053 0.068636879 0.063619971, 0.051812097 0.068644077 -0.063612282, -0.063109547 0.0584189 0.063619316, -0.059066504 0.062510908 -0.063612461, -0.063109651 0.058426067 -0.063612685, -0.059066474 0.06250374 0.063619524, 0.042200834 0.074930444 0.06362018, 0.047111779 0.071951434 -0.063611984, 0.042200744 0.074937582 -0.063611925, -0.066870853 0.054073349 0.063619033, -0.066870809 0.054080486 -0.063612998, 0.037101388 0.077581763 0.063620269, 0.037101746 0.077588946 -0.063611791, 0.084072664 -0.018108785 0.063615084, 0.082675621 -0.023676515 -0.063617527, 0.084072635 -0.018101558 -0.06361714, 0.082675532 -0.023683637 0.063614666, -0.070333451 0.049486116 0.063618764, -0.070333391 0.049493089 -0.063613176, 0.03183651 0.079886585 0.063620657, 0.031836614 0.079893664 -0.063611582, 0.085094199 -0.01245296 0.063615382, 0.085094109 -0.012445658 -0.063616842, -0.073481858 0.044677705 0.063618839, -0.073482051 0.044685021 -0.063613519, 0.026429266 0.081834733 0.063620716, 0.02642937 0.081841752 -0.063611373, 0.085735664 -0.0067413598 0.063615575, 0.085735723 -0.006734252 -0.063616574, -0.07630223 0.039669856 0.063618183, -0.076302245 0.039676905 -0.063613787, 0.020904183 0.083417296 0.063620776, 0.020904198 0.083424389 -0.063611358, 0.085994199 -0.0009997189 0.063616037, 0.085994408 -0.00099271536 -0.063616127, -0.078781813 0.034484789 0.063617989, -0.078781754 0.034491956 -0.063614145, 0.01528582 0.084627166 0.063620865, 0.015285745 0.084634304 -0.063611209, 0.085868627 0.0047461241 0.063616291, 0.085868776 0.0047534704 -0.063616008, -0.080909342 0.029145911 0.063617751, -0.080909356 0.029153019 -0.063614488, 0.0095988214 0.085459188 0.063620746, -0.082675651 0.023676604 0.063617393, -0.082675561 0.023683622 -0.063614786, 0.0095987767 0.085466355 -0.063611284, 0.085359722 0.010471001 0.063616633, 0.085359767 0.010478169 -0.063615501, 0.0038688779 0.08590962 0.063620895, 0.0038691163 0.085916549 -0.063611209, 0.084469453 0.016148999 0.063617095, 0.084469557 0.016156048 -0.063615054, -0.0018779039 0.08597593 0.063620955, -0.0018780082 0.085983172 -0.063611344, 0.08320196 0.021754906 0.063617349, 0.083201945 0.021762073 -0.06361489, -0.0076164305 0.085658669 0.063621014, -0.0076165199 0.085665688 -0.063611165, 0.081562757 0.027263656 0.063617438, 0.081562892 0.027270705 -0.063614607, -0.013321072 0.084958509 0.063620761, -0.013321012 0.084965691 -0.063611254, 0.07955952 0.032650501 0.063617945, 0.079559445 0.032657713 -0.063614294, -0.018966079 0.083879009 0.063620836, -0.018966049 0.083886206 -0.063611344, 0.077200711 0.037891656 0.063618183, 0.077200815 0.037898704 -0.063614026, -0.024526566 0.082425117 0.063620627, -0.024526611 0.082432151 -0.063611552, 0.074497223 0.042963415 0.063618571, 0.074497357 0.042970389 -0.063613698, -0.029977441 0.080602691 0.063620478, -0.0299775 0.080609947 -0.063611507, 0.071460932 0.047843352 0.06361869, 0.071461022 0.047850579 -0.06361331, -0.035294443 0.078420311 0.063620493, -0.03529419 0.078427538 -0.063611597, 0.068105578 0.052509591 0.063619077, 0.068105698 0.052516639 -0.063613012, -0.040453702 0.075887889 0.063620254, -0.040453464 0.075894967 -0.063611776, 0.064446092 0.056941241 0.063619256, 0.064446107 0.056948543 -0.063612819, -0.045432404 0.073016539 0.063620225, -0.04543218 0.073023453 -0.06361182, 0.060498774 0.061118469 0.063619524, 0.060498729 0.061125845 -0.06361267, -0.050208181 0.069818825 0.063620001, -0.050208077 0.069825768 -0.063612103, 0.05628112 0.065022916 0.063619703, 0.056280911 0.065030187 -0.063612282, -0.054759622 0.066309333 0.063619837, -0.054759577 0.066316485 -0.063612238, 0.062108502 -0.017787173 -0.035858884, 0.05319123 -0.015232235 -0.051925018, 0.053399667 -0.014047265 -0.05185236, 0.062317222 -0.016602263 -0.035785839, 0.053354144 -0.012861833 -0.051638514, 0.06227161 -0.015416875 -0.035572141, 0.053057358 -0.011745021 -0.051296204, 0.061974779 -0.014300019 -0.035229921, 0.052526295 -0.010761529 -0.050845012, 0.061443642 -0.013316482 -0.034778655, 0.051791981 -0.0099684745 -0.050311297, 0.060709178 -0.012523428 -0.034245104, 0.050896987 -0.0094121546 -0.049726129, 0.059814394 -0.011967123 -0.033659682, 0.05881083 -0.011679769 -0.033057153, 0.049893305 -0.009124577 -0.04912363, 0.048839703 -0.0091228783 -0.048538268, 0.057757109 -0.011677936 -0.032472044, 0.047796905 -0.0094068348 -0.048004538, 0.056714162 -0.011961967 -0.031938255, 0.046825618 -0.0099603683 -0.047553495, 0.05574283 -0.012515202 -0.031487241, 0.045982376 -0.01075083 -0.04721126, 0.054899782 -0.013305679 -0.031144828, 0.045316204 -0.011732206 -0.046997488, 0.054233536 -0.014287144 -0.030931324, 0.044865638 -0.01284793 -0.046925023, 0.053783223 -0.015403017 -0.030858666, 0.068046495 -0.018389896 -0.02952373, 0.065124333 -0.018651158 -0.034425691, 0.065407038 -0.017111793 -0.034337848, 0.06782186 -0.019423977 -0.029565349, 0.068132967 -0.017345339 -0.029404327, 0.065383419 -0.015566021 -0.034078971, 0.068073794 -0.0163064 -0.029217944, 0.067947969 -0.01560618 -0.029054821, 0.065054566 -0.014091343 -0.033661842, 0.067757502 -0.014933199 -0.028862059, 0.067233205 -0.013756171 -0.02842471, 0.064436898 -0.012761414 -0.033107728, 0.066515014 -0.01273559 -0.027903512, 0.063561454 -0.011643201 -0.032443777, 0.065623313 -0.011898085 -0.027308613, 0.062472329 -0.010792732 -0.031704113, 0.064601094 -0.011284426 -0.026665375, 0.061223879 -0.01025255 -0.030925199, 0.06335485 -0.010888129 -0.025917485, 0.059878752 -0.010049894 -0.030146345, 0.061910853 -0.010822326 -0.025089264, 0.058504552 -0.010195002 -0.029406667, 0.060480729 -0.011148736 -0.024309948, 0.05716978 -0.010680154 -0.028742805, 0.05986236 -0.011428639 -0.023957908, 0.059281811 -0.011798561 -0.023582265, 0.055941805 -0.011481553 -0.028188914, 0.058253646 -0.012611151 -0.023140937, 0.05488205 -0.01255852 -0.027771965, 0.057372123 -0.013624609 -0.022812784, 0.054043666 -0.013857409 -0.027513117, 0.056671396 -0.014799401 -0.022610605, 0.0534686 -0.015313104 -0.027425542, 0.056178823 -0.016089514 -0.022542536, 0.055550978 -0.012240872 -0.029714718, 0.057021603 -0.011281356 -0.030378446, 0.054380879 -0.013645634 -0.029288903, 0.064583734 -0.017438605 -0.034743741, 0.06388244 -0.01636675 -0.034995422, 0.053893819 -0.014377043 -0.028323695, 0.063633606 -0.014555663 -0.034569055, 0.062893823 -0.012963027 -0.033905178, 0.061736047 -0.011744961 -0.033068821, 0.0602732 -0.011020437 -0.03214176, 0.058648616 -0.010860726 -0.031214744, 0.034120888 0.066392228 0.046967655, 0.033179104 0.06669572 0.046673119, 0.033014268 0.066364765 0.045616239, 0.034741938 0.066524625 0.047572196, 0.03425169 0.066955581 0.047765166, -0.0026709437 0.075832948 0.048413396, 0.0026584268 0.076781854 0.049009055, -0.0027043223 0.076780379 0.049009055, 0.034594327 0.066241995 0.047110945, 0.033982456 0.067047238 0.047717601, 0.031962126 0.070071757 0.049094886, 0.031471014 0.068940133 0.048334032, 0.033005059 0.06866017 0.048635006, 0.032638311 0.070318416 0.049281776, 0.031831563 0.071083084 0.049378663, -0.002643019 0.075041682 0.047621638, 0.002625525 0.075834587 0.048413187, 0.031629384 0.069954008 0.048981518, 0.0025981665 0.075043246 0.047621667, 0.032301188 0.067742988 0.047572404, 0.033269733 0.068418771 0.048563302, -0.0026091635 0.074076876 0.045616806, -0.003685087 0.073905796 0.044504017, 0.001719743 0.073977634 0.044503987, 0.033444345 0.067229286 0.047621191, -0.0081646442 0.077455565 0.049378783, -0.0027806759 0.078948393 0.049504399, -0.0082813203 0.078562155 0.049504384, -0.0027414858 0.077836558 0.049378902, 0.031241596 0.069906503 0.048875093, 0.030257165 0.070619226 0.049008965, 0.030475348 0.069819748 0.048635155, 0.032502204 0.067199573 0.046967655, -0.0080538988 0.076404721 0.049009129, 0.032164067 0.067455366 0.047110885, -0.0079545081 0.075461894 0.048413351, 0.030013114 0.069157586 0.04796499, 0.029899001 0.069957405 0.04856351, -0.007871449 0.074674502 0.047621503, -0.0077702701 0.07371442 0.045616686, -0.0078090131 0.074082226 0.046673432, 0.02948463 0.069479451 0.048054039, 0.028747469 0.070223749 0.048413038, -0.0090700686 0.073439643 0.044503927, 0.029291183 0.069269121 0.047765344, 0.029805481 0.068877563 0.047572255, -0.01516363 0.076394469 0.049378768, -0.013741523 0.077792928 0.049504429, -0.01913476 0.076644957 0.049504071, -0.013547927 0.076697424 0.049378961, 0.029009938 0.069343776 0.047717869, 0.028447539 0.069491133 0.047621399, 0.028221846 0.068939731 0.046673089, 0.029191554 0.068702251 0.046967894, 0.029678881 0.068585008 0.047110796, -0.014957905 0.075357795 0.049009129, 0.028081775 0.06859757 0.045616329, -0.013364166 0.075656772 0.049009055, -0.0089792609 0.075968623 0.048834443, -0.014773399 0.074428067 0.048413202, -0.013199329 0.074723259 0.048413172, -0.0093823671 0.075297683 0.048413321, -0.009465158 0.074162275 0.047164232, -0.0089353919 0.074331209 0.047320619, -0.010694116 0.074322775 0.047621638, -0.009439081 0.075751394 0.048737854, -0.014619231 0.073651403 0.047621712, -0.013061553 0.07394357 0.047621578, -0.018865317 0.075565398 0.049378917, -0.01450333 0.073067114 0.046673417, -0.012957901 0.073357046 0.046673402, -0.012504011 0.075468466 0.048834383, -0.018609315 0.074540198 0.04900907, -0.012004524 0.074924409 0.04841347, -0.012047738 0.07378675 0.047164157, -0.012384057 0.073834881 0.047320873, -0.012076974 0.075375929 0.048737884, -0.014431208 0.072704375 0.045616686, -0.0144068 0.072581604 0.044504091, -0.012893498 0.072992817 0.045616686, -0.009234935 0.073545262 0.045616657, -0.010993391 0.073303118 0.045616671, -0.008428216 0.07364206 0.045616746, -0.0094309151 0.073893294 0.046673506, -0.010828793 0.073701397 0.046673387, -0.020699859 0.075083837 0.049378842, -0.024434775 0.075123549 0.049503997, -0.012003928 0.073518991 0.046673581, -0.018379688 0.073620349 0.048413202, -0.06077157 0.044038966 0.04757081, -0.060038596 0.045097142 0.047619849, -0.061281234 0.04508625 0.048562124, -0.061586604 0.044841826 0.048633873, -0.062118903 0.043411583 0.048332542, -0.020418942 0.074064821 0.04900898, -0.060193986 0.044147119 0.046966389, -0.0595624 0.04473938 0.046671942, -0.059266776 0.044517308 0.045615003, -0.01818794 0.072852284 0.047621444, -0.060513422 0.043852001 0.0471095, -0.020167023 0.073151052 0.048413262, -0.018043637 0.072274566 0.046673387, -0.019956678 0.072387859 0.047621563, -0.062339619 0.041790172 0.047570884, -0.063183233 0.042562574 0.04863368, -0.063403696 0.042049184 0.048561886, -0.063170716 0.04059431 0.047619671, -0.017954201 0.071915522 0.045616537, -0.019666821 0.071336478 0.044504106, -0.062272057 0.04116416 0.04696627, -0.024090827 0.074065506 0.049378708, -0.06207484 0.04161261 0.047109455, -0.062669545 0.040272251 0.046671629, -0.062358364 0.040072426 0.045614943, -0.019798249 0.071813717 0.046673119, -0.063817218 0.039497018 0.047570601, -0.064673811 0.040261611 0.048633426, -0.065108195 0.038784876 0.048332393, -0.064394265 0.040516049 0.048561797, -0.023763776 0.073060364 0.049008876, -0.06325151 0.039643124 0.046966404, -0.019700199 0.071457177 0.045616478, -0.02347061 0.072158903 0.048413113, -0.063546062 0.03932932 0.047109395, -0.065479591 0.037365049 0.047963426, -0.066101268 0.037872657 0.048633307, -0.066290498 0.037332729 0.048561797, -0.02612558 0.073372394 0.049378857, -0.029615879 0.073236033 0.049503937, -0.023225784 0.071406111 0.047621444, -0.025771201 0.072376907 0.049008772, -0.065667465 0.036662504 0.047763571, -0.065217316 0.037140012 0.047570691, -0.066660881 0.03625308 0.048411071, -0.023041427 0.070839718 0.046673372, -0.02545321 0.071483895 0.048413083, -0.065767378 0.036399961 0.047715977, -0.065965444 0.035874948 0.047619522, -0.065442234 0.035590321 0.046671435, -0.06510666 0.036516607 0.046966121, -0.065117434 0.035413742 0.045614526, -0.022927105 0.070487902 0.045616478, -0.064940244 0.036982283 0.047109187, -0.024821609 0.069710359 0.044503748, -0.025187552 0.070738018 0.047621444, -0.066523924 0.034745395 0.047570437, -0.067167118 0.035731554 0.048561469, -0.067421243 0.035469785 0.048633203, -0.067753583 0.033953279 0.048332125, -0.065972403 0.034928188 0.046965942, -0.029198706 0.07220453 0.049378529, -0.024987787 0.07017681 0.046673328, -0.066241324 0.034597769 0.047109008, -0.028802574 0.071224749 0.049008787, -0.068022683 0.032506004 0.047963098, -0.068671897 0.032983825 0.048633158, -0.02486375 0.069828495 0.045616403, -0.068827376 0.032419011 0.048561305, -0.02844727 0.070345983 0.048413098, -0.031411946 0.071269706 0.049378753, -0.03465268 0.070991844 0.049503818, -0.068363652 0.031989947 0.048052087, -0.069129765 0.031290486 0.048410743, -0.028150409 0.069612071 0.047621354, -0.068160206 0.031789839 0.047763199, -0.067748636 0.032292515 0.047570229, -0.030985743 0.070302516 0.049008831, -0.068243772 0.03151454 0.047715589, -0.068408519 0.030964032 0.047619194, -0.067865863 0.030718356 0.046671137, -0.027926952 0.069059744 0.046673194, -0.067594633 0.031674802 0.046965614, -0.067528829 0.030565843 0.045614272, -0.030603439 0.069435045 0.048412964, -0.067461088 0.032155544 0.047109053, -0.071180105 0.029415414 0.049092695, -0.069814175 0.030491546 0.048633009, -0.071449891 0.030084372 0.04927966, -0.02778843 0.068716943 0.045616508, -0.029844075 0.067712754 0.044503585, -0.070041016 0.028942332 0.048331633, -0.072177276 0.029270187 0.049376085, -0.071050644 0.029085949 0.048979297, -0.034164548 0.069991887 0.049378589, -0.068877593 0.029809102 0.047570243, -0.069585353 0.030758545 0.048561335, -0.030284226 0.068710685 0.047621265, -0.070991471 0.028694734 0.048872739, -0.07166858 0.027684167 0.049006298, -0.070881486 0.027921438 0.048632845, -0.033700883 0.069042176 0.049008667, -0.068342537 0.030027673 0.046965599, -0.030043811 0.068165645 0.046673298, -0.033285111 0.068190232 0.048412934, -0.068585053 0.029682532 0.04710862, -0.07020621 0.027475208 0.047962904, -0.071000591 0.027334064 0.048561051, -0.029894739 0.067827299 0.045616314, -0.036530718 0.068786547 0.049378499, -0.039520472 0.068401456 0.049503714, -0.032937795 0.067478687 0.047621235, -0.070508584 0.026935682 0.04805176, -0.071229562 0.026160896 0.04841058, -0.036034986 0.067853257 0.049008608, -0.032676697 0.066943571 0.046673104, -0.070291951 0.026748776 0.047762826, -0.069920391 0.027273655 0.047569856, -0.074876785 0.021443635 0.049375817, -0.074244007 0.02699469 0.049501523, -0.075946435 0.021750122 0.049500883, -0.035590276 0.067015991 0.04841277, -0.070357352 0.026461676 0.047715366, -0.070486322 0.025888011 0.04761894, -0.06992723 0.025682479 0.046670675, -0.032514393 0.066611096 0.04561621, -0.069723666 0.02666457 0.046965599, -0.069580257 0.025555208 0.045614183, -0.034707353 0.065353528 0.04450348, -0.069623545 0.027157873 0.04710871, -0.038964033 0.06743829 0.049378455, 0.045151979 0.059932619 0.047555298, 0.046030104 0.058872938 0.047110498, 0.046226561 0.059124008 0.047571808, 0.044772357 0.059514612 0.046635032, 0.045643032 0.060497433 0.048333824, 0.044036299 0.060772702 0.047571838, 0.04384926 0.060514733 0.047110528, -0.035219014 0.066316694 0.047621265, 0.045612365 0.05842185 0.045595586, 0.046654761 0.057598621 0.045615911, 0.046315223 0.058541507 0.046967238, 0.046575725 0.05750151 0.044502944, -0.038435251 0.066523135 0.049008593, 0.04344815 0.060048565 0.045595795, 0.043409914 0.06072703 0.046967417, 0.042325705 0.06085071 0.04561606, 0.04225412 0.060747832 0.04450345, -0.0711395 0.020373628 0.044501051, -0.069462433 0.02551195 0.044501439, -0.071260154 0.02040787 0.045613721, -0.034939721 0.065790713 0.04667294, 0.040671617 0.063058913 0.047555625, 0.041128039 0.063652769 0.048333794, 0.039724499 0.064074442 0.047964841, 0.040315956 0.062619105 0.046635211, 0.04162097 0.062068373 0.047110468, 0.039493948 0.063818112 0.047572076, 0.076190189 -0.016173691 0.049373597, 0.075946078 -0.021755233 0.049498647, 0.077278599 -0.016404659 0.04949896, 0.039326221 0.063547075 0.047110528, 0.074876577 -0.021449059 0.049373284, 0.041798353 0.062333092 0.047571957, -0.037960976 0.065702349 0.048412696, 0.041229665 0.061593071 0.045595825, 0.041925758 0.061761081 0.046967268, 0.075156331 -0.015954211 0.049003914, -0.034766227 0.065464154 0.045616418, 0.038952559 0.063057676 0.045595884, 0.073860452 -0.021157995 0.049003541, 0.037770748 0.063777789 0.04561618, 0.037706792 0.063670203 0.04450345, 0.038868815 0.063729048 0.046967536, -0.041454479 0.065936446 0.049378261, -0.044195816 0.065478131 0.049503461, 0.074229062 -0.015757367 0.04840827, 0.035975814 0.065850884 0.047555625, 0.035645276 0.06539081 0.046635509, 0.036990613 0.064934179 0.047110736, 0.037148476 0.065211236 0.047572166, 0.036395729 0.06647189 0.048333645, 0.072949305 -0.020897046 0.048407912, 0.034961313 0.066792697 0.04796505, -0.037564844 0.065016806 0.047621131, 0.036627322 0.064435914 0.045595855, 0.037313014 0.064652294 0.046967477, 0.073454663 -0.015592948 0.047616467, 0.072188064 -0.020678952 0.047616303, -0.04089205 0.065041855 0.049008563, 0.034249485 0.065730587 0.045596033, 0.032958418 0.066252768 0.04450351, 0.072871909 -0.015469357 0.046668604, 0.071615458 -0.020514965 0.046668321, 0.072510153 -0.015392572 0.045611814, 0.071259931 -0.020412952 0.045611396, 0.031089306 0.068293661 0.047555804, 0.030784905 0.06781441 0.046635598, 0.0711395 -0.020378456 0.044498816, -0.037266865 0.064500988 0.046673089, 0.072436944 -0.015131071 0.044499069, 0.031829894 0.066935837 0.045596242, 0.077132598 -0.010819465 0.049374104, 0.07823433 -0.01097405 0.049499169, -0.04038763 0.064239219 0.048412859, 0.029364079 0.068053678 0.045596093, 0.076086268 -0.010672837 0.049004287, -0.037082002 0.064180747 0.04561621, 0.02803418 0.068481743 0.044503748, -0.039385393 0.062645689 0.044503406, -0.04357332 0.064555928 0.049378246, -0.0095534325 0.077296659 0.049378842, -0.010791093 0.076066315 0.049009204, -0.039966077 0.063568994 0.04762125, -0.010939896 0.077483743 0.049448401, 0.075147182 -0.010541096 0.048408478, 0.074363321 -0.010431081 0.04761681, -0.012245446 0.076916084 0.049378946, -0.042982295 0.063680187 0.049008369, 0.07377322 -0.01034832 0.046668738, -0.03964904 0.063064709 0.04667303, -0.010732442 0.075117186 0.048413426, 0.073407054 -0.01029703 0.045612022, -0.061539322 0.042937726 0.047554344, -0.042451799 0.06289421 0.048412576, -0.06110999 0.042569861 0.046634227, 0.073348105 -0.0098033547 0.044499367, 0.077699214 -0.0054125786 0.049374223, -0.060049921 0.043447345 0.045594856, -0.059166491 0.044442192 0.044502527, -0.039452255 0.062751725 0.045616284, 0.078809142 -0.0054899901 0.049499482, -0.061596766 0.04122515 0.045594633, -0.042008907 0.062238082 0.047621042, 0.076644942 -0.0053392202 0.04900451, -0.062253073 0.040004835 0.04450205, -0.064500272 0.038346604 0.047554046, -0.064050138 0.038003355 0.046634078, -0.046157256 0.062734649 0.049378186, -0.048656017 0.062235683 0.049503326, 0.075699195 -0.0052732378 0.048408866, -0.063059062 0.038951799 0.045594394, -0.041675553 0.061744258 0.046672732, 0.074909478 -0.0052183568 0.047617272, -0.064439699 0.036622912 0.045594186, -0.065007195 0.035353929 0.04450199, -0.04553096 0.06188339 0.049008429, -0.067119345 0.033552215 0.047554001, 0.074315205 -0.0051769614 0.04666914, -0.04146874 0.061437741 0.04561609, -0.043853536 0.059603631 0.044503346, -0.06664972 0.03323476 0.046633735, 0.073946327 -0.0051512569 0.045612216, 0.073867843 -0.0044230223 0.044499651, -0.065732524 0.034248963 0.045594275, 0.077887475 2.0578504e-05 0.049374595, -0.044969127 0.06111975 0.048412561, -0.066939488 0.031825379 0.045594141, -0.067414835 0.030514345 0.044501603, 0.078999966 2.0995736e-05 0.049499765, 0.076830536 2.0295382e-05 0.049004629, -0.047970757 0.061359078 0.049378186, -0.069382921 0.028580025 0.047553644, -0.044499815 0.0604821 0.047620818, -0.068894535 0.028289154 0.046633437, 0.07588245 1.9997358e-05 0.048409149, -0.068055332 0.029363513 0.045594111, -0.047319725 0.060526431 0.049008176, -0.069082469 0.026858374 0.045594022, 0.075091049 1.975894e-05 0.04761745, -0.044146851 0.060002223 0.046672702, 0.074495062 1.9684434e-05 0.046669438, -0.046735734 0.059779614 0.048412308, 0.074125305 1.950562e-05 0.045612499, 0.073993474 0.00098077953 0.044499934, -0.043927759 0.059704468 0.045615926, 0.077695921 0.0054538101 0.049374953, 0.078805909 0.0055316985 0.049500093, -0.046248198 0.059156016 0.047620654, 0.076641798 0.0053795874 0.049005136, -0.050613388 0.059197888 0.049377963, -0.052878946 0.058689997 0.049503028, 0.075696126 0.0053132623 0.048409432, -0.045881435 0.058686599 0.046672821, -0.049926817 0.05839473 0.049008235, 0.074906364 0.0052577108 0.047617674, -0.045653641 0.05839549 0.045615762, -0.048087388 0.056243539 0.044502974, 0.073943123 0.0051903427 0.045612842, 0.074312046 0.0052161217 0.046669737, -0.052134246 0.05786328 0.049377963, 0.073724374 0.0063793361 0.044500262, -0.049310878 0.057674214 0.048412338, 0.077126041 0.01086016 0.049375206, 0.078227848 0.011015356 0.049500406, -0.051426783 0.057078168 0.049008191, 0.076079622 0.010712802 0.049005464, -0.048796281 0.057072431 0.047620609, 0.076899722 0.012360826 0.049375266, 0.077268735 0.016445458 0.049500793, 0.075140819 0.01058057 0.04840976, -0.050792292 0.056373969 0.048412263, -0.048409149 0.056619689 0.046672747, 0.075856477 0.012192935 0.049005389, -0.050262332 0.055785865 0.04762055, 0.074356943 0.010470226 0.047618032, -0.048168898 0.056338504 0.045615822, 0.074920356 0.012042522 0.048409745, -0.054799899 0.055345535 0.049377471, -0.056844354 0.054858327 0.04950285, -0.049863681 0.05534333 0.046672612, 0.074138761 0.011916861 0.047618002, -0.054056346 0.054594502 0.049007818, 0.073401019 0.010335654 0.04561305, 0.073767081 0.010387138 0.04666999, 0.073061615 0.011743873 0.044500381, -0.049615964 0.055068463 0.045615762, 0.076180562 0.016213685 0.049375534, -0.052064881 0.052583292 0.044502899, 0.073550582 0.011822194 0.04666999, -0.056043625 0.054085776 0.049377605, -0.053389266 0.053921029 0.048411936, 0.075146928 0.015993759 0.049005717, 0.073185608 0.011763558 0.045613214, -0.055283278 0.053351864 0.049007699, 0.075792253 0.017941043 0.049375564, -0.05283235 0.053358361 0.047620416, 0.075933278 0.021795332 0.049501032, 0.074219704 0.015796244 0.048409969, -0.054601222 0.052693576 0.048412159, 0.074763924 0.017697677 0.049005717, -0.05241324 0.052934989 0.046672419, 0.07344529 0.015631467 0.04761833, -0.054031372 0.052143723 0.047620252, 0.073841348 0.017479256 0.048410118, -0.052153081 0.052672297 0.045615464, 0.07286261 0.015507549 0.046670288, -0.058693931 0.051197633 0.049377501, -0.060532764 0.050759524 0.04950273, 0.073070958 0.01729691 0.047618419, -0.053602815 0.051730156 0.046672195, 0.072501019 0.015430465 0.045613289, -0.057897493 0.050503105 0.049007758, 0.072009444 0.017045707 0.044500828, 0.074863747 0.021488309 0.049375921, -0.053336725 0.051473454 0.045615524, -0.055764437 0.048642531 0.044502661, 0.072491229 0.017159685 0.046670228, -0.059680209 0.050044447 0.049377337, -0.057182968 0.04987967 0.048411921, 0.073847979 0.021196768 0.049006164, 0.07213138 0.017074496 0.045613557, -0.05887042 0.04936552 0.049007758, 0.074280277 0.023425668 0.049376011, 0.074227616 0.027039111 0.049501389, -0.056586489 0.0493595 0.047620237, 0.072936773 0.020935252 0.048410296, -0.058144107 0.048756465 0.048411757, 0.073272526 0.023107886 0.049006104, -0.056137666 0.048967943 0.04667218, 0.07217586 0.020716697 0.047618657, -0.057537466 0.048247665 0.047620013, -0.055858821 0.048724681 0.045615405, 0.072368294 0.022822544 0.048410356, -0.057081074 0.047865078 0.046671987, 0.07160306 0.020552456 0.046670586, -0.062274754 0.046776816 0.049377292, -0.06392625 0.046413273 0.049502566, 0.071613297 0.022584513 0.047618747, -0.056797668 0.047627404 0.045615181, 0.071247831 0.020450488 0.045613706, 0.070572823 0.022256553 0.044501156, -0.061429635 0.046142042 0.049007416, 0.0731823 0.026658282 0.049376011, 0.071045086 0.022405282 0.046670586, -0.060671762 0.045572594 0.048411652, 0.072189212 0.026296481 0.049006253, 0.070692405 0.022294015 0.045613825, 0.071298644 0.025972098 0.048410416, 0.072371915 0.028785259 0.04937622, 0.072160453 0.032151088 0.049501508, 0.070554554 0.025701016 0.047618836, 0.071389943 0.028394669 0.049006522, 0.069994882 0.025497183 0.046670794, 0.070509076 0.028044343 0.048410684, 0.069647387 0.025370583 0.045613915, 0.068759829 0.027348772 0.044501394, 0.069773406 0.02775161 0.047619045, 0.071144119 0.031698212 0.049376369, 0.069220141 0.027531534 0.046670914, 0.070178792 0.031268254 0.049006581, 0.068876356 0.027394846 0.045614183, 0.069312945 0.030882314 0.048410833, 0.070077583 0.033991247 0.049376667, 0.06974189 0.037106469 0.049501866, 0.068589762 0.030560136 0.047619075, 0.06912671 0.033529952 0.04900679, 0.068045676 0.030317679 0.046671122, 0.068273664 0.033116266 0.048411071, 0.067707896 0.030167341 0.045614034, 0.066579893 0.032294974 0.044501513, 0.068759546 0.036583662 0.049376667, 0.067561403 0.032770753 0.047619194, 0.067826495 0.036087438 0.049006879, -0.073111385 0.026851892 0.04937619, 0.067025438 0.032510877 0.046671182, -0.072119549 0.026487753 0.049006373, 0.066989511 0.035642147 0.048411131, -0.07386075 0.021152735 0.049005955, 0.066692591 0.032349423 0.045614451, -0.072949275 0.020891696 0.048410371, 0.067409232 0.039015874 0.049376696, 0.066983268 0.041880965 0.049502224, 0.066290706 0.035270289 0.047619313, -0.072188094 0.020673588 0.047618598, -0.071615592 0.020509705 0.046670601, 0.06649445 0.03848663 0.049006939, 0.065764904 0.034990534 0.046671331, 0.073440149 -0.010058537 0.045612037, 0.065674081 0.038011566 0.04841131, 0.073970526 -0.0047908723 0.04561238, 0.074123695 0.00050094724 0.045612425, 0.065438405 0.034816667 0.04561457, 0.064044654 0.037068874 0.044502079, 0.073898539 0.0057903975 0.045612946, 0.066039935 0.041291088 0.049376816, 0.048480153 0.060957253 0.049378037, 0.048357368 0.059700772 0.049008012, 0.049022555 0.060521886 0.049377948, 0.048618704 0.062264651 0.049503565, 0.064988717 0.037615031 0.047619492, 0.04694742 0.061692253 0.049281329, 0.065143824 0.040730864 0.049007058, 0.046221405 0.062687144 0.049378067, 0.044156641 0.065504491 0.049503624, 0.064473286 0.037316695 0.046671599, 0.044473708 0.063939065 0.049378127, 0.044005394 0.064262137 0.049378306, 0.064340085 0.040228248 0.048411518, 0.04387027 0.063071355 0.04900822, 0.042389005 0.064908803 0.049281657, 0.064153254 0.03713131 0.04561466, 0.064381272 0.043832347 0.049377054, 0.063898444 0.046451449 0.049502432, 0.041628987 0.065826446 0.049378246, 0.039479434 0.068425134 0.049503624, 0.039687693 0.067014799 0.049378246, 0.039306253 0.067239136 0.049378425, 0.039149195 0.066105574 0.049008489, 0.063668787 0.039808512 0.047619641, 0.063507706 0.043237537 0.049007177, 0.037611127 0.067789197 0.049281746, 0.063163683 0.039492682 0.046671659, 0.036824316 0.068629742 0.049378335, 0.034610122 0.071012408 0.049503922, 0.034689844 0.069733009 0.049378544, 0.034406543 0.069873288 0.049378395, 0.034219205 0.06878683 0.049008489, 0.06272392 0.042703986 0.048411399, 0.062850222 0.039296582 0.045614839, 0.061167881 0.041644633 0.044502228, 0.062998578 0.045797154 0.049377173, 0.02957198 0.073253796 0.049503893, 0.029507071 0.072079182 0.049378633, 0.062069625 0.042258561 0.04761979, 0.0074268579 0.07374984 0.045616716, 0.0077260733 0.07371901 0.045616716, 0.0077646673 0.0740868 0.046673566, 0.0071153343 0.073654756 0.044504017, 0.0025776327 0.074448034 0.046673477, 0.0025647283 0.074078545 0.045616835, 0.0021437705 0.074091792 0.045616776, 0.062143624 0.045175746 0.049007177, -0.0026221275 0.07444641 0.046673596, 0.061577097 0.041923448 0.046671778, -0.0031503141 0.074055776 0.045616806, 0.061377034 0.044618294 0.048411667, 0.061271474 0.041715279 0.045614988, 0.060736611 0.044152826 0.047620058, -0.062652439 0.046269611 0.049377143, 0.06100966 0.04841505 0.049377233, -0.063344225 0.044694394 0.049280435, 0.060502321 0.050795689 0.04950276, 0.060254648 0.043802544 0.046671897, -0.064300522 0.043950424 0.049377084, -0.067008391 0.041841 0.049502373, -0.065523237 0.042106152 0.049377143, 0.060181722 0.047757953 0.049007416, -0.065795481 0.041679814 0.049377009, -0.064634293 0.041534901 0.049007103, 0.059955701 0.043585181 0.045615107, 0.057964653 0.045998529 0.044502616, 0.059439391 0.047168776 0.048411757, -0.066394538 0.040023282 0.049280122, -0.067273855 0.039248914 0.049376801, -0.069763899 0.037064672 0.04950206, -0.068422362 0.037211195 0.049376577, 0.059650213 0.050080225 0.049377352, -0.06860286 0.036877126 0.049376562, -0.067493871 0.036705956 0.049006805, 0.058819041 0.046676487 0.047620118, -0.069101274 0.035144776 0.049279839, 0.05884093 0.049400613 0.049007416, -0.069903925 0.034347162 0.049376518, -0.072179809 0.032107845 0.049501598, 0.058352455 0.046306357 0.046671987, -0.070956126 0.032117233 0.049376413, -0.071060076 0.031886578 0.049376234, -0.069993272 0.031681433 0.049006477, 0.058114827 0.048790902 0.048411936, 0.058062881 0.046076372 0.045615137, 0.057508528 0.048282012 0.047620177, 0.07449472 0.00026154518 0.046669245, 0.057312638 0.052739337 0.049377471, 0.056811452 0.054892257 0.049502909, 0.074290261 0.0055177659 0.046669722, 0.057052284 0.047899067 0.046672195, 0.047286093 0.059599161 0.048562855, 0.0472624 0.058348984 0.047620714, 0.047760725 0.058964074 0.04841271, 0.056534916 0.052023634 0.049007863, 0.047047406 0.059917659 0.048634499, 0.056769073 0.047661334 0.045615226, 0.054452151 0.050107092 0.044502795, 0.056011319 0.054119274 0.049377739, 0.055837363 0.051381648 0.048411995, 0.044736534 0.06246002 0.04900825, 0.0552513 0.053384796 0.049007833, 0.044827789 0.061596051 0.048634589, 0.044328183 0.061830625 0.048563063, 0.055254847 0.050845593 0.047620237, 0.043329149 0.062293038 0.048412651, 0.042876959 0.061643153 0.047620952, 0.054569602 0.052726105 0.048412085, 0.042832017 0.062876508 0.048563093, 0.042582452 0.063168913 0.04863447, 0.054816574 0.050442174 0.046672344, 0.054000169 0.052176133 0.047620356, 0.054544479 0.05019173 0.045615405, 0.040111005 0.065526366 0.049008638, 0.053309798 0.056782067 0.04937765, 0.05284375 0.058721542 0.049502999, 0.05357185 0.051762104 0.046672285, 0.040246814 0.064682022 0.048634708, 0.03971982 0.064887181 0.048563272, 0.03866604 0.065289676 0.048412859, 0.038151622 0.065821439 0.048563153, 0.052586496 0.056011587 0.049007952, 0.038262874 0.064608514 0.047621161, 0.053305835 0.051505119 0.045615464, 0.037893236 0.066088304 0.048634887, 0.050649107 0.053948388 0.044502884, 0.052099675 0.057894394 0.049377799, 0.05193761 0.055320635 0.048412293, 0.051392704 0.057108894 0.049007952, 0.035276026 0.068250835 0.049008638, 0.051395714 0.05474323 0.047620535, 0.035454363 0.067428067 0.048635185, 0.050758392 0.056404293 0.048412323, 0.03490147 0.067600846 0.048563302, 0.033796906 0.067937985 0.048412919, 0.050988168 0.054308951 0.046672434, 0.050228924 0.05581592 0.047620475, 0.050734758 0.054039508 0.045615524, 0.049830407 0.055372968 0.046672523, 0.029106647 0.071101084 0.049008697, 0.049583107 0.055098101 0.045615584, 0.002366066 0.074455053 0.046673566, -0.0028940141 0.074436337 0.046673834, 0.046887577 0.057886079 0.046672732, -0.0081396997 0.074046612 0.046673447, -0.064037681 0.042448893 0.049007103, -0.063836753 0.041022375 0.048411459, -0.066934973 0.03771539 0.049006939, -0.069483042 0.03278549 0.049006611, 0.024166524 0.074040666 0.049378723, 0.024389863 0.075138077 0.04950425, 0.023838699 0.073035985 0.049008876, 0.02354458 0.072134793 0.048413187, 0.0232988 0.071382284 0.047621369, 0.023113966 0.070815906 0.046673417, 0.022999346 0.070464343 0.045616388, 0.022960365 0.070345402 0.044503868, 0.018820018 0.075576663 0.049378783, 0.019088954 0.076656461 0.049504071, 0.018564701 0.07455124 0.049008906, 0.018335611 0.073631451 0.048413187, 0.01814431 0.072863117 0.047621459, 0.018000424 0.072285026 0.046673417, 0.017910987 0.071926206 0.045616627, 0.01776427 0.071833596 0.044503838, 0.013502091 0.076705679 0.049378991, 0.013694823 0.077801302 0.04950425, 0.013318807 0.075664759 0.049009085, 0.042536795 0.061154187 0.046672821, 0.013154536 0.074731067 0.048413336, 0.013017356 0.073951319 0.047621667, 0.012913972 0.073364541 0.046673506, 0.012849897 0.073000401 0.045616627, 0.012473047 0.072938904 0.044503927, 0.0081181228 0.077460527 0.049378932, 0.0082341731 0.078567147 0.04950425, 0.008008182 0.076409444 0.049009055, 0.039030313 0.06428732 0.047765136, 0.0079094172 0.075466514 0.048413366, 0.038774461 0.064394847 0.047717571, 0.0078267753 0.074679136 0.047621667, 0.037959218 0.064095989 0.04667294, 0.0026950538 0.077838004 0.04937923, 0.0027333796 0.078950018 0.049504399, 0.034457922 0.067152187 0.04805395, -0.053458199 -0.0014325082 0.0015962571, -0.053953335 -0.00027678907 0.0017161071, -0.055261612 -0.0015152395 0.0023451298, -0.052492365 0.00090046227 0.0014999807, -0.046344966 -0.033823177 0.0053852648, -0.047556132 -0.032097921 0.0053856671, -0.046446279 -0.033897161 0.0064978898, -0.055567622 -0.00033704937 0.0025520772, -0.054640457 0.00030298531 0.0019816905, -0.049086869 -0.029945895 0.0064982772, -0.053604752 0.00091961026 0.0016253144, -0.053840816 0.00012364984 0.0016832352, -0.043827802 -0.035512656 0.0033804178, -0.045565099 -0.033254161 0.0033807009, -0.044290304 -0.035887778 0.0043284446, -0.046046346 -0.033605233 0.0043286532, -0.053814515 0.0016865581 0.0016832799, -0.04054828 -0.035073593 0.001623407, -0.04165481 -0.033751994 0.0016233623, -0.041347519 -0.035765052 0.0019932091, -0.042475954 -0.034417182 0.0019932389, -0.054661453 0.00093778968 0.0019952357, -0.040790334 -0.03305158 0.0014979243, -0.0539141 0.0020721704 0.0017161667, -0.055529818 0.0020730197 0.0025522411, -0.055183873 0.0032974035 0.0023455769, -0.047249779 -0.031891063 0.0043287724, -0.052214131 0.0054721236 0.0015001297, -0.053379834 0.0032291412 0.0015964061, -0.043212444 -0.035014197 0.0025889128, -0.0449256 -0.032787204 0.0025890321, -0.055314586 0.0057969391 0.002591297, -0.054406896 0.0050571561 0.001981914, -0.054371938 0.0056983232 0.0019955784, -0.055386573 0.0044929832 0.0025524497, -0.053320676 0.0055881739 0.0016258061, -0.046756074 -0.031557858 0.003380537, -0.053772375 0.0044220686 0.0017160624, -0.04415971 -0.032228589 0.001993224, -0.053625405 0.0048127919 0.0016833842, -0.05346328 0.0063673854 0.0016835034, -0.048979774 -0.029880658 0.0053855628, -0.053528994 0.0067588836 0.0017163455, -0.046099648 -0.031114683 0.0025888979, -0.055139735 0.0068908036 0.0025527924, -0.054687798 0.0080850571 0.002346009, -0.043515876 -0.029370606 0.0014982969, -0.043306172 -0.031605422 0.0016237199, -0.051538318 0.010002032 0.0015004426, -0.052895471 0.007866025 0.0015967935, -0.048664153 -0.029687956 0.0043286979, -0.054598793 0.010595948 0.0025915056, -0.05376032 0.0097728372 0.0019821823, -0.053668231 0.010415375 0.0019958317, -0.054786652 0.0092893094 0.0025526881, -0.053183347 0.0090873092 0.0017162412, -0.045313999 -0.030584306 0.0019934028, -0.052630708 0.010213941 0.0016257614, -0.053002372 0.0094651282 0.0016836077, -0.048155561 -0.029377729 0.0033807009, -0.050172701 -0.027830988 0.0053857416, -0.051392242 -0.025790229 0.0064982921, -0.044438094 -0.029993132 0.0016237199, -0.047479719 -0.028965235 0.0025891662, -0.04984957 -0.027651489 0.0043288767, -0.046670437 -0.028471485 0.0019936413, -0.049328387 -0.02736263 0.0033809692, -0.051279932 -0.025733829 0.0053857714, -0.045768261 -0.0279212 0.0016236007, -0.045909971 -0.025466338 0.001498431, -0.048636213 -0.026978523 0.0025893897, -0.050949544 -0.025567919 0.0043291003, -0.047806963 -0.026518628 0.0019937307, -0.050416976 -0.025300875 0.0033809543, -0.052407414 -0.023352295 0.0053859055, -0.053346321 -0.021458149 0.0064987391, -0.046882972 -0.026005849 0.0016237497, -0.049709439 -0.024945602 0.0025895089, -0.052069634 -0.023201749 0.0043292642, -0.048862174 -0.024520308 0.0019938052, -0.053229973 -0.021411166 0.0053860545, -0.051525563 -0.022959217 0.003381148, -0.047955021 -0.021367863 0.00149858, -0.04791759 -0.024046257 0.0016240478, -0.052886724 -0.021273211 0.0043293685, -0.050802335 -0.02263695 0.0025897324, -0.052334279 -0.021050975 0.0033812523, -0.049936414 -0.022250921 0.0019938052, -0.05424343 -0.018695757 0.0053861886, -0.054935917 -0.016979545 0.0064987391, -0.051599666 -0.020755365 0.0025896132, -0.048971176 -0.021820903 0.0016239285, -0.053893536 -0.018575236 0.0043294281, -0.050720155 -0.020401463 0.0019940138, -0.054816321 -0.016942471 0.0053863823, -0.053330481 -0.018381253 0.0033815503, -0.049634635 -0.017107248 0.0014989823, -0.049739718 -0.020007208 0.0016242266, -0.054462925 -0.016833261 0.0043293536, -0.05258207 -0.01812312 0.0025897175, -0.053893849 -0.016657293 0.0033812821, -0.05168581 -0.017814085 0.0019942969, -0.055666283 -0.013897076 0.0053865165, -0.056150556 -0.012384996 0.006499216, -0.053137541 -0.01642336 0.0025899708, -0.050686643 -0.017469823 0.0016242713, -0.055307508 -0.013807535 0.0043297261, -0.052231461 -0.016143605 0.0019944161, -0.056028083 -0.01235792 0.0053865016, -0.054729536 -0.013663068 0.0033815205, -0.051221967 -0.015831336 0.0016244054, -0.050936878 -0.012716249 0.0014990419, -0.055666983 -0.012278169 0.0043298006, -0.056395993 0.011213481 0.0065004677, -0.055156812 0.015797958 0.0053881407, -0.055277348 0.015832305 0.0065007061, -0.05396153 -0.013471127 0.0025901496, -0.055085301 -0.01214999 0.0033818185, -0.053041562 -0.013241664 0.0019943416, -0.05431208 -0.011979327 0.0025901198, -0.056665659 -0.0089924634 0.0053866506, -0.056981429 -0.0077058375 0.0064994842, -0.052016154 -0.012985632 0.0016243905, 0.055156723 -0.015798241 0.0053862929, 0.053663746 -0.020299226 0.0053862333, 0.055277228 -0.015832946 0.0064990073, 0.053781018 -0.020343646 0.0064987987, -0.053386465 -0.011774987 0.0019945055, 0.054801047 -0.015696451 0.0043295026, 0.053317904 -0.020168215 0.0043293685, -0.056300521 -0.008934617 0.0043300986, 0.05276072 -0.019957617 0.0033813268, 0.054228708 -0.015532508 0.0033816099, -0.056857303 -0.0076890886 0.0053870231, 0.053467408 -0.015314281 0.0025899559, 0.052020252 -0.019677356 0.0025897026, -0.051851332 -0.0082283914 0.0014994889, -0.052354321 -0.011547312 0.0016245693, -0.055712134 -0.0088410378 0.0033818334, 0.051133499 -0.019342005 0.0019940138, 0.052556098 -0.015053213 0.0019941032, -0.056490764 -0.007639423 0.0043299645, 0.051804215 -0.024661466 0.0053860694, 0.051917315 -0.024715289 0.006498605, 0.05014506 -0.018968046 0.0016243011, -0.054929987 -0.0087170154 0.0025902689, 0.049018472 -0.018799782 0.0014987886, 0.050470576 -0.014456019 0.0014990121, 0.051540121 -0.014762282 0.0016243458, 0.05147025 -0.024502441 0.0043290108, -0.05590038 -0.0075594783 0.0033819377, -0.053993881 -0.008568272 0.001994729, 0.050932437 -0.024246395 0.0033810735, -0.055115968 -0.0074533373 0.0025904626, 0.050217643 -0.023906037 0.0025895089, -0.05723384 -0.0040195733 0.0053870976, 0.049361601 -0.023498476 0.0019939244, -0.05742313 -0.0029741079 0.006499663, -0.052950099 -0.0084027648 0.0016249269, 0.049590752 -0.0288551 0.0053856969, 0.049699113 -0.028918192 0.0064982772, -0.054176494 -0.0073260516 0.0019946843, 0.048407435 -0.023044199 0.0016240031, 0.047193438 -0.023000434 0.0014986694, -0.056864917 -0.0039937049 0.0043302029, 0.049271107 -0.028669029 0.0043289065, -0.052371085 -0.0036777705 0.0014996678, -0.053129211 -0.0071845949 0.0016249716, 0.048756227 -0.028369457 0.0033807158, -0.056270704 -0.0039519072 0.0033824146, 0.048071846 -0.027971134 0.0025894046, -0.055480912 -0.0038962811 0.0025905669, 0.047252521 -0.027494401 0.0019934624, -0.05453518 -0.0038298517 0.0019949526, 0.046339124 -0.026962921 0.0016238093, -0.053480968 -0.0037557781 0.0016250908, 0.045009315 -0.027026072 0.0014983416, 0.04416506 -0.03662394 0.0053852648, 0.043312311 -0.037628412 0.0053852797, 0.04426156 -0.036704108 0.0064978302, 0.041079327 -0.040233746 0.0064976066, 0.043033317 -0.037385985 0.0043284148, 0.043880269 -0.036387846 0.0043284297, -0.056323737 0.010930449 0.0053879172, 0.042583525 -0.036995098 0.0033801198, 0.043421865 -0.036007613 0.0033804923, -0.055960849 0.010860085 0.0043310076, -0.054801241 0.015696153 0.0043313503, 0.042812243 -0.035502002 0.0025888234, 0.041985884 -0.036475793 0.0025887191, 0.040989861 -0.040145949 0.0053848624, -0.055376008 0.010746643 0.0033830106, -0.054228514 0.015531957 0.0033835173, 0.041270137 -0.035854116 0.0019932538, 0.042082608 -0.034896955 0.0019931197, -0.053467527 0.015314192 0.0025916696, 0.040725619 -0.039887205 0.0043281168, 0.039868116 -0.041260198 0.0053848475, -0.052556217 0.015053228 0.0019958913, 0.037616536 -0.043488666 0.0064976364, 0.041269138 -0.034222424 0.0016233176, 0.040472403 -0.035160929 0.0016232133, -0.051540256 0.014762282 0.0016262829, 0.039632574 -0.034431368 0.0014979839, -0.05047062 0.0144559 0.0015007406, 0.040300131 -0.039470404 0.0033802688, 0.046152249 -0.027281642 0.0016237497, 0.039611131 -0.040994152 0.0043281168, 0.039734483 -0.03891629 0.0025885999, 0.045754507 -0.028630123 0.0017205626, 0.043954208 -0.03069742 0.0016236156, 0.044985428 -0.029165566 0.0016237497, 0.042482674 -0.030846119 0.001498118, 0.039197117 -0.040565833 0.0033801794, 0.043670371 -0.031099975 0.0016237199, 0.044820771 -0.031302571 0.001993373, 0.03905715 -0.03825289 0.0019930303, 0.043184474 -0.032376871 0.0017204136, 0.037534639 -0.04339388 0.005384624, 0.042347819 -0.032877967 0.0016233176, 0.038646951 -0.03999643 0.0025886446, 0.0039932728 -0.056865022 0.0043272972, 0.0034933984 -0.057268545 0.0053840876, 0.0040192157 -0.057233959 0.0053841323, 0.036480635 -0.037754431 0.0014979541, 0.038302004 -0.037513331 0.0016233176, 0.0029737204 -0.057423323 0.0064968318, 0.037292585 -0.043114066 0.0043279976, 0.0019984692 -0.057243377 0.0050227195, 0.03798835 -0.039314538 0.0019930154, 0.0009919256 -0.057366267 0.0053841323, 0.00033336878 -0.057374045 0.0053841025, -0.0017785132 -0.0574729 0.0064964294, -0.000984326 -0.057366416 0.0053839833, 0.036120206 -0.044577897 0.0053848624, 0.033896923 -0.046446472 0.0064973086, -0.00097797811 -0.056996733 0.0043274462, -0.0013794899 -0.05735831 0.0053840727, 0.036902949 -0.042663559 0.0033800006, 0.037253886 -0.038554668 0.0016230792, -0.0029107034 -0.057204053 0.0050228834, 0.035887554 -0.044290736 0.0043279529, -0.0038800389 -0.057243526 0.0053841919, -0.0065185279 -0.057129636 0.0064967275, 0.03638497 -0.042064533 0.0025884807, -0.004580915 -0.057191908 0.0053841472, -0.005980283 -0.057062387 0.005384028, -0.0059416741 -0.056694597 0.0043274313, -0.0062421411 -0.057034492 0.0053840429, 0.035512447 -0.043827727 0.003379941, -0.0077983588 -0.056744769 0.0050228983, 0.035764873 -0.041347593 0.0019928366, 0.033822969 -0.046345085 0.0053847283, -0.0087242872 -0.05670774 0.0053841025, -0.011213899 -0.056396216 0.0064967573, 0.035014093 -0.043212414 0.0025885254, -0.0094614029 -0.05658935 0.0053839684, -0.010930866 -0.056323946 0.0053840578, -0.026963025 -0.046339333 0.0016228557, -0.027281672 -0.046152294 0.0016228706, -0.027494386 -0.047252685 0.0019924492, -0.027026176 -0.04500939 0.0014973283, 0.035073504 -0.04054822 0.0016230941, -0.028630212 -0.045754671 0.0017193556, 0.033051506 -0.040790394 0.0014974922, 0.033604801 -0.046046466 0.0043278933, -0.029165581 -0.044985548 0.0016228408, -0.03084603 -0.042482644 0.0014974475, 0.034417138 -0.04247579 0.0019928068, -0.030697539 -0.043954447 0.0016228706, -0.031099945 -0.04367049 0.0016226918, 0.032097459 -0.047556385 0.0053846389, -0.031302705 -0.044820607 0.0019926876, -0.032376871 -0.043184593 0.0017196834, 0.029945642 -0.049086973 0.0064972341, 0.033253923 -0.045565233 0.0033798814, 0.033751816 -0.041654855 0.00162296, -0.03287816 -0.042348042 0.0016230196, -0.034431368 -0.039632544 0.0014975816, -0.03422232 -0.041269273 0.0016229153, 0.031890675 -0.047249749 0.0043278784, -0.057268262 -0.0034935772 0.0053869337, 0.032787144 -0.044925585 0.0025885254, -0.057243094 -0.0019987524 0.0050258934, 0.03155753 -0.046756119 0.0033797324, -0.057366282 -0.00099241734 0.0053871274, 0.032228202 -0.04415977 0.0019925833, -0.057373881 -0.0003336072 0.0053873509, -0.057472527 0.0017781258 0.0064999759, -0.057366103 0.00098380446 0.0053874552, -0.056996614 0.00097756088 0.0043304861, -0.057358086 0.0013791323 0.0053874403, 0.02988027 -0.048979908 0.0053846091, 0.031114623 -0.046099752 0.0025882721, -0.057203993 0.0029102862 0.0050263107, 0.031605154 -0.043306187 0.0016229004, 0.029370651 -0.043515682 0.001497671, 0.029687777 -0.048664212 0.004327774, -0.057243302 0.0038797557 0.0053875446, -0.057129502 0.0065182149 0.0065001696, -0.057191566 0.0045806319 0.0053874552, -0.057062119 0.0059798807 0.0053876936, -0.057034269 0.0062420219 0.005387634, 0.030584261 -0.045313865 0.0019925833, -0.056694493 0.0059415251 0.0043307096, -0.056744665 0.0077980906 0.0050264895, 0.02937752 -0.048155725 0.0033797175, 0.02783078 -0.050172985 0.0053844303, 0.025789738 -0.051392317 0.0064969957, -0.056707621 0.0087239295 0.0053876489, 0.029992893 -0.044437945 0.001622811, -0.056589261 0.0094611496 0.005387798, 0.02896519 -0.04747957 0.002588287, 0.04759863 -0.028382912 0.0024384558, 0.047358558 -0.028584853 0.0023670048, 0.027651399 -0.04984948 0.0043276846, 0.028471529 -0.046670303 0.0019925982, 0.047047898 -0.029842079 0.0026680231, 0.027362347 -0.049328536 0.003379643, 0.046136752 -0.030517638 0.0023670644, 0.04624711 -0.032298893 0.0033806115, 0.045962825 -0.03096199 0.0024385899, 0.045597821 -0.031845406 0.0025890917, 0.025733441 -0.05128023 0.005384475, 0.04535301 -0.030526131 0.0019934773, 0.027921036 -0.045768186 0.0016227961, 0.025466144 -0.045909926 0.0014973134, 0.026978225 -0.048636064 0.0025882125, 0.045075759 -0.03223972 0.0024383068, 0.044811502 -0.032432482 0.0023667663, 0.02556774 -0.050949723 0.0043277144, 0.026518628 -0.047807053 0.0019925386, 0.044405684 -0.033647984 0.0026676357, 0.043432966 -0.034256503 0.0023668706, 0.025300607 -0.050417259 0.003379643, 0.043231323 -0.034673855 0.0024380833, 0.023352072 -0.052407667 0.0053843111, 0.042638227 -0.034216002 0.0019929856, 0.021457717 -0.053346395 0.0064968467, 0.026005909 -0.046882987 0.0016225576, 0.003951624 -0.056270719 0.0033791661, 0.0032995492 -0.05646354 0.0035779178, 0.024945527 -0.049709484 0.002588138, 0.0038961768 -0.055480808 0.0025876611, 0.0029719323 -0.056553215 0.00368011, 0.023201466 -0.052069843 0.0043275803, 0.024520278 -0.048861921 0.001992628, 0.00066693127 -0.057103842 0.004554525, 0.021411031 -0.053230122 0.0053843856, 0.0016493648 -0.056306168 0.0032827705, 0.022959068 -0.051525787 0.0033795983, 0.00011329353 -0.057154521 0.0046699643, 0.00050485134 -0.056918576 0.0041603744, 0.024046242 -0.047917575 0.0016227663, 0.021367952 -0.047954708 0.0014971942, 0.021272957 -0.052886963 0.0043273419, 3.8594007e-06 -0.057005137 0.0043272525, 0.00050243735 -0.056629092 0.0036800355, 0.022636801 -0.05080229 0.0025881976, -0.00032345951 -0.057004154 0.0043271631, -0.00096766651 -0.056401074 0.0033791959, 1.1146069e-05 -0.056559995 0.0035779029, -0.00095406175 -0.055609375 0.0025878847, 0.021050796 -0.052334294 0.0033795834, 0.022250831 -0.049936473 0.0019924492, -0.0016052127 -0.056537136 0.0035779923, -0.0019248128 -0.056598753 0.00368011, 0.018695369 -0.054243505 0.0053840876, 0.016979083 -0.0549362 0.0064968616, 0.020755172 -0.051599652 0.0025878549, -0.0042398721 -0.056950018 0.0045544803, -0.0047959238 -0.056952998 0.0046699196, 0.021820769 -0.048971131 0.0016225576, 0.018574983 -0.053893864 0.0043275058, -0.0032355636 -0.056237385 0.003282845, 0.020401463 -0.050720081 0.0019923449, -0.0044143647 -0.056749389 0.0041603446, -0.0048992485 -0.056794077 0.0043274015, 0.016942188 -0.054816484 0.0053840429, -0.0043918192 -0.056460857 0.0036804378, 0.018380851 -0.05333057 0.0033794194, -0.0052468479 -0.056763217 0.0043272972, -0.0058797002 -0.056102186 0.0033792555, 0.01710704 -0.049634755 0.0014969856, 0.020007119 -0.049739599 0.0016224682, -0.0048897117 -0.056348056 0.0035779029, -0.0057971179 -0.055314556 0.0025878698, 0.016832963 -0.054463148 0.0043272376, -0.0064977556 -0.056185395 0.0035781264, 0.01812306 -0.052581906 0.0025878102, -0.0068072975 -0.056220844 0.0036801398, 0.016657099 -0.053893864 0.0033793747, -0.0091152936 -0.056375384 0.0045543462, 0.01781401 -0.051685572 0.0019923598, -0.0096693635 -0.05633083 0.0046699941, 0.013896823 -0.055666655 0.0053841174, 0.012384608 -0.056150734 0.0064966977, -0.0080962628 -0.055745557 0.0032828301, 0.0164233 -0.053137451 0.0025878847, -0.0093006343 -0.056155667 0.0041606277, 0.017469585 -0.050686449 0.0016223788, -0.0097661316 -0.056162328 0.0043274164, -0.0092533082 -0.05587025 0.0036801547, -0.010131225 -0.056097552 0.0043274313, -0.010860533 -0.055961058 0.0043272823, 0.013807058 -0.055307642 0.0043272525, -0.010746971 -0.055376112 0.0033791661, 0.016143396 -0.052231714 0.0019920915, -0.0097537339 -0.05571264 0.0035780221, -0.010596067 -0.054598838 0.0025877953, 0.012357652 -0.056028336 0.0053841621, -0.027971312 -0.0480721 0.0025881529, -0.028383061 -0.047598824 0.0024374574, -0.028369486 -0.048756421 0.0033797324, 0.013662979 -0.054729789 0.0033793598, -0.028584853 -0.047358602 0.002366215, 0.015831202 -0.051221982 0.0016224235, 0.012715966 -0.050936714 0.0014970005, 0.012277961 -0.055667162 0.0043274164, -0.029841959 -0.047048032 0.0026670545, 0.013471112 -0.053961411 0.00258784, -0.030517653 -0.046136871 0.0023661852, -0.03184551 -0.045597926 0.002588287, -0.030962005 -0.045963064 0.0024375618, 0.012149796 -0.055085421 0.0033792406, -0.032298818 -0.046247318 0.003379792, -0.030526072 -0.045353204 0.0019927025, 0.01324144 -0.053041622 0.0019921362, -0.032239795 -0.045076072 0.0024378002, 0.011979267 -0.05431214 0.0025878251, -0.032432482 -0.044811577 0.0023662597, 0.0089922696 -0.056665882 0.0053842068, -0.033647925 -0.044405729 0.0026671588, 0.007705465 -0.056981638 0.0064965785, 0.012985677 -0.052016333 0.0016225129, -0.034256637 -0.043432906 0.0023660958, 0.011774972 -0.053386211 0.0019920319, 0.0089343786 -0.056300551 0.004327327, -0.036007524 -0.043422043 0.0033800453, -0.034674048 -0.043231428 0.002437681, -0.035502195 -0.042812601 0.0025885403, -0.034897089 -0.042082638 0.0019928217, -0.034216121 -0.042638287 0.0019928515, 0.0076885521 -0.056857452 0.0053840131, -0.05646348 -0.0032999068 0.0035811067, 0.011547297 -0.052354246 0.0016223788, 0.0082282573 -0.051851273 0.0014969856, 0.0088408589 -0.055712372 0.0033793151, -0.056553289 -0.0029721558 0.003683269, 0.0076390207 -0.056490943 0.0043274909, -0.057103708 -0.00066711009 0.0045577437, 0.0087169856 -0.054930314 0.0025877804, -0.056306258 -0.0016495287 0.0032858253, 0.0075592995 -0.055900529 0.0033792108, -0.057154432 -0.00011344254 0.0046731979, -0.056918308 -0.00050523877 0.0041635185, 0.008568272 -0.05399403 0.0019921213, -0.057004914 -4.157424e-06 0.0043305457, -0.056629121 -0.00050257146 0.0036832094, 0.0074531585 -0.055115893 0.0025877804, -0.057004064 0.00032289326 0.0043303967, -0.05640097 0.00096744299 0.0033823848, -0.056559727 -1.1265278e-05 0.003581211, -0.055609331 0.00095401704 0.0025909692, 0.0084026605 -0.052950025 0.0016222447, -0.056536943 0.0016048402 0.0035810918, 0.0073260218 -0.05417645 0.0019920617, -0.056598648 0.0019247234 0.0036833286, 0.0036777258 -0.052370995 0.0014968663, 0.0071845651 -0.053129017 0.0016221851, -0.056949824 0.0042396784 0.0045577884, -0.056952909 0.004795596 0.0046735108, -0.056237131 0.0032352656 0.0032860786, -0.05674915 0.0044139028 0.0041637868, 0.0038297623 -0.054535151 0.001992017, -0.056793988 0.0048989654 0.004330799, -0.056460634 0.0043915063 0.0036836118, -0.056763053 0.0052465945 0.0043308437, -0.056101963 0.005879283 0.0033828616, 0.0037556291 -0.053480893 0.0016224384, -0.056347981 0.0048894435 0.0035814494, -0.05618532 0.0064976215 0.0035814196, -0.056220666 0.0068072379 0.0036836565, -0.056375295 0.0091151595 0.0045580417, -0.056330562 0.00966914 0.0046735853, -0.055745423 0.0080961585 0.0032864511, -0.056155682 0.0093002468 0.0041642338, -0.056162268 0.0097657293 0.0043311268, -0.055870309 0.0092529356 0.0036836863, -0.056097358 0.010130852 0.0043309778, -0.055712521 0.0097536147 0.0035815686, 0.048237339 -0.029317379 0.003429696, 0.047779918 -0.030443445 0.0037158877, 0.046984583 -0.031285599 0.0034295171, 0.046735331 -0.032639891 0.0043285936, 0.045643166 -0.033212319 0.0034295619, 0.045097202 -0.034292802 0.0037157834, 0.044231668 -0.035070211 0.0034293681, -0.015798196 -0.055157095 0.005384177, -0.015832812 -0.055277601 0.0064967275, 0.0027605146 -0.055499956 0.0025491565, 0.0015153438 -0.055261523 0.0023422986, -0.015696496 -0.054801434 0.0043273717, 0.00033709407 -0.055567607 0.0025492162, -0.015532583 -0.054228887 0.0033795536, -0.002072975 -0.055529833 0.0025490075, -0.015314341 -0.053467572 0.00258784, -0.00093790889 -0.054661423 0.0019921213, -0.0032975376 -0.055183887 0.0023422837, -0.010415375 -0.053668261 0.0019921362, -0.015053451 -0.052556127 0.0019922107, -0.020299017 -0.053664118 0.0053844303, -0.0044932812 -0.055386588 0.0025492311, -0.020343289 -0.053781345 0.0064967871, -0.0056983382 -0.054371715 0.0019920617, -0.0068908185 -0.055139765 0.0025493205, -0.010002077 -0.051538408 0.001496911, -0.014762253 -0.051540226 0.0016223788, -0.010214016 -0.052630737 0.0016221404, -0.014455989 -0.050470531 0.0014970601, -0.0201682 -0.053318173 0.004327476, -0.0080851614 -0.054687902 0.0023422986, -0.019957528 -0.052761033 0.003379494, -0.009289369 -0.054786697 0.0025492311, -0.02931717 -0.048237637 0.0034286529, -0.019677222 -0.052020505 0.002587989, -0.028669089 -0.04927136 0.0043277293, -0.019341961 -0.051133618 0.0019923896, -0.03044337 -0.047780171 0.0037150383, -0.024661288 -0.051804468 0.0053842664, -0.024715066 -0.051917702 0.006496951, -0.031285554 -0.046984881 0.0034287572, -0.032639921 -0.046735644 0.0043279529, -0.018799737 -0.049018666 0.0014973134, -0.018967971 -0.050145134 0.0016225427, -0.033212155 -0.045643449 0.0034288317, -0.024502367 -0.051470488 0.0043276995, -0.034292758 -0.045097202 0.0037153065, -0.024246246 -0.050932735 0.0033794791, -0.035070106 -0.044232026 0.0034288913, -0.036387742 -0.043880552 0.0043280423, -0.023905963 -0.050217718 0.0025881529, -0.055499941 -0.0027605891 0.0025521815, -0.023498401 -0.049361825 0.0019922405, -0.028854847 -0.04959105 0.0053844154, -0.028918013 -0.049699485 0.0064969957, -0.023044109 -0.048407421 0.0016223639, -0.023000538 -0.047193512 0.0014971644, 0.049148887 -0.029489234 0.0051573366, 0.048921525 -0.029801801 0.0050442517, 0.04839088 -0.030878946 0.0055212528, 0.047141314 -0.032923654 0.0064979643, 0.047648162 -0.031797931 0.0050442666, 0.047449887 -0.032151863 0.0051573962, 0.04703851 -0.032851681 0.0053853095, 0.046544015 -0.033449933 0.0051573217, 0.046290636 -0.033743724 0.0050440431, -0.036623791 -0.044165269 0.0053848177, -0.037628368 -0.043312654 0.0053848922, -0.036703765 -0.044261947 0.0064974874, -0.040233612 -0.04107973 0.0064975172, 0.045673713 -0.034772158 0.0055206567, 0.044856697 -0.035627797 0.0050438941, -0.037385747 -0.043033525 0.0043280125, 0.044630677 -0.035963058 0.0051570833, 0.0030069798 -0.053756803 0.0016800761, 0.0026298612 -0.053889871 0.0017129183, -0.036995173 -0.042583823 0.0033799708, 0.001432538 -0.05345802 0.0015933216, -0.00090064108 -0.052492335 0.001496911, -0.036475986 -0.041985825 0.0025884807, -0.00030303001 -0.054640666 0.0019786656, -0.00091972947 -0.053604692 0.001622349, 0.00027668476 -0.05395326 0.001712963, -0.04014574 -0.040990278 0.0053849071, -0.00012375414 -0.053840816 0.0016800463, -0.035854056 -0.041270211 0.0019927323, -0.0016866624 -0.053814471 0.0016801357, -0.039887115 -0.040725768 0.0043281019, -0.0020723045 -0.053914219 0.0017129183, -0.0054721683 -0.052214041 0.0014969707, -0.0032291561 -0.0533797 0.0015932769, -0.041260049 -0.03986834 0.0053850263, -0.043488473 -0.037616983 0.0064977854, -0.035161152 -0.040472388 0.0016230643, -0.0050572306 -0.054406822 0.0019787848, -0.0055881441 -0.053320691 0.001622349, -0.03947036 -0.04030028 0.0033803433, -0.0044220984 -0.053772509 0.0017130971, -0.0048128068 -0.053625464 0.0016801953, -0.040994078 -0.039611325 0.0043281466, -0.03891626 -0.039734542 0.002588734, -0.0063674897 -0.053463176 0.0016801208, -0.006758824 -0.053528979 0.001712963, -0.040565595 -0.039197415 0.003380239, -0.0078662187 -0.052895591 0.001593411, -0.038252965 -0.039057225 0.0019928664, -0.0097729713 -0.053760231 0.0019787252, -0.043393686 -0.037534893 0.0053852648, -0.0090873688 -0.053183228 0.0017128736, -0.03999649 -0.038647145 0.0025885999, -0.0094653666 -0.053002343 0.001680091, -0.037513375 -0.038302228 0.0016230196, -0.0377547 -0.036480904 0.0014977306, -0.043113917 -0.037292868 0.0043282956, -0.029488966 -0.049149185 0.0051565021, -0.039314613 -0.037988409 0.001993075, -0.029801458 -0.048921898 0.005043298, -0.044577748 -0.036120728 0.0053853542, -0.030878738 -0.048391268 0.0055200607, -0.032923445 -0.047141775 0.0064972937, -0.042663321 -0.036903188 0.0033802837, -0.031797737 -0.047648489 0.0050432831, -0.032851651 -0.047038913 0.0053845644, -0.032151714 -0.047450244 0.005156517, -0.038554564 -0.037253961 0.0016230494, -0.033449784 -0.046544328 0.005156517, -0.03374362 -0.04629077 0.0050432533, -0.042064577 -0.036385149 0.0025888085, -0.034772113 -0.045674011 0.0055202395, -0.035627678 -0.044857129 0.0050432831, -0.03596288 -0.044631094 0.0051565766, -0.053757057 -0.0030070245 0.0016829222, -0.05388993 -0.0026299059 0.0017157942, -0.043114036 -0.037292451 -0.0043328702, -0.044577762 -0.036120042 -0.005389601, -0.044290438 -0.035887331 -0.0043327063, -0.05237104 -0.0036778599 -0.0015002936, -0.053458154 -0.0014322102 -0.0015965849, -0.05249247 0.0009008199 -0.0015001148, -0.055261403 -0.0015150905 -0.0023455322, -0.05395332 -0.00027652085 -0.0017162263, -0.044159874 -0.032228142 -0.0019970834, -0.045313999 -0.030584112 -0.0019970238, -0.043306127 -0.031605124 -0.0016271174, -0.044438079 -0.029992908 -0.0016272068, -0.055567488 -0.00033675134 -0.0025525987, -0.053840771 0.00012387335 -0.0016831309, -0.043827683 -0.035512403 -0.0033846498, -0.045565233 -0.033253685 -0.0033844411, -0.043212473 -0.035013989 -0.0025928766, -0.053604707 0.00091987848 -0.0016252995, -0.054661497 0.00093798339 -0.0019950718, -0.054640532 0.00030304492 -0.0019816607, -0.055609494 0.00095431507 -0.0025907308, -0.044925645 -0.032786846 -0.0025926977, -0.046099663 -0.03111437 -0.0025926977, -0.05381465 0.0016866922 -0.0016830564, -0.046046272 -0.033604875 -0.0043324679, -0.053914279 0.002072528 -0.0017162114, -0.055529833 0.0020731986 -0.0025522113, -0.055183962 0.0032976866 -0.0023454428, -0.045768186 -0.027921051 -0.001627028, -0.043515772 -0.029370576 -0.00150159, -0.045910105 -0.025466144 -0.0015016645, -0.053379521 0.0032292157 -0.0015963465, -0.046756089 -0.031557247 -0.0033843964, -0.052214071 0.0054723471 -0.001499936, -0.05377242 0.0044223219 -0.0017158687, -0.055386558 0.0044933408 -0.0025521666, -0.046345025 -0.033822775 -0.0053893328, -0.053625405 0.0048130155 -0.0016829371, -0.053320706 0.0055884272 -0.0016249567, -0.046446249 -0.033896595 -0.0065021217, -0.054406881 0.0050573945 -0.0019815713, -0.054371729 0.0056983978 -0.0019949526, -0.055314496 0.0057972968 -0.0025906265, -0.046670422 -0.028471306 -0.0019968897, -0.053463012 0.0063675195 -0.0016830117, -0.047249764 -0.031890601 -0.0043324828, -0.05513975 0.0068911165 -0.0025520474, -0.053528905 0.0067590624 -0.0017159432, -0.054687873 0.0080853701 -0.0023452342, -0.047479689 -0.02896513 -0.0025924742, -0.046883076 -0.0260057 -0.0016269088, -0.052895576 0.0078663528 -0.001595974, -0.051538542 0.010002419 -0.0014995635, -0.049086809 -0.029945031 -0.0065015852, -0.047556356 -0.032097444 -0.0053891242, -0.053183347 0.0090874881 -0.0017156005, -0.054786578 0.0092895627 -0.0025520027, -0.04815565 -0.029377267 -0.0033840835, -0.053002462 0.0094654262 -0.0016826838, -0.052630767 0.010214373 -0.0016248524, -0.053668216 0.010415614 -0.0019946098, -0.053760216 0.0097729713 -0.0019813925, -0.054598927 0.010596216 -0.0025903881, -0.047807068 -0.02651833 -0.0019965917, -0.048664093 -0.029687509 -0.0043325573, -0.048636124 -0.02697821 -0.0025925636, -0.047917679 -0.024046138 -0.0016266853, -0.047954828 -0.021367848 -0.0015014112, -0.048979715 -0.029880166 -0.0053892434, -0.049328312 -0.027362242 -0.0033842027, -0.0488621 -0.024520084 -0.001996696, -0.049849376 -0.02765125 -0.0043322146, -0.049709603 -0.024945304 -0.0025922954, -0.048971027 -0.021820635 -0.0016267449, -0.050172895 -0.027830422 -0.0053891093, -0.051391959 -0.02578935 -0.006501615, -0.050417021 -0.025300458 -0.0033839792, -0.049936399 -0.022250831 -0.0019963682, -0.050949469 -0.025567546 -0.0043319315, -0.049739748 -0.020006865 -0.00162673, -0.049634799 -0.017107099 -0.0015011281, -0.050802335 -0.022636577 -0.0025921762, -0.051279962 -0.025733367 -0.0053889453, -0.05072017 -0.020401359 -0.0019965172, -0.051525697 -0.022958785 -0.0033838898, -0.051599607 -0.020755038 -0.0025921315, -0.052069709 -0.023201331 -0.004332006, -0.050686479 -0.01746954 -0.0016264915, -0.052334249 -0.021050587 -0.0033836663, -0.052407458 -0.023351744 -0.0053887218, -0.053346246 -0.021457449 -0.0065014958, -0.051685661 -0.017813951 -0.0019961596, -0.052887008 -0.021272823 -0.0043320209, -0.051221982 -0.015831187 -0.0016262233, -0.050936699 -0.012715995 -0.0015009791, -0.052581996 -0.018122792 -0.002591908, -0.053229973 -0.021410868 -0.0053885877, -0.05223152 -0.016143277 -0.0019961447, -0.053330466 -0.018380567 -0.0033837259, -0.053137556 -0.016423181 -0.0025918633, -0.053893611 -0.018574804 -0.0043315589, -0.052016258 -0.012985408 -0.0016262233, -0.053893745 -0.016656891 -0.0033835024, -0.054935917 -0.016978785 -0.0065011233, -0.054243252 -0.018695235 -0.0053884536, -0.053041503 -0.01324141 -0.0019960254, -0.054462895 -0.016832709 -0.0043316036, -0.052354306 -0.011547238 -0.0016261488, -0.051851228 -0.008228153 -0.0015006363, -0.053961352 -0.013471067 -0.0025915951, -0.054816306 -0.016941845 -0.0053883195, -0.053386465 -0.011774659 -0.0019960105, -0.054729462 -0.01366283 -0.003383413, -0.054312065 -0.011978984 -0.0025914758, -0.055307552 -0.01380688 -0.0043315738, -0.055085272 -0.012149602 -0.0033832937, -0.05154033 0.014762297 -0.0016245097, -0.050470665 0.014456093 -0.0014993101, -0.052950054 -0.0084025115 -0.0016261637, -0.056150526 -0.012384146 -0.0065008849, -0.055666357 -0.013896406 -0.0053881556, -0.055667087 -0.012277737 -0.0043313801, -0.053993925 -0.0085681081 -0.0019956082, -0.056395963 0.011214152 -0.0064995438, -0.055277273 0.015833125 -0.0064991564, -0.055156827 0.015798509 -0.0053864866, 0.051540181 -0.014762223 -0.001626417, 0.050145119 -0.018967882 -0.0016263723, 0.050470546 -0.014455646 -0.0015009344, -0.053129032 -0.007184431 -0.0016257614, 0.049018547 -0.018799454 -0.001501143, -0.056028038 -0.012357473 -0.0053881854, 0.052556098 -0.015053093 -0.0019960701, 0.051133543 -0.019341707 -0.0019962341, -0.054930031 -0.0087167919 -0.0025914758, 0.052020177 -0.019677013 -0.0025921911, 0.053467512 -0.015314072 -0.0025918484, -0.054176271 -0.0073259473 -0.0019955784, 0.054228604 -0.015532061 -0.0033835322, 0.052760705 -0.019957259 -0.0033837408, -0.055712134 -0.0088407546 -0.0033830255, 0.054801166 -0.015696079 -0.0043316633, 0.053317875 -0.020167887 -0.0043318123, 0.048407435 -0.023043931 -0.0016266555, -0.055115879 -0.0074529499 -0.0025913715, 0.047193602 -0.023000374 -0.0015013814, -0.056300536 -0.0089340955 -0.0043311566, 0.05366382 -0.020298764 -0.0053886175, 0.053781018 -0.020342931 -0.0065011531, 0.055277318 -0.015832126 -0.0065012723, 0.055156723 -0.015797839 -0.005388394, -0.055900544 -0.0075589865 -0.0033830255, 0.049361587 -0.023498148 -0.0019965619, -0.053480998 -0.0037555993 -0.001625672, 0.050217628 -0.023905694 -0.0025922656, -0.056981385 -0.0077048689 -0.006500721, -0.056665659 -0.0089919567 -0.005388096, -0.056490749 -0.0076389015 -0.0043310374, 0.050932378 -0.024245963 -0.0033840537, 0.051470354 -0.024502054 -0.0043320507, -0.054535106 -0.0038296729 -0.0019954741, 0.04633899 -0.026962742 -0.0016268939, 0.045009404 -0.027025893 -0.0015018582, -0.056857258 -0.0076884627 -0.0053879768, -0.055480808 -0.0038960278 -0.0025911629, 0.0518042 -0.024660915 -0.00538899, 0.051917374 -0.024714753 -0.0065015554, 0.04725261 -0.027494237 -0.0019966811, -0.056270763 -0.0039514303 -0.003382802, -0.056864902 -0.0039932281 -0.0043307245, 0.048071995 -0.027971029 -0.0025925189, 0.048756287 -0.028369114 -0.003384158, 0.049271166 -0.028668672 -0.0043322593, -0.057423189 -0.0029733181 -0.0065003783, -0.057233572 -0.0040192455 -0.0053876936, 0.049590722 -0.028854549 -0.0053890496, 0.049699068 -0.028917477 -0.0065018535, 0.041269168 -0.034222126 -0.0016274899, 0.040472373 -0.035160884 -0.0016272217, 0.039632514 -0.03443107 -0.0015021563, 0.041270286 -0.035853863 -0.0019970834, 0.042082667 -0.034896731 -0.0019971728, 0.041985869 -0.036475614 -0.0025929362, -0.052556172 0.015053436 -0.0019942671, 0.042812303 -0.035502017 -0.0025927573, -0.053467542 0.015314385 -0.0025901049, 0.04342176 -0.036007121 -0.0033846647, 0.04258354 -0.036994725 -0.0033846647, 0.038302124 -0.037513167 -0.0016275048, -0.055376038 0.010747224 -0.0033819377, -0.054228783 0.015532568 -0.003381744, 0.036480844 -0.037754267 -0.0015023947, -0.055960849 0.010860622 -0.0043299496, -0.05480136 0.01569663 -0.0043297857, 0.043880254 -0.036387324 -0.0043327361, 0.043033272 -0.037385315 -0.0043327659, -0.056323707 0.01093109 -0.0053868741, 0.039057255 -0.038252726 -0.0019973814, 0.046152174 -0.027281448 -0.001627028, 0.037253916 -0.038554385 -0.0016274154, 0.044261485 -0.036703408 -0.0065020472, 0.043312415 -0.037627995 -0.0053895563, 0.04416503 -0.036623344 -0.0053896606, 0.041079462 -0.040233105 -0.0065024346, 0.045754626 -0.028629765 -0.0017237216, 0.039734408 -0.038915813 -0.0025930852, 0.04248257 -0.030845761 -0.0015018731, 0.044985443 -0.029165164 -0.0016270578, 0.043954283 -0.030697241 -0.0016272217, 0.044820666 -0.031302407 -0.0019970089, 0.043670386 -0.031099692 -0.0016271621, 0.037988365 -0.039314389 -0.0019975305, 0.040300086 -0.039469987 -0.0033848584, 0.043184429 -0.032376707 -0.0017238855, 0.042347968 -0.032877773 -0.0016272664, 0.038647011 -0.039996073 -0.0025931597, 0.0040192902 -0.057233348 -0.0053907335, 0.0034931898 -0.057267904 -0.005390659, 0.0039933324 -0.056864664 -0.0043338239, 0.040725604 -0.039886773 -0.0043329597, 0.0029735714 -0.057422549 -0.0065032691, 0.0019983053 -0.057242766 -0.005029425, 0.03507337 -0.040548012 -0.0016277134, 0.03305155 -0.040790111 -0.0015024841, 0.000992015 -0.057365924 -0.0053907037, 0.039197162 -0.040565446 -0.0033847988, 0.040989801 -0.040145531 -0.0053897947, -0.00098416209 -0.057366073 -0.0053906292, 0.00033332407 -0.057373419 -0.0053907186, -0.0017784834 -0.057472125 -0.0065033734, -0.0013795197 -0.057357758 -0.0053907484, -0.0009778738 -0.056996346 -0.004333958, 0.035764873 -0.041347399 -0.001997456, -0.0029105991 -0.05720368 -0.005029425, 0.039611071 -0.04099375 -0.0043329597, -0.003880024 -0.057242975 -0.0053906143, -0.006518513 -0.057128996 -0.0065035075, 0.03375189 -0.041654542 -0.0016278476, -0.0059804022 -0.057061762 -0.0053908229, -0.0045808405 -0.057191283 -0.0053906292, 0.036385059 -0.042064384 -0.0025932491, -0.0062423348 -0.057033882 -0.0053906143, -0.0059417337 -0.05669412 -0.0043338984, 0.039868131 -0.041259721 -0.0053898841, 0.03761667 -0.043488011 -0.0065027028, -0.0077982992 -0.056744203 -0.0050295144, 0.034417123 -0.042475805 -0.0019975901, 0.03690289 -0.042663082 -0.0033849776, -0.011213899 -0.056395561 -0.0065031648, -0.0087240934 -0.056707337 -0.0053905547, 0.035013914 -0.043212175 -0.0025932938, -0.010930821 -0.056323424 -0.005390808, -0.0094614178 -0.056589007 -0.0053907037, -0.026962966 -0.046338931 -0.0016278923, -0.027281657 -0.046152055 -0.0016280115, -0.027026162 -0.045009211 -0.0015025884, 0.037292674 -0.043113679 -0.0043330789, -0.02749449 -0.047252417 -0.0019979179, -0.028630137 -0.045754522 -0.0017247647, 0.031605244 -0.043305919 -0.0016278177, -0.029165566 -0.044985205 -0.0016280413, 0.029370561 -0.043515563 -0.0015025735, 0.035512432 -0.043827176 -0.0033851117, -0.030846149 -0.04248248 -0.0015023947, -0.030697554 -0.043954134 -0.0016279817, -0.031302661 -0.044820487 -0.0019976646, -0.03109996 -0.043670356 -0.0016279072, 0.037534624 -0.043393373 -0.005389899, -0.03237696 -0.043184489 -0.0017245412, 0.032228172 -0.044159576 -0.0019976497, -0.03287828 -0.042347804 -0.0016278327, -0.034431309 -0.039632514 -0.0015023351, -0.03422226 -0.041269079 -0.0016277581, 0.035887554 -0.044290096 -0.0043330938, -0.057268202 -0.0034931302 -0.0053876638, 0.029992864 -0.044437706 -0.0016280264, 0.032787114 -0.044925243 -0.0025931746, -0.057243094 -0.0019982457 -0.0050263107, -0.057366297 -0.00099174678 -0.0053874999, 0.036120296 -0.044577509 -0.0053898692, 0.033896878 -0.046445772 -0.0065027177, 0.030584171 -0.045313671 -0.0019977987, -0.057373732 -0.00033298135 -0.0053875744, -0.057472736 0.0017787367 -0.0065000206, -0.057366356 0.00098459423 -0.0053875297, 0.033253744 -0.045564845 -0.0033851713, -0.057358265 0.0013796538 -0.0053874105, -0.056996495 0.00097811222 -0.0043306351, -0.057203934 0.0029108673 -0.0050260276, 0.031114608 -0.046099469 -0.0025935322, -0.057129428 0.0065187663 -0.0064996183, -0.057243496 0.0038802773 -0.005387336, 0.033605039 -0.046045974 -0.0043332279, -0.057062179 0.0059805363 -0.0053870678, -0.057191551 0.0045810193 -0.0053872913, 0.027920946 -0.045767888 -0.0016279221, 0.025466129 -0.045909837 -0.0015026778, -0.057034045 0.0062424988 -0.0053870827, -0.056694388 0.005941987 -0.0043301731, 0.031557575 -0.046755686 -0.0033852458, 0.033822954 -0.046344563 -0.0053900778, -0.056744665 0.0077985376 -0.0050257146, -0.056707516 0.008724317 -0.0053870082, 0.028471455 -0.046670243 -0.0019978136, -0.056589276 0.0094615668 -0.0053869039, 0.03189078 -0.047249287 -0.0043333173, 0.04759872 -0.028382733 -0.0024421215, 0.028965175 -0.04747951 -0.002593413, 0.047358602 -0.028584555 -0.0023704916, 0.026005924 -0.046882734 -0.0016281903, 0.029945552 -0.049086362 -0.0065029562, 0.032097548 -0.047555774 -0.0053901225, 0.047047868 -0.029841587 -0.0026714057, 0.029377535 -0.048155263 -0.0033850968, 0.045353219 -0.030525848 -0.0019968748, 0.02651836 -0.047806755 -0.0019979477, 0.046136856 -0.030517429 -0.0023706257, 0.045597926 -0.031845272 -0.0025927871, 0.045962915 -0.030961692 -0.0024423003, 0.046246991 -0.03229852 -0.0033843368, 0.029687703 -0.04866381 -0.0043333471, 0.045075819 -0.032239527 -0.0024421811, 0.026978388 -0.04863587 -0.0025936663, 0.044811547 -0.032432288 -0.0023707449, 0.024046272 -0.047917292 -0.0016281754, 0.021367997 -0.047954604 -0.0015029311, 0.029880419 -0.048979446 -0.0053901225, 0.044405654 -0.033647597 -0.0026717037, 0.027362317 -0.049328163 -0.0033853948, 0.042638138 -0.034215674 -0.0019970834, 0.024520248 -0.048861906 -0.0019979477, 0.043432891 -0.034256235 -0.0023707598, 0.043231443 -0.03467384 -0.0024423003, 0.02765134 -0.049848944 -0.0043335557, 0.024945498 -0.049709201 -0.0025935918, 0.0039516389 -0.056270346 -0.0033857375, 0.003299728 -0.056463331 -0.0035845041, 0.0038962364 -0.055480629 -0.0025939196, 0.0029720813 -0.056552976 -0.0036866963, 0.021820828 -0.048971057 -0.0016281456, 0.02783066 -0.050172374 -0.005390197, 0.025789812 -0.051391631 -0.0065030009, 0.0016493499 -0.056305811 -0.0032893121, 0.025300547 -0.050416857 -0.0033853203, 0.022250906 -0.04993619 -0.0019980222, 0.025567815 -0.050949171 -0.0043334514, -0.00095403194 -0.055609077 -0.0025940835, 1.104176e-05 -0.056559578 -0.0035845041, -0.00096768141 -0.056400701 -0.0033857077, 0.020007119 -0.049739525 -0.0016281605, 0.00050234795 -0.056628838 -0.0036868751, 0.00050488114 -0.056918055 -0.0041668415, 0.01710692 -0.049634397 -0.0015030205, 0.022636861 -0.050802156 -0.0025937259, 0.00066690147 -0.057103351 -0.0045612156, 3.9190054e-06 -0.057004765 -0.0043339729, 0.025733605 -0.05127956 -0.0053903908, 0.00011321902 -0.057154059 -0.0046765208, 0.020401388 -0.050719842 -0.0019980669, -0.0003233999 -0.057003692 -0.004333809, 0.022959083 -0.051525414 -0.0033855289, -0.0016051829 -0.056536674 -0.0035845637, 0.020755172 -0.051599309 -0.0025937408, 0.023201481 -0.052069485 -0.0043336004, -0.0019248873 -0.056598306 -0.0036865175, 0.0174696 -0.050686195 -0.0016281754, -0.0032356828 -0.056236923 -0.0032893419, 0.021050662 -0.052333832 -0.0033853203, 0.021457747 -0.053345546 -0.0065031201, 0.023352027 -0.05240716 -0.0053903908, -0.0057972968 -0.055314273 -0.002594173, -0.004889816 -0.056347698 -0.0035844743, -0.0058796853 -0.056101725 -0.0033856034, 0.01781401 -0.051685587 -0.0019982159, -0.0044144243 -0.056749001 -0.0041669905, -0.0043917745 -0.056460485 -0.0036866069, 0.021272972 -0.05288662 -0.00433366, -0.0042399317 -0.056949511 -0.0045609921, -0.0048993081 -0.056793749 -0.0043339431, 0.015831336 -0.051221773 -0.0016283095, 0.01271598 -0.05093658 -0.0015030056, 0.018122867 -0.052581638 -0.0025938749, -0.0047958493 -0.056952581 -0.0046768039, -0.0052469373 -0.056762591 -0.0043339878, 0.021411031 -0.053229526 -0.0053903908, -0.0064978004 -0.056185067 -0.003584519, 0.016143322 -0.052231342 -0.001998201, 0.01838094 -0.053330183 -0.0033856034, -0.0068074614 -0.056220457 -0.0036866367, 0.016423434 -0.053137153 -0.0025939643, -0.0080963224 -0.055745184 -0.0032893717, 0.018574968 -0.053893417 -0.0043335855, 0.012985587 -0.052016154 -0.0016282499, -0.010596052 -0.054598644 -0.0025938153, -0.0097537786 -0.055712149 -0.0035843253, -0.010746971 -0.055375755 -0.0033857077, 0.016657069 -0.053893477 -0.003385514, 0.016979277 -0.054935485 -0.0065031946, 0.018695563 -0.054242969 -0.0053904951, -0.0093006939 -0.056155339 -0.004166618, -0.0092532337 -0.055870011 -0.0036865771, -0.0091153234 -0.056374922 -0.004561007, 0.01324141 -0.053041384 -0.001998201, -0.0097661465 -0.056161761 -0.0043339133, 0.016832978 -0.054462463 -0.0043336451, -0.0096695721 -0.056330249 -0.0046767443, -0.010131299 -0.056097075 -0.0043339431, 0.011547327 -0.052354112 -0.0016285032, 0.0082282126 -0.051851183 -0.0015031844, -0.010860324 -0.055960581 -0.0043340027, 0.013471216 -0.053961307 -0.0025938153, -0.027971223 -0.048071757 -0.0025937557, -0.028382987 -0.047598705 -0.0024430305, -0.028369427 -0.048756003 -0.0033852905, 0.016942143 -0.054815903 -0.0053906441, -0.028584987 -0.047358364 -0.0023714304, 0.011775017 -0.053386107 -0.0019981861, 0.013662934 -0.054729417 -0.0033856779, -0.029842019 -0.0470476 -0.0026725084, 0.011979043 -0.054311857 -0.0025939643, -0.030526042 -0.045353115 -0.0019976944, -0.030517519 -0.046136633 -0.0023715198, 0.013807163 -0.05530709 -0.0043336898, -0.031845495 -0.045597717 -0.0025934279, -0.030961961 -0.045962736 -0.0024429411, -0.032298654 -0.046246871 -0.0033850968, 0.012149736 -0.055085018 -0.0033857375, -0.032239899 -0.04507567 -0.0024431348, 0.008402586 -0.052949846 -0.0016283542, -0.032432362 -0.044811234 -0.0023714006, 0.013896808 -0.055665895 -0.00539051, 0.012384638 -0.056150019 -0.006503284, -0.03364791 -0.04440552 -0.0026723146, 0.012277871 -0.055666715 -0.00433366, 0.0085681826 -0.053993687 -0.0019984543, -0.034216091 -0.042637989 -0.0019976348, -0.034897029 -0.042082444 -0.0019977093, -0.034256503 -0.043432862 -0.0023712367, 0.0071845055 -0.053128824 -0.001628533, 0.003677696 -0.052370861 -0.0015029758, -0.034673929 -0.043231353 -0.0024427921, 0.012357578 -0.056027845 -0.0053906441, -0.035502061 -0.042812273 -0.0025933534, -0.036007464 -0.043421715 -0.0033850819, 0.008716777 -0.054929987 -0.002594009, -0.05646351 -0.0032994747 -0.00358136, -0.056553274 -0.0029718578 -0.0036835223, 0.0073262453 -0.054176182 -0.0019983053, 0.0088409185 -0.05571194 -0.0033856183, -0.056306019 -0.0016491711 -0.0032862127, 0.0074532777 -0.055115521 -0.0025940686, 0.0089343041 -0.056300178 -0.0043339729, -0.056559891 -1.0699034e-05 -0.0035812557, -0.056401178 0.00096794963 -0.0033824444, 0.007559374 -0.055900142 -0.0033857375, -0.056918383 -0.00050476193 -0.004163757, -0.056629077 -0.00050210953 -0.0036835223, 0.0037557334 -0.05348067 -0.001628384, -0.057103708 -0.00066663325 -0.0045578331, 0.007705465 -0.056980997 -0.0065033287, 0.0089922547 -0.056665301 -0.0053907633, -0.057004973 -3.7103891e-06 -0.0043306202, 0.0076390356 -0.056490466 -0.0043338537, -0.057154343 -0.00011307001 -0.0046733171, 0.0038298815 -0.054534987 -0.0019982308, -0.05700399 0.00032354891 -0.0043308139, -0.056536809 0.0016052276 -0.0035811514, 0.007688567 -0.056856871 -0.0053906441, -0.056598514 0.0019250512 -0.0036833882, -0.056237146 0.0032357723 -0.0032859892, -0.056348011 0.0048899651 -0.0035810769, -0.056101933 0.0058798343 -0.0033822656, -0.056749091 0.0044145286 -0.004163295, -0.056460619 0.0043922067 -0.0036832839, -0.056949928 0.0042402148 -0.0045577735, -0.056794107 0.0048994273 -0.0043303072, -0.056952909 0.0047960281 -0.0046730489, -0.05676274 0.0052469224 -0.0043304116, -0.056185365 0.0064980835 -0.0035808384, -0.056220636 0.0068076402 -0.0036832094, -0.055745631 0.0080965459 -0.003285557, -0.055712506 0.0097538531 -0.0035806596, -0.056155652 0.009300828 -0.0041632056, -0.055870265 0.0092536211 -0.0036830306, -0.056375295 0.0091154724 -0.0045571923, -0.056162164 0.0097662061 -0.00432989, -0.056330487 0.0096697509 -0.0046729594, -0.056097537 0.010131359 -0.0043302476, 0.048237443 -0.029317036 -0.0034331679, 0.047780007 -0.030442983 -0.0037198067, 0.046984673 -0.031285316 -0.0034333616, 0.046735242 -0.032639518 -0.0043324679, 0.045643136 -0.033212006 -0.0034333467, -0.010214135 -0.052630559 -0.0016283691, -0.014762238 -0.051540151 -0.0016283244, -0.010002077 -0.051538214 -0.0015031099, -0.014455944 -0.050470501 -0.0015028566, 0.045096964 -0.034292266 -0.0037197471, -0.010415494 -0.053667948 -0.0019982159, -0.015053362 -0.052555889 -0.0019982755, 0.044231743 -0.035069674 -0.003433615, 0.0027604252 -0.055499807 -0.002555415, -0.015314385 -0.053467408 -0.0025940239, -0.015532285 -0.054228351 -0.0033855587, -0.015696228 -0.054801047 -0.0043335855, 0.0015153736 -0.055261165 -0.0023486465, 0.00033701956 -0.055567279 -0.0025555342, -0.01896812 -0.050144911 -0.0016280562, -0.0020729601 -0.055529624 -0.0025555789, -0.00093777478 -0.054661289 -0.0019983053, -0.018799827 -0.049018487 -0.0015030801, -0.015832812 -0.055276901 -0.0065031201, -0.015798256 -0.055156603 -0.0053905249, -0.01934202 -0.051133409 -0.0019979924, -0.0032975823 -0.055183515 -0.0023486763, -0.019677326 -0.052020177 -0.0025938451, -0.0044932067 -0.055386424 -0.0025555193, -0.0068907589 -0.055139348 -0.0025554448, -0.0056983382 -0.054371461 -0.0019982308, -0.019957483 -0.052760631 -0.0033855885, -0.02016817 -0.05331777 -0.00433366, -0.0080852658 -0.054687619 -0.0023486614, -0.023044124 -0.048407376 -0.0016281307, -0.023000523 -0.047193393 -0.0015027821, -0.0092894137 -0.054786235 -0.0025555342, -0.020343378 -0.053780571 -0.0065031201, -0.020298988 -0.053663611 -0.0053904057, -0.029317215 -0.04823719 -0.0034343302, -0.02349852 -0.049361318 -0.0019978881, -0.028669104 -0.049270928 -0.0043334663, -0.023906007 -0.050217554 -0.0025938749, -0.030443355 -0.047779948 -0.0037205666, -0.031285569 -0.046984479 -0.0034343451, -0.02424632 -0.050932348 -0.0033855289, -0.032639891 -0.046735182 -0.0043331534, -0.033212155 -0.045642987 -0.0034341365, -0.024502352 -0.051470116 -0.0043335408, -0.034292802 -0.045096904 -0.0037202835, -0.024661213 -0.051803946 -0.0053904951, -0.024715081 -0.051917195 -0.0065031946, -0.035069942 -0.044231623 -0.0034340322, -0.036387831 -0.043880194 -0.0043329895, -0.055500001 -0.0027602911 -0.0025525093, -0.028855041 -0.049590454 -0.0053905249, -0.028917894 -0.04969871 -0.006502986, 0.049148858 -0.029488713 -0.0051610172, 0.04892157 -0.02980116 -0.0050477982, -0.035161078 -0.040472105 -0.0016277134, 0.04839094 -0.030878335 -0.0055245906, 0.047141328 -0.032922834 -0.006502226, 0.047648162 -0.031797439 -0.0050480068, -0.035854146 -0.041270033 -0.0019976348, 0.047449902 -0.032151327 -0.0051609129, 0.047038555 -0.032851279 -0.0053893775, 0.046544135 -0.033449307 -0.0051611364, -0.036475882 -0.041985855 -0.0025933236, 0.046290547 -0.033743232 -0.0050481111, 0.045673713 -0.034771636 -0.0055250227, -0.036995023 -0.042583466 -0.0033849627, 0.044856682 -0.03562732 -0.0050482899, -0.037513435 -0.038302049 -0.0016276985, 0.044630632 -0.035962671 -0.0051610619, -0.037754506 -0.036480665 -0.0015021563, 0.0030069798 -0.053756639 -0.0016863197, 0.0026298612 -0.053889692 -0.0017192662, -0.037385657 -0.043033108 -0.0043331683, -0.03825295 -0.039057016 -0.0019975007, 0.0014323294 -0.053457662 -0.0015995204, -0.00090070069 -0.052492037 -0.0015030801, -0.038554564 -0.037253767 -0.0016276985, 0.00027666986 -0.053953007 -0.0017192364, -0.040233508 -0.041078925 -0.0065025389, -0.037628204 -0.043312117 -0.0053899884, -0.03670384 -0.044261098 -0.0065025538, -0.036623687 -0.044164956 -0.005390048, -0.00012372434 -0.053840607 -0.0016861558, -0.00091969967 -0.053604499 -0.0016284138, -0.00030298531 -0.054640353 -0.0019848645, -0.038916245 -0.039734244 -0.0025931299, -0.0016865432 -0.053814292 -0.001686275, -0.039314568 -0.037988037 -0.001997292, -0.039470345 -0.040299997 -0.0033847392, -0.0020722747 -0.053913921 -0.0017190427, -0.039996296 -0.038646862 -0.002593115, -0.003229171 -0.053379476 -0.001599431, -0.0054723471 -0.052213848 -0.001503244, -0.03988716 -0.040725306 -0.0043330789, -0.0044220686 -0.05377233 -0.001719147, -0.0048128814 -0.053625286 -0.0016861558, -0.0055882335 -0.053320363 -0.0016285479, -0.040548369 -0.03507337 -0.001627475, -0.040790394 -0.033051357 -0.0015020967, -0.0050570518 -0.054406598 -0.0019848943, -0.0063674301 -0.053462982 -0.0016862154, -0.04056561 -0.039197013 -0.0033847988, -0.040145889 -0.040989563 -0.0053897053, -0.0067588985 -0.053528711 -0.0017191768, -0.041347608 -0.035764679 -0.0019970536, -0.0078661144 -0.052895278 -0.00159958, -0.040994018 -0.039610937 -0.0043327957, -0.0090872496 -0.053183049 -0.0017190129, -0.0094653517 -0.053002194 -0.0016861707, -0.041654825 -0.033751741 -0.0016272664, -0.042064711 -0.036384895 -0.0025930405, -0.0097728968 -0.053760022 -0.0019845963, -0.029488966 -0.049148679 -0.0051620007, -0.041260213 -0.039867833 -0.005389601, -0.043488353 -0.037616208 -0.0065021962, -0.042475849 -0.034417108 -0.0019970685, -0.029801488 -0.048921317 -0.0050488859, -0.03292349 -0.047140941 -0.0065028071, -0.030878767 -0.048390523 -0.0055257082, -0.042663321 -0.036902845 -0.0033846945, -0.031797692 -0.047648221 -0.0050486475, -0.032851502 -0.047038168 -0.0053901076, -0.032151729 -0.047449663 -0.0051618516, -0.033449546 -0.046543673 -0.0051619858, -0.03374356 -0.046290547 -0.005048871, -0.034771964 -0.0456734 -0.0055256039, -0.043393701 -0.037534282 -0.0053896606, -0.035627812 -0.044856295 -0.0050486326, -0.035962924 -0.044630453 -0.0051615536, -0.053756922 -0.0030069351 -0.0016836226, -0.05388996 -0.0026297122 -0.0017162263, 0.042944193 0.063711137 -0.049001366, 0.038923562 0.0674669 -0.049370915, 0.043534875 0.064587504 -0.049370959, 0.038395584 0.066551611 -0.049001083, 0.006667465 0.074876264 -0.047709808, 0.0072963536 0.075533837 -0.048404887, 0.007220149 0.0747457 -0.047613412, 0.042414188 0.062925026 -0.048405796, 0.037921607 0.065730333 -0.048405275, 0.0071630925 0.074152693 -0.04666537, 0.0063906908 0.074940816 -0.047757238, 0.006319657 0.075216949 -0.048046365, 0.0062031597 0.074393794 -0.046959803, 0.0071275383 0.073784426 -0.045608461, 0.0057462901 0.074834585 -0.047564372, 0.005722031 0.074516758 -0.047102883, 0.0099825859 0.076372787 -0.049086899, 0.0097999871 0.075152665 -0.04832609, 0.0083507001 0.075727254 -0.048627257, 0.041971743 0.062268436 -0.047614142, 0.0095395297 0.076939896 -0.04927364, 0.037526011 0.065044492 -0.047614172, 0.010628954 0.077161685 -0.049370363, 0.010202572 0.076096624 -0.048973262, 0.0084619373 0.074576452 -0.047564462, 0.0079981536 0.075662434 -0.048555598, 0.041431874 0.061467767 -0.045609146, 0.042253941 0.060752869 -0.044496894, 0.037706941 0.063675255 -0.044496521, 0.047933862 0.061393321 -0.049371377, 0.044156775 0.065510049 -0.049496427, 0.048618674 0.062270254 -0.049496412, 0.010506466 0.075850889 -0.048866987, 0.011719078 0.075934395 -0.0490008, 0.01111044 0.075371757 -0.048627019, 0.047283545 0.060560286 -0.049001679, 0.0080040246 0.074221626 -0.046959922, 0.0084261298 0.074259683 -0.047103167, 0.04670012 0.059813023 -0.048405811, 0.046212867 0.059188962 -0.047614202, 0.011152148 0.074565247 -0.047957301, 0.011672601 0.075183362 -0.048555687, 0.045618653 0.05842787 -0.045609504, 0.045846224 0.058719471 -0.046666309, 0.046575889 0.057506293 -0.04449676, 0.011770606 0.074558586 -0.048046112, 0.012790442 0.074799627 -0.048404962, 0.01182352 0.074277446 -0.047757104, 0.011180103 0.074217618 -0.047564328, 0.053309888 0.056787595 -0.04937157, 0.052843735 0.05872719 -0.049496993, 0.056811541 0.054897889 -0.049497053, 0.052099526 0.057900012 -0.049371466, 0.012101755 0.074191913 -0.047709852, 0.012657017 0.074019164 -0.047613502, 0.012556449 0.073431998 -0.046665341, 0.052586481 0.056017131 -0.049001664, 0.011608034 0.07374388 -0.046959728, 0.0513926 0.057114333 -0.049001858, 0.011132434 0.073902428 -0.047103226, 0.012494266 0.073067442 -0.04560867, 0.047837615 0.059700489 -0.048826948, 0.05193764 0.05532597 -0.048405945, 0.050758407 0.056409732 -0.048406005, 0.047824487 0.058917955 -0.048405901, 0.047293663 0.057910517 -0.047157079, 0.046933576 0.058334246 -0.047313645, 0.051395848 0.054748535 -0.04761447, 0.050228819 0.055821076 -0.04761444, 0.048421323 0.057396173 -0.047614083, 0.048112676 0.059272975 -0.048730254, 0.056011334 0.054124653 -0.049371615, 0.050987974 0.0543143 -0.046666443, 0.049830347 0.055378214 -0.046666399, 0.055251285 0.053390369 -0.049002081, 0.050563335 0.057410181 -0.048826888, 0.049851432 0.057212844 -0.048405841, 0.049285859 0.056224629 -0.047157153, 0.049596503 0.056087747 -0.04731369, 0.050734952 0.054044604 -0.045609683, 0.050649002 0.053953215 -0.044497222, 0.049582973 0.055103421 -0.045609623, 0.050151929 0.057557568 -0.048730403, 0.046771571 0.05750908 -0.045609236, 0.048135117 0.056372613 -0.045609564, 0.057312712 0.052744761 -0.0493716, 0.060502291 0.050801158 -0.049497277, 0.0461386 0.058018133 -0.045609325, 0.047122076 0.057700485 -0.046666414, 0.048206523 0.056797594 -0.046666384, 0.049106956 0.056020916 -0.046666205, 0.054569647 0.052731737 -0.048406214, 0.074872658 0.0051928312 -0.047568351, 0.075859234 0.0058118105 -0.048559368, 0.075988889 0.0054426789 -0.048630849, 0.074810997 0.0064786375 -0.047617197, 0.075683385 0.0039473176 -0.048330188, 0.056534991 0.052029103 -0.049002141, 0.074439719 0.0055903643 -0.046963692, 0.054000154 0.052181304 -0.047614679, 0.074217603 0.0064271092 -0.04666917, 0.073849097 0.0063952953 -0.045612425, 0.055837467 0.051387101 -0.048406273, 0.074554592 0.005170837 -0.047107115, 0.05357185 0.051767394 -0.046666756, 0.055254892 0.050850868 -0.047614738, 0.075012222 0.0024549365 -0.047568426, 0.076136768 0.0026636422 -0.048631012, 0.076052174 0.0021113902 -0.048559636, 0.075084105 0.0010003597 -0.04761745, 0.053306013 0.051510409 -0.045609817, 0.054452062 0.050112128 -0.04449743, 0.059650272 0.050085723 -0.049371988, 0.0746236 0.0019593835 -0.046963826, 0.07469362 0.0024445802 -0.047107026, 0.054816455 0.050447479 -0.04666689, 0.07448855 0.00099240243 -0.046669424, 0.074118838 0.00098754466 -0.045612499, 0.07505177 -0.00027272105 -0.047568694, 0.076183364 -7.7486038e-05 -0.048631266, 0.075769886 -0.0015603006 -0.048330396, 0.058840826 0.049406216 -0.04900229, 0.07608068 0.00028635561 -0.048559785, 0.074649125 0.00015059114 -0.0469639, 0.054544404 0.050197139 -0.045609936, 0.058114871 0.048796684 -0.048406556, 0.074733004 -0.00027169287 -0.047107056, 0.06100966 0.048420444 -0.049372181, 0.063898459 0.046457067 -0.049497321, 0.07533358 -0.0029616356 -0.047961533, 0.0761296 -0.0028597862 -0.048631504, 0.076004192 -0.0034181774 -0.048560023, 0.057508305 0.048287511 -0.047614902, 0.060181826 0.047763437 -0.04900226, 0.05705224 0.047904253 -0.046666831, 0.07512106 -0.0036571026 -0.047761589, 0.074991748 -0.003013581 -0.047568873, 0.075746983 -0.0045302957 -0.048409402, 0.059439242 0.047174364 -0.048406422, 0.075066611 -0.0039325953 -0.047714368, 0.056769118 0.04766646 -0.045610085, 0.0749567 -0.0044829994 -0.047617704, 0.074362114 -0.0044475347 -0.046669781, 0.074567646 -0.0034838319 -0.046964288, 0.073992983 -0.0044255108 -0.045613125, 0.057964563 0.04600364 -0.044497639, 0.074673072 -0.0030008852 -0.047107533, 0.058818996 0.046681911 -0.047615096, 0.074832454 -0.0057369769 -0.047568962, 0.075900406 -0.0052406043 -0.048560008, 0.075977281 -0.0055972189 -0.048631474, 0.062998533 0.045802772 -0.049372196, 0.075456217 -0.0070598572 -0.048330724, 0.074461296 -0.0052897483 -0.046964228, 0.0583525 0.046311617 -0.046666741, 0.062143743 0.045181349 -0.049002528, 0.074514702 -0.0057125986 -0.047107533, 0.058062747 0.046081677 -0.045610264, 0.074918717 -0.0084301233 -0.047961935, 0.075722039 -0.0083682835 -0.048631653, 0.075555176 -0.0089297444 -0.048560396, 0.06137687 0.044623807 -0.04840669, 0.064381197 0.04383789 -0.049372137, 0.066983402 0.041886479 -0.049497977, 0.074934423 -0.0090483874 -0.04805094, 0.060736567 0.044158131 -0.047615051, 0.075214028 -0.010047436 -0.048409835, 0.063507631 0.043243065 -0.049002513, 0.074656084 -0.0091105103 -0.047762021, 0.074573085 -0.0084663332 -0.047569051, 0.060254738 0.04380779 -0.04666701, 0.074580863 -0.0093883276 -0.047714561, 0.074429467 -0.0099426359 -0.047617957, 0.073838815 -0.0098637491 -0.046670184, 0.062723979 0.042709485 -0.048406601, 0.07411547 -0.0089090168 -0.046964705, 0.073472291 -0.0098147541 -0.045613185, 0.074256271 -0.0084301382 -0.047107697, 0.059955552 0.043590397 -0.045610249, 0.075960755 -0.012723461 -0.049091771, 0.074743778 -0.012521863 -0.048330948, 0.075371742 -0.011087552 -0.048631936, 0.061167881 0.041649729 -0.044497773, 0.076543972 -0.012298957 -0.049278557, 0.076729953 -0.013374656 -0.049375579, 0.075676695 -0.012934566 -0.048978209, 0.066039816 0.041296586 -0.049372509, 0.074215934 -0.011170581 -0.04756932, 0.06206952 0.04226391 -0.047615334, 0.075318992 -0.010739759 -0.048560351, 0.065143794 0.040736198 -0.049002603, 0.075419396 -0.013235092 -0.04887192, 0.07545878 -0.014451072 -0.049005702, 0.074916512 -0.013832808 -0.048631832, 0.073877767 -0.010702193 -0.046964645, 0.06157729 0.041928604 -0.046667188, 0.073900759 -0.011123329 -0.047107875, 0.06433998 0.040233612 -0.048406884, 0.074107379 -0.013853967 -0.047962248, 0.074706644 -0.014394194 -0.04856053, 0.061271414 0.041720405 -0.045610592, 0.067409113 0.039021596 -0.049372524, 0.069741741 0.037111998 -0.049498007, 0.063668743 0.039813727 -0.047615454, 0.074078277 -0.01447174 -0.048051149, 0.07427983 -0.015510678 -0.048410013, 0.066494375 0.038491905 -0.049002767, 0.074876681 -0.021443501 -0.049375936, 0.07727848 -0.016399115 -0.049501017, 0.075946212 -0.021749809 -0.049501434, 0.073795527 -0.014515832 -0.047762454, 0.073758274 -0.013873696 -0.047569528, 0.063163638 0.039498031 -0.046667278, 0.065673962 0.03801702 -0.048407048, 0.073699057 -0.014793888 -0.047714993, 0.073504806 -0.015348956 -0.047618479, 0.072921753 -0.015227333 -0.046670526, 0.062850133 0.039301872 -0.045610383, 0.07326889 -0.014286384 -0.04696475, 0.072559834 -0.015151769 -0.045613497, 0.064044654 0.037073791 -0.044498131, 0.068759531 0.036589384 -0.049372658, 0.073445112 -0.013814896 -0.047108024, -0.0065748245 0.074753776 -0.047547907, -0.0078808665 0.074319527 -0.047103107, -0.0079144835 0.074636579 -0.047564447, 0.064988837 0.037620276 -0.047615409, -0.0064742118 0.074197948 -0.046627909, -0.0066926479 0.075492933 -0.048326105, -0.0051835477 0.074875757 -0.047564372, -0.0051615089 0.074557692 -0.047102958, -0.0077652037 0.073715612 -0.045588404, -0.0090856552 0.073569119 -0.045608684, -0.0082982928 0.07418941 -0.046959847, -0.0090700537 0.073444709 -0.044495896, -0.073198259 0.026620045 -0.049373418, -0.075946197 0.021755531 -0.049498916, -0.074243769 0.027000248 -0.049498469, 0.067826673 0.036092803 -0.049002916, -0.07487677 0.021449178 -0.049373507, -0.005068019 0.073949814 -0.045588359, -0.0046762675 0.07450515 -0.046959817, -0.0036912262 0.074036077 -0.04560858, -0.0036850274 0.073910892 -0.04449594, 0.064473167 0.03732188 -0.046667397, -0.072205022 0.026258945 -0.049003482, -0.0011189878 0.075034097 -0.047548041, -0.0024591088 0.075014845 -0.047564313, -0.0011917651 0.075779527 -0.04832609, 0.00022216141 0.075394437 -0.047957137, -0.07386075 0.021158174 -0.04900372, -0.001050055 0.074472621 -0.04662776, -0.0024486184 0.074696109 -0.047103047, 0.00028218329 0.075054511 -0.047564521, 0.066989511 0.035647646 -0.048407063, 0.00028087199 0.07473582 -0.047103122, -0.071314171 0.025934815 -0.048407644, -0.002368331 0.074085444 -0.045588359, -0.0028698146 0.074596807 -0.046959728, -0.072949275 0.020896941 -0.048407942, 0.064153284 0.037136465 -0.045610592, 0.0003388375 0.074122712 -0.045588106, 0.0017226636 0.074108019 -0.045608595, 0.0017198473 0.073982716 -0.044495925, 0.070077538 0.033996701 -0.049372971, 0.072160438 0.032156631 -0.04949826, 0.00076547265 0.074648023 -0.046959758, -0.070570067 0.02566424 -0.047616169, -0.072188333 0.020679057 -0.047616616, 0.0043429583 0.074916586 -0.047547951, 0.0030095279 0.074994534 -0.047564313, 0.0043156445 0.075665995 -0.048326105, 0.0029966831 0.074676171 -0.047103181, 0.0057021827 0.075178683 -0.047957033, 0.004379645 0.074351102 -0.046627775, 0.066290736 0.035275474 -0.047615692, -0.070010141 0.025460646 -0.046667948, -0.071615443 0.020514995 -0.046668351, 0.003041178 0.074061155 -0.045588344, 0.0025738627 0.074607655 -0.046959847, -0.069662616 0.025334239 -0.045611396, -0.071260035 0.020413041 -0.045611516, -0.071139529 0.020378485 -0.04449898, 0.069126591 0.033535555 -0.04900302, -0.069462478 0.025516927 -0.044498563, 0.0057439059 0.073900595 -0.04558824, 0.0071154237 0.073659733 -0.04449603, -0.071163327 0.031661376 -0.049373046, -0.07217972 0.032113403 -0.049498141, 0.065764859 0.03499572 -0.046667457, 0.0097818524 0.074402064 -0.047547862, -0.070197701 0.031231731 -0.049003169, 0.0097863525 0.073834151 -0.046627954, 0.068273723 0.03312178 -0.048407197, 0.0084345341 0.07364209 -0.0455883, 0.011118323 0.07328482 -0.04558827, 0.065438375 0.034821972 -0.045610845, -0.069331437 0.030846387 -0.04840745, 0.066579923 0.032299802 -0.044498339, 0.012473032 0.072943866 -0.044496, -0.068608031 0.030524373 -0.047616005, 0.071144164 0.031703666 -0.049372897, 0.049028233 0.060523093 -0.049371213, 0.049426556 0.058824316 -0.049001694, 0.067561328 0.032776162 -0.047615632, 0.050303027 0.059947997 -0.049440935, -0.068063885 0.030282259 -0.046667919, 0.070178941 0.031273574 -0.049003229, 0.051110417 0.058775038 -0.049371496, -0.067725956 0.030131817 -0.045610949, -0.067414686 0.030519351 -0.044498399, 0.067025393 0.032516047 -0.046667561, -0.068781495 0.036548212 -0.049372673, 0.048874304 0.058050007 -0.048405752, -0.069763988 0.037070125 -0.049497977, 0.0693129 0.030887663 -0.048407227, 0.074940726 0.0038520694 -0.04755187, 0.074381977 0.0037673116 -0.046631768, -0.067848071 0.036052361 -0.049002945, 0.06669271 0.032354563 -0.045611024, 0.073947161 0.0050728023 -0.045592219, 0.07372424 0.0063843727 -0.044499695, -0.067010999 0.035607532 -0.048407212, 0.068589717 0.030565381 -0.047615886, 0.074083 0.0023688227 -0.045592353, 0.07399337 0.00098590553 -0.044499934, -0.06631197 0.035236001 -0.047615722, 0.075022131 -0.001610443 -0.047552198, 0.07237196 0.028790817 -0.049373239, 0.074227601 0.027044684 -0.049498752, 0.074458629 -0.0016634464 -0.046632111, 0.068045631 0.03032285 -0.046667889, 0.07412003 -0.00033403933 -0.045592383, -0.06578587 0.034956366 -0.046667516, 0.074058428 -0.0030409098 -0.045592606, -0.065459222 0.034782708 -0.045610666, -0.065007105 0.035359025 -0.044498175, 0.071390033 0.028400168 -0.049003303, 0.073867947 -0.0044180155 -0.044500351, -0.066064611 0.041257232 -0.04937236, 0.074705973 -0.007064566 -0.047552586, 0.067707822 0.030172482 -0.045611009, 0.074139193 -0.0070850402 -0.046632335, 0.068759844 0.027353734 -0.044498608, -0.067008346 0.041846544 -0.049497768, -0.065168232 0.040697411 -0.049002573, 0.073898092 -0.0057391524 -0.04559277, 0.070509017 0.028049648 -0.048407495, 0.073639035 -0.0084341019 -0.045593068, 0.073348135 -0.0097981691 -0.044500664, -0.064364061 0.040195316 -0.04840681, 0.07318221 0.026663676 -0.049373299, 0.069773421 0.027756885 -0.047615901, 0.073993787 -0.012481064 -0.047552824, -0.0636926 0.03977567 -0.047615379, 0.073425472 -0.012469217 -0.046632737, 0.072189197 0.026302025 -0.049003512, 0.07328251 -0.011113614 -0.045593098, -0.063187271 0.039460286 -0.046667218, 0.072827443 -0.013782591 -0.045593277, 0.072436988 -0.015126139 -0.044501036, 0.069220036 0.027536809 -0.046667978, -0.062873662 0.039264306 -0.045610577, -0.062253043 0.040009871 -0.044498041, -0.063026115 0.045765176 -0.049372151, 0.07129854 0.025977507 -0.048407614, -0.063926384 0.04641889 -0.049497724, -0.062170833 0.04514423 -0.049002513, 0.068876326 0.027400002 -0.045611262, 0.070554644 0.025706336 -0.047616214, -0.061403677 0.04458721 -0.04840672, 0.074280322 0.023431182 -0.049373493, 0.075933188 0.021800891 -0.049498916, -0.060763165 0.044121876 -0.047615156, 0.069994837 0.025502458 -0.046668023, 0.073272467 0.023113295 -0.049003631, -0.059981748 0.043554485 -0.045610353, -0.0602808 0.043771818 -0.046666831, -0.05916664 0.044447199 -0.044497624, 0.069647372 0.025375888 -0.045611411, -0.059680209 0.05004999 -0.049371868, -0.060532868 0.050765082 -0.049497381, 0.070573002 0.022261545 -0.044499025, 0.074863687 0.021493956 -0.049373522, -0.058870524 0.049371034 -0.049002051, 0.072368249 0.022828028 -0.048407823, -0.058693856 0.05120331 -0.049371913, -0.056844294 0.05486387 -0.049497172, 0.073847994 0.021202385 -0.049003899, -0.058143958 0.048761889 -0.048406303, 0.071613193 0.022589818 -0.047616258, -0.057897478 0.050508514 -0.049002096, 0.072936714 0.020940557 -0.048407912, -0.057537362 0.04825291 -0.047614902, 0.07104516 0.022410542 -0.046668157, -0.057183161 0.049885094 -0.048406541, 0.072175771 0.02072221 -0.047616333, 0.070692524 0.02229917 -0.045611501, 0.075792313 0.017946482 -0.049373761, 0.077268779 0.016450942 -0.049499199, -0.056586519 0.04936482 -0.047614664, -0.056797624 0.047632441 -0.045610145, -0.057081088 0.047870234 -0.046666831, 0.071603134 0.020557687 -0.046668291, -0.055764452 0.048647568 -0.044497401, 0.074763894 0.017702997 -0.049003974, -0.056043729 0.054091215 -0.049371615, -0.056137517 0.048972979 -0.046666712, 0.071247801 0.020455629 -0.045611665, -0.055283308 0.053357437 -0.049002007, 0.072009489 0.017050683 -0.044499189, 0.076180607 0.016219363 -0.049373806, -0.05585897 0.04873012 -0.045609891, 0.073841363 0.017484605 -0.048408166, -0.054799885 0.055351079 -0.04937166, -0.052878842 0.058695644 -0.049496919, 0.075146794 0.015999243 -0.049004033, -0.054601237 0.052699044 -0.048406228, 0.073070988 0.017302215 -0.047616482, -0.054056406 0.054600075 -0.049001783, -0.054031417 0.052149013 -0.047614783, 0.074219614 0.015801862 -0.048408255, 0.072491214 0.017164811 -0.046668425, -0.053389445 0.053926334 -0.048406094, -0.053602844 0.051735446 -0.046666652, 0.073445305 0.015636832 -0.047616661, 0.07213138 0.017079666 -0.045611873, -0.052832261 0.053363681 -0.047614649, 0.076899931 0.012366116 -0.049373895, 0.078227848 0.011020809 -0.049499586, -0.053336874 0.051478669 -0.045609877, 0.072862729 0.015512735 -0.046668589, -0.052064911 0.052588388 -0.044497386, -0.052134335 0.057868943 -0.049371541, 0.075856537 0.012198403 -0.049004316, -0.0524133 0.05294019 -0.046666548, 0.072501048 0.015435711 -0.045611843, -0.051426724 0.057083741 -0.049001694, 0.073061675 0.01174891 -0.044499472, 0.077126041 0.010865718 -0.049374118, -0.052152976 0.052677423 -0.045609802, 0.074920371 0.012047827 -0.048408359, -0.050613701 0.05920355 -0.049371481, -0.048656076 0.062241107 -0.04949668, -0.050792247 0.056379467 -0.048405915, 0.076079577 0.01071845 -0.04900445, 0.074138761 0.011921987 -0.047617078, -0.049926683 0.058400273 -0.049001813, -0.050262287 0.055791065 -0.04761444, 0.075140953 0.010586128 -0.048408493, 0.073550582 0.011827528 -0.046668783, -0.049310878 0.057679668 -0.048406035, 0.074356914 0.010475487 -0.047617078, -0.049863577 0.055348426 -0.046666354, 0.073185444 0.011768833 -0.045612067, 0.073767051 0.010392517 -0.046668932, -0.048796356 0.05707787 -0.047614336, -0.049616024 0.055073693 -0.045609564, -0.048087537 0.056248516 -0.044496924, 0.077597141 0.0067199916 -0.049374297, 0.078805968 0.005537048 -0.049499944, -0.047970712 0.061364666 -0.049371347, 0.0734009 0.010340676 -0.045612231, 0.07654433 0.0066287667 -0.049004689, -0.048409164 0.056624934 -0.04666619, -0.047319785 0.060531929 -0.049001411, 0.075599909 0.0065470934 -0.048408806, -0.048168927 0.056343898 -0.045609668, -0.046735957 0.059785098 -0.048405766, -0.046157256 0.062740192 -0.049371332, -0.044195801 0.0654836 -0.049496502, -0.046248347 0.059161425 -0.047614276, -0.045531034 0.061888918 -0.049001426, -0.045881376 0.058692023 -0.046666175, -0.044969171 0.061125353 -0.048405603, -0.045653567 0.05840075 -0.045609549, -0.04385373 0.059608728 -0.044496849, -0.044499815 0.06048739 -0.047614202, -0.043573275 0.064561442 -0.049371094, -0.044146895 0.060007617 -0.04666613, -0.042982325 0.063685507 -0.049001351, -0.043927863 0.059709683 -0.04560937, -0.042451769 0.062899679 -0.048405632, -0.041454494 0.065942168 -0.049371034, -0.039520606 0.068407133 -0.049496338, -0.042008936 0.062243283 -0.047614038, -0.040892035 0.065047234 -0.049001381, -0.041675702 0.061749533 -0.046665952, -0.040387467 0.064244702 -0.048405379, -0.041468725 0.061442941 -0.045609146, -0.039385587 0.06265074 -0.044496581, -0.038963854 0.067443654 -0.049370989, -0.039966121 0.06357424 -0.047614008, -0.038435265 0.066528589 -0.049001157, -0.039648935 0.063069925 -0.046665967, 0.076242298 -0.015920758 -0.049375579, -0.037960917 0.065707803 -0.048405379, 0.075207815 -0.015704647 -0.049005836, 0.07386066 -0.021152437 -0.049006328, -0.03945224 0.062756941 -0.045609221, -0.036530703 0.068792149 -0.049370721, -0.034652531 0.070997357 -0.049496204, 0.072949186 -0.020891413 -0.048410267, -0.037564933 0.065022096 -0.047614083, 0.072188109 -0.020673648 -0.047618791, -0.036034986 0.067858636 -0.049001098, 0.071615472 -0.020509705 -0.046670631, -0.037266985 0.064506188 -0.046665832, 0.071259916 -0.020407856 -0.0456139, 0.07113938 -0.020373344 -0.044501275, -0.067627728 0.030351698 -0.045611084, -0.03559038 0.067021504 -0.048405409, -0.065289065 0.03510116 -0.045610815, -0.037081838 0.064186037 -0.045609146, -0.034707412 0.06535849 -0.044496387, -0.062617391 0.039671853 -0.045610458, -0.034164473 0.069997385 -0.049370676, -0.059626386 0.044040024 -0.045610353, -0.035219073 0.066322163 -0.047613934, -0.0088559538 0.077385187 -0.049370393, -0.0094170421 0.076254159 -0.049000621, -0.0095466077 0.077302948 -0.049370423, -0.008281365 0.078567699 -0.049495697, -0.033701032 0.069047764 -0.049000978, -0.0071665794 0.077197209 -0.04927358, -0.034939691 0.065796092 -0.046665967, -0.0060238242 0.077657014 -0.049370393, -0.0027805269 0.078954071 -0.049495816, -0.033285111 0.068195656 -0.04840526, -0.0038785785 0.077793658 -0.049370363, -0.0033102036 0.077819958 -0.049370274, -0.0038260818 0.076738209 -0.04900068, -0.034766167 0.06546925 -0.045609117, -0.0015964359 0.077512488 -0.049273804, -0.031411886 0.0712751 -0.049370751, -0.029615849 0.073241591 -0.04949604, -0.00046591461 0.077888981 -0.049370363, 0.002733469 0.078955516 -0.049495816, -0.032937914 0.067484125 -0.0476138, 0.0018101782 0.077869192 -0.049370438, 0.0022525638 0.077857688 -0.049370497, 0.0017854869 0.076812655 -0.049000546, -0.030985743 0.070308089 -0.049000934, -0.032676712 0.066948816 -0.046665773, 0.0039818585 0.077426791 -0.049273461, 0.0050944835 0.077723429 -0.049370423, 0.0082342327 0.078572482 -0.049495786, 0.0074891597 0.077529341 -0.049370319, -0.030603364 0.069440618 -0.048405379, 0.0078037083 0.077498421 -0.049370557, 0.0073875338 0.076477498 -0.04900071, -0.032514542 0.066616401 -0.045608908, -0.02984421 0.067717716 -0.044496343, -0.029198825 0.072210163 -0.049370691, 0.013694897 0.077806786 -0.049495935, -0.030284032 0.068715855 -0.04761368, 0.013128206 0.076775894 -0.049370497, 0.032744706 0.066503286 -0.045608878, 0.032474414 0.066635698 -0.045608953, 0.032636508 0.066968217 -0.046665758, -0.028802589 0.071230412 -0.049001008, 0.032958493 0.06625773 -0.044496611, 0.037228182 0.064528435 -0.046665862, 0.037043482 0.06420821 -0.045609191, 0.037407801 0.063996702 -0.045609146, -0.03004387 0.068170667 -0.046665579, 0.041638762 0.061774373 -0.046666011, 0.041879863 0.061163351 -0.045609206, -0.028447211 0.070351377 -0.048405185, -0.029894695 0.067832261 -0.045609027, -0.028150365 0.069617212 -0.04761377, 0.077649206 0.0060896575 -0.049374387, -0.02612561 0.073378041 -0.049370736, -0.024434894 0.075129151 -0.049495876, 0.077402234 0.0043869615 -0.049277797, -0.027927041 0.069064915 -0.046665624, -0.025771081 0.072382197 -0.049001008, 0.077819601 0.0032499582 -0.049374446, 0.079000145 2.6419759e-05 -0.049500138, 0.077880323 0.0010378212 -0.049374789, 0.077885613 0.00053188205 -0.049374759, 0.076823741 0.0010236651 -0.049004883, -0.027788445 0.068722129 -0.045608982, -0.024821654 0.0697155 -0.044496208, -0.025453031 0.07148923 -0.048405081, 0.077517033 -0.0011906475 -0.049277976, 0.077852905 -0.0023130029 -0.049374998, 0.078809202 -0.0054843873 -0.04950048, -0.024090677 0.074071065 -0.049370527, 0.077748314 -0.0046501458 -0.049374998, 0.07772471 -0.0050284714 -0.049374998, -0.025187507 0.070743293 -0.047613576, 0.076693311 -0.004586935 -0.04900521, 0.077230483 -0.006762296 -0.049278393, -0.02376385 0.07306613 -0.049000978, -0.024987802 0.07018207 -0.046665549, 0.077489138 -0.0078639835 -0.049375281, 0.078234509 -0.010968432 -0.049500734, 0.077201203 -0.010312796 -0.04937543, -0.023470551 0.072164446 -0.048405066, 0.077167243 -0.010563403 -0.049375445, 0.076153696 -0.010172874 -0.049005404, -0.024863645 0.069833681 -0.045608759, -0.023225829 0.071411505 -0.047613457, -0.020699888 0.075089321 -0.049370527, -0.019134745 0.07665053 -0.049495757, -0.063058823 0.039665163 -0.046667159, -0.060102791 0.044016153 -0.046667039, -0.023041472 0.070844993 -0.04666549, -0.0085620284 0.075600877 -0.048555627, -0.0092039108 0.074527383 -0.047613457, -0.0093010664 0.07531333 -0.048404902, -0.020419061 0.074070424 -0.04900074, -0.0081908405 0.075744554 -0.048626974, -0.02292712 0.070493191 -0.045608774, -0.019666642 0.071341455 -0.044496119, -0.018865332 0.075571001 -0.049370408, -0.020167083 0.073156506 -0.048405141, -0.018609554 0.074545667 -0.049000785, -0.0048845261 0.076677933 -0.049000606, -0.0054193735 0.075993136 -0.048627034, -0.019956857 0.072393045 -0.047613546, -0.0048711598 0.075928047 -0.048555583, -0.0037787259 0.075791255 -0.048404738, -0.0037392825 0.075000286 -0.047613516, -0.018379644 0.073625833 -0.048404947, -0.0030481517 0.076022923 -0.048555434, -0.019798428 0.071818873 -0.046665519, -0.0026816577 0.076139107 -0.048626885, -0.01818803 0.072857738 -0.047613472, -0.019700214 0.071462244 -0.045608789, -0.015163705 0.076399937 -0.049370423, -0.013741493 0.07779862 -0.049495861, 0.00066302717 0.076830596 -0.049000606, -0.018043786 0.072279692 -0.046665505, 0.00010092556 0.076186165 -0.048627064, -0.01495783 0.075363263 -0.04900071, 0.00065650046 0.076081365 -0.048555553, 0.0017634183 0.075864986 -0.048404858, -0.017954022 0.071920902 -0.04560858, 0.0024815053 0.0760438 -0.048555493, 0.0017450899 0.075073406 -0.047613442, -0.01440686 0.072586656 -0.044495985, 0.002842024 0.076133341 -0.048627019, -0.013548017 0.076703131 -0.049370527, -0.014773443 0.074433342 -0.048404917, -0.013364077 0.075662211 -0.0490008, 0.0062071681 0.076582372 -0.049000666, -0.014619261 0.073656738 -0.047613457, -0.013199165 0.074728638 -0.048404902, 0.0056205243 0.075978667 -0.048626885, -0.014503345 0.073072448 -0.046665311, 0.0061807781 0.07583262 -0.048555702, -0.013061523 0.07394886 -0.047613442, -0.014431417 0.072709695 -0.045608699, -0.012957886 0.073362187 -0.046665326, 0.012950286 0.075734138 -0.04900077, -0.012893453 0.072997972 -0.045608655, 0.037411556 0.064422324 -0.046665937, 0.041864172 0.061621934 -0.04666613, -0.0091308653 0.073936164 -0.04666543, 0.046107829 0.058514103 -0.04666625, 0.076801479 0.0021149665 -0.049004808, 0.075875923 0.0010109395 -0.048409089, 0.076753661 -0.0034347028 -0.049005195, 0.07630536 -0.0089660734 -0.049005419, 0.018697292 0.075612798 -0.049370438, 0.019088894 0.07666187 -0.049495876, 0.018443629 0.074586913 -0.049000666, 0.01821591 0.073666558 -0.048404902, 0.018026099 0.072897807 -0.047613516, 0.017883107 0.072319448 -0.046665296, 0.017794132 0.071960449 -0.045608714, 0.017764017 0.071838886 -0.044496268, 0.024046257 0.074085236 -0.049370512, 0.024389863 0.075143769 -0.049495891, 0.023720071 0.073080271 -0.049000934, 0.023427308 0.072178513 -0.048405111, 0.023182973 0.071425155 -0.04761368, 0.022999033 0.070858687 -0.046665445, 0.02288489 0.07050696 -0.045608684, 0.022960395 0.070350394 -0.044496238, 0.029155582 0.072227478 -0.049370736, 0.029571846 0.073259309 -0.049496144, 0.028759956 0.071247622 -0.049000904, -0.0037097335 0.074405342 -0.046665326, 0.028405011 0.070368454 -0.048405305, 0.028108537 0.069634289 -0.047613531, 0.027885705 0.069081724 -0.046665698, 0.027747259 0.068738833 -0.045608819, 0.02803427 0.068486705 -0.044496134, 0.034122631 0.070017666 -0.049371064, 0.034610063 0.071018025 -0.049496159, 0.033659607 0.06906797 -0.049001083, 0.033244222 0.068215594 -0.048405305, 0.00092382729 0.075207323 -0.047757268, 0.032897413 0.06750381 -0.047613695, 0.0011978894 0.075162932 -0.047709852, 0.0017312169 0.074477673 -0.046665356, 0.039479464 0.068430662 -0.049496233, 0.0045094192 0.058015525 0.020638198, 0.001799643 0.058162823 0.020638406, 0.0017837584 0.057646304 0.019047797, 0.0044691861 0.057500482 0.019047827, 0.0018601418 0.060116887 0.023329556, -0.00018343329 0.061498374 0.024312794, -0.00017949939 0.060145527 0.023329616, -0.00017607212 0.059026435 0.02208668, 0.0018254817 0.05899854 0.02208662, 0.0047657788 0.061313778 0.024312884, 0.0065380931 0.057301894 0.019047678, 0.0065183043 0.0571284 0.01738444, 0.0045742095 0.058849245 0.02208668, 0.0065967143 0.057815298 0.020638168, 0.004660964 0.05996494 0.023329645, 0.0090818405 0.056954309 0.019047827, 0.01121366 0.056395069 0.01738441, 0.0066914856 0.058646217 0.02208668, 0.0091630518 0.0574646 0.020638317, 0.0068183541 0.059758067 0.023329675, 0.0096839666 0.060731336 0.024312943, 0.011247784 0.056566462 0.019047648, 0.0092948079 0.058290213 0.02208668, 0.011348605 0.057073087 0.020638257, 0.0094709694 0.059395462 0.023329556, 0.013635308 0.056038812 0.019047707, 0.015832603 0.05527626 0.017384291, 0.011511803 0.057893306 0.022086591, 0.013757437 0.056540847 0.020638257, 0.011729896 0.05899097 0.023329586, 0.01453951 0.059755325 0.024312824, 0.015880674 0.055444464 0.019047737, 0.013955176 0.057353348 0.02208665, 0.01602295 0.055941164 0.020638078, 0.014219761 0.058440775 0.023329437, 0.018100351 0.054759964 0.019047618, 0.020343333 0.053780124 0.017384112, 0.016253293 0.056744978 0.022086501, 0.018262595 0.055250511 0.020638168, 0.016561449 0.057820663 0.023329645, 0.019300818 0.058391586 0.024312556, 0.020405143 0.053943679 0.019047588, 0.018524915 0.056044459 0.02208662, 0.02058804 0.054426908 0.020638168, 0.018876314 0.057106942 0.023329347, 0.022448182 0.053125963 0.019047499, 0.024714947 0.051916435 0.017384082, 0.020883888 0.055208728 0.022086471, 0.022649318 0.053601816 0.02063787, 0.021279842 0.056255534 0.023329437, 0.023937076 0.056649074 0.024312645, 0.024790168 0.052074194 0.019047588, 0.02297473 0.054372013 0.022086382, 0.025012285 0.052540734 0.020637989, 0.02341035 0.055402845 0.023329377, 0.02665028 0.051147327 0.019047379, 0.028917998 0.049698129 0.017383963, 0.025371671 0.053295717 0.022086561, 0.026889026 0.051605582 0.02063787, 0.02585277 0.054306149 0.023329288, 0.028417885 0.054539159 0.024312526, 0.029005796 0.049849153 0.01904723, 0.027275652 0.052346975 0.022086263, 0.029265761 0.0502958 0.02063781, 0.027792662 0.053339437 0.023329377, 0.030679613 0.048836991 0.01904729, 0.032923356 0.047140419 0.017383784, 0.029686391 0.05101867 0.022086263, 0.03095451 0.049274564 0.020637751, 0.030249089 0.051985726 0.023329109, 0.032714307 0.052075803 0.024312407, 0.033023313 0.047283694 0.019047171, 0.03139928 0.049982503 0.022086054, 0.03331922 0.04770726 0.020637631, 0.031994492 0.050930113 0.023329198, 0.034509942 0.046210006 0.019046903, 0.03670375 0.044260636 0.017383665, 0.033797994 0.048392877 0.022086084, 0.034819171 0.046623796 0.020637631, 0.034438908 0.049310207 0.023329228, 0.036798611 0.049274474 0.024312228, 0.036815271 0.044395149 0.019046932, 0.035319582 0.047293827 0.022085965, 0.037145168 0.044792831 0.020637423, 0.035989091 0.0481904 0.02332893, 0.038116574 0.043283179 0.019046932, 0.040233463 0.041078418 0.017383486, 0.037678972 0.045436338 0.022085905, 0.059122682 -0.016935378 0.024308518, 0.060293481 -0.012123078 0.024308726, 0.057821915 -0.016562641 0.023325354, 0.038457975 0.043670759 0.020637363, -0.053987741 0.020289883 0.01904577, -0.055277318 0.015831694 0.017382115, -0.053781033 0.020342454 0.017382324, 0.038393289 0.046297923 0.02332899, -0.055445537 0.015879706 0.019045487, 0.040644407 0.046153575 0.0243119, -0.054471567 0.020471498 0.020636097, 0.039010614 0.044298485 0.022085756, -0.055942371 0.016021937 0.020636037, 0.040355727 0.041203231 0.019046813, -0.055254236 0.020765588 0.022084579, -0.05674617 0.01625216 0.0220844, -0.056301713 0.021159291 0.023327395, -0.057568386 0.021635309 0.024310574, -0.059122726 0.016932711 0.024310201, 0.039750203 0.045138285 0.023328841, -0.057821929 0.016560227 0.023327336, 0.040717334 0.041572288 0.020637363, -0.052179947 0.024568334 0.019045815, -0.051917553 0.024714231 0.017382458, -0.052647725 0.024788216 0.02063638, 0.041475788 0.040075719 0.019046664, 0.043488339 0.037615716 0.017383188, 0.041302532 0.042169705 0.022085756, -0.053404182 0.025144443 0.022085041, 0.041847423 0.040434629 0.020637184, -0.054416612 0.025620982 0.023327753, -0.055640668 0.026197448 0.024310857, -0.053351954 0.030589536 0.024311185, 0.042085618 0.042969123 0.023328722, -0.050033718 0.028687328 0.019046262, -0.049699128 0.028917149 0.017382801, 0.044226602 0.042733431 0.024311781, 0.042448789 0.0410157 0.022085875, -0.050482005 0.028944135 0.020636752, 0.043620497 0.037729949 0.019046545, -0.051207542 0.029360056 0.022085086, 0.043253601 0.041793272 0.023328632, -0.052178249 0.029916614 0.023327857, 0.044566095 0.036608323 0.019046634, 0.046446264 0.03389585 0.017383218, 0.044011444 0.038068101 0.020637095, -0.047563151 0.032620221 0.0190465, -0.047141448 0.032922357 0.017383173, 0.044965625 0.036936074 0.020637035, -0.047989309 0.032912418 0.020636827, 0.044643924 0.038614795 0.022085607, -0.04867889 0.033385307 0.022085428, 0.04561168 0.037466824 0.022085547, -0.049601734 0.034018278 0.023328096, -0.050717652 0.034783557 0.024311259, 0.04549028 0.039347112 0.023328334, 0.047521919 0.039036036 0.024311513, -0.04478392 0.036341771 0.019046545, -0.044261694 0.036702752 0.017383307, 0.046587378 0.03399919 0.019046485, 0.046476379 0.038177207 0.023328513, -0.045185253 0.036667258 0.020637125, -0.045834556 0.037194163 0.022085458, 0.047367424 0.032903537 0.019046456, 0.049086615 0.029944867 0.017382801, -0.046703532 0.037899181 0.023328483, 0.047004819 0.034303531 0.020636797, -0.047754064 0.038751736 0.024311423, 0.047791824 0.033198237 0.020637035, -0.041714266 0.039827421 0.019046754, -0.041079402 0.04023245 0.017383441, -0.042088136 0.04018423 0.020637408, 0.047680393 0.034796432 0.022085398, 0.048478618 0.033675313 0.022085369, -0.04269293 0.040761679 0.022085667, 0.048584312 0.035456225 0.023328185, 0.050508946 0.035085589 0.024311393, -0.043502286 0.04153432 0.023328543, -0.044480994 0.042468771 0.024311811, 0.04923594 0.030035794 0.019046098, 0.049397767 0.034313872 0.023328215, -0.0383742 0.043054983 0.019046992, -0.037616581 0.043487355 0.017383769, 0.04986158 0.028985471 0.019046068, 0.05139181 0.025788933 0.017382443, -0.038718164 0.04344064 0.020637393, 0.049677029 0.030304715 0.020636529, -0.039274469 0.044064641 0.02208589, 0.050308347 0.02924481 0.020636648, -0.040018976 0.044900119 0.023328841, 0.050390989 0.030740291 0.02208519, -0.040919319 0.04591009 0.02431187, -0.034785151 0.046003103 0.019047007, -0.033897072 0.046445116 0.017383918, 0.051031262 0.029665157 0.022084951, 0.051346347 0.031322926 0.023327976, -0.035096884 0.046415254 0.020637631, 0.05316864 0.030907363 0.024311125, 0.051548302 0.025867298 0.019046009, -0.035601258 0.047082186 0.022085965, 0.051998794 0.030227527 0.023328006, -0.036276072 0.04797481 0.02332899, 0.052010208 0.026098952 0.02063641, -0.037092149 0.049053997 0.024312079, -0.030970439 0.048652977 0.01904723, -0.029945776 0.04908587 0.017383799, 0.052757502 0.026473805 0.022084951, -0.031248152 0.049088761 0.020637825, 0.053757742 0.026975706 0.023327827, 0.05548352 0.026528805 0.024310708, 0.053508475 0.021521941 0.019045711, 0.053346083 0.021456972 0.017382443, -0.031697124 0.049794286 0.022086203, -0.032298133 0.05073835 0.023329109, -0.033024669 0.051879466 0.024312288, 0.053987816 0.021714777 0.020636231, -0.026955009 0.050987408 0.019047365, -0.025789917 0.051391065 0.017383948, 0.054763794 0.022026747 0.022084802, 0.055801913 0.022444427 0.023327589, -0.025868341 0.051547319 0.019047365, -0.027196676 0.051444024 0.020637825, 0.05743821 0.021978304 0.02431047, 0.0551029 0.017029867 0.019045353, 0.054935828 0.016978323 0.017382085, -0.026100159 0.052009031 0.02063787, 0.05559665 0.017182365 0.020635992, -0.027587399 0.052183375 0.022086278, 0.056395575 0.017429143 0.022084385, -0.026475161 0.052756295 0.022086233, -0.028110519 0.053172648 0.023329332, -0.028742924 0.054368734 0.024312466, 0.057464898 0.017759711 0.023327291, 0.05902046 0.017285213 0.02431044, -0.022764996 0.052991033 0.019047454, -0.021457851 0.053345203 0.017384142, 0.05632104 0.012421474 0.019045264, 0.056150407 0.012383714 0.017381877, -0.026977092 0.053756431 0.023329213, -0.024274886 0.056505263 0.024312571, 0.056825727 0.012532607 0.020635515, -0.021523088 0.053507283 0.019047514, 0.057642475 0.012712568 0.022083938, -0.022968799 0.053465754 0.020638153, -0.021715999 0.053986728 0.020638019, 0.058735222 0.012953475 0.023326933, 0.060220078 0.012479916 0.024310052, 0.057154506 0.0077281296 0.019044906, 0.05698131 0.0077047497 0.017381459, -0.023298845 0.054233998 0.022086382, -0.022028118 0.054762393 0.022086546, 0.057666764 0.0077971667 0.020635307, -0.023740605 0.055262268 0.023329467, -0.018426985 0.054650947 0.019047752, -0.016979188 0.054934934 0.017384425, 0.058495462 0.0079091191 0.022083879, 0.059604377 0.0080589801 0.023326844, 0.061029181 0.0075937063 0.024309903, -0.022445828 0.055800706 0.023329392, -0.019649267 0.058275312 0.024312824, -0.017030895 0.055101976 0.019047663, 0.057597607 0.0029819161 0.019044772, 0.057422921 0.0029726624 0.017381236, -0.018592045 0.05514051 0.020638078, 0.058113605 0.0030083656 0.020635277, -0.017183527 0.055595532 0.020638064, 0.05894886 0.0030514598 0.02208361, -0.018859267 0.055932999 0.022086605, 0.060066372 0.0031094253 0.023326457, 0.061442479 0.002658233 0.024309605, -0.017430574 0.056394517 0.022086546, -0.01921685 0.056993142 0.023329496, 0.057647154 -0.0017848015 0.019044384, 0.057472438 -0.0017792583 0.017380893, -0.01396957 0.055956483 0.019047648, -0.012384772 0.056149602 0.017384082, 0.058163702 -0.0018008947 0.020634875, -0.017760932 0.057463631 0.023329407, 0.058999628 -0.001826793 0.022083238, -0.014895946 0.0596672 0.024312794, -0.014094681 0.056457773 0.020638302, 0.060118169 -0.0018614978 0.023326203, 0.061457291 -0.0022943914 0.024309114, -0.012422502 0.056320176 0.019047648, 0.057303026 -0.0065392405 0.019044191, -0.014297217 0.057269141 0.022086665, 0.057129413 -0.0065193623 0.017380834, -0.012533635 0.056824639 0.020638138, 0.057816401 -0.0065979064 0.020634741, -0.014568508 0.05835478 0.023329541, 0.058647424 -0.0066927969 0.022082984, -0.01271376 0.057641193 0.02208671, 0.059759244 -0.0068196356 0.02332589, -0.0094215274 0.056899026 0.019047707, -0.0077055395 0.056980491 0.01738447, 0.061073363 -0.0072321743 0.024309009, 0.056567222 -0.011248842 0.019043744, 0.056395903 -0.011214659 0.017380491, 0.055277228 -0.015833527 0.017380312, -0.012954801 0.058734089 0.023329705, -0.010046512 0.060672417 0.02431272, 0.055445343 -0.015881732 0.019043595, -0.0095059872 0.057408929 0.020638198, 0.057074204 -0.011349887 0.020634338, 0.055942118 -0.016024306 0.020634159, 0.057894409 -0.011512965 0.022082791, -0.0077289939 0.057153672 0.019047678, -0.0096425414 0.058233783 0.022086695, 0.056746051 -0.016254365 0.022082403, 0.058992133 -0.011731327 0.023325577, -0.0077983141 0.057665735 0.020638198, -0.0098254085 0.059337869 0.023329601, -0.0048124492 0.057472676 0.019047797, -0.0029738247 0.057422206 0.01738441, -0.007910341 0.0584943 0.022086531, -0.004855603 0.057987496 0.020638198, -0.0080601573 0.05960311 0.023329705, -0.0051316619 0.061284125 0.024312854, -0.0029828846 0.057596803 0.019047737, -0.0049253106 0.058820873 0.022086591, -0.0030096173 0.058112517 0.020638257, -0.0050188303 0.059936166 0.023329675, -0.00017222762 0.057673767 0.019047737, 0.0017782748 0.057471529 0.01738441, -0.0030528903 0.058947653 0.02208668, -0.00017368793 0.058190241 0.020638257, -0.0031107664 0.06006518 0.023329705, -0.073293477 -0.0014858842 0.032891124, -0.072364345 0.0039499998 0.031443059, -0.073199347 0.0039954334 0.032891423, -0.072457448 -0.0014688522 0.031442657, 0.012249902 -0.07143113 0.031438798, 0.0088826418 -0.071927354 0.031438753, 0.012391135 -0.072255433 0.032887161, 0.0089851618 -0.072757497 0.032886952, 0.0069570988 -0.07297951 0.032887191, 0.0090485215 -0.0732705 0.034477517, 0.0070059299 -0.073493898 0.034477487, -0.073868006 0.0044186562 0.036145374, -0.073208585 0.0095212162 0.034482285, -0.073348314 0.0097989887 0.036145598, -0.073715389 0.0040236264 0.034481987, -0.07133846 -0.0014461875 0.030199721, -0.071246833 0.0038889796 0.030200228, 0.0036762059 -0.073735461 0.034477472, 0.003685087 -0.073910221 0.036140904, -0.069895878 0.0038154274 0.029217169, -0.069985792 -0.0014187992 0.029216781, 0.011832014 -0.068994582 0.029212967, 0.0087455362 -0.070816815 0.030195877, 0.012060747 -0.070328042 0.030196056, -0.072695971 0.0094545037 0.032891542, 0.0066432208 -0.069685861 0.029213011, -0.071866736 0.0093468577 0.031443208, 0.0068776309 -0.072146684 0.031438664, 0.0036504716 -0.073219329 0.032887101, -0.072292164 0.0149654 0.034482688, 0.0014944226 -0.073811933 0.034477621, -0.072437108 0.015126795 0.036146015, -0.070971489 0.020325974 0.034482911, -0.0017198473 -0.073981985 0.036140874, -0.069415271 0.009027943 0.029217288, -0.070757017 0.0092024356 0.030200332, 0.0067714006 -0.071032658 0.030195907, -0.071785927 0.01486069 0.032891959, -0.070474535 0.020183653 0.032892391, 0.003608793 -0.072384 0.031438589, 0.0014839172 -0.073295325 0.032886863, -0.070967123 0.014691293 0.031443492, -0.069670796 0.019953489 0.031444058, -0.0017157942 -0.073807195 0.034477592, -0.069871351 0.014464363 0.030200556, -0.068594933 0.019645482 0.030200869, -0.068546459 0.014190167 0.029217765, 0.0014170408 -0.069987372 0.029213041, 0.0035530329 -0.071266264 0.030196011, 0.001467064 -0.072458923 0.031438664, -0.0017039478 -0.073290348 0.032887116, -0.0040255338 -0.073717281 0.034477577, -0.0071155727 -0.073659003 0.036140695, 0.0014443845 -0.071340203 0.030195966, -0.0016843677 -0.072454154 0.031438693, -0.0039974153 -0.07320106 0.032887191, -0.0070988089 -0.073485047 0.034477606, -0.0038169473 -0.069897726 0.029212981, -0.00165838 -0.071335375 0.030195832, -0.0039518923 -0.072366074 0.0314385, -0.0070490837 -0.072970659 0.032887205, -0.0095231384 -0.073210374 0.034477592, -0.012473062 -0.0729433 0.036141008, -0.0038908124 -0.071248561 0.030195862, -0.0069687217 -0.072137952 0.031438723, -0.0094565153 -0.072697759 0.032886997, -0.012443796 -0.072770745 0.034477726, -0.0068609416 -0.07102415 0.030195773, -0.009029761 -0.069416851 0.029213026, -0.0093484968 -0.071868435 0.031438574, -0.012356713 -0.072261348 0.032887176, -0.014967307 -0.072294012 0.034477651, -0.017764211 -0.071838081 0.036141187, -0.00920403 -0.070758522 0.0301961, -0.012215585 -0.071437001 0.031438783, -0.014862493 -0.071787879 0.032887146, -0.017722279 -0.071668297 0.034477741, -0.012026951 -0.070333585 0.030195922, -0.014191806 -0.068547964 0.02921313, -0.014693022 -0.070968762 0.031438813, -0.017598063 -0.071166635 0.032887086, -0.020327836 -0.070973232 0.0344778, -0.022960573 -0.070349857 0.036141187, -0.014466122 -0.069872871 0.030196041, -0.017397419 -0.070354745 0.031438947, -0.020185515 -0.070476532 0.032886952, -0.022906214 -0.070183486 0.034477755, -0.019274667 -0.067295626 0.029213056, -0.01712878 -0.069268271 0.030196026, -0.019955188 -0.069672391 0.031438902, -0.022745967 -0.06969218 0.032887146, -0.025574625 -0.069255769 0.034477904, -0.028034225 -0.068486303 0.036141247, -0.019647226 -0.068596393 0.030196205, -0.022486508 -0.068897069 0.031438977, -0.025395781 -0.068770945 0.032887384, -0.027968153 -0.068324283 0.034477919, -0.024249554 -0.065667331 0.029213205, -0.022139326 -0.06783326 0.030196086, -0.025105953 -0.06798622 0.031438977, -0.027772412 -0.067845985 0.032887384, -0.030678451 -0.06715104 0.034477741, -0.032958657 -0.066257074 0.036141217, -0.024718344 -0.066936389 0.03019616, -0.027455479 -0.067071944 0.031438991, -0.030463755 -0.066680968 0.032887518, -0.032880828 -0.066100448 0.034478113, -0.027031705 -0.06603618 0.030196026, -0.029089049 -0.063671365 0.029213294, -0.030116364 -0.06592007 0.031438917, -0.03265059 -0.065637782 0.032887548, -0.035610899 -0.064670548 0.034478232, -0.03770709 -0.063674435 0.0361415, -0.029651254 -0.064902082 0.030196115, -0.032278106 -0.064888924 0.031439185, -0.035361364 -0.064217865 0.032887623, -0.037617937 -0.063524082 0.034478143, -0.031779796 -0.063886836 0.030196384, -0.033765659 -0.061319679 0.029213414, -0.034958124 -0.063485071 0.031439185, -0.037354589 -0.063079134 0.032887533, -0.071139485 0.020373985 0.036146179, -0.04034391 -0.061828658 0.034478188, -0.04225421 -0.060752168 0.036141694, -0.034418419 -0.062504768 0.030196413, -0.036928445 -0.062359646 0.031439275, -0.067294091 0.019272983 0.029217854, -0.040061533 -0.061395675 0.032887757, 0.07097137 -0.020329773 0.034480631, 0.069298282 -0.025456086 0.034480229, 0.07113938 -0.020377934 0.036143824, 0.069462255 -0.025516272 0.036143526, -0.042154387 -0.060608625 0.034478307, 0.070474431 -0.020187393 0.032889917, 0.068813086 -0.025277898 0.032889694, -0.038253576 -0.058624744 0.029213578, -0.036358222 -0.061396748 0.030196503, 0.068028092 -0.024989218 0.031441495, -0.039604515 -0.060695082 0.031439334, 0.069670737 -0.019957021 0.03144154, -0.041859344 -0.06018436 0.032887965, 0.067255169 -0.030446589 0.034480155, 0.067414567 -0.0305188 0.036143497, 0.06697759 -0.024603426 0.030198604, 0.065665469 -0.024251089 0.0292155, 0.067293942 -0.019276023 0.029215932, -0.044851437 -0.058640853 0.034478396, 0.068594813 -0.01964882 0.030198723, -0.046575934 -0.057505801 0.036141723, -0.038992986 -0.059758008 0.030196443, 0.066784546 -0.030233398 0.03288956, -0.041381672 -0.059497669 0.031439453, 0.06602256 -0.029888496 0.031440929, -0.044537514 -0.058230191 0.032887846, 0.064853624 -0.035274774 0.034479797, 0.065007165 -0.03535834 0.036143035, -0.046465874 -0.057369888 0.03447862, 0.065003127 -0.029426947 0.030198291, -0.04074277 -0.058578938 0.030196488, 0.063669682 -0.029090598 0.029215097, -0.042527542 -0.055602297 0.029213712, 0.064399704 -0.035027832 0.032889113, -0.044029474 -0.057565853 0.031439662, -0.046140596 -0.056968182 0.032887787, 0.063664988 -0.034627989 0.031440854, -0.049108163 -0.055124924 0.03447862, -0.050649151 -0.053952649 0.036141962, 0.0621057 -0.039914548 0.034479499, 0.062252894 -0.040009275 0.036142945, -0.043349594 -0.056676894 0.030196577, 0.062681928 -0.034093305 0.030197859, 0.061317757 -0.033767253 0.029214978, -0.045614421 -0.056318268 0.031439602, 0.061671034 -0.039635181 0.03288886, -0.048764318 -0.054739013 0.032887846, 0.060967624 -0.039182946 0.031440526, -0.050529614 -0.053825095 0.034478873, -0.044909924 -0.055448711 0.030196816, -0.04656373 -0.052268654 0.029214099, 0.059026659 -0.04434146 0.034479141, 0.059166491 -0.044446483 0.036142647, 0.060026005 -0.038577855 0.030197769, 0.05862309 -0.0382552 0.029214591, -0.048208073 -0.05411455 0.031439736, -0.05017592 -0.053448141 0.032887995, 0.05861342 -0.044031233 0.032888636, -0.053090096 -0.051301166 0.034478873, -0.05445227 -0.050111443 0.036142349, 0.057944953 -0.043528825 0.031440392, -0.0474637 -0.053278953 0.03019698, 0.05563277 -0.048532039 0.034479126, -0.049603522 -0.05283837 0.031439826, 0.055764258 -0.048646972 0.03614223, 0.057050064 -0.042856544 0.030197382, -0.054323554 -0.049993098 0.034478977, 0.055600569 -0.042529225 0.029214457, -0.052718416 -0.050941885 0.032888278, 0.055243209 -0.048192278 0.032888532, -0.048837453 -0.052022353 0.030197039, 0.054612935 -0.047642395 0.031440198, -0.050339326 -0.04864265 0.029214159, -0.053943291 -0.049642965 0.032888368, 0.051941782 -0.052463397 0.034478933, 0.052064762 -0.052587718 0.036141962, -0.052117005 -0.050360858 0.031439707, 0.053769693 -0.04690665 0.030197293, -0.056775242 -0.047190204 0.034478948, 0.052266851 -0.046565071 0.029214218, 0.051578134 -0.052096158 0.032888278, -0.057964832 -0.046002984 0.036142379, -0.053328127 -0.049076378 0.031440124, 0.050989836 -0.051501736 0.031439751, -0.051312372 -0.049582958 0.030197024, 0.047973767 -0.056114927 0.034478709, -0.057827815 -0.04589434 0.034479246, 0.048087314 -0.056247935 0.036141872, -0.056377709 -0.046859786 0.032888561, 0.050202355 -0.050706431 0.030197009, 0.048641115 -0.050340921 0.029214025, -0.0538335 -0.044744998 0.029214457, -0.052504629 -0.048318833 0.03019695, 0.047637865 -0.055722266 0.032887951, -0.057422996 -0.045573026 0.03288877, 0.047094405 -0.0550863 0.031439766, -0.055734679 -0.046325073 0.031440273, 0.043749779 -0.059467152 0.034478769, -0.056767896 -0.045052961 0.031440228, 0.043853328 -0.059607983 0.036141738, -0.06014286 -0.042815343 0.03447926, 0.046367288 -0.054235816 0.03019689, 0.04474324 -0.053835168 0.029213667, -0.061167806 -0.041649237 0.036142752, 0.043443605 -0.059050858 0.032887742, -0.054874077 -0.045609862 0.030197412, -0.061023429 -0.041550666 0.034479529, 0.042947859 -0.058377042 0.031439528, -0.05702655 -0.040596768 0.029214606, -0.055891529 -0.044357404 0.030197382, -0.059721977 -0.04251574 0.032888874, 0.039292365 -0.062502056 0.034478143, 0.039385527 -0.062650278 0.036141559, 0.040595099 -0.057028338 0.029213548, 0.042284817 -0.057475716 0.030196577, -0.060596213 -0.04125993 0.032888889, -0.059040725 -0.042030424 0.031440467, 0.039017379 -0.062064514 0.032887608, 0.038572282 -0.061356291 0.0314392, -0.059905097 -0.040789112 0.031440586, -0.063174143 -0.038201272 0.034479558, -0.064044967 -0.03707324 0.036142975, 0.034625307 -0.065203443 0.034478188, 0.034707308 -0.065357849 0.036141202, -0.058128834 -0.041381568 0.030197665, 0.036219999 -0.05990243 0.029213622, 0.037976608 -0.060408905 0.030196518, 0.033371344 -0.065853983 0.034477964, -0.063893571 -0.036985487 0.034479707, -0.059900835 -0.036221683 0.029214889, -0.058980122 -0.040159196 0.030197591, 0.029843986 -0.067717105 0.036141306, 0.034382895 -0.064747006 0.032887444, -0.062731951 -0.037933767 0.032889068, 0.033137724 -0.065392971 0.032887578, -0.063446313 -0.036726519 0.032889247, 0.033990711 -0.064008355 0.0314392, -0.062016323 -0.037500873 0.031440556, -0.062722608 -0.036307529 0.031440854, 0.032759741 -0.06464687 0.031439096, 0.029773429 -0.067557201 0.034477934, -0.065852165 -0.033373505 0.034480006, -0.066579923 -0.032299101 0.036143258, 0.033465952 -0.063019946 0.03019619, -0.061058611 -0.036921889 0.030197769, 0.031642303 -0.062441677 0.029213443, 0.028357014 -0.068163916 0.034477934, -0.061754063 -0.035746738 0.030197948, 0.024821579 -0.0697148 0.036141276, -0.062440202 -0.031643972 0.029214919, 0.032253951 -0.063648701 0.030196279, -0.065391272 -0.033139691 0.032889321, 0.029565215 -0.067084074 0.03288728, 0.028158441 -0.067686424 0.032887444, -0.064645335 -0.032761529 0.031440943, -0.068161711 -0.028358981 0.034479946, 0.029227942 -0.066318646 0.031438917, -0.068759859 -0.027353093 0.036143377, -0.063646972 -0.03225553 0.030197993, 0.02783747 -0.06691435 0.031439021, -0.067684725 -0.028160483 0.03288947, 0.024763107 -0.069550216 0.03447777, 0.028776467 -0.065294564 0.030196384, 0.026887745 -0.06463182 0.029213294, -0.06691274 -0.02783905 0.031441137, 0.023183957 -0.070092216 0.034477636, -0.070090532 -0.023185775 0.034480467, 0.019666508 -0.071340635 0.036140978, 0.027407527 -0.065881133 0.03019616, -0.070572883 -0.022260934 0.036144018, 0.024589553 -0.069063172 0.032887265, -0.064630121 -0.026889339 0.029215425, -0.06587933 -0.02740927 0.030198395, -0.069599718 -0.023023471 0.032889798, 0.023021623 -0.06960164 0.032887071, 0.024309024 -0.068275318 0.031439006, -0.068805978 -0.022760764 0.03144148, 0.019620165 -0.071172372 0.034477726, -0.071626931 -0.017883256 0.034480736, 0.022759214 -0.068807423 0.031438977, -0.072009504 -0.017049968 0.036144122, -0.066458762 -0.021984354 0.029215679, -0.067743227 -0.022409409 0.030198529, 0.021982744 -0.066460386 0.029213116, 0.023933709 -0.067221001 0.030196205, -0.071125522 -0.017757967 0.032890096, 0.017881364 -0.071628988 0.034477785, 0.014406726 -0.072586015 0.036141112, 0.019482851 -0.070673943 0.032887042, -0.070314392 -0.017555207 0.031441689, 0.022407591 -0.067745015 0.030195892, -0.072763041 -0.012480408 0.034481063, -0.073061779 -0.011748329 0.036144465, 0.017756045 -0.071127549 0.032887101, -0.067915782 -0.016956493 0.029216141, -0.069228485 -0.017284229 0.030198991, 0.0192606 -0.069867641 0.031438664, -0.07225354 -0.012393117 0.032890528, 0.014372766 -0.072414592 0.034477636, -0.071429372 -0.01225169 0.031442076, 0.017553538 -0.070315823 0.031438693, 0.016954795 -0.067917377 0.029213071, 0.018963084 -0.068788618 0.030196026, -0.07349205 -0.0070081055 0.034481332, -0.073724359 -0.0063836873 0.036144719, -0.068992868 -0.011833608 0.029216185, -0.070326433 -0.01206249 0.030199379, 0.014272079 -0.071907565 0.032887176, -0.072977394 -0.006959036 0.032890692, 0.01247853 -0.072764739 0.034477785, 0.0090700686 -0.073444098 0.036140978, -0.072145239 -0.0068793148 0.03144218, 0.017282337 -0.06922999 0.030196115, 0.014109224 -0.071087152 0.031438902, -0.073810101 -0.0014964193 0.034481719, -0.073993683 -0.00098513067 0.036145121, -0.069684163 -0.0066447258 0.029216528, -0.071031153 -0.0067731291 0.030199438, 0.013891429 -0.069989517 0.030195832, -0.065709367 -0.0023157299 0.026763082, -0.063424155 -0.0050548613 0.025535911, -0.061442524 -0.0026611388 0.024309263, -0.061029464 -0.0075964481 0.024308935, -0.065107599 -0.009171471 0.02676253, -0.06475465 0.011396542 0.026763633, -0.061778054 -0.022507831 0.02676183, -0.058357388 -0.025350168 0.025534719, -0.057438239 -0.021980986 0.02430816, -0.055483595 -0.026531696 0.024307877, -0.059087113 -0.028842017 0.026761353, -0.060293585 0.012120336 0.024310037, -0.061073482 0.0072292686 0.024309784, -0.059599653 -0.032480776 0.02798824, -0.065591305 0.0045654774 0.026763514, -0.055748865 -0.034860268 0.026761085, -0.030850455 -0.05806458 0.026759714, -0.034504592 -0.0584521 0.02798672, -0.061457366 0.0022916496 0.024309576, -0.036750764 -0.054521769 0.026759878, -0.027335584 -0.057454988 0.025532961, -0.028417885 -0.05454196 0.024306372, -0.023937047 -0.05665189 0.024306238, -0.024612263 -0.060971245 0.02675958, -0.011398196 -0.064755991 0.026759252, -0.0072262734 -0.063214675 0.025532514, -0.0096842051 -0.060734123 0.024306014, -0.004567042 -0.065592811 0.026759416, -0.0047658086 -0.061316445 0.024305895, -0.00065676868 -0.067873284 0.027986273, 0.0023141354 -0.065710679 0.026759371, -0.060220346 -0.012482628 0.024308652, -0.063792139 -0.015926853 0.026762277, 0.033367231 -0.0591086 0.027986526, 0.028840587 -0.059088394 0.026759744, 0.034859002 -0.05575034 0.026759952, 0.037092075 -0.049056664 0.024306685, 0.036088362 -0.052401513 0.025533244, 0.040495172 -0.05180113 0.026760191, -0.059020713 -0.017287835 0.024308592, 0.033024505 -0.051882327 0.024306521, 0.050380036 -0.042249724 0.026760831, 0.051131278 -0.037866041 0.025534064, 0.047754124 -0.038754553 0.02430737, 0.050717577 -0.034786165 0.024307519, 0.05452013 -0.03675212 0.026761025, 0.058450297 -0.034506038 0.027987882, 0.058062896 -0.030851886 0.026761323, -0.053168669 -0.030910224 0.024307653, 0.057568282 -0.021637887 0.024308175, 0.060164869 -0.020697802 0.025535047, 0.060969546 -0.024613649 0.026761651, 0.064183667 -0.022080198 0.027988777, -0.050509185 -0.035088256 0.024307385, -0.051799759 -0.040496722 0.026760846, -0.047521994 -0.039038718 0.024307087, -0.047283024 -0.045689285 0.02676034, -0.044226646 -0.042736113 0.024307027, -0.040644616 -0.046156287 0.024306893, -0.042248309 -0.050381422 0.026760131, -0.036798894 -0.049277097 0.024306729, -0.032714427 -0.052078441 0.024306342, -0.019301012 -0.058394268 0.024306074, -0.018104345 -0.063209683 0.026759475, -0.014539674 -0.059758008 0.024306044, 0.000183478 -0.061501145 0.024305761, 0.0051315427 -0.061286986 0.024305865, 0.0091699064 -0.065108791 0.026759401, 0.010046318 -0.060675323 0.024306089, 0.015925467 -0.063793629 0.02675958, 0.014896005 -0.059669986 0.024305895, 0.01964888 -0.058278084 0.024306029, 0.022506133 -0.061779499 0.026759282, 0.024274543 -0.05650799 0.024306267, 0.028742716 -0.054371431 0.024306327, 0.040919185 -0.045912936 0.024306774, 0.045688048 -0.047284439 0.026760384, 0.044480875 -0.042471379 0.024306878, 0.053352013 -0.030592442 0.024307638, 0.055640519 -0.026200131 0.024307966, -0.061998621 0.014292568 0.025536925, -0.066139907 0.015247449 0.02799058, -0.067854464 0.0016704351 0.027989939, -0.034313604 -0.077769831 0.062995493, -0.039540619 -0.075246841 0.062995881, 0.07776621 -0.034316942 0.062997818, 0.07524325 -0.039544046 0.062997758, -0.028926805 -0.079930142 0.062995389, 0.079926416 -0.028930128 0.062998474, -0.081714302 0.023401201 0.063001215, 0.081714407 -0.023408502 0.062998831, -0.023404941 -0.081717893 0.062995464, -0.083121091 0.017770439 0.063000962, -0.017773896 -0.083124489 0.062995568, -0.084140137 0.012056381 0.063000768, -0.012060106 -0.084143668 0.062995344, -0.084767088 0.0062865615 0.063000366, -0.0062901229 -0.084770545 0.062995359, -0.084998637 0.00048710406 0.062999994, -0.00049060583 -0.085002169 0.062995136, -0.084834069 -0.0053144544 0.06299977, 0.0053110123 -0.084837586 0.06299521, -0.084273845 -0.011091426 0.062999353, 0.011087775 -0.084277302 0.062995329, -0.083320677 -0.016816765 0.062998891, 0.016813055 -0.083324194 0.06299524, -0.081979051 -0.022463381 0.062998891, 0.022459835 -0.081982628 0.062995121, -0.080255374 -0.028005525 0.062998444, 0.028002113 -0.080258742 0.062995493, -0.078157097 -0.033417195 0.062998116, 0.03341347 -0.078160658 0.062995598, -0.075694799 -0.03867285 0.062997699, 0.038669139 -0.07569842 0.062995538, -0.072879419 -0.043748274 0.062997878, 0.043744668 -0.07288295 0.062995836, -0.0697245 -0.048619583 0.062997252, 0.048616081 -0.069727793 0.062996179, -0.066244051 -0.053264603 0.062997103, 0.053260982 -0.066247523 0.062996089, -0.062455073 -0.057660997 0.062996745, 0.057657376 -0.062458456 0.062996373, -0.058374748 -0.061788723 0.062996536, 0.061784998 -0.058377981 0.062996656, -0.054022178 -0.065628275 0.062996238, 0.065624699 -0.054025814 0.062996969, -0.049417943 -0.069161907 0.062996134, 0.069158316 -0.049421385 0.062997267, -0.044583187 -0.072373137 0.062995911, 0.072369561 -0.044586793 0.062997594, -0.083320737 -0.016809538 -0.063001007, 0.0053109676 -0.084830269 -0.06300509, -0.00049063563 -0.084995121 -0.063004792, -0.084273756 -0.011084437 -0.063000664, -0.0062900931 -0.084763393 -0.063004971, -0.08483398 -0.0053073615 -0.063000649, -0.012060106 -0.08413659 -0.063004971, 0.081714183 -0.023401275 -0.063001499, 0.07992664 -0.028923184 -0.063001752, -0.084998667 0.00049412251 -0.062999845, 0.077766195 -0.034309909 -0.063002154, -0.017773837 -0.083117455 -0.063004851, -0.084767133 0.0062934905 -0.062999934, -0.023404956 -0.081710741 -0.063004687, 0.075243369 -0.039536998 -0.063002214, -0.084140122 0.012063563 -0.062999368, -0.028926626 -0.079923078 -0.063004658, 0.072369576 -0.044579566 -0.06300272, -0.083121002 0.017777294 -0.062999129, -0.03431353 -0.077762753 -0.06300436, -0.081714138 0.023408204 -0.062998936, 0.06915845 -0.049414307 -0.063003004, -0.039540559 -0.075239837 -0.063004613, 0.065624729 -0.054018632 -0.063003153, -0.044583097 -0.072365984 -0.06300427, 0.061785176 -0.058370993 -0.063003421, -0.049417987 -0.069154635 -0.063004062, 0.057657421 -0.062451333 -0.06300357, -0.054022282 -0.065621093 -0.063003778, 0.053261042 -0.066240519 -0.063003793, -0.058374718 -0.061781496 -0.063003629, 0.048616081 -0.069720611 -0.063004106, -0.062455073 -0.057654008 -0.063003376, 0.043744743 -0.072875917 -0.063004136, -0.066244051 -0.05325745 -0.063003346, 0.038669258 -0.075691253 -0.063004524, -0.069724277 -0.04861252 -0.063003033, 0.033413529 -0.078153655 -0.063004464, -0.072879374 -0.043741196 -0.063002706, 0.028002068 -0.080251724 -0.063004673, -0.075694904 -0.038665578 -0.063002467, 0.022459865 -0.081975415 -0.063004792, -0.078157187 -0.033409983 -0.063002035, 0.016813055 -0.083317161 -0.063004851, -0.080255166 -0.027998507 -0.063001662, 0.011087909 -0.084270224 -0.063004822, -0.081979096 -0.022456378 -0.063001335, 0.016245201 0.042191297 -0.0014976859, 0.015869945 0.041303113 -0.0014978349, 0.016245276 0.042191193 0.0015021861, 0.015869886 0.041302949 0.001502037, 0.015292898 0.040530428 -0.0014978945, 0.015292972 0.040530175 0.0015022457, 0.014547899 0.039918244 -0.0014978647, 0.014547899 0.03991808 0.0015021563, 0.013677925 0.039502382 -0.0014980137, 0.01367788 0.039502159 0.0015021861, 0.012733817 0.039306626 -0.0014979839, 0.012733638 0.039306551 0.001502037, 0.011769965 0.039342582 -0.0014981031, 0.01177004 0.039342508 0.0015020967, 0.010843039 0.039608076 -0.0014979839, 0.010843173 0.039607882 0.0015021563, 0.010006428 0.040087804 -0.0014979243, 0.010006502 0.040087551 0.0015021265, 0.0093091279 0.040753707 -0.0014978647, 0.0093090832 0.040753409 0.0015020967, 0.0087911636 0.041567191 -0.0014977455, 0.0087912381 0.041566953 0.0015020669, 0.0084831715 0.042480946 -0.0014977455, 0.0084832907 0.042480633 0.0015023053, 0.008402735 0.043441892 -0.0014976561, 0.0084024966 0.043441638 0.0015022755, 0.0085544735 0.04439421 -0.0014977455, 0.0085544884 0.044393927 0.0015023351, 0.035137683 -0.033486098 -0.0015019476, 0.034762457 -0.034374386 -0.001502037, 0.035137713 -0.033486441 0.001497969, 0.034762397 -0.034374669 0.00149782, 0.034185395 -0.035147116 -0.0015020818, 0.034185395 -0.03514719 0.001497969, 0.033440292 -0.035759181 -0.0015021116, 0.033440232 -0.0357593 0.0014979541, 0.032570332 -0.036175177 -0.0015020221, 0.032570273 -0.036175281 0.0014978349, 0.03162618 -0.036370799 -0.0015022904, 0.03162612 -0.036370978 0.0014977157, 0.03066276 -0.036334917 -0.0015022755, 0.030662626 -0.036335021 0.0014977604, 0.029735461 -0.036069289 -0.0015023351, 0.029735431 -0.036069527 0.00149782, 0.028898999 -0.03558968 -0.0015020967, 0.028898999 -0.035589889 0.0014979094, 0.028201416 -0.034923658 -0.0015021563, 0.028201431 -0.034924075 0.0014978498, 0.02768375 -0.034110367 -0.0015019923, 0.027683616 -0.034110561 0.0014978647, 0.027375564 -0.033196568 -0.0015019774, 0.027375758 -0.033196688 0.0014979839, 0.027295128 -0.032235593 -0.0015020221, 0.027295351 -0.032235697 0.0014979839, 0.027446911 -0.031283364 -0.001501888, 0.027447 -0.031283498 0.0014981329, -0.039846942 -0.012009129 0.0014992058, -0.039846942 -0.012008816 -0.0015007257, -0.04022254 -0.012897238 0.0014991462, -0.040222406 -0.012897015 -0.001500845, -0.040799424 -0.013669997 0.0014991909, -0.040799424 -0.013669595 -0.0015009195, -0.041544616 -0.014281899 0.0014990568, -0.041544661 -0.014281705 -0.0015009791, -0.042414472 -0.014697939 0.001498878, -0.042414561 -0.014697701 -0.0015009195, -0.043358773 -0.014893755 0.0014991909, -0.043358773 -0.014893398 -0.0015011132, -0.044322267 -0.014857665 0.0014989078, -0.044322193 -0.014857471 -0.001500845, -0.045249403 -0.01459223 0.0014990866, -0.045249388 -0.014592066 -0.0015008003, -0.046085849 -0.014112547 0.0014990717, -0.046085909 -0.014112353 -0.0015009344, -0.046783283 -0.013446614 0.0014990717, -0.046783298 -0.013446495 -0.0015009195, -0.047301129 -0.012633219 0.0014990568, -0.047300965 -0.012633085 -0.0015009046, -0.047609374 -0.011719406 0.0014991909, -0.04760921 -0.011719331 -0.0015007406, -0.047689602 -0.010758609 0.0014992654, -0.047689632 -0.010758191 -0.0015007704, -0.047537878 -0.009806186 0.001499325, -0.047537893 -0.0098060668 -0.001500681, 0.011647493 -0.024358451 0.0014985204, 0.014498562 -0.022776961 0.0014985949, 0.011647508 -0.024358526 -0.0015014559, 0.014498621 -0.022776783 -0.0015014857, -0.025956377 0.0074346215 -0.0014996678, -0.025956362 0.007434532 0.0015002191, -0.026663199 0.0042517781 -0.0014999211, 0.017138302 -0.020863414 0.0014987588, 0.017138377 -0.020863235 -0.0015013963, -0.026663303 0.0042514205 0.0015001148, 0.019528076 -0.018645421 0.0014989972, 0.019528046 -0.018645287 -0.0015012473, -0.026981458 0.0010066181 0.0015000105, -0.026981339 0.0010068417 -0.0015002936, 0.021633223 -0.016155675 0.001498878, 0.021633223 -0.016155422 -0.0015010387, -0.026905954 -0.0022529513 0.0014998019, -0.026905835 -0.002252847 -0.0015002787, 0.023422822 -0.013430282 0.0014991015, 0.023422733 -0.013430029 -0.0015007854, -0.026438326 -0.0054796338 0.0014993995, -0.026438117 -0.0054794401 -0.0015004128, 0.024870858 -0.010508895 0.0014992952, 0.024871007 -0.010508895 -0.0015006661, -0.025584936 -0.0086265057 0.0014994591, -0.025584906 -0.0086262077 -0.0015004277, 0.025956228 -0.0074344277 0.0014995337, 0.025956139 -0.007434234 -0.0015006065, -0.024358585 -0.011647522 0.0014991313, -0.024358615 -0.011647239 -0.0015007854, -0.022777081 -0.014498636 0.0014990121, -0.02277717 -0.014498472 -0.0015010387, -0.020863324 -0.017138422 0.0014989525, -0.02086328 -0.017138138 -0.0015010834, -0.01864551 -0.019528225 0.0014987886, -0.018645614 -0.019527987 -0.0015012622, -0.016155645 -0.021633193 0.0014984906, -0.016155675 -0.021633074 -0.0015013069, -0.013430268 -0.023422927 0.0014985502, -0.013430163 -0.023422748 -0.0015013963, -0.010508984 -0.024871022 0.0014985502, -0.010508999 -0.024870738 -0.0015016198, -0.0074345022 -0.025956303 0.001498431, -0.0074345618 -0.025956243 -0.001501739, -0.0042515397 -0.026663199 0.0014982522, -0.0042516142 -0.026662931 -0.0015016496, -0.0010067075 -0.026981294 0.0014983416, -0.0010068864 -0.026980951 -0.0015016645, 0.002252847 -0.02690582 0.0014983118, 0.0022527874 -0.026905626 -0.00150159, 0.005479455 -0.026438102 0.0014983863, 0.0054795295 -0.026437908 -0.0015017092, 0.0086263567 -0.025584906 0.0014983416, 0.0086262375 -0.025584623 -0.0015014857, -0.015832707 -0.055276275 -0.01738444, -0.011213943 -0.05639492 -0.01738447, -0.0065184534 -0.057128355 -0.01738435, -0.0017786026 -0.057471499 -0.01738447, 0.0029735714 -0.057422251 -0.01738438, -0.055277303 0.015833616 -0.017380312, -0.056395963 0.011214837 -0.01738061, 0.0077053905 -0.056980297 -0.017384559, -0.057129458 0.0065193474 -0.017380819, 0.012384668 -0.056149468 -0.01738444, -0.057472587 0.0017793924 -0.017381191, 0.016979173 -0.054934919 -0.01738435, -0.057423249 -0.0029726923 -0.017381594, 0.021457687 -0.053345263 -0.017384335, -0.056981429 -0.0077044219 -0.017381668, 0.025789782 -0.051391199 -0.017384127, -0.056150481 -0.01238364 -0.017381862, 0.029945642 -0.049085885 -0.017383918, -0.054936051 -0.016978234 -0.017382085, -0.053346276 -0.021456882 -0.017382368, 0.033896968 -0.04644534 -0.017383873, -0.051392138 -0.025788829 -0.017382637, 0.037616462 -0.043487206 -0.017383695, -0.049086779 -0.029944554 -0.017382845, -0.046446294 -0.033895895 -0.017383069, 0.041079417 -0.040232643 -0.017383575, -0.043488503 -0.037615702 -0.017383292, 0.044261396 -0.036702842 -0.017383337, 0.047141343 -0.032922372 -0.01738289, -0.040233597 -0.041078344 -0.017383575, -0.03670384 -0.044260547 -0.017383665, 0.049699128 -0.028917 -0.017383009, -0.032923386 -0.047140464 -0.017383888, 0.0519173 -0.024714082 -0.017382652, -0.028917953 -0.049698204 -0.017384157, 0.053780973 -0.020342335 -0.017382443, 0.055277362 -0.015831679 -0.017381981, -0.024715021 -0.05191648 -0.017384112, -0.020343408 -0.053780168 -0.017384306, -0.017764166 -0.071834162 -0.036149129, -0.017764106 -0.07183373 -0.0445043, -0.02296041 -0.070345685 -0.036149174, -0.012473106 -0.072938591 -0.04450427, -0.022960603 -0.070345223 -0.044504225, -0.028034344 -0.068482026 -0.036149085, 0.071139291 -0.020373762 -0.036146343, 0.069462299 -0.025512338 -0.036146492, -0.028034449 -0.068481565 -0.044503942, -0.032958612 -0.066253126 -0.036148816, 0.069462433 -0.025511861 -0.044501618, 0.067414477 -0.030514628 -0.03614673, -0.032958522 -0.066252574 -0.044503883, -0.037706941 -0.063670397 -0.036148742, 0.067414507 -0.030514061 -0.04450193, 0.06500718 -0.035354331 -0.036147058, -0.037706926 -0.063669965 -0.044503734, -0.04225418 -0.0607481 -0.03614831, 0.065007254 -0.035353646 -0.044502258, 0.062252879 -0.040005058 -0.036147282, -0.042254254 -0.060747638 -0.044503495, -0.046575934 -0.057501748 -0.036148429, 0.062252805 -0.040004656 -0.044502333, 0.059166551 -0.044442609 -0.036147624, -0.046575949 -0.057501271 -0.044503331, -0.050649136 -0.053948551 -0.03614819, 0.05916658 -0.044442177 -0.044502631, 0.055764303 -0.048642799 -0.036147863, -0.050649121 -0.053947985 -0.044503316, -0.054452375 -0.050107494 -0.036148056, 0.055764392 -0.048642531 -0.044502869, 0.052064747 -0.052583486 -0.036148146, -0.054452211 -0.050106943 -0.044503152, -0.057964846 -0.045998916 -0.036147743, 0.052064687 -0.052583039 -0.044503167, 0.048087388 -0.056244001 -0.03614825, -0.057964787 -0.045998499 -0.044502601, -0.061167955 -0.041645035 -0.036147654, 0.048087373 -0.056243464 -0.044503435, 0.043853432 -0.059603974 -0.036148503, -0.061167926 -0.041644648 -0.044502288, -0.064044863 -0.037069157 -0.036147401, 0.043853328 -0.059603497 -0.044503391, 0.039385498 -0.062646151 -0.036148533, -0.064044803 -0.037068546 -0.044502184, -0.066579968 -0.032295316 -0.036146849, 0.039385363 -0.062645599 -0.044503599, 0.034707353 -0.065353766 -0.036148801, -0.066579983 -0.032294691 -0.044502035, -0.068759993 -0.02734901 -0.03614673, 0.034707308 -0.065353408 -0.044503897, 0.029843941 -0.067713141 -0.036148801, -0.068759784 -0.027348578 -0.044501558, -0.070573017 -0.022256881 -0.036146238, 0.029844016 -0.067712501 -0.044503912, 0.024821535 -0.069710702 -0.036149085, -0.070572957 -0.022256494 -0.044501498, -0.072009608 -0.01704596 -0.036146209, 0.024821654 -0.069710448 -0.044504032, 0.019666597 -0.071336627 -0.036149085, -0.072009549 -0.017045602 -0.044501066, -0.073061958 -0.011744052 -0.036145866, 0.019666567 -0.071336284 -0.044504091, 0.01440677 -0.072582006 -0.036149204, -0.073062032 -0.01174359 -0.044500887, -0.07372424 -0.0063796937 -0.036145523, 0.014406681 -0.072581485 -0.04450421, 0.0090700388 -0.073439971 -0.036149338, -0.073724344 -0.0063790381 -0.044500306, -0.073993698 -0.00098115206 -0.03614527, 0.009070009 -0.073439524 -0.0445043, 0.0036849231 -0.07390599 -0.036149442, -0.073993653 -0.00098060071 -0.044500142, -0.073867902 0.0044227242 -0.036144778, 0.0036849231 -0.073905677 -0.044504225, -0.0017198771 -0.073978066 -0.036149234, -0.073867887 0.0044230968 -0.044499844, -0.073348343 0.0098028183 -0.03614454, -0.0017199516 -0.0739775 -0.044504315, -0.073348239 0.0098034143 -0.044499665, -0.072437078 0.015130788 -0.036144108, -0.0071152598 -0.073655099 -0.036149263, -0.007115528 -0.073654592 -0.04450433, -0.072437286 0.015131518 -0.044499263, -0.071139425 0.020378083 -0.036143884, -0.012473136 -0.072939262 -0.036149248, -0.011214048 -0.056396812 0.017377988, -0.0065185726 -0.057130381 0.017378122, -0.0017784238 -0.057473511 0.017378032, -0.056395948 0.011213049 0.017381847, 0.0029736757 -0.057424083 0.017377838, -0.057129353 0.0065174103 0.017381519, 0.0077054501 -0.056982264 0.017377913, -0.057472631 0.001777336 0.017381191, 0.012384579 -0.05615145 0.017377973, -0.057423145 -0.002974689 0.017380938, 0.016979143 -0.054936901 0.017378137, -0.056981519 -0.0077064186 0.017380729, 0.021457717 -0.053347126 0.017378256, -0.056150451 -0.012385637 0.017380536, 0.025789857 -0.051393032 0.017378345, -0.054936036 -0.016980231 0.017380372, 0.029945582 -0.049087748 0.017378479, -0.053346306 -0.02145876 0.017380103, 0.033897102 -0.046447188 0.017378613, -0.051392093 -0.025790632 0.017379805, 0.037616596 -0.043489441 0.017378762, -0.049086943 -0.029946461 0.017379522, 0.041079357 -0.040234625 0.017378867, -0.046446294 -0.033897817 0.017379269, -0.043488443 -0.037617564 0.017379239, 0.044261679 -0.036704794 0.017378911, -0.040233538 -0.041080311 0.017378926, 0.047141299 -0.03292425 0.017379358, -0.036703989 -0.044262409 0.017378777, 0.049699083 -0.028918996 0.017379448, -0.03292343 -0.047142372 0.017378539, 0.051917329 -0.02471602 0.017379791, -0.028917983 -0.049700156 0.01737839, 0.053781033 -0.020344287 0.017379984, -0.024715081 -0.051918313 0.01737836, -0.020343348 -0.053782031 0.017378002, -0.015832782 -0.055278122 0.017378077, -0.022960544 -0.070350498 0.044495896, -0.028034404 -0.068486601 0.044496074, -0.017764196 -0.071838751 0.044495866, -0.012473211 -0.072943687 0.044495746, -0.072437093 0.015126348 0.044500902, -0.0071155131 -0.073659539 0.044495761, -0.073348343 0.009798497 0.04450047, -0.0017199665 -0.073982522 0.044495761, -0.073867872 0.00441809 0.044500276, 0.0036849231 -0.073910639 0.044495687, -0.073993519 -0.0009855479 0.044500008, 0.0090699941 -0.073444575 0.044495702, -0.0737243 -0.0063841343 0.044499427, 0.014406741 -0.072586566 0.044495717, -0.073061869 -0.011748731 0.044499323, 0.019666627 -0.071341291 0.044496, -0.072009489 -0.017050609 0.04449898, 0.024821505 -0.069715232 0.044496015, -0.070573166 -0.022261411 0.044498622, 0.029843926 -0.067717493 0.044496208, -0.068759993 -0.027353555 0.04449822, 0.034707308 -0.065358415 0.044496298, -0.066580117 -0.032299623 0.044498175, 0.039385498 -0.062650621 0.044496328, -0.064044908 -0.037073672 0.044497758, 0.043853298 -0.059608534 0.044496462, -0.061167866 -0.041649729 0.044497713, 0.048087284 -0.056248337 0.044496864, -0.057964712 -0.046003535 0.044497341, 0.052064717 -0.05258818 0.044496834, -0.054452151 -0.05011186 0.044496983, 0.055764377 -0.048647404 0.044497162, -0.050649107 -0.053953052 0.044496968, 0.059166446 -0.044447109 0.044497415, -0.046576053 -0.057506084 0.04449673, 0.062252924 -0.040009707 0.044497654, -0.042254254 -0.060752645 0.044496417, 0.065007165 -0.035358801 0.044497952, -0.03770709 -0.063674957 0.044496223, 0.067414582 -0.030519247 0.044498235, -0.032958716 -0.066257417 0.044496104, 0.069462165 -0.025516957 0.044498488, -0.055027187 0.026196718 -0.023955524, -0.054307446 0.025854304 -0.023324937, -0.055662975 0.026153073 -0.024307832, -0.05339095 0.030524641 -0.024307624, -0.054427907 0.020589367 -0.02063413, -0.052541971 0.025013492 -0.020633727, -0.052075416 0.024791285 -0.019043133, -0.055445418 0.015881985 -0.019043639, -0.055942193 0.016024321 -0.020634264, -0.053944603 0.020406485 -0.019043341, 0.024790078 0.052076504 -0.019041702, 0.026172757 0.051395386 -0.019041628, 0.024715021 0.051918447 -0.01737836, 0.026786685 0.052601144 -0.022080794, 0.029686198 0.05102095 -0.022080719, 0.029265687 0.050298139 -0.020632178, -0.055210173 0.020885274 -0.022082388, -0.053296968 0.025373101 -0.022082195, 0.026407152 0.051856086 -0.020632252, -0.05674617 0.016254768 -0.022082806, 0.025012314 0.052542984 -0.020632252, -0.056256965 0.021281272 -0.02332516, -0.057822108 0.016563013 -0.023325503, 0.027294606 0.053598613 -0.023323491, 0.030249178 0.051988319 -0.023323372, -0.057002291 0.021563262 -0.023955971, -0.057577565 0.021613494 -0.024308175, 0.02537176 0.05329816 -0.022080734, 0.021974936 0.053325519 -0.019041449, 0.020343289 0.05378215 -0.017378196, 0.027656153 0.054308891 -0.023954168, 0.027908474 0.054804489 -0.024306282, 0.059122667 -0.016932711 -0.024310306, 0.057821929 -0.016560107 -0.023327306, 0.02585271 0.054308653 -0.023323357, 0.02343221 0.056862354 -0.024306163, 0.022171795 0.053803548 -0.020632312, 0.020405143 0.053945601 -0.019041553, 0.022490308 0.05457662 -0.02208063, 0.020587996 0.054429099 -0.020632178, 0.022916809 0.055611536 -0.023323298, 0.017636061 0.054913476 -0.019041583, 0.015832648 0.055278286 -0.017378062, 0.020883843 0.055211291 -0.022080466, 0.023220405 0.056348458 -0.0239539, 0.017794013 0.055405483 -0.020632073, 0.021279812 0.056258351 -0.023323372, 0.018805623 0.058555737 -0.024306118, 0.015880749 0.055446491 -0.01904133, 0.018049732 0.056201726 -0.022080287, 0.016022936 0.055943519 -0.020631969, 0.018391997 0.057267353 -0.023323298, 0.013183996 0.056148767 -0.019041404, 0.01121372 0.056396976 -0.017377973, 0.016253233 0.056747362 -0.0220806, 0.018635631 0.058026314 -0.0239539, 0.013302177 0.056652039 -0.020631954, 0.016561285 0.05782339 -0.023323089, 0.014058381 0.059873044 -0.024306163, 0.011247739 0.056568593 -0.019041374, 0.013493359 0.05746609 -0.022080392, 0.011348754 0.0570755 -0.020631984, 0.013749093 0.058555722 -0.023323104, 0.0086474866 0.057023987 -0.019041359, 0.006518364 0.057130381 -0.017378002, 0.011511669 0.057895795 -0.022080332, 0.013931394 0.059331521 -0.023953721, 0.0087248534 0.057535127 -0.020631924, 0.01173003 0.058993474 -0.023323253, 0.0092207044 0.060806379 -0.024305984, 0.0065381378 0.057304293 -0.019041419, 0.0088502616 0.058361918 -0.022080421, 0.0065967739 0.057817683 -0.020632058, 0.0090180337 0.059468493 -0.023323074, 0.0040552914 0.057533264 -0.019041255, 0.001778394 0.057473347 -0.017377913, 0.0066915303 0.058648527 -0.022080362, 0.0091374964 0.060256541 -0.023953885, 0.0040915906 0.058048844 -0.020631894, 0.0068183541 0.059760734 -0.023323074, 0.0043242425 0.061349228 -0.024305955, 0.0017839521 0.057648361 -0.0190413, 0.0041504204 0.058883041 -0.022080392, 0.0017997772 0.058165029 -0.020631894, 0.0042291582 0.05999954 -0.02332297, -0.00056295097 0.057673171 -0.01904121, -0.0029737055 0.057424024 -0.017378047, 0.0018256605 0.05900085 -0.022080407, 0.0042851567 0.060794622 -0.023953691, -0.00056776404 0.058190018 -0.020631954, 0.0018603206 0.060119614 -0.023322925, -0.00060024858 0.061498538 -0.02430588, -0.0029827952 0.05759868 -0.01904127, -0.00057592988 0.059026212 -0.022080347, -0.0030095577 0.058115035 -0.02063185, -0.00058695674 0.060145527 -0.023323044, -0.0051774979 0.057443142 -0.01904121, -0.0077055842 0.056982338 -0.017377988, -0.00059485435 0.06094259 -0.023953661, -0.0030527413 0.058950067 -0.022080287, -0.0052237958 0.057957947 -0.02063185, -0.0031106621 0.060067922 -0.023323089, -0.0055208653 0.061253279 -0.024305865, -0.007728979 0.057155669 -0.0190413, -0.005298838 0.058790892 -0.022080377, -0.059122741 0.016935483 -0.024308428, -0.0077982545 0.057668075 -0.020631984, 0.056565076 -0.011258215 -0.019045264, 0.056395829 -0.011212826 -0.017381787, 0.055445328 -0.015879571 -0.019045502, -0.0053994656 0.059905529 -0.023323163, 0.057071984 -0.011359274 -0.020635724, -0.0097586811 0.056844383 -0.019041359, -0.012384772 0.056151524 -0.017378166, 0.055942312 -0.016021952 -0.020636052, -0.005470857 0.060699344 -0.02395381, 0.057892174 -0.011522174 -0.02208437, 0.056746066 -0.016252026 -0.022084564, -0.007910341 0.058496788 -0.0220806, 0.058989629 -0.011740565 -0.023327187, 0.057303011 -0.0065370351 -0.019044995, -0.0098460317 0.057353854 -0.020631865, 0.057129309 -0.0065174252 -0.017381534, -0.0080603063 0.059605852 -0.023322955, 0.057816461 -0.0065956116 -0.02063556, -0.010405913 0.06061472 -0.024305835, -0.012422398 0.056322291 -0.019041449, 0.058647305 -0.0066903532 -0.022084013, -0.0099875033 0.058178082 -0.022080317, 0.059759274 -0.0068170577 -0.023326829, -0.012533709 0.056827083 -0.020631999, 0.057647273 -0.001782611 -0.019044682, -0.010176942 0.05928117 -0.02332291, 0.057472408 -0.001777336 -0.017381221, -0.014277443 0.055880889 -0.019041523, -0.016979218 0.054936871 -0.017377973, 0.060551077 -0.0069073737 -0.023957521, 0.061179221 -0.0062717497 -0.024309903, -0.010311931 0.060066625 -0.023953736, 0.058163807 -0.0017985851 -0.020635337, -0.012713864 0.057643756 -0.022080317, 0.058999538 -0.0018244684 -0.022083744, -0.01440537 0.056381747 -0.020632088, 0.060118213 -0.0018589348 -0.02332662, -0.012954772 0.058736652 -0.023323059, -0.015224427 0.059587196 -0.024306118, 0.057597607 0.0029839277 -0.01904434, 0.05742301 0.0029747933 -0.017381102, -0.017031029 0.0551043 -0.019041568, 0.06091471 -0.0018836111 -0.023957357, 0.061484933 -0.0013545007 -0.024309576, -0.014612302 0.057191983 -0.022080332, 0.058113798 0.0030106306 -0.020634994, 0.0589488 0.0030539781 -0.022083372, -0.017183572 0.055598021 -0.020632088, -0.014889285 0.058276236 -0.023323029, 0.060066432 0.0031119734 -0.023326159, -0.018704399 0.054558694 -0.019041598, -0.02145794 0.053347141 -0.01737833, -0.015086591 0.059048504 -0.02395384, 0.057154596 0.0077301562 -0.019044206, 0.056981325 0.0077066571 -0.017380759, -0.017430514 0.056396872 -0.022080645, 0.060862452 0.0031533241 -0.023956835, 0.061396196 0.0035714656 -0.024309292, 0.057666779 0.0077994764 -0.020634636, -0.018872008 0.055047691 -0.020632207, 0.058495477 0.0079114735 -0.022083193, -0.017760918 0.057466254 -0.023323059, -0.019944996 0.05817771 -0.024306178, -0.019143283 0.055838853 -0.022080377, 0.059604317 0.0080617815 -0.02332592, 0.056321025 0.012423515 -0.019043773, 0.056150451 0.012385726 -0.017380387, -0.021523088 0.053509399 -0.019041508, 0.060394228 0.0081684738 -0.02395685, 0.060913414 0.0084744096 -0.024309039, -0.019506156 0.05689761 -0.023323134, 0.056825787 0.012534901 -0.020634219, -0.021716014 0.053989023 -0.020632178, 0.05764249 0.012715146 -0.022082955, -0.023011476 0.05288662 -0.019041598, -0.025789842 0.051392987 -0.017378375, 0.058735251 0.012956262 -0.023325711, -0.019764662 0.05765152 -0.023954093, -0.022027969 0.054764882 -0.022080585, 0.055124819 0.016960964 -0.019043669, 0.054935887 0.016980276 -0.017380223, -0.023217648 0.053360462 -0.020632178, 0.059513405 0.013127834 -0.023956269, 0.060039833 0.013322845 -0.024308667, -0.022445738 0.055803299 -0.023323298, 0.055618718 0.017112926 -0.020634294, -0.024537757 0.056394339 -0.024306238, -0.023551226 0.054127365 -0.022080764, 0.056417927 0.017358989 -0.022082731, 0.057487637 0.01768817 -0.023325488, -0.025868326 0.051549435 -0.019041687, -0.023997784 0.055153653 -0.023323238, 0.053590372 0.021319017 -0.019043431, 0.053346172 0.021458834 -0.017379969, -0.027170852 0.050874949 -0.019041747, -0.029945776 0.049087793 -0.017378494, 0.058249325 0.01792258 -0.023956224, 0.058780819 0.018086061 -0.024308443, -0.026100323 0.052011371 -0.020632178, -0.024315715 0.055884436 -0.023954108, 0.054070637 0.02151005 -0.020633891, 0.054847717 0.021819264 -0.022082448, -0.027414277 0.051330745 -0.020632178, -0.026475236 0.052758843 -0.02208069, 0.055887446 0.022233054 -0.023325205, 0.051712021 0.025540158 -0.019043222, 0.05139187 0.02579087 -0.017379791, -0.027808145 0.052068487 -0.022080779, -0.026977092 0.053759187 -0.023323357, 0.056627989 0.022527605 -0.023955956, 0.057144701 0.022733197 -0.024308175, -0.028972849 0.054249302 -0.024306491, 0.052175552 0.025768995 -0.020633712, -0.030036747 0.049237326 -0.019041911, -0.028335422 0.053055808 -0.023323357, -0.03115584 0.048536897 -0.019041941, -0.033896968 0.046447173 -0.01737842, 0.052925229 0.026139513 -0.022082239, -0.030305967 0.04967846 -0.020632476, 0.053928569 0.026635095 -0.023324832, 0.049501792 0.029597566 -0.01904279, 0.049086764 0.02994667 -0.017379403, -0.028710887 0.053758845 -0.023954242, 0.054643214 0.026988104 -0.023955569, 0.055141911 0.027234256 -0.024307787, -0.031434879 0.048971772 -0.02063255, -0.030741438 0.05039233 -0.022080883, 0.049945503 0.02986294 -0.020633578, -0.031886563 0.049675494 -0.022080913, 0.050663128 0.030291915 -0.022081986, -0.031324208 0.051347762 -0.02332373, -0.033222169 0.051756039 -0.02430661, 0.051623702 0.030866399 -0.023324698, -0.034000054 0.046588659 -0.019041955, 0.046974078 0.033464968 -0.019042581, 0.046446249 0.033897907 -0.017379284, -0.032491326 0.050617322 -0.023323625, 0.052307814 0.031275406 -0.0239553, -0.034940749 0.045887262 -0.019041941, -0.037616655 0.043489218 -0.017378613, 0.052784964 0.031560674 -0.024307653, -0.034304842 0.04700616 -0.020632491, 0.047394916 0.033764765 -0.020633161, 0.048075959 0.034249932 -0.022081688, -0.032921791 0.051288128 -0.023954257, -0.035254046 0.046298474 -0.020632654, 0.048987553 0.034899533 -0.023324639, -0.034797654 0.047681555 -0.022081122, 0.044144601 0.037117541 -0.019042492, 0.043488249 0.037617803 -0.01737909, -0.035760462 0.046963677 -0.022081017, 0.049636617 0.03536205 -0.023955122, 0.050089493 0.035684735 -0.024307325, -0.035457492 0.048585847 -0.023323685, 0.044540226 0.03745015 -0.020632923, -0.037731111 0.043621883 -0.01904206, 0.045180261 0.037988558 -0.02208136, -0.035927132 0.049229369 -0.023954332, -0.037258208 0.048930764 -0.024306685, -0.03643842 0.047854304 -0.023323625, 0.046036899 0.038708791 -0.023324236, 0.041032106 0.040531918 -0.019042253, 0.040233389 0.041080356 -0.017378926, -0.038069263 0.044012681 -0.020632625, 0.046646833 0.0392216 -0.023955032, -0.036921293 0.048488334 -0.023954436, 0.047072396 0.039579526 -0.024307162, -0.038616195 0.04464519 -0.022081152, 0.041399717 0.040895253 -0.020632759, -0.039348483 0.045491874 -0.023323938, 0.041994676 0.04148306 -0.022081435, -0.041204393 0.040356815 -0.019042313, -0.041079551 0.040234536 -0.017379016, 0.04279086 0.042269558 -0.023324192, -0.0398698 0.046094611 -0.023954481, 0.037656248 0.043686196 -0.01904206, 0.03670384 0.044262528 -0.017378867, -0.041055277 0.045791537 -0.024306849, -0.041573673 0.040718526 -0.020632699, 0.043357804 0.042829603 -0.023954764, 0.043753564 0.043220326 -0.024306908, -0.04217118 0.041303799 -0.02208139, 0.03799355 0.044077888 -0.02063255, -0.042970479 0.042086825 -0.023324162, 0.038539603 0.044711202 -0.022081301, -0.044396281 0.036816493 -0.019042447, -0.044261664 0.036704794 -0.017378971, 0.039270237 0.045559153 -0.023323908, -0.043539852 0.042644665 -0.023954764, -0.044588625 0.042358339 -0.024307087, 0.034038574 0.046560392 -0.019041881, 0.032923296 0.047142312 -0.017378524, -0.044793963 0.037146449 -0.020633116, 0.03979069 0.046162754 -0.023954645, 0.040153518 0.046583906 -0.024306715, -0.045437783 0.037680298 -0.022081569, 0.033023387 0.04728584 -0.019042015, 0.0343436 0.046977654 -0.020632491, -0.046299249 0.03839469 -0.023324326, -0.047284782 0.033024579 -0.019042701, -0.047141612 0.032924354 -0.017379314, 0.033319235 0.047709778 -0.020632461, -0.046912611 0.038903475 -0.023955077, 0.034837157 0.047652781 -0.022080868, -0.04783614 0.038653299 -0.024307385, -0.047708541 0.033320636 -0.02063331, 0.033798173 0.048395172 -0.022080988, -0.048394114 0.03379938 -0.022081837, 0.035497591 0.048556432 -0.023323804, 0.030202463 0.049135596 -0.019041762, 0.028917864 0.049700245 -0.017378539, -0.049311683 0.034440443 -0.023324415, 0.035968065 0.049199715 -0.023954466, 0.036296129 0.049648523 -0.02430667, -0.049850404 0.029006958 -0.019042805, -0.049699292 0.028918862 -0.017379552, -0.049964979 0.034896642 -0.023955196, -0.050776511 0.03470026 -0.024307385, 0.034438908 0.049312875 -0.023323536, -0.050297007 0.029266939 -0.020633504, 0.029005796 0.049851403 -0.019041836, 0.030473158 0.04957594 -0.020632386, -0.051019773 0.029687673 -0.022081956, 0.034895092 0.049966261 -0.023954436, 0.032205731 0.052394614 -0.024306566, -0.051987022 0.03025052 -0.023324698, -0.051917538 0.024716064 -0.017379835, 0.030911133 0.05028832 -0.022080958, -0.052675903 0.030651376 -0.0239553, 0.031497166 0.051241875 -0.023323581, 0.031914428 0.051920816 -0.023954213, -0.053781047 0.020344228 -0.017380089, -0.053391322 -0.045268282 -0.029219434, -0.056184798 -0.044586897 -0.03056258, -0.056656241 -0.041108936 -0.0292193, -0.056328923 -0.047758549 -0.034611911, -0.054342687 -0.050006732 -0.034611925, 0.059890822 -0.043207914 -0.034611747, 0.059047565 -0.044353366 -0.034611613, -0.056941405 -0.045186996 -0.03176634, -0.055445984 -0.047010064 -0.031766564, -0.057502732 -0.04563266 -0.033132896, -0.055992544 -0.047473535 -0.033133119, 0.05565232 -0.048545182 -0.03461197, 0.058694825 -0.044088513 -0.033132866, 0.055319935 -0.048255488 -0.033133164, -0.054018155 -0.049708232 -0.033133283, 0.059533074 -0.04294996 -0.033132672, -0.054709405 -0.046385556 -0.030562729, 0.05812189 -0.043658167 -0.031766385, 0.054779708 -0.047784299 -0.03176637, -0.052563086 -0.051874205 -0.034612313, 0.058952108 -0.042530686 -0.031766146, -0.053490937 -0.049222946 -0.031766489, 0.057349816 -0.043078333 -0.03056255, 0.056767687 -0.040954754 -0.029219389, 0.053514197 -0.045123026 -0.029219314, 0.054052114 -0.047149763 -0.030562893, -0.053810179 -0.045623332 -0.02956681, 0.06212762 -0.039924741 -0.034611657, -0.052249134 -0.051564485 -0.033133268, 0.058168888 -0.041965827 -0.03056246, -0.049821943 -0.049169272 -0.029219672, -0.05278033 -0.048569098 -0.030562982, 0.062981442 -0.038563907 -0.034611523, 0.061756611 -0.039686471 -0.033132464, -0.050547391 -0.05384022 -0.034612149, 0.057212844 -0.041276097 -0.029566735, -0.051739112 -0.051061109 -0.031766742, 0.062605381 -0.03833349 -0.033132538, -0.050245419 -0.053518891 -0.033133194, 0.06115374 -0.039299011 -0.031765983, -0.05105187 -0.050382838 -0.030563191, 0.061994299 -0.037959397 -0.031766146, -0.048497081 -0.055693895 -0.034612387, 0.060341507 -0.038777068 -0.030562416, 0.059697062 -0.036552981 -0.029218987, -0.049754918 -0.052996248 -0.031766757, 0.064876392 -0.035283282 -0.034611255, -0.050212681 -0.049554944 -0.029566988, 0.061170638 -0.037455216 -0.030562177, -0.04820779 -0.055361405 -0.033133492, 0.064488888 -0.035072535 -0.033132136, -0.045968235 -0.052789718 -0.02922, -0.049094081 -0.052292198 -0.030563131, 0.065713003 -0.033699796 -0.034611166, -0.046482325 -0.057386279 -0.034612358, 0.060165495 -0.036839649 -0.029566452, -0.047736943 -0.054820821 -0.031767026, 0.063859388 -0.03473036 -0.031765848, -0.04620479 -0.057043582 -0.033133551, 0.065320626 -0.03349857 -0.033132195, -0.047102898 -0.05409275 -0.030563191, 0.062286243 -0.031942546 -0.029218569, 0.06301111 -0.03426902 -0.030562118, -0.044154778 -0.059195548 -0.034612507, -0.045753673 -0.056486815 -0.031766891, 0.064682931 -0.033171579 -0.031765759, 0.067279056 -0.030453384 -0.034610942, -0.046328798 -0.053203732 -0.029567391, -0.043891191 -0.058842137 -0.033133596, 0.063823566 -0.032731041 -0.030561954, -0.045145869 -0.055736557 -0.030563116, 0.066877156 -0.030271679 -0.033131942, -0.041852012 -0.056108952 -0.02922006, -0.042169273 -0.060626224 -0.034612685, 0.068069443 -0.028643295 -0.034610882, -0.043462634 -0.058267787 -0.031766996, 0.062774613 -0.032193094 -0.029566303, 0.066224366 -0.0299761 -0.03176555, -0.041917518 -0.060264096 -0.033133671, -0.042885199 -0.057493895 -0.030563623, 0.067662954 -0.028472289 -0.033132017, 0.064519688 -0.027149945 -0.02921845, 0.065344542 -0.029578 -0.030561954, -0.039560258 -0.06235978 -0.03461276, -0.041508198 -0.059675947 -0.031767234, -0.042180344 -0.056548998 -0.029567495, 0.069322631 -0.025461078 -0.034610763, -0.039324299 -0.061987415 -0.033133879, 0.067002416 -0.028194338 -0.031765342, -0.040956855 -0.05888319 -0.030563504, -0.037497342 -0.059108198 -0.029220194, 0.068908691 -0.02530922 -0.033131704, -0.037631184 -0.063542485 -0.034612849, 0.066112325 -0.027820095 -0.030561671, -0.038940251 -0.061382338 -0.031767339, 0.070037499 -0.023423478 -0.034610674, 0.070996329 -0.020333067 -0.034610376, -0.037406489 -0.063162997 -0.033133835, 0.068235993 -0.025062203 -0.031765163, -0.038422823 -0.060567111 -0.030563638, 0.065025762 -0.027362779 -0.029565722, -0.034740224 -0.065168008 -0.034612775, 0.069619179 -0.023283541 -0.033131555, 0.070572376 -0.020211503 -0.033131555, -0.037041187 -0.062546507 -0.031767324, 0.067329466 -0.024729371 -0.030561537, -0.037791431 -0.059571654 -0.029567689, 0.066385224 -0.02220206 -0.029218152, -0.034532815 -0.064778879 -0.033133805, 0.068939567 -0.023056313 -0.031765297, 0.069883466 -0.020014241 -0.031764895, -0.032928497 -0.061769918 -0.029220402, -0.036549151 -0.061715901 -0.030563429, 0.068023726 -0.022750124 -0.030561432, 0.068954989 -0.019748628 -0.030561417, 0.067468375 -0.020413414 -0.029524475, 0.066986531 -0.021350011 -0.029404849, -0.032892451 -0.06611979 -0.034613028, 0.066905737 -0.022376195 -0.029565379, -0.034195691 -0.064146534 -0.031767458, -0.070542812 -0.00093576312 -0.029564187, -0.0708967 0.0013844073 -0.029829189, -0.069981053 -0.0016268194 -0.02921696, -0.069904476 0.0036601722 -0.029216602, -0.03269586 -0.065725312 -0.033133924, -0.033741489 -0.063294485 -0.030563608, -0.070286214 -0.0060825199 -0.029564515, -0.070803687 -0.003882885 -0.029829457, -0.069654599 -0.011196673 -0.029565006, -0.070319921 -0.0091284215 -0.029829711, -0.069658577 -0.0069047511 -0.029217348, -0.029721826 -0.067604318 -0.034613013, -0.032376736 -0.065083548 -0.031767428, 0.042004392 -0.055995017 -0.029220209, 0.040106699 -0.058476493 -0.029832527, 0.037657678 -0.059005901 -0.029220268, 0.037548676 -0.059724838 -0.029567629, 0.041808277 -0.056824669 -0.02956745, -0.033186838 -0.062254339 -0.029567868, 0.04611133 -0.052664712 -0.029219911, 0.044337615 -0.055337384 -0.029832169, -0.029544353 -0.067200735 -0.033134043, 0.045844823 -0.053621337 -0.029567331, -0.028171986 -0.064079165 -0.029220521, -0.031946629 -0.064219087 -0.030563831, 0.049636707 -0.050131664 -0.029567003, 0.048323497 -0.051893145 -0.029832155, -0.071825653 0.0028500557 -0.030722454, -0.070423111 0.0042161793 -0.029563919, -0.071599856 0.0042866319 -0.030560002, -0.072563797 0.0043443888 -0.031763554, -0.027977958 -0.068344429 -0.034612939, -0.029255942 -0.066544801 -0.031767711, -0.07215403 0.001589179 -0.031054452, -0.027810931 -0.067936391 -0.033134088, -0.071881711 0.00022494793 -0.030722633, -0.071721569 -0.00095120072 -0.030560225, -0.072687164 -0.00096394122 -0.031763926, -0.0288672 -0.06566073 -0.030563757, -0.071840376 -0.0024452209 -0.030722708, -0.027539402 -0.067273304 -0.031767622, -0.072075889 -0.0037119538 -0.031054884, -0.024533972 -0.069655046 -0.034613311, -0.071703225 -0.0050673187 -0.030722871, -0.072422758 -0.00626719 -0.031764194, -0.071460858 -0.0061841011 -0.030560568, -0.028392851 -0.064581737 -0.029568106, -0.071465313 -0.0077272654 -0.030723169, -0.027173668 -0.066379532 -0.03056401, -0.023254439 -0.066022843 -0.0292207, -0.022914559 -0.070204437 -0.034613237, -0.071608856 -0.0089930743 -0.031054944, -0.024387404 -0.069239035 -0.033134088, -0.07177192 -0.01153712 -0.031764448, -0.071135148 -0.010332212 -0.030723289, -0.070818499 -0.011383757 -0.030560881, 0.038176119 -0.060722888 -0.030563563, 0.03946507 -0.060077414 -0.03072609, 0.038690165 -0.061540365 -0.031767353, -0.022777602 -0.069785282 -0.033134401, -0.024149463 -0.068563193 -0.031767726, 0.040685371 -0.059608683 -0.03105782, 0.041633084 -0.058596089 -0.030726135, -0.022555128 -0.069104001 -0.03176783, 0.043079212 -0.058551773 -0.031767309, 0.042506918 -0.057774127 -0.030563489, -0.023828492 -0.067652524 -0.03056398, 0.043780908 -0.057009041 -0.030726045, -0.019205809 -0.07130827 -0.034613177, -0.018204495 -0.06758979 -0.029220775, -0.022255644 -0.068186119 -0.030564025, 0.044951826 -0.056461066 -0.031057686, 0.045833826 -0.055372134 -0.030725881, 0.047238171 -0.055251122 -0.031766787, 0.046610981 -0.054517254 -0.030563265, -0.02343671 -0.066540614 -0.029568151, 0.047859073 -0.053631395 -0.030725569, -0.017728552 -0.07168977 -0.034613281, 0.048975438 -0.053008929 -0.031057492, -0.019091189 -0.07088235 -0.033134416, 0.049785867 -0.051847667 -0.030725554, 0.051145494 -0.051655442 -0.031766593, 0.050466031 -0.050969407 -0.030562907, -0.017622724 -0.071261734 -0.033134297, -0.072808877 0.0029802471 -0.032044977, -0.018904775 -0.070190519 -0.031767726, -0.070971578 0.020329744 -0.034480661, -0.072291464 0.015100405 -0.034608454, -0.073279232 0.0043873191 -0.033130035, -0.073049024 0.0016697943 -0.032397762, -0.017450586 -0.070565969 -0.031767756, -0.07047452 0.020187348 -0.032890186, -0.071859717 0.015010223 -0.033129454, -0.072868958 0.00031921268 -0.032045364, -0.018653646 -0.069258213 -0.030564308, -0.071158275 0.014863446 -0.031763047, -0.073403746 -0.00097353756 -0.033130318, -0.069670767 0.01995711 -0.031441659, -0.072831675 -0.0023575425 -0.032045335, -0.013768286 -0.072554499 -0.034613341, -0.070212975 0.014665961 -0.030559465, -0.072975472 -0.0036769956 -0.03239809, -0.068594992 0.019648805 -0.030198857, -0.013050288 -0.068771064 -0.029220819, -0.017218828 -0.06962873 -0.030564114, -0.018347099 -0.068119928 -0.029568091, -0.073200643 0.0097830594 -0.034608752, -0.073136702 -0.0063291788 -0.033130556, -0.072696865 -0.0050160438 -0.032045811, -0.068557292 0.014141887 -0.02921626, -0.069058999 0.014424995 -0.029563531, -0.067294091 0.019276097 -0.029215917, -0.01368627 -0.072121114 -0.033134386, -0.072463378 -0.0076827258 -0.032045886, -0.072763607 0.009724617 -0.033129677, -0.072510928 -0.0090043247 -0.032398403, -0.072053209 0.0096295327 -0.031763107, -0.013552457 -0.071417421 -0.031767711, -0.072479531 -0.011650756 -0.033130899, -0.07213442 -0.010324001 -0.03204605, -0.01337257 -0.070468679 -0.030564249, -0.071095943 0.0095015913 -0.030559674, 0.039938524 -0.060948148 -0.032048792, 0.03907147 -0.062146813 -0.03313379, -0.0082523525 -0.073386833 -0.034613281, 0.041145399 -0.060380161 -0.032401189, -0.013152763 -0.069310486 -0.029568136, -0.073719352 0.0044137537 -0.034609035, -0.069927648 0.0093454421 -0.029563755, 0.043503851 -0.059129089 -0.033133611, 0.042137936 -0.059448868 -0.032048643, -0.0082031041 -0.072948694 -0.033134565, -0.069428682 0.0089262575 -0.029216334, 0.04429321 -0.05786103 -0.032048732, -0.008122921 -0.072236344 -0.031768039, 0.045451343 -0.057209238 -0.03240104, -0.0080149919 -0.071276993 -0.030564189, 0.046376839 -0.056204692 -0.032048568, 0.04770413 -0.055795744 -0.033133402, -0.0026889145 -0.073800355 -0.03461355, 0.048410088 -0.054463491 -0.032048509, -0.0078833401 -0.070105478 -0.029568151, -0.0078219026 -0.069560051 -0.02922076, 0.049513549 -0.053732201 -0.032400891, -0.002673015 -0.073359594 -0.033134356, 0.050366819 -0.052658945 -0.0320483, 0.051649764 -0.052164748 -0.033133417, -0.07364352 0.0017037541 -0.033847541, -0.0026468784 -0.072643474 -0.03176789, -0.073844686 -0.00097930431 -0.034609318, -0.0026119053 -0.071678475 -0.030564174, -0.073570937 -0.0036799461 -0.033847809, -0.073576182 -0.0063668936 -0.034609601, 0.0028894395 -0.07379286 -0.034613371, -0.072915062 -0.011720732 -0.034609973, -0.073105529 -0.009043768 -0.033848166, -0.0025688261 -0.070500508 -0.029568061, -0.0025487542 -0.069951892 -0.029220849, 0.039306253 -0.06252028 -0.034612745, 0.041465178 -0.060882121 -0.033851057, 0.0028720647 -0.073352218 -0.03313452, 0.043765217 -0.059484378 -0.034612611, 0.0028441846 -0.072635904 -0.031768069, 0.045801401 -0.057690844 -0.033850834, 0.04799059 -0.056130901 -0.034612447, 0.0028063506 -0.071671188 -0.030564278, 0.05196017 -0.05247809 -0.034612253, 0.049893156 -0.054191381 -0.033850774, 0.008451432 -0.073363975 -0.03461349, 0.0027602464 -0.070493355 -0.029568255, 0.002738744 -0.069944575 -0.029220894, 0.008401081 -0.072926149 -0.03313449, 0.0083189905 -0.072214141 -0.031767815, 0.0082084388 -0.071254894 -0.030564249, 0.013965324 -0.072516665 -0.034613311, -0.07186465 -0.017011687 -0.034610301, 0.0080107301 -0.069538429 -0.02922079, 0.0080735534 -0.070083708 -0.0295683, -0.068938613 -0.01214318 -0.029217541, -0.071435601 -0.016910344 -0.033131316, 0.013881877 -0.072083816 -0.033134356, -0.070738226 -0.016745314 -0.031764641, 0.013746306 -0.071380079 -0.03176786, -0.06979841 -0.016522944 -0.030561194, 0.013563871 -0.070431978 -0.030564129, -0.067825034 -0.017312154 -0.029217869, 0.019399375 -0.071255878 -0.034613192, -0.070430994 -0.022212297 -0.034610271, 0.01334095 -0.0692745 -0.02956818, -0.069973826 -0.023613602 -0.034610584, 0.013237163 -0.068735361 -0.029220745, -0.070010483 -0.022079781 -0.033131763, 0.019283742 -0.07083036 -0.033134326, 0.019095361 -0.070138887 -0.031767696, -0.069555834 -0.023472682 -0.033131778, -0.069327131 -0.021864161 -0.031764999, 0.018841714 -0.069207206 -0.030564114, -0.068876773 -0.023243576 -0.031765133, 0.024722919 -0.069588125 -0.034613147, -0.066324607 -0.022382334 -0.029218093, -0.068405941 -0.021573856 -0.030561507, 0.01838775 -0.067540139 -0.029220745, 0.018532053 -0.068069786 -0.029567972, 0.024575338 -0.06917268 -0.033134326, -0.068621621 -0.027293995 -0.034610808, -0.067961872 -0.022934869 -0.030561462, -0.067991301 -0.028828248 -0.034610748, 0.024335265 -0.068497285 -0.031767711, -0.068211958 -0.027131006 -0.033131912, 0.024012193 -0.067587405 -0.030564055, -0.066844732 -0.022558004 -0.029565528, -0.067585453 -0.028655961 -0.033132017, 0.029783994 -0.067576945 -0.034612998, 0.023433611 -0.065959498 -0.029220626, 0.023617551 -0.066476718 -0.029568002, -0.06754601 -0.026866347 -0.031765431, -0.066925704 -0.028376371 -0.031765476, 0.029606149 -0.067173421 -0.033134073, 0.029317155 -0.066517845 -0.031767622, -0.066648528 -0.026509687 -0.030561626, -0.064445704 -0.02732496 -0.029218271, 0.02892758 -0.065634206 -0.030563921, -0.066446081 -0.032230362 -0.034611076, -0.066036567 -0.027999476 -0.030561641, 0.034637466 -0.065222561 -0.034612879, -0.066049367 -0.032037944 -0.033132121, 0.028452173 -0.064555541 -0.029567927, 0.028345719 -0.064002514 -0.029220477, -0.065621108 -0.033878282 -0.034610972, 0.034430683 -0.064833075 -0.033134043, -0.064951256 -0.027539268 -0.029565915, 0.034094557 -0.064200327 -0.031767398, -0.065404713 -0.031725287 -0.031765535, 0.033641607 -0.063347608 -0.030563742, -0.065229371 -0.033675879 -0.03313227, -0.062199309 -0.032111615 -0.029218644, -0.064535707 -0.031303763 -0.030562058, 0.033088773 -0.062306419 -0.029567882, 0.03309603 -0.061680019 -0.029220432, -0.06459257 -0.033347011 -0.031765878, -0.063916028 -0.036994711 -0.034611285, -0.063734546 -0.032904312 -0.030562073, -0.063534647 -0.036773652 -0.033132493, -0.062876552 -0.038734719 -0.034611493, -0.062687024 -0.032363385 -0.029565975, -0.062914193 -0.036414832 -0.031765863, -0.062501267 -0.038503543 -0.033132523, -0.059597895 -0.036714911 -0.029219046, -0.062078208 -0.0359312 -0.030562192, -0.061044946 -0.04156144 -0.034611568, -0.061891153 -0.038127646 -0.031765983, -0.060680583 -0.041313529 -0.033132687, -0.061068878 -0.03762123 -0.030562237, -0.059773177 -0.043370426 -0.034611568, -0.060088038 -0.040909976 -0.031766072, -0.060065165 -0.037002936 -0.029566467, -0.059416339 -0.043111429 -0.033132643, -0.059289828 -0.040366739 -0.030562535, -0.05784826 -0.045906618 -0.034611806, -0.058836341 -0.04269056 -0.03176634, -0.058054879 -0.042123705 -0.03056258, 0.049955294 -0.049033731 -0.029219761, -0.057100683 -0.041431308 -0.029566854, 0.069842458 0.0046943426 -0.029216602, 0.06551069 0.0056048483 -0.026762977, 0.069289014 0.0099526346 -0.029216275, 0.064539954 0.012557521 -0.026762515, 0.065734714 -0.0014116615 -0.02676335, 0.069752872 -0.0058731586 -0.029217213, 0.069997385 -0.00059112906 -0.02921693, 0.069110587 -0.011121556 -0.029217586, 0.065209404 -0.0084120184 -0.026763752, -0.060143203 0.020760953 -0.025535092, -0.060917854 0.024741709 -0.026761919, -0.065647393 0.024300858 -0.02921547, -0.064160556 0.022147849 -0.027989, -0.058507174 0.038432062 -0.029214785, -0.058325559 0.034717098 -0.02798833, -0.061241284 0.033906177 -0.029215068, -0.054287732 0.037095115 -0.026761115, -0.057933047 0.031095743 -0.026761413, -0.031122327 0.062702611 -0.029213309, -0.032685056 0.059488803 -0.027986899, -0.035766467 0.06017445 -0.029213399, -0.034035593 0.056256682 -0.026759967, -0.027843997 0.059565008 -0.026759908, -0.021328896 0.066673189 -0.029213056, -0.017884061 0.065478191 -0.027986467, -0.021334782 0.062193915 -0.026759684, -0.016235605 0.068092987 -0.029213145, -0.014582381 0.064114183 -0.026759639, 0.020339727 0.066981539 -0.029213205, 0.017767832 0.065509945 -0.027986392, 0.015225828 0.068325579 -0.029213101, -0.063625842 0.0291868 -0.029215142, 0.013296515 0.064393148 -0.026759654, 0.020086125 0.062608317 -0.026759595, 0.051356897 0.047567099 -0.029214203, 0.047769815 0.048220426 -0.027987495, 0.047620118 0.051307857 -0.029213935, 0.044224322 0.048656344 -0.026760474, 0.049159572 0.043663904 -0.026760831, 0.060732722 0.034808889 -0.029215023, 0.057712361 0.035726935 -0.027988076, 0.057932019 0.039294019 -0.029214695, 0.053534567 0.038173735 -0.026761129, 0.057299152 0.032248512 -0.026761591, 0.0678574 0.001548782 -0.027990028, -0.055439517 0.042738885 -0.029214472, -0.052055582 0.046801731 -0.029214263, -0.050023392 0.042671487 -0.026760846, -0.048374221 0.050597563 -0.029214203, -0.045189112 0.047761813 -0.026760608, -0.044417202 0.054104745 -0.029213965, -0.039839327 0.052307293 -0.02676028, -0.040206432 0.057303056 -0.029213548, -0.026300713 0.06487307 -0.029213324, -0.011049271 0.069124147 -0.02921319, -0.0058001578 0.069760948 -0.02921313, -0.0076639652 0.065303415 -0.026759684, -0.00051803887 0.069999799 -0.029212996, -0.00065790117 0.065748364 -0.026759475, 0.0047672242 0.069839075 -0.029212907, 0.0063556731 0.065443739 -0.026759654, 0.010025322 0.069280013 -0.029212981, 0.025337771 0.065255076 -0.029213339, 0.026646465 0.060109958 -0.026759714, 0.030191004 0.063156247 -0.029213339, 0.032903194 0.056926638 -0.026759952, 0.03487201 0.060697109 -0.029213458, 0.039353937 0.057891697 -0.029213682, 0.038784727 0.053093895 -0.026760191, 0.043611467 0.05475615 -0.02921389, 0.054800749 0.043554589 -0.029214546, 0.063186929 0.030125156 -0.029215276, 0.065280348 0.025269777 -0.029215515, 0.060410619 0.025955603 -0.026761681, 0.067001507 0.020269841 -0.029215857, 0.062833443 0.019366995 -0.026762247, 0.068340242 0.015154555 -0.029215977, -0.011174798 0.084937274 -0.063407645, -0.013217658 0.084306255 -0.06320256, -0.011131197 0.084606752 -0.063202515, -0.011088088 0.084277317 -0.062995344, -0.016813025 0.083324313 -0.062995449, -0.013269305 0.084635451 -0.063407749, -0.016878963 0.083650053 -0.06320253, -0.018818945 0.083234876 -0.063202515, -0.022459924 0.081982568 -0.062995434, -0.016944826 0.083976611 -0.063407704, -0.018892482 0.083560109 -0.06340766, -0.022547662 0.082303017 -0.063202575, -0.0243361 0.081792057 -0.06320256, -0.028002024 0.080258861 -0.062995717, -0.022635803 0.082624525 -0.063407749, -0.024431109 0.082111582 -0.063407958, -0.028111681 0.080572575 -0.06320259, -0.029744521 0.079983875 -0.063202783, -0.033413559 0.078160688 -0.062995806, -0.028221384 0.080887139 -0.063407972, -0.02986078 0.080296531 -0.063407779, -0.033544347 0.078466251 -0.063202709, -0.035020351 0.077818587 -0.063202888, -0.038669407 0.075698406 -0.06299594, -0.033675238 0.078772813 -0.063407898, -0.035157204 0.078122616 -0.063408151, -0.03882052 0.075994432 -0.063202918, -0.040139586 0.07530579 -0.063203081, -0.043744788 0.072882995 -0.062996045, -0.038972288 0.076291069 -0.06340836, -0.040296391 0.075599998 -0.063408107, -0.043915883 0.073168069 -0.063203231, -0.044087291 0.073453635 -0.063408196, -0.048806235 0.07000035 -0.063203275, -0.048616171 0.069727778 -0.062996224, -0.048996955 0.070273712 -0.063408479, -0.053469315 0.066506535 -0.06320335, -0.053260997 0.066247463 -0.062996462, -0.053678155 0.066766217 -0.063408628, -0.057883009 0.06270273 -0.063203663, -0.057657614 0.0624585 -0.062996507, -0.058109045 0.062947512 -0.063408881, -0.062026575 0.058606282 -0.063203782, -0.061785251 0.058378354 -0.062996745, -0.062269092 0.058835387 -0.063409209, -0.065881237 0.054237008 -0.063204259, -0.065624923 0.054025814 -0.062997058, -0.066138789 0.054448754 -0.063409403, -0.069428772 0.049614668 -0.063204452, -0.069158375 0.049421325 -0.062997267, -0.069699883 0.049808353 -0.063409805, -0.072652549 0.044760928 -0.063204616, -0.072369725 0.044586673 -0.062997773, -0.072936252 0.044935822 -0.063409984, -0.075537726 0.03969866 -0.063205004, -0.075243428 0.039544135 -0.062997878, -0.075832486 0.039853737 -0.063410357, -0.078070208 0.034451291 -0.063205495, -0.077766359 0.03431721 -0.062998131, -0.078375235 0.034585834 -0.063410446, -0.080238968 0.029043287 -0.063205495, -0.079926655 0.028930187 -0.062998474, -0.082033664 0.023499906 -0.063206002, -0.08055234 0.02915664 -0.063410774, -0.082354262 0.023591757 -0.063411132, 0.08341974 -0.017960951 -0.063208193, 0.083120897 -0.01777029 -0.063001096, 0.082033724 -0.023492768 -0.06320855, 0.083745629 -0.018031105 -0.063413426, 0.082354128 -0.02358456 -0.063413829, 0.084433377 -0.01234898 -0.063207924, 0.084140033 -0.012056485 -0.063000754, 0.084763274 -0.012397259 -0.063413158, 0.085069954 -0.0066818446 -0.063207507, 0.084766909 -0.0062864274 -0.06300053, 0.085402325 -0.0067078173 -0.06341292, 0.085326523 -0.00098493695 -0.063207209, 0.084998682 -0.00048716366 -0.063000217, 0.085659817 -0.00098879635 -0.063412547, 0.085202008 0.004716441 -0.063206986, 0.08483395 0.0053146034 -0.062999934, 0.085534856 0.0047349185 -0.063412398, 0.084697053 0.010396868 -0.063206807, 0.084273651 0.011091515 -0.062999561, 0.085027859 0.010437414 -0.063411996, 0.083813608 0.016030833 -0.063206315, 0.083320484 0.016816691 -0.062999204, 0.084141046 0.016093358 -0.0634114, 0.082555994 0.021593228 -0.063206077, 0.081979051 0.022463515 -0.062998936, 0.082878396 0.021677464 -0.06341134, 0.080929548 0.027059078 -0.063205689, 0.080255076 0.02800566 -0.062998772, 0.08124575 0.027164683 -0.063411042, 0.078941762 0.032404065 -0.063205466, 0.078157037 0.03341721 -0.062998176, 0.079250187 0.03253068 -0.063410625, 0.076601386 0.037604541 -0.063205004, 0.075694576 0.03867279 -0.062997892, 0.076900586 0.037751272 -0.063410476, 0.073918894 0.042636856 -0.063204691, 0.072879344 0.043748438 -0.062997639, 0.073164329 0.04391937 -0.063204587, 0.074207529 0.042803392 -0.063410059, 0.07344991 0.044091001 -0.063409984, 0.070906088 0.047478855 -0.063204572, 0.069724217 0.048619851 -0.062997296, 0.06999667 0.048809886 -0.063204378, 0.071183249 0.047664434 -0.063409835, 0.070270121 0.049000472 -0.063409746, 0.067576915 0.052109107 -0.063204274, 0.066243991 0.053264648 -0.062997267, 0.066503003 0.053472668 -0.063204259, 0.06784071 0.052312359 -0.063409686, 0.06676273 0.053681687 -0.063409507, 0.063945636 0.056506127 -0.063204005, 0.062454998 0.057661116 -0.062996954, 0.06269902 0.057886466 -0.06320399, 0.064195514 0.056726933 -0.06340915, 0.062943846 0.058112517 -0.063409194, 0.060029 0.060651094 -0.063203827, 0.058374614 0.061788753 -0.06299679, 0.05860281 0.062030077 -0.063203558, 0.060263291 0.060887977 -0.06340903, 0.058831841 0.062272564 -0.063408971, 0.055843979 0.064525172 -0.063203409, 0.054022163 0.065628409 -0.062996328, 0.056062207 0.064777285 -0.063408718, 0.054233402 0.065884918 -0.063203409, 0.054445148 0.066142112 -0.063408822, 0.051409751 0.068110988 -0.063203305, 0.049417824 0.069161966 -0.062996164, 0.0516105 0.068377241 -0.06340839, 0.049610928 0.069432199 -0.063203245, 0.049804911 0.0697034 -0.063408643, 0.046746016 0.07139267 -0.063203141, 0.044583097 0.072373107 -0.062995955, 0.04692854 0.071671635 -0.063408509, 0.044757366 0.072655976 -0.063203201, 0.044932172 0.072939828 -0.063408405, 0.041873291 0.074355587 -0.063203052, 0.03954041 0.075246915 -0.062995777, 0.042036787 0.07464613 -0.063408554, 0.039695203 0.0755409 -0.063202947, 0.039850071 0.075836033 -0.06340839, 0.036813542 0.076986581 -0.063202828, 0.034313634 0.077769741 -0.062995791, 0.036957383 0.077287152 -0.063408062, 0.03444764 0.078073755 -0.063202724, 0.034582198 0.078378767 -0.063408002, 0.031589478 0.079273418 -0.063202828, 0.028926566 0.079930156 -0.062995777, 0.031712651 0.079583064 -0.063408002, 0.029039636 0.080242589 -0.063202605, 0.029153123 0.08055599 -0.063407943, 0.026224375 0.081206366 -0.06320259, 0.023404717 0.081717774 -0.062995359, 0.026326761 0.081523582 -0.063407883, 0.023496374 0.0820373 -0.063202456, 0.023588002 0.082357809 -0.063407734, 0.020741895 0.082776725 -0.063202605, 0.017773703 0.083124593 -0.062995508, 0.020822972 0.083100021 -0.063407674, 0.017843172 0.083449513 -0.0632025, 0.01791288 0.083775505 -0.063407674, 0.015166968 0.083977208 -0.063202381, 0.012059942 0.084143743 -0.062995449, 0.01522626 0.084305108 -0.063407674, 0.012107015 0.084472507 -0.0632025, 0.012154296 0.084802568 -0.063407779, 0.0095244199 0.084802687 -0.063202426, 0.0062899143 0.08477062 -0.062995449, 0.0095616132 0.08513391 -0.063407689, 0.0063144118 0.085101947 -0.063202307, 0.0063392669 0.085434332 -0.06340754, 0.0038390458 0.085249558 -0.063202381, 0.00049056113 0.085002214 -0.062995255, 0.0038540214 0.085582569 -0.063407674, 0.00049243867 0.085334435 -0.063202456, 0.00049443543 0.085667819 -0.063407525, -0.0018631667 0.08531557 -0.063202307, -0.0053110123 0.084837556 -0.06299524, -0.0018705428 0.085648671 -0.063407809, -0.0053319037 0.085169211 -0.0632025, -0.0053526312 0.085501745 -0.0634076, -0.0075572729 0.08500056 -0.063202247, -0.0075867921 0.085332587 -0.063407645, -0.013269275 0.08462818 0.063417301, -0.011174828 0.084930062 0.063417256, -0.013217688 0.084298879 0.063211858, -0.011131436 0.084599555 0.063211873, -0.011087954 0.084270209 0.063004658, -0.016813308 0.083316997 0.063004628, -0.016944885 0.083969414 0.063417122, -0.018892258 0.083552942 0.063417286, -0.016878873 0.083642885 0.063211784, -0.018818796 0.083227754 0.063211784, -0.022459924 0.08197543 0.06300433, -0.022635788 0.082617342 0.063416943, -0.024431169 0.08210434 0.063417181, -0.022547662 0.08229591 0.063211724, -0.024336129 0.081784979 0.063211694, -0.028001994 0.080251634 0.063004673, -0.028221458 0.08088018 0.063416973, -0.029860646 0.080289215 0.063416913, -0.028111458 0.080565318 0.063211516, -0.029744595 0.079976887 0.063211486, -0.033413589 0.07815361 0.063004434, -0.033675224 0.07876578 0.063416943, -0.035157204 0.078115463 0.063416705, -0.033544213 0.078459159 0.06321153, -0.035020322 0.077811524 0.063211337, -0.038669288 0.075691164 0.063004166, -0.03897208 0.076283842 0.063416719, -0.040296406 0.075592816 0.063416675, -0.038820446 0.075987026 0.063211203, -0.040139616 0.075298801 0.063211292, -0.043744832 0.072875872 0.063004002, -0.044087306 0.073446602 0.063416407, -0.043915704 0.073160544 0.063211083, -0.048996925 0.070266619 0.063416287, -0.048806325 0.069993243 0.063210994, -0.04861635 0.069720834 0.063003898, -0.053678095 0.066759169 0.063416168, -0.0534693 0.066499293 0.0632108, -0.053261101 0.066240445 0.063003689, -0.058108956 0.062940478 0.063416004, -0.057882845 0.062695414 0.063210458, -0.057657465 0.062451437 0.063003585, -0.062268972 0.05882819 0.063415602, -0.062026724 0.058599204 0.063210309, -0.061785132 0.058371007 0.063003317, -0.066138685 0.054441676 0.063415542, -0.065881357 0.054229781 0.063210204, -0.065624848 0.054018557 0.063003168, -0.069700018 0.04980132 0.063415244, -0.069428802 0.049607456 0.063210055, -0.069158569 0.049414381 0.063002706, -0.072936401 0.044928595 0.06341508, -0.072652429 0.04475382 0.063209429, -0.072369501 0.044579491 0.063002422, -0.075832471 0.039846703 0.063414738, -0.075537533 0.039691508 0.063209325, -0.075243503 0.039536908 0.063002259, -0.078375161 0.034578577 0.063414335, -0.078070223 0.034444079 0.063208953, -0.077766314 0.034310028 0.063002035, -0.080552429 0.029149488 0.063414156, -0.082354173 0.023584485 0.063413888, -0.080239117 0.029036045 0.063208729, -0.082033709 0.023492888 0.063208267, -0.079926565 0.028923064 0.063001484, 0.083745852 -0.018038362 0.063411459, 0.082354262 -0.023591772 0.063411057, 0.083419785 -0.017968133 0.063206032, 0.083120987 -0.017777294 0.06299898, 0.082033724 -0.023499846 0.063205764, 0.084763288 -0.012404472 0.063411772, 0.084433526 -0.012356192 0.0632063, 0.084139973 -0.012063608 0.062999263, 0.08540228 -0.0067151785 0.063412145, 0.085069954 -0.0066889971 0.063206702, 0.084766924 -0.0062935799 0.062999681, 0.085659698 -0.0009958595 0.063412398, 0.085326597 -0.0009919703 0.06320709, 0.084998667 -0.0004940629 0.06299983, 0.085534871 0.0047277808 0.063412726, 0.085201979 0.0047093481 0.063207373, 0.08483386 0.005307585 0.063000247, 0.085027933 0.010430127 0.063413084, 0.084696934 0.010389686 0.063207552, 0.084273756 0.011084393 0.063000605, 0.084141016 0.016086265 0.063413233, 0.083813697 0.016023606 0.06320776, 0.083320469 0.016809523 0.063001066, 0.082878321 0.021670312 0.063413829, 0.082555979 0.021585941 0.063208461, 0.081979007 0.022456437 0.063001215, 0.081245586 0.027157664 0.063413978, 0.080929726 0.027051777 0.063208669, 0.080255032 0.027998447 0.063001484, 0.079250157 0.032523498 0.063414335, 0.078941926 0.032396957 0.063208789, 0.078157142 0.033410028 0.063001812, 0.076900616 0.037744284 0.063414633, 0.076601267 0.037597269 0.063209116, 0.075694636 0.038665652 0.063002288, 0.074207515 0.042796373 0.063414872, 0.073450029 0.044083729 0.063414752, 0.073918909 0.042629644 0.063209325, 0.072879255 0.043741256 0.063002467, 0.07316424 0.043912128 0.063209504, 0.071183205 0.047657207 0.06341517, 0.070270181 0.048993245 0.063415229, 0.070906103 0.047471717 0.063209713, 0.069724143 0.048612669 0.063002706, 0.069996774 0.048802704 0.063209802, 0.067840666 0.052305356 0.063415468, 0.066762805 0.053674713 0.063415587, 0.067576796 0.052101925 0.0632101, 0.066243976 0.053257391 0.063002884, 0.06650278 0.053465575 0.0632101, 0.064195305 0.056719959 0.063415617, 0.062943965 0.058105484 0.063415736, 0.063945651 0.056499124 0.06321013, 0.062454909 0.057653859 0.063003331, 0.06269896 0.057879418 0.063210398, 0.060263544 0.060880855 0.063415915, 0.058831751 0.062265351 0.063416004, 0.060028881 0.060644001 0.063210368, 0.058374524 0.061781615 0.063003242, 0.05860275 0.062023222 0.063210398, 0.056062192 0.064770177 0.063416153, 0.055844069 0.064518109 0.063210636, 0.054022074 0.065621108 0.063003749, 0.054445326 0.066135079 0.063416094, 0.054233372 0.065877616 0.063210875, 0.051610649 0.068370074 0.063416272, 0.05140996 0.068103984 0.063210875, 0.049417704 0.069154814 0.063003868, 0.049804628 0.069696456 0.063416451, 0.049610913 0.069425166 0.063210905, 0.046928465 0.071664557 0.063416332, 0.046745867 0.071385756 0.063211054, 0.044583112 0.072366014 0.063004047, 0.044932157 0.072932616 0.063416541, 0.044757366 0.072648868 0.063211113, 0.042036802 0.074638978 0.063416541, 0.041873157 0.074348643 0.063210994, 0.03954041 0.075239867 0.063004225, 0.039850146 0.07582888 0.063416719, 0.039695054 0.075534016 0.063211352, 0.036957264 0.077280104 0.063416779, 0.036813527 0.076979458 0.063211471, 0.034313619 0.077762768 0.063004315, 0.034582078 0.078371704 0.063416988, 0.03444767 0.078066692 0.06321159, 0.03171277 0.07957606 0.063416958, 0.031589359 0.079266369 0.06321159, 0.028926402 0.079923004 0.063004553, 0.029153079 0.080548808 0.063416958, 0.029039651 0.080235377 0.063211471, 0.026326597 0.08151646 0.063417077, 0.026224256 0.081199199 0.063211501, 0.023404628 0.081710875 0.063004553, 0.023587942 0.082350567 0.063416988, 0.02349627 0.082030222 0.06321159, 0.020822853 0.083092824 0.063417137, 0.02074191 0.082769409 0.06321165, 0.017773747 0.083117396 0.063004524, 0.017912924 0.083768383 0.063417107, 0.017843246 0.083442241 0.06321165, 0.015226305 0.084298134 0.063417107, 0.015166909 0.083970144 0.063211709, 0.012060016 0.08413671 0.063004643, 0.012154549 0.084795445 0.063417256, 0.012107283 0.084465533 0.063211769, 0.0095613599 0.085126862 0.063417166, 0.0095243752 0.084795535 0.063211769, 0.0062898993 0.084763318 0.063004643, 0.0063391626 0.085427299 0.063417226, 0.0063145459 0.08509478 0.063211739, 0.0038540661 0.085575327 0.063417256, 0.0038390458 0.085242406 0.063211828, 0.00049060583 0.084995076 0.063004613, 0.00049450994 0.085660636 0.063417286, 0.00049242377 0.085327357 0.063211739, -0.001870513 0.085641712 0.063417315, -0.0018632114 0.085308433 0.063211799, -0.0053111315 0.084830418 0.063004762, -0.0053527355 0.085494727 0.063417301, -0.0053318143 0.085162014 0.063211799, -0.0075866878 0.085325494 0.063417166, -0.0075572431 0.084993467 0.063211635, 0.013269112 -0.084635362 0.063407645, 0.011174694 -0.084937111 0.063407466, 0.013320878 -0.084965572 0.063611254, 0.013217524 -0.084306002 0.063202247, 0.011131018 -0.084606588 0.063202426, 0.016944692 -0.083976671 0.063407615, 0.018965974 -0.083886266 0.063611329, 0.018892318 -0.083560079 0.063407838, 0.016878799 -0.083649889 0.063202322, 0.018818662 -0.083234772 0.063202441, 0.022635758 -0.082624435 0.06340754, 0.024526477 -0.082432091 0.063611493, 0.024431139 -0.082111612 0.063407794, 0.022547662 -0.082303047 0.063202381, 0.024335966 -0.081792027 0.063202649, 0.028221294 -0.080887169 0.063407764, 0.029977322 -0.080609903 0.063611776, 0.02986072 -0.080296427 0.063408002, 0.028111324 -0.08057256 0.063202605, 0.029744506 -0.07998392 0.063202664, 0.033675179 -0.078772768 0.063407898, 0.035294265 -0.078427494 0.063611597, 0.035157099 -0.078122556 0.063408002, 0.033544034 -0.078466162 0.063202396, 0.035020173 -0.077818587 0.06320262, 0.03897205 -0.076290935 0.063408256, 0.040453717 -0.075895056 0.063611716, 0.040296167 -0.075599954 0.063408211, 0.038820416 -0.075994223 0.063202575, 0.040139675 -0.075305715 0.063202783, 0.044087246 -0.073453769 0.063408047, 0.045432195 -0.073023483 0.063612044, 0.043915659 -0.073167831 0.063203081, 0.048996747 -0.070273742 0.063408449, 0.050207958 -0.069825962 0.063612029, 0.048806235 -0.070000336 0.063203156, 0.053677887 -0.066766262 0.063408673, 0.054759368 -0.066316471 0.063612223, 0.053469062 -0.06650652 0.063203305, 0.058108926 -0.062947556 0.063408971, 0.05906634 -0.062510982 0.063612685, 0.05788286 -0.062702626 0.063203543, 0.062268838 -0.058835313 0.063409254, 0.063109607 -0.058426157 0.063612834, 0.062026426 -0.058606312 0.063203722, 0.066138521 -0.054448575 0.063409373, 0.066870704 -0.054080203 0.063613042, 0.065881282 -0.054236874 0.06320402, 0.069699779 -0.049808472 0.063409701, 0.070333377 -0.049493194 0.063613296, 0.069428667 -0.049614549 0.063204184, 0.072936237 -0.044935822 0.06340988, 0.073481813 -0.044684798 0.06361343, 0.072652429 -0.044761136 0.063204482, 0.075832382 -0.039853752 0.063410208, 0.076302156 -0.03967692 0.063613951, 0.075537518 -0.03969872 0.063204974, 0.078375205 -0.034585819 0.06341055, 0.07878162 -0.034491941 0.063614249, 0.078070283 -0.034451142 0.063205212, 0.080552369 -0.029156893 0.063410804, 0.080909267 -0.029152945 0.063614577, 0.080239013 -0.029043317 0.063205495, -0.083745882 0.01803121 0.06341359, -0.084072679 0.018101484 0.063617289, -0.083420083 0.017960876 0.063208193, -0.084763512 0.012397319 0.063413247, -0.085094139 0.012445688 0.063616738, -0.084433526 0.012348995 0.063207611, -0.08540234 0.0067079514 0.063412875, -0.085735887 0.0067342371 0.063616231, -0.085070059 0.0066819489 0.063207448, -0.085659876 0.00098891556 0.063412562, -0.085994378 0.00099264085 0.063616216, -0.085326597 0.00098499656 0.063207209, -0.085534871 -0.0047348589 0.063412055, -0.085868895 -0.0047532171 0.063615695, -0.085202128 -0.0047164857 0.063206881, -0.085027784 -0.010437399 0.063411698, -0.085359856 -0.010478109 0.063615322, -0.084697008 -0.010396838 0.0632063, -0.084141001 -0.016093373 0.063411802, -0.084469497 -0.016156211 0.063615143, -0.083813697 -0.016030714 0.063206211, -0.0828785 -0.021677464 0.063411161, -0.08320196 -0.021762028 0.06361489, -0.082556143 -0.021592885 0.063205808, -0.081245884 -0.027164653 0.063410982, -0.081563011 -0.027270719 0.063614368, -0.080929682 -0.027059019 0.063205555, -0.079250336 -0.032530561 0.063410655, -0.079559594 -0.032657564 0.063614205, -0.078941822 -0.032403976 0.063205138, -0.07690075 -0.037751168 0.063410327, -0.077200949 -0.03789863 0.063613817, -0.076601461 -0.037604377 0.06320484, -0.074207976 -0.042803422 0.063410044, -0.074497327 -0.042970464 0.063613638, -0.073450193 -0.044090927 0.063409939, -0.071461126 -0.047850594 0.063613325, -0.073918983 -0.042636782 0.063204676, -0.073164359 -0.043919176 0.063204676, -0.07118322 -0.047664434 0.063409925, -0.070270494 -0.049000517 0.063409686, -0.068105683 -0.052516595 0.063613176, -0.070906281 -0.047479048 0.063204348, -0.069996804 -0.048809767 0.063204348, -0.067840949 -0.052312508 0.063409612, -0.066762686 -0.053681612 0.063409314, -0.064446107 -0.056948259 0.063612729, -0.067576945 -0.052108869 0.063203931, -0.066502959 -0.053472713 0.06320411, -0.064195588 -0.056726992 0.063409299, -0.062943861 -0.058112666 0.063409105, -0.0604987 -0.06112577 0.063612565, -0.06394586 -0.056506187 0.063203856, -0.062699169 -0.057886466 0.063203707, -0.060263589 -0.060887963 0.063408956, -0.058831871 -0.062272683 0.063408941, -0.05628106 -0.065030053 0.063612491, -0.060029253 -0.060651138 0.063203469, -0.058603033 -0.062030122 0.063203514, -0.056062147 -0.064777255 0.063408926, -0.055844143 -0.064525217 0.063203469, -0.054445326 -0.066142142 0.063408762, -0.051812202 -0.068643942 0.063612163, -0.054233491 -0.065884903 0.063203305, -0.051610753 -0.068377241 0.063408658, -0.05140993 -0.068111032 0.063203245, -0.049805015 -0.069703355 0.063408643, -0.04711175 -0.071951553 0.063611865, -0.049611151 -0.069432139 0.063202947, -0.046928361 -0.07167162 0.0634083, -0.046746001 -0.071392819 0.063203141, -0.044932336 -0.072939873 0.063408434, -0.042200908 -0.074937478 0.06361188, -0.044757441 -0.072655961 0.063203126, -0.042036787 -0.074646145 0.063408285, -0.041873321 -0.074355543 0.063202828, -0.039850265 -0.075836092 0.063408032, -0.037101641 -0.077588797 0.063611671, -0.039695114 -0.075540841 0.063202694, -0.036957458 -0.077287182 0.063408092, -0.036813542 -0.076986328 0.063202575, -0.034582451 -0.078378573 0.063407958, -0.031836718 -0.079893738 0.063611686, -0.034447819 -0.07807371 0.06320253, -0.031713009 -0.079582989 0.063408017, -0.031589568 -0.079273447 0.063202664, -0.029153258 -0.080555975 0.063407972, -0.026429713 -0.081841633 0.063611373, -0.02903986 -0.0802425 0.063202575, -0.026326835 -0.081523463 0.063408047, -0.0262243 -0.081206337 0.063202426, -0.023588151 -0.08235772 0.063407645, -0.020904273 -0.083424285 0.063611344, -0.023496345 -0.08203721 0.063202336, -0.020823061 -0.083099931 0.063407779, -0.020742163 -0.082776546 0.063202322, -0.017913148 -0.083775401 0.063407779, -0.01528579 -0.08463414 0.063611284, -0.017843306 -0.083449632 0.063202381, -0.015226424 -0.084304988 0.063407749, -0.015167102 -0.083977163 0.063202322, -0.01215452 -0.084802657 0.063407511, -0.0095989406 -0.085466251 0.06361112, -0.012107164 -0.084472612 0.063202232, -0.0095616579 -0.085134 0.063407674, -0.0095244348 -0.084802791 0.063202441, -0.006339252 -0.085434347 0.063407466, -0.0038692802 -0.085916504 0.063611194, -0.0063147545 -0.085101977 0.063202292, -0.0038541853 -0.085582539 0.063407615, -0.0038391054 -0.085249603 0.063202128, -0.00049439073 -0.085667834 0.063407689, 0.0018779188 -0.085983008 0.063611209, -0.00049260259 -0.085334539 0.063202351, 0.0018703341 -0.08564876 0.0634076, 0.0018631965 -0.0853156 0.063202173, 0.005352661 -0.085501909 0.063407615, 0.007616356 -0.085665584 0.063611269, 0.0053318143 -0.085169211 0.063202187, 0.007586807 -0.085332707 0.06340757, 0.0075571835 -0.08500044 0.063202173, 0.011174664 -0.084930077 -0.063417315, 0.013320982 -0.084958598 -0.063620925, 0.0076162964 -0.085658595 -0.063620865, 0.013217553 -0.084298775 -0.063211903, 0.011131138 -0.084599584 -0.063211977, 0.013269141 -0.08462806 -0.063417226, 0.016878694 -0.083642691 -0.063211977, 0.018818691 -0.083227739 -0.063211903, 0.016944677 -0.083969548 -0.063417256, 0.018966019 -0.083878919 -0.063620821, 0.018892393 -0.083552897 -0.063417226, -0.084072694 0.018108726 -0.063614845, 0.022547603 -0.08229588 -0.063211933, 0.02433601 -0.081784964 -0.063211858, 0.022635594 -0.082617149 -0.063417196, 0.024526402 -0.082424998 -0.063620701, 0.024430975 -0.08210437 -0.063416943, 0.028111398 -0.080565348 -0.063211709, 0.029744551 -0.079976901 -0.063211903, 0.028221205 -0.080880031 -0.063416988, 0.029977322 -0.08060275 -0.063620538, 0.02986072 -0.080289155 -0.063416868, 0.033544138 -0.078459024 -0.063211545, 0.035020187 -0.077811465 -0.063211679, 0.033675119 -0.078765482 -0.063416958, 0.035294235 -0.078420237 -0.063620359, 0.03515695 -0.078115404 -0.063416928, 0.038820475 -0.075987235 -0.063211575, 0.040139437 -0.075298592 -0.063211307, 0.038972035 -0.076283976 -0.063416868, 0.040453568 -0.075887904 -0.063620314, 0.040296197 -0.075592726 -0.06341669, 0.043915719 -0.073160663 -0.063211128, 0.044087201 -0.073446512 -0.06341657, 0.04543218 -0.07301639 -0.063620076, 0.048806295 -0.069993451 -0.063211083, 0.048996925 -0.070266709 -0.063416362, 0.050207973 -0.069818795 -0.063619897, 0.053469062 -0.066499367 -0.063210964, 0.053678051 -0.066759095 -0.063416243, 0.054759413 -0.066309348 -0.063619792, 0.057882845 -0.062695488 -0.063210875, 0.05810906 -0.062940344 -0.063416094, 0.059066325 -0.06250371 -0.063619733, 0.062026724 -0.058599189 -0.063210532, 0.062268972 -0.058828175 -0.06341581, 0.063109443 -0.05841881 -0.063619331, 0.065881342 -0.054229736 -0.063210413, 0.066138476 -0.054441541 -0.063415483, 0.066870674 -0.05407314 -0.063619241, 0.069428712 -0.04960753 -0.063209757, 0.069699943 -0.049801245 -0.063415438, 0.070333153 -0.049486041 -0.063618898, 0.072652474 -0.044753969 -0.063209727, 0.072936162 -0.04492867 -0.063414901, 0.073481947 -0.044677779 -0.063618541, 0.075537324 -0.039691404 -0.06320931, 0.075832516 -0.039846569 -0.063414723, 0.076302245 -0.039669797 -0.063618273, 0.078070208 -0.034444094 -0.063209161, 0.078375176 -0.034578681 -0.063414291, 0.078781679 -0.034484759 -0.063618049, 0.080238894 -0.029036134 -0.063208893, 0.080552474 -0.029149398 -0.063413963, 0.080909356 -0.029145837 -0.063617706, -0.083419979 0.017968088 -0.063206255, -0.083745971 0.018038407 -0.0634114, -0.084433734 0.012356222 -0.063206613, -0.084763363 0.012404412 -0.063411787, -0.085094273 0.012452915 -0.063615263, -0.085070029 0.0066891611 -0.063207045, -0.085402399 0.0067151636 -0.0634121, -0.085735768 0.0067413598 -0.063615769, -0.085326716 0.00099204481 -0.063207105, -0.085660055 0.00099588931 -0.063412338, -0.085994303 0.0009996891 -0.063615978, -0.085202113 -0.0047093481 -0.063207403, -0.085534871 -0.0047278851 -0.063412815, -0.085868627 -0.0047461092 -0.063616395, -0.084697038 -0.010389596 -0.063207701, -0.085027993 -0.010430142 -0.063413218, -0.085359812 -0.010470957 -0.063616589, -0.083813682 -0.016023591 -0.063208044, -0.084141105 -0.016086206 -0.063413322, -0.084469736 -0.016149014 -0.063617021, -0.082556024 -0.021585852 -0.063208416, -0.0828785 -0.021670252 -0.06341368, -0.083201975 -0.02175495 -0.063617289, -0.080929756 -0.027051777 -0.063208595, -0.08124575 -0.027157515 -0.063413993, -0.081562996 -0.027263373 -0.06361787, -0.078941911 -0.032396913 -0.063208997, -0.079250336 -0.032523558 -0.06341435, -0.07955949 -0.032650605 -0.063618019, -0.076601431 -0.037597254 -0.063209474, -0.076900735 -0.037744105 -0.063414589, -0.077200979 -0.037891492 -0.063618213, -0.073918954 -0.042629704 -0.063209787, -0.073164478 -0.043912053 -0.063209698, -0.074207708 -0.042796195 -0.063414827, -0.074497387 -0.042963237 -0.063618451, -0.073450238 -0.044083551 -0.063414827, -0.071461156 -0.047843188 -0.063618824, -0.070906371 -0.047471717 -0.063209936, -0.069996879 -0.048802614 -0.063209876, -0.071183205 -0.047657222 -0.063415214, -0.070270196 -0.048993275 -0.063415259, -0.068105668 -0.052509502 -0.063619047, -0.067577004 -0.052101657 -0.06321013, -0.066503033 -0.053465649 -0.063210189, -0.067840919 -0.052305296 -0.063415453, -0.066762775 -0.053674489 -0.063415423, -0.064446196 -0.056941167 -0.063619256, -0.06394586 -0.056499019 -0.063210517, -0.062699184 -0.057879269 -0.063210547, -0.064195514 -0.056719795 -0.063415766, -0.06294404 -0.058105409 -0.063415691, -0.06049858 -0.061118543 -0.063619524, -0.060029075 -0.060643971 -0.063210547, -0.058603063 -0.062023029 -0.063210741, -0.060263529 -0.060881108 -0.063415825, -0.058831841 -0.062265426 -0.063415915, -0.056281149 -0.065022796 -0.063619763, -0.055844024 -0.064518034 -0.063210875, -0.056062207 -0.064770117 -0.063416004, -0.054233626 -0.065877706 -0.063210964, -0.054445356 -0.066135019 -0.063416302, -0.051812187 -0.068636879 -0.063619986, -0.051409721 -0.068104014 -0.063210964, -0.051610693 -0.06836997 -0.063416228, -0.049611062 -0.069425061 -0.063211113, -0.049804941 -0.069696233 -0.063416526, -0.047111616 -0.071944267 -0.06362009, -0.046746045 -0.071385577 -0.063211322, -0.046928644 -0.071664527 -0.063416407, -0.044757485 -0.072648734 -0.063211367, -0.044932306 -0.072932556 -0.06341657, -0.042200878 -0.074930474 -0.063620344, -0.041873425 -0.074348539 -0.063211232, -0.042036965 -0.074638918 -0.063416615, -0.039694965 -0.075533897 -0.063211486, -0.03985025 -0.075828925 -0.06341666, -0.037101761 -0.077581868 -0.063620374, -0.036813647 -0.076979265 -0.063211769, -0.036957473 -0.07727997 -0.063416734, -0.03444767 -0.078066602 -0.06321156, -0.034582317 -0.07837154 -0.063417047, -0.031836748 -0.079886571 -0.063620627, -0.031589568 -0.079266325 -0.063211754, -0.031712845 -0.079575911 -0.063416898, -0.029039621 -0.080235526 -0.063211679, -0.029153198 -0.080548942 -0.063416913, -0.026429579 -0.081834599 -0.063620746, -0.026224256 -0.081199184 -0.063211843, -0.02632685 -0.08151634 -0.063417122, -0.023496345 -0.082030132 -0.063211769, -0.023588091 -0.082350507 -0.063417062, -0.020904332 -0.083417147 -0.063620776, -0.020742089 -0.082769483 -0.063211858, -0.020823032 -0.083092734 -0.063417152, -0.017843351 -0.083442226 -0.063211933, -0.017913058 -0.083768412 -0.063417062, -0.015285745 -0.084627286 -0.063621014, -0.015167207 -0.083970129 -0.063211918, -0.015226483 -0.084297985 -0.063417241, -0.012107208 -0.084465429 -0.063211992, -0.012154549 -0.084795401 -0.063417152, -0.0095989257 -0.085459054 -0.063620999, -0.0095243007 -0.084795579 -0.063211933, -0.0095616281 -0.085126802 -0.063417271, -0.0063147545 -0.085094795 -0.063211948, -0.0063393563 -0.085427225 -0.063417375, -0.0038692057 -0.085909426 -0.063620925, -0.0038392693 -0.085242331 -0.063212097, -0.0038542151 -0.085575417 -0.063417345, -0.00049249828 -0.085327342 -0.063212022, -0.00049450994 -0.085660636 -0.063417375, 0.0018776506 -0.085975856 -0.063620865, 0.0018631965 -0.085308403 -0.063211963, 0.0018704236 -0.085641757 -0.063417464, 0.0053317398 -0.085162073 -0.063211948, 0.0053526014 -0.085494727 -0.063417315, 0.0075571835 -0.084993452 -0.063212007, 0.0075866282 -0.08532542 -0.063417345, -0.063621551 -0.01659283 -0.026764169, -0.061489761 -0.023281261 -0.026764691, -0.059071481 -0.017110065 -0.02431047, -0.06502834 -0.0097150952 -0.026763573, -0.060251728 -0.012326956 -0.024309948, -0.061045215 -0.0074644983 -0.024309665, -0.065693423 -0.0027266741 -0.026763484, -0.061447084 -0.0025542527 -0.024309486, -0.061454266 0.0023723543 -0.024309143, -0.065609872 0.0042929649 -0.026762903, -0.061067417 0.0072838217 -0.024309054, -0.064778373 0.011263505 -0.0267625, -0.060288429 0.012148693 -0.024308592, 0.059100524 -0.024118051 -0.025657788, 0.055223465 -0.027065784 -0.024311006, 0.058105081 -0.023476318 -0.024985686, 0.056748658 -0.037235364 -0.027992278, 0.057636529 -0.023046985 -0.024642229, 0.056515172 -0.033600405 -0.026765138, 0.057212859 -0.022558525 -0.024310738, 0.052610621 -0.039434329 -0.026765361, 0.03004764 -0.060859978 -0.0279935, 0.031538591 -0.057690546 -0.026766598, 0.025207937 -0.060724199 -0.026766703, 0.011759847 -0.064688057 -0.026766971, 0.014998615 -0.066195369 -0.027994037, 0.018589795 -0.063065663 -0.026766628, -0.019607127 -0.064979777 -0.027993783, -0.016104698 -0.063745752 -0.026766732, -0.022809371 -0.061665326 -0.026766807, -0.049836382 -0.046078324 -0.02799274, -0.046313286 -0.046669051 -0.026765779, -0.051025182 -0.041465402 -0.026765376, 0.05977571 -0.027383327 -0.02676475, 0.062583014 -0.024556175 -0.027618259, -0.055155501 -0.03578876 -0.026765302, -0.059221953 -0.033161283 -0.027991995, -0.058656871 -0.029704332 -0.026764855, 0.061382473 -0.024667129 -0.026997745, 0.060202867 -0.024518624 -0.02633442, -0.067860216 0.00142847 -0.027989969, -0.062013626 0.01423043 -0.025535479, 0.052879557 -0.031399161 -0.024311304, 0.050196439 -0.035531163 -0.024311572, -0.066156015 0.01518096 -0.027989253, 0.047191337 -0.039435118 -0.024311751, 0.048106164 -0.044818774 -0.026765704, 0.065233812 -0.0233244 -0.028801784, 0.063892499 -0.024133876 -0.028236255, 0.04388319 -0.043086037 -0.024311945, 0.043053359 -0.04969202 -0.026766017, 0.040293381 -0.04646033 -0.024311975, 0.036444902 -0.049536452 -0.024312258, 0.037509874 -0.053999215 -0.026766241, 0.032362923 -0.052294642 -0.024312347, 0.028072983 -0.054717392 -0.024312645, 0.023602948 -0.05678907 -0.02431266, 0.018981516 -0.058496132 -0.024312675, 0.014238149 -0.05982779 -0.024312794, 0.0094035119 -0.060775355 -0.024312943, 0.0047958493 -0.065573201 -0.026766792, 0.0045084208 -0.061333045 -0.024312913, -0.00041535497 -0.06149736 -0.024312764, -0.0022229254 -0.065710783 -0.026767045, -0.005336687 -0.06126669 -0.024312913, -0.0092163384 -0.065099269 -0.026766941, -0.010223836 -0.060642704 -0.024312854, -0.015045226 -0.059629813 -0.024312869, -0.019770041 -0.058234274 -0.024312586, -0.024368122 -0.056464925 -0.024312571, -0.029254109 -0.058881879 -0.026766509, -0.028809741 -0.054333314 -0.024312407, -0.035365313 -0.055427343 -0.02676639, -0.033066541 -0.051852822 -0.024312332, -0.037111089 -0.049039662 -0.024312168, -0.041073382 -0.051340863 -0.026766241, -0.040917501 -0.045911685 -0.024311826, -0.044461265 -0.042489111 -0.02431187, -0.047719777 -0.038793921 -0.024311796, -0.05067198 -0.034849718 -0.024311483, -0.053298905 -0.030681893 -0.024311081, -0.055583894 -0.026317284 -0.024310917, -0.057512447 -0.021783531 -0.024310827, -0.046860814 0.05708158 -0.034606144, -0.047990799 0.056134835 -0.034606099, -0.048087582 0.056248039 -0.036141798, 0.060161278 0.040805936 -0.031761572, 0.056941286 0.045190841 -0.031761259, 0.060754374 0.041208327 -0.033128023, -0.041198969 0.058717519 -0.030556843, -0.04052192 0.057752535 -0.029561028, -0.042506993 0.057777643 -0.030556872, -0.038176164 0.0607263 -0.030556738, 0.057502657 0.045636356 -0.033127725, 0.059361994 0.040263698 -0.03055805, 0.056184843 0.04459022 -0.030557677, -0.043765306 0.059488118 -0.034605965, -0.046581045 0.056740612 -0.033127218, -0.043503866 0.059132978 -0.03312692, -0.04770422 0.055799574 -0.033127144, 0.057848096 0.045910537 -0.034606531, 0.054342553 0.050010741 -0.034606457, 0.057964563 0.046003282 -0.036142528, 0.054452166 0.050111696 -0.036142468, -0.046126351 0.056186661 -0.031760499, 0.055261433 0.043857455 -0.029561758, 0.05838643 0.039602011 -0.029562026, -0.043079168 0.058555558 -0.031760529, -0.047238424 0.055254728 -0.031760633, 0.054018229 0.049712077 -0.033127651, -0.045513496 0.055440187 -0.030557141, 0.053490907 0.049226701 -0.031761229, -0.051035613 0.053381354 -0.034606144, -0.052064881 0.052587777 -0.036142036, 0.052780136 0.048572585 -0.030557483, -0.046610966 0.054520667 -0.030557171, 0.050547138 0.053843975 -0.034606174, -0.044765472 0.054529086 -0.029561117, 0.050649121 0.053952679 -0.036142066, 0.051912889 0.04777433 -0.029561535, -0.050730869 0.053062782 -0.033127353, -0.050235733 0.052544639 -0.03176102, 0.050245374 0.053522408 -0.033127323, 0.049754992 0.053000063 -0.031760901, -0.049568281 0.051846534 -0.03055723, -0.054919302 0.049376875 -0.034606472, 0.049093962 0.052295849 -0.030557141, -0.055764407 0.048647046 -0.036142319, -0.04875356 0.050994381 -0.029561356, -0.054591432 0.049082056 -0.033127785, 0.048287094 0.051436275 -0.029561311, -0.054058537 0.048602805 -0.031761229, -0.053340361 0.047956988 -0.030557379, -0.05848977 0.045090571 -0.03460671, -0.059166655 0.044446841 -0.036142766, -0.052463755 0.047168866 -0.029561862, -0.058140367 0.044821188 -0.033127785, -0.057572737 0.044383615 -0.031761333, -0.05680804 0.043793932 -0.030557647, -0.061726302 0.04054676 -0.034606993, -0.062252954 0.040009394 -0.03614302, -0.055874214 0.043074071 -0.029561758, -0.061357602 0.040304542 -0.033128217, -0.060758635 0.039911225 -0.031761616, -0.059951469 0.039380819 -0.030558035, -0.064610481 0.035771862 -0.034607366, -0.06500715 0.035358414 -0.036143228, -0.058966294 0.038733691 -0.02956222, 0.03594847 0.060704678 -0.029560938, -0.06422475 0.035558224 -0.033128247, -0.063597754 0.035211101 -0.031761825, -0.062752932 0.034743249 -0.030558303, -0.067126274 0.030792743 -0.034607425, 0.032892242 0.066123933 -0.034605503, 0.027977943 0.068348244 -0.034605429, 0.032958478 0.066257179 -0.03614147, -0.067414626 0.030518949 -0.036143497, 0.02803418 0.068486348 -0.036141321, -0.061721563 0.034172073 -0.029562339, 0.031421408 0.063167036 -0.029560864, 0.03194645 0.06422247 -0.03055644, -0.066725597 0.030608729 -0.033128664, 0.027810767 0.067940414 -0.033126563, 0.032695726 0.065728948 -0.033126622, -0.066073969 0.030310035 -0.031761959, 0.027539328 0.067276955 -0.031760111, 0.032376528 0.065087333 -0.031760097, 0.02717337 0.066383079 -0.03055656, -0.065196261 0.029907152 -0.030558407, -0.069259077 0.025638014 -0.034607828, 0.02291429 0.070208445 -0.034605265, -0.069462568 0.025516629 -0.036143601, 0.022960365 0.070349991 -0.036141217, 0.021458954 0.070666596 -0.03460516, -0.064124689 0.029415742 -0.029562488, 0.017764151 0.071838215 -0.036141008, 0.022777468 0.069789022 -0.033126473, -0.068845421 0.02548483 -0.033128813, 0.021330655 0.070244789 -0.033126324, -0.068173379 0.025236174 -0.031762287, 0.022555143 0.069107622 -0.031759962, -0.067267656 0.024900585 -0.030558705, 0.02112256 0.069559142 -0.031759962, -0.066162139 0.024491459 -0.029563114, 0.022255421 0.068189606 -0.030556589, 0.046461403 0.053570047 -0.029826149, 0.017728508 0.071693793 -0.03460519, 0.044403851 0.054823771 -0.029561132, 0.040283516 0.057918772 -0.029560998, 0.042356431 0.056871608 -0.02982612, 0.020841941 0.068634823 -0.030556306, 0.016063675 0.072084919 -0.034605071, 0.012473121 0.072943494 -0.036141053, 0.017622501 0.071265534 -0.03312625, 0.038017556 0.059859186 -0.029825926, 0.020499378 0.067506939 -0.029560626, 0.033468693 0.062516332 -0.029825583, 0.015967712 0.071654633 -0.033126235, 0.048158109 0.053366542 -0.030719623, 0.017450422 0.070569843 -0.031759933, 0.01581189 0.070955023 -0.031760082, 0.047391236 0.054433376 -0.031051412, 0.046176985 0.055089623 -0.030719548, 0.017218709 0.069632098 -0.030556321, 0.045753568 0.056490421 -0.031760648, 0.04514578 0.05573988 -0.030557096, 0.044098824 0.056766883 -0.030719355, 0.012447968 0.072796464 -0.034605101, 0.043267593 0.057765484 -0.031051397, 0.015601844 0.070012137 -0.030556217, 0.012373582 0.072361857 -0.033126324, 0.040956616 0.058886707 -0.030556738, 0.04199639 0.058339745 -0.03071934, 0.041508034 0.059679657 -0.031760618, 0.039800256 0.059859306 -0.03071928, 0.010576755 0.073091894 -0.034605086, 0.007115379 0.073659331 -0.036140904, 0.015345424 0.068861514 -0.029560447, 0.038910493 0.060785785 -0.031051144, 0.037041083 0.062550306 -0.031760424, 0.037587747 0.061273023 -0.030719191, 0.036549121 0.061719164 -0.030556679, 0.012252718 0.071655348 -0.031759799, 0.010513663 0.072655246 -0.033126086, 0.035285786 0.062627003 -0.030719191, 0.012089953 0.070703313 -0.030556217, 0.034343362 0.063478112 -0.031050861, 0.032974944 0.063873872 -0.030718967, 0.0071009248 0.073510915 -0.034604982, 0.010410935 0.07194601 -0.031759858, 0.04887113 0.054053605 -0.032042384, 0.0070587844 0.073071972 -0.033126041, 0.048014924 0.055079207 -0.032394633, 0.010272503 0.070990145 -0.030556127, 0.04686445 0.055802509 -0.032042176, 0.046204463 0.057047486 -0.033127323, 0.005029574 0.073681831 -0.03460519, 0.044783384 0.057486132 -0.032042205, 0.0017197728 0.073982105 -0.036140829, 0.0069897175 0.072358713 -0.031759918, 0.043858364 0.058443308 -0.032394364, 0.010103792 0.069823414 -0.029560238, 0.042653933 0.059083417 -0.032042071, 0.0049993545 0.073241636 -0.033126324, 0.041917264 0.060268059 -0.033126786, 0.0068967789 0.07139723 -0.030555978, 0.040455192 0.060610145 -0.032041863, 0.0017163306 0.073833182 -0.034605116, 0.039466903 0.061494291 -0.032394275, 0.038214594 0.062047303 -0.032041773, 0.0374064 0.063166857 -0.033126801, 0.0049506277 0.072526842 -0.031759769, 0.035910025 0.06340903 -0.032041907, 0.0017061383 0.073392332 -0.03312628, 0.071567848 -0.018219575 -0.034610167, 0.072436988 -0.015126541 -0.03614603, 0.034864023 0.064215928 -0.032394096, 0.0048848242 0.07156314 -0.030556157, 0.071140587 -0.018110931 -0.033131406, 0.0335702 0.064678237 -0.032041818, -0.00054645538 0.073851094 -0.034605071, -0.0036851317 0.073910356 -0.036141038, 0.048417553 0.055517659 -0.033844545, 0.0016894937 0.072675779 -0.031759828, 0.072291344 -0.015096501 -0.034609988, 0.046575755 0.05750604 -0.036141872, 0.046482295 0.057390139 -0.034606084, 0.070446044 -0.017934129 -0.031764835, 0.0048046112 0.070386916 -0.029560432, 0.044233322 0.058905646 -0.033844233, 0.04225418 0.060752377 -0.036141723, -0.00054319203 0.073410138 -0.033126056, 0.071859568 -0.015006274 -0.033131078, 0.04216902 0.060630113 -0.03460592, 0.039812684 0.061979249 -0.033844173, 0.0016670972 0.071710125 -0.030556127, 0.069510326 -0.017695963 -0.030561328, 0.037631139 0.063546315 -0.034605592, 0.037706897 0.063674718 -0.036141545, 0.035179481 0.064721659 -0.033844009, -0.0036775917 0.073761567 -0.034605131, 0.072912842 -0.011733234 -0.034610003, 0.07334815 -0.0097986162 -0.036145672, -0.00053788722 0.072693363 -0.031759635, 0.07115823 -0.014859691 -0.031764552, 0.068367824 -0.017405257 -0.029565364, -0.003655687 0.073321268 -0.033126205, 0.07247749 -0.011663184 -0.033130944, -0.00053079426 0.071727514 -0.030556053, 0.070212752 -0.014662504 -0.03056109, -0.0061194748 0.073599219 -0.034604982, -0.0090701282 0.073444143 -0.036141038, 0.073200539 -0.0097791106 -0.03460972, -0.0036199093 0.072605222 -0.031759784, 0.071770042 -0.011549532 -0.031764477, -0.00052201748 0.070548624 -0.029560447, 0.072763413 -0.0097206682 -0.033130944, -0.0060827136 0.073159561 -0.033126265, -0.0035717338 0.071640626 -0.030556276, 0.070816532 -0.01139605 -0.030560672, 0.072053134 -0.009625867 -0.031764343, -0.0090516955 0.073296234 -0.034605131, -0.0060234368 0.072445437 -0.031759799, 0.073590592 -0.0061960518 -0.034609646, 0.073867798 -0.0044185668 -0.036145151, -0.0089978576 0.072858751 -0.03312628, 0.069652572 -0.011208832 -0.029564977, 0.071095973 -0.0094981492 -0.030560791, -0.0059432983 0.071482763 -0.030556202, 0.073151261 -0.0061591268 -0.033130839, -0.011657208 0.072927251 -0.034605101, -0.014406756 0.072586238 -0.036140934, -0.0089100301 0.072147191 -0.031759694, 0.073719278 -0.0044097602 -0.034609348, -0.0058458 0.070308089 -0.029560372, -0.011587694 0.072491944 -0.033126235, 0.072437033 -0.0060989559 -0.031764224, 0.073279068 -0.0043834597 -0.033130631, -0.0087915659 0.071188778 -0.030556291, 0.071474761 -0.0060181022 -0.030560508, -0.014377967 0.072440132 -0.034604937, 0.072563633 -0.0043406188 -0.031764135, -0.011474654 0.071784168 -0.031759784, 0.073848516 -0.00062349439 -0.034609288, 0.073993474 0.00098533928 -0.036145121, -0.014292017 0.072007582 -0.03312628, 0.070300028 -0.0059192479 -0.02956453, 0.071599737 -0.0042831004 -0.030560523, -0.011322081 0.070830375 -0.030556232, -0.017128825 0.071839347 -0.034605056, 0.073844597 0.00098317862 -0.034609213, -0.019666761 0.071340978 -0.036141068, -0.014152572 0.07130453 -0.031759739, 0.073407561 -0.0006197691 -0.033130318, -0.011135951 0.069666177 -0.029560506, 0.073403791 0.00097727776 -0.03313008, -0.017026335 0.071410358 -0.033126414, -0.013964608 0.07035701 -0.030556187, 0.072690949 -0.00061392784 -0.031763837, 0.072687164 0.00096786022 -0.031763807, -0.019627005 0.071197316 -0.034605131, 0.071725219 -0.0006057322 -0.030560195, -0.016860202 0.070713148 -0.031759813, 0.073685065 0.0049527287 -0.03460899, 0.07372427 0.0063837767 -0.036144763, -0.019510016 0.07077226 -0.033126324, 0.071721524 0.0009547919 -0.030560151, -0.016636148 0.069773585 -0.030556276, 0.073575929 0.0063709021 -0.034608975, 0.070546448 -0.00059591234 -0.029564217, -0.022502378 0.070341393 -0.034605265, -0.024821669 0.069714963 -0.036141261, 0.073245108 0.0049229413 -0.033130109, -0.01931943 0.070081219 -0.031759784, 0.073136672 0.0063328147 -0.033129916, -0.016362727 0.06862694 -0.029560551, -0.022367999 0.069921374 -0.033126548, 0.072530031 0.0048750043 -0.031763554, -0.019062787 0.069150135 -0.030556336, 0.072422773 0.006270811 -0.031763524, 0.071566328 0.0048100501 -0.030559883, -0.024771854 0.069574624 -0.03460525, -0.022149861 0.069238812 -0.031759873, 0.073101103 0.010500461 -0.034608692, 0.073061824 0.011748299 -0.036144555, 0.07146053 0.0061875731 -0.030559808, -0.024623901 0.069159254 -0.033126503, 0.070390359 0.0047310293 -0.029564023, -0.021855354 0.068318829 -0.030556411, 0.072664693 0.010437757 -0.033129677, -0.027747676 0.0684423 -0.034605473, -0.02984412 0.067717239 -0.036141425, 0.071955353 0.010335878 -0.031763181, -0.0243835 0.068484083 -0.031760246, -0.021496192 0.067196056 -0.029560417, 0.070999295 0.010198429 -0.030559659, 0.072100058 0.015988499 -0.034608349, -0.027582034 0.068033591 -0.033126399, 0.072009355 0.017050222 -0.036144271, -0.024059445 0.067573979 -0.030556321, 0.069832563 0.01003094 -0.029563829, 0.071669623 0.015892893 -0.033129588, -0.029784128 0.067580894 -0.034605533, 0.070969895 0.015737906 -0.031762898, -0.027312681 0.067369178 -0.031760082, -0.029606313 0.06717734 -0.033126235, 0.070027098 0.015528768 -0.030559197, -0.026949912 0.066474244 -0.030556396, 0.070687786 0.021385267 -0.034607992, 0.070572823 0.022261128 -0.036143929, -0.032834455 0.066152483 -0.034605503, -0.034707382 0.065358087 -0.036141425, 0.068876088 0.015273526 -0.029563501, -0.029317334 0.06652151 -0.031760022, -0.026506945 0.065381855 -0.029560819, 0.070265561 0.021257609 -0.03312923, -0.032638565 0.065757513 -0.033126682, 0.069579661 0.021050066 -0.0317626, -0.028927803 0.065637589 -0.03055656, 0.068655282 0.020770222 -0.030559108, -0.034637481 0.06522654 -0.034605637, 0.068871886 0.026660055 -0.034607857, 0.068759769 0.027353197 -0.036143512, -0.032319874 0.065115482 -0.031760082, 0.067526981 0.020428881 -0.029563144, -0.034430861 0.064837053 -0.033126518, 0.068460733 0.026500806 -0.033128664, -0.031890616 0.064250275 -0.030556425, 0.067792282 0.026242107 -0.031762511, -0.034094557 0.064204022 -0.031760216, -0.03773421 0.063485324 -0.034605607, 0.066891745 0.025893345 -0.030558601, -0.039385453 0.062650308 -0.036141545, 0.066663116 0.031782672 -0.034607351, 0.066579893 0.032299429 -0.036143288, -0.031366438 0.063194364 -0.029560566, -0.033641741 0.063350976 -0.030556604, 0.065792397 0.025467932 -0.029563025, -0.037508905 0.063106284 -0.033126801, 0.066265047 0.03159292 -0.033128425, -0.039306298 0.06252411 -0.034605682, 0.065618202 0.031284437 -0.031762138, -0.037142619 0.062490121 -0.031760439, 0.064746559 0.030868679 -0.030558527, -0.039071605 0.062150806 -0.03312695, 0.064074039 0.036724001 -0.034607306, 0.064044774 0.03707324 -0.036142945, -0.036649421 0.061659992 -0.030556783, 0.063682407 0.03036131 -0.029562578, -0.038690224 0.061543927 -0.031760275, 0.063691452 0.036504656 -0.033128306, -0.042418391 0.060455874 -0.034606025, -0.043853536 0.059608206 -0.036141858, 0.063069582 0.036148354 -0.031761765, -0.036047027 0.060646564 -0.029560924, 0.062231764 0.035668075 -0.030558214, 0.061119288 0.041455865 -0.034606844, 0.061167955 0.041649356 -0.036142826, -0.042165309 0.060094893 -0.033126846, 0.061209142 0.035081729 -0.029562354, -0.04175368 0.05950813 -0.031760424, 0.05225262 -0.025609896 -0.020636544, 0.050034881 -0.029710159 -0.02063702, 0.049590617 -0.029446363 -0.019046217, -0.044059515 -0.042105198 -0.023959771, -0.045490488 -0.039346918 -0.023328662, -0.043483183 -0.041554362 -0.023328766, 0.053003564 -0.025977835 -0.022085175, -0.038716286 -0.043442115 -0.020637602, -0.040355787 -0.041203305 -0.019046962, -0.038372487 -0.04305619 -0.019046918, 0.050753981 -0.030137092 -0.022085458, 0.054008409 -0.026470348 -0.023327887, 0.051716179 -0.030708551 -0.02332826, -0.040717542 -0.041572452 -0.020637482, -0.042085722 -0.042969137 -0.023328796, -0.04267405 -0.040781379 -0.02208589, -0.041302651 -0.042169735 -0.022086009, 0.053654268 -0.02115576 -0.019045651, 0.051788554 -0.025382444 -0.019046009, -0.03681545 -0.044394895 -0.019047037, 0.054724455 -0.02682142 -0.023958921, 0.052401677 -0.031115532 -0.02395913, -0.039272785 -0.044066399 -0.022086218, -0.037145361 -0.044792816 -0.02063784, 0.05413492 -0.021345094 -0.02063635, -0.040017188 -0.044901624 -0.0233289, 0.05491291 -0.021651745 -0.022084996, -0.034802824 -0.045989782 -0.019047156, 0.056539521 -0.021372378 -0.023582637, 0.055953979 -0.022062287 -0.023327783, -0.037679002 -0.045436472 -0.022086293, 0.056836694 -0.02199398 -0.023958683, 0.05669567 -0.022354737 -0.023958445, -0.040547669 -0.045496926 -0.02395983, -0.035114735 -0.046401724 -0.020637885, -0.038393363 -0.046297655 -0.023329064, -0.033023611 -0.047283605 -0.019047216, -0.035619527 -0.047068492 -0.022086233, -0.033319458 -0.047707245 -0.020637989, -0.036294639 -0.047960788 -0.023329124, -0.031009912 -0.048627794 -0.019047245, -0.033798233 -0.048392788 -0.022086427, -0.036775723 -0.048596516 -0.023960128, -0.03128776 -0.049063578 -0.020637929, -0.034438789 -0.049310058 -0.023329109, -0.02900593 -0.049849167 -0.01904723, -0.031737342 -0.049768671 -0.022086397, -0.029265761 -0.05029577 -0.020637989, -0.032339096 -0.050712064 -0.023329332, -0.027017966 -0.050953895 -0.019047469, -0.02968654 -0.051018521 -0.02208665, -0.032767788 -0.051384181 -0.023960277, -0.027260035 -0.051410541 -0.020638034, -0.030249283 -0.051985547 -0.023329437, -0.024790183 -0.052074194 -0.019047588, -0.027651742 -0.052149355 -0.022086427, -0.025012404 -0.052540645 -0.020638213, -0.028175965 -0.053137794 -0.023329362, -0.022852451 -0.052953064 -0.019047514, -0.028549522 -0.053842425 -0.023960456, -0.025371864 -0.053295627 -0.022086605, -0.023057386 -0.053427577 -0.020638049, -0.025852859 -0.054306 -0.023329481, -0.020405233 -0.053943425 -0.019047573, -0.023388624 -0.0541953 -0.022086695, -0.020588115 -0.054426804 -0.020638227, -0.023831978 -0.05522269 -0.023329481, -0.018540457 -0.054612458 -0.019047722, -0.024147943 -0.055954739 -0.023960471, -0.020883918 -0.055208832 -0.022086933, -0.018706724 -0.055101678 -0.020638317, -0.021279886 -0.05625546 -0.02332963, -0.015880808 -0.0554443 -0.019047827, -0.018975392 -0.055893525 -0.022086859, -0.016023174 -0.055940926 -0.020638227, -0.019335151 -0.056953013 -0.023329556, -0.014109552 -0.055921212 -0.019047752, -0.019591615 -0.057708025 -0.023960561, -0.016253248 -0.056745023 -0.022086918, -0.014236003 -0.056422353 -0.020638198, -0.016561508 -0.057820529 -0.023329794, -0.011247873 -0.056566298 -0.019047618, -0.014440551 -0.057232976 -0.022087023, -0.011348844 -0.057073116 -0.020638287, -0.014714196 -0.058318064 -0.023329601, -0.0095879138 -0.056871116 -0.019047692, -0.014909431 -0.059091046 -0.02396062, -0.011511758 -0.057893172 -0.022086903, -0.0096736699 -0.05738087 -0.020638436, -0.011730134 -0.058990702 -0.023329675, -0.0098129213 -0.058205336 -0.022086948, -0.0065381527 -0.057301939 -0.019047782, -0.0099989772 -0.059308693 -0.02332975, -0.0065967888 -0.057815313 -0.020638257, -0.056538627 0.011392847 -0.019043744, -0.0050048679 -0.057456195 -0.019047722, -0.057045311 0.011494964 -0.020634636, -0.010131434 -0.060094833 -0.023960888, -0.0066917241 -0.058646128 -0.022086978, -0.057864919 0.011660084 -0.022082955, -0.0050498098 -0.057970926 -0.020638421, -0.058962137 0.011881322 -0.023325667, -0.0068185329 -0.059757859 -0.023329794, -0.057269201 0.0068307817 -0.019044086, -0.0051223338 -0.05880408 -0.022087142, -0.059743777 0.012038931 -0.023956597, -0.057782188 0.006891951 -0.020634949, -0.0017839819 -0.057646111 -0.019047782, -0.0052192807 -0.059918806 -0.023329675, -0.058612734 0.0069909543 -0.022083238, -0.00038975477 -0.057672396 -0.019047752, -0.059723794 0.0071237087 -0.023325995, -0.0017998219 -0.058162779 -0.020638466, -0.0052885264 -0.060712978 -0.023960873, -0.057632044 0.0022245646 -0.01904428, -0.00039298832 -0.058189154 -0.020638376, -0.060515672 0.0072181821 -0.023957178, -0.001825735 -0.058998361 -0.022086918, -0.00039871037 -0.059025332 -0.022086903, -0.058148444 0.0022447109 -0.020635068, -0.058984056 0.0022769719 -0.022083595, -0.0018602461 -0.060116798 -0.023329854, -0.060102344 0.0023201555 -0.023326233, -0.057625085 -0.0023954958 -0.019044682, 0.0029827207 -0.057596654 -0.019047797, -0.00040636957 -0.060144141 -0.023329884, -0.060899064 0.0023510456 -0.023957387, 0.0042280704 -0.057518527 -0.019047707, 0.0030094534 -0.058112532 -0.020638227, -0.058141455 -0.002416864 -0.020635307, -0.0004118681 -0.060941577 -0.023960844, -0.058976963 -0.002451703 -0.022083715, 0.0042658448 -0.058033824 -0.020638645, -0.060095087 -0.0024980009 -0.023326531, -0.057248414 -0.0070004016 -0.019045085, 0.003052637 -0.058947533 -0.022087067, 0.0043271929 -0.058867797 -0.022087082, -0.060891673 -0.0025310367 -0.023957685, 0.003110677 -0.060065031 -0.02332969, -0.057761207 -0.0070632696 -0.020635664, 0.0077290088 -0.057153568 -0.019047678, -0.058591276 -0.0071645677 -0.022083938, 0.0031518191 -0.060861379 -0.023960695, -0.059702203 -0.0073004514 -0.023326769, 0.0044092834 -0.05998382 -0.023329645, 0.0077981949 -0.057665497 -0.020638317, -0.056504413 -0.011560276 -0.019045159, -0.060493633 -0.0073970854 -0.023957849, 0.0044676363 -0.060778975 -0.023960859, 0.0079102963 -0.058494344 -0.022086859, -0.05701068 -0.01166375 -0.020635739, 0.0080601722 -0.05960311 -0.023329824, -0.057829648 -0.011831433 -0.022084326, -0.058926135 -0.012055784 -0.023327202, 0.012422428 -0.056320056 -0.019047663, -0.055397362 -0.016046211 -0.019045547, 0.0081671327 -0.060393259 -0.023960799, 0.01253362 -0.056824699 -0.020638511, -0.059707269 -0.012215689 -0.023958176, -0.055893853 -0.016189814 -0.020636067, 0.012713656 -0.057641193 -0.022086799, 0.012954772 -0.058733925 -0.02332975, -0.056697011 -0.016422436 -0.022084668, 0.01703079 -0.055101857 -0.019047678, -0.057771951 -0.016733751 -0.023327231, 0.013126507 -0.059512615 -0.023960829, -0.053935096 -0.020428881 -0.019045636, 0.017183393 -0.055595547 -0.020638213, -0.0585379 -0.01695551 -0.023958296, 0.01743035 -0.056394458 -0.022086903, -0.053508386 -0.021522015 -0.019045606, 0.017760769 -0.057463437 -0.02332975, -0.054418445 -0.020612001 -0.02063629, 0.021523029 -0.053507224 -0.019047588, -0.05398789 -0.021714821 -0.020636499, 0.017996252 -0.058225214 -0.023960799, -0.055200502 -0.020908147 -0.022084847, 0.021715894 -0.053986549 -0.020638198, -0.054763883 -0.022026643 -0.022084892, 0.022027895 -0.054762483 -0.022086769, -0.05624713 -0.02130428 -0.023327604, -0.052126929 -0.02468051 -0.019045964, 0.02244556 -0.055800572 -0.023329511, 0.025868297 -0.051547155 -0.019047469, -0.056992844 -0.021586806 -0.023958623, -0.055802047 -0.022444233 -0.023327634, 0.022743151 -0.056540295 -0.023960531, 0.02609998 -0.052008957 -0.020638198, -0.051548362 -0.025867015 -0.019046068, 0.026474953 -0.052756354 -0.02208665, -0.052593976 -0.024901569 -0.020636588, -0.05654186 -0.02274169 -0.023958698, 0.026976883 -0.053756446 -0.023329347, -0.052010179 -0.026098803 -0.020636648, 0.030036658 -0.049234807 -0.01904732, -0.053349733 -0.025259435 -0.022085294, 0.02733469 -0.054469034 -0.023960426, -0.052757636 -0.026473865 -0.022085056, 0.030305728 -0.049675941 -0.020638034, -0.054361075 -0.025738209 -0.023327827, 0.030741379 -0.050389767 -0.022086561, -0.049984008 -0.02877374 -0.019046336, 0.031324118 -0.051345095 -0.023329288, -0.055081829 -0.026079521 -0.02395907, 0.034000024 -0.046586275 -0.01904732, -0.053757936 -0.026975632 -0.023328021, 0.031739324 -0.052025586 -0.023960367, -0.049236178 -0.03003557 -0.019046262, 0.034304604 -0.047003672 -0.02063784, -0.050432086 -0.029031649 -0.020636752, 0.034797624 -0.04767926 -0.022086352, -0.049677193 -0.0303047 -0.020636916, 0.035457313 -0.048582926 -0.023329109, -0.051156625 -0.029448733 -0.022085488, 0.037730858 -0.043619365 -0.019047052, -0.050391033 -0.030740216 -0.022085369, 0.03592743 -0.049227118 -0.023960143, -0.052126482 -0.030006841 -0.023328185, 0.038069099 -0.044010401 -0.020637736, -0.047520369 -0.032682359 -0.01904653, 0.038616195 -0.044642687 -0.022086114, -0.052817523 -0.030404583 -0.023958951, -0.051346466 -0.031322762 -0.023328274, 0.039348304 -0.045488894 -0.023329169, 0.041153535 -0.040406317 -0.019047022, -0.04794623 -0.032975167 -0.020637095, 0.039869905 -0.046091914 -0.023960069, -0.046587527 -0.033998758 -0.019046575, 0.041522369 -0.040768489 -0.020637304, -0.0486352 -0.033448964 -0.022085488, 0.042119086 -0.041354239 -0.022086054, -0.047004879 -0.034303471 -0.02063714, 0.042917654 -0.04213807 -0.023328751, -0.049557075 -0.034083068 -0.023328319, 0.044256017 -0.036982387 -0.019046649, -0.047680467 -0.034796432 -0.022085682, -0.044751555 -0.03638123 -0.019046485, 0.043486521 -0.042696729 -0.023959771, -0.050214246 -0.034534872 -0.023959398, 0.044652551 -0.037313953 -0.020637199, -0.048584297 -0.035456017 -0.023328379, 0.045294255 -0.037850067 -0.02208595, -0.04515259 -0.036707327 -0.020637229, 0.046153069 -0.038567543 -0.023328513, -0.043620497 -0.037729859 -0.01904659, 0.047074303 -0.033321172 -0.0190465, -0.045801476 -0.037234664 -0.02208589, 0.046764791 -0.039078861 -0.023959622, -0.044011563 -0.038067937 -0.020637318, 0.047496274 -0.03361997 -0.02063714, -0.046669871 -0.037940457 -0.023328602, -0.041695893 -0.039846659 -0.019046947, 0.048178673 -0.034102961 -0.022085533, 0.04909198 -0.034749493 -0.023328394, -0.044643924 -0.038614973 -0.02208595, -0.047288612 -0.038443431 -0.023959756, -0.042069361 -0.040203616 -0.020637468, 0.049742877 -0.035210133 -0.023959339, -0.059166595 0.044442818 0.036147535, -0.062253088 0.040005282 0.036147252, 0.037706882 0.063670576 0.036148608, 0.032958478 0.066253245 0.036148846, -0.06500721 0.035354301 0.036146924, 0.02803418 0.068482161 0.036149055, -0.067414835 0.030514985 0.036146909, 0.022960544 0.070345968 0.036148965, 0.072436959 -0.015130699 0.036144093, -0.069462419 0.025512412 0.036146641, 0.017764211 0.071834192 0.036149025, 0.07334812 -0.0098027587 0.036144286, 0.012473047 0.072939366 0.036149204, 0.073867813 -0.0044224411 0.036144912, 0.0071153343 0.073655143 0.036149055, 0.073993444 0.00098125637 0.036145285, 0.0017198324 0.073978215 0.036149234, 0.073724195 0.0063797683 0.036145449, -0.003684938 0.073906258 0.036149263, 0.073061869 0.011744425 0.036145687, -0.0090702176 0.073440194 0.036149174, 0.072009489 0.017046094 0.036146075, -0.01440683 0.072582215 0.036149308, 0.070572868 0.02225703 0.036146343, -0.019666672 0.07133694 0.036149114, 0.068759784 0.027349174 0.036146641, -0.024821758 0.069711074 0.036148921, 0.066579908 0.032295391 0.036146909, -0.02984415 0.067713141 0.03614895, 0.064044729 0.037069261 0.036147147, -0.034707502 0.065354124 0.036148578, 0.06116797 0.041645229 0.036147594, -0.039385527 0.062646165 0.036148429, 0.057964534 0.045999169 0.036147505, -0.043853372 0.0596039 0.036148429, 0.054452062 0.050107658 0.036147803, -0.048087493 0.056244016 0.03614819, 0.050649107 0.053948715 0.03614828, -0.052064672 0.052583635 0.036147982, 0.046575785 0.057501853 0.036148548, -0.055764407 0.048643008 0.036147773, 0.042254061 0.060748309 0.036148399, 0.020343155 0.053780794 0.0065028667, 0.015832692 0.05527699 0.0065028071, 0.01121369 0.056395754 0.0065030754, 0.0065182447 0.057129279 0.0065029562, 0.0017784238 0.057472318 0.0065030456, 0.056395993 -0.011214092 0.0064993054, -0.0029737055 0.057422906 0.0065030456, 0.057129338 -0.0065186322 0.0064995885, -0.0077057183 0.056981161 0.0065031648, 0.057472467 -0.0017785877 0.0064999163, -0.012384787 0.056150168 0.0065031052, 0.057422981 0.0029734373 0.0065000951, -0.016979292 0.054935679 0.006502986, -0.021457955 0.053345948 0.0065030158, 0.05698128 0.0077053308 0.0065002441, -0.025789827 0.051391706 0.0065026432, 0.056150436 0.012384444 0.006500423, -0.029945731 0.049086422 0.0065025538, 0.054935887 0.016979024 0.0065008998, -0.033896983 0.046445921 0.0065024346, 0.053346097 0.021457598 0.006501019, -0.037616685 0.043488026 0.0065023005, 0.051391959 0.025789663 0.0065012574, -0.041079581 0.040233195 0.0065021515, 0.049086735 0.029945433 0.006501615, -0.044261709 0.036703631 0.0065018237, 0.046446294 0.0338967 0.0065015852, -0.047141597 0.032923132 0.0065016001, 0.043488219 0.037616298 0.0065020323, -0.049699217 0.02891764 0.0065014511, 0.040233508 0.041079029 0.0065021813, -0.051917493 0.024714738 0.0065013319, -0.053781047 0.020343065 0.0065009743, 0.03670378 0.044261307 0.0065023601, 0.032923296 0.047141045 0.0065024495, 0.028917938 0.04969877 0.0065025091, 0.02471514 0.051917091 0.0065027773, 0.015832692 0.055277735 -0.0064969361, 0.01121372 0.056396574 -0.0064969957, 0.0065182745 0.057129696 -0.0064969361, 0.001778394 0.057473034 -0.0064970553, 0.056395859 -0.011213452 -0.0065007806, -0.0029737651 0.057423532 -0.0064968467, 0.057129219 -0.0065180212 -0.0065006465, -0.0077056289 0.056981742 -0.0064968467, 0.057472497 -0.0017779619 -0.0065002143, -0.012384862 0.056150913 -0.0064969659, 0.05742304 0.0029740036 -0.0064999312, 0.05698137 0.0077059716 -0.0064997226, -0.016979292 0.05493632 -0.0064971149, 0.056150377 0.012385219 -0.0064993203, -0.021457851 0.053346604 -0.0064971149, 0.054935887 0.016979665 -0.0064993501, -0.025789797 0.051392406 -0.0064973533, 0.053346097 0.021458223 -0.0064988136, -0.029945761 0.049087271 -0.0064973831, 0.05139187 0.025790334 -0.0064988434, -0.033896908 0.046446636 -0.0064975321, 0.049086675 0.029946163 -0.0064986348, -0.037616625 0.043488845 -0.0064975917, 0.046446249 0.033897251 -0.0064982176, -0.041079506 0.040233865 -0.0064979494, 0.043488324 0.037617147 -0.0064980388, -0.044261575 0.036704242 -0.0064981431, 0.040233478 0.041079879 -0.00649786, -0.047141403 0.032923818 -0.0064983964, -0.049699113 0.028918341 -0.0064984858, 0.036703616 0.044262052 -0.0064976513, -0.051917449 0.024715573 -0.0064987093, 0.032923311 0.04714185 -0.0064975917, -0.053781137 0.02034387 -0.0064989179, 0.028917789 0.049699634 -0.0064972937, 0.024715096 0.051917762 -0.0064972341, 0.020343259 0.053781494 -0.0064970851, -0.045840338 -0.0075330287 -0.001500532, -0.04658556 -0.0081451982 -0.0015007555, -0.044970602 -0.0071170628 -0.0015006363, 0.030845866 0.042482927 -0.0014976859, 0.034431204 0.039632678 -0.0014978945, 0.016155526 0.021633431 -0.0014988631, -0.044026181 -0.0069214851 -0.0015006661, -0.043062523 -0.0069573373 -0.0015006363, 0.013430133 0.023423076 -0.0014987588, 0.01050888 0.024870917 -0.0014986843, 0.027026013 0.045009643 -0.0014976263, 0.03528969 -0.032533884 -0.0015020967, 0.0074344575 0.025956452 -0.00149858, 0.0042515099 0.026663378 -0.0014985502, 0.035209313 -0.031573132 -0.0015021116, 0.034901097 -0.030659229 -0.0015019029, 0.023000345 0.04719387 -0.0014973879, 0.016397148 0.043143526 -0.0014977753, 0.016316772 0.044104621 -0.0014976859, 0.034383267 -0.029845744 -0.0015019476, 0.001006633 0.026981503 -0.0014985949, 0.033685789 -0.029179737 -0.0015015453, -0.0022530109 0.026905864 -0.0014987141, 0.032849208 -0.028700218 -0.0015017986, 0.018799648 0.049018696 -0.0014973283, 0.015490785 0.045831755 -0.0014973879, 0.014793292 0.046497434 -0.0014974475, 0.016008466 0.0450183 -0.0014976263, 0.0144559 0.050470799 -0.0014973283, 0.013029695 0.047242865 -0.0014974475, 0.012066141 0.047278732 -0.0014974177, 0.013956845 0.046977311 -0.0014974177, -0.049018651 0.018800005 -0.0014990568, -0.024870977 0.010509148 -0.0014995933, 0.010002017 0.051538661 -0.0014974177, 0.010251835 0.046667159 -0.0014974177, 0.009506613 0.046055079 -0.0014975369, 0.011121765 0.04708302 -0.0014974773, -0.047193661 0.023000479 -0.0014989078, -0.023422986 0.013430282 -0.0014992356, 0.027822435 -0.030394971 -0.0015018284, 0.028399244 -0.02962257 -0.0015018135, 0.005472064 0.052214354 -0.0014972091, 0.0089297891 0.045282379 -0.0014977455, -0.04500939 0.027026296 -0.0014986843, -0.021633416 0.016155779 -0.0014992803, 0.00090056658 0.052492604 -0.0014971793, -0.042482674 0.030846134 -0.0014983118, 0.029144496 -0.029010221 -0.0015017837, -0.0036779344 0.052371219 -0.0014971495, -0.039632499 0.034431428 -0.0014982224, -0.019528344 0.018645585 -0.001499027, -0.0082283467 0.051851496 -0.0014972091, -0.0054796338 0.026438251 -0.0014986843, 0.030014381 -0.028594226 -0.0015017837, 0.030958638 -0.028398797 -0.0015018135, -0.036480904 0.037754521 -0.0014979243, -0.017138451 0.020863354 -0.0014989972, -0.012716264 0.050936922 -0.0014973283, -0.0086264461 0.025584981 -0.0014987439, 0.031922311 -0.028434664 -0.0015015751, -0.033051535 0.040790468 -0.0014979392, -0.017107338 0.049634784 -0.0014973283, -0.029370651 0.043515876 -0.0014976859, -0.01449874 0.022777095 -0.0014989227, -0.021368027 0.047954917 -0.0014973134, -0.011647284 0.02435869 -0.0014988482, -0.025466338 0.045910195 -0.001497522, 0.051538453 -0.010002032 -0.001500681, 0.026663065 -0.0042513758 -0.0015004724, 0.052214086 -0.005471915 -0.0015005022, 0.026981249 -0.0010065436 -0.0015000701, 0.052492231 -0.00090046227 -0.0015003234, 0.026905909 0.0022530556 -0.0014999658, 0.051851168 0.0082284659 -0.0014996827, 0.05237101 0.0036780685 -0.0014999807, 0.026437983 0.0054798126 -0.001499936, 0.050936714 0.012716249 -0.0014995337, 0.025584906 0.0086266249 -0.0014995486, 0.049634695 0.017107382 -0.0014990568, 0.047954649 0.021368101 -0.001498878, 0.024358451 0.011647642 -0.0014995188, 0.045909882 0.025466368 -0.0014988184, 0.022776917 0.01449874 -0.0014993995, 0.043515652 0.029370874 -0.0014982522, 0.020863205 0.017138556 -0.0014990717, 0.040790156 0.033051625 -0.0014982224, -0.039695218 -0.011056498 -0.0015008152, -0.039775789 -0.010095537 -0.0015008003, -0.040083781 -0.0091819167 -0.0015007555, -0.040601566 -0.0083683133 -0.0015006363, -0.041298926 -0.0077027082 -0.0015005022, 0.037754402 0.036481038 -0.0014982224, 0.018645361 0.019528419 -0.0014988631, -0.042135492 -0.0072228312 -0.0015005916, -0.047162667 -0.0089177638 -0.0015006065, -0.045840278 -0.0075334311 0.0014994442, -0.046585605 -0.0081455261 0.0014994591, -0.044970497 -0.007117182 0.0014995486, -0.044026151 -0.0069217086 0.0014993995, -0.043062657 -0.0069575757 0.0014996082, 0.016155481 0.021633327 0.0015010983, 0.013430193 0.02342315 0.0015011281, 0.010508969 0.024870932 0.0015011728, 0.030846044 0.042482555 0.0015023649, 0.027026013 0.045009404 0.0015022755, 0.035289675 -0.032534048 0.0014979094, 0.0074343979 0.025956348 0.0015013963, 0.0042515099 0.02666311 0.0015013814, 0.035209209 -0.031573191 0.001497969, 0.023000315 0.047193468 0.0015026033, 0.016397104 0.043143347 0.0015023053, 0.034901097 -0.030659467 0.001498282, 0.016316608 0.044104174 0.0015023649, 0.034383327 -0.029846042 0.0014982522, 0.0010065585 0.026981369 0.001501292, 0.033685833 -0.029180005 0.0014981925, -0.0022530556 0.026905835 0.0015014559, 0.032849327 -0.028700426 0.0014982522, 0.018799707 0.049018428 0.0015026331, 0.015490711 0.045831516 0.0015023351, 0.014793232 0.046497419 0.0015023947, 0.016008541 0.045018017 0.0015023649, 0.014455914 0.05047068 0.0015028417, 0.01302968 0.047242612 0.0015023649, 0.012066081 0.047278658 0.0015024543, 0.013956651 0.046977177 0.0015026927, 0.010001928 0.051538542 0.0015026331, 0.010251939 0.046666756 0.0015025735, 0.009506911 0.046054825 0.0015024543, 0.011121973 0.047082841 0.0015025735, -0.049018577 0.018799573 0.0015008301, -0.024870992 0.010508895 0.0015002042, 0.0054721832 0.052214086 0.0015028715, 0.0089299381 0.045282155 0.0015025139, -0.047193557 0.023000389 0.0015011579, 0.027822286 -0.030395299 0.0014980882, 0.028399259 -0.029622704 0.0014980733, -0.023423046 0.013430148 0.0015007854, 0.00090047717 0.052492231 0.0015028119, -0.021633267 0.016155526 0.0015008301, -0.045009509 0.027026042 0.0015013814, -0.003677845 0.052371159 0.0015027821, 0.029144391 -0.029010534 0.0014981925, -0.042482734 0.030846 0.00150159, -0.0082283467 0.051851347 0.0015027225, 0.0300145 -0.028594553 0.0014983565, 0.030958697 -0.028398871 0.0014981925, -0.0054796785 0.026437983 0.0015013814, -0.019528285 0.018645346 0.0015008897, -0.039632618 0.034431338 0.0015018582, -0.012716189 0.050936863 0.0015028119, -0.0086264461 0.025584921 0.0015011579, -0.036480859 0.037754536 0.0015019029, -0.017138407 0.020863116 0.0015010834, 0.031922281 -0.028434932 0.0014983565, -0.017107248 0.049634606 0.0015025735, -0.033051595 0.040790334 0.0015020967, -0.021367997 0.047954798 0.0015023947, -0.011647448 0.024358436 0.0015010983, -0.014498651 0.022776917 0.0015012324, -0.02937071 0.043515712 0.00150235, -0.025466278 0.045910001 0.0015024096, 0.051538393 -0.010002077 0.0014992803, 0.026663288 -0.0042516589 0.0014998019, 0.052213982 -0.0054721832 0.0014995039, 0.026981205 -0.001006633 0.0014997721, 0.052492365 -0.00090064108 0.0014998317, 0.052370995 0.0036778152 0.0015000701, 0.026905701 0.0022528321 0.0015000552, 0.051851109 0.008228302 0.0015001595, 0.050936744 0.012716055 0.0015005767, 0.026438013 0.0054795146 0.0015001297, 0.025584936 0.0086264014 0.0015005171, 0.049634546 0.017107114 0.0015009046, 0.047954649 0.021368131 0.001501143, 0.024358332 0.011647567 0.0015005171, 0.045910046 0.025466159 0.0015012324, 0.022776902 0.014498547 0.0015008599, 0.043515712 0.02937071 0.0015015304, 0.02086331 0.017138243 0.0015007854, 0.04079029 0.033051625 0.0015016794, -0.039695248 -0.011056796 0.0014994889, -0.039775804 -0.010095805 0.0014993697, -0.040083781 -0.0091821253 0.0014993995, -0.040601686 -0.0083686709 0.0014994293, -0.041299015 -0.0077027678 0.0014996082, 0.037754387 0.036480829 0.001501888, 0.018645316 0.019528165 0.0015010387, -0.042135611 -0.0072230548 0.0014994144, 0.034431279 0.039632678 0.0015021265, -0.047162563 -0.0089179724 0.0014993101, -0.061058268 0.057690695 -0.049496934, -0.0648527 0.05338949 -0.049497083, -0.016615391 0.082343116 -0.049495518, -0.010957569 0.083285347 -0.049495608, -0.022195742 0.081017449 -0.049495682, -0.056979194 0.061723024 -0.049496725, 0.039520457 -0.068401396 -0.049503937, -0.052634388 0.065467507 -0.049496487, 0.034652412 -0.070991695 -0.049504042, -0.027672708 0.079313904 -0.049495578, -0.048044443 0.068906888 -0.049496278, 0.044195771 -0.065477967 -0.049503967, -0.033020362 0.077240497 -0.049495772, 0.0296157 -0.07323578 -0.04950431, -0.043229997 0.072024718 -0.049496055, -0.03821443 0.074807107 -0.049495831, 0.048655733 -0.062235624 -0.049503595, 0.024434581 -0.075123325 -0.049504429, 0.052878723 -0.058689773 -0.049503401, 0.0191347 -0.076644972 -0.049504369, 0.056844071 -0.054858193 -0.049503148, 0.013741389 -0.077792868 -0.049504474, 0.060532585 -0.05075942 -0.049502969, 0.0082812905 -0.078562006 -0.049504608, 0.063926235 -0.046413168 -0.04950276, 0.0027805269 -0.078948334 -0.049504608, 0.067008212 -0.041840792 -0.049502566, -0.0027334392 -0.078949973 -0.049504533, 0.069763929 -0.037064686 -0.049502209, -0.0082342774 -0.078566954 -0.049504578, 0.07217963 -0.032107905 -0.049501851, -0.013695031 -0.077801138 -0.049504533, 0.074243888 -0.026994541 -0.049501702, -0.019089162 -0.076656103 -0.049504563, 0.082142994 -0.017561853 -0.049501136, -0.024389938 -0.075137928 -0.049504444, 0.083150178 -0.011915296 -0.049500734, -0.029572263 -0.073253512 -0.049504399, 0.083769664 -0.006213069 -0.049500391, -0.034610182 -0.071012229 -0.049504191, 0.083998516 -0.00048197806 -0.049500391, -0.039479643 -0.068425059 -0.049504012, 0.08383584 0.0052513331 -0.049499959, -0.044156805 -0.065504476 -0.049503699, -0.048618808 -0.062264517 -0.049503595, 0.083282173 0.010960266 -0.049499527, -0.052843854 -0.058721304 -0.04950349, 0.08234027 0.016618177 -0.049499288, -0.056811646 -0.054892078 -0.049503282, 0.081014588 0.022198513 -0.049498796, -0.060502484 -0.050795406 -0.049503058, 0.079310939 0.027675465 -0.049498558, -0.063898757 -0.04645133 -0.049502775, 0.077237636 0.033023283 -0.049498379, -0.066983283 -0.041880846 -0.049502477, 0.074804157 0.038217321 -0.049498007, -0.069741815 -0.03710638 -0.049502149, 0.072022021 0.043232903 -0.049497709, -0.072160736 -0.03215085 -0.049501821, 0.068903834 0.048047155 -0.049497366, -0.074227795 -0.027038887 -0.049501687, 0.065464482 0.052637309 -0.049497023, -0.075933352 -0.021795213 -0.049501255, 0.061720148 0.056981981 -0.049497068, -0.077268735 -0.016445234 -0.049501225, 0.057687864 0.06106104 -0.04949674, -0.078228012 -0.011015147 -0.049500689, 0.053386658 0.064855546 -0.049496412, -0.078806043 -0.0055314451 -0.049500495, 0.048836514 0.068347558 -0.049496368, -0.079000056 -2.0831823e-05 -0.049500123, 0.044058561 0.071520954 -0.049496189, -0.078809232 0.0054900944 -0.049499884, 0.039075315 0.074360922 -0.049495861, -0.078234643 0.010974228 -0.049499556, 0.033909753 0.076854154 -0.049495846, -0.077278689 0.016404822 -0.049499258, 0.028586239 0.078989103 -0.049495861, 0.023129448 0.080755621 -0.049495578, -0.078986481 0.0285891 -0.049498349, 0.017564639 0.082146078 -0.049495623, -0.076851338 0.033912554 -0.049498126, 0.011918113 0.083153114 -0.049495369, -0.074358165 0.039078116 -0.049498022, 0.0062158555 0.083772525 -0.049495548, 0.00048483908 0.084001511 -0.049495369, -0.071518242 0.044061497 -0.049497649, -0.0052484423 0.083838731 -0.049495399, -0.068344653 0.048839346 -0.049497351, 0.012060046 0.084142998 -0.050495371, 0.017773807 0.083123833 -0.050495371, 0.084766805 -0.006287083 -0.050500572, 0.084140226 -0.012057275 -0.05050081, 0.023404613 0.081717163 -0.05049549, 0.083120912 -0.017771006 -0.050500959, -0.079926506 0.028929397 -0.050498575, 0.028926447 0.079929575 -0.050495505, -0.077766418 0.034316525 -0.050498217, 0.034313545 0.077769056 -0.050495729, -0.075243294 0.03954345 -0.050497875, 0.039540455 0.075246245 -0.050495863, -0.072369546 0.044585794 -0.050497591, 0.044582993 0.072372332 -0.050496072, -0.069158569 0.049420729 -0.050497413, 0.049417779 0.06916137 -0.050496101, -0.065624893 0.054025084 -0.05049707, 0.054022104 0.065627784 -0.050496489, -0.061785221 0.058377668 -0.050496802, 0.058374673 0.061787933 -0.050496548, -0.05765754 0.062457785 -0.050496474, 0.062454939 0.057660446 -0.050496832, -0.053260997 0.066246897 -0.050496235, 0.066244155 0.053263754 -0.050497189, -0.04861629 0.069727153 -0.050496101, 0.069724247 0.048619166 -0.050497323, -0.043744713 0.07288225 -0.050495893, 0.072879389 0.0437475 -0.050497562, -0.038669199 0.075697556 -0.050495714, 0.075694725 0.038672104 -0.050497681, -0.033413544 0.078160167 -0.050495625, 0.078157172 0.03341639 -0.050498292, -0.028001979 0.080258042 -0.05049552, 0.080255151 0.02800487 -0.050498575, -0.022460014 0.081981853 -0.050495401, 0.081979051 0.022462919 -0.050498798, -0.016813114 0.083323389 -0.050495222, 0.083320454 0.01681599 -0.050499067, -0.011088073 0.084276572 -0.050495356, 0.084273666 0.011090845 -0.050499529, -0.0053110123 0.084836796 -0.050495327, 0.084833831 0.0053140223 -0.050499752, 0.00049053133 0.085001498 -0.050495327, 0.084998667 -0.00048780441 -0.050500125, 0.0062898844 0.084769949 -0.050495386, 0.03431347 0.077763304 0.050504178, 0.028926641 0.07992363 0.050504297, -0.077766404 0.034310684 0.050501794, -0.079926535 0.028923765 0.050501674, 0.023404777 0.081711307 0.050504625, 0.083120912 -0.017776757 0.050498888, 0.017773777 0.083118185 0.050504595, 0.084140092 -0.012062907 0.050499067, 0.012059957 0.084137365 0.050504804, 0.084766895 -0.0062927604 0.050499678, 0.006289959 0.084764376 0.050504684, 0.084998667 -0.00049355626 0.050499782, 0.00049057603 0.08499603 0.050504684, 0.08483389 0.0053081363 0.050500348, -0.0053112507 0.084831163 0.050504774, 0.084273666 0.011085123 0.050500453, -0.011088073 0.08427085 0.050504476, 0.083320528 0.016810358 0.05050087, -0.016813099 0.083317712 0.050504595, 0.081978977 0.022457108 0.050501287, -0.022460073 0.081976265 0.05050455, 0.08025527 0.027999118 0.050501734, -0.028002053 0.080252469 0.050504357, 0.078157142 0.033410788 0.050501794, -0.033413619 0.078154251 0.050504237, 0.075694606 0.038666531 0.050502092, -0.038669273 0.075691983 0.050504237, 0.072879359 0.043741941 0.050502419, -0.043744758 0.072876588 0.05050385, 0.069724292 0.04861331 0.050502628, -0.048616156 0.069721401 0.050503775, 0.066243961 0.053258091 0.050503016, -0.053260937 0.066241235 0.050503582, 0.062454849 0.057654724 0.050503075, -0.057657644 0.062452123 0.050503463, 0.058374554 0.061782286 0.050503373, -0.061785236 0.058371902 0.05050309, 0.054022163 0.065621912 0.050503731, -0.065624774 0.054019451 0.050502971, 0.049417913 0.069155604 0.050503761, -0.069158331 0.049414918 0.050502867, 0.044583023 0.07236664 0.050503999, -0.07236965 0.044580221 0.050502464, 0.03954047 0.075240552 0.050504297, -0.075243324 0.039537817 0.050502315, -0.052843839 -0.058726996 0.049496517, -0.056811482 -0.05489783 0.04949677, -0.078227967 -0.011020705 0.049499303, -0.07726869 -0.016450763 0.049498886, -0.06050244 -0.050800979 0.049496964, -0.075933307 -0.021800682 0.049498752, -0.063898578 -0.046456978 0.049497217, -0.07422787 -0.027044311 0.049498275, -0.066983357 -0.0418863 0.04949747, 0.074804068 0.038211644 0.049501956, 0.072022021 0.043227494 0.049502462, -0.072160557 -0.032156467 0.049498096, 0.068903834 0.048041597 0.04950273, -0.069741875 -0.037111863 0.049497843, 0.07723777 0.033017591 0.049501628, 0.065464586 0.052631825 0.04950285, 0.079310864 0.027669922 0.049501479, 0.061720103 0.056976572 0.049502999, 0.081014559 0.02219291 0.049501121, 0.057687879 0.061055675 0.049503267, 0.082340196 0.016612634 0.049500614, 0.05338645 0.064850226 0.049503595, 0.083282202 0.010954931 0.049500495, 0.04883641 0.068342105 0.049503803, 0.0838359 0.0052457601 0.049500182, 0.044058532 0.071515322 0.049503833, 0.083998621 -0.00048752129 0.049499765, 0.039075285 0.074355423 0.049504042, 0.083769754 -0.0062187612 0.049499497, 0.033909708 0.076848671 0.049504191, 0.083150268 -0.011920765 0.049499169, 0.028586239 0.078983456 0.049504429, 0.082142994 -0.017567366 0.049498647, 0.023129374 0.080750212 0.049504548, 0.017564774 0.082140401 0.049504429, 0.074243769 -0.02700001 0.049498454, 0.011918038 0.083147496 0.049504548, 0.072179735 -0.032113358 0.049498141, 0.0062159896 0.083767176 0.049504638, 0.069763854 -0.037070155 0.049497649, 0.00048485398 0.083995938 0.049504548, 0.067008108 -0.041846275 0.049497694, -0.0052487254 0.083833203 0.049504459, 0.063926041 -0.046418741 0.049497321, -0.01095745 0.083279595 0.049504638, 0.06053257 -0.050764889 0.049497023, -0.016615361 0.082337692 0.049504519, 0.056844085 -0.054863751 0.049496651, -0.022195816 0.081011906 0.049504519, 0.052878737 -0.058695331 0.049496546, -0.027672678 0.079308316 0.049504384, 0.048655748 -0.062241092 0.049496382, -0.033020526 0.077235103 0.049504131, 0.044195786 -0.065483496 0.04949607, -0.038214356 0.074801594 0.049504057, 0.039520487 -0.06840685 0.049496174, -0.043230116 0.072019354 0.049503893, 0.034652457 -0.070997149 0.049495742, -0.048044294 0.068901435 0.049503818, 0.029615834 -0.073241293 0.049495682, -0.052634403 0.065462112 0.049503699, 0.02443473 -0.075128749 0.049495637, -0.056979299 0.06171757 0.049503282, 0.019134805 -0.076650411 0.049495637, -0.061058491 0.057685226 0.049503282, 0.013741359 -0.077798501 0.049495533, -0.064852729 0.053383812 0.049502939, 0.0082812905 -0.07856749 0.049495563, 0.0027805567 -0.078953743 0.049495548, -0.068344861 0.048833877 0.049502552, -0.0027334988 -0.078955308 0.049495474, -0.071518123 0.044055939 0.049502179, -0.0082343519 -0.078572437 0.049495503, -0.074358106 0.039072752 0.049502015, -0.013695017 -0.077806532 0.049495518, -0.076851383 0.033907071 0.049501762, -0.019089103 -0.076661855 0.049495474, -0.078986272 0.028583601 0.049501553, -0.024390012 -0.075143471 0.049495786, -0.029572085 -0.073259205 0.049495652, -0.077278659 0.01639919 0.049500719, -0.034610227 -0.071017981 0.049495891, -0.078234836 0.010968804 0.04950048, -0.039479673 -0.068430498 0.049496129, -0.078809366 0.0054846108 0.049500078, -0.044156745 -0.06550993 0.049496144, -0.078999981 -2.6285648e-05 0.049500063, -0.048618749 -0.062270164 0.049496382, -0.078805938 -0.0055369288 0.049499601, 0.065709323 0.0023126453 0.026763141, 0.063423991 0.0050521195 0.025536433, 0.065107286 0.00916861 0.026763648, 0.069415167 -0.0090312511 0.029216185, 0.064754501 -0.011399582 0.026762471, 0.068546399 -0.014193401 0.02921617, 0.061778083 0.022504702 0.026764303, 0.058357313 0.025347427 0.025537848, 0.059087098 0.028839022 0.026764691, 0.059900969 0.036218524 0.029218912, 0.059599623 0.032477871 0.027991772, 0.062439889 0.031640679 0.029218704, 0.069895983 -0.003818512 0.029216692, 0.065591037 -0.0045682639 0.026762918, 0.055748716 0.034857437 0.026765049, 0.033765584 0.061316341 0.029220432, 0.034504503 0.058449134 0.02799347, 0.038253516 0.058621511 0.029220134, 0.036750585 0.054518804 0.026766062, 0.030850381 0.058061495 0.0267663, 0.069684044 0.0066416115 0.029217184, 0.069985673 0.001415506 0.029216945, 0.027335554 0.057452038 0.025539368, 0.024612069 0.06096825 0.026766539, 0.011398077 0.064753085 0.026766837, 0.0072261095 0.063211948 0.025539726, 0.0045668185 0.06558986 0.026766747, 0.068992764 0.011830404 0.029217511, 0.00065654516 0.067870349 0.027993649, -0.0023144186 0.065707862 0.026766628, -0.0014171898 0.069984138 0.029220849, 0.0038169324 0.06989412 0.029220879, 0.067915529 0.016953081 0.029217929, 0.063792065 0.015924037 0.026764035, -0.036220133 0.059899122 0.029220209, -0.03336741 0.059105575 0.027993232, -0.031642392 0.062438414 0.029220402, 0.066458747 0.02198115 0.029218107, -0.028840631 0.059085637 0.026766166, -0.034858808 0.055747345 0.026766136, -0.036088467 0.052398637 0.025539249, -0.040495276 0.05179821 0.026766002, 0.064629942 0.026886135 0.029218346, -0.050380111 0.042246759 0.026765376, -0.051131293 0.03786312 0.025538221, -0.054520309 0.036749169 0.026765078, -0.058623239 0.038251862 0.029219031, -0.058450416 0.034503266 0.027991995, -0.058062941 0.03084892 0.026764795, -0.06131795 0.033764005 0.029218778, -0.06016475 0.020694822 0.025537491, 0.057026669 0.040593579 0.029219061, -0.0609698 0.024610817 0.026764557, -0.065665662 0.024248019 0.029218256, -0.064183831 0.022077352 0.027991325, 0.051799625 0.040493727 0.026765585, 0.053833529 0.044741809 0.029219329, 0.050339371 0.048639491 0.029219568, 0.047283009 0.045686364 0.026765704, 0.046563625 0.052265391 0.029219717, 0.042527318 0.05559887 0.029220164, 0.042248234 0.050378606 0.026765764, 0.029088885 0.063668132 0.029220432, 0.024249405 0.065663993 0.029220492, 0.019274503 0.067292467 0.029220521, 0.018104166 0.063206911 0.026766598, 0.014191717 0.068544805 0.0292207, 0.009029597 0.069413498 0.0292207, -0.0066432059 0.069682464 0.02922079, -0.011832029 0.068991244 0.02922067, -0.0091700852 0.065106004 0.026766807, -0.016954929 0.067914024 0.029220685, -0.015925378 0.063790634 0.026766539, -0.021982849 0.066457093 0.029220477, -0.0268877 0.064628482 0.029220536, -0.022506326 0.061776668 0.026766509, -0.040595159 0.057024896 0.029220045, -0.044743389 0.05383186 0.02922006, -0.045687929 0.047281489 0.026765898, -0.04864119 0.050337672 0.029219687, -0.052267045 0.046561927 0.029219374, -0.055600628 0.042525843 0.029219374, -0.063669771 0.029087275 0.029218525, 0.061998531 -0.014295489 0.025535345, 0.066139951 -0.01525034 0.027989089, 0.067854345 -0.0016733706 0.027989864, -0.012249917 0.071427524 0.031446934, -0.00888291 0.071924105 0.031446844, -0.012391478 0.072251782 0.032895148, 0.073208258 -0.0095249116 0.034481153, -0.008985281 0.072753772 0.032895237, -0.0069572031 0.07297568 0.032895297, -0.0090488493 0.073266685 0.034485906, -0.0070062578 0.073490202 0.034485817, 0.073715359 -0.0040275156 0.034481525, 0.07133843 0.0014428645 0.030199885, 0.071246862 -0.0038923472 0.030199692, 0.072457358 0.0014653057 0.031442761, 0.072364196 -0.0039534718 0.031442672, -0.0036763847 0.07373178 0.034485906, 0.073199213 -0.0039990991 0.03289105, 0.072695747 -0.0094582438 0.032890648, -0.0087456405 0.070813358 0.030203909, -0.012060881 0.070324719 0.030203909, 0.071866527 -0.0093502253 0.031442195, -0.0068778098 0.072143406 0.031446815, 0.07229206 -0.014969036 0.03448084, -0.0036505461 0.073215514 0.032895327, 0.070756853 -0.0092055947 0.030199364, -0.0014945269 0.073808074 0.034485787, 0.071785972 -0.014864415 0.03289026, -0.0067716539 0.071029395 0.030203879, 0.070967212 -0.014694765 0.031441763, -0.0036088526 0.072380692 0.031446844, -0.0014840066 0.07329163 0.032895505, 0.069871128 -0.014467731 0.030198872, 0.0017157197 0.073803395 0.034486026, -0.0035533011 0.071263015 0.030203819, -0.0014671683 0.07245557 0.031446815, 0.0017037094 0.073286742 0.032895237, 0.0040253699 0.073713526 0.034485996, -0.0014444292 0.071336791 0.030203938, 0.0016843081 0.072450817 0.031446815, 0.0039972961 0.073197529 0.032895356, 0.0070984364 0.073481336 0.034485936, 0.0016582906 0.071332276 0.030203849, 0.0039516389 0.072362736 0.031446844, 0.0070488155 0.072966754 0.032895416, 0.0095230043 0.073206574 0.034485847, 0.0038906336 0.071245268 0.0302037, 0.0069684684 0.072134778 0.031446815, 0.0094562173 0.072694197 0.032895058, 0.012443542 0.072767004 0.034485787, 0.0068610013 0.071020782 0.030203909, 0.0093484223 0.071864933 0.031446815, 0.0123564 0.072257668 0.032895207, 0.014967144 0.072290123 0.034485817, 0.0092040896 0.070755318 0.030203909, 0.012215495 0.071433499 0.031446755, 0.014862448 0.071784168 0.032895207, 0.017722309 0.071664467 0.034485847, 0.012026936 0.07033065 0.030203849, 0.014692903 0.070965454 0.031446636, 0.017598093 0.071163058 0.032895088, 0.020327777 0.070969522 0.034485728, 0.014465809 0.069869667 0.0302037, 0.017397255 0.070351362 0.031446725, 0.020185351 0.070472717 0.032895267, 0.022906154 0.070179731 0.034485728, 0.017128706 0.069264919 0.030203938, 0.019955307 0.069668993 0.031446636, 0.022745818 0.069688365 0.032895237, 0.025574625 0.069252029 0.034485459, 0.019647002 0.068593174 0.03020376, 0.022486389 0.068893805 0.031446755, 0.025395662 0.06876716 0.032894969, 0.0279679 0.068320468 0.034485489, 0.022139043 0.067829847 0.030203611, 0.025105834 0.067982897 0.031446666, 0.027772337 0.0678422 0.032895088, 0.030678332 0.06714727 0.034485519, 0.024718285 0.066933081 0.030203581, 0.0274553 0.067068696 0.031446576, 0.030463636 0.066677243 0.03289482, 0.032880634 0.066096738 0.034485489, 0.027031451 0.066032916 0.030203491, 0.030116081 0.065916777 0.031446457, 0.032650441 0.065634117 0.032894939, 0.035610706 0.064666659 0.03448537, 0.029651076 0.064898804 0.030203521, 0.032278001 0.064885348 0.031446457, 0.035361439 0.064214066 0.03289482, 0.037617624 0.063520178 0.034485608, 0.031779557 0.063883647 0.030203432, 0.034958065 0.063481688 0.031446218, 0.03735441 0.063075557 0.032894731, 0.040343881 0.061824709 0.0344854, 0.034418285 0.062501445 0.030203372, 0.036928475 0.06235607 0.031446159, 0.040061355 0.061391965 0.032894552, -0.069298401 0.025452331 0.034483224, 0.042154282 0.060604975 0.034485132, 0.036358118 0.061393291 0.030203342, -0.0688131 0.025274187 0.03289251, 0.039604455 0.060691893 0.031446069, -0.068028122 0.024985865 0.031444058, 0.041858971 0.060180768 0.032894492, -0.067255586 0.030442834 0.034483507, 0.044851512 0.05863677 0.034484923, -0.06697771 0.024600029 0.03020145, 0.038992852 0.059754625 0.030203283, -0.06678462 0.030229747 0.032892823, 0.041381598 0.059494317 0.031446069, 0.044537395 0.058226421 0.032894433, -0.066022843 0.029885069 0.03144443, 0.046465814 0.057366163 0.034485012, -0.064853638 0.035270944 0.034483865, 0.040742576 0.058575526 0.030203134, -0.065003395 0.02942358 0.030201614, 0.044029355 0.057562396 0.03144604, -0.06439966 0.035024062 0.032893062, 0.046140492 0.056964442 0.032894284, -0.063665092 0.034624606 0.031444699, 0.049108088 0.055121332 0.034484893, 0.043349475 0.056673467 0.030203044, -0.062105969 0.039910764 0.034484059, 0.045614243 0.056314886 0.03144598, -0.062682062 0.034089923 0.030201599, -0.061671317 0.039631471 0.032893524, 0.048764229 0.054735243 0.032894105, 0.050529465 0.053821146 0.034484774, -0.060967654 0.039179474 0.031445101, 0.044910014 0.055445343 0.030202985, -0.059026688 0.044337854 0.034484267, 0.048207998 0.054111212 0.03144592, -0.060026109 0.038574576 0.030201986, 0.050175712 0.053444326 0.032894284, -0.058613554 0.044027492 0.032893747, 0.053089947 0.051297277 0.034484774, 0.047463611 0.053275511 0.030202836, -0.057944953 0.043525189 0.031445324, 0.049603313 0.052835092 0.031445712, -0.055632815 0.048528165 0.034484565, 0.054323688 0.049989209 0.034484714, -0.057050243 0.04285343 0.030202314, 0.052718461 0.050938234 0.032894105, -0.055243254 0.048188537 0.032893702, 0.048837408 0.052019134 0.030202657, 0.053943187 0.049639344 0.032893986, -0.054613128 0.047638878 0.031445384, 0.05211702 0.050357267 0.031445503, -0.051941887 0.052459672 0.034484729, 0.056775182 0.04718633 0.034484357, -0.053769767 0.046903178 0.030202508, 0.053327993 0.049073398 0.031445533, 0.051312208 0.049579665 0.030202687, -0.051578313 0.052092388 0.032894105, -0.050989881 0.051498383 0.031445682, 0.057827845 0.045890495 0.034484297, 0.056377769 0.046856105 0.032893807, -0.047973841 0.056111157 0.034484953, 0.052504331 0.04831554 0.030202687, -0.050202489 0.050703123 0.030202702, 0.057422757 0.045569256 0.032893658, -0.047638014 0.055718437 0.032894224, 0.055734545 0.04632172 0.031445324, -0.047094643 0.055083036 0.031445801, 0.056767881 0.045049593 0.031445265, 0.060142905 0.042811513 0.034484029, -0.043749839 0.059463352 0.034485087, -0.046367228 0.054232284 0.030203, 0.054874063 0.045606315 0.030202478, -0.04344368 0.059047118 0.032894433, 0.06102331 0.041546836 0.034483999, 0.055891246 0.044354022 0.03020227, 0.059721753 0.042512 0.032893628, -0.042947963 0.05837357 0.031446084, -0.039292455 0.062498361 0.034485206, 0.060596243 0.0412561 0.032893568, -0.042284966 0.057472393 0.030203015, 0.059040487 0.042027131 0.031445086, -0.039017409 0.062060848 0.032894492, 0.059904993 0.040785477 0.031445146, -0.038572237 0.061352938 0.031446382, 0.063174129 0.038197324 0.034483999, 0.058128834 0.041378319 0.030202359, -0.03462553 0.065199912 0.034485281, -0.037976697 0.060405582 0.030203372, 0.063893408 0.036981806 0.03448385, 0.058979869 0.040155873 0.03020215, -0.033371687 0.065850198 0.034485534, 0.062731892 0.037930042 0.03289333, -0.034382924 0.064743325 0.03289482, 0.063446194 0.036722884 0.0328933, -0.033138052 0.065389141 0.032894775, 0.062016502 0.037497476 0.031444788, -0.033990964 0.064004958 0.031446099, 0.06272234 0.036304176 0.031444907, -0.032759979 0.064643577 0.031446382, -0.029773593 0.067553163 0.034485668, 0.06585215 0.033369735 0.034483612, 0.06105864 0.036918551 0.030202091, -0.033465981 0.063016593 0.030203357, 0.061753854 0.035743609 0.030201852, -0.028356969 0.068160042 0.034485668, 0.065391049 0.033136085 0.032893121, -0.032254025 0.063645378 0.030203581, -0.029565245 0.067080438 0.03289488, 0.064645126 0.032758206 0.031444639, -0.02815865 0.067682832 0.032895118, 0.068161711 0.028355196 0.034483314, -0.029227883 0.066315293 0.031446517, 0.063646972 0.032252267 0.030201614, -0.027837545 0.066910937 0.031446636, 0.067684665 0.028156593 0.032892764, -0.024763018 0.069546282 0.034485683, -0.028776646 0.065291464 0.030203432, 0.066912562 0.027835578 0.031444162, 0.070090428 0.02318196 0.034483194, -0.023184121 0.070088461 0.034485608, -0.027407601 0.065877706 0.030203596, 0.065879598 0.027405664 0.030201435, -0.024589688 0.069059432 0.032895148, 0.069599539 0.02301982 0.032892376, -0.023021758 0.0695979 0.032895193, 0.068805695 0.022757336 0.031444013, -0.024309218 0.06827186 0.031446591, 0.071626902 0.017879546 0.034482867, -0.01962027 0.071168333 0.034485862, 0.067743212 0.022406116 0.030201137, -0.022759259 0.068803906 0.031446815, -0.023933768 0.067217633 0.030203596, 0.071125537 0.017754257 0.032892227, -0.017881423 0.071625009 0.034485921, 0.070314199 0.017551854 0.031443715, -0.01948303 0.070670113 0.032895193, 0.072762877 0.012476757 0.034482241, -0.022407651 0.067741603 0.030203626, 0.069228396 0.017280653 0.030200869, -0.017756253 0.071123779 0.032895043, 0.07225351 0.012389421 0.03289184, -0.019260794 0.069864213 0.03144674, 0.071429238 0.012248337 0.031443596, -0.014372915 0.072410733 0.034485698, -0.017553538 0.070312545 0.031446606, 0.073491946 0.0070043653 0.034482211, -0.018963218 0.06878534 0.0302037, 0.070326328 0.012059137 0.030200511, 0.072977558 0.0069551766 0.032891542, -0.014272094 0.071903929 0.032895148, -0.01247862 0.072760999 0.034485787, 0.07214503 0.0068760067 0.031443149, -0.017282605 0.069226727 0.030203864, 0.073810071 0.0014927089 0.034481913, -0.014109433 0.071083799 0.031446874, 0.071030989 0.0067698956 0.030200213, 0.073293388 0.0014821589 0.032891288, -0.013891578 0.069986001 0.03020376, -0.0045094341 -0.05801791 0.020631716, -0.0017999262 -0.058164984 0.020631865, -0.0017838031 -0.057648212 0.019041166, -0.004469499 -0.057502463 0.019041389, -0.0018602908 -0.06011942 0.02332285, 0.00017946959 -0.060147941 0.023322925, 0.00017607212 -0.059028924 0.022080109, -0.0018257052 -0.059000775 0.02207996, -0.0065380782 -0.057304174 0.01904121, -0.0045742989 -0.058851689 0.022080123, -0.0065968335 -0.057817638 0.020631701, -0.004660964 -0.05996725 0.02332294, -0.0090818554 -0.056956261 0.0190413, -0.0066915751 -0.058648795 0.022080064, -0.0091632903 -0.05746679 0.020631805, -0.0068184137 -0.059760451 0.023322865, -0.011247903 -0.056568518 0.019041479, -0.0092948675 -0.058292761 0.022080079, -0.011348665 -0.057075471 0.020631671, -0.0094711035 -0.059397995 0.023322955, -0.013635471 -0.056040838 0.019041389, -0.011511847 -0.057895795 0.022080019, -0.013757631 -0.056543216 0.020631939, -0.01173009 -0.058993235 0.023322865, -0.015880868 -0.055446371 0.01904124, -0.01395528 -0.057355747 0.022080094, -0.016023055 -0.055943429 0.02063188, -0.014219716 -0.058443204 0.023322925, -0.018100515 -0.054761946 0.019041538, -0.016253412 -0.056747243 0.022080272, -0.018262729 -0.055252805 0.020631805, -0.016561568 -0.057823166 0.023323178, -0.020405233 -0.053945556 0.019041583, -0.018525168 -0.056046754 0.022080302, -0.020588115 -0.054429263 0.02063188, -0.018876359 -0.057109475 0.023323104, -0.022448301 -0.053127944 0.019041583, -0.020883963 -0.055211157 0.022080228, -0.022649467 -0.053604111 0.020631805, -0.021279901 -0.056258112 0.023323163, -0.024790213 -0.052076355 0.019041479, -0.022974879 -0.054374412 0.022080436, -0.025012478 -0.052542984 0.020632088, -0.023410425 -0.055405244 0.023323193, -0.026650414 -0.051149234 0.019041613, -0.025371924 -0.053298131 0.022080317, -0.026889235 -0.051607803 0.020632058, -0.025852904 -0.054308593 0.023323417, -0.02900587 -0.049851313 0.019041657, -0.027275637 -0.052349538 0.022080407, -0.02926597 -0.050298214 0.020632133, -0.027792737 -0.05334188 0.023323193, -0.030679688 -0.048838973 0.019041702, -0.029686257 -0.05102101 0.022080585, -0.030954614 -0.049276739 0.020632133, -0.030249149 -0.051988229 0.023323357, -0.033023462 -0.047285676 0.019041866, -0.031399429 -0.049984887 0.022080526, -0.033319294 -0.047709644 0.020632237, -0.031994775 -0.050932616 0.023323491, -0.034510121 -0.046211943 0.01904197, -0.033798113 -0.048395306 0.022080898, -0.034819365 -0.046626136 0.02063261, -0.034439057 -0.049312755 0.023323536, -0.036815479 -0.044397056 0.01904197, -0.035319582 -0.047296345 0.022080809, -0.037145242 -0.044795111 0.020632595, -0.035989329 -0.048192844 0.023323521, -0.038116589 -0.043285176 0.01904206, -0.037679002 -0.045438886 0.022080928, -0.038458079 -0.043673173 0.02063255, 0.053987697 -0.020291761 0.019043267, -0.038393497 -0.046300396 0.02332373, 0.054471493 -0.020473734 0.020633757, -0.039010763 -0.044300899 0.022080913, 0.05525431 -0.020768136 0.02208215, -0.040355802 -0.041205376 0.019042134, 0.056301624 -0.02116169 0.023325056, -0.039750338 -0.045140728 0.02332361, -0.040717602 -0.041574627 0.020632595, 0.052179828 -0.024570078 0.019043103, 0.052647427 -0.024790511 0.020633534, -0.041475832 -0.040077716 0.019042253, -0.041302636 -0.042172238 0.022081032, 0.053404003 -0.025146842 0.022081852, -0.041847646 -0.040437102 0.020632833, 0.054416344 -0.025623426 0.023324773, -0.042085707 -0.042971745 0.023323894, 0.050033584 -0.028689086 0.019042894, -0.042448997 -0.041018009 0.022081196, 0.050481826 -0.028946444 0.02063328, -0.043620557 -0.037732095 0.019042343, 0.051207438 -0.02936241 0.022081539, -0.043253645 -0.041795745 0.023323894, 0.052178159 -0.029919147 0.023324683, -0.044566274 -0.03661032 0.019042432, -0.044011414 -0.038070306 0.020632863, 0.047562897 -0.032622322 0.019042596, -0.04496564 -0.036938488 0.020632938, 0.047989145 -0.032914877 0.020633087, -0.044644132 -0.038617462 0.022081211, 0.048678741 -0.03338778 0.022081569, 0.04960157 -0.034020752 0.023324385, -0.045611709 -0.037469268 0.022081241, -0.045490369 -0.039349467 0.023323983, 0.044783741 -0.036343694 0.019042552, -0.046587422 -0.034000993 0.019042537, -0.046476543 -0.038179666 0.023324147, 0.045185208 -0.036669642 0.020632982, -0.047367498 -0.032905519 0.019042492, 0.045834407 -0.037196562 0.022081375, -0.047004968 -0.034305781 0.020632893, 0.046703413 -0.0379017 0.023324162, 0.041714177 -0.039829522 0.019042388, -0.047792062 -0.033200592 0.020633221, -0.047680348 -0.034798905 0.022081405, 0.042088136 -0.040186524 0.020632595, -0.048478931 -0.033677682 0.022081375, 0.042692944 -0.040764034 0.022081017, -0.048584387 -0.035458639 0.023324147, 0.043502182 -0.041537002 0.023323923, -0.049236044 -0.030037746 0.019042924, -0.049397886 -0.034316272 0.02332443, 0.038374156 -0.043057054 0.01904209, -0.049861804 -0.028987318 0.019042984, 0.038718015 -0.043442979 0.020632714, -0.049677238 -0.030307114 0.02063325, 0.039274275 -0.044067204 0.022081047, -0.050308511 -0.02924706 0.020633265, 0.040018916 -0.044902742 0.023323834, -0.050391123 -0.03074263 0.022081569, -0.05103147 -0.029667586 0.022081703, 0.034785077 -0.0460051 0.019041881, -0.051346436 -0.031325519 0.023324534, 0.035096779 -0.046417654 0.020632371, -0.051548466 -0.025869146 0.019043013, 0.035601243 -0.047084719 0.022080824, -0.051999032 -0.030229971 0.023324445, 0.036276147 -0.047977328 0.023323834, -0.052010313 -0.026101217 0.020633519, 0.030970454 -0.048655018 0.019041598, -0.052757531 -0.026476264 0.022081897, -0.053757966 -0.02697818 0.023324668, 0.031247988 -0.049091145 0.020632282, 0.031697094 -0.049796507 0.02208057, -0.053508475 -0.021523997 0.019043252, 0.032298058 -0.050740659 0.023323476, -0.053987831 -0.021717101 0.020633623, 0.026955023 -0.050989389 0.019041613, -0.05476369 -0.022029251 0.022082105, 0.025868222 -0.051549286 0.019041598, -0.055801839 -0.022446856 0.023324952, 0.027196527 -0.051446348 0.020632088, -0.055103019 -0.017031908 0.019043535, 0.026100025 -0.052011356 0.020632014, -0.055596903 -0.017184585 0.020633921, 0.027587384 -0.052185714 0.022080466, -0.05639571 -0.017431602 0.022082314, 0.026474983 -0.052758723 0.022080421, 0.02811043 -0.053175151 0.023323223, -0.057464838 -0.01776208 0.023325354, 0.022764817 -0.05299291 0.019041553, -0.056321099 -0.012423471 0.019043669, 0.026976928 -0.053759053 0.023323342, -0.056825787 -0.012534931 0.020634204, 0.021523029 -0.05350925 0.019041434, -0.057642639 -0.012714863 0.022082642, 0.022968739 -0.053467929 0.020632043, -0.05873543 -0.012956023 0.023325607, 0.021715865 -0.053989023 0.020632103, -0.05715476 -0.0077300221 0.019044057, 0.023298904 -0.054236323 0.022080332, 0.02202794 -0.054764941 0.022080243, -0.057666913 -0.0077994764 0.020634368, 0.023740619 -0.055264786 0.023323029, -0.058495507 -0.0079116672 0.02208294, 0.018426865 -0.054652885 0.0190413, -0.059604585 -0.008061409 0.023325831, 0.02244547 -0.055803165 0.023323074, 0.017030835 -0.055104122 0.019041434, -0.057597592 -0.0029838681 0.019044459, 0.01859203 -0.055142924 0.020631999, -0.058113992 -0.0030106455 0.02063486, 0.017183378 -0.055597931 0.020631894, -0.058948994 -0.0030539334 0.022083238, 0.018859223 -0.055935219 0.022080287, -0.060066491 -0.0031119287 0.023326039, 0.01743038 -0.056396902 0.022080183, 0.019216672 -0.056995705 0.023323148, -0.057647288 0.0017828494 0.019044563, 0.013969466 -0.05595839 0.01904133, -0.058163792 0.0017985702 0.020635009, 0.017760798 -0.057466075 0.02332297, -0.058999687 0.001824528 0.022083536, 0.014094546 -0.056460112 0.020631805, -0.060118318 0.0018589795 0.023326293, 0.012422279 -0.056322053 0.019041315, -0.057303011 0.0065371543 0.019044846, 0.014297158 -0.057271421 0.022080019, -0.05781658 0.006595701 0.020635366, 0.012533709 -0.056827053 0.020631656, 0.014568269 -0.058357254 0.023323044, -0.058647528 0.0066903085 0.022083744, 0.012713656 -0.057643607 0.022080183, -0.059759155 0.0068171024 0.02332662, 0.0094215572 -0.056901142 0.01904121, -0.056567594 0.011246935 0.019045204, 0.012954652 -0.058736473 0.02332297, 0.0095059574 -0.057411164 0.020631939, -0.057074204 0.011347413 0.020635545, -0.057894602 0.011510685 0.022083998, 0.0077288896 -0.057155699 0.019041315, 0.0096424669 -0.058236241 0.022080034, -0.058992162 0.011728838 0.023326963, 0.0077981651 -0.057667881 0.02063179, 0.0098253638 -0.059340268 0.023322836, 0.0048122704 -0.057474673 0.01904121, 0.0079102814 -0.058496714 0.022079989, 0.0048554391 -0.057989895 0.020631656, 0.0080601573 -0.059605628 0.02332291, 0.0029826462 -0.057598695 0.019041121, 0.0049252063 -0.058823273 0.022079989, 0.0030093789 -0.058114976 0.020631745, 0.0050186515 -0.059938595 0.023322821, 0.00017204881 -0.057675615 0.01904133, 0.0030527413 -0.058950171 0.022080034, 0.00017362833 -0.058192641 0.020631731, 0.0031106472 -0.060067698 0.023322791, -0.041971713 -0.062262997 -0.047621086, -0.037526101 -0.065039143 -0.047621205, -0.037921667 -0.065724775 -0.048412979, -0.0066677034 -0.07487078 -0.047718197, -0.0072965026 -0.075528115 -0.048413455, -0.007220462 -0.074740201 -0.047621787, -0.0071631521 -0.074147359 -0.04667373, -0.0063197911 -0.075211391 -0.048054561, -0.0063908398 -0.074935451 -0.047765628, -0.042414278 -0.062919393 -0.048412874, -0.0062033385 -0.074388385 -0.046968222, -0.0071275085 -0.073779449 -0.045616835, -0.0057464242 -0.074829251 -0.047572821, -0.0057219863 -0.074511603 -0.047111496, -0.00998272 -0.076367065 -0.049095452, -0.0098003149 -0.075146884 -0.048334524, -0.0083508193 -0.075721547 -0.048635438, -0.0095396787 -0.076934293 -0.049282402, -0.041432098 -0.061462507 -0.04561618, -0.010629028 -0.077155873 -0.0493792, -0.047934085 -0.061387658 -0.049378216, -0.010202676 -0.076090723 -0.048981756, -0.043535024 -0.064581826 -0.049378157, -0.0084622204 -0.074571013 -0.047572866, -0.047283635 -0.060554609 -0.049008295, -0.042944103 -0.063705519 -0.049008563, -0.0079984069 -0.075656921 -0.048564032, -0.010506541 -0.075845361 -0.048875451, -0.046700254 -0.059807494 -0.048412383, -0.011718944 -0.075928748 -0.049009368, -0.011110649 -0.075366035 -0.048635468, -0.0080040395 -0.074216366 -0.046968251, -0.046212941 -0.059183612 -0.047620848, -0.0084262341 -0.074254468 -0.047111362, -0.011152267 -0.074559659 -0.047965705, -0.011672482 -0.075177804 -0.048564017, -0.045618787 -0.05842261 -0.04561612, -0.045846283 -0.058714077 -0.046672806, -0.01177083 -0.074552909 -0.048054591, -0.012790412 -0.074794203 -0.048413351, -0.053309917 -0.056782022 -0.049377948, -0.052099735 -0.057894304 -0.049377739, -0.011823758 -0.074272305 -0.047765598, -0.011180177 -0.074212283 -0.047572777, -0.0525866 -0.056011453 -0.049008086, -0.051392645 -0.057108805 -0.049008012, -0.012101948 -0.074186563 -0.047718227, -0.012657166 -0.074013814 -0.047621697, -0.012556598 -0.073426619 -0.046673685, -0.011608139 -0.073738575 -0.046968088, -0.011132762 -0.073897094 -0.047111437, -0.051937714 -0.055320233 -0.048412248, -0.05075857 -0.056404144 -0.048412472, -0.012494385 -0.07306242 -0.045616731, -0.047837824 -0.059694871 -0.048833653, -0.051395953 -0.054743245 -0.047620863, -0.050229028 -0.055815682 -0.047620744, -0.047824576 -0.058912247 -0.048412517, -0.048112839 -0.059267253 -0.048736915, -0.046933725 -0.058329001 -0.047319964, -0.056011453 -0.054119006 -0.049377769, -0.047293931 -0.057905212 -0.047163635, -0.048421592 -0.057390675 -0.047620907, -0.050988123 -0.054308951 -0.046672449, -0.049830586 -0.055372864 -0.046672821, -0.055251315 -0.053384677 -0.049007833, -0.050735012 -0.054039434 -0.045615762, -0.049582943 -0.055098146 -0.045615911, -0.050563395 -0.05740428 -0.048833624, -0.049851596 -0.057207271 -0.048412442, -0.049285829 -0.056219459 -0.047163561, -0.057312787 -0.052739188 -0.049377635, -0.049596637 -0.056082413 -0.047319889, -0.050152153 -0.057551935 -0.048736826, -0.054569677 -0.052725941 -0.048412099, -0.046771675 -0.05750379 -0.04561612, -0.046138823 -0.058012798 -0.045616046, -0.0471223 -0.057695091 -0.046672866, -0.048135221 -0.056367442 -0.045615807, -0.056535065 -0.052023381 -0.049007922, -0.048206508 -0.056792408 -0.046672627, -0.049107075 -0.056015506 -0.046672612, -0.054000318 -0.052175909 -0.047620565, -0.074872747 -0.0051874816 -0.047569007, -0.075859323 -0.0058060735 -0.048560038, -0.075988948 -0.0054369271 -0.048631579, -0.074811146 -0.0064731985 -0.047617972, -0.075683489 -0.0039417595 -0.048330545, -0.055837318 -0.051381499 -0.048412099, -0.074440032 -0.0055849701 -0.046964437, -0.074217692 -0.0064219087 -0.046669841, -0.073849216 -0.0063900352 -0.045612961, -0.05357182 -0.051762208 -0.046672463, -0.074554667 -0.005165562 -0.047107548, -0.055254921 -0.050845444 -0.047620609, -0.053306103 -0.051505104 -0.045615494, -0.075012252 -0.0024495572 -0.047568679, -0.076136857 -0.0026581287 -0.048631415, -0.076052129 -0.0021057576 -0.048559904, -0.059650511 -0.050079912 -0.049377561, -0.075084254 -0.00099501014 -0.047617719, -0.054816574 -0.050442293 -0.046672314, -0.074623719 -0.001954034 -0.046964124, -0.058841005 -0.049400553 -0.049007863, -0.074693725 -0.0024390966 -0.047107339, -0.074488729 -0.00098711252 -0.046669453, -0.074118793 -0.00098226964 -0.045612812, -0.075051919 0.00027804077 -0.047568589, -0.076080799 -0.00028064847 -0.048559919, -0.076183617 8.3148479e-05 -0.048631221, -0.054544523 -0.050191656 -0.04561545, -0.075770006 0.001565963 -0.048330322, -0.058114812 -0.048791006 -0.04841195, -0.074649185 -0.00014549494 -0.046964005, -0.061009824 -0.048414826 -0.049377412, -0.074733138 0.00027696788 -0.047107354, -0.057508484 -0.048282072 -0.047620296, -0.075333476 0.0029671043 -0.04796128, -0.07612972 0.0028654784 -0.048630998, -0.076004326 0.0034238696 -0.048559621, -0.060181931 -0.047757849 -0.049007565, -0.057052404 -0.047898933 -0.04667224, -0.059439301 -0.047168598 -0.048411787, -0.07512103 0.0036623329 -0.047761336, -0.075747058 0.0045359284 -0.048408896, -0.074991688 0.0030190498 -0.04756847, -0.056769118 -0.047661319 -0.045615271, -0.07506682 0.0039380938 -0.047713682, -0.058819249 -0.046676427 -0.047620133, -0.074956849 0.0044885427 -0.047617391, -0.074362218 0.0044527054 -0.046669245, -0.07456775 0.0034893155 -0.046963751, -0.073993027 0.0044307411 -0.045612678, -0.074673325 0.0030060261 -0.047107056, -0.062998548 -0.045797139 -0.049377292, -0.074832454 0.0057421625 -0.047568262, -0.075900584 0.0052463412 -0.048559427, -0.075977445 0.0056028813 -0.048630893, -0.058352575 -0.046306223 -0.046671957, -0.075456366 0.0070655197 -0.048329875, -0.07446152 0.0052952468 -0.046963498, -0.062143981 -0.045175523 -0.049007505, -0.058063015 -0.046076447 -0.045615286, -0.074514836 0.005717963 -0.04710713, -0.061377212 -0.044618189 -0.048411667, -0.074918777 0.0084356666 -0.047961041, -0.075722277 0.0083739758 -0.048630714, -0.07555528 0.0089354366 -0.048559412, -0.064381257 -0.043832123 -0.049377099, -0.060736746 -0.044152796 -0.047619998, -0.074934736 0.0090541542 -0.048049778, -0.075214148 0.010052994 -0.048408702, -0.063507676 -0.043237373 -0.049007505, -0.060254887 -0.043802485 -0.046672061, -0.074656099 0.0091159493 -0.047761008, -0.07457307 0.0084714592 -0.047568098, -0.074580953 0.0093936771 -0.047713429, -0.074429542 0.0099479705 -0.047617063, -0.06272392 -0.042704016 -0.048411608, -0.073839068 0.0098691285 -0.046668813, -0.05995582 -0.043585077 -0.045615062, -0.074115455 0.0089143366 -0.046963483, -0.07347244 0.0098199695 -0.045612082, -0.07425642 0.0084354579 -0.047106877, -0.06603995 -0.041290939 -0.04937695, -0.075960979 0.012729168 -0.049090385, -0.074743986 0.012527511 -0.048329681, -0.075371847 0.011092961 -0.048630595, -0.076544002 0.01230441 -0.049277246, -0.076730162 0.013380483 -0.049374104, -0.062069759 -0.042258441 -0.047619805, -0.075676724 0.012940124 -0.048976704, -0.074216038 0.01117599 -0.047567874, -0.065143988 -0.040730789 -0.049007237, -0.075319186 0.010745421 -0.048559174, -0.075419471 0.013240814 -0.048870519, -0.075458765 0.014456496 -0.049004123, -0.074916676 0.013838485 -0.048630536, -0.061577201 -0.04192318 -0.046671778, -0.073877797 0.010707557 -0.046963111, -0.06434007 -0.040228054 -0.048411354, -0.061271608 -0.041715145 -0.045615122, -0.067409292 -0.03901577 -0.049376979, -0.073900729 0.011128545 -0.047106683, -0.074107572 0.013859585 -0.047960684, -0.074706778 0.014399856 -0.048558891, -0.063668877 -0.039808482 -0.047619835, -0.066494733 -0.038486287 -0.049006954, -0.074078336 0.014477506 -0.048049465, -0.074279875 0.015516356 -0.048408225, -0.063163787 -0.039492756 -0.046671674, -0.065674081 -0.038011447 -0.048411429, -0.073795587 0.014521241 -0.047760844, -0.073758483 0.013879031 -0.047567889, -0.062850326 -0.039296627 -0.045614883, -0.073699266 0.014799282 -0.047713175, -0.07350494 0.015354455 -0.047616705, -0.072921708 0.015232503 -0.046668708, -0.068759546 -0.036583707 -0.049376994, -0.073268935 0.014291674 -0.04696323, -0.072559997 0.015156984 -0.045611843, -0.06498903 -0.037615046 -0.047619715, -0.073445171 0.013820171 -0.047106609, 0.006574735 -0.074748322 -0.047556415, 0.005161494 -0.074552536 -0.047111735, 0.0064741671 -0.074192822 -0.046636105, 0.0078808814 -0.074314296 -0.047111511, -0.067826718 -0.036087245 -0.049006909, 0.0066923052 -0.075487196 -0.048334479, 0.0051833987 -0.074870378 -0.047572836, 0.0079144835 -0.074631244 -0.047572747, 0.0077651739 -0.073710248 -0.045596734, 0.0090854466 -0.073563904 -0.045616865, 0.0082981884 -0.074183941 -0.046968102, 0.073198229 -0.026614398 -0.049376175, -0.064473525 -0.037316561 -0.046671659, 0.00506787 -0.073944613 -0.045596465, 0.0046763122 -0.07449995 -0.046968132, 0.0036911815 -0.074030906 -0.045616746, 0.072204918 -0.026253119 -0.049006566, -0.06698969 -0.035641938 -0.048411012, 0.00111866 -0.075028434 -0.04755646, 0.0011913329 -0.07577379 -0.048334613, -0.00022241473 -0.075388685 -0.047965407, 0.0010498762 -0.074467272 -0.046636134, 0.0024484992 -0.074690789 -0.047111526, -0.00028210878 -0.075049132 -0.047572836, -0.0002810806 -0.074730352 -0.047111467, -0.064153403 -0.037131295 -0.045614854, 0.00245893 -0.075009301 -0.047572836, 0.071313977 -0.025929317 -0.048410505, 0.0023683012 -0.074080467 -0.0455966, 0.002869606 -0.074591473 -0.046968192, -0.070077613 -0.033991128 -0.049376786, -0.00033888221 -0.074117556 -0.045596525, 0.070569947 -0.025658935 -0.047619104, -0.0017227083 -0.0741027 -0.04561694, -0.066290841 -0.035270244 -0.047619492, -0.00076557696 -0.074642703 -0.046968102, -0.0043430477 -0.074911177 -0.0475564, -0.003009662 -0.074989319 -0.047572896, -0.0043157786 -0.075660363 -0.048334703, -0.002996847 -0.074670777 -0.047111616, -0.005702436 -0.075173035 -0.047965512, 0.070010126 -0.025455415 -0.046671093, -0.0043800473 -0.074345678 -0.046636239, -0.069126949 -0.033529863 -0.049006835, -0.0030412376 -0.074055791 -0.045596585, -0.0025742054 -0.074602142 -0.046968117, 0.069662586 -0.025328889 -0.045614123, -0.065765038 -0.03499037 -0.046671525, -0.0057440251 -0.07389532 -0.045596659, 0.071162999 -0.031655535 -0.049376443, -0.068273783 -0.033116132 -0.048410952, -0.0097819269 -0.074396789 -0.047556326, -0.0097863525 -0.073828861 -0.046636105, 0.070197463 -0.031226143 -0.049006686, -0.065438509 -0.034816712 -0.04561469, -0.0084346384 -0.073636696 -0.04559657, 0.069331408 -0.03084065 -0.048410907, -0.071144357 -0.031698078 -0.049376443, -0.011118516 -0.073279485 -0.04559657, -0.067561463 -0.032770708 -0.047619507, -0.049028218 -0.060517356 -0.049378023, 0.06860809 -0.030518979 -0.047619462, -0.04942669 -0.05881846 -0.049008146, -0.070178911 -0.031267941 -0.049006656, -0.050303206 -0.059942275 -0.0494477, 0.068063647 -0.030277029 -0.046671152, -0.067025542 -0.032510713 -0.046671152, -0.051110372 -0.058769464 -0.049378052, 0.067725822 -0.030126646 -0.045614451, -0.06931299 -0.030882105 -0.048410863, 0.068781406 -0.036542654 -0.049376965, -0.048874363 -0.058044434 -0.048412427, -0.066692844 -0.032349259 -0.045614496, -0.07494086 -0.003846854 -0.047552362, -0.074382186 -0.0037619621 -0.046632081, -0.068589926 -0.030559927 -0.047619388, -0.07394737 -0.0050675869 -0.045592919, 0.067848176 -0.036046669 -0.049006954, -0.074083135 -0.002363503 -0.045592606, 0.06701082 -0.035601869 -0.048411161, -0.072372034 -0.02878502 -0.049376383, -0.075022295 0.001615867 -0.04755199, -0.074458748 0.0016686767 -0.046631798, 0.066311672 -0.035230413 -0.047619671, -0.068045825 -0.030317649 -0.046671212, -0.074120164 0.00033934414 -0.045592427, 0.065785661 -0.034950942 -0.04667154, -0.071390197 -0.028394535 -0.049006656, -0.074058473 0.0030460507 -0.045592219, 0.065459251 -0.034777448 -0.0456146, -0.067708001 -0.030167028 -0.04561463, -0.074706197 0.0070699751 -0.047551885, -0.074139372 0.0070904642 -0.046631604, 0.066064581 -0.04125157 -0.049376979, -0.070509166 -0.02804406 -0.048410714, -0.073898166 0.0057443231 -0.045592204, 0.065168247 -0.040691704 -0.049007237, -0.073639125 0.008439377 -0.045591831, -0.0731823 -0.026658013 -0.04937616, 0.064363912 -0.040189534 -0.048411325, -0.069773495 -0.027751565 -0.047619298, -0.073993981 0.012486517 -0.047551394, -0.073425665 0.012474537 -0.046631202, -0.072189361 -0.026296362 -0.049006417, 0.063692525 -0.039770395 -0.047619864, -0.073282585 0.01111877 -0.045591772, -0.069220111 -0.027531445 -0.046671078, 0.063187271 -0.039454967 -0.046671778, -0.072827652 0.01378791 -0.045591697, 0.062873527 -0.039259076 -0.045614854, -0.071298555 -0.02597174 -0.048410609, 0.063025951 -0.04575932 -0.049377412, -0.068876326 -0.027394786 -0.045614451, 0.062170655 -0.045138642 -0.04900755, -0.070554435 -0.025701061 -0.04761897, -0.074280322 -0.023425534 -0.049376234, 0.061403632 -0.044581458 -0.048411742, -0.069994941 -0.025497124 -0.046671018, 0.060762912 -0.044116497 -0.047620028, -0.073272571 -0.023107499 -0.049006402, -0.069647595 -0.025370538 -0.045614034, 0.059981629 -0.043549284 -0.045615137, 0.060280934 -0.043766543 -0.046672001, -0.074863762 -0.021488369 -0.049375892, 0.059680149 -0.050044462 -0.049377382, -0.072368383 -0.022822365 -0.048410594, 0.058870345 -0.049365282 -0.049007908, -0.073848113 -0.02119641 -0.049006164, 0.058693826 -0.051197618 -0.049377665, -0.071613252 -0.022584558 -0.04761894, 0.058143944 -0.048756316 -0.048411593, -0.072936788 -0.020935103 -0.048410356, 0.057897434 -0.050502986 -0.049007788, -0.07104513 -0.022405237 -0.046670824, 0.057537228 -0.048247725 -0.047620267, -0.07217595 -0.020716727 -0.047618836, 0.057183042 -0.049879596 -0.048412025, -0.070692599 -0.022294089 -0.045614079, -0.075792283 -0.017940983 -0.049375787, 0.056586444 -0.049359277 -0.047620326, -0.071603268 -0.020552412 -0.046670571, 0.05679743 -0.047627091 -0.04561536, 0.05708088 -0.047864914 -0.046672329, -0.074763924 -0.017697424 -0.049005941, 0.056043535 -0.054085463 -0.049377859, 0.056137517 -0.048967928 -0.046672195, -0.071247846 -0.020450428 -0.045613751, 0.055283114 -0.053351685 -0.049007878, -0.076180547 -0.016213611 -0.049375549, -0.073841557 -0.017479017 -0.048410192, 0.055858791 -0.048724532 -0.045615539, 0.05479978 -0.055345371 -0.049377963, -0.075147048 -0.015993625 -0.049005926, 0.054601118 -0.052693292 -0.048411995, -0.073071137 -0.017296612 -0.047618613, 0.054056227 -0.054594353 -0.049007997, -0.074219778 -0.01579617 -0.048409998, 0.054031417 -0.052143663 -0.047620609, -0.072491542 -0.017159551 -0.046670422, 0.053389177 -0.053920761 -0.048412114, -0.073445365 -0.015631422 -0.047618523, 0.053602681 -0.051730171 -0.046672404, -0.072131529 -0.017074376 -0.045613825, 0.052832276 -0.053358182 -0.047620609, -0.076900005 -0.012360647 -0.049375519, -0.072862715 -0.015507445 -0.046670407, 0.053336576 -0.051473245 -0.045615628, 0.052134216 -0.057863235 -0.049378097, -0.075856492 -0.012192935 -0.049005598, 0.052413136 -0.0529349 -0.046672449, -0.072501063 -0.015430585 -0.045613721, 0.051426649 -0.057078019 -0.04900825, -0.077126235 -0.010860145 -0.04937534, -0.07492052 -0.012042284 -0.04840973, 0.052152976 -0.052672237 -0.045615733, 0.050613523 -0.059197783 -0.049378127, -0.07607989 -0.010712683 -0.049005464, 0.050792113 -0.056373864 -0.048412129, -0.074138969 -0.011916742 -0.047618106, 0.049926788 -0.058394611 -0.04900831, -0.075140908 -0.010580465 -0.048409805, 0.050262168 -0.05578582 -0.047620788, -0.073550791 -0.011822253 -0.046670273, 0.049310714 -0.05767408 -0.048412398, -0.074357033 -0.010470226 -0.047618046, 0.049863458 -0.055343106 -0.046672851, -0.073185608 -0.011763632 -0.045613542, -0.0737672 -0.010387123 -0.046670139, 0.048796222 -0.057072461 -0.047620729, -0.077597424 -0.0067141652 -0.049375057, 0.049615934 -0.055068493 -0.045615807, -0.073400989 -0.010335535 -0.045613274, 0.047970593 -0.061358988 -0.049378246, -0.076544523 -0.0066229999 -0.049005285, 0.048409149 -0.056619763 -0.046672881, 0.04731968 -0.060526446 -0.049008504, -0.075599939 -0.006541431 -0.048409432, 0.048168659 -0.056338549 -0.045615807, 0.046735734 -0.05977954 -0.048412368, 0.046157107 -0.062734425 -0.049378276, 0.046248153 -0.059155986 -0.047620893, 0.045530811 -0.061883286 -0.049008444, 0.045881212 -0.058686793 -0.046672806, 0.044969097 -0.061119691 -0.048412532, 0.045653492 -0.058395207 -0.04561606, 0.04449977 -0.060481906 -0.047620878, 0.04357329 -0.064555764 -0.049378335, 0.044146836 -0.060002312 -0.04667297, 0.042982101 -0.063679948 -0.049008414, 0.043927655 -0.059704512 -0.04561615, 0.042451739 -0.06289421 -0.048412576, 0.041454479 -0.065936446 -0.049378291, 0.042008877 -0.062237948 -0.047621265, 0.040892035 -0.065041751 -0.049008623, 0.041675538 -0.061744228 -0.04667291, 0.040387273 -0.06423901 -0.048412651, 0.041468814 -0.061437815 -0.04561612, 0.038963869 -0.067438081 -0.049378574, 0.039965928 -0.06356895 -0.047621176, 0.038434952 -0.066522971 -0.049008623, 0.03964889 -0.063064769 -0.046673015, -0.076242357 0.015926242 -0.049373776, 0.037960827 -0.065702096 -0.048412785, -0.075208008 0.015710264 -0.049004108, 0.039452225 -0.062751666 -0.04561609, 0.03653051 -0.068786636 -0.049378693, 0.03756474 -0.065016732 -0.047621191, 0.036034927 -0.067853034 -0.049008906, 0.037266865 -0.064501062 -0.046673194, 0.035590231 -0.067015916 -0.048412994, 0.067627773 -0.030346394 -0.045614511, 0.037081853 -0.064180896 -0.045616418, 0.065288961 -0.035096064 -0.045614555, 0.034164324 -0.069991633 -0.049378648, 0.062617332 -0.039666653 -0.045614988, 0.035219014 -0.066316813 -0.047621399, 0.059626147 -0.044034868 -0.045615107, 0.033700824 -0.069041938 -0.049008936, 0.0088558495 -0.077379465 -0.049378946, 0.0094169378 -0.076248556 -0.049009159, 0.0095464289 -0.077297404 -0.04937923, 0.0071664304 -0.077191442 -0.049282283, 0.034939498 -0.065790683 -0.046673343, 0.033285081 -0.068190128 -0.048413098, 0.0060238391 -0.077651218 -0.04937911, 0.0038784593 -0.077787921 -0.049379155, 0.034766153 -0.065464079 -0.045616478, 0.0033100992 -0.077814296 -0.049379155, 0.031411856 -0.071269438 -0.049378946, 0.0038256645 -0.076732442 -0.049009264, 0.0015963316 -0.077506974 -0.049282253, 0.032937855 -0.06747885 -0.047621369, 0.00046572089 -0.077883095 -0.04937914, -0.0018101782 -0.077863559 -0.049379289, 0.030985594 -0.070302382 -0.049009085, -0.0022527426 -0.077852145 -0.049379066, -0.0017857999 -0.076807007 -0.049009472, -0.0039819181 -0.07742101 -0.049282372, 0.032676548 -0.066943571 -0.046673194, 0.030603349 -0.069434941 -0.048413038, -0.0050945133 -0.077717885 -0.049379081, -0.0074893385 -0.077523649 -0.049379125, 0.032514274 -0.066611186 -0.045616448, -0.0078038722 -0.077492729 -0.049379095, 0.029198676 -0.072204441 -0.049378857, -0.0073876828 -0.076471776 -0.049009264, 0.030284017 -0.06871064 -0.047621414, 0.028802499 -0.07122457 -0.04900898, -0.013128296 -0.076770157 -0.049379081, -0.03274475 -0.066498265 -0.045616537, -0.032474577 -0.066630632 -0.045616493, -0.032636598 -0.066963002 -0.046673238, 0.030043736 -0.06816566 -0.046673432, -0.037228435 -0.064523131 -0.046673208, -0.037043542 -0.06420283 -0.045616359, -0.037407786 -0.063991353 -0.045616373, 0.028447077 -0.070345804 -0.048413098, -0.041638702 -0.061769098 -0.046673089, -0.041880086 -0.06115815 -0.045616314, 0.029894546 -0.067827195 -0.045616493, 0.02815026 -0.069612041 -0.047621518, 0.02612552 -0.073372334 -0.049378932, -0.077649191 -0.0060842782 -0.049375042, 0.027926877 -0.069059759 -0.046673432, 0.025770962 -0.072376654 -0.049008995, -0.077402323 -0.0043815523 -0.049278215, 0.027788296 -0.068716884 -0.045616597, -0.077819884 -0.0032440424 -0.049374923, -0.07788071 -0.0010319799 -0.0493747, -0.077885672 -0.00052629411 -0.0493747, 0.025453061 -0.071483716 -0.048413068, -0.076823816 -0.0010178685 -0.049005061, 0.024090573 -0.074065298 -0.049378857, -0.077517077 0.0011963546 -0.049277693, 0.025187492 -0.070737943 -0.047621578, -0.077852964 0.0023186803 -0.049374685, -0.077748448 0.0046557188 -0.049374387, 0.023763657 -0.073060349 -0.049009025, -0.07772474 0.0050341338 -0.049374536, -0.076693386 0.0045924634 -0.049004912, 0.024987563 -0.07017678 -0.046673506, -0.077230588 0.006768018 -0.049277708, 0.023470461 -0.072158843 -0.048413321, -0.077489242 0.007869646 -0.049374357, -0.077201396 0.010318533 -0.049374029, 0.024863601 -0.069828451 -0.045616716, -0.077167377 0.010569125 -0.049374148, -0.076153889 0.010178536 -0.04900445, 0.02322565 -0.071406066 -0.047621533, 0.02069971 -0.075083569 -0.049379051, 0.063058928 -0.039659873 -0.046671793, 0.023041263 -0.070839629 -0.046673506, 0.020418957 -0.074064791 -0.049009234, 0.060102716 -0.044011012 -0.04667215, 0.0085618049 -0.075595215 -0.048564225, 0.0092037469 -0.074522093 -0.047621727, 0.0093007833 -0.075307667 -0.048413411, 0.022927046 -0.070488065 -0.045616731, 0.0081907511 -0.075738922 -0.048635408, 0.018865168 -0.075565338 -0.049379095, 0.020167083 -0.073150948 -0.048413396, 0.018609196 -0.074540094 -0.0490091, 0.0048843622 -0.076672271 -0.049009264, 0.019956619 -0.07238774 -0.047621533, 0.0054192692 -0.075987592 -0.048635393, 0.018379703 -0.073620319 -0.048413217, 0.0048710257 -0.075922519 -0.048564062, 0.0037787557 -0.075785622 -0.048413426, 0.019798249 -0.071813598 -0.046673596, 0.0037392676 -0.074995041 -0.047621787, 0.0030480921 -0.076017454 -0.048564106, 0.018187791 -0.072852343 -0.047621578, 0.0026814342 -0.076133475 -0.048635572, 0.01970011 -0.071457073 -0.045616716, 0.015163556 -0.076394215 -0.049379051, 0.018043578 -0.072274372 -0.0466737, -0.00066316128 -0.076824814 -0.049009278, 0.01495786 -0.07535769 -0.049009293, -0.00010107458 -0.076180473 -0.048635408, 0.017953917 -0.071915507 -0.045616835, -0.00065675378 -0.076075539 -0.048564017, -0.0017637461 -0.075859249 -0.048413262, 0.013547838 -0.076697275 -0.049378991, -0.0024816394 -0.076037943 -0.048564106, 0.014773294 -0.074427933 -0.048413306, -0.001745224 -0.075067893 -0.047621742, -0.0028420836 -0.076127663 -0.048635587, 0.013364151 -0.075656563 -0.049009442, 0.014619112 -0.073651195 -0.047621876, 0.01319918 -0.074723095 -0.048413247, -0.0062073916 -0.076576546 -0.049009278, 0.014503092 -0.073067039 -0.046673626, -0.005620718 -0.075973049 -0.048635408, 0.013061494 -0.073943645 -0.047621757, -0.006180957 -0.075826958 -0.048564076, 0.014431208 -0.072704375 -0.04561685, 0.012957841 -0.073356897 -0.04667373, 0.012893528 -0.072992891 -0.045616925, -0.012950197 -0.075728506 -0.049009472, 0.0091307759 -0.073930904 -0.0466737, -0.037411615 -0.064417213 -0.046673208, -0.041864097 -0.061616629 -0.046672881, -0.046108067 -0.058508754 -0.046672687, -0.076801494 -0.0021092296 -0.049004972, -0.075876042 -0.0010052919 -0.048409179, -0.076753706 0.0034402013 -0.049004778, -0.018697456 -0.075607032 -0.049379081, -0.076305434 0.0089717656 -0.04900451, -0.018443942 -0.074581131 -0.04900901, -0.018216088 -0.07366091 -0.048413247, -0.018026114 -0.072892576 -0.047621742, -0.017883033 -0.072314262 -0.046673596, -0.017794281 -0.071955279 -0.045616835, -0.024046406 -0.074079677 -0.049379051, -0.02372025 -0.073074445 -0.04900907, -0.023427531 -0.072172865 -0.048413128, -0.023183048 -0.071419984 -0.047621563, -0.022999138 -0.070853412 -0.046673417, -0.022885025 -0.070501685 -0.045616776, -0.029155642 -0.072221801 -0.049378902, -0.028760076 -0.071241885 -0.049008965, -0.028405145 -0.070362672 -0.048413411, -0.028108716 -0.069628969 -0.047621563, 0.0037095696 -0.074400231 -0.04667379, -0.027885884 -0.069076404 -0.046673447, -0.027747363 -0.068733498 -0.045616567, -0.03412278 -0.070012093 -0.049378708, -0.033659816 -0.069062158 -0.049008846, -0.033244461 -0.068209872 -0.048412964, -0.032897577 -0.067498431 -0.047621369, -0.0009239167 -0.075201795 -0.047765791, -0.0011979491 -0.075157687 -0.047718331, -0.0017313957 -0.074472487 -0.046673849, -0.038923547 -0.067461282 -0.049378499, -0.038395554 -0.066545859 -0.049008757, 0.030878633 0.048391402 -0.0055202544, 0.032151565 0.047450215 -0.0051565468, 0.031797498 0.047648564 -0.0050434172, 0.03344959 0.046544254 -0.0051566064, 0.032851607 0.047038883 -0.005384773, 0.032639742 0.046735644 -0.0043282509, 0.041259944 0.039868519 -0.0053850412, 0.043393627 0.037534967 -0.0053853095, 0.040994048 0.039611489 -0.0043286681, 0.043113828 0.037292987 -0.0043286085, 0.033743545 0.046291038 -0.0050436258, 0.041654617 0.033752203 -0.0016235411, 0.044159785 0.032228515 -0.0019934475, 0.043306112 0.031605393 -0.0016236007, 0.033212021 0.045643404 -0.003429085, 0.04247582 0.034417376 -0.0019932389, 0.034292623 0.045097247 -0.0037153065, 0.034771904 0.045674056 -0.0055204332, 0.044290483 0.035887763 -0.0043286085, 0.042663395 0.036903307 -0.0033803284, 0.043827608 0.03551276 -0.0033804178, 0.044437855 0.029993355 -0.0016237199, 0.035069957 0.044231907 -0.0034290552, 0.035627604 0.044856951 -0.0050436258, 0.036387637 0.043880895 -0.0043282211, 0.035962626 0.044630975 -0.005156666, 0.043212369 0.035014212 -0.002589047, 0.044925347 0.032787442 -0.0025891066, 0.036623597 0.044165403 -0.0053850412, 0.054535076 0.0038300753 -0.0019949079, 0.053756863 0.0030071139 -0.0016829967, 0.053480893 0.0037559271 -0.0016252398, 0.044577569 0.036120683 -0.0053854585, 0.053889796 0.0026300251 -0.0017159581, 0.055261254 0.0015155375 -0.002345562, 0.055499911 0.0027606785 -0.0025524199, 0.045313746 0.030584499 -0.0019934773, 0.053457901 0.0014327765 -0.0015963316, 0.045565039 0.033254161 -0.0033807158, 0.05395326 0.00027684867 -0.0017160773, 0.046099618 0.031114966 -0.0025890768, 0.055567294 0.00033733249 -0.0025526285, 0.053840742 -0.00012353063 -0.0016833246, 0.046046153 0.033605337 -0.0043287277, 0.053604648 -0.00091938674 -0.0016254336, 0.054640442 -0.00030273199 -0.001981765, 0.055609196 -0.00095371902 -0.0025910139, 0.054661244 -0.00093765557 -0.0019953698, 0.045768172 0.027921245 -0.001624018, 0.053814366 -0.0016864687 -0.0016835183, 0.05391413 -0.0020720959 -0.0017162561, 0.046755865 0.031557798 -0.0033808053, 0.055529624 -0.0020726323 -0.0025525689, 0.055183783 -0.0032972246 -0.0023458302, 0.046344936 0.033823311 -0.0053855181, 0.053379551 -0.0032287985 -0.0015966594, 0.046670288 0.028471574 -0.001993686, 0.053772286 -0.0044218153 -0.0017164499, 0.055386409 -0.0044928789 -0.0025526285, 0.053625435 -0.0048126131 -0.0016834289, 0.053320527 -0.0055878609 -0.0016258359, 0.04724966 0.031891033 -0.0043288767, 0.054406792 -0.0050569028 -0.0019820482, 0.054371595 -0.0056981742 -0.0019955635, 0.055314571 -0.0057968646 -0.0025913119, 0.047479615 0.028965265 -0.002589196, 0.053463116 -0.0063671023 -0.0016835779, 0.046882853 0.026006088 -0.0016241074, 0.053529009 -0.0067587048 -0.0017165393, 0.055139542 -0.0068905205 -0.0025528222, 0.047556072 0.032097876 -0.0053856075, 0.054687634 -0.0080849081 -0.0023461282, 0.052895412 -0.0078659356 -0.0015968829, 0.048155501 0.029377833 -0.0033810139, 0.054786533 -0.0092890114 -0.0025531203, 0.053183183 -0.0090871006 -0.001716733, 0.047806948 0.026518822 -0.0019936562, 0.052630559 -0.010213882 -0.0016261041, 0.053002402 -0.0094651133 -0.0016836822, 0.053668007 -0.010415107 -0.0019958615, 0.053760201 -0.0097726434 -0.0019823164, 0.054598793 -0.010595724 -0.0025916398, 0.048664078 0.02968812 -0.004329145, 0.048635885 0.026978672 -0.0025894344, 0.047917396 0.02404651 -0.0016239882, 0.0489797 0.029880702 -0.0053856075, 0.049328417 0.027362615 -0.0033810735, 0.048861995 0.024520487 -0.0019938648, 0.049849331 0.027651682 -0.0043290257, 0.049709424 0.024945676 -0.0025895834, 0.048971102 0.021820948 -0.001624167, 0.050172597 0.027831003 -0.0053859055, 0.050417006 0.025300756 -0.0033810437, 0.049936369 0.022251099 -0.0019939244, 0.05094941 0.025568143 -0.0043292344, 0.04973954 0.020007417 -0.0016242564, 0.050802171 0.022637025 -0.0025898516, 0.051279917 0.025733888 -0.0053859055, 0.050719902 0.020401657 -0.0019941628, 0.051525414 0.022959322 -0.0033814013, 0.051599607 0.020755395 -0.002589792, 0.052069515 0.023201734 -0.0043293834, 0.050686523 0.017469913 -0.0016245544, 0.052334189 0.021051005 -0.0033814013, 0.052407369 0.023352385 -0.0053862333, 0.051685646 0.017814353 -0.0019942224, 0.052886888 0.02127333 -0.0043295026, 0.051221848 0.01583156 -0.0016244948, 0.052581936 0.018123254 -0.0025897622, 0.053229824 0.021411195 -0.0053861141, 0.052231625 0.016143441 -0.0019943118, 0.053330496 0.018381223 -0.0033815503, 0.053137109 0.016423687 -0.0025901496, 0.053893536 0.01857543 -0.0043296218, 0.052016079 0.012985826 -0.0016248226, 0.053893656 0.016657561 -0.0033815205, 0.054243252 0.018695846 -0.0053864121, 0.053041518 0.013241842 -0.0019944608, 0.054462835 0.016833499 -0.0043296516, 0.052354276 0.011547521 -0.0016248226, 0.053961322 0.01347141 -0.0025900602, 0.054816067 0.016942635 -0.0053864419, 0.053386256 0.0117753 -0.0019946098, 0.054729596 0.013663173 -0.0033819079, 0.05431217 0.01197952 -0.0025901794, -0.050145015 0.018968061 -0.0016244203, 0.055307373 0.013807461 -0.0043298006, -0.051133692 0.019342095 -0.0019941777, 0.055085063 0.01214996 -0.0033819675, -0.052020252 0.01967752 -0.0025897473, 0.052950069 0.0084029138 -0.001624912, -0.052760914 0.019957721 -0.0033815503, 0.055666238 0.013897076 -0.0053867102, -0.053318039 0.020168528 -0.0043296367, 0.055666819 0.012278363 -0.0043300688, -0.04840751 0.023044482 -0.0016240329, 0.053993717 0.0085685402 -0.0019948184, -0.05366385 0.02029939 -0.0053864121, 0.053128913 0.0071848035 -0.0016250312, 0.056027859 0.01235792 -0.0053869188, -0.049361661 0.02349861 -0.0019938499, 0.054930076 0.0087171048 -0.0025903881, -0.050217614 0.023905888 -0.0025895387, 0.05417636 0.0073264092 -0.0019946992, -0.050932363 0.024246454 -0.0033813566, 0.055712014 0.0088411421 -0.0033820868, -0.051470384 0.024502501 -0.0043293536, -0.046339318 0.026963115 -0.0016237944, 0.055115685 0.0074535161 -0.0025904477, 0.056300372 0.0089345127 -0.004330188, -0.051804274 0.024661496 -0.0053860247, -0.047252595 0.027494743 -0.0019936115, 0.05590032 0.0075594634 -0.0033819675, -0.04807198 0.027971372 -0.0025894046, 0.056665525 0.0089926869 -0.0053868592, 0.056490526 0.0076394677 -0.0043300986, -0.048756406 0.028369561 -0.0033810139, -0.049271271 0.028669134 -0.0043290108, 0.056857109 0.0076890141 -0.0053870827, 0.055480763 0.0038963109 -0.0025908351, -0.049590707 0.028855205 -0.0053859502, 0.056270555 0.0039519966 -0.0033823252, 0.056864709 0.0039936155 -0.0043305457, 0.057233617 0.0040196925 -0.0053871721, -0.041269243 0.034222618 -0.0016233474, -0.040472612 0.035161123 -0.0016235262, -0.041270286 0.035854235 -0.0019931346, -0.042082801 0.034897059 -0.001993224, -0.042812452 0.0355023 -0.0025890172, -0.041986093 0.036476016 -0.0025888532, -0.042583659 0.036995322 -0.0033804178, -0.043421939 0.036007673 -0.0033804923, -0.038302243 0.037513569 -0.0016231984, -0.043033391 0.037386 -0.0043285787, -0.043880507 0.036388054 -0.0043286383, -0.039057195 0.038253158 -0.0019932538, -0.03725405 0.038554624 -0.001623258, -0.04331252 0.037628502 -0.005385384, -0.04416506 0.03662388 -0.0053855926, -0.039734557 0.038916484 -0.0025886595, 0.055375993 -0.010746688 -0.0033831447, -0.037988394 0.039314821 -0.0019930899, 0.05596076 -0.010860145 -0.0043312013, -0.040300101 0.039470464 -0.0033804178, 0.056323722 -0.010930553 -0.0053880215, -0.03864713 0.039996475 -0.0025885403, -0.046152294 0.027281612 -0.0016237944, -0.040725738 0.039887354 -0.0043284744, -0.045754701 0.028630435 -0.001720503, -0.035073608 0.040548459 -0.0016231239, -0.044985428 0.029165477 -0.0016236901, -0.043954298 0.030697629 -0.0016238391, -0.044820726 0.031302825 -0.0019934028, -0.04367055 0.031100065 -0.0016236007, -0.039197326 0.040565878 -0.0033803433, -0.04098992 0.040146083 -0.0053853095, -0.035765037 0.041347668 -0.0019929558, -0.043184713 0.032377094 -0.0017203093, -0.042348072 0.032878175 -0.0016235709, -0.039611056 0.040994272 -0.0043283701, -0.004019469 0.057234034 -0.0053841472, -0.003493458 0.057268426 -0.0053841472, -0.003993392 0.056865096 -0.0043275952, -0.033751979 0.041654885 -0.0016230792, -0.036385208 0.04206489 -0.0025884509, -0.0019987226 0.057243288 -0.0050230026, -0.039868116 0.041260153 -0.0053851753, -0.00099214911 0.057366431 -0.0053842664, 0.00098413229 0.057366595 -0.0053842068, -0.00033330917 0.057374075 -0.0053841174, -0.034417316 0.042476162 -0.0019928366, 0.0013794601 0.057358384 -0.005384177, 0.00097769499 0.056996748 -0.004327476, -0.036903247 0.042663723 -0.0033802539, -0.035014242 0.043212667 -0.0025885254, 0.0029104054 0.057204187 -0.0050231218, 0.0038799942 0.057243437 -0.005384326, -0.037292808 0.043114036 -0.0043281913, 0.0059801042 0.057062492 -0.0053842068, 0.0045808554 0.057191685 -0.0053841174, -0.031605437 0.043306217 -0.0016230494, 0.0062422454 0.057034373 -0.0053843558, 0.005941689 0.056694567 -0.0043274164, -0.035512596 0.043827876 -0.0033799559, -0.037534714 0.04339388 -0.0053849965, 0.0077981651 0.05674471 -0.0050231516, 0.008724004 0.056707785 -0.0053843558, -0.032228336 0.044159904 -0.0019927472, 0.010930657 0.056324214 -0.005384326, 0.0094613135 0.056589633 -0.0053842664, 0.027494162 0.047252849 -0.0019924939, 0.027281389 0.046152428 -0.0016228855, 0.026962891 0.046339259 -0.0016228259, -0.035887614 0.044290543 -0.0043281913, 0.028630018 0.045754924 -0.0017194748, -0.029993132 0.044438258 -0.0016229451, -0.032787308 0.044925839 -0.0025885254, 0.029165342 0.044985577 -0.0016229153, 0.030697435 0.043954402 -0.0016230345, 0.031099856 0.043670803 -0.0016230345, -0.036120385 0.044577911 -0.0053848624, 0.031302407 0.04482092 -0.0019928217, -0.030584231 0.045314178 -0.0019927472, 0.032376826 0.043184802 -0.0017196238, -0.033253908 0.045565218 -0.003379941, 0.032878071 0.042347983 -0.0016230941, 0.03422229 0.041269377 -0.0016228855, 0.057268158 0.0034936517 -0.0053871721, -0.031114697 0.046099856 -0.0025884509, -0.033605054 0.046046451 -0.0043281764, 0.057242945 0.0019987673 -0.005026117, -0.027921185 0.045768261 -0.0016227812, -0.031557754 0.046756044 -0.0033799112, 0.057366073 0.00099244714 -0.0053876638, 0.057373732 0.00033356249 -0.0053873956, 0.057366252 -0.00098396838 -0.0053875297, 0.057358041 -0.001379028 -0.0053875297, 0.056996509 -0.00097753108 -0.0043306351, -0.033823177 0.046345308 -0.005384922, -0.028471559 0.046670541 -0.0019925982, 0.057203695 -0.0029103458 -0.0050264299, 0.057243153 -0.0038796812 -0.0053875446, -0.031890795 0.047249928 -0.0043279976, 0.057062119 -0.0059800595 -0.0053877383, 0.057191432 -0.0045806468 -0.0053877085, -0.028965309 0.047479957 -0.0025882274, 0.057034031 -0.0062420815 -0.0053877234, 0.056694224 -0.0059413314 -0.0043308288, -0.026005998 0.046883106 -0.0016229004, 0.056744456 -0.0077979714 -0.0050266683, -0.032097861 0.047556534 -0.0053847581, 0.056707576 -0.0087238401 -0.0053879619, -0.029377639 0.04815568 -0.0033798367, 0.056589097 -0.0094610453 -0.0053878427, -0.026518553 0.047807142 -0.0019925386, -0.047598824 0.028383121 -0.0024387538, -0.029687867 0.048664242 -0.0043280423, -0.047358602 0.028585047 -0.0023671687, -0.026978433 0.048636138 -0.0025881529, -0.024046302 0.047917619 -0.0016228259, -0.047047868 0.029842108 -0.0026682615, -0.045353264 0.030526236 -0.0019934624, -0.029880419 0.048980102 -0.0053846687, -0.027362332 0.04932858 -0.0033799708, -0.046136856 0.030517787 -0.0023671687, -0.045963004 0.030962065 -0.0024387538, -0.045597896 0.031845644 -0.0025891662, -0.024520308 0.048862323 -0.00199233, -0.046247065 0.032298878 -0.0033806115, -0.045075834 0.032239884 -0.0024386197, -0.027651623 0.049849585 -0.0043278635, -0.044811532 0.032432482 -0.0023669302, -0.024945363 0.049709678 -0.0025881231, -0.021820843 0.04897137 -0.0016225576, -0.044405714 0.033647865 -0.0026680082, -0.027830869 0.050172925 -0.0053846538, -0.042638227 0.034216136 -0.0019931644, -0.025300637 0.050417244 -0.003379643, -0.04343307 0.034256756 -0.0023667961, -0.043231562 0.034674034 -0.0024384856, -0.02225101 0.049936578 -0.0019923449, -0.0255678 0.050949678 -0.0043278039, -0.0039517879 0.056270897 -0.0033793449, -0.0032996833 0.056463644 -0.0035780966, -0.0038962364 0.055480957 -0.0025877655, -0.0029721856 0.056553587 -0.0036803484, -0.020007223 0.049739659 -0.0016224384, -0.022636935 0.050802648 -0.002588138, -0.0016494989 0.056306288 -0.0032829046, -0.02573368 0.051280156 -0.0053844303, -0.020401552 0.050720334 -0.0019923598, 0.00095400214 0.055609569 -0.0025878549, -1.1205673e-05 0.056559935 -0.0035782456, 0.0009676218 0.056401119 -0.0033792853, -0.022959262 0.051525697 -0.0033796132, -0.00050258636 0.056629241 -0.003680259, -0.00050508976 0.056918666 -0.0041604936, -0.020755395 0.051599875 -0.0025879592, -0.00066700578 0.057103813 -0.0045546293, -0.023201585 0.052069992 -0.0043279529, -3.9935112e-06 0.057005167 -0.0043275952, -0.017469764 0.050686702 -0.0016226619, -0.00011327863 0.057154581 -0.0046701133, -0.021050945 0.052334428 -0.0033795238, 0.0003233254 0.057004139 -0.0043273568, -0.023352131 0.052407816 -0.0053844005, 0.0016049445 0.056537196 -0.0035780966, -0.01781401 0.051685885 -0.0019925684, 0.0019248426 0.056598812 -0.003680259, -0.021273166 0.052886963 -0.0043274462, 0.0032355785 0.056237534 -0.0032829344, -0.015831307 0.051222011 -0.0016224533, -0.018123016 0.052582145 -0.0025878996, -0.021411061 0.053230211 -0.0053846687, 0.0057970881 0.055314705 -0.0025877357, 0.0048895776 0.056348294 -0.0035781264, 0.005879432 0.056102186 -0.0033794045, 0.0044142306 0.056749418 -0.0041604638, 0.0043917596 0.056461006 -0.0036803484, -0.016143501 0.052231818 -0.0019924641, -0.018381029 0.0533306 -0.0033796281, 0.004239738 0.056950003 -0.0045548081, 0.0048990846 0.056794301 -0.0043275058, -0.016423434 0.053137645 -0.002588138, 0.0047958195 0.056952879 -0.0046699941, -0.018575013 0.053893849 -0.0043276399, 0.0052468777 0.056763008 -0.0043272674, -0.012985617 0.052016377 -0.0016225576, 0.0064978004 0.056185365 -0.0035782158, -0.016657352 0.053893998 -0.0033795089, 0.0068072677 0.056220844 -0.003680259, -0.018695593 0.054243624 -0.0053844303, 0.0080960095 0.055745661 -0.003282845, -0.0132415 0.053041786 -0.0019921958, -0.016833231 0.054463133 -0.004327476, -0.011547491 0.052354604 -0.0016226768, 0.010595948 0.054599121 -0.0025877953, 0.0097536743 0.055712625 -0.0035782456, 0.010746837 0.055376291 -0.0033796132, -0.013471216 0.053961545 -0.0025879145, 0.0093002617 0.05615595 -0.0041605234, 0.0092530549 0.055870563 -0.0036803484, -0.016942233 0.054816425 -0.0053843111, 0.0091151893 0.056375504 -0.0045548081, -0.011774957 0.053386435 -0.0019921958, 0.0097658336 0.056162313 -0.0043275058, 0.0096694231 0.056330726 -0.0046701431, -0.013663113 0.054729685 -0.0033795834, 0.01013118 0.056097731 -0.0043275356, 0.010860294 0.055960968 -0.004327476, -0.011979297 0.054312289 -0.0025877655, 0.027971163 0.048072174 -0.0025883019, 0.028382793 0.047598928 -0.0024377108, 0.028369248 0.048756555 -0.0033799112, 0.028584659 0.047358781 -0.0023662448, -0.013807416 0.055307746 -0.0043272674, -0.012149677 0.055085331 -0.0033795089, 0.029841766 0.047048002 -0.0026671886, -0.0084026605 0.052950263 -0.0016225576, -0.013896927 0.055666581 -0.0053843558, 0.030525848 0.045353293 -0.0019925535, -0.012278035 0.055667162 -0.0043274164, 0.030517414 0.046137199 -0.002366215, 0.031845361 0.045598239 -0.0025884807, 0.030961931 0.045963258 -0.002437979, 0.032298669 0.046247184 -0.0033800304, -0.0085683763 0.05399403 -0.001992166, 0.032239586 0.045076087 -0.0024378002, -0.0071846247 0.053129271 -0.0016225576, 0.032432303 0.044811696 -0.002366364, -0.012357697 0.056028441 -0.0053842217, 0.033647716 0.044405922 -0.0026672781, -0.0087169409 0.054930374 -0.0025878549, -0.0073262751 0.054176629 -0.0019921958, 0.034215942 0.042638391 -0.0019927621, 0.034896702 0.042082995 -0.0019928217, -0.0088411868 0.055712447 -0.0033795238, 0.034256324 0.043433264 -0.0023662746, 0.034673899 0.043231592 -0.002437979, -0.0074532628 0.055116072 -0.0025878847, 0.035502017 0.042812601 -0.0025883913, 0.036007389 0.043421984 -0.0033801496, -0.0089344382 0.056300446 -0.0043272972, 0.056463242 0.0032999814 -0.0035811514, 0.056553006 0.0029722303 -0.0036833584, -0.0075593591 0.055900797 -0.0033793747, -0.0037557781 0.053480968 -0.0016225278, 0.056306019 0.001649648 -0.0032857805, -0.0089924186 0.056665897 -0.0053843707, -0.0076394081 0.056490988 -0.0043275654, 0.056559697 1.1414289e-05 -0.0035813302, 0.056400761 -0.00096733868 -0.0033825636, -0.0038298368 0.0545353 -0.0019921362, 0.056918383 0.00050516427 -0.0041637123, 0.056628898 0.00050269067 -0.0036834627, -0.0076887757 0.056857511 -0.0053842962, 0.057103515 0.00066711009 -0.0045578182, 0.057004854 4.1872263e-06 -0.0043306351, 0.057154268 0.00011359155 -0.004673332, 0.057003886 -0.00032308698 -0.004330799, 0.056536868 -0.0016049594 -0.0035814643, 0.05659844 -0.0019244999 -0.0036834925, 0.056237355 -0.0032352805 -0.0032863766, 0.056347966 -0.0048894435 -0.003581658, 0.056101739 -0.0058793277 -0.0033828765, 0.056749091 -0.0044139326 -0.0041638017, 0.05646047 -0.0043915361 -0.0036836863, 0.056949735 -0.0042394847 -0.0045580417, 0.056793928 -0.0048989505 -0.0043309927, 0.056952775 -0.0047954917 -0.0046735406, 0.056762815 -0.0052466094 -0.0043309182, 0.056185186 -0.0064975023 -0.0035815984, 0.056220606 -0.0068071038 -0.0036837161, 0.055745244 -0.0080959201 -0.0032866746, 0.055712327 -0.0097535402 -0.0035818666, 0.056155547 -0.0093002915 -0.0041641146, 0.055870071 -0.0092528611 -0.0036838204, 0.056375295 -0.0091149956 -0.0045582652, 0.056162015 -0.0097656399 -0.0043311566, 0.056330517 -0.0096693337 -0.0046739131, 0.056097388 -0.010130972 -0.0043311715, -0.048237443 0.029317379 -0.0034298748, 0.010214031 0.052630886 -0.0016224682, 0.014762238 0.051540375 -0.0016223192, -0.047780111 0.03044346 -0.0037161261, 0.010415345 0.053668275 -0.0019922853, 0.015053242 0.052556366 -0.0019923151, -0.046984807 0.031285733 -0.0034298897, -0.046735406 0.032640055 -0.0043287426, 0.015314266 0.053467661 -0.0025879145, -0.045643285 0.033212408 -0.0034298599, 0.015532166 0.054228976 -0.0033795536, -0.045097142 0.034292802 -0.0037160665, 0.015696332 0.054801673 -0.0043276548, -0.044231728 0.035070136 -0.0034296662, 0.018967941 0.050145134 -0.0016226172, -0.0027605891 0.055500165 -0.0025493801, 0.015798107 0.055156976 -0.0053843558, 0.019341812 0.051133767 -0.0019922853, -0.0015152693 0.055261642 -0.0023425221, -0.00033712387 0.055567682 -0.0025492907, 0.019677311 0.052020416 -0.0025879443, 0.0020727515 0.055530161 -0.0025491118, 0.00093770027 0.054661587 -0.0019922256, 0.019957393 0.052760988 -0.0033796728, 0.020168081 0.053318277 -0.004327774, 0.0032973886 0.055183992 -0.0023423433, 0.023044199 0.048407733 -0.0016226768, 0.0044931173 0.055386543 -0.0025493205, 0.020298868 0.053663999 -0.0053844452, 0.0068906546 0.055139899 -0.0025492907, 0.0056980848 0.054371759 -0.0019922256, 0.023498297 0.049361765 -0.0019924343, 0.0080851316 0.054687858 -0.0023424923, 0.023905829 0.050217792 -0.0025882721, 0.0092892647 0.054786921 -0.0025492609, 0.024246052 0.050932735 -0.0033797026, 0.02931717 0.048237517 -0.0034288168, 0.024502099 0.051470593 -0.0043278039, 0.02866888 0.049271464 -0.0043278337, 0.030443221 0.04778038 -0.0037151575, 0.024661213 0.051804453 -0.0053845644, 0.031285495 0.046984941 -0.0034290552, 0.028854877 0.049591079 -0.0053846538, 0.035161108 0.040472552 -0.0016231239, -0.049149096 0.02948916 -0.0051575899, -0.048921689 0.029801801 -0.0050444305, 0.035854101 0.041270614 -0.0019929409, -0.048391044 0.030879036 -0.005521208, -0.04764846 0.031797975 -0.0050442219, 0.036475688 0.041986048 -0.0025885999, -0.047449887 0.032151967 -0.0051573664, -0.047038615 0.032851875 -0.0053855628, -0.046544045 0.033449829 -0.0051571727, 0.036994934 0.042583823 -0.0033802092, -0.0462908 0.033743933 -0.0050441921, 0.037513331 0.038302317 -0.0016232431, -0.045673832 0.034772262 -0.0055210292, -0.044856817 0.035627976 -0.0050440729, 0.037385747 0.043033376 -0.0043283105, -0.044630796 0.035963252 -0.0051572323, 0.038252756 0.039057449 -0.0019930005, -0.0030070841 0.053756997 -0.0016800761, 0.038554594 0.037254244 -0.0016232729, -0.0026300251 0.053890064 -0.0017132163, 0.037628248 0.043312699 -0.0053850114, -0.0014326274 0.053458229 -0.0015933812, 0.038916215 0.039734721 -0.0025885403, -0.00027692318 0.053953454 -0.0017132461, 0.039314434 0.037988499 -0.0019929409, 0.00012367964 0.053840995 -0.0016801059, 0.00091961026 0.053604946 -0.0016224086, 0.039470136 0.040300325 -0.003380239, 0.0003029108 0.054640725 -0.0019786656, 0.039996415 0.038647205 -0.0025886893, 0.0016864836 0.053814769 -0.0016802549, 0.039887056 0.040725946 -0.0043283999, 0.0020723641 0.053914353 -0.0017130375, 0.040548101 0.035073653 -0.0016235411, 0.0032289624 0.053379714 -0.0015932918, 0.0044218898 0.053772628 -0.0017130971, 0.040565535 0.039197534 -0.003380537, 0.0048126578 0.053625643 -0.0016800463, 0.0055880547 0.053320795 -0.0016224086, 0.040145814 0.040990055 -0.0053851306, 0.0050571263 0.054406971 -0.0019787848, 0.041347459 0.035765246 -0.0019931197, 0.006367296 0.05346325 -0.0016803741, 0.0067587495 0.053529039 -0.0017132759, 0.042064622 0.036385328 -0.0025888383, 0.0078659952 0.052895814 -0.0015934408, 0.0090872049 0.053183272 -0.0017131269, 0.009465158 0.053002566 -0.0016803145, 0.009772867 0.053760454 -0.001978755, 0.029488817 0.04914926 -0.0051562786, 0.029801384 0.048921987 -0.005043447, 0.053840682 -0.00012385845 0.0016831458, 0.053953171 0.00027669966 0.0017158687, 0.054640427 -0.00030308962 0.0019815862, 0.053604618 -0.00091971457 0.0016252697, 0.041347519 0.035765022 0.0019972324, 0.042475775 0.034417197 0.0019969344, 0.042064518 0.036385134 0.0025929511, 0.043212399 0.035014004 0.0025927126, 0.053814381 -0.0016867071 0.0016830266, 0.054661334 -0.00093790889 0.0019949973, 0.046344846 0.033822834 0.005389303, 0.047556147 0.032097355 0.0053890944, 0.053914055 -0.0020723045 0.0017158091, 0.055529773 -0.0020729899 0.0025520325, 0.043827504 0.035512388 0.0033842623, 0.045565113 0.03325367 0.0033843219, 0.044290394 0.035887346 0.0043325126, 0.055183664 -0.0032973439 0.0023451149, 0.053379446 -0.0032291114 0.0015961528, 0.046046138 0.033604905 0.0043325722, 0.041654587 0.03375189 0.0016270876, 0.04054831 0.035073578 0.0016271472, 0.055314437 -0.0057971627 0.0025906265, 0.054406688 -0.0050571263 0.001981318, 0.05437161 -0.0056982934 0.0019949377, 0.053320482 -0.0055880398 0.0016249865, 0.05538632 -0.0044932067 0.0025520325, 0.04724969 0.031890661 0.0043323934, 0.053772211 -0.0044219345 0.0017156601, 0.044925541 0.032787099 0.0025927424, 0.053625196 -0.0048128963 0.0016828179, 0.053462923 -0.0063674003 0.0016826838, 0.046755925 0.031557336 0.0033842027, 0.05352883 -0.0067587048 0.0017155707, 0.044159725 0.032228187 0.0019969642, 0.055139586 -0.0068908185 0.0025518239, 0.054687768 -0.0080851018 0.0023450553, 0.052895486 -0.0078661442 0.0015957803, 0.048979759 0.029880136 0.0053889155, 0.054786444 -0.0092895031 0.0025515556, 0.053760171 -0.0097729564 0.0019812137, 0.054598674 -0.010596022 0.0025903136, 0.046099663 0.031114593 0.0025927424, 0.053668052 -0.01041548 0.0019946545, 0.043306068 0.031605273 0.0016269684, 0.053182989 -0.0090872794 0.0017154366, 0.048664063 0.029687539 0.0043320656, 0.052630588 -0.01021412 0.0016245842, 0.053002477 -0.0094653219 0.0016824305, 0.045313835 0.030584231 0.0019968748, 0.048155546 0.029377386 0.0033840835, 0.050172657 0.027830482 0.0053890347, 0.0444379 0.029993027 0.0016269386, 0.047479659 0.028965071 0.002592653, 0.049849346 0.027651265 0.0043319464, 0.046670198 0.02847144 0.0019969046, 0.049328446 0.027362302 0.0033838749, 0.051279932 0.025733337 0.0053886473, 0.045768127 0.027921185 0.001626879, 0.04863596 0.026978239 0.0025924146, 0.050949484 0.025567442 0.0043319464, 0.047806978 0.026518509 0.0019966662, 0.05041714 0.025300309 0.0033839047, 0.052407384 0.023351774 0.0053885877, 0.046882927 0.02600576 0.00162673, 0.049709335 0.024945527 0.0025921464, 0.0520695 0.023201376 0.0043318272, 0.04886198 0.024520382 0.0019963682, 0.053229883 0.021410882 0.0053884983, 0.051525488 0.02295889 0.0033837557, 0.047917292 0.024046391 0.001626581, 0.052886724 0.021272764 0.0043317676, 0.050802335 0.022636786 0.0025920868, 0.052334234 0.021050557 0.0033834577, 0.049936235 0.022250995 0.0019965768, 0.054243147 0.01869528 0.0053884387, 0.051599652 0.020755365 0.0025918484, 0.048970953 0.021820754 0.0016264319, 0.053893551 0.018574715 0.0043315887, 0.05072014 0.020401388 0.0019962788, 0.054816142 0.01694186 0.0053882599, 0.053330377 0.01838088 0.0033834875, 0.04973954 0.020007074 0.0016262829, 0.054462776 0.016832903 0.0043314695, 0.052581891 0.018123031 0.0025919974, 0.05389379 0.016656846 0.0033833683, 0.051685482 0.017813981 0.0019961596, 0.055666253 0.013896421 0.0053882301, 0.053137317 0.016423285 0.0025919676, 0.050686479 0.017469659 0.0016262829, 0.055307448 0.013807014 0.0043313503, 0.052231595 0.016143396 0.0019960105, 0.056027979 0.012357548 0.0053879619, 0.054729506 0.0136628 0.0033832192, 0.051221758 0.015831411 0.0016264021, 0.055666864 0.012277871 0.0043310225, 0.053961322 0.013471067 0.0025916398, 0.055085212 0.012149543 0.0033832192, 0.053041503 0.013241395 0.0019958615, 0.054311946 0.011979073 0.0025916398, 0.056665629 0.008992061 0.005387634, -0.053663969 0.020298794 0.0053886324, 0.052016139 0.012985602 0.0016259849, -0.053317979 0.020167857 0.0043315738, 0.053386286 0.011775076 0.0019959211, 0.056300357 0.0089340061 0.0043310523, -0.052760765 0.019957185 0.003383562, -0.052020356 0.019677266 0.0025918931, 0.056857064 0.0076884478 0.0053878427, 0.052354142 0.011547476 0.0016258359, -0.051133558 0.019341856 0.001996249, 0.055712193 0.0088406056 0.0033830404, -0.051804349 0.02466087 0.0053886026, 0.056490704 0.0076389015 0.0043308437, -0.05014509 0.018967867 0.0016263872, 0.054930091 0.008716777 0.0025913715, -0.05147028 0.024502024 0.004332006, 0.055900306 0.0075591207 0.0033830106, -0.050932571 0.024246037 0.0033838451, 0.053993747 0.0085680932 0.0019955933, -0.050217673 0.023905769 0.0025922507, 0.055115804 0.0074532777 0.0025912821, -0.049361765 0.023498222 0.001996398, 0.057233527 0.0040191412 0.0053873956, -0.049590796 0.028854728 0.0053889602, 0.05295004 0.008402586 0.0016257465, -0.048407406 0.023044124 0.0016266108, 0.05417636 0.0073261708 0.0019955635, 0.056864783 0.0039931685 0.0043308139, -0.049271196 0.028668627 0.0043322146, -0.048756436 0.028369114 0.003384158, 0.053129017 0.0071845502 0.0016256869, 0.056270525 0.0039515048 0.0033827126, -0.04807201 0.027970985 0.0025924891, 0.055480778 0.0038962811 0.0025911629, -0.047252804 0.027494356 0.0019967556, 0.054534942 0.0038297474 0.0019955933, -0.046339363 0.026962936 0.0016268492, 0.053480834 0.0037557036 0.0016254783, -0.043312579 0.037628025 0.0053894222, -0.044165149 0.036623433 0.0053894222, -0.043033391 0.037385494 0.0043327212, -0.043880552 0.036387444 0.004332453, 0.056323797 -0.010931253 0.0053866953, -0.042583689 0.036994919 0.0033844858, -0.043422043 0.03600724 0.0033844709, -0.041985944 0.036475718 0.0025928617, 0.055960745 -0.010860592 0.0043297559, -0.042812496 0.035501897 0.0025928468, -0.04099001 0.040145636 0.005389601, 0.055376023 -0.010747015 0.0033819526, -0.042082891 0.034896925 0.001997143, -0.041270316 0.035853937 0.0019972473, -0.040725842 0.039886937 0.0043326914, -0.039868206 0.041259736 0.005389452, -0.041269317 0.03422223 0.0016272962, -0.040472522 0.035160974 0.0016272366, -0.046152383 0.027281582 0.0016268939, -0.040300176 0.039469987 0.0033847243, -0.04575479 0.028630108 0.001723811, -0.039610937 0.04099372 0.0043326318, -0.039734483 0.038916335 0.0025931448, -0.044985533 0.029165283 0.001627028, -0.043954268 0.03069748 0.001627028, -0.04367049 0.031099856 0.0016268492, -0.044820681 0.031302512 0.0019969195, -0.039197385 0.040565655 0.0033846498, -0.03905721 0.038252994 0.0019973069, -0.043184727 0.032376841 0.0017239898, -0.042347997 0.032878071 0.0016272068, -0.037534729 0.043393165 0.0053896606, -0.0040193796 0.057233408 0.0053906441, -0.0034935772 0.057268053 0.0053904951, -0.0039935708 0.056864515 0.0043338537, -0.038647056 0.039996326 0.0025929064, -0.0019985735 0.057242647 0.0050292611, -0.038302243 0.037513584 0.001627326, -0.00099217892 0.057365775 0.0053906143, -0.037292808 0.043113664 0.0043328404, -0.037988439 0.039314464 0.0019973963, -0.00033348799 0.057373539 0.0053905547, 0.00098398328 0.057366148 0.0053905249, 0.000977844 0.056996107 0.0043338537, 0.0013792217 0.057357892 0.0053905845, -0.03612043 0.044577524 0.0053897947, -0.036903113 0.042663217 0.0033848435, 0.0029105246 0.057203621 0.0050293207, -0.03725408 0.038554564 0.0016274303, 0.0038800836 0.05724299 0.0053905547, -0.035887733 0.044290245 0.0043329298, 0.0045805573 0.057191446 0.0053906143, 0.005980134 0.057061911 0.0053905547, 0.0062423944 0.057033777 0.0053904951, -0.036385044 0.042064533 0.0025933385, 0.005941689 0.056694165 0.0043337643, -0.035512537 0.043827355 0.0033847541, 0.0077981353 0.056744337 0.0050290823, -0.035764948 0.041347653 0.001997456, 0.0087239742 0.056707337 0.0053905845, 0.0094614029 0.056588992 0.0053905845, 0.010930687 0.056323558 0.0053904057, -0.033823133 0.046344683 0.0053897351, 0.027281374 0.046152309 0.001627773, 0.026962906 0.046339124 0.0016277432, 0.027494356 0.047252536 0.0019978881, -0.035014212 0.043212414 0.0025933087, 0.028630137 0.045754641 0.0017245114, -0.035073534 0.04054825 0.0016275048, 0.029165402 0.044985473 0.0016278923, -0.033605009 0.046046078 0.0043329597, 0.030697539 0.043954298 0.0016278028, 0.031099811 0.04367052 0.0016278028, 0.031302676 0.044820681 0.0019977391, -0.034417376 0.042475894 0.0019976348, 0.032376796 0.043184489 0.001724571, -0.032097831 0.04755576 0.0053901225, 0.032878041 0.042347819 0.0016275942, -0.033254072 0.045564994 0.0033850521, 0.03422229 0.041269168 0.0016277432, 0.057268202 0.0034931451 0.0053874552, -0.033752069 0.041654706 0.0016275793, 0.057243019 0.0019983053 0.0050260127, -0.031890914 0.047249258 0.0043329895, -0.032787114 0.044925466 0.0025933683, 0.057366088 0.00099189579 0.005387336, 0.057373792 0.00033302605 0.0053872764, -0.031557471 0.046755672 0.003385216, 0.057366058 -0.00098454952 0.005387187, 0.056996256 -0.00097806752 0.0043303967, 0.057358027 -0.0013796985 0.005387187, -0.032228276 0.044159755 0.0019975901, 0.057203934 -0.0029108822 0.005025804, -0.029880449 0.048979476 0.0053900927, -0.031114817 0.046099603 0.0025933683, 0.057243407 -0.0038803369 0.0053872466, 0.057191327 -0.0045810342 0.0053870678, 0.057062134 -0.0059805363 0.0053868592, -0.031605378 0.043306157 0.0016279072, 0.057034105 -0.006242469 0.0053868443, 0.056694239 -0.0059418976 0.0043301731, -0.029687852 0.048663661 0.0043333173, 0.056744531 -0.0077984333 0.0050256103, -0.030584276 0.04531382 0.0019975603, -0.029377609 0.048155412 0.0033849776, 0.056707531 -0.0087244362 0.0053866357, 0.056589082 -0.0094615221 0.0053868294, -0.027830705 0.050172329 0.0053901225, -0.047598839 0.028382912 0.0024418384, -0.029993206 0.044438064 0.0016278028, -0.047358632 0.028584823 0.0023703426, -0.028965309 0.047479689 0.0025935471, -0.027651504 0.049849063 0.0043333769, -0.047047839 0.029841796 0.002671361, -0.046136916 0.030517489 0.0023706704, -0.028471678 0.046670422 0.0019977987, -0.04559806 0.031845361 0.0025926381, -0.045963019 0.030961931 0.0024418831, -0.046247065 0.032298476 0.0033842325, -0.045353293 0.030525982 0.0019969046, -0.027362585 0.049328282 0.0033852607, -0.045075968 0.032239705 0.0024420321, -0.025733799 0.051279843 0.0053902268, -0.044811502 0.032432333 0.0023706406, -0.02792117 0.045768112 0.0016279221, -0.026978537 0.048635975 0.0025935173, -0.025567725 0.050949126 0.0043332428, -0.044405699 0.033647746 0.0026714951, -0.043432906 0.034256384 0.0023706257, -0.026518688 0.047807097 0.0019978136, -0.043231428 0.03467384 0.0024423301, -0.042638227 0.034215823 0.0019970238, -0.025300682 0.050416917 0.0033852011, -0.023352161 0.052407146 0.0053902566, -0.0039517879 0.056270406 0.0033856034, -0.0032996535 0.056463093 0.0035842359, -0.0038963258 0.055480942 0.0025938451, -0.026005998 0.046882898 0.0016278774, -0.0029722154 0.056552932 0.0036866367, -0.024945527 0.049709499 0.0025937855, -0.00066700578 0.05710341 0.0045607984, -0.023201555 0.052069321 0.0043334365, -0.0016495287 0.056305915 0.0032892227, -0.024520382 0.0488621 0.0019978881, -0.00011345744 0.057154134 0.0046763122, -0.021410987 0.053229585 0.0053904355, -0.00050514936 0.056918249 0.0041667521, -0.022959203 0.05152525 0.0033851713, -4.0829182e-06 0.057004631 0.0043338239, -0.00050246716 0.056628779 0.0036864281, -0.024046347 0.04791747 0.0016278774, 0.00032329559 0.057003736 0.0043338835, 0.0009676218 0.056400612 0.0033857226, -0.021273121 0.052886635 0.0043334365, -1.1116266e-05 0.056559429 0.0035842657, 0.00095400214 0.055609226 0.0025940537, -0.022636935 0.050802231 0.0025936663, 0.0016050637 0.056536824 0.0035844147, -0.021050841 0.052334011 0.0033852458, 0.0019249916 0.056598276 0.0036864877, -0.02225095 0.049936324 0.0019980073, 0.0042397678 0.05694972 0.004560858, -0.018695772 0.054243073 0.0053905249, 0.0047957599 0.05695273 0.0046766102, -0.020755395 0.051599577 0.0025936812, 0.0032354891 0.056236967 0.0032891929, -0.021820918 0.048970968 0.0016279966, 0.0044142008 0.056749105 0.0041668117, -0.018575072 0.053893492 0.0043335259, 0.0048991442 0.056793675 0.0043335557, 0.0043917894 0.056460395 0.0036864281, -0.020401523 0.050720081 0.0019980073, 0.0052469373 0.056762636 0.0043335855, 0.005879432 0.056101784 0.0033856928, 0.0048897564 0.056347832 0.0035844147, 0.0057971179 0.055314496 0.0025939941, -0.016942233 0.054815978 0.0053903162, -0.018381104 0.053330243 0.0033853948, 0.0064977109 0.056185052 0.0035841763, -0.020007208 0.04973954 0.0016282797, 0.0068072975 0.056220397 0.0036863983, -0.016833156 0.054462671 0.0043335259, 0.0091151595 0.056375086 0.004561007, -0.018122986 0.052581862 0.0025937259, 0.0096693337 0.056330338 0.0046765208, -0.016657233 0.053893581 0.003385365, 0.0080960989 0.055745214 0.0032891333, -0.017814055 0.051685572 0.0019980371, 0.0093005002 0.056155503 0.0041668415, -0.013896927 0.055666029 0.0053903461, 0.0097658634 0.056161895 0.0043336451, 0.0092531145 0.055870086 0.0036865771, -0.016423509 0.053137243 0.0025939047, 0.010131121 0.05609709 0.0043338239, 0.010860384 0.055960596 0.0043335557, 0.010746807 0.055375814 0.0033855736, -0.017469868 0.050686494 0.0016281009, 0.0097535253 0.055712163 0.0035842061, 0.010595858 0.054598659 0.0025939345, 0.028382912 0.047598764 0.002442956, 0.027971163 0.048071921 0.0025936067, -0.013807312 0.055307195 0.0043335855, 0.028369278 0.048756123 0.0033851862, -0.016143486 0.052231491 0.0019981265, 0.028584898 0.047358692 0.0023714006, -0.012357727 0.056027696 0.0053902864, 0.029841721 0.047048017 0.0026723146, -0.013663098 0.054729357 0.0033855736, 0.030517414 0.046136782 0.0023713708, -0.015831426 0.051221848 0.0016281009, 0.032298699 0.046246737 0.0033850968, 0.030961871 0.045963079 0.0024428964, 0.031845346 0.04559797 0.0025933683, -0.012278169 0.055666596 0.0043338239, 0.030525878 0.045353159 0.0019975901, -0.013471231 0.053961292 0.0025939047, 0.032239646 0.045075968 0.0024427176, -0.012149826 0.055085123 0.003385365, 0.032432288 0.044811457 0.0023714602, -0.013241515 0.053041518 0.0019981861, 0.033647597 0.044405788 0.0026722252, -0.011979297 0.054312095 0.0025939643, 0.034256354 0.043432906 0.0023711324, -0.0089924335 0.056665391 0.0053904057, -0.012985662 0.052016065 0.0016282201, 0.035501972 0.042812511 0.0025933981, 0.034673929 0.043231383 0.0024425983, 0.034896925 0.042082697 0.0019976199, 0.036007345 0.043421671 0.0033847392, 0.034216017 0.042638212 0.0019974709, -0.011775121 0.053386226 0.0019982159, 0.056463271 0.0032995492 0.0035813153, 0.056553066 0.0029719323 0.003683418, -0.0089344382 0.056300223 0.0043335557, -0.0076888204 0.05685696 0.0053904653, 0.057103589 0.00066658854 0.0045575202, -0.011547416 0.052354291 0.0016280115, -0.0088410079 0.055711806 0.003385663, 0.056306079 0.0016493797 0.0032862425, 0.057154253 0.00011304021 0.004673332, -0.0076391995 0.056490555 0.0043338239, 0.056918383 0.00050474703 0.0041634738, -0.008716926 0.054930106 0.0025939941, 0.057004869 3.5613775e-06 0.0043304563, -0.0075594783 0.055900306 0.0033855438, 0.056628972 0.00050213933 0.003683418, 0.057003871 -0.00032350421 0.0043304265, -0.008568272 0.053993791 0.0019982159, 0.056400821 -0.00096783042 0.003382355, 0.056559697 1.0803342e-05 0.0035811067, -0.0074534118 0.055115685 0.0025940537, 0.055609196 -0.00095416605 0.0025908947, 0.056536868 -0.0016053021 0.0035811067, 0.05659847 -0.0019250363 0.0036832094, -0.0084027052 0.05295001 0.0016283989, 0.056949809 -0.0042401254 0.0045575202, -0.0073262155 0.054176301 0.0019983351, 0.056952804 -0.0047960579 0.0046730638, 0.056237146 -0.0032356828 0.0032857656, -0.007184729 0.053129047 0.0016283393, 0.056749091 -0.0044146925 0.004163295, 0.056793943 -0.0048993826 0.004330337, 0.056460544 -0.0043919384 0.0036829114, 0.056762815 -0.0052470714 0.0043303668, 0.056101888 -0.0058798194 0.0033821464, -0.0038299263 0.05453518 0.0019982457, 0.056347892 -0.0048898458 0.0035807788, 0.056185216 -0.0064980239 0.0035808086, -0.0037558079 0.053480789 0.0016281605, 0.056220442 -0.0068074316 0.0036827773, 0.056375176 -0.0091156363 0.0045571476, 0.056330502 -0.0096696317 0.0046725571, 0.055745259 -0.0080965161 0.0032854974, 0.056155577 -0.0093007386 0.004163146, 0.056162074 -0.0097661465 0.0043299198, 0.055870101 -0.0092533976 0.0036827177, 0.056097373 -0.010131404 0.0043298751, 0.055712253 -0.0097539723 0.0035806298, -0.048237607 0.029316872 0.0034331381, -0.047780141 0.030442953 0.0037195534, -0.046984777 0.031285316 0.0034332424, -0.046735391 0.032639399 0.0043321997, -0.045643151 0.033211902 0.0034333169, -0.045097068 0.034292355 0.0037197769, -0.044231772 0.035069764 0.0034332573, -0.0027606785 0.055499867 0.0025552809, -0.0015154183 0.055261403 0.0023484826, 0.015798092 0.055156574 0.0053904653, -0.00033709407 0.055567458 0.0025554299, 0.00093761086 0.054661393 0.0019982755, 0.0020728409 0.055529803 0.0025552809, 0.015696198 0.054801032 0.0043335259, 0.0032972991 0.055183828 0.0023484826, 0.015532166 0.054228425 0.0033853948, 0.015314251 0.053467512 0.0025939047, 0.0044930279 0.055386439 0.0025554299, 0.0068907142 0.055139452 0.0025554001, 0.0056981444 0.054371655 0.0019983351, 0.010415137 0.053668082 0.0019980371, 0.015053213 0.052556068 0.0019981861, 0.020298958 0.053663567 0.0053903759, 0.0080851614 0.054687694 0.002348572, 0.014762178 0.051540256 0.0016282499, 0.010214061 0.052630588 0.0016282499, 0.0092892647 0.054786414 0.0025553703, 0.020168081 0.053317741 0.0043334067, 0.029317126 0.04823716 0.0034341812, 0.01995717 0.052760571 0.0033852458, 0.028668836 0.049270898 0.0043330789, 0.030443236 0.047779933 0.0037204623, 0.019677207 0.052020222 0.0025937855, 0.031285509 0.046984628 0.0034339726, 0.019341826 0.051133558 0.0019980669, 0.032639682 0.046735317 0.0043331385, 0.033212021 0.045643061 0.0034340322, 0.024660975 0.051804021 0.0053903759, 0.034292564 0.045096889 0.0037203133, 0.018967897 0.050144956 0.0016279817, 0.024502158 0.051470265 0.0043334961, 0.035069913 0.044231489 0.0034338534, 0.036387578 0.043880284 0.0043328404, 0.024246141 0.050932437 0.0033853054, 0.055499956 0.0027604848 0.0025524497, 0.023905858 0.050217524 0.0025937855, 0.055261403 0.0015152991 0.002345413, 0.023498341 0.049361587 0.0019978881, 0.055567473 0.00033712387 0.0025523603, 0.028854951 0.049590543 0.0053900778, 0.02304405 0.048407435 0.0016279519, -0.049149096 0.029488742 0.005160749, -0.04892166 0.029801324 0.0050476044, -0.048390985 0.030878484 0.0055245161, -0.047648385 0.031797335 0.0050477386, -0.047450051 0.032151535 0.0051609725, -0.047038659 0.032851428 0.005389154, -0.04654412 0.033449307 0.0051608831, -0.046290681 0.033743322 0.0050479174, -0.045673817 0.034771606 0.0055247098, -0.044856802 0.03562744 0.0050478727, 0.036623716 0.044164851 0.0053899288, 0.03762807 0.043312088 0.0053896904, -0.044630751 0.035962656 0.005161047, -0.0030072033 0.053756759 0.0016860962, -0.0026300251 0.053889632 0.0017189682, 0.037385702 0.043033034 0.0043329, -0.001432538 0.053457871 0.0015993714, 0.000302881 0.054640502 0.0019847453, 0.036994919 0.042583346 0.003384769, 0.00091958046 0.053604737 0.0016284287, -0.00027671456 0.053953126 0.0017191172, 0.00012385845 0.053840712 0.0016860068, 0.036475867 0.041985765 0.0025933087, 0.0016865134 0.053814605 0.001686126, 0.040145621 0.040989518 0.005389601, 0.0020723045 0.05391413 0.0017188787, 0.035854056 0.041270331 0.0019975603, 0.0032289922 0.053379521 0.0015991628, 0.039887026 0.040725544 0.004332751, 0.0050570667 0.054406941 0.0019846559, 0.0055881441 0.053320572 0.0016282499, 0.004422009 0.05377242 0.0017189085, 0.04125993 0.039867952 0.005389601, 0.0048127472 0.05362539 0.0016861856, 0.035160854 0.040472463 0.0016277134, 0.006367296 0.053463086 0.0016860664, 0.039470196 0.040299937 0.0033847094, 0.0067587197 0.053528786 0.001718998, 0.040993989 0.039610788 0.0043326914, 0.0078662336 0.052895501 0.001599282, 0.038916111 0.039734483 0.0025930703, 0.0097728372 0.053760216 0.0019846857, 0.04056564 0.039197117 0.0033845901, 0.0090872347 0.053183213 0.001718998, 0.038252816 0.03905721 0.0019974113, 0.0094651878 0.053002253 0.001685977, 0.043393478 0.037534535 0.005389452, 0.029488966 0.049148813 0.0051618814, 0.029801384 0.048921302 0.0050487816, 0.039996222 0.03864716 0.0025930107, 0.037513286 0.038302228 0.0016273558, 0.030878693 0.048390597 0.0055256486, 0.043113813 0.037292525 0.0043325424, 0.039314494 0.037988231 0.0019973218, 0.031797722 0.047648072 0.0050485134, 0.032851443 0.047038332 0.00538975, 0.032151476 0.047449693 0.0051615238, 0.044577673 0.036120042 0.0053893924, 0.033449546 0.046543911 0.005161643, 0.042663231 0.03690283 0.0033844113, 0.033743382 0.046290591 0.0050484836, 0.03855443 0.037253827 0.0016272962, 0.034771919 0.04567346 0.0055254102, 0.035627633 0.044856548 0.0050485432, 0.035962865 0.044630423 0.0051616728, 0.053756818 0.00300695 0.0016831756, 0.053889751 0.0026298016 0.0017161071, 0.053457826 0.0014324486 0.0015963614, -0.031962365 -0.070077077 0.049086988, -0.031471118 -0.068945408 0.048326254, -0.033005238 -0.068665475 0.048627123, -0.03263846 -0.07032387 0.049273893, 0.0026431382 -0.075047031 0.047613129, -0.0025981814 -0.075048581 0.047613189, -0.0026256591 -0.075839758 0.048405007, -0.031831682 -0.071088567 0.049370587, -0.031629533 -0.069959193 0.048973501, 0.0026708841 -0.075838283 0.048404902, -0.032301307 -0.067748398 0.047564656, -0.033444449 -0.067234561 0.047613755, -0.033269629 -0.06842418 0.048555791, 0.0026090294 -0.074082047 0.045608327, -0.031241789 -0.069911793 0.048867047, 0.0081645548 -0.077461079 0.049370185, -0.030257255 -0.070624486 0.049000964, -0.030475333 -0.069825128 0.048627198, 0.002741456 -0.077841759 0.049370244, -0.032502204 -0.067204878 0.046960309, -0.033179313 -0.066700965 0.046665594, -0.033014283 -0.06637001 0.045608848, 0.0080537945 -0.07641001 0.049000531, 0.0027042329 -0.07678555 0.049000427, 0.0079543442 -0.075467154 0.048404977, -0.032164127 -0.067460567 0.047103122, -0.030013204 -0.069162771 0.047957391, -0.02989921 -0.069962755 0.048555642, 0.0078713745 -0.074679852 0.047613308, -0.029485002 -0.069484621 0.048046291, -0.028747499 -0.070229053 0.04840517, 0.007770136 -0.073719695 0.045608312, 0.0078089088 -0.074087411 0.046665221, -0.029291406 -0.0692745 0.047757477, -0.029805526 -0.068882808 0.047564551, 0.015163645 -0.076399952 0.049370468, 0.013547882 -0.076702818 0.049370363, -0.029010102 -0.06934908 0.047710031, -0.028447583 -0.069496199 0.047613502, -0.02822195 -0.068945065 0.04666543, -0.029191643 -0.068707436 0.046960101, -0.02967909 -0.068590268 0.047103196, -0.028081834 -0.068602785 0.04560861, 0.014957815 -0.075363278 0.049000725, 0.013364017 -0.075661957 0.049000368, 0.008979097 -0.075973943 0.04882589, 0.01477325 -0.074433282 0.048404872, 0.013198987 -0.074728549 0.048404783, 0.0093821436 -0.075302929 0.048404872, 0.0094651133 -0.074167475 0.047155902, 0.0089351982 -0.074336395 0.047312409, 0.010694131 -0.074328229 0.047613412, 0.0094387084 -0.075756788 0.04872942, 0.014619112 -0.073656708 0.047613442, 0.01306136 -0.073948681 0.047613174, 0.018865228 -0.075570792 0.049370393, 0.014503211 -0.073072478 0.046665117, 0.012503862 -0.075473696 0.04882589, 0.012957722 -0.073362082 0.046665415, 0.012004629 -0.074929744 0.048404872, 0.012383863 -0.073840097 0.047312334, 0.012047544 -0.073791951 0.047155961, 0.018609241 -0.074545503 0.04900071, 0.012076795 -0.075381279 0.048729464, 0.0092346817 -0.073550537 0.045608595, 0.0084281862 -0.07364729 0.045608461, 0.0094307661 -0.073898524 0.046665072, 0.014431208 -0.072709605 0.045608342, 0.012893453 -0.072998032 0.045608297, 0.010993108 -0.073308259 0.045608506, 0.010828733 -0.073706552 0.046665281, 0.012003839 -0.073524311 0.046665028, 0.020699859 -0.075089172 0.049370572, 0.06077148 -0.044044331 0.047565997, 0.061280847 -0.045091495 0.048557028, 0.06158641 -0.044847086 0.048628792, 0.060038626 -0.045102477 0.047614932, 0.062118739 -0.043416888 0.048327699, 0.018379509 -0.073625699 0.048405036, 0.020419046 -0.074070439 0.049000695, 0.060193971 -0.044152334 0.046961352, 0.059562385 -0.044744626 0.046666771, 0.059266701 -0.044522464 0.045610085, 0.018187806 -0.072857603 0.047613427, 0.060513332 -0.043857217 0.047104642, 0.020167068 -0.073156267 0.048405066, 0.018043533 -0.072279572 0.04666537, 0.06233938 -0.041795462 0.047566086, 0.063183054 -0.042567983 0.048628688, 0.063403547 -0.042054474 0.048556954, 0.01995644 -0.072393 0.047613427, 0.063170522 -0.040599629 0.0476152, 0.017953917 -0.071920738 0.045608416, 0.062272057 -0.04116936 0.046961561, 0.062074482 -0.0416179 0.047104791, 0.062669337 -0.040277466 0.046667263, 0.024090558 -0.074070752 0.049370468, 0.062358335 -0.040077552 0.045610383, 0.063817188 -0.039502412 0.04756628, 0.064673722 -0.040267035 0.048629031, 0.065108269 -0.038790241 0.048328102, 0.064393923 -0.04052116 0.048557267, 0.019798234 -0.071818724 0.04666537, 0.063251078 -0.039648309 0.046961725, 0.023763731 -0.073065788 0.049000725, 0.019699916 -0.071462318 0.04560861, 0.063546091 -0.039334536 0.047105014, 0.02347061 -0.072164342 0.048405066, 0.065479562 -0.037370339 0.047959298, 0.066101179 -0.037878245 0.048628971, 0.066290662 -0.037338078 0.048557311, 0.026125401 -0.073377773 0.049370572, 0.023225591 -0.071411431 0.047613516, 0.025771007 -0.072382212 0.049000606, 0.06566754 -0.036667928 0.047759384, 0.066660941 -0.036258489 0.048407003, 0.065217257 -0.037145287 0.04756631, 0.023041442 -0.070844918 0.046665356, 0.065767318 -0.036405429 0.047711834, 0.025453016 -0.071488976 0.048404872, 0.065965429 -0.035880104 0.047615543, 0.06544213 -0.035595536 0.046667397, 0.065106452 -0.036521703 0.046961814, 0.065117359 -0.035418868 0.045610532, 0.064940214 -0.036987543 0.047105014, 0.022926986 -0.070493177 0.045608521, 0.066523865 -0.03475064 0.047566563, 0.067421183 -0.035475254 0.048629254, 0.067753598 -0.033958524 0.04832828, 0.025187388 -0.070743233 0.047613412, 0.067167029 -0.035737023 0.048557654, 0.065972358 -0.034933522 0.046961963, 0.02919881 -0.072209895 0.049370542, 0.024987578 -0.070181921 0.046665519, 0.066241324 -0.034603029 0.047105223, 0.028802484 -0.071230158 0.049000844, 0.068022862 -0.032511413 0.047959462, 0.068671763 -0.03298901 0.048629433, 0.068827361 -0.032424405 0.048557758, 0.024863571 -0.069833621 0.045608655, 0.028447017 -0.070351139 0.048405051, 0.068363607 -0.031995133 0.048048452, 0.031411976 -0.071275011 0.049370661, 0.069129601 -0.031295806 0.048407406, 0.028150231 -0.069617286 0.047613487, 0.068160117 -0.031795084 0.047759831, 0.067748532 -0.032297805 0.047566801, 0.030985638 -0.070307851 0.0490008, 0.068243429 -0.031519741 0.047712058, 0.068408355 -0.030969307 0.047615722, 0.067865744 -0.030723542 0.046667665, 0.027927056 -0.069064915 0.046665475, 0.067594737 -0.031680033 0.046962202, 0.067528784 -0.030570999 0.045610726, 0.06746076 -0.032160595 0.047105119, 0.071179926 -0.029420719 0.049089283, 0.070040837 -0.028947651 0.048328474, 0.069813997 -0.030496731 0.048629284, 0.0306032 -0.06944038 0.048405185, 0.071449846 -0.030089632 0.049276248, 0.072177082 -0.029275373 0.049372971, 0.027788237 -0.068722084 0.045608848, 0.071050584 -0.029091343 0.048976153, 0.068877503 -0.029814512 0.04756698, 0.034164578 -0.069997147 0.049370632, 0.069585294 -0.030763805 0.048557818, 0.030283928 -0.068715855 0.047613576, 0.070991337 -0.028700203 0.048869297, 0.071668535 -0.027689502 0.049003303, 0.070881233 -0.027926698 0.048629656, 0.033701017 -0.069047555 0.04900077, 0.068342552 -0.030032739 0.046962202, 0.030043855 -0.068170786 0.0466654, 0.033284947 -0.068195626 0.048405245, 0.068584859 -0.029687762 0.047105372, 0.070206001 -0.027480468 0.047959775, 0.071000397 -0.027339429 0.04855819, 0.029894605 -0.067832321 0.045608625, 0.03653042 -0.068791911 0.049370795, 0.032937691 -0.067483872 0.047613531, 0.070508406 -0.026941031 0.048048675, 0.071229473 -0.026166111 0.048407778, 0.036034971 -0.067858577 0.049000844, 0.070291847 -0.026754111 0.04775995, 0.069920212 -0.027279019 0.047566906, 0.032676414 -0.066948637 0.046665505, 0.035590351 -0.0670214 0.048405394, 0.070357054 -0.026466921 0.047712147, 0.070486277 -0.025893196 0.04761596, 0.069927067 -0.025687799 0.046667874, 0.069723606 -0.026669905 0.046962276, 0.069579929 -0.025560319 0.045610994, 0.032514349 -0.066616401 0.045608789, 0.069623396 -0.027163103 0.047105566, -0.045152083 -0.059937954 0.047548622, -0.046030208 -0.058878228 0.047103733, -0.046226501 -0.059129283 0.047565207, -0.044772491 -0.059519872 0.046628237, 0.038963705 -0.067443416 0.049370706, -0.045643106 -0.060502574 0.048326746, -0.044036314 -0.060778156 0.047565013, -0.04384923 -0.060519919 0.047103688, 0.035218984 -0.066322014 0.047613829, -0.045612454 -0.058426768 0.045589104, -0.046315223 -0.058546633 0.046960652, -0.04665488 -0.057603821 0.045609355, -0.043448195 -0.060053736 0.045588881, 0.038435116 -0.066528454 0.049001217, -0.043409929 -0.06073235 0.046960309, -0.04232581 -0.060855746 0.045609191, -0.040671736 -0.063064262 0.047548458, -0.04112795 -0.063658118 0.048326612, -0.039724663 -0.064079806 0.047957674, 0.034939513 -0.065796018 0.046665817, -0.040316075 -0.06262438 0.046628386, -0.041621029 -0.062073559 0.047103584, -0.039493993 -0.063823313 0.047564894, -0.039326325 -0.063552245 0.04710333, -0.041798487 -0.062338293 0.047564998, -0.04122974 -0.061597988 0.045588806, -0.041925713 -0.061766192 0.046960384, -0.076190278 0.016168132 0.04937546, 0.037960768 -0.065707594 0.048405498, -0.038952604 -0.063062683 0.045588687, 0.034766257 -0.06546922 0.045608789, -0.037770927 -0.06378299 0.045608968, -0.075156689 0.015948862 0.049005657, -0.038868874 -0.063734338 0.04696025, -0.035975918 -0.065856054 0.047548234, -0.037148595 -0.065216452 0.04756473, -0.036395729 -0.066477403 0.048326388, 0.041454419 -0.065941855 0.049370825, -0.036990941 -0.064939573 0.047103614, -0.034961522 -0.066798076 0.047957435, -0.035645425 -0.065395966 0.046628028, -0.034742028 -0.066529706 0.047564596, -0.034594551 -0.066247135 0.04710339, -0.074229121 0.015752137 0.048410043, -0.036627457 -0.064441159 0.045588732, -0.037313268 -0.064657316 0.046960339, 0.037564784 -0.065021947 0.047613755, -0.034249544 -0.065735906 0.045588449, 0.04089193 -0.065047234 0.049001008, -0.034121007 -0.066397518 0.046960324, -0.073454633 0.015587643 0.04761833, -0.03108938 -0.06829901 0.047548026, -0.072871983 0.015463933 0.046670288, -0.030785084 -0.06781964 0.046627849, 0.037266836 -0.064506292 0.046665758, -0.072510257 0.015387341 0.045613408, -0.031830147 -0.066940814 0.045588672, 0.040387362 -0.064244479 0.048405468, -0.029364169 -0.068058833 0.045588478, -0.077132642 0.01081416 0.049375191, 0.037081853 -0.064186096 0.045608908, 0.0095535368 -0.077301964 0.04937017, 0.043573231 -0.064561203 0.049370959, 0.010790795 -0.076071754 0.049000591, -0.076086193 0.010667399 0.049005434, 0.010939553 -0.077488974 0.049439654, 0.039965957 -0.063574269 0.04761371, -0.075147167 0.010535747 0.048409879, 0.012245253 -0.076921433 0.049370199, 0.042982042 -0.063685283 0.049001202, 0.010732248 -0.075122535 0.048404872, -0.074363351 0.010425776 0.047617972, 0.039648831 -0.06306988 0.046665922, -0.073773429 0.010342956 0.046669766, 0.061539173 -0.042943016 0.047549427, 0.061110035 -0.042575195 0.046629369, 0.04245162 -0.062899485 0.048405528, 0.060049802 -0.043452471 0.045589864, -0.073407158 0.010291874 0.045613185, 0.039452031 -0.062756673 0.045608953, -0.077699423 0.0054073036 0.049374938, 0.061596557 -0.041230485 0.045589983, 0.042008802 -0.062243283 0.047613978, 0.064500287 -0.038351864 0.047549993, 0.064050004 -0.038008615 0.046629637, 0.046157032 -0.062739909 0.049371168, -0.076645076 0.0053339303 0.049005285, 0.063058943 -0.038957015 0.045590118, -0.075699434 0.0052681416 0.048409402, 0.041675627 -0.061749399 0.046665877, 0.064439684 -0.036628067 0.045590088, 0.045530736 -0.061888665 0.049001426, 0.067119271 -0.0335574 0.047550038, 0.066649377 -0.033239841 0.046629995, -0.074909598 0.0052129179 0.047617674, 0.041468635 -0.061442912 0.045608997, -0.07431519 0.005171746 0.046669796, 0.065732241 -0.034254104 0.045590401, 0.044968978 -0.06112504 0.048405588, 0.066939354 -0.031830743 0.045590505, -0.073946387 0.0051462203 0.045612916, -0.077887431 -2.5823712e-05 0.049374625, 0.069382906 -0.0285853 0.047550291, 0.047970533 -0.061364606 0.049371272, -0.07683067 -2.5600195e-05 0.049004704, 0.068894371 -0.028294489 0.046630293, 0.044499889 -0.060487404 0.047614038, 0.068055272 -0.029368624 0.045590669, 0.047319636 -0.060532004 0.049001351, 0.069082379 -0.026863441 0.045590952, -0.075882643 -2.5272369e-05 0.04840906, 0.044146657 -0.060007498 0.04666613, -0.07509093 -2.5033951e-05 0.047617406, 0.046735734 -0.059784994 0.048405871, -0.074495226 -2.4780631e-05 0.046669319, 0.04392761 -0.059709504 0.045609251, -0.074125245 -2.4631619e-05 0.045612454, 0.046248242 -0.05916132 0.047613963, -0.077696174 -0.005458951 0.049374253, 0.050613552 -0.059203461 0.049371332, -0.076641902 -0.0053850561 0.049004599, 0.045881346 -0.058692038 0.046666265, -0.075696141 -0.0053184479 0.048408896, 0.049926698 -0.058400095 0.049001604, -0.074906483 -0.0052631199 0.047617137, 0.045653522 -0.058400512 0.045609325, 0.052134037 -0.057868838 0.049371406, -0.073943391 -0.0051953644 0.045612395, -0.074312299 -0.0052212924 0.046669096, 0.049310595 -0.057679459 0.048405901, -0.077126175 -0.010865673 0.049374133, 0.051426694 -0.057083562 0.04900156, -0.076079682 -0.010718226 0.049004257, 0.048796132 -0.057077825 0.047614127, -0.076899931 -0.012365982 0.049373925, 0.050792038 -0.056379288 0.048405975, -0.075141117 -0.010585874 0.048408508, 0.048409119 -0.056624994 0.046666145, -0.075856626 -0.012198284 0.049004123, 0.050262272 -0.05579105 0.047614217, -0.074356988 -0.010475472 0.047616988, 0.048169017 -0.056343868 0.045609355, 0.05479987 -0.055350766 0.049371585, -0.074920595 -0.012047887 0.048408374, 0.049863532 -0.055348471 0.046666309, 0.054056242 -0.054599836 0.049001783, -0.074138865 -0.011922032 0.047616929, -0.073401049 -0.010340676 0.045612007, -0.073767141 -0.010392278 0.046668768, 0.049615845 -0.055073455 0.045609444, 0.05604367 -0.05409117 0.049371377, -0.076180547 -0.016219154 0.049373642, -0.073550731 -0.011827499 0.046668738, 0.053389266 -0.053926244 0.048406288, -0.075147107 -0.015999153 0.04900381, 0.055283204 -0.053357109 0.049001798, -0.073185652 -0.011768878 0.045612022, 0.05283232 -0.053363532 0.047614336, -0.075792447 -0.017946377 0.049373731, -0.074219584 -0.015801698 0.04840818, 0.054601192 -0.052698866 0.048406199, 0.052413136 -0.052940294 0.046666503, -0.074763939 -0.017702967 0.049003765, 0.054031298 -0.052149028 0.04761456, -0.073445305 -0.015636861 0.047616497, 0.052152947 -0.052677348 0.045609489, -0.073841482 -0.017484412 0.048408315, 0.058693796 -0.051203236 0.04937169, -0.072862715 -0.015512794 0.046668425, 0.053602874 -0.051735431 0.046666577, -0.073071063 -0.017302051 0.047616571, 0.057897389 -0.050508335 0.049001992, -0.072501004 -0.01543574 0.045611456, 0.05333665 -0.051478505 0.045609683, -0.074863926 -0.021493748 0.049373254, 0.059680119 -0.050049976 0.049371809, -0.072491527 -0.017164841 0.046668276, 0.057182983 -0.049885273 0.048406348, -0.073848009 -0.021201983 0.049003556, 0.058870301 -0.049370825 0.049001902, -0.072131515 -0.017079651 0.04561156, 0.056586295 -0.049364701 0.047614634, -0.074280351 -0.023430958 0.049373269, -0.072936818 -0.020940647 0.048407927, 0.058143914 -0.048761651 0.048406288, 0.056137592 -0.048973098 0.046666577, -0.073272511 -0.023113102 0.049003571, -0.072175816 -0.020722032 0.047616184, 0.057537168 -0.04825291 0.047614798, 0.055858716 -0.048729926 0.045609891, -0.072368383 -0.022828102 0.048407733, 0.05708091 -0.0478701 0.046666563, -0.071603253 -0.020557761 0.046668291, 0.062274605 -0.046782091 0.049372032, -0.071613446 -0.022589713 0.047616124, 0.056797475 -0.047632366 0.04561004, -0.071247876 -0.020455509 0.045611352, 0.061429694 -0.046147302 0.049002185, -0.073182479 -0.026663467 0.049373224, 0.060671717 -0.045577928 0.048406422, -0.07104522 -0.022410467 0.046668068, -0.072189316 -0.026301876 0.049003199, -0.070692405 -0.022299439 0.045611292, -0.071298614 -0.025977328 0.048407614, -0.07237196 -0.028790668 0.049373016, -0.070554659 -0.025706187 0.04761599, -0.071390092 -0.028400019 0.049003199, -0.069995061 -0.025502428 0.046667948, -0.070509076 -0.028049558 0.04840757, -0.069647521 -0.025375813 0.045611128, -0.069773525 -0.027756989 0.047615901, -0.071144357 -0.031703606 0.049372762, -0.069220096 -0.027536854 0.046667635, -0.070179075 -0.03127338 0.04900305, -0.068876699 -0.027400002 0.045610994, -0.069313273 -0.03088744 0.04840745, -0.070077538 -0.033996597 0.049372792, -0.068589836 -0.030565292 0.047615737, -0.06912677 -0.033535525 0.049002945, -0.06804578 -0.030322999 0.04666777, -0.068273649 -0.03312169 0.048407301, -0.067707956 -0.030172378 0.045610905, -0.068759739 -0.036589041 0.049372658, -0.067561448 -0.032776043 0.047615603, 0.073111266 -0.026857466 0.049373224, -0.067826837 -0.036092684 0.049002752, 0.072119296 -0.026493087 0.049003318, -0.067025453 -0.032516092 0.046667606, -0.066989824 -0.035647333 0.048407048, -0.066692755 -0.032354608 0.045610815, -0.067409366 -0.039021328 0.04937236, -0.066290855 -0.035275355 0.047615364, -0.066494688 -0.038491741 0.049002618, -0.07344012 0.010053426 0.04561311, -0.065764919 -0.034995705 0.046667367, -0.073970407 0.0047857761 0.045612901, -0.07412374 -0.00050601363 0.04561244, -0.065674141 -0.038017005 0.048406869, -0.073898807 -0.0057954192 0.045612171, -0.065438613 -0.034821913 0.045610592, -0.048480421 -0.060962707 0.049371317, -0.04902266 -0.060527369 0.049371079, -0.048357427 -0.059706211 0.049001381, -0.066039935 -0.041296616 0.049372271, -0.064988971 -0.037620217 0.04761529, -0.04694742 -0.061697677 0.04927443, -0.046221524 -0.062692553 0.049371064, -0.065143898 -0.040736124 0.049002469, -0.044473812 -0.06394431 0.049371019, -0.044005528 -0.064267501 0.049371138, -0.064473316 -0.03732194 0.046667233, -0.043870449 -0.063076675 0.049001351, -0.064340085 -0.040233508 0.048406914, -0.04238911 -0.064914122 0.049274191, -0.064153284 -0.037136599 0.045610517, -0.041629225 -0.065831766 0.049370944, -0.039687797 -0.067020252 0.049370706, -0.064381287 -0.043837756 0.049372092, -0.039306402 -0.067244515 0.049370855, -0.039149448 -0.066110641 0.049001008, -0.063668922 -0.039813817 0.047615334, -0.037611321 -0.067794338 0.049274147, -0.063507676 -0.043242842 0.049002275, -0.036824346 -0.068635315 0.049370527, -0.034690022 -0.069738269 0.049370721, -0.034406528 -0.069878519 0.049370676, -0.063163772 -0.039497837 0.046667233, -0.034219384 -0.06879203 0.049001038, -0.062723801 -0.042709351 0.048406705, -0.062850177 -0.039301857 0.045610309, -0.029506952 -0.072084546 0.049370408, -0.062998652 -0.045802563 0.049371913, -0.0074267685 -0.0737551 0.045608371, -0.0077261031 -0.07372427 0.045608401, -0.0077648461 -0.074091926 0.046665132, -0.0025776029 -0.074453235 0.046665177, -0.0025647581 -0.074083537 0.045608133, -0.062069699 -0.042263791 0.047615036, -0.0021438152 -0.074097142 0.045608431, -0.062143758 -0.045181111 0.049002215, 0.0026219785 -0.07445167 0.046665221, 0.0031501353 -0.074060962 0.045608461, -0.061577305 -0.041928485 0.046666831, -0.061377063 -0.044623762 0.048406675, -0.061271667 -0.041720435 0.045610264, 0.062652215 -0.046275049 0.049371913, -0.060736686 -0.04415819 0.047615021, -0.061009705 -0.04842034 0.049371734, 0.063344166 -0.044699788 0.049275428, 0.064300403 -0.043956056 0.049372077, 0.065523118 -0.042111561 0.04937233, -0.060254842 -0.043807819 0.046666801, 0.065795228 -0.041685104 0.049372226, 0.064634085 -0.041540205 0.049002379, -0.060181946 -0.047763467 0.049002096, 0.066394523 -0.040028721 0.049275592, -0.059955806 -0.043590158 0.045610175, 0.067273661 -0.039254442 0.049372345, -0.059439331 -0.047173962 0.048406616, 0.068422109 -0.037216246 0.049372479, 0.068602517 -0.036882609 0.04937236, 0.067493767 -0.036711514 0.049002692, -0.059650347 -0.050085634 0.049371749, 0.069101244 -0.03515026 0.049275964, -0.05881913 -0.046681777 0.047614813, 0.069903731 -0.034352571 0.049372599, -0.058840871 -0.049406067 0.049002022, 0.070956007 -0.032122701 0.049372792, 0.071060032 -0.031892121 0.049372658, -0.05835259 -0.046311498 0.046666712, 0.069993243 -0.031686723 0.049003109, -0.058114976 -0.048796415 0.048406333, -0.058062911 -0.046081647 0.045609906, -0.074494779 -0.00026662648 0.046669304, -0.057508543 -0.048287272 0.047614887, -0.074290395 -0.0055229515 0.046668813, -0.057312742 -0.052744612 0.049371555, -0.047286272 -0.059604526 0.048556313, -0.047760904 -0.058969423 0.048405826, -0.047262505 -0.058354169 0.047614142, -0.057052478 -0.047904268 0.046666682, -0.047047704 -0.059922859 0.048627853, -0.056535169 -0.052028894 0.049001858, -0.056769252 -0.047666371 0.045609966, -0.056011528 -0.054124668 0.0493716, -0.044736758 -0.06246537 0.049001068, -0.055837452 -0.051386908 0.048406288, -0.04482764 -0.061601281 0.048627719, -0.055251479 -0.053390279 0.049001798, -0.044328362 -0.061836168 0.048556119, -0.04332909 -0.062298298 0.048405707, -0.042877018 -0.061648324 0.047613963, -0.042832181 -0.062881723 0.048555955, -0.055254832 -0.050850898 0.047614396, -0.054569557 -0.052731484 0.048406169, -0.042582437 -0.063174188 0.04862763, -0.054816589 -0.050447509 0.046666533, -0.054000348 -0.052181318 0.04761444, -0.054544538 -0.050197169 0.045609728, -0.040111139 -0.065531641 0.049001127, -0.053309977 -0.056787431 0.049371243, -0.0402468 -0.064687416 0.048627496, -0.053571925 -0.051767334 0.046666458, -0.039719865 -0.064892665 0.048555791, -0.038666159 -0.06529507 0.048405424, -0.038151726 -0.065826729 0.048555925, -0.03826277 -0.064613849 0.047613889, -0.052586734 -0.056016877 0.049001589, -0.037893414 -0.066093549 0.048627406, -0.053305879 -0.051510304 0.045609683, -0.052099586 -0.057899907 0.049371392, -0.051937684 -0.055325702 0.048405871, -0.051392749 -0.057114139 0.049001619, -0.035276115 -0.068256155 0.0490008, -0.051395804 -0.05474852 0.047614321, -0.035454378 -0.067433447 0.048627421, -0.034901664 -0.0676063 0.048555776, -0.03379707 -0.067943335 0.048405364, -0.05075869 -0.056409538 0.048405886, -0.050988257 -0.054314166 0.046666309, -0.050228924 -0.055821076 0.047614291, -0.050735071 -0.054044649 0.045609534, -0.04983069 -0.055378214 0.04666625, -0.029106617 -0.071106404 0.049000695, -0.049583137 -0.055103272 0.045609385, -0.0023660213 -0.074460238 0.046665028, 0.002894029 -0.074441642 0.046665192, 0.0081397742 -0.074051797 0.046665192, -0.046887681 -0.05789116 0.046666265, 0.064037547 -0.042454153 0.049002305, 0.063836619 -0.04102765 0.048406526, 0.066934854 -0.037721023 0.049002692, 0.069483027 -0.03279078 0.049002886, -0.024166644 -0.074046195 0.049370408, -0.023838863 -0.073041469 0.049000636, -0.023544624 -0.072140247 0.048405126, -0.023299083 -0.07138744 0.047613442, -0.02311416 -0.070821106 0.046665519, -0.02299948 -0.070469514 0.045608625, -0.018820181 -0.075582102 0.049370274, -0.018564776 -0.074556679 0.04900071, -0.01833573 -0.073636636 0.048404962, -0.018144339 -0.072868615 0.047613353, -0.018000454 -0.072290376 0.046665341, -0.01791127 -0.071931377 0.045608744, -0.013502255 -0.07671082 0.049370185, -0.013318971 -0.075670168 0.049000636, -0.042536899 -0.061159238 0.046665773, -0.013154685 -0.074736372 0.048405051, -0.013017312 -0.073956668 0.047613144, -0.012914121 -0.073369876 0.046665132, -0.012849912 -0.073005572 0.045608565, -0.0081182718 -0.077465996 0.049370289, -0.0080082566 -0.076414689 0.049000517, -0.039030403 -0.06429258 0.047757909, -0.0079094768 -0.075471893 0.048404858, -0.03877455 -0.064400151 0.047710314, -0.037959218 -0.064101219 0.046665967, -0.0078269094 -0.074684545 0.047613323, -0.0026950091 -0.077843457 0.049370214, -0.002658397 -0.076787323 0.049000531, -0.034458026 -0.067157373 0.04804641, -0.034251735 -0.066960931 0.047757685, -0.0339825 -0.067052469 0.047710136, 0.061691269 -0.021336406 -0.034569338, 0.060220763 -0.022295997 -0.033905908, 0.060148805 -0.020674929 -0.035230219, 0.061422959 -0.023283958 -0.033108115, 0.062861383 -0.019931719 -0.034995556, 0.060991883 -0.019884333 -0.035572514, 0.061658055 -0.018902898 -0.035786197, 0.064549297 -0.020106778 -0.034338027, 0.063710883 -0.021405622 -0.034079239, 0.053333893 -0.016332075 -0.028323814, 0.053185791 -0.016852319 -0.027513146, 0.053359762 -0.017210439 -0.029289231, 0.064023823 -0.019393563 -0.034743935, 0.053574651 -0.016587913 -0.030931488, 0.053620234 -0.017773286 -0.03114523, 0.053209439 -0.018398032 -0.027772352, 0.053608865 -0.019021675 -0.0297153, 0.05391711 -0.018890262 -0.031487629, 0.053538427 -0.019872963 -0.028189108, 0.054348409 -0.020614341 -0.030378863, 0.054448053 -0.019873723 -0.031938791, 0.055182412 -0.020666644 -0.032472447, 0.054155931 -0.021202654 -0.028743595, 0.055031225 -0.022320867 -0.029407158, 0.055506155 -0.021832198 -0.03121528, 0.056077331 -0.021223128 -0.033057734, 0.05612053 -0.023171291 -0.03014718, 0.056969047 -0.022556573 -0.032142565, 0.05708085 -0.021510437 -0.033660367, 0.057369024 -0.023711339 -0.03092593, 0.058714107 -0.023914069 -0.03170456, 0.058593616 -0.022716314 -0.033069253, 0.058134794 -0.021512166 -0.034245521, 0.060088456 -0.02376923 -0.032444358, 0.059177399 -0.021228269 -0.034779176, 0.062651008 -0.022482693 -0.033662245, 0.055913642 -0.017444938 -0.022610992, 0.055886313 -0.018812463 -0.022813112, 0.056097552 -0.0201388 -0.023141146, 0.04465726 -0.014032885 -0.046997637, 0.044702724 -0.015218303 -0.047211483, 0.044999734 -0.016335189 -0.047553942, 0.045530662 -0.017318517 -0.048005059, 0.046265125 -0.018111601 -0.04853873, 0.047160074 -0.018668041 -0.049123943, 0.048163548 -0.018955439 -0.049726725, 0.049217299 -0.018957138 -0.05031167, 0.050260186 -0.018673003 -0.050845414, 0.051231429 -0.018119901 -0.051296622, 0.052074775 -0.017329365 -0.051638827, 0.052740827 -0.016347915 -0.05185248, 0.077810958 0.0332627 0.049719989, 0.075500414 0.038567156 0.049878657, 0.075359508 0.038495198 0.049720258, 0.077956453 0.033324942 0.049878269, 0.075606585 0.038621143 0.050068289, -0.027878076 0.079896852 0.049722642, -0.033327937 0.077953771 0.049880669, -0.03326568 0.077808186 0.049722403, 0.078066111 0.033371776 0.05006808, -0.027969569 0.080158845 0.050070912, -0.033374697 0.078063414 0.050070405, -0.027930111 0.080046371 0.049880847, 0.075672463 0.038655132 0.050279588, -0.033403724 0.078131288 0.050281644, 0.07813406 0.033400938 0.050279468, -0.027993858 0.080228701 0.050281912, 0.072212696 0.04334189 0.049527556, 0.075002402 0.038312897 0.049527198, -0.033108026 0.077439636 0.049529418, -0.038315669 0.07499969 0.049529225, -0.038411781 0.075188026 0.049603283, 0.072393969 0.043450639 0.049601585, 0.075190619 0.03840898 0.049601376, -0.033191055 0.077633932 0.049603447, 0.07255657 0.043548092 0.049720615, -0.038498074 0.075356618 0.049722433, 0.072692364 0.043629542 0.049878985, -0.038570225 0.075497732 0.049880654, 0.072794333 0.04369095 0.050068468, -0.038624391 0.075603664 0.050070375, 0.072857842 0.043729037 0.050279856, -0.038657993 0.075669602 0.050281644, 0.069086567 0.048168942 0.049527705, -0.043344766 0.072210029 0.04952912, 0.069259778 0.048289731 0.049601644, -0.04345338 0.072391272 0.049603179, 0.069415331 0.048398063 0.049720973, -0.043550923 0.072553724 0.04972221, 0.069545209 0.048488542 0.049879164, -0.043632478 0.072689623 0.049880445, 0.069643036 0.04855679 0.050068945, -0.04369396 0.0727918 0.050070181, 0.069703743 0.048599109 0.050280124, -0.043731734 0.072855011 0.050281361, 0.065637991 0.052771345 0.049528152, -0.048171625 0.069083869 0.049528942, 0.065802872 0.052903548 0.049601972, -0.048292354 0.069257125 0.049603105, 0.065950513 0.053022325 0.049721211, -0.048400909 0.069412544 0.049721986, 0.066073954 0.053121537 0.049879432, -0.048491746 0.069542423 0.049880326, 0.06616661 0.053196087 0.050069124, -0.048559636 0.069640219 0.050070032, 0.066224396 0.053242505 0.050280243, -0.048602015 0.069700822 0.050281182, 0.061883628 0.057127416 0.049528331, -0.052773982 0.065635398 0.049528718, 0.062038869 0.057270885 0.049602091, -0.052906319 0.065800101 0.049602821, 0.062178135 0.057399377 0.04972139, -0.05302535 0.065947905 0.049721941, 0.062294483 0.05750671 0.04987973, -0.053124294 0.066071182 0.049880132, 0.062382102 0.057587489 0.050069362, -0.053199172 0.066164061 0.050069988, 0.062436402 0.057637706 0.050280541, -0.053245425 0.066221535 0.050281003, 0.057840645 0.061217383 0.049528509, -0.057130173 0.061880931 0.049528629, 0.057985753 0.061370999 0.049602658, -0.057273567 0.062036261 0.04960233, 0.058116049 0.061508596 0.049721569, -0.057402104 0.062175572 0.049721643, 0.058224738 0.061623782 0.049880028, -0.057509586 0.06229189 0.049880117, 0.058306575 0.061710373 0.0500696, -0.057590321 0.06237939 0.050069585, 0.058357328 0.061764255 0.050280929, -0.057640612 0.06243372 0.050280914, 0.053527981 0.065021783 0.049528688, -0.061220139 0.057838067 0.049528316, 0.05366233 0.06518501 0.049602717, -0.061373681 0.05798313 0.049602374, 0.053782731 0.065331265 0.049721867, -0.061511651 0.058113292 0.04972145, 0.053883582 0.065453604 0.049880177, -0.061626539 0.058221877 0.04987973, 0.053959161 0.065545619 0.050069779, -0.061713412 0.058303773 0.050069422, 0.054006249 0.065602496 0.050280929, -0.061767146 0.058354601 0.050280735, 0.048965693 0.068523154 0.049528867, -0.06502451 0.053525388 0.049528047, 0.049088567 0.068695083 0.049602985, -0.065187782 0.053659648 0.049602091, 0.049198866 0.068849191 0.049722046, -0.065334126 0.053780153 0.049721196, 0.049290955 0.068978071 0.049880296, -0.065456361 0.053880706 0.049879476, 0.049360156 0.069075063 0.050069958, -0.06554839 0.053956524 0.050069287, 0.049403131 0.0691351 0.050281256, -0.065605491 0.054003432 0.050280377, 0.044175178 0.071704879 0.049529165, -0.068526015 0.048963115 0.049527705, 0.044286132 0.071884826 0.049602985, -0.06869784 0.049086183 0.049602076, 0.044385582 0.072046235 0.049722254, -0.068852231 0.049196318 0.049721107, 0.044468671 0.072180942 0.049880594, -0.068980962 0.049288213 0.049879238, 0.044531196 0.072282448 0.050070018, -0.069077775 0.049357504 0.050068915, 0.04456991 0.072345421 0.050281376, -0.069138125 0.049400583 0.05027993, 0.039178848 0.074552432 0.049529314, -0.07170777 0.044172689 0.049527481, 0.039277166 0.074739426 0.049603194, -0.071887612 0.044283405 0.04960151, 0.039365411 0.074907228 0.049722552, -0.072049111 0.044382766 0.04972057, 0.039438933 0.075047284 0.049880594, -0.072183862 0.044465825 0.049878851, 0.039494455 0.075152844 0.050070405, -0.072285429 0.044528335 0.050068513, 0.039528817 0.075218305 0.050281554, -0.072348192 0.044567123 0.050279915, 0.033999622 0.077052116 0.049529195, -0.074555233 0.0391763 0.049527183, 0.034084976 0.077245593 0.049603432, -0.074742153 0.039274618 0.049601272, 0.034161508 0.077418953 0.049722522, -0.074910104 0.03936249 0.049720347, 0.034225523 0.077563822 0.049880862, -0.075050309 0.039436251 0.049878702, 0.034273416 0.077672899 0.050070524, -0.075155646 0.039491534 0.050068274, 0.034303337 0.07774052 0.050281733, -0.075220942 0.039525941 0.050279573, 0.028661966 0.079192638 0.049529582, -0.077055022 0.033997074 0.049526945, 0.028733909 0.079391539 0.049603492, -0.077248394 0.034082264 0.049600929, 0.028798252 0.079569682 0.049722612, -0.077421814 0.034158796 0.049720049, 0.028852254 0.079718545 0.049880922, -0.077566594 0.034222648 0.049878359, 0.028892785 0.079830736 0.050070733, -0.077675626 0.034270778 0.050067902, 0.028918028 0.079900175 0.050281942, -0.077743217 0.034300685 0.050279334, 0.082360685 -0.017613977 0.049524069, 0.023190647 0.080964133 0.049529523, -0.079195544 0.028659254 0.049526617, 0.023248881 0.081167504 0.04960385, 0.082567319 -0.017658144 0.049598187, -0.079394251 0.028731138 0.049600556, 0.023301095 0.081349537 0.049722731, 0.082752779 -0.017698005 0.049717143, 0.082907498 -0.017730996 0.049875468, -0.079572469 0.028795645 0.049719796, 0.023344636 0.081501707 0.049881279, 0.023377359 0.081616342 0.050070822, 0.083024025 -0.017755926 0.050065145, -0.079721451 0.028849572 0.049878284, 0.083096579 -0.017771393 0.050276235, 0.023397774 0.081687286 0.050281912, 0.017611325 0.082357943 0.049529612, -0.079833433 0.028889999 0.050067961, 0.083370537 -0.011952505 0.049524456, -0.079902992 0.028915241 0.050278887, 0.083579808 -0.011982337 0.049598396, 0.017655462 0.082564622 0.049603552, 0.08376734 -0.012009442 0.049717516, 0.017695159 0.082750097 0.04972285, 0.083924055 -0.012032047 0.049875766, 0.017728269 0.082904726 0.04988116, 0.017753035 0.083021179 0.050070673, 0.084041908 -0.012048766 0.050065562, 0.084115371 -0.012059286 0.050276697, 0.017768532 0.083093762 0.05028218, 0.083991542 -0.0062350631 0.049524546, 0.011949629 0.083367988 0.049529642, 0.011979729 0.083577141 0.04960373, 0.084202319 -0.0062507093 0.049598694, 0.084391475 -0.0062648803 0.049717724, 0.012006551 0.083764687 0.049722761, 0.084549338 -0.0062767714 0.049876273, 0.012028843 0.083921447 0.04988113, 0.084668085 -0.0062854737 0.050065771, 0.01204589 0.08403945 0.050070792, 0.084741876 -0.0062908232 0.050276995, 0.01205644 0.084112436 0.050282061, 0.08422108 -0.0004888624 0.049524993, 0.0062325299 0.083988994 0.049529791, 0.084432408 -0.00049003959 0.049599126, 0.0062480867 0.084199756 0.04960373, 0.084622115 -0.00049127638 0.049718142, 0.0062619746 0.084388629 0.04972285, 0.084780499 -0.00049218535 0.049876422, 0.0062737465 0.084546551 0.049881101, 0.08489953 -0.00049291551 0.050065979, 0.0062825978 0.084665403 0.050070852, 0.08497344 -0.00049331784 0.050277472, 0.0062882304 0.084739015 0.050282031, 0.084057942 0.0052596629 0.049525246, 0.00048607588 0.084218457 0.049529821, 0.084268928 0.0052728951 0.049599424, 0.00048738718 0.084429845 0.04960385, 0.084458202 0.0052845478 0.04971844, 0.00048831105 0.084619313 0.049722999, 0.08461614 0.0052945763 0.04987672, 0.00048929453 0.084777668 0.049881339, 0.084734961 0.005302012 0.050066575, 0.00049006939 0.084896877 0.050070941, 0.08480899 0.0053064823 0.05027768, 0.00049054623 0.084970668 0.05028218, 0.083502784 0.010983691 0.049525559, -0.0052623749 0.084055364 0.049529612, 0.083712295 0.011011437 0.049599767, -0.0052759647 0.08426626 0.04960382, 0.083900258 0.011035979 0.049718589, -0.005287528 0.084455475 0.04972294, 0.084057435 0.011056527 0.049877107, -0.005297482 0.084613264 0.049881399, 0.084175557 0.011072218 0.05006659, -0.0053049028 0.084732249 0.050070852, 0.084248781 0.011081904 0.050278038, -0.0053096414 0.084806189 0.05028218, 0.082558304 0.016656637 0.049525917, -0.010986507 0.083500221 0.049529701, 0.082765698 0.01669842 0.049600005, -0.011014223 0.083709896 0.04960379, 0.082951561 0.016735867 0.049719155, -0.01103881 0.083897531 0.04972291, 0.083106697 0.016767219 0.049877465, -0.011059582 0.08405453 0.04988116, 0.083223403 0.016790763 0.050067276, -0.011075139 0.084172651 0.050070882, 0.083295941 0.016805217 0.050278395, -0.011084765 0.084246114 0.050282001, -0.01665929 0.082555875 0.049529672, 0.081229135 0.022251815 0.049526304, 0.081432983 0.022307575 0.049600333, -0.016701281 0.082763031 0.049603775, 0.081615821 0.022357583 0.049719393, -0.016738743 0.082948714 0.049722731, 0.081768423 0.022399515 0.049877763, -0.016769975 0.083103999 0.049881145, -0.016793638 0.083220705 0.050070927, 0.081883386 0.022430956 0.050067395, 0.081954852 0.022450611 0.050278604, -0.016808331 0.083293229 0.050282046, 0.079521075 0.027743056 0.049526662, -0.022254497 0.081226513 0.049529761, 0.07972075 0.027812645 0.049600601, -0.022310436 0.081430271 0.049603775, 0.079899818 0.027875051 0.049719721, -0.022360593 0.081613183 0.049722865, -0.022402376 0.081765771 0.04988113, 0.080049187 0.027927369 0.04987812, 0.080161661 0.027966574 0.050067544, -0.022433847 0.081880599 0.050070629, 0.080231532 0.027990729 0.050278962, -0.022453368 0.081952021 0.050281927, 0.077442259 0.033105239 0.0495269, -0.027745992 0.079518408 0.049529567, 0.077636614 0.033188254 0.049600959, -0.027815402 0.079717979 0.049603462, -0.043453544 0.0723968 -0.049594954, -0.038498148 0.075362429 -0.049713999, -0.038411722 0.07519336 -0.049595013, 0.072692379 0.043635294 -0.049874157, 0.075606495 0.038627103 -0.050063923, 0.075500473 0.038572952 -0.049874336, 0.072794423 0.043696642 -0.050063834, 0.075672433 0.03866075 -0.050275311, 0.072857961 0.04373461 -0.050275251, -0.043550909 0.072559446 -0.049714312, -0.038570002 0.07550329 -0.049872339, 0.075002313 0.03831844 -0.049522936, 0.077442199 0.033110723 -0.049523488, -0.043632463 0.072695225 -0.049872354, -0.043693811 0.072797313 -0.05006209, -0.038624167 0.075609282 -0.050062045, 0.07763654 0.03319408 -0.049597293, -0.043731749 0.072860733 -0.050273433, -0.038657889 0.075675175 -0.050273165, 0.075190648 0.038414568 -0.04959707, 0.075359374 0.03850092 -0.049716085, 0.077810958 0.033268437 -0.049716473, -0.033107936 0.07744503 -0.04952094, -0.038315535 0.075005174 -0.049520925, 0.077956393 0.033330649 -0.049874827, -0.0331911 0.077639416 -0.049594775, 0.078066051 0.033377439 -0.050064281, -0.03326568 0.077813804 -0.049714044, 0.07813403 0.033406526 -0.050275669, -0.033327922 0.077959418 -0.049872294, 0.079521105 0.027748689 -0.049523756, -0.033374667 0.078069061 -0.050061867, 0.079720572 0.027818426 -0.049597606, -0.033403769 0.078136936 -0.050273269, -0.027745962 0.079523921 -0.049520671, 0.079899698 0.027880803 -0.049716786, 0.080049187 0.027932957 -0.049875066, -0.027815565 0.079723552 -0.049594566, 0.080161676 0.027972236 -0.050064623, -0.027878225 0.079902619 -0.049713984, 0.080231577 0.027996495 -0.050275937, -0.0279302 0.080052003 -0.049871966, 0.081229225 0.022257239 -0.049523979, -0.027969405 0.080164537 -0.050061554, 0.081433147 0.022313207 -0.049598008, -0.027993873 0.080234587 -0.05027321, 0.081615731 0.022363305 -0.049717024, -0.022254691 0.081232026 -0.049520448, 0.081768557 0.022405177 -0.049875408, -0.022310525 0.081435964 -0.049594551, 0.081883416 0.022436678 -0.050064981, -0.022360548 0.081618801 -0.049713716, 0.081954867 0.022456184 -0.050276473, -0.022402242 0.081771433 -0.049871981, 0.082558334 0.0166623 -0.049524218, -0.022433802 0.081886455 -0.050061628, 0.082765475 0.016704038 -0.049598187, -0.022453427 0.081957772 -0.050273225, 0.082951501 0.016741484 -0.049717158, -0.016659319 0.082561374 -0.049520671, 0.083106861 0.016772851 -0.049875692, -0.016701251 0.082768619 -0.049594402, 0.083223432 0.016796365 -0.050065115, -0.016738698 0.082954362 -0.049713582, 0.083295941 0.016811073 -0.050276801, -0.016769931 0.083109587 -0.049871936, 0.083502963 0.010989323 -0.049524531, -0.016793579 0.083226427 -0.050061449, 0.083712384 0.011016861 -0.049598441, -0.016808257 0.083298758 -0.050272942, 0.083900481 0.011041537 -0.04971765, -0.010986686 0.08350578 -0.049520209, -0.011014193 0.083715424 -0.049594358, 0.08405745 0.01106225 -0.04987599, 0.084175497 0.011077866 -0.050065532, -0.011038989 0.083903477 -0.049713627, 0.084248871 0.011087492 -0.050276905, -0.011059597 0.084060386 -0.049871966, 0.084057987 0.0052652508 -0.04952468, -0.011075094 0.084178448 -0.050061539, -0.011084735 0.084251866 -0.050272867, 0.084268898 0.0052784979 -0.049598664, -0.0052624941 0.084060878 -0.049520358, 0.084458098 0.0052903295 -0.049717963, 0.084616289 0.0053001195 -0.049876347, -0.0052757114 0.084271684 -0.049594298, 0.084734917 0.0053076446 -0.050065875, -0.0052874684 0.084460944 -0.049713448, 0.084808916 0.0053122193 -0.050277203, -0.0052974969 0.08461906 -0.049871832, 0.084221095 -0.00048324466 -0.049525112, -0.0053049028 0.084737971 -0.05006142, -0.0053095222 0.084811851 -0.050272867, 0.084432378 -0.00048454106 -0.049599066, 0.00048589706 0.08422403 -0.049520463, 0.084622234 -0.00048564374 -0.049718291, 0.08478035 -0.00048643351 -0.049876645, 0.00048725307 0.084435359 -0.049594313, 0.00048834085 0.084624872 -0.049713522, 0.08489956 -0.00048716366 -0.050066203, 0.084973425 -0.0004876852 -0.050277755, 0.00048929453 0.084783345 -0.049871787, 0.00049003959 0.084902525 -0.050061449, 0.083991706 -0.0062295496 -0.049525455, 0.00049048662 0.084976435 -0.050273106, 0.084202394 -0.0062453598 -0.04959923, 0.0062322617 0.083994567 -0.049520463, 0.084391415 -0.0062593818 -0.049718559, 0.0062479675 0.084205225 -0.049594402, 0.084549278 -0.0062710643 -0.049876958, 0.0062620342 0.084394291 -0.049713627, 0.0846681 -0.0062798709 -0.050066501, 0.08474192 -0.0062852651 -0.050278068, 0.0062738359 0.084552333 -0.049871862, 0.083370417 -0.011946946 -0.049525797, 0.006282568 0.08467111 -0.050061449, 0.0062880963 0.084744781 -0.050272852, 0.08357963 -0.011976764 -0.049600005, 0.011949778 0.083373293 -0.049520627, 0.083767369 -0.01200372 -0.049718931, 0.011979669 0.083582565 -0.049594328, 0.0839241 -0.012026221 -0.049877316, 0.084042117 -0.012043148 -0.050066844, 0.012006462 0.08377032 -0.049713582, 0.084115297 -0.012053668 -0.050278306, 0.012028992 0.083926842 -0.049871817, 0.01204592 0.084044814 -0.05006139, 0.082360566 -0.017608345 -0.049526155, 0.012056485 0.084118247 -0.050273001, 0.08256726 -0.017652705 -0.049600273, 0.017611161 0.082363531 -0.049520388, 0.08275272 -0.017692298 -0.049719274, 0.017655343 0.082570285 -0.049594283, 0.082907498 -0.017725408 -0.049877644, 0.017695114 0.082755744 -0.049713477, 0.017728135 0.082910478 -0.049871862, 0.083024099 -0.017750293 -0.050067082, 0.01775296 0.083027005 -0.05006136, 0.083096504 -0.01776576 -0.050278574, 0.017768428 0.083099395 -0.050272986, 0.023190618 0.080969676 -0.049520701, 0.023248911 0.081173003 -0.049594611, 0.023301035 0.081355318 -0.049713805, 0.023344696 0.081507325 -0.049871981, 0.023377404 0.081622019 -0.050061658, 0.023397818 0.081693038 -0.05027312, 0.028661937 0.079198331 -0.04952088, 0.028733924 0.079397127 -0.049594551, 0.028798386 0.07957533 -0.049713627, -0.079195634 0.028664753 -0.049523577, 0.028852358 0.079724327 -0.04987213, 0.02889283 0.079836443 -0.050061688, -0.07939437 0.028736845 -0.049597532, 0.028917924 0.079906031 -0.05027321, -0.079572529 0.028801337 -0.049716592, 0.033999622 0.077057779 -0.049520805, -0.07972157 0.028855145 -0.04987511, 0.034084976 0.077251166 -0.049594656, -0.079833508 0.028895795 -0.050064504, -0.079903066 0.028920799 -0.050276101, 0.034161523 0.07742466 -0.049713969, -0.077054977 0.034002542 -0.049523324, 0.034225404 0.077569574 -0.049872339, 0.034273461 0.077678636 -0.050061807, -0.077248305 0.034087881 -0.049597114, 0.034303233 0.077746272 -0.050273314, -0.077421844 0.034164384 -0.049716428, -0.077566788 0.03422837 -0.049874589, 0.039178744 0.074557871 -0.049521059, 0.039277047 0.074745119 -0.049594969, -0.077675685 0.034276575 -0.050064191, -0.077743411 0.034306377 -0.050275698, 0.039365426 0.074912906 -0.049714088, -0.074555069 0.03918165 -0.049522907, 0.039438978 0.075053185 -0.049872652, -0.074742272 0.039280057 -0.049596995, 0.039494365 0.075158477 -0.050062105, 0.039528802 0.075223923 -0.050273448, -0.074910045 0.039368242 -0.04971607, 0.044175282 0.071710423 -0.049521089, -0.075050175 0.039441884 -0.04987438, -0.075155526 0.039497316 -0.050063983, 0.044285983 0.071890563 -0.049595132, -0.075221092 0.039531633 -0.05027537, 0.044385672 0.072051853 -0.049714252, 0.044468552 0.072186634 -0.049872532, -0.071707696 0.044178098 -0.049522683, -0.071887583 0.044289023 -0.049596637, 0.044531122 0.072288081 -0.050062045, -0.072049081 0.044388384 -0.049715802, 0.04456991 0.072351053 -0.050273508, -0.072183833 0.044471413 -0.049874172, 0.048965886 0.068528622 -0.049521357, 0.049088657 0.068700612 -0.049595326, -0.072285309 0.044534087 -0.050063744, -0.072348252 0.044572845 -0.050275192, 0.04919894 0.068855017 -0.049714386, -0.068525955 0.048968792 -0.049522415, 0.049291015 0.068983734 -0.049872681, -0.06869778 0.049091667 -0.049596325, 0.049360245 0.069080755 -0.050062373, 0.049403131 0.069140792 -0.05027388, -0.068852216 0.049201757 -0.049715474, -0.068981007 0.049293935 -0.049873799, 0.053528026 0.065027371 -0.049521461, -0.069077834 0.049363062 -0.050063327, 0.053662345 0.065190539 -0.04959552, -0.069138035 0.049406171 -0.0502747, 0.053782865 0.065336972 -0.049714595, -0.065024644 0.053530946 -0.049522057, 0.053883612 0.065459177 -0.04987289, -0.065187842 0.05366531 -0.049596086, 0.053959325 0.065551132 -0.050062358, 0.054006383 0.065608293 -0.050274059, -0.065334156 0.053785846 -0.04971537, 0.05784075 0.061222881 -0.049521849, -0.06545639 0.053886339 -0.049873486, -0.065548494 0.053962111 -0.050063074, 0.057985798 0.061376616 -0.049595654, -0.065605476 0.054009065 -0.050274462, -0.06122008 0.057843447 -0.049522042, 0.058116078 0.061514303 -0.049714789, 0.058224902 0.0616294 -0.049873099, -0.06137377 0.057988718 -0.049595892, 0.058306605 0.06171611 -0.050062761, -0.061511576 0.058119044 -0.049715102, 0.058357269 0.061769828 -0.050274163, -0.061626628 0.058227628 -0.049873441, 0.061883822 0.057132915 -0.049521938, -0.061713099 0.058309391 -0.05006288, 0.062039018 0.057276338 -0.049595788, -0.061767191 0.058360368 -0.050274417, 0.062178224 0.05740498 -0.049715117, -0.057130173 0.06188643 -0.049521759, 0.062294513 0.057512328 -0.049873605, -0.057273552 0.062041894 -0.049595505, 0.062382102 0.057593092 -0.050062835, -0.057402268 0.062181264 -0.049714819, 0.062436432 0.05764325 -0.050274432, 0.065637946 0.05277662 -0.049522206, -0.057509661 0.062297568 -0.049873099, -0.057590365 0.062385127 -0.050062865, 0.065802962 0.052909002 -0.049596056, -0.057640687 0.062439442 -0.050274163, 0.065950513 0.053027973 -0.049715355, -0.052773938 0.065640956 -0.049521521, 0.066073924 0.053127065 -0.049873546, -0.052906409 0.065805599 -0.049595356, 0.066166937 0.053201854 -0.050063163, -0.05302529 0.065953568 -0.04971458, 0.06622453 0.053248152 -0.05027467, -0.053124338 0.066076905 -0.049873009, 0.069086492 0.048174351 -0.049522504, -0.053199008 0.066169739 -0.050062492, 0.069259822 0.048295289 -0.049596414, -0.053245381 0.066227481 -0.050273955, 0.069415465 0.048403665 -0.049715623, -0.048171639 0.069089383 -0.049521357, 0.069545299 0.048494309 -0.049874067, -0.048292488 0.069262743 -0.049595192, 0.069642931 0.048562407 -0.050063431, 0.069703698 0.048604637 -0.050274834, -0.048400894 0.069418341 -0.049714401, -0.048491403 0.069548145 -0.049872681, 0.072212875 0.043347418 -0.049522743, -0.048559591 0.069645911 -0.050062224, 0.072394028 0.043456122 -0.049596593, -0.048601866 0.06970641 -0.050273776, 0.072556525 0.043553814 -0.049715772, -0.043344676 0.072215661 -0.049521163, -0.011517301 0.0068717897 0.028891996, -0.010891587 0.0063802898 0.028891996, -0.011304945 0.0070835054 0.028591841, -0.010736063 0.0066367984 0.028592199, -0.010166675 0.0060530156 0.028891891, -0.010077089 0.0063391328 0.028591901, -0.0093842745 0.0059085339 0.028891951, -0.009365961 0.0062079132 0.028592035, -0.0085901022 0.0059554726 0.028891951, -0.0086438656 0.0062506497 0.028591886, -0.0078303963 0.0061913729 0.028892085, -0.0079531074 0.0064649135 0.028591827, -0.0073337257 0.0068383664 0.028591841, -0.007148996 0.0066018999 0.028891951, -0.0068216771 0.0073492527 0.028592095, -0.0065856874 0.007163763 0.028891951, -0.0064467192 0.0079676062 0.028592065, -0.0061733276 0.0078440756 0.02889207, -0.0062308609 0.0086578429 0.028592169, -0.0059358031 0.0086033642 0.028892249, -0.0061862618 0.0093796849 0.028592154, -0.0058867186 0.0093974471 0.028892159, -0.0063156784 0.010091156 0.028592348, -0.0060291141 0.010180205 0.028892323, -0.006611675 0.010751113 0.028592348, -0.0063547045 0.010905877 0.028892472, -0.0070569664 0.011320889 0.028592333, -0.0068445206 0.011532918 0.028892413, -0.0069186389 0.011604801 0.028892308, -0.0069948137 0.01167427 0.028892264, -0.0070733279 0.011741579 0.028892443, -0.0074571371 0.011657596 0.028592363, -0.0075044334 0.011857688 0.028732613, -0.0079096854 0.011919543 0.028592318, -0.0079470277 0.011976779 0.028629005, -0.0084007829 0.012099236 0.028592303, -0.0010441542 -0.010223836 0.028890997, -0.0018157512 -0.0099947155 0.028590992, -0.0012564361 -0.01043582 0.028591007, -0.0016738921 -0.0097300112 0.028891027, -0.0024634004 -0.0096980929 0.028591126, -0.0024040043 -0.0094021857 0.028891101, -0.0031626374 -0.0095623136 0.028591186, -0.0031916946 -0.0092598498 0.028891057, -0.003874138 -0.0095953941 0.028590992, -0.0039904416 -0.0093111843 0.028891146, -0.0045578927 -0.0097952187 0.028591156, -0.0047532469 -0.0095536113 0.028891131, -0.0051751435 -0.010150552 0.028591111, -0.0054354221 -0.009972319 0.028891087, -0.0056913197 -0.010641381 0.028590977, -0.0059966296 -0.010542944 0.028891012, -0.0060772002 -0.011240259 0.028591082, -0.0064038336 -0.011232004 0.028890952, -0.0063111484 -0.011913016 0.028590873, -0.0066333562 -0.011998907 0.028890982, -0.006518364 -0.012430102 0.028731212, -0.0063796043 -0.012622088 0.028590918, -0.0064002275 -0.012873232 0.028627425, -0.0062791556 -0.013327301 0.028590843, 0.039119318 -0.010719851 0.02559796, 0.038980111 -0.010307565 0.025500402, 0.038970798 -0.01030995 0.025598049, 0.039720133 -0.011328131 0.025244549, 0.039456829 -0.011013612 0.025244534, 0.039676204 -0.011372104 0.025320366, 0.03962332 -0.011424974 0.025500476, 0.039344847 -0.011091918 0.025500476, 0.039616391 -0.011431634 0.025598019, 0.039336875 -0.011097521 0.02559796, 0.039643452 -0.011404768 0.025406778, 0.039368048 -0.011075497 0.025406733, 0.03912802 -0.010715678 0.025500387, 0.039405942 -0.011049241 0.025320485, 0.039153829 -0.010703757 0.025406897, 0.039007783 -0.010300279 0.025406957, 0.039052278 -0.010288447 0.025320455, 0.039195821 -0.010684252 0.025320455, 0.03911227 -0.010272324 0.025244549, 0.039252058 -0.010657921 0.025244653, 0.031595573 0.02982375 0.023931086, 0.031382978 0.029921159 0.023931265, 0.031546608 0.029743806 0.023902744, 0.031432405 0.030075625 0.024039596, 0.03164053 0.029897586 0.023977548, 0.031680092 0.029962301 0.024039596, 0.031840146 0.02974017 0.023977488, 0.031778932 0.029679134 0.023931324, 0.031139642 0.029774919 0.023893297, 0.030935526 0.0298623 0.023902774, 0.030951723 0.029766142 0.023893416, 0.031146735 0.029872239 0.023902833, 0.031354278 0.029831916 0.023902804, 0.03115356 0.029965773 0.023931295, 0.031165287 0.030127645 0.024039626, 0.031409532 0.030003548 0.023977548, 0.030732512 0.029803023 0.023902744, 0.030770928 0.029713348 0.023893207, 0.030920208 0.029954895 0.023931295, 0.03089346 0.030115008 0.024039656, 0.031159803 0.030051902 0.023977458, 0.031893864 0.029793724 0.024039626, 0.030549377 0.029697597 0.023902878, 0.0306077 0.029619396 0.023893416, 0.030695826 0.029889345 0.023931295, 0.030632138 0.03003858 0.024039686, 0.030905947 0.030040056 0.023977488, 0.030396223 0.029551923 0.023902655, 0.03047131 0.029489771 0.02389349, 0.03049323 0.029772833 0.023931414, 0.030661866 0.029968858 0.023977518, 0.030396178 0.029902726 0.024039567, 0.030281633 0.029374018 0.023902848, 0.030369416 0.029331461 0.023893401, 0.030323908 0.029611766 0.023931146, 0.030441597 0.02984193 0.023977488, 0.030198976 0.029715285 0.024039492, 0.030212358 0.029174432 0.023902848, 0.030307561 0.02915363 0.023893252, 0.030289471 0.028966308 0.023893252, 0.030221656 0.028754652 0.02390267, 0.030316174 0.028779805 0.023893222, 0.030197278 0.02941528 0.02393128, 0.030257255 0.029666752 0.023977533, 0.030051529 0.029486299 0.024039716, 0.030191928 0.028963953 0.023902774, 0.030120581 0.029194504 0.02393125, 0.029962167 0.02922903 0.024039462, 0.030119598 0.029453084 0.023977518, 0.030098096 0.028961942 0.023931265, 0.030131057 0.028730631 0.023931175, 0.031712502 0.029612884 0.023902804, 0.031643495 0.029544041 0.023893476, 0.031495556 0.029660657 0.023893446, 0.029936001 0.028958261 0.024039656, 0.030036241 0.029212937 0.023977429, 0.031324506 0.029739067 0.023893476, 0.030011609 0.028960034 0.023977458, 0.030047596 0.028708175 0.023977518, 0.029974401 0.028688863 0.024039492, -0.012883425 0.04123421 0.023894012, -0.012796402 0.041427493 0.0239034, -0.012952328 0.041303471 0.02390334, -0.012744606 0.041344762 0.023893952, -0.012616575 0.04151386 0.023903385, -0.011762142 0.04123272 0.023893937, -0.01169306 0.041301697 0.023903459, -0.011900872 0.041343808 0.023894086, -0.012422174 0.041557923 0.023903415, -0.01264751 0.041602254 0.02393195, -0.012432575 0.041651085 0.023931965, -0.012450486 0.041812241 0.024040088, -0.012442112 0.041737035 0.023978248, -0.01219371 0.041811973 0.024040416, -0.012202293 0.041736662 0.023978129, -0.012212127 0.041650832 0.023931891, -0.012846172 0.041506991 0.023931935, -0.013018608 0.041369677 0.023931697, -0.012700796 0.041755497 0.024040163, -0.012675971 0.041683838 0.023978055, -0.012892097 0.041580111 0.023978159, -0.013079673 0.041430891 0.02397798, -0.012932241 0.041644454 0.024040416, -0.013133138 0.041484624 0.024040252, -0.011848897 0.041426107 0.023903415, -0.012060851 0.041421056 0.023894072, -0.012028277 0.041513085 0.023903489, -0.012233794 0.041460767 0.023894072, -0.011626631 0.041368097 0.023931846, -0.011798918 0.04150556 0.023931921, -0.012222707 0.041557625 0.023903638, -0.012411356 0.041460887 0.023894101, -0.011997342 0.041601464 0.023931935, -0.011712313 0.041642934 0.024040148, -0.011752754 0.041578695 0.023978159, -0.011511922 0.041482538 0.024040222, -0.011565536 0.041429058 0.023978114, -0.012584478 0.041421562 0.023893893, -0.01194343 0.041754544 0.024040297, -0.011968672 0.041683137 0.023978233, -0.042982176 0.012163281 0.025245905, -0.043044031 0.012156293 0.025321871, -0.042865694 0.011649311 0.025245696, -0.042924389 0.011628821 0.025321588, -0.04296799 0.011613503 0.025408089, -0.043089986 0.012151286 0.025408193, -0.042408779 0.014193773 0.025599524, -0.042750284 0.013751566 0.025502041, -0.042401895 0.014187053 0.025502056, -0.043001831 0.013252452 0.02559939, -0.042758316 0.013756499 0.025599271, -0.042992786 0.013249159 0.025501743, -0.043117508 0.012705788 0.025501788, -0.042966008 0.013239861 0.025408134, -0.0430893 0.012702569 0.025408134, -0.042981759 0.012690246 0.02524592, -0.04304336 0.012697205 0.025321871, -0.042726174 0.013736382 0.025408149, -0.042381793 0.014166921 0.025408223, -0.042863712 0.013203979 0.025246069, -0.042922392 0.013224646 0.025321782, -0.042687073 0.013711646 0.025321648, -0.04234919 0.014134184 0.025321856, -0.042305335 0.014090091 0.025246128, -0.042634308 0.013678446 0.025246009, -0.042406499 0.010665119 0.025501683, -0.042753562 0.011101618 0.025501743, -0.04241322 0.010658234 0.025599226, -0.042761669 0.011096373 0.025599241, -0.042994872 0.011604279 0.025501892, -0.043004051 0.01160112 0.025599211, -0.042386204 0.010685012 0.025407955, -0.042729333 0.011116639 0.025408119, -0.043118268 0.012148038 0.025501966, -0.04312788 0.012147099 0.025599346, -0.042637706 0.011174321 0.025245711, -0.042690277 0.011141017 0.025321648, -0.042309448 0.010761887 0.025245801, -0.042353526 0.010717809 0.025321618, -0.043127075 0.012706682 0.02559942, -0.030773476 -0.03271696 0.025319159, -0.031127498 -0.032265678 0.025319219, -0.030806214 -0.032749847 0.025405675, -0.030729502 -0.032673031 0.025243521, -0.031166956 -0.032289669 0.02540566, -0.031557158 -0.031186 0.025596812, -0.031518593 -0.030594826 0.025499433, -0.031528011 -0.030593172 0.025596976, -0.031547606 -0.031185493 0.025499359, -0.031409204 -0.031757653 0.02540566, -0.031519055 -0.031183496 0.025405586, -0.031436309 -0.031766102 0.02549924, -0.03130585 -0.031724766 0.025243461, -0.031365171 -0.031743556 0.025319174, -0.031074226 -0.032233447 0.025243253, -0.031351149 -0.030027628 0.025499389, -0.031360075 -0.030023739 0.025596917, -0.031490549 -0.030599713 0.025405675, -0.031410977 -0.031175807 0.02524358, -0.031472936 -0.031180203 0.025319368, -0.031054959 -0.029515982 0.025499314, -0.031062737 -0.029510349 0.025597036, -0.031325236 -0.030038953 0.025405794, -0.031383604 -0.030617833 0.025243431, -0.031444892 -0.030607373 0.025319412, -0.030646354 -0.029088438 0.025499597, -0.030652449 -0.029080912 0.025596917, -0.031032071 -0.029533207 0.025405645, -0.031282693 -0.030057102 0.025319219, -0.031225517 -0.030081719 0.025243402, -0.030148536 -0.028769344 0.025499493, -0.030152649 -0.028760791 0.025597036, -0.030628219 -0.029110536 0.025405794, -0.03099525 -0.02956064 0.025319442, -0.03094545 -0.029598162 0.02524361, -0.029589489 -0.028576657 0.025499463, -0.029591516 -0.028567389 0.025597066, -0.030136153 -0.028794929 0.025405839, -0.030559391 -0.029194191 0.025243536, -0.030598938 -0.029146031 0.025319442, -0.028413057 -0.028596744 0.025596887, -0.029000789 -0.028521225 0.025499552, -0.028415725 -0.028606042 0.025499597, -0.029004157 -0.028658047 0.025243521, -0.028451189 -0.028738365 0.025243446, -0.028434947 -0.028678313 0.025319412, -0.029000551 -0.028511763 0.02559711, -0.030826285 -0.03276965 0.025499284, -0.031191245 -0.032304525 0.025499374, -0.03083317 -0.032776415 0.025596887, -0.03119953 -0.032309562 0.025596708, -0.029583484 -0.028604567 0.025405779, -0.031445414 -0.031769246 0.025596976, -0.030088842 -0.028892666 0.02524364, -0.030115917 -0.028836623 0.025319397, -0.029001549 -0.028549775 0.025405854, -0.028423056 -0.02863358 0.025405884, -0.029560462 -0.028710529 0.02524361, -0.029573649 -0.028649732 0.025319397, -0.029002622 -0.028595924 0.025319412, 0.010191366 -0.040782973 0.023898885, 0.010016471 -0.040763065 0.023889512, 0.010122329 -0.040851951 0.023889348, 0.0098969191 -0.040693611 0.023889482, 0.0097923875 -0.040552095 0.02389884, 0.0097670704 -0.040646166 0.023889437, 0.010372624 -0.040602282 0.024035707, 0.010219663 -0.04047358 0.024035543, 0.01031898 -0.040655747 0.023973614, 0.010072619 -0.04068312 0.0238989, 0.010257691 -0.040716782 0.023927405, 0.010126501 -0.040606409 0.023927271, 0.0099381506 -0.040605456 0.023898914, 0.010176063 -0.040535823 0.02397351, 0.0099779963 -0.040520281 0.023927346, 0.0098168552 -0.040461481 0.023927242, 0.010014653 -0.040442079 0.023973525, 0.0098392814 -0.040377915 0.023973614, 0.0098589808 -0.040304855 0.024035767, 0.01004678 -0.04037343 0.024035648, -0.037194222 -0.037102342 0.02714178, -0.040206671 -0.033814594 0.027142063, -0.037407666 -0.037315503 0.02704443, 0.034290433 0.040566087 0.026905239, 0.034455791 0.040761665 0.026718706, 0.030874729 0.043536946 0.026718676, 0.037788704 0.03769277 0.026718289, 0.037607417 0.037511989 0.02690497, 0.034108341 0.040350437 0.027048886, 0.033913657 0.04012014 0.02714631, 0.037194118 0.037099689 0.027145892, 0.037407503 0.037312672 0.027048528, 0.030726761 0.043328106 0.026905268, 0.027071297 0.045998484 0.026718706, 0.030563295 0.043097764 0.027049035, 0.030388981 0.042851686 0.027146369, 0.026941299 0.045777783 0.026905417, 0.02307263 0.048128411 0.026718855, 0.026798159 0.045534447 0.027049243, 0.026645184 0.045274645 0.027146578, 0.022961974 0.047897503 0.026905477, 0.018907875 0.049911797 0.026719034, 0.022839874 0.04764308 0.027049065, 0.022709608 0.047371164 0.027146608, 0.018817216 0.049672365 0.026905745, 0.014606774 0.051335394 0.026719123, 0.018717051 0.049408242 0.027049392, 0.018610239 0.049126476 0.027146608, 0.014536679 0.051089257 0.026905715, 0.0102005 0.052389383 0.026719213, 0.014459491 0.050817668 0.027049571, 0.014376968 0.050527692 0.027146846, 0.010151535 0.052137926 0.026905686, 0.005720675 0.053065583 0.026719093, 0.010097563 0.051860929 0.027049452, 0.010039806 0.051564917 0.027146786, 0.0056932271 0.052810922 0.026905686, 0.0011996329 0.053359747 0.026719168, 0.0056630373 0.052530453 0.02704972, 0.0056307018 0.052230656 0.027146816, 0.0011939406 0.053103521 0.026905715, -0.0033301413 0.053269163 0.026719227, 0.0011875331 0.052821413 0.027049378, 0.0011807382 0.052519858 0.027146891, -0.0033140779 0.053013653 0.02690585, -0.0078357458 0.052794948 0.026719138, -0.0032964051 0.052731723 0.027049601, -0.0032775998 0.052430898 0.027147055, -0.0077979863 0.052541614 0.026905701, -0.0077565908 0.052262172 0.027049378, -0.0077123642 0.051963985 0.027146757, -0.012225986 0.051690876 0.02690576, -0.012284786 0.051940024 0.026719153, -0.012161046 0.051416263 0.027049407, -0.012091577 0.05112277 0.027146742, -0.016565681 0.050467744 0.026905596, -0.016645521 0.050711274 0.026719123, -0.016477704 0.050199658 0.027049407, -0.016383767 0.049913213 0.027146757, -0.020786211 0.048881322 0.026905447, -0.020886362 0.04911682 0.026719123, -0.024976537 0.047168553 0.026718721, -0.020675749 0.048621267 0.02704908, -0.020557657 0.048344031 0.027146667, -0.024856791 0.046942383 0.026905507, -0.024724722 0.046692804 0.02704899, -0.024583608 0.046426401 0.027146652, -0.028748423 0.044665158 0.026905283, -0.028886884 0.04488048 0.026718706, -0.028595582 0.044427946 0.027049065, -0.028432369 0.044174105 0.027146444, -0.03243278 0.042066365 0.026905209, -0.032589108 0.042269006 0.026718497, -0.032260478 0.041842639 0.027048901, -0.032076389 0.041603848 0.02714622, -0.035883605 0.039164186 0.026905134, -0.036056384 0.039352879 0.026718453, -0.035692751 0.038956121 0.027048796, -0.035489231 0.038733855 0.027146101, -0.039075762 0.035979852 0.02690497, -0.039264157 0.03615351 0.026718095, -0.042188838 0.032693416 0.026718035, -0.03886807 0.0357887 0.027048573, -0.03864637 0.03558448 0.027145892, -0.041986465 0.032536551 0.026904702, -0.04176335 0.032363519 0.027048439, -0.041524872 0.032179058 0.027145803, -0.044594526 0.028858602 0.026904523, -0.04480958 0.028997749 0.026717767, -0.044357538 0.028705269 0.027048334, -0.044104442 0.028541505 0.027145714, -0.046881512 0.024972692 0.02690421, -0.047107488 0.025093228 0.026717603, -0.049065843 0.021007821 0.026717409, -0.046632424 0.024840102 0.027048051, -0.0463662 0.024698317 0.027145371, -0.048830584 0.02090694 0.026903898, -0.048570946 0.020795956 0.027047753, -0.048293903 0.020677105 0.027145073, -0.050427839 0.016690582 0.026903749, -0.050670937 0.016770959 0.026717126, -0.051910639 0.012413353 0.026716828, -0.050159737 0.016601905 0.027047306, -0.049873531 0.01650697 0.027144998, -0.051661581 0.012353733 0.02690351, -0.051387101 0.012288213 0.027047172, -0.051093891 0.012218013 0.027144581, -0.052523285 0.007928133 0.026903287, -0.05277653 0.0079663992 0.026716605, -0.052244335 0.0078859478 0.027047038, -0.051946208 0.0078409016 0.027144283, -0.053006634 0.0034452826 0.026902795, -0.053262189 0.0034618825 0.026716247, -0.053364024 -0.0010674298 0.026716128, -0.052724987 0.0034269989 0.027046636, -0.052424148 0.0034075379 0.027144119, -0.053108051 -0.0010624081 0.026902631, -0.052825645 -0.0010567307 0.027046517, -0.052524239 -0.0010508001 0.027143806, -0.052826717 -0.0055624992 0.026902467, -0.053081274 -0.0055893511 0.026715994, -0.05241631 -0.010070711 0.026715562, -0.052545756 -0.0055330247 0.027046084, -0.052246079 -0.0055014044 0.027143523, -0.052164763 -0.010022402 0.026902005, -0.051887497 -0.009969309 0.027046084, -0.051591277 -0.0099124312 0.027143359, -0.051127017 -0.014410242 0.02690202, -0.051373467 -0.014479786 0.026715443, -0.050855175 -0.014333621 0.027045816, -0.050565034 -0.014251977 0.02714327, -0.049720898 -0.018694133 0.026901916, -0.049960509 -0.01878427 0.026715279, -0.048187762 -0.02295357 0.026714921, -0.049456626 -0.018594801 0.027045667, -0.049174443 -0.018488735 0.027142957, -0.047956556 -0.02284345 0.026901394, -0.047701612 -0.02272208 0.02704531, -0.047429398 -0.022592336 0.027142659, -0.045846567 -0.02682808 0.026901156, -0.04606767 -0.026957482 0.026714653, -0.04361555 -0.030767158 0.026714414, -0.045602903 -0.026685476 0.027045146, -0.045342699 -0.026533321 0.02714251, -0.043406397 -0.030619562 0.02690123, -0.043175578 -0.030456886 0.027044937, -0.042929366 -0.030283108 0.027142361, -0.040653408 -0.034190401 0.026900932, -0.040849492 -0.034355089 0.026714206, -0.037788823 -0.037695765 0.026714236, -0.037607595 -0.037514806 0.026900649, -0.040437281 -0.034008771 0.027044609, 0.013789296 0.044473946 0.025394082, 0.013177067 0.044963419 0.025394291, 0.013789147 0.044474602 0.015394151, 0.013177037 0.044963986 0.015394002, 0.012471318 0.045304939 0.015394121, 0.012471259 0.045304283 0.025394082, 0.011707455 0.045480415 0.015394092, 0.011707455 0.045479655 0.025394112, 0.010923654 0.045481309 0.015394241, 0.010923624 0.045480818 0.025394067, 0.010159284 0.045307934 0.015394062, 0.010159403 0.045307189 0.025394171, 0.0094527304 0.044968709 0.01539427, 0.0094527602 0.044968098 0.025394186, 0.008839339 0.044480368 0.025394171, 0.0088392794 0.044480965 0.015394002, 0.034464017 0.029885605 0.024978817, 0.03244856 0.029348448 0.022893369, 0.032364517 0.029580086 0.022893369, 0.034256041 0.030459106 0.024979055, 0.032241508 0.029793918 0.022893429, 0.033951715 0.030987918 0.024979055, 0.032083377 0.029982954 0.022893369, 0.033560112 0.031455651 0.024978995, 0.012074992 -0.03981474 0.024453625, 0.012038767 -0.038940221 0.024975091, 0.012551859 -0.039594173 0.024975121, 0.012896016 -0.040350571 0.024975106, 0.01187098 -0.040574506 0.023932129, 0.011194721 -0.040373817 0.023410738, 0.0099845231 -0.043832213 0.023932204, 0.0098598301 -0.042794243 0.022889212, 0.010177255 -0.042684555 0.022889212, 0.011086285 -0.044562146 0.024974838, 0.010300666 -0.044832915 0.024974942, 0.010967687 -0.043426394 0.023932084, 0.010459915 -0.042503476 0.022889212, 0.010692015 -0.042260706 0.022889331, 0.01236023 -0.043512926 0.024974823, 0.011785835 -0.044113636 0.024974689, 0.011687174 -0.04264307 0.023932189, 0.010860339 -0.041970238 0.02288951, 0.012776539 -0.0427939 0.024974853, 0.012008384 -0.041629091 0.023932278, 0.010955319 -0.041648164 0.022889301, 0.010971665 -0.041312665 0.02288942, 0.01305224 -0.041166753 0.024974987, 0.013011619 -0.041996732 0.024975121, 0.010908544 -0.040983066 0.022889301, 0.0094740689 -0.043345615 0.023410454, 0.0091932416 -0.042777389 0.022889391, 0.0095255524 -0.042825773 0.022889197, 0.0086508244 -0.044791669 0.024974808, 0.0094272494 -0.044387624 0.024453327, 0.0094732493 -0.044910923 0.024974763, 0.010769472 -0.040677339 0.022889465, 0.010562032 -0.040413126 0.02288942, -0.010054618 0.039729685 0.023936659, -0.010989338 0.040204287 0.022893935, -0.010918319 0.04051289 0.022893965, -0.0088460743 0.040276438 0.024979562, -0.0090214908 0.039512575 0.024979621, -0.0098664463 0.04066965 0.023936614, -0.010917991 0.040829539 0.02289395, -0.0088450611 0.041060194 0.024979502, -0.010052413 0.041610345 0.023936749, -0.010988146 0.041138202 0.022893965, -0.0090184212 0.041824639 0.024979711, -0.010715276 0.039595425 0.023415208, -0.011324704 0.039671689 0.022893921, -0.011127025 0.039919049 0.022893906, -0.0098517537 0.038194641 0.024979293, -0.0098488927 0.039014786 0.024458155, -0.00936234 0.038806751 0.024979621, -0.010712713 0.041746303 0.023415297, -0.011125088 0.041423902 0.022894055, -0.01132232 0.041671738 0.022893891, -0.0098455548 0.043144524 0.02497977, -0.0098448992 0.042324379 0.024458185, -0.0093576908 0.042531118 0.02497974, -0.01201281 0.006377548 0.025391892, -0.012012735 0.0063774288 0.027891994, -0.012460366 0.0069121569 0.027892053, -0.012606651 0.0071375221 0.025392026, -0.012808293 0.0075164139 0.027892038, -0.013178989 0.0090794861 0.029970378, -0.013045952 0.0081719905 0.027892128, -0.013045937 0.0081718266 0.02981247, -0.013001338 0.0080171674 0.025392145, -0.013173908 0.0089659095 0.025391966, -0.013114572 0.0099282712 0.025392205, -0.013100281 0.010001361 0.030098721, -0.012826458 0.010848671 0.0253921, -0.012811288 0.010881603 0.030188963, -0.012326509 0.011673242 0.025392234, -0.012325421 0.011674717 0.030235976, -0.011666372 0.012336478 0.030236781, -0.011643961 0.012354627 0.025392279, -0.010873973 0.012826264 0.030190855, -0.01081799 0.012852192 0.025392279, -0.0099946409 0.013118476 0.030101702, -0.0098971277 0.013137892 0.025392488, -0.0090734512 0.01320073 0.02997455, -0.0081408471 0.013064772 0.027892366, -0.0086039901 0.013160378 0.029897138, -0.0081409216 0.013064623 0.029812768, -0.0089342594 0.013194963 0.025392309, -0.0079862177 0.013019845 0.025392428, -0.0074859411 0.012825489 0.027892396, -0.0071072578 0.012622997 0.025392413, -0.0068824738 0.012476087 0.027892351, -0.0063489079 0.012027457 0.025392219, -0.0063489228 0.012027174 0.027892441, -0.0062123835 -0.015379131 0.025390595, -0.0062123388 -0.015379399 0.030125394, -0.0066609234 -0.014843464 0.030039042, -0.006806165 -0.014619291 0.025390655, -0.0070096999 -0.014236748 0.029932827, -0.0072454065 -0.013584748 0.027890995, -0.0072454512 -0.013584808 0.029811144, -0.0072007924 -0.013739422 0.025390938, -0.0073734224 -0.01279065 0.025390834, -0.0073793381 -0.012644649 0.027890965, -0.0073140711 -0.011828259 0.025390968, -0.0072880387 -0.011699289 0.027890995, -0.0070260316 -0.010907888 0.025390923, -0.0069762766 -0.010801971 0.027891055, -0.0065260977 -0.010083467 0.025390938, -0.006461665 -0.010003805 0.02789098, -0.0058433861 -0.0094024986 0.025390998, -0.0057736486 -0.0093491077 0.027891308, -0.0050174147 -0.0089046806 0.025391221, -0.0049504489 -0.0088753104 0.027891114, -0.0040965229 -0.0086188316 0.025391161, -0.004038766 -0.0086088181 0.027891144, -0.0031339228 -0.0085618496 0.025391147, -0.0030900538 -0.0085648149 0.027891323, -0.0021856129 -0.0087368935 0.025391102, -0.0021577179 -0.0087459087 0.027891174, -0.0013068467 -0.009133637 0.025391117, -0.0012942851 -0.009141311 0.027891055, -0.00054851174 -0.009729445 0.025391027, -0.00054863095 -0.0097294301 0.027891204, 0.0091430694 0.0012698174 0.027891546, 0.009729147 0.00052262843 0.025391489, 0.0097291917 0.00052274764 0.027891532, 0.0091355294 0.0012824535 0.025391653, 0.008749634 0.002134338 0.02789183, 0.008740738 0.0021621287 0.025391594, 0.008570984 0.0030671507 0.02789183, 0.0085679889 0.0031109303 0.025391877, 0.008617416 0.0040156245 0.027891949, 0.0086275488 0.0040735155 0.025391921, 0.0088861138 0.0049266517 0.027891889, 0.0089155883 0.0049937367 0.025391906, 0.0093621165 0.0057485998 0.027891949, 0.0094155669 0.0058182627 0.025391921, 0.010018349 0.0064352006 0.027892038, 0.010098249 0.0064991713 0.025391936, 0.01081793 0.0069475323 0.027892038, 0.010924146 0.0069971234 0.025392026, 0.011715904 0.0072570592 0.027892128, 0.011845082 0.0072829574 0.0253921, 0.012661383 0.0073461682 0.027892038, 0.013601378 0.0072098523 0.027892098, 0.013601348 0.0072097331 0.029812321, 0.014254957 0.0069709867 0.029934525, 0.012807667 0.0073398203 0.025391981, 0.013755962 0.007164821 0.025391802, 0.014634788 0.0067680329 0.025391847, 0.014856651 0.0066227615 0.030039892, 0.015393034 0.0061725378 0.025391906, 0.015393302 0.0061720014 0.030126244, 0.016940579 -0.0092795491 0.030874595, 0.01797694 -0.0067324489 0.030873343, 0.018088326 -0.0067741126 0.030874714, 0.016836062 -0.009222582 0.030873403, 0.017758131 -0.0066504478 0.030828983, 0.017866388 -0.0066911429 0.030858219, 0.016631231 -0.0091099888 0.030828774, 0.016732395 -0.0091655999 0.03085804, 0.01875183 -0.0041055381 0.030873492, 0.018868148 -0.0041309595 0.030874774, 0.018523753 -0.0040556043 0.030828983, 0.018636614 -0.0040803254 0.030858323, -0.013425052 -0.013393119 0.030828565, -0.01138258 -0.015167415 0.030828491, -0.0135068 -0.013474733 0.030857623, 0.019145101 -0.0013951808 0.030873582, 0.019263864 -0.0014036745 0.030874878, 0.019027323 -0.0013864487 0.030858383, -0.013590485 -0.01355809 0.030873075, -0.011522979 -0.015354231 0.030872896, -0.013674825 -0.013642207 0.030874208, 0.018912092 -0.0013781488 0.030829132, -0.01159434 -0.015449464 0.030873984, -0.0114519 -0.015259817 0.030857578, 0.019148305 0.0013436675 0.030873761, 0.019267321 0.001352191 0.030874938, 0.019030556 0.0013355017 0.030858666, 0.01891543 0.001327306 0.030829355, -0.0092207193 -0.016837746 0.030872822, -0.0092779249 -0.016942188 0.030874059, -0.0091639906 -0.016734123 0.030857474, -0.0091084391 -0.016633019 0.030828312, 0.018762067 0.0040551722 0.030874014, 0.018878415 0.0040804148 0.030875117, -0.0067307353 -0.017978683 0.030872598, 0.018533796 0.0040058047 0.030829415, 0.018646613 0.0040303171 0.030858785, -0.006772548 -0.018090174 0.030873969, -0.0066490173 -0.017759919 0.030828312, -0.006689474 -0.017867997 0.030857563, 0.017993733 0.0066840053 0.030874178, 0.018105358 0.0067255348 0.030875415, 0.017883018 0.0066429526 0.030858919, -0.0041039437 -0.018753648 0.030872732, 0.017774835 0.0066026896 0.030829847, -0.0041292459 -0.018870115 0.030874014, -0.0040539056 -0.018525407 0.030828267, -0.0040785819 -0.018638298 0.030857503, 0.016859159 0.0091767311 0.030874252, 0.01696381 0.0092337132 0.030875519, 0.016755447 0.0091202259 0.030858979, -0.0013933629 -0.019146845 0.030872896, -0.001402095 -0.019265532 0.030873984, 0.016653925 0.0090651214 0.030829951, -0.0013764948 -0.018913805 0.030828476, -0.0013847798 -0.019028947 0.030857503, 0.013674527 0.013638794 0.030875921, 0.015381217 0.011482567 0.030874386, 0.013590306 0.013554707 0.030874595, 0.015476659 0.011553839 0.030875668, 0.0013454556 -0.019150168 0.030872554, 0.0013536811 -0.01926899 0.03087391, 0.015286699 0.011411905 0.030858994, 0.013506711 0.013471335 0.030859277, 0.013424963 0.013389632 0.03083007, 0.0013370216 -0.019032195 0.030857459, 0.015194118 0.011342719 0.030829951, 0.0013289303 -0.018917114 0.030828223, 0.0040568262 -0.018763825 0.030872822, 0.0040819496 -0.018880218 0.030873969, 0.0040074289 -0.01853542 0.030828193, 0.004031837 -0.018648177 0.030857474, 0.006685704 -0.017995507 0.030872703, 0.006727159 -0.01810731 0.030873924, 0.0066042989 -0.017776549 0.030828357, 0.0066444427 -0.017884761 0.030857578, 0.0091783404 -0.016860932 0.030872717, 0.0092352927 -0.0169653 0.030874029, 0.0090667903 -0.016655803 0.030828401, 0.009121865 -0.01675719 0.030857578, 0.011484206 -0.01538305 0.030873001, 0.011555612 -0.015478522 0.030874103, 0.011344641 -0.015195906 0.030828431, 0.011413634 -0.015288457 0.030857772, 0.013556361 -0.013592139 0.030873016, 0.013640374 -0.01367636 0.030874237, 0.013472885 -0.013508558 0.030857861, 0.013391405 -0.01342684 0.030828565, 0.015352517 -0.011524528 0.03087312, 0.015447706 -0.011595979 0.030874401, 0.015165672 -0.011384264 0.030828625, 0.015257999 -0.011453509 0.03085795, -0.043332085 -0.016034648 0.015390649, -0.043331981 -0.016035467 0.027201995, -0.044149652 -0.015736908 0.027062446, -0.044150919 -0.015735492 0.015390709, -0.044901863 -0.015301526 0.026942089, -0.044904917 -0.015298948 0.015390605, -0.045571938 -0.014738545 0.026843607, -0.045571879 -0.014737934 0.015390798, 0.010524064 0.037156135 0.028437629, 0.010372728 0.037280411 0.028430209, 0.010524005 0.037156373 0.025393769, 0.010349035 0.037296087 0.025393501, 0.010200083 0.037373111 0.028426275, 0.010147452 0.037393495 0.025393739, 0.0099738836 0.037437171 0.028425872, 0.0099292099 0.037443668 0.02539362, 0.0097390115 0.03744705 0.02843067, 0.0097053051 0.037443891 0.025393605, 0.0095082819 0.037401542 0.028440073, 0.0094868839 0.037394345 0.025393635, 0.0092944503 0.037303135 0.028453529, 0.0092850924 0.037297368 0.025393665, 0.0091097951 0.037157819 0.028470874, 0.0091097951 0.037158117 0.025393695, 0.0095111132 -0.021011084 0.030647099, 0.0085589737 -0.021416724 0.030647084, 0.024342984 -0.016046986 0.030113176, 0.018940464 -0.013159037 0.030647561, 0.019511923 -0.012295932 0.030647546, 0.0070244372 -0.021967947 0.03064692, 0.0075895339 -0.02177915 0.030647188, 0.0093735754 -0.022601679 0.030541927, 0.024908409 -0.018165529 0.029930145, 0.022629961 -0.015721798 0.030273438, 0.021364406 -0.0048931539 0.030725494, 0.020491183 -0.0056200773 0.030767322, 0.022003829 -0.0072879046 0.030639455, 0.018331245 -0.013995528 0.030647412, 0.021901906 -0.016721264 0.030273363, 0.025473416 -0.020281911 0.029724151, 0.017685026 -0.014803976 0.030647457, 0.014398873 0.014361039 0.030821532, 0.016375482 0.013817221 0.030757576, 0.015122712 0.015083238 0.030761689, 0.015846401 0.015805215 0.030696228, 0.021129832 -0.017687097 0.030273229, 0.017003089 -0.015582398 0.030647472, 0.016905025 0.011828944 0.030805081, 0.017434567 0.009840548 0.03083913, 0.026037872 -0.022396326 0.029494449, 0.023639992 -0.019788206 0.029929966, 0.020315081 -0.018617421 0.030273303, 0.017964199 0.0078519881 0.030860752, 0.018494174 0.005863443 0.030870825, 0.016286835 -0.016329512 0.030647561, 0.022728413 -0.020828858 0.029929906, 0.019024298 0.0038749129 0.030870184, 0.019459397 -0.019509926 0.03027305, 0.01955469 0.0018864274 0.030858651, 0.020085245 -0.00010189414 0.030835062, 0.026601464 -0.024508253 0.029240951, 0.025320634 -0.023204252 0.029494464, 0.015538022 -0.017043769 0.030647412, 0.020724759 -0.002497822 0.030790195, 0.021771193 -0.021827519 0.02993001, 0.018564582 -0.020363301 0.030273214, 0.0046738982 -0.021334082 0.030729726, 0.024254173 -0.024316788 0.029494584, 0.026547894 -0.027232826 0.028962955, 0.026674896 -0.027256742 0.028946459, 0.0021094084 -0.020642459 0.030796394, 0.026792124 -0.027249366 0.028934479, 0.02689296 -0.027218789 0.028926939, 0.026985601 -0.027166843 0.028922409, 0.027053908 -0.027107716 0.028921574, -0.0004555434 -0.019950941 0.030841216, 0.027104363 -0.027045459 0.028922662, 0.027143702 -0.026976287 0.028926119, 0.027171224 -0.026901796 0.02893135, 0.027185872 -0.026824042 0.028938264, 0.027187422 -0.026744753 0.028946638, 0.027164534 -0.026617691 0.028963014, -0.0030206889 -0.019259751 0.030865029, 0.014757693 -0.017723769 0.030647457, 0.020770043 -0.022782296 0.029929996, -0.0055857897 -0.018568933 0.030869991, -0.0081513077 -0.017878368 0.030857041, 0.017632395 -0.021175787 0.030273095, 0.023138955 -0.025380433 0.029494435, 0.023433834 -0.026393324 0.029364675, -0.010716692 -0.017187983 0.030824795, 0.013947904 -0.018368006 0.030647248, 0.019727007 -0.023691162 0.029929742, -0.013281867 -0.016498148 0.030771211, 0.020315543 -0.025552616 0.029713422, 0.01666458 -0.021945417 0.030273035, 0.017193109 -0.02471073 0.030011117, -0.014398992 -0.014364541 0.030819893, 0.013109773 -0.018975258 0.030647397, -0.015122876 -0.015086651 0.030760095, -0.01584661 -0.015808433 0.030694276, 0.015663311 -0.022671178 0.030272886, 0.021393567 -0.0086143166 0.030647755, 0.012245268 -0.019544363 0.030647174, 0.022642985 -0.0096818805 0.03053011, 0.020985544 -0.0095655173 0.030647799, 0.014066637 -0.023867458 0.030258715, 0.014630601 -0.023350999 0.030272797, 0.023210049 -0.011805102 0.030412242, 0.011721089 -0.023234814 0.030412912, 0.011356115 -0.02007404 0.030647174, 0.02053532 -0.010497421 0.030647755, 0.027179778 -0.026680723 0.028954327, 0.023776695 -0.013926849 0.030273288, 0.020043775 -0.011408031 0.03064774, 0.010444179 -0.020563319 0.030647233, -0.0093282461 0.038861826 0.028483421, -0.0098517239 0.038194358 0.028573081, -0.0089817047 0.039631605 0.028365895, -0.0088302493 0.040456593 0.028227955, -0.0088785291 0.041290268 0.028077126, -0.0091236532 0.042090416 0.027921438, -0.0094341636 0.042647913 0.027805597, -0.0098455548 0.043144315 0.027695104, 0.034257054 0.030457333 0.027381331, 0.034464046 0.029885381 0.027425677, 0.033951402 0.030988514 0.027355522, 0.033560127 0.031455591 0.027349591, 0.0095003247 -0.044911489 0.027364343, 0.008650884 -0.044791847 0.027421564, 0.010271162 -0.044839367 0.027344957, 0.01093863 -0.044629544 0.027355134, 0.011546895 -0.04429397 0.027390659, 0.01207836 -0.043843791 0.027450055, 0.012507811 -0.04330048 0.027530596, 0.012821108 -0.042685464 0.027628928, 0.013007522 -0.04202117 0.027741805, 0.013059989 -0.041335523 0.027864143, 0.01297769 -0.040653273 0.027991414, 0.012763858 -0.040001005 0.028118432, 0.01245144 -0.039438501 0.028233439, 0.012038916 -0.038940221 0.028340429, -0.015525058 -0.053805754 0.015388519, -0.020421863 -0.052144244 0.012888685, -0.019999757 -0.052308083 0.019284606, -0.024332404 -0.050438419 0.019284889, -0.024658114 -0.050279871 0.012888968, -0.028492451 -0.048210755 0.019284979, 0.045534775 -0.032598063 0.012889802, 0.042687312 -0.036246806 0.012889728, 0.043385044 -0.035409033 0.019285545, 0.040250003 -0.0389359 0.015389264, 0.040250018 -0.038936004 0.019285411, -0.028725892 -0.048071802 0.012888968, -0.032449946 -0.045641109 0.019285142, 0.039647549 0.039547563 0.012893945, 0.042778075 0.036138549 0.012893647, 0.039647534 0.039547324 0.019289792, 0.042836353 0.036068901 0.019289643, -0.032597452 -0.045535386 0.012888998, -0.036177203 -0.042746976 0.019285336, 0.04561621 0.032482401 0.012893289, -0.03624627 -0.042688057 0.012889296, -0.039647654 -0.039549336 0.019285321, 0.045721039 0.032334626 0.019289434, -0.039647579 -0.039549008 0.01288949, 0.038834184 -0.040348202 0.015389219, 0.035299197 -0.043474808 0.019285128, 0.038834006 -0.040348455 0.019285396, 0.039548263 -0.03964825 0.01288937, 0.039783671 -0.039412156 0.015389428, 0.048142791 0.028604671 0.012893319, 0.039311722 -0.039882988 0.015389487, 0.048280984 0.028370485 0.019289076, 0.050340727 0.024531201 0.012892991, 0.050498232 0.024205014 0.019288898, 0.036139086 -0.042778656 0.012889206, 0.052194476 0.020290345 0.012892902, 0.032483086 -0.04561691 0.012889028, 0.031513944 -0.046292186 0.019284979, 0.052356869 0.01986751 0.019288719, 0.053843677 0.015389234 0.015392393, 0.028605312 -0.04814367 0.012888983, 0.027504653 -0.048780993 0.019284874, 0.053843752 0.015389144 0.01928857, 0.024531975 -0.050341487 0.012888804, 0.023300201 -0.050923482 0.019284815, 0.053691834 0.015910909 0.012892723, 0.054023221 0.014747173 0.015392482, 0.020291045 -0.052195176 0.012888744, 0.054194838 0.014102921 0.015392363, 0.05435881 0.013456747 0.015392363, 0.018930301 -0.052704439 0.01928471, 0.055298954 0.008832261 0.019288123, 0.054358989 0.013456494 0.019288391, 0.01591152 -0.053692639 0.012888566, 0.014426008 -0.054110944 0.019284576, 0.054822415 0.011422768 0.012892246, 0.011423364 -0.054823205 0.012888581, 0.0098193288 -0.055133402 0.019284442, 0.055578619 0.0068564564 0.012892008, 0.055846274 0.0041452944 0.019287884, 0.006857127 -0.055579364 0.012888536, 0.055954948 0.0022434443 0.01289171, 0.055997029 -0.00057131052 0.01928772, 0.0051427782 -0.055764407 0.019284427, 0.0022441298 -0.055955738 0.012888506, 0.055949152 -0.0023850352 0.012891531, 0.055750147 -0.00528346 0.019287407, 0.0004298985 -0.055999428 0.019284487, 0.05556123 -0.0069968551 0.012891158, 0.055107564 -0.0099584609 0.01928708, -0.0023843944 -0.055949911 0.012888461, -0.0042862594 -0.055836678 0.019284442, -0.0069964379 -0.055561975 0.012888581, -0.0089718252 -0.055277616 0.019284487, 0.05479379 -0.011561349 0.01289095, 0.054073587 -0.014562652 0.019286752, 0.053651839 -0.016046703 0.012890786, 0.052655727 -0.019063517 0.019286633, -0.013593704 -0.054325864 0.015388533, -0.013593659 -0.054326147 0.019284531, -0.011560753 -0.054794475 0.012888685, 0.052143618 -0.020422474 0.012890473, 0.050863907 -0.023428798 0.019286335, 0.050279036 -0.02465871 0.012890384, 0.048710927 -0.0276279 0.019286096, -0.015524879 -0.053806156 0.019284517, 0.048071131 -0.028726593 0.012889951, 0.046212018 -0.03163074 0.019285858, -0.016046181 -0.05365254 0.012888551, -0.014239579 -0.054160148 0.015388519, -0.01488331 -0.053986773 0.015388504, 0.047189891 0.033602685 0.021492034, 0.043370664 0.034203693 0.023804367, 0.044253588 0.037384734 0.021492362, 0.040182784 0.033847675 0.026116818, 0.042884037 0.03035301 0.026116669, 0.047048464 0.028937116 0.023804277, 0.049803585 0.029591054 0.021491826, 0.052077189 0.025377184 0.021491498, 0.040615365 -0.039302662 0.022701129, 0.040912673 -0.041016459 0.021487802, 0.039199561 -0.040715083 0.02270104, 0.045282066 0.026643515 0.026116252, 0.044159949 -0.037497997 0.021487981, 0.053995162 0.020989895 0.021491468, 0.050089732 0.023279712 0.023803979, 0.047360212 0.022746086 0.026116133, 0.049103454 0.018687531 0.026115835, 0.050499737 0.014497072 0.026115641, 0.052453801 0.017307207 0.023803473, 0.054810092 0.015646532 0.022290409, 0.055544153 0.016459316 0.021491051, 0.037385851 -0.044254899 0.021487832, 0.05532518 0.013714105 0.022290319, 0.05410853 0.01110059 0.023803189, 0.051014915 0.012564644 0.026115537, 0.051890016 0.0082352459 0.026115239, 0.056713581 0.011816323 0.021490932, 0.057495922 0.0070926845 0.021490574, 0.055031642 0.0047439933 0.023802832, 0.052398458 0.0038475394 0.026115075, 0.052536666 -0.00056730211 0.026114747, 0.057885244 0.0023203939 0.02149041, 0.055210382 -0.0016768277 0.023802444, 0.052303404 -0.0049780607 0.026114583, 0.057879224 -0.0024677515 0.021490142, 0.057477951 -0.0072389841 0.021489754, 0.054642498 -0.0080750138 0.023801923, 0.051700637 -0.0093536675 0.026114076, 0.056683868 -0.011960685 0.021489516, 0.053335711 -0.014364198 0.023801595, 0.050732389 -0.013663262 0.026114061, 0.04940559 -0.017876238 0.026113823, 0.055502608 -0.016600728 0.021489203, 0.051307708 -0.020458862 0.023801282, 0.047729567 -0.02196297 0.02611348, 0.053942412 -0.021127477 0.021489054, 0.052013397 -0.025509834 0.02148889, 0.048585594 -0.026277065 0.023801029, 0.04571636 -0.025894389 0.026113361, 0.049729243 -0.029717952 0.021488562, 0.04520683 -0.031739846 0.023800686, 0.043379888 -0.029642746 0.026113272, 0.04073678 -0.033181697 0.026112914, 0.047105417 -0.033723071 0.021488234, 0.041216478 -0.036773384 0.023800492, 0.03780587 -0.036486223 0.026112795, 0.040222824 -0.038908944 0.023177937, 0.036668897 -0.041309819 0.023800373, 0.038806826 -0.040321514 0.023177862, 0.036389947 -0.03789857 0.026112556, 0.033078179 -0.040821299 0.026112452, 0.031625256 -0.04528749 0.023799941, 0.029532567 -0.043455482 0.026112527, 0.025778234 -0.045782536 0.026112214, 0.033603698 -0.047191024 0.021487609, 0.029592007 -0.049804941 0.02148746, 0.026154101 -0.048652664 0.023799717, 0.021841839 -0.047785863 0.02611208, 0.025378168 -0.052078649 0.02148734, 0.020328984 -0.051359951 0.023799583, 0.017750978 -0.049451694 0.02611199, 0.020991027 -0.05399628 0.021487266, 0.016460404 -0.0555453 0.021487042, 0.014229238 -0.0533728 0.023799494, 0.013534769 -0.050768003 0.026112005, 0.0092228353 -0.051725537 0.026111871, 0.01181747 -0.056715101 0.021487042, 0.0079370439 -0.054663748 0.023799568, 0.0048455894 -0.052317396 0.026111841, 0.0070935786 -0.057497025 0.021486878, 0.0015374124 -0.055215731 0.023799315, 0.00043423474 -0.052539453 0.026111901, 0.0023214668 -0.057886466 0.021486878, -0.0024665892 -0.057880446 0.021486953, -0.0048830509 -0.055020735 0.023799375, -0.0039803684 -0.052390262 0.026111856, -0.0083665997 -0.051870793 0.026111886, -0.0072377771 -0.057479233 0.021486968, -0.011237413 -0.054081783 0.023799345, -0.012693882 -0.0509848 0.02611196, -0.013853788 -0.055291846 0.02228649, -0.011959583 -0.056685179 0.021487176, -0.015785068 -0.054772004 0.022286266, -0.017439827 -0.05241169 0.023799673, -0.014624894 -0.050464675 0.026111826, -0.018811926 -0.04905808 0.02611196, -0.016599596 -0.05550389 0.021487027, -0.021126419 -0.053943515 0.021487221, -0.023406401 -0.05003269 0.023799822, -0.022865996 -0.047304526 0.026112065, -0.026758477 -0.045216799 0.026112139, -0.025508732 -0.052014723 0.021487117, -0.02905637 -0.046977073 0.023799837, -0.030461803 -0.042809322 0.026112527, -0.029716849 -0.04973039 0.02148743, -0.033721894 -0.047106817 0.021487579, -0.034313649 -0.04328613 0.023800194, -0.033949822 -0.040099472 0.026112631, -0.037496671 -0.044161052 0.021487743, 0.04030022 0.035772577 0.024960577, 0.037197694 0.037103206 0.026116937, 0.042316571 0.037562519 0.022648424, 0.041015282 0.04091157 0.02149266, -0.035874858 -0.040212065 0.024956226, -0.037197784 -0.037106156 0.026112676, -0.037669688 -0.042223632 0.022644162, -0.041015491 -0.040913969 0.021487862, 0.039199486 -0.040714785 0.019875094, 0.039067134 -0.040582046 0.019661531, 0.04061532 -0.039302364 0.019875214, 0.040483192 -0.039169833 0.019661874, -0.015784979 -0.054772004 0.020424753, -0.013853833 -0.05529207 0.020424694, 0.055325359 0.01371412 0.020428598, 0.054810166 0.015646443 0.020428687, 0.032748371 0.030646086 0.025246918, 0.032309547 0.030992225 0.025246948, 0.031801462 0.031224817 0.025246948, 0.031252816 0.031331301 0.025246978, 0.030694604 0.031305447 0.025247067, 0.030158386 0.031148732 0.025246903, 0.029674098 0.030869842 0.025246888, 0.029269144 0.030484825 0.025246873, 0.028966323 0.030014992 0.025246948, 0.028782949 0.029487118 0.025246873, 0.028729215 0.028930828 0.025246724, 0.028807983 0.028377652 0.025246918, 0.011227056 -0.039749876 0.025243104, 0.010913208 -0.039485782 0.025242954, 0.010558277 -0.039280131 0.025243059, 0.010172844 -0.03913933 0.02524294, -0.010657102 0.042334855 0.025247604, -0.011068821 0.042663872 0.025247529, -0.011543393 0.042893276 0.025247559, -0.012057126 0.043011144 0.025247857, -0.01258412 0.043011829 0.025247648, -0.013098061 0.042895272 0.025247633, -0.01357317 0.042667061 0.025247619, -0.013985664 0.042338952 0.025247738, -0.0045131892 -0.013684168 0.025390804, -0.0045132488 -0.013684109 0.026890785, -0.0042097121 -0.013922647 0.025390789, -0.004209891 -0.013922408 0.026890814, -0.0038581789 -0.014081195 0.025390789, -0.0038583875 -0.014081135 0.026890904, -0.0034790188 -0.014151201 0.025390849, -0.0034790188 -0.014151245 0.026890844, -0.0030938983 -0.014128417 0.025390819, -0.0030940622 -0.014128372 0.026890814, -0.0027256459 -0.01401417 0.025390849, -0.0027257055 -0.014014155 0.026890904, -0.0023952127 -0.01381503 0.025390789, -0.0023952276 -0.013815045 0.026890844, -0.0021221787 -0.013542578 0.025390759, -0.0021222234 -0.013542622 0.026890829, -0.0019221753 -0.013212755 0.025390774, -0.0019222796 -0.013212815 0.026890874, -0.0018068999 -0.012844592 0.025390759, -0.0018069595 -0.012844712 0.026890755, -0.0017831326 -0.012459651 0.025390863, -0.0017832369 -0.012459636 0.026890859, -0.0018523186 -0.012080088 0.025390953, -0.0018523484 -0.012080193 0.026890829, -0.0020100772 -0.011728257 0.025390953, -0.0020102262 -0.011728227 0.026890844, -0.0022475719 -0.011424273 0.025390789, -0.0022475719 -0.011424378 0.026890963, -0.010313764 0.0080724955 0.026891842, -0.010010555 0.0078343004 0.026892081, -0.010313705 0.0080724955 0.0253921, -0.010010332 0.0078342706 0.025392026, -0.0096587241 0.0076755136 0.026891932, -0.009658888 0.0076755136 0.025391966, -0.0092795044 0.0076054484 0.026892141, -0.0092795193 0.007605508 0.025392026, -0.0088945478 0.0076283067 0.026892051, -0.0088946074 0.0076283962 0.025392085, -0.0085262358 0.0077426285 0.026892096, -0.0085261911 0.0077426434 0.02539213, -0.0081957132 0.0079414994 0.026892081, -0.0081957579 0.0079416484 0.025391966, -0.0079227686 0.0082141012 0.026892215, -0.0079226196 0.0082141757 0.025391966, -0.007722646 0.0085439235 0.026891887, -0.0077227652 0.0085439384 0.025391996, -0.0076075047 0.0089120865 0.026892111, -0.0076076239 0.0089121014 0.02539213, -0.0075837076 0.0092969388 0.026892096, -0.0075837076 0.0092970431 0.02539219, -0.0076527745 0.0096765459 0.026892051, -0.0076527596 0.0096765906 0.025392145, -0.0078106672 0.010028511 0.026892081, -0.0078106076 0.010028541 0.025392264, -0.008048147 0.010332599 0.026892096, -0.008048147 0.01033248 0.025392205, 0.011428356 0.002217561 0.026891708, 0.011731789 0.001979202 0.026891887, 0.01142849 0.0022175014 0.025391653, 0.011731699 0.001979351 0.025391653, 0.012083381 0.0018204004 0.026891619, 0.012083322 0.0018203706 0.025391683, 0.012462541 0.0017504543 0.026891649, 0.012462437 0.0017504841 0.025391713, 0.012847677 0.0017732531 0.026891768, 0.012847617 0.0017732233 0.025391743, 0.013216019 0.0018875003 0.026891664, 0.013216108 0.0018875599 0.025391728, 0.013546243 0.0020868331 0.026891634, 0.013546392 0.0020867735 0.025391743, 0.013819337 0.0023591518 0.026891679, 0.013819441 0.0023591965 0.025391921, 0.014019489 0.0026889294 0.026891813, 0.01401934 0.0026888698 0.025391802, 0.014134645 0.0030571371 0.026891649, 0.014134616 0.0030571371 0.025391683, 0.014158368 0.0034420043 0.026891932, 0.014158398 0.0034421533 0.025391892, 0.014089391 0.0038215518 0.026891798, 0.014089242 0.0038215965 0.025391787, 0.013931423 0.0041735023 0.026891679, 0.013931453 0.0041734874 0.025391892, 0.013693988 0.0044773221 0.026891828, 0.013693959 0.0044774711 0.025391862, -0.0070570409 0.011321187 0.026892364, -0.0066116601 0.010751322 0.026892066, -0.0063156635 0.010091379 0.02689226, -0.0061862171 0.009379968 0.026892096, -0.0062308311 0.0086580664 0.026892036, -0.0064466745 0.0079677552 0.026892066, -0.0068217218 0.0073491931 0.026891962, -0.0073337406 0.0068384558 0.026892051, -0.0079531819 0.0064651519 0.026891947, -0.008643955 0.0062508136 0.026891857, -0.0093659908 0.0062081218 0.026892036, -0.010077074 0.0063393563 0.026891887, -0.010736212 0.0066370368 0.026892066, -0.011304989 0.007083863 0.026891857, -0.0012564659 -0.010435626 0.026890919, -0.00083823502 -0.010961697 0.028591141, -0.00081121922 -0.011005431 0.026891053, -0.00054767728 -0.011567265 0.028590947, -0.00051517785 -0.011665329 0.026890934, -0.00039891899 -0.012222439 0.028590947, -0.00038570166 -0.012376741 0.026890978, -0.00039973855 -0.012894124 0.028590932, -0.00043018162 -0.013098702 0.02689077, -0.00055000186 -0.013548821 0.028590977, -0.00064636767 -0.013788953 0.02689077, -0.00084222853 -0.014153838 0.028590769, -0.0012617409 -0.014678448 0.030310228, -0.0012617558 -0.014678285 0.028590843, -0.0017376989 -0.015064791 0.030430183, -0.001021266 -0.014407337 0.026890844, -0.0015332699 -0.014918208 0.026890665, -0.0021526366 -0.015291601 0.02689074, -0.0022843033 -0.015347198 0.03053087, -0.0028432608 -0.015505746 0.026890665, -0.0029528737 -0.015523776 0.030614406, -0.0035652518 -0.015548706 0.026890829, -0.0036459714 -0.015542716 0.03066279, -0.0042765588 -0.015417293 0.02689068, -0.0043263584 -0.015401348 0.030672938, -0.0049573332 -0.015106604 0.030643165, -0.0049357563 -0.015119746 0.026890621, -0.0055043548 -0.014672995 0.030576363, -0.0055044144 -0.014672816 0.026890874, 0.014685154 0.0054658055 0.030577362, 0.014685005 0.0054660887 0.026891813, 0.015070304 0.0049917847 0.030638129, 0.015130401 0.0048962086 0.026891842, 0.015350118 0.004452467 0.030669957, 0.015426487 0.0042363554 0.026891783, 0.01553005 0.0037780702 0.030669957, 0.015555874 0.0035248697 0.026891723, 0.015549257 0.0030799955 0.030630812, 0.015511513 0.0028029531 0.026891813, 0.015406787 0.0023974627 0.030554727, 0.015295401 0.002112776 0.026891664, 0.015110224 0.0017654449 0.030445442, 0.014679834 0.0012234151 0.028591648, 0.014679834 0.0012232363 0.030311093, 0.014920428 0.0014942735 0.026891604, 0.01440835 0.00098362565 0.026891693, 0.014154062 0.00080512464 0.028591782, 0.013789028 0.00061014295 0.026891604, 0.013548493 0.00051441789 0.028591573, 0.01309827 0.00039598346 0.026891604, 0.012893274 0.0003656745 0.028591692, 0.012376428 0.00035317242 0.026891649, 0.0122215 0.00036665797 0.028591722, 0.011665091 0.00048431754 0.026891619, 0.011566684 0.00051684678 0.028591469, 0.011005938 0.00078204274 0.026891783, 0.01096192 0.00080902874 0.028591752, 0.010437235 0.0012289435 0.026891753, 0.010437131 0.0012286454 0.028591827, -0.046193182 0.036282375 0.020896241, -0.043123737 0.039881617 0.020896539, -0.0434497 0.036892474 0.018913269, -0.0489631 0.032447591 0.020896062, -0.046347931 0.033178434 0.018913046, -0.048929617 0.029237762 0.018912882, -0.05141519 0.028402373 0.020895794, -0.05117704 0.025097221 0.018912539, 0.038113877 0.044693455 0.020896614, 0.040355369 0.040253684 0.018913299, 0.036893368 0.043448627 0.018913478, 0.041586712 0.041481629 0.020896465, -0.053533986 0.024173111 0.020895571, -0.053074881 0.02078554 0.018912286, 0.034393847 0.047615513 0.020896852, 0.033179477 0.046346962 0.018913686, -0.055305675 0.019787058 0.020895243, -0.054609984 0.016331598 0.018912047, 0.030450881 0.050228626 0.020896822, 0.029238671 0.048928529 0.018913895, -0.056718618 0.015272841 0.020895168, -0.055772305 0.011766151 0.018911794, -0.05776377 0.010659248 0.020894736, 0.026310414 0.052516028 0.02089709, 0.025098234 0.051176012 0.018913984, -0.056553468 0.0071202964 0.018911466, -0.058434188 0.0059765577 0.020894408, -0.056948259 0.0024258941 0.018911123, 0.021999061 0.05446291 0.020897061, 0.020786405 0.053073794 0.018914074, -0.058725715 0.001255244 0.0208942, -0.056954205 -0.0022850782 0.018910915, 0.017545313 0.056056365 0.020897388, -0.058636397 -0.0034742653 0.020894006, 0.016332567 0.054609105 0.018914014, -0.05657123 -0.0069807619 0.018910766, -0.058166891 -0.0081811547 0.020893559, 0.0129776 0.057286397 0.020897478, 0.011767089 0.055771247 0.018914282, -0.055801362 -0.011628434 0.018910497, -0.057319909 -0.012835279 0.020893455, 0.0083258152 0.058144823 0.020897448, 0.0071212053 0.056552395 0.018914342, -0.054650828 -0.016196683 0.018910185, -0.056101367 -0.017406046 0.020893231, 0.0036199093 0.05862622 0.020897418, 0.0024267435 0.056947321 0.018914312, -0.053126737 -0.0206545 0.018909976, -0.054518938 -0.021863773 0.020892829, -0.0011093318 0.058727354 0.020897359, -0.051239535 -0.024971128 0.018909588, -0.0022844076 0.056953296 0.018914312, -0.052582964 -0.026180014 0.02089262, -0.0058314502 0.058447704 0.020897448, -0.049002573 -0.029117152 0.018909439, -0.0069797039 0.056570157 0.018914402, -0.050305948 -0.030326173 0.02089256, -0.01051563 0.057789013 0.020897299, -0.011627585 0.055800542 0.018914282, -0.046430841 -0.033064246 0.018909231, -0.047702685 -0.034275725 0.020892188, -0.043541893 -0.036785558 0.018909007, -0.015131742 0.056755394 0.020897254, -0.016195893 0.05464974 0.018914312, -0.04479003 -0.038003117 0.020892039, -0.040355533 -0.040255576 0.018908888, -0.019649774 0.055353731 0.020897344, -0.02065365 0.053125635 0.018914044, -0.041587025 -0.041484013 0.020891801, -0.024040237 0.053593189 0.020897314, -0.024970159 0.051238641 0.018913969, -0.028274775 0.051484823 0.020896971, -0.029116139 0.049001545 0.018913895, -0.032326147 0.049042866 0.020896941, -0.033063263 0.046429977 0.018913537, -0.036167756 0.04628256 0.020896703, -0.036784708 0.043540865 0.018913567, -0.039774746 0.043222189 0.020896569, -0.040254638 0.04035446 0.018913418, -0.01048401 0.015712559 0.03184177, -0.0090324581 0.016589388 0.031841815, -0.0091454685 0.016796872 0.031872377, -0.016798571 -0.0091472119 0.031870753, -0.017929137 -0.0066634119 0.031870857, -0.018152371 -0.0067462921 0.031873226, -0.010614857 0.015908927 0.031872183, -0.016591236 -0.0090342015 0.031840116, -0.016263485 -0.0091493726 0.031781808, -0.017352909 -0.0068617463 0.031782016, -0.011301681 0.01513496 0.031841516, -0.012363121 0.013974547 0.031783149, -0.010355636 0.015520439 0.031783208, -0.011443093 0.01532425 0.031872183, -0.017707571 -0.0065810829 0.031840384, -0.012672558 0.014324307 0.031872079, -0.011585549 0.015515327 0.031874627, -0.013676032 0.013708457 0.031874642, -0.015326202 -0.011444673 0.031870767, -0.015516967 -0.011587173 0.031873226, -0.013710231 -0.013677627 0.031872928, -0.017007738 -0.0092610866 0.031873286, -0.013541564 -0.013509408 0.031870514, -0.013507679 0.013539821 0.031872064, -0.015136838 -0.011303395 0.03184028, -0.013374344 -0.01334253 0.031840026, -0.014874384 -0.011268139 0.031781659, -0.012516141 0.014147475 0.031841531, -0.013340831 0.013372526 0.031841561, -0.014142424 0.012170747 0.03178297, -0.014496773 0.012475491 0.031872004, 0.011279732 0.014862627 0.031783044, 0.013210744 0.013176069 0.031783223, 0.013374239 0.013339162 0.031841561, -0.015487939 0.011622638 0.031874344, -0.015297338 0.011479661 0.031872079, -0.013210848 -0.013179377 0.031781718, 0.011562228 0.015234575 0.031872123, 0.013710201 0.013674051 0.031874463, 0.011624277 0.015486136 0.031874716, -0.014317498 0.012321234 0.031841516, 0.01354146 0.013505906 0.031872034, -0.01605323 0.010396525 0.031871989, -0.016984507 0.0093001574 0.03187418, 0.011419415 0.015046418 0.03184168, -0.015108421 0.011337742 0.031841502, 0.0093646944 0.016675577 0.031872347, 0.0093018413 0.016982853 0.031874642, -0.015661195 0.01014252 0.031782895, -0.015855029 0.010268062 0.031841516, 0.0092489719 0.016469508 0.031841815, 0.0091360807 0.016268224 0.031783238, 0.0069904625 0.017801702 0.031872347, 0.0067899823 0.018133774 0.031874627, -0.016775683 0.0091857314 0.031871989, -0.017313987 0.0081257224 0.031871855, -0.018135414 0.0067882836 0.031874195, 0.0069041848 0.017581791 0.03184174, 0.006819725 0.017366901 0.031783417, -0.016568497 0.0090722591 0.031841293, -0.016891062 0.0079271793 0.03178297, -0.017100155 0.0080254227 0.031841248, 0.004484266 0.018591747 0.031872422, 0.0041399896 0.01891543 0.031874716, 0.0044286549 0.018362418 0.0318418, -0.017912418 0.0067049414 0.031871751, 0.0043746531 0.018137798 0.031783506, -0.018255517 0.0057052672 0.031871736, -0.018917203 0.0041382164 0.031873927, 0.0018932819 0.019031033 0.031872451, 0.0014055073 0.019312024 0.03187491, -0.017691061 0.006621927 0.031841323, 0.0018699765 0.018795997 0.03184177, 0.0018471181 0.018566117 0.031783462, -0.01780957 0.0055658072 0.031782612, -0.018030062 0.0056347847 0.031841308, -0.00073334575 0.019110978 0.031872392, -0.0013573468 0.019315362 0.031874791, -0.018684417 0.0040872693 0.031871691, -0.00072416663 0.018874899 0.03184177, -0.00071540475 0.018644184 0.031783581, -0.018860385 0.0031795502 0.031871498, -0.019313827 0.0014039427 0.031873688, -0.018453851 0.0040369034 0.031840965, -0.0033459365 0.018830091 0.031872123, -0.0040926635 0.01892589 0.031874835, -0.018399656 0.0031018406 0.031782463, -0.018627331 0.0031402111 0.031841055, -0.0040422678 0.018692836 0.031872377, -0.0033046901 0.018597469 0.031841725, -0.0032642484 0.018370166 0.031783164, -0.019076407 0.0013866425 0.031871349, -0.019117579 0.00059518218 0.031871453, -0.01931724 -0.0013590008 0.031873614, -0.0039923191 0.018462032 0.03184177, -0.0057516992 0.017749324 0.031783417, -0.018840611 0.0013694167 0.031841025, -0.018650576 0.00058048964 0.031782478, -0.0058956444 0.018193603 0.031872615, -0.0067447126 0.018150657 0.031874657, -0.018881321 0.00058764219 0.031840786, -0.0066616833 0.017927468 0.031872392, -0.0058229268 0.017968968 0.031841978, -0.0190797 -0.0013423562 0.031871259, -0.018844038 -0.0013258308 0.031840667, -0.0065794587 0.017705947 0.0318418, -0.0081304014 0.0167934 0.031783327, -0.0185574 -0.0019515306 0.03178221, -0.0083339214 0.017213777 0.031872153, -0.0092594475 0.01700601 0.031874672, -0.018694669 -0.0040440857 0.031871125, -0.018927589 -0.0040943623 0.031873658, -0.018463805 -0.0039941519 0.031840652, -0.018122286 -0.0044475198 0.031782091, -0.0082309842 0.017001107 0.031841666, -0.044863954 -0.014032438 0.02733779, -0.044863909 -0.014032438 0.02639088, -0.045326337 -0.013476089 0.02726607, -0.045421422 -0.013331428 0.026390851, -0.045678303 -0.012852073 0.027223945, -0.045809165 -0.012523815 0.026390865, -0.045966178 -0.011929601 0.027214214, -0.046007395 -0.011650264 0.026390955, -0.046024427 -0.01096347 0.027259961, -0.046006262 -0.010754481 0.02639088, -0.04584913 -0.010012433 0.027357668, -0.045805871 -0.0098815858 0.026391074, -0.045416266 -0.0090751499 0.026391193, -0.045451969 -0.009133175 0.027501181, -0.044856891 -0.0083754361 0.026391208, -0.044856951 -0.0083755702 0.02768144, 0.011627406 0.037297919 0.02885966, 0.011748493 0.03696537 0.026393846, 0.01162973 0.037293047 0.026393607, 0.011748582 0.036964923 0.02887933, 0.011453986 0.037597433 0.02884303, 0.011455774 0.037595153 0.026393935, 0.011232048 0.037862405 0.02882947, 0.011231959 0.037862584 0.026393592, 0.0054521561 0.025400132 0.031423166, 0.0043231547 0.025616497 0.031423181, 0.0037809014 0.022403032 0.031675726, 0.0057461262 0.021981031 0.031675801, 0.0047681332 0.022213772 0.031675741, 0.0062322617 0.029035613 0.031063631, 0.0049420595 0.029282913 0.031063795, 0.0065704584 0.025134146 0.031423211, 0.0069269836 0.032271788 0.030679092, 0.0077069998 0.035713866 0.030201599, 0.0062394738 0.034247607 0.030443534, 0.0067130029 0.021705329 0.031675696, 0.0075107515 0.028731495 0.031063691, 0.0076758564 0.024819016 0.031423226, 0.0083477199 0.031933799 0.030679151, 0.0076664388 0.021387175 0.031675741, 0.0087743998 0.028371021 0.031063572, 0.0092350543 0.035328135 0.030204445, 0.010717213 0.036834449 0.029927135, 0.010636777 0.037034959 0.029900357, 0.010510057 0.037210718 0.029879108, 0.010394484 0.037315205 0.029868364, 0.010255873 0.037401378 0.029861167, 0.010103613 0.037460625 0.029858366, 0.0099511445 0.037490189 0.029860213, 0.0098035932 0.037493631 0.029865474, 0.0096575618 0.037472337 0.02987437, 0.0095166564 0.037426978 0.029886812, 0.0093860924 0.037359372 0.029902101, 0.0093045831 0.03730154 0.029913917, 0.009229809 0.037234887 0.029926926, 0.0087663233 0.024455041 0.031423256, 0.0097522736 0.031533316 0.030678988, 0.011485875 0.033942476 0.030302078, 0.0086050332 0.021026999 0.031675652, 0.010020733 0.027955204 0.031063631, 0.0098393857 0.024043381 0.031423122, 0.011137664 0.031071067 0.030679017, 0.012248814 0.031071618 0.030629367, 0.0095269084 0.020625815 0.031675696, 0.011247605 0.027484685 0.031063661, 0.013005257 0.028224781 0.030910611, 0.010893315 0.02358453 0.031423062, 0.010429978 0.020184264 0.031675771, 0.012452304 0.026960298 0.031063408, 0.013764471 0.025365174 0.031151205, 0.011926025 0.023079768 0.031423226, 0.011312664 0.019703194 0.031675711, 0.01293543 0.022529587 0.031423122, 0.014380068 0.023047015 0.031316623, 0.012173206 0.019183487 0.031675488, 0.013919353 0.021935284 0.031423077, 0.014980525 0.020783901 0.031453565, 0.013009846 0.018626317 0.031675443, 0.013821095 0.01803261 0.031675547, 0.015594035 0.018472508 0.031569898, 0.014605314 0.017403483 0.031675443, 0.015360922 0.016740367 0.031675488, 0.01454246 0.014504462 0.031811923, -0.021388873 0.006662026 0.031696454, -0.023268148 0.004791379 0.031600863, 0.01537469 0.015334681 0.031741425, 0.016206622 0.016164258 0.031663582, -0.019550562 0.0084918588 0.031765923, -0.017690673 0.010344014 0.031814277, -0.01667197 0.011358947 0.031831905, -0.015652433 0.012375012 0.031843901, -0.014633223 0.013391152 0.031850055, -0.013614669 0.014407188 0.031850904, -0.012596533 0.015423119 0.031846002, -0.011579573 0.016438663 0.031835794, -0.010562092 0.017454475 0.031819791, -0.0095431358 0.018472254 0.031797484, -0.0078422427 0.020172164 0.031746343, -0.0061391294 0.021874651 0.031675756, -0.0044380426 0.023575574 0.031584337, -0.016780555 -0.015320823 0.031673595, -0.015374839 -0.015338063 0.03173992, -0.014542714 -0.014508083 0.031810105, -0.016206622 -0.01616776 0.031661928, -0.017887726 -0.015717268 0.031595826, -0.01744169 -0.014563501 0.031673715, -0.01961422 -0.015254349 0.031515598, -0.018068761 -0.013777763 0.03167367, -0.021364525 -0.01478526 0.031420961, -0.01866062 -0.012964949 0.031673789, -0.019215629 -0.012126952 0.031673819, -0.021971881 -0.013866127 0.031421065, -0.023061052 -0.014330402 0.031316087, -0.019733205 -0.011265144 0.031673789, -0.022563696 -0.012880683 0.031421214, -0.024815455 -0.013859719 0.031193197, -0.020211875 -0.010381252 0.031673968, -0.023111314 -0.011869803 0.031421021, -0.02650477 -0.013406903 0.031060934, -0.020651579 -0.0094769001 0.031674013, -0.023613632 -0.010836065 0.031421229, -0.021050394 -0.0085541755 0.031673983, -0.026993036 -0.01238662 0.031061307, -0.029953972 -0.012481406 0.030745834, -0.02824147 -0.012940779 0.03091003, -0.024069831 -0.0097810626 0.031421378, -0.021407962 -0.0076147616 0.031674057, -0.027514473 -0.011180356 0.031061366, -0.024478883 -0.0087067634 0.031421453, -0.021723777 -0.0066601783 0.031674027, -0.027982011 -0.0099524707 0.03106156, -0.024839863 -0.0076154768 0.031421363, -0.031100526 -0.011061549 0.030676737, -0.03340739 -0.01155445 0.030367568, -0.021997064 -0.0056927502 0.031674281, -0.028394818 -0.0087050498 0.031061456, -0.025152341 -0.0065092146 0.031421587, -0.031559438 -0.0096749514 0.030676723, -0.03686288 -0.010626584 0.029924318, -0.022227377 -0.004714489 0.031674325, -0.028752014 -0.007440567 0.03106162, -0.02541551 -0.0053903013 0.031421542, -0.031956375 -0.0082695037 0.030676886, -0.022413999 -0.0037264526 0.0316744, -0.029052943 -0.0061615109 0.031061649, -0.03535296 -0.0091484636 0.030201837, -0.035717249 -0.0076021105 0.030201957, -0.037259609 -0.0091381669 0.029924408, -0.037393153 -0.0093080848 0.029897586, -0.037481904 -0.0095058382 0.02987659, -0.037514627 -0.009658277 0.029865816, -0.037519917 -0.0098211616 0.029858291, -0.037495345 -0.0099829435 0.029855624, -0.037444636 -0.010129631 0.029857323, -0.037373811 -0.010258973 0.029862836, -0.037282288 -0.010374904 0.029871762, -0.03717263 -0.01047419 0.029884249, -0.037048712 -0.010553524 0.029899374, -0.03695789 -0.010595351 0.02991119, -0.025629088 -0.0042607784 0.031421706, -0.032290861 -0.0068478882 0.030676886, -0.03422837 -0.0061189681 0.030447081, -0.022556767 -0.0027314872 0.031674355, -0.02929695 -0.0048701912 0.031061888, -0.025792405 -0.0031228811 0.031421766, -0.032562032 -0.0054129064 0.030676946, -0.032688841 -0.0045857877 0.03067711, -0.022655576 -0.0017309785 0.031674355, -0.029483557 -0.0035696775 0.031061873, -0.031193078 -0.003096655 0.030877814, -0.025905073 -0.0019789785 0.031421781, -0.029657423 -0.0015675426 0.031061918, -0.022709727 -0.00072722137 0.03167443, -0.025967285 -0.00083117187 0.031421736, -0.028155237 -7.2285533e-05 0.031220868, -0.022719532 0.00027801096 0.031674474, -0.025978491 0.0003181994 0.031422108, -0.026624173 0.0014517009 0.031361505, -0.022684902 0.0012827516 0.031674623, -0.025939003 0.0014669895 0.031422138, -0.02511847 0.0029504299 0.031480521, -0.022606 0.0022849739 0.031674609, -0.022482738 0.0032827109 0.031674787, -0.022315457 0.0042739213 0.031674609, -0.00421983 0.022324309 0.031675771, -0.0032280385 0.022489026 0.031675696, -0.0027374327 0.025275752 0.031470284, -0.0022301078 0.022610009 0.031675756, -0.0012276471 0.022686332 0.031675756, -0.0014038682 0.025940895 0.031423569, -0.0012593567 0.026753351 0.031352013, -0.00022289157 0.022718579 0.031675756, -0.00025486946 0.025977463 0.031423226, 0.00025376678 0.028265879 0.031211093, 0.00078228116 0.022706136 0.031675711, 0.00089451671 0.025963217 0.031423435, 0.0017295778 0.029741257 0.031053528, 0.0017859936 0.022649303 0.031675711, 0.0020421445 0.025898293 0.03142333, 0.003247261 0.031257689 0.030870378, 0.0027860105 0.022548273 0.031675845, 0.0031857789 0.025782749 0.031423375, 0.0036417246 0.029472664 0.031063676, 0.0047187507 0.032728299 0.030671552, -0.010553449 0.042438105 0.028197587, -0.010918319 0.042740285 0.028100535, -0.010553479 0.042438284 0.025600955, -0.010990798 0.04278788 0.025600925, -0.011336327 0.042969525 0.028016478, -0.011494756 0.043031305 0.025601, -0.011790633 0.043115139 0.027949408, -0.012040496 0.043156728 0.025601223, -0.012264967 0.043171898 0.027901977, -0.012600422 0.043157414 0.025601134, -0.012743771 0.043137044 0.027875438, -0.013146281 0.043033451 0.025601149, -0.01320526 0.043011904 0.027872205, -0.013650835 0.042791247 0.025601029, -0.013635814 0.04280065 0.027891278, -0.013871878 0.042635426 0.02791363, -0.014089078 0.042442605 0.025600851, -0.014089078 0.04244259 0.027943715, 0.032852113 0.03074947 0.025600404, 0.032852128 0.03074947 0.027870268, 0.03238602 0.031117067 0.025600523, 0.032048777 0.031289339 0.027924746, 0.03184627 0.031364068 0.025600374, 0.031585857 0.031432644 0.027984753, 0.031263575 0.031477362 0.025600463, 0.031106129 0.031483829 0.028062418, 0.030670643 0.031449601 0.025600344, 0.030627072 0.031442225 0.028155908, 0.030100673 0.031283408 0.025600418, 0.03016825 0.031310663 0.028260171, 0.029586494 0.030987188 0.025600269, 0.029751375 0.03110005 0.02836962, 0.029156253 0.030578017 0.02560018, 0.029030517 0.030412242 0.028610647, 0.028834626 0.030079111 0.025600433, 0.028798088 0.029999912 0.028718889, 0.028639868 0.029518396 0.025600329, 0.028646201 0.029546022 0.028819427, 0.028583512 0.029068902 0.028907567, 0.028582677 0.028927565 0.025600165, 0.028598115 0.028701097 0.028964356, 0.028666452 0.028339952 0.025600225, 0.028666407 0.028339654 0.029010803, 0.011330843 -0.039646566 0.025596291, 0.011330813 -0.039646715 0.028797492, 0.010997355 -0.039366037 0.025596425, 0.010992005 -0.039362341 0.02888155, 0.010620281 -0.03914766 0.025596425, 0.010616973 -0.039146274 0.028951421, 0.010210976 -0.038998097 0.025596589, 0.010211065 -0.038998157 0.029007062, -0.049020886 0.032485962 0.020913839, -0.051531643 0.028466731 0.020947292, -0.049073875 0.032521099 0.020947516, -0.051476225 0.028436124 0.020913646, -0.046391562 0.036438048 0.021122217, -0.049180508 0.032591745 0.021193564, -0.046398431 0.036443472 0.021193519, -0.04917331 0.032586992 0.021122113, -0.046371594 0.036422387 0.021054968, -0.049152091 0.032572985 0.021054834, -0.046339869 0.036397412 0.020996004, -0.049118355 0.032550663 0.020995528, -0.046297699 0.036364317 0.020947769, -0.0462479 0.036325186 0.020914197, -0.043308869 0.040052816 0.0211225, -0.043315321 0.040058658 0.021193802, -0.04163608 -0.041533068 0.020909742, -0.043290466 0.040035754 0.021055132, -0.043260634 0.040008202 0.020996153, -0.043221354 0.039971888 0.020948023, -0.043174908 0.039928854 0.020914212, -0.039945573 0.043407813 0.021122709, -0.039951295 0.04341425 0.021194026, -0.039928585 0.043389305 0.021055356, -0.039900899 0.043359429 0.020996258, -0.039864779 0.043320104 0.020948127, -0.039821878 0.043273538 0.02091448, -0.036322996 0.046481401 0.021122828, -0.036328375 0.046488285 0.021194175, -0.036307514 0.046461523 0.021055445, -0.036282569 0.046429619 0.020996362, -0.036249489 0.046387523 0.020948499, -0.036210507 0.046337351 0.020914569, -0.032464966 0.049253732 0.021123186, -0.032469675 0.049260527 0.021194234, -0.032451019 0.049232513 0.021055683, -0.032428667 0.049198493 0.020996615, -0.032399297 0.049153849 0.02094835, -0.032364339 0.049100786 0.020914838, -0.028396279 0.05170618 0.021123245, -0.028400481 0.051713482 0.021194413, -0.028384179 0.051683843 0.021056041, -0.028364584 0.051648349 0.020996839, -0.02833879 0.05160144 0.020948589, -0.028308421 0.051545948 0.020915031, -0.024143532 0.053823397 0.021123275, -0.024147049 0.053831175 0.021194756, -0.024133101 0.053800315 0.021056101, -0.02411668 0.05376333 0.020996779, -0.024094626 0.053714588 0.020948634, -0.024068639 0.053656727 0.020914942, -0.019734159 0.055591598 0.021123394, -0.01973708 0.055599764 0.021194667, -0.019725636 0.055567771 0.021056086, -0.01971218 0.05552958 0.020997018, -0.019694328 0.055479005 0.020948917, -0.019673109 0.055419534 0.020915031, -0.01519686 0.056999385 0.021123484, -0.015199155 0.057007626 0.021194756, -0.015190244 0.056974873 0.021056056, -0.015179843 0.056935698 0.020997092, -0.015166044 0.056884021 0.020948946, -0.015149742 0.056822643 0.0209153, -0.01056093 0.058037236 0.021123528, -0.010562479 0.058045492 0.021194816, -0.01055634 0.058012322 0.021056175, -0.010549039 0.057972446 0.020997167, -0.010539532 0.057919785 0.02094911, -0.010528266 0.057857499 0.020915285, -0.0058565736 0.058698863 0.021123588, -0.005857408 0.058707237 0.021194845, -0.0058540702 0.05867368 0.021056205, -0.0058499277 0.058633238 0.020997047, -0.0058446527 0.058580235 0.020949006, -0.0058383644 0.058517218 0.020915359, -0.0011140704 0.05897966 0.021123528, -0.0011142492 0.058988243 0.021194816, 0.041765422 0.041659757 0.021122783, 0.038283229 0.044891939 0.021193981, 0.041771531 0.041665956 0.021194071, -0.0011135936 0.058954418 0.021056175, -0.0011128783 0.058913901 0.020997047, -0.0011119246 0.058860406 0.020949215, 0.04163599 0.041530907 0.020914346, -0.0011105835 0.058797061 0.020915478, -0.044982404 -0.038166314 0.021117985, -0.041771561 -0.041668251 0.021189243, -0.044988975 -0.038171858 0.021189243, -0.041765615 -0.041662142 0.021117985, 0.0036353767 0.058878079 0.021123797, 0.0036357641 0.058886841 0.021194726, -0.044963166 -0.038149983 0.021050736, -0.041747659 -0.04164426 0.021050557, 0.0036338866 0.058852896 0.021056324, -0.044932097 -0.038123667 0.020991579, -0.04171893 -0.04161568 0.020991445, 0.0036313832 0.058812499 0.020997196, -0.044891387 -0.038088888 0.020943522, -0.041680977 -0.041577831 0.020943537, -0.044843152 -0.038048133 0.020909965, 0.0036281943 0.058759078 0.020949006, 0.0036242306 0.058695897 0.020915359, -0.047907546 -0.034423068 0.021118239, -0.047914535 -0.034427896 0.0211896, 0.0083615184 0.058394581 0.021123558, 0.0083627105 0.058403239 0.021194845, -0.047887072 -0.034408271 0.021050945, 0.0083579123 0.058369681 0.021056205, -0.047854096 -0.034384504 0.020991921, 0.0083522499 0.058329538 0.020997107, -0.047810644 -0.034353346 0.02094388, 0.0083445907 0.058276638 0.020949095, -0.047759086 -0.034316361 0.020910159, 0.0083355904 0.058213815 0.02091524, -0.050522 -0.030456379 0.021118581, -0.050529346 -0.030460879 0.021190003, 0.013033122 0.0575324 0.021123469, 0.013035297 0.057540774 0.021194875, -0.050500408 -0.030443415 0.021051392, 0.013027757 0.057507694 0.021056145, -0.050465554 -0.03042233 0.02099216, 0.013018787 0.057468206 0.020997077, -0.050419793 -0.030394867 0.020944163, 0.013006896 0.057416111 0.020949155, -0.050365493 -0.03036207 0.020910293, 0.012992889 0.057354167 0.0209153, -0.052808776 -0.026292399 0.021118835, -0.05281657 -0.026296169 0.021190181, 0.017620564 0.056297287 0.021123409, 0.017623156 0.056305468 0.021194756, -0.052786201 -0.026281133 0.021051556, 0.017613024 0.056272849 0.021056205, -0.052749649 -0.026262969 0.020992398, 0.017600834 0.0562343 0.020996988, -0.052701935 -0.026239172 0.020944327, -0.052645281 -0.026210979 0.020910695, 0.01758486 0.056183174 0.020949006, 0.017566025 0.05612269 0.0209153, -0.05475308 -0.021957725 0.021119013, -0.054761201 -0.021961033 0.021190375, 0.022093445 0.054696769 0.02112326, 0.022096783 0.054704711 0.021194577, -0.054729685 -0.021948233 0.021051645, 0.022083998 0.05467324 0.021056026, -0.05469206 -0.021933213 0.020992562, -0.05464232 -0.021913394 0.020944551, 0.022068828 0.054635853 0.020996839, 0.02204892 0.054586127 0.020948768, -0.054583594 -0.021889746 0.020910934, 0.022025198 0.054527417 0.020915151, -0.056342304 -0.017480791 0.021119326, -0.056350574 -0.017483264 0.021190688, 0.026423216 0.052741513 0.02112326, 0.026427209 0.052749097 0.021194637, -0.056318253 -0.017473161 0.021051913, 0.026411891 0.052719027 0.021055847, -0.05627948 -0.0174613 0.020992801, -0.056228384 -0.01744543 0.020944774, 0.02639389 0.052682638 0.02099672, -0.05616802 -0.017426595 0.020911083, 0.02636978 0.052634895 0.020948797, -0.057566255 -0.012890384 0.02111952, 0.026341379 0.052578181 0.020915031, -0.0575746 -0.012892336 0.021190807, 0.030581772 0.050444365 0.021123052, 0.030586034 0.050451741 0.021194458, -0.05754146 -0.01288487 0.021052212, 0.03056851 0.050422877 0.021055669, -0.057501867 -0.012876034 0.020993143, 0.0305475 0.050388053 0.02099666, -0.057449669 -0.012864396 0.020945132, -0.057387799 -0.012850598 0.020911247, 0.030519694 0.050342321 0.020948529, -0.05841659 -0.0082165003 0.021119788, 0.030487001 0.050288215 0.020914823, -0.058425069 -0.008217752 0.021191165, 0.034541607 0.047819927 0.021122962, 0.034546748 0.047827035 0.021194249, -0.058391511 -0.0082129389 0.021052599, 0.03452678 0.047799468 0.021055698, -0.058351412 -0.0082072318 0.020993218, 0.034503043 0.047766522 0.020996541, -0.058298498 -0.0081997961 0.020945251, -0.05823575 -0.008190915 0.020911559, 0.03447175 0.047723383 0.02094838, 0.034434631 0.04767184 0.020914793, -0.058888122 -0.0034893006 0.021120146, -0.058896944 -0.0034897327 0.021191373, 0.038277656 0.044885412 0.021122754, -0.058862939 -0.0034876317 0.021052673, 0.04174754 0.041641936 0.021055251, 0.038261145 0.044866115 0.021055311, -0.058822557 -0.0034853667 0.020993695, 0.041718796 0.041613385 0.020996153, -0.058769107 -0.0034822971 0.020945564, 0.0382348 0.044835299 0.020996302, 0.041680902 0.041575596 0.020948201, -0.058705926 -0.0034784675 0.020911813, 0.03820011 0.044794634 0.020948321, -0.058978051 0.0012605786 0.021120459, -0.058986634 0.0012607723 0.021191716, 0.038158983 0.044746473 0.020914614, -0.058952674 0.0012599379 0.021052971, -0.058912084 0.0012592524 0.020993903, -0.058858663 0.001257956 0.020945847, -0.058795407 0.0012567341 0.020912096, -0.058685124 0.0060022026 0.021120533, -0.058693841 0.0060030669 0.021191761, -0.058660045 0.0059997141 0.021053329, -0.058619663 0.0059956163 0.020994082, -0.058566511 0.0059901029 0.020946234, -0.058503509 0.0059836805 0.020912305, -0.05801186 0.010704964 0.021120951, -0.058020338 0.010706455 0.021192208, -0.057987019 0.010700434 0.021053627, -0.057947204 0.010693148 0.020994425, -0.057894483 0.010683298 0.020946562, -0.057832226 0.010671735 0.020912588, -0.056962341 0.015338346 0.021121144, -0.056970492 0.015340522 0.021192327, -0.056937784 0.015331671 0.021053776, -0.056898624 0.01532121 0.020994693, -0.056846976 0.015307248 0.020946696, -0.056785762 0.015290931 0.020912901, -0.05554314 0.019872218 0.021121383, -0.055551305 0.01987499 0.02119267, -0.055519491 0.01986362 0.021054178, -0.05548124 0.019849956 0.020994917, -0.055430889 0.019831866 0.020946905, -0.055371165 0.019810557 0.02091296, -0.053763881 0.024276927 0.0211218, -0.053771749 0.024280608 0.021193042, -0.053740904 0.024266616 0.021054268, -0.053703979 0.024249911 0.020995036, -0.053655207 0.024227858 0.020947143, -0.053597495 0.024201751 0.020913363, -0.051636145 0.028524593 0.021121845, -0.05164367 0.028528586 0.021193236, -0.051613867 0.028512388 0.021054476, -0.051578552 0.028492495 0.020995408, -0.058869466 -0.0034881234 0.021878749, -0.058959156 0.0012601763 0.021879166, -0.058979616 0.0012606233 0.021817937, -0.058836401 -0.0034861267 0.021934107, -0.058926225 0.0012592822 0.021934405, -0.058881894 0.001258418 0.021981448, -0.058792382 -0.003483519 0.02198115, -0.058418214 -0.0082166344 0.021817192, -0.058896914 -0.0034897029 0.021753415, -0.05842495 -0.0082177222 0.021753296, -0.058889836 -0.0034894347 0.02181761, -0.058398023 -0.0082138181 0.021878496, -0.058365196 -0.0082092434 0.021933869, -0.058321521 -0.0082031786 0.021980703, 0.03821519 0.044812173 0.021983832, 0.041697368 0.041591913 0.021983802, 0.041728616 0.04162325 0.021936715, -0.05756776 -0.012890831 0.021816969, -0.057574451 -0.012892365 0.021752849, -0.057547882 -0.012886301 0.021878287, -0.057515487 -0.012879089 0.021933675, -0.057472423 -0.012869477 0.021980584, -0.056344002 -0.017481223 0.02181676, -0.056350589 -0.017483264 0.021752566, -0.056324452 -0.017475143 0.02187784, -0.056292742 -0.017465338 0.021933258, -0.056250647 -0.0174523 0.02198045, -0.054754496 -0.021958411 0.021816522, -0.054761052 -0.021960884 0.021752506, -0.054735735 -0.021950856 0.021877766, -0.054704949 -0.021938518 0.021933123, -0.054663956 -0.021921948 0.021980122, -0.052810162 -0.026293054 0.021816403, -0.052816465 -0.026296169 0.021752372, -0.052791998 -0.026284099 0.021877587, -0.05276233 -0.026269242 0.02193296, -0.052722812 -0.026249588 0.021979943, -0.050523534 -0.030457318 0.021816149, -0.050529331 -0.030461058 0.021752089, -0.050505847 -0.030446798 0.021877155, -0.050477743 -0.030429676 0.021932647, -0.050439671 -0.030406877 0.02197957, -0.047908962 -0.034423977 0.021815926, -0.047914609 -0.03442803 0.021751717, -0.047892272 -0.034411982 0.021876901, -0.047865376 -0.034392595 0.021932438, -0.047829479 -0.034367144 0.021979421, -0.044983611 -0.038167238 0.021815643, -0.044989049 -0.038171902 0.021751493, -0.041771561 -0.0416684 0.021751121, -0.041766644 -0.041663319 0.021815494, -0.044968128 -0.03815417 0.021876693, -0.041752145 -0.04164879 0.021876559, -0.044942722 -0.038132802 0.02193208, -0.041728735 -0.041625619 0.021931991, -0.041697383 -0.041594312 0.021978915, -0.04490912 -0.038104236 0.021979183, 0.038278744 0.044886738 0.021820188, 0.041771472 0.041665927 0.021755934, 0.038283125 0.044892043 0.021756053, 0.041766658 0.041660979 0.021820039, 0.038265392 0.044871122 0.021881402, 0.041752055 0.04164654 0.021881342, 0.03824389 0.044845924 0.021936774, 0.034542531 0.047821268 0.021820426, 0.034546718 0.047826976 0.021756291, 0.034530491 0.047804818 0.021881789, 0.034511194 0.047777802 0.021936983, 0.034485266 0.047741964 0.021983951, 0.030582488 0.050445691 0.021820754, 0.030585974 0.050451756 0.0217565, 0.030571848 0.050428107 0.02188167, 0.030554742 0.050399825 0.021937132, 0.030531794 0.050362185 0.021984309, 0.02642408 0.052742928 0.021820754, 0.02642715 0.052749068 0.021756619, 0.026414722 0.052724749 0.021881998, 0.026400059 0.052695066 0.021937579, 0.026380241 0.052655548 0.021984249, 0.022094131 0.054698139 0.021821022, 0.022096872 0.05470477 0.021756738, 0.022086591 0.054679275 0.021882057, 0.022074074 0.054648593 0.02193749, 0.022057533 0.054607511 0.021984577, 0.01762104 0.056298822 0.021820992, 0.017623097 0.056305215 0.021756828, 0.01761502 0.056279123 0.021881998, 0.017605007 0.056247726 0.021937519, 0.017591864 0.056205466 0.021984577, 0.013033718 0.057534114 0.021821052, 0.013035148 0.057540819 0.021756887, 0.013029128 0.057513967 0.021882176, 0.013021737 0.057481855 0.021937639, 0.013012052 0.057438731 0.021984577, 0.0083616972 0.05839619 0.021821111, 0.0083627701 0.058403075 0.021756977, 0.0083588362 0.058376014 0.021882296, 0.0083541572 0.058343232 0.021937579, 0.0083479583 0.058299527 0.021984667, 0.0036354959 0.058879688 0.021821082, 0.0036360621 0.058886632 0.021756887, 0.0036343336 0.058859184 0.021882385, 0.0036322176 0.058826327 0.021937668, 0.0036296248 0.058781996 0.021984667, -0.0011142492 0.058981344 0.021821082, -0.0011141896 0.058988199 0.021757036, -0.0011137426 0.058961019 0.021882206, -0.0011131763 0.058927849 0.021937817, -0.0011122227 0.058883682 0.021984756, -0.0058566332 0.058700368 0.021821141, -0.0058574378 0.058707386 0.021757126, -0.005854696 0.058680072 0.021882147, -0.0058514476 0.058647156 0.021937639, -0.0058469176 0.058603153 0.021984637, -0.010561198 0.058038965 0.021821126, -0.01056236 0.058045506 0.021756887, -0.010557443 0.058018714 0.021882206, -0.010551631 0.057986215 0.021937728, -0.010543615 0.057942659 0.021984607, -0.015197128 0.057000816 0.021820962, -0.015199065 0.057007581 0.021756932, -0.015191883 0.056980908 0.021882057, -0.015183508 0.056949139 0.021937564, -0.015172005 0.056906298 0.021984488, -0.019734606 0.055593029 0.021821022, -0.01973702 0.055599734 0.021756843, -0.019727722 0.055573881 0.021882057, -0.01971662 0.055542529 0.021937653, -0.019701958 0.055501044 0.021984383, -0.024144217 0.053824648 0.021820724, -0.024146989 0.053831294 0.021756709, -0.024135903 0.053806141 0.021882117, -0.024122164 0.053775981 0.0219374, -0.024104208 0.053735629 0.021984205, -0.028397143 0.05170764 0.021820739, -0.028400481 0.051713601 0.021756545, -0.028387293 0.05168955 0.021881878, -0.028371349 0.051660657 0.021937266, -0.028350025 0.051621705 0.021984264, -0.032465979 0.04925476 0.021820471, -0.032469645 0.049260557 0.021756396, -0.032454595 0.049237698 0.021881774, -0.032436386 0.04921028 0.021937087, -0.032412082 0.049173266 0.021984175, -0.036324158 0.046482578 0.021820366, -0.03632839 0.046488285 0.021756187, -0.036311477 0.046466663 0.021881491, -0.036291093 0.046440482 0.021936938, -0.036263853 0.046405703 0.021983847, -0.039946601 0.043409094 0.021820307, -0.039951429 0.043414295 0.021755978, -0.039932787 0.043393984 0.021881312, -0.039910257 0.043369576 0.021936819, -0.039880604 0.0433373 0.021983773, -0.04331024 0.040053993 0.021820068, -0.043315262 0.040058792 0.021755815, -0.043295264 0.040040076 0.021881238, -0.043270916 0.04001756 0.021936595, -0.043238536 0.039987624 0.021983698, -0.046392918 0.036439106 0.02181989, -0.046398371 0.036443323 0.021755561, -0.046376824 0.036426619 0.021880999, -0.046350732 0.03640607 0.021936372, -0.046315908 0.036378726 0.021983474, -0.049174607 0.032587945 0.021819681, -0.049180388 0.032591701 0.021755636, -0.0491575 0.032576635 0.021880895, -0.049129993 0.032558352 0.021936163, -0.049093202 0.032534018 0.021983191, -0.051637486 0.028525203 0.021819323, -0.05164355 0.028528735 0.021755368, -0.051619485 0.028515249 0.021880478, -0.051590562 0.028499305 0.02193594, -0.051551864 0.028477952 0.021982983, -0.053765342 0.024277627 0.021819293, -0.053771779 0.024280548 0.021755025, -0.05374679 0.024269104 0.021880135, -0.053716585 0.024255723 0.021935806, -0.053676426 0.024237514 0.021982819, -0.055544809 0.019872695 0.02181901, -0.055551246 0.019874826 0.021754712, -0.055525497 0.019865558 0.021880046, -0.055494353 0.019854635 0.021935597, -0.055452749 0.019839704 0.021982431, -0.056963846 0.015338659 0.021818697, -0.056970567 0.015340403 0.021754563, -0.056944042 0.015333295 0.021879852, -0.056912154 0.015324667 0.021935374, -0.056869343 0.015313134 0.021982282, -0.058013499 0.010705218 0.021818355, -0.058020368 0.010706604 0.021754384, -0.057993338 0.010701433 0.021879509, -0.057960838 0.010695592 0.021934867, -0.057917401 0.010687396 0.02198194, -0.058687001 0.0060025454 0.021818161, -0.058693647 0.0060031712 0.021754086, -0.058666542 0.0060002804 0.021879315, -0.0586337 0.0059970617 0.021934673, -0.058589712 0.0059924722 0.021981776, -0.0589865 0.0012608469 0.021753877, -0.033063278 0.046430141 0.012894049, -0.036784649 0.043541282 0.012894183, -0.029116184 0.049001917 0.012894437, -0.040355563 -0.040255293 0.012889355, -0.024970174 0.051238954 0.012894511, -0.043541953 -0.036785141 0.012889534, -0.020653516 0.053125784 0.012894735, -0.046431109 -0.033063844 0.012889788, -0.016195789 0.054649904 0.01289475, -0.049002662 -0.029116794 0.012889922, -0.011627465 0.055800706 0.01289466, -0.051239654 -0.024970949 0.012890279, -0.0069796443 0.056570366 0.012894779, -0.053126663 -0.020654291 0.012890324, -0.0022842288 0.056953534 0.012894899, -0.054650828 -0.016196564 0.012890652, 0.0024267137 0.056947619 0.01289466, -0.055801481 -0.011628181 0.01289095, 0.0071211457 0.056552768 0.012894809, -0.056571037 -0.006980449 0.012891278, 0.011767149 0.055771634 0.012894869, -0.056954414 -0.0022849888 0.012891531, 0.016332477 0.054609239 0.012894541, -0.056948483 0.0024261028 0.012891844, 0.020786434 0.053074002 0.012894481, -0.056553468 0.0071205646 0.012892142, 0.025098294 0.051176146 0.012894511, -0.05577229 0.011766404 0.012892321, 0.029238701 0.048928931 0.012894422, -0.054610059 0.016331777 0.012892663, 0.033179447 0.046347156 0.012894154, -0.053074777 0.02078563 0.012892708, 0.036893457 0.043449029 0.012894094, -0.05117701 0.025097519 0.012893006, 0.040355369 0.040253818 0.012893975, -0.048929513 0.029238015 0.012893423, -0.046347931 0.033178777 0.012893647, -0.043449759 0.036892772 0.012893692, -0.040254608 0.040354818 0.01289393, -0.054989606 -0.011284083 0.024348214, -0.053307891 -0.01759167 0.024347618, -0.05592753 -0.004823789 0.024348453, -0.056109071 0.0017015189 0.024348736, -0.055532232 0.0082040578 0.024349347, -0.054203987 0.0145953 0.024349585, -0.052142888 0.020789176 0.024349898, -0.049376622 0.026702091 0.02435036, -0.045942768 0.032253683 0.024350524, -0.041887507 0.037369296 0.024350882, -0.037265837 0.041979536 0.02435118, -0.032140225 0.046021894 0.02435112, -0.026579946 0.049442083 0.024351627, -0.020660102 0.052193418 0.024351656, -0.014460981 0.054238915 0.024351716, -0.0080663264 0.055550978 0.024351791, -0.0015625358 0.056111768 0.024351835, 0.0049624741 0.055913776 0.024351776, 0.011420369 0.054959521 0.024351776, 0.01772362 0.053262234 0.024351805, 0.02378729 0.050844461 0.024351567, 0.029529214 0.047739074 0.024351507, 0.034871921 0.043988213 0.02435118, -0.040948793 -0.03635101 0.025530532, -0.04407683 -0.034763098 0.024346694, -0.043013141 -0.038183317 0.02316317, 0.036451891 0.040856212 0.025534958, 0.038289502 0.042916089 0.023167521, -0.047814384 -0.029411033 0.024346977, -0.050905272 -0.02366136 0.02434741, 0.020464927 0.039605439 0.028849691, 0.021069199 0.045617312 0.02767396, 0.018692851 0.040471926 0.028849557, 0.018042088 0.036201641 0.029589802, 0.020011097 0.03485471 0.029632807, 0.018997759 0.032607645 0.030022651, 0.02219668 0.03866151 0.028849393, 0.0215334 0.033935368 0.029632762, 0.019474238 0.030816242 0.030213192, 0.019950777 0.029024124 0.030387446, 0.025018573 0.043576717 0.02767393, -0.028270468 -0.027844146 0.029713854, -0.027988389 -0.027920231 0.029737592, -0.02595301 -0.025889799 0.030180544, 0.02388519 0.037641764 0.028849393, -0.023659527 -0.02133438 0.030816868, -0.023912787 -0.023854747 0.030578017, -0.021868393 -0.021815389 0.03092961, -0.029038176 -0.027730301 0.02963613, 0.023013562 0.032949656 0.029632628, 0.020433784 0.027207494 0.030547872, 0.021824628 0.028475657 0.030295461, 0.020905644 0.025432691 0.030689225, 0.02552703 0.036548436 0.028849363, 0.024448514 0.031899452 0.029632464, -0.032508656 -0.031434074 0.028722689, -0.033953384 -0.033869833 0.02816762, -0.032326266 -0.032246768 0.028636262, 0.028772026 0.041195095 0.027673781, 0.023062944 0.02748242 0.030295402, 0.02139017 0.023610637 0.03081882, 0.027118683 0.035383552 0.028849304, 0.025835574 0.030786797 0.029632494, 0.024256006 0.026435301 0.030295581, 0.023912743 0.02385132 0.03058064, 0.02595295 0.025886342 0.030183509, 0.027799934 0.029028118 0.02963227, 0.027894139 0.029858485 0.02951993, 0.028657258 0.034149498 0.028849274, 0.028660655 0.031319141 0.029242218, 0.027172312 0.029613733 0.029632434, 0.028187707 0.030637935 0.029387489, 0.032300293 0.038490936 0.027673632, 0.030139953 0.032848343 0.028849229, 0.029284522 0.031864315 0.029093131, 0.030025348 0.032242268 0.028948262, 0.030836537 0.032427862 0.028817028, -0.035135925 -0.033531979 0.028037935, -0.035576269 -0.035488501 0.027669504, -0.03248705 -0.030603617 0.028836221, -0.032925367 -0.030059293 0.028845534, -0.047480196 0.010219201 0.028040305, -0.043491349 0.01047276 0.028818637, -0.048885018 0.011627987 0.027672127, -0.042226851 0.0094206929 0.029094622, -0.042922989 0.0098677874 0.028949961, -0.043785453 0.008387506 0.028847873, -0.010101914 0.047504097 0.02804251, -0.0099776387 0.04318282 0.028899282, -0.0095094442 0.042597696 0.029025704, -0.0091830194 0.041927263 0.029158846, -0.011507094 0.048912376 0.027674153, -0.0082795322 0.043804511 0.028849736, 0.033618286 0.035050169 0.028041601, 0.021868408 0.021811932 0.030932173, 0.031588987 0.032419771 0.028717071, 0.033953086 0.033866897 0.02817145, 0.035576046 0.03548561 0.027673334, 0.027913213 0.028199226 0.029716983, 0.027988359 0.027916819 0.029740751, 0.032325938 0.032243803 0.028640032, -0.026497751 -0.024191454 0.030292466, -0.029805616 -0.027793676 0.029535443, -0.029683426 -0.027099788 0.029629171, -0.031287566 -0.028493986 0.02926375, -0.030590445 -0.028052837 0.029406503, -0.02754195 -0.022995621 0.030292705, -0.027251944 -0.020369515 0.03054589, -0.046883956 -0.0097411573 0.028184071, -0.046414316 -0.0087064207 0.028321996, -0.032264486 -0.029807165 0.028969839, -0.046071053 -0.0082077235 0.028409734, -0.031856939 -0.029090628 0.029115304, -0.04566814 -0.0077538192 0.028505698, -0.030853063 -0.025760263 0.029629424, -0.028531998 -0.021754861 0.030292585, -0.034222707 -0.028573424 0.028845876, -0.03196229 -0.024370342 0.029629484, -0.038573176 -0.032205477 0.027669638, -0.029466212 -0.020471558 0.030292913, -0.029070765 -0.019881099 0.030385122, -0.035453126 -0.027031645 0.028845742, -0.033008784 -0.022932678 0.029629484, -0.039959952 -0.030467644 0.027669623, -0.036614016 -0.025437176 0.028845876, -0.03399092 -0.021450073 0.029629648, -0.03086412 -0.01939936 0.03021051, -0.032656342 -0.018917933 0.030019805, -0.041268557 -0.028670236 0.027669713, -0.037703171 -0.023792565 0.02884604, -0.034906358 -0.019925609 0.029629588, -0.042496219 -0.026816756 0.027669907, -0.038718835 -0.022101626 0.028846115, -0.035753459 -0.018362164 0.029629931, -0.036250457 -0.017952383 0.029586479, -0.043640807 -0.024910688 0.027670205, -0.039658397 -0.020367265 0.028846115, -0.044699803 -0.022956088 0.027670085, -0.040520415 -0.018593013 0.028846249, -0.039854169 -0.016984031 0.029082462, -0.045671389 -0.020956337 0.027670339, -0.046553656 -0.018915653 0.027670339, -0.043466136 -0.016013443 0.02850537, -0.047344625 -0.016837835 0.027670637, -0.044520229 -0.015595183 0.028332189, -0.045451924 -0.014946729 0.028191924, -0.048043221 -0.014727145 0.027670607, -0.046212271 -0.014100626 0.028092891, -0.046759933 -0.013099775 0.028040633, -0.048647344 -0.012587816 0.02767083, -0.047063112 -0.011996031 0.028039098, -0.047104448 -0.010857135 0.028088078, -0.049156606 -0.010423571 0.027670845, -0.049885258 -0.0060383826 0.027671114, -0.044143975 -0.0062347651 0.028847054, -0.042665988 -0.0047623217 0.029154658, -0.044452637 -0.0033945143 0.028847083, -0.041153446 -0.0032548159 0.029446363, -0.039662972 -0.0017699301 0.029711366, -0.044559225 -0.0014249533 0.028847411, -0.038162336 -0.00027486682 0.029955745, -0.040189341 0.00049339235 0.029630855, -0.036659971 0.0012219995 0.03017889, -0.050223693 -0.0016057789 0.027671427, -0.04412739 0.012760326 0.028583884, -0.044109583 0.012006015 0.028627828, -0.044578388 0.00054736435 0.028847337, -0.040127993 0.0022704899 0.029630944, -0.035170749 0.002705425 0.030378461, -0.035696626 0.0036091059 0.030294105, -0.033657983 0.0042124391 0.030560657, -0.044510648 0.0025186688 0.028847486, -0.039988264 0.0040431619 0.029630959, -0.050168976 0.0028392375 0.027671605, -0.043999538 0.013426974 0.028570563, -0.044355497 0.0044851303 0.02884762, -0.039770082 0.0058079958 0.029631078, -0.035501838 0.0051845163 0.030294016, -0.035237774 0.006749779 0.030294299, -0.030299827 0.0075576156 0.030892283, -0.04411374 0.0064426959 0.028847769, -0.039474234 0.0075615942 0.029631212, -0.040620804 0.0090900809 0.029387549, -0.041443571 0.0091563761 0.02924335, -0.049721539 0.0072620511 0.027671993, -0.034904584 0.0083018839 0.030294448, -0.038379297 0.010071665 0.029715776, -0.03903833 0.0095604956 0.029631376, -0.039801046 0.0092269629 0.029519573, -0.034503192 0.0098376572 0.030294538, -0.036167324 0.012276024 0.029951721, -0.02863428 0.0092166364 0.031021163, -0.043894693 0.011198461 0.028709114, -0.034034103 0.011354282 0.030294642, -0.029156879 0.011183232 0.030892447, -0.033979103 0.014456928 0.030143008, -0.026951522 0.010893241 0.031128988, -0.047665849 0.015902832 0.027672306, -0.043739483 0.014057145 0.028582528, -0.043474257 0.014474303 0.028606877, -0.043149292 0.014849916 0.028643891, -0.032897398 0.014317736 0.030294731, -0.028054222 0.013716221 0.030892536, -0.025158703 0.012679562 0.031219542, -0.031781882 0.016647488 0.03029488, -0.046915814 0.017995775 0.027672425, -0.041505083 0.016488761 0.028832972, -0.032231733 0.015758857 0.03029485, -0.027419955 0.014943719 0.030892715, -0.023365632 0.014466628 0.031286538, -0.04607375 0.020053312 0.027672708, -0.039860353 0.018128499 0.028997838, -0.026732087 0.016141906 0.030892581, -0.027967289 0.020450592 0.030465111, -0.045141608 0.02207166 0.027672693, -0.03821601 0.019767791 0.029138461, -0.025991857 0.017308593 0.03089273, -0.021572098 0.016254544 0.031330645, -0.044121087 0.024046913 0.027672842, -0.036572635 0.021406204 0.029255778, -0.038162664 0.023045152 0.028848782, -0.034928486 0.023045748 0.029349744, -0.02520068 0.01844126 0.030892819, -0.043014079 0.025975183 0.027672946, -0.037105978 0.024710596 0.028848812, -0.02436024 0.019537956 0.030892864, -0.026349768 0.022063419 0.030502632, -0.019778371 0.018043458 0.03135255, -0.041822955 0.027852193 0.027673081, -0.03597647 0.02632761 0.028848842, -0.033286184 0.024683312 0.029420614, -0.023472115 0.02059637 0.030892834, -0.024732813 0.02367641 0.030519783, -0.040549859 0.029674932 0.02767314, -0.034776747 0.027893245 0.028849036, -0.031641722 0.026323259 0.029468924, -0.022537977 0.021614626 0.030892953, -0.018053219 0.019764215 0.031353161, -0.039197564 0.031439617 0.027673438, -0.033508688 0.029404357 0.028848931, -0.029998943 0.02796185 0.029494599, -0.02155979 0.022590294 0.030892983, -0.023115441 0.025289685 0.030516773, -0.037768409 0.033142492 0.027673364, -0.032175288 0.030857787 0.028849199, -0.02843827 0.029518232 0.029498324, -0.020539343 0.023521811 0.030893058, -0.021473035 0.026928097 0.030492917, -0.030778676 0.032250687 0.028849155, -0.026877925 0.031074926 0.029481664, -0.019478768 0.024407417 0.030893132, -0.016328678 0.021484792 0.031333342, -0.034691408 0.036350951 0.027673751, -0.029322013 0.033580586 0.028849289, -0.018379986 0.02524507 0.030893207, -0.019831657 0.028566107 0.030448288, -0.027807832 0.034844831 0.028849438, -0.025317326 0.032631785 0.029444888, -0.017245188 0.026033282 0.03089352, -0.018189728 0.03020446 0.03038229, -0.014602885 0.023207307 0.031292677, -0.031342909 0.039274633 0.027673736, -0.026239157 0.036040753 0.028849304, -0.023756906 0.034189016 0.029387474, -0.016076714 0.026770517 0.030893207, -0.024619251 0.037166044 0.028849408, -0.021504402 0.036436558 0.029268458, -0.014876783 0.027455479 0.030893266, -0.016547844 0.031843334 0.030294627, -0.012876421 0.024930865 0.031231299, -0.027748868 0.041890979 0.027673781, -0.022951111 0.038218766 0.028849527, -0.013647616 0.028086811 0.03089349, -0.014905676 0.033482328 0.03018482, -0.01121968 0.026585087 0.031151682, -0.012391925 0.02866286 0.030893609, -0.023937851 0.044179603 0.027674034, -0.019252047 0.038684562 0.029105693, -0.019483313 0.040097475 0.028849691, -0.012766331 0.03352882 0.03029573, -0.01326555 0.035119832 0.030052423, -0.0095641017 0.028238758 0.031051055, -0.017690688 0.040920094 0.028849527, -0.016998604 0.040933684 0.028898597, -0.01273036 0.044149697 0.028582662, -0.013469368 0.043982998 0.028572813, -0.019939512 0.046122402 0.027674153, -0.011270732 0.034060732 0.030295894, -0.011633635 0.036748931 0.029898077, -0.0098100603 0.029646143 0.030893579, -0.0084889233 0.030050844 0.030893356, -0.0079211593 0.029879689 0.03092958, -0.01787971 0.046959177 0.027674004, -0.014743567 0.043184608 0.028645366, -0.0097530186 0.034525931 0.030295938, -0.0099771023 0.038402721 0.02971749, -0.015785158 0.047704041 0.027674064, -0.014152735 0.043654814 0.028594196, -0.0082163215 0.034923494 0.030295789, -0.0090036094 0.040454522 0.029420495, -0.0091604888 0.039722651 0.029536888, -0.0094755292 0.039041698 0.029635593, -0.0097064078 0.038707912 0.029679939, -0.0062662959 0.031532794 0.030784503, -0.0066633523 0.03525275 0.030296028, -0.0047550499 0.033042133 0.030631438, -0.0074643493 0.039491415 0.029633045, -0.0090115666 0.0412018 0.029292375, -0.011974722 0.044147387 0.028623685, -0.01123938 0.043977544 0.02869302, -0.010561883 0.043649539 0.02878654, -0.0050973892 0.035513014 0.030295894, -0.0057102442 0.039782971 0.02963306, -0.0035214722 0.035703808 0.030295998, -0.0032481551 0.034547389 0.030458629, -0.0063338578 0.04412809 0.028849781, -0.003944844 0.03999652 0.029633135, -0.0071389973 0.049738064 0.027674109, -0.004375726 0.044365078 0.028849989, -0.0021718144 0.040131852 0.029633164, -0.0017268062 0.036066815 0.03026323, -0.0049318373 0.05000487 0.027674273, -0.0024088621 0.044515088 0.02884993, -0.00039440393 0.040188625 0.029632986, -0.0027150512 0.050174356 0.027674332, -0.00043740869 0.044578001 0.028849974, 0.0013837516 0.040166765 0.029633105, 0.0017990172 0.039588273 0.02972506, -0.00049301982 0.050245345 0.027674243, 0.0087556541 0.046350703 0.028335571, 0.0097829401 0.0468335 0.028195545, 0.0015349686 0.044553772 0.028849885, 0.0017300248 0.050217897 0.027674183, 0.0035042763 0.044442192 0.02884981, 0.003816098 0.041602522 0.029362559, 0.003949672 0.05009225 0.027674258, 0.0061616898 0.049868405 0.027674273, 0.0058240294 0.043607712 0.028960645, 0.0083615482 0.049547046 0.027674213, 0.0078665316 0.045646757 0.028508633, 0.010545075 0.049128726 0.027674139, 0.010895938 0.047069043 0.028096393, 0.012708038 0.048614338 0.027674228, 0.013143957 0.04675369 0.028042287, 0.012036413 0.047042936 0.028044268, 0.014845937 0.048004642 0.027674109, 0.014150888 0.046219975 0.028091043, 0.015006959 0.045471072 0.028187335, 0.016954899 0.047300965 0.027674109, 0.016120404 0.043424085 0.028508708, 0.015668333 0.044546843 0.028324991, 0.015928596 0.044000313 0.02841267, 0.01903066 0.046504542 0.027674109, 0.017082632 0.039807767 0.029086128, -0.023908377 -0.021597117 0.029766187, -0.027162492 -0.022882745 0.029334173, -0.025686219 -0.021118596 0.029637128, -0.026176572 -0.024004236 0.029334009, -0.031049579 -0.027863041 0.028354287, -0.030019745 -0.025289595 0.028770208, -0.030268818 -0.02749227 0.028497607, -0.028930247 -0.026529074 0.028770074, -0.040182933 -0.03385067 0.02611284, -0.034887448 -0.031991199 0.027276516, -0.035639241 -0.035551488 0.026624143, -0.032745212 -0.031587899 0.02764909, -0.032778531 -0.030718729 0.027761683, -0.032611325 -0.029870108 0.02789636, -0.032252163 -0.029083893 0.028045341, -0.028100297 -0.021720767 0.029334143, -0.027462959 -0.020640314 0.029493257, -0.027621254 -0.027553707 0.02880834, -0.028076336 -0.027431041 0.028769955, -0.025794283 -0.025731444 0.029202729, -0.033214092 -0.027980238 0.028045595, -0.031721249 -0.028402016 0.028200969, -0.028746247 -0.027309641 0.028705224, -0.03105627 -0.024005294 0.028770074, -0.036201179 -0.030496478 0.027276665, -0.034076199 -0.033992365 0.02710855, -0.032509163 -0.032429114 0.027565449, -0.034360841 -0.026559442 0.028045803, -0.03203769 -0.022678748 0.028770193, -0.029238358 -0.020162269 0.029334068, -0.042884097 -0.030355975 0.026113197, -0.037451014 -0.028947905 0.027276665, -0.035446793 -0.025091752 0.028045759, -0.032962635 -0.021311969 0.028770387, -0.032785177 -0.019207448 0.028968602, -0.038634792 -0.027348042 0.027276933, -0.03647013 -0.023579434 0.028045654, -0.033829316 -0.019907683 0.028770328, -0.045282155 -0.02664645 0.026113287, -0.039750159 -0.025699899 0.027276739, -0.03742902 -0.022025451 0.028045893, -0.040795103 -0.024006292 0.027276903, -0.038321674 -0.0204328 0.028046101, -0.036325112 -0.018254489 0.028538406, -0.047360197 -0.022748902 0.026113465, -0.041768104 -0.022270173 0.027277127, -0.042667314 -0.020494834 0.027277187, -0.039856941 -0.017303601 0.028041735, -0.049103498 -0.018690526 0.026113898, -0.043491006 -0.01868321 0.027277291, -0.043379396 -0.016355336 0.027477503, -0.044592187 -0.015876561 0.027277529, -0.044237792 -0.01683858 0.027277187, -0.045655474 -0.015112683 0.027118132, -0.050499976 -0.014499813 0.026114047, -0.046319112 -0.014372081 0.027031407, -0.046832293 -0.013522252 0.026977703, -0.023963645 -0.023905471 0.029560208, -0.022129655 -0.022075966 0.029880375, -0.029418916 -0.027311251 0.028624102, -0.025638804 -0.028087318 0.028963298, -0.012234911 -0.031696424 0.029543251, -0.0098124146 -0.027958155 0.030062348, -0.0097509474 -0.032365292 0.029565692, -0.0080042332 -0.025879085 0.030316979, -0.0098057836 -0.025393799 0.0303047, -0.011057571 -0.027489409 0.030062348, -0.011607379 -0.024908707 0.030280486, -0.014719084 -0.031027555 0.029495135, -0.012280479 -0.026965261 0.030062348, -0.013478532 -0.026386842 0.030062333, -0.01340878 -0.024423435 0.030243844, -0.014649525 -0.025755107 0.030062482, -0.015209854 -0.02393876 0.030194506, -0.015790954 -0.025071338 0.030062437, -0.017202526 -0.030358851 0.029420555, -0.016712636 -0.029381633 0.02956596, -0.016900495 -0.024337232 0.030062631, -0.016940579 -0.023472786 0.030134708, -0.019685104 -0.02969037 0.029319301, -0.01801464 -0.028601751 0.029566139, -0.021670654 -0.029155821 0.029218495, -0.019280478 -0.027764052 0.029566064, -0.023655206 -0.02862148 0.029099941, -0.020507455 -0.026870623 0.029566109, -0.018670917 -0.023007125 0.030062765, -0.02169311 -0.025922626 0.02956602, -0.020400658 -0.02254127 0.029978156, -0.023313582 -0.0278593 0.029218107, -0.022834942 -0.024922714 0.029566243, -0.024540976 -0.026784569 0.029218346, 0.023963705 0.023901895 0.029562712, 0.024978101 0.022770867 0.02956897, 0.022129685 0.022072479 0.029883161, 0.022591636 0.020338506 0.029980764, 0.028282121 0.025070623 0.0290021, 0.026447058 0.024110004 0.029298127, 0.027621046 0.027550414 0.028811485, 0.025794327 0.025728077 0.02920559, 0.025975227 0.021626353 0.029568791, 0.023053899 0.018604115 0.030065566, 0.028943375 0.02258949 0.029164031, 0.027502775 0.022898316 0.029298231, 0.02960518 0.020106986 0.029297873, 0.026920125 0.020438343 0.029568851, 0.023516372 0.01686883 0.030137524, 0.025106609 0.015724689 0.03006506, 0.023978963 0.015133202 0.030196965, 0.027810588 0.019209027 0.029568687, 0.02578713 0.014581606 0.030065134, 0.024458304 0.013334587 0.030246332, 0.030267209 0.017623201 0.029404461, 0.028644949 0.017941296 0.029568583, 0.026416004 0.013409406 0.030064926, 0.024937868 0.011535749 0.030282676, 0.030797273 0.015635058 0.029470459, 0.029421628 0.016637087 0.029568523, 0.026991397 0.012209877 0.030064866, 0.030139029 0.015299529 0.029568553, 0.031857654 0.011657238 0.029552162, 0.02751255 0.010985762 0.030064881, 0.031327292 0.013646215 0.029519603, 0.025417522 0.0097367465 0.03030704, 0.030795544 0.013931081 0.02956818, 0.025897086 0.00793764 0.030319035, 0.027977809 0.0097395927 0.030064628, 0.032387942 0.0096681416 0.02956821, 0.036317989 0.023810372 0.028048649, 0.037429065 0.022022545 0.028048187, 0.036860868 0.021774352 0.028161705, 0.038467735 0.024867892 0.027590811, 0.039285183 0.027805641 0.027112097, 0.040419474 0.026129782 0.027112067, 0.03738834 0.026462972 0.027590856, 0.032508895 0.032426342 0.027569026, 0.034076065 0.033989474 0.027112216, 0.033241093 0.032020628 0.027521282, 0.039479122 0.023229033 0.027590632, 0.042273149 0.027328208 0.026627779, 0.041087151 0.029081151 0.026628047, 0.038321704 0.020429924 0.028048173, 0.037539527 0.019228354 0.028275758, 0.041482002 0.024407625 0.027111918, 0.040420666 0.021548972 0.027590528, 0.043384716 0.025527284 0.026627749, 0.039146632 0.018801063 0.028047979, 0.038218617 0.016681209 0.028360039, 0.042471454 0.022642329 0.027111664, 0.041290864 0.019830868 0.027590469, 0.044419453 0.023680881 0.026627749, 0.039902508 0.017138809 0.028048038, 0.04338561 0.020837024 0.027111754, 0.042087987 0.018077597 0.027590424, 0.045375451 0.021792799 0.026627719, 0.040587589 0.015446499 0.028047726, 0.038898021 0.014133349 0.028414488, 0.044223279 0.018994942 0.027111456, 0.042810827 0.016292617 0.027590349, 0.046251744 0.019866318 0.026627421, 0.041201085 0.013726711 0.0280478, 0.039577335 0.011585057 0.028439954, 0.045052826 0.013044864 0.027367994, 0.044982687 0.017119214 0.027111471, 0.035474703 0.032526985 0.027112335, 0.033863038 0.031463489 0.027507275, 0.034346506 0.030780181 0.027528018, 0.043457851 0.014478505 0.027590156, 0.034545779 0.030357644 0.027554423, 0.037101895 0.034019098 0.026628137, 0.035639122 0.035548627 0.026628226, 0.047046065 0.017904371 0.026627317, 0.034691468 0.029910982 0.027591109, 0.036810771 0.031007186 0.027112156, 0.035233393 0.027878806 0.027763307, 0.045662552 0.015213162 0.027111381, 0.036242962 0.028011084 0.027591079, 0.035775512 0.025845185 0.027915806, 0.047756866 0.015911132 0.026627153, 0.038499117 0.032429427 0.026628256, 0.038081527 0.02943249 0.027112037, 0.039828315 0.030782491 0.026628017, -0.045716614 -0.0010137707 0.02760525, -0.045717016 0.00099258125 0.027605295, -0.041228563 -0.00091433525 0.02843909, -0.052536905 0.00056450069 0.026114643, -0.04122898 0.00089503825 0.028439358, -0.044255614 0.011508316 0.027605742, -0.050732538 0.013660401 0.026115581, -0.044369116 0.012378469 0.027538672, -0.044275209 0.013254583 0.027507752, -0.036509499 0.0018152744 0.029185966, -0.04114987 0.0027021468 0.028439462, -0.034960523 0.0033600628 0.029390097, -0.05101499 -0.01256752 0.026114166, -0.047282919 -0.010303065 0.027054116, -0.047347501 -0.011589736 0.02697809, -0.036630422 0.0040249676 0.02914305, -0.033410162 0.0049063712 0.029572099, -0.043977961 0.014086172 0.027515456, -0.045629442 0.0029969066 0.027605474, -0.040991679 0.0045046359 0.028439716, -0.028320521 0.0099823028 0.030021727, -0.034277707 0.013527796 0.029143661, -0.026622027 0.011676103 0.030124292, -0.036418617 0.0056279004 0.029143095, -0.04545413 0.004995048 0.027605414, -0.049405739 0.017873347 0.026115894, -0.04365766 0.014614135 0.027543634, -0.045763344 -0.0074136853 0.027477771, -0.051890194 -0.008238107 0.026114345, -0.044226781 -0.0058812946 0.027821988, -0.052303568 0.004975155 0.026115149, -0.043250918 0.015086025 0.027590379, -0.046912163 -0.0090732127 0.027184054, -0.046419322 -0.008191064 0.027318895, -0.040754721 0.006298244 0.028439522, -0.036136642 0.0072197616 0.029143199, -0.031714633 0.0065972656 0.029746234, -0.039483085 0.0088910609 0.028570428, -0.040336311 0.008715719 0.028434798, -0.045191094 0.0069840699 0.027605742, -0.040439069 0.008079797 0.028439611, -0.041203469 0.0087428093 0.028284892, -0.042041808 0.008970812 0.028128415, -0.035785168 0.0087977499 0.029143393, -0.030017927 0.0082892925 0.029896006, -0.038005292 0.0098098814 0.028772011, -0.03869006 0.0092627704 0.028685242, -0.05170083 0.0093508363 0.026115313, -0.044841245 0.0089594722 0.027605742, -0.042804316 0.0093877763 0.027974024, -0.031087294 0.0091058165 0.029746473, -0.036141992 0.011668444 0.028973013, -0.043448299 0.0099697858 0.027830526, -0.044405118 0.010917664 0.027605906, -0.043942139 0.010689273 0.027705222, -0.030657902 0.010460496 0.029746607, -0.029623017 0.013107032 0.029746503, -0.032412395 0.01538837 0.029284447, -0.042587817 0.016651034 0.027606145, -0.041761786 0.016571477 0.027762607, -0.029019535 0.014393657 0.029746816, -0.024923161 0.013370469 0.030204654, -0.03054589 0.017249987 0.029396817, -0.041816488 0.0185031 0.0276061, -0.040271655 0.018057615 0.027915165, -0.028360188 0.015652671 0.029746786, -0.02905193 0.018739969 0.029465988, -0.027557641 0.020230785 0.029517874, -0.023223624 0.015065491 0.030263439, -0.047729775 0.021960184 0.026116073, -0.040964544 0.020319328 0.027606279, -0.038780898 0.019545034 0.028048441, -0.027646318 0.01688157 0.029747009, -0.040033862 0.0220965 0.027606323, -0.037289128 0.021032989 0.028161705, -0.04571633 0.025891513 0.026116386, -0.039026111 0.023831174 0.027606562, -0.035423487 0.022893816 0.028275952, -0.043380022 0.029639944 0.02611652, -0.026060313 0.019239366 0.029747009, -0.021523967 0.016760737 0.030301616, -0.037943289 0.025519982 0.027606502, -0.033557117 0.024755538 0.028360441, -0.025191411 0.020364046 0.029747024, -0.019824103 0.018456191 0.030319452, -0.026062921 0.021721363 0.029552013, -0.036787346 0.027159557 0.027606606, -0.024568409 0.023212373 0.029568836, -0.040736958 0.033179 0.026116684, -0.035560593 0.028746903 0.027606755, -0.031690285 0.026617721 0.028415278, -0.034265473 0.030279115 0.027606964, -0.029823095 0.028480247 0.028440729, -0.033827007 0.032494381 0.027368665, -0.037806079 0.036483303 0.026116982, -0.049105048 0.001874879 0.026892677, -0.048763067 0.0060819238 0.026892841, -0.045452043 -0.0050163269 0.027605042, -0.04268761 -0.0043464154 0.028142035, -0.052398637 -0.0038504452 0.026114628, -0.045628205 -0.0030179918 0.027604967, -0.041146278 -0.0028089881 0.028437912, -0.039602548 -0.0012695938 0.028710365, -0.047578216 0.0097558051 0.0270174, -0.048060894 0.010244176 0.026893035, -0.03805697 0.00027215481 0.028959751, -0.045223504 0.019224942 0.026893571, -0.043406963 0.023034886 0.026893809, -0.047023177 -0.011502489 0.015391022, -0.047023147 -0.011503205 0.026731908, -0.046985522 -0.010527387 0.026788339, -0.046974093 -0.010448352 0.015390903, -0.046759889 -0.0095812529 0.026879132, -0.046704888 -0.0094278455 0.015391037, -0.046270996 -0.0085560977 0.027023539, -0.046227381 -0.0084866732 0.015391052, -0.045562983 -0.0076673478 0.027202368, -0.045563012 -0.0076669157 0.015391082, -0.045503259 -0.0076078922 0.027217194, 0.016117066 0.044293582 0.027321875, 0.016877204 0.044009686 0.027321875, 0.016462356 0.043336794 0.027480617, 0.017401874 0.039811954 0.028045088, 0.018811941 0.049055114 0.026117533, 0.014624804 0.050461888 0.026117444, 0.014719903 0.046097428 0.027057379, 0.01363793 0.046796679 0.026981205, 0.022865981 0.04730168 0.026117593, 0.018712014 0.043261304 0.027321696, 0.020514071 0.042436421 0.027321666, 0.018343747 0.036277577 0.028541386, 0.02032876 0.037899166 0.028126508, 0.019287854 0.032735363 0.028971538, 0.019990534 0.033777714 0.028773472, 0.022279978 0.041536614 0.027321696, 0.026758313 0.045213908 0.026117265, 0.021903992 0.037011191 0.028126553, 0.015599549 0.045161471 0.027187198, 0.021392733 0.032907575 0.028773412, 0.02023375 0.029186219 0.029337004, 0.024006099 0.040563479 0.027321786, 0.02344048 0.036057785 0.028126374, 0.022757262 0.031979188 0.028773278, 0.020707279 0.027409464 0.02949585, 0.030461639 0.042806476 0.026117325, 0.025690079 0.039518476 0.027321637, 0.021789193 0.028044194 0.02933681, 0.021181077 0.025631562 0.029639587, 0.024935484 0.035040647 0.028126433, 0.024081439 0.030994236 0.028773278, 0.02732861 0.038403556 0.027321517, 0.022948891 0.027103603 0.029336914, 0.021655247 0.023852453 0.029768601, 0.02638641 0.033961341 0.028126329, 0.027722701 0.030583844 0.028433964, 0.025362879 0.029954553 0.028773084, 0.028184444 0.031322211 0.028283343, 0.028918862 0.037221104 0.027321339, 0.033949584 0.040096611 0.026117146, 0.027499631 0.028005943 0.028773099, 0.024068087 0.026114732 0.029336825, 0.027367949 0.028876528 0.028685957, 0.02779074 0.03282246 0.028125986, 0.028807074 0.031934068 0.028126091, 0.026599795 0.02886188 0.028773054, 0.027444378 0.029753298 0.028570741, 0.030458003 0.035972506 0.027321339, 0.029555812 0.03238368 0.027971134, 0.031943128 0.034660384 0.027321279, 0.030387178 0.032645732 0.027827322, 0.031262085 0.032706574 0.027702212, 0.031898007 0.032620266 0.027627289, 0.01355058 0.046473265 0.015394181, 0.013550609 0.046472624 0.026735216, 0.014377952 0.045951307 0.026791662, 0.014439106 0.045903623 0.015394211, 0.015082926 0.045284763 0.026881993, 0.015188158 0.045160294 0.015394062, 0.015727937 0.044345781 0.027026862, 0.015764534 0.044276372 0.015394092, 0.016142339 0.043290123 0.027205348, 0.016142428 0.043291017 0.015394092, 0.016164064 0.043208823 0.027220279, 0.042266294 0.0014995039 0.028254434, 0.045795411 0.0010126084 0.027589411, 0.042944804 -0.0010458231 0.028133869, 0.028317109 -0.0011383295 0.030198172, 0.03216514 -0.0021154881 0.029765174, 0.028951928 -0.003518641 0.030113548, 0.035621226 -0.0024588406 0.029308915, 0.032226846 -0.00070232153 0.029765397, 0.045795992 -0.0009971112 0.027589262, 0.03204149 -0.0035238713 0.029765174, 0.036164641 -0.0044960678 0.029202893, 0.04570812 -0.0030048192 0.027589306, 0.043623045 -0.0035898089 0.027983308, 0.031856224 -0.004925862 0.029765129, 0.029523 -0.0056598037 0.030017227, 0.03670755 -0.0065324605 0.029077813, 0.03160955 -0.0063184053 0.02976498, 0.037250265 -0.0085679591 0.028934181, 0.030093774 -0.0078001171 0.029901132, 0.03130199 -0.0076987594 0.029764935, 0.037792787 -0.010601819 0.028770983, 0.035780028 -0.01048401 0.029077724, 0.038291723 -0.011724472 0.028640807, 0.037997365 -0.011187524 0.028712615, 0.030664355 -0.0099394768 0.029764757, 0.0450349 -0.010422125 0.027504832, 0.044755161 -0.011258081 0.027520195, 0.044288829 -0.012003422 0.027572945, 0.04366143 -0.012618139 0.027659804, 0.039555952 -0.012906879 0.028374448, 0.035286024 -0.012043267 0.02907759, 0.038856268 -0.012392104 0.028516576, 0.031234473 -0.012077108 0.029607564, 0.03932853 -0.013422683 0.028383359, 0.040356115 -0.01324518 0.028220579, 0.034723759 -0.013579369 0.029077411, 0.031780481 -0.014123842 0.029436573, 0.042079628 -0.013327911 0.027912721, 0.043351874 -0.014795735 0.027588531, 0.04121308 -0.013388023 0.028063938, 0.03870213 -0.015134782 0.028383434, 0.034094825 -0.015089229 0.029077411, 0.042661294 -0.016682714 0.027588367, 0.038001075 -0.016817778 0.028383389, 0.033400387 -0.016570181 0.029077306, 0.032325909 -0.016169071 0.029244706, 0.032870859 -0.018212035 0.029032126, 0.041888565 -0.018537939 0.027588516, 0.037226826 -0.018468246 0.0283833, 0.041035235 -0.020357326 0.027588353, 0.036381081 -0.020083368 0.028383136, 0.033415198 -0.020253107 0.028798327, 0.040102988 -0.022137702 0.027588174, 0.035852358 -0.029392272 0.027476653, 0.03604418 -0.030681968 0.027276635, 0.035244495 -0.027113199 0.027849704, 0.03546524 -0.021659702 0.028383002, 0.034025863 -0.022543296 0.028510183, 0.03909342 -0.023875192 0.027588025, 0.035914361 -0.031984642 0.027117133, 0.044300854 -0.0061321259 0.027801692, 0.03800866 -0.02556701 0.027587891, 0.034635797 -0.024829954 0.028193966, 0.036850676 -0.027209491 0.027588025, 0.046212748 -0.015385926 0.026986226, 0.042909697 -0.013067976 0.02777575, 0.035604745 -0.032929733 0.027030259, 0.03512533 -0.033799037 0.026976675, 0.045259684 -0.01924333 0.026882961, 0.033582717 0.0051864386 0.029544517, 0.031854138 0.0049352497 0.029765591, 0.032903105 0.00773561 0.029568046, 0.026412293 0.0060051978 0.030318782, 0.027047321 0.0036236048 0.030300155, 0.044915006 0.0089929104 0.027590036, 0.045573458 0.011113778 0.027366817, 0.040092677 0.0096524954 0.02843979, 0.040636256 0.0076131225 0.028421551, 0.032040045 0.0035332888 0.029765457, 0.034262508 0.0026375055 0.029493779, 0.027682275 0.0012423694 0.030260086, 0.04497835 -0.0086734146 0.027589008, 0.045110524 -0.0095425397 0.027528465, 0.045266181 0.0070142299 0.027589872, 0.041179821 0.0055746585 0.02838476, 0.032164171 0.0021247566 0.029765442, 0.045530468 0.0050219893 0.027589723, 0.041723013 0.0035366714 0.028329059, 0.034942076 8.8751316e-05 0.029415399, 0.032226577 0.00071185827 0.029765338, 0.045706838 0.0030203611 0.027589619, 0.03553009 -0.029429585 0.027216226, 0.035551816 -0.029511124 0.027201161, 0.035551801 -0.029510155 0.015389889, 0.033291206 -0.021032035 0.028446078, 0.031040967 -0.012591839 0.029305741, 0.026104748 0.0059239417 0.015391856, 0.02857475 -0.0033413023 0.029855832, 0.026104733 0.005923152 0.030050561, 0.044755444 -0.008716017 0.027428269, 0.044768453 -0.0087644905 0.027423546, 0.044768319 -0.0087644905 0.024976939, 0.042588159 -0.00058706105 0.027998731, 0.039873645 0.0095944256 0.024978012, 0.041231439 0.0045019984 0.028197154, 0.039873794 0.0095941275 0.028277531, 0.035282895 -0.00035919249 0.029199123, 0.033109978 0.0077909082 0.0293708, 0.033110127 0.0077909082 0.024977744, 0.038004547 -0.010567576 0.024976641, 0.036639482 -0.0054476559 0.028945535, 0.037994206 -0.01052855 0.028574049, 0.038004592 -0.010567859 0.028570384, 0.041242674 -0.01107277 0.02289094, 0.042211786 -0.010814354 0.022891045, 0.041583464 -0.011066228 0.022891209, 0.041912898 -0.010978311 0.022891045, 0.040345892 -0.01062341 0.022891089, 0.040146858 -0.010346696 0.022891, 0.040605187 -0.010844633 0.02289103, 0.04091014 -0.010997429 0.022890955, 0.042650864 -0.01029934 0.022891104, 0.042462766 -0.010583416 0.022891045, 0.040020034 -0.010030121 0.022891015, 0.042752996 -0.0093016028 0.022891104, 0.042765796 -0.0099782348 0.022891074, 0.042800531 -0.0096392035 0.022890985, 0.03512539 0.0083285272 0.022892252, 0.037858382 0.0090571642 0.022892118, 0.023734733 -0.039086938 0.02760309, 0.021997601 -0.04009065 0.027602911, 0.021404669 -0.035250023 0.028437376, 0.01983808 -0.036154926 0.028437197, 0.012159988 -0.044082865 0.027602732, 0.011463076 -0.044616058 0.027535468, 0.010657549 -0.044972956 0.027504563, 0.016681194 -0.032528251 0.029184148, 0.018233255 -0.036990315 0.028437167, 0.014568761 -0.031959236 0.029388219, 0.032562673 -0.035798773 0.027052641, 0.033709258 -0.03521128 0.026976496, 0.014828026 -0.033737883 0.029140949, 0.012454361 -0.031389639 0.029570043, 0.0097886026 -0.045130983 0.027512103, 0.020218045 -0.041016683 0.027602851, 0.016593441 -0.037754387 0.028437048, 0.0055137426 -0.029519737 0.030019403, 0.005421862 -0.036451608 0.02914089, 0.0031976551 -0.028895885 0.030122116, 0.013333887 -0.034355864 0.02914086, 0.018399626 -0.041863993 0.027602881, 0.0091712624 -0.04511784 0.027540356, 0.029300734 -0.0359274 0.02747637, 0.027205423 -0.035363004 0.027820423, 0.0085591674 -0.045001358 0.027586818, 0.031312391 -0.036092445 0.027182415, 0.030302003 -0.03610681 0.027317226, 0.014921591 -0.038445845 0.028437063, 0.01181443 -0.034907624 0.029140934, 0.010142311 -0.030766785 0.029744193, 0.012040138 -0.038641214 0.028567821, 0.01261878 -0.039292291 0.028431863, 0.016545758 -0.042630896 0.027602851, 0.013220817 -0.039063171 0.028437272, 0.01302886 -0.040056825 0.028282136, 0.013250381 -0.040896773 0.028125539, 0.010271877 -0.035392225 0.029140741, 0.007828638 -0.03014347 0.029893845, 0.010505497 -0.037821054 0.028769404, 0.011321813 -0.038140312 0.028682619, 0.014660105 -0.04331556 0.027602777, 0.013270721 -0.04176572 0.027970925, 0.0076563209 -0.031477705 0.029744074, 0.0079644173 -0.037136421 0.028970227, 0.013088703 -0.042614251 0.027827501, 0.01274623 -0.043916821 0.027602836, 0.012712419 -0.043401867 0.027702019, 0.0062682182 -0.031783119 0.029744163, 0.0034589618 -0.032210246 0.029744118, 0.0028779358 -0.035766408 0.02928178, 0.0068723112 -0.045209989 0.027602598, 0.0065283179 -0.044454545 0.027759194, 0.0020429939 -0.032331124 0.029744193, 0.00088076293 -0.028271824 0.030202284, 0.00033250451 -0.035080835 0.029393822, 0.004882738 -0.045467764 0.027602687, 0.0044960529 -0.043907419 0.027911887, 0.00062295794 -0.032389507 0.029743999, -0.0017049164 -0.03453216 0.029463172, -0.0037428886 -0.033983395 0.029514909, -0.0014367849 -0.02764751 0.030260891, 0.0028839111 -0.045638219 0.027602583, 0.0024626702 -0.043359727 0.028044865, -0.00079835951 -0.032385543 0.029744044, 0.00087939203 -0.045720682 0.027602717, 0.00042812526 -0.042811811 0.028157994, -0.0011267066 -0.045715287 0.027602553, -0.002116248 -0.042126819 0.02827242, -0.0036332458 -0.032191023 0.029744193, -0.003754884 -0.027023241 0.030299157, -0.003130734 -0.045621946 0.027602553, -0.0046617836 -0.041441441 0.028356925, -0.0050416291 -0.032000676 0.029743999, -0.0060730428 -0.026398927 0.030317008, -0.0057813972 -0.033434346 0.029548928, -0.0051285923 -0.045440733 0.027602524, -0.0078196377 -0.032885522 0.029565901, -0.0071167052 -0.04517217 0.027602881, -0.0072079003 -0.040755689 0.028411433, -0.0090911835 -0.044816345 0.027602673, -0.0097545236 -0.040069923 0.028436944, -0.011227936 -0.045541525 0.027364701, 0.022927463 -0.043465778 0.026890218, 0.019113094 -0.045273155 0.026889995, 0.027068898 -0.036856771 0.027603075, 0.02510646 -0.034797549 0.028140247, 0.025426373 -0.038008437 0.02760309, 0.023004353 -0.034231514 0.028436258, 0.020899281 -0.033664465 0.028708622, 0.015338928 -0.046083778 0.027014241, 0.015157372 -0.046746135 0.02689001, 0.018791318 -0.033096611 0.028957844, 0.0059611946 -0.048779398 0.026889846, 0.0017533898 -0.049111038 0.026889771, 0.033472419 -0.034973174 0.015389651, 0.033472419 -0.034973845 0.026730523, 0.032607585 -0.035429478 0.026787236, 0.032534733 -0.03545779 0.015389636, 0.03167662 -0.035706863 0.026877537, 0.031516418 -0.035734743 0.015389681, 0.030543447 -0.035795808 0.027022108, 0.030462757 -0.035791785 0.015389621, 0.02942048 -0.035627201 0.027200997, 0.029420361 -0.035626441 0.015389487, 0.029338866 -0.035605267 0.027215719, -0.01737617 -0.040175125 0.027980834, -0.019935697 -0.04124254 0.02758719, -0.01904954 -0.039409146 0.027980775, -0.019983545 -0.046203107 0.026623696, -0.018023834 -0.04700239 0.026623636, -0.017233327 -0.044941187 0.02710776, -0.019107148 -0.044177175 0.027107835, -0.020689145 -0.038573593 0.027980804, -0.019833162 -0.037355632 0.02825214, -0.018184423 -0.042044252 0.027587131, -0.020947069 -0.043335006 0.027108148, -0.0216517 -0.040368184 0.02758719, -0.021907851 -0.045322463 0.026623756, -0.022292212 -0.037669897 0.027980968, -0.02237691 -0.036670789 0.028132126, -0.022750169 -0.042416021 0.027108043, -0.023329407 -0.039422393 0.027587041, -0.023793638 -0.044361532 0.02662386, -0.024512857 -0.041422337 0.027107954, -0.024965629 -0.038406864 0.027587235, -0.024919167 -0.03598623 0.027981326, -0.025637224 -0.043322086 0.026623815, -0.026232287 -0.040355355 0.027108192, -0.026558086 -0.037323356 0.027587339, -0.027459994 -0.035301879 0.027799889, -0.027435556 -0.042206138 0.026623994, -0.027905449 -0.039216965 0.027108297, -0.028103381 -0.036174119 0.027587518, -0.029185399 -0.04101561 0.026624143, -0.032049447 -0.033239171 0.027514234, -0.032305226 -0.032847628 0.027534723, -0.029529139 -0.038009271 0.027108267, -0.0295991 -0.034960955 0.027587622, -0.02999939 -0.034617886 0.027587533, -0.030883566 -0.039752647 0.026624218, -0.01316072 -0.045027047 0.027363777, -0.013940379 -0.041492686 0.0279807, -0.011685669 -0.039549872 0.028437078, -0.013723686 -0.039000988 0.028419062, -0.031100631 -0.036734536 0.027108505, -0.030779108 -0.034318388 0.027529225, -0.014588878 -0.043423057 0.027587071, -0.015672162 -0.040869892 0.027980804, -0.015760839 -0.038452446 0.028382182, -0.032527193 -0.038419336 0.026624218, -0.015329093 -0.04562594 0.027107924, -0.032617435 -0.035394669 0.027108416, -0.031475872 -0.033850074 0.027504206, -0.016401291 -0.042771429 0.027587101, -0.034113288 -0.03701815 0.026624188, -0.016032279 -0.047718525 0.026623622, -0.01779744 -0.037903875 0.028326839, -0.043250561 -0.016057417 0.027216747, -0.034858778 -0.018317267 0.028446406, -0.026423827 -0.020588815 0.02930522, -0.0079213828 -0.025570527 0.015389964, -0.017179623 -0.023078442 0.029854834, -0.0079214126 -0.0255716 0.030048594, -0.029924586 -0.034403726 0.027426884, -0.029973224 -0.034390524 0.027421921, -0.029973134 -0.034390479 0.024975464, -0.021801278 -0.036591142 0.02799651, -0.011626914 -0.039331034 0.024975181, -0.016715646 -0.037960798 0.028194562, -0.011626825 -0.039331138 0.028274596, -0.01795122 -0.03037867 0.029197529, -0.0098066479 -0.03257221 0.02936849, -0.0098067075 -0.032571808 0.024975523, -0.028153151 -0.027631164 0.024975792, -0.023036003 -0.029009357 0.028944269, -0.028113708 -0.027642116 0.028573185, -0.028153092 -0.027631477 0.028569236, -0.011084422 -0.037316844 0.02288954, -0.029430956 -0.032376394 0.022889793, -0.010348931 -0.034585789 0.022889599, -0.029747054 -0.032248661 0.022889748, -0.030023381 -0.032048896 0.022889763, -0.030243874 -0.03178905 0.022889897, -0.030395895 -0.031483799 0.022889987, -0.03047049 -0.03115122 0.022889867, -0.03046307 -0.030810311 0.022889853, -0.030374438 -0.0304811 0.022889987, -0.030209661 -0.030182585 0.022889942, -0.029978067 -0.02993229 0.022889912, -0.02869539 -0.029645145 0.022890016, -0.029693425 -0.029744655 0.022889927, -0.029372096 -0.029630691 0.022889823, -0.029032946 -0.029596716 0.022890016, 0.007720381 0.045482472 0.027220353, 0.0077800453 0.04554221 0.027205437, 0.0077800751 0.04554294 0.015394151, 0.0015673339 0.039345011 0.028449535, -0.0046172738 0.033175662 0.029308394, -0.018183589 0.019644216 0.015392572, -0.011395201 0.026414543 0.029857486, -0.018183395 0.019643262 0.030051231, -0.014830917 0.043115199 0.027431145, -0.014795303 0.043150708 0.027426302, -0.014795348 0.043150678 0.024979845, -0.020787001 0.037173733 0.028000787, -0.028247014 0.029732525 0.024979085, -0.024515957 0.033454299 0.028198615, -0.028247073 0.029732361 0.028278574, -0.017331839 0.030733094 0.029200956, -0.023303643 0.02477631 0.029371709, -0.023303613 0.024776548 0.024978623, -0.013603657 0.034452081 0.028947964, -0.0098806322 0.038165703 0.028576821, -0.024776623 0.026253462 0.022893012, -0.013322279 0.041674078 0.022894025, -0.026774153 0.028255925 0.022893205, -0.013074547 0.04187125 0.02289398, -0.011569589 0.041869417 0.022893921, -0.012789011 0.04200837 0.02289404, -0.011854708 0.042007282 0.022894055, -0.01216352 0.042078048 0.022894055, -0.01248014 0.042078421 0.02289407, -0.016841099 0.041429773 0.027804375, -0.014979213 0.043286845 0.027591914, -0.018704146 0.0395713 0.027985573, -0.020568311 0.037712127 0.028136224, -0.022433192 0.035851702 0.028256133, -0.023925841 0.034362748 0.028330699, -0.025418997 0.032873303 0.028386265, -0.026912838 0.031383187 0.028422832, -0.028407142 0.029892817 0.028440952, -0.02128464 0.026487797 0.02954568, -0.0231525 0.02462475 0.029569, -0.019416928 0.028351024 0.02949515, -0.01754953 0.030213773 0.029417157, -0.015682817 0.032075852 0.029310882, -0.014190078 0.033565119 0.029204965, -0.012697846 0.035053492 0.029080421, -0.011206776 0.036541387 0.028936699, -0.0097164512 0.038027987 0.028773695, 0.005856961 0.044077143 0.027853772, 0.0075265765 0.045742884 0.027481049, 0.0041842163 0.042408228 0.02819778, 0.0025087297 0.040736496 0.028513789, 0.00083053112 0.039062485 0.028801784, -0.00066480041 0.037570566 0.02903533, -0.0021617115 0.036077127 0.029247716, -0.003660202 0.034582302 0.029439241, -0.0051598549 0.033086136 0.029610246, -0.0067259371 0.031523243 0.029767066, -0.0082933605 0.029959917 0.029903337, -0.0098614097 0.028395072 0.030019134, -0.011430249 0.026829824 0.030115321, -0.013174251 0.025090128 0.030199617, -0.01491861 0.023349866 0.030261293, -0.016663358 0.021609321 0.0303009, -0.018408269 0.019868657 0.030319601, -0.010375738 0.005385071 0.025391877, -0.0094275624 0.0052099675 0.025391951, -0.0098358542 0.010662407 0.0253921, -0.010166094 0.010463193 0.025392279, -0.011254549 0.0057819337 0.025391921, -0.0051879287 0.009438917 0.025392234, -0.0052473396 0.0084765404 0.02539219, -0.010439083 0.010190696 0.025392279, -0.0055354387 0.0075561255 0.025392085, -0.0053605735 0.010387599 0.025392264, -0.01063922 0.0098608583 0.025392041, -0.0060352534 0.0067315251 0.025392011, -0.010551214 0.0083764344 0.025391996, -0.0057552755 0.011267707 0.025392205, -0.010754436 0.0094927847 0.025391936, -0.0067179948 0.0060504228 0.025392026, -0.010709047 0.0087284297 0.025392056, -0.010778219 0.0091080219 0.025392056, -0.0075437874 0.0055529028 0.025391862, -0.0083515048 0.010570735 0.025392085, -0.0084648132 0.0052670091 0.025391966, -0.0087030381 0.010729581 0.025392234, -0.0090823025 0.010799468 0.025392279, -0.0094673783 0.010776728 0.025392175, 0.011366352 -0.0004697293 0.025391549, 0.012314618 -0.00064501166 0.025391549, 0.012274653 0.0049216151 0.025391877, 0.011906341 0.0048075169 0.025391936, 0.010487616 -7.2985888e-05 0.025391504, 0.016554102 0.0035839677 0.025391862, 0.016494721 0.0026216358 0.025391668, 0.011575952 0.004608199 0.025391877, 0.016206622 0.0017014295 0.025391534, 0.016381666 0.0045327991 0.025391757, 0.015986934 0.0054126233 0.025391951, 0.011302769 0.0043358207 0.025391906, 0.015706778 0.00087662041 0.025391653, 0.011190996 0.0025214106 0.025391713, 0.015024111 0.00019565225 0.025391638, 0.011103034 0.0040059239 0.025391877, 0.011033028 0.0028734654 0.025391921, 0.010987759 0.0036380887 0.025391728, 0.010964006 0.0032528639 0.025391892, 0.014198259 -0.00030212104 0.025391594, 0.013390645 0.0047157258 0.025391996, 0.013277277 -0.00058797002 0.025391474, 0.013039082 0.0048744082 0.025391951, 0.012659699 0.0049443692 0.025391877, -0.0045751184 -0.016371667 0.02539061, -0.0036268085 -0.016546741 0.025390521, -0.0040353537 -0.011094302 0.025390923, -0.0043655783 -0.011293516 0.025390953, -0.005453974 -0.015974879 0.025390655, 0.00061254203 -0.012317792 0.025390819, 0.00055326521 -0.013280153 0.02539067, -0.0046387762 -0.011565864 0.025390878, 0.00026507676 -0.014200389 0.025390625, 0.00043986738 -0.011369109 0.025390878, -0.0002348572 -0.01502502 0.025390685, -0.0048386306 -0.011895657 0.025391042, -0.0047507286 -0.013380274 0.025390744, 4.5329332e-05 -0.010489285 0.025391042, -0.00091743469 -0.015705988 0.025390685, -0.0049539208 -0.012263805 0.025390908, -0.0049085766 -0.013028383 0.025390849, -0.0049776733 -0.012648821 0.025390849, -0.0017432421 -0.01620388 0.025390729, -0.0025509745 -0.011186138 0.025390983, -0.0026642382 -0.016489595 0.02539064, -0.0029025525 -0.011027202 0.025390878, -0.0032818168 -0.010957226 0.025391102, -0.0036668628 -0.010980085 0.025390834, -0.014266372 -0.00016887486 0.030564681, -0.014208108 -0.0013017356 0.030564651, -0.010045752 -0.00035247207 0.029716343, -0.0095726252 0.012450397 0.030925959, -0.010228515 0.012292013 0.03100197, -0.0089055598 0.012474403 0.030827671, -0.008251369 0.012366489 0.030711412, -0.010843962 0.01200214 0.031051815, -0.011387125 0.011594027 0.031072229, -0.0080197901 -0.0079516619 0.029934078, -0.0098675787 -0.010306209 0.030564219, -0.0077315122 -0.0090328008 0.030047804, -0.010655195 -0.0094897151 0.030564338, -0.0090177804 -0.011057734 0.030563951, -0.0074438453 -0.010111898 0.03018266, -0.0071569085 -0.011188224 0.030337945, -0.0081109554 -0.01173915 0.03056404, -0.006585449 -0.013331771 0.030709967, -0.00099891424 -0.014836043 0.030709758, 0.00045080483 -0.014261886 0.030563891, 0.00057141483 -0.013269261 0.030337706, 0.0015821606 -0.014181018 0.03056398, 0.0013601482 -0.012482643 0.030182585, -0.012174323 0.010492861 0.031023666, 0.0027037859 -0.01401037 0.03056398, 0.0021508038 -0.011694103 0.030047715, 0.0038083345 -0.013751313 0.030563951, 0.0029429495 -0.010903835 0.029933661, 0.0048886389 -0.013405159 0.030564055, 0.0037364364 -0.010112375 0.029840425, 0.0059379935 -0.012974322 0.03056404, 0.0045310706 -0.0093194991 0.029767677, 0.0069499612 -0.012461543 0.0305641, 0.012484521 -0.0069072694 0.030564457, 0.012993634 -0.0058935285 0.030564427, 0.0093064606 -0.0045561194 0.029767886, 0.010101095 -0.0037634969 0.029840842, 0.01342085 -0.0048427284 0.030564502, 0.010894641 -0.002971977 0.029934347, 0.013762966 -0.0037612021 0.03056471, 0.011686817 -0.0021817237 0.030048147, 0.014018133 -0.0026557446 0.030564606, 0.012477592 -0.0013932139 0.030183166, 0.014184669 -0.001533702 0.030564696, 0.013266146 -0.00060653687 0.030338377, 0.014261678 -0.00040195882 0.030564889, 0.014836699 0.00096037984 0.030710772, 0.011204198 0.0071271062 0.030338779, 0.011708543 0.0081507564 0.030565262, 0.010128677 0.0074168295 0.030183554, 0.01334624 0.0065503865 0.030710995, 0.011023819 0.0090552866 0.030565336, 0.0090505481 0.007707268 0.030048862, 0.010269374 0.0099024922 0.030565411, 0.0079700351 0.0079980791 0.029934973, 0.0094500184 0.010687038 0.030565307, 0.0068877637 0.0082895309 0.029841468, 0.0085709393 0.011404157 0.030565381, -0.0049766004 -0.015393108 0.031050175, -0.0065428615 -0.017476544 0.031781405, -0.0043514222 -0.015660167 0.031070709, -0.0017928481 0.01062724 0.029841468, -0.0021448433 0.014103398 0.030565634, -0.0028751493 0.010918662 0.029935107, -0.0010174215 0.014229149 0.03056559, -0.0032586753 0.013888374 0.030565575, -0.0039556026 0.011209428 0.030049101, -0.0043520927 0.013585657 0.03056553, -0.0050338209 0.011499852 0.030183852, -0.003989175 -0.018229842 0.031781405, -0.0030031353 -0.015792489 0.031022459, -0.0054178238 0.013196886 0.030565605, -0.0061094463 0.011789486 0.030339122, -0.0064492226 0.012724683 0.03056556, -0.012460053 0.0091032982 0.030854285, -0.014597967 0.0082572997 0.031216815, -0.012347445 0.0082805306 0.03071104, -0.012749389 0.0064023584 0.030565187, -0.012384146 0.0098495632 0.030957177, -0.014669687 0.0086916834 0.031296656, -0.0013544559 -0.018611953 0.031781182, -0.015506878 0.0055618882 0.031133279, -0.013217852 0.0053690374 0.030565128, -0.013602793 0.0043018907 0.030565053, -0.014112696 0.0020930022 0.030564919, -0.016361207 0.0019288808 0.031133071, -0.014234588 0.00096519291 0.030564919, -0.011761472 -0.0025784075 0.030078426, -0.0094664544 -0.0025254041 0.029674739, -0.0091768205 -0.0036121309 0.029685214, -0.0097561777 -0.0014387667 0.029685214, -0.014059693 -0.0024264604 0.030564576, -0.013822749 -0.0035359859 0.030564532, -0.016446739 -0.00095999241 0.031132847, -0.012595683 -0.006702587 0.030564502, -0.010564491 -0.0063414723 0.030134425, -0.013088271 -0.0056807548 0.030564487, -0.012023658 -0.007682085 0.030564234, -0.015809074 -0.0046368688 0.031132668, -0.013498247 -0.0046228915 0.030564368, -0.010126293 -0.0073783696 0.030177072, -0.011375353 -0.0086131394 0.030564338, -0.0083084255 -0.0068685859 0.029840469, -0.0085976571 -0.0057841837 0.029767737, -0.014755815 -0.0073283762 0.031132653, -0.011053041 -0.01221849 0.031132415, -0.011201113 -0.014925286 0.031781614, -0.008786127 -0.014288649 0.031215563, -0.0063527524 -0.013950303 0.030825853, -0.0089630336 -0.016367704 0.031781286, -0.0055352896 -0.015004128 0.031000182, -0.0071811229 -0.015773565 0.031375691, -0.0060002953 -0.014514625 0.030923724, -0.0016558617 -0.015345052 0.030853018, 2.4199486e-05 -0.016773909 0.031215519, -0.0023406446 -0.015652612 0.030955732, -0.00031840801 -0.017051086 0.031295091, 0.0013077706 -0.018615365 0.031781361, 0.0026578754 -0.01626046 0.031132177, 0.003943339 -0.018239692 0.031781465, 0.0088358968 -0.011203498 0.030564025, 0.0070017874 -0.0099521726 0.030103222, 0.0079180449 -0.011869982 0.030564114, 0.0053265393 -0.0085262805 0.02971597, 0.0050724596 -0.015676066 0.031132057, 0.0064987391 -0.017492875 0.031781361, 0.011163518 -0.01495342 0.031781718, 0.0085187107 -0.014102831 0.031132221, 0.0089219511 -0.016389936 0.03178142, 0.0099539608 -0.0069981813 0.030103311, 0.0085111409 -0.0053495914 0.029716015, 0.011896417 -0.0078775585 0.030564234, 0.011233106 -0.0087976903 0.030564368, 0.010542169 -0.01266171 0.031132087, 0.0096979439 -0.01046598 0.030564263, 0.013177589 -0.013212442 0.031781763, 0.012665421 -0.010537252 0.03113246, 0.010498643 -0.0096624792 0.030564129, 0.014923602 -0.011202633 0.031781822, 0.014105499 -0.0085131526 0.031132445, 0.016365811 -0.0089648217 0.031781852, 0.01567696 -0.0050659478 0.031132698, 0.018228084 -0.0039909035 0.031782359, 0.0174748 -0.0065445006 0.031781867, 0.016260222 -0.0026512146 0.031133026, 0.018610284 -0.0013561696 0.031782344, 0.016772196 -6.8023801e-05 0.031216294, 0.015257105 0.0014724433 0.030826852, 0.01576063 0.002708599 0.031001329, 0.016999319 0.00019942224 0.031281278, 0.018613502 0.001306206 0.031782404, 0.015569881 0.0020615458 0.030925363, 0.01411514 0.0062362701 0.030854106, 0.0143089 0.0087485313 0.031216875, 0.014723584 0.0057974309 0.03095679, 0.016388074 0.0089203715 0.031783074, 0.014951721 0.011161774 0.031783015, 0.0076377094 0.012049109 0.030565411, 0.0063341558 0.010565981 0.030135438, 0.0058040619 0.0085814148 0.029768646, 0.0066561699 0.012617707 0.030565485, 0.012210846 0.011057526 0.031133518, 0.0093976557 0.013529673 0.031133533, 0.0023747087 0.014066368 0.030565456, 0.0023718476 0.011835441 0.030085519, 0.0034849942 0.013833374 0.030565619, 0.0072953403 0.014769584 0.031133801, 0.0056324601 0.013106629 0.030565724, 0.0045762062 0.015824586 0.031133875, 0.004573226 0.013512596 0.030565575, 0.00011634827 0.01426515 0.030565456, 0.00088348985 0.016449288 0.031133801, 0.0012496114 0.014210761 0.03056559, 0.018237948 0.0039418638 0.031782627, -0.0020312369 0.016347304 0.031133875, 0.01573579 0.0040613115 0.031071857, 0.015518814 0.0047067255 0.031062454, 0.015817404 0.00338687 0.031051308, -0.004424423 0.015867785 0.031133667, -0.0083279163 0.014557153 0.031217128, -0.013901606 0.0032075942 0.030565068, -0.016037241 0.0037696958 0.031133145, -0.01699847 0.0044436604 0.031447858, 0.015175879 0.0052940398 0.031023666, 0.017491072 0.0064971596 0.031782851, -0.0088870972 -0.0046986341 0.029716089, -0.0099517703 -0.0049034655 0.029897302, -0.012518808 -0.0040468127 0.030311093, -0.016232446 -0.0028166473 0.031132817, -0.017237335 -0.0034054071 0.031447202, -0.013070628 -0.0080952942 0.030838206, -0.014937028 -0.0092537552 0.031446949, -0.011335626 -0.010386974 0.030838087, -0.012953445 -0.01187247 0.031446815, 0.006122604 -0.007732287 0.029684871, 0.0070648789 -0.0084122419 0.02987729, 0.0069188923 -0.0069379359 0.029674381, 0.0068409145 -0.014988795 0.031132057, 0.0077150762 -0.0061435848 0.029684752, 0.0084034055 -0.0070748925 0.029877171, 0.0069351792 -0.01614508 0.031446651, 0.014990687 -0.0068347454 0.031132668, 0.015816465 -0.0076533407 0.031447068, 0.0047189593 0.0088736266 0.029716909, 0.0049115419 0.0099452436 0.029898152, 0.0036334991 0.0091660321 0.029685825, 0.010874718 0.012373954 0.031133816, 0.0025475323 0.0094585121 0.029675394, 0.0031107664 0.010516748 0.029875457, 0.0014613867 0.0097507983 0.02968587, 0.011276335 0.013472363 0.03144829, 0.0013537407 0.01310055 0.030315459, 0.0027477443 0.016242236 0.03113386, 0.0033237934 0.017251238 0.031448379, -0.0064082742 0.015336916 0.031175226, -0.0062119961 0.016433597 0.031448364, -0.013133973 -0.0099473149 0.031132475, 0.009141624 -0.0087169558 0.030198365, 0.004289031 0.011869937 0.030198082, 0.00020292401 0.011766255 0.030025676, -0.00070902705 0.010335505 0.02976878, 0.00037583709 0.010043249 0.029716879, -0.011775911 0.0061371624 0.030338943, -0.011488989 0.0050607324 0.030183524, -0.011201307 0.0039819181 0.030048564, -0.010913134 0.0029007047 0.029934585, -0.010624513 0.0018177778 0.029841051, -0.010335192 0.00073298812 0.029768273, -0.023019791 -0.027434424 0.030301899, -0.02351889 -0.029121608 0.03006579, -0.017830223 -0.022900179 0.031132072, -0.0271184 -0.035386369 0.028845578, -0.02695176 -0.035190642 0.028894216, -0.030028746 -0.034362897 0.028641328, -0.02877222 -0.041197807 0.027669117, -0.030388996 -0.04285486 0.027141511, -0.021109834 -0.023009628 0.030891076, -0.019846499 -0.022358552 0.03103973, -0.024210811 -0.026389331 0.030302048, -0.025737241 -0.028525323 0.029914618, -0.032300577 -0.038493767 0.027669266, -0.033913732 -0.040123269 0.02714178, 0.025598973 0.024427563 0.030364498, 0.023060545 0.021050364 0.030893564, 0.026133031 0.023855314 0.030364364, 0.028478593 0.021710992 0.0303047, 0.029542327 0.022078499 0.030150503, 0.022503138 0.019424617 0.031060085, 0.023969233 0.020009741 0.030893371, 0.031904042 -0.0062201768 0.030739456, 0.028855741 -0.0044056326 0.031115696, 0.030042455 -0.008845821 0.030880928, 0.034839317 -0.0082897395 0.03030318, 0.03764236 -0.008297056 0.029895902, 0.033028886 0.031891808 0.028589576, 0.037046194 -0.0060648769 0.030050829, 0.030896798 -0.0045152307 0.030892119, 0.035171762 -0.0067404956 0.030303136, -0.01078774 -0.047355577 0.028037176, -0.010040075 -0.051567867 0.027141079, -0.0093558729 -0.043589979 0.028845057, -0.011274621 -0.043133616 0.028844982, -0.014377117 -0.050530598 0.027141124, -0.0092176348 -0.039963081 0.029491052, 0.033631101 0.031386763 0.028571725, 0.040206566 0.033811614 0.027145922, 0.034101412 0.030753538 0.028587967, 0.034295171 0.030359 0.028611392, -0.030759141 -0.034071654 0.02858834, -0.031404018 -0.033617258 0.028568119, -0.031925559 -0.033025652 0.028582111, -0.032151297 -0.032649353 0.028604195, 0.023142323 0.01702179 0.031164095, 0.024830818 0.018929899 0.030893341, 0.025644019 0.017813101 0.030893207, 0.023781776 0.014617994 0.031244978, 0.030318901 0.019161344 0.030296579, 0.038572982 0.032202587 0.027673364, 0.03443639 0.029940858 0.028644785, 0.035033658 0.027697533 0.028833643, 0.026406899 0.016661167 0.030893251, 0.039959773 0.030464828 0.027673185, 0.042929366 0.030280188 0.027145714, 0.035631284 0.025453284 0.028998196, 0.027118117 0.015477031 0.030893102, 0.024421871 0.012213349 0.031303033, 0.031095847 0.01624383 0.030405596, 0.041268378 0.028667375 0.027673125, 0.036228746 0.023209482 0.029138699, 0.03770265 0.023788854 0.028848723, 0.036825985 0.020967171 0.029255778, 0.027776226 0.014262244 0.030893043, 0.042495996 0.02681388 0.027672827, 0.045342505 0.026530385 0.027145475, 0.038717896 0.022098079 0.028848872, 0.028379917 0.013019726 0.030893013, 0.025062665 0.0098074824 0.031339258, 0.031684279 0.014035419 0.030464217, 0.043640628 0.024907827 0.027672917, 0.039657727 0.020363763 0.028848708, 0.0374237 0.018723503 0.029349387, 0.02892822 0.011751518 0.030892879, 0.032273129 0.011825278 0.030501708, 0.044699714 0.022953138 0.027672768, 0.047429338 0.022589371 0.027145207, 0.040519595 0.018589735 0.028848544, 0.03802076 0.016482621 0.029420137, 0.02941969 0.010460541 0.03089273, 0.025704414 0.0073995739 0.031354338, 0.045671254 0.020953402 0.027672604, 0.041302428 0.01677911 0.028848454, 0.038618743 0.014238477 0.029468253, 0.029853731 0.0091489404 0.03089276, 0.032861486 0.0096176118 0.030518815, 0.046553493 0.018912762 0.027672455, 0.049174279 0.018485948 0.027144998, 0.042004123 0.014935717 0.028848305, 0.039216399 0.011996448 0.029493749, 0.030229211 0.0078193843 0.030892625, 0.026346356 0.0049917102 0.031347916, 0.033450425 0.0074088871 0.030516177, 0.04734461 0.016834959 0.027672455, 0.042623773 0.013063103 0.028848082, 0.030545652 0.0064744949 0.030892611, 0.048043057 0.014724165 0.027672276, 0.05056487 0.014248997 0.02714467, 0.043160051 0.011164919 0.028848112, 0.039784208 0.0098666549 0.029497221, 0.03080219 0.0051170588 0.030892536, 0.034049213 0.0051635802 0.030492291, 0.043611705 0.0092448592 0.028847799, 0.040351972 0.0077368468 0.029480383, 0.030998439 0.0037495345 0.030892506, 0.026989311 0.0025820881 0.031320721, 0.034648418 0.0029175729 0.030447468, 0.049156457 0.010420591 0.027672067, 0.051591307 0.0099094808 0.027144566, 0.043977976 0.0073067993 0.028847858, 0.040920004 0.0056070983 0.029443324, 0.031133935 0.0023748279 0.030892447, 0.044258192 0.0053542554 0.028847694, 0.041488156 0.0034770519 0.029385835, 0.031208783 0.00099520385 0.030892298, 0.027610973 0.00025363266 0.03127341, 0.035247728 0.00067181885 0.030381083, 0.049885213 0.0060352683 0.027671769, 0.052245945 0.0054985136 0.027144253, 0.044451833 0.0033913851 0.028847724, 0.051093712 -0.012220904 0.027143285, 0.051945999 -0.0078438967 0.027143508, 0.044771984 -0.0088264942 0.028642625, 0.031222135 -0.0003862232 0.030892149, 0.044883832 -0.0095732957 0.028591186, 0.028233558 -0.0020770878 0.031205416, 0.035847247 -0.0015742183 0.030293494, 0.044558331 0.0014218092 0.028847679, 0.042308703 0.00040231645 0.029266417, 0.031174719 -0.0017668158 0.030892029, 0.0437067 -0.01225771 0.028689831, 0.044221431 -0.01170592 0.028620496, 0.050223455 0.0016028732 0.027671531, 0.05252412 0.0010477602 0.027144074, 0.044577673 -0.00055065751 0.028847352, 0.043129161 -0.0026721358 0.029103458, 0.03562963 -0.0036057979 0.030303255, 0.036447033 -0.0038206726 0.030183479, 0.044509739 -0.0025218576 0.028847367, 0.050168723 -0.0028422028 0.027671307, 0.052423939 -0.0034102798 0.027143806, 0.049994007 -0.0050584972 0.027671307, 0.043950364 -0.0057480484 0.028896078, 0.049721375 -0.0072649717 0.027671084, 0.049873337 -0.016509995 0.027143076, 0.038247511 -0.010563537 0.029714778, 0.034438506 -0.0098226368 0.030302927, 0.038982362 -0.011930734 0.029533714, 0.038550273 -0.011317402 0.029632613, 0.043083772 -0.012680411 0.028783366, 0.03837651 -0.010950536 0.029677108, 0.048884928 -0.011630893 0.02767092, 0.044826239 -0.010329172 0.028569609, 0.044601202 -0.011052504 0.028579921, 0.03811115 -0.012718081 0.029632583, 0.040188774 -0.012799099 0.02928929, 0.039537668 -0.01243259 0.02941744, 0.033435807 -0.012827948 0.030302808, 0.031183481 -0.013113722 0.030571878, 0.042289212 -0.014111996 0.028846741, 0.042387381 -0.012952939 0.028896153, 0.041646942 -0.013065994 0.029022336, 0.040902808 -0.013013378 0.029155806, 0.037511364 -0.014391214 0.029632345, 0.047665775 -0.015905827 0.027670577, 0.041623682 -0.015968949 0.028846502, 0.036838204 -0.01603654 0.02963236, 0.04691574 -0.01799871 0.027670428, 0.048293665 -0.02068007 0.027142763, 0.040876582 -0.017794326 0.028846368, 0.038646102 -0.035587505 0.027141884, 0.03566885 -0.03189142 0.028190792, 0.035316244 -0.032972977 0.028091878, 0.036092803 -0.017650262 0.029632255, 0.032236248 -0.017052069 0.030208603, 0.04607369 -0.020056352 0.027670249, 0.040049464 -0.019584969 0.028846294, 0.03527689 -0.019229516 0.029632315, 0.032714739 -0.018842429 0.030017674, 0.045141429 -0.022074595 0.027670249, 0.04636617 -0.024701208 0.027142525, 0.039144039 -0.021337315 0.028846309, 0.044120759 -0.024049804 0.027670041, 0.035489097 -0.038736731 0.027141616, 0.032953426 -0.035367236 0.028086707, 0.031876788 -0.035734206 0.02818273, 0.038162082 -0.023047909 0.028846219, 0.033674061 -0.022431627 0.02958481, 0.043013856 -0.02597788 0.027669907, 0.044104397 -0.028544441 0.027142376, 0.037105277 -0.024713442 0.028846115, 0.041822895 -0.027855188 0.027669951, 0.035975918 -0.026330575 0.028846085, 0.034635812 -0.026030824 0.029081151, 0.040549964 -0.029677987 0.027669802, 0.041524798 -0.03218177 0.027142301, 0.039197534 -0.031442553 0.027669668, 0.035599574 -0.029638723 0.028504536, 0.03576453 -0.030760393 0.028331444, 0.037768364 -0.033145651 0.027669623, 0.036265299 -0.034783676 0.027669504, 0.034723192 -0.033947662 0.028039455, 0.033918932 -0.03476204 0.028038025, 0.034691229 -0.036353901 0.027669355, 0.03304933 -0.037852839 0.02766934, 0.03207621 -0.041606933 0.027141765, 0.030745834 -0.035844982 0.028320417, 0.030142203 -0.035797089 0.028407946, 0.0313427 -0.039277643 0.027669251, 0.027469307 -0.035114497 0.028845504, 0.029547796 -0.0356756 0.028504163, 0.026238695 -0.036043376 0.028845355, 0.023391634 -0.034014225 0.029445186, 0.02461879 -0.037168801 0.02884534, 0.021359816 -0.033465728 0.029709876, 0.020683125 -0.034445405 0.029631391, 0.019313872 -0.032913551 0.029954433, 0.027748764 -0.041893929 0.027669147, 0.028432354 -0.044177264 0.027141556, 0.022950664 -0.03822121 0.02884528, 0.019139424 -0.0353266 0.029631287, 0.017265663 -0.032360524 0.030177504, 0.021237478 -0.039199024 0.028845295, 0.017558098 -0.036138654 0.029631257, 0.023937643 -0.044182375 0.027669027, 0.024583414 -0.046429276 0.027141243, 0.014210448 -0.032872975 0.030301794, 0.013173342 -0.031255618 0.030559123, 0.019482866 -0.040100083 0.02884531, 0.015942454 -0.036879897 0.029631197, 0.012742445 -0.033469528 0.030301616, 0.010905072 -0.030643165 0.030735552, 0.017690316 -0.040922791 0.02884528, 0.014295682 -0.037549138 0.029631183, 0.019939348 -0.046125278 0.027668968, 0.020557538 -0.048346877 0.027141169, 0.011249557 -0.034000397 0.030301452, 0.008596316 -0.030019775 0.030890673, 0.015862882 -0.041665286 0.028844953, 0.012620836 -0.038144648 0.029631168, 0.011908352 -0.039084643 0.02951698, 0.012436584 -0.039726257 0.029384613, 0.012790531 -0.040471777 0.029240742, 0.0097347051 -0.034464613 0.030301526, 0.010465816 -0.038275763 0.029713169, 0.011237949 -0.038590699 0.02962859, 0.01400435 -0.042326093 0.028845042, 0.012953371 -0.041282177 0.029091522, 0.012914345 -0.042108878 0.02894704, 0.0071503073 -0.03039673 0.030890495, 0.006326139 -0.029406816 0.031019285, 0.015784949 -0.047707006 0.027668789, 0.016383514 -0.049916044 0.027141094, 0.012674481 -0.042903215 0.028815687, 0.0082006902 -0.034861639 0.030301392, 0.012247682 -0.043615505 0.028706059, 0.0075054318 -0.037477046 0.029945016, 0.0066507459 -0.035190254 0.030301511, 0.0044361353 -0.030909747 0.030890554, 0.0040326118 -0.028787702 0.031126961, 0.011506826 -0.048915356 0.027668804, 0.012091532 -0.05112578 0.027141094, 0.011655807 -0.044205338 0.028624654, 0.0092003942 -0.044889331 0.028603479, 0.011011288 -0.044598043 0.028580859, 0.010370061 -0.044820711 0.028567314, 0.0096945018 -0.044910416 0.02857925, 0.0050876588 -0.035449907 0.030301511, 0.0045772195 -0.036687329 0.030134141, 0.0030645877 -0.031075671 0.030890465, 0.0015936941 -0.028129503 0.031217486, 0.0016364157 -0.03589426 0.030284762, 0.0016869605 -0.031180769 0.030890495, 0.0071387887 -0.049740896 0.027668715, 0.0077123493 -0.05196698 0.02714096, 0.0087127835 -0.044795632 0.028640464, 0.0064713508 -0.044191316 0.028829753, 0.0043755472 -0.044367582 0.028844938, 0.0042290092 -0.043586761 0.028994337, 0.00030629337 -0.031224817 0.030890629, -0.00084577501 -0.027471289 0.031284198, -0.0013032407 -0.035101831 0.030397251, 0.0049316883 -0.050008073 0.02766858, 0.0032773763 -0.052433819 0.027140975, 0.0024085939 -0.044517681 0.028845087, 0.0019870549 -0.04298234 0.029135048, -0.0010751635 -0.0312078 0.030890554, 0.0027150214 -0.050177157 0.027668715, 0.00043730438 -0.044580713 0.028844982, -0.00025369227 -0.042378321 0.029252216, -0.0024544597 -0.031129733 0.030890554, -0.0032864213 -0.026813388 0.031328261, -0.0035105497 -0.034506783 0.030457273, 0.00049284101 -0.050248161 0.02766858, -0.001180917 -0.052522942 0.02714102, -0.0015351176 -0.044556424 0.028844878, -0.0024954677 -0.041774049 0.02934587, -0.0038290471 -0.030990794 0.030890629, -0.0057177991 -0.033912078 0.030496895, -0.0017302036 -0.050220892 0.02766861, -0.0035042763 -0.044444844 0.028845012, -0.0047348589 -0.041170701 0.029416844, -0.0051959455 -0.03079094 0.030890509, -0.0057280362 -0.026155397 0.031350046, -0.0039498359 -0.050095186 0.02766867, -0.0056307763 -0.052233592 0.027141035, -0.0054668486 -0.044246271 0.028845102, -0.0069771856 -0.040566474 0.029465184, -0.0065528303 -0.030531064 0.030890509, -0.0079251528 -0.033317491 0.03051579, -0.0061619878 -0.049871385 0.027668625, -0.0074185431 -0.043961242 0.028845191, -0.0078968108 -0.030211419 0.030890688, -0.0077421218 -0.025612995 0.03135182, -0.010132596 -0.032723099 0.030514717, -0.0083617717 -0.049550042 0.027668744, -0.0092253238 -0.029832587 0.030890569, -0.011346206 -0.0393897 0.029494464, -0.010535836 -0.029395267 0.030890614, -0.0097585917 -0.025070325 0.031338692, -0.012363255 -0.032122642 0.030493081, -0.013171464 -0.042592809 0.028844953, -0.01347433 -0.03881678 0.029477745, -0.011825651 -0.02890031 0.030890524, -0.011775598 -0.024527639 0.031310216, -0.014594436 -0.031522021 0.030450508, -0.015042454 -0.041968524 0.028844982, -0.015602693 -0.038243905 0.029440954, -0.013092428 -0.028349042 0.030890599, -0.016954944 -0.047303855 0.027668938, -0.018610403 -0.049129456 0.027141199, -0.016884193 -0.041262016 0.028845087, -0.014333487 -0.027742326 0.030890703, -0.013794705 -0.023984745 0.031266809, -0.01682575 -0.030921772 0.03038688, -0.018692836 -0.040474653 0.028845221, -0.017731711 -0.037670955 0.029383659, -0.01554653 -0.027081043 0.030890539, -0.019057214 -0.030321464 0.03030178, -0.021069333 -0.045620307 0.027668715, -0.022709787 -0.047373936 0.027141243, -0.016728938 -0.026366934 0.030890867, -0.015813202 -0.02344209 0.031207398, -0.02306664 -0.044643566 0.027669013, -0.026645437 -0.045277491 0.027141511, -0.020804465 -0.036844105 0.029264346, -0.022196546 -0.038664162 0.028845295, -0.017878994 -0.025601104 0.030890912, -0.02128908 -0.029721305 0.030194879, -0.025018707 -0.043579623 0.027668953, -0.023885056 -0.037644416 0.028845489, -0.023877427 -0.036017507 0.029101714, -0.018993825 -0.024785191 0.030890942, 0.054989457 0.011281207 0.024349496, 0.053307757 0.017588809 0.024349749, 0.051373318 0.014477 0.026717171, 0.058321327 0.0082006156 0.021981865, 0.057472289 0.012867108 0.021981955, 0.056250393 0.017449886 0.021982342, 0.055927396 0.0048211813 0.024349019, 0.053081244 0.0055862516 0.026716605, 0.053363889 0.001064688 0.026716202, 0.058792278 0.0034811795 0.021981627, 0.056109086 -0.0017042309 0.024348482, 0.05326204 -0.0034648031 0.026715919, 0.058589444 -0.0059948713 0.021980986, 0.058881775 -0.0012609512 0.02198121, 0.055531964 -0.0082066357 0.024348229, 0.052776426 -0.0079692006 0.02671586, 0.051910609 -0.012416303 0.026715577, 0.057917103 -0.010689825 0.021980882, 0.054204017 -0.014597997 0.024347931, 0.050670698 -0.016773924 0.026715353, 0.055452585 -0.019842044 0.021980345, 0.056869313 -0.015315607 0.021980599, 0.052142754 -0.020791963 0.024347469, 0.049065828 -0.021010652 0.026714981, 0.053676322 -0.024239793 0.021979958, 0.049376532 -0.026704937 0.024347231, 0.047107249 -0.025096104 0.026714802, 0.044809401 -0.029000595 0.026714653, 0.049093083 -0.032536238 0.021979585, 0.051551729 -0.028480321 0.021979868, 0.045942634 -0.032256722 0.024346843, 0.042188644 -0.032696322 0.026714459, 0.046315849 -0.03638117 0.021979392, 0.041887403 -0.037372157 0.024346769, 0.039264113 -0.036156386 0.026714221, 0.043238312 -0.039990053 0.021979243, 0.037265643 -0.041982278 0.024346441, 0.036056459 -0.039356023 0.026713952, 0.032589093 -0.042271838 0.026713818, 0.036263719 -0.046408057 0.021978751, 0.039880276 -0.043339714 0.021979049, 0.032139987 -0.046024725 0.024346247, 0.028886855 -0.04488337 0.026713789, 0.032411814 -0.04917559 0.021978721, 0.026579738 -0.049444765 0.024346054, 0.024976447 -0.047171652 0.026713565, 0.020886198 -0.049119845 0.026713446, 0.024104133 -0.053738028 0.021978393, 0.028349876 -0.051624134 0.021978393, 0.020659983 -0.05219613 0.02434586, 0.016645491 -0.050714105 0.026713312, 0.019701838 -0.055503398 0.021978319, 0.014460906 -0.054241896 0.024345562, 0.012284815 -0.051943064 0.026713252, 0.010543659 -0.057945102 0.021978036, 0.01517193 -0.056908727 0.021978185, 0.0080661327 -0.055553749 0.024345592, 0.0078355521 -0.052797735 0.026713222, 0.0033299476 -0.053272083 0.026713237, 0.0058468133 -0.058605447 0.021978229, 0.0015622377 -0.056114614 0.024345696, -0.0011998266 -0.053362519 0.026713118, -0.0036296993 -0.058784649 0.021978021, 0.0011120588 -0.058886126 0.021978006, -0.0049625635 -0.055916563 0.024345577, -0.0057207644 -0.053068638 0.026713282, -0.0083478987 -0.058301717 0.021978319, -0.01142031 -0.054962292 0.024345651, -0.010200694 -0.052392259 0.026713267, -0.014606938 -0.051338479 0.026713297, -0.013012126 -0.057441071 0.021978155, -0.01772368 -0.053264961 0.024345905, -0.018908009 -0.049914718 0.026713595, -0.022057742 -0.054610074 0.021978483, -0.017591953 -0.056207836 0.021978229, -0.023787349 -0.050847188 0.024345875, -0.02307272 -0.048131466 0.02671358, -0.027071282 -0.04600136 0.02671361, -0.026380286 -0.052658185 0.021978393, -0.029529408 -0.047741771 0.024346262, -0.030874908 -0.043539852 0.026713669, -0.03448537 -0.047744378 0.021978676, -0.030532062 -0.050364465 0.021978527, -0.034872189 -0.043990985 0.024346486, -0.034456059 -0.040764704 0.026714027, -0.038215458 -0.044814765 0.021978945, 0.040948719 0.036348045 0.0255346, 0.040849268 0.034352154 0.02671814, 0.044076517 0.034760311 0.024350673, 0.043012977 0.038180739 0.023167253, 0.044909015 0.038101837 0.021983564, -0.036451906 -0.040859044 0.025530145, -0.038289681 -0.042918637 0.023162603, 0.04361558 0.030764282 0.026717961, 0.047829345 0.034364596 0.021983355, 0.047814131 0.029408336 0.024350405, 0.046067551 0.026954606 0.026717693, 0.052722648 0.026247144 0.021982849, 0.050439551 0.030404449 0.021983147, 0.050905123 0.02365844 0.024350137, 0.048187524 0.022950724 0.026717573, 0.04996042 0.018781364 0.026717275, 0.054663837 0.021919563 0.021982521, 0.052416041 0.010067865 0.026716813, 0.043315083 -0.040061265 0.021189228, 0.046398193 -0.036445707 0.021751612, 0.043315127 -0.040061101 0.0217513, 0.046398193 -0.036445752 0.021189407, 0.039951295 -0.043416813 0.021189123, 0.03995128 -0.043416649 0.021751165, 0.036328226 -0.046490625 0.021189079, 0.036328077 -0.04649061 0.021750927, 0.044988766 0.038169444 0.021193773, 0.044988871 0.038169488 0.021755874, 0.032469496 -0.049263045 0.021188885, 0.032469511 -0.04926312 0.021750838, 0.04791446 0.034425706 0.021193415, 0.047914386 0.034425512 0.021755457, 0.028400347 -0.051716074 0.021188661, 0.028400347 -0.051715896 0.021750823, 0.050529137 0.03045851 0.021193445, 0.050529048 0.030458629 0.021755487, 0.024146929 -0.053833678 0.021188438, 0.02414684 -0.053833634 0.021750554, 0.052816316 0.026293904 0.021192998, 0.05281651 0.02629368 0.021755248, 0.019736871 -0.055602089 0.021188557, 0.019736841 -0.055602059 0.021750569, 0.054760933 0.02195856 0.021193027, 0.054761022 0.021958545 0.021754861, 0.015198931 -0.057009995 0.021188229, 0.015198871 -0.05700995 0.02175048, 0.056350425 0.017480999 0.02119261, 0.05635041 0.017480895 0.021754742, 0.010562271 -0.058048025 0.021188155, 0.010562345 -0.05804801 0.021750346, 0.057574362 0.012890011 0.021192282, 0.057574496 0.012890011 0.021754265, 0.005857259 -0.05870977 0.021188542, 0.005857259 -0.058709666 0.021750376, 0.058425084 0.0082152337 0.021191925, 0.058425039 0.0082152486 0.021754146, 0.0011140704 -0.058990747 0.02118817, 0.00111413 -0.058990613 0.021750316, 0.05889672 0.0034875423 0.02119188, 0.05889672 0.0034873933 0.021753833, -0.0036361367 -0.058888987 0.021188319, -0.0036362112 -0.058888927 0.021750331, 0.058986366 -0.0012631565 0.021191671, 0.05898647 -0.0012632757 0.021753624, -0.0083628595 -0.05840537 0.021188453, 0.058693737 -0.0060055107 0.021191239, 0.058693677 -0.0060055554 0.021753311, -0.0083628744 -0.05840537 0.021750554, -0.013035461 -0.057543159 0.021188438, 0.058020219 -0.010708883 0.021190956, 0.058020264 -0.010708883 0.021752998, -0.013035491 -0.057543099 0.02175042, -0.017623335 -0.056307763 0.021188274, 0.056970403 -0.015342787 0.021190777, 0.056970328 -0.015342951 0.021752805, -0.01762329 -0.056307703 0.02175054, -0.022096947 -0.05470705 0.021188676, 0.055551156 -0.019877404 0.02119045, 0.055551186 -0.019877374 0.021752581, -0.022096932 -0.054706976 0.021750644, -0.026427299 -0.052751556 0.021188468, 0.053771749 -0.024282902 0.021190271, 0.053771749 -0.024282917 0.021752179, -0.026427343 -0.052751601 0.021750778, -0.030586317 -0.050453916 0.021188691, -0.030586258 -0.050453916 0.021750793, 0.051643431 -0.028530896 0.021189928, 0.051643446 -0.028531 0.021752059, -0.034546733 -0.04782936 0.021188974, -0.034546822 -0.04782936 0.021750942, 0.049180418 -0.032594085 0.021189749, 0.049180314 -0.032594055 0.021751896, -0.038283303 -0.044894397 0.021189094, -0.038283259 -0.044894442 0.021751031, 0.040254459 -0.040356204 0.01288943, 0.04344967 -0.036894187 0.012889609, 0.04344961 -0.036894515 0.018909022, 0.03678453 -0.043542504 0.012889132, 0.040254623 -0.040356666 0.018908903, 0.03678444 -0.043542892 0.018908814, 0.033063173 -0.046431482 0.012889013, 0.033063263 -0.046431899 0.018908471, 0.043541774 0.036783874 0.012893677, 0.043541849 0.03678368 0.018913239, 0.029116109 -0.049003199 0.012888744, 0.029116109 -0.049003541 0.018908262, 0.046430781 0.033062533 0.012893558, 0.046430722 0.033062115 0.018913031, 0.024970025 -0.051240325 0.012888819, 0.024969965 -0.051240578 0.018908247, 0.049002498 0.029115424 0.01289317, 0.049002558 0.029115289 0.018912703, 0.020653442 -0.053127244 0.012888551, 0.020653352 -0.053127646 0.018908218, 0.051239565 0.024969399 0.012893111, 0.051239625 0.024969146 0.018912494, 0.016195655 -0.054651275 0.012888566, 0.016195714 -0.054651722 0.018908054, 0.053126678 0.02065289 0.012892783, 0.053126633 0.020652428 0.018912286, 0.011627391 -0.055802166 0.012888432, 0.011627376 -0.05580239 0.018907934, 0.054650649 0.016195074 0.012892514, 0.054650754 0.016194656 0.018911988, 0.0069795847 -0.056571677 0.012888625, 0.0069795698 -0.056572229 0.01890789, 0.055801332 0.011626706 0.012892395, 0.055801466 0.011626333 0.018911719, 0.0022840649 -0.056954801 0.012888461, 0.0022840649 -0.056955203 0.018907756, 0.056570917 0.0069790334 0.012892216, 0.056571037 0.0069786608 0.018911511, -0.0024268478 -0.056949094 0.012888402, -0.0024268776 -0.056949437 0.018907934, 0.05695419 0.0022835732 0.01289174, 0.056954145 0.0022832006 0.018911287, -0.0071213543 -0.05655399 0.012888357, -0.0071213543 -0.056554362 0.018907785, 0.056948364 -0.0024275184 0.012891605, 0.056948274 -0.0024278462 0.018911168, -0.011767179 -0.055772975 0.012888402, 0.056553409 -0.0071219653 0.012891203, 0.056553334 -0.007122308 0.018910691, -0.011767238 -0.055773184 0.018907949, -0.01633276 -0.054610655 0.01288864, -0.016332701 -0.054610938 0.018908083, 0.055772156 -0.011767864 0.012891024, 0.055772066 -0.011768088 0.018910512, -0.020786434 -0.053075492 0.01288867, 0.054609895 -0.016333371 0.012890726, 0.05460991 -0.016333535 0.018910155, -0.020786494 -0.05307579 0.018908054, -0.025098249 -0.051177546 0.01288861, 0.053074792 -0.020787165 0.012890384, 0.053074718 -0.020787358 0.018909901, -0.025098503 -0.05117783 0.018908307, -0.029238746 -0.048930317 0.012888655, -0.02923882 -0.048930556 0.018908352, 0.051176891 -0.025098905 0.012890324, 0.051176861 -0.025099203 0.018909752, -0.033179641 -0.046348646 0.012889042, -0.033179432 -0.046348885 0.018908337, 0.048929438 -0.029239461 0.012889981, 0.048929423 -0.029239744 0.018909469, -0.036893621 -0.043450311 0.012889087, -0.036893651 -0.043450564 0.018908828, 0.046347782 -0.033180192 0.012889609, 0.046347782 -0.033180535 0.018909276, 0.036246166 0.042686641 0.012893945, 0.032597199 0.045534059 0.012894243, 0.028725684 0.048070416 0.012894392, 0.024657965 0.050278276 0.012894481, 0.020421803 0.052142993 0.012894422, 0.016046047 0.053651124 0.01289469, 0.011560649 0.054793119 0.01289472, 0.0069962442 0.055560693 0.01289475, 0.002384156 0.055948406 0.012894839, -0.0022442639 0.055954278 0.01289469, -0.0068572462 0.055577993 0.01289469, -0.011423528 0.054821789 0.012894601, -0.015911698 0.053691268 0.01289475, -0.020291194 0.052194029 0.01289463, -0.024532109 0.050340071 0.012894481, -0.028605372 0.04814209 0.012894288, -0.032483324 0.045615494 0.012894154, -0.036139265 0.0427773 0.012894079, -0.039548472 0.039646789 0.012893885, -0.042778105 -0.036139861 0.012889668, -0.042687491 0.036245316 0.012893736, -0.045616344 -0.032483757 0.012889758, -0.045534775 0.032596618 0.012893498, -0.04814291 -0.028606132 0.012889996, -0.048071086 0.028724924 0.012893185, -0.050340876 -0.024532661 0.012890249, -0.050279081 0.024657279 0.012893066, -0.052194625 -0.02029179 0.012890458, -0.052143663 0.020420954 0.012892842, -0.053692013 -0.015912399 0.012890697, -0.053651944 0.016045317 0.012892634, -0.054822475 -0.011424154 0.012891099, -0.055578753 -0.0068579763 0.012891427, -0.054793864 0.011559933 0.012892276, -0.055955052 -0.0022448599 0.012891442, -0.055561274 0.0069957078 0.012891993, -0.05594942 0.0023835599 0.012891874, 0.058869421 0.0034857988 0.021879151, 0.058959037 -0.0012625754 0.021878883, 0.058979452 -0.0012630969 0.021817818, 0.058889881 0.0034869164 0.021818146, 0.058836266 0.0034837723 0.021934554, 0.058926031 -0.0012618005 0.02193433, 0.058418185 0.0082143098 0.02181828, 0.058397785 0.0082115829 0.021879524, 0.058365166 0.0082069188 0.021934927, 0.057567641 0.012888387 0.021818429, 0.057547644 0.012883946 0.021879673, 0.057515442 0.012876749 0.021935105, 0.056343839 0.017478883 0.021818578, 0.056324214 0.017472729 0.021880001, 0.056292698 0.017463118 0.021935344, 0.054754525 0.021956101 0.021819055, 0.054735512 0.021948427 0.02188006, 0.0547048 0.021936104 0.021935672, 0.052810088 0.026290625 0.021819234, 0.052791834 0.026281536 0.021880686, 0.052762315 0.026266783 0.021935701, 0.050523326 0.030455083 0.021819353, 0.050505728 0.030444369 0.021880627, 0.050477326 0.030427307 0.021936119, 0.047908783 0.034421548 0.021819621, 0.047892138 0.034409687 0.021880865, 0.047865316 0.034390405 0.021936238, 0.044983551 0.038164973 0.021819979, 0.044967964 0.038151711 0.021881163, 0.044942647 0.038130328 0.021936536, -0.038278788 -0.044889048 0.021815345, -0.038265571 -0.044873461 0.021876499, -0.038244084 -0.044848219 0.021931976, -0.034542799 -0.047823712 0.021815315, -0.034530699 -0.047806874 0.021876246, -0.034511387 -0.047780275 0.021931589, -0.030582502 -0.050448045 0.021814913, -0.030571997 -0.050430581 0.02187635, -0.030554935 -0.050402358 0.021931544, -0.02642408 -0.052745521 0.021814883, -0.02641502 -0.052727088 0.021876037, -0.026400164 -0.05269745 0.021931514, -0.022094354 -0.054700628 0.021814674, -0.022086784 -0.054681733 0.021875978, -0.022074357 -0.054650873 0.02193138, -0.01762113 -0.056301206 0.021814674, -0.01761502 -0.056281671 0.021875679, -0.017605186 -0.056249857 0.021931157, -0.013033852 -0.057536453 0.021814421, -0.013029292 -0.057516456 0.021875814, -0.013021931 -0.057484254 0.021931157, -0.0083618164 -0.058398739 0.021814555, -0.0083590597 -0.058378428 0.021875739, -0.0083542168 -0.05834578 0.021931127, -0.0036358237 -0.058882102 0.021814406, -0.0036345124 -0.058861718 0.02187565, -0.0036324263 -0.058828637 0.021931052, 0.0011140555 -0.058983818 0.021814436, 0.0011137575 -0.058963239 0.02187553, 0.0011131316 -0.058930174 0.021931082, 0.0058564097 -0.058702767 0.021814451, 0.0058546066 -0.058682472 0.02187562, 0.0058513284 -0.05864951 0.021931052, 0.010561064 -0.058041319 0.021814585, 0.010557294 -0.058021054 0.021875784, 0.010551527 -0.057988673 0.021931067, 0.015197083 -0.057003319 0.021814644, 0.015191734 -0.056983396 0.021875754, 0.01518321 -0.056951508 0.021931291, 0.019734591 -0.055595621 0.021814868, 0.019727722 -0.055576146 0.021875888, 0.019716814 -0.055545002 0.021931291, 0.024144083 -0.053827241 0.021814853, 0.024135605 -0.053808555 0.021875903, 0.024122015 -0.05377841 0.02193141, 0.028396934 -0.051709801 0.021814778, 0.028387189 -0.05169186 0.021875978, 0.02837123 -0.051662877 0.021931425, 0.032465696 -0.049257159 0.021815047, 0.03245458 -0.049240083 0.02187629, 0.032436356 -0.049212396 0.021931678, 0.03632389 -0.046485126 0.02181524, 0.036311299 -0.046468899 0.021876454, 0.036291003 -0.046442837 0.021931812, 0.039946556 -0.043411613 0.021815389, 0.039932728 -0.043396533 0.021876499, 0.039910257 -0.043372035 0.021931872, 0.043310121 -0.040056407 0.021815613, 0.043294966 -0.04004252 0.021876782, 0.043270648 -0.0400199 0.021932125, 0.046392739 -0.036441416 0.021815747, 0.046376601 -0.036428869 0.021876901, 0.046350598 -0.036408305 0.021932408, 0.049174413 -0.032590136 0.02181603, 0.049157411 -0.032578841 0.02187717, 0.049129784 -0.032560706 0.021932527, 0.051637352 -0.028527558 0.021816164, 0.0516195 -0.028517723 0.021877334, 0.051590413 -0.028501689 0.021932989, 0.053765297 -0.024280056 0.021816447, 0.05374667 -0.024271473 0.021877408, 0.053716585 -0.024257943 0.021933004, 0.055544689 -0.019874975 0.02181673, 0.055525392 -0.019868076 0.021877989, 0.055494204 -0.019856855 0.021933213, 0.056963757 -0.015340969 0.021817058, 0.056943834 -0.015335754 0.021878257, 0.056911841 -0.015327096 0.021933481, 0.058013499 -0.010707751 0.021817192, 0.057993144 -0.010703936 0.021878287, 0.057960719 -0.010697961 0.021933734, 0.058686823 -0.006004855 0.021817431, 0.058666289 -0.0060026348 0.021878824, 0.058633268 -0.0059993267 0.021934107, 0.032464713 -0.049255699 0.021117464, 0.036322907 -0.046483874 0.021117747, 0.032450885 -0.049234703 0.021050125, 0.036307275 -0.046463847 0.021050364, 0.032428682 -0.049200758 0.020991012, 0.03628239 -0.046431944 0.020991266, 0.032399148 -0.049156144 0.020942986, 0.036249384 -0.046389759 0.02094321, 0.036167592 -0.046284959 0.020891517, 0.032326072 -0.04904522 0.020891398, 0.028396234 -0.05170849 0.021117508, 0.028384149 -0.051686257 0.02105014, 0.04478994 0.038000733 0.020896286, 0.028364331 -0.051650688 0.020990834, 0.028338715 -0.051603779 0.020942807, 0.028274655 -0.051487282 0.020891339, 0.024143323 -0.053825617 0.021117419, 0.024133042 -0.05380255 0.021049827, 0.024116546 -0.053765655 0.020990789, 0.024094522 -0.053716809 0.020942867, 0.024040014 -0.053595558 0.020891055, 0.019734085 -0.055594042 0.021117061, 0.019725546 -0.055569991 0.021049798, 0.019712001 -0.055531904 0.020990774, 0.01969406 -0.055481523 0.020942613, 0.01964967 -0.055356249 0.02089107, 0.015196681 -0.057001635 0.021117091, 0.01519011 -0.056977168 0.021049872, 0.015179768 -0.056938067 0.020990536, 0.015165955 -0.056886211 0.020942524, 0.015131757 -0.056757823 0.020890996, 0.010560766 -0.058039606 0.021117106, 0.010556266 -0.058014631 0.021049634, 0.010548949 -0.057974741 0.020990461, 0.010539412 -0.05792214 0.020942435, 0.010515556 -0.057791263 0.020890728, 0.0058564246 -0.058701038 0.021116987, 0.0058538318 -0.058676153 0.021049619, 0.0058498383 -0.058635607 0.020990655, 0.0058444291 -0.058582366 0.020942509, 0.0011091083 -0.058729798 0.020890832, 0.0058313906 -0.058450252 0.020890802, 0.0011139661 -0.058982104 0.021116957, 0.0011134446 -0.058956772 0.021049649, 0.0011128187 -0.058916315 0.020990402, 0.0011118054 -0.058862537 0.020942494, -0.0036200434 -0.058628738 0.020891085, -0.0036355704 -0.058880389 0.021116987, -0.0036341697 -0.058855176 0.021049589, -0.0036316067 -0.058814779 0.02099061, -0.0036282986 -0.058761254 0.020942464, -0.0083615184 -0.05839698 0.021117002, -0.0083579272 -0.058371976 0.021049693, -0.0083523095 -0.058331862 0.020990565, -0.0083446056 -0.058278814 0.020942509, -0.0083258003 -0.058147281 0.020890817, -0.013033465 -0.057534695 0.021117151, -0.013027877 -0.057510078 0.021049753, -0.013018996 -0.05747053 0.020990625, -0.013007134 -0.057418361 0.020942479, -0.01297763 -0.057288751 0.020890906, -0.017620653 -0.056299537 0.021117225, -0.017613187 -0.056275278 0.021049902, -0.017600983 -0.05623658 0.020990729, -0.017585099 -0.056185752 0.020942658, -0.017545372 -0.05605875 0.020890951, -0.022093698 -0.054699078 0.021117225, -0.022084281 -0.054675698 0.021049887, -0.022068948 -0.054638118 0.020990804, -0.022048995 -0.054588377 0.020942584, -0.021999151 -0.0544651 0.020891041, -0.026423365 -0.052743822 0.021117166, -0.026412085 -0.052721187 0.021050021, -0.02639395 -0.052684903 0.020990908, -0.026370019 -0.05263716 0.020942628, -0.026310369 -0.052518487 0.02089119, -0.038114011 -0.044695854 0.02089183, 0.044982284 0.038164034 0.021122426, -0.030581862 -0.05044657 0.021117523, -0.0305686 -0.050425008 0.021050125, 0.044962823 0.038147762 0.021055222, 0.044932067 0.038121358 0.020996064, -0.030547723 -0.050390393 0.020990983, 0.044891223 0.038086653 0.020947933, -0.030519933 -0.050344616 0.020943001, -0.03045097 -0.050230995 0.020891309, 0.047907457 0.034420684 0.021122217, -0.034541756 -0.047822192 0.021117568, 0.047886863 0.034405902 0.021054983, -0.034527034 -0.047801703 0.021050289, 0.047853947 0.034382209 0.020995736, -0.034503236 -0.047768965 0.020991102, 0.047810525 0.034350902 0.020947546, 0.047702476 0.034273431 0.020896107, -0.03447184 -0.047725514 0.020942986, -0.034394071 -0.047617704 0.020891458, 0.050521716 0.030454054 0.021122038, -0.038277701 -0.044887796 0.021117672, 0.050500214 0.030441016 0.021054536, -0.038261294 -0.044868529 0.021050394, 0.050465539 0.030420154 0.020995468, 0.050419509 0.030392483 0.020947546, -0.038235158 -0.044837594 0.020991385, 0.050305814 0.030323759 0.020895779, 0.052808702 0.02628997 0.021121681, -0.038200274 -0.044797063 0.020943224, 0.052785948 0.0262786 0.021054387, 0.052749708 0.026260734 0.020995259, 0.052701801 0.026236817 0.020947218, 0.052582845 0.026177526 0.0208956, 0.054753065 0.021955341 0.021121532, 0.054729566 0.021945879 0.021054208, 0.054691881 0.021930903 0.020995051, 0.05464232 0.021911055 0.020947009, 0.054518849 0.021861628 0.020895392, 0.056342259 0.017478377 0.021121234, 0.056318074 0.017470941 0.02105391, 0.056279391 0.017458871 0.020994872, 0.056228191 0.017443135 0.020946711, 0.056101248 0.017403677 0.020895243, 0.057565928 0.012888119 0.021120906, 0.057541236 0.012882575 0.021053672, 0.057501733 0.012873635 0.020994425, 0.057449654 0.012862027 0.020946443, 0.05731988 0.012833029 0.020894796, 0.05841668 0.008214131 0.021120608, 0.058391467 0.0082105547 0.021053433, 0.058351249 0.0082048625 0.020994186, 0.058298424 0.0081975013 0.020946324, 0.058166787 0.0081788749 0.020894676, 0.058888182 0.003486976 0.021120593, 0.058862865 0.0034854263 0.021053225, 0.058822393 0.0034830272 0.020994112, 0.058769017 0.0034797341 0.020945951, 0.058636323 0.0034719706 0.020894483, 0.058977813 -0.0012629628 0.02112022, 0.058952555 -0.0012622923 0.021052748, 0.058911964 -0.0012614876 0.020993754, 0.058858514 -0.0012603104 0.020945743, 0.05872561 -0.0012574792 0.020894244, 0.058685079 -0.0060045421 0.021119893, 0.058659956 -0.0060020238 0.021052614, 0.058619559 -0.0059979558 0.020993516, 0.058566391 -0.0059924722 0.020945385, 0.058434278 -0.0059789866 0.020893767, 0.058011696 -0.010707363 0.021119773, 0.057986706 -0.010702863 0.021052256, 0.057946905 -0.010695264 0.020993143, 0.057894379 -0.010685697 0.020945087, 0.057763577 -0.010661513 0.020893514, 0.056962222 -0.015340656 0.021119371, 0.056937635 -0.015333936 0.021052152, 0.056898624 -0.015323445 0.020992979, 0.056846902 -0.015309498 0.020944849, 0.056718543 -0.015275061 0.02089332, 0.055543005 -0.019874543 0.021119311, 0.055519432 -0.019866064 0.02105166, 0.055481091 -0.019852206 0.020992696, 0.05543071 -0.019834295 0.020944655, 0.055305675 -0.019789353 0.020893216, 0.053763807 -0.024279267 0.021118984, 0.05374074 -0.024268955 0.021051645, 0.053703666 -0.024252132 0.020992547, 0.053655013 -0.024230242 0.020944357, 0.053533986 -0.024175584 0.020892814, 0.051635876 -0.028526753 0.021118566, 0.051613674 -0.028514504 0.021051273, 0.051578403 -0.028494984 0.020992175, 0.05153133 -0.028469041 0.020944133, 0.05141513 -0.028404757 0.020892546, 0.049173146 -0.032589316 0.021118462, 0.049152032 -0.032575309 0.021051034, 0.049118325 -0.032552928 0.020991892, 0.049073637 -0.032523334 0.02094388, 0.048962787 -0.032449827 0.020892218, 0.046391532 -0.036440402 0.021118194, 0.04637152 -0.036424786 0.021050885, 0.046339631 -0.036399662 0.020991758, 0.04629764 -0.036366731 0.020943835, 0.046193004 -0.036284551 0.020892248, 0.043308973 -0.040055305 0.021118119, 0.043290213 -0.040038064 0.021050766, 0.043260559 -0.040010467 0.020991534, 0.04322128 -0.039974123 0.020943493, 0.043123707 -0.039883867 0.020892009, 0.039945319 -0.043410271 0.021118015, 0.039928257 -0.04339169 0.021050528, 0.039900824 -0.043361723 0.020991415, 0.039864749 -0.043322504 0.020943522, 0.039774641 -0.043224543 0.020891786, 0.034585595 -0.029768571 0.027680233, 0.032315359 -0.021253675 0.02892448, 0.03458564 -0.02976872 0.026390076, 0.030037314 -0.012709454 0.029786482, 0.0276272 -0.0036692023 0.030318752, 0.025009096 0.006150648 0.030516684, 0.02250351 0.01554881 0.030370206, 0.015176207 0.043032661 0.02639389, 0.017814666 0.033135802 0.029092178, 0.016489416 0.03810674 0.028452471, 0.015176147 0.043032646 0.027684167, -0.043072015 -0.015070006 0.027681008, -0.034562677 -0.017361477 0.028924972, -0.043072119 -0.015069857 0.026390642, -0.026023954 -0.019661024 0.029786021, -0.016989902 -0.022093832 0.030317605, -0.0071764737 -0.024736434 0.030514941, 0.0022151321 -0.027265728 0.030367941, 0.029680535 -0.034661561 0.026389822, 0.019790411 -0.031998366 0.029088736, 0.024757922 -0.033335879 0.028448388, 0.02968049 -0.034661591 0.02767995, 0.0084862709 0.044834167 0.027684435, 0.0022472441 0.038610384 0.028927982, 0.0084863305 0.044834271 0.026394144, -0.004013747 0.032365322 0.029788837, -0.010637462 0.025757924 0.030320466, -0.017832726 0.018580645 0.03051734, -0.02471897 0.011711761 0.030370012, -0.037605405 -0.0011423826 0.029090554, -0.041247457 -0.0047754198 0.028449893, -0.038455278 -0.01001367 0.026391223, -0.038468212 -0.0095494539 0.026391059, -0.038373664 -0.0090948045 0.026391134, -0.038176954 -0.0086742342 0.026391223, -0.037888482 -0.0083101988 0.026391193, 0.027061716 -0.028687328 0.026389971, 0.026599169 -0.028727248 0.026389986, 0.026139721 -0.028659523 0.026390001, 0.027502775 -0.028541908 0.026390016, 0.027898297 -0.028298438 0.026390046, 0.030599222 -0.034797117 0.026389867, 0.031524569 -0.03471747 0.026389822, 0.032406539 -0.034426451 0.026389733, 0.033197433 -0.033939868 0.026389614, 0.033855155 -0.033283845 0.026389778, 0.02822727 -0.027970627 0.026390091, 0.034343705 -0.032494202 0.026389688, 0.03463693 -0.031612843 0.026389807, 0.034718975 -0.03068772 0.026389748, 0.028592393 -0.02621299 0.026390046, 0.028471425 -0.027575776 0.026390046, 0.010478884 0.038337067 0.026393801, 0.010882169 0.038142249 0.026393622, 0.028617889 -0.027135029 0.026390076, 0.02865909 -0.026672423 0.02639015, 0.014834315 0.043896183 0.026394039, 0.014302552 0.044657633 0.026394159, 0.0084036291 0.037866056 0.026393831, 0.0087541044 0.038144603 0.026393846, 0.0091578662 0.038338646 0.026393712, 0.0095945597 0.038437575 0.026393965, 0.010042518 0.038437158 0.026393861, 0.013609499 0.045276016 0.026394069, 0.0092155337 0.045409366 0.026394174, 0.012792647 0.045717746 0.026394248, 0.010057688 0.045800909 0.026394114, -0.036996022 -0.011657417 0.026391044, 0.011895895 0.045959264 0.026394293, 0.010967284 0.045987472 0.026394293, -0.037427351 -0.011485457 0.02639097, -0.037807524 -0.011218578 0.026391089, -0.038115725 -0.010871336 0.026391104, -0.038335577 -0.010462284 0.026390985, -0.044330359 -0.014481336 0.026390865, -0.043726906 -0.014830634 0.026390925, 0.026558742 -0.018585548 0.029766947, 0.028592244 -0.026213109 0.028875872, 0.024522483 -0.01094839 0.030355528, 0.021869689 -0.00099775195 0.030731887, 0.018885404 0.01019603 0.030758724, 0.014028668 0.028412044 0.029856443, 0.016314238 0.019839853 0.030458421, -0.029373556 -0.013710395 0.029767051, -0.036996156 -0.011657611 0.028876647, -0.02174142 -0.015765563 0.030355364, -0.011797518 -0.018443421 0.030731052, -0.00061134994 -0.02145575 0.030756921, 0.017592549 -0.026357889 0.029853255, 0.0090258867 -0.02405104 0.030456036, 0.026139647 -0.028659612 0.028875619, 0.0028147101 0.032290876 0.029769897, 0.0084034801 0.037865818 0.028879419, -0.0027813017 0.026708841 0.030357599, -0.010072321 0.019436017 0.030733153, -0.018274322 0.011254758 0.030758724, -0.03162162 -0.0020592362 0.029854819, -0.025340408 0.0042061806 0.030457526, -0.037888423 -0.0083102584 0.028876811, 0.0089107901 -0.043826014 0.027938902, 0.009394452 -0.043906569 0.02789253, 0.0089108646 -0.043826088 0.025596023, 0.009498179 -0.043911204 0.025596216, 0.0098794848 -0.043891549 0.027868971, 0.010089248 -0.043855608 0.025596127, 0.010354236 -0.04378292 0.027868778, 0.010650396 -0.043662116 0.025596187, 0.010799199 -0.043583855 0.027892113, 0.011150211 -0.043341815 0.025596187, 0.011195809 -0.043303385 0.02793771, 0.011560306 -0.042912751 0.025596157, 0.011529982 -0.042952552 0.028003633, 0.011788949 -0.042545959 0.02808705, 0.011857808 -0.042399079 0.025596365, 0.011964992 -0.042097896 0.028184772, 0.012025729 -0.041829705 0.02559641, 0.012051627 -0.041627645 0.028292239, 0.012054756 -0.041236833 0.025596261, 0.012047619 -0.041154265 0.028404742, 0.011943176 -0.040653974 0.025596291, 0.011946097 -0.0406636 0.028526172, 0.011759833 -0.040223032 0.028639942, 0.011697203 -0.040113658 0.025596306, 0.011560678 -0.039911717 0.028723374, -0.029713154 -0.033424973 0.027939394, -0.011474848 -0.038336456 0.028787717, -0.029713228 -0.033425003 0.025596738, -0.0029668808 -0.040627688 0.028666332, 0.0029963255 -0.042233631 0.028384537, -0.028413057 -0.028597102 0.029007584, -0.028909862 -0.028515831 0.028941572, -0.02940625 -0.0285348 0.028857574, -0.029889926 -0.028651699 0.028758407, -0.030336469 -0.028859735 0.028648987, -0.0307336 -0.029151216 0.028532282, -0.031077787 -0.029530749 0.028408095, -0.031327665 -0.029951736 0.028291553, -0.031491965 -0.030419454 0.02818048, -0.031561121 -0.030910239 0.028080598, -0.031531289 -0.031408682 0.02799587, -0.031402916 -0.031891853 0.027930379, -0.031180143 -0.032340705 0.027886897, -0.0308709 -0.032737762 0.027867615, -0.030499652 -0.033057109 0.025596708, -0.030490413 -0.033063501 0.027873069, -0.030122504 -0.033275381 0.025596783, -0.030117154 -0.033278018 0.027897641, -0.0082992613 -0.034013703 0.029807389, -0.017122135 -0.031637609 0.029674143, -0.022804439 -0.030107528 0.029411495, 0.0093547553 -0.042177483 0.023889408, 0.0095410198 -0.042204663 0.023889378, 0.0097285211 -0.04218699 0.023889318, 0.0099065304 -0.042125404 0.023889288, 0.010065034 -0.042023972 0.023889333, 0.010289282 -0.04172495 0.023889273, 0.010195136 -0.04188785 0.023889467, 0.010342687 -0.041544423 0.023889422, 0.010351852 -0.04135634 0.023889363, 0.010316476 -0.041171387 0.023889318, 0.010238498 -0.041000038 0.023889378, -0.029269308 -0.031776488 0.023889929, -0.029601544 -0.03159298 0.02388978, -0.029446512 -0.031704724 0.023889929, -0.029725134 -0.031447157 0.023889989, -0.029810488 -0.031276092 0.023890063, -0.029798329 -0.030713871 0.023890078, -0.029848009 -0.030898377 0.023889959, -0.029852092 -0.031089529 0.023889959, -0.029416487 -0.030301034 0.023890093, -0.029576167 -0.030406222 0.023889959, -0.029705986 -0.030546561 0.023890063, -0.028857023 -0.030245245 0.023889959, -0.029236436 -0.030237123 0.023890108, -0.029046237 -0.030218005 0.023889974, 0.033497676 0.029627934 0.027942866, 0.033348635 0.030039251 0.027900457, 0.033497781 0.029627919 0.025600135, 0.033349246 0.030037507 0.025600433, 0.033131719 0.030415386 0.027876258, 0.033131689 0.030415207 0.025600374, 0.043802038 -0.0090221316 0.02794084, 0.038936481 0.009228304 0.028790489, 0.043802068 -0.0090220571 0.025598034, 0.036666468 0.017742336 0.028669462, 0.035075575 0.023709401 0.028388053, 0.038970873 -0.010310382 0.029008582, 0.039148808 -0.01078102 0.028942421, 0.039413512 -0.01120162 0.028858587, 0.039756447 -0.011561915 0.028759509, 0.040082633 -0.011799201 0.025598004, 0.040159911 -0.01184471 0.028649896, 0.040610835 -0.012042955 0.028533101, 0.040622354 -0.012046352 0.025597975, 0.041111678 -0.012150928 0.02840896, 0.041204989 -0.012159497 0.025598049, 0.041601509 -0.012157023 0.028292611, 0.041798055 -0.012131989 0.025597885, 0.042088628 -0.0120655 0.028181508, 0.042367801 -0.011965483 0.02559799, 0.042548254 -0.011879787 0.028081641, 0.04288213 -0.011669427 0.025598079, 0.042964891 -0.011604801 0.027997077, 0.043312117 -0.011260211 0.025598064, 0.043319076 -0.011251971 0.02793166, 0.043596596 -0.010834605 0.027888164, 0.043633863 -0.010761216 0.025598049, 0.04378581 -0.010368422 0.027868867, 0.043828771 -0.010200679 0.025598109, 0.043877676 -0.0098759979 0.027874514, 0.043885738 -0.0096097589 0.025598109, 0.043876708 -0.0094452053 0.027898818, 0.033604771 0.009816885 0.029809758, 0.035958558 0.0009881705 0.02967605, 0.037474543 -0.0046979338 0.029413089, 0.040948465 -0.010326728 0.023891091, 0.041119292 -0.010412425 0.023891076, 0.041305721 -0.010454655 0.023890972, 0.042152658 -0.009461686 0.023891151, 0.040620402 -0.0098702163 0.023891211, 0.04069145 -0.010047585 0.023891047, 0.040802985 -0.010202691 0.023891151, 0.041496977 -0.010451168 0.023891062, 0.041681632 -0.010401785 0.023891196, 0.041849166 -0.010309771 0.02389124, 0.041989803 -0.010180369 0.023891091, 0.042095318 -0.010021016 0.02389127, 0.042159811 -0.0098411888 0.023891151, 0.042179242 -0.0096508861 0.0238913, 0.031848267 0.029188395 0.023893356, 0.031801164 0.029318258 0.023893327, 0.031732202 0.029438019 0.023893356, -0.042408749 0.014193699 0.027942151, -0.042721763 0.013813362 0.027895436, -0.042952105 0.013382524 0.027872041, -0.043094903 0.012912706 0.027872235, -0.043143153 0.01242432 0.027896136, -0.043095633 0.011938676 0.027942702, -0.042954415 0.011470661 0.028009817, -0.042727128 0.011042684 0.028094471, -0.042421445 0.010666624 0.028193042, -0.042051509 0.01035817 0.028301924, -0.04197593 0.010308653 0.025599182, -0.04163143 0.010127351 0.028416231, -0.041471824 0.010065064 0.025599286, -0.041158766 0.0099774003 0.028536201, -0.040926233 0.0099399686 0.025599226, -0.040680766 0.0099240392 0.028650209, -0.040366277 0.0099392235 0.025599182, -0.040199652 0.0099633932 0.028757676, -0.039820373 0.010063052 0.025599211, -0.039735004 0.010094553 0.028854325, -0.039315745 0.010305449 0.025599197, -0.039301381 0.010314345 0.028937325, -0.039078623 0.010473728 0.028976887, -0.038877577 0.010653839 0.025599226, -0.038877651 0.010653749 0.029009864, -0.027461722 0.02910316 0.028791577, -0.033700019 0.022880688 0.02866973, -0.038072124 0.018519536 0.028387904, -0.010557979 0.038902581 0.029011473, -0.010239154 0.039292037 0.028945386, -0.010558009 0.038902834 0.025600865, -0.010208368 0.039340049 0.025600836, -0.010007322 0.039731547 0.028861374, -0.0099647939 0.039844036 0.025600776, -0.0098669827 0.040208846 0.028762326, -0.0098396242 0.040389702 0.02560097, -0.0098237693 0.040699527 0.028652683, -0.0098388791 0.040949479 0.025600985, -0.0098776817 0.041189283 0.028536126, -0.0099628568 0.041495427 0.02560094, -0.010034144 0.041677058 0.028412253, -0.01020506 0.042000204 0.025601, -0.010256618 0.042079046 0.028302595, -0.025305837 0.024191841 0.029810578, -0.018836543 0.030644566 0.02967757, -0.014670402 0.034800395 0.029415146, -0.040083259 0.011862665 0.023892358, -0.041132867 0.011800468 0.023892328, -0.040969491 0.011701405 0.023892283, -0.040787086 0.011644378 0.023892373, -0.040596381 0.011632472 0.023892328, -0.040408254 0.011666581 0.023892462, -0.040233865 0.011745036 0.023892269, -0.041267872 0.01193583 0.023892298, -0.041366681 0.012099519 0.023892313, -0.041423321 0.012282044 0.023892283, -0.041434631 0.012472883 0.023892462, -0.041399792 0.012660861 0.023892254, -0.041321322 0.012835145 0.023892313, -0.041203082 0.012985364 0.023892507, -0.011763632 0.040111616 0.023893908, -0.01157552 0.040410072 0.023893997, -0.011652648 0.040250167 0.023893893, -0.011535794 0.040583029 0.023894012, -0.011535525 0.040760741 0.023894101, -0.011574864 0.040933847 0.023893952, -0.011651605 0.041093886 0.023894057, 0.019593433 -0.022442102 0.031050935, 0.018187359 -0.019059852 0.031388894, 0.017326534 -0.019845903 0.031388789, 0.020566881 -0.021553323 0.031051114, 0.025224641 -0.026434138 0.030198216, 0.023864537 -0.022890463 0.030668527, 0.022828832 -0.023923442 0.030668527, 0.018906668 -0.012593359 0.031674162, 0.019444987 -0.011744797 0.03167437, 0.016984463 -0.0093034506 0.031873181, 0.022808 -0.026692629 0.030400053, 0.026542321 -0.027701125 0.02992323, 0.021926224 -0.014604375 0.031389251, 0.022550642 -0.013620228 0.031389371, 0.026756197 -0.027731776 0.029896513, 0.024892151 -0.016367733 0.031051278, 0.026971623 -0.027709752 0.029875591, 0.027120009 -0.027661979 0.029864743, 0.027263746 -0.027585149 0.029857472, 0.027391449 -0.027482986 0.029854596, 0.026369035 -0.02529259 0.030198157, 0.0183312 -0.013417378 0.031674027, 0.01548776 -0.01162602 0.031873181, 0.02125892 -0.015560001 0.031389058, 0.016431868 -0.020592988 0.031388834, 0.014940485 -0.017112941 0.031674027, 0.014169008 -0.017756984 0.031673819, 0.021748215 -0.024909928 0.030668497, 0.016773894 0.014027283 0.031731695, 0.017719701 -0.014215067 0.031674027, 0.024040163 -0.017595604 0.031051219, 0.025984958 -0.020451397 0.030668795, 0.025447041 -0.018440783 0.03086783, 0.015516669 0.011583865 0.031874225, 0.013369724 -0.018366471 0.031673819, 0.011585444 -0.015518755 0.031872883, 0.018581748 -0.023286715 0.03105095, 0.017339155 0.011898801 0.031783238, 0.020549893 -0.016485155 0.031389132, 0.017007589 0.0092575699 0.031874225, 0.015504941 -0.021299466 0.031388804, 0.017073885 -0.014984965 0.031673923, 0.013675749 -0.013711974 0.031873032, 0.017908975 0.0097545236 0.031819656, 0.018479332 0.0076107979 0.031841934, 0.020625144 -0.025847524 0.030668572, 0.019070059 -0.025682464 0.030800983, 0.020911798 -0.026180267 0.030612558, 0.02323845 -0.01864177 0.031051219, 0.012544304 -0.018939763 0.031673789, 0.0092592984 -0.017009422 0.03187269, 0.026540577 -0.022528499 0.030440599, 0.018152267 0.0067428052 0.031874046, 0.019800574 -0.017378047 0.031389102, 0.019049957 0.0054682791 0.031850368, 0.017533556 -0.024085864 0.031050891, 0.01718244 -0.025172547 0.030975774, 0.01892741 0.0040910542 0.031874046, 0.014547706 -0.02196458 0.031388849, 0.015329644 -0.024671495 0.031129435, 0.019621342 0.003326416 0.031846091, 0.01931712 0.0013556629 0.031873867, 0.011694357 -0.019476339 0.0316737, 0.016394243 -0.015725568 0.031673953, 0.02239114 -0.019651353 0.031051129, 0.020193249 0.0011849552 0.031828433, 0.01356189 -0.02258648 0.031388775, 0.013451874 -0.024163723 0.031268016, 0.020766035 -0.00095716119 0.031796724, 0.010821462 -0.019974455 0.031673744, 0.011588648 -0.023659945 0.03138876, 0.019012675 -0.018236816 0.031388924, 0.019313604 -0.0014072955 0.031873733, 0.0099273175 -0.020433545 0.031673655, 0.021388754 -0.0032845736 0.031745374, 0.0090138018 -0.020852759 0.031673729, 0.0067445189 -0.0181541 0.031872645, 0.0091465116 -0.022999227 0.0315229, 0.018917084 -0.0041417331 0.031873509, 0.0080827475 -0.021230996 0.031673536, 0.02201207 -0.0056126118 0.031674579, 0.024853647 -0.021812409 0.03066881, 0.007135734 -0.021567687 0.031673595, 0.0067097843 -0.022340029 0.031630918, 0.027076781 -0.024533466 0.030198291, 0.015682682 -0.01643534 0.031673923, 0.018135399 -0.0067916811 0.031873196, 0.0061749071 -0.021862358 0.03167364, 0.0040925741 -0.018929139 0.031872645, 0.0042519271 -0.02167511 0.03171578, 0.022635132 -0.0079389662 0.031582996, 0.0018282086 -0.021019951 0.031777367, 0.021500155 -0.020622551 0.031051144, 0.001357168 -0.019318789 0.0318726, -0.00042693317 -0.020410687 0.031816885, -0.0014058203 -0.019315436 0.031872585, -0.0026816279 -0.019802272 0.031840637, -0.0041401535 -0.018918812 0.03187263, -0.004935503 -0.019194975 0.031849235, -0.0067901015 -0.018137202 0.031872615, -0.0071896613 -0.018588096 0.031843394, -0.0093019754 -0.016986176 0.031872705, -0.0094400197 -0.017983273 0.031823009, -0.011691824 -0.017378688 0.031786561, -0.011624455 -0.015489638 0.031872705, -0.013946339 -0.016773969 0.031733602, 0.027493343 -0.02736555 0.029856533, 0.027569771 -0.027239576 0.029861897, 0.027624443 -0.027102306 0.029870912, 0.027655616 -0.026957825 0.029883444, 0.027662396 -0.026810557 0.029898539, 0.027653217 -0.026711285 0.02991043, 0.027632788 -0.026613265 0.02992335, 0.020828262 -0.0090678781 0.031674266, 0.023257941 -0.010264307 0.031468824, 0.020406798 -0.009980306 0.03167437, 0.023798943 -0.012283981 0.031350166, 0.019945547 -0.010873139 0.031674355, 0.024352372 -0.014350995 0.031208977, 0.011000693 0.038061231 0.02882041, 0.010745406 0.038220778 0.028814495, 0.010356635 0.038375422 0.028811187, 0.0099462867 0.038445503 0.02881372, 0.0095221102 0.038428158 0.028822526, 0.0091127753 0.03832227 0.028836668, 0.0087357759 0.038133159 0.028855756, -0.038075492 -0.0085256994 0.028860733, -0.038223073 -0.0087529868 0.028846905, -0.038356215 -0.0090445876 0.028833002, -0.038440257 -0.0093498528 0.028822154, -0.038475126 -0.0096691102 0.028813988, -0.038459122 -0.0099851787 0.028809622, -0.038394824 -0.01029034 0.028808385, -0.038269341 -0.010611296 0.028811157, -0.038042128 -0.010969952 0.028819725, -0.037746236 -0.011271372 0.028833866, -0.037393659 -0.011503309 0.028852969, 0.026419729 -0.028713882 0.028859511, 0.026690423 -0.028727978 0.028845668, 0.027009353 -0.028697595 0.028831944, 0.02731593 -0.028617665 0.028821081, 0.02760984 -0.028488323 0.0288129, 0.027875483 -0.028316334 0.02880843, 0.028107569 -0.02810806 0.028807372, 0.028322622 -0.027838901 0.028810143, 0.028519839 -0.027462944 0.028818905, 0.028632715 -0.027055725 0.028832972, 0.02865757 -0.026634514 0.028852135, 0.03471373 -0.030565143 0.027527124, 0.034681216 -0.031358913 0.027400628, 0.034432769 -0.032288834 0.027286604, 0.033967897 -0.033134609 0.027222663, 0.03331323 -0.033844933 0.027213246, 0.032505602 -0.034378767 0.027258545, 0.031594217 -0.034702525 0.027356401, 0.030634105 -0.03479816 0.027499661, 0.0091120601 0.04534331 0.027531654, 0.0098155737 0.045712158 0.027405098, 0.010745198 0.045962095 0.027290806, 0.011710018 0.045982376 0.027227178, 0.012652665 0.045770466 0.027217597, 0.013518721 0.045337886 0.027263016, 0.014254898 0.044710413 0.027360722, 0.014817804 0.043926835 0.027504265, -0.04373911 -0.014824912 0.027545094, -0.044336498 -0.014476866 0.027430952, 0.016568378 -0.0090755373 0.031840295, 0.015297264 -0.011482939 0.031870797, 0.016775638 -0.0091890842 0.031870902, 0.015108347 -0.011341199 0.031840205, 0.017912194 -0.0067082345 0.031870857, 0.017691091 -0.0066254735 0.031840548, 0.018684372 -0.0040908009 0.031871244, 0.018453494 -0.0040402859 0.031840697, 0.019076139 -0.0013900846 0.031871155, 0.018840492 -0.0013729483 0.031840578, 0.019079626 0.0013388395 0.031871423, -0.011481375 -0.015299037 0.031870425, 0.018843964 0.0013222843 0.031840906, -0.011339635 -0.015110001 0.031839892, 0.01869446 0.0040403754 0.031871647, -0.0091874748 -0.016777307 0.031870335, 0.018463716 0.0039907247 0.031840995, -0.0090740621 -0.016570151 0.031839982, 0.017929077 0.006659925 0.031871721, -0.0067064315 -0.017914161 0.031870246, 0.017707601 0.0065775365 0.031841204, -0.006623596 -0.017692938 0.031839773, 0.016798511 0.0091436952 0.03187184, -0.0040891767 -0.018686339 0.03187032, 0.016590983 0.0090307593 0.031841293, -0.0040385872 -0.018455327 0.031839803, 0.015325889 0.011441365 0.031871989, -0.0013884008 -0.019077897 0.031870291, 0.015136689 0.011299923 0.031841353, -0.0013712794 -0.018842399 0.031839818, 0.001340583 -0.019081175 0.031870306, 0.0013239235 -0.018845811 0.031839684, 0.0040422082 -0.018696383 0.03187032, 0.0039922893 -0.018465534 0.031839713, 0.00666143 -0.017930746 0.03187041, 0.0065793246 -0.01770927 0.031839818, 0.0091453493 -0.016800299 0.03187041, 0.009032324 -0.016592801 0.031839833, 0.011442944 -0.015327781 0.031870514, 0.011301562 -0.015138462 0.031840011, 0.01350762 -0.013543308 0.031870693, 0.013340831 -0.013375908 0.031840146, 0.012589604 0.0064465255 0.028691441, 0.013341278 0.0062441528 0.030311465, 0.012013778 0.0066015273 0.02889204, 0.012960449 0.006346643 0.028617904, 0.013341263 0.0062441081 0.028591901, 0.0090167075 0.0074087679 0.029644668, 0.004656285 0.0085827112 0.029310405, -0.0040763021 0.010934472 0.029644877, 0.00028398633 0.0097602904 0.02931045, -0.008400768 0.012098908 0.03031154, -0.00071063638 -0.014128715 0.028690279, -0.00028841197 -0.013707429 0.028891087, -0.00098238885 -0.014400035 0.028616533, 0.0019090772 -0.011515424 0.029643625, 0.005106166 -0.008326441 0.029309511, 0.011509031 -0.0019397289 0.029644132, 0.013706416 0.00025244057 0.028891698, 0.0083120167 -0.0051287711 0.029309765, 0.014347002 0.00089134276 0.028628334, 0.014022589 0.00056751072 0.028732032, -0.011879161 0.0076772124 0.028691545, -0.012079626 0.0084293187 0.030311346, -0.011725411 0.0071009248 0.028892085, -0.011978075 0.0080484301 0.028618023, -0.01207979 0.0084294379 0.02859211, -0.010925978 0.0041019469 0.029644325, -0.0097625852 -0.00026130676 0.029309928, -0.0074330121 -0.0089997202 0.029643655, -0.0085961968 -0.0046365857 0.02930969, -0.0062791258 -0.013327271 0.030310228, 0.0093726069 0.0024972558 0.028891861, 0.01294522 6.9618225e-05 0.028891683, -9.6842647e-05 -0.012226701 0.028890997, -0.00010772049 -0.012978092 0.028891057, -0.01158917 0.0069460124 0.0288921, -0.01165843 0.0070225298 0.028892145, 0.012162313 7.1525574e-05 0.028891787, -0.00025609136 -0.011492133 0.028891206, 0.0092621148 0.0032723546 0.028891876, 0.011401802 0.00025768578 0.028891653, -0.00057737529 -0.010813013 0.028890997, 0.009337157 0.0040516108 0.028891891, 0.010706589 0.00061774254 0.028891698, 0.0095939189 0.0047913939 0.02889204, 0.010115787 0.0011315942 0.028891698, 0.0096625537 0.0017699003 0.028891891, 0.010017648 0.0054496378 0.028891936, 0.010584474 0.0059897155 0.028892145, 0.011262536 0.0063811988 0.028892085, 0.0099974871 0.0017891228 0.028591752, 0.0099918395 0.0017986596 0.026891604, 0.009702459 0.0024374127 0.028591782, 0.0096959174 0.0024587214 0.026891708, 0.0095685273 0.0031369925 0.028591931, 0.0095663965 0.0031700581 0.026891693, 0.0096032917 0.0038485229 0.028591871, 0.0096110851 0.0038918853 0.026891783, 0.0098048598 0.0045316815 0.028591931, 0.0098271072 0.0045819879 0.026891828, 0.010161921 0.0051482022 0.028591812, 0.010201842 0.0052005351 0.026891813, 0.010654032 0.0056629777 0.028591871, 0.010713965 0.0057112873 0.026891783, 0.01125367 0.0060474575 0.028592214, 0.011333495 0.0060846508 0.026891872, 0.011927187 0.0062795281 0.028591976, 0.012024164 0.0062988698 0.026891813, 0.012636319 0.0063462853 0.028592065, 0.013834283 0.0060635805 0.030415326, 0.012745947 0.0063418001 0.026891798, 0.013457179 0.0062104315 0.026891783, 0.014116377 0.0059128702 0.026891842, 0.014289111 0.0057996958 0.030505344, -0.0058375746 -0.01427564 0.030504063, -0.0059497207 -0.01410304 0.02689077, -0.0061006546 -0.013819456 0.030414, -0.0062458515 -0.013443053 0.026890859, -0.0063752234 -0.012731627 0.026890934, -0.0063306242 -0.01200965 0.026890814, -0.006114468 -0.011319667 0.026890919, -0.0057397485 -0.010701016 0.026891142, -0.0052276403 -0.010190383 0.026890919, -0.0046082884 -0.0098170787 0.026891112, -0.00391756 -0.0096027106 0.026890993, -0.0031954646 -0.009559989 0.026891112, -0.0024843365 -0.0096911788 0.026890889, -0.0018251538 -0.0099889189 0.026890993, -0.011640504 0.0074846596 0.028591976, -0.011750162 0.0076535344 0.026892036, -0.011901498 0.0079378486 0.028592259, -0.012179792 0.0091160089 0.030446172, -0.012046203 0.0083134919 0.026892185, -0.012175694 0.009024933 0.026892051, -0.01213102 0.0097468793 0.026892215, -0.012118697 0.0098100901 0.030555129, -0.011914998 0.010437131 0.026892215, -0.011899233 0.010471627 0.03063108, -0.011540145 0.011055455 0.026892066, -0.01153256 0.011064976 0.030670479, -0.011028096 0.011566445 0.026892394, -0.010443524 0.011923611 0.030631363, -0.010408804 0.011939839 0.026892304, -0.0097811967 0.012141541 0.030555204, -0.0097180158 0.012154058 0.026892349, -0.0089960098 0.012196779 0.026892319, -0.0082848668 0.012065411 0.026892275, -0.0076257288 0.011767849 0.026892215, -0.010754257 0.0094928294 0.02689226, -0.010639042 0.0098608136 0.026892275, -0.010439187 0.010190845 0.026892111, -0.0083513856 0.010570601 0.026892111, -0.010166049 0.010463089 0.026892126, -0.0087030083 0.010729358 0.0268922, -0.0098357648 0.010662124 0.0268922, -0.0090823174 0.010799438 0.026892304, -0.010551363 0.0083767176 0.026892081, -0.0094673485 0.010776535 0.026892215, -0.010709167 0.0087283701 0.02689223, -0.010778278 0.0091079473 0.026892141, 0.01110293 0.0040058494 0.026891813, 0.011302933 0.0043359697 0.026891634, 0.011575997 0.0046082884 0.026892051, 0.013390675 0.0047157109 0.026891798, 0.011906311 0.0048073083 0.026891664, 0.012274697 0.0049216598 0.026891738, 0.013039023 0.0048744231 0.026891708, 0.012659818 0.0049442798 0.026891813, 0.011190861 0.0025214255 0.026891619, 0.011033148 0.002873376 0.026891693, 0.010963917 0.0032529235 0.026891708, 0.010987669 0.003637746 0.026891828, -0.0049538761 -0.012263954 0.026890948, -0.0048386157 -0.01189582 0.026890799, -0.0046387464 -0.011565909 0.026890904, -0.004365623 -0.011293575 0.026890889, -0.0040353239 -0.011094376 0.026891083, -0.0025509894 -0.011186048 0.026890948, -0.0036669821 -0.010980085 0.026891097, -0.0047506839 -0.013380364 0.026890755, -0.0029023737 -0.011027366 0.026890963, -0.0032818019 -0.010957211 0.026890889, -0.0049085319 -0.013028532 0.026890785, -0.0049775988 -0.012648836 0.026890904, -0.038981006 0.010757551 0.025245771, -0.011513889 0.039861158 0.024040282, -0.039833635 0.011612445 0.024038792, -0.010661274 0.039006546 0.02524747, -0.011353761 0.040061861 0.024040058, -0.010332257 0.039417997 0.02524747, -0.011241823 0.040292948 0.024040148, -0.010103106 0.039892465 0.02524738, -0.011184454 0.040543109 0.024040356, -0.0099850893 0.040406376 0.025247529, -0.011184037 0.040799841 0.024040312, -0.0099843144 0.040933222 0.025247544, -0.01124087 0.041050062 0.024040252, -0.01010108 0.041447386 0.025247544, -0.010329217 0.04192245 0.025247455, -0.011352003 0.04128167 0.024040297, -0.04145281 0.013235793 0.024038747, -0.041623563 0.013018295 0.024038643, -0.041737288 0.012766466 0.024038762, -0.041787565 0.012494832 0.024038598, -0.041771114 0.012218773 0.024038628, -0.041689351 0.011954784 0.024038628, -0.041546613 0.011718169 0.024038732, -0.041351348 0.011522502 0.024038494, -0.041897923 0.01043269 0.025245696, -0.041115031 0.011379063 0.024038628, -0.041423365 0.010203332 0.025245667, -0.040851131 0.01129654 0.024038464, -0.040909678 0.010085493 0.025245622, -0.04057534 0.011279672 0.024038494, -0.040382594 0.010084808 0.025245711, -0.040303573 0.01132898 0.024038553, -0.039868578 0.010201395 0.025245801, -0.040051252 0.011442035 0.024038598, -0.039393544 0.010429457 0.025245696, -0.02967526 -0.033283472 0.025243282, 0.0092627704 -0.042518884 0.024035573, -0.029361129 -0.032117978 0.024036065, 0.0089489073 -0.043684646 0.02524291, 0.0095019341 -0.04376483 0.025242731, 0.0095321983 -0.04255791 0.024035588, 0.0098031461 -0.042532444 0.024035677, 0.010058224 -0.043712214 0.025242671, 0.010060579 -0.042443722 0.024035633, 0.010586619 -0.043530256 0.025242835, 0.010289818 -0.042296767 0.024035618, 0.011057019 -0.043228745 0.025242865, 0.010477766 -0.042100042 0.024035677, 0.011443257 -0.042824909 0.025242865, 0.010614216 -0.041864395 0.024035573, 0.011723325 -0.042341277 0.025242746, 0.010691226 -0.041603476 0.024035707, 0.011881426 -0.041805193 0.025242925, 0.010704547 -0.041331485 0.024035692, 0.011908546 -0.04124707 0.025242895, 0.010653362 -0.041064233 0.024035707, 0.011803642 -0.04069823 0.025242999, 0.010540605 -0.040816486 0.024035558, 0.011572048 -0.040189579 0.025242954, -0.028764933 -0.029903889 0.024036318, -0.029038578 -0.02986455 0.024036348, -0.029313609 -0.029891863 0.024036288, -0.029574126 -0.029984295 0.024036318, -0.029804945 -0.030136541 0.024036288, -0.029992461 -0.030339256 0.024036363, -0.030126154 -0.030581325 0.024036333, -0.030198142 -0.030848101 0.024036303, -0.030203968 -0.031124577 0.024036348, -0.030143574 -0.031394228 0.024036139, -0.030020356 -0.031641647 0.02403605, -0.029841617 -0.031852543 0.024036169, -0.030415505 -0.032937154 0.025243476, -0.029617518 -0.032014221 0.024036199, -0.030060485 -0.03314285 0.025243342, 0.040278673 -0.0099612027 0.024037346, 0.040381581 -0.010217682 0.024037346, 0.040542871 -0.010442093 0.024037331, 0.040753141 -0.010621503 0.024037316, 0.040158957 -0.011674166 0.025244489, 0.041000217 -0.010745347 0.024037376, 0.040667012 -0.011907026 0.02524446, 0.041269779 -0.010806382 0.024037346, 0.041215599 -0.012013316 0.025244609, 0.041546151 -0.010801107 0.024037331, 0.041773841 -0.011987492 0.025244519, 0.04181321 -0.010729998 0.024037376, 0.042310312 -0.011830747 0.02524437, 0.042055503 -0.010596901 0.024037346, 0.042794585 -0.011551842 0.025244504, 0.042258799 -0.010409802 0.024037376, 0.043199509 -0.011166811 0.025244579, 0.042411447 -0.010179445 0.024037361, 0.043502241 -0.010697126 0.025244638, 0.042504534 -0.0099191219 0.024037391, 0.043685704 -0.010169223 0.025244653, 0.042532742 -0.0096440762 0.024037391, 0.043739483 -0.0096129775 0.025244772, 0.042494193 -0.0093706548 0.024037436, 0.043660641 -0.0090598166 0.025244787, 0.032189801 0.02927947 0.024039567, 0.033356234 0.029590338 0.025246829, 0.032121733 0.029467136 0.024039626, 0.033216313 0.029975891 0.025246948, 0.033011734 0.030331537 0.025246888, 0.032022014 0.02964054 0.024039626, -0.039540499 0.041054398 0.020430133, -0.040912732 0.041014031 0.021492675, -0.040956497 0.03964214 0.020430043, -0.037385985 0.044252694 0.021492735, 0.037496537 0.044158652 0.02149269, 0.036177099 0.04274486 0.01929009, -0.044159979 0.037495568 0.021492347, -0.040250108 0.038933992 0.019289836, -0.043385088 0.035407022 0.019289583, 0.0337217 0.047104418 0.021492839, 0.032449856 0.045638978 0.01929006, -0.047105685 0.033720598 0.021492198, -0.046212152 0.031628832 0.01928924, -0.049729481 0.029715523 0.021491915, -0.048711032 0.027625769 0.019289002, 0.029716671 0.049728245 0.021493018, 0.028492242 0.048208788 0.019290388, -0.052013591 0.025507465 0.021491736, -0.050864041 0.02342689 0.019288912, 0.025508493 0.052012414 0.021493196, 0.024332345 0.050436571 0.019290388, -0.053942457 0.021125212 0.021491453, -0.052655771 0.019061357 0.019288808, 0.02112624 0.053941205 0.021493137, 0.019999474 0.052306011 0.019290656, -0.055502906 0.016598269 0.021491259, -0.054073766 0.014560565 0.019288346, 0.015659243 0.054303616 0.019880563, 0.015524745 0.053803965 0.019290537, -0.056683943 0.011958227 0.021490932, -0.055107713 0.0099565834 0.019288063, 0.016599417 0.05550164 0.021493405, -0.057477996 0.0072365105 0.021490633, 0.013728112 0.054823667 0.019880414, -0.055750266 0.005281508 0.019287735, 0.0089717507 0.055275694 0.019290656, 0.013593584 0.054324105 0.019290656, -0.057879299 0.0024654418 0.021490514, 0.011959434 0.05668284 0.021493345, -0.055997133 0.00056909025 0.019287497, -0.057885438 -0.002322644 0.021490097, 0.0072376728 0.057476744 0.021493524, -0.055846378 -0.0041473806 0.019287229, 0.004286021 0.055834845 0.019290835, -0.057495937 -0.0070948452 0.021489784, 0.00246647 0.057877943 0.021493465, -0.055298984 -0.008834362 0.01928696, -0.00042995811 0.055997342 0.019290626, -0.0023216605 0.057884187 0.021493465, -0.0051429272 0.055762202 0.019290984, -0.054859012 -0.013591841 0.019876614, -0.054358989 -0.013458461 0.01928696, -0.0070936978 0.057494685 0.021493435, -0.05671376 -0.011818677 0.021489501, -0.0098194778 0.05513145 0.019290611, -0.011817515 0.056712568 0.021493345, -0.014426142 0.054109037 0.019290566, -0.055544153 -0.01646167 0.021489456, -0.016460568 0.05554302 0.02149336, -0.054343686 -0.015524462 0.019876674, -0.018930554 0.052702338 0.019290656, -0.052357018 -0.019869521 0.019286513, -0.053843856 -0.015391171 0.019286811, -0.020991266 0.053994015 0.021493092, -0.053995147 -0.020992368 0.02148886, -0.023300409 0.05092144 0.019290462, -0.050498381 -0.024206907 0.01928623, -0.025378302 0.052076057 0.021493241, -0.052077442 -0.025379419 0.02148886, -0.027504891 0.048778847 0.019290388, -0.048281044 -0.028372422 0.019286141, -0.049803793 -0.029593229 0.021488622, -0.029592276 0.049802452 0.021493033, -0.045721143 -0.032336608 0.019285664, -0.03151384 0.046290129 0.01929009, -0.047189981 -0.033604994 0.021488294, -0.033604011 0.047188669 0.021492898, -0.042836428 -0.036070958 0.019285589, -0.035299405 0.043472752 0.019290224, -0.044253781 -0.037387133 0.021488011, -0.038834095 0.040346503 0.019289792, -0.01464653 0.0018790513 0.029656425, -0.011602014 0.0027557611 0.029036775, -0.011311248 0.0016653836 0.028943479, -0.014453888 0.0030224919 0.02965644, -0.014748827 0.00072437525 0.029656291, -0.011020258 0.0005735755 0.028871, -0.014760479 -0.0004350245 0.029656261, -0.010728806 -0.00051917136 0.028819114, -0.014680967 -0.0015919507 0.029656276, -0.01043734 -0.0016124994 0.028787836, -0.0145109 -0.0027387589 0.029656082, -0.010145649 -0.0027064979 0.028777048, -0.014251336 -0.0038688183 0.029656082, -0.013904184 -0.0049752444 0.029655933, -0.0098540485 -0.0038002878 0.028787553, -0.013471112 -0.006050691 0.029655963, -0.0095624775 -0.0048939735 0.028818712, -0.012954816 -0.0070888996 0.029655933, -0.0092711449 -0.0059867799 0.028870732, -0.012358829 -0.0080834478 0.029655918, -0.0089800358 -0.0070783496 0.028943121, -0.011686668 -0.0090282857 0.029655784, -0.0086894184 -0.0081686378 0.029036194, -0.010942534 -0.0099173337 0.029655695, -0.0083992928 -0.0092570037 0.029149875, -0.010130689 -0.010745347 0.029655755, -0.0081096292 -0.01034312 0.029284373, -0.0092565566 -0.011507168 0.02965571, -0.007820785 -0.011426896 0.029439434, -0.0083252937 -0.012197688 0.029655784, 0.0015901774 -0.014682472 0.029655457, 0.0010256767 -0.013809174 0.02943939, 0.0018197298 -0.013017103 0.029284388, -0.0005555898 -0.015386388 0.029811218, 0.0027371347 -0.014512494 0.029655501, 0.0026155263 -0.012223184 0.02914986, 0.0038672686 -0.01425305 0.029655486, 0.0034130365 -0.011427715 0.02903606, 0.0049735308 -0.013905525 0.029655486, 0.0042118877 -0.01063095 0.028943047, 0.0060490072 -0.013472497 0.029655501, 0.0099155605 -0.010943964 0.029655725, 0.0090265721 -0.011688232 0.029655591, 0.0066136718 -0.0082350969 0.028787374, 0.0074153244 -0.0074355155 0.028777018, 0.010743544 -0.010132268 0.029655635, -0.0055756271 -0.015898347 0.030197352, -0.0048461258 -0.0162763 0.030235246, 0.013348252 -0.0063165873 0.029656038, 0.0098187327 -0.0050381869 0.028870702, 0.010618553 -0.0042401701 0.02894339, 0.012811601 -0.007344231 0.029655993, 0.013802603 -0.0052495897 0.029655889, 0.011417449 -0.0034433454 0.029036313, 0.014171854 -0.0041506588 0.029656023, 0.012214914 -0.0026478618 0.029150397, 0.014453754 -0.0030258596 0.029656217, 0.013010845 -0.0018539876 0.029284924, 0.014646426 -0.0018823594 0.029656291, 0.013804778 -0.0010620356 0.029440045, 0.014748856 -0.00072751939 0.029656291, 0.01538603 0.00051517785 0.029812023, 0.012358695 0.0080800802 0.029656768, 0.011444658 0.0077904463 0.029440612, 0.011686623 0.0090248734 0.029656768, 0.010361657 0.0080820769 0.029285595, 0.010942236 0.0099140704 0.029656798, 0.0092763901 0.0083743036 0.029150933, 0.010130584 0.010742053 0.029656917, 0.0081887543 0.0086673647 0.029037267, 0.0092563331 0.011503682 0.029656887, 0.0070990324 0.0089608431 0.028943822, 0.0083251894 0.012194604 0.029656768, 0.0060082674 0.0092544258 0.028871477, -0.0039467365 -0.016514137 0.030234069, -0.0030159503 -0.016537771 0.030186906, 0.007342577 0.012810096 0.029656932, 0.0049161911 0.0095484257 0.028819308, 0.0063147545 0.013346806 0.029657006, 0.0038233995 0.0098428875 0.028788552, 0.0052480102 0.013801068 0.029657006, 0.0041490197 0.014170229 0.02965714, 0.002730161 0.01013726 0.02877818, -0.0021094084 -0.01634711 0.030096591, 0.0030241907 0.014452159 0.029657066, 0.0016370118 0.010431454 0.028788552, 0.0018807948 0.014644891 0.029657021, 0.00054433942 0.010725752 0.028819501, 0.00072574615 0.014747187 0.029657155, -0.00054776669 0.011020005 0.02887179, -0.00043359399 0.014758661 0.02965714, -0.0016387105 0.011313617 0.028944135, -0.0015902817 0.014679134 0.029657066, -0.0027372241 0.014509171 0.029657155, -0.0027281642 0.011607096 0.029037267, -0.0038671792 0.014249593 0.029656947, -0.0038158894 0.011899978 0.029151067, -0.0049735606 0.013902366 0.029657185, -0.0049012303 0.01219216 0.029285803, -0.0060490668 0.013469189 0.02965723, -0.0059842318 0.01248388 0.029440954, -0.015143499 0.0081243366 0.030294538, -0.01334852 0.0063132793 0.029656738, -0.013802812 0.0052464902 0.029656664, -0.017272949 0.0078219771 0.030829698, -0.016068906 0.010065764 0.030829892, -0.01682733 0.0012618005 0.030206367, -0.01895754 0.000418365 0.030829176, -0.018730253 0.0029544383 0.030829325, -0.016145408 -0.0049089938 0.03020595, -0.017602503 -0.0070526898 0.030828774, -0.018388569 -0.0046305805 0.030829117, -0.015054747 -0.0076247156 0.030205891, -0.016499072 -0.0093474537 0.030828774, -0.012982279 -0.010781929 0.030205742, -0.015098274 -0.011473745 0.030828714, -0.011279419 -0.012552693 0.030205637, -0.0092297196 -0.014498919 0.030293301, -0.0091160387 -0.014846578 0.030360848, -8.4593892e-05 -0.01749067 0.030380636, -0.0012764186 -0.015956536 0.02996932, 0.000292629 -0.017185315 0.030293241, 0.0026954859 -0.016659573 0.030205294, 0.0064721256 -0.01116848 0.029234514, 0.0070871413 -0.012956411 0.029655561, 0.0058124661 -0.0090343505 0.028818429, 0.0050117671 -0.0098330528 0.028870389, 0.008081913 -0.012360379 0.029655561, 0.0051534474 -0.016070083 0.030205265, 0.010341823 -0.0074772537 0.02920419, 0.009018153 -0.0058368444 0.028818533, 0.016285524 0.0018880069 0.030074358, 0.016520262 0.0027774125 0.030172303, 0.012196079 -0.0083269477 0.029655874, 0.011505261 -0.0092580616 0.029655784, 0.0082167983 -0.0066359341 0.028787479, 0.010725573 -0.013029456 0.030205637, 0.012551114 -0.011280999 0.030205682, 0.014386028 -0.0088219196 0.030205965, 0.016626745 -0.0028829426 0.030206203, 0.017182752 -0.0003374666 0.030294091, 0.015905946 0.0011533648 0.029954806, 0.016545355 0.0037025362 0.030229077, 0.016356364 0.0046105087 0.030240342, 0.017460406 -3.1143427e-06 0.030373216, 0.014520183 0.0091917813 0.030294701, 0.01486893 0.0090763718 0.030362293, 0.013027444 0.010723919 0.030206934, 0.010899365 0.012880877 0.030206949, 0.011450797 0.015112519 0.03083013, 0.0088848472 0.014344364 0.030207187, 0.0092580914 0.016546726 0.03083013, 0.0054407418 0.01597175 0.030207172, 0.0043873191 0.018445954 0.030830517, 0.0068885386 0.017664954 0.030830294, 0.0030310452 0.016598418 0.030207217, 0.0018023252 0.018874571 0.030830473, 5.1349401e-05 0.016872838 0.030207291, -0.00081676245 0.018942982 0.030830532, -0.0061158538 0.015725851 0.030207202, -0.0083834082 0.017006636 0.030830294, -0.0059588253 0.017999843 0.030830279, -0.0085975081 0.01506798 0.030342028, 0.015964925 0.0054482818 0.030205175, -0.008845523 0.015094012 0.030384451, -0.010647893 0.015688524 0.030830175, -0.016707018 0.0068992227 0.030555785, -0.018165365 0.005437389 0.030829832, -0.014171943 0.0041472316 0.029656395, -0.017622173 0.0032583177 0.030508846, -0.015820906 -0.00026230514 0.029922023, -0.017918006 -0.00033576787 0.030508682, -0.018842831 -0.002125293 0.030829072, -0.015503064 -0.0031681657 0.029922009, -0.01755093 -0.0036261231 0.030508518, -0.014107123 -0.0092613846 0.030205756, -0.014748573 -0.010182485 0.030508012, 0.00624156 -0.014541775 0.029921412, 0.007052213 -0.016476944 0.030507714, 0.0088648945 -0.013108358 0.029921249, 0.010025114 -0.014856547 0.030507922, 0.014201418 -0.0069791675 0.029921755, 0.016104579 -0.0078634024 0.030508444, 0.015260458 -0.0041835159 0.029921874, 0.017295867 -0.0046940744 0.030508548, 0.007209003 0.015255556 0.030207276, 0.0072939992 0.016367942 0.030509606, -0.0014488399 0.01575473 0.029923066, -0.0015958548 0.017848164 0.0305098, -0.0034206212 0.018649474 0.030830398, -0.0043522418 0.015211076 0.029922828, -0.0048858821 0.017240733 0.030509546, -0.016772568 -0.0018551052 0.030206114, 0.0080838054 -0.014814034 0.030205578, 0.015788063 -0.0059586912 0.030205995, -0.0030859411 0.016588435 0.030207098, -0.012709245 0.014070973 0.0308301, -0.014527738 0.012184709 0.0308301, -0.012470588 0.0060137957 0.029440597, -0.012181684 0.0049301386 0.029285252, -0.011892125 0.003843829 0.029150516, -0.02953276 0.04345268 0.026117295, -0.023775935 0.039151683 0.027591765, -0.025470376 0.038071111 0.027591631, -0.014252365 0.028910831 0.029767096, -0.01550667 0.028257981 0.029766932, -0.025778413 0.045779571 0.026117429, -0.022035688 0.040156767 0.02759178, -0.012970552 0.029508293 0.029767066, -0.020253181 0.041084662 0.02759172, -0.021841958 0.047783211 0.026117355, -0.011663526 0.030048668 0.029767007, -0.010334283 0.030531421 0.029767066, -0.0089851022 0.030955181 0.029767081, -0.0089936554 0.039021298 0.028643638, -0.0088122487 0.036226079 0.029080138, -0.0093115568 0.038497925 0.028715536, -0.013493091 0.044210285 0.027508005, -0.013534844 0.050765157 0.026117727, -0.012629151 0.044386178 0.027523205, -0.011750638 0.044354811 0.02757597, -0.010904372 0.044118777 0.027663186, -0.0086016655 0.040707931 0.028377444, -0.0072147846 0.036577851 0.029080257, -0.0086974502 0.039844185 0.028519422, -0.017751127 0.049448863 0.026117578, -0.0080413222 0.040768743 0.028386414, -0.008708775 0.041569948 0.028223783, -0.0056034327 0.036858767 0.029080302, -0.009498775 0.043103874 0.02791588, -0.0088639259 0.044939533 0.027592108, -0.0090134144 0.042383522 0.028066888, -0.0062453747 0.041082129 0.028386429, -0.0039812624 0.03706938 0.029080063, -0.0068842769 0.045284957 0.027591988, -0.0092229545 0.051722541 0.026117831, -0.0044373274 0.041316465 0.028386503, -0.0023515224 0.037208214 0.029080421, -0.0048913062 0.045543462 0.027591944, -0.0026207864 0.041471273 0.028386638, -0.0028888881 0.04571417 0.027591914, -0.00043433905 0.052536607 0.026117802, -0.004845649 0.052314311 0.026117742, -0.00079920888 0.041546479 0.028386518, -0.00088104606 0.045796901 0.027592152, 0.0083664358 0.051868007 0.026117712, 0.0010237992 0.041541442 0.028386697, 0.0085477829 0.046553791 0.027280733, 0.0011284947 0.045791402 0.027591929, 0.0039802492 0.052387416 0.026117653, 0.0097409487 0.047093123 0.027121618, 0.00313586 0.045697734 0.027591944, 0.0051374137 0.045516267 0.027592003, -0.0097830892 0.04771252 0.026989579, -0.010139108 0.043692484 0.027778789, 0.012693673 0.050981849 0.026117653, 0.010714322 0.047297284 0.02703473, 0.01170674 0.047316894 0.026981175, -0.0059660077 0.048815623 0.026886821, -0.020202726 0.025116339 0.029766858, -0.036389962 0.037895679 0.026116937, -0.030246943 0.034398884 0.027591258, -0.032412291 0.033908024 0.027368307, -0.033078313 0.040818378 0.026116937, -0.019081473 0.025978372 0.029766798, -0.014292628 0.043835834 0.027531445, -0.028708994 0.035692453 0.027591437, -0.017923743 0.026790351 0.029766917, -0.027115673 0.036917388 0.027591631, -0.016731337 0.027550608 0.029766992, -0.043370754 -0.034206316 0.023800477, -0.047048494 -0.028939813 0.023800775, -0.040956378 0.039641932 0.02229169, -0.039540663 0.041054279 0.022291869, -0.05009 -0.023282066 0.023801312, -0.052454025 -0.01730983 0.02380155, -0.05434373 -0.015524507 0.022702575, -0.054108709 -0.011103079 0.023801878, -0.054858997 -0.013592109 0.022702575, -0.055031672 -0.0047465265 0.023802251, -0.055210352 0.0016743839 0.023802668, -0.054642648 0.0080726296 0.023802906, -0.053335935 0.014361531 0.023803383, -0.051307827 0.020456463 0.023803636, -0.048585728 0.026274532 0.023803964, -0.045206815 0.031737208 0.023804367, -0.041216612 0.036770806 0.023804709, -0.036668852 0.041307315 0.023804829, -0.031625301 0.045284793 0.023804933, -0.026154086 0.048650116 0.023805171, -0.020329222 0.051357538 0.02380535, -0.014229357 0.053370357 0.023805678, -0.0079369843 0.054661423 0.023805454, -0.001537323 0.055213049 0.023805588, 0.0048829317 0.055018261 0.023805559, 0.013728201 0.054823488 0.022706628, 0.011237383 0.054079339 0.023805648, 0.017439753 0.052409232 0.023805439, 0.015659332 0.054303408 0.022706538, 0.023406297 0.050030053 0.02380532, 0.029056251 0.046974584 0.023805171, 0.034313366 0.043283552 0.023804963, -0.040300459 -0.035775289 0.024956599, -0.042316779 -0.037564844 0.022644356, 0.035874739 0.040209249 0.024960876, 0.03766951 0.042221427 0.022648722, -0.040250227 0.038934261 0.015393734, -0.038834244 0.040346727 0.015393853, -0.039783746 0.039410681 0.015393794, -0.039311796 0.039881572 0.015393764, -0.053843781 -0.015390873 0.015390649, -0.054023266 -0.014748722 0.015390784, -0.054194927 -0.01410459 0.015390635, -0.054359019 -0.013458341 0.015390903, 0.013593674 0.054324284 0.015394658, 0.015524685 0.053804383 0.015394568, 0.01423943 0.054158583 0.015394717, 0.014883161 0.053985313 0.015394747, 0.023047253 0.017391354 0.029846385, 0.025589585 0.0078555495 0.030050665, 0.025589511 0.0078565031 0.015392199, 0.020762503 0.025960714 0.02934055, 0.018584877 0.034128904 0.028532445, 0.01737231 0.038676664 0.027931914, 0.0035390556 -0.02865766 0.029843822, -0.0059902072 -0.026091486 0.030048653, -0.0059901327 -0.026090637 0.015390232, 0.012102753 -0.030963734 0.029337361, 0.020265341 -0.033161789 0.028528705, 0.024809971 -0.034385443 0.02792792, -0.026586324 0.011261269 0.029845908, -0.019599393 0.018231094 0.030051142, -0.019599468 0.018231824 0.015392542, -0.032865494 0.004998073 0.029339343, -0.038850352 -0.00097183883 0.028530419, -0.042182729 -0.0042955726 0.027929559, -0.042941973 -0.014586955 0.025390714, -0.044503704 -0.0087293833 0.025391087, -0.037465572 -0.0098699182 0.025390938, 0.030614346 -0.034297362 0.025389716, 0.029810473 -0.034178555 0.025389865, 0.031424001 -0.034227565 0.025389642, -0.04500857 -0.0093662888 0.025390968, -0.037472084 -0.0096376985 0.025391042, -0.037424907 -0.0094104707 0.025391042, -0.037326485 -0.0092000961 0.025390998, -0.037182182 -0.009018153 0.025391057, 0.032195702 -0.033972874 0.025389567, 0.032887951 -0.033547312 0.025389552, 0.03346324 -0.032973319 0.025389612, 0.034147263 -0.031511113 0.025389925, 0.033890799 -0.032282308 0.025389671, 0.03421922 -0.030701637 0.025389805, 0.034102365 -0.029897541 0.025390089, 0.026629448 -0.027727753 0.025390029, 0.026860893 -0.027707621 0.025389925, 0.026399806 -0.027693734 0.025390044, 0.027081236 -0.027634948 0.025389954, 0.027278975 -0.027513266 0.025390044, 0.010782212 0.03670755 0.025393546, 0.014692962 0.04290396 0.025393859, 0.027626052 -0.026470542 0.025390014, 0.010635823 0.037022606 0.02539368, 0.010722876 0.036871433 0.02539368, 0.027443439 -0.027349338 0.025390014, 0.027565539 -0.027151898 0.025390029, 0.027638912 -0.026931524 0.025390089, 0.027659327 -0.026700363 0.025390223, -0.043696776 -0.014286041 0.025390804, -0.044361964 -0.013819188 0.025390789, -0.044901371 -0.01321125 0.025390834, -0.045286253 -0.012495637 0.025390744, 0.01418069 0.044006139 0.025394112, 0.014485151 0.043477446 0.025394142, -0.036736026 -0.010691702 0.025390893, -0.03695178 -0.010605901 0.025390893, -0.037141711 -0.010472253 0.025391042, -0.037295893 -0.010298654 0.025390923, -0.045495629 -0.011710241 0.025390804, -0.045352921 -0.010102317 0.025390983, -0.04551813 -0.010898009 0.025390968, -0.037405774 -0.01009424 0.025391012, 0.027626052 -0.02647087 0.028467208, 0.027617753 -0.026439905 0.028469533, 0.02557759 -0.018787563 0.029362127, 0.023530081 -0.011107177 0.029950038, 0.020913422 -0.0012929589 0.030318812, 0.017918304 0.009941414 0.030345693, 0.013067812 0.028135195 0.029448062, 0.015354246 0.019558683 0.030048102, 0.010789961 0.03667669 0.028473735, 0.010782301 0.036707416 0.02847074, -0.036736012 -0.01069203 0.028468177, -0.0367053 -0.010700241 0.028470561, -0.029057145 -0.01275979 0.029362559, -0.021376252 -0.014828265 0.029950216, -0.011567548 -0.017469808 0.03031823, -0.00028021634 -0.020509288 0.030342311, 0.017839208 -0.025388584 0.029444396, 0.0092769414 -0.023082912 0.030044794, 0.026369259 -0.02768518 0.02846995, 0.026399747 -0.027694002 0.028467238, 0.0090872645 0.037135288 0.028473154, 0.0034449697 0.031507149 0.029369518, -0.0022215843 0.025854856 0.029958069, -0.0094286352 0.018665865 0.030322284, -0.01764451 0.01047042 0.030344009, -0.030932724 -0.0027847141 0.029442251, -0.024682418 0.0034499764 0.030042782, -0.037159771 -0.0089958757 0.02847068, -0.037182182 -0.0090182722 0.028466433, 0.011571854 -0.038547575 0.02497527, 0.011574253 -0.038549066 0.028430298, 0.011044025 -0.038241848 0.02497524, 0.011045203 -0.038242519 0.028507218, 0.010470971 -0.038032368 0.024975136, 0.010471061 -0.038032562 0.028568774, -0.001554206 -0.042043537 0.028089687, -0.0096956939 -0.039851144 0.028274789, -0.0096955895 -0.039850995 0.024975136, 0.0035280585 -0.043412194 0.027819291, 0.0086022317 -0.0447786 0.027426243, -0.02900137 -0.027511686 0.028478697, -0.028988242 -0.027511805 0.024975643, -0.029851377 -0.027600706 0.028359145, -0.029827923 -0.027595669 0.024975672, -0.030651346 -0.027891934 0.028218776, -0.030623153 -0.027877763 0.024975792, -0.031355947 -0.028366551 0.028064743, -0.03132759 -0.028342083 0.024975583, -0.031923354 -0.028993964 0.027907148, -0.031900465 -0.028961495 0.024975941, -0.032325506 -0.029743686 0.027754143, -0.032308474 -0.029700011 0.024975523, -0.032527953 -0.030514687 0.024975553, -0.03253524 -0.030568808 0.027615368, -0.032545939 -0.031358331 0.024975419, -0.032538608 -0.031423941 0.027498499, -0.032361463 -0.032181725 0.024975523, -0.032334596 -0.032254845 0.027411565, -0.031985477 -0.032936946 0.024975449, -0.031932577 -0.033015117 0.02735962, -0.031439558 -0.033580437 0.024975479, -0.031419143 -0.033599541 0.027345508, -0.030858397 -0.034015283 0.027360439, -0.030755609 -0.034074455 0.024975419, -0.030427441 -0.034234226 0.027385637, 0.010431752 -0.038022101 0.028572395, 0.0023030937 -0.035833061 0.02910991, -0.0078755319 -0.033091679 0.024975404, -0.0027847737 -0.034462959 0.029294476, -0.007875368 -0.033092096 0.02936846, 0.010160208 -0.040130973 0.022889316, 0.010373533 -0.040254459 0.022889301, 0.0099286586 -0.040046215 0.02288942, -0.0091533065 -0.03783679 0.022889569, -0.0084176511 -0.035105869 0.022889659, 0.032907516 0.031970099 0.024979204, 0.032895744 0.031977311 0.02737385, 0.032152027 0.032316446 0.024979442, 0.032127544 0.03232421 0.027434319, 0.031336173 0.032474756 0.024979115, 0.031304345 0.032476813 0.027526975, 0.030506045 0.032436296 0.024979144, 0.030470461 0.032430068 0.027646467, 0.029708356 0.032202989 0.024979174, 0.029671982 0.032187164 0.027786165, 0.028988063 0.031788453 0.02497901, 0.02895537 0.031763539 0.027937531, 0.028386042 0.031215712 0.02497898, 0.028361768 0.03118597 0.028091595, 0.027935907 0.03051728 0.024978802, 0.027919114 0.030482367 0.028240427, 0.027663141 0.029732168 0.024978995, 0.02765426 0.029690549 0.028376505, 0.027582958 0.028905034 0.024978876, 0.027583644 0.028884813 0.02848728, 0.02770035 0.02808246 0.0249791, 0.02770023 0.028082073 0.028572485, 0.037186548 0.019673377 0.028093308, 0.039358556 0.011526674 0.028277427, 0.039358601 0.011526883 0.024977922, 0.035830751 0.024759382 0.027823105, 0.034476861 0.029836878 0.027430266, 0.038325071 -0.011362657 0.028479442, 0.038318694 -0.011350766 0.024976626, 0.0388273 -0.012053743 0.028360084, 0.038810983 -0.012036011 0.024976656, 0.039479375 -0.01260078 0.028219387, 0.039452955 -0.012583479 0.024976581, 0.040242806 -0.012974009 0.028065711, 0.040207446 -0.012961596 0.024976537, 0.041069597 -0.013151646 0.027908102, 0.041030258 -0.013147935 0.024976671, 0.041920096 -0.013125256 0.027755067, 0.041873947 -0.013131961 0.024976745, 0.042689055 -0.012914464 0.024976537, 0.0427396 -0.012894005 0.027616411, 0.043428719 -0.012508422 0.024976462, 0.043481931 -0.012469679 0.027499691, 0.044049621 -0.011937082 0.024976611, 0.044099391 -0.011877328 0.027412817, 0.04451558 -0.011233747 0.024976596, 0.044556931 -0.011149034 0.027360752, 0.044800028 -0.010439634 0.024976671, 0.044806108 -0.010412186 0.027346924, 0.044886053 -0.009718582 0.02736178, 0.044885814 -0.0095999092 0.02497685, 0.04485999 -0.0092360824 0.027387083, 0.027710766 0.028042734 0.028576255, 0.029879346 0.019908637 0.029112875, 0.032594875 0.0097234845 0.024977818, 0.031236812 0.014817551 0.029297099, 0.032594696 0.0097232908 0.029370859, 0.034610316 0.010261118 0.022892252, 0.029715642 0.028619945 0.022893324, 0.037343159 0.01098974 0.022892281, 0.029668331 0.028952271 0.022893339, 0.029700577 0.029286459 0.022893369, 0.029810742 0.029603601 0.022893205, 0.02999267 0.029886052 0.022893399, 0.031819642 0.030190766 0.022893399, 0.03023605 0.030117512 0.022893429, 0.030527025 0.030284911 0.022893369, 0.031184658 0.030394644 0.022893369, 0.031514436 0.030330703 0.022893101, 0.030849442 0.030378982 0.02289319, -0.043638915 0.014233723 0.027367979, -0.043115005 0.014901832 0.027424842, -0.04311505 0.014901906 0.024978086, -0.043636099 0.014238372 0.024978027, -0.043983459 0.013469338 0.024978012, -0.043987036 0.013457805 0.027348205, -0.044136479 0.012639537 0.024977997, -0.044137463 0.012623027 0.027366713, -0.04408659 0.011797488 0.024977982, -0.044083312 0.011779219 0.027422175, -0.043836594 0.010991395 0.024977803, -0.043828353 0.010973021 0.027511507, -0.043401077 0.010268763 0.024977908, -0.043389648 0.010254636 0.02762866, -0.04280518 0.0096713305 0.024977803, -0.042793378 0.0096619129 0.027767196, -0.042083621 0.0092339963 0.024977848, -0.042077929 0.0092313737 0.027917802, -0.041278362 0.008981958 0.024977922, -0.041281953 0.0089826286 0.028073221, -0.040436223 0.0089299679 0.024977878, -0.040446907 0.0089292228 0.028223932, -0.039606154 0.0090811402 0.024977967, -0.039623141 0.0090760142 0.02836217, -0.038836211 0.0094264448 0.024977878, -0.038855523 0.0094146729 0.028479367, -0.038496614 0.0096590221 0.028529301, -0.038171366 0.00994578 0.024977878, -0.03817144 0.0099456608 0.02857165, -0.035632342 0.022365496 0.028093338, -0.029663309 0.02831997 0.02827853, -0.02966319 0.028320134 0.024979129, -0.039359018 0.018648461 0.027822822, -0.043079361 0.014937341 0.02742961, -0.010522693 0.043673784 0.027563885, -0.010457695 0.043633983 0.024979755, -0.011163414 0.043974787 0.024979845, -0.011313826 0.044023857 0.027458757, -0.011927217 0.044150174 0.024979815, -0.012083501 0.044164374 0.027392209, -0.012710929 0.044151172 0.02497983, -0.01278764 0.044141307 0.027358502, -0.013475299 0.043977857 0.024979815, -0.013474941 0.043977872 0.027350366, -0.014115334 0.043679118 0.027369037, -0.014181852 0.043638498 0.02497986, -0.014472425 0.043435439 0.027393371, -0.038142487 0.009974435 0.028575048, -0.032182679 0.015919611 0.029112741, -0.024719536 0.023364142 0.024978697, -0.028452143 0.019640684 0.029297441, -0.024719611 0.023363873 0.029371634, -0.041516632 0.011311769 0.022892237, -0.039644346 0.011422753 0.022892237, -0.04122512 0.011135101 0.022892252, -0.040899754 0.011033297 0.022892356, -0.040559486 0.011012316 0.022892252, -0.040224031 0.011073276 0.022892222, -0.039913014 0.011212885 0.022892475, -0.041757524 0.011553273 0.022892222, -0.041933641 0.011845306 0.022892222, -0.042034626 0.012170881 0.022892356, -0.042054698 0.012511313 0.022892147, -0.041992933 0.012846395 0.022892222, -0.041852519 0.013157174 0.022892222, -0.04164201 0.01342535 0.022892386, -0.026192471 0.024840906 0.022893116, -0.028190151 0.026843518 0.022892997, 0.0064068139 0.025290534 0.030410141, 0.0084634423 0.028055146 0.030099571, 0.0075350106 0.024977565 0.030410007, 0.0071959794 0.028406739 0.030099779, 0.010200977 0.036824852 0.028938353, 0.0088838339 0.03506951 0.029242903, 0.010124147 0.036897004 0.028930694, 0.010033011 0.036951214 0.028926134, 0.0099475086 0.036980912 0.028925329, 0.0079304278 0.0352972 0.029242828, 0.0080018342 0.031587988 0.029723734, 0.0098683536 0.036993325 0.028926492, 0.0097888112 0.036992714 0.028929859, 0.0097106099 0.036979288 0.028934762, 0.0096358359 0.036953151 0.028941795, 0.0095665455 0.03691496 0.028950244, 0.0095147789 0.03687644 0.028958082, 0.0094678998 0.036831498 0.028966635, 0.010308951 0.036604881 0.028966561, 0.0086481273 0.024614394 0.030409962, 0.0064953566 0.02153118 0.030689195, 0.0074548125 0.021218017 0.030689016, 0.011075407 0.033726826 0.029339239, 0.0094111264 0.031197295 0.029723763, 0.0083994567 0.020862177 0.03068918, 0.0067724586 0.018086895 0.030876055, 0.0097135603 0.027647272 0.030099675, 0.0097437501 0.024201721 0.030409843, 0.011842817 0.030845031 0.029666916, 0.010801405 0.030743554 0.029723793, 0.0093271136 0.020464331 0.03068924, 0.0092778206 0.016938895 0.030875832, 0.012611091 0.027959675 0.029950097, 0.010944396 0.027183712 0.030099779, 0.010819763 0.023740187 0.030409768, 0.010235697 0.020025238 0.030689329, 0.013380229 0.025070757 0.030190885, 0.012152851 0.026665255 0.030099869, 0.011874139 0.023230895 0.030409813, 0.013996035 0.022756949 0.030353576, 0.011123925 0.019545794 0.030689046, 0.011989772 0.019027233 0.030688986, 0.011594087 0.015446037 0.030875877, 0.014612436 0.020441383 0.030491084, 0.0128313 0.018470079 0.030688778, 0.014435589 0.017245427 0.030688956, 0.015229166 0.018123925 0.030604765, 0.015194803 0.016580358 0.030688941, -0.036694705 -0.010200635 0.028955355, -0.036754057 -0.010175079 0.028947651, -0.036632612 -0.010219008 0.028963894, -0.036821842 -0.010134131 0.028939098, -0.023601621 0.0038355738 0.030586526, -0.021765321 0.0056660324 0.030688047, -0.018868372 0.0041276962 0.030875325, -0.018088579 0.0067707151 0.030875325, -0.019928291 0.0074971914 0.030765533, -0.018090814 0.0093286037 0.030820251, -0.016940638 0.0092760772 0.030875459, -0.017066211 0.010350376 0.030842245, -0.016041458 0.01137206 0.030857965, -0.01544781 0.011592448 0.030875608, -0.015016869 0.012393817 0.03086783, -0.013992354 0.013415754 0.030872181, -0.013640597 0.013673007 0.030875623, -0.012967825 0.014437422 0.030871093, -0.011555701 0.015475139 0.030875966, -0.01194343 0.015459493 0.030864984, -0.010919034 0.016481459 0.030852929, -0.0092355013 0.016961962 0.030875802, -0.009894982 0.017503813 0.030835286, -0.0081394315 0.019256145 0.03079021, -0.0067271888 0.018103763 0.030875936, -0.0063840449 0.021008208 0.030724972, -0.0040821135 0.018876836 0.03087604, -0.0046294332 0.02275984 0.03063795, 0.010266125 0.036727384 0.02895008, -0.017584071 -0.015341416 0.030627996, -0.01662007 -0.015154988 0.030686915, -0.019321099 -0.014874309 0.030549094, -0.017283261 -0.01439406 0.030687213, -0.015476823 -0.011557236 0.030874372, -0.02105765 -0.014407367 0.030457094, -0.017911479 -0.013604164 0.030687153, -0.018503815 -0.012786746 0.030687198, -0.019058809 -0.011943832 0.030687436, -0.022793248 -0.013940752 0.030351564, -0.016963765 -0.0092369765 0.030874699, -0.019575343 -0.011076808 0.030687183, -0.022708595 -0.012849376 0.030407742, -0.024527714 -0.013474554 0.030231863, -0.020052582 -0.010187268 0.030687407, -0.023262143 -0.011817724 0.030407876, -0.026261136 -0.013008311 0.030097529, -0.020489246 -0.0092774183 0.030687436, -0.018105522 -0.0067287683 0.030874714, -0.023768887 -0.010762006 0.030407891, -0.020884886 -0.0083487034 0.030687302, -0.026697308 -0.012087777 0.03009738, -0.027993232 -0.012542754 0.029947862, -0.024227694 -0.0096848756 0.030407935, -0.021238446 -0.0074035078 0.030687585, -0.02721262 -0.010878071 0.030097574, -0.029724315 -0.012077078 0.029782981, -0.024637654 -0.0085882097 0.03040795, -0.021549001 -0.0064432025 0.030687571, -0.018878639 -0.0040836632 0.030874699, -0.027673244 -0.0096459985 0.030097634, -0.024998173 -0.0074741244 0.030408084, -0.030772209 -0.010726124 0.029721275, -0.033181801 -0.011147052 0.029405624, -0.021816298 -0.0054698288 0.030687764, -0.028078154 -0.0083946884 0.030097723, -0.025308222 -0.0063450336 0.030408114, -0.031222478 -0.0093346685 0.029721364, -0.022039801 -0.0044855773 0.030687734, -0.028426319 -0.0071266741 0.030097857, -0.025567293 -0.0052032322 0.030408144, -0.031609684 -0.0079244971 0.029721409, -0.022218615 -0.0034922063 0.03068772, -0.01926741 -0.0013554394 0.030874982, -0.028717399 -0.0058440417 0.030097932, -0.035093382 -0.008797735 0.029240564, -0.035433501 -0.0079582483 0.029220492, -0.03685689 -0.009377256 0.028964028, -0.03694123 -0.0094752759 0.028947651, -0.036993295 -0.0095805824 0.028935596, -0.037017316 -0.0096834153 0.028928116, -0.037018552 -0.0097892433 0.028923422, -0.03700152 -0.0098781586 0.028922707, -0.036972925 -0.0099528879 0.028923869, -0.036932722 -0.010021463 0.028927177, -0.036881894 -0.010082424 0.028932303, -0.025774986 -0.0040508211 0.030408248, -0.031933278 -0.006498307 0.029721558, -0.034008995 -0.0065380186 0.029456586, -0.022352874 -0.0024919063 0.03068769, -0.028950632 -0.0045498163 0.030097976, -0.025930703 -0.0028903782 0.030408397, -0.032192588 -0.005059287 0.029721797, -0.031156093 -0.0036941618 0.029867038, -0.032583028 -0.0051166713 0.029671684, -0.022442117 -0.0014866292 0.030687854, -0.029125467 -0.0032463223 0.030098185, -0.029728025 -0.0022703558 0.030042946, -0.026034176 -0.0017242134 0.030408502, -0.028298602 -0.00084592402 0.030200005, -0.022486135 -0.00047811866 0.030687958, -0.026085213 -0.00055447221 0.030408442, -0.026868284 0.0005800426 0.030338258, -0.022484869 0.00053115189 0.030687854, -0.019263998 0.0014003217 0.030875012, -0.026083797 0.00061650574 0.030408606, -0.02543664 0.0020066798 0.030458078, -0.022438258 0.0015392154 0.030688107, -0.022346556 0.002544567 0.030688047, -0.022209749 0.0035445243 0.030688092, -0.0044839978 0.022037983 0.030689329, -0.0028754473 0.024510831 0.03052789, -0.0034906864 0.022216797 0.030689165, -0.0013537705 0.019265801 0.030876115, -0.0024903119 0.022351041 0.03068924, -0.0013281405 0.026055485 0.030410066, -0.0014849007 0.02244024 0.03068921, 0.00021824241 0.02759929 0.030270949, -0.00047659874 0.022484452 0.03068924, 0.0014020205 0.019262135 0.0308761, 0.00053268671 0.02248311 0.03068921, 0.001763612 0.029141724 0.030110657, 0.00061795115 0.026081994 0.030410022, 0.0015410185 0.022436485 0.03068924, 0.0033075511 0.030683041 0.029928103, 0.0017877817 0.026028126 0.030409932, 0.0029535592 0.025921598 0.030409917, 0.0035461187 0.022208095 0.030689254, 0.0041293204 0.018866584 0.030876085, 0.004850328 0.032222658 0.029723153, 0.0033176541 0.029115513 0.030099779, 0.004113704 0.025763154 0.030410066, 0.0045389831 0.022026584 0.030689165, 0.0063909888 0.033760965 0.029494897, 0.0046206117 0.028937384 0.030099794, 0.0052653849 0.025552541 0.030410066, 0.0055226982 0.021800816 0.030689165, 0.0059142709 0.028700963 0.030099779, 0.0065766275 0.031915233 0.029723793, 0.010722667 0.036870793 0.028457925, 0.010635585 0.037022382 0.028446645, -0.037271887 -0.0091209114 0.028457835, -0.037346542 -0.0092342049 0.02844885, -0.037417471 -0.0093892664 0.028438792, -0.037460819 -0.0095536858 0.028431162, -0.037475988 -0.0097234845 0.028425694, -0.03746219 -0.0098924935 0.028423026, -0.037419289 -0.01005806 0.028423011, -0.037349105 -0.010213569 0.028425395, -0.037254035 -0.010354459 0.028430477, -0.0371335 -0.010479718 0.028438285, -0.036946774 -0.010608256 0.028451487, 0.026536509 -0.027720422 0.028456569, 0.026675582 -0.027727962 0.028447136, 0.026843891 -0.027711093 0.0284376, 0.027006954 -0.027665988 0.028430045, 0.027160719 -0.027593657 0.028424665, 0.027299419 -0.027496934 0.028422043, 0.027420625 -0.027377427 0.028421924, 0.027518928 -0.027240023 0.028424531, 0.02759321 -0.027086958 0.028429672, 0.027641132 -0.026919946 0.028437331, 0.027658969 -0.026694328 0.028450593, 0.035710692 -0.030486807 0.027044073, 0.035714582 -0.030553102 0.015389875, 0.035674453 -0.031476274 0.026911572, 0.035654798 -0.031606689 0.015389919, 0.035400406 -0.032559767 0.026798978, 0.035375148 -0.032624334 0.015389696, 0.034888282 -0.033561319 0.026730731, 0.034888297 -0.033560768 0.015389711, 0.0085474849 0.046169057 0.027048007, 0.0086018145 0.046205163 0.015394151, 0.0094214082 0.046631441 0.026915893, 0.0095439851 0.046680257 0.015394211, 0.010498971 0.046935767 0.026803151, 0.010565162 0.046946883 0.015394092, 0.011619389 0.046992585 0.026735216, 0.011619449 0.04699342 0.015394241, -0.045871645 -0.014410034 0.026803285, -0.045930088 -0.014338091 0.015390798, -0.046142802 -0.014053777 0.026769906, -0.046243265 -0.013902098 0.015390813, -0.046507895 -0.013435721 0.026731864, -0.04650791 -0.013434932 0.015390724, -0.017883107 -0.0066462755 0.030858189, -0.016755462 -0.0091237426 0.030857965, -0.017993912 -0.006687358 0.030873477, -0.01148434 0.015379623 0.030874714, -0.012865707 0.014244229 0.03087461, -0.016859218 -0.0091800839 0.030873224, -0.0153815 -0.01148589 0.030873001, -0.011413753 0.015284866 0.030859426, -0.012786657 0.014156654 0.030859351, -0.013556495 0.013588741 0.030874714, -0.015286833 -0.011415243 0.030857906, -0.013473049 0.013505057 0.030859217, -0.014706835 0.012334824 0.03087461, -0.014616296 0.012258872 0.030859306, -0.015352532 0.011521131 0.030874386, -0.015258238 0.011450142 0.030859321, 0.011591792 0.015298694 0.030874655, -0.016266927 0.010189667 0.030874431, -0.016166702 0.010127217 0.030858979, 0.011520445 0.015204474 0.030859292, -0.016836137 0.0092189759 0.030874372, 0.0093721151 0.016750455 0.030874684, -0.016732514 0.0091621876 0.030858934, 0.0093143582 0.016647473 0.030859545, -0.017485738 0.007918492 0.030874372, 0.006973356 0.01788263 0.030874893, -0.017377973 0.0078697205 0.030858904, 0.0069302917 0.017772555 0.030859485, -0.017977044 0.006728828 0.030874193, 0.0044414103 0.018673062 0.030874699, -0.017866418 0.0066875815 0.030858964, 0.0044139326 0.018558204 0.030859575, -0.018389255 0.0055041909 0.030874237, 0.0018247664 0.019107044 0.030874833, -0.018275991 0.0054704398 0.030858964, 0.0018134117 0.018989474 0.030859709, -0.018751934 0.0041021705 0.030874029, -0.018636554 0.0040769577 0.03085871, -0.00082677603 0.019176006 0.030874789, -0.00082173944 0.019058079 0.0308595, -0.018961087 0.0029908568 0.03087391, -0.0034626424 0.01887919 0.030874982, -0.018844336 0.0029726475 0.03085871, -0.0034415126 0.018763125 0.03085959, -0.019145042 0.0013915747 0.03087385, -0.019027352 0.0013830066 0.030858561, -0.0060321391 0.018221512 0.030874848, -0.019190982 0.0004235059 0.030873775, -0.0066857338 0.017992139 0.030874759, -0.019072995 0.0004209578 0.030858546, -0.0059950948 0.018109515 0.03085953, -0.0066445768 0.017881334 0.0308595, -0.019148499 -0.0013472587 0.030873865, -0.019074932 -0.0021514744 0.030873746, -0.0084866881 0.017215982 0.03087461, -0.019030735 -0.0013389587 0.030858383, -0.0091785043 0.016857475 0.030874789, -0.018957585 -0.0021381378 0.030858457, -0.0084344447 0.01711008 0.030859545, -0.018762216 -0.0040585548 0.030873477, -0.0091219544 0.016753748 0.030859351, -0.018646717 -0.0040336847 0.030858397, -0.010779083 0.015881956 0.030874789, -0.010712788 0.015784025 0.030859455, -0.00055554509 -0.015386283 0.027890876, 0.015386 0.00051543117 0.0278918, -0.0057553351 0.011267513 0.027892292, -0.0094275475 0.0052101165 0.027891904, -0.008464843 0.005267024 0.027891904, -0.010375753 0.0053852946 0.02789183, -0.0075438917 0.0055526942 0.027892023, -0.011254594 0.0057819337 0.027891994, -0.0067179501 0.0060505867 0.027892098, 0.00059495866 -0.01211141 0.027891085, 0.012108266 -0.00062689185 0.027891621, 0.00059394538 -0.01300703 0.027890965, -0.0060352981 0.0067316592 0.027892083, 0.013004139 -0.00062806904 0.027891636, 0.00039677322 -0.011237919 0.027891114, 0.011235371 -0.00042633712 0.027891442, 0.00039336085 -0.013880104 0.027890906, 0.013877541 -0.00042979419 0.027891666, 3.7848949e-06 -0.014686704 0.027890816, 0.010428771 -3.6671758e-05 0.027891576, 9.149313e-06 -0.010430396 0.02789095, -0.005535394 0.0075562 0.027891979, 0.014685139 -4.2110682e-05 0.027891561, -0.0052473545 0.0084765106 0.027892113, -0.0051879734 0.0094389468 0.027892143, -0.0053605437 0.010387719 0.027892172, -0.011380464 0.042941749 0.023936704, -0.012320518 0.043130025 0.023936853, -0.01326102 0.042944103 0.023936793, -0.011245966 0.042280942 0.023415223, -0.010665745 0.043147519 0.024458364, -0.013396919 0.04228361 0.023415193, -0.013975263 0.043151438 0.024458364, -0.04092139 0.0099826455 0.023934931, -0.041953161 0.010345131 0.023935243, -0.039834544 0.010103762 0.023935154, -0.042280734 0.013455838 0.023413554, -0.042961329 0.013238445 0.023935184, -0.043163344 0.0140118 0.024456799, -0.039615497 0.010783806 0.02341345, -0.039061591 0.0098999739 0.024456322, -0.043085292 0.012152106 0.023935214, -0.04272534 0.011119321 0.02393505, -0.031518474 -0.030915812 0.023932651, -0.031233966 -0.029859915 0.023932949, -0.031316444 -0.031990632 0.02393277, -0.030668288 -0.032871082 0.023932606, -0.028988451 -0.029076591 0.023411438, -0.02951695 -0.028595805 0.023932964, -0.028948084 -0.028034538 0.02445437, -0.029969797 -0.032720804 0.023411095, -0.030458152 -0.03364259 0.024454072, -0.030519709 -0.029031888 0.023932695, 0.043361574 -0.011127412 0.023934081, 0.042531863 -0.011839658 0.023933813, 0.043800205 -0.010125741 0.023934051, 0.039674073 -0.010568231 0.023412287, 0.039522052 -0.011266395 0.023933798, 0.038751453 -0.01105459 0.024455354, 0.043320954 -0.0095959157 0.023412451, 0.044363126 -0.0095584393 0.024455443, 0.040401146 -0.011916652 0.023933768, 0.041475371 -0.012121484 0.023933738, 0.032685682 0.031493992 0.024457723, 0.032124177 0.030615315 0.02341485, 0.03192541 0.031291917 0.023936301, 0.029148132 0.028902158 0.023414642, 0.02866295 0.029413745 0.023936093, 0.028106257 0.028857678 0.024457499, 0.030871123 0.031432047 0.023936212, 0.029856265 0.031113386 0.023936152, 0.029071078 0.03039594 0.023936227, -0.044503778 -0.0087287426 0.015391186, -0.042941958 -0.014586389 0.015390709, 0.029810548 -0.034178019 0.015389666, 0.034102485 -0.029896796 0.0153898, 0.014692992 0.04290472 0.015394062, 0.014485091 0.043478101 0.015393943, -0.043696985 -0.014285326 0.015390739, 0.01418063 0.044006661 0.015393972, -0.044362023 -0.013818637 0.015390813, 0.034219116 -0.030701026 0.015389919, 0.034147292 -0.031510592 0.01538983, -0.044901446 -0.013210803 0.015390798, 0.033890784 -0.032281652 0.015389651, 0.033463404 -0.032972828 0.015389696, -0.04500854 -0.0093655437 0.015391052, 0.032888025 -0.03354682 0.015389755, -0.045286223 -0.012494922 0.015390903, -0.04549554 -0.01170972 0.015390947, 0.032195747 -0.033972293 0.015389562, -0.045352891 -0.010101706 0.015390933, 0.031424001 -0.034227014 0.015389845, -0.04551819 -0.010897428 0.015391022, 0.030614391 -0.03429696 0.015389726, -0.034290627 -0.040569052 0.026900679, -0.034108326 -0.040353388 0.02704449, -0.03072679 -0.043331042 0.026900366, -0.030563548 -0.04310064 0.027044103, -0.026941493 -0.045780838 0.026900247, -0.026798353 -0.045537397 0.027043968, -0.022962123 -0.047900468 0.026900053, -0.022840038 -0.047645837 0.027043834, -0.018817171 -0.04967536 0.026899964, -0.018717319 -0.049411297 0.02704373, -0.014536902 -0.051092148 0.026899964, -0.014459565 -0.050820708 0.027043656, -0.01015164 -0.052140921 0.026899725, -0.010097742 -0.051863715 0.027043715, -0.0056931823 -0.052814156 0.026899859, -0.0056630522 -0.052533284 0.027043656, -0.001193881 -0.053106591 0.026899695, -0.001187712 -0.052824378 0.027043536, 0.0033137798 -0.053016454 0.0268998, 0.0032963455 -0.052734688 0.0270437, 0.0077979714 -0.05254443 0.0268998, 0.0077566206 -0.052265286 0.027043626, 0.012225837 -0.051693812 0.026899874, 0.012160853 -0.051419109 0.027043611, 0.016565546 -0.050470799 0.026899964, 0.016477525 -0.050202504 0.027043611, 0.020786017 -0.048884049 0.026900008, 0.020675555 -0.048624322 0.027043864, 0.024856642 -0.046945274 0.026899993, 0.024724588 -0.046695739 0.027043864, 0.028748378 -0.044668213 0.026900202, 0.028595418 -0.044430748 0.027044117, 0.03243272 -0.042069227 0.026900411, 0.032260224 -0.041845664 0.027044162, 0.035883382 -0.039167151 0.026900545, 0.035692677 -0.038959071 0.027044296, 0.039075643 -0.035982996 0.026900768, 0.038867995 -0.035791531 0.027044594, 0.041986153 -0.032539442 0.026901081, 0.041763172 -0.032366484 0.027044833, 0.044594526 -0.028861627 0.02690126, 0.044357449 -0.028708234 0.027045116, 0.046881273 -0.024975598 0.026901364, 0.046632171 -0.024843037 0.027045146, 0.04883033 -0.02090992 0.026901767, 0.048570886 -0.020798773 0.027045235, 0.050427556 -0.016693354 0.026901856, 0.050159633 -0.016604811 0.027045533, 0.051661611 -0.012356833 0.026902333, 0.051386893 -0.012291074 0.027045891, 0.05252327 -0.0079310536 0.026902407, 0.052243963 -0.0078888386 0.027046084, 0.053006545 -0.0034481138 0.026902676, 0.052724883 -0.0034300089 0.027046323, 0.053107962 0.0010593683 0.02690275, 0.052825585 0.0010538101 0.027046591, 0.052826643 0.0055596083 0.026903287, 0.052545786 0.0055299103 0.027046755, 0.052164659 0.010019451 0.026903138, 0.051887438 0.0099663138 0.027047157, 0.051126748 0.014407247 0.026903674, 0.050855145 0.01433067 0.027047321, 0.049720719 0.018691421 0.026903898, 0.049456447 0.018591836 0.027047604, 0.047956467 0.022840604 0.026903987, 0.047701478 0.022719115 0.027047664, 0.045846507 0.026825204 0.026904315, 0.045602784 0.026682779 0.027047962, 0.043406308 0.030616701 0.026904434, 0.043175668 0.03045392 0.02704829, 0.040653184 0.034187391 0.026904643, 0.040437132 0.034005791 0.027048498, 0.010126993 -0.042099163 0.023898602, 0.0099490285 -0.0422135 0.023898751, 0.0097490996 -0.042282283 0.023898736, 0.0099898279 -0.042297632 0.023927197, 0.0097688437 -0.042373925 0.023927227, 0.0097872317 -0.042458281 0.02397345, 0.0095341504 -0.042482197 0.02397339, 0.0095363259 -0.042395785 0.023927271, 0.010273039 -0.041946396 0.023898795, 0.010186642 -0.042171642 0.023927227, 0.010027483 -0.042375505 0.023973405, 0.010378912 -0.041763514 0.023898736, 0.009282589 -0.042445734 0.02397342, 0.010348022 -0.042002589 0.023927212, 0.010241494 -0.042238355 0.02397345, 0.010438755 -0.041560605 0.023898974, 0.010465205 -0.041800514 0.023927286, 0.010417208 -0.042054549 0.02397345, 0.010449231 -0.04134953 0.023898751, 0.010531262 -0.041576222 0.023927376, 0.010544628 -0.041834638 0.023973465, 0.01040931 -0.041141838 0.023898795, 0.010542691 -0.04134284 0.023927286, 0.010616571 -0.04159072 0.023973465, 0.010321811 -0.040949374 0.023898765, 0.010498732 -0.041113272 0.023927256, 0.010628968 -0.041336879 0.023973629, 0.010401994 -0.040900648 0.023927227, 0.010581106 -0.04108724 0.02397351, 0.0093294233 -0.042271718 0.023898765, 0.0095384568 -0.042302042 0.02389881, 0.010475799 -0.040855691 0.023973435, 0.0093049556 -0.042362228 0.023927465, -0.028784737 -0.029976845 0.023974195, -0.028807223 -0.03006044 0.023927733, -0.028831586 -0.030150846 0.02389954, -0.029341459 -0.03204447 0.023974061, -0.029319078 -0.031961054 0.023927838, -0.02929464 -0.031870559 0.023899391, -0.029044002 -0.030120373 0.023899332, -0.029257625 -0.030141845 0.023899257, -0.029990688 -0.031339929 0.023927793, -0.029884949 -0.031552553 0.023927793, -0.029902399 -0.031308591 0.023899332, -0.029806525 -0.031500742 0.023899332, -0.030072063 -0.031368926 0.023974046, -0.030128643 -0.031116962 0.023974121, -0.030042648 -0.031108499 0.023928031, -0.029041991 -0.030026734 0.023927912, -0.029493734 -0.031790316 0.023899212, -0.029459998 -0.030213714 0.023899242, -0.02966769 -0.031664461 0.023899257, -0.029731467 -0.031733274 0.023927838, -0.029278249 -0.030050144 0.023927927, -0.029957131 -0.031599879 0.023974076, -0.029040337 -0.029940158 0.023974329, -0.029539093 -0.031872258 0.023927838, -0.029639214 -0.030331746 0.023899421, -0.029790163 -0.031796724 0.023974076, -0.029501781 -0.03012979 0.023927942, -0.029580742 -0.031947896 0.023973972, -0.029297084 -0.029965907 0.023974076, -0.029785007 -0.030489385 0.023899481, -0.029699937 -0.030260161 0.023927823, -0.029540315 -0.030052245 0.023974121, -0.029888898 -0.030677199 0.02389957, -0.029861137 -0.030434459 0.023927897, -0.029755771 -0.030194208 0.023974121, -0.029944599 -0.030884653 0.023899332, -0.029975742 -0.030642167 0.023927972, -0.029931143 -0.030383795 0.023974016, -0.029949188 -0.031099185 0.023899302, -0.030037552 -0.030871183 0.023927957, -0.03005597 -0.030609652 0.023974255, -0.03012304 -0.030858934 0.023974195, -0.029710636 -0.033415586 0.025499314, -0.029703304 -0.033388272 0.025405496, -0.030118436 -0.033266634 0.02549921, -0.029691279 -0.033343583 0.025319219, -0.030106425 -0.033240795 0.025405571, -0.030494094 -0.033049077 0.025499329, -0.030086756 -0.033199072 0.025319174, -0.030477807 -0.033025965 0.025405541, -0.030451208 -0.032988071 0.025319263, 0.010208383 -0.039007291 0.025498748, 0.010201067 -0.03903468 0.025405139, 0.010189071 -0.039079383 0.025318891, 0.0089133531 -0.043816745 0.025498778, 0.0089206547 -0.043789208 0.02540496, 0.008932665 -0.043744653 0.025318578, 0.011848971 -0.04239516 0.025498703, 0.011529878 -0.042889968 0.02540496, 0.011552766 -0.042906865 0.025498748, 0.010616258 -0.039156258 0.025498956, 0.011822879 -0.042384028 0.025405273, 0.011988133 -0.041823268 0.025405139, 0.011780396 -0.04236576 0.025318697, 0.010991856 -0.03937383 0.025498971, 0.01194264 -0.041815624 0.025318652, 0.010646239 -0.043653637 0.025498778, 0.010604098 -0.039181948 0.025405258, 0.011144087 -0.043334484 0.025498793, 0.011324003 -0.039653197 0.025498897, 0.011126012 -0.04331252 0.02540496, 0.011492968 -0.042862356 0.025318667, 0.01097545 -0.039396971 0.025405183, 0.010087222 -0.043846279 0.025498569, 0.010584652 -0.039223984 0.025318727, 0.011688918 -0.040118575 0.025498956, 0.010633871 -0.043627962 0.02540499, 0.011096686 -0.043276787 0.025318548, 0.011303797 -0.039673299 0.025405154, 0.0094984025 -0.043901578 0.025498629, 0.010948926 -0.039434806 0.025318697, 0.011933863 -0.040656805 0.025498763, 0.010081187 -0.043818444 0.02540493, 0.011664718 -0.040133342 0.025405124, 0.010613739 -0.043586284 0.025318637, 0.0094992518 -0.043873399 0.025404915, 0.011271238 -0.039705887 0.025318772, 0.012045175 -0.041237518 0.025498867, 0.010071442 -0.043773264 0.025318548, 0.0095004588 -0.043827087 0.025318548, 0.011906952 -0.040665329 0.025405109, 0.011625201 -0.040157363 0.025318861, 0.012016341 -0.041828007 0.025498748, 0.012016743 -0.041239426 0.025405243, 0.011862919 -0.040679425 0.025318727, 0.011970654 -0.041242927 0.025318816, -0.040375635 0.010022894 0.025321513, -0.039848104 0.010142714 0.025321603, -0.039832994 0.010099068 0.02540791, -0.040370688 0.0099770576 0.025408179, -0.041970775 0.010316834 0.025501609, -0.038884372 0.010660633 0.025501758, -0.041468605 0.010074332 0.025501683, -0.040925235 0.0099495798 0.025501728, -0.041459203 0.01010111 0.02540794, -0.040922031 0.0099777728 0.025407895, -0.040916666 0.010023624 0.025321633, -0.041955605 0.010340855 0.025407955, -0.041443929 0.010144711 0.025321633, -0.041931003 0.01037997 0.025321692, -0.039320797 0.010313526 0.025501594, -0.039823592 0.010072067 0.025501683, -0.038904473 0.01068078 0.025408059, -0.039335981 0.010337651 0.025408074, -0.04036738 0.0099487603 0.025501743, -0.039360449 0.010376841 0.025321528, -0.038937211 0.010713592 0.025321573, -0.014082253 0.042435676 0.025503576, -0.014062226 0.042415738 0.025409833, -0.014029562 0.042383075 0.025323436, -0.010564685 0.038909614 0.025503308, -0.010584831 0.038929656 0.025409549, -0.010617405 0.038962349 0.025323048, -0.010213226 0.041995019 0.025503531, -0.0099986494 0.041482925 0.025409877, -0.0099718273 0.041492283 0.025503352, -0.010237336 0.041979879 0.025409743, -0.013143033 0.043024272 0.02550365, -0.01058048 0.042411432 0.025409847, -0.010276377 0.041955307 0.025323242, -0.010613263 0.042378798 0.025323227, -0.013645887 0.042782903 0.025503501, -0.0098491609 0.040390819 0.025503322, -0.013630778 0.042758912 0.025409818, -0.0098484159 0.04094848 0.025503427, -0.012599289 0.043147773 0.025503501, -0.0098767877 0.040945277 0.025409818, -0.010042399 0.041467831 0.025323451, -0.013133705 0.042997494 0.025409728, -0.0099737346 0.039847255 0.025503337, -0.01360625 0.042719752 0.02532357, -0.012041509 0.043147042 0.025503561, -0.0098772943 0.040393934 0.025409609, -0.012596041 0.043119475 0.025410131, -0.009922564 0.04094021 0.025323257, -0.010216445 0.039345145 0.025503293, -0.013118625 0.042954013 0.025323585, -0.011497974 0.043022215 0.025503531, -0.010000795 0.039856657 0.025409728, -0.012044787 0.043118805 0.025409877, -0.0099233389 0.040399194 0.025323331, -0.012590975 0.04307358 0.025323495, -0.010240555 0.039360359 0.02540952, -0.010996014 0.042779744 0.025503546, -0.010044217 0.039871871 0.025323212, -0.010279536 0.039384693 0.025323212, -0.011507422 0.042995393 0.025409758, -0.012050003 0.043072999 0.025323391, -0.010560423 0.042431414 0.025503501, -0.011011094 0.042755663 0.025409773, -0.011522979 0.042952001 0.025323346, -0.011035711 0.042716607 0.025323346, -0.041272044 0.01305446 0.023901775, -0.041484803 0.012934193 0.023930416, -0.04140459 0.012885571 0.02390179, -0.04059051 0.011535168 0.023901686, -0.040379435 0.011573628 0.023901835, -0.04153201 0.012478992 0.023901761, -0.04082188 0.011456221 0.023930207, -0.040585071 0.011441559 0.023930237, -0.040804699 0.011548296 0.023901671, -0.041493028 0.012690142 0.02390182, -0.04158251 0.012717977 0.023930207, -0.040837571 0.011371136 0.023976669, -0.041048244 0.011527136 0.023930326, -0.041083738 0.011448145 0.023976445, -0.04018344 0.011661351 0.023901835, -0.041399375 0.013182074 0.023976669, -0.041558743 0.012979209 0.023976684, -0.04133831 0.01312089 0.023930341, -0.040014416 0.011793628 0.023901671, -0.04151924 0.012264609 0.023901671, -0.040351614 0.011483893 0.023930222, -0.041625544 0.012484714 0.023930296, -0.0405799 0.011355221 0.023976535, -0.040135145 0.011581108 0.023930222, -0.039948061 0.01172708 0.023930147, -0.041665062 0.012743846 0.023976475, -0.041455612 0.012059703 0.023901924, -0.04032588 0.011401281 0.023976356, -0.040090412 0.01150699 0.023976445, -0.039886966 0.01166594 0.023976579, -0.041611642 0.012247905 0.023930311, -0.041711822 0.012490183 0.023976654, -0.041344836 0.011875689 0.023901701, -0.041541293 0.012021437 0.023930266, -0.041696638 0.012232468 0.023976699, -0.041193336 0.011723712 0.023901701, -0.041418731 0.011818007 0.023930237, -0.041620165 0.011985838 0.02397649, -0.041009605 0.01161246 0.023901775, -0.041251063 0.011650026 0.023929983, -0.041486964 0.011764765 0.023976609, -0.041304588 0.011582106 0.02397652, -0.011567354 0.039914802 0.023978069, -0.011628419 0.039976075 0.023931876, -0.01169467 0.040042654 0.023903295, -0.011259615 0.040551618 0.023978069, -0.011313528 0.040318131 0.023977995, -0.011394918 0.040346697 0.023931697, -0.011345595 0.040561512 0.023931846, -0.011568993 0.041145787 0.023903489, -0.011482656 0.040966004 0.023903355, -0.011438549 0.040771574 0.023903415, -0.011394173 0.040996835 0.023931935, -0.011345327 0.040781766 0.023931906, -0.011259586 0.040791407 0.023978338, -0.011489481 0.041195422 0.02393204, -0.011312336 0.041025177 0.023978114, -0.011416286 0.041241407 0.023978129, -0.011570185 0.040198207 0.023903295, -0.011483401 0.040377885 0.02390334, -0.011490792 0.040148228 0.023931876, -0.011438757 0.040572226 0.023903444, -0.011417717 0.040102065 0.023978084, 0.042421028 -0.0093900263 0.023975328, 0.032116666 0.029259801 0.023977578, 0.042337537 -0.009412393 0.023929179, 0.032033116 0.029237598 0.023931295, 0.042246774 -0.0094365925 0.023900598, 0.031942472 0.029213533 0.023902863, 0.031889588 0.029359281 0.023902565, 0.031974614 0.029399008 0.023931086, 0.031812131 0.029493868 0.023902833, 0.032053068 0.029435247 0.023977429, 0.031889096 0.029547498 0.023931205, 0.031959981 0.029596955 0.023977369, 0.042063981 -0.010243684 0.023900703, 0.042266533 -0.010106742 0.023929149, 0.042182535 -0.010064781 0.023900688, 0.042135447 -0.010304451 0.023929134, 0.040606022 -0.010094404 0.023900464, 0.040731266 -0.010268852 0.023900449, 0.042201191 -0.010360673 0.023975387, 0.042011291 -0.010535315 0.023975357, 0.040435463 -0.0099194348 0.023929089, 0.040523842 -0.010139674 0.02392903, 0.040526122 -0.0098953992 0.023900554, 0.041960835 -0.01046522 0.023929045, 0.042276889 -0.0096490681 0.023900524, 0.042254999 -0.009862721 0.023900554, 0.040894508 -0.010408208 0.023900554, 0.042346418 -0.0098832548 0.023929089, 0.04066214 -0.010332271 0.023929104, 0.042343661 -0.01014556 0.023975238, 0.04044795 -0.010181278 0.023975268, 0.040352002 -0.0099416375 0.023975268, 0.042370662 -0.00964728 0.023929089, 0.04108654 -0.010504067 0.023900479, 0.042430624 -0.0099025071 0.023975447, 0.042457119 -0.0096456707 0.023975387, 0.040842876 -0.01048632 0.023929134, 0.040598541 -0.010390878 0.023975462, 0.041295752 -0.010551631 0.023900539, 0.041054949 -0.010592535 0.023928925, 0.040794998 -0.010558441 0.023975194, 0.041510507 -0.010547563 0.023900628, 0.041286394 -0.010645047 0.02392903, 0.041025802 -0.010674059 0.023975492, 0.041717902 -0.01049231 0.02390033, 0.041523561 -0.010640591 0.023929015, 0.041277498 -0.010731146 0.023975149, 0.041905999 -0.010388941 0.023900673, 0.041752964 -0.010579377 0.023929, 0.041535795 -0.010726258 0.023975313, 0.041784942 -0.010659769 0.023975313, 0.02867575 0.028342366 0.025502831, 0.028703317 0.028349623 0.025409058, 0.028747842 0.028361589 0.025322586, 0.030676782 0.031412095 0.025409311, 0.031257465 0.031393513 0.025322676, 0.031260788 0.031439468 0.025409102, 0.030684546 0.031366706 0.025322676, 0.028592274 0.028927729 0.025502846, 0.028649315 0.029516429 0.025502712, 0.032845274 0.030742615 0.025502861, 0.02862075 0.028928518 0.025409237, 0.032380909 0.031108767 0.02550295, 0.028843358 0.030074984 0.025502712, 0.031843394 0.031355202 0.02550295, 0.032366112 0.031084403 0.025409102, 0.031834677 0.031328037 0.025409132, 0.028677136 0.029510364 0.025409177, 0.031820387 0.031283975 0.025322676, 0.033123881 0.030409619 0.02550289, 0.028666988 0.028929576 0.025322631, 0.029163614 0.030571878 0.025502786, 0.032825142 0.030722618 0.025409251, 0.032342136 0.031045139 0.025322825, 0.028868958 0.030062497 0.025409102, 0.033340454 0.030033648 0.025502831, 0.028722107 0.02950047 0.025322571, 0.033488452 0.02962549 0.025502801, 0.029592007 0.03097941 0.025502965, 0.033100635 0.030393451 0.025409311, 0.032792464 0.030690044 0.025322706, 0.029185399 0.030553937 0.025409088, 0.033314571 0.030021667 0.025409222, 0.033461034 0.029618055 0.025409341, 0.028910458 0.030042231 0.025322661, 0.033062816 0.030367076 0.025322676, 0.030104637 0.031274527 0.025502875, 0.033272877 0.030002207 0.025322825, 0.033416286 0.029606283 0.025322676, 0.029609069 0.03095673 0.025409102, 0.029221222 0.030524388 0.025322691, 0.030672297 0.031440243 0.025502861, 0.030115724 0.03124842 0.025409177, 0.02963683 0.030919686 0.02532278, 0.03126277 0.031467736 0.02550292, 0.030133784 0.031205893 0.025322869, 0.043304875 -0.011254147 0.025500506, 0.043625191 -0.010756984 0.02550061, 0.043792814 -0.0090244412 0.025500566, 0.043791622 -0.010192424 0.025406942, 0.04359965 -0.010744557 0.025406897, 0.043819293 -0.010198474 0.025500506, 0.043746293 -0.010182485 0.02532047, 0.043801591 -0.0096116066 0.025320455, 0.043847814 -0.0096105784 0.025407031, 0.042876467 -0.011661634 0.025500476, 0.043283001 -0.011236057 0.025406733, 0.043558165 -0.010724232 0.025320455, 0.043720677 -0.0090436637 0.025320545, 0.042363882 -0.011956364 0.025500432, 0.042859375 -0.011638641 0.025406942, 0.043247372 -0.011206478 0.025320455, 0.041796297 -0.012122557 0.025500491, 0.04235284 -0.011930391 0.025406912, 0.042831808 -0.011601761 0.025320426, 0.041205794 -0.012149975 0.025500476, 0.041791797 -0.012094378 0.025406733, 0.042334616 -0.011887848 0.025320366, 0.04062514 -0.012037411 0.025500461, 0.04120779 -0.012121528 0.025406912, 0.041784033 -0.012048885 0.025320411, 0.040087774 -0.011790946 0.025500417, 0.040633902 -0.012010172 0.025406912, 0.043876261 -0.0096098781 0.025500447, 0.041211084 -0.012075335 0.025320306, 0.040102482 -0.011766568 0.025406718, 0.043765306 -0.0090318173 0.025406912, 0.040648043 -0.011966318 0.025320396, 0.040126547 -0.011727065 0.025320351 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 3, 1, 0, -1, 4, 5, 6, -1, 7, 1, 3, -1, 2, 1, 8, -1, 9, 5, 4, -1, 10, 11, 12, -1, 9, 13, 5, -1, 12, 11, 14, -1, 15, 13, 9, -1, 15, 16, 13, -1, 17, 16, 15, -1, 10, 18, 11, -1, 19, 20, 17, -1, 21, 18, 10, -1, 21, 22, 18, -1, 23, 20, 24, -1, 17, 20, 16, -1, 25, 22, 21, -1, 24, 20, 19, -1, 26, 27, 28, -1, 29, 27, 26, -1, 30, 31, 25, -1, 25, 31, 22, -1, 8, 32, 30, -1, 29, 33, 27, -1, 30, 32, 31, -1, 6, 33, 29, -1, 34, 35, 7, -1, 8, 35, 32, -1, 7, 35, 1, -1, 1, 35, 8, -1, 6, 36, 33, -1, 5, 36, 6, -1, 11, 37, 14, -1, 5, 38, 36, -1, 13, 38, 5, -1, 14, 37, 39, -1, 40, 41, 42, -1, 16, 43, 13, -1, 18, 44, 11, -1, 11, 44, 37, -1, 13, 43, 38, -1, 20, 45, 16, -1, 23, 45, 20, -1, 16, 45, 43, -1, 46, 45, 23, -1, 22, 47, 18, -1, 18, 47, 44, -1, 28, 48, 49, -1, 31, 50, 22, -1, 27, 48, 28, -1, 22, 50, 47, -1, 33, 51, 27, -1, 27, 51, 48, -1, 32, 52, 31, -1, 31, 52, 50, -1, 53, 54, 34, -1, 36, 55, 33, -1, 34, 54, 35, -1, 33, 55, 51, -1, 35, 54, 32, -1, 32, 54, 52, -1, 37, 56, 39, -1, 38, 57, 36, -1, 36, 57, 55, -1, 39, 56, 58, -1, 43, 59, 38, -1, 37, 60, 56, -1, 38, 59, 57, -1, 45, 61, 43, -1, 44, 60, 37, -1, 46, 61, 45, -1, 62, 61, 46, -1, 43, 61, 59, -1, 47, 63, 44, -1, 44, 63, 60, -1, 48, 64, 49, -1, 49, 64, 65, -1, 47, 66, 63, -1, 50, 66, 47, -1, 51, 67, 48, -1, 48, 67, 64, -1, 52, 68, 50, -1, 50, 68, 66, -1, 69, 70, 53, -1, 53, 70, 54, -1, 52, 70, 68, -1, 54, 70, 52, -1, 55, 71, 51, -1, 51, 71, 67, -1, 56, 72, 58, -1, 55, 73, 71, -1, 57, 73, 55, -1, 58, 72, 74, -1, 60, 75, 56, -1, 59, 76, 57, -1, 56, 75, 72, -1, 57, 76, 73, -1, 77, 78, 62, -1, 62, 78, 61, -1, 61, 78, 59, -1, 60, 79, 75, -1, 63, 79, 60, -1, 59, 78, 76, -1, 64, 80, 65, -1, 66, 81, 63, -1, 65, 80, 82, -1, 63, 81, 79, -1, 67, 83, 64, -1, 64, 83, 80, -1, 68, 84, 66, -1, 66, 84, 81, -1, 85, 86, 69, -1, 69, 86, 70, -1, 67, 87, 83, -1, 70, 86, 68, -1, 71, 87, 67, -1, 68, 86, 84, -1, 72, 88, 74, -1, 73, 89, 71, -1, 71, 89, 87, -1, 74, 88, 90, -1, 76, 91, 73, -1, 75, 92, 72, -1, 72, 92, 88, -1, 73, 91, 89, -1, 93, 94, 77, -1, 77, 94, 78, -1, 76, 94, 91, -1, 78, 94, 76, -1, 75, 95, 92, -1, 79, 95, 75, -1, 82, 96, 97, -1, 80, 96, 82, -1, 79, 98, 95, -1, 81, 98, 79, -1, 83, 99, 80, -1, 81, 100, 98, -1, 84, 100, 81, -1, 80, 99, 96, -1, 86, 101, 84, -1, 84, 101, 100, -1, 87, 102, 83, -1, 103, 101, 85, -1, 83, 102, 99, -1, 85, 101, 86, -1, 90, 104, 105, -1, 87, 106, 102, -1, 89, 106, 87, -1, 88, 104, 90, -1, 89, 107, 106, -1, 92, 108, 88, -1, 91, 107, 89, -1, 91, 109, 107, -1, 88, 108, 104, -1, 110, 109, 93, -1, 95, 111, 92, -1, 93, 109, 94, -1, 94, 109, 91, -1, 92, 111, 108, -1, 97, 112, 113, -1, 96, 112, 97, -1, 98, 114, 95, -1, 95, 114, 111, -1, 96, 115, 112, -1, 98, 116, 114, -1, 99, 115, 96, -1, 100, 116, 98, -1, 117, 118, 103, -1, 103, 118, 101, -1, 99, 119, 115, -1, 100, 118, 116, -1, 101, 118, 100, -1, 105, 120, 121, -1, 102, 119, 99, -1, 106, 122, 102, -1, 104, 120, 105, -1, 102, 122, 119, -1, 107, 123, 106, -1, 106, 123, 122, -1, 108, 124, 104, -1, 109, 125, 107, -1, 104, 124, 120, -1, 110, 125, 109, -1, 107, 125, 123, -1, 108, 126, 124, -1, 111, 126, 108, -1, 127, 125, 110, -1, 112, 128, 113, -1, 113, 128, 129, -1, 111, 130, 126, -1, 114, 130, 111, -1, 112, 131, 128, -1, 116, 132, 114, -1, 114, 132, 130, -1, 115, 131, 112, -1, 133, 134, 117, -1, 117, 134, 118, -1, 118, 134, 116, -1, 115, 135, 131, -1, 116, 134, 132, -1, 121, 136, 137, -1, 119, 135, 115, -1, 119, 138, 135, -1, 120, 136, 121, -1, 122, 138, 119, -1, 123, 139, 122, -1, 122, 139, 138, -1, 124, 140, 120, -1, 125, 141, 123, -1, 127, 141, 125, -1, 120, 140, 136, -1, 142, 141, 127, -1, 126, 143, 124, -1, 123, 141, 139, -1, 124, 143, 140, -1, 128, 144, 129, -1, 130, 145, 126, -1, 129, 144, 146, -1, 126, 145, 143, -1, 128, 147, 144, -1, 132, 148, 130, -1, 131, 147, 128, -1, 130, 148, 145, -1, 149, 150, 133, -1, 133, 150, 134, -1, 134, 150, 132, -1, 135, 151, 131, -1, 132, 150, 148, -1, 137, 152, 153, -1, 131, 151, 147, -1, 138, 154, 135, -1, 136, 152, 137, -1, 135, 154, 151, -1, 136, 155, 152, -1, 139, 156, 138, -1, 140, 155, 136, -1, 138, 156, 154, -1, 157, 158, 142, -1, 139, 158, 156, -1, 142, 158, 141, -1, 141, 158, 139, -1, 143, 159, 140, -1, 144, 160, 146, -1, 140, 159, 155, -1, 145, 161, 143, -1, 143, 161, 159, -1, 146, 160, 162, -1, 147, 163, 144, -1, 148, 164, 145, -1, 144, 163, 160, -1, 145, 164, 161, -1, 165, 166, 149, -1, 149, 166, 150, -1, 150, 166, 148, -1, 151, 167, 147, -1, 148, 166, 164, -1, 147, 167, 163, -1, 153, 168, 169, -1, 169, 168, 170, -1, 151, 171, 167, -1, 152, 168, 153, -1, 154, 171, 151, -1, 156, 172, 154, -1, 170, 173, 174, -1, 154, 172, 171, -1, 152, 173, 168, -1, 155, 173, 152, -1, 175, 176, 157, -1, 168, 173, 170, -1, 157, 176, 158, -1, 158, 176, 156, -1, 156, 176, 172, -1, 174, 177, 178, -1, 160, 179, 162, -1, 155, 177, 173, -1, 159, 177, 155, -1, 162, 179, 180, -1, 173, 177, 174, -1, 178, 181, 182, -1, 160, 183, 179, -1, 161, 181, 159, -1, 163, 183, 160, -1, 177, 181, 178, -1, 159, 181, 177, -1, 182, 184, 185, -1, 167, 186, 163, -1, 164, 184, 161, -1, 163, 186, 183, -1, 161, 184, 181, -1, 171, 187, 167, -1, 181, 184, 182, -1, 164, 188, 184, -1, 185, 188, 189, -1, 189, 188, 190, -1, 190, 188, 191, -1, 167, 187, 186, -1, 191, 188, 165, -1, 184, 188, 185, -1, 166, 188, 164, -1, 172, 192, 171, -1, 165, 188, 166, -1, 171, 192, 187, -1, 193, 194, 175, -1, 175, 194, 176, -1, 176, 194, 172, -1, 172, 194, 192, -1, 180, 195, 196, -1, 179, 195, 180, -1, 183, 197, 179, -1, 179, 197, 195, -1, 183, 198, 197, -1, 186, 198, 183, -1, 186, 199, 198, -1, 187, 199, 186, -1, 187, 200, 199, -1, 192, 200, 187, -1, 169, 170, 201, -1, 192, 202, 200, -1, 203, 202, 193, -1, 193, 202, 194, -1, 194, 202, 192, -1, 195, 204, 196, -1, 196, 204, 205, -1, 197, 206, 195, -1, 195, 206, 204, -1, 198, 207, 197, -1, 197, 207, 206, -1, 208, 209, 210, -1, 199, 211, 198, -1, 198, 211, 207, -1, 210, 209, 212, -1, 200, 213, 199, -1, 208, 214, 209, -1, 199, 213, 211, -1, 215, 214, 208, -1, 202, 216, 200, -1, 203, 216, 202, -1, 200, 216, 213, -1, 217, 216, 203, -1, 218, 219, 215, -1, 204, 220, 205, -1, 215, 219, 214, -1, 218, 221, 219, -1, 205, 220, 222, -1, 223, 221, 218, -1, 206, 224, 204, -1, 204, 224, 220, -1, 223, 225, 221, -1, 226, 225, 223, -1, 41, 227, 42, -1, 42, 227, 226, -1, 226, 227, 225, -1, 206, 228, 224, -1, 207, 228, 206, -1, 212, 229, 230, -1, 211, 231, 207, -1, 209, 229, 212, -1, 207, 231, 228, -1, 209, 232, 229, -1, 213, 233, 211, -1, 211, 233, 231, -1, 214, 232, 209, -1, 234, 235, 217, -1, 216, 235, 213, -1, 217, 235, 216, -1, 214, 236, 232, -1, 219, 236, 214, -1, 213, 235, 233, -1, 221, 237, 219, -1, 219, 237, 236, -1, 220, 238, 222, -1, 222, 238, 239, -1, 224, 240, 220, -1, 221, 241, 237, -1, 225, 241, 221, -1, 220, 240, 238, -1, 225, 242, 241, -1, 243, 242, 41, -1, 41, 242, 227, -1, 224, 244, 240, -1, 227, 242, 225, -1, 228, 244, 224, -1, 229, 245, 230, -1, 230, 245, 246, -1, 231, 247, 228, -1, 232, 248, 229, -1, 228, 247, 244, -1, 229, 248, 245, -1, 233, 249, 231, -1, 231, 249, 247, -1, 236, 250, 232, -1, 251, 252, 234, -1, 234, 252, 235, -1, 235, 252, 233, -1, 232, 250, 248, -1, 233, 252, 249, -1, 236, 253, 250, -1, 238, 254, 239, -1, 237, 253, 236, -1, 239, 254, 255, -1, 238, 256, 254, -1, 237, 257, 253, -1, 241, 257, 237, -1, 240, 256, 238, -1, 241, 258, 257, -1, 242, 258, 241, -1, 243, 258, 242, -1, 259, 258, 243, -1, 244, 260, 240, -1, 240, 260, 256, -1, 245, 261, 246, -1, 246, 261, 262, -1, 247, 263, 244, -1, 244, 263, 260, -1, 249, 264, 247, -1, 248, 265, 245, -1, 247, 264, 263, -1, 245, 265, 261, -1, 266, 267, 251, -1, 251, 267, 252, -1, 250, 268, 248, -1, 249, 267, 264, -1, 252, 267, 249, -1, 248, 268, 265, -1, 254, 269, 255, -1, 250, 270, 268, -1, 253, 270, 250, -1, 255, 269, 271, -1, 257, 272, 253, -1, 256, 273, 254, -1, 253, 272, 270, -1, 254, 273, 269, -1, 258, 274, 257, -1, 259, 274, 258, -1, 275, 274, 259, -1, 256, 276, 273, -1, 257, 274, 272, -1, 260, 276, 256, -1, 261, 277, 262, -1, 262, 277, 278, -1, 263, 279, 260, -1, 260, 279, 276, -1, 265, 280, 261, -1, 264, 281, 263, -1, 261, 280, 277, -1, 263, 281, 279, -1, 282, 283, 266, -1, 266, 283, 267, -1, 264, 283, 281, -1, 268, 284, 265, -1, 267, 283, 264, -1, 265, 284, 280, -1, 270, 285, 268, -1, 271, 286, 287, -1, 268, 285, 284, -1, 269, 286, 271, -1, 272, 288, 270, -1, 269, 289, 286, -1, 270, 288, 285, -1, 275, 290, 274, -1, 273, 289, 269, -1, 291, 290, 275, -1, 272, 290, 288, -1, 274, 290, 272, -1, 273, 292, 289, -1, 277, 293, 278, -1, 276, 292, 273, -1, 279, 294, 276, -1, 278, 293, 295, -1, 276, 294, 292, -1, 280, 296, 277, -1, 277, 296, 293, -1, 281, 297, 279, -1, 279, 297, 294, -1, 283, 298, 281, -1, 280, 299, 296, -1, 284, 299, 280, -1, 300, 298, 282, -1, 281, 298, 297, -1, 282, 298, 283, -1, 286, 301, 287, -1, 287, 301, 302, -1, 285, 303, 284, -1, 284, 303, 299, -1, 288, 304, 285, -1, 286, 305, 301, -1, 285, 304, 303, -1, 291, 306, 290, -1, 289, 305, 286, -1, 288, 306, 304, -1, 290, 306, 288, -1, 307, 306, 291, -1, 293, 308, 295, -1, 289, 309, 305, -1, 292, 309, 289, -1, 294, 310, 292, -1, 295, 308, 311, -1, 292, 310, 309, -1, 296, 312, 293, -1, 297, 313, 294, -1, 293, 312, 308, -1, 294, 313, 310, -1, 298, 314, 297, -1, 299, 315, 296, -1, 300, 314, 298, -1, 296, 315, 312, -1, 316, 314, 300, -1, 297, 314, 313, -1, 301, 317, 302, -1, 303, 318, 299, -1, 299, 318, 315, -1, 302, 317, 319, -1, 303, 320, 318, -1, 301, 321, 317, -1, 304, 320, 303, -1, 307, 322, 306, -1, 305, 321, 301, -1, 304, 322, 320, -1, 306, 322, 304, -1, 309, 323, 305, -1, 324, 322, 307, -1, 305, 323, 321, -1, 308, 325, 311, -1, 310, 326, 309, -1, 311, 325, 327, -1, 312, 328, 308, -1, 309, 326, 323, -1, 310, 329, 326, -1, 313, 329, 310, -1, 308, 328, 325, -1, 330, 331, 316, -1, 316, 331, 314, -1, 315, 332, 312, -1, 314, 331, 313, -1, 313, 331, 329, -1, 312, 332, 328, -1, 317, 333, 319, -1, 318, 334, 315, -1, 315, 334, 332, -1, 319, 333, 335, -1, 320, 336, 318, -1, 321, 337, 317, -1, 317, 337, 333, -1, 318, 336, 334, -1, 322, 338, 320, -1, 324, 338, 322, -1, 320, 338, 336, -1, 323, 339, 321, -1, 340, 338, 324, -1, 321, 339, 337, -1, 325, 341, 327, -1, 326, 342, 323, -1, 327, 341, 343, -1, 323, 342, 339, -1, 328, 344, 325, -1, 325, 344, 341, -1, 329, 345, 326, -1, 326, 345, 342, -1, 332, 346, 328, -1, 347, 348, 330, -1, 330, 348, 331, -1, 331, 348, 329, -1, 329, 348, 345, -1, 328, 346, 344, -1, 334, 349, 332, -1, 333, 350, 335, -1, 332, 349, 346, -1, 335, 350, 351, -1, 337, 352, 333, -1, 336, 353, 334, -1, 334, 353, 349, -1, 333, 352, 350, -1, 354, 355, 340, -1, 338, 355, 336, -1, 340, 355, 338, -1, 336, 355, 353, -1, 337, 356, 352, -1, 339, 356, 337, -1, 341, 357, 343, -1, 343, 357, 358, -1, 342, 359, 339, -1, 344, 360, 341, -1, 339, 359, 356, -1, 345, 361, 342, -1, 341, 360, 357, -1, 342, 361, 359, -1, 362, 363, 347, -1, 346, 364, 344, -1, 345, 363, 361, -1, 347, 363, 348, -1, 348, 363, 345, -1, 344, 364, 360, -1, 350, 365, 351, -1, 349, 366, 346, -1, 351, 365, 367, -1, 346, 366, 364, -1, 350, 368, 365, -1, 353, 369, 349, -1, 352, 368, 350, -1, 349, 369, 366, -1, 370, 371, 354, -1, 354, 371, 355, -1, 352, 372, 368, -1, 355, 371, 353, -1, 353, 371, 369, -1, 356, 372, 352, -1, 357, 373, 358, -1, 358, 373, 374, -1, 356, 375, 372, -1, 359, 375, 356, -1, 359, 2, 375, -1, 357, 4, 373, -1, 360, 4, 357, -1, 361, 2, 359, -1, 361, 0, 2, -1, 3, 0, 362, -1, 362, 0, 363, -1, 364, 9, 360, -1, 363, 0, 361, -1, 360, 9, 4, -1, 367, 10, 12, -1, 366, 15, 364, -1, 364, 15, 9, -1, 365, 10, 367, -1, 369, 17, 366, -1, 368, 21, 365, -1, 366, 17, 15, -1, 365, 21, 10, -1, 24, 19, 370, -1, 370, 19, 371, -1, 372, 25, 368, -1, 369, 19, 17, -1, 371, 19, 369, -1, 373, 29, 374, -1, 368, 25, 21, -1, 374, 29, 26, -1, 375, 30, 372, -1, 372, 30, 25, -1, 2, 8, 375, -1, 373, 6, 29, -1, 375, 8, 30, -1, 4, 6, 373, -1, 376, 377, 378, -1, 379, 380, 381, -1, 378, 377, 382, -1, 381, 380, 383, -1, 376, 384, 377, -1, 385, 384, 376, -1, 386, 387, 388, -1, 388, 387, 389, -1, 379, 387, 380, -1, 390, 391, 392, -1, 389, 387, 379, -1, 392, 391, 393, -1, 393, 391, 385, -1, 385, 391, 384, -1, 394, 395, 396, -1, 397, 398, 399, -1, 400, 395, 394, -1, 399, 398, 401, -1, 402, 403, 400, -1, 397, 404, 398, -1, 405, 404, 397, -1, 400, 403, 395, -1, 402, 406, 403, -1, 405, 407, 404, -1, 408, 406, 402, -1, 382, 407, 405, -1, 382, 409, 407, -1, 408, 410, 406, -1, 383, 410, 408, -1, 377, 409, 382, -1, 380, 411, 383, -1, 383, 411, 410, -1, 377, 412, 409, -1, 387, 413, 380, -1, 384, 412, 377, -1, 380, 413, 411, -1, 384, 414, 412, -1, 415, 413, 386, -1, 386, 413, 387, -1, 416, 414, 390, -1, 390, 414, 391, -1, 391, 414, 384, -1, 396, 417, 418, -1, 395, 417, 396, -1, 401, 419, 420, -1, 398, 419, 401, -1, 395, 421, 417, -1, 398, 422, 419, -1, 403, 421, 395, -1, 406, 423, 403, -1, 404, 422, 398, -1, 407, 424, 404, -1, 403, 423, 421, -1, 404, 424, 422, -1, 406, 425, 423, -1, 409, 426, 407, -1, 410, 425, 406, -1, 407, 426, 424, -1, 411, 427, 410, -1, 412, 428, 409, -1, 410, 427, 425, -1, 411, 429, 427, -1, 409, 428, 426, -1, 415, 429, 413, -1, 414, 430, 412, -1, 416, 430, 414, -1, 431, 429, 415, -1, 413, 429, 411, -1, 432, 430, 416, -1, 417, 433, 418, -1, 412, 430, 428, -1, 419, 434, 420, -1, 418, 433, 435, -1, 421, 436, 417, -1, 420, 434, 437, -1, 417, 436, 433, -1, 422, 438, 419, -1, 419, 438, 434, -1, 423, 439, 421, -1, 424, 440, 422, -1, 421, 439, 436, -1, 425, 441, 423, -1, 422, 440, 438, -1, 424, 442, 440, -1, 426, 442, 424, -1, 423, 441, 439, -1, 427, 443, 425, -1, 426, 444, 442, -1, 425, 443, 441, -1, 428, 444, 426, -1, 427, 445, 443, -1, 429, 445, 427, -1, 431, 445, 429, -1, 446, 447, 432, -1, 448, 445, 431, -1, 432, 447, 430, -1, 430, 447, 428, -1, 428, 447, 444, -1, 433, 449, 435, -1, 434, 450, 437, -1, 435, 449, 451, -1, 436, 452, 433, -1, 437, 450, 453, -1, 433, 452, 449, -1, 438, 454, 434, -1, 434, 454, 450, -1, 439, 455, 436, -1, 440, 456, 438, -1, 436, 455, 452, -1, 438, 456, 454, -1, 441, 457, 439, -1, 439, 457, 455, -1, 442, 458, 440, -1, 440, 458, 456, -1, 441, 459, 457, -1, 443, 459, 441, -1, 442, 460, 458, -1, 444, 460, 442, -1, 445, 461, 443, -1, 462, 461, 448, -1, 463, 464, 446, -1, 448, 461, 445, -1, 446, 464, 447, -1, 443, 461, 459, -1, 447, 464, 444, -1, 444, 464, 460, -1, 449, 465, 451, -1, 450, 466, 453, -1, 451, 465, 467, -1, 453, 466, 468, -1, 452, 469, 449, -1, 449, 469, 465, -1, 454, 470, 450, -1, 450, 470, 466, -1, 455, 471, 452, -1, 452, 471, 469, -1, 456, 472, 454, -1, 454, 472, 470, -1, 457, 473, 455, -1, 456, 474, 472, -1, 458, 474, 456, -1, 455, 473, 471, -1, 457, 475, 473, -1, 459, 475, 457, -1, 458, 476, 474, -1, 460, 476, 458, -1, 477, 478, 462, -1, 462, 478, 461, -1, 461, 478, 459, -1, 479, 480, 463, -1, 463, 480, 464, -1, 459, 478, 475, -1, 464, 480, 460, -1, 460, 480, 476, -1, 467, 481, 482, -1, 465, 481, 467, -1, 466, 483, 468, -1, 468, 483, 484, -1, 469, 485, 465, -1, 465, 485, 481, -1, 470, 486, 466, -1, 466, 486, 483, -1, 469, 487, 485, -1, 471, 487, 469, -1, 470, 488, 486, -1, 472, 488, 470, -1, 473, 489, 471, -1, 474, 490, 472, -1, 471, 489, 487, -1, 473, 491, 489, -1, 472, 490, 488, -1, 475, 491, 473, -1, 476, 492, 474, -1, 474, 492, 490, -1, 475, 493, 491, -1, 494, 493, 477, -1, 495, 496, 479, -1, 477, 493, 478, -1, 479, 496, 480, -1, 478, 493, 475, -1, 480, 496, 476, -1, 476, 496, 492, -1, 482, 497, 498, -1, 481, 497, 482, -1, 483, 499, 484, -1, 481, 500, 497, -1, 484, 499, 501, -1, 486, 502, 483, -1, 485, 500, 481, -1, 483, 502, 499, -1, 485, 503, 500, -1, 486, 504, 502, -1, 487, 503, 485, -1, 488, 504, 486, -1, 487, 505, 503, -1, 488, 506, 504, -1, 489, 505, 487, -1, 490, 506, 488, -1, 491, 507, 489, -1, 489, 507, 505, -1, 490, 508, 506, -1, 493, 509, 491, -1, 492, 508, 490, -1, 494, 509, 493, -1, 491, 509, 507, -1, 496, 510, 492, -1, 492, 510, 508, -1, 511, 509, 494, -1, 512, 510, 495, -1, 495, 510, 496, -1, 501, 513, 514, -1, 498, 515, 516, -1, 497, 515, 498, -1, 500, 517, 497, -1, 499, 513, 501, -1, 497, 517, 515, -1, 499, 518, 513, -1, 502, 518, 499, -1, 503, 519, 500, -1, 504, 520, 502, -1, 500, 519, 517, -1, 502, 520, 518, -1, 505, 521, 503, -1, 506, 522, 504, -1, 504, 522, 520, -1, 503, 521, 519, -1, 507, 523, 505, -1, 508, 524, 506, -1, 505, 523, 521, -1, 509, 525, 507, -1, 506, 524, 522, -1, 511, 525, 509, -1, 526, 525, 511, -1, 527, 528, 512, -1, 507, 525, 523, -1, 512, 528, 510, -1, 508, 528, 524, -1, 510, 528, 508, -1, 515, 529, 516, -1, 514, 530, 531, -1, 513, 530, 514, -1, 516, 529, 532, -1, 515, 533, 529, -1, 518, 534, 513, -1, 517, 533, 515, -1, 513, 534, 530, -1, 519, 535, 517, -1, 520, 536, 518, -1, 517, 535, 533, -1, 518, 536, 534, -1, 521, 537, 519, -1, 519, 537, 535, -1, 520, 538, 536, -1, 521, 539, 537, -1, 522, 538, 520, -1, 523, 539, 521, -1, 524, 540, 522, -1, 522, 540, 538, -1, 541, 542, 526, -1, 526, 542, 525, -1, 525, 542, 523, -1, 543, 544, 527, -1, 527, 544, 528, -1, 523, 542, 539, -1, 528, 544, 524, -1, 524, 544, 540, -1, 531, 545, 546, -1, 529, 547, 532, -1, 530, 545, 531, -1, 532, 547, 548, -1, 533, 549, 529, -1, 529, 549, 547, -1, 534, 550, 530, -1, 533, 551, 549, -1, 530, 550, 545, -1, 536, 552, 534, -1, 534, 552, 550, -1, 535, 551, 533, -1, 537, 553, 535, -1, 536, 554, 552, -1, 538, 554, 536, -1, 535, 553, 551, -1, 537, 555, 553, -1, 539, 555, 537, -1, 540, 556, 538, -1, 557, 558, 541, -1, 538, 556, 554, -1, 541, 558, 542, -1, 542, 558, 539, -1, 559, 560, 543, -1, 543, 560, 544, -1, 539, 558, 555, -1, 544, 560, 540, -1, 540, 560, 556, -1, 546, 561, 562, -1, 547, 563, 548, -1, 545, 561, 546, -1, 548, 563, 564, -1, 547, 565, 563, -1, 545, 566, 561, -1, 549, 565, 547, -1, 567, 568, 569, -1, 550, 566, 545, -1, 551, 570, 549, -1, 549, 570, 565, -1, 552, 571, 550, -1, 550, 571, 566, -1, 551, 572, 570, -1, 553, 572, 551, -1, 552, 573, 571, -1, 554, 573, 552, -1, 555, 574, 553, -1, 556, 575, 554, -1, 553, 574, 572, -1, 576, 577, 557, -1, 578, 579, 580, -1, 554, 575, 573, -1, 557, 577, 558, -1, 555, 577, 574, -1, 581, 582, 559, -1, 558, 577, 555, -1, 559, 582, 560, -1, 560, 582, 556, -1, 583, 584, 585, -1, 556, 582, 575, -1, 564, 586, 587, -1, 585, 584, 588, -1, 562, 589, 567, -1, 563, 586, 564, -1, 567, 589, 568, -1, 583, 590, 584, -1, 561, 589, 562, -1, 563, 591, 586, -1, 592, 590, 583, -1, 565, 591, 563, -1, 568, 593, 594, -1, 561, 593, 589, -1, 565, 595, 591, -1, 596, 597, 592, -1, 566, 593, 561, -1, 589, 593, 568, -1, 592, 597, 590, -1, 570, 595, 565, -1, 594, 598, 599, -1, 596, 600, 597, -1, 570, 601, 595, -1, 593, 598, 594, -1, 602, 600, 596, -1, 572, 601, 570, -1, 571, 598, 566, -1, 602, 603, 600, -1, 566, 598, 593, -1, 572, 604, 601, -1, 599, 605, 606, -1, 607, 603, 602, -1, 573, 605, 571, -1, 574, 604, 572, -1, 608, 609, 610, -1, 611, 609, 607, -1, 574, 612, 604, -1, 610, 609, 611, -1, 607, 609, 603, -1, 598, 605, 599, -1, 613, 612, 576, -1, 571, 605, 598, -1, 576, 612, 577, -1, 606, 614, 615, -1, 577, 612, 574, -1, 586, 616, 587, -1, 588, 617, 618, -1, 573, 614, 605, -1, 605, 614, 606, -1, 575, 614, 573, -1, 584, 617, 588, -1, 614, 619, 615, -1, 587, 616, 620, -1, 584, 621, 617, -1, 615, 619, 580, -1, 575, 619, 614, -1, 578, 619, 581, -1, 580, 619, 578, -1, 581, 619, 582, -1, 582, 619, 575, -1, 590, 621, 584, -1, 586, 622, 616, -1, 590, 623, 621, -1, 591, 622, 586, -1, 597, 623, 590, -1, 595, 624, 591, -1, 591, 624, 622, -1, 601, 625, 595, -1, 597, 626, 623, -1, 595, 625, 624, -1, 600, 626, 597, -1, 600, 627, 626, -1, 604, 628, 601, -1, 601, 628, 625, -1, 603, 627, 600, -1, 603, 629, 627, -1, 609, 629, 603, -1, 612, 630, 604, -1, 613, 630, 612, -1, 631, 629, 608, -1, 604, 630, 628, -1, 608, 629, 609, -1, 617, 632, 618, -1, 633, 630, 613, -1, 616, 634, 620, -1, 618, 632, 635, -1, 620, 634, 636, -1, 621, 637, 617, -1, 617, 637, 632, -1, 622, 638, 616, -1, 621, 639, 637, -1, 616, 638, 634, -1, 624, 640, 622, -1, 622, 640, 638, -1, 623, 639, 621, -1, 623, 641, 639, -1, 624, 642, 640, -1, 626, 641, 623, -1, 626, 643, 641, -1, 627, 643, 626, -1, 625, 642, 624, -1, 628, 644, 625, -1, 629, 645, 627, -1, 625, 644, 642, -1, 646, 645, 631, -1, 628, 647, 644, -1, 631, 645, 629, -1, 648, 647, 633, -1, 627, 645, 643, -1, 630, 647, 628, -1, 633, 647, 630, -1, 635, 649, 650, -1, 634, 651, 636, -1, 632, 649, 635, -1, 636, 651, 652, -1, 637, 653, 632, -1, 632, 653, 649, -1, 638, 654, 634, -1, 639, 655, 637, -1, 634, 654, 651, -1, 637, 655, 653, -1, 640, 656, 638, -1, 638, 656, 654, -1, 641, 657, 639, -1, 639, 657, 655, -1, 640, 658, 656, -1, 642, 658, 640, -1, 643, 659, 641, -1, 641, 659, 657, -1, 644, 660, 642, -1, 646, 661, 645, -1, 642, 660, 658, -1, 662, 661, 646, -1, 643, 661, 659, -1, 663, 664, 648, -1, 645, 661, 643, -1, 647, 664, 644, -1, 648, 664, 647, -1, 649, 665, 650, -1, 644, 664, 660, -1, 651, 666, 652, -1, 650, 665, 667, -1, 653, 668, 649, -1, 652, 666, 669, -1, 649, 668, 665, -1, 651, 670, 666, -1, 654, 670, 651, -1, 653, 671, 668, -1, 655, 671, 653, -1, 654, 672, 670, -1, 656, 672, 654, -1, 657, 673, 655, -1, 655, 673, 671, -1, 658, 674, 656, -1, 656, 674, 672, -1, 659, 675, 657, -1, 660, 676, 658, -1, 657, 675, 673, -1, 661, 677, 659, -1, 662, 677, 661, -1, 658, 676, 674, -1, 678, 679, 663, -1, 680, 677, 662, -1, 663, 679, 664, -1, 659, 677, 675, -1, 664, 679, 660, -1, 665, 681, 667, -1, 660, 679, 676, -1, 667, 681, 682, -1, 666, 683, 669, -1, 669, 683, 684, -1, 668, 685, 665, -1, 670, 686, 666, -1, 666, 686, 683, -1, 665, 685, 681, -1, 671, 687, 668, -1, 670, 688, 686, -1, 668, 687, 685, -1, 672, 688, 670, -1, 671, 689, 687, -1, 674, 690, 672, -1, 673, 689, 671, -1, 673, 691, 689, -1, 675, 691, 673, -1, 672, 690, 688, -1, 674, 692, 690, -1, 676, 692, 674, -1, 675, 693, 691, -1, 680, 693, 677, -1, 676, 694, 692, -1, 695, 693, 680, -1, 696, 694, 678, -1, 677, 693, 675, -1, 678, 694, 679, -1, 679, 694, 676, -1, 682, 697, 698, -1, 681, 697, 682, -1, 684, 699, 700, -1, 683, 699, 684, -1, 683, 701, 699, -1, 681, 702, 697, -1, 685, 702, 681, -1, 687, 703, 685, -1, 686, 701, 683, -1, 685, 703, 702, -1, 686, 704, 701, -1, 688, 704, 686, -1, 687, 705, 703, -1, 690, 706, 688, -1, 689, 705, 687, -1, 691, 707, 689, -1, 688, 706, 704, -1, 692, 708, 690, -1, 690, 708, 706, -1, 689, 707, 705, -1, 695, 709, 693, -1, 693, 709, 691, -1, 696, 710, 694, -1, 692, 710, 708, -1, 711, 709, 695, -1, 691, 709, 707, -1, 712, 710, 696, -1, 694, 710, 692, -1, 699, 713, 700, -1, 697, 714, 698, -1, 698, 714, 715, -1, 700, 713, 716, -1, 702, 717, 697, -1, 701, 718, 699, -1, 697, 717, 714, -1, 702, 719, 717, -1, 699, 718, 713, -1, 703, 719, 702, -1, 701, 720, 718, -1, 704, 720, 701, -1, 705, 721, 703, -1, 703, 721, 719, -1, 706, 722, 704, -1, 704, 722, 720, -1, 707, 723, 705, -1, 705, 723, 721, -1, 709, 724, 707, -1, 706, 725, 722, -1, 711, 724, 709, -1, 708, 725, 706, -1, 707, 724, 723, -1, 710, 726, 708, -1, 727, 724, 711, -1, 712, 726, 710, -1, 728, 726, 712, -1, 708, 726, 725, -1, 714, 729, 715, -1, 713, 730, 716, -1, 715, 729, 731, -1, 716, 730, 732, -1, 717, 733, 714, -1, 718, 734, 713, -1, 714, 733, 729, -1, 713, 734, 730, -1, 719, 735, 717, -1, 720, 736, 718, -1, 717, 735, 733, -1, 718, 736, 734, -1, 721, 737, 719, -1, 720, 738, 736, -1, 719, 737, 735, -1, 722, 738, 720, -1, 723, 739, 721, -1, 721, 739, 737, -1, 725, 740, 722, -1, 741, 742, 727, -1, 722, 740, 738, -1, 724, 742, 723, -1, 743, 744, 728, -1, 727, 742, 724, -1, 728, 744, 726, -1, 723, 742, 739, -1, 726, 744, 725, -1, 725, 744, 740, -1, 729, 745, 731, -1, 731, 745, 746, -1, 730, 747, 732, -1, 733, 748, 729, -1, 732, 747, 749, -1, 734, 750, 730, -1, 729, 748, 745, -1, 730, 750, 747, -1, 735, 751, 733, -1, 734, 378, 750, -1, 733, 751, 748, -1, 736, 378, 734, -1, 735, 381, 751, -1, 737, 381, 735, -1, 738, 376, 736, -1, 736, 376, 378, -1, 739, 379, 737, -1, 738, 385, 376, -1, 737, 379, 381, -1, 740, 385, 738, -1, 741, 389, 742, -1, 388, 389, 741, -1, 742, 389, 739, -1, 392, 393, 743, -1, 739, 389, 379, -1, 743, 393, 744, -1, 744, 393, 740, -1, 740, 393, 385, -1, 745, 400, 746, -1, 746, 400, 394, -1, 747, 397, 749, -1, 749, 397, 399, -1, 745, 402, 400, -1, 748, 402, 745, -1, 747, 405, 397, -1, 750, 405, 747, -1, 751, 408, 748, -1, 378, 382, 750, -1, 748, 408, 402, -1, 381, 383, 751, -1, 750, 382, 405, -1, 751, 383, 408, -1, 752, 753, 754, -1, 755, 756, 757, -1, 755, 758, 756, -1, 759, 760, 761, -1, 759, 752, 760, -1, 762, 757, 763, -1, 762, 755, 757, -1, 764, 761, 765, -1, 766, 767, 768, -1, 764, 759, 761, -1, 766, 769, 767, -1, 770, 763, 771, -1, 770, 762, 763, -1, 772, 765, 773, -1, 774, 768, 775, -1, 772, 764, 765, -1, 774, 766, 768, -1, 776, 771, 777, -1, 776, 770, 771, -1, 778, 773, 779, -1, 780, 775, 781, -1, 778, 772, 773, -1, 780, 774, 775, -1, 782, 777, 783, -1, 782, 776, 777, -1, 784, 779, 785, -1, 784, 778, 779, -1, 786, 781, 787, -1, 786, 780, 781, -1, 788, 783, 789, -1, 788, 782, 783, -1, 790, 785, 791, -1, 792, 787, 793, -1, 790, 784, 785, -1, 792, 786, 787, -1, 794, 789, 795, -1, 794, 788, 789, -1, 796, 790, 791, -1, 797, 795, 798, -1, 797, 794, 795, -1, 796, 791, 799, -1, 800, 793, 801, -1, 800, 792, 793, -1, 802, 796, 799, -1, 802, 799, 803, -1, 804, 801, 805, -1, 804, 800, 801, -1, 806, 802, 803, -1, 806, 803, 807, -1, 808, 805, 809, -1, 808, 804, 805, -1, 810, 806, 807, -1, 810, 807, 811, -1, 812, 809, 813, -1, 812, 808, 809, -1, 814, 810, 811, -1, 814, 811, 815, -1, 816, 813, 817, -1, 816, 812, 813, -1, 818, 814, 815, -1, 818, 815, 819, -1, 820, 817, 821, -1, 820, 816, 817, -1, 822, 818, 819, -1, 822, 819, 823, -1, 824, 821, 825, -1, 824, 820, 821, -1, 826, 822, 823, -1, 826, 823, 827, -1, 828, 825, 829, -1, 828, 824, 825, -1, 830, 827, 831, -1, 832, 829, 833, -1, 830, 826, 827, -1, 832, 828, 829, -1, 834, 831, 835, -1, 834, 830, 831, -1, 836, 833, 837, -1, 836, 832, 833, -1, 838, 835, 839, -1, 838, 834, 835, -1, 840, 837, 841, -1, 840, 836, 837, -1, 842, 839, 843, -1, 842, 838, 839, -1, 844, 841, 845, -1, 844, 840, 841, -1, 846, 843, 847, -1, 846, 842, 843, -1, 753, 845, 754, -1, 753, 844, 845, -1, 758, 847, 756, -1, 758, 846, 847, -1, 752, 754, 760, -1, 848, 849, 850, -1, 851, 850, 852, -1, 851, 848, 850, -1, 853, 852, 854, -1, 853, 851, 852, -1, 855, 854, 856, -1, 855, 853, 854, -1, 857, 856, 858, -1, 857, 855, 856, -1, 859, 858, 860, -1, 859, 857, 858, -1, 861, 859, 860, -1, 862, 860, 863, -1, 862, 863, 864, -1, 862, 861, 860, -1, 865, 864, 866, -1, 865, 862, 864, -1, 867, 866, 868, -1, 867, 865, 866, -1, 869, 868, 870, -1, 869, 867, 868, -1, 871, 870, 872, -1, 871, 869, 870, -1, 873, 872, 874, -1, 873, 871, 872, -1, 875, 873, 874, -1, 876, 877, 878, -1, 876, 879, 877, -1, 880, 878, 881, -1, 880, 876, 878, -1, 882, 880, 881, -1, 883, 881, 884, -1, 883, 882, 881, -1, 885, 883, 884, -1, 886, 884, 887, -1, 886, 885, 884, -1, 888, 887, 889, -1, 888, 886, 887, -1, 890, 889, 891, -1, 890, 888, 889, -1, 892, 891, 893, -1, 892, 890, 891, -1, 894, 893, 895, -1, 894, 892, 893, -1, 896, 895, 897, -1, 896, 894, 895, -1, 898, 897, 899, -1, 898, 896, 897, -1, 900, 898, 899, -1, 901, 899, 902, -1, 901, 900, 899, -1, 903, 902, 904, -1, 903, 901, 902, -1, 905, 904, 906, -1, 905, 903, 904, -1, 907, 906, 908, -1, 907, 905, 906, -1, 909, 907, 908, -1, 910, 902, 899, -1, 910, 904, 902, -1, 910, 911, 869, -1, 910, 899, 911, -1, 912, 871, 873, -1, 912, 873, 875, -1, 912, 906, 904, -1, 912, 910, 871, -1, 912, 904, 910, -1, 913, 878, 877, -1, 913, 877, 848, -1, 913, 848, 914, -1, 913, 914, 878, -1, 915, 875, 908, -1, 915, 908, 906, -1, 915, 912, 875, -1, 915, 906, 912, -1, 914, 848, 851, -1, 914, 851, 853, -1, 914, 881, 878, -1, 916, 853, 855, -1, 916, 884, 881, -1, 916, 914, 853, -1, 916, 881, 914, -1, 917, 855, 857, -1, 917, 857, 859, -1, 917, 887, 884, -1, 917, 889, 887, -1, 917, 916, 855, -1, 917, 884, 916, -1, 918, 859, 861, -1, 918, 891, 889, -1, 918, 917, 859, -1, 918, 889, 917, -1, 919, 861, 862, -1, 919, 893, 891, -1, 919, 895, 893, -1, 919, 891, 918, -1, 919, 918, 861, -1, 920, 862, 865, -1, 920, 897, 895, -1, 920, 919, 862, -1, 920, 895, 919, -1, 911, 865, 867, -1, 911, 867, 869, -1, 911, 899, 897, -1, 911, 897, 920, -1, 911, 920, 865, -1, 910, 869, 871, -1, 921, 922, 923, -1, 921, 924, 925, -1, 926, 927, 928, -1, 921, 929, 924, -1, 921, 925, 930, -1, 921, 930, 922, -1, 931, 932, 933, -1, 931, 933, 934, -1, 931, 934, 935, -1, 936, 937, 926, -1, 938, 931, 935, -1, 936, 939, 937, -1, 938, 932, 931, -1, 940, 933, 932, -1, 940, 941, 933, -1, 942, 943, 944, -1, 940, 945, 941, -1, 946, 947, 948, -1, 946, 949, 947, -1, 950, 938, 935, -1, 950, 951, 952, -1, 950, 932, 938, -1, 950, 952, 932, -1, 950, 935, 951, -1, 953, 945, 940, -1, 953, 923, 922, -1, 954, 949, 946, -1, 953, 922, 945, -1, 954, 928, 949, -1, 955, 953, 940, -1, 956, 926, 928, -1, 957, 952, 958, -1, 956, 928, 954, -1, 959, 936, 926, -1, 957, 932, 952, -1, 959, 926, 956, -1, 960, 943, 961, -1, 962, 958, 963, -1, 960, 964, 943, -1, 962, 957, 958, -1, 965, 966, 957, -1, 965, 957, 962, -1, 967, 968, 969, -1, 967, 970, 968, -1, 971, 962, 963, -1, 971, 965, 962, -1, 971, 963, 972, -1, 971, 972, 973, -1, 974, 965, 971, -1, 974, 966, 965, -1, 974, 975, 966, -1, 976, 970, 967, -1, 974, 973, 977, -1, 974, 971, 973, -1, 976, 978, 970, -1, 979, 956, 954, -1, 980, 981, 978, -1, 980, 978, 976, -1, 982, 983, 984, -1, 982, 984, 959, -1, 982, 985, 983, -1, 982, 956, 979, -1, 982, 979, 986, -1, 987, 988, 981, -1, 982, 959, 956, -1, 987, 981, 980, -1, 989, 967, 969, -1, 990, 988, 987, -1, 990, 991, 988, -1, 992, 978, 981, -1, 993, 967, 989, -1, 994, 995, 985, -1, 994, 996, 995, -1, 994, 988, 996, -1, 993, 976, 967, -1, 994, 992, 981, -1, 994, 997, 992, -1, 998, 991, 990, -1, 994, 981, 988, -1, 998, 999, 1000, -1, 1001, 1002, 964, -1, 998, 1000, 991, -1, 1001, 1003, 1004, -1, 1001, 964, 1003, -1, 1005, 1004, 983, -1, 1006, 969, 1007, -1, 1005, 983, 985, -1, 1005, 1002, 1001, -1, 1006, 989, 969, -1, 1005, 1008, 1002, -1, 1005, 985, 995, -1, 1005, 995, 1008, -1, 1005, 1001, 1004, -1, 1009, 976, 993, -1, 1010, 1011, 1012, -1, 1010, 1013, 1014, -1, 1009, 980, 976, -1, 1010, 1012, 1013, -1, 1015, 989, 1006, -1, 1016, 1011, 1010, -1, 1016, 1017, 1011, -1, 1016, 1018, 1017, -1, 1015, 993, 989, -1, 1019, 987, 980, -1, 1019, 980, 1009, -1, 1020, 1016, 1010, -1, 1021, 1009, 993, -1, 1021, 993, 1015, -1, 1022, 990, 987, -1, 1022, 987, 1019, -1, 1023, 1019, 1009, -1, 1024, 1014, 1025, -1, 1024, 1025, 1026, -1, 1024, 1026, 1027, -1, 1023, 1009, 1021, -1, 1028, 998, 990, -1, 1028, 999, 998, -1, 1028, 990, 1022, -1, 1028, 1029, 999, -1, 1030, 1024, 1027, -1, 1031, 1006, 1007, -1, 1030, 1032, 1024, -1, 1030, 1027, 1033, -1, 1030, 1033, 1034, -1, 1035, 1022, 1019, -1, 1035, 1019, 1023, -1, 1036, 1037, 1038, -1, 1036, 1027, 1039, -1, 1036, 1039, 1037, -1, 1040, 1015, 1006, -1, 1040, 1006, 1031, -1, 1041, 1033, 1027, -1, 1041, 1034, 1033, -1, 1041, 1027, 1036, -1, 1042, 1022, 1035, -1, 1042, 1028, 1022, -1, 1042, 1029, 1028, -1, 1043, 1021, 1015, -1, 1044, 1041, 1036, -1, 1043, 1015, 1040, -1, 1045, 1038, 1046, -1, 1045, 1046, 1047, -1, 1048, 1007, 1049, -1, 1048, 1031, 1007, -1, 1050, 1023, 1021, -1, 1050, 1021, 1043, -1, 1051, 1031, 1048, -1, 1051, 1040, 1031, -1, 1052, 1053, 1045, -1, 1052, 1047, 1054, -1, 1055, 1035, 1023, -1, 1052, 1045, 1047, -1, 1055, 1023, 1050, -1, 1056, 1043, 1040, -1, 1057, 1052, 1054, -1, 1056, 1040, 1051, -1, 1057, 1058, 1059, -1, 1057, 1054, 1058, -1, 1060, 1059, 1061, -1, 1060, 1053, 1052, -1, 1062, 1042, 1035, -1, 1060, 1057, 1059, -1, 1062, 1029, 1042, -1, 1060, 1063, 1053, -1, 1062, 1035, 1055, -1, 1060, 1052, 1057, -1, 1062, 1064, 1029, -1, 1065, 1050, 1043, -1, 1066, 1067, 1068, -1, 1065, 1043, 1056, -1, 1066, 1058, 1067, -1, 1066, 1068, 1069, -1, 1070, 1061, 1059, -1, 1071, 1048, 1049, -1, 1070, 1058, 1066, -1, 1070, 1059, 1058, -1, 1072, 1055, 1050, -1, 1072, 1050, 1065, -1, 1073, 1070, 1066, -1, 1074, 1048, 1071, -1, 1074, 1051, 1048, -1, 1075, 1069, 1076, -1, 1077, 1062, 1055, -1, 1075, 1076, 1078, -1, 1077, 1064, 1062, -1, 1077, 1055, 1072, -1, 1079, 1056, 1051, -1, 1079, 1051, 1074, -1, 1080, 1049, 1081, -1, 1082, 1075, 1078, -1, 1080, 1071, 1049, -1, 1082, 1078, 1083, -1, 1084, 1065, 1056, -1, 1084, 1056, 1079, -1, 1085, 1075, 1082, -1, 1085, 1086, 1075, -1, 1087, 1074, 1071, -1, 1087, 1071, 1080, -1, 1088, 1089, 1090, -1, 1088, 1083, 1089, -1, 1091, 1072, 1065, -1, 1088, 1082, 1083, -1, 1088, 1085, 1082, -1, 1091, 1065, 1084, -1, 1092, 1090, 1093, -1, 1094, 1074, 1087, -1, 1092, 1088, 1090, -1, 1092, 1086, 1085, -1, 1094, 1079, 1074, -1, 1092, 1095, 1086, -1, 1092, 1085, 1088, -1, 1096, 1097, 1098, -1, 1099, 1100, 1064, -1, 1099, 1064, 1077, -1, 1096, 1101, 1097, -1, 1099, 1077, 1072, -1, 1096, 1098, 1102, -1, 1099, 1072, 1091, -1, 1103, 1096, 1102, -1, 1103, 1101, 1096, -1, 1104, 1080, 1081, -1, 1105, 1089, 1106, -1, 1107, 1079, 1094, -1, 1105, 1106, 1097, -1, 1105, 1097, 1101, -1, 1107, 1084, 1079, -1, 1108, 1102, 1109, -1, 1108, 1110, 1101, -1, 1111, 1087, 1080, -1, 1108, 1109, 1110, -1, 1108, 1103, 1102, -1, 1108, 1101, 1103, -1, 1112, 1090, 1089, -1, 1112, 1093, 1090, -1, 1111, 1080, 1104, -1, 1112, 1089, 1105, -1, 1113, 1084, 1107, -1, 1113, 1091, 1084, -1, 1114, 1087, 1111, -1, 1115, 1112, 1105, -1, 1116, 1101, 1110, -1, 1114, 1094, 1087, -1, 1116, 1110, 1117, -1, 1118, 1100, 1099, -1, 1118, 1099, 1091, -1, 1118, 1091, 1113, -1, 1119, 1081, 1120, -1, 1119, 1104, 1081, -1, 1121, 1107, 1094, -1, 1122, 1116, 1117, -1, 1122, 1117, 1123, -1, 1121, 1094, 1114, -1, 1124, 1111, 1104, -1, 1124, 1104, 1119, -1, 1125, 1107, 1121, -1, 1126, 1127, 1116, -1, 1126, 1116, 1122, -1, 1128, 1129, 1130, -1, 1125, 1113, 1107, -1, 1131, 1114, 1111, -1, 1132, 1123, 1133, -1, 1131, 1111, 1124, -1, 1132, 1122, 1123, -1, 1132, 1133, 1134, -1, 1132, 1126, 1122, -1, 1135, 1100, 1118, -1, 1135, 1118, 1113, -1, 1136, 1134, 1137, -1, 1135, 1113, 1125, -1, 1136, 1127, 1126, -1, 1135, 1138, 1100, -1, 1136, 1139, 1127, -1, 1136, 1132, 1134, -1, 1136, 1126, 1132, -1, 1140, 1119, 1120, -1, 1141, 1142, 1143, -1, 1141, 1144, 1142, -1, 1141, 1145, 1146, -1, 1141, 1147, 1144, -1, 1141, 1146, 1147, -1, 1148, 1121, 1114, -1, 1141, 1143, 1145, -1, 1148, 1114, 1131, -1, 1149, 1150, 1151, -1, 1149, 1142, 1144, -1, 1149, 1152, 1150, -1, 1153, 1124, 1119, -1, 1149, 1151, 1142, -1, 1154, 1144, 1147, -1, 1154, 1155, 1156, -1, 1153, 1119, 1140, -1, 1154, 1147, 1155, -1, 1154, 1157, 1152, -1, 1154, 1156, 1157, -1, 1158, 1159, 1160, -1, 1154, 1149, 1144, -1, 1161, 1125, 1121, -1, 1154, 1152, 1149, -1, 1161, 1121, 1148, -1, 1162, 1163, 1164, -1, 1162, 1165, 1166, -1, 1162, 1164, 1167, -1, 1168, 1169, 1170, -1, 1162, 1171, 1165, -1, 1162, 1167, 1171, -1, 1168, 1172, 1169, -1, 1162, 1166, 1173, -1, 1174, 1131, 1124, -1, 1162, 1173, 1163, -1, 1175, 1156, 1176, -1, 1175, 1166, 1165, -1, 1174, 1124, 1153, -1, 1175, 1176, 1166, -1, 1177, 1172, 1168, -1, 1175, 1157, 1156, -1, 1178, 1135, 1125, -1, 1179, 1175, 1165, -1, 1177, 1180, 1172, -1, 1178, 1138, 1135, -1, 1179, 1157, 1175, -1, 1179, 1181, 1182, -1, 1178, 1125, 1161, -1, 1179, 1165, 1171, -1, 1179, 1183, 1181, -1, 1179, 1171, 1183, -1, 1184, 1120, 1185, -1, 1179, 1182, 1157, -1, 1186, 1180, 1177, -1, 1184, 1140, 1120, -1, 1187, 1188, 1189, -1, 1187, 1190, 1191, -1, 1187, 1189, 1190, -1, 1186, 1192, 1180, -1, 1187, 1191, 1193, -1, 1187, 1193, 924, -1, 1194, 1148, 1131, -1, 1187, 929, 1188, -1, 1187, 924, 929, -1, 1195, 1181, 1196, -1, 1194, 1131, 1174, -1, 1195, 1182, 1181, -1, 1195, 1189, 1188, -1, 1197, 1192, 1186, -1, 1197, 1198, 1192, -1, 1195, 1196, 1189, -1, 1199, 1140, 1184, -1, 1200, 1195, 1188, -1, 1199, 1153, 1140, -1, 1200, 923, 1201, -1, 1200, 1201, 1182, -1, 1200, 1182, 1195, -1, 1202, 1198, 1197, -1, 1200, 1188, 929, -1, 1200, 921, 923, -1, 1202, 1203, 1198, -1, 1200, 929, 921, -1, 1204, 1205, 1203, -1, 1206, 1207, 955, -1, 1204, 1208, 1205, -1, 1206, 955, 940, -1, 1209, 1161, 1148, -1, 1206, 957, 966, -1, 1204, 1203, 1202, -1, 1209, 1148, 1194, -1, 1206, 932, 957, -1, 1204, 1210, 1208, -1, 1206, 975, 1207, -1, 1206, 966, 975, -1, 1206, 940, 932, -1, 1211, 953, 955, -1, 1211, 955, 1207, -1, 1212, 1170, 1213, -1, 1214, 1174, 1153, -1, 1211, 1201, 923, -1, 1212, 1168, 1170, -1, 1214, 1153, 1199, -1, 1211, 923, 953, -1, 1215, 1211, 1207, -1, 1216, 1168, 1212, -1, 1215, 1201, 1211, -1, 1215, 1207, 975, -1, 1217, 1138, 1178, -1, 1215, 974, 977, -1, 1216, 1177, 1168, -1, 1217, 1161, 1209, -1, 1215, 975, 974, -1, 1217, 1178, 1161, -1, 1215, 977, 1218, -1, 1215, 1218, 1201, -1, 1217, 1219, 1138, -1, 1220, 1184, 1185, -1, 1221, 954, 946, -1, 1221, 1222, 986, -1, 1221, 986, 979, -1, 1221, 946, 948, -1, 1221, 979, 954, -1, 1223, 1194, 1174, -1, 1224, 948, 968, -1, 1225, 1177, 1216, -1, 1223, 1174, 1214, -1, 1224, 1222, 1221, -1, 1225, 1186, 1177, -1, 1226, 1186, 1225, -1, 1224, 1221, 948, -1, 1227, 1224, 968, -1, 1228, 1184, 1220, -1, 1227, 968, 970, -1, 1227, 997, 1222, -1, 1226, 1197, 1186, -1, 1227, 992, 997, -1, 1228, 1199, 1184, -1, 1227, 1222, 1224, -1, 1227, 978, 992, -1, 1227, 970, 978, -1, 1229, 1197, 1226, -1, 1230, 1194, 1223, -1, 1231, 986, 1222, -1, 1230, 1209, 1194, -1, 1231, 982, 986, -1, 1229, 1202, 1197, -1, 1231, 994, 985, -1, 1231, 1222, 997, -1, 1231, 997, 994, -1, 1231, 985, 982, -1, 1232, 1204, 1202, -1, 1233, 1010, 1014, -1, 1232, 1202, 1229, -1, 1234, 1214, 1199, -1, 1233, 1235, 1020, -1, 1232, 1236, 1210, -1, 1233, 1020, 1010, -1, 1233, 1024, 1032, -1, 1232, 1210, 1204, -1, 1234, 1199, 1228, -1, 1233, 1014, 1024, -1, 1237, 1212, 1213, -1, 1233, 1032, 1235, -1, 1238, 1020, 1235, -1, 1238, 1239, 1018, -1, 1240, 1209, 1230, -1, 1238, 1018, 1016, -1, 1240, 1217, 1209, -1, 1238, 1016, 1020, -1, 1240, 1219, 1217, -1, 1237, 1213, 1241, -1, 1242, 1239, 1238, -1, 1242, 1238, 1235, -1, 1243, 1223, 1214, -1, 1242, 1030, 1034, -1, 1242, 1235, 1032, -1, 1244, 1216, 1212, -1, 1242, 1034, 1245, -1, 1242, 1032, 1030, -1, 1242, 1245, 1239, -1, 1243, 1214, 1234, -1, 1246, 1045, 1053, -1, 1244, 1212, 1237, -1, 1246, 1053, 1063, -1, 1246, 1063, 1247, -1, 1248, 1185, 1249, -1, 1246, 1044, 1036, -1, 1250, 1216, 1244, -1, 1246, 1038, 1045, -1, 1248, 1220, 1185, -1, 1246, 1036, 1038, -1, 1246, 1247, 1044, -1, 1251, 1245, 1034, -1, 1252, 1230, 1223, -1, 1251, 1034, 1041, -1, 1250, 1225, 1216, -1, 1251, 1044, 1247, -1, 1253, 1225, 1250, -1, 1251, 1041, 1044, -1, 1253, 1226, 1225, -1, 1254, 1245, 1251, -1, 1252, 1223, 1243, -1, 1254, 1251, 1247, -1, 1254, 1061, 1255, -1, 1256, 1220, 1248, -1, 1254, 1060, 1061, -1, 1254, 1247, 1063, -1, 1254, 1063, 1060, -1, 1256, 1228, 1220, -1, 1254, 1255, 1245, -1, 1257, 1073, 1066, -1, 1258, 1226, 1253, -1, 1257, 1066, 1069, -1, 1258, 1229, 1226, -1, 1257, 1069, 1075, -1, 1259, 1230, 1252, -1, 1257, 1075, 1086, -1, 1259, 1260, 1219, -1, 1257, 1095, 1261, -1, 1259, 1240, 1230, -1, 1257, 1086, 1095, -1, 1262, 1263, 1236, -1, 1257, 1261, 1073, -1, 1259, 1219, 1240, -1, 1264, 1255, 1061, -1, 1264, 1070, 1073, -1, 1265, 1237, 1241, -1, 1266, 1228, 1256, -1, 1264, 1061, 1070, -1, 1264, 1073, 1261, -1, 1267, 1093, 1268, -1, 1266, 1234, 1228, -1, 1267, 1255, 1264, -1, 1267, 1261, 1095, -1, 1265, 1241, 1269, -1, 1267, 1095, 1092, -1, 1270, 1244, 1237, -1, 1267, 1264, 1261, -1, 1267, 1092, 1093, -1, 1270, 1237, 1265, -1, 1267, 1268, 1255, -1, 1271, 1248, 1249, -1, 1272, 1101, 1116, -1, 1272, 1105, 1101, -1, 1273, 1243, 1234, -1, 1272, 1115, 1105, -1, 1272, 1116, 1127, -1, 1273, 1234, 1266, -1, 1272, 1274, 1115, -1, 1272, 1139, 1274, -1, 1272, 1127, 1139, -1, 1275, 1250, 1244, -1, 1276, 1268, 1093, -1, 1277, 1256, 1248, -1, 1276, 1112, 1115, -1, 1276, 1115, 1274, -1, 1276, 1093, 1112, -1, 1277, 1248, 1271, -1, 1278, 1137, 1159, -1, 1275, 1244, 1270, -1, 1278, 1268, 1276, -1, 1279, 1253, 1250, -1, 1278, 1139, 1136, -1, 1278, 1276, 1274, -1, 1280, 1252, 1243, -1, 1278, 1274, 1139, -1, 1278, 1136, 1137, -1, 1280, 1243, 1273, -1, 1278, 1159, 1268, -1, 1279, 1250, 1275, -1, 1281, 1253, 1279, -1, 1282, 1256, 1277, -1, 1281, 1258, 1253, -1, 1282, 1266, 1256, -1, 1283, 1284, 1263, -1, 1285, 1259, 1252, -1, 1286, 1265, 1269, -1, 1285, 1260, 1259, -1, 1285, 1252, 1280, -1, 1286, 1269, 1287, -1, 1288, 1273, 1266, -1, 1288, 1266, 1282, -1, 1289, 1265, 1286, -1, 1290, 1249, 1291, -1, 1289, 1270, 1265, -1, 1290, 1271, 1249, -1, 1292, 1270, 1289, -1, 1293, 1280, 1273, -1, 1292, 1275, 1270, -1, 1293, 1273, 1288, -1, 1294, 1277, 1271, -1, 1295, 1279, 1275, -1, 1294, 1271, 1290, -1, 1295, 1275, 1292, -1, 1296, 1260, 1285, -1, 1296, 1285, 1280, -1, 1296, 1280, 1293, -1, 1296, 1297, 1260, -1, 1298, 1284, 1299, -1, 1300, 1290, 1291, -1, 1298, 1301, 1284, -1, 1302, 1282, 1277, -1, 1303, 1287, 1304, -1, 1302, 1277, 1294, -1, 1303, 1286, 1287, -1, 1305, 1294, 1290, -1, 1306, 1286, 1303, -1, 1306, 1289, 1286, -1, 1305, 1290, 1300, -1, 1307, 1288, 1282, -1, 1308, 1303, 1304, -1, 1308, 1304, 1309, -1, 1307, 1282, 1302, -1, 1310, 1292, 1289, -1, 1311, 1302, 1294, -1, 1310, 1289, 1306, -1, 1311, 1294, 1305, -1, 1312, 1293, 1288, -1, 1313, 1303, 1308, -1, 1313, 1306, 1303, -1, 1312, 1288, 1307, -1, 1314, 1307, 1302, -1, 1315, 1292, 1310, -1, 1314, 1302, 1311, -1, 1316, 1296, 1293, -1, 1315, 1295, 1292, -1, 1316, 1297, 1296, -1, 1316, 1293, 1312, -1, 1317, 1310, 1306, -1, 1317, 1306, 1313, -1, 1318, 1291, 1319, -1, 1318, 1300, 1291, -1, 1320, 1307, 1314, -1, 1320, 1312, 1307, -1, 1321, 1310, 1317, -1, 1322, 1300, 1318, -1, 1321, 1315, 1310, -1, 1323, 1301, 1324, -1, 1322, 1305, 1300, -1, 1323, 1325, 1301, -1, 1326, 1312, 1320, -1, 1326, 1297, 1316, -1, 1327, 1308, 1309, -1, 1326, 1316, 1312, -1, 1326, 1328, 1297, -1, 1329, 1315, 1321, -1, 1329, 1324, 1315, -1, 1330, 1318, 1319, -1, 1331, 1311, 1305, -1, 1332, 1308, 1327, -1, 1331, 1305, 1322, -1, 1332, 1313, 1308, -1, 1333, 1323, 1324, -1, 1333, 1325, 1323, -1, 1334, 1318, 1330, -1, 1334, 1322, 1318, -1, 1333, 1324, 1329, -1, 1335, 1327, 1309, -1, 1336, 1314, 1311, -1, 1335, 1309, 1337, -1, 1336, 1311, 1331, -1, 1338, 1313, 1332, -1, 1339, 1331, 1322, -1, 1338, 1317, 1313, -1, 1340, 1332, 1327, -1, 1339, 1322, 1334, -1, 1340, 1327, 1335, -1, 1341, 1320, 1314, -1, 1342, 1321, 1317, -1, 1341, 1314, 1336, -1, 1342, 1317, 1338, -1, 1343, 1336, 1331, -1, 1344, 1338, 1332, -1, 1343, 1331, 1339, -1, 1344, 1332, 1340, -1, 1345, 1326, 1320, -1, 1345, 1328, 1326, -1, 1345, 1320, 1341, -1, 1346, 1329, 1321, -1, 1347, 1319, 1348, -1, 1347, 1330, 1319, -1, 1346, 1321, 1342, -1, 1349, 1338, 1344, -1, 1350, 1341, 1336, -1, 1349, 1342, 1338, -1, 1350, 1336, 1343, -1, 1351, 1325, 1333, -1, 1351, 1333, 1329, -1, 1351, 1329, 1346, -1, 1352, 1330, 1347, -1, 1351, 1353, 1325, -1, 1354, 1335, 1337, -1, 1352, 1334, 1330, -1, 1355, 1328, 1345, -1, 1355, 1345, 1341, -1, 1355, 1341, 1350, -1, 1355, 1356, 1328, -1, 1357, 1346, 1342, -1, 1357, 1342, 1349, -1, 1358, 1347, 1348, -1, 1359, 1339, 1334, -1, 1360, 1335, 1354, -1, 1360, 1340, 1335, -1, 1359, 1334, 1352, -1, 1361, 1346, 1357, -1, 1361, 1351, 1346, -1, 1361, 1353, 1351, -1, 1362, 1347, 1358, -1, 1363, 1337, 1364, -1, 1363, 1354, 1337, -1, 1362, 1352, 1347, -1, 1365, 1343, 1339, -1, 1365, 1339, 1359, -1, 1366, 1344, 1340, -1, 1366, 1340, 1360, -1, 1367, 1359, 1352, -1, 1367, 1352, 1362, -1, 1368, 1360, 1354, -1, 1369, 1350, 1343, -1, 1368, 1354, 1363, -1, 1369, 1343, 1365, -1, 1370, 1349, 1344, -1, 1370, 1344, 1366, -1, 1371, 1365, 1359, -1, 1371, 1359, 1367, -1, 1372, 1355, 1350, -1, 1372, 1356, 1355, -1, 1373, 1360, 1368, -1, 1372, 1350, 1369, -1, 1373, 1366, 1360, -1, 1374, 1369, 1365, -1, 1375, 1357, 1349, -1, 1374, 1365, 1371, -1, 1375, 1349, 1370, -1, 1376, 1348, 1377, -1, 1376, 1358, 1348, -1, 1378, 1370, 1366, -1, 1378, 1366, 1373, -1, 1379, 1369, 1374, -1, 1380, 1361, 1357, -1, 1379, 1356, 1372, -1, 1380, 1381, 1353, -1, 1379, 1372, 1369, -1, 1380, 1353, 1361, -1, 1380, 1357, 1375, -1, 1379, 1239, 1356, -1, 1382, 1362, 1358, -1, 1383, 1363, 1364, -1, 1382, 1358, 1376, -1, 1384, 1375, 1370, -1, 1384, 1370, 1378, -1, 1385, 1367, 1362, -1, 1386, 1363, 1383, -1, 1385, 1362, 1382, -1, 1386, 1368, 1363, -1, 1011, 1371, 1367, -1, 1387, 1375, 1384, -1, 1011, 1367, 1385, -1, 1387, 1381, 1380, -1, 1387, 1380, 1375, -1, 1017, 1374, 1371, -1, 1388, 1368, 1386, -1, 1017, 1371, 1011, -1, 1388, 1373, 1368, -1, 1018, 1379, 1374, -1, 1018, 1239, 1379, -1, 1018, 1374, 1017, -1, 1389, 1364, 1390, -1, 1389, 1383, 1364, -1, 1391, 1378, 1373, -1, 1391, 1373, 1388, -1, 1392, 1383, 1389, -1, 1392, 1386, 1383, -1, 1393, 1378, 1391, -1, 1393, 1384, 1378, -1, 1394, 1386, 1392, -1, 1394, 1388, 1386, -1, 1395, 1384, 1393, -1, 1395, 1396, 1381, -1, 1395, 1381, 1387, -1, 1395, 1387, 1384, -1, 1397, 1388, 1394, -1, 1397, 1391, 1388, -1, 1398, 1389, 1390, -1, 1399, 1393, 1391, -1, 1399, 1391, 1397, -1, 1400, 1389, 1398, -1, 1400, 1392, 1389, -1, 1401, 1395, 1393, -1, 1401, 1396, 1395, -1, 1401, 1393, 1399, -1, 1402, 1394, 1392, -1, 1402, 1392, 1400, -1, 1403, 1398, 1390, -1, 1403, 1390, 1404, -1, 1405, 1397, 1394, -1, 1405, 1394, 1402, -1, 1406, 1400, 1398, -1, 1406, 1398, 1403, -1, 1407, 1399, 1397, -1, 1407, 1397, 1405, -1, 1408, 1400, 1406, -1, 1408, 1402, 1400, -1, 1409, 1396, 1401, -1, 1409, 1401, 1399, -1, 1409, 1399, 1407, -1, 1409, 1410, 1396, -1, 1411, 1403, 1404, -1, 1412, 1405, 1402, -1, 1412, 1402, 1408, -1, 1413, 1406, 1403, -1, 1413, 1403, 1411, -1, 1414, 1129, 1128, -1, 1415, 1407, 1405, -1, 1415, 1405, 1412, -1, 1416, 1414, 1128, -1, 1417, 1408, 1406, -1, 1416, 1128, 1418, -1, 1417, 1406, 1413, -1, 1419, 1407, 1415, -1, 1419, 1409, 1407, -1, 1123, 1416, 1418, -1, 1419, 1410, 1409, -1, 1123, 1418, 1420, -1, 1421, 1404, 1422, -1, 1421, 1411, 1404, -1, 1133, 1123, 1420, -1, 1423, 1412, 1408, -1, 1133, 1420, 1424, -1, 1423, 1408, 1417, -1, 1134, 1133, 1424, -1, 1134, 1424, 1425, -1, 1426, 1413, 1411, -1, 1137, 1160, 1159, -1, 1426, 1411, 1421, -1, 1137, 1134, 1425, -1, 1137, 1425, 1160, -1, 1427, 1415, 1412, -1, 1428, 1229, 1258, -1, 1428, 1262, 1236, -1, 1427, 1412, 1423, -1, 1428, 1258, 1262, -1, 1428, 1232, 1229, -1, 1429, 1417, 1413, -1, 1428, 1236, 1232, -1, 1430, 1258, 1281, -1, 1430, 1281, 1283, -1, 1430, 1262, 1258, -1, 1429, 1413, 1426, -1, 1430, 1263, 1262, -1, 1430, 1283, 1263, -1, 1431, 1299, 1284, -1, 1432, 1433, 1410, -1, 1431, 1284, 1283, -1, 1432, 1419, 1415, -1, 1432, 1410, 1419, -1, 1432, 1415, 1427, -1, 1434, 1301, 1298, -1, 1434, 1324, 1301, -1, 1435, 1421, 1422, -1, 1436, 1437, 1438, -1, 1436, 1438, 1439, -1, 1440, 1417, 1429, -1, 1440, 1423, 1417, -1, 1441, 1436, 1439, -1, 1442, 1426, 1421, -1, 1442, 1421, 1435, -1, 1443, 1439, 1444, -1, 1443, 1441, 1439, -1, 1445, 1427, 1423, -1, 1443, 1444, 1446, -1, 1445, 1423, 1440, -1, 1447, 1446, 1444, -1, 1448, 1426, 1442, -1, 1447, 1449, 1446, -1, 1448, 1429, 1426, -1, 1450, 1447, 1444, -1, 1451, 1433, 1432, -1, 1451, 1427, 1445, -1, 1451, 1432, 1427, -1, 1452, 1422, 1453, -1, 1454, 1444, 1455, -1, 1452, 1435, 1422, -1, 1454, 1450, 1444, -1, 1454, 1455, 1456, -1, 1457, 1458, 1456, -1, 1459, 1429, 1448, -1, 1459, 1440, 1429, -1, 1457, 1456, 1455, -1, 1460, 1442, 1435, -1, 1460, 1435, 1452, -1, 1461, 1457, 1455, -1, 1462, 1440, 1459, -1, 1462, 1445, 1440, -1, 1463, 1464, 1465, -1, 1463, 1455, 1464, -1, 1463, 1461, 1455, -1, 1466, 1467, 1465, -1, 1468, 1442, 1460, -1, 1466, 1465, 1464, -1, 1468, 1448, 1442, -1, 1469, 1445, 1462, -1, 1469, 1451, 1445, -1, 1469, 1470, 1433, -1, 1469, 1433, 1451, -1, 1471, 1452, 1453, -1, 934, 1466, 1464, -1, 935, 934, 1464, -1, 935, 1464, 1472, -1, 935, 1472, 1473, -1, 1474, 1448, 1468, -1, 1475, 1476, 1477, -1, 1475, 1478, 1476, -1, 1474, 1459, 1448, -1, 1475, 1477, 1479, -1, 1475, 1480, 1478, -1, 1475, 1479, 1480, -1, 1481, 944, 1480, -1, 1482, 1452, 1471, -1, 1481, 942, 944, -1, 1482, 1460, 1452, -1, 1481, 1483, 942, -1, 1484, 1459, 1474, -1, 1485, 943, 942, -1, 1485, 961, 943, -1, 1484, 1462, 1459, -1, 1486, 1468, 1460, -1, 1003, 964, 960, -1, 1486, 1460, 1482, -1, 1002, 1000, 999, -1, 1487, 1469, 1462, -1, 1487, 1462, 1484, -1, 1487, 1470, 1469, -1, 1002, 999, 964, -1, 1488, 1474, 1468, -1, 1489, 1382, 1376, -1, 1489, 1376, 1377, -1, 1488, 1468, 1486, -1, 1490, 1471, 1453, -1, 1491, 1489, 1377, -1, 1490, 1453, 1492, -1, 1493, 1484, 1474, -1, 1494, 1491, 1377, -1, 1493, 1474, 1488, -1, 1494, 1377, 1495, -1, 1494, 1495, 1496, -1, 1497, 1482, 1471, -1, 1498, 1496, 1495, -1, 1497, 1471, 1490, -1, 1498, 1499, 1496, -1, 1500, 1487, 1484, -1, 1500, 1484, 1493, -1, 1500, 1470, 1487, -1, 1500, 1501, 1470, -1, 1502, 1486, 1482, -1, 1503, 1498, 1495, -1, 1502, 1482, 1497, -1, 1504, 1495, 1505, -1, 1504, 1503, 1495, -1, 1504, 1505, 1506, -1, 1507, 1490, 1492, -1, 1508, 1506, 1505, -1, 1508, 1509, 1506, -1, 1510, 1488, 1486, -1, 1510, 1486, 1502, -1, 1511, 1508, 1505, -1, 1512, 1497, 1490, -1, 1513, 1505, 1514, -1, 1512, 1490, 1507, -1, 1513, 1511, 1505, -1, 1515, 1493, 1488, -1, 1513, 1514, 1516, -1, 1515, 1488, 1510, -1, 1517, 1518, 1516, -1, 1517, 1516, 1514, -1, 1519, 1502, 1497, -1, 1519, 1497, 1512, -1, 1098, 1517, 1514, -1, 1520, 1500, 1493, -1, 1520, 1501, 1500, -1, 1520, 1493, 1515, -1, 1102, 1514, 1129, -1, 1102, 1098, 1514, -1, 1521, 1510, 1502, -1, 1102, 1129, 1414, -1, 1521, 1502, 1519, -1, 1522, 1281, 1279, -1, 1522, 1299, 1431, -1, 1522, 1283, 1281, -1, 1522, 1279, 1295, -1, 1523, 1492, 1524, -1, 1522, 1431, 1283, -1, 1522, 1295, 1299, -1, 1525, 1315, 1324, -1, 1525, 1434, 1298, -1, 1523, 1507, 1492, -1, 1525, 1298, 1299, -1, 1525, 1324, 1434, -1, 1525, 1295, 1315, -1, 1525, 1299, 1295, -1, 1526, 1515, 1510, -1, 1527, 1528, 1529, -1, 1527, 1529, 1437, -1, 1526, 1510, 1521, -1, 1530, 1512, 1507, -1, 1531, 1527, 1437, -1, 1531, 1436, 1441, -1, 1531, 1437, 1436, -1, 1530, 1507, 1523, -1, 1532, 1501, 1520, -1, 1532, 1533, 1501, -1, 1532, 1520, 1515, -1, 1532, 1515, 1526, -1, 1534, 1523, 1524, -1, 1145, 1531, 1441, -1, 1535, 1519, 1512, -1, 1536, 1443, 1446, -1, 1535, 1512, 1530, -1, 1536, 1446, 1449, -1, 1537, 1523, 1534, -1, 1538, 1145, 1441, -1, 1538, 1443, 1536, -1, 1538, 1441, 1443, -1, 1537, 1530, 1523, -1, 1539, 1536, 1449, -1, 1539, 1538, 1536, -1, 1540, 1521, 1519, -1, 1539, 1449, 1541, -1, 1539, 1541, 1542, -1, 1540, 1519, 1535, -1, 1543, 1535, 1530, -1, 1544, 1541, 1449, -1, 1544, 1542, 1541, -1, 1545, 1544, 1449, -1, 1543, 1530, 1537, -1, 1546, 1521, 1540, -1, 1545, 1449, 1447, -1, 1546, 1526, 1521, -1, 1545, 1447, 1450, -1, 1547, 1535, 1543, -1, 1547, 1540, 1535, -1, 1163, 1545, 1450, -1, 1548, 1526, 1546, -1, 1548, 1533, 1532, -1, 1548, 1532, 1526, -1, 1549, 1456, 1458, -1, 1550, 1524, 1551, -1, 1549, 1454, 1456, -1, 1550, 1534, 1524, -1, 1552, 1546, 1540, -1, 1552, 1540, 1547, -1, 1553, 1163, 1450, -1, 1553, 1450, 1454, -1, 1553, 1454, 1549, -1, 1554, 1458, 1555, -1, 1554, 1553, 1549, -1, 1554, 1549, 1458, -1, 1556, 1555, 1458, -1, 1557, 1534, 1550, -1, 1556, 1558, 1555, -1, 1557, 1537, 1534, -1, 1559, 1548, 1546, -1, 1559, 1546, 1552, -1, 1559, 1533, 1548, -1, 1560, 1457, 1461, -1, 1559, 1561, 1533, -1, 1560, 1458, 1457, -1, 1562, 1550, 1551, -1, 1560, 1556, 1458, -1, 1563, 1543, 1537, -1, 1191, 1560, 1461, -1, 1563, 1537, 1557, -1, 1564, 1557, 1550, -1, 1564, 1550, 1562, -1, 1565, 1465, 1467, -1, 1565, 1463, 1465, -1, 1566, 1543, 1563, -1, 1566, 1547, 1543, -1, 1567, 1463, 1565, -1, 1567, 1461, 1463, -1, 1567, 1191, 1461, -1, 1568, 1563, 1557, -1, 1568, 1557, 1564, -1, 1569, 1565, 1467, -1, 1569, 1467, 1570, -1, 1571, 1552, 1547, -1, 1569, 1567, 1565, -1, 1571, 1547, 1566, -1, 941, 1570, 1467, -1, 941, 945, 1570, -1, 1572, 1566, 1563, -1, 1572, 1563, 1568, -1, 933, 1467, 1466, -1, 1573, 1559, 1552, -1, 1573, 1561, 1559, -1, 933, 941, 1467, -1, 1573, 1552, 1571, -1, 933, 1466, 934, -1, 1438, 1551, 1439, -1, 1438, 1562, 1551, -1, 1574, 1566, 1572, -1, 1574, 1571, 1566, -1, 1437, 1564, 1562, -1, 951, 1473, 1575, -1, 951, 935, 1473, -1, 1437, 1562, 1438, -1, 1576, 1561, 1573, -1, 1576, 1573, 1571, -1, 958, 952, 951, -1, 1576, 1571, 1574, -1, 958, 951, 1575, -1, 1576, 1152, 1561, -1, 958, 1575, 963, -1, 1529, 1568, 1564, -1, 1577, 1479, 939, -1, 1577, 1480, 1479, -1, 1529, 1564, 1437, -1, 1577, 939, 936, -1, 1577, 1481, 1480, -1, 1577, 936, 1483, -1, 1577, 1483, 1481, -1, 1528, 1568, 1529, -1, 1578, 1483, 936, -1, 1528, 1572, 1568, -1, 1578, 1485, 942, -1, 1578, 942, 1483, -1, 1578, 936, 959, -1, 1578, 959, 961, -1, 1578, 961, 1485, -1, 1579, 1572, 1528, -1, 1579, 1574, 1572, -1, 1580, 961, 959, -1, 1580, 1003, 960, -1, 1580, 960, 961, -1, 1150, 1574, 1579, -1, 1150, 1576, 1574, -1, 1150, 1152, 1576, -1, 984, 1580, 959, -1, 1004, 984, 983, -1, 1004, 1580, 984, -1, 1004, 1003, 1580, -1, 996, 988, 991, -1, 1008, 991, 1000, -1, 1008, 995, 996, -1, 1008, 996, 991, -1, 1008, 1000, 1002, -1, 1012, 1385, 1382, -1, 1012, 1011, 1385, -1, 1013, 1489, 1491, -1, 1013, 1012, 1382, -1, 1013, 1382, 1489, -1, 1014, 1013, 1491, -1, 1581, 1494, 1496, -1, 1581, 1496, 1499, -1, 1025, 1491, 1494, -1, 1025, 1494, 1581, -1, 1025, 1014, 1491, -1, 1026, 1025, 1581, -1, 1026, 1581, 1499, -1, 1026, 1499, 1582, -1, 1026, 1582, 1027, -1, 1039, 1582, 1499, -1, 1039, 1027, 1582, -1, 1037, 1498, 1503, -1, 1037, 1499, 1498, -1, 1037, 1039, 1499, -1, 1038, 1037, 1503, -1, 1583, 1504, 1506, -1, 1583, 1506, 1509, -1, 1046, 1504, 1583, -1, 1046, 1503, 1504, -1, 1046, 1038, 1503, -1, 1047, 1046, 1583, -1, 1047, 1583, 1509, -1, 1047, 1509, 1054, -1, 1067, 1054, 1509, -1, 1067, 1058, 1054, -1, 1068, 1067, 1509, -1, 1068, 1509, 1508, -1, 1068, 1508, 1511, -1, 1069, 1068, 1511, -1, 1584, 1513, 1516, -1, 1584, 1516, 1518, -1, 1076, 1511, 1513, -1, 1076, 1069, 1511, -1, 1076, 1513, 1584, -1, 1585, 1472, 1586, -1, 1585, 1473, 1472, -1, 1078, 1518, 1083, -1, 1078, 1584, 1518, -1, 1078, 1076, 1584, -1, 1587, 1473, 1585, -1, 1106, 1083, 1518, -1, 1106, 1089, 1083, -1, 1587, 1575, 1473, -1, 1097, 1106, 1518, -1, 1588, 963, 1575, -1, 1097, 1518, 1517, -1, 1097, 1517, 1098, -1, 1588, 1575, 1587, -1, 1589, 972, 963, -1, 1589, 963, 1588, -1, 1590, 973, 972, -1, 1590, 972, 1589, -1, 1591, 977, 973, -1, 1109, 1414, 1416, -1, 1591, 1218, 977, -1, 1591, 973, 1590, -1, 1109, 1102, 1414, -1, 1591, 1592, 1218, -1, 1593, 1586, 1594, -1, 1593, 1585, 1586, -1, 1117, 1109, 1416, -1, 1117, 1110, 1109, -1, 1117, 1416, 1123, -1, 1595, 1585, 1593, -1, 1143, 1531, 1145, -1, 1595, 1587, 1585, -1, 1143, 1527, 1531, -1, 1143, 1528, 1527, -1, 1151, 1528, 1143, -1, 1596, 1587, 1595, -1, 1596, 1588, 1587, -1, 1151, 1579, 1528, -1, 1151, 1150, 1579, -1, 1142, 1151, 1143, -1, 1597, 1588, 1596, -1, 1597, 1589, 1588, -1, 1598, 1590, 1589, -1, 1598, 1589, 1597, -1, 1599, 1591, 1590, -1, 1599, 1592, 1591, -1, 1599, 1600, 1592, -1, 1599, 1590, 1598, -1, 1601, 1593, 1594, -1, 1146, 1538, 1539, -1, 1146, 1539, 1542, -1, 1601, 1594, 1602, -1, 1146, 1145, 1538, -1, 1155, 1146, 1542, -1, 1603, 1595, 1593, -1, 1155, 1147, 1146, -1, 1603, 1593, 1601, -1, 1155, 1542, 1604, -1, 1155, 1604, 1156, -1, 1605, 1596, 1595, -1, 1173, 1542, 1544, -1, 1173, 1544, 1545, -1, 1173, 1545, 1163, -1, 1605, 1595, 1603, -1, 1176, 1542, 1173, -1, 1606, 1597, 1596, -1, 1176, 1604, 1542, -1, 1176, 1156, 1604, -1, 1606, 1596, 1605, -1, 1166, 1176, 1173, -1, 1607, 1598, 1597, -1, 1607, 1597, 1606, -1, 1608, 1609, 1600, -1, 1608, 1600, 1599, -1, 1608, 1598, 1607, -1, 1164, 1163, 1553, -1, 1608, 1599, 1598, -1, 1164, 1553, 1554, -1, 1610, 1601, 1602, -1, 1610, 1602, 1611, -1, 1612, 1603, 1601, -1, 1612, 1601, 1610, -1, 1613, 1554, 1555, -1, 1613, 1164, 1554, -1, 1613, 1167, 1164, -1, 1614, 1603, 1612, -1, 1614, 1605, 1603, -1, 1615, 1555, 1558, -1, 1616, 1605, 1614, -1, 1615, 1558, 1617, -1, 1615, 1613, 1555, -1, 1183, 1617, 1181, -1, 1616, 1606, 1605, -1, 1183, 1167, 1613, -1, 1477, 1607, 1606, -1, 1183, 1171, 1167, -1, 1477, 1606, 1616, -1, 1183, 1615, 1617, -1, 1183, 1613, 1615, -1, 1190, 1560, 1191, -1, 1476, 1608, 1607, -1, 1476, 1607, 1477, -1, 1476, 1478, 1609, -1, 1190, 1558, 1556, -1, 1476, 1609, 1608, -1, 1190, 1556, 1560, -1, 1196, 1617, 1558, -1, 1196, 1181, 1617, -1, 1618, 1611, 1619, -1, 1618, 1610, 1611, -1, 1196, 1558, 1190, -1, 927, 1610, 1618, -1, 927, 1612, 1610, -1, 1189, 1196, 1190, -1, 937, 1614, 1612, -1, 937, 1612, 927, -1, 1193, 1191, 1567, -1, 1193, 1567, 1569, -1, 939, 1614, 937, -1, 939, 1616, 1614, -1, 1479, 1477, 1616, -1, 1620, 1193, 1569, -1, 1479, 1616, 939, -1, 1620, 1569, 1570, -1, 1480, 944, 1478, -1, 949, 1619, 947, -1, 949, 1618, 1619, -1, 925, 1193, 1620, -1, 925, 924, 1193, -1, 930, 1570, 945, -1, 928, 1618, 949, -1, 930, 945, 922, -1, 930, 925, 1620, -1, 928, 927, 1618, -1, 930, 1620, 1570, -1, 926, 937, 927, -1, 1621, 1622, 1623, -1, 1624, 1622, 1621, -1, 1625, 1626, 1627, -1, 1628, 1622, 1629, -1, 1627, 1626, 1630, -1, 1631, 1632, 1624, -1, 1629, 1632, 1631, -1, 1633, 1634, 1635, -1, 1624, 1632, 1622, -1, 1622, 1632, 1629, -1, 1635, 1634, 1636, -1, 1624, 1637, 1631, -1, 1638, 1639, 1640, -1, 1640, 1639, 1641, -1, 1631, 1637, 1642, -1, 1643, 1639, 1638, -1, 1637, 1644, 1642, -1, 1645, 1644, 1646, -1, 1642, 1644, 1645, -1, 1636, 1647, 1625, -1, 1624, 1644, 1637, -1, 1625, 1647, 1626, -1, 1648, 1649, 1624, -1, 1624, 1649, 1644, -1, 1644, 1649, 1646, -1, 1650, 1651, 1633, -1, 1633, 1651, 1634, -1, 1652, 1653, 1654, -1, 1655, 1653, 1652, -1, 1654, 1653, 1656, -1, 1634, 1657, 1636, -1, 1655, 1658, 1653, -1, 1636, 1657, 1647, -1, 1649, 1658, 1646, -1, 1648, 1658, 1649, -1, 1646, 1658, 1655, -1, 1641, 1659, 1650, -1, 1656, 1660, 1648, -1, 1650, 1659, 1651, -1, 1653, 1660, 1656, -1, 1658, 1660, 1653, -1, 1648, 1660, 1658, -1, 1648, 1661, 1656, -1, 1626, 1662, 1630, -1, 1656, 1661, 1654, -1, 1661, 1663, 1654, -1, 1651, 1664, 1634, -1, 1654, 1663, 1665, -1, 1634, 1664, 1657, -1, 1648, 1663, 1661, -1, 1665, 1663, 1666, -1, 1667, 1668, 1643, -1, 1669, 1670, 1648, -1, 1641, 1668, 1659, -1, 1643, 1668, 1639, -1, 1648, 1670, 1663, -1, 1639, 1668, 1641, -1, 1663, 1670, 1666, -1, 1626, 1671, 1662, -1, 1672, 1673, 1674, -1, 1675, 1673, 1672, -1, 1647, 1671, 1626, -1, 1670, 1676, 1666, -1, 1659, 1677, 1651, -1, 1669, 1676, 1670, -1, 1651, 1677, 1664, -1, 1666, 1676, 1675, -1, 1675, 1676, 1673, -1, 1678, 1679, 1669, -1, 1674, 1679, 1678, -1, 1657, 1680, 1647, -1, 1673, 1679, 1674, -1, 1669, 1679, 1676, -1, 1676, 1679, 1673, -1, 1647, 1680, 1671, -1, 1662, 1681, 1630, -1, 1630, 1681, 1682, -1, 1667, 1683, 1668, -1, 1668, 1683, 1659, -1, 1659, 1683, 1677, -1, 1664, 1684, 1657, -1, 1657, 1684, 1680, -1, 1662, 1685, 1681, -1, 1671, 1685, 1662, -1, 1677, 1686, 1664, -1, 1664, 1686, 1684, -1, 1671, 1687, 1685, -1, 1680, 1687, 1671, -1, 1681, 1688, 1682, -1, 1677, 1689, 1686, -1, 1690, 1689, 1667, -1, 1667, 1689, 1683, -1, 1683, 1689, 1677, -1, 1680, 1691, 1687, -1, 1684, 1691, 1680, -1, 1681, 1692, 1688, -1, 1685, 1692, 1681, -1, 1686, 1693, 1684, -1, 1684, 1693, 1691, -1, 1687, 1694, 1685, -1, 1685, 1694, 1692, -1, 1688, 1695, 1682, -1, 1682, 1695, 1696, -1, 1690, 1697, 1689, -1, 1686, 1697, 1693, -1, 1689, 1697, 1686, -1, 1691, 1698, 1687, -1, 1687, 1698, 1694, -1, 1692, 1699, 1688, -1, 1688, 1699, 1695, -1, 1693, 1700, 1691, -1, 1691, 1700, 1698, -1, 1695, 1701, 1696, -1, 1694, 1702, 1692, -1, 1692, 1702, 1699, -1, 1703, 1704, 1690, -1, 1690, 1704, 1697, -1, 1697, 1704, 1693, -1, 1693, 1704, 1700, -1, 1699, 1705, 1695, -1, 1695, 1705, 1701, -1, 1698, 1706, 1694, -1, 1694, 1706, 1702, -1, 1702, 1707, 1699, -1, 1699, 1707, 1705, -1, 1700, 1708, 1698, -1, 1698, 1708, 1706, -1, 1701, 1709, 1696, -1, 1696, 1709, 1710, -1, 1706, 1711, 1702, -1, 1702, 1711, 1707, -1, 1703, 1712, 1704, -1, 1704, 1712, 1700, -1, 1700, 1712, 1708, -1, 1701, 1713, 1709, -1, 1705, 1713, 1701, -1, 1708, 1714, 1706, -1, 1706, 1714, 1711, -1, 1709, 1715, 1710, -1, 1707, 1716, 1705, -1, 1705, 1716, 1713, -1, 1717, 1718, 1703, -1, 1708, 1718, 1714, -1, 1703, 1718, 1712, -1, 1712, 1718, 1708, -1, 1713, 1719, 1709, -1, 1709, 1719, 1715, -1, 1711, 1720, 1707, -1, 1707, 1720, 1716, -1, 1713, 1721, 1719, -1, 1716, 1721, 1713, -1, 1714, 1722, 1711, -1, 1711, 1722, 1720, -1, 1715, 1723, 1710, -1, 1710, 1723, 1724, -1, 1720, 1725, 1716, -1, 1716, 1725, 1721, -1, 1717, 1726, 1718, -1, 1718, 1726, 1714, -1, 1714, 1726, 1722, -1, 1719, 1727, 1715, -1, 1715, 1727, 1723, -1, 1720, 1728, 1725, -1, 1722, 1728, 1720, -1, 1723, 1729, 1724, -1, 1721, 1730, 1719, -1, 1719, 1730, 1727, -1, 1717, 1731, 1726, -1, 1722, 1731, 1728, -1, 1732, 1731, 1717, -1, 1726, 1731, 1722, -1, 1727, 1733, 1723, -1, 1734, 1735, 1736, -1, 1723, 1733, 1729, -1, 1721, 1737, 1730, -1, 1725, 1737, 1721, -1, 1730, 1738, 1727, -1, 1727, 1738, 1733, -1, 1725, 1739, 1737, -1, 1728, 1739, 1725, -1, 1737, 1740, 1730, -1, 1730, 1740, 1738, -1, 1729, 1741, 1724, -1, 1724, 1741, 1742, -1, 1728, 1743, 1739, -1, 1744, 1745, 1746, -1, 1731, 1743, 1728, -1, 1732, 1743, 1731, -1, 1746, 1745, 1747, -1, 1737, 1748, 1740, -1, 1739, 1748, 1737, -1, 1749, 1750, 1744, -1, 1733, 1751, 1729, -1, 1729, 1751, 1741, -1, 1744, 1750, 1745, -1, 1749, 1752, 1750, -1, 1753, 1752, 1749, -1, 1741, 1754, 1742, -1, 1755, 1756, 1753, -1, 1757, 1758, 1732, -1, 1732, 1758, 1743, -1, 1753, 1756, 1752, -1, 1739, 1758, 1748, -1, 1743, 1758, 1739, -1, 1738, 1759, 1733, -1, 1755, 1760, 1756, -1, 1761, 1760, 1755, -1, 1733, 1759, 1751, -1, 1751, 1762, 1741, -1, 1745, 1763, 1747, -1, 1741, 1762, 1754, -1, 1747, 1763, 1764, -1, 1761, 1765, 1760, -1, 1738, 1766, 1759, -1, 1740, 1766, 1738, -1, 1767, 1765, 1768, -1, 1769, 1765, 1761, -1, 1768, 1765, 1769, -1, 1750, 1770, 1745, -1, 1759, 1771, 1751, -1, 1745, 1770, 1763, -1, 1751, 1771, 1762, -1, 1748, 1772, 1740, -1, 1750, 1773, 1770, -1, 1740, 1772, 1766, -1, 1752, 1773, 1750, -1, 1766, 1774, 1759, -1, 1759, 1774, 1771, -1, 1756, 1775, 1752, -1, 1754, 1776, 1742, -1, 1752, 1775, 1773, -1, 1756, 1777, 1775, -1, 1760, 1777, 1756, -1, 1742, 1776, 1778, -1, 1757, 1779, 1758, -1, 1758, 1779, 1748, -1, 1748, 1779, 1772, -1, 1764, 1780, 1781, -1, 1763, 1780, 1764, -1, 1772, 1782, 1766, -1, 1766, 1782, 1774, -1, 1765, 1783, 1760, -1, 1767, 1783, 1765, -1, 1784, 1783, 1767, -1, 1760, 1783, 1777, -1, 1754, 1785, 1776, -1, 1763, 1786, 1780, -1, 1762, 1785, 1754, -1, 1770, 1786, 1763, -1, 1787, 1788, 1757, -1, 1757, 1788, 1779, -1, 1779, 1788, 1772, -1, 1770, 1789, 1786, -1, 1772, 1788, 1782, -1, 1762, 1790, 1785, -1, 1771, 1790, 1762, -1, 1773, 1789, 1770, -1, 1775, 1791, 1773, -1, 1774, 1792, 1771, -1, 1773, 1791, 1789, -1, 1771, 1792, 1790, -1, 1775, 1793, 1791, -1, 1777, 1793, 1775, -1, 1774, 1794, 1792, -1, 1782, 1794, 1774, -1, 1784, 1795, 1783, -1, 1783, 1795, 1777, -1, 1777, 1795, 1793, -1, 1787, 1796, 1788, -1, 1797, 1795, 1784, -1, 1788, 1796, 1782, -1, 1782, 1796, 1794, -1, 1798, 1799, 1800, -1, 1800, 1799, 1801, -1, 1798, 1802, 1799, -1, 1803, 1802, 1798, -1, 1734, 1804, 1735, -1, 1803, 1805, 1802, -1, 1806, 1805, 1803, -1, 1735, 1807, 1808, -1, 1809, 1810, 1806, -1, 1806, 1810, 1805, -1, 1799, 1811, 1801, -1, 1804, 1807, 1735, -1, 1808, 1812, 1813, -1, 1809, 1814, 1810, -1, 1815, 1814, 1809, -1, 1807, 1812, 1808, -1, 1813, 1672, 1816, -1, 1802, 1817, 1799, -1, 1799, 1817, 1811, -1, 1812, 1672, 1813, -1, 1811, 1818, 1801, -1, 1816, 1674, 1819, -1, 1801, 1818, 1820, -1, 1672, 1674, 1816, -1, 1821, 1822, 1815, -1, 1819, 1678, 1823, -1, 1824, 1822, 1821, -1, 1823, 1678, 1825, -1, 1815, 1822, 1814, -1, 1825, 1678, 1669, -1, 1805, 1826, 1802, -1, 1802, 1826, 1817, -1, 1674, 1678, 1819, -1, 1797, 1827, 1795, -1, 1795, 1827, 1793, -1, 1811, 1828, 1818, -1, 1817, 1828, 1811, -1, 1810, 1829, 1805, -1, 1805, 1829, 1826, -1, 1797, 1830, 1827, -1, 1831, 1832, 1833, -1, 1833, 1832, 1797, -1, 1797, 1832, 1830, -1, 1826, 1834, 1817, -1, 1833, 1835, 1831, -1, 1817, 1834, 1828, -1, 1831, 1835, 1836, -1, 1814, 1837, 1810, -1, 1833, 1838, 1835, -1, 1810, 1837, 1829, -1, 1818, 1839, 1820, -1, 1824, 1840, 1833, -1, 1833, 1840, 1838, -1, 1821, 1840, 1824, -1, 1829, 1841, 1826, -1, 1842, 1843, 1844, -1, 1826, 1841, 1834, -1, 1845, 1846, 1824, -1, 1844, 1843, 1847, -1, 1822, 1846, 1814, -1, 1824, 1846, 1822, -1, 1814, 1846, 1837, -1, 1828, 1848, 1818, -1, 1843, 1849, 1847, -1, 1818, 1848, 1839, -1, 1837, 1850, 1829, -1, 1849, 1851, 1847, -1, 1829, 1850, 1841, -1, 1847, 1852, 1853, -1, 1853, 1852, 1854, -1, 1820, 1855, 1856, -1, 1851, 1852, 1847, -1, 1839, 1855, 1820, -1, 1857, 1858, 1854, -1, 1828, 1859, 1848, -1, 1854, 1858, 1853, -1, 1834, 1859, 1828, -1, 1846, 1860, 1837, -1, 1837, 1860, 1850, -1, 1845, 1860, 1846, -1, 1858, 1861, 1853, -1, 1848, 1862, 1839, -1, 1839, 1862, 1855, -1, 1853, 1863, 1864, -1, 1861, 1863, 1853, -1, 1841, 1865, 1834, -1, 1864, 1866, 1867, -1, 1834, 1865, 1859, -1, 1863, 1866, 1864, -1, 1868, 1869, 1867, -1, 1867, 1869, 1864, -1, 1848, 1870, 1862, -1, 1859, 1870, 1848, -1, 1868, 1871, 1869, -1, 1850, 1872, 1841, -1, 1841, 1872, 1865, -1, 1869, 1871, 1864, -1, 1855, 1873, 1856, -1, 1864, 1874, 1875, -1, 1871, 1874, 1864, -1, 1859, 1876, 1870, -1, 1874, 1877, 1875, -1, 1875, 1877, 1878, -1, 1879, 1880, 1881, -1, 1865, 1876, 1859, -1, 1882, 1880, 1879, -1, 1845, 1883, 1860, -1, 1860, 1883, 1850, -1, 1850, 1883, 1872, -1, 1882, 1884, 1880, -1, 1885, 1883, 1845, -1, 1862, 1886, 1855, -1, 1855, 1886, 1873, -1, 1882, 1887, 1884, -1, 1888, 1887, 1882, -1, 1872, 1889, 1865, -1, 1890, 1887, 1888, -1, 1865, 1889, 1876, -1, 1888, 1891, 1890, -1, 1873, 1892, 1856, -1, 1890, 1891, 1893, -1, 1888, 1894, 1891, -1, 1856, 1892, 1895, -1, 1870, 1896, 1862, -1, 1862, 1896, 1886, -1, 1883, 1897, 1872, -1, 1888, 1898, 1894, -1, 1885, 1897, 1883, -1, 1899, 1898, 1888, -1, 1872, 1897, 1889, -1, 1900, 1898, 1899, -1, 1873, 1901, 1892, -1, 1785, 1902, 1776, -1, 1886, 1901, 1873, -1, 1776, 1902, 1778, -1, 1876, 1903, 1870, -1, 1902, 1904, 1778, -1, 1870, 1903, 1896, -1, 1896, 1905, 1886, -1, 1886, 1905, 1901, -1, 1904, 1906, 1778, -1, 1889, 1907, 1876, -1, 1906, 1908, 1778, -1, 1876, 1907, 1903, -1, 1778, 1908, 1909, -1, 1909, 1908, 1910, -1, 1911, 1912, 1910, -1, 1892, 1913, 1895, -1, 1910, 1912, 1909, -1, 1896, 1914, 1905, -1, 1903, 1914, 1896, -1, 1912, 1915, 1909, -1, 1889, 1916, 1907, -1, 1917, 1916, 1885, -1, 1885, 1916, 1897, -1, 1897, 1916, 1889, -1, 1892, 1918, 1913, -1, 1915, 1919, 1909, -1, 1901, 1918, 1892, -1, 1909, 1919, 1920, -1, 1920, 1921, 1922, -1, 1919, 1921, 1920, -1, 1922, 1923, 1920, -1, 1907, 1924, 1903, -1, 1925, 1923, 1922, -1, 1903, 1924, 1914, -1, 1923, 1926, 1920, -1, 1905, 1927, 1901, -1, 1901, 1927, 1918, -1, 1925, 1926, 1923, -1, 1895, 1928, 1929, -1, 1913, 1928, 1895, -1, 1926, 1930, 1920, -1, 1920, 1930, 1734, -1, 1907, 1931, 1924, -1, 1930, 1932, 1734, -1, 1916, 1931, 1907, -1, 1734, 1932, 1804, -1, 1917, 1931, 1916, -1, 1914, 1933, 1905, -1, 1793, 1934, 1791, -1, 1791, 1934, 1789, -1, 1905, 1933, 1927, -1, 1793, 1935, 1934, -1, 1827, 1935, 1793, -1, 1830, 1935, 1827, -1, 1918, 1936, 1913, -1, 1913, 1936, 1928, -1, 1924, 1937, 1914, -1, 1830, 1938, 1935, -1, 1914, 1937, 1933, -1, 1918, 1939, 1936, -1, 1830, 1940, 1938, -1, 1832, 1940, 1830, -1, 1927, 1939, 1918, -1, 1941, 1942, 1943, -1, 1928, 1944, 1929, -1, 1943, 1942, 1836, -1, 1831, 1945, 1832, -1, 1924, 1946, 1937, -1, 1836, 1945, 1831, -1, 1947, 1946, 1917, -1, 1832, 1945, 1940, -1, 1917, 1946, 1931, -1, 1940, 1945, 1942, -1, 1931, 1946, 1924, -1, 1942, 1945, 1836, -1, 1933, 1948, 1927, -1, 1943, 1949, 1941, -1, 1927, 1948, 1939, -1, 1836, 1949, 1943, -1, 1838, 1950, 1835, -1, 1936, 1951, 1928, -1, 1835, 1950, 1836, -1, 1836, 1950, 1949, -1, 1928, 1951, 1944, -1, 1933, 1952, 1948, -1, 1838, 1953, 1950, -1, 1937, 1952, 1933, -1, 1838, 1954, 1953, -1, 1939, 1955, 1936, -1, 1840, 1954, 1838, -1, 1936, 1955, 1951, -1, 1806, 1956, 1809, -1, 1809, 1956, 1815, -1, 1944, 1957, 1929, -1, 1821, 1958, 1840, -1, 1815, 1958, 1821, -1, 1929, 1957, 1959, -1, 1840, 1958, 1954, -1, 1946, 1960, 1937, -1, 1956, 1958, 1815, -1, 1947, 1960, 1946, -1, 1937, 1960, 1952, -1, 1954, 1958, 1956, -1, 1961, 1962, 1842, -1, 1948, 1963, 1939, -1, 1939, 1963, 1955, -1, 1964, 1962, 1961, -1, 1843, 1965, 1849, -1, 1951, 1966, 1944, -1, 1962, 1965, 1842, -1, 1842, 1965, 1843, -1, 1944, 1966, 1957, -1, 1948, 1967, 1963, -1, 1849, 1968, 1851, -1, 1851, 1968, 1852, -1, 1952, 1967, 1948, -1, 1957, 1969, 1959, -1, 1965, 1970, 1849, -1, 1849, 1970, 1968, -1, 1955, 1971, 1951, -1, 1951, 1971, 1966, -1, 1968, 1972, 1852, -1, 1852, 1972, 1854, -1, 1968, 1973, 1972, -1, 1947, 1974, 1960, -1, 1970, 1973, 1968, -1, 1960, 1974, 1952, -1, 1975, 1974, 1947, -1, 1952, 1974, 1967, -1, 1966, 1976, 1957, -1, 1973, 1977, 1972, -1, 1957, 1976, 1969, -1, 1970, 1978, 1973, -1, 1963, 1979, 1955, -1, 1854, 1980, 1857, -1, 1955, 1979, 1971, -1, 1972, 1980, 1854, -1, 1977, 1980, 1972, -1, 1857, 1980, 1981, -1, 1981, 1982, 1983, -1, 1971, 1984, 1966, -1, 1973, 1982, 1977, -1, 1966, 1984, 1976, -1, 1978, 1982, 1973, -1, 1977, 1982, 1980, -1, 1980, 1982, 1981, -1, 1963, 1985, 1979, -1, 1983, 1986, 1981, -1, 1967, 1985, 1963, -1, 1981, 1986, 1857, -1, 1857, 1987, 1858, -1, 1969, 1988, 1959, -1, 1986, 1987, 1857, -1, 1959, 1988, 1989, -1, 1858, 1987, 1861, -1, 1971, 1990, 1984, -1, 1979, 1990, 1971, -1, 1861, 1991, 1863, -1, 1863, 1991, 1866, -1, 1866, 1992, 1867, -1, 1975, 1993, 1974, -1, 1974, 1993, 1967, -1, 1991, 1992, 1866, -1, 1967, 1993, 1985, -1, 1969, 1994, 1988, -1, 1976, 1994, 1969, -1, 1861, 1995, 1991, -1, 1987, 1995, 1861, -1, 1985, 1996, 1979, -1, 1991, 1997, 1992, -1, 1995, 1997, 1991, -1, 1979, 1996, 1990, -1, 1997, 1998, 1992, -1, 1988, 1999, 1989, -1, 1995, 2000, 1997, -1, 1984, 2001, 1976, -1, 1976, 2001, 1994, -1, 1867, 2002, 1868, -1, 1868, 2002, 2003, -1, 1998, 2002, 1992, -1, 2004, 2005, 1975, -1, 1992, 2002, 1867, -1, 1975, 2005, 1993, -1, 2003, 2006, 2007, -1, 1993, 2005, 1985, -1, 2002, 2006, 2003, -1, 1985, 2005, 1996, -1, 1997, 2006, 1998, -1, 1994, 2008, 1988, -1, 2000, 2006, 1997, -1, 1998, 2006, 2002, -1, 1988, 2008, 1999, -1, 2003, 2009, 1868, -1, 2007, 2009, 2003, -1, 1984, 2010, 2001, -1, 1990, 2010, 1984, -1, 1868, 2011, 1871, -1, 2001, 2012, 1994, -1, 2009, 2011, 1868, -1, 1994, 2012, 2008, -1, 1871, 2013, 1874, -1, 1874, 2013, 1877, -1, 1996, 2014, 1990, -1, 1990, 2014, 2010, -1, 2013, 2015, 1877, -1, 1877, 2015, 1878, -1, 1989, 2016, 2017, -1, 1999, 2016, 1989, -1, 2011, 2018, 1871, -1, 2001, 2019, 2012, -1, 1871, 2018, 2013, -1, 2013, 2020, 2015, -1, 2010, 2019, 2001, -1, 2018, 2020, 2013, -1, 1996, 2021, 2014, -1, 2020, 2022, 2015, -1, 2004, 2021, 2005, -1, 2005, 2021, 1996, -1, 2018, 2023, 2020, -1, 1878, 2024, 2025, -1, 2008, 2026, 1999, -1, 2025, 2024, 2027, -1, 2015, 2024, 1878, -1, 1999, 2026, 2016, -1, 2022, 2024, 2015, -1, 2010, 2028, 2019, -1, 2027, 2029, 2030, -1, 2024, 2029, 2027, -1, 2020, 2029, 2022, -1, 2014, 2028, 2010, -1, 2023, 2029, 2020, -1, 2022, 2029, 2024, -1, 2016, 2031, 2017, -1, 2032, 2033, 2034, -1, 1881, 2033, 2032, -1, 2008, 2035, 2026, -1, 1884, 2036, 1880, -1, 1881, 2036, 2033, -1, 1880, 2036, 1881, -1, 2012, 2035, 2008, -1, 2004, 2037, 2021, -1, 2014, 2037, 2028, -1, 2038, 2037, 2004, -1, 2021, 2037, 2014, -1, 2016, 2039, 2031, -1, 2026, 2039, 2016, -1, 1884, 2040, 2036, -1, 2012, 2041, 2035, -1, 1887, 2042, 1884, -1, 1884, 2042, 2040, -1, 2019, 2041, 2012, -1, 2043, 2044, 1893, -1, 2026, 2045, 2039, -1, 2046, 2044, 2043, -1, 2035, 2045, 2026, -1, 1890, 2047, 1887, -1, 1893, 2047, 1890, -1, 1887, 2047, 2042, -1, 2044, 2047, 1893, -1, 2042, 2047, 2044, -1, 2019, 2048, 2041, -1, 1893, 2049, 2043, -1, 2028, 2048, 2019, -1, 2043, 2049, 2046, -1, 2041, 2050, 2035, -1, 2035, 2050, 2045, -1, 1891, 2051, 1893, -1, 1893, 2051, 2049, -1, 2031, 2052, 2017, -1, 1894, 2051, 1891, -1, 1894, 2053, 2051, -1, 2017, 2052, 2054, -1, 2028, 2055, 2048, -1, 2037, 2055, 2028, -1, 2038, 2055, 2037, -1, 1894, 2056, 2053, -1, 2048, 2057, 2041, -1, 1898, 2056, 1894, -1, 2041, 2057, 2050, -1, 2039, 2058, 2031, -1, 2059, 2060, 2061, -1, 2031, 2058, 2052, -1, 2061, 2060, 2062, -1, 1898, 2063, 2056, -1, 2060, 2063, 2062, -1, 2056, 2063, 2060, -1, 1900, 2063, 1898, -1, 2062, 2063, 1900, -1, 2052, 2064, 2054, -1, 1790, 2065, 1785, -1, 2055, 2066, 2048, -1, 2067, 2066, 2038, -1, 1792, 2065, 1790, -1, 2038, 2066, 2055, -1, 2048, 2066, 2057, -1, 2045, 2068, 2039, -1, 1902, 2069, 1904, -1, 2065, 2069, 1785, -1, 2039, 2068, 2058, -1, 1785, 2069, 1902, -1, 2052, 2070, 2064, -1, 1904, 2071, 1906, -1, 2058, 2070, 2052, -1, 1906, 2071, 1908, -1, 2050, 2072, 2045, -1, 2045, 2072, 2068, -1, 2069, 2073, 1904, -1, 1904, 2073, 2071, -1, 2068, 2074, 2058, -1, 2071, 2075, 1908, -1, 1908, 2075, 1910, -1, 2058, 2074, 2070, -1, 2071, 2076, 2075, -1, 2057, 2077, 2050, -1, 2073, 2076, 2071, -1, 2076, 2078, 2075, -1, 2050, 2077, 2072, -1, 2073, 2079, 2076, -1, 2068, 2080, 2074, -1, 2072, 2080, 2068, -1, 1910, 2081, 1911, -1, 2064, 1844, 2054, -1, 2075, 2081, 1910, -1, 2078, 2081, 2075, -1, 2054, 1844, 1847, -1, 1911, 2081, 2082, -1, 2082, 2083, 2084, -1, 2076, 2083, 2078, -1, 2079, 2083, 2076, -1, 2078, 2083, 2081, -1, 2067, 2085, 2066, -1, 2081, 2083, 2082, -1, 2066, 2085, 2057, -1, 2057, 2085, 2077, -1, 2084, 2086, 2082, -1, 2077, 2087, 2072, -1, 2082, 2086, 1911, -1, 2072, 2087, 2080, -1, 1911, 2088, 1912, -1, 2070, 1842, 2064, -1, 2064, 1842, 1844, -1, 1912, 2088, 1915, -1, 2086, 2088, 1911, -1, 2089, 2090, 2067, -1, 1915, 2091, 1919, -1, 2067, 2090, 2085, -1, 2085, 2090, 2077, -1, 1919, 2091, 1921, -1, 2077, 2090, 2087, -1, 2074, 1961, 2070, -1, 1921, 2092, 1922, -1, 2070, 1961, 1842, -1, 2091, 2092, 1921, -1, 2080, 1964, 2074, -1, 2074, 1964, 1961, -1, 2088, 2093, 1915, -1, 1915, 2093, 2091, -1, 2091, 2094, 2092, -1, 2087, 2095, 2080, -1, 2093, 2094, 2091, -1, 2080, 2095, 1964, -1, 2094, 2096, 2092, -1, 2093, 2097, 2094, -1, 1922, 2098, 1925, -1, 1925, 2098, 2099, -1, 2092, 2098, 1922, -1, 2089, 2100, 2090, -1, 2096, 2098, 2092, -1, 2090, 2100, 2087, -1, 2087, 2100, 2095, -1, 2099, 2101, 1652, -1, 2098, 2101, 2099, -1, 2094, 2101, 2096, -1, 2097, 2101, 2094, -1, 2096, 2101, 2098, -1, 2099, 2102, 1925, -1, 1652, 2102, 2099, -1, 1925, 2103, 1926, -1, 2102, 2103, 1925, -1, 1930, 2104, 1932, -1, 1926, 2104, 1930, -1, 1932, 2105, 1804, -1, 2104, 2105, 1932, -1, 2103, 2106, 1926, -1, 1926, 2106, 2104, -1, 2104, 2107, 2105, -1, 2106, 2107, 2104, -1, 2107, 2108, 2105, -1, 2106, 2109, 2107, -1, 1804, 2110, 1807, -1, 1807, 2110, 1812, -1, 2105, 2110, 1804, -1, 2108, 2110, 2105, -1, 2109, 2111, 2107, -1, 2110, 2111, 1812, -1, 1812, 2111, 1672, -1, 2108, 2111, 2110, -1, 2107, 2111, 2108, -1, 1935, 2112, 1934, -1, 1938, 2112, 1935, -1, 1934, 2112, 1789, -1, 1789, 2112, 1786, -1, 1938, 2113, 2112, -1, 1941, 2114, 1942, -1, 1940, 2114, 1938, -1, 1942, 2114, 1940, -1, 2115, 2114, 1941, -1, 1938, 2114, 2113, -1, 1949, 2116, 1941, -1, 1950, 2116, 1949, -1, 1953, 2116, 1950, -1, 1941, 2116, 2115, -1, 1953, 2117, 2116, -1, 1803, 2118, 1806, -1, 1806, 2118, 1956, -1, 1953, 2118, 2117, -1, 1954, 2118, 1953, -1, 1878, 2119, 1875, -1, 1956, 2118, 1954, -1, 1875, 2119, 2120, -1, 1965, 2121, 1970, -1, 2095, 2121, 1964, -1, 1964, 2121, 1962, -1, 1962, 2121, 1965, -1, 2121, 2122, 1970, -1, 2025, 2123, 1878, -1, 1878, 2123, 2119, -1, 1970, 2124, 1978, -1, 1982, 2124, 1983, -1, 1978, 2124, 1982, -1, 2122, 2124, 1970, -1, 2027, 2125, 2025, -1, 2025, 2125, 2123, -1, 1986, 2126, 1987, -1, 1987, 2126, 1995, -1, 1983, 2126, 1986, -1, 2030, 2127, 2027, -1, 2128, 2126, 1983, -1, 2027, 2127, 2125, -1, 2126, 2129, 1995, -1, 2130, 2131, 2030, -1, 2030, 2131, 2127, -1, 2119, 2132, 2120, -1, 2129, 2133, 1995, -1, 2006, 2133, 2007, -1, 2120, 2132, 2134, -1, 2000, 2133, 2006, -1, 1995, 2133, 2000, -1, 2135, 2136, 2007, -1, 2137, 2138, 2139, -1, 2140, 2138, 2137, -1, 2139, 2138, 2130, -1, 2009, 2136, 2011, -1, 2011, 2136, 2018, -1, 2130, 2138, 2131, -1, 2007, 2136, 2009, -1, 2123, 2141, 2119, -1, 2119, 2141, 2132, -1, 2136, 2142, 2018, -1, 2125, 2143, 2123, -1, 2123, 2143, 2141, -1, 2142, 2144, 2018, -1, 2018, 2144, 2023, -1, 2029, 2144, 2030, -1, 2023, 2144, 2029, -1, 2036, 2145, 2033, -1, 2127, 2146, 2125, -1, 2125, 2146, 2143, -1, 2033, 2145, 2034, -1, 2040, 2145, 2036, -1, 2034, 2145, 2147, -1, 2127, 2148, 2146, -1, 2040, 2149, 2145, -1, 2131, 2148, 2127, -1, 2132, 2150, 2134, -1, 2134, 2150, 2151, -1, 2040, 2152, 2149, -1, 2153, 2152, 2046, -1, 2042, 2152, 2040, -1, 2154, 2155, 2140, -1, 2044, 2152, 2042, -1, 2140, 2155, 2138, -1, 2046, 2152, 2044, -1, 2138, 2155, 2131, -1, 2051, 2156, 2049, -1, 2049, 2156, 2046, -1, 2131, 2155, 2148, -1, 2053, 2156, 2051, -1, 2141, 2157, 2132, -1, 2132, 2157, 2150, -1, 2046, 2156, 2153, -1, 2053, 2158, 2156, -1, 2141, 2159, 2157, -1, 2143, 2159, 2141, -1, 2053, 2160, 2158, -1, 2060, 2160, 2056, -1, 2161, 2160, 2059, -1, 2146, 2162, 2143, -1, 2056, 2160, 2053, -1, 2059, 2160, 2060, -1, 2143, 2162, 2159, -1, 2065, 2163, 2069, -1, 1792, 2163, 2065, -1, 2146, 2164, 2162, -1, 2069, 2163, 2073, -1, 2148, 2164, 2146, -1, 1794, 2163, 1792, -1, 2151, 2165, 2166, -1, 2163, 1623, 2073, -1, 2150, 2165, 2151, -1, 2148, 2167, 2164, -1, 2168, 2167, 2154, -1, 2154, 2167, 2155, -1, 2155, 2167, 2148, -1, 2073, 1628, 2079, -1, 2083, 1628, 2084, -1, 2079, 1628, 2083, -1, 1623, 1628, 2073, -1, 2150, 2147, 2165, -1, 1642, 1645, 2084, -1, 2157, 2147, 2150, -1, 2084, 1645, 2086, -1, 2086, 1645, 2088, -1, 2088, 1645, 2093, -1, 2157, 2034, 2147, -1, 2159, 2034, 2157, -1, 1645, 1646, 2093, -1, 2162, 2032, 2159, -1, 2159, 2032, 2034, -1, 1646, 1655, 2093, -1, 2164, 1881, 2162, -1, 2093, 1655, 2097, -1, 2101, 1655, 1652, -1, 2162, 1881, 2032, -1, 2097, 1655, 2101, -1, 1654, 1665, 1652, -1, 1652, 1665, 2102, -1, 2103, 1665, 2106, -1, 2102, 1665, 2103, -1, 2167, 1879, 2164, -1, 2168, 1879, 2167, -1, 2164, 1879, 1881, -1, 1882, 1879, 2168, -1, 1665, 1666, 2106, -1, 2106, 1675, 2109, -1, 2111, 1675, 1672, -1, 1666, 1675, 2106, -1, 2109, 1675, 2111, -1, 1786, 2169, 1780, -1, 1780, 2169, 1781, -1, 1786, 2170, 2169, -1, 2112, 2170, 1786, -1, 2113, 2170, 2112, -1, 2113, 2171, 2170, -1, 1781, 2171, 2172, -1, 2169, 2171, 1781, -1, 2170, 2171, 2169, -1, 2114, 2173, 2113, -1, 2115, 2173, 2114, -1, 2113, 2173, 2171, -1, 2171, 2174, 2172, -1, 2115, 2174, 2173, -1, 2175, 2174, 2115, -1, 2173, 2174, 2171, -1, 2172, 2174, 2175, -1, 2115, 2176, 2175, -1, 2175, 2176, 2172, -1, 2116, 2177, 2115, -1, 2178, 2179, 2180, -1, 2115, 2177, 2176, -1, 2117, 2177, 2116, -1, 2180, 2179, 2181, -1, 2176, 2182, 2172, -1, 2177, 2182, 2176, -1, 2172, 2182, 1800, -1, 2117, 2182, 2177, -1, 2118, 2183, 2117, -1, 2117, 2183, 2182, -1, 1803, 2183, 2118, -1, 2161, 2184, 2178, -1, 2178, 2184, 2179, -1, 2183, 2185, 2182, -1, 2182, 2185, 1800, -1, 1803, 2185, 2183, -1, 1798, 2185, 1803, -1, 1800, 2185, 1798, -1, 2100, 2186, 2095, -1, 2089, 2186, 2100, -1, 2121, 2187, 2122, -1, 2059, 2188, 2161, -1, 2186, 2187, 2095, -1, 2161, 2188, 2184, -1, 2089, 2187, 2186, -1, 2095, 2187, 2121, -1, 2187, 2189, 2122, -1, 2190, 2189, 2089, -1, 2089, 2189, 2187, -1, 2061, 2191, 2059, -1, 2059, 2191, 2188, -1, 2124, 2192, 1983, -1, 2128, 2192, 2193, -1, 1983, 2192, 2128, -1, 2122, 2194, 2124, -1, 2190, 2194, 2189, -1, 2124, 2194, 2192, -1, 2179, 2195, 2181, -1, 2189, 2194, 2122, -1, 2193, 2196, 2190, -1, 2192, 2196, 2193, -1, 2190, 2196, 2194, -1, 2194, 2196, 2192, -1, 2062, 2197, 2061, -1, 2061, 2197, 2191, -1, 2190, 2198, 2193, -1, 2184, 2199, 2179, -1, 2193, 2198, 2128, -1, 2190, 2200, 2198, -1, 2179, 2199, 2195, -1, 2128, 2200, 2126, -1, 2198, 2200, 2128, -1, 2126, 2200, 2129, -1, 2201, 2202, 2190, -1, 2195, 2203, 2181, -1, 2200, 2202, 2129, -1, 2181, 2203, 2204, -1, 2190, 2202, 2200, -1, 1900, 2205, 2062, -1, 1899, 2205, 1900, -1, 2007, 2206, 2135, -1, 2062, 2205, 2197, -1, 2135, 2206, 2207, -1, 2133, 2206, 2007, -1, 2184, 2208, 2199, -1, 2188, 2208, 2184, -1, 2201, 2209, 2202, -1, 2202, 2209, 2129, -1, 2129, 2209, 2133, -1, 2133, 2209, 2206, -1, 2207, 2210, 2201, -1, 2199, 2211, 2195, -1, 2201, 2210, 2209, -1, 2195, 2211, 2203, -1, 2209, 2210, 2206, -1, 2206, 2210, 2207, -1, 2191, 2212, 2188, -1, 2201, 2213, 2207, -1, 2207, 2213, 2135, -1, 2188, 2212, 2208, -1, 2135, 2214, 2136, -1, 2208, 2215, 2199, -1, 2201, 2214, 2213, -1, 2199, 2215, 2211, -1, 2213, 2214, 2135, -1, 2136, 2214, 2142, -1, 2137, 2216, 2201, -1, 2197, 2217, 2191, -1, 2191, 2217, 2212, -1, 2201, 2216, 2214, -1, 2214, 2216, 2142, -1, 2144, 2218, 2030, -1, 2203, 2219, 2204, -1, 2030, 2218, 2130, -1, 2142, 2220, 2144, -1, 2137, 2220, 2216, -1, 2144, 2220, 2218, -1, 2216, 2220, 2142, -1, 2212, 2221, 2208, -1, 2208, 2221, 2215, -1, 2139, 2222, 2137, -1, 1899, 2223, 2205, -1, 2137, 2222, 2220, -1, 2224, 2223, 1899, -1, 2130, 2222, 2139, -1, 2197, 2223, 2217, -1, 2218, 2222, 2130, -1, 2220, 2222, 2218, -1, 2205, 2223, 2197, -1, 2203, 2225, 2219, -1, 2165, 2226, 2166, -1, 2211, 2225, 2203, -1, 2147, 2226, 2165, -1, 2217, 2227, 2212, -1, 2145, 2228, 2147, -1, 2149, 2228, 2145, -1, 2147, 2228, 2226, -1, 2212, 2227, 2221, -1, 2219, 2229, 2204, -1, 2166, 2230, 2231, -1, 2226, 2230, 2166, -1, 2204, 2229, 1627, -1, 2228, 2230, 2226, -1, 2149, 2230, 2228, -1, 2211, 2232, 2225, -1, 2149, 2233, 2230, -1, 2153, 2233, 2152, -1, 2152, 2233, 2149, -1, 2215, 2232, 2211, -1, 2234, 2235, 2153, -1, 2153, 2235, 2233, -1, 2224, 2236, 2223, -1, 2230, 2235, 2231, -1, 2223, 2236, 2217, -1, 2233, 2235, 2230, -1, 2231, 2235, 2234, -1, 2217, 2236, 2227, -1, 2153, 2237, 2234, -1, 2219, 1635, 2229, -1, 2234, 2237, 2231, -1, 2225, 1635, 2219, -1, 2153, 2238, 2237, -1, 2158, 2238, 2156, -1, 2156, 2238, 2153, -1, 2215, 2239, 2232, -1, 2221, 2239, 2215, -1, 2158, 2240, 2238, -1, 2232, 1633, 2225, -1, 2231, 2240, 2180, -1, 2225, 1633, 1635, -1, 2238, 2240, 2237, -1, 2237, 2240, 2231, -1, 2158, 2241, 2240, -1, 2227, 1640, 2221, -1, 2160, 2241, 2158, -1, 2221, 1640, 2239, -1, 2161, 2241, 2160, -1, 2161, 2242, 2241, -1, 2241, 2242, 2240, -1, 2229, 1625, 1627, -1, 2180, 2242, 2178, -1, 2178, 2242, 2161, -1, 2240, 2242, 2180, -1, 1796, 2243, 1794, -1, 2239, 1650, 2232, -1, 2232, 1650, 1633, -1, 1787, 2243, 1796, -1, 1787, 2244, 2243, -1, 2227, 1638, 1640, -1, 2236, 1638, 2227, -1, 1643, 1638, 2224, -1, 2163, 2244, 1623, -1, 2224, 1638, 2236, -1, 1794, 2244, 2163, -1, 2243, 2244, 1794, -1, 2229, 1636, 1625, -1, 1787, 1621, 2244, -1, 1635, 1636, 2229, -1, 1624, 1621, 1787, -1, 2244, 1621, 1623, -1, 2084, 1629, 1642, -1, 1640, 1641, 2239, -1, 2239, 1641, 1650, -1, 1628, 1629, 2084, -1, 1642, 1629, 1631, -1, 1623, 1622, 1628, -1, 2245, 2246, 2247, -1, 2248, 2249, 2250, -1, 2251, 2252, 2249, -1, 2253, 2254, 2255, -1, 2249, 2252, 2250, -1, 2255, 2254, 2256, -1, 2257, 2252, 2251, -1, 2252, 2258, 2250, -1, 2259, 2260, 2261, -1, 2250, 2258, 2262, -1, 2263, 2264, 2265, -1, 2261, 2260, 2266, -1, 2252, 2264, 2258, -1, 2257, 2264, 2252, -1, 2258, 2264, 2262, -1, 2266, 2267, 2253, -1, 2262, 2264, 2263, -1, 2265, 2264, 2257, -1, 2253, 2267, 2254, -1, 2263, 2268, 2262, -1, 2247, 2269, 2259, -1, 2262, 2268, 2250, -1, 2259, 2269, 2260, -1, 2263, 2270, 2268, -1, 2268, 2270, 2250, -1, 2271, 2270, 2263, -1, 2272, 2270, 2271, -1, 2256, 2273, 2274, -1, 2274, 2273, 2275, -1, 2272, 2276, 2270, -1, 2266, 2277, 2267, -1, 2270, 2276, 2250, -1, 2260, 2277, 2266, -1, 2250, 2276, 2278, -1, 2276, 2279, 2278, -1, 2280, 2279, 2272, -1, 2247, 2281, 2269, -1, 2272, 2279, 2276, -1, 2246, 2281, 2247, -1, 2278, 2282, 2283, -1, 2284, 2281, 2246, -1, 2279, 2282, 2278, -1, 2283, 2285, 2286, -1, 2282, 2285, 2283, -1, 2279, 2285, 2282, -1, 2286, 2285, 2287, -1, 2254, 2288, 2256, -1, 2280, 2285, 2279, -1, 2287, 2285, 2280, -1, 2256, 2288, 2273, -1, 2283, 2289, 2278, -1, 2286, 2289, 2283, -1, 2269, 2290, 2260, -1, 2260, 2290, 2277, -1, 2291, 2292, 2286, -1, 2293, 2292, 2291, -1, 2267, 2294, 2254, -1, 2286, 2292, 2289, -1, 2289, 2292, 2278, -1, 2254, 2294, 2288, -1, 2273, 2295, 2275, -1, 2293, 2296, 2292, -1, 2292, 2296, 2278, -1, 2278, 2296, 2297, -1, 2298, 2299, 2284, -1, 2284, 2299, 2281, -1, 2281, 2299, 2269, -1, 2296, 2300, 2297, -1, 2269, 2299, 2290, -1, 2293, 2300, 2296, -1, 2301, 2300, 2293, -1, 2277, 2302, 2267, -1, 2297, 2303, 2304, -1, 2304, 2303, 2305, -1, 2267, 2302, 2294, -1, 2300, 2303, 2297, -1, 2305, 2306, 2307, -1, 2301, 2306, 2300, -1, 2303, 2306, 2305, -1, 2273, 2308, 2295, -1, 2300, 2306, 2303, -1, 2288, 2308, 2273, -1, 2307, 2306, 2301, -1, 2277, 2309, 2302, -1, 2290, 2309, 2277, -1, 2288, 2310, 2308, -1, 2294, 2310, 2288, -1, 2275, 2311, 2312, -1, 2295, 2311, 2275, -1, 2290, 2313, 2309, -1, 2298, 2313, 2299, -1, 2299, 2313, 2290, -1, 2294, 2314, 2310, -1, 2302, 2314, 2294, -1, 2295, 2315, 2311, -1, 2308, 2315, 2295, -1, 2302, 2316, 2314, -1, 2309, 2316, 2302, -1, 2310, 2317, 2308, -1, 2308, 2317, 2315, -1, 2311, 2318, 2312, -1, 2298, 2319, 2313, -1, 2320, 2319, 2298, -1, 2309, 2319, 2316, -1, 2313, 2319, 2309, -1, 2310, 2321, 2317, -1, 2314, 2321, 2310, -1, 2315, 2322, 2311, -1, 2311, 2322, 2318, -1, 2316, 2323, 2314, -1, 2314, 2323, 2321, -1, 2318, 2324, 2312, -1, 2312, 2324, 2325, -1, 2317, 2326, 2315, -1, 2315, 2326, 2322, -1, 2316, 2327, 2323, -1, 2319, 2327, 2316, -1, 2320, 2327, 2319, -1, 2322, 2328, 2318, -1, 2318, 2328, 2324, -1, 2317, 2329, 2326, -1, 2321, 2329, 2317, -1, 2326, 2330, 2322, -1, 2322, 2330, 2328, -1, 2323, 2331, 2321, -1, 2321, 2331, 2329, -1, 2324, 2332, 2325, -1, 2326, 2333, 2330, -1, 2329, 2333, 2326, -1, 2327, 2334, 2323, -1, 2335, 2334, 2320, -1, 2323, 2334, 2331, -1, 2320, 2334, 2327, -1, 2324, 2336, 2332, -1, 2328, 2336, 2324, -1, 2331, 2337, 2329, -1, 2329, 2337, 2333, -1, 2332, 2338, 2325, -1, 2325, 2338, 2339, -1, 2330, 2340, 2328, -1, 2328, 2340, 2336, -1, 2331, 2341, 2337, -1, 2335, 2341, 2334, -1, 2334, 2341, 2331, -1, 2336, 2342, 2332, -1, 2332, 2342, 2338, -1, 2333, 2343, 2330, -1, 2330, 2343, 2340, -1, 2336, 2344, 2342, -1, 2340, 2344, 2336, -1, 2333, 2345, 2343, -1, 2337, 2345, 2333, -1, 2338, 2346, 2339, -1, 2343, 2347, 2340, -1, 2340, 2347, 2344, -1, 2348, 2349, 2335, -1, 2335, 2349, 2341, -1, 2341, 2349, 2337, -1, 2337, 2349, 2345, -1, 2342, 2350, 2338, -1, 2338, 2350, 2346, -1, 2343, 2351, 2347, -1, 2345, 2351, 2343, -1, 2346, 2352, 2339, -1, 2339, 2352, 2353, -1, 2344, 2354, 2342, -1, 2342, 2354, 2350, -1, 2349, 2355, 2345, -1, 2348, 2355, 2349, -1, 2345, 2355, 2351, -1, 2346, 2356, 2352, -1, 2350, 2356, 2346, -1, 2344, 2357, 2354, -1, 2347, 2357, 2344, -1, 2350, 2358, 2356, -1, 2354, 2358, 2350, -1, 2351, 2359, 2347, -1, 2347, 2359, 2357, -1, 2357, 2360, 2354, -1, 2297, 2361, 2362, -1, 2354, 2360, 2358, -1, 2352, 2363, 2353, -1, 2364, 2365, 2348, -1, 2355, 2365, 2351, -1, 2348, 2365, 2355, -1, 2351, 2365, 2359, -1, 2359, 2366, 2357, -1, 2357, 2366, 2360, -1, 2356, 2367, 2352, -1, 2368, 2369, 2370, -1, 2352, 2367, 2363, -1, 2371, 2372, 2373, -1, 2363, 2374, 2353, -1, 2373, 2372, 2375, -1, 2353, 2374, 2248, -1, 2359, 2376, 2366, -1, 2364, 2376, 2365, -1, 2377, 2378, 2371, -1, 2365, 2376, 2359, -1, 2371, 2378, 2372, -1, 2356, 2379, 2367, -1, 2358, 2379, 2356, -1, 2377, 2380, 2378, -1, 2381, 2380, 2377, -1, 2367, 2382, 2363, -1, 2363, 2382, 2374, -1, 2383, 2384, 2381, -1, 2360, 2385, 2358, -1, 2381, 2384, 2380, -1, 2358, 2385, 2379, -1, 2386, 2387, 2383, -1, 2383, 2387, 2384, -1, 2372, 2388, 2375, -1, 2379, 2389, 2367, -1, 2367, 2389, 2382, -1, 2375, 2388, 2390, -1, 2360, 2391, 2385, -1, 2366, 2391, 2360, -1, 2386, 2392, 2387, -1, 2393, 2392, 2394, -1, 2395, 2392, 2386, -1, 2385, 2396, 2379, -1, 2394, 2392, 2395, -1, 2378, 2397, 2372, -1, 2372, 2397, 2388, -1, 2379, 2396, 2389, -1, 2374, 2398, 2248, -1, 2378, 2399, 2397, -1, 2400, 2401, 2364, -1, 2364, 2401, 2376, -1, 2376, 2401, 2366, -1, 2366, 2401, 2391, -1, 2380, 2399, 2378, -1, 2385, 2402, 2396, -1, 2391, 2402, 2385, -1, 2384, 2403, 2380, -1, 2380, 2403, 2399, -1, 2387, 2404, 2384, -1, 2374, 2405, 2398, -1, 2382, 2405, 2374, -1, 2384, 2404, 2403, -1, 2390, 2406, 2407, -1, 2400, 2408, 2401, -1, 2401, 2408, 2391, -1, 2391, 2408, 2402, -1, 2388, 2406, 2390, -1, 2382, 2409, 2405, -1, 2392, 2410, 2387, -1, 2387, 2410, 2404, -1, 2389, 2409, 2382, -1, 2411, 2410, 2393, -1, 2393, 2410, 2392, -1, 2397, 2412, 2388, -1, 2396, 2413, 2389, -1, 2388, 2412, 2406, -1, 2389, 2413, 2409, -1, 2396, 2414, 2413, -1, 2402, 2414, 2396, -1, 2399, 2415, 2397, -1, 2397, 2415, 2412, -1, 2403, 2416, 2399, -1, 2399, 2416, 2415, -1, 2404, 2417, 2403, -1, 2418, 2419, 2400, -1, 2400, 2419, 2408, -1, 2403, 2417, 2416, -1, 2408, 2419, 2402, -1, 2402, 2419, 2414, -1, 2411, 2420, 2410, -1, 2404, 2420, 2417, -1, 2421, 2420, 2411, -1, 2410, 2420, 2404, -1, 2422, 2423, 2424, -1, 2422, 2425, 2423, -1, 2426, 2425, 2422, -1, 2297, 2304, 2361, -1, 2426, 2427, 2425, -1, 2361, 2305, 2428, -1, 2429, 2427, 2426, -1, 2428, 2305, 2430, -1, 2304, 2305, 2361, -1, 2431, 2432, 2429, -1, 2305, 2307, 2430, -1, 2429, 2432, 2427, -1, 2423, 2433, 2424, -1, 2430, 2434, 2435, -1, 2424, 2433, 2436, -1, 2307, 2434, 2430, -1, 2435, 2437, 2438, -1, 2438, 2437, 2370, -1, 2434, 2437, 2435, -1, 2439, 2440, 2431, -1, 2431, 2440, 2432, -1, 2437, 2441, 2370, -1, 2423, 2442, 2433, -1, 2370, 2441, 2368, -1, 2425, 2442, 2423, -1, 2412, 2443, 2406, -1, 2406, 2443, 2407, -1, 2433, 2444, 2436, -1, 2445, 2446, 2447, -1, 2448, 2446, 2445, -1, 2443, 2449, 2407, -1, 2447, 2446, 2439, -1, 2439, 2446, 2440, -1, 2427, 2450, 2425, -1, 2451, 2452, 2453, -1, 2407, 2452, 2451, -1, 2449, 2452, 2407, -1, 2454, 2455, 2453, -1, 2425, 2450, 2442, -1, 2453, 2455, 2451, -1, 2442, 2456, 2433, -1, 2433, 2456, 2444, -1, 2432, 2457, 2427, -1, 2455, 2458, 2451, -1, 2427, 2457, 2450, -1, 2451, 2459, 2424, -1, 2424, 2459, 2422, -1, 2458, 2459, 2451, -1, 2442, 2460, 2456, -1, 2461, 2462, 2463, -1, 2450, 2460, 2442, -1, 2432, 2464, 2457, -1, 2465, 2462, 2461, -1, 2440, 2464, 2432, -1, 2465, 2466, 2462, -1, 2436, 2467, 2468, -1, 2444, 2467, 2436, -1, 2465, 2469, 2466, -1, 2457, 2470, 2450, -1, 2450, 2470, 2460, -1, 2440, 2471, 2464, -1, 2472, 2473, 2474, -1, 2474, 2473, 2465, -1, 2465, 2473, 2469, -1, 2448, 2471, 2446, -1, 2472, 2475, 2476, -1, 2446, 2471, 2440, -1, 2474, 2475, 2472, -1, 2444, 2477, 2467, -1, 2456, 2477, 2444, -1, 2474, 2478, 2475, -1, 2464, 2479, 2457, -1, 2457, 2479, 2470, -1, 2474, 2480, 2478, -1, 2481, 2480, 2474, -1, 2467, 2482, 2468, -1, 2483, 2484, 2481, -1, 2456, 2485, 2477, -1, 2481, 2484, 2480, -1, 2481, 2486, 2483, -1, 2483, 2486, 2487, -1, 2460, 2485, 2456, -1, 2471, 2488, 2464, -1, 2464, 2488, 2479, -1, 2448, 2488, 2471, -1, 2489, 2488, 2448, -1, 2481, 2490, 2486, -1, 2467, 2491, 2482, -1, 2477, 2491, 2467, -1, 2486, 2490, 2487, -1, 2470, 2492, 2460, -1, 2493, 2494, 2481, -1, 2460, 2492, 2485, -1, 2481, 2494, 2490, -1, 2485, 2495, 2477, -1, 2496, 2497, 2493, -1, 2493, 2497, 2494, -1, 2477, 2495, 2491, -1, 2498, 2499, 2500, -1, 2479, 2501, 2470, -1, 2470, 2501, 2492, -1, 2502, 2499, 2498, -1, 2499, 2503, 2500, -1, 2482, 2504, 2468, -1, 2503, 2505, 2500, -1, 2468, 2504, 2506, -1, 2492, 2507, 2485, -1, 2500, 2505, 2508, -1, 2508, 2505, 2509, -1, 2485, 2507, 2495, -1, 2510, 2511, 2509, -1, 2488, 2512, 2479, -1, 2509, 2511, 2508, -1, 2489, 2512, 2488, -1, 2511, 2513, 2508, -1, 2479, 2512, 2501, -1, 2491, 2514, 2482, -1, 2482, 2514, 2504, -1, 2513, 2515, 2508, -1, 2516, 2515, 2517, -1, 2501, 2518, 2492, -1, 2508, 2515, 2516, -1, 2492, 2518, 2507, -1, 2419, 2519, 2414, -1, 2504, 2520, 2506, -1, 2418, 2519, 2419, -1, 2495, 2521, 2491, -1, 2418, 2522, 2519, -1, 2491, 2521, 2514, -1, 2418, 2523, 2522, -1, 2489, 2524, 2512, -1, 2525, 2524, 2489, -1, 2501, 2524, 2518, -1, 2512, 2524, 2501, -1, 2514, 2526, 2504, -1, 2418, 2527, 2523, -1, 2528, 2527, 2418, -1, 2504, 2526, 2520, -1, 2529, 2527, 2528, -1, 2507, 2530, 2495, -1, 2528, 2531, 2529, -1, 2529, 2531, 2532, -1, 2495, 2530, 2521, -1, 2528, 2533, 2531, -1, 2521, 2534, 2514, -1, 2514, 2534, 2526, -1, 2535, 2536, 2528, -1, 2518, 2537, 2507, -1, 2507, 2537, 2530, -1, 2528, 2536, 2533, -1, 2538, 2539, 2535, -1, 2520, 2540, 2506, -1, 2535, 2539, 2536, -1, 2506, 2540, 2541, -1, 2535, 2542, 2538, -1, 2538, 2542, 2543, -1, 2530, 2544, 2521, -1, 2521, 2544, 2534, -1, 2525, 2545, 2524, -1, 2524, 2545, 2518, -1, 2542, 2546, 2543, -1, 2518, 2545, 2537, -1, 2535, 2546, 2542, -1, 2368, 2547, 2535, -1, 2520, 2548, 2540, -1, 2535, 2547, 2546, -1, 2526, 2548, 2520, -1, 2368, 2549, 2547, -1, 2441, 2549, 2368, -1, 2537, 2550, 2530, -1, 2415, 2551, 2412, -1, 2416, 2551, 2415, -1, 2530, 2550, 2544, -1, 2534, 2552, 2526, -1, 2526, 2552, 2548, -1, 2412, 2553, 2443, -1, 2551, 2553, 2412, -1, 2540, 2554, 2541, -1, 2443, 2553, 2449, -1, 2555, 2556, 2525, -1, 2525, 2556, 2545, -1, 2545, 2556, 2537, -1, 2537, 2556, 2550, -1, 2553, 2557, 2449, -1, 2534, 2558, 2552, -1, 2453, 2559, 2454, -1, 2544, 2558, 2534, -1, 2452, 2559, 2453, -1, 2540, 2560, 2554, -1, 2548, 2560, 2540, -1, 2449, 2561, 2452, -1, 2557, 2561, 2449, -1, 2452, 2561, 2559, -1, 2562, 2563, 2564, -1, 2454, 2563, 2562, -1, 2561, 2563, 2559, -1, 2550, 2565, 2544, -1, 2559, 2563, 2454, -1, 2564, 2566, 2562, -1, 2544, 2565, 2558, -1, 2562, 2566, 2454, -1, 2548, 2567, 2560, -1, 2552, 2567, 2548, -1, 2566, 2568, 2454, -1, 2455, 2568, 2458, -1, 2454, 2568, 2455, -1, 2541, 2569, 2570, -1, 2554, 2569, 2541, -1, 2550, 2571, 2565, -1, 2555, 2571, 2556, -1, 2556, 2571, 2550, -1, 2568, 2572, 2458, -1, 2552, 2573, 2567, -1, 2459, 2574, 2422, -1, 2558, 2573, 2552, -1, 2422, 2574, 2426, -1, 2554, 2575, 2569, -1, 2459, 2576, 2574, -1, 2458, 2576, 2459, -1, 2560, 2575, 2554, -1, 2572, 2576, 2458, -1, 2426, 2577, 2429, -1, 2565, 2578, 2558, -1, 2574, 2577, 2426, -1, 2558, 2578, 2573, -1, 2429, 2577, 2431, -1, 2576, 2577, 2574, -1, 2560, 2579, 2575, -1, 2580, 2581, 2582, -1, 2463, 2581, 2580, -1, 2567, 2579, 2560, -1, 2462, 2583, 2463, -1, 2569, 2584, 2570, -1, 2466, 2583, 2462, -1, 2463, 2583, 2581, -1, 2555, 2585, 2571, -1, 2565, 2585, 2578, -1, 2586, 2585, 2555, -1, 2571, 2585, 2565, -1, 2466, 2587, 2583, -1, 2567, 2588, 2579, -1, 2573, 2588, 2567, -1, 2575, 2589, 2569, -1, 2569, 2589, 2584, -1, 2578, 2590, 2573, -1, 2573, 2590, 2588, -1, 2591, 2592, 2593, -1, 2584, 2594, 2570, -1, 2595, 2596, 2592, -1, 2570, 2594, 2597, -1, 2587, 2596, 2595, -1, 2579, 2598, 2575, -1, 2466, 2599, 2587, -1, 2587, 2599, 2596, -1, 2469, 2599, 2466, -1, 2575, 2598, 2589, -1, 2473, 2599, 2469, -1, 2596, 2600, 2592, -1, 2585, 2601, 2578, -1, 2586, 2601, 2585, -1, 2578, 2601, 2590, -1, 2599, 2602, 2596, -1, 2596, 2602, 2600, -1, 2584, 2603, 2594, -1, 2473, 2602, 2599, -1, 2472, 2602, 2473, -1, 2592, 2604, 2593, -1, 2589, 2603, 2584, -1, 2600, 2604, 2592, -1, 2593, 2604, 2476, -1, 2588, 2605, 2579, -1, 2602, 2604, 2600, -1, 2579, 2605, 2598, -1, 2476, 2604, 2472, -1, 2472, 2604, 2602, -1, 2476, 2606, 2593, -1, 2593, 2606, 2591, -1, 2598, 2607, 2589, -1, 2589, 2607, 2603, -1, 2590, 2608, 2588, -1, 2476, 2609, 2606, -1, 2588, 2608, 2605, -1, 2478, 2609, 2475, -1, 2475, 2609, 2476, -1, 2594, 2610, 2597, -1, 2478, 2611, 2609, -1, 2605, 2612, 2598, -1, 2598, 2612, 2607, -1, 2613, 2614, 2586, -1, 2586, 2614, 2601, -1, 2601, 2614, 2590, -1, 2615, 2616, 2617, -1, 2590, 2614, 2608, -1, 2603, 2618, 2594, -1, 2594, 2618, 2610, -1, 2611, 2619, 2620, -1, 2620, 2619, 2616, -1, 2605, 2621, 2612, -1, 2478, 2622, 2611, -1, 2608, 2621, 2605, -1, 2611, 2622, 2619, -1, 2480, 2622, 2478, -1, 2484, 2622, 2480, -1, 2619, 2623, 2616, -1, 2610, 2624, 2597, -1, 2597, 2624, 2625, -1, 2607, 2626, 2603, -1, 2619, 2627, 2623, -1, 2622, 2627, 2619, -1, 2484, 2627, 2622, -1, 2603, 2626, 2618, -1, 2483, 2627, 2484, -1, 2617, 2628, 2487, -1, 2487, 2628, 2483, -1, 2613, 2629, 2614, -1, 2623, 2628, 2616, -1, 2614, 2629, 2608, -1, 2483, 2628, 2627, -1, 2608, 2629, 2621, -1, 2627, 2628, 2623, -1, 2616, 2628, 2617, -1, 2617, 2630, 2615, -1, 2487, 2630, 2617, -1, 2618, 2631, 2610, -1, 2610, 2631, 2624, -1, 2612, 2632, 2607, -1, 2607, 2632, 2626, -1, 2487, 2633, 2630, -1, 2490, 2633, 2487, -1, 2626, 2634, 2618, -1, 2618, 2634, 2631, -1, 2490, 2635, 2633, -1, 2621, 2636, 2612, -1, 2612, 2636, 2632, -1, 2624, 2637, 2625, -1, 2638, 2639, 2640, -1, 2632, 2641, 2626, -1, 2626, 2641, 2634, -1, 2642, 2643, 2613, -1, 2613, 2643, 2629, -1, 2635, 2644, 2645, -1, 2629, 2643, 2621, -1, 2645, 2644, 2639, -1, 2621, 2643, 2636, -1, 2494, 2646, 2490, -1, 2624, 2647, 2637, -1, 2497, 2646, 2494, -1, 2490, 2646, 2635, -1, 2635, 2646, 2644, -1, 2631, 2647, 2624, -1, 2644, 2648, 2639, -1, 2632, 2649, 2641, -1, 2496, 2650, 2497, -1, 2636, 2649, 2632, -1, 2497, 2650, 2646, -1, 2646, 2650, 2644, -1, 2644, 2650, 2648, -1, 2639, 2651, 2640, -1, 2625, 2652, 2653, -1, 2640, 2651, 2654, -1, 2650, 2651, 2648, -1, 2637, 2652, 2625, -1, 2654, 2651, 2496, -1, 2496, 2651, 2650, -1, 2631, 2655, 2647, -1, 2648, 2651, 2639, -1, 2656, 2657, 2502, -1, 2658, 2657, 2656, -1, 2634, 2655, 2631, -1, 2643, 2659, 2636, -1, 2636, 2659, 2649, -1, 2657, 2660, 2502, -1, 2642, 2659, 2643, -1, 2502, 2660, 2499, -1, 2499, 2660, 2503, -1, 2637, 2661, 2652, -1, 2647, 2661, 2637, -1, 2634, 2662, 2655, -1, 2660, 2663, 2503, -1, 2641, 2662, 2634, -1, 2647, 2664, 2661, -1, 2505, 2665, 2509, -1, 2509, 2665, 2510, -1, 2663, 2666, 2503, -1, 2655, 2664, 2647, -1, 2503, 2666, 2505, -1, 2505, 2666, 2665, -1, 2641, 2667, 2662, -1, 2668, 2669, 2670, -1, 2649, 2667, 2641, -1, 2510, 2669, 2668, -1, 2662, 2671, 2655, -1, 2665, 2669, 2510, -1, 2655, 2671, 2664, -1, 2666, 2669, 2665, -1, 2670, 2672, 2668, -1, 2668, 2672, 2510, -1, 2652, 2673, 2653, -1, 2511, 2674, 2513, -1, 2672, 2674, 2510, -1, 2510, 2674, 2511, -1, 2649, 2675, 2667, -1, 2659, 2675, 2649, -1, 2642, 2675, 2659, -1, 2676, 2675, 2642, -1, 2674, 2677, 2513, -1, 2667, 2678, 2662, -1, 2662, 2678, 2671, -1, 2661, 2679, 2652, -1, 2515, 2680, 2517, -1, 2652, 2679, 2673, -1, 2517, 2680, 2681, -1, 2513, 2682, 2515, -1, 2515, 2682, 2680, -1, 2673, 2683, 2653, -1, 2677, 2682, 2513, -1, 2653, 2683, 2684, -1, 2680, 2685, 2681, -1, 2675, 2686, 2667, -1, 2681, 2685, 2687, -1, 2667, 2686, 2678, -1, 2687, 2685, 2688, -1, 2676, 2686, 2675, -1, 2682, 2685, 2680, -1, 2661, 2689, 2679, -1, 2413, 2690, 2409, -1, 2414, 2690, 2413, -1, 2664, 2689, 2661, -1, 2522, 2691, 2519, -1, 2679, 2692, 2673, -1, 2519, 2691, 2414, -1, 2673, 2692, 2683, -1, 2414, 2691, 2690, -1, 2671, 2693, 2664, -1, 2664, 2693, 2689, -1, 2522, 2694, 2691, -1, 2679, 2695, 2692, -1, 2689, 2695, 2679, -1, 2678, 2696, 2671, -1, 2265, 2697, 2698, -1, 2671, 2696, 2693, -1, 2693, 2699, 2689, -1, 2689, 2699, 2695, -1, 2694, 2700, 2701, -1, 2701, 2700, 2697, -1, 2683, 2702, 2684, -1, 2523, 2703, 2522, -1, 2694, 2703, 2700, -1, 2527, 2703, 2523, -1, 2522, 2703, 2694, -1, 2704, 2705, 2676, -1, 2678, 2705, 2696, -1, 2676, 2705, 2686, -1, 2686, 2705, 2678, -1, 2700, 2706, 2697, -1, 2693, 2707, 2699, -1, 2696, 2707, 2693, -1, 2529, 2708, 2527, -1, 2703, 2708, 2700, -1, 2527, 2708, 2703, -1, 2700, 2708, 2706, -1, 2692, 2709, 2683, -1, 2532, 2710, 2529, -1, 2683, 2709, 2702, -1, 2697, 2710, 2698, -1, 2706, 2710, 2697, -1, 2698, 2710, 2532, -1, 2529, 2710, 2708, -1, 2708, 2710, 2706, -1, 2698, 2711, 2265, -1, 2704, 2712, 2705, -1, 2705, 2712, 2696, -1, 2696, 2712, 2707, -1, 2532, 2711, 2698, -1, 2695, 2582, 2692, -1, 2692, 2582, 2709, -1, 2533, 2713, 2531, -1, 2531, 2713, 2532, -1, 2532, 2713, 2711, -1, 2699, 2580, 2695, -1, 2695, 2580, 2582, -1, 2533, 2714, 2713, -1, 2707, 2463, 2699, -1, 2699, 2463, 2580, -1, 2287, 2715, 2716, -1, 2465, 2461, 2704, -1, 2704, 2461, 2712, -1, 2714, 2717, 2718, -1, 2712, 2461, 2707, -1, 2707, 2461, 2463, -1, 2718, 2717, 2715, -1, 2714, 2719, 2717, -1, 2536, 2719, 2533, -1, 2539, 2719, 2536, -1, 2533, 2719, 2714, -1, 2717, 2720, 2715, -1, 2538, 2721, 2539, -1, 2719, 2721, 2717, -1, 2539, 2721, 2719, -1, 2717, 2721, 2720, -1, 2543, 2722, 2538, -1, 2716, 2722, 2543, -1, 2715, 2722, 2716, -1, 2538, 2722, 2721, -1, 2720, 2722, 2715, -1, 2721, 2722, 2720, -1, 2716, 2723, 2287, -1, 2543, 2723, 2716, -1, 2546, 2724, 2543, -1, 2543, 2724, 2723, -1, 2546, 2725, 2724, -1, 2307, 2726, 2434, -1, 2725, 2727, 2728, -1, 2728, 2727, 2726, -1, 2547, 2729, 2546, -1, 2549, 2729, 2547, -1, 2546, 2729, 2725, -1, 2725, 2729, 2727, -1, 2727, 2730, 2726, -1, 2727, 2731, 2730, -1, 2441, 2731, 2549, -1, 2549, 2731, 2729, -1, 2729, 2731, 2727, -1, 2730, 2732, 2726, -1, 2441, 2732, 2731, -1, 2437, 2732, 2441, -1, 2434, 2732, 2437, -1, 2731, 2732, 2730, -1, 2726, 2732, 2434, -1, 2416, 2733, 2551, -1, 2551, 2733, 2553, -1, 2417, 2733, 2416, -1, 2553, 2733, 2557, -1, 2733, 2734, 2557, -1, 2564, 2735, 2736, -1, 2734, 2735, 2557, -1, 2563, 2735, 2564, -1, 2557, 2735, 2561, -1, 2561, 2735, 2563, -1, 2736, 2737, 2564, -1, 2564, 2737, 2566, -1, 2566, 2737, 2568, -1, 2738, 2739, 2740, -1, 2568, 2737, 2572, -1, 2740, 2739, 2741, -1, 2737, 2742, 2572, -1, 2743, 2744, 2738, -1, 2431, 2745, 2439, -1, 2742, 2745, 2572, -1, 2572, 2745, 2576, -1, 2738, 2744, 2739, -1, 2577, 2745, 2431, -1, 2576, 2745, 2577, -1, 2583, 2746, 2581, -1, 2743, 2747, 2744, -1, 2587, 2746, 2583, -1, 2638, 2747, 2743, -1, 2582, 2746, 2709, -1, 2581, 2746, 2582, -1, 2640, 2748, 2638, -1, 2638, 2748, 2747, -1, 2654, 2749, 2640, -1, 2587, 2750, 2746, -1, 2640, 2749, 2748, -1, 2591, 2751, 2592, -1, 2587, 2751, 2750, -1, 2739, 2752, 2741, -1, 2592, 2751, 2595, -1, 2595, 2751, 2587, -1, 2591, 2753, 2754, -1, 2741, 2752, 2755, -1, 2606, 2753, 2591, -1, 2609, 2753, 2606, -1, 2611, 2753, 2609, -1, 2756, 2757, 2493, -1, 2654, 2757, 2749, -1, 2493, 2757, 2496, -1, 2496, 2757, 2654, -1, 2744, 2758, 2739, -1, 2739, 2758, 2752, -1, 2611, 2759, 2753, -1, 2747, 2760, 2744, -1, 2620, 2761, 2611, -1, 2744, 2760, 2758, -1, 2615, 2761, 2616, -1, 2616, 2761, 2620, -1, 2611, 2761, 2759, -1, 2615, 2762, 2763, -1, 2748, 2764, 2747, -1, 2633, 2762, 2630, -1, 2635, 2762, 2633, -1, 2747, 2764, 2760, -1, 2630, 2762, 2615, -1, 2749, 2765, 2748, -1, 2748, 2765, 2764, -1, 2635, 2766, 2762, -1, 2752, 2767, 2755, -1, 2755, 2767, 2768, -1, 2635, 2769, 2766, -1, 2645, 2769, 2635, -1, 2770, 2771, 2756, -1, 2638, 2769, 2639, -1, 2756, 2771, 2757, -1, 2639, 2769, 2645, -1, 2757, 2771, 2749, -1, 2749, 2771, 2765, -1, 2658, 2772, 2657, -1, 2657, 2772, 2660, -1, 2758, 2773, 2752, -1, 2774, 2772, 2658, -1, 2752, 2773, 2767, -1, 2660, 2772, 2663, -1, 2758, 2775, 2773, -1, 2760, 2775, 2758, -1, 2772, 2776, 2663, -1, 2663, 2777, 2666, -1, 2776, 2777, 2663, -1, 2760, 2778, 2775, -1, 2670, 2777, 2779, -1, 2764, 2778, 2760, -1, 2666, 2777, 2669, -1, 2669, 2777, 2670, -1, 2672, 2780, 2674, -1, 2670, 2780, 2672, -1, 2674, 2780, 2677, -1, 2765, 2781, 2764, -1, 2779, 2780, 2670, -1, 2764, 2781, 2778, -1, 2768, 2498, 2500, -1, 2767, 2498, 2768, -1, 2780, 2782, 2677, -1, 2765, 2783, 2781, -1, 2784, 2783, 2770, -1, 2770, 2783, 2771, -1, 2685, 2785, 2688, -1, 2682, 2785, 2685, -1, 2771, 2783, 2765, -1, 2677, 2785, 2682, -1, 2688, 2785, 2786, -1, 2782, 2785, 2677, -1, 2690, 2787, 2409, -1, 2773, 2502, 2767, -1, 2691, 2787, 2690, -1, 2694, 2787, 2691, -1, 2767, 2502, 2498, -1, 2409, 2787, 2405, -1, 2773, 2656, 2502, -1, 2775, 2656, 2773, -1, 2775, 2658, 2656, -1, 2694, 2251, 2787, -1, 2778, 2658, 2775, -1, 2781, 2774, 2778, -1, 2694, 2257, 2251, -1, 2778, 2774, 2658, -1, 2265, 2257, 2697, -1, 2701, 2257, 2694, -1, 2697, 2257, 2701, -1, 2265, 2271, 2263, -1, 2711, 2271, 2265, -1, 2713, 2271, 2711, -1, 2714, 2271, 2713, -1, 2784, 2788, 2783, -1, 2781, 2788, 2774, -1, 2789, 2788, 2784, -1, 2783, 2788, 2781, -1, 2714, 2272, 2271, -1, 2714, 2280, 2272, -1, 2718, 2280, 2714, -1, 2287, 2280, 2715, -1, 2715, 2280, 2718, -1, 2723, 2291, 2287, -1, 2724, 2291, 2723, -1, 2287, 2291, 2286, -1, 2725, 2291, 2724, -1, 2725, 2293, 2291, -1, 2725, 2301, 2293, -1, 2307, 2301, 2726, -1, 2728, 2301, 2725, -1, 2726, 2301, 2728, -1, 2420, 2790, 2417, -1, 2421, 2790, 2420, -1, 2417, 2791, 2733, -1, 2733, 2791, 2734, -1, 2790, 2791, 2417, -1, 2517, 2792, 2516, -1, 2421, 2793, 2790, -1, 2791, 2793, 2734, -1, 2794, 2793, 2421, -1, 2790, 2793, 2791, -1, 2735, 2795, 2736, -1, 2793, 2795, 2734, -1, 2734, 2795, 2735, -1, 2681, 2796, 2517, -1, 2793, 2797, 2795, -1, 2794, 2797, 2793, -1, 2517, 2796, 2792, -1, 2795, 2797, 2736, -1, 2736, 2797, 2798, -1, 2798, 2797, 2794, -1, 2798, 2799, 2736, -1, 2687, 2800, 2681, -1, 2794, 2799, 2798, -1, 2799, 2801, 2736, -1, 2681, 2800, 2796, -1, 2737, 2801, 2742, -1, 2736, 2801, 2737, -1, 2794, 2802, 2799, -1, 2801, 2802, 2742, -1, 2445, 2802, 2794, -1, 2799, 2802, 2801, -1, 2687, 2803, 2800, -1, 2688, 2803, 2687, -1, 2802, 2804, 2742, -1, 2745, 2804, 2439, -1, 2792, 2805, 2516, -1, 2742, 2804, 2745, -1, 2447, 2806, 2445, -1, 2802, 2806, 2804, -1, 2804, 2806, 2439, -1, 2516, 2805, 2807, -1, 2439, 2806, 2447, -1, 2445, 2806, 2802, -1, 2709, 2808, 2702, -1, 2702, 2808, 2684, -1, 2808, 2809, 2684, -1, 2746, 2809, 2709, -1, 2786, 2810, 2688, -1, 2709, 2809, 2808, -1, 2688, 2810, 2803, -1, 2750, 2809, 2746, -1, 2792, 2811, 2805, -1, 2809, 2812, 2684, -1, 2796, 2811, 2792, -1, 2750, 2812, 2809, -1, 2684, 2812, 2813, -1, 2805, 2814, 2807, -1, 2751, 2815, 2750, -1, 2750, 2815, 2812, -1, 2816, 2817, 2818, -1, 2812, 2815, 2813, -1, 2818, 2817, 2819, -1, 2819, 2817, 2786, -1, 2786, 2817, 2810, -1, 2815, 2820, 2813, -1, 2813, 2820, 2821, -1, 2821, 2822, 2754, -1, 2754, 2822, 2591, -1, 2800, 2823, 2796, -1, 2591, 2822, 2751, -1, 2820, 2822, 2821, -1, 2751, 2822, 2815, -1, 2796, 2823, 2811, -1, 2815, 2822, 2820, -1, 2754, 2824, 2821, -1, 2811, 2825, 2805, -1, 2805, 2825, 2814, -1, 2821, 2824, 2813, -1, 2803, 2826, 2800, -1, 2753, 2827, 2754, -1, 2800, 2826, 2823, -1, 2754, 2827, 2824, -1, 2824, 2827, 2813, -1, 2759, 2827, 2753, -1, 2811, 2828, 2825, -1, 2759, 2829, 2827, -1, 2823, 2828, 2811, -1, 2827, 2829, 2813, -1, 2813, 2829, 2830, -1, 2803, 2831, 2826, -1, 2810, 2831, 2803, -1, 2761, 2832, 2759, -1, 2829, 2832, 2830, -1, 2759, 2832, 2829, -1, 2830, 2833, 2834, -1, 2832, 2833, 2830, -1, 2807, 2835, 2836, -1, 2814, 2835, 2807, -1, 2763, 2837, 2615, -1, 2615, 2837, 2761, -1, 2834, 2837, 2763, -1, 2761, 2837, 2832, -1, 2833, 2837, 2834, -1, 2832, 2837, 2833, -1, 2834, 2838, 2830, -1, 2763, 2838, 2834, -1, 2826, 2839, 2823, -1, 2823, 2839, 2828, -1, 2810, 2840, 2831, -1, 2816, 2840, 2817, -1, 2766, 2841, 2762, -1, 2817, 2840, 2810, -1, 2762, 2841, 2763, -1, 2814, 2842, 2835, -1, 2838, 2841, 2830, -1, 2763, 2841, 2838, -1, 2825, 2842, 2814, -1, 2766, 2843, 2841, -1, 2826, 2844, 2839, -1, 2841, 2843, 2830, -1, 2830, 2843, 2740, -1, 2769, 2845, 2766, -1, 2831, 2844, 2826, -1, 2843, 2845, 2740, -1, 2766, 2845, 2843, -1, 2738, 2846, 2743, -1, 2835, 2847, 2836, -1, 2740, 2846, 2738, -1, 2845, 2846, 2740, -1, 2825, 2848, 2842, -1, 2743, 2849, 2638, -1, 2638, 2849, 2769, -1, 2846, 2849, 2743, -1, 2769, 2849, 2845, -1, 2845, 2849, 2846, -1, 2828, 2848, 2825, -1, 2788, 2850, 2774, -1, 2816, 2851, 2840, -1, 2789, 2850, 2788, -1, 2831, 2851, 2844, -1, 2852, 2851, 2816, -1, 2840, 2851, 2831, -1, 2842, 2853, 2835, -1, 2835, 2853, 2847, -1, 2850, 2854, 2774, -1, 2772, 2854, 2776, -1, 2774, 2854, 2772, -1, 2855, 2856, 2789, -1, 2828, 2857, 2848, -1, 2839, 2857, 2828, -1, 2854, 2856, 2776, -1, 2842, 2261, 2853, -1, 2850, 2856, 2854, -1, 2789, 2856, 2850, -1, 2777, 2858, 2779, -1, 2848, 2261, 2842, -1, 2856, 2858, 2776, -1, 2776, 2858, 2777, -1, 2859, 2860, 2855, -1, 2779, 2860, 2859, -1, 2855, 2860, 2856, -1, 2839, 2245, 2857, -1, 2858, 2860, 2779, -1, 2856, 2860, 2858, -1, 2844, 2245, 2839, -1, 2855, 2861, 2859, -1, 2859, 2861, 2779, -1, 2847, 2255, 2836, -1, 2836, 2255, 2274, -1, 2780, 2862, 2782, -1, 2857, 2259, 2848, -1, 2848, 2259, 2261, -1, 2779, 2862, 2780, -1, 2861, 2862, 2779, -1, 2855, 2863, 2861, -1, 2844, 2864, 2245, -1, 2861, 2863, 2862, -1, 2818, 2863, 2855, -1, 2851, 2864, 2844, -1, 2852, 2864, 2851, -1, 2853, 2253, 2847, -1, 2862, 2863, 2782, -1, 2863, 2865, 2782, -1, 2847, 2253, 2255, -1, 2785, 2865, 2786, -1, 2782, 2865, 2785, -1, 2863, 2866, 2865, -1, 2865, 2866, 2786, -1, 2819, 2866, 2818, -1, 2818, 2866, 2863, -1, 2857, 2247, 2259, -1, 2786, 2866, 2819, -1, 2245, 2247, 2857, -1, 2398, 2867, 2248, -1, 2405, 2867, 2398, -1, 2255, 2256, 2274, -1, 2405, 2868, 2867, -1, 2867, 2868, 2248, -1, 2251, 2868, 2787, -1, 2853, 2266, 2253, -1, 2787, 2868, 2405, -1, 2261, 2266, 2853, -1, 2251, 2249, 2868, -1, 2284, 2246, 2852, -1, 2868, 2249, 2248, -1, 2864, 2246, 2245, -1, 2852, 2246, 2864, -1, 2869, 2870, 2871, -1, 2869, 2872, 2870, -1, 2873, 2874, 2875, -1, 2876, 2877, 2872, -1, 2873, 2875, 2878, -1, 2873, 2879, 2880, -1, 2873, 2880, 2874, -1, 2876, 2872, 2869, -1, 2881, 2878, 2882, -1, 2881, 2883, 2879, -1, 2881, 2884, 2883, -1, 2881, 2879, 2873, -1, 2881, 2873, 2878, -1, 2885, 2886, 2887, -1, 2888, 2877, 2876, -1, 2885, 2887, 2889, -1, 2888, 2890, 2877, -1, 2885, 2889, 2891, -1, 2892, 2885, 2891, -1, 2892, 2886, 2885, -1, 2893, 2894, 2887, -1, 2895, 2896, 2897, -1, 2893, 2887, 2886, -1, 2898, 2899, 2900, -1, 2898, 2871, 2899, -1, 2893, 2875, 2894, -1, 2901, 2892, 2891, -1, 2901, 2886, 2892, -1, 2901, 2902, 2903, -1, 2901, 2891, 2902, -1, 2904, 2871, 2898, -1, 2901, 2903, 2886, -1, 2905, 2875, 2893, -1, 2904, 2869, 2871, -1, 2905, 2882, 2878, -1, 2905, 2878, 2875, -1, 2906, 2905, 2893, -1, 2907, 2876, 2869, -1, 2907, 2869, 2904, -1, 2908, 2888, 2876, -1, 2909, 2903, 2910, -1, 2908, 2876, 2907, -1, 2909, 2886, 2903, -1, 2911, 2896, 2912, -1, 2911, 2913, 2896, -1, 2914, 2910, 2915, -1, 2914, 2909, 2910, -1, 2916, 2917, 2909, -1, 2916, 2909, 2914, -1, 2918, 2919, 2920, -1, 2918, 2921, 2919, -1, 2922, 2914, 2915, -1, 2922, 2916, 2914, -1, 2922, 2915, 2923, -1, 2922, 2923, 2924, -1, 2925, 2921, 2918, -1, 2926, 2916, 2922, -1, 2925, 2927, 2921, -1, 2926, 2917, 2916, -1, 2926, 2928, 2917, -1, 2926, 2922, 2924, -1, 2926, 2924, 2929, -1, 2930, 2907, 2904, -1, 2931, 2932, 2927, -1, 2931, 2927, 2925, -1, 2933, 2934, 2935, -1, 2936, 2937, 2932, -1, 2933, 2935, 2908, -1, 2933, 2938, 2934, -1, 2936, 2932, 2931, -1, 2933, 2907, 2930, -1, 2933, 2930, 2939, -1, 2933, 2908, 2907, -1, 2940, 2918, 2920, -1, 2941, 2937, 2936, -1, 2941, 2942, 2937, -1, 2943, 2918, 2940, -1, 2944, 2927, 2932, -1, 2945, 2946, 2938, -1, 2943, 2925, 2918, -1, 2945, 2947, 2946, -1, 2945, 2937, 2947, -1, 2948, 2942, 2941, -1, 2948, 2949, 2950, -1, 2948, 2950, 2942, -1, 2945, 2944, 2932, -1, 2945, 2951, 2944, -1, 2945, 2932, 2937, -1, 2952, 2953, 2913, -1, 2954, 2920, 2955, -1, 2952, 2956, 2957, -1, 2954, 2940, 2920, -1, 2952, 2913, 2956, -1, 2958, 2957, 2934, -1, 2958, 2934, 2938, -1, 2958, 2953, 2952, -1, 2958, 2959, 2953, -1, 2958, 2938, 2946, -1, 2960, 2925, 2943, -1, 2958, 2946, 2959, -1, 2958, 2952, 2957, -1, 2961, 2962, 2963, -1, 2960, 2931, 2925, -1, 2961, 2964, 2962, -1, 2961, 2963, 2965, -1, 2966, 2940, 2954, -1, 2966, 2943, 2940, -1, 2967, 2964, 2961, -1, 2968, 2936, 2931, -1, 2967, 2969, 2964, -1, 2968, 2931, 2960, -1, 2967, 2970, 2969, -1, 2971, 2960, 2943, -1, 2972, 2967, 2961, -1, 2971, 2943, 2966, -1, 2973, 2941, 2936, -1, 2973, 2936, 2968, -1, 2974, 2968, 2960, -1, 2974, 2960, 2971, -1, 2975, 2965, 2976, -1, 2975, 2976, 2977, -1, 2975, 2977, 2978, -1, 2979, 2948, 2941, -1, 2979, 2949, 2948, -1, 2979, 2941, 2973, -1, 2979, 2980, 2949, -1, 2981, 2954, 2955, -1, 2982, 2975, 2978, -1, 2982, 2983, 2975, -1, 2984, 2973, 2968, -1, 2982, 2978, 2985, -1, 2984, 2968, 2974, -1, 2982, 2985, 2986, -1, 2987, 2988, 2989, -1, 2990, 2966, 2954, -1, 2987, 2978, 2991, -1, 2990, 2954, 2981, -1, 2987, 2991, 2988, -1, 2992, 2985, 2978, -1, 2992, 2986, 2985, -1, 2993, 2973, 2984, -1, 2993, 2979, 2973, -1, 2993, 2980, 2979, -1, 2992, 2978, 2987, -1, 2994, 2971, 2966, -1, 2994, 2966, 2990, -1, 2995, 2992, 2987, -1, 2996, 2955, 2997, -1, 2998, 2989, 2999, -1, 2996, 2981, 2955, -1, 2998, 2999, 3000, -1, 3001, 2974, 2971, -1, 3001, 2971, 2994, -1, 3002, 2981, 2996, -1, 3002, 2990, 2981, -1, 3003, 2984, 2974, -1, 3004, 3005, 2998, -1, 3004, 3000, 3006, -1, 3003, 2974, 3001, -1, 3004, 2998, 3000, -1, 3007, 2994, 2990, -1, 3007, 2990, 3002, -1, 3008, 3004, 3006, -1, 3009, 2993, 2984, -1, 3008, 3010, 3011, -1, 3009, 2980, 2993, -1, 3008, 3006, 3010, -1, 3009, 2984, 3003, -1, 3012, 3011, 3013, -1, 3012, 3005, 3004, -1, 3009, 3014, 2980, -1, 3012, 3008, 3011, -1, 3012, 3015, 3005, -1, 3016, 3001, 2994, -1, 3012, 3004, 3008, -1, 3016, 2994, 3007, -1, 3017, 3018, 3019, -1, 3017, 3010, 3018, -1, 3020, 2996, 2997, -1, 3017, 3019, 3021, -1, 3022, 3013, 3011, -1, 3022, 3010, 3017, -1, 3023, 3003, 3001, -1, 3023, 3001, 3016, -1, 3022, 3011, 3010, -1, 3024, 2996, 3020, -1, 3024, 3002, 2996, -1, 3025, 3022, 3017, -1, 3026, 3009, 3003, -1, 3026, 3014, 3009, -1, 3026, 3003, 3023, -1, 3027, 3021, 3028, -1, 3027, 3028, 3029, -1, 3030, 3007, 3002, -1, 3030, 3002, 3024, -1, 3031, 2997, 3032, -1, 3031, 3020, 2997, -1, 3033, 3027, 3029, -1, 3034, 3016, 3007, -1, 3033, 3029, 3035, -1, 3034, 3007, 3030, -1, 3036, 3024, 3020, -1, 3037, 3027, 3033, -1, 3037, 3038, 3027, -1, 3036, 3020, 3031, -1, 3039, 3023, 3016, -1, 3039, 3016, 3034, -1, 3040, 3041, 3042, -1, 3040, 3035, 3041, -1, 3040, 3033, 3035, -1, 3040, 3037, 3033, -1, 3043, 3024, 3036, -1, 3044, 3042, 3045, -1, 3044, 3040, 3042, -1, 3043, 3030, 3024, -1, 3044, 3038, 3037, -1, 3044, 3046, 3038, -1, 3044, 3037, 3040, -1, 3047, 3023, 3039, -1, 3048, 3049, 3050, -1, 3047, 3051, 3014, -1, 3047, 3014, 3026, -1, 3047, 3026, 3023, -1, 3048, 3052, 3053, -1, 3048, 3050, 3052, -1, 3054, 3049, 3048, -1, 3055, 3031, 3032, -1, 3054, 3048, 3053, -1, 3056, 3050, 3049, -1, 3057, 3030, 3043, -1, 3056, 3058, 3050, -1, 3057, 3034, 3030, -1, 3056, 3041, 3058, -1, 3059, 3036, 3031, -1, 3060, 3053, 3061, -1, 3060, 3061, 3062, -1, 3060, 3062, 3049, -1, 3060, 3049, 3054, -1, 3060, 3054, 3053, -1, 3059, 3031, 3055, -1, 3063, 3042, 3041, -1, 3064, 3039, 3034, -1, 3063, 3045, 3042, -1, 3064, 3034, 3057, -1, 3063, 3041, 3056, -1, 3065, 3063, 3056, -1, 3066, 3036, 3059, -1, 3066, 3043, 3036, -1, 3067, 3062, 3068, -1, 3069, 3047, 3039, -1, 3069, 3051, 3047, -1, 3069, 3039, 3064, -1, 3067, 3049, 3062, -1, 3070, 3032, 3071, -1, 3070, 3055, 3032, -1, 3072, 3043, 3066, -1, 3073, 3067, 3068, -1, 3072, 3057, 3043, -1, 3073, 3068, 3074, -1, 3075, 3055, 3070, -1, 3076, 3077, 3078, -1, 3075, 3059, 3055, -1, 3079, 3067, 3073, -1, 3079, 3080, 3067, -1, 3081, 3057, 3072, -1, 3081, 3064, 3057, -1, 3082, 3066, 3059, -1, 3082, 3059, 3075, -1, 3083, 3084, 3085, -1, 3083, 3079, 3073, -1, 3086, 3051, 3069, -1, 3083, 3073, 3074, -1, 3086, 3064, 3081, -1, 3083, 3074, 3084, -1, 3086, 3069, 3064, -1, 3087, 3085, 3088, -1, 3086, 3089, 3051, -1, 3087, 3080, 3079, -1, 3090, 3070, 3071, -1, 3087, 3083, 3085, -1, 3087, 3091, 3080, -1, 3087, 3079, 3083, -1, 3092, 3093, 3094, -1, 3095, 3072, 3066, -1, 3092, 3096, 3093, -1, 3095, 3066, 3082, -1, 3092, 3097, 3098, -1, 3092, 3099, 3096, -1, 3092, 3098, 3099, -1, 3092, 3094, 3097, -1, 3100, 3101, 3102, -1, 3100, 3093, 3096, -1, 3100, 3103, 3101, -1, 3104, 3105, 3106, -1, 3107, 3075, 3070, -1, 3100, 3102, 3093, -1, 3104, 3108, 3105, -1, 3109, 3096, 3099, -1, 3109, 3110, 3111, -1, 3107, 3070, 3090, -1, 3109, 3099, 3110, -1, 3109, 3112, 3103, -1, 3113, 3081, 3072, -1, 3109, 3111, 3112, -1, 3113, 3072, 3095, -1, 3109, 3100, 3096, -1, 3109, 3103, 3100, -1, 3114, 3108, 3104, -1, 3115, 3116, 3117, -1, 3115, 3117, 3118, -1, 3114, 3119, 3108, -1, 3115, 3120, 3121, -1, 3115, 3118, 3122, -1, 3123, 3082, 3075, -1, 3115, 3124, 3120, -1, 3115, 3122, 3124, -1, 3115, 3121, 3116, -1, 3123, 3075, 3107, -1, 3125, 3119, 3114, -1, 3126, 3111, 3127, -1, 3126, 3121, 3120, -1, 3125, 3128, 3119, -1, 3129, 3086, 3081, -1, 3126, 3127, 3121, -1, 3129, 3089, 3086, -1, 3126, 3112, 3111, -1, 3129, 3081, 3113, -1, 3130, 3112, 3126, -1, 3130, 3131, 3132, -1, 3130, 3126, 3120, -1, 3130, 3120, 3124, -1, 3133, 3071, 3134, -1, 3130, 3135, 3131, -1, 3133, 3090, 3071, -1, 3130, 3124, 3135, -1, 3136, 3128, 3125, -1, 3130, 3132, 3112, -1, 3136, 3137, 3128, -1, 3138, 3139, 3140, -1, 3138, 3141, 3139, -1, 3138, 3140, 3142, -1, 3138, 3143, 3141, -1, 3144, 3095, 3082, -1, 3138, 3142, 2883, -1, 3145, 3137, 3136, -1, 3138, 2884, 3143, -1, 3144, 3082, 3123, -1, 3138, 2883, 2884, -1, 3145, 3146, 3137, -1, 3147, 3131, 3148, -1, 3149, 3150, 3146, -1, 3147, 3132, 3131, -1, 3149, 3151, 3150, -1, 3149, 3146, 3145, -1, 3152, 3090, 3133, -1, 3147, 3148, 3141, -1, 3149, 3153, 3151, -1, 3152, 3107, 3090, -1, 3147, 3141, 3143, -1, 3154, 3147, 3143, -1, 3154, 2882, 3155, -1, 3154, 3155, 3132, -1, 3154, 3132, 3147, -1, 3156, 3106, 3157, -1, 3154, 3143, 2884, -1, 3154, 2881, 2882, -1, 3156, 3104, 3106, -1, 3158, 3113, 3095, -1, 3154, 2884, 2881, -1, 3159, 2909, 2917, -1, 3159, 2906, 2893, -1, 3160, 3104, 3156, -1, 3158, 3095, 3144, -1, 3159, 2893, 2886, -1, 3159, 2928, 3161, -1, 3159, 3161, 2906, -1, 3160, 3114, 3104, -1, 3159, 2886, 2909, -1, 3159, 2917, 2928, -1, 3162, 3123, 3107, -1, 3163, 2905, 2906, -1, 3163, 2906, 3161, -1, 3162, 3107, 3152, -1, 3163, 2882, 2905, -1, 3163, 3155, 2882, -1, 3164, 3161, 2928, -1, 3165, 3089, 3129, -1, 3164, 3163, 3161, -1, 3165, 3129, 3113, -1, 3164, 3155, 3163, -1, 3166, 3114, 3160, -1, 3165, 3113, 3158, -1, 3164, 2926, 2929, -1, 3164, 2928, 2926, -1, 3166, 3125, 3114, -1, 3165, 3167, 3089, -1, 3164, 2929, 3168, -1, 3164, 3168, 3155, -1, 3169, 3125, 3166, -1, 3170, 3133, 3134, -1, 3171, 3172, 2939, -1, 3171, 2904, 2898, -1, 3171, 2939, 2930, -1, 3169, 3136, 3125, -1, 3173, 3144, 3123, -1, 3171, 2898, 2900, -1, 3173, 3123, 3162, -1, 3171, 2930, 2904, -1, 3174, 2900, 2919, -1, 3175, 3136, 3169, -1, 3174, 3172, 3171, -1, 3175, 3145, 3136, -1, 3176, 3133, 3170, -1, 3174, 3171, 2900, -1, 3177, 3174, 2919, -1, 3178, 3149, 3145, -1, 3177, 2919, 2921, -1, 3178, 3145, 3175, -1, 3176, 3152, 3133, -1, 3177, 2951, 3172, -1, 3178, 3179, 3153, -1, 3177, 2944, 2951, -1, 3177, 3172, 3174, -1, 3178, 3153, 3149, -1, 3180, 3144, 3173, -1, 3177, 2927, 2944, -1, 3181, 3156, 3157, -1, 3180, 3158, 3144, -1, 3177, 2921, 2927, -1, 3182, 2939, 3172, -1, 3182, 2933, 2939, -1, 3182, 2945, 2938, -1, 3182, 3172, 2951, -1, 3182, 2951, 2945, -1, 3181, 3157, 3183, -1, 3184, 3162, 3152, -1, 3182, 2938, 2933, -1, 3185, 2961, 2965, -1, 3185, 3186, 2972, -1, 3184, 3152, 3176, -1, 3185, 2972, 2961, -1, 3185, 2975, 2983, -1, 3187, 3160, 3156, -1, 3185, 2965, 2975, -1, 3185, 2983, 3186, -1, 3188, 3158, 3180, -1, 3189, 2972, 3186, -1, 3188, 3165, 3158, -1, 3189, 3190, 2970, -1, 3187, 3156, 3181, -1, 3188, 3167, 3165, -1, 3189, 2970, 2967, -1, 3189, 2967, 2972, -1, 3191, 3160, 3187, -1, 3192, 3173, 3162, -1, 3193, 3190, 3189, -1, 3193, 3189, 3186, -1, 3193, 2982, 2986, -1, 3193, 3186, 2983, -1, 3193, 2986, 3194, -1, 3192, 3162, 3184, -1, 3193, 2983, 2982, -1, 3191, 3166, 3160, -1, 3193, 3194, 3190, -1, 3195, 3166, 3191, -1, 3196, 2998, 3005, -1, 3195, 3169, 3166, -1, 3197, 3134, 3198, -1, 3196, 3005, 3015, -1, 3196, 3015, 3199, -1, 3197, 3170, 3134, -1, 3196, 2995, 2987, -1, 3196, 2989, 2998, -1, 3196, 2987, 2989, -1, 3196, 3199, 2995, -1, 3200, 3180, 3173, -1, 3201, 3194, 2986, -1, 3202, 3169, 3195, -1, 3202, 3175, 3169, -1, 3201, 2986, 2992, -1, 3201, 2995, 3199, -1, 3200, 3173, 3192, -1, 3201, 2992, 2995, -1, 3203, 3194, 3201, -1, 3204, 3205, 3179, -1, 3206, 3170, 3197, -1, 3203, 3201, 3199, -1, 3203, 3013, 3207, -1, 3203, 3012, 3013, -1, 3208, 3181, 3183, -1, 3206, 3176, 3170, -1, 3203, 3199, 3015, -1, 3203, 3015, 3012, -1, 3203, 3207, 3194, -1, 3209, 3017, 3021, -1, 3210, 3180, 3200, -1, 3209, 3211, 3025, -1, 3210, 3212, 3167, -1, 3209, 3021, 3027, -1, 3210, 3188, 3180, -1, 3209, 3027, 3038, -1, 3208, 3183, 3213, -1, 3209, 3046, 3211, -1, 3214, 3187, 3181, -1, 3210, 3167, 3188, -1, 3209, 3038, 3046, -1, 3209, 3025, 3017, -1, 3214, 3181, 3208, -1, 3215, 3207, 3013, -1, 3216, 3176, 3206, -1, 3215, 3013, 3022, -1, 3215, 3022, 3025, -1, 3215, 3025, 3211, -1, 3216, 3184, 3176, -1, 3217, 3045, 3218, -1, 3217, 3207, 3215, -1, 3219, 3191, 3187, -1, 3217, 3211, 3046, -1, 3217, 3044, 3045, -1, 3217, 3046, 3044, -1, 3220, 3197, 3198, -1, 3217, 3215, 3211, -1, 3217, 3218, 3207, -1, 3221, 3192, 3184, -1, 3222, 3056, 3049, -1, 3222, 3067, 3080, -1, 3219, 3187, 3214, -1, 3221, 3184, 3216, -1, 3222, 3065, 3056, -1, 3223, 3195, 3191, -1, 3222, 3049, 3067, -1, 3222, 3224, 3065, -1, 3222, 3091, 3224, -1, 3222, 3080, 3091, -1, 3225, 3206, 3197, -1, 3226, 3218, 3045, -1, 3226, 3045, 3063, -1, 3226, 3063, 3065, -1, 3223, 3191, 3219, -1, 3226, 3065, 3224, -1, 3227, 3195, 3223, -1, 3225, 3197, 3220, -1, 3228, 3088, 3229, -1, 3228, 3218, 3226, -1, 3227, 3202, 3195, -1, 3230, 3200, 3192, -1, 3228, 3226, 3224, -1, 3228, 3087, 3088, -1, 3230, 3192, 3221, -1, 3228, 3224, 3091, -1, 3231, 3232, 3205, -1, 3228, 3091, 3087, -1, 3233, 3208, 3213, -1, 3228, 3229, 3218, -1, 3234, 3206, 3225, -1, 3233, 3213, 3235, -1, 3234, 3216, 3206, -1, 3236, 3208, 3233, -1, 3237, 3210, 3200, -1, 3237, 3212, 3210, -1, 3237, 3200, 3230, -1, 3238, 3221, 3216, -1, 3236, 3214, 3208, -1, 3238, 3216, 3234, -1, 3239, 3214, 3236, -1, 3239, 3219, 3214, -1, 3240, 3198, 3241, -1, 3240, 3220, 3198, -1, 3242, 3223, 3219, -1, 3243, 3230, 3221, -1, 3242, 3219, 3239, -1, 3243, 3221, 3238, -1, 3244, 3225, 3220, -1, 3245, 3232, 3246, -1, 3244, 3220, 3240, -1, 3245, 3247, 3232, -1, 3248, 3212, 3237, -1, 3248, 3237, 3230, -1, 3249, 3235, 3250, -1, 3248, 3230, 3243, -1, 3248, 3251, 3212, -1, 3249, 3233, 3235, -1, 3252, 3240, 3241, -1, 3253, 3233, 3249, -1, 3253, 3236, 3233, -1, 3254, 3234, 3225, -1, 3254, 3225, 3244, -1, 3255, 3249, 3250, -1, 3255, 3250, 3256, -1, 3257, 3244, 3240, -1, 3257, 3240, 3252, -1, 3258, 3239, 3236, -1, 3258, 3236, 3253, -1, 3259, 3238, 3234, -1, 3259, 3234, 3254, -1, 3260, 3249, 3255, -1, 3261, 3254, 3244, -1, 3260, 3253, 3249, -1, 3261, 3244, 3257, -1, 3262, 3239, 3258, -1, 3263, 3243, 3238, -1, 3262, 3242, 3239, -1, 3263, 3238, 3259, -1, 3264, 3258, 3253, -1, 3264, 3253, 3260, -1, 3265, 3259, 3254, -1, 3265, 3254, 3261, -1, 3266, 3248, 3243, -1, 3266, 3251, 3248, -1, 3266, 3243, 3263, -1, 3267, 3241, 3268, -1, 3267, 3252, 3241, -1, 3269, 3258, 3264, -1, 3269, 3262, 3258, -1, 3270, 3247, 3271, -1, 3272, 3259, 3265, -1, 3270, 3273, 3247, -1, 3272, 3263, 3259, -1, 3274, 3252, 3267, -1, 3275, 3255, 3256, -1, 3274, 3257, 3252, -1, 3276, 3262, 3269, -1, 3276, 3271, 3262, -1, 3277, 3263, 3272, -1, 3277, 3251, 3266, -1, 3277, 3266, 3263, -1, 3278, 3255, 3275, -1, 3277, 3279, 3251, -1, 3280, 3267, 3268, -1, 3278, 3260, 3255, -1, 3281, 3270, 3271, -1, 3281, 3273, 3270, -1, 3282, 3261, 3257, -1, 3282, 3257, 3274, -1, 3281, 3271, 3276, -1, 3283, 3275, 3256, -1, 3283, 3256, 3284, -1, 3285, 3267, 3280, -1, 3286, 3260, 3278, -1, 3285, 3274, 3267, -1, 3287, 3265, 3261, -1, 3286, 3264, 3260, -1, 3288, 3275, 3283, -1, 3287, 3261, 3282, -1, 3288, 3278, 3275, -1, 3289, 3269, 3264, -1, 3290, 3282, 3274, -1, 3289, 3264, 3286, -1, 3290, 3274, 3285, -1, 3291, 3272, 3265, -1, 3292, 3286, 3278, -1, 3292, 3278, 3288, -1, 3291, 3265, 3287, -1, 3293, 3276, 3269, -1, 3294, 3287, 3282, -1, 3294, 3282, 3290, -1, 3293, 3269, 3289, -1, 3295, 3277, 3272, -1, 3295, 3279, 3277, -1, 3296, 3289, 3286, -1, 3295, 3272, 3291, -1, 3296, 3286, 3292, -1, 3297, 3268, 3298, -1, 3297, 3280, 3268, -1, 3299, 3273, 3281, -1, 3299, 3281, 3276, -1, 3299, 3276, 3293, -1, 3300, 3291, 3287, -1, 3300, 3287, 3294, -1, 3299, 3301, 3273, -1, 3302, 3283, 3284, -1, 3303, 3280, 3297, -1, 3304, 3293, 3289, -1, 3304, 3289, 3296, -1, 3303, 3285, 3280, -1, 3305, 3279, 3295, -1, 3305, 3295, 3291, -1, 3305, 3291, 3300, -1, 3306, 3283, 3302, -1, 3305, 3307, 3279, -1, 3308, 3297, 3298, -1, 3306, 3288, 3283, -1, 3309, 3299, 3293, -1, 3310, 3290, 3285, -1, 3309, 3293, 3304, -1, 3309, 3301, 3299, -1, 3311, 3284, 3312, -1, 3311, 3302, 3284, -1, 3310, 3285, 3303, -1, 3313, 3292, 3288, -1, 3314, 3297, 3308, -1, 3313, 3288, 3306, -1, 3314, 3303, 3297, -1, 3315, 3294, 3290, -1, 3316, 3306, 3302, -1, 3315, 3290, 3310, -1, 3316, 3302, 3311, -1, 3317, 3296, 3292, -1, 3318, 3310, 3303, -1, 3318, 3303, 3314, -1, 3317, 3292, 3313, -1, 3319, 3300, 3294, -1, 3319, 3294, 3315, -1, 3320, 3313, 3306, -1, 3320, 3306, 3316, -1, 3321, 3315, 3310, -1, 3321, 3310, 3318, -1, 3322, 3304, 3296, -1, 3323, 3305, 3300, -1, 3322, 3296, 3317, -1, 3323, 3307, 3305, -1, 3323, 3300, 3319, -1, 3324, 3319, 3315, -1, 3324, 3315, 3321, -1, 3325, 3317, 3313, -1, 3325, 3313, 3320, -1, 3326, 3327, 3301, -1, 3328, 3298, 3329, -1, 3326, 3304, 3322, -1, 3328, 3308, 3298, -1, 3326, 3309, 3304, -1, 3326, 3301, 3309, -1, 3330, 3311, 3312, -1, 3331, 3319, 3324, -1, 3331, 3307, 3323, -1, 3331, 3323, 3319, -1, 3331, 3190, 3307, -1, 3332, 3314, 3308, -1, 3332, 3308, 3328, -1, 3333, 3322, 3317, -1, 3333, 3317, 3325, -1, 3334, 3316, 3311, -1, 3334, 3311, 3330, -1, 3335, 3318, 3314, -1, 3335, 3314, 3332, -1, 3336, 3327, 3326, -1, 3336, 3326, 3322, -1, 3336, 3322, 3333, -1, 2964, 3321, 3318, -1, 2964, 3318, 3335, -1, 3337, 3316, 3334, -1, 3337, 3320, 3316, -1, 2969, 3324, 3321, -1, 2969, 3321, 2964, -1, 3338, 3312, 3339, -1, 3338, 3330, 3312, -1, 2970, 3331, 3324, -1, 2970, 3190, 3331, -1, 2970, 3324, 2969, -1, 3340, 3320, 3337, -1, 3340, 3325, 3320, -1, 3341, 3330, 3338, -1, 3341, 3334, 3330, -1, 3342, 3325, 3340, -1, 3342, 3333, 3325, -1, 3343, 3337, 3334, -1, 3343, 3334, 3341, -1, 3344, 3336, 3333, -1, 3344, 3333, 3342, -1, 3344, 3345, 3327, -1, 3344, 3327, 3336, -1, 3346, 3337, 3343, -1, 3346, 3340, 3337, -1, 3347, 3338, 3339, -1, 3348, 3340, 3346, -1, 3348, 3342, 3340, -1, 3349, 3338, 3347, -1, 3349, 3341, 3338, -1, 3350, 3344, 3342, -1, 3350, 3345, 3344, -1, 3350, 3342, 3348, -1, 3351, 3343, 3341, -1, 3351, 3341, 3349, -1, 3352, 3347, 3339, -1, 3352, 3339, 3353, -1, 3354, 3346, 3343, -1, 3354, 3343, 3351, -1, 3355, 3347, 3352, -1, 3355, 3349, 3347, -1, 3356, 3348, 3346, -1, 3356, 3346, 3354, -1, 3357, 3351, 3349, -1, 3357, 3349, 3355, -1, 3358, 3345, 3350, -1, 3358, 3350, 3348, -1, 3358, 3348, 3356, -1, 3358, 3359, 3345, -1, 3360, 3352, 3353, -1, 3361, 3354, 3351, -1, 3361, 3351, 3357, -1, 3362, 3352, 3360, -1, 3362, 3355, 3352, -1, 3363, 3356, 3354, -1, 3363, 3354, 3361, -1, 3364, 3077, 3076, -1, 3365, 3357, 3355, -1, 3366, 3364, 3076, -1, 3365, 3355, 3362, -1, 3366, 3076, 3367, -1, 3368, 3358, 3356, -1, 3368, 3359, 3358, -1, 3074, 3366, 3367, -1, 3368, 3356, 3363, -1, 3369, 3353, 3370, -1, 3074, 3367, 3371, -1, 3369, 3360, 3353, -1, 3372, 3361, 3357, -1, 3372, 3357, 3365, -1, 3084, 3074, 3371, -1, 3084, 3371, 3373, -1, 3374, 3362, 3360, -1, 3085, 3084, 3373, -1, 3085, 3373, 3375, -1, 3374, 3360, 3369, -1, 3376, 3363, 3361, -1, 3088, 3085, 3375, -1, 3376, 3361, 3372, -1, 3088, 3375, 3377, -1, 3088, 3377, 3378, -1, 3088, 3378, 3229, -1, 3379, 3175, 3202, -1, 3380, 3365, 3362, -1, 3379, 3204, 3179, -1, 3379, 3202, 3204, -1, 3379, 3178, 3175, -1, 3380, 3362, 3374, -1, 3379, 3179, 3178, -1, 3381, 3202, 3227, -1, 3381, 3227, 3231, -1, 3382, 3363, 3376, -1, 3381, 3204, 3202, -1, 3382, 3383, 3359, -1, 3381, 3205, 3204, -1, 3382, 3359, 3368, -1, 3381, 3231, 3205, -1, 3382, 3368, 3363, -1, 3384, 3246, 3232, -1, 3384, 3232, 3231, -1, 3385, 3369, 3370, -1, 3386, 3247, 3245, -1, 3387, 3372, 3365, -1, 3386, 3271, 3247, -1, 3387, 3365, 3380, -1, 3388, 3389, 3390, -1, 3388, 3390, 3391, -1, 3392, 3369, 3385, -1, 3393, 3388, 3391, -1, 3392, 3374, 3369, -1, 3394, 3376, 3372, -1, 3394, 3372, 3387, -1, 3395, 3391, 3396, -1, 3395, 3393, 3391, -1, 3397, 3374, 3392, -1, 3395, 3396, 3398, -1, 3397, 3380, 3374, -1, 3399, 3398, 3396, -1, 3399, 3400, 3398, -1, 3401, 3376, 3394, -1, 3401, 3382, 3376, -1, 3401, 3383, 3382, -1, 3402, 3399, 3396, -1, 3403, 3370, 3404, -1, 3403, 3385, 3370, -1, 3405, 3396, 3406, -1, 3407, 3380, 3397, -1, 3405, 3402, 3396, -1, 3405, 3406, 3408, -1, 3409, 3410, 3408, -1, 3407, 3387, 3380, -1, 3411, 3392, 3385, -1, 3409, 3408, 3406, -1, 3411, 3385, 3403, -1, 3412, 3394, 3387, -1, 3413, 3409, 3406, -1, 3412, 3387, 3407, -1, 3414, 3415, 3416, -1, 3417, 3392, 3411, -1, 3414, 3406, 3415, -1, 3414, 3413, 3406, -1, 3418, 3419, 3416, -1, 3417, 3397, 3392, -1, 3418, 3416, 3415, -1, 3420, 3401, 3394, -1, 3420, 3383, 3401, -1, 3420, 3394, 3412, -1, 3420, 3421, 3383, -1, 3422, 3403, 3404, -1, 2889, 3418, 3415, -1, 2891, 2889, 3415, -1, 2891, 3415, 3423, -1, 3424, 3397, 3417, -1, 2891, 3423, 3425, -1, 3424, 3407, 3397, -1, 3426, 3427, 3428, -1, 3429, 3403, 3422, -1, 3426, 3430, 3427, -1, 3426, 3428, 3431, -1, 3426, 3432, 3430, -1, 3426, 3431, 3432, -1, 3429, 3411, 3403, -1, 3433, 2897, 3432, -1, 3434, 3412, 3407, -1, 3434, 3407, 3424, -1, 3433, 2895, 2897, -1, 3433, 3435, 2895, -1, 3436, 2896, 2895, -1, 3437, 3417, 3411, -1, 3436, 2912, 2896, -1, 3437, 3411, 3429, -1, 2956, 2913, 2911, -1, 3438, 3420, 3412, -1, 3438, 3421, 3420, -1, 3438, 3412, 3434, -1, 2953, 2950, 2949, -1, 2953, 2949, 2913, -1, 3439, 3424, 3417, -1, 3439, 3417, 3437, -1, 3440, 3332, 3328, -1, 3440, 3328, 3329, -1, 3441, 3422, 3404, -1, 3441, 3404, 3442, -1, 3443, 3440, 3329, -1, 3444, 3434, 3424, -1, 3444, 3424, 3439, -1, 3445, 3429, 3422, -1, 3446, 3443, 3329, -1, 3446, 3329, 3447, -1, 3445, 3422, 3441, -1, 3446, 3447, 3448, -1, 3449, 3448, 3447, -1, 3449, 3450, 3448, -1, 3451, 3421, 3438, -1, 3451, 3434, 3444, -1, 3451, 3438, 3434, -1, 3451, 3452, 3421, -1, 3453, 3437, 3429, -1, 3453, 3429, 3445, -1, 3454, 3449, 3447, -1, 3455, 3447, 3456, -1, 3455, 3454, 3447, -1, 3457, 3441, 3442, -1, 3455, 3456, 3458, -1, 3459, 3458, 3456, -1, 3460, 3439, 3437, -1, 3459, 3461, 3458, -1, 3460, 3437, 3453, -1, 3462, 3459, 3456, -1, 3463, 3445, 3441, -1, 3463, 3441, 3457, -1, 3464, 3444, 3439, -1, 3465, 3456, 3466, -1, 3464, 3439, 3460, -1, 3465, 3462, 3456, -1, 3465, 3466, 3467, -1, 3468, 3445, 3463, -1, 3469, 3470, 3467, -1, 3468, 3453, 3445, -1, 3469, 3467, 3466, -1, 3052, 3469, 3466, -1, 3471, 3451, 3444, -1, 3471, 3452, 3451, -1, 3471, 3444, 3464, -1, 3053, 3466, 3077, -1, 3472, 3460, 3453, -1, 3053, 3052, 3466, -1, 3472, 3453, 3468, -1, 3053, 3077, 3364, -1, 3473, 3442, 3474, -1, 3475, 3227, 3223, -1, 3473, 3457, 3442, -1, 3475, 3246, 3384, -1, 3475, 3231, 3227, -1, 3475, 3223, 3242, -1, 3475, 3384, 3231, -1, 3475, 3242, 3246, -1, 3476, 3262, 3271, -1, 3476, 3386, 3245, -1, 3476, 3245, 3246, -1, 3476, 3271, 3386, -1, 3477, 3460, 3472, -1, 3476, 3242, 3262, -1, 3477, 3464, 3460, -1, 3476, 3246, 3242, -1, 3478, 3479, 3480, -1, 3481, 3457, 3473, -1, 3478, 3480, 3389, -1, 3481, 3463, 3457, -1, 3482, 3478, 3389, -1, 3482, 3388, 3393, -1, 3483, 3452, 3471, -1, 3483, 3484, 3452, -1, 3483, 3471, 3464, -1, 3482, 3389, 3388, -1, 3483, 3464, 3477, -1, 3485, 3473, 3474, -1, 3486, 3463, 3481, -1, 3486, 3468, 3463, -1, 3097, 3482, 3393, -1, 3487, 3473, 3485, -1, 3488, 3395, 3398, -1, 3488, 3398, 3400, -1, 3487, 3481, 3473, -1, 3489, 3097, 3393, -1, 3489, 3395, 3488, -1, 3489, 3393, 3395, -1, 3490, 3468, 3486, -1, 3491, 3488, 3400, -1, 3491, 3489, 3488, -1, 3490, 3472, 3468, -1, 3491, 3400, 3492, -1, 3491, 3492, 3493, -1, 3494, 3481, 3487, -1, 3494, 3486, 3481, -1, 3495, 3492, 3400, -1, 3496, 3472, 3490, -1, 3495, 3493, 3492, -1, 3496, 3477, 3472, -1, 3497, 3495, 3400, -1, 3497, 3400, 3399, -1, 3497, 3399, 3402, -1, 3498, 3486, 3494, -1, 3498, 3490, 3486, -1, 3499, 3477, 3496, -1, 3499, 3484, 3483, -1, 3499, 3483, 3477, -1, 3117, 3497, 3402, -1, 3500, 3474, 3501, -1, 3502, 3408, 3410, -1, 3502, 3405, 3408, -1, 3500, 3485, 3474, -1, 3503, 3496, 3490, -1, 3503, 3490, 3498, -1, 3504, 3402, 3405, -1, 3504, 3117, 3402, -1, 3505, 3485, 3500, -1, 3504, 3405, 3502, -1, 3506, 3410, 3507, -1, 3506, 3504, 3502, -1, 3505, 3487, 3485, -1, 3506, 3502, 3410, -1, 3508, 3499, 3496, -1, 3509, 3507, 3410, -1, 3508, 3496, 3503, -1, 3508, 3484, 3499, -1, 3509, 3510, 3507, -1, 3508, 3511, 3484, -1, 3512, 3409, 3413, -1, 3513, 3500, 3501, -1, 3512, 3410, 3409, -1, 3514, 3487, 3505, -1, 3512, 3509, 3410, -1, 3514, 3494, 3487, -1, 3515, 3505, 3500, -1, 3515, 3500, 3513, -1, 3140, 3512, 3413, -1, 3516, 3416, 3419, -1, 3516, 3414, 3416, -1, 3517, 3494, 3514, -1, 3517, 3498, 3494, -1, 3518, 3514, 3505, -1, 3519, 3414, 3516, -1, 3518, 3505, 3515, -1, 3519, 3413, 3414, -1, 3519, 3140, 3413, -1, 3520, 3498, 3517, -1, 3521, 3516, 3419, -1, 3520, 3503, 3498, -1, 3521, 3419, 2874, -1, 3521, 3519, 3516, -1, 3522, 3517, 3514, -1, 2894, 2874, 3419, -1, 3522, 3514, 3518, -1, 2894, 2875, 2874, -1, 3523, 3508, 3503, -1, 3523, 3511, 3508, -1, 2887, 3419, 3418, -1, 3523, 3503, 3520, -1, 2887, 2894, 3419, -1, 3390, 3501, 3391, -1, 2887, 3418, 2889, -1, 3390, 3513, 3501, -1, 3524, 3517, 3522, -1, 3524, 3520, 3517, -1, 3389, 3515, 3513, -1, 2902, 3425, 3525, -1, 3389, 3513, 3390, -1, 2902, 2891, 3425, -1, 3526, 3511, 3523, -1, 3526, 3523, 3520, -1, 3526, 3520, 3524, -1, 3526, 3103, 3511, -1, 3480, 3518, 3515, -1, 2910, 2903, 2902, -1, 2910, 3525, 2915, -1, 3480, 3515, 3389, -1, 2910, 2902, 3525, -1, 3527, 3431, 2890, -1, 3527, 3432, 3431, -1, 3479, 3518, 3480, -1, 3527, 2890, 2888, -1, 3479, 3522, 3518, -1, 3527, 3433, 3432, -1, 3527, 2888, 3435, -1, 3527, 3435, 3433, -1, 3528, 3435, 2888, -1, 3528, 3436, 2895, -1, 3529, 3522, 3479, -1, 3528, 2895, 3435, -1, 3529, 3524, 3522, -1, 3528, 2888, 2908, -1, 3528, 2908, 2912, -1, 3528, 2912, 3436, -1, 3101, 3524, 3529, -1, 3530, 2912, 2908, -1, 3101, 3526, 3524, -1, 3530, 2956, 2911, -1, 3101, 3103, 3526, -1, 3530, 2911, 2912, -1, 2935, 3530, 2908, -1, 2957, 2935, 2934, -1, 2957, 3530, 2935, -1, 2957, 2956, 3530, -1, 2947, 2937, 2942, -1, 2959, 2942, 2950, -1, 2959, 2946, 2947, -1, 2959, 2947, 2942, -1, 2959, 2950, 2953, -1, 2962, 3335, 3332, -1, 2962, 2964, 3335, -1, 2963, 3440, 3443, -1, 2963, 2962, 3332, -1, 2963, 3332, 3440, -1, 2965, 2963, 3443, -1, 3531, 3446, 3448, -1, 3531, 3448, 3450, -1, 2976, 3443, 3446, -1, 2976, 3446, 3531, -1, 2976, 2965, 3443, -1, 2977, 2976, 3531, -1, 2977, 3531, 3450, -1, 2977, 3450, 3532, -1, 2977, 3532, 2978, -1, 2991, 3532, 3450, -1, 2991, 2978, 3532, -1, 2988, 3449, 3454, -1, 2988, 3450, 3449, -1, 2988, 2991, 3450, -1, 2989, 2988, 3454, -1, 3533, 3455, 3458, -1, 3533, 3458, 3461, -1, 2999, 3455, 3533, -1, 2999, 3454, 3455, -1, 2999, 2989, 3454, -1, 3000, 2999, 3533, -1, 3000, 3533, 3461, -1, 3000, 3461, 3006, -1, 3018, 3006, 3461, -1, 3018, 3010, 3006, -1, 3019, 3018, 3461, -1, 3019, 3461, 3459, -1, 3019, 3459, 3462, -1, 3021, 3019, 3462, -1, 3534, 3465, 3467, -1, 3534, 3467, 3470, -1, 3535, 3423, 3536, -1, 3535, 3425, 3423, -1, 3028, 3462, 3465, -1, 3028, 3021, 3462, -1, 3028, 3465, 3534, -1, 3029, 3470, 3035, -1, 3537, 3425, 3535, -1, 3029, 3534, 3470, -1, 3029, 3028, 3534, -1, 3537, 3525, 3425, -1, 3058, 3035, 3470, -1, 3058, 3041, 3035, -1, 3538, 2915, 3525, -1, 3538, 3525, 3537, -1, 3050, 3058, 3470, -1, 3050, 3469, 3052, -1, 3050, 3470, 3469, -1, 3539, 2915, 3538, -1, 3539, 2923, 2915, -1, 3540, 2924, 2923, -1, 3540, 2923, 3539, -1, 3541, 2929, 2924, -1, 3541, 3168, 2929, -1, 3541, 2924, 3540, -1, 3541, 3542, 3168, -1, 3061, 3053, 3364, -1, 3061, 3364, 3366, -1, 3543, 3536, 3544, -1, 3543, 3535, 3536, -1, 3068, 3062, 3061, -1, 3068, 3061, 3366, -1, 3545, 3535, 3543, -1, 3068, 3366, 3074, -1, 3545, 3537, 3535, -1, 3094, 3482, 3097, -1, 3094, 3478, 3482, -1, 3094, 3479, 3478, -1, 3546, 3537, 3545, -1, 3546, 3538, 3537, -1, 3102, 3479, 3094, -1, 3102, 3529, 3479, -1, 3102, 3101, 3529, -1, 3547, 3539, 3538, -1, 3093, 3102, 3094, -1, 3547, 3538, 3546, -1, 3548, 3539, 3547, -1, 3548, 3540, 3539, -1, 3549, 3540, 3548, -1, 3549, 3541, 3540, -1, 3549, 3542, 3541, -1, 3549, 3550, 3542, -1, 3551, 3543, 3544, -1, 3551, 3544, 3552, -1, 3098, 3489, 3491, -1, 3098, 3491, 3493, -1, 3098, 3097, 3489, -1, 3553, 3545, 3543, -1, 3553, 3543, 3551, -1, 3110, 3098, 3493, -1, 3110, 3099, 3098, -1, 3110, 3493, 3554, -1, 3110, 3554, 3111, -1, 3555, 3546, 3545, -1, 3116, 3493, 3495, -1, 3116, 3495, 3497, -1, 3555, 3545, 3553, -1, 3116, 3497, 3117, -1, 3556, 3546, 3555, -1, 3556, 3547, 3546, -1, 3127, 3493, 3116, -1, 3127, 3554, 3493, -1, 3127, 3111, 3554, -1, 3557, 3548, 3547, -1, 3121, 3127, 3116, -1, 3557, 3547, 3556, -1, 3558, 3559, 3550, -1, 3558, 3549, 3548, -1, 3558, 3550, 3549, -1, 3558, 3548, 3557, -1, 3560, 3551, 3552, -1, 3118, 3117, 3504, -1, 3560, 3552, 3561, -1, 3118, 3504, 3506, -1, 3562, 3553, 3551, -1, 3562, 3551, 3560, -1, 3563, 3553, 3562, -1, 3564, 3118, 3506, -1, 3563, 3555, 3553, -1, 3564, 3122, 3118, -1, 3564, 3506, 3507, -1, 3565, 3555, 3563, -1, 3566, 3507, 3510, -1, 3565, 3556, 3555, -1, 3566, 3510, 3567, -1, 3566, 3564, 3507, -1, 3428, 3557, 3556, -1, 3428, 3556, 3565, -1, 3135, 3567, 3131, -1, 3135, 3122, 3564, -1, 3135, 3124, 3122, -1, 3135, 3566, 3567, -1, 3427, 3558, 3557, -1, 3135, 3564, 3566, -1, 3427, 3557, 3428, -1, 3427, 3430, 3559, -1, 3427, 3559, 3558, -1, 3139, 3510, 3509, -1, 3139, 3509, 3512, -1, 2870, 3561, 3568, -1, 3139, 3512, 3140, -1, 2870, 3560, 3561, -1, 3148, 3567, 3510, -1, 3148, 3131, 3567, -1, 2872, 3560, 2870, -1, 2872, 3562, 3560, -1, 3148, 3510, 3139, -1, 2877, 3563, 3562, -1, 2877, 3562, 2872, -1, 3141, 3148, 3139, -1, 3142, 3140, 3519, -1, 3142, 3519, 3521, -1, 2890, 3563, 2877, -1, 2890, 3565, 3563, -1, 3431, 3428, 3565, -1, 3431, 3565, 2890, -1, 2880, 3142, 3521, -1, 2880, 3521, 2874, -1, 3432, 2897, 3430, -1, 2871, 3568, 2899, -1, 2871, 2870, 3568, -1, 2879, 3142, 2880, -1, 2879, 2883, 3142, -1, 3569, 3570, 3571, -1, 3569, 3571, 3572, -1, 3573, 3574, 3575, -1, 3573, 3576, 3577, -1, 3573, 3578, 3574, -1, 3573, 3575, 3576, -1, 3579, 3572, 3580, -1, 3581, 3577, 3570, -1, 3581, 3570, 3569, -1, 3582, 3569, 3572, -1, 3582, 3572, 3579, -1, 3583, 3573, 3577, -1, 3583, 3577, 3581, -1, 3583, 3578, 3573, -1, 3584, 3580, 3585, -1, 3584, 3579, 3580, -1, 3586, 3581, 3569, -1, 3586, 3569, 3582, -1, 3587, 3582, 3579, -1, 3587, 3579, 3584, -1, 3588, 3583, 3581, -1, 3588, 3578, 3583, -1, 3588, 3581, 3586, -1, 3588, 3589, 3578, -1, 3590, 3584, 3585, -1, 3591, 3586, 3582, -1, 3591, 3582, 3587, -1, 3592, 3587, 3584, -1, 3592, 3584, 3590, -1, 3593, 3588, 3586, -1, 3593, 3589, 3588, -1, 3593, 3586, 3591, -1, 3594, 3585, 3595, -1, 3594, 3590, 3585, -1, 3596, 3587, 3592, -1, 3596, 3591, 3587, -1, 3597, 3592, 3590, -1, 3597, 3590, 3594, -1, 3598, 3599, 3589, -1, 3598, 3589, 3593, -1, 3598, 3593, 3591, -1, 3598, 3591, 3596, -1, 3600, 3594, 3595, -1, 3601, 3596, 3592, -1, 3601, 3592, 3597, -1, 3602, 3597, 3594, -1, 3602, 3594, 3600, -1, 3603, 3599, 3598, -1, 3603, 3596, 3601, -1, 3603, 3598, 3596, -1, 3604, 3595, 3605, -1, 3604, 3600, 3595, -1, 3606, 3601, 3597, -1, 3606, 3597, 3602, -1, 3607, 3602, 3600, -1, 3607, 3600, 3604, -1, 3608, 3601, 3606, -1, 3608, 3599, 3603, -1, 3608, 3609, 3599, -1, 3608, 3603, 3601, -1, 3610, 3604, 3605, -1, 3611, 3606, 3602, -1, 3611, 3602, 3607, -1, 3612, 3607, 3604, -1, 3612, 3604, 3610, -1, 3613, 3606, 3611, -1, 3613, 3609, 3608, -1, 3613, 3608, 3606, -1, 3614, 3605, 3615, -1, 3614, 3610, 3605, -1, 3616, 3611, 3607, -1, 3616, 3607, 3612, -1, 3617, 3612, 3610, -1, 3617, 3610, 3614, -1, 3618, 3613, 3611, -1, 3618, 3609, 3613, -1, 3618, 3611, 3616, -1, 3618, 3619, 3609, -1, 3620, 3614, 3615, -1, 3621, 3612, 3617, -1, 3621, 3616, 3612, -1, 3622, 3617, 3614, -1, 3622, 3614, 3620, -1, 3623, 3616, 3621, -1, 3623, 3618, 3616, -1, 3623, 3619, 3618, -1, 3624, 3615, 3625, -1, 3624, 3620, 3615, -1, 3626, 3621, 3617, -1, 3626, 3617, 3622, -1, 3627, 3622, 3620, -1, 3627, 3620, 3624, -1, 3628, 3623, 3621, -1, 3628, 3621, 3626, -1, 3628, 3619, 3623, -1, 3628, 3629, 3619, -1, 3630, 3624, 3625, -1, 3631, 3626, 3622, -1, 3631, 3622, 3627, -1, 3632, 3627, 3624, -1, 3632, 3624, 3630, -1, 3633, 3628, 3626, -1, 3633, 3626, 3631, -1, 3633, 3629, 3628, -1, 3634, 3625, 3635, -1, 3634, 3630, 3625, -1, 3636, 3631, 3627, -1, 3636, 3627, 3632, -1, 3637, 3632, 3630, -1, 3637, 3630, 3634, -1, 3638, 3639, 3629, -1, 3638, 3631, 3636, -1, 3638, 3629, 3633, -1, 3638, 3633, 3631, -1, 3640, 3634, 3635, -1, 3641, 3636, 3632, -1, 3641, 3632, 3637, -1, 3642, 3637, 3634, -1, 3642, 3634, 3640, -1, 3643, 3639, 3638, -1, 3643, 3636, 3641, -1, 3643, 3638, 3636, -1, 3644, 3635, 3645, -1, 3644, 3640, 3635, -1, 3646, 3637, 3642, -1, 3646, 3641, 3637, -1, 3647, 3640, 3644, -1, 3647, 3642, 3640, -1, 3648, 3643, 3641, -1, 3648, 3641, 3646, -1, 3648, 3649, 3639, -1, 3648, 3639, 3643, -1, 3650, 3644, 3645, -1, 3651, 3646, 3642, -1, 3651, 3642, 3647, -1, 3652, 3647, 3644, -1, 3652, 3644, 3650, -1, 3653, 3646, 3651, -1, 3653, 3649, 3648, -1, 3653, 3648, 3646, -1, 3654, 3645, 3655, -1, 3654, 3650, 3645, -1, 3656, 3647, 3652, -1, 3656, 3651, 3647, -1, 3657, 3658, 3659, -1, 3660, 3652, 3650, -1, 3660, 3650, 3654, -1, 3661, 3662, 3663, -1, 3664, 3651, 3656, -1, 3661, 3665, 3662, -1, 3664, 3653, 3651, -1, 3664, 3649, 3653, -1, 3664, 3666, 3649, -1, 3667, 3665, 3661, -1, 3668, 3656, 3652, -1, 3668, 3652, 3660, -1, 3667, 3669, 3665, -1, 3670, 3654, 3655, -1, 3671, 3672, 3669, -1, 3671, 3669, 3667, -1, 3673, 3674, 3675, -1, 3676, 3664, 3656, -1, 3676, 3656, 3668, -1, 3673, 3672, 3671, -1, 3676, 3666, 3664, -1, 3673, 3677, 3672, -1, 3673, 3675, 3677, -1, 3678, 3660, 3654, -1, 3679, 3663, 3680, -1, 3679, 3661, 3663, -1, 3678, 3654, 3670, -1, 3681, 3661, 3679, -1, 3682, 3670, 3655, -1, 3682, 3655, 3683, -1, 3684, 3668, 3660, -1, 3681, 3667, 3661, -1, 3684, 3660, 3678, -1, 3685, 3667, 3681, -1, 3686, 3678, 3670, -1, 3685, 3671, 3667, -1, 3687, 3671, 3685, -1, 3686, 3670, 3682, -1, 3687, 3673, 3671, -1, 3687, 3688, 3674, -1, 3687, 3689, 3688, -1, 3687, 3674, 3673, -1, 3690, 3676, 3668, -1, 3690, 3666, 3676, -1, 3690, 3668, 3684, -1, 3691, 3679, 3680, -1, 3691, 3680, 3692, -1, 3690, 3693, 3666, -1, 3694, 3678, 3686, -1, 3694, 3684, 3678, -1, 3695, 3681, 3679, -1, 3695, 3679, 3691, -1, 3696, 3682, 3683, -1, 3697, 3681, 3695, -1, 3697, 3685, 3681, -1, 3698, 3690, 3684, -1, 3698, 3693, 3690, -1, 3698, 3684, 3694, -1, 3699, 3685, 3697, -1, 3700, 3696, 3683, -1, 3699, 3687, 3685, -1, 3700, 3683, 3701, -1, 3699, 3689, 3687, -1, 3702, 3686, 3682, -1, 3703, 3692, 3704, -1, 3702, 3682, 3696, -1, 3703, 3691, 3692, -1, 3705, 3696, 3700, -1, 3706, 3695, 3691, -1, 3705, 3702, 3696, -1, 3706, 3691, 3703, -1, 3707, 3694, 3686, -1, 3707, 3686, 3702, -1, 3708, 3697, 3695, -1, 3708, 3695, 3706, -1, 3709, 3707, 3702, -1, 3710, 3697, 3708, -1, 3710, 3711, 3689, -1, 3709, 3702, 3705, -1, 3710, 3699, 3697, -1, 3710, 3689, 3699, -1, 3712, 3698, 3694, -1, 3712, 3713, 3693, -1, 3712, 3693, 3698, -1, 3712, 3694, 3707, -1, 3714, 3704, 3715, -1, 3714, 3703, 3704, -1, 3716, 3700, 3701, -1, 3717, 3713, 3712, -1, 3718, 3703, 3714, -1, 3717, 3707, 3709, -1, 3718, 3706, 3703, -1, 3717, 3712, 3707, -1, 3719, 3708, 3706, -1, 3720, 3701, 3721, -1, 3719, 3706, 3718, -1, 3720, 3716, 3701, -1, 3722, 3711, 3710, -1, 3722, 3708, 3719, -1, 3723, 3705, 3700, -1, 3722, 3724, 3711, -1, 3723, 3700, 3716, -1, 3722, 3710, 3708, -1, 3725, 3723, 3716, -1, 3726, 3714, 3715, -1, 3725, 3716, 3720, -1, 3726, 3715, 3727, -1, 3728, 3714, 3726, -1, 3729, 3709, 3705, -1, 3728, 3718, 3714, -1, 3729, 3705, 3723, -1, 3730, 3729, 3723, -1, 3730, 3723, 3725, -1, 3731, 3719, 3718, -1, 3731, 3718, 3728, -1, 3732, 3709, 3729, -1, 3732, 3733, 3713, -1, 3732, 3713, 3717, -1, 3734, 3719, 3731, -1, 3732, 3717, 3709, -1, 3734, 3722, 3719, -1, 3734, 3735, 3724, -1, 3734, 3724, 3722, -1, 3736, 3720, 3721, -1, 3737, 3733, 3732, -1, 3738, 3727, 3739, -1, 3737, 3732, 3729, -1, 3738, 3726, 3727, -1, 3737, 3729, 3730, -1, 3740, 3721, 3741, -1, 3742, 3728, 3726, -1, 3740, 3736, 3721, -1, 3743, 3720, 3736, -1, 3742, 3726, 3738, -1, 3744, 3728, 3742, -1, 3743, 3725, 3720, -1, 3745, 3743, 3736, -1, 3744, 3731, 3728, -1, 3745, 3736, 3740, -1, 3746, 3734, 3731, -1, 3746, 3731, 3744, -1, 3746, 3735, 3734, -1, 3747, 3730, 3725, -1, 3746, 3748, 3735, -1, 3747, 3725, 3743, -1, 3749, 3739, 3750, -1, 3751, 3747, 3743, -1, 3751, 3743, 3745, -1, 3749, 3738, 3739, -1, 3752, 3733, 3737, -1, 3753, 3742, 3738, -1, 3752, 3737, 3730, -1, 3752, 3730, 3747, -1, 3752, 3754, 3733, -1, 3755, 3740, 3741, -1, 3753, 3738, 3749, -1, 3756, 3742, 3753, -1, 3757, 3747, 3751, -1, 3756, 3744, 3742, -1, 3757, 3752, 3747, -1, 3758, 3744, 3756, -1, 3757, 3754, 3752, -1, 3758, 3748, 3746, -1, 3759, 3740, 3755, -1, 3758, 3746, 3744, -1, 3759, 3745, 3740, -1, 3758, 3760, 3748, -1, 3761, 3749, 3750, -1, 3761, 3750, 3762, -1, 3763, 3751, 3745, -1, 3763, 3745, 3759, -1, 3764, 3749, 3761, -1, 3765, 3757, 3751, -1, 3765, 3754, 3757, -1, 3764, 3753, 3749, -1, 3765, 3751, 3763, -1, 3765, 3766, 3754, -1, 3767, 3741, 3768, -1, 3767, 3755, 3741, -1, 3769, 3753, 3764, -1, 3769, 3756, 3753, -1, 3770, 3758, 3756, -1, 3770, 3771, 3760, -1, 3772, 3755, 3767, -1, 3770, 3760, 3758, -1, 3770, 3756, 3769, -1, 3772, 3759, 3755, -1, 3773, 3762, 3774, -1, 3773, 3761, 3762, -1, 3775, 3759, 3772, -1, 3775, 3763, 3759, -1, 3776, 3763, 3775, -1, 3777, 3773, 3774, -1, 3776, 3765, 3763, -1, 3778, 3764, 3761, -1, 3776, 3766, 3765, -1, 3778, 3761, 3773, -1, 3776, 3779, 3766, -1, 3780, 3768, 3781, -1, 3780, 3767, 3768, -1, 3782, 3778, 3773, -1, 3782, 3773, 3777, -1, 3783, 3772, 3767, -1, 3784, 3769, 3764, -1, 3783, 3767, 3780, -1, 3784, 3764, 3778, -1, 3785, 3775, 3772, -1, 3786, 3778, 3782, -1, 3785, 3772, 3783, -1, 3786, 3784, 3778, -1, 3787, 3771, 3770, -1, 3787, 3788, 3771, -1, 3789, 3776, 3775, -1, 3789, 3779, 3776, -1, 3787, 3770, 3769, -1, 3789, 3775, 3785, -1, 3787, 3769, 3784, -1, 3789, 3790, 3779, -1, 3791, 3774, 3792, -1, 3793, 3781, 3794, -1, 3791, 3777, 3774, -1, 3793, 3780, 3781, -1, 3795, 3796, 3788, -1, 3795, 3788, 3787, -1, 3795, 3784, 3786, -1, 3797, 3783, 3780, -1, 3795, 3787, 3784, -1, 3797, 3780, 3793, -1, 3798, 3791, 3792, -1, 3799, 3785, 3783, -1, 3799, 3783, 3797, -1, 3800, 3782, 3777, -1, 3800, 3777, 3791, -1, 3801, 3791, 3798, -1, 3802, 3789, 3785, -1, 3802, 3790, 3789, -1, 3802, 3803, 3790, -1, 3802, 3785, 3799, -1, 3801, 3800, 3791, -1, 3804, 3794, 3805, -1, 3806, 3782, 3800, -1, 3804, 3793, 3794, -1, 3806, 3786, 3782, -1, 3807, 3800, 3801, -1, 3807, 3806, 3800, -1, 3808, 3797, 3793, -1, 3809, 3795, 3786, -1, 3809, 3786, 3806, -1, 3808, 3793, 3804, -1, 3809, 3796, 3795, -1, 3810, 3792, 3811, -1, 3812, 3799, 3797, -1, 3812, 3797, 3808, -1, 3810, 3798, 3792, -1, 3813, 3814, 3803, -1, 3815, 3809, 3806, -1, 3813, 3802, 3799, -1, 3815, 3806, 3807, -1, 3813, 3803, 3802, -1, 3815, 3796, 3809, -1, 3815, 3816, 3796, -1, 3813, 3799, 3812, -1, 3817, 3810, 3811, -1, 3818, 3805, 3819, -1, 3818, 3804, 3805, -1, 3820, 3798, 3810, -1, 3821, 3808, 3804, -1, 3821, 3804, 3818, -1, 3820, 3801, 3798, -1, 3822, 3820, 3810, -1, 3822, 3810, 3817, -1, 3823, 3808, 3821, -1, 3824, 3807, 3801, -1, 3823, 3812, 3808, -1, 3824, 3801, 3820, -1, 3825, 3812, 3823, -1, 3825, 3826, 3814, -1, 3827, 3820, 3822, -1, 3825, 3814, 3813, -1, 3827, 3824, 3820, -1, 3825, 3813, 3812, -1, 3828, 3815, 3807, -1, 3829, 3819, 3830, -1, 3828, 3816, 3815, -1, 3828, 3807, 3824, -1, 3831, 3811, 3832, -1, 3829, 3818, 3819, -1, 3831, 3817, 3811, -1, 3833, 3818, 3829, -1, 3834, 3824, 3827, -1, 3834, 3816, 3828, -1, 3833, 3821, 3818, -1, 3834, 3828, 3824, -1, 3835, 3823, 3821, -1, 3834, 3836, 3816, -1, 3837, 3822, 3817, -1, 3835, 3821, 3833, -1, 3837, 3817, 3831, -1, 3838, 3825, 3823, -1, 3838, 3826, 3825, -1, 3838, 3823, 3835, -1, 3838, 3839, 3826, -1, 3840, 3831, 3832, -1, 3841, 3829, 3830, -1, 3842, 3827, 3822, -1, 3841, 3830, 3843, -1, 3842, 3822, 3837, -1, 3844, 3837, 3831, -1, 3845, 3829, 3841, -1, 3845, 3833, 3829, -1, 3844, 3831, 3840, -1, 3846, 3834, 3827, -1, 3846, 3836, 3834, -1, 3847, 3835, 3833, -1, 3846, 3827, 3842, -1, 3847, 3833, 3845, -1, 3848, 3842, 3837, -1, 3848, 3837, 3844, -1, 3849, 3838, 3835, -1, 3849, 3839, 3838, -1, 3849, 3835, 3847, -1, 3850, 3832, 3851, -1, 3850, 3840, 3832, -1, 3849, 3852, 3839, -1, 3853, 3854, 3855, -1, 3853, 3843, 3854, -1, 3853, 3841, 3843, -1, 3856, 3857, 3836, -1, 3856, 3836, 3846, -1, 3853, 3855, 3858, -1, 3856, 3846, 3842, -1, 3856, 3842, 3848, -1, 3859, 3840, 3850, -1, 3859, 3844, 3840, -1, 3860, 3845, 3841, -1, 3860, 3853, 3858, -1, 3860, 3858, 3861, -1, 3860, 3841, 3853, -1, 3862, 3847, 3845, -1, 3863, 3850, 3851, -1, 3862, 3845, 3860, -1, 3864, 3844, 3859, -1, 3862, 3860, 3861, -1, 3862, 3861, 3865, -1, 3864, 3848, 3844, -1, 3866, 3849, 3847, -1, 3866, 3852, 3849, -1, 3866, 3865, 3659, -1, 3866, 3862, 3865, -1, 3867, 3859, 3850, -1, 3866, 3847, 3862, -1, 3866, 3659, 3658, -1, 3866, 3658, 3852, -1, 3867, 3850, 3863, -1, 3868, 3857, 3856, -1, 3868, 3856, 3848, -1, 3868, 3848, 3864, -1, 3869, 3851, 3870, -1, 3869, 3863, 3851, -1, 3871, 3864, 3859, -1, 3871, 3859, 3867, -1, 3872, 3867, 3863, -1, 3872, 3863, 3869, -1, 3873, 3874, 3857, -1, 3873, 3857, 3868, -1, 3873, 3864, 3871, -1, 3873, 3868, 3864, -1, 3875, 3869, 3870, -1, 3876, 3871, 3867, -1, 3876, 3867, 3872, -1, 3877, 3869, 3875, -1, 3877, 3872, 3869, -1, 3878, 3873, 3871, -1, 3878, 3874, 3873, -1, 3878, 3871, 3876, -1, 3879, 3870, 3880, -1, 3879, 3875, 3870, -1, 3881, 3872, 3877, -1, 3881, 3876, 3872, -1, 3882, 3877, 3875, -1, 3882, 3875, 3879, -1, 3883, 3878, 3876, -1, 3883, 3874, 3878, -1, 3883, 3876, 3881, -1, 3883, 3574, 3874, -1, 3571, 3879, 3880, -1, 3576, 3877, 3882, -1, 3576, 3881, 3877, -1, 3570, 3882, 3879, -1, 3570, 3879, 3571, -1, 3575, 3881, 3576, -1, 3575, 3574, 3883, -1, 3575, 3883, 3881, -1, 3572, 3880, 3580, -1, 3572, 3571, 3880, -1, 3577, 3576, 3882, -1, 3577, 3882, 3570, -1, 3884, 3885, 3886, -1, 3887, 3885, 3884, -1, 3888, 3889, 3890, -1, 3891, 3892, 3893, -1, 3893, 3892, 3894, -1, 3895, 3896, 3897, -1, 3898, 3896, 3895, -1, 3899, 3900, 3887, -1, 3894, 3901, 3902, -1, 3903, 3900, 3904, -1, 3904, 3900, 3899, -1, 3887, 3900, 3885, -1, 3905, 3906, 3907, -1, 3907, 3906, 3888, -1, 3886, 3908, 3898, -1, 3909, 3906, 3905, -1, 3898, 3908, 3896, -1, 3888, 3906, 3889, -1, 3885, 3910, 3886, -1, 3891, 3911, 3892, -1, 3889, 3911, 3891, -1, 3892, 3912, 3894, -1, 3886, 3910, 3908, -1, 3894, 3912, 3901, -1, 3896, 3913, 3897, -1, 3901, 3914, 3902, -1, 3915, 3913, 3916, -1, 3902, 3914, 3917, -1, 3897, 3913, 3915, -1, 3918, 3919, 3903, -1, 3909, 3920, 3906, -1, 3903, 3919, 3900, -1, 3906, 3920, 3889, -1, 3900, 3919, 3885, -1, 3889, 3920, 3911, -1, 3885, 3919, 3910, -1, 3916, 3921, 3922, -1, 3911, 3923, 3892, -1, 3892, 3923, 3912, -1, 3908, 3921, 3896, -1, 3913, 3921, 3916, -1, 3896, 3921, 3913, -1, 3901, 3924, 3914, -1, 3922, 3925, 3926, -1, 3912, 3924, 3901, -1, 3908, 3925, 3921, -1, 3910, 3925, 3908, -1, 3921, 3925, 3922, -1, 3914, 3927, 3917, -1, 3926, 3928, 3929, -1, 3930, 3928, 3918, -1, 3925, 3928, 3926, -1, 3931, 3932, 3909, -1, 3918, 3928, 3919, -1, 3909, 3932, 3920, -1, 3919, 3928, 3910, -1, 3911, 3932, 3923, -1, 3910, 3928, 3925, -1, 3929, 3928, 3930, -1, 3920, 3932, 3911, -1, 3923, 3933, 3912, -1, 3912, 3933, 3924, -1, 3924, 3934, 3914, -1, 3914, 3934, 3927, -1, 3927, 3935, 3917, -1, 3917, 3935, 3936, -1, 3923, 3937, 3933, -1, 3932, 3937, 3923, -1, 3931, 3937, 3932, -1, 3933, 3938, 3924, -1, 3924, 3938, 3934, -1, 3934, 3939, 3927, -1, 3927, 3939, 3935, -1, 3935, 3940, 3936, -1, 3941, 3942, 3931, -1, 3931, 3942, 3937, -1, 3937, 3942, 3933, -1, 3933, 3942, 3938, -1, 3934, 3943, 3939, -1, 3938, 3943, 3934, -1, 3939, 3944, 3935, -1, 3935, 3944, 3940, -1, 3936, 3945, 3946, -1, 3940, 3945, 3936, -1, 3941, 3947, 3942, -1, 3942, 3947, 3938, -1, 3938, 3947, 3943, -1, 3943, 3948, 3939, -1, 3939, 3948, 3944, -1, 3944, 3949, 3940, -1, 3940, 3949, 3945, -1, 3945, 3950, 3946, -1, 3947, 3951, 3943, -1, 3952, 3951, 3941, -1, 3941, 3951, 3947, -1, 3943, 3951, 3948, -1, 3944, 3953, 3949, -1, 3948, 3953, 3944, -1, 3949, 3954, 3945, -1, 3945, 3954, 3950, -1, 3950, 3955, 3946, -1, 3946, 3955, 3956, -1, 3948, 3957, 3953, -1, 3951, 3957, 3948, -1, 3952, 3957, 3951, -1, 3953, 3958, 3949, -1, 3949, 3958, 3954, -1, 3954, 3959, 3950, -1, 3950, 3959, 3955, -1, 3955, 3960, 3956, -1, 3957, 3961, 3953, -1, 3952, 3961, 3957, -1, 3953, 3961, 3958, -1, 3962, 3961, 3952, -1, 3958, 3963, 3954, -1, 3954, 3963, 3959, -1, 3959, 3964, 3955, -1, 3955, 3964, 3960, -1, 3960, 3965, 3956, -1, 3956, 3965, 3966, -1, 3958, 3967, 3963, -1, 3961, 3967, 3958, -1, 3962, 3967, 3961, -1, 3959, 3968, 3964, -1, 3963, 3968, 3959, -1, 3964, 3969, 3960, -1, 3960, 3969, 3965, -1, 3965, 3970, 3966, -1, 3971, 3972, 3962, -1, 3962, 3972, 3967, -1, 3967, 3972, 3963, -1, 3963, 3972, 3968, -1, 3968, 3973, 3964, -1, 3964, 3973, 3969, -1, 3969, 3974, 3965, -1, 3965, 3974, 3970, -1, 3970, 3975, 3966, -1, 3966, 3975, 3976, -1, 3968, 3977, 3973, -1, 3971, 3977, 3972, -1, 3972, 3977, 3968, -1, 3973, 3978, 3969, -1, 3969, 3978, 3974, -1, 3974, 3979, 3970, -1, 3970, 3979, 3975, -1, 3975, 3980, 3976, -1, 3981, 3982, 3971, -1, 3977, 3982, 3973, -1, 3971, 3982, 3977, -1, 3973, 3982, 3978, -1, 3978, 3983, 3974, -1, 3974, 3983, 3979, -1, 3979, 3984, 3975, -1, 3975, 3984, 3980, -1, 3976, 3985, 3986, -1, 3980, 3985, 3976, -1, 3981, 3987, 3982, -1, 3982, 3987, 3978, -1, 3978, 3987, 3983, -1, 3983, 3988, 3979, -1, 3979, 3988, 3984, -1, 3984, 3989, 3980, -1, 3980, 3989, 3985, -1, 3985, 3990, 3986, -1, 3981, 3991, 3987, -1, 3992, 3991, 3981, -1, 3983, 3991, 3988, -1, 3987, 3991, 3983, -1, 3988, 3993, 3984, -1, 3984, 3993, 3989, -1, 3989, 3994, 3985, -1, 3985, 3994, 3990, -1, 3990, 3995, 3986, -1, 3986, 3995, 3996, -1, 3988, 3997, 3993, -1, 3992, 3997, 3991, -1, 3991, 3997, 3988, -1, 3989, 3998, 3994, -1, 3993, 3998, 3989, -1, 3994, 3999, 3990, -1, 3990, 3999, 3995, -1, 3995, 4000, 3996, -1, 3997, 4001, 3993, -1, 3992, 4001, 3997, -1, 3993, 4001, 3998, -1, 4002, 4001, 3992, -1, 3998, 4003, 3994, -1, 3994, 4003, 3999, -1, 3999, 4004, 3995, -1, 3915, 3916, 4005, -1, 3995, 4004, 4000, -1, 4000, 4006, 3996, -1, 3996, 4006, 4007, -1, 3998, 4008, 4003, -1, 4001, 4008, 3998, -1, 4002, 4008, 4001, -1, 4003, 4009, 3999, -1, 3999, 4009, 4004, -1, 3930, 4010, 3929, -1, 4004, 4011, 4000, -1, 4012, 4013, 4014, -1, 4000, 4011, 4006, -1, 4014, 4013, 4015, -1, 4006, 4016, 4007, -1, 4017, 4018, 4012, -1, 4019, 4020, 4002, -1, 4008, 4020, 4003, -1, 4012, 4018, 4013, -1, 4003, 4020, 4009, -1, 4002, 4020, 4008, -1, 4017, 4021, 4018, -1, 4009, 4022, 4004, -1, 4023, 4021, 4017, -1, 4004, 4022, 4011, -1, 4011, 4024, 4006, -1, 4015, 4025, 4026, -1, 4006, 4024, 4016, -1, 4013, 4025, 4015, -1, 4023, 4027, 4021, -1, 4028, 4027, 4029, -1, 4016, 4030, 4007, -1, 4031, 4027, 4023, -1, 4007, 4030, 4032, -1, 4029, 4027, 4031, -1, 4019, 4033, 4020, -1, 4018, 4034, 4013, -1, 4020, 4033, 4009, -1, 4009, 4033, 4022, -1, 4013, 4034, 4025, -1, 4022, 4035, 4011, -1, 4011, 4035, 4024, -1, 4021, 4036, 4018, -1, 4018, 4036, 4034, -1, 4024, 4037, 4016, -1, 4016, 4037, 4030, -1, 4026, 4038, 4039, -1, 4030, 4040, 4032, -1, 4025, 4038, 4026, -1, 4021, 4041, 4036, -1, 4019, 4042, 4033, -1, 4043, 4041, 4028, -1, 4044, 4042, 4019, -1, 4028, 4041, 4027, -1, 4033, 4042, 4022, -1, 4027, 4041, 4021, -1, 4022, 4042, 4035, -1, 4034, 4045, 4025, -1, 4025, 4045, 4038, -1, 4024, 4046, 4037, -1, 4035, 4046, 4024, -1, 4037, 4047, 4030, -1, 4034, 4048, 4045, -1, 4030, 4047, 4040, -1, 4036, 4048, 4034, -1, 4040, 4049, 4032, -1, 4032, 4049, 4050, -1, 4038, 4051, 4039, -1, 4039, 4051, 4052, -1, 4044, 4053, 4042, -1, 4042, 4053, 4035, -1, 4036, 4054, 4048, -1, 4035, 4053, 4046, -1, 4055, 4054, 4043, -1, 4041, 4054, 4036, -1, 4043, 4054, 4041, -1, 4046, 4056, 4037, -1, 4037, 4056, 4047, -1, 4038, 4057, 4051, -1, 4045, 4057, 4038, -1, 4047, 4058, 4040, -1, 4040, 4058, 4049, -1, 4048, 4059, 4045, -1, 4049, 4060, 4050, -1, 4045, 4059, 4057, -1, 4053, 4061, 4046, -1, 4062, 4061, 4044, -1, 4052, 4063, 4064, -1, 4044, 4061, 4053, -1, 4046, 4061, 4056, -1, 4051, 4063, 4052, -1, 4048, 4065, 4059, -1, 4055, 4065, 4054, -1, 4066, 4065, 4055, -1, 4056, 4067, 4047, -1, 4054, 4065, 4048, -1, 4047, 4067, 4058, -1, 4049, 4068, 4060, -1, 4051, 4069, 4063, -1, 4058, 4068, 4049, -1, 4060, 4070, 4050, -1, 4057, 4069, 4051, -1, 4050, 4070, 4071, -1, 4057, 4072, 4069, -1, 4061, 4073, 4056, -1, 4059, 4072, 4057, -1, 4063, 4074, 4064, -1, 4056, 4073, 4067, -1, 4062, 4073, 4061, -1, 4067, 4075, 4058, -1, 4064, 4074, 4076, -1, 4058, 4075, 4068, -1, 4066, 4077, 4065, -1, 4065, 4077, 4059, -1, 4070, 4078, 4071, -1, 4079, 4077, 4066, -1, 4059, 4077, 4072, -1, 4068, 4080, 4060, -1, 4063, 4081, 4074, -1, 4060, 4080, 4070, -1, 4069, 4081, 4063, -1, 4062, 4082, 4073, -1, 4072, 4083, 4069, -1, 4073, 4082, 4067, -1, 4069, 4083, 4081, -1, 4084, 4082, 4062, -1, 4067, 4082, 4075, -1, 4070, 4085, 4078, -1, 4080, 4085, 4070, -1, 4076, 4086, 4087, -1, 4075, 4088, 4068, -1, 4068, 4088, 4080, -1, 4074, 4086, 4076, -1, 4072, 4089, 4083, -1, 4077, 4089, 4072, -1, 4079, 4089, 4077, -1, 4078, 4090, 4071, -1, 4091, 4089, 4079, -1, 4081, 4092, 4074, -1, 4071, 4090, 4093, -1, 4074, 4092, 4086, -1, 4080, 4094, 4085, -1, 4088, 4094, 4080, -1, 4081, 4095, 4092, -1, 4084, 4096, 4082, -1, 4075, 4096, 4088, -1, 4082, 4096, 4075, -1, 4083, 4095, 4081, -1, 4086, 4097, 4087, -1, 4090, 4098, 4093, -1, 4087, 4097, 4099, -1, 4085, 4100, 4078, -1, 4078, 4100, 4090, -1, 4091, 4101, 4089, -1, 4083, 4101, 4095, -1, 4102, 4101, 4091, -1, 4103, 4104, 4084, -1, 4084, 4104, 4096, -1, 4089, 4101, 4083, -1, 4088, 4104, 4094, -1, 4096, 4104, 4088, -1, 4092, 4105, 4086, -1, 4090, 4106, 4098, -1, 4086, 4105, 4097, -1, 4095, 4107, 4092, -1, 4100, 4106, 4090, -1, 4092, 4107, 4105, -1, 4085, 4108, 4100, -1, 4094, 4108, 4085, -1, 4097, 4109, 4099, -1, 4100, 4110, 4106, -1, 4099, 4109, 4111, -1, 4108, 4110, 4100, -1, 4098, 4112, 4093, -1, 4101, 4113, 4095, -1, 4114, 4113, 4102, -1, 4095, 4113, 4107, -1, 4093, 4112, 4115, -1, 4102, 4113, 4101, -1, 4097, 4116, 4109, -1, 4103, 4117, 4104, -1, 4104, 4117, 4094, -1, 4094, 4117, 4108, -1, 4105, 4116, 4097, -1, 4112, 4118, 4115, -1, 4105, 4119, 4116, -1, 4120, 4121, 4103, -1, 4103, 4121, 4117, -1, 4107, 4119, 4105, -1, 4108, 4121, 4110, -1, 4117, 4121, 4108, -1, 4098, 4122, 4112, -1, 4106, 4122, 4098, -1, 4111, 4123, 4124, -1, 4109, 4123, 4111, -1, 4125, 4126, 4114, -1, 4122, 4127, 4112, -1, 4114, 4126, 4113, -1, 4107, 4126, 4119, -1, 4112, 4127, 4118, -1, 4113, 4126, 4107, -1, 4110, 4128, 4106, -1, 4116, 4129, 4109, -1, 4109, 4129, 4123, -1, 4106, 4128, 4122, -1, 4116, 4130, 4129, -1, 4122, 4131, 4127, -1, 4128, 4131, 4122, -1, 4119, 4130, 4116, -1, 4118, 4132, 4115, -1, 4115, 4132, 4133, -1, 4124, 4134, 4135, -1, 4123, 4134, 4124, -1, 4120, 4136, 4121, -1, 4121, 4136, 4110, -1, 4110, 4136, 4128, -1, 4137, 4138, 4125, -1, 4126, 4138, 4119, -1, 4125, 4138, 4126, -1, 4119, 4138, 4130, -1, 4134, 4139, 4135, -1, 4132, 4140, 4133, -1, 4141, 4142, 4120, -1, 4120, 4142, 4136, -1, 4135, 4139, 4143, -1, 4128, 4142, 4131, -1, 4123, 4144, 4134, -1, 4136, 4142, 4128, -1, 4118, 4145, 4132, -1, 4127, 4145, 4118, -1, 4129, 4144, 4123, -1, 4144, 4146, 4134, -1, 4145, 4147, 4132, -1, 4134, 4146, 4139, -1, 4132, 4147, 4140, -1, 4129, 4148, 4144, -1, 4131, 4149, 4127, -1, 4130, 4148, 4129, -1, 4127, 4149, 4145, -1, 4145, 4150, 4147, -1, 4148, 4151, 4144, -1, 4149, 4150, 4145, -1, 4144, 4151, 4146, -1, 4139, 4152, 4143, -1, 4133, 4153, 4154, -1, 4137, 4155, 4138, -1, 4140, 4153, 4133, -1, 4138, 4155, 4130, -1, 4131, 4156, 4149, -1, 4157, 4155, 4137, -1, 4130, 4155, 4148, -1, 4141, 4156, 4142, -1, 4142, 4156, 4131, -1, 4152, 4158, 4143, -1, 4149, 4159, 4150, -1, 4141, 4159, 4156, -1, 4143, 4158, 4160, -1, 4161, 4159, 4141, -1, 4148, 4162, 4151, -1, 4156, 4159, 4149, -1, 4147, 4163, 4140, -1, 4155, 4162, 4148, -1, 4157, 4162, 4155, -1, 4146, 4164, 4139, -1, 4139, 4164, 4152, -1, 4140, 4163, 4153, -1, 4164, 4165, 4152, -1, 4147, 4166, 4163, -1, 4150, 4166, 4147, -1, 4153, 4167, 4154, -1, 4152, 4165, 4158, -1, 4151, 4168, 4146, -1, 4154, 4167, 4169, -1, 4146, 4168, 4164, -1, 4161, 4170, 4159, -1, 4150, 4170, 4166, -1, 4159, 4170, 4150, -1, 4164, 4171, 4165, -1, 4168, 4171, 4164, -1, 4153, 4172, 4167, -1, 4158, 4173, 4160, -1, 4162, 4174, 4151, -1, 4163, 4172, 4153, -1, 4157, 4174, 4162, -1, 4175, 4174, 4157, -1, 4151, 4174, 4168, -1, 4166, 4176, 4163, -1, 4163, 4176, 4172, -1, 4173, 4177, 4160, -1, 4167, 4178, 4169, -1, 4160, 4177, 4179, -1, 4168, 4180, 4171, -1, 4169, 4178, 4181, -1, 4175, 4180, 4174, -1, 4174, 4180, 4168, -1, 4165, 4182, 4158, -1, 4183, 4184, 4161, -1, 4158, 4182, 4173, -1, 4170, 4184, 4166, -1, 4166, 4184, 4176, -1, 4161, 4184, 4170, -1, 4167, 4185, 4178, -1, 4182, 4186, 4173, -1, 4173, 4186, 4177, -1, 4172, 4185, 4167, -1, 4165, 4187, 4182, -1, 4171, 4187, 4165, -1, 4176, 4188, 4172, -1, 4172, 4188, 4185, -1, 4177, 4189, 4179, -1, 4178, 4190, 4181, -1, 4182, 4191, 4186, -1, 4181, 4190, 4192, -1, 4187, 4191, 4182, -1, 4193, 4194, 4183, -1, 4183, 4194, 4184, -1, 4195, 4196, 4175, -1, 4171, 4196, 4187, -1, 4184, 4194, 4176, -1, 4175, 4196, 4180, -1, 4176, 4194, 4188, -1, 4180, 4196, 4171, -1, 4185, 4197, 4178, -1, 4179, 4198, 4199, -1, 4178, 4197, 4190, -1, 4189, 4198, 4179, -1, 4186, 4200, 4177, -1, 4185, 4201, 4197, -1, 4177, 4200, 4189, -1, 4188, 4201, 4185, -1, 4195, 4202, 4196, -1, 4190, 4203, 4192, -1, 4187, 4202, 4191, -1, 4196, 4202, 4187, -1, 4192, 4203, 4204, -1, 4200, 4205, 4189, -1, 4206, 4207, 4193, -1, 4189, 4205, 4198, -1, 4193, 4207, 4194, -1, 4194, 4207, 4188, -1, 4186, 4208, 4200, -1, 4188, 4207, 4201, -1, 4197, 4209, 4190, -1, 4191, 4208, 4186, -1, 4190, 4209, 4203, -1, 4198, 4210, 4199, -1, 4201, 4211, 4197, -1, 4200, 4212, 4205, -1, 4208, 4212, 4200, -1, 4197, 4211, 4209, -1, 4213, 4214, 4195, -1, 4195, 4214, 4202, -1, 4203, 4215, 4204, -1, 4202, 4214, 4191, -1, 4191, 4214, 4208, -1, 4204, 4215, 4216, -1, 4217, 4218, 4206, -1, 4206, 4218, 4207, -1, 4207, 4218, 4201, -1, 4205, 4219, 4198, -1, 4198, 4219, 4210, -1, 4201, 4218, 4211, -1, 4209, 4220, 4203, -1, 4199, 4221, 4222, -1, 4203, 4220, 4215, -1, 4210, 4221, 4199, -1, 4211, 4223, 4209, -1, 4213, 4224, 4214, -1, 4209, 4223, 4220, -1, 4208, 4224, 4212, -1, 4214, 4224, 4208, -1, 4205, 4225, 4219, -1, 4215, 4226, 4216, -1, 4212, 4225, 4205, -1, 4216, 4226, 4227, -1, 4210, 3890, 4221, -1, 4228, 4229, 4217, -1, 4217, 4229, 4218, -1, 4211, 4229, 4223, -1, 4219, 3890, 4210, -1, 4218, 4229, 4211, -1, 4221, 3893, 4222, -1, 4215, 3884, 4226, -1, 4213, 4230, 4224, -1, 4220, 3884, 4215, -1, 4212, 4230, 4225, -1, 3905, 4230, 4213, -1, 4223, 3887, 4220, -1, 4224, 4230, 4212, -1, 4219, 3888, 3890, -1, 4220, 3887, 3884, -1, 4225, 3888, 4219, -1, 4226, 3898, 4227, -1, 3890, 3891, 4221, -1, 4227, 3898, 3895, -1, 4221, 3891, 3893, -1, 3904, 3899, 4228, -1, 4228, 3899, 4229, -1, 3893, 3894, 4222, -1, 4223, 3899, 3887, -1, 4229, 3899, 4223, -1, 4222, 3894, 3902, -1, 3884, 3886, 4226, -1, 4230, 3907, 4225, -1, 4226, 3886, 3898, -1, 3905, 3907, 4230, -1, 4225, 3907, 3888, -1, 3890, 3889, 3891, -1, 4231, 4232, 4233, -1, 4233, 4232, 4234, -1, 4235, 4232, 4231, -1, 4234, 4232, 4235, -1, 3918, 4236, 3930, -1, 4237, 4238, 4239, -1, 4240, 4238, 4241, -1, 4242, 4236, 4243, -1, 4241, 4238, 4237, -1, 4239, 4238, 4240, -1, 4141, 4244, 4161, -1, 3903, 4245, 3918, -1, 4241, 4244, 4246, -1, 4236, 4245, 4243, -1, 4246, 4244, 4141, -1, 4161, 4244, 4241, -1, 4247, 4248, 4002, -1, 4002, 4248, 4019, -1, 4243, 4245, 4249, -1, 4019, 4248, 4250, -1, 3918, 4245, 4236, -1, 4250, 4248, 4247, -1, 4228, 4231, 3904, -1, 4247, 4251, 4252, -1, 4252, 4251, 4253, -1, 4253, 4251, 4254, -1, 4245, 4231, 4249, -1, 4254, 4251, 4247, -1, 4255, 4256, 4257, -1, 4249, 4231, 4233, -1, 4258, 4256, 4255, -1, 4217, 4235, 4228, -1, 4259, 4256, 4258, -1, 4257, 4256, 4259, -1, 4258, 4260, 4261, -1, 4228, 4235, 4231, -1, 3931, 4260, 3941, -1, 4261, 4260, 3931, -1, 4234, 4235, 4262, -1, 3941, 4260, 4258, -1, 4206, 4263, 4217, -1, 4137, 4264, 4157, -1, 4193, 4263, 4206, -1, 4157, 4264, 4265, -1, 4266, 4264, 4137, -1, 4217, 4263, 4235, -1, 4265, 4264, 4266, -1, 4235, 4263, 4262, -1, 4267, 4268, 4269, -1, 4262, 4263, 4270, -1, 4271, 4268, 4267, -1, 4263, 4237, 4270, -1, 4266, 4268, 4271, -1, 4183, 4237, 4193, -1, 4269, 4268, 4266, -1, 4272, 4273, 4274, -1, 4274, 4273, 4275, -1, 4270, 4237, 4239, -1, 4276, 4273, 4272, -1, 4193, 4237, 4263, -1, 4275, 4273, 4276, -1, 4161, 4241, 4183, -1, 4066, 4277, 4276, -1, 4278, 4277, 4055, -1, 4183, 4241, 4237, -1, 4276, 4277, 4278, -1, 4055, 4277, 4066, -1, 4240, 4241, 4279, -1, 4120, 4246, 4141, -1, 4280, 4281, 3657, -1, 4282, 4281, 4280, -1, 4241, 4246, 4279, -1, 3657, 4283, 4029, -1, 4281, 4283, 3657, -1, 4279, 4246, 4284, -1, 4029, 4283, 4028, -1, 4103, 4285, 4120, -1, 4028, 4283, 4282, -1, 4282, 4283, 4281, -1, 4246, 4285, 4284, -1, 4120, 4285, 4246, -1, 4284, 4285, 4286, -1, 4103, 4287, 4285, -1, 4084, 4287, 4103, -1, 4062, 4287, 4084, -1, 4288, 4287, 4289, -1, 4286, 4287, 4288, -1, 4285, 4287, 4286, -1, 4044, 4290, 4062, -1, 4287, 4290, 4289, -1, 4289, 4290, 4291, -1, 4062, 4290, 4287, -1, 4019, 4250, 4044, -1, 4290, 4250, 4291, -1, 4044, 4250, 4290, -1, 4291, 4250, 4292, -1, 3992, 4247, 4002, -1, 4292, 4247, 4252, -1, 4250, 4247, 4292, -1, 3981, 4254, 3992, -1, 4253, 4254, 4293, -1, 3992, 4254, 4247, -1, 3971, 4294, 3981, -1, 3962, 4294, 3971, -1, 4293, 4294, 4295, -1, 3981, 4294, 4254, -1, 4254, 4294, 4293, -1, 3952, 4255, 3962, -1, 4295, 4255, 4257, -1, 3962, 4255, 4294, -1, 4294, 4255, 4295, -1, 3952, 4258, 4255, -1, 3941, 4258, 3952, -1, 4259, 4258, 4296, -1, 4258, 4261, 4296, -1, 3909, 4261, 3931, -1, 4296, 4261, 4297, -1, 3905, 4298, 3909, -1, 3909, 4298, 4261, -1, 4261, 4298, 4297, -1, 4297, 4298, 4299, -1, 4213, 4300, 3905, -1, 4195, 4300, 4213, -1, 3905, 4300, 4298, -1, 4298, 4300, 4299, -1, 4301, 4300, 4302, -1, 4299, 4300, 4301, -1, 4300, 4303, 4302, -1, 4175, 4303, 4195, -1, 4195, 4303, 4300, -1, 4302, 4303, 4304, -1, 4303, 4265, 4304, -1, 4175, 4265, 4303, -1, 4157, 4265, 4175, -1, 4304, 4265, 4305, -1, 4125, 4266, 4137, -1, 4305, 4266, 4271, -1, 4265, 4266, 4305, -1, 4114, 4269, 4125, -1, 4267, 4269, 4306, -1, 4125, 4269, 4266, -1, 4269, 4307, 4306, -1, 4102, 4307, 4114, -1, 4091, 4307, 4102, -1, 4306, 4307, 4308, -1, 4114, 4307, 4269, -1, 4079, 4272, 4091, -1, 4308, 4272, 4274, -1, 4091, 4272, 4307, -1, 4307, 4272, 4308, -1, 4079, 4276, 4272, -1, 4066, 4276, 4079, -1, 4275, 4276, 4309, -1, 4276, 4278, 4309, -1, 4043, 4278, 4055, -1, 4309, 4278, 4310, -1, 4278, 4282, 4310, -1, 4043, 4282, 4278, -1, 4028, 4282, 4043, -1, 4310, 4282, 4280, -1, 4242, 4311, 4236, -1, 3675, 4311, 4242, -1, 4311, 4312, 4236, -1, 3930, 4312, 4010, -1, 4010, 4312, 3675, -1, 3675, 4312, 4311, -1, 4236, 4312, 3930, -1, 3904, 4313, 3903, -1, 3903, 4313, 4245, -1, 4231, 4313, 3904, -1, 4245, 4313, 4231, -1, 557, 4314, 576, -1, 4315, 4314, 557, -1, 581, 4316, 578, -1, 4317, 4316, 581, -1, 576, 4318, 613, -1, 578, 4319, 579, -1, 4314, 4318, 576, -1, 4316, 4319, 578, -1, 610, 4320, 608, -1, 4319, 4321, 579, -1, 613, 4322, 633, -1, 4318, 4322, 613, -1, 608, 4323, 631, -1, 4320, 4323, 608, -1, 633, 4324, 648, -1, 4322, 4324, 633, -1, 4323, 4325, 631, -1, 631, 4325, 646, -1, 648, 4326, 663, -1, 4324, 4326, 648, -1, 4325, 4327, 646, -1, 646, 4327, 662, -1, 663, 4328, 678, -1, 4326, 4328, 663, -1, 4327, 4329, 662, -1, 662, 4329, 680, -1, 4328, 4330, 678, -1, 678, 4330, 696, -1, 4329, 4331, 680, -1, 680, 4331, 695, -1, 4330, 4332, 696, -1, 696, 4332, 712, -1, 4331, 4333, 695, -1, 695, 4333, 711, -1, 4332, 4334, 712, -1, 712, 4334, 728, -1, 4333, 4335, 711, -1, 711, 4335, 727, -1, 4334, 4336, 728, -1, 728, 4336, 743, -1, 4335, 4337, 727, -1, 727, 4337, 741, -1, 4336, 4338, 743, -1, 743, 4338, 392, -1, 4337, 4339, 741, -1, 741, 4339, 388, -1, 4338, 4340, 392, -1, 392, 4340, 390, -1, 4339, 4341, 388, -1, 388, 4341, 386, -1, 4340, 4342, 390, -1, 390, 4342, 416, -1, 4341, 4343, 386, -1, 386, 4343, 415, -1, 4342, 4344, 416, -1, 416, 4344, 432, -1, 4343, 4345, 415, -1, 415, 4345, 431, -1, 4344, 4346, 432, -1, 432, 4346, 446, -1, 4345, 4347, 431, -1, 431, 4347, 448, -1, 4346, 4348, 446, -1, 446, 4348, 463, -1, 4347, 4349, 448, -1, 448, 4349, 462, -1, 4348, 4350, 463, -1, 463, 4350, 479, -1, 4349, 4351, 462, -1, 462, 4351, 477, -1, 4350, 4352, 479, -1, 479, 4352, 495, -1, 4351, 4353, 477, -1, 477, 4353, 494, -1, 4352, 4354, 495, -1, 495, 4354, 512, -1, 4353, 4355, 494, -1, 494, 4355, 511, -1, 512, 4356, 527, -1, 4354, 4356, 512, -1, 4355, 4357, 511, -1, 511, 4357, 526, -1, 527, 4358, 543, -1, 4356, 4358, 527, -1, 526, 4359, 541, -1, 4357, 4359, 526, -1, 543, 4360, 559, -1, 4358, 4360, 543, -1, 541, 4315, 557, -1, 4359, 4315, 541, -1, 559, 4317, 581, -1, 4360, 4317, 559, -1, 69, 4361, 85, -1, 4362, 4363, 127, -1, 127, 4363, 142, -1, 85, 4364, 103, -1, 4361, 4364, 85, -1, 142, 4365, 157, -1, 4363, 4365, 142, -1, 103, 4366, 117, -1, 4364, 4366, 103, -1, 157, 4367, 175, -1, 4365, 4367, 157, -1, 4368, 4369, 40, -1, 40, 4369, 41, -1, 117, 4370, 133, -1, 4366, 4370, 117, -1, 4369, 4371, 41, -1, 175, 4372, 193, -1, 4367, 4372, 175, -1, 41, 4371, 243, -1, 133, 4373, 149, -1, 4370, 4373, 133, -1, 193, 4374, 203, -1, 4372, 4374, 193, -1, 4371, 4375, 243, -1, 243, 4375, 259, -1, 149, 4376, 165, -1, 4373, 4376, 149, -1, 203, 4377, 217, -1, 4374, 4377, 203, -1, 4375, 4378, 259, -1, 191, 4379, 190, -1, 259, 4378, 275, -1, 165, 4379, 191, -1, 4376, 4379, 165, -1, 217, 4380, 234, -1, 4377, 4380, 217, -1, 4379, 4381, 190, -1, 4378, 4382, 275, -1, 275, 4382, 291, -1, 4380, 4383, 234, -1, 234, 4383, 251, -1, 4382, 4384, 291, -1, 291, 4384, 307, -1, 4383, 4385, 251, -1, 251, 4385, 266, -1, 4384, 4386, 307, -1, 307, 4386, 324, -1, 4385, 4387, 266, -1, 266, 4387, 282, -1, 4386, 4388, 324, -1, 324, 4388, 340, -1, 4387, 4389, 282, -1, 282, 4389, 300, -1, 4388, 4390, 340, -1, 340, 4390, 354, -1, 4389, 4391, 300, -1, 300, 4391, 316, -1, 4390, 4392, 354, -1, 354, 4392, 370, -1, 4391, 4393, 316, -1, 316, 4393, 330, -1, 4392, 4394, 370, -1, 370, 4394, 24, -1, 4393, 4395, 330, -1, 330, 4395, 347, -1, 4394, 4396, 24, -1, 24, 4396, 23, -1, 4395, 4397, 347, -1, 347, 4397, 362, -1, 4396, 4398, 23, -1, 23, 4398, 46, -1, 4397, 4399, 362, -1, 362, 4399, 3, -1, 4398, 4400, 46, -1, 46, 4400, 62, -1, 4399, 4401, 3, -1, 3, 4401, 7, -1, 4400, 4402, 62, -1, 62, 4402, 77, -1, 4401, 4403, 7, -1, 7, 4403, 34, -1, 4402, 4404, 77, -1, 77, 4404, 93, -1, 4403, 4405, 34, -1, 34, 4405, 53, -1, 4404, 4406, 93, -1, 93, 4406, 110, -1, 4405, 4407, 53, -1, 53, 4407, 69, -1, 4406, 4362, 110, -1, 110, 4362, 127, -1, 4407, 4361, 69, -1, 4408, 4409, 4410, -1, 4410, 4409, 4411, -1, 4411, 4412, 4413, -1, 4409, 4412, 4411, -1, 4413, 4414, 4415, -1, 4412, 4414, 4413, -1, 4415, 4416, 4417, -1, 4414, 4416, 4415, -1, 4417, 4418, 4419, -1, 4416, 4418, 4417, -1, 4419, 4420, 4421, -1, 4418, 4420, 4419, -1, 4421, 4422, 4423, -1, 4420, 4422, 4421, -1, 4423, 4424, 4425, -1, 4422, 4424, 4423, -1, 4425, 4426, 4427, -1, 4424, 4426, 4425, -1, 4427, 4428, 4429, -1, 4426, 4428, 4427, -1, 4429, 4430, 4431, -1, 4428, 4430, 4429, -1, 4431, 4432, 4433, -1, 4430, 4432, 4431, -1, 4433, 4434, 4435, -1, 4432, 4434, 4433, -1, 4436, 4437, 4438, -1, 4438, 4437, 4439, -1, 4439, 4440, 4441, -1, 4437, 4440, 4439, -1, 4441, 4442, 4443, -1, 4440, 4442, 4441, -1, 4443, 4444, 4445, -1, 4442, 4444, 4443, -1, 4445, 4446, 4447, -1, 4444, 4446, 4445, -1, 4447, 4448, 4449, -1, 4446, 4448, 4447, -1, 4449, 4450, 4451, -1, 4448, 4450, 4449, -1, 4451, 4452, 4453, -1, 4450, 4452, 4451, -1, 4453, 4454, 4455, -1, 4452, 4454, 4453, -1, 4455, 4456, 4457, -1, 4454, 4456, 4455, -1, 4457, 4458, 4459, -1, 4456, 4458, 4457, -1, 4459, 4460, 4461, -1, 4458, 4460, 4459, -1, 4461, 4462, 4463, -1, 4460, 4462, 4461, -1, 4464, 4465, 4466, -1, 4466, 4467, 4468, -1, 4465, 4467, 4466, -1, 4468, 4469, 4470, -1, 4467, 4469, 4468, -1, 4470, 4471, 4472, -1, 4469, 4471, 4470, -1, 4472, 4473, 4474, -1, 4471, 4473, 4472, -1, 4474, 4475, 4476, -1, 4473, 4475, 4474, -1, 4476, 4477, 4478, -1, 4475, 4477, 4476, -1, 4478, 4479, 4480, -1, 4477, 4479, 4478, -1, 4480, 4481, 4482, -1, 4479, 4481, 4480, -1, 4482, 4483, 4484, -1, 4481, 4483, 4482, -1, 4484, 4485, 4486, -1, 4483, 4485, 4484, -1, 4486, 4487, 4488, -1, 4485, 4487, 4486, -1, 4488, 4489, 4490, -1, 4487, 4489, 4488, -1, 4489, 4491, 4490, -1, 4492, 4493, 4494, -1, 4494, 4493, 4495, -1, 4496, 4497, 4498, -1, 4495, 4499, 4500, -1, 4493, 4499, 4495, -1, 4497, 4501, 4498, -1, 4500, 4502, 4503, -1, 4499, 4502, 4500, -1, 4498, 4504, 4505, -1, 4501, 4504, 4498, -1, 4503, 4506, 4507, -1, 4502, 4506, 4503, -1, 4505, 4508, 4509, -1, 4504, 4508, 4505, -1, 4507, 4510, 4511, -1, 4506, 4510, 4507, -1, 4509, 4512, 4513, -1, 4508, 4512, 4509, -1, 4511, 4514, 4515, -1, 4510, 4514, 4511, -1, 4513, 4516, 4517, -1, 4512, 4516, 4513, -1, 4515, 4518, 4519, -1, 4514, 4518, 4515, -1, 4517, 4520, 4521, -1, 4516, 4520, 4517, -1, 4521, 4522, 4523, -1, 4520, 4522, 4521, -1, 4523, 4524, 4525, -1, 4522, 4524, 4523, -1, 4525, 4526, 4527, -1, 4524, 4526, 4525, -1, 4527, 4528, 4529, -1, 4526, 4528, 4527, -1, 4528, 4530, 4529, -1, 4529, 4530, 4531, -1, 4530, 4532, 4531, -1, 4531, 4532, 4533, -1, 4532, 4534, 4533, -1, 4533, 4534, 4535, -1, 4534, 4536, 4535, -1, 4535, 4536, 4537, -1, 4536, 4538, 4537, -1, 4537, 4538, 4539, -1, 4538, 4540, 4539, -1, 4539, 4540, 4541, -1, 4540, 4542, 4541, -1, 4541, 4542, 4543, -1, 4542, 4544, 4543, -1, 4543, 4544, 4545, -1, 4544, 4492, 4545, -1, 4545, 4492, 4494, -1, 4546, 2493, 4547, -1, 2756, 2493, 4546, -1, 2493, 2481, 4547, -1, 4548, 2481, 4549, -1, 4547, 2481, 4548, -1, 4549, 2474, 4550, -1, 2481, 2474, 4549, -1, 2369, 2368, 4551, -1, 4551, 2368, 4552, -1, 4550, 2465, 4553, -1, 2474, 2465, 4550, -1, 4552, 2535, 4554, -1, 2368, 2535, 4552, -1, 4553, 2704, 4555, -1, 2465, 2704, 4553, -1, 4554, 2528, 4556, -1, 2535, 2528, 4554, -1, 4555, 2676, 4557, -1, 2704, 2676, 4555, -1, 4556, 2418, 4558, -1, 2528, 2418, 4556, -1, 4557, 2642, 4559, -1, 2676, 2642, 4557, -1, 2418, 2400, 4558, -1, 4558, 2400, 4560, -1, 2642, 2613, 4559, -1, 2400, 2364, 4560, -1, 4559, 2586, 4561, -1, 4560, 2364, 4562, -1, 2613, 2586, 4559, -1, 2364, 2348, 4562, -1, 4561, 2555, 4563, -1, 4562, 2348, 4564, -1, 2586, 2555, 4561, -1, 2348, 2335, 4564, -1, 2555, 2525, 4563, -1, 4564, 2335, 4565, -1, 4563, 2525, 4566, -1, 2335, 2320, 4565, -1, 2525, 2489, 4566, -1, 4565, 2320, 4567, -1, 4566, 2489, 4568, -1, 2320, 2298, 4567, -1, 4569, 2298, 4570, -1, 2489, 2448, 4568, -1, 4567, 2298, 4569, -1, 4568, 2448, 4571, -1, 2298, 2284, 4570, -1, 4570, 2284, 4572, -1, 2448, 2445, 4571, -1, 4571, 2445, 4573, -1, 2284, 2852, 4572, -1, 2445, 2794, 4573, -1, 4573, 2794, 4574, -1, 2852, 2816, 4572, -1, 4575, 2816, 4576, -1, 4572, 2816, 4575, -1, 2794, 2421, 4574, -1, 4574, 2421, 4577, -1, 2816, 2818, 4576, -1, 4576, 2818, 4578, -1, 2421, 2411, 4577, -1, 4577, 2411, 4579, -1, 2818, 2855, 4578, -1, 4578, 2855, 4580, -1, 2411, 2393, 4579, -1, 4579, 2393, 4581, -1, 2393, 2394, 4581, -1, 2855, 2789, 4580, -1, 4581, 2394, 4582, -1, 4580, 2789, 4583, -1, 2789, 2784, 4583, -1, 4583, 2784, 4584, -1, 2784, 2770, 4584, -1, 4584, 2770, 4546, -1, 2770, 2756, 4546, -1, 4585, 4586, 4587, -1, 4588, 4586, 4585, -1, 4587, 4589, 4590, -1, 4586, 4589, 4587, -1, 4591, 3378, 4592, -1, 4590, 4593, 4594, -1, 4589, 4593, 4590, -1, 4592, 4595, 4596, -1, 3378, 4595, 4592, -1, 4594, 4597, 4598, -1, 4593, 4597, 4594, -1, 4595, 4599, 4596, -1, 4596, 4599, 4600, -1, 4598, 4601, 4602, -1, 4597, 4601, 4598, -1, 4599, 4603, 4600, -1, 4600, 4603, 4604, -1, 4602, 4605, 4606, -1, 4601, 4605, 4602, -1, 4603, 4607, 4604, -1, 4604, 4607, 4608, -1, 4606, 4609, 4610, -1, 4605, 4609, 4606, -1, 4607, 4611, 4608, -1, 4608, 4611, 4612, -1, 4610, 4613, 4614, -1, 4609, 4613, 4610, -1, 4611, 4615, 4612, -1, 4612, 4615, 4616, -1, 4613, 4617, 4614, -1, 4614, 4617, 4618, -1, 4615, 4619, 4616, -1, 4616, 4619, 4620, -1, 4617, 4621, 4618, -1, 4618, 4621, 4622, -1, 4619, 4623, 4620, -1, 4620, 4623, 4624, -1, 4621, 4625, 4622, -1, 4622, 4625, 4626, -1, 4623, 4627, 4624, -1, 4624, 4627, 4628, -1, 4625, 4629, 4626, -1, 4626, 4629, 4630, -1, 4627, 4631, 4628, -1, 4628, 4631, 4632, -1, 4629, 4633, 4630, -1, 4630, 4633, 4634, -1, 4631, 4635, 4632, -1, 4632, 4635, 4636, -1, 4633, 4637, 4634, -1, 4634, 4637, 4638, -1, 4635, 4639, 4636, -1, 4636, 4639, 4640, -1, 4637, 4641, 4638, -1, 4638, 4641, 4642, -1, 4639, 4643, 4640, -1, 4640, 4643, 4644, -1, 4641, 4645, 4642, -1, 4642, 4645, 4646, -1, 4643, 4647, 4644, -1, 4644, 4647, 4648, -1, 4645, 4649, 4646, -1, 4646, 4649, 4650, -1, 4647, 4651, 4648, -1, 4648, 4651, 4652, -1, 4649, 4653, 4650, -1, 4650, 4653, 4654, -1, 4651, 4655, 4652, -1, 4652, 4655, 4656, -1, 4653, 4657, 4654, -1, 4654, 4657, 4658, -1, 4655, 4659, 4656, -1, 4656, 4659, 4660, -1, 4658, 4661, 4662, -1, 4657, 4661, 4658, -1, 4659, 4663, 4660, -1, 4662, 4664, 4665, -1, 4660, 4663, 4666, -1, 4661, 4664, 4662, -1, 4663, 4667, 4666, -1, 4665, 4668, 4669, -1, 4666, 4667, 4670, -1, 4664, 4668, 4665, -1, 4668, 3151, 4669, -1, 4670, 4588, 4585, -1, 4667, 4588, 4670, -1, 4671, 4672, 1875, -1, 1875, 4672, 1864, -1, 1864, 4673, 1853, -1, 1736, 3662, 1734, -1, 4672, 4673, 1864, -1, 1734, 4674, 1920, -1, 1853, 4675, 1847, -1, 3662, 4674, 1734, -1, 4673, 4675, 1853, -1, 1920, 4676, 1909, -1, 4674, 4676, 1920, -1, 1847, 4677, 2054, -1, 4675, 4677, 1847, -1, 1909, 4678, 1778, -1, 4676, 4678, 1909, -1, 2054, 4679, 2017, -1, 4677, 4679, 2054, -1, 1778, 4680, 1742, -1, 4678, 4680, 1778, -1, 2017, 4681, 1989, -1, 4679, 4681, 2017, -1, 4680, 4682, 1742, -1, 1742, 4682, 1724, -1, 1989, 4683, 1959, -1, 4681, 4683, 1989, -1, 4682, 4684, 1724, -1, 1724, 4684, 1710, -1, 1959, 4685, 1929, -1, 4683, 4685, 1959, -1, 4684, 4686, 1710, -1, 1710, 4686, 1696, -1, 1929, 4687, 1895, -1, 4685, 4687, 1929, -1, 4686, 4688, 1696, -1, 1696, 4688, 1682, -1, 4687, 4689, 1895, -1, 1895, 4689, 1856, -1, 4688, 4690, 1682, -1, 1682, 4690, 1630, -1, 4689, 4691, 1856, -1, 4690, 4692, 1630, -1, 1856, 4691, 1820, -1, 1630, 4692, 1627, -1, 4691, 4693, 1820, -1, 4692, 4694, 1627, -1, 1627, 4694, 2204, -1, 1820, 4693, 1801, -1, 4694, 4695, 2204, -1, 4693, 4696, 1801, -1, 2204, 4695, 2181, -1, 1801, 4696, 1800, -1, 4695, 4697, 2181, -1, 4696, 4698, 1800, -1, 2181, 4697, 2180, -1, 1800, 4698, 2172, -1, 4697, 4699, 2180, -1, 4698, 4700, 2172, -1, 2180, 4699, 2231, -1, 2172, 4700, 1781, -1, 4699, 4701, 2231, -1, 4700, 4702, 1781, -1, 2231, 4701, 2166, -1, 1781, 4702, 1764, -1, 4701, 4703, 2166, -1, 4702, 4704, 1764, -1, 2166, 4703, 2151, -1, 1764, 4704, 1747, -1, 4704, 3855, 1747, -1, 1747, 3855, 1746, -1, 4703, 4705, 2151, -1, 4705, 4706, 2151, -1, 2151, 4706, 2134, -1, 4706, 4707, 2134, -1, 2134, 4707, 2120, -1, 2120, 4671, 1875, -1, 4707, 4671, 2120, -1, 3966, 4708, 3956, -1, 4709, 4708, 3966, -1, 3956, 4710, 3946, -1, 4708, 4710, 3956, -1, 4005, 1158, 3915, -1, 3946, 4711, 3936, -1, 4710, 4711, 3946, -1, 3915, 4712, 3897, -1, 1158, 4712, 3915, -1, 3936, 4713, 3917, -1, 4711, 4713, 3936, -1, 4712, 4714, 3897, -1, 3897, 4714, 3895, -1, 3917, 4715, 3902, -1, 4713, 4715, 3917, -1, 4714, 4716, 3895, -1, 3895, 4716, 4227, -1, 3902, 4717, 4222, -1, 4715, 4717, 3902, -1, 4716, 4718, 4227, -1, 4227, 4718, 4216, -1, 4222, 4719, 4199, -1, 4717, 4719, 4222, -1, 4718, 4720, 4216, -1, 4216, 4720, 4204, -1, 4199, 4721, 4179, -1, 4719, 4721, 4199, -1, 4720, 4722, 4204, -1, 4204, 4722, 4192, -1, 4721, 4723, 4179, -1, 4179, 4723, 4160, -1, 4722, 4724, 4192, -1, 4192, 4724, 4181, -1, 4723, 4725, 4160, -1, 4160, 4725, 4143, -1, 4724, 4726, 4181, -1, 4181, 4726, 4169, -1, 4725, 4727, 4143, -1, 4143, 4727, 4135, -1, 4726, 4728, 4169, -1, 4169, 4728, 4154, -1, 4727, 4729, 4135, -1, 4135, 4729, 4124, -1, 4728, 4730, 4154, -1, 4154, 4730, 4133, -1, 4729, 4731, 4124, -1, 4124, 4731, 4111, -1, 4730, 4732, 4133, -1, 4133, 4732, 4115, -1, 4731, 4733, 4111, -1, 4111, 4733, 4099, -1, 4732, 4734, 4115, -1, 4115, 4734, 4093, -1, 4733, 4735, 4099, -1, 4099, 4735, 4087, -1, 4734, 4736, 4093, -1, 4093, 4736, 4071, -1, 4735, 4737, 4087, -1, 4087, 4737, 4076, -1, 4736, 4738, 4071, -1, 4071, 4738, 4050, -1, 4737, 4739, 4076, -1, 4076, 4739, 4064, -1, 4738, 4740, 4050, -1, 4050, 4740, 4032, -1, 4739, 4741, 4064, -1, 4064, 4741, 4052, -1, 4740, 4742, 4032, -1, 4032, 4742, 4007, -1, 4741, 4743, 4052, -1, 4052, 4743, 4039, -1, 4742, 4744, 4007, -1, 4007, 4744, 3996, -1, 4039, 4745, 4026, -1, 4743, 4745, 4039, -1, 4744, 4746, 3996, -1, 4026, 4747, 4015, -1, 3996, 4746, 3986, -1, 4745, 4747, 4026, -1, 4746, 4748, 3986, -1, 4015, 4749, 4014, -1, 3986, 4748, 3976, -1, 4747, 4749, 4015, -1, 4749, 1208, 4014, -1, 3976, 4709, 3966, -1, 4748, 4709, 3976, -1, 4750, 4751, 4752, -1, 4750, 4753, 4751, -1, 4750, 4752, 4753, -1, 4754, 4755, 4756, -1, 4754, 4757, 4758, -1, 4754, 4759, 4757, -1, 4760, 4761, 4762, -1, 4754, 4756, 4759, -1, 4763, 4764, 4765, -1, 4766, 4767, 4755, -1, 4763, 4765, 4768, -1, 4766, 4755, 4754, -1, 4766, 4758, 4769, -1, 4766, 4754, 4758, -1, 4770, 4768, 4761, -1, 4771, 4751, 4767, -1, 4770, 4761, 4760, -1, 4771, 4752, 4751, -1, 4771, 4767, 4766, -1, 4771, 4766, 4769, -1, 4771, 4769, 4772, -1, 4773, 4774, 4764, -1, 4773, 4764, 4763, -1, 4775, 4771, 4772, -1, 4775, 4752, 4771, -1, 4775, 4772, 4776, -1, 4775, 4776, 4752, -1, 4777, 4763, 4768, -1, 4777, 4768, 4770, -1, 4778, 4760, 4762, -1, 4778, 4762, 4779, -1, 4780, 4781, 4774, -1, 901, 4782, 4783, -1, 4780, 4774, 4773, -1, 4784, 4773, 4763, -1, 4784, 4763, 4777, -1, 4784, 4781, 4780, -1, 4784, 4780, 4773, -1, 4784, 4785, 4781, -1, 4786, 4770, 4760, -1, 4786, 4760, 4778, -1, 4787, 4778, 4779, -1, 4788, 4777, 4770, -1, 4788, 4770, 4786, -1, 4789, 4786, 4778, -1, 4789, 4778, 4787, -1, 4790, 4784, 4777, -1, 4790, 4777, 4788, -1, 4791, 4779, 4792, -1, 4791, 4787, 4779, -1, 4793, 4786, 4789, -1, 4793, 4788, 4786, -1, 4794, 4785, 4784, -1, 4794, 4784, 4790, -1, 4795, 4789, 4787, -1, 4795, 4787, 4791, -1, 4796, 4797, 4785, -1, 4796, 4785, 4794, -1, 4796, 4790, 4788, -1, 4796, 4788, 4793, -1, 4796, 4794, 4790, -1, 4798, 4791, 4792, -1, 4799, 4793, 4789, -1, 4799, 4789, 4795, -1, 4800, 4795, 4791, -1, 4800, 4791, 4798, -1, 4801, 4793, 4799, -1, 4801, 4796, 4793, -1, 4802, 4792, 4803, -1, 4802, 4798, 4792, -1, 4804, 4795, 4800, -1, 4804, 4799, 4795, -1, 4805, 4796, 4801, -1, 4805, 4797, 4796, -1, 4806, 4800, 4798, -1, 4806, 4798, 4802, -1, 4807, 4799, 4804, -1, 4807, 4797, 4805, -1, 4807, 4808, 4797, -1, 4807, 4801, 4799, -1, 4807, 4805, 4801, -1, 4809, 4802, 4803, -1, 4810, 4800, 4806, -1, 4810, 4804, 4800, -1, 4811, 4802, 4809, -1, 4811, 4806, 4802, -1, 4812, 4807, 4804, -1, 4812, 4804, 4810, -1, 4813, 4803, 4814, -1, 4813, 4809, 4803, -1, 4815, 4810, 4806, -1, 4815, 4806, 4811, -1, 4816, 4808, 4807, -1, 4816, 4807, 4812, -1, 4817, 4811, 4809, -1, 4817, 4809, 4813, -1, 4818, 4812, 4810, -1, 4818, 4810, 4815, -1, 4818, 4808, 4816, -1, 4818, 4816, 4812, -1, 4818, 4819, 4808, -1, 4820, 4813, 4814, -1, 4821, 4815, 4811, -1, 4821, 4811, 4817, -1, 4822, 4817, 4813, -1, 4822, 4813, 4820, -1, 4823, 4818, 4815, -1, 4823, 4815, 4821, -1, 4824, 4814, 4825, -1, 4824, 4820, 4814, -1, 4826, 4821, 4817, -1, 4826, 4817, 4822, -1, 4827, 4819, 4818, -1, 4827, 4818, 4823, -1, 4828, 4822, 4820, -1, 4828, 4820, 4824, -1, 4829, 4823, 4821, -1, 4829, 4821, 4826, -1, 4829, 4819, 4827, -1, 4829, 4830, 4819, -1, 4829, 4827, 4823, -1, 4831, 4824, 4825, -1, 4832, 4826, 4822, -1, 4832, 4822, 4828, -1, 4833, 4828, 4824, -1, 4833, 4824, 4831, -1, 4834, 4826, 4832, -1, 4834, 4829, 4826, -1, 4835, 4825, 4836, -1, 4835, 4831, 4825, -1, 4837, 4832, 4828, -1, 4837, 4828, 4833, -1, 4838, 4830, 4829, -1, 4838, 4829, 4834, -1, 4839, 4833, 4831, -1, 4839, 4831, 4835, -1, 4840, 4834, 4832, -1, 4840, 4841, 4830, -1, 4840, 4832, 4837, -1, 4840, 4830, 4838, -1, 4840, 4838, 4834, -1, 4842, 4835, 4836, -1, 4843, 4837, 4833, -1, 4843, 4833, 4839, -1, 4844, 4835, 4842, -1, 4844, 4839, 4835, -1, 4845, 4837, 4843, -1, 4845, 4840, 4837, -1, 4846, 4836, 4847, -1, 4846, 4842, 4836, -1, 4848, 4840, 4845, -1, 4848, 4841, 4840, -1, 4849, 4839, 4844, -1, 4849, 4843, 4839, -1, 4850, 4844, 4842, -1, 4850, 4842, 4846, -1, 4851, 4845, 4843, -1, 4851, 4848, 4845, -1, 4851, 4841, 4848, -1, 4851, 4852, 4841, -1, 4851, 4843, 4849, -1, 4853, 4846, 4847, -1, 4854, 4849, 4844, -1, 4854, 4844, 4850, -1, 4855, 4776, 4772, -1, 4856, 4850, 4846, -1, 4856, 4846, 4853, -1, 4857, 4582, 4858, -1, 4857, 4859, 4582, -1, 4860, 4851, 4849, -1, 4860, 4849, 4854, -1, 4861, 4859, 4857, -1, 4862, 4847, 4863, -1, 4861, 4864, 4859, -1, 4862, 4853, 4847, -1, 4865, 4852, 4851, -1, 4865, 4851, 4860, -1, 4866, 4867, 4864, -1, 4868, 4854, 4850, -1, 4866, 4864, 4861, -1, 4868, 4850, 4856, -1, 4869, 901, 4783, -1, 4869, 4867, 4866, -1, 4869, 900, 901, -1, 4869, 4783, 4867, -1, 4870, 4857, 4858, -1, 4871, 4856, 4853, -1, 4870, 4858, 4872, -1, 4871, 4853, 4862, -1, 4873, 4860, 4854, -1, 4874, 4857, 4870, -1, 4873, 4852, 4865, -1, 4873, 4854, 4868, -1, 4873, 4865, 4860, -1, 4873, 4875, 4852, -1, 4874, 4861, 4857, -1, 4876, 4862, 4863, -1, 4877, 4861, 4874, -1, 4878, 4856, 4871, -1, 4878, 4868, 4856, -1, 4877, 4866, 4861, -1, 4879, 900, 4869, -1, 4879, 4869, 4866, -1, 4880, 4871, 4862, -1, 4879, 4866, 4877, -1, 4879, 898, 900, -1, 4880, 4862, 4876, -1, 4881, 4870, 4872, -1, 4882, 4873, 4868, -1, 4881, 4872, 4883, -1, 4882, 4868, 4878, -1, 4884, 4863, 4885, -1, 4886, 4887, 898, -1, 4884, 4876, 4863, -1, 4886, 4879, 4887, -1, 4886, 898, 4879, -1, 4888, 4875, 4873, -1, 4888, 4873, 4882, -1, 4889, 4874, 4870, -1, 4890, 4878, 4871, -1, 4889, 4870, 4881, -1, 4890, 4871, 4880, -1, 4891, 4877, 4874, -1, 4891, 4874, 4889, -1, 4892, 4880, 4876, -1, 4892, 4876, 4884, -1, 4893, 4879, 4877, -1, 4893, 4887, 4879, -1, 4894, 4882, 4878, -1, 4894, 4875, 4888, -1, 4893, 4877, 4891, -1, 4894, 4878, 4890, -1, 4894, 4895, 4875, -1, 4896, 4881, 4883, -1, 4894, 4888, 4882, -1, 4896, 4883, 4897, -1, 4898, 4884, 4885, -1, 4899, 4900, 4887, -1, 4899, 4893, 4900, -1, 4901, 4890, 4880, -1, 4899, 4887, 4893, -1, 4901, 4880, 4892, -1, 4902, 4889, 4881, -1, 4902, 4881, 4896, -1, 4903, 4891, 4889, -1, 4903, 4889, 4902, -1, 4904, 4892, 4884, -1, 4904, 4884, 4898, -1, 4905, 4894, 4890, -1, 4905, 4890, 4901, -1, 4906, 4891, 4903, -1, 4907, 4885, 4908, -1, 4906, 4900, 4893, -1, 4906, 4893, 4891, -1, 4907, 4898, 4885, -1, 4909, 4894, 4905, -1, 4910, 4897, 4911, -1, 4909, 4895, 4894, -1, 4910, 4896, 4897, -1, 4912, 4901, 4892, -1, 4912, 4892, 4904, -1, 4913, 4906, 4914, -1, 4913, 4914, 4900, -1, 4913, 4900, 4906, -1, 4915, 4896, 4910, -1, 4916, 4904, 4898, -1, 4915, 4902, 4896, -1, 4916, 4898, 4907, -1, 4917, 4903, 4902, -1, 4918, 4919, 4895, -1, 4917, 4902, 4915, -1, 4918, 4901, 4912, -1, 4918, 4905, 4901, -1, 4918, 4895, 4909, -1, 4918, 4909, 4905, -1, 4920, 4912, 4904, -1, 4921, 4914, 4906, -1, 4921, 4906, 4903, -1, 4921, 4903, 4917, -1, 4920, 4904, 4916, -1, 4922, 4911, 4923, -1, 4924, 4907, 4908, -1, 4922, 4910, 4911, -1, 4925, 4921, 4926, -1, 4925, 4914, 4921, -1, 4927, 4912, 4920, -1, 4925, 4926, 4914, -1, 4927, 4918, 4912, -1, 4928, 4915, 4910, -1, 4928, 4910, 4922, -1, 4929, 4907, 4924, -1, 4929, 4916, 4907, -1, 4930, 4917, 4915, -1, 4930, 4915, 4928, -1, 4931, 4908, 4932, -1, 4931, 4924, 4908, -1, 4933, 4926, 4921, -1, 4934, 4919, 4918, -1, 4934, 4918, 4927, -1, 4933, 4917, 4930, -1, 4935, 4920, 4916, -1, 4933, 4921, 4917, -1, 4935, 4916, 4929, -1, 4936, 4922, 4923, -1, 4936, 4923, 4937, -1, 4938, 4929, 4924, -1, 4938, 4924, 4931, -1, 4939, 4926, 4933, -1, 4939, 4940, 4926, -1, 4941, 4919, 4934, -1, 4941, 4927, 4920, -1, 4941, 4920, 4935, -1, 4941, 4934, 4927, -1, 4942, 4928, 4922, -1, 4942, 4922, 4936, -1, 4941, 4943, 4919, -1, 4944, 4929, 4938, -1, 4945, 4930, 4928, -1, 4944, 4935, 4929, -1, 4945, 4928, 4942, -1, 4946, 4933, 4930, -1, 4947, 4931, 4932, -1, 4946, 4930, 4945, -1, 4948, 4935, 4944, -1, 4948, 4941, 4935, -1, 4949, 4937, 4950, -1, 4951, 4932, 4952, -1, 4949, 4936, 4937, -1, 4951, 4947, 4932, -1, 4953, 4933, 4946, -1, 4953, 4939, 4933, -1, 4953, 4954, 4940, -1, 4955, 4938, 4931, -1, 4953, 4940, 4939, -1, 4955, 4931, 4947, -1, 4956, 4943, 4941, -1, 4956, 4941, 4948, -1, 4957, 4936, 4949, -1, 4957, 4942, 4936, -1, 4958, 4945, 4942, -1, 4959, 4947, 4951, -1, 4959, 4955, 4947, -1, 4958, 4942, 4957, -1, 4960, 4944, 4938, -1, 4961, 4946, 4945, -1, 4960, 4938, 4955, -1, 4961, 4945, 4958, -1, 4962, 4950, 4963, -1, 4964, 4960, 4955, -1, 4962, 4949, 4950, -1, 4964, 4955, 4959, -1, 4965, 4948, 4944, -1, 4965, 4943, 4956, -1, 4966, 4967, 4954, -1, 4965, 4944, 4960, -1, 4966, 4953, 4946, -1, 4965, 4956, 4948, -1, 4966, 4954, 4953, -1, 4965, 4968, 4943, -1, 4966, 4946, 4961, -1, 4969, 4957, 4949, -1, 4970, 4951, 4952, -1, 4969, 4949, 4962, -1, 4971, 4960, 4964, -1, 4971, 4965, 4960, -1, 4972, 4952, 4973, -1, 4974, 4958, 4957, -1, 4972, 4970, 4952, -1, 4974, 4957, 4969, -1, 4975, 4951, 4970, -1, 4976, 4961, 4958, -1, 4975, 4959, 4951, -1, 4976, 4958, 4974, -1, 4977, 4963, 4978, -1, 4977, 4962, 4963, -1, 4979, 4968, 4965, -1, 4979, 4965, 4971, -1, 4980, 4981, 4967, -1, 4982, 4975, 4970, -1, 4980, 4967, 4966, -1, 4982, 4970, 4972, -1, 4980, 4966, 4961, -1, 4983, 4964, 4959, -1, 4980, 4961, 4976, -1, 4983, 4959, 4975, -1, 4984, 4962, 4977, -1, 4984, 4969, 4962, -1, 4985, 4983, 4975, -1, 4985, 4975, 4982, -1, 4986, 4969, 4984, -1, 4987, 4971, 4964, -1, 4986, 4974, 4969, -1, 4987, 4968, 4979, -1, 4987, 4988, 4968, -1, 4989, 4976, 4974, -1, 4989, 4974, 4986, -1, 4987, 4964, 4983, -1, 4987, 4979, 4971, -1, 4990, 4972, 4973, -1, 4991, 4978, 4992, -1, 4991, 4977, 4978, -1, 4993, 4983, 4985, -1, 4994, 4980, 4976, -1, 4993, 4987, 4983, -1, 4994, 4976, 4989, -1, 4995, 4973, 4996, -1, 4994, 4997, 4981, -1, 4995, 4990, 4973, -1, 4994, 4981, 4980, -1, 4998, 4972, 4990, -1, 4999, 4977, 4991, -1, 4998, 4982, 4972, -1, 4999, 4984, 4977, -1, 5000, 4986, 4984, -1, 5001, 4988, 4987, -1, 5001, 4987, 4993, -1, 5002, 4990, 4995, -1, 5000, 4984, 4999, -1, 5003, 4986, 5000, -1, 5002, 4998, 4990, -1, 5003, 4989, 4986, -1, 5004, 4985, 4982, -1, 5004, 4982, 4998, -1, 5005, 4992, 5006, -1, 5007, 5004, 4998, -1, 5005, 4991, 4992, -1, 5007, 4998, 5002, -1, 5008, 4997, 4994, -1, 5008, 4989, 5003, -1, 5008, 5009, 4997, -1, 5008, 4994, 4989, -1, 5010, 4985, 5004, -1, 5011, 4999, 4991, -1, 5011, 4991, 5005, -1, 5010, 4993, 4985, -1, 5012, 4995, 4996, -1, 5013, 5000, 4999, -1, 5014, 4988, 5001, -1, 5014, 5001, 4993, -1, 5013, 4999, 5011, -1, 5014, 4993, 5010, -1, 5014, 5015, 4988, -1, 5016, 5004, 5007, -1, 5017, 5003, 5000, -1, 5016, 5010, 5004, -1, 5017, 5000, 5013, -1, 5018, 5006, 5019, -1, 5020, 4995, 5012, -1, 5018, 5005, 5006, -1, 5020, 5002, 4995, -1, 5021, 5008, 5003, -1, 5022, 5010, 5016, -1, 5021, 5009, 5008, -1, 5022, 5014, 5010, -1, 5021, 5003, 5017, -1, 5022, 5015, 5014, -1, 5021, 5023, 5009, -1, 5024, 5007, 5002, -1, 5025, 5011, 5005, -1, 5024, 5002, 5020, -1, 5026, 5016, 5007, -1, 5025, 5005, 5018, -1, 5027, 5013, 5011, -1, 5026, 5007, 5024, -1, 5027, 5011, 5025, -1, 5028, 4996, 5029, -1, 5030, 5017, 5013, -1, 5028, 5012, 4996, -1, 5030, 5013, 5027, -1, 5031, 5016, 5026, -1, 5032, 5019, 5033, -1, 5031, 5022, 5016, -1, 5031, 5015, 5022, -1, 5032, 5018, 5019, -1, 5031, 5026, 5034, -1, 5031, 5034, 5015, -1, 5035, 5020, 5012, -1, 5036, 5021, 5017, -1, 5036, 5023, 5021, -1, 5035, 5012, 5028, -1, 5036, 5037, 5023, -1, 5036, 5017, 5030, -1, 5038, 5024, 5020, -1, 5039, 5025, 5018, -1, 5038, 5020, 5035, -1, 5040, 5026, 5024, -1, 5039, 5018, 5032, -1, 5040, 5034, 5026, -1, 5040, 5024, 5038, -1, 5041, 5027, 5025, -1, 5042, 5029, 5043, -1, 5041, 5025, 5039, -1, 5042, 5028, 5029, -1, 5044, 5030, 5027, -1, 5044, 5027, 5041, -1, 5045, 5034, 5040, -1, 5045, 5040, 5046, -1, 5047, 5033, 5048, -1, 5045, 5046, 5034, -1, 5047, 5032, 5033, -1, 5049, 5028, 5042, -1, 5049, 5035, 5028, -1, 5050, 5051, 5037, -1, 5050, 5030, 5044, -1, 5050, 5037, 5036, -1, 5052, 5035, 5049, -1, 5050, 5036, 5030, -1, 5052, 5038, 5035, -1, 5053, 5047, 5048, -1, 5054, 5039, 5032, -1, 5055, 5038, 5052, -1, 5055, 5040, 5038, -1, 5055, 5046, 5040, -1, 5054, 5032, 5047, -1, 5056, 5043, 5057, -1, 5056, 5042, 5043, -1, 5058, 5047, 5053, -1, 5058, 5054, 5047, -1, 5059, 5046, 5055, -1, 5060, 5041, 5039, -1, 5059, 5055, 5061, -1, 5059, 5061, 5046, -1, 5062, 5042, 5056, -1, 5060, 5039, 5054, -1, 5062, 5049, 5042, -1, 5063, 5054, 5058, -1, 5063, 5060, 5054, -1, 5064, 5049, 5062, -1, 5065, 5044, 5041, -1, 5064, 5052, 5049, -1, 5065, 5041, 5060, -1, 5066, 5048, 5067, -1, 5068, 5052, 5064, -1, 5068, 5055, 5052, -1, 5066, 5053, 5048, -1, 5068, 5061, 5055, -1, 5069, 5070, 5051, -1, 5071, 5057, 5072, -1, 5069, 5044, 5065, -1, 5069, 5051, 5050, -1, 5071, 5056, 5057, -1, 5069, 5050, 5044, -1, 5073, 5074, 5061, -1, 5073, 5061, 5068, -1, 5073, 5068, 5074, -1, 5075, 5060, 5063, -1, 5076, 5056, 5071, -1, 5075, 5065, 5060, -1, 5076, 5062, 5056, -1, 5077, 5066, 5067, -1, 5078, 5053, 5066, -1, 5079, 5064, 5062, -1, 5078, 5058, 5053, -1, 5080, 5069, 5065, -1, 5079, 5062, 5076, -1, 5080, 5081, 5070, -1, 5082, 5064, 5079, -1, 5080, 5065, 5075, -1, 5080, 5070, 5069, -1, 5082, 5068, 5064, -1, 4765, 5066, 5077, -1, 5082, 5074, 5068, -1, 4765, 5078, 5066, -1, 4756, 5072, 5083, -1, 4756, 5071, 5072, -1, 5084, 5058, 5078, -1, 5085, 4753, 5074, -1, 5084, 5063, 5058, -1, 5085, 5082, 4753, -1, 5085, 5074, 5082, -1, 4764, 5084, 5078, -1, 4755, 5071, 4756, -1, 4764, 5078, 4765, -1, 4755, 5076, 5071, -1, 5086, 5075, 5063, -1, 5086, 5063, 5084, -1, 4767, 5076, 4755, -1, 4761, 5067, 4762, -1, 4767, 5079, 5076, -1, 4761, 5077, 5067, -1, 4751, 5079, 4767, -1, 5087, 5081, 5080, -1, 5087, 5080, 5075, -1, 5087, 5075, 5086, -1, 4751, 4753, 5082, -1, 4751, 5082, 5079, -1, 4759, 5088, 4551, -1, 4774, 5084, 4764, -1, 4759, 5083, 5088, -1, 4774, 5081, 5087, -1, 4759, 4551, 4757, -1, 4774, 5087, 5086, -1, 4774, 4781, 5081, -1, 4774, 5086, 5084, -1, 4768, 4765, 5077, -1, 4768, 5077, 4761, -1, 4759, 4756, 5083, -1, 5089, 5090, 5091, -1, 5092, 5093, 4614, -1, 4608, 5094, 4604, -1, 5095, 5094, 4608, -1, 5096, 5097, 5098, -1, 5098, 5097, 5099, -1, 5100, 5101, 5095, -1, 5102, 5101, 5100, -1, 5099, 5103, 5092, -1, 5095, 5104, 5094, -1, 5092, 5103, 5093, -1, 5101, 5104, 5095, -1, 5096, 5105, 5097, -1, 5102, 5106, 5101, -1, 5090, 5105, 5096, -1, 5107, 5106, 5102, -1, 5093, 5108, 4614, -1, 5101, 5109, 5104, -1, 4614, 5108, 4610, -1, 5106, 5109, 5101, -1, 5097, 5110, 5099, -1, 5107, 5111, 5106, -1, 5099, 5110, 5103, -1, 5112, 5111, 5113, -1, 5113, 5111, 5114, -1, 5114, 5111, 5107, -1, 5090, 5115, 5105, -1, 5094, 5116, 4604, -1, 5089, 5115, 5090, -1, 5103, 5117, 5093, -1, 5106, 5118, 5109, -1, 5111, 5118, 5106, -1, 5093, 5117, 5108, -1, 5119, 5120, 5089, -1, 5105, 5120, 5097, -1, 5116, 5121, 4604, -1, 5097, 5120, 5110, -1, 5115, 5120, 5105, -1, 4604, 5121, 4600, -1, 5089, 5120, 5115, -1, 5094, 5122, 5116, -1, 5108, 5123, 4610, -1, 5104, 5122, 5094, -1, 5112, 5124, 5111, -1, 5103, 5125, 5117, -1, 5111, 5124, 5118, -1, 5110, 5125, 5103, -1, 5116, 5126, 5121, -1, 5122, 5126, 5116, -1, 5117, 5127, 5108, -1, 5108, 5127, 5123, -1, 5109, 5128, 5104, -1, 5104, 5128, 5122, -1, 5120, 5129, 5110, -1, 5110, 5129, 5125, -1, 5122, 5130, 5126, -1, 4610, 5131, 4606, -1, 5128, 5130, 5122, -1, 5123, 5131, 4610, -1, 5118, 5132, 5109, -1, 5133, 5132, 5112, -1, 5112, 5132, 5124, -1, 5109, 5132, 5128, -1, 5125, 5134, 5117, -1, 5124, 5132, 5118, -1, 5117, 5134, 5127, -1, 5121, 5135, 4600, -1, 5119, 5136, 5120, -1, 5120, 5136, 5129, -1, 5128, 5137, 5130, -1, 5127, 5138, 5123, -1, 5132, 5137, 5128, -1, 5126, 5139, 5121, -1, 5123, 5138, 5131, -1, 5121, 5139, 5135, -1, 5140, 5141, 5119, -1, 5119, 5141, 5136, -1, 5125, 5141, 5134, -1, 5129, 5141, 5125, -1, 5136, 5141, 5129, -1, 5135, 5142, 4600, -1, 5131, 5143, 4606, -1, 4600, 5142, 4596, -1, 5133, 5144, 5132, -1, 5127, 5145, 5138, -1, 5132, 5144, 5137, -1, 5134, 5145, 5127, -1, 5130, 5146, 5126, -1, 5126, 5146, 5139, -1, 5138, 5147, 5131, -1, 5131, 5147, 5143, -1, 5135, 5148, 5142, -1, 5134, 5149, 5145, -1, 5139, 5148, 5135, -1, 5141, 5149, 5134, -1, 5150, 5151, 5133, -1, 5130, 5151, 5146, -1, 5137, 5151, 5130, -1, 4606, 5152, 4602, -1, 5133, 5151, 5144, -1, 5143, 5152, 4606, -1, 5144, 5151, 5137, -1, 5138, 5153, 5147, -1, 5139, 5154, 5148, -1, 5145, 5153, 5138, -1, 5146, 5154, 5139, -1, 5142, 5155, 4596, -1, 5141, 5156, 5149, -1, 5140, 5156, 5141, -1, 5147, 5157, 5143, -1, 5151, 5158, 5146, -1, 5146, 5158, 5154, -1, 5143, 5157, 5152, -1, 5145, 5159, 5153, -1, 5148, 5160, 5142, -1, 5140, 5159, 5156, -1, 5142, 5160, 5155, -1, 5161, 5159, 5140, -1, 5149, 5159, 5145, -1, 5156, 5159, 5149, -1, 5152, 5162, 4602, -1, 5155, 5163, 4596, -1, 4596, 5163, 4592, -1, 5153, 5164, 5147, -1, 5147, 5164, 5157, -1, 5150, 5165, 5151, -1, 5151, 5165, 5158, -1, 5154, 5166, 5148, -1, 5152, 5167, 5162, -1, 5148, 5166, 5160, -1, 5157, 5167, 5152, -1, 5159, 5168, 5153, -1, 5153, 5168, 5164, -1, 5155, 5169, 5163, -1, 5160, 5169, 5155, -1, 5170, 5171, 5150, -1, 4602, 5172, 4598, -1, 5154, 5171, 5166, -1, 5162, 5172, 4602, -1, 5158, 5171, 5154, -1, 5164, 5173, 5157, -1, 5157, 5173, 5167, -1, 5150, 5171, 5165, -1, 5165, 5171, 5158, -1, 5161, 5174, 5159, -1, 5159, 5174, 5168, -1, 5163, 5175, 4592, -1, 5167, 5176, 5162, -1, 5162, 5176, 5172, -1, 5166, 5177, 5160, -1, 5160, 5177, 5169, -1, 5164, 5178, 5173, -1, 5179, 5178, 5161, -1, 5161, 5178, 5174, -1, 5174, 5178, 5168, -1, 5168, 5178, 5164, -1, 5169, 5180, 5163, -1, 5163, 5180, 5175, -1, 5172, 5181, 4598, -1, 5171, 5182, 5166, -1, 5167, 5183, 5176, -1, 5166, 5182, 5177, -1, 5173, 5183, 5167, -1, 4591, 5184, 5185, -1, 5176, 5186, 5172, -1, 4592, 5184, 4591, -1, 5175, 5184, 4592, -1, 5172, 5186, 5181, -1, 5177, 5187, 5169, -1, 5178, 5188, 5173, -1, 5173, 5188, 5183, -1, 5169, 5187, 5180, -1, 5171, 5189, 5182, -1, 5181, 5190, 4598, -1, 5170, 5189, 5171, -1, 4598, 5190, 4594, -1, 5185, 5191, 5192, -1, 5180, 5191, 5175, -1, 5183, 5193, 5176, -1, 5175, 5191, 5184, -1, 5176, 5193, 5186, -1, 5184, 5191, 5185, -1, 5182, 5194, 5177, -1, 5179, 5195, 5178, -1, 5196, 5194, 5170, -1, 5170, 5194, 5189, -1, 5178, 5195, 5188, -1, 5186, 5197, 5181, -1, 5189, 5194, 5182, -1, 5177, 5194, 5187, -1, 5192, 5198, 5199, -1, 5181, 5197, 5190, -1, 5180, 5198, 5191, -1, 5200, 5201, 5179, -1, 5187, 5198, 5180, -1, 5179, 5201, 5195, -1, 5183, 5201, 5193, -1, 5191, 5198, 5192, -1, 5188, 5201, 5183, -1, 5199, 5202, 5203, -1, 5195, 5201, 5188, -1, 5204, 5202, 5205, -1, 5190, 5206, 4594, -1, 5198, 5202, 5199, -1, 5194, 5202, 5187, -1, 5187, 5202, 5198, -1, 5203, 5202, 5204, -1, 5205, 5207, 5196, -1, 5186, 5208, 5197, -1, 5196, 5207, 5194, -1, 5202, 5207, 5205, -1, 5193, 5208, 5186, -1, 5194, 5207, 5202, -1, 5209, 5210, 5211, -1, 5211, 5210, 5212, -1, 5190, 5213, 5206, -1, 5197, 5213, 5190, -1, 5201, 5214, 5193, -1, 5193, 5214, 5208, -1, 5215, 5216, 5211, -1, 5217, 5218, 5219, -1, 4594, 5220, 4590, -1, 5206, 5220, 4594, -1, 5208, 5221, 5197, -1, 5222, 5223, 5224, -1, 5197, 5221, 5213, -1, 5224, 5223, 5225, -1, 5226, 5223, 5222, -1, 5200, 5227, 5201, -1, 5201, 5227, 5214, -1, 5228, 5229, 5222, -1, 5213, 5230, 5206, -1, 5231, 5229, 5228, -1, 5206, 5230, 5220, -1, 5232, 5233, 5200, -1, 5208, 5233, 5221, -1, 5200, 5233, 5227, -1, 5234, 5235, 5228, -1, 5214, 5233, 5208, -1, 5212, 5236, 5237, -1, 5238, 5236, 5239, -1, 5227, 5233, 5214, -1, 5210, 5236, 5212, -1, 5220, 5240, 4590, -1, 5237, 5236, 5238, -1, 5221, 5241, 5213, -1, 5210, 5242, 5236, -1, 5213, 5241, 5230, -1, 5220, 5243, 5240, -1, 5210, 5244, 5242, -1, 5245, 5244, 5209, -1, 5246, 5244, 5245, -1, 5230, 5243, 5220, -1, 5209, 5244, 5210, -1, 5221, 5247, 5241, -1, 5216, 5248, 5211, -1, 5211, 5248, 5209, -1, 5233, 5247, 5221, -1, 5209, 5248, 5245, -1, 5230, 5249, 5243, -1, 5245, 5248, 5246, -1, 5241, 5249, 5230, -1, 5216, 5250, 5248, -1, 4590, 5251, 4587, -1, 5215, 5252, 5216, -1, 5240, 5251, 4590, -1, 5216, 5252, 5250, -1, 5253, 5252, 5254, -1, 5233, 5255, 5247, -1, 5254, 5252, 5215, -1, 5218, 5256, 5219, -1, 5232, 5255, 5233, -1, 5255, 5257, 5247, -1, 5241, 5257, 5249, -1, 5254, 5256, 5253, -1, 5232, 5257, 5255, -1, 5215, 5256, 5254, -1, 5258, 5257, 5232, -1, 5219, 5256, 5215, -1, 5247, 5257, 5241, -1, 5251, 5259, 4587, -1, 5218, 5260, 5256, -1, 5240, 5261, 5251, -1, 5243, 5261, 5240, -1, 5262, 5263, 5264, -1, 5217, 5263, 5218, -1, 5264, 5263, 5217, -1, 5218, 5263, 5260, -1, 5265, 5266, 5267, -1, 5251, 5268, 5259, -1, 5223, 5266, 5225, -1, 5225, 5266, 5265, -1, 5261, 5268, 5251, -1, 5243, 5269, 5261, -1, 5223, 5270, 5266, -1, 5249, 5269, 5243, -1, 5226, 5271, 5223, -1, 5223, 5271, 5270, -1, 5269, 5272, 5261, -1, 5273, 5271, 5274, -1, 5261, 5272, 5268, -1, 5274, 5271, 5226, -1, 5249, 5275, 5269, -1, 5257, 5275, 5249, -1, 5274, 5276, 5273, -1, 5222, 5276, 5226, -1, 5226, 5276, 5274, -1, 5229, 5276, 5222, -1, 4587, 5277, 4585, -1, 5259, 5277, 4587, -1, 5278, 5279, 5258, -1, 5229, 5280, 5276, -1, 5229, 5281, 5280, -1, 5275, 5279, 5269, -1, 5231, 5281, 5229, -1, 5269, 5279, 5272, -1, 5282, 5281, 5283, -1, 5283, 5281, 5231, -1, 5258, 5284, 5257, -1, 5279, 5284, 5258, -1, 5275, 5284, 5279, -1, 5257, 5284, 5275, -1, 5283, 5285, 5282, -1, 5228, 5285, 5231, -1, 5231, 5285, 5283, -1, 5277, 5286, 4585, -1, 5235, 5285, 5228, -1, 5235, 5287, 5285, -1, 5268, 5288, 5259, -1, 5259, 5288, 5277, -1, 5234, 5289, 5235, -1, 5290, 5289, 5291, -1, 5291, 5289, 5234, -1, 5235, 5289, 5287, -1, 5277, 5292, 5286, -1, 5204, 879, 5203, -1, 5288, 5292, 5277, -1, 5236, 5293, 5239, -1, 5272, 5294, 5268, -1, 5242, 5293, 5236, -1, 5295, 5296, 4669, -1, 5239, 5293, 5297, -1, 5268, 5294, 5288, -1, 4669, 5296, 4665, -1, 5242, 5298, 5293, -1, 5288, 5299, 5292, -1, 5300, 5301, 5295, -1, 5294, 5299, 5288, -1, 5242, 5302, 5298, -1, 5295, 5301, 5296, -1, 5244, 5302, 5242, -1, 5279, 5303, 5272, -1, 5246, 5302, 5244, -1, 5272, 5303, 5294, -1, 5300, 5304, 5301, -1, 5305, 5302, 5246, -1, 5306, 5304, 5300, -1, 5250, 5307, 5248, -1, 5286, 5308, 4585, -1, 5306, 5309, 5304, -1, 5248, 5307, 5246, -1, 5246, 5307, 5305, -1, 4585, 5308, 4670, -1, 5250, 5310, 5307, -1, 5311, 5309, 5306, -1, 5312, 5313, 5278, -1, 5294, 5313, 5299, -1, 5303, 5313, 5294, -1, 5278, 5314, 5279, -1, 4665, 5315, 4662, -1, 5316, 5317, 5253, -1, 5279, 5314, 5303, -1, 5313, 5314, 5278, -1, 5296, 5315, 4665, -1, 5250, 5317, 5310, -1, 5303, 5314, 5313, -1, 5252, 5317, 5250, -1, 5318, 5319, 5320, -1, 5253, 5317, 5252, -1, 5320, 5319, 5311, -1, 5311, 5319, 5309, -1, 5286, 5321, 5308, -1, 5253, 5322, 5316, -1, 5292, 5321, 5286, -1, 5256, 5322, 5253, -1, 5260, 5322, 5256, -1, 5301, 5323, 5296, -1, 5296, 5323, 5315, -1, 5260, 5324, 5322, -1, 5304, 5325, 5301, -1, 5299, 5326, 5292, -1, 5292, 5326, 5321, -1, 5301, 5325, 5323, -1, 5327, 5328, 5262, -1, 5260, 5328, 5324, -1, 5313, 5329, 5299, -1, 5262, 5328, 5263, -1, 5304, 5330, 5325, -1, 5263, 5328, 5260, -1, 5299, 5329, 5326, -1, 5309, 5330, 5304, -1, 5267, 5331, 5332, -1, 5270, 5331, 5266, -1, 5308, 5333, 4670, -1, 5266, 5331, 5267, -1, 4670, 5333, 4666, -1, 5270, 5334, 5331, -1, 5312, 5335, 5313, -1, 5315, 5336, 4662, -1, 5313, 5335, 5329, -1, 4662, 5336, 4658, -1, 5309, 5337, 5330, -1, 5319, 5337, 5309, -1, 5338, 5339, 5273, -1, 5318, 5337, 5319, -1, 5270, 5339, 5334, -1, 5321, 5340, 5308, -1, 5341, 5337, 5318, -1, 5271, 5339, 5270, -1, 5273, 5339, 5271, -1, 5273, 5342, 5338, -1, 5308, 5340, 5333, -1, 5323, 5297, 5315, -1, 5276, 5342, 5273, -1, 5280, 5342, 5276, -1, 5321, 5343, 5340, -1, 5315, 5297, 5336, -1, 5326, 5343, 5321, -1, 5280, 5344, 5342, -1, 5325, 5239, 5323, -1, 5323, 5239, 5297, -1, 5329, 5345, 5326, -1, 5280, 5346, 5344, -1, 5326, 5345, 5343, -1, 5330, 5238, 5325, -1, 5281, 5346, 5280, -1, 5325, 5238, 5239, -1, 5347, 5346, 5282, -1, 4666, 5348, 4660, -1, 5282, 5346, 5281, -1, 5333, 5348, 4666, -1, 5282, 5349, 5347, -1, 5285, 5349, 5282, -1, 5329, 5350, 5345, -1, 5287, 5349, 5285, -1, 5351, 5350, 5312, -1, 5287, 5352, 5349, -1, 5312, 5350, 5335, -1, 5335, 5350, 5329, -1, 5341, 5237, 5337, -1, 5333, 5353, 5348, -1, 5212, 5237, 5341, -1, 5330, 5237, 5238, -1, 5289, 5354, 5287, -1, 5337, 5237, 5330, -1, 5287, 5354, 5352, -1, 5355, 5354, 5290, -1, 5340, 5353, 5333, -1, 5290, 5354, 5289, -1, 5293, 5356, 5297, -1, 5340, 5357, 5353, -1, 5305, 5356, 5302, -1, 4654, 5356, 5358, -1, 5298, 5356, 5293, -1, 5358, 5356, 5305, -1, 5297, 5356, 5336, -1, 5343, 5357, 5340, -1, 5302, 5356, 5298, -1, 5345, 5359, 5343, -1, 4658, 5356, 4654, -1, 5336, 5356, 4658, -1, 5358, 5360, 4654, -1, 5343, 5359, 5357, -1, 5316, 5360, 5317, -1, 5317, 5360, 5310, -1, 5361, 5360, 5316, -1, 4650, 5360, 5361, -1, 5305, 5360, 5358, -1, 5348, 5362, 4660, -1, 5307, 5360, 5305, -1, 4654, 5360, 4650, -1, 5310, 5360, 5307, -1, 5363, 5364, 5327, -1, 4660, 5362, 4656, -1, 5316, 5364, 5361, -1, 5361, 5364, 4650, -1, 5351, 5365, 5350, -1, 5322, 5364, 5316, -1, 5350, 5365, 5345, -1, 5324, 5364, 5322, -1, 5345, 5365, 5359, -1, 5328, 5364, 5324, -1, 4646, 5364, 5363, -1, 4650, 5364, 4646, -1, 5366, 5365, 5351, -1, 5327, 5364, 5328, -1, 5367, 5368, 4628, -1, 5353, 5369, 5348, -1, 5339, 5368, 5334, -1, 5332, 5368, 5367, -1, 5334, 5368, 5331, -1, 4624, 5368, 5370, -1, 5370, 5368, 5338, -1, 5338, 5368, 5339, -1, 5348, 5369, 5362, -1, 5331, 5368, 5332, -1, 5357, 5371, 5353, -1, 4628, 5368, 4624, -1, 5353, 5371, 5369, -1, 5344, 5372, 5342, -1, 5370, 5372, 4624, -1, 5347, 5372, 5346, -1, 5338, 5372, 5370, -1, 4620, 5372, 5373, -1, 5373, 5372, 5347, -1, 5359, 5374, 5357, -1, 5342, 5372, 5338, -1, 4624, 5372, 4620, -1, 5346, 5372, 5344, -1, 5375, 5376, 5355, -1, 5357, 5374, 5371, -1, 5354, 5376, 5352, -1, 5355, 5376, 5354, -1, 5362, 5377, 4656, -1, 5373, 5376, 4620, -1, 5347, 5376, 5373, -1, 5349, 5376, 5347, -1, 4616, 5376, 5375, -1, 4620, 5376, 4616, -1, 4656, 5377, 4652, -1, 5352, 5376, 5349, -1, 5365, 5378, 5359, -1, 5366, 5378, 5365, -1, 5379, 5378, 5366, -1, 5359, 5378, 5374, -1, 5219, 5215, 5211, -1, 5369, 5380, 5362, -1, 5362, 5380, 5377, -1, 5369, 5381, 5380, -1, 5371, 5381, 5369, -1, 5374, 5382, 5371, -1, 5371, 5382, 5381, -1, 5377, 5383, 4652, -1, 4652, 5383, 4648, -1, 5363, 5384, 4646, -1, 4646, 5384, 4642, -1, 5385, 5386, 5379, -1, 5264, 5217, 5387, -1, 5374, 5386, 5382, -1, 5379, 5386, 5378, -1, 5387, 5217, 5219, -1, 5378, 5386, 5374, -1, 5327, 5388, 5363, -1, 5377, 5389, 5383, -1, 5363, 5388, 5384, -1, 5380, 5389, 5377, -1, 5262, 5390, 5327, -1, 5327, 5390, 5388, -1, 5381, 5391, 5380, -1, 5380, 5391, 5389, -1, 5387, 5392, 5264, -1, 5382, 5393, 5381, -1, 5264, 5392, 5262, -1, 5262, 5392, 5390, -1, 5381, 5393, 5391, -1, 5394, 5392, 5387, -1, 5383, 5395, 4648, -1, 4642, 5396, 4638, -1, 4648, 5395, 4644, -1, 5384, 5396, 4642, -1, 5385, 5397, 5386, -1, 4638, 5398, 4634, -1, 5399, 5397, 5385, -1, 5386, 5397, 5382, -1, 5396, 5398, 4638, -1, 5388, 5400, 5384, -1, 5382, 5397, 5393, -1, 5389, 5401, 5383, -1, 5384, 5400, 5396, -1, 5383, 5401, 5395, -1, 5391, 5402, 5389, -1, 5396, 5403, 5398, -1, 5400, 5403, 5396, -1, 5389, 5402, 5401, -1, 5390, 5404, 5388, -1, 5393, 5405, 5391, -1, 5388, 5404, 5400, -1, 5391, 5405, 5402, -1, 5404, 5406, 5400, -1, 5400, 5406, 5403, -1, 5395, 5407, 4644, -1, 4644, 5407, 4640, -1, 5408, 5409, 5394, -1, 5394, 5409, 5392, -1, 5410, 5411, 5399, -1, 5392, 5409, 5390, -1, 5399, 5411, 5397, -1, 5390, 5409, 5404, -1, 5397, 5411, 5393, -1, 5393, 5411, 5405, -1, 5401, 5412, 5395, -1, 5398, 5413, 4634, -1, 5395, 5412, 5407, -1, 5409, 5414, 5404, -1, 5404, 5414, 5406, -1, 5413, 5415, 4634, -1, 5402, 5416, 5401, -1, 5401, 5416, 5412, -1, 4634, 5415, 4630, -1, 5398, 5417, 5413, -1, 5403, 5417, 5398, -1, 5405, 5418, 5402, -1, 5402, 5418, 5416, -1, 5409, 5419, 5414, -1, 5408, 5419, 5409, -1, 5417, 5420, 5413, -1, 5407, 5421, 4640, -1, 5413, 5420, 5415, -1, 4640, 5421, 4636, -1, 5422, 5423, 5410, -1, 5403, 5424, 5417, -1, 5410, 5423, 5411, -1, 5411, 5423, 5405, -1, 5405, 5423, 5418, -1, 5406, 5424, 5403, -1, 5424, 5425, 5417, -1, 5412, 5426, 5407, -1, 5407, 5426, 5421, -1, 5417, 5425, 5420, -1, 5412, 5427, 5426, -1, 5414, 5428, 5406, -1, 5406, 5428, 5424, -1, 5419, 5428, 5414, -1, 5408, 5428, 5419, -1, 5416, 5427, 5412, -1, 5429, 5428, 5408, -1, 5416, 5430, 5427, -1, 5415, 5431, 4630, -1, 5418, 5430, 5416, -1, 5428, 5432, 5424, -1, 5424, 5432, 5425, -1, 4636, 5433, 4632, -1, 5420, 5434, 5415, -1, 5421, 5433, 4636, -1, 5415, 5434, 5431, -1, 5418, 5435, 5430, -1, 5436, 5435, 5422, -1, 5422, 5435, 5423, -1, 5423, 5435, 5418, -1, 5431, 5437, 4630, -1, 5426, 5438, 5421, -1, 5421, 5438, 5433, -1, 4630, 5437, 4626, -1, 5428, 5439, 5432, -1, 5429, 5439, 5428, -1, 5426, 5440, 5438, -1, 5425, 5441, 5420, -1, 5420, 5441, 5434, -1, 5427, 5440, 5426, -1, 5430, 5442, 5427, -1, 5434, 5443, 5431, -1, 5427, 5442, 5440, -1, 5431, 5443, 5437, -1, 5433, 5367, 4632, -1, 5444, 5445, 5429, -1, 5432, 5445, 5425, -1, 5425, 5445, 5441, -1, 4632, 5367, 4628, -1, 5439, 5445, 5432, -1, 5435, 5446, 5430, -1, 5429, 5445, 5439, -1, 5436, 5446, 5435, -1, 5430, 5446, 5442, -1, 5447, 5446, 5436, -1, 5434, 5448, 5443, -1, 5441, 5448, 5434, -1, 5433, 5332, 5367, -1, 5437, 5449, 4626, -1, 5438, 5332, 5433, -1, 5440, 5267, 5438, -1, 5438, 5267, 5332, -1, 5445, 5450, 5441, -1, 5441, 5450, 5448, -1, 5443, 5451, 5437, -1, 5442, 5265, 5440, -1, 5437, 5451, 5449, -1, 5440, 5265, 5267, -1, 5449, 5452, 4626, -1, 4626, 5452, 4622, -1, 5444, 5453, 5445, -1, 5224, 5225, 5447, -1, 5445, 5453, 5450, -1, 5446, 5225, 5442, -1, 5447, 5225, 5446, -1, 5442, 5225, 5265, -1, 5443, 5454, 5451, -1, 5448, 5454, 5443, -1, 5449, 5455, 5452, -1, 5451, 5455, 5449, -1, 5456, 5457, 5444, -1, 5444, 5457, 5453, -1, 5450, 5457, 5448, -1, 5453, 5457, 5450, -1, 5448, 5457, 5454, -1, 5452, 5458, 4622, -1, 5454, 5459, 5451, -1, 5451, 5459, 5455, -1, 5455, 5460, 5452, -1, 5452, 5460, 5458, -1, 5457, 5461, 5454, -1, 5454, 5461, 5459, -1, 4622, 5462, 4618, -1, 5458, 5462, 4622, -1, 5459, 5463, 5455, -1, 5455, 5463, 5460, -1, 5456, 5464, 5457, -1, 5457, 5464, 5461, -1, 5458, 5465, 5462, -1, 5460, 5465, 5458, -1, 5461, 5466, 5459, -1, 5456, 5466, 5464, -1, 5464, 5466, 5461, -1, 5091, 5466, 5456, -1, 5459, 5466, 5463, -1, 5462, 5467, 4618, -1, 5463, 5468, 5460, -1, 5460, 5468, 5465, -1, 5462, 5098, 5467, -1, 5465, 5098, 5462, -1, 5375, 5100, 4616, -1, 5466, 5469, 5463, -1, 5463, 5469, 5468, -1, 4616, 5100, 4612, -1, 5470, 5234, 5228, -1, 5291, 5234, 5470, -1, 5355, 5102, 5375, -1, 5467, 5092, 4618, -1, 4618, 5092, 4614, -1, 5375, 5102, 5100, -1, 5468, 5096, 5465, -1, 5465, 5096, 5098, -1, 5355, 5107, 5102, -1, 5091, 5471, 5466, -1, 5466, 5471, 5469, -1, 5290, 5107, 5355, -1, 5098, 5099, 5467, -1, 5113, 5114, 5470, -1, 5467, 5099, 5092, -1, 5470, 5114, 5291, -1, 5291, 5114, 5290, -1, 5290, 5114, 5107, -1, 5469, 5090, 5468, -1, 5100, 5095, 4612, -1, 5468, 5090, 5096, -1, 4612, 5095, 4608, -1, 5091, 5090, 5471, -1, 5471, 5090, 5469, -1, 5472, 5473, 5474, -1, 4926, 5473, 4914, -1, 5475, 5473, 4926, -1, 5474, 5473, 5475, -1, 5473, 5476, 4914, -1, 5477, 5476, 5478, -1, 4900, 5476, 4887, -1, 4914, 5476, 4900, -1, 890, 5479, 888, -1, 894, 5480, 892, -1, 892, 5480, 890, -1, 5476, 5480, 4887, -1, 5477, 5480, 5476, -1, 4887, 5480, 894, -1, 5479, 5480, 5477, -1, 890, 5480, 5479, -1, 5479, 886, 888, -1, 4776, 5481, 5482, -1, 5320, 5481, 4855, -1, 4855, 5481, 4776, -1, 5483, 5484, 5320, -1, 5479, 885, 886, -1, 5481, 5484, 5482, -1, 5320, 5484, 5481, -1, 5482, 5484, 5483, -1, 5485, 5486, 5487, -1, 5488, 5486, 5485, -1, 5479, 883, 885, -1, 5489, 5486, 5488, -1, 5487, 5486, 5489, -1, 5490, 5491, 5492, -1, 5493, 5491, 5494, -1, 5492, 5491, 5493, -1, 5494, 5491, 5490, -1, 5495, 5496, 5497, -1, 5479, 882, 883, -1, 5498, 5496, 5495, -1, 5499, 5496, 5498, -1, 5497, 5496, 5499, -1, 5500, 5501, 5502, -1, 5503, 5482, 5483, -1, 5502, 5501, 5504, -1, 5504, 5501, 5505, -1, 4776, 5482, 4752, -1, 5505, 5501, 5500, -1, 5506, 5507, 5508, -1, 5487, 5489, 5503, -1, 5508, 5507, 5509, -1, 5510, 5507, 5506, -1, 5509, 5507, 5510, -1, 5482, 5489, 4752, -1, 5511, 5512, 5513, -1, 5503, 5489, 5482, -1, 5513, 5512, 5514, -1, 5515, 5512, 5511, -1, 4752, 5489, 4753, -1, 5514, 5512, 5515, -1, 5472, 5516, 5473, -1, 5517, 5488, 5485, -1, 5476, 5516, 5478, -1, 5489, 5488, 4753, -1, 5478, 5516, 5472, -1, 5473, 5516, 5476, -1, 5074, 5488, 5061, -1, 4753, 5488, 5074, -1, 5518, 5519, 5517, -1, 5517, 5519, 5488, -1, 5488, 5519, 5061, -1, 5061, 5519, 5046, -1, 5520, 5521, 5518, -1, 5522, 5521, 5520, -1, 5518, 5521, 5519, -1, 5519, 5521, 5046, -1, 5046, 5521, 5034, -1, 5521, 5523, 5034, -1, 5524, 5523, 5522, -1, 5015, 5523, 4988, -1, 5034, 5523, 5015, -1, 5522, 5523, 5521, -1, 5524, 5493, 5523, -1, 5492, 5493, 5524, -1, 5523, 5493, 4988, -1, 4988, 5493, 4968, -1, 5525, 5494, 5490, -1, 5493, 5494, 4968, -1, 4968, 5494, 4943, -1, 5494, 5497, 4943, -1, 5495, 5497, 5525, -1, 5525, 5497, 5494, -1, 4919, 5497, 4895, -1, 4943, 5497, 4919, -1, 5526, 5499, 5498, -1, 4895, 5499, 4875, -1, 5497, 5499, 4895, -1, 5527, 5528, 5526, -1, 5499, 5528, 4875, -1, 4875, 5528, 4852, -1, 5526, 5528, 5499, -1, 5529, 5530, 5527, -1, 5531, 5530, 5529, -1, 5528, 5530, 4852, -1, 5527, 5530, 5528, -1, 4841, 5530, 4830, -1, 4852, 5530, 4841, -1, 5530, 5532, 4830, -1, 5531, 5532, 5530, -1, 5533, 5532, 5531, -1, 4830, 5532, 4819, -1, 5502, 5504, 5533, -1, 5532, 5504, 4819, -1, 4819, 5504, 4808, -1, 5533, 5504, 5532, -1, 5534, 5505, 5500, -1, 4797, 5505, 4785, -1, 4808, 5505, 4797, -1, 5504, 5505, 4808, -1, 5505, 5535, 4785, -1, 5536, 5535, 5534, -1, 5534, 5535, 5505, -1, 4785, 5535, 4781, -1, 5536, 5537, 5535, -1, 5535, 5537, 4781, -1, 5538, 5537, 5536, -1, 5539, 5537, 5538, -1, 4781, 5537, 5081, -1, 5539, 5540, 5537, -1, 5537, 5540, 5081, -1, 5541, 5540, 5539, -1, 5070, 5540, 5051, -1, 5081, 5540, 5070, -1, 5540, 5509, 5051, -1, 5508, 5509, 5541, -1, 5051, 5509, 5037, -1, 5541, 5509, 5540, -1, 5509, 5510, 5037, -1, 5542, 5510, 5506, -1, 5037, 5510, 5023, -1, 5542, 5514, 5510, -1, 5513, 5514, 5542, -1, 5009, 5514, 4997, -1, 5023, 5514, 5009, -1, 5510, 5514, 5023, -1, 5543, 5515, 5511, -1, 5514, 5515, 4997, -1, 4997, 5515, 4981, -1, 5544, 5545, 5543, -1, 5515, 5545, 4981, -1, 4887, 896, 898, -1, 4981, 5545, 4967, -1, 5543, 5545, 5515, -1, 5546, 5547, 5544, -1, 5548, 5547, 5546, -1, 4887, 894, 896, -1, 4954, 5547, 4940, -1, 4967, 5547, 4954, -1, 5544, 5547, 5545, -1, 5545, 5547, 4967, -1, 5474, 5475, 5548, -1, 4940, 5475, 4926, -1, 5547, 5475, 4940, -1, 5548, 5475, 5547, -1, 5549, 815, 811, -1, 5550, 5551, 5552, -1, 5550, 5552, 5553, -1, 5554, 5551, 5550, -1, 5554, 5549, 5551, -1, 5554, 815, 5549, -1, 5555, 5550, 5553, -1, 5556, 5553, 5557, -1, 5556, 5555, 5553, -1, 5558, 5550, 5555, -1, 5558, 5554, 5550, -1, 5558, 815, 5554, -1, 5558, 819, 815, -1, 5559, 5558, 5555, -1, 5559, 5555, 5556, -1, 5559, 819, 5558, -1, 5560, 5556, 5557, -1, 5561, 5557, 5562, -1, 5561, 5560, 5557, -1, 5563, 823, 819, -1, 5563, 5559, 5556, -1, 5563, 819, 5559, -1, 5563, 5556, 5560, -1, 5564, 823, 5563, -1, 5564, 5560, 5561, -1, 5564, 5563, 5560, -1, 5565, 5561, 5562, -1, 5566, 5562, 5567, -1, 5566, 5565, 5562, -1, 5568, 823, 5564, -1, 5568, 5561, 5565, -1, 5568, 827, 823, -1, 5568, 5564, 5561, -1, 5569, 5568, 5565, -1, 5569, 827, 5568, -1, 5569, 5565, 5566, -1, 5570, 5566, 5567, -1, 5571, 5567, 5572, -1, 5571, 5570, 5567, -1, 5573, 5569, 5566, -1, 5573, 827, 5569, -1, 5573, 5566, 5570, -1, 5573, 831, 827, -1, 5574, 831, 5573, -1, 5574, 5573, 5570, -1, 5574, 5570, 5571, -1, 5575, 5571, 5572, -1, 5576, 5572, 5577, -1, 5576, 5575, 5572, -1, 5578, 5571, 5575, -1, 5578, 831, 5574, -1, 5578, 5574, 5571, -1, 5578, 835, 831, -1, 5579, 5578, 5575, -1, 5579, 835, 5578, -1, 5579, 5575, 5576, -1, 5580, 5576, 5577, -1, 5581, 5579, 5576, -1, 5581, 5576, 5580, -1, 5581, 835, 5579, -1, 5581, 839, 835, -1, 5582, 5577, 5583, -1, 5582, 5580, 5577, -1, 5584, 5581, 5580, -1, 5584, 839, 5581, -1, 5584, 5580, 5582, -1, 5584, 843, 839, -1, 5585, 5583, 5586, -1, 5585, 5582, 5583, -1, 5587, 843, 5584, -1, 5587, 5584, 5582, -1, 5587, 5582, 5585, -1, 5587, 847, 843, -1, 5588, 5586, 5589, -1, 5588, 5585, 5586, -1, 5590, 5587, 5585, -1, 5590, 847, 5587, -1, 5590, 5585, 5588, -1, 5590, 756, 847, -1, 5591, 5589, 5592, -1, 5591, 5588, 5589, -1, 5593, 5590, 5588, -1, 5593, 756, 5590, -1, 5593, 5588, 5591, -1, 5593, 757, 756, -1, 5594, 5592, 5595, -1, 5594, 5591, 5592, -1, 5596, 5593, 5591, -1, 5596, 757, 5593, -1, 5596, 5591, 5594, -1, 5596, 763, 757, -1, 5597, 5595, 5598, -1, 5597, 5594, 5595, -1, 5599, 5596, 5594, -1, 5599, 763, 5596, -1, 5599, 5594, 5597, -1, 5599, 771, 763, -1, 5600, 5598, 5601, -1, 5600, 5597, 5598, -1, 5602, 5599, 5597, -1, 5602, 5597, 5600, -1, 5602, 771, 5599, -1, 5602, 777, 771, -1, 5603, 5601, 5604, -1, 5603, 5600, 5601, -1, 5605, 5602, 5600, -1, 5605, 5600, 5603, -1, 5605, 777, 5602, -1, 5605, 783, 777, -1, 5606, 5604, 5607, -1, 5606, 5603, 5604, -1, 5608, 5603, 5606, -1, 5608, 5605, 5603, -1, 5608, 783, 5605, -1, 5608, 789, 783, -1, 5609, 5606, 5607, -1, 5609, 5607, 5610, -1, 5609, 5610, 4381, -1, 5609, 4381, 5611, -1, 5612, 5611, 5613, -1, 5612, 5609, 5611, -1, 5612, 5608, 5606, -1, 5612, 795, 789, -1, 5612, 5606, 5609, -1, 5612, 5613, 795, -1, 5612, 789, 5608, -1, 798, 795, 5613, -1, 5614, 4368, 5615, -1, 5614, 5616, 4368, -1, 5617, 5616, 5614, -1, 5617, 768, 767, -1, 5617, 5618, 5616, -1, 5617, 767, 5618, -1, 5619, 5615, 5620, -1, 5619, 5614, 5615, -1, 5621, 5617, 5614, -1, 5621, 768, 5617, -1, 5621, 775, 768, -1, 5621, 5614, 5619, -1, 5622, 5620, 5623, -1, 5622, 5619, 5620, -1, 5624, 5621, 5619, -1, 5624, 5619, 5622, -1, 5624, 781, 775, -1, 5624, 775, 5621, -1, 5625, 5623, 5626, -1, 5625, 5622, 5623, -1, 5627, 5624, 5622, -1, 5627, 787, 781, -1, 5627, 781, 5624, -1, 5627, 5622, 5625, -1, 5628, 5626, 5629, -1, 5628, 5625, 5626, -1, 5630, 787, 5627, -1, 5630, 5627, 5625, -1, 5630, 5625, 5628, -1, 5630, 793, 787, -1, 5631, 5629, 5632, -1, 5631, 5628, 5629, -1, 5633, 801, 793, -1, 5633, 5630, 5628, -1, 5633, 793, 5630, -1, 5633, 5628, 5631, -1, 5634, 5632, 5635, -1, 5634, 5631, 5632, -1, 5636, 801, 5633, -1, 5636, 5633, 5631, -1, 5636, 5631, 5634, -1, 5636, 805, 801, -1, 5637, 5635, 5638, -1, 5637, 5634, 5635, -1, 5639, 5634, 5637, -1, 5639, 809, 805, -1, 5639, 5636, 5634, -1, 5639, 805, 5636, -1, 5640, 5638, 5641, -1, 5640, 5637, 5638, -1, 5642, 5639, 5637, -1, 5642, 809, 5639, -1, 5642, 813, 809, -1, 5642, 5637, 5640, -1, 5643, 5641, 5644, -1, 5643, 5640, 5641, -1, 5645, 5642, 5640, -1, 5645, 813, 5642, -1, 5645, 5640, 5643, -1, 5645, 817, 813, -1, 5646, 5644, 5647, -1, 5646, 5643, 5644, -1, 5648, 817, 5645, -1, 5648, 5645, 5643, -1, 5648, 821, 817, -1, 5648, 5643, 5646, -1, 5649, 5647, 5650, -1, 5649, 5646, 5647, -1, 5651, 5649, 5650, -1, 5652, 5648, 5646, -1, 5652, 5646, 5649, -1, 5652, 821, 5648, -1, 5652, 825, 821, -1, 5653, 825, 5652, -1, 5653, 5652, 5649, -1, 5653, 829, 825, -1, 5653, 5649, 5651, -1, 5654, 5651, 5650, -1, 5654, 5650, 5655, -1, 5656, 5654, 5655, -1, 5657, 5653, 5651, -1, 5657, 829, 5653, -1, 5657, 5651, 5654, -1, 5658, 5657, 5654, -1, 5658, 833, 829, -1, 5658, 5654, 5656, -1, 5658, 829, 5657, -1, 5659, 5655, 5660, -1, 5659, 5656, 5655, -1, 5661, 5659, 5660, -1, 5662, 5658, 5656, -1, 5662, 5656, 5659, -1, 5662, 833, 5658, -1, 5663, 833, 5662, -1, 5663, 5662, 5659, -1, 5663, 837, 833, -1, 5663, 5659, 5661, -1, 5664, 5660, 5665, -1, 5664, 5661, 5660, -1, 5666, 5664, 5665, -1, 5667, 5663, 5661, -1, 5667, 837, 5663, -1, 5667, 5661, 5664, -1, 5668, 837, 5667, -1, 5668, 5667, 5664, -1, 5668, 841, 837, -1, 5668, 5664, 5666, -1, 5669, 5665, 5670, -1, 5669, 5666, 5665, -1, 5671, 5669, 5670, -1, 5672, 5666, 5669, -1, 5672, 841, 5668, -1, 5672, 5668, 5666, -1, 5673, 5669, 5671, -1, 5673, 841, 5672, -1, 5673, 845, 841, -1, 5673, 5672, 5669, -1, 5674, 5671, 5670, -1, 5674, 5670, 5675, -1, 5676, 845, 5673, -1, 5676, 5673, 5671, -1, 5676, 5671, 5674, -1, 5677, 5674, 5675, -1, 5678, 845, 5676, -1, 5678, 5676, 5674, -1, 5678, 5674, 5677, -1, 5678, 754, 845, -1, 5679, 5675, 5680, -1, 5679, 5677, 5675, -1, 5681, 5678, 5677, -1, 5681, 754, 5678, -1, 5681, 5677, 5679, -1, 5682, 5679, 5680, -1, 5683, 754, 5681, -1, 5683, 5681, 5679, -1, 5683, 5679, 5682, -1, 5683, 760, 754, -1, 5684, 5680, 5685, -1, 5684, 5682, 5680, -1, 5686, 5683, 5682, -1, 5686, 760, 5683, -1, 5686, 5682, 5684, -1, 5687, 5684, 5685, -1, 5688, 760, 5686, -1, 5688, 5686, 5684, -1, 5688, 5684, 5687, -1, 5688, 761, 760, -1, 5689, 5685, 5690, -1, 5689, 5687, 5685, -1, 5691, 5688, 5687, -1, 5691, 761, 5688, -1, 5691, 5687, 5689, -1, 5692, 5689, 5690, -1, 5693, 761, 5691, -1, 5693, 5691, 5689, -1, 5693, 5689, 5692, -1, 5693, 765, 761, -1, 5694, 5690, 5695, -1, 5694, 5692, 5690, -1, 5696, 5693, 5692, -1, 5696, 765, 5693, -1, 5696, 5692, 5694, -1, 5697, 5694, 5695, -1, 5698, 765, 5696, -1, 5698, 5696, 5694, -1, 5698, 773, 765, -1, 5698, 5694, 5697, -1, 5699, 5695, 5700, -1, 5699, 5697, 5695, -1, 5701, 773, 5698, -1, 5701, 5698, 5697, -1, 5701, 5697, 5699, -1, 5702, 5699, 5700, -1, 5703, 773, 5701, -1, 5703, 779, 773, -1, 5703, 5701, 5699, -1, 5703, 5699, 5702, -1, 5704, 5702, 5700, -1, 5704, 5700, 5705, -1, 5706, 5702, 5704, -1, 5706, 779, 5703, -1, 5706, 5703, 5702, -1, 5707, 5704, 5705, -1, 5708, 785, 779, -1, 5708, 5704, 5707, -1, 5708, 5706, 5704, -1, 5708, 779, 5706, -1, 5709, 5705, 5710, -1, 5709, 5707, 5705, -1, 5711, 5708, 5707, -1, 5711, 5707, 5709, -1, 5711, 785, 5708, -1, 5712, 5709, 5710, -1, 5713, 5709, 5712, -1, 5713, 785, 5711, -1, 5713, 791, 785, -1, 5713, 5711, 5709, -1, 5714, 5712, 5710, -1, 5714, 5710, 5715, -1, 5716, 5713, 5712, -1, 5716, 5712, 5714, -1, 5716, 791, 5713, -1, 5717, 5714, 5715, -1, 5718, 5716, 5714, -1, 5718, 5714, 5717, -1, 5718, 791, 5716, -1, 5718, 799, 791, -1, 5719, 5717, 5715, -1, 5719, 5715, 5720, -1, 5721, 5717, 5719, -1, 5721, 5718, 5717, -1, 5721, 799, 5718, -1, 5722, 5719, 5720, -1, 5723, 5721, 5719, -1, 5723, 799, 5721, -1, 5723, 5719, 5722, -1, 5723, 803, 799, -1, 5724, 5720, 5725, -1, 5724, 5722, 5720, -1, 5726, 803, 5723, -1, 5726, 5723, 5722, -1, 5726, 5722, 5724, -1, 5727, 5724, 5725, -1, 5728, 5726, 5724, -1, 5728, 803, 5726, -1, 5728, 5724, 5727, -1, 5728, 807, 803, -1, 5729, 5725, 5730, -1, 5729, 5727, 5725, -1, 5731, 5728, 5727, -1, 5731, 807, 5728, -1, 5731, 5727, 5729, -1, 5732, 5729, 5730, -1, 5733, 5731, 5729, -1, 5733, 807, 5731, -1, 5733, 5729, 5732, -1, 5733, 811, 807, -1, 5734, 5730, 5552, -1, 5734, 5732, 5730, -1, 5735, 811, 5733, -1, 5735, 5733, 5732, -1, 5735, 5732, 5734, -1, 5551, 5734, 5552, -1, 5549, 5735, 5734, -1, 5549, 5734, 5551, -1, 5549, 811, 5735, -1, 5736, 5737, 814, -1, 5738, 5739, 5737, -1, 5738, 5740, 5739, -1, 5738, 5737, 5736, -1, 5738, 5741, 5740, -1, 5742, 814, 818, -1, 5742, 5736, 814, -1, 5743, 5742, 818, -1, 5744, 5738, 5736, -1, 5744, 5741, 5738, -1, 5744, 5736, 5742, -1, 5745, 5741, 5744, -1, 5745, 5746, 5741, -1, 5745, 5742, 5743, -1, 5745, 5744, 5742, -1, 5747, 818, 822, -1, 5747, 5743, 818, -1, 5748, 5747, 822, -1, 5749, 5743, 5747, -1, 5749, 5746, 5745, -1, 5749, 5745, 5743, -1, 5750, 5751, 5746, -1, 5750, 5749, 5747, -1, 5750, 5747, 5748, -1, 5750, 5746, 5749, -1, 5752, 822, 826, -1, 5752, 5748, 822, -1, 5753, 5752, 826, -1, 5754, 5750, 5748, -1, 5754, 5748, 5752, -1, 5754, 5751, 5750, -1, 5755, 5752, 5753, -1, 5755, 5751, 5754, -1, 5755, 5756, 5751, -1, 5755, 5754, 5752, -1, 5757, 826, 830, -1, 5757, 5753, 826, -1, 5758, 5757, 830, -1, 5759, 5753, 5757, -1, 5759, 5755, 5753, -1, 5759, 5756, 5755, -1, 5760, 5757, 5758, -1, 5760, 5756, 5759, -1, 5760, 5759, 5757, -1, 5760, 5761, 5756, -1, 5762, 830, 834, -1, 5762, 5758, 830, -1, 5763, 5762, 834, -1, 5764, 5760, 5758, -1, 5764, 5761, 5760, -1, 5764, 5758, 5762, -1, 5765, 5761, 5764, -1, 5765, 5762, 5763, -1, 5765, 5764, 5762, -1, 5765, 5766, 5761, -1, 5767, 834, 838, -1, 5767, 5763, 834, -1, 5768, 5765, 5763, -1, 5768, 5766, 5765, -1, 5768, 5763, 5767, -1, 5769, 838, 842, -1, 5769, 5767, 838, -1, 5770, 5766, 5768, -1, 5770, 5768, 5767, -1, 5770, 5767, 5769, -1, 5770, 5771, 5766, -1, 5772, 842, 846, -1, 5772, 5769, 842, -1, 5773, 5770, 5769, -1, 5773, 5771, 5770, -1, 5773, 5769, 5772, -1, 5773, 5774, 5771, -1, 5775, 846, 758, -1, 5775, 5772, 846, -1, 5776, 5773, 5772, -1, 5776, 5774, 5773, -1, 5776, 5772, 5775, -1, 5776, 5777, 5774, -1, 5778, 758, 755, -1, 5778, 5775, 758, -1, 5779, 5776, 5775, -1, 5779, 5777, 5776, -1, 5779, 5775, 5778, -1, 5779, 5780, 5777, -1, 5781, 755, 762, -1, 5781, 5778, 755, -1, 5782, 5779, 5778, -1, 5782, 5780, 5779, -1, 5782, 5778, 5781, -1, 5782, 5783, 5780, -1, 5784, 762, 770, -1, 5784, 5781, 762, -1, 5785, 5782, 5781, -1, 5785, 5783, 5782, -1, 5785, 5781, 5784, -1, 5785, 5786, 5783, -1, 5787, 770, 776, -1, 5787, 5784, 770, -1, 5788, 5785, 5784, -1, 5788, 5786, 5785, -1, 5788, 5784, 5787, -1, 5788, 5789, 5786, -1, 5790, 776, 782, -1, 5790, 5787, 776, -1, 5791, 5788, 5787, -1, 5791, 5789, 5788, -1, 5791, 5787, 5790, -1, 5791, 5792, 5789, -1, 5793, 782, 788, -1, 5793, 5790, 782, -1, 5794, 5791, 5790, -1, 5794, 5792, 5791, -1, 5794, 5790, 5793, -1, 5794, 5795, 5792, -1, 5796, 788, 794, -1, 5796, 5793, 788, -1, 5796, 794, 5797, -1, 5798, 5797, 5799, -1, 5798, 5796, 5797, -1, 5798, 5800, 5795, -1, 5798, 5799, 5800, -1, 5798, 5794, 5793, -1, 5798, 5795, 5794, -1, 5798, 5793, 5796, -1, 5797, 794, 797, -1, 4320, 5800, 5799, -1, 5801, 769, 766, -1, 5801, 5802, 769, -1, 5803, 5804, 4321, -1, 5803, 5802, 5801, -1, 5803, 5805, 5802, -1, 5803, 4321, 5805, -1, 5806, 766, 774, -1, 5806, 5801, 766, -1, 5807, 5801, 5806, -1, 5807, 5803, 5801, -1, 5807, 5804, 5803, -1, 5807, 5808, 5804, -1, 5809, 5806, 774, -1, 5809, 774, 780, -1, 5810, 5811, 5808, -1, 5810, 5806, 5809, -1, 5810, 5808, 5807, -1, 5810, 5807, 5806, -1, 5812, 780, 786, -1, 5812, 5809, 780, -1, 5813, 5809, 5812, -1, 5813, 5810, 5809, -1, 5813, 5811, 5810, -1, 5813, 5814, 5811, -1, 5815, 786, 792, -1, 5815, 5812, 786, -1, 5816, 5813, 5812, -1, 5816, 5814, 5813, -1, 5816, 5812, 5815, -1, 5816, 5817, 5814, -1, 5818, 792, 800, -1, 5818, 5815, 792, -1, 5819, 5817, 5816, -1, 5819, 5815, 5818, -1, 5819, 5820, 5817, -1, 5819, 5816, 5815, -1, 5821, 5818, 800, -1, 5821, 800, 804, -1, 5822, 5819, 5818, -1, 5822, 5823, 5820, -1, 5822, 5820, 5819, -1, 5822, 5818, 5821, -1, 5824, 804, 808, -1, 5824, 5821, 804, -1, 5825, 5823, 5822, -1, 5825, 5822, 5821, -1, 5825, 5826, 5823, -1, 5825, 5821, 5824, -1, 5827, 808, 812, -1, 5827, 5824, 808, -1, 5828, 5825, 5824, -1, 5828, 5829, 5826, -1, 5828, 5826, 5825, -1, 5828, 5824, 5827, -1, 5830, 5827, 812, -1, 5830, 812, 816, -1, 5831, 5829, 5828, -1, 5831, 5828, 5827, -1, 5831, 5827, 5830, -1, 5831, 5832, 5829, -1, 5833, 816, 820, -1, 5833, 5830, 816, -1, 5834, 5831, 5830, -1, 5834, 5832, 5831, -1, 5834, 5830, 5833, -1, 5834, 5835, 5832, -1, 5836, 820, 824, -1, 5836, 5833, 820, -1, 5837, 5836, 824, -1, 5837, 824, 828, -1, 5838, 5835, 5834, -1, 5838, 5834, 5833, -1, 5838, 5833, 5836, -1, 5838, 5839, 5835, -1, 5840, 5839, 5838, -1, 5840, 5836, 5837, -1, 5840, 5838, 5836, -1, 5841, 5837, 828, -1, 5842, 5841, 828, -1, 5842, 828, 832, -1, 5843, 5840, 5837, -1, 5843, 5839, 5840, -1, 5843, 5837, 5841, -1, 5843, 5844, 5839, -1, 5845, 5841, 5842, -1, 5845, 5843, 5841, -1, 5845, 5844, 5843, -1, 5846, 5842, 832, -1, 5847, 5846, 832, -1, 5847, 832, 836, -1, 5848, 5842, 5846, -1, 5848, 5844, 5845, -1, 5848, 5849, 5844, -1, 5848, 5845, 5842, -1, 5850, 5848, 5846, -1, 5850, 5849, 5848, -1, 5850, 5846, 5847, -1, 5851, 5847, 836, -1, 5852, 836, 840, -1, 5852, 5851, 836, -1, 5853, 5850, 5847, -1, 5853, 5847, 5851, -1, 5853, 5854, 5849, -1, 5853, 5849, 5850, -1, 5855, 5853, 5851, -1, 5855, 5854, 5853, -1, 5855, 5851, 5852, -1, 5856, 5852, 840, -1, 5857, 5856, 840, -1, 5857, 840, 844, -1, 5858, 5855, 5852, -1, 5858, 5852, 5856, -1, 5858, 5859, 5854, -1, 5858, 5854, 5855, -1, 5860, 5858, 5856, -1, 5860, 5859, 5858, -1, 5860, 5856, 5857, -1, 5861, 5857, 844, -1, 5862, 5860, 5857, -1, 5862, 5857, 5861, -1, 5862, 5859, 5860, -1, 5862, 5863, 5859, -1, 5864, 844, 753, -1, 5864, 5861, 844, -1, 5865, 5861, 5864, -1, 5865, 5862, 5861, -1, 5865, 5863, 5862, -1, 5866, 5864, 753, -1, 5867, 5863, 5865, -1, 5867, 5864, 5866, -1, 5867, 5868, 5863, -1, 5867, 5865, 5864, -1, 5869, 753, 752, -1, 5869, 5866, 753, -1, 5870, 5867, 5866, -1, 5870, 5868, 5867, -1, 5870, 5866, 5869, -1, 5871, 5869, 752, -1, 5872, 5870, 5869, -1, 5872, 5868, 5870, -1, 5872, 5873, 5868, -1, 5872, 5869, 5871, -1, 5874, 752, 759, -1, 5874, 5871, 752, -1, 5875, 5872, 5871, -1, 5875, 5873, 5872, -1, 5875, 5871, 5874, -1, 5876, 5874, 759, -1, 5877, 5875, 5874, -1, 5877, 5873, 5875, -1, 5877, 5878, 5873, -1, 5877, 5874, 5876, -1, 5879, 759, 764, -1, 5879, 5876, 759, -1, 5880, 5877, 5876, -1, 5880, 5878, 5877, -1, 5880, 5876, 5879, -1, 5881, 5879, 764, -1, 5882, 5880, 5879, -1, 5882, 5878, 5880, -1, 5882, 5883, 5878, -1, 5882, 5879, 5881, -1, 5884, 764, 772, -1, 5884, 5881, 764, -1, 5885, 5882, 5881, -1, 5885, 5883, 5882, -1, 5885, 5881, 5884, -1, 5886, 5884, 772, -1, 5887, 5888, 5883, -1, 5887, 5885, 5884, -1, 5887, 5883, 5885, -1, 5887, 5884, 5886, -1, 5889, 772, 778, -1, 5889, 5886, 772, -1, 5890, 5888, 5887, -1, 5890, 5887, 5886, -1, 5890, 5886, 5889, -1, 5891, 5889, 778, -1, 5892, 5893, 5888, -1, 5892, 5888, 5890, -1, 5892, 5890, 5889, -1, 5892, 5889, 5891, -1, 5894, 5891, 778, -1, 5894, 778, 784, -1, 5895, 5891, 5894, -1, 5895, 5893, 5892, -1, 5895, 5892, 5891, -1, 5896, 5894, 784, -1, 5897, 5898, 5893, -1, 5897, 5894, 5896, -1, 5897, 5895, 5894, -1, 5897, 5893, 5895, -1, 5899, 784, 790, -1, 5899, 5896, 784, -1, 5900, 5897, 5896, -1, 5900, 5898, 5897, -1, 5900, 5896, 5899, -1, 5901, 5899, 790, -1, 5902, 5898, 5900, -1, 5902, 5899, 5901, -1, 5902, 5900, 5899, -1, 5902, 5903, 5898, -1, 5904, 5901, 790, -1, 5904, 790, 796, -1, 5905, 5901, 5904, -1, 5905, 5902, 5901, -1, 5905, 5903, 5902, -1, 5906, 5904, 796, -1, 5907, 5904, 5906, -1, 5907, 5905, 5904, -1, 5907, 5903, 5905, -1, 5907, 5908, 5903, -1, 5909, 796, 802, -1, 5909, 5906, 796, -1, 5910, 5907, 5906, -1, 5910, 5908, 5907, -1, 5910, 5906, 5909, -1, 5911, 5909, 802, -1, 5912, 5910, 5909, -1, 5912, 5909, 5911, -1, 5912, 5908, 5910, -1, 5912, 5913, 5908, -1, 5914, 802, 806, -1, 5914, 5911, 802, -1, 5915, 5912, 5911, -1, 5915, 5913, 5912, -1, 5915, 5911, 5914, -1, 5916, 5914, 806, -1, 5917, 5914, 5916, -1, 5917, 5915, 5914, -1, 5917, 5913, 5915, -1, 5917, 5918, 5913, -1, 5919, 5916, 806, -1, 5919, 806, 810, -1, 5920, 5916, 5919, -1, 5920, 5917, 5916, -1, 5920, 5918, 5917, -1, 5921, 5919, 810, -1, 5922, 5919, 5921, -1, 5922, 5920, 5919, -1, 5922, 5918, 5920, -1, 5922, 5740, 5918, -1, 5737, 810, 814, -1, 5737, 5921, 810, -1, 5739, 5922, 5921, -1, 5739, 5740, 5922, -1, 5739, 5921, 5737, -1, 5923, 5924, 5925, -1, 5926, 5927, 5924, -1, 5926, 4334, 5927, -1, 5926, 5924, 5923, -1, 5926, 4336, 4334, -1, 5928, 5925, 5929, -1, 5928, 5923, 5925, -1, 5930, 5928, 5929, -1, 5931, 5926, 5923, -1, 5931, 4336, 5926, -1, 5931, 5923, 5928, -1, 5932, 4336, 5931, -1, 5932, 5928, 5930, -1, 5932, 4338, 4336, -1, 5932, 5931, 5928, -1, 5933, 5929, 5934, -1, 5933, 5930, 5929, -1, 5935, 5933, 5934, -1, 5936, 5930, 5933, -1, 5936, 5932, 5930, -1, 5936, 4338, 5932, -1, 5937, 4340, 4338, -1, 5937, 5936, 5933, -1, 5937, 5933, 5935, -1, 5937, 4338, 5936, -1, 5938, 5934, 5939, -1, 5938, 5935, 5934, -1, 5940, 5938, 5939, -1, 5941, 5937, 5935, -1, 5941, 5935, 5938, -1, 5941, 4340, 5937, -1, 5942, 5938, 5940, -1, 5942, 4340, 5941, -1, 5942, 4342, 4340, -1, 5942, 5941, 5938, -1, 5943, 5939, 5944, -1, 5943, 5940, 5939, -1, 5945, 5943, 5944, -1, 5946, 5940, 5943, -1, 5946, 5942, 5940, -1, 5946, 4342, 5942, -1, 5947, 5943, 5945, -1, 5947, 4342, 5946, -1, 5947, 5946, 5943, -1, 5947, 4344, 4342, -1, 5948, 5944, 5949, -1, 5948, 5945, 5944, -1, 5950, 5948, 5949, -1, 5951, 5947, 5945, -1, 5951, 4344, 5947, -1, 5951, 5945, 5948, -1, 5952, 4344, 5951, -1, 5952, 5948, 5950, -1, 5952, 5951, 5948, -1, 5952, 4346, 4344, -1, 5953, 5949, 5954, -1, 5953, 5950, 5949, -1, 5955, 5952, 5950, -1, 5955, 4346, 5952, -1, 5955, 5950, 5953, -1, 5956, 5954, 5957, -1, 5956, 5953, 5954, -1, 5958, 4346, 5955, -1, 5958, 5955, 5953, -1, 5958, 5953, 5956, -1, 5958, 4348, 4346, -1, 5959, 5957, 5960, -1, 5959, 5956, 5957, -1, 5961, 5958, 5956, -1, 5961, 4348, 5958, -1, 5961, 5956, 5959, -1, 5961, 4350, 4348, -1, 5962, 5960, 5963, -1, 5962, 5959, 5960, -1, 5964, 5961, 5959, -1, 5964, 4350, 5961, -1, 5964, 5959, 5962, -1, 5964, 4352, 4350, -1, 5965, 5963, 5966, -1, 5965, 5962, 5963, -1, 5967, 5964, 5962, -1, 5967, 4352, 5964, -1, 5967, 5962, 5965, -1, 5967, 4354, 4352, -1, 5968, 5966, 5969, -1, 5968, 5965, 5966, -1, 5970, 5967, 5965, -1, 5970, 4354, 5967, -1, 5970, 5965, 5968, -1, 5970, 4356, 4354, -1, 5971, 5969, 5972, -1, 5971, 5968, 5969, -1, 5973, 5970, 5968, -1, 5973, 4356, 5970, -1, 5973, 5968, 5971, -1, 5973, 4358, 4356, -1, 5974, 5972, 5975, -1, 5974, 5971, 5972, -1, 5976, 5973, 5971, -1, 5976, 4358, 5973, -1, 5976, 5971, 5974, -1, 5976, 4360, 4358, -1, 5977, 5975, 5978, -1, 5977, 5974, 5975, -1, 5979, 5976, 5974, -1, 5979, 4360, 5976, -1, 5979, 5974, 5977, -1, 5979, 4317, 4360, -1, 5980, 5978, 5981, -1, 5980, 5977, 5978, -1, 5982, 5979, 5977, -1, 5982, 4317, 5979, -1, 5982, 5977, 5980, -1, 5982, 4316, 4317, -1, 5983, 5981, 5984, -1, 5983, 5980, 5981, -1, 5983, 5984, 5802, -1, 5985, 5802, 5805, -1, 5985, 5805, 4321, -1, 5985, 5983, 5802, -1, 5985, 5982, 5980, -1, 5985, 4316, 5982, -1, 5985, 4319, 4316, -1, 5985, 4321, 4319, -1, 5985, 5980, 5983, -1, 5802, 5984, 769, -1, 5986, 5797, 797, -1, 5986, 797, 5987, -1, 5988, 5799, 5797, -1, 5988, 4320, 5799, -1, 5988, 5797, 5986, -1, 5988, 4323, 4320, -1, 5989, 5987, 5990, -1, 5989, 5986, 5987, -1, 5991, 5986, 5989, -1, 5991, 4323, 5988, -1, 5991, 4325, 4323, -1, 5991, 5988, 5986, -1, 5992, 5989, 5990, -1, 5992, 5990, 5993, -1, 5994, 5991, 5989, -1, 5994, 4327, 4325, -1, 5994, 5989, 5992, -1, 5994, 4325, 5991, -1, 5995, 5993, 5996, -1, 5995, 5992, 5993, -1, 5997, 5992, 5995, -1, 5997, 5994, 5992, -1, 5997, 4327, 5994, -1, 5997, 4329, 4327, -1, 5998, 5995, 5996, -1, 5998, 5996, 5999, -1, 6000, 4329, 5997, -1, 6000, 5995, 5998, -1, 6000, 4331, 4329, -1, 6000, 5997, 5995, -1, 6001, 5999, 6002, -1, 6001, 5998, 5999, -1, 6003, 5998, 6001, -1, 6003, 4333, 4331, -1, 6003, 6000, 5998, -1, 6003, 4331, 6000, -1, 6004, 6001, 6002, -1, 6004, 6002, 6005, -1, 6006, 6003, 6001, -1, 6006, 4333, 6003, -1, 6006, 6001, 6004, -1, 6006, 4335, 4333, -1, 6007, 6005, 6008, -1, 6007, 6004, 6005, -1, 6009, 6006, 6004, -1, 6009, 4335, 6006, -1, 6009, 4337, 4335, -1, 6009, 6004, 6007, -1, 6010, 6008, 6011, -1, 6010, 6007, 6008, -1, 6012, 6009, 6007, -1, 6012, 4337, 6009, -1, 6012, 4339, 4337, -1, 6012, 6007, 6010, -1, 6013, 6010, 6011, -1, 6013, 6011, 6014, -1, 6015, 4339, 6012, -1, 6015, 6012, 6010, -1, 6015, 6010, 6013, -1, 6015, 4341, 4339, -1, 6016, 6014, 6017, -1, 6016, 6013, 6014, -1, 6018, 6015, 6013, -1, 6018, 6013, 6016, -1, 6018, 4343, 4341, -1, 6018, 4341, 6015, -1, 6019, 6016, 6017, -1, 6019, 6017, 6020, -1, 6021, 6019, 6020, -1, 6021, 6020, 6022, -1, 6023, 6016, 6019, -1, 6023, 4343, 6018, -1, 6023, 6018, 6016, -1, 6023, 4345, 4343, -1, 6024, 4345, 6023, -1, 6024, 6023, 6019, -1, 6024, 6019, 6021, -1, 6025, 6021, 6022, -1, 6026, 6025, 6022, -1, 6026, 6022, 6027, -1, 6028, 4345, 6024, -1, 6028, 6021, 6025, -1, 6028, 4347, 4345, -1, 6028, 6024, 6021, -1, 6029, 6028, 6025, -1, 6029, 6025, 6026, -1, 6029, 4347, 6028, -1, 6030, 6026, 6027, -1, 6031, 6027, 6032, -1, 6031, 6030, 6027, -1, 6033, 6026, 6030, -1, 6033, 6029, 6026, -1, 6033, 4347, 6029, -1, 6033, 4349, 4347, -1, 6034, 6033, 6030, -1, 6034, 6030, 6031, -1, 6034, 4349, 6033, -1, 6035, 6031, 6032, -1, 6036, 6032, 6037, -1, 6036, 6035, 6032, -1, 6038, 4349, 6034, -1, 6038, 6034, 6031, -1, 6038, 4351, 4349, -1, 6038, 6031, 6035, -1, 6039, 4351, 6038, -1, 6039, 6038, 6035, -1, 6039, 6035, 6036, -1, 6040, 6036, 6037, -1, 6041, 6040, 6037, -1, 6041, 6037, 6042, -1, 6043, 6039, 6036, -1, 6043, 6036, 6040, -1, 6043, 4351, 6039, -1, 6043, 4353, 4351, -1, 6044, 6043, 6040, -1, 6044, 4353, 6043, -1, 6044, 6040, 6041, -1, 6045, 6041, 6042, -1, 6046, 6044, 6041, -1, 6046, 6041, 6045, -1, 6046, 4353, 6044, -1, 6046, 4355, 4353, -1, 6047, 6042, 6048, -1, 6047, 6045, 6042, -1, 6049, 6045, 6047, -1, 6049, 6046, 6045, -1, 6049, 4355, 6046, -1, 6050, 6047, 6048, -1, 6051, 4355, 6049, -1, 6051, 6047, 6050, -1, 6051, 4357, 4355, -1, 6051, 6049, 6047, -1, 6052, 6050, 6048, -1, 6052, 6048, 6053, -1, 6054, 6050, 6052, -1, 6054, 6051, 6050, -1, 6054, 4357, 6051, -1, 6055, 6052, 6053, -1, 6056, 6054, 6052, -1, 6056, 4357, 6054, -1, 6056, 6052, 6055, -1, 6056, 4359, 4357, -1, 6057, 6053, 6058, -1, 6057, 6055, 6053, -1, 6059, 6056, 6055, -1, 6059, 4359, 6056, -1, 6059, 6055, 6057, -1, 6060, 6057, 6058, -1, 6061, 6059, 6057, -1, 6061, 4359, 6059, -1, 6061, 4315, 4359, -1, 6061, 6057, 6060, -1, 6062, 6058, 6063, -1, 6062, 6060, 6058, -1, 6064, 6061, 6060, -1, 6064, 4315, 6061, -1, 6064, 6060, 6062, -1, 6065, 6062, 6063, -1, 6066, 6064, 6062, -1, 6066, 4315, 6064, -1, 6066, 4314, 4315, -1, 6066, 6062, 6065, -1, 6067, 6063, 6068, -1, 6067, 6065, 6063, -1, 6069, 6066, 6065, -1, 6069, 4314, 6066, -1, 6069, 6065, 6067, -1, 6070, 6067, 6068, -1, 6071, 6069, 6067, -1, 6071, 4318, 4314, -1, 6071, 4314, 6069, -1, 6071, 6067, 6070, -1, 6072, 6068, 6073, -1, 6072, 6070, 6068, -1, 6074, 4318, 6071, -1, 6074, 6071, 6070, -1, 6074, 6070, 6072, -1, 6075, 6072, 6073, -1, 6076, 4318, 6074, -1, 6076, 4322, 4318, -1, 6076, 6074, 6072, -1, 6076, 6072, 6075, -1, 6077, 6075, 6073, -1, 6077, 6073, 6078, -1, 6079, 6075, 6077, -1, 6079, 4322, 6076, -1, 6079, 6076, 6075, -1, 6080, 6077, 6078, -1, 6081, 4324, 4322, -1, 6081, 6077, 6080, -1, 6081, 6079, 6077, -1, 6081, 4322, 6079, -1, 6082, 6078, 6083, -1, 6082, 6080, 6078, -1, 6084, 6081, 6080, -1, 6084, 4324, 6081, -1, 6084, 6080, 6082, -1, 6085, 6082, 6083, -1, 6086, 4324, 6084, -1, 6086, 6082, 6085, -1, 6086, 6084, 6082, -1, 6086, 4326, 4324, -1, 6087, 6085, 6083, -1, 6087, 6083, 6088, -1, 6089, 6085, 6087, -1, 6089, 6086, 6085, -1, 6089, 4326, 6086, -1, 6090, 6087, 6088, -1, 6091, 6087, 6090, -1, 6091, 6089, 6087, -1, 6091, 4326, 6089, -1, 6091, 4328, 4326, -1, 6092, 6090, 6088, -1, 6092, 6088, 6093, -1, 6094, 6090, 6092, -1, 6094, 6091, 6090, -1, 6094, 4328, 6091, -1, 6095, 6092, 6093, -1, 6096, 6094, 6092, -1, 6096, 4328, 6094, -1, 6096, 6092, 6095, -1, 6096, 4330, 4328, -1, 6097, 6095, 6093, -1, 6097, 6093, 6098, -1, 6099, 6095, 6097, -1, 6099, 4330, 6096, -1, 6099, 6096, 6095, -1, 6100, 6097, 6098, -1, 6101, 6099, 6097, -1, 6101, 6097, 6100, -1, 6101, 4330, 6099, -1, 6101, 4332, 4330, -1, 6102, 6098, 6103, -1, 6102, 6100, 6098, -1, 6104, 6101, 6100, -1, 6104, 4332, 6101, -1, 6104, 6100, 6102, -1, 6105, 6102, 6103, -1, 6106, 6102, 6105, -1, 6106, 6104, 6102, -1, 6106, 4332, 6104, -1, 6106, 4334, 4332, -1, 5924, 6103, 5925, -1, 5924, 6105, 6103, -1, 5927, 6105, 5924, -1, 5927, 6106, 6105, -1, 5927, 4334, 6106, -1, 6107, 6108, 6109, -1, 6110, 6111, 4406, -1, 6110, 4406, 4404, -1, 6112, 6111, 6110, -1, 6112, 6107, 6111, -1, 6112, 6108, 6107, -1, 6113, 6110, 4404, -1, 6114, 6113, 4404, -1, 6114, 4404, 4402, -1, 6115, 6110, 6113, -1, 6115, 6112, 6110, -1, 6115, 6108, 6112, -1, 6115, 6116, 6108, -1, 6117, 6113, 6114, -1, 6117, 6115, 6113, -1, 6118, 798, 5613, -1, 6117, 6116, 6115, -1, 6119, 6114, 4402, -1, 6120, 4402, 4400, -1, 6120, 6119, 4402, -1, 6121, 6122, 6116, -1, 6121, 6117, 6114, -1, 6121, 6116, 6117, -1, 6121, 6114, 6119, -1, 6123, 6122, 6121, -1, 6123, 6119, 6120, -1, 6123, 6121, 6119, -1, 6124, 6120, 4400, -1, 6125, 4400, 4398, -1, 6125, 6124, 4400, -1, 6126, 6122, 6123, -1, 6126, 6120, 6124, -1, 6126, 6127, 6122, -1, 6126, 6123, 6120, -1, 6128, 6126, 6124, -1, 6128, 6127, 6126, -1, 6128, 6124, 6125, -1, 6129, 6125, 4398, -1, 6130, 4398, 4396, -1, 6130, 6129, 4398, -1, 6131, 6128, 6125, -1, 6131, 6127, 6128, -1, 6131, 6125, 6129, -1, 6131, 6132, 6127, -1, 6133, 6132, 6131, -1, 6133, 6131, 6129, -1, 6133, 6129, 6130, -1, 6134, 6130, 4396, -1, 6135, 4396, 4394, -1, 6135, 6134, 4396, -1, 6136, 6130, 6134, -1, 6136, 6132, 6133, -1, 6136, 6133, 6130, -1, 6136, 6137, 6132, -1, 6138, 6136, 6134, -1, 6138, 6137, 6136, -1, 6138, 6134, 6135, -1, 6139, 6135, 4394, -1, 6140, 6138, 6135, -1, 6140, 6135, 6139, -1, 6140, 6137, 6138, -1, 6140, 6141, 6137, -1, 6142, 4394, 4392, -1, 6142, 6139, 4394, -1, 6143, 6140, 6139, -1, 6143, 6139, 6142, -1, 6143, 6141, 6140, -1, 6143, 6144, 6141, -1, 6145, 4392, 4390, -1, 6145, 6142, 4392, -1, 6146, 6144, 6143, -1, 6146, 6142, 6145, -1, 6146, 6143, 6142, -1, 6146, 6147, 6144, -1, 6148, 4390, 4388, -1, 6148, 6145, 4390, -1, 6149, 6146, 6145, -1, 6149, 6147, 6146, -1, 6149, 6145, 6148, -1, 6149, 6150, 6147, -1, 6151, 4388, 4386, -1, 6151, 6148, 4388, -1, 6152, 6149, 6148, -1, 6152, 6150, 6149, -1, 6152, 6148, 6151, -1, 6152, 6153, 6150, -1, 6154, 4386, 4384, -1, 6154, 6151, 4386, -1, 6155, 6152, 6151, -1, 6155, 6153, 6152, -1, 6155, 6151, 6154, -1, 6155, 6156, 6153, -1, 6157, 4384, 4382, -1, 6157, 6154, 4384, -1, 6158, 6155, 6154, -1, 6158, 6156, 6155, -1, 6158, 6154, 6157, -1, 6158, 6159, 6156, -1, 6160, 4382, 4378, -1, 6160, 6157, 4382, -1, 6161, 6158, 6157, -1, 6161, 6157, 6160, -1, 6161, 6159, 6158, -1, 6161, 6162, 6159, -1, 6163, 4378, 4375, -1, 6163, 6160, 4378, -1, 6164, 6161, 6160, -1, 6164, 6160, 6163, -1, 6164, 6162, 6161, -1, 6164, 6165, 6162, -1, 6166, 4375, 4371, -1, 6166, 6163, 4375, -1, 6167, 6163, 6166, -1, 6167, 6164, 6163, -1, 6167, 6165, 6164, -1, 6167, 6168, 6165, -1, 6169, 6166, 4371, -1, 6169, 4371, 4369, -1, 6169, 4369, 4368, -1, 6169, 4368, 5616, -1, 6170, 5616, 5618, -1, 6170, 6169, 5616, -1, 6170, 6167, 6166, -1, 6170, 6166, 6169, -1, 6170, 5618, 6171, -1, 6170, 6168, 6167, -1, 6170, 6171, 6168, -1, 767, 6171, 5618, -1, 6172, 5611, 4381, -1, 6172, 4381, 4379, -1, 6173, 5613, 5611, -1, 6173, 5611, 6172, -1, 6173, 6118, 5613, -1, 6174, 6172, 4379, -1, 6174, 4379, 4376, -1, 6175, 6173, 6172, -1, 6175, 6118, 6173, -1, 6175, 6172, 6174, -1, 6175, 6176, 6118, -1, 6177, 4376, 4373, -1, 6177, 6174, 4376, -1, 6178, 6174, 6177, -1, 6178, 6179, 6176, -1, 6178, 6175, 6174, -1, 6178, 6176, 6175, -1, 6180, 4373, 4370, -1, 6180, 6177, 4373, -1, 6181, 6178, 6177, -1, 6181, 6179, 6178, -1, 6181, 6182, 6179, -1, 6181, 6177, 6180, -1, 6183, 4370, 4366, -1, 6183, 6180, 4370, -1, 6184, 6181, 6180, -1, 6184, 6180, 6183, -1, 6184, 6185, 6182, -1, 6184, 6182, 6181, -1, 6186, 4366, 4364, -1, 6186, 6183, 4366, -1, 6187, 6184, 6183, -1, 6187, 6188, 6185, -1, 6187, 6185, 6184, -1, 6187, 6183, 6186, -1, 6189, 4364, 4361, -1, 6189, 6186, 4364, -1, 6190, 6188, 6187, -1, 6190, 6187, 6186, -1, 6190, 6186, 6189, -1, 6190, 6191, 6188, -1, 6192, 4361, 4407, -1, 6192, 6189, 4361, -1, 6193, 6190, 6189, -1, 6193, 6194, 6191, -1, 6193, 6191, 6190, -1, 6193, 6189, 6192, -1, 6195, 4407, 4405, -1, 6195, 6192, 4407, -1, 6196, 6194, 6193, -1, 6196, 6192, 6195, -1, 6196, 6197, 6194, -1, 6196, 6193, 6192, -1, 6198, 6195, 4405, -1, 6198, 4405, 4403, -1, 6199, 6197, 6196, -1, 6199, 6196, 6195, -1, 6199, 6200, 6197, -1, 6199, 6195, 6198, -1, 6201, 4403, 4401, -1, 6201, 6198, 4403, -1, 6202, 6200, 6199, -1, 6202, 6199, 6198, -1, 6202, 6203, 6200, -1, 6202, 6198, 6201, -1, 6204, 4401, 4399, -1, 6204, 6201, 4401, -1, 6205, 6204, 4399, -1, 6206, 6201, 6204, -1, 6206, 6203, 6202, -1, 6206, 6202, 6201, -1, 6206, 6207, 6203, -1, 6208, 6206, 6204, -1, 6208, 6207, 6206, -1, 6208, 6209, 6207, -1, 6208, 6204, 6205, -1, 6210, 4399, 4397, -1, 6210, 6205, 4399, -1, 6211, 6210, 4397, -1, 6212, 6209, 6208, -1, 6212, 6205, 6210, -1, 6212, 6208, 6205, -1, 6213, 6212, 6210, -1, 6213, 6210, 6211, -1, 6213, 6209, 6212, -1, 6213, 6214, 6209, -1, 6215, 4397, 4395, -1, 6215, 6211, 4397, -1, 6216, 6215, 4395, -1, 6217, 6211, 6215, -1, 6217, 6214, 6213, -1, 6217, 6213, 6211, -1, 6218, 6215, 6216, -1, 6218, 6219, 6214, -1, 6218, 6214, 6217, -1, 6218, 6217, 6215, -1, 6220, 4395, 4393, -1, 6220, 6216, 4395, -1, 6221, 6220, 4393, -1, 6222, 6219, 6218, -1, 6222, 6216, 6220, -1, 6222, 6218, 6216, -1, 6223, 6219, 6222, -1, 6223, 6222, 6220, -1, 6223, 6224, 6219, -1, 6223, 6220, 6221, -1, 6225, 4393, 4391, -1, 6225, 6221, 4393, -1, 6226, 6225, 4391, -1, 6227, 6224, 6223, -1, 6227, 6223, 6221, -1, 6227, 6221, 6225, -1, 6228, 6225, 6226, -1, 6228, 6224, 6227, -1, 6228, 6227, 6225, -1, 6228, 6229, 6224, -1, 6230, 4391, 4389, -1, 6230, 6226, 4391, -1, 6231, 6226, 6230, -1, 6231, 6228, 6226, -1, 6231, 6229, 6228, -1, 6232, 6230, 4389, -1, 6233, 6229, 6231, -1, 6233, 6230, 6232, -1, 6233, 6234, 6229, -1, 6233, 6231, 6230, -1, 6235, 4389, 4387, -1, 6235, 6232, 4389, -1, 6236, 6233, 6232, -1, 6236, 6234, 6233, -1, 6236, 6232, 6235, -1, 6237, 6235, 4387, -1, 6238, 6236, 6235, -1, 6238, 6234, 6236, -1, 6238, 6235, 6237, -1, 6238, 6239, 6234, -1, 6240, 4387, 4385, -1, 6240, 6237, 4387, -1, 6241, 6238, 6237, -1, 6241, 6239, 6238, -1, 6241, 6237, 6240, -1, 6242, 6240, 4385, -1, 6243, 6239, 6241, -1, 6243, 6241, 6240, -1, 6243, 6240, 6242, -1, 6243, 6244, 6239, -1, 6245, 4385, 4383, -1, 6245, 6242, 4385, -1, 6246, 6243, 6242, -1, 6246, 6244, 6243, -1, 6246, 6242, 6245, -1, 6247, 6245, 4383, -1, 6248, 6244, 6246, -1, 6248, 6246, 6245, -1, 6248, 6245, 6247, -1, 6248, 6249, 6244, -1, 6250, 4383, 4380, -1, 6250, 6247, 4383, -1, 6251, 6248, 6247, -1, 6251, 6249, 6248, -1, 6251, 6247, 6250, -1, 6252, 6250, 4380, -1, 6253, 6249, 6251, -1, 6253, 6251, 6250, -1, 6253, 6250, 6252, -1, 6253, 6254, 6249, -1, 6255, 4380, 4377, -1, 6255, 6252, 4380, -1, 6256, 6253, 6252, -1, 6256, 6254, 6253, -1, 6256, 6252, 6255, -1, 6257, 6255, 4377, -1, 6258, 6256, 6255, -1, 6258, 6259, 6254, -1, 6258, 6254, 6256, -1, 6258, 6255, 6257, -1, 6260, 6257, 4377, -1, 6260, 4377, 4374, -1, 6261, 6257, 6260, -1, 6261, 6259, 6258, -1, 6261, 6258, 6257, -1, 6262, 6260, 4374, -1, 6263, 6264, 6259, -1, 6263, 6260, 6262, -1, 6263, 6261, 6260, -1, 6263, 6259, 6261, -1, 6265, 4374, 4372, -1, 6265, 6262, 4374, -1, 6266, 6263, 6262, -1, 6266, 6262, 6265, -1, 6266, 6264, 6263, -1, 6267, 6265, 4372, -1, 6268, 6265, 6267, -1, 6268, 6264, 6266, -1, 6268, 6269, 6264, -1, 6268, 6266, 6265, -1, 6270, 6267, 4372, -1, 6270, 4372, 4367, -1, 6271, 6268, 6267, -1, 6271, 6267, 6270, -1, 6271, 6269, 6268, -1, 6272, 6270, 4367, -1, 6273, 6271, 6270, -1, 6273, 6270, 6272, -1, 6273, 6269, 6271, -1, 6273, 6274, 6269, -1, 6275, 6272, 4367, -1, 6275, 4367, 4365, -1, 6276, 6272, 6275, -1, 6276, 6273, 6272, -1, 6276, 6274, 6273, -1, 6277, 6275, 4365, -1, 6278, 6276, 6275, -1, 6278, 6274, 6276, -1, 6278, 6275, 6277, -1, 6278, 6279, 6274, -1, 6280, 4365, 4363, -1, 6280, 6277, 4365, -1, 6281, 6279, 6278, -1, 6281, 6278, 6277, -1, 6281, 6277, 6280, -1, 6282, 6280, 4363, -1, 6283, 6281, 6280, -1, 6283, 6279, 6281, -1, 6283, 6280, 6282, -1, 6283, 6284, 6279, -1, 6285, 4363, 4362, -1, 6285, 6282, 4363, -1, 6286, 6283, 6282, -1, 6286, 6284, 6283, -1, 6286, 6282, 6285, -1, 6287, 6285, 4362, -1, 6288, 6286, 6285, -1, 6288, 6284, 6286, -1, 6288, 6285, 6287, -1, 6288, 6109, 6284, -1, 6289, 4362, 4406, -1, 6289, 6287, 4362, -1, 6290, 6109, 6288, -1, 6290, 6288, 6287, -1, 6290, 6287, 6289, -1, 6111, 6289, 4406, -1, 6107, 6290, 6289, -1, 6107, 6289, 6111, -1, 6107, 6109, 6290, -1, 5408, 6291, 6292, -1, 6292, 6291, 6293, -1, 6291, 6294, 6295, -1, 5387, 6294, 6291, -1, 5219, 6294, 5387, -1, 6295, 6294, 6296, -1, 5219, 6297, 6294, -1, 6294, 6297, 6296, -1, 5211, 6297, 5219, -1, 6298, 6297, 6299, -1, 6296, 6297, 6298, -1, 6297, 6300, 6299, -1, 5341, 6300, 5212, -1, 6299, 6300, 6301, -1, 6300, 6302, 6301, -1, 5318, 6302, 5341, -1, 6301, 6302, 6303, -1, 5341, 6302, 6300, -1, 6304, 6305, 6306, -1, 5112, 6307, 5133, -1, 6306, 6305, 6308, -1, 5133, 6307, 6309, -1, 6308, 6305, 6310, -1, 6311, 6307, 5112, -1, 6309, 6307, 6311, -1, 5436, 6312, 5447, -1, 5447, 6312, 6313, -1, 6313, 6312, 6314, -1, 6314, 6312, 5436, -1, 6315, 6316, 5399, -1, 5399, 6316, 5410, -1, 5410, 6316, 6317, -1, 6317, 6316, 6315, -1, 5278, 6318, 6319, -1, 5258, 6318, 5278, -1, 6320, 6318, 5258, -1, 6319, 6318, 6320, -1, 5089, 6321, 5119, -1, 5119, 6321, 6322, -1, 6323, 6321, 5089, -1, 5150, 6324, 5170, -1, 6322, 6321, 6323, -1, 5170, 6324, 6325, -1, 6326, 6327, 6328, -1, 5444, 6327, 5456, -1, 6325, 6324, 6329, -1, 6328, 6327, 5444, -1, 6329, 6324, 6330, -1, 5456, 6327, 6326, -1, 6330, 6324, 6304, -1, 5211, 6331, 6297, -1, 6300, 6331, 5212, -1, 6304, 6324, 6305, -1, 5212, 6331, 5211, -1, 5133, 6309, 5150, -1, 6297, 6331, 6300, -1, 5150, 6309, 6324, -1, 6302, 6332, 6303, -1, 6303, 6332, 4855, -1, 6324, 6309, 6305, -1, 6333, 6309, 6334, -1, 6305, 6309, 6333, -1, 5320, 6335, 5318, -1, 5113, 6311, 5112, -1, 6302, 6335, 6332, -1, 6332, 6335, 4855, -1, 4855, 6335, 5320, -1, 6309, 6311, 6334, -1, 5318, 6335, 6302, -1, 6334, 6311, 6336, -1, 5470, 6337, 5113, -1, 5196, 5170, 6338, -1, 6338, 5170, 6339, -1, 5113, 6337, 6311, -1, 6339, 5170, 6325, -1, 6311, 6337, 6336, -1, 6336, 6337, 6340, -1, 5228, 6341, 5470, -1, 5222, 6341, 5228, -1, 6337, 6341, 6340, -1, 6342, 6341, 6343, -1, 6340, 6341, 6342, -1, 5470, 6341, 6337, -1, 5224, 6344, 5222, -1, 5222, 6344, 6341, -1, 6341, 6344, 6343, -1, 6343, 6344, 6345, -1, 5447, 6313, 5224, -1, 5224, 6313, 6344, -1, 6344, 6313, 6345, -1, 6345, 6313, 6346, -1, 5422, 6314, 5436, -1, 6347, 6314, 6348, -1, 6346, 6314, 6347, -1, 6313, 6314, 6346, -1, 5410, 6317, 5422, -1, 6314, 6317, 6348, -1, 5422, 6317, 6314, -1, 6348, 6317, 6349, -1, 5385, 6315, 5399, -1, 6317, 6315, 6349, -1, 6349, 6315, 6350, -1, 5385, 6351, 6315, -1, 5379, 6351, 5385, -1, 6352, 6351, 6353, -1, 6350, 6351, 6352, -1, 6315, 6351, 6350, -1, 5366, 6354, 5379, -1, 5351, 6354, 5366, -1, 6351, 6354, 6353, -1, 5379, 6354, 6351, -1, 6353, 6354, 6355, -1, 5312, 6356, 5351, -1, 6354, 6356, 6355, -1, 5351, 6356, 6354, -1, 6355, 6356, 6357, -1, 5278, 6319, 5312, -1, 5312, 6319, 6356, -1, 6356, 6319, 6357, -1, 6358, 6319, 6359, -1, 6357, 6319, 6358, -1, 5232, 6320, 5258, -1, 6359, 6320, 6360, -1, 6319, 6320, 6359, -1, 5200, 6361, 5232, -1, 6360, 6361, 6362, -1, 5232, 6361, 6320, -1, 6320, 6361, 6360, -1, 6361, 6363, 6362, -1, 5179, 6363, 5200, -1, 5161, 6363, 5179, -1, 6364, 6363, 6365, -1, 6362, 6363, 6364, -1, 5200, 6363, 6361, -1, 5140, 6366, 5161, -1, 5161, 6366, 6363, -1, 6363, 6366, 6365, -1, 6365, 6366, 6367, -1, 6366, 6322, 6367, -1, 5119, 6322, 5140, -1, 5140, 6322, 6366, -1, 6367, 6322, 6368, -1, 5091, 6323, 5089, -1, 6322, 6323, 6368, -1, 6369, 6323, 6370, -1, 6368, 6323, 6369, -1, 5456, 6326, 5091, -1, 6370, 6326, 6371, -1, 5091, 6326, 6323, -1, 6323, 6326, 6370, -1, 5429, 6328, 5444, -1, 6371, 6328, 6372, -1, 6326, 6328, 6371, -1, 5408, 6292, 5429, -1, 6373, 6292, 6293, -1, 6372, 6292, 6373, -1, 6328, 6292, 6372, -1, 5429, 6292, 6328, -1, 5394, 6291, 5408, -1, 5387, 6291, 5394, -1, 6293, 6291, 6295, -1, 6374, 6375, 6376, -1, 6377, 6378, 6379, -1, 6380, 6381, 6382, -1, 6382, 6381, 5524, -1, 5524, 6381, 6383, -1, 6383, 6381, 6380, -1, 6379, 6378, 6384, -1, 6385, 6386, 6377, -1, 6387, 6388, 6374, -1, 6389, 6388, 6387, -1, 6377, 6386, 6378, -1, 6374, 6390, 6375, -1, 6391, 6392, 6393, -1, 6388, 6390, 6374, -1, 6393, 6392, 6394, -1, 6389, 6395, 6388, -1, 6385, 6396, 6386, -1, 6397, 6396, 6385, -1, 6398, 6395, 6389, -1, 5513, 6396, 6397, -1, 5542, 6396, 5513, -1, 6388, 6399, 6390, -1, 6395, 6399, 6388, -1, 6384, 6400, 6391, -1, 6382, 6401, 6398, -1, 6398, 6401, 6395, -1, 6391, 6400, 6392, -1, 879, 876, 5203, -1, 6384, 6402, 6400, -1, 6375, 6403, 6376, -1, 6378, 6402, 6384, -1, 6376, 6403, 6404, -1, 6386, 6405, 6378, -1, 5520, 6406, 5522, -1, 6378, 6405, 6402, -1, 6395, 6406, 6399, -1, 6401, 6406, 6395, -1, 6392, 6407, 6394, -1, 6406, 6408, 5522, -1, 6401, 6408, 6406, -1, 6382, 6408, 6401, -1, 6394, 6407, 6409, -1, 5522, 6408, 6382, -1, 6396, 6410, 6386, -1, 6375, 6411, 6403, -1, 5506, 6410, 5542, -1, 5542, 6410, 6396, -1, 6386, 6410, 6405, -1, 6390, 6411, 6375, -1, 6399, 6412, 6390, -1, 6400, 6413, 6392, -1, 6390, 6412, 6411, -1, 6392, 6413, 6407, -1, 6402, 6414, 6400, -1, 6406, 6415, 6399, -1, 6400, 6414, 6413, -1, 6399, 6415, 6412, -1, 6403, 6416, 6404, -1, 6402, 6417, 6414, -1, 6405, 6417, 6402, -1, 6404, 6416, 6418, -1, 5520, 6419, 6406, -1, 6406, 6419, 6415, -1, 6411, 6420, 6403, -1, 5508, 6421, 5506, -1, 6403, 6420, 6416, -1, 5506, 6421, 6410, -1, 6410, 6421, 6405, -1, 6405, 6421, 6417, -1, 6411, 6422, 6420, -1, 6412, 6422, 6411, -1, 6415, 6423, 6412, -1, 6412, 6423, 6422, -1, 6416, 6424, 6418, -1, 6418, 6424, 6425, -1, 5518, 6426, 5520, -1, 5520, 6426, 6419, -1, 6419, 6426, 6415, -1, 6415, 6426, 6423, -1, 6420, 6427, 6416, -1, 6416, 6427, 6424, -1, 6422, 6428, 6420, -1, 6420, 6428, 6427, -1, 6423, 6429, 6422, -1, 6422, 6429, 6428, -1, 6424, 6430, 6425, -1, 6425, 6430, 6431, -1, 5517, 6432, 5518, -1, 5518, 6432, 6426, -1, 6426, 6432, 6423, -1, 6423, 6432, 6429, -1, 6424, 6433, 6430, -1, 6427, 6433, 6424, -1, 6427, 6434, 6433, -1, 6428, 6434, 6427, -1, 6429, 6435, 6428, -1, 6428, 6435, 6434, -1, 6430, 6436, 6431, -1, 6431, 6436, 6437, -1, 5485, 6438, 5517, -1, 5517, 6438, 6432, -1, 6432, 6438, 6429, -1, 6429, 6438, 6435, -1, 5538, 6439, 5539, -1, 6433, 6440, 6430, -1, 6430, 6440, 6436, -1, 6434, 6441, 6433, -1, 6433, 6441, 6440, -1, 6434, 6442, 6441, -1, 6435, 6442, 6434, -1, 6436, 6443, 6437, -1, 6444, 6445, 6446, -1, 6437, 6443, 6447, -1, 6446, 6445, 6448, -1, 6435, 6449, 6442, -1, 5487, 6449, 5485, -1, 5536, 6450, 5538, -1, 5485, 6449, 6438, -1, 6451, 6450, 5536, -1, 6438, 6449, 6435, -1, 6436, 6452, 6443, -1, 6444, 6453, 6445, -1, 6440, 6452, 6436, -1, 6454, 6453, 6444, -1, 6440, 6455, 6452, -1, 6441, 6455, 6440, -1, 6454, 6456, 6453, -1, 6457, 6456, 6454, -1, 5534, 6458, 5536, -1, 6441, 6459, 6455, -1, 6451, 6458, 6457, -1, 5536, 6458, 6451, -1, 6442, 6459, 6441, -1, 6457, 6458, 6456, -1, 6443, 6460, 6447, -1, 6445, 6461, 6448, -1, 6462, 6460, 5295, -1, 6448, 6461, 6463, -1, 6447, 6460, 6462, -1, 6461, 6464, 6463, -1, 5503, 6465, 5487, -1, 6463, 6464, 6466, -1, 5487, 6465, 6449, -1, 6442, 6465, 6459, -1, 6445, 6467, 6461, -1, 6449, 6465, 6442, -1, 6443, 6468, 6460, -1, 6460, 6468, 5295, -1, 6453, 6467, 6445, -1, 5295, 6468, 5300, -1, 6452, 6468, 6443, -1, 6467, 6469, 6461, -1, 6455, 6470, 6452, -1, 6461, 6469, 6464, -1, 6452, 6470, 6468, -1, 6468, 6470, 5300, -1, 5300, 6470, 5306, -1, 6456, 6471, 6453, -1, 6453, 6471, 6467, -1, 6455, 6472, 6470, -1, 6470, 6472, 5306, -1, 5306, 6472, 5311, -1, 6467, 6473, 6469, -1, 6459, 6472, 6455, -1, 6471, 6473, 6467, -1, 5320, 6474, 5483, -1, 5500, 6475, 5534, -1, 5483, 6474, 5503, -1, 5534, 6475, 6458, -1, 5503, 6474, 6465, -1, 6458, 6475, 6456, -1, 6459, 6474, 6472, -1, 6465, 6474, 6459, -1, 6456, 6475, 6471, -1, 6472, 6474, 5311, -1, 5311, 6474, 5320, -1, 5541, 6476, 5508, -1, 5508, 6476, 6421, -1, 6464, 6477, 6466, -1, 6478, 6476, 5541, -1, 6479, 6480, 5539, -1, 6471, 6481, 6473, -1, 6475, 6481, 6471, -1, 5539, 6480, 5541, -1, 6477, 6482, 6466, -1, 6466, 6482, 6483, -1, 6469, 6484, 6464, -1, 6464, 6484, 6477, -1, 6439, 6485, 5539, -1, 5500, 6486, 6475, -1, 6475, 6486, 6481, -1, 6450, 6487, 5538, -1, 6477, 6488, 6482, -1, 6484, 6488, 6477, -1, 6417, 6489, 6414, -1, 6469, 6490, 6484, -1, 6421, 6489, 6417, -1, 6473, 6490, 6469, -1, 6476, 6489, 6421, -1, 6490, 6491, 6484, -1, 6476, 6492, 6489, -1, 6484, 6491, 6488, -1, 6478, 6493, 6476, -1, 6473, 6494, 6490, -1, 6476, 6493, 6492, -1, 5502, 6494, 5500, -1, 6495, 6493, 6496, -1, 6481, 6494, 6473, -1, 6496, 6493, 6478, -1, 5500, 6494, 6486, -1, 6486, 6494, 6481, -1, 6496, 6497, 6495, -1, 6478, 6497, 6496, -1, 6482, 6498, 6483, -1, 5541, 6497, 6478, -1, 6480, 6497, 5541, -1, 6480, 6499, 6497, -1, 6494, 6500, 6490, -1, 6490, 6500, 6491, -1, 6488, 6501, 6482, -1, 6502, 6503, 6479, -1, 6482, 6501, 6498, -1, 6480, 6503, 6499, -1, 6479, 6503, 6480, -1, 6504, 6503, 6502, -1, 5539, 6505, 6479, -1, 6479, 6505, 6502, -1, 6483, 6506, 6507, -1, 6485, 6505, 5539, -1, 6498, 6506, 6483, -1, 6502, 6505, 6504, -1, 5502, 6508, 6494, -1, 6494, 6508, 6500, -1, 6485, 6509, 6505, -1, 6510, 6511, 6512, -1, 6488, 6513, 6501, -1, 6491, 6513, 6488, -1, 6512, 6511, 6439, -1, 6439, 6511, 6485, -1, 6498, 6514, 6506, -1, 6485, 6511, 6509, -1, 6512, 6515, 6510, -1, 6439, 6515, 6512, -1, 5538, 6515, 6439, -1, 6501, 6514, 6498, -1, 6487, 6515, 5538, -1, 5502, 6516, 6508, -1, 6508, 6516, 6500, -1, 6491, 6516, 6513, -1, 5533, 6516, 5502, -1, 6500, 6516, 6491, -1, 6487, 6517, 6515, -1, 6457, 6518, 6451, -1, 6506, 6519, 6507, -1, 6451, 6518, 6450, -1, 6450, 6518, 6487, -1, 6501, 6520, 6514, -1, 6487, 6518, 6517, -1, 6489, 6521, 6414, -1, 6513, 6520, 6501, -1, 6492, 6521, 6489, -1, 6414, 6521, 6413, -1, 6506, 6522, 6519, -1, 6492, 6523, 6521, -1, 6514, 6522, 6506, -1, 6513, 6524, 6520, -1, 6516, 6524, 6513, -1, 6493, 6525, 6492, -1, 6495, 6525, 6493, -1, 6492, 6525, 6523, -1, 6526, 6525, 6495, -1, 6519, 6527, 6507, -1, 6497, 6528, 6495, -1, 6499, 6528, 6497, -1, 6507, 6527, 6529, -1, 6495, 6528, 6526, -1, 6520, 6530, 6514, -1, 6514, 6530, 6522, -1, 6499, 6531, 6528, -1, 5533, 6532, 6516, -1, 6516, 6532, 6524, -1, 6462, 5295, 4669, -1, 6503, 6533, 6499, -1, 6504, 6533, 6503, -1, 6499, 6533, 6531, -1, 6522, 6534, 6519, -1, 6535, 6533, 6504, -1, 6519, 6534, 6527, -1, 6524, 6536, 6520, -1, 5531, 6536, 5533, -1, 6505, 6537, 6504, -1, 6532, 6536, 6524, -1, 6509, 6537, 6505, -1, 6520, 6536, 6530, -1, 6504, 6537, 6535, -1, 5533, 6536, 6532, -1, 6527, 6538, 6529, -1, 6509, 6539, 6537, -1, 6509, 6540, 6539, -1, 6541, 6540, 6510, -1, 6530, 6542, 6522, -1, 6510, 6540, 6511, -1, 6522, 6542, 6534, -1, 6511, 6540, 6509, -1, 6510, 6543, 6541, -1, 6534, 6544, 6527, -1, 6515, 6543, 6510, -1, 6527, 6544, 6538, -1, 5185, 6545, 4591, -1, 6517, 6543, 6515, -1, 4591, 6545, 6546, -1, 6517, 6547, 6543, -1, 6536, 6548, 6530, -1, 6530, 6548, 6542, -1, 5192, 6549, 5185, -1, 5185, 6549, 6545, -1, 6517, 6550, 6547, -1, 6457, 6550, 6518, -1, 6538, 6551, 6529, -1, 6518, 6550, 6517, -1, 6454, 6550, 6457, -1, 6529, 6551, 6552, -1, 6407, 6553, 6409, -1, 6534, 6554, 6544, -1, 6413, 6553, 6407, -1, 6542, 6554, 6534, -1, 6545, 6555, 6546, -1, 6409, 6553, 6556, -1, 6556, 6553, 6557, -1, 6557, 6553, 6526, -1, 5192, 6558, 6549, -1, 6521, 6553, 6413, -1, 6523, 6553, 6521, -1, 6525, 6553, 6523, -1, 5531, 6559, 6536, -1, 6526, 6553, 6525, -1, 6536, 6559, 6548, -1, 5199, 6558, 5192, -1, 6556, 6560, 6561, -1, 6557, 6560, 6556, -1, 6526, 6560, 6557, -1, 6544, 6562, 6538, -1, 6545, 6563, 6555, -1, 6561, 6560, 6564, -1, 6528, 6560, 6526, -1, 6549, 6563, 6545, -1, 6564, 6560, 6535, -1, 6538, 6562, 6551, -1, 6531, 6560, 6528, -1, 6533, 6560, 6531, -1, 6535, 6560, 6533, -1, 6537, 6565, 6535, -1, 5529, 6566, 5531, -1, 876, 6567, 5203, -1, 6568, 6565, 6541, -1, 5531, 6566, 6559, -1, 6540, 6565, 6539, -1, 6541, 6565, 6540, -1, 6542, 6566, 6554, -1, 6561, 6565, 6569, -1, 6548, 6566, 6542, -1, 6539, 6565, 6537, -1, 6559, 6566, 6548, -1, 5199, 6567, 6558, -1, 6564, 6565, 6561, -1, 5203, 6567, 5199, -1, 6569, 6565, 6568, -1, 6535, 6565, 6564, -1, 6541, 6570, 6568, -1, 6551, 6571, 6552, -1, 6543, 6570, 6541, -1, 6550, 6570, 6547, -1, 6546, 6572, 6573, -1, 6446, 6570, 6444, -1, 6555, 6572, 6546, -1, 6454, 6570, 6550, -1, 6569, 6570, 6446, -1, 6554, 6574, 6544, -1, 6547, 6570, 6543, -1, 6568, 6570, 6569, -1, 6544, 6574, 6562, -1, 6444, 6570, 6454, -1, 6549, 6575, 6563, -1, 6558, 6575, 6549, -1, 6567, 6576, 882, -1, 876, 6576, 6567, -1, 6562, 6577, 6551, -1, 882, 6576, 880, -1, 880, 6576, 876, -1, 6551, 6577, 6571, -1, 6555, 6578, 6572, -1, 6563, 6578, 6555, -1, 6566, 6579, 6554, -1, 6554, 6579, 6574, -1, 6567, 6580, 6558, -1, 6571, 6581, 6552, -1, 882, 6580, 6567, -1, 6552, 6581, 6582, -1, 5479, 6580, 882, -1, 6558, 6580, 6575, -1, 6572, 6583, 6573, -1, 6574, 6584, 6562, -1, 6562, 6584, 6577, -1, 6563, 6585, 6578, -1, 5529, 6586, 6566, -1, 6566, 6586, 6579, -1, 6575, 6585, 6563, -1, 6572, 6587, 6583, -1, 6577, 6588, 6571, -1, 6571, 6588, 6581, -1, 6578, 6587, 6572, -1, 5527, 6589, 5529, -1, 6574, 6589, 6584, -1, 6580, 6590, 6575, -1, 5529, 6589, 6586, -1, 6579, 6589, 6574, -1, 6575, 6590, 6585, -1, 6586, 6589, 6579, -1, 6578, 6591, 6587, -1, 6581, 6592, 6582, -1, 6585, 6591, 6578, -1, 6584, 6593, 6577, -1, 6577, 6593, 6588, -1, 6583, 6594, 6573, -1, 6573, 6594, 6595, -1, 6588, 6596, 6581, -1, 5479, 6597, 6580, -1, 6581, 6596, 6592, -1, 6580, 6597, 6590, -1, 6585, 6598, 6591, -1, 6590, 6598, 6585, -1, 6584, 6599, 6593, -1, 5479, 6598, 6597, -1, 6589, 6599, 6584, -1, 5477, 6598, 5479, -1, 6597, 6598, 6590, -1, 6587, 6600, 6583, -1, 6592, 6601, 6582, -1, 6582, 6601, 6602, -1, 6583, 6600, 6594, -1, 6588, 6603, 6596, -1, 6594, 6604, 6595, -1, 6593, 6603, 6588, -1, 5527, 6605, 6589, -1, 6589, 6605, 6599, -1, 6596, 6606, 6592, -1, 6587, 6607, 6600, -1, 6591, 6607, 6587, -1, 6594, 6608, 6604, -1, 6600, 6608, 6594, -1, 6592, 6606, 6601, -1, 6599, 6609, 6593, -1, 6593, 6609, 6603, -1, 5527, 6609, 6605, -1, 6605, 6609, 6599, -1, 5526, 6609, 5527, -1, 6598, 6610, 6591, -1, 6591, 6610, 6607, -1, 6601, 6611, 6602, -1, 6600, 6612, 6608, -1, 6607, 6612, 6600, -1, 6596, 6613, 6606, -1, 6604, 6614, 6595, -1, 6603, 6613, 6596, -1, 6595, 6614, 6615, -1, 6601, 6616, 6611, -1, 5477, 6617, 6598, -1, 6606, 6616, 6601, -1, 6598, 6617, 6610, -1, 6607, 6618, 6612, -1, 6603, 6619, 6613, -1, 6617, 6618, 6610, -1, 5478, 6618, 5477, -1, 6609, 6619, 6603, -1, 5477, 6618, 6617, -1, 6610, 6618, 6607, -1, 6611, 6620, 6602, -1, 6614, 6621, 6615, -1, 6602, 6620, 6622, -1, 6613, 6623, 6606, -1, 6608, 6624, 6604, -1, 6606, 6623, 6616, -1, 6604, 6624, 6614, -1, 6609, 6625, 6619, -1, 5526, 6625, 6609, -1, 6624, 6626, 6614, -1, 6614, 6626, 6621, -1, 6616, 6627, 6611, -1, 6611, 6627, 6620, -1, 5498, 6628, 5526, -1, 6612, 6629, 6608, -1, 5526, 6628, 6625, -1, 6608, 6629, 6624, -1, 6613, 6628, 6623, -1, 6629, 6630, 6624, -1, 6619, 6628, 6613, -1, 6625, 6628, 6619, -1, 6624, 6630, 6626, -1, 6620, 6631, 6622, -1, 6618, 6632, 6612, -1, 6612, 6632, 6629, -1, 6616, 6633, 6627, -1, 6623, 6633, 6616, -1, 6621, 6634, 6615, -1, 6615, 6634, 6635, -1, 6627, 6636, 6620, -1, 6629, 6637, 6630, -1, 6620, 6636, 6631, -1, 6632, 6637, 6629, -1, 5472, 6637, 5478, -1, 6628, 6638, 6623, -1, 6623, 6638, 6633, -1, 6634, 6639, 6635, -1, 6618, 6640, 6632, -1, 5478, 6640, 6618, -1, 6631, 6641, 6622, -1, 6632, 6640, 6637, -1, 6637, 6640, 5478, -1, 6622, 6641, 6642, -1, 6626, 6643, 6621, -1, 6621, 6643, 6634, -1, 6633, 6644, 6627, -1, 6627, 6644, 6636, -1, 6643, 6645, 6634, -1, 5498, 6646, 6628, -1, 6628, 6646, 6638, -1, 6634, 6645, 6639, -1, 6636, 6647, 6631, -1, 6626, 6648, 6643, -1, 6631, 6647, 6641, -1, 6630, 6648, 6626, -1, 5495, 6649, 5498, -1, 6643, 6650, 6645, -1, 5498, 6649, 6646, -1, 6638, 6649, 6633, -1, 6633, 6649, 6644, -1, 6648, 6650, 6643, -1, 6646, 6649, 6638, -1, 6630, 6651, 6648, -1, 6641, 6652, 6642, -1, 6637, 6651, 6630, -1, 6644, 6653, 6636, -1, 6636, 6653, 6647, -1, 6635, 6654, 6655, -1, 6639, 6654, 6635, -1, 6651, 6656, 6648, -1, 6647, 6657, 6641, -1, 6648, 6656, 6650, -1, 6641, 6657, 6652, -1, 5474, 6656, 5472, -1, 6651, 6658, 6656, -1, 6644, 6659, 6653, -1, 6637, 6658, 6651, -1, 6656, 6658, 5472, -1, 6649, 6659, 6644, -1, 5472, 6658, 6637, -1, 6645, 6660, 6639, -1, 6639, 6660, 6654, -1, 6652, 6661, 6642, -1, 6642, 6661, 6662, -1, 6650, 6663, 6645, -1, 6653, 6664, 6647, -1, 6647, 6664, 6657, -1, 6645, 6663, 6660, -1, 5495, 6665, 6649, -1, 6656, 6666, 6650, -1, 6650, 6666, 6663, -1, 6649, 6665, 6659, -1, 6654, 6667, 6655, -1, 6657, 6668, 6652, -1, 6652, 6668, 6661, -1, 6655, 6667, 6669, -1, 5525, 6670, 5495, -1, 5495, 6670, 6665, -1, 6656, 6671, 6666, -1, 6659, 6670, 6653, -1, 5474, 6671, 6656, -1, 6653, 6670, 6664, -1, 6665, 6670, 6659, -1, 6654, 6672, 6667, -1, 6661, 6673, 6662, -1, 6660, 6672, 6654, -1, 6663, 6674, 6660, -1, 6664, 6675, 6657, -1, 6657, 6675, 6668, -1, 6660, 6674, 6672, -1, 6661, 6676, 6673, -1, 6666, 6677, 6663, -1, 6668, 6676, 6661, -1, 6670, 6678, 6664, -1, 6663, 6677, 6674, -1, 6667, 6679, 6669, -1, 6664, 6678, 6675, -1, 6669, 6679, 6680, -1, 6662, 6681, 6682, -1, 6673, 6681, 6662, -1, 5548, 6683, 5474, -1, 6666, 6683, 6677, -1, 6671, 6683, 6666, -1, 6675, 6684, 6668, -1, 5474, 6683, 6671, -1, 6668, 6684, 6676, -1, 6670, 6685, 6678, -1, 6672, 6686, 6667, -1, 6667, 6686, 6679, -1, 5525, 6685, 6670, -1, 6673, 6687, 6681, -1, 6674, 6688, 6672, -1, 6672, 6688, 6686, -1, 6676, 6687, 6673, -1, 6678, 6689, 6675, -1, 6675, 6689, 6684, -1, 6685, 6689, 6678, -1, 5490, 6689, 5525, -1, 6677, 6690, 6674, -1, 5525, 6689, 6685, -1, 6674, 6690, 6688, -1, 6681, 6691, 6682, -1, 6679, 6692, 6680, -1, 6680, 6692, 6693, -1, 6676, 6694, 6687, -1, 6684, 6694, 6676, -1, 5546, 6695, 5548, -1, 6683, 6695, 6677, -1, 5548, 6695, 6683, -1, 6677, 6695, 6690, -1, 6681, 6696, 6691, -1, 6687, 6696, 6681, -1, 6679, 6697, 6692, -1, 6686, 6697, 6679, -1, 6684, 6698, 6694, -1, 6689, 6698, 6684, -1, 6688, 6699, 6686, -1, 6686, 6699, 6697, -1, 6687, 6700, 6696, -1, 6694, 6700, 6687, -1, 6691, 6701, 6682, -1, 6690, 6702, 6688, -1, 6688, 6702, 6699, -1, 6682, 6701, 6703, -1, 6693, 6704, 6705, -1, 5490, 6706, 6689, -1, 6689, 6706, 6698, -1, 6692, 6704, 6693, -1, 5492, 6707, 5490, -1, 5490, 6707, 6706, -1, 5544, 6708, 5546, -1, 6694, 6707, 6700, -1, 5546, 6708, 6695, -1, 6698, 6707, 6694, -1, 6695, 6708, 6690, -1, 6706, 6707, 6698, -1, 6690, 6708, 6702, -1, 6691, 6709, 6701, -1, 6697, 6710, 6692, -1, 6696, 6709, 6691, -1, 6692, 6710, 6704, -1, 6701, 6711, 6703, -1, 6697, 6712, 6710, -1, 6699, 6712, 6697, -1, 6700, 6713, 6696, -1, 6696, 6713, 6709, -1, 6702, 6714, 6699, -1, 6699, 6714, 6712, -1, 6709, 6715, 6701, -1, 6701, 6715, 6711, -1, 6705, 6716, 6717, -1, 6704, 6716, 6705, -1, 6700, 6718, 6713, -1, 6707, 6718, 6700, -1, 5543, 6719, 5544, -1, 5544, 6719, 6708, -1, 6708, 6719, 6702, -1, 6702, 6719, 6714, -1, 6713, 6720, 6709, -1, 6710, 6721, 6704, -1, 6709, 6720, 6715, -1, 6704, 6721, 6716, -1, 6711, 6722, 6703, -1, 6703, 6722, 6723, -1, 6710, 6724, 6721, -1, 5492, 6725, 6707, -1, 6712, 6724, 6710, -1, 6707, 6725, 6718, -1, 6712, 6726, 6724, -1, 5524, 6383, 5492, -1, 5492, 6383, 6725, -1, 6714, 6726, 6712, -1, 6718, 6383, 6713, -1, 6713, 6383, 6720, -1, 6725, 6383, 6718, -1, 6717, 6727, 6728, -1, 6722, 6387, 6723, -1, 6716, 6727, 6717, -1, 6711, 6729, 6722, -1, 6714, 6730, 6726, -1, 5511, 6730, 5543, -1, 6715, 6729, 6711, -1, 5543, 6730, 6719, -1, 6719, 6730, 6714, -1, 6716, 6379, 6727, -1, 6729, 6389, 6722, -1, 6722, 6389, 6387, -1, 6721, 6379, 6716, -1, 6720, 6731, 6715, -1, 6724, 6377, 6721, -1, 6715, 6731, 6729, -1, 6721, 6377, 6379, -1, 6724, 6385, 6377, -1, 6729, 6398, 6389, -1, 6731, 6398, 6729, -1, 6726, 6385, 6724, -1, 6383, 6380, 6720, -1, 6727, 6391, 6728, -1, 6720, 6380, 6731, -1, 6728, 6391, 6393, -1, 6387, 6374, 6723, -1, 6723, 6374, 6376, -1, 6730, 6397, 6726, -1, 5511, 6397, 6730, -1, 6726, 6397, 6385, -1, 5522, 6382, 5524, -1, 5513, 6397, 5511, -1, 6727, 6384, 6391, -1, 6379, 6384, 6727, -1, 6731, 6382, 6398, -1, 6380, 6382, 6731, -1, 6732, 6733, 6734, -1, 6735, 6368, 6736, -1, 6735, 6736, 6737, -1, 6738, 6733, 6732, -1, 6739, 6740, 6741, -1, 6738, 6742, 6733, -1, 6743, 6744, 6742, -1, 6739, 6745, 6740, -1, 6746, 6737, 6747, -1, 6746, 6747, 6748, -1, 6746, 6368, 6735, -1, 6743, 6742, 6738, -1, 6746, 6735, 6737, -1, 6749, 4579, 4581, -1, 6749, 6750, 4579, -1, 6746, 6367, 6368, -1, 6749, 4581, 4859, -1, 6751, 6741, 4576, -1, 6752, 6333, 6753, -1, 6754, 6748, 6745, -1, 6752, 6744, 6743, -1, 6752, 6305, 6333, -1, 6752, 6753, 6744, -1, 6754, 6745, 6739, -1, 6755, 6739, 6741, -1, 6756, 6749, 4859, -1, 6755, 6741, 6751, -1, 6756, 4859, 4864, -1, 6756, 6732, 6750, -1, 6756, 6750, 6749, -1, 6757, 6746, 6748, -1, 6757, 6748, 6754, -1, 6758, 6738, 6732, -1, 6758, 6732, 6756, -1, 6758, 4864, 4867, -1, 6759, 4576, 4578, -1, 6759, 6751, 4576, -1, 6758, 6756, 4864, -1, 6758, 4867, 6760, -1, 6761, 6743, 6738, -1, 6762, 6754, 6739, -1, 6761, 6758, 6760, -1, 6762, 6739, 6755, -1, 6761, 6738, 6758, -1, 6761, 6760, 6763, -1, 6764, 6752, 6743, -1, 6764, 6305, 6752, -1, 6765, 6367, 6746, -1, 6764, 6743, 6761, -1, 6765, 6746, 6757, -1, 6764, 6761, 6763, -1, 6764, 6763, 6310, -1, 6764, 6310, 6305, -1, 6766, 6755, 6751, -1, 6766, 6751, 6759, -1, 6767, 6757, 6754, -1, 6767, 6754, 6762, -1, 6767, 6367, 6765, -1, 6767, 6765, 6757, -1, 6767, 6365, 6367, -1, 6768, 6759, 4578, -1, 6769, 6762, 6755, -1, 6769, 6755, 6766, -1, 6770, 6766, 6759, -1, 6770, 6759, 6768, -1, 6771, 6762, 6769, -1, 6771, 6767, 6762, -1, 6772, 4578, 4580, -1, 6772, 6768, 4578, -1, 6773, 6769, 6766, -1, 6773, 6766, 6770, -1, 6774, 6365, 6767, -1, 6774, 6767, 6771, -1, 6775, 6770, 6768, -1, 6775, 6768, 6772, -1, 6776, 6769, 6773, -1, 6776, 6364, 6365, -1, 6776, 6771, 6769, -1, 6776, 6365, 6774, -1, 6776, 6774, 6771, -1, 6777, 6772, 4580, -1, 6778, 6773, 6770, -1, 6778, 6770, 6775, -1, 6779, 6772, 6777, -1, 6779, 6775, 6772, -1, 6780, 6773, 6778, -1, 6780, 6776, 6773, -1, 6781, 4580, 4583, -1, 6781, 6777, 4580, -1, 6782, 6775, 6779, -1, 6782, 6778, 6775, -1, 6783, 6776, 6780, -1, 6783, 6364, 6776, -1, 6784, 6779, 6777, -1, 6784, 6777, 6781, -1, 6785, 6783, 6780, -1, 6785, 6778, 6782, -1, 6785, 6364, 6783, -1, 6785, 6362, 6364, -1, 6785, 6780, 6778, -1, 6786, 6781, 4583, -1, 6787, 6782, 6779, -1, 6787, 6779, 6784, -1, 6788, 6784, 6781, -1, 6788, 6781, 6786, -1, 6789, 6782, 6787, -1, 6789, 6785, 6782, -1, 6790, 4583, 4584, -1, 6790, 6786, 4583, -1, 6791, 6785, 6789, -1, 6791, 6362, 6785, -1, 6792, 6787, 6784, -1, 6792, 6784, 6788, -1, 6793, 6788, 6786, -1, 6793, 6786, 6790, -1, 6794, 6789, 6787, -1, 6794, 6787, 6792, -1, 6794, 6791, 6789, -1, 6794, 6362, 6791, -1, 6794, 6360, 6362, -1, 6795, 6790, 4584, -1, 6796, 6792, 6788, -1, 6796, 6788, 6793, -1, 6797, 6793, 6790, -1, 6797, 6790, 6795, -1, 6798, 6794, 6792, -1, 6798, 6792, 6796, -1, 6799, 4584, 4546, -1, 6799, 6795, 4584, -1, 6800, 6360, 6794, -1, 6800, 6794, 6798, -1, 6801, 6796, 6793, -1, 6801, 6793, 6797, -1, 6802, 6797, 6795, -1, 6802, 6795, 6799, -1, 6803, 6798, 6796, -1, 6803, 6360, 6800, -1, 6803, 6796, 6801, -1, 6803, 6359, 6360, -1, 6803, 6800, 6798, -1, 6804, 6799, 4546, -1, 6805, 6801, 6797, -1, 6805, 6797, 6802, -1, 6806, 6802, 6799, -1, 6806, 6799, 6804, -1, 6807, 6803, 6801, -1, 6807, 6801, 6805, -1, 6808, 4546, 4547, -1, 6808, 6804, 4546, -1, 6809, 6803, 6807, -1, 6809, 6359, 6803, -1, 6810, 6805, 6802, -1, 6810, 6802, 6806, -1, 6811, 6804, 6808, -1, 6811, 6806, 6804, -1, 6812, 6358, 6359, -1, 6812, 6805, 6810, -1, 6812, 6807, 6805, -1, 6812, 6359, 6809, -1, 6812, 6809, 6807, -1, 6813, 6808, 4547, -1, 6814, 6806, 6811, -1, 6814, 6810, 6806, -1, 6815, 6808, 6813, -1, 6815, 6811, 6808, -1, 6816, 6810, 6814, -1, 6816, 6812, 6810, -1, 6817, 6813, 4547, -1, 6817, 4547, 4548, -1, 6818, 6358, 6812, -1, 6818, 6812, 6816, -1, 4859, 4581, 4582, -1, 6819, 6814, 6811, -1, 6819, 6811, 6815, -1, 6820, 6815, 6813, -1, 6820, 6813, 6817, -1, 6821, 6358, 6818, -1, 6821, 6816, 6814, -1, 6821, 6814, 6819, -1, 6821, 6818, 6816, -1, 6821, 6357, 6358, -1, 6822, 6819, 6815, -1, 6822, 6815, 6820, -1, 6823, 6817, 4548, -1, 6824, 6819, 6822, -1, 6824, 6821, 6819, -1, 4783, 6760, 4867, -1, 6825, 6820, 6817, -1, 4782, 6760, 4783, -1, 6826, 4757, 4551, -1, 6825, 6817, 6823, -1, 6827, 4548, 4549, -1, 6827, 6823, 4548, -1, 6826, 4551, 4552, -1, 6828, 4758, 4757, -1, 6829, 6357, 6821, -1, 6829, 6821, 6824, -1, 6830, 6822, 6820, -1, 6830, 6820, 6825, -1, 6828, 4757, 6826, -1, 6831, 4769, 4758, -1, 6831, 4758, 6828, -1, 6832, 6823, 6827, -1, 6833, 4772, 4769, -1, 6832, 6825, 6823, -1, 6834, 6824, 6822, -1, 6833, 4769, 6831, -1, 6834, 6357, 6829, -1, 6834, 6822, 6830, -1, 6834, 6829, 6824, -1, 6835, 6826, 4552, -1, 6835, 4552, 4554, -1, 6834, 6355, 6357, -1, 6836, 6830, 6825, -1, 6836, 6825, 6832, -1, 6837, 4855, 4772, -1, 6837, 6303, 4855, -1, 6837, 4772, 6833, -1, 6838, 6828, 6826, -1, 6839, 6827, 4549, -1, 6838, 6826, 6835, -1, 6840, 6834, 6830, -1, 6840, 6830, 6836, -1, 6841, 6828, 6838, -1, 6842, 4549, 4550, -1, 6842, 6839, 4549, -1, 6841, 6831, 6828, -1, 6843, 6831, 6841, -1, 6844, 6832, 6827, -1, 6843, 6833, 6831, -1, 6844, 6827, 6839, -1, 6845, 6355, 6834, -1, 6846, 6835, 4554, -1, 6845, 6834, 6840, -1, 6846, 4554, 4556, -1, 6847, 6839, 6842, -1, 6848, 6303, 6837, -1, 6847, 6844, 6839, -1, 6848, 6301, 6303, -1, 6848, 6833, 6843, -1, 6849, 6836, 6832, -1, 6848, 6837, 6833, -1, 6849, 6832, 6844, -1, 6850, 6849, 6844, -1, 6851, 6838, 6835, -1, 6851, 6835, 6846, -1, 6850, 6844, 6847, -1, 6852, 6841, 6838, -1, 6852, 6838, 6851, -1, 6853, 6840, 6836, -1, 6853, 6355, 6845, -1, 6853, 6353, 6355, -1, 6853, 6836, 6849, -1, 6853, 6845, 6840, -1, 6854, 6841, 6852, -1, 6854, 6843, 6841, -1, 6855, 4556, 4558, -1, 6856, 6842, 4550, -1, 6857, 6849, 6850, -1, 6855, 6846, 4556, -1, 6858, 6848, 6843, -1, 6857, 6853, 6849, -1, 6858, 6301, 6848, -1, 6858, 6299, 6301, -1, 6859, 4550, 4553, -1, 6858, 6843, 6854, -1, 6859, 6856, 4550, -1, 6860, 6847, 6842, -1, 6861, 6846, 6855, -1, 6861, 6851, 6846, -1, 6860, 6842, 6856, -1, 6862, 6353, 6853, -1, 6863, 6851, 6861, -1, 6863, 6852, 6851, -1, 6862, 6853, 6857, -1, 6864, 6860, 6856, -1, 6865, 6852, 6863, -1, 6864, 6856, 6859, -1, 6865, 6854, 6852, -1, 6866, 6855, 4558, -1, 6867, 6850, 6847, -1, 6867, 6847, 6860, -1, 6866, 4558, 4560, -1, 6868, 6867, 6860, -1, 6869, 6299, 6858, -1, 6869, 6854, 6865, -1, 6868, 6860, 6864, -1, 6869, 6298, 6299, -1, 6870, 6850, 6867, -1, 6869, 6858, 6854, -1, 6870, 6857, 6850, -1, 6871, 6855, 6866, -1, 6871, 6861, 6855, -1, 6872, 6859, 4553, -1, 6873, 6861, 6871, -1, 6874, 6353, 6862, -1, 6874, 6862, 6857, -1, 6873, 6863, 6861, -1, 6874, 6352, 6353, -1, 6874, 6857, 6870, -1, 6875, 6865, 6863, -1, 6876, 6867, 6868, -1, 6875, 6863, 6873, -1, 6876, 6870, 6867, -1, 6877, 6864, 6859, -1, 6878, 4560, 4562, -1, 6878, 6866, 4560, -1, 6877, 6859, 6872, -1, 6879, 6298, 6869, -1, 6879, 6865, 6875, -1, 6880, 6874, 6870, -1, 6879, 6296, 6298, -1, 6880, 6352, 6874, -1, 6880, 6870, 6876, -1, 6879, 6869, 6865, -1, 6881, 6864, 6877, -1, 6882, 6866, 6878, -1, 6882, 6871, 6866, -1, 6881, 6868, 6864, -1, 6883, 6876, 6868, -1, 6883, 6868, 6881, -1, 6884, 6871, 6882, -1, 6884, 6873, 6871, -1, 6885, 6875, 6873, -1, 6885, 6873, 6884, -1, 6886, 4553, 4555, -1, 6886, 6872, 4553, -1, 6887, 6878, 4562, -1, 6888, 6880, 6876, -1, 6888, 6352, 6880, -1, 6888, 6876, 6883, -1, 6887, 4562, 4564, -1, 6888, 6883, 6350, -1, 6888, 6350, 6352, -1, 6889, 6872, 6886, -1, 6889, 6877, 6872, -1, 6890, 6875, 6885, -1, 6890, 6879, 6875, -1, 6890, 6295, 6296, -1, 6890, 6296, 6879, -1, 6891, 6882, 6878, -1, 6892, 6881, 6877, -1, 6891, 6878, 6887, -1, 6892, 6877, 6889, -1, 6893, 6881, 6892, -1, 6893, 6883, 6881, -1, 6893, 6350, 6883, -1, 6894, 6884, 6882, -1, 6894, 6882, 6891, -1, 6895, 4555, 4557, -1, 6895, 6886, 4555, -1, 6896, 6885, 6884, -1, 6896, 6884, 6894, -1, 6897, 6350, 6893, -1, 6897, 6893, 6349, -1, 6898, 6887, 4564, -1, 6897, 6349, 6350, -1, 6899, 6886, 6895, -1, 6898, 4564, 4565, -1, 6899, 6889, 6886, -1, 6900, 6890, 6885, -1, 6900, 6295, 6890, -1, 6900, 6293, 6295, -1, 6901, 6889, 6899, -1, 6901, 6892, 6889, -1, 6900, 6885, 6896, -1, 6902, 6898, 4565, -1, 6903, 6893, 6892, -1, 6904, 6887, 6898, -1, 6903, 6892, 6901, -1, 6903, 6349, 6893, -1, 6904, 6891, 6887, -1, 6905, 6895, 4557, -1, 6905, 4557, 4559, -1, 6906, 6904, 6898, -1, 6906, 6898, 6902, -1, 6907, 6349, 6903, -1, 6907, 6903, 6348, -1, 6908, 6894, 6891, -1, 6907, 6348, 6349, -1, 6908, 6891, 6904, -1, 6909, 6899, 6895, -1, 6909, 6895, 6905, -1, 6910, 6904, 6906, -1, 6910, 6908, 6904, -1, 6911, 6901, 6899, -1, 6912, 6896, 6894, -1, 6911, 6899, 6909, -1, 6912, 6894, 6908, -1, 6913, 4565, 4567, -1, 6914, 6903, 6901, -1, 6914, 6348, 6903, -1, 6913, 6902, 4565, -1, 6914, 6901, 6911, -1, 6915, 4559, 4561, -1, 6916, 6373, 6293, -1, 6916, 6293, 6900, -1, 6915, 6905, 4559, -1, 6916, 6900, 6896, -1, 6916, 6896, 6912, -1, 6917, 6908, 6910, -1, 6918, 6348, 6914, -1, 6918, 6347, 6348, -1, 6918, 6914, 6347, -1, 6917, 6912, 6908, -1, 6919, 6909, 6905, -1, 6920, 6913, 4567, -1, 6919, 6905, 6915, -1, 6921, 6909, 6919, -1, 6921, 6911, 6909, -1, 6922, 6906, 6902, -1, 6922, 6902, 6913, -1, 6923, 6912, 6917, -1, 6923, 6372, 6373, -1, 6924, 6914, 6911, -1, 6923, 6373, 6916, -1, 6923, 6916, 6912, -1, 6924, 6911, 6921, -1, 6925, 6922, 6913, -1, 6924, 6347, 6914, -1, 6925, 6913, 6920, -1, 6926, 4561, 4563, -1, 6926, 6915, 4561, -1, 6927, 6906, 6922, -1, 6928, 6346, 6347, -1, 6928, 6924, 6346, -1, 6928, 6347, 6924, -1, 6927, 6910, 6906, -1, 6929, 6922, 6925, -1, 6930, 6919, 6915, -1, 6929, 6927, 6922, -1, 6930, 6915, 6926, -1, 6931, 6910, 6927, -1, 6931, 6917, 6910, -1, 6932, 6921, 6919, -1, 6933, 6920, 4567, -1, 6932, 6919, 6930, -1, 6933, 4567, 4569, -1, 6934, 6921, 6932, -1, 6935, 6923, 6917, -1, 6934, 6924, 6921, -1, 6935, 6372, 6923, -1, 6934, 6346, 6924, -1, 6935, 6917, 6931, -1, 6936, 4563, 4566, -1, 6937, 6927, 6929, -1, 6937, 6372, 6935, -1, 6937, 6931, 6927, -1, 6936, 6926, 4563, -1, 6937, 6935, 6931, -1, 6938, 6934, 6345, -1, 6937, 6371, 6372, -1, 6938, 6346, 6934, -1, 6939, 6933, 4569, -1, 6938, 6345, 6346, -1, 6940, 6930, 6926, -1, 6941, 6925, 6920, -1, 6940, 6926, 6936, -1, 6941, 6920, 6933, -1, 6942, 6932, 6930, -1, 6943, 6941, 6933, -1, 6943, 6933, 6939, -1, 6942, 6930, 6940, -1, 6944, 6934, 6932, -1, 6944, 6345, 6934, -1, 6944, 6932, 6942, -1, 6945, 6925, 6941, -1, 6945, 6929, 6925, -1, 6946, 4566, 4568, -1, 6947, 6941, 6943, -1, 6947, 6945, 6941, -1, 6946, 6936, 4566, -1, 6948, 6345, 6944, -1, 6949, 6937, 6929, -1, 6948, 6944, 6343, -1, 6949, 6929, 6945, -1, 6948, 6343, 6345, -1, 6950, 6940, 6936, -1, 6951, 4569, 4570, -1, 6950, 6936, 6946, -1, 6951, 6939, 4569, -1, 6952, 6942, 6940, -1, 6953, 6371, 6937, -1, 6953, 6937, 6949, -1, 6952, 6940, 6950, -1, 6954, 6371, 6953, -1, 6955, 6942, 6952, -1, 6954, 6945, 6947, -1, 6955, 6944, 6942, -1, 6955, 6343, 6944, -1, 6954, 6949, 6945, -1, 6954, 6953, 6949, -1, 6954, 6370, 6371, -1, 6956, 4568, 4571, -1, 6956, 6946, 4568, -1, 6957, 6943, 6939, -1, 6957, 6939, 6951, -1, 6958, 6343, 6955, -1, 6958, 6342, 6343, -1, 6959, 6951, 4570, -1, 6960, 6946, 6956, -1, 6961, 6947, 6943, -1, 6960, 6950, 6946, -1, 6961, 6943, 6957, -1, 6962, 6952, 6950, -1, 6962, 6950, 6960, -1, 6963, 6957, 6951, -1, 6963, 6951, 6959, -1, 6964, 6955, 6952, -1, 6965, 6947, 6961, -1, 6964, 6952, 6962, -1, 6965, 6954, 6947, -1, 6966, 4571, 4573, -1, 6967, 6961, 6957, -1, 6966, 6956, 4571, -1, 6967, 6957, 6963, -1, 6968, 4570, 4572, -1, 6968, 6959, 4570, -1, 6969, 6958, 6955, -1, 6969, 6342, 6958, -1, 6969, 6955, 6964, -1, 6969, 6340, 6342, -1, 6970, 6954, 6965, -1, 6971, 6960, 6956, -1, 6970, 6370, 6954, -1, 6971, 6956, 6966, -1, 6972, 6369, 6370, -1, 6972, 6965, 6961, -1, 6972, 6961, 6967, -1, 6972, 6970, 6965, -1, 6973, 6962, 6960, -1, 6972, 6370, 6970, -1, 6974, 6959, 6968, -1, 6973, 6960, 6971, -1, 6974, 6963, 6959, -1, 6975, 6964, 6962, -1, 6975, 6962, 6973, -1, 6976, 6968, 4572, -1, 6977, 4573, 4574, -1, 6977, 6966, 4573, -1, 6978, 6967, 6963, -1, 6978, 6963, 6974, -1, 6979, 6969, 6964, -1, 6979, 6340, 6969, -1, 6979, 6964, 6975, -1, 6979, 6336, 6340, -1, 6980, 6974, 6968, -1, 6980, 6968, 6976, -1, 6981, 6966, 6977, -1, 6981, 6971, 6966, -1, 6982, 6967, 6978, -1, 6982, 6972, 6967, -1, 6983, 4572, 4575, -1, 6984, 6973, 6971, -1, 6984, 6971, 6981, -1, 6983, 6976, 4572, -1, 6985, 6975, 6973, -1, 6986, 6974, 6980, -1, 6985, 6973, 6984, -1, 6986, 6978, 6974, -1, 6734, 4574, 4577, -1, 6987, 6972, 6982, -1, 6734, 6977, 4574, -1, 6987, 6369, 6972, -1, 6988, 6976, 6983, -1, 6989, 6979, 6975, -1, 6989, 6336, 6979, -1, 6989, 6975, 6985, -1, 6989, 6334, 6336, -1, 6988, 6980, 6976, -1, 6733, 6977, 6734, -1, 6736, 6978, 6986, -1, 6736, 6369, 6987, -1, 6733, 6981, 6977, -1, 6736, 6368, 6369, -1, 6736, 6987, 6982, -1, 6736, 6982, 6978, -1, 6742, 6981, 6733, -1, 6742, 6984, 6981, -1, 6740, 6983, 4575, -1, 6747, 6986, 6980, -1, 6747, 6980, 6988, -1, 6744, 6985, 6984, -1, 6744, 6984, 6742, -1, 6745, 6983, 6740, -1, 6750, 4577, 4579, -1, 6750, 6734, 4577, -1, 6745, 6988, 6983, -1, 6737, 6736, 6986, -1, 6737, 6986, 6747, -1, 6753, 6333, 6334, -1, 6741, 6740, 4575, -1, 6753, 6989, 6985, -1, 6741, 4575, 4576, -1, 6753, 6334, 6989, -1, 6753, 6985, 6744, -1, 6732, 6734, 6750, -1, 6748, 6988, 6745, -1, 6748, 6747, 6988, -1, 6990, 1245, 6991, -1, 6992, 1201, 6993, -1, 1182, 1201, 6992, -1, 6991, 1255, 6994, -1, 1245, 1255, 6991, -1, 6993, 1218, 6995, -1, 1201, 1218, 6993, -1, 6994, 1268, 6996, -1, 1255, 1268, 6994, -1, 1218, 1592, 6995, -1, 1208, 1210, 4014, -1, 6995, 1592, 6997, -1, 4014, 1210, 6998, -1, 6996, 1159, 6999, -1, 1268, 1159, 6996, -1, 6997, 1600, 7000, -1, 6999, 1158, 4005, -1, 1592, 1600, 6997, -1, 1159, 1158, 6999, -1, 6998, 1236, 7001, -1, 1210, 1236, 6998, -1, 7000, 1609, 7002, -1, 1600, 1609, 7000, -1, 1236, 1263, 7001, -1, 7001, 1263, 7003, -1, 7002, 1478, 7004, -1, 1609, 1478, 7002, -1, 1263, 1284, 7003, -1, 7003, 1284, 7005, -1, 7004, 944, 7006, -1, 1478, 944, 7004, -1, 1284, 1301, 7005, -1, 7005, 1301, 7007, -1, 7006, 943, 7008, -1, 944, 943, 7006, -1, 1301, 1325, 7007, -1, 7007, 1325, 7009, -1, 7008, 964, 7010, -1, 1325, 1353, 7009, -1, 943, 964, 7008, -1, 7009, 1353, 7011, -1, 964, 999, 7010, -1, 7010, 999, 7012, -1, 1353, 1381, 7011, -1, 7011, 1381, 7013, -1, 999, 1029, 7012, -1, 7012, 1029, 7014, -1, 1381, 1396, 7013, -1, 7013, 1396, 7015, -1, 1029, 1064, 7014, -1, 7014, 1064, 7016, -1, 1396, 1410, 7015, -1, 7015, 1410, 7017, -1, 1064, 1100, 7016, -1, 7016, 1100, 7018, -1, 1410, 1433, 7017, -1, 7017, 1433, 7019, -1, 1100, 1138, 7018, -1, 7018, 1138, 7020, -1, 1433, 1470, 7019, -1, 7019, 1470, 7021, -1, 1138, 1219, 7020, -1, 7020, 1219, 7022, -1, 1470, 1501, 7021, -1, 7021, 1501, 7023, -1, 1219, 1260, 7022, -1, 7022, 1260, 7024, -1, 1501, 1533, 7023, -1, 7023, 1533, 7025, -1, 1260, 1297, 7024, -1, 7024, 1297, 7026, -1, 1533, 1561, 7025, -1, 7025, 1561, 7027, -1, 1297, 1328, 7026, -1, 7026, 1328, 7028, -1, 1561, 1152, 7027, -1, 7027, 1152, 7029, -1, 1328, 1356, 7028, -1, 7028, 1356, 7030, -1, 1152, 1157, 7029, -1, 7029, 1157, 7031, -1, 1356, 1239, 7030, -1, 7030, 1239, 6990, -1, 1157, 1182, 7031, -1, 7031, 1182, 6992, -1, 1239, 1245, 6990, -1, 7032, 3595, 7033, -1, 3605, 3595, 7032, -1, 3595, 3585, 7033, -1, 7033, 3585, 7034, -1, 7035, 3580, 7036, -1, 7034, 3580, 7035, -1, 3585, 3580, 7034, -1, 3855, 3854, 1746, -1, 1746, 3854, 7037, -1, 7036, 3880, 7038, -1, 3580, 3880, 7036, -1, 7037, 3843, 7039, -1, 3854, 3843, 7037, -1, 7038, 3870, 7040, -1, 3880, 3870, 7038, -1, 7039, 3830, 7041, -1, 3843, 3830, 7039, -1, 7040, 3851, 7042, -1, 3870, 3851, 7040, -1, 7041, 3819, 7043, -1, 3830, 3819, 7041, -1, 7042, 3832, 7044, -1, 3851, 3832, 7042, -1, 3819, 3805, 7043, -1, 7044, 3811, 7045, -1, 7043, 3805, 7046, -1, 3832, 3811, 7044, -1, 7045, 3792, 7047, -1, 3805, 3794, 7046, -1, 3811, 3792, 7045, -1, 7046, 3794, 7048, -1, 7047, 3774, 7049, -1, 3794, 3781, 7048, -1, 3792, 3774, 7047, -1, 7048, 3781, 7050, -1, 7049, 3762, 7051, -1, 3774, 3762, 7049, -1, 3781, 3768, 7050, -1, 7050, 3768, 7052, -1, 7051, 3750, 7053, -1, 3768, 3741, 7052, -1, 3762, 3750, 7051, -1, 7052, 3741, 7054, -1, 3750, 3739, 7053, -1, 7053, 3739, 7055, -1, 3741, 3721, 7054, -1, 7054, 3721, 7056, -1, 3739, 3727, 7055, -1, 7055, 3727, 7057, -1, 3721, 3701, 7056, -1, 7056, 3701, 7058, -1, 3727, 3715, 7057, -1, 7057, 3715, 7059, -1, 3701, 3683, 7058, -1, 7058, 3683, 7060, -1, 3715, 3704, 7059, -1, 7059, 3704, 7061, -1, 3683, 3655, 7060, -1, 3704, 3692, 7061, -1, 7060, 3655, 7062, -1, 7061, 3692, 7063, -1, 3692, 3680, 7063, -1, 3655, 3645, 7062, -1, 7063, 3680, 7064, -1, 7062, 3645, 7065, -1, 3680, 3663, 7064, -1, 7064, 3663, 1736, -1, 3645, 3635, 7065, -1, 7065, 3635, 7066, -1, 3663, 3662, 1736, -1, 3635, 3625, 7066, -1, 7066, 3625, 7067, -1, 3625, 3615, 7067, -1, 7067, 3615, 7068, -1, 3615, 3605, 7068, -1, 7068, 3605, 7032, -1, 6635, 3194, 6615, -1, 6529, 3155, 6507, -1, 3132, 3155, 6529, -1, 6615, 3207, 6595, -1, 3194, 3207, 6615, -1, 6507, 3168, 6483, -1, 3155, 3168, 6507, -1, 6595, 3218, 6573, -1, 3207, 3218, 6595, -1, 3168, 3542, 6483, -1, 3151, 3153, 4669, -1, 6483, 3542, 6466, -1, 4669, 3153, 6462, -1, 6573, 3229, 6546, -1, 3218, 3229, 6573, -1, 6466, 3550, 6463, -1, 6546, 3378, 4591, -1, 3542, 3550, 6466, -1, 3229, 3378, 6546, -1, 6462, 3179, 6447, -1, 3153, 3179, 6462, -1, 6463, 3559, 6448, -1, 3550, 3559, 6463, -1, 3179, 3205, 6447, -1, 6447, 3205, 6437, -1, 6448, 3430, 6446, -1, 3559, 3430, 6448, -1, 3205, 3232, 6437, -1, 6437, 3232, 6431, -1, 6446, 2897, 6569, -1, 3430, 2897, 6446, -1, 3232, 3247, 6431, -1, 6431, 3247, 6425, -1, 6569, 2896, 6561, -1, 2897, 2896, 6569, -1, 3247, 3273, 6425, -1, 6425, 3273, 6418, -1, 6561, 2913, 6556, -1, 3273, 3301, 6418, -1, 2896, 2913, 6561, -1, 6418, 3301, 6404, -1, 2913, 2949, 6556, -1, 6556, 2949, 6409, -1, 3301, 3327, 6404, -1, 6404, 3327, 6376, -1, 2949, 2980, 6409, -1, 6409, 2980, 6394, -1, 3327, 3345, 6376, -1, 6376, 3345, 6723, -1, 2980, 3014, 6394, -1, 6394, 3014, 6393, -1, 3345, 3359, 6723, -1, 6723, 3359, 6703, -1, 3014, 3051, 6393, -1, 6393, 3051, 6728, -1, 3359, 3383, 6703, -1, 6703, 3383, 6682, -1, 3051, 3089, 6728, -1, 6728, 3089, 6717, -1, 3383, 3421, 6682, -1, 6682, 3421, 6662, -1, 3089, 3167, 6717, -1, 6717, 3167, 6705, -1, 3421, 3452, 6662, -1, 6662, 3452, 6642, -1, 3167, 3212, 6705, -1, 6705, 3212, 6693, -1, 3452, 3484, 6642, -1, 6642, 3484, 6622, -1, 3212, 3251, 6693, -1, 6693, 3251, 6680, -1, 3484, 3511, 6622, -1, 6622, 3511, 6602, -1, 3251, 3279, 6680, -1, 6680, 3279, 6669, -1, 3511, 3103, 6602, -1, 6602, 3103, 6582, -1, 3279, 3307, 6669, -1, 6669, 3307, 6655, -1, 3103, 3112, 6582, -1, 6582, 3112, 6552, -1, 3307, 3190, 6655, -1, 6655, 3190, 6635, -1, 3112, 3132, 6552, -1, 6552, 3132, 6529, -1, 3190, 3194, 6635, -1, 7069, 7070, 4792, -1, 7070, 7071, 4803, -1, 4803, 7071, 4814, -1, 4582, 2394, 4858, -1, 4814, 7072, 4825, -1, 7071, 7072, 4814, -1, 4858, 7073, 4872, -1, 2394, 7073, 4858, -1, 4825, 7074, 4836, -1, 7072, 7074, 4825, -1, 4872, 7075, 4883, -1, 7073, 7075, 4872, -1, 4836, 7076, 4847, -1, 4883, 7077, 4897, -1, 7074, 7076, 4836, -1, 7075, 7077, 4883, -1, 4847, 7078, 4863, -1, 4897, 7079, 4911, -1, 7076, 7078, 4847, -1, 7077, 7079, 4897, -1, 7079, 7080, 4911, -1, 4863, 7081, 4885, -1, 4911, 7080, 4923, -1, 7078, 7081, 4863, -1, 7080, 7082, 4923, -1, 4885, 7083, 4908, -1, 4923, 7082, 4937, -1, 7081, 7083, 4885, -1, 7082, 7084, 4937, -1, 4932, 7085, 4952, -1, 4937, 7084, 4950, -1, 4908, 7085, 4932, -1, 7083, 7085, 4908, -1, 7084, 7086, 4950, -1, 4950, 7086, 4963, -1, 4952, 7087, 4973, -1, 7085, 7087, 4952, -1, 7086, 7088, 4963, -1, 4963, 7088, 4978, -1, 4973, 7089, 4996, -1, 7087, 7089, 4973, -1, 7088, 7090, 4978, -1, 7089, 7091, 4996, -1, 4996, 7091, 5029, -1, 7090, 7092, 4978, -1, 4978, 7092, 4992, -1, 7091, 7093, 5029, -1, 5029, 7093, 5043, -1, 7092, 7094, 4992, -1, 7093, 7095, 5043, -1, 4992, 7094, 5006, -1, 5043, 7095, 5057, -1, 7094, 7096, 5006, -1, 7095, 7097, 5057, -1, 5006, 7096, 5019, -1, 5057, 7097, 5072, -1, 7097, 7098, 5072, -1, 7096, 7099, 5019, -1, 5072, 7098, 5083, -1, 5019, 7099, 5033, -1, 7098, 7100, 5083, -1, 5083, 7100, 5088, -1, 7099, 7101, 5033, -1, 5033, 7101, 5048, -1, 7100, 7102, 5088, -1, 5088, 7102, 4551, -1, 7101, 7103, 5048, -1, 7102, 2369, 4551, -1, 5048, 7103, 5067, -1, 7103, 7104, 5067, -1, 5067, 7104, 4762, -1, 7104, 7105, 4762, -1, 4762, 7105, 4779, -1, 4779, 7069, 4792, -1, 7105, 7069, 4779, -1, 4792, 7070, 4803, -1, 2248, 7106, 7107, -1, 2248, 7108, 7106, -1, 2248, 7107, 2353, -1, 7109, 7110, 7111, -1, 2250, 7108, 2248, -1, 2250, 7112, 7108, -1, 2250, 7113, 7112, -1, 4444, 4442, 2436, -1, 4444, 2436, 2468, -1, 4440, 2436, 4442, -1, 4446, 4444, 2468, -1, 4414, 7111, 7114, -1, 4437, 2436, 4440, -1, 4437, 2424, 2436, -1, 4416, 4414, 7114, -1, 4448, 4446, 2468, -1, 4448, 2468, 2506, -1, 4416, 7114, 7115, -1, 4412, 7109, 7111, -1, 4412, 7111, 4414, -1, 4436, 2424, 4437, -1, 4418, 4416, 7115, -1, 4450, 4448, 2506, -1, 4409, 7116, 7109, -1, 4409, 7109, 4412, -1, 7117, 2424, 4436, -1, 4420, 7115, 7118, -1, 4420, 4418, 7115, -1, 4408, 7116, 4409, -1, 4452, 4450, 2506, -1, 4452, 2506, 2541, -1, 4422, 4420, 7118, -1, 4422, 7118, 7119, -1, 7120, 2451, 2424, -1, 7120, 2424, 7117, -1, 4454, 4452, 2541, -1, 2278, 4498, 7113, -1, 7121, 2451, 7120, -1, 2278, 7113, 2250, -1, 7122, 7116, 4408, -1, 4456, 4454, 2541, -1, 7122, 4408, 7123, -1, 4456, 2541, 2570, -1, 4424, 4422, 7119, -1, 7124, 7122, 7123, -1, 4426, 4424, 7119, -1, 7125, 2407, 2451, -1, 7125, 2451, 7121, -1, 4458, 4456, 2570, -1, 4426, 7119, 7126, -1, 4428, 4426, 7126, -1, 7127, 2407, 7125, -1, 4428, 7126, 7128, -1, 7129, 2390, 2407, -1, 7129, 2407, 7127, -1, 4430, 4428, 7128, -1, 2297, 4498, 2278, -1, 2297, 4496, 4498, -1, 7130, 7122, 7124, -1, 7130, 7131, 7132, -1, 7130, 7133, 7131, -1, 7130, 7124, 7133, -1, 2362, 4496, 2297, -1, 7134, 7130, 7132, -1, 4494, 4460, 4458, -1, 7134, 7135, 7136, -1, 7134, 7137, 7135, -1, 7134, 7132, 7137, -1, 7138, 4496, 2362, -1, 4494, 4458, 2570, -1, 7138, 7139, 4496, -1, 7140, 7134, 7136, -1, 4495, 4462, 4460, -1, 7140, 7141, 7142, -1, 7140, 7143, 7141, -1, 7140, 7136, 7143, -1, 4495, 4460, 4494, -1, 7144, 7139, 7138, -1, 4500, 4462, 4495, -1, 7144, 7145, 7139, -1, 4500, 7146, 4462, -1, 4500, 7147, 7146, -1, 4545, 2570, 2597, -1, 7148, 7140, 7142, -1, 4545, 2597, 2625, -1, 7148, 7149, 4434, -1, 7148, 7142, 7149, -1, 7150, 7145, 7144, -1, 4545, 4494, 2570, -1, 7150, 7151, 7145, -1, 7152, 7148, 4434, -1, 4543, 4545, 2625, -1, 4543, 2625, 2653, -1, 7152, 4434, 4432, -1, 7153, 7151, 7150, -1, 4503, 7154, 7147, -1, 7155, 4430, 7128, -1, 4503, 7147, 4500, -1, 7155, 7152, 4432, -1, 7155, 4432, 4430, -1, 7156, 7157, 7151, -1, 7156, 7151, 7153, -1, 4541, 2653, 2684, -1, 4541, 2684, 2813, -1, 7158, 7155, 7128, -1, 7158, 7128, 7159, -1, 4541, 4543, 2653, -1, 4507, 7160, 7154, -1, 4507, 7161, 7160, -1, 7162, 7163, 7157, -1, 7162, 7157, 7156, -1, 7164, 7159, 7165, -1, 7164, 7158, 7159, -1, 4507, 7154, 4503, -1, 4511, 7166, 7161, -1, 4511, 7161, 4507, -1, 7167, 7163, 7162, -1, 7168, 7164, 7165, -1, 7169, 7170, 7163, -1, 7169, 7163, 7167, -1, 4539, 2813, 2830, -1, 7171, 7165, 7172, -1, 7171, 7168, 7165, -1, 4539, 4541, 2813, -1, 7173, 7171, 7172, -1, 7173, 7172, 7170, -1, 7173, 7170, 7169, -1, 4515, 7129, 7166, -1, 4515, 7166, 4511, -1, 4515, 2375, 2390, -1, 4515, 2390, 7129, -1, 4537, 2830, 2740, -1, 4537, 4539, 2830, -1, 4519, 2375, 4515, -1, 4519, 7174, 2373, -1, 4519, 2373, 2375, -1, 4535, 4537, 2740, -1, 4535, 2740, 2741, -1, 4535, 2741, 2755, -1, 4533, 2755, 2768, -1, 4533, 4535, 2755, -1, 7175, 7174, 4519, -1, 7175, 7176, 7174, -1, 7177, 7178, 7176, -1, 7177, 7176, 7175, -1, 4531, 2768, 2500, -1, 4531, 4533, 2768, -1, 7179, 7180, 7181, -1, 7179, 7181, 7178, -1, 7179, 7178, 7177, -1, 4529, 4531, 2500, -1, 4529, 2500, 2508, -1, 4529, 2508, 2516, -1, 7182, 7180, 7179, -1, 7182, 7183, 7180, -1, 4527, 4529, 2516, -1, 4527, 2516, 2807, -1, 7184, 7185, 7183, -1, 7184, 7183, 7182, -1, 4525, 2807, 2836, -1, 4525, 4527, 2807, -1, 2274, 4525, 2836, -1, 7186, 7185, 7184, -1, 7187, 7186, 7184, -1, 4523, 4525, 2274, -1, 7188, 7186, 7187, -1, 7189, 7188, 7187, -1, 7190, 7188, 7189, -1, 7191, 7190, 7189, -1, 4471, 2274, 2275, -1, 4473, 4471, 2275, -1, 4469, 4523, 2274, -1, 4469, 2274, 4471, -1, 4475, 2275, 2312, -1, 4475, 4473, 2275, -1, 4467, 4521, 4523, -1, 4467, 4523, 4469, -1, 4477, 4475, 2312, -1, 4465, 4517, 4521, -1, 4465, 4521, 4467, -1, 7192, 7190, 7191, -1, 4479, 2312, 2325, -1, 4479, 4477, 2312, -1, 7193, 4517, 4465, -1, 4481, 4479, 2325, -1, 7194, 4517, 7193, -1, 7194, 4513, 4517, -1, 4483, 4481, 2325, -1, 7195, 4513, 7194, -1, 7195, 4509, 4513, -1, 7196, 4509, 7195, -1, 7197, 4509, 7196, -1, 2339, 4483, 2325, -1, 2339, 4485, 4483, -1, 2339, 4487, 4485, -1, 7198, 7192, 7191, -1, 7198, 7191, 7199, -1, 4489, 4487, 2339, -1, 4505, 4509, 7197, -1, 7200, 4505, 7197, -1, 4498, 7200, 7113, -1, 4498, 4505, 7200, -1, 2353, 7201, 4491, -1, 2353, 7107, 7201, -1, 2353, 4489, 2339, -1, 2353, 4491, 4489, -1, 7110, 7198, 7199, -1, 7110, 7199, 7111, -1, 7202, 1787, 7203, -1, 7204, 1787, 7202, -1, 7203, 1787, 1757, -1, 7205, 1624, 7204, -1, 7206, 1624, 7205, -1, 7204, 1624, 1787, -1, 4443, 4445, 1845, -1, 1845, 4445, 1885, -1, 1845, 4441, 4443, -1, 4445, 4447, 1885, -1, 7207, 4415, 7208, -1, 1824, 4439, 1845, -1, 4415, 4417, 7208, -1, 1845, 4439, 4441, -1, 7208, 4417, 7209, -1, 7210, 4413, 7207, -1, 7207, 4413, 4415, -1, 1885, 4449, 1917, -1, 4447, 4449, 1885, -1, 4417, 4419, 7209, -1, 1824, 4438, 4439, -1, 7210, 4411, 4413, -1, 7211, 4411, 7210, -1, 4449, 4451, 1917, -1, 1824, 7212, 4438, -1, 7209, 4421, 7213, -1, 4419, 4421, 7209, -1, 7211, 4410, 4411, -1, 4421, 4423, 7213, -1, 1917, 4453, 1947, -1, 4451, 4453, 1917, -1, 7213, 4423, 7214, -1, 1833, 7215, 1824, -1, 1824, 7215, 7212, -1, 7211, 7216, 4410, -1, 4410, 7216, 7217, -1, 4453, 4455, 1947, -1, 1833, 7218, 7215, -1, 7206, 1648, 1624, -1, 4501, 1648, 7206, -1, 4423, 4425, 7214, -1, 1947, 4457, 1975, -1, 4455, 4457, 1947, -1, 7216, 7219, 7217, -1, 1797, 7220, 1833, -1, 4425, 4427, 7214, -1, 1833, 7220, 7218, -1, 7214, 4427, 7221, -1, 4457, 4459, 1975, -1, 4427, 4429, 7221, -1, 1797, 7222, 7220, -1, 7221, 4429, 7223, -1, 1784, 7224, 1797, -1, 4429, 4431, 7223, -1, 1797, 7224, 7222, -1, 7216, 7225, 7219, -1, 7226, 7225, 7227, -1, 7228, 7225, 7226, -1, 7219, 7225, 7228, -1, 4501, 1669, 1648, -1, 4497, 1669, 4501, -1, 7225, 7229, 7227, -1, 7230, 7229, 7231, -1, 7232, 7229, 7230, -1, 7227, 7229, 7232, -1, 4497, 1825, 1669, -1, 7229, 7233, 7231, -1, 4461, 4492, 4459, -1, 7234, 7233, 7235, -1, 7236, 7233, 7234, -1, 7231, 7233, 7236, -1, 4459, 4492, 1975, -1, 4497, 7237, 1825, -1, 7238, 7237, 4497, -1, 4463, 4493, 4461, -1, 4461, 4493, 4492, -1, 7233, 7239, 7235, -1, 7240, 7239, 4435, -1, 7235, 7239, 7240, -1, 4463, 4499, 4493, -1, 7238, 7241, 7237, -1, 7242, 4499, 4463, -1, 7243, 4499, 7242, -1, 7244, 7241, 7238, -1, 4492, 4544, 1975, -1, 7239, 7245, 4435, -1, 2004, 4544, 2038, -1, 1975, 4544, 2004, -1, 4435, 7245, 4433, -1, 7246, 7247, 7244, -1, 7244, 7247, 7241, -1, 4431, 7248, 7223, -1, 7245, 7248, 4433, -1, 2038, 4542, 2067, -1, 4544, 4542, 2038, -1, 4433, 7248, 4431, -1, 7249, 4502, 7243, -1, 7246, 7250, 7247, -1, 7243, 4502, 4499, -1, 7248, 7251, 7223, -1, 7252, 4506, 7249, -1, 7253, 4506, 7252, -1, 7223, 7251, 7254, -1, 7249, 4506, 4502, -1, 7255, 7256, 7246, -1, 7246, 7256, 7250, -1, 4542, 4540, 2067, -1, 7254, 7257, 7258, -1, 7251, 7257, 7254, -1, 2089, 4540, 2190, -1, 7255, 7259, 7256, -1, 2067, 4540, 2089, -1, 7260, 7259, 7255, -1, 7261, 4510, 7253, -1, 7257, 7262, 7258, -1, 7253, 4510, 4506, -1, 7260, 7263, 7259, -1, 7258, 7264, 7265, -1, 7262, 7264, 7258, -1, 2190, 4538, 2201, -1, 4540, 4538, 2190, -1, 7266, 7267, 7260, -1, 7260, 7267, 7263, -1, 7266, 7268, 7267, -1, 7265, 7268, 7266, -1, 7264, 7268, 7265, -1, 7261, 4514, 4510, -1, 7224, 4514, 7261, -1, 1767, 4514, 1784, -1, 1784, 4514, 7224, -1, 4538, 4536, 2201, -1, 2201, 4536, 2137, -1, 1768, 4518, 1767, -1, 7269, 4518, 1768, -1, 1767, 4518, 4514, -1, 2140, 4534, 2154, -1, 2137, 4534, 2140, -1, 4536, 4534, 2137, -1, 4534, 4532, 2154, -1, 2154, 4532, 2168, -1, 7269, 7270, 4518, -1, 7271, 7270, 7269, -1, 7271, 7272, 7270, -1, 7273, 7272, 7271, -1, 2168, 4530, 1882, -1, 4532, 4530, 2168, -1, 7274, 7275, 7273, -1, 7276, 7275, 7274, -1, 7273, 7275, 7272, -1, 1888, 4528, 1899, -1, 1882, 4528, 1888, -1, 4530, 4528, 1882, -1, 7277, 7278, 7276, -1, 7276, 7278, 7275, -1, 1899, 4526, 2224, -1, 4528, 4526, 1899, -1, 7277, 7279, 7278, -1, 7280, 7279, 7277, -1, 2224, 4524, 1643, -1, 4526, 4524, 2224, -1, 7280, 7281, 7279, -1, 4524, 1667, 1643, -1, 7281, 7282, 7279, -1, 4524, 4522, 1667, -1, 7281, 7283, 7282, -1, 7283, 7284, 7282, -1, 7283, 7285, 7284, -1, 7285, 7286, 7284, -1, 1667, 4470, 1690, -1, 4470, 4472, 1690, -1, 4522, 4468, 1667, -1, 1667, 4468, 4470, -1, 1690, 4474, 1703, -1, 4472, 4474, 1690, -1, 4520, 4466, 4522, -1, 4522, 4466, 4468, -1, 4474, 4476, 1703, -1, 4520, 4464, 4466, -1, 4516, 4464, 4520, -1, 7285, 7287, 7286, -1, 1703, 4478, 1717, -1, 4476, 4478, 1703, -1, 4516, 7288, 4464, -1, 4478, 4480, 1717, -1, 4516, 7289, 7288, -1, 4512, 7289, 4516, -1, 4480, 4482, 1717, -1, 4512, 7290, 7289, -1, 4508, 7290, 4512, -1, 4508, 7291, 7290, -1, 4508, 7292, 7291, -1, 7287, 7293, 7286, -1, 7286, 7293, 7294, -1, 4484, 1732, 4482, -1, 4486, 1732, 4484, -1, 4482, 1732, 1717, -1, 4486, 4488, 1732, -1, 4508, 4504, 7292, -1, 4504, 7295, 7292, -1, 7295, 4501, 7206, -1, 4504, 4501, 7295, -1, 7293, 7296, 7294, -1, 7294, 7296, 7207, -1, 7297, 1757, 4490, -1, 7203, 1757, 7297, -1, 4488, 1757, 1732, -1, 4490, 1757, 4488, -1, 7296, 7210, 7207, -1, 7165, 7265, 7172, -1, 7258, 7265, 7165, -1, 7172, 7266, 7170, -1, 7265, 7266, 7172, -1, 7170, 7260, 7163, -1, 7266, 7260, 7170, -1, 4518, 7270, 4519, -1, 4519, 7270, 7175, -1, 7163, 7255, 7157, -1, 7260, 7255, 7163, -1, 7175, 7272, 7177, -1, 7270, 7272, 7175, -1, 7157, 7246, 7151, -1, 7255, 7246, 7157, -1, 7177, 7275, 7179, -1, 7272, 7275, 7177, -1, 7151, 7244, 7145, -1, 7246, 7244, 7151, -1, 7179, 7278, 7182, -1, 7275, 7278, 7179, -1, 7145, 7238, 7139, -1, 7244, 7238, 7145, -1, 7182, 7279, 7184, -1, 7278, 7279, 7182, -1, 7139, 4497, 4496, -1, 7238, 4497, 7139, -1, 7184, 7282, 7187, -1, 7279, 7282, 7184, -1, 7187, 7284, 7189, -1, 7282, 7284, 7187, -1, 7189, 7286, 7191, -1, 7284, 7286, 7189, -1, 7191, 7294, 7199, -1, 7286, 7294, 7191, -1, 7199, 7207, 7111, -1, 7294, 7207, 7199, -1, 7207, 7208, 7111, -1, 7111, 7208, 7114, -1, 7208, 7209, 7114, -1, 7114, 7209, 7115, -1, 7209, 7213, 7115, -1, 7115, 7213, 7118, -1, 7213, 7214, 7118, -1, 7118, 7214, 7119, -1, 7214, 7221, 7119, -1, 7119, 7221, 7126, -1, 7221, 7223, 7126, -1, 7126, 7223, 7128, -1, 7223, 7254, 7128, -1, 7128, 7254, 7159, -1, 7254, 7258, 7159, -1, 7159, 7258, 7165, -1, 4491, 7201, 4490, -1, 4490, 7201, 7297, -1, 7297, 7107, 7203, -1, 7201, 7107, 7297, -1, 7203, 7106, 7202, -1, 7107, 7106, 7203, -1, 7202, 7108, 7204, -1, 7106, 7108, 7202, -1, 7204, 7112, 7205, -1, 7108, 7112, 7204, -1, 7205, 7113, 7206, -1, 7112, 7113, 7205, -1, 7206, 7200, 7295, -1, 7113, 7200, 7206, -1, 7295, 7197, 7292, -1, 7200, 7197, 7295, -1, 7292, 7196, 7291, -1, 7197, 7196, 7292, -1, 7291, 7195, 7290, -1, 7196, 7195, 7291, -1, 7290, 7194, 7289, -1, 7195, 7194, 7290, -1, 7289, 7193, 7288, -1, 7194, 7193, 7289, -1, 7288, 4465, 4464, -1, 7193, 4465, 7288, -1, 4462, 7146, 4463, -1, 4463, 7146, 7242, -1, 7242, 7147, 7243, -1, 7146, 7147, 7242, -1, 7243, 7154, 7249, -1, 7147, 7154, 7243, -1, 7249, 7160, 7252, -1, 7154, 7160, 7249, -1, 7252, 7161, 7253, -1, 7160, 7161, 7252, -1, 7253, 7166, 7261, -1, 7161, 7166, 7253, -1, 7261, 7129, 7224, -1, 7166, 7129, 7261, -1, 7224, 7127, 7222, -1, 7129, 7127, 7224, -1, 7222, 7125, 7220, -1, 7127, 7125, 7222, -1, 7220, 7121, 7218, -1, 7125, 7121, 7220, -1, 7218, 7120, 7215, -1, 7121, 7120, 7218, -1, 7215, 7117, 7212, -1, 7120, 7117, 7215, -1, 7212, 4436, 4438, -1, 7117, 4436, 7212, -1, 4434, 7149, 4435, -1, 4435, 7149, 7240, -1, 7240, 7142, 7235, -1, 7149, 7142, 7240, -1, 7235, 7141, 7234, -1, 7142, 7141, 7235, -1, 7234, 7143, 7236, -1, 7141, 7143, 7234, -1, 7236, 7136, 7231, -1, 7143, 7136, 7236, -1, 7231, 7135, 7230, -1, 7136, 7135, 7231, -1, 7230, 7137, 7232, -1, 7135, 7137, 7230, -1, 7232, 7132, 7227, -1, 7137, 7132, 7232, -1, 7227, 7131, 7226, -1, 7132, 7131, 7227, -1, 7226, 7133, 7228, -1, 7131, 7133, 7226, -1, 7228, 7124, 7219, -1, 7133, 7124, 7228, -1, 7219, 7123, 7217, -1, 7124, 7123, 7219, -1, 7217, 4408, 4410, -1, 7123, 4408, 7217, -1, 7298, 3250, 7299, -1, 7298, 3256, 3250, -1, 7300, 7301, 3501, -1, 7300, 3501, 3474, -1, 7302, 7300, 3474, -1, 7302, 3474, 3442, -1, 7303, 3256, 7298, -1, 7303, 3284, 3256, -1, 7304, 374, 26, -1, 7305, 3284, 7303, -1, 7305, 3312, 3284, -1, 7306, 26, 28, -1, 7307, 7302, 3442, -1, 7307, 3442, 3404, -1, 7306, 7304, 26, -1, 7308, 3312, 7305, -1, 7309, 358, 374, -1, 7309, 374, 7304, -1, 7308, 3339, 3312, -1, 7310, 7307, 3404, -1, 7311, 28, 49, -1, 7310, 3404, 3370, -1, 7311, 7306, 28, -1, 7312, 3339, 7308, -1, 7312, 3353, 3339, -1, 7313, 7310, 3370, -1, 7313, 3353, 7312, -1, 7313, 3370, 3353, -1, 7314, 358, 7309, -1, 7314, 343, 358, -1, 7315, 49, 65, -1, 7315, 7311, 49, -1, 7316, 343, 7314, -1, 7316, 327, 343, -1, 7317, 7315, 65, -1, 7317, 65, 82, -1, 7318, 327, 7316, -1, 7318, 311, 327, -1, 7319, 7317, 82, -1, 7319, 82, 97, -1, 7320, 311, 7318, -1, 7320, 295, 311, -1, 7321, 7319, 97, -1, 7321, 97, 113, -1, 7322, 295, 7320, -1, 7322, 278, 295, -1, 7323, 7321, 113, -1, 7323, 113, 129, -1, 7324, 278, 7322, -1, 7324, 262, 278, -1, 7325, 7323, 129, -1, 7325, 129, 146, -1, 7326, 246, 262, -1, 7326, 262, 7324, -1, 7327, 7325, 146, -1, 7327, 146, 162, -1, 7328, 230, 246, -1, 7328, 246, 7326, -1, 7329, 7327, 162, -1, 7329, 162, 180, -1, 7330, 230, 7328, -1, 7330, 212, 230, -1, 7331, 7329, 180, -1, 7331, 180, 196, -1, 3078, 212, 7330, -1, 3078, 210, 212, -1, 7332, 210, 3078, -1, 7333, 7331, 196, -1, 7333, 196, 205, -1, 3077, 7332, 3078, -1, 7334, 7332, 3077, -1, 7335, 205, 222, -1, 7335, 7333, 205, -1, 3466, 7334, 3077, -1, 7336, 7334, 3466, -1, 7337, 222, 239, -1, 7337, 7335, 222, -1, 3456, 7336, 3466, -1, 7338, 7336, 3456, -1, 7339, 239, 255, -1, 7339, 7337, 239, -1, 3447, 7338, 3456, -1, 7340, 7338, 3447, -1, 7341, 7339, 255, -1, 7341, 255, 271, -1, 3329, 7340, 3447, -1, 7342, 7341, 271, -1, 7343, 7340, 3329, -1, 287, 7342, 271, -1, 3298, 7343, 3329, -1, 7344, 7342, 287, -1, 7345, 7343, 3298, -1, 302, 7344, 287, -1, 3268, 7345, 3298, -1, 7346, 7344, 302, -1, 7347, 7345, 3268, -1, 319, 7346, 302, -1, 3241, 7347, 3268, -1, 7348, 7346, 319, -1, 7349, 7347, 3241, -1, 335, 7348, 319, -1, 3198, 7349, 3241, -1, 7350, 7348, 335, -1, 7351, 7349, 3198, -1, 351, 7350, 335, -1, 3134, 7351, 3198, -1, 7352, 7350, 351, -1, 7353, 7351, 3134, -1, 367, 7352, 351, -1, 3071, 7353, 3134, -1, 7354, 7352, 367, -1, 7355, 7353, 3071, -1, 12, 7354, 367, -1, 3032, 7355, 3071, -1, 7356, 7354, 12, -1, 7357, 7355, 3032, -1, 14, 7356, 12, -1, 2997, 7357, 3032, -1, 7358, 7356, 14, -1, 7359, 7357, 2997, -1, 39, 7358, 14, -1, 2955, 7359, 2997, -1, 7360, 7358, 39, -1, 7361, 7359, 2955, -1, 58, 7360, 39, -1, 2920, 7361, 2955, -1, 7362, 7360, 58, -1, 7363, 7361, 2920, -1, 74, 7362, 58, -1, 2919, 7363, 2920, -1, 7364, 7362, 74, -1, 7365, 7363, 2919, -1, 90, 7364, 74, -1, 2900, 7365, 2919, -1, 7366, 7364, 90, -1, 7367, 7365, 2900, -1, 7367, 2900, 2899, -1, 105, 7366, 90, -1, 7368, 7366, 105, -1, 7369, 7367, 2899, -1, 7369, 2899, 3568, -1, 121, 7368, 105, -1, 7370, 7368, 121, -1, 7371, 7369, 3568, -1, 7371, 3568, 3561, -1, 137, 7370, 121, -1, 7372, 7370, 137, -1, 7373, 7371, 3561, -1, 7373, 3561, 3552, -1, 153, 7372, 137, -1, 7374, 7372, 153, -1, 7375, 3552, 3544, -1, 7375, 7373, 3552, -1, 169, 7374, 153, -1, 3105, 7374, 169, -1, 201, 3105, 169, -1, 7376, 7375, 3544, -1, 7376, 3544, 3536, -1, 7377, 3105, 201, -1, 7377, 3106, 3105, -1, 7378, 7376, 3536, -1, 7378, 3536, 3423, -1, 7379, 3106, 7377, -1, 7379, 3157, 3106, -1, 7380, 3423, 3415, -1, 7380, 7378, 3423, -1, 7381, 3157, 7379, -1, 7381, 3183, 3157, -1, 7382, 7380, 3415, -1, 7382, 3415, 3406, -1, 7383, 3406, 3396, -1, 7383, 7382, 3406, -1, 7384, 3213, 3183, -1, 7384, 3183, 7381, -1, 7385, 3396, 3391, -1, 7385, 7383, 3396, -1, 7386, 3235, 3213, -1, 7386, 3213, 7384, -1, 7299, 3250, 3235, -1, 7299, 3235, 7386, -1, 7301, 7385, 3391, -1, 7301, 3391, 3501, -1, 7387, 5715, 7388, -1, 5720, 5715, 7387, -1, 7389, 5620, 7390, -1, 5623, 5620, 7389, -1, 7388, 5710, 7391, -1, 5715, 5710, 7388, -1, 7390, 5615, 7392, -1, 190, 4381, 7393, -1, 5620, 5615, 7390, -1, 7392, 4368, 40, -1, 7391, 5705, 7394, -1, 5615, 4368, 7392, -1, 5710, 5705, 7391, -1, 7393, 5610, 7395, -1, 4381, 5610, 7393, -1, 7394, 5700, 7396, -1, 5705, 5700, 7394, -1, 5610, 5607, 7395, -1, 7395, 5607, 7397, -1, 7396, 5695, 7398, -1, 5700, 5695, 7396, -1, 5607, 5604, 7397, -1, 7397, 5604, 7399, -1, 7398, 5690, 7400, -1, 5695, 5690, 7398, -1, 5604, 5601, 7399, -1, 7399, 5601, 7401, -1, 5690, 5685, 7400, -1, 7400, 5685, 7402, -1, 5601, 5598, 7401, -1, 7401, 5598, 7403, -1, 5685, 5680, 7402, -1, 7402, 5680, 7404, -1, 5598, 5595, 7403, -1, 7403, 5595, 7405, -1, 5680, 5675, 7404, -1, 7404, 5675, 7406, -1, 5595, 5592, 7405, -1, 7405, 5592, 7407, -1, 5675, 5670, 7406, -1, 7406, 5670, 7408, -1, 5592, 5589, 7407, -1, 7407, 5589, 7409, -1, 5670, 5665, 7408, -1, 7408, 5665, 7410, -1, 5589, 5586, 7409, -1, 7409, 5586, 7411, -1, 5665, 5660, 7410, -1, 7410, 5660, 7412, -1, 5586, 5583, 7411, -1, 7411, 5583, 7413, -1, 5660, 5655, 7412, -1, 7412, 5655, 7414, -1, 5583, 5577, 7413, -1, 7413, 5577, 7415, -1, 5655, 5650, 7414, -1, 7414, 5650, 7416, -1, 5577, 5572, 7415, -1, 7415, 5572, 7417, -1, 5650, 5647, 7416, -1, 7416, 5647, 7418, -1, 5572, 5567, 7417, -1, 7417, 5567, 7419, -1, 5647, 5644, 7418, -1, 7418, 5644, 7420, -1, 5567, 5562, 7419, -1, 7419, 5562, 7421, -1, 5644, 5641, 7420, -1, 7420, 5641, 7422, -1, 5562, 5557, 7421, -1, 7421, 5557, 7423, -1, 5641, 5638, 7422, -1, 7422, 5638, 7424, -1, 5557, 5553, 7423, -1, 7423, 5553, 7425, -1, 5638, 5635, 7424, -1, 7424, 5635, 7426, -1, 5553, 5552, 7425, -1, 7425, 5552, 7427, -1, 7426, 5632, 7428, -1, 5635, 5632, 7426, -1, 5552, 5730, 7427, -1, 7427, 5730, 7429, -1, 7428, 5629, 7430, -1, 5632, 5629, 7428, -1, 7429, 5725, 7431, -1, 5730, 5725, 7429, -1, 7430, 5626, 7389, -1, 5629, 5626, 7430, -1, 7431, 5720, 7387, -1, 5725, 5720, 7431, -1, 5626, 5623, 7389, -1, 7432, 5883, 7433, -1, 5878, 5883, 7432, -1, 7434, 5795, 7435, -1, 5792, 5795, 7434, -1, 7433, 5888, 7436, -1, 7435, 5800, 610, -1, 5883, 5888, 7433, -1, 5795, 5800, 7435, -1, 579, 4321, 7437, -1, 5800, 4320, 610, -1, 7436, 5893, 7438, -1, 5888, 5893, 7436, -1, 7437, 5804, 7439, -1, 4321, 5804, 7437, -1, 7438, 5898, 7440, -1, 5893, 5898, 7438, -1, 5804, 5808, 7439, -1, 7439, 5808, 7441, -1, 7440, 5903, 7442, -1, 5898, 5903, 7440, -1, 5808, 5811, 7441, -1, 7441, 5811, 7443, -1, 7442, 5908, 7444, -1, 5903, 5908, 7442, -1, 5811, 5814, 7443, -1, 7443, 5814, 7445, -1, 5908, 5913, 7444, -1, 7444, 5913, 7446, -1, 5814, 5817, 7445, -1, 7445, 5817, 7447, -1, 5913, 5918, 7446, -1, 7446, 5918, 7448, -1, 5817, 5820, 7447, -1, 7447, 5820, 7449, -1, 5918, 5740, 7448, -1, 7448, 5740, 7450, -1, 5820, 5823, 7449, -1, 7449, 5823, 7451, -1, 5740, 5741, 7450, -1, 7450, 5741, 7452, -1, 5823, 5826, 7451, -1, 7451, 5826, 7453, -1, 5741, 5746, 7452, -1, 7452, 5746, 7454, -1, 5826, 5829, 7453, -1, 7453, 5829, 7455, -1, 5746, 5751, 7454, -1, 7454, 5751, 7456, -1, 5829, 5832, 7455, -1, 7455, 5832, 7457, -1, 5751, 5756, 7456, -1, 7456, 5756, 7458, -1, 5832, 5835, 7457, -1, 7457, 5835, 7459, -1, 5756, 5761, 7458, -1, 7458, 5761, 7460, -1, 5835, 5839, 7459, -1, 7459, 5839, 7461, -1, 5761, 5766, 7460, -1, 7460, 5766, 7462, -1, 5839, 5844, 7461, -1, 7461, 5844, 7463, -1, 5766, 5771, 7462, -1, 7462, 5771, 7464, -1, 5844, 5849, 7463, -1, 7463, 5849, 7465, -1, 5771, 5774, 7464, -1, 7464, 5774, 7466, -1, 5849, 5854, 7465, -1, 7465, 5854, 7467, -1, 5774, 5777, 7466, -1, 7466, 5777, 7468, -1, 5854, 5859, 7467, -1, 7467, 5859, 7469, -1, 5777, 5780, 7468, -1, 7468, 5780, 7470, -1, 5859, 5863, 7469, -1, 7469, 5863, 7471, -1, 7470, 5783, 7472, -1, 5780, 5783, 7470, -1, 5863, 5868, 7471, -1, 7471, 5868, 7473, -1, 7472, 5786, 7474, -1, 5783, 5786, 7472, -1, 7473, 5873, 7475, -1, 5868, 5873, 7473, -1, 7474, 5789, 7476, -1, 5786, 5789, 7474, -1, 7475, 5878, 7432, -1, 5873, 5878, 7475, -1, 7476, 5792, 7434, -1, 5789, 5792, 7476, -1, 467, 482, 7477, -1, 467, 7477, 7478, -1, 698, 7479, 682, -1, 698, 7480, 7479, -1, 451, 7478, 7481, -1, 451, 467, 7478, -1, 715, 7480, 698, -1, 715, 7482, 7480, -1, 435, 451, 7481, -1, 435, 7481, 7483, -1, 731, 7484, 7482, -1, 731, 7482, 715, -1, 418, 7483, 7485, -1, 1404, 7486, 7487, -1, 418, 435, 7483, -1, 746, 7488, 7484, -1, 1422, 7487, 7489, -1, 746, 7484, 731, -1, 396, 7485, 7490, -1, 1422, 1404, 7487, -1, 396, 418, 7485, -1, 394, 7488, 746, -1, 394, 7490, 7488, -1, 394, 396, 7490, -1, 1390, 7491, 7486, -1, 1390, 7486, 1404, -1, 1453, 1422, 7489, -1, 1453, 7489, 7492, -1, 1364, 7491, 1390, -1, 1364, 7493, 7491, -1, 1492, 7492, 7494, -1, 1492, 1453, 7492, -1, 1337, 7493, 1364, -1, 1337, 7495, 7493, -1, 1524, 7494, 7496, -1, 1524, 1492, 7494, -1, 1309, 7495, 1337, -1, 1309, 7497, 7495, -1, 1551, 7496, 7498, -1, 1551, 1524, 7496, -1, 1304, 7497, 1309, -1, 1304, 7499, 7497, -1, 1439, 7498, 7500, -1, 1439, 1551, 7498, -1, 1287, 7501, 7499, -1, 1287, 7499, 1304, -1, 1444, 7500, 7502, -1, 1444, 1439, 7500, -1, 1269, 7503, 7501, -1, 1269, 7501, 1287, -1, 1455, 7502, 7504, -1, 1455, 1444, 7502, -1, 1241, 7505, 7503, -1, 1241, 7503, 1269, -1, 1464, 7504, 7506, -1, 1464, 1455, 7504, -1, 1213, 7507, 7505, -1, 1213, 7505, 1241, -1, 1472, 1464, 7506, -1, 1472, 7506, 7508, -1, 1170, 7509, 7507, -1, 1170, 7507, 1213, -1, 1586, 7508, 7510, -1, 1586, 1472, 7508, -1, 1169, 569, 7509, -1, 1169, 7509, 1170, -1, 567, 569, 1169, -1, 1594, 7510, 7511, -1, 1594, 1586, 7510, -1, 7512, 567, 1169, -1, 562, 567, 7512, -1, 1602, 7511, 7513, -1, 1602, 1594, 7511, -1, 7514, 562, 7512, -1, 546, 562, 7514, -1, 1611, 7513, 7515, -1, 1611, 1602, 7513, -1, 7516, 546, 7514, -1, 531, 546, 7516, -1, 1619, 7515, 7517, -1, 1619, 1611, 7515, -1, 7518, 531, 7516, -1, 514, 531, 7518, -1, 947, 7517, 7519, -1, 947, 1619, 7517, -1, 7520, 514, 7518, -1, 948, 947, 7519, -1, 501, 514, 7520, -1, 7521, 948, 7519, -1, 7522, 501, 7520, -1, 968, 948, 7521, -1, 484, 501, 7522, -1, 7523, 968, 7521, -1, 7524, 484, 7522, -1, 969, 968, 7523, -1, 468, 484, 7524, -1, 7525, 969, 7523, -1, 7526, 468, 7524, -1, 1007, 969, 7525, -1, 453, 468, 7526, -1, 7527, 1007, 7525, -1, 7528, 453, 7526, -1, 1049, 1007, 7527, -1, 437, 453, 7528, -1, 7529, 1049, 7527, -1, 7530, 437, 7528, -1, 1081, 1049, 7529, -1, 420, 437, 7530, -1, 7531, 1081, 7529, -1, 7532, 420, 7530, -1, 1120, 1081, 7531, -1, 401, 420, 7532, -1, 7533, 1120, 7531, -1, 7534, 401, 7532, -1, 1185, 1120, 7533, -1, 399, 401, 7534, -1, 7535, 1185, 7533, -1, 7536, 399, 7534, -1, 1249, 1185, 7535, -1, 749, 399, 7536, -1, 7537, 1249, 7535, -1, 7538, 749, 7536, -1, 1291, 1249, 7537, -1, 732, 749, 7538, -1, 7539, 1291, 7537, -1, 7540, 732, 7538, -1, 1319, 1291, 7539, -1, 716, 732, 7540, -1, 7541, 1319, 7539, -1, 7542, 716, 7540, -1, 1348, 1319, 7541, -1, 700, 716, 7542, -1, 7543, 1348, 7541, -1, 7544, 700, 7542, -1, 1377, 1348, 7543, -1, 684, 7544, 7545, -1, 684, 700, 7544, -1, 7546, 1377, 7543, -1, 1495, 1377, 7546, -1, 669, 7545, 7547, -1, 669, 684, 7545, -1, 7548, 1495, 7546, -1, 1505, 1495, 7548, -1, 652, 7547, 7549, -1, 652, 669, 7547, -1, 7550, 1505, 7548, -1, 1514, 1505, 7550, -1, 636, 7549, 7551, -1, 636, 652, 7549, -1, 7552, 1514, 7550, -1, 1129, 1514, 7552, -1, 620, 7551, 7553, -1, 620, 636, 7551, -1, 7554, 1129, 7552, -1, 1130, 1129, 7554, -1, 587, 7553, 7555, -1, 587, 620, 7553, -1, 585, 1130, 7554, -1, 564, 7555, 7556, -1, 564, 587, 7555, -1, 588, 7557, 1130, -1, 588, 1130, 585, -1, 548, 7556, 7558, -1, 548, 564, 7556, -1, 618, 7559, 7557, -1, 618, 7557, 588, -1, 532, 7558, 7560, -1, 532, 548, 7558, -1, 635, 7561, 7559, -1, 635, 7559, 618, -1, 516, 7560, 7562, -1, 516, 532, 7560, -1, 650, 7563, 7561, -1, 650, 7561, 635, -1, 498, 7562, 7564, -1, 498, 516, 7562, -1, 667, 7565, 7563, -1, 667, 7563, 650, -1, 482, 498, 7564, -1, 482, 7564, 7477, -1, 682, 7479, 7565, -1, 682, 7565, 667, -1, 7566, 7567, 3826, -1, 3826, 7567, 3814, -1, 7568, 7567, 7566, -1, 3814, 7567, 7568, -1, 7569, 7570, 7571, -1, 7572, 7573, 3779, -1, 3766, 7573, 7574, -1, 3658, 7570, 3852, -1, 7574, 7573, 7572, -1, 3779, 7573, 3766, -1, 7575, 7576, 7577, -1, 7578, 7579, 7569, -1, 7574, 7576, 7580, -1, 7580, 7576, 7575, -1, 7570, 7579, 3852, -1, 7577, 7576, 7574, -1, 7581, 7582, 7583, -1, 7583, 7582, 7584, -1, 3852, 7579, 3839, -1, 7585, 7582, 7581, -1, 7569, 7579, 7570, -1, 7584, 7582, 7585, -1, 7586, 7566, 7587, -1, 7585, 7588, 3629, -1, 3629, 7588, 3619, -1, 7589, 7588, 7585, -1, 7579, 7566, 3839, -1, 3619, 7588, 7589, -1, 7590, 7591, 3589, -1, 3839, 7566, 3826, -1, 7592, 7591, 7590, -1, 7593, 7568, 7586, -1, 3578, 7591, 7592, -1, 3589, 7591, 3578, -1, 7592, 7594, 7595, -1, 7586, 7568, 7566, -1, 7596, 7594, 7597, -1, 7595, 7594, 7596, -1, 3814, 7568, 3803, -1, 7597, 7594, 7592, -1, 7598, 7599, 7593, -1, 7600, 7601, 7602, -1, 7603, 7599, 7598, -1, 7602, 7601, 7604, -1, 7605, 7601, 7600, -1, 7593, 7599, 7568, -1, 7604, 7601, 7605, -1, 7568, 7599, 3803, -1, 3760, 7606, 7607, -1, 3803, 7599, 3790, -1, 3771, 7606, 3760, -1, 7599, 7572, 3790, -1, 7605, 7606, 3771, -1, 7608, 7572, 7603, -1, 7607, 7606, 7605, -1, 7609, 7610, 3724, -1, 3724, 7610, 3711, -1, 3790, 7572, 3779, -1, 7611, 7610, 7609, -1, 7603, 7572, 7599, -1, 3711, 7610, 7611, -1, 7577, 7574, 7608, -1, 7612, 7613, 7611, -1, 7614, 7613, 7615, -1, 7608, 7574, 7572, -1, 7611, 7613, 7614, -1, 7615, 7613, 7612, -1, 3766, 7574, 3754, -1, 3674, 7616, 3675, -1, 7617, 7580, 7575, -1, 7618, 7616, 3674, -1, 7574, 7580, 3754, -1, 7619, 7620, 7618, -1, 4010, 7620, 7619, -1, 3754, 7580, 3733, -1, 7618, 7620, 7616, -1, 7580, 7621, 3733, -1, 3675, 7620, 4010, -1, 7622, 7621, 7617, -1, 7616, 7620, 3675, -1, 7617, 7621, 7580, -1, 3733, 7621, 3713, -1, 7623, 7624, 7622, -1, 7625, 7624, 7623, -1, 3693, 7624, 3666, -1, 3713, 7624, 3693, -1, 7621, 7624, 3713, -1, 7622, 7624, 7621, -1, 7626, 7627, 7625, -1, 7624, 7627, 3666, -1, 3666, 7627, 3649, -1, 7625, 7627, 7624, -1, 7583, 7584, 7626, -1, 7627, 7584, 3649, -1, 7626, 7584, 7627, -1, 3649, 7584, 3639, -1, 7584, 7585, 3639, -1, 7628, 7585, 7581, -1, 3639, 7585, 3629, -1, 7629, 7589, 7628, -1, 7628, 7589, 7585, -1, 3619, 7589, 3609, -1, 7630, 7631, 7629, -1, 7632, 7631, 7630, -1, 3609, 7631, 3599, -1, 7629, 7631, 7589, -1, 7589, 7631, 3609, -1, 7633, 7590, 7632, -1, 3599, 7590, 3589, -1, 7632, 7590, 7631, -1, 7631, 7590, 3599, -1, 7633, 7592, 7590, -1, 7597, 7592, 7633, -1, 3578, 7592, 3574, -1, 7592, 7595, 3574, -1, 7634, 7595, 7596, -1, 3574, 7595, 3874, -1, 7635, 7636, 7634, -1, 7634, 7636, 7595, -1, 7595, 7636, 3874, -1, 3874, 7636, 3857, -1, 7637, 7638, 7635, -1, 7639, 7638, 7637, -1, 7635, 7638, 7636, -1, 3836, 7638, 3816, -1, 3857, 7638, 3836, -1, 7636, 7638, 3857, -1, 7640, 7641, 7639, -1, 7639, 7641, 7638, -1, 7638, 7641, 3816, -1, 3816, 7641, 3796, -1, 7602, 7604, 7640, -1, 7641, 7604, 3796, -1, 3796, 7604, 3788, -1, 7640, 7604, 7641, -1, 7642, 7605, 7600, -1, 3788, 7605, 3771, -1, 7604, 7605, 3788, -1, 7643, 7607, 7642, -1, 3760, 7607, 3748, -1, 7642, 7607, 7605, -1, 7607, 7644, 3748, -1, 7645, 7644, 7643, -1, 7646, 7644, 7645, -1, 3748, 7644, 3735, -1, 7643, 7644, 7607, -1, 7647, 7609, 7646, -1, 3735, 7609, 3724, -1, 7646, 7609, 7644, -1, 7644, 7609, 3735, -1, 7647, 7611, 7609, -1, 7612, 7611, 7647, -1, 3711, 7611, 3689, -1, 7611, 7614, 3689, -1, 7648, 7614, 7615, -1, 3689, 7614, 3688, -1, 7614, 7618, 3688, -1, 7648, 7618, 7614, -1, 7619, 7618, 7648, -1, 3688, 7618, 3674, -1, 3658, 7649, 7570, -1, 3657, 7649, 3658, -1, 7649, 7650, 7570, -1, 7571, 7650, 4029, -1, 4029, 7650, 3657, -1, 3657, 7650, 7649, -1, 7570, 7650, 7571, -1, 7587, 7651, 7578, -1, 7578, 7651, 7579, -1, 7566, 7651, 7587, -1, 7579, 7651, 7566, -1, 7652, 7653, 7654, -1, 7003, 7655, 7001, -1, 7656, 7657, 7658, -1, 7658, 7657, 7659, -1, 7660, 7655, 7003, -1, 7661, 7662, 7663, -1, 7578, 7662, 7587, -1, 7587, 7662, 7661, -1, 7663, 7662, 7664, -1, 7659, 7665, 7008, -1, 7666, 7667, 7660, -1, 7635, 7668, 7669, -1, 7634, 7668, 7635, -1, 7660, 7667, 7655, -1, 7669, 7668, 7652, -1, 7652, 7668, 7653, -1, 7666, 7670, 7667, -1, 7664, 7670, 7666, -1, 7656, 7671, 7657, -1, 7655, 7672, 7001, -1, 7653, 7671, 7656, -1, 7657, 7673, 7659, -1, 6998, 7672, 4012, -1, 7659, 7673, 7665, -1, 7001, 7672, 6998, -1, 7569, 7674, 7578, -1, 7665, 7675, 7008, -1, 7578, 7674, 7662, -1, 7662, 7674, 7664, -1, 7008, 7675, 7006, -1, 7664, 7674, 7670, -1, 7667, 7676, 7655, -1, 7634, 7677, 7668, -1, 7668, 7677, 7653, -1, 7672, 7676, 4012, -1, 7653, 7677, 7671, -1, 7655, 7676, 7672, -1, 4012, 7676, 4017, -1, 7667, 7678, 7676, -1, 7671, 7679, 7657, -1, 7670, 7678, 7667, -1, 7657, 7679, 7673, -1, 7676, 7678, 4017, -1, 7673, 7680, 7665, -1, 4017, 7678, 4023, -1, 7665, 7680, 7675, -1, 4029, 7681, 7571, -1, 7571, 7681, 7569, -1, 7670, 7681, 7678, -1, 7674, 7681, 7670, -1, 7675, 7682, 7006, -1, 7678, 7681, 4023, -1, 7569, 7681, 7674, -1, 4023, 7681, 4031, -1, 4031, 7681, 4029, -1, 7596, 7683, 7634, -1, 7634, 7683, 7677, -1, 7677, 7683, 7671, -1, 7671, 7683, 7679, -1, 7673, 7684, 7680, -1, 7679, 7684, 7673, -1, 7680, 7685, 7675, -1, 7675, 7685, 7682, -1, 7682, 7686, 7006, -1, 7006, 7686, 7004, -1, 7683, 7687, 7679, -1, 7596, 7687, 7683, -1, 7679, 7687, 7684, -1, 7684, 7688, 7680, -1, 7680, 7688, 7685, -1, 7685, 7689, 7682, -1, 7682, 7689, 7686, -1, 7686, 7690, 7004, -1, 7597, 7691, 7596, -1, 7684, 7691, 7688, -1, 7596, 7691, 7687, -1, 7687, 7691, 7684, -1, 7685, 7692, 7689, -1, 7688, 7692, 7685, -1, 7689, 7693, 7686, -1, 7686, 7693, 7690, -1, 7004, 7694, 7002, -1, 7690, 7694, 7004, -1, 7597, 7695, 7691, -1, 7691, 7695, 7688, -1, 7688, 7695, 7692, -1, 7692, 7696, 7689, -1, 7689, 7696, 7693, -1, 7693, 7697, 7690, -1, 7690, 7697, 7694, -1, 7694, 7698, 7002, -1, 7695, 7699, 7692, -1, 7633, 7699, 7597, -1, 7597, 7699, 7695, -1, 7692, 7699, 7696, -1, 7693, 7700, 7697, -1, 7696, 7700, 7693, -1, 7697, 7701, 7694, -1, 7694, 7701, 7698, -1, 7698, 7702, 7002, -1, 7002, 7702, 7000, -1, 7696, 7703, 7700, -1, 7699, 7703, 7696, -1, 7633, 7703, 7699, -1, 7700, 7704, 7697, -1, 7697, 7704, 7701, -1, 7701, 7705, 7698, -1, 7698, 7705, 7702, -1, 7702, 7706, 7000, -1, 7703, 7707, 7700, -1, 7632, 7707, 7633, -1, 7633, 7707, 7703, -1, 7700, 7707, 7704, -1, 7704, 7708, 7701, -1, 7701, 7708, 7705, -1, 7705, 7709, 7702, -1, 7702, 7709, 7706, -1, 7706, 7710, 7000, -1, 7000, 7710, 6997, -1, 7704, 7711, 7708, -1, 7632, 7711, 7707, -1, 7707, 7711, 7704, -1, 7708, 7712, 7705, -1, 7705, 7712, 7709, -1, 7709, 7713, 7706, -1, 7706, 7713, 7710, -1, 7710, 7714, 6997, -1, 7630, 7715, 7632, -1, 7632, 7715, 7711, -1, 7708, 7715, 7712, -1, 7711, 7715, 7708, -1, 7709, 7716, 7713, -1, 7712, 7716, 7709, -1, 7713, 7717, 7710, -1, 7710, 7717, 7714, -1, 7714, 7718, 6997, -1, 6997, 7718, 6995, -1, 7630, 7719, 7715, -1, 7715, 7719, 7712, -1, 7712, 7719, 7716, -1, 7716, 7720, 7713, -1, 7713, 7720, 7717, -1, 7717, 7721, 7714, -1, 7714, 7721, 7718, -1, 7718, 7722, 6995, -1, 7629, 7723, 7630, -1, 7719, 7723, 7716, -1, 7716, 7723, 7720, -1, 7630, 7723, 7719, -1, 7720, 7724, 7717, -1, 7717, 7724, 7721, -1, 7718, 7725, 7722, -1, 7721, 7725, 7718, -1, 7722, 7726, 6995, -1, 6995, 7726, 6993, -1, 7629, 7727, 7723, -1, 7720, 7727, 7724, -1, 7723, 7727, 7720, -1, 7724, 7728, 7721, -1, 7721, 7728, 7725, -1, 7722, 7729, 7726, -1, 7725, 7729, 7722, -1, 7726, 7730, 6993, -1, 7628, 7731, 7629, -1, 7629, 7731, 7727, -1, 7724, 7731, 7728, -1, 7727, 7731, 7724, -1, 7728, 7732, 7725, -1, 7725, 7732, 7729, -1, 7729, 7733, 7726, -1, 7726, 7733, 7730, -1, 7730, 7734, 6993, -1, 6993, 7734, 6992, -1, 7731, 7735, 7728, -1, 7628, 7735, 7731, -1, 7728, 7735, 7732, -1, 7729, 7736, 7733, -1, 7732, 7736, 7729, -1, 7733, 7737, 7730, -1, 7730, 7737, 7734, -1, 7734, 7738, 6992, -1, 7581, 7739, 7628, -1, 7735, 7739, 7732, -1, 7628, 7739, 7735, -1, 7732, 7739, 7736, -1, 7736, 7740, 7733, -1, 7733, 7740, 7737, -1, 7737, 7741, 7734, -1, 7734, 7741, 7738, -1, 6998, 4012, 4014, -1, 7738, 7742, 6992, -1, 6992, 7742, 7031, -1, 7739, 7743, 7736, -1, 7581, 7743, 7739, -1, 7736, 7743, 7740, -1, 7737, 7744, 7741, -1, 7740, 7744, 7737, -1, 7741, 7745, 7738, -1, 7738, 7745, 7742, -1, 3916, 7746, 4005, -1, 7742, 7747, 7031, -1, 4005, 7746, 6999, -1, 7583, 7748, 7581, -1, 3922, 7749, 3916, -1, 7581, 7748, 7743, -1, 7743, 7748, 7740, -1, 7740, 7748, 7744, -1, 3916, 7749, 7746, -1, 7744, 7750, 7741, -1, 3922, 7751, 7749, -1, 7741, 7750, 7745, -1, 3926, 7751, 3922, -1, 7745, 7752, 7742, -1, 7742, 7752, 7747, -1, 7746, 7753, 6999, -1, 6999, 7753, 6996, -1, 7747, 7754, 7031, -1, 7619, 7755, 4010, -1, 7031, 7754, 7029, -1, 3929, 7755, 3926, -1, 4010, 7755, 3929, -1, 3926, 7755, 7751, -1, 7744, 7756, 7750, -1, 7583, 7756, 7748, -1, 7748, 7756, 7744, -1, 7749, 7757, 7746, -1, 7750, 7758, 7745, -1, 7746, 7757, 7753, -1, 7745, 7758, 7752, -1, 7752, 7759, 7747, -1, 7749, 7760, 7757, -1, 7747, 7759, 7754, -1, 7751, 7760, 7749, -1, 7754, 7761, 7029, -1, 6996, 7762, 6994, -1, 7626, 7763, 7583, -1, 7753, 7762, 6996, -1, 7583, 7763, 7756, -1, 7751, 7764, 7760, -1, 7756, 7763, 7750, -1, 7755, 7764, 7751, -1, 7750, 7763, 7758, -1, 7648, 7764, 7619, -1, 7752, 7765, 7759, -1, 7619, 7764, 7755, -1, 7758, 7765, 7752, -1, 7757, 7766, 7753, -1, 7753, 7766, 7762, -1, 7759, 7767, 7754, -1, 7754, 7767, 7761, -1, 7760, 7768, 7757, -1, 7761, 7769, 7029, -1, 7029, 7769, 7027, -1, 7757, 7768, 7766, -1, 7626, 7770, 7763, -1, 6994, 7771, 6991, -1, 7763, 7770, 7758, -1, 7758, 7770, 7765, -1, 7762, 7771, 6994, -1, 7765, 7772, 7759, -1, 7760, 7773, 7768, -1, 7759, 7772, 7767, -1, 7615, 7773, 7648, -1, 7764, 7773, 7760, -1, 7648, 7773, 7764, -1, 7766, 7774, 7762, -1, 7767, 7775, 7761, -1, 7762, 7774, 7771, -1, 7761, 7775, 7769, -1, 7769, 7776, 7027, -1, 7768, 7777, 7766, -1, 7625, 7778, 7626, -1, 7766, 7777, 7774, -1, 7626, 7778, 7770, -1, 7770, 7778, 7765, -1, 7765, 7778, 7772, -1, 6991, 7779, 6990, -1, 7771, 7779, 6991, -1, 7772, 7780, 7767, -1, 7768, 7781, 7777, -1, 7767, 7780, 7775, -1, 7615, 7781, 7773, -1, 7769, 7782, 7776, -1, 7612, 7781, 7615, -1, 7775, 7782, 7769, -1, 7773, 7781, 7768, -1, 7774, 7783, 7771, -1, 7027, 7784, 7025, -1, 7771, 7783, 7779, -1, 7776, 7784, 7027, -1, 7778, 7785, 7772, -1, 7772, 7785, 7780, -1, 7777, 7786, 7774, -1, 7625, 7785, 7778, -1, 7774, 7786, 7783, -1, 7775, 7787, 7782, -1, 7779, 7788, 6990, -1, 7780, 7787, 7775, -1, 6990, 7788, 7030, -1, 7784, 7789, 7025, -1, 7777, 7790, 7786, -1, 7781, 7790, 7777, -1, 7776, 7791, 7784, -1, 7647, 7790, 7612, -1, 7612, 7790, 7781, -1, 7783, 7792, 7779, -1, 7782, 7791, 7776, -1, 7779, 7792, 7788, -1, 7623, 7793, 7625, -1, 7625, 7793, 7785, -1, 7780, 7793, 7787, -1, 7785, 7793, 7780, -1, 7791, 7794, 7784, -1, 7784, 7794, 7789, -1, 7783, 7795, 7792, -1, 7786, 7795, 7783, -1, 7787, 7796, 7782, -1, 7782, 7796, 7791, -1, 7788, 7797, 7030, -1, 7030, 7797, 7028, -1, 7789, 7798, 7025, -1, 7790, 7799, 7786, -1, 7647, 7799, 7790, -1, 7025, 7798, 7023, -1, 7646, 7799, 7647, -1, 7786, 7799, 7795, -1, 7791, 7800, 7794, -1, 7796, 7800, 7791, -1, 7793, 7801, 7787, -1, 7788, 7802, 7797, -1, 7623, 7801, 7793, -1, 7792, 7802, 7788, -1, 7787, 7801, 7796, -1, 7795, 7803, 7792, -1, 7798, 7804, 7023, -1, 7792, 7803, 7802, -1, 7789, 7805, 7798, -1, 7794, 7805, 7789, -1, 7797, 7806, 7028, -1, 7028, 7806, 7026, -1, 7622, 7807, 7623, -1, 7799, 7808, 7795, -1, 7796, 7807, 7800, -1, 7646, 7808, 7799, -1, 7795, 7808, 7803, -1, 7623, 7807, 7801, -1, 7801, 7807, 7796, -1, 7645, 7808, 7646, -1, 7798, 7809, 7804, -1, 7797, 7810, 7806, -1, 7805, 7809, 7798, -1, 7802, 7810, 7797, -1, 7800, 7811, 7794, -1, 7794, 7811, 7805, -1, 7803, 7812, 7802, -1, 7802, 7812, 7810, -1, 7805, 7813, 7809, -1, 7811, 7813, 7805, -1, 7804, 7814, 7023, -1, 7026, 7815, 7024, -1, 7806, 7815, 7026, -1, 7023, 7814, 7021, -1, 7808, 7816, 7803, -1, 7622, 7817, 7807, -1, 7643, 7816, 7645, -1, 7803, 7816, 7812, -1, 7807, 7817, 7800, -1, 7645, 7816, 7808, -1, 7810, 7818, 7806, -1, 7800, 7817, 7811, -1, 7806, 7818, 7815, -1, 7814, 7819, 7021, -1, 7617, 7820, 7622, -1, 7622, 7820, 7817, -1, 7811, 7820, 7813, -1, 7817, 7820, 7811, -1, 7804, 7821, 7814, -1, 7809, 7821, 7804, -1, 7810, 7822, 7818, -1, 7812, 7822, 7810, -1, 7024, 7823, 7022, -1, 7821, 7824, 7814, -1, 7815, 7823, 7024, -1, 7814, 7824, 7819, -1, 7642, 7825, 7643, -1, 7816, 7825, 7812, -1, 7813, 7826, 7809, -1, 7643, 7825, 7816, -1, 7812, 7825, 7822, -1, 7809, 7826, 7821, -1, 7818, 7827, 7815, -1, 7815, 7827, 7823, -1, 7821, 7828, 7824, -1, 7826, 7828, 7821, -1, 7822, 7829, 7818, -1, 7819, 7830, 7021, -1, 7021, 7830, 7019, -1, 7818, 7829, 7827, -1, 7617, 7831, 7820, -1, 7820, 7831, 7813, -1, 7813, 7831, 7826, -1, 7022, 7832, 7020, -1, 7823, 7832, 7022, -1, 7642, 7833, 7825, -1, 7600, 7833, 7642, -1, 7825, 7833, 7822, -1, 7830, 7834, 7019, -1, 7822, 7833, 7829, -1, 7575, 7835, 7617, -1, 7617, 7835, 7831, -1, 7832, 7836, 7020, -1, 7826, 7835, 7828, -1, 7020, 7836, 7018, -1, 7831, 7835, 7826, -1, 7819, 7837, 7830, -1, 7823, 7838, 7832, -1, 7824, 7837, 7819, -1, 7827, 7838, 7823, -1, 7837, 7839, 7830, -1, 7830, 7839, 7834, -1, 7832, 7840, 7836, -1, 7838, 7840, 7832, -1, 7828, 7841, 7824, -1, 7829, 7842, 7827, -1, 7824, 7841, 7837, -1, 7827, 7842, 7838, -1, 7837, 7843, 7839, -1, 7841, 7843, 7837, -1, 7838, 7844, 7840, -1, 7842, 7844, 7838, -1, 7836, 7845, 7018, -1, 7019, 7846, 7017, -1, 7834, 7846, 7019, -1, 7828, 7847, 7841, -1, 7600, 7848, 7833, -1, 7833, 7848, 7829, -1, 7829, 7848, 7842, -1, 7575, 7847, 7835, -1, 7835, 7847, 7828, -1, 7602, 7848, 7600, -1, 7841, 7849, 7843, -1, 7845, 7850, 7018, -1, 7577, 7849, 7575, -1, 7575, 7849, 7847, -1, 7847, 7849, 7841, -1, 7018, 7850, 7016, -1, 7839, 7851, 7834, -1, 7842, 7852, 7844, -1, 7848, 7852, 7842, -1, 7602, 7852, 7848, -1, 7834, 7851, 7846, -1, 7836, 7853, 7845, -1, 7840, 7853, 7836, -1, 7839, 7854, 7851, -1, 7843, 7854, 7839, -1, 7853, 7855, 7845, -1, 7845, 7855, 7850, -1, 7846, 7856, 7017, -1, 7017, 7856, 7015, -1, 7844, 7857, 7840, -1, 7577, 7858, 7849, -1, 7840, 7857, 7853, -1, 7849, 7858, 7843, -1, 7843, 7858, 7854, -1, 7853, 7859, 7855, -1, 7851, 7860, 7846, -1, 7857, 7859, 7853, -1, 7850, 7861, 7016, -1, 7846, 7860, 7856, -1, 7852, 7862, 7844, -1, 7854, 7863, 7851, -1, 7640, 7862, 7602, -1, 7602, 7862, 7852, -1, 7844, 7862, 7857, -1, 7851, 7863, 7860, -1, 7856, 7864, 7015, -1, 7016, 7865, 7014, -1, 7861, 7865, 7016, -1, 7015, 7864, 7013, -1, 7640, 7866, 7862, -1, 7608, 7867, 7577, -1, 7857, 7866, 7859, -1, 7858, 7867, 7854, -1, 7862, 7866, 7857, -1, 7855, 7868, 7850, -1, 7854, 7867, 7863, -1, 7850, 7868, 7861, -1, 7577, 7867, 7858, -1, 7860, 7869, 7856, -1, 7856, 7869, 7864, -1, 7868, 7870, 7861, -1, 7861, 7870, 7865, -1, 7863, 7871, 7860, -1, 7860, 7871, 7869, -1, 7855, 7872, 7868, -1, 7859, 7872, 7855, -1, 7864, 7873, 7013, -1, 7865, 7874, 7014, -1, 7013, 7873, 7011, -1, 7603, 7875, 7608, -1, 7868, 7876, 7870, -1, 7608, 7875, 7867, -1, 7872, 7876, 7868, -1, 7863, 7875, 7871, -1, 7867, 7875, 7863, -1, 7639, 7877, 7640, -1, 7864, 7878, 7873, -1, 7859, 7877, 7872, -1, 7640, 7877, 7866, -1, 7869, 7878, 7864, -1, 7866, 7877, 7859, -1, 7014, 7879, 7012, -1, 7871, 7880, 7869, -1, 7874, 7879, 7014, -1, 7870, 7881, 7865, -1, 7869, 7880, 7878, -1, 7865, 7881, 7874, -1, 7873, 7882, 7011, -1, 7639, 7883, 7877, -1, 7011, 7882, 7009, -1, 7872, 7883, 7876, -1, 7877, 7883, 7872, -1, 7598, 7884, 7603, -1, 7603, 7884, 7875, -1, 7871, 7884, 7880, -1, 7881, 7885, 7874, -1, 7875, 7884, 7871, -1, 7874, 7885, 7879, -1, 7878, 7886, 7873, -1, 7873, 7886, 7882, -1, 7870, 7887, 7881, -1, 7876, 7887, 7870, -1, 7878, 7888, 7886, -1, 7879, 7889, 7012, -1, 7880, 7888, 7878, -1, 7881, 7890, 7885, -1, 7887, 7890, 7881, -1, 7882, 7891, 7009, -1, 7637, 7892, 7639, -1, 7009, 7891, 7007, -1, 7639, 7892, 7883, -1, 7883, 7892, 7876, -1, 7593, 7893, 7598, -1, 7876, 7892, 7887, -1, 7598, 7893, 7884, -1, 7884, 7893, 7880, -1, 7880, 7893, 7888, -1, 7886, 7894, 7882, -1, 7885, 7895, 7879, -1, 7882, 7894, 7891, -1, 7879, 7895, 7889, -1, 7012, 7896, 7010, -1, 7889, 7896, 7012, -1, 7886, 7897, 7894, -1, 7888, 7897, 7886, -1, 7637, 7898, 7892, -1, 7887, 7898, 7890, -1, 7891, 7899, 7007, -1, 7892, 7898, 7887, -1, 7885, 7900, 7895, -1, 7007, 7899, 7005, -1, 7890, 7900, 7885, -1, 7586, 7901, 7593, -1, 7593, 7901, 7893, -1, 7893, 7901, 7888, -1, 7889, 7654, 7896, -1, 7888, 7901, 7897, -1, 7891, 7902, 7899, -1, 7895, 7654, 7889, -1, 7894, 7902, 7891, -1, 7896, 7658, 7010, -1, 7897, 7663, 7894, -1, 7637, 7903, 7898, -1, 7890, 7903, 7900, -1, 7635, 7903, 7637, -1, 7894, 7663, 7902, -1, 7898, 7903, 7890, -1, 7895, 7652, 7654, -1, 7005, 7660, 7003, -1, 7899, 7660, 7005, -1, 7900, 7652, 7895, -1, 7654, 7656, 7896, -1, 7587, 7661, 7586, -1, 7586, 7661, 7901, -1, 7897, 7661, 7663, -1, 7901, 7661, 7897, -1, 7896, 7656, 7658, -1, 7658, 7659, 7010, -1, 7899, 7666, 7660, -1, 7010, 7659, 7008, -1, 7902, 7666, 7899, -1, 7903, 7669, 7900, -1, 7635, 7669, 7903, -1, 7900, 7669, 7652, -1, 7902, 7664, 7666, -1, 7654, 7653, 7656, -1, 7663, 7664, 7902, -1, 7904, 7905, 7906, -1, 7904, 7906, 7907, -1, 7908, 4296, 7909, -1, 7908, 7910, 7911, -1, 7908, 4259, 4296, -1, 7908, 7909, 7910, -1, 7912, 7907, 4672, -1, 7913, 7911, 7905, -1, 7913, 7905, 7904, -1, 7914, 7904, 7907, -1, 7914, 7907, 7912, -1, 7915, 7908, 7911, -1, 7915, 7911, 7913, -1, 7915, 4259, 7908, -1, 7916, 4672, 4671, -1, 7916, 7912, 4672, -1, 4280, 3657, 3659, -1, 7917, 7913, 7904, -1, 7917, 7904, 7914, -1, 7918, 7914, 7912, -1, 7918, 7912, 7916, -1, 7919, 7915, 7913, -1, 7919, 4259, 7915, -1, 7919, 7913, 7917, -1, 7919, 4257, 4259, -1, 7920, 7916, 4671, -1, 7921, 7917, 7914, -1, 7921, 7914, 7918, -1, 7922, 7918, 7916, -1, 7922, 7916, 7920, -1, 7923, 7919, 7917, -1, 7923, 7917, 7921, -1, 7923, 4257, 7919, -1, 7924, 4671, 4707, -1, 7924, 7920, 4671, -1, 7925, 7921, 7918, -1, 7925, 7918, 7922, -1, 7926, 7922, 7920, -1, 7926, 7920, 7924, -1, 7927, 4295, 4257, -1, 7927, 7921, 7925, -1, 7927, 4257, 7923, -1, 7927, 7923, 7921, -1, 7928, 7924, 4707, -1, 7929, 7925, 7922, -1, 7929, 7922, 7926, -1, 7930, 7926, 7924, -1, 7930, 7924, 7928, -1, 7931, 4295, 7927, -1, 7931, 7925, 7929, -1, 7931, 7927, 7925, -1, 7932, 4707, 4706, -1, 7932, 7928, 4707, -1, 7933, 7929, 7926, -1, 7933, 7926, 7930, -1, 7934, 7930, 7928, -1, 7934, 7928, 7932, -1, 7935, 7929, 7933, -1, 7935, 4295, 7931, -1, 7935, 4293, 4295, -1, 7935, 7931, 7929, -1, 7936, 7932, 4706, -1, 7937, 7930, 7934, -1, 7937, 7933, 7930, -1, 7938, 7934, 7932, -1, 7938, 7932, 7936, -1, 7939, 7935, 7933, -1, 7939, 4293, 7935, -1, 7939, 7933, 7937, -1, 7940, 4706, 4705, -1, 7940, 7936, 4706, -1, 7941, 7937, 7934, -1, 7941, 7934, 7938, -1, 7942, 7938, 7936, -1, 7942, 7936, 7940, -1, 7943, 4293, 7939, -1, 7943, 7937, 7941, -1, 7943, 7939, 7937, -1, 7943, 4253, 4293, -1, 7944, 7940, 4705, -1, 7945, 7938, 7942, -1, 7945, 7941, 7938, -1, 7946, 7942, 7940, -1, 7946, 7940, 7944, -1, 7947, 7941, 7945, -1, 7947, 7943, 7941, -1, 7947, 4253, 7943, -1, 7948, 4705, 4703, -1, 7948, 7944, 4705, -1, 7949, 7945, 7942, -1, 7949, 7942, 7946, -1, 7950, 7946, 7944, -1, 7950, 7944, 7948, -1, 7951, 7947, 7945, -1, 7951, 7945, 7949, -1, 7951, 4253, 7947, -1, 7951, 4252, 4253, -1, 7952, 7948, 4703, -1, 7953, 7949, 7946, -1, 7953, 7946, 7950, -1, 7954, 7950, 7948, -1, 7954, 7948, 7952, -1, 7955, 7951, 7949, -1, 7955, 7949, 7953, -1, 7955, 4252, 7951, -1, 7956, 4703, 4701, -1, 7956, 7952, 4703, -1, 7957, 7953, 7950, -1, 7957, 7950, 7954, -1, 7958, 7954, 7952, -1, 7958, 7952, 7956, -1, 7959, 7955, 7953, -1, 7959, 4292, 4252, -1, 7959, 7953, 7957, -1, 7959, 4252, 7955, -1, 7960, 7956, 4701, -1, 7961, 7957, 7954, -1, 7961, 7954, 7958, -1, 7962, 7958, 7956, -1, 7962, 7956, 7960, -1, 7963, 4292, 7959, -1, 7963, 7957, 7961, -1, 7963, 7959, 7957, -1, 7964, 4701, 4699, -1, 7964, 7960, 4701, -1, 7965, 7961, 7958, -1, 7965, 7958, 7962, -1, 7966, 7960, 7964, -1, 7966, 7962, 7960, -1, 7967, 7963, 7961, -1, 7967, 7961, 7965, -1, 7967, 4291, 4292, -1, 7967, 4292, 7963, -1, 7968, 7964, 4699, -1, 7969, 7965, 7962, -1, 7969, 7962, 7966, -1, 7970, 7966, 7964, -1, 7970, 7964, 7968, -1, 7971, 7965, 7969, -1, 7971, 4291, 7967, -1, 7971, 7967, 7965, -1, 7972, 7968, 4699, -1, 7972, 4699, 4697, -1, 7973, 7966, 7970, -1, 7973, 7969, 7966, -1, 7974, 7970, 7968, -1, 3675, 4242, 3677, -1, 7975, 3858, 3855, -1, 7974, 7968, 7972, -1, 7976, 7969, 7973, -1, 7976, 7971, 7969, -1, 7976, 4291, 7971, -1, 7975, 3855, 4704, -1, 7976, 4289, 4291, -1, 7977, 3861, 3858, -1, 7978, 7973, 7970, -1, 7978, 7970, 7974, -1, 7977, 3858, 7975, -1, 7979, 3865, 3861, -1, 7980, 7972, 4697, -1, 7979, 3861, 7977, -1, 7981, 3865, 7979, -1, 7982, 7976, 7973, -1, 7981, 3659, 3865, -1, 7982, 7973, 7978, -1, 7982, 4289, 7976, -1, 7981, 4280, 3659, -1, 7983, 7974, 7972, -1, 7984, 7975, 4704, -1, 7984, 4704, 4702, -1, 7983, 7972, 7980, -1, 7985, 7977, 7975, -1, 7986, 7980, 4697, -1, 7985, 7975, 7984, -1, 7986, 4697, 4695, -1, 7987, 7978, 7974, -1, 7988, 7977, 7985, -1, 7987, 7974, 7983, -1, 7988, 7979, 7977, -1, 7989, 7983, 7980, -1, 7990, 7979, 7988, -1, 7990, 4310, 4280, -1, 7989, 7980, 7986, -1, 7990, 4280, 7981, -1, 7990, 7981, 7979, -1, 7991, 7982, 7978, -1, 7991, 4289, 7982, -1, 7992, 7984, 4702, -1, 7991, 7978, 7987, -1, 7992, 4702, 4700, -1, 7991, 4288, 4289, -1, 7993, 7983, 7989, -1, 7994, 7985, 7984, -1, 7993, 7987, 7983, -1, 7994, 7984, 7992, -1, 7995, 7986, 4695, -1, 7996, 7988, 7985, -1, 7996, 7985, 7994, -1, 7997, 7991, 7987, -1, 7997, 4288, 7991, -1, 7998, 7988, 7996, -1, 7997, 7987, 7993, -1, 7998, 4310, 7990, -1, 7999, 7995, 4695, -1, 7998, 7990, 7988, -1, 7998, 4309, 4310, -1, 7999, 4695, 4694, -1, 8000, 7989, 7986, -1, 8001, 4700, 4698, -1, 8001, 7992, 4700, -1, 8000, 7986, 7995, -1, 8002, 7995, 7999, -1, 8002, 8000, 7995, -1, 8003, 7992, 8001, -1, 8004, 7993, 7989, -1, 8003, 7994, 7992, -1, 8004, 7989, 8000, -1, 8005, 7994, 8003, -1, 8005, 7996, 7994, -1, 8006, 7998, 7996, -1, 8007, 8004, 8000, -1, 8006, 4309, 7998, -1, 8006, 7996, 8005, -1, 8006, 4275, 4309, -1, 8007, 8000, 8002, -1, 8008, 7997, 7993, -1, 8008, 4288, 7997, -1, 8009, 4698, 4696, -1, 8008, 4286, 4288, -1, 8008, 7993, 8004, -1, 8009, 8001, 4698, -1, 8010, 7999, 4694, -1, 8011, 8004, 8007, -1, 8012, 8003, 8001, -1, 8011, 8008, 8004, -1, 8012, 8001, 8009, -1, 8011, 4286, 8008, -1, 8013, 8010, 4694, -1, 8014, 8005, 8003, -1, 8013, 4694, 4692, -1, 8014, 8003, 8012, -1, 8015, 8002, 7999, -1, 8016, 8006, 8005, -1, 8016, 4275, 8006, -1, 8016, 8005, 8014, -1, 8015, 7999, 8010, -1, 8016, 4274, 4275, -1, 8017, 8009, 4696, -1, 8018, 8010, 8013, -1, 8017, 4696, 4693, -1, 8018, 8015, 8010, -1, 8019, 8002, 8015, -1, 8019, 8007, 8002, -1, 8020, 8009, 8017, -1, 8021, 8019, 8015, -1, 8020, 8012, 8009, -1, 8022, 8012, 8020, -1, 8021, 8015, 8018, -1, 8022, 8014, 8012, -1, 8023, 4284, 4286, -1, 8023, 8011, 8007, -1, 8024, 4274, 8016, -1, 8023, 4286, 8011, -1, 8024, 8014, 8022, -1, 8023, 8007, 8019, -1, 8024, 4308, 4274, -1, 8024, 8016, 8014, -1, 8025, 8013, 4692, -1, 8026, 4284, 8023, -1, 8026, 8019, 8021, -1, 8027, 4693, 4691, -1, 8027, 8017, 4693, -1, 8026, 8023, 8019, -1, 8028, 4692, 4690, -1, 8029, 8017, 8027, -1, 8028, 8025, 4692, -1, 8030, 8018, 8013, -1, 8029, 8020, 8017, -1, 8031, 8022, 8020, -1, 8030, 8013, 8025, -1, 8031, 8020, 8029, -1, 8032, 8030, 8025, -1, 8032, 8025, 8028, -1, 8033, 4308, 8024, -1, 8033, 8024, 8022, -1, 8034, 8021, 8018, -1, 8033, 4306, 4308, -1, 8034, 8018, 8030, -1, 8033, 8022, 8031, -1, 8035, 8034, 8030, -1, 8035, 8030, 8032, -1, 8036, 4691, 4689, -1, 8036, 8027, 4691, -1, 8037, 4284, 8026, -1, 8037, 8026, 8021, -1, 8037, 8021, 8034, -1, 8038, 8029, 8027, -1, 8037, 4279, 4284, -1, 8038, 8027, 8036, -1, 8039, 8028, 4690, -1, 8040, 8031, 8029, -1, 8041, 8034, 8035, -1, 8040, 8029, 8038, -1, 8041, 8037, 8034, -1, 8042, 8033, 8031, -1, 8041, 4279, 8037, -1, 8042, 8031, 8040, -1, 8042, 4267, 4306, -1, 8043, 8032, 8028, -1, 8042, 4306, 8033, -1, 8044, 8036, 4689, -1, 8043, 8028, 8039, -1, 8044, 4689, 4687, -1, 8045, 8035, 8032, -1, 8045, 8032, 8043, -1, 8046, 8041, 8035, -1, 8047, 8036, 8044, -1, 8046, 8035, 8045, -1, 8046, 4279, 8041, -1, 8046, 4240, 4279, -1, 8047, 8038, 8036, -1, 8048, 8040, 8038, -1, 8049, 4690, 4688, -1, 8049, 8039, 4690, -1, 8048, 8038, 8047, -1, 8050, 8042, 8040, -1, 8050, 4271, 4267, -1, 8051, 8043, 8039, -1, 8051, 8039, 8049, -1, 8050, 4267, 8042, -1, 8050, 8040, 8048, -1, 8052, 4687, 4685, -1, 8052, 8044, 4687, -1, 8053, 8045, 8043, -1, 8053, 8043, 8051, -1, 8054, 8052, 4685, -1, 8055, 8045, 8053, -1, 8055, 8046, 8045, -1, 8056, 8044, 8052, -1, 8055, 4240, 8046, -1, 8056, 8047, 8044, -1, 8055, 4239, 4240, -1, 8057, 4688, 4686, -1, 8057, 8049, 4688, -1, 8058, 8056, 8052, -1, 8059, 8049, 8057, -1, 8058, 8052, 8054, -1, 8059, 8051, 8049, -1, 8060, 8048, 8047, -1, 8060, 8047, 8056, -1, 8061, 8051, 8059, -1, 8061, 8053, 8051, -1, 8062, 8056, 8058, -1, 8062, 8060, 8056, -1, 8063, 4305, 4271, -1, 8064, 8055, 8053, -1, 8063, 4271, 8050, -1, 8064, 8053, 8061, -1, 8063, 8050, 8048, -1, 8064, 4239, 8055, -1, 8063, 8048, 8060, -1, 8064, 4270, 4239, -1, 8065, 4685, 4683, -1, 8066, 4686, 4684, -1, 8065, 8054, 4685, -1, 8066, 8057, 4686, -1, 8067, 4304, 4305, -1, 8067, 4305, 8063, -1, 8068, 8059, 8057, -1, 8067, 8060, 8062, -1, 8067, 8063, 8060, -1, 8068, 8057, 8066, -1, 8069, 8065, 4683, -1, 8070, 8061, 8059, -1, 8071, 8054, 8065, -1, 8070, 8059, 8068, -1, 8071, 8058, 8054, -1, 8072, 8064, 8061, -1, 8073, 8065, 8069, -1, 8072, 4270, 8064, -1, 8072, 4262, 4270, -1, 8072, 8061, 8070, -1, 8073, 8071, 8065, -1, 8074, 4684, 4682, -1, 8075, 8058, 8071, -1, 8074, 8066, 4684, -1, 8075, 8062, 8058, -1, 8076, 8071, 8073, -1, 8077, 8066, 8074, -1, 8077, 8068, 8066, -1, 8076, 8075, 8071, -1, 8078, 8067, 8062, -1, 8078, 8062, 8075, -1, 8078, 4304, 8067, -1, 8079, 8068, 8077, -1, 8079, 8070, 8068, -1, 8080, 4683, 4681, -1, 8080, 8069, 4683, -1, 8081, 8070, 8079, -1, 8082, 8078, 8075, -1, 8081, 4234, 4262, -1, 8082, 8075, 8076, -1, 8081, 8072, 8070, -1, 8082, 4304, 8078, -1, 8081, 4262, 8072, -1, 8082, 4302, 4304, -1, 8083, 8080, 4681, -1, 8084, 4682, 4680, -1, 8084, 8074, 4682, -1, 8085, 8069, 8080, -1, 8086, 8074, 8084, -1, 8085, 8073, 8069, -1, 8086, 8077, 8074, -1, 8087, 8085, 8080, -1, 8087, 8080, 8083, -1, 8088, 8077, 8086, -1, 8089, 8076, 8073, -1, 8088, 8079, 8077, -1, 8089, 8073, 8085, -1, 8090, 8079, 8088, -1, 8090, 4233, 4234, -1, 8091, 8085, 8087, -1, 8090, 4234, 8081, -1, 8091, 8089, 8085, -1, 8090, 8081, 8079, -1, 8092, 8082, 8076, -1, 8092, 4302, 8082, -1, 8092, 8076, 8089, -1, 8093, 4680, 4678, -1, 8094, 4681, 4679, -1, 8093, 8084, 4680, -1, 8095, 8084, 8093, -1, 8095, 8086, 8084, -1, 8094, 8083, 4681, -1, 8096, 8089, 8091, -1, 8096, 4302, 8092, -1, 8096, 8092, 8089, -1, 8097, 8088, 8086, -1, 8096, 4301, 4302, -1, 8098, 8087, 8083, -1, 8098, 8083, 8094, -1, 8097, 8086, 8095, -1, 8099, 8090, 8088, -1, 8099, 4233, 8090, -1, 8099, 8088, 8097, -1, 8099, 4249, 4233, -1, 8100, 8094, 4679, -1, 8101, 4678, 4676, -1, 8102, 8091, 8087, -1, 8102, 8087, 8098, -1, 8101, 8093, 4678, -1, 8103, 8095, 8093, -1, 8104, 8098, 8094, -1, 8104, 8094, 8100, -1, 8103, 8093, 8101, -1, 8105, 8096, 8091, -1, 8105, 4301, 8096, -1, 8105, 8091, 8102, -1, 8106, 8095, 8103, -1, 8107, 8098, 8104, -1, 8107, 8102, 8098, -1, 8106, 8097, 8095, -1, 8108, 8099, 8097, -1, 8108, 4249, 8099, -1, 8108, 8097, 8106, -1, 8109, 4679, 4677, -1, 8109, 8100, 4679, -1, 8108, 4243, 4249, -1, 8110, 4674, 3662, -1, 8110, 4676, 4674, -1, 8110, 8101, 4676, -1, 8111, 4301, 8105, -1, 8111, 4299, 4301, -1, 8111, 8105, 8102, -1, 8110, 3662, 3665, -1, 8111, 8102, 8107, -1, 8112, 8100, 8109, -1, 8112, 8104, 8100, -1, 8113, 8103, 8101, -1, 8113, 8110, 3665, -1, 8113, 3665, 3669, -1, 8113, 8101, 8110, -1, 8114, 8106, 8103, -1, 8115, 8109, 4677, -1, 8114, 8103, 8113, -1, 8116, 8104, 8112, -1, 8114, 8113, 3669, -1, 8114, 3669, 3672, -1, 8116, 8107, 8104, -1, 8117, 8108, 8106, -1, 8117, 4243, 8108, -1, 8117, 8114, 3672, -1, 8117, 3672, 3677, -1, 8118, 8112, 8109, -1, 8117, 8106, 8114, -1, 8117, 3677, 4242, -1, 8117, 4242, 4243, -1, 8118, 8109, 8115, -1, 8119, 4299, 8111, -1, 8119, 8111, 8107, -1, 8119, 8107, 8116, -1, 8120, 4677, 4675, -1, 8120, 8115, 4677, -1, 8121, 8116, 8112, -1, 8121, 8112, 8118, -1, 8122, 8118, 8115, -1, 8122, 8115, 8120, -1, 8123, 4299, 8119, -1, 8123, 4297, 4299, -1, 8123, 8116, 8121, -1, 8123, 8119, 8116, -1, 8124, 8120, 4675, -1, 8125, 8121, 8118, -1, 8125, 8118, 8122, -1, 8126, 8120, 8124, -1, 8126, 8122, 8120, -1, 8127, 8123, 8121, -1, 8127, 4297, 8123, -1, 8127, 8121, 8125, -1, 8128, 4675, 4673, -1, 8128, 8124, 4675, -1, 8129, 8122, 8126, -1, 8129, 8125, 8122, -1, 8130, 8126, 8124, -1, 8130, 8124, 8128, -1, 8131, 8127, 8125, -1, 8131, 4297, 8127, -1, 8131, 8125, 8129, -1, 8131, 4296, 4297, -1, 7906, 8128, 4673, -1, 7910, 8126, 8130, -1, 7910, 8129, 8126, -1, 7905, 8130, 8128, -1, 7905, 8128, 7906, -1, 7909, 8129, 7910, -1, 7909, 4296, 8131, -1, 7909, 8131, 8129, -1, 7907, 4673, 4672, -1, 7907, 7906, 4673, -1, 7911, 7910, 8130, -1, 7911, 8130, 7905, -1, 8132, 8133, 8134, -1, 8135, 8136, 8137, -1, 8135, 8137, 8138, -1, 8135, 8139, 8136, -1, 8135, 8140, 8139, -1, 8132, 8134, 8141, -1, 8142, 8138, 8143, -1, 8142, 8144, 8140, -1, 8142, 8145, 8144, -1, 8142, 8135, 8138, -1, 8142, 8140, 8135, -1, 8146, 8147, 8148, -1, 8146, 8148, 8149, -1, 8150, 4605, 4601, -1, 8146, 8149, 8151, -1, 8152, 7341, 7342, -1, 8153, 8146, 8151, -1, 8152, 8154, 7341, -1, 8153, 8147, 8146, -1, 8155, 8148, 8147, -1, 8156, 8157, 8154, -1, 8155, 8137, 8158, -1, 8156, 8154, 8152, -1, 8155, 8158, 8148, -1, 8159, 8153, 8151, -1, 8159, 8147, 8153, -1, 8160, 8141, 8157, -1, 8159, 8161, 8162, -1, 8159, 8151, 8161, -1, 8159, 8162, 8147, -1, 8163, 8137, 8155, -1, 8163, 8143, 8138, -1, 8160, 8157, 8156, -1, 8163, 8138, 8137, -1, 8164, 8132, 8141, -1, 8165, 8163, 8155, -1, 8164, 8141, 8160, -1, 8166, 8162, 8167, -1, 8168, 4605, 8169, -1, 8168, 4609, 4605, -1, 8166, 8147, 8162, -1, 8170, 8167, 8171, -1, 8170, 8166, 8167, -1, 8172, 7344, 7346, -1, 8172, 8173, 7344, -1, 8174, 8175, 8166, -1, 8174, 8166, 8170, -1, 8176, 8177, 8173, -1, 8176, 8173, 8172, -1, 8178, 8170, 8171, -1, 8178, 8174, 8170, -1, 8178, 8171, 8179, -1, 8178, 8179, 8180, -1, 8181, 8174, 8178, -1, 8181, 8175, 8174, -1, 8181, 8182, 8175, -1, 8181, 8178, 8180, -1, 8183, 8184, 8177, -1, 8181, 8180, 8185, -1, 8183, 8177, 8176, -1, 8186, 8160, 8156, -1, 8187, 8184, 8183, -1, 8187, 8188, 8184, -1, 8189, 8186, 8190, -1, 8189, 8191, 8164, -1, 8189, 8160, 8186, -1, 8189, 8164, 8160, -1, 8192, 8172, 7346, -1, 8189, 8193, 8191, -1, 8189, 8194, 8193, -1, 8195, 8188, 8187, -1, 8195, 8196, 8188, -1, 8197, 8172, 8192, -1, 8197, 8176, 8172, -1, 8198, 4613, 8199, -1, 8198, 8196, 8195, -1, 8198, 8199, 8196, -1, 8200, 8177, 8184, -1, 8201, 8202, 8194, -1, 8203, 7346, 7348, -1, 8201, 8204, 8202, -1, 8201, 8188, 8204, -1, 8203, 8192, 7346, -1, 8201, 8200, 8184, -1, 8201, 8205, 8200, -1, 8206, 8176, 8197, -1, 8201, 8184, 8188, -1, 8207, 4609, 8208, -1, 8207, 8208, 8209, -1, 8206, 8183, 8176, -1, 8207, 8210, 4609, -1, 8211, 8197, 8192, -1, 8212, 8194, 8202, -1, 8212, 8209, 8193, -1, 8212, 8207, 8209, -1, 8211, 8192, 8203, -1, 8212, 8202, 8213, -1, 8212, 8213, 8210, -1, 8212, 8210, 8207, -1, 8212, 8193, 8194, -1, 8214, 8187, 8183, -1, 8215, 8216, 8217, -1, 8215, 8218, 8216, -1, 8214, 8183, 8206, -1, 8215, 8217, 8219, -1, 8220, 8197, 8211, -1, 8221, 8222, 8218, -1, 8221, 8223, 8222, -1, 8221, 8218, 8215, -1, 8220, 8206, 8197, -1, 8224, 8195, 8187, -1, 8224, 8187, 8214, -1, 8225, 8221, 8215, -1, 8226, 8214, 8206, -1, 8226, 8206, 8220, -1, 8227, 8198, 8195, -1, 8227, 8195, 8224, -1, 8227, 4617, 4613, -1, 8227, 4613, 8198, -1, 8228, 8219, 8229, -1, 8228, 8229, 8230, -1, 8231, 8203, 7348, -1, 8228, 8230, 8232, -1, 8233, 8224, 8214, -1, 8233, 8214, 8226, -1, 8234, 8228, 8232, -1, 8235, 8211, 8203, -1, 8234, 8236, 8228, -1, 8234, 8232, 8237, -1, 8235, 8203, 8231, -1, 8234, 8237, 8238, -1, 8239, 8240, 8241, -1, 8239, 8232, 8240, -1, 8242, 8227, 8224, -1, 8239, 8241, 8243, -1, 8242, 8224, 8233, -1, 8242, 4617, 8227, -1, 8244, 8220, 8211, -1, 8244, 8211, 8235, -1, 8245, 8232, 8239, -1, 8245, 8237, 8232, -1, 8245, 8238, 8237, -1, 8246, 7348, 7350, -1, 8246, 8231, 7348, -1, 8247, 8245, 8239, -1, 8248, 8226, 8220, -1, 8248, 8220, 8244, -1, 8249, 8243, 8250, -1, 8249, 8250, 8251, -1, 8252, 8235, 8231, -1, 8252, 8231, 8246, -1, 8253, 8233, 8226, -1, 8253, 8226, 8248, -1, 8254, 8244, 8235, -1, 8255, 8251, 8256, -1, 8254, 8235, 8252, -1, 8255, 8257, 8249, -1, 8255, 8249, 8251, -1, 8258, 8242, 8233, -1, 8258, 4617, 8242, -1, 8258, 8233, 8253, -1, 8258, 4621, 4617, -1, 8259, 8255, 8256, -1, 8260, 8248, 8244, -1, 8259, 8261, 8262, -1, 8259, 8256, 8261, -1, 8260, 8244, 8254, -1, 8263, 8257, 8255, -1, 8263, 8262, 8264, -1, 8263, 8265, 8257, -1, 8263, 8259, 8262, -1, 8266, 8246, 7350, -1, 8263, 8255, 8259, -1, 8267, 8268, 8269, -1, 8270, 8253, 8248, -1, 8267, 8261, 8268, -1, 8270, 8248, 8260, -1, 8267, 8269, 8271, -1, 8272, 8264, 8262, -1, 8273, 8252, 8246, -1, 8273, 8246, 8266, -1, 8272, 8261, 8267, -1, 8272, 8262, 8261, -1, 8274, 8258, 8253, -1, 8274, 4621, 8258, -1, 8274, 8253, 8270, -1, 8275, 8272, 8267, -1, 8276, 8254, 8252, -1, 8276, 8252, 8273, -1, 8277, 8271, 8278, -1, 8277, 8278, 8279, -1, 8280, 7350, 7352, -1, 8280, 8266, 7350, -1, 8281, 8260, 8254, -1, 8281, 8254, 8276, -1, 8282, 8279, 8283, -1, 8282, 8277, 8279, -1, 8284, 8273, 8266, -1, 8284, 8266, 8280, -1, 8285, 8270, 8260, -1, 8286, 8277, 8282, -1, 8286, 8287, 8277, -1, 8285, 8260, 8281, -1, 8288, 8283, 8289, -1, 8290, 8276, 8273, -1, 8288, 8289, 8291, -1, 8290, 8273, 8284, -1, 8288, 8286, 8282, -1, 8288, 8282, 8283, -1, 8292, 4621, 8274, -1, 8293, 8291, 8294, -1, 8292, 8274, 8270, -1, 8292, 4625, 4621, -1, 8293, 8288, 8291, -1, 8292, 8270, 8285, -1, 8293, 8287, 8286, -1, 8293, 8295, 8287, -1, 8293, 8286, 8288, -1, 8296, 8280, 7352, -1, 8297, 8298, 8299, -1, 8297, 8300, 8301, -1, 8302, 8276, 8290, -1, 8297, 8299, 8300, -1, 8303, 8298, 8297, -1, 8302, 8281, 8276, -1, 8303, 8297, 8301, -1, 8304, 8299, 8298, -1, 8305, 8280, 8296, -1, 8305, 8284, 8280, -1, 8304, 8306, 8299, -1, 8304, 8289, 8306, -1, 8307, 8308, 8309, -1, 8307, 8301, 8308, -1, 8310, 8281, 8302, -1, 8307, 8309, 8298, -1, 8307, 8298, 8303, -1, 8307, 8303, 8301, -1, 8310, 8285, 8281, -1, 8311, 8291, 8289, -1, 8312, 8284, 8305, -1, 8311, 8294, 8291, -1, 8311, 8289, 8304, -1, 8312, 8290, 8284, -1, 8313, 8292, 8285, -1, 8313, 4625, 8292, -1, 8313, 8285, 8310, -1, 8314, 8296, 7352, -1, 8315, 8311, 8304, -1, 8314, 7352, 7354, -1, 8316, 8309, 8317, -1, 8316, 8298, 8309, -1, 8318, 8302, 8290, -1, 8318, 8290, 8312, -1, 8319, 8296, 8314, -1, 8320, 8316, 8317, -1, 8319, 8305, 8296, -1, 8320, 8317, 8321, -1, 8322, 8302, 8318, -1, 3108, 7374, 3105, -1, 8322, 8310, 8302, -1, 8323, 8312, 8305, -1, 8323, 8305, 8319, -1, 8324, 8316, 8320, -1, 8324, 8325, 8316, -1, 8326, 4625, 8313, -1, 8326, 8313, 8310, -1, 8326, 8310, 8322, -1, 8326, 4629, 4625, -1, 8327, 8328, 8329, -1, 8327, 8320, 8321, -1, 8330, 8314, 7354, -1, 8327, 8324, 8320, -1, 8327, 8321, 8328, -1, 8331, 8329, 8332, -1, 8333, 8318, 8312, -1, 8331, 8327, 8329, -1, 8333, 8312, 8323, -1, 8331, 8325, 8324, -1, 8331, 8334, 8325, -1, 8331, 8324, 8327, -1, 8335, 8336, 8337, -1, 8335, 8337, 8338, -1, 8339, 8319, 8314, -1, 8335, 8340, 8341, -1, 8335, 8341, 8336, -1, 8335, 8342, 8340, -1, 8339, 8314, 8330, -1, 8335, 8338, 8342, -1, 8343, 8344, 8345, -1, 8343, 8338, 8337, -1, 8346, 3076, 3078, -1, 8343, 8345, 8338, -1, 8347, 8322, 8318, -1, 8347, 8318, 8333, -1, 8343, 4655, 8344, -1, 8348, 8337, 8336, -1, 8348, 8349, 8350, -1, 8348, 8336, 8349, -1, 8346, 3078, 7330, -1, 8348, 4659, 4655, -1, 8348, 8350, 4659, -1, 8351, 3367, 3076, -1, 8348, 8343, 8337, -1, 8352, 8319, 8339, -1, 8348, 4655, 8343, -1, 8352, 8323, 8319, -1, 8353, 8354, 8355, -1, 8353, 8356, 8357, -1, 8353, 8355, 8358, -1, 8353, 8359, 8356, -1, 8360, 8326, 8322, -1, 8353, 8358, 8359, -1, 8360, 4629, 8326, -1, 8353, 8361, 8354, -1, 8351, 3076, 8346, -1, 8353, 8357, 8361, -1, 8362, 3371, 3367, -1, 8360, 8322, 8347, -1, 8363, 8350, 8364, -1, 8363, 8357, 8356, -1, 8365, 7354, 7356, -1, 8363, 8364, 8357, -1, 8365, 8330, 7354, -1, 8363, 4659, 8350, -1, 8366, 8363, 8356, -1, 8362, 3367, 8351, -1, 8366, 4659, 8363, -1, 8367, 3373, 3371, -1, 8366, 8368, 4663, -1, 8369, 8333, 8323, -1, 8366, 8356, 8359, -1, 8366, 8370, 8368, -1, 8366, 8359, 8370, -1, 8369, 8323, 8352, -1, 8366, 4663, 4659, -1, 8371, 8372, 8373, -1, 8367, 3371, 8362, -1, 8371, 8374, 8372, -1, 8371, 8373, 8375, -1, 8376, 3375, 3373, -1, 8371, 8377, 8374, -1, 8378, 8330, 8365, -1, 8371, 8375, 8144, -1, 8376, 3373, 8367, -1, 8378, 8339, 8330, -1, 8371, 8145, 8377, -1, 8371, 8144, 8145, -1, 8379, 8368, 8380, -1, 8379, 4663, 8368, -1, 8381, 3377, 3375, -1, 8381, 3378, 3377, -1, 8379, 8380, 8374, -1, 8381, 4595, 3378, -1, 8382, 8347, 8333, -1, 8379, 8374, 8377, -1, 8383, 8379, 8377, -1, 8381, 3375, 8376, -1, 8382, 8333, 8369, -1, 8383, 8143, 4667, -1, 8383, 4663, 8379, -1, 8383, 4667, 4663, -1, 8383, 8377, 8145, -1, 8384, 7330, 7328, -1, 8383, 8142, 8143, -1, 8383, 8145, 8142, -1, 8384, 8346, 7330, -1, 8385, 8352, 8339, -1, 8386, 8165, 8155, -1, 8386, 8387, 8165, -1, 8385, 8339, 8378, -1, 8386, 8166, 8175, -1, 8386, 8147, 8166, -1, 8386, 8175, 8182, -1, 8386, 8155, 8147, -1, 8386, 8182, 8387, -1, 8388, 8351, 8346, -1, 8389, 4629, 8360, -1, 8390, 8165, 8387, -1, 8389, 8360, 8347, -1, 8390, 8163, 8165, -1, 8389, 8347, 8382, -1, 8390, 8143, 8163, -1, 8388, 8346, 8384, -1, 8389, 4633, 4629, -1, 8390, 4667, 8143, -1, 8391, 8351, 8388, -1, 8391, 8362, 8351, -1, 8392, 8365, 7356, -1, 8393, 8390, 8387, -1, 8393, 4667, 8390, -1, 8393, 8181, 8185, -1, 8393, 8182, 8181, -1, 8393, 8387, 8182, -1, 8394, 8369, 8352, -1, 8393, 8185, 4588, -1, 8394, 8352, 8385, -1, 8393, 4588, 4667, -1, 8395, 8190, 8186, -1, 8395, 8186, 8156, -1, 8396, 8362, 8391, -1, 8395, 8397, 8190, -1, 8395, 8152, 7342, -1, 8395, 8156, 8152, -1, 8398, 8365, 8392, -1, 8396, 8367, 8362, -1, 8399, 7342, 7344, -1, 8400, 8367, 8396, -1, 8399, 8397, 8395, -1, 8398, 8378, 8365, -1, 8401, 8369, 8394, -1, 8399, 8395, 7342, -1, 8400, 8376, 8367, -1, 8401, 8382, 8369, -1, 8402, 7344, 8173, -1, 8402, 8397, 8399, -1, 8403, 8376, 8400, -1, 8402, 8177, 8200, -1, 8403, 4595, 8381, -1, 8402, 8173, 8177, -1, 8402, 8205, 8397, -1, 8403, 8381, 8376, -1, 8402, 8399, 7344, -1, 8403, 4599, 4595, -1, 8404, 8385, 8378, -1, 8402, 8200, 8205, -1, 8405, 8384, 7328, -1, 8406, 8189, 8190, -1, 8406, 8190, 8397, -1, 8404, 8378, 8398, -1, 8406, 8194, 8189, -1, 8406, 8201, 8194, -1, 8405, 7328, 7326, -1, 8406, 8397, 8205, -1, 8406, 8205, 8201, -1, 8407, 8382, 8401, -1, 8408, 8215, 8219, -1, 8407, 8389, 8382, -1, 8408, 8409, 8225, -1, 8407, 4633, 8389, -1, 8408, 8219, 8228, -1, 8408, 8225, 8215, -1, 8408, 8228, 8236, -1, 8408, 8236, 8409, -1, 8410, 8394, 8385, -1, 8411, 8225, 8409, -1, 8412, 8384, 8405, -1, 8411, 4653, 8223, -1, 8411, 8221, 8225, -1, 8412, 8388, 8384, -1, 8410, 8385, 8404, -1, 8411, 8223, 8221, -1, 8413, 4653, 8411, -1, 8413, 8411, 8409, -1, 8414, 8388, 8412, -1, 8415, 7356, 7358, -1, 8413, 8234, 8238, -1, 8413, 8409, 8236, -1, 8415, 8392, 7356, -1, 8413, 8238, 4657, -1, 8414, 8391, 8388, -1, 8413, 8236, 8234, -1, 8413, 4657, 4653, -1, 8416, 8417, 8247, -1, 8418, 8391, 8414, -1, 8416, 8257, 8265, -1, 8418, 8396, 8391, -1, 8419, 8401, 8394, -1, 8416, 8265, 8417, -1, 8416, 8243, 8249, -1, 8416, 8239, 8243, -1, 8416, 8249, 8257, -1, 8419, 8394, 8410, -1, 8416, 8247, 8239, -1, 8420, 8247, 8417, -1, 8420, 4657, 8238, -1, 8421, 8400, 8396, -1, 8422, 8392, 8415, -1, 8420, 8238, 8245, -1, 8421, 8396, 8418, -1, 8420, 8245, 8247, -1, 8422, 8398, 8392, -1, 8423, 4657, 8420, -1, 8423, 8264, 4661, -1, 8423, 8417, 8265, -1, 8424, 4603, 4599, -1, 8423, 8265, 8263, -1, 8425, 8407, 8401, -1, 8423, 8263, 8264, -1, 8425, 4637, 4633, -1, 8423, 8420, 8417, -1, 8425, 8401, 8419, -1, 8423, 4661, 4657, -1, 8425, 4633, 8407, -1, 8426, 8275, 8267, -1, 8426, 8267, 8271, -1, 8426, 8427, 8275, -1, 8428, 7326, 7324, -1, 8429, 8398, 8422, -1, 8426, 8271, 8277, -1, 8426, 8277, 8287, -1, 8428, 8405, 7326, -1, 8426, 8295, 8427, -1, 8426, 8287, 8295, -1, 8430, 4661, 8264, -1, 8429, 8404, 8398, -1, 8431, 8412, 8405, -1, 8430, 8275, 8427, -1, 8430, 8272, 8275, -1, 8430, 8264, 8272, -1, 8431, 8405, 8428, -1, 8432, 8294, 4664, -1, 8433, 8415, 7358, -1, 8432, 4661, 8430, -1, 8432, 8430, 8427, -1, 8432, 8427, 8295, -1, 8432, 8293, 8294, -1, 8434, 8414, 8412, -1, 8435, 8404, 8429, -1, 8432, 8295, 8293, -1, 8434, 8412, 8431, -1, 8432, 4664, 4661, -1, 8436, 8304, 8298, -1, 8436, 8315, 8304, -1, 8435, 8410, 8404, -1, 8436, 8437, 8315, -1, 8438, 8422, 8415, -1, 8436, 8298, 8316, -1, 8439, 8418, 8414, -1, 8436, 8316, 8325, -1, 8436, 8334, 8437, -1, 8436, 8325, 8334, -1, 8438, 8415, 8433, -1, 8440, 4664, 8294, -1, 8440, 8315, 8437, -1, 8439, 8414, 8434, -1, 8441, 8419, 8410, -1, 8440, 8294, 8311, -1, 8440, 8311, 8315, -1, 8442, 8421, 8418, -1, 8441, 8410, 8435, -1, 8443, 4668, 4664, -1, 8443, 8332, 4668, -1, 8443, 4664, 8440, -1, 8442, 8418, 8439, -1, 8443, 8440, 8437, -1, 8444, 4607, 4603, -1, 8445, 8429, 8422, -1, 8443, 8437, 8334, -1, 8443, 8331, 8332, -1, 8445, 8422, 8438, -1, 8443, 8334, 8331, -1, 8446, 7324, 7322, -1, 8447, 4637, 8425, -1, 8447, 8425, 8419, -1, 8447, 8419, 8441, -1, 8446, 8428, 7324, -1, 8448, 8431, 8428, -1, 8449, 8435, 8429, -1, 8448, 8428, 8446, -1, 8449, 8429, 8445, -1, 8450, 7358, 7360, -1, 8451, 8431, 8448, -1, 8450, 8433, 7358, -1, 8451, 8434, 8431, -1, 8452, 8441, 8435, -1, 8452, 8435, 8449, -1, 8453, 8434, 8451, -1, 8454, 8438, 8433, -1, 8454, 8433, 8450, -1, 8453, 8439, 8434, -1, 8455, 4637, 8447, -1, 8455, 8447, 8441, -1, 8455, 8441, 8452, -1, 8456, 4607, 8457, -1, 8456, 4611, 4607, -1, 8455, 4641, 4637, -1, 8458, 8450, 7360, -1, 8459, 7322, 7320, -1, 8460, 8438, 8454, -1, 8459, 8446, 7322, -1, 8461, 8446, 8459, -1, 8461, 8448, 8446, -1, 8460, 8445, 8438, -1, 8462, 8454, 8450, -1, 8463, 8459, 7320, -1, 8462, 8450, 8458, -1, 8463, 7320, 7318, -1, 8464, 8449, 8445, -1, 8464, 8445, 8460, -1, 8465, 8451, 8448, -1, 8466, 8460, 8454, -1, 8465, 8448, 8461, -1, 8466, 8454, 8462, -1, 8467, 8461, 8459, -1, 8468, 8452, 8449, -1, 8467, 8459, 8463, -1, 8469, 8451, 8465, -1, 8468, 8449, 8464, -1, 8469, 8453, 8451, -1, 8470, 8464, 8460, -1, 8470, 8460, 8466, -1, 8471, 8465, 8461, -1, 8472, 8455, 8452, -1, 8471, 8461, 8467, -1, 8472, 4641, 8455, -1, 8472, 8452, 8468, -1, 8473, 7360, 7362, -1, 8473, 8458, 7360, -1, 8474, 8465, 8471, -1, 8475, 8464, 8470, -1, 8475, 8468, 8464, -1, 8474, 8469, 8465, -1, 8476, 4611, 8477, -1, 8476, 4615, 4611, -1, 8478, 8458, 8473, -1, 8478, 8462, 8458, -1, 8479, 8463, 7318, -1, 8480, 8469, 8474, -1, 8481, 8468, 8475, -1, 8481, 4641, 8472, -1, 8481, 8472, 8468, -1, 8480, 8477, 8469, -1, 8481, 4645, 4641, -1, 8482, 8467, 8463, -1, 8483, 8473, 7362, -1, 8482, 8463, 8479, -1, 8484, 8466, 8462, -1, 8484, 8462, 8478, -1, 8485, 8476, 8477, -1, 8485, 4615, 8476, -1, 8485, 8477, 8480, -1, 8486, 8479, 7318, -1, 8486, 7318, 7316, -1, 8487, 8473, 8483, -1, 8488, 8471, 8467, -1, 8487, 8478, 8473, -1, 8488, 8467, 8482, -1, 8489, 8470, 8466, -1, 8489, 8466, 8484, -1, 8490, 8479, 8486, -1, 8490, 8482, 8479, -1, 8491, 8484, 8478, -1, 8491, 8478, 8487, -1, 8492, 8474, 8471, -1, 8493, 8475, 8470, -1, 8493, 8470, 8489, -1, 8492, 8471, 8488, -1, 8494, 8488, 8482, -1, 8494, 8482, 8490, -1, 8495, 8489, 8484, -1, 8495, 8484, 8491, -1, 8496, 8480, 8474, -1, 8497, 8481, 8475, -1, 8497, 4645, 8481, -1, 8496, 8474, 8492, -1, 8497, 8475, 8493, -1, 8498, 8492, 8488, -1, 8499, 7362, 7364, -1, 8498, 8488, 8494, -1, 8499, 8483, 7362, -1, 8500, 8489, 8495, -1, 8501, 8485, 8480, -1, 8500, 8493, 8489, -1, 8501, 4615, 8485, -1, 8501, 8480, 8496, -1, 8501, 4619, 4615, -1, 8502, 8486, 7316, -1, 8503, 8483, 8499, -1, 8503, 8487, 8483, -1, 8504, 8492, 8498, -1, 8504, 8496, 8492, -1, 8505, 8493, 8500, -1, 8505, 4645, 8497, -1, 8505, 8497, 8493, -1, 8505, 4649, 4645, -1, 8506, 8490, 8486, -1, 8507, 8499, 7364, -1, 8506, 8486, 8502, -1, 8508, 8491, 8487, -1, 8509, 8496, 8504, -1, 8509, 8501, 8496, -1, 8509, 4619, 8501, -1, 8508, 8487, 8503, -1, 8510, 8502, 7316, -1, 8510, 7316, 7314, -1, 8511, 8499, 8507, -1, 8512, 8494, 8490, -1, 8511, 8503, 8499, -1, 8512, 8490, 8506, -1, 8513, 8495, 8491, -1, 8513, 8491, 8508, -1, 8514, 8506, 8502, -1, 8514, 8502, 8510, -1, 8515, 8508, 8503, -1, 8515, 8503, 8511, -1, 8516, 8498, 8494, -1, 8516, 8494, 8512, -1, 8517, 8495, 8513, -1, 8517, 8500, 8495, -1, 8518, 8512, 8506, -1, 8519, 8508, 8515, -1, 8519, 8513, 8508, -1, 8518, 8506, 8514, -1, 8520, 8504, 8498, -1, 8521, 8500, 8517, -1, 8521, 8505, 8500, -1, 8521, 4649, 8505, -1, 8520, 8498, 8516, -1, 8522, 8513, 8519, -1, 8522, 8517, 8513, -1, 8523, 8516, 8512, -1, 8523, 8512, 8518, -1, 8524, 7364, 7366, -1, 8524, 8507, 7364, -1, 8525, 8509, 8504, -1, 8525, 4619, 8509, -1, 8525, 4623, 4619, -1, 8525, 8504, 8520, -1, 8526, 8521, 8517, -1, 8526, 4649, 8521, -1, 8527, 8510, 7314, -1, 8526, 8517, 8522, -1, 8526, 4653, 4649, -1, 8528, 8511, 8507, -1, 8528, 8507, 8524, -1, 8529, 8516, 8523, -1, 8529, 8520, 8516, -1, 8530, 8510, 8527, -1, 8531, 8515, 8511, -1, 8530, 8514, 8510, -1, 8531, 8511, 8528, -1, 8532, 4623, 8525, -1, 8218, 8519, 8515, -1, 8532, 8525, 8520, -1, 8532, 8520, 8529, -1, 8533, 8518, 8514, -1, 8218, 8515, 8531, -1, 8222, 8522, 8519, -1, 8533, 8514, 8530, -1, 8222, 8519, 8218, -1, 8534, 7314, 7309, -1, 8223, 8526, 8522, -1, 8534, 8527, 7314, -1, 8223, 4653, 8526, -1, 8223, 8522, 8222, -1, 8535, 8523, 8518, -1, 8535, 8518, 8533, -1, 8536, 8527, 8534, -1, 8536, 8530, 8527, -1, 8537, 8523, 8535, -1, 8537, 8529, 8523, -1, 8538, 8533, 8530, -1, 8538, 8530, 8536, -1, 8539, 8529, 8537, -1, 8539, 4627, 4623, -1, 8539, 4623, 8532, -1, 8539, 8532, 8529, -1, 8540, 8535, 8533, -1, 8540, 8533, 8538, -1, 8541, 8534, 7309, -1, 8542, 8537, 8535, -1, 8542, 8535, 8540, -1, 8543, 8534, 8541, -1, 8543, 8536, 8534, -1, 8544, 8537, 8542, -1, 8544, 8539, 8537, -1, 8544, 4627, 8539, -1, 8545, 8536, 8543, -1, 8545, 8538, 8536, -1, 8546, 8541, 7309, -1, 8546, 7309, 7304, -1, 8547, 8540, 8538, -1, 8547, 8538, 8545, -1, 8548, 8541, 8546, -1, 8548, 8543, 8541, -1, 8549, 8542, 8540, -1, 8549, 8540, 8547, -1, 8550, 8545, 8543, -1, 8550, 8543, 8548, -1, 8551, 8544, 8542, -1, 8551, 4627, 8544, -1, 8551, 8542, 8549, -1, 8551, 4631, 4627, -1, 8552, 8546, 7304, -1, 8553, 8547, 8545, -1, 8553, 8545, 8550, -1, 8554, 8548, 8546, -1, 8554, 8546, 8552, -1, 8555, 8549, 8547, -1, 8555, 8547, 8553, -1, 8556, 7374, 3108, -1, 8557, 8550, 8548, -1, 8557, 8548, 8554, -1, 8558, 8556, 3108, -1, 8558, 3108, 3119, -1, 8559, 8551, 8549, -1, 8559, 4631, 8551, -1, 8559, 8549, 8555, -1, 8321, 8558, 3119, -1, 8560, 7304, 7306, -1, 8560, 8552, 7304, -1, 8321, 3119, 3128, -1, 8561, 8553, 8550, -1, 8561, 8550, 8557, -1, 8328, 8321, 3128, -1, 8562, 8552, 8560, -1, 8328, 3128, 3137, -1, 8562, 8554, 8552, -1, 8329, 8328, 3137, -1, 8563, 8555, 8553, -1, 8329, 3137, 3146, -1, 8563, 8553, 8561, -1, 8332, 3151, 4668, -1, 8564, 8557, 8554, -1, 8332, 8329, 3146, -1, 8564, 8554, 8562, -1, 8332, 3146, 3150, -1, 8332, 3150, 3151, -1, 8565, 8424, 4599, -1, 8565, 8400, 8421, -1, 8566, 4631, 8559, -1, 8565, 8403, 8400, -1, 8566, 4635, 4631, -1, 8565, 4599, 8403, -1, 8566, 8559, 8555, -1, 8565, 8421, 8424, -1, 8566, 8555, 8563, -1, 8567, 8444, 4603, -1, 8567, 8442, 8444, -1, 8567, 8424, 8421, -1, 8568, 8560, 7306, -1, 8567, 4603, 8424, -1, 8567, 8421, 8442, -1, 8569, 4607, 8444, -1, 8570, 8561, 8557, -1, 8569, 8457, 4607, -1, 8570, 8557, 8564, -1, 8571, 8477, 4611, -1, 8572, 8560, 8568, -1, 8571, 4611, 8456, -1, 8573, 8574, 8575, -1, 8572, 8562, 8560, -1, 8573, 8575, 7321, -1, 8576, 8573, 7321, -1, 8577, 8561, 8570, -1, 8577, 8563, 8561, -1, 8578, 8562, 8572, -1, 8578, 8564, 8562, -1, 8579, 7321, 7323, -1, 8579, 7323, 8580, -1, 8579, 8576, 7321, -1, 8581, 8563, 8577, -1, 8581, 4635, 8566, -1, 8581, 8566, 8563, -1, 8582, 8580, 7323, -1, 8583, 7306, 7311, -1, 8582, 8584, 8580, -1, 8583, 8568, 7306, -1, 8585, 8582, 7323, -1, 8586, 8564, 8578, -1, 8586, 8570, 8564, -1, 8587, 7323, 7325, -1, 8587, 8585, 7323, -1, 8587, 7325, 8588, -1, 8589, 8568, 8583, -1, 8589, 8572, 8568, -1, 8590, 8588, 7325, -1, 8590, 8591, 8588, -1, 8592, 8590, 7325, -1, 8593, 8570, 8586, -1, 8593, 8577, 8570, -1, 8594, 8578, 8572, -1, 8594, 8572, 8589, -1, 8595, 7327, 8596, -1, 8595, 7325, 7327, -1, 8597, 4635, 8581, -1, 8595, 8592, 7325, -1, 8597, 8577, 8593, -1, 8597, 4639, 4635, -1, 8597, 8581, 8577, -1, 8598, 8596, 7327, -1, 8599, 8583, 7311, -1, 8598, 8600, 8596, -1, 8601, 8578, 8594, -1, 8601, 8586, 8578, -1, 8149, 8598, 7327, -1, 8602, 8589, 8583, -1, 8151, 8149, 7327, -1, 8151, 7327, 7329, -1, 8151, 7329, 8603, -1, 8602, 8583, 8599, -1, 8604, 8605, 8606, -1, 8607, 8593, 8586, -1, 8604, 4597, 8605, -1, 8607, 8586, 8601, -1, 8604, 8606, 8608, -1, 8604, 8609, 4597, -1, 8604, 8608, 8609, -1, 8610, 4601, 8609, -1, 8611, 8594, 8589, -1, 8610, 8150, 4601, -1, 8611, 8589, 8602, -1, 8610, 8612, 8150, -1, 8613, 4605, 8150, -1, 8614, 8597, 8593, -1, 8613, 8169, 4605, -1, 8614, 4639, 8597, -1, 8614, 8593, 8607, -1, 8615, 8601, 8594, -1, 8208, 4609, 8168, -1, 8615, 8594, 8611, -1, 8210, 8199, 4613, -1, 8210, 4613, 4609, -1, 8616, 7311, 7315, -1, 8617, 8524, 7366, -1, 8616, 8599, 7311, -1, 8618, 8607, 8601, -1, 8618, 8601, 8615, -1, 8617, 8528, 8524, -1, 8619, 8602, 8599, -1, 8619, 8599, 8616, -1, 8620, 8617, 7366, -1, 8621, 8614, 8607, -1, 8622, 7366, 7368, -1, 8621, 4639, 8614, -1, 8622, 7368, 8623, -1, 8621, 8607, 8618, -1, 8621, 4643, 4639, -1, 8622, 8620, 7366, -1, 8624, 8623, 7368, -1, 8625, 8611, 8602, -1, 8624, 8626, 8623, -1, 8625, 8602, 8619, -1, 8627, 8616, 7315, -1, 8628, 8624, 7368, -1, 8629, 8615, 8611, -1, 8630, 7368, 7370, -1, 8629, 8611, 8625, -1, 8630, 7370, 8631, -1, 8630, 8628, 7368, -1, 8632, 8616, 8627, -1, 8632, 8619, 8616, -1, 8633, 8631, 7370, -1, 8633, 8634, 8631, -1, 8635, 8618, 8615, -1, 8636, 8633, 7370, -1, 8635, 8615, 8629, -1, 8637, 8625, 8619, -1, 8637, 8619, 8632, -1, 8638, 8636, 7370, -1, 8638, 7370, 7372, -1, 8638, 7372, 8639, -1, 8640, 8621, 8618, -1, 8640, 4643, 8621, -1, 8640, 8618, 8635, -1, 8641, 8639, 7372, -1, 8641, 8642, 8639, -1, 8643, 8629, 8625, -1, 8643, 8625, 8637, -1, 8644, 7315, 7317, -1, 8300, 8641, 7372, -1, 8644, 8627, 7315, -1, 8301, 7372, 7374, -1, 8301, 8300, 7372, -1, 8301, 7374, 8556, -1, 8645, 8444, 8442, -1, 8645, 8453, 8457, -1, 8646, 8635, 8629, -1, 8645, 8439, 8453, -1, 8646, 8629, 8643, -1, 8645, 8457, 8569, -1, 8645, 8569, 8444, -1, 8645, 8442, 8439, -1, 8647, 8632, 8627, -1, 8648, 8571, 8456, -1, 8648, 8456, 8457, -1, 8647, 8627, 8644, -1, 8648, 8457, 8453, -1, 8648, 8453, 8469, -1, 8648, 8469, 8477, -1, 8648, 8477, 8571, -1, 8649, 8650, 8651, -1, 8652, 4643, 8640, -1, 8652, 4647, 4643, -1, 8652, 8640, 8635, -1, 8649, 8651, 8574, -1, 8652, 8635, 8646, -1, 8653, 8649, 8574, -1, 8653, 8573, 8576, -1, 8654, 8644, 7317, -1, 8653, 8574, 8573, -1, 8655, 8637, 8632, -1, 8655, 8632, 8647, -1, 8656, 8644, 8654, -1, 8340, 8653, 8576, -1, 8656, 8647, 8644, -1, 8657, 8579, 8580, -1, 8657, 8580, 8584, -1, 8658, 8643, 8637, -1, 8658, 8637, 8655, -1, 8659, 8340, 8576, -1, 8659, 8579, 8657, -1, 8659, 8576, 8579, -1, 8660, 8647, 8656, -1, 8661, 8657, 8584, -1, 8661, 8659, 8657, -1, 8660, 8655, 8647, -1, 8661, 8584, 8662, -1, 8663, 8643, 8658, -1, 8661, 8662, 8664, -1, 8663, 8646, 8643, -1, 8665, 8662, 8584, -1, 8665, 8664, 8662, -1, 8666, 8655, 8660, -1, 8667, 8582, 8585, -1, 8666, 8658, 8655, -1, 8667, 8665, 8584, -1, 8668, 8646, 8663, -1, 8667, 8584, 8582, -1, 8668, 4647, 8652, -1, 8668, 8652, 8646, -1, 8669, 7317, 7319, -1, 8354, 8667, 8585, -1, 8669, 8654, 7317, -1, 8670, 8663, 8658, -1, 8670, 8658, 8666, -1, 8671, 8587, 8588, -1, 8671, 8588, 8591, -1, 8672, 8654, 8669, -1, 8673, 8585, 8587, -1, 8672, 8656, 8654, -1, 8673, 8587, 8671, -1, 8674, 8668, 8663, -1, 8673, 8354, 8585, -1, 8674, 8663, 8670, -1, 8674, 4647, 8668, -1, 8675, 8591, 8676, -1, 8675, 8671, 8591, -1, 8674, 4651, 4647, -1, 8677, 8669, 7319, -1, 8675, 8673, 8671, -1, 8678, 8676, 8591, -1, 8679, 8656, 8672, -1, 8679, 8660, 8656, -1, 8678, 8680, 8676, -1, 8681, 8591, 8590, -1, 8682, 8669, 8677, -1, 8681, 8590, 8592, -1, 8681, 8678, 8591, -1, 8682, 8672, 8669, -1, 8683, 8660, 8679, -1, 8683, 8666, 8660, -1, 8684, 8672, 8682, -1, 8373, 8681, 8592, -1, 8685, 8595, 8596, -1, 8684, 8679, 8672, -1, 8686, 8666, 8683, -1, 8685, 8596, 8600, -1, 8686, 8670, 8666, -1, 8687, 8592, 8595, -1, 8687, 8373, 8592, -1, 8688, 8683, 8679, -1, 8687, 8595, 8685, -1, 8689, 8685, 8600, -1, 8688, 8679, 8684, -1, 8689, 8600, 8136, -1, 8690, 8670, 8686, -1, 8689, 8687, 8685, -1, 8690, 8674, 8670, -1, 8690, 4651, 8674, -1, 8158, 8136, 8600, -1, 8158, 8137, 8136, -1, 8575, 8677, 7319, -1, 8575, 7319, 7321, -1, 8148, 8600, 8598, -1, 8148, 8158, 8600, -1, 8691, 8686, 8683, -1, 8691, 8683, 8688, -1, 8148, 8598, 8149, -1, 8574, 8682, 8677, -1, 8574, 8677, 8575, -1, 8692, 8690, 8686, -1, 8692, 4651, 8690, -1, 8692, 8686, 8691, -1, 8692, 4655, 4651, -1, 8161, 8603, 8693, -1, 8651, 8684, 8682, -1, 8161, 8151, 8603, -1, 8651, 8682, 8574, -1, 8650, 8688, 8684, -1, 8167, 8162, 8161, -1, 8167, 8693, 8171, -1, 8650, 8684, 8651, -1, 8167, 8161, 8693, -1, 8694, 8691, 8688, -1, 8695, 8608, 8133, -1, 8695, 8609, 8608, -1, 8695, 8610, 8609, -1, 8694, 8688, 8650, -1, 8695, 8133, 8132, -1, 8695, 8132, 8612, -1, 8695, 8612, 8610, -1, 8344, 8692, 8691, -1, 8696, 8612, 8132, -1, 8344, 4655, 8692, -1, 8696, 8613, 8150, -1, 8344, 8691, 8694, -1, 8696, 8150, 8612, -1, 8696, 8132, 8164, -1, 8696, 8164, 8169, -1, 8696, 8169, 8613, -1, 8697, 8169, 8164, -1, 8697, 8168, 8169, -1, 8697, 8208, 8168, -1, 8191, 8697, 8164, -1, 8209, 8697, 8191, -1, 8209, 8208, 8697, -1, 8209, 8191, 8193, -1, 8204, 8188, 8196, -1, 8213, 8202, 8204, -1, 8213, 8204, 8196, -1, 8213, 8199, 8210, -1, 8213, 8196, 8199, -1, 8216, 8531, 8528, -1, 8216, 8218, 8531, -1, 8217, 8528, 8617, -1, 8217, 8617, 8620, -1, 8217, 8216, 8528, -1, 8219, 8217, 8620, -1, 8698, 8622, 8623, -1, 8698, 8623, 8626, -1, 8229, 8219, 8620, -1, 8229, 8622, 8698, -1, 8229, 8620, 8622, -1, 8230, 8698, 8626, -1, 8230, 8229, 8698, -1, 8230, 8626, 8699, -1, 8230, 8699, 8232, -1, 8240, 8699, 8626, -1, 8240, 8232, 8699, -1, 8241, 8624, 8628, -1, 8241, 8626, 8624, -1, 8241, 8240, 8626, -1, 8243, 8241, 8628, -1, 8700, 8630, 8631, -1, 8700, 8631, 8634, -1, 8250, 8243, 8628, -1, 8250, 8628, 8630, -1, 8250, 8630, 8700, -1, 8251, 8700, 8634, -1, 8251, 8250, 8700, -1, 8251, 8634, 8256, -1, 8268, 8256, 8634, -1, 8268, 8261, 8256, -1, 8269, 8268, 8634, -1, 8269, 8633, 8636, -1, 8269, 8634, 8633, -1, 8271, 8269, 8636, -1, 8701, 7329, 7331, -1, 8701, 8603, 7329, -1, 8702, 8638, 8639, -1, 8702, 8639, 8642, -1, 8278, 8636, 8638, -1, 8278, 8271, 8636, -1, 8703, 8693, 8603, -1, 8278, 8638, 8702, -1, 8703, 8603, 8701, -1, 8279, 8642, 8283, -1, 8704, 8171, 8693, -1, 8279, 8702, 8642, -1, 8704, 8693, 8703, -1, 8279, 8278, 8702, -1, 8306, 8283, 8642, -1, 8306, 8289, 8283, -1, 8705, 8171, 8704, -1, 8705, 8179, 8171, -1, 8706, 8180, 8179, -1, 8299, 8306, 8642, -1, 8299, 8642, 8641, -1, 8299, 8641, 8300, -1, 8706, 8179, 8705, -1, 8707, 8185, 8180, -1, 8707, 4588, 8185, -1, 8707, 8180, 8706, -1, 8707, 4586, 4588, -1, 8708, 7331, 7333, -1, 8708, 8701, 7331, -1, 8308, 8301, 8556, -1, 8709, 8703, 8701, -1, 8308, 8556, 8558, -1, 8709, 8701, 8708, -1, 8317, 8308, 8558, -1, 8710, 8704, 8703, -1, 8317, 8309, 8308, -1, 8317, 8558, 8321, -1, 8342, 8653, 8340, -1, 8710, 8703, 8709, -1, 8711, 8705, 8704, -1, 8342, 8649, 8653, -1, 8342, 8650, 8649, -1, 8711, 8704, 8710, -1, 8345, 8650, 8342, -1, 8712, 8705, 8711, -1, 8345, 8694, 8650, -1, 8712, 8706, 8705, -1, 8345, 8344, 8694, -1, 8338, 8345, 8342, -1, 8713, 8706, 8712, -1, 8713, 8707, 8706, -1, 8713, 4586, 8707, -1, 8713, 4589, 4586, -1, 8714, 8708, 7333, -1, 8714, 7333, 7335, -1, 8715, 8709, 8708, -1, 8715, 8708, 8714, -1, 8341, 8659, 8661, -1, 8341, 8661, 8664, -1, 8341, 8340, 8659, -1, 8716, 8710, 8709, -1, 8716, 8709, 8715, -1, 8349, 8341, 8664, -1, 8349, 8336, 8341, -1, 8717, 8711, 8710, -1, 8349, 8664, 8718, -1, 8349, 8718, 8350, -1, 8717, 8710, 8716, -1, 8361, 8667, 8354, -1, 8361, 8664, 8665, -1, 8719, 8712, 8711, -1, 8361, 8665, 8667, -1, 8364, 8664, 8361, -1, 8719, 8711, 8717, -1, 8720, 4593, 4589, -1, 8720, 8713, 8712, -1, 8720, 4589, 8713, -1, 8364, 8718, 8664, -1, 8364, 8350, 8718, -1, 8720, 8712, 8719, -1, 8721, 8714, 7335, -1, 8357, 8364, 8361, -1, 8721, 7335, 7337, -1, 8722, 8715, 8714, -1, 8355, 8354, 8673, -1, 8355, 8673, 8675, -1, 8722, 8714, 8721, -1, 8723, 8715, 8722, -1, 8723, 8716, 8715, -1, 8724, 8716, 8723, -1, 8725, 8355, 8675, -1, 8724, 8717, 8716, -1, 8725, 8358, 8355, -1, 8606, 8719, 8717, -1, 8725, 8675, 8676, -1, 8606, 8717, 8724, -1, 8605, 8720, 8719, -1, 8726, 8680, 8727, -1, 8605, 8719, 8606, -1, 8726, 8725, 8676, -1, 8605, 4597, 4593, -1, 8605, 4593, 8720, -1, 8726, 8676, 8680, -1, 8370, 8727, 8368, -1, 8370, 8726, 8727, -1, 8370, 8359, 8358, -1, 8728, 8721, 7337, -1, 8370, 8725, 8726, -1, 8370, 8358, 8725, -1, 8728, 7337, 7339, -1, 8372, 8680, 8678, -1, 8729, 8722, 8721, -1, 8372, 8678, 8681, -1, 8372, 8681, 8373, -1, 8380, 8727, 8680, -1, 8729, 8721, 8728, -1, 8380, 8368, 8727, -1, 8134, 8723, 8722, -1, 8380, 8680, 8372, -1, 8134, 8722, 8729, -1, 8133, 8724, 8723, -1, 8374, 8380, 8372, -1, 8133, 8723, 8134, -1, 8608, 8606, 8724, -1, 8375, 8373, 8687, -1, 8608, 8724, 8133, -1, 8375, 8687, 8689, -1, 8609, 4601, 4597, -1, 8154, 7339, 7341, -1, 8154, 8728, 7339, -1, 8139, 8375, 8689, -1, 8139, 8689, 8136, -1, 8157, 8729, 8728, -1, 8157, 8728, 8154, -1, 8140, 8375, 8139, -1, 8141, 8134, 8729, -1, 8140, 8144, 8375, -1, 8141, 8729, 8157, -1, 8730, 8731, 8732, -1, 7101, 8733, 8734, -1, 8734, 8733, 8735, -1, 8736, 8737, 8738, -1, 7094, 8737, 8736, -1, 8738, 8737, 8739, -1, 8733, 8740, 8735, -1, 8741, 8742, 8743, -1, 8735, 8740, 8744, -1, 8745, 8742, 8741, -1, 8744, 8740, 8746, -1, 8740, 8747, 8746, -1, 7099, 8747, 7101, -1, 7101, 8747, 8733, -1, 8739, 8748, 8749, -1, 8749, 8748, 8750, -1, 8733, 8747, 8740, -1, 8743, 8751, 7190, -1, 8752, 8753, 8754, -1, 8746, 8753, 8752, -1, 8747, 8753, 8746, -1, 8747, 8755, 8753, -1, 8753, 8755, 8754, -1, 7099, 8755, 8747, -1, 8756, 8757, 8745, -1, 8758, 8755, 7099, -1, 8754, 8755, 8758, -1, 8745, 8757, 8742, -1, 8759, 8760, 8761, -1, 8761, 8760, 7181, -1, 7094, 8762, 8737, -1, 7092, 8762, 7094, -1, 8739, 8762, 8748, -1, 8737, 8762, 8739, -1, 8760, 8763, 7181, -1, 8764, 8763, 8765, -1, 8742, 8766, 8743, -1, 8759, 8763, 8760, -1, 8765, 8763, 8759, -1, 8743, 8766, 8751, -1, 8763, 8767, 7181, -1, 8750, 8768, 8756, -1, 8764, 8767, 8763, -1, 7181, 8767, 7178, -1, 8756, 8768, 8757, -1, 8767, 8769, 7178, -1, 8764, 8769, 8767, -1, 8742, 8770, 8766, -1, 8771, 8769, 8764, -1, 8757, 8770, 8742, -1, 8769, 8772, 7178, -1, 8748, 8773, 8750, -1, 7178, 8772, 8774, -1, 8750, 8773, 8768, -1, 8771, 8775, 8769, -1, 8769, 8775, 8772, -1, 8772, 8775, 8774, -1, 8776, 8775, 8771, -1, 8774, 8775, 8777, -1, 8777, 8775, 8776, -1, 8751, 8778, 7190, -1, 7190, 8778, 7188, -1, 8777, 8779, 8774, -1, 8774, 8779, 7178, -1, 8779, 8780, 7178, -1, 8768, 8781, 8757, -1, 8757, 8781, 8770, -1, 8777, 8780, 8779, -1, 8782, 8780, 8777, -1, 8783, 8780, 8782, -1, 7092, 8784, 8762, -1, 8762, 8784, 8748, -1, 8780, 8785, 7178, -1, 8748, 8784, 8773, -1, 8783, 8785, 8780, -1, 8751, 8786, 8778, -1, 7178, 8785, 7176, -1, 8766, 8786, 8751, -1, 8783, 8787, 8785, -1, 8788, 8787, 8783, -1, 8785, 8787, 7176, -1, 7176, 8789, 8790, -1, 8773, 8791, 8768, -1, 8787, 8789, 7176, -1, 8790, 8792, 8793, -1, 8768, 8791, 8781, -1, 8793, 8792, 8794, -1, 8788, 8792, 8787, -1, 8789, 8792, 8790, -1, 8794, 8792, 8788, -1, 8770, 8795, 8766, -1, 8787, 8792, 8789, -1, 8790, 8796, 7176, -1, 8793, 8796, 8790, -1, 8766, 8795, 8786, -1, 8778, 8797, 7188, -1, 8796, 8798, 7176, -1, 8793, 8798, 8796, -1, 8799, 8798, 8793, -1, 7090, 8800, 7092, -1, 8773, 8800, 8791, -1, 7092, 8800, 8784, -1, 8801, 8798, 8799, -1, 8784, 8800, 8773, -1, 8798, 8802, 7176, -1, 8801, 8802, 8798, -1, 8770, 8803, 8795, -1, 8781, 8803, 8770, -1, 7176, 8802, 7174, -1, 8804, 8805, 8801, -1, 8802, 8805, 7174, -1, 8778, 8806, 8797, -1, 8801, 8805, 8802, -1, 8786, 8806, 8778, -1, 8807, 8808, 8809, -1, 7174, 8808, 8807, -1, 8805, 8808, 7174, -1, 8804, 8810, 8805, -1, 8809, 8810, 8811, -1, 8808, 8810, 8809, -1, 8791, 8812, 8781, -1, 8805, 8810, 8808, -1, 8811, 8810, 8804, -1, 8781, 8812, 8803, -1, 8786, 8813, 8806, -1, 8795, 8813, 8786, -1, 7188, 8814, 7186, -1, 8797, 8814, 7188, -1, 8791, 8815, 8812, -1, 7090, 8815, 8800, -1, 8800, 8815, 8791, -1, 8795, 8816, 8813, -1, 8803, 8816, 8795, -1, 8797, 8817, 8814, -1, 8806, 8817, 8797, -1, 8803, 8818, 8816, -1, 8812, 8818, 8803, -1, 8813, 8819, 8806, -1, 8806, 8819, 8817, -1, 8814, 8820, 7186, -1, 7088, 8821, 7090, -1, 7090, 8821, 8815, -1, 8812, 8821, 8818, -1, 8815, 8821, 8812, -1, 8813, 8822, 8819, -1, 8816, 8822, 8813, -1, 8817, 8823, 8814, -1, 8814, 8823, 8820, -1, 8818, 8824, 8816, -1, 8816, 8824, 8822, -1, 8820, 8825, 7186, -1, 7186, 8825, 7185, -1, 8819, 8826, 8817, -1, 8817, 8826, 8823, -1, 8821, 8827, 8818, -1, 7088, 8827, 8821, -1, 8818, 8827, 8824, -1, 8823, 8828, 8820, -1, 8820, 8828, 8825, -1, 8822, 8829, 8819, -1, 8819, 8829, 8826, -1, 8823, 8830, 8828, -1, 8826, 8830, 8823, -1, 8824, 8831, 8822, -1, 8822, 8831, 8829, -1, 8825, 8832, 7185, -1, 8829, 8833, 8826, -1, 8826, 8833, 8830, -1, 7086, 8834, 7088, -1, 7088, 8834, 8827, -1, 8824, 8834, 8831, -1, 8827, 8834, 8824, -1, 8828, 8835, 8825, -1, 8825, 8835, 8832, -1, 8831, 8836, 8829, -1, 8829, 8836, 8833, -1, 8832, 8837, 7185, -1, 7185, 8837, 7183, -1, 8830, 8838, 8828, -1, 8828, 8838, 8835, -1, 7086, 8839, 8834, -1, 8834, 8839, 8831, -1, 8831, 8839, 8836, -1, 8835, 8840, 8832, -1, 8832, 8840, 8837, -1, 8833, 8841, 8830, -1, 8830, 8841, 8838, -1, 8838, 8842, 8835, -1, 8835, 8842, 8840, -1, 8836, 8843, 8833, -1, 8833, 8843, 8841, -1, 8837, 8844, 7183, -1, 8841, 8845, 8838, -1, 8838, 8845, 8842, -1, 7084, 8846, 7086, -1, 7086, 8846, 8839, -1, 8839, 8846, 8836, -1, 8836, 8846, 8843, -1, 8840, 8847, 8837, -1, 8837, 8847, 8844, -1, 8841, 8848, 8845, -1, 8843, 8848, 8841, -1, 8844, 8849, 7183, -1, 7183, 8849, 7180, -1, 8842, 8850, 8840, -1, 8840, 8850, 8847, -1, 8843, 8851, 8848, -1, 8846, 8851, 8843, -1, 7084, 8851, 8846, -1, 8844, 8852, 8849, -1, 8847, 8852, 8844, -1, 8842, 8853, 8850, -1, 7073, 2394, 2395, -1, 8845, 8853, 8842, -1, 8850, 8854, 8847, -1, 2361, 8855, 2362, -1, 8847, 8854, 8852, -1, 2362, 8855, 7138, -1, 8848, 8856, 8845, -1, 2361, 8857, 8855, -1, 8845, 8856, 8853, -1, 2428, 8857, 2361, -1, 8850, 8858, 8854, -1, 8853, 8858, 8850, -1, 2430, 8859, 2428, -1, 8849, 8860, 7180, -1, 2428, 8859, 8857, -1, 2435, 8861, 2430, -1, 8848, 8862, 8856, -1, 7082, 8862, 7084, -1, 7084, 8862, 8851, -1, 2430, 8861, 8859, -1, 8851, 8862, 8848, -1, 2435, 8863, 8861, -1, 2438, 8863, 2435, -1, 8856, 8864, 8853, -1, 8855, 8865, 7138, -1, 8853, 8864, 8858, -1, 8852, 8866, 8849, -1, 7138, 8865, 7144, -1, 8849, 8866, 8860, -1, 7102, 8867, 2369, -1, 2370, 8867, 2438, -1, 8860, 8868, 7180, -1, 2369, 8867, 2370, -1, 2438, 8867, 8863, -1, 7180, 8868, 7181, -1, 8862, 8869, 8856, -1, 7082, 8869, 8862, -1, 8856, 8869, 8864, -1, 8855, 8870, 8865, -1, 8854, 8871, 8852, -1, 8857, 8870, 8855, -1, 8852, 8871, 8866, -1, 8859, 8872, 8857, -1, 8857, 8872, 8870, -1, 8860, 8873, 8868, -1, 8866, 8873, 8860, -1, 8861, 8874, 8859, -1, 8854, 8875, 8871, -1, 8858, 8875, 8854, -1, 8859, 8874, 8872, -1, 8863, 8876, 8861, -1, 8861, 8876, 8874, -1, 8865, 8877, 7144, -1, 8871, 8878, 8866, -1, 8866, 8878, 8873, -1, 7144, 8877, 7150, -1, 8864, 8879, 8858, -1, 8858, 8879, 8875, -1, 7102, 8880, 8867, -1, 7100, 8880, 7102, -1, 8867, 8880, 8863, -1, 8863, 8880, 8876, -1, 8865, 8881, 8877, -1, 8875, 8882, 8871, -1, 8871, 8882, 8878, -1, 8868, 8761, 7181, -1, 8870, 8881, 8865, -1, 8870, 8883, 8881, -1, 7080, 8884, 7082, -1, 8872, 8883, 8870, -1, 8864, 8884, 8879, -1, 7082, 8884, 8869, -1, 8869, 8884, 8864, -1, 8879, 8885, 8875, -1, 8874, 8886, 8872, -1, 8875, 8885, 8882, -1, 8872, 8886, 8883, -1, 8868, 8759, 8761, -1, 8874, 8887, 8886, -1, 8873, 8759, 8868, -1, 8876, 8887, 8874, -1, 7080, 8888, 8884, -1, 8884, 8888, 8879, -1, 8879, 8888, 8885, -1, 8873, 8889, 8759, -1, 7098, 8890, 7100, -1, 8878, 8889, 8873, -1, 8876, 8890, 8887, -1, 8880, 8890, 8876, -1, 7100, 8890, 8880, -1, 8882, 8891, 8878, -1, 8878, 8891, 8889, -1, 8882, 8892, 8891, -1, 8885, 8892, 8882, -1, 7079, 8893, 7080, -1, 7080, 8893, 8888, -1, 8888, 8893, 8885, -1, 8885, 8893, 8892, -1, 8894, 8895, 7156, -1, 8894, 8896, 8895, -1, 8897, 8896, 8894, -1, 8898, 8899, 8897, -1, 8897, 8899, 8896, -1, 8898, 8900, 8899, -1, 8901, 8900, 8898, -1, 8895, 8902, 7156, -1, 7156, 8902, 7162, -1, 7174, 8807, 2373, -1, 2373, 8807, 2371, -1, 8901, 8903, 8900, -1, 8904, 8903, 8901, -1, 8895, 8905, 8902, -1, 8807, 8809, 2371, -1, 8896, 8905, 8895, -1, 2371, 8809, 2377, -1, 8902, 8906, 7162, -1, 7093, 8907, 7095, -1, 7095, 8907, 8908, -1, 8809, 8811, 2377, -1, 8908, 8907, 8904, -1, 8904, 8907, 8903, -1, 2377, 8811, 2381, -1, 8899, 8909, 8896, -1, 8896, 8909, 8905, -1, 8811, 8910, 2381, -1, 8905, 8911, 8902, -1, 8902, 8911, 8906, -1, 2381, 8910, 2383, -1, 8910, 8912, 2383, -1, 8900, 8913, 8899, -1, 2383, 8912, 2386, -1, 8899, 8913, 8909, -1, 8912, 8914, 2386, -1, 2395, 8914, 7073, -1, 2386, 8914, 2395, -1, 8909, 8915, 8905, -1, 8905, 8915, 8911, -1, 8881, 8916, 8877, -1, 8877, 8916, 7150, -1, 8903, 8917, 8900, -1, 8900, 8917, 8913, -1, 8916, 8918, 7150, -1, 7162, 8919, 7167, -1, 8906, 8919, 7162, -1, 7153, 8920, 8921, -1, 7150, 8920, 7153, -1, 8918, 8920, 7150, -1, 8922, 8923, 8921, -1, 8921, 8923, 7153, -1, 8913, 8924, 8909, -1, 8909, 8924, 8915, -1, 7093, 8925, 8907, -1, 8907, 8925, 8903, -1, 8903, 8925, 8917, -1, 8906, 8926, 8919, -1, 8923, 8927, 7153, -1, 7156, 8928, 8894, -1, 8927, 8928, 7153, -1, 8911, 8926, 8906, -1, 7153, 8928, 7156, -1, 8917, 8929, 8913, -1, 8930, 8931, 8932, -1, 8913, 8929, 8924, -1, 7074, 8931, 8930, -1, 8919, 8933, 7167, -1, 8911, 8934, 8926, -1, 7074, 8935, 8931, -1, 8915, 8934, 8911, -1, 7093, 8936, 8925, -1, 7074, 8937, 8935, -1, 8917, 8936, 8929, -1, 8925, 8936, 8917, -1, 8938, 8939, 7072, -1, 7091, 8936, 7093, -1, 7072, 8939, 7074, -1, 8926, 8940, 8919, -1, 7074, 8939, 8937, -1, 8938, 8941, 8942, -1, 8919, 8940, 8933, -1, 7072, 8941, 8938, -1, 8915, 8943, 8934, -1, 8924, 8943, 8915, -1, 8934, 8944, 8926, -1, 7072, 8945, 8941, -1, 7071, 8946, 7072, -1, 8926, 8944, 8940, -1, 8924, 8947, 8943, -1, 8929, 8947, 8924, -1, 7072, 8946, 8945, -1, 8948, 8949, 7071, -1, 7071, 8949, 8946, -1, 8933, 8950, 7167, -1, 7071, 8951, 8948, -1, 8948, 8951, 8952, -1, 7167, 8950, 7169, -1, 8943, 8953, 8934, -1, 8934, 8953, 8944, -1, 8936, 8954, 8929, -1, 7071, 8955, 8951, -1, 7091, 8954, 8936, -1, 8951, 8955, 8952, -1, 7070, 8956, 7071, -1, 8929, 8954, 8947, -1, 8933, 8957, 8950, -1, 7071, 8956, 8955, -1, 8940, 8957, 8933, -1, 8958, 8959, 7070, -1, 7070, 8959, 8956, -1, 8960, 8961, 8962, -1, 8947, 8963, 8943, -1, 8962, 8961, 7116, -1, 8943, 8963, 8953, -1, 8961, 8964, 7116, -1, 8950, 8965, 7169, -1, 8944, 8966, 8940, -1, 7109, 8967, 8968, -1, 8940, 8966, 8957, -1, 8964, 8967, 7116, -1, 7116, 8967, 7109, -1, 8968, 8969, 7109, -1, 7091, 8970, 8954, -1, 8971, 8969, 8968, -1, 7089, 8970, 7091, -1, 8954, 8970, 8947, -1, 8947, 8970, 8963, -1, 8957, 8972, 8950, -1, 8950, 8972, 8965, -1, 8969, 8973, 7109, -1, 8953, 8974, 8944, -1, 8944, 8974, 8966, -1, 7110, 8975, 8976, -1, 8973, 8975, 7109, -1, 7109, 8975, 7110, -1, 8893, 8977, 8892, -1, 8957, 8978, 8972, -1, 8966, 8978, 8957, -1, 7079, 8977, 8893, -1, 8963, 8979, 8953, -1, 8953, 8979, 8974, -1, 7079, 8980, 8977, -1, 7169, 8981, 7173, -1, 8965, 8981, 7169, -1, 8974, 8982, 8966, -1, 7079, 8983, 8980, -1, 7077, 8984, 7079, -1, 8966, 8982, 8978, -1, 7079, 8984, 8983, -1, 8985, 8984, 7077, -1, 8985, 8986, 8987, -1, 7077, 8986, 8985, -1, 7089, 8988, 8970, -1, 8970, 8988, 8963, -1, 8963, 8988, 8979, -1, 8972, 8989, 8965, -1, 7077, 8990, 8986, -1, 8965, 8989, 8981, -1, 7075, 8991, 7077, -1, 8974, 8992, 8982, -1, 7077, 8991, 8990, -1, 8979, 8992, 8974, -1, 8993, 8994, 7075, -1, 7075, 8994, 8991, -1, 8978, 8995, 8972, -1, 7075, 8996, 8993, -1, 8972, 8995, 8989, -1, 8993, 8996, 8997, -1, 8981, 8998, 7173, -1, 7075, 8999, 8996, -1, 7087, 9000, 7089, -1, 7089, 9000, 8988, -1, 8988, 9000, 8979, -1, 8996, 8999, 8997, -1, 8979, 9000, 8992, -1, 7073, 9001, 7075, -1, 8982, 9002, 8978, -1, 8978, 9002, 8995, -1, 7075, 9001, 8999, -1, 8914, 9003, 7073, -1, 7073, 9003, 9001, -1, 8989, 9004, 8981, -1, 8981, 9004, 8998, -1, 8886, 9005, 8883, -1, 8992, 9006, 8982, -1, 8883, 9005, 8881, -1, 8982, 9006, 9002, -1, 8881, 9007, 8916, -1, 8916, 9007, 8918, -1, 9005, 9007, 8881, -1, 8989, 9008, 9004, -1, 8995, 9008, 8989, -1, 8998, 9009, 7173, -1, 9007, 9010, 8918, -1, 7173, 9009, 7171, -1, 8921, 9011, 8922, -1, 8992, 9012, 9006, -1, 8920, 9011, 8921, -1, 7087, 9012, 9000, -1, 9000, 9012, 8992, -1, 8995, 9013, 9008, -1, 8918, 9014, 8920, -1, 9010, 9014, 8918, -1, 8920, 9014, 9011, -1, 9002, 9013, 8995, -1, 8922, 9015, 9016, -1, 9004, 9017, 8998, -1, 9011, 9015, 8922, -1, 8998, 9017, 9009, -1, 9016, 9015, 9018, -1, 9014, 9015, 9011, -1, 9016, 9019, 8922, -1, 9018, 9019, 9016, -1, 9006, 9020, 9002, -1, 8922, 9021, 8923, -1, 9002, 9020, 9013, -1, 9008, 9022, 9004, -1, 8923, 9021, 8927, -1, 9004, 9022, 9017, -1, 9019, 9021, 8922, -1, 9009, 9023, 7171, -1, 9021, 9024, 8927, -1, 7087, 9025, 9012, -1, 8894, 9026, 8897, -1, 9012, 9025, 9006, -1, 8928, 9026, 8894, -1, 7085, 9025, 7087, -1, 9006, 9025, 9020, -1, 9008, 9027, 9022, -1, 8927, 9028, 8928, -1, 9024, 9028, 8927, -1, 8928, 9028, 9026, -1, 8897, 9029, 8898, -1, 9013, 9027, 9008, -1, 8898, 9029, 8901, -1, 9026, 9029, 8897, -1, 9009, 9030, 9023, -1, 9028, 9029, 9026, -1, 9017, 9030, 9009, -1, 9020, 9031, 9013, -1, 9032, 9033, 9034, -1, 8932, 9033, 9032, -1, 8935, 9035, 8931, -1, 9013, 9031, 9027, -1, 8931, 9035, 8932, -1, 7171, 9036, 7168, -1, 9023, 9036, 7171, -1, 8932, 9035, 9033, -1, 9022, 9037, 9017, -1, 9017, 9037, 9030, -1, 8935, 9038, 9035, -1, 9025, 9039, 9020, -1, 7085, 9039, 9025, -1, 9020, 9039, 9031, -1, 9030, 9040, 9023, -1, 9023, 9040, 9036, -1, 9041, 9042, 9043, -1, 9027, 9044, 9022, -1, 9022, 9044, 9037, -1, 9045, 9046, 9042, -1, 9030, 9047, 9040, -1, 9037, 9047, 9030, -1, 9038, 9046, 9045, -1, 9038, 9048, 9046, -1, 8935, 9048, 9038, -1, 8937, 9048, 8935, -1, 9027, 9049, 9044, -1, 8939, 9048, 8937, -1, 9031, 9049, 9027, -1, 9046, 9050, 9042, -1, 9036, 9051, 7168, -1, 8938, 9052, 8939, -1, 9048, 9052, 9046, -1, 8939, 9052, 9048, -1, 9044, 9053, 9037, -1, 9046, 9052, 9050, -1, 9042, 9054, 9043, -1, 9050, 9054, 9042, -1, 9037, 9053, 9047, -1, 8938, 9054, 9052, -1, 8942, 9054, 8938, -1, 9052, 9054, 9050, -1, 7083, 9055, 7085, -1, 9043, 9054, 8942, -1, 9039, 9055, 9031, -1, 9043, 9056, 9041, -1, 7085, 9055, 9039, -1, 9031, 9055, 9049, -1, 8942, 9056, 9043, -1, 9036, 9057, 9051, -1, 9040, 9057, 9036, -1, 8942, 9058, 9056, -1, 8941, 9058, 8942, -1, 8945, 9058, 8941, -1, 9044, 9059, 9053, -1, 9049, 9059, 9044, -1, 8945, 9060, 9058, -1, 7168, 9061, 7164, -1, 9051, 9061, 7168, -1, 9047, 9062, 9040, -1, 9040, 9062, 9057, -1, 7083, 9063, 9055, -1, 9064, 9065, 9066, -1, 9055, 9063, 9049, -1, 9049, 9063, 9059, -1, 9060, 9067, 9068, -1, 9068, 9067, 9065, -1, 9057, 9069, 9051, -1, 9051, 9069, 9061, -1, 9053, 9070, 9047, -1, 9060, 9071, 9067, -1, 9047, 9070, 9062, -1, 8945, 9071, 9060, -1, 8946, 9071, 8945, -1, 8949, 9071, 8946, -1, 9067, 9072, 9065, -1, 9062, 9073, 9057, -1, 9057, 9073, 9069, -1, 9067, 9074, 9072, -1, 9071, 9074, 9067, -1, 9059, 9075, 9053, -1, 8949, 9074, 9071, -1, 9053, 9075, 9070, -1, 8948, 9074, 8949, -1, 9066, 9076, 8952, -1, 9065, 9076, 9066, -1, 9072, 9076, 9065, -1, 9061, 9077, 7164, -1, 8952, 9076, 8948, -1, 8948, 9076, 9074, -1, 9074, 9076, 9072, -1, 9066, 9078, 9064, -1, 8952, 9078, 9066, -1, 9070, 9079, 9062, -1, 9062, 9079, 9073, -1, 8955, 9080, 8952, -1, 7081, 9081, 7083, -1, 8952, 9080, 9078, -1, 7083, 9081, 9063, -1, 9059, 9081, 9075, -1, 9063, 9081, 9059, -1, 8955, 9082, 9080, -1, 9069, 9083, 9061, -1, 9061, 9083, 9077, -1, 9070, 9084, 9079, -1, 9075, 9084, 9070, -1, 7164, 9085, 7158, -1, 9077, 9085, 7164, -1, 9086, 9087, 9088, -1, 9073, 9089, 9069, -1, 9082, 9090, 9091, -1, 9069, 9089, 9083, -1, 9091, 9090, 9087, -1, 9075, 9092, 9084, -1, 8959, 9093, 8956, -1, 8955, 9093, 9082, -1, 9081, 9092, 9075, -1, 7081, 9092, 9081, -1, 9082, 9093, 9090, -1, 8956, 9093, 8955, -1, 9077, 9094, 9085, -1, 9090, 9095, 9087, -1, 9083, 9094, 9077, -1, 8958, 9096, 8959, -1, 9073, 9097, 9089, -1, 8959, 9096, 9093, -1, 9093, 9096, 9090, -1, 9090, 9096, 9095, -1, 9079, 9097, 9073, -1, 9088, 9098, 9099, -1, 9089, 9100, 9083, -1, 9096, 9098, 9095, -1, 9099, 9098, 8958, -1, 9087, 9098, 9088, -1, 9083, 9100, 9094, -1, 8958, 9098, 9096, -1, 9095, 9098, 9087, -1, 9101, 9102, 8960, -1, 9103, 9102, 9101, -1, 8960, 9104, 8961, -1, 9079, 9105, 9097, -1, 8961, 9104, 8964, -1, 9084, 9105, 9079, -1, 9102, 9104, 8960, -1, 9089, 9106, 9100, -1, 9104, 9107, 8964, -1, 9097, 9106, 9089, -1, 9085, 9108, 7158, -1, 9084, 9109, 9105, -1, 9092, 9109, 9084, -1, 7081, 9109, 9092, -1, 8968, 9110, 8971, -1, 8967, 9110, 8968, -1, 7078, 9109, 7081, -1, 9105, 9111, 9097, -1, 8964, 9112, 8967, -1, 9097, 9111, 9106, -1, 8967, 9112, 9110, -1, 9107, 9112, 8964, -1, 9113, 9114, 9115, -1, 9094, 9116, 9085, -1, 8971, 9114, 9113, -1, 9110, 9114, 8971, -1, 9112, 9114, 9110, -1, 9085, 9116, 9108, -1, 9115, 9117, 9113, -1, 9108, 9118, 7158, -1, 9113, 9117, 8971, -1, 7158, 9118, 7155, -1, 8971, 9119, 8969, -1, 8969, 9119, 8973, -1, 9109, 9120, 9105, -1, 9117, 9119, 8971, -1, 9105, 9120, 9111, -1, 7078, 9120, 9109, -1, 9119, 9121, 8973, -1, 9100, 9122, 9094, -1, 9094, 9122, 9116, -1, 9108, 9123, 9118, -1, 8975, 9124, 8976, -1, 9116, 9123, 9108, -1, 8976, 9124, 9125, -1, 9106, 9126, 9100, -1, 9121, 9127, 8973, -1, 8973, 9127, 8975, -1, 8975, 9127, 9124, -1, 9100, 9126, 9122, -1, 9127, 9128, 9124, -1, 9122, 9129, 9116, -1, 9116, 9129, 9123, -1, 9124, 9128, 9125, -1, 9130, 9128, 9131, -1, 9125, 9128, 9130, -1, 9106, 9132, 9126, -1, 9111, 9132, 9106, -1, 8891, 9133, 8889, -1, 8892, 9133, 8891, -1, 8980, 9134, 8977, -1, 8977, 9134, 8892, -1, 8892, 9134, 9133, -1, 9122, 9135, 9129, -1, 9126, 9135, 9122, -1, 9118, 9136, 7155, -1, 8980, 9137, 9134, -1, 7076, 9138, 7078, -1, 9120, 9138, 9111, -1, 7078, 9138, 9120, -1, 9111, 9138, 9132, -1, 9132, 9139, 9126, -1, 9126, 9139, 9135, -1, 8776, 9140, 9141, -1, 9123, 9142, 9118, -1, 9137, 9143, 9144, -1, 9118, 9142, 9136, -1, 9144, 9143, 9140, -1, 7076, 9145, 9138, -1, 9132, 9145, 9139, -1, 8980, 9146, 9137, -1, 9138, 9145, 9132, -1, 9137, 9146, 9143, -1, 8983, 9146, 8980, -1, 9129, 9034, 9123, -1, 8984, 9146, 8983, -1, 9123, 9034, 9142, -1, 9143, 9147, 9140, -1, 9135, 9032, 9129, -1, 9146, 9148, 9143, -1, 8985, 9148, 8984, -1, 9129, 9032, 9034, -1, 8984, 9148, 9146, -1, 9143, 9148, 9147, -1, 9141, 9149, 8987, -1, 8987, 9149, 8985, -1, 9140, 9149, 9141, -1, 9147, 9149, 9140, -1, 9139, 8932, 9135, -1, 8985, 9149, 9148, -1, 9135, 8932, 9032, -1, 9148, 9149, 9147, -1, 9141, 9150, 8776, -1, 8987, 9150, 9141, -1, 8986, 9151, 8987, -1, 7074, 8930, 7076, -1, 8990, 9151, 8986, -1, 7076, 8930, 9145, -1, 8987, 9151, 9150, -1, 9145, 8930, 9139, -1, 9139, 8930, 8932, -1, 8990, 9152, 9151, -1, 8794, 9153, 9154, -1, 9152, 9155, 9156, -1, 9156, 9155, 9153, -1, 8991, 9157, 8990, -1, 8990, 9157, 9152, -1, 8994, 9157, 8991, -1, 9152, 9157, 9155, -1, 9155, 9158, 9153, -1, 8993, 9159, 8994, -1, 8994, 9159, 9157, -1, 9157, 9159, 9155, -1, 9155, 9159, 9158, -1, 8997, 9160, 8993, -1, 9154, 9160, 8997, -1, 8993, 9160, 9159, -1, 9153, 9160, 9154, -1, 9158, 9160, 9153, -1, 9159, 9160, 9158, -1, 9154, 9161, 8794, -1, 8997, 9161, 9154, -1, 8999, 9162, 8997, -1, 8997, 9162, 9161, -1, 8999, 9163, 9162, -1, 8811, 9164, 8910, -1, 9163, 9165, 9166, -1, 9166, 9165, 9164, -1, 9001, 9167, 8999, -1, 9003, 9167, 9001, -1, 8999, 9167, 9163, -1, 9163, 9167, 9165, -1, 9165, 9168, 9164, -1, 9165, 9169, 9168, -1, 8914, 9169, 9003, -1, 9003, 9169, 9167, -1, 9167, 9169, 9165, -1, 9168, 9170, 9164, -1, 9169, 9170, 9168, -1, 8914, 9170, 9169, -1, 8912, 9170, 8914, -1, 8910, 9170, 8912, -1, 9164, 9170, 8910, -1, 8886, 9171, 9005, -1, 9172, 9173, 7140, -1, 9005, 9171, 9007, -1, 9007, 9171, 9010, -1, 7140, 9173, 7134, -1, 8887, 9171, 8886, -1, 9171, 9174, 9010, -1, 9175, 9176, 9172, -1, 9172, 9176, 9173, -1, 9174, 9177, 9010, -1, 9018, 9177, 9178, -1, 9010, 9177, 9014, -1, 9015, 9177, 9018, -1, 9014, 9177, 9015, -1, 9086, 9179, 9175, -1, 9018, 9180, 9019, -1, 9175, 9179, 9176, -1, 9178, 9180, 9018, -1, 9019, 9180, 9021, -1, 9021, 9180, 9024, -1, 9086, 9181, 9179, -1, 9088, 9181, 9086, -1, 9180, 9182, 9024, -1, 9099, 9183, 9088, -1, 9088, 9183, 9181, -1, 8901, 9184, 8904, -1, 9182, 9184, 9024, -1, 9173, 9185, 7134, -1, 9024, 9184, 9028, -1, 9029, 9184, 8901, -1, 9028, 9184, 9029, -1, 7134, 9185, 7130, -1, 9035, 9186, 9033, -1, 9038, 9186, 9035, -1, 9034, 9186, 9142, -1, 7069, 9187, 7070, -1, 9033, 9186, 9034, -1, 9099, 9187, 9183, -1, 7070, 9187, 8958, -1, 8958, 9187, 9099, -1, 9176, 9188, 9173, -1, 9173, 9188, 9185, -1, 9038, 9189, 9186, -1, 9041, 9190, 9042, -1, 9176, 9191, 9188, -1, 9042, 9190, 9045, -1, 9179, 9191, 9176, -1, 9038, 9190, 9189, -1, 9045, 9190, 9038, -1, 9041, 9192, 9193, -1, 9058, 9192, 9056, -1, 9181, 9194, 9179, -1, 9056, 9192, 9041, -1, 9060, 9192, 9058, -1, 9179, 9194, 9191, -1, 9183, 9195, 9181, -1, 9181, 9195, 9194, -1, 9060, 9196, 9192, -1, 7130, 9197, 7122, -1, 9185, 9197, 7130, -1, 9068, 9198, 9060, -1, 9065, 9198, 9068, -1, 9064, 9198, 9065, -1, 7105, 9199, 7069, -1, 9060, 9198, 9196, -1, 7069, 9199, 9187, -1, 9187, 9199, 9183, -1, 9064, 9200, 9201, -1, 9183, 9199, 9195, -1, 9082, 9200, 9080, -1, 9078, 9200, 9064, -1, 9080, 9200, 9078, -1, 9188, 9202, 9185, -1, 9185, 9202, 9197, -1, 9082, 9203, 9200, -1, 9191, 9204, 9188, -1, 9188, 9204, 9202, -1, 9082, 9205, 9203, -1, 9091, 9205, 9082, -1, 9194, 9206, 9191, -1, 9086, 9205, 9087, -1, 9087, 9205, 9091, -1, 9102, 9207, 9104, -1, 9191, 9206, 9204, -1, 9194, 9208, 9206, -1, 9103, 9207, 9102, -1, 9195, 9208, 9194, -1, 9209, 9207, 9103, -1, 9104, 9207, 9107, -1, 7122, 8962, 7116, -1, 9197, 8962, 7122, -1, 9207, 9210, 9107, -1, 9195, 9211, 9208, -1, 9112, 9212, 9114, -1, 7104, 9211, 7105, -1, 9115, 9212, 8735, -1, 7105, 9211, 9199, -1, 9199, 9211, 9195, -1, 9210, 9212, 9107, -1, 9114, 9212, 9115, -1, 9107, 9212, 9112, -1, 9115, 8744, 9117, -1, 9197, 8960, 8962, -1, 9119, 8744, 9121, -1, 9202, 8960, 9197, -1, 9117, 8744, 9119, -1, 8735, 8744, 9115, -1, 9202, 9101, 8960, -1, 9204, 9101, 9202, -1, 8744, 8746, 9121, -1, 9206, 9103, 9204, -1, 9204, 9103, 9101, -1, 9121, 8752, 9127, -1, 9127, 8752, 9128, -1, 9128, 8752, 9131, -1, 9131, 8752, 8754, -1, 8746, 8752, 9121, -1, 9208, 9209, 9206, -1, 9206, 9209, 9103, -1, 9137, 8765, 9134, -1, 8889, 8765, 8759, -1, 9133, 8765, 8889, -1, 9134, 8765, 9133, -1, 9137, 8764, 8765, -1, 7104, 9213, 9211, -1, 7103, 9213, 7104, -1, 9208, 9213, 9209, -1, 9211, 9213, 9208, -1, 9144, 8771, 9137, -1, 8776, 8771, 9140, -1, 9140, 8771, 9144, -1, 9137, 8771, 8764, -1, 9150, 8782, 8776, -1, 9151, 8782, 9150, -1, 9152, 8782, 9151, -1, 8776, 8782, 8777, -1, 9152, 8783, 8782, -1, 9152, 8788, 8783, -1, 9156, 8788, 9152, -1, 8794, 8788, 9153, -1, 9153, 8788, 9156, -1, 8794, 8799, 8793, -1, 9163, 8799, 9162, -1, 9161, 8799, 8794, -1, 9162, 8799, 9161, -1, 9163, 8801, 8799, -1, 8976, 9214, 7110, -1, 8811, 8804, 9164, -1, 9166, 8804, 9163, -1, 9163, 8804, 8801, -1, 9164, 8804, 9166, -1, 7098, 9215, 8890, -1, 8890, 9215, 8887, -1, 8887, 9216, 9171, -1, 8976, 9217, 9214, -1, 9125, 9217, 8976, -1, 9171, 9216, 9174, -1, 9215, 9216, 8887, -1, 9216, 9218, 9174, -1, 9215, 9218, 9216, -1, 7097, 9218, 7098, -1, 7098, 9218, 9215, -1, 9218, 9219, 9174, -1, 9130, 9220, 9125, -1, 9174, 9219, 9177, -1, 9125, 9220, 9217, -1, 9177, 9219, 9178, -1, 7097, 9221, 9218, -1, 9219, 9221, 9178, -1, 9218, 9221, 9219, -1, 9222, 9221, 7097, -1, 9178, 9221, 9222, -1, 7097, 9223, 9222, -1, 9131, 9224, 9130, -1, 9222, 9223, 9178, -1, 9130, 9224, 9220, -1, 9223, 9225, 9178, -1, 9214, 9226, 7110, -1, 9178, 9225, 9180, -1, 7110, 9226, 7198, -1, 9180, 9225, 9182, -1, 9225, 9227, 9182, -1, 9223, 9227, 9225, -1, 7097, 9227, 9223, -1, 7095, 9227, 7097, -1, 9227, 9228, 9182, -1, 8754, 9229, 9131, -1, 9131, 9229, 9224, -1, 9184, 9228, 8904, -1, 9182, 9228, 9184, -1, 7095, 9230, 9227, -1, 9227, 9230, 9228, -1, 9214, 9231, 9226, -1, 9228, 9230, 8904, -1, 9217, 9231, 9214, -1, 8908, 9230, 7095, -1, 8904, 9230, 8908, -1, 9142, 9232, 9136, -1, 9136, 9232, 7155, -1, 9226, 9233, 7198, -1, 9142, 9234, 9232, -1, 9189, 9234, 9186, -1, 7096, 9235, 7099, -1, 7099, 9235, 8758, -1, 8754, 9235, 9229, -1, 9186, 9234, 9142, -1, 8758, 9235, 8754, -1, 9232, 9234, 7155, -1, 9189, 9236, 9234, -1, 9217, 9237, 9231, -1, 9234, 9236, 7155, -1, 9220, 9237, 9217, -1, 7155, 9236, 7152, -1, 9190, 9238, 9189, -1, 9231, 9239, 9226, -1, 9236, 9238, 7152, -1, 9189, 9238, 9236, -1, 9226, 9239, 9233, -1, 9238, 9240, 7152, -1, 7152, 9240, 9241, -1, 9224, 9242, 9220, -1, 9193, 9243, 9041, -1, 9041, 9243, 9190, -1, 9190, 9243, 9238, -1, 9220, 9242, 9237, -1, 9238, 9243, 9240, -1, 9240, 9243, 9241, -1, 9231, 9244, 9239, -1, 9241, 9243, 9193, -1, 9237, 9244, 9231, -1, 9241, 9245, 7152, -1, 9193, 9245, 9241, -1, 9229, 9246, 9224, -1, 9196, 9247, 9192, -1, 9224, 9246, 9242, -1, 9192, 9247, 9193, -1, 9193, 9247, 9245, -1, 9245, 9247, 7152, -1, 7198, 9248, 7192, -1, 9233, 9248, 7198, -1, 9196, 9249, 9247, -1, 9247, 9249, 7152, -1, 7152, 9249, 7148, -1, 9249, 9250, 7148, -1, 9242, 9251, 9237, -1, 9198, 9250, 9196, -1, 9237, 9251, 9244, -1, 9196, 9250, 9249, -1, 7148, 9252, 9253, -1, 7096, 9254, 9235, -1, 9250, 9252, 7148, -1, 9235, 9254, 9229, -1, 9064, 9255, 9198, -1, 9229, 9254, 9246, -1, 9253, 9255, 9201, -1, 9233, 9256, 9248, -1, 9201, 9255, 9064, -1, 9198, 9255, 9250, -1, 9250, 9255, 9252, -1, 9252, 9255, 9253, -1, 9239, 9256, 9233, -1, 9253, 9257, 7148, -1, 9201, 9257, 9253, -1, 9246, 8738, 9242, -1, 9242, 8738, 9251, -1, 9200, 9258, 9201, -1, 9203, 9258, 9200, -1, 9201, 9258, 9257, -1, 9257, 9258, 7148, -1, 9248, 8741, 7192, -1, 9239, 9259, 9256, -1, 7148, 9260, 7140, -1, 9203, 9260, 9258, -1, 9258, 9260, 7148, -1, 9244, 9259, 9239, -1, 9246, 8736, 8738, -1, 9205, 9261, 9203, -1, 9254, 8736, 9246, -1, 9260, 9261, 7140, -1, 7094, 8736, 7096, -1, 9203, 9261, 9260, -1, 7140, 9262, 9172, -1, 7096, 8736, 9254, -1, 9172, 9262, 9175, -1, 9256, 8745, 9248, -1, 9261, 9262, 7140, -1, 9248, 8745, 8741, -1, 9086, 9263, 9205, -1, 9175, 9263, 9086, -1, 9205, 9263, 9261, -1, 9262, 9263, 9175, -1, 9261, 9263, 9262, -1, 9244, 8749, 9259, -1, 7103, 9264, 9213, -1, 9213, 9264, 9209, -1, 9251, 8749, 9244, -1, 9259, 8756, 9256, -1, 9264, 9265, 9209, -1, 9209, 9265, 9207, -1, 9256, 8756, 8745, -1, 9207, 9265, 9210, -1, 7101, 8730, 7103, -1, 9264, 8730, 9265, -1, 9251, 8739, 8749, -1, 8738, 8739, 9251, -1, 9265, 8730, 9210, -1, 7103, 8730, 9264, -1, 8741, 8743, 7192, -1, 9212, 8732, 8735, -1, 9210, 8732, 9212, -1, 7192, 8743, 7190, -1, 8730, 8732, 9210, -1, 8734, 8731, 7101, -1, 8735, 8731, 8734, -1, 8732, 8731, 8735, -1, 8749, 8750, 9259, -1, 7101, 8731, 8730, -1, 9259, 8750, 8756, -1, 7273, 9266, 9267, -1, 9267, 9266, 9268, -1, 9268, 9266, 9269, -1, 9270, 9271, 9272, -1, 9272, 9271, 9273, -1, 7273, 9274, 9269, -1, 9269, 9274, 9275, -1, 9276, 9277, 7058, -1, 9274, 9278, 9275, -1, 7058, 9277, 7056, -1, 9275, 9278, 9279, -1, 7273, 9278, 9274, -1, 9280, 9281, 9282, -1, 9279, 9278, 9283, -1, 7271, 9284, 7273, -1, 9282, 9281, 9285, -1, 7273, 9284, 9278, -1, 9278, 9284, 9283, -1, 7287, 9286, 9287, -1, 9287, 9286, 9270, -1, 9288, 9289, 9290, -1, 9270, 9286, 9271, -1, 9290, 9289, 9291, -1, 9292, 9289, 9288, -1, 9285, 9293, 9276, -1, 7271, 9294, 9284, -1, 9276, 9293, 9277, -1, 9283, 9294, 9292, -1, 9284, 9294, 9283, -1, 9292, 9294, 9289, -1, 9273, 9295, 9280, -1, 9280, 9295, 9281, -1, 9291, 9296, 7271, -1, 9289, 9296, 9291, -1, 9294, 9296, 9289, -1, 7271, 9296, 9294, -1, 7271, 9297, 9291, -1, 9291, 9297, 9290, -1, 9281, 9298, 9285, -1, 9285, 9298, 9293, -1, 7271, 9299, 9297, -1, 9297, 9299, 9290, -1, 9273, 9300, 9295, -1, 9290, 9299, 9301, -1, 9271, 9300, 9273, -1, 9301, 9299, 9302, -1, 7269, 9303, 7271, -1, 9277, 9304, 7056, -1, 7271, 9303, 9299, -1, 9299, 9303, 9302, -1, 9305, 9306, 9307, -1, 9295, 9308, 9281, -1, 9307, 9306, 9309, -1, 9281, 9308, 9298, -1, 7285, 9310, 7287, -1, 7269, 9311, 9303, -1, 9303, 9311, 9302, -1, 7287, 9310, 9286, -1, 9305, 9311, 9306, -1, 9286, 9310, 9271, -1, 9271, 9310, 9300, -1, 9302, 9311, 9305, -1, 9293, 9312, 9277, -1, 9313, 9314, 7269, -1, 9309, 9314, 9313, -1, 7269, 9314, 9311, -1, 9277, 9312, 9304, -1, 9311, 9314, 9306, -1, 9306, 9314, 9309, -1, 9300, 9315, 9295, -1, 9295, 9315, 9308, -1, 9298, 9316, 9293, -1, 9293, 9316, 9312, -1, 9304, 9317, 7056, -1, 7056, 9317, 7054, -1, 7285, 9318, 9310, -1, 9310, 9318, 9300, -1, 9300, 9318, 9315, -1, 9308, 9319, 9298, -1, 9298, 9319, 9316, -1, 9304, 9320, 9317, -1, 9312, 9320, 9304, -1, 9315, 9321, 9308, -1, 9308, 9321, 9319, -1, 9312, 9322, 9320, -1, 9316, 9322, 9312, -1, 9317, 9323, 7054, -1, 7283, 9324, 7285, -1, 7285, 9324, 9318, -1, 9315, 9324, 9321, -1, 9318, 9324, 9315, -1, 9316, 9325, 9322, -1, 9319, 9325, 9316, -1, 9320, 9326, 9317, -1, 9317, 9326, 9323, -1, 9321, 9327, 9319, -1, 9319, 9327, 9325, -1, 9322, 9328, 9320, -1, 9320, 9328, 9326, -1, 9323, 9329, 7054, -1, 7054, 9329, 7052, -1, 9324, 9330, 9321, -1, 9321, 9330, 9327, -1, 7283, 9330, 9324, -1, 9325, 9331, 9322, -1, 9322, 9331, 9328, -1, 9323, 9332, 9329, -1, 9326, 9332, 9323, -1, 9325, 9333, 9331, -1, 9327, 9333, 9325, -1, 9329, 9334, 7052, -1, 9328, 9335, 9326, -1, 9326, 9335, 9332, -1, 7281, 9336, 7283, -1, 9330, 9336, 9327, -1, 9327, 9336, 9333, -1, 7283, 9336, 9330, -1, 9332, 9337, 9329, -1, 9329, 9337, 9334, -1, 9331, 9338, 9328, -1, 9328, 9338, 9335, -1, 9332, 9339, 9337, -1, 9335, 9339, 9332, -1, 9331, 9340, 9338, -1, 9333, 9340, 9331, -1, 9334, 9341, 7052, -1, 7052, 9341, 7050, -1, 9338, 9342, 9335, -1, 9335, 9342, 9339, -1, 7281, 9343, 9336, -1, 9336, 9343, 9333, -1, 9333, 9343, 9340, -1, 9334, 9344, 9341, -1, 9337, 9344, 9334, -1, 9340, 9345, 9338, -1, 9338, 9345, 9342, -1, 9341, 9346, 7050, -1, 9339, 9347, 9337, -1, 9337, 9347, 9344, -1, 7280, 9348, 7281, -1, 7281, 9348, 9343, -1, 9343, 9348, 9340, -1, 9340, 9348, 9345, -1, 9344, 9349, 9341, -1, 9341, 9349, 9346, -1, 9339, 9350, 9347, -1, 9342, 9350, 9339, -1, 9347, 9351, 9344, -1, 9344, 9351, 9349, -1, 9345, 9352, 9342, -1, 9342, 9352, 9350, -1, 7050, 9353, 7048, -1, 9346, 9353, 7050, -1, 9350, 9354, 9347, -1, 9347, 9354, 9351, -1, 7280, 9355, 9348, -1, 9348, 9355, 9345, -1, 9345, 9355, 9352, -1, 9349, 9356, 9346, -1, 9346, 9356, 9353, -1, 9350, 9357, 9354, -1, 9352, 9357, 9350, -1, 9353, 9358, 7048, -1, 9349, 9359, 9356, -1, 9351, 9359, 9349, -1, 7280, 9360, 9355, -1, 7277, 9360, 7280, -1, 9352, 9360, 9357, -1, 7037, 1744, 1746, -1, 9355, 9360, 9352, -1, 9353, 9361, 9358, -1, 9356, 9361, 9353, -1, 9351, 9362, 9359, -1, 9354, 9362, 9351, -1, 9356, 9363, 9361, -1, 9359, 9363, 9356, -1, 9354, 9364, 9362, -1, 9357, 9364, 9354, -1, 9362, 9365, 9359, -1, 9359, 9365, 9363, -1, 9358, 9366, 7048, -1, 1735, 9367, 1736, -1, 1736, 9367, 7064, -1, 7048, 9366, 7046, -1, 9357, 9368, 9364, -1, 7277, 9368, 9360, -1, 1735, 9369, 9367, -1, 9360, 9368, 9357, -1, 1808, 9369, 1735, -1, 9364, 9370, 9362, -1, 9362, 9370, 9365, -1, 9358, 9371, 9366, -1, 1813, 9372, 1808, -1, 9361, 9371, 9358, -1, 1808, 9372, 9369, -1, 1816, 9373, 1813, -1, 9366, 9374, 7046, -1, 1813, 9373, 9372, -1, 7276, 9375, 7277, -1, 1816, 9376, 9373, -1, 7277, 9375, 9368, -1, 9368, 9375, 9364, -1, 1819, 9376, 1816, -1, 9364, 9375, 9370, -1, 9363, 9377, 9361, -1, 9367, 9378, 7064, -1, 9361, 9377, 9371, -1, 7064, 9378, 7063, -1, 9371, 9379, 9366, -1, 7237, 9380, 1825, -1, 9366, 9379, 9374, -1, 1823, 9380, 1819, -1, 1825, 9380, 1823, -1, 1819, 9380, 9376, -1, 9365, 9381, 9363, -1, 9363, 9381, 9377, -1, 9367, 9382, 9378, -1, 9377, 9383, 9371, -1, 9369, 9382, 9367, -1, 9371, 9383, 9379, -1, 9372, 9384, 9369, -1, 9365, 9385, 9381, -1, 9370, 9385, 9365, -1, 9369, 9384, 9382, -1, 9372, 9386, 9384, -1, 9373, 9386, 9372, -1, 9377, 9387, 9383, -1, 9381, 9387, 9377, -1, 9373, 9388, 9386, -1, 9374, 9389, 7046, -1, 9376, 9388, 9373, -1, 7046, 9389, 7043, -1, 9378, 9390, 7063, -1, 9375, 9391, 9370, -1, 7063, 9390, 7061, -1, 9370, 9391, 9385, -1, 7276, 9391, 9375, -1, 9380, 9392, 9376, -1, 9385, 9393, 9381, -1, 7241, 9392, 7237, -1, 7237, 9392, 9380, -1, 9376, 9392, 9388, -1, 9381, 9393, 9387, -1, 9374, 9394, 9389, -1, 9379, 9394, 9374, -1, 9382, 9395, 9378, -1, 9378, 9395, 9390, -1, 9384, 9396, 9382, -1, 7274, 9397, 7276, -1, 7276, 9397, 9391, -1, 9385, 9397, 9393, -1, 9391, 9397, 9385, -1, 9382, 9396, 9395, -1, 9379, 9398, 9394, -1, 9383, 9398, 9379, -1, 9386, 9399, 9384, -1, 9384, 9399, 9396, -1, 9387, 9400, 9383, -1, 9383, 9400, 9398, -1, 9386, 9401, 9399, -1, 9388, 9401, 9386, -1, 9393, 9402, 9387, -1, 9387, 9402, 9400, -1, 7241, 9403, 9392, -1, 9392, 9403, 9388, -1, 9388, 9403, 9401, -1, 7247, 9403, 7241, -1, 7274, 9404, 9397, -1, 9397, 9404, 9393, -1, 9393, 9404, 9402, -1, 7057, 9405, 7055, -1, 9406, 9405, 7057, -1, 9406, 9407, 9405, -1, 9408, 9407, 9406, -1, 7037, 9409, 1744, -1, 9408, 9410, 9407, -1, 9411, 9410, 9408, -1, 9411, 9412, 9410, -1, 9409, 9413, 1744, -1, 1744, 9413, 1749, -1, 9414, 9412, 9411, -1, 9405, 9415, 7055, -1, 9413, 9416, 1749, -1, 1749, 9416, 1753, -1, 9417, 9418, 9414, -1, 9414, 9418, 9412, -1, 9416, 9307, 1753, -1, 1753, 9307, 1755, -1, 9407, 9419, 9405, -1, 9307, 9309, 1755, -1, 9405, 9419, 9415, -1, 1755, 9309, 1761, -1, 1768, 9313, 7269, -1, 7055, 9420, 7053, -1, 9415, 9420, 7055, -1, 9309, 9313, 1761, -1, 9421, 9422, 9417, -1, 1761, 9313, 1769, -1, 7256, 9422, 9421, -1, 1769, 9313, 1768, -1, 9417, 9422, 9418, -1, 9403, 9423, 9401, -1, 9410, 9424, 9407, -1, 7247, 9423, 9403, -1, 9407, 9424, 9419, -1, 7247, 9425, 9423, -1, 9419, 9426, 9415, -1, 9415, 9426, 9420, -1, 9412, 9427, 9410, -1, 7250, 9428, 7247, -1, 9429, 9428, 7250, -1, 7247, 9428, 9425, -1, 9410, 9427, 9424, -1, 7250, 9430, 9429, -1, 9429, 9430, 9431, -1, 9424, 9432, 9419, -1, 9419, 9432, 9426, -1, 9418, 9433, 9412, -1, 7250, 9434, 9430, -1, 9412, 9433, 9427, -1, 7256, 9435, 7250, -1, 9420, 9436, 7053, -1, 7250, 9435, 9434, -1, 9421, 9435, 7256, -1, 9437, 9438, 7038, -1, 9439, 9438, 9437, -1, 9427, 9440, 9424, -1, 9424, 9440, 9432, -1, 9438, 9441, 7038, -1, 7259, 9442, 7256, -1, 9418, 9442, 9433, -1, 7256, 9442, 9422, -1, 9422, 9442, 9418, -1, 9441, 9443, 7038, -1, 9426, 9444, 9420, -1, 9420, 9444, 9436, -1, 9433, 9445, 9427, -1, 7038, 9446, 7036, -1, 7036, 9446, 9447, -1, 9443, 9446, 7038, -1, 9427, 9445, 9440, -1, 9448, 9449, 9447, -1, 9447, 9449, 7036, -1, 7053, 9450, 7051, -1, 9436, 9450, 7053, -1, 9426, 9451, 9444, -1, 9449, 9452, 7036, -1, 9432, 9451, 9426, -1, 7259, 9453, 9442, -1, 7036, 9454, 7035, -1, 9442, 9453, 9433, -1, 9452, 9454, 7036, -1, 9433, 9453, 9445, -1, 9444, 9455, 9436, -1, 7035, 9456, 9457, -1, 9454, 9456, 7035, -1, 9436, 9455, 9450, -1, 9457, 9458, 7035, -1, 9432, 9459, 9451, -1, 9440, 9459, 9432, -1, 9460, 9458, 9457, -1, 9444, 9461, 9455, -1, 9451, 9461, 9444, -1, 9458, 9462, 7035, -1, 9460, 9462, 9458, -1, 9445, 9463, 9440, -1, 9440, 9463, 9459, -1, 7035, 9464, 7034, -1, 9462, 9464, 7035, -1, 9464, 9465, 7034, -1, 7034, 9465, 9466, -1, 9450, 9467, 7051, -1, 7211, 9468, 9469, -1, 9469, 9468, 9470, -1, 9459, 9471, 9451, -1, 7211, 9472, 9468, -1, 9451, 9471, 9461, -1, 7259, 9473, 9453, -1, 9453, 9473, 9445, -1, 7263, 9473, 7259, -1, 9445, 9473, 9463, -1, 7210, 9474, 7211, -1, 7211, 9474, 9472, -1, 9455, 9475, 9450, -1, 9476, 9474, 7210, -1, 9450, 9475, 9467, -1, 7210, 9477, 9476, -1, 9476, 9477, 9478, -1, 9463, 9479, 9459, -1, 9459, 9479, 9471, -1, 7210, 9480, 9477, -1, 9467, 9481, 7051, -1, 7296, 9482, 7210, -1, 7051, 9481, 7049, -1, 9461, 9483, 9455, -1, 7210, 9482, 9480, -1, 9455, 9483, 9475, -1, 9484, 9482, 7296, -1, 9394, 9485, 9389, -1, 9463, 9486, 9479, -1, 9389, 9485, 7043, -1, 7263, 9486, 9473, -1, 9473, 9486, 9463, -1, 9485, 9487, 7043, -1, 9475, 9488, 9467, -1, 9467, 9488, 9481, -1, 9461, 9489, 9483, -1, 9471, 9489, 9461, -1, 9487, 9490, 7043, -1, 9490, 9491, 7043, -1, 9483, 9492, 9475, -1, 7043, 9491, 7041, -1, 7041, 9491, 9493, -1, 9475, 9492, 9488, -1, 9494, 9495, 9493, -1, 9493, 9495, 7041, -1, 9479, 9496, 9471, -1, 9471, 9496, 9489, -1, 9495, 9497, 7041, -1, 9481, 9498, 7049, -1, 9489, 9499, 9483, -1, 9497, 9500, 7041, -1, 9483, 9499, 9492, -1, 7041, 9500, 7039, -1, 7039, 9501, 9502, -1, 7263, 9503, 9486, -1, 9500, 9501, 7039, -1, 7267, 9503, 7263, -1, 9486, 9503, 9479, -1, 9479, 9503, 9496, -1, 9502, 9504, 7039, -1, 9505, 9504, 9502, -1, 9488, 9506, 9481, -1, 9504, 9507, 7039, -1, 9481, 9506, 9498, -1, 9496, 9508, 9489, -1, 9505, 9507, 9504, -1, 9489, 9508, 9499, -1, 9492, 9509, 9488, -1, 7039, 9510, 7037, -1, 9488, 9509, 9506, -1, 9507, 9510, 7039, -1, 9510, 9511, 7037, -1, 7037, 9511, 9409, -1, 7049, 9512, 7047, -1, 9399, 9513, 9396, -1, 9498, 9512, 7049, -1, 9496, 9514, 9508, -1, 9401, 9513, 9399, -1, 7267, 9514, 9503, -1, 9503, 9514, 9496, -1, 9423, 9515, 9401, -1, 9425, 9515, 9423, -1, 9499, 9516, 9492, -1, 9401, 9515, 9513, -1, 9492, 9516, 9509, -1, 9506, 9517, 9498, -1, 9498, 9517, 9512, -1, 9425, 9518, 9515, -1, 9428, 9519, 9425, -1, 9508, 9520, 9499, -1, 9425, 9519, 9518, -1, 9499, 9520, 9516, -1, 9521, 9522, 9431, -1, 9523, 9522, 9521, -1, 9519, 9524, 9522, -1, 9506, 9525, 9517, -1, 9429, 9524, 9428, -1, 9428, 9524, 9519, -1, 9509, 9525, 9506, -1, 9522, 9524, 9431, -1, 9431, 9524, 9429, -1, 9431, 9526, 9521, -1, 9521, 9526, 9523, -1, 9512, 9527, 7047, -1, 9431, 9528, 9526, -1, 9430, 9528, 9431, -1, 9508, 9529, 9520, -1, 7268, 9529, 7267, -1, 7267, 9529, 9514, -1, 9514, 9529, 9508, -1, 9434, 9528, 9430, -1, 9509, 9530, 9525, -1, 9516, 9530, 9509, -1, 9512, 9531, 9527, -1, 9434, 9532, 9528, -1, 9517, 9531, 9512, -1, 9435, 9533, 9434, -1, 9516, 9534, 9530, -1, 9434, 9533, 9532, -1, 9414, 9535, 9417, -1, 9411, 9535, 9414, -1, 9520, 9534, 9516, -1, 9535, 9536, 9417, -1, 9525, 9537, 9517, -1, 9435, 9536, 9533, -1, 9421, 9536, 9435, -1, 9517, 9537, 9531, -1, 9417, 9536, 9421, -1, 9533, 9536, 9535, -1, 9527, 9538, 7047, -1, 9539, 9540, 9439, -1, 9541, 9540, 9539, -1, 7047, 9538, 7045, -1, 7268, 9542, 9529, -1, 9520, 9542, 9534, -1, 9439, 9543, 9438, -1, 9438, 9543, 9441, -1, 9529, 9542, 9520, -1, 9540, 9543, 9439, -1, 9530, 9544, 9525, -1, 9525, 9544, 9537, -1, 9441, 9545, 9443, -1, 9531, 9546, 9527, -1, 9443, 9545, 9446, -1, 9527, 9546, 9538, -1, 9441, 9547, 9545, -1, 9543, 9547, 9441, -1, 9534, 9548, 9530, -1, 9530, 9548, 9544, -1, 9545, 9549, 9446, -1, 9446, 9549, 9447, -1, 9538, 9550, 7045, -1, 9545, 9551, 9549, -1, 9547, 9551, 9545, -1, 9531, 9552, 9546, -1, 9537, 9552, 9531, -1, 9551, 9553, 9549, -1, 9547, 9554, 9551, -1, 7268, 9555, 9542, -1, 7264, 9555, 7268, -1, 9448, 9556, 9557, -1, 9534, 9555, 9548, -1, 9549, 9556, 9447, -1, 9553, 9556, 9549, -1, 9542, 9555, 9534, -1, 9447, 9556, 9448, -1, 9538, 9558, 9550, -1, 9557, 9559, 9560, -1, 9556, 9559, 9557, -1, 9546, 9558, 9538, -1, 9551, 9559, 9553, -1, 9554, 9559, 9551, -1, 9553, 9559, 9556, -1, 9544, 9561, 9537, -1, 9537, 9561, 9552, -1, 9557, 9562, 9448, -1, 9560, 9562, 9557, -1, 9552, 9563, 9546, -1, 9546, 9563, 9558, -1, 9448, 9564, 9449, -1, 9548, 9565, 9544, -1, 9562, 9564, 9448, -1, 9544, 9565, 9561, -1, 9449, 9564, 9452, -1, 9452, 9566, 9454, -1, 9454, 9566, 9456, -1, 9550, 9567, 7045, -1, 7045, 9567, 7044, -1, 9566, 9568, 9456, -1, 9456, 9568, 9457, -1, 9552, 9569, 9563, -1, 9452, 9570, 9566, -1, 9561, 9569, 9552, -1, 9564, 9570, 9452, -1, 7264, 9571, 9555, -1, 9555, 9571, 9548, -1, 9548, 9571, 9565, -1, 9566, 9572, 9568, -1, 9570, 9572, 9566, -1, 9558, 9573, 9550, -1, 9550, 9573, 9567, -1, 9572, 9574, 9568, -1, 9570, 9575, 9572, -1, 9565, 9576, 9561, -1, 9460, 9577, 9578, -1, 9568, 9577, 9457, -1, 9561, 9576, 9569, -1, 9574, 9577, 9568, -1, 9457, 9577, 9460, -1, 9578, 9579, 9580, -1, 9567, 9581, 7044, -1, 9577, 9579, 9578, -1, 9572, 9579, 9574, -1, 9558, 9582, 9573, -1, 9575, 9579, 9572, -1, 9574, 9579, 9577, -1, 9563, 9582, 9558, -1, 9578, 9583, 9460, -1, 9580, 9583, 9578, -1, 7262, 9584, 7264, -1, 7264, 9584, 9571, -1, 9565, 9584, 9576, -1, 9460, 9585, 9462, -1, 9571, 9584, 9565, -1, 9583, 9585, 9460, -1, 9573, 9586, 9567, -1, 9464, 9587, 9465, -1, 9567, 9586, 9581, -1, 9462, 9587, 9464, -1, 9569, 9588, 9563, -1, 9563, 9588, 9582, -1, 9465, 9589, 9466, -1, 9587, 9589, 9465, -1, 9582, 9590, 9573, -1, 9573, 9590, 9586, -1, 9585, 9591, 9462, -1, 9569, 9592, 9588, -1, 9576, 9592, 9569, -1, 9462, 9591, 9587, -1, 9587, 9593, 9589, -1, 9591, 9593, 9587, -1, 7044, 9594, 7042, -1, 9581, 9594, 7044, -1, 9593, 9595, 9589, -1, 9591, 9596, 9593, -1, 9582, 9597, 9590, -1, 9589, 9598, 9466, -1, 9588, 9597, 9582, -1, 9599, 9598, 9600, -1, 9466, 9598, 9599, -1, 9595, 9598, 9589, -1, 7262, 9601, 9584, -1, 9600, 9602, 9603, -1, 9584, 9601, 9576, -1, 9576, 9601, 9592, -1, 9593, 9602, 9595, -1, 9596, 9602, 9593, -1, 9598, 9602, 9600, -1, 9595, 9602, 9598, -1, 9470, 9604, 9605, -1, 9586, 9606, 9581, -1, 9605, 9604, 9607, -1, 9581, 9606, 9594, -1, 9588, 9608, 9597, -1, 9470, 9609, 9604, -1, 9472, 9609, 9468, -1, 9592, 9608, 9588, -1, 9468, 9609, 9470, -1, 9594, 9610, 7042, -1, 9472, 9611, 9609, -1, 9586, 9612, 9606, -1, 9474, 9613, 9472, -1, 9590, 9612, 9586, -1, 7262, 9614, 9601, -1, 9592, 9614, 9608, -1, 7257, 9614, 7262, -1, 9472, 9613, 9611, -1, 9601, 9614, 9592, -1, 9615, 9616, 9617, -1, 9617, 9616, 9478, -1, 9594, 9618, 9610, -1, 9476, 9619, 9474, -1, 9606, 9618, 9594, -1, 9478, 9619, 9476, -1, 9474, 9619, 9613, -1, 9616, 9619, 9478, -1, 9590, 9620, 9612, -1, 9613, 9619, 9616, -1, 9617, 9621, 9615, -1, 9597, 9620, 9590, -1, 9478, 9621, 9617, -1, 9612, 9622, 9606, -1, 9606, 9622, 9618, -1, 9477, 9623, 9478, -1, 9480, 9623, 9477, -1, 9478, 9623, 9621, -1, 9608, 9624, 9597, -1, 9597, 9624, 9620, -1, 9480, 9625, 9623, -1, 9612, 9626, 9622, -1, 9620, 9626, 9612, -1, 9480, 9627, 9625, -1, 7042, 9628, 7040, -1, 9482, 9627, 9480, -1, 9610, 9628, 7042, -1, 9614, 9629, 9608, -1, 9630, 9631, 9632, -1, 7257, 9629, 9614, -1, 9633, 9631, 9630, -1, 9482, 9634, 9627, -1, 9608, 9629, 9624, -1, 9627, 9634, 9631, -1, 9631, 9634, 9632, -1, 9484, 9634, 9482, -1, 9624, 9635, 9620, -1, 9632, 9634, 9484, -1, 9620, 9635, 9626, -1, 9398, 9636, 9394, -1, 9400, 9636, 9398, -1, 9636, 9637, 9394, -1, 9610, 9638, 9628, -1, 9618, 9638, 9610, -1, 9394, 9637, 9485, -1, 9628, 9639, 7040, -1, 9485, 9637, 9487, -1, 9490, 9640, 9491, -1, 7251, 9641, 7257, -1, 9629, 9641, 9624, -1, 9624, 9641, 9635, -1, 9487, 9640, 9490, -1, 7257, 9641, 9629, -1, 9618, 9642, 9638, -1, 9637, 9643, 9487, -1, 9622, 9642, 9618, -1, 9487, 9643, 9640, -1, 9491, 9644, 9493, -1, 9628, 9645, 9639, -1, 9640, 9644, 9491, -1, 9638, 9645, 9628, -1, 9643, 9646, 9640, -1, 9640, 9646, 9644, -1, 9622, 9647, 9642, -1, 9626, 9647, 9622, -1, 9646, 9648, 9644, -1, 9642, 9649, 9638, -1, 9643, 9650, 9646, -1, 9638, 9649, 9645, -1, 9493, 9651, 9494, -1, 9644, 9651, 9493, -1, 9648, 9651, 9644, -1, 9635, 9652, 9626, -1, 9494, 9651, 9653, -1, 9626, 9652, 9647, -1, 9646, 9654, 9648, -1, 9647, 9655, 9642, -1, 9650, 9654, 9646, -1, 9648, 9654, 9651, -1, 9651, 9654, 9653, -1, 9653, 9654, 9656, -1, 9642, 9655, 9649, -1, 9639, 9437, 7040, -1, 9653, 9657, 9494, -1, 7040, 9437, 7038, -1, 9656, 9657, 9653, -1, 9494, 9658, 9495, -1, 9495, 9658, 9497, -1, 9635, 9659, 9652, -1, 7251, 9659, 9641, -1, 9657, 9658, 9494, -1, 9641, 9659, 9635, -1, 9497, 9660, 9500, -1, 9500, 9660, 9501, -1, 9652, 9661, 9647, -1, 9647, 9661, 9655, -1, 9501, 9662, 9502, -1, 9645, 9439, 9639, -1, 9660, 9662, 9501, -1, 9639, 9439, 9437, -1, 9658, 9663, 9497, -1, 7248, 9664, 7251, -1, 7251, 9664, 9659, -1, 9497, 9663, 9660, -1, 9659, 9664, 9652, -1, 9652, 9664, 9661, -1, 9660, 9665, 9662, -1, 9649, 9539, 9645, -1, 9663, 9665, 9660, -1, 9645, 9539, 9439, -1, 9665, 9666, 9662, -1, 9649, 9541, 9539, -1, 9663, 9667, 9665, -1, 9655, 9541, 9649, -1, 9505, 9668, 9669, -1, 9662, 9668, 9502, -1, 9502, 9668, 9505, -1, 9661, 9670, 9655, -1, 9666, 9668, 9662, -1, 9669, 9671, 9288, -1, 9655, 9670, 9541, -1, 9668, 9671, 9669, -1, 9665, 9671, 9666, -1, 9667, 9671, 9665, -1, 9666, 9671, 9668, -1, 9669, 9672, 9505, -1, 9288, 9672, 9669, -1, 7248, 9673, 9664, -1, 9664, 9673, 9661, -1, 9505, 9674, 9507, -1, 9661, 9673, 9670, -1, 9672, 9674, 9505, -1, 9510, 9675, 9511, -1, 9507, 9675, 9510, -1, 9511, 9676, 9409, -1, 9675, 9676, 9511, -1, 9674, 9677, 9507, -1, 9507, 9677, 9675, -1, 9677, 9678, 9675, -1, 9675, 9678, 9676, -1, 9678, 9679, 9676, -1, 9677, 9680, 9678, -1, 9676, 9681, 9409, -1, 9409, 9681, 9413, -1, 9413, 9681, 9416, -1, 9679, 9681, 9676, -1, 9680, 9682, 9678, -1, 9681, 9682, 9416, -1, 9416, 9682, 9307, -1, 9679, 9682, 9681, -1, 9678, 9682, 9679, -1, 9396, 9683, 9395, -1, 9513, 9683, 9396, -1, 9515, 9683, 9513, -1, 9518, 9683, 9515, -1, 9518, 9684, 9683, -1, 9519, 9685, 9518, -1, 9518, 9685, 9684, -1, 9686, 9685, 9523, -1, 9522, 9685, 9519, -1, 9523, 9685, 9522, -1, 9526, 9687, 9523, -1, 9523, 9687, 9686, -1, 9528, 9687, 9526, -1, 9532, 9687, 9528, -1, 9532, 9688, 9687, -1, 9408, 9689, 9411, -1, 9532, 9689, 9688, -1, 9533, 9689, 9532, -1, 9411, 9689, 9535, -1, 9535, 9689, 9533, -1, 9543, 9690, 9547, -1, 9670, 9690, 9541, -1, 9541, 9690, 9540, -1, 9540, 9690, 9543, -1, 9690, 9691, 9547, -1, 9466, 9692, 7034, -1, 7034, 9692, 7033, -1, 9691, 9693, 9547, -1, 9559, 9693, 9560, -1, 9554, 9693, 9559, -1, 9547, 9693, 9554, -1, 9694, 9695, 9560, -1, 9564, 9695, 9570, -1, 9562, 9695, 9564, -1, 9599, 9696, 9466, -1, 9560, 9695, 9562, -1, 9466, 9696, 9692, -1, 9695, 9697, 9570, -1, 9600, 9698, 9599, -1, 9599, 9698, 9696, -1, 9603, 9699, 9600, -1, 9600, 9699, 9698, -1, 9570, 9700, 9575, -1, 9579, 9700, 9580, -1, 9575, 9700, 9579, -1, 9697, 9700, 9570, -1, 9585, 9701, 9591, -1, 9702, 9701, 9580, -1, 9703, 9704, 9603, -1, 9603, 9704, 9699, -1, 9580, 9701, 9583, -1, 9583, 9701, 9585, -1, 9692, 9705, 7033, -1, 7033, 9705, 7032, -1, 9701, 9706, 9591, -1, 7229, 9707, 7233, -1, 7233, 9707, 9708, -1, 9708, 9707, 9703, -1, 9706, 9709, 9591, -1, 9703, 9707, 9704, -1, 9591, 9709, 9596, -1, 9696, 9710, 9692, -1, 9602, 9709, 9603, -1, 9596, 9709, 9602, -1, 9611, 9711, 9609, -1, 9692, 9710, 9705, -1, 9609, 9711, 9604, -1, 9604, 9711, 9607, -1, 9698, 9712, 9696, -1, 9607, 9711, 9713, -1, 9696, 9712, 9710, -1, 9611, 9714, 9711, -1, 9699, 9715, 9698, -1, 9698, 9715, 9712, -1, 9613, 9716, 9611, -1, 9611, 9716, 9714, -1, 9615, 9716, 9616, -1, 9704, 9717, 9699, -1, 9616, 9716, 9613, -1, 9699, 9717, 9715, -1, 9718, 9716, 9615, -1, 9621, 9719, 9615, -1, 7032, 9720, 7068, -1, 9625, 9719, 9623, -1, 9705, 9720, 7032, -1, 9623, 9719, 9621, -1, 9615, 9719, 9718, -1, 9625, 9721, 9719, -1, 7225, 9722, 7229, -1, 7229, 9722, 9707, -1, 9707, 9722, 9704, -1, 9704, 9722, 9717, -1, 9710, 9723, 9705, -1, 9625, 9724, 9721, -1, 9627, 9724, 9625, -1, 9631, 9724, 9627, -1, 9633, 9724, 9631, -1, 9705, 9723, 9720, -1, 9725, 9724, 9633, -1, 9712, 9726, 9710, -1, 9710, 9726, 9723, -1, 9637, 9727, 9643, -1, 9636, 9727, 9637, -1, 9400, 9727, 9636, -1, 9402, 9727, 9400, -1, 9715, 9728, 9712, -1, 9712, 9728, 9726, -1, 9727, 9729, 9643, -1, 9717, 9730, 9715, -1, 9715, 9730, 9728, -1, 9643, 9731, 9650, -1, 9650, 9731, 9654, -1, 7068, 9732, 7067, -1, 9654, 9731, 9656, -1, 9729, 9731, 9643, -1, 9720, 9732, 7068, -1, 9275, 9279, 9656, -1, 9656, 9279, 9657, -1, 9658, 9279, 9663, -1, 9717, 9733, 9730, -1, 9657, 9279, 9658, -1, 7216, 9733, 7225, -1, 7225, 9733, 9722, -1, 9722, 9733, 9717, -1, 9720, 9713, 9732, -1, 9723, 9713, 9720, -1, 9279, 9283, 9663, -1, 9723, 9607, 9713, -1, 9663, 9292, 9667, -1, 9671, 9292, 9288, -1, 9667, 9292, 9671, -1, 9726, 9607, 9723, -1, 9283, 9292, 9663, -1, 9672, 9301, 9674, -1, 9290, 9301, 9288, -1, 9726, 9605, 9607, -1, 9288, 9301, 9672, -1, 9674, 9301, 9677, -1, 9728, 9605, 9726, -1, 9728, 9470, 9605, -1, 9730, 9470, 9728, -1, 9301, 9302, 9677, -1, 9677, 9305, 9680, -1, 9680, 9305, 9682, -1, 9682, 9305, 9307, -1, 9302, 9305, 9677, -1, 9733, 9469, 9730, -1, 7216, 9469, 9733, -1, 9390, 9734, 7061, -1, 7211, 9469, 7216, -1, 9395, 9734, 9390, -1, 9730, 9469, 9470, -1, 9395, 9735, 9734, -1, 9683, 9735, 9395, -1, 9684, 9735, 9683, -1, 9734, 9736, 7061, -1, 7061, 9736, 7059, -1, 9735, 9736, 9734, -1, 9684, 9736, 9735, -1, 9684, 9737, 9736, -1, 9686, 9737, 9685, -1, 9685, 9737, 9684, -1, 9736, 9738, 7059, -1, 9686, 9738, 9737, -1, 9739, 9738, 9686, -1, 7059, 9738, 9739, -1, 9737, 9738, 9736, -1, 9686, 9740, 9739, -1, 9739, 9740, 7059, -1, 9687, 9741, 9686, -1, 9688, 9741, 9687, -1, 9686, 9741, 9740, -1, 9741, 9742, 9740, -1, 9740, 9742, 7059, -1, 9688, 9742, 9741, -1, 7059, 9742, 7057, -1, 9689, 9743, 9688, -1, 9688, 9743, 9742, -1, 9408, 9743, 9689, -1, 9744, 9745, 7065, -1, 7065, 9745, 7062, -1, 9743, 9746, 9742, -1, 9742, 9746, 7057, -1, 9408, 9746, 9743, -1, 7057, 9746, 9406, -1, 9406, 9746, 9408, -1, 9673, 9747, 9670, -1, 7248, 9747, 9673, -1, 9670, 9748, 9690, -1, 9725, 9749, 9744, -1, 9690, 9748, 9691, -1, 9744, 9749, 9745, -1, 7248, 9748, 9747, -1, 9747, 9748, 9670, -1, 7245, 9750, 7248, -1, 9748, 9750, 9691, -1, 7248, 9750, 9748, -1, 9693, 9751, 9560, -1, 9560, 9751, 9694, -1, 9725, 9752, 9749, -1, 9633, 9752, 9725, -1, 9694, 9751, 9753, -1, 9691, 9754, 9693, -1, 9750, 9754, 9691, -1, 7245, 9754, 9750, -1, 9693, 9754, 9751, -1, 9753, 9755, 7245, -1, 9751, 9755, 9753, -1, 7245, 9755, 9754, -1, 9630, 9756, 9633, -1, 9754, 9755, 9751, -1, 9633, 9756, 9752, -1, 7245, 9757, 9753, -1, 9745, 9758, 7062, -1, 9753, 9757, 9694, -1, 9694, 9759, 9695, -1, 9757, 9759, 9694, -1, 9695, 9759, 9697, -1, 7245, 9759, 9757, -1, 9632, 9760, 9630, -1, 9630, 9760, 9756, -1, 7239, 9761, 7245, -1, 7245, 9761, 9759, -1, 9745, 9762, 9758, -1, 9759, 9761, 9697, -1, 9749, 9762, 9745, -1, 9580, 9763, 9702, -1, 9702, 9763, 9764, -1, 9700, 9763, 9580, -1, 9697, 9765, 9700, -1, 7062, 9766, 7060, -1, 7239, 9765, 9761, -1, 9758, 9766, 7062, -1, 9761, 9765, 9697, -1, 9700, 9765, 9763, -1, 9764, 9767, 7239, -1, 7296, 9768, 9484, -1, 9763, 9767, 9764, -1, 9484, 9768, 9632, -1, 7239, 9767, 9765, -1, 9632, 9768, 9760, -1, 9765, 9767, 9763, -1, 7239, 9769, 9764, -1, 9764, 9769, 9702, -1, 9752, 9770, 9749, -1, 9749, 9770, 9762, -1, 9702, 9771, 9701, -1, 9769, 9771, 9702, -1, 9762, 9772, 9758, -1, 9758, 9772, 9766, -1, 7239, 9771, 9769, -1, 9701, 9771, 9706, -1, 7233, 9773, 7239, -1, 9756, 9774, 9752, -1, 9752, 9774, 9770, -1, 7239, 9773, 9771, -1, 9771, 9773, 9706, -1, 9603, 9775, 9703, -1, 9709, 9775, 9603, -1, 9770, 9776, 9762, -1, 9762, 9776, 9772, -1, 9706, 9777, 9709, -1, 7233, 9777, 9773, -1, 9773, 9777, 9706, -1, 9756, 9778, 9774, -1, 9709, 9777, 9775, -1, 9760, 9778, 9756, -1, 7233, 9779, 9777, -1, 9708, 9779, 7233, -1, 9703, 9779, 9708, -1, 9766, 9780, 7060, -1, 9775, 9779, 9703, -1, 9777, 9779, 9775, -1, 9713, 9781, 9732, -1, 9732, 9781, 7067, -1, 9714, 9782, 9711, -1, 9774, 9783, 9770, -1, 9713, 9782, 9781, -1, 9770, 9783, 9776, -1, 9760, 9784, 9778, -1, 9711, 9782, 9713, -1, 7293, 9784, 7296, -1, 7296, 9784, 9768, -1, 9768, 9784, 9760, -1, 9782, 9785, 9781, -1, 9766, 9786, 9780, -1, 7067, 9785, 7066, -1, 9781, 9785, 7067, -1, 9772, 9786, 9766, -1, 9714, 9785, 9782, -1, 9778, 9787, 9774, -1, 9716, 9788, 9714, -1, 9718, 9788, 9716, -1, 9714, 9788, 9785, -1, 9774, 9787, 9783, -1, 9789, 9790, 9718, -1, 9780, 9791, 7060, -1, 9718, 9790, 9788, -1, 9785, 9790, 7066, -1, 9788, 9790, 9785, -1, 7066, 9790, 9789, -1, 9718, 9792, 9789, -1, 7060, 9791, 7058, -1, 9772, 9793, 9786, -1, 9789, 9792, 7066, -1, 9719, 9794, 9718, -1, 9776, 9793, 9772, -1, 9721, 9794, 9719, -1, 7293, 9795, 9784, -1, 9718, 9794, 9792, -1, 9784, 9795, 9778, -1, 9778, 9795, 9787, -1, 9794, 9796, 9792, -1, 9786, 9282, 9780, -1, 9780, 9282, 9791, -1, 7066, 9796, 7065, -1, 9792, 9796, 7066, -1, 9721, 9796, 9794, -1, 9783, 9272, 9776, -1, 9724, 9797, 9721, -1, 9776, 9272, 9793, -1, 9721, 9797, 9796, -1, 9725, 9797, 9724, -1, 9725, 9798, 9797, -1, 9797, 9798, 9796, -1, 7065, 9798, 9744, -1, 9744, 9798, 9725, -1, 9786, 9280, 9282, -1, 9796, 9798, 7065, -1, 9793, 9280, 9786, -1, 9404, 9799, 9402, -1, 9783, 9270, 9272, -1, 9787, 9270, 9783, -1, 7274, 9799, 9404, -1, 7274, 9800, 9799, -1, 9791, 9276, 7058, -1, 9727, 9800, 9729, -1, 9799, 9800, 9402, -1, 9402, 9800, 9727, -1, 7273, 9801, 7274, -1, 9800, 9801, 9729, -1, 7274, 9801, 9800, -1, 9272, 9273, 9793, -1, 9793, 9273, 9280, -1, 9656, 9268, 9275, -1, 7287, 9287, 7293, -1, 9275, 9268, 9269, -1, 7293, 9287, 9795, -1, 9731, 9268, 9656, -1, 9795, 9287, 9787, -1, 9787, 9287, 9270, -1, 7273, 9267, 9801, -1, 9791, 9285, 9276, -1, 9731, 9267, 9268, -1, 9282, 9285, 9791, -1, 9729, 9267, 9731, -1, 9801, 9267, 9729, -1, 9269, 9266, 7273, -1, 9802, 9803, 9804, -1, 9802, 9804, 9805, -1, 9806, 9807, 9808, -1, 9802, 9805, 9809, -1, 9810, 9802, 9809, -1, 9810, 9803, 9802, -1, 9806, 9808, 9811, -1, 9812, 9804, 9803, -1, 9812, 9813, 9814, -1, 9815, 4717, 4715, -1, 9812, 9814, 9804, -1, 9816, 9810, 9809, -1, 9816, 9803, 9810, -1, 9817, 7545, 7544, -1, 9816, 9818, 9819, -1, 9816, 9809, 9818, -1, 9817, 9820, 7545, -1, 9816, 9819, 9803, -1, 9821, 9813, 9812, -1, 9821, 9822, 9813, -1, 9821, 9823, 9822, -1, 9824, 9825, 9820, -1, 9824, 9820, 9817, -1, 9826, 9811, 9825, -1, 9827, 9821, 9812, -1, 9828, 9819, 9829, -1, 9826, 9825, 9824, -1, 9828, 9803, 9819, -1, 9830, 9806, 9811, -1, 9830, 9811, 9826, -1, 9831, 9829, 9832, -1, 9833, 4717, 9834, -1, 9831, 9828, 9829, -1, 9833, 4719, 4717, -1, 9835, 9836, 9828, -1, 9835, 9828, 9831, -1, 9837, 7542, 7540, -1, 9837, 9838, 7542, -1, 9839, 9831, 9832, -1, 9839, 9835, 9831, -1, 9839, 9832, 9840, -1, 9839, 9840, 9841, -1, 9842, 9835, 9839, -1, 9842, 9836, 9835, -1, 9842, 9843, 9836, -1, 9842, 9839, 9841, -1, 9842, 9841, 9844, -1, 9845, 9846, 9838, -1, 9845, 9838, 9837, -1, 9847, 9826, 9824, -1, 9848, 9849, 9846, -1, 9848, 9846, 9845, -1, 9850, 9851, 9852, -1, 9850, 9853, 9851, -1, 9850, 9826, 9847, -1, 9850, 9847, 9854, -1, 9850, 9830, 9826, -1, 9850, 9852, 9830, -1, 9855, 9849, 9848, -1, 9855, 9856, 9849, -1, 9857, 9837, 7540, -1, 9858, 9856, 9855, -1, 9859, 9846, 9849, -1, 9858, 9860, 9856, -1, 9861, 9862, 9863, -1, 9861, 9856, 9862, -1, 9864, 9837, 9857, -1, 9861, 9865, 9859, -1, 9861, 9859, 9849, -1, 9861, 9849, 9856, -1, 9864, 9845, 9837, -1, 9861, 9863, 9853, -1, 9866, 9867, 9868, -1, 9869, 9870, 9860, -1, 9869, 4721, 9870, -1, 9866, 4719, 9867, -1, 9869, 9860, 9858, -1, 9866, 9871, 4719, -1, 9872, 9868, 9851, -1, 9872, 9851, 9853, -1, 9872, 9863, 9873, -1, 9872, 9873, 9871, -1, 9874, 7540, 7538, -1, 9872, 9866, 9868, -1, 9872, 9871, 9866, -1, 9874, 9857, 7540, -1, 9872, 9853, 9863, -1, 9875, 9876, 9877, -1, 9875, 9878, 9876, -1, 9875, 9877, 9879, -1, 9880, 9845, 9864, -1, 9880, 9848, 9845, -1, 9881, 9864, 9857, -1, 9882, 9883, 9878, -1, 9882, 9884, 9883, -1, 9881, 9857, 9874, -1, 9882, 9878, 9875, -1, 9885, 9855, 9848, -1, 9885, 9848, 9880, -1, 9886, 9882, 9875, -1, 9887, 9864, 9881, -1, 9887, 9880, 9864, -1, 9888, 9858, 9855, -1, 9888, 9855, 9885, -1, 9889, 9879, 9890, -1, 9889, 9890, 9891, -1, 9892, 9885, 9880, -1, 9889, 9891, 9893, -1, 9892, 9880, 9887, -1, 9894, 4721, 9869, -1, 9894, 9869, 9858, -1, 9894, 9858, 9888, -1, 9895, 9889, 9893, -1, 9894, 4723, 4721, -1, 9895, 9896, 9889, -1, 9895, 9893, 9897, -1, 9898, 9874, 7538, -1, 9895, 9897, 9899, -1, 9900, 9901, 9902, -1, 9900, 9893, 9903, -1, 9904, 9888, 9885, -1, 9904, 9885, 9892, -1, 9900, 9903, 9901, -1, 9905, 9897, 9893, -1, 9906, 9881, 9874, -1, 9905, 9899, 9897, -1, 9906, 9874, 9898, -1, 9905, 9893, 9900, -1, 9907, 9894, 9888, -1, 9907, 9888, 9904, -1, 9907, 4723, 9894, -1, 9908, 9905, 9900, -1, 9909, 9887, 9881, -1, 9910, 9902, 9911, -1, 9909, 9881, 9906, -1, 9910, 9911, 9912, -1, 9913, 7538, 7536, -1, 9913, 9898, 7538, -1, 9914, 9892, 9887, -1, 9914, 9887, 9909, -1, 9915, 9898, 9913, -1, 9915, 9906, 9898, -1, 9916, 9912, 9917, -1, 9916, 9918, 9910, -1, 9916, 9910, 9912, -1, 9919, 9904, 9892, -1, 9919, 9892, 9914, -1, 9920, 9916, 9917, -1, 9921, 9909, 9906, -1, 9920, 9922, 9923, -1, 9920, 9917, 9922, -1, 9924, 9918, 9916, -1, 9921, 9906, 9915, -1, 9924, 9923, 9925, -1, 9924, 9926, 9918, -1, 9924, 9920, 9923, -1, 9927, 9907, 9904, -1, 9924, 9916, 9920, -1, 9927, 4723, 9907, -1, 9927, 9904, 9919, -1, 9928, 9929, 9930, -1, 9927, 4725, 4723, -1, 9931, 9914, 9909, -1, 9928, 9922, 9932, -1, 9928, 9932, 9929, -1, 9931, 9909, 9921, -1, 9933, 9925, 9923, -1, 9933, 9922, 9928, -1, 9934, 9913, 7536, -1, 9933, 9923, 9922, -1, 9935, 9919, 9914, -1, 9935, 9914, 9931, -1, 9936, 9933, 9928, -1, 9937, 9913, 9934, -1, 9937, 9915, 9913, -1, 9938, 9930, 9939, -1, 9938, 9939, 9940, -1, 9941, 9927, 9919, -1, 9941, 4725, 9927, -1, 9941, 9919, 9935, -1, 9942, 9915, 9937, -1, 9942, 9921, 9915, -1, 9943, 9938, 9940, -1, 9944, 7536, 7534, -1, 9943, 9940, 9945, -1, 9944, 9934, 7536, -1, 9946, 9931, 9921, -1, 9946, 9921, 9942, -1, 9947, 9938, 9943, -1, 9947, 9948, 9938, -1, 9949, 9937, 9934, -1, 9950, 9945, 9951, -1, 9950, 9951, 9952, -1, 9949, 9934, 9944, -1, 9950, 9947, 9943, -1, 9953, 9935, 9931, -1, 9950, 9943, 9945, -1, 9954, 9952, 9955, -1, 9953, 9931, 9946, -1, 9954, 9950, 9952, -1, 9954, 9948, 9947, -1, 9954, 9956, 9948, -1, 9954, 9947, 9950, -1, 9957, 9958, 9959, -1, 9960, 9942, 9937, -1, 9957, 9961, 9962, -1, 9960, 9937, 9949, -1, 9957, 9959, 9961, -1, 9963, 4725, 9941, -1, 9964, 9958, 9957, -1, 9963, 9941, 9935, -1, 9963, 4727, 4725, -1, 9963, 9935, 9953, -1, 9964, 9957, 9962, -1, 9965, 9959, 9958, -1, 9966, 9944, 7534, -1, 9965, 9951, 9967, -1, 9965, 9967, 9959, -1, 9968, 9942, 9960, -1, 9969, 9970, 9971, -1, 9969, 9962, 9970, -1, 9969, 9971, 9958, -1, 9968, 9946, 9942, -1, 9969, 9958, 9964, -1, 9969, 9964, 9962, -1, 9972, 9944, 9966, -1, 9973, 9952, 9951, -1, 9973, 9955, 9952, -1, 9972, 9949, 9944, -1, 9973, 9951, 9965, -1, 9974, 9946, 9968, -1, 9974, 9953, 9946, -1, 9975, 9960, 9949, -1, 9975, 9949, 9972, -1, 9976, 9973, 9965, -1, 9977, 9971, 9978, -1, 9977, 9958, 9971, -1, 9979, 4727, 9963, -1, 9979, 9953, 9974, -1, 9979, 9963, 9953, -1, 9980, 7534, 7532, -1, 9980, 9966, 7534, -1, 9981, 9968, 9960, -1, 9981, 9960, 9975, -1, 9982, 9978, 9983, -1, 9982, 9977, 9978, -1, 9984, 9966, 9980, -1, 9985, 9986, 9977, -1, 9984, 9972, 9966, -1, 9985, 9977, 9982, -1, 9987, 9968, 9981, -1, 9987, 9974, 9968, -1, 9988, 9975, 9972, -1, 9989, 9983, 9990, -1, 9989, 9990, 9991, -1, 9988, 9972, 9984, -1, 9989, 9982, 9983, -1, 9989, 9985, 9982, -1, 1172, 7512, 1169, -1, 9992, 9991, 9993, -1, 9992, 9986, 9985, -1, 9994, 4727, 9979, -1, 9994, 9979, 9974, -1, 9992, 9989, 9991, -1, 9994, 9974, 9987, -1, 9992, 9995, 9986, -1, 9994, 4729, 4727, -1, 9992, 9985, 9989, -1, 9996, 9997, 9998, -1, 9996, 9999, 9997, -1, 10000, 9980, 7532, -1, 9996, 10001, 10002, -1, 9996, 10003, 9999, -1, 9996, 10002, 10003, -1, 9996, 9998, 10001, -1, 10004, 9981, 9975, -1, 10005, 10006, 9997, -1, 10005, 10007, 10006, -1, 10004, 9975, 9988, -1, 10005, 9997, 9999, -1, 10005, 4742, 10007, -1, 10008, 9999, 10003, -1, 10009, 9984, 9980, -1, 10008, 10010, 10011, -1, 10008, 10003, 10010, -1, 10009, 9980, 10000, -1, 10008, 4744, 4742, -1, 10008, 10011, 4744, -1, 10008, 10005, 9999, -1, 10008, 4742, 10005, -1, 10012, 10013, 10014, -1, 10015, 9987, 9981, -1, 10012, 10016, 10017, -1, 10015, 9981, 10004, -1, 10012, 10014, 10018, -1, 10012, 10019, 10016, -1, 10012, 10018, 10019, -1, 10012, 10020, 10013, -1, 10012, 10017, 10020, -1, 10021, 10011, 10022, -1, 10023, 1128, 1130, -1, 10021, 10017, 10016, -1, 10021, 10022, 10017, -1, 10024, 9984, 10009, -1, 10021, 4744, 10011, -1, 10025, 10021, 10016, -1, 10024, 9988, 9984, -1, 10025, 4744, 10021, -1, 10023, 1130, 7557, -1, 10026, 9994, 9987, -1, 10025, 10027, 4746, -1, 10026, 4729, 9994, -1, 10025, 10016, 10019, -1, 10028, 1418, 1128, -1, 10026, 9987, 10015, -1, 10025, 10029, 10027, -1, 10025, 10019, 10029, -1, 10025, 4746, 4744, -1, 10030, 10031, 10032, -1, 10033, 7532, 7530, -1, 10030, 10034, 10031, -1, 10033, 10000, 7532, -1, 10030, 10032, 10035, -1, 10030, 10036, 10034, -1, 10030, 10035, 10037, -1, 10028, 1128, 10023, -1, 10030, 10038, 10036, -1, 10039, 1420, 1418, -1, 10030, 10037, 10038, -1, 10039, 1424, 1420, -1, 10040, 10027, 10041, -1, 10042, 10004, 9988, -1, 10040, 4746, 10027, -1, 10042, 9988, 10024, -1, 10040, 10041, 10034, -1, 10040, 10034, 10036, -1, 10039, 1418, 10028, -1, 10043, 10040, 10036, -1, 10043, 9823, 4748, -1, 10044, 10000, 10033, -1, 10043, 4748, 4746, -1, 10044, 10009, 10000, -1, 10043, 4746, 10040, -1, 10043, 10045, 9823, -1, 10043, 10036, 10038, -1, 10046, 1424, 10039, -1, 10043, 10038, 10045, -1, 10047, 9812, 9803, -1, 10048, 1425, 1424, -1, 10047, 9828, 9836, -1, 10048, 1424, 10046, -1, 10047, 9843, 10049, -1, 10050, 10015, 10004, -1, 10047, 9803, 9828, -1, 10047, 10049, 9827, -1, 10047, 9836, 9843, -1, 10050, 10004, 10042, -1, 10047, 9827, 9812, -1, 10051, 1160, 1425, -1, 10052, 9823, 9821, -1, 10051, 1158, 1160, -1, 10052, 9827, 10049, -1, 10051, 4712, 1158, -1, 10053, 10024, 10009, -1, 10052, 4748, 9823, -1, 10052, 9821, 9827, -1, 10051, 1425, 10048, -1, 10053, 10009, 10044, -1, 10054, 10049, 9843, -1, 10054, 10052, 10049, -1, 10054, 4748, 10052, -1, 10055, 7557, 7559, -1, 10054, 9842, 9844, -1, 10056, 4729, 10026, -1, 10054, 9843, 9842, -1, 10055, 10023, 7557, -1, 10056, 10015, 10050, -1, 10054, 9844, 4709, -1, 10056, 10026, 10015, -1, 10054, 4709, 4748, -1, 10056, 4731, 4729, -1, 10057, 9847, 9824, -1, 10057, 9817, 7544, -1, 10058, 10033, 7530, -1, 10057, 9854, 9847, -1, 10057, 10059, 9854, -1, 10060, 10028, 10023, -1, 10057, 9824, 9817, -1, 10061, 7544, 7542, -1, 10060, 10023, 10055, -1, 10062, 10042, 10024, -1, 10061, 10059, 10057, -1, 10062, 10024, 10053, -1, 10063, 10039, 10028, -1, 10061, 10057, 7544, -1, 10064, 7542, 9838, -1, 10064, 9846, 9859, -1, 10065, 10033, 10058, -1, 10064, 9838, 9846, -1, 10063, 10028, 10060, -1, 10064, 9865, 10059, -1, 10064, 9859, 9865, -1, 10065, 10044, 10033, -1, 10064, 10059, 10061, -1, 10064, 10061, 7542, -1, 10066, 9850, 9854, -1, 10067, 10039, 10063, -1, 10068, 10042, 10062, -1, 10066, 10059, 9865, -1, 10068, 10050, 10042, -1, 10066, 9854, 10059, -1, 10066, 9861, 9853, -1, 10066, 9865, 9861, -1, 10067, 10046, 10039, -1, 10066, 9853, 9850, -1, 10069, 10046, 10067, -1, 10070, 9875, 9879, -1, 10070, 10071, 9886, -1, 10072, 10053, 10044, -1, 10070, 9879, 9889, -1, 10070, 9886, 9875, -1, 10070, 9889, 9896, -1, 10069, 10048, 10046, -1, 10072, 10044, 10065, -1, 10070, 9896, 10071, -1, 10073, 9886, 10071, -1, 10074, 10048, 10069, -1, 10073, 4741, 9884, -1, 10073, 9882, 9886, -1, 10074, 10051, 10048, -1, 10075, 10050, 10068, -1, 10074, 4712, 10051, -1, 10075, 10056, 10050, -1, 10073, 9884, 9882, -1, 10074, 4714, 4712, -1, 10075, 4731, 10056, -1, 10076, 10055, 7559, -1, 10077, 4741, 10073, -1, 10077, 10073, 10071, -1, 10077, 9895, 9899, -1, 10078, 10062, 10053, -1, 10077, 10071, 9896, -1, 10076, 7559, 7561, -1, 10077, 9899, 4743, -1, 10077, 9896, 9895, -1, 10077, 4743, 4741, -1, 10078, 10053, 10072, -1, 10079, 9918, 9926, -1, 10079, 9926, 10080, -1, 10079, 9908, 9900, -1, 10079, 9900, 9902, -1, 10081, 7530, 7528, -1, 10079, 9902, 9910, -1, 10082, 10055, 10076, -1, 10079, 9910, 9918, -1, 10081, 10058, 7530, -1, 10079, 10080, 9908, -1, 10083, 4743, 9899, -1, 10082, 10060, 10055, -1, 10083, 9899, 9905, -1, 10083, 9908, 10080, -1, 10084, 10060, 10082, -1, 10085, 10068, 10062, -1, 10083, 9905, 9908, -1, 10086, 4743, 10083, -1, 10086, 10083, 10080, -1, 10084, 10063, 10060, -1, 10085, 10062, 10078, -1, 10086, 9925, 4745, -1, 10086, 10080, 9926, -1, 10086, 9926, 9924, -1, 10087, 10058, 10081, -1, 10086, 9924, 9925, -1, 10086, 4745, 4743, -1, 10088, 9928, 9930, -1, 10087, 10065, 10058, -1, 10088, 9936, 9928, -1, 10088, 9930, 9938, -1, 10088, 9938, 9948, -1, 10088, 9956, 10089, -1, 10090, 10063, 10084, -1, 10088, 9948, 9956, -1, 10090, 10067, 10063, -1, 10091, 10075, 10068, -1, 10088, 10089, 9936, -1, 10092, 10067, 10090, -1, 10091, 4733, 4731, -1, 10093, 4745, 9925, -1, 10092, 10069, 10067, -1, 10091, 10068, 10085, -1, 10091, 4731, 10075, -1, 10093, 9933, 9936, -1, 10093, 9936, 10089, -1, 10093, 9925, 9933, -1, 10094, 10065, 10087, -1, 10095, 9955, 4747, -1, 10096, 4716, 4714, -1, 10095, 10093, 10089, -1, 10095, 10089, 9956, -1, 10095, 9954, 9955, -1, 10094, 10072, 10065, -1, 10095, 9956, 9954, -1, 10095, 4745, 10093, -1, 10095, 4747, 4745, -1, 10097, 7561, 7563, -1, 10098, 9965, 9958, -1, 10098, 9977, 9986, -1, 10097, 10076, 7561, -1, 10098, 9976, 9965, -1, 10099, 10081, 7528, -1, 10098, 9958, 9977, -1, 10100, 10076, 10097, -1, 10098, 10101, 9976, -1, 10098, 9986, 9995, -1, 10098, 9995, 10101, -1, 10102, 10072, 10094, -1, 10103, 4747, 9955, -1, 10103, 9955, 9973, -1, 10103, 9973, 9976, -1, 10102, 10078, 10072, -1, 10100, 10082, 10076, -1, 10104, 10087, 10081, -1, 10103, 9976, 10101, -1, 10105, 4749, 4747, -1, 10105, 9993, 4749, -1, 10105, 4747, 10103, -1, 10106, 10084, 10082, -1, 10105, 10103, 10101, -1, 10106, 10082, 10100, -1, 10104, 10081, 10099, -1, 10105, 9992, 9993, -1, 10105, 10101, 9995, -1, 10107, 10085, 10078, -1, 10105, 9995, 9992, -1, 10107, 10078, 10102, -1, 10108, 10090, 10084, -1, 10108, 10084, 10106, -1, 10109, 10094, 10087, -1, 10109, 10087, 10104, -1, 10110, 10092, 10090, -1, 10110, 10090, 10108, -1, 10111, 4733, 10091, -1, 10111, 10091, 10085, -1, 10112, 4718, 4716, -1, 10111, 10085, 10107, -1, 10113, 10102, 10094, -1, 10114, 10097, 7563, -1, 10113, 10094, 10109, -1, 10114, 7563, 7565, -1, 10115, 7528, 7526, -1, 10115, 10099, 7528, -1, 10116, 10097, 10114, -1, 10116, 10100, 10097, -1, 10117, 10107, 10102, -1, 10117, 10102, 10113, -1, 10118, 10100, 10116, -1, 10119, 10104, 10099, -1, 10118, 10106, 10100, -1, 10119, 10099, 10115, -1, 10120, 10108, 10106, -1, 10121, 4733, 10111, -1, 10121, 10111, 10107, -1, 10121, 10107, 10117, -1, 10121, 4735, 4733, -1, 10120, 10106, 10118, -1, 10122, 10115, 7526, -1, 10123, 4718, 10124, -1, 10123, 4720, 4718, -1, 10125, 10104, 10119, -1, 10126, 10114, 7565, -1, 10125, 10109, 10104, -1, 10126, 7565, 7479, -1, 10127, 10119, 10115, -1, 10128, 10114, 10126, -1, 10127, 10115, 10122, -1, 10128, 10116, 10114, -1, 10129, 10113, 10109, -1, 10129, 10109, 10125, -1, 10130, 10126, 7479, -1, 10131, 10125, 10119, -1, 10130, 7479, 7480, -1, 10131, 10119, 10127, -1, 10132, 10118, 10116, -1, 10133, 10117, 10113, -1, 10132, 10116, 10128, -1, 10133, 10113, 10129, -1, 10134, 10126, 10130, -1, 10134, 10128, 10126, -1, 10135, 10129, 10125, -1, 10135, 10125, 10131, -1, 10136, 10120, 10118, -1, 10137, 10121, 10117, -1, 10136, 10118, 10132, -1, 10137, 4735, 10121, -1, 10137, 10117, 10133, -1, 10138, 7526, 7524, -1, 10138, 10122, 7526, -1, 10139, 10132, 10128, -1, 10139, 10128, 10134, -1, 10140, 10129, 10135, -1, 10140, 10133, 10129, -1, 10141, 10122, 10138, -1, 10141, 10127, 10122, -1, 10142, 10136, 10132, -1, 10142, 10132, 10139, -1, 10143, 4720, 10144, -1, 10145, 10133, 10140, -1, 10143, 4722, 4720, -1, 10145, 4735, 10137, -1, 10145, 10137, 10133, -1, 10145, 4737, 4735, -1, 10146, 10138, 7524, -1, 10147, 10130, 7480, -1, 10148, 10144, 10136, -1, 10149, 10131, 10127, -1, 10148, 10136, 10142, -1, 10149, 10127, 10141, -1, 10150, 10134, 10130, -1, 10150, 10130, 10147, -1, 10151, 10138, 10146, -1, 10152, 10144, 10148, -1, 10151, 10141, 10138, -1, 10152, 10143, 10144, -1, 10152, 4722, 10143, -1, 10153, 10135, 10131, -1, 10154, 10147, 7480, -1, 10154, 7480, 7482, -1, 10153, 10131, 10149, -1, 10155, 10139, 10134, -1, 10156, 10149, 10141, -1, 10155, 10134, 10150, -1, 10156, 10141, 10151, -1, 10157, 10140, 10135, -1, 10158, 10150, 10147, -1, 10158, 10147, 10154, -1, 10157, 10135, 10153, -1, 10159, 10149, 10156, -1, 10159, 10153, 10149, -1, 10160, 10142, 10139, -1, 10161, 10145, 10140, -1, 10160, 10139, 10155, -1, 10161, 4737, 10145, -1, 10162, 10155, 10150, -1, 10161, 10140, 10157, -1, 10162, 10150, 10158, -1, 10163, 7524, 7522, -1, 10164, 10148, 10142, -1, 10163, 10146, 7524, -1, 10164, 10142, 10160, -1, 10165, 10157, 10153, -1, 10165, 10153, 10159, -1, 10166, 10155, 10162, -1, 10166, 10160, 10155, -1, 10167, 10146, 10163, -1, 10168, 10152, 10148, -1, 10168, 4722, 10152, -1, 10167, 10151, 10146, -1, 10168, 10148, 10164, -1, 10169, 4737, 10161, -1, 10168, 4724, 4722, -1, 10169, 10161, 10157, -1, 10170, 10154, 7482, -1, 10169, 4739, 4737, -1, 10169, 10157, 10165, -1, 10171, 10163, 7522, -1, 10172, 10160, 10166, -1, 10172, 10164, 10160, -1, 10173, 10156, 10151, -1, 10174, 10158, 10154, -1, 10173, 10151, 10167, -1, 10174, 10154, 10170, -1, 10175, 10163, 10171, -1, 10176, 10164, 10172, -1, 10176, 10168, 10164, -1, 10176, 4724, 10168, -1, 10175, 10167, 10163, -1, 10177, 10159, 10156, -1, 10178, 10170, 7482, -1, 10178, 7482, 7484, -1, 10177, 10156, 10173, -1, 10179, 10162, 10158, -1, 10180, 10173, 10167, -1, 10180, 10167, 10175, -1, 10179, 10158, 10174, -1, 10181, 10165, 10159, -1, 10181, 10159, 10177, -1, 10182, 10174, 10170, -1, 10182, 10170, 10178, -1, 10183, 10166, 10162, -1, 10184, 10173, 10180, -1, 10184, 10177, 10173, -1, 10183, 10162, 10179, -1, 10185, 10169, 10165, -1, 10185, 4739, 10169, -1, 10185, 10165, 10181, -1, 10186, 10179, 10174, -1, 10187, 10181, 10177, -1, 10187, 10177, 10184, -1, 10186, 10174, 10182, -1, 10188, 10172, 10166, -1, 10189, 7522, 7520, -1, 10189, 10171, 7522, -1, 10188, 10166, 10183, -1, 10190, 10183, 10179, -1, 10191, 10181, 10187, -1, 10191, 4739, 10185, -1, 10190, 10179, 10186, -1, 10191, 10185, 10181, -1, 10191, 4741, 4739, -1, 10192, 10176, 10172, -1, 10192, 4724, 10176, -1, 10193, 10175, 10171, -1, 10192, 4726, 4724, -1, 10193, 10171, 10189, -1, 10192, 10172, 10188, -1, 10194, 10178, 7484, -1, 10195, 10180, 10175, -1, 10196, 10183, 10190, -1, 10195, 10175, 10193, -1, 10196, 10188, 10183, -1, 10197, 10178, 10194, -1, 9878, 10184, 10180, -1, 10197, 10182, 10178, -1, 9878, 10180, 10195, -1, 9883, 10187, 10184, -1, 9883, 10184, 9878, -1, 10198, 4726, 10192, -1, 10198, 10192, 10188, -1, 10198, 10188, 10196, -1, 9884, 10191, 10187, -1, 9884, 4741, 10191, -1, 10199, 10182, 10197, -1, 9884, 10187, 9883, -1, 10199, 10186, 10182, -1, 10200, 7484, 7488, -1, 10200, 10194, 7484, -1, 10201, 10190, 10186, -1, 10201, 10186, 10199, -1, 10202, 10194, 10200, -1, 10202, 10197, 10194, -1, 10203, 10196, 10190, -1, 10203, 10190, 10201, -1, 10204, 10197, 10202, -1, 10204, 10199, 10197, -1, 10205, 10196, 10203, -1, 10205, 4728, 4726, -1, 10205, 4726, 10198, -1, 10205, 10198, 10196, -1, 10206, 10199, 10204, -1, 10206, 10201, 10199, -1, 10207, 10200, 7488, -1, 10208, 10203, 10201, -1, 10208, 10201, 10206, -1, 10209, 10200, 10207, -1, 10209, 10202, 10200, -1, 10210, 10205, 10203, -1, 10210, 10203, 10208, -1, 10210, 4728, 10205, -1, 10211, 10204, 10202, -1, 10211, 10202, 10209, -1, 10212, 10207, 7488, -1, 10212, 7488, 7490, -1, 10213, 10206, 10204, -1, 10213, 10204, 10211, -1, 10214, 10207, 10212, -1, 10214, 10209, 10207, -1, 10215, 10208, 10206, -1, 10215, 10206, 10213, -1, 10216, 10209, 10214, -1, 10216, 10211, 10209, -1, 10217, 10210, 10208, -1, 10217, 4728, 10210, -1, 10217, 10208, 10215, -1, 10217, 4730, 4728, -1, 10218, 10212, 7490, -1, 10219, 10211, 10216, -1, 10219, 10213, 10211, -1, 10220, 7512, 1172, -1, 10221, 10214, 10212, -1, 10222, 10220, 1172, -1, 10221, 10212, 10218, -1, 10222, 1172, 1180, -1, 10223, 10213, 10219, -1, 10223, 10215, 10213, -1, 9983, 10222, 1180, -1, 9983, 1180, 1192, -1, 10224, 10216, 10214, -1, 10224, 10214, 10221, -1, 9990, 9983, 1192, -1, 10225, 10215, 10223, -1, 10225, 10217, 10215, -1, 10225, 4730, 10217, -1, 9990, 1192, 1198, -1, 10226, 7490, 7485, -1, 10226, 10218, 7490, -1, 9991, 9990, 1198, -1, 10227, 10216, 10224, -1, 9991, 1198, 1203, -1, 10227, 10219, 10216, -1, 9993, 1208, 4749, -1, 10228, 10218, 10226, -1, 9993, 9991, 1203, -1, 10228, 10221, 10218, -1, 9993, 1203, 1205, -1, 9993, 1205, 1208, -1, 10229, 10096, 4714, -1, 10229, 10069, 10092, -1, 10229, 10074, 10069, -1, 10229, 4714, 10074, -1, 10229, 10092, 10096, -1, 10230, 10223, 10219, -1, 10231, 10112, 4716, -1, 10231, 10110, 10112, -1, 10231, 10096, 10092, -1, 10231, 4716, 10096, -1, 10230, 10219, 10227, -1, 10231, 10092, 10110, -1, 10232, 4718, 10112, -1, 10232, 10124, 4718, -1, 10233, 10224, 10221, -1, 10233, 10221, 10228, -1, 10234, 10144, 4720, -1, 10235, 10225, 10223, -1, 10234, 4720, 10123, -1, 10235, 4732, 4730, -1, 10235, 4730, 10225, -1, 10235, 10223, 10230, -1, 10236, 10237, 7564, -1, 10236, 10238, 10237, -1, 10239, 10226, 7485, -1, 10240, 10227, 10224, -1, 10240, 10224, 10233, -1, 10241, 10236, 7564, -1, 10242, 7564, 7562, -1, 10243, 10226, 10239, -1, 10242, 10241, 7564, -1, 10243, 10228, 10226, -1, 10242, 7562, 10244, -1, 10245, 10244, 7562, -1, 10246, 10227, 10240, -1, 10246, 10230, 10227, -1, 10245, 10247, 10244, -1, 10248, 10228, 10243, -1, 10248, 10233, 10228, -1, 10249, 10245, 7562, -1, 10250, 10230, 10246, -1, 10251, 7562, 7560, -1, 10250, 4732, 10235, -1, 10250, 10235, 10230, -1, 10251, 10249, 7562, -1, 10251, 7560, 10252, -1, 10253, 7485, 7483, -1, 10254, 10255, 10252, -1, 10253, 10239, 7485, -1, 10254, 10252, 7560, -1, 10256, 10233, 10248, -1, 10256, 10240, 10233, -1, 10257, 10254, 7560, -1, 10258, 10239, 10253, -1, 10259, 7558, 10260, -1, 10259, 7560, 7558, -1, 10258, 10243, 10239, -1, 10259, 10257, 7560, -1, 10261, 10260, 7558, -1, 10262, 10240, 10256, -1, 10261, 10263, 10260, -1, 10262, 10246, 10240, -1, 10264, 10248, 10243, -1, 10264, 10243, 10258, -1, 10265, 4732, 10250, -1, 9805, 10261, 7558, -1, 9809, 9805, 7558, -1, 10265, 10246, 10262, -1, 9809, 7558, 7556, -1, 10265, 4734, 4732, -1, 10265, 10250, 10246, -1, 9809, 7556, 10266, -1, 10267, 10253, 7483, -1, 10268, 10269, 10270, -1, 10268, 4713, 10269, -1, 10268, 10270, 10271, -1, 10268, 10272, 4713, -1, 10268, 10271, 10272, -1, 10273, 10248, 10264, -1, 10274, 4715, 10272, -1, 10273, 10256, 10248, -1, 10274, 9815, 4715, -1, 10275, 10258, 10253, -1, 10274, 10276, 9815, -1, 10277, 4717, 9815, -1, 10277, 9834, 4717, -1, 10275, 10253, 10267, -1, 10278, 10262, 10256, -1, 10278, 10256, 10273, -1, 9867, 4719, 9833, -1, 9871, 9870, 4721, -1, 10279, 10264, 10258, -1, 10279, 10258, 10275, -1, 9871, 4721, 4719, -1, 10280, 10265, 10262, -1, 10281, 10189, 7520, -1, 10280, 4734, 10265, -1, 10280, 10262, 10278, -1, 10282, 10273, 10264, -1, 10281, 10193, 10189, -1, 10282, 10264, 10279, -1, 10283, 7483, 7481, -1, 10284, 10281, 7520, -1, 10285, 7520, 7518, -1, 10285, 7518, 10286, -1, 10283, 10267, 7483, -1, 10287, 10278, 10273, -1, 10285, 10284, 7520, -1, 10288, 10286, 7518, -1, 10287, 10273, 10282, -1, 10288, 10289, 10286, -1, 10290, 10275, 10267, -1, 10290, 10267, 10283, -1, 10291, 10288, 7518, -1, 10292, 10280, 10278, -1, 10292, 4734, 10280, -1, 10292, 10278, 10287, -1, 10293, 7518, 7516, -1, 10292, 4736, 4734, -1, 10293, 10291, 7518, -1, 10294, 10279, 10275, -1, 10293, 7516, 10295, -1, 10294, 10275, 10290, -1, 10296, 10295, 7516, -1, 10296, 10297, 10295, -1, 10298, 10283, 7481, -1, 10299, 10296, 7516, -1, 10300, 10282, 10279, -1, 10300, 10279, 10294, -1, 10301, 7516, 7514, -1, 10302, 10283, 10298, -1, 10301, 10299, 7516, -1, 10302, 10290, 10283, -1, 10301, 7514, 10303, -1, 10304, 10303, 7514, -1, 10305, 10287, 10282, -1, 10304, 10306, 10303, -1, 10305, 10282, 10300, -1, 10307, 10294, 10290, -1, 9961, 10304, 7514, -1, 10307, 10290, 10302, -1, 9962, 7514, 7512, -1, 9962, 9961, 7514, -1, 10308, 10292, 10287, -1, 10308, 4736, 10292, -1, 10308, 10287, 10305, -1, 9962, 7512, 10220, -1, 10309, 10112, 10110, -1, 10309, 10124, 10232, -1, 10309, 10232, 10112, -1, 10310, 10300, 10294, -1, 10309, 10120, 10124, -1, 10309, 10110, 10108, -1, 10309, 10108, 10120, -1, 10310, 10294, 10307, -1, 10311, 10136, 10144, -1, 10311, 10144, 10234, -1, 10311, 10120, 10136, -1, 10312, 7481, 7478, -1, 10311, 10123, 10124, -1, 10312, 10298, 7481, -1, 10311, 10234, 10123, -1, 10311, 10124, 10120, -1, 10313, 10314, 10238, -1, 10313, 10315, 10314, -1, 10316, 10305, 10300, -1, 10316, 10300, 10310, -1, 10317, 10313, 10238, -1, 10317, 10236, 10241, -1, 10318, 10302, 10298, -1, 10317, 10238, 10236, -1, 10318, 10298, 10312, -1, 10319, 4736, 10308, -1, 10319, 4738, 4736, -1, 10319, 10308, 10305, -1, 10319, 10305, 10316, -1, 10001, 10317, 10241, -1, 10320, 10312, 7478, -1, 10321, 10242, 10244, -1, 10322, 10307, 10302, -1, 10321, 10244, 10247, -1, 10322, 10302, 10318, -1, 10323, 10001, 10241, -1, 10323, 10242, 10321, -1, 10323, 10241, 10242, -1, 10324, 10312, 10320, -1, 10325, 10321, 10247, -1, 10324, 10318, 10312, -1, 10325, 10323, 10321, -1, 10325, 10247, 10326, -1, 10325, 10326, 10327, -1, 10328, 10326, 10247, -1, 10329, 10310, 10307, -1, 10328, 10327, 10326, -1, 10329, 10307, 10322, -1, 10330, 10322, 10318, -1, 10331, 10328, 10247, -1, 10331, 10247, 10245, -1, 10330, 10318, 10324, -1, 10332, 10310, 10329, -1, 10331, 10245, 10249, -1, 10332, 10316, 10310, -1, 10013, 10331, 10249, -1, 10333, 10329, 10322, -1, 10333, 10322, 10330, -1, 10334, 10316, 10332, -1, 10335, 10252, 10255, -1, 10334, 4738, 10319, -1, 10334, 10319, 10316, -1, 10335, 10251, 10252, -1, 10336, 7478, 7477, -1, 10337, 10249, 10251, -1, 10337, 10251, 10335, -1, 10337, 10013, 10249, -1, 10336, 10320, 7478, -1, 10338, 10332, 10329, -1, 10339, 10255, 10340, -1, 10339, 10335, 10255, -1, 10339, 10337, 10335, -1, 10338, 10329, 10333, -1, 10341, 10340, 10255, -1, 10341, 10342, 10340, -1, 10343, 10320, 10336, -1, 10343, 10324, 10320, -1, 10344, 10341, 10255, -1, 10345, 10334, 10332, -1, 10345, 10332, 10338, -1, 10345, 4738, 10334, -1, 10344, 10255, 10254, -1, 10345, 4740, 4738, -1, 10344, 10254, 10257, -1, 10346, 10336, 7477, -1, 10347, 10330, 10324, -1, 10347, 10324, 10343, -1, 10032, 10344, 10257, -1, 10348, 10343, 10336, -1, 10349, 10259, 10260, -1, 10348, 10336, 10346, -1, 10349, 10260, 10263, -1, 10350, 10333, 10330, -1, 10351, 10257, 10259, -1, 10351, 10259, 10349, -1, 10351, 10032, 10257, -1, 10350, 10330, 10347, -1, 10352, 10263, 10353, -1, 10354, 10347, 10343, -1, 10354, 10343, 10348, -1, 10352, 10349, 10263, -1, 10352, 10351, 10349, -1, 9814, 10353, 10263, -1, 10355, 10338, 10333, -1, 9814, 9813, 10353, -1, 10355, 10333, 10350, -1, 9804, 10263, 10261, -1, 9804, 9814, 10263, -1, 10356, 10347, 10354, -1, 10356, 10350, 10347, -1, 10357, 10345, 10338, -1, 9804, 10261, 9805, -1, 10357, 4740, 10345, -1, 10357, 10338, 10355, -1, 10237, 10346, 7477, -1, 10237, 7477, 7564, -1, 10358, 10355, 10350, -1, 10358, 10350, 10356, -1, 9818, 10266, 10359, -1, 9818, 9809, 10266, -1, 10238, 10348, 10346, -1, 10238, 10346, 10237, -1, 9829, 9818, 10359, -1, 9829, 9819, 9818, -1, 10360, 10355, 10358, -1, 9829, 10359, 9832, -1, 10360, 4740, 10357, -1, 10360, 10357, 10355, -1, 10360, 4742, 4740, -1, 10361, 10271, 9807, -1, 10361, 10272, 10271, -1, 10314, 10354, 10348, -1, 10361, 10274, 10272, -1, 10361, 9807, 9806, -1, 10361, 9806, 10276, -1, 10314, 10348, 10238, -1, 10361, 10276, 10274, -1, 10362, 10276, 9806, -1, 10362, 10277, 9815, -1, 10362, 9815, 10276, -1, 10362, 9806, 9830, -1, 10362, 9830, 9834, -1, 10315, 10356, 10354, -1, 10362, 9834, 10277, -1, 10315, 10354, 10314, -1, 10363, 9834, 9830, -1, 10363, 9833, 9834, -1, 10364, 10358, 10356, -1, 10363, 9867, 9833, -1, 10364, 10356, 10315, -1, 9852, 10363, 9830, -1, 10007, 10360, 10358, -1, 10007, 4742, 10360, -1, 10007, 10358, 10364, -1, 9868, 10363, 9852, -1, 9868, 9852, 9851, -1, 9868, 9867, 10363, -1, 9862, 9856, 9860, -1, 9873, 9860, 9870, -1, 9873, 9862, 9860, -1, 9873, 9863, 9862, -1, 9873, 9870, 9871, -1, 9876, 10195, 10193, -1, 9876, 9878, 10195, -1, 9877, 10193, 10281, -1, 9877, 10281, 10284, -1, 9877, 9876, 10193, -1, 9879, 9877, 10284, -1, 10365, 10285, 10286, -1, 10365, 10286, 10289, -1, 9890, 9879, 10284, -1, 9890, 10285, 10365, -1, 9890, 10284, 10285, -1, 9891, 10365, 10289, -1, 9891, 9890, 10365, -1, 9891, 10289, 10366, -1, 9891, 10366, 9893, -1, 9903, 10366, 10289, -1, 9903, 9893, 10366, -1, 9901, 10288, 10291, -1, 9901, 10289, 10288, -1, 9901, 9903, 10289, -1, 9902, 9901, 10291, -1, 10367, 10293, 10295, -1, 10367, 10295, 10297, -1, 9911, 10293, 10367, -1, 9911, 10291, 10293, -1, 9911, 9902, 10291, -1, 9912, 9911, 10367, -1, 9912, 10367, 10297, -1, 9912, 10297, 9917, -1, 9932, 9917, 10297, -1, 9932, 9922, 9917, -1, 9929, 10296, 10299, -1, 9929, 9932, 10297, -1, 9929, 10297, 10296, -1, 9930, 9929, 10299, -1, 10368, 10301, 10303, -1, 10368, 10303, 10306, -1, 9939, 9930, 10299, -1, 9939, 10299, 10301, -1, 9939, 10301, 10368, -1, 9940, 10368, 10306, -1, 10369, 7556, 7555, -1, 9940, 9939, 10368, -1, 10369, 10266, 7556, -1, 9940, 10306, 9945, -1, 9967, 9951, 9945, -1, 9967, 9945, 10306, -1, 10370, 10359, 10266, -1, 9959, 9967, 10306, -1, 10370, 10266, 10369, -1, 10371, 9832, 10359, -1, 9959, 10306, 10304, -1, 10371, 10359, 10370, -1, 9959, 10304, 9961, -1, 10372, 9832, 10371, -1, 10372, 9840, 9832, -1, 10373, 9841, 9840, -1, 9970, 10220, 10222, -1, 10373, 9840, 10372, -1, 10374, 9844, 9841, -1, 9970, 9962, 10220, -1, 10374, 4709, 9844, -1, 10374, 9841, 10373, -1, 10374, 4708, 4709, -1, 9978, 9970, 10222, -1, 10375, 7555, 7553, -1, 9978, 9971, 9970, -1, 10375, 10369, 7555, -1, 9978, 10222, 9983, -1, 9998, 10317, 10001, -1, 10376, 10370, 10369, -1, 9998, 10313, 10317, -1, 9998, 10315, 10313, -1, 10376, 10369, 10375, -1, 10006, 10315, 9998, -1, 10006, 10364, 10315, -1, 10377, 10371, 10370, -1, 10006, 10007, 10364, -1, 9997, 10006, 9998, -1, 10377, 10370, 10376, -1, 10378, 10372, 10371, -1, 10378, 10371, 10377, -1, 10379, 10372, 10378, -1, 10379, 10373, 10372, -1, 10380, 10373, 10379, -1, 10380, 10374, 10373, -1, 10380, 4708, 10374, -1, 10380, 4710, 4708, -1, 10002, 10323, 10325, -1, 10002, 10325, 10327, -1, 10381, 10375, 7553, -1, 10002, 10001, 10323, -1, 10381, 7553, 7551, -1, 10010, 10002, 10327, -1, 10382, 10376, 10375, -1, 10010, 10003, 10002, -1, 10382, 10375, 10381, -1, 10010, 10327, 10383, -1, 10010, 10383, 10011, -1, 10020, 10328, 10331, -1, 10020, 10331, 10013, -1, 10020, 10327, 10328, -1, 10384, 10377, 10376, -1, 10022, 10327, 10020, -1, 10384, 10376, 10382, -1, 10022, 10383, 10327, -1, 10385, 10378, 10377, -1, 10022, 10011, 10383, -1, 10017, 10022, 10020, -1, 10385, 10377, 10384, -1, 10386, 10379, 10378, -1, 10386, 10378, 10385, -1, 10387, 4711, 4710, -1, 10014, 10013, 10337, -1, 10387, 10380, 10379, -1, 10387, 4710, 10380, -1, 10014, 10337, 10339, -1, 10387, 10379, 10386, -1, 10388, 10381, 7551, -1, 10388, 7551, 7549, -1, 10389, 10382, 10381, -1, 10389, 10381, 10388, -1, 10390, 10014, 10339, -1, 10390, 10018, 10014, -1, 10391, 10382, 10389, -1, 10390, 10339, 10340, -1, 10391, 10384, 10382, -1, 10392, 10340, 10342, -1, 10392, 10342, 10393, -1, 10394, 10384, 10391, -1, 10392, 10390, 10340, -1, 10029, 10393, 10027, -1, 10029, 10018, 10390, -1, 10394, 10385, 10384, -1, 10029, 10019, 10018, -1, 10270, 10386, 10385, -1, 10029, 10392, 10393, -1, 10029, 10390, 10392, -1, 10270, 10385, 10394, -1, 10031, 10342, 10341, -1, 10031, 10341, 10344, -1, 10269, 10387, 10386, -1, 10269, 10386, 10270, -1, 10031, 10344, 10032, -1, 10269, 4713, 4711, -1, 10269, 4711, 10387, -1, 10041, 10342, 10031, -1, 10041, 10393, 10342, -1, 10041, 10027, 10393, -1, 10395, 10388, 7549, -1, 10395, 7549, 7547, -1, 10396, 10389, 10388, -1, 10034, 10041, 10031, -1, 10396, 10388, 10395, -1, 9808, 10391, 10389, -1, 10035, 10032, 10351, -1, 10035, 10351, 10352, -1, 9808, 10389, 10396, -1, 9807, 10394, 10391, -1, 9807, 10391, 9808, -1, 10271, 10270, 10394, -1, 10397, 10035, 10352, -1, 10397, 10352, 10353, -1, 10271, 10394, 9807, -1, 10272, 4715, 4713, -1, 10398, 10035, 10397, -1, 9820, 7547, 7545, -1, 10398, 10037, 10035, -1, 9820, 10395, 7547, -1, 9825, 10396, 10395, -1, 10399, 9813, 9822, -1, 10399, 10353, 9813, -1, 10399, 10397, 10353, -1, 10399, 10398, 10397, -1, 9825, 10395, 9820, -1, 10045, 9822, 9823, -1, 10045, 10399, 9822, -1, 9811, 9808, 10396, -1, 10045, 10037, 10398, -1, 9811, 10396, 9825, -1, 10045, 10038, 10037, -1, 10045, 10398, 10399, -1, 10400, 10401, 10402, -1, 10400, 10403, 10401, -1, 10404, 10405, 10406, -1, 10404, 10406, 848, -1, 10404, 10407, 10408, -1, 10404, 10400, 10405, -1, 10404, 10408, 10400, -1, 10409, 908, 875, -1, 10409, 10410, 908, -1, 10409, 875, 10411, -1, 10409, 10411, 10410, -1, 10412, 848, 877, -1, 10412, 877, 10407, -1, 10412, 10404, 848, -1, 10412, 10407, 10404, -1, 10411, 875, 10413, -1, 10411, 10413, 10414, -1, 10411, 10415, 10410, -1, 10416, 10414, 10417, -1, 10416, 10418, 10415, -1, 10416, 10411, 10414, -1, 10416, 10415, 10411, -1, 10419, 10417, 10420, -1, 10419, 10420, 10421, -1, 10419, 10422, 10418, -1, 10419, 10423, 10422, -1, 10419, 10416, 10417, -1, 10419, 10418, 10416, -1, 10424, 10421, 10425, -1, 10424, 10426, 10423, -1, 10424, 10419, 10421, -1, 10424, 10423, 10419, -1, 10427, 10425, 10428, -1, 10427, 10429, 10426, -1, 10427, 10430, 10429, -1, 10427, 10424, 10425, -1, 10427, 10426, 10424, -1, 10431, 10428, 10432, -1, 10431, 10433, 10430, -1, 10431, 10427, 10428, -1, 10431, 10430, 10427, -1, 10401, 10432, 10434, -1, 10401, 10434, 10402, -1, 10401, 10403, 10433, -1, 10401, 10433, 10431, -1, 10401, 10431, 10432, -1, 10400, 10402, 10405, -1, 10400, 10435, 10403, -1, 10400, 10408, 10435, -1, 10436, 909, 908, -1, 10436, 908, 10410, -1, 10437, 10410, 10415, -1, 10437, 10436, 10410, -1, 10438, 10415, 10418, -1, 10438, 10437, 10415, -1, 6760, 10418, 10422, -1, 6760, 10438, 10418, -1, 6763, 6760, 10422, -1, 6310, 10422, 10423, -1, 6310, 6763, 10422, -1, 6308, 6310, 10423, -1, 6306, 10423, 10426, -1, 6306, 6308, 10423, -1, 6304, 10426, 10429, -1, 6304, 6306, 10426, -1, 6330, 10429, 10430, -1, 6330, 6304, 10429, -1, 6329, 6330, 10430, -1, 6325, 10430, 10433, -1, 6325, 6329, 10430, -1, 6339, 10433, 10403, -1, 6339, 6325, 10433, -1, 6338, 10403, 10435, -1, 6338, 6339, 10403, -1, 5196, 10435, 10408, -1, 5196, 6338, 10435, -1, 5205, 10408, 10407, -1, 5205, 5196, 10408, -1, 5204, 10407, 877, -1, 5204, 5205, 10407, -1, 879, 5204, 877, -1, 6760, 4782, 10438, -1, 4782, 10437, 10438, -1, 4782, 10436, 10437, -1, 4782, 909, 10436, -1, 4782, 907, 909, -1, 4782, 905, 907, -1, 4782, 903, 905, -1, 4782, 901, 903, -1, 874, 872, 10439, -1, 863, 849, 864, -1, 864, 849, 866, -1, 866, 849, 868, -1, 868, 849, 870, -1, 870, 849, 872, -1, 10439, 849, 10440, -1, 10440, 849, 10441, -1, 10441, 849, 10442, -1, 10442, 849, 10443, -1, 10443, 849, 10444, -1, 10444, 849, 10445, -1, 10445, 849, 10446, -1, 10446, 849, 10447, -1, 10447, 849, 10448, -1, 10448, 849, 10449, -1, 10449, 849, 10450, -1, 872, 849, 10439, -1, 863, 860, 849, -1, 860, 858, 849, -1, 849, 852, 850, -1, 858, 856, 849, -1, 849, 854, 852, -1, 856, 854, 849, -1, 10413, 875, 874, -1, 10413, 874, 10439, -1, 10414, 10439, 10440, -1, 10414, 10413, 10439, -1, 10417, 10440, 10441, -1, 10417, 10414, 10440, -1, 10420, 10441, 10442, -1, 10420, 10417, 10441, -1, 10421, 10442, 10443, -1, 10421, 10420, 10442, -1, 10425, 10443, 10444, -1, 10425, 10421, 10443, -1, 10428, 10444, 10445, -1, 10428, 10425, 10444, -1, 10432, 10445, 10446, -1, 10432, 10428, 10445, -1, 10434, 10446, 10447, -1, 10434, 10432, 10446, -1, 10402, 10447, 10448, -1, 10402, 10434, 10447, -1, 10405, 10448, 10449, -1, 10405, 10402, 10448, -1, 10406, 10449, 10450, -1, 10406, 10405, 10449, -1, 848, 10450, 849, -1, 848, 10406, 10450, -1, 6063, 6249, 6254, -1, 6063, 6058, 6249, -1, 5978, 6165, 6168, -1, 5978, 5975, 6165, -1, 6068, 6254, 6259, -1, 6068, 6063, 6254, -1, 5981, 6168, 6171, -1, 5981, 5978, 6168, -1, 797, 798, 6118, -1, 6073, 6259, 6264, -1, 5984, 6171, 767, -1, 6073, 6068, 6259, -1, 5984, 5981, 6171, -1, 5987, 797, 6118, -1, 5987, 6118, 6176, -1, 769, 5984, 767, -1, 6078, 6264, 6269, -1, 6078, 6073, 6264, -1, 5990, 6176, 6179, -1, 5990, 5987, 6176, -1, 6083, 6269, 6274, -1, 6083, 6078, 6269, -1, 5993, 6179, 6182, -1, 5993, 5990, 6179, -1, 6088, 6274, 6279, -1, 6088, 6083, 6274, -1, 5996, 6182, 6185, -1, 5996, 5993, 6182, -1, 6093, 6088, 6279, -1, 6093, 6279, 6284, -1, 5999, 6185, 6188, -1, 5999, 5996, 6185, -1, 6098, 6093, 6284, -1, 6098, 6284, 6109, -1, 6002, 6188, 6191, -1, 6002, 5999, 6188, -1, 6103, 6098, 6109, -1, 6103, 6109, 6108, -1, 6005, 6191, 6194, -1, 6005, 6002, 6191, -1, 5925, 6103, 6108, -1, 5925, 6108, 6116, -1, 6008, 6194, 6197, -1, 6008, 6005, 6194, -1, 5929, 5925, 6116, -1, 5929, 6116, 6122, -1, 6011, 6197, 6200, -1, 6011, 6008, 6197, -1, 5934, 5929, 6122, -1, 5934, 6122, 6127, -1, 6014, 6200, 6203, -1, 6014, 6011, 6200, -1, 5939, 5934, 6127, -1, 5939, 6127, 6132, -1, 6017, 6203, 6207, -1, 6017, 6014, 6203, -1, 5944, 5939, 6132, -1, 5944, 6132, 6137, -1, 6020, 6207, 6209, -1, 6020, 6017, 6207, -1, 5949, 6137, 6141, -1, 5949, 5944, 6137, -1, 6022, 6209, 6214, -1, 6022, 6020, 6209, -1, 5954, 6141, 6144, -1, 5954, 5949, 6141, -1, 6027, 6214, 6219, -1, 6027, 6022, 6214, -1, 5957, 6144, 6147, -1, 5957, 5954, 6144, -1, 6032, 6219, 6224, -1, 6032, 6027, 6219, -1, 5960, 6147, 6150, -1, 5960, 5957, 6147, -1, 6037, 6224, 6229, -1, 6037, 6032, 6224, -1, 5963, 6150, 6153, -1, 5963, 5960, 6150, -1, 6042, 6229, 6234, -1, 6042, 6037, 6229, -1, 5966, 6153, 6156, -1, 5966, 5963, 6153, -1, 6048, 6234, 6239, -1, 6048, 6042, 6234, -1, 5969, 6156, 6159, -1, 5969, 5966, 6156, -1, 6053, 6239, 6244, -1, 6053, 6048, 6239, -1, 5972, 6159, 6162, -1, 5972, 5969, 6159, -1, 6058, 6244, 6249, -1, 6058, 6053, 6244, -1, 5975, 6162, 6165, -1, 5975, 5972, 6162, -1, 10451, 10452, 10453, -1, 10454, 10455, 10452, -1, 10456, 10457, 10458, -1, 10459, 10455, 10454, -1, 10460, 10461, 10462, -1, 10459, 10463, 10455, -1, 10462, 10461, 10457, -1, 7457, 10463, 7455, -1, 7456, 10464, 7454, -1, 7455, 10463, 10465, -1, 7454, 10464, 10466, -1, 10465, 10463, 10459, -1, 10466, 10464, 10460, -1, 10460, 10464, 10461, -1, 7486, 10467, 7487, -1, 10468, 10467, 7486, -1, 10469, 10470, 7529, -1, 7529, 10470, 7531, -1, 10469, 10471, 10470, -1, 10468, 10472, 10467, -1, 10473, 10472, 10468, -1, 10474, 10471, 10469, -1, 10473, 10475, 10472, -1, 10453, 10475, 10473, -1, 10474, 10476, 10471, -1, 10458, 10476, 10474, -1, 10453, 10477, 10475, -1, 10458, 10478, 10476, -1, 10457, 10478, 10458, -1, 10452, 10477, 10453, -1, 10452, 10479, 10477, -1, 10457, 10480, 10478, -1, 10455, 10479, 10452, -1, 7457, 10481, 10463, -1, 10461, 10480, 10457, -1, 10455, 10481, 10479, -1, 579, 7437, 580, -1, 10461, 10482, 10480, -1, 7459, 10481, 7457, -1, 10463, 10481, 10455, -1, 7458, 10482, 7456, -1, 7456, 10482, 10464, -1, 10464, 10482, 10461, -1, 7487, 10483, 7489, -1, 10467, 10483, 7487, -1, 7531, 10484, 7533, -1, 10472, 10485, 10467, -1, 10467, 10485, 10483, -1, 10470, 10484, 7531, -1, 10470, 10486, 10484, -1, 10475, 10487, 10472, -1, 10471, 10486, 10470, -1, 10471, 10488, 10486, -1, 10472, 10487, 10485, -1, 10477, 10489, 10475, -1, 10476, 10488, 10471, -1, 10478, 10490, 10476, -1, 10475, 10489, 10487, -1, 10479, 10491, 10477, -1, 10476, 10490, 10488, -1, 10477, 10491, 10489, -1, 10480, 10492, 10478, -1, 10479, 10493, 10491, -1, 7459, 10493, 10481, -1, 10478, 10492, 10490, -1, 10482, 10494, 10480, -1, 7461, 10493, 7459, -1, 7458, 10494, 10482, -1, 10481, 10493, 10479, -1, 7460, 10494, 7458, -1, 10483, 10495, 7489, -1, 10480, 10494, 10492, -1, 10484, 10496, 7533, -1, 7489, 10495, 7492, -1, 7533, 10496, 7535, -1, 10483, 10497, 10495, -1, 10486, 10498, 10484, -1, 10484, 10498, 10496, -1, 10485, 10497, 10483, -1, 10487, 10499, 10485, -1, 10488, 10500, 10486, -1, 10485, 10499, 10497, -1, 10489, 10501, 10487, -1, 10486, 10500, 10498, -1, 10488, 10502, 10500, -1, 10490, 10502, 10488, -1, 10487, 10501, 10499, -1, 10491, 10503, 10489, -1, 10490, 10504, 10502, -1, 10489, 10503, 10501, -1, 10492, 10504, 10490, -1, 7463, 10505, 7461, -1, 10493, 10505, 10491, -1, 7462, 10506, 7460, -1, 7461, 10505, 10493, -1, 7460, 10506, 10494, -1, 10491, 10505, 10503, -1, 10494, 10506, 10492, -1, 10492, 10506, 10504, -1, 10495, 10507, 7492, -1, 10496, 10508, 7535, -1, 7492, 10507, 7494, -1, 10497, 10509, 10495, -1, 7535, 10508, 7537, -1, 10498, 10510, 10496, -1, 10495, 10509, 10507, -1, 10496, 10510, 10508, -1, 10499, 10511, 10497, -1, 10498, 10512, 10510, -1, 10497, 10511, 10509, -1, 10500, 10512, 10498, -1, 10499, 10513, 10511, -1, 10501, 10513, 10499, -1, 10502, 10514, 10500, -1, 10500, 10514, 10512, -1, 10503, 10515, 10501, -1, 10502, 10516, 10514, -1, 10501, 10515, 10513, -1, 10504, 10516, 10502, -1, 7465, 10517, 7463, -1, 7463, 10517, 10505, -1, 10505, 10517, 10503, -1, 7464, 10518, 7462, -1, 7462, 10518, 10506, -1, 10503, 10517, 10515, -1, 10506, 10518, 10504, -1, 10504, 10518, 10516, -1, 10507, 10519, 7494, -1, 10508, 10520, 7537, -1, 7494, 10519, 7496, -1, 7537, 10520, 7539, -1, 10509, 10521, 10507, -1, 10510, 10522, 10508, -1, 10508, 10522, 10520, -1, 10507, 10521, 10519, -1, 10511, 10523, 10509, -1, 10510, 10524, 10522, -1, 10509, 10523, 10521, -1, 10512, 10524, 10510, -1, 10513, 10525, 10511, -1, 10511, 10525, 10523, -1, 10514, 10526, 10512, -1, 10512, 10526, 10524, -1, 10515, 10527, 10513, -1, 10516, 10528, 10514, -1, 10513, 10527, 10525, -1, 10514, 10528, 10526, -1, 7467, 10529, 7465, -1, 7465, 10529, 10517, -1, 10517, 10529, 10515, -1, 7466, 10530, 7464, -1, 7464, 10530, 10518, -1, 10515, 10529, 10527, -1, 10518, 10530, 10516, -1, 10516, 10530, 10528, -1, 7496, 10531, 7498, -1, 10520, 10532, 7539, -1, 10519, 10531, 7496, -1, 7539, 10532, 7541, -1, 10521, 10533, 10519, -1, 10522, 10534, 10520, -1, 10520, 10534, 10532, -1, 10519, 10533, 10531, -1, 10521, 10535, 10533, -1, 10522, 10536, 10534, -1, 10523, 10535, 10521, -1, 10524, 10536, 10522, -1, 10525, 10537, 10523, -1, 10526, 10538, 10524, -1, 10523, 10537, 10535, -1, 10524, 10538, 10536, -1, 10527, 10539, 10525, -1, 10525, 10539, 10537, -1, 10528, 10540, 10526, -1, 10526, 10540, 10538, -1, 7469, 10541, 7467, -1, 7467, 10541, 10529, -1, 7468, 10542, 7466, -1, 10527, 10541, 10539, -1, 7466, 10542, 10530, -1, 10529, 10541, 10527, -1, 10530, 10542, 10528, -1, 10528, 10542, 10540, -1, 7498, 10543, 7500, -1, 10531, 10543, 7498, -1, 10532, 10544, 7541, -1, 7541, 10544, 7543, -1, 10531, 10545, 10543, -1, 10534, 10546, 10532, -1, 10533, 10545, 10531, -1, 10532, 10546, 10544, -1, 10533, 10547, 10545, -1, 10534, 10548, 10546, -1, 10536, 10548, 10534, -1, 10535, 10547, 10533, -1, 10537, 10549, 10535, -1, 10536, 10550, 10548, -1, 10535, 10549, 10547, -1, 10538, 10550, 10536, -1, 10539, 10551, 10537, -1, 10537, 10551, 10549, -1, 10538, 10552, 10550, -1, 10539, 10553, 10551, -1, 10541, 10553, 10539, -1, 10540, 10552, 10538, -1, 10542, 10554, 10540, -1, 7471, 10553, 7469, -1, 7470, 10554, 7468, -1, 7469, 10553, 10541, -1, 10540, 10554, 10552, -1, 10543, 10555, 7500, -1, 7468, 10554, 10542, -1, 10544, 10556, 7543, -1, 7500, 10555, 7502, -1, 7543, 10556, 7546, -1, 10545, 10557, 10543, -1, 10543, 10557, 10555, -1, 10546, 10558, 10544, -1, 10544, 10558, 10556, -1, 10545, 10559, 10557, -1, 10547, 10559, 10545, -1, 10546, 10560, 10558, -1, 10548, 10560, 10546, -1, 10549, 10561, 10547, -1, 10550, 10562, 10548, -1, 10547, 10561, 10559, -1, 10548, 10562, 10560, -1, 10551, 10563, 10549, -1, 10549, 10563, 10561, -1, 10550, 10564, 10562, -1, 10552, 10564, 10550, -1, 10553, 10565, 10551, -1, 7471, 10565, 10553, -1, 7473, 10565, 7471, -1, 7472, 10566, 7470, -1, 10551, 10565, 10563, -1, 7470, 10566, 10554, -1, 10554, 10566, 10552, -1, 10552, 10566, 10564, -1, 10555, 10567, 7502, -1, 10556, 10568, 7546, -1, 7502, 10567, 7504, -1, 7546, 10568, 7548, -1, 10557, 10569, 10555, -1, 10558, 10570, 10556, -1, 10556, 10570, 10568, -1, 10555, 10569, 10567, -1, 10557, 10571, 10569, -1, 10559, 10571, 10557, -1, 10558, 10572, 10570, -1, 10560, 10572, 10558, -1, 10561, 10573, 10559, -1, 10562, 10574, 10560, -1, 10559, 10573, 10571, -1, 10560, 10574, 10572, -1, 10563, 10575, 10561, -1, 10564, 10576, 10562, -1, 10561, 10575, 10573, -1, 10562, 10576, 10574, -1, 7475, 10577, 7473, -1, 10563, 10577, 10575, -1, 7473, 10577, 10565, -1, 7474, 10578, 7472, -1, 10565, 10577, 10563, -1, 7472, 10578, 10566, -1, 10566, 10578, 10564, -1, 10564, 10578, 10576, -1, 10567, 10579, 7504, -1, 10568, 10580, 7548, -1, 7504, 10579, 7506, -1, 10567, 10581, 10579, -1, 7548, 10580, 7550, -1, 10569, 10581, 10567, -1, 10570, 10582, 10568, -1, 10568, 10582, 10580, -1, 10571, 10583, 10569, -1, 10572, 10584, 10570, -1, 10570, 10584, 10582, -1, 10569, 10583, 10581, -1, 10571, 10585, 10583, -1, 10573, 10585, 10571, -1, 10572, 10586, 10584, -1, 10574, 10586, 10572, -1, 10575, 10587, 10573, -1, 10576, 10588, 10574, -1, 10573, 10587, 10585, -1, 7432, 10589, 7475, -1, 10574, 10588, 10586, -1, 7475, 10589, 10577, -1, 10577, 10589, 10575, -1, 7476, 10590, 7474, -1, 7474, 10590, 10578, -1, 10575, 10589, 10587, -1, 10578, 10590, 10576, -1, 10576, 10590, 10588, -1, 10579, 10591, 7506, -1, 10580, 10592, 7550, -1, 7506, 10591, 7508, -1, 10579, 10593, 10591, -1, 7550, 10592, 7552, -1, 10581, 10593, 10579, -1, 10580, 10594, 10592, -1, 10582, 10594, 10580, -1, 7554, 583, 585, -1, 10583, 10595, 10581, -1, 10581, 10595, 10593, -1, 10584, 10596, 10582, -1, 10582, 10596, 10594, -1, 10585, 10597, 10583, -1, 10586, 10598, 10584, -1, 10584, 10598, 10596, -1, 10583, 10597, 10595, -1, 10585, 10599, 10597, -1, 10587, 10599, 10585, -1, 10586, 10600, 10598, -1, 10588, 10600, 10586, -1, 7433, 10601, 7432, -1, 7432, 10601, 10589, -1, 10589, 10601, 10587, -1, 7434, 10602, 7476, -1, 7476, 10602, 10590, -1, 10587, 10601, 10599, -1, 10590, 10602, 10588, -1, 10588, 10602, 10600, -1, 568, 10603, 569, -1, 7508, 10604, 7510, -1, 7554, 10605, 583, -1, 10591, 10604, 7508, -1, 569, 10603, 7509, -1, 10592, 10605, 7552, -1, 10591, 10606, 10604, -1, 594, 10607, 568, -1, 7552, 10605, 7554, -1, 583, 10608, 592, -1, 10593, 10606, 10591, -1, 568, 10607, 10603, -1, 10592, 10608, 10605, -1, 10593, 10609, 10606, -1, 10594, 10608, 10592, -1, 599, 10610, 594, -1, 10605, 10608, 583, -1, 10595, 10609, 10593, -1, 594, 10610, 10607, -1, 599, 10611, 10610, -1, 592, 10612, 596, -1, 10595, 10613, 10609, -1, 10594, 10612, 10608, -1, 606, 10611, 599, -1, 10597, 10613, 10595, -1, 10596, 10612, 10594, -1, 10597, 10614, 10613, -1, 615, 10615, 606, -1, 10608, 10612, 592, -1, 606, 10615, 10611, -1, 596, 10616, 602, -1, 10599, 10614, 10597, -1, 7437, 10617, 580, -1, 10599, 10618, 10614, -1, 580, 10617, 615, -1, 10598, 10616, 10596, -1, 615, 10617, 10615, -1, 7436, 10618, 7433, -1, 7433, 10618, 10601, -1, 10612, 10616, 596, -1, 10596, 10616, 10612, -1, 10601, 10618, 10599, -1, 10604, 10619, 7510, -1, 602, 10620, 607, -1, 7509, 10621, 7507, -1, 10598, 10620, 10616, -1, 10603, 10621, 7509, -1, 10616, 10620, 602, -1, 10600, 10620, 10598, -1, 7510, 10619, 7511, -1, 10620, 10622, 607, -1, 610, 10622, 7435, -1, 10603, 10623, 10621, -1, 7435, 10622, 7434, -1, 607, 10622, 611, -1, 10607, 10623, 10603, -1, 611, 10622, 610, -1, 10604, 10624, 10619, -1, 10600, 10622, 10620, -1, 7434, 10622, 10602, -1, 10602, 10622, 10600, -1, 10606, 10624, 10604, -1, 10610, 10625, 10607, -1, 10607, 10625, 10623, -1, 10609, 10626, 10606, -1, 10606, 10626, 10624, -1, 10611, 10627, 10610, -1, 10613, 10628, 10609, -1, 10610, 10627, 10625, -1, 10609, 10628, 10626, -1, 10614, 10629, 10613, -1, 10615, 10630, 10611, -1, 10611, 10630, 10627, -1, 10613, 10629, 10628, -1, 10615, 10631, 10630, -1, 10617, 10631, 10615, -1, 10618, 10632, 10614, -1, 7436, 10632, 10618, -1, 7439, 10631, 7437, -1, 7437, 10631, 10617, -1, 7438, 10632, 7436, -1, 10621, 10633, 7507, -1, 10614, 10632, 10629, -1, 10619, 10634, 7511, -1, 7507, 10633, 7505, -1, 7511, 10634, 7513, -1, 10624, 10635, 10619, -1, 10623, 10636, 10621, -1, 10619, 10635, 10634, -1, 10621, 10636, 10633, -1, 10623, 10637, 10636, -1, 10626, 10638, 10624, -1, 10625, 10637, 10623, -1, 10624, 10638, 10635, -1, 10627, 10639, 10625, -1, 10625, 10639, 10637, -1, 10628, 10640, 10626, -1, 10627, 10641, 10639, -1, 10626, 10640, 10638, -1, 10630, 10641, 10627, -1, 10628, 10642, 10640, -1, 10629, 10642, 10628, -1, 7441, 10643, 7439, -1, 10631, 10643, 10630, -1, 7440, 10644, 7438, -1, 10630, 10643, 10641, -1, 7438, 10644, 10632, -1, 7439, 10643, 10631, -1, 10632, 10644, 10629, -1, 10633, 10645, 7505, -1, 10629, 10644, 10642, -1, 10634, 10646, 7513, -1, 7505, 10645, 7503, -1, 7513, 10646, 7515, -1, 10636, 10647, 10633, -1, 10634, 10648, 10646, -1, 10633, 10647, 10645, -1, 10637, 10649, 10636, -1, 10635, 10648, 10634, -1, 10636, 10649, 10647, -1, 10638, 10650, 10635, -1, 10639, 10651, 10637, -1, 10637, 10651, 10649, -1, 10635, 10650, 10648, -1, 10640, 10652, 10638, -1, 10639, 10653, 10651, -1, 10638, 10652, 10650, -1, 10641, 10653, 10639, -1, 10640, 10654, 10652, -1, 10642, 10654, 10640, -1, 7441, 10655, 10643, -1, 7443, 10655, 7441, -1, 7442, 10656, 7440, -1, 10641, 10655, 10653, -1, 7440, 10656, 10644, -1, 10643, 10655, 10641, -1, 10644, 10656, 10642, -1, 10645, 10657, 7503, -1, 10642, 10656, 10654, -1, 7503, 10657, 7501, -1, 10646, 10658, 7515, -1, 10645, 10659, 10657, -1, 7515, 10658, 7517, -1, 10648, 10660, 10646, -1, 10646, 10660, 10658, -1, 10647, 10659, 10645, -1, 10647, 10661, 10659, -1, 10648, 10662, 10660, -1, 10649, 10661, 10647, -1, 10650, 10662, 10648, -1, 10651, 10663, 10649, -1, 10652, 10664, 10650, -1, 10649, 10663, 10661, -1, 10651, 10665, 10663, -1, 10650, 10664, 10662, -1, 10653, 10665, 10651, -1, 10654, 10666, 10652, -1, 10655, 10667, 10653, -1, 10652, 10666, 10664, -1, 7443, 10667, 10655, -1, 7444, 10668, 7442, -1, 7445, 10667, 7443, -1, 7442, 10668, 10656, -1, 10653, 10667, 10665, -1, 10656, 10668, 10654, -1, 10654, 10668, 10666, -1, 7501, 10669, 7499, -1, 10658, 10670, 7517, -1, 10657, 10669, 7501, -1, 7517, 10670, 7519, -1, 10659, 10671, 10657, -1, 10657, 10671, 10669, -1, 10658, 10672, 10670, -1, 10660, 10672, 10658, -1, 10661, 10673, 10659, -1, 10659, 10673, 10671, -1, 10662, 10674, 10660, -1, 10660, 10674, 10672, -1, 10661, 10675, 10673, -1, 10662, 10676, 10674, -1, 10664, 10676, 10662, -1, 10663, 10675, 10661, -1, 10663, 10677, 10675, -1, 10666, 10678, 10664, -1, 10665, 10677, 10663, -1, 10665, 10679, 10677, -1, 10667, 10679, 10665, -1, 10664, 10678, 10676, -1, 10666, 10680, 10678, -1, 7447, 10679, 7445, -1, 7445, 10679, 10667, -1, 7446, 10680, 7444, -1, 7444, 10680, 10668, -1, 10668, 10680, 10666, -1, 10669, 10681, 7499, -1, 7519, 10682, 7521, -1, 7499, 10681, 7497, -1, 10670, 10682, 7519, -1, 10671, 10683, 10669, -1, 10669, 10683, 10681, -1, 10670, 10684, 10682, -1, 10672, 10684, 10670, -1, 10673, 10685, 10671, -1, 10671, 10685, 10683, -1, 10672, 10686, 10684, -1, 10673, 10687, 10685, -1, 10674, 10686, 10672, -1, 10675, 10687, 10673, -1, 10674, 10688, 10686, -1, 10675, 10689, 10687, -1, 10676, 10688, 10674, -1, 10678, 10690, 10676, -1, 10677, 10689, 10675, -1, 7447, 10691, 10679, -1, 10676, 10690, 10688, -1, 10677, 10691, 10689, -1, 10680, 10692, 10678, -1, 7446, 10692, 10680, -1, 7449, 10691, 7447, -1, 10678, 10692, 10690, -1, 10679, 10691, 10677, -1, 7448, 10692, 7446, -1, 10682, 10693, 7521, -1, 10681, 10694, 7497, -1, 7497, 10694, 7495, -1, 7521, 10693, 7523, -1, 10683, 10695, 10681, -1, 10681, 10695, 10694, -1, 10684, 10696, 10682, -1, 10682, 10696, 10693, -1, 10683, 10697, 10695, -1, 10686, 10698, 10684, -1, 10685, 10697, 10683, -1, 10684, 10698, 10696, -1, 10687, 10699, 10685, -1, 10685, 10699, 10697, -1, 10688, 10700, 10686, -1, 10686, 10700, 10698, -1, 10688, 10701, 10700, -1, 10687, 10702, 10699, -1, 10690, 10701, 10688, -1, 10689, 10702, 10687, -1, 7449, 10703, 10691, -1, 10691, 10703, 10689, -1, 7451, 10703, 7449, -1, 7450, 10704, 7448, -1, 10689, 10703, 10702, -1, 10692, 10704, 10690, -1, 7448, 10704, 10692, -1, 10694, 10705, 7495, -1, 10690, 10704, 10701, -1, 10693, 10706, 7523, -1, 7495, 10705, 7493, -1, 7523, 10706, 7525, -1, 10694, 10707, 10705, -1, 10693, 10708, 10706, -1, 10696, 10708, 10693, -1, 10695, 10707, 10694, -1, 10695, 10709, 10707, -1, 10697, 10709, 10695, -1, 10698, 10710, 10696, -1, 10696, 10710, 10708, -1, 10700, 10711, 10698, -1, 10697, 10712, 10709, -1, 10698, 10711, 10710, -1, 10699, 10712, 10697, -1, 10702, 10713, 10699, -1, 10699, 10713, 10712, -1, 10701, 10714, 10700, -1, 7453, 10715, 7451, -1, 10700, 10714, 10711, -1, 7451, 10715, 10703, -1, 7452, 10716, 7450, -1, 10703, 10715, 10702, -1, 10702, 10715, 10713, -1, 7450, 10716, 10704, -1, 10704, 10716, 10701, -1, 10701, 10716, 10714, -1, 10705, 10717, 7493, -1, 10706, 10718, 7525, -1, 7493, 10717, 7491, -1, 7525, 10718, 7527, -1, 10707, 10719, 10705, -1, 10705, 10719, 10717, -1, 10708, 10720, 10706, -1, 10706, 10720, 10718, -1, 10709, 10451, 10707, -1, 10707, 10451, 10719, -1, 10710, 10456, 10708, -1, 10708, 10456, 10720, -1, 10712, 10454, 10709, -1, 10711, 10462, 10710, -1, 10709, 10454, 10451, -1, 10710, 10462, 10456, -1, 10713, 10459, 10712, -1, 10711, 10460, 10462, -1, 10712, 10459, 10454, -1, 10714, 10460, 10711, -1, 7455, 10465, 7453, -1, 7453, 10465, 10715, -1, 7454, 10466, 7452, -1, 10715, 10465, 10713, -1, 7452, 10466, 10716, -1, 10713, 10465, 10459, -1, 10716, 10466, 10714, -1, 10714, 10466, 10460, -1, 7491, 10468, 7486, -1, 10717, 10468, 7491, -1, 10718, 10469, 7527, -1, 7527, 10469, 7529, -1, 10719, 10473, 10717, -1, 10720, 10474, 10718, -1, 10717, 10473, 10468, -1, 10718, 10474, 10469, -1, 10451, 10453, 10719, -1, 10719, 10453, 10473, -1, 10720, 10458, 10474, -1, 10456, 10458, 10720, -1, 10454, 10452, 10451, -1, 10462, 10457, 10456, -1, 10721, 10722, 10723, -1, 10724, 10725, 10726, -1, 10727, 10728, 10725, -1, 10729, 10728, 10727, -1, 7414, 10728, 10729, -1, 10730, 10722, 10721, -1, 7416, 10728, 7414, -1, 10730, 10731, 10722, -1, 10732, 10733, 7353, -1, 10734, 10731, 10730, -1, 10735, 10736, 10734, -1, 7353, 10733, 7351, -1, 10734, 10736, 10731, -1, 10732, 10737, 10733, -1, 10738, 10739, 10735, -1, 10735, 10739, 10736, -1, 10740, 10737, 10732, -1, 7415, 10739, 7413, -1, 7413, 10739, 10738, -1, 10741, 10742, 10740, -1, 10740, 10742, 10737, -1, 7313, 10743, 7310, -1, 10744, 10743, 7313, -1, 10726, 10745, 10741, -1, 10723, 10746, 10744, -1, 10741, 10745, 10742, -1, 10726, 10747, 10745, -1, 10744, 10746, 10743, -1, 10725, 10747, 10726, -1, 10722, 10748, 10723, -1, 7418, 10749, 7416, -1, 10728, 10749, 10725, -1, 7416, 10749, 10728, -1, 10723, 10748, 10746, -1, 10725, 10749, 10747, -1, 10731, 10750, 10722, -1, 10733, 10751, 7351, -1, 10722, 10750, 10748, -1, 10731, 10752, 10750, -1, 10736, 10752, 10731, -1, 7351, 10751, 7349, -1, 10737, 10753, 10733, -1, 10733, 10753, 10751, -1, 10736, 10754, 10752, -1, 7415, 10754, 10739, -1, 7417, 10754, 7415, -1, 10739, 10754, 10736, -1, 10743, 10755, 7310, -1, 10737, 10756, 10753, -1, 10742, 10756, 10737, -1, 7310, 10755, 7307, -1, 10742, 10757, 10756, -1, 10746, 10758, 10743, -1, 10745, 10757, 10742, -1, 10743, 10758, 10755, -1, 10747, 10759, 10745, -1, 10748, 10760, 10746, -1, 10745, 10759, 10757, -1, 7420, 10761, 7418, -1, 10746, 10760, 10758, -1, 7418, 10761, 10749, -1, 10747, 10761, 10759, -1, 10749, 10761, 10747, -1, 10750, 10762, 10748, -1, 10751, 10763, 7349, -1, 10748, 10762, 10760, -1, 7349, 10763, 7347, -1, 10750, 10764, 10762, -1, 10753, 10765, 10751, -1, 10752, 10764, 10750, -1, 10751, 10765, 10763, -1, 7419, 10766, 7417, -1, 10754, 10766, 10752, -1, 7417, 10766, 10754, -1, 10752, 10766, 10764, -1, 10753, 10767, 10765, -1, 10755, 10768, 7307, -1, 10756, 10767, 10753, -1, 7307, 10768, 7302, -1, 10757, 10769, 10756, -1, 10758, 10770, 10755, -1, 10756, 10769, 10767, -1, 10755, 10770, 10768, -1, 10759, 10771, 10757, -1, 10757, 10771, 10769, -1, 10760, 10772, 10758, -1, 7422, 10773, 7420, -1, 7420, 10773, 10761, -1, 10761, 10773, 10759, -1, 10758, 10772, 10770, -1, 10759, 10773, 10771, -1, 10760, 10774, 10772, -1, 10763, 10775, 7347, -1, 10762, 10774, 10760, -1, 10764, 10776, 10762, -1, 7347, 10775, 7345, -1, 10765, 10777, 10763, -1, 10762, 10776, 10774, -1, 10763, 10777, 10775, -1, 7421, 10778, 7419, -1, 10764, 10778, 10776, -1, 10766, 10778, 10764, -1, 7419, 10778, 10766, -1, 10765, 10779, 10777, -1, 10768, 10780, 7302, -1, 10767, 10779, 10765, -1, 7302, 10780, 7300, -1, 10769, 10781, 10767, -1, 10770, 10782, 10768, -1, 10767, 10781, 10779, -1, 10768, 10782, 10780, -1, 10771, 10783, 10769, -1, 10770, 10784, 10782, -1, 10769, 10783, 10781, -1, 10772, 10784, 10770, -1, 7424, 10785, 7422, -1, 7422, 10785, 10773, -1, 10773, 10785, 10771, -1, 10771, 10785, 10783, -1, 10774, 10786, 10772, -1, 10775, 10787, 7345, -1, 10772, 10786, 10784, -1, 7345, 10787, 7343, -1, 10774, 10788, 10786, -1, 10776, 10788, 10774, -1, 10777, 10789, 10775, -1, 7423, 10790, 7421, -1, 7421, 10790, 10778, -1, 10775, 10789, 10787, -1, 10778, 10790, 10776, -1, 10776, 10790, 10788, -1, 10779, 10791, 10777, -1, 7300, 10792, 7301, -1, 10777, 10791, 10789, -1, 10780, 10792, 7300, -1, 10782, 10793, 10780, -1, 10779, 10794, 10791, -1, 10781, 10794, 10779, -1, 10780, 10793, 10792, -1, 10781, 10795, 10794, -1, 10784, 10796, 10782, -1, 10782, 10796, 10793, -1, 10783, 10795, 10781, -1, 10785, 10797, 10783, -1, 7426, 10797, 7424, -1, 10783, 10797, 10795, -1, 7424, 10797, 10785, -1, 10784, 10798, 10796, -1, 10786, 10798, 10784, -1, 10787, 10799, 7343, -1, 10786, 10800, 10798, -1, 7343, 10799, 7340, -1, 10788, 10800, 10786, -1, 10788, 10801, 10800, -1, 7425, 10801, 7423, -1, 7423, 10801, 10790, -1, 10789, 10802, 10787, -1, 10790, 10801, 10788, -1, 10787, 10802, 10799, -1, 7301, 10803, 7385, -1, 10789, 10804, 10802, -1, 10791, 10804, 10789, -1, 10792, 10803, 7301, -1, 10794, 10805, 10791, -1, 10792, 10806, 10803, -1, 10791, 10805, 10804, -1, 10793, 10806, 10792, -1, 10794, 10807, 10805, -1, 10795, 10807, 10794, -1, 10793, 10808, 10806, -1, 10796, 10808, 10793, -1, 7428, 10809, 7426, -1, 7426, 10809, 10797, -1, 10797, 10809, 10795, -1, 10798, 10810, 10796, -1, 10795, 10809, 10807, -1, 10796, 10810, 10808, -1, 10799, 10811, 7340, -1, 10800, 10812, 10798, -1, 10798, 10812, 10810, -1, 7340, 10811, 7338, -1, 10801, 10813, 10800, -1, 10802, 10814, 10799, -1, 7425, 10813, 10801, -1, 10800, 10813, 10812, -1, 10799, 10814, 10811, -1, 7427, 10813, 7425, -1, 10803, 10815, 7385, -1, 10802, 10816, 10814, -1, 10804, 10816, 10802, -1, 7385, 10815, 7383, -1, 10804, 10817, 10816, -1, 10803, 10818, 10815, -1, 10805, 10817, 10804, -1, 10806, 10818, 10803, -1, 10808, 10819, 10806, -1, 10807, 10820, 10805, -1, 10805, 10820, 10817, -1, 7430, 10821, 7428, -1, 10806, 10819, 10818, -1, 10807, 10821, 10820, -1, 10810, 10822, 10808, -1, 10809, 10821, 10807, -1, 7428, 10821, 10809, -1, 10808, 10822, 10819, -1, 10812, 10823, 10810, -1, 10811, 10824, 7338, -1, 10810, 10823, 10822, -1, 7338, 10824, 7336, -1, 10813, 10825, 10812, -1, 10811, 10826, 10824, -1, 7427, 10825, 10813, -1, 7429, 10825, 7427, -1, 10812, 10825, 10823, -1, 10814, 10826, 10811, -1, 10815, 10827, 7383, -1, 7383, 10827, 7382, -1, 10814, 10828, 10826, -1, 10816, 10828, 10814, -1, 10815, 10829, 10827, -1, 10817, 10830, 10816, -1, 10816, 10830, 10828, -1, 10818, 10829, 10815, -1, 10819, 10831, 10818, -1, 10820, 10832, 10817, -1, 10817, 10832, 10830, -1, 10818, 10831, 10829, -1, 7389, 10833, 7430, -1, 10819, 10834, 10831, -1, 7430, 10833, 10821, -1, 10821, 10833, 10820, -1, 10822, 10834, 10819, -1, 10820, 10833, 10832, -1, 10824, 10835, 7336, -1, 10823, 10836, 10822, -1, 7336, 10835, 7334, -1, 10822, 10836, 10834, -1, 7431, 10837, 7429, -1, 10824, 10838, 10835, -1, 7429, 10837, 10825, -1, 10825, 10837, 10823, -1, 10823, 10837, 10836, -1, 10826, 10838, 10824, -1, 10827, 10839, 7382, -1, 7382, 10839, 7380, -1, 10828, 10840, 10826, -1, 10827, 10841, 10839, -1, 10826, 10840, 10838, -1, 10829, 10841, 10827, -1, 10830, 10842, 10828, -1, 10828, 10842, 10840, -1, 10832, 10843, 10830, -1, 10831, 10844, 10829, -1, 10830, 10843, 10842, -1, 10829, 10844, 10841, -1, 7390, 10845, 7389, -1, 10831, 10846, 10844, -1, 7389, 10845, 10833, -1, 10834, 10846, 10831, -1, 10832, 10845, 10843, -1, 10833, 10845, 10832, -1, 10836, 10847, 10834, -1, 7332, 10848, 208, -1, 10834, 10847, 10846, -1, 10835, 10848, 7334, -1, 7387, 10849, 7431, -1, 7431, 10849, 10837, -1, 10837, 10849, 10836, -1, 7334, 10848, 7332, -1, 208, 10850, 215, -1, 10836, 10849, 10847, -1, 10835, 10850, 10848, -1, 10839, 10851, 7380, -1, 10838, 10850, 10835, -1, 10848, 10850, 208, -1, 7380, 10851, 7378, -1, 215, 10852, 218, -1, 10839, 10853, 10851, -1, 10841, 10853, 10839, -1, 10840, 10852, 10838, -1, 10850, 10852, 215, -1, 10838, 10852, 10850, -1, 218, 10854, 223, -1, 10844, 10855, 10841, -1, 10840, 10854, 10852, -1, 10842, 10854, 10840, -1, 10841, 10855, 10853, -1, 10852, 10854, 218, -1, 10844, 10856, 10855, -1, 223, 10857, 226, -1, 10846, 10856, 10844, -1, 10842, 10857, 10854, -1, 10843, 10857, 10842, -1, 10847, 10858, 10846, -1, 10854, 10857, 223, -1, 10857, 10859, 226, -1, 7392, 10859, 7390, -1, 10846, 10858, 10856, -1, 226, 10859, 42, -1, 10843, 10859, 10857, -1, 7388, 10860, 7387, -1, 42, 10859, 7392, -1, 7387, 10860, 10849, -1, 7390, 10859, 10845, -1, 10849, 10860, 10847, -1, 10845, 10859, 10843, -1, 10847, 10860, 10858, -1, 7378, 10861, 7376, -1, 10851, 10861, 7378, -1, 10851, 10862, 10861, -1, 10853, 10862, 10851, -1, 10853, 10863, 10862, -1, 10855, 10863, 10853, -1, 10855, 10864, 10863, -1, 10856, 10864, 10855, -1, 10856, 10865, 10864, -1, 10858, 10865, 10856, -1, 7332, 208, 210, -1, 10858, 10866, 10865, -1, 7391, 10866, 7388, -1, 7388, 10866, 10860, -1, 10860, 10866, 10858, -1, 10861, 10867, 7376, -1, 7376, 10867, 7375, -1, 10861, 10868, 10867, -1, 10862, 10868, 10861, -1, 10863, 10869, 10862, -1, 7392, 40, 42, -1, 10862, 10869, 10868, -1, 170, 10870, 201, -1, 10864, 10871, 10863, -1, 10863, 10871, 10869, -1, 201, 10870, 7377, -1, 10865, 10872, 10864, -1, 174, 10873, 170, -1, 10864, 10872, 10871, -1, 170, 10873, 10870, -1, 10866, 10874, 10865, -1, 7391, 10874, 10866, -1, 7394, 10874, 7391, -1, 178, 10875, 174, -1, 10865, 10874, 10872, -1, 174, 10875, 10873, -1, 10867, 10876, 7375, -1, 178, 10877, 10875, -1, 7375, 10876, 7373, -1, 182, 10877, 178, -1, 10868, 10878, 10867, -1, 185, 10879, 182, -1, 10867, 10878, 10876, -1, 182, 10879, 10877, -1, 7393, 10880, 190, -1, 189, 10880, 185, -1, 190, 10880, 189, -1, 10868, 10881, 10878, -1, 185, 10880, 10879, -1, 10869, 10881, 10868, -1, 7377, 10882, 7379, -1, 10871, 10883, 10869, -1, 10870, 10882, 7377, -1, 10869, 10883, 10881, -1, 10872, 10884, 10871, -1, 10870, 10885, 10882, -1, 10873, 10885, 10870, -1, 10871, 10884, 10883, -1, 7396, 10886, 7394, -1, 10875, 10887, 10873, -1, 10872, 10886, 10884, -1, 10873, 10887, 10885, -1, 7394, 10886, 10874, -1, 10874, 10886, 10872, -1, 10877, 10888, 10875, -1, 10876, 10889, 7373, -1, 10875, 10888, 10887, -1, 7373, 10889, 7371, -1, 10878, 10890, 10876, -1, 10879, 10891, 10877, -1, 10877, 10891, 10888, -1, 10876, 10890, 10889, -1, 10879, 10892, 10891, -1, 10880, 10892, 10879, -1, 10881, 10893, 10878, -1, 7395, 10892, 7393, -1, 7393, 10892, 10880, -1, 10878, 10893, 10890, -1, 10882, 10894, 7379, -1, 7379, 10894, 7381, -1, 10881, 10895, 10893, -1, 10883, 10895, 10881, -1, 10885, 10896, 10882, -1, 10884, 10897, 10883, -1, 10882, 10896, 10894, -1, 10883, 10897, 10895, -1, 7398, 10898, 7396, -1, 10885, 10899, 10896, -1, 7396, 10898, 10886, -1, 10886, 10898, 10884, -1, 10884, 10898, 10897, -1, 10887, 10899, 10885, -1, 10889, 10900, 7371, -1, 10888, 10901, 10887, -1, 10887, 10901, 10899, -1, 7371, 10900, 7369, -1, 10888, 10902, 10901, -1, 10889, 10903, 10900, -1, 10891, 10902, 10888, -1, 10890, 10903, 10889, -1, 10892, 10904, 10891, -1, 7397, 10904, 7395, -1, 7395, 10904, 10892, -1, 10891, 10904, 10902, -1, 10893, 10905, 10890, -1, 10890, 10905, 10903, -1, 10893, 10906, 10905, -1, 7381, 10907, 7384, -1, 10895, 10906, 10893, -1, 10894, 10907, 7381, -1, 10896, 10908, 10894, -1, 10897, 10909, 10895, -1, 10895, 10909, 10906, -1, 10894, 10908, 10907, -1, 10899, 10910, 10896, -1, 7400, 10911, 7398, -1, 7398, 10911, 10898, -1, 10898, 10911, 10897, -1, 10897, 10911, 10909, -1, 10896, 10910, 10908, -1, 10899, 10912, 10910, -1, 10900, 10913, 7369, -1, 10901, 10912, 10899, -1, 7369, 10913, 7367, -1, 10900, 10914, 10913, -1, 10903, 10914, 10900, -1, 10902, 10915, 10901, -1, 10901, 10915, 10912, -1, 10904, 10916, 10902, -1, 7399, 10916, 7397, -1, 7397, 10916, 10904, -1, 10902, 10916, 10915, -1, 10905, 10917, 10903, -1, 10907, 10918, 7384, -1, 10903, 10917, 10914, -1, 10906, 10919, 10905, -1, 7384, 10918, 7386, -1, 10905, 10919, 10917, -1, 10908, 10920, 10907, -1, 10909, 10921, 10906, -1, 10906, 10921, 10919, -1, 10907, 10920, 10918, -1, 10909, 10922, 10921, -1, 10908, 10923, 10920, -1, 7402, 10922, 7400, -1, 7400, 10922, 10911, -1, 10911, 10922, 10909, -1, 10910, 10923, 10908, -1, 10910, 10924, 10923, -1, 7367, 10925, 7365, -1, 10913, 10925, 7367, -1, 10912, 10924, 10910, -1, 10912, 10926, 10924, -1, 10913, 10927, 10925, -1, 10915, 10926, 10912, -1, 10914, 10927, 10913, -1, 10915, 10928, 10926, -1, 7401, 10928, 7399, -1, 10916, 10928, 10915, -1, 7399, 10928, 10916, -1, 10914, 10929, 10927, -1, 10918, 10930, 7386, -1, 10917, 10929, 10914, -1, 10919, 10931, 10917, -1, 7386, 10930, 7299, -1, 10917, 10931, 10929, -1, 10920, 10932, 10918, -1, 10921, 10933, 10919, -1, 10919, 10933, 10931, -1, 10918, 10932, 10930, -1, 7402, 10934, 10922, -1, 10920, 10935, 10932, -1, 7404, 10934, 7402, -1, 10921, 10934, 10933, -1, 10922, 10934, 10921, -1, 10925, 10936, 7365, -1, 10923, 10935, 10920, -1, 10924, 10937, 10923, -1, 10923, 10937, 10935, -1, 7365, 10936, 7363, -1, 10924, 10938, 10937, -1, 10925, 10939, 10936, -1, 10926, 10938, 10924, -1, 10927, 10939, 10925, -1, 10928, 10940, 10926, -1, 7401, 10940, 10928, -1, 7403, 10940, 7401, -1, 10926, 10940, 10938, -1, 10930, 10941, 7299, -1, 10927, 10942, 10939, -1, 10929, 10942, 10927, -1, 7299, 10941, 7298, -1, 10931, 10943, 10929, -1, 10929, 10943, 10942, -1, 10932, 10944, 10930, -1, 10931, 10945, 10943, -1, 10930, 10944, 10941, -1, 10933, 10945, 10931, -1, 10932, 10946, 10944, -1, 7406, 10947, 7404, -1, 7404, 10947, 10934, -1, 10934, 10947, 10933, -1, 10933, 10947, 10945, -1, 10935, 10946, 10932, -1, 10935, 10948, 10946, -1, 10936, 10949, 7363, -1, 10937, 10948, 10935, -1, 7363, 10949, 7361, -1, 10937, 10950, 10948, -1, 10936, 10951, 10949, -1, 10938, 10950, 10937, -1, 10938, 10952, 10950, -1, 10939, 10951, 10936, -1, 7405, 10952, 7403, -1, 10940, 10952, 10938, -1, 7403, 10952, 10940, -1, 10942, 10953, 10939, -1, 10939, 10953, 10951, -1, 10941, 10954, 7298, -1, 7298, 10954, 7303, -1, 10942, 10955, 10953, -1, 10944, 10956, 10941, -1, 10943, 10955, 10942, -1, 10941, 10956, 10954, -1, 10945, 10957, 10943, -1, 10943, 10957, 10955, -1, 10946, 10958, 10944, -1, 7408, 10959, 7406, -1, 10945, 10959, 10957, -1, 7406, 10959, 10947, -1, 10947, 10959, 10945, -1, 10944, 10958, 10956, -1, 10949, 10960, 7361, -1, 10946, 10961, 10958, -1, 10948, 10961, 10946, -1, 7361, 10960, 7359, -1, 10948, 10962, 10961, -1, 10951, 10963, 10949, -1, 10950, 10962, 10948, -1, 10949, 10963, 10960, -1, 10952, 10964, 10950, -1, 7405, 10964, 10952, -1, 7407, 10964, 7405, -1, 10951, 10965, 10963, -1, 10950, 10964, 10962, -1, 10953, 10965, 10951, -1, 10954, 10966, 7303, -1, 7303, 10966, 7305, -1, 10955, 10967, 10953, -1, 10953, 10967, 10965, -1, 10954, 10968, 10966, -1, 10956, 10968, 10954, -1, 10957, 10969, 10955, -1, 10955, 10969, 10967, -1, 10956, 10970, 10968, -1, 10958, 10970, 10956, -1, 7410, 10971, 7408, -1, 7408, 10971, 10959, -1, 10959, 10971, 10957, -1, 10957, 10971, 10969, -1, 10958, 10972, 10970, -1, 10961, 10972, 10958, -1, 10960, 10973, 7359, -1, 7359, 10973, 7357, -1, 10962, 10974, 10961, -1, 10963, 10975, 10960, -1, 10961, 10974, 10972, -1, 7409, 10976, 7407, -1, 10960, 10975, 10973, -1, 10962, 10976, 10974, -1, 7407, 10976, 10964, -1, 10964, 10976, 10962, -1, 10965, 10977, 10963, -1, 10966, 10978, 7305, -1, 10963, 10977, 10975, -1, 7305, 10978, 7308, -1, 10965, 10979, 10977, -1, 10967, 10979, 10965, -1, 10968, 10980, 10966, -1, 10966, 10980, 10978, -1, 10969, 10981, 10967, -1, 10967, 10981, 10979, -1, 7412, 10982, 7410, -1, 10970, 10983, 10968, -1, 7410, 10982, 10971, -1, 10971, 10982, 10969, -1, 10968, 10983, 10980, -1, 10969, 10982, 10981, -1, 10972, 10984, 10970, -1, 10973, 10985, 7357, -1, 10970, 10984, 10983, -1, 7357, 10985, 7355, -1, 10974, 10986, 10972, -1, 10973, 10987, 10985, -1, 10972, 10986, 10984, -1, 10975, 10987, 10973, -1, 7411, 10988, 7409, -1, 7409, 10988, 10976, -1, 10976, 10988, 10974, -1, 10974, 10988, 10986, -1, 10977, 10989, 10975, -1, 7308, 10990, 7312, -1, 10975, 10989, 10987, -1, 10978, 10990, 7308, -1, 10977, 10724, 10989, -1, 10979, 10724, 10977, -1, 10980, 10721, 10978, -1, 10978, 10721, 10990, -1, 10979, 10727, 10724, -1, 10981, 10727, 10979, -1, 10981, 10729, 10727, -1, 10983, 10730, 10980, -1, 10980, 10730, 10721, -1, 7414, 10729, 7412, -1, 7412, 10729, 10982, -1, 10982, 10729, 10981, -1, 10984, 10734, 10983, -1, 7355, 10732, 7353, -1, 10983, 10734, 10730, -1, 10985, 10732, 7355, -1, 10986, 10735, 10984, -1, 10984, 10735, 10734, -1, 10987, 10740, 10985, -1, 7413, 10738, 7411, -1, 10985, 10740, 10732, -1, 7411, 10738, 10988, -1, 10986, 10738, 10735, -1, 10988, 10738, 10986, -1, 7312, 10744, 7313, -1, 10987, 10741, 10740, -1, 10990, 10744, 7312, -1, 10989, 10741, 10987, -1, 10724, 10726, 10989, -1, 10990, 10723, 10744, -1, 10989, 10726, 10741, -1, 10727, 10725, 10724, -1, 10721, 10723, 10990, -1, 10991, 10992, 10993, -1, 10993, 10992, 10994, -1, 10994, 10995, 10996, -1, 10992, 10995, 10994, -1, 10996, 10997, 10998, -1, 10995, 10997, 10996, -1, 10998, 10999, 11000, -1, 10997, 10999, 10998, -1, 11000, 11001, 11002, -1, 10999, 11001, 11000, -1, 11001, 11003, 11002, -1, 11001, 11004, 11003, -1, 11004, 11005, 11003, -1, 11004, 11006, 11005, -1, 11006, 11007, 11005, -1, 11006, 11008, 11007, -1, 11008, 11009, 11007, -1, 11008, 11010, 11009, -1, 11010, 11011, 11009, -1, 11010, 11012, 11011, -1, 11012, 11013, 11011, -1, 11012, 11014, 11013, -1, 11014, 11015, 11013, -1, 11014, 11016, 11015, -1, 11016, 11017, 11015, -1, 11016, 11018, 11017, -1, 11018, 11019, 11017, -1, 11019, 11020, 11017, -1, 11017, 11021, 11022, -1, 11020, 11021, 11017, -1, 11021, 11023, 11022, -1, 11023, 11024, 11022, -1, 11023, 11025, 11024, -1, 11025, 11026, 11024, -1, 11027, 11028, 11029, -1, 11027, 11030, 11028, -1, 11030, 11031, 11028, -1, 11030, 11032, 11031, -1, 11032, 11033, 11031, -1, 11032, 11034, 11033, -1, 11034, 11035, 11033, -1, 11034, 11036, 11035, -1, 11036, 11037, 11035, -1, 11036, 11038, 11037, -1, 11038, 11039, 11037, -1, 11038, 11040, 11039, -1, 11040, 11041, 11039, -1, 11040, 11042, 11041, -1, 11042, 11043, 11041, -1, 11042, 11044, 11043, -1, 11044, 11045, 11043, -1, 11044, 11046, 11045, -1, 11045, 11047, 11048, -1, 11046, 11047, 11045, -1, 11047, 11049, 11048, -1, 11049, 11050, 11048, -1, 11051, 11052, 11053, -1, 11054, 11055, 11056, -1, 11057, 11058, 11059, -1, 11059, 11058, 11060, -1, 11061, 11062, 11057, -1, 11057, 11062, 11058, -1, 11060, 11063, 11051, -1, 11058, 11063, 11060, -1, 11051, 11063, 11052, -1, 11056, 11064, 11061, -1, 11061, 11064, 11062, -1, 11055, 11064, 11056, -1, 11052, 11065, 11066, -1, 11062, 11065, 11058, -1, 11058, 11065, 11063, -1, 11063, 11065, 11052, -1, 11067, 11068, 11069, -1, 11066, 11068, 11067, -1, 11069, 11068, 11070, -1, 11070, 11068, 11055, -1, 11062, 11068, 11065, -1, 11065, 11068, 11066, -1, 11055, 11068, 11064, -1, 11064, 11068, 11062, -1, 11071, 11072, 11073, -1, 11074, 11075, 11076, -1, 11077, 11075, 11078, -1, 11078, 11075, 11071, -1, 11076, 11075, 11077, -1, 11079, 11080, 11081, -1, 11082, 11080, 11079, -1, 11083, 11084, 11082, -1, 11072, 11084, 11083, -1, 11085, 11086, 11074, -1, 11071, 11086, 11072, -1, 11075, 11086, 11071, -1, 11074, 11086, 11075, -1, 11081, 11087, 11088, -1, 11080, 11087, 11081, -1, 11084, 11089, 11082, -1, 11082, 11089, 11080, -1, 11090, 11091, 11085, -1, 11072, 11091, 11084, -1, 11092, 11076, 11077, -1, 11086, 11091, 11072, -1, 11085, 11091, 11086, -1, 11088, 11093, 11094, -1, 11087, 11093, 11088, -1, 11089, 11095, 11080, -1, 11080, 11095, 11087, -1, 11096, 11097, 11090, -1, 11091, 11097, 11084, -1, 11084, 11097, 11089, -1, 11090, 11097, 11091, -1, 11094, 11098, 11099, -1, 11093, 11098, 11094, -1, 11087, 11100, 11093, -1, 11095, 11100, 11087, -1, 11097, 11101, 11089, -1, 11102, 11101, 11096, -1, 11089, 11101, 11095, -1, 11096, 11101, 11097, -1, 11099, 11103, 11104, -1, 11098, 11103, 11099, -1, 11093, 11105, 11098, -1, 11100, 11105, 11093, -1, 11095, 11106, 11100, -1, 11102, 11106, 11101, -1, 11107, 11106, 11102, -1, 11101, 11106, 11095, -1, 11104, 11108, 11109, -1, 11103, 11108, 11104, -1, 11110, 11111, 11112, -1, 11098, 11113, 11103, -1, 11105, 11113, 11098, -1, 11106, 11114, 11100, -1, 11115, 11114, 11107, -1, 11107, 11114, 11106, -1, 11100, 11114, 11105, -1, 11108, 11116, 11109, -1, 11109, 11116, 11110, -1, 11110, 11116, 11111, -1, 11113, 11117, 11103, -1, 11103, 11117, 11108, -1, 11118, 11119, 11115, -1, 11115, 11119, 11114, -1, 11105, 11119, 11113, -1, 11114, 11119, 11105, -1, 11111, 11120, 11121, -1, 11108, 11120, 11116, -1, 11122, 11073, 11123, -1, 11116, 11120, 11111, -1, 11123, 11073, 11124, -1, 11117, 11120, 11108, -1, 11125, 11126, 11118, -1, 11118, 11126, 11119, -1, 11113, 11126, 11117, -1, 11119, 11126, 11113, -1, 11124, 11083, 11127, -1, 11121, 11128, 11129, -1, 11129, 11128, 11130, -1, 11073, 11083, 11124, -1, 11130, 11128, 11125, -1, 11125, 11128, 11126, -1, 11117, 11128, 11120, -1, 11126, 11128, 11117, -1, 11078, 11071, 11122, -1, 11120, 11128, 11121, -1, 11122, 11071, 11073, -1, 11127, 11082, 11079, -1, 11083, 11082, 11127, -1, 11073, 11072, 11083, -1, 11131, 11132, 11133, -1, 11134, 11132, 11131, -1, 11135, 11132, 11134, -1, 11136, 11137, 11138, -1, 11139, 11140, 11135, -1, 11141, 11140, 11139, -1, 11142, 11143, 11144, -1, 11144, 11143, 11145, -1, 11146, 11143, 11141, -1, 11145, 11143, 11146, -1, 11133, 11147, 11148, -1, 11132, 11147, 11133, -1, 11135, 11147, 11132, -1, 11140, 11147, 11135, -1, 11149, 11150, 11142, -1, 11142, 11150, 11143, -1, 11141, 11150, 11140, -1, 11143, 11150, 11141, -1, 11148, 11151, 11152, -1, 11153, 11151, 11149, -1, 11149, 11151, 11150, -1, 11152, 11151, 11153, -1, 11147, 11151, 11148, -1, 11140, 11151, 11147, -1, 11150, 11151, 11140, -1, 11153, 11154, 11152, -1, 11138, 11155, 11156, -1, 11137, 11155, 11138, -1, 11156, 11157, 11158, -1, 11155, 11157, 11156, -1, 11159, 11160, 11137, -1, 11137, 11160, 11155, -1, 11158, 11161, 11162, -1, 11157, 11161, 11158, -1, 11160, 11163, 11155, -1, 11155, 11163, 11157, -1, 11164, 11165, 11166, -1, 11167, 11165, 11159, -1, 11166, 11165, 11167, -1, 11159, 11165, 11160, -1, 11162, 11139, 11168, -1, 11161, 11139, 11162, -1, 11163, 11146, 11157, -1, 11157, 11146, 11161, -1, 11169, 11170, 11164, -1, 11164, 11170, 11165, -1, 11165, 11170, 11160, -1, 11160, 11170, 11163, -1, 11168, 11135, 11134, -1, 11139, 11135, 11168, -1, 11146, 11141, 11161, -1, 11161, 11141, 11139, -1, 11144, 11145, 11169, -1, 11169, 11145, 11170, -1, 11170, 11145, 11163, -1, 11163, 11145, 11146, -1, 11171, 11172, 11173, -1, 11173, 11172, 11174, -1, 11175, 11172, 11176, -1, 11174, 11172, 11175, -1, 11177, 11178, 11179, -1, 11180, 11178, 11181, -1, 11181, 11178, 11177, -1, 11182, 11178, 11180, -1, 11183, 11184, 11182, -1, 11185, 11184, 11183, -1, 11186, 11187, 11171, -1, 11171, 11187, 11172, -1, 11176, 11187, 11185, -1, 11172, 11187, 11176, -1, 11179, 11188, 11189, -1, 11178, 11188, 11179, -1, 11182, 11188, 11178, -1, 11184, 11188, 11182, -1, 11190, 11191, 11186, -1, 11186, 11191, 11187, -1, 11185, 11191, 11184, -1, 11187, 11191, 11185, -1, 11189, 11192, 11193, -1, 11193, 11192, 11194, -1, 11194, 11192, 11195, -1, 11195, 11192, 11190, -1, 11190, 11192, 11191, -1, 11188, 11192, 11189, -1, 11184, 11192, 11188, -1, 11191, 11192, 11184, -1, 11196, 11197, 11198, -1, 11198, 11197, 11199, -1, 11199, 11200, 11201, -1, 11197, 11200, 11199, -1, 11202, 11203, 11196, -1, 11196, 11203, 11197, -1, 11201, 11204, 11205, -1, 11200, 11204, 11201, -1, 11203, 11175, 11197, -1, 11197, 11175, 11200, -1, 11206, 11207, 11208, -1, 11209, 11207, 11202, -1, 11208, 11207, 11209, -1, 11202, 11207, 11203, -1, 11205, 11183, 11210, -1, 11204, 11183, 11205, -1, 11175, 11176, 11200, -1, 11200, 11176, 11204, -1, 11173, 11174, 11206, -1, 11207, 11174, 11203, -1, 11203, 11174, 11175, -1, 11206, 11174, 11207, -1, 11210, 11182, 11180, -1, 11183, 11182, 11210, -1, 11176, 11185, 11204, -1, 11204, 11185, 11183, -1, 11211, 11212, 11213, -1, 11214, 11212, 11211, -1, 11213, 11212, 11215, -1, 11216, 11217, 11218, -1, 11219, 11217, 11216, -1, 11220, 11221, 11222, -1, 11222, 11221, 11219, -1, 11223, 11224, 11225, -1, 11212, 11224, 11215, -1, 11215, 11224, 11220, -1, 11225, 11224, 11212, -1, 11218, 11226, 11227, -1, 11217, 11226, 11218, -1, 11221, 11228, 11219, -1, 11219, 11228, 11217, -1, 11229, 11230, 11223, -1, 11220, 11230, 11221, -1, 11223, 11230, 11224, -1, 11224, 11230, 11220, -1, 11227, 11231, 11232, -1, 11226, 11231, 11227, -1, 11217, 11233, 11226, -1, 11228, 11233, 11217, -1, 11234, 11235, 11229, -1, 11229, 11235, 11230, -1, 11221, 11235, 11228, -1, 11230, 11235, 11221, -1, 11232, 11236, 11237, -1, 11231, 11236, 11232, -1, 11226, 11238, 11231, -1, 11233, 11238, 11226, -1, 11235, 11239, 11228, -1, 11240, 11239, 11234, -1, 11234, 11239, 11235, -1, 11228, 11239, 11233, -1, 11237, 11241, 11242, -1, 11236, 11241, 11237, -1, 11238, 11243, 11231, -1, 11231, 11243, 11236, -1, 11233, 11244, 11238, -1, 11240, 11244, 11239, -1, 11245, 11244, 11240, -1, 11239, 11244, 11233, -1, 11242, 11246, 11247, -1, 11241, 11246, 11242, -1, 11236, 11248, 11241, -1, 11243, 11248, 11236, -1, 11249, 11250, 11245, -1, 11238, 11250, 11243, -1, 11244, 11250, 11238, -1, 11245, 11250, 11244, -1, 11251, 11252, 11253, -1, 11246, 11252, 11247, -1, 11254, 11255, 11256, -1, 11247, 11252, 11257, -1, 11257, 11252, 11251, -1, 11258, 11259, 11260, -1, 11260, 11259, 11261, -1, 11248, 11262, 11241, -1, 11241, 11262, 11246, -1, 11261, 11222, 11263, -1, 11264, 11265, 11249, -1, 11243, 11265, 11248, -1, 11250, 11265, 11243, -1, 11249, 11265, 11250, -1, 11259, 11222, 11261, -1, 11253, 11266, 11267, -1, 11213, 11215, 11258, -1, 11252, 11266, 11253, -1, 11262, 11266, 11246, -1, 11246, 11266, 11252, -1, 11258, 11215, 11259, -1, 11268, 11269, 11264, -1, 11263, 11219, 11216, -1, 11264, 11269, 11265, -1, 11265, 11269, 11248, -1, 11248, 11269, 11262, -1, 11222, 11219, 11263, -1, 11267, 11270, 11256, -1, 11254, 11270, 11268, -1, 11262, 11270, 11266, -1, 11268, 11270, 11269, -1, 11266, 11270, 11267, -1, 11256, 11270, 11254, -1, 11259, 11220, 11222, -1, 11269, 11270, 11262, -1, 11215, 11220, 11259, -1, 11225, 11212, 11214, -1, 11271, 11272, 11273, -1, 11274, 11275, 11276, -1, 11277, 11278, 11279, -1, 11271, 11280, 11272, -1, 11281, 11282, 11271, -1, 11271, 11282, 11280, -1, 11272, 11283, 11274, -1, 11280, 11283, 11272, -1, 11274, 11283, 11275, -1, 11279, 11284, 11281, -1, 11281, 11284, 11282, -1, 11278, 11284, 11279, -1, 11275, 11285, 11286, -1, 11282, 11285, 11280, -1, 11280, 11285, 11283, -1, 11283, 11285, 11275, -1, 11286, 11287, 11288, -1, 11288, 11287, 11289, -1, 11289, 11287, 11290, -1, 11290, 11287, 11278, -1, 11282, 11287, 11285, -1, 11278, 11287, 11284, -1, 11285, 11287, 11286, -1, 11284, 11287, 11282, -1, 11291, 11292, 11293, -1, 11294, 11295, 11296, -1, 11294, 11297, 11295, -1, 11294, 11298, 11297, -1, 11299, 11298, 11294, -1, 11299, 11300, 11301, -1, 11299, 11302, 11298, -1, 11299, 11301, 11302, -1, 11303, 11294, 11296, -1, 11303, 11296, 11304, -1, 11305, 11306, 11300, -1, 11305, 11294, 11303, -1, 11305, 11300, 11299, -1, 11305, 11299, 11294, -1, 11307, 11304, 11308, -1, 11307, 11303, 11304, -1, 11309, 11303, 11307, -1, 11309, 11305, 11303, -1, 11309, 11310, 11306, -1, 11309, 11306, 11305, -1, 11311, 11307, 11308, -1, 11311, 11308, 11312, -1, 11313, 11307, 11311, -1, 11313, 11310, 11309, -1, 11313, 11314, 11310, -1, 11313, 11309, 11307, -1, 11315, 11312, 11316, -1, 11315, 11311, 11312, -1, 11317, 11313, 11311, -1, 11317, 11314, 11313, -1, 11317, 11318, 11314, -1, 11317, 11311, 11315, -1, 11319, 11316, 11320, -1, 11319, 11315, 11316, -1, 11321, 11315, 11319, -1, 11321, 11322, 11318, -1, 11321, 11318, 11317, -1, 11321, 11317, 11315, -1, 11323, 11320, 11324, -1, 11323, 11319, 11320, -1, 11325, 11321, 11319, -1, 11325, 11322, 11321, -1, 11325, 11326, 11322, -1, 11325, 11319, 11323, -1, 11327, 11324, 11328, -1, 11327, 11323, 11324, -1, 11329, 11323, 11327, -1, 11329, 11330, 11326, -1, 11329, 11326, 11325, -1, 11329, 11325, 11323, -1, 11331, 11328, 11332, -1, 11331, 11327, 11328, -1, 11333, 11330, 11329, -1, 11333, 11334, 11330, -1, 11333, 11329, 11327, -1, 11333, 11327, 11331, -1, 11335, 11332, 11336, -1, 11335, 11331, 11332, -1, 11337, 11333, 11331, -1, 11337, 11334, 11333, -1, 11337, 11338, 11334, -1, 11337, 11331, 11335, -1, 11339, 11335, 11336, -1, 11340, 11337, 11335, -1, 11340, 11338, 11337, -1, 11340, 11341, 11338, -1, 11340, 11335, 11339, -1, 11342, 11336, 11343, -1, 11342, 11339, 11336, -1, 11344, 11340, 11339, -1, 11344, 11345, 11341, -1, 11344, 11339, 11342, -1, 11344, 11341, 11340, -1, 11346, 11343, 11347, -1, 11346, 11342, 11343, -1, 11348, 11342, 11346, -1, 11348, 11345, 11344, -1, 11348, 11349, 11345, -1, 11348, 11344, 11342, -1, 11350, 11351, 11352, -1, 11350, 11347, 11351, -1, 11350, 11346, 11347, -1, 11353, 11348, 11346, -1, 11353, 11354, 11349, -1, 11353, 11346, 11350, -1, 11353, 11349, 11348, -1, 11355, 11350, 11352, -1, 11356, 11353, 11350, -1, 11356, 11350, 11355, -1, 11356, 11354, 11353, -1, 11356, 11357, 11354, -1, 11358, 11352, 11359, -1, 11358, 11355, 11352, -1, 11360, 11356, 11355, -1, 11360, 11357, 11356, -1, 11360, 11355, 11358, -1, 11360, 11361, 11357, -1, 11362, 11359, 11363, -1, 11362, 11358, 11359, -1, 11364, 11360, 11358, -1, 11364, 11361, 11360, -1, 11364, 11358, 11362, -1, 11364, 11365, 11361, -1, 11366, 11363, 11367, -1, 11366, 11362, 11363, -1, 11368, 11364, 11362, -1, 11368, 11365, 11364, -1, 11368, 11369, 11365, -1, 11368, 11362, 11366, -1, 11370, 11371, 11372, -1, 11370, 11367, 11371, -1, 11370, 11366, 11367, -1, 11373, 11374, 11369, -1, 11373, 11369, 11368, -1, 11373, 11368, 11366, -1, 11373, 11366, 11370, -1, 11375, 11370, 11372, -1, 11376, 11377, 11374, -1, 11376, 11374, 11373, -1, 11376, 11373, 11370, -1, 11376, 11370, 11375, -1, 11378, 11372, 11379, -1, 11378, 11375, 11372, -1, 11380, 11381, 11377, -1, 11380, 11377, 11376, -1, 11380, 11376, 11375, -1, 11380, 11375, 11378, -1, 11382, 11383, 11384, -1, 11382, 11379, 11383, -1, 11382, 11378, 11379, -1, 11385, 11386, 11381, -1, 11385, 11381, 11380, -1, 11385, 11380, 11378, -1, 11385, 11378, 11382, -1, 11387, 11382, 11384, -1, 11388, 11389, 11386, -1, 11388, 11386, 11385, -1, 11388, 11385, 11382, -1, 11388, 11382, 11387, -1, 11390, 11391, 11392, -1, 11390, 11384, 11391, -1, 11390, 11387, 11384, -1, 11393, 11394, 11389, -1, 11393, 11389, 11388, -1, 11393, 11388, 11387, -1, 11393, 11387, 11390, -1, 11395, 11390, 11392, -1, 11396, 11390, 11395, -1, 11396, 11397, 11394, -1, 11396, 11394, 11393, -1, 11396, 11393, 11390, -1, 11398, 11392, 11399, -1, 11398, 11395, 11392, -1, 11400, 11397, 11396, -1, 11400, 11395, 11398, -1, 11400, 11401, 11397, -1, 11400, 11396, 11395, -1, 11402, 11398, 11399, -1, 11402, 11403, 11404, -1, 11402, 11399, 11403, -1, 11405, 11400, 11398, -1, 11405, 11401, 11400, -1, 11405, 11406, 11401, -1, 11405, 11398, 11402, -1, 11407, 11402, 11404, -1, 11408, 11406, 11405, -1, 11408, 11405, 11402, -1, 11408, 11402, 11407, -1, 11408, 11409, 11406, -1, 11410, 11411, 11412, -1, 11410, 11404, 11411, -1, 11410, 11407, 11404, -1, 11413, 11408, 11407, -1, 11413, 11409, 11408, -1, 11413, 11407, 11410, -1, 11413, 11414, 11409, -1, 11415, 11410, 11412, -1, 11416, 11413, 11410, -1, 11416, 11414, 11413, -1, 11416, 11410, 11415, -1, 11416, 11417, 11414, -1, 11418, 11412, 11419, -1, 11418, 11415, 11412, -1, 11420, 11415, 11418, -1, 11420, 11416, 11415, -1, 11420, 11417, 11416, -1, 11420, 11421, 11417, -1, 11422, 11423, 11424, -1, 11422, 11419, 11423, -1, 11422, 11418, 11419, -1, 11425, 11418, 11422, -1, 11425, 11420, 11418, -1, 11425, 11421, 11420, -1, 11425, 11426, 11421, -1, 11427, 11422, 11424, -1, 11428, 11422, 11427, -1, 11428, 11425, 11422, -1, 11428, 11426, 11425, -1, 11428, 11429, 11426, -1, 11430, 11431, 11432, -1, 11430, 11424, 11431, -1, 11430, 11427, 11424, -1, 11433, 11428, 11427, -1, 11433, 11429, 11428, -1, 11433, 11427, 11430, -1, 11433, 11434, 11429, -1, 11435, 11430, 11432, -1, 11436, 11430, 11435, -1, 11436, 11433, 11430, -1, 11436, 11434, 11433, -1, 11436, 11437, 11434, -1, 11438, 11439, 11440, -1, 11438, 11432, 11439, -1, 11438, 11440, 11441, -1, 11438, 11435, 11432, -1, 11442, 11438, 11441, -1, 11442, 11441, 11293, -1, 11442, 11293, 11292, -1, 11442, 11436, 11435, -1, 11442, 11437, 11436, -1, 11442, 11435, 11438, -1, 11442, 11292, 11437, -1, 11443, 11444, 11445, -1, 11446, 11444, 11447, -1, 11445, 11444, 11446, -1, 11447, 11448, 11449, -1, 11444, 11448, 11447, -1, 11449, 11450, 11451, -1, 11448, 11450, 11449, -1, 11451, 11452, 11453, -1, 11450, 11452, 11451, -1, 11453, 11454, 11455, -1, 11452, 11454, 11453, -1, 11454, 11456, 11455, -1, 11455, 11457, 11458, -1, 11456, 11457, 11455, -1, 11459, 11460, 11461, -1, 11462, 11461, 11463, -1, 11462, 11459, 11461, -1, 11464, 11463, 11465, -1, 11464, 11462, 11463, -1, 11466, 11464, 11465, -1, 11467, 11468, 11469, -1, 11467, 11469, 11470, -1, 11467, 11470, 11471, -1, 11467, 11472, 11468, -1, 11467, 11471, 11472, -1, 11473, 11474, 11475, -1, 11473, 11476, 11477, -1, 11478, 11475, 11479, -1, 11478, 11479, 11480, -1, 11478, 11481, 11482, -1, 11478, 11482, 11476, -1, 11478, 11473, 11475, -1, 11478, 11476, 11473, -1, 11483, 11480, 11484, -1, 11483, 11485, 11481, -1, 11483, 11481, 11478, -1, 11483, 11478, 11480, -1, 11486, 11484, 11487, -1, 11486, 11487, 11488, -1, 11486, 11489, 11490, -1, 11486, 11490, 11485, -1, 11486, 11483, 11484, -1, 11486, 11485, 11483, -1, 11471, 11488, 11491, -1, 11471, 11470, 11489, -1, 11471, 11489, 11486, -1, 11471, 11486, 11488, -1, 11492, 11493, 11494, -1, 11492, 11494, 11474, -1, 11492, 11495, 11493, -1, 11492, 11474, 11473, -1, 11496, 11477, 11497, -1, 11496, 11497, 11495, -1, 11496, 11492, 11473, -1, 11496, 11495, 11492, -1, 11496, 11473, 11477, -1, 11472, 11491, 11498, -1, 11472, 11498, 11499, -1, 11472, 11499, 11468, -1, 11472, 11471, 11491, -1, 11500, 11501, 11502, -1, 11500, 11503, 11504, -1, 11505, 11502, 11506, -1, 11505, 11507, 11503, -1, 11505, 11500, 11502, -1, 11505, 11503, 11500, -1, 11508, 11506, 11509, -1, 11508, 11510, 11507, -1, 11508, 11507, 11505, -1, 11508, 11505, 11506, -1, 11511, 11512, 11513, -1, 11511, 11513, 11501, -1, 11511, 11514, 11512, -1, 11511, 11501, 11500, -1, 11515, 11504, 11516, -1, 11515, 11516, 11514, -1, 11515, 11514, 11511, -1, 11515, 11511, 11500, -1, 11515, 11500, 11504, -1, 11517, 11509, 11518, -1, 11517, 11518, 11519, -1, 11517, 11519, 11520, -1, 11517, 11508, 11509, -1, 11521, 11520, 11522, -1, 11521, 11522, 11510, -1, 11521, 11517, 11520, -1, 11521, 11508, 11517, -1, 11521, 11510, 11508, -1, 11523, 11524, 11525, -1, 11526, 11525, 11527, -1, 11526, 11523, 11525, -1, 11528, 11529, 11530, -1, 11531, 11527, 11529, -1, 11531, 11526, 11527, -1, 11532, 11529, 11528, -1, 11532, 11531, 11529, -1, 11533, 11528, 11534, -1, 11533, 11532, 11528, -1, 11535, 11534, 11536, -1, 11535, 11533, 11534, -1, 11537, 11536, 11538, -1, 11537, 11538, 11539, -1, 11537, 11535, 11536, -1, 11540, 11539, 11541, -1, 11540, 11537, 11539, -1, 11542, 11541, 11543, -1, 11542, 11540, 11541, -1, 11544, 11543, 11545, -1, 11544, 11542, 11543, -1, 11546, 11545, 11547, -1, 11546, 11547, 11548, -1, 11549, 11544, 11545, -1, 11549, 11545, 11546, -1, 11550, 11546, 11551, -1, 11550, 11549, 11546, -1, 11552, 11551, 11553, -1, 11552, 11550, 11551, -1, 11554, 11553, 11555, -1, 11554, 11552, 11553, -1, 11556, 11557, 11558, -1, 11559, 11558, 11560, -1, 11559, 11556, 11558, -1, 11561, 11560, 11562, -1, 11561, 11559, 11560, -1, 11563, 11559, 11561, -1, 11564, 11561, 11565, -1, 11564, 11563, 11561, -1, 11566, 11565, 11567, -1, 11566, 11564, 11565, -1, 11568, 11567, 11569, -1, 11568, 11566, 11567, -1, 11570, 11569, 11571, -1, 11570, 11568, 11569, -1, 11572, 11571, 11573, -1, 11572, 11570, 11571, -1, 11574, 11573, 11575, -1, 11574, 11572, 11573, -1, 11576, 11575, 11577, -1, 11576, 11574, 11575, -1, 11578, 11577, 11579, -1, 11578, 11576, 11577, -1, 11580, 11579, 11581, -1, 11580, 11578, 11579, -1, 11582, 11581, 11583, -1, 11582, 11580, 11581, -1, 11584, 11583, 11585, -1, 11584, 11582, 11583, -1, 11586, 11587, 11588, -1, 11589, 11586, 11590, -1, 11589, 11587, 11586, -1, 11591, 11590, 11592, -1, 11591, 11589, 11590, -1, 11593, 11592, 11594, -1, 11593, 11591, 11592, -1, 11595, 11594, 11596, -1, 11595, 11593, 11594, -1, 11597, 11596, 11598, -1, 11597, 11595, 11596, -1, 11599, 11598, 11600, -1, 11599, 11597, 11598, -1, 11601, 11600, 11602, -1, 11601, 11599, 11600, -1, 11603, 11602, 11604, -1, 11603, 11601, 11602, -1, 11605, 11604, 11606, -1, 11605, 11603, 11604, -1, 11607, 11608, 11609, -1, 11610, 11606, 11607, -1, 11610, 11605, 11606, -1, 11611, 11610, 11607, -1, 11612, 11609, 11613, -1, 11612, 11607, 11609, -1, 11612, 11611, 11607, -1, 11614, 11613, 11615, -1, 11614, 11612, 11613, -1, 11616, 11617, 11618, -1, 11619, 11617, 11616, -1, 11620, 11621, 11622, -1, 11622, 11621, 11623, -1, 11623, 11621, 11619, -1, 11619, 11621, 11617, -1, 11617, 11624, 11618, -1, 11618, 11624, 11625, -1, 11626, 11627, 11620, -1, 11617, 11627, 11624, -1, 11620, 11627, 11621, -1, 11621, 11627, 11617, -1, 11628, 11629, 11630, -1, 11625, 11631, 11632, -1, 11624, 11631, 11625, -1, 11626, 11633, 11627, -1, 11634, 11635, 11636, -1, 11637, 11633, 11626, -1, 11636, 11635, 11638, -1, 11627, 11633, 11624, -1, 11624, 11633, 11631, -1, 11630, 11639, 11634, -1, 11632, 11640, 11641, -1, 11629, 11639, 11630, -1, 11631, 11640, 11632, -1, 11634, 11639, 11635, -1, 11637, 11642, 11633, -1, 11643, 11642, 11637, -1, 11638, 11644, 11645, -1, 11635, 11644, 11638, -1, 11633, 11642, 11631, -1, 11631, 11642, 11640, -1, 11639, 11646, 11635, -1, 11647, 11646, 11629, -1, 11640, 11648, 11641, -1, 11641, 11648, 11649, -1, 11635, 11646, 11644, -1, 11629, 11646, 11639, -1, 11644, 11650, 11645, -1, 11651, 11652, 11643, -1, 11645, 11650, 11653, -1, 11640, 11652, 11648, -1, 11643, 11652, 11642, -1, 11642, 11652, 11640, -1, 11654, 11655, 11647, -1, 11644, 11655, 11650, -1, 11647, 11655, 11646, -1, 11649, 11656, 11657, -1, 11646, 11655, 11644, -1, 11648, 11656, 11649, -1, 11651, 11658, 11652, -1, 11650, 11659, 11653, -1, 11652, 11658, 11648, -1, 11660, 11658, 11651, -1, 11653, 11659, 11661, -1, 11648, 11658, 11656, -1, 11662, 11663, 11654, -1, 11656, 11664, 11657, -1, 11654, 11663, 11655, -1, 11650, 11663, 11659, -1, 11655, 11663, 11650, -1, 11657, 11664, 11665, -1, 11660, 11666, 11658, -1, 11658, 11666, 11656, -1, 11661, 11667, 11668, -1, 11669, 11666, 11660, -1, 11659, 11667, 11661, -1, 11656, 11666, 11664, -1, 11670, 11671, 11662, -1, 11672, 11673, 11674, -1, 11663, 11671, 11659, -1, 11664, 11673, 11665, -1, 11662, 11671, 11663, -1, 11659, 11671, 11667, -1, 11675, 11673, 11672, -1, 11665, 11673, 11675, -1, 11668, 11676, 11677, -1, 11674, 11678, 11679, -1, 11667, 11676, 11668, -1, 11679, 11678, 11680, -1, 11673, 11678, 11674, -1, 11666, 11678, 11664, -1, 11669, 11678, 11666, -1, 11667, 11681, 11676, -1, 11682, 11678, 11669, -1, 11683, 11681, 11670, -1, 11680, 11678, 11682, -1, 11664, 11678, 11673, -1, 11670, 11681, 11671, -1, 11671, 11681, 11667, -1, 11676, 11684, 11677, -1, 11677, 11684, 11685, -1, 11686, 11687, 11683, -1, 11683, 11687, 11681, -1, 11681, 11687, 11676, -1, 11676, 11687, 11684, -1, 11685, 11688, 11689, -1, 11684, 11688, 11685, -1, 11690, 11691, 11686, -1, 11687, 11691, 11684, -1, 11686, 11691, 11687, -1, 11684, 11691, 11688, -1, 11689, 11692, 11693, -1, 11688, 11692, 11689, -1, 11694, 11695, 11690, -1, 11688, 11695, 11692, -1, 11690, 11695, 11691, -1, 11691, 11695, 11688, -1, 11692, 11696, 11693, -1, 11693, 11696, 11697, -1, 11698, 11699, 11694, -1, 11692, 11699, 11696, -1, 11694, 11699, 11695, -1, 11695, 11699, 11692, -1, 11696, 11700, 11697, -1, 11697, 11700, 11701, -1, 11696, 11702, 11700, -1, 11703, 11702, 11698, -1, 11698, 11702, 11699, -1, 11699, 11702, 11696, -1, 11701, 11704, 11705, -1, 11700, 11704, 11701, -1, 11706, 11707, 11703, -1, 11702, 11707, 11700, -1, 11700, 11707, 11704, -1, 11703, 11707, 11702, -1, 11704, 11619, 11705, -1, 11705, 11619, 11616, -1, 11622, 11623, 11706, -1, 11706, 11623, 11707, -1, 11707, 11623, 11704, -1, 11704, 11623, 11619, -1, 11708, 11709, 11710, -1, 11711, 11710, 11712, -1, 11711, 11708, 11710, -1, 11713, 11712, 11714, -1, 11713, 11711, 11712, -1, 11715, 11713, 11714, -1, 11716, 11717, 11718, -1, 11718, 11717, 11719, -1, 11719, 11720, 11721, -1, 11717, 11720, 11719, -1, 11721, 11722, 11723, -1, 11720, 11722, 11721, -1, 11723, 11724, 11725, -1, 11722, 11724, 11723, -1, 11725, 11726, 11727, -1, 11724, 11726, 11725, -1, 11727, 11728, 11729, -1, 11726, 11728, 11727, -1, 11729, 11730, 11731, -1, 11728, 11730, 11729, -1, 11732, 11733, 11689, -1, 11734, 11735, 11736, -1, 11737, 11738, 11739, -1, 11740, 11741, 11734, -1, 11739, 11738, 11733, -1, 11734, 11741, 11735, -1, 11733, 11738, 11689, -1, 11689, 11738, 11737, -1, 11742, 11743, 11625, -1, 11618, 11743, 11744, -1, 11744, 11743, 11742, -1, 11735, 11745, 11705, -1, 11625, 11743, 11618, -1, 11735, 11746, 11745, -1, 11741, 11746, 11735, -1, 11747, 11746, 11740, -1, 11740, 11746, 11741, -1, 11745, 11748, 11705, -1, 11749, 11750, 11672, -1, 11751, 11750, 11749, -1, 11705, 11748, 11701, -1, 11752, 11750, 11751, -1, 11747, 11753, 11746, -1, 11750, 11675, 11672, -1, 11745, 11753, 11748, -1, 11746, 11753, 11745, -1, 11748, 11754, 11701, -1, 11750, 11755, 11675, -1, 11755, 11756, 11675, -1, 11757, 11758, 11747, -1, 11747, 11758, 11753, -1, 11756, 11665, 11675, -1, 11753, 11759, 11748, -1, 11756, 11760, 11665, -1, 11760, 11657, 11665, -1, 11748, 11759, 11754, -1, 11760, 11761, 11657, -1, 11754, 11762, 11701, -1, 11761, 11649, 11657, -1, 11758, 11763, 11753, -1, 11757, 11763, 11758, -1, 11761, 11764, 11649, -1, 11753, 11763, 11759, -1, 11759, 11765, 11754, -1, 11766, 11641, 11764, -1, 11754, 11765, 11762, -1, 11764, 11641, 11649, -1, 11766, 11767, 11641, -1, 11768, 11769, 11757, -1, 11757, 11769, 11763, -1, 11767, 11632, 11641, -1, 11762, 11770, 11701, -1, 11767, 11771, 11632, -1, 11759, 11772, 11765, -1, 11771, 11625, 11632, -1, 11771, 11742, 11625, -1, 11763, 11772, 11759, -1, 11737, 11685, 11689, -1, 11762, 11773, 11770, -1, 11737, 11774, 11685, -1, 11765, 11773, 11762, -1, 11768, 11775, 11769, -1, 11776, 11775, 11777, -1, 11774, 11778, 11685, -1, 11777, 11775, 11779, -1, 11779, 11775, 11780, -1, 11780, 11775, 11781, -1, 11778, 11677, 11685, -1, 11781, 11775, 11782, -1, 11778, 11783, 11677, -1, 11782, 11775, 11784, -1, 11784, 11775, 11785, -1, 11785, 11775, 11786, -1, 11786, 11775, 11787, -1, 11787, 11775, 11788, -1, 11789, 11775, 11768, -1, 11788, 11775, 11789, -1, 11783, 11668, 11677, -1, 11763, 11775, 11772, -1, 11769, 11775, 11763, -1, 11783, 11790, 11668, -1, 11770, 11791, 11701, -1, 11701, 11791, 11697, -1, 11790, 11661, 11668, -1, 11772, 11792, 11765, -1, 11765, 11792, 11773, -1, 11793, 11653, 11661, -1, 11793, 11794, 11653, -1, 11773, 11795, 11770, -1, 11770, 11795, 11791, -1, 11794, 11645, 11653, -1, 11792, 11796, 11797, -1, 11797, 11796, 11776, -1, 11775, 11796, 11772, -1, 11776, 11796, 11775, -1, 11794, 11798, 11645, -1, 11772, 11796, 11792, -1, 11798, 11638, 11645, -1, 11791, 11799, 11697, -1, 11792, 11800, 11773, -1, 11797, 11800, 11792, -1, 11798, 11801, 11638, -1, 11802, 11800, 11797, -1, 11795, 11800, 11802, -1, 11773, 11800, 11795, -1, 11791, 11803, 11799, -1, 11801, 11636, 11638, -1, 11804, 11803, 11802, -1, 11802, 11803, 11795, -1, 11795, 11803, 11791, -1, 11801, 11805, 11636, -1, 11799, 11806, 11697, -1, 11801, 11807, 11805, -1, 11801, 11808, 11807, -1, 11804, 11809, 11803, -1, 11799, 11809, 11806, -1, 11790, 11793, 11661, -1, 11803, 11809, 11799, -1, 11744, 11810, 11618, -1, 11806, 11811, 11697, -1, 11812, 11810, 11744, -1, 11697, 11811, 11693, -1, 11812, 11813, 11810, -1, 11810, 11813, 11618, -1, 11814, 11815, 11804, -1, 11809, 11815, 11806, -1, 11816, 11813, 11812, -1, 11806, 11815, 11811, -1, 11618, 11813, 11616, -1, 11811, 11815, 11814, -1, 11804, 11815, 11809, -1, 11817, 11818, 11814, -1, 11816, 11819, 11813, -1, 11811, 11818, 11693, -1, 11813, 11819, 11616, -1, 11814, 11818, 11811, -1, 11820, 11788, 11789, -1, 11821, 11822, 11816, -1, 11818, 11823, 11693, -1, 11819, 11822, 11616, -1, 11817, 11823, 11818, -1, 11816, 11822, 11819, -1, 11734, 11736, 11821, -1, 11739, 11732, 11817, -1, 11823, 11732, 11693, -1, 11822, 11736, 11616, -1, 11693, 11732, 11689, -1, 11616, 11736, 11705, -1, 11817, 11732, 11823, -1, 11821, 11736, 11822, -1, 11739, 11733, 11732, -1, 11736, 11735, 11705, -1, 11824, 11516, 11504, -1, 11824, 11514, 11516, -1, 11824, 11825, 11514, -1, 11826, 11504, 11503, -1, 11826, 11824, 11504, -1, 11827, 11503, 11507, -1, 11827, 11826, 11503, -1, 11828, 11507, 11510, -1, 11828, 11827, 11507, -1, 11829, 11510, 11522, -1, 11829, 11828, 11510, -1, 11830, 11522, 11520, -1, 11830, 11829, 11522, -1, 11831, 11830, 11520, -1, 11832, 11459, 11462, -1, 11832, 11833, 11459, -1, 11834, 11462, 11464, -1, 11834, 11832, 11462, -1, 11835, 11464, 11466, -1, 11835, 11834, 11464, -1, 11836, 11495, 11497, -1, 11836, 11837, 11495, -1, 11838, 11497, 11477, -1, 11838, 11836, 11497, -1, 11839, 11477, 11476, -1, 11839, 11838, 11477, -1, 11840, 11476, 11482, -1, 11840, 11839, 11476, -1, 11841, 11482, 11481, -1, 11841, 11840, 11482, -1, 11842, 11481, 11485, -1, 11842, 11841, 11481, -1, 11843, 11485, 11490, -1, 11843, 11842, 11485, -1, 11844, 11843, 11490, -1, 11845, 11490, 11489, -1, 11845, 11844, 11490, -1, 11846, 11489, 11470, -1, 11846, 11845, 11489, -1, 11847, 11470, 11469, -1, 11847, 11846, 11470, -1, 11848, 11469, 11468, -1, 11848, 11847, 11469, -1, 11849, 11848, 11468, -1, 11850, 11851, 11852, -1, 11853, 11854, 11855, -1, 11851, 11854, 11853, -1, 11856, 11857, 11858, -1, 11858, 11859, 11860, -1, 11855, 11861, 11862, -1, 11854, 11861, 11855, -1, 11857, 11859, 11858, -1, 11863, 11864, 11865, -1, 11865, 11864, 11866, -1, 11862, 11867, 11868, -1, 11861, 11867, 11862, -1, 11864, 11869, 11866, -1, 11868, 11870, 11871, -1, 11866, 11869, 11872, -1, 11867, 11870, 11868, -1, 11870, 11873, 11871, -1, 11874, 11875, 11876, -1, 11859, 11877, 11878, -1, 11869, 11879, 11872, -1, 11878, 11877, 11880, -1, 11872, 11879, 11881, -1, 11880, 11877, 11874, -1, 11857, 11877, 11859, -1, 11879, 11882, 11881, -1, 11881, 11882, 11883, -1, 11877, 11884, 11874, -1, 11874, 11884, 11875, -1, 11882, 11885, 11883, -1, 11875, 11886, 11887, -1, 11883, 11885, 11888, -1, 11884, 11886, 11875, -1, 11885, 11889, 11888, -1, 11887, 11890, 11891, -1, 11888, 11889, 11892, -1, 11886, 11890, 11887, -1, 11890, 11893, 11891, -1, 11891, 11893, 11894, -1, 11889, 11895, 11896, -1, 11893, 11897, 11894, -1, 11896, 11895, 11898, -1, 11898, 11895, 11899, -1, 11894, 11897, 11900, -1, 11885, 11895, 11889, -1, 11899, 11901, 11902, -1, 11897, 11903, 11900, -1, 11900, 11903, 11904, -1, 11899, 11905, 11901, -1, 11895, 11905, 11899, -1, 11903, 11906, 11904, -1, 11904, 11906, 11907, -1, 11901, 11908, 11909, -1, 11905, 11908, 11901, -1, 11906, 11910, 11907, -1, 11909, 11911, 11912, -1, 11907, 11910, 11913, -1, 11908, 11911, 11909, -1, 11910, 11914, 11913, -1, 11912, 11915, 11916, -1, 11911, 11915, 11912, -1, 11913, 11914, 11917, -1, 11916, 11918, 11919, -1, 11914, 11920, 11917, -1, 11915, 11918, 11916, -1, 11917, 11920, 11921, -1, 11921, 11922, 11923, -1, 11920, 11922, 11921, -1, 11919, 11924, 11925, -1, 11918, 11924, 11919, -1, 11925, 11926, 11927, -1, 11924, 11926, 11925, -1, 11923, 11928, 11929, -1, 11922, 11930, 11923, -1, 11923, 11930, 11928, -1, 11927, 11931, 11932, -1, 11926, 11931, 11927, -1, 11932, 11933, 11934, -1, 11931, 11933, 11932, -1, 11850, 11852, 11935, -1, 11934, 11936, 11937, -1, 11933, 11936, 11934, -1, 11928, 11938, 11939, -1, 11939, 11938, 11940, -1, 11940, 11938, 11850, -1, 11930, 11938, 11928, -1, 11937, 11856, 11858, -1, 11936, 11856, 11937, -1, 11852, 11851, 11853, -1, 11938, 11851, 11850, -1, 11941, 11942, 11943, -1, 11944, 11942, 11945, -1, 11941, 11946, 11942, -1, 11942, 11946, 11945, -1, 11947, 11946, 11941, -1, 11948, 11946, 11947, -1, 11949, 11950, 11951, -1, 11945, 11946, 11952, -1, 11953, 11950, 11949, -1, 11954, 11955, 11948, -1, 11948, 11955, 11946, -1, 11946, 11955, 11952, -1, 11952, 11955, 11956, -1, 11956, 11955, 11957, -1, 11958, 11959, 11960, -1, 11960, 11959, 11961, -1, 11961, 11959, 11954, -1, 11954, 11959, 11955, -1, 11955, 11959, 11957, -1, 11950, 11962, 11951, -1, 11957, 11959, 11958, -1, 11963, 11964, 11965, -1, 11965, 11964, 11966, -1, 11967, 11964, 11963, -1, 11968, 11964, 11967, -1, 11966, 11969, 11970, -1, 11970, 11969, 11971, -1, 11964, 11969, 11966, -1, 11968, 11969, 11964, -1, 11972, 11969, 11968, -1, 11972, 11973, 11969, -1, 11971, 11973, 11974, -1, 11975, 11973, 11972, -1, 11976, 11973, 11975, -1, 11969, 11973, 11971, -1, 11974, 11977, 11978, -1, 11973, 11977, 11974, -1, 11976, 11977, 11973, -1, 11979, 11977, 11976, -1, 11978, 11980, 11981, -1, 11981, 11980, 11982, -1, 11977, 11980, 11978, -1, 11979, 11980, 11977, -1, 11983, 11980, 11979, -1, 11982, 11984, 11985, -1, 11986, 11984, 11983, -1, 11987, 11984, 11986, -1, 11980, 11984, 11982, -1, 11983, 11984, 11980, -1, 11984, 11988, 11985, -1, 11987, 11988, 11984, -1, 11985, 11988, 11989, -1, 11990, 11988, 11987, -1, 11989, 11991, 11992, -1, 11961, 11963, 11960, -1, 11992, 11991, 11993, -1, 11988, 11991, 11989, -1, 11990, 11991, 11988, -1, 11994, 11991, 11990, -1, 11961, 11967, 11963, -1, 11953, 11991, 11994, -1, 11993, 11995, 11996, -1, 11996, 11995, 11997, -1, 11997, 11995, 11949, -1, 11991, 11995, 11993, -1, 11949, 11995, 11953, -1, 11953, 11995, 11991, -1, 11951, 11998, 11999, -1, 11999, 11998, 12000, -1, 12000, 11998, 12001, -1, 11962, 11998, 11951, -1, 12001, 12002, 12003, -1, 12003, 12002, 12004, -1, 11998, 12002, 12001, -1, 11962, 12002, 11998, -1, 12005, 12002, 11962, -1, 12006, 12002, 12005, -1, 12004, 12007, 12008, -1, 12009, 12007, 12006, -1, 12002, 12007, 12004, -1, 12006, 12007, 12002, -1, 12008, 12010, 12011, -1, 12012, 12010, 12009, -1, 12013, 12010, 12012, -1, 12009, 12010, 12007, -1, 12007, 12010, 12008, -1, 12013, 12014, 12010, -1, 12010, 12014, 12011, -1, 12011, 12014, 12015, -1, 12015, 12014, 12016, -1, 12017, 12014, 12013, -1, 12017, 12018, 12014, -1, 12014, 12018, 12016, -1, 12016, 12018, 12019, -1, 12020, 12018, 12017, -1, 12019, 12021, 12022, -1, 12020, 12021, 12018, -1, 12018, 12021, 12019, -1, 12023, 12021, 12020, -1, 12024, 12021, 12023, -1, 12022, 12025, 12026, -1, 12026, 12025, 12027, -1, 12021, 12025, 12022, -1, 12024, 12025, 12021, -1, 12028, 12025, 12024, -1, 12027, 12029, 12030, -1, 12030, 12029, 12031, -1, 12031, 12029, 12032, -1, 12025, 12029, 12027, -1, 12028, 12029, 12025, -1, 12032, 12029, 12028, -1, 12033, 12034, 12035, -1, 12035, 12034, 12036, -1, 12037, 12034, 12033, -1, 12038, 12034, 12037, -1, 12036, 12039, 12040, -1, 12040, 12039, 12041, -1, 12042, 12039, 12038, -1, 12038, 12039, 12034, -1, 12034, 12039, 12036, -1, 12042, 12043, 12039, -1, 12041, 12043, 12044, -1, 12045, 12043, 12042, -1, 12046, 12043, 12045, -1, 12031, 12037, 12033, -1, 12039, 12043, 12041, -1, 12032, 12037, 12031, -1, 12043, 12047, 12044, -1, 12046, 12047, 12043, -1, 12044, 12047, 12048, -1, 12049, 12047, 12046, -1, 11944, 12050, 11942, -1, 12051, 12050, 11944, -1, 11942, 12052, 11943, -1, 12050, 12052, 11942, -1, 11943, 12052, 12053, -1, 12051, 12052, 12050, -1, 12053, 12052, 12051, -1, 12047, 12054, 12048, -1, 12048, 12054, 12055, -1, 12049, 12056, 12047, -1, 12055, 12056, 12057, -1, 12047, 12056, 12054, -1, 12054, 12056, 12055, -1, 12057, 12056, 12049, -1, 11941, 11943, 11866, -1, 11962, 12058, 11875, -1, 11943, 11865, 11866, -1, 11875, 12058, 12059, -1, 11943, 12053, 11865, -1, 12057, 12049, 11871, -1, 11871, 12049, 11868, -1, 11868, 12046, 11862, -1, 12058, 11950, 12060, -1, 12049, 12046, 11868, -1, 11962, 11950, 12058, -1, 12061, 11858, 11860, -1, 12060, 11858, 12061, -1, 11950, 11953, 12060, -1, 11862, 12045, 11855, -1, 12060, 11953, 11858, -1, 12046, 12045, 11862, -1, 12045, 12042, 11855, -1, 11858, 11994, 11937, -1, 11953, 11994, 11858, -1, 11855, 12042, 11853, -1, 11937, 11990, 11934, -1, 12042, 12038, 11853, -1, 11994, 11990, 11937, -1, 11853, 12038, 11852, -1, 11934, 11987, 11932, -1, 11990, 11987, 11934, -1, 11852, 12062, 11935, -1, 11932, 11986, 11927, -1, 11987, 11986, 11932, -1, 12038, 12037, 11852, -1, 11852, 12037, 12062, -1, 11986, 11983, 11927, -1, 12037, 12063, 12062, -1, 11927, 11983, 11925, -1, 11983, 11979, 11925, -1, 12063, 12032, 11929, -1, 11925, 11979, 11919, -1, 11929, 12032, 11923, -1, 12037, 12032, 12063, -1, 11979, 11976, 11919, -1, 11923, 12028, 11921, -1, 11919, 11976, 11916, -1, 12032, 12028, 11923, -1, 11976, 11975, 11916, -1, 11921, 12024, 11917, -1, 11916, 11975, 11912, -1, 12028, 12024, 11921, -1, 12024, 12023, 11917, -1, 11975, 11972, 11912, -1, 12023, 11913, 11917, -1, 11912, 11972, 11909, -1, 12023, 12020, 11913, -1, 11909, 11968, 11901, -1, 11972, 11968, 11909, -1, 12020, 11907, 11913, -1, 12020, 12017, 11907, -1, 11901, 11967, 11902, -1, 11968, 11967, 11901, -1, 12017, 11904, 11907, -1, 11967, 12064, 11902, -1, 12017, 12013, 11904, -1, 12013, 11900, 11904, -1, 12013, 12012, 11900, -1, 11967, 11961, 12064, -1, 12064, 11961, 12065, -1, 12012, 11894, 11900, -1, 11961, 11888, 12065, -1, 12012, 12009, 11894, -1, 12065, 11888, 11892, -1, 12009, 11891, 11894, -1, 11961, 11954, 11888, -1, 12009, 12006, 11891, -1, 11954, 11883, 11888, -1, 12006, 11887, 11891, -1, 11954, 11948, 11883, -1, 12006, 12005, 11887, -1, 11948, 11881, 11883, -1, 11948, 11947, 11881, -1, 12005, 11875, 11887, -1, 11947, 11872, 11881, -1, 12005, 11962, 11875, -1, 11947, 11941, 11872, -1, 11941, 11866, 11872, -1, 11875, 12059, 11876, -1, 12066, 12067, 11092, -1, 11092, 12067, 11076, -1, 11076, 12068, 11074, -1, 12067, 12068, 11076, -1, 11074, 12069, 11085, -1, 12068, 12069, 11074, -1, 11085, 12070, 11090, -1, 12069, 12070, 11085, -1, 11090, 12071, 11096, -1, 12070, 12071, 11090, -1, 11096, 12072, 11102, -1, 12071, 12072, 11096, -1, 11102, 12073, 11107, -1, 12072, 12073, 11102, -1, 11107, 12074, 11115, -1, 12073, 12074, 11107, -1, 11115, 12075, 11118, -1, 12074, 12075, 11115, -1, 11118, 12076, 11125, -1, 12075, 12076, 11118, -1, 11125, 12077, 11130, -1, 12076, 12077, 11125, -1, 12078, 12079, 11277, -1, 11277, 12079, 11278, -1, 11290, 12080, 11289, -1, 11278, 12080, 11290, -1, 12079, 12080, 11278, -1, 12080, 12081, 11289, -1, 12082, 12083, 11166, -1, 11164, 12083, 11169, -1, 11166, 12083, 11164, -1, 11169, 12084, 11144, -1, 12083, 12084, 11169, -1, 11144, 12085, 11142, -1, 12084, 12085, 11144, -1, 11142, 12086, 11149, -1, 12085, 12086, 11142, -1, 11149, 12087, 11153, -1, 12086, 12087, 11149, -1, 11153, 12088, 11154, -1, 12087, 12088, 11153, -1, 12088, 12089, 11154, -1, 12090, 12091, 12092, -1, 12092, 12093, 12094, -1, 12091, 12093, 12092, -1, 12094, 12095, 12096, -1, 12093, 12095, 12094, -1, 12096, 12097, 12098, -1, 12095, 12097, 12096, -1, 12098, 12099, 12100, -1, 12097, 12099, 12098, -1, 12100, 12101, 12102, -1, 12099, 12101, 12100, -1, 12102, 12103, 12104, -1, 12101, 12103, 12102, -1, 12104, 12105, 12106, -1, 12103, 12105, 12104, -1, 12106, 12107, 12108, -1, 12105, 12107, 12106, -1, 12108, 12109, 12110, -1, 12107, 12109, 12108, -1, 12110, 12111, 12112, -1, 12109, 12111, 12110, -1, 12112, 12113, 12114, -1, 12111, 12113, 12112, -1, 12114, 12115, 12116, -1, 12113, 12115, 12114, -1, 12115, 12117, 12116, -1, 12118, 12119, 12120, -1, 12120, 12119, 12121, -1, 12121, 12122, 12123, -1, 12119, 12122, 12121, -1, 12123, 12124, 12125, -1, 12122, 12124, 12123, -1, 12125, 12126, 12127, -1, 12124, 12126, 12125, -1, 12127, 12128, 12129, -1, 12126, 12128, 12127, -1, 12129, 12130, 12131, -1, 12128, 12130, 12129, -1, 12131, 12132, 12133, -1, 12130, 12132, 12131, -1, 12133, 12134, 12135, -1, 12132, 12134, 12133, -1, 12135, 12136, 12137, -1, 12134, 12136, 12135, -1, 12137, 12138, 12139, -1, 12136, 12138, 12137, -1, 12139, 12140, 12141, -1, 12138, 12140, 12139, -1, 12141, 12142, 12143, -1, 12140, 12142, 12141, -1, 12143, 12144, 12145, -1, 12142, 12144, 12143, -1, 12146, 12147, 12148, -1, 12148, 12147, 12149, -1, 12149, 12150, 12151, -1, 12147, 12150, 12149, -1, 12151, 12152, 12153, -1, 12150, 12152, 12151, -1, 12153, 12154, 12155, -1, 12152, 12154, 12153, -1, 12155, 12156, 12157, -1, 12154, 12156, 12155, -1, 12157, 12158, 12159, -1, 12156, 12158, 12157, -1, 12159, 12160, 12161, -1, 12158, 12160, 12159, -1, 12161, 12162, 12163, -1, 12160, 12162, 12161, -1, 12163, 12164, 12165, -1, 12162, 12164, 12163, -1, 12165, 12166, 12167, -1, 12164, 12166, 12165, -1, 12167, 12168, 12169, -1, 12166, 12168, 12167, -1, 12169, 12170, 12171, -1, 12168, 12170, 12169, -1, 12171, 12172, 12173, -1, 12170, 12172, 12171, -1, 12174, 12175, 11017, -1, 11017, 12175, 11015, -1, 11015, 12176, 11013, -1, 12175, 12176, 11015, -1, 11013, 12177, 11011, -1, 12176, 12177, 11013, -1, 11011, 12178, 11009, -1, 12177, 12178, 11011, -1, 11009, 12179, 11007, -1, 12178, 12179, 11009, -1, 11007, 12180, 11005, -1, 12179, 12180, 11007, -1, 11005, 12181, 11003, -1, 12180, 12181, 11005, -1, 11003, 12182, 11002, -1, 12181, 12182, 11003, -1, 11002, 12183, 11000, -1, 12182, 12183, 11002, -1, 11000, 12184, 10998, -1, 12183, 12184, 11000, -1, 10998, 12185, 10996, -1, 12184, 12185, 10998, -1, 10996, 12186, 10994, -1, 12185, 12186, 10996, -1, 10994, 12187, 10993, -1, 12186, 12187, 10994, -1, 11029, 12188, 12189, -1, 12189, 12190, 12191, -1, 12188, 12190, 12189, -1, 12191, 12192, 12193, -1, 12190, 12192, 12191, -1, 12193, 12194, 12195, -1, 12192, 12194, 12193, -1, 12195, 12196, 12197, -1, 12194, 12196, 12195, -1, 12197, 12198, 12199, -1, 12196, 12198, 12197, -1, 12200, 12201, 12202, -1, 12199, 12203, 12201, -1, 12198, 12203, 12199, -1, 12203, 12204, 12201, -1, 12202, 12205, 12206, -1, 12201, 12205, 12202, -1, 12204, 12205, 12201, -1, 12206, 12207, 12208, -1, 12205, 12207, 12206, -1, 12208, 12209, 12210, -1, 12207, 12209, 12208, -1, 12210, 12211, 12212, -1, 12209, 12211, 12210, -1, 12213, 12214, 12215, -1, 12212, 12214, 12213, -1, 12211, 12214, 12212, -1, 12214, 12216, 12215, -1, 12217, 12218, 12219, -1, 12219, 12220, 12221, -1, 12218, 12220, 12219, -1, 12221, 12222, 12223, -1, 12220, 12222, 12221, -1, 12223, 12224, 12225, -1, 12222, 12224, 12223, -1, 12225, 12226, 12227, -1, 12224, 12226, 12225, -1, 12227, 12228, 12229, -1, 12226, 12228, 12227, -1, 12229, 12230, 12231, -1, 12228, 12230, 12229, -1, 12228, 12232, 12230, -1, 12230, 12233, 12234, -1, 12232, 12233, 12230, -1, 12234, 12235, 12236, -1, 12233, 12235, 12234, -1, 12236, 12237, 12238, -1, 12235, 12237, 12236, -1, 12238, 12239, 12240, -1, 12237, 12239, 12238, -1, 12240, 12241, 12242, -1, 12239, 12241, 12240, -1, 12242, 12243, 12244, -1, 12241, 12243, 12242, -1, 12244, 12245, 12246, -1, 12243, 12245, 12244, -1, 12247, 12248, 12249, -1, 12250, 12247, 12251, -1, 12252, 12250, 12251, -1, 12253, 12250, 12252, -1, 12254, 12253, 12252, -1, 12255, 12256, 12257, -1, 12255, 12258, 12256, -1, 12259, 12253, 12254, -1, 12260, 12259, 12254, -1, 12261, 12257, 12262, -1, 12261, 12255, 12257, -1, 12263, 12259, 12260, -1, 12264, 12263, 12260, -1, 12265, 12262, 12266, -1, 12267, 12263, 12264, -1, 12265, 12261, 12262, -1, 12268, 12267, 12264, -1, 12269, 12267, 12268, -1, 12270, 12266, 12271, -1, 12270, 12265, 12266, -1, 12272, 12269, 12268, -1, 12273, 12269, 12272, -1, 12274, 12273, 12272, -1, 12275, 12271, 12276, -1, 12275, 12270, 12271, -1, 12277, 12273, 12274, -1, 12278, 12277, 12274, -1, 12279, 12275, 12276, -1, 12280, 12277, 12278, -1, 12279, 12276, 12281, -1, 12282, 12280, 12278, -1, 12283, 12280, 12282, -1, 12284, 12279, 12281, -1, 12284, 12281, 12285, -1, 12286, 12283, 12282, -1, 12287, 12283, 12286, -1, 12288, 12284, 12285, -1, 12288, 12285, 12289, -1, 12290, 12287, 12286, -1, 12291, 12287, 12290, -1, 12292, 12288, 12289, -1, 12292, 12289, 12293, -1, 12294, 12291, 12290, -1, 12295, 12291, 12294, -1, 12296, 12292, 12293, -1, 12297, 12295, 12294, -1, 12296, 12293, 12298, -1, 12299, 12295, 12297, -1, 12300, 12296, 12298, -1, 12301, 12299, 12297, -1, 12300, 12298, 12302, -1, 12303, 12299, 12301, -1, 12304, 12302, 12305, -1, 12306, 12303, 12301, -1, 12304, 12300, 12302, -1, 12307, 12303, 12306, -1, 12308, 12307, 12306, -1, 12309, 12305, 12310, -1, 12309, 12304, 12305, -1, 12311, 12307, 12308, -1, 12312, 12311, 12308, -1, 12313, 12310, 12314, -1, 12313, 12309, 12310, -1, 12315, 12311, 12312, -1, 12316, 12314, 12317, -1, 12316, 12313, 12314, -1, 12318, 12317, 12319, -1, 12318, 12316, 12317, -1, 12320, 12319, 12321, -1, 12320, 12318, 12319, -1, 12322, 12321, 12323, -1, 12322, 12320, 12321, -1, 12324, 12323, 12325, -1, 12324, 12322, 12323, -1, 12248, 12325, 12249, -1, 12248, 12324, 12325, -1, 12247, 12249, 12251, -1, 12326, 12327, 12328, -1, 12329, 12330, 12331, -1, 12326, 12328, 12332, -1, 12333, 12334, 12335, -1, 12336, 12337, 12338, -1, 12336, 12338, 12326, -1, 12336, 12332, 12339, -1, 12333, 12335, 12340, -1, 12336, 12326, 12332, -1, 12333, 12340, 12330, -1, 12333, 12330, 12329, -1, 12341, 12342, 12343, -1, 12344, 12345, 12346, -1, 12344, 12347, 12345, -1, 12344, 12346, 12348, -1, 12341, 12339, 12342, -1, 12344, 12329, 12347, -1, 12349, 12341, 12343, -1, 12350, 12348, 12351, -1, 12350, 12352, 12334, -1, 12350, 12344, 12348, -1, 12350, 12351, 12352, -1, 12353, 12337, 12336, -1, 12350, 12334, 12333, -1, 12353, 12336, 12339, -1, 12350, 12333, 12329, -1, 12353, 12339, 12341, -1, 12350, 12329, 12344, -1, 12354, 12341, 12349, -1, 12354, 12355, 12337, -1, 12354, 12353, 12341, -1, 12354, 12337, 12353, -1, 12356, 12349, 12343, -1, 12357, 12358, 12359, -1, 12356, 12343, 12360, -1, 12361, 12356, 12360, -1, 12362, 12352, 12351, -1, 12363, 12364, 12365, -1, 12366, 12354, 12349, -1, 12366, 12349, 12356, -1, 12363, 12367, 12364, -1, 12366, 12355, 12354, -1, 12368, 12360, 12369, -1, 12370, 12367, 12363, -1, 12368, 12361, 12360, -1, 12370, 12359, 12367, -1, 12370, 12357, 12359, -1, 12371, 12366, 12356, -1, 12372, 12365, 12373, -1, 12371, 12374, 12355, -1, 12371, 12356, 12361, -1, 12372, 12363, 12365, -1, 12371, 12355, 12366, -1, 12375, 12361, 12368, -1, 12375, 12374, 12371, -1, 12376, 12370, 12363, -1, 12376, 12377, 12357, -1, 12375, 12371, 12361, -1, 12376, 12363, 12372, -1, 12376, 12357, 12370, -1, 12378, 12373, 12379, -1, 12380, 12368, 12369, -1, 12381, 12369, 12382, -1, 12381, 12380, 12369, -1, 12378, 12372, 12373, -1, 12383, 12372, 12378, -1, 12383, 12384, 12377, -1, 12385, 12374, 12375, -1, 12385, 12375, 12368, -1, 12383, 12377, 12376, -1, 12385, 12368, 12380, -1, 12383, 12376, 12372, -1, 12385, 12386, 12374, -1, 12387, 12380, 12381, -1, 12388, 12379, 12389, -1, 12387, 12385, 12380, -1, 12388, 12378, 12379, -1, 12387, 12386, 12385, -1, 12390, 12383, 12378, -1, 12390, 12384, 12383, -1, 12391, 12381, 12382, -1, 12390, 12392, 12384, -1, 12390, 12378, 12388, -1, 12393, 12382, 12394, -1, 12393, 12391, 12382, -1, 12395, 12389, 12396, -1, 12395, 12388, 12389, -1, 12397, 12387, 12381, -1, 12397, 12386, 12387, -1, 12397, 12381, 12391, -1, 12398, 12392, 12390, -1, 12398, 12390, 12388, -1, 12398, 12399, 12392, -1, 12397, 12400, 12386, -1, 12398, 12388, 12395, -1, 12401, 12391, 12393, -1, 12401, 12397, 12391, -1, 12402, 12396, 12403, -1, 12401, 12400, 12397, -1, 12404, 12393, 12394, -1, 12402, 12395, 12396, -1, 12405, 12399, 12398, -1, 12405, 12406, 12399, -1, 12407, 12394, 12408, -1, 12405, 12398, 12395, -1, 12407, 12404, 12394, -1, 12405, 12395, 12402, -1, 12409, 12401, 12393, -1, 12410, 12403, 12411, -1, 12409, 12400, 12401, -1, 12409, 12393, 12404, -1, 12410, 12402, 12403, -1, 12409, 12412, 12400, -1, 12413, 12404, 12407, -1, 12414, 12410, 12411, -1, 12413, 12409, 12404, -1, 12413, 12412, 12409, -1, 12415, 12402, 12410, -1, 12415, 12416, 12406, -1, 12417, 12407, 12408, -1, 12415, 12405, 12402, -1, 12415, 12406, 12405, -1, 12418, 12408, 12419, -1, 12420, 12421, 12416, -1, 12420, 12415, 12410, -1, 12418, 12417, 12408, -1, 12420, 12416, 12415, -1, 12420, 12410, 12414, -1, 12422, 12407, 12417, -1, 12422, 12423, 12412, -1, 12424, 12411, 12425, -1, 12422, 12413, 12407, -1, 12422, 12412, 12413, -1, 12424, 12414, 12411, -1, 12426, 12423, 12422, -1, 12426, 12422, 12417, -1, 12427, 12424, 12425, -1, 12426, 12417, 12418, -1, 12428, 12414, 12424, -1, 12429, 12418, 12419, -1, 12428, 12421, 12420, -1, 12428, 12420, 12414, -1, 12430, 12418, 12429, -1, 12431, 12432, 12421, -1, 12431, 12424, 12427, -1, 12431, 12421, 12428, -1, 12430, 12433, 12423, -1, 12431, 12428, 12424, -1, 12430, 12426, 12418, -1, 12430, 12423, 12426, -1, 12434, 12425, 12435, -1, 12436, 12419, 12437, -1, 12434, 12427, 12425, -1, 12436, 12429, 12419, -1, 12328, 12434, 12435, -1, 12438, 12439, 12433, -1, 12440, 12432, 12431, -1, 12440, 12431, 12427, -1, 12438, 12430, 12429, -1, 12440, 12427, 12434, -1, 12438, 12433, 12430, -1, 12438, 12429, 12436, -1, 12327, 12338, 12432, -1, 12330, 12437, 12331, -1, 12327, 12432, 12440, -1, 12327, 12434, 12328, -1, 12327, 12440, 12434, -1, 12330, 12436, 12437, -1, 12332, 12435, 12342, -1, 12340, 12439, 12438, -1, 12340, 12335, 12439, -1, 12332, 12328, 12435, -1, 12340, 12438, 12436, -1, 12340, 12436, 12330, -1, 12339, 12332, 12342, -1, 12329, 12331, 12347, -1, 12326, 12338, 12327, -1, 12441, 12442, 12443, -1, 12443, 12444, 12445, -1, 12442, 12444, 12443, -1, 12445, 12446, 12447, -1, 12444, 12446, 12445, -1, 12447, 12448, 12449, -1, 12446, 12448, 12447, -1, 12449, 12450, 12451, -1, 12448, 12450, 12449, -1, 12450, 12452, 12451, -1, 12451, 12453, 12454, -1, 12452, 12453, 12451, -1, 12454, 12455, 12456, -1, 12453, 12455, 12454, -1, 12457, 12458, 12459, -1, 12457, 12460, 12458, -1, 12461, 12459, 12462, -1, 12461, 12457, 12459, -1, 12463, 12462, 12464, -1, 12463, 12461, 12462, -1, 12465, 12466, 12467, -1, 12468, 12469, 12389, -1, 12470, 12466, 12465, -1, 12470, 12471, 12466, -1, 12472, 12469, 12468, -1, 12472, 12465, 12469, -1, 12473, 12471, 12470, -1, 12473, 12474, 12475, -1, 12473, 12475, 12471, -1, 12476, 12468, 12389, -1, 12476, 12389, 12379, -1, 12477, 12470, 12465, -1, 12477, 12465, 12472, -1, 12478, 12472, 12468, -1, 12478, 12468, 12476, -1, 12479, 12473, 12470, -1, 12479, 12470, 12477, -1, 12479, 12474, 12473, -1, 12480, 12476, 12379, -1, 12481, 12477, 12472, -1, 12481, 12472, 12478, -1, 12482, 12483, 12484, -1, 12482, 12484, 12485, -1, 12482, 12485, 12486, -1, 12482, 12486, 12487, -1, 12482, 12487, 12488, -1, 12482, 12488, 12489, -1, 12482, 12489, 12490, -1, 12482, 12490, 12491, -1, 12482, 12491, 12492, -1, 12482, 12492, 12493, -1, 12482, 12493, 12494, -1, 12482, 12494, 12495, -1, 12482, 12495, 12474, -1, 12482, 12474, 12479, -1, 12496, 12478, 12476, -1, 12496, 12476, 12480, -1, 12497, 12483, 12482, -1, 12497, 12479, 12477, -1, 12497, 12498, 12483, -1, 12497, 12482, 12479, -1, 12497, 12477, 12481, -1, 12499, 12480, 12379, -1, 12500, 12481, 12478, -1, 12500, 12478, 12496, -1, 12501, 12496, 12480, -1, 12501, 12480, 12499, -1, 12502, 12481, 12500, -1, 12502, 12503, 12498, -1, 12502, 12500, 12503, -1, 12502, 12498, 12497, -1, 12502, 12497, 12481, -1, 12504, 12379, 12373, -1, 12504, 12499, 12379, -1, 12505, 12506, 12503, -1, 12505, 12503, 12500, -1, 12505, 12500, 12496, -1, 12505, 12496, 12501, -1, 12507, 12501, 12499, -1, 12507, 12499, 12504, -1, 12508, 12504, 12373, -1, 12509, 12510, 12506, -1, 12509, 12506, 12505, -1, 12509, 12501, 12507, -1, 12509, 12505, 12501, -1, 12511, 12510, 12509, -1, 12511, 12507, 12504, -1, 12511, 12509, 12507, -1, 12511, 12504, 12508, -1, 12512, 12508, 12373, -1, 12513, 12514, 12510, -1, 12513, 12510, 12511, -1, 12513, 12511, 12508, -1, 12513, 12508, 12512, -1, 12513, 12512, 12514, -1, 12515, 12373, 12365, -1, 12515, 12512, 12373, -1, 12515, 12514, 12512, -1, 12516, 12517, 12514, -1, 12516, 12514, 12515, -1, 12518, 12517, 12516, -1, 12518, 12516, 12515, -1, 12518, 12515, 12365, -1, 12519, 12520, 12517, -1, 12519, 12517, 12518, -1, 12519, 12518, 12365, -1, 12521, 12365, 12364, -1, 12521, 12519, 12365, -1, 12521, 12520, 12519, -1, 12522, 12520, 12521, -1, 12522, 12364, 12523, -1, 12524, 12525, 12394, -1, 12522, 12523, 12526, -1, 12522, 12526, 12527, -1, 12522, 12527, 12520, -1, 12522, 12521, 12364, -1, 12382, 12524, 12394, -1, 12528, 12524, 12382, -1, 12369, 12528, 12382, -1, 12529, 12528, 12369, -1, 12530, 12529, 12369, -1, 12360, 12530, 12369, -1, 12531, 12530, 12360, -1, 12532, 12531, 12360, -1, 12343, 12532, 12360, -1, 12533, 12532, 12343, -1, 12534, 12533, 12343, -1, 12342, 12534, 12343, -1, 12535, 12534, 12342, -1, 12435, 12535, 12342, -1, 12435, 12536, 12535, -1, 12537, 12536, 12435, -1, 12425, 12537, 12435, -1, 12538, 12537, 12425, -1, 12539, 12538, 12425, -1, 12411, 12539, 12425, -1, 12540, 12539, 12411, -1, 12541, 12542, 12543, -1, 12541, 12544, 12542, -1, 12541, 12545, 12544, -1, 12541, 12543, 12346, -1, 12546, 12346, 12345, -1, 12546, 12541, 12346, -1, 12546, 12545, 12541, -1, 12546, 12547, 12545, -1, 12548, 12546, 12345, -1, 12548, 12547, 12546, -1, 12548, 12549, 12547, -1, 12550, 12548, 12345, -1, 12550, 12549, 12548, -1, 12551, 12345, 12347, -1, 12551, 12550, 12345, -1, 12551, 12549, 12550, -1, 12552, 12553, 12549, -1, 12552, 12551, 12553, -1, 12552, 12549, 12551, -1, 12554, 12551, 12347, -1, 12554, 12553, 12551, -1, 12555, 12553, 12554, -1, 12555, 12556, 12553, -1, 12557, 12554, 12347, -1, 12558, 12554, 12557, -1, 12558, 12556, 12555, -1, 12558, 12555, 12554, -1, 12558, 12559, 12556, -1, 12560, 12347, 12331, -1, 12560, 12557, 12347, -1, 12561, 12557, 12560, -1, 12561, 12559, 12558, -1, 12561, 12558, 12557, -1, 12562, 12560, 12331, -1, 12563, 12559, 12561, -1, 12563, 12564, 12565, -1, 12563, 12565, 12559, -1, 12566, 12560, 12562, -1, 12566, 12561, 12560, -1, 12567, 12562, 12331, -1, 12568, 12561, 12566, -1, 12568, 12564, 12563, -1, 12568, 12563, 12561, -1, 12569, 12562, 12567, -1, 12569, 12566, 12562, -1, 12570, 12331, 12437, -1, 12570, 12567, 12331, -1, 12571, 12566, 12569, -1, 12571, 12568, 12566, -1, 12572, 12569, 12567, -1, 12572, 12567, 12570, -1, 12573, 12564, 12568, -1, 12573, 12568, 12571, -1, 12573, 12574, 12564, -1, 12575, 12570, 12437, -1, 12576, 12571, 12569, -1, 12576, 12569, 12572, -1, 12577, 12572, 12570, -1, 12577, 12570, 12575, -1, 12578, 12573, 12571, -1, 12578, 12574, 12573, -1, 12578, 12571, 12576, -1, 12578, 12579, 12574, -1, 12580, 12575, 12437, -1, 12581, 12572, 12577, -1, 12581, 12576, 12572, -1, 12582, 12577, 12575, -1, 12582, 12575, 12580, -1, 12583, 12576, 12581, -1, 12583, 12578, 12576, -1, 12584, 12580, 12437, -1, 12585, 12577, 12582, -1, 12585, 12581, 12577, -1, 12586, 12579, 12578, -1, 12586, 12578, 12583, -1, 12586, 12583, 12587, -1, 12586, 12587, 12588, -1, 12586, 12588, 12589, -1, 12586, 12589, 12590, -1, 12586, 12590, 12591, -1, 12586, 12591, 12592, -1, 12586, 12592, 12593, -1, 12586, 12593, 12594, -1, 12586, 12594, 12595, -1, 12586, 12595, 12596, -1, 12586, 12596, 12597, -1, 12586, 12597, 12598, -1, 12586, 12598, 12599, -1, 12586, 12599, 12579, -1, 12600, 12582, 12580, -1, 12600, 12580, 12584, -1, 12601, 12583, 12581, -1, 12601, 12581, 12585, -1, 12601, 12587, 12583, -1, 12601, 12602, 12587, -1, 12603, 12437, 12419, -1, 12603, 12584, 12437, -1, 12604, 12582, 12600, -1, 12604, 12585, 12582, -1, 12605, 12584, 12603, -1, 12605, 12600, 12584, -1, 12606, 12602, 12601, -1, 12606, 12601, 12585, -1, 12606, 12604, 12607, -1, 12606, 12585, 12604, -1, 12606, 12607, 12602, -1, 12608, 12603, 12419, -1, 12609, 12607, 12604, -1, 12609, 12605, 12610, -1, 12609, 12604, 12600, -1, 12609, 12610, 12607, -1, 12609, 12600, 12605, -1, 12611, 12610, 12605, -1, 12611, 12605, 12603, -1, 12611, 12612, 12610, -1, 12611, 12603, 12608, -1, 12613, 12608, 12419, -1, 12614, 12608, 12613, -1, 12614, 12611, 12608, -1, 12614, 12612, 12611, -1, 12614, 12615, 12612, -1, 12616, 12419, 12408, -1, 12616, 12613, 12419, -1, 12617, 12615, 12614, -1, 12617, 12613, 12616, -1, 12617, 12618, 12615, -1, 12617, 12614, 12613, -1, 12619, 12616, 12408, -1, 12620, 12616, 12619, -1, 12620, 12617, 12616, -1, 12620, 12618, 12617, -1, 12620, 12621, 12618, -1, 12622, 12620, 12619, -1, 12622, 12621, 12620, -1, 12622, 12619, 12408, -1, 12623, 12408, 12394, -1, 12623, 12621, 12622, -1, 12623, 12525, 12621, -1, 12623, 12622, 12408, -1, 12624, 12525, 12623, -1, 12624, 12623, 12394, -1, 12624, 12394, 12525, -1, 12625, 12540, 12411, -1, 12626, 12411, 12403, -1, 12626, 12625, 12411, -1, 12626, 12540, 12625, -1, 12626, 12627, 12540, -1, 12628, 12626, 12403, -1, 12628, 12627, 12626, -1, 12629, 12628, 12403, -1, 12630, 12631, 12627, -1, 12630, 12627, 12628, -1, 12630, 12628, 12629, -1, 12630, 12629, 12631, -1, 12632, 12403, 12396, -1, 12632, 12629, 12403, -1, 12632, 12631, 12629, -1, 12633, 12634, 12631, -1, 12633, 12631, 12632, -1, 12635, 12632, 12396, -1, 12636, 12637, 12634, -1, 12636, 12632, 12635, -1, 12636, 12634, 12633, -1, 12636, 12633, 12632, -1, 12638, 12635, 12396, -1, 12639, 12635, 12638, -1, 12639, 12640, 12637, -1, 12639, 12637, 12636, -1, 12639, 12636, 12635, -1, 12641, 12396, 12389, -1, 12641, 12638, 12396, -1, 12642, 12638, 12641, -1, 12642, 12639, 12638, -1, 12642, 12640, 12639, -1, 12467, 12641, 12389, -1, 12643, 12644, 12640, -1, 12643, 12640, 12642, -1, 12466, 12642, 12641, -1, 12466, 12641, 12467, -1, 12469, 12467, 12389, -1, 12471, 12475, 12644, -1, 12471, 12644, 12643, -1, 12471, 12643, 12642, -1, 12471, 12642, 12466, -1, 12465, 12467, 12469, -1, 12645, 12646, 12647, -1, 12647, 12646, 12648, -1, 12648, 12649, 12650, -1, 12646, 12649, 12648, -1, 12650, 12651, 12652, -1, 12649, 12651, 12650, -1, 12652, 12653, 12654, -1, 12651, 12653, 12652, -1, 12654, 12655, 12656, -1, 12653, 12655, 12654, -1, 12656, 12657, 12658, -1, 12655, 12657, 12656, -1, 12657, 12659, 12658, -1, 12658, 12660, 12661, -1, 12659, 12660, 12658, -1, 12660, 12662, 12661, -1, 12663, 12664, 12665, -1, 12665, 12666, 12667, -1, 12664, 12666, 12665, -1, 12667, 12668, 12669, -1, 12666, 12668, 12667, -1, 12669, 12670, 12671, -1, 12668, 12670, 12669, -1, 12671, 12672, 12673, -1, 12670, 12672, 12671, -1, 12672, 12674, 12673, -1, 12675, 12676, 12677, -1, 12673, 12676, 12675, -1, 12674, 12676, 12673, -1, 12677, 12678, 12679, -1, 12676, 12678, 12677, -1, 12679, 12680, 12681, -1, 12678, 12680, 12679, -1, 12680, 12682, 12681, -1, 12681, 12683, 12684, -1, 12682, 12683, 12681, -1, 12684, 12685, 12686, -1, 12683, 12685, 12684, -1, 12685, 12687, 12686, -1, 12688, 12689, 12690, -1, 12690, 12691, 12692, -1, 12689, 12691, 12690, -1, 12692, 12693, 12694, -1, 12691, 12693, 12692, -1, 12693, 12695, 12694, -1, 12696, 12697, 12698, -1, 12696, 12699, 12697, -1, 12696, 12253, 12699, -1, 12696, 12250, 12253, -1, 12700, 12701, 12702, -1, 12700, 12703, 12701, -1, 12704, 12703, 12700, -1, 12704, 12705, 12703, -1, 12706, 12707, 12705, -1, 12706, 12705, 12704, -1, 12708, 12698, 12707, -1, 12708, 12707, 12706, -1, 12709, 12696, 12698, -1, 12709, 12250, 12696, -1, 12709, 12698, 12708, -1, 12709, 12247, 12250, -1, 12710, 12702, 12711, -1, 12311, 12315, 12712, -1, 12710, 12700, 12702, -1, 12713, 12704, 12700, -1, 12713, 12700, 12710, -1, 12714, 12706, 12704, -1, 12714, 12704, 12713, -1, 12715, 12708, 12706, -1, 12715, 12706, 12714, -1, 12716, 12708, 12715, -1, 12716, 12709, 12708, -1, 12716, 12247, 12709, -1, 12716, 12248, 12247, -1, 12717, 12711, 12718, -1, 12717, 12710, 12711, -1, 12719, 12713, 12710, -1, 12719, 12710, 12717, -1, 12720, 12714, 12713, -1, 12720, 12713, 12719, -1, 12721, 12715, 12714, -1, 12721, 12714, 12720, -1, 12722, 12716, 12715, -1, 12722, 12248, 12716, -1, 12722, 12715, 12721, -1, 12722, 12324, 12248, -1, 12723, 12718, 12724, -1, 12723, 12717, 12718, -1, 12725, 12719, 12717, -1, 12725, 12717, 12723, -1, 12726, 12720, 12719, -1, 12726, 12719, 12725, -1, 12727, 12721, 12720, -1, 12727, 12720, 12726, -1, 12728, 12322, 12324, -1, 12728, 12721, 12727, -1, 12728, 12722, 12721, -1, 12728, 12324, 12722, -1, 12729, 12724, 12730, -1, 12729, 12723, 12724, -1, 12731, 12725, 12723, -1, 12731, 12723, 12729, -1, 12732, 12726, 12725, -1, 12732, 12725, 12731, -1, 12733, 12727, 12726, -1, 12733, 12726, 12732, -1, 12734, 12320, 12322, -1, 12734, 12322, 12728, -1, 12734, 12728, 12727, -1, 12734, 12727, 12733, -1, 12735, 12730, 12736, -1, 12735, 12729, 12730, -1, 12737, 12729, 12735, -1, 12737, 12731, 12729, -1, 12738, 12731, 12737, -1, 12738, 12732, 12731, -1, 12739, 12732, 12738, -1, 12739, 12733, 12732, -1, 12740, 12734, 12733, -1, 12740, 12733, 12739, -1, 12740, 12318, 12320, -1, 12740, 12320, 12734, -1, 12741, 12736, 12742, -1, 12741, 12735, 12736, -1, 12743, 12735, 12741, -1, 12743, 12737, 12735, -1, 12744, 12737, 12743, -1, 12744, 12738, 12737, -1, 12745, 12738, 12744, -1, 12745, 12739, 12738, -1, 12746, 12318, 12740, -1, 12746, 12739, 12745, -1, 12746, 12316, 12318, -1, 12746, 12740, 12739, -1, 12747, 12741, 12742, -1, 12747, 12742, 12748, -1, 12749, 12741, 12747, -1, 12749, 12743, 12741, -1, 12750, 12744, 12743, -1, 12750, 12743, 12749, -1, 12751, 12745, 12744, -1, 12751, 12744, 12750, -1, 12752, 12746, 12745, -1, 12752, 12316, 12746, -1, 12752, 12745, 12751, -1, 12752, 12313, 12316, -1, 12753, 12748, 12754, -1, 12753, 12747, 12748, -1, 12755, 12749, 12747, -1, 12755, 12747, 12753, -1, 12756, 12750, 12749, -1, 12756, 12749, 12755, -1, 12757, 12751, 12750, -1, 12757, 12750, 12756, -1, 12758, 12752, 12751, -1, 12758, 12313, 12752, -1, 12758, 12751, 12757, -1, 12758, 12309, 12313, -1, 12759, 12753, 12754, -1, 12759, 12754, 12760, -1, 12761, 12755, 12753, -1, 12761, 12753, 12759, -1, 12762, 12755, 12761, -1, 12762, 12756, 12755, -1, 12763, 12757, 12756, -1, 12763, 12756, 12762, -1, 12764, 12304, 12309, -1, 12764, 12757, 12763, -1, 12764, 12758, 12757, -1, 12764, 12309, 12758, -1, 12765, 12759, 12760, -1, 12765, 12760, 12766, -1, 12767, 12761, 12759, -1, 12767, 12759, 12765, -1, 12768, 12761, 12767, -1, 12768, 12762, 12761, -1, 12769, 12763, 12762, -1, 12769, 12762, 12768, -1, 12770, 12300, 12304, -1, 12770, 12304, 12764, -1, 12770, 12764, 12763, -1, 12770, 12763, 12769, -1, 12771, 12766, 12772, -1, 12771, 12765, 12766, -1, 12773, 12774, 12775, -1, 12776, 12765, 12771, -1, 12776, 12767, 12765, -1, 12777, 12768, 12767, -1, 12777, 12767, 12776, -1, 12778, 12768, 12777, -1, 12778, 12769, 12768, -1, 12258, 12255, 12779, -1, 12780, 12769, 12778, -1, 12780, 12300, 12770, -1, 12780, 12296, 12300, -1, 12781, 12782, 12783, -1, 12780, 12770, 12769, -1, 12781, 12784, 12782, -1, 12785, 12772, 12786, -1, 12785, 12771, 12772, -1, 12787, 12784, 12781, -1, 12787, 12788, 12784, -1, 12789, 12771, 12785, -1, 12789, 12776, 12771, -1, 12790, 12791, 12788, -1, 12792, 12777, 12776, -1, 12792, 12776, 12789, -1, 12790, 12788, 12787, -1, 12793, 12791, 12790, -1, 12793, 12794, 12791, -1, 12795, 12311, 12712, -1, 12796, 12777, 12792, -1, 12795, 12794, 12793, -1, 12796, 12778, 12777, -1, 12795, 12712, 12794, -1, 12797, 12780, 12778, -1, 12797, 12296, 12780, -1, 12797, 12778, 12796, -1, 12798, 12783, 12799, -1, 12798, 12781, 12783, -1, 12797, 12292, 12296, -1, 12800, 12786, 12801, -1, 12802, 12781, 12798, -1, 12802, 12787, 12781, -1, 12800, 12785, 12786, -1, 12803, 12785, 12800, -1, 12803, 12789, 12785, -1, 12804, 12787, 12802, -1, 12804, 12790, 12787, -1, 12805, 12792, 12789, -1, 12806, 12790, 12804, -1, 12805, 12789, 12803, -1, 12806, 12793, 12790, -1, 12807, 12796, 12792, -1, 12808, 12795, 12793, -1, 12808, 12311, 12795, -1, 12807, 12792, 12805, -1, 12808, 12307, 12311, -1, 12808, 12793, 12806, -1, 12809, 12797, 12796, -1, 12809, 12292, 12797, -1, 12809, 12796, 12807, -1, 12810, 12799, 12811, -1, 12809, 12288, 12292, -1, 12810, 12798, 12799, -1, 12812, 12801, 12813, -1, 12812, 12800, 12801, -1, 12814, 12798, 12810, -1, 12814, 12802, 12798, -1, 12815, 12803, 12800, -1, 12816, 12804, 12802, -1, 12815, 12800, 12812, -1, 12816, 12802, 12814, -1, 12817, 12805, 12803, -1, 12817, 12803, 12815, -1, 12818, 12804, 12816, -1, 12818, 12806, 12804, -1, 12819, 12807, 12805, -1, 12820, 12808, 12806, -1, 12820, 12307, 12808, -1, 12819, 12805, 12817, -1, 12820, 12303, 12307, -1, 12820, 12806, 12818, -1, 12821, 12807, 12819, -1, 12821, 12809, 12807, -1, 12821, 12288, 12809, -1, 12822, 12810, 12811, -1, 12822, 12811, 12823, -1, 12821, 12284, 12288, -1, 12824, 12813, 12825, -1, 12824, 12812, 12813, -1, 12826, 12810, 12822, -1, 12827, 12812, 12824, -1, 12826, 12814, 12810, -1, 12827, 12815, 12812, -1, 12828, 12816, 12814, -1, 12828, 12814, 12826, -1, 12829, 12815, 12827, -1, 12829, 12817, 12815, -1, 12830, 12816, 12828, -1, 12830, 12818, 12816, -1, 12831, 12303, 12820, -1, 12831, 12820, 12818, -1, 12832, 12819, 12817, -1, 12831, 12818, 12830, -1, 12832, 12817, 12829, -1, 12831, 12299, 12303, -1, 12833, 12821, 12819, -1, 12833, 12284, 12821, -1, 12833, 12279, 12284, -1, 12834, 12823, 12835, -1, 12833, 12819, 12832, -1, 12836, 12825, 12837, -1, 12834, 12822, 12823, -1, 12836, 12824, 12825, -1, 12838, 12826, 12822, -1, 12839, 12824, 12836, -1, 12838, 12822, 12834, -1, 12839, 12827, 12824, -1, 12840, 12828, 12826, -1, 12840, 12826, 12838, -1, 12841, 12828, 12840, -1, 12842, 12829, 12827, -1, 12841, 12830, 12828, -1, 12842, 12827, 12839, -1, 12843, 12832, 12829, -1, 12844, 12299, 12831, -1, 12844, 12831, 12830, -1, 12844, 12830, 12841, -1, 12843, 12829, 12842, -1, 12844, 12295, 12299, -1, 12845, 12275, 12279, -1, 12845, 12279, 12833, -1, 12845, 12833, 12832, -1, 12846, 12835, 12847, -1, 12845, 12832, 12843, -1, 12846, 12834, 12835, -1, 12848, 12837, 12849, -1, 12850, 12834, 12846, -1, 12848, 12836, 12837, -1, 12850, 12838, 12834, -1, 12851, 12839, 12836, -1, 12852, 12840, 12838, -1, 12851, 12836, 12848, -1, 12852, 12838, 12850, -1, 12853, 12840, 12852, -1, 12854, 12842, 12839, -1, 12853, 12841, 12840, -1, 12854, 12839, 12851, -1, 12855, 12844, 12841, -1, 12855, 12295, 12844, -1, 12856, 12843, 12842, -1, 12855, 12841, 12853, -1, 12856, 12842, 12854, -1, 12855, 12291, 12295, -1, 12857, 12846, 12847, -1, 12858, 12270, 12275, -1, 12857, 12847, 12859, -1, 12858, 12275, 12845, -1, 12858, 12845, 12843, -1, 12858, 12843, 12856, -1, 12860, 12849, 12861, -1, 12860, 12848, 12849, -1, 12862, 12846, 12857, -1, 12862, 12850, 12846, -1, 12863, 12848, 12860, -1, 12864, 12850, 12862, -1, 12863, 12851, 12848, -1, 12864, 12852, 12850, -1, 12865, 12851, 12863, -1, 12866, 12852, 12864, -1, 12866, 12853, 12852, -1, 12865, 12854, 12851, -1, 12867, 12855, 12853, -1, 12868, 12854, 12865, -1, 12867, 12853, 12866, -1, 12867, 12287, 12291, -1, 12868, 12856, 12854, -1, 12867, 12291, 12855, -1, 12869, 12857, 12859, -1, 12870, 12856, 12868, -1, 12870, 12265, 12270, -1, 12869, 12859, 12871, -1, 12870, 12858, 12856, -1, 12870, 12270, 12858, -1, 12872, 12861, 12873, -1, 12874, 12862, 12857, -1, 12872, 12860, 12861, -1, 12874, 12857, 12869, -1, 12875, 12860, 12872, -1, 12876, 12864, 12862, -1, 12875, 12863, 12860, -1, 12876, 12862, 12874, -1, 12877, 12863, 12875, -1, 12878, 12864, 12876, -1, 12878, 12866, 12864, -1, 12877, 12865, 12863, -1, 12879, 12867, 12866, -1, 12879, 12283, 12287, -1, 12880, 12865, 12877, -1, 12879, 12287, 12867, -1, 12879, 12866, 12878, -1, 12880, 12868, 12865, -1, 12881, 12870, 12868, -1, 12881, 12265, 12870, -1, 12882, 12871, 12883, -1, 12881, 12868, 12880, -1, 12882, 12869, 12871, -1, 12881, 12261, 12265, -1, 12884, 12873, 12774, -1, 12884, 12872, 12873, -1, 12885, 12869, 12882, -1, 12884, 12773, 12886, -1, 12884, 12774, 12773, -1, 12885, 12874, 12869, -1, 12887, 12875, 12872, -1, 12887, 12884, 12886, -1, 12888, 12876, 12874, -1, 12887, 12886, 12889, -1, 12888, 12874, 12885, -1, 12887, 12872, 12884, -1, 12890, 12876, 12888, -1, 12891, 12875, 12887, -1, 12890, 12878, 12876, -1, 12891, 12887, 12889, -1, 12891, 12889, 12892, -1, 12893, 12878, 12890, -1, 12891, 12877, 12875, -1, 12894, 12877, 12891, -1, 12893, 12280, 12283, -1, 12894, 12880, 12877, -1, 12893, 12283, 12879, -1, 12893, 12879, 12878, -1, 12894, 12891, 12892, -1, 12894, 12892, 12779, -1, 12895, 12883, 12896, -1, 12897, 12880, 12894, -1, 12897, 12881, 12880, -1, 12897, 12261, 12881, -1, 12895, 12882, 12883, -1, 12897, 12894, 12779, -1, 12897, 12255, 12261, -1, 12897, 12779, 12255, -1, 12898, 12882, 12895, -1, 12898, 12885, 12882, -1, 12899, 12888, 12885, -1, 12899, 12885, 12898, -1, 12900, 12888, 12899, -1, 12900, 12890, 12888, -1, 12901, 12893, 12890, -1, 12901, 12280, 12893, -1, 12901, 12890, 12900, -1, 12901, 12277, 12280, -1, 12902, 12896, 12903, -1, 12902, 12895, 12896, -1, 12904, 12895, 12902, -1, 12904, 12898, 12895, -1, 12905, 12899, 12898, -1, 12905, 12898, 12904, -1, 12906, 12900, 12899, -1, 12906, 12899, 12905, -1, 12907, 12901, 12900, -1, 12907, 12277, 12901, -1, 12907, 12900, 12906, -1, 12907, 12273, 12277, -1, 12908, 12903, 12909, -1, 12908, 12902, 12903, -1, 12910, 12904, 12902, -1, 12910, 12902, 12908, -1, 12911, 12905, 12904, -1, 12911, 12904, 12910, -1, 12912, 12906, 12905, -1, 12912, 12905, 12911, -1, 12913, 12906, 12912, -1, 12913, 12907, 12906, -1, 12913, 12273, 12907, -1, 12913, 12269, 12273, -1, 12914, 12909, 12915, -1, 12914, 12908, 12909, -1, 12916, 12910, 12908, -1, 12916, 12908, 12914, -1, 12917, 12911, 12910, -1, 12917, 12910, 12916, -1, 12918, 12912, 12911, -1, 12918, 12911, 12917, -1, 12919, 12913, 12912, -1, 12919, 12269, 12913, -1, 12919, 12912, 12918, -1, 12919, 12267, 12269, -1, 12920, 12915, 12921, -1, 12920, 12914, 12915, -1, 12922, 12916, 12914, -1, 12922, 12914, 12920, -1, 12923, 12917, 12916, -1, 12923, 12916, 12922, -1, 12924, 12918, 12917, -1, 12924, 12917, 12923, -1, 12925, 12919, 12918, -1, 12925, 12267, 12919, -1, 12925, 12263, 12267, -1, 12925, 12918, 12924, -1, 12926, 12921, 12927, -1, 12926, 12920, 12921, -1, 12928, 12920, 12926, -1, 12928, 12922, 12920, -1, 12929, 12923, 12922, -1, 12929, 12922, 12928, -1, 12930, 12923, 12929, -1, 12930, 12924, 12923, -1, 12931, 12259, 12263, -1, 12931, 12263, 12925, -1, 12931, 12925, 12924, -1, 12931, 12924, 12930, -1, 12932, 12927, 12933, -1, 12932, 12926, 12927, -1, 12934, 12928, 12926, -1, 12934, 12926, 12932, -1, 12935, 12928, 12934, -1, 12935, 12929, 12928, -1, 12697, 12929, 12935, -1, 12697, 12930, 12929, -1, 12699, 12930, 12697, -1, 12699, 12253, 12259, -1, 12699, 12259, 12931, -1, 12699, 12931, 12930, -1, 12703, 12933, 12701, -1, 12703, 12932, 12933, -1, 12705, 12934, 12932, -1, 12705, 12932, 12703, -1, 12707, 12934, 12705, -1, 12707, 12935, 12934, -1, 12698, 12935, 12707, -1, 12698, 12697, 12935, -1, 12936, 12937, 12938, -1, 12939, 12937, 12936, -1, 12939, 12940, 12937, -1, 12939, 12941, 12940, -1, 12939, 12942, 12941, -1, 12943, 12944, 12945, -1, 12943, 12946, 12944, -1, 12947, 12946, 12943, -1, 12947, 12936, 12946, -1, 12948, 12939, 12936, -1, 12948, 12942, 12939, -1, 12948, 12936, 12947, -1, 12948, 12949, 12942, -1, 12950, 12951, 12952, -1, 12953, 12945, 12954, -1, 12953, 12943, 12945, -1, 12955, 12943, 12953, -1, 12955, 12947, 12943, -1, 12956, 12948, 12947, -1, 12956, 12949, 12948, -1, 12956, 12947, 12955, -1, 12956, 12957, 12949, -1, 12958, 12954, 12959, -1, 12958, 12953, 12954, -1, 12960, 12953, 12958, -1, 12960, 12955, 12953, -1, 12961, 12956, 12955, -1, 12961, 12957, 12956, -1, 12961, 12955, 12960, -1, 12961, 12962, 12957, -1, 12963, 12959, 12964, -1, 12963, 12958, 12959, -1, 12965, 12958, 12963, -1, 12965, 12960, 12958, -1, 12966, 12961, 12960, -1, 12966, 12962, 12961, -1, 12966, 12960, 12965, -1, 12966, 12967, 12962, -1, 12968, 12964, 12969, -1, 12968, 12963, 12964, -1, 12970, 12963, 12968, -1, 12970, 12965, 12963, -1, 12971, 12966, 12965, -1, 12971, 12967, 12966, -1, 12971, 12965, 12970, -1, 12971, 12972, 12967, -1, 12973, 12969, 12974, -1, 12973, 12968, 12969, -1, 12975, 12968, 12973, -1, 12975, 12970, 12968, -1, 12976, 12971, 12970, -1, 12976, 12977, 12972, -1, 12976, 12972, 12971, -1, 12976, 12970, 12975, -1, 12978, 12974, 12979, -1, 12978, 12973, 12974, -1, 12980, 12973, 12978, -1, 12980, 12975, 12973, -1, 12981, 12982, 12977, -1, 12981, 12976, 12975, -1, 12981, 12977, 12976, -1, 12981, 12975, 12980, -1, 12983, 12984, 12985, -1, 12983, 12979, 12984, -1, 12983, 12985, 12986, -1, 12983, 12978, 12979, -1, 12987, 12986, 12988, -1, 12987, 12983, 12986, -1, 12987, 12978, 12983, -1, 12987, 12980, 12978, -1, 12989, 12980, 12987, -1, 12989, 12988, 12990, -1, 12989, 12990, 12991, -1, 12989, 12992, 12982, -1, 12989, 12991, 12992, -1, 12989, 12982, 12981, -1, 12989, 12981, 12980, -1, 12989, 12987, 12988, -1, 12993, 12994, 12995, -1, 12993, 12996, 12994, -1, 12997, 12996, 12993, -1, 12997, 12998, 12996, -1, 12999, 12952, 12998, -1, 12999, 12998, 12997, -1, 12999, 12950, 12952, -1, 13000, 12993, 12995, -1, 13000, 12995, 13001, -1, 13002, 12997, 12993, -1, 13002, 12993, 13000, -1, 13003, 12997, 13002, -1, 13003, 13004, 12950, -1, 13003, 12950, 12999, -1, 13003, 12999, 12997, -1, 13005, 13001, 13006, -1, 13005, 13000, 13001, -1, 13007, 13002, 13000, -1, 13007, 13000, 13005, -1, 13008, 13003, 13002, -1, 13008, 13002, 13007, -1, 13008, 13009, 13004, -1, 13008, 13004, 13003, -1, 13010, 13005, 13006, -1, 13010, 13006, 13011, -1, 13012, 13007, 13005, -1, 13012, 13005, 13010, -1, 13013, 13007, 13012, -1, 13013, 13014, 13009, -1, 13013, 13008, 13007, -1, 13013, 13009, 13008, -1, 13015, 13011, 13016, -1, 13015, 13010, 13011, -1, 13017, 13012, 13010, -1, 13017, 13010, 13015, -1, 13018, 13013, 13012, -1, 13018, 13014, 13013, -1, 13018, 13019, 13014, -1, 13018, 13012, 13017, -1, 13020, 13016, 13021, -1, 13020, 13015, 13016, -1, 13022, 13017, 13015, -1, 13022, 13015, 13020, -1, 13023, 13019, 13018, -1, 13023, 13018, 13017, -1, 13023, 13024, 13019, -1, 13023, 13017, 13022, -1, 13025, 13021, 13026, -1, 13025, 13020, 13021, -1, 13027, 13020, 13025, -1, 13027, 13022, 13020, -1, 13028, 13022, 13027, -1, 13028, 13029, 13024, -1, 13028, 13024, 13023, -1, 13028, 13023, 13022, -1, 13030, 13025, 13026, -1, 13030, 13026, 13031, -1, 13032, 13025, 13030, -1, 13032, 13027, 13025, -1, 13033, 13029, 13028, -1, 13033, 13027, 13032, -1, 13033, 13034, 13029, -1, 13033, 13028, 13027, -1, 13035, 13031, 13036, -1, 13035, 13030, 13031, -1, 13037, 13032, 13030, -1, 13037, 13030, 13035, -1, 13038, 13033, 13032, -1, 13038, 13034, 13033, -1, 13038, 13039, 13034, -1, 13038, 13032, 13037, -1, 13040, 13035, 13036, -1, 13040, 13036, 13041, -1, 13042, 13035, 13040, -1, 13042, 13037, 13035, -1, 13043, 13038, 13037, -1, 13043, 13037, 13042, -1, 13043, 13039, 13038, -1, 13043, 13044, 13039, -1, 13045, 13040, 13041, -1, 13045, 13041, 13046, -1, 13047, 13040, 13045, -1, 13047, 13042, 13040, -1, 13048, 13043, 13042, -1, 13048, 13042, 13047, -1, 13048, 13049, 13044, -1, 13048, 13044, 13043, -1, 13050, 13046, 13051, -1, 13050, 13045, 13046, -1, 13052, 13047, 13045, -1, 13052, 13045, 13050, -1, 13053, 13048, 13047, -1, 13053, 13054, 13049, -1, 13053, 13049, 13048, -1, 13053, 13047, 13052, -1, 13055, 13051, 13056, -1, 13055, 13050, 13051, -1, 13057, 13052, 13050, -1, 13057, 13050, 13055, -1, 13058, 13059, 13054, -1, 13058, 13054, 13053, -1, 13058, 13053, 13052, -1, 13058, 13052, 13057, -1, 13060, 13056, 13061, -1, 13060, 13055, 13056, -1, 13062, 13057, 13055, -1, 13062, 13055, 13060, -1, 13063, 13064, 13059, -1, 13063, 13059, 13058, -1, 13063, 13058, 13057, -1, 13063, 13057, 13062, -1, 13065, 13061, 13066, -1, 13065, 13060, 13061, -1, 13067, 13062, 13060, -1, 13067, 13060, 13065, -1, 13068, 13069, 13064, -1, 13068, 13064, 13063, -1, 13068, 13063, 13062, -1, 13068, 13062, 13067, -1, 13070, 13066, 13071, -1, 13070, 13065, 13066, -1, 13072, 13065, 13070, -1, 13072, 13067, 13065, -1, 13073, 13068, 13067, -1, 13073, 13067, 13072, -1, 13073, 13074, 13069, -1, 13073, 13069, 13068, -1, 13075, 13071, 13076, -1, 13075, 13070, 13071, -1, 13077, 13070, 13075, -1, 13077, 13072, 13070, -1, 13078, 13074, 13073, -1, 13078, 13072, 13077, -1, 13078, 13073, 13072, -1, 13078, 13079, 13074, -1, 13080, 13076, 13081, -1, 13080, 13075, 13076, -1, 13082, 13077, 13075, -1, 13082, 13075, 13080, -1, 13083, 13078, 13077, -1, 13083, 13079, 13078, -1, 13083, 13077, 13082, -1, 13083, 13084, 13079, -1, 13085, 13081, 13086, -1, 13085, 13080, 13081, -1, 13087, 13080, 13085, -1, 13087, 13082, 13080, -1, 13088, 13083, 13082, -1, 13088, 13084, 13083, -1, 13088, 13089, 13084, -1, 13088, 13082, 13087, -1, 13090, 13086, 13091, -1, 13090, 13085, 13086, -1, 13092, 13087, 13085, -1, 13092, 13085, 13090, -1, 13093, 13088, 13087, -1, 13093, 13089, 13088, -1, 13093, 13087, 13092, -1, 13093, 13094, 13089, -1, 13095, 13091, 13096, -1, 13095, 13090, 13091, -1, 13097, 13092, 13090, -1, 13097, 13090, 13095, -1, 13098, 13093, 13092, -1, 13098, 13094, 13093, -1, 13098, 13092, 13097, -1, 13098, 13099, 13094, -1, 13100, 13096, 13101, -1, 13100, 13095, 13096, -1, 13102, 13097, 13095, -1, 13102, 13095, 13100, -1, 13103, 13098, 13097, -1, 13103, 13099, 13098, -1, 13103, 13097, 13102, -1, 13103, 13104, 13099, -1, 13105, 13101, 13106, -1, 13105, 13100, 13101, -1, 13107, 13102, 13100, -1, 13107, 13100, 13105, -1, 13108, 13103, 13102, -1, 13108, 13104, 13103, -1, 13108, 13102, 13107, -1, 13108, 13109, 13104, -1, 13110, 13106, 13111, -1, 13110, 13105, 13106, -1, 13112, 13107, 13105, -1, 13112, 13105, 13110, -1, 13113, 13114, 13109, -1, 13113, 13108, 13107, -1, 13113, 13109, 13108, -1, 13113, 13107, 13112, -1, 13115, 13111, 13116, -1, 13115, 13110, 13111, -1, 13117, 13112, 13110, -1, 13117, 13110, 13115, -1, 13118, 13119, 13114, -1, 13118, 13114, 13113, -1, 13118, 13113, 13112, -1, 13118, 13112, 13117, -1, 13120, 13116, 13121, -1, 13120, 13115, 13116, -1, 13122, 13115, 13120, -1, 13122, 13117, 13115, -1, 13123, 13119, 13118, -1, 13123, 13124, 13119, -1, 13123, 13118, 13117, -1, 13123, 13117, 13122, -1, 13125, 13121, 13126, -1, 13125, 13120, 13121, -1, 13127, 13120, 13125, -1, 13127, 13122, 13120, -1, 13128, 13122, 13127, -1, 13128, 13129, 13124, -1, 13128, 13124, 13123, -1, 13128, 13123, 13122, -1, 13130, 13126, 13131, -1, 13130, 13125, 13126, -1, 13132, 13127, 13125, -1, 13132, 13125, 13130, -1, 13133, 13128, 13127, -1, 13133, 13127, 13132, -1, 13133, 13134, 13129, -1, 13133, 13129, 13128, -1, 12938, 13131, 13135, -1, 12938, 13130, 13131, -1, 12937, 13130, 12938, -1, 12937, 13132, 13130, -1, 12940, 13133, 13132, -1, 12940, 13134, 13133, -1, 12940, 13132, 12937, -1, 12940, 12941, 13134, -1, 12946, 12938, 13135, -1, 12946, 13135, 12944, -1, 12936, 12938, 12946, -1, 13136, 13137, 12321, -1, 13138, 12319, 12317, -1, 13138, 13136, 12319, -1, 13139, 12312, 12308, -1, 13140, 12317, 12314, -1, 13140, 13138, 12317, -1, 13141, 12308, 12306, -1, 13141, 13139, 12308, -1, 13142, 12314, 12310, -1, 13142, 13140, 12314, -1, 13143, 12306, 12301, -1, 13143, 13141, 12306, -1, 13144, 12310, 12305, -1, 13144, 13142, 12310, -1, 13145, 12301, 12297, -1, 13145, 13143, 12301, -1, 13146, 12305, 12302, -1, 13146, 13144, 12305, -1, 13147, 12297, 12294, -1, 13147, 13145, 12297, -1, 13148, 12302, 12298, -1, 13148, 13146, 12302, -1, 13149, 13147, 12294, -1, 13149, 12294, 12290, -1, 13150, 13148, 12298, -1, 13151, 12290, 12286, -1, 13151, 13149, 12290, -1, 13152, 12298, 12293, -1, 13152, 12293, 12289, -1, 13152, 13150, 12298, -1, 13153, 12286, 12282, -1, 13153, 13151, 12286, -1, 13154, 12289, 12285, -1, 13155, 12282, 12278, -1, 13155, 13153, 12282, -1, 13154, 13152, 12289, -1, 13156, 13154, 12285, -1, 13157, 13155, 12278, -1, 13158, 13156, 12285, -1, 13159, 12278, 12274, -1, 13158, 12285, 12281, -1, 13159, 12274, 12272, -1, 13158, 12281, 12276, -1, 13159, 13157, 12278, -1, 13160, 13158, 12276, -1, 13161, 12272, 12268, -1, 13160, 12276, 12271, -1, 13161, 13159, 12272, -1, 13162, 13160, 12271, -1, 13163, 12268, 12264, -1, 13162, 12271, 12266, -1, 13163, 13161, 12268, -1, 13164, 13162, 12266, -1, 13164, 12266, 12262, -1, 13165, 12264, 12260, -1, 13165, 13163, 12264, -1, 13166, 13164, 12262, -1, 13166, 12262, 12257, -1, 13167, 12260, 12254, -1, 13167, 13165, 12260, -1, 13168, 13166, 12257, -1, 13168, 12257, 12256, -1, 13169, 12254, 12252, -1, 13169, 13167, 12254, -1, 13170, 13168, 12256, -1, 13171, 12252, 12251, -1, 13171, 13169, 12252, -1, 13172, 12251, 12249, -1, 13172, 13171, 12251, -1, 13173, 12249, 12325, -1, 13173, 13172, 12249, -1, 13174, 12325, 12323, -1, 13174, 13173, 12325, -1, 13137, 12323, 12321, -1, 13137, 13174, 12323, -1, 13136, 12321, 12319, -1, 12724, 12718, 13081, -1, 12730, 13076, 13071, -1, 12730, 12724, 13076, -1, 12782, 12985, 12984, -1, 12736, 13071, 13066, -1, 12736, 12730, 13071, -1, 12783, 12984, 12979, -1, 12783, 12782, 12984, -1, 12742, 13066, 13061, -1, 12742, 12736, 13066, -1, 12799, 12979, 12974, -1, 12799, 12783, 12979, -1, 12748, 13061, 13056, -1, 12748, 12742, 13061, -1, 12811, 12974, 12969, -1, 12811, 12799, 12974, -1, 12754, 13056, 13051, -1, 12754, 12748, 13056, -1, 12823, 12811, 12969, -1, 12823, 12969, 12964, -1, 12760, 13051, 13046, -1, 12760, 12754, 13051, -1, 12835, 12823, 12964, -1, 12835, 12964, 12959, -1, 12766, 13046, 13041, -1, 12766, 12760, 13046, -1, 12847, 12835, 12959, -1, 12847, 12959, 12954, -1, 12772, 13041, 13036, -1, 12772, 12766, 13041, -1, 12859, 12954, 12945, -1, 12859, 12847, 12954, -1, 12786, 13036, 13031, -1, 12786, 12772, 13036, -1, 12871, 12945, 12944, -1, 12871, 12859, 12945, -1, 12801, 12786, 13031, -1, 12801, 13031, 13026, -1, 12883, 12944, 13135, -1, 12883, 12871, 12944, -1, 12813, 12801, 13026, -1, 12813, 13026, 13021, -1, 12896, 13135, 13131, -1, 12896, 12883, 13135, -1, 12825, 12813, 13021, -1, 12825, 13021, 13016, -1, 12903, 13131, 13126, -1, 12903, 12896, 13131, -1, 12837, 12825, 13016, -1, 12837, 13016, 13011, -1, 12909, 13126, 13121, -1, 12909, 12903, 13126, -1, 12849, 12837, 13011, -1, 12849, 13011, 13006, -1, 12915, 13121, 13116, -1, 12915, 12909, 13121, -1, 12861, 12849, 13006, -1, 12861, 13006, 13001, -1, 12921, 13116, 13111, -1, 12921, 12915, 13116, -1, 12873, 12861, 13001, -1, 12873, 13001, 12995, -1, 12927, 13111, 13106, -1, 12927, 12921, 13111, -1, 12774, 12873, 12995, -1, 12774, 12995, 12994, -1, 12775, 12774, 12994, -1, 12933, 13106, 13101, -1, 12933, 12927, 13106, -1, 12701, 13101, 13096, -1, 12701, 12933, 13101, -1, 12702, 13096, 13091, -1, 12702, 12701, 13096, -1, 12711, 13091, 13086, -1, 12711, 12702, 13091, -1, 12718, 13086, 13081, -1, 12718, 12711, 13086, -1, 12724, 13081, 13076, -1, 13175, 13176, 11419, -1, 13175, 12957, 13176, -1, 13175, 12949, 12957, -1, 13177, 12949, 13175, -1, 13177, 11411, 11404, -1, 13177, 12942, 12949, -1, 13177, 13175, 11411, -1, 13178, 11404, 11403, -1, 13178, 13177, 11404, -1, 13178, 12942, 13177, -1, 13178, 13134, 12941, -1, 13178, 12941, 12942, -1, 13179, 11403, 11399, -1, 13179, 11399, 11392, -1, 13179, 13134, 13178, -1, 13179, 13178, 11403, -1, 13179, 13129, 13134, -1, 13180, 13179, 11392, -1, 13180, 11392, 11391, -1, 13180, 13119, 13124, -1, 13180, 13124, 13129, -1, 13180, 13129, 13179, -1, 13181, 11391, 11384, -1, 13181, 13114, 13119, -1, 13181, 13119, 13180, -1, 13181, 13180, 11391, -1, 13182, 11384, 11383, -1, 13182, 11383, 11379, -1, 13182, 13114, 13181, -1, 13182, 13181, 11384, -1, 13182, 13104, 13109, -1, 13182, 13109, 13114, -1, 13183, 11379, 11372, -1, 13183, 13104, 13182, -1, 13183, 13182, 11379, -1, 13183, 13099, 13104, -1, 13184, 13183, 11372, -1, 13184, 11372, 11371, -1, 13184, 13089, 13094, -1, 13184, 13094, 13099, -1, 13184, 13099, 13183, -1, 13185, 11371, 11367, -1, 13185, 11367, 11363, -1, 13185, 13184, 11371, -1, 13185, 13089, 13184, -1, 13185, 13084, 13089, -1, 13186, 11363, 11359, -1, 13186, 13079, 13084, -1, 13186, 13084, 13185, -1, 13186, 13185, 11363, -1, 13187, 11359, 11352, -1, 13187, 11352, 11351, -1, 13187, 13069, 13074, -1, 13187, 13074, 13079, -1, 13187, 13186, 11359, -1, 13187, 13079, 13186, -1, 13188, 13069, 13187, -1, 13188, 13187, 11351, -1, 13188, 11351, 11347, -1, 13188, 13064, 13069, -1, 13189, 13188, 11347, -1, 13189, 13064, 13188, -1, 13189, 11347, 11343, -1, 13189, 13054, 13059, -1, 13189, 13059, 13064, -1, 13190, 13189, 11343, -1, 13190, 11343, 11336, -1, 13190, 11336, 11332, -1, 13190, 13054, 13189, -1, 13190, 13049, 13054, -1, 13191, 11332, 11328, -1, 13191, 13190, 11332, -1, 13191, 13039, 13044, -1, 13191, 13044, 13049, -1, 13191, 13049, 13190, -1, 13192, 11328, 11324, -1, 13192, 13191, 11328, -1, 13192, 13034, 13039, -1, 13192, 13039, 13191, -1, 13193, 11324, 11320, -1, 13193, 11320, 11316, -1, 13193, 13192, 11324, -1, 13193, 13024, 13029, -1, 13193, 13029, 13034, -1, 13193, 13034, 13192, -1, 13194, 11316, 11312, -1, 13194, 13019, 13024, -1, 13194, 13024, 13193, -1, 13194, 13193, 11316, -1, 13195, 11312, 11308, -1, 13195, 11308, 11304, -1, 13195, 13014, 13019, -1, 13195, 13194, 11312, -1, 13195, 13019, 13194, -1, 13196, 11304, 11296, -1, 13196, 13004, 13009, -1, 13196, 13009, 13014, -1, 13196, 13195, 11304, -1, 13196, 13014, 13195, -1, 13197, 13196, 11296, -1, 13197, 11296, 11295, -1, 13197, 12950, 13004, -1, 13197, 13004, 13196, -1, 13198, 11440, 11439, -1, 13198, 12991, 11440, -1, 13198, 11439, 13199, -1, 13200, 13198, 13199, -1, 13200, 12991, 13198, -1, 13200, 12992, 12991, -1, 13200, 13199, 12992, -1, 13201, 13197, 11295, -1, 13201, 11295, 11297, -1, 13202, 12950, 13197, -1, 13202, 13197, 13201, -1, 13202, 13201, 11297, -1, 13202, 11297, 12951, -1, 13202, 12951, 12950, -1, 13199, 11439, 11432, -1, 13199, 12982, 12992, -1, 13203, 11432, 11431, -1, 13203, 12972, 12977, -1, 13203, 12977, 12982, -1, 13203, 13199, 11432, -1, 13203, 12982, 13199, -1, 13204, 11431, 11424, -1, 13204, 11424, 11423, -1, 13204, 12972, 13203, -1, 13204, 13203, 11431, -1, 13204, 12967, 12972, -1, 13176, 11423, 11419, -1, 13176, 13204, 11423, -1, 13176, 12967, 13204, -1, 13176, 12957, 12962, -1, 13176, 12962, 12967, -1, 13175, 11419, 11412, -1, 13175, 11412, 11411, -1, 13205, 11314, 13206, -1, 13205, 13207, 13208, -1, 13205, 13206, 13207, -1, 13209, 13205, 13208, -1, 13209, 13208, 13210, -1, 13211, 13205, 13209, -1, 13212, 13209, 13210, -1, 13212, 13210, 13213, -1, 13212, 13213, 13214, -1, 13215, 13205, 13211, -1, 13216, 13217, 13218, -1, 13215, 11314, 13205, -1, 13215, 11310, 11314, -1, 13219, 13211, 13209, -1, 13220, 13221, 13222, -1, 13219, 13215, 13211, -1, 13219, 11310, 13215, -1, 13219, 13209, 13212, -1, 13223, 13216, 13218, -1, 13224, 13212, 13214, -1, 13224, 13214, 13225, -1, 13226, 13225, 13227, -1, 13228, 13212, 13224, -1, 13228, 13219, 13212, -1, 13229, 13224, 13225, -1, 13230, 13231, 13232, -1, 13229, 13225, 13226, -1, 13233, 11310, 13219, -1, 13233, 13219, 13228, -1, 13233, 11306, 11310, -1, 13234, 13226, 13227, -1, 13234, 13227, 13235, -1, 13236, 13224, 13229, -1, 13236, 11306, 13233, -1, 13236, 13233, 13228, -1, 13236, 13228, 13224, -1, 13237, 13229, 13226, -1, 13237, 13226, 13234, -1, 13238, 13234, 13235, -1, 13238, 13235, 13239, -1, 13238, 13240, 13241, -1, 13238, 13239, 13240, -1, 13238, 13241, 13242, -1, 13243, 13236, 13229, -1, 13243, 13229, 13237, -1, 13243, 13237, 13244, -1, 13245, 13244, 13237, -1, 13245, 13237, 13234, -1, 13245, 13234, 13238, -1, 13245, 13238, 13242, -1, 13245, 13242, 13246, -1, 13245, 13246, 13244, -1, 13247, 11306, 13236, -1, 13247, 13236, 13243, -1, 13247, 11300, 11306, -1, 13248, 13243, 13244, -1, 13248, 11300, 13247, -1, 13248, 13247, 13243, -1, 13248, 13244, 13249, -1, 13248, 13249, 13250, -1, 13248, 13250, 13251, -1, 13252, 13231, 13230, -1, 13252, 11292, 11291, -1, 13252, 13253, 13231, -1, 13252, 11291, 13253, -1, 13252, 13230, 13254, -1, 13252, 13255, 11292, -1, 13252, 13254, 13255, -1, 13256, 13257, 13258, -1, 13256, 11397, 11401, -1, 13256, 13258, 11397, -1, 13256, 13259, 13260, -1, 13256, 13260, 13257, -1, 13256, 13261, 13259, -1, 13256, 11401, 13261, -1, 13262, 13263, 13264, -1, 13262, 13264, 13265, -1, 13262, 11345, 13266, -1, 13262, 13267, 11341, -1, 13262, 13266, 13263, -1, 13262, 13265, 13267, -1, 13262, 11341, 11345, -1, 13268, 11300, 13248, -1, 13239, 13235, 13269, -1, 13268, 13248, 13251, -1, 13268, 13251, 13270, -1, 13268, 13270, 13271, -1, 13268, 13271, 13272, -1, 13268, 13272, 11301, -1, 13268, 11301, 11300, -1, 13273, 13241, 13240, -1, 13274, 13273, 13240, -1, 13271, 13270, 13275, -1, 13276, 13223, 13218, -1, 13276, 13221, 13220, -1, 13276, 13277, 13223, -1, 13276, 13218, 13221, -1, 13278, 13279, 13280, -1, 13278, 13280, 13277, -1, 13278, 13277, 13276, -1, 13281, 13220, 13282, -1, 13281, 13276, 13220, -1, 11417, 13283, 13284, -1, 13255, 13254, 13285, -1, 11417, 13284, 13286, -1, 13255, 13285, 13287, -1, 11417, 13286, 13288, -1, 13255, 13287, 13279, -1, 13289, 13276, 13281, -1, 13289, 13278, 13276, -1, 13289, 13279, 13278, -1, 13290, 13281, 13282, -1, 13291, 13255, 13279, -1, 13291, 13279, 13289, -1, 13292, 13289, 13281, -1, 13292, 13290, 13282, -1, 13292, 13281, 13290, -1, 13293, 11292, 13255, -1, 13293, 13255, 13291, -1, 13294, 13282, 13295, -1, 13296, 13289, 13292, -1, 13296, 13291, 13289, -1, 13297, 13292, 13282, -1, 13297, 13282, 13294, -1, 13297, 13294, 13295, -1, 13298, 11437, 11292, -1, 13298, 11292, 13293, -1, 13298, 13293, 13291, -1, 13298, 13291, 13296, -1, 13299, 13292, 13297, -1, 13299, 13296, 13292, -1, 13300, 13297, 13295, -1, 13300, 13295, 13301, -1, 13300, 13301, 13302, -1, 13303, 13298, 13296, -1, 13303, 11437, 13298, -1, 13303, 13296, 13299, -1, 13304, 13299, 13297, -1, 13304, 13297, 13300, -1, 13305, 13300, 13302, -1, 13306, 11434, 11437, -1, 13306, 13299, 13304, -1, 13306, 13303, 13299, -1, 13306, 11437, 13303, -1, 13307, 13300, 13305, -1, 13307, 13304, 13300, -1, 13308, 13305, 13302, -1, 13308, 13302, 13309, -1, 13310, 11434, 13306, -1, 13310, 13306, 13304, -1, 13310, 13304, 13307, -1, 13311, 13307, 13305, -1, 13311, 13305, 13308, -1, 13311, 13308, 13309, -1, 13312, 13310, 13307, -1, 13312, 11429, 11434, -1, 13312, 11434, 13310, -1, 13312, 13307, 13311, -1, 13313, 13311, 13309, -1, 13313, 13309, 13314, -1, 13315, 13312, 13311, -1, 13315, 13313, 13314, -1, 13315, 11429, 13312, -1, 13315, 13311, 13313, -1, 13316, 11426, 11429, -1, 13316, 13315, 13314, -1, 13316, 13314, 13317, -1, 13316, 11429, 13315, -1, 13316, 13317, 11426, -1, 13318, 13317, 13319, -1, 13318, 13319, 13320, -1, 13318, 11426, 13317, -1, 13321, 13318, 13320, -1, 13321, 11421, 11426, -1, 13321, 11426, 13318, -1, 13321, 13320, 13322, -1, 13321, 13322, 13323, -1, 13321, 13323, 11421, -1, 13324, 11417, 11421, -1, 13324, 13323, 13325, -1, 13324, 13325, 13326, -1, 13324, 11421, 13323, -1, 13327, 13324, 13326, -1, 13327, 13326, 13283, -1, 13327, 11417, 13324, -1, 13327, 13283, 11417, -1, 13328, 11414, 11417, -1, 13328, 13288, 13329, -1, 13328, 13329, 13330, -1, 13328, 11417, 13288, -1, 13331, 11414, 13328, -1, 13331, 13328, 13330, -1, 13331, 13330, 13332, -1, 13331, 13332, 13333, -1, 13334, 13333, 13335, -1, 13334, 13331, 13333, -1, 13336, 13335, 13337, -1, 13338, 11409, 11414, -1, 13338, 11414, 13331, -1, 13338, 13331, 13334, -1, 13339, 11397, 13340, -1, 13341, 13338, 13334, -1, 13341, 11409, 13338, -1, 13341, 13334, 13335, -1, 13341, 13335, 13336, -1, 13342, 13337, 13343, -1, 13342, 13336, 13337, -1, 13344, 13343, 13345, -1, 13346, 13341, 13336, -1, 13346, 13336, 13342, -1, 13347, 13342, 13343, -1, 13347, 13343, 13344, -1, 13347, 13344, 13345, -1, 13348, 11406, 11409, -1, 13348, 13341, 13346, -1, 13348, 11409, 13341, -1, 11394, 11397, 13339, -1, 11394, 13339, 13349, -1, 13350, 13342, 13347, -1, 13350, 13348, 13346, -1, 13350, 11406, 13348, -1, 13350, 13346, 13342, -1, 13351, 13345, 13352, -1, 13351, 13347, 13345, -1, 13353, 13352, 13345, -1, 13353, 13345, 13354, -1, 13355, 13350, 13347, -1, 13355, 13347, 13351, -1, 13356, 13351, 13352, -1, 13356, 13357, 13358, -1, 13356, 13352, 13353, -1, 13356, 13353, 13357, -1, 13359, 11401, 11406, -1, 13359, 11406, 13350, -1, 13359, 13350, 13355, -1, 13360, 13353, 13354, -1, 13360, 13361, 13362, -1, 13360, 13362, 13363, -1, 13360, 13363, 13357, -1, 13360, 13357, 13353, -1, 13261, 13358, 13259, -1, 13261, 13351, 13356, -1, 13261, 13356, 13358, -1, 13261, 11401, 13359, -1, 13261, 13359, 13355, -1, 13261, 13355, 13351, -1, 13364, 13365, 13361, -1, 13364, 13354, 13366, -1, 13364, 13361, 13360, -1, 13364, 13360, 13354, -1, 13258, 13340, 11397, -1, 13258, 13257, 13367, -1, 13258, 13367, 13340, -1, 13368, 13365, 13364, -1, 13368, 13364, 13366, -1, 13369, 13368, 13366, -1, 13369, 13370, 13365, -1, 13369, 13371, 13370, -1, 13369, 13366, 13371, -1, 13369, 13365, 13368, -1, 13372, 11394, 13349, -1, 13372, 13349, 13373, -1, 13372, 13373, 13374, -1, 13372, 13374, 13375, -1, 13376, 13370, 13371, -1, 13377, 13376, 13371, -1, 13377, 13378, 13379, -1, 13377, 13371, 13378, -1, 13380, 11389, 11394, -1, 13380, 13372, 13375, -1, 13380, 11394, 13372, -1, 13380, 13375, 13381, -1, 13382, 13379, 13370, -1, 13382, 13370, 13376, -1, 13382, 13377, 13379, -1, 13382, 13376, 13377, -1, 13383, 13379, 13378, -1, 13383, 13378, 13384, -1, 13385, 13380, 13381, -1, 13385, 11389, 13380, -1, 13385, 13381, 13386, -1, 13387, 13379, 13383, -1, 13387, 13383, 13384, -1, 13387, 13388, 13379, -1, 13389, 11386, 11389, -1, 13389, 11389, 13385, -1, 13389, 13385, 13386, -1, 13389, 13386, 13390, -1, 13391, 13387, 13384, -1, 13391, 13388, 13387, -1, 13391, 13384, 13392, -1, 13393, 13390, 13394, -1, 13393, 11386, 13389, -1, 13393, 13389, 13390, -1, 13395, 13394, 13396, -1, 13395, 13393, 13394, -1, 13397, 13391, 13392, -1, 13397, 13388, 13391, -1, 13398, 11381, 11386, -1, 13398, 11386, 13393, -1, 13398, 13393, 13395, -1, 13399, 13395, 13396, -1, 13400, 13401, 13388, -1, 13400, 13392, 13402, -1, 13400, 13388, 13397, -1, 13400, 13397, 13392, -1, 13403, 11381, 13398, -1, 13403, 13398, 13395, -1, 13403, 13395, 13399, -1, 13404, 13396, 13405, -1, 13404, 13399, 13396, -1, 13406, 13407, 13401, -1, 13406, 13401, 13400, -1, 13406, 13400, 13402, -1, 13408, 13403, 13399, -1, 13408, 11377, 11381, -1, 13408, 11381, 13403, -1, 13408, 13399, 13404, -1, 13409, 13404, 13405, -1, 13409, 13405, 13410, -1, 13411, 13406, 13402, -1, 13411, 13407, 13406, -1, 13411, 13402, 13412, -1, 13413, 13404, 13409, -1, 13413, 11377, 13408, -1, 13413, 13408, 13404, -1, 13414, 13409, 13410, -1, 13414, 13410, 13415, -1, 13416, 13407, 13411, -1, 13416, 13411, 13412, -1, 13416, 13417, 13407, -1, 13416, 13412, 13417, -1, 13418, 11374, 11377, -1, 13418, 11377, 13413, -1, 13418, 13413, 13409, -1, 13418, 13409, 13414, -1, 13419, 11374, 13418, -1, 13419, 13414, 13415, -1, 13419, 13418, 13414, -1, 13419, 13415, 13420, -1, 13421, 13422, 13417, -1, 13421, 13417, 13412, -1, 13423, 13420, 13424, -1, 13423, 13419, 13420, -1, 13425, 13422, 13421, -1, 13425, 13421, 13412, -1, 13425, 13412, 13426, -1, 13427, 11369, 11374, -1, 13427, 11374, 13419, -1, 13427, 13419, 13423, -1, 13428, 13423, 13424, -1, 13428, 13427, 13423, -1, 13428, 11369, 13427, -1, 13429, 13430, 13422, -1, 13429, 13422, 13425, -1, 13429, 13425, 13426, -1, 13431, 13428, 13424, -1, 13431, 13424, 13432, -1, 13433, 13430, 13429, -1, 13433, 13434, 13430, -1, 13433, 13429, 13426, -1, 13433, 13426, 13435, -1, 13436, 11365, 11369, -1, 13436, 11369, 13428, -1, 13436, 13428, 13431, -1, 13437, 11365, 13436, -1, 13437, 13431, 13432, -1, 13437, 13432, 13438, -1, 13437, 13436, 13431, -1, 13439, 13433, 13435, -1, 13439, 13434, 13433, -1, 13440, 13438, 13441, -1, 13440, 13437, 13438, -1, 13442, 13434, 13439, -1, 13442, 13443, 13434, -1, 13442, 13444, 13443, -1, 13442, 13439, 13435, -1, 13442, 13435, 13444, -1, 13445, 11361, 11365, -1, 13445, 11365, 13437, -1, 13445, 13437, 13440, -1, 13446, 11361, 13445, -1, 13446, 13440, 13441, -1, 13446, 13445, 13440, -1, 13447, 13448, 13443, -1, 13447, 13443, 13444, -1, 13447, 13444, 13449, -1, 13450, 13448, 13447, -1, 13450, 13447, 13449, -1, 13451, 11357, 11361, -1, 13451, 11361, 13446, -1, 13451, 13441, 13452, -1, 13451, 13446, 13441, -1, 13453, 11357, 13451, -1, 13453, 13451, 13452, -1, 13454, 13455, 13448, -1, 13454, 13449, 13456, -1, 13454, 13448, 13450, -1, 13454, 13450, 13449, -1, 13457, 13452, 13458, -1, 13457, 13453, 13452, -1, 13459, 11349, 13460, -1, 13461, 11357, 13453, -1, 13461, 13457, 13458, -1, 13461, 13453, 13457, -1, 13461, 11354, 11357, -1, 13462, 13463, 13455, -1, 13462, 13455, 13454, -1, 13462, 13454, 13456, -1, 13462, 13456, 13464, -1, 13465, 13456, 13466, -1, 13465, 13464, 13456, -1, 13467, 13458, 13468, -1, 13467, 13461, 13458, -1, 13467, 11349, 11354, -1, 13467, 11354, 13461, -1, 13469, 13462, 13464, -1, 13469, 13465, 13466, -1, 13469, 13470, 13463, -1, 13469, 13463, 13462, -1, 13469, 13464, 13465, -1, 13471, 13468, 13472, -1, 13471, 13472, 13460, -1, 13471, 11349, 13467, -1, 13471, 13460, 11349, -1, 13471, 13467, 13468, -1, 13473, 13469, 13466, -1, 13473, 13470, 13469, -1, 13473, 13474, 13475, -1, 13473, 13475, 13476, -1, 13473, 13476, 13477, -1, 13473, 13477, 13470, -1, 13473, 13466, 13478, -1, 13479, 13473, 13478, -1, 13479, 13474, 13473, -1, 13479, 13478, 13480, -1, 13481, 13482, 13474, -1, 13481, 13474, 13479, -1, 13266, 13483, 13484, -1, 13266, 13484, 13485, -1, 13266, 13485, 13263, -1, 13266, 11345, 13483, -1, 13486, 13479, 13480, -1, 13267, 13265, 13482, -1, 13267, 13482, 13481, -1, 13487, 13481, 13479, -1, 13487, 13479, 13486, -1, 11345, 13459, 13483, -1, 13488, 13486, 13480, -1, 13488, 13480, 13489, -1, 11345, 11349, 13459, -1, 13490, 13481, 13487, -1, 13490, 13267, 13481, -1, 13491, 13487, 13486, -1, 13491, 13488, 13489, -1, 13491, 13486, 13488, -1, 13492, 11341, 13267, -1, 13492, 13267, 13490, -1, 13493, 13490, 13487, -1, 13493, 13487, 13491, -1, 13494, 13491, 13489, -1, 13494, 13489, 13495, -1, 13496, 11341, 13492, -1, 13496, 13492, 13490, -1, 13496, 13490, 13493, -1, 13496, 11338, 11341, -1, 13497, 13493, 13491, -1, 13497, 13491, 13494, -1, 13498, 13494, 13495, -1, 13499, 13493, 13497, -1, 13499, 13496, 13493, -1, 13499, 11338, 13496, -1, 13500, 13497, 13494, -1, 13500, 13494, 13498, -1, 13501, 13498, 13495, -1, 13501, 13495, 13502, -1, 13503, 13497, 13500, -1, 11326, 13504, 13505, -1, 13503, 13499, 13497, -1, 13503, 11338, 13499, -1, 13503, 11334, 11338, -1, 13506, 13500, 13498, -1, 13506, 13498, 13501, -1, 13506, 13501, 13502, -1, 13507, 13503, 13500, -1, 13507, 13500, 13506, -1, 13507, 11334, 13503, -1, 13508, 13506, 13502, -1, 13508, 13502, 13509, -1, 13510, 13507, 13506, -1, 13510, 11334, 13507, -1, 13510, 13506, 13508, -1, 13510, 11330, 11334, -1, 13511, 11330, 13510, -1, 13511, 13508, 13509, -1, 13511, 13510, 13508, -1, 13511, 13509, 13512, -1, 13513, 11330, 13511, -1, 13513, 13504, 11326, -1, 13513, 13512, 13514, -1, 13513, 13514, 13504, -1, 13513, 13511, 13512, -1, 13513, 11326, 11330, -1, 13515, 11326, 13505, -1, 13515, 13505, 13516, -1, 13517, 11326, 13515, -1, 13517, 13518, 11322, -1, 13517, 13516, 13519, -1, 13517, 13519, 13518, -1, 13517, 11322, 11326, -1, 13517, 13515, 13516, -1, 13520, 11322, 13518, -1, 13520, 13518, 13521, -1, 13520, 11318, 11322, -1, 13520, 13521, 13522, -1, 13523, 11318, 13520, -1, 13523, 13520, 13522, -1, 13523, 13524, 11318, -1, 13523, 13522, 13525, -1, 13523, 13525, 13526, -1, 13523, 13526, 13524, -1, 13527, 11318, 13524, -1, 13527, 13524, 13528, -1, 13527, 11314, 11318, -1, 13207, 13528, 13208, -1, 13206, 11314, 13527, -1, 13206, 13528, 13207, -1, 13206, 13527, 13528, -1, 13529, 13530, 13531, -1, 13532, 13530, 13529, -1, 13533, 13534, 13535, -1, 13532, 13534, 13530, -1, 13536, 13534, 13532, -1, 13535, 13534, 13536, -1, 13537, 13538, 12055, -1, 12055, 13538, 13539, -1, 13540, 13538, 13541, -1, 13541, 13538, 13542, -1, 13542, 13538, 13543, -1, 13539, 13538, 13540, -1, 13531, 13544, 13545, -1, 13546, 13547, 13548, -1, 13530, 13544, 13531, -1, 13543, 13549, 13550, -1, 13547, 13551, 13548, -1, 13550, 13549, 13533, -1, 13533, 13549, 13534, -1, 13534, 13552, 13530, -1, 13544, 13552, 13545, -1, 13530, 13552, 13544, -1, 13537, 13553, 13538, -1, 13543, 13553, 13549, -1, 13554, 13540, 13555, -1, 13538, 13553, 13543, -1, 13534, 13556, 13552, -1, 13549, 13556, 13534, -1, 13545, 13557, 13558, -1, 13552, 13557, 13545, -1, 13559, 13560, 13537, -1, 13553, 13560, 13549, -1, 13549, 13560, 13556, -1, 13537, 13560, 13553, -1, 13552, 13561, 13557, -1, 13554, 13539, 13540, -1, 13556, 13561, 13552, -1, 13558, 13562, 13563, -1, 13557, 13562, 13558, -1, 13560, 13564, 13556, -1, 13559, 13564, 13560, -1, 13556, 13564, 13561, -1, 13561, 13565, 13557, -1, 13557, 13565, 13562, -1, 13562, 13566, 13563, -1, 13567, 13568, 13559, -1, 13564, 13568, 13561, -1, 13561, 13568, 13565, -1, 13559, 13568, 13564, -1, 13565, 13569, 13562, -1, 13562, 13569, 13566, -1, 13568, 13570, 13565, -1, 13565, 13570, 13569, -1, 13567, 13570, 13568, -1, 13569, 13571, 13566, -1, 13566, 13571, 13563, -1, 13563, 13571, 13572, -1, 13573, 13574, 13567, -1, 13569, 13574, 13571, -1, 13567, 13574, 13570, -1, 13570, 13574, 13569, -1, 13573, 13575, 13574, -1, 13571, 13575, 13572, -1, 13574, 13575, 13571, -1, 13572, 13575, 13576, -1, 13577, 13578, 13573, -1, 13576, 13578, 13579, -1, 13575, 13578, 13576, -1, 13573, 13578, 13575, -1, 13580, 13581, 13577, -1, 13579, 13581, 13580, -1, 13578, 13581, 13579, -1, 13577, 13581, 13578, -1, 13577, 13582, 13580, -1, 13577, 13583, 13582, -1, 13582, 13583, 13584, -1, 13584, 13583, 13585, -1, 13586, 13532, 13587, -1, 13548, 13532, 13586, -1, 13587, 13532, 13529, -1, 13551, 13532, 13548, -1, 13535, 13536, 13588, -1, 13588, 13536, 13551, -1, 13551, 13536, 13532, -1, 13589, 13546, 13548, -1, 13590, 13591, 13592, -1, 13592, 13591, 13593, -1, 13593, 13591, 13594, -1, 13594, 13595, 13596, -1, 13591, 13595, 13594, -1, 13590, 13595, 13591, -1, 13597, 13598, 13590, -1, 13595, 13598, 13596, -1, 13590, 13598, 13595, -1, 13596, 13599, 13600, -1, 13597, 13599, 13598, -1, 13598, 13599, 13596, -1, 13600, 13601, 13602, -1, 13599, 13601, 13600, -1, 13601, 13603, 13602, -1, 13604, 13605, 13597, -1, 13599, 13605, 13601, -1, 13597, 13605, 13599, -1, 13602, 13606, 13607, -1, 13603, 13606, 13602, -1, 13608, 13609, 13604, -1, 13601, 13609, 13603, -1, 13605, 13609, 13601, -1, 13604, 13609, 13605, -1, 13610, 13611, 13608, -1, 13606, 13611, 13607, -1, 13608, 13611, 13609, -1, 13609, 13611, 13603, -1, 13603, 13611, 13606, -1, 13612, 13613, 13610, -1, 13607, 13613, 13614, -1, 13611, 13613, 13607, -1, 13610, 13613, 13611, -1, 13614, 13615, 13616, -1, 13613, 13615, 13614, -1, 13589, 13617, 13612, -1, 13612, 13617, 13613, -1, 13613, 13617, 13615, -1, 13616, 13618, 13587, -1, 13587, 13618, 13586, -1, 13615, 13618, 13616, -1, 13586, 13619, 13548, -1, 13589, 13619, 13617, -1, 13618, 13619, 13586, -1, 13548, 13619, 13589, -1, 13617, 13619, 13615, -1, 13615, 13619, 13618, -1, 13620, 13621, 13622, -1, 13622, 13621, 13623, -1, 13624, 13625, 13626, -1, 13627, 13625, 13620, -1, 13626, 13625, 13627, -1, 13620, 13625, 13621, -1, 13623, 13628, 13629, -1, 13621, 13628, 13623, -1, 13630, 13631, 13624, -1, 13621, 13631, 13628, -1, 13624, 13631, 13625, -1, 13625, 13631, 13621, -1, 13628, 13631, 13630, -1, 13632, 13633, 13630, -1, 13629, 13633, 13634, -1, 13630, 13633, 13628, -1, 13628, 13633, 13629, -1, 13634, 13635, 13636, -1, 13633, 13637, 13634, -1, 13634, 13637, 13635, -1, 13632, 13637, 13633, -1, 13636, 13638, 13639, -1, 13635, 13638, 13636, -1, 13640, 13641, 13632, -1, 13632, 13641, 13637, -1, 13637, 13641, 13635, -1, 13639, 13642, 13643, -1, 13638, 13642, 13639, -1, 13644, 13645, 13640, -1, 13641, 13645, 13635, -1, 13635, 13645, 13638, -1, 13640, 13645, 13641, -1, 13642, 13646, 13643, -1, 13644, 13647, 13645, -1, 13638, 13647, 13642, -1, 13645, 13647, 13638, -1, 13648, 13649, 13650, -1, 13643, 13649, 13651, -1, 13650, 13649, 13646, -1, 13646, 13649, 13643, -1, 13650, 13652, 13644, -1, 13644, 13652, 13647, -1, 13646, 13652, 13650, -1, 13642, 13652, 13646, -1, 13647, 13652, 13642, -1, 13653, 13654, 13655, -1, 13655, 13654, 13648, -1, 13651, 13654, 13653, -1, 13648, 13654, 13649, -1, 13649, 13654, 13651, -1, 13656, 13657, 13658, -1, 13659, 13657, 13656, -1, 13660, 13661, 13662, -1, 13662, 13661, 13659, -1, 13663, 13664, 13665, -1, 13659, 13666, 13657, -1, 11952, 13667, 11945, -1, 13660, 13667, 13661, -1, 11945, 13667, 13668, -1, 13668, 13667, 13660, -1, 13658, 13669, 13670, -1, 13657, 13669, 13658, -1, 13661, 13671, 13659, -1, 13659, 13671, 13666, -1, 13666, 13672, 13657, -1, 13657, 13672, 13669, -1, 11952, 13673, 13667, -1, 13661, 13673, 13671, -1, 13667, 13673, 13661, -1, 13670, 13674, 13675, -1, 13669, 13674, 13670, -1, 13671, 13676, 13666, -1, 13666, 13676, 13672, -1, 13669, 13677, 13674, -1, 13672, 13677, 13669, -1, 13673, 13678, 13671, -1, 11956, 13678, 11952, -1, 13671, 13678, 13676, -1, 11952, 13678, 13673, -1, 13674, 13679, 13675, -1, 13676, 13680, 13672, -1, 13672, 13680, 13677, -1, 13674, 13681, 13679, -1, 13677, 13681, 13674, -1, 13676, 13682, 13680, -1, 11956, 13682, 13678, -1, 13678, 13682, 13676, -1, 13675, 13683, 13684, -1, 13679, 13683, 13675, -1, 13680, 13685, 13677, -1, 13677, 13685, 13681, -1, 13681, 13686, 13679, -1, 13679, 13686, 13683, -1, 11956, 13687, 13682, -1, 11957, 13687, 11956, -1, 13680, 13687, 13685, -1, 13682, 13687, 13680, -1, 13684, 13688, 13689, -1, 13689, 13688, 13690, -1, 13683, 13688, 13684, -1, 13681, 13691, 13686, -1, 13685, 13691, 13681, -1, 13665, 13692, 13693, -1, 13693, 13692, 13694, -1, 13686, 13695, 13683, -1, 13694, 13692, 13696, -1, 13688, 13695, 13690, -1, 13683, 13695, 13688, -1, 13664, 13692, 13665, -1, 11944, 13697, 12051, -1, 13698, 13697, 13664, -1, 11957, 13699, 13687, -1, 12051, 13697, 13698, -1, 13687, 13699, 13685, -1, 13664, 13697, 13692, -1, 13685, 13699, 13691, -1, 13700, 13701, 13702, -1, 13696, 13701, 13700, -1, 13695, 13703, 13690, -1, 13692, 13701, 13696, -1, 13686, 13703, 13695, -1, 13691, 13703, 13686, -1, 13702, 13704, 13705, -1, 13690, 13706, 11958, -1, 11958, 13706, 11957, -1, 11957, 13706, 13699, -1, 13703, 13706, 13690, -1, 13699, 13706, 13691, -1, 13692, 13707, 13701, -1, 13691, 13706, 13703, -1, 13697, 13707, 13692, -1, 11944, 13707, 13697, -1, 13701, 13708, 13702, -1, 13702, 13708, 13704, -1, 13705, 13662, 13656, -1, 13704, 13662, 13705, -1, 11945, 13709, 11944, -1, 13701, 13709, 13708, -1, 11944, 13709, 13707, -1, 13707, 13709, 13701, -1, 13704, 13660, 13662, -1, 13708, 13660, 13704, -1, 13662, 13659, 13656, -1, 11945, 13668, 13709, -1, 13709, 13668, 13708, -1, 13708, 13668, 13660, -1, 13710, 13711, 13712, -1, 13713, 13711, 13710, -1, 13712, 13711, 13714, -1, 13715, 13716, 13717, -1, 13717, 13716, 13718, -1, 13719, 13720, 13721, -1, 13714, 13720, 13719, -1, 13722, 13723, 13724, -1, 13721, 13725, 13726, -1, 13716, 13727, 13718, -1, 13711, 13728, 13714, -1, 13714, 13728, 13720, -1, 13720, 13729, 13721, -1, 13730, 13731, 13732, -1, 13721, 13729, 13725, -1, 13725, 13733, 13726, -1, 13720, 13734, 13729, -1, 13727, 13735, 13736, -1, 13737, 13738, 13739, -1, 13740, 13734, 13728, -1, 13736, 13735, 13741, -1, 13723, 13738, 13742, -1, 13728, 13734, 13720, -1, 13716, 13735, 13727, -1, 13742, 13738, 13743, -1, 13743, 13738, 13737, -1, 13722, 13738, 13723, -1, 13725, 13744, 13733, -1, 13729, 13744, 13725, -1, 13726, 13745, 13746, -1, 13747, 13745, 13748, -1, 13733, 13745, 13726, -1, 13734, 13749, 13729, -1, 13729, 13749, 13744, -1, 13748, 13750, 13751, -1, 13751, 13750, 13752, -1, 13744, 13750, 13733, -1, 13733, 13750, 13745, -1, 13745, 13750, 13748, -1, 13747, 13753, 13745, -1, 13746, 13753, 13754, -1, 13754, 13753, 13755, -1, 13755, 13753, 13756, -1, 13756, 13753, 13747, -1, 13745, 13753, 13746, -1, 13757, 13758, 13749, -1, 13752, 13758, 13759, -1, 13749, 13758, 13744, -1, 13750, 13758, 13752, -1, 13744, 13758, 13750, -1, 13754, 13760, 13730, -1, 13755, 13760, 13754, -1, 13761, 13760, 13755, -1, 13762, 13763, 13764, -1, 13764, 13763, 13715, -1, 13715, 13763, 13716, -1, 13760, 13765, 13730, -1, 13731, 13765, 13761, -1, 13730, 13765, 13731, -1, 13761, 13765, 13760, -1, 13731, 13766, 13732, -1, 13767, 13766, 13731, -1, 13741, 13768, 13769, -1, 13735, 13768, 13741, -1, 13732, 13770, 13771, -1, 13772, 13770, 13767, -1, 13766, 13770, 13732, -1, 13767, 13770, 13766, -1, 13769, 13773, 13774, -1, 13770, 13775, 13771, -1, 13776, 13777, 13778, -1, 13772, 13775, 13770, -1, 13779, 13780, 13773, -1, 13773, 13780, 13774, -1, 13774, 13780, 13781, -1, 13772, 13782, 13775, -1, 13771, 13782, 13778, -1, 13776, 13782, 13772, -1, 13775, 13782, 13771, -1, 13778, 13782, 13776, -1, 13781, 13783, 13784, -1, 13785, 13786, 13783, -1, 13783, 13786, 13784, -1, 13784, 13786, 13787, -1, 13788, 13786, 13785, -1, 13778, 13789, 13790, -1, 13777, 13789, 13778, -1, 13786, 13791, 13787, -1, 13788, 13791, 13786, -1, 13787, 13791, 13792, -1, 13790, 13793, 13794, -1, 13789, 13793, 13790, -1, 13795, 13793, 13777, -1, 13777, 13793, 13789, -1, 13794, 13793, 13795, -1, 13788, 13796, 13791, -1, 13795, 13797, 13794, -1, 13791, 13796, 13792, -1, 13798, 13796, 13788, -1, 13796, 13799, 13792, -1, 13798, 13799, 13796, -1, 13792, 13799, 13800, -1, 13798, 13801, 13799, -1, 13799, 13801, 13800, -1, 13800, 13801, 13802, -1, 13802, 13801, 13803, -1, 13803, 13801, 13804, -1, 13804, 13801, 13798, -1, 13713, 13805, 13711, -1, 13740, 13805, 13713, -1, 13711, 13805, 13728, -1, 13728, 13805, 13740, -1, 13734, 13806, 13749, -1, 13749, 13806, 13757, -1, 13757, 13806, 13740, -1, 13740, 13806, 13734, -1, 13739, 13807, 13808, -1, 13809, 13807, 13738, -1, 13738, 13807, 13739, -1, 13808, 13810, 13811, -1, 13811, 13810, 13812, -1, 13757, 13813, 13758, -1, 13759, 13814, 13762, -1, 13807, 13810, 13808, -1, 13763, 13814, 13716, -1, 13809, 13810, 13807, -1, 13757, 13814, 13813, -1, 13813, 13814, 13758, -1, 13716, 13814, 13757, -1, 13758, 13814, 13759, -1, 13812, 13712, 13815, -1, 13762, 13814, 13763, -1, 13769, 13816, 13773, -1, 13810, 13710, 13812, -1, 13773, 13816, 13779, -1, 13809, 13710, 13810, -1, 13768, 13816, 13769, -1, 13713, 13710, 13809, -1, 13735, 13816, 13768, -1, 13812, 13710, 13712, -1, 13779, 13816, 13735, -1, 13780, 13817, 13781, -1, 13781, 13817, 13783, -1, 13783, 13817, 13785, -1, 13815, 13714, 13719, -1, 13785, 13817, 13779, -1, 13779, 13817, 13780, -1, 13712, 13714, 13815, -1, 13818, 13819, 13820, -1, 13821, 13820, 13822, -1, 13821, 13818, 13820, -1, 13823, 13822, 13824, -1, 13823, 13821, 13822, -1, 13825, 13824, 13826, -1, 13825, 13823, 13824, -1, 13827, 13825, 13826, -1, 13723, 13820, 13724, -1, 13724, 13820, 13819, -1, 13723, 13822, 13820, -1, 13723, 13742, 13822, -1, 13743, 13824, 13742, -1, 13742, 13824, 13822, -1, 13737, 13826, 13743, -1, 13743, 13826, 13824, -1, 13737, 13828, 13826, -1, 13829, 13830, 13831, -1, 13831, 13830, 13832, -1, 13833, 13830, 13829, -1, 13834, 13835, 13836, -1, 13837, 13838, 13833, -1, 13830, 13838, 13832, -1, 13833, 13838, 13830, -1, 13832, 13839, 13840, -1, 13837, 13839, 13838, -1, 13838, 13839, 13832, -1, 13840, 13841, 13842, -1, 13839, 13841, 13840, -1, 13841, 13843, 13842, -1, 13837, 13844, 13839, -1, 13845, 13844, 13837, -1, 13839, 13844, 13841, -1, 13841, 13846, 13843, -1, 13835, 13833, 13847, -1, 13847, 13833, 13829, -1, 13842, 13848, 13849, -1, 13834, 13833, 13835, -1, 13843, 13848, 13842, -1, 13844, 13850, 13841, -1, 13841, 13850, 13846, -1, 13845, 13850, 13844, -1, 13846, 13851, 13843, -1, 13843, 13851, 13848, -1, 13849, 13852, 13853, -1, 13848, 13852, 13849, -1, 13854, 13855, 13845, -1, 13850, 13855, 13846, -1, 13845, 13855, 13850, -1, 13846, 13855, 13851, -1, 13853, 13856, 13857, -1, 13848, 13858, 13852, -1, 13851, 13858, 13848, -1, 13852, 13859, 13853, -1, 13853, 13859, 13856, -1, 13854, 13860, 13855, -1, 13851, 13860, 13858, -1, 13855, 13860, 13851, -1, 13857, 13861, 13862, -1, 13856, 13861, 13857, -1, 13858, 13863, 13852, -1, 13852, 13863, 13859, -1, 13864, 13865, 13866, -1, 13859, 13865, 13856, -1, 13856, 13865, 13861, -1, 13858, 13867, 13863, -1, 13860, 13867, 13858, -1, 13868, 13867, 13854, -1, 13854, 13867, 13860, -1, 13869, 13870, 13871, -1, 13861, 13870, 13862, -1, 13862, 13870, 13622, -1, 13622, 13870, 13620, -1, 13620, 13870, 13627, -1, 13627, 13870, 13869, -1, 13866, 13872, 13873, -1, 13863, 13872, 13859, -1, 13865, 13872, 13866, -1, 13859, 13872, 13865, -1, 13871, 13874, 13875, -1, 13875, 13874, 13864, -1, 13864, 13874, 13865, -1, 13865, 13874, 13861, -1, 13870, 13874, 13871, -1, 13861, 13874, 13870, -1, 13868, 13876, 13867, -1, 13873, 13876, 13877, -1, 13867, 13876, 13863, -1, 13863, 13876, 13872, -1, 13872, 13876, 13873, -1, 13877, 13878, 13879, -1, 13879, 13878, 13880, -1, 13880, 13878, 13881, -1, 13664, 13878, 13698, -1, 13698, 13878, 12051, -1, 12051, 13878, 13868, -1, 13876, 13878, 13877, -1, 13868, 13878, 13876, -1, 13881, 13878, 13664, -1, 13869, 13626, 13627, -1, 13881, 13664, 13663, -1, 13882, 13883, 13884, -1, 13885, 13884, 13886, -1, 13885, 13882, 13884, -1, 13887, 13886, 13888, -1, 13887, 13885, 13886, -1, 13889, 13888, 13890, -1, 13889, 13887, 13888, -1, 13891, 13889, 13890, -1, 13835, 13884, 13836, -1, 13836, 13884, 13883, -1, 13835, 13886, 13884, -1, 13835, 13847, 13886, -1, 13829, 13888, 13847, -1, 13847, 13888, 13886, -1, 13831, 13890, 13829, -1, 13829, 13890, 13888, -1, 13831, 13892, 13890, -1, 13893, 13894, 13895, -1, 13896, 13897, 13898, -1, 13899, 13897, 13900, -1, 13900, 13897, 13896, -1, 13894, 13901, 13895, -1, 11971, 13901, 13894, -1, 13898, 13902, 13903, -1, 13897, 13902, 13898, -1, 13899, 13902, 13897, -1, 13903, 13902, 13899, -1, 11974, 13904, 11971, -1, 13905, 13904, 11974, -1, 13895, 13904, 13905, -1, 11971, 13904, 13901, -1, 13901, 13904, 13895, -1, 13903, 13906, 13898, -1, 13907, 13906, 13908, -1, 13908, 13906, 13903, -1, 13898, 13906, 13907, -1, 13908, 13909, 13907, -1, 13910, 13909, 13908, -1, 13911, 13912, 13913, -1, 13913, 13912, 13910, -1, 13907, 13912, 13911, -1, 13910, 13912, 13909, -1, 13909, 13912, 13907, -1, 13913, 13914, 13911, -1, 13915, 13914, 13916, -1, 13917, 13914, 13915, -1, 13918, 11981, 13919, -1, 13916, 13914, 13913, -1, 11978, 11981, 13918, -1, 13911, 13914, 13917, -1, 13919, 11981, 13920, -1, 13920, 11981, 13921, -1, 13922, 13923, 13924, -1, 13924, 13923, 13915, -1, 13915, 13923, 13917, -1, 13917, 13923, 13925, -1, 13922, 13926, 13923, -1, 13927, 13926, 13922, -1, 13923, 13928, 13925, -1, 13925, 13928, 13929, -1, 13930, 13931, 13932, -1, 13932, 13931, 13927, -1, 13927, 13931, 13926, -1, 13926, 13933, 13923, -1, 13923, 13933, 13928, -1, 13928, 13934, 13929, -1, 13926, 13935, 13933, -1, 11982, 13935, 13931, -1, 13931, 13935, 13926, -1, 13933, 13936, 13928, -1, 13928, 13936, 13934, -1, 13929, 13937, 13938, -1, 13938, 13937, 13939, -1, 13934, 13937, 13929, -1, 13933, 13940, 13936, -1, 13935, 13940, 13933, -1, 13936, 13941, 13934, -1, 13934, 13941, 13937, -1, 13940, 13942, 13936, -1, 11985, 13942, 13940, -1, 11989, 13942, 11985, -1, 13936, 13942, 13941, -1, 13937, 13943, 13939, -1, 13941, 13943, 13937, -1, 13939, 13943, 13944, -1, 13942, 13945, 13941, -1, 11989, 13945, 13942, -1, 13941, 13945, 13943, -1, 13946, 11993, 13947, -1, 13948, 11993, 13946, -1, 13943, 13949, 13944, -1, 13944, 13949, 13950, -1, 11992, 13951, 11989, -1, 11989, 13951, 13945, -1, 13945, 13951, 13943, -1, 13949, 13951, 13950, -1, 11993, 13952, 13947, -1, 13943, 13951, 13949, -1, 11974, 13953, 13905, -1, 13951, 13954, 13950, -1, 13950, 13954, 13955, -1, 11992, 13954, 13951, -1, 11993, 13956, 11992, -1, 13954, 13956, 13955, -1, 11992, 13956, 13954, -1, 13955, 13956, 13948, -1, 13948, 13956, 11993, -1, 11982, 13957, 11981, -1, 11981, 13957, 13921, -1, 13921, 13957, 13958, -1, 13958, 13957, 13930, -1, 13930, 13957, 13931, -1, 13952, 11996, 13959, -1, 13931, 13957, 11982, -1, 13959, 11996, 13960, -1, 11982, 13961, 13935, -1, 13940, 13961, 11985, -1, 13935, 13961, 13940, -1, 11985, 13961, 11982, -1, 11993, 11996, 13952, -1, 13962, 13963, 13964, -1, 13964, 13963, 13965, -1, 13965, 13963, 13966, -1, 11966, 13967, 11965, -1, 11965, 13967, 13968, -1, 13968, 13967, 13969, -1, 13969, 13967, 13970, -1, 13963, 13971, 13966, -1, 13972, 13971, 13962, -1, 13966, 13971, 13973, -1, 11974, 11978, 13953, -1, 13962, 13971, 13963, -1, 13953, 11978, 13974, -1, 13974, 11978, 13975, -1, 13970, 13976, 13977, -1, 13967, 13976, 13970, -1, 11966, 13976, 13967, -1, 11978, 13918, 13975, -1, 13971, 13978, 13973, -1, 13972, 13978, 13971, -1, 11970, 13979, 11966, -1, 13977, 13979, 13980, -1, 11966, 13979, 13976, -1, 13976, 13979, 13977, -1, 13981, 13982, 13972, -1, 13973, 13982, 13896, -1, 13978, 13982, 13973, -1, 13972, 13982, 13978, -1, 13980, 13983, 13893, -1, 13979, 13983, 13980, -1, 11970, 13983, 13979, -1, 13982, 13900, 13896, -1, 13981, 13900, 13982, -1, 13899, 13900, 13981, -1, 13983, 13894, 13893, -1, 11970, 13894, 13983, -1, 11971, 13894, 11970, -1, 13984, 13985, 13986, -1, 13987, 13984, 13986, -1, 13988, 13987, 13986, -1, 13989, 13988, 13986, -1, 13990, 13988, 13989, -1, 13991, 13990, 13989, -1, 13992, 13993, 13994, -1, 13995, 13992, 13994, -1, 13996, 13997, 13995, -1, 13996, 13995, 13994, -1, 13998, 13997, 13996, -1, 13999, 14000, 14001, -1, 14002, 14003, 13999, -1, 14002, 13999, 14001, -1, 14004, 14003, 14002, -1, 14005, 14004, 14002, -1, 14006, 14007, 14008, -1, 14008, 14007, 14009, -1, 14010, 14011, 14012, -1, 14012, 14011, 14013, -1, 14013, 14011, 14006, -1, 14007, 14014, 14015, -1, 14016, 14017, 14011, -1, 14014, 14017, 14018, -1, 14018, 14017, 14019, -1, 14006, 14017, 14007, -1, 14011, 14017, 14006, -1, 14007, 14017, 14014, -1, 14020, 14021, 14016, -1, 14016, 14021, 14017, -1, 13992, 13953, 13974, -1, 13905, 13995, 13895, -1, 13995, 13893, 13895, -1, 13893, 13997, 13980, -1, 13995, 13997, 13893, -1, 13997, 13977, 13980, -1, 13997, 13970, 13977, -1, 13997, 13998, 13970, -1, 13998, 13969, 13970, -1, 13992, 13995, 13953, -1, 13953, 13995, 13905, -1, 14000, 13962, 13964, -1, 13972, 13999, 13981, -1, 13999, 13899, 13981, -1, 13899, 14003, 13903, -1, 13999, 14003, 13899, -1, 14003, 13908, 13903, -1, 14003, 13910, 13908, -1, 14003, 14004, 13910, -1, 14004, 13913, 13910, -1, 14000, 13999, 13962, -1, 13962, 13999, 13972, -1, 13984, 13948, 13946, -1, 13984, 13955, 13948, -1, 13955, 13987, 13950, -1, 13987, 13944, 13950, -1, 13987, 13939, 13944, -1, 13987, 13938, 13939, -1, 13938, 13988, 13929, -1, 13988, 13925, 13929, -1, 13988, 13917, 13925, -1, 13988, 13911, 13917, -1, 13911, 13990, 13907, -1, 13990, 13898, 13907, -1, 13990, 13896, 13898, -1, 13990, 13973, 13896, -1, 13973, 13991, 13966, -1, 13990, 13991, 13973, -1, 13991, 13965, 13966, -1, 13984, 13987, 13955, -1, 13987, 13988, 13938, -1, 13988, 13990, 13911, -1, 14016, 14001, 14020, -1, 14002, 14001, 14016, -1, 14021, 13994, 14017, -1, 13996, 13994, 14021, -1, 14022, 14023, 14024, -1, 12004, 14023, 14022, -1, 14024, 14023, 14025, -1, 14026, 12015, 14027, -1, 14027, 12015, 14028, -1, 14029, 14030, 14031, -1, 14025, 14030, 14029, -1, 12000, 14032, 14033, -1, 14031, 14034, 14035, -1, 12015, 14036, 14028, -1, 14023, 14037, 14025, -1, 14025, 14037, 14030, -1, 14030, 14038, 14031, -1, 14039, 14040, 14041, -1, 14031, 14038, 14034, -1, 14034, 14042, 14035, -1, 14030, 14043, 14038, -1, 14036, 12016, 14044, -1, 14045, 12001, 14046, -1, 12008, 14043, 14037, -1, 14044, 12016, 14047, -1, 14032, 12001, 14048, -1, 14037, 14043, 14030, -1, 12015, 12016, 14036, -1, 14048, 12001, 14049, -1, 14049, 12001, 14045, -1, 12000, 12001, 14032, -1, 14034, 14050, 14042, -1, 14038, 14050, 14034, -1, 14035, 14051, 14052, -1, 14053, 14051, 14054, -1, 14042, 14051, 14035, -1, 14043, 14055, 14038, -1, 14038, 14055, 14050, -1, 14054, 14056, 14057, -1, 14057, 14056, 14058, -1, 14050, 14056, 14042, -1, 14042, 14056, 14051, -1, 14051, 14056, 14054, -1, 14053, 14059, 14051, -1, 14052, 14059, 14060, -1, 14060, 14059, 14061, -1, 14061, 14059, 14062, -1, 14062, 14059, 14053, -1, 14051, 14059, 14052, -1, 12011, 14063, 14055, -1, 14058, 14063, 14064, -1, 14055, 14063, 14050, -1, 14056, 14063, 14058, -1, 14050, 14063, 14056, -1, 14060, 14065, 14039, -1, 14061, 14065, 14060, -1, 14066, 14065, 14061, -1, 14067, 14068, 14069, -1, 14069, 14068, 14026, -1, 14026, 14068, 12015, -1, 14065, 14070, 14039, -1, 14040, 14070, 14066, -1, 14039, 14070, 14040, -1, 14066, 14070, 14065, -1, 14040, 14071, 14041, -1, 14072, 14071, 14040, -1, 14047, 14073, 14074, -1, 12016, 14073, 14047, -1, 14041, 14075, 14076, -1, 14077, 14075, 14072, -1, 14071, 14075, 14041, -1, 14072, 14075, 14071, -1, 14074, 14078, 14079, -1, 14075, 14080, 14076, -1, 14081, 14082, 14083, -1, 14077, 14080, 14075, -1, 12019, 14084, 14078, -1, 14078, 14084, 14079, -1, 14079, 14084, 14085, -1, 14077, 14086, 14080, -1, 14076, 14086, 14083, -1, 14081, 14086, 14077, -1, 14080, 14086, 14076, -1, 14083, 14086, 14081, -1, 14085, 14087, 14088, -1, 12022, 14089, 14087, -1, 14087, 14089, 14088, -1, 14088, 14089, 14090, -1, 12026, 14089, 12022, -1, 14083, 14091, 14092, -1, 14082, 14091, 14083, -1, 14089, 14093, 14090, -1, 12026, 14093, 14089, -1, 14090, 14093, 14094, -1, 14092, 14095, 14096, -1, 14091, 14095, 14092, -1, 14097, 14095, 14082, -1, 14082, 14095, 14091, -1, 14096, 14095, 14097, -1, 12026, 14098, 14093, -1, 14097, 14099, 14096, -1, 14093, 14098, 14094, -1, 12027, 14098, 12026, -1, 14098, 14100, 14094, -1, 12027, 14100, 14098, -1, 14094, 14100, 14101, -1, 12027, 14102, 14100, -1, 14100, 14102, 14101, -1, 14101, 14102, 14103, -1, 14103, 14102, 14104, -1, 14104, 14102, 12030, -1, 12030, 14102, 12027, -1, 12004, 14105, 14023, -1, 12008, 14105, 12004, -1, 14023, 14105, 14037, -1, 14037, 14105, 12008, -1, 14043, 14106, 14055, -1, 14055, 14106, 12011, -1, 12011, 14106, 12008, -1, 12008, 14106, 14043, -1, 14046, 14107, 14108, -1, 12003, 14107, 12001, -1, 12001, 14107, 14046, -1, 14108, 14109, 14110, -1, 14110, 14109, 14111, -1, 12011, 14112, 14063, -1, 14064, 14113, 14067, -1, 14107, 14109, 14108, -1, 14068, 14113, 12015, -1, 12003, 14109, 14107, -1, 12011, 14113, 14112, -1, 14112, 14113, 14063, -1, 12015, 14113, 12011, -1, 14063, 14113, 14064, -1, 14111, 14024, 14114, -1, 14067, 14113, 14068, -1, 14074, 14115, 14078, -1, 14109, 14022, 14111, -1, 14078, 14115, 12019, -1, 12003, 14022, 14109, -1, 14073, 14115, 14074, -1, 12004, 14022, 12003, -1, 12016, 14115, 14073, -1, 14111, 14022, 14024, -1, 12019, 14115, 12016, -1, 14084, 14116, 14085, -1, 14085, 14116, 14087, -1, 14087, 14116, 12022, -1, 14114, 14025, 14029, -1, 12022, 14116, 12019, -1, 12019, 14116, 14084, -1, 14024, 14025, 14114, -1, 14117, 14118, 14119, -1, 14120, 14119, 14121, -1, 14120, 14117, 14119, -1, 14122, 14121, 14123, -1, 14122, 14120, 14121, -1, 14124, 14123, 14125, -1, 14124, 14122, 14123, -1, 14126, 14124, 14125, -1, 14032, 14119, 14033, -1, 14033, 14119, 14118, -1, 14032, 14121, 14119, -1, 14032, 14048, 14121, -1, 14049, 14123, 14048, -1, 14048, 14123, 14121, -1, 14045, 14125, 14049, -1, 14049, 14125, 14123, -1, 14045, 14127, 14125, -1, 14128, 14129, 14130, -1, 12040, 14131, 12036, -1, 12036, 14131, 14132, -1, 14133, 14131, 14134, -1, 14132, 14131, 14133, -1, 14130, 14135, 14136, -1, 14137, 14138, 14129, -1, 14134, 14138, 14137, -1, 14129, 14139, 14130, -1, 14130, 14139, 14135, -1, 12040, 14140, 14131, -1, 14131, 14140, 14134, -1, 14134, 14140, 14138, -1, 14136, 14141, 14142, -1, 14135, 14141, 14136, -1, 14138, 14143, 14129, -1, 14129, 14143, 14139, -1, 14135, 14144, 14141, -1, 14141, 14144, 14142, -1, 14139, 14144, 14135, -1, 14138, 14145, 14143, -1, 12041, 14145, 12040, -1, 12040, 14145, 14140, -1, 14140, 14145, 14138, -1, 14139, 14146, 14144, -1, 14143, 14146, 14139, -1, 14142, 14147, 14148, -1, 14144, 14147, 14142, -1, 14145, 14149, 14143, -1, 14143, 14149, 14146, -1, 12041, 14149, 14145, -1, 14144, 14150, 14147, -1, 14146, 14150, 14144, -1, 14147, 14151, 14148, -1, 14148, 14151, 14152, -1, 12044, 14153, 12041, -1, 12041, 14153, 14149, -1, 14149, 14153, 14146, -1, 14146, 14153, 14150, -1, 14150, 14154, 14147, -1, 14147, 14154, 14151, -1, 14151, 14155, 14152, -1, 14150, 14156, 14154, -1, 14153, 14156, 14150, -1, 14157, 13554, 14158, -1, 14158, 13554, 13555, -1, 12044, 14156, 14153, -1, 14154, 14159, 14151, -1, 14151, 14159, 14155, -1, 14152, 14160, 14161, -1, 14155, 14160, 14152, -1, 12048, 14162, 12044, -1, 14163, 14164, 14165, -1, 12044, 14162, 14156, -1, 14165, 14164, 14166, -1, 14154, 14162, 14159, -1, 14156, 14162, 14154, -1, 14161, 14167, 14168, -1, 14159, 14167, 14155, -1, 14163, 14169, 14164, -1, 14155, 14167, 14160, -1, 14160, 14167, 14161, -1, 14166, 14170, 14171, -1, 12048, 14172, 14162, -1, 14164, 14170, 14166, -1, 14162, 14172, 14159, -1, 14159, 14172, 14167, -1, 14163, 14173, 14169, -1, 14168, 14174, 14175, -1, 14175, 14174, 14157, -1, 14164, 14176, 14170, -1, 14167, 14174, 14168, -1, 14169, 14176, 14164, -1, 14157, 14174, 13554, -1, 12055, 14177, 12048, -1, 12036, 14178, 12035, -1, 13554, 14177, 13539, -1, 12035, 14178, 14163, -1, 13539, 14177, 12055, -1, 14172, 14177, 14167, -1, 14163, 14178, 14173, -1, 14167, 14177, 14174, -1, 14171, 14128, 14179, -1, 12048, 14177, 14172, -1, 14174, 14177, 13554, -1, 14170, 14128, 14171, -1, 14173, 14133, 14169, -1, 14169, 14133, 14176, -1, 14170, 14137, 14128, -1, 14176, 14137, 14170, -1, 14173, 14132, 14133, -1, 12036, 14132, 14178, -1, 14178, 14132, 14173, -1, 14179, 14130, 14136, -1, 14128, 14130, 14179, -1, 14133, 14134, 14176, -1, 14176, 14134, 14137, -1, 14137, 14129, 14128, -1, 14180, 11709, 11708, -1, 14181, 14180, 11708, -1, 14182, 14181, 11708, -1, 14183, 14182, 11708, -1, 14184, 14182, 14183, -1, 14185, 14184, 14183, -1, 14186, 14187, 14188, -1, 14189, 14186, 14188, -1, 14190, 14191, 14189, -1, 14190, 14189, 14188, -1, 14192, 14191, 14190, -1, 14193, 14194, 14195, -1, 14196, 14197, 14193, -1, 14196, 14193, 14195, -1, 14198, 14197, 14196, -1, 14199, 14198, 14196, -1, 14200, 14201, 14202, -1, 14203, 14204, 14201, -1, 14204, 14205, 14201, -1, 14205, 14206, 14201, -1, 14206, 14207, 14201, -1, 14208, 14209, 14207, -1, 14207, 14209, 14201, -1, 14210, 14211, 14209, -1, 14209, 14211, 14201, -1, 14201, 14212, 14202, -1, 14213, 14214, 14211, -1, 14211, 14215, 14201, -1, 14201, 14215, 14212, -1, 14214, 14215, 14211, -1, 14186, 14152, 14161, -1, 14148, 14189, 14142, -1, 14189, 14136, 14142, -1, 14136, 14191, 14179, -1, 14189, 14191, 14136, -1, 14191, 14171, 14179, -1, 14191, 14166, 14171, -1, 14191, 14192, 14166, -1, 14192, 14165, 14166, -1, 14186, 14189, 14152, -1, 14152, 14189, 14148, -1, 14194, 13590, 13592, -1, 13597, 14193, 13604, -1, 14193, 13608, 13604, -1, 13608, 14197, 13610, -1, 14193, 14197, 13608, -1, 14197, 13612, 13610, -1, 14197, 13589, 13612, -1, 13589, 14198, 13546, -1, 14197, 14198, 13589, -1, 14198, 13547, 13546, -1, 14194, 14193, 13590, -1, 13590, 14193, 13597, -1, 14180, 13576, 13579, -1, 13576, 14181, 13572, -1, 14181, 13563, 13572, -1, 14181, 13558, 13563, -1, 13558, 14182, 13545, -1, 14181, 14182, 13558, -1, 14182, 13531, 13545, -1, 14182, 13529, 13531, -1, 14182, 13587, 13529, -1, 13616, 14184, 13614, -1, 13587, 14184, 13616, -1, 14184, 13607, 13614, -1, 14184, 13602, 13607, -1, 14184, 13600, 13602, -1, 13596, 14185, 13594, -1, 13600, 14185, 13596, -1, 14184, 14185, 13600, -1, 14185, 13593, 13594, -1, 14180, 14181, 13576, -1, 14182, 14184, 13587, -1, 14190, 14188, 14201, -1, 14190, 14201, 14200, -1, 14196, 14195, 14202, -1, 14196, 14202, 14212, -1, 14216, 14217, 14218, -1, 14219, 14216, 14218, -1, 14220, 14219, 14218, -1, 14221, 14220, 14218, -1, 14222, 14220, 14221, -1, 14223, 14222, 14221, -1, 14224, 14225, 14226, -1, 14227, 14224, 14226, -1, 14228, 14229, 14227, -1, 14228, 14227, 14226, -1, 14230, 14229, 14228, -1, 14231, 14232, 14233, -1, 11514, 14234, 14231, -1, 11514, 14231, 14233, -1, 14235, 14234, 11514, -1, 11825, 14235, 11514, -1, 11512, 11501, 11513, -1, 11512, 11502, 11501, -1, 11512, 11506, 11502, -1, 11512, 11509, 11506, -1, 11512, 11518, 11509, -1, 14236, 14237, 11512, -1, 14238, 14237, 14236, -1, 14237, 14239, 11512, -1, 11518, 14240, 11519, -1, 11512, 14240, 11518, -1, 14239, 14241, 11512, -1, 11512, 14242, 14240, -1, 11512, 14243, 14242, -1, 14241, 14244, 11512, -1, 11512, 14244, 14243, -1, 14224, 14245, 14246, -1, 14247, 14227, 14248, -1, 14227, 14249, 14248, -1, 14249, 14229, 14250, -1, 14227, 14229, 14249, -1, 14229, 14251, 14250, -1, 14229, 14252, 14251, -1, 14229, 14230, 14252, -1, 14230, 14253, 14252, -1, 14224, 14227, 14245, -1, 14245, 14227, 14247, -1, 14232, 14254, 14255, -1, 14256, 14231, 14257, -1, 14231, 14258, 14257, -1, 14258, 14234, 14259, -1, 14231, 14234, 14258, -1, 14234, 14260, 14259, -1, 14234, 14261, 14260, -1, 14234, 14235, 14261, -1, 14235, 14262, 14261, -1, 14232, 14231, 14254, -1, 14254, 14231, 14256, -1, 14216, 14263, 14264, -1, 14216, 14265, 14263, -1, 14265, 14219, 14266, -1, 14219, 14267, 14266, -1, 14219, 14268, 14267, -1, 14219, 14269, 14268, -1, 14269, 14220, 14270, -1, 14220, 14271, 14270, -1, 14220, 14272, 14271, -1, 14220, 14273, 14272, -1, 14273, 14222, 14274, -1, 14222, 14275, 14274, -1, 14222, 14276, 14275, -1, 14222, 14277, 14276, -1, 14277, 14223, 14278, -1, 14222, 14223, 14277, -1, 14223, 14279, 14278, -1, 14216, 14219, 14265, -1, 14219, 14220, 14269, -1, 14220, 14222, 14273, -1, 11512, 14233, 14236, -1, 11514, 14233, 11512, -1, 14228, 14226, 14237, -1, 14228, 14237, 14238, -1, 14280, 12123, 12125, -1, 14280, 12125, 14281, -1, 11542, 11544, 14282, -1, 11542, 14282, 14283, -1, 14284, 12121, 12123, -1, 14284, 12120, 12121, -1, 14284, 12123, 14280, -1, 12139, 14285, 14286, -1, 11540, 14283, 14287, -1, 11540, 11542, 14283, -1, 12137, 14286, 14288, -1, 12137, 12139, 14286, -1, 11523, 12120, 14284, -1, 12141, 14289, 14285, -1, 11537, 11540, 14287, -1, 12141, 14285, 12139, -1, 11537, 14287, 14290, -1, 12135, 14288, 14291, -1, 12135, 12137, 14288, -1, 11526, 14292, 12120, -1, 11526, 12120, 11523, -1, 12143, 14293, 14289, -1, 12143, 11554, 14293, -1, 11535, 14290, 14294, -1, 11535, 11537, 14290, -1, 12143, 14289, 12141, -1, 12133, 14291, 14295, -1, 11531, 14296, 14292, -1, 12133, 12135, 14291, -1, 11531, 14292, 11526, -1, 11533, 14294, 14297, -1, 11533, 11535, 14294, -1, 11532, 11533, 14297, -1, 11532, 14297, 14296, -1, 11532, 14296, 11531, -1, 12145, 11554, 12143, -1, 12131, 14295, 14298, -1, 12131, 12133, 14295, -1, 14299, 11552, 11554, -1, 14299, 11554, 12145, -1, 12129, 14298, 14300, -1, 12129, 12131, 14298, -1, 14301, 11550, 11552, -1, 14301, 11552, 14299, -1, 12127, 12129, 14300, -1, 14302, 11550, 14301, -1, 14302, 11549, 11550, -1, 14281, 12127, 14300, -1, 14281, 12125, 12127, -1, 14303, 11549, 14302, -1, 11544, 11549, 14303, -1, 11544, 14303, 14282, -1, 14304, 12153, 14305, -1, 14304, 12151, 12153, -1, 11603, 11605, 14306, -1, 11603, 14306, 14307, -1, 14308, 12151, 14304, -1, 14308, 12149, 12151, -1, 12167, 14309, 14310, -1, 11601, 14307, 14311, -1, 11601, 11603, 14307, -1, 12165, 14310, 14312, -1, 11587, 12148, 12149, -1, 12165, 12167, 14310, -1, 12169, 14313, 14309, -1, 12169, 14314, 14313, -1, 11587, 12149, 14308, -1, 12169, 14309, 12167, -1, 11599, 14311, 14315, -1, 11599, 11601, 14311, -1, 12163, 14312, 14316, -1, 12163, 12165, 14312, -1, 11589, 14317, 12148, -1, 11589, 12148, 11587, -1, 12171, 11614, 14314, -1, 12171, 14314, 12169, -1, 11597, 11599, 14315, -1, 12161, 14316, 14318, -1, 11597, 14315, 14319, -1, 12161, 12163, 14316, -1, 11591, 14320, 14317, -1, 11591, 14317, 11589, -1, 11595, 14321, 14322, -1, 11595, 14319, 14321, -1, 11595, 11597, 14319, -1, 12173, 11614, 12171, -1, 11593, 14322, 14320, -1, 11593, 11595, 14322, -1, 11593, 14320, 11591, -1, 12159, 14318, 14323, -1, 12159, 12161, 14318, -1, 14324, 11612, 11614, -1, 14324, 11611, 11612, -1, 14324, 11614, 12173, -1, 12157, 14323, 14325, -1, 12157, 12159, 14323, -1, 14326, 11611, 14324, -1, 12155, 12157, 14325, -1, 11610, 11611, 14326, -1, 14327, 11610, 14326, -1, 14305, 12155, 14325, -1, 14305, 12153, 12155, -1, 11605, 11610, 14327, -1, 11605, 14327, 14306, -1, 14328, 12094, 12096, -1, 14328, 12096, 14329, -1, 11574, 11576, 14330, -1, 11574, 14330, 14331, -1, 14332, 12094, 14328, -1, 14332, 12092, 12094, -1, 14332, 12090, 12092, -1, 12110, 14333, 14334, -1, 11572, 14331, 14335, -1, 12108, 14334, 14336, -1, 12108, 12110, 14334, -1, 11572, 11574, 14331, -1, 12112, 14337, 14333, -1, 11556, 12090, 14332, -1, 12112, 14333, 12110, -1, 12106, 14336, 14338, -1, 11570, 14335, 14339, -1, 12106, 12108, 14336, -1, 11570, 11572, 14335, -1, 11559, 14340, 12090, -1, 12114, 14341, 14337, -1, 12114, 11584, 14341, -1, 11559, 12090, 11556, -1, 12114, 14337, 12112, -1, 12104, 14338, 14342, -1, 11568, 14339, 14343, -1, 12104, 12106, 14338, -1, 11568, 11570, 14339, -1, 11563, 14344, 14340, -1, 11563, 14340, 11559, -1, 12116, 11584, 12114, -1, 11566, 11568, 14343, -1, 11564, 11566, 14343, -1, 11564, 14345, 14344, -1, 12102, 14342, 14346, -1, 11564, 14343, 14345, -1, 11564, 14344, 11563, -1, 12102, 12104, 14342, -1, 14347, 11582, 11584, -1, 14347, 11584, 12116, -1, 12100, 14346, 14348, -1, 12100, 12102, 14346, -1, 14349, 11580, 11582, -1, 14349, 11582, 14347, -1, 12098, 12100, 14348, -1, 14350, 11580, 14349, -1, 14350, 11578, 11580, -1, 14329, 12098, 14348, -1, 14329, 12096, 12098, -1, 14351, 11578, 14350, -1, 11576, 11578, 14351, -1, 11576, 14351, 14330, -1, 14352, 14353, 14354, -1, 14355, 12338, 14356, -1, 14357, 12338, 14355, -1, 14358, 12338, 14357, -1, 14359, 12337, 14360, -1, 14356, 12337, 14359, -1, 12338, 12337, 14356, -1, 14361, 14362, 14363, -1, 14364, 14362, 14361, -1, 14363, 14365, 14366, -1, 14362, 14365, 14363, -1, 14367, 14368, 14369, -1, 14366, 14368, 14367, -1, 14365, 14368, 14366, -1, 14370, 14371, 14372, -1, 14372, 14373, 14374, -1, 14371, 14373, 14372, -1, 14360, 12355, 14375, -1, 14374, 14376, 14377, -1, 14373, 14376, 14374, -1, 12337, 12355, 14360, -1, 14377, 14378, 14379, -1, 14376, 14378, 14377, -1, 14378, 14380, 14379, -1, 14379, 14380, 14381, -1, 14380, 14382, 14381, -1, 14381, 14382, 14383, -1, 14382, 14384, 14383, -1, 14385, 14386, 14387, -1, 14387, 14386, 14388, -1, 14388, 14389, 14390, -1, 14386, 14389, 14388, -1, 14390, 14391, 14392, -1, 14389, 14391, 14390, -1, 14392, 14393, 14394, -1, 14391, 14393, 14392, -1, 14394, 14395, 14396, -1, 14393, 14395, 14394, -1, 14396, 14397, 14398, -1, 14395, 14397, 14396, -1, 14399, 14400, 14401, -1, 14402, 14400, 14399, -1, 14400, 14403, 14401, -1, 14401, 14403, 14404, -1, 14403, 14405, 14404, -1, 14404, 14405, 14406, -1, 14406, 14407, 14408, -1, 14405, 14407, 14406, -1, 14407, 14409, 14408, -1, 14410, 14411, 14412, -1, 14413, 14414, 14415, -1, 14416, 14414, 14413, -1, 14414, 14417, 14415, -1, 14415, 14417, 14418, -1, 14417, 14419, 14418, -1, 14418, 14419, 14420, -1, 14412, 14421, 14422, -1, 14419, 14423, 14420, -1, 14420, 14423, 14424, -1, 14411, 14421, 14412, -1, 14424, 14425, 14358, -1, 14423, 14425, 14424, -1, 14426, 14427, 14428, -1, 14428, 14427, 14429, -1, 14430, 14431, 14426, -1, 14375, 14431, 14430, -1, 14427, 14431, 12386, -1, 14426, 14431, 14427, -1, 12355, 14431, 14375, -1, 12374, 14431, 12355, -1, 12386, 14431, 12374, -1, 14421, 14432, 14422, -1, 14429, 14433, 14434, -1, 12386, 14433, 14427, -1, 14427, 14433, 14429, -1, 14434, 14433, 14435, -1, 12400, 14433, 12386, -1, 14436, 14437, 14438, -1, 12423, 14437, 12412, -1, 14353, 14439, 14354, -1, 14440, 14439, 14441, -1, 14442, 14439, 14440, -1, 14354, 14439, 14442, -1, 14443, 14439, 14353, -1, 14444, 14439, 14443, -1, 14437, 14445, 14438, -1, 14352, 14445, 14353, -1, 12423, 14445, 14437, -1, 14438, 14445, 14352, -1, 12433, 14445, 12423, -1, 14446, 14447, 14448, -1, 14449, 14447, 14446, -1, 14444, 14450, 14451, -1, 14451, 14450, 14448, -1, 12335, 14450, 12439, -1, 14364, 14452, 14453, -1, 14454, 14452, 14361, -1, 14455, 14452, 14454, -1, 14449, 14452, 14447, -1, 14447, 14452, 14455, -1, 14453, 14452, 14449, -1, 14361, 14452, 14364, -1, 14448, 14456, 14446, -1, 14450, 14456, 14448, -1, 12335, 14456, 14450, -1, 12334, 14456, 12335, -1, 14365, 14457, 14368, -1, 14362, 14457, 14365, -1, 14458, 14457, 12362, -1, 14369, 14459, 14460, -1, 14457, 14459, 14368, -1, 14368, 14459, 14369, -1, 14458, 14459, 14457, -1, 14461, 14459, 14458, -1, 14462, 14463, 14410, -1, 14464, 14463, 14462, -1, 14460, 14463, 14464, -1, 14459, 14463, 14460, -1, 14461, 14463, 14459, -1, 14410, 14463, 14411, -1, 14411, 14463, 14461, -1, 14465, 14466, 14370, -1, 14370, 14466, 14371, -1, 14371, 14466, 14373, -1, 14467, 14468, 14465, -1, 14422, 14468, 14467, -1, 14432, 14468, 14422, -1, 14465, 14468, 14466, -1, 14466, 14468, 14469, -1, 14469, 14468, 14432, -1, 14373, 14470, 14376, -1, 14469, 14470, 14466, -1, 14471, 14470, 14469, -1, 14466, 14470, 14373, -1, 14376, 14470, 14378, -1, 14472, 14473, 14474, -1, 14383, 14473, 14475, -1, 14384, 14473, 14383, -1, 14474, 14473, 14384, -1, 14378, 14476, 14380, -1, 14470, 14476, 14378, -1, 14471, 14476, 14470, -1, 14477, 14476, 14471, -1, 14478, 14479, 14480, -1, 14384, 14479, 14474, -1, 14387, 14481, 14385, -1, 14482, 14481, 14387, -1, 14385, 14481, 14483, -1, 14483, 14481, 14484, -1, 14474, 14485, 14472, -1, 14472, 14485, 14486, -1, 14487, 14485, 14478, -1, 14478, 14485, 14479, -1, 14479, 14485, 14474, -1, 14485, 14488, 14486, -1, 14489, 14488, 14484, -1, 14490, 14488, 14487, -1, 14487, 14488, 14485, -1, 14486, 14488, 14489, -1, 14484, 14488, 14483, -1, 14488, 14491, 14483, -1, 14483, 14491, 14385, -1, 14492, 14491, 14490, -1, 14490, 14491, 14488, -1, 14389, 14493, 14391, -1, 14494, 14493, 14495, -1, 14493, 14496, 14391, -1, 14391, 14496, 14393, -1, 14393, 14496, 14395, -1, 14497, 14496, 14494, -1, 14494, 14496, 14493, -1, 14497, 14498, 14496, -1, 14398, 14498, 14499, -1, 14397, 14498, 14398, -1, 14395, 14498, 14397, -1, 14496, 14498, 14395, -1, 14500, 14501, 14502, -1, 14498, 14501, 14499, -1, 14503, 14501, 14500, -1, 14499, 14501, 14503, -1, 14502, 14501, 14497, -1, 14497, 14501, 14498, -1, 14504, 14505, 14402, -1, 14506, 14505, 14504, -1, 14402, 14505, 14400, -1, 14507, 14505, 14506, -1, 14508, 14505, 14507, -1, 14509, 14510, 14409, -1, 14408, 14510, 14511, -1, 14409, 14510, 14408, -1, 14512, 14510, 14509, -1, 14508, 14513, 14505, -1, 14505, 14513, 14400, -1, 14403, 14513, 14405, -1, 12358, 14513, 14508, -1, 14400, 14513, 14403, -1, 14409, 14514, 14509, -1, 12377, 14514, 12357, -1, 14515, 14516, 14517, -1, 12377, 14518, 14514, -1, 12384, 14518, 12377, -1, 14509, 14518, 14512, -1, 14512, 14518, 14519, -1, 14514, 14518, 14509, -1, 12384, 14520, 14518, -1, 14518, 14520, 14519, -1, 12392, 14520, 12384, -1, 14519, 14520, 14521, -1, 14521, 14520, 14517, -1, 14522, 14523, 14416, -1, 12406, 14523, 12399, -1, 14524, 14523, 14522, -1, 14502, 14525, 14500, -1, 14523, 14526, 14416, -1, 12406, 14526, 14523, -1, 12416, 14526, 12406, -1, 14527, 14525, 14528, -1, 14416, 14526, 14414, -1, 14529, 14525, 14527, -1, 14500, 14525, 14529, -1, 14414, 14526, 14417, -1, 14526, 14530, 14417, -1, 12416, 14530, 14526, -1, 14417, 14530, 14419, -1, 12421, 14530, 12416, -1, 14425, 14531, 14358, -1, 14358, 14531, 12338, -1, 12338, 14531, 12432, -1, 14532, 14533, 14436, -1, 14433, 14533, 14435, -1, 14435, 14533, 14532, -1, 14436, 14533, 14437, -1, 12400, 14534, 14433, -1, 14437, 14534, 12412, -1, 14533, 14534, 14437, -1, 14433, 14534, 14533, -1, 12412, 14534, 12400, -1, 14535, 14536, 14506, -1, 14528, 14536, 14535, -1, 14537, 14538, 14455, -1, 14441, 14538, 14537, -1, 14447, 14538, 14448, -1, 14455, 14538, 14447, -1, 14451, 14539, 14444, -1, 14444, 14539, 14439, -1, 14525, 14536, 14528, -1, 14441, 14539, 14538, -1, 14538, 14539, 14448, -1, 14448, 14539, 14451, -1, 14439, 14539, 14441, -1, 14445, 14540, 14353, -1, 14353, 14540, 14443, -1, 14443, 14540, 14444, -1, 14444, 14540, 14450, -1, 12433, 14541, 14445, -1, 14450, 14541, 12439, -1, 14540, 14541, 14450, -1, 14445, 14541, 14540, -1, 12439, 14541, 12433, -1, 14536, 14507, 14506, -1, 14449, 14542, 14453, -1, 14446, 14542, 14449, -1, 14456, 14542, 14446, -1, 12334, 14543, 14456, -1, 14456, 14543, 14542, -1, 12352, 14543, 12334, -1, 14453, 14544, 14364, -1, 14364, 14544, 14362, -1, 14362, 14544, 14457, -1, 12362, 14545, 12352, -1, 14457, 14545, 12362, -1, 14544, 14545, 14457, -1, 14546, 14547, 14548, -1, 14475, 14547, 14546, -1, 14473, 14547, 14475, -1, 14380, 14549, 14382, -1, 14384, 14549, 14479, -1, 14382, 14549, 14384, -1, 14476, 14549, 14380, -1, 14550, 14551, 14482, -1, 14548, 14551, 14550, -1, 14482, 14551, 14481, -1, 14547, 14551, 14548, -1, 14549, 14552, 14479, -1, 14479, 14552, 14480, -1, 14476, 14552, 14549, -1, 14480, 14552, 14477, -1, 14477, 14552, 14476, -1, 14491, 14553, 14385, -1, 14385, 14553, 14386, -1, 14389, 14553, 14493, -1, 14386, 14553, 14389, -1, 14491, 14554, 14553, -1, 14495, 14554, 14492, -1, 14553, 14554, 14493, -1, 14492, 14554, 14491, -1, 14493, 14554, 14495, -1, 14555, 14556, 14557, -1, 14511, 14556, 14555, -1, 14510, 14556, 14511, -1, 14405, 14558, 14407, -1, 14407, 14558, 14409, -1, 14409, 14558, 14514, -1, 14513, 14558, 14405, -1, 14559, 14560, 14561, -1, 14557, 14560, 14559, -1, 14556, 14560, 14557, -1, 14561, 14560, 14516, -1, 14514, 14562, 12357, -1, 12358, 14562, 14513, -1, 14513, 14562, 14558, -1, 12357, 14562, 12358, -1, 14558, 14562, 14514, -1, 14524, 14563, 14515, -1, 14522, 14563, 14524, -1, 14515, 14563, 14516, -1, 14517, 14564, 14515, -1, 14524, 14564, 14523, -1, 14515, 14564, 14524, -1, 14520, 14564, 14517, -1, 14520, 14565, 14564, -1, 12392, 14565, 14520, -1, 14523, 14565, 12399, -1, 12399, 14565, 12392, -1, 14564, 14565, 14523, -1, 14419, 14566, 14423, -1, 14423, 14566, 14425, -1, 14531, 14566, 12432, -1, 14530, 14566, 14419, -1, 14425, 14566, 14531, -1, 14530, 14567, 14566, -1, 14566, 14567, 12432, -1, 12421, 14567, 14530, -1, 12432, 14567, 12421, -1, 14453, 14568, 14544, -1, 14545, 14568, 12352, -1, 14542, 14568, 14453, -1, 14543, 14568, 14542, -1, 12352, 14568, 14543, -1, 14544, 14568, 14545, -1, 14472, 14569, 14473, -1, 14473, 14569, 14547, -1, 14486, 14569, 14472, -1, 14547, 14569, 14551, -1, 14484, 14569, 14489, -1, 14481, 14569, 14484, -1, 14489, 14569, 14486, -1, 14551, 14569, 14481, -1, 14512, 14570, 14510, -1, 14560, 14570, 14516, -1, 14521, 14570, 14519, -1, 14510, 14570, 14556, -1, 14519, 14570, 14512, -1, 14556, 14570, 14560, -1, 14516, 14570, 14517, -1, 14517, 14570, 14521, -1, 14416, 14571, 14522, -1, 14563, 14571, 14516, -1, 14572, 14571, 14413, -1, 14573, 14571, 14572, -1, 14561, 14571, 14573, -1, 14413, 14571, 14416, -1, 14516, 14571, 14561, -1, 14522, 14571, 14563, -1, 14428, 14429, 14574, -1, 14574, 14434, 14575, -1, 14429, 14434, 14574, -1, 14575, 14435, 14576, -1, 14434, 14435, 14575, -1, 14435, 14532, 14576, -1, 14576, 14532, 14577, -1, 14577, 14436, 14578, -1, 14532, 14436, 14577, -1, 14436, 14438, 14578, -1, 14578, 14438, 14579, -1, 14579, 14352, 14354, -1, 14438, 14352, 14579, -1, 14580, 14581, 14582, -1, 14583, 14584, 14585, -1, 14583, 14586, 14584, -1, 14583, 14587, 14586, -1, 14588, 14589, 13222, -1, 14588, 13222, 13221, -1, 14590, 13221, 13218, -1, 14590, 13218, 13217, -1, 14590, 13217, 14591, -1, 14590, 14580, 14589, -1, 14590, 14591, 14580, -1, 14590, 14588, 13221, -1, 14590, 14589, 14588, -1, 14592, 14593, 14587, -1, 14592, 14583, 14585, -1, 14592, 14587, 14583, -1, 14592, 14585, 14593, -1, 14594, 13239, 13269, -1, 14594, 13240, 13239, -1, 14594, 13269, 14595, -1, 14594, 13274, 13240, -1, 14596, 14597, 14598, -1, 14596, 14594, 14595, -1, 14596, 14595, 14599, -1, 14596, 14599, 14600, -1, 14596, 14600, 14597, -1, 14596, 13274, 14594, -1, 14596, 14598, 13274, -1, 14601, 14602, 14603, -1, 14601, 14604, 14605, -1, 14606, 13271, 13275, -1, 14601, 14607, 14608, -1, 14601, 14605, 14609, -1, 13272, 13271, 14606, -1, 14601, 14603, 14604, -1, 14601, 14609, 14607, -1, 14601, 14608, 14602, -1, 14610, 14611, 14612, -1, 14610, 14613, 14614, -1, 14610, 14615, 14613, -1, 14610, 14614, 14611, -1, 14610, 14612, 14615, -1, 14616, 13272, 14606, -1, 11301, 13272, 14616, -1, 14617, 11301, 14616, -1, 14617, 14616, 14618, -1, 14617, 14618, 14619, -1, 14593, 14585, 14620, -1, 14621, 14593, 14620, -1, 13231, 14622, 14623, -1, 13231, 14623, 13232, -1, 13253, 14621, 14622, -1, 13253, 14622, 13231, -1, 11291, 14593, 14621, -1, 11291, 14621, 13253, -1, 14595, 13269, 14599, -1, 14600, 14599, 14624, -1, 14625, 14624, 14598, -1, 14625, 14600, 14624, -1, 14597, 14625, 14598, -1, 14597, 14600, 14625, -1, 14626, 14624, 14627, -1, 14626, 14598, 14624, -1, 14626, 14628, 14598, -1, 14629, 14617, 14619, -1, 14629, 14619, 14630, -1, 14629, 14630, 14631, -1, 14632, 14626, 14627, -1, 14632, 14628, 14626, -1, 14633, 14629, 14631, -1, 14633, 14617, 14629, -1, 14633, 14634, 14617, -1, 14633, 14631, 14635, -1, 14636, 14632, 14627, -1, 14636, 14627, 14637, -1, 14636, 14628, 14632, -1, 14636, 14638, 14628, -1, 14639, 14633, 14635, -1, 14639, 14635, 14640, -1, 14639, 14634, 14633, -1, 14641, 14640, 14642, -1, 14641, 14639, 14640, -1, 14643, 14636, 14637, -1, 14643, 14638, 14636, -1, 14644, 14634, 14639, -1, 14644, 14645, 14634, -1, 14644, 14639, 14641, -1, 14646, 14641, 14642, -1, 14647, 14637, 14648, -1, 14647, 14643, 14637, -1, 14647, 14638, 14643, -1, 14647, 14649, 14638, -1, 14650, 14645, 14644, -1, 14650, 14644, 14641, -1, 14650, 14641, 14646, -1, 14651, 14642, 14652, -1, 14651, 14646, 14642, -1, 14653, 14648, 14654, -1, 14653, 14647, 14648, -1, 14653, 14649, 14647, -1, 14653, 14654, 14649, -1, 14655, 14645, 14650, -1, 14655, 14650, 14646, -1, 14655, 14646, 14651, -1, 14655, 14656, 14645, -1, 14657, 14651, 14652, -1, 14657, 14652, 14658, -1, 14659, 14648, 14660, -1, 14659, 14654, 14648, -1, 14661, 14655, 14651, -1, 14661, 14651, 14657, -1, 14661, 14656, 14655, -1, 14662, 14658, 14663, -1, 14662, 14657, 14658, -1, 14664, 14660, 14665, -1, 14664, 14659, 14660, -1, 14664, 14654, 14659, -1, 14664, 14665, 14654, -1, 14666, 14657, 14662, -1, 14666, 14667, 14656, -1, 14666, 14661, 14657, -1, 14666, 14656, 14661, -1, 14668, 14663, 14669, -1, 14668, 14662, 14663, -1, 14670, 14660, 14671, -1, 14670, 14665, 14660, -1, 14670, 14672, 14665, -1, 14673, 14667, 14666, -1, 14673, 14666, 14662, -1, 14673, 14662, 14668, -1, 14674, 14668, 14669, -1, 14675, 14672, 14670, -1, 14675, 14670, 14671, -1, 14676, 14668, 14674, -1, 14676, 14677, 14667, -1, 14676, 14673, 14668, -1, 14676, 14667, 14673, -1, 14678, 14674, 14669, -1, 14678, 14676, 14674, -1, 14678, 14677, 14676, -1, 14678, 14669, 14679, -1, 14680, 14672, 14675, -1, 14680, 14675, 14671, -1, 14680, 14681, 14672, -1, 14682, 14678, 14679, -1, 14682, 14679, 14683, -1, 14684, 14671, 14685, -1, 14684, 14681, 14680, -1, 14684, 14680, 14671, -1, 14684, 14686, 14681, -1, 14687, 14678, 14682, -1, 14687, 14688, 14677, -1, 14687, 14677, 14678, -1, 14689, 14682, 14683, -1, 14689, 14683, 14690, -1, 14689, 14688, 14687, -1, 14689, 14687, 14682, -1, 14691, 14684, 14685, -1, 14691, 14686, 14684, -1, 14692, 14690, 14693, -1, 14692, 14689, 14690, -1, 14694, 14695, 14696, -1, 14694, 14685, 14695, -1, 14694, 14686, 14691, -1, 14694, 14691, 14685, -1, 14694, 14696, 14686, -1, 14697, 14698, 14688, -1, 14697, 14689, 14692, -1, 14697, 14688, 14689, -1, 14699, 14697, 14692, -1, 14699, 14698, 14697, -1, 14699, 14692, 14693, -1, 14700, 14701, 14702, -1, 14703, 14696, 14695, -1, 14700, 14702, 14704, -1, 14703, 14695, 14705, -1, 14703, 14706, 14696, -1, 14707, 14699, 14693, -1, 14707, 14693, 14708, -1, 14709, 14703, 14705, -1, 14710, 14700, 14711, -1, 14709, 14706, 14703, -1, 14712, 14699, 14707, -1, 14712, 14698, 14699, -1, 14712, 14713, 14698, -1, 14712, 14707, 14708, -1, 14714, 14712, 14708, -1, 14714, 14713, 14712, -1, 14714, 14708, 14715, -1, 14716, 14709, 14705, -1, 14716, 14717, 14706, -1, 14716, 14706, 14709, -1, 14718, 14714, 14715, -1, 14608, 14705, 14602, -1, 14608, 14716, 14705, -1, 14608, 14717, 14716, -1, 14608, 14607, 14717, -1, 14719, 14720, 14713, -1, 14719, 14713, 14714, -1, 14719, 14714, 14718, -1, 14721, 14701, 14720, -1, 14721, 14718, 14715, -1, 14721, 14720, 14719, -1, 14721, 14715, 14722, -1, 14721, 14719, 14718, -1, 14609, 14605, 14607, -1, 14723, 14702, 14701, -1, 14723, 14722, 14702, -1, 14723, 14721, 14722, -1, 14723, 14701, 14721, -1, 14724, 14700, 14710, -1, 14604, 14725, 14605, -1, 14726, 14725, 14604, -1, 14726, 14727, 14728, -1, 14724, 14710, 14729, -1, 14726, 14728, 14730, -1, 14726, 14604, 14603, -1, 14726, 14730, 14725, -1, 14731, 14711, 14700, -1, 14731, 14700, 14704, -1, 14731, 14704, 14732, -1, 14731, 14732, 14733, -1, 14731, 14733, 14711, -1, 14734, 14735, 14736, -1, 14734, 14736, 14727, -1, 14734, 14726, 14603, -1, 14734, 14727, 14726, -1, 14737, 14603, 14738, -1, 14737, 14734, 14603, -1, 14739, 14735, 14734, -1, 14739, 14740, 14741, -1, 14739, 14741, 14742, -1, 14739, 14742, 14735, -1, 14743, 14734, 14737, -1, 14743, 14737, 14738, -1, 14744, 14740, 14739, -1, 14744, 14724, 14729, -1, 14744, 14729, 14740, -1, 14745, 14739, 14734, -1, 14745, 14734, 14743, -1, 14746, 14743, 14738, -1, 14747, 14748, 14724, -1, 14747, 14724, 14744, -1, 14747, 14739, 14745, -1, 14747, 14744, 14739, -1, 14749, 14745, 14743, -1, 14750, 14751, 14752, -1, 14749, 14743, 14746, -1, 14753, 14738, 14754, -1, 14753, 14746, 14738, -1, 14755, 14748, 14747, -1, 14755, 14745, 14749, -1, 14755, 14747, 14745, -1, 14756, 14749, 14746, -1, 14756, 14746, 14753, -1, 14757, 14754, 14758, -1, 14757, 14753, 14754, -1, 14759, 14748, 14755, -1, 14759, 14760, 14748, -1, 14759, 14755, 14749, -1, 14759, 14749, 14756, -1, 14761, 14753, 14757, -1, 14761, 14756, 14753, -1, 14761, 14757, 14758, -1, 14762, 14760, 14759, -1, 14762, 14759, 14756, -1, 14763, 14764, 14765, -1, 14762, 14756, 14761, -1, 14766, 14761, 14758, -1, 14766, 14758, 14767, -1, 14768, 14761, 14766, -1, 14768, 14762, 14761, -1, 14768, 14769, 14760, -1, 14768, 14760, 14762, -1, 14770, 14766, 14767, -1, 14771, 14768, 14766, -1, 14771, 14766, 14770, -1, 14771, 14769, 14768, -1, 14772, 14767, 14773, -1, 14772, 14770, 14767, -1, 14774, 14772, 14773, -1, 14774, 14769, 14771, -1, 14774, 14770, 14772, -1, 14774, 14775, 14769, -1, 14774, 14771, 14770, -1, 14774, 14773, 14775, -1, 14776, 14773, 14777, -1, 14776, 14777, 14778, -1, 14776, 14775, 14773, -1, 14779, 14778, 14751, -1, 14779, 14750, 14775, -1, 14779, 14776, 14778, -1, 14779, 14775, 14776, -1, 14779, 14751, 14750, -1, 14780, 14752, 14781, -1, 14780, 14781, 14782, -1, 14780, 14763, 14750, -1, 14780, 14750, 14752, -1, 14783, 14780, 14782, -1, 14783, 14764, 14763, -1, 14783, 14782, 14764, -1, 14783, 14763, 14780, -1, 14784, 14763, 14765, -1, 14784, 14785, 14763, -1, 14784, 14765, 14786, -1, 14784, 14786, 14787, -1, 14788, 14789, 14785, -1, 14788, 14787, 14790, -1, 14788, 14790, 14789, -1, 14788, 14784, 14787, -1, 14788, 14785, 14784, -1, 14791, 14785, 14789, -1, 14791, 14789, 14792, -1, 14793, 14792, 14794, -1, 14793, 14791, 14792, -1, 14795, 14794, 14796, -1, 14797, 14785, 14791, -1, 14797, 14798, 14785, -1, 14797, 14791, 14793, -1, 14799, 14793, 14794, -1, 14799, 14794, 14795, -1, 14799, 14795, 14796, -1, 14799, 14798, 14797, -1, 14799, 14797, 14793, -1, 14800, 14796, 14801, -1, 14802, 14799, 14796, -1, 14802, 14796, 14800, -1, 14803, 14800, 14801, -1, 14804, 14805, 14798, -1, 14804, 14798, 14799, -1, 14804, 14799, 14802, -1, 14806, 14801, 14807, -1, 14806, 14803, 14801, -1, 14808, 14805, 14804, -1, 14808, 14802, 14800, -1, 14808, 14800, 14803, -1, 14808, 14804, 14802, -1, 14809, 14806, 14807, -1, 14809, 14803, 14806, -1, 14810, 14807, 14811, -1, 14812, 14808, 14803, -1, 14812, 14803, 14809, -1, 14813, 14809, 14807, -1, 14813, 14807, 14810, -1, 14814, 14815, 14805, -1, 14814, 14805, 14808, -1, 14814, 14808, 14812, -1, 14816, 14811, 14817, -1, 14816, 14810, 14811, -1, 14818, 14815, 14814, -1, 14818, 14812, 14809, -1, 14818, 14809, 14813, -1, 14818, 14814, 14812, -1, 14819, 14820, 14821, -1, 14819, 14821, 14822, -1, 14819, 14813, 14810, -1, 14819, 14816, 14820, -1, 14819, 14810, 14816, -1, 14823, 14816, 14817, -1, 14823, 14824, 14825, -1, 14823, 14825, 14820, -1, 14823, 14820, 14816, -1, 14826, 14813, 14819, -1, 14826, 14822, 14827, -1, 14826, 14827, 14828, -1, 14826, 14819, 14822, -1, 14826, 14818, 14813, -1, 14829, 14817, 14830, -1, 14829, 14823, 14817, -1, 14831, 14826, 14828, -1, 14831, 14832, 14815, -1, 14831, 14833, 14832, -1, 14831, 14818, 14826, -1, 14831, 14828, 14833, -1, 14831, 14815, 14818, -1, 14834, 14824, 14823, -1, 14835, 14832, 14833, -1, 14834, 14829, 14830, -1, 14834, 14823, 14829, -1, 14834, 14830, 14836, -1, 14834, 14836, 14824, -1, 14837, 14836, 14830, -1, 14838, 14830, 14839, -1, 14838, 14837, 14830, -1, 14840, 14841, 14842, -1, 14840, 14843, 14841, -1, 14840, 14842, 14844, -1, 14840, 14844, 14845, -1, 14840, 14845, 14846, -1, 14840, 14846, 14843, -1, 14847, 14838, 14848, -1, 14847, 14836, 14837, -1, 14847, 14837, 14838, -1, 14847, 14848, 14836, -1, 14849, 14848, 14838, -1, 14849, 14838, 14839, -1, 14849, 14839, 14850, -1, 14849, 14851, 14848, -1, 14852, 14849, 14850, -1, 14852, 14851, 14849, -1, 14853, 14854, 14855, -1, 14853, 14855, 14856, -1, 14857, 14853, 14856, -1, 14857, 14856, 14858, -1, 14859, 14852, 14850, -1, 14859, 14851, 14852, -1, 14859, 14850, 14860, -1, 14859, 14861, 14851, -1, 14862, 14863, 14854, -1, 14862, 14853, 14857, -1, 14862, 14854, 14853, -1, 14841, 14832, 14835, -1, 14864, 14857, 14858, -1, 14841, 14835, 14842, -1, 14864, 14858, 14865, -1, 14866, 14859, 14860, -1, 14866, 14861, 14859, -1, 14855, 14841, 14843, -1, 14867, 14862, 14857, -1, 14867, 14863, 14862, -1, 14867, 14857, 14864, -1, 14868, 14864, 14865, -1, 14868, 14865, 14869, -1, 14870, 14860, 14871, -1, 14870, 14861, 14866, -1, 14870, 14872, 14861, -1, 14870, 14866, 14860, -1, 14873, 14874, 14863, -1, 14873, 14863, 14867, -1, 14873, 14867, 14864, -1, 14873, 14864, 14868, -1, 14875, 14868, 14869, -1, 14875, 14869, 14876, -1, 14854, 14841, 14855, -1, 14877, 14870, 14871, -1, 14877, 14872, 14870, -1, 14877, 14878, 14872, -1, 14879, 14874, 14873, -1, 14879, 14873, 14868, -1, 14879, 14868, 14875, -1, 14880, 14875, 14876, -1, 14880, 14876, 14881, -1, 14882, 14871, 14883, -1, 14882, 14877, 14871, -1, 14882, 14878, 14877, -1, 14884, 14879, 14875, -1, 14884, 14885, 14874, -1, 14884, 14874, 14879, -1, 14884, 14875, 14880, -1, 14886, 14880, 14881, -1, 14886, 14881, 14887, -1, 14888, 14882, 14883, -1, 14888, 14883, 14889, -1, 14888, 14889, 14878, -1, 14888, 14878, 14882, -1, 14890, 14880, 14886, -1, 14890, 14885, 14884, -1, 14890, 14884, 14880, -1, 14891, 14886, 14887, -1, 14892, 14889, 14883, -1, 14892, 14883, 14893, -1, 14892, 14894, 14889, -1, 14895, 14611, 14885, -1, 14895, 14890, 14886, -1, 14895, 14885, 14890, -1, 14895, 14886, 14891, -1, 14612, 14895, 14891, -1, 14612, 14611, 14895, -1, 14612, 14887, 14615, -1, 14612, 14891, 14887, -1, 14896, 14892, 14893, -1, 14896, 14894, 14892, -1, 14613, 14615, 14897, -1, 14898, 14896, 14893, -1, 14898, 14894, 14896, -1, 14898, 14899, 14900, -1, 14898, 14893, 14899, -1, 14898, 14900, 14894, -1, 14901, 14614, 14613, -1, 14901, 14613, 14897, -1, 14901, 14897, 14902, -1, 14903, 14900, 14899, -1, 14903, 14899, 14904, -1, 14903, 14905, 14900, -1, 14906, 14901, 14902, -1, 14906, 14902, 14907, -1, 14908, 14903, 14904, -1, 14908, 14905, 14903, -1, 14909, 14910, 14614, -1, 14909, 14901, 14906, -1, 14909, 14614, 14901, -1, 14911, 14910, 14909, -1, 14911, 14906, 14907, -1, 14911, 14909, 14906, -1, 14912, 14908, 14904, -1, 14912, 14905, 14908, -1, 14912, 14904, 14913, -1, 14912, 14914, 14905, -1, 14915, 14911, 14907, -1, 14915, 14907, 14916, -1, 14917, 14912, 14913, -1, 14917, 14914, 14912, -1, 14917, 14918, 14914, -1, 14919, 14920, 14910, -1, 14919, 14911, 14915, -1, 14919, 14910, 14911, -1, 14921, 14917, 14913, -1, 14921, 14918, 14917, -1, 14921, 14913, 14922, -1, 14923, 14924, 14920, -1, 14923, 14915, 14916, -1, 14923, 14920, 14919, -1, 14923, 14919, 14915, -1, 14923, 14916, 14925, -1, 14926, 14923, 14925, -1, 14927, 14918, 14921, -1, 14927, 14921, 14922, -1, 14927, 14922, 14582, -1, 14927, 14928, 14918, -1, 14929, 14923, 14926, -1, 14929, 14924, 14923, -1, 14930, 14926, 14925, -1, 14930, 14929, 14926, -1, 14930, 14924, 14929, -1, 14930, 14925, 14931, -1, 14932, 14927, 14582, -1, 14932, 14928, 14927, -1, 14932, 14581, 14928, -1, 14932, 14582, 14581, -1, 14586, 14931, 14584, -1, 14586, 14587, 14924, -1, 14586, 14924, 14930, -1, 14586, 14930, 14931, -1, 14580, 14582, 14589, -1, 14580, 14591, 14581, -1, 14933, 14934, 14935, -1, 14933, 14936, 14937, -1, 14933, 14937, 14938, -1, 14933, 14938, 14934, -1, 14939, 14940, 14941, -1, 14939, 14942, 14936, -1, 14939, 14933, 14940, -1, 14939, 14936, 14933, -1, 14943, 14941, 14944, -1, 14943, 14939, 14941, -1, 14943, 14942, 14939, -1, 14943, 14945, 14946, -1, 14943, 14946, 14942, -1, 14947, 14944, 14948, -1, 14947, 14948, 14949, -1, 14947, 14945, 14943, -1, 14947, 14943, 14944, -1, 14947, 14950, 14945, -1, 14951, 14947, 14949, -1, 14951, 14949, 14952, -1, 14951, 14953, 14954, -1, 14951, 14954, 14950, -1, 14951, 14950, 14947, -1, 14955, 14952, 14956, -1, 14955, 14957, 14953, -1, 14955, 14953, 14951, -1, 14955, 14951, 14952, -1, 14958, 14956, 14959, -1, 14958, 14959, 14960, -1, 14958, 14957, 14955, -1, 14958, 14955, 14956, -1, 14958, 14961, 14962, -1, 14958, 14962, 14957, -1, 14963, 14961, 14958, -1, 14963, 14960, 14964, -1, 14963, 14958, 14960, -1, 14963, 14965, 14961, -1, 14966, 14964, 14967, -1, 14966, 14968, 14965, -1, 14966, 14965, 14963, -1, 14966, 14963, 14964, -1, 14969, 14967, 14970, -1, 14969, 14970, 14971, -1, 14969, 14966, 14967, -1, 14969, 14972, 14973, -1, 14969, 14968, 14966, -1, 14969, 14973, 14968, -1, 14974, 14971, 14975, -1, 14974, 14976, 14972, -1, 14974, 14972, 14969, -1, 14974, 14969, 14971, -1, 14977, 14976, 14974, -1, 14977, 14975, 14978, -1, 14977, 14978, 14979, -1, 14977, 14980, 14981, -1, 14977, 14981, 14976, -1, 14977, 14974, 14975, -1, 14982, 14980, 14977, -1, 14982, 14977, 14979, -1, 14982, 14979, 14983, -1, 14982, 14984, 14980, -1, 14985, 14982, 14983, -1, 14985, 14984, 14982, -1, 14985, 14983, 14986, -1, 14985, 14987, 14988, -1, 14985, 14988, 14984, -1, 14989, 14985, 14986, -1, 14989, 14986, 14990, -1, 14989, 14990, 14991, -1, 14989, 14987, 14985, -1, 14989, 14992, 14987, -1, 14993, 14991, 14994, -1, 14993, 14989, 14991, -1, 14993, 14992, 14989, -1, 14993, 14995, 14996, -1, 14993, 14996, 14992, -1, 14997, 14994, 14998, -1, 14997, 14999, 14995, -1, 14997, 14993, 14994, -1, 14997, 14995, 14993, -1, 15000, 14998, 15001, -1, 15000, 15001, 15002, -1, 15000, 14997, 14998, -1, 15000, 15003, 14999, -1, 15000, 14999, 14997, -1, 15004, 15002, 15005, -1, 15004, 15006, 15007, -1, 15004, 15007, 15003, -1, 15004, 15000, 15002, -1, 15004, 15003, 15000, -1, 15008, 15005, 15009, -1, 15008, 15009, 15010, -1, 15008, 15011, 15006, -1, 15008, 15004, 15005, -1, 15008, 15006, 15004, -1, 15012, 15008, 15010, -1, 15012, 15010, 15013, -1, 15012, 15014, 15015, -1, 15012, 15015, 15011, -1, 15012, 15011, 15008, -1, 15016, 15014, 15012, -1, 15016, 15013, 15017, -1, 15016, 15018, 15014, -1, 15016, 15012, 15013, -1, 15019, 11297, 15020, -1, 15019, 15020, 15021, -1, 15022, 12951, 11297, -1, 15022, 11297, 15019, -1, 15022, 15019, 15021, -1, 15022, 15023, 12951, -1, 15022, 15021, 15023, -1, 15024, 15016, 15017, -1, 15024, 15017, 11440, -1, 15024, 11440, 12991, -1, 15025, 15016, 15024, -1, 15025, 15018, 15016, -1, 15025, 15024, 12991, -1, 15025, 12991, 15018, -1, 15021, 15020, 15026, -1, 15021, 15027, 15023, -1, 15028, 15026, 15029, -1, 15028, 15030, 15031, -1, 15028, 15031, 15027, -1, 15028, 15021, 15026, -1, 15028, 15027, 15021, -1, 15032, 15029, 15033, -1, 15032, 15033, 15034, -1, 15032, 15030, 15028, -1, 15032, 15028, 15029, -1, 15032, 15035, 15030, -1, 14934, 15034, 14935, -1, 14934, 15032, 15034, -1, 14934, 15035, 15032, -1, 14934, 14938, 15035, -1, 14933, 14935, 15036, -1, 14933, 15036, 14940, -1, 15037, 15038, 15039, -1, 15037, 15040, 15038, -1, 15041, 15039, 15042, -1, 15041, 15037, 15039, -1, 15043, 15042, 15044, -1, 15043, 15041, 15042, -1, 15045, 12775, 12994, -1, 15045, 12994, 15046, -1, 15047, 15044, 15048, -1, 15047, 15043, 15044, -1, 15049, 15046, 15050, -1, 15049, 15045, 15046, -1, 15051, 15048, 15052, -1, 15051, 15047, 15048, -1, 15053, 15050, 15054, -1, 15053, 15049, 15050, -1, 15055, 15052, 15056, -1, 15055, 15051, 15052, -1, 15057, 15054, 15058, -1, 15057, 15053, 15054, -1, 15059, 15056, 15060, -1, 15059, 15055, 15056, -1, 15061, 15057, 15058, -1, 15061, 15058, 15062, -1, 15063, 15060, 15064, -1, 15065, 15061, 15062, -1, 15063, 15059, 15060, -1, 15065, 15062, 15066, -1, 15067, 15064, 15068, -1, 15069, 15066, 15070, -1, 15067, 15063, 15064, -1, 15069, 15065, 15066, -1, 15071, 15068, 15072, -1, 15073, 15069, 15070, -1, 15071, 15067, 15068, -1, 15073, 15070, 15074, -1, 15075, 15072, 15076, -1, 15077, 15074, 15078, -1, 15077, 15073, 15074, -1, 15075, 15071, 15072, -1, 15079, 15075, 15076, -1, 15079, 15076, 15080, -1, 15081, 15078, 15082, -1, 15081, 15077, 15078, -1, 15083, 15079, 15080, -1, 15084, 15082, 15085, -1, 15083, 15080, 15086, -1, 15084, 15081, 15082, -1, 15087, 15083, 15086, -1, 15088, 15085, 15089, -1, 15087, 15086, 15090, -1, 15088, 15084, 15085, -1, 15091, 15087, 15090, -1, 15092, 15089, 15093, -1, 15091, 15090, 15094, -1, 15092, 15088, 15089, -1, 15095, 15091, 15094, -1, 15096, 15093, 15097, -1, 15095, 15094, 15098, -1, 15096, 15092, 15093, -1, 15099, 15095, 15098, -1, 15100, 15097, 15101, -1, 15099, 15098, 15102, -1, 15100, 15096, 15097, -1, 15103, 15099, 15102, -1, 15103, 15102, 15104, -1, 15105, 15101, 15106, -1, 15105, 15100, 15101, -1, 15107, 15103, 15104, -1, 15107, 15104, 15108, -1, 15109, 15106, 15110, -1, 15109, 15105, 15106, -1, 15111, 15107, 15108, -1, 15111, 15108, 15112, -1, 15040, 15110, 15038, -1, 15040, 15109, 15110, -1, 12782, 15112, 12985, -1, 12782, 15111, 15112, -1, 15113, 15114, 15115, -1, 15116, 15117, 15118, -1, 15116, 15113, 15117, -1, 15119, 15118, 15120, -1, 15119, 15116, 15118, -1, 15121, 13170, 12256, -1, 15121, 12256, 15122, -1, 15123, 15120, 15124, -1, 15123, 15119, 15120, -1, 15125, 15122, 15126, -1, 15125, 15121, 15122, -1, 15127, 15124, 15128, -1, 15127, 15123, 15124, -1, 15129, 15126, 15130, -1, 15129, 15125, 15126, -1, 15131, 15128, 15132, -1, 15131, 15127, 15128, -1, 15133, 15130, 15134, -1, 15133, 15129, 15130, -1, 15135, 15132, 15136, -1, 15135, 15131, 15132, -1, 15137, 15133, 15134, -1, 15137, 15134, 15138, -1, 15139, 15136, 15140, -1, 15139, 15135, 15136, -1, 15141, 15138, 15142, -1, 15141, 15137, 15138, -1, 15143, 15140, 15144, -1, 15143, 15139, 15140, -1, 15145, 15142, 15146, -1, 15145, 15141, 15142, -1, 15147, 15144, 15148, -1, 15149, 15146, 15150, -1, 15147, 15143, 15144, -1, 15149, 15145, 15146, -1, 15151, 15148, 15152, -1, 15153, 15149, 15150, -1, 15151, 15147, 15148, -1, 15153, 15150, 15154, -1, 15155, 15152, 15156, -1, 15157, 15154, 15158, -1, 15157, 15153, 15154, -1, 15155, 15151, 15152, -1, 15159, 15155, 15156, -1, 15160, 15158, 15161, -1, 15159, 15156, 15162, -1, 15160, 15157, 15158, -1, 15163, 15159, 15162, -1, 15163, 15162, 15164, -1, 15165, 15161, 15166, -1, 15165, 15160, 15161, -1, 15167, 15163, 15164, -1, 15168, 15166, 15169, -1, 15167, 15164, 15170, -1, 15168, 15165, 15166, -1, 15171, 15167, 15170, -1, 15172, 15169, 15173, -1, 15171, 15170, 15174, -1, 15172, 15168, 15169, -1, 15175, 15171, 15174, -1, 15175, 15174, 15176, -1, 15177, 15173, 15178, -1, 15177, 15172, 15173, -1, 15179, 15175, 15176, -1, 15179, 15176, 15180, -1, 15181, 15178, 15182, -1, 15181, 15177, 15178, -1, 15183, 15179, 15180, -1, 15183, 15180, 15184, -1, 15185, 15182, 15186, -1, 15185, 15181, 15182, -1, 13139, 15183, 15184, -1, 13139, 15184, 12312, -1, 15114, 15186, 15115, -1, 15114, 15185, 15186, -1, 15113, 15115, 15117, -1, 11915, 15153, 15157, -1, 11911, 15149, 15153, -1, 11911, 15153, 11915, -1, 11918, 15157, 15160, -1, 11918, 11915, 15157, -1, 11908, 15145, 15149, -1, 11908, 15149, 11911, -1, 11924, 15160, 15165, -1, 11924, 11918, 15160, -1, 11905, 15145, 11908, -1, 15141, 15145, 11905, -1, 11926, 15165, 15168, -1, 11926, 11924, 15165, -1, 11895, 15141, 11905, -1, 15137, 15141, 11895, -1, 11931, 15168, 15172, -1, 11931, 11926, 15168, -1, 11885, 15137, 11895, -1, 15133, 15137, 11885, -1, 11933, 15172, 15177, -1, 11933, 11931, 15172, -1, 11882, 15133, 11885, -1, 15129, 15133, 11882, -1, 11936, 15177, 15181, -1, 11936, 11933, 15177, -1, 11879, 15129, 11882, -1, 15125, 15129, 11879, -1, 11856, 15181, 15185, -1, 11856, 11936, 15181, -1, 11869, 15125, 11879, -1, 15121, 15125, 11869, -1, 11857, 11856, 15185, -1, 11857, 15185, 15114, -1, 11864, 15121, 11869, -1, 11863, 13170, 15121, -1, 11863, 15121, 11864, -1, 11877, 11857, 15114, -1, 11877, 15114, 15113, -1, 13168, 13170, 11863, -1, 11884, 11877, 15113, -1, 11884, 15113, 15116, -1, 15187, 13168, 11863, -1, 13166, 13168, 15187, -1, 11886, 11884, 15116, -1, 11886, 15116, 15119, -1, 15188, 13166, 15187, -1, 13164, 13166, 15188, -1, 11890, 11886, 15119, -1, 11890, 15119, 15123, -1, 15189, 13164, 15188, -1, 13162, 13164, 15189, -1, 11893, 15123, 15127, -1, 11893, 11890, 15123, -1, 15190, 13162, 15189, -1, 13160, 13162, 15190, -1, 11897, 15127, 15131, -1, 11897, 11893, 15127, -1, 15191, 13160, 15190, -1, 13158, 13160, 15191, -1, 11903, 15131, 15135, -1, 11903, 11897, 15131, -1, 15192, 13158, 15191, -1, 13156, 13158, 15192, -1, 11906, 15135, 15139, -1, 11906, 11903, 15135, -1, 15193, 13156, 15192, -1, 13154, 13156, 15193, -1, 15194, 13154, 15193, -1, 11910, 15139, 15143, -1, 11910, 11906, 15139, -1, 13152, 13154, 15194, -1, 15195, 13152, 15194, -1, 11914, 15143, 15147, -1, 11914, 11910, 15143, -1, 11920, 11914, 15147, -1, 13150, 13152, 15195, -1, 13150, 15195, 15196, -1, 15151, 11920, 15147, -1, 11922, 11920, 15151, -1, 13148, 13150, 15196, -1, 13148, 15196, 15197, -1, 15155, 11922, 15151, -1, 11930, 11922, 15155, -1, 13146, 13148, 15197, -1, 13146, 15197, 15198, -1, 15159, 11930, 15155, -1, 11938, 11930, 15159, -1, 13144, 15198, 15199, -1, 13144, 13146, 15198, -1, 15163, 11938, 15159, -1, 11851, 11938, 15163, -1, 13142, 15199, 15200, -1, 13142, 13144, 15199, -1, 15167, 11851, 15163, -1, 11854, 11851, 15167, -1, 13140, 15200, 15201, -1, 13140, 13142, 15200, -1, 15171, 11854, 15167, -1, 11861, 11854, 15171, -1, 13138, 15201, 15202, -1, 13138, 13140, 15201, -1, 15175, 11861, 15171, -1, 13136, 15202, 15203, -1, 13136, 13138, 15202, -1, 15179, 11861, 15175, -1, 15179, 11867, 11861, -1, 11870, 11867, 15179, -1, 13137, 15203, 15204, -1, 13137, 13136, 15203, -1, 15183, 11870, 15179, -1, 11873, 11870, 15183, -1, 13139, 11873, 15183, -1, 13174, 13137, 15204, -1, 13174, 15204, 15205, -1, 15206, 11873, 13139, -1, 13141, 15206, 13139, -1, 13173, 15205, 15207, -1, 13173, 13174, 15205, -1, 15208, 15206, 13141, -1, 13143, 15208, 13141, -1, 13172, 15207, 15209, -1, 13172, 13173, 15207, -1, 13145, 15210, 15208, -1, 13145, 15208, 13143, -1, 13171, 15209, 15211, -1, 13171, 13172, 15209, -1, 13147, 15210, 13145, -1, 13147, 15212, 15210, -1, 13169, 15211, 15213, -1, 13169, 13171, 15211, -1, 15214, 15212, 13147, -1, 13149, 15214, 13147, -1, 13167, 13169, 15213, -1, 13167, 15213, 15215, -1, 15216, 15214, 13149, -1, 13151, 15216, 13149, -1, 13165, 15215, 15217, -1, 13165, 13167, 15215, -1, 15218, 15216, 13151, -1, 13153, 15219, 15218, -1, 13153, 15218, 13151, -1, 13163, 15217, 15220, -1, 13163, 13165, 15217, -1, 13155, 15221, 15219, -1, 13155, 15219, 13153, -1, 13161, 15220, 15222, -1, 13161, 13163, 15220, -1, 13157, 15223, 15221, -1, 13157, 15221, 13155, -1, 13159, 15222, 15223, -1, 13159, 13161, 15222, -1, 13159, 15223, 13157, -1, 15224, 15225, 15226, -1, 15224, 15226, 15227, -1, 15228, 14946, 15229, -1, 15228, 15229, 15225, -1, 15228, 15225, 15224, -1, 15228, 14942, 14946, -1, 15230, 15078, 15074, -1, 15230, 15227, 15078, -1, 15231, 15227, 15230, -1, 15231, 15224, 15227, -1, 15232, 15228, 15224, -1, 15232, 14942, 15228, -1, 15232, 15224, 15231, -1, 15232, 14936, 14942, -1, 15233, 15074, 15070, -1, 15233, 15230, 15074, -1, 15234, 15230, 15233, -1, 15234, 15231, 15230, -1, 15235, 15232, 15231, -1, 15235, 14936, 15232, -1, 15235, 15231, 15234, -1, 15235, 14937, 14936, -1, 15235, 14938, 14937, -1, 15236, 15070, 15066, -1, 15236, 15233, 15070, -1, 15237, 15234, 15233, -1, 15237, 15233, 15236, -1, 15238, 15235, 15234, -1, 15238, 14938, 15235, -1, 15238, 15234, 15237, -1, 15239, 15066, 15062, -1, 15239, 15236, 15066, -1, 15240, 15237, 15236, -1, 15240, 15236, 15239, -1, 15241, 15237, 15240, -1, 15241, 15238, 15237, -1, 15241, 14938, 15238, -1, 15241, 15035, 14938, -1, 15242, 15062, 15058, -1, 15242, 15239, 15062, -1, 15243, 15239, 15242, -1, 15243, 15240, 15239, -1, 15244, 15241, 15240, -1, 15244, 15035, 15241, -1, 15244, 15240, 15243, -1, 15244, 15030, 15035, -1, 15245, 15058, 15054, -1, 15245, 15242, 15058, -1, 15246, 15243, 15242, -1, 15246, 15242, 15245, -1, 15247, 15244, 15243, -1, 15247, 15030, 15244, -1, 15247, 15031, 15030, -1, 15247, 15243, 15246, -1, 15247, 15027, 15031, -1, 15248, 15054, 15050, -1, 15248, 15245, 15054, -1, 15249, 15246, 15245, -1, 15249, 15245, 15248, -1, 15250, 15246, 15249, -1, 15250, 15027, 15247, -1, 15250, 15247, 15246, -1, 15251, 15050, 15046, -1, 15251, 15046, 12996, -1, 15251, 15248, 15050, -1, 15252, 15248, 15251, -1, 15252, 12996, 12998, -1, 15252, 15251, 12996, -1, 15252, 15249, 15248, -1, 15253, 15249, 15252, -1, 15253, 12998, 12952, -1, 15253, 15252, 12998, -1, 15253, 12952, 15023, -1, 15253, 15023, 15027, -1, 15253, 15250, 15249, -1, 15253, 15027, 15250, -1, 12996, 15046, 12994, -1, 12951, 15023, 12952, -1, 15254, 12986, 12985, -1, 15254, 12985, 15112, -1, 15255, 12988, 12986, -1, 15255, 12986, 15254, -1, 15256, 12990, 12988, -1, 15256, 12991, 12990, -1, 15256, 12988, 15255, -1, 15256, 15018, 12991, -1, 15257, 15254, 15112, -1, 15257, 15112, 15108, -1, 15258, 15255, 15254, -1, 15258, 15254, 15257, -1, 15259, 15255, 15258, -1, 15259, 15014, 15018, -1, 15259, 15018, 15256, -1, 15259, 15256, 15255, -1, 15260, 15108, 15104, -1, 15260, 15257, 15108, -1, 15261, 15257, 15260, -1, 15261, 15258, 15257, -1, 15262, 15259, 15258, -1, 15262, 15258, 15261, -1, 15262, 15015, 15014, -1, 15262, 15014, 15259, -1, 15263, 15260, 15104, -1, 15263, 15104, 15102, -1, 15264, 15261, 15260, -1, 15264, 15260, 15263, -1, 15265, 15261, 15264, -1, 15265, 15011, 15015, -1, 15265, 15262, 15261, -1, 15265, 15015, 15262, -1, 15266, 15102, 15098, -1, 15266, 15263, 15102, -1, 15267, 15264, 15263, -1, 15267, 15263, 15266, -1, 15268, 15264, 15267, -1, 15268, 15265, 15264, -1, 15268, 15011, 15265, -1, 15268, 15006, 15011, -1, 15269, 15098, 15094, -1, 15269, 15266, 15098, -1, 15270, 15267, 15266, -1, 15270, 15266, 15269, -1, 15271, 15007, 15006, -1, 15271, 15267, 15270, -1, 15271, 15268, 15267, -1, 15271, 15006, 15268, -1, 15272, 15094, 15090, -1, 15272, 15269, 15094, -1, 15273, 15270, 15269, -1, 15273, 15269, 15272, -1, 15274, 15007, 15271, -1, 15274, 15271, 15270, -1, 15274, 15003, 15007, -1, 15274, 15270, 15273, -1, 15275, 15272, 15090, -1, 15275, 15090, 15086, -1, 15276, 15273, 15272, -1, 15276, 15272, 15275, -1, 15277, 15003, 15274, -1, 15277, 15273, 15276, -1, 15277, 14999, 15003, -1, 15277, 15274, 15273, -1, 15278, 15086, 15080, -1, 15278, 15275, 15086, -1, 15279, 15275, 15278, -1, 15279, 15276, 15275, -1, 15280, 15276, 15279, -1, 15280, 14999, 15277, -1, 15280, 14995, 14999, -1, 15280, 15277, 15276, -1, 15281, 15278, 15080, -1, 15281, 15080, 15076, -1, 15282, 15279, 15278, -1, 15282, 15278, 15281, -1, 15283, 14995, 15280, -1, 15283, 15280, 15279, -1, 15283, 14996, 14995, -1, 15283, 15279, 15282, -1, 15284, 15281, 15076, -1, 15284, 15076, 15072, -1, 15285, 15281, 15284, -1, 15285, 15282, 15281, -1, 15286, 14996, 15283, -1, 15286, 15283, 15282, -1, 15286, 14992, 14996, -1, 15286, 15282, 15285, -1, 15287, 15284, 15072, -1, 15287, 15072, 15068, -1, 15288, 15285, 15284, -1, 15288, 15284, 15287, -1, 15289, 14987, 14992, -1, 15289, 14992, 15286, -1, 15289, 15286, 15285, -1, 15289, 15285, 15288, -1, 15290, 15287, 15068, -1, 15290, 15068, 15064, -1, 15291, 15287, 15290, -1, 15291, 15288, 15287, -1, 15292, 14988, 14987, -1, 15292, 14987, 15289, -1, 15292, 15289, 15288, -1, 15292, 15288, 15291, -1, 15293, 15064, 15060, -1, 15293, 15290, 15064, -1, 15294, 15291, 15290, -1, 15294, 15290, 15293, -1, 15295, 14984, 14988, -1, 15295, 14988, 15292, -1, 15295, 15292, 15291, -1, 15295, 15291, 15294, -1, 15296, 15060, 15056, -1, 15296, 15293, 15060, -1, 15297, 15293, 15296, -1, 15297, 15294, 15293, -1, 15298, 14980, 14984, -1, 15298, 14981, 14980, -1, 15298, 14984, 15295, -1, 15298, 15295, 15294, -1, 15298, 15294, 15297, -1, 15299, 15056, 15052, -1, 15299, 15296, 15056, -1, 15300, 15296, 15299, -1, 15300, 15297, 15296, -1, 15301, 15298, 15297, -1, 15301, 15297, 15300, -1, 15301, 14981, 15298, -1, 15302, 15052, 15048, -1, 15302, 15299, 15052, -1, 15303, 15299, 15302, -1, 15303, 15300, 15299, -1, 15304, 15301, 15300, -1, 15304, 14981, 15301, -1, 15304, 15300, 15303, -1, 15304, 14976, 14981, -1, 15304, 14972, 14976, -1, 15305, 15048, 15044, -1, 15305, 15302, 15048, -1, 15306, 15303, 15302, -1, 15306, 15302, 15305, -1, 15307, 15304, 15303, -1, 15307, 14972, 15304, -1, 15307, 15303, 15306, -1, 15308, 15044, 15042, -1, 15308, 15305, 15044, -1, 15309, 15305, 15308, -1, 15309, 15306, 15305, -1, 15310, 14972, 15307, -1, 15310, 15307, 15306, -1, 15310, 14973, 14972, -1, 15310, 15306, 15309, -1, 15311, 15042, 15039, -1, 15311, 15308, 15042, -1, 15312, 15309, 15308, -1, 15312, 15308, 15311, -1, 15313, 15310, 15309, -1, 15313, 14973, 15310, -1, 15313, 15309, 15312, -1, 15313, 14968, 14973, -1, 15313, 14965, 14968, -1, 15314, 15039, 15038, -1, 15314, 15311, 15039, -1, 15315, 15312, 15311, -1, 15315, 15311, 15314, -1, 15316, 15313, 15312, -1, 15316, 14965, 15313, -1, 15316, 15312, 15315, -1, 15317, 15038, 15110, -1, 15317, 15314, 15038, -1, 15318, 15315, 15314, -1, 15318, 15314, 15317, -1, 15319, 14965, 15316, -1, 15319, 15316, 15315, -1, 15319, 15315, 15318, -1, 15319, 14961, 14965, -1, 15320, 15110, 15106, -1, 15320, 15317, 15110, -1, 15321, 15318, 15317, -1, 15321, 15317, 15320, -1, 15322, 15319, 15318, -1, 15322, 14961, 15319, -1, 15322, 15318, 15321, -1, 15322, 14962, 14961, -1, 15323, 15106, 15101, -1, 15323, 15320, 15106, -1, 15324, 15321, 15320, -1, 15324, 15320, 15323, -1, 15325, 14957, 14962, -1, 15325, 15322, 15321, -1, 15325, 14962, 15322, -1, 15325, 14953, 14957, -1, 15325, 15321, 15324, -1, 15326, 15101, 15097, -1, 15326, 15323, 15101, -1, 15327, 15324, 15323, -1, 15327, 15323, 15326, -1, 15328, 15324, 15327, -1, 15328, 14953, 15325, -1, 15328, 15325, 15324, -1, 15329, 15097, 15093, -1, 15329, 15326, 15097, -1, 15330, 15326, 15329, -1, 15330, 15327, 15326, -1, 15331, 14954, 14953, -1, 15331, 14953, 15328, -1, 15331, 15328, 15327, -1, 15331, 15327, 15330, -1, 15332, 15093, 15089, -1, 15332, 15329, 15093, -1, 15333, 15329, 15332, -1, 15333, 15330, 15329, -1, 15334, 15330, 15333, -1, 15334, 14950, 14954, -1, 15334, 14954, 15331, -1, 15334, 15331, 15330, -1, 15335, 15089, 15085, -1, 15335, 15332, 15089, -1, 15336, 15333, 15332, -1, 15336, 15332, 15335, -1, 15337, 15334, 15333, -1, 15337, 15333, 15336, -1, 15337, 14945, 14950, -1, 15337, 14946, 14945, -1, 15337, 14950, 15334, -1, 15226, 15335, 15085, -1, 15226, 15085, 15082, -1, 15225, 15335, 15226, -1, 15225, 15336, 15335, -1, 15229, 15337, 15336, -1, 15229, 14946, 15337, -1, 15229, 15336, 15225, -1, 15227, 15082, 15078, -1, 15227, 15226, 15082, -1, 15338, 15043, 15047, -1, 15338, 15339, 15043, -1, 15340, 15341, 15339, -1, 15340, 15339, 15338, -1, 15342, 15343, 15341, -1, 15342, 15341, 15340, -1, 15344, 15345, 15343, -1, 15344, 15346, 15345, -1, 15344, 15343, 15342, -1, 15344, 15347, 15346, -1, 15348, 15047, 15051, -1, 15045, 12773, 12775, -1, 15348, 15338, 15047, -1, 15349, 15340, 15338, -1, 15349, 15338, 15348, -1, 15350, 12258, 12779, -1, 15351, 15342, 15340, -1, 15351, 15340, 15349, -1, 15352, 15344, 15342, -1, 15352, 15347, 15344, -1, 15352, 15342, 15351, -1, 15352, 15353, 15347, -1, 15354, 15051, 15055, -1, 15354, 15348, 15051, -1, 15355, 15348, 15354, -1, 15355, 15349, 15348, -1, 15356, 15351, 15349, -1, 15356, 15349, 15355, -1, 15357, 15352, 15351, -1, 15357, 15353, 15352, -1, 15357, 15351, 15356, -1, 15357, 15358, 15353, -1, 15359, 15055, 15059, -1, 15359, 15354, 15055, -1, 15360, 15354, 15359, -1, 15360, 15355, 15354, -1, 15361, 15355, 15360, -1, 15361, 15356, 15355, -1, 15362, 15357, 15356, -1, 15362, 15358, 15357, -1, 15362, 15363, 15358, -1, 15362, 15356, 15361, -1, 15364, 15059, 15063, -1, 15364, 15359, 15059, -1, 15365, 15359, 15364, -1, 15365, 15360, 15359, -1, 15366, 15361, 15360, -1, 15366, 15360, 15365, -1, 15367, 15368, 15363, -1, 15367, 15361, 15366, -1, 15367, 15363, 15362, -1, 15367, 15362, 15361, -1, 15369, 15063, 15067, -1, 15369, 15364, 15063, -1, 15370, 15364, 15369, -1, 15370, 15365, 15364, -1, 15371, 15366, 15365, -1, 15371, 15365, 15370, -1, 15372, 15373, 15368, -1, 15372, 15368, 15367, -1, 15372, 15367, 15366, -1, 15372, 15366, 15371, -1, 15374, 15067, 15071, -1, 15374, 15369, 15067, -1, 15375, 15370, 15369, -1, 15375, 15369, 15374, -1, 15376, 15370, 15375, -1, 15376, 15371, 15370, -1, 15377, 15371, 15376, -1, 15377, 15378, 15379, -1, 15377, 15379, 15373, -1, 15377, 15373, 15372, -1, 15377, 15372, 15371, -1, 15380, 15071, 15075, -1, 15380, 15374, 15071, -1, 15381, 15374, 15380, -1, 15381, 15375, 15374, -1, 15382, 15376, 15375, -1, 15382, 15375, 15381, -1, 15383, 15377, 15376, -1, 15383, 15376, 15382, -1, 15383, 15384, 15378, -1, 15383, 15378, 15377, -1, 15385, 15075, 15079, -1, 15385, 15380, 15075, -1, 15386, 15380, 15385, -1, 15386, 15381, 15380, -1, 15387, 15382, 15381, -1, 15387, 15381, 15386, -1, 15388, 15383, 15382, -1, 15388, 15384, 15383, -1, 15388, 15382, 15387, -1, 15389, 15079, 15083, -1, 15389, 15385, 15079, -1, 15390, 15386, 15385, -1, 15390, 15385, 15389, -1, 15391, 15387, 15386, -1, 15391, 15386, 15390, -1, 15392, 15384, 15388, -1, 15392, 15388, 15387, -1, 15392, 15387, 15391, -1, 15392, 15393, 15384, -1, 15394, 15083, 15087, -1, 15394, 15389, 15083, -1, 15395, 15389, 15394, -1, 15395, 15390, 15389, -1, 15396, 15391, 15390, -1, 15396, 15390, 15395, -1, 15397, 15392, 15391, -1, 15397, 15393, 15392, -1, 15397, 15391, 15396, -1, 15397, 15398, 15393, -1, 15399, 15087, 15091, -1, 15399, 15394, 15087, -1, 15400, 15394, 15399, -1, 15400, 15395, 15394, -1, 15401, 15396, 15395, -1, 15401, 15395, 15400, -1, 15402, 15396, 15401, -1, 15402, 15397, 15396, -1, 15402, 15398, 15397, -1, 15402, 15403, 15398, -1, 15404, 15091, 15095, -1, 15404, 15399, 15091, -1, 15405, 15399, 15404, -1, 15405, 15400, 15399, -1, 15406, 15401, 15400, -1, 15406, 15400, 15405, -1, 15407, 15408, 15403, -1, 15407, 15402, 15401, -1, 15407, 15403, 15402, -1, 15407, 15401, 15406, -1, 15409, 15095, 15099, -1, 15409, 15404, 15095, -1, 15410, 15405, 15404, -1, 15410, 15404, 15409, -1, 15411, 15405, 15410, -1, 15411, 15406, 15405, -1, 15412, 15413, 15408, -1, 15412, 15408, 15407, -1, 15412, 15407, 15406, -1, 12315, 15414, 12712, -1, 15412, 15406, 15411, -1, 15415, 12886, 12773, -1, 15416, 15099, 15103, -1, 15416, 15409, 15099, -1, 15415, 12773, 15045, -1, 15417, 15410, 15409, -1, 15418, 12889, 12886, -1, 15417, 15409, 15416, -1, 15418, 12886, 15415, -1, 15419, 12892, 12889, -1, 15419, 12889, 15418, -1, 15420, 15411, 15410, -1, 15421, 15350, 12779, -1, 15420, 15410, 15417, -1, 15421, 12779, 12892, -1, 15422, 15413, 15412, -1, 15421, 12892, 15419, -1, 15422, 15423, 15413, -1, 15422, 15412, 15411, -1, 15422, 15411, 15420, -1, 15424, 15045, 15049, -1, 15425, 15103, 15107, -1, 15424, 15415, 15045, -1, 15425, 15416, 15103, -1, 15426, 15418, 15415, -1, 15426, 15415, 15424, -1, 15427, 15416, 15425, -1, 15428, 15418, 15426, -1, 15427, 15417, 15416, -1, 15429, 15417, 15427, -1, 15428, 15419, 15418, -1, 15430, 15419, 15428, -1, 15429, 15420, 15417, -1, 15430, 15431, 15350, -1, 15432, 15423, 15422, -1, 15430, 15421, 15419, -1, 15432, 15422, 15420, -1, 15430, 15350, 15421, -1, 15432, 15420, 15429, -1, 15432, 15433, 15423, -1, 15434, 15049, 15053, -1, 15435, 15111, 12782, -1, 15434, 15424, 15049, -1, 15435, 15107, 15111, -1, 15435, 12782, 12784, -1, 15436, 15424, 15434, -1, 15436, 15426, 15424, -1, 15435, 15425, 15107, -1, 15437, 15425, 15435, -1, 15437, 12784, 12788, -1, 15438, 15428, 15426, -1, 15438, 15426, 15436, -1, 15437, 15427, 15425, -1, 15437, 15435, 12784, -1, 15439, 15431, 15430, -1, 15440, 15429, 15427, -1, 15439, 15428, 15438, -1, 15439, 15430, 15428, -1, 15440, 15427, 15437, -1, 15440, 15437, 12788, -1, 15439, 15441, 15431, -1, 15440, 12788, 12791, -1, 15442, 15434, 15053, -1, 15443, 15432, 15429, -1, 15443, 15433, 15432, -1, 15442, 15053, 15057, -1, 15443, 15429, 15440, -1, 15443, 15440, 12791, -1, 15443, 12791, 12794, -1, 15443, 12794, 12712, -1, 15444, 15436, 15434, -1, 15443, 15414, 15433, -1, 15443, 12712, 15414, -1, 15444, 15434, 15442, -1, 15445, 15438, 15436, -1, 15445, 15436, 15444, -1, 15446, 15441, 15439, -1, 15446, 15439, 15438, -1, 15446, 15447, 15441, -1, 15446, 15438, 15445, -1, 15448, 15442, 15057, -1, 15448, 15057, 15061, -1, 15449, 15442, 15448, -1, 15449, 15444, 15442, -1, 15450, 15445, 15444, -1, 15450, 15444, 15449, -1, 15451, 15446, 15445, -1, 15451, 15445, 15450, -1, 15451, 15452, 15447, -1, 15451, 15447, 15446, -1, 15453, 15448, 15061, -1, 15453, 15061, 15065, -1, 15454, 15448, 15453, -1, 15454, 15449, 15448, -1, 15455, 15450, 15449, -1, 15455, 15449, 15454, -1, 15456, 15450, 15455, -1, 15456, 15451, 15450, -1, 15456, 15457, 15452, -1, 15456, 15452, 15451, -1, 15458, 15065, 15069, -1, 15458, 15453, 15065, -1, 15459, 15453, 15458, -1, 15459, 15454, 15453, -1, 15460, 15455, 15454, -1, 15460, 15454, 15459, -1, 15461, 15456, 15455, -1, 15461, 15455, 15460, -1, 15461, 15457, 15456, -1, 15461, 15462, 15457, -1, 15463, 15458, 15069, -1, 15463, 15069, 15073, -1, 15464, 15459, 15458, -1, 15464, 15458, 15463, -1, 15465, 15460, 15459, -1, 15465, 15459, 15464, -1, 15466, 15460, 15465, -1, 15466, 15462, 15461, -1, 15466, 15461, 15460, -1, 15466, 15467, 15462, -1, 15468, 15073, 15077, -1, 15468, 15463, 15073, -1, 15469, 15464, 15463, -1, 15469, 15463, 15468, -1, 15470, 15464, 15469, -1, 15470, 15465, 15464, -1, 15471, 15467, 15466, -1, 15471, 15466, 15465, -1, 15471, 15465, 15470, -1, 15471, 15472, 15467, -1, 15473, 15077, 15081, -1, 15473, 15468, 15077, -1, 15474, 15468, 15473, -1, 15474, 15469, 15468, -1, 15475, 15470, 15469, -1, 15475, 15469, 15474, -1, 15476, 15470, 15475, -1, 15476, 15477, 15472, -1, 15476, 15471, 15470, -1, 15476, 15472, 15471, -1, 15478, 15081, 15084, -1, 15478, 15473, 15081, -1, 15479, 15474, 15473, -1, 15479, 15473, 15478, -1, 15480, 15474, 15479, -1, 15480, 15475, 15474, -1, 15481, 15475, 15480, -1, 15481, 15482, 15477, -1, 15481, 15477, 15476, -1, 15481, 15476, 15475, -1, 15483, 15084, 15088, -1, 15483, 15478, 15084, -1, 15484, 15478, 15483, -1, 15484, 15479, 15478, -1, 15485, 15480, 15479, -1, 15485, 15479, 15484, -1, 15486, 15481, 15480, -1, 15486, 15482, 15481, -1, 15486, 15480, 15485, -1, 15486, 15487, 15482, -1, 15488, 15088, 15092, -1, 15488, 15483, 15088, -1, 15489, 15483, 15488, -1, 15489, 15484, 15483, -1, 15490, 15485, 15484, -1, 15490, 15484, 15489, -1, 15491, 15485, 15490, -1, 15491, 15486, 15485, -1, 15491, 15487, 15486, -1, 15491, 15492, 15487, -1, 15493, 15092, 15096, -1, 15493, 15488, 15092, -1, 15494, 15489, 15488, -1, 15494, 15488, 15493, -1, 15495, 15490, 15489, -1, 15495, 15489, 15494, -1, 15496, 15491, 15490, -1, 15496, 15492, 15491, -1, 15496, 15490, 15495, -1, 15496, 15497, 15492, -1, 15498, 15096, 15100, -1, 15498, 15493, 15096, -1, 15499, 15494, 15493, -1, 15499, 15493, 15498, -1, 15500, 15495, 15494, -1, 15500, 15494, 15499, -1, 15501, 15496, 15495, -1, 15501, 15497, 15496, -1, 15501, 15495, 15500, -1, 15501, 15502, 15497, -1, 15503, 15100, 15105, -1, 15503, 15498, 15100, -1, 15504, 15499, 15498, -1, 15504, 15498, 15503, -1, 15505, 15500, 15499, -1, 15505, 15499, 15504, -1, 15506, 15501, 15500, -1, 15506, 15502, 15501, -1, 15506, 15500, 15505, -1, 15506, 15507, 15502, -1, 15508, 15105, 15109, -1, 15508, 15503, 15105, -1, 15509, 15504, 15503, -1, 15509, 15503, 15508, -1, 15510, 15505, 15504, -1, 15510, 15504, 15509, -1, 15511, 15505, 15510, -1, 15511, 15506, 15505, -1, 15511, 15507, 15506, -1, 15511, 15512, 15507, -1, 15513, 15109, 15040, -1, 15513, 15508, 15109, -1, 15514, 15509, 15508, -1, 15514, 15508, 15513, -1, 15515, 15510, 15509, -1, 15515, 15509, 15514, -1, 15516, 15517, 15512, -1, 15516, 15511, 15510, -1, 15516, 15512, 15511, -1, 15516, 15510, 15515, -1, 15518, 15040, 15037, -1, 15518, 15513, 15040, -1, 15519, 15514, 15513, -1, 15519, 15513, 15518, -1, 15520, 15514, 15519, -1, 15520, 15515, 15514, -1, 15521, 15522, 15517, -1, 15521, 15517, 15516, -1, 15521, 15516, 15515, -1, 15521, 15515, 15520, -1, 15523, 15037, 15041, -1, 15523, 15518, 15037, -1, 15524, 15518, 15523, -1, 15524, 15519, 15518, -1, 15525, 15519, 15524, -1, 15525, 15520, 15519, -1, 15526, 15521, 15520, -1, 15526, 15527, 15522, -1, 15526, 15520, 15525, -1, 15526, 15522, 15521, -1, 15339, 15041, 15043, -1, 15339, 15523, 15041, -1, 15341, 15523, 15339, -1, 15341, 15524, 15523, -1, 15343, 15525, 15524, -1, 15343, 15524, 15341, -1, 15345, 15525, 15343, -1, 15345, 15527, 15526, -1, 15345, 15346, 15527, -1, 15345, 15526, 15525, -1, 15528, 15529, 15530, -1, 15529, 15531, 15530, -1, 15531, 15532, 15530, -1, 15532, 15533, 15530, -1, 15534, 15535, 15533, -1, 15536, 15535, 15534, -1, 15537, 15535, 15536, -1, 15533, 15535, 15530, -1, 15537, 15538, 15535, -1, 15539, 15540, 15541, -1, 15540, 15542, 15541, -1, 15542, 15543, 15541, -1, 15543, 15544, 15541, -1, 15545, 15546, 15544, -1, 15547, 15546, 15545, -1, 15548, 15546, 15547, -1, 15544, 15546, 15541, -1, 15548, 15549, 15546, -1, 15550, 15551, 15552, -1, 15551, 15553, 15552, -1, 15553, 15554, 15552, -1, 15554, 15555, 15552, -1, 15556, 12455, 15555, -1, 15557, 12455, 15556, -1, 15558, 12455, 15557, -1, 15555, 12455, 15552, -1, 15558, 12456, 12455, -1, 12452, 12450, 15559, -1, 12453, 12452, 15559, -1, 12455, 15559, 15560, -1, 12455, 15560, 15561, -1, 12455, 15561, 15562, -1, 12455, 12453, 15559, -1, 15563, 12455, 15562, -1, 15564, 15565, 15546, -1, 15566, 15546, 15565, -1, 15567, 15564, 15546, -1, 15568, 15546, 15569, -1, 15568, 15569, 15570, -1, 15568, 15570, 15571, -1, 15568, 15571, 15572, -1, 15568, 15572, 15573, -1, 15568, 15567, 15546, -1, 15574, 15573, 15575, -1, 15574, 15575, 15576, -1, 15574, 15576, 15577, -1, 15574, 15577, 15530, -1, 15574, 15568, 15573, -1, 15535, 15578, 15530, -1, 15579, 15574, 15530, -1, 15535, 15580, 15581, -1, 15535, 15581, 12464, -1, 15535, 12464, 12462, -1, 15535, 12462, 12459, -1, 15535, 12459, 12458, -1, 15535, 12458, 15578, -1, 15582, 15579, 15530, -1, 15583, 15582, 15530, -1, 15584, 15580, 15535, -1, 15578, 15583, 15530, -1, 15585, 15580, 15584, -1, 15552, 15586, 15587, -1, 15552, 15587, 15588, -1, 15552, 15588, 15589, -1, 15552, 15589, 15590, -1, 15552, 15590, 15580, -1, 15591, 15580, 15585, -1, 15592, 15552, 15580, -1, 15593, 15580, 15591, -1, 15594, 15592, 15580, -1, 15595, 15541, 15546, -1, 15596, 15580, 15593, -1, 15595, 15546, 15566, -1, 15597, 15594, 15580, -1, 15598, 15541, 15595, -1, 15597, 15580, 15596, -1, 15552, 12455, 15586, -1, 15586, 12455, 15563, -1, 15599, 15541, 15598, -1, 15600, 15541, 15599, -1, 15601, 15541, 15600, -1, 15601, 12446, 12444, -1, 15601, 12444, 12442, -1, 15601, 12442, 15602, -1, 15601, 15602, 15603, -1, 15601, 15603, 15541, -1, 15559, 12446, 15601, -1, 15559, 12450, 12448, -1, 15559, 12448, 12446, -1, 15604, 15605, 15578, -1, 15606, 15604, 15578, -1, 15607, 15606, 15578, -1, 15608, 15607, 15578, -1, 12458, 15609, 15610, -1, 12458, 15610, 15608, -1, 12458, 15608, 15578, -1, 12460, 15609, 12458, -1, 15611, 15612, 15595, -1, 15613, 15611, 15595, -1, 15614, 15613, 15595, -1, 15615, 15614, 15595, -1, 15566, 15616, 15617, -1, 15566, 15617, 15615, -1, 15566, 15615, 15595, -1, 15618, 15616, 15566, -1, 15619, 15620, 15586, -1, 15621, 15619, 15586, -1, 15622, 15621, 15586, -1, 15623, 15622, 15586, -1, 15563, 15624, 15625, -1, 15563, 15625, 15623, -1, 15563, 15623, 15586, -1, 15626, 15624, 15563, -1, 15627, 15628, 15629, -1, 15629, 15628, 15630, -1, 15630, 15631, 15632, -1, 15628, 15631, 15630, -1, 15632, 15633, 15634, -1, 15631, 15633, 15632, -1, 15634, 15635, 15636, -1, 15633, 15635, 15634, -1, 15636, 15637, 15638, -1, 15635, 15637, 15636, -1, 15637, 15639, 15638, -1, 15638, 15640, 15641, -1, 15639, 15640, 15638, -1, 15641, 15642, 15643, -1, 15640, 15642, 15641, -1, 15643, 15644, 15645, -1, 15642, 15644, 15643, -1, 15645, 15646, 15647, -1, 15644, 15646, 15645, -1, 15646, 15648, 15647, -1, 15647, 15649, 15650, -1, 15648, 15649, 15647, -1, 15650, 15651, 12688, -1, 15649, 15651, 15650, -1, 15651, 12689, 12688, -1, 15652, 15653, 15654, -1, 15655, 15629, 15653, -1, 15656, 15629, 15655, -1, 15653, 15629, 15654, -1, 15656, 15627, 15629, -1, 15657, 15658, 11251, -1, 11251, 15658, 11257, -1, 11257, 15659, 11247, -1, 15658, 15659, 11257, -1, 11247, 15660, 11242, -1, 15659, 15660, 11247, -1, 11242, 15661, 11237, -1, 15660, 15661, 11242, -1, 11237, 15662, 11232, -1, 15661, 15662, 11237, -1, 15662, 15663, 11232, -1, 11232, 15664, 11227, -1, 15663, 15664, 11232, -1, 11227, 15665, 11218, -1, 15664, 15665, 11227, -1, 11218, 15666, 11216, -1, 15665, 15666, 11218, -1, 11216, 15667, 11263, -1, 15666, 15667, 11216, -1, 11263, 15668, 11261, -1, 15667, 15668, 11263, -1, 15668, 15669, 11261, -1, 11261, 15670, 11260, -1, 15669, 15670, 11261, -1, 15671, 15672, 15673, -1, 11260, 15672, 15671, -1, 15670, 15672, 11260, -1, 15673, 15674, 15654, -1, 15672, 15674, 15673, -1, 15674, 15652, 15654, -1, 12695, 15675, 12694, -1, 15676, 11251, 15675, -1, 15677, 11251, 15676, -1, 15675, 11251, 12694, -1, 15677, 15657, 11251, -1, 15678, 15679, 15680, -1, 15681, 15678, 15680, -1, 15682, 15678, 15681, -1, 15683, 15682, 15684, -1, 11273, 15683, 15685, -1, 11273, 15685, 15686, -1, 11273, 15686, 15687, -1, 11273, 15687, 15688, -1, 11273, 15678, 15682, -1, 11273, 15682, 15683, -1, 11274, 11273, 11272, -1, 11276, 15678, 11273, -1, 11276, 11273, 11274, -1, 15689, 15678, 11276, -1, 15690, 15691, 15689, -1, 15692, 15690, 15689, -1, 15693, 15692, 15689, -1, 15694, 15695, 15696, -1, 15694, 15696, 15693, -1, 15694, 15693, 15689, -1, 15697, 15698, 15699, -1, 15697, 15699, 15694, -1, 15697, 15694, 15689, -1, 15700, 15689, 11276, -1, 15700, 15697, 15689, -1, 15701, 15697, 15700, -1, 15702, 15701, 15700, -1, 15703, 15704, 15705, -1, 15705, 15704, 15706, -1, 15706, 15707, 15708, -1, 15704, 15707, 15706, -1, 15708, 12664, 12663, -1, 15707, 12664, 15708, -1, 15709, 15710, 15711, -1, 15712, 15705, 15710, -1, 15713, 15705, 15712, -1, 15710, 15705, 15711, -1, 15713, 15703, 15705, -1, 11053, 15714, 11051, -1, 11051, 15715, 11060, -1, 15714, 15715, 11051, -1, 11060, 15716, 11059, -1, 15715, 15716, 11060, -1, 11059, 15717, 15718, -1, 15716, 15717, 11059, -1, 15717, 15719, 15718, -1, 15718, 15720, 15721, -1, 15719, 15720, 15718, -1, 15721, 15722, 15723, -1, 15720, 15722, 15721, -1, 15723, 15724, 15725, -1, 15722, 15724, 15723, -1, 15725, 15726, 15727, -1, 15724, 15726, 15725, -1, 15727, 15728, 15729, -1, 15726, 15728, 15727, -1, 15729, 15730, 15731, -1, 15728, 15730, 15729, -1, 15730, 15732, 15731, -1, 15731, 15733, 15734, -1, 15732, 15733, 15731, -1, 15734, 15735, 15736, -1, 15733, 15735, 15734, -1, 15736, 15737, 15738, -1, 15735, 15737, 15736, -1, 15738, 15739, 15711, -1, 15737, 15739, 15738, -1, 15739, 15709, 15711, -1, 12687, 15740, 12686, -1, 15741, 11053, 15740, -1, 15742, 11053, 15741, -1, 15740, 11053, 12686, -1, 15742, 15714, 11053, -1, 15743, 15744, 15745, -1, 15746, 15747, 15748, -1, 15746, 15748, 15749, -1, 15746, 15749, 15743, -1, 15746, 15745, 15750, -1, 15746, 15750, 15751, -1, 15746, 15751, 15752, -1, 15746, 15752, 15753, -1, 15746, 15753, 15754, -1, 15746, 15754, 15755, -1, 15746, 15755, 15756, -1, 15746, 15743, 15745, -1, 11109, 11110, 11112, -1, 15757, 11112, 15747, -1, 15757, 15747, 15746, -1, 11104, 11109, 11112, -1, 11123, 15757, 15758, -1, 11123, 15758, 15759, -1, 11123, 11112, 15757, -1, 11094, 11099, 11104, -1, 11094, 11104, 11112, -1, 11094, 11112, 11123, -1, 11127, 11123, 11124, -1, 11081, 11088, 11094, -1, 11081, 11094, 11123, -1, 11079, 11081, 11123, -1, 11079, 11123, 11127, -1, 15760, 15761, 11177, -1, 11177, 15761, 11181, -1, 11181, 15762, 11180, -1, 15761, 15762, 11181, -1, 11180, 15763, 11210, -1, 15762, 15763, 11180, -1, 11210, 15764, 11205, -1, 15763, 15764, 11210, -1, 11205, 15765, 11201, -1, 15764, 15765, 11205, -1, 11201, 15766, 11199, -1, 15765, 15766, 11201, -1, 11199, 15767, 11198, -1, 15766, 15767, 11199, -1, 15767, 15768, 11198, -1, 11198, 15769, 15770, -1, 15768, 15769, 11198, -1, 15770, 15771, 15772, -1, 15769, 15771, 15770, -1, 15772, 15773, 15774, -1, 15771, 15773, 15772, -1, 15774, 15775, 15776, -1, 15773, 15775, 15774, -1, 15776, 15777, 15778, -1, 15775, 15777, 15776, -1, 15778, 15779, 15780, -1, 15777, 15779, 15778, -1, 15779, 15781, 15780, -1, 15780, 15782, 15783, -1, 15781, 15782, 15780, -1, 15782, 15784, 15783, -1, 12662, 15785, 12661, -1, 15786, 11177, 15785, -1, 15787, 11177, 15786, -1, 15785, 11177, 12661, -1, 15787, 15760, 11177, -1, 15788, 15789, 15790, -1, 15790, 15789, 15791, -1, 15791, 15792, 15793, -1, 15789, 15792, 15791, -1, 15793, 15794, 15795, -1, 15792, 15794, 15793, -1, 15795, 15796, 15797, -1, 15794, 15796, 15795, -1, 15797, 15798, 15799, -1, 15796, 15798, 15797, -1, 15799, 15800, 15801, -1, 15798, 15800, 15799, -1, 15801, 15802, 12647, -1, 15800, 15802, 15801, -1, 15802, 12645, 12647, -1, 15784, 15803, 15783, -1, 15804, 15790, 15803, -1, 15805, 15790, 15804, -1, 15803, 15790, 15783, -1, 15805, 15788, 15790, -1, 15806, 15807, 15808, -1, 15806, 15808, 15809, -1, 15806, 15809, 15810, -1, 15806, 15810, 15811, -1, 15806, 15811, 15812, -1, 15813, 15807, 15806, -1, 15814, 15813, 15806, -1, 15815, 15814, 15806, -1, 15816, 15815, 15806, -1, 15817, 15816, 15806, -1, 15818, 15817, 15806, -1, 15819, 15818, 15806, -1, 15820, 15819, 15806, -1, 15821, 15820, 15822, -1, 15823, 15820, 15821, -1, 15824, 15820, 15823, -1, 11131, 15819, 15820, -1, 11136, 15824, 15825, -1, 11136, 15825, 15826, -1, 11136, 15820, 15824, -1, 11134, 15820, 11136, -1, 11134, 11131, 15820, -1, 11168, 11134, 11136, -1, 11156, 11136, 11138, -1, 11162, 11168, 11136, -1, 11158, 11136, 11156, -1, 11158, 11162, 11136, -1, 15827, 15828, 15829, -1, 15827, 15830, 15828, -1, 15831, 15832, 15833, -1, 15834, 15835, 15836, -1, 15831, 15837, 15838, -1, 15839, 15840, 15835, -1, 15831, 15838, 15841, -1, 15839, 15842, 15840, -1, 15831, 15841, 15843, -1, 15839, 15835, 15834, -1, 15831, 15843, 15844, -1, 15831, 15844, 15845, -1, 15831, 15845, 15846, -1, 15831, 15847, 15832, -1, 15831, 15846, 15847, -1, 15848, 15834, 15849, -1, 15850, 15839, 15834, -1, 15851, 15852, 15853, -1, 15851, 15829, 15852, -1, 15854, 15830, 15827, -1, 15855, 12523, 12364, -1, 15850, 15834, 15848, -1, 15855, 12526, 12523, -1, 15854, 15833, 15830, -1, 15855, 12527, 12526, -1, 15854, 15837, 15831, -1, 15854, 15831, 15833, -1, 15856, 15848, 15849, -1, 15857, 15842, 15839, -1, 15857, 15858, 15859, -1, 15860, 15855, 12364, -1, 15857, 15859, 15842, -1, 15861, 15853, 15862, -1, 15857, 15839, 15850, -1, 15863, 15829, 15851, -1, 15864, 15855, 15860, -1, 15863, 15827, 15829, -1, 15865, 15848, 15856, -1, 15866, 15864, 15860, -1, 15865, 15850, 15848, -1, 15867, 15851, 15853, -1, 15868, 15849, 15869, -1, 15867, 15853, 15861, -1, 15870, 15864, 15866, -1, 15871, 15870, 15866, -1, 15872, 15863, 15873, -1, 15872, 15873, 15874, -1, 15868, 15856, 15849, -1, 15872, 15874, 15837, -1, 15872, 15837, 15854, -1, 15872, 15827, 15863, -1, 15875, 15858, 15857, -1, 15872, 15854, 15827, -1, 15875, 15857, 15850, -1, 15876, 15862, 15877, -1, 15875, 15850, 15865, -1, 15875, 15878, 15858, -1, 15879, 15871, 15866, -1, 15880, 15865, 15856, -1, 15876, 15861, 15862, -1, 15881, 15871, 15879, -1, 15882, 15873, 15863, -1, 15882, 15883, 15873, -1, 15880, 15856, 15868, -1, 15884, 15881, 15879, -1, 15882, 15851, 15867, -1, 15882, 15863, 15851, -1, 15882, 15867, 15883, -1, 15885, 15886, 15883, -1, 15887, 15881, 15884, -1, 15885, 15867, 15861, -1, 15885, 15861, 15876, -1, 15885, 15883, 15867, -1, 15888, 15887, 15884, -1, 15889, 15876, 15877, -1, 15890, 15868, 15869, -1, 15891, 15875, 15865, -1, 15892, 15887, 15888, -1, 15893, 15894, 15886, -1, 15893, 15889, 15894, -1, 15891, 15878, 15875, -1, 15893, 15886, 15885, -1, 15891, 15865, 15880, -1, 15893, 15885, 15876, -1, 15893, 15876, 15889, -1, 15895, 15892, 15888, -1, 15896, 15897, 15894, -1, 15896, 15894, 15889, -1, 15896, 15889, 15877, -1, 15898, 15868, 15890, -1, 15899, 15895, 15888, -1, 15900, 15896, 15877, -1, 15900, 15897, 15896, -1, 15901, 15895, 15899, -1, 15902, 15877, 15903, -1, 15902, 15904, 15897, -1, 15902, 15897, 15900, -1, 15902, 15900, 15877, -1, 15905, 15901, 15899, -1, 15906, 15904, 15902, -1, 15898, 15880, 15868, -1, 15906, 15902, 15903, -1, 15907, 15901, 15905, -1, 15908, 15878, 15891, -1, 15909, 15910, 15904, -1, 15908, 15911, 15878, -1, 15909, 15904, 15906, -1, 15909, 15906, 15903, -1, 15912, 15890, 15869, -1, 15913, 15907, 15905, -1, 15914, 15915, 15916, -1, 15914, 15903, 15915, -1, 15914, 15916, 15910, -1, 15914, 15909, 15903, -1, 15917, 15907, 15913, -1, 15914, 15910, 15909, -1, 15918, 15916, 15915, -1, 15919, 15880, 15898, -1, 15920, 15918, 15915, -1, 15921, 15918, 15920, -1, 15922, 15921, 15920, -1, 15919, 15891, 15880, -1, 15923, 15921, 15922, -1, 15828, 15898, 15890, -1, 15924, 15923, 15922, -1, 15828, 15890, 15912, -1, 15925, 15923, 15924, -1, 15832, 15911, 15908, -1, 15832, 15891, 15919, -1, 15926, 15925, 15924, -1, 15832, 15908, 15891, -1, 15927, 15925, 15926, -1, 15928, 15927, 15926, -1, 15852, 15912, 15869, -1, 15928, 15929, 15927, -1, 15852, 15869, 15862, -1, 15930, 15929, 15928, -1, 15931, 15930, 15928, -1, 15830, 15919, 15898, -1, 15932, 15930, 15931, -1, 15830, 15898, 15828, -1, 15847, 15911, 15832, -1, 15847, 15846, 15933, -1, 12346, 15932, 15931, -1, 15847, 15933, 15934, -1, 15847, 15934, 15935, -1, 15847, 15935, 15936, -1, 15847, 15936, 15937, -1, 12543, 15932, 12346, -1, 15847, 15937, 15938, -1, 15847, 15938, 15939, -1, 12542, 15932, 12543, -1, 15847, 15939, 15911, -1, 12544, 15932, 12542, -1, 15829, 15828, 15912, -1, 15940, 15913, 15836, -1, 15940, 15917, 15913, -1, 15829, 15912, 15852, -1, 15940, 15941, 15917, -1, 15942, 15943, 15941, -1, 15942, 15940, 15836, -1, 15942, 15941, 15940, -1, 15944, 15942, 15836, -1, 15944, 15943, 15942, -1, 15833, 15919, 15830, -1, 15944, 15945, 15943, -1, 15833, 15832, 15919, -1, 15853, 15852, 15862, -1, 15835, 15944, 15836, -1, 15840, 15945, 15944, -1, 15840, 15842, 15945, -1, 15840, 15944, 15835, -1, 15834, 15836, 15849, -1, 15946, 12463, 12464, -1, 15946, 12464, 15581, -1, 15947, 15581, 15580, -1, 15947, 15946, 15581, -1, 15948, 15580, 15590, -1, 15948, 15947, 15580, -1, 15949, 15590, 15589, -1, 15949, 15948, 15590, -1, 15950, 15589, 15588, -1, 15950, 15949, 15589, -1, 15951, 15588, 15587, -1, 15951, 15950, 15588, -1, 15952, 15587, 15586, -1, 15952, 15951, 15587, -1, 15620, 15952, 15586, -1, 15953, 15626, 15563, -1, 15953, 15563, 15562, -1, 15954, 15562, 15561, -1, 15954, 15953, 15562, -1, 15955, 15954, 15561, -1, 15956, 15561, 15560, -1, 15956, 15955, 15561, -1, 15957, 15560, 15559, -1, 15957, 15956, 15560, -1, 15958, 15957, 15559, -1, 15959, 15559, 15601, -1, 15959, 15958, 15559, -1, 15960, 15601, 15600, -1, 15960, 15959, 15601, -1, 15961, 15600, 15599, -1, 15961, 15960, 15600, -1, 15962, 15599, 15598, -1, 15962, 15961, 15599, -1, 15963, 15598, 15595, -1, 15963, 15962, 15598, -1, 15612, 15963, 15595, -1, 15964, 15618, 15566, -1, 15964, 15566, 15565, -1, 15965, 15565, 15564, -1, 15965, 15964, 15565, -1, 15966, 15965, 15564, -1, 15967, 15564, 15567, -1, 15967, 15966, 15564, -1, 15968, 15567, 15568, -1, 15968, 15967, 15567, -1, 15969, 15968, 15568, -1, 15970, 15568, 15574, -1, 15970, 15969, 15568, -1, 15971, 15574, 15579, -1, 15971, 15970, 15574, -1, 15972, 15579, 15582, -1, 15972, 15971, 15579, -1, 15973, 15582, 15583, -1, 15973, 15972, 15582, -1, 15974, 15583, 15578, -1, 15974, 15973, 15583, -1, 15605, 15974, 15578, -1, 15528, 15530, 15975, -1, 15975, 15577, 15976, -1, 15530, 15577, 15975, -1, 15976, 15576, 15977, -1, 15577, 15576, 15976, -1, 15977, 15575, 15978, -1, 15576, 15575, 15977, -1, 15978, 15573, 15979, -1, 15575, 15573, 15978, -1, 15979, 15572, 15980, -1, 15573, 15572, 15979, -1, 15980, 15571, 15981, -1, 15572, 15571, 15980, -1, 15571, 15570, 15981, -1, 15981, 15569, 15982, -1, 15570, 15569, 15981, -1, 15982, 15546, 15549, -1, 15569, 15546, 15982, -1, 15550, 15552, 15983, -1, 15983, 15592, 15984, -1, 15552, 15592, 15983, -1, 15984, 15594, 15985, -1, 15592, 15594, 15984, -1, 15985, 15597, 15986, -1, 15594, 15597, 15985, -1, 15986, 15596, 15987, -1, 15597, 15596, 15986, -1, 15987, 15593, 15988, -1, 15596, 15593, 15987, -1, 15988, 15591, 15989, -1, 15593, 15591, 15988, -1, 15591, 15585, 15989, -1, 15989, 15584, 15990, -1, 15585, 15584, 15989, -1, 15990, 15535, 15538, -1, 15584, 15535, 15990, -1, 15539, 15541, 15991, -1, 15991, 15603, 15992, -1, 15541, 15603, 15991, -1, 15992, 15602, 12441, -1, 15603, 15602, 15992, -1, 15602, 12442, 12441, -1, 14584, 15652, 14585, -1, 14931, 15652, 14584, -1, 15653, 14907, 14902, -1, 15653, 14916, 14907, -1, 14897, 15653, 14902, -1, 14615, 15653, 14897, -1, 14887, 15653, 14615, -1, 15655, 14887, 14881, -1, 15655, 15653, 14887, -1, 14876, 15655, 14881, -1, 14869, 15655, 14876, -1, 15656, 15655, 14869, -1, 14865, 15656, 14869, -1, 14858, 15656, 14865, -1, 14856, 15656, 14858, -1, 15627, 15656, 14856, -1, 14855, 15627, 14856, -1, 15653, 15652, 14931, -1, 15653, 14931, 14925, -1, 15653, 14925, 14916, -1, 14843, 15627, 14855, -1, 14843, 15628, 15627, -1, 14846, 15631, 15628, -1, 14846, 15628, 14843, -1, 14845, 15633, 15631, -1, 14845, 15631, 14846, -1, 14844, 15635, 15633, -1, 14844, 15633, 14845, -1, 14842, 15637, 15635, -1, 14842, 15635, 14844, -1, 14835, 15639, 15637, -1, 14835, 15640, 15639, -1, 14835, 15637, 14842, -1, 14833, 15642, 15640, -1, 14833, 15640, 14835, -1, 14828, 15644, 15642, -1, 14828, 15642, 14833, -1, 14827, 15646, 15644, -1, 14827, 15644, 14828, -1, 14822, 15648, 15646, -1, 14822, 15649, 15648, -1, 14822, 15646, 14827, -1, 14821, 15651, 15649, -1, 14821, 15649, 14822, -1, 14820, 12691, 12689, -1, 14820, 12689, 15651, -1, 14820, 15651, 14821, -1, 14825, 12693, 12691, -1, 14825, 12691, 14820, -1, 14824, 12695, 12693, -1, 14824, 12693, 14825, -1, 13216, 15658, 15657, -1, 13223, 15659, 15658, -1, 13223, 15658, 13216, -1, 13277, 15660, 15659, -1, 13277, 15659, 13223, -1, 13280, 15661, 15660, -1, 13280, 15660, 13277, -1, 13279, 15662, 15661, -1, 13279, 15661, 13280, -1, 13287, 15663, 15662, -1, 13287, 15664, 15663, -1, 13287, 15662, 13279, -1, 13285, 15665, 15664, -1, 13285, 15664, 13287, -1, 13254, 15666, 15665, -1, 13254, 15665, 13285, -1, 13230, 15667, 15666, -1, 13230, 15666, 13254, -1, 13232, 15668, 15667, -1, 13232, 15667, 13230, -1, 14623, 15669, 15668, -1, 14623, 15668, 13232, -1, 14622, 15670, 15669, -1, 14622, 15669, 14623, -1, 14621, 15672, 15670, -1, 14621, 15670, 14622, -1, 14620, 15674, 15672, -1, 14620, 15672, 14621, -1, 14585, 15652, 15674, -1, 14585, 15674, 14620, -1, 14836, 12695, 14824, -1, 14848, 12695, 14836, -1, 15675, 14872, 14878, -1, 15675, 14861, 14872, -1, 14889, 15675, 14878, -1, 14894, 15675, 14889, -1, 14900, 15675, 14894, -1, 15676, 14900, 14905, -1, 15676, 15675, 14900, -1, 14914, 15676, 14905, -1, 14918, 15676, 14914, -1, 15677, 14918, 14928, -1, 15677, 15676, 14918, -1, 14581, 15677, 14928, -1, 14591, 15677, 14581, -1, 15657, 15677, 14591, -1, 13217, 15657, 14591, -1, 13216, 15657, 13217, -1, 15675, 12695, 14848, -1, 15675, 14848, 14851, -1, 15675, 14851, 14861, -1, 13458, 12662, 13468, -1, 13452, 12662, 13458, -1, 15785, 13432, 13424, -1, 15785, 13438, 13432, -1, 13420, 15785, 13424, -1, 13415, 15785, 13420, -1, 13410, 15785, 13415, -1, 15786, 13410, 13405, -1, 15786, 15785, 13410, -1, 13396, 15786, 13405, -1, 13394, 15786, 13396, -1, 15787, 15786, 13394, -1, 13390, 15787, 13394, -1, 13386, 15787, 13390, -1, 13381, 15787, 13386, -1, 15760, 15787, 13381, -1, 13375, 15760, 13381, -1, 15785, 12662, 13452, -1, 15785, 13452, 13441, -1, 15785, 13441, 13438, -1, 13374, 15760, 13375, -1, 13374, 15761, 15760, -1, 13373, 15762, 15761, -1, 13373, 15761, 13374, -1, 13349, 15763, 15762, -1, 13349, 15762, 13373, -1, 13339, 15764, 15763, -1, 13339, 15763, 13349, -1, 13340, 15765, 15764, -1, 13340, 15764, 13339, -1, 13367, 15766, 15765, -1, 13367, 15767, 15766, -1, 13367, 15765, 13340, -1, 13257, 15768, 15767, -1, 13257, 15767, 13367, -1, 13260, 15769, 15768, -1, 13260, 15768, 13257, -1, 13259, 15771, 15769, -1, 13259, 15769, 13260, -1, 13358, 15773, 15771, -1, 13358, 15775, 15773, -1, 13358, 15771, 13259, -1, 13357, 15777, 15775, -1, 13357, 15775, 13358, -1, 13363, 15779, 15777, -1, 13363, 15777, 13357, -1, 13362, 15781, 15779, -1, 13362, 15782, 15781, -1, 13362, 15779, 13363, -1, 13361, 15784, 15782, -1, 13361, 15782, 13362, -1, 13477, 15789, 15788, -1, 13477, 15788, 13470, -1, 13476, 15792, 15789, -1, 13476, 15789, 13477, -1, 13475, 15794, 15792, -1, 13475, 15792, 13476, -1, 13474, 15796, 15794, -1, 13474, 15794, 13475, -1, 13482, 15798, 15796, -1, 13482, 15796, 13474, -1, 13265, 15800, 15798, -1, 13265, 15798, 13482, -1, 13264, 15802, 15800, -1, 13264, 15800, 13265, -1, 13263, 12646, 12645, -1, 13263, 12645, 15802, -1, 13263, 15802, 13264, -1, 13485, 12649, 12646, -1, 13485, 12646, 13263, -1, 13484, 12651, 12649, -1, 13484, 12649, 13485, -1, 13483, 12653, 12651, -1, 13483, 12651, 13484, -1, 13459, 12655, 12653, -1, 13459, 12653, 13483, -1, 13460, 12657, 12655, -1, 13460, 12655, 13459, -1, 13472, 12659, 12657, -1, 13472, 12660, 12659, -1, 13472, 12657, 13460, -1, 13468, 12662, 12660, -1, 13468, 12660, 13472, -1, 13365, 15784, 13361, -1, 13370, 15784, 13365, -1, 15803, 13388, 13401, -1, 15803, 13379, 13388, -1, 13407, 15803, 13401, -1, 13417, 15803, 13407, -1, 13422, 15803, 13417, -1, 15804, 13422, 13430, -1, 15804, 15803, 13422, -1, 13434, 15804, 13430, -1, 13443, 15804, 13434, -1, 15805, 13443, 13448, -1, 15805, 15804, 13443, -1, 13455, 15805, 13448, -1, 13463, 15805, 13455, -1, 15788, 15805, 13463, -1, 13470, 15788, 13463, -1, 15803, 15784, 13370, -1, 15803, 13370, 13379, -1, 14722, 15709, 14702, -1, 14715, 15709, 14722, -1, 15710, 14690, 14683, -1, 15710, 14693, 14690, -1, 14679, 15710, 14683, -1, 14669, 15710, 14679, -1, 14663, 15710, 14669, -1, 15712, 14663, 14658, -1, 15712, 15710, 14663, -1, 14652, 15712, 14658, -1, 14642, 15712, 14652, -1, 15713, 15712, 14642, -1, 14640, 15713, 14642, -1, 14635, 15713, 14640, -1, 14631, 15713, 14635, -1, 15703, 15713, 14631, -1, 14630, 15703, 14631, -1, 15710, 15709, 14715, -1, 15710, 14715, 14708, -1, 15710, 14708, 14693, -1, 14619, 15703, 14630, -1, 14619, 15704, 15703, -1, 14618, 15707, 15704, -1, 14618, 15704, 14619, -1, 14616, 12664, 15707, -1, 14616, 15707, 14618, -1, 14606, 12666, 12664, -1, 14606, 12664, 14616, -1, 13275, 12668, 12666, -1, 13275, 12666, 14606, -1, 13270, 12670, 12668, -1, 13270, 12668, 13275, -1, 13251, 12672, 12670, -1, 13251, 12670, 13270, -1, 13250, 12674, 12672, -1, 13250, 12676, 12674, -1, 13250, 12672, 13251, -1, 13249, 12676, 13250, -1, 13244, 12678, 12676, -1, 13244, 12676, 13249, -1, 13246, 12680, 12678, -1, 13246, 12678, 13244, -1, 13242, 12682, 12680, -1, 13242, 12683, 12682, -1, 13242, 12680, 13246, -1, 13241, 12685, 12683, -1, 13241, 12683, 13242, -1, 13273, 12687, 12685, -1, 13273, 12685, 13241, -1, 14730, 15715, 15714, -1, 14730, 15714, 14725, -1, 14728, 15716, 15715, -1, 14728, 15715, 14730, -1, 14727, 15717, 15716, -1, 14727, 15716, 14728, -1, 14736, 15719, 15717, -1, 14736, 15717, 14727, -1, 14735, 15720, 15719, -1, 14735, 15719, 14736, -1, 14742, 15722, 15720, -1, 14742, 15720, 14735, -1, 14741, 15724, 15722, -1, 14741, 15722, 14742, -1, 14740, 15726, 15724, -1, 14740, 15724, 14741, -1, 14729, 15728, 15726, -1, 14729, 15730, 15728, -1, 14729, 15726, 14740, -1, 14710, 15732, 15730, -1, 14710, 15730, 14729, -1, 14711, 15733, 15732, -1, 14711, 15732, 14710, -1, 14733, 15735, 15733, -1, 14733, 15733, 14711, -1, 14732, 15737, 15735, -1, 14732, 15735, 14733, -1, 14704, 15739, 15737, -1, 14704, 15737, 14732, -1, 14702, 15709, 15739, -1, 14702, 15739, 14704, -1, 13274, 12687, 13273, -1, 14598, 12687, 13274, -1, 15740, 14649, 14654, -1, 15740, 14638, 14649, -1, 14665, 15740, 14654, -1, 14672, 15740, 14665, -1, 14681, 15740, 14672, -1, 15741, 14681, 14686, -1, 15741, 15740, 14681, -1, 14696, 15741, 14686, -1, 14706, 15741, 14696, -1, 15742, 14706, 14717, -1, 15742, 15741, 14706, -1, 14607, 15742, 14717, -1, 14605, 15742, 14607, -1, 15714, 15742, 14605, -1, 14725, 15714, 14605, -1, 15740, 12687, 14598, -1, 15740, 14598, 14628, -1, 15740, 14628, 14638, -1, 13314, 15539, 13317, -1, 15540, 13314, 13309, -1, 15540, 15539, 13314, -1, 13302, 15540, 13309, -1, 13301, 15540, 13302, -1, 15542, 13301, 13295, -1, 15542, 15540, 13301, -1, 13282, 15542, 13295, -1, 13220, 15542, 13282, -1, 13222, 15542, 13220, -1, 15543, 13222, 14589, -1, 15543, 15542, 13222, -1, 14582, 15543, 14589, -1, 14922, 15543, 14582, -1, 14913, 15543, 14922, -1, 14904, 15543, 14913, -1, 15544, 14904, 14899, -1, 15544, 15543, 14904, -1, 14893, 15544, 14899, -1, 14883, 15544, 14893, -1, 14871, 15544, 14883, -1, 15545, 14871, 14860, -1, 15545, 15544, 14871, -1, 14850, 15545, 14860, -1, 14839, 15545, 14850, -1, 14830, 15545, 14839, -1, 14817, 15545, 14830, -1, 14811, 15545, 14817, -1, 15547, 14807, 14801, -1, 15547, 14811, 14807, -1, 15547, 15545, 14811, -1, 14796, 15547, 14801, -1, 14794, 15547, 14796, -1, 15548, 15547, 14794, -1, 14792, 15548, 14794, -1, 14789, 15548, 14792, -1, 15549, 15548, 14789, -1, 14790, 15549, 14789, -1, 15991, 13317, 15539, -1, 15991, 13319, 13317, -1, 15992, 13320, 13319, -1, 15992, 13319, 15991, -1, 12441, 13322, 13320, -1, 12441, 13320, 15992, -1, 12443, 13322, 12441, -1, 12445, 13323, 13322, -1, 12445, 13322, 12443, -1, 12447, 13325, 13323, -1, 12447, 13323, 12445, -1, 12449, 13326, 13325, -1, 12449, 13325, 12447, -1, 12451, 13283, 13326, -1, 12451, 13326, 12449, -1, 12454, 13284, 13283, -1, 12454, 13286, 13284, -1, 12454, 13283, 12451, -1, 12456, 13288, 13286, -1, 12456, 13286, 12454, -1, 15975, 14778, 14777, -1, 15975, 14777, 15528, -1, 15976, 14751, 14778, -1, 15976, 14778, 15975, -1, 15977, 14752, 14751, -1, 15977, 14751, 15976, -1, 15978, 14781, 14752, -1, 15978, 14752, 15977, -1, 15979, 14782, 14781, -1, 15979, 14781, 15978, -1, 15980, 14764, 14782, -1, 15980, 14782, 15979, -1, 15981, 14765, 14764, -1, 15981, 14764, 15980, -1, 15982, 14786, 14765, -1, 15982, 14787, 14786, -1, 15982, 14765, 15981, -1, 15549, 14790, 14787, -1, 15549, 14787, 15982, -1, 13512, 15550, 13514, -1, 13509, 15550, 13512, -1, 15551, 15550, 13509, -1, 13502, 15551, 13509, -1, 13495, 15551, 13502, -1, 15553, 13495, 13489, -1, 15553, 15551, 13495, -1, 13480, 15553, 13489, -1, 13478, 15553, 13480, -1, 13466, 15553, 13478, -1, 15554, 13466, 13456, -1, 15554, 15553, 13466, -1, 13449, 15554, 13456, -1, 13444, 15554, 13449, -1, 13435, 15554, 13444, -1, 15555, 13435, 13426, -1, 15555, 15554, 13435, -1, 13412, 15555, 13426, -1, 13402, 15555, 13412, -1, 13392, 15555, 13402, -1, 15556, 13392, 13384, -1, 15556, 15555, 13392, -1, 13378, 15556, 13384, -1, 13371, 15556, 13378, -1, 13366, 15556, 13371, -1, 13354, 15556, 13366, -1, 15557, 13343, 13337, -1, 15557, 13345, 13343, -1, 15557, 13354, 13345, -1, 15557, 15556, 13354, -1, 13335, 15557, 13337, -1, 13333, 15557, 13335, -1, 15558, 15557, 13333, -1, 13332, 15558, 13333, -1, 13330, 15558, 13332, -1, 13329, 15558, 13330, -1, 12456, 15558, 13329, -1, 13288, 12456, 13329, -1, 14773, 15528, 14777, -1, 15529, 14773, 14767, -1, 15529, 15528, 14773, -1, 14758, 15529, 14767, -1, 14754, 15529, 14758, -1, 15531, 15529, 14754, -1, 14738, 15531, 14754, -1, 14603, 15531, 14738, -1, 15532, 15531, 14603, -1, 14602, 15532, 14603, -1, 14705, 15532, 14602, -1, 14695, 15532, 14705, -1, 14685, 15532, 14695, -1, 15533, 14685, 14671, -1, 15533, 15532, 14685, -1, 14660, 15533, 14671, -1, 14648, 15533, 14660, -1, 14637, 15533, 14648, -1, 15534, 15533, 14637, -1, 14627, 15534, 14637, -1, 14624, 15534, 14627, -1, 14599, 15534, 14624, -1, 13269, 15534, 14599, -1, 13235, 15534, 13269, -1, 13227, 15534, 13235, -1, 15536, 13214, 13213, -1, 15536, 13225, 13214, -1, 15536, 13227, 13225, -1, 15536, 15534, 13227, -1, 13210, 15536, 13213, -1, 13208, 15536, 13210, -1, 15537, 15536, 13208, -1, 13528, 15537, 13208, -1, 15538, 15537, 13528, -1, 13524, 15538, 13528, -1, 15983, 13514, 15550, -1, 15983, 13504, 13514, -1, 15984, 13505, 13504, -1, 15984, 13504, 15983, -1, 15985, 13516, 13505, -1, 15985, 13505, 15984, -1, 15986, 13519, 13516, -1, 15986, 13516, 15985, -1, 15987, 13518, 13519, -1, 15987, 13519, 15986, -1, 15988, 13521, 13518, -1, 15988, 13518, 15987, -1, 15989, 13522, 13521, -1, 15989, 13521, 15988, -1, 15990, 13525, 13522, -1, 15990, 13526, 13525, -1, 15990, 13522, 15989, -1, 15538, 13524, 13526, -1, 15538, 13526, 15990, -1, 15911, 15939, 15605, -1, 15878, 15911, 15605, -1, 15604, 15858, 15878, -1, 15604, 15859, 15858, -1, 15604, 15878, 15605, -1, 15842, 15859, 15604, -1, 15945, 15842, 15604, -1, 15606, 15943, 15945, -1, 15606, 15941, 15943, -1, 15606, 15945, 15604, -1, 15917, 15941, 15606, -1, 15907, 15917, 15606, -1, 15607, 15901, 15907, -1, 15607, 15895, 15901, -1, 15607, 15907, 15606, -1, 15892, 15895, 15607, -1, 15887, 15892, 15607, -1, 15608, 15881, 15887, -1, 15608, 15871, 15881, -1, 15608, 15870, 15871, -1, 15608, 15887, 15607, -1, 15864, 15870, 15608, -1, 15855, 15864, 15608, -1, 15610, 12520, 12527, -1, 15610, 12517, 12520, -1, 15610, 12527, 15855, -1, 15610, 15855, 15608, -1, 12514, 12517, 15610, -1, 15609, 12514, 15610, -1, 15609, 12510, 12514, -1, 15609, 12506, 12510, -1, 12503, 12506, 15609, -1, 12498, 12503, 15609, -1, 12460, 12498, 15609, -1, 12460, 12483, 12498, -1, 12457, 12483, 12460, -1, 12457, 12484, 12483, -1, 12461, 12485, 12484, -1, 12461, 12484, 12457, -1, 12463, 12486, 12485, -1, 12463, 12485, 12461, -1, 15946, 12486, 12463, -1, 15947, 12487, 12486, -1, 15947, 12486, 15946, -1, 15948, 12488, 12487, -1, 15948, 12489, 12488, -1, 15948, 12487, 15947, -1, 15949, 12490, 12489, -1, 15949, 12489, 15948, -1, 15950, 12491, 12490, -1, 15950, 12490, 15949, -1, 15951, 12492, 12491, -1, 15951, 12491, 15950, -1, 15952, 12493, 12492, -1, 15952, 12494, 12493, -1, 15952, 12492, 15951, -1, 15620, 12495, 12494, -1, 15620, 12494, 15952, -1, 15964, 15841, 15838, -1, 15964, 15838, 15618, -1, 15965, 15841, 15964, -1, 15966, 15843, 15841, -1, 15966, 15841, 15965, -1, 15967, 15844, 15843, -1, 15967, 15843, 15966, -1, 15968, 15845, 15844, -1, 15968, 15844, 15967, -1, 15969, 15846, 15845, -1, 15969, 15845, 15968, -1, 15970, 15933, 15846, -1, 15970, 15846, 15969, -1, 15971, 15934, 15933, -1, 15971, 15933, 15970, -1, 15972, 15935, 15934, -1, 15972, 15934, 15971, -1, 15973, 15936, 15935, -1, 15973, 15935, 15972, -1, 15974, 15937, 15936, -1, 15974, 15938, 15937, -1, 15974, 15936, 15973, -1, 15605, 15939, 15938, -1, 15605, 15938, 15974, -1, 15626, 12602, 15624, -1, 15626, 12587, 12602, -1, 15626, 12588, 12587, -1, 12474, 12495, 15620, -1, 12475, 12474, 15620, -1, 15619, 12644, 12475, -1, 15619, 12640, 12644, -1, 15619, 12475, 15620, -1, 12637, 12640, 15619, -1, 12634, 12637, 15619, -1, 15621, 12631, 12634, -1, 15621, 12627, 12631, -1, 15621, 12634, 15619, -1, 12540, 12627, 15621, -1, 12539, 12540, 15621, -1, 15622, 12538, 12539, -1, 15622, 12537, 12538, -1, 15622, 12539, 15621, -1, 12536, 12537, 15622, -1, 12535, 12536, 15622, -1, 12534, 12535, 15622, -1, 12533, 12534, 15622, -1, 15623, 12532, 12533, -1, 15623, 12531, 12532, -1, 15623, 12530, 12531, -1, 15623, 12529, 12530, -1, 15623, 12533, 15622, -1, 12528, 12529, 15623, -1, 12524, 12528, 15623, -1, 15625, 12524, 15623, -1, 15625, 12525, 12524, -1, 15625, 12621, 12525, -1, 12618, 12621, 15625, -1, 12615, 12618, 15625, -1, 15624, 12615, 15625, -1, 15624, 12612, 12615, -1, 15624, 12610, 12612, -1, 12607, 12610, 15624, -1, 12602, 12607, 15624, -1, 12574, 12579, 15612, -1, 15611, 12564, 12574, -1, 15611, 12565, 12564, -1, 15611, 12574, 15612, -1, 12559, 12565, 15611, -1, 12556, 12559, 15611, -1, 15613, 12553, 12556, -1, 15613, 12549, 12553, -1, 15613, 12556, 15611, -1, 12547, 12549, 15613, -1, 12545, 12547, 15613, -1, 12544, 12545, 15613, -1, 15614, 15932, 12544, -1, 15614, 15930, 15932, -1, 15614, 12544, 15613, -1, 15929, 15930, 15614, -1, 15927, 15929, 15614, -1, 15925, 15927, 15614, -1, 15615, 15923, 15925, -1, 15615, 15921, 15923, -1, 15615, 15925, 15614, -1, 15918, 15921, 15615, -1, 15916, 15918, 15615, -1, 15617, 15910, 15916, -1, 15617, 15904, 15910, -1, 15617, 15916, 15615, -1, 15897, 15904, 15617, -1, 15894, 15897, 15617, -1, 15616, 15894, 15617, -1, 15616, 15886, 15894, -1, 15616, 15883, 15886, -1, 15616, 15873, 15883, -1, 15874, 15873, 15616, -1, 15837, 15874, 15616, -1, 15618, 15837, 15616, -1, 15618, 15838, 15837, -1, 15953, 12588, 15626, -1, 15953, 12589, 12588, -1, 15954, 12589, 15953, -1, 15955, 12590, 12589, -1, 15955, 12589, 15954, -1, 15956, 12591, 12590, -1, 15956, 12590, 15955, -1, 15957, 12592, 12591, -1, 15957, 12591, 15956, -1, 15958, 12593, 12592, -1, 15958, 12592, 15957, -1, 15959, 12594, 12593, -1, 15959, 12593, 15958, -1, 15960, 12595, 12594, -1, 15960, 12594, 15959, -1, 15961, 12596, 12595, -1, 15961, 12595, 15960, -1, 15962, 12597, 12596, -1, 15962, 12596, 15961, -1, 15963, 12598, 12597, -1, 15963, 12599, 12598, -1, 15963, 12597, 15962, -1, 15612, 12579, 12599, -1, 15612, 12599, 15963, -1, 15993, 15994, 15995, -1, 15993, 14492, 14490, -1, 15993, 14495, 14492, -1, 15993, 15996, 15994, -1, 15993, 14490, 15996, -1, 15997, 15995, 15836, -1, 15997, 15836, 15913, -1, 15998, 15995, 15997, -1, 15998, 15993, 15995, -1, 15998, 14495, 15993, -1, 15999, 15913, 15905, -1, 15999, 15997, 15913, -1, 16000, 15997, 15999, -1, 16000, 14494, 14495, -1, 16000, 14497, 14494, -1, 16000, 14495, 15998, -1, 16000, 15998, 15997, -1, 16001, 15905, 15899, -1, 16001, 15999, 15905, -1, 16002, 16000, 15999, -1, 16002, 14497, 16000, -1, 16002, 15999, 16001, -1, 16003, 15899, 15888, -1, 16004, 12348, 12346, -1, 16003, 16001, 15899, -1, 16004, 12346, 15931, -1, 16005, 14502, 14497, -1, 16005, 16002, 16001, -1, 16006, 12351, 12348, -1, 16005, 14497, 16002, -1, 16006, 12362, 12351, -1, 16005, 16001, 16003, -1, 16006, 14458, 12362, -1, 16007, 15888, 15884, -1, 16006, 14461, 14458, -1, 16007, 16003, 15888, -1, 16006, 12348, 16004, -1, 16008, 15931, 15928, -1, 16009, 16003, 16007, -1, 16009, 14525, 14502, -1, 16008, 16004, 15931, -1, 16009, 14536, 14525, -1, 16009, 14502, 16005, -1, 16010, 14461, 16006, -1, 16009, 16005, 16003, -1, 16010, 16006, 16004, -1, 16010, 14411, 14461, -1, 16010, 16004, 16008, -1, 16011, 15884, 15879, -1, 16011, 16007, 15884, -1, 16012, 15928, 15926, -1, 16013, 14536, 16009, -1, 16012, 16008, 15928, -1, 16013, 16007, 16011, -1, 16014, 14421, 14411, -1, 16014, 14411, 16010, -1, 16013, 16009, 16007, -1, 16014, 16010, 16008, -1, 16015, 15879, 15866, -1, 16014, 16008, 16012, -1, 16015, 16011, 15879, -1, 16016, 15926, 15924, -1, 16016, 16012, 15926, -1, 16017, 16013, 16011, -1, 16017, 16011, 16015, -1, 16018, 16014, 16012, -1, 16017, 14507, 14536, -1, 16018, 16012, 16016, -1, 16017, 14536, 16013, -1, 16018, 14432, 14421, -1, 16019, 15860, 12364, -1, 16018, 14421, 16014, -1, 16019, 15866, 15860, -1, 16020, 16016, 15924, -1, 16019, 16015, 15866, -1, 16020, 15924, 15922, -1, 16019, 12364, 12367, -1, 16021, 16017, 16015, -1, 16022, 14469, 14432, -1, 16021, 14507, 16017, -1, 16022, 16018, 16016, -1, 16021, 16019, 12367, -1, 16022, 14432, 16018, -1, 16021, 12367, 12359, -1, 16022, 16016, 16020, -1, 16021, 12359, 12358, -1, 16021, 16015, 16019, -1, 16021, 14508, 14507, -1, 16023, 15922, 15920, -1, 16021, 12358, 14508, -1, 16023, 16020, 15922, -1, 16024, 16022, 16020, -1, 16024, 14471, 14469, -1, 16024, 14469, 16022, -1, 16024, 16020, 16023, -1, 16025, 15920, 15915, -1, 16025, 16023, 15920, -1, 16026, 14477, 14471, -1, 16026, 14471, 16024, -1, 16026, 16024, 16023, -1, 16026, 16023, 16025, -1, 16027, 15915, 15903, -1, 16027, 16025, 15915, -1, 16028, 14477, 16026, -1, 16028, 16026, 16025, -1, 16028, 16025, 16027, -1, 16029, 15903, 15877, -1, 16029, 16027, 15903, -1, 16030, 14477, 16028, -1, 16030, 14480, 14477, -1, 16030, 16028, 16027, -1, 16030, 16027, 16029, -1, 16031, 15877, 15862, -1, 16031, 16029, 15877, -1, 16032, 16030, 16029, -1, 16032, 14478, 14480, -1, 16032, 14487, 14478, -1, 16032, 14480, 16030, -1, 16032, 16029, 16031, -1, 16033, 16031, 15862, -1, 16033, 15862, 15869, -1, 16034, 16031, 16033, -1, 16034, 14490, 14487, -1, 16034, 14487, 16032, -1, 16034, 16032, 16031, -1, 15994, 15869, 15849, -1, 15994, 16033, 15869, -1, 15996, 14490, 16034, -1, 15996, 16034, 16033, -1, 15996, 16033, 15994, -1, 15995, 15994, 15849, -1, 15995, 15849, 15836, -1, 15517, 15522, 15115, -1, 15512, 15517, 15186, -1, 15182, 15512, 15186, -1, 15507, 15512, 15182, -1, 15178, 15507, 15182, -1, 15414, 12315, 12312, -1, 15414, 12312, 15184, -1, 15502, 15507, 15178, -1, 15173, 15502, 15178, -1, 15433, 15184, 15180, -1, 15433, 15414, 15184, -1, 15497, 15502, 15173, -1, 15169, 15497, 15173, -1, 15423, 15180, 15176, -1, 15492, 15497, 15169, -1, 15423, 15433, 15180, -1, 15166, 15492, 15169, -1, 15487, 15492, 15166, -1, 15413, 15176, 15174, -1, 15413, 15423, 15176, -1, 15161, 15487, 15166, -1, 15482, 15487, 15161, -1, 15158, 15482, 15161, -1, 15408, 15174, 15170, -1, 15408, 15413, 15174, -1, 15477, 15482, 15158, -1, 15154, 15477, 15158, -1, 15403, 15408, 15170, -1, 15472, 15477, 15154, -1, 15403, 15170, 15164, -1, 15150, 15472, 15154, -1, 15467, 15472, 15150, -1, 15398, 15403, 15164, -1, 15398, 15164, 15162, -1, 15146, 15467, 15150, -1, 15462, 15467, 15146, -1, 15393, 15398, 15162, -1, 15393, 15162, 15156, -1, 15142, 15462, 15146, -1, 15457, 15462, 15142, -1, 15384, 15393, 15156, -1, 15384, 15156, 15152, -1, 15138, 15457, 15142, -1, 15452, 15457, 15138, -1, 15378, 15384, 15152, -1, 15134, 15452, 15138, -1, 15378, 15152, 15148, -1, 15447, 15452, 15134, -1, 15379, 15378, 15148, -1, 15130, 15447, 15134, -1, 15379, 15148, 15144, -1, 15441, 15447, 15130, -1, 15373, 15144, 15140, -1, 15126, 15441, 15130, -1, 15373, 15379, 15144, -1, 15431, 15441, 15126, -1, 15122, 15431, 15126, -1, 15368, 15140, 15136, -1, 15368, 15373, 15140, -1, 15350, 15431, 15122, -1, 12256, 15350, 15122, -1, 15363, 15136, 15132, -1, 15363, 15368, 15136, -1, 12258, 15350, 12256, -1, 15358, 15132, 15128, -1, 15358, 15363, 15132, -1, 15353, 15128, 15124, -1, 15353, 15358, 15128, -1, 15347, 15124, 15120, -1, 15347, 15353, 15124, -1, 15346, 15120, 15118, -1, 15346, 15347, 15120, -1, 15527, 15118, 15117, -1, 15527, 15346, 15118, -1, 15522, 15117, 15115, -1, 15522, 15527, 15117, -1, 15517, 15115, 15186, -1, 16035, 16036, 16037, -1, 16038, 16036, 16035, -1, 16039, 16036, 16038, -1, 16036, 16040, 16037, -1, 16040, 16041, 16037, -1, 16042, 11021, 16043, -1, 11025, 16044, 11026, -1, 11023, 16044, 11025, -1, 11021, 16044, 11023, -1, 16042, 16044, 11021, -1, 11021, 16037, 16043, -1, 16043, 16037, 16041, -1, 16045, 12200, 16046, -1, 16047, 12200, 16045, -1, 12201, 12200, 16047, -1, 12200, 16048, 16046, -1, 16048, 16049, 16046, -1, 16050, 16051, 16052, -1, 16053, 12231, 12230, -1, 16054, 12231, 16053, -1, 16051, 12231, 16054, -1, 16050, 12231, 16051, -1, 16051, 16046, 16049, -1, 16051, 16049, 16052, -1, 16055, 16056, 16057, -1, 16058, 16056, 16055, -1, 16059, 16056, 16058, -1, 16056, 16060, 16057, -1, 16060, 16061, 16057, -1, 16062, 11046, 16063, -1, 11049, 16064, 11050, -1, 11047, 16064, 11049, -1, 11046, 16064, 11047, -1, 16062, 16064, 11046, -1, 11046, 16057, 16063, -1, 16063, 16057, 16061, -1, 10999, 11038, 11036, -1, 10999, 10997, 11038, -1, 10995, 11040, 10997, -1, 10995, 11042, 11040, -1, 11001, 11036, 11034, -1, 11001, 10999, 11036, -1, 10992, 11042, 10995, -1, 10992, 11044, 11042, -1, 11004, 11034, 11032, -1, 11004, 11032, 16065, -1, 11004, 11001, 11034, -1, 10991, 11044, 10992, -1, 10991, 11046, 11044, -1, 16066, 16067, 16068, -1, 16069, 11046, 10991, -1, 16070, 11046, 16069, -1, 16071, 16072, 16067, -1, 16071, 16067, 16066, -1, 16057, 11046, 16070, -1, 16051, 16068, 16046, -1, 11006, 16065, 16073, -1, 16051, 16066, 16068, -1, 16074, 16075, 16072, -1, 11006, 11004, 16065, -1, 16074, 16072, 16071, -1, 11008, 11006, 16073, -1, 11008, 16073, 16076, -1, 16077, 11027, 16075, -1, 16077, 16075, 16074, -1, 11010, 16076, 16078, -1, 16079, 11030, 11027, -1, 16079, 11027, 16077, -1, 11010, 11008, 16076, -1, 16080, 11032, 11030, -1, 11012, 11010, 16078, -1, 11012, 16078, 16081, -1, 16080, 11030, 16079, -1, 11014, 11012, 16081, -1, 11014, 16081, 16082, -1, 16065, 11032, 16080, -1, 11016, 16082, 16083, -1, 11016, 11014, 16082, -1, 11018, 16083, 16037, -1, 11018, 11016, 16083, -1, 11019, 11018, 16037, -1, 11020, 11019, 16037, -1, 11021, 11020, 16037, -1, 10997, 11040, 11038, -1, 12245, 16084, 12246, -1, 12245, 16085, 16084, -1, 16085, 16086, 16084, -1, 16085, 16087, 16086, -1, 16087, 16088, 16086, -1, 16088, 16089, 16090, -1, 16087, 16089, 16088, -1, 16090, 16091, 16092, -1, 16089, 16091, 16090, -1, 16092, 16093, 16094, -1, 16091, 16093, 16092, -1, 16094, 16095, 16096, -1, 16093, 16095, 16094, -1, 16096, 16097, 16098, -1, 16095, 16097, 16096, -1, 16098, 16099, 16100, -1, 16097, 16099, 16098, -1, 16100, 16101, 16102, -1, 16099, 16101, 16100, -1, 16036, 16039, 16103, -1, 16102, 16104, 16039, -1, 16101, 16104, 16102, -1, 16104, 16105, 16039, -1, 16103, 16106, 16107, -1, 16039, 16106, 16103, -1, 16105, 16106, 16039, -1, 16107, 12218, 12217, -1, 16106, 12218, 16107, -1, 12215, 12216, 16108, -1, 16108, 16109, 16110, -1, 12216, 16109, 16108, -1, 16110, 11050, 16064, -1, 16109, 11050, 16110, -1, 16109, 16111, 11050, -1, 11050, 16112, 11048, -1, 16111, 16112, 11050, -1, 11048, 16113, 11045, -1, 16112, 16113, 11048, -1, 11045, 16114, 11043, -1, 16113, 16114, 11045, -1, 11043, 16115, 11041, -1, 16114, 16115, 11043, -1, 11041, 16116, 11039, -1, 16115, 16116, 11041, -1, 11039, 16117, 11037, -1, 16116, 16117, 11039, -1, 11037, 16118, 11035, -1, 16117, 16118, 11037, -1, 11035, 16119, 11033, -1, 16118, 16119, 11035, -1, 11033, 16120, 11031, -1, 16119, 16120, 11033, -1, 11031, 16121, 11028, -1, 16120, 16121, 11031, -1, 11028, 12188, 11029, -1, 16121, 12188, 11028, -1, 10993, 12187, 16122, -1, 16122, 16123, 16124, -1, 12187, 16123, 16122, -1, 16056, 16059, 16125, -1, 16124, 16126, 16059, -1, 16123, 16126, 16124, -1, 16059, 16127, 16125, -1, 16126, 16127, 16059, -1, 16125, 16128, 16129, -1, 16127, 16128, 16125, -1, 16129, 16130, 16131, -1, 16128, 16130, 16129, -1, 16131, 16132, 16133, -1, 16130, 16132, 16131, -1, 16133, 16134, 16135, -1, 16132, 16134, 16133, -1, 16135, 16136, 16137, -1, 16134, 16136, 16135, -1, 16136, 16138, 16137, -1, 16137, 11026, 16044, -1, 16137, 16139, 11026, -1, 16138, 16139, 16137, -1, 11026, 16140, 11024, -1, 16139, 16140, 11026, -1, 11024, 16141, 11022, -1, 16140, 16141, 11024, -1, 11022, 12174, 11017, -1, 16141, 12174, 11022, -1, 12176, 12138, 12177, -1, 12176, 12140, 12138, -1, 12176, 12142, 12140, -1, 12124, 12185, 12184, -1, 16130, 16142, 16143, -1, 16130, 16128, 16142, -1, 12126, 12184, 12183, -1, 12126, 12124, 12184, -1, 12122, 12186, 12185, -1, 12122, 12185, 12124, -1, 12175, 12142, 12176, -1, 12128, 12183, 12182, -1, 12128, 12126, 12183, -1, 12119, 12186, 12122, -1, 16132, 16143, 16144, -1, 12130, 12182, 12181, -1, 16132, 16130, 16143, -1, 12174, 16145, 12144, -1, 12130, 12128, 12182, -1, 12174, 12142, 12175, -1, 12174, 12144, 12142, -1, 12118, 12187, 12186, -1, 12118, 16123, 12187, -1, 16134, 16144, 16146, -1, 12118, 12186, 12119, -1, 16134, 16132, 16144, -1, 16141, 16147, 16145, -1, 12132, 12181, 12180, -1, 16141, 16145, 12174, -1, 12132, 12130, 12181, -1, 16136, 16146, 16148, -1, 16136, 16134, 16146, -1, 16140, 16149, 16147, -1, 16150, 16126, 16123, -1, 16140, 16147, 16141, -1, 16150, 16123, 12118, -1, 16138, 16148, 16151, -1, 12134, 12180, 12179, -1, 16138, 16136, 16148, -1, 12134, 12132, 12180, -1, 16139, 16151, 16149, -1, 16139, 16138, 16151, -1, 16139, 16149, 16140, -1, 12178, 12134, 12179, -1, 16152, 16126, 16150, -1, 12136, 12134, 12178, -1, 16127, 16126, 16152, -1, 16153, 16127, 16152, -1, 12177, 12138, 12136, -1, 12177, 12136, 12178, -1, 16128, 16153, 16142, -1, 16128, 16127, 16153, -1, 16093, 16154, 16155, -1, 16093, 16091, 16154, -1, 12220, 12168, 12222, -1, 12220, 12170, 12168, -1, 12152, 12241, 12239, -1, 16095, 16155, 16156, -1, 16095, 16093, 16155, -1, 12154, 12239, 12237, -1, 12218, 16157, 12172, -1, 12154, 12152, 12239, -1, 12218, 12172, 12170, -1, 12218, 12170, 12220, -1, 16097, 16156, 16158, -1, 12150, 12243, 12241, -1, 16097, 16095, 16156, -1, 12150, 12241, 12152, -1, 12156, 12237, 12235, -1, 16106, 16157, 12218, -1, 12156, 12154, 12237, -1, 16099, 16158, 16159, -1, 12147, 12245, 12243, -1, 16099, 16097, 16158, -1, 12147, 12243, 12150, -1, 16105, 16160, 16157, -1, 16105, 16157, 16106, -1, 12158, 12235, 12233, -1, 12158, 12156, 12235, -1, 16101, 16159, 16161, -1, 16101, 16099, 16159, -1, 16104, 16161, 16160, -1, 16104, 16101, 16161, -1, 16104, 16160, 16105, -1, 12146, 12245, 12147, -1, 12160, 12233, 12232, -1, 12160, 12158, 12233, -1, 16162, 16087, 16085, -1, 16162, 16085, 12245, -1, 16162, 12245, 12146, -1, 12162, 12232, 12228, -1, 12162, 12160, 12232, -1, 16163, 16087, 16162, -1, 12164, 12228, 12226, -1, 12164, 12162, 12228, -1, 16089, 16087, 16163, -1, 16164, 16089, 16163, -1, 12166, 12164, 12226, -1, 12224, 12166, 12226, -1, 16165, 16089, 16164, -1, 16091, 16089, 16165, -1, 16154, 16091, 16165, -1, 12222, 12166, 12224, -1, 12222, 12168, 12166, -1, 12192, 12115, 12113, -1, 12192, 12113, 12194, -1, 16114, 16166, 16167, -1, 16114, 16113, 16166, -1, 12097, 12209, 12207, -1, 12099, 12207, 12205, -1, 12099, 12097, 12207, -1, 12190, 12115, 12192, -1, 12190, 12117, 12115, -1, 12095, 12211, 12209, -1, 12095, 12209, 12097, -1, 12101, 12099, 12205, -1, 12093, 12214, 12211, -1, 12093, 12211, 12095, -1, 12103, 12205, 12204, -1, 12103, 12101, 12205, -1, 16115, 16167, 16168, -1, 16115, 16114, 16167, -1, 12091, 12216, 12214, -1, 12188, 12117, 12190, -1, 12091, 12214, 12093, -1, 16116, 16169, 16170, -1, 16116, 16168, 16169, -1, 12105, 12204, 12203, -1, 16116, 16115, 16168, -1, 12105, 12103, 12204, -1, 16121, 16171, 12117, -1, 16121, 12117, 12188, -1, 16117, 16170, 16172, -1, 16173, 16111, 16109, -1, 16173, 16109, 12216, -1, 16117, 16116, 16170, -1, 16173, 12216, 12091, -1, 16120, 16174, 16171, -1, 12107, 12203, 12198, -1, 16120, 16171, 16121, -1, 12107, 12105, 12203, -1, 16118, 16172, 16175, -1, 16118, 16117, 16172, -1, 16119, 16175, 16174, -1, 16119, 16118, 16175, -1, 16119, 16174, 16120, -1, 16176, 16111, 16173, -1, 12109, 12198, 12196, -1, 12109, 12107, 12198, -1, 16112, 16111, 16176, -1, 16177, 16112, 16176, -1, 12111, 12109, 12196, -1, 12194, 12111, 12196, -1, 12113, 12111, 12194, -1, 16113, 16177, 16166, -1, 16113, 16112, 16177, -1, 12173, 12172, 14324, -1, 14324, 16157, 14326, -1, 12172, 16157, 14324, -1, 14326, 16160, 14327, -1, 16157, 16160, 14326, -1, 14327, 16161, 14306, -1, 16160, 16161, 14327, -1, 14306, 16159, 14307, -1, 16161, 16159, 14306, -1, 14307, 16158, 14311, -1, 16159, 16158, 14307, -1, 14311, 16156, 14315, -1, 16158, 16156, 14311, -1, 14315, 16155, 14319, -1, 16156, 16155, 14315, -1, 14319, 16154, 14321, -1, 16155, 16154, 14319, -1, 14321, 16165, 14322, -1, 16154, 16165, 14321, -1, 14322, 16164, 14320, -1, 16165, 16164, 14322, -1, 14320, 16163, 14317, -1, 16164, 16163, 14320, -1, 14317, 16162, 12148, -1, 16163, 16162, 14317, -1, 16162, 12146, 12148, -1, 12144, 16145, 12145, -1, 12145, 16145, 14299, -1, 14299, 16147, 14301, -1, 16145, 16147, 14299, -1, 14301, 16149, 14302, -1, 16147, 16149, 14301, -1, 14302, 16151, 14303, -1, 16149, 16151, 14302, -1, 14303, 16148, 14282, -1, 16151, 16148, 14303, -1, 14282, 16146, 14283, -1, 16148, 16146, 14282, -1, 14283, 16144, 14287, -1, 16146, 16144, 14283, -1, 14287, 16143, 14290, -1, 16144, 16143, 14287, -1, 14290, 16142, 14294, -1, 16143, 16142, 14290, -1, 14294, 16153, 14297, -1, 16142, 16153, 14294, -1, 14297, 16152, 14296, -1, 16153, 16152, 14297, -1, 14296, 16150, 14292, -1, 16152, 16150, 14296, -1, 14292, 12118, 12120, -1, 16150, 12118, 14292, -1, 12117, 16171, 12116, -1, 12116, 16171, 14347, -1, 14347, 16174, 14349, -1, 16171, 16174, 14347, -1, 14349, 16175, 14350, -1, 16174, 16175, 14349, -1, 14350, 16172, 14351, -1, 16175, 16172, 14350, -1, 14351, 16170, 14330, -1, 16172, 16170, 14351, -1, 14330, 16169, 14331, -1, 16170, 16169, 14330, -1, 14331, 16168, 14335, -1, 16169, 16168, 14331, -1, 14335, 16167, 14339, -1, 16168, 16167, 14335, -1, 14339, 16166, 14343, -1, 16167, 16166, 14339, -1, 14343, 16177, 14345, -1, 16166, 16177, 14343, -1, 14345, 16176, 14344, -1, 16177, 16176, 14345, -1, 14344, 16173, 14340, -1, 16176, 16173, 14344, -1, 14340, 12091, 12090, -1, 16173, 12091, 14340, -1, 12231, 14396, 14398, -1, 14396, 16050, 14394, -1, 14394, 16050, 14392, -1, 12231, 16050, 14396, -1, 16050, 14390, 14392, -1, 16050, 14388, 14390, -1, 14388, 16052, 14387, -1, 14387, 16052, 14482, -1, 16050, 16052, 14388, -1, 16052, 14550, 14482, -1, 16052, 14548, 14550, -1, 14548, 16049, 14546, -1, 14546, 16049, 14475, -1, 16052, 16049, 14548, -1, 16049, 14383, 14475, -1, 16049, 14381, 14383, -1, 14381, 16048, 14379, -1, 14379, 16048, 14377, -1, 16049, 16048, 14381, -1, 16048, 14374, 14377, -1, 16048, 14372, 14374, -1, 14372, 12200, 14370, -1, 16048, 12200, 14372, -1, 12202, 14370, 12200, -1, 12202, 14465, 14370, -1, 12206, 14467, 14465, -1, 12206, 14465, 12202, -1, 12208, 14422, 14467, -1, 12208, 14467, 12206, -1, 12210, 14422, 12208, -1, 14412, 14422, 12210, -1, 12212, 14412, 12210, -1, 14410, 14412, 12212, -1, 12213, 14410, 12212, -1, 14462, 14410, 12213, -1, 12215, 14464, 14462, -1, 12215, 14462, 12213, -1, 16108, 14460, 14464, -1, 16108, 14464, 12215, -1, 16110, 14460, 16108, -1, 14369, 14460, 16110, -1, 16064, 14369, 16110, -1, 16103, 14504, 14402, -1, 16103, 14402, 16036, -1, 16107, 14506, 14504, -1, 16107, 14504, 16103, -1, 12217, 14535, 14506, -1, 12217, 14506, 16107, -1, 12219, 14528, 14535, -1, 12219, 14535, 12217, -1, 12221, 14527, 14528, -1, 12221, 14528, 12219, -1, 12223, 14529, 14527, -1, 12223, 14527, 12221, -1, 12225, 14500, 14529, -1, 12225, 14529, 12223, -1, 12227, 14503, 14500, -1, 12227, 14500, 12225, -1, 12229, 14499, 14503, -1, 12229, 14503, 12227, -1, 12231, 14398, 14499, -1, 12231, 14499, 12229, -1, 16064, 14367, 14369, -1, 14367, 16062, 14366, -1, 14366, 16062, 14363, -1, 16064, 16062, 14367, -1, 16062, 14361, 14363, -1, 16062, 14454, 14361, -1, 14454, 16063, 14455, -1, 14455, 16063, 14537, -1, 16062, 16063, 14454, -1, 16063, 14441, 14537, -1, 16063, 14440, 14441, -1, 14440, 16061, 14442, -1, 14442, 16061, 14354, -1, 16063, 16061, 14440, -1, 16061, 14579, 14354, -1, 16061, 14578, 14579, -1, 14578, 16060, 14577, -1, 14577, 16060, 14576, -1, 16061, 16060, 14578, -1, 16060, 14575, 14576, -1, 16060, 14574, 14575, -1, 14574, 16056, 14428, -1, 16060, 16056, 14574, -1, 16044, 14424, 14358, -1, 14424, 16042, 14420, -1, 14420, 16042, 14418, -1, 16044, 16042, 14424, -1, 16042, 14415, 14418, -1, 16042, 14413, 14415, -1, 14413, 16043, 14572, -1, 14572, 16043, 14573, -1, 16042, 16043, 14413, -1, 16043, 14561, 14573, -1, 16043, 14559, 14561, -1, 14559, 16041, 14557, -1, 14557, 16041, 14555, -1, 16043, 16041, 14559, -1, 16041, 14511, 14555, -1, 16041, 14408, 14511, -1, 14408, 16040, 14406, -1, 14406, 16040, 14404, -1, 16041, 16040, 14408, -1, 16040, 14401, 14404, -1, 16040, 14399, 14401, -1, 14399, 16036, 14402, -1, 16040, 16036, 14399, -1, 16125, 14428, 16056, -1, 16125, 14426, 14428, -1, 16129, 14430, 14426, -1, 16129, 14426, 16125, -1, 14375, 14430, 16129, -1, 16131, 14375, 16129, -1, 16133, 14360, 14375, -1, 16133, 14375, 16131, -1, 16135, 14359, 14360, -1, 16135, 14356, 14359, -1, 16135, 14360, 16133, -1, 16137, 14355, 14356, -1, 16137, 14356, 16135, -1, 14357, 14355, 16137, -1, 16044, 14358, 14357, -1, 16044, 14357, 16137, -1, 16178, 16179, 16180, -1, 16178, 16181, 16179, -1, 16179, 16181, 16182, -1, 16182, 16183, 16184, -1, 16181, 16183, 16182, -1, 16184, 16185, 16186, -1, 16183, 16185, 16184, -1, 16186, 16187, 16188, -1, 16185, 16187, 16186, -1, 16188, 16189, 16190, -1, 16187, 16189, 16188, -1, 16189, 16191, 16190, -1, 16190, 16192, 16193, -1, 16191, 16192, 16190, -1, 16193, 12082, 11166, -1, 16192, 12082, 16193, -1, 16194, 11195, 16195, -1, 11194, 11195, 16194, -1, 16195, 11190, 16196, -1, 11195, 11190, 16195, -1, 16196, 11186, 16197, -1, 11190, 11186, 16196, -1, 16197, 11171, 16198, -1, 11186, 11171, 16197, -1, 16198, 11173, 16199, -1, 11171, 11173, 16198, -1, 16199, 11206, 16200, -1, 11173, 11206, 16199, -1, 16200, 11208, 16201, -1, 11206, 11208, 16200, -1, 16201, 16202, 16203, -1, 11208, 16202, 16201, -1, 16203, 16204, 16205, -1, 16202, 16204, 16203, -1, 16205, 16206, 16207, -1, 16204, 16206, 16205, -1, 16207, 16208, 16209, -1, 16206, 16208, 16207, -1, 16209, 16210, 16211, -1, 16208, 16210, 16209, -1, 16211, 16212, 16180, -1, 16210, 16212, 16211, -1, 16212, 16178, 16180, -1, 12089, 11194, 11154, -1, 11154, 11194, 16194, -1, 16213, 16214, 16215, -1, 16213, 16216, 16214, -1, 16216, 16217, 16214, -1, 16218, 16217, 16219, -1, 16214, 16217, 16218, -1, 16219, 16220, 16221, -1, 16217, 16220, 16219, -1, 16221, 16222, 16223, -1, 16220, 16222, 16221, -1, 16223, 16224, 16225, -1, 16222, 16224, 16223, -1, 16225, 16226, 16227, -1, 16224, 16226, 16225, -1, 16227, 16228, 16229, -1, 16226, 16228, 16227, -1, 16229, 16230, 16231, -1, 16228, 16230, 16229, -1, 16231, 16232, 16233, -1, 16230, 16232, 16231, -1, 16233, 16234, 16235, -1, 16232, 16234, 16233, -1, 16235, 16236, 11277, -1, 16234, 16236, 16235, -1, 16236, 12078, 11277, -1, 11255, 11254, 16237, -1, 16237, 11254, 16238, -1, 16238, 11268, 16239, -1, 11254, 11268, 16238, -1, 16239, 11264, 16240, -1, 11268, 11264, 16239, -1, 16240, 11249, 16241, -1, 11264, 11249, 16240, -1, 16241, 11245, 16242, -1, 11249, 11245, 16241, -1, 16242, 11240, 16243, -1, 11245, 11240, 16242, -1, 16243, 11234, 16244, -1, 11240, 11234, 16243, -1, 16244, 11229, 16245, -1, 11234, 11229, 16244, -1, 16245, 11223, 16246, -1, 11229, 11223, 16245, -1, 16246, 11225, 16247, -1, 11223, 11225, 16246, -1, 16247, 11214, 16248, -1, 11225, 11214, 16247, -1, 16248, 16249, 16250, -1, 11214, 16249, 16248, -1, 16250, 16251, 16215, -1, 16249, 16251, 16250, -1, 16251, 16213, 16215, -1, 11289, 11255, 16237, -1, 12081, 11255, 11289, -1, 11130, 11069, 16252, -1, 12077, 11069, 11130, -1, 11069, 11070, 16252, -1, 16252, 11070, 16253, -1, 16253, 11055, 16254, -1, 11070, 11055, 16253, -1, 16254, 11054, 16255, -1, 11055, 11054, 16254, -1, 16255, 16256, 16257, -1, 11054, 16256, 16255, -1, 16257, 16258, 16259, -1, 16256, 16258, 16257, -1, 16259, 16260, 16261, -1, 16258, 16260, 16259, -1, 16261, 16262, 16263, -1, 16260, 16262, 16261, -1, 16263, 16264, 16265, -1, 16262, 16264, 16263, -1, 16265, 16266, 16267, -1, 16264, 16266, 16265, -1, 16267, 16268, 16269, -1, 16266, 16268, 16267, -1, 16269, 16270, 16271, -1, 16268, 16270, 16269, -1, 16271, 16272, 16273, -1, 16270, 16272, 16271, -1, 16273, 16274, 16275, -1, 16272, 16274, 16273, -1, 16274, 16276, 16275, -1, 16277, 16278, 16279, -1, 16278, 16280, 16279, -1, 16279, 16281, 16282, -1, 16280, 16281, 16279, -1, 16282, 12066, 11092, -1, 16281, 12066, 16282, -1, 16276, 16277, 16275, -1, 16276, 16278, 16277, -1, 16283, 16284, 16285, -1, 16286, 16284, 16283, -1, 12053, 16287, 11865, -1, 11865, 16287, 16288, -1, 16285, 16289, 16290, -1, 16290, 16289, 16291, -1, 16284, 16289, 16285, -1, 16288, 16292, 16293, -1, 16287, 16292, 16288, -1, 16291, 16294, 16295, -1, 16289, 16294, 16291, -1, 16295, 16296, 16297, -1, 16293, 16298, 16299, -1, 16294, 16296, 16295, -1, 16292, 16298, 16293, -1, 16297, 16300, 16301, -1, 16299, 16302, 16303, -1, 16296, 16300, 16297, -1, 16298, 16302, 16299, -1, 16301, 16304, 16305, -1, 16302, 16306, 16303, -1, 16300, 16304, 16301, -1, 16303, 16306, 16307, -1, 16305, 16308, 16309, -1, 16304, 16308, 16305, -1, 16307, 16310, 16311, -1, 16309, 16312, 16313, -1, 16306, 16314, 16307, -1, 16308, 16312, 16309, -1, 16307, 16314, 16310, -1, 16312, 16315, 16313, -1, 16314, 16316, 16310, -1, 16313, 16315, 16317, -1, 16316, 16318, 16319, -1, 16315, 16320, 16317, -1, 16314, 16321, 16316, -1, 16316, 16321, 16318, -1, 16317, 16320, 16322, -1, 16320, 16323, 16322, -1, 16321, 16324, 16318, -1, 16322, 16323, 16325, -1, 16318, 16324, 16326, -1, 16323, 16327, 16325, -1, 16324, 16328, 16326, -1, 16325, 16327, 16329, -1, 16326, 16328, 16330, -1, 16328, 16331, 16330, -1, 16331, 16332, 16330, -1, 16329, 16333, 16334, -1, 16331, 16335, 16332, -1, 16327, 16336, 16329, -1, 16329, 16336, 16333, -1, 16335, 16337, 16332, -1, 16335, 16338, 16337, -1, 16338, 16339, 16337, -1, 16336, 16340, 16333, -1, 16338, 16341, 16339, -1, 16333, 16340, 16342, -1, 16341, 16343, 16339, -1, 16340, 16344, 16342, -1, 16342, 16344, 16345, -1, 16341, 16346, 16343, -1, 16340, 16347, 16344, -1, 16346, 16348, 16343, -1, 16347, 16349, 16344, -1, 16346, 16350, 16348, -1, 16347, 16351, 16349, -1, 16350, 16352, 16348, -1, 16351, 16353, 16349, -1, 16351, 16354, 16353, -1, 16350, 16355, 16352, -1, 16354, 16356, 16353, -1, 16355, 16357, 16352, -1, 16354, 16358, 16356, -1, 16355, 16359, 16357, -1, 16358, 16360, 16356, -1, 16359, 16361, 16357, -1, 16358, 16362, 16360, -1, 16359, 16286, 16361, -1, 16362, 11871, 16360, -1, 16286, 16363, 16361, -1, 16362, 12057, 11871, -1, 16286, 16283, 16363, -1, 16364, 16365, 16366, -1, 16364, 16367, 16365, -1, 16368, 16366, 16369, -1, 16368, 16364, 16366, -1, 16370, 16369, 16371, -1, 16370, 16368, 16369, -1, 16372, 16371, 16373, -1, 16372, 16370, 16371, -1, 16374, 16373, 16375, -1, 16374, 16372, 16373, -1, 16376, 16374, 16375, -1, 16377, 16375, 16378, -1, 16377, 16376, 16375, -1, 16379, 16378, 16380, -1, 16379, 16377, 16378, -1, 16381, 16380, 16382, -1, 16381, 16379, 16380, -1, 16383, 16382, 16384, -1, 16383, 16381, 16382, -1, 16385, 16384, 16386, -1, 16385, 16383, 16384, -1, 16387, 16386, 16388, -1, 16387, 16385, 16386, -1, 16389, 16388, 16390, -1, 16389, 16387, 16388, -1, 16391, 16390, 16392, -1, 16391, 16389, 16390, -1, 16393, 16392, 11562, -1, 16393, 16391, 16392, -1, 16394, 16395, 16396, -1, 16394, 16397, 16395, -1, 16398, 16396, 16399, -1, 16398, 16394, 16396, -1, 16400, 16399, 16401, -1, 16400, 16398, 16399, -1, 16402, 16400, 16401, -1, 16402, 16401, 16403, -1, 16404, 16402, 16403, -1, 16405, 16406, 16407, -1, 16405, 16407, 16408, -1, 16409, 16405, 16408, -1, 11654, 11647, 11557, -1, 11654, 16410, 16411, -1, 11654, 11557, 16410, -1, 16412, 16413, 16414, -1, 16412, 16415, 16413, -1, 16416, 16414, 16417, -1, 16416, 16412, 16414, -1, 16418, 16417, 16419, -1, 16418, 16416, 16417, -1, 16420, 16419, 16421, -1, 16420, 16418, 16419, -1, 16422, 16421, 16423, -1, 16422, 16420, 16421, -1, 16424, 16423, 16425, -1, 16424, 16422, 16423, -1, 16426, 11608, 16427, -1, 16428, 16427, 16429, -1, 16428, 16426, 16427, -1, 16430, 16428, 16429, -1, 16430, 16429, 16431, -1, 16432, 16430, 16431, -1, 16432, 16431, 16433, -1, 16434, 16432, 16433, -1, 16434, 16433, 16435, -1, 16436, 16435, 16437, -1, 11662, 11654, 16411, -1, 11662, 16438, 16439, -1, 11662, 16411, 16438, -1, 16436, 16434, 16435, -1, 16440, 16436, 16437, -1, 16440, 16437, 16441, -1, 16442, 16440, 16441, -1, 16442, 16441, 16443, -1, 16444, 16442, 16443, -1, 16445, 16444, 16443, -1, 16445, 16443, 16446, -1, 11670, 11662, 16439, -1, 11670, 16439, 16447, -1, 16448, 16445, 16446, -1, 16448, 16446, 16449, -1, 16450, 16448, 16449, -1, 16450, 16449, 16451, -1, 16452, 16450, 16451, -1, 16452, 16451, 16453, -1, 16454, 16452, 16453, -1, 16454, 16453, 16455, -1, 16456, 16454, 16455, -1, 16457, 16456, 16455, -1, 16457, 16455, 16458, -1, 16459, 16457, 16458, -1, 16459, 16458, 16460, -1, 16461, 16459, 16460, -1, 16461, 16460, 16462, -1, 16463, 16461, 16462, -1, 16463, 16462, 16464, -1, 16463, 16464, 11548, -1, 16465, 16466, 16467, -1, 16465, 16468, 16469, -1, 16465, 16469, 11530, -1, 16465, 11530, 16466, -1, 16470, 16471, 16472, -1, 16470, 16364, 16368, -1, 16470, 16367, 16364, -1, 16473, 16474, 16475, -1, 16473, 16376, 16377, -1, 16476, 16474, 16473, -1, 16476, 16477, 16474, -1, 16476, 16473, 16377, -1, 16476, 16379, 16381, -1, 16476, 16377, 16379, -1, 16478, 11628, 16479, -1, 16478, 16385, 16387, -1, 16480, 16387, 16389, -1, 16480, 11628, 16478, -1, 16480, 16389, 16391, -1, 16480, 16478, 16387, -1, 16480, 11629, 11628, -1, 16481, 11562, 11560, -1, 16481, 16480, 16391, -1, 16481, 11629, 16480, -1, 16481, 16393, 11562, -1, 16481, 16391, 16393, -1, 16482, 11557, 11647, -1, 16482, 11558, 11557, -1, 16482, 11560, 11558, -1, 16482, 16481, 11560, -1, 16482, 11629, 16481, -1, 16482, 11647, 11629, -1, 16483, 11683, 11670, -1, 16483, 11670, 16447, -1, 16483, 16447, 16484, -1, 16485, 11683, 16483, -1, 16485, 16484, 16397, -1, 16485, 16397, 16394, -1, 16485, 16483, 16484, -1, 16486, 11686, 11683, -1, 16486, 16398, 16400, -1, 16486, 11683, 16485, -1, 16486, 16485, 16394, -1, 16486, 16394, 16398, -1, 16487, 16488, 16404, -1, 16487, 16407, 16406, -1, 16487, 16489, 16407, -1, 16487, 16490, 16489, -1, 16487, 16403, 16490, -1, 16487, 16491, 16488, -1, 16487, 16406, 16491, -1, 16487, 16404, 16403, -1, 16492, 11690, 11686, -1, 16492, 16400, 16402, -1, 16492, 11686, 16486, -1, 16492, 16486, 16400, -1, 16493, 16494, 16413, -1, 11643, 16495, 16496, -1, 16493, 16497, 16498, -1, 16493, 16498, 16409, -1, 16493, 16499, 16494, -1, 16493, 16408, 16499, -1, 16493, 16413, 16415, -1, 16493, 16409, 16408, -1, 16493, 16415, 16497, -1, 16500, 11703, 11698, -1, 16500, 16406, 16405, -1, 16501, 11706, 11703, -1, 16501, 16500, 16405, -1, 16501, 16409, 16498, -1, 16501, 16405, 16409, -1, 16501, 11703, 16500, -1, 16502, 11622, 11706, -1, 16502, 16498, 16497, -1, 16502, 11706, 16501, -1, 16502, 16497, 16415, -1, 16502, 16501, 16498, -1, 16503, 11637, 11626, -1, 16503, 16420, 16422, -1, 16503, 16422, 16424, -1, 16504, 16425, 16505, -1, 16504, 16424, 16425, -1, 16504, 16503, 16424, -1, 16504, 11637, 16503, -1, 11651, 16506, 16507, -1, 16508, 11643, 11637, -1, 11651, 16496, 16506, -1, 16508, 16505, 16495, -1, 16508, 16504, 16505, -1, 16508, 16495, 11643, -1, 11651, 11643, 16496, -1, 16508, 11637, 16504, -1, 16509, 11609, 11608, -1, 16509, 11608, 16426, -1, 16510, 11669, 11615, -1, 16510, 11609, 16509, -1, 16510, 11682, 11669, -1, 16510, 11613, 11609, -1, 16510, 11615, 11613, -1, 16510, 16509, 11682, -1, 16511, 16430, 16432, -1, 16511, 11680, 11682, -1, 16511, 16509, 16426, -1, 16511, 16426, 16428, -1, 16511, 11682, 16509, -1, 16511, 16428, 16430, -1, 16512, 16511, 16432, -1, 16512, 16434, 16436, -1, 16512, 11680, 16511, -1, 16512, 16432, 16434, -1, 16512, 16513, 11680, -1, 16514, 16436, 16440, -1, 16514, 16512, 16436, -1, 16514, 16515, 16513, -1, 16514, 16513, 16512, -1, 16516, 16517, 16518, -1, 16516, 16444, 16445, -1, 16519, 16448, 16450, -1, 16519, 16516, 16445, -1, 16519, 16520, 16517, -1, 16519, 16445, 16448, -1, 16519, 16517, 16516, -1, 16521, 16452, 16454, -1, 16521, 16450, 16452, -1, 16521, 16520, 16519, -1, 16521, 16519, 16450, -1, 16521, 16522, 16520, -1, 16523, 16461, 16463, -1, 16523, 16524, 16525, -1, 16526, 16524, 16523, -1, 16526, 16463, 11548, -1, 11660, 16527, 11615, -1, 16526, 16523, 16463, -1, 11660, 16507, 16527, -1, 16526, 11547, 11545, -1, 16526, 11548, 11547, -1, 16528, 16526, 11545, -1, 16528, 16524, 16526, -1, 16528, 11543, 16529, -1, 11660, 11651, 16507, -1, 16528, 11545, 11543, -1, 16528, 16529, 16524, -1, 16530, 16531, 16468, -1, 16530, 16467, 16532, -1, 16530, 16465, 16467, -1, 16530, 16468, 16465, -1, 16533, 16530, 16532, -1, 16533, 16532, 16367, -1, 16533, 16472, 16531, -1, 16533, 16531, 16530, -1, 16533, 16367, 16470, -1, 16533, 16470, 16472, -1, 16534, 16470, 16368, -1, 16534, 16368, 16370, -1, 11669, 11660, 11615, -1, 16534, 16370, 16372, -1, 16535, 16471, 16470, -1, 16535, 16536, 16471, -1, 16535, 16470, 16534, -1, 16537, 16376, 16473, -1, 16537, 16372, 16374, -1, 16537, 16374, 16376, -1, 16538, 16473, 16475, -1, 16538, 16537, 16473, -1, 16538, 16475, 16536, -1, 16539, 16476, 16381, -1, 16539, 16381, 16383, -1, 16539, 16383, 16385, -1, 16539, 16385, 16478, -1, 16540, 16477, 16476, -1, 16540, 16478, 16479, -1, 16540, 16479, 16477, -1, 16540, 16476, 16539, -1, 16540, 16539, 16478, -1, 16541, 16404, 16488, -1, 16541, 16492, 16402, -1, 16541, 16402, 16404, -1, 16542, 11694, 11690, -1, 16542, 16492, 16541, -1, 16542, 11690, 16492, -1, 16543, 16406, 16500, -1, 16543, 16488, 16491, -1, 16543, 16491, 16406, -1, 16544, 11698, 11694, -1, 16544, 16543, 16500, -1, 16544, 16500, 11698, -1, 16545, 16415, 16412, -1, 16545, 16412, 16416, -1, 16545, 16502, 16415, -1, 16546, 11620, 11622, -1, 16546, 16502, 16545, -1, 16546, 11622, 16502, -1, 16547, 16416, 16418, -1, 16547, 16418, 16420, -1, 16547, 16420, 16503, -1, 16548, 11626, 11620, -1, 16548, 16547, 16503, -1, 16548, 16503, 11626, -1, 16549, 16444, 16516, -1, 16549, 16514, 16440, -1, 16549, 16440, 16442, -1, 16549, 16442, 16444, -1, 16550, 16516, 16518, -1, 16550, 16514, 16549, -1, 16550, 16518, 16515, -1, 16550, 16549, 16516, -1, 16550, 16515, 16514, -1, 16551, 16521, 16454, -1, 16551, 16454, 16456, -1, 16551, 16456, 16457, -1, 16552, 16522, 16521, -1, 16552, 16521, 16551, -1, 16552, 16553, 16522, -1, 16554, 16457, 16459, -1, 16554, 16459, 16461, -1, 16554, 16461, 16523, -1, 16555, 16523, 16525, -1, 16555, 16554, 16523, -1, 16555, 16525, 16553, -1, 16556, 16534, 16372, -1, 16556, 16536, 16535, -1, 16556, 16535, 16534, -1, 16556, 16537, 16538, -1, 16556, 16538, 16536, -1, 16556, 16372, 16537, -1, 16557, 11694, 16542, -1, 16557, 16544, 11694, -1, 16557, 16542, 16541, -1, 16557, 16543, 16544, -1, 16557, 16541, 16488, -1, 16557, 16488, 16543, -1, 16558, 11620, 16546, -1, 16558, 16548, 11620, -1, 16558, 16546, 16545, -1, 16558, 16547, 16548, -1, 16558, 16545, 16416, -1, 16558, 16416, 16547, -1, 16559, 16457, 16554, -1, 16559, 16554, 16555, -1, 16559, 16551, 16457, -1, 16559, 16552, 16551, -1, 16559, 16553, 16552, -1, 16559, 16555, 16553, -1, 16529, 11543, 11541, -1, 16560, 16529, 11541, -1, 16560, 11539, 11538, -1, 16560, 11541, 11539, -1, 16561, 11536, 11534, -1, 16561, 11538, 11536, -1, 16561, 16560, 11538, -1, 16469, 16561, 11534, -1, 16469, 11528, 11530, -1, 16469, 11534, 11528, -1, 16466, 11530, 16562, -1, 16467, 16562, 16563, -1, 16467, 16466, 16562, -1, 16532, 16563, 16564, -1, 16532, 16467, 16563, -1, 16367, 16564, 16365, -1, 16367, 16532, 16564, -1, 16565, 16566, 16567, -1, 14276, 16568, 14275, -1, 16569, 16568, 14276, -1, 14258, 16568, 16569, -1, 16570, 16571, 16566, -1, 16566, 16571, 14248, -1, 16568, 16572, 14275, -1, 14275, 16572, 14259, -1, 14259, 16572, 14258, -1, 14258, 16572, 16568, -1, 14248, 16573, 14247, -1, 14247, 16573, 16574, -1, 16574, 16573, 16570, -1, 16571, 16573, 14248, -1, 16570, 16573, 16571, -1, 14259, 16575, 14275, -1, 14274, 16575, 14260, -1, 14260, 16575, 14259, -1, 14275, 16575, 14274, -1, 14260, 16576, 14274, -1, 14261, 16576, 14260, -1, 14262, 16577, 14261, -1, 14273, 16577, 14262, -1, 14274, 16577, 14273, -1, 16576, 16577, 14274, -1, 14261, 16577, 16576, -1, 16578, 16579, 16580, -1, 16580, 16579, 14262, -1, 16581, 16582, 16583, -1, 14262, 16579, 14273, -1, 16583, 16582, 16584, -1, 14273, 16579, 14272, -1, 16584, 16582, 16585, -1, 14272, 16579, 16578, -1, 16586, 16587, 16588, -1, 16588, 16587, 16578, -1, 16589, 16582, 16581, -1, 14272, 16587, 14271, -1, 16578, 16587, 14272, -1, 16586, 16590, 16587, -1, 16591, 16590, 16586, -1, 16587, 16592, 14271, -1, 14271, 16592, 14270, -1, 16593, 16594, 16595, -1, 16595, 16594, 16591, -1, 16591, 16594, 16590, -1, 16590, 16596, 16587, -1, 16587, 16596, 16592, -1, 16592, 16597, 14270, -1, 16590, 16598, 16596, -1, 16599, 16598, 16594, -1, 16594, 16598, 16590, -1, 16596, 16600, 16592, -1, 16592, 16600, 16597, -1, 16597, 16601, 14270, -1, 14270, 16601, 14269, -1, 14269, 16601, 14268, -1, 16596, 16602, 16600, -1, 16598, 16602, 16596, -1, 16600, 16603, 16597, -1, 16597, 16603, 16601, -1, 16600, 16604, 16603, -1, 16602, 16604, 16600, -1, 16605, 16604, 16606, -1, 16606, 16604, 16602, -1, 16601, 16607, 14268, -1, 16603, 16607, 16601, -1, 14268, 16607, 14267, -1, 16604, 16608, 16603, -1, 16605, 16608, 16604, -1, 16603, 16608, 16607, -1, 14263, 16609, 14264, -1, 16607, 16610, 14267, -1, 14264, 16609, 16611, -1, 14267, 16610, 14266, -1, 16605, 16612, 16608, -1, 16608, 16612, 16607, -1, 16610, 16612, 14266, -1, 16613, 16612, 16605, -1, 16609, 16614, 16611, -1, 16607, 16612, 16610, -1, 16574, 14245, 14247, -1, 16612, 16615, 14266, -1, 16613, 16615, 16612, -1, 14266, 16615, 14265, -1, 16613, 16616, 16615, -1, 16615, 16616, 14265, -1, 14265, 16616, 14263, -1, 16609, 16616, 16613, -1, 14263, 16616, 16609, -1, 16585, 16617, 16618, -1, 16618, 16617, 16593, -1, 16582, 16617, 16585, -1, 16593, 16617, 16594, -1, 16594, 16617, 16599, -1, 16614, 16619, 16620, -1, 16599, 16617, 16582, -1, 16620, 16619, 16621, -1, 16599, 16622, 16598, -1, 16606, 16622, 16599, -1, 16602, 16622, 16606, -1, 16598, 16622, 16602, -1, 16609, 16619, 16614, -1, 14254, 16623, 14255, -1, 14255, 16623, 14279, -1, 14279, 16623, 14278, -1, 16624, 16625, 16626, -1, 16626, 16625, 14253, -1, 14253, 16625, 14252, -1, 16627, 16625, 16624, -1, 16623, 16628, 14278, -1, 14256, 16628, 14254, -1, 14245, 16589, 14246, -1, 14278, 16628, 14277, -1, 14246, 16589, 16629, -1, 14254, 16628, 16623, -1, 14252, 16630, 14251, -1, 16574, 16589, 14245, -1, 16627, 16630, 16625, -1, 16625, 16630, 14252, -1, 16589, 16581, 16629, -1, 16628, 16631, 14277, -1, 14256, 16631, 16628, -1, 14251, 16632, 14250, -1, 16627, 16632, 16630, -1, 16630, 16632, 14251, -1, 16565, 16632, 16627, -1, 16631, 16633, 14277, -1, 14256, 16633, 16631, -1, 14257, 16633, 14256, -1, 14277, 16633, 14276, -1, 14250, 16567, 14249, -1, 16565, 16567, 16632, -1, 16632, 16567, 14250, -1, 14258, 16569, 14257, -1, 16633, 16569, 14276, -1, 14257, 16569, 16633, -1, 14249, 16566, 14248, -1, 16567, 16566, 14249, -1, 16570, 16566, 16565, -1, 16358, 16634, 16362, -1, 13537, 16634, 13559, -1, 16354, 16635, 16358, -1, 16351, 16635, 16354, -1, 16634, 16635, 13559, -1, 13559, 16635, 13567, -1, 16636, 16284, 16637, -1, 16358, 16635, 16634, -1, 16289, 16284, 16636, -1, 16347, 16638, 16351, -1, 16351, 16638, 16635, -1, 13567, 16638, 13573, -1, 13573, 16638, 13577, -1, 16635, 16638, 13567, -1, 16340, 16639, 16347, -1, 16640, 16639, 16340, -1, 13577, 16639, 13583, -1, 13583, 16639, 16640, -1, 16284, 16286, 16637, -1, 16347, 16639, 16638, -1, 16638, 16639, 13577, -1, 16327, 16641, 16336, -1, 16336, 16641, 16642, -1, 16642, 16641, 13722, -1, 13722, 16641, 13738, -1, 16327, 16643, 16641, -1, 16323, 16643, 16327, -1, 16641, 16643, 13738, -1, 13738, 16643, 13809, -1, 13809, 16643, 13713, -1, 16320, 16644, 16323, -1, 16315, 16644, 16320, -1, 16323, 16644, 16643, -1, 16643, 16644, 13713, -1, 13713, 16644, 13740, -1, 16312, 16645, 16315, -1, 13740, 16645, 13757, -1, 16315, 16645, 16644, -1, 16644, 16645, 13740, -1, 16308, 16646, 16312, -1, 16645, 16646, 13757, -1, 13757, 16646, 13716, -1, 13716, 16646, 13735, -1, 16312, 16646, 16645, -1, 16304, 16647, 16308, -1, 16300, 16647, 16304, -1, 16308, 16647, 16646, -1, 16646, 16647, 13735, -1, 13735, 16647, 13779, -1, 16296, 16648, 16300, -1, 13779, 16648, 13785, -1, 16300, 16648, 16647, -1, 16647, 16648, 13779, -1, 16648, 16649, 13785, -1, 16294, 16649, 16296, -1, 16289, 16649, 16294, -1, 13785, 16649, 13788, -1, 13788, 16649, 13798, -1, 16296, 16649, 16648, -1, 16289, 16650, 16649, -1, 16649, 16650, 13798, -1, 13798, 16650, 13804, -1, 13804, 16650, 16636, -1, 16636, 16650, 16289, -1, 16340, 16642, 16640, -1, 16637, 16651, 16624, -1, 16624, 16651, 16627, -1, 16286, 16651, 16637, -1, 16359, 16652, 16286, -1, 16340, 16336, 16642, -1, 16355, 16652, 16359, -1, 16286, 16652, 16651, -1, 16651, 16652, 16627, -1, 16627, 16652, 16565, -1, 16565, 16652, 16570, -1, 16350, 16653, 16355, -1, 16570, 16653, 16574, -1, 16355, 16653, 16652, -1, 16652, 16653, 16570, -1, 16346, 16654, 16350, -1, 16341, 16654, 16346, -1, 16574, 16654, 16589, -1, 16350, 16654, 16653, -1, 16653, 16654, 16574, -1, 16341, 16655, 16654, -1, 16654, 16655, 16589, -1, 16338, 16655, 16341, -1, 16589, 16655, 16582, -1, 16582, 16655, 16599, -1, 16338, 16656, 16655, -1, 16655, 16656, 16599, -1, 16335, 16656, 16338, -1, 16599, 16656, 16606, -1, 16331, 16657, 16335, -1, 16328, 16657, 16331, -1, 16656, 16657, 16606, -1, 16335, 16657, 16656, -1, 16606, 16657, 16605, -1, 16324, 16658, 16328, -1, 16657, 16658, 16605, -1, 16328, 16658, 16657, -1, 16605, 16658, 16613, -1, 16613, 16658, 16609, -1, 16659, 16660, 16321, -1, 16321, 16660, 16324, -1, 16658, 16660, 16609, -1, 16324, 16660, 16658, -1, 16609, 16660, 16619, -1, 16619, 16660, 16659, -1, 16314, 16661, 16662, -1, 16306, 16661, 16314, -1, 16662, 16661, 13834, -1, 13834, 16661, 13833, -1, 16302, 16663, 16306, -1, 16306, 16663, 16661, -1, 13833, 16663, 13837, -1, 13837, 16663, 13845, -1, 16661, 16663, 13833, -1, 16298, 16664, 16302, -1, 16292, 16664, 16298, -1, 13845, 16664, 13854, -1, 16663, 16664, 13845, -1, 16302, 16664, 16663, -1, 16292, 16665, 16664, -1, 16321, 16314, 16659, -1, 16664, 16665, 13854, -1, 16287, 16665, 16292, -1, 16659, 16314, 16662, -1, 13854, 16665, 13868, -1, 13537, 16666, 16634, -1, 12057, 16666, 12055, -1, 12055, 16666, 13537, -1, 16362, 16667, 12057, -1, 12057, 16667, 16666, -1, 16666, 16667, 16634, -1, 16634, 16667, 16362, -1, 16665, 16668, 13868, -1, 13868, 16668, 12051, -1, 16668, 16669, 12051, -1, 16287, 16669, 16665, -1, 12053, 16669, 16287, -1, 16665, 16669, 16668, -1, 12051, 16669, 12053, -1, 16307, 15191, 16303, -1, 15191, 15190, 16303, -1, 16303, 15190, 16299, -1, 15209, 15207, 16291, -1, 16291, 16670, 16290, -1, 15207, 16670, 16291, -1, 15190, 15189, 16299, -1, 16299, 15189, 16293, -1, 11873, 15206, 11871, -1, 11871, 15206, 16360, -1, 15189, 15188, 16293, -1, 16293, 15188, 16288, -1, 15206, 15208, 16360, -1, 15188, 15187, 16288, -1, 16360, 15208, 16356, -1, 16288, 15187, 11865, -1, 16671, 16361, 16363, -1, 15187, 11863, 11865, -1, 16670, 15205, 16672, -1, 16672, 15205, 16673, -1, 15208, 15210, 16356, -1, 16673, 15205, 16671, -1, 16356, 15210, 16353, -1, 15207, 15205, 16670, -1, 15210, 15212, 16353, -1, 16353, 15212, 16349, -1, 15205, 15204, 16671, -1, 16671, 15204, 16361, -1, 16361, 15203, 16357, -1, 15212, 15214, 16349, -1, 16349, 15214, 16344, -1, 15204, 15203, 16361, -1, 15214, 16674, 16344, -1, 16357, 15202, 16352, -1, 16344, 16674, 16345, -1, 15203, 15202, 16357, -1, 15202, 15201, 16352, -1, 16352, 15201, 16348, -1, 15201, 15200, 16348, -1, 15214, 15216, 16674, -1, 16348, 15200, 16343, -1, 16674, 15216, 16675, -1, 16675, 15216, 16676, -1, 16676, 15216, 16677, -1, 16677, 16329, 16334, -1, 15200, 15199, 16343, -1, 16343, 15199, 16339, -1, 15216, 15218, 16677, -1, 16677, 15218, 16329, -1, 15199, 15198, 16339, -1, 16339, 15198, 16337, -1, 15218, 15219, 16329, -1, 16329, 15219, 16325, -1, 15198, 15197, 16337, -1, 16337, 15197, 16332, -1, 15219, 15221, 16325, -1, 16325, 15221, 16322, -1, 15197, 15196, 16332, -1, 16332, 15196, 16330, -1, 15221, 15223, 16322, -1, 16322, 15223, 16317, -1, 15196, 15195, 16330, -1, 15223, 15222, 16317, -1, 16330, 15195, 16326, -1, 16317, 15222, 16313, -1, 15195, 15194, 16326, -1, 16326, 15194, 16318, -1, 15222, 15220, 16313, -1, 16313, 15220, 16309, -1, 15220, 15217, 16309, -1, 16309, 15217, 16305, -1, 16318, 16678, 16319, -1, 15194, 15193, 16318, -1, 16318, 15193, 16678, -1, 16305, 15215, 16301, -1, 15217, 15215, 16305, -1, 16301, 15213, 16297, -1, 15215, 15213, 16301, -1, 16679, 16307, 16311, -1, 16297, 15211, 16295, -1, 15193, 15192, 16678, -1, 15213, 15211, 16297, -1, 16678, 15192, 16680, -1, 16680, 15192, 16681, -1, 16681, 15192, 16679, -1, 16295, 15209, 16291, -1, 15211, 15209, 16295, -1, 15192, 15191, 16679, -1, 16679, 15191, 16307, -1, 16682, 16683, 16684, -1, 16685, 16682, 16684, -1, 13891, 16685, 16684, -1, 16686, 16685, 13891, -1, 16687, 16686, 13891, -1, 13892, 16687, 13891, -1, 13890, 13892, 13891, -1, 16688, 16689, 16690, -1, 16691, 16688, 16690, -1, 14126, 16691, 16690, -1, 16692, 16691, 14126, -1, 16693, 16692, 14126, -1, 14127, 16693, 14126, -1, 14125, 14127, 14126, -1, 16694, 16695, 16696, -1, 16697, 16694, 16696, -1, 13827, 16697, 16696, -1, 16698, 16697, 13827, -1, 16699, 16698, 13827, -1, 13828, 16699, 13827, -1, 13826, 13828, 13827, -1, 16700, 16701, 16702, -1, 16703, 16704, 16705, -1, 16706, 16701, 16700, -1, 16702, 16701, 16707, -1, 16707, 16701, 16708, -1, 16708, 16701, 16709, -1, 16709, 16701, 16710, -1, 16704, 16711, 16705, -1, 16704, 16712, 16711, -1, 16704, 16713, 16712, -1, 16713, 16714, 16715, -1, 16701, 11731, 16710, -1, 16704, 16716, 16713, -1, 16713, 16716, 16714, -1, 16704, 16717, 16716, -1, 16718, 16719, 16704, -1, 16704, 16720, 16718, -1, 16719, 16721, 16704, -1, 16704, 16722, 16717, -1, 16721, 16722, 16704, -1, 16723, 16724, 16725, -1, 11718, 16724, 16726, -1, 16726, 16724, 16727, -1, 16727, 16724, 16723, -1, 16722, 16728, 16717, -1, 11721, 16724, 11719, -1, 11719, 16724, 11718, -1, 16725, 16724, 16717, -1, 16728, 16729, 16717, -1, 16729, 16730, 16717, -1, 16730, 16731, 16717, -1, 16731, 16725, 16717, -1, 11731, 11457, 11729, -1, 11729, 11457, 11727, -1, 11721, 11457, 16724, -1, 11727, 11457, 11725, -1, 11725, 11457, 11723, -1, 11723, 11457, 11721, -1, 16701, 11457, 11731, -1, 16732, 16733, 16700, -1, 11457, 11456, 16724, -1, 16734, 16735, 16733, -1, 16736, 11444, 11443, -1, 16733, 16735, 16700, -1, 16737, 11444, 16736, -1, 16724, 11448, 16737, -1, 16737, 11448, 11444, -1, 16700, 16738, 16704, -1, 16704, 16738, 16720, -1, 16700, 16739, 16738, -1, 11454, 11450, 11456, -1, 11452, 11450, 11454, -1, 11456, 11450, 16724, -1, 16724, 11450, 11448, -1, 16700, 16740, 16739, -1, 16700, 16741, 16740, -1, 16742, 16743, 16735, -1, 16744, 16743, 16742, -1, 16735, 16743, 16700, -1, 16700, 16745, 16741, -1, 16700, 16702, 16745, -1, 16743, 16706, 16700, -1, 16746, 16747, 16725, -1, 16747, 16748, 16725, -1, 16748, 16749, 16725, -1, 16749, 16750, 16725, -1, 16750, 16751, 16725, -1, 16752, 16723, 16753, -1, 16753, 16723, 16751, -1, 16751, 16723, 16725, -1, 16752, 16754, 16723, -1, 16754, 16755, 16723, -1, 16756, 16757, 16738, -1, 16757, 16758, 16738, -1, 16758, 16759, 16738, -1, 16759, 16760, 16738, -1, 16760, 16761, 16738, -1, 16762, 16720, 16763, -1, 16763, 16720, 16761, -1, 16761, 16720, 16738, -1, 16762, 16764, 16720, -1, 16764, 16765, 16720, -1, 11730, 16766, 11731, -1, 16766, 16767, 11731, -1, 16767, 16768, 11731, -1, 16768, 16769, 11731, -1, 16769, 16770, 11731, -1, 16771, 16710, 16772, -1, 16772, 16710, 16770, -1, 16770, 16710, 11731, -1, 16771, 16773, 16710, -1, 16773, 16774, 16710, -1, 11849, 11468, 16775, -1, 16776, 16775, 16777, -1, 16776, 11849, 16775, -1, 16778, 16777, 16779, -1, 16778, 16776, 16777, -1, 16780, 16778, 16779, -1, 16781, 16782, 16783, -1, 11495, 16784, 16781, -1, 11495, 16781, 16783, -1, 16785, 16784, 11495, -1, 11837, 16785, 11495, -1, 16786, 14199, 14196, -1, 16786, 14196, 16787, -1, 16788, 16787, 16789, -1, 16788, 16786, 16787, -1, 16790, 16789, 16791, -1, 16790, 16788, 16789, -1, 16792, 16791, 16793, -1, 16792, 16790, 16791, -1, 16794, 16793, 16795, -1, 16794, 16792, 16793, -1, 16796, 16797, 16798, -1, 16796, 16795, 16797, -1, 16796, 16794, 16795, -1, 16799, 16798, 16800, -1, 16799, 16796, 16798, -1, 16801, 16800, 16802, -1, 16801, 16799, 16800, -1, 16803, 16802, 16804, -1, 16803, 16801, 16802, -1, 16805, 16804, 16806, -1, 16805, 16803, 16804, -1, 16807, 16805, 16806, -1, 16808, 16806, 16809, -1, 16808, 16807, 16806, -1, 16810, 16809, 14188, -1, 16810, 16808, 16809, -1, 14187, 16810, 14188, -1, 16811, 16780, 16779, -1, 16812, 16811, 16779, -1, 16813, 16814, 16812, -1, 16813, 16812, 16779, -1, 16815, 16814, 16813, -1, 11494, 11493, 11474, -1, 11493, 11475, 11474, -1, 11493, 11479, 11475, -1, 11493, 11480, 11479, -1, 11493, 11484, 11480, -1, 11484, 11499, 11487, -1, 11487, 11499, 11488, -1, 11488, 11499, 11491, -1, 11491, 11499, 11498, -1, 11493, 11499, 11484, -1, 11499, 16816, 16817, -1, 11493, 16818, 11499, -1, 11499, 16818, 16816, -1, 16819, 16820, 11493, -1, 11493, 16820, 16818, -1, 11835, 11466, 16821, -1, 16822, 16821, 16823, -1, 16822, 11835, 16821, -1, 16824, 16823, 16825, -1, 16824, 16822, 16823, -1, 16826, 16825, 16827, -1, 16826, 16824, 16825, -1, 16828, 16827, 16829, -1, 16828, 16826, 16827, -1, 16830, 16829, 16831, -1, 16830, 16828, 16829, -1, 16832, 16831, 16833, -1, 16832, 16830, 16831, -1, 16834, 16833, 16835, -1, 16834, 16832, 16833, -1, 16836, 16835, 16837, -1, 16836, 16834, 16835, -1, 16838, 16837, 16839, -1, 16838, 16836, 16837, -1, 16840, 16839, 16841, -1, 16840, 16838, 16839, -1, 16842, 16840, 16841, -1, 16843, 16844, 16845, -1, 11459, 16846, 16843, -1, 11459, 16843, 16845, -1, 16847, 16846, 11459, -1, 11833, 16847, 11459, -1, 16848, 14005, 14002, -1, 16848, 14002, 16849, -1, 16850, 16849, 16851, -1, 16850, 16848, 16849, -1, 16852, 16851, 16853, -1, 16852, 16850, 16851, -1, 16854, 16853, 16855, -1, 16854, 16852, 16853, -1, 16856, 16855, 16857, -1, 16856, 16854, 16855, -1, 16858, 16859, 16860, -1, 16858, 16857, 16859, -1, 16858, 16856, 16857, -1, 16861, 16860, 16862, -1, 16861, 16858, 16860, -1, 16863, 16862, 16864, -1, 16863, 16861, 16862, -1, 16865, 16864, 16866, -1, 16865, 16863, 16864, -1, 16867, 16866, 16868, -1, 16867, 16865, 16866, -1, 16869, 16867, 16868, -1, 16870, 16868, 16871, -1, 16870, 16869, 16868, -1, 16872, 16871, 13994, -1, 16872, 16870, 16871, -1, 13993, 16872, 13994, -1, 16873, 16842, 16841, -1, 16874, 16873, 16841, -1, 16875, 16876, 16874, -1, 16875, 16874, 16841, -1, 16877, 16876, 16875, -1, 16878, 16879, 16880, -1, 16881, 16882, 16879, -1, 16879, 11460, 16880, -1, 16882, 16883, 16879, -1, 11460, 11463, 11461, -1, 16883, 16884, 16879, -1, 11463, 16885, 11465, -1, 11460, 16885, 11463, -1, 16886, 16887, 16884, -1, 16884, 16887, 16879, -1, 16885, 16888, 16889, -1, 16890, 16888, 16887, -1, 16879, 16888, 11460, -1, 11460, 16888, 16885, -1, 16887, 16888, 16879, -1, 16891, 16892, 16893, -1, 16891, 16894, 16895, -1, 16891, 16893, 16894, -1, 16896, 16895, 16897, -1, 16896, 16891, 16895, -1, 16898, 16897, 16899, -1, 16898, 16896, 16897, -1, 16900, 16899, 16901, -1, 16900, 16898, 16899, -1, 16902, 16901, 16903, -1, 16902, 16900, 16901, -1, 16904, 16903, 16905, -1, 16904, 16902, 16903, -1, 16906, 16905, 16907, -1, 16906, 16904, 16905, -1, 16908, 16907, 16909, -1, 16908, 16906, 16907, -1, 16910, 16909, 16911, -1, 16910, 16908, 16909, -1, 16912, 16911, 16913, -1, 16912, 16910, 16911, -1, 16914, 16913, 16915, -1, 16914, 16912, 16913, -1, 16916, 16914, 16915, -1, 16917, 16915, 16918, -1, 16917, 16916, 16915, -1, 16919, 16917, 16918, -1, 16920, 16921, 16922, -1, 16893, 16923, 16920, -1, 16893, 16920, 16922, -1, 16924, 16923, 16893, -1, 16892, 16924, 16893, -1, 16925, 11831, 11520, -1, 16925, 16926, 16927, -1, 16925, 11520, 16926, -1, 16928, 16927, 16929, -1, 16928, 16925, 16927, -1, 16930, 16929, 16931, -1, 16930, 16928, 16929, -1, 16932, 16931, 16933, -1, 16932, 16930, 16931, -1, 16934, 16932, 16933, -1, 16935, 16933, 16936, -1, 16935, 16934, 16933, -1, 16937, 16936, 14226, -1, 16937, 16935, 16936, -1, 14225, 16937, 14226, -1, 16938, 16919, 16918, -1, 16939, 16938, 16918, -1, 16940, 16941, 16939, -1, 16940, 16939, 16918, -1, 16942, 16941, 16940, -1, 16943, 16944, 16945, -1, 16945, 16944, 16946, -1, 16946, 16944, 16947, -1, 16947, 16944, 16948, -1, 16948, 16944, 16949, -1, 16943, 16950, 16944, -1, 16950, 16951, 16944, -1, 16951, 16952, 16944, -1, 16952, 16953, 16944, -1, 16953, 16954, 16944, -1, 16954, 16955, 16944, -1, 16955, 16956, 16944, -1, 16956, 16957, 16944, -1, 16956, 16958, 16957, -1, 16959, 16960, 16961, -1, 16962, 16960, 16959, -1, 16963, 16964, 16965, -1, 16965, 16964, 16966, -1, 16966, 16964, 16967, -1, 16968, 16964, 16969, -1, 16967, 16964, 16970, -1, 16970, 16964, 16971, -1, 16971, 16964, 16972, -1, 16972, 16964, 16973, -1, 16973, 16964, 16974, -1, 16974, 16964, 16975, -1, 16975, 16964, 16976, -1, 16976, 16964, 16968, -1, 16977, 16964, 16963, -1, 16961, 16978, 16979, -1, 16979, 16978, 16980, -1, 16981, 16982, 16977, -1, 16962, 16982, 16960, -1, 16977, 16982, 16964, -1, 16964, 16982, 16969, -1, 16969, 16982, 16962, -1, 16980, 16983, 16984, -1, 16960, 16985, 16961, -1, 16961, 16985, 16978, -1, 16978, 16986, 16980, -1, 16980, 16986, 16983, -1, 16987, 16988, 16981, -1, 16981, 16988, 16982, -1, 16985, 16988, 16987, -1, 16982, 16988, 16960, -1, 16960, 16988, 16985, -1, 16983, 16989, 16984, -1, 16984, 16989, 16990, -1, 16991, 16992, 16987, -1, 16987, 16992, 16985, -1, 16985, 16992, 16978, -1, 16978, 16992, 16986, -1, 16986, 16993, 16983, -1, 16983, 16993, 16989, -1, 16989, 16994, 16990, -1, 16995, 16996, 16991, -1, 16991, 16996, 16992, -1, 16992, 16996, 16986, -1, 16986, 16996, 16993, -1, 16995, 16997, 16996, -1, 16993, 16997, 16989, -1, 16989, 16997, 16994, -1, 16996, 16997, 16993, -1, 16998, 16999, 16995, -1, 16995, 16999, 16997, -1, 16994, 16999, 16990, -1, 16997, 16999, 16994, -1, 16999, 17000, 16990, -1, 16998, 17000, 16999, -1, 16990, 17000, 17001, -1, 17002, 17003, 16998, -1, 17000, 17003, 17001, -1, 16998, 17003, 17000, -1, 17001, 17003, 17002, -1, 17001, 17004, 11672, -1, 17005, 17004, 17001, -1, 11749, 17006, 11751, -1, 11751, 17006, 11752, -1, 11752, 17006, 17005, -1, 17005, 17006, 17004, -1, 17004, 17006, 11672, -1, 11672, 17006, 11749, -1, 17007, 17008, 17009, -1, 17008, 17010, 17009, -1, 17011, 17012, 17013, -1, 17012, 17014, 17013, -1, 17012, 17015, 17014, -1, 17015, 17016, 17014, -1, 17016, 17017, 17014, -1, 17016, 17018, 17017, -1, 17018, 17019, 17017, -1, 17019, 17020, 17017, -1, 17019, 17021, 17020, -1, 17021, 17022, 17020, -1, 17022, 17023, 17020, -1, 17022, 17024, 17023, -1, 17024, 17025, 17023, -1, 17026, 17025, 17024, -1, 17026, 17027, 17025, -1, 17027, 17028, 17025, -1, 17029, 17028, 17027, -1, 17029, 17030, 17028, -1, 17030, 17031, 17028, -1, 17030, 17032, 17031, -1, 17032, 17033, 17031, -1, 17032, 17034, 17033, -1, 17035, 16977, 16963, -1, 17002, 17005, 17001, -1, 17036, 17037, 11808, -1, 11805, 17037, 11636, -1, 11807, 17037, 11805, -1, 11808, 17037, 11807, -1, 17038, 17039, 17036, -1, 11636, 17039, 17040, -1, 17037, 17039, 11636, -1, 17036, 17039, 17037, -1, 17041, 17042, 17038, -1, 17039, 17042, 17040, -1, 17038, 17042, 17039, -1, 17041, 17043, 17042, -1, 17042, 17043, 17040, -1, 17041, 17044, 17043, -1, 17043, 17044, 17040, -1, 17045, 17044, 17041, -1, 17040, 17044, 17046, -1, 17044, 17047, 17046, -1, 17045, 17047, 17044, -1, 17045, 17048, 17047, -1, 17049, 17048, 17045, -1, 17047, 17050, 17046, -1, 17049, 17051, 17048, -1, 17048, 17051, 17047, -1, 17052, 17051, 17049, -1, 17047, 17051, 17050, -1, 17046, 17053, 17054, -1, 17050, 17053, 17046, -1, 17050, 17055, 17053, -1, 17052, 17055, 17051, -1, 17051, 17055, 17050, -1, 17053, 17056, 17054, -1, 17052, 17057, 17055, -1, 17058, 17057, 17052, -1, 17055, 17059, 17053, -1, 17053, 17059, 17056, -1, 17056, 17060, 17054, -1, 17057, 17061, 17055, -1, 17058, 17061, 17057, -1, 17055, 17061, 17059, -1, 17062, 17061, 17058, -1, 17056, 17063, 17060, -1, 17059, 17063, 17056, -1, 17060, 17064, 17054, -1, 17054, 17064, 17065, -1, 17059, 17066, 17063, -1, 17061, 17066, 17059, -1, 17060, 17067, 17064, -1, 17063, 17067, 17060, -1, 17062, 17068, 17061, -1, 17069, 17068, 17062, -1, 17061, 17068, 17066, -1, 17064, 17070, 17065, -1, 17066, 17071, 17063, -1, 17063, 17071, 17067, -1, 17067, 17072, 17064, -1, 17064, 17072, 17070, -1, 17069, 17073, 17068, -1, 17068, 17073, 17066, -1, 17066, 17073, 17071, -1, 17009, 17073, 17069, -1, 17070, 17074, 17065, -1, 17067, 17075, 17072, -1, 17071, 17075, 17067, -1, 17070, 17076, 17074, -1, 17072, 17076, 17070, -1, 17071, 17077, 17075, -1, 17073, 17077, 17071, -1, 17074, 17078, 17065, -1, 17065, 17078, 17079, -1, 17072, 17080, 17076, -1, 17075, 17080, 17072, -1, 17073, 17081, 17077, -1, 17009, 17081, 17073, -1, 17010, 17081, 17009, -1, 17082, 17081, 17083, -1, 17083, 17081, 17084, -1, 17084, 17081, 17085, -1, 17085, 17081, 17086, -1, 17086, 17081, 17087, -1, 17077, 17081, 17082, -1, 17087, 17081, 17088, -1, 17088, 17081, 17089, -1, 17089, 17081, 17090, -1, 17090, 17081, 17091, -1, 17091, 17081, 17010, -1, 17076, 17092, 17074, -1, 17074, 17092, 17078, -1, 17075, 17093, 17080, -1, 17077, 17093, 17075, -1, 17094, 17093, 17082, -1, 17082, 17093, 17077, -1, 17078, 17095, 17079, -1, 17080, 17096, 17076, -1, 17076, 17096, 17092, -1, 17092, 17097, 17078, -1, 17078, 17097, 17095, -1, 17093, 17098, 17080, -1, 17094, 17098, 17093, -1, 17099, 17098, 17100, -1, 17100, 17098, 17094, -1, 17080, 17098, 17096, -1, 17096, 17098, 17099, -1, 17095, 17101, 17079, -1, 17097, 17102, 17103, -1, 17092, 17102, 17097, -1, 17103, 17102, 17099, -1, 17096, 17102, 17092, -1, 17099, 17102, 17096, -1, 17097, 17104, 17095, -1, 17103, 17104, 17097, -1, 17095, 17104, 17101, -1, 17105, 17104, 17103, -1, 17101, 17106, 17079, -1, 17104, 17107, 17101, -1, 17105, 17107, 17104, -1, 17108, 17107, 17105, -1, 17101, 17107, 17106, -1, 17106, 17109, 17079, -1, 17079, 17109, 17110, -1, 17106, 17111, 17109, -1, 17107, 17111, 17106, -1, 17108, 17111, 17107, -1, 17112, 17111, 17108, -1, 17109, 17113, 17110, -1, 17112, 17113, 17111, -1, 17111, 17113, 17109, -1, 17113, 17114, 17110, -1, 17112, 17114, 17113, -1, 17011, 17114, 17112, -1, 17011, 17115, 17114, -1, 17110, 17115, 17013, -1, 17114, 17115, 17110, -1, 17013, 17115, 17011, -1, 17034, 17116, 17033, -1, 17117, 17118, 17034, -1, 17034, 17118, 17116, -1, 17116, 17118, 17033, -1, 17033, 17118, 17119, -1, 17117, 17120, 17118, -1, 17118, 17120, 17119, -1, 17121, 17122, 17117, -1, 17117, 17122, 17120, -1, 17120, 17122, 17119, -1, 17123, 17124, 17121, -1, 17121, 17124, 17122, -1, 17122, 17124, 17119, -1, 17119, 17124, 17125, -1, 17123, 17126, 17124, -1, 17124, 17126, 17125, -1, 17127, 17128, 17123, -1, 17123, 17128, 17126, -1, 17126, 17129, 17125, -1, 17130, 17131, 17127, -1, 17127, 17131, 17128, -1, 17128, 17131, 17126, -1, 17126, 17131, 17129, -1, 17129, 17132, 17125, -1, 17131, 17132, 17129, -1, 17132, 17133, 17125, -1, 17125, 17133, 17134, -1, 17135, 17136, 17130, -1, 17130, 17136, 17131, -1, 17131, 17136, 17132, -1, 17132, 17137, 17133, -1, 17133, 17138, 17134, -1, 17139, 17140, 17135, -1, 17135, 17140, 17136, -1, 17136, 17140, 17132, -1, 17132, 17140, 17137, -1, 17137, 17141, 17133, -1, 17133, 17141, 17138, -1, 17138, 17142, 17134, -1, 17139, 17143, 17140, -1, 17137, 17143, 17141, -1, 17140, 17143, 17137, -1, 17141, 16959, 17138, -1, 17138, 16959, 17142, -1, 16968, 17144, 17139, -1, 17139, 17144, 17143, -1, 17142, 16979, 17134, -1, 17134, 16979, 16984, -1, 17143, 16962, 17141, -1, 17141, 16962, 16959, -1, 17142, 16961, 16979, -1, 16959, 16961, 17142, -1, 17144, 16969, 17143, -1, 17143, 16969, 16962, -1, 16968, 16969, 17144, -1, 16979, 16980, 16984, -1, 16755, 17145, 16723, -1, 16723, 17145, 16727, -1, 16727, 17146, 16726, -1, 17145, 17146, 16727, -1, 16726, 11716, 11718, -1, 17146, 11716, 16726, -1, 16774, 17147, 16710, -1, 16710, 17147, 16709, -1, 16709, 17148, 16708, -1, 17147, 17148, 16709, -1, 17148, 17149, 16708, -1, 16708, 17150, 16707, -1, 17149, 17150, 16708, -1, 16707, 17151, 16702, -1, 17150, 17151, 16707, -1, 17151, 17152, 16702, -1, 16702, 17153, 16745, -1, 17152, 17153, 16702, -1, 16745, 17154, 16741, -1, 17153, 17154, 16745, -1, 16741, 17155, 16740, -1, 17154, 17155, 16741, -1, 16740, 17156, 16739, -1, 17155, 17156, 16740, -1, 16739, 17157, 16738, -1, 17156, 17157, 16739, -1, 17157, 16756, 16738, -1, 16765, 17158, 16720, -1, 16720, 17158, 16718, -1, 16718, 17159, 16719, -1, 17158, 17159, 16718, -1, 17159, 17160, 16719, -1, 16719, 17161, 16721, -1, 17160, 17161, 16719, -1, 16721, 17162, 16722, -1, 17161, 17162, 16721, -1, 17162, 17163, 16722, -1, 16722, 17164, 16728, -1, 17163, 17164, 16722, -1, 16728, 17165, 16729, -1, 17164, 17165, 16728, -1, 16729, 17166, 16730, -1, 17165, 17166, 16729, -1, 16730, 17167, 16731, -1, 17166, 17167, 16730, -1, 16731, 17168, 16725, -1, 17167, 17168, 16731, -1, 17168, 16746, 16725, -1, 13986, 13985, 17169, -1, 17170, 17169, 17171, -1, 17170, 13986, 17169, -1, 17172, 17171, 17173, -1, 17172, 17170, 17171, -1, 17174, 17173, 17175, -1, 17174, 17172, 17173, -1, 17176, 17174, 17175, -1, 14218, 14217, 17177, -1, 17178, 17177, 17179, -1, 17178, 14218, 17177, -1, 17180, 17179, 17181, -1, 17180, 17178, 17179, -1, 17182, 17181, 17183, -1, 17182, 17180, 17181, -1, 17184, 17182, 17183, -1, 11715, 11714, 17185, -1, 17186, 17185, 17187, -1, 17186, 11715, 17185, -1, 17188, 17187, 17189, -1, 17188, 17186, 17187, -1, 17190, 17188, 17189, -1, 16782, 14101, 14103, -1, 14094, 16781, 14090, -1, 16781, 14088, 14090, -1, 14088, 16784, 14085, -1, 16781, 16784, 14088, -1, 16784, 14079, 14085, -1, 16784, 14074, 14079, -1, 16784, 16785, 14074, -1, 16785, 14047, 14074, -1, 16782, 16781, 14094, -1, 16782, 14094, 14101, -1, 11837, 14047, 16785, -1, 11837, 14044, 14047, -1, 11837, 11836, 14044, -1, 11836, 14036, 14044, -1, 11836, 11838, 14036, -1, 11838, 14028, 14036, -1, 11838, 11839, 14028, -1, 11840, 14027, 11839, -1, 11839, 14027, 14028, -1, 11841, 14026, 11840, -1, 11840, 14026, 14027, -1, 11842, 14069, 11841, -1, 11841, 14069, 14026, -1, 11842, 11843, 14069, -1, 11843, 14067, 14069, -1, 11843, 11844, 14067, -1, 11844, 14064, 14067, -1, 11844, 11845, 14064, -1, 11846, 14058, 11845, -1, 11845, 14058, 14064, -1, 11847, 14057, 11846, -1, 11846, 14057, 14058, -1, 11848, 14054, 11847, -1, 11847, 14054, 14057, -1, 11848, 11849, 14054, -1, 11849, 14053, 14054, -1, 11849, 16776, 14053, -1, 16778, 14062, 16776, -1, 16776, 14062, 14053, -1, 16811, 14061, 16780, -1, 16780, 14061, 16778, -1, 16778, 14061, 14062, -1, 14199, 13547, 14198, -1, 16786, 13551, 14199, -1, 14199, 13551, 13547, -1, 16786, 13588, 13551, -1, 16786, 16788, 13588, -1, 16788, 13535, 13588, -1, 16788, 16790, 13535, -1, 16790, 13533, 13535, -1, 16790, 16792, 13533, -1, 16792, 13550, 13533, -1, 16792, 16794, 13550, -1, 16794, 13543, 13550, -1, 16794, 16796, 13543, -1, 16796, 13542, 13543, -1, 16796, 16799, 13542, -1, 16799, 13541, 13542, -1, 16799, 16801, 13541, -1, 16801, 13540, 13541, -1, 16801, 16803, 13540, -1, 16803, 13555, 13540, -1, 16803, 14158, 13555, -1, 16803, 16805, 14158, -1, 16805, 14157, 14158, -1, 16805, 16807, 14157, -1, 16807, 14175, 14157, -1, 16807, 16808, 14175, -1, 16808, 14168, 14175, -1, 16808, 16810, 14168, -1, 14186, 14161, 14187, -1, 14187, 14161, 16810, -1, 16810, 14161, 14168, -1, 16811, 14066, 14061, -1, 14040, 16812, 14072, -1, 16812, 14077, 14072, -1, 14077, 16814, 14081, -1, 16812, 16814, 14077, -1, 16814, 14082, 14081, -1, 16814, 14097, 14082, -1, 16814, 16815, 14097, -1, 16815, 14099, 14097, -1, 16811, 16812, 14040, -1, 16811, 14040, 14066, -1, 16921, 13800, 13802, -1, 13792, 16920, 13787, -1, 16920, 13784, 13787, -1, 13784, 16923, 13781, -1, 16920, 16923, 13784, -1, 16923, 13774, 13781, -1, 16923, 13769, 13774, -1, 16923, 16924, 13769, -1, 16924, 13741, 13769, -1, 16921, 16920, 13792, -1, 16921, 13792, 13800, -1, 16892, 13741, 16924, -1, 16892, 13736, 13741, -1, 16892, 16891, 13736, -1, 16891, 13727, 13736, -1, 16891, 16896, 13727, -1, 16896, 13718, 13727, -1, 16896, 16898, 13718, -1, 16898, 13717, 13718, -1, 16898, 16900, 13717, -1, 16900, 13715, 13717, -1, 16900, 16902, 13715, -1, 16902, 13764, 13715, -1, 16902, 16904, 13764, -1, 16904, 13762, 13764, -1, 16904, 16906, 13762, -1, 16906, 13759, 13762, -1, 16906, 16908, 13759, -1, 16908, 13752, 13759, -1, 16908, 16910, 13752, -1, 16910, 13751, 13752, -1, 16910, 16912, 13751, -1, 16912, 13748, 13751, -1, 16912, 16914, 13748, -1, 16914, 13747, 13748, -1, 16914, 16916, 13747, -1, 16916, 13756, 13747, -1, 16916, 16917, 13756, -1, 16938, 13755, 16919, -1, 16919, 13755, 16917, -1, 16917, 13755, 13756, -1, 11825, 14262, 14235, -1, 11825, 16580, 14262, -1, 11825, 11824, 16580, -1, 11824, 16578, 16580, -1, 11824, 11826, 16578, -1, 11826, 16588, 16578, -1, 11826, 11827, 16588, -1, 11827, 16586, 16588, -1, 11827, 11828, 16586, -1, 11828, 16591, 16586, -1, 11828, 11829, 16591, -1, 11829, 16595, 16591, -1, 11829, 11830, 16595, -1, 11830, 16593, 16595, -1, 11830, 11831, 16593, -1, 11831, 16618, 16593, -1, 11831, 16925, 16618, -1, 16925, 16585, 16618, -1, 16925, 16928, 16585, -1, 16928, 16584, 16585, -1, 16928, 16930, 16584, -1, 16932, 16583, 16930, -1, 16930, 16583, 16584, -1, 16934, 16581, 16932, -1, 16932, 16581, 16583, -1, 16934, 16935, 16581, -1, 16935, 16629, 16581, -1, 16935, 16937, 16629, -1, 14224, 14246, 14225, -1, 14225, 14246, 16937, -1, 16937, 14246, 16629, -1, 16938, 13761, 13755, -1, 13731, 16939, 13767, -1, 16939, 13772, 13767, -1, 13772, 16941, 13776, -1, 16939, 16941, 13772, -1, 16941, 13777, 13776, -1, 16941, 13795, 13777, -1, 16941, 16942, 13795, -1, 16942, 13797, 13795, -1, 16938, 16939, 13731, -1, 16938, 13731, 13761, -1, 16844, 13684, 13689, -1, 13675, 16843, 13670, -1, 16843, 13658, 13670, -1, 13658, 16846, 13656, -1, 16843, 16846, 13658, -1, 16846, 13705, 13656, -1, 16846, 13702, 13705, -1, 16846, 16847, 13702, -1, 16847, 13700, 13702, -1, 16844, 16843, 13675, -1, 16844, 13675, 13684, -1, 11833, 13700, 16847, -1, 11832, 13696, 11833, -1, 11833, 13696, 13700, -1, 11832, 13694, 13696, -1, 11832, 11834, 13694, -1, 11835, 13693, 11834, -1, 11834, 13693, 13694, -1, 16822, 13665, 11835, -1, 11835, 13665, 13693, -1, 16822, 13663, 13665, -1, 16822, 16824, 13663, -1, 16824, 13881, 13663, -1, 16824, 16826, 13881, -1, 16826, 13880, 13881, -1, 16826, 16828, 13880, -1, 16828, 13879, 13880, -1, 16828, 16830, 13879, -1, 16830, 13877, 13879, -1, 16830, 16832, 13877, -1, 16832, 13873, 13877, -1, 16832, 16834, 13873, -1, 16834, 13866, 13873, -1, 16834, 16836, 13866, -1, 16836, 13864, 13866, -1, 16836, 16838, 13864, -1, 16838, 13875, 13864, -1, 16838, 16840, 13875, -1, 16840, 13871, 13875, -1, 16840, 16842, 13871, -1, 16873, 13869, 16842, -1, 16842, 13869, 13871, -1, 14005, 13913, 14004, -1, 14005, 13916, 13913, -1, 14005, 16848, 13916, -1, 16848, 13915, 13916, -1, 16848, 16850, 13915, -1, 16850, 13924, 13915, -1, 16850, 16852, 13924, -1, 16852, 13922, 13924, -1, 16852, 16854, 13922, -1, 16854, 13927, 13922, -1, 16854, 16856, 13927, -1, 16856, 13932, 13927, -1, 16856, 16858, 13932, -1, 16858, 13930, 13932, -1, 16858, 16861, 13930, -1, 16861, 13958, 13930, -1, 16861, 16863, 13958, -1, 16863, 13921, 13958, -1, 16863, 16865, 13921, -1, 16865, 13920, 13921, -1, 16867, 13919, 16865, -1, 16865, 13919, 13920, -1, 16867, 16869, 13919, -1, 16869, 13918, 13919, -1, 16869, 16870, 13918, -1, 16870, 13975, 13918, -1, 16870, 16872, 13975, -1, 13992, 13974, 13993, -1, 13993, 13974, 16872, -1, 16872, 13974, 13975, -1, 16873, 13626, 13869, -1, 16873, 13624, 13626, -1, 16874, 13632, 13630, -1, 16874, 13640, 13632, -1, 13640, 16876, 13644, -1, 16874, 16876, 13640, -1, 16876, 13650, 13644, -1, 16876, 13648, 13650, -1, 16876, 16877, 13648, -1, 16877, 13655, 13648, -1, 16873, 16874, 13630, -1, 16873, 13630, 13624, -1, 16689, 14092, 14096, -1, 16689, 14083, 14092, -1, 14083, 16688, 14076, -1, 16688, 14041, 14076, -1, 16688, 14039, 14041, -1, 16688, 14060, 14039, -1, 14060, 16691, 14052, -1, 16691, 14035, 14052, -1, 16691, 14031, 14035, -1, 16691, 14029, 14031, -1, 14029, 16692, 14114, -1, 16691, 16692, 14029, -1, 16692, 14111, 14114, -1, 16692, 14110, 14111, -1, 16692, 16693, 14110, -1, 16693, 14108, 14110, -1, 16693, 14046, 14108, -1, 16693, 14127, 14046, -1, 14127, 14045, 14046, -1, 16689, 16688, 14083, -1, 16688, 16691, 14060, -1, 13579, 11709, 14180, -1, 13580, 11710, 13579, -1, 13579, 11710, 11709, -1, 13580, 11712, 11710, -1, 13580, 13582, 11712, -1, 13582, 11714, 11712, -1, 13584, 17185, 13582, -1, 13582, 17185, 11714, -1, 13584, 17187, 17185, -1, 13584, 13585, 17187, -1, 13585, 17189, 17187, -1, 13946, 13985, 13984, -1, 13947, 17169, 13946, -1, 13946, 17169, 13985, -1, 13947, 17171, 17169, -1, 13947, 13952, 17171, -1, 13959, 17173, 13952, -1, 13952, 17173, 17171, -1, 13960, 17175, 13959, -1, 13959, 17175, 17173, -1, 16695, 13790, 13794, -1, 16695, 13778, 13790, -1, 13778, 16694, 13771, -1, 16694, 13732, 13771, -1, 16694, 13730, 13732, -1, 16694, 13754, 13730, -1, 13754, 16697, 13746, -1, 16697, 13726, 13746, -1, 16697, 13721, 13726, -1, 16697, 13719, 13721, -1, 13719, 16698, 13815, -1, 16697, 16698, 13719, -1, 16698, 13812, 13815, -1, 16698, 13811, 13812, -1, 16698, 16699, 13811, -1, 16699, 13808, 13811, -1, 16699, 13739, 13808, -1, 16699, 13828, 13739, -1, 13828, 13737, 13739, -1, 16695, 16694, 13778, -1, 16694, 16697, 13754, -1, 16683, 13651, 13653, -1, 16683, 13643, 13651, -1, 13636, 16682, 13634, -1, 13639, 16682, 13636, -1, 16682, 13629, 13634, -1, 16682, 13623, 13629, -1, 16682, 13622, 13623, -1, 13862, 16685, 13857, -1, 13622, 16685, 13862, -1, 16685, 13853, 13857, -1, 16685, 13849, 13853, -1, 13849, 16686, 13842, -1, 16685, 16686, 13849, -1, 16686, 13840, 13842, -1, 16686, 16687, 13840, -1, 16687, 13832, 13840, -1, 16687, 13892, 13832, -1, 13892, 13831, 13832, -1, 16683, 16682, 13639, -1, 16683, 13639, 13643, -1, 16682, 16685, 13622, -1, 14264, 14217, 14216, -1, 16611, 17177, 14264, -1, 14264, 17177, 14217, -1, 16611, 17179, 17177, -1, 16611, 16614, 17179, -1, 16620, 17181, 16614, -1, 16614, 17181, 17179, -1, 16621, 17183, 16620, -1, 16620, 17183, 17181, -1, 11789, 11768, 16747, -1, 11768, 11757, 16747, -1, 11747, 16748, 11757, -1, 11757, 16748, 16747, -1, 11747, 11740, 16748, -1, 11740, 11734, 16748, -1, 11821, 16749, 11734, -1, 11816, 16749, 11821, -1, 11734, 16749, 16748, -1, 11816, 11812, 16749, -1, 11812, 11744, 16749, -1, 11742, 16750, 11744, -1, 11771, 16750, 11742, -1, 11744, 16750, 16749, -1, 11771, 11767, 16750, -1, 11767, 11766, 16750, -1, 11766, 11764, 16750, -1, 11761, 16751, 11764, -1, 11760, 16751, 11761, -1, 11756, 16751, 11760, -1, 11764, 16751, 16750, -1, 11756, 11755, 16751, -1, 11755, 11750, 16751, -1, 17005, 16753, 11752, -1, 11752, 16753, 11750, -1, 11750, 16753, 16751, -1, 17005, 17002, 16753, -1, 17002, 16998, 16753, -1, 16998, 16752, 16753, -1, 16995, 16752, 16998, -1, 16991, 16752, 16995, -1, 16991, 16987, 16752, -1, 16987, 16981, 16752, -1, 16981, 16754, 16752, -1, 16977, 16754, 16981, -1, 16977, 16755, 16754, -1, 17035, 17145, 16977, -1, 16977, 17145, 16755, -1, 16963, 17146, 17035, -1, 17035, 17146, 17145, -1, 16965, 11716, 16963, -1, 16963, 11716, 17146, -1, 16966, 11717, 16965, -1, 16965, 11717, 11716, -1, 16967, 11720, 16966, -1, 16966, 11720, 11717, -1, 16970, 11722, 16967, -1, 16967, 11722, 11720, -1, 16971, 11724, 16970, -1, 16972, 11724, 16971, -1, 16970, 11724, 11722, -1, 16973, 11726, 16972, -1, 16972, 11726, 11724, -1, 16974, 11728, 16973, -1, 16975, 11728, 16974, -1, 16973, 11728, 11726, -1, 16976, 11730, 16975, -1, 16975, 11730, 11728, -1, 16976, 16766, 11730, -1, 11776, 16765, 16764, -1, 11777, 17158, 11776, -1, 11776, 17158, 16765, -1, 11779, 17159, 11777, -1, 11777, 17159, 17158, -1, 11779, 17160, 17159, -1, 11780, 17161, 11779, -1, 11779, 17161, 17160, -1, 11781, 17162, 11780, -1, 11780, 17162, 17161, -1, 11782, 17163, 11781, -1, 11781, 17163, 17162, -1, 11784, 17164, 11782, -1, 11782, 17164, 17163, -1, 11785, 17165, 11784, -1, 11784, 17165, 17164, -1, 11786, 17166, 11785, -1, 11785, 17166, 17165, -1, 11787, 17167, 11786, -1, 11786, 17167, 17166, -1, 11788, 17168, 11787, -1, 11820, 17168, 11788, -1, 11787, 17168, 17167, -1, 11789, 16746, 11820, -1, 11820, 16746, 17168, -1, 11789, 16747, 16746, -1, 17094, 16773, 16771, -1, 17082, 16773, 17094, -1, 17083, 16773, 17082, -1, 16976, 16968, 16766, -1, 16968, 17139, 16766, -1, 17135, 16767, 17139, -1, 17139, 16767, 16766, -1, 17135, 17130, 16767, -1, 17130, 17127, 16767, -1, 17127, 17123, 16767, -1, 17121, 16768, 17123, -1, 17123, 16768, 16767, -1, 17121, 17117, 16768, -1, 17117, 17034, 16768, -1, 17032, 16769, 17034, -1, 17030, 16769, 17032, -1, 17034, 16769, 16768, -1, 17030, 17029, 16769, -1, 17029, 17027, 16769, -1, 17027, 17026, 16769, -1, 17026, 17024, 16769, -1, 17022, 16770, 17024, -1, 17021, 16770, 17022, -1, 17019, 16770, 17021, -1, 17018, 16770, 17019, -1, 17024, 16770, 16769, -1, 17018, 17016, 16770, -1, 17016, 17015, 16770, -1, 17012, 16772, 17015, -1, 17011, 16772, 17012, -1, 17015, 16772, 16770, -1, 17011, 17112, 16772, -1, 17112, 17108, 16772, -1, 17108, 16771, 16772, -1, 17105, 16771, 17108, -1, 17103, 16771, 17105, -1, 17103, 17099, 16771, -1, 17099, 17100, 16771, -1, 17100, 17094, 16771, -1, 17009, 17069, 16757, -1, 17062, 16758, 17069, -1, 17069, 16758, 16757, -1, 17062, 17058, 16758, -1, 17058, 17052, 16758, -1, 17052, 17049, 16758, -1, 17045, 16759, 17049, -1, 17041, 16759, 17045, -1, 17049, 16759, 16758, -1, 17041, 17038, 16759, -1, 17038, 17036, 16759, -1, 17036, 11808, 16759, -1, 11801, 16760, 11808, -1, 11808, 16760, 16759, -1, 11801, 11798, 16760, -1, 11798, 11794, 16760, -1, 11794, 11793, 16760, -1, 11790, 16761, 11793, -1, 11783, 16761, 11790, -1, 11793, 16761, 16760, -1, 11783, 11778, 16761, -1, 11778, 11774, 16761, -1, 11737, 16763, 11774, -1, 11739, 16763, 11737, -1, 11774, 16763, 16761, -1, 11739, 11817, 16763, -1, 11817, 11814, 16763, -1, 11804, 16762, 11814, -1, 11814, 16762, 16763, -1, 11804, 11802, 16762, -1, 11802, 11797, 16762, -1, 11797, 16764, 16762, -1, 11776, 16764, 11797, -1, 17083, 16774, 16773, -1, 17084, 17147, 17083, -1, 17083, 17147, 16774, -1, 17085, 17148, 17084, -1, 17084, 17148, 17147, -1, 17085, 17149, 17148, -1, 17086, 17150, 17085, -1, 17085, 17150, 17149, -1, 17087, 17151, 17086, -1, 17086, 17151, 17150, -1, 17088, 17152, 17087, -1, 17087, 17152, 17151, -1, 17089, 17153, 17088, -1, 17088, 17153, 17152, -1, 17090, 17154, 17089, -1, 17089, 17154, 17153, -1, 17091, 17155, 17090, -1, 17090, 17155, 17154, -1, 17010, 17156, 17091, -1, 17091, 17156, 17155, -1, 17008, 17157, 17010, -1, 17007, 17157, 17008, -1, 17010, 17157, 17156, -1, 17009, 16756, 17007, -1, 17007, 16756, 17157, -1, 17009, 16757, 16756, -1, 17191, 17192, 17193, -1, 17194, 17195, 17025, -1, 17193, 17192, 17196, -1, 17040, 17197, 11636, -1, 11636, 17197, 11634, -1, 17198, 17199, 17194, -1, 17194, 17199, 17195, -1, 16560, 17199, 17198, -1, 17196, 17197, 17040, -1, 17195, 17200, 17023, -1, 16479, 17201, 16477, -1, 17197, 17201, 11634, -1, 11634, 17201, 11630, -1, 11630, 17201, 16479, -1, 16477, 17201, 17192, -1, 17195, 17202, 17200, -1, 17192, 17201, 17196, -1, 16561, 17202, 16560, -1, 17196, 17201, 17197, -1, 17199, 17202, 17195, -1, 16560, 17202, 17199, -1, 17023, 17203, 17020, -1, 17200, 17203, 17023, -1, 11680, 16513, 11679, -1, 17202, 17204, 17200, -1, 16561, 17204, 17202, -1, 17200, 17204, 17203, -1, 17203, 17205, 17020, -1, 16469, 17206, 16561, -1, 17203, 17206, 17205, -1, 16479, 11628, 11630, -1, 17204, 17206, 17203, -1, 16561, 17206, 17204, -1, 11674, 17207, 11672, -1, 17205, 17208, 17020, -1, 17020, 17208, 17017, -1, 11672, 17207, 17001, -1, 17205, 17209, 17208, -1, 11674, 17210, 17207, -1, 11679, 17210, 11674, -1, 16469, 17209, 17206, -1, 16513, 17210, 11679, -1, 17206, 17209, 17205, -1, 17208, 17211, 17017, -1, 17207, 17212, 17001, -1, 17001, 17212, 16990, -1, 16468, 17213, 16469, -1, 16515, 17214, 16513, -1, 17209, 17213, 17208, -1, 16469, 17213, 17209, -1, 16513, 17214, 17210, -1, 17210, 17214, 17207, -1, 17208, 17213, 17211, -1, 17207, 17214, 17212, -1, 17211, 17215, 17017, -1, 17017, 17215, 17014, -1, 16990, 17216, 16984, -1, 16468, 17217, 17213, -1, 17212, 17216, 16990, -1, 17213, 17217, 17211, -1, 16518, 17218, 16515, -1, 17211, 17217, 17215, -1, 17212, 17218, 17216, -1, 17214, 17218, 17212, -1, 16515, 17218, 17214, -1, 17215, 17219, 17014, -1, 17216, 17220, 16984, -1, 16984, 17220, 17134, -1, 16531, 17221, 16468, -1, 16468, 17221, 17217, -1, 17217, 17221, 17215, -1, 16518, 17222, 17218, -1, 17215, 17221, 17219, -1, 16517, 17222, 16518, -1, 17216, 17222, 17220, -1, 17219, 17223, 17014, -1, 17218, 17222, 17216, -1, 17014, 17223, 17013, -1, 17134, 17224, 17125, -1, 16531, 17225, 17221, -1, 17220, 17224, 17134, -1, 17221, 17225, 17219, -1, 17219, 17225, 17223, -1, 16520, 17226, 16517, -1, 17222, 17226, 17220, -1, 16517, 17226, 17222, -1, 17223, 17227, 17013, -1, 17220, 17226, 17224, -1, 16472, 17228, 16531, -1, 17125, 17229, 17119, -1, 16531, 17228, 17225, -1, 17224, 17229, 17125, -1, 17225, 17228, 17223, -1, 17223, 17228, 17227, -1, 16522, 17230, 16520, -1, 17226, 17230, 17224, -1, 17227, 17231, 17013, -1, 16520, 17230, 17226, -1, 17013, 17231, 17110, -1, 17224, 17230, 17229, -1, 17119, 17232, 17033, -1, 16472, 17233, 17228, -1, 17228, 17233, 17227, -1, 17229, 17232, 17119, -1, 17227, 17233, 17231, -1, 16522, 17234, 17230, -1, 16553, 17234, 16522, -1, 17231, 17235, 17110, -1, 17230, 17234, 17229, -1, 17229, 17234, 17232, -1, 16471, 17236, 16472, -1, 16472, 17236, 17233, -1, 17232, 17237, 17033, -1, 17233, 17236, 17231, -1, 17033, 17237, 17031, -1, 17231, 17236, 17235, -1, 17110, 17238, 17079, -1, 17235, 17238, 17110, -1, 17237, 17239, 17031, -1, 16471, 17240, 17236, -1, 16525, 17241, 16553, -1, 17236, 17240, 17235, -1, 17234, 17241, 17232, -1, 17235, 17240, 17238, -1, 17232, 17241, 17237, -1, 16553, 17241, 17234, -1, 16524, 17242, 16525, -1, 17238, 17243, 17079, -1, 17237, 17242, 17239, -1, 16525, 17242, 17241, -1, 17241, 17242, 17237, -1, 17079, 17244, 17065, -1, 17243, 17244, 17079, -1, 17239, 17245, 17031, -1, 16536, 17246, 16471, -1, 17031, 17245, 17028, -1, 16471, 17246, 17240, -1, 17240, 17246, 17238, -1, 17238, 17246, 17243, -1, 17245, 17247, 17028, -1, 16536, 17248, 17246, -1, 17242, 17249, 17239, -1, 17243, 17248, 17244, -1, 16524, 17249, 17242, -1, 17246, 17248, 17243, -1, 17239, 17249, 17245, -1, 17065, 17250, 17054, -1, 16529, 17251, 16524, -1, 17244, 17250, 17065, -1, 17245, 17251, 17247, -1, 16524, 17251, 17249, -1, 16475, 17252, 16536, -1, 17249, 17251, 17245, -1, 16536, 17252, 17248, -1, 17248, 17252, 17244, -1, 17244, 17252, 17250, -1, 17028, 17253, 17025, -1, 17247, 17253, 17028, -1, 17054, 17193, 17046, -1, 17250, 17193, 17054, -1, 16474, 17191, 16475, -1, 17253, 17194, 17025, -1, 16475, 17191, 17252, -1, 17252, 17191, 17250, -1, 16529, 17254, 17251, -1, 17250, 17191, 17193, -1, 17251, 17254, 17247, -1, 17247, 17254, 17253, -1, 17046, 17196, 17040, -1, 16560, 17198, 16529, -1, 16529, 17198, 17254, -1, 17193, 17196, 17046, -1, 17253, 17198, 17194, -1, 17254, 17198, 17253, -1, 16477, 17192, 16474, -1, 16474, 17192, 17191, -1, 17025, 17195, 17023, -1, 16427, 11608, 11607, -1, 16429, 16427, 11607, -1, 16431, 16429, 11607, -1, 16433, 16431, 11607, -1, 16435, 16433, 11607, -1, 16437, 16435, 11607, -1, 16441, 16437, 11607, -1, 16443, 16441, 11607, -1, 16446, 16443, 11607, -1, 11546, 16449, 16446, -1, 11546, 16451, 16449, -1, 11546, 16453, 16451, -1, 11546, 16455, 16453, -1, 11546, 16458, 16455, -1, 11546, 16460, 16458, -1, 11546, 16462, 16460, -1, 11546, 16464, 16462, -1, 11546, 16446, 11607, -1, 11548, 16464, 11546, -1, 16395, 16397, 17255, -1, 16396, 16395, 17255, -1, 16399, 16396, 17255, -1, 16401, 16399, 17255, -1, 16403, 16401, 17255, -1, 16490, 16403, 17255, -1, 16489, 16490, 17255, -1, 16407, 16489, 17255, -1, 16408, 16407, 17255, -1, 17256, 16423, 16421, -1, 17256, 16421, 16419, -1, 17256, 16419, 16417, -1, 17256, 16417, 16414, -1, 17256, 16414, 16413, -1, 17256, 16413, 16494, -1, 17256, 16494, 16499, -1, 17256, 16499, 16408, -1, 17256, 16408, 17255, -1, 16425, 16423, 17256, -1, 16562, 11530, 11529, -1, 16563, 16562, 11529, -1, 16564, 16563, 11529, -1, 16365, 16564, 11529, -1, 16366, 16365, 11529, -1, 16369, 16366, 11529, -1, 16371, 16369, 11529, -1, 16373, 16371, 11529, -1, 16375, 16373, 11529, -1, 11561, 16378, 16375, -1, 11561, 16380, 16378, -1, 11561, 16382, 16380, -1, 11561, 16384, 16382, -1, 11561, 16386, 16384, -1, 11561, 16388, 16386, -1, 11561, 16390, 16388, -1, 11561, 16392, 16390, -1, 11561, 16375, 11529, -1, 11562, 16392, 11561, -1, 17257, 11555, 11602, -1, 11604, 11553, 11606, -1, 11555, 11553, 11604, -1, 11573, 17258, 11575, -1, 11553, 11551, 11606, -1, 11561, 11529, 11527, -1, 11561, 11527, 11565, -1, 11546, 11607, 11551, -1, 11551, 11607, 11606, -1, 17258, 17259, 11575, -1, 11575, 17259, 11577, -1, 11571, 17260, 11573, -1, 11573, 17260, 17258, -1, 11577, 17261, 11579, -1, 17259, 17261, 11577, -1, 11569, 17262, 11571, -1, 11571, 17262, 17260, -1, 11579, 17263, 11581, -1, 11581, 17263, 11590, -1, 17261, 17263, 11579, -1, 11567, 11524, 11569, -1, 11569, 11524, 17262, -1, 17264, 17265, 17266, -1, 11590, 17267, 11592, -1, 17263, 17267, 11590, -1, 11565, 11525, 11567, -1, 11567, 11525, 11524, -1, 17265, 17268, 17266, -1, 17269, 17270, 17264, -1, 17264, 17270, 17265, -1, 17271, 17272, 17273, -1, 17266, 17272, 17271, -1, 17268, 17272, 17266, -1, 17269, 17274, 17270, -1, 17275, 17274, 17269, -1, 11565, 11527, 11525, -1, 17267, 17276, 11592, -1, 17272, 17277, 17273, -1, 17275, 11588, 17274, -1, 11592, 17276, 11594, -1, 11585, 11588, 17275, -1, 17273, 17256, 17255, -1, 17277, 17256, 17273, -1, 11594, 17278, 11596, -1, 17276, 17278, 11594, -1, 11583, 11586, 11585, -1, 11596, 17279, 11598, -1, 11585, 11586, 11588, -1, 17278, 17279, 11596, -1, 17279, 17280, 11598, -1, 11581, 11590, 11583, -1, 11583, 11590, 11586, -1, 11598, 17280, 11600, -1, 11600, 17257, 11602, -1, 17280, 17257, 11600, -1, 11602, 11555, 11604, -1, 14314, 11614, 11615, -1, 14314, 11615, 16527, -1, 14314, 16527, 16507, -1, 14313, 16507, 16506, -1, 14313, 14314, 16507, -1, 14309, 16506, 16496, -1, 14309, 14313, 16506, -1, 14310, 16496, 16495, -1, 14310, 14309, 16496, -1, 14312, 16495, 16505, -1, 14312, 14310, 16495, -1, 17256, 16505, 16425, -1, 14316, 14312, 16505, -1, 14316, 16505, 17256, -1, 14318, 17256, 17277, -1, 14318, 14316, 17256, -1, 14323, 17277, 17272, -1, 14323, 14318, 17277, -1, 14325, 17272, 17268, -1, 14325, 14323, 17272, -1, 14305, 17268, 17265, -1, 14305, 14325, 17268, -1, 14304, 17265, 17270, -1, 14304, 14305, 17265, -1, 14308, 17270, 17274, -1, 14308, 14304, 17270, -1, 11587, 17274, 11588, -1, 11587, 14308, 17274, -1, 11584, 11585, 17275, -1, 14341, 17275, 17269, -1, 14341, 11584, 17275, -1, 14337, 17269, 17264, -1, 14337, 14341, 17269, -1, 14333, 17264, 17266, -1, 14333, 14337, 17264, -1, 14334, 17266, 17271, -1, 14334, 14333, 17266, -1, 14336, 17271, 17273, -1, 14336, 14334, 17271, -1, 16484, 17255, 16397, -1, 14338, 17273, 17255, -1, 14338, 14336, 17273, -1, 14342, 17255, 16484, -1, 14342, 14338, 17255, -1, 14346, 16484, 16447, -1, 14346, 14342, 16484, -1, 14348, 16447, 16439, -1, 14348, 14346, 16447, -1, 14329, 16439, 16438, -1, 14329, 14348, 16439, -1, 14328, 16438, 16411, -1, 14328, 14329, 16438, -1, 14332, 16411, 16410, -1, 14332, 14328, 16411, -1, 11556, 16410, 11557, -1, 11556, 14332, 16410, -1, 14293, 11554, 11555, -1, 14293, 11555, 17257, -1, 14289, 17257, 17280, -1, 14289, 14293, 17257, -1, 14285, 17280, 17279, -1, 14285, 14289, 17280, -1, 14286, 17279, 17278, -1, 14286, 14285, 17279, -1, 14288, 17278, 17276, -1, 14288, 14286, 17278, -1, 14291, 17276, 17267, -1, 14291, 14288, 17276, -1, 14295, 17267, 17263, -1, 14295, 14291, 17267, -1, 14298, 17263, 17261, -1, 14298, 14295, 17263, -1, 14300, 17261, 17259, -1, 14300, 14298, 17261, -1, 14281, 17259, 17258, -1, 14281, 14300, 17259, -1, 14280, 17258, 17260, -1, 14280, 14281, 17258, -1, 14284, 17260, 17262, -1, 14284, 14280, 17260, -1, 11523, 17262, 11524, -1, 11523, 14284, 17262, -1, 16940, 16918, 16944, -1, 16940, 16944, 16957, -1, 17281, 14242, 14243, -1, 17281, 16929, 16927, -1, 17282, 14243, 14244, -1, 17282, 16931, 16929, -1, 17282, 17281, 14243, -1, 17282, 16929, 17281, -1, 17283, 14244, 14241, -1, 17283, 16933, 16931, -1, 17283, 16931, 17282, -1, 17283, 17282, 14244, -1, 17284, 11519, 14240, -1, 17284, 14240, 14242, -1, 17284, 14242, 17281, -1, 17285, 11520, 11519, -1, 17285, 16927, 16926, -1, 17285, 16926, 11520, -1, 17285, 11519, 17284, -1, 17285, 17284, 17281, -1, 17285, 17281, 16927, -1, 17286, 14241, 14239, -1, 17286, 14239, 14237, -1, 17286, 14237, 14226, -1, 17286, 17283, 14241, -1, 17287, 14226, 16936, -1, 17287, 16936, 16933, -1, 17287, 17286, 14226, -1, 17287, 17283, 17286, -1, 17287, 16933, 17283, -1, 17288, 16907, 17289, -1, 17288, 17289, 16945, -1, 17290, 16913, 16911, -1, 17290, 16947, 16948, -1, 17290, 16911, 17288, -1, 17290, 17288, 16947, -1, 17291, 16956, 16955, -1, 17291, 16955, 16954, -1, 17291, 16954, 17292, -1, 17293, 16895, 16894, -1, 17293, 16894, 16893, -1, 17293, 16893, 16956, -1, 17293, 17291, 17292, -1, 17293, 16956, 17291, -1, 17293, 17292, 16895, -1, 17294, 16944, 16918, -1, 17294, 16948, 16949, -1, 17294, 16949, 16944, -1, 17294, 17290, 16948, -1, 17295, 16918, 16915, -1, 17295, 16915, 16913, -1, 17295, 17294, 16918, -1, 17295, 16913, 17290, -1, 17295, 17290, 17294, -1, 17292, 16897, 16895, -1, 17292, 16954, 16953, -1, 17296, 16901, 16899, -1, 17296, 16899, 16897, -1, 17296, 16953, 16952, -1, 17296, 16952, 16951, -1, 17296, 17292, 16953, -1, 17296, 16897, 17292, -1, 17297, 16903, 16901, -1, 17297, 16951, 16950, -1, 17297, 16950, 16943, -1, 17297, 17296, 16951, -1, 17297, 16901, 17296, -1, 17289, 16907, 16905, -1, 17289, 16905, 16903, -1, 17289, 16943, 16945, -1, 17289, 17297, 16943, -1, 17289, 16903, 17297, -1, 17288, 16911, 16909, -1, 17288, 16909, 16907, -1, 17288, 16945, 16946, -1, 17288, 16946, 16947, -1, 16956, 16922, 16958, -1, 16893, 16922, 16956, -1, 11493, 16783, 16819, -1, 11495, 16783, 11493, -1, 11468, 11499, 16817, -1, 16775, 11468, 16817, -1, 16777, 16817, 16816, -1, 16777, 16775, 16817, -1, 16779, 16816, 16818, -1, 16779, 16777, 16816, -1, 17298, 16797, 17299, -1, 17298, 17299, 14209, -1, 17300, 16804, 16802, -1, 17300, 16802, 16800, -1, 17300, 14207, 14206, -1, 17300, 14206, 14205, -1, 17300, 16800, 17298, -1, 17300, 17298, 14207, -1, 17301, 16806, 16804, -1, 17301, 14205, 14204, -1, 17301, 16804, 17300, -1, 17301, 17300, 14205, -1, 17302, 14196, 14212, -1, 17302, 14212, 14215, -1, 17302, 14215, 14214, -1, 17302, 14214, 17303, -1, 17304, 16789, 16787, -1, 17304, 16787, 14196, -1, 17304, 17302, 17303, -1, 17304, 14196, 17302, -1, 17304, 17303, 16789, -1, 17305, 14201, 14188, -1, 17305, 14204, 14203, -1, 17305, 14203, 14201, -1, 17305, 17301, 14204, -1, 17306, 14188, 16809, -1, 17306, 16809, 16806, -1, 17306, 16806, 17301, -1, 17306, 17301, 17305, -1, 17306, 17305, 14188, -1, 17303, 16791, 16789, -1, 17303, 14214, 14213, -1, 17307, 16795, 16793, -1, 17307, 16793, 16791, -1, 17307, 14213, 14211, -1, 17307, 14211, 14210, -1, 17307, 17303, 14213, -1, 17307, 16791, 17303, -1, 17299, 16797, 16795, -1, 17299, 14210, 14209, -1, 17299, 17307, 14210, -1, 17299, 16795, 17307, -1, 17298, 16800, 16798, -1, 17298, 16798, 16797, -1, 17298, 14209, 14208, -1, 17298, 14208, 14207, -1, 16820, 16779, 16818, -1, 16813, 16779, 16820, -1, 16875, 16841, 16879, -1, 16875, 16879, 16878, -1, 17308, 16864, 16862, -1, 17308, 17309, 14007, -1, 17308, 16862, 17309, -1, 17310, 14014, 14018, -1, 17310, 16868, 16866, -1, 17310, 17308, 14014, -1, 17310, 16866, 17308, -1, 17311, 14016, 14011, -1, 17311, 14011, 14010, -1, 17311, 14010, 17312, -1, 17313, 14002, 14016, -1, 17313, 16851, 16849, -1, 17313, 16849, 14002, -1, 17313, 17311, 17312, -1, 17313, 17312, 16851, -1, 17313, 14016, 17311, -1, 17314, 14018, 14019, -1, 17314, 14019, 14017, -1, 17314, 17310, 14018, -1, 17315, 14017, 13994, -1, 17315, 13994, 16871, -1, 17315, 16871, 16868, -1, 17315, 17310, 17314, -1, 17315, 17314, 14017, -1, 17315, 16868, 17310, -1, 17312, 14010, 14012, -1, 17312, 16853, 16851, -1, 17316, 14012, 14013, -1, 17316, 14013, 14006, -1, 17316, 16857, 16855, -1, 17316, 16855, 16853, -1, 17316, 17312, 14012, -1, 17316, 16853, 17312, -1, 17317, 14006, 14008, -1, 17317, 14008, 14009, -1, 17317, 16859, 16857, -1, 17317, 17316, 14006, -1, 17317, 16857, 17316, -1, 17309, 14009, 14007, -1, 17309, 16862, 16860, -1, 17309, 16860, 16859, -1, 17309, 16859, 17317, -1, 17309, 17317, 14009, -1, 17308, 14007, 14015, -1, 17308, 14015, 14014, -1, 17308, 16866, 16864, -1, 17318, 17319, 17320, -1, 17318, 17320, 16823, -1, 17318, 11466, 17319, -1, 17321, 16882, 16881, -1, 17321, 16881, 16879, -1, 17321, 16879, 16841, -1, 17321, 17322, 16882, -1, 17323, 16841, 16839, -1, 17323, 16839, 16837, -1, 17323, 17321, 16841, -1, 17323, 16837, 17322, -1, 17323, 17322, 17321, -1, 17320, 16889, 16888, -1, 17320, 16825, 16823, -1, 17324, 16888, 16890, -1, 17324, 16890, 16887, -1, 17324, 16829, 16827, -1, 17324, 16827, 16825, -1, 17324, 17320, 16888, -1, 17324, 16825, 17320, -1, 17325, 16887, 16886, -1, 17325, 16831, 16829, -1, 17325, 16829, 17324, -1, 17325, 17324, 16887, -1, 17326, 16886, 16884, -1, 17326, 16884, 16883, -1, 17326, 16835, 16833, -1, 17326, 16833, 16831, -1, 17326, 16831, 17325, -1, 17326, 17325, 16886, -1, 17322, 16883, 16882, -1, 17322, 16837, 16835, -1, 17322, 16835, 17326, -1, 17322, 17326, 16883, -1, 17319, 11466, 11465, -1, 17319, 11465, 16885, -1, 17319, 16885, 16889, -1, 17319, 16889, 17320, -1, 17318, 16823, 16821, -1, 17318, 16821, 11466, -1, 11460, 16845, 16880, -1, 11459, 16845, 11460, -1, 16677, 13818, 16676, -1, 16673, 16671, 14221, -1, 11458, 17327, 14221, -1, 14221, 17327, 16696, -1, 17328, 17329, 14183, -1, 14183, 17329, 16690, -1, 16672, 14221, 16696, -1, 17330, 17331, 13989, -1, 13989, 17331, 16684, -1, 16672, 16673, 14221, -1, 16670, 16672, 16696, -1, 17331, 13891, 16684, -1, 11708, 17328, 14183, -1, 17332, 13889, 13891, -1, 17332, 13891, 17331, -1, 11711, 17328, 11708, -1, 11711, 17333, 17328, -1, 17334, 13887, 13889, -1, 17334, 13889, 17332, -1, 11445, 13885, 13887, -1, 11445, 13887, 17334, -1, 11713, 17333, 11711, -1, 11713, 17335, 17333, -1, 13882, 16680, 16681, -1, 13882, 16681, 16679, -1, 11446, 13882, 13885, -1, 11446, 13885, 11445, -1, 11447, 13882, 11446, -1, 17176, 11859, 11878, -1, 17176, 11878, 11880, -1, 17184, 16678, 16680, -1, 17184, 16680, 13882, -1, 17336, 17170, 17172, -1, 17184, 13882, 11447, -1, 11715, 17335, 11713, -1, 17184, 11447, 11449, -1, 17337, 17336, 17172, -1, 17337, 17172, 17174, -1, 11451, 17184, 11449, -1, 13827, 16696, 17327, -1, 17182, 17184, 11451, -1, 17330, 17170, 17336, -1, 17330, 13986, 17170, -1, 17186, 17335, 11715, -1, 17186, 17338, 17335, -1, 11453, 17182, 11451, -1, 17339, 17337, 17174, -1, 17339, 17174, 17176, -1, 17180, 17182, 11453, -1, 14117, 17176, 11880, -1, 13825, 13827, 17327, -1, 14117, 11880, 11874, -1, 17340, 17339, 17176, -1, 13825, 17327, 17341, -1, 17188, 17338, 17186, -1, 11455, 17180, 11453, -1, 17342, 17176, 14117, -1, 17342, 17340, 17176, -1, 17178, 17180, 11455, -1, 17190, 17338, 17188, -1, 17178, 11455, 11458, -1, 17190, 17343, 17338, -1, 17190, 17344, 17343, -1, 14218, 17178, 11458, -1, 17345, 17342, 14117, -1, 17345, 14117, 14120, -1, 13823, 13825, 17341, -1, 13823, 17341, 17346, -1, 16690, 17329, 14126, -1, 17347, 17345, 14120, -1, 13821, 17346, 17348, -1, 17347, 14120, 14122, -1, 13821, 13823, 17346, -1, 13818, 13821, 17348, -1, 13818, 17348, 17344, -1, 13818, 17344, 17190, -1, 17349, 17347, 14122, -1, 14124, 17349, 14122, -1, 11939, 16690, 11928, -1, 17329, 17349, 14124, -1, 11940, 14183, 16690, -1, 11940, 16690, 11939, -1, 16675, 17190, 16674, -1, 11850, 14183, 11940, -1, 14126, 17329, 14124, -1, 13989, 13986, 17330, -1, 16675, 13818, 17190, -1, 13989, 11896, 11898, -1, 14221, 14218, 11458, -1, 13989, 11898, 11899, -1, 16684, 11896, 13989, -1, 16676, 13818, 16675, -1, 16684, 11889, 11896, -1, 17327, 16701, 17341, -1, 16701, 16706, 17341, -1, 17341, 16743, 17346, -1, 16706, 16743, 17341, -1, 17346, 16744, 17348, -1, 16743, 16744, 17346, -1, 17348, 16742, 17344, -1, 16744, 16742, 17348, -1, 17344, 16735, 17343, -1, 16742, 16735, 17344, -1, 17343, 16734, 17338, -1, 16735, 16734, 17343, -1, 17338, 16733, 17335, -1, 16734, 16733, 17338, -1, 17335, 16732, 17333, -1, 16733, 16732, 17335, -1, 17333, 16700, 17328, -1, 16732, 16700, 17333, -1, 11457, 16701, 17327, -1, 11457, 17327, 11458, -1, 16724, 16737, 17331, -1, 17331, 16737, 17332, -1, 17332, 16736, 17334, -1, 16737, 16736, 17332, -1, 17334, 11443, 11445, -1, 16736, 11443, 17334, -1, 16717, 16724, 17331, -1, 16717, 17331, 17330, -1, 17329, 16704, 17349, -1, 17349, 16703, 17347, -1, 16704, 16703, 17349, -1, 17347, 16705, 17345, -1, 16703, 16705, 17347, -1, 17345, 16711, 17342, -1, 16705, 16711, 17345, -1, 17342, 16712, 17340, -1, 16711, 16712, 17342, -1, 17340, 16713, 17339, -1, 16712, 16713, 17340, -1, 17339, 16715, 17337, -1, 16713, 16715, 17339, -1, 17337, 16714, 17336, -1, 16715, 16714, 17337, -1, 17336, 16716, 17330, -1, 16714, 16716, 17336, -1, 16716, 16717, 17330, -1, 17328, 16704, 17329, -1, 16700, 16704, 17328, -1, 16636, 16285, 16290, -1, 13804, 16636, 16290, -1, 13803, 13804, 16290, -1, 16922, 16290, 16670, -1, 16922, 16670, 16958, -1, 16922, 13803, 16290, -1, 13802, 13803, 16922, -1, 16921, 13802, 16922, -1, 16696, 16957, 16958, -1, 16696, 16958, 16670, -1, 16940, 16957, 16696, -1, 13797, 16942, 16940, -1, 13794, 13797, 16940, -1, 16695, 16940, 16696, -1, 16695, 13794, 16940, -1, 14233, 14279, 14223, -1, 14233, 14223, 14221, -1, 14233, 14221, 14236, -1, 14238, 14236, 14221, -1, 14255, 14279, 14233, -1, 14232, 14255, 14233, -1, 14253, 14230, 14228, -1, 16671, 14228, 14238, -1, 16671, 14238, 14221, -1, 16626, 14253, 14228, -1, 16363, 14228, 16671, -1, 16363, 16626, 14228, -1, 16624, 16626, 16363, -1, 16637, 16363, 16283, -1, 16637, 16624, 16363, -1, 16285, 16637, 16283, -1, 16636, 16637, 16285, -1, 12031, 12063, 11929, -1, 12030, 12031, 11929, -1, 14104, 12030, 11929, -1, 16783, 11929, 11928, -1, 16783, 11928, 16819, -1, 16783, 14104, 11929, -1, 14103, 14104, 16783, -1, 16782, 14103, 16783, -1, 16690, 16820, 16819, -1, 16690, 16819, 11928, -1, 16813, 16820, 16690, -1, 14099, 16815, 16813, -1, 14096, 14099, 16813, -1, 16689, 16813, 16690, -1, 16689, 14096, 16813, -1, 14195, 13593, 14185, -1, 14195, 14185, 14183, -1, 14202, 14195, 14183, -1, 14200, 14202, 14183, -1, 13592, 13593, 14195, -1, 14194, 13592, 14195, -1, 14165, 14192, 14190, -1, 11850, 14190, 14200, -1, 11850, 14200, 14183, -1, 14163, 14165, 14190, -1, 11935, 14190, 11850, -1, 11935, 14163, 14190, -1, 12035, 14163, 11935, -1, 12033, 11935, 12062, -1, 12033, 12035, 11935, -1, 12031, 12033, 12062, -1, 12031, 12062, 12063, -1, 17176, 11860, 11859, -1, 11997, 11949, 12060, -1, 11997, 12061, 11860, -1, 11997, 12060, 12061, -1, 11996, 11860, 17176, -1, 11996, 11997, 11860, -1, 17175, 13960, 11996, -1, 17175, 11996, 17176, -1, 11876, 14117, 11874, -1, 12000, 14033, 14118, -1, 12000, 14118, 14117, -1, 12000, 14117, 11876, -1, 11999, 12059, 12058, -1, 11999, 11876, 12059, -1, 11999, 12000, 11876, -1, 11951, 11999, 12058, -1, 11949, 11951, 12058, -1, 11949, 12058, 12060, -1, 11960, 12065, 11892, -1, 11958, 11960, 11892, -1, 13690, 11958, 11892, -1, 16845, 11892, 11889, -1, 16845, 13690, 11892, -1, 16880, 16845, 11889, -1, 13689, 13690, 16845, -1, 16844, 13689, 16845, -1, 16684, 16878, 16880, -1, 16684, 16880, 11889, -1, 16875, 16878, 16684, -1, 13655, 16877, 16875, -1, 13653, 13655, 16875, -1, 16683, 16875, 16684, -1, 16683, 13653, 16875, -1, 14001, 13965, 13991, -1, 14001, 13991, 13989, -1, 14001, 13989, 14020, -1, 14021, 14020, 13989, -1, 13964, 13965, 14001, -1, 14000, 13964, 14001, -1, 13969, 13998, 13996, -1, 11899, 13996, 14021, -1, 11899, 14021, 13989, -1, 13968, 13969, 13996, -1, 11902, 13996, 11899, -1, 11902, 13968, 13996, -1, 11965, 13968, 11902, -1, 11963, 11902, 12064, -1, 11963, 11965, 11902, -1, 11960, 11963, 12064, -1, 11960, 12064, 12065, -1, 16659, 16316, 16319, -1, 17184, 16319, 16678, -1, 16619, 16319, 17184, -1, 16619, 16659, 16319, -1, 17183, 16621, 16619, -1, 17183, 16619, 17184, -1, 16311, 13882, 16679, -1, 13834, 13836, 13883, -1, 13834, 13883, 13882, -1, 13834, 13882, 16311, -1, 16662, 16311, 16310, -1, 16662, 13834, 16311, -1, 16659, 16662, 16310, -1, 16659, 16310, 16316, -1, 16640, 16342, 16345, -1, 17190, 16345, 16674, -1, 13583, 16345, 17190, -1, 13583, 16640, 16345, -1, 17189, 13585, 13583, -1, 17189, 13583, 17190, -1, 16334, 13818, 16677, -1, 13722, 13724, 13819, -1, 13722, 13819, 13818, -1, 13722, 13818, 16334, -1, 16642, 16334, 16333, -1, 16642, 13722, 16334, -1, 16640, 16642, 16333, -1, 16640, 16333, 16342, -1, 11301, 14617, 11302, -1, 17350, 11441, 11440, -1, 17350, 11440, 15017, -1, 17351, 11293, 11441, -1, 17351, 11291, 11293, -1, 17351, 14593, 11291, -1, 17351, 11441, 17350, -1, 17352, 17350, 15017, -1, 17352, 15017, 15013, -1, 17353, 14587, 14593, -1, 17353, 17350, 17352, -1, 17353, 14593, 17351, -1, 17353, 17351, 17350, -1, 17354, 15013, 15010, -1, 17354, 17352, 15013, -1, 17355, 17352, 17354, -1, 17355, 17353, 17352, -1, 17355, 14924, 14587, -1, 17355, 14587, 17353, -1, 17356, 17354, 15010, -1, 17356, 15010, 15009, -1, 17357, 14920, 14924, -1, 17357, 14924, 17355, -1, 17357, 17355, 17354, -1, 17357, 17354, 17356, -1, 17358, 17356, 15009, -1, 17358, 15009, 15005, -1, 17359, 17357, 17356, -1, 17359, 14920, 17357, -1, 17359, 17356, 17358, -1, 17359, 14910, 14920, -1, 17360, 15005, 15002, -1, 17360, 17358, 15005, -1, 17361, 17358, 17360, -1, 17361, 14614, 14910, -1, 17361, 17359, 17358, -1, 17361, 14910, 17359, -1, 17362, 17360, 15002, -1, 17362, 15002, 15001, -1, 17363, 17361, 17360, -1, 17363, 14614, 17361, -1, 17363, 17360, 17362, -1, 17363, 14611, 14614, -1, 17364, 15001, 14998, -1, 17364, 17362, 15001, -1, 17365, 14885, 14611, -1, 17365, 17362, 17364, -1, 17365, 14611, 17363, -1, 17365, 17363, 17362, -1, 17366, 14998, 14994, -1, 17366, 17364, 14998, -1, 17367, 17364, 17366, -1, 17367, 14874, 14885, -1, 17367, 17365, 17364, -1, 17367, 14885, 17365, -1, 17368, 14994, 14991, -1, 17368, 17366, 14994, -1, 17369, 17367, 17366, -1, 17369, 14874, 17367, -1, 17369, 14863, 14874, -1, 17369, 14854, 14863, -1, 17369, 17366, 17368, -1, 17370, 14991, 14990, -1, 17370, 17368, 14991, -1, 17371, 17368, 17370, -1, 17371, 17369, 17368, -1, 17371, 14854, 17369, -1, 17372, 17370, 14990, -1, 17372, 14990, 14986, -1, 17373, 14854, 17371, -1, 17373, 17370, 17372, -1, 17373, 17371, 17370, -1, 17373, 14841, 14854, -1, 17374, 17372, 14986, -1, 17374, 14986, 14983, -1, 17375, 14841, 17373, -1, 17375, 17373, 17372, -1, 17375, 14832, 14841, -1, 17375, 17372, 17374, -1, 17376, 14983, 14979, -1, 17376, 17374, 14983, -1, 17377, 14832, 17375, -1, 17377, 17375, 17374, -1, 17377, 17374, 17376, -1, 17377, 14815, 14832, -1, 17377, 14805, 14815, -1, 17378, 17376, 14979, -1, 17378, 14979, 14978, -1, 17379, 17376, 17378, -1, 17379, 14805, 17377, -1, 17379, 17377, 17376, -1, 17380, 14978, 14975, -1, 17380, 17378, 14978, -1, 17381, 14805, 17379, -1, 17381, 17379, 17378, -1, 17381, 14798, 14805, -1, 17381, 17378, 17380, -1, 17382, 14975, 14971, -1, 17382, 17380, 14975, -1, 17383, 17381, 17380, -1, 17383, 14798, 17381, -1, 17383, 14785, 14798, -1, 17383, 17380, 17382, -1, 17384, 14971, 14970, -1, 17384, 17382, 14971, -1, 17385, 17383, 17382, -1, 17385, 14785, 17383, -1, 17385, 14763, 14785, -1, 17385, 14750, 14763, -1, 17385, 17382, 17384, -1, 17386, 14970, 14967, -1, 17386, 17384, 14970, -1, 17387, 17385, 17384, -1, 17387, 14750, 17385, -1, 17387, 17384, 17386, -1, 17388, 14967, 14964, -1, 17388, 17386, 14967, -1, 17389, 14775, 14750, -1, 17389, 14750, 17387, -1, 17389, 17387, 17386, -1, 17389, 17386, 17388, -1, 17390, 14964, 14960, -1, 17390, 17388, 14964, -1, 17391, 14769, 14775, -1, 17391, 14775, 17389, -1, 17391, 17389, 17388, -1, 17391, 17388, 17390, -1, 17392, 14960, 14959, -1, 17392, 17390, 14960, -1, 17393, 14760, 14769, -1, 17393, 14769, 17391, -1, 17393, 17391, 17390, -1, 17393, 17390, 17392, -1, 17394, 14959, 14956, -1, 17394, 17392, 14959, -1, 17395, 14748, 14760, -1, 17395, 14760, 17393, -1, 17395, 17393, 17392, -1, 17395, 17392, 17394, -1, 17396, 14956, 14952, -1, 17396, 17394, 14956, -1, 17397, 14724, 14748, -1, 17397, 14700, 14724, -1, 17397, 14748, 17395, -1, 17397, 17395, 17394, -1, 17397, 17394, 17396, -1, 17398, 14952, 14949, -1, 17398, 17396, 14952, -1, 17399, 17396, 17398, -1, 17399, 14700, 17397, -1, 17399, 17397, 17396, -1, 17400, 14949, 14948, -1, 17400, 17398, 14949, -1, 17401, 14700, 17399, -1, 17401, 17398, 17400, -1, 17401, 17399, 17398, -1, 17401, 14701, 14700, -1, 17401, 14720, 14701, -1, 17402, 17400, 14948, -1, 17402, 14948, 14944, -1, 17403, 17400, 17402, -1, 17403, 17401, 17400, -1, 17403, 14720, 17401, -1, 17404, 14944, 14941, -1, 17404, 17402, 14944, -1, 17405, 17403, 17402, -1, 17405, 14720, 17403, -1, 17405, 17402, 17404, -1, 17405, 14713, 14720, -1, 17406, 14941, 14940, -1, 17406, 17404, 14941, -1, 17407, 17405, 17404, -1, 17407, 14713, 17405, -1, 17407, 17404, 17406, -1, 17407, 14698, 14713, -1, 17407, 14688, 14698, -1, 17408, 14940, 15036, -1, 17408, 17406, 14940, -1, 17409, 14688, 17407, -1, 17409, 17407, 17406, -1, 17409, 17406, 17408, -1, 17410, 17408, 15036, -1, 17410, 15036, 14935, -1, 17411, 17408, 17410, -1, 17411, 17409, 17408, -1, 17411, 14688, 17409, -1, 17411, 14677, 14688, -1, 17412, 14935, 15034, -1, 17412, 17410, 14935, -1, 17413, 17410, 17412, -1, 17413, 17411, 17410, -1, 17413, 14677, 17411, -1, 17413, 14667, 14677, -1, 17414, 15034, 15033, -1, 17414, 17412, 15034, -1, 17415, 17413, 17412, -1, 17415, 14667, 17413, -1, 17415, 17412, 17414, -1, 17415, 14656, 14667, -1, 17416, 15033, 15029, -1, 17416, 17414, 15033, -1, 17417, 17415, 17414, -1, 17417, 14656, 17415, -1, 17417, 17414, 17416, -1, 17417, 14645, 14656, -1, 17418, 15029, 15026, -1, 17418, 17416, 15029, -1, 17419, 17416, 17418, -1, 17419, 17417, 17416, -1, 17419, 14645, 17417, -1, 17419, 14634, 14645, -1, 17420, 15020, 11297, -1, 17420, 15026, 15020, -1, 17420, 17418, 15026, -1, 17420, 11297, 11298, -1, 17421, 17418, 17420, -1, 17421, 11302, 14617, -1, 17421, 11298, 11302, -1, 17421, 17419, 17418, -1, 17421, 14634, 17419, -1, 17421, 17420, 11298, -1, 17421, 14617, 14634, -1, 15682, 17422, 15684, -1, 17423, 17422, 15682, -1, 17424, 17425, 17423, -1, 17426, 17425, 17424, -1, 16221, 17427, 16219, -1, 16219, 17427, 17428, -1, 17429, 17427, 17426, -1, 17428, 17427, 17429, -1, 15684, 17430, 15683, -1, 17422, 17430, 15684, -1, 17423, 17431, 17422, -1, 17425, 17431, 17423, -1, 16223, 17432, 16221, -1, 17426, 17432, 17425, -1, 17427, 17432, 17426, -1, 16221, 17432, 17427, -1, 15683, 17433, 15685, -1, 17430, 17433, 15683, -1, 16214, 16218, 17434, -1, 17422, 17435, 17430, -1, 17431, 17435, 17422, -1, 16225, 17436, 16223, -1, 17432, 17436, 17425, -1, 16223, 17436, 17432, -1, 17425, 17436, 17431, -1, 15685, 17437, 15686, -1, 17433, 17437, 15685, -1, 17430, 17438, 17433, -1, 17435, 17438, 17430, -1, 17436, 17439, 17431, -1, 17431, 17439, 17435, -1, 16225, 17439, 17436, -1, 15686, 17440, 15687, -1, 17437, 17440, 15686, -1, 17433, 17441, 17437, -1, 17438, 17441, 17433, -1, 16229, 17442, 16227, -1, 16227, 17442, 16225, -1, 17435, 17442, 17438, -1, 16225, 17442, 17439, -1, 17439, 17442, 17435, -1, 15687, 17443, 15688, -1, 17440, 17443, 15687, -1, 17437, 17444, 17440, -1, 17441, 17444, 17437, -1, 16231, 17445, 16229, -1, 16229, 17445, 17442, -1, 17438, 17445, 17441, -1, 17442, 17445, 17438, -1, 15688, 17446, 11273, -1, 11273, 17446, 11271, -1, 17443, 17446, 15688, -1, 17440, 17447, 17443, -1, 17444, 17447, 17440, -1, 16233, 17448, 16231, -1, 16231, 17448, 17445, -1, 17441, 17448, 17444, -1, 17445, 17448, 17441, -1, 17447, 17449, 17443, -1, 17443, 17449, 17446, -1, 11271, 17449, 11281, -1, 17446, 17449, 11271, -1, 16235, 17450, 16233, -1, 17451, 17452, 15678, -1, 16233, 17450, 17448, -1, 15678, 17452, 15679, -1, 17444, 17450, 17447, -1, 15679, 17452, 15680, -1, 17448, 17450, 17444, -1, 11277, 17453, 16235, -1, 11281, 17453, 11279, -1, 15680, 17424, 15681, -1, 11279, 17453, 11277, -1, 17447, 17453, 17449, -1, 16235, 17453, 17450, -1, 17449, 17453, 11281, -1, 17452, 17424, 15680, -1, 17450, 17453, 17447, -1, 17454, 17429, 17451, -1, 17451, 17429, 17452, -1, 15681, 17423, 15682, -1, 17424, 17423, 15681, -1, 17452, 17426, 17424, -1, 17429, 17426, 17452, -1, 16219, 17428, 16218, -1, 17434, 17428, 17454, -1, 16218, 17428, 17434, -1, 17454, 17428, 17429, -1, 16237, 17455, 11289, -1, 11288, 17455, 11286, -1, 11289, 17455, 11288, -1, 11286, 17456, 11275, -1, 17455, 17456, 11286, -1, 11275, 17457, 11276, -1, 17456, 17457, 11275, -1, 17457, 15700, 11276, -1, 16215, 16214, 17458, -1, 17458, 17434, 17459, -1, 16214, 17434, 17458, -1, 17459, 17454, 17460, -1, 17434, 17454, 17459, -1, 17460, 17451, 15689, -1, 17454, 17451, 17460, -1, 17451, 15678, 15689, -1, 17461, 17462, 15702, -1, 17463, 17464, 17465, -1, 17465, 17464, 17466, -1, 16247, 17467, 16246, -1, 16246, 17467, 17468, -1, 17469, 17467, 17463, -1, 17456, 17470, 17457, -1, 17468, 17467, 17469, -1, 17457, 17470, 17461, -1, 15690, 17471, 15691, -1, 15691, 17471, 15689, -1, 15701, 17472, 15697, -1, 15689, 17471, 17460, -1, 17473, 17471, 15690, -1, 17462, 17472, 15701, -1, 17466, 17474, 17473, -1, 17461, 17475, 17462, -1, 17464, 17474, 17466, -1, 16248, 17476, 16247, -1, 16247, 17476, 17467, -1, 17470, 17475, 17461, -1, 16239, 17477, 16238, -1, 17467, 17476, 17463, -1, 17455, 17477, 17456, -1, 17463, 17476, 17464, -1, 16238, 17477, 17455, -1, 17460, 17478, 17459, -1, 17456, 17477, 17470, -1, 15697, 17479, 15698, -1, 17471, 17478, 17460, -1, 17473, 17478, 17471, -1, 17474, 17478, 17473, -1, 17464, 17480, 17474, -1, 16250, 17480, 16248, -1, 16248, 17480, 17476, -1, 17472, 17479, 15697, -1, 17476, 17480, 17464, -1, 17462, 17481, 17472, -1, 17458, 17482, 16250, -1, 17459, 17482, 17458, -1, 17475, 17481, 17462, -1, 16250, 17482, 17480, -1, 17480, 17482, 17474, -1, 17474, 17482, 17478, -1, 17478, 17482, 17459, -1, 16240, 17483, 16239, -1, 17470, 17483, 17475, -1, 16237, 16238, 17455, -1, 17477, 17483, 17470, -1, 16239, 17483, 17477, -1, 15698, 17484, 15699, -1, 17479, 17484, 15698, -1, 17472, 17485, 17479, -1, 17481, 17485, 17472, -1, 16240, 17486, 17483, -1, 16241, 17486, 16240, -1, 17483, 17486, 17475, -1, 17475, 17486, 17481, -1, 15699, 17487, 15694, -1, 17484, 17487, 15699, -1, 17479, 17488, 17484, -1, 17485, 17488, 17479, -1, 16242, 17489, 16241, -1, 17486, 17489, 17481, -1, 17481, 17489, 17485, -1, 16241, 17489, 17486, -1, 15694, 17490, 15695, -1, 17487, 17490, 15694, -1, 17488, 17491, 17484, -1, 17484, 17491, 17487, -1, 17485, 17492, 17488, -1, 16243, 17492, 16242, -1, 16242, 17492, 17489, -1, 17489, 17492, 17485, -1, 15695, 17493, 15696, -1, 17490, 17493, 15695, -1, 17491, 17494, 17487, -1, 17487, 17494, 17490, -1, 17488, 17495, 17491, -1, 16243, 17495, 17492, -1, 16244, 17495, 16243, -1, 17492, 17495, 17488, -1, 15696, 17465, 15693, -1, 17493, 17465, 15696, -1, 17494, 17469, 17490, -1, 17490, 17469, 17493, -1, 16245, 17496, 16244, -1, 16244, 17496, 17495, -1, 17495, 17496, 17491, -1, 17491, 17496, 17494, -1, 15693, 17466, 15692, -1, 17465, 17466, 15693, -1, 17469, 17463, 17493, -1, 17493, 17463, 17465, -1, 16246, 17468, 16245, -1, 16250, 16215, 17458, -1, 17494, 17468, 17469, -1, 16245, 17468, 17496, -1, 17496, 17468, 17494, -1, 15700, 17461, 15702, -1, 15692, 17473, 15690, -1, 17457, 17461, 15700, -1, 17466, 17473, 15692, -1, 15702, 17462, 15701, -1, 17497, 15673, 15654, -1, 16249, 11214, 11211, -1, 17498, 17499, 17497, -1, 17497, 17499, 15673, -1, 17500, 17501, 17498, -1, 17498, 17501, 17499, -1, 15673, 17502, 15671, -1, 15671, 17502, 11260, -1, 11260, 17502, 11258, -1, 17499, 17502, 15673, -1, 16251, 17503, 16213, -1, 16213, 17503, 17500, -1, 17500, 17503, 17501, -1, 11258, 17504, 11213, -1, 17501, 17504, 17499, -1, 17502, 17504, 11258, -1, 17499, 17504, 17502, -1, 16249, 17505, 16251, -1, 11213, 17505, 11211, -1, 17504, 17505, 11213, -1, 16251, 17505, 17503, -1, 17501, 17505, 17504, -1, 17503, 17505, 17501, -1, 11211, 17505, 16249, -1, 11251, 11253, 12694, -1, 12694, 11253, 17506, -1, 17506, 11267, 17507, -1, 11253, 11267, 17506, -1, 17507, 11256, 17508, -1, 17508, 11256, 12081, -1, 11267, 11256, 17507, -1, 11256, 11255, 12081, -1, 15629, 17509, 15654, -1, 15654, 17509, 17497, -1, 17497, 17510, 17498, -1, 17509, 17510, 17497, -1, 17498, 17511, 17500, -1, 17510, 17511, 17498, -1, 17500, 16216, 16213, -1, 17511, 16216, 17500, -1, 17512, 17513, 17514, -1, 17506, 17515, 12694, -1, 17516, 17513, 17512, -1, 17517, 17518, 17516, -1, 12692, 17519, 12690, -1, 16228, 17518, 16230, -1, 16230, 17518, 17520, -1, 17515, 17519, 12692, -1, 17520, 17518, 17517, -1, 15636, 17521, 15634, -1, 17507, 17522, 17506, -1, 17523, 17521, 15636, -1, 17506, 17522, 17515, -1, 12690, 17524, 12688, -1, 17514, 17525, 17523, -1, 17513, 17525, 17514, -1, 17519, 17524, 12690, -1, 16226, 17526, 16228, -1, 17515, 17527, 17519, -1, 17518, 17526, 17516, -1, 16228, 17526, 17518, -1, 17516, 17526, 17513, -1, 15634, 17528, 15632, -1, 17522, 17527, 17515, -1, 12079, 17529, 12080, -1, 17508, 17529, 17507, -1, 12080, 17529, 17508, -1, 17521, 17528, 15634, -1, 17507, 17529, 17522, -1, 12688, 17530, 15650, -1, 12081, 12080, 17508, -1, 17523, 17531, 17521, -1, 17525, 17531, 17523, -1, 17524, 17530, 12688, -1, 16224, 17532, 16226, -1, 17519, 17533, 17524, -1, 16226, 17532, 17526, -1, 17527, 17533, 17519, -1, 17513, 17532, 17525, -1, 17526, 17532, 17513, -1, 17528, 17534, 15632, -1, 12078, 17535, 12079, -1, 15632, 17534, 15630, -1, 17529, 17535, 17522, -1, 17522, 17535, 17527, -1, 15630, 17534, 17509, -1, 12079, 17535, 17529, -1, 15650, 17536, 15647, -1, 17530, 17536, 15650, -1, 17521, 17537, 17528, -1, 17531, 17537, 17521, -1, 17533, 17538, 17524, -1, 16222, 17539, 16224, -1, 16224, 17539, 17532, -1, 17525, 17539, 17531, -1, 17532, 17539, 17525, -1, 17524, 17538, 17530, -1, 17528, 17540, 17534, -1, 17527, 17541, 17533, -1, 17509, 17540, 17510, -1, 17534, 17540, 17509, -1, 12078, 17541, 17535, -1, 17537, 17540, 17528, -1, 17535, 17541, 17527, -1, 15647, 17542, 15645, -1, 16220, 17543, 16222, -1, 16222, 17543, 17539, -1, 17531, 17543, 17537, -1, 17539, 17543, 17531, -1, 17536, 17542, 15647, -1, 16220, 17544, 17543, -1, 17511, 17544, 16216, -1, 17510, 17544, 17511, -1, 16216, 17544, 16217, -1, 16217, 17544, 16220, -1, 17538, 17545, 17530, -1, 17537, 17544, 17540, -1, 17540, 17544, 17510, -1, 17543, 17544, 17537, -1, 17530, 17545, 17536, -1, 16236, 17546, 12078, -1, 17533, 17546, 17538, -1, 12078, 17546, 17541, -1, 17541, 17546, 17533, -1, 15645, 17547, 15643, -1, 17542, 17547, 15645, -1, 17545, 17548, 17536, -1, 17536, 17548, 17542, -1, 17546, 17549, 17538, -1, 16234, 17549, 16236, -1, 16236, 17549, 17546, -1, 17538, 17549, 17545, -1, 15643, 17512, 15641, -1, 17547, 17512, 15643, -1, 17548, 17517, 17542, -1, 17542, 17517, 17547, -1, 17549, 17550, 17545, -1, 17545, 17550, 17548, -1, 16234, 17550, 17549, -1, 16232, 17550, 16234, -1, 15641, 17514, 15638, -1, 15630, 17509, 15629, -1, 17512, 17514, 15641, -1, 17517, 17516, 17547, -1, 17547, 17516, 17512, -1, 17550, 17520, 17548, -1, 17548, 17520, 17517, -1, 16230, 17520, 16232, -1, 16232, 17520, 17550, -1, 15638, 17523, 15636, -1, 17514, 17523, 15638, -1, 12694, 17515, 12692, -1, 16208, 17551, 16210, -1, 16210, 17551, 17552, -1, 17552, 17551, 17553, -1, 17553, 17551, 17554, -1, 15772, 17555, 15770, -1, 15770, 17555, 11198, -1, 11198, 17555, 11196, -1, 15783, 17556, 15780, -1, 17557, 17555, 15772, -1, 17558, 17559, 17557, -1, 17560, 17559, 17558, -1, 16206, 17561, 16208, -1, 17554, 17561, 17560, -1, 16208, 17561, 17551, -1, 17551, 17561, 17554, -1, 11196, 17562, 11202, -1, 17555, 17562, 11196, -1, 17557, 17562, 17555, -1, 17559, 17562, 17557, -1, 16204, 17563, 16206, -1, 16206, 17563, 17561, -1, 17560, 17563, 17559, -1, 17561, 17563, 17560, -1, 16202, 17564, 16204, -1, 11202, 17564, 11209, -1, 16204, 17564, 17563, -1, 11209, 17564, 16202, -1, 17562, 17564, 11202, -1, 17559, 17564, 17562, -1, 17563, 17564, 17559, -1, 16202, 11208, 11209, -1, 17556, 17565, 15780, -1, 15780, 17566, 15778, -1, 17565, 17566, 15780, -1, 17567, 17568, 17556, -1, 17556, 17568, 17565, -1, 15778, 17569, 15776, -1, 17566, 17569, 15778, -1, 17568, 17553, 17565, -1, 17565, 17553, 17566, -1, 16212, 17570, 16178, -1, 16178, 17570, 17571, -1, 17571, 17570, 17567, -1, 17567, 17570, 17568, -1, 15776, 17558, 15774, -1, 17569, 17558, 15776, -1, 17553, 17554, 17566, -1, 17566, 17554, 17569, -1, 16210, 17552, 16212, -1, 17570, 17552, 17568, -1, 17568, 17552, 17553, -1, 16212, 17552, 17570, -1, 15774, 17557, 15772, -1, 17558, 17557, 15774, -1, 17554, 17560, 17569, -1, 17569, 17560, 17558, -1, 11177, 11179, 12661, -1, 12661, 11179, 17572, -1, 17572, 11189, 17573, -1, 11179, 11189, 17572, -1, 17573, 11193, 17574, -1, 11189, 11193, 17573, -1, 17574, 11194, 12089, -1, 11193, 11194, 17574, -1, 15783, 15790, 17556, -1, 17556, 17575, 17567, -1, 15790, 17575, 17556, -1, 17567, 17576, 17571, -1, 17575, 17576, 17567, -1, 17571, 17577, 16178, -1, 17576, 17577, 17571, -1, 17577, 16181, 16178, -1, 17578, 17579, 17580, -1, 17581, 17579, 17578, -1, 12658, 17582, 12656, -1, 17583, 17584, 17581, -1, 16192, 17584, 12082, -1, 17585, 17584, 17583, -1, 17586, 17582, 12658, -1, 12082, 17584, 17585, -1, 15797, 17587, 15795, -1, 17573, 17588, 17572, -1, 17572, 17588, 17586, -1, 17589, 17587, 15797, -1, 12656, 17590, 12654, -1, 17580, 17591, 17589, -1, 17579, 17591, 17580, -1, 17582, 17590, 12656, -1, 16191, 17592, 16192, -1, 17584, 17592, 17581, -1, 17581, 17592, 17579, -1, 17586, 17593, 17582, -1, 16192, 17592, 17584, -1, 17588, 17593, 17586, -1, 15795, 17594, 15793, -1, 17574, 17595, 17573, -1, 12088, 17595, 17574, -1, 17573, 17595, 17588, -1, 12654, 17596, 12652, -1, 17587, 17594, 15795, -1, 17589, 17597, 17587, -1, 17590, 17596, 12654, -1, 12089, 12088, 17574, -1, 17591, 17597, 17589, -1, 17582, 17598, 17590, -1, 17593, 17598, 17582, -1, 16189, 17599, 16191, -1, 16191, 17599, 17592, -1, 17579, 17599, 17591, -1, 17592, 17599, 17579, -1, 17594, 17600, 15793, -1, 12087, 17601, 12088, -1, 15793, 17600, 15791, -1, 17595, 17601, 17588, -1, 17588, 17601, 17593, -1, 12088, 17601, 17595, -1, 15791, 17600, 17575, -1, 12652, 17602, 12650, -1, 17587, 17603, 17594, -1, 17597, 17603, 17587, -1, 17596, 17602, 12652, -1, 17598, 17604, 17590, -1, 16187, 17605, 16189, -1, 16189, 17605, 17599, -1, 17591, 17605, 17597, -1, 17590, 17604, 17596, -1, 17599, 17605, 17591, -1, 12086, 17606, 12087, -1, 17575, 17607, 17576, -1, 17600, 17607, 17575, -1, 17601, 17606, 17593, -1, 17603, 17607, 17594, -1, 17593, 17606, 17598, -1, 17594, 17607, 17600, -1, 12087, 17606, 17601, -1, 12650, 17608, 12648, -1, 16185, 17609, 16187, -1, 17597, 17609, 17603, -1, 16187, 17609, 17605, -1, 17602, 17608, 12650, -1, 17605, 17609, 17597, -1, 16185, 17610, 17609, -1, 17577, 17610, 16181, -1, 17576, 17610, 17577, -1, 16181, 17610, 16183, -1, 16183, 17610, 16185, -1, 17603, 17610, 17607, -1, 17596, 17611, 17602, -1, 17607, 17610, 17576, -1, 17604, 17611, 17596, -1, 17609, 17610, 17603, -1, 12085, 17612, 12086, -1, 17598, 17612, 17604, -1, 12086, 17612, 17606, -1, 17606, 17612, 17598, -1, 12648, 17613, 12647, -1, 17608, 17613, 12648, -1, 17611, 17614, 17602, -1, 17602, 17614, 17608, -1, 17612, 17615, 17604, -1, 12084, 17615, 12085, -1, 12085, 17615, 17612, -1, 17604, 17615, 17611, -1, 12647, 17578, 15801, -1, 17613, 17578, 12647, -1, 17614, 17583, 17608, -1, 17608, 17583, 17613, -1, 17615, 17616, 17611, -1, 17611, 17616, 17614, -1, 12084, 17616, 17615, -1, 15791, 17575, 15790, -1, 12083, 17616, 12084, -1, 15801, 17580, 15799, -1, 17578, 17580, 15801, -1, 17583, 17581, 17613, -1, 17613, 17581, 17578, -1, 17616, 17585, 17614, -1, 17614, 17585, 17583, -1, 12082, 17585, 12083, -1, 12083, 17585, 17616, -1, 15799, 17589, 15797, -1, 17580, 17589, 15799, -1, 12661, 17586, 12658, -1, 17572, 17586, 12661, -1, 17617, 17618, 17619, -1, 17620, 17621, 15810, -1, 15817, 17622, 15816, -1, 17623, 17624, 17625, -1, 17626, 17622, 15817, -1, 17625, 17624, 17620, -1, 17619, 17627, 17626, -1, 16205, 17628, 16203, -1, 17629, 17628, 17623, -1, 16203, 17628, 17630, -1, 17630, 17628, 17629, -1, 17618, 17627, 17619, -1, 15811, 17631, 15812, -1, 15812, 17631, 15806, -1, 17632, 17633, 17634, -1, 15806, 17631, 17635, -1, 16195, 17633, 17632, -1, 17621, 17631, 15811, -1, 17634, 17633, 17618, -1, 15816, 17636, 15815, -1, 17620, 17637, 17621, -1, 17624, 17637, 17620, -1, 17622, 17636, 15816, -1, 17626, 17638, 17622, -1, 17628, 17639, 17623, -1, 16207, 17639, 16205, -1, 17627, 17638, 17626, -1, 17623, 17639, 17624, -1, 16205, 17639, 17628, -1, 17635, 17640, 17641, -1, 16196, 17642, 16195, -1, 16195, 17642, 17633, -1, 17633, 17642, 17618, -1, 17621, 17640, 17631, -1, 17618, 17642, 17627, -1, 17637, 17640, 17621, -1, 17631, 17640, 17635, -1, 15815, 17643, 15814, -1, 16194, 16195, 17632, -1, 17624, 17644, 17637, -1, 16209, 17644, 16207, -1, 17639, 17644, 17624, -1, 17636, 17643, 15815, -1, 16207, 17644, 17639, -1, 17641, 17645, 17646, -1, 17646, 17645, 16180, -1, 16180, 17645, 16211, -1, 16211, 17645, 16209, -1, 17622, 17647, 17636, -1, 17640, 17645, 17641, -1, 17644, 17645, 17637, -1, 17637, 17645, 17640, -1, 16209, 17645, 17644, -1, 17638, 17647, 17622, -1, 17627, 17648, 17638, -1, 16197, 17648, 16196, -1, 16196, 17648, 17642, -1, 17642, 17648, 17627, -1, 15814, 17649, 15813, -1, 17643, 17649, 15814, -1, 17636, 17650, 17643, -1, 17647, 17650, 17636, -1, 16198, 17651, 16197, -1, 16197, 17651, 17648, -1, 17638, 17651, 17647, -1, 17648, 17651, 17638, -1, 15813, 17652, 15807, -1, 17649, 17652, 15813, -1, 17650, 17653, 17643, -1, 17643, 17653, 17649, -1, 17647, 17654, 17650, -1, 16199, 17654, 16198, -1, 16198, 17654, 17651, -1, 17651, 17654, 17647, -1, 15807, 17655, 15808, -1, 17652, 17655, 15807, -1, 17653, 17656, 17649, -1, 17649, 17656, 17652, -1, 17650, 17657, 17653, -1, 16199, 17657, 17654, -1, 16200, 17657, 16199, -1, 17654, 17657, 17650, -1, 15808, 17625, 15809, -1, 17655, 17625, 15808, -1, 17656, 17629, 17652, -1, 17652, 17629, 17655, -1, 17653, 17658, 17656, -1, 17657, 17658, 17653, -1, 16201, 17658, 16200, -1, 16200, 17658, 17657, -1, 15809, 17620, 15810, -1, 17625, 17620, 15809, -1, 15819, 17619, 15818, -1, 17617, 17619, 15819, -1, 17629, 17623, 17655, -1, 17655, 17623, 17625, -1, 15818, 17626, 15817, -1, 16203, 17630, 16201, -1, 17658, 17630, 17656, -1, 16201, 17630, 17658, -1, 17619, 17626, 15818, -1, 17656, 17630, 17629, -1, 15810, 17621, 15811, -1, 17634, 17618, 17617, -1, 16179, 17659, 16180, -1, 17646, 17659, 17641, -1, 16180, 17659, 17646, -1, 17641, 17660, 17635, -1, 17659, 17660, 17641, -1, 17635, 17661, 15806, -1, 17660, 17661, 17635, -1, 17661, 15820, 15806, -1, 16194, 17632, 11154, -1, 11154, 17632, 11152, -1, 11152, 17634, 11148, -1, 17632, 17634, 11152, -1, 11148, 17617, 11133, -1, 17634, 17617, 11148, -1, 11133, 15819, 11131, -1, 17617, 15819, 11133, -1, 16186, 17662, 16184, -1, 16184, 17662, 17663, -1, 17663, 17662, 17664, -1, 17664, 17662, 17665, -1, 15825, 17666, 15826, -1, 15826, 17666, 11136, -1, 11136, 17666, 11137, -1, 15820, 17661, 15822, -1, 17667, 17666, 15825, -1, 17668, 17669, 17667, -1, 17670, 17669, 17668, -1, 16188, 17671, 16186, -1, 16186, 17671, 17662, -1, 17665, 17671, 17670, -1, 17662, 17671, 17665, -1, 11137, 17672, 11159, -1, 17666, 17672, 11137, -1, 17667, 17672, 17666, -1, 17669, 17672, 17667, -1, 16190, 17673, 16188, -1, 16188, 17673, 17671, -1, 17670, 17673, 17669, -1, 17671, 17673, 17670, -1, 16193, 17674, 16190, -1, 11159, 17674, 11167, -1, 16190, 17674, 17673, -1, 11167, 17674, 16193, -1, 17672, 17674, 11159, -1, 17669, 17674, 17672, -1, 17673, 17674, 17669, -1, 16193, 11166, 11167, -1, 17660, 17675, 17661, -1, 17661, 17675, 15822, -1, 15822, 17676, 15821, -1, 17675, 17676, 15822, -1, 17659, 17677, 17660, -1, 17660, 17677, 17675, -1, 15821, 17678, 15823, -1, 17676, 17678, 15821, -1, 17677, 17664, 17675, -1, 17675, 17664, 17676, -1, 16182, 17679, 16179, -1, 16179, 17679, 17659, -1, 17659, 17679, 17677, -1, 15823, 17668, 15824, -1, 17678, 17668, 15823, -1, 17664, 17665, 17676, -1, 17676, 17665, 17678, -1, 16184, 17663, 16182, -1, 17679, 17663, 17677, -1, 16182, 17663, 17679, -1, 17677, 17663, 17664, -1, 15824, 17667, 15825, -1, 17668, 17667, 15824, -1, 17678, 17670, 17668, -1, 17665, 17670, 17678, -1, 16275, 16277, 17680, -1, 17680, 17681, 17682, -1, 16277, 17681, 17680, -1, 17682, 17683, 17684, -1, 17681, 17683, 17682, -1, 17684, 17685, 15746, -1, 17683, 17685, 17684, -1, 17685, 15757, 15746, -1, 17685, 15758, 15757, -1, 16277, 16279, 17681, -1, 16282, 11092, 11077, -1, 17683, 17686, 17685, -1, 15758, 17686, 15759, -1, 17685, 17686, 15758, -1, 17681, 17687, 17683, -1, 17683, 17687, 17686, -1, 15759, 17688, 11123, -1, 11123, 17688, 11122, -1, 17686, 17688, 15759, -1, 17681, 17689, 17687, -1, 16279, 17689, 17681, -1, 11122, 17690, 11078, -1, 17687, 17690, 17686, -1, 17686, 17690, 17688, -1, 17688, 17690, 11122, -1, 16282, 17691, 16279, -1, 11078, 17691, 11077, -1, 17687, 17691, 17690, -1, 16279, 17691, 17689, -1, 17689, 17691, 17687, -1, 17690, 17691, 11078, -1, 11077, 17691, 16282, -1, 17692, 17693, 17694, -1, 17695, 17693, 17692, -1, 17696, 17697, 15748, -1, 16269, 17698, 16267, -1, 16267, 17698, 17699, -1, 17700, 17701, 17702, -1, 17699, 17698, 17703, -1, 17703, 17698, 17695, -1, 15755, 17704, 15756, -1, 17702, 17701, 17696, -1, 17705, 17704, 15755, -1, 15749, 17706, 15743, -1, 15756, 17704, 17684, -1, 17697, 17706, 15749, -1, 17693, 17707, 17694, -1, 17694, 17707, 17705, -1, 17696, 17708, 17697, -1, 16271, 17709, 16269, -1, 17695, 17709, 17693, -1, 17701, 17708, 17696, -1, 16269, 17709, 17698, -1, 17698, 17709, 17695, -1, 16254, 17710, 16253, -1, 17711, 17710, 17700, -1, 17705, 17712, 17704, -1, 17700, 17710, 17701, -1, 16253, 17710, 17711, -1, 17684, 17712, 17682, -1, 17707, 17712, 17705, -1, 15743, 17713, 15744, -1, 17704, 17712, 17684, -1, 16273, 17714, 16271, -1, 16271, 17714, 17709, -1, 17693, 17714, 17707, -1, 17706, 17713, 15743, -1, 17709, 17714, 17693, -1, 16275, 17715, 16273, -1, 17697, 17716, 17706, -1, 17680, 17715, 16275, -1, 17682, 17715, 17680, -1, 17708, 17716, 17697, -1, 16252, 16253, 17711, -1, 17712, 17715, 17682, -1, 17707, 17715, 17712, -1, 17714, 17715, 17707, -1, 16255, 17717, 16254, -1, 16273, 17715, 17714, -1, 17701, 17717, 17708, -1, 16254, 17717, 17710, -1, 17710, 17717, 17701, -1, 15744, 17718, 15745, -1, 17713, 17718, 15744, -1, 17706, 17719, 17713, -1, 17716, 17719, 17706, -1, 16257, 17720, 16255, -1, 17717, 17720, 17708, -1, 17708, 17720, 17716, -1, 16255, 17720, 17717, -1, 15745, 17721, 15750, -1, 17718, 17721, 15745, -1, 17713, 17722, 17718, -1, 17719, 17722, 17713, -1, 16259, 17723, 16257, -1, 17716, 17723, 17719, -1, 17720, 17723, 17716, -1, 16257, 17723, 17720, -1, 15750, 17724, 15751, -1, 17721, 17724, 15750, -1, 17722, 17725, 17718, -1, 17718, 17725, 17721, -1, 17719, 17726, 17722, -1, 16261, 17726, 16259, -1, 17723, 17726, 17719, -1, 16259, 17726, 17723, -1, 15751, 17727, 15752, -1, 17724, 17727, 15751, -1, 17721, 17728, 17724, -1, 17725, 17728, 17721, -1, 16263, 17729, 16261, -1, 17722, 17729, 17725, -1, 17726, 17729, 17722, -1, 16261, 17729, 17726, -1, 17727, 17692, 15752, -1, 15752, 17692, 15753, -1, 15756, 17684, 15746, -1, 17728, 17703, 17724, -1, 17724, 17703, 17727, -1, 16265, 17730, 16263, -1, 16263, 17730, 17729, -1, 17725, 17730, 17728, -1, 17729, 17730, 17725, -1, 15753, 17694, 15754, -1, 17692, 17694, 15753, -1, 17703, 17695, 17727, -1, 17727, 17695, 17692, -1, 16267, 17699, 16265, -1, 16265, 17699, 17730, -1, 17728, 17699, 17703, -1, 17730, 17699, 17728, -1, 17694, 17705, 15754, -1, 17702, 17696, 15747, -1, 15754, 17705, 15755, -1, 15747, 17696, 15748, -1, 15748, 17697, 15749, -1, 16252, 17711, 11130, -1, 11130, 17711, 11129, -1, 11129, 17700, 11121, -1, 17711, 17700, 11129, -1, 11121, 17702, 11111, -1, 17700, 17702, 11121, -1, 11111, 15747, 11112, -1, 17702, 15747, 11111, -1, 11053, 11052, 12686, -1, 12686, 11052, 17731, -1, 17731, 11066, 17732, -1, 11052, 11066, 17731, -1, 17732, 11067, 17733, -1, 17733, 11067, 12077, -1, 11066, 11067, 17732, -1, 11067, 11069, 12077, -1, 17734, 17735, 17736, -1, 12069, 17735, 12070, -1, 17737, 17735, 17734, -1, 17738, 17739, 12684, -1, 12070, 17735, 17737, -1, 12665, 17740, 12663, -1, 17733, 17741, 17732, -1, 17742, 17740, 12665, -1, 17732, 17741, 17738, -1, 12681, 17743, 12679, -1, 17744, 17745, 17742, -1, 17746, 17745, 17744, -1, 17739, 17743, 12681, -1, 17738, 17747, 17739, -1, 12068, 17748, 12069, -1, 17736, 17748, 17746, -1, 17735, 17748, 17736, -1, 12069, 17748, 17735, -1, 17741, 17747, 17738, -1, 12663, 17749, 15708, -1, 12076, 17750, 12077, -1, 12077, 17750, 17733, -1, 17733, 17750, 17741, -1, 17740, 17749, 12663, -1, 12679, 17751, 12677, -1, 17742, 17752, 17740, -1, 17745, 17752, 17742, -1, 17743, 17751, 12679, -1, 12067, 17753, 12068, -1, 17746, 17753, 17745, -1, 17747, 17754, 17739, -1, 12068, 17753, 17748, -1, 17739, 17754, 17743, -1, 17748, 17753, 17746, -1, 17749, 17755, 15708, -1, 15708, 17755, 15706, -1, 12075, 17756, 12076, -1, 12076, 17756, 17750, -1, 17750, 17756, 17741, -1, 15706, 17755, 17757, -1, 17741, 17756, 17747, -1, 12677, 17758, 12675, -1, 17740, 17759, 17749, -1, 17752, 17759, 17740, -1, 17751, 17758, 12677, -1, 17745, 17760, 17752, -1, 17743, 17761, 17751, -1, 12066, 17760, 12067, -1, 12067, 17760, 17753, -1, 17753, 17760, 17745, -1, 17754, 17761, 17743, -1, 17757, 17762, 17763, -1, 17749, 17762, 17755, -1, 12074, 17764, 12075, -1, 17755, 17762, 17757, -1, 17756, 17764, 17747, -1, 17759, 17762, 17749, -1, 12066, 17765, 17760, -1, 17747, 17764, 17754, -1, 12075, 17764, 17756, -1, 12675, 17766, 12673, -1, 16281, 17765, 12066, -1, 17760, 17765, 17752, -1, 17752, 17765, 17759, -1, 16281, 17767, 17765, -1, 17758, 17766, 12675, -1, 17768, 17767, 16280, -1, 17763, 17767, 17768, -1, 16280, 17767, 16281, -1, 17751, 17769, 17758, -1, 17762, 17767, 17763, -1, 17759, 17767, 17762, -1, 17765, 17767, 17759, -1, 17761, 17769, 17751, -1, 12073, 17770, 12074, -1, 12074, 17770, 17764, -1, 17764, 17770, 17754, -1, 17754, 17770, 17761, -1, 12673, 17771, 12671, -1, 17766, 17771, 12673, -1, 17758, 17772, 17766, -1, 17769, 17772, 17758, -1, 12072, 17773, 12073, -1, 17761, 17773, 17769, -1, 17770, 17773, 17761, -1, 12073, 17773, 17770, -1, 12671, 17774, 12669, -1, 17771, 17774, 12671, -1, 17772, 17734, 17766, -1, 17766, 17734, 17771, -1, 17769, 17775, 17772, -1, 15706, 17757, 15705, -1, 12071, 17775, 12072, -1, 12072, 17775, 17773, -1, 17773, 17775, 17769, -1, 12669, 17744, 12667, -1, 17774, 17744, 12669, -1, 17734, 17736, 17771, -1, 17771, 17736, 17774, -1, 17772, 17737, 17734, -1, 12070, 17737, 12071, -1, 17775, 17737, 17772, -1, 12071, 17737, 17775, -1, 12667, 17742, 12665, -1, 16280, 16278, 17768, -1, 17744, 17742, 12667, -1, 12686, 17738, 12684, -1, 17731, 17738, 12686, -1, 17774, 17746, 17744, -1, 17732, 17738, 17731, -1, 17736, 17746, 17774, -1, 12684, 17739, 12681, -1, 15734, 17776, 15731, -1, 17777, 17776, 15734, -1, 15711, 17778, 15738, -1, 17779, 17780, 17781, -1, 17781, 17780, 17777, -1, 16272, 17782, 16274, -1, 17783, 17782, 17784, -1, 17784, 17782, 17779, -1, 16274, 17782, 17783, -1, 15731, 17785, 15729, -1, 17776, 17785, 15731, -1, 17780, 17786, 17777, -1, 17777, 17786, 17776, -1, 16270, 17787, 16272, -1, 16272, 17787, 17782, -1, 17779, 17787, 17780, -1, 17782, 17787, 17779, -1, 16276, 16274, 17788, -1, 15729, 17789, 15727, -1, 17785, 17789, 15729, -1, 17776, 17790, 17785, -1, 17786, 17790, 17776, -1, 16268, 17791, 16270, -1, 16270, 17791, 17787, -1, 17780, 17791, 17786, -1, 17787, 17791, 17780, -1, 15727, 17792, 15725, -1, 17789, 17792, 15727, -1, 17785, 17793, 17789, -1, 17790, 17793, 17785, -1, 17791, 17794, 17786, -1, 16266, 17794, 16268, -1, 16268, 17794, 17791, -1, 17786, 17794, 17790, -1, 15725, 17795, 15723, -1, 17792, 17795, 15725, -1, 17789, 17796, 17792, -1, 17793, 17796, 17789, -1, 16264, 17797, 16266, -1, 17790, 17797, 17793, -1, 17794, 17797, 17790, -1, 16266, 17797, 17794, -1, 15723, 17798, 15721, -1, 17795, 17798, 15723, -1, 17792, 17799, 17795, -1, 17796, 17799, 17792, -1, 16262, 17800, 16264, -1, 17793, 17800, 17796, -1, 16264, 17800, 17797, -1, 17797, 17800, 17793, -1, 15721, 17801, 15718, -1, 15718, 17801, 11059, -1, 11059, 17801, 11057, -1, 17798, 17801, 15721, -1, 17795, 17802, 17798, -1, 17799, 17802, 17795, -1, 17778, 17803, 15738, -1, 16260, 17804, 16262, -1, 17796, 17804, 17799, -1, 15738, 17781, 15736, -1, 17800, 17804, 17796, -1, 16262, 17804, 17800, -1, 17803, 17781, 15738, -1, 17802, 17805, 17798, -1, 11057, 17805, 11061, -1, 17801, 17805, 11057, -1, 17798, 17805, 17801, -1, 17806, 17784, 17778, -1, 16258, 17807, 16260, -1, 16260, 17807, 17804, -1, 17778, 17784, 17803, -1, 17804, 17807, 17799, -1, 15736, 17777, 15734, -1, 17799, 17807, 17802, -1, 11054, 17808, 16256, -1, 16256, 17808, 16258, -1, 17781, 17777, 15736, -1, 16258, 17808, 17807, -1, 11061, 17808, 11056, -1, 11056, 17808, 11054, -1, 17802, 17808, 17805, -1, 17807, 17808, 17802, -1, 17805, 17808, 11061, -1, 17803, 17779, 17781, -1, 17784, 17779, 17803, -1, 17788, 17783, 17806, -1, 16274, 17783, 17788, -1, 17806, 17783, 17784, -1, 15711, 15705, 17778, -1, 17778, 17757, 17806, -1, 15705, 17757, 17778, -1, 17806, 17763, 17788, -1, 17757, 17763, 17806, -1, 17788, 17768, 16276, -1, 17763, 17768, 17788, -1, 17768, 16278, 16276, -1, 16047, 12199, 12201, -1, 16047, 16045, 12199, -1, 16045, 12197, 12199, -1, 16045, 16046, 12197, -1, 12197, 16068, 12195, -1, 16046, 16068, 12197, -1, 12195, 16067, 12193, -1, 16068, 16067, 12195, -1, 12193, 16072, 12191, -1, 16067, 16072, 12193, -1, 12191, 16075, 12189, -1, 16072, 16075, 12191, -1, 12189, 11027, 11029, -1, 16075, 11027, 12189, -1, 16038, 16102, 16039, -1, 16038, 16035, 16102, -1, 16035, 16100, 16102, -1, 16035, 16037, 16100, -1, 16100, 16083, 16098, -1, 16037, 16083, 16100, -1, 16098, 16082, 16096, -1, 16083, 16082, 16098, -1, 16096, 16081, 16094, -1, 16082, 16081, 16096, -1, 16094, 16078, 16092, -1, 16081, 16078, 16094, -1, 16092, 16076, 16090, -1, 16078, 16076, 16092, -1, 16090, 16073, 16088, -1, 16076, 16073, 16090, -1, 16088, 16065, 16086, -1, 16073, 16065, 16088, -1, 16086, 16080, 16084, -1, 16065, 16080, 16086, -1, 16084, 16079, 12246, -1, 16080, 16079, 16084, -1, 12246, 16077, 12244, -1, 16079, 16077, 12246, -1, 12244, 16074, 12242, -1, 16077, 16074, 12244, -1, 12242, 16071, 12240, -1, 16074, 16071, 12242, -1, 12240, 16066, 12238, -1, 16071, 16066, 12240, -1, 16066, 12236, 12238, -1, 16066, 16051, 12236, -1, 16051, 16054, 12236, -1, 16054, 12234, 12236, -1, 16054, 16053, 12234, -1, 16053, 12230, 12234, -1, 16058, 16124, 16059, -1, 16058, 16055, 16124, -1, 16055, 16122, 16124, -1, 16122, 16057, 10993, -1, 16055, 16057, 16122, -1, 16057, 16070, 10993, -1, 16070, 16069, 10993, -1, 16069, 10991, 10993, -1 - ] - } - } - ] - } - ] - name "wheel_respondable_fl" - contactMaterial "wheel" - boundingObject Transform { - rotation 1 0 0 1.57 - children [ - Cylinder { - height 0.149 - radius 0.165 - } - ] - } - physics Physics { - mass 3 - } - } - } - ] - } - DEF TR_JOINT_RR Transform { - translation 0.324 0 -0.292 - rotation 1 0 0 0 - children [ - DEF JOINT_RR HingeJoint { - jointParameters HingeJointParameters { - axis 0 0 1 - suspensionSpringConstant 6000 - suspensionDampingConstant 150 - suspensionAxis 0 1 0 - } - device [ - RotationalMotor { - name "motor_rr" - controlPID 20 5 0 - maxTorque 500 - } - ] - endPoint DEF WHEEL_RR Solid { - rotation 0 0 1 0 - children [ - USE RIGHT_WHEEL_SHAPE - ] - name "wheel_respondable_rr" - contactMaterial "wheel" - boundingObject Transform { - rotation 1 0 0 1.57 - children [ - Cylinder { - height 0.149 - radius 0.165 - } - ] - } - physics Physics { - mass 3 - } - } - } - ] - } - DEF TR_JOINT_RL Transform { - translation 0.324 0 0.292 - rotation 1 0 0 0 - children [ - DEF JOINT_RL HingeJoint { - jointParameters HingeJointParameters { - axis 0 0 1 - suspensionSpringConstant 6000 - suspensionDampingConstant 150 - suspensionAxis 0 1 0 - } - device [ - RotationalMotor { - name "motor_rl" - controlPID 20 5 0 - maxTorque 500 - } - ] - endPoint Solid { - rotation 0 0 1 0 - children [ - USE LEFT_WHEEL_SHAPE - ] - name "wheel_respondable_rl" - contactMaterial "wheel" - boundingObject Transform { - rotation 1 0 0 1.57 - children [ - Cylinder { - height 0.149 - radius 0.165 - } - ] - } - physics Physics { - mass 3 - } - } - } - ] - } - DEF BODY_SHAPE Group { - children [ - DEF main_body Transform { - rotation 0 1 0 3.14 - children [ - DEF main_body_shape Shape { - appearance Appearance { - material Material { - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.21575078 0.15644756 -0.062790677, -0.21613365 0.15644753 -0.062744334, -0.2157508 0.15544762 -0.062790677, -0.2161337 0.1554476 -0.062744334, -0.21649432 0.15644753 -0.062607601, -0.21649437 0.1554476 -0.062607542, -0.2168119 0.15644756 -0.062388346, -0.21681175 0.15544748 -0.062388405, -0.21706747 0.15644741 -0.062099651, -0.21706752 0.15544748 -0.06209971, -0.21724673 0.15644741 -0.061758086, -0.21724682 0.15544754 -0.061758235, -0.21733899 0.15644732 -0.06138356, -0.21733902 0.15544742 -0.06138365, -0.21733902 0.15644738 -0.060997918, -0.21733908 0.15544742 -0.060997799, -0.21724676 0.15644741 -0.060623243, -0.21724679 0.15544742 -0.060623392, -0.21706751 0.15644731 -0.060281947, -0.21706748 0.15544732 -0.060281947, -0.21681182 0.15644732 -0.059993044, -0.21681175 0.15544733 -0.059993044, -0.21649432 0.15644729 -0.059773877, -0.21649426 0.15544735 -0.059774026, -0.2161337 0.15644741 -0.059636995, -0.21613362 0.15544733 -0.059637263, -0.21575086 0.15644735 -0.059590712, -0.21575066 0.1554473 -0.059590712, -0.2157508 0.15644543 -0.024390712, -0.21613371 0.15644541 -0.024344161, -0.21575084 0.15544541 -0.024390712, -0.21613361 0.15544537 -0.024344161, -0.21649434 0.15644537 -0.024207458, -0.21649425 0.15544528 -0.024207458, -0.21681184 0.15644538 -0.023988381, -0.21681176 0.15544528 -0.023988411, -0.21706755 0.15644529 -0.023699597, -0.21706742 0.15544531 -0.023699597, -0.21724677 0.15644532 -0.023358002, -0.21724676 0.15544534 -0.023358181, -0.21733907 0.15644524 -0.022983566, -0.21733908 0.15544534 -0.022983655, -0.21733907 0.15644524 -0.022597924, -0.21733908 0.15544534 -0.022597775, -0.21724682 0.15644532 -0.022223279, -0.21724677 0.15544531 -0.022223487, -0.21706754 0.15644518 -0.021881774, -0.21706755 0.15544522 -0.021881953, -0.2168119 0.15644526 -0.021593019, -0.21681182 0.15544522 -0.021593019, -0.21649434 0.15644524 -0.021374062, -0.21649434 0.15544522 -0.021374062, -0.21613371 0.15644521 -0.02123709, -0.21613364 0.15544522 -0.02123709, -0.21575075 0.15644515 -0.021190718, -0.21575074 0.15544522 -0.021190718, -0.19875078 0.15644479 -0.012090638, -0.19925331 0.15644477 -0.012029603, -0.19875076 0.15544486 -0.012090638, -0.19925326 0.15544483 -0.012029871, -0.19972675 0.15644489 -0.011850134, -0.19972672 0.15544482 -0.011850134, -0.20014326 0.15644477 -0.011562601, -0.20014332 0.15544479 -0.01156278, -0.20047906 0.15644471 -0.011183456, -0.20047911 0.15544482 -0.011183605, -0.20071428 0.15644471 -0.010735318, -0.20071426 0.15544468 -0.010735497, -0.20083544 0.15644464 -0.010243848, -0.20083544 0.15544468 -0.010243848, -0.20083544 0.15644464 -0.0097374767, -0.20083553 0.15544471 -0.0097375661, -0.20071431 0.15644459 -0.0092460364, -0.20071419 0.15544458 -0.0092460364, -0.20047905 0.15644458 -0.0087977499, -0.20047899 0.15544458 -0.0087977499, -0.20014326 0.15644458 -0.0084187835, -0.20014332 0.15544461 -0.008418873, -0.19972673 0.15644462 -0.0081313103, -0.19972669 0.15544456 -0.0081313998, -0.19925332 0.15644453 -0.0079516023, -0.19925331 0.15544455 -0.0079517812, -0.19875073 0.15644453 -0.0078906864, -0.19875069 0.15544453 -0.0078907758, -0.19875072 0.15644366 0.0079094023, -0.19925325 0.15644361 0.007970348, -0.19875072 0.15544361 0.0079093128, -0.19925325 0.15544359 0.007970348, -0.19972675 0.15644364 0.0081498772, -0.19972672 0.15544365 0.0081498772, -0.20014332 0.15644367 0.0084374994, -0.20014332 0.15544365 0.00843741, -0.20047902 0.15644358 0.0088163763, -0.20047906 0.15544368 0.0088163763, -0.20071432 0.15644358 0.0092648417, -0.20071419 0.15544356 0.0092646927, -0.20083548 0.15644361 0.0097561926, -0.20083548 0.1554435 0.0097561032, -0.20083553 0.15644358 0.010262474, -0.20083551 0.15544358 0.010262474, -0.20071428 0.15644349 0.010753974, -0.20071426 0.15544346 0.010753974, -0.20047909 0.15644351 0.011202231, -0.20047893 0.15544344 0.011202231, -0.20014334 0.15644346 0.011581257, -0.20014338 0.15544353 0.011581168, -0.19972675 0.15644346 0.01186879, -0.19972667 0.1554434 0.0118687, -0.19925331 0.15644334 0.01204823, -0.19925326 0.1554434 0.012048379, -0.19875081 0.15644343 0.012109354, -0.19875075 0.15544344 0.012109265, -0.37875095 0.15644249 0.0079094023, -0.37925336 0.15644246 0.0079704374, -0.37875074 0.15544251 0.0079094023, -0.37925342 0.15544255 0.007970348, -0.37972668 0.15644248 0.0081498772, -0.37972674 0.15544251 0.0081497282, -0.38014337 0.15644243 0.0084374994, -0.38014337 0.15544245 0.00843741, -0.38047919 0.15644245 0.0088163763, -0.38047913 0.15544245 0.0088163763, -0.38071439 0.15644239 0.0092646927, -0.38071445 0.15544248 0.0092646927, -0.3808355 0.15644234 0.0097561926, -0.38083556 0.15544242 0.0097561926, -0.3808355 0.15644234 0.010262474, -0.38083556 0.15544242 0.010262325, -0.38071445 0.15644236 0.010753974, -0.38071439 0.15544236 0.010753885, -0.38047913 0.15644233 0.011202231, -0.38047913 0.15544237 0.011202231, -0.38014337 0.15644234 0.011581168, -0.38014337 0.15544236 0.011581168, -0.37972674 0.15644224 0.0118687, -0.3797268 0.15544243 0.01186879, -0.37925342 0.15644227 0.012048379, -0.37925348 0.1554423 0.01204823, -0.37875095 0.15644228 0.012109354, -0.37875089 0.15544233 0.012109265, -0.37875077 0.15644364 -0.012090638, -0.37925348 0.15644369 -0.012029603, -0.37875089 0.15544373 -0.012090638, -0.37925351 0.1554437 -0.012029752, -0.3797268 0.15644366 -0.011849985, -0.37972674 0.15544362 -0.011850223, -0.38014337 0.1564436 -0.011562601, -0.38014337 0.15544373 -0.011562601, -0.38047919 0.15644358 -0.011183605, -0.38047907 0.1554435 -0.011183724, -0.38071439 0.15644352 -0.010735318, -0.38071439 0.15544358 -0.010735378, -0.38083556 0.15644352 -0.010243848, -0.38083556 0.15544359 -0.010243848, -0.3808355 0.15644354 -0.0097375661, -0.38083556 0.1554435 -0.0097375661, -0.38071439 0.15644345 -0.0092459768, -0.38071439 0.15544342 -0.0092461258, -0.38047907 0.15644339 -0.0087977499, -0.38047913 0.15544343 -0.0087977499, -0.3801434 0.15644342 -0.008418873, -0.38014337 0.15544346 -0.008419022, -0.37972668 0.1564434 -0.0081312507, -0.37972674 0.15544344 -0.0081313103, -0.37925354 0.15644349 -0.0079516023, -0.37925348 0.15544346 -0.0079516023, -0.37875095 0.15644343 -0.0078907758, -0.37875095 0.15544346 -0.0078906864, -0.2597509 0.15644552 -0.029590592, -0.26162368 0.15644538 -0.029406175, -0.2597509 0.15544546 -0.029590592, -0.26162362 0.15544537 -0.029406324, -0.26342458 0.15644538 -0.028859958, -0.26342449 0.15544535 -0.028859958, -0.2650843 0.15644521 -0.027972922, -0.26508421 0.15544525 -0.027972922, -0.26653892 0.15644515 -0.026778921, -0.26653904 0.15544528 -0.026778921, -0.26773292 0.15644509 -0.02532424, -0.26773292 0.15544513 -0.02532424, -0.2686201 0.15644503 -0.02366434, -0.26862004 0.15544499 -0.023664609, -0.26916629 0.15644488 -0.021863475, -0.26916635 0.15544489 -0.021863714, -0.2693508 0.15644476 -0.019990638, -0.26935074 0.15544477 -0.019990757, -0.26916629 0.15644467 -0.0181178, -0.26916629 0.15544468 -0.0181178, -0.26862004 0.15644461 -0.016316906, -0.26862004 0.15544465 -0.016316876, -0.26773292 0.15644449 -0.014657155, -0.26773286 0.1554445 -0.014657363, -0.26653901 0.15644436 -0.013202533, -0.26653892 0.15544435 -0.013202533, -0.26508427 0.15644437 -0.012008622, -0.26508427 0.15544438 -0.012008622, -0.26342452 0.15644434 -0.011121407, -0.26342452 0.15544429 -0.011121407, -0.26162365 0.15644431 -0.01057516, -0.26162368 0.15544434 -0.01057516, -0.25975081 0.15644431 -0.010390654, -0.25975081 0.15544429 -0.010390654, -0.27075085 0.15644327 0.0074093491, -0.27113372 0.15644324 0.0074559599, -0.27075076 0.15544331 0.0074092001, -0.27113378 0.15544334 0.0074558109, -0.27149433 0.15644324 0.007592544, -0.27149448 0.15544328 0.0075924546, -0.27181187 0.15644322 0.0078116804, -0.27181178 0.15544319 0.0078115314, -0.27206761 0.15644321 0.0081004053, -0.27206755 0.15544322 0.0081004053, -0.27224687 0.15644315 0.0084419399, -0.2722469 0.15544325 0.0084417313, -0.27233917 0.15644324 0.0088165849, -0.2723392 0.15544318 0.0088163763, -0.27233917 0.15644324 0.009202227, -0.27233914 0.15544313 0.009202078, -0.27224681 0.15644307 0.0095768124, -0.27224687 0.1554431 0.0095766634, -0.27206755 0.15644306 0.009918347, -0.27206752 0.15544306 0.0099181086, -0.27181175 0.15644306 0.010207012, -0.2718119 0.15544325 0.010206923, -0.27149427 0.15644297 0.010426059, -0.27149433 0.15544301 0.01042591, -0.27113378 0.15644315 0.010562733, -0.27113384 0.15544319 0.010562882, -0.27075079 0.15644303 0.010609254, -0.27075085 0.1554431 0.010609254, -0.24875087 0.15644345 0.0074093491, -0.24913369 0.1564434 0.0074558109, -0.24875085 0.15544337 0.0074092001, -0.24913378 0.15544349 0.0074557215, -0.24949437 0.15644333 0.007592544, -0.24949439 0.15544337 0.0075924546, -0.24981174 0.1564433 0.0078116804, -0.24981169 0.15544328 0.0078116804, -0.2500675 0.1564433 0.0081004947, -0.25006756 0.15544328 0.0081004053, -0.25024673 0.15644327 0.0084419399, -0.25024673 0.15544325 0.0084419399, -0.25033912 0.15644327 0.0088165849, -0.25033903 0.15544328 0.0088163763, -0.25033912 0.1564433 0.009202078, -0.25033909 0.15544331 0.009202227, -0.25024685 0.15644319 0.0095766634, -0.25024679 0.15544331 0.0095766634, -0.25006759 0.15644321 0.009918198, -0.25006756 0.15544322 0.009918198, -0.24981174 0.15644312 0.010207012, -0.24981175 0.15544313 0.010206923, -0.24949437 0.15644315 0.010426059, -0.24949433 0.15544319 0.010426059, -0.24913366 0.15644325 0.010562882, -0.24913369 0.15544322 0.010562733, -0.24875075 0.15644321 0.010609403, -0.24875078 0.15544316 0.010609254, -0.25975087 0.15644315 0.0099095255, -0.26172122 0.15644315 0.010103419, -0.25975078 0.15544319 0.0099091977, -0.26172113 0.15544313 0.01010333, -0.26361588 0.15644306 0.010678187, -0.26361588 0.1554431 0.010678187, -0.26536205 0.15644304 0.011611536, -0.26536205 0.15544301 0.011611477, -0.26689255 0.15644294 0.012867704, -0.26689255 0.15544298 0.012867555, -0.26814863 0.15644288 0.014398083, -0.26814866 0.15544292 0.014397934, -0.26908201 0.1564427 0.016144291, -0.26908195 0.15544271 0.016144142, -0.26965669 0.15644264 0.018038914, -0.26965672 0.15544271 0.018038973, -0.26985091 0.15644264 0.020009235, -0.26985079 0.15544254 0.020009235, -0.26965681 0.15644239 0.021979734, -0.26965666 0.15544246 0.021979734, -0.26908204 0.15644228 0.023874566, -0.26908195 0.15544224 0.023874357, -0.26814863 0.15644222 0.025620624, -0.26814857 0.15544219 0.025620595, -0.26689252 0.1564422 0.027151152, -0.26689264 0.15544216 0.027151152, -0.26536199 0.15644196 0.028407171, -0.26536205 0.15544201 0.028406993, -0.26361591 0.15644205 0.029340521, -0.26361591 0.15544206 0.029340491, -0.26172119 0.15644211 0.029915228, -0.26172113 0.155442 0.029915228, -0.2597509 0.15644215 0.030109301, -0.25975087 0.15544212 0.030109301, -0.24875081 0.15644214 0.029409453, -0.24913371 0.15644211 0.029455885, -0.24875078 0.15544212 0.029409304, -0.24913374 0.15544218 0.029455766, -0.24949433 0.15644212 0.029592618, -0.2494943 0.15544212 0.029592738, -0.24981175 0.15644208 0.029811785, -0.24981174 0.15544206 0.029811785, -0.25006756 0.15644205 0.03010045, -0.25006759 0.15544215 0.030100212, -0.25024685 0.15644208 0.030441865, -0.25024676 0.15544215 0.030441806, -0.25033918 0.15644212 0.030816332, -0.25033909 0.15544212 0.030816332, -0.25033918 0.15644212 0.031202123, -0.25033909 0.15544212 0.031202123, -0.25024673 0.15644199 0.031576768, -0.25024685 0.15544209 0.031576619, -0.25006753 0.1564419 0.031918213, -0.25006759 0.155442 0.031918213, -0.24981183 0.15644187 0.032207116, -0.24981174 0.15544188 0.032207027, -0.24949427 0.15644188 0.032426164, -0.24949437 0.15544197 0.032426104, -0.2491338 0.15644202 0.032562897, -0.24913363 0.15544191 0.032562837, -0.24875084 0.15644194 0.032609448, -0.24875079 0.15544191 0.032609448, -0.27075085 0.15644199 0.029409513, -0.27113366 0.15644196 0.029455885, -0.27075079 0.15544197 0.029409453, -0.27113366 0.155442 0.029455885, -0.27149436 0.15644196 0.029592738, -0.2714943 0.1554419 0.029592738, -0.27181187 0.156442 0.029811785, -0.27181178 0.155442 0.029811636, -0.27206758 0.15644191 0.030100212, -0.27206749 0.15544188 0.03010045, -0.27224687 0.15644199 0.030442044, -0.27224684 0.15544194 0.030442044, -0.27233917 0.15644202 0.03081654, -0.27233908 0.15544194 0.030816332, -0.27233914 0.15644191 0.031202182, -0.27233911 0.15544191 0.031201974, -0.27224687 0.15644191 0.031576768, -0.27224681 0.15544187 0.031576619, -0.27206758 0.15644178 0.031918213, -0.27206755 0.15544182 0.031918153, -0.27181187 0.15644179 0.032207176, -0.27181178 0.15544184 0.032207027, -0.27149436 0.15644176 0.032426164, -0.27149436 0.15544176 0.032426164, -0.27113372 0.15644181 0.032562897, -0.27113375 0.15544184 0.032562897, -0.2707507 0.15644176 0.032609448, -0.27075079 0.15544179 0.032609299, -0.36700085 0.15643893 0.070909396, -0.36762312 0.15643905 0.070984945, -0.36700085 0.15543905 0.070909247, -0.36762306 0.15543899 0.070984945, -0.36820915 0.15643904 0.071207151, -0.36820903 0.15543899 0.071207002, -0.36872503 0.15643898 0.07156311, -0.36872503 0.155439 0.07156311, -0.36914065 0.15643896 0.072032645, -0.36914071 0.15543905 0.072032407, -0.369432 0.15643895 0.072587356, -0.36943179 0.15543889 0.072587326, -0.36958185 0.15643887 0.073196009, -0.36958197 0.155439 0.0731958, -0.36958188 0.1564389 0.073822811, -0.36958197 0.15543899 0.073822603, -0.36943188 0.15643875 0.074431285, -0.36943182 0.15543871 0.074431285, -0.36914057 0.15643871 0.074986354, -0.36914065 0.15543877 0.074986354, -0.36872503 0.15643881 0.075455591, -0.36872503 0.15543878 0.075455591, -0.36820909 0.15643874 0.07581161, -0.36820909 0.15543868 0.075811461, -0.367623 0.15643865 0.076033875, -0.36762306 0.15543874 0.076033667, -0.36700085 0.15643871 0.076109573, -0.36700085 0.1554388 0.076109156, -0.21050073 0.15644832 -0.076090649, -0.21112294 0.15644829 -0.076015189, -0.21050082 0.15544833 -0.076090649, -0.211123 0.15544832 -0.076015189, -0.21170908 0.15644833 -0.075792894, -0.21170911 0.15544836 -0.075792894, -0.2122249 0.15644826 -0.075436786, -0.21222484 0.15544827 -0.075436965, -0.21264055 0.15644819 -0.074967667, -0.2126406 0.15544829 -0.074967846, -0.21293178 0.1564482 -0.074412689, -0.21293186 0.15544823 -0.074412778, -0.21308182 0.15644822 -0.073804095, -0.21308175 0.15544811 -0.073804095, -0.21308182 0.15644822 -0.073177263, -0.21308181 0.15544817 -0.073177323, -0.2129318 0.1564481 -0.07256864, -0.2129318 0.15544805 -0.072568849, -0.21264061 0.1564481 -0.072013751, -0.21264055 0.15544811 -0.072013751, -0.2122249 0.15644805 -0.071544543, -0.21222489 0.15544805 -0.071544573, -0.2117091 0.15644813 -0.071188584, -0.21170902 0.15544805 -0.071188584, -0.211123 0.15644801 -0.070966139, -0.21112294 0.15544802 -0.070966318, -0.21050081 0.15644807 -0.07089068, -0.21050076 0.15544806 -0.070890769, -0.21050082 0.15644005 0.070909396, -0.21112299 0.15643999 0.070985094, -0.21050082 0.15544008 0.070909247, -0.21112297 0.15544 0.070984796, -0.21170908 0.15643999 0.071207151, -0.21170893 0.15543994 0.071207151, -0.21222492 0.15644005 0.07156311, -0.21222486 0.15543997 0.07156311, -0.21264057 0.15643999 0.072032645, -0.21264055 0.15544 0.072032556, -0.2129318 0.15643996 0.072587356, -0.21293172 0.15543994 0.072587326, -0.21308182 0.15643993 0.0731958, -0.21308179 0.15543994 0.0731958, -0.21308188 0.15643996 0.073822811, -0.21308179 0.15543994 0.073822811, -0.21293178 0.15643978 0.074431285, -0.21293184 0.15543981 0.074431255, -0.21264055 0.15643977 0.074986205, -0.21264061 0.15543982 0.074986354, -0.21222486 0.15643972 0.075455591, -0.21222484 0.15543978 0.075455502, -0.21170913 0.15643983 0.075811759, -0.21170902 0.1554397 0.075811461, -0.21112293 0.15643969 0.076033875, -0.21112299 0.15543976 0.076033667, -0.21050076 0.15643978 0.076109365, -0.21050075 0.15543978 0.076109365, -0.36700085 0.15644728 -0.076090649, -0.36762312 0.15644735 -0.07601513, -0.36700088 0.15544739 -0.076090649, -0.367623 0.15544727 -0.07601513, -0.36820915 0.15644732 -0.075792745, -0.36820915 0.15544735 -0.075793013, -0.36872497 0.1564472 -0.075436696, -0.36872497 0.1554473 -0.075436965, -0.36914071 0.1564472 -0.074967667, -0.36914071 0.1554473 -0.074967667, -0.36943194 0.1564472 -0.074412689, -0.36943194 0.15544719 -0.074412689, -0.36958191 0.15644716 -0.073804095, -0.36958185 0.15544719 -0.073804334, -0.36958197 0.15644716 -0.073177263, -0.36958197 0.15544726 -0.073177323, -0.369432 0.15644716 -0.07256864, -0.36943194 0.15544719 -0.07256864, -0.36914065 0.15644713 -0.072013691, -0.36914068 0.15544713 -0.072013751, -0.36872497 0.15644708 -0.071544543, -0.36872503 0.15544713 -0.071544573, -0.36820921 0.15644708 -0.071188435, -0.36820915 0.15544713 -0.071188584, -0.36762312 0.15644708 -0.070966229, -0.36762312 0.15544708 -0.070966229, -0.36700085 0.15644711 -0.07089068, -0.36700091 0.15544708 -0.070890769, -0.18975072 0.15544826 -0.07299073, -0.18975079 0.15644006 0.073009446, -0.18975072 0.15544008 0.073009416, -0.18975081 0.15644826 -0.072990492, -0.38275081 0.15544736 -0.077990606, -0.19475074 0.15644853 -0.077990606, -0.19475071 0.15544851 -0.077990606, -0.38275084 0.1564474 -0.077990606, -0.38775083 0.15543884 0.073009506, -0.38775083 0.15644696 -0.07299073, -0.38775089 0.15544705 -0.07299079, -0.38775089 0.15643884 0.073009446, -0.19475076 0.15543978 0.078009382, -0.3827509 0.15643856 0.078009412, -0.38275084 0.15543853 0.078009382, -0.19475074 0.15643978 0.078009412, -0.26925477 0.15644193 0.030442253, -0.37702259 0.15644355 -0.011183724, -0.36527678 0.15644714 -0.071544513, -0.36579248 0.15644705 -0.071188435, -0.37678745 0.1564436 -0.010735318, -0.25015083 0.15644488 -0.019990638, -0.38586828 0.15643859 0.076918527, -0.38725576 0.15643869 0.075178877, -0.38666013 0.15643868 0.076126888, -0.25033537 0.15644503 -0.021863624, -0.38492021 0.1564386 0.077514157, -0.20806976 0.1564481 -0.07256864, -0.20791978 0.15644823 -0.073177263, -0.20791978 0.15644826 -0.073804095, -0.20806979 0.15644823 -0.074412689, -0.20836097 0.15644823 -0.074967727, -0.38762555 0.15643878 0.074121937, -0.20877667 0.15644832 -0.075436786, -0.20929243 0.15644826 -0.075792894, -0.20987861 0.15644835 -0.076015189, -0.38386339 0.15643853 0.077884093, -0.26943406 0.15644185 0.031918213, -0.26925474 0.15644199 0.031576946, -0.26916242 0.15644193 0.031202421, -0.214434 0.15644734 -0.060281947, -0.21425471 0.1564474 -0.060623303, -0.21416248 0.15644753 -0.060997799, -0.2087767 0.15644813 -0.071544543, -0.19824827 0.15644483 -0.012029603, -0.214434 0.15644529 -0.023699477, -0.20836097 0.15644813 -0.072013691, -0.19666608 0.15644473 -0.010243848, -0.19678728 0.15644474 -0.010735318, -0.19702254 0.15644474 -0.011183456, -0.19735824 0.15644485 -0.011562601, -0.19777487 0.15644479 -0.011850134, -0.1908416 0.15643989 0.076127037, -0.19024591 0.15643986 0.075178877, -0.19163327 0.15643983 0.076918527, -0.18987609 0.15644833 -0.074103341, -0.19363819 0.15644859 -0.077865437, -0.19024593 0.15644842 -0.075160131, -0.19258134 0.15643984 0.077514157, -0.1898762 0.15644006 0.074121937, -0.19363819 0.15643981 0.077883914, -0.19258134 0.15644857 -0.077495411, -0.19084167 0.1564485 -0.076108173, -0.19163333 0.15644848 -0.076899871, -0.36637864 0.15644732 -0.07601513, -0.20806979 0.15643999 0.072587326, -0.25088161 0.15644512 -0.02366434, -0.36637869 0.15643884 0.076033875, -0.19666612 0.15644354 0.010262474, -0.19666611 0.15644361 0.0097561926, -0.20836101 0.15643999 0.072032556, -0.19666615 0.15644473 -0.0097375661, -0.20877673 0.15644014 0.071563318, -0.20929252 0.15644 0.071207002, -0.27000728 0.15644181 0.032426223, -0.26968974 0.15644178 0.032207116, -0.25260898 0.15644298 0.012867555, -0.25176865 0.15644521 -0.025324091, -0.25135288 0.15644288 0.014397964, -0.25413957 0.15644313 0.011611685, -0.25296253 0.15644524 -0.026778921, -0.25588563 0.15644303 0.010678187, -0.2504195 0.15644273 0.01614435, -0.24836791 0.15644322 0.010562882, -0.36527678 0.15643886 0.075455591, -0.3648611 0.15643881 0.074986354, -0.36579254 0.1564388 0.07581161, -0.24800718 0.15644316 0.010426149, -0.25778031 0.15644315 0.010103419, -0.24984482 0.15644279 0.018038914, -0.2476898 0.15644325 0.010206923, -0.27036795 0.15644184 0.032562897, -0.24965082 0.1564427 0.020009413, -0.24743392 0.15644319 0.009918347, -0.21536784 0.15644516 -0.02123709, -0.3782483 0.15644225 0.012048379, -0.24725479 0.1564433 0.0095768124, -0.24725477 0.15644212 0.030442044, -0.36637864 0.15643901 0.070984945, -0.37777492 0.15644222 0.01186879, -0.36579248 0.15643895 0.071207151, -0.37735829 0.15644231 0.011581168, -0.19824822 0.15644369 0.007970348, -0.37702259 0.15644237 0.011202231, -0.36527678 0.15643902 0.07156311, -0.21500722 0.15644518 -0.021374002, -0.37678733 0.15644236 0.010753974, -0.19824819 0.15644458 -0.0079516023, -0.21468973 0.15644522 -0.021593019, -0.19777481 0.15644361 0.0081498772, -0.19777481 0.15644456 -0.0081312507, -0.21443401 0.15644522 -0.021881774, -0.19735821 0.15644465 -0.008418873, -0.25778031 0.15644202 0.029915228, -0.25588569 0.15644208 0.029340521, -0.19735818 0.15644363 0.0084374994, -0.21425471 0.15644531 -0.022223279, -0.27036801 0.15644333 0.0074558109, -0.19702257 0.15644465 -0.0087977499, -0.19678719 0.15644363 0.0092648417, -0.19702242 0.15644361 0.0088165849, -0.21416244 0.15644534 -0.022597775, -0.19678728 0.15644465 -0.0092460364, -0.21416244 0.15644534 -0.022983566, -0.27000722 0.15644315 0.007592544, -0.21425471 0.15644531 -0.023358151, -0.37666616 0.1564436 -0.010243848, -0.3782483 0.15644248 0.0079704374, -0.26968977 0.15644315 0.0078116804, -0.3782483 0.15644343 -0.0079516023, -0.37666616 0.15644242 0.010262474, -0.37666616 0.15644242 0.0097563416, -0.37777498 0.15644252 0.0081498772, -0.37777498 0.15644346 -0.0081313103, -0.25413957 0.15644212 0.028407171, -0.37735829 0.15644248 0.0084374994, -0.37735829 0.1564434 -0.008418873, -0.25787792 0.15644431 -0.01057516, -0.3648611 0.15644707 -0.072013691, -0.37702265 0.15644349 -0.0087976605, -0.2544173 0.15644529 -0.027972832, -0.3766661 0.15644346 -0.0097375661, -0.37702253 0.1564424 0.0088163763, -0.37678739 0.15644252 0.0092646927, -0.37678728 0.1564434 -0.0092459768, -0.25607705 0.15644436 -0.011121407, -0.36456981 0.15644711 -0.072568849, -0.27036795 0.15644319 0.010562882, -0.25607708 0.15644541 -0.028859958, -0.24836791 0.15644193 0.032562897, -0.36441985 0.15644729 -0.073177204, -0.24836791 0.15644336 0.0074557215, -0.25441727 0.1564444 -0.012008414, -0.25296256 0.15644442 -0.013202384, -0.25787795 0.15644547 -0.029406175, -0.2480073 0.15644337 0.007592544, -0.36441979 0.15644719 -0.073804095, -0.2153679 0.15644537 -0.024344161, -0.24768977 0.15644334 0.0078116804, -0.25176874 0.15644464 -0.014657125, -0.27000728 0.15644309 0.010426059, -0.24800727 0.15644197 0.032426164, -0.25088167 0.15644476 -0.016316906, -0.21536788 0.15644732 -0.059636995, -0.36456987 0.15644729 -0.074412778, -0.38666013 0.15644723 -0.076108173, -0.38492021 0.15644719 -0.07749556, -0.38586828 0.15644725 -0.076899871, -0.3872557 0.15644713 -0.075160131, -0.38386354 0.15644732 -0.077865437, -0.38762555 0.15644704 -0.074103341, -0.21468976 0.15644532 -0.023988262, -0.21500725 0.15644738 -0.059773877, -0.21500716 0.15644535 -0.024207309, -0.24768978 0.15644191 0.032207027, -0.36441976 0.15643895 0.073822603, -0.36441976 0.15643895 0.073196009, -0.21468976 0.15644737 -0.059993044, -0.26968983 0.15644309 0.010207012, -0.25260904 0.15644228 0.027151152, -0.36456981 0.15643895 0.072587356, -0.36456981 0.1564388 0.074431285, -0.3648611 0.15643898 0.072032407, -0.26943401 0.15644309 0.009918347, -0.24743399 0.15644196 0.031918213, -0.24716257 0.15644214 0.031202182, -0.24716257 0.15644214 0.030816481, -0.26925474 0.15644319 0.0095768124, -0.2472548 0.15644211 0.031576768, -0.20987859 0.15644005 0.070984945, -0.24716246 0.15644325 0.009202227, -0.21536791 0.15644753 -0.062744334, -0.24716257 0.15644342 0.0088165849, -0.21500725 0.15644754 -0.062607542, -0.19824827 0.15644346 0.012048379, -0.24725483 0.1564434 0.0084419399, -0.19777481 0.15644336 0.01186879, -0.21468979 0.15644754 -0.062388256, -0.19735819 0.15644346 0.011581257, -0.21443407 0.15644751 -0.062099651, -0.19702242 0.15644348 0.01120232, -0.19678728 0.15644358 0.010754123, -0.26916254 0.15644322 0.009202227, -0.26916251 0.15644324 0.0088165849, -0.2142548 0.1564476 -0.061758086, -0.20987852 0.15644802 -0.070966229, -0.251353 0.15644231 0.025620595, -0.24836789 0.15644209 0.029455885, -0.26925474 0.15644319 0.0084419399, -0.26943398 0.15644315 0.0081004053, -0.25041956 0.15644237 0.023874566, -0.21416253 0.15644757 -0.06138356, -0.20929255 0.15644811 -0.071188524, -0.3782483 0.1564437 -0.012029663, -0.24768978 0.15644209 0.029811785, -0.24800727 0.15644212 0.029592738, -0.3648611 0.15644728 -0.074967846, -0.20987861 0.15643983 0.076033875, -0.20929252 0.1564398 0.07581161, -0.20877664 0.15643983 0.075455591, -0.20836093 0.15643978 0.074986354, -0.2080697 0.15643981 0.074431285, -0.20791967 0.15643989 0.073822811, -0.20791979 0.15644 0.0731958, -0.37777498 0.1564437 -0.011849985, -0.24743406 0.15644342 0.0081004053, -0.24984485 0.15644255 0.021979734, -0.24743399 0.15644212 0.03010045, -0.36527684 0.1564474 -0.075436786, -0.36637858 0.15644699 -0.070966229, -0.37735841 0.1564437 -0.011562601, -0.36579254 0.15644732 -0.075792894, -0.25033522 0.15644482 -0.0181178, -0.26943403 0.15644194 0.03010045, -0.2696898 0.15644193 0.029811785, -0.27000722 0.15644193 0.029592738, -0.2703678 0.15644197 0.029455885, -0.26916254 0.15644202 0.03081654, -0.26925477 0.155442 0.030441865, -0.36527666 0.1554471 -0.071544573, -0.37702259 0.15544362 -0.011183605, -0.36579248 0.15544704 -0.071188584, -0.25015089 0.15544492 -0.019990638, -0.37678745 0.15544362 -0.010735497, -0.25033531 0.15544501 -0.021863624, -0.38492027 0.15543862 0.077514157, -0.38586828 0.15543866 0.076918676, -0.38666007 0.15543865 0.07612668, -0.38725582 0.15543874 0.075178877, -0.20806973 0.15544814 -0.072568849, -0.20791969 0.15544818 -0.073177323, -0.20791975 0.15544824 -0.073804095, -0.20806965 0.15544818 -0.074412778, -0.20836101 0.15544827 -0.074967846, -0.38762549 0.15543878 0.074121937, -0.20877667 0.15544827 -0.075436965, -0.2092925 0.15544838 -0.075792894, -0.20987859 0.15544838 -0.076015189, -0.38386348 0.1554386 0.077884093, -0.26943401 0.15544176 0.031918153, -0.26925474 0.15544188 0.031576619, -0.26916245 0.15544192 0.031202123, -0.21443394 0.15544739 -0.060281947, -0.21425478 0.1554475 -0.060623392, -0.21416247 0.15544744 -0.060997918, -0.19824824 0.15544485 -0.012029663, -0.21443397 0.15544532 -0.023699597, -0.20877664 0.15544814 -0.071544573, -0.20836098 0.15544814 -0.072013751, -0.19666608 0.15544476 -0.010243848, -0.19678722 0.15544474 -0.010735378, -0.19702242 0.15544473 -0.011183724, -0.19024593 0.15543999 0.075178728, -0.19084157 0.15543987 0.076126888, -0.19163327 0.15543982 0.076918527, -0.19735821 0.15544485 -0.011562601, -0.19777487 0.1554448 -0.011850312, -0.18987612 0.15544836 -0.0741034, -0.19363813 0.15544853 -0.077865437, -0.18987612 0.15544008 0.074121788, -0.19258131 0.15543982 0.077514127, -0.19363819 0.15543982 0.077883914, -0.19258131 0.15544856 -0.07749556, -0.19024588 0.15544839 -0.07516019, -0.19084166 0.15544848 -0.076108173, -0.19163328 0.1554485 -0.076899961, -0.20806979 0.15544003 0.072587326, -0.36637866 0.15544748 -0.076015189, -0.25088155 0.15544507 -0.023664489, -0.19666599 0.1554435 0.010262474, -0.19666609 0.15544361 0.0097560436, -0.19666608 0.15544476 -0.0097375661, -0.36637864 0.15543881 0.076033875, -0.20836104 0.15544005 0.072032407, -0.2087767 0.15544008 0.07156302, -0.20929243 0.15543993 0.071207002, -0.27000719 0.15544182 0.032426104, -0.26968974 0.15544175 0.032207027, -0.25176871 0.15544525 -0.02532424, -0.25260907 0.1554431 0.012867466, -0.25135291 0.15544298 0.014397845, -0.25413954 0.15544319 0.011611536, -0.25296253 0.15544531 -0.026778921, -0.25588566 0.15544313 0.010678187, -0.24836788 0.15544316 0.010562792, -0.25041962 0.15544286 0.016144142, -0.36527669 0.15543884 0.075455502, -0.3648611 0.15543884 0.074986205, -0.24800715 0.15544322 0.010426059, -0.36579254 0.15543875 0.075811461, -0.2577804 0.15544315 0.010103479, -0.24768969 0.15544313 0.010206923, -0.24984482 0.15544277 0.018038914, -0.27036789 0.15544185 0.032562897, -0.24743399 0.15544328 0.009918198, -0.24965078 0.15544268 0.020009205, -0.21536788 0.15544525 -0.02123709, -0.37824839 0.1554423 0.01204811, -0.24725471 0.1554433 0.0095764548, -0.24725477 0.15544216 0.030441865, -0.37777495 0.15544239 0.01186879, -0.36637864 0.15543911 0.070984945, -0.37735826 0.15544239 0.011581257, -0.36579248 0.15543893 0.071207151, -0.19824816 0.15544364 0.0079702288, -0.37702259 0.15544231 0.011202231, -0.36527669 0.15543902 0.07156302, -0.21500723 0.1554452 -0.021374062, -0.37678745 0.15544245 0.010753974, -0.19824822 0.15544459 -0.0079517812, -0.21468976 0.15544519 -0.021593228, -0.19777487 0.15544456 -0.0081313103, -0.19777487 0.1554437 0.0081497282, -0.21443401 0.15544523 -0.021881774, -0.19735822 0.15544462 -0.008419022, -0.25778031 0.15544203 0.029915139, -0.25588572 0.15544212 0.029340491, -0.19735827 0.15544373 0.00843741, -0.21425478 0.15544537 -0.022223487, -0.27036786 0.15544325 0.0074558109, -0.19702244 0.15544462 -0.0087979585, -0.19678731 0.1554437 0.0092646927, -0.1970225 0.1554437 0.0088163763, -0.21416241 0.15544534 -0.022597775, -0.19678722 0.15544464 -0.0092461258, -0.21416241 0.15544534 -0.022983566, -0.27000719 0.15544318 0.007592544, -0.21425468 0.15544532 -0.023358151, -0.37666616 0.15544361 -0.010243848, -0.37824842 0.15544255 0.007970348, -0.26968977 0.15544325 0.0078115314, -0.37824821 0.1554434 -0.0079517215, -0.37666616 0.15544239 0.010262474, -0.3766661 0.15544237 0.0097561032, -0.37777498 0.15544347 -0.0081313103, -0.37777492 0.15544249 0.0081498772, -0.25413954 0.15544218 0.028406993, -0.25787792 0.1554444 -0.01057528, -0.37735823 0.15544342 -0.008418873, -0.37735817 0.15544248 0.00843741, -0.36486104 0.15544702 -0.072013691, -0.37702248 0.15544339 -0.0087978691, -0.25441736 0.15544534 -0.027972832, -0.37666616 0.15544361 -0.0097375661, -0.37702259 0.15544248 0.0088163763, -0.37678728 0.15544347 -0.0092460364, -0.37678728 0.15544246 0.0092646927, -0.25607699 0.15544434 -0.011121407, -0.36456972 0.15544702 -0.072568849, -0.27036795 0.15544313 0.010562882, -0.25607699 0.15544537 -0.028859958, -0.24836791 0.15544197 0.032562837, -0.36441973 0.15544716 -0.073177204, -0.2544173 0.15544447 -0.012008622, -0.24836794 0.15544343 0.0074557215, -0.25787795 0.1554454 -0.029406324, -0.25296262 0.15544461 -0.013202533, -0.24800716 0.15544336 0.0075924546, -0.36441985 0.15544723 -0.073804095, -0.21536788 0.15544543 -0.024344161, -0.25176865 0.15544462 -0.014657274, -0.24768977 0.15544337 0.0078115314, -0.27000731 0.15544316 0.01042591, -0.24800718 0.15544195 0.032426164, -0.21536784 0.15544732 -0.059637263, -0.25088161 0.15544471 -0.016316906, -0.36456981 0.15544721 -0.074412778, -0.3849203 0.15544733 -0.07749556, -0.38666013 0.15544721 -0.076108173, -0.38586834 0.15544721 -0.076899871, -0.38386342 0.15544732 -0.077865437, -0.38762552 0.1554471 -0.074103341, -0.38725576 0.15544721 -0.075160131, -0.21500729 0.15544744 -0.059774026, -0.21468975 0.15544532 -0.023988381, -0.21500728 0.15544543 -0.024207458, -0.24768977 0.15544192 0.032207027, -0.36441976 0.15543893 0.073822603, -0.36441976 0.15543902 0.073196009, -0.21468976 0.15544733 -0.059993222, -0.26968974 0.15544307 0.010206923, -0.25260907 0.15544233 0.027151152, -0.36456972 0.15543893 0.072587356, -0.36456981 0.15543887 0.074431285, -0.36486095 0.15543893 0.072032556, -0.26943403 0.1554431 0.009918198, -0.24743393 0.155442 0.031918213, -0.2471624 0.15544206 0.031202182, -0.2471624 0.15544206 0.030816481, -0.26925477 0.15544313 0.0095764548, -0.24725473 0.1554421 0.031576768, -0.20987864 0.15544011 0.070984945, -0.24716245 0.15544337 0.009202227, -0.2153679 0.15544757 -0.062744334, -0.24716245 0.15544337 0.0088163763, -0.21500729 0.15544757 -0.062607542, -0.19824815 0.1554434 0.01204823, -0.24725479 0.15544343 0.0084419399, -0.19777483 0.1554434 0.0118687, -0.21468978 0.1554475 -0.062388405, -0.19735818 0.15544346 0.011581168, -0.19702239 0.15544346 0.011202231, -0.21443401 0.15544751 -0.06209971, -0.19678718 0.15544349 0.010753885, -0.26916254 0.15544322 0.009202227, -0.20987858 0.15544806 -0.070966229, -0.21425477 0.15544753 -0.061758146, -0.26916248 0.15544319 0.0088163763, -0.251353 0.15544239 0.025620624, -0.24836789 0.15544213 0.029455766, -0.26925477 0.15544313 0.0084419399, -0.26943398 0.15544316 0.0081004053, -0.25041962 0.15544245 0.023874536, -0.20929249 0.15544806 -0.071188584, -0.21416248 0.15544757 -0.06138356, -0.3782483 0.15544368 -0.012029752, -0.24768977 0.1554421 0.029811785, -0.24800716 0.15544218 0.029592738, -0.36486113 0.1554473 -0.074967846, -0.20987858 0.15543981 0.076033875, -0.20929249 0.15543972 0.075811461, -0.20877661 0.15543972 0.075455502, -0.20836093 0.15543976 0.074986205, -0.20806988 0.15543994 0.074431255, -0.20791973 0.15544005 0.073822603, -0.20791973 0.15544005 0.0731958, -0.37777498 0.15544365 -0.011850134, -0.24743405 0.15544334 0.0081004053, -0.24984482 0.15544257 0.021979704, -0.36527678 0.15544739 -0.075436965, -0.24743405 0.15544218 0.030100212, -0.36637864 0.1554471 -0.070966318, -0.37735835 0.15544368 -0.01156278, -0.36579266 0.15544742 -0.075793013, -0.25033522 0.1554448 -0.018117681, -0.26943406 0.15544204 0.030100212, -0.26968983 0.15544203 0.029811606, -0.27000725 0.155442 0.029592618, -0.27036786 0.15544203 0.029455885, -0.26916245 0.15544197 0.030816332, 0.19874941 0.15644732 -0.011690632, 0.19834253 0.15644732 -0.011641368, 0.19874938 0.15544733 -0.011690632, 0.19834256 0.15544736 -0.011641368, 0.19795933 0.15644732 -0.011495933, 0.19795939 0.1554473 -0.011496022, 0.19762212 0.15644729 -0.011263117, 0.19762212 0.1554473 -0.011263117, 0.19735029 0.15644726 -0.010956332, 0.19735034 0.15544727 -0.010956332, 0.19715984 0.15644723 -0.010593489, 0.1971599 0.15544729 -0.010593548, 0.19706181 0.15644725 -0.010195449, 0.19706185 0.15544726 -0.010195598, 0.19706178 0.15644723 -0.0097856969, 0.19706184 0.15544726 -0.0097859651, 0.19715989 0.15644716 -0.0093878359, 0.19715992 0.15544716 -0.0093878955, 0.19735034 0.15644716 -0.0090248436, 0.19735043 0.15544714 -0.0090250224, 0.19762208 0.15644714 -0.0087182075, 0.19762209 0.1554472 -0.0087182075, 0.19795938 0.15644714 -0.0084853619, 0.19795936 0.15544716 -0.0084853917, 0.19834258 0.15644714 -0.0083401352, 0.19834258 0.15544716 -0.0083401352, 0.19874938 0.15644714 -0.0082906336, 0.19874941 0.15544717 -0.0082907528, 0.19874936 0.15644625 0.0083093196, 0.19834259 0.15644619 0.0083588511, 0.19874944 0.15544617 0.0083093196, 0.19834262 0.15544617 0.0083587021, 0.19795945 0.15644614 0.0085041672, 0.19795938 0.1554462 0.0085041672, 0.19762203 0.15644619 0.0087368339, 0.19762212 0.15544614 0.0087368339, 0.19735026 0.15644619 0.0090437084, 0.19735032 0.15544617 0.0090437084, 0.19715992 0.15644617 0.0094065517, 0.19715983 0.15544623 0.0094065517, 0.19706185 0.15644605 0.0098044425, 0.19706178 0.15544613 0.0098043829, 0.19706178 0.15644607 0.010214224, 0.19706184 0.15544608 0.010214224, 0.19715983 0.1564461 0.010612264, 0.19715999 0.15544601 0.010612115, 0.19735037 0.15644607 0.010974988, 0.19735034 0.15544608 0.010974988, 0.19762211 0.15644605 0.011281833, 0.19762209 0.15544608 0.011281684, 0.19795938 0.15644602 0.011514649, 0.19795947 0.15544602 0.0115145, 0.19834249 0.15644601 0.011659876, 0.19834259 0.15544602 0.011659816, 0.19874948 0.1564461 0.011709347, 0.19874929 0.15544614 0.011709347, 0.37874946 0.15644735 0.0083093196, 0.37834266 0.15644735 0.0083588511, 0.37874952 0.15544733 0.00830926, 0.37834266 0.15544739 0.0083587021, 0.37795946 0.15644731 0.0085041672, 0.37795946 0.15544733 0.0085041672, 0.37762216 0.15644732 0.0087368339, 0.37762216 0.15544733 0.0087367445, 0.37735048 0.15644731 0.0090438277, 0.37735036 0.15544738 0.0090434998, 0.37715998 0.15644731 0.0094065517, 0.37715992 0.15544736 0.0094065517, 0.37706184 0.15644723 0.0098045915, 0.37706181 0.15544732 0.0098044425, 0.37706184 0.15644723 0.010214224, 0.37706187 0.15544726 0.010214224, 0.3771598 0.15644728 0.010612264, 0.37715998 0.15544721 0.010612115, 0.37735039 0.15644719 0.010975137, 0.37735042 0.15544726 0.010974899, 0.37762222 0.15644719 0.011281833, 0.37762222 0.15544717 0.011281714, 0.37795952 0.15644719 0.011514559, 0.37795952 0.15544726 0.011514559, 0.37834272 0.15644714 0.011659965, 0.37834272 0.15544713 0.011659876, 0.37874946 0.1564472 0.011709347, 0.37874952 0.15544726 0.011709198, 0.37874946 0.15644851 -0.011690572, 0.37834266 0.15644856 -0.011641368, 0.37874952 0.15544856 -0.011690721, 0.37834266 0.15544854 -0.011641368, 0.3779594 0.15644844 -0.011495844, 0.3779594 0.15544847 -0.011496022, 0.37762222 0.15644845 -0.011263028, 0.37762222 0.15544847 -0.011263207, 0.37735042 0.15644841 -0.010956272, 0.37735048 0.15544844 -0.010956332, 0.37715998 0.15644833 -0.010593489, 0.37716004 0.15544842 -0.010593548, 0.37706193 0.15644842 -0.010195449, 0.37706187 0.15544844 -0.010195598, 0.37706181 0.15644844 -0.0097857565, 0.37706187 0.15544844 -0.0097857565, 0.37715992 0.1564483 -0.0093878359, 0.37715992 0.15544832 -0.0093878955, 0.37735039 0.15644833 -0.0090248436, 0.37735042 0.15544839 -0.0090250224, 0.37762216 0.15644833 -0.0087182075, 0.3776221 0.15544839 -0.0087182075, 0.37795946 0.15644833 -0.0084853619, 0.37795946 0.15544835 -0.0084853619, 0.37834266 0.15644833 -0.0083401352, 0.37834266 0.15544835 -0.0083402246, 0.37874946 0.15644833 -0.008290574, 0.37874952 0.15544827 -0.0082907528, 0.21049938 0.15644269 0.070909396, 0.20987715 0.15644275 0.070984945, 0.21049941 0.15544274 0.070909396, 0.20987721 0.1554427 0.070984945, 0.20929112 0.15644267 0.071207002, 0.20929113 0.15544274 0.071207002, 0.20877521 0.15644276 0.07156311, 0.20877527 0.15544274 0.07156302, 0.20835961 0.15644261 0.072032556, 0.20835973 0.15544263 0.072032407, 0.20806839 0.15644264 0.072587356, 0.2080684 0.15544268 0.072587356, 0.20791829 0.15644267 0.0731958, 0.20791829 0.15544274 0.0731958, 0.20791833 0.1564426 0.073822811, 0.20791842 0.15544264 0.073822603, 0.20806831 0.15644249 0.074431285, 0.20806834 0.15544257 0.074431255, 0.20835963 0.15644251 0.074986354, 0.20835963 0.15544251 0.074986205, 0.2087753 0.15644243 0.075455591, 0.20877528 0.15544248 0.075455502, 0.20929115 0.15644237 0.075811759, 0.2092911 0.15544254 0.07581161, 0.20987716 0.15644246 0.076033875, 0.20987722 0.15544245 0.076033667, 0.21049935 0.15644251 0.076109365, 0.21049944 0.15544251 0.076109156, 0.36699948 0.15645204 -0.076090559, 0.36637726 0.156452 -0.07601513, 0.36699948 0.15545207 -0.076090649, 0.3663772 0.15545216 -0.076015189, 0.36579117 0.156452 -0.075792745, 0.36579117 0.15545198 -0.075792745, 0.36527541 0.156452 -0.075436696, 0.36527529 0.15545198 -0.075436786, 0.36485973 0.15645187 -0.074967667, 0.36485973 0.15545198 -0.074967667, 0.36456832 0.15645193 -0.074412689, 0.36456844 0.15545189 -0.074412778, 0.36441848 0.1564519 -0.073804006, 0.36441842 0.15545188 -0.073804095, 0.36441842 0.1564519 -0.073177263, 0.36441836 0.15545194 -0.073177531, 0.36456832 0.15645179 -0.07256864, 0.36456844 0.1554518 -0.072568849, 0.36485973 0.15645182 -0.072013691, 0.36485967 0.15545186 -0.072013691, 0.36527529 0.15645179 -0.071544543, 0.36527529 0.15545185 -0.071544573, 0.36579117 0.15645182 -0.071188524, 0.36579117 0.15545182 -0.071188584, 0.36637717 0.15645181 -0.070966229, 0.36637726 0.15545182 -0.070966318, 0.36699948 0.15645172 -0.070890769, 0.36699951 0.15545177 -0.070890769, 0.36699948 0.1564437 0.070909396, 0.3663772 0.1564438 0.070984945, 0.36699951 0.15544377 0.070909247, 0.36637726 0.15544379 0.070984945, 0.36579117 0.15644366 0.07120724, 0.36579117 0.1554437 0.071207151, 0.36527541 0.1564437 0.071563318, 0.36527535 0.15544376 0.07156311, 0.36485967 0.15644376 0.072032556, 0.36485967 0.15544377 0.072032407, 0.36456844 0.15644369 0.072587356, 0.36456832 0.15544379 0.072587356, 0.36441848 0.15644361 0.073196217, 0.36441842 0.15544373 0.073196217, 0.36441839 0.15644366 0.073822811, 0.36441842 0.15544373 0.073822603, 0.3645685 0.15644346 0.074431285, 0.3645685 0.15544344 0.074431285, 0.36485973 0.15644343 0.074986354, 0.36485979 0.15544347 0.074986205, 0.36527532 0.1564434 0.075455591, 0.36527541 0.15544346 0.075455502, 0.36579117 0.15644348 0.07581161, 0.36579117 0.1554435 0.07581161, 0.36637726 0.15644348 0.076033875, 0.36637726 0.1554435 0.076033667, 0.36699948 0.15644337 0.076109365, 0.36699942 0.15544339 0.076109365, 0.21049938 0.15645103 -0.076090649, 0.20987719 0.15645102 -0.076015189, 0.21049944 0.155451 -0.076090649, 0.20987715 0.15545109 -0.076015189, 0.20929118 0.15645099 -0.075792745, 0.2092912 0.15545098 -0.075792894, 0.2087753 0.15645099 -0.075436786, 0.20877536 0.15545097 -0.075436786, 0.20835969 0.1564509 -0.074967727, 0.20835966 0.15545091 -0.074967727, 0.20806842 0.1564509 -0.074412689, 0.2080684 0.15545091 -0.074412778, 0.20791833 0.1564509 -0.073804095, 0.20791835 0.15545091 -0.073804095, 0.20791833 0.1564509 -0.073177263, 0.20791838 0.1554509 -0.073177323, 0.20806831 0.15645084 -0.07256864, 0.20806839 0.15545079 -0.072568849, 0.20835963 0.15645076 -0.072013691, 0.20835964 0.15545073 -0.072013751, 0.20877527 0.15645075 -0.071544573, 0.20877533 0.15545079 -0.071544573, 0.20929115 0.15645079 -0.071188524, 0.20929112 0.15545079 -0.071188584, 0.20987722 0.15645081 -0.070966229, 0.20987715 0.15545081 -0.070966318, 0.21049939 0.15645073 -0.070890769, 0.21049944 0.15545079 -0.070890978, 0.38774952 0.15545194 -0.07299073, 0.38774955 0.15644372 0.073009446, 0.38774952 0.15544377 0.073009446, 0.38774952 0.15645191 -0.07299073, 0.19474946 0.15645105 -0.077990606, 0.38274953 0.15545225 -0.077990606, 0.19474936 0.15545106 -0.077990606, 0.38274959 0.15645213 -0.077990606, 0.18974943 0.15544251 0.073009416, 0.18974948 0.15645064 -0.072990492, 0.18974939 0.1554507 -0.07299073, 0.18974935 0.15644255 0.073009446, 0.38274953 0.15544349 0.078009412, 0.19474937 0.15644234 0.078009412, 0.19474937 0.15544231 0.078009382, 0.38274959 0.15644346 0.078009412, 0.21112168 0.1564424 0.076033875, 0.38043702 0.15644851 -0.0097857565, 0.38043717 0.1564472 0.0098044425, 0.38043717 0.1564472 0.010214224, 0.38043711 0.15644842 -0.010195449, 0.1916319 0.15644239 0.076918676, 0.1902445 0.15644237 0.075178936, 0.19084015 0.15644239 0.076127037, 0.19258006 0.15644224 0.077514365, 0.18987483 0.15644243 0.074121997, 0.19363686 0.15644224 0.077883914, 0.36762169 0.15644348 0.076033875, 0.36820772 0.15644351 0.07581161, 0.3687236 0.15644348 0.075455591, 0.36913922 0.15644352 0.074986354, 0.36943051 0.15644355 0.074431285, 0.36958048 0.15644364 0.073822811, 0.36958051 0.15644363 0.073196217, 0.36943051 0.1564437 0.072587356, 0.38386211 0.15644354 0.077884093, 0.38586697 0.15644357 0.076918527, 0.38491896 0.15644349 0.077514157, 0.38725433 0.15644363 0.075178877, 0.3876242 0.15644372 0.074121937, 0.38665858 0.15644364 0.076126888, 0.36913919 0.15644369 0.072032407, 0.3687236 0.15644369 0.07156311, 0.36820778 0.15644367 0.071207151, 0.36762163 0.15644373 0.070985094, 0.21263918 0.15644264 0.072032645, 0.20043711 0.15644611 0.010214224, 0.20043705 0.15644605 0.0098044425, 0.19915621 0.15644601 0.011659965, 0.37915638 0.15644726 0.011659876, 0.21112162 0.15644267 0.070984945, 0.19953939 0.15644601 0.011514649, 0.37953952 0.15644719 0.011514649, 0.37987682 0.15644719 0.011281833, 0.21170764 0.15644276 0.071207151, 0.19987671 0.15644601 0.011281833, 0.20014851 0.15644604 0.010974988, 0.21222353 0.1564427 0.071563318, 0.38014853 0.15644722 0.010975137, 0.20033891 0.15644611 0.010612264, 0.380339 0.15644725 0.010612115, 0.19915624 0.15644717 -0.0083400756, 0.19915627 0.15644614 0.0083588511, 0.20043693 0.15644732 -0.0097857565, 0.19987677 0.15644614 0.0087368339, 0.19953944 0.15644717 -0.0084853619, 0.19953947 0.15644614 0.0085041672, 0.20043699 0.15644728 -0.010195449, 0.21263914 0.15645084 -0.072013751, 0.19987668 0.15644716 -0.0087182075, 0.20014845 0.15644614 0.0090437084, 0.37953949 0.15644734 0.0085041672, 0.37915632 0.15644833 -0.0083400756, 0.37915632 0.1564474 0.0083588511, 0.20014852 0.15644717 -0.0090250224, 0.20033891 0.1564462 0.0094065517, 0.20033894 0.15644716 -0.0093878955, 0.37987676 0.15644729 0.0087368339, 0.37953952 0.15644826 -0.0084853619, 0.37987682 0.15644827 -0.0087182075, 0.38014862 0.15644732 0.0090437084, 0.38014862 0.15644826 -0.0090248436, 0.380339 0.15644838 -0.0093877167, 0.38033912 0.15644731 0.0094065517, 0.18987469 0.15645078 -0.074103341, 0.19084023 0.15645091 -0.076108173, 0.1902445 0.1564509 -0.075160131, 0.19258 0.15645099 -0.07749556, 0.19163191 0.15645093 -0.076899871, 0.19363678 0.15645103 -0.077865437, 0.19915618 0.15644738 -0.011641368, 0.21293047 0.15645081 -0.07256864, 0.1995395 0.15644723 -0.011495933, 0.19987679 0.15644726 -0.011263028, 0.2111216 0.15645075 -0.070966229, 0.21170767 0.15645081 -0.071188524, 0.20014854 0.15644728 -0.010956332, 0.20033897 0.15644728 -0.010593489, 0.21222357 0.15645084 -0.071544543, 0.21308038 0.15645093 -0.073177204, 0.21308044 0.15645093 -0.073804006, 0.21293049 0.15645093 -0.074412689, 0.36762169 0.15645179 -0.070966318, 0.36820772 0.15645182 -0.071188524, 0.21263918 0.15645093 -0.074967667, 0.21222354 0.15644246 0.075455591, 0.2126392 0.15644243 0.074986354, 0.21222357 0.15645099 -0.075436786, 0.21293047 0.15644246 0.074431285, 0.21170774 0.15645102 -0.075792745, 0.21170774 0.15644246 0.07581161, 0.2111216 0.15645103 -0.07601513, 0.21308053 0.15644252 0.073822811, 0.21308036 0.15644279 0.073196217, 0.3687236 0.15645181 -0.071544513, 0.36913922 0.15645187 -0.072013691, 0.36943051 0.15645184 -0.07256864, 0.380339 0.15644842 -0.010593489, 0.3801485 0.15644847 -0.010956332, 0.37987682 0.15644845 -0.011263117, 0.37953958 0.15644848 -0.011495844, 0.37915632 0.15644857 -0.011641368, 0.3695806 0.15645191 -0.073177323, 0.3695806 0.15645184 -0.073804095, 0.36943057 0.15645187 -0.074412689, 0.21293047 0.15644267 0.072587356, 0.36913919 0.15645199 -0.074967667, 0.3687236 0.15645203 -0.075436696, 0.36820784 0.15645203 -0.075792745, 0.36762163 0.15645207 -0.07601513, 0.38491896 0.15645224 -0.07749556, 0.38386217 0.15645224 -0.077865437, 0.38762417 0.15645206 -0.074103341, 0.38665858 0.15645224 -0.076108173, 0.38725439 0.15645213 -0.075160131, 0.38586697 0.15645213 -0.076899871, 0.3849189 0.15545227 -0.07749556, 0.21263918 0.15544271 0.072032556, 0.38386211 0.15545225 -0.077865437, 0.19024457 0.1554424 0.075178877, 0.19163196 0.15544228 0.076918468, 0.19084018 0.15544233 0.076126888, 0.38665858 0.15545225 -0.076108173, 0.1925801 0.15544224 0.077514157, 0.38586691 0.15545219 -0.076899961, 0.38725433 0.15545221 -0.075160131, 0.38762417 0.15545209 -0.0741034, 0.21112165 0.155451 -0.076015189, 0.38043717 0.15544841 -0.0097859651, 0.38043717 0.15544721 0.0098043829, 0.38043717 0.15544721 0.010214224, 0.38043711 0.15544841 -0.010195598, 0.21112169 0.15544242 0.076033667, 0.19363675 0.15544236 0.077883914, 0.18987468 0.15544257 0.074121937, 0.36762169 0.15544352 0.076033667, 0.36820772 0.15544358 0.07581161, 0.36872354 0.15544349 0.075455591, 0.36913916 0.15544352 0.074986205, 0.36943051 0.15544355 0.074431255, 0.36958048 0.15544376 0.073822603, 0.36958054 0.1554437 0.073196009, 0.36943051 0.15544374 0.072587326, 0.38586703 0.15544359 0.076918527, 0.3849189 0.15544355 0.077514157, 0.38386211 0.15544358 0.077884093, 0.38762408 0.15544377 0.074121937, 0.38725433 0.1554437 0.075178877, 0.38665858 0.15544365 0.076126888, 0.36913916 0.15544379 0.072032407, 0.36872354 0.15544374 0.07156311, 0.36820781 0.15544379 0.071207002, 0.36762172 0.15544373 0.070984945, 0.20043693 0.15544616 0.010214224, 0.20043701 0.15544614 0.0098044425, 0.19915622 0.15544608 0.011659876, 0.37915632 0.15544726 0.011659876, 0.19953939 0.15544608 0.011514559, 0.21112165 0.1554427 0.070984945, 0.37953952 0.15544729 0.0115145, 0.19987676 0.15544605 0.011281714, 0.21170771 0.15544274 0.071207002, 0.37987682 0.15544729 0.011281684, 0.20014848 0.1554461 0.010974988, 0.21222362 0.15544266 0.07156302, 0.38014856 0.15544723 0.010974988, 0.20033894 0.1554461 0.010612115, 0.380339 0.1554473 0.010612115, 0.19915625 0.15544716 -0.0083402246, 0.19915628 0.15544614 0.0083587021, 0.19953944 0.15544716 -0.0084853917, 0.1995395 0.15544623 0.0085040182, 0.19987674 0.15544616 0.0087367445, 0.20043698 0.15544721 -0.0097857565, 0.19987676 0.15544716 -0.0087183565, 0.20014855 0.15544614 0.0090437084, 0.20043705 0.15544726 -0.010195598, 0.21263918 0.15545082 -0.072013751, 0.20014851 0.15544717 -0.0090250224, 0.37915626 0.15544835 -0.0083401352, 0.37915629 0.15544735 0.0083587021, 0.37953952 0.15544733 0.0085040182, 0.200339 0.15544717 -0.0093878955, 0.20033896 0.15544617 0.0094065517, 0.37953952 0.15544827 -0.0084853917, 0.37987682 0.1554483 -0.0087182075, 0.37987682 0.15544729 0.0087368339, 0.38014856 0.15544838 -0.0090250224, 0.3801485 0.15544726 0.0090434998, 0.380339 0.15544733 0.0094065517, 0.380339 0.15544841 -0.0093878955, 0.19084024 0.15545091 -0.076108173, 0.18987474 0.15545082 -0.074103341, 0.19024457 0.15545087 -0.07516019, 0.19258001 0.15545103 -0.07749556, 0.19163193 0.15545098 -0.076899961, 0.19363679 0.15545106 -0.077865437, 0.19915624 0.15544738 -0.011641368, 0.19953942 0.15544733 -0.011496022, 0.21112165 0.15545073 -0.070966318, 0.19987682 0.15544727 -0.011263207, 0.2129305 0.15545085 -0.072568849, 0.21170774 0.15545079 -0.071188584, 0.20014843 0.15544727 -0.010956332, 0.21222353 0.15545085 -0.071544573, 0.20033899 0.15544721 -0.010593548, 0.21308045 0.15545088 -0.073177323, 0.21308045 0.15545094 -0.073804095, 0.21293046 0.15545094 -0.074412778, 0.36762175 0.15545183 -0.070966318, 0.36820784 0.15545185 -0.071188584, 0.21222354 0.15544254 0.075455502, 0.21263927 0.15544251 0.074986205, 0.2129305 0.15544242 0.074431285, 0.2126392 0.155451 -0.074967846, 0.21170768 0.15544242 0.075811461, 0.21222353 0.15545106 -0.075436786, 0.21170765 0.15545106 -0.075792894, 0.21308054 0.1554426 0.073822603, 0.21308048 0.15544266 0.0731958, 0.3687236 0.15545179 -0.071544573, 0.36913916 0.15545186 -0.072013751, 0.21293056 0.15544268 0.072587356, 0.36943051 0.15545189 -0.072568849, 0.37915626 0.15544854 -0.011641368, 0.37953958 0.15544845 -0.011495933, 0.37987682 0.15544847 -0.011263207, 0.38014844 0.1554485 -0.010956392, 0.380339 0.15544848 -0.010593548, 0.36958054 0.15545192 -0.073177531, 0.36958054 0.15545189 -0.073804095, 0.36943057 0.15545192 -0.074412689, 0.36913922 0.15545203 -0.074967727, 0.36872354 0.15545209 -0.075436786, 0.36820772 0.15545209 -0.075792894, 0.36762172 0.15545207 -0.076015189, 0.16799942 0.15545149 -0.088990793, 0.1679994 0.15645148 -0.088990524, 0.16799946 0.15644148 0.089009389, 0.16799936 0.15544148 0.089009389, 0.1619994 0.15544114 0.095009372, 0.1619994 0.15644114 0.095009372, -0.1620007 0.15643899 0.095009372, -0.16200073 0.15543906 0.095009372, -0.16800074 0.15644926 -0.088990673, -0.1680007 0.1554493 -0.088990793, -0.16800079 0.15543935 0.08900927, -0.16800074 0.15643929 0.089009389, 0.16199942 0.15645178 -0.094990775, 0.1619994 0.1554518 -0.094990775, -0.1620007 0.15544967 -0.094990775, -0.16200076 0.15644972 -0.094990775, -0.16669168 0.15544955 -0.092731729, -0.16785036 0.15544946 -0.090325937, -0.16740659 0.15544945 -0.091594085, -0.1657417 0.15544961 -0.093681708, -0.16460404 0.15544966 -0.094396755, 0.16740511 0.15544136 0.091612533, 0.16669032 0.15544134 0.092750266, 0.1657403 0.15544128 0.093700334, 0.16333441 0.15544125 0.09485884, 0.16460267 0.15544119 0.094415024, 0.16784887 0.15544148 0.090344355, 0.13569942 0.15544508 0.020509318, 0.15319934 0.15544526 0.020509258, 0.15319942 0.15544753 -0.020490751, 0.13569939 0.15544748 -0.020490751, 0.16574033 0.15545171 -0.093681708, 0.16669036 0.1554517 -0.092731729, 0.16740526 0.15545158 -0.091594085, 0.16784894 0.1554516 -0.090325937, 0.16333449 0.15545182 -0.094840303, 0.16460268 0.15545185 -0.094396606, -0.16669175 0.15543911 0.092750415, -0.16460392 0.15543905 0.094415024, -0.16574164 0.15543908 0.093700483, -0.1678503 0.15543921 0.090344355, -0.1633358 0.15543896 0.09485884, -0.16740656 0.15543914 0.091612533, -0.13570073 0.15544337 0.020509318, -0.15320072 0.15544328 0.020509318, -0.13570067 0.15544567 -0.020490751, -0.15320066 0.15544555 -0.02049081, -0.16333583 0.15544975 -0.094840303, -0.16460404 0.15644968 -0.094396517, -0.16574173 0.15644957 -0.093681708, -0.1633359 0.15644975 -0.094840214, 0.16669041 0.15644121 0.092750415, 0.1674052 0.15644127 0.091612801, 0.1657403 0.15644121 0.093700483, -0.16669181 0.15644959 -0.092731521, -0.16785033 0.15644942 -0.090325937, -0.1674066 0.15644951 -0.091593996, 0.16333441 0.1564412 0.094858959, 0.16460262 0.1564412 0.094415233, 0.16784886 0.15644142 0.090344414, 0.13569941 0.15644509 0.020509437, 0.15319937 0.15644522 0.020509318, 0.15319943 0.15644751 -0.020490661, 0.13569936 0.15644747 -0.020490751, 0.16740523 0.15645161 -0.091593996, 0.16574028 0.15645176 -0.093681619, 0.1678489 0.1564516 -0.090325877, 0.16669039 0.15645172 -0.092731521, 0.16333452 0.15645175 -0.094840214, 0.16460273 0.15645176 -0.094396517, -0.16460402 0.15643898 0.094415024, -0.16669168 0.15643905 0.092750415, -0.16574167 0.15643905 0.093700483, -0.1678503 0.15643924 0.090344414, -0.16740654 0.15643908 0.091612682, -0.16333596 0.15643911 0.094859108, -0.13570072 0.1564433 0.020509437, -0.15320079 0.15644322 0.020509318, -0.13570079 0.15644568 -0.020490661, -0.15320078 0.15644562 -0.020490661, -0.27245089 0.16034321 0.009009704, -0.27405083 0.16194308 0.009009704, -0.27240148 0.16034317 0.0094164759, -0.2739549 0.16194305 0.0097994953, -0.27367279 0.16194311 0.010543242, -0.27225605 0.16034302 0.009799704, -0.27322102 0.16194314 0.01119794, -0.27202329 0.16034311 0.010136947, -0.27262542 0.16194302 0.0117255, -0.27171656 0.16034311 0.010408625, -0.27192113 0.16194294 0.012095198, -0.27135369 0.16034311 0.010599121, -0.27114865 0.16194305 0.012285545, -0.27095571 0.16034305 0.010697141, -0.27035311 0.16194302 0.012285694, -0.27054581 0.16034311 0.010697141, -0.26958066 0.16194302 0.012095287, -0.27014795 0.16034311 0.010599032, -0.26887631 0.16194309 0.0117255, -0.26978514 0.1603431 0.010408774, -0.26828077 0.16194308 0.011198029, -0.26947841 0.16034313 0.010136947, -0.26782885 0.16194311 0.010543242, -0.26924559 0.1603432 0.0097994953, -0.26754674 0.16194314 0.0097994953, -0.26910022 0.16034317 0.0094163269, -0.26745084 0.1619432 0.009009704, -0.26905081 0.16034319 0.0090094954, -0.2724508 0.15644321 0.0090093464, -0.27240145 0.15644312 0.0094163269, -0.27225611 0.15644306 0.0097994953, -0.27202323 0.15644301 0.010136709, -0.27171642 0.15644306 0.010408476, -0.27135363 0.15644298 0.010598883, -0.27095568 0.15644313 0.010696903, -0.27054581 0.156443 0.010696903, -0.27014795 0.15644303 0.010598883, -0.26978517 0.15644312 0.010408476, -0.26947838 0.15644321 0.010136709, -0.26924551 0.15644312 0.0097994953, -0.26910028 0.15644318 0.0094162375, -0.26905078 0.15644315 0.0090093464, -0.24758062 0.16194306 0.012095287, -0.24835309 0.16194312 0.012285694, -0.24949357 0.16194287 0.016036049, -0.25167289 0.16194338 0.0074759573, -0.25674054 0.16194321 0.0094295591, -0.25195494 0.16194329 0.0082200915, -0.24687631 0.16194329 0.0117255, -0.24893825 0.16194287 0.017988309, -0.24628076 0.16194326 0.011198029, -0.24875084 0.16194263 0.020009831, -0.27322102 0.16194177 0.033198074, -0.27445373 0.1619418 0.033311352, -0.27409634 0.16194171 0.033880189, -0.27362129 0.16194171 0.034355, -0.27262542 0.16194174 0.033725396, -0.27305254 0.16194181 0.034712657, -0.27241853 0.16194177 0.034934565, -0.25145087 0.16194355 0.0050094873, -0.25122106 0.16194353 0.0068214089, -0.25062552 0.16194347 0.0062939078, -0.27367279 0.16194177 0.032543227, -0.27467561 0.16194177 0.032677099, -0.24582887 0.16194315 0.010543242, -0.24582885 0.16194218 0.029476061, -0.24475083 0.16194195 0.032009795, -0.27192107 0.16194174 0.034095332, -0.27175084 0.16194174 0.035009816, -0.2739549 0.1619419 0.031799451, -0.2747508 0.16194174 0.032009795, -0.25145087 0.16194355 0.0044096857, -0.25873592 0.16194326 0.0090567023, -0.26076576 0.16194321 0.0090567023, -0.26805082 0.16194344 0.0044096857, -0.27114859 0.16194174 0.03428565, -0.24992105 0.16194344 0.00592421, -0.27405074 0.16194186 0.0310096, -0.27035317 0.16194177 0.03428559, -0.27395496 0.16194195 0.030219808, -0.2695806 0.16194174 0.034095123, -0.27367282 0.16194195 0.02947621, -0.2447508 0.16194329 0.0080096871, -0.24554674 0.16194326 0.0097994953, -0.24545088 0.16194338 0.009009704, -0.24554676 0.16194335 0.0082199425, -0.24775085 0.1619436 0.0050096661, -0.24835309 0.16194348 0.0057338029, -0.24758068 0.16194348 0.00592421, -0.24914864 0.16194348 0.0057337433, -0.24482605 0.16194344 0.0073422045, -0.24582881 0.16194341 0.0074761063, -0.24708328 0.16194355 0.0050848275, -0.24687627 0.1619435 0.0062937886, -0.24504793 0.16194341 0.0067080408, -0.24628076 0.16194344 0.0068212599, -0.24644914 0.1619435 0.0053068548, -0.24588034 0.1619435 0.0056641251, -0.24540532 0.16194341 0.0061391443, -0.26805088 0.1619435 0.0050096661, -0.27175084 0.16194339 0.0050096661, -0.27035311 0.16194335 0.0057335049, -0.26958069 0.16194332 0.0059240013, -0.26787993 0.16194221 0.027420238, -0.26887628 0.16194205 0.028293952, -0.26828074 0.16194196 0.028821453, -0.26958069 0.16194212 0.027924076, -0.2663798 0.16194206 0.028787747, -0.26782885 0.16194201 0.02947621, -0.26754668 0.16194198 0.030219808, -0.2691032 0.16194221 0.025800511, -0.27035311 0.16194206 0.027733818, -0.27114862 0.16194206 0.027733818, -0.26465389 0.16194198 0.029856578, -0.2674509 0.16194199 0.031009659, -0.2675468 0.16194201 0.031799451, -0.27000797 0.16194224 0.023983255, -0.2719211 0.16194206 0.027924076, -0.27262548 0.16194203 0.028293714, -0.26276109 0.16194205 0.030589744, -0.26782885 0.16194184 0.032543227, -0.26828077 0.16194181 0.033197984, -0.27056369 0.16194248 0.022031024, -0.27322108 0.16194206 0.028821573, -0.26076576 0.16194199 0.03096278, -0.26887622 0.16194174 0.033725545, -0.27075085 0.16194263 0.020009711, -0.25122097 0.16194198 0.033197984, -0.25674054 0.16194206 0.030589744, -0.25873592 0.16194209 0.03096278, -0.27056339 0.16194259 0.017988458, -0.25062546 0.16194187 0.033725545, -0.27000809 0.16194278 0.016036108, -0.25167289 0.16194201 0.032543376, -0.24992108 0.16194189 0.034095123, -0.25195494 0.16194201 0.031799361, -0.25484771 0.16194206 0.029856578, -0.26910332 0.16194294 0.014219001, -0.25205085 0.16194201 0.0310096, -0.24775082 0.16194186 0.035009667, -0.24914873 0.16194195 0.03428559, -0.27475086 0.1619432 0.0080096871, -0.24835305 0.1619419 0.03428559, -0.251955 0.16194218 0.030219987, -0.27395496 0.1619432 0.0082199425, -0.27467564 0.16194327 0.0073422045, -0.25312188 0.16194218 0.028787926, -0.24758068 0.16194187 0.034095123, -0.24708337 0.16194196 0.034934357, -0.25167289 0.16194212 0.029476061, -0.27367285 0.16194326 0.0074761063, -0.27445379 0.1619433 0.0067080408, -0.24687628 0.16194195 0.033725545, -0.24644914 0.16194189 0.034712657, -0.26787999 0.16194302 0.012599096, -0.2458804 0.16194189 0.034355, -0.25122103 0.16194224 0.028821453, -0.27322099 0.16194332 0.0068214387, -0.27409628 0.16194329 0.0061391443, -0.24628076 0.16194193 0.033198074, -0.24540535 0.16194187 0.033880189, -0.27362129 0.16194323 0.0056642443, -0.25162175 0.16194224 0.027420238, -0.25062555 0.16194215 0.028293714, -0.27262548 0.16194329 0.0062937886, -0.24504796 0.16194186 0.033311412, -0.24582885 0.16194195 0.032543227, -0.27305242 0.16194327 0.0053068548, -0.24992107 0.16194215 0.027924076, -0.26637986 0.16194314 0.011231616, -0.24482599 0.16194195 0.032677099, -0.27241835 0.16194335 0.0050848275, -0.27192101 0.16194332 0.0059240013, -0.24554679 0.16194212 0.031799451, -0.27114865 0.16194338 0.0057338029, -0.24545082 0.16194206 0.031009659, -0.25039855 0.16194245 0.025800511, -0.24914858 0.16194215 0.027733818, -0.24835309 0.16194218 0.027733669, -0.24554674 0.16194218 0.030219987, -0.26465395 0.16194311 0.010162726, -0.26754674 0.16194317 0.008219853, -0.24949364 0.16194244 0.023983255, -0.24758068 0.16194224 0.027924076, -0.24687624 0.16194221 0.028293714, -0.26828077 0.16194326 0.0068214089, -0.26782891 0.1619433 0.0074761063, -0.26887622 0.16194335 0.0062937886, -0.26276115 0.16194323 0.0094295591, -0.24893811 0.16194254 0.022030845, -0.24628079 0.16194221 0.028821304, -0.25122106 0.16194323 0.01119794, -0.25312182 0.16194317 0.011231616, -0.25162175 0.16194308 0.012599096, -0.2506254 0.16194311 0.0117255, -0.25167289 0.16194323 0.010543242, -0.24992105 0.16194311 0.012095317, -0.25039855 0.16194305 0.014219001, -0.25195494 0.16194323 0.0097993463, -0.25484774 0.16194323 0.010162964, -0.24914862 0.16194308 0.012285784, -0.25205079 0.16194326 0.0090094954, -0.27245083 0.16034195 0.0310096, -0.27240136 0.16034189 0.03141652, -0.27225611 0.16034192 0.031799659, -0.27202329 0.16034183 0.032136992, -0.27171645 0.16034178 0.03240864, -0.27135363 0.16034177 0.032599196, -0.27095565 0.16034177 0.032697245, -0.27054581 0.16034174 0.032697245, -0.27014801 0.1603418 0.032599077, -0.26978514 0.16034187 0.03240864, -0.26947841 0.16034186 0.032136902, -0.26924562 0.16034199 0.0317996, -0.26910022 0.16034189 0.031416371, -0.26905081 0.16034192 0.0310096, -0.27245083 0.15644194 0.031009361, -0.27240142 0.15644191 0.031416252, -0.27225605 0.15644193 0.031799302, -0.27202329 0.15644178 0.032136664, -0.27171651 0.15644181 0.032408342, -0.2713536 0.15644181 0.032598987, -0.27095577 0.15644179 0.032697096, -0.27054587 0.15644178 0.032697037, -0.27014795 0.15644181 0.032598987, -0.26978511 0.15644184 0.032408342, -0.26947838 0.15644184 0.032136902, -0.26924554 0.15644197 0.031799361, -0.26910025 0.15644193 0.031416252, -0.26905081 0.15644199 0.031009361, -0.25045082 0.1603421 0.0310096, -0.25040153 0.1603421 0.03141652, -0.25025609 0.1603421 0.0317996, -0.25002334 0.16034195 0.032136992, -0.24971652 0.16034189 0.03240864, -0.24935369 0.16034198 0.032599136, -0.24895568 0.16034196 0.032697245, -0.24854587 0.16034193 0.032697245, -0.24814789 0.16034187 0.032599077, -0.24778508 0.16034199 0.03240864, -0.2474784 0.16034195 0.032137141, -0.24724548 0.16034205 0.031799451, -0.24710019 0.1603421 0.03141652, -0.24705069 0.16034199 0.0310096, -0.25045076 0.15644205 0.031009302, -0.25040144 0.15644208 0.031416252, -0.25025609 0.15644202 0.031799361, -0.25002319 0.1564419 0.032136664, -0.24971645 0.15644191 0.032408342, -0.2493536 0.15644188 0.032599077, -0.24895579 0.15644199 0.032697037, -0.2485459 0.15644188 0.032696947, -0.24814799 0.15644193 0.032598779, -0.24778509 0.15644193 0.032408342, -0.24747837 0.1564419 0.032136664, -0.24724555 0.15644199 0.031799361, -0.24710023 0.15644209 0.031416252, -0.24705085 0.15644214 0.031009361, -0.25045094 0.16034336 0.0090094954, -0.25040153 0.16034338 0.0094163269, -0.25025615 0.16034326 0.0097994953, -0.25002334 0.16034326 0.010136858, -0.24971654 0.1603432 0.010408625, -0.24935374 0.16034332 0.010599121, -0.24895579 0.16034323 0.010697141, -0.24854597 0.16034326 0.010697141, -0.24814798 0.16034326 0.010599032, -0.24778517 0.16034327 0.010408625, -0.24747835 0.16034326 0.010136858, -0.24724554 0.16034326 0.009799704, -0.24710019 0.16034333 0.0094165653, -0.24705084 0.16034332 0.0090094954, -0.25045076 0.1564433 0.0090093464, -0.25040135 0.15644324 0.0094162375, -0.25025609 0.15644321 0.0097993463, -0.25002328 0.15644321 0.010136709, -0.24971642 0.15644318 0.010408476, -0.24935365 0.15644318 0.010598883, -0.24895573 0.15644321 0.010696992, -0.2485458 0.15644318 0.010696903, -0.24814789 0.15644321 0.010598883, -0.24778509 0.15644321 0.010408476, -0.24747826 0.15644321 0.010136798, -0.24724555 0.15644319 0.0097993463, -0.2471002 0.15644331 0.0094163269, -0.24705087 0.15644342 0.009009257, -0.27075091 0.17494249 0.020010605, -0.27056369 0.17494273 0.017989144, -0.27000818 0.17494276 0.016036704, -0.26910332 0.17494287 0.014219627, -0.26787996 0.17494291 0.012599781, -0.26637989 0.17494315 0.011232212, -0.26465398 0.17494315 0.010163561, -0.26276121 0.17494322 0.0094303936, -0.26076591 0.17494327 0.0090572983, -0.25873601 0.17494333 0.0090572983, -0.25674069 0.17494331 0.0094303936, -0.25484776 0.17494318 0.010163769, -0.25312188 0.17494315 0.011232212, -0.25162184 0.17494312 0.01259993, -0.25039852 0.17494299 0.014219627, -0.2494937 0.17494282 0.016036734, -0.2489382 0.17494276 0.017989114, -0.24875094 0.17494275 0.020010486, -0.2477508 0.15644358 0.0050094277, -0.25145075 0.15644351 0.0050094873, -0.24475078 0.15644336 0.0080092996, -0.24475078 0.15644193 0.032009408, -0.26805079 0.15644345 0.0050094277, -0.27175081 0.15644348 0.0050094277, -0.27475077 0.15644175 0.032009408, -0.27475074 0.15644312 0.0080092996, -0.27175084 0.15644172 0.035009429, -0.2477508 0.15644184 0.035009429, -0.2499429 0.15644279 0.018058524, -0.24971645 0.15644334 0.0076104254, -0.24935362 0.15644336 0.0074197203, -0.25002319 0.1564433 0.0078821033, -0.25025615 0.15644334 0.0082193464, -0.25040144 0.1564433 0.0086023659, -0.25779986 0.15644315 0.010201439, -0.25592387 0.15644307 0.010770515, -0.24895573 0.15644342 0.0073217005, -0.27409622 0.15644163 0.033879802, -0.27362126 0.15644169 0.03435491, -0.27445364 0.1564417 0.033310875, -0.25975075 0.15644313 0.010009304, -0.25345081 0.15644369 0.0024093837, -0.26605079 0.15644354 0.0024093837, -0.27305254 0.15644166 0.03471218, -0.27241841 0.15644172 0.034934267, -0.27467558 0.15644175 0.032676861, -0.25145087 0.15644357 0.0044093281, -0.24854587 0.1564434 0.007321611, -0.24814795 0.1564434 0.0074197203, -0.27240148 0.15644197 0.03060244, -0.24710023 0.15644334 0.0086025149, -0.24724551 0.15644333 0.0082193464, -0.24975082 0.1564427 0.020009443, -0.27225611 0.15644199 0.030219421, -0.244826 0.15644342 0.0073418468, -0.24708325 0.1564436 0.0050845295, -0.24778512 0.15644337 0.0076102167, -0.27202323 0.15644193 0.029881999, -0.24644908 0.15644349 0.0053064376, -0.24504791 0.15644348 0.0067076832, -0.24747831 0.15644334 0.0078818947, -0.24588029 0.15644348 0.0056638867, -0.24540532 0.15644339 0.0061389059, -0.26947835 0.15644196 0.029881999, -0.26682189 0.15644218 0.027080432, -0.26924565 0.15644203 0.030219451, -0.26978505 0.15644193 0.029610321, -0.27014789 0.15644187 0.029419824, -0.26530641 0.15644202 0.028324023, -0.26910019 0.15644199 0.03060244, -0.26806545 0.15644222 0.025565073, -0.27054578 0.15644194 0.029321775, -0.27095562 0.15644199 0.029321775, -0.26357767 0.15644205 0.029248133, -0.26898965 0.15644228 0.02383627, -0.27135369 0.15644202 0.029419824, -0.27171651 0.15644199 0.029610321, -0.26170161 0.15644202 0.029817119, -0.26955861 0.1564424 0.021960273, -0.26975086 0.15644267 0.020009235, -0.25975081 0.15644206 0.030009493, -0.25779986 0.15644211 0.029817268, -0.2695587 0.15644273 0.018058464, -0.26898956 0.15644276 0.016182557, -0.25592387 0.15644206 0.029248133, -0.26806548 0.15644284 0.014453635, -0.25419512 0.15644212 0.028324023, -0.25040135 0.15644205 0.03060244, -0.27240151 0.15644327 0.0086026341, -0.24708325 0.15644188 0.034934357, -0.25025606 0.15644211 0.030219421, -0.27467561 0.15644328 0.0073418468, -0.27225608 0.15644318 0.008219257, -0.27445379 0.1564433 0.0067074746, -0.2464492 0.15644194 0.03471218, -0.24588028 0.1564419 0.034354761, -0.27202329 0.15644321 0.0078821033, -0.27409634 0.15644327 0.0061388165, -0.2526798 0.15644224 0.027080432, -0.25002325 0.15644208 0.029881999, -0.26682189 0.15644287 0.012938276, -0.24971649 0.15644211 0.029610321, -0.24540532 0.15644187 0.033879802, -0.27362135 0.15644336 0.0056638867, -0.27171656 0.15644327 0.0076102167, -0.24935365 0.15644217 0.029419824, -0.24504791 0.15644193 0.033311114, -0.27305248 0.1564434 0.0053064376, -0.24482602 0.15644193 0.032676861, -0.27241838 0.15644339 0.0050845295, -0.27135369 0.15644333 0.0074197501, -0.25143611 0.15644234 0.025565073, -0.2489557 0.15644208 0.029321656, -0.24854589 0.15644214 0.029321775, -0.2653065 0.156443 0.011694536, -0.27095577 0.15644327 0.0073217005, -0.2705459 0.15644325 0.0073217005, -0.24710009 0.15644208 0.03060244, -0.24724551 0.15644214 0.030219451, -0.24747825 0.15644208 0.029881999, -0.25051194 0.15644237 0.0238363, -0.24814789 0.15644209 0.029419824, -0.24778509 0.1564422 0.029610381, -0.26910028 0.15644318 0.0086026341, -0.26357761 0.15644306 0.010770664, -0.26924556 0.15644322 0.008219257, -0.26947832 0.15644316 0.0078821033, -0.26978511 0.15644321 0.0076104254, -0.27014789 0.15644324 0.0074197203, -0.2499429 0.15644258 0.021960214, -0.2617017 0.15644312 0.010201439, -0.26805094 0.15644352 0.0044093281, -0.25267971 0.156443 0.012938276, -0.25419512 0.15644312 0.011694685, -0.25143602 0.15644285 0.014453515, -0.25051191 0.15644276 0.016182616, -0.24975088 0.15344277 0.020009205, -0.2499429 0.15344277 0.018058285, -0.25051197 0.15344289 0.016182289, -0.25143608 0.15344304 0.014453486, -0.25267971 0.15344302 0.012938127, -0.25419509 0.15344316 0.011694416, -0.25592393 0.15344319 0.010770276, -0.2577998 0.15344307 0.010201439, -0.25975087 0.15344322 0.010009304, -0.26170164 0.15344316 0.01020135, -0.26357764 0.15344317 0.010770515, -0.26530644 0.15344301 0.011694416, -0.26682186 0.15344293 0.012938216, -0.26806551 0.15344287 0.014453486, -0.26898968 0.15344277 0.016182408, -0.26955858 0.15344259 0.018058285, -0.26975074 0.15344262 0.020009235, -0.26286054 0.15344425 -0.011014208, -0.36467719 0.15343924 0.069082007, -0.36580434 0.15343931 0.068654492, 0.36699942 0.15345213 -0.078490809, 0.36819604 0.15345216 -0.078345492, 0.39076343 0.15345435 -0.11399089, -0.41100082 0.15345007 -0.12999089, -0.41000089 0.15344919 -0.11475472, -0.41000083 0.15345004 -0.12999095, -0.26894221 0.15344462 -0.017589554, -0.36580431 0.1534469 -0.068636134, 0.21517453 0.15345085 -0.071717814, 0.36232439 0.15345185 -0.071717873, 0.3620359 0.15345179 -0.072888121, -0.26104969 0.15344441 -0.010580078, -0.25918883 0.15344435 -0.01050742, -0.3907648 0.15344927 -0.11399089, -0.37111574 0.15344726 -0.076331213, -0.37031654 0.15344734 -0.077233419, -0.36932451 0.15344746 -0.077918127, -0.36368528 0.15343922 0.069766745, -0.371676 0.15344729 -0.075263813, -0.36819735 0.15344743 -0.078345492, -0.25734937 0.15344435 -0.010799393, 0.36932305 0.15345213 -0.077918127, 0.36288473 0.15345161 -0.070650443, -0.36700082 0.15344749 -0.078490809, -0.36288592 0.15343907 0.070668921, -0.26955867 0.1534425 0.021960154, 0.21461436 0.15345068 -0.070650443, -0.36580434 0.15344751 -0.078345492, 0.3703151 0.1534521 -0.077233419, 0.21282306 0.15344244 0.077936456, 0.17923555 0.15344007 0.11400925, 0.213815 0.15344244 0.077251717, 0.21169597 0.15344243 0.07836397, 0.21049941 0.15344223 0.078509018, -0.25560239 0.15344441 -0.011444345, -0.36467719 0.15344742 -0.077918127, 0.20930283 0.15344241 0.078363821, 0.20817585 0.15344235 0.077936456, 0.20718381 0.15344246 0.077251926, 0.20638455 0.15344234 0.076349691, -0.36232582 0.15343907 0.071735993, -0.26898959 0.15344229 0.023835912, -0.36368519 0.15344739 -0.077233419, 0.36368391 0.15345155 -0.069748268, 0.21381506 0.15345067 -0.069748178, 0.21381508 0.1534428 0.069766656, 0.37111434 0.15345213 -0.076331213, -0.36203721 0.15343896 0.072906449, -0.26806545 0.15344222 0.025564834, 0.40999946 0.15345533 -0.12999089, 0.40999949 0.15345442 -0.11475472, 0.41099948 0.15345538 -0.12999095, -0.25401491 0.15344453 -0.012417927, 0.37167457 0.1534521 -0.075263813, -0.26682186 0.15344219 0.027080283, -0.25264761 0.15344459 -0.01368244, -0.25155342 0.15344462 -0.015189424, -0.36203736 0.15343903 0.074111983, -0.2653065 0.15344208 0.028323933, -0.37031648 0.153447 -0.069748178, -0.37031648 0.15343919 0.069766745, -0.36932448 0.15344697 -0.069063529, -0.37111589 0.15344705 -0.070650443, -0.2507742 0.15344477 -0.016880974, -0.37111577 0.15343903 0.070668831, -0.36232573 0.15343878 0.07528238, -0.26357755 0.15344205 0.029247984, -0.36932448 0.15343922 0.069082007, -0.2503401 0.15344492 -0.018691912, -0.20817718 0.15344797 -0.069063529, -0.36819759 0.15343931 0.068654492, -0.36819738 0.15344687 -0.068636164, -0.36700085 0.15344693 -0.068490759, -0.36700085 0.15343925 0.068509236, 0.36368397 0.15344386 0.069766745, 0.36467588 0.15345164 -0.069063529, 0.21461438 0.15344274 0.070668831, 0.36288461 0.15344371 0.070668921, 0.36467585 0.15344392 0.069082007, 0.21517453 0.1534427 0.071736082, 0.36232439 0.15344374 0.071735993, -0.254195 0.15344211 0.028323874, -0.2138164 0.15344018 0.069766745, -0.25267968 0.15344226 0.027080342, -0.40923694 0.15343641 0.11400931, -0.40923694 0.15344915 -0.11399089, 0.36580291 0.15344395 0.068654403, 0.36580285 0.15345164 -0.068636164, 0.36699954 0.15345156 -0.068490759, -0.41000089 0.15343638 0.11477329, 0.21546294 0.15344268 0.072906598, 0.36203596 0.1534436 0.072906598, -0.25592393 0.15344208 0.029248103, -0.21461567 0.15344001 0.070668831, -0.21282443 0.15344025 0.069082007, -0.251436 0.15344232 0.025564924, 0.36699936 0.15344401 0.068509176, 0.21546295 0.15344274 0.074111983, 0.36203602 0.15344353 0.074111983, -0.25779977 0.153442 0.029817089, -0.21517591 0.15344 0.071736082, -0.36232582 0.15344718 -0.071717873, -0.26685393 0.15344518 -0.026299194, -0.36203721 0.15344712 -0.07288824, -0.21169734 0.15344021 0.068654492, -0.25051197 0.15344241 0.023836091, 0.3681961 0.15344395 0.068654403, -0.24994297 0.15344253 0.021960214, -0.26548681 0.15344524 -0.027563676, 0.3681961 0.15345162 -0.068636164, -0.36203721 0.1534472 -0.074093565, 0.21517447 0.15344256 0.075282231, 0.36232445 0.15344343 0.075282231, 0.21461424 0.15344256 0.076349542, -0.21546429 0.15343992 0.072906449, -0.26794815 0.15344509 -0.024792239, -0.36288592 0.15344703 -0.070650563, -0.25975084 0.15344211 0.030009225, -0.26389906 0.1534453 -0.028537109, -0.36232573 0.15344737 -0.075263813, 0.36932316 0.15344389 0.069082007, -0.21050078 0.15344025 0.068509236, 0.36932316 0.15345159 -0.069063529, -0.2687273 0.15344496 -0.023100838, 0.36288449 0.15344343 0.076349482, -0.26170182 0.15344211 0.029817119, -0.21546429 0.15343992 0.074111775, -0.2093042 0.15344019 0.068654492, 0.37031516 0.15344387 0.069766745, 0.37031516 0.15345168 -0.069748357, -0.26215211 0.15344542 -0.0291823, 0.36368385 0.15344341 0.077251926, -0.2151759 0.15343979 0.07528238, -0.36288583 0.1534387 0.076349482, -0.21381634 0.15344834 -0.077233419, -0.1792368 0.15345065 -0.11399089, -0.21461579 0.15344831 -0.076331213, -0.36288604 0.1534474 -0.076331213, -0.20817713 0.15344018 0.069082007, 0.37111434 0.15344378 0.070668921, 0.37111446 0.15345168 -0.070650443, -0.21282434 0.15344845 -0.077918127, -0.20718519 0.15344799 -0.069748178, -0.36368528 0.15343885 0.077251926, -0.21461573 0.15343973 0.076349542, -0.26916152 0.15344483 -0.021289751, -0.20718509 0.15344013 0.069766656, -0.36368528 0.15344702 -0.069748268, -0.21381637 0.15343973 0.077251926, -0.2151759 0.15344828 -0.075263813, -0.39076489 0.15343654 0.11400931, -0.21169731 0.15344846 -0.078345492, -0.26031286 0.15344545 -0.029474124, -0.21546426 0.15344816 -0.074093446, -0.21050079 0.15344846 -0.078490809, -0.26923418 0.15344483 -0.019428864, -0.36467728 0.15344699 -0.069063529, 0.36580285 0.1534434 0.07836397, 0.39076343 0.15344143 0.11400925, 0.36699948 0.15344317 0.078509286, 0.36467585 0.1534434 0.077936456, -0.21546429 0.1534481 -0.072888121, 0.3711144 0.15344346 0.076349542, 0.37167469 0.15344349 0.07528238, 0.3703151 0.15344343 0.077251926, 0.3693231 0.15344349 0.077936456, 0.36819601 0.1534434 0.07836397, -0.25845191 0.15344551 -0.029401436, -0.20930415 0.15344848 -0.078345492, 0.40923557 0.15345448 -0.11399089, 0.40999952 0.15344153 0.11477329, 0.40923557 0.15344155 0.11400925, 0.40999952 0.15344062 0.13000916, 0.41099951 0.15344065 0.13000916, -0.21169728 0.15343958 0.078363821, -0.17923677 0.15343776 0.11400931, -0.21050084 0.15343961 0.078509018, -0.21282437 0.15343973 0.077936396, 0.37196311 0.15344355 0.074111983, -0.20718518 0.15343973 0.077251926, -0.20638588 0.15343976 0.076349542, -0.21517579 0.15344805 -0.071717873, 0.37196299 0.15344371 0.072906449, -0.20817712 0.15343969 0.077936396, 0.37167451 0.15344375 0.071736082, -0.20930421 0.15343972 0.078363821, 0.37196296 0.15345186 -0.072888121, 0.37167457 0.1534518 -0.071717873, 0.37196305 0.1534519 -0.074093446, -0.37196437 0.15343894 0.072906449, -0.371676 0.15343897 0.071736082, -0.3719644 0.15344708 -0.07288824, -0.3719644 0.15344715 -0.074093446, -0.37196442 0.15343888 0.074111983, -0.371676 0.15344711 -0.071717873, -0.371676 0.15343876 0.075282231, -0.15800072 0.15344925 -0.086990908, 0.16076332 0.15345284 -0.11399089, -0.16076468 0.15345088 -0.11399089, 0.17923555 0.1534529 -0.11399089, 0.20553592 0.15345092 -0.074093446, 0.20582429 0.15345098 -0.075263813, 0.20638454 0.153451 -0.076331213, 0.20553592 0.1534508 -0.072888121, 0.20582433 0.15345076 -0.071717873, 0.20638448 0.15345065 -0.070650443, 0.20718379 0.15345064 -0.069748268, 0.15799941 0.15345128 -0.086990908, 0.20553583 0.15344264 0.072906449, 0.20582436 0.1534427 0.071735993, 0.20638452 0.15344271 0.070668831, 0.20718378 0.15344287 0.069766745, 0.20553583 0.15344264 0.074111983, 0.20582448 0.15344241 0.07528238, 0.16076329 0.15344009 0.11400931, 0.15799938 0.15344144 0.087009177, -0.16076465 0.15343791 0.11400931, -0.15800074 0.15343942 0.087009177, -0.2055372 0.15344815 -0.07288824, -0.20817718 0.15344848 -0.077918127, -0.20582566 0.15344815 -0.071717814, -0.20638588 0.15344802 -0.070650443, 0.20718387 0.15345104 -0.077233419, -0.2055372 0.15343995 0.072906449, -0.2055372 0.15343995 0.074111983, -0.20582569 0.15343983 0.075282529, -0.25664082 0.15344536 -0.028967366, 0.20817578 0.1534511 -0.077918127, -0.20553721 0.15344827 -0.074093565, -0.20582573 0.15344009 0.071736291, -0.20582572 0.15344842 -0.075263813, -0.20638582 0.15344003 0.070668921, -0.20638588 0.15344837 -0.076331213, 0.20930286 0.15345106 -0.078345492, -0.41100082 0.15343542 0.13000916, -0.20718512 0.15344842 -0.077233419, 0.21049944 0.15345113 -0.078490779, 0.21169603 0.15345113 -0.078345492, -0.25494939 0.1534453 -0.028188184, -0.21461564 0.15344796 -0.070650443, 0.21282302 0.15345117 -0.077918127, 0.21381506 0.15345109 -0.077233419, -0.25344244 0.15344533 -0.027093753, -0.21381633 0.15344793 -0.069748268, -0.41000095 0.15343544 0.13000937, -0.25217786 0.15344518 -0.025726661, -0.21282437 0.15344796 -0.069063649, 0.20817579 0.15344286 0.069081917, -0.36467731 0.15343881 0.077936456, -0.36580431 0.15343876 0.07836397, 0.20817584 0.15345065 -0.069063529, -0.36700079 0.15343857 0.078509018, -0.36819738 0.1534387 0.07836397, -0.36932448 0.15343872 0.077936456, -0.37031648 0.15343869 0.077251926, -0.37111574 0.1534387 0.076349542, 0.20930284 0.15344283 0.068654403, 0.20930281 0.15345058 -0.068636164, 0.21049942 0.15345055 -0.068490848, -0.25120434 0.15344512 -0.024139211, -0.21169734 0.15344787 -0.068636015, 0.2104995 0.15344289 0.068509236, -0.2505593 0.15344509 -0.02239199, 0.211696 0.15344292 0.068654492, -0.21050078 0.15344788 -0.068490759, 0.21169597 0.15345061 -0.068636164, 0.21282303 0.15344295 0.069082007, -0.25026757 0.15344507 -0.02055271, -0.20930412 0.15344785 -0.068636164, 0.21282305 0.15345067 -0.069063529, 0.36368397 0.15345202 -0.077233419, 0.21461433 0.15345104 -0.076331213, 0.36288467 0.15345198 -0.076331213, 0.36467585 0.15345208 -0.077918127, -0.26732358 0.15344447 -0.014254943, -0.26605907 0.15344441 -0.012887701, 0.36232445 0.1534519 -0.075263813, 0.21517447 0.15345104 -0.075263813, 0.36580297 0.1534521 -0.078345492, -0.26829723 0.15344462 -0.015842453, 0.21546297 0.15345091 -0.074093446, 0.36203596 0.15345182 -0.074093446, -0.26455212 0.15344432 -0.011793479, 0.21546301 0.15345086 -0.07288824, -0.25664091 0.15644544 -0.028967157, -0.25494945 0.15644535 -0.028187975, -0.25845188 0.15644541 -0.029401287, -0.26031294 0.15644541 -0.029473886, -0.26215208 0.15644532 -0.029182151, -0.26389915 0.15644532 -0.028537109, -0.26548684 0.15644524 -0.027563438, -0.26685393 0.15644512 -0.026299015, -0.26794815 0.15644506 -0.02479209, -0.26872736 0.15644494 -0.02310057, -0.26916152 0.15644479 -0.021289602, -0.26923412 0.15644473 -0.019428566, -0.2689423 0.15644459 -0.017589346, -0.26829728 0.15644462 -0.015842214, -0.26732367 0.15644446 -0.014254704, -0.26605916 0.15644443 -0.012887463, -0.26455227 0.15644443 -0.011793241, -0.36700097 0.1544469 -0.068490848, -0.36580434 0.15444694 -0.068636015, -0.36467716 0.1544469 -0.069063529, -0.36368528 0.15444696 -0.069748178, -0.36288592 0.15444696 -0.070650414, -0.36232585 0.15444715 -0.071717814, -0.36203736 0.15444718 -0.072888032, -0.36203736 0.15444727 -0.074093297, -0.36232573 0.15444727 -0.075263813, -0.36288604 0.15444735 -0.076331213, -0.36368528 0.15444738 -0.0772333, -0.36467722 0.15444741 -0.077918127, -0.36580428 0.15444747 -0.078345492, -0.36700085 0.15444741 -0.078490779, -0.20930415 0.15444791 -0.068636015, -0.21050075 0.15444785 -0.068490699, -0.20817718 0.15444802 -0.069063529, -0.20718515 0.154448 -0.069748178, -0.20638579 0.154448 -0.070650443, -0.20582579 0.15444817 -0.071717814, -0.2055372 0.15444811 -0.072888032, -0.20553723 0.15444823 -0.074093297, -0.2058257 0.15444833 -0.075263724, -0.20638588 0.15444838 -0.076331213, -0.20718515 0.15444839 -0.077233419, -0.20817718 0.15444843 -0.077918127, -0.2093042 0.15444849 -0.078345492, -0.21050075 0.15444842 -0.078490779, -0.20930432 0.15443976 0.078364059, -0.21050087 0.15443964 0.078509435, -0.20817716 0.15443978 0.077936605, -0.20718512 0.15443969 0.077251926, -0.20638585 0.15443981 0.076349542, -0.20582579 0.15443988 0.07528238, -0.20553723 0.15443999 0.074111983, -0.20553723 0.15443999 0.072906598, -0.20582573 0.15444005 0.071736291, -0.20638588 0.15444003 0.070668921, -0.2071851 0.15444012 0.069766834, -0.20817712 0.15444015 0.069082007, -0.20930415 0.15444015 0.068654492, -0.21050081 0.15444028 0.068509236, -0.36580431 0.15443879 0.07836397, -0.36700085 0.1544386 0.078509435, -0.36467731 0.15443879 0.077936456, -0.36368528 0.15443876 0.077251926, -0.36288592 0.1544387 0.076349691, -0.36232585 0.15443881 0.07528238, -0.36203736 0.15443893 0.074111983, -0.3620373 0.15443899 0.072906598, -0.36232588 0.15443905 0.071736082, -0.36288592 0.15443903 0.070668921, -0.36368531 0.15443915 0.069766745, -0.36467719 0.15443912 0.069081917, -0.36580434 0.15443921 0.068654492, -0.36700091 0.15443926 0.068509236, 0.3681961 0.15445164 -0.068636164, 0.36699942 0.15445168 -0.068490759, 0.36932305 0.1544517 -0.0690635, 0.37031505 0.15445176 -0.069748178, 0.37111434 0.1544517 -0.070650414, 0.37167451 0.15445177 -0.071717545, 0.37196311 0.15445182 -0.072888121, 0.37196299 0.15445188 -0.074093297, 0.37167463 0.154452 -0.075263724, 0.37111434 0.15445212 -0.076331213, 0.3703151 0.15445212 -0.077233419, 0.36932316 0.15445215 -0.077918127, 0.36819598 0.15445213 -0.078345492, 0.36699942 0.15445219 -0.078490779, 0.21169597 0.15445058 -0.068636015, 0.21049942 0.1544506 -0.068490759, 0.21282305 0.1544506 -0.069063529, 0.213815 0.15445071 -0.069748178, 0.21461432 0.15445071 -0.070650443, 0.21517447 0.15445077 -0.071717814, 0.21546304 0.15445077 -0.072888121, 0.21546298 0.15445092 -0.074093446, 0.21517453 0.15445095 -0.075263724, 0.2146143 0.15445107 -0.076331213, 0.21381505 0.15445107 -0.077233419, 0.21282299 0.15445113 -0.077918127, 0.21169603 0.15445119 -0.078345492, 0.21049938 0.15445116 -0.078490779, 0.3681961 0.15444334 0.07836397, 0.36699942 0.15444334 0.078509286, 0.36932305 0.15444344 0.077936456, 0.37031505 0.15444346 0.077251717, 0.3711144 0.15444346 0.076349542, 0.37167463 0.15444347 0.07528238, 0.37196311 0.15444356 0.074111983, 0.37196299 0.15444373 0.072906688, 0.37167457 0.1544437 0.071736082, 0.37111434 0.15444377 0.070668921, 0.37031505 0.1544439 0.069766745, 0.3693231 0.1544439 0.069082007, 0.36819601 0.15444392 0.068654492, 0.36699942 0.15444392 0.068509236, 0.21169595 0.15444249 0.078364059, 0.21049944 0.15444224 0.078509286, 0.21282297 0.15444249 0.077936605, 0.21381499 0.15444249 0.077251926, 0.21461438 0.15444246 0.076349542, 0.21517453 0.15444246 0.07528238, 0.21546292 0.15444271 0.074111983, 0.21546298 0.15444262 0.072906598, 0.21517454 0.15444271 0.071736082, 0.21461444 0.15444268 0.070668831, 0.21381497 0.15444297 0.069766745, 0.21282306 0.15444291 0.069082007, 0.21169595 0.15444297 0.068654492, 0.21049944 0.15444291 0.068509236, -0.41100037 0.082638472 -0.014681086, -0.4110004 0.082465455 -0.015383229, -0.41100013 0.043443292 -0.010146812, -0.4110004 0.085442007 0.012755379, -0.4110004 0.085443467 -0.01274465, -0.41100037 0.084724069 0.012842521, -0.4110004 0.08472541 -0.012831822, -0.4110004 0.086160004 0.012842521, -0.41099977 -0.032561466 0.075650141, -0.41099969 -0.029489607 0.064256296, -0.41099963 -0.03256093 0.064255968, -0.41099969 -0.024238542 0.086919025, -0.41100037 0.0824655 -0.016106471, -0.4110004 0.086161375 -0.012831673, -0.41100013 0.038318351 0.13200288, -0.4110001 0.03799583 0.12910219, -0.4110001 0.036673769 0.12963615, -0.41100037 0.082638636 -0.016808674, -0.4110001 0.03910324 0.12849899, -0.4110004 0.086837664 -0.013088092, -0.4110001 0.040044218 0.12765931, -0.41100058 0.087431431 0.013509974, -0.41100046 0.086836278 0.013099149, -0.4110001 0.0407691 0.12662743, -0.41100037 0.082974717 -0.017448917, -0.4110004 0.087432817 -0.013499007, -0.4110004 0.087912455 -0.014040247, -0.4110004 0.087910846 0.014051303, -0.4110004 0.08824864 -0.014680639, -0.4110004 0.088246986 0.014691576, -0.4110004 0.088421717 -0.015382871, -0.4110004 0.088419989 0.015393987, -0.41100004 0.034809038 0.11861919, -0.41100004 0.029436499 0.1081811, -0.4110001 0.034260526 0.11876406, -0.4110001 0.035369575 0.11853184, -0.41100007 0.035936028 0.11850269, -0.4110001 0.037188798 0.11864714, -0.4110001 0.038375735 0.11907353, -0.4110001 0.039434388 0.11975898, -0.41100004 0.029435918 0.12071301, -0.41099972 -0.023551464 0.052006558, -0.41099969 -0.029488891 0.05200623, -0.41099975 -0.022414684 0.051868781, -0.41100049 0.084049702 -0.018401042, -0.4110004 0.083455697 -0.041999176, -0.41100037 0.08345443 -0.017990336, -0.41099975 -0.021343946 0.051462606, -0.41100037 0.082976148 -0.042540625, -0.4110001 0.039393276 -0.014197305, -0.4109998 -0.020401508 0.0508122, -0.4110004 0.084725887 -0.01865755, -0.4110004 0.084050938 -0.041588262, -0.41099975 -0.019642189 0.049955234, -0.41100037 0.082640037 -0.043181106, -0.41099975 -0.019109949 0.048941508, -0.41100037 0.085443765 -0.018744692, -0.4110004 0.084727138 -0.041331843, -0.41100037 0.08246702 -0.04388319, -0.4110004 0.086161703 -0.01865755, -0.41100028 0.085445032 -0.041244671, -0.41100037 0.082467094 -0.044606432, -0.4110004 0.086162955 -0.041331843, -0.41100037 0.082640156 -0.045308694, -0.4110004 0.087433115 -0.017990157, -0.4110004 0.086839259 -0.041588202, -0.4110004 0.086837962 -0.018401042, -0.41099969 -0.023550883 0.04250659, -0.41099969 -0.02948764 0.02925624, -0.41099969 -0.029488444 0.042506352, -0.41099975 -0.022414267 0.042644754, -0.4109996 -0.021343544 0.04305084, -0.41099983 -0.020401016 0.043701336, -0.41099966 -0.032558993 0.02925624, -0.41099969 -0.02948688 0.015498862, -0.41099966 -0.032558128 0.015498623, -0.4110004 0.087912574 -0.017448679, -0.4110004 0.087434426 -0.041998938, -0.4110004 0.087914079 -0.042540357, -0.41099992 0.0064420849 0.010150686, -0.41099969 -0.029485196 -0.015501037, -0.4110004 0.08824873 -0.016808286, -0.4110004 0.08825016 -0.043180689, -0.41100004 0.010492176 0.01420112, -0.41099975 -0.019641772 0.044558451, -0.41099975 -0.019109771 0.045572415, -0.41099975 -0.018835783 0.04668428, -0.41100046 0.088421762 -0.016106114, -0.4110004 0.088423267 -0.043882802, -0.41099975 -0.018835783 0.047829345, -0.41099966 -0.032555684 -0.029258594, -0.41099966 -0.032556489 -0.015501246, -0.41099969 -0.029484391 -0.029258475, -0.41099986 0.0064433813 -0.010148838, -0.41099972 -0.023546174 -0.042508289, -0.41099969 -0.029483676 -0.042508528, -0.4110001 0.041431829 0.12421097, -0.41100079 0.15143529 0.13200922, -0.4110001 0.041334704 0.12295355, -0.4110001 0.041239813 0.12545739, -0.41100004 0.029448718 -0.10817657, -0.41099975 -0.019104376 -0.048942283, -0.41099975 -0.019636482 -0.049956307, -0.41099972 -0.024228826 -0.086920634, -0.41099975 -0.022409409 -0.042646185, -0.4110004 0.084051237 -0.046901092, -0.41100037 0.08345595 -0.046490267, -0.41100037 0.082976326 -0.045949146, -0.41099975 -0.021338657 -0.043052033, -0.41100082 0.15268241 0.13157292, -0.41100085 0.15299903 0.13125621, -0.41100082 0.15230308 0.13181098, -0.41100079 0.15188035 0.13195901, -0.41100004 0.029449314 -0.11921583, -0.41100019 0.034273952 -0.11875887, -0.41100004 0.030259371 -0.12038119, -0.41100085 0.15323733 0.13087694, -0.41100004 0.03482236 -0.11861415, -0.41100004 0.035382912 -0.11852686, -0.41099975 -0.020396188 -0.043702647, -0.41100088 0.15338533 0.13045441, -0.41100007 0.035949349 -0.11849751, -0.4110001 0.03720215 -0.11864196, -0.41099992 0.01049377 -0.014198884, -0.41099975 -0.01963678 -0.044559583, -0.4110001 0.039391652 0.014202788, -0.4110001 0.038389161 -0.1190681, -0.41099975 -0.019104585 -0.045573637, -0.4110001 0.039447919 -0.11975332, -0.41099975 -0.018830508 -0.046685413, -0.41100058 0.084727451 -0.047157511, -0.4110001 0.040322676 -0.12066178, -0.41099975 -0.018830359 -0.047830507, -0.4110004 0.085445374 -0.047244653, -0.4110001 0.040967539 -0.12174563, -0.4110004 0.086163282 -0.047157511, -0.41099998 0.041348517 -0.12294774, -0.41099972 -0.023545533 -0.052008376, -0.41099969 -0.029482275 -0.065258577, -0.41099969 -0.029483125 -0.052008614, -0.41099972 -0.02039583 -0.050813422, -0.41099972 -0.021338165 -0.051463947, -0.41099975 -0.022408873 -0.051869974, -0.41100037 0.08345072 0.046500817, -0.4110004 0.082971141 0.045959488, -0.41099998 0.038010284 -0.12909694, -0.41100019 0.038333192 -0.13199748, -0.4110001 0.036688432 -0.12963106, -0.4110001 0.040783331 -0.12662168, -0.4110001 0.040058509 -0.12765361, -0.41100037 0.084045917 0.046911582, -0.4110001 0.039117709 -0.1284935, -0.41100037 0.082635149 0.045318976, -0.4110004 0.086839512 -0.046900943, -0.41100082 0.15145011 -0.13199089, -0.41100022 0.040309221 0.12066738, -0.41100052 0.084722206 0.047168389, -0.4110001 0.041445717 -0.1242051, -0.4110001 0.041254029 -0.12545155, -0.4110004 0.088423356 -0.044606164, -0.4110004 0.088250354 -0.045308515, -0.4110004 0.087914273 -0.045948908, -0.4110004 0.087434739 -0.046490058, -0.41100034 0.082461983 0.044616923, -0.4110001 0.040953875 0.12175117, -0.4110004 0.085440069 0.047255382, -0.41100046 0.082462236 0.043893829, -0.41100082 0.152318 -0.13179274, -0.41100082 0.1518952 -0.13194074, -0.41100043 0.086158022 0.04716824, -0.41100082 0.15325207 -0.13085867, -0.41100082 0.15301381 -0.131238, -0.41100088 0.15339999 -0.13043587, -0.41100085 0.15269715 -0.13155459, -0.4110004 0.082635269 0.043191358, -0.41100046 0.086834252 0.046911582, -0.4110004 0.082971349 0.042550936, -0.41100016 0.0434421 0.010152712, -0.4110004 0.087429449 0.046500877, -0.4110004 0.087909102 0.045959756, -0.4110004 0.088245183 0.045319274, -0.41099966 -0.032553032 -0.075652704, -0.41099966 -0.032553658 -0.065258607, -0.41100046 0.088418305 0.044617221, -0.4110004 0.08841835 0.043893978, -0.41100046 0.083452478 0.018000707, -0.4110004 0.08297278 0.017459378, -0.41100037 0.083450973 0.042009607, -0.41100037 0.084047526 0.018411592, -0.41100037 0.084046185 0.041598931, -0.41100037 0.082636699 0.016818985, -0.4110004 0.084722459 0.041342422, -0.41100046 0.084723756 0.01866813, -0.41100037 0.082463637 0.016116843, -0.4110004 0.085440353 0.041255251, -0.4110004 0.085441679 0.018755302, -0.41100037 0.082463726 0.015393451, -0.4110004 0.086159602 0.018668309, -0.41100049 0.08615838 0.041342422, -0.41100037 0.082636878 0.014691338, -0.41100046 0.086835861 0.01841177, -0.4110004 0.08683458 0.04159908, -0.41100034 0.082972974 0.014050946, -0.4110004 0.087909281 0.042551383, -0.4110004 0.087431088 0.018001094, -0.41100046 0.087429702 0.042010054, -0.4110004 0.087910697 0.017459616, -0.4110004 0.088246897 0.016819343, -0.4110004 0.088245377 0.043191716, -0.4110004 0.088419899 0.016117081, -0.4110004 0.083452627 0.013509706, -0.4110004 0.083454058 -0.013499156, -0.4110004 0.082974598 -0.014040574, -0.41100037 0.084047824 0.013098851, -0.4110004 0.084049299 -0.01308842, -0.41460463 0.038010225 -0.12909676, -0.4159877 0.039279848 -0.12837468, -0.41729417 0.040273398 -0.1273966, -0.41849634 0.040986389 -0.1262071, -0.41948566 0.041369244 -0.12493502, -0.4202258 0.04143998 -0.12367292, -0.42069706 0.041250929 -0.12253232, -0.42093405 0.040883213 -0.12156658, -0.42099187 0.040415257 -0.12078686, -0.420912 0.039847836 -0.12011738, -0.42071363 0.039213806 -0.11957093, -0.42042106 0.038545758 -0.11914884, -0.42005986 0.03787145 -0.11884411, -0.41951257 0.036999792 -0.11859874, -0.4191317 0.03645806 -0.11852102, -0.41874737 0.035949439 -0.11849751, -0.4172973 0.034260526 0.11876397, -0.4180496 0.035088211 0.11856844, -0.41874737 0.035936072 0.11850269, -0.41400039 0.085445359 -0.047244653, -0.41400039 0.086163282 -0.047157511, -0.41400054 0.086839601 -0.046900913, -0.41400042 0.087434754 -0.046490058, -0.41400042 0.087914258 -0.045948699, -0.41400042 0.088250294 -0.045308515, -0.41400054 0.088423446 -0.044606045, -0.41400054 0.088423386 -0.043882802, -0.41400042 0.088250205 -0.043180868, -0.41400054 0.087914065 -0.042540357, -0.41400054 0.0874345 -0.041998938, -0.41400054 0.086839303 -0.041588262, -0.41400054 0.086163059 -0.041331783, -0.41400039 0.085445106 -0.041244581, -0.41400039 0.085443765 -0.018744603, -0.41400042 0.086161688 -0.018657461, -0.41400042 0.086837962 -0.018400922, -0.41400054 0.087433204 -0.017990097, -0.41400042 0.087912634 -0.017448798, -0.41400054 0.088248774 -0.016808376, -0.41400042 0.088421792 -0.016106114, -0.41400054 0.088421717 -0.015382931, -0.41400042 0.088248625 -0.014680728, -0.41400048 0.087912485 -0.014040336, -0.41400054 0.087432876 -0.013499096, -0.41400042 0.086837664 -0.013088241, -0.41400054 0.086161405 -0.012831673, -0.41400054 0.085443467 -0.01274465, -0.41400054 0.085442126 0.012755468, -0.41400054 0.086159959 0.012842521, -0.41400054 0.086836234 0.013099089, -0.41400054 0.087431297 0.013509974, -0.41400042 0.087910846 0.014051303, -0.41400045 0.088246986 0.014691576, -0.41400042 0.088419974 0.015394047, -0.41400054 0.088419929 0.01611729, -0.41400042 0.088246837 0.016819343, -0.41400042 0.087910712 0.017459765, -0.41400054 0.087431177 0.018001154, -0.41400054 0.086835846 0.01841189, -0.41400042 0.086159572 0.018668309, -0.41400039 0.085441649 0.018755302, -0.41400039 0.085440382 0.041255549, -0.41400042 0.086158291 0.041342512, -0.41400042 0.086834595 0.04159908, -0.41400039 0.087429717 0.042009845, -0.41400042 0.087909237 0.042551234, -0.41400042 0.088245362 0.043191567, -0.41400054 0.088418439 0.043893978, -0.41400042 0.08841829 0.044617102, -0.41400042 0.088245258 0.045319274, -0.41400054 0.087909088 0.045959607, -0.41400054 0.087429509 0.046501085, -0.41400054 0.086834326 0.046911821, -0.4140006 0.086158082 0.047168389, -0.41400042 0.085440114 0.047255412, 0.41099986 0.097446352 0.028506145, 0.41099986 0.098163038 0.051093206, 0.41099992 0.09744513 0.051006034, 0.41099986 0.098845989 -0.068637446, 0.4109998 0.099439487 -0.035139427, 0.41099986 0.098844141 -0.035550252, 0.41099986 0.094466761 0.054367498, 0.41099992 0.094639927 0.05506967, 0.41099995 0.081564382 0.053211525, 0.41100001 0.081102267 0.054076031, 0.4109998 0.098840609 0.028162614, 0.41099986 0.098839372 0.051349863, 0.41099986 0.099920869 -0.069589719, 0.41099983 0.099918827 -0.034598127, 0.41099986 0.09944132 -0.069048271, 0.41100073 -0.032547832 -0.075651273, 0.4110007 -0.029467925 -0.06275855, 0.4110007 -0.032548457 -0.062758729, 0.41100058 -0.024196684 -0.08691822, 0.41099986 0.094975933 0.055710211, 0.41100004 0.080480352 0.054833367, 0.41099983 0.10025701 -0.070230201, 0.41099983 0.10025498 -0.033957705, 0.4109998 0.10043022 -0.070932254, 0.41100037 0.038417131 -0.13139139, 0.41100022 0.03832829 -0.12863328, 0.41100031 0.036900997 -0.12921001, 0.41100031 0.039334893 -0.12808464, 0.41099986 0.099434525 0.051760629, 0.4109998 0.099435851 0.027751699, 0.41100028 0.040190235 -0.12732111, 0.41099986 0.10042801 -0.033255592, 0.41100022 0.040849209 -0.12638317, 0.41099983 0.095455617 0.056251362, 0.41099983 0.10042796 -0.0325322, 0.41100028 0.030097604 -0.12117369, 0.41100025 0.034581721 -0.11936168, 0.41100028 0.029954821 -0.12096818, 0.4109998 0.099914089 0.052301899, 0.41099992 0.099915445 0.02721025, 0.41099989 0.10025154 0.026569828, 0.41099986 0.096050769 0.056662247, 0.4110001 0.065772548 0.0695398, 0.41099989 0.10025011 0.052942351, 0.41099992 0.096726865 0.056918785, 0.41100061 -0.021341786 0.051462606, 0.41100052 0.0030247569 0.066000834, 0.41100064 -0.029475003 0.062756285, 0.41100022 0.029941157 0.12097265, 0.41100034 0.034568235 0.11936666, 0.41100022 0.030083999 0.12117799, 0.41100058 -0.019639701 0.044558451, 0.41100055 -0.01910764 0.045572415, 0.41100025 0.029941857 0.10829575, 0.41100055 -0.018833593 0.046684429, 0.41100052 -0.018833682 0.047829345, 0.41100076 -0.019107938 0.048941359, 0.41099986 0.10042469 0.025867805, 0.4109998 0.10042313 0.053644702, 0.41100064 -0.019640058 0.049955234, 0.41100058 -0.020399496 0.0508122, 0.41100031 0.035175294 0.11916555, 0.41100046 0.00315018 0.067113265, 0.41100058 -0.02420643 0.086916551, 0.41099986 0.096055582 -0.03023766, 0.41099983 0.095460176 -0.025139555, 0.41099992 0.095460445 -0.030648574, 0.41099983 0.097444862 0.057006165, 0.41100028 0.029954135 -0.10829113, 0.41100025 0.035188809 -0.11916034, 0.41100022 0.035816491 -0.11903833, 0.41099989 0.094980523 -0.024598315, 0.41099986 0.094980821 -0.031189904, 0.41100022 0.036454722 -0.11899744, 0.41100019 0.037593648 -0.11912899, 0.41100028 0.038672581 -0.11951609, 0.41100031 0.039635062 -0.12013917, 0.41100031 0.03580308 0.1190436, 0.4110007 -0.023543462 -0.052008286, 0.41100067 -0.029468462 -0.052008614, 0.4109998 0.096055403 -0.025550589, 0.41100067 -0.022406682 -0.051869974, 0.41099983 0.094644338 -0.023958042, 0.41099986 0.094644815 -0.031830296, 0.41100019 0.036441386 0.11900286, 0.41100058 -0.021336123 -0.051463947, 0.41099983 0.096731573 -0.02580671, 0.41099986 0.096731737 -0.029981241, 0.41099992 0.09744969 -0.02989395, 0.41099998 0.094471231 -0.02325584, 0.41099983 0.094471782 -0.032532558, 0.41100001 0.081950903 -0.051287845, 0.41100031 0.037580192 0.1191342, 0.41099986 0.097449452 -0.025894001, 0.41100022 0.038659334 0.11952163, 0.41100046 0.0035199225 0.068170145, 0.41099986 0.094471261 -0.022532597, 0.41100004 0.06223692 0.071003899, 0.41100022 0.039621696 0.12014462, 0.41099986 0.098167643 -0.029981241, 0.4109998 0.098167464 -0.02580674, 0.41099992 0.098843813 -0.030237421, 0.41100046 0.0049150884 -0.069908455, 0.41100052 0.0041233599 -0.069116667, 0.41100028 0.040416732 0.12097062, 0.41100013 0.063212305 0.070908174, 0.41100046 0.0035276413 -0.068168715, 0.41100043 0.0041156113 0.069118157, 0.41100049 0.0058631003 -0.070504054, 0.41100016 0.041002929 0.12195601, 0.41099992 0.098843575 -0.025550321, 0.41100013 0.064150244 0.070623651, 0.41099989 0.099439159 -0.030648336, 0.41099992 0.099438816 -0.025139466, 0.41099992 0.099918738 -0.031189665, 0.41100049 0.0069199204 -0.070873693, 0.41100046 0.0049073696 0.069910035, 0.41100052 0.0031577349 -0.067111924, 0.4109998 0.099918395 -0.024597988, 0.4109998 0.10025495 -0.031829938, 0.4109998 0.10025446 -0.023957595, 0.41100052 -0.019102499 -0.045573637, 0.41100052 0.0030322224 -0.065999374, 0.4110007 -0.019634709 -0.044559792, 0.41100052 -0.018828377 -0.046685413, 0.41100058 -0.018828288 -0.047830507, 0.41100058 -0.01910229 -0.048942253, 0.41100058 -0.019634336 -0.049956307, 0.41100064 -0.020393714 -0.050813422, 0.41100052 0.0058551431 0.070505723, 0.41100049 0.0080325603 -0.070999011, 0.41099989 0.10042737 -0.023255333, 0.41100028 0.038313895 0.12863873, 0.41100028 0.038402393 0.13139664, 0.41100031 0.036886543 0.12921502, 0.41100016 0.040834993 0.12638868, 0.41100016 0.040175945 0.12732695, 0.41100061 -0.023543939 -0.04250811, 0.41100061 -0.029469609 -0.031758562, 0.41100064 -0.029469043 -0.042508528, 0.41100022 0.039320678 0.12809013, 0.41100058 -0.022407249 -0.042646185, 0.41100058 -0.021336526 -0.043052241, 0.41100058 -0.020394072 -0.043702647, 0.41099972 0.098162889 0.056918874, 0.41099975 0.10764551 0.13139649, 0.4109998 0.098839089 0.056662366, 0.4109998 0.099434301 0.05625169, 0.41100049 0.0069119632 0.070875719, 0.4110001 0.065014735 0.070161715, 0.41100028 0.041349202 0.12304889, 0.41100022 0.041437551 0.1241921, 0.4110004 0.023952007 -0.072998241, 0.41100028 0.041262835 0.12532507, 0.41099986 0.10042742 -0.02253215, 0.41100076 -0.032551199 -0.015501395, 0.41100064 -0.032550201 -0.031758651, 0.41099975 0.10764739 0.13140054, 0.41100034 0.023952067 -0.070998088, 0.4109998 0.099913925 0.05571039, 0.41099983 0.10024993 0.055070058, 0.41099972 0.10042307 0.054367736, 0.41099992 0.10042466 0.025144622, 0.4109998 0.10042533 0.015867814, 0.41100037 0.026952073 -0.072997913, 0.41099986 0.10042533 0.015144572, 0.41100073 -0.029470548 -0.015501007, 0.41099951 0.15329485 0.13075878, 0.41099951 0.15311767 0.13109909, 0.41099951 0.15340392 0.13039111, 0.41099951 0.15287881 0.13139902, 0.41099977 0.10766026 -0.13138331, 0.41099948 0.1528936 -0.13138069, 0.41099992 0.08194524 0.051297858, 0.41099986 0.094469085 0.015867457, 0.41099986 0.094469115 0.015144184, 0.41099986 0.094642207 0.014442042, 0.41099992 0.094644189 -0.021830454, 0.41100064 -0.029472232 0.015498862, 0.41100022 0.041363135 -0.12304322, 0.41100022 0.041016698 -0.12195019, 0.41100028 0.041451365 -0.12418614, 0.41100022 0.041277066 -0.12531932, 0.41099975 0.1076622 -0.13138737, 0.41100031 0.02394402 0.071001783, 0.41100025 0.023943961 0.073002085, 0.41100049 0.0080245435 0.071000949, 0.41100004 0.062244967 -0.070996001, 0.41100034 0.040430322 -0.12096505, 0.41100034 0.026951954 -0.070998028, 0.41100004 0.063220426 -0.070899919, 0.41100007 0.064158276 -0.070615247, 0.41099986 0.096055076 -0.020237789, 0.41099992 0.095457911 0.01326032, 0.41099986 0.095459864 -0.020648524, 0.4109998 0.094978347 0.013801798, 0.41099983 0.094980329 -0.021189883, 0.41100067 -0.032552853 0.015498832, 0.41100064 -0.029473141 0.031756237, 0.41100064 -0.032553703 0.031756148, 0.41100064 -0.023548752 0.04250659, 0.41100067 -0.029473767 0.042506352, 0.41099986 0.096053228 0.012849435, 0.41100067 -0.022412047 0.042644754, 0.41099986 0.096731111 -0.01998128, 0.4109998 0.096729413 0.012593165, 0.4109998 0.097449169 -0.019894019, 0.41100067 -0.021341428 0.04305084, 0.41099986 0.095462784 -0.07353963, 0.41100004 0.065022752 -0.070153221, 0.41099986 0.094983205 -0.07299839, 0.41100004 0.065780312 -0.069531307, 0.41099986 0.097447306 0.012506112, 0.41099986 0.096058056 -0.073950514, 0.41099986 0.094647035 -0.072357997, 0.41099998 0.098167062 -0.019981161, 0.41099992 0.098165214 0.012593165, 0.41099998 0.098843336 -0.02023755, 0.41099986 0.096734181 -0.074206933, 0.4109996 0.15313247 -0.13108052, 0.41099957 0.15330961 -0.13074039, 0.41099983 0.098841459 0.012849674, 0.41099992 0.094473943 -0.071655735, 0.41099951 0.15341872 -0.13037263, 0.41099986 0.097452253 -0.074293926, 0.41099983 0.099438637 -0.020648375, 0.41099992 0.099436671 0.013260558, 0.41100064 -0.020399034 0.043701336, 0.4109998 0.09991625 0.013801888, 0.41099989 0.094473988 -0.070932701, 0.4109998 0.099918231 -0.021189705, 0.4109998 0.10025439 -0.021830097, 0.4109998 0.098170266 -0.074206814, 0.41099992 0.10025223 0.01444228, 0.4109998 0.098846421 -0.073950306, 0.41099983 0.09464702 -0.07023035, 0.41100004 0.080486581 -0.054823413, 0.41099983 0.094983071 -0.069589958, 0.4109998 0.099441603 -0.073539302, 0.41099983 0.09546262 -0.069048539, 0.41099986 0.099921077 -0.072998032, 0.4109998 0.095457733 0.017751381, 0.41099986 0.09545742 0.0232604, 0.41099986 0.094978139 0.017210051, 0.41099998 0.081108406 -0.05406557, 0.41099986 0.094977781 0.023801729, 0.41099986 0.094642058 0.016569689, 0.4109998 0.096057817 -0.068637714, 0.4109998 0.096052676 0.022849515, 0.4109998 0.096052915 0.018162325, 0.41099983 0.094641685 0.024442121, 0.4109998 0.1002572 -0.072357669, 0.41099992 0.081570417 -0.053201213, 0.4109998 0.096728921 0.022593096, 0.41099983 0.096733928 -0.068381384, 0.4109998 0.096728995 0.018418893, 0.4109998 0.097447053 0.018505976, 0.41099986 0.094468519 0.025144234, 0.41099986 0.097446725 0.022506043, 0.41099986 0.10043016 -0.071655408, 0.41099986 0.098164737 0.022593275, 0.41099986 0.098164901 0.018418893, 0.41099986 0.098841101 0.018162474, 0.41099992 0.097451836 -0.068293944, 0.41099998 0.081854954 -0.052263275, 0.41099983 0.098840877 0.022849694, 0.41099992 0.099436402 0.017751649, 0.41099998 0.099436134 0.023260459, 0.41099983 0.099915996 0.01721032, 0.41099986 0.099915594 0.023801938, 0.41099983 0.10025212 0.016569927, 0.4109998 0.10025164 0.02444236, 0.41100061 -0.022412464 0.051868662, 0.41100064 -0.023549348 0.052006438, 0.41099995 0.094468489 0.025867358, 0.4110007 -0.029474318 0.05200623, 0.41099986 0.094641551 0.02656953, 0.41099986 0.094977647 0.027210101, 0.41099986 0.095457062 0.02775155, 0.41099986 0.096052215 0.028162256, 0.41100082 -0.03255631 0.075648621, 0.4110007 -0.032555565 0.062756106, 0.41100034 0.026943877 0.071002081, 0.41100028 0.026943967 0.073002085, 0.4109998 0.095460683 -0.035139605, 0.41099983 0.094981045 -0.034598276, 0.41099983 0.096055955 -0.03555049, 0.41099989 0.094644859 -0.033957943, 0.4109998 0.096732154 -0.035806909, 0.41099992 0.094471768 -0.033255801, 0.41099992 0.095455676 0.05176048, 0.41099983 0.094976246 0.05230172, 0.4109998 0.097450122 -0.035893962, 0.41099998 0.096051037 0.051349625, 0.41099986 0.098169833 -0.068381384, 0.4109998 0.09816803 -0.035806701, 0.41099975 0.094640121 0.052941993, 0.41099986 0.096728489 0.028418675, 0.41099986 0.096727237 0.051093206, 0.41099986 0.094466895 0.053644195, 0.41099998 0.081849054 0.052273616, 0.41099986 0.098164394 0.028418973, 0.41471013 0.038313836 0.12863873, 0.41603544 0.039524779 0.12793835, 0.41729 0.040461749 0.12697481, 0.41841406 0.041098982 0.12582015, 0.41931501 0.041405275 0.1246004, 0.41990104 0.041419759 0.12354098, 0.42027333 0.041238546 0.12259413, 0.42046434 0.040925652 0.12179174, 0.42051718 0.04053925 0.12113835, 0.42046389 0.040075004 0.12056817, 0.42031726 0.039555565 0.12009118, 0.42009374 0.039004207 0.11970951, 0.41981134 0.038441569 0.1194203, 0.41937318 0.03770265 0.11916448, 0.41892979 0.037047878 0.11903979, 0.41847613 0.036441371 0.11900286, 0.41681617 0.034581691 -0.11936168, 0.41768152 0.035500646 -0.11908944, 0.41847613 0.036454692 -0.11899738, 0.41399977 0.097451895 -0.068293944, 0.41399989 0.098169789 -0.068381175, 0.41399989 0.098846003 -0.068637446, 0.41399989 0.09944129 -0.069048271, 0.41399983 0.099920943 -0.0695896, 0.41399994 0.10025698 -0.070230201, 0.41399983 0.10043019 -0.070932373, 0.41399983 0.10043019 -0.071655408, 0.41399986 0.10025714 -0.072357669, 0.4139998 0.099921063 -0.072998241, 0.41399994 0.099441573 -0.073539302, 0.41399989 0.098846301 -0.073950246, 0.41399989 0.098170146 -0.074206725, 0.41399989 0.097452179 -0.074293926, 0.41399989 0.097449586 -0.02989395, 0.41399983 0.098167673 -0.029981121, 0.41399989 0.098843858 -0.03023766, 0.41399986 0.099439144 -0.030648336, 0.41399983 0.099918768 -0.031189665, 0.41399989 0.10025485 -0.031829938, 0.41399983 0.10042806 -0.0325322, 0.41399989 0.10042807 -0.033255413, 0.41399986 0.10025491 -0.033957615, 0.41399989 0.099918902 -0.034598127, 0.41399994 0.099439397 -0.035139427, 0.41399989 0.098844185 -0.035550281, 0.41399989 0.098167986 -0.035806701, 0.41399983 0.097450048 -0.035893962, 0.41399983 0.097449124 -0.019894019, 0.41399983 0.098167107 -0.019981131, 0.41399983 0.098843411 -0.02023755, 0.41399989 0.099438548 -0.020648375, 0.41399994 0.099918142 -0.021189705, 0.41399983 0.10025428 -0.021829918, 0.41399983 0.10042746 -0.02253218, 0.4139998 0.10042749 -0.023255333, 0.41399994 0.10025439 -0.023957595, 0.41399986 0.09991841 -0.024597988, 0.4139998 0.099438861 -0.025139317, 0.41399994 0.098843649 -0.025550291, 0.41399989 0.098167434 -0.02580671, 0.41399994 0.097449422 -0.025893912, 0.41399989 0.097446933 0.018505976, 0.41399983 0.098164931 0.018418893, 0.41399989 0.098841116 0.018162474, 0.41399989 0.099436402 0.017751649, 0.41399983 0.099916071 0.01721032, 0.41399974 0.10025215 0.016569957, 0.41399994 0.10042533 0.015867814, 0.41399989 0.10042529 0.015144572, 0.41399986 0.10025218 0.014442429, 0.41399986 0.099916175 0.013801947, 0.41399994 0.099436656 0.013260558, 0.41399989 0.098841503 0.012849793, 0.41399989 0.098165259 0.012593254, 0.41399994 0.097447321 0.012506112, 0.41399983 0.097446367 0.028506145, 0.41399983 0.09816432 0.028418794, 0.41399994 0.09884046 0.028162614, 0.41399989 0.099435762 0.027751699, 0.41399983 0.099915504 0.02721037, 0.41399994 0.10025159 0.026569977, 0.4139998 0.10042477 0.025867864, 0.41399983 0.10042472 0.025144622, 0.41399989 0.10025169 0.024442419, 0.41399989 0.099915609 0.023801938, 0.41399989 0.099436149 0.023260608, 0.41399989 0.098840937 0.022849724, 0.41399994 0.098164752 0.022593305, 0.41399983 0.097446769 0.022506043, 0.41399989 0.097444877 0.057006076, 0.41399983 0.098162845 0.056918874, 0.41399994 0.098839059 0.056662485, 0.41399986 0.099434257 0.05625169, 0.41399983 0.09991388 0.05571039, 0.41399994 0.10024992 0.055069968, 0.41399994 0.10042304 0.054367855, 0.41399983 0.10042307 0.053644612, 0.41399977 0.10025023 0.05294247, 0.41399983 0.099914178 0.052302107, 0.41399986 0.099434465 0.051760629, 0.41399977 0.098839402 0.051349863, 0.41399977 0.098163202 0.051093325, 0.41399989 0.097445115 0.051005974, 0.40982896 -0.015559435 0.13199975, 0.39017221 -0.015559644 0.13199975, 0.41000062 -0.015730977 0.13199975, 0.41000041 0.023440585 0.13200207, 0.41100034 0.024440587 0.13200207, 0.41100025 0.035170257 0.13200267, 0.40999958 0.13461213 0.13200818, 0.40982804 0.1344406 0.13200815, 0.41099951 0.15144061 0.13200922, 0.40999952 0.15144059 0.13200922, 0.39017123 0.13444045 0.13200818, 0.38699958 0.13444044 0.13200818, 0.38999969 0.13144052 0.13200803, 0.38699999 0.059440479 0.13200389, 0.27100012 0.059439614 0.1320041, 0.26799998 0.06243965 0.13200419, -0.39017138 -0.015564576 0.13199975, -0.40982816 -0.015564695 0.13199975, -0.40999982 -0.015736222 0.13199975, -0.41000006 0.023435324 0.13200186, -0.4110001 0.034665048 0.13200267, -0.41099998 0.024435341 0.13200186, 0.26799962 0.13143966 0.13200803, -0.39017236 0.13443546 0.13200815, 0.27099961 0.13443972 0.13200818, -0.40982917 0.13443531 0.13200818, -0.41000077 0.13460694 0.13200818, -0.41000086 0.15143532 0.13200922, 0.39000008 0.062440485 0.13200434, -0.41099969 -0.02618812 0.089300022, -0.41099969 -0.026311725 0.089161649, -0.41099963 -0.034061 0.11399879, -0.41099966 -0.026041061 0.089413151, -0.41099969 -0.025875553 0.089497343, -0.41099951 -0.034059122 0.078672215, -0.41099998 0.02661483 0.12041749, -0.41100004 0.02651681 0.12024064, -0.41100004 0.026456371 0.12004794, -0.41099998 0.023436204 0.11400194, -0.41100004 0.024436206 0.11500205, -0.41100004 0.026436493 0.11089884, -0.41099998 0.026436046 0.11984684, -0.41099998 0.025804758 0.10996909, -0.41100001 0.026014119 0.11008261, -0.41100004 0.026408166 0.11066245, -0.41100004 0.026190773 0.11024208, -0.41100001 0.02632466 0.1104394, 0.41100064 -0.026446611 0.08893244, 0.41100073 -0.03405571 0.11399879, 0.41100076 -0.034053773 0.078666732, 0.41100064 -0.025574178 0.089601859, 0.41100064 -0.025904939 0.08943437, 0.41100058 -0.026199132 0.089208707, 0.41100046 0.025676131 0.1098368, 0.4110004 0.023441523 0.11400194, 0.41100028 0.026449531 0.11038302, 0.4110004 0.026717559 0.11077736, 0.41100034 0.026095614 0.11006339, 0.41100037 0.026884943 0.11122368, 0.41100043 0.026941717 0.11169715, 0.41100034 0.024441525 0.11500205, 0.41100037 0.02694127 0.11953346, 0.41100028 0.026982114 0.11993565, 0.41100043 0.027298883 0.12067492, 0.41100025 0.027103037 0.12032123, -0.40999982 -0.016328633 0.1329997, -0.40999982 -0.016088307 0.13269313, -0.41000006 0.023435324 0.13300209, -0.40999964 -0.015889719 0.13235788, 0.41000065 -0.015884504 0.13235788, 0.41000035 0.02344057 0.13300188, 0.41000059 -0.016083106 0.13269301, 0.41000059 -0.016323358 0.13299961, -0.40982816 -0.015549883 -0.13200034, -0.39017147 -0.015549749 -0.13200034, -0.40999982 -0.015721455 -0.13200034, -0.41000006 0.023450166 -0.1319982, -0.41100004 0.024450019 -0.13199808, -0.41100007 0.034679726 -0.13199748, -0.41000077 0.13462177 -0.131992, -0.40982923 0.13445024 -0.131992, -0.41000089 0.15145022 -0.13199116, 0.40982905 -0.015544638 -0.13200034, 0.41000059 -0.015716165 -0.13200034, 0.39017209 -0.015544757 -0.13200034, 0.41000041 0.023455366 -0.13199808, 0.4110004 0.035184965 -0.13199748, 0.41100034 0.024455428 -0.13199808, -0.39017242 0.13445036 -0.131992, 0.39017126 0.13445526 -0.131992, 0.40982804 0.13445544 -0.131992, 0.40999967 0.134627 -0.131992, 0.40999958 0.15145545 -0.13199116, 0.41099957 0.15145545 -0.13199116, 0.41100064 -0.026189074 -0.089210525, 0.41100061 -0.026436567 -0.088934347, 0.41100073 -0.034042895 -0.11400144, 0.41100058 -0.02589491 -0.089436278, 0.41100058 -0.025564149 -0.089603767, 0.41100064 -0.034044832 -0.078669474, 0.41100028 0.027312472 -0.12067072, 0.41100028 0.027116433 -0.12031706, 0.41100031 0.026995659 -0.11993153, 0.41100028 0.023454487 -0.1139981, 0.41100028 0.026954725 -0.11952926, 0.41100034 0.024454474 -0.11499806, 0.41100028 0.026954338 -0.11169292, 0.41100034 0.025688484 -0.10983275, 0.41100025 0.02689752 -0.11121963, 0.41100028 0.026107982 -0.11005943, 0.41100025 0.02673012 -0.11077307, 0.41100034 0.026461884 -0.11037908, -0.41099969 -0.026301667 -0.089163497, -0.41099963 -0.03404811 -0.11400144, -0.41099963 -0.034050211 -0.078675106, -0.41099969 -0.02586551 -0.08949922, -0.41099969 -0.026030988 -0.089415029, -0.41099963 -0.026178107 -0.089301929, -0.41100004 0.026026562 -0.11007856, -0.41099998 0.026203215 -0.1102383, -0.41100004 0.025817186 -0.10996519, -0.41099998 0.026337042 -0.11043526, -0.41100004 0.026420549 -0.1106583, -0.41100004 0.026448965 -0.11089478, -0.41099998 0.023449138 -0.1139981, -0.41099998 0.02444917 -0.114998, -0.41100004 0.026449546 -0.11984272, -0.41100004 0.02662833 -0.12041335, -0.41099998 0.02653037 -0.12023665, -0.41100004 0.026469901 -0.1200438, -0.41000077 0.15338519 0.13045426, -0.41000089 0.1532373 0.13087694, -0.41000083 0.1529991 0.13125606, -0.41000086 0.15268236 0.13157292, -0.41000077 0.15230313 0.13181119, -0.41000077 0.15188044 0.13195901, -0.41000083 0.15189521 -0.13194083, -0.41000089 0.15231793 -0.13179274, -0.41000077 0.15269721 -0.13155459, -0.41000089 0.1530138 -0.131238, -0.41000077 0.15325205 -0.13085867, -0.41000077 0.1534 -0.13043587, 0.41000077 -0.03404288 -0.11440174, 0.41000074 -0.034042835 -0.11500137, -0.40959927 -0.034061044 0.11399879, -0.40999958 -0.034060985 0.11439909, 0.40960041 -0.03404288 -0.11400144, -0.4099997 -0.034061059 0.11499859, 0.41000071 -0.03405574 0.11439909, -0.39039999 -0.034060806 0.11399864, -0.17959918 -0.034059525 0.11399879, -0.16039996 -0.034059376 0.11399879, 0.16040103 -0.034057438 0.11399879, 0.17960031 -0.0340572 0.11399879, 0.3904011 -0.034055859 0.11399864, 0.40960041 -0.034055695 0.11399879, -0.40999958 -0.034048155 -0.11440174, -0.40959924 -0.0340482 -0.11400144, -0.39040014 -0.034047946 -0.11400144, -0.1795992 -0.034046642 -0.11400144, -0.1603999 -0.034046531 -0.11400144, 0.16040097 -0.034044504 -0.11400144, 0.1796003 -0.034044378 -0.11400144, 0.3904011 -0.034043014 -0.11400144, 0.4110007 -0.034052595 0.058233961, 0.4110007 -0.034051403 0.036278084, 0.4110007 -0.034049943 0.010976568, 0.4110007 -0.034048662 -0.01097919, 0.4110007 -0.034047216 -0.036280885, 0.4110007 -0.03404595 -0.058236614, -0.41099966 -0.03405118 -0.060777381, -0.41099963 -0.034052655 -0.033740148, -0.41099963 -0.034053952 -0.01101993, -0.41099951 -0.034055218 0.011017159, -0.41099963 -0.034056395 0.033737406, -0.41099966 -0.03405793 0.060774371, 0.41000071 -0.03405574 0.11499868, -0.40999958 -0.034048155 -0.11500137, -0.41099963 -0.032782212 0.059498861, -0.41099966 -0.032489315 0.058791891, -0.41099966 -0.032657847 0.059347466, -0.41099966 -0.03256546 0.059174493, -0.41099975 -0.032508463 0.058987036, -0.41099966 -0.032507166 0.035525247, -0.41099966 -0.032656506 0.03516458, -0.41099966 -0.032488003 0.035720274, -0.41099963 -0.032564133 0.035337552, -0.41099969 -0.032780856 0.035013303, -0.41099963 -0.0327795 0.0097415298, -0.41099963 -0.032486513 0.0090345293, -0.41099969 -0.03265509 0.0095900446, -0.41099963 -0.032562628 0.0094173104, -0.41099966 -0.032505706 0.0092296749, -0.41099975 -0.032504648 -0.0092322379, -0.41099963 -0.032561585 -0.0094197839, -0.41099963 -0.0324855 -0.0090370625, -0.41099963 -0.032653973 -0.009592846, -0.41099969 -0.032778293 -0.0097443014, -0.41099969 -0.032652527 -0.035167322, -0.41099966 -0.03256011 -0.035340205, -0.41099963 -0.032776877 -0.035015717, -0.41099969 -0.032503158 -0.03552787, -0.41099966 -0.032483995 -0.035722986, -0.41099966 -0.032501951 -0.05898951, -0.41099966 -0.032558814 -0.059177145, -0.41099966 -0.032482699 -0.058794424, -0.41099975 -0.032651156 -0.059349969, -0.41099966 -0.032775521 -0.059501722, 0.41100067 -0.032805189 -0.056941405, 0.4110007 -0.032620475 -0.056595579, 0.4110007 -0.033053964 -0.057244554, 0.41100076 -0.032506689 -0.056220368, 0.41100079 -0.032468304 -0.055830255, 0.41100067 -0.032469258 -0.038687035, 0.41100076 -0.032507703 -0.038296953, 0.41100079 -0.032806322 -0.037576094, 0.41100067 -0.032621488 -0.037921682, 0.4110007 -0.033055082 -0.037272945, 0.41100076 -0.032807916 -0.0096840411, 0.41100067 -0.032623112 -0.0093380958, 0.4110007 -0.033056587 -0.0099870712, 0.4110007 -0.032509357 -0.008962974, 0.4110007 -0.032470912 -0.0085728616, 0.41100067 -0.032624125 0.009335652, 0.41100067 -0.032809049 0.0096813291, 0.41100073 -0.032510385 0.0089603215, 0.41100076 -0.03247194 0.0085701793, 0.41100073 -0.033057779 0.0099844784, 0.41100076 -0.032810643 0.037573382, 0.4110007 -0.03262578 0.037919119, 0.41100076 -0.033059403 0.037270263, 0.41100067 -0.032511935 0.0382943, 0.4110007 -0.032473549 0.038684532, 0.41100067 -0.032626733 0.056592986, 0.41100076 -0.032811627 0.056938872, 0.41100067 -0.032512948 0.056217715, 0.41100073 -0.032474548 0.055827811, 0.4110007 -0.033060297 0.057241842, -0.41000006 0.02345024 -0.13299812, -0.4099997 -0.015874848 -0.13235869, -0.40999982 -0.016073391 -0.13269378, -0.40999982 -0.016313702 -0.13300036, -0.41100001 0.024450213 -0.13299812, -0.4099997 -0.03455089 -0.1150014, -0.41099963 -0.034550935 -0.11400144, -0.41700003 0.024449185 -0.11499806, -0.41700003 0.024450198 -0.13299812, -0.41699997 0.023449033 -0.11399819, -0.41699967 -0.034550875 -0.11400144, -0.41099957 -0.034549817 -0.13400139, -0.4099997 -0.034549728 -0.13300146, -0.41099998 0.023450315 -0.1339982, -0.41699991 0.023450106 -0.1339982, -0.41699961 -0.034549832 -0.13400148, -0.41099963 -0.035549805 -0.13300146, -0.41800007 0.02345027 -0.13299812, -0.41799966 -0.034549817 -0.13300146, -0.4179996 -0.027892649 -0.12212993, -0.41799954 -0.03455092 -0.1150014, -0.41799989 0.016791761 -0.12212728, -0.41799974 -0.027492926 -0.12258084, -0.41799989 0.016392142 -0.12257825, -0.41799989 0.020507023 -0.12257825, -0.41799995 0.020107359 -0.12212707, -0.41799995 0.023449183 -0.11499821, -0.41799963 -0.028388664 -0.12178759, -0.41799989 0.019611388 -0.12178488, -0.41799963 -0.027212873 -0.12311454, -0.41799989 0.016112119 -0.12311228, -0.41800001 0.015967831 -0.12369736, -0.41799992 0.020787194 -0.12311183, -0.41799989 0.019047722 -0.12157114, -0.41799974 -0.028952226 -0.12157364, -0.41799995 0.020931318 -0.123697, -0.4179996 -0.02706857 -0.12369971, -0.41799989 0.018449485 -0.12149854, -0.4179996 -0.029550537 -0.12150116, -0.41799992 0.017851233 -0.12157114, -0.41799963 -0.027068555 -0.12430237, -0.41799989 0.015967891 -0.12430005, -0.41799989 0.017287672 -0.12178488, -0.4179996 -0.030148745 -0.121574, -0.41799966 -0.027212843 -0.12488745, -0.41799989 0.016112193 -0.12488504, -0.41799954 -0.030712277 -0.12178759, -0.4179996 -0.027492777 -0.12542124, -0.41799989 0.016392216 -0.12541877, -0.41799992 0.01679191 -0.12586994, -0.41799971 -0.031208247 -0.12212993, -0.41799963 -0.027892366 -0.12587236, -0.41799971 -0.031607896 -0.12258105, -0.4179996 -0.031887949 -0.12311478, -0.4179996 -0.032032177 -0.12369998, -0.41800001 0.018449873 -0.12649833, -0.41800001 0.019048184 -0.12642573, -0.41799989 0.019611567 -0.12621199, -0.41799989 0.020107552 -0.12586959, -0.41799992 0.020507172 -0.12541841, -0.41799992 0.020787194 -0.12488483, -0.41800007 0.020931453 -0.12429972, -0.41800001 0.017288044 -0.12621222, -0.41799992 0.017851576 -0.12642594, -0.41799963 -0.029550239 -0.12650116, -0.41799963 -0.028951973 -0.12642859, -0.41799966 -0.02838847 -0.12621473, -0.4179996 -0.032032132 -0.12430267, -0.4179996 -0.031887874 -0.12488781, -0.4179996 -0.031607851 -0.12542133, -0.41799963 -0.031208202 -0.12587245, -0.4179996 -0.030712053 -0.12621473, -0.4179996 -0.030148551 -0.12642859, -0.41099995 0.018449575 -0.12149854, -0.41100004 0.019047871 -0.12157114, -0.41099998 0.019611374 -0.12178479, -0.41100007 0.020107493 -0.12212722, -0.41099998 0.020507082 -0.12257825, -0.41099998 0.020787135 -0.12311177, -0.41099998 0.020931467 -0.123697, -0.41099998 0.020931497 -0.12429972, -0.41099998 0.020787299 -0.12488483, -0.41099998 0.020507172 -0.12541862, -0.41099998 0.020107582 -0.12586974, -0.41099998 0.019611657 -0.12621222, -0.41099995 0.019048065 -0.12642573, -0.41099998 0.018449843 -0.12649833, -0.41099969 -0.029550523 -0.12150125, -0.41099969 -0.028952256 -0.12157364, -0.41099969 -0.028388739 -0.12178738, -0.41099969 -0.027892634 -0.12212984, -0.41099969 -0.027492911 -0.12258084, -0.41099969 -0.027212873 -0.12311454, -0.41099969 -0.027068689 -0.12369971, -0.41099969 -0.027068466 -0.12430237, -0.41099977 -0.02721262 -0.12488757, -0.41099969 -0.027492851 -0.12542124, -0.41099966 -0.027892441 -0.12587236, -0.41099969 -0.028388396 -0.12621473, -0.41099969 -0.028951868 -0.12642859, -0.41099969 -0.02955018 -0.12650116, -0.41099966 -0.030148521 -0.12642859, -0.41099966 -0.030712023 -0.12621473, -0.41099963 -0.031208113 -0.12587245, -0.41099966 -0.031607777 -0.12542148, -0.41099966 -0.031887829 -0.12488781, -0.41099966 -0.032032087 -0.12430267, -0.41099969 -0.032032162 -0.12369998, -0.41099966 -0.031887963 -0.12311478, -0.41099969 -0.031607836 -0.12258111, -0.41099969 -0.031208247 -0.12213008, -0.41099966 -0.030712321 -0.12178774, -0.41099966 -0.030148789 -0.121574, -0.41099995 0.017851561 -0.12642594, -0.41100004 0.017288074 -0.12621222, -0.41100004 0.016792044 -0.12586994, -0.41099998 0.016392305 -0.12541877, -0.41099995 0.016112238 -0.12488504, -0.41099995 0.01596792 -0.12429987, -0.41099995 0.01596792 -0.12369715, -0.41099998 0.016112059 -0.12311201, -0.41099995 0.016392142 -0.12257843, -0.41099998 0.016791776 -0.12212746, -0.41099998 0.017287701 -0.12178497, -0.41099995 0.017851263 -0.12157114, -0.41699958 -0.035549924 -0.13300158, -0.41099963 -0.035550922 -0.11500151, -0.41699955 -0.035550982 -0.11500151, 0.41099951 0.15185408 -0.13195087, 0.40999958 0.1519005 -0.13194074, 0.41099945 0.15223663 -0.13183202, 0.40999952 0.15232319 -0.13179283, 0.41099945 0.15258788 -0.13163947, 0.40999955 0.15270238 -0.13155453, 0.40999946 0.15301906 -0.131238, 0.40999952 0.15325736 -0.13085867, 0.40999946 0.15340529 -0.13043587, 0.40999946 0.15339051 0.13045441, 0.40999952 0.15324262 0.13087694, 0.40999952 0.15300432 0.13125606, 0.40999946 0.15268765 0.13157277, 0.41099951 0.152573 0.13165779, 0.40999952 0.15230843 0.13181119, 0.41099948 0.15222183 0.13185032, 0.40999952 0.15188566 0.13195901, 0.41099948 0.15183924 0.13196908, -0.4099997 -0.034563735 0.11499874, -0.41099966 -0.034563735 0.11399879, -0.41100004 0.024435267 0.13300209, -0.41700003 0.023436263 0.11400194, -0.41699961 -0.034563765 0.11399879, -0.41699991 0.024435222 0.13300209, -0.41700003 0.02443634 0.11500205, -0.41099963 -0.035563797 0.11499859, -0.4099997 -0.034564748 0.13299878, -0.41099963 -0.03556481 0.13299851, -0.41699967 -0.035563752 0.11499868, -0.41699955 -0.03556484 0.13299851, -0.41099963 -0.034564927 0.13399868, -0.4179996 -0.034564823 0.13299866, -0.41799957 -0.034563839 0.11499868, -0.41799966 -0.027906746 0.12587024, -0.41799995 0.023435205 0.13300188, -0.41800001 0.016777739 0.12587284, -0.4179996 -0.027507007 0.12541924, -0.41799989 0.016378134 0.12542187, -0.41800001 0.02049306 0.12542199, -0.41799992 0.020093367 0.1258731, -0.4179996 -0.028402641 0.12621258, -0.41799989 0.019597322 0.12621532, -0.4179996 -0.027226821 0.12488566, -0.41799989 0.016098112 0.12488784, -0.41799989 0.020773306 0.12488829, -0.41800004 0.019033924 0.12642898, -0.4179996 -0.028966188 0.1264265, -0.41799995 0.020917505 0.12430333, -0.41799966 -0.027082607 0.12430058, -0.41799989 0.015953973 0.12430309, -0.41799989 0.018435583 0.12650166, -0.4179996 -0.029564515 0.12649892, -0.41799963 -0.027082518 0.12369777, -0.41799989 0.015953973 0.12370001, -0.41799989 0.017837256 0.12642898, -0.4179996 -0.030162752 0.12642635, -0.41799989 0.017273754 0.12621526, -0.41799963 -0.027226701 0.12311246, -0.41799989 0.016098157 0.12311505, -0.4179996 -0.030726254 0.12621243, -0.41799963 -0.027506754 0.12257887, -0.41799989 0.016378284 0.12258138, -0.41799989 0.016777992 0.12213017, -0.41799971 -0.031222209 0.12587009, -0.4179996 -0.027906373 0.12212776, -0.41799971 -0.031621873 0.12541912, -0.41799954 -0.031901881 0.12488531, -0.41799957 -0.03204605 0.12430035, -0.41800007 0.023436293 0.1150019, -0.41799992 0.018435821 0.12150173, -0.41799992 0.019034132 0.1215743, -0.41799989 0.01959765 0.1217881, -0.41799995 0.020093605 0.1221305, -0.41799989 0.020493194 0.12258159, -0.41800007 0.020773321 0.12311532, -0.41799995 0.020917505 0.12370025, -0.41799989 0.017274022 0.12178801, -0.41799989 0.017837435 0.1215743, -0.4179996 -0.029564276 0.12149887, -0.4179996 -0.02896589 0.12157144, -0.4179996 -0.028402373 0.12178542, -0.41799957 -0.03204605 0.12369727, -0.4179996 -0.031901777 0.12311246, -0.4179996 -0.031621754 0.12257861, -0.4179996 -0.031222105 0.12212755, -0.4179996 -0.03072606 0.12178515, -0.41799954 -0.030162603 0.12157144, -0.41099998 0.018435597 0.12650166, -0.41099998 0.019033909 0.12642898, -0.41099998 0.019597352 0.12621532, -0.41099998 0.020093396 0.1258731, -0.41099998 0.020493075 0.12542199, -0.41099998 0.020773321 0.12488817, -0.41099998 0.02091758 0.12430333, -0.41099998 0.020917609 0.12370025, -0.41099998 0.020773321 0.12311532, -0.41099998 0.020493254 0.12258159, -0.41099998 0.02009365 0.1221305, -0.41099998 0.01959762 0.1217881, -0.41099998 0.019034132 0.12157418, -0.41099995 0.018435836 0.12150158, -0.41099969 -0.029564559 0.12649892, -0.41099969 -0.028966144 0.1264265, -0.41099969 -0.028402716 0.12621258, -0.41099969 -0.027906656 0.12587024, -0.41099969 -0.027506843 0.12541924, -0.41099969 -0.027226776 0.12488554, -0.41099966 -0.027082592 0.12430058, -0.41099966 -0.027082592 0.12369753, -0.41099969 -0.027226746 0.12311246, -0.41099969 -0.027506799 0.12257887, -0.41099969 -0.027906388 0.12212776, -0.41099969 -0.028402358 0.12178542, -0.41099969 -0.028965861 0.12157144, -0.41099966 -0.029564217 0.12149896, -0.41099969 -0.030162483 0.12157144, -0.41099966 -0.030725971 0.12178515, -0.41099957 -0.031222075 0.12212755, -0.41099969 -0.031621784 0.12257861, -0.41099969 -0.031901807 0.12311219, -0.41099966 -0.03204596 0.12369727, -0.41099966 -0.032046095 0.12430035, -0.41099969 -0.031901807 0.12488531, -0.41099966 -0.031621829 0.12541901, -0.41099966 -0.031222299 0.12587009, -0.41099969 -0.030726284 0.12621243, -0.41099966 -0.030162767 0.12642635, -0.41099995 0.017837524 0.1215743, -0.41099995 0.017274052 0.12178792, -0.41099995 0.016778037 0.12213017, -0.41099995 0.016378313 0.12258138, -0.41099995 0.016098201 0.12311505, -0.41099995 0.015953973 0.12370001, -0.41099995 0.015953973 0.124303, -0.41099995 0.016098201 0.12488802, -0.41099995 0.016378149 0.12542175, -0.41099995 0.016777784 0.12587284, -0.41099998 0.017273754 0.12621526, -0.41099995 0.017837346 0.12642898, -0.41699955 -0.034565032 0.13399883, -0.41699991 0.023435026 0.13400178, -0.41099998 0.023435146 0.13400193, 0.41000059 -0.016068131 -0.13269378, 0.41000041 0.023455456 -0.13299812, 0.41000065 -0.016308472 -0.13300036, 0.41000071 -0.015869647 -0.13235869, 0.41100034 0.024455547 -0.13299812, 0.41000071 -0.034545675 -0.11500137, 0.41100076 -0.03454563 -0.11400144, 0.41700038 0.024454504 -0.11499806, 0.41700044 0.024455458 -0.13299812, 0.41700068 -0.034545571 -0.11400144, 0.41700038 0.023454487 -0.1139981, 0.41000071 -0.034544557 -0.13300128, 0.41100082 -0.034544557 -0.13400139, 0.41100034 0.02345562 -0.1339982, 0.41700068 -0.034544483 -0.13400154, 0.41700038 0.023455501 -0.1339982, 0.4110007 -0.0355445 -0.13300146, 0.41800067 -0.034544498 -0.13300146, 0.41800034 0.023455545 -0.13299812, 0.41800037 0.016397461 -0.12257843, 0.41800037 0.016797155 -0.12212737, 0.41800076 -0.0278873 -0.12212975, 0.41800067 -0.027487636 -0.12258084, 0.41800061 -0.027207479 -0.12311454, 0.41800067 -0.031602547 -0.12258111, 0.41800079 -0.031202912 -0.12212999, 0.41800067 -0.034545526 -0.11500137, 0.41800037 0.017293155 -0.12178488, 0.41800037 0.023454487 -0.11499821, 0.41800076 -0.030706957 -0.12178759, 0.41800037 0.016117439 -0.12311207, 0.41800064 -0.031882554 -0.12311478, 0.41800067 -0.02706328 -0.12369971, 0.41800082 -0.030143484 -0.121574, 0.41800025 0.017856553 -0.12157114, 0.41800037 0.015973136 -0.12369736, 0.41800079 -0.032026857 -0.12369998, 0.41800067 -0.029545173 -0.12150125, 0.41800037 0.018454909 -0.12149839, 0.41800079 -0.032026738 -0.12430267, 0.4180004 0.015973225 -0.12429987, 0.41800079 -0.028946877 -0.12157379, 0.41800067 -0.027063176 -0.12430237, 0.41800037 0.019053161 -0.12157114, 0.41800067 -0.028383255 -0.12178738, 0.41800037 0.016117543 -0.12488519, 0.41800067 -0.027207434 -0.12488757, 0.41800073 -0.027487502 -0.12542124, 0.41800037 0.019616753 -0.12178479, 0.4180004 0.01639761 -0.12541877, 0.41800031 0.020112753 -0.12212713, 0.41800037 0.016797245 -0.12586994, 0.41800067 -0.027887106 -0.1258723, 0.41800031 0.020512462 -0.12257819, 0.41800037 0.020792469 -0.12311183, 0.41800037 0.020936757 -0.123697, 0.41800064 -0.028946534 -0.12642859, 0.41800064 -0.02954486 -0.12650116, 0.41800064 -0.028383031 -0.12621473, 0.41800067 -0.03188251 -0.1248879, 0.41800067 -0.031602353 -0.12542139, 0.4180007 -0.031202704 -0.12587245, 0.4180007 -0.030706674 -0.12621473, 0.41800079 -0.030143112 -0.12642859, 0.41800037 0.019053474 -0.12642573, 0.41800034 0.018455222 -0.12649842, 0.41800037 0.019616976 -0.12621199, 0.41800037 0.020112872 -0.12586959, 0.41800034 0.020512655 -0.12541841, 0.41800031 0.020792663 -0.12488483, 0.41800037 0.020936847 -0.12429972, 0.41800037 0.017293274 -0.12621222, 0.41800037 0.017856851 -0.12642573, 0.41100034 0.018454865 -0.12149845, 0.4110004 0.017856479 -0.12157114, 0.4110004 0.017292976 -0.12178488, 0.41100043 0.016797066 -0.12212728, 0.41100043 0.016397387 -0.12257843, 0.41100037 0.016117409 -0.12311228, 0.41100037 0.015973195 -0.12369715, 0.41100043 0.01597321 -0.12429987, 0.41100034 0.016117543 -0.12488519, 0.41100037 0.01639761 -0.12541877, 0.41100034 0.0167972 -0.12586994, 0.41100043 0.017293245 -0.12621222, 0.41100043 0.017856807 -0.12642588, 0.41100043 0.018455073 -0.12649842, 0.41100064 -0.029545218 -0.12150116, 0.41100067 -0.030143484 -0.12157373, 0.41100064 -0.030706912 -0.12178759, 0.41100067 -0.031202897 -0.12213008, 0.41100076 -0.031602591 -0.12258111, 0.41100064 -0.031882614 -0.12311478, 0.41100082 -0.032026872 -0.12369998, 0.4110007 -0.032026857 -0.12430267, 0.41100076 -0.031882554 -0.12488781, 0.41100082 -0.031602532 -0.12542139, 0.41100079 -0.031202868 -0.1258726, 0.4110007 -0.030706733 -0.12621473, 0.4110007 -0.030143231 -0.12642859, 0.4110007 -0.029544905 -0.12650116, 0.41100064 -0.028946623 -0.12642859, 0.41100064 -0.028383121 -0.12621473, 0.41100064 -0.027887091 -0.12587236, 0.41100064 -0.027487457 -0.12542124, 0.41100058 -0.027207404 -0.12488757, 0.4110007 -0.027063265 -0.12430222, 0.41100064 -0.02706328 -0.12369971, 0.41100064 -0.027207538 -0.12311454, 0.41100058 -0.027487591 -0.12258084, 0.4110007 -0.027887329 -0.12212984, 0.41100061 -0.028383315 -0.12178759, 0.4110007 -0.028946981 -0.12157379, 0.41100043 0.01905334 -0.12642588, 0.41100031 0.019616991 -0.12621199, 0.41100034 0.020112887 -0.12586959, 0.41100034 0.020512491 -0.12541841, 0.41100028 0.020792618 -0.12488483, 0.41100028 0.020936802 -0.12429972, 0.4110004 0.020936608 -0.123697, 0.41100034 0.020792499 -0.12311177, 0.4110004 0.020512357 -0.12257819, 0.41100034 0.020112678 -0.12212707, 0.41100043 0.019616634 -0.12178479, 0.41100043 0.019053131 -0.12157114, 0.41700068 -0.03554444 -0.13300158, 0.4170008 -0.035545602 -0.11500151, 0.41100067 -0.035545528 -0.11500151, 0.41100067 -0.034558415 0.11399879, 0.41000071 -0.034558445 0.11499868, 0.41100034 0.024440587 0.13300188, 0.41700074 -0.034558445 0.11399879, 0.41700038 0.023441553 0.11400194, 0.41700032 0.024440527 0.13300209, 0.41700032 0.02444154 0.11500205, 0.4110007 -0.035558432 0.11499844, 0.41100076 -0.035559505 0.13299851, 0.41000071 -0.034559473 0.13299866, 0.41700068 -0.035559386 0.13299851, 0.41700074 -0.035558477 0.11499859, 0.4110007 -0.034559682 0.13399868, 0.41800073 -0.034559369 0.13299878, 0.41800085 -0.03455846 0.11499868, 0.41800037 0.016783103 0.12587284, 0.41800067 -0.027901277 0.12587024, 0.4180004 0.016383484 0.12542187, 0.41800067 -0.027501628 0.12541924, 0.4180007 -0.031616539 0.12541912, 0.41800055 -0.031216845 0.12587009, 0.41800037 0.017279103 0.12621532, 0.41800037 0.023440614 0.13300188, 0.41800064 -0.03072086 0.12621243, 0.41800037 0.016103595 0.12488784, 0.4180007 -0.031896457 0.12488522, 0.41800061 -0.027221352 0.12488554, 0.41800067 -0.027077183 0.12430058, 0.41800082 -0.030157432 0.12642635, 0.41800025 0.017842636 0.12642898, 0.41800082 -0.032040745 0.12430035, 0.41800034 0.015959367 0.124303, 0.41800067 -0.029559106 0.12649892, 0.41800037 0.018440902 0.12650166, 0.41800067 -0.028960824 0.12642635, 0.41800034 0.015959367 0.12370013, 0.41800061 -0.027077153 0.12369765, 0.41800034 0.019039199 0.12642922, 0.41800064 -0.028397277 0.12621258, 0.41800037 0.016103581 0.12311505, 0.41800067 -0.027221307 0.12311269, 0.41800067 -0.027501389 0.12257887, 0.41800037 0.019602731 0.12621532, 0.41800037 0.016383618 0.12258138, 0.41800046 0.020098731 0.12587322, 0.41800052 0.016783297 0.12213017, 0.41800067 -0.027900994 0.12212776, 0.41800037 0.02049844 0.12542199, 0.41800037 0.020778626 0.12488829, 0.41800031 0.020922899 0.12430321, 0.41800067 -0.028960526 0.12157156, 0.41800064 -0.029558852 0.12149908, 0.41800055 -0.028397009 0.12178542, 0.41800067 -0.032040685 0.12369753, 0.4180007 -0.031896412 0.12311231, 0.41800064 -0.03161636 0.12257861, 0.4180007 -0.031216666 0.12212746, 0.41800055 -0.030720621 0.12178515, 0.41800067 -0.030157119 0.12157144, 0.41800022 0.023441628 0.1150019, 0.41800031 0.019039527 0.1215743, 0.41800046 0.018441096 0.12150179, 0.41800049 0.019602954 0.12178801, 0.41800046 0.020098895 0.1221305, 0.41800037 0.020498514 0.12258159, 0.41800049 0.020778626 0.12311532, 0.41800037 0.020922855 0.12370025, 0.41800049 0.017279282 0.12178801, 0.41800049 0.017842785 0.1215743, 0.41100031 0.018440917 0.12650155, 0.4110004 0.017842561 0.12642898, 0.41100043 0.017279059 0.12621512, 0.41100034 0.016783059 0.12587272, 0.41100043 0.01638338 0.12542175, 0.41100049 0.016103506 0.12488784, 0.41100043 0.015959263 0.124303, 0.41100037 0.015959278 0.12370013, 0.41100034 0.016103551 0.12311505, 0.41100037 0.016383618 0.12258138, 0.41100037 0.016783327 0.12213017, 0.41100034 0.017279372 0.12178792, 0.41100043 0.017842799 0.12157418, 0.41100037 0.018441141 0.12150158, 0.41100064 -0.029559135 0.12649892, 0.41100061 -0.030157402 0.12642621, 0.41100061 -0.030720964 0.12621258, 0.41100073 -0.031216994 0.12587024, 0.4110007 -0.031616598 0.12541912, 0.41100076 -0.031896561 0.12488531, 0.4110007 -0.0320407 0.12430023, 0.4110007 -0.0320407 0.12369739, 0.4110007 -0.031896502 0.12311231, 0.41100076 -0.03161642 0.12257861, 0.4110007 -0.031216785 0.12212755, 0.41100082 -0.030720741 0.12178524, 0.41100076 -0.030157238 0.12157144, 0.41100079 -0.029558972 0.12149896, 0.41100067 -0.028960511 0.12157144, 0.4110007 -0.028397128 0.12178554, 0.4110007 -0.027901158 0.12212791, 0.41100058 -0.027501419 0.12257887, 0.41100067 -0.027221352 0.12311269, 0.41100058 -0.027077109 0.12369765, 0.41100076 -0.027077228 0.12430046, 0.41100079 -0.027221531 0.12488554, 0.4110007 -0.027501687 0.12541924, 0.41100076 -0.027901381 0.12587036, 0.4110007 -0.028397381 0.1262127, 0.4110007 -0.028960884 0.1264265, 0.4110004 0.019039348 0.1215743, 0.41100034 0.019602939 0.12178801, 0.41100034 0.02009891 0.12213041, 0.41100034 0.020498559 0.12258147, 0.4110004 0.020778567 0.12311532, 0.41100043 0.02092281 0.12370025, 0.41100034 0.020922825 0.12430333, 0.41100028 0.020778582 0.12488829, 0.41100028 0.02049835 0.12542199, 0.41100028 0.020098746 0.1258731, 0.41100031 0.019602746 0.12621532, 0.41100034 0.019039214 0.12642898, 0.41700074 -0.034559637 0.13399883, 0.41700026 0.02344054 0.13400193, 0.41100037 0.023440361 0.13400178, 0.26799998 0.062439471 0.13400425, 0.2679995 0.13143957 0.13400821, 0.3869997 0.13444024 0.13400824, 0.27099943 0.13443968 0.13400824, 0.38999969 0.13144031 0.13400801, 0.39000008 0.062440276 0.13400425, 0.38700017 0.059440255 0.13400395, 0.271 0.059439555 0.13400395, 0.36149967 0.1204402 0.13400738, 0.37199977 0.10944015 0.13400681, 0.37244481 0.10939004 0.13400681, 0.36142704 0.11984189 0.13400741, 0.29057992 0.063382208 0.13400407, 0.29012874 0.063781843 0.13400425, 0.28978637 0.064277828 0.13400425, 0.29111347 0.063102126 0.13400425, 0.28957269 0.064841345 0.13400425, 0.29169875 0.062957823 0.13400431, 0.28949997 0.065439701 0.13400431, 0.36142701 0.12103842 0.13400741, 0.29230139 0.062957823 0.13400431, 0.28957263 0.066037938 0.13400431, 0.37286744 0.10924217 0.13400681, 0.36121336 0.12160195 0.13400741, 0.36087096 0.12209791 0.13400762, 0.36041993 0.12249766 0.13400762, 0.35988611 0.1227777 0.13400762, 0.35930106 0.12292188 0.13400741, 0.35869837 0.12292188 0.13400771, 0.37399974 0.10744023 0.13400657, 0.3732467 0.10900387 0.13400681, 0.3735635 0.10868712 0.13400666, 0.37380174 0.10830796 0.13400681, 0.37394962 0.10788527 0.13400666, 0.28599983 0.10943957 0.13400666, 0.35869831 0.1179584 0.13400738, 0.35811311 0.11810258 0.13400738, 0.35757962 0.11838265 0.13400738, 0.35712835 0.11878234 0.13400738, 0.37200004 0.077440128 0.13400514, 0.28600004 0.077439591 0.13400514, 0.35569873 0.067921877 0.13400431, 0.35511348 0.067777663 0.13400431, 0.35457984 0.067497537 0.13400431, 0.35412869 0.067097872 0.13400431, 0.29387131 0.06709747 0.13400431, 0.3581132 0.12277766 0.13400762, 0.3575795 0.12249754 0.13400762, 0.28988618 0.12277719 0.13400771, 0.29041985 0.12249716 0.13400762, 0.28475294 0.077875987 0.13400514, 0.28443632 0.078192607 0.13400514, 0.28513214 0.077637687 0.13400491, 0.28978631 0.066601485 0.13400431, 0.28419799 0.078571826 0.13400514, 0.28555495 0.077489793 0.13400491, 0.29012874 0.06709747 0.13400431, 0.28405014 0.078994498 0.13400514, 0.28399992 0.07943961 0.13400514, 0.2905798 0.067497134 0.13400431, 0.29342023 0.06749709 0.13400431, 0.29288653 0.067777231 0.13400431, 0.29230139 0.067921415 0.13400455, 0.29169866 0.0679214 0.13400455, 0.29111359 0.067777187 0.13400431, 0.28399974 0.10743959 0.13400666, 0.28405002 0.10788463 0.13400666, 0.28419775 0.10830741 0.13400666, 0.28443617 0.10868652 0.13400681, 0.28712836 0.11878187 0.13400741, 0.28475288 0.10900331 0.13400666, 0.28513199 0.10924157 0.13400666, 0.28555483 0.10938936 0.13400681, 0.28757954 0.1183821 0.13400741, 0.28678608 0.11927781 0.13400741, 0.28811324 0.11810214 0.13400717, 0.28657231 0.11984136 0.13400762, 0.28869826 0.11795793 0.13400738, 0.28649965 0.1204397 0.13400738, 0.28930104 0.11795788 0.13400738, 0.28657225 0.12103795 0.13400741, 0.28988618 0.11810219 0.13400738, 0.28678599 0.12160152 0.13400741, 0.29041991 0.11838225 0.13400738, 0.28712833 0.12209743 0.13400741, 0.2908709 0.11878192 0.13400717, 0.28757945 0.12249725 0.13400762, 0.28811315 0.12277716 0.13400762, 0.28869835 0.12292141 0.13400762, 0.28930107 0.1229214 0.13400762, 0.35457996 0.063382581 0.13400425, 0.35412875 0.06378223 0.13400431, 0.29387119 0.063781872 0.13400425, 0.2934202 0.063382223 0.13400425, 0.35378641 0.06427826 0.13400425, 0.29421371 0.064277843 0.13400425, 0.35511348 0.063102499 0.13400431, 0.29288656 0.063102111 0.13400425, 0.35357267 0.064841807 0.13400431, 0.29442737 0.064841419 0.13400425, 0.35569867 0.06295827 0.13400407, 0.35350007 0.065439969 0.13400431, 0.29449996 0.065439671 0.13400425, 0.35357273 0.0660384 0.13400431, 0.29442737 0.066037938 0.13400431, 0.29421368 0.06660147 0.13400431, 0.3537865 0.066601872 0.13400431, 0.35630143 0.062958226 0.13400407, 0.35688663 0.063102484 0.13400425, 0.3574203 0.063382566 0.13400425, 0.35787138 0.063782215 0.13400431, 0.35821369 0.064278215 0.13400425, 0.35842749 0.064841762 0.13400431, 0.35850009 0.065439999 0.13400431, 0.35842732 0.06603843 0.13400431, 0.35821363 0.066601798 0.13400431, 0.35787126 0.067097917 0.13400455, 0.35742012 0.067497596 0.13400431, 0.35688654 0.067777619 0.13400431, 0.35630134 0.067921788 0.13400431, 0.37244499 0.0774903 0.13400491, 0.37286779 0.077638149 0.13400514, 0.37324694 0.077876538 0.13400514, 0.37380198 0.078572333 0.13400514, 0.37356362 0.078193188 0.13400491, 0.37394974 0.078995138 0.13400514, 0.37399989 0.079440236 0.13400514, 0.3567861 0.1192783 0.13400741, 0.29121321 0.11927792 0.13400741, 0.3565723 0.11984181 0.13400738, 0.29142696 0.11984133 0.13400741, 0.29149964 0.12043973 0.13400741, 0.35649973 0.12044011 0.13400741, 0.29142705 0.12103797 0.13400741, 0.35657242 0.12103841 0.13400762, 0.3567861 0.12160192 0.13400762, 0.2912133 0.12160152 0.13400762, 0.35712841 0.12209786 0.13400762, 0.29087093 0.12209753 0.13400762, 0.35930097 0.11795844 0.13400741, 0.35988626 0.11810261 0.13400717, 0.3604199 0.1183826 0.13400717, 0.36087099 0.11878234 0.13400738, 0.36121336 0.11927828 0.13400738, 0.2914997 0.12043989 0.13200755, 0.29142702 0.11984161 0.13200755, 0.29121339 0.11927807 0.13200755, 0.29087105 0.11878206 0.1320072, 0.29041991 0.11838237 0.13200732, 0.28988618 0.11810237 0.13200732, 0.28930098 0.11795812 0.1320072, 0.28869823 0.11795811 0.1320072, 0.28811318 0.11810233 0.1320072, 0.28757951 0.11838239 0.13200732, 0.28712842 0.11878203 0.13200755, 0.28678608 0.11927795 0.13200755, 0.2865724 0.11984156 0.13200755, 0.28649968 0.12043983 0.13200755, 0.36149967 0.12044032 0.13200755, 0.36142698 0.11984198 0.13200732, 0.36121336 0.11927851 0.13200732, 0.3608709 0.11878254 0.13200732, 0.36041996 0.11838281 0.13200755, 0.35988626 0.11810277 0.13200732, 0.35930112 0.11795856 0.13200732, 0.35869834 0.11795856 0.13200732, 0.35811326 0.11810274 0.13200732, 0.35757953 0.11838277 0.13200732, 0.35712847 0.1187824 0.13200732, 0.3567861 0.11927846 0.13200732, 0.35657236 0.11984193 0.13200755, 0.3564997 0.12044024 0.13200755, 0.3585 0.065440238 0.13200434, 0.35842732 0.064842075 0.13200434, 0.35821363 0.064278483 0.13200434, 0.35787129 0.063782483 0.13200434, 0.35742027 0.063382819 0.1320041, 0.3568866 0.063102737 0.13200419, 0.35630146 0.062958434 0.13200419, 0.35569879 0.062958404 0.13200419, 0.35511366 0.063102692 0.13200419, 0.3545799 0.063382849 0.13200419, 0.35412872 0.063782483 0.13200419, 0.35378644 0.064278468 0.13200419, 0.3535727 0.064841911 0.13200434, 0.35349998 0.065440178 0.13200434, 0.29450008 0.06543979 0.13200434, 0.29442742 0.064841539 0.13200419, 0.29421371 0.064278081 0.13200419, 0.29387131 0.063782007 0.13200434, 0.2934202 0.063382402 0.13200419, 0.29288656 0.06310226 0.13200419, 0.29230139 0.062958047 0.1320041, 0.29169872 0.062958017 0.13200419, 0.29111362 0.063102245 0.13200419, 0.29057989 0.063382328 0.13200419, 0.29012871 0.063782021 0.13200434, 0.28978637 0.064278036 0.13200419, 0.28957269 0.064841598 0.13200419, 0.28950009 0.065439761 0.13200448, 0.2859998 0.10943977 0.13200666, 0.37199977 0.10944036 0.13200666, 0.37399983 0.10744032 0.13200666, 0.37399995 0.079440325 0.13200517, 0.37199995 0.077440396 0.13200493, 0.28599992 0.07743983 0.13200508, 0.28399992 0.079439819 0.13200517, 0.2839998 0.10743978 0.13200675, 0.28957263 0.066038147 0.13200448, 0.28978643 0.06660156 0.13200448, 0.29012874 0.067097664 0.13200448, 0.29057983 0.067497313 0.13200448, 0.29111353 0.06777741 0.13200434, 0.29169866 0.067921594 0.13200448, 0.29230139 0.067921594 0.13200448, 0.29288658 0.067777351 0.13200457, 0.29342011 0.067497358 0.13200448, 0.29387128 0.067097649 0.13200448, 0.2942138 0.06660156 0.13200434, 0.29442742 0.066038132 0.13200434, 0.35357276 0.066038489 0.13200434, 0.35378641 0.066602036 0.13200434, 0.35412875 0.067098036 0.13200448, 0.35457996 0.067497641 0.13200448, 0.35511354 0.067777768 0.13200448, 0.35569879 0.067921951 0.13200448, 0.35630143 0.067921922 0.13200448, 0.35688654 0.067777827 0.13200448, 0.35742018 0.067497671 0.13200457, 0.35787135 0.067098081 0.13200448, 0.35821363 0.066602051 0.13200434, 0.35842732 0.066038549 0.13200434, 0.3565723 0.12103859 0.13200755, 0.35678601 0.12160204 0.13200755, 0.35712853 0.12209809 0.13200776, 0.35757941 0.12249784 0.13200755, 0.3581132 0.12277779 0.13200755, 0.35869828 0.122922 0.13200755, 0.35930106 0.12292205 0.13200755, 0.3598862 0.1227778 0.13200755, 0.36041978 0.12249778 0.13200755, 0.36087099 0.12209809 0.13200755, 0.36121333 0.12160216 0.13200755, 0.36142704 0.12103862 0.13200755, 0.28657228 0.12103816 0.13200755, 0.28678605 0.12160163 0.13200755, 0.28712836 0.1220976 0.13200755, 0.28757951 0.12249729 0.13200776, 0.28811315 0.12277739 0.13200755, 0.28869823 0.12292164 0.13200776, 0.28930098 0.12292166 0.13200776, 0.28988624 0.12277744 0.13200755, 0.29041982 0.12249727 0.13200755, 0.29087093 0.12209766 0.13200755, 0.29121336 0.12160166 0.13200755, 0.29142705 0.12103815 0.13200755, 0.28555498 0.077489883 0.13200508, 0.2851322 0.077637836 0.13200508, 0.28475299 0.077876106 0.13200508, 0.28443623 0.078192785 0.13200517, 0.28419793 0.078571975 0.13200508, 0.28405005 0.078994751 0.13200517, 0.28405002 0.10788472 0.13200666, 0.2841979 0.10830747 0.13200675, 0.28443605 0.10868676 0.13200675, 0.28475273 0.1090035 0.13200675, 0.28513211 0.10924165 0.13200675, 0.2855548 0.10938961 0.13200675, 0.37244484 0.1093902 0.13200675, 0.37286755 0.1092422 0.13200675, 0.37324676 0.10900405 0.13200666, 0.37356344 0.10868736 0.13200666, 0.37380168 0.10830809 0.13200675, 0.37394965 0.10788539 0.13200666, 0.37394989 0.078995258 0.13200508, 0.37380192 0.078572601 0.13200508, 0.37356362 0.078193367 0.13200508, 0.373247 0.077876702 0.13200508, 0.37286773 0.077638403 0.13200508, 0.37244508 0.077490568 0.13200493, 0.39237329 0.15437543 0.11400931, 0.39177474 0.15418009 0.11400925, 0.3912302 0.15386413 0.11400931, 0.39299944 0.15444146 0.11400931, 0.40876886 0.15386431 0.11400925, 0.40822431 0.15418015 0.11400925, 0.40762571 0.15437542 0.11400934, 0.4069995 0.15444155 0.11400931, 0.39123011 0.15387702 -0.11399089, 0.3917748 0.15419295 -0.11399089, 0.39237323 0.15438831 -0.11399089, 0.3929995 0.15445431 -0.11399089, 0.4069995 0.15445441 -0.11399089, 0.40762571 0.15438831 -0.11399089, 0.40822425 0.15419307 -0.11399089, 0.40876886 0.15387708 -0.11399089, -0.41000077 0.1374502 -0.13399176, 0.40999973 0.13745545 -0.13399176, 0.40999976 0.13672428 -0.13390125, -0.41000065 0.13671912 -0.13390125, 0.40999958 0.13603741 -0.13363551, -0.41000077 0.13603209 -0.13363533, 0.40999964 0.1354358 -0.13321011, -0.41000077 0.13543056 -0.13321023, 0.40999961 0.13495614 -0.13265102, -0.41000077 0.13495086 -0.13265102, 0.40999952 0.15387714 -0.11522149, -0.41000083 0.15387185 -0.11522149, 0.40999958 0.15419312 -0.11576621, -0.41000092 0.15418793 -0.11576603, 0.40999949 0.15438847 -0.11636464, -0.41000077 0.15438323 -0.11636467, -0.41000089 0.15444919 -0.11699085, 0.40999958 0.15445451 -0.11699076, -0.41000086 0.15211785 -0.13391592, -0.41000086 0.15145034 -0.13399102, -0.41000089 0.15275191 -0.13369374, -0.41000089 0.15332071 -0.13333632, -0.41000077 0.1537957 -0.1328613, -0.41000089 0.15415302 -0.13229243, -0.41000083 0.15437491 -0.13165845, -0.41000089 0.15445016 -0.13099076, 0.40999955 0.15145555 -0.13399102, 0.40999952 0.15445532 -0.13099076, 0.40999955 0.15212315 -0.13391592, 0.40999952 0.1543802 -0.13165845, 0.40999946 0.15275715 -0.13369371, 0.40999946 0.15415829 -0.13229243, 0.40999958 0.15332599 -0.13333632, 0.40999952 0.15380098 -0.1328613, -0.098786958 0.14415318 -0.13399132, 0.098892599 0.14387269 -0.13399132, -0.098893777 0.14387138 -0.13399132, -0.0995574 0.14328353 -0.13399132, 0.099556223 0.1432848 -0.13399161, -0.099849947 0.14321138 -0.13399161, 0.099289291 0.14342487 -0.13399161, -0.40093639 0.14362147 -0.13399161, -0.40071091 0.14342171 -0.13399161, -0.098750621 0.14445227 -0.13399132, 0.098785751 0.14415443 -0.13399161, -0.4011077 0.14386949 -0.13399161, 0.09984874 0.14321268 -0.13399161, -0.40044412 0.1432817 -0.13399161, -0.40121451 0.14415127 -0.13399161, 0.098749466 0.14445356 -0.13399132, -0.098786995 0.14475146 -0.13399132, -0.40015152 0.14320952 -0.13399161, -0.40125084 0.14445041 -0.13399132, -0.098893784 0.14503314 -0.13399132, 0.098785743 0.14475268 -0.13399132, -0.39985013 0.14320944 -0.13399161, -0.40121448 0.14474943 -0.13399132, 0.098892607 0.14503449 -0.13399132, -0.3995575 0.14328162 -0.13399161, -0.099290572 0.14548101 -0.13399132, 0.099063739 0.14528251 -0.13399132, -0.099065028 0.14528121 -0.13399132, -0.4011077 0.1450313 -0.13399132, -0.40093651 0.1452793 -0.13399132, -0.09955743 0.14562102 -0.13399132, 0.09928938 0.1454823 -0.13399132, -0.40071085 0.14547908 -0.13399132, 0.09955617 0.14562231 -0.13399132, -0.40044412 0.14561915 -0.13399132, -0.099849984 0.14569314 -0.13399132, 0.099848785 0.14569443 -0.13399132, -0.40015152 0.14569128 -0.13399132, -0.39985022 0.14569129 -0.13399132, -0.3995575 0.14561912 -0.13399132, 0.1095638 0.14362472 -0.13399161, 0.10978939 0.14342487 -0.13399161, 0.10093508 0.14362471 -0.13399161, 0.10070954 0.14342482 -0.13399161, -0.27593637 0.14362226 -0.13399161, -0.27571076 0.14342242 -0.13399161, -0.39906517 0.14362144 -0.13399161, 0.1093926 0.14387274 -0.13399161, -0.39929077 0.14342166 -0.13399161, -0.2761074 0.14387017 -0.13399161, 0.10110623 0.14387269 -0.13399161, -0.39889404 0.14386949 -0.13399161, 0.11005618 0.14328489 -0.13399161, 0.10044274 0.14328481 -0.13399161, -0.27544391 0.14328241 -0.13399161, 0.10928579 0.14415449 -0.13399161, -0.27621439 0.14415205 -0.13399132, 0.10124946 0.1444536 -0.13399161, 0.10121306 0.1441545 -0.13399161, -0.39878711 0.14415123 -0.13399161, -0.27515143 0.14321032 -0.13399161, 0.11034879 0.14321274 -0.13399161, 0.10015009 0.14321271 -0.13399161, -0.27625072 0.14445117 -0.13399132, 0.10924936 0.14445367 -0.13399161, 0.10121305 0.14475276 -0.13399132, -0.39875075 0.14445034 -0.13399161, -0.27485004 0.14321032 -0.13399161, -0.27621442 0.1447503 -0.13399132, 0.10928573 0.1447528 -0.13399132, -0.39878723 0.1447496 -0.13399132, 0.1011063 0.14503452 -0.13399132, 0.10939265 0.14503452 -0.13399132, -0.27610755 0.14503205 -0.13399132, 0.10956375 0.14528257 -0.13399132, -0.39889395 0.14503133 -0.13399132, 0.10093503 0.14528252 -0.13399132, -0.27593642 0.14528003 -0.13399132, 0.10978935 0.14548236 -0.13399132, -0.39906529 0.14527932 -0.13399132, 0.10070956 0.1454823 -0.13399132, -0.27571076 0.14547986 -0.13399132, 0.11005615 0.14562245 -0.13399132, -0.39929071 0.14547913 -0.13399132, 0.10044266 0.14562237 -0.13399132, -0.27544397 0.14561991 -0.13399132, 0.11034873 0.14569457 -0.13399132, -0.27515143 0.14569205 -0.13399132, 0.10015008 0.14569449 -0.13399132, 0.26206386 0.14362574 -0.13399161, 0.26228949 0.14342585 -0.13399132, 0.11143509 0.14362475 -0.13399161, 0.11120957 0.14342487 -0.13399161, 0.11094272 0.14328481 -0.13399161, 0.26189262 0.14387372 -0.13399161, -0.27406508 0.14362231 -0.13399161, -0.26371071 0.14342245 -0.13399161, -0.27429062 0.14342242 -0.13399161, 0.11160624 0.14387277 -0.13399132, -0.2639364 0.14362235 -0.13399161, 0.26255631 0.14328584 -0.13399161, 0.11065006 0.14321274 -0.13399161, 0.26178578 0.14415553 -0.13399161, -0.27389395 0.14387032 -0.13399161, -0.26410756 0.14387035 -0.13399161, 0.11171315 0.1441545 -0.13399132, -0.26344392 0.14328244 -0.13399161, -0.27455747 0.14328249 -0.13399161, 0.26284888 0.1432137 -0.13399161, 0.11174943 0.14445366 -0.13399161, 0.26174954 0.14445463 -0.13399161, -0.27378699 0.14415205 -0.13399161, -0.26421434 0.14415212 -0.13399132, -0.26315138 0.14321035 -0.13399161, 0.11160628 0.14503455 -0.13399132, 0.26178584 0.14475375 -0.13399132, 0.11171313 0.14475282 -0.13399132, -0.27378708 0.14475033 -0.13399132, -0.26425076 0.14445126 -0.13399161, -0.27375078 0.14445117 -0.13399161, 0.26189271 0.14503555 -0.13399132, -0.26285011 0.14321038 -0.13399161, -0.2642144 0.14475036 -0.13399132, 0.11143503 0.14528258 -0.13399132, 0.2620638 0.14528352 -0.13399132, 0.11094271 0.14562237 -0.13399132, 0.26228943 0.14548331 -0.13399132, 0.11120951 0.14548239 -0.13399132, -0.27389395 0.14503208 -0.13399132, -0.26410761 0.14503217 -0.13399132, 0.11065008 0.14569457 -0.13399132, 0.2625562 0.14562342 -0.13399132, -0.27406511 0.14528005 -0.13399132, -0.26393634 0.14528012 -0.13399132, 0.26284888 0.14569549 -0.13399132, -0.26371074 0.14547989 -0.13399132, -0.27429062 0.14547984 -0.13399132, -0.26344401 0.14562002 -0.13399132, -0.27455747 0.1456199 -0.13399132, -0.26315138 0.14569217 -0.13399132, -0.27485001 0.14569207 -0.13399132, 0.26393512 0.14362575 -0.13399161, 0.27428943 0.14342594 -0.13399132, 0.26370963 0.14342585 -0.13399161, 0.27406389 0.14362575 -0.13399161, 0.26421323 0.14415544 -0.13399161, 0.27389267 0.14387381 -0.13399132, 0.26410636 0.14387368 -0.13399161, 0.27455625 0.1432859 -0.13399161, 0.26344275 0.14328584 -0.13399161, 0.26315019 0.14321378 -0.13399161, 0.2737858 0.14415558 -0.13399132, -0.11143629 0.14362335 -0.13399161, -0.11121076 0.14342348 -0.13399161, -0.26206502 0.14362231 -0.13399161, -0.26229057 0.14342245 -0.13399161, -0.26255742 0.1432825 -0.13399161, 0.26424953 0.14445463 -0.13399161, -0.11160754 0.14387137 -0.13399132, 0.27484891 0.14321376 -0.13399161, 0.27374953 0.14445472 -0.13399161, -0.26178706 0.1441521 -0.13399161, -0.26189384 0.14387026 -0.13399161, 0.26421323 0.14475375 -0.13399132, -0.11094385 0.14328343 -0.13399161, -0.11171434 0.14415312 -0.13399161, 0.26410636 0.14503558 -0.13399132, 0.27378586 0.14475378 -0.13399132, -0.11065139 0.14321136 -0.13399132, -0.11175065 0.14445221 -0.13399161, 0.26393518 0.14528355 -0.13399132, 0.27389267 0.14503559 -0.13399132, -0.26178703 0.14475039 -0.13399132, -0.2617507 0.14445117 -0.13399161, -0.11035003 0.14321141 -0.13399132, 0.2637096 0.14548331 -0.13399132, 0.27406386 0.14528356 -0.13399132, -0.11171442 0.14475143 -0.13399132, 0.2742894 0.14548337 -0.13399132, -0.11160749 0.14503315 -0.13399161, -0.26189387 0.14503218 -0.13399132, 0.27455616 0.14562348 -0.13399132, 0.26315019 0.14569554 -0.13399132, 0.26344275 0.1456234 -0.13399132, -0.26206517 0.14528017 -0.13399132, -0.1114363 0.14528114 -0.13399132, 0.27484882 0.1456956 -0.13399132, -0.26255745 0.14562 -0.13399132, -0.11121079 0.14548096 -0.13399132, -0.26229066 0.14547999 -0.13399132, -0.11094397 0.14562103 -0.13399132, -0.26285014 0.14569217 -0.13399132, -0.11065137 0.14569315 -0.13399132, 0.27610627 0.14387381 -0.13399161, 0.39906403 0.14362654 -0.13399161, 0.27593514 0.14362583 -0.13399161, 0.27570963 0.14342594 -0.13399161, 0.39928952 0.14342669 -0.13399161, 0.27544275 0.1432859 -0.13399161, 0.39889267 0.14387462 -0.13399132, 0.27621326 0.1441555 -0.13399161, 0.39955619 0.14328681 -0.13399161, -0.10093626 0.14362329 -0.13399161, -0.1007107 0.1434235 -0.13399132, -0.109565 0.14362331 -0.13399161, -0.10979056 0.14342348 -0.13399161, 0.39878592 0.14415638 -0.13399132, 0.27624956 0.14445469 -0.13399132, -0.10110743 0.14387134 -0.13399161, -0.10939384 0.14387135 -0.13399161, 0.27621323 0.14475384 -0.13399132, 0.3987495 0.14445554 -0.13399132, -0.10044391 0.14328352 -0.13399161, -0.11005737 0.14328337 -0.13399161, 0.3987858 0.14475465 -0.13399132, 0.27610621 0.1450357 -0.13399132, -0.10928699 0.14415307 -0.13399161, -0.10121435 0.14415315 -0.13399132, -0.10015134 0.14321142 -0.13399161, 0.2759352 0.14528358 -0.13399132, 0.39889267 0.14503649 -0.13399132, -0.10925066 0.14445223 -0.13399132, -0.10125064 0.14445227 -0.13399132, 0.39906386 0.14528447 -0.13399132, 0.27570951 0.14548346 -0.13399132, 0.27544272 0.14562351 -0.13399132, 0.3992894 0.14548424 -0.13399132, -0.10928699 0.14475133 -0.13399132, -0.10121436 0.1447514 -0.13399161, 0.39955631 0.14562431 -0.13399132, -0.10939377 0.14503314 -0.13399132, -0.10110744 0.14503321 -0.13399132, -0.10956499 0.14528109 -0.13399132, -0.10093632 0.14528117 -0.13399132, -0.10979054 0.14548089 -0.13399132, -0.10071078 0.14548099 -0.13399132, -0.11005747 0.14562108 -0.13399132, -0.10044388 0.145621 -0.13399132, 0.4012495 0.14445546 -0.13399161, 0.4012132 0.1441564 -0.13399161, 0.40110633 0.1438746 -0.13399161, 0.4009352 0.14362663 -0.13399161, 0.4007096 0.14342675 -0.13399161, 0.40044281 0.14328673 -0.13399161, 0.40015027 0.14321461 -0.13399161, 0.39984891 0.14321455 -0.13399161, -0.10015134 0.14569323 -0.13399132, 0.27515027 0.14321378 -0.13399161, -0.11035004 0.14569314 -0.13399132, 0.39984879 0.1456964 -0.13399132, 0.40015015 0.14569642 -0.13399132, 0.40044281 0.14562434 -0.13399132, 0.40070972 0.14548422 -0.13399132, 0.40093526 0.14528432 -0.13399132, 0.40110645 0.14503638 -0.13399132, 0.40121326 0.1447546 -0.13399132, 0.27515018 0.1456956 -0.13399132, 0.099063784 0.14362472 -0.13399161, -0.099064991 0.14362337 -0.13399132, -0.099290609 0.14342354 -0.13399132, 0.40124968 0.14445536 -0.1319914, 0.40121326 0.14415628 -0.1319914, 0.40110645 0.14387444 -0.13199134, 0.40093529 0.14362642 -0.1319914, 0.40070966 0.1434266 -0.1319914, 0.40044287 0.14328659 -0.1319914, 0.40015021 0.14321455 -0.1319914, 0.39984891 0.14321446 -0.1319914, 0.39955631 0.14328668 -0.1319914, 0.39928946 0.1434266 -0.1319914, 0.39906386 0.14362654 -0.13199143, 0.39889267 0.1438745 -0.1319914, 0.39878586 0.14415625 -0.1319914, 0.39874953 0.14445533 -0.13199134, 0.2762495 0.14445463 -0.1319914, 0.27621323 0.14415547 -0.1319914, 0.27610639 0.14387369 -0.1319914, 0.27593517 0.14362574 -0.1319914, 0.27570954 0.14342588 -0.13199134, 0.27544281 0.14328584 -0.13199143, 0.27515015 0.14321369 -0.1319914, 0.27484885 0.14321375 -0.1319914, 0.27455619 0.14328584 -0.1319914, 0.2742894 0.14342579 -0.1319914, 0.27406392 0.14362563 -0.1319914, 0.27389276 0.14387362 -0.13199134, 0.2737858 0.14415544 -0.1319914, 0.2737495 0.14445463 -0.1319914, 0.26424947 0.14445457 -0.1319914, 0.2642132 0.14415535 -0.1319914, 0.2641063 0.14387366 -0.1319914, 0.26393512 0.14362569 -0.1319914, 0.2637096 0.14342578 -0.1319914, 0.26344278 0.14328569 -0.1319914, 0.26315022 0.1432136 -0.1319914, 0.26284888 0.14321367 -0.1319914, 0.26255623 0.14328575 -0.1319914, 0.26228949 0.14342573 -0.13199134, 0.26206383 0.14362568 -0.1319914, 0.26189271 0.14387357 -0.1319914, 0.26178589 0.14415538 -0.1319914, 0.26174942 0.14445449 -0.1319914, 0.10124944 0.1444535 -0.13199134, 0.10121314 0.14415438 -0.1319914, 0.10110625 0.14387253 -0.1319914, 0.10093508 0.14362456 -0.1319914, 0.10070953 0.14342469 -0.1319914, 0.10044274 0.14328468 -0.1319914, 0.10015009 0.14321256 -0.1319914, 0.099848807 0.14321256 -0.1319914, 0.099556223 0.14328468 -0.1319914, 0.09928932 0.14342469 -0.1319914, 0.099063799 0.14362454 -0.1319914, 0.098892637 0.14387256 -0.1319914, 0.098785765 0.14415431 -0.1319914, 0.098749436 0.14445347 -0.1319914, -0.098750561 0.14445215 -0.1319914, -0.098786935 0.14415298 -0.1319914, -0.098893747 0.14387123 -0.1319914, -0.099064954 0.14362322 -0.1319914, -0.099290557 0.14342344 -0.1319914, -0.099557377 0.14328338 -0.1319914, -0.099849947 0.14321128 -0.1319914, -0.10015136 0.14321135 -0.1319914, -0.10044386 0.14328337 -0.1319914, -0.10071068 0.14342333 -0.1319914, -0.1009363 0.14362326 -0.1319914, -0.10110751 0.14387126 -0.13199134, -0.10121437 0.14415306 -0.1319914, -0.10125067 0.14445215 -0.13199134, -0.26175082 0.14445114 -0.13199134, -0.26178712 0.14415203 -0.1319914, -0.26189387 0.14387023 -0.1319914, -0.26206511 0.14362225 -0.1319914, -0.26229063 0.14342237 -0.1319914, -0.26255751 0.14328234 -0.1319914, -0.26285014 0.14321038 -0.1319914, -0.26315138 0.14321032 -0.1319914, -0.26344401 0.14328226 -0.1319914, -0.26371086 0.14342237 -0.1319914, -0.26393646 0.14362228 -0.13199134, -0.26410758 0.14387026 -0.1319914, -0.26421437 0.144152 -0.13199134, -0.26425076 0.14445117 -0.1319914, -0.27375066 0.14445102 -0.1319914, -0.27378702 0.14415193 -0.1319914, -0.27389395 0.14387017 -0.13199134, -0.27406508 0.14362216 -0.13199128, -0.27429059 0.14342225 -0.13199134, -0.27455738 0.1432822 -0.1319914, -0.27485004 0.14321017 -0.1319914, -0.27515143 0.14321017 -0.1319914, -0.27544391 0.14328218 -0.1319914, -0.27571076 0.14342228 -0.1319914, -0.27593637 0.14362216 -0.13199134, -0.27610749 0.14387015 -0.1319914, -0.27621442 0.1441519 -0.13199134, -0.27625078 0.14445107 -0.1319914, -0.39875087 0.14445031 -0.1319914, -0.39878711 0.14415115 -0.1319914, -0.39889398 0.14386934 -0.1319914, -0.39906511 0.14362136 -0.1319914, -0.39929077 0.1434215 -0.1319914, -0.39955768 0.14328155 -0.1319914, -0.39985013 0.14320938 -0.13199143, -0.4001514 0.1432094 -0.13199143, -0.40044412 0.14328152 -0.13199143, -0.40071088 0.14342153 -0.1319914, -0.40093639 0.14362139 -0.1319914, -0.4011077 0.14386931 -0.13199134, -0.40121448 0.14415111 -0.13199128, -0.40125081 0.14445025 -0.13199128, 0.11174942 0.14445354 -0.1319914, 0.11171313 0.1441544 -0.1319914, 0.11160625 0.14387263 -0.1319914, 0.11143511 0.14362463 -0.1319914, 0.11120956 0.14342473 -0.1319914, 0.11094277 0.14328469 -0.1319914, 0.11065009 0.14321269 -0.1319914, 0.11034875 0.14321268 -0.1319914, 0.11005616 0.14328481 -0.1319914, 0.10978936 0.14342475 -0.1319914, 0.10956378 0.14362465 -0.1319914, 0.10939261 0.14387263 -0.1319914, 0.1092858 0.14415438 -0.1319914, 0.10924942 0.14445353 -0.1319914, -0.10925071 0.14445217 -0.1319914, -0.10928702 0.14415304 -0.13199134, -0.10939389 0.14387129 -0.13199134, -0.10956505 0.14362328 -0.13199134, -0.10979064 0.14342336 -0.1319914, -0.11005736 0.14328335 -0.1319914, -0.11035003 0.14321132 -0.1319914, -0.11065138 0.14321125 -0.1319914, -0.11094392 0.14328331 -0.1319914, -0.11121084 0.14342341 -0.1319914, -0.11143638 0.14362326 -0.1319914, -0.11160754 0.14387125 -0.1319914, -0.11171434 0.144153 -0.1319914, -0.11175071 0.14445212 -0.1319914, -0.11171439 0.14475125 -0.13199128, -0.1116074 0.14503294 -0.13199134, -0.1114363 0.14528099 -0.13199128, -0.11121074 0.14548081 -0.13199128, -0.110944 0.14562091 -0.13199134, -0.1106514 0.14569308 -0.13199128, -0.1103501 0.14569309 -0.13199128, -0.11005751 0.14562094 -0.13199134, -0.10979059 0.14548083 -0.13199134, -0.10956502 0.14528106 -0.13199134, -0.10939384 0.14503305 -0.1319914, -0.10928705 0.14475133 -0.13199134, 0.10928575 0.14475262 -0.13199134, 0.10939264 0.14503443 -0.13199134, 0.10956372 0.14528245 -0.13199134, 0.10978936 0.14548226 -0.13199134, 0.11005615 0.14562233 -0.13199128, 0.11034877 0.14569439 -0.13199128, 0.11065009 0.14569445 -0.13199116, 0.11094267 0.14562227 -0.13199128, 0.11120951 0.14548227 -0.13199128, 0.11143504 0.14528246 -0.13199128, 0.1116063 0.14503449 -0.13199128, 0.11171308 0.14475271 -0.13199128, -0.40121451 0.14474937 -0.13199128, -0.40110758 0.14503112 -0.13199128, -0.40093639 0.14527911 -0.13199134, -0.40071085 0.14547893 -0.13199128, -0.40044406 0.145619 -0.13199128, -0.40015158 0.1456911 -0.13199134, -0.39985013 0.14569114 -0.13199134, -0.3995575 0.14561895 -0.13199128, -0.39929071 0.14547898 -0.13199128, -0.3990652 0.14527917 -0.13199134, -0.39889398 0.14503124 -0.13199128, -0.39878723 0.14474942 -0.13199128, -0.27621448 0.14475024 -0.13199128, -0.27610743 0.14503194 -0.13199134, -0.27593639 0.14527996 -0.13199134, -0.27571082 0.1454798 -0.13199134, -0.27544403 0.14561987 -0.13199128, -0.2751514 0.14569196 -0.13199134, -0.27485013 0.14569199 -0.13199134, -0.27455753 0.14561984 -0.13199116, -0.27429065 0.1454798 -0.13199128, -0.27406517 0.14528 -0.13199128, -0.27389383 0.14503193 -0.13199134, -0.27378696 0.14475012 -0.13199128, -0.26421446 0.1447503 -0.1319914, -0.26410747 0.14503193 -0.1319914, -0.26393628 0.14527997 -0.13199128, -0.26371074 0.14547977 -0.13199116, -0.2634441 0.14562 -0.13199134, -0.26315138 0.14569202 -0.13199134, -0.26285011 0.14569199 -0.13199134, -0.26255748 0.14561991 -0.13199128, -0.26229066 0.14547986 -0.13199134, -0.26206514 0.14528005 -0.13199134, -0.26189387 0.14503208 -0.13199134, -0.261787 0.14475027 -0.13199134, -0.10121439 0.14475137 -0.13199134, -0.10110747 0.14503309 -0.13199134, -0.10093629 0.14528105 -0.1319914, -0.10071074 0.14548087 -0.1319914, -0.10044399 0.14562102 -0.13199134, -0.10015133 0.14569308 -0.13199128, -0.099849999 0.14569308 -0.13199128, -0.099557444 0.14562103 -0.13199134, -0.099290632 0.14548095 -0.13199134, -0.099064998 0.14528109 -0.13199134, -0.098893844 0.14503305 -0.13199128, -0.098786965 0.14475131 -0.13199134, 0.098785758 0.14475262 -0.13199128, 0.098892592 0.14503437 -0.13199134, 0.099063754 0.14528239 -0.13199128, 0.099289335 0.14548218 -0.13199134, 0.099556133 0.14562227 -0.13199128, 0.099848747 0.14569439 -0.13199134, 0.10015004 0.14569438 -0.13199134, 0.10044268 0.14562221 -0.13199128, 0.10070954 0.14548215 -0.13199128, 0.10093505 0.14528234 -0.13199128, 0.10110623 0.14503439 -0.13199134, 0.10121309 0.14475264 -0.13199128, 0.26178584 0.14475358 -0.1319914, 0.26189268 0.14503548 -0.1319914, 0.26206386 0.1452834 -0.1319914, 0.26228943 0.14548315 -0.13199116, 0.26255623 0.14562331 -0.13199134, 0.26284888 0.14569537 -0.13199128, 0.26315019 0.14569539 -0.13199134, 0.26344275 0.14562321 -0.13199128, 0.26370957 0.14548321 -0.13199134, 0.26393512 0.14528345 -0.13199134, 0.26410633 0.14503545 -0.13199134, 0.26421314 0.14475366 -0.13199134, 0.27378583 0.14475374 -0.13199134, 0.2738927 0.14503545 -0.13199134, 0.27406392 0.14528346 -0.13199134, 0.2742894 0.14548329 -0.13199128, 0.27455628 0.14562336 -0.13199134, 0.27484885 0.14569542 -0.13199116, 0.27515021 0.14569548 -0.13199116, 0.27544278 0.14562336 -0.13199134, 0.2757096 0.14548331 -0.13199128, 0.2759352 0.14528349 -0.13199134, 0.27610639 0.14503551 -0.13199134, 0.2762132 0.14475375 -0.13199134, 0.39878592 0.14475439 -0.13199128, 0.39889279 0.14503624 -0.13199134, 0.39906392 0.14528419 -0.13199134, 0.39928952 0.145484 -0.13199128, 0.39955637 0.14562415 -0.13199134, 0.39984891 0.14569625 -0.13199134, 0.40015015 0.14569631 -0.13199134, 0.40044281 0.14562418 -0.13199134, 0.40070966 0.14548412 -0.13199134, 0.4009352 0.14528431 -0.13199134, 0.40110633 0.14503635 -0.13199134, 0.4012132 0.14475457 -0.13199134, 0.40999964 0.13494119 0.1326675, -0.41000077 0.13493586 0.13266729, 0.40999961 0.13542093 0.13322656, -0.41000077 0.13541564 0.13322656, 0.40999964 0.1360223 0.13365199, -0.41000065 0.13601696 0.13365205, 0.40999964 0.13670933 0.13391788, -0.41000077 0.13670409 0.13391788, 0.40999964 0.13744041 0.13400839, -0.41000077 0.13743517 0.13400839, -0.41000089 0.15437017 0.11638303, 0.40999946 0.1544414 0.11700942, 0.40999946 0.15437548 0.11638303, -0.41000089 0.15443617 0.11700942, -0.41000089 0.15417489 0.11578454, 0.40999952 0.15418015 0.11578454, -0.41000077 0.153859 0.11523999, 0.40999952 0.15386431 0.11523999, 0.098785721 0.14413932 0.13400884, -0.098786958 0.14413807 0.1340086, 0.098892555 0.1438576 0.13400869, -0.33621445 0.14473484 0.13400884, -0.39875075 0.14443529 0.13400869, -0.33625093 0.14443575 0.13400869, -0.098893777 0.14385624 0.13400869, -0.099557422 0.14326848 0.13400869, -0.099849947 0.14319631 0.1340086, 0.099848799 0.14319754 0.1340086, -0.39878714 0.14473437 0.13400884, -0.098750614 0.14443715 0.13400869, 0.40093514 0.14361158 0.13400869, 0.40070963 0.1434117 0.13400869, -0.33610761 0.14501657 0.13400869, 0.098749414 0.14443845 0.13400869, 0.40110633 0.14385948 0.13400869, 0.40044281 0.14327165 0.13400869, 0.40121326 0.14414132 0.13400869, -0.39889392 0.14501619 0.13400884, 0.098785676 0.1447376 0.13400869, -0.098787062 0.14473642 0.13400869, -0.33593652 0.1452647 0.13400884, 0.40015027 0.14319949 0.13400869, 0.40124962 0.1444404 0.13400884, -0.39906517 0.14526419 0.13400869, 0.40999958 0.15144049 0.1340092, -0.33571091 0.14546447 0.13400884, -0.098893858 0.14501815 0.13400884, 0.39984891 0.14319947 0.13400869, 0.098892704 0.14501935 0.13400884, 0.4012132 0.14473954 0.13400884, -0.33544412 0.14560448 0.13400869, -0.39929077 0.14546402 0.13400884, 0.39955625 0.14327165 0.13400869, 0.40110633 0.1450213 0.13400884, 0.099063791 0.14526737 0.13400884, -0.099065095 0.14526615 0.13400884, -0.39955756 0.14560403 0.13400884, 0.4009352 0.14526932 0.13400884, 0.099289313 0.14546722 0.13400884, -0.099290632 0.14546593 0.13400884, 0.40070966 0.14546905 0.13400884, 0.099556096 0.14560732 0.13400884, -0.0995574 0.14560594 0.13400884, 0.40044281 0.1456092 0.13400884, 0.40015015 0.14568135 0.13400884, 0.099848785 0.14567935 0.13400869, -0.099849962 0.14567806 0.13400896, -0.40125081 0.14443535 0.13400869, -0.40121451 0.1441361 0.13400884, -0.39955753 0.14326648 0.13400869, -0.335444 0.14326686 0.13400869, -0.40110776 0.14385439 0.13400869, -0.40093642 0.14360631 0.13400869, -0.40071082 0.14340644 0.13400869, -0.40044412 0.14326653 0.13400869, -0.40015143 0.14319436 0.1340086, -0.39985004 0.14319429 0.13400869, -0.10015129 0.14319631 0.1340086, 0.39984885 0.14568129 0.13400869, -0.33515143 0.14319481 0.13400869, -0.33485007 0.14319478 0.13400869, -0.2751514 0.14319521 0.1340086, -0.26285011 0.14319526 0.13400869, -0.11065137 0.14319628 0.13400884, -0.11034996 0.14319624 0.13400884, -0.27485013 0.14319521 0.1340086, -0.26315135 0.14319527 0.1340086, 0.39955631 0.14560917 0.13400884, -0.41000098 0.15143527 0.1340092, -0.39985016 0.14567612 0.13400884, -0.40015158 0.14567618 0.13400884, -0.40044406 0.14560398 0.13400884, -0.40071091 0.145464 0.13400884, -0.40093651 0.14526419 0.13400884, -0.40110776 0.14501619 0.13400884, -0.40121457 0.14473444 0.13400884, -0.33515146 0.14567666 0.13400884, -0.1011074 0.14385617 0.13400869, -0.10956499 0.14360826 0.13400869, -0.10093628 0.14360827 0.13400869, -0.10071082 0.14340848 0.13400869, 0.11065009 0.14567943 0.13400869, 0.26284888 0.14568035 0.13400884, 0.26315013 0.14568044 0.13400869, 0.27484882 0.14568049 0.13400884, 0.27515018 0.14568049 0.13400884, -0.10979052 0.14340831 0.1340086, -0.10044391 0.14326841 0.13400869, 0.11034876 0.14567949 0.13400869, 0.10015015 0.1456793 0.13400869, -0.10015133 0.14567809 0.13400896, -0.11035002 0.14567801 0.13400896, -0.11065134 0.14567806 0.13400896, -0.26285008 0.14567699 0.13400884, -0.26315138 0.14567702 0.13400884, 0.27593517 0.14361072 0.1340086, 0.27570966 0.14341077 0.13400869, 0.39906386 0.14361152 0.13400869, -0.27485007 0.14567697 0.13400869, 0.39928943 0.14341156 0.13400884, -0.27515137 0.14567697 0.13400869, -0.33485013 0.14567658 0.13400884, -0.10939385 0.14385624 0.13400869, -0.1100573 0.1432683 0.1340086, 0.27610636 0.14385867 0.13400869, -0.10928692 0.14413798 0.13400884, 0.39889267 0.14385945 0.13400869, 0.27544275 0.14327079 0.13400869, -0.10121437 0.14413804 0.13400884, 0.39878586 0.14414129 0.13400869, 0.27621323 0.14414039 0.13400869, -0.10925062 0.14443709 0.13400884, 0.27515027 0.14319864 0.1340086, -0.10125065 0.14443719 0.13400884, 0.3987858 0.14473952 0.13400869, 0.27624959 0.14443949 0.13400884, 0.39874956 0.14444044 0.13400869, -0.10110747 0.1450181 0.13400869, -0.10928689 0.14473619 0.13400884, -0.10121424 0.14473623 0.13400884, 0.27484891 0.14319865 0.1340086, 0.2762132 0.1447387 0.13400869, -0.10939375 0.14501794 0.13400884, 0.39906397 0.1452693 0.13400884, 0.27610621 0.14502057 0.13400884, 0.39889273 0.14502135 0.13400869, -0.10071071 0.14546585 0.13400896, -0.10956497 0.14526594 0.13400884, -0.1009363 0.1452661 0.13400884, 0.27593499 0.14526859 0.13400884, -0.10979053 0.14546575 0.13400884, -0.10044384 0.14560591 0.13400884, 0.27570954 0.14546835 0.13400884, 0.39928943 0.1454691 0.13400884, -0.11005739 0.14560586 0.13400896, 0.27544278 0.1456084 0.13400884, -0.26206508 0.14360732 0.1340086, -0.26229066 0.14340737 0.1340086, -0.11143626 0.14360818 0.13400884, -0.11121072 0.1434083 0.13400869, -0.26189393 0.14385518 0.1340086, 0.27406392 0.14361067 0.1340086, 0.26370952 0.14341079 0.1340086, 0.27428949 0.14341082 0.13400884, 0.26393515 0.14361066 0.1340086, -0.11160745 0.1438562 0.13400869, -0.26255745 0.14326736 0.13400869, -0.11094384 0.14326829 0.1340086, -0.261787 0.14413695 0.13400869, 0.27389267 0.14385873 0.13400869, 0.26410627 0.14385864 0.1340086, 0.26344267 0.14327085 0.13400869, -0.1117506 0.14443704 0.13400869, -0.11171432 0.14413792 0.13400869, 0.27455619 0.14327082 0.13400869, 0.2642132 0.14414039 0.1340086, -0.2617507 0.14443612 0.13400869, 0.2737858 0.14414054 0.13400884, 0.26315024 0.14319859 0.1340086, 0.26424947 0.14443955 0.1340086, -0.261787 0.14473528 0.13400884, -0.11160741 0.14501795 0.13400869, -0.11171443 0.14473632 0.13400884, 0.2737495 0.14443964 0.13400869, 0.26284885 0.14319867 0.1340086, 0.26421329 0.14473864 0.13400884, -0.26189393 0.14501707 0.13400884, 0.2737858 0.14473872 0.13400869, 0.2641063 0.14502051 0.13400884, -0.26206511 0.14526507 0.13400884, -0.11143634 0.145266 0.13400884, 0.27389267 0.14502046 0.13400869, 0.26393512 0.1452684 0.13400884, -0.2622906 0.14546488 0.13400884, -0.11121073 0.14546582 0.13400884, 0.27406386 0.14526844 0.13400896, 0.26370963 0.14546822 0.13400884, -0.26255739 0.14560488 0.13400869, -0.110944 0.14560592 0.13400884, 0.2742894 0.14546829 0.13400896, 0.26344278 0.14560829 0.13400869, 0.27455619 0.14560844 0.13400884, -0.27406517 0.14360723 0.13400869, -0.27429062 0.14340732 0.1340086, -0.26393631 0.14360724 0.13400884, -0.26371077 0.14340734 0.13400869, -0.27389392 0.14385515 0.13400869, 0.11143504 0.14360966 0.1340086, 0.11120951 0.14340986 0.1340086, 0.26206392 0.14361061 0.13400869, 0.26228946 0.14341074 0.13400884, -0.26410758 0.14385518 0.13400869, 0.26255625 0.14327073 0.13400869, -0.27455741 0.1432673 0.13400869, -0.26344392 0.14326736 0.13400869, 0.11160624 0.14385767 0.13400884, -0.27378702 0.14413691 0.13400869, 0.26178584 0.14414036 0.13400869, 0.26189271 0.14385855 0.13400869, -0.26421434 0.14413694 0.13400869, 0.11094265 0.14326979 0.1340086, 0.11171315 0.14413948 0.13400869, -0.27375066 0.14443611 0.13400869, 0.11065009 0.14319772 0.1340086, -0.26425076 0.14443612 0.13400869, -0.27378708 0.14473519 0.13400869, 0.11174946 0.14443859 0.13400869, -0.2642144 0.14473525 0.13400884, 0.2617496 0.14443946 0.13400869, 0.11034875 0.14319772 0.1340086, -0.27389395 0.14501706 0.13400884, -0.26410753 0.14501706 0.13400884, 0.11171309 0.14473768 0.13400884, 0.26178581 0.14473855 0.13400869, -0.27406517 0.14526498 0.13400869, -0.2639364 0.14526504 0.13400884, 0.26189271 0.14502038 0.13400884, 0.11160636 0.14501943 0.13400884, -0.27429068 0.14546481 0.13400869, -0.2637108 0.14546487 0.13400884, 0.26228946 0.14546818 0.13400869, 0.11143512 0.14526744 0.13400884, 0.26206389 0.14526835 0.13400869, -0.27455747 0.14560488 0.13400869, -0.26344401 0.14560491 0.13400884, 0.26255625 0.14560831 0.13400884, 0.11120951 0.14546724 0.13400884, 0.11094271 0.14560731 0.13400884, -0.27610755 0.14385511 0.13400869, -0.33406517 0.1436068 0.13400869, -0.27593637 0.14360715 0.1340086, -0.33429062 0.14340694 0.13400869, -0.27571076 0.14340724 0.1340086, -0.3338939 0.14385475 0.13400869, -0.27621448 0.14413702 0.13400884, 0.10956385 0.14360958 0.1340086, 0.10070956 0.14340968 0.1340086, 0.10978939 0.14340977 0.13400869, 0.10093508 0.1436096 0.1340086, -0.33455753 0.1432669 0.1340086, -0.27544394 0.14326724 0.1340086, 0.10939269 0.14385754 0.13400869, 0.10110629 0.14385755 0.13400884, -0.33378705 0.14413661 0.13400869, -0.27625072 0.14443609 0.13400869, 0.10044275 0.1432696 0.13400869, 0.11005621 0.14326976 0.13400884, 0.10121315 0.1441393 0.13400884, -0.33375078 0.14443569 0.13400869, 0.10928582 0.14413935 0.13400869, 0.10015018 0.14319755 0.1340086, -0.27621442 0.14473519 0.13400884, -0.33378723 0.14473487 0.13400884, 0.10124949 0.14443846 0.13400884, 0.10924946 0.14443851 0.13400869, -0.27610755 0.14501703 0.13400869, -0.33389398 0.1450166 0.13400869, 0.10121313 0.14473756 0.13400869, 0.1092858 0.14473762 0.13400884, -0.33406517 0.14526469 0.13400884, 0.10110632 0.14501935 0.13400884, -0.27571082 0.14546478 0.13400869, -0.27593639 0.14526491 0.13400869, 0.1093926 0.14501944 0.13400884, -0.33429071 0.14546449 0.13400884, 0.10093506 0.14526737 0.13400869, 0.1095638 0.14526744 0.13400884, -0.27544403 0.14560485 0.13400884, -0.3345575 0.14560449 0.13400884, 0.10070956 0.14546718 0.13400869, 0.10978937 0.14546724 0.13400884, 0.10044266 0.14560723 0.13400869, 0.11005615 0.14560731 0.13400869, -0.33610746 0.14385471 0.13400869, -0.39906517 0.14360631 0.13400869, -0.33593637 0.14360677 0.13400869, -0.33571082 0.14340691 0.13400869, -0.39929065 0.14340654 0.13400869, -0.33621439 0.14413649 0.13400869, -0.39889392 0.14385435 0.13400884, -0.099064983 0.14360832 0.1340086, -0.099290654 0.14340849 0.13400869, 0.099063739 0.14360958 0.13400884, 0.099289402 0.14340967 0.13400869, -0.39878711 0.14413615 0.13400869, 0.09955626 0.1432696 0.1340086, -0.40125075 0.14443539 0.13200878, -0.40121448 0.14413628 0.13200878, -0.4011077 0.14385445 0.13200878, -0.40093642 0.14360653 0.13200878, -0.40071085 0.14340666 0.13200878, -0.40044412 0.14326669 0.13200878, -0.40015158 0.14319459 0.13200878, -0.39985013 0.14319457 0.13200878, -0.39955747 0.14326663 0.13200863, -0.39929077 0.14340673 0.13200878, -0.39906517 0.1436066 0.13200878, -0.39889395 0.14385451 0.13200863, -0.39878717 0.14413631 0.13200878, -0.39875078 0.14443551 0.13200878, -0.33625084 0.14443593 0.13200878, -0.33621451 0.14413667 0.13200878, -0.33610761 0.14385493 0.13200878, -0.33593637 0.14360689 0.13200878, -0.33571085 0.14340712 0.13200878, -0.33544394 0.14326701 0.13200863, -0.3351514 0.14319494 0.13200878, -0.33485004 0.14319491 0.13200878, -0.33455744 0.1432671 0.13200878, -0.33429071 0.14340712 0.13200878, -0.33406517 0.14360701 0.13200878, -0.3338939 0.14385493 0.13200878, -0.33378711 0.14413673 0.13200878, -0.33375072 0.14443584 0.13200878, -0.27625072 0.14443626 0.13200878, -0.27621448 0.14413717 0.13200878, -0.27610752 0.1438553 0.13200878, -0.27593637 0.14360733 0.13200878, -0.27571067 0.14340749 0.13200878, -0.27544388 0.14326748 0.13200878, -0.2751514 0.1431953 0.13200878, -0.2748501 0.14319539 0.13200878, -0.27455735 0.14326742 0.13200878, -0.27429059 0.14340748 0.13200878, -0.27406508 0.14360735 0.13200878, -0.27389389 0.14385535 0.13200878, -0.27378702 0.14413708 0.13200878, -0.27375069 0.14443615 0.13200878, -0.2642507 0.14443624 0.13200878, -0.26421434 0.14413717 0.13200878, -0.26410753 0.14385536 0.13200878, -0.26393634 0.14360747 0.13200878, -0.26371086 0.14340752 0.13200878, -0.26344395 0.1432676 0.13200878, -0.26315138 0.14319539 0.13200863, -0.26285011 0.14319539 0.13200878, -0.26255742 0.14326754 0.13200878, -0.26229072 0.1434076 0.13200878, -0.26206511 0.1436075 0.13200878, -0.26189384 0.14385542 0.13200863, -0.261787 0.14413711 0.13200878, -0.26175064 0.1444363 0.13200878, -0.10125069 0.1444374 0.13200878, -0.10121437 0.14413822 0.13200863, -0.10110746 0.14385644 0.13200878, -0.10093628 0.14360845 0.13200863, -0.10071082 0.14340863 0.13200863, -0.10044391 0.14326862 0.13200863, -0.10015128 0.14319648 0.13200878, -0.099849947 0.14319648 0.13200878, -0.099557415 0.14326866 0.13200878, -0.099290624 0.14340861 0.13200878, -0.099065013 0.14360847 0.13200878, -0.098893836 0.14385648 0.13200878, -0.098787017 0.14413829 0.13200878, -0.098750643 0.14443733 0.13200878, 0.098749489 0.14443862 0.13200878, 0.098785788 0.14413953 0.13200878, 0.098892607 0.14385772 0.13200878, 0.099063806 0.14360976 0.13200878, 0.099289343 0.14340985 0.13200878, 0.099556297 0.14326979 0.13200878, 0.099848762 0.14319782 0.13200878, 0.10015011 0.14319779 0.13200878, 0.10044268 0.14326984 0.13200863, 0.10070947 0.14340992 0.13200878, 0.10093502 0.14360984 0.13200878, 0.1011062 0.14385779 0.13200863, 0.10121308 0.14413957 0.13200878, 0.10124937 0.14443871 0.13200878, 0.26174954 0.14443964 0.13200878, 0.26178586 0.14414054 0.13200878, 0.26189271 0.14385876 0.13200863, 0.2620638 0.14361078 0.13200878, 0.2622894 0.14341092 0.13200878, 0.26255628 0.14327094 0.13200878, 0.26284885 0.14319879 0.13200878, 0.26315013 0.14319885 0.13200863, 0.26344281 0.14327092 0.13200878, 0.26370963 0.14341089 0.13200878, 0.26393512 0.14361078 0.13200878, 0.2641063 0.14385882 0.13200863, 0.2642132 0.14414057 0.13200878, 0.26424959 0.14443973 0.13200878, 0.27374947 0.14443976 0.13200878, 0.2737858 0.14414069 0.13200863, 0.27389267 0.14385882 0.13200878, 0.27406392 0.14361078 0.13200878, 0.27428952 0.14341097 0.13200878, 0.27455619 0.143271 0.13200863, 0.27484891 0.14319885 0.13200878, 0.27515024 0.14319888 0.13200878, 0.27544275 0.14327103 0.13200878, 0.27570954 0.14341104 0.13200878, 0.27593514 0.14361091 0.13200878, 0.27610627 0.14385885 0.13200878, 0.27621317 0.14414066 0.13200878, 0.27624956 0.14443976 0.13200878, 0.39874962 0.14444053 0.13200878, 0.39878589 0.14414145 0.13200878, 0.39889279 0.14385965 0.13200878, 0.39906392 0.14361161 0.13200878, 0.3992894 0.14341184 0.13200863, 0.39955619 0.14327183 0.13200863, 0.39984885 0.14319968 0.13200863, 0.40015021 0.14319971 0.13200863, 0.40044284 0.14327177 0.13200878, 0.4007096 0.1434118 0.13200878, 0.4009352 0.14361167 0.13200878, 0.40110639 0.14385965 0.13200878, 0.4012132 0.14414151 0.13200878, 0.40124956 0.14444053 0.13200878, 0.10924949 0.14443868 0.13200878, 0.10928579 0.14413953 0.13200878, 0.10939264 0.14385778 0.13200863, 0.10956384 0.14360981 0.13200878, 0.10978936 0.14340997 0.13200878, 0.11005618 0.14326997 0.13200878, 0.11034876 0.14319785 0.13200863, 0.11065011 0.14319783 0.13200863, 0.11094272 0.1432699 0.13200863, 0.11120951 0.14341 0.13200878, 0.1114351 0.14360984 0.13200878, 0.11160628 0.14385781 0.13200863, 0.11171308 0.1441396 0.13200878, 0.11174946 0.14443871 0.13200878, -0.11175063 0.14443718 0.13200878, -0.11171432 0.14413813 0.13200878, -0.11160746 0.14385635 0.13200878, -0.11143634 0.14360845 0.13200863, -0.11121081 0.1434086 0.13200863, -0.11094387 0.14326848 0.13200863, -0.11065139 0.14319648 0.13200878, -0.11035009 0.14319646 0.13200878, -0.11005732 0.14326847 0.13200863, -0.10979047 0.14340851 0.13200878, -0.109565 0.14360836 0.13200878, -0.10939384 0.14385639 0.13200878, -0.10928698 0.14413817 0.13200878, -0.10925062 0.14443725 0.13200863, -0.41000089 0.15210272 0.13393398, 0.40999946 0.15210797 0.13393398, -0.41000074 0.15273678 0.13371198, 0.40999946 0.15274212 0.13371198, -0.41000077 0.15330578 0.13335468, 0.40999946 0.1533111 0.13335468, -0.41000077 0.15378074 0.13287981, 0.40999952 0.15378608 0.13287981, -0.41000089 0.15413831 0.13231094, 0.40999952 0.15414348 0.13231094, -0.41000086 0.15436015 0.13167696, 0.40999952 0.15436538 0.13167687, -0.41000077 0.15443532 0.13100938, 0.40999946 0.15444064 0.13100938, -0.10928693 0.14473642 0.13200878, -0.10939377 0.14501818 0.13200878, -0.10956501 0.14526621 0.13200878, -0.10979053 0.14546597 0.13200878, -0.11005743 0.14560604 0.13200898, -0.11034998 0.14567816 0.13200878, -0.11065137 0.14567816 0.13200878, -0.11094396 0.14560612 0.13200898, -0.1112107 0.14546597 0.13200878, -0.11143634 0.14526618 0.13200878, -0.11160737 0.1450181 0.13200878, -0.11171433 0.14473641 0.13200878, 0.11171302 0.14473793 0.13200878, 0.11160628 0.14501965 0.13200878, 0.11143504 0.1452677 0.13200878, 0.11120948 0.14546746 0.13200878, 0.11094271 0.1456075 0.13200878, 0.11065008 0.14567961 0.13200878, 0.11034872 0.14567959 0.13200878, 0.1100563 0.14560743 0.13200878, 0.10978939 0.14546737 0.13200878, 0.10956387 0.14526755 0.13200878, 0.1093927 0.14501959 0.13200878, 0.10928579 0.14473778 0.13200878, 0.4012132 0.1447397 0.13200878, 0.40110639 0.14502144 0.13200878, 0.4009352 0.14526947 0.13200878, 0.40070966 0.14546925 0.13200878, 0.40044281 0.14560929 0.13200878, 0.40015027 0.14568144 0.13200898, 0.39984903 0.14568141 0.13200878, 0.39955625 0.14560941 0.13200878, 0.39928943 0.1454692 0.13200878, 0.39906397 0.14526947 0.13200878, 0.39889273 0.14502151 0.13200878, 0.39878592 0.14473964 0.13200878, 0.27621317 0.14473888 0.13200878, 0.27610624 0.14502072 0.13200878, 0.27593517 0.14526871 0.13200878, 0.27570963 0.14546852 0.13200878, 0.27544272 0.14560854 0.13200878, 0.27515021 0.14568061 0.13200878, 0.27484885 0.14568064 0.13200878, 0.27455625 0.14560857 0.13200878, 0.27428943 0.1454685 0.13200878, 0.2740638 0.14526871 0.13200878, 0.27389264 0.14502072 0.13200878, 0.27378583 0.1447389 0.13200878, 0.26421311 0.14473888 0.13200878, 0.26410621 0.14502069 0.13200878, 0.26393512 0.14526865 0.13200878, 0.26370963 0.14546843 0.13200878, 0.26344278 0.14560843 0.13200878, 0.26315024 0.1456805 0.13200878, 0.26284897 0.14568052 0.13200878, 0.26255628 0.14560837 0.13200878, 0.26228946 0.14546829 0.13200878, 0.26206389 0.14526851 0.13200878, 0.26189274 0.14502054 0.13200878, 0.26178595 0.14473875 0.13200878, 0.10121311 0.14473774 0.13200878, 0.1011063 0.14501956 0.13200878, 0.10093506 0.14526755 0.13200878, 0.10070954 0.14546728 0.13200878, 0.10044266 0.14560741 0.13200878, 0.10015019 0.14567947 0.13200878, 0.099848807 0.14567949 0.13200878, 0.099556118 0.14560747 0.13200878, 0.099289335 0.14546734 0.13200878, 0.099063784 0.14526755 0.13200878, 0.098892726 0.1450195 0.13200878, 0.09878581 0.14473778 0.13200878, -0.098787062 0.14473657 0.13200878, -0.098893844 0.14501829 0.13200878, -0.099065058 0.14526628 0.13200878, -0.099290572 0.14546604 0.13200878, -0.099557407 0.14560615 0.13200878, -0.099850029 0.14567827 0.13200878, -0.10015136 0.1456783 0.13200878, -0.10044392 0.14560613 0.13200878, -0.10071082 0.14546612 0.13200878, -0.10093633 0.14526623 0.13200878, -0.10110755 0.14501831 0.13200878, -0.10121438 0.1447365 0.13200878, -0.261787 0.1447355 0.13200878, -0.26189399 0.14501733 0.13200878, -0.26206514 0.1452653 0.13200878, -0.26229066 0.14546505 0.13200878, -0.26255745 0.14560504 0.13200878, -0.26285005 0.14567715 0.13200878, -0.26315135 0.14567718 0.13200878, -0.26344401 0.14560506 0.13200878, -0.26371086 0.145465 0.13200878, -0.26393637 0.14526513 0.13200878, -0.2641075 0.14501721 0.13200878, -0.2642144 0.14473534 0.13200878, -0.27378699 0.1447354 0.13200878, -0.27389389 0.14501715 0.13200878, -0.27406505 0.14526507 0.13200878, -0.27429062 0.14546493 0.13200878, -0.27455747 0.14560504 0.13200878, -0.27485001 0.14567709 0.13200878, -0.27515143 0.14567712 0.13200878, -0.27544403 0.145605 0.13200878, -0.27571076 0.14546488 0.13200878, -0.27593639 0.14526512 0.13200878, -0.27610755 0.14501718 0.13200878, -0.27621439 0.14473531 0.13200878, -0.33378717 0.14473502 0.13200878, -0.3338939 0.14501674 0.13200878, -0.33406523 0.14526483 0.13200878, -0.33429074 0.14546457 0.13200878, -0.33455756 0.14560457 0.13200878, -0.33485013 0.14567679 0.13200878, -0.33515146 0.14567679 0.13200878, -0.335444 0.14560458 0.13200878, -0.33571085 0.14546451 0.13200878, -0.33593646 0.14526474 0.13200878, -0.33610758 0.14501671 0.13200878, -0.33621451 0.14473499 0.13200878, -0.39878711 0.14473462 0.13200878, -0.39889395 0.14501634 0.13200878, -0.39906517 0.14526433 0.13200878, -0.39929077 0.14546421 0.13200878, -0.3995575 0.14560416 0.13200878, -0.39985004 0.14567624 0.13200878, -0.4001514 0.14567633 0.13200878, -0.40044412 0.14560415 0.13200878, -0.40071091 0.14546414 0.13200878, -0.40093639 0.14526436 0.13200878, -0.40110764 0.14501633 0.13200878, -0.40121457 0.14473458 0.13200878, -0.40822563 0.15417492 0.11400931, -0.40877017 0.15385902 0.11400931, -0.40700081 0.15443629 0.11400931, -0.40762714 0.15437029 0.11400934, -0.39123133 0.15385914 0.11400931, -0.39177606 0.15417515 0.11400934, -0.39237472 0.15437041 0.11400931, -0.39300087 0.15443642 0.11400931, -0.40877017 0.15387183 -0.11399089, -0.40822572 0.15418787 -0.11399089, -0.40762708 0.15438318 -0.11399065, -0.40700075 0.15444918 -0.11399089, -0.39300084 0.15444931 -0.11399065, -0.39237472 0.15438321 -0.11399089, -0.39177606 0.15418789 -0.11399089, -0.39123139 0.15387194 -0.11399089, -0.4092308 -0.034569114 0.11399879, -0.40876457 -0.03498961 0.11399879, -0.40822098 -0.035303816 0.11399879, -0.40699953 -0.035563692 0.11399852, -0.4076241 -0.035498068 0.11399852, -0.39177844 -0.035303697 0.11399864, -0.39299962 -0.035563588 0.11399864, -0.3923752 -0.035497978 0.11399864, -0.39123484 -0.034989491 0.11399864, -0.39076862 -0.0345691 0.11399879, -0.39076862 -0.034556225 -0.11400156, -0.3912349 -0.034976602 -0.11400144, -0.39177826 -0.035290927 -0.11400144, -0.39237532 -0.035485029 -0.11400156, -0.39299962 -0.035550743 -0.11400144, -0.4076241 -0.035485134 -0.11400156, -0.40699968 -0.035550863 -0.11400156, -0.40822098 -0.035291001 -0.11400156, -0.40876457 -0.034976766 -0.11400156, -0.40923068 -0.034556434 -0.11400144, -0.4099997 -0.035485014 -0.11637719, 0.41000077 -0.035479814 -0.11637707, 0.41000071 -0.035285681 -0.11578004, 0.41000083 -0.035545513 -0.11700152, -0.4099997 -0.035550699 -0.11700152, -0.4099997 -0.035290882 -0.11578019, 0.41000077 -0.03497152 -0.11523651, -0.40999964 -0.034976795 -0.11523668, 0.41000071 -0.034551159 -0.11477052, -0.4099997 -0.034556404 -0.11477031, -0.40999973 -0.033851445 -0.13370429, -0.4099997 -0.034420237 -0.13334693, -0.4099997 -0.034895271 -0.13287179, -0.4099997 -0.035252795 -0.13230325, -0.4099997 -0.035474643 -0.131669, -0.4099997 -0.033217296 -0.13392629, -0.4099997 -0.035549954 -0.13100146, -0.4099997 -0.032549724 -0.13400139, -0.40999982 -0.017325014 -0.13373919, -0.40999982 -0.017923638 -0.13393463, -0.40999982 -0.01854974 -0.13400055, -0.40999982 -0.016780436 -0.13342322, 0.41000059 -0.016775191 -0.13342322, 0.41000065 -0.017319828 -0.13373919, 0.41000059 -0.017918378 -0.13393463, 0.41000059 -0.018544525 -0.13400055, 0.41000071 -0.035544649 -0.13100137, 0.41000077 -0.035469443 -0.131669, 0.41000074 -0.035247505 -0.13230313, 0.41000071 -0.034890041 -0.13287179, 0.41000071 -0.034414977 -0.13334693, 0.41000071 -0.033846259 -0.13370429, 0.41000071 -0.033212036 -0.13392629, 0.41000068 -0.032544598 -0.13400139, -0.26189274 -0.026129782 -0.13400109, -0.15360644 -0.026129045 -0.134001, -0.26206407 -0.026377745 -0.134001, 0.1515649 -0.02637507 -0.134001, 0.15179047 -0.02657491 -0.13400109, 0.11143614 -0.026375324 -0.134001, -0.15320972 -0.026576877 -0.134001, -0.15294278 -0.026716933 -0.134001, -0.26228946 -0.026577592 -0.134001, 0.11121057 -0.026575126 -0.134001, -0.26255637 -0.026717611 -0.134001, 0.15139374 -0.026127063 -0.134001, -0.15371327 -0.025847271 -0.134001, -0.40093532 -0.026378617 -0.134001, -0.40070978 -0.026578456 -0.134001, -0.40110663 -0.026130617 -0.134001, -0.26178595 -0.025848068 -0.134001, 0.11160731 -0.026127324 -0.134001, -0.26284897 -0.026789717 -0.134001, -0.15265021 -0.026789032 -0.134001, -0.29162607 -0.02862642 -0.13400109, -0.40044299 -0.026718467 -0.134001, 0.15205736 -0.026714973 -0.134001, 0.11094381 -0.026715189 -0.134001, -0.40121344 -0.02584891 -0.134001, 0.15128684 -0.025845341 -0.13400082, -0.40015045 -0.026790589 -0.13400109, 0.3587456 -0.026985452 -0.134001, 0.39906511 -0.026373595 -0.134001, 0.35832101 -0.027600527 -0.13400109, -0.4012498 -0.025549695 -0.134001, -0.15374966 -0.025548108 -0.134001, 0.11171421 -0.025845572 -0.13400082, -0.26178595 -0.025249675 -0.13400082, -0.26174968 -0.025548823 -0.134001, 0.1523499 -0.026787087 -0.134001, -0.15234892 -0.026789054 -0.134001, -0.39984897 -0.026790619 -0.134001, 0.39929065 -0.026573375 -0.134001, 0.35776168 -0.028096154 -0.13400109, 0.11065122 -0.026787318 -0.134001, -0.40121344 -0.025250584 -0.134001, 0.35901067 -0.026286796 -0.134001, 0.39889386 -0.02612552 -0.134001, 0.15125051 -0.025546141 -0.134001, -0.39955643 -0.026718482 -0.134001, 0.11175055 -0.025546454 -0.134001, -0.15371329 -0.025248945 -0.134001, -0.40110663 -0.024968833 -0.134001, 0.3995575 -0.026713386 -0.13400109, 0.35710004 -0.028443411 -0.13400109, -0.15360646 -0.024967149 -0.13400082, 0.35910067 -0.025544912 -0.134001, 0.39878699 -0.02584374 -0.13400079, 0.15128689 -0.025247037 -0.134001, -0.2618928 -0.024967857 -0.134001, -0.40093532 -0.024720818 -0.13400082, 0.11160734 -0.024965532 -0.134001, 0.11171421 -0.025247276 -0.134001, -0.1534353 -0.024719223 -0.13400082, -0.40070978 -0.024520949 -0.13400082, -0.26228955 -0.024520122 -0.13400079, -0.26206401 -0.024719939 -0.13400082, 0.3987506 -0.025544524 -0.13400082, 0.15139373 -0.024965249 -0.134001, -0.40044299 -0.024380937 -0.134001, -0.1532097 -0.024519376 -0.13400082, 0.39878696 -0.025245413 -0.134001, 0.35901055 -0.024803013 -0.13400082, 0.15156488 -0.024717264 -0.134001, -0.15294282 -0.024379373 -0.13400082, -0.40015045 -0.024308816 -0.13400082, 0.1114362 -0.024717532 -0.13400082, -0.26255631 -0.024380118 -0.134001, -0.39984909 -0.024308786 -0.13400082, 0.39889377 -0.024963617 -0.134001, 0.35874566 -0.024104297 -0.13400079, -0.15265022 -0.024307273 -0.13400082, 0.15179044 -0.024517432 -0.13400082, 0.11121062 -0.0245177 -0.13400082, -0.39955643 -0.024380967 -0.13400079, -0.262849 -0.024307959 -0.13400082, 0.39906493 -0.024715677 -0.13400082, 0.35832098 -0.023489162 -0.13400079, 0.11094378 -0.024377674 -0.13400082, 0.15205725 -0.024377361 -0.13400082, 0.3992905 -0.024515808 -0.13400082, 0.11065122 -0.02430556 -0.13400082, 0.15234984 -0.024305224 -0.13400082, 0.35776165 -0.022993639 -0.13400079, -0.39906409 -0.026378617 -0.134001, -0.35832009 -0.027605191 -0.13400109, -0.39928958 -0.026578456 -0.134001, 0.39955735 -0.024375811 -0.13400082, 0.35709986 -0.022646263 -0.13400079, -0.35776076 -0.028100654 -0.134001, -0.15139274 -0.026129052 -0.134001, -0.1114352 -0.026376754 -0.134001, -0.15156394 -0.026377015 -0.134001, -0.15178952 -0.026576832 -0.134001, -0.39889279 -0.026130661 -0.134001, -0.35874465 -0.026990041 -0.134001, -0.11120962 -0.026576594 -0.13400109, -0.35709903 -0.028447941 -0.13400109, -0.15205626 -0.026716918 -0.13400109, -0.11160638 -0.026128776 -0.134001, -0.39878598 -0.02584888 -0.134001, -0.35900965 -0.026291296 -0.134001, -0.15128586 -0.025847271 -0.13400082, -0.11094281 -0.026716627 -0.134001, -0.35637334 -0.028626859 -0.134001, 0.15343623 -0.026375093 -0.134001, 0.26229051 -0.026574187 -0.134001, 0.15321067 -0.026574917 -0.134001, 0.15294383 -0.026714928 -0.134001, 0.26206496 -0.026374362 -0.134001, -0.3987861 -0.025250569 -0.134001, -0.35909978 -0.025549412 -0.134001, -0.39874962 -0.025549755 -0.134001, 0.29162696 -0.028622679 -0.13400109, -0.1117133 -0.025846973 -0.13400082, 0.35637435 -0.028622285 -0.13400109, 0.35562691 -0.028622255 -0.13400109, 0.15371422 -0.025845312 -0.134001, 0.26189375 -0.026126333 -0.134001, 0.15360737 -0.026127085 -0.134001, -0.35562599 -0.028626844 -0.13400109, 0.29237422 -0.02862262 -0.13400109, -0.11065028 -0.026788689 -0.134001, 0.099849924 -0.026787423 -0.134001, -0.099848859 -0.026788659 -0.134001, 0.10015122 -0.026787408 -0.13400109, 0.26255736 -0.02671425 -0.134001, 0.15265125 -0.026787095 -0.134001, -0.39889291 -0.024968773 -0.13400079, -0.35900956 -0.024807602 -0.134001, 0.40125057 -0.025544584 -0.134001, 0.40121433 -0.02584368 -0.134001, 0.40110746 -0.02612552 -0.134001, 0.40093628 -0.026373461 -0.134001, 0.40071073 -0.02657333 -0.134001, -0.1512859 -0.025249004 -0.134001, -0.11174958 -0.025547847 -0.13400082, -0.1512496 -0.02554816 -0.134001, 0.40044394 -0.026713371 -0.134001, 0.40015128 -0.026785508 -0.134001, 0.39985004 -0.026785553 -0.134001, 0.15375054 -0.025546134 -0.13400082, 0.26178694 -0.025844671 -0.13400082, 0.11034986 -0.026787326 -0.134001, -0.39906421 -0.024720773 -0.13400079, -0.35874459 -0.024108768 -0.134001, -0.1103489 -0.026788719 -0.134001, 0.39984992 -0.024303645 -0.13400082, 0.26284999 -0.026786357 -0.134001, 0.40015128 -0.0243036 -0.13400082, 0.40044388 -0.024375767 -0.13400079, 0.40071073 -0.024515897 -0.13400082, 0.40093634 -0.024715751 -0.13400082, 0.40110752 -0.024963677 -0.13400082, 0.40121439 -0.025245443 -0.134001, -0.11171331 -0.025248654 -0.13400082, 0.35637423 -0.022467434 -0.13400079, 0.35562697 -0.022467449 -0.13400079, 0.29162693 -0.022467829 -0.13400079, 0.26175058 -0.025545426 -0.134001, -0.39928964 -0.024520874 -0.13400079, -0.35832009 -0.023493707 -0.13400082, 0.26284993 -0.024304584 -0.13400082, 0.15265116 -0.024305262 -0.13400082, 0.11034989 -0.024305567 -0.134001, 0.10015118 -0.024305627 -0.13400079, 0.26178688 -0.025246337 -0.13400082, 0.09984985 -0.024305634 -0.13400079, -0.099848874 -0.024306923 -0.13400079, -0.10015021 -0.024306916 -0.13400082, -0.35776079 -0.022998124 -0.13400082, -0.11034892 -0.024306908 -0.13400082, -0.11065027 -0.024306923 -0.13400082, -0.15139273 -0.024967209 -0.134001, -0.1116064 -0.024966925 -0.134001, -0.15234889 -0.024307296 -0.134001, 0.15371422 -0.025247015 -0.134001, -0.29162607 -0.022471592 -0.13400079, -0.29237339 -0.022471629 -0.13400079, -0.35562608 -0.022471935 -0.13400079, 0.29237434 -0.022467904 -0.13400079, 0.15343617 -0.024717264 -0.13400082, 0.26189372 -0.024964504 -0.13400082, 0.1536074 -0.024965286 -0.13400082, -0.357099 -0.022650823 -0.13400082, -0.15178947 -0.024519436 -0.134001, -0.11143521 -0.024718985 -0.13400082, -0.15156394 -0.024719268 -0.134001, -0.35637343 -0.022471979 -0.13400079, -0.15205631 -0.024379373 -0.13400082, -0.11120969 -0.024519145 -0.134001, 0.26206487 -0.024716549 -0.13400082, 0.26229042 -0.024516672 -0.13400082, 0.15294378 -0.024377391 -0.13400082, 0.15321064 -0.024517462 -0.13400082, -0.11094291 -0.02437903 -0.13400082, 0.26255727 -0.024376653 -0.13400079, -0.3532548 -0.026989982 -0.13400109, -0.29431999 -0.027604707 -0.13400109, -0.35367924 -0.027605146 -0.13400109, -0.29376066 -0.028100267 -0.13400109, -0.35423866 -0.028100625 -0.13400109, -0.29474458 -0.026989765 -0.13400109, -0.29309896 -0.028447531 -0.13400109, -0.3549003 -0.028448015 -0.13400109, -0.10956391 -0.026376769 -0.134001, -0.10070965 -0.026576489 -0.134001, -0.10978947 -0.026576616 -0.134001, -0.29500955 -0.026290908 -0.134001, -0.35298976 -0.026291326 -0.134001, -0.10093522 -0.026376717 -0.134001, -0.1011063 -0.026128717 -0.134001, -0.29237336 -0.028626427 -0.13400109, 0.27406499 -0.02637434 -0.134001, 0.27429059 -0.026574187 -0.134001, 0.26393625 -0.026374355 -0.13400109, 0.26371071 -0.026574187 -0.13400109, 0.27389374 -0.026126303 -0.134001, -0.10939271 -0.026128799 -0.134001, -0.10044285 -0.02671653 -0.13400109, -0.11005632 -0.026716605 -0.134001, -0.3528997 -0.025549427 -0.13400082, -0.29509962 -0.025549009 -0.134001, 0.26421428 -0.025844678 -0.134001, 0.26410744 -0.02612634 -0.13400109, -0.10121325 -0.025846928 -0.13400082, 0.27455735 -0.026714221 -0.134001, 0.26344389 -0.026714258 -0.134001, 0.26315129 -0.026786387 -0.134001, -0.29500952 -0.024807252 -0.13400082, -0.35298976 -0.024807557 -0.134001, -0.10928588 -0.025847025 -0.134001, -0.10015025 -0.026788667 -0.134001, 0.26425058 -0.02554547 -0.134001, 0.2737869 -0.025844514 -0.134001, -0.35325482 -0.024108812 -0.13400079, -0.29474452 -0.02410841 -0.13400082, -0.35367927 -0.023493782 -0.13400082, 0.27485004 -0.02678635 -0.134001, -0.10124958 -0.02554778 -0.134001, -0.10924953 -0.025547907 -0.13400082, 0.26421434 -0.025246352 -0.13400082, 0.27375063 -0.025545426 -0.134001, -0.29432002 -0.023493335 -0.13400079, -0.10928582 -0.025248729 -0.13400082, -0.10121321 -0.025248632 -0.134001, 0.26410741 -0.024964526 -0.13400082, 0.2737869 -0.02524624 -0.134001, -0.35423872 -0.022998154 -0.13400079, -0.29376069 -0.022997744 -0.13400079, -0.10110638 -0.024966873 -0.134001, 0.26393622 -0.024716519 -0.13400079, 0.27389386 -0.024964519 -0.134001, -0.10939272 -0.024966955 -0.13400082, -0.35490048 -0.022650853 -0.13400079, -0.29309902 -0.022650421 -0.13400079, -0.10093524 -0.024718948 -0.134001, 0.26371068 -0.024516717 -0.13400082, 0.27406502 -0.024716556 -0.13400082, -0.10956389 -0.024719007 -0.13400082, -0.10070962 -0.024519086 -0.13400082, 0.27429056 -0.024516709 -0.13400082, -0.10978944 -0.024519183 -0.134001, 0.26315126 -0.024304502 -0.134001, 0.27455729 -0.024376586 -0.13400082, 0.26344377 -0.024376623 -0.13400082, -0.1004428 -0.024379037 -0.13400082, -0.11005633 -0.024379052 -0.13400082, 0.27484989 -0.024304532 -0.13400082, -0.28925478 -0.026989602 -0.134001, -0.27593532 -0.026377775 -0.13400109, -0.28967914 -0.027604729 -0.134001, -0.27570969 -0.026577637 -0.134001, -0.29023859 -0.028100267 -0.134001, -0.28898972 -0.026290879 -0.13400109, -0.27610642 -0.026129827 -0.13400109, -0.27544284 -0.026717648 -0.134001, -0.29090032 -0.028447613 -0.13400139, -0.28889963 -0.025549017 -0.134001, -0.27621329 -0.025848091 -0.13400082, -0.27515036 -0.026789799 -0.134001, 0.27593628 -0.026374333 -0.134001, 0.28968015 -0.027600907 -0.13400109, 0.27571073 -0.026574127 -0.134001, -0.099063925 -0.02637668 -0.134001, 0.099290408 -0.026575238 -0.134001, -0.099289484 -0.026576512 -0.134001, 0.099064894 -0.026375398 -0.134001, -0.27624965 -0.02554889 -0.13400079, -0.27484894 -0.026789792 -0.134001, 0.29023963 -0.028096586 -0.13400109, -0.098892704 -0.026128694 -0.134001, 0.098893672 -0.026127368 -0.134001, 0.27544385 -0.026714176 -0.134001, -0.28898972 -0.024807155 -0.134001, -0.27621332 -0.025249802 -0.13400082, 0.099557258 -0.026715256 -0.134001, 0.28925574 -0.026985928 -0.13400109, -0.099556319 -0.026716508 -0.134001, 0.098786868 -0.025845662 -0.134001, 0.27610743 -0.026126251 -0.134001, -0.0987859 -0.025846928 -0.134001, -0.28925478 -0.02410832 -0.13400082, -0.27610645 -0.024968036 -0.134001, 0.29090133 -0.028443836 -0.13400109, 0.27515131 -0.026786372 -0.134001, 0.098750524 -0.025546513 -0.134001, 0.28899071 -0.026287213 -0.134001, -0.28967929 -0.023493297 -0.13400082, -0.27593526 -0.024720073 -0.13400082, -0.098749585 -0.025547795 -0.134001, 0.27621433 -0.025844567 -0.134001, 0.098786891 -0.02524738 -0.13400082, -0.27570972 -0.024520189 -0.13400079, -0.29023865 -0.022997767 -0.13400079, -0.098785959 -0.025248602 -0.134001, 0.28890058 -0.025545232 -0.134001, -0.27544287 -0.024380118 -0.13400079, 0.098893732 -0.024965607 -0.13400082, -0.29090038 -0.022650503 -0.13400079, -0.098892786 -0.024966821 -0.134001, 0.27621427 -0.025246173 -0.134001, 0.27625063 -0.025545381 -0.13400082, -0.27515027 -0.024308093 -0.13400082, 0.28899065 -0.024803415 -0.13400082, 0.099064887 -0.024717622 -0.13400082, 0.27610737 -0.024964407 -0.134001, -0.099063903 -0.024718888 -0.13400082, 0.28925571 -0.024104618 -0.13400082, -0.27484891 -0.024308145 -0.13400082, 0.09929046 -0.024517797 -0.13400082, 0.27593625 -0.024716467 -0.13400082, -0.099289492 -0.024519116 -0.13400082, 0.28968018 -0.023489594 -0.13400079, -0.099556327 -0.024378993 -0.13400082, 0.099557258 -0.024377748 -0.13400079, 0.27571067 -0.024516664 -0.134001, 0.29023957 -0.022994064 -0.13400079, 0.27544388 -0.024376668 -0.13400079, -0.27406406 -0.02637773 -0.134001, -0.26370966 -0.02657754 -0.134001, -0.27428961 -0.026577592 -0.134001, -0.26393527 -0.02637773 -0.134001, 0.29090124 -0.022646703 -0.13400079, 0.27515128 -0.024304517 -0.13400082, -0.27389282 -0.026129812 -0.134001, -0.26410651 -0.02612973 -0.134001, -0.26344293 -0.026717611 -0.134001, -0.27455634 -0.026717715 -0.134001, -0.27378589 -0.025848068 -0.13400082, -0.26421332 -0.025847971 -0.134001, 0.10093618 -0.026375383 -0.134001, 0.10979046 -0.026575193 -0.134001, 0.10071059 -0.0265752 -0.134001, -0.26315022 -0.026789777 -0.134001, 0.10956492 -0.026375338 -0.134001, 0.10110736 -0.026127435 -0.134001, 0.10939369 -0.026127331 -0.134001, -0.27378601 -0.025249764 -0.134001, -0.26424971 -0.025548801 -0.134001, -0.27374968 -0.02554889 -0.134001, 0.1100573 -0.026715189 -0.134001, 0.10044381 -0.026715316 -0.134001, -0.26421326 -0.02524972 -0.13400082, 0.10121419 -0.025845654 -0.13400082, 0.10928686 -0.025845617 -0.134001, 0.29432091 -0.027600877 -0.134001, 0.35368022 -0.027600572 -0.134001, 0.29376158 -0.028096512 -0.13400109, 0.29474548 -0.026985846 -0.134001, 0.35423955 -0.02809608 -0.13400109, 0.29309991 -0.028443836 -0.13400109, 0.35325572 -0.026985481 -0.134001, -0.27389288 -0.024967991 -0.134001, -0.26410654 -0.024967931 -0.134001, 0.10125051 -0.025546521 -0.134001, 0.10925052 -0.025546432 -0.134001, 0.35490146 -0.028443456 -0.13400109, -0.27406403 -0.024719998 -0.134001, -0.26393524 -0.024719976 -0.13400082, 0.35299072 -0.026286721 -0.134001, 0.1012142 -0.02524735 -0.134001, 0.10928684 -0.025247313 -0.13400082, 0.29501054 -0.026287109 -0.134001, -0.26370975 -0.024520107 -0.13400082, -0.27428958 -0.024520174 -0.134001, 0.35290065 -0.025544882 -0.134001, 0.10110729 -0.024965532 -0.13400082, 0.10939369 -0.02496548 -0.13400082, 0.2951006 -0.025545239 -0.134001, -0.27455637 -0.024380252 -0.13400079, -0.26344302 -0.024380036 -0.13400082, 0.10956486 -0.024717525 -0.13400082, 0.35299078 -0.024803042 -0.134001, 0.29501045 -0.024803378 -0.13400079, 0.10093614 -0.024717577 -0.13400082, -0.2631503 -0.024307929 -0.13400082, 0.29474545 -0.024104588 -0.13400082, 0.10979042 -0.024517693 -0.13400082, 0.1007106 -0.024517722 -0.13400079, 0.29432097 -0.023489565 -0.13400082, 0.35325572 -0.024104252 -0.13400079, 0.11005723 -0.024377644 -0.13400082, 0.10044377 -0.024377726 -0.134001, 0.35368022 -0.023489192 -0.13400079, 0.29376164 -0.022994056 -0.13400079, 0.35423961 -0.022993624 -0.13400079, -0.15343523 -0.026377015 -0.134001, 0.29309985 -0.022646755 -0.13400079, 0.35490128 -0.022646293 -0.13400079, 0.15375055 -0.02554629 -0.13200094, 0.15371424 -0.025845446 -0.13200094, 0.1536074 -0.026127197 -0.13200094, 0.1534362 -0.026375175 -0.13200094, 0.15321063 -0.026575036 -0.13200094, 0.15294382 -0.026715077 -0.13200106, 0.15265124 -0.026787177 -0.13200094, 0.15234984 -0.026787147 -0.13200094, 0.15205728 -0.026715055 -0.13200094, 0.15179047 -0.026575014 -0.13200094, 0.15156493 -0.026375189 -0.13200094, 0.15139374 -0.026127212 -0.13200094, 0.15128691 -0.025845483 -0.13200094, 0.15125056 -0.025546312 -0.13200094, -0.15124957 -0.025548235 -0.13200094, -0.15128595 -0.025847346 -0.13200094, -0.15139277 -0.026129164 -0.13200094, -0.151564 -0.026377119 -0.13200094, -0.15178955 -0.026576944 -0.13200094, -0.15205631 -0.02671697 -0.13200106, -0.15234892 -0.026789099 -0.13200094, -0.15265024 -0.026789106 -0.13200094, -0.15294284 -0.026717015 -0.13200094, -0.15320969 -0.026576929 -0.13200094, -0.15343526 -0.026377112 -0.13200094, -0.15360644 -0.026129141 -0.13200094, -0.15371329 -0.02584736 -0.13200094, -0.15374969 -0.025548197 -0.13200094, 0.40125072 -0.025544733 -0.13200094, 0.40121433 -0.025843859 -0.13200094, 0.40110746 -0.02612561 -0.13200094, 0.40093634 -0.02637367 -0.13200094, 0.40071073 -0.026573464 -0.13200094, 0.400444 -0.02671352 -0.13200094, 0.40015128 -0.026785538 -0.13200094, 0.39984995 -0.026785508 -0.13200094, 0.39955738 -0.026713505 -0.13200094, 0.39929053 -0.02657342 -0.13200106, 0.39906499 -0.02637364 -0.13200094, 0.39889392 -0.02612564 -0.13200094, 0.39878699 -0.025843889 -0.13200106, 0.39875072 -0.025544778 -0.13200094, 0.27625051 -0.02554547 -0.13200094, 0.27621424 -0.025844581 -0.13200094, 0.27610731 -0.02612637 -0.13200094, 0.27593616 -0.026374318 -0.13200094, 0.27571064 -0.026574127 -0.13200094, 0.27544388 -0.026714258 -0.13200094, 0.27515131 -0.026786372 -0.13200094, 0.27484989 -0.026786365 -0.13200094, 0.27455729 -0.026714228 -0.13200106, 0.27429044 -0.026574224 -0.13200106, 0.27406502 -0.026374482 -0.13200094, 0.27389377 -0.026126459 -0.13200094, 0.2737869 -0.025844708 -0.13200094, 0.27375057 -0.025545485 -0.13200094, 0.26425064 -0.025545634 -0.13200094, 0.26421428 -0.025844723 -0.13200094, 0.26410741 -0.026126474 -0.13200094, 0.26393628 -0.026374511 -0.13200094, 0.26371071 -0.026574314 -0.13200094, 0.26344383 -0.026714362 -0.13200094, 0.26315123 -0.026786424 -0.13200112, 0.26284999 -0.026786543 -0.13200094, 0.26255739 -0.026714414 -0.13200094, 0.26229051 -0.026574366 -0.13200094, 0.26206496 -0.026374504 -0.13200106, 0.26189375 -0.026126459 -0.13200094, 0.26178691 -0.025844753 -0.13200094, 0.2617507 -0.025545627 -0.13200094, 0.1012505 -0.025546625 -0.13200094, 0.10121421 -0.025845744 -0.13200094, 0.10110731 -0.026127502 -0.13200094, 0.10093611 -0.02637548 -0.13200094, 0.10071059 -0.026575312 -0.13200094, 0.10044378 -0.02671539 -0.13200094, 0.1001512 -0.02678749 -0.13200094, 0.099849887 -0.026787527 -0.13200094, 0.099557273 -0.026715398 -0.13200094, 0.099290438 -0.026575372 -0.13200094, 0.099064916 -0.026375547 -0.13200094, 0.098893709 -0.026127554 -0.13200094, 0.098786861 -0.025845796 -0.13200094, 0.098750532 -0.025546655 -0.13200094, -0.098749541 -0.025547922 -0.13200094, -0.09878587 -0.025847085 -0.13200094, -0.098892733 -0.026128858 -0.13200094, -0.099063911 -0.026376784 -0.13200094, -0.099289455 -0.026576631 -0.13200094, -0.099556305 -0.026716664 -0.13200106, -0.099848896 -0.026788816 -0.13200094, -0.10015021 -0.026788801 -0.13200094, -0.10044279 -0.026716679 -0.13200094, -0.10070964 -0.026576631 -0.13200094, -0.10093518 -0.026376791 -0.13200106, -0.10110637 -0.026128821 -0.13200094, -0.1012133 -0.025847025 -0.13200094, -0.10124961 -0.025547892 -0.13200094, -0.26174968 -0.025548883 -0.13200094, -0.26178592 -0.02584812 -0.13200094, -0.2618928 -0.026129842 -0.13200094, -0.26206398 -0.026377857 -0.13200106, -0.26228949 -0.026577659 -0.13200094, -0.26255631 -0.026717752 -0.13200094, -0.26284903 -0.026789777 -0.13200094, -0.2631503 -0.026789851 -0.13200094, -0.26344293 -0.0267177 -0.13200106, -0.26370972 -0.026577644 -0.13200094, -0.26393533 -0.026377819 -0.13200094, -0.26410651 -0.026129849 -0.13200094, -0.26421332 -0.025848128 -0.13200094, -0.26424962 -0.025548995 -0.13200094, -0.27374962 -0.025549039 -0.13200094, -0.27378598 -0.025848165 -0.13200106, -0.27389288 -0.026129857 -0.13200094, -0.27406412 -0.026377849 -0.13200106, -0.27428967 -0.026577689 -0.13200094, -0.2745564 -0.026717827 -0.13200094, -0.27484897 -0.026789829 -0.13200094, -0.2751503 -0.026789948 -0.13200094, -0.27544287 -0.026717812 -0.13200094, -0.27570969 -0.026577726 -0.13200094, -0.27593532 -0.026377901 -0.13200094, -0.27610645 -0.026129901 -0.13200094, -0.27621335 -0.02584821 -0.13200094, -0.27624974 -0.025549002 -0.13200094, -0.39874962 -0.025549889 -0.13200094, -0.3987861 -0.025849 -0.13200106, -0.39889279 -0.02613081 -0.13200094, -0.39906409 -0.026378706 -0.13200106, -0.39928961 -0.02657856 -0.13200094, -0.39955643 -0.026718587 -0.13200094, -0.39984897 -0.026790708 -0.13200106, -0.40015033 -0.026790708 -0.13200106, -0.40044299 -0.026718572 -0.13200112, -0.40070978 -0.026578546 -0.13200094, -0.40093532 -0.026378721 -0.13200094, -0.40110663 -0.026130706 -0.13200094, -0.40121344 -0.025848985 -0.13200094, -0.40124968 -0.025549844 -0.13200094, 0.11175051 -0.025546551 -0.13200094, 0.11171421 -0.025845706 -0.13200094, 0.11160737 -0.026127465 -0.13200094, 0.1114362 -0.026375473 -0.13200094, 0.11121064 -0.026575282 -0.13200094, 0.11094383 -0.026715346 -0.13200094, 0.1106512 -0.02678743 -0.13200094, 0.11034991 -0.026787452 -0.13200106, 0.11005725 -0.026715294 -0.13200094, 0.10979043 -0.026575282 -0.13200094, 0.10956484 -0.026375458 -0.13200094, 0.10939366 -0.026127473 -0.13200094, 0.10928688 -0.025845721 -0.13200094, 0.10925052 -0.025546588 -0.13200094, -0.10924961 -0.025547951 -0.13200094, -0.10928594 -0.025847092 -0.13200094, -0.10939273 -0.026128918 -0.13200094, -0.10956392 -0.026376858 -0.13200094, -0.10978951 -0.026576683 -0.13200094, -0.11005635 -0.026716724 -0.13200094, -0.11034894 -0.026788808 -0.13200094, -0.11065029 -0.026788801 -0.13200094, -0.1109429 -0.026716672 -0.13200094, -0.11120968 -0.026576698 -0.13200094, -0.11143521 -0.026376888 -0.13200094, -0.11160636 -0.026128888 -0.13200094, -0.11171322 -0.025847137 -0.13200094, -0.11174963 -0.025547944 -0.13200094, -0.35909978 -0.025549486 -0.13200094, -0.35900965 -0.026291415 -0.13200094, -0.35874465 -0.026990131 -0.13200094, -0.35832009 -0.027605191 -0.13200112, -0.35776076 -0.028100803 -0.13200112, -0.357099 -0.028448075 -0.13200112, -0.35637322 -0.028627023 -0.13200112, -0.35562608 -0.028626949 -0.13200112, -0.35490039 -0.028448105 -0.13200112, -0.35423866 -0.028100833 -0.13200112, -0.35367927 -0.027605236 -0.13200094, -0.3532548 -0.02699019 -0.13200106, -0.35298982 -0.0262914 -0.13200094, -0.3528997 -0.025549471 -0.13200094, -0.29509962 -0.025549158 -0.13200094, -0.29500958 -0.02629102 -0.13200094, -0.29474455 -0.026989803 -0.13200094, -0.29431999 -0.027604833 -0.13200106, -0.29376063 -0.028100491 -0.13200106, -0.29309899 -0.028447695 -0.13200112, -0.29237336 -0.028626554 -0.13200106, -0.29162595 -0.028626554 -0.13200112, -0.29090038 -0.028447673 -0.13200112, -0.29023862 -0.028100386 -0.13200112, -0.28967929 -0.027604781 -0.13200094, -0.28925478 -0.026989721 -0.13200112, -0.28898978 -0.026290923 -0.13200094, -0.28889966 -0.025549062 -0.13200094, 0.28890058 -0.025545411 -0.13200094, 0.28899077 -0.02628734 -0.13200094, 0.28925571 -0.026986085 -0.13200094, 0.28968021 -0.027601115 -0.13200094, 0.29023951 -0.028096594 -0.13200106, 0.29090133 -0.028443925 -0.13200106, 0.29162681 -0.028622746 -0.13200112, 0.29237422 -0.028622776 -0.13200094, 0.2931 -0.028444014 -0.13200106, 0.29376164 -0.028096661 -0.13200106, 0.29432109 -0.027601078 -0.13200112, 0.29474565 -0.02698604 -0.13200106, 0.2950106 -0.026287317 -0.13200094, 0.29510063 -0.025545396 -0.13200094, 0.35290065 -0.025545046 -0.13200094, 0.35299072 -0.02628684 -0.13200094, 0.35325563 -0.026985571 -0.13200094, 0.35368022 -0.027600661 -0.13200112, 0.35423967 -0.028096229 -0.13200106, 0.3549014 -0.028443515 -0.13200106, 0.35562703 -0.028622419 -0.13200112, 0.35637429 -0.028622359 -0.13200112, 0.35709992 -0.0284435 -0.13200112, 0.35776162 -0.028096154 -0.13200112, 0.35832104 -0.027600631 -0.13200106, 0.35874555 -0.026985615 -0.13200094, 0.35901055 -0.02628687 -0.13200094, 0.35910061 -0.025544941 -0.13200094, 0.35901064 -0.024803132 -0.13200094, 0.35874552 -0.024104342 -0.13200094, 0.35832101 -0.023489237 -0.13200094, 0.35776165 -0.022993758 -0.13200094, 0.35709989 -0.022646427 -0.13200094, 0.35637429 -0.022467583 -0.13200061, 0.35562688 -0.022467509 -0.13200094, 0.35490131 -0.022646427 -0.13200094, 0.35423958 -0.022993714 -0.13200094, 0.35368022 -0.023489326 -0.13200094, 0.35325572 -0.024104357 -0.13200094, 0.35299066 -0.024803072 -0.13200094, 0.29501054 -0.024803475 -0.13200094, 0.29474556 -0.024104752 -0.13200094, 0.29432103 -0.023489721 -0.13200094, 0.29376164 -0.022994153 -0.13200094, 0.29309985 -0.022646807 -0.13200094, 0.29237431 -0.022468001 -0.13200094, 0.29162696 -0.022467986 -0.13200094, 0.29090133 -0.022646829 -0.13200094, 0.29023963 -0.022994168 -0.13200094, 0.28968027 -0.023489788 -0.13200094, 0.28925571 -0.024104781 -0.13200094, 0.28899068 -0.024803549 -0.13200094, -0.28898978 -0.024807245 -0.13200094, -0.28925478 -0.024108477 -0.13200094, -0.28967929 -0.023493439 -0.13200094, -0.29023862 -0.022997864 -0.13200094, -0.29090032 -0.022650637 -0.13200094, -0.29162601 -0.022471718 -0.13200094, -0.29237327 -0.022471771 -0.13200094, -0.29309902 -0.02265054 -0.13200094, -0.29376069 -0.022997864 -0.13200094, -0.29432008 -0.023493432 -0.13200094, -0.29474458 -0.024108522 -0.13200094, -0.29500958 -0.024807274 -0.13200094, -0.35298976 -0.024807662 -0.13200094, -0.35325482 -0.024108857 -0.13200094, -0.35367939 -0.023493797 -0.13200094, -0.35423872 -0.022998273 -0.13200094, -0.35490039 -0.022651002 -0.13200094, -0.35562596 -0.022472188 -0.13200094, -0.35637334 -0.022472188 -0.13200094, -0.35709903 -0.022651002 -0.13200094, -0.3577607 -0.022998303 -0.13200094, -0.35832012 -0.023493826 -0.13200094, -0.35874459 -0.024108917 -0.13200094, -0.35900959 -0.024807766 -0.13200094, -0.11171328 -0.025248803 -0.13200094, -0.11160642 -0.02496703 -0.13200094, -0.11143525 -0.024719059 -0.13200094, -0.1112097 -0.024519213 -0.13200094, -0.11094285 -0.024379179 -0.13200094, -0.11065034 -0.024307013 -0.13200094, -0.11034897 -0.024307005 -0.13200094, -0.11005634 -0.024379157 -0.13200094, -0.10978951 -0.02451925 -0.13200094, -0.10956394 -0.024719059 -0.13200094, -0.10939272 -0.024967037 -0.13200094, -0.1092859 -0.025248818 -0.13200094, 0.10928687 -0.025247484 -0.13200094, 0.10939371 -0.024965622 -0.13200094, 0.10956489 -0.024717651 -0.13200094, 0.10979046 -0.024517827 -0.13200094, 0.11005725 -0.024377771 -0.13200094, 0.11034985 -0.024305694 -0.13200094, 0.11065118 -0.024305657 -0.13200094, 0.11094379 -0.024377793 -0.13200094, 0.11121064 -0.024517827 -0.13200094, 0.11143613 -0.024717636 -0.13200094, 0.11160731 -0.024965614 -0.13200094, 0.11171421 -0.025247395 -0.13200094, -0.40121344 -0.025250673 -0.13200094, -0.40110663 -0.024968952 -0.13200094, -0.40093532 -0.024720997 -0.13200094, -0.40070978 -0.024521142 -0.13200094, -0.40044299 -0.024381101 -0.13200094, -0.40015033 -0.024309009 -0.13200094, -0.39984897 -0.024309024 -0.13200094, -0.39955643 -0.024381131 -0.13200094, -0.39928961 -0.024521038 -0.13200094, -0.39906409 -0.024720937 -0.13200094, -0.39889288 -0.024968848 -0.13200094, -0.39878598 -0.025250643 -0.13200094, -0.27621335 -0.025249876 -0.13200094, -0.27610648 -0.02496811 -0.13200094, -0.27593532 -0.024720177 -0.13200094, -0.27570969 -0.024520315 -0.13200094, -0.27544293 -0.024380267 -0.13200094, -0.27515033 -0.024308152 -0.13200094, -0.27484897 -0.02430816 -0.13200094, -0.27455643 -0.024380289 -0.13200094, -0.27428955 -0.024520308 -0.13200094, -0.27406409 -0.02472011 -0.13200094, -0.27389282 -0.024968117 -0.13200094, -0.27378592 -0.025249913 -0.13200094, -0.26421332 -0.025249824 -0.13200106, -0.26410651 -0.024967946 -0.13200094, -0.2639353 -0.024720065 -0.13200094, -0.26370981 -0.024520181 -0.13200094, -0.26344302 -0.02438017 -0.13200094, -0.2631503 -0.024308085 -0.13200094, -0.26284906 -0.024308071 -0.13200094, -0.26255631 -0.0243802 -0.13200094, -0.26228952 -0.024520211 -0.13200094, -0.26206401 -0.024720021 -0.13200094, -0.26189286 -0.024967976 -0.13200094, -0.26178592 -0.025249794 -0.13200094, -0.10121325 -0.025248751 -0.13200094, -0.10110644 -0.024966933 -0.13200094, -0.10093523 -0.024719015 -0.13200094, -0.10070967 -0.024519168 -0.13200094, -0.10044284 -0.024379104 -0.13200094, -0.10015022 -0.024307013 -0.13200094, -0.099848896 -0.02430702 -0.13200094, -0.099556342 -0.024379089 -0.13200094, -0.099289432 -0.024519198 -0.13200094, -0.099063911 -0.02471903 -0.13200094, -0.098892756 -0.024966955 -0.13200094, -0.09878587 -0.025248751 -0.13200094, 0.098786831 -0.025247484 -0.13200094, 0.098893665 -0.024965689 -0.13200094, 0.099064887 -0.024717681 -0.13200094, 0.099290386 -0.024517857 -0.13200094, 0.099557213 -0.02437783 -0.13200094, 0.099849865 -0.024305739 -0.13200094, 0.10015123 -0.024305768 -0.13200094, 0.10044375 -0.02437786 -0.13200094, 0.10071062 -0.024517916 -0.13200094, 0.10093617 -0.024717711 -0.13200094, 0.10110735 -0.024965674 -0.13200094, 0.1012142 -0.025247462 -0.13200094, 0.26178694 -0.025246434 -0.13200094, 0.26189372 -0.024964646 -0.13200094, 0.26206487 -0.024716683 -0.13200094, 0.26229054 -0.024516888 -0.13200094, 0.2625573 -0.024376757 -0.13200094, 0.26284987 -0.024304681 -0.13200094, 0.26315135 -0.024304725 -0.13200094, 0.26344389 -0.024376862 -0.13200094, 0.26371068 -0.024516843 -0.13200094, 0.26393625 -0.024716683 -0.13200094, 0.26410744 -0.024964623 -0.13200094, 0.26421422 -0.025246426 -0.13200094, 0.27378693 -0.025246382 -0.13200094, 0.27389374 -0.024964646 -0.13200094, 0.2740649 -0.024716586 -0.13200094, 0.27429047 -0.024516746 -0.13200094, 0.27455729 -0.024376705 -0.13200094, 0.27484989 -0.024304628 -0.13200094, 0.27515125 -0.024304621 -0.13200094, 0.27544385 -0.024376713 -0.13200094, 0.27571064 -0.024516724 -0.13200094, 0.27593622 -0.024716578 -0.13200094, 0.2761074 -0.024964556 -0.13200094, 0.27621424 -0.025246389 -0.13200094, 0.39878705 -0.025245577 -0.13200094, 0.39889398 -0.024963841 -0.13200094, 0.39906511 -0.024715811 -0.13200094, 0.39929059 -0.024515972 -0.13200094, 0.39955738 -0.024375916 -0.13200094, 0.39985004 -0.024303854 -0.13200094, 0.40015134 -0.024303824 -0.13200094, 0.40044394 -0.024376005 -0.13200094, 0.40071076 -0.024515986 -0.13200094, 0.40093625 -0.024715796 -0.13200094, 0.40110746 -0.024963796 -0.13200094, 0.40121433 -0.025245473 -0.13200094, -0.15371336 -0.025249042 -0.13200094, -0.15360646 -0.024967223 -0.13200094, -0.15343533 -0.024719328 -0.13200094, -0.15320973 -0.024519473 -0.13200094, -0.15294291 -0.024379469 -0.13200094, -0.15265025 -0.024307378 -0.13200094, -0.15234895 -0.024307355 -0.13200094, -0.15205638 -0.02437944 -0.13200094, -0.15178955 -0.024519503 -0.13200094, -0.15156396 -0.024719328 -0.13200094, -0.15139279 -0.024967283 -0.13200094, -0.15128595 -0.025249034 -0.13200094, 0.15128689 -0.025247157 -0.13200094, 0.15139373 -0.024965398 -0.13200094, 0.15156485 -0.024717383 -0.13200094, 0.15179047 -0.024517551 -0.13200094, 0.15205732 -0.02437754 -0.13200094, 0.15234989 -0.024305403 -0.13200094, 0.15265121 -0.024305396 -0.13200094, 0.15294376 -0.02437751 -0.13200094, 0.15321065 -0.024517544 -0.13200094, 0.1534362 -0.024717376 -0.13200094, 0.15360738 -0.024965331 -0.13200094, 0.15371417 -0.025247104 -0.13200094, -0.4099997 -0.034569249 0.1147678, 0.41000071 -0.034564018 0.11476751, -0.40999958 -0.034989685 0.11523385, 0.41000074 -0.034984469 0.11523376, -0.4099997 -0.035303906 0.11577739, 0.41000071 -0.035298601 0.11577721, -0.40999958 -0.035498127 0.11637427, 0.41000071 -0.035492823 0.11637427, -0.4099997 -0.035563961 0.1169986, 0.41000083 -0.035558745 0.1169986, -0.4099997 -0.035564587 0.13099851, -0.4099997 -0.03548947 0.13166626, -0.4099997 -0.035267636 0.13230042, -0.4099997 -0.034910277 0.13286941, -0.4099997 -0.034435168 0.13334416, -0.4099997 -0.03386654 0.13370152, -0.4099997 -0.033232465 0.13392349, -0.4099997 -0.032564864 0.13399883, -0.40999982 -0.017340139 0.13373812, -0.40999982 -0.018564925 0.13399942, -0.40999982 -0.017938733 0.13393371, -0.40999982 -0.016795352 0.13342233, 0.41000065 -0.018559679 0.13399966, 0.41000053 -0.017933398 0.1339335, 0.41000053 -0.017334849 0.13373812, 0.41000059 -0.016790107 0.13342218, 0.41000071 -0.033861324 0.13370173, 0.41000077 -0.034429953 0.13334416, 0.41000074 -0.034904957 0.13286917, 0.41000074 -0.035262346 0.13230042, 0.41000071 -0.03548421 0.13166614, 0.41000068 -0.03322722 0.13392366, 0.41000077 -0.035559461 0.1309986, 0.41000071 -0.032559603 0.13399883, -0.11160637 -0.026143894 0.13399915, -0.15128596 -0.025862329 0.1339993, -0.15139282 -0.026144117 0.13399915, 0.26284987 -0.026801459 0.13399915, 0.1526513 -0.026802175 0.13399915, 0.29162702 -0.028637819 0.13399892, 0.26255739 -0.026729338 0.13399915, 0.1529437 -0.026729986 0.13399906, -0.11174954 -0.025562987 0.13399915, -0.11171322 -0.025862142 0.1339993, -0.35874456 -0.027005196 0.13399906, -0.39906409 -0.026393741 0.13399906, -0.35831997 -0.027620316 0.13399906, 0.26178691 -0.025859714 0.13399915, 0.15375051 -0.025561251 0.13399915, 0.15371414 -0.025860347 0.13399915, -0.39928961 -0.026593506 0.13399906, 0.40093634 -0.026388556 0.13399906, 0.40071067 -0.026588365 0.13399915, -0.15205629 -0.02673202 0.13399906, -0.15234892 -0.026804104 0.13399906, -0.11065024 -0.026803836 0.1339993, -0.35776064 -0.028115809 0.13399915, 0.26175061 -0.025560625 0.13399915, 0.40110752 -0.026140571 0.13399915, -0.15124963 -0.025563188 0.13399915, -0.39889291 -0.026145756 0.13399915, 0.15234992 -0.026802167 0.13399915, 0.40044388 -0.026728377 0.13399915, -0.35900965 -0.026306421 0.13399915, 0.40121433 -0.025858805 0.13399915, -0.39955643 -0.026733533 0.13399915, -0.15128595 -0.02526404 0.13399906, -0.35709897 -0.028463036 0.13399906, 0.40015122 -0.026800543 0.13399915, 0.26189378 -0.024979688 0.1339993, 0.15371412 -0.025262028 0.13399915, 0.26178688 -0.025261432 0.1339993, 0.40125069 -0.025559738 0.13399915, -0.11160637 -0.024982065 0.13399915, -0.11171326 -0.025263786 0.13399915, -0.35909978 -0.025564522 0.13399915, -0.39878604 -0.025863975 0.13399906, 0.39985007 -0.026800573 0.13399915, 0.40121427 -0.025260463 0.13399915, 0.1536074 -0.024980411 0.13399942, -0.15139274 -0.024982333 0.13399915, 0.39955738 -0.026728436 0.13399906, -0.39874968 -0.025564834 0.13399915, 0.40110752 -0.024978772 0.1339993, 0.15343614 -0.024732366 0.1339993, -0.15156393 -0.024734385 0.13399915, 0.26229048 -0.024531864 0.1339993, 0.26206496 -0.024731711 0.1339993, 0.40093628 -0.024730757 0.13399915, -0.1114352 -0.02473411 0.13399915, 0.15321065 -0.024532564 0.1339993, -0.39878604 -0.025265694 0.13399915, -0.35900959 -0.024822682 0.13399915, -0.15178947 -0.024534538 0.13399906, 0.40071064 -0.024530873 0.13399915, -0.11094287 -0.024394214 0.1339993, -0.11120965 -0.024534255 0.13399915, -0.39889291 -0.024983853 0.1339993, 0.15294386 -0.024392523 0.1339993, 0.40044382 -0.024390921 0.13399915, 0.26284993 -0.024319671 0.13399915, 0.26255739 -0.024391852 0.1339993, -0.35874459 -0.024123892 0.1339993, -0.11065022 -0.024322115 0.1339993, -0.15205631 -0.024394527 0.1339993, 0.15265122 -0.024320379 0.1339993, -0.39906409 -0.024735913 0.13399915, 0.40015128 -0.02431877 0.1339993, -0.35832015 -0.023508862 0.1339993, -0.15234885 -0.024322391 0.13399915, -0.3577607 -0.023013324 0.13399942, -0.39928964 -0.024536088 0.1339993, -0.357099 -0.022666007 0.13399942, -0.39955643 -0.024396062 0.1339993, 0.39984995 -0.024318814 0.1339993, 0.39955738 -0.024390891 0.1339993, 0.151565 -0.026390217 0.13399915, 0.11121052 -0.026590191 0.13399906, 0.15179053 -0.026590101 0.13399915, 0.15205732 -0.026730046 0.13399906, 0.11143611 -0.026390374 0.13399915, 0.15139374 -0.02614221 0.13399915, 0.1116073 -0.026142426 0.13399906, 0.39906511 -0.026388556 0.13399915, 0.35832101 -0.027615607 0.13399906, 0.39929059 -0.02658841 0.13399915, -0.15343526 -0.026392154 0.13399915, -0.26206407 -0.026392832 0.13399906, -0.15320966 -0.026591972 0.13399915, 0.35776165 -0.028111264 0.13399906, 0.1109437 -0.026730262 0.13399915, -0.26228952 -0.026592657 0.13399906, 0.3988938 -0.026140571 0.13399915, 0.35874555 -0.027000621 0.13399915, 0.15125054 -0.025561273 0.1339993, 0.11171416 -0.025860675 0.13399915, 0.15128691 -0.025860488 0.1339993, -0.15371329 -0.025862381 0.13399915, -0.2618928 -0.026144855 0.13399906, -0.15360633 -0.026144214 0.13399915, 0.35709992 -0.028458506 0.13399906, -0.29237321 -0.028641604 0.13399892, -0.29162589 -0.028641529 0.13399915, 0.1106512 -0.026802428 0.13399906, 0.099849887 -0.026802555 0.13399906, -0.26255643 -0.026732698 0.13399915, -0.15294281 -0.02673208 0.13399915, -0.35562605 -0.028641924 0.13399906, -0.099848874 -0.026803799 0.13399906, -0.10015021 -0.026803806 0.13399906, -0.11034894 -0.026803792 0.13399915, 0.39878693 -0.025858864 0.1339993, 0.35901061 -0.026301876 0.13399915, -0.35637331 -0.028641954 0.13399906, -0.40124968 -0.025564834 0.13399915, -0.40121344 -0.02586399 0.13399915, -0.40110663 -0.026145712 0.13399915, -0.26178595 -0.025863111 0.13399906, 0.11175045 -0.025561489 0.13399906, -0.40093526 -0.026393831 0.13399906, -0.40070978 -0.026593626 0.13399906, -0.40044299 -0.026733637 0.13399915, 0.35637429 -0.028637335 0.13399892, -0.40015033 -0.026805699 0.13399906, -0.26284909 -0.02680476 0.13399906, -0.1526503 -0.026804112 0.13399906, -0.39984897 -0.026805729 0.13399906, 0.11034984 -0.026802391 0.13399906, -0.35637343 -0.022487119 0.1339993, 0.39878705 -0.025260597 0.13399915, 0.35910061 -0.025559962 0.13399915, 0.39875069 -0.025559708 0.13399915, -0.35562608 -0.022487104 0.13399942, 0.15128691 -0.02526217 0.13399915, 0.11171413 -0.025262341 0.13399915, -0.39984909 -0.024323925 0.1339993, -0.40015045 -0.024323985 0.13399915, -0.40044299 -0.024396092 0.13399915, -0.40070978 -0.024536118 0.13399915, -0.15374957 -0.025563255 0.13399915, -0.26174968 -0.025563926 0.13399915, -0.40093532 -0.024735898 0.13399915, 0.35562691 -0.028637335 0.13399906, -0.40110663 -0.024983913 0.1339993, -0.40121338 -0.025265709 0.13399915, 0.35562697 -0.022482648 0.1339993, 0.29237431 -0.022483021 0.13399942, 0.39889386 -0.024978787 0.1339993, 0.35901061 -0.024818137 0.1339993, 0.2916269 -0.022482954 0.1339993, 0.15234983 -0.024320379 0.1339993, 0.11065118 -0.024320662 0.13399915, 0.11034983 -0.024320669 0.13399915, 0.15139373 -0.024980396 0.13399915, 0.11160728 -0.02498059 0.1339993, 0.10015126 -0.024320826 0.13399915, 0.099849954 -0.024320833 0.13399915, -0.099848866 -0.024321996 0.1339993, -0.10015022 -0.024322018 0.1339993, -0.15371323 -0.025264084 0.13399915, -0.26178592 -0.025264807 0.13399915, -0.11034887 -0.024322107 0.1339993, -0.15265019 -0.024322428 0.13399915, -0.29162607 -0.022486627 0.13399942, 0.39906511 -0.024730831 0.1339993, 0.35874552 -0.024119377 0.13399942, -0.262849 -0.024323121 0.13399915, -0.29237339 -0.022486702 0.1339993, 0.15156494 -0.024732396 0.13399915, 0.11143614 -0.024732672 0.1339993, -0.15360634 -0.02498237 0.13399915, -0.2618928 -0.024983071 0.1339993, 0.39929059 -0.024530992 0.1339993, 0.35832095 -0.023504272 0.1339993, 0.15179051 -0.024532579 0.1339993, 0.11121064 -0.024532862 0.1339993, -0.15343525 -0.024734393 0.1339993, -0.26206395 -0.024735108 0.13399915, 0.15205735 -0.02439259 0.13399915, 0.35776162 -0.023008749 0.13399915, -0.15320961 -0.024534553 0.1339993, -0.26228955 -0.024535261 0.13399915, 0.11094377 -0.024392769 0.1339993, 0.35709986 -0.022661433 0.1339993, -0.26255634 -0.02439525 0.13399915, -0.15294282 -0.02439452 0.1339993, 0.35637426 -0.022482604 0.1339993, 0.294321 -0.027616054 0.13399915, 0.29376161 -0.028111629 0.13399892, 0.35368022 -0.027615651 0.13399906, 0.109565 -0.026390515 0.13399906, 0.10071061 -0.02659034 0.13399906, 0.10979052 -0.026590325 0.13399906, 0.35423967 -0.028111234 0.13399906, 0.1009362 -0.026390538 0.13399906, 0.29474548 -0.027000956 0.13399906, 0.35325572 -0.027000591 0.13399906, 0.10939375 -0.026142493 0.13399915, 0.10110736 -0.02614256 0.1339993, 0.29309994 -0.028458998 0.13399906, -0.26393521 -0.026392825 0.13399915, -0.27428955 -0.026592754 0.13399906, -0.26370972 -0.02659265 0.13399915, -0.27406397 -0.026392929 0.13399906, 0.10044391 -0.026730463 0.13399915, 0.11005717 -0.026730254 0.13399906, 0.35490134 -0.028458536 0.13399892, 0.29501054 -0.026302285 0.13399906, 0.10121424 -0.025860794 0.1339993, 0.35299078 -0.02630192 0.13399915, -0.26410639 -0.026144855 0.13399915, -0.27389285 -0.026144981 0.1339993, 0.10928697 -0.025860801 0.13399915, -0.2745564 -0.02673284 0.13399915, -0.26344284 -0.026732765 0.13399915, 0.10015118 -0.026802525 0.13399906, 0.29237422 -0.028637804 0.13399892, -0.27378595 -0.025863223 0.13399915, 0.29510066 -0.025560409 0.13399915, 0.35290077 -0.025560021 0.13399906, -0.26421332 -0.025863141 0.13399915, 0.10925053 -0.025561526 0.13399915, 0.10125054 -0.025561623 0.13399915, -0.274849 -0.026804902 0.13399906, -0.2631503 -0.02680482 0.13399906, -0.26424959 -0.025563978 0.13399915, -0.27374968 -0.025564037 0.13399915, 0.10928689 -0.025262445 0.13399915, 0.10121427 -0.02526249 0.13399915, 0.29501045 -0.024818473 0.13399915, 0.35299072 -0.024818212 0.13399915, -0.27378589 -0.025264852 0.13399915, -0.2642132 -0.025264822 0.13399915, 0.10939368 -0.02498062 0.13399915, 0.10110735 -0.024980731 0.13399915, 0.35325566 -0.024119318 0.1339993, 0.29474562 -0.024119742 0.1339993, 0.35368016 -0.023504272 0.13399942, -0.26410645 -0.024983048 0.1339993, -0.27389279 -0.024983086 0.1339993, 0.10093623 -0.024732739 0.13399915, 0.10956486 -0.024732664 0.13399915, 0.35423967 -0.023008794 0.1339993, 0.29432097 -0.023504674 0.1339993, -0.27406403 -0.02473513 0.13399915, -0.26393521 -0.024735093 0.13399915, 0.29376161 -0.023009136 0.13399942, 0.10979045 -0.024532817 0.13399915, 0.10071062 -0.024532914 0.13399915, -0.27428952 -0.024535276 0.13399915, 0.29309994 -0.022661828 0.1339993, 0.10044376 -0.024392851 0.1339993, 0.35490131 -0.022661477 0.1339993, -0.26370969 -0.024535261 0.13399915, 0.11005731 -0.024392799 0.13399915, -0.2634429 -0.02439525 0.1339993, -0.27455643 -0.02439525 0.1339993, -0.26315027 -0.024323016 0.13399915, -0.27484897 -0.024323106 0.13399915, 0.28925574 -0.027001001 0.13399906, 0.27593628 -0.026389413 0.13399906, 0.28968018 -0.027616009 0.13399906, 0.27571073 -0.026589222 0.13399915, 0.2902396 -0.028111689 0.13399906, 0.28899077 -0.026302278 0.13399915, 0.27610731 -0.026141338 0.13399906, -0.099063896 -0.026391827 0.13399906, -0.099289477 -0.026591659 0.13399906, 0.099064864 -0.026390515 0.13399906, 0.099290416 -0.02659031 0.13399906, -0.098892711 -0.026143841 0.13399915, 0.27544391 -0.02672933 0.13399915, 0.29090139 -0.028459013 0.13399906, 0.098893672 -0.026142538 0.13399915, 0.28890055 -0.025560401 0.13399915, 0.2762143 -0.025859728 0.13399915, -0.27593526 -0.026392959 0.13399906, -0.28967923 -0.027619816 0.13399906, -0.27570975 -0.026592784 0.13399906, -0.099556305 -0.02673167 0.13399915, 0.099557325 -0.026730396 0.13399915, 0.27515134 -0.026801459 0.13399915, -0.29023859 -0.028115459 0.13399915, -0.2754429 -0.026732855 0.13399906, -0.098785892 -0.025862023 0.13399906, 0.098786823 -0.025860779 0.13399915, 0.27625063 -0.025560513 0.1339993, 0.27485001 -0.02680143 0.13399915, -0.27610642 -0.026144952 0.13399915, -0.28925478 -0.027004771 0.13399906, 0.28899065 -0.024818517 0.13399915, 0.2762143 -0.025261372 0.13399915, 0.098750502 -0.025561631 0.13399915, -0.098749541 -0.025562927 0.13399915, -0.29090029 -0.028462678 0.13399892, -0.2751503 -0.026804864 0.13399906, 0.27610743 -0.024979606 0.1339993, 0.28925571 -0.024119779 0.1339993, 0.098786891 -0.02526252 0.13399915, -0.098785929 -0.02526366 0.13399915, -0.27621335 -0.025863163 0.13399915, -0.28898975 -0.026306003 0.13399915, 0.28968012 -0.023504652 0.1339993, 0.27593625 -0.024731547 0.1339993, 0.098893762 -0.024980776 0.1339993, -0.098892771 -0.02498199 0.1339993, 0.2902396 -0.023009114 0.1339993, 0.27571073 -0.024531722 0.13399915, -0.28889963 -0.025564149 0.13399906, 0.099064879 -0.024732739 0.13399915, -0.099063963 -0.024733953 0.1339993, -0.27621329 -0.025264829 0.13399915, -0.27624971 -0.025564015 0.13399915, 0.27544382 -0.024391681 0.13399915, 0.29090136 -0.02266182 0.1339993, 0.099290416 -0.024532907 0.13399915, -0.099289566 -0.024534084 0.13399915, -0.27610645 -0.024983123 0.13399915, -0.28898969 -0.024822287 0.13399915, 0.27515125 -0.024319619 0.1339993, -0.28925481 -0.02412349 0.1339993, 0.099557266 -0.024392836 0.1339993, -0.099556297 -0.024394087 0.13399915, -0.27593532 -0.024735175 0.13399915, 0.27484989 -0.024319641 0.1339993, -0.28967932 -0.023508392 0.1339993, -0.27570969 -0.024535321 0.13399915, -0.29023865 -0.023012891 0.13399942, -0.27544287 -0.024395265 0.13399915, -0.29090044 -0.022665575 0.13399915, 0.26393625 -0.02638945 0.13399906, 0.26371071 -0.026589289 0.13399906, 0.2740649 -0.026389346 0.13399915, -0.27515033 -0.024323136 0.13399915, 0.2742905 -0.026589185 0.13399915, 0.26410738 -0.026141442 0.13399915, 0.27389371 -0.026141375 0.13399915, 0.26344386 -0.02672933 0.13399915, -0.10093518 -0.026391797 0.13399906, -0.10978951 -0.026591659 0.13399915, -0.10070968 -0.026591636 0.13399906, 0.27455738 -0.026729301 0.13399906, -0.10956396 -0.026391819 0.13399906, 0.26421422 -0.025859676 0.13399906, -0.10110637 -0.026143827 0.13399915, -0.10939278 -0.026143834 0.13399915, 0.27378693 -0.025859654 0.1339993, 0.2631512 -0.0268014 0.13399906, -0.11005636 -0.02673167 0.13399906, -0.10044283 -0.02673167 0.13399906, 0.26425052 -0.025560573 0.13399915, -0.10121325 -0.025862075 0.1339993, -0.10928592 -0.025862068 0.13399915, 0.2737506 -0.025560491 0.13399915, -0.29431999 -0.027619831 0.13399906, -0.35367933 -0.027620226 0.13399906, -0.29376066 -0.028115399 0.13399906, -0.29474464 -0.027004786 0.13399906, 0.26421428 -0.025261417 0.13399915, -0.35423866 -0.028115779 0.13399906, -0.29309884 -0.02846273 0.13399906, 0.27378684 -0.025261335 0.13399906, -0.29500961 -0.026306018 0.13399906, -0.3532548 -0.027005076 0.13399906, -0.10124952 -0.025562935 0.13399915, -0.10924961 -0.025562935 0.13399915, 0.26410744 -0.024979658 0.13399915, -0.35490039 -0.02846311 0.13399906, 0.2738938 -0.024979629 0.1339993, -0.10121325 -0.025263794 0.13399906, -0.10928582 -0.025263816 0.13399915, 0.26393619 -0.024731606 0.13399915, -0.35298982 -0.026306406 0.13399915, 0.27406493 -0.024731614 0.1339993, -0.10110635 -0.02498202 0.13399915, -0.1093927 -0.024982065 0.1339993, -0.29509971 -0.025564149 0.13399915, -0.3528997 -0.025564477 0.13399906, 0.26371065 -0.024531819 0.13399915, 0.27429047 -0.024531759 0.1339993, -0.10956391 -0.02473411 0.13399915, -0.10093518 -0.024734057 0.1339993, -0.29500955 -0.024822257 0.13399915, -0.35298976 -0.024822667 0.1339993, -0.29474452 -0.024123572 0.1339993, 0.2634438 -0.024391785 0.13399915, -0.10978943 -0.0245343 0.13399915, 0.27455729 -0.024391636 0.1339993, -0.1007096 -0.024534188 0.1339993, 0.26315126 -0.024319693 0.13399915, -0.35325482 -0.024123818 0.13399915, -0.29432002 -0.023508467 0.1339993, -0.11005633 -0.024394177 0.1339993, -0.10044275 -0.024394199 0.1339993, -0.29376069 -0.023012862 0.13399942, -0.35367927 -0.023508862 0.1339993, -0.29309896 -0.022665568 0.13399942, -0.35423866 -0.023013279 0.13399942, -0.35490048 -0.022665977 0.1339993, 0.26206496 -0.026389502 0.13399915, 0.15321064 -0.026589952 0.13399915, 0.26229054 -0.026589334 0.13399915, 0.15343615 -0.026390143 0.13399915, -0.151564 -0.02639211 0.13399906, -0.15178959 -0.026591927 0.13399906, -0.11143521 -0.026391856 0.13399915, -0.11120964 -0.026591703 0.1339993, -0.11094279 -0.026731744 0.13399915, 0.26189369 -0.026141435 0.13399906, 0.15360734 -0.026142165 0.13399906, -0.15374959 -0.025563069 0.13199921, -0.15371335 -0.02586218 0.13199921, -0.15360646 -0.026143953 0.13199921, -0.15343529 -0.026391916 0.13199906, -0.1532097 -0.026591748 0.13199921, -0.15294284 -0.026731871 0.13199906, -0.15265027 -0.02680397 0.13199906, -0.15234894 -0.026803955 0.13199906, -0.15205625 -0.026731864 0.13199906, -0.15178955 -0.026591785 0.13199906, -0.15156397 -0.026391953 0.13199906, -0.15139273 -0.026143953 0.13199921, -0.15128595 -0.025862187 0.13199921, -0.15124959 -0.025563061 0.13199906, 0.15125056 -0.025561146 0.13199921, 0.15128687 -0.025860243 0.13199906, 0.15139368 -0.026141986 0.13199921, 0.15156485 -0.026389956 0.13199906, 0.15179045 -0.026589826 0.131999, 0.15205732 -0.026729919 0.13199921, 0.15234993 -0.026802018 0.13199906, 0.1526513 -0.026802003 0.13199906, 0.15294382 -0.026729867 0.13199906, 0.15321067 -0.02658987 0.13199921, 0.1534362 -0.026390046 0.13199921, 0.15360734 -0.026142046 0.13199921, 0.15371427 -0.02586028 0.13199921, 0.15375057 -0.025561109 0.13199921, -0.26424959 -0.025563799 0.1319993, -0.26421332 -0.025862962 0.13199921, -0.26410645 -0.026144668 0.13199921, -0.26393527 -0.026392646 0.13199921, -0.26370981 -0.026592456 0.13199921, -0.26344287 -0.026732586 0.13199921, -0.26315027 -0.026804619 0.131999, -0.26284897 -0.026804663 0.13199906, -0.26255646 -0.026732549 0.13199906, -0.26228952 -0.026592501 0.13199921, -0.26206398 -0.026392698 0.13199921, -0.26189274 -0.026144743 0.13199906, -0.26178592 -0.025862947 0.13199921, -0.26174968 -0.025563747 0.13199921, -0.27624965 -0.025563851 0.1319993, -0.27621335 -0.025862955 0.13199921, -0.27610639 -0.02614481 0.13199906, -0.27593523 -0.02639284 0.13199921, -0.27570969 -0.026592635 0.13199921, -0.27544278 -0.026732683 0.13199921, -0.2751503 -0.0268047 0.13199906, -0.27484894 -0.026804782 0.13199921, -0.27455631 -0.026732668 0.13199906, -0.27428949 -0.026592575 0.13199921, -0.27406394 -0.02639278 0.13199921, -0.27389276 -0.026144765 0.13199921, -0.27378589 -0.025862999 0.13199921, -0.27374968 -0.025563851 0.13199921, -0.40124968 -0.025564671 0.13199921, -0.40121344 -0.025863826 0.13199921, -0.40110663 -0.026145622 0.13199921, -0.40093532 -0.026393592 0.13199921, -0.40070978 -0.026593477 0.13199921, -0.40044299 -0.026733398 0.13199921, -0.40015045 -0.02680555 0.13199906, -0.39984903 -0.02680555 0.13199906, -0.39955655 -0.026733384 0.13199906, -0.39928961 -0.026593313 0.13199906, -0.39906403 -0.026393548 0.13199906, -0.39889288 -0.026145503 0.13199921, -0.3987861 -0.025863796 0.13199921, -0.39874971 -0.025564596 0.13199921, 0.09875048 -0.025561415 0.1319993, 0.098786794 -0.025860555 0.13199921, 0.098893695 -0.026142411 0.13199921, 0.099064961 -0.026390426 0.13199921, 0.099290498 -0.026590213 0.13199921, 0.099557251 -0.026730202 0.13199921, 0.099849857 -0.026802346 0.13199906, 0.10015123 -0.026802346 0.13199906, 0.10044377 -0.026730187 0.13199906, 0.10071054 -0.026590154 0.13199906, 0.10093612 -0.026390322 0.13199906, 0.10110736 -0.026142329 0.13199906, 0.10121417 -0.025860526 0.13199906, 0.10125054 -0.02556143 0.13199921, -0.10124954 -0.025562748 0.1319993, -0.10121322 -0.025861889 0.13199921, -0.1011063 -0.026143678 0.13199906, -0.10093516 -0.026391692 0.13199921, -0.10070963 -0.026591495 0.13199921, -0.10044283 -0.026731499 0.13199906, -0.10015021 -0.026803628 0.13199921, -0.099848889 -0.026803613 0.13199921, -0.099556342 -0.026731491 0.13199921, -0.099289484 -0.026591487 0.13199921, -0.099063896 -0.02639164 0.13199921, -0.098892704 -0.026143655 0.13199921, -0.098785907 -0.025861859 0.13199921, -0.098749526 -0.025562748 0.13199921, 0.26175061 -0.025560461 0.13199921, 0.26178694 -0.025859594 0.13199921, 0.26189381 -0.026141353 0.13199921, 0.26206499 -0.026389338 0.13199921, 0.26229048 -0.026589103 0.13199921, 0.26255736 -0.026729189 0.13199921, 0.26285002 -0.026801288 0.13199921, 0.26315129 -0.026801258 0.13199921, 0.26344389 -0.026729248 0.13199921, 0.26371065 -0.026589118 0.13199921, 0.26393625 -0.026389308 0.13199906, 0.26410735 -0.026141256 0.13199906, 0.26421434 -0.025859579 0.13199921, 0.26425061 -0.025560394 0.13199921, 0.27375057 -0.025560327 0.1319993, 0.2737869 -0.02585946 0.13199921, 0.27389371 -0.026141219 0.13199921, 0.27406499 -0.026389286 0.13199921, 0.27429047 -0.02658911 0.1319993, 0.27455738 -0.026729107 0.13199906, 0.27484998 -0.026801221 0.13199921, 0.27515125 -0.026801199 0.13199921, 0.27544379 -0.026729025 0.13199921, 0.27571058 -0.026588976 0.13199921, 0.27593628 -0.026389204 0.13199921, 0.27610737 -0.026141152 0.13199921, 0.27621418 -0.025859416 0.13199921, 0.27625057 -0.025560282 0.1319993, 0.3987506 -0.025559574 0.13199921, 0.39878693 -0.02585873 0.1319993, 0.39889386 -0.026140437 0.13199921, 0.39906505 -0.026388437 0.13199921, 0.39929053 -0.026588231 0.13199921, 0.39955738 -0.026728258 0.13199906, 0.39984992 -0.026800424 0.13199921, 0.40015128 -0.026800379 0.13199921, 0.40044394 -0.026728302 0.1319993, 0.40071079 -0.026588246 0.13199921, 0.40093628 -0.026388422 0.13199921, 0.40110746 -0.026140392 0.13199906, 0.40121433 -0.025858626 0.13199921, 0.40125066 -0.025559545 0.13199921, 0.10925053 -0.025561377 0.13199921, 0.10928685 -0.025860541 0.13199906, 0.10939364 -0.026142225 0.13199906, 0.10956489 -0.026390232 0.131999, 0.10979047 -0.026590146 0.13199921, 0.11005732 -0.026730157 0.13199921, 0.11034986 -0.026802257 0.13199906, 0.1106512 -0.026802264 0.13199906, 0.11094379 -0.026730105 0.13199906, 0.11121063 -0.026590094 0.13199921, 0.11143617 -0.026390292 0.13199921, 0.11160739 -0.026142314 0.13199921, 0.11171419 -0.025860518 0.1319993, 0.11175054 -0.0255614 0.13199921, -0.11174955 -0.025562815 0.1319993, -0.11171322 -0.025861971 0.13199921, -0.11160645 -0.02614364 0.13199921, -0.11143528 -0.026391611 0.13199906, -0.11120975 -0.02659148 0.13199906, -0.11094283 -0.026731573 0.13199906, -0.11065025 -0.026803643 0.13199921, -0.1103489 -0.026803635 0.13199921, -0.11005632 -0.026731528 0.13199906, -0.1097895 -0.026591517 0.13199921, -0.10956391 -0.026391678 0.13199921, -0.10939272 -0.0261437 0.13199906, -0.10928588 -0.025861949 0.13199921, -0.10924959 -0.025562786 0.13199921, -0.35909966 -0.025564417 0.13199921, -0.35900956 -0.026306272 0.13199906, -0.35874459 -0.027005032 0.13199906, -0.35832009 -0.027620032 0.13199906, -0.3577607 -0.028115615 0.13199921, -0.35709897 -0.028462872 0.13199906, -0.35637331 -0.028641745 0.131999, -0.35562605 -0.028641745 0.13199906, -0.35490039 -0.028462946 0.13199906, -0.35423866 -0.0281156 0.13199906, -0.35367924 -0.027620107 0.13199906, -0.35325482 -0.027004972 0.13199906, -0.35298973 -0.026306152 0.13199921, -0.35289973 -0.025564313 0.13199921, -0.29509965 -0.025564 0.13199921, -0.29500955 -0.026305817 0.13199906, -0.29474455 -0.027004592 0.13199906, -0.29431999 -0.027619667 0.13199921, -0.2937606 -0.028115258 0.13199906, -0.2930989 -0.028462537 0.13199906, -0.29237327 -0.028641328 0.131999, -0.29162604 -0.028641269 0.131999, -0.29090035 -0.028462477 0.13199885, -0.29023862 -0.028115258 0.13199906, -0.28967932 -0.02761963 0.13199906, -0.28925481 -0.027004518 0.13199906, -0.28898972 -0.02630581 0.13199906, -0.28889975 -0.025563858 0.13199921, 0.28890055 -0.02556023 0.13199921, 0.28899071 -0.026302069 0.13199921, 0.28925574 -0.027000844 0.13199906, 0.28968021 -0.027615868 0.13199906, 0.2902396 -0.02811148 0.13199906, 0.29090127 -0.028458714 0.131999, 0.29162696 -0.028637618 0.131999, 0.29237434 -0.028637663 0.131999, 0.29309985 -0.028458774 0.131999, 0.29376167 -0.028111495 0.131999, 0.29432103 -0.027615845 0.13199906, 0.29474556 -0.027000837 0.13199921, 0.2950106 -0.026302114 0.13199906, 0.29510063 -0.025560237 0.13199921, 0.35290065 -0.025559813 0.13199921, 0.35299078 -0.026301697 0.13199906, 0.35325572 -0.027000472 0.13199921, 0.35368028 -0.027615517 0.13199906, 0.35423973 -0.0281111 0.13199906, 0.35490146 -0.028458342 0.13199906, 0.35562694 -0.028637186 0.13199906, 0.35637429 -0.028637245 0.13199906, 0.35709998 -0.028458402 0.13199921, 0.35776165 -0.02811107 0.13199906, 0.35832098 -0.027615488 0.13199906, 0.35874555 -0.027000397 0.13199921, 0.35901064 -0.026301697 0.13199921, 0.35910061 -0.025559828 0.1319993, 0.35901055 -0.024817884 0.13199921, 0.35874549 -0.024119169 0.13199921, 0.35832095 -0.023504093 0.1319993, 0.35776171 -0.023008615 0.1319993, 0.35709992 -0.022661254 0.13199945, 0.3563742 -0.022482306 0.1319993, 0.35562694 -0.022482321 0.1319993, 0.35490134 -0.022661269 0.1319993, 0.35423964 -0.023008525 0.1319993, 0.35368016 -0.023504093 0.1319993, 0.35325575 -0.024119154 0.1319993, 0.35299072 -0.024817899 0.13199921, 0.29501057 -0.024818271 0.1319993, 0.29474548 -0.024119534 0.1319993, 0.29432097 -0.023504503 0.1319993, 0.29376164 -0.023008943 0.13199945, 0.29309985 -0.022661641 0.1319993, 0.29237428 -0.02248279 0.13199945, 0.29162702 -0.022482879 0.1319993, 0.2909013 -0.022661686 0.1319993, 0.29023969 -0.023009017 0.1319993, 0.28968027 -0.023504548 0.1319993, 0.28925568 -0.024119578 0.1319993, 0.28899071 -0.02481842 0.13199921, -0.28898975 -0.024822138 0.1319993, -0.28925481 -0.024123348 0.1319993, -0.28967926 -0.023508266 0.1319993, -0.29023865 -0.023012742 0.13199945, -0.29090038 -0.022665374 0.1319993, -0.2916261 -0.022486486 0.1319993, -0.29237339 -0.022486553 0.1319993, -0.29309902 -0.022665367 0.13199945, -0.29376069 -0.023012705 0.1319993, -0.29432002 -0.023508243 0.13199921, -0.29474452 -0.0241234 0.13199921, -0.29500958 -0.024822116 0.13199921, -0.35298973 -0.024822503 0.13199921, -0.35325482 -0.024123728 0.1319993, -0.35367927 -0.023508653 0.1319993, -0.35423866 -0.023013055 0.1319993, -0.35490039 -0.022665843 0.13199945, -0.35562608 -0.02248694 0.1319993, -0.35637334 -0.02248694 0.13199945, -0.35709891 -0.022665858 0.1319993, -0.35776064 -0.0230131 0.1319993, -0.35832012 -0.023508713 0.13199921, -0.35874459 -0.024123773 0.13199921, -0.35900953 -0.024822593 0.13199921, -0.10928589 -0.025263637 0.13199906, -0.10939273 -0.024981871 0.13199921, -0.1095639 -0.024733864 0.1319993, -0.10978947 -0.024534076 0.1319993, -0.11005639 -0.024393953 0.1319993, -0.11034887 -0.024321951 0.1319993, -0.1106502 -0.024321921 0.1319993, -0.1109428 -0.024394028 0.13199945, -0.11120962 -0.024534084 0.13199921, -0.11143522 -0.024733938 0.13199921, -0.11160638 -0.024981901 0.13199921, -0.11171327 -0.025263608 0.13199921, 0.11171415 -0.025262132 0.13199906, 0.11160725 -0.024980366 0.13199921, 0.11143614 -0.024732418 0.13199921, 0.11121058 -0.024532601 0.13199921, 0.11094379 -0.024392635 0.1319993, 0.11065117 -0.024320468 0.13199921, 0.11034978 -0.024320461 0.13199921, 0.11005732 -0.024392664 0.13199921, 0.10979051 -0.024532735 0.1319993, 0.10956495 -0.024732552 0.1319993, 0.10939373 -0.024980523 0.1319993, 0.10928695 -0.025262341 0.1319993, 0.40121433 -0.025260389 0.13199921, 0.40110746 -0.024978593 0.1319993, 0.40093628 -0.024730653 0.1319993, 0.40071073 -0.024530783 0.1319993, 0.40044394 -0.024390757 0.1319993, 0.40015125 -0.02431865 0.1319993, 0.39985004 -0.024318606 0.1319993, 0.39955738 -0.024390727 0.13199921, 0.39929059 -0.024530813 0.13199921, 0.39906493 -0.024730638 0.13199921, 0.39889377 -0.024978667 0.13199921, 0.39878705 -0.025260404 0.13199906, 0.27621424 -0.025261141 0.1319993, 0.27610743 -0.024979353 0.1319993, 0.27593625 -0.024731345 0.1319993, 0.27571064 -0.024531558 0.1319993, 0.27544385 -0.02439151 0.1319993, 0.27515125 -0.02431941 0.1319993, 0.27484992 -0.024319395 0.1319993, 0.27455735 -0.024391577 0.1319993, 0.2742905 -0.024531573 0.1319993, 0.27406499 -0.024731442 0.1319993, 0.27389377 -0.024979413 0.13199906, 0.27378699 -0.025261171 0.13199921, 0.26421428 -0.025261216 0.13199921, 0.26410741 -0.024979495 0.13199921, 0.26393622 -0.024731509 0.13199921, 0.26371065 -0.02453173 0.13199921, 0.26344386 -0.024391629 0.13199921, 0.26315126 -0.024319544 0.13199921, 0.26284999 -0.024319611 0.1319993, 0.2625573 -0.024391629 0.13199921, 0.26229054 -0.024531692 0.1319993, 0.26206493 -0.024731494 0.13199921, 0.26189384 -0.024979487 0.13199921, 0.26178691 -0.025261238 0.13199921, -0.098785937 -0.025263488 0.1319993, -0.098892763 -0.024981774 0.1319993, -0.099063955 -0.024733797 0.1319993, -0.099289514 -0.024533927 0.1319993, -0.099556305 -0.024393961 0.1319993, -0.099848874 -0.024321802 0.1319993, -0.10015023 -0.024321817 0.1319993, -0.1004428 -0.024393998 0.13199921, -0.10070964 -0.02453398 0.1319993, -0.10093518 -0.024733856 0.13199921, -0.10110639 -0.024981812 0.13199921, -0.10121325 -0.025263585 0.13199906, 0.1012142 -0.025262304 0.13199906, 0.10110738 -0.0249805 0.13199921, 0.10093623 -0.024732612 0.13199921, 0.10071066 -0.02453275 0.1319993, 0.10044374 -0.024392635 0.1319993, 0.10015123 -0.024320588 0.1319993, 0.09984985 -0.02432055 0.13199921, 0.099557228 -0.02439262 0.1319993, 0.09929046 -0.024532698 0.1319993, 0.099064879 -0.02473253 0.1319993, 0.098893642 -0.024980463 0.1319993, 0.098786831 -0.025262319 0.1319993, -0.3987861 -0.02526544 0.13199921, -0.39889288 -0.0249836 0.13199921, -0.39906409 -0.024735734 0.1319993, -0.39928952 -0.024535924 0.1319993, -0.39955643 -0.024395883 0.13199921, -0.39984909 -0.024323806 0.1319993, -0.40015045 -0.024323821 0.1319993, -0.40044299 -0.024395972 0.13199921, -0.40070978 -0.024535984 0.1319993, -0.40093532 -0.024735749 0.1319993, -0.40110651 -0.024983793 0.13199921, -0.40121332 -0.025265574 0.1319993, -0.27378589 -0.025264688 0.13199921, -0.27389282 -0.024982959 0.13199921, -0.27406397 -0.024734996 0.1319993, -0.27428952 -0.024535105 0.13199921, -0.27455643 -0.024395049 0.1319993, -0.27484897 -0.024322972 0.1319993, -0.27515036 -0.024322949 0.13199921, -0.27544287 -0.024395093 0.13199921, -0.27570972 -0.024535149 0.13199921, -0.27593526 -0.024735034 0.1319993, -0.27610645 -0.024982959 0.13199921, -0.27621329 -0.025264688 0.1319993, -0.26178595 -0.025264591 0.13199921, -0.26189283 -0.024982855 0.13199921, -0.26206407 -0.024734847 0.1319993, -0.26228967 -0.024534993 0.13199921, -0.26255646 -0.024394996 0.13199921, -0.26284897 -0.02432289 0.1319993, -0.26315033 -0.024322882 0.1319993, -0.26344281 -0.024395049 0.1319993, -0.26370963 -0.024535127 0.1319993, -0.26393521 -0.024734974 0.1319993, -0.26410648 -0.024982914 0.1319993, -0.2642132 -0.025264688 0.13199921, 0.15371424 -0.025261909 0.13199921, 0.15360732 -0.024980135 0.1319993, 0.15343614 -0.02473215 0.13199921, 0.15321065 -0.024532355 0.13199921, 0.1529438 -0.024392322 0.13199921, 0.15265121 -0.024320222 0.1319993, 0.15234992 -0.024320304 0.13199945, 0.15205738 -0.024392448 0.1319993, 0.15179051 -0.02453243 0.13199906, 0.15156491 -0.024732247 0.13199921, 0.15139379 -0.024980299 0.13199921, 0.15128691 -0.025262043 0.13199921, -0.1512859 -0.025263883 0.13199921, -0.15139276 -0.024982154 0.13199906, -0.15156396 -0.024734206 0.13199921, -0.15178953 -0.024534293 0.13199921, -0.15205635 -0.024394259 0.1319993, -0.15234894 -0.024322197 0.13199921, -0.15265019 -0.024322242 0.13199921, -0.15294285 -0.024394326 0.13199921, -0.15320967 -0.02453436 0.13199921, -0.15343523 -0.024734214 0.1319993, -0.15360637 -0.024982169 0.1319993, -0.15371327 -0.025263935 0.13199921, 0.40923187 -0.034564018 0.11399879, 0.40923187 -0.034551159 -0.11400144, 0.40876564 -0.034984395 0.11399879, 0.40876564 -0.03497161 -0.11400144, 0.40822205 -0.035298616 0.11399864, 0.40822208 -0.035285771 -0.11400144, 0.40762511 -0.035492748 0.11399864, 0.40762511 -0.035479933 -0.11400156, 0.40700075 -0.035558477 0.11399879, 0.40700069 -0.035545632 -0.11400156, 0.39300066 -0.035545707 -0.11400156, 0.39300075 -0.035558581 0.11399879, 0.39237642 -0.035492897 0.11399879, 0.39237639 -0.035480022 -0.11400144, 0.39177924 -0.035298675 0.11399864, 0.39177936 -0.03528589 -0.11400144, 0.39123586 -0.034984529 0.11399879, 0.39123577 -0.034971625 -0.11400144, 0.39076963 -0.034564123 0.11399879, 0.39076966 -0.034551293 -0.11400144, -0.40902045 0.13443531 0.13322656, -0.40950018 0.13443533 0.13266738, -0.40700075 0.13443519 0.13400824, -0.40841904 0.13443522 0.13365199, -0.40773186 0.13443516 0.13391785, -0.39300081 0.13443539 0.13400824, -0.39050138 0.1344355 0.13266738, -0.39098108 0.13443546 0.13322635, -0.39226976 0.13443531 0.13391764, -0.39158258 0.13443527 0.13365199, -0.3905004 -0.01556462 0.13265894, -0.39098009 -0.015564665 0.13321801, -0.39158162 -0.01556468 0.13364346, -0.39226875 -0.01556477 0.1339093, -0.39299974 -0.01556474 0.13399987, -0.40773091 -0.015564814 0.1339093, -0.40699968 -0.015564933 0.13399966, -0.40841803 -0.015564889 0.13364346, -0.40901944 -0.01556471 0.13321801, -0.40949926 -0.015564784 0.13265894, 0.39097992 0.13444045 0.13322656, 0.39050016 0.13444042 0.13266738, 0.39158145 0.1344403 0.1336519, 0.39299962 0.13444035 0.13400821, 0.39226845 0.13444033 0.13391785, 0.40699962 0.13444038 0.13400824, 0.40841773 0.1344405 0.13365199, 0.40773079 0.13444044 0.13391764, 0.40901932 0.1344406 0.13322656, 0.40949902 0.13444057 0.13266738, 0.4095 -0.015559435 0.13265894, 0.40902033 -0.015559524 0.13321798, 0.4084188 -0.015559658 0.13364346, 0.40773174 -0.015559629 0.1339093, 0.40700069 -0.015559703 0.13399987, 0.39226943 -0.015559763 0.1339093, 0.39300063 -0.015559733 0.13399987, 0.3915824 -0.015559748 0.13364346, 0.3909809 -0.015559658 0.13321801, 0.39050123 -0.015559644 0.13265894, -0.40841898 0.13445035 -0.13363551, -0.40902048 0.1344503 -0.13321023, -0.40950024 0.1344503 -0.13265102, -0.40773186 0.13445029 -0.13390146, -0.40700081 0.1344503 -0.13399188, -0.39098114 0.13445041 -0.13321023, -0.39158258 0.13445044 -0.13363551, -0.39226976 0.13445048 -0.13390146, -0.39300081 0.13445041 -0.13399182, -0.39050135 0.13445035 -0.13265102, -0.40949926 -0.015549824 -0.13265936, -0.40901944 -0.015549883 -0.13321857, -0.40841803 -0.01554969 -0.13364394, -0.40773091 -0.015549764 -0.13390987, -0.4069998 -0.015549794 -0.13400055, -0.39226875 -0.0155496 -0.13390984, -0.39299974 -0.015549675 -0.13400023, -0.39158162 -0.015549615 -0.13364394, -0.39098009 -0.01554963 -0.13321857, -0.3905004 -0.01554969 -0.13265936, 0.39158145 0.13445543 -0.13363551, 0.39097998 0.13445543 -0.13321023, 0.39050022 0.1344554 -0.13265102, 0.39226857 0.13445541 -0.13390146, 0.39299956 0.13445541 -0.13399221, 0.40699968 0.13445552 -0.13399188, 0.40901932 0.13445555 -0.13321023, 0.40841782 0.13445555 -0.1336356, 0.40773079 0.1344555 -0.13390149, 0.40949902 0.13445547 -0.13265134, 0.39050117 -0.015544713 -0.13265936, 0.39098081 -0.015544623 -0.13321857, 0.39158246 -0.015544623 -0.13364394, 0.39226958 -0.015544757 -0.13390984, 0.39300057 -0.015544668 -0.13400055, 0.40700057 -0.015544504 -0.13400055, 0.40773162 -0.015544474 -0.13390984, 0.40841874 -0.015544519 -0.13364379, 0.40902025 -0.015544608 -0.13321857, 0.40950003 -0.015544593 -0.13265957, 0.16177469 0.15417859 0.11400925, 0.16123001 0.15386263 0.11400931, 0.16299947 0.15443996 0.11400931, 0.16237316 0.15437399 0.11400925, 0.17876877 0.1538628 0.11400931, 0.1782241 0.1541788 0.11400925, 0.1776256 0.15437399 0.11400931, 0.17699945 0.15444005 0.11400934, 0.16123 0.1538755 -0.11399089, 0.16177462 0.15419148 -0.11399089, 0.16237324 0.1543868 -0.11399089, 0.16299933 0.15445285 -0.11399089, 0.17699938 0.15445298 -0.11399089, 0.17762555 0.15438685 -0.11399089, 0.17822419 0.15419161 -0.11399089, 0.1787688 0.15387568 -0.11399089, -0.17700076 0.15443783 0.11400925, -0.17762694 0.15437175 0.11400931, -0.17822549 0.15417643 0.11400931, -0.17877015 0.15386049 0.11400931, -0.16123134 0.15386058 0.11400925, -0.16177592 0.15417652 0.11400931, -0.16237459 0.15437184 0.11400931, -0.16300079 0.15443794 0.11400931, -0.17877007 0.15387331 -0.11399089, -0.17822546 0.1541892 -0.11399089, -0.17762688 0.15438457 -0.11399089, -0.17700084 0.15445076 -0.11399089, -0.1630007 0.15445071 -0.11399089, -0.16237465 0.15438475 -0.11399089, -0.16177598 0.15418941 -0.11399089, -0.16123131 0.1538734 -0.11399089, 0.16076945 -0.034565568 0.11399864, 0.16123579 -0.034986012 0.11399864, 0.16177925 -0.035300195 0.11399864, 0.16237627 -0.035494402 0.11399864, 0.16300063 -0.035560049 0.11399879, 0.17923172 -0.034565479 0.11399864, 0.17822199 -0.035300113 0.11399864, 0.17876557 -0.034985945 0.11399879, 0.17700061 -0.035559952 0.11399864, 0.17762497 -0.035494253 0.11399864, 0.17923172 -0.034552574 -0.11400144, 0.17876543 -0.034973025 -0.11400144, 0.17822196 -0.035287209 -0.11400144, 0.17762494 -0.035481393 -0.11400156, 0.1770007 -0.035547219 -0.11400156, 0.16300063 -0.035547219 -0.11400144, 0.16237624 -0.035481498 -0.11400144, 0.16177924 -0.03528735 -0.11400144, 0.16123575 -0.034973204 -0.11400144, 0.16076951 -0.034552753 -0.11400144, -0.17822088 -0.035302415 0.11399864, -0.1792307 -0.034567714 0.11399879, -0.17876446 -0.03498818 0.11399879, -0.17762388 -0.035496525 0.11399864, -0.17699954 -0.03556221 0.11399864, -0.16076843 -0.034567595 0.11399879, -0.16299953 -0.035562091 0.11399864, -0.16237523 -0.035496399 0.11399864, -0.16177815 -0.035302274 0.11399864, -0.16123466 -0.034988046 0.11399879, -0.16076837 -0.034554794 -0.11400156, -0.16123462 -0.034975231 -0.11400144, -0.16177818 -0.035289437 -0.11400156, -0.16237521 -0.035483532 -0.11400156, -0.16299951 -0.035549305 -0.11400156, -0.17699961 -0.035549328 -0.11400156, -0.17762396 -0.035483643 -0.11400144, -0.17822094 -0.035289489 -0.11400156, -0.17876449 -0.034975275 -0.11400144, -0.17923069 -0.034554899 -0.11400144, -0.41400039 0.084722117 0.04716824, -0.41400039 0.084045917 0.046911582, -0.41400039 0.083450675 0.046500787, -0.41400039 0.082971171 0.045959458, -0.41400039 0.082635045 0.045318976, -0.41400036 0.082462043 0.044617072, -0.41400039 0.082462117 0.04389368, -0.41400051 0.082635343 0.043191358, -0.41400051 0.082971469 0.042550936, -0.41400054 0.083451048 0.042009756, -0.41400054 0.084046289 0.041598842, -0.41400054 0.084722459 0.041342512, -0.41400054 0.084859252 0.045362279, -0.41400042 0.08660911 0.0438122, -0.41400042 0.086681202 0.044104919, -0.41400054 0.086469024 0.043545619, -0.41400042 0.085141063 0.04546909, -0.41400042 0.085440114 0.045505539, -0.41400039 0.084411591 0.04354541, -0.41400042 0.084611446 0.043319806, -0.41400039 0.084859431 0.043148562, -0.41400042 0.086681202 0.04440622, -0.41400042 0.086608991 0.0446987, -0.41400039 0.08427158 0.0438122, -0.41400054 0.085739374 0.04546909, -0.41400039 0.085141227 0.04304181, -0.41400054 0.086468905 0.044965521, -0.41400054 0.086021096 0.045362279, -0.41400039 0.084199414 0.04410477, -0.41400051 0.08626911 0.045191094, -0.41400039 0.085440338 0.043005362, -0.41400039 0.084199414 0.044406071, -0.41400042 0.085739464 0.043041602, -0.41400039 0.084271401 0.044698492, -0.41400042 0.086021215 0.043148711, -0.41400051 0.084411457 0.044965431, -0.41400039 0.086269245 0.043319657, -0.41400042 0.084611252 0.045191035, -0.41100037 0.085440308 0.043005273, -0.41100037 0.085141152 0.043041602, -0.4110004 0.084859446 0.043148413, -0.4110004 0.084611401 0.043319508, -0.4110004 0.084411532 0.043545172, -0.4110004 0.084271535 0.043812051, -0.41100037 0.084199458 0.044104621, -0.41100037 0.084199458 0.044405982, -0.4110004 0.084271327 0.044698641, -0.4110004 0.084411338 0.044965282, -0.4110004 0.084611207 0.045191035, -0.41100043 0.084859252 0.04536213, -0.4110004 0.085140973 0.04546909, -0.4110004 0.085440069 0.04550533, -0.4110004 0.085739225 0.04546909, -0.4110004 0.086021006 0.045362279, -0.4110004 0.086268976 0.045191035, -0.4110004 0.086468846 0.044965431, -0.4110004 0.086608931 0.044698641, -0.4110004 0.086681172 0.044406071, -0.4110004 0.086681172 0.04410477, -0.4110004 0.086609036 0.0438122, -0.4110004 0.086468965 0.04354541, -0.41100037 0.08626917 0.043319806, -0.4110004 0.086021185 0.043148711, -0.41100052 0.085739508 0.043041602, -0.41400042 0.084723726 0.018668309, -0.41400039 0.084047526 0.018411711, -0.41400039 0.083452404 0.018000856, -0.41400039 0.082972765 0.017459378, -0.41400039 0.082636774 0.016818926, -0.41400039 0.082463637 0.016116843, -0.41400039 0.082463801 0.0153936, -0.41400036 0.082636863 0.014691219, -0.41400036 0.082972959 0.014050946, -0.41400039 0.083452642 0.013509825, -0.41400039 0.084047854 0.01309894, -0.41400054 0.084724098 0.012842432, -0.41400042 0.084860846 0.016862109, -0.41400039 0.084612966 0.016690955, -0.41400054 0.086470634 0.015045241, -0.41400051 0.084413186 0.015045181, -0.41400039 0.08461304 0.014819726, -0.41400042 0.08486104 0.014648423, -0.41400054 0.08427313 0.015312061, -0.41400045 0.08661066 0.015312269, -0.41400042 0.086682782 0.015604839, -0.41400042 0.085142806 0.01454173, -0.41400042 0.085142657 0.0169691, -0.41400054 0.084201053 0.01560469, -0.41400051 0.085740924 0.016969159, -0.41400039 0.085441813 0.017005548, -0.41400039 0.085441902 0.014505342, -0.41400054 0.084201053 0.015906051, -0.41400042 0.086682782 0.015906081, -0.41400042 0.086610571 0.016198859, -0.41400039 0.085741058 0.014541581, -0.41400042 0.086470544 0.016465649, -0.41400054 0.08602275 0.016862109, -0.41400039 0.086270675 0.016691163, -0.41400039 0.08427301 0.016198501, -0.41400042 0.08602275 0.014648512, -0.41400039 0.084413022 0.0164655, -0.41400045 0.086270764 0.014819726, -0.41100046 0.085441887 0.014505342, -0.4110004 0.085142761 0.014541581, -0.4110004 0.084860951 0.014648423, -0.4110004 0.08461301 0.014819577, -0.41100043 0.084413171 0.015045241, -0.4110004 0.08427313 0.015312061, -0.41100037 0.084200948 0.015604481, -0.4110004 0.084201023 0.015906081, -0.4110004 0.084273055 0.016198501, -0.41100037 0.084413022 0.01646544, -0.41100037 0.084612966 0.016690955, -0.4110004 0.084860876 0.016862109, -0.4110004 0.085142702 0.016968951, -0.41100037 0.085441828 0.017005399, -0.4110004 0.085740954 0.0169691, -0.4110004 0.086022705 0.016862109, -0.4110004 0.086270705 0.016691104, -0.4110004 0.08647044 0.0164655, -0.4110004 0.086610585 0.016198501, -0.4110004 0.086682692 0.015906081, -0.4110004 0.086682796 0.01560469, -0.41100037 0.086610645 0.01531215, -0.41100037 0.086470634 0.015045241, -0.4110004 0.086270869 0.014819816, -0.41100037 0.086022824 0.014648423, -0.41100037 0.085741073 0.01454173, -0.41400051 0.084725529 -0.012831822, -0.41400039 0.084049284 -0.013088331, -0.41400039 0.083454102 -0.013499245, -0.41400039 0.082974583 -0.014040574, -0.41400051 0.082638502 -0.014680967, -0.41400036 0.08246541 -0.015383139, -0.41400051 0.082465544 -0.016106471, -0.41400051 0.082638666 -0.016808674, -0.41400051 0.082974836 -0.017449006, -0.41400051 0.083454475 -0.017990455, -0.41400042 0.084049597 -0.018401131, -0.41400051 0.084725872 -0.018657461, -0.41400054 0.084862679 -0.014637813, -0.41400042 0.084614709 -0.014808998, -0.41400054 0.086472437 -0.016454592, -0.41400039 0.084414959 -0.016454741, -0.41400039 0.084614813 -0.016680375, -0.41400039 0.084862724 -0.016851649, -0.41400039 0.084274948 -0.016188011, -0.41400042 0.085144535 -0.016958401, -0.41400054 0.086612493 -0.016187802, -0.41400042 0.08668454 -0.015895233, -0.41400039 0.084202796 -0.015895382, -0.41400042 0.085443676 -0.016994581, -0.41400039 0.08514443 -0.014531001, -0.41400042 0.085443571 -0.014494672, -0.41400051 0.084202737 -0.01559402, -0.41400042 0.085742846 -0.016958252, -0.41400039 0.08668448 -0.015593991, -0.41400054 0.086612418 -0.015301362, -0.41400039 0.084274769 -0.015301362, -0.41400042 0.085742727 -0.014530882, -0.41400042 0.086024597 -0.01685144, -0.41400042 0.086472288 -0.015034571, -0.41400042 0.086024493 -0.014637932, -0.41400039 0.08441478 -0.01503478, -0.41400042 0.086272538 -0.014808998, -0.41400042 0.086272612 -0.016680256, -0.4110004 0.08544372 -0.0169947, -0.4110004 0.08514455 -0.016958341, -0.4110004 0.084862813 -0.016851529, -0.4110004 0.084614813 -0.016680375, -0.4110004 0.08441487 -0.016454741, -0.4110004 0.084274903 -0.016188011, -0.41100037 0.084202796 -0.015895471, -0.4110004 0.084202752 -0.01559411, -0.4110004 0.084274784 -0.015301451, -0.4110004 0.084414795 -0.01503478, -0.4110004 0.084614649 -0.014808998, -0.41100037 0.084862649 -0.014637932, -0.4110004 0.085144356 -0.014530912, -0.4110004 0.085443512 -0.014494672, -0.4110004 0.085742682 -0.014530882, -0.4110004 0.086024463 -0.014637813, -0.4110004 0.086272404 -0.014808998, -0.4110004 0.086472243 -0.015034452, -0.4110004 0.086612374 -0.015301242, -0.4110004 0.086684436 -0.015593871, -0.4110004 0.086684495 -0.015895382, -0.4110004 0.086612433 -0.016187802, -0.4110004 0.086472377 -0.016454682, -0.4110004 0.086272568 -0.016680256, -0.41100037 0.086024553 -0.016851529, -0.4110004 0.085742861 -0.016958252, -0.41400042 0.084727138 -0.041331843, -0.41400039 0.084050924 -0.041588262, -0.41400042 0.083455697 -0.041999146, -0.41400054 0.082976177 -0.042540625, -0.41400054 0.082640141 -0.043180987, -0.41400039 0.082467094 -0.04388319, -0.41400039 0.082467094 -0.044606611, -0.41400039 0.082640231 -0.045308664, -0.41400051 0.082976446 -0.045948938, -0.41400042 0.083456025 -0.046490237, -0.41400039 0.084051222 -0.046901092, -0.41400039 0.084727436 -0.047157511, -0.41400042 0.084864244 -0.043137953, -0.41400039 0.084616244 -0.043309048, -0.41400054 0.086474001 -0.044954643, -0.41400054 0.084416553 -0.044954821, -0.41400039 0.084616423 -0.045180306, -0.41400054 0.084864408 -0.04535161, -0.41400051 0.084276497 -0.044687852, -0.41400051 0.085146189 -0.045458481, -0.41400042 0.086613998 -0.044687852, -0.41400054 0.086686164 -0.044395193, -0.41400054 0.084204435 -0.044395551, -0.41400039 0.085445359 -0.04549472, -0.41400039 0.08514604 -0.043030933, -0.41400042 0.085445121 -0.042994663, -0.41400054 0.084204376 -0.044094011, -0.41400042 0.085744441 -0.045458302, -0.41400042 0.08668609 -0.044093803, -0.41400042 0.086613998 -0.043801382, -0.41400051 0.084276497 -0.043801472, -0.41400042 0.085744247 -0.043030933, -0.41400039 0.086026147 -0.045351431, -0.41400042 0.086473912 -0.043534562, -0.41400039 0.086026058 -0.043137714, -0.41400051 0.084416509 -0.043534592, -0.41400054 0.086274117 -0.043308929, -0.41400054 0.086274266 -0.045180276, -0.4110004 0.085445315 -0.045494542, -0.41100037 0.085146129 -0.045458481, -0.4110004 0.084864318 -0.04535161, -0.4110004 0.084616333 -0.045180276, -0.4110004 0.084416419 -0.044954851, -0.41100037 0.084276468 -0.044688031, -0.4110004 0.084204346 -0.044395402, -0.4110004 0.084204346 -0.044094041, -0.41100037 0.084276468 -0.043801472, -0.4110004 0.084416419 -0.043534681, -0.41100043 0.084616289 -0.043309227, -0.4110004 0.084864244 -0.043137744, -0.41100037 0.08514604 -0.043031052, -0.4110004 0.085445136 -0.042994693, -0.4110004 0.085744292 -0.043031052, -0.4110004 0.086026043 -0.043137953, -0.4110004 0.086274058 -0.043309048, -0.4110004 0.086473912 -0.043534562, -0.4110004 0.086614013 -0.043801352, -0.41100049 0.086686179 -0.044094011, -0.4110004 0.086686164 -0.044395372, -0.4110004 0.086614013 -0.044687852, -0.4110004 0.086473972 -0.044954821, -0.4110004 0.086274147 -0.045180276, -0.4110004 0.086026162 -0.045351461, -0.4110004 0.085744351 -0.045458302, 0.41399994 0.096727192 0.051093206, 0.41399989 0.096050993 0.051349625, 0.41399994 0.095455796 0.05176048, 0.41399992 0.094976157 0.05230172, 0.41399986 0.094640061 0.052942112, 0.41399986 0.09446688 0.053644255, 0.41399986 0.09446688 0.054367498, 0.41399989 0.094639912 0.055069759, 0.41399977 0.094976053 0.055710301, 0.41399986 0.095455602 0.05625163, 0.41399983 0.096050769 0.056662247, 0.41399983 0.096726984 0.056918874, 0.41399994 0.098273829 0.05307053, 0.41399983 0.098473743 0.053295895, 0.41399989 0.09661597 0.054941729, 0.41399983 0.096864045 0.055112824, 0.41399994 0.09661606 0.053070322, 0.41399983 0.096416235 0.053295895, 0.41399994 0.096864179 0.052899197, 0.41399989 0.096276179 0.053562835, 0.4139998 0.098613665 0.053562835, 0.41399994 0.098685786 0.053855404, 0.41399989 0.09714593 0.052792326, 0.41399977 0.096204132 0.053855255, 0.41399989 0.097145811 0.055219725, 0.41399989 0.097445115 0.052756056, 0.41399994 0.098685786 0.054156855, 0.41399977 0.096204132 0.054156765, 0.41399994 0.097744077 0.055219725, 0.41399994 0.097444907 0.055256054, 0.41399989 0.097744241 0.052792326, 0.4139998 0.098613665 0.054449365, 0.41399989 0.096276119 0.054449275, 0.41399994 0.098473623 0.054716274, 0.41399989 0.098025993 0.052899197, 0.41399994 0.098025829 0.055112913, 0.41399989 0.09641619 0.054716155, 0.41399989 0.098273829 0.054941878, 0.41099992 0.097444892 0.055256113, 0.41099992 0.097145766 0.055219725, 0.41099986 0.096863955 0.055112913, 0.41099986 0.096616 0.054941729, 0.4109998 0.096416235 0.054716155, 0.41099998 0.096276134 0.054449275, 0.41099986 0.096203968 0.054156765, 0.41099986 0.096203968 0.053855345, 0.41099992 0.096276194 0.053562835, 0.41099992 0.096416205 0.053295806, 0.41099986 0.096616134 0.053070232, 0.41099975 0.096864209 0.052899286, 0.4109998 0.097146004 0.052792326, 0.41099983 0.09744516 0.052756146, 0.4109998 0.097744361 0.052792326, 0.41099975 0.098026022 0.052899197, 0.41099986 0.098273844 0.05307053, 0.4109998 0.098473743 0.053295895, 0.41099986 0.098613724 0.053562835, 0.41099983 0.098685905 0.053855643, 0.41099983 0.098685905 0.054156944, 0.41099986 0.098613724 0.054449365, 0.41099986 0.098473713 0.054716155, 0.41099986 0.098273814 0.054941729, 0.41099992 0.098025799 0.055112913, 0.41099992 0.097744048 0.055219725, 0.41399989 0.096728876 0.022593275, 0.41399994 0.096052587 0.022849515, 0.41399994 0.095457435 0.0232604, 0.41399994 0.094977677 0.023801729, 0.41399989 0.094641566 0.024442121, 0.41399989 0.094468489 0.025144115, 0.41399989 0.094468489 0.025867358, 0.41399989 0.094641432 0.02656962, 0.41399992 0.094977587 0.027210101, 0.41399992 0.095457047 0.02775155, 0.41399989 0.096052304 0.028162375, 0.41399989 0.09672837 0.028418675, 0.41399994 0.098475352 0.024796024, 0.41399989 0.096865639 0.026612684, 0.41399994 0.096617609 0.026441678, 0.41399983 0.096617669 0.024570152, 0.41399989 0.096417829 0.024795815, 0.41399983 0.096865773 0.024399206, 0.41399994 0.096277788 0.025062695, 0.41399994 0.098615363 0.025062904, 0.41399989 0.09714748 0.024292365, 0.41399977 0.098687559 0.025355324, 0.41399989 0.096205667 0.025355324, 0.41399983 0.097446591 0.024256155, 0.41399994 0.096205622 0.025656715, 0.41399989 0.09714736 0.026719734, 0.41399994 0.097745791 0.024292544, 0.41399989 0.097446516 0.026756033, 0.41399994 0.096277744 0.025949284, 0.41399977 0.098687559 0.025656715, 0.41399989 0.098027512 0.024399206, 0.41399989 0.097745761 0.026719734, 0.41399983 0.098615423 0.025949374, 0.41399994 0.0964178 0.026216075, 0.41399986 0.098275527 0.02457054, 0.41399989 0.098027468 0.026612774, 0.41399983 0.098475322 0.026216075, 0.41399983 0.098275468 0.026441678, 0.41099983 0.097446591 0.026756063, 0.4109998 0.097147509 0.026719734, 0.41099983 0.096865684 0.026612774, 0.4109998 0.096617684 0.026441678, 0.41099983 0.096417874 0.026216075, 0.41099975 0.096277907 0.025949284, 0.4109998 0.096205711 0.025656715, 0.4109998 0.096205711 0.025355324, 0.41099975 0.096277907 0.025062844, 0.41099986 0.096417874 0.024795905, 0.41099986 0.096617728 0.024570361, 0.4109998 0.096865758 0.024399206, 0.4109998 0.097147509 0.024292365, 0.4109998 0.09744668 0.024256006, 0.41099992 0.097745776 0.024292246, 0.4109998 0.098027572 0.024399206, 0.41099983 0.098275512 0.024570361, 0.41099992 0.098475337 0.024796024, 0.4109998 0.098615393 0.025062844, 0.41099986 0.09868747 0.025355473, 0.41099986 0.09868747 0.025656834, 0.4109998 0.098615393 0.025949284, 0.4109998 0.098475382 0.026216075, 0.41099983 0.098275512 0.026441738, 0.4109998 0.098027512 0.026612893, 0.41099986 0.097745746 0.026719734, 0.41399994 0.096729353 0.012593165, 0.41399989 0.096053138 0.012849644, 0.41399997 0.095457911 0.01326032, 0.41399989 0.094978318 0.013801649, 0.41399997 0.094642162 0.014442042, 0.41399989 0.094469056 0.015144184, 0.41399983 0.094469056 0.015867457, 0.41399989 0.094642028 0.016569689, 0.41399997 0.094978064 0.017210051, 0.41399989 0.095457628 0.01775144, 0.41399994 0.096052811 0.018162325, 0.41399994 0.09672901 0.018418893, 0.41399989 0.098276004 0.01457046, 0.41399986 0.098475963 0.014795974, 0.41399994 0.096618116 0.016441628, 0.41399994 0.096866161 0.016612843, 0.41399983 0.096618325 0.014570311, 0.41399983 0.09641847 0.014795855, 0.41399977 0.096866429 0.014399126, 0.41399989 0.096278384 0.015062764, 0.41399994 0.098615929 0.015062913, 0.41399994 0.098688051 0.015355423, 0.41399977 0.09714815 0.014292315, 0.41399983 0.096206307 0.015355334, 0.41399994 0.097147912 0.016719684, 0.41399983 0.097447187 0.014256224, 0.41399983 0.098688036 0.015656933, 0.41399983 0.096206218 0.015656725, 0.41399994 0.097446978 0.016756013, 0.41399989 0.097746447 0.014292344, 0.41399989 0.098615885 0.015949443, 0.41399977 0.097746372 0.016719684, 0.41399994 0.096278369 0.015949205, 0.41399977 0.098475933 0.016216233, 0.41399983 0.098028079 0.014399365, 0.41399994 0.09802793 0.016612992, 0.41399994 0.096418351 0.016216114, 0.41399983 0.098276049 0.016441688, 0.4109998 0.097447142 0.016756132, 0.4109998 0.097148016 0.016719684, 0.41099983 0.09686619 0.016612843, 0.41099992 0.096618176 0.016441628, 0.4109998 0.096418425 0.016215995, 0.4109998 0.096278414 0.015949205, 0.41099986 0.096206293 0.015656784, 0.41099992 0.096206188 0.015355334, 0.4109998 0.096278444 0.015062764, 0.41099975 0.096418515 0.014795855, 0.41099983 0.096618325 0.014570311, 0.41099992 0.09686625 0.014399275, 0.4109998 0.097148076 0.014292315, 0.41099992 0.097447157 0.014256075, 0.41099992 0.097746313 0.014292344, 0.41099992 0.098028049 0.014399275, 0.41099992 0.098276019 0.014570341, 0.4109998 0.098475978 0.014795974, 0.41099992 0.098615885 0.015062913, 0.4109998 0.098688111 0.015355423, 0.41099986 0.098687977 0.015656933, 0.41099992 0.098615885 0.015949324, 0.41099986 0.098475799 0.016216233, 0.41099983 0.09827593 0.016441688, 0.4109998 0.098028019 0.016612992, 0.41099992 0.097746283 0.016719684, 0.41399989 0.096731499 -0.025806859, 0.41399994 0.096055329 -0.025550589, 0.41399992 0.095460087 -0.025139645, 0.41399992 0.094980448 -0.024598226, 0.41399994 0.094644248 -0.023957893, 0.41399997 0.094471246 -0.023255691, 0.41399989 0.094471246 -0.022532597, 0.41399997 0.094644219 -0.021830335, 0.41399983 0.094980329 -0.021189883, 0.41399989 0.095459878 -0.020648524, 0.41399994 0.096055031 -0.020237699, 0.41399983 0.096731156 -0.019981161, 0.41399986 0.09827818 -0.023829564, 0.41399989 0.098478064 -0.02360405, 0.41399989 0.096620366 -0.021958306, 0.41399989 0.096868291 -0.021787181, 0.41399989 0.09662044 -0.023829564, 0.41399983 0.096420616 -0.023604169, 0.41399977 0.096868545 -0.024000838, 0.41399994 0.09628053 -0.02333726, 0.41399989 0.098618031 -0.023337111, 0.41399983 0.098690182 -0.023044601, 0.41399989 0.097150192 -0.02410771, 0.41399994 0.096208364 -0.02304475, 0.41399989 0.097150013 -0.02168031, 0.41399989 0.097449347 -0.024144068, 0.41399983 0.098690167 -0.02274324, 0.41399983 0.096208423 -0.022743389, 0.41399989 0.097449228 -0.021644041, 0.41399994 0.097748533 -0.02410771, 0.41399989 0.098618031 -0.022450581, 0.41399983 0.097748503 -0.02168031, 0.41399977 0.09628059 -0.02245076, 0.41399983 0.098478064 -0.02218388, 0.41399983 0.098030254 -0.024000809, 0.41399989 0.098030135 -0.021787181, 0.41399994 0.096420541 -0.02218397, 0.41399983 0.09827809 -0.021958306, 0.41099986 0.097449288 -0.021644041, 0.41099986 0.097150132 -0.02168031, 0.4109998 0.096868381 -0.021787181, 0.41099986 0.096620426 -0.021958306, 0.41099983 0.096420616 -0.02218397, 0.4109998 0.09628047 -0.02245076, 0.4109998 0.096208438 -0.022743389, 0.41099986 0.096208408 -0.02304475, 0.41099986 0.09628056 -0.023337379, 0.41099992 0.096420467 -0.023604169, 0.41099986 0.09662047 -0.023829564, 0.41099992 0.096868396 -0.024000809, 0.4109998 0.097150296 -0.02410771, 0.4109998 0.097449407 -0.024144068, 0.41099992 0.097748518 -0.02410771, 0.4109998 0.098030299 -0.024000809, 0.41099986 0.098278314 -0.023829564, 0.41099986 0.098478094 -0.02360405, 0.41099986 0.098618105 -0.02333726, 0.4109998 0.098690227 -0.023044601, 0.41099992 0.098690152 -0.02274324, 0.41099986 0.098618105 -0.02245073, 0.41099986 0.098478094 -0.02218388, 0.41099986 0.09827815 -0.021958247, 0.4109998 0.098030105 -0.021787181, 0.41099992 0.097748339 -0.02168031, 0.41399989 0.096732169 -0.03580676, 0.41399989 0.096055791 -0.03555049, 0.41399989 0.095460683 -0.035139576, 0.41399989 0.09498097 -0.034598276, 0.414 0.094644874 -0.033957943, 0.41399986 0.094471842 -0.033255801, 0.41399989 0.094471708 -0.032532558, 0.41399989 0.094644725 -0.031830296, 0.41399994 0.094980836 -0.031189904, 0.41399989 0.09546043 -0.030648574, 0.41399989 0.096055523 -0.03023766, 0.41399994 0.096731752 -0.029981241, 0.41399983 0.098278835 -0.033829466, 0.41399983 0.098478734 -0.033604011, 0.41399989 0.096620873 -0.031958327, 0.41399994 0.096620992 -0.033829555, 0.41399983 0.096868843 -0.031787142, 0.41399989 0.096421212 -0.033604249, 0.41399989 0.096869022 -0.034000859, 0.41399977 0.098618776 -0.033337221, 0.41399989 0.096281126 -0.03333737, 0.41399977 0.098690838 -0.033044443, 0.41399983 0.097150773 -0.034107819, 0.41399983 0.097150683 -0.031680331, 0.41399994 0.09620896 -0.0330448, 0.41399989 0.098690689 -0.032743201, 0.41399994 0.097449854 -0.03414391, 0.41399989 0.09774901 -0.031680331, 0.41399989 0.097449765 -0.031643942, 0.41399994 0.098618552 -0.032450631, 0.41399994 0.09620896 -0.03274335, 0.41399989 0.097749099 -0.03410767, 0.41399989 0.098478481 -0.03218399, 0.41399977 0.096281141 -0.032450721, 0.41399994 0.098030716 -0.031787142, 0.41399983 0.09803082 -0.034000769, 0.41399994 0.098278686 -0.031958237, 0.41399989 0.096421018 -0.03218399, 0.4109998 0.097449824 -0.031643942, 0.4109998 0.097150758 -0.031680331, 0.4109998 0.096868977 -0.031787142, 0.41099986 0.096620858 -0.031958327, 0.41099992 0.096421093 -0.03218399, 0.4109998 0.096281111 -0.032450721, 0.4109998 0.096208945 -0.03274335, 0.41099986 0.096208945 -0.033044711, 0.41099986 0.096281201 -0.03333737, 0.41099975 0.096421257 -0.03360416, 0.4109998 0.096621066 -0.033829555, 0.4109998 0.096869007 -0.034000799, 0.4109998 0.097150847 -0.03410767, 0.4109998 0.097449914 -0.034144059, 0.4109998 0.097749159 -0.03410767, 0.41099992 0.098030806 -0.034000799, 0.4109998 0.098278865 -0.033829555, 0.41099986 0.098478645 -0.033604011, 0.41099992 0.098618612 -0.033337221, 0.4109998 0.098690793 -0.033044711, 0.41099986 0.098690689 -0.032743201, 0.4109998 0.098618641 -0.032450542, 0.4109998 0.09847863 -0.03218399, 0.4109998 0.098278746 -0.031958327, 0.4109998 0.098030791 -0.031787142, 0.4109998 0.09774898 -0.031680331, 0.41399989 0.09673433 -0.074206933, 0.41399989 0.096058026 -0.073950514, 0.41399994 0.095462829 -0.07353963, 0.41399983 0.094983205 -0.0729983, 0.414 0.094647065 -0.072357908, 0.41399977 0.094474047 -0.071655944, 0.41399989 0.094473943 -0.070932701, 0.41399994 0.094646871 -0.07023035, 0.41399997 0.094982952 -0.069590077, 0.41399994 0.095462531 -0.069048539, 0.41399989 0.096057698 -0.068637595, 0.41399989 0.096733898 -0.068381384, 0.41399994 0.098280951 -0.072229549, 0.41399989 0.098480806 -0.072003916, 0.41399989 0.096623093 -0.070358381, 0.41399983 0.096623123 -0.072229818, 0.41399977 0.096871138 -0.070187196, 0.41399997 0.096423313 -0.072004065, 0.41399977 0.096871287 -0.072400823, 0.41399994 0.098620817 -0.071737185, 0.41399989 0.096283272 -0.071737185, 0.41399983 0.098692968 -0.071444705, 0.41399983 0.097152919 -0.072507545, 0.41399983 0.097152829 -0.070080295, 0.41399989 0.09621115 -0.071444765, 0.41399983 0.098692968 -0.071143255, 0.41399983 0.097452074 -0.072543964, 0.41399977 0.09775123 -0.070080385, 0.41399983 0.097452 -0.070043996, 0.41399983 0.098620728 -0.070850745, 0.41399989 0.09621115 -0.071143404, 0.41399986 0.097751305 -0.072507545, 0.41399983 0.098480716 -0.070583954, 0.41399989 0.096283183 -0.070850745, 0.41399983 0.098032862 -0.070187077, 0.41399986 0.098032981 -0.072400764, 0.41399983 0.098280862 -0.070358291, 0.41399994 0.096423239 -0.070583954, 0.4109998 0.09745203 -0.070043996, 0.4109998 0.097152874 -0.070080385, 0.41099989 0.096871063 -0.070187196, 0.4109998 0.096623078 -0.0703585, 0.4109998 0.096423313 -0.070583954, 0.4109998 0.096283212 -0.070850834, 0.4109998 0.096211106 -0.071143344, 0.41099986 0.09621118 -0.071444765, 0.41099986 0.096283257 -0.071737424, 0.4109998 0.096423358 -0.072004154, 0.41099983 0.096623212 -0.072229818, 0.41099992 0.096871108 -0.072400823, 0.4109998 0.097152963 -0.072507545, 0.4109998 0.097452074 -0.072544053, 0.41099992 0.0977512 -0.072507545, 0.41099986 0.098032951 -0.072400823, 0.41099992 0.098280907 -0.072229609, 0.41099986 0.098480791 -0.072003916, 0.4109998 0.098620862 -0.071737185, 0.41099986 0.098692864 -0.071444497, 0.41099992 0.098692909 -0.071143344, 0.4109998 0.098620817 -0.070850745, 0.4109998 0.098480746 -0.070583895, 0.41099983 0.098280817 -0.070358291, 0.41099992 0.098032832 -0.070187196, 0.4109998 0.097751185 -0.070080295, 0.20930283 0.15444295 0.068654403, 0.20817585 0.15444282 0.069082215, 0.20718379 0.15444282 0.069766745, 0.20638451 0.15444261 0.070668921, 0.20582433 0.15444273 0.071736082, 0.20553584 0.15444262 0.072906598, 0.20553592 0.15444256 0.074112013, 0.20582433 0.15444246 0.07528238, 0.20638444 0.15444244 0.076349691, 0.20718378 0.15444238 0.077251926, 0.2081759 0.15444228 0.077936456, 0.20930295 0.15444233 0.07836397, 0.36580285 0.15444392 0.068654492, 0.3646757 0.15444392 0.069082007, 0.36368385 0.15444383 0.069766745, 0.36288455 0.1544437 0.070668921, 0.36232439 0.15444373 0.071736082, 0.36203596 0.15444361 0.072906598, 0.36203584 0.1544437 0.074111983, 0.36232439 0.15444349 0.075282231, 0.36288461 0.15444343 0.076349542, 0.36368379 0.15444349 0.077251926, 0.36467591 0.15444335 0.077936456, 0.36580285 0.15444337 0.07836397, 0.2093028 0.15445115 -0.078345492, 0.20817578 0.1544511 -0.077918127, 0.20718382 0.15445101 -0.077233419, 0.20638448 0.15445097 -0.076331213, 0.20582435 0.15445097 -0.075263813, 0.20553593 0.15445085 -0.074093297, 0.20553583 0.15445079 -0.072888121, 0.20582439 0.15445073 -0.071717814, 0.20638452 0.15445065 -0.070650443, 0.20718373 0.15445067 -0.069748178, 0.20817584 0.15445057 -0.0690635, 0.2093028 0.15445061 -0.068636134, 0.36580282 0.15445213 -0.078345492, 0.36467591 0.15445207 -0.077918127, 0.36368385 0.15445206 -0.077233419, 0.3628847 0.15445192 -0.076331213, 0.36232439 0.15445203 -0.075263813, 0.36203596 0.15445186 -0.074093565, 0.36203596 0.15445174 -0.072888121, 0.36232439 0.1544517 -0.071717814, 0.36288461 0.15445165 -0.070650324, 0.36368385 0.15445164 -0.069748178, 0.36467591 0.15445159 -0.069063529, 0.36580297 0.15445158 -0.068636134, 0.45741853 0.15444621 0.037616089, 0.46235365 0.15444429 0.071373209, 0.45717058 0.15444623 0.037444845, -0.49000093 0.15443578 0.11475928, -0.4820008 0.15443465 0.13403709, -0.49000081 0.1544347 0.13403709, 0.45770034 0.15444615 0.03772299, 0.46307012 0.15444435 0.070738301, 0.4626734 0.15444432 0.071012244, -0.46213087 0.1544466 -0.073200002, -0.46235505 0.15444668 -0.073626742, -0.46201548 0.15444651 -0.072731957, -0.46267459 0.15444657 -0.073987678, -0.4700008 0.1544473 -0.086490706, -0.47676 0.15444863 -0.11164148, -0.47683218 0.15444866 -0.11193405, -0.47676 0.15444863 -0.11134027, -0.48928523 0.15443584 0.11299266, -0.48982432 0.15443583 0.11358888, -0.48969164 0.15443583 0.11335371, -0.48952195 0.15443584 0.11316083, -0.48901892 0.15443593 0.11287735, -0.48991963 0.15443578 0.11386685, 0.45799953 0.15444627 0.037759289, 0.46352085 0.15444435 0.070567504, -0.4885616 0.15443584 0.11278374, -0.48800093 0.15443599 0.1127594, -0.2138164 0.15443978 0.077251717, -0.4897677 0.15443608 0.10954364, -0.48940668 0.15443614 0.10995026, -0.48959956 0.15443592 0.10978018, -0.21461582 0.15443976 0.076349542, -0.21282439 0.15443966 0.077936456, -0.48917142 0.15443602 0.11008285, -0.4898828 0.15443607 0.10927723, -0.48889342 0.15443602 0.11017795, -0.48997638 0.15443611 0.10881992, -0.21517593 0.15443982 0.075282529, -0.21169731 0.15443964 0.07836397, -0.4880009 0.15443607 0.11025928, -0.49000087 0.1544362 0.10825942, -0.49000081 0.15443623 0.10733767, -0.21546428 0.15443988 0.074111983, -0.48970982 0.15443635 0.10625039, -0.48996165 0.15443631 0.10680391, -0.48988691 0.15443635 0.10655667, 0.46999952 0.15444621 0.039759204, 0.4639996 0.15444435 0.070509091, -0.48958632 0.15443635 0.10610186, 0.46799943 0.15444621 0.037759289, 0.46598497 0.15444431 0.072268233, 0.46586946 0.15444435 0.071799979, 0.46564546 0.15444432 0.071373209, 0.46532574 0.15444435 0.071012154, 0.46492901 0.15444435 0.070738301, 0.46447805 0.15444432 0.070567355, -0.48941514 0.15443636 0.10592355, 0.46997502 0.15444623 0.039198563, -0.47800079 0.1544359 0.11275925, -0.21546444 0.15444003 0.072906598, 0.46889183 0.15444629 0.037840411, -0.47770175 0.15443587 0.11272301, 0.4698815 0.1544462 0.038741365, 0.46916983 0.15444629 0.037935778, -0.47742 0.1544359 0.11261614, 0.46976641 0.15444615 0.038474962, 0.46940526 0.15444629 0.038068488, -0.47717199 0.15443593 0.1124451, 0.46959817 0.15444626 0.038238302, -0.47697219 0.15443605 0.11221941, -0.47800091 0.15443607 0.11025928, -0.21517593 0.15443999 0.071736082, -0.4700008 0.15443753 0.086509362, -0.47676 0.15443611 0.1113586, -0.47683212 0.15443622 0.11106612, -0.47697219 0.15443614 0.11079927, -0.47717205 0.15443619 0.11057372, -0.47742012 0.15443619 0.11040242, -0.47770181 0.15443619 0.11029573, -0.21461573 0.15444003 0.070669129, -0.47683212 0.15443622 0.11195256, -0.46564695 0.15443832 0.073645547, -0.46532711 0.1544383 0.074006394, -0.46493047 0.15443814 0.074280098, -0.21381646 0.15444021 0.069766745, -0.46587101 0.15443832 0.073218569, -0.46447954 0.15443815 0.074451342, -0.46598625 0.15443829 0.072750553, -0.46400085 0.15443817 0.074509457, -0.46598625 0.15443829 0.072268084, -0.46352229 0.15443817 0.074451342, -0.37111589 0.15444736 -0.076330975, -0.38500088 0.15444683 -0.067490891, 0.46969029 0.15444651 0.034664974, 0.4695203 0.1544465 0.034857824, 0.46928382 0.15444644 0.035026148, -0.37031642 0.15444727 -0.077233419, -0.36932448 0.15444747 -0.077918127, -0.36819747 0.15444747 -0.078345492, -0.46307161 0.15443833 0.074280247, 0.46982285 0.15444651 0.034429833, 0.46901748 0.15444644 0.035141274, -0.47697225 0.15444863 -0.11220087, -0.48200086 0.15444979 -0.13401867, -0.46267468 0.15443841 0.074006394, 0.4699181 0.15444648 0.034151539, 0.46856025 0.15444641 0.035234854, 0.46999949 0.15444654 0.033259258, 0.46799949 0.15444647 0.035259321, 0.45799944 0.15444639 0.035259321, -0.19250077 0.15444034 0.067509368, -0.2146157 0.15444796 -0.070650443, -0.47676 0.15443611 0.11165999, -0.46235505 0.15443844 0.073645338, -0.21381637 0.15444793 -0.069748178, -0.46213087 0.15443833 0.073218569, -0.46201548 0.15443841 0.072750404, -0.47000101 0.15444021 0.039759204, -0.46400079 0.15443845 0.07050918, -0.46447951 0.15443842 0.070567504, -0.46493039 0.15443838 0.07073845, -0.21517587 0.15444803 -0.071717814, -0.4653272 0.15443844 0.071012154, -0.4656471 0.15443847 0.071373209, -0.46587101 0.15443835 0.071799979, -0.46352229 0.15443845 0.070567504, -0.21546434 0.15444809 -0.072888121, -0.21546429 0.15444818 -0.074093297, -0.21517584 0.15444824 -0.075263724, -0.46928519 0.15444027 0.037992403, -0.46982417 0.15444021 0.038588837, -0.46969166 0.15444021 0.038353369, -0.46952185 0.15444025 0.038160726, -0.21461579 0.1544484 -0.076331213, -0.46901891 0.15444031 0.037877396, -0.4699195 0.15444027 0.038866833, 0.38499942 0.1544517 -0.067490891, -0.46856168 0.15444027 0.037783816, -0.21381639 0.1544483 -0.077233419, -0.46800098 0.15444031 0.037759379, -0.21282442 0.15444845 -0.077918127, 0.45697084 0.15445024 -0.035780802, 0.4571707 0.15445028 -0.035555169, 0.45717064 0.15444635 0.035573527, 0.45697078 0.15444635 0.03579922, 0.45741859 0.15445033 -0.035384044, 0.45770043 0.15444633 0.035295531, 0.45741856 0.15444636 0.035402521, -0.46976766 0.15444031 0.034543619, -0.46940675 0.15444043 0.034950212, -0.46959957 0.15444054 0.0347801, 0.4577004 0.15445031 -0.035277143, -0.46917132 0.15444043 0.035082564, 0.45799956 0.15445028 -0.035240665, -0.46988276 0.15444043 0.034277245, -0.46889332 0.15444043 0.03517805, -0.46997657 0.15444058 0.033820018, -0.46800092 0.15444037 0.035259321, -0.47000101 0.15444058 0.033259109, -0.19250067 0.15444788 -0.067490801, -0.45800087 0.15444031 0.037759379, -0.46307147 0.15443847 0.07073845, -0.45770171 0.15444033 0.037722841, -0.46267459 0.15443832 0.071012154, -0.21169738 0.15444842 -0.078345492, -0.45742008 0.15444037 0.037616089, 0.46999946 0.15445033 -0.033240691, -0.46235493 0.15443839 0.071373209, 0.46799949 0.15445043 -0.035240665, -0.45717207 0.1544404 0.037444845, 0.46851614 0.15445045 -0.035223261, -0.46213093 0.15443845 0.071799979, 0.4699488 0.15445033 -0.033994928, 0.16249952 0.15444137 0.089009181, 0.46902448 0.15445036 -0.035120353, -0.16250083 0.15443937 0.089009389, -0.45697215 0.15444033 0.03721939, 0.46984628 0.15445033 -0.034355387, 0.46930549 0.15445045 -0.034995332, 0.46972361 0.15445039 -0.034596696, 0.46954271 0.15445034 -0.034818515, 0.19249938 0.15444279 0.067509279, -0.45800087 0.15444049 0.035259321, 0.46975395 0.15445057 -0.038434759, 0.46935549 0.15445046 -0.038016483, 0.46911415 0.15445054 -0.037894025, 0.46957731 0.15445055 -0.038197443, -0.37111577 0.15443876 0.076349482, -0.37031654 0.15443873 0.077251926, -0.38500085 0.15443912 0.067509279, -0.36932451 0.15443878 0.077936456, 0.46987912 0.15445054 -0.038715765, -0.371676 0.15443875 0.075282529, 0.46875364 0.15445055 -0.037791416, -0.36819753 0.15443876 0.07836397, 0.46998194 0.15445067 -0.039224073, 0.46799961 0.15445045 -0.037740752, -0.37196437 0.15443881 0.074111983, 0.46999952 0.15445058 -0.039740726, 0.45799956 0.1544504 -0.037740722, -0.37196442 0.15443894 0.072906598, -0.371676 0.15443899 0.071736082, 0.46267328 0.15445243 -0.070993796, 0.45770037 0.15445045 -0.037704483, 0.45741856 0.15445051 -0.037597552, 0.46235359 0.1544524 -0.071354643, 0.45717052 0.15445052 -0.037426367, -0.37111574 0.15443906 0.070668921, 0.46307012 0.15445232 -0.070719734, 0.46212956 0.15445237 -0.071781501, 0.45697081 0.15445045 -0.037200823, -0.37031651 0.15443921 0.069766745, 0.46352091 0.15445229 -0.070548788, -0.36932442 0.15443917 0.069082007, 0.46399954 0.15445237 -0.070490822, 0.16249947 0.15445136 -0.088990793, -0.16250071 0.15444934 -0.088990793, 0.46447814 0.15445237 -0.070548788, -0.36819744 0.15443921 0.068654552, -0.47000083 0.15444423 -0.033240721, 0.46212956 0.15445246 -0.073200002, 0.46201405 0.15445237 -0.072731957, 0.19249937 0.15445046 -0.067490652, 0.46492895 0.15445234 -0.070719734, 0.46235356 0.1544525 -0.07362707, 0.46532574 0.15445243 -0.070993736, 0.46267316 0.15445255 -0.073987827, 0.46564543 0.15445244 -0.071354643, 0.46586949 0.15445244 -0.071781501, 0.46598491 0.15445247 -0.072249636, -0.46935686 0.15444444 -0.034965023, -0.46975541 0.15444434 -0.034546986, -0.46957859 0.15444429 -0.034784093, -0.46911556 0.15444444 -0.035087481, -0.46988052 0.15444432 -0.034265772, -0.46875495 0.15444444 -0.03519012, 0.46999946 0.15445332 -0.086490706, 0.46586946 0.15445259 -0.073200092, 0.46564549 0.15445252 -0.07362707, 0.46598491 0.15445247 -0.072731838, -0.46998343 0.15444425 -0.033757433, 0.46307012 0.15445247 -0.07426165, 0.46352085 0.15445247 -0.074432597, 0.46399948 0.15445255 -0.074490741, 0.46447816 0.15445252 -0.074432626, 0.4649289 0.15445261 -0.07426168, 0.46532574 0.15445253 -0.073987678, -0.46800092 0.15444437 -0.035240784, 0.47697073 0.15445474 -0.11078067, 0.47717068 0.15445462 -0.11055516, 0.47741863 0.15445462 -0.11038397, 0.47683075 0.15445468 -0.11104761, 0.47770038 0.15445462 -0.11027716, 0.47675872 0.15445471 -0.11134003, -0.46930715 0.15444456 -0.037986204, -0.46954414 0.15444455 -0.0381632, -0.4697251 0.15444447 -0.038384691, -0.46984765 0.15444453 -0.038626119, 0.47799957 0.15445477 -0.11024071, 0.47675872 0.15445477 -0.11164139, 0.47683075 0.1544548 -0.11193405, -0.469026 0.15444449 -0.037861243, -0.46995029 0.15444452 -0.038986608, 0.47697082 0.15445484 -0.11220087, -0.46851751 0.15444447 -0.037758246, -0.47000089 0.15444461 -0.039740816, -0.46800092 0.15444447 -0.037740722, 0.48941377 0.15445447 -0.10590501, -0.45800087 0.15444444 -0.035240665, -0.45770165 0.15444444 -0.035277143, -0.4577018 0.15444049 0.035295531, 0.48996258 0.15445459 -0.10679664, 0.48988533 0.15445454 -0.10653804, 0.48975715 0.15445445 -0.10630049, 0.4899945 0.15445462 -0.10706244, -0.45742014 0.15444455 -0.035383835, 0.48999944 0.15445456 -0.10731922, -0.45742008 0.1544406 0.035402521, 0.48799959 0.15445469 -0.11024071, 0.4899995 0.15445465 -0.10824071, -0.45717192 0.15444443 -0.035555169, 0.48851633 0.1544546 -0.11022328, -0.45717207 0.15444054 0.035573527, 0.48994899 0.1544546 -0.10899486, 0.48902455 0.15445468 -0.11012028, 0.4898462 0.15445468 -0.10935532, -0.45697215 0.15444437 -0.035780683, 0.48930559 0.15445462 -0.10999526, -0.45697221 0.15444045 0.03579922, 0.48972383 0.15445463 -0.10959683, 0.48954281 0.15445463 -0.10981844, -0.45800093 0.15444461 -0.037740722, 0.48975405 0.15445493 -0.11343475, 0.48935542 0.1544549 -0.11301635, 0.48911414 0.15445492 -0.1128941, 0.4895772 0.15445493 -0.11319758, 0.48987913 0.15445502 -0.11371575, 0.48875359 0.15445487 -0.11279164, -0.46564698 0.15444651 -0.071354583, -0.46532729 0.15444645 -0.070993736, 0.48998198 0.15445499 -0.11422409, 0.48799947 0.1544549 -0.11274098, -0.46493033 0.15444636 -0.070719734, 0.48999944 0.15445498 -0.11474083, 0.47799954 0.15445484 -0.11274098, -0.46587083 0.15444641 -0.07178171, 0.48199955 0.15445602 -0.13401867, 0.47717071 0.15445477 -0.11242644, 0.47741866 0.15445472 -0.11259754, 0.47770044 0.15445472 -0.11270444, -0.46447942 0.1544463 -0.070548877, 0.4899995 0.15445609 -0.13401867, 0.38499954 0.15444399 0.067509368, 0.45675865 0.15444621 0.03635858, 0.45683077 0.15444635 0.036066011, 0.45683077 0.15445025 -0.036047474, 0.45675871 0.15445028 -0.036340043, 0.45675865 0.15445033 -0.036641493, -0.46598637 0.15444651 -0.072249696, 0.45683077 0.15445025 -0.036933914, 0.46201405 0.15445235 -0.072249696, 0.45675862 0.15444621 0.03666003, 0.45683077 0.15444615 0.0369526, 0.45697081 0.15444627 0.03721939, 0.46212956 0.15444428 0.071799979, 0.46201414 0.15444435 0.072268233, -0.46400091 0.15444638 -0.070490822, 0.46201417 0.15444425 0.072750404, -0.21169731 0.15444015 0.068654492, -0.21282443 0.15444019 0.069082007, -0.21169731 0.1544479 -0.068636134, -0.21282437 0.15444791 -0.069063529, -0.46352229 0.15444636 -0.070548877, 0.46999964 0.15444349 0.086509362, 0.48199949 0.15444089 0.13403709, -0.46307144 0.15444644 -0.070719823, -0.45770165 0.15444453 -0.037704483, -0.46267459 0.15444644 -0.070993736, -0.45741996 0.15444459 -0.037597552, -0.45676008 0.15444037 0.03666003, -0.4568322 0.15444042 0.0369526, -0.46201554 0.15443835 0.072268233, -0.45676002 0.15444037 0.03635858, -0.45683217 0.15444055 0.036066011, -0.45683214 0.15444447 -0.036047474, -0.4567599 0.15444437 -0.036340043, -0.45676002 0.15444444 -0.036641374, -0.46235499 0.15444651 -0.071354643, -0.4568322 0.15444456 -0.036933914, -0.45697209 0.15444452 -0.037200704, -0.45717195 0.15444459 -0.037426487, -0.46213093 0.15444654 -0.071781501, -0.46201548 0.15444651 -0.072249636, 0.4769707 0.1544423 0.11221941, 0.47717068 0.154442 0.11244495, 0.47741863 0.15444204 0.11261614, 0.47683084 0.15444225 0.11195256, 0.47770038 0.154442 0.11272301, 0.47675857 0.15444218 0.11166008, 0.47799954 0.1544421 0.11275925, 0.47675872 0.15444225 0.11135872, -0.46598637 0.15444651 -0.072731957, -0.46587101 0.15444656 -0.073200002, -0.46564695 0.15444656 -0.07362707, -0.46532723 0.15444659 -0.073987678, -0.46493039 0.15444654 -0.07426168, -0.4644796 0.15444663 -0.074432597, -0.46400079 0.15444654 -0.074490681, -0.46352232 0.15444665 -0.074432597, -0.46307144 0.15444656 -0.07426165, 0.48999944 0.1544421 0.11475919, 0.48799941 0.15444218 0.11275925, 0.48999959 0.15444095 0.13403709, 0.48997501 0.15444212 0.11419867, 0.48889199 0.15444206 0.11284067, 0.48988149 0.15444204 0.11374135, 0.48916999 0.15444209 0.11293598, 0.48976639 0.15444216 0.11347498, -0.48996386 0.15444821 -0.10679664, -0.48975846 0.15444829 -0.1063007, -0.48988679 0.1544483 -0.10653804, -0.48959324 0.15444827 -0.10609005, 0.48940536 0.15444225 0.1130686, 0.48959813 0.1544421 0.11323841, -0.49000096 0.15444838 -0.10731922, -0.48941514 0.15444823 -0.10590492, -0.48935688 0.15444851 -0.10996495, -0.48975542 0.15444842 -0.109547, -0.48957869 0.15444843 -0.10978405, -0.48911548 0.15444845 -0.1100875, -0.48988038 0.15444843 -0.10926579, -0.48875481 0.15444839 -0.11019008, -0.48998341 0.15444836 -0.10875739, -0.48800096 0.15444846 -0.11024071, -0.49000087 0.15444835 -0.10824071, 0.48969033 0.15444236 0.10966502, 0.48952046 0.15444231 0.10985787, 0.48928392 0.15444231 0.11002596, 0.48982286 0.15444244 0.10942967, 0.48901758 0.1544423 0.11014117, -0.48930702 0.1544486 -0.11298634, -0.48954418 0.15444864 -0.11316322, -0.48972526 0.15444879 -0.11338468, 0.4899182 0.15444238 0.10915183, 0.48856035 0.15444228 0.11023469, -0.48984763 0.15444864 -0.11362617, 0.4899995 0.15444238 0.10825919, 0.48799953 0.15444234 0.11025928, -0.48902592 0.15444863 -0.11286126, 0.48999944 0.15444262 0.10733767, -0.48995027 0.1544487 -0.11398678, -0.48851767 0.15444861 -0.11275844, -0.49000081 0.1544487 -0.11474083, -0.4880009 0.15444866 -0.11274098, -0.47800091 0.15444848 -0.11024071, 0.48976353 0.15444253 0.10632898, 0.4898853 0.15444267 0.10655643, 0.48997673 0.15444246 0.10689832, -0.47770187 0.15444858 -0.11027716, 0.48999432 0.15444255 0.10709046, -0.47741991 0.15444849 -0.11038397, 0.47799942 0.1544423 0.11025928, 0.47770032 0.15444228 0.11029561, 0.47741854 0.15444222 0.11040242, 0.47717071 0.15444219 0.11057363, 0.47697076 0.15444228 0.11079918, 0.47683075 0.15444221 0.11106612, -0.47717199 0.1544486 -0.11055516, 0.48941371 0.15444253 0.10592355, 0.46267322 0.15444428 0.074006394, -0.47697231 0.15444857 -0.11078067, 0.46235344 0.15444431 0.073645338, -0.47683212 0.15444863 -0.1110474, 0.46307006 0.15444417 0.074280098, 0.46212947 0.15444429 0.073218569, -0.47800085 0.1544487 -0.11274074, 0.46352085 0.15444416 0.074451193, 0.46399948 0.15444417 0.074509308, 0.46447816 0.15444413 0.074451193, 0.46492901 0.15444405 0.074280098, -0.47770175 0.15444858 -0.11270444, -0.47742 0.15444858 -0.11259769, -0.47717205 0.15444866 -0.11242644, -0.49000087 0.15444978 -0.13401882, 0.46532574 0.15444426 0.074006394, 0.46564546 0.15444428 0.073645547, -0.37111595 0.15444699 -0.070650563, -0.37031654 0.15444694 -0.069748357, 0.46586952 0.15444425 0.073218569, -0.36932451 0.15444699 -0.069063529, -0.37167606 0.15444708 -0.071717873, 0.46598497 0.15444426 0.072750404, -0.3681975 0.154447 -0.068636015, -0.37196442 0.15444708 -0.072888121, -0.3719644 0.15444718 -0.074093446, -0.37167594 0.15444729 -0.075263724, -0.46400079 0.15543811 0.074509308, -0.46447939 0.15543811 0.074451193, -0.46493047 0.1554382 0.074280098, -0.46532711 0.15543833 0.074006394, -0.46564683 0.15543833 0.073645338, -0.46587083 0.15543832 0.073218659, -0.4659864 0.15543842 0.072750553, -0.46598622 0.15543829 0.072268233, -0.46587104 0.15543838 0.071800187, -0.46564692 0.15543844 0.071373358, -0.4653272 0.15543836 0.071012154, -0.46493039 0.15543841 0.070738301, -0.4644796 0.1554385 0.070567504, -0.46400079 0.15543841 0.070509389, 0.46399948 0.15544419 0.074509308, 0.4635208 0.15544423 0.074451193, 0.46307012 0.15544418 0.074280247, 0.46267331 0.15544423 0.074006543, 0.46235362 0.15544425 0.073645547, 0.46212956 0.15544425 0.073218569, 0.46201405 0.15544435 0.072750404, 0.46201405 0.15544425 0.072268233, 0.46212944 0.15544435 0.071799979, 0.4623535 0.15544435 0.071373299, 0.46267334 0.15544438 0.071012244, 0.46307006 0.1554444 0.070738301, 0.46352085 0.15544435 0.070567355, 0.46399948 0.1554444 0.070509389, -0.46400079 0.1554466 -0.074490741, -0.46352229 0.1554466 -0.074432716, -0.4630715 0.15544663 -0.07426168, -0.46267468 0.1554466 -0.073987678, -0.46235499 0.15544668 -0.073626801, -0.46213093 0.1554466 -0.073199943, -0.46201554 0.1554465 -0.072731838, -0.46201554 0.1554465 -0.072249636, -0.46213087 0.15544648 -0.071781501, -0.46235493 0.15544654 -0.071354583, -0.46267459 0.15544648 -0.070993796, -0.46307147 0.15544645 -0.070719823, -0.46352217 0.15544635 -0.070548728, -0.46400085 0.15544632 -0.070490703, 0.46399954 0.15545259 -0.074490681, 0.46447811 0.15545256 -0.074432626, 0.4649289 0.15545255 -0.07426168, 0.46532586 0.15545259 -0.073987678, 0.4656454 0.15545256 -0.073626801, 0.46586946 0.15545256 -0.073200002, 0.46598491 0.15545252 -0.072731838, 0.46598491 0.15545255 -0.072249696, 0.46586946 0.1554525 -0.071781501, 0.46564546 0.15545243 -0.071354583, 0.4653258 0.15545249 -0.070993736, 0.4649289 0.15545242 -0.070719823, 0.46447816 0.1554524 -0.070548877, 0.46399942 0.1554524 -0.070490703, -0.19250074 0.15544793 -0.067490652, -0.38500085 0.15544677 -0.067490652, 0.16249946 0.15545146 -0.088990793, 0.18656994 0.15545347 -0.12221985, 0.18617317 0.1554535 -0.12249382, -0.40297952 0.15544988 -0.12593274, -0.4025009 0.15545 -0.12599082, -0.47530097 0.15544993 -0.13401867, 0.1858535 0.1554535 -0.12285475, 0.18562935 0.15545356 -0.12328158, 0.16014531 0.15545338 -0.12285475, -0.47530094 0.15543598 0.11479367, -0.47489747 0.15543589 0.11276542, -0.47519901 0.15543593 0.11375965, 0.16036935 0.15545335 -0.12328143, -0.47530094 0.15543477 0.13403709, -0.47374853 0.15543617 0.11104591, -0.47440764 0.15543608 0.1118492, -0.45667759 0.15543725 0.093974993, 0.18702075 0.15545353 -0.1220489, 0.18551396 0.15545356 -0.12374978, 0.16048481 0.15545338 -0.12374969, -0.39750072 0.15544975 -0.12199064, -0.40250084 0.15544972 -0.12199064, 0.18749943 0.15545353 -0.12199076, 0.19249938 0.15545045 -0.067490652, 0.18617326 0.15543965 0.12251236, 0.16249944 0.15544145 0.08900927, 0.15982568 0.15543953 0.12251236, 0.15217313 0.15543953 0.12251236, 0.15185341 0.1554395 0.12287329, 0.15256992 0.15543948 0.12223853, 0.15302074 0.15543954 0.12206759, 0.15349929 0.15543959 0.12200929, -0.4038271 0.15543574 0.12550639, -0.40414676 0.15543571 0.12514542, -0.39702222 0.15544979 -0.1220489, 0.0041452944 0.15543851 0.12287329, 0.18551399 0.15545364 -0.12423186, -0.40343028 0.1554357 0.12578018, 0.16048482 0.15545341 -0.12423186, 0.18657 0.15543966 0.12223853, 0.18702066 0.15543979 0.12206747, 0.18562932 0.15545364 -0.12470002, 0.1874994 0.1554397 0.12200929, -0.40437084 0.1554358 0.12471865, 0.003825549 0.15543857 0.12251221, 0.0034287162 0.15543857 0.12223841, 0.15849937 0.15543959 0.12200929, 0.15897804 0.15543951 0.12206747, 0.16036949 0.15545341 -0.12470002, 0.15942892 0.15543948 0.12223841, -0.40297952 0.15543564 0.12595113, 0.18585341 0.15545364 -0.12512679, -0.40448633 0.15543588 0.1242504, -0.39657143 0.15544972 -0.12221976, 0.16014536 0.15545347 -0.12512679, -0.40250084 0.15543573 0.12600945, -0.16250068 0.15544929 -0.088990793, -0.0041466504 0.15545233 -0.12285475, -0.15185478 0.15545128 -0.12285466, 0.18617316 0.1554537 -0.12548776, -0.40448624 0.15543593 0.12376823, -0.39617464 0.15544979 -0.12249382, 0.15982568 0.15545347 -0.12548776, -0.0038269572 0.15545233 -0.12249382, -0.40437099 0.15543593 0.12330009, -0.45609292 0.15543722 0.093262747, 0.18656993 0.15545371 -0.12576164, -0.0034301542 0.15545227 -0.12221985, 0.15942885 0.15545347 -0.12576179, -0.40414694 0.15543593 0.12287329, -0.39585492 0.15544979 -0.12285475, -0.45565858 0.15543726 0.092450127, -0.40382719 0.1554359 0.12251221, -0.4553912 0.15543726 0.091568574, -0.0043707155 0.15545227 -0.12328158, -0.15163073 0.1554514 -0.12328158, 0.18702072 0.15545371 -0.12593274, 0.15897802 0.15545352 -0.12593274, -0.39563081 0.15544975 -0.12328158, -0.40343037 0.15543598 0.12223853, -0.45530078 0.15543735 0.090651497, 0.18749933 0.15545376 -0.12599082, 0.15849939 0.15545355 -0.12599082, 0.19249943 0.15545355 -0.12199076, -0.39551541 0.15544981 -0.12374969, -0.0044861101 0.15545227 -0.12374978, -0.15151533 0.15545134 -0.12374978, -0.15151531 0.15545143 -0.12423186, -0.3975009 0.15545002 -0.12599082, 0.19297804 0.15545349 -0.1220489, -0.39750078 0.15543576 0.12600936, 0.19342881 0.15545356 -0.12221976, -0.0044860505 0.15545233 -0.12423186, 0.19382569 0.15545353 -0.12249382, -0.0043706894 0.15545239 -0.12470002, -0.1516307 0.15545143 -0.12470002, 0.19414538 0.15545356 -0.12285466, -0.0041466653 0.15545239 -0.12512679, -0.15185484 0.15545149 -0.12512694, -0.15217447 0.15545143 -0.12548779, -0.19250076 0.15544038 0.067509279, 0.38499939 0.15544415 0.067509279, 0.39749953 0.15544105 0.12200929, 0.39702085 0.15544109 0.12206759, -0.18750075 0.15543729 0.12200929, -0.0038268827 0.15545242 -0.12548776, 0.40249941 0.15544108 0.12200929, 0.40297815 0.15544108 0.12206747, 0.40342894 0.15544109 0.12223841, -0.0034301542 0.15545245 -0.12576179, -0.15257131 0.15545146 -0.1257617, -0.15302214 0.15545148 -0.12593265, -0.0029792935 0.15545246 -0.12593265, -0.16250077 0.15543939 0.08900927, 0.19436942 0.15545362 -0.12328158, -0.15982702 0.1554375 0.12251221, -0.18617442 0.15543723 0.12251236, -0.0025006197 0.15545252 -0.12599082, -0.15350078 0.15545155 -0.12599085, -0.18702205 0.15543728 0.12206747, -0.18657134 0.15543731 0.12223853, -0.15943022 0.15543753 0.12223841, -0.15897939 0.15543747 0.12206747, -0.15850067 0.15543744 0.12200929, -0.15350071 0.1554375 0.12200929, -0.15302207 0.15543748 0.12206747, -0.15257123 0.15543745 0.12223841, -0.1521745 0.15543753 0.12251236, -0.15185477 0.1554375 0.12287329, 0.19249947 0.15544277 0.06750907, -0.288827 0.15545049 -0.12249382, -0.38500068 0.15543909 0.067509279, -0.40297946 0.15543598 0.12206747, -0.40250084 0.15543589 0.12200929, -0.39750084 0.15543595 0.12200929, -0.39702222 0.15543599 0.12206729, -0.28914687 0.15545049 -0.12285466, -0.39657143 0.15543598 0.12223841, -0.28843024 0.15545043 -0.12221985, 0.28749949 0.15544009 0.12600936, 0.47529957 0.15544084 0.13403718, 0.39749959 0.15544078 0.12600936, -0.3961747 0.15543596 0.12251236, 0.40436944 0.15544115 0.12471856, 0.4044849 0.15544111 0.1242504, 0.40414539 0.15544097 0.12514542, 0.40382573 0.15544091 0.12550654, 0.40342894 0.15544094 0.12578033, 0.40297809 0.15544087 0.12595128, 0.40249947 0.15544088 0.12600945, -0.28937083 0.15545052 -0.12328158, -0.39585492 0.15543596 0.1228732, -0.28797945 0.15545043 -0.1220489, -0.39563081 0.15543592 0.12330009, -0.28948623 0.15545052 -0.1237496, 0.47519764 0.15544209 0.1137595, 0.47440627 0.15544233 0.11184905, 0.4752996 0.15544206 0.11479367, 0.4748961 0.15544204 0.11276551, 0.1924994 0.15543978 0.12200929, -0.39551559 0.15543599 0.12376823, 0.45667616 0.1554431 0.093975022, -0.2875008 0.15545048 -0.12199076, 0.40448484 0.15544115 0.12376823, 0.40436947 0.15544111 0.12330009, 0.19297804 0.15543979 0.12206747, 0.47374728 0.15544224 0.11104603, -0.28948623 0.1554506 -0.12423186, -0.39551544 0.15544993 -0.12423186, -0.39563081 0.15544988 -0.12470002, 0.45609161 0.15544313 0.093262747, 0.40414542 0.15544111 0.12287329, -0.28937078 0.15545058 -0.12470002, -0.39585477 0.15544993 -0.12512694, 0.19342881 0.15543973 0.12223853, 0.45565733 0.1554431 0.092450127, 0.40382573 0.15544102 0.12251236, 0.45538983 0.15544321 0.091568455, -0.28914687 0.15545064 -0.12512694, -0.28882709 0.15545061 -0.12548779, -0.39617452 0.15544987 -0.12548779, 0.45529947 0.15544333 0.090651259, 0.19382571 0.15543967 0.12251221, -0.28843027 0.15545061 -0.1257617, -0.39657143 0.1554499 -0.1257617, 0.28117314 0.15545417 -0.12249382, -0.28797942 0.15545058 -0.12593274, -0.39702228 0.15544993 -0.12593274, 0.19414532 0.15543978 0.12287329, -0.2875008 0.15545067 -0.12599082, 0.28085348 0.1554541 -0.12285466, 0.19436944 0.15543973 0.12330009, 0.28157002 0.15545413 -0.12221976, -0.39657137 0.15543571 0.12578018, -0.28882709 0.15543643 0.12550654, -0.39617452 0.15543571 0.12550654, 0.2806294 0.15545416 -0.12328158, 0.28202084 0.15545408 -0.12204881, -0.28914678 0.15543652 0.12514542, -0.39585486 0.15543577 0.12514542, 0.28051403 0.15545416 -0.12374969, 0.19448483 0.15545362 -0.12374978, -0.39702222 0.15543574 0.12595113, -0.28843021 0.15543643 0.12578018, 0.1944848 0.1554537 -0.12423186, -0.28937081 0.15543664 0.12471856, -0.39563081 0.1554359 0.12471856, 0.28249943 0.1554541 -0.12199076, 0.28051403 0.15545422 -0.12423186, 0.19436941 0.15545368 -0.12470002, -0.28797951 0.15543656 0.12595113, -0.28948629 0.15543656 0.12425052, -0.39551541 0.15543593 0.12425028, 0.2806294 0.15545423 -0.12470002, 0.19414541 0.15545364 -0.12512679, -0.2875008 0.15543643 0.12600936, 0.28085342 0.15545428 -0.12512679, -0.28948623 0.15543661 0.12376823, 0.28117317 0.15545431 -0.12548776, 0.19382565 0.15545368 -0.12548776, 0.28156999 0.15545425 -0.1257617, 0.19382572 0.15543948 0.12550639, 0.28117317 0.15544018 0.12550639, 0.1941454 0.1554395 0.12514542, 0.19342886 0.15545368 -0.12576179, 0.19342884 0.15543956 0.12578018, 0.28202087 0.15545423 -0.12593265, -0.28937081 0.15543664 0.12330009, 0.28085357 0.15544005 0.12514542, 0.19297804 0.15545374 -0.12593265, -0.28914675 0.15543664 0.12287329, 0.28249943 0.15545431 -0.12599082, 0.19436939 0.15543975 0.12471865, 0.19249938 0.1554538 -0.12599082, 0.19297802 0.1554396 0.12595128, 0.28157005 0.15544006 0.12578033, 0.28749949 0.15545411 -0.12199064, -0.288827 0.15543665 0.12251236, -0.2825008 0.15545049 -0.12199076, 0.28062937 0.15544026 0.12471856, 0.19448477 0.15543973 0.1242504, -0.28843027 0.15543662 0.12223853, 0.2820209 0.15544005 0.12595128, -0.28202218 0.15545046 -0.1220489, 0.28051403 0.15544027 0.1242504, -0.28797936 0.15543662 0.12206747, -0.28750074 0.15543664 0.12200908, 0.19448477 0.15543973 0.12376834, 0.1924994 0.15543948 0.12600936, 0.28249949 0.15544012 0.12600945, -0.28157133 0.15545052 -0.12221985, 0.28051397 0.1554403 0.12376823, -0.2811746 0.15545055 -0.12249382, 0.2806294 0.15544029 0.12330009, 0.28085342 0.15544033 0.12287329, -0.28085482 0.15545048 -0.12285466, 0.2811732 0.15544033 0.12251236, 0.28157005 0.15544035 0.12223841, -0.28063077 0.15545055 -0.12328143, 0.28202096 0.15544029 0.12206747, 0.28249946 0.15544033 0.12200929, 0.28797808 0.15545411 -0.1220489, 0.28842887 0.15545416 -0.12221985, 0.28749949 0.15544036 0.12200929, 0.28882572 0.15545416 -0.12249382, -0.47374851 0.15544857 -0.11102746, -0.47489753 0.15544865 -0.11274685, -0.47440764 0.1554486 -0.11183049, -0.47530094 0.15544879 -0.11477502, -0.47519895 0.15544875 -0.11374097, 0.28914541 0.15545414 -0.12285455, -0.45667741 0.15544771 -0.093956247, 0.0034287758 0.15545234 -0.12221985, 0.0038255602 0.15545234 -0.12249382, -0.0038269609 0.15543832 0.12550639, -0.0041466951 0.15543832 0.12514542, -0.1521745 0.15543734 0.12550639, 0.0041452795 0.15545234 -0.12285466, 0.28936946 0.15545416 -0.12328158, -0.15185478 0.15543735 0.12514542, -0.28157139 0.1554365 0.12578018, -0.19382694 0.15543702 0.12550639, -0.2811746 0.15543652 0.12550639, -0.003430143 0.15543833 0.12578033, -0.15257135 0.15543734 0.12578033, -0.15302214 0.15543732 0.12595113, -0.0043707006 0.15543844 0.12471856, 0.28948492 0.15545419 -0.12374978, -0.28085479 0.15543649 0.12514542, -0.19414674 0.15543708 0.12514542, -0.2806308 0.15543665 0.12471865, -0.15163074 0.15543745 0.12471856, -0.0029793084 0.15543827 0.12595128, -0.15350078 0.15543731 0.12600936, -0.19343023 0.15543698 0.12578033, -0.0044860654 0.15543844 0.1242504, -0.19437082 0.15543722 0.12471865, -0.28051525 0.15543658 0.1242504, -0.15151528 0.15543744 0.1242504, -0.15151535 0.15543747 0.12376823, 0.28882563 0.15544018 0.12550639, 0.3958534 0.15544087 0.12514542, 0.2891455 0.15544009 0.12514569, 0.39617327 0.15544087 0.12550654, 0.28842878 0.15544015 0.12578018, 0.39656994 0.15544088 0.12578033, -0.0025006197 0.15543827 0.12600936, -0.28202224 0.15543655 0.12595113, -0.19297937 0.15543705 0.12595128, -0.0044860505 0.15543841 0.12376834, 0.3956295 0.15544094 0.12471865, 0.28936952 0.1554403 0.12471856, -0.0043706857 0.15543844 0.12330009, -0.19448613 0.1554372 0.1242504, 0.28797808 0.15544018 0.12595113, 0.39702091 0.15544081 0.12595113, -0.28250083 0.1554365 0.12600936, -0.19250068 0.15543702 0.12600936, -0.15163067 0.15543751 0.12329994, -0.0041466765 0.1554385 0.1228732, 0.39551404 0.155441 0.12425052, -0.19448619 0.15543726 0.12376823, -0.28051537 0.15543665 0.12376808, 0.28948489 0.15544033 0.12425052, -0.0038269162 0.1554385 0.12251221, 0.3955141 0.15544094 0.12376834, -0.19437082 0.15543722 0.12330009, -0.28063074 0.15543664 0.12330009, 0.28948489 0.15544027 0.12376823, -0.0034301132 0.15543848 0.12223841, 0.38499948 0.1554518 -0.067490652, -0.45530096 0.15544772 -0.09063296, 0.39617327 0.15545481 -0.12249382, 0.39585355 0.15545486 -0.12285455, 0.39657 0.15545481 -0.12221985, 0.39562944 0.15545483 -0.12328158, 0.1521731 0.15545329 -0.12249382, 0.15185338 0.15545329 -0.12285475, 0.15256995 0.15545329 -0.12221985, 0.15162931 0.15545329 -0.12328158, 0.0043693818 0.15545231 -0.12328158, 0.39702085 0.15545486 -0.1220489, 0.39551416 0.15545481 -0.1237496, 0.15302067 0.15545331 -0.1220489, 0.15151396 0.15545332 -0.1237496, 0.0044847764 0.15545233 -0.12374969, 0.39749947 0.15545493 -0.12199076, 0.39551416 0.15545492 -0.12423186, 0.28948489 0.15545428 -0.12423186, -0.19382697 0.15545106 -0.12249382, 0.15349939 0.15545331 -0.12199076, 0.3956295 0.15545493 -0.12470002, 0.28936952 0.15545428 -0.12470002, 0.15151401 0.15545338 -0.12423186, 0.004484728 0.15545245 -0.12423186, -0.19414665 0.15545106 -0.12285475, 0.15162942 0.15545341 -0.12470002, 0.0043693483 0.15545243 -0.12470002, 0.39585349 0.15545504 -0.12512694, 0.28914544 0.15545428 -0.12512679, 0.0041452982 0.15545246 -0.12512679, -0.19343017 0.15545103 -0.12221985, 0.39617333 0.15545504 -0.12548776, 0.28882569 0.15545435 -0.12548776, -0.19437085 0.15545109 -0.12328143, 0.15185338 0.15545343 -0.12512694, 0.39657006 0.15545504 -0.12576179, 0.2884289 0.15545428 -0.1257617, 0.39702085 0.15545502 -0.12593259, 0.28797814 0.15545428 -0.12593265, 0.28749943 0.1554544 -0.12599082, -0.19297935 0.15545106 -0.1220489, 0.15217318 0.15545341 -0.12548779, 0.0038255788 0.15545243 -0.12548776, 0.39749959 0.15545502 -0.12599082, -0.19448619 0.15545115 -0.12374978, -0.28051546 0.15545052 -0.12374969, 0.40249947 0.15545487 -0.12199079, 0.40297809 0.15545487 -0.1220489, 0.15256995 0.15545349 -0.12576164, 0.0034288466 0.15545243 -0.1257617, 0.0029780008 0.15545246 -0.12593265, -0.19250081 0.15545109 -0.12199079, -0.19448622 0.15545116 -0.12423186, 0.40342894 0.15545492 -0.12221985, -0.28051537 0.15545064 -0.12423186, 0.15302074 0.15545349 -0.12593265, -0.19437078 0.15545121 -0.12470002, -0.28063077 0.15545055 -0.12470002, 0.15349942 0.15545352 -0.12599082, 0.0024993271 0.15545252 -0.12599082, -0.19414669 0.15545121 -0.12512679, -0.28085485 0.15545058 -0.12512679, -0.19382699 0.15545121 -0.12548779, -0.28117454 0.15545061 -0.12548776, -0.28157127 0.15545061 -0.12576179, -0.1934302 0.15545118 -0.12576179, -0.28202221 0.15545066 -0.12593265, -0.19297943 0.15545121 -0.12593274, -0.28250074 0.1554507 -0.12599082, -0.19250068 0.15545127 -0.12599082, -0.18750079 0.15545113 -0.12199076, -0.18702213 0.15545112 -0.1220489, 0.45529953 0.15545349 -0.09063296, -0.18657126 0.1554511 -0.12221985, -0.1861745 0.15545107 -0.12249382, 0.15849936 0.15545334 -0.12199079, 0.45538989 0.15545352 -0.091549799, 0.40382579 0.15545487 -0.12249382, 0.45565727 0.15545353 -0.092431441, 0.40414542 0.15545493 -0.12285455, 0.45609173 0.15545355 -0.09324412, 0.40436947 0.15545493 -0.12328158, 0.15897797 0.15545338 -0.1220489, 0.45667616 0.15545355 -0.093956336, 0.4044849 0.15545496 -0.12374978, 0.4044849 0.15545505 -0.12423186, -0.15982693 0.1554513 -0.12249382, -0.16014668 0.15545124 -0.12285466, -0.18585472 0.15545107 -0.12285466, -0.18563074 0.15545119 -0.12328158, -0.15943019 0.15545124 -0.12221985, 0.47440633 0.15545477 -0.11183049, 0.47519764 0.1554549 -0.11374108, 0.47374722 0.15545465 -0.11102732, 0.47489622 0.15545471 -0.11274676, 0.15942882 0.15545338 -0.12221985, -0.16037074 0.15545124 -0.12328158, -0.18551528 0.15545112 -0.12374978, -0.15897948 0.15545136 -0.1220489, 0.47529945 0.15545496 -0.11477502, 0.47529945 0.15545605 -0.13401867, 0.40249941 0.15545511 -0.12599082, -0.16048616 0.15545136 -0.12374969, 0.4043695 0.15545505 -0.12470002, 0.40414539 0.15545508 -0.12512694, 0.40382579 0.15545499 -0.12548776, -0.18551533 0.15545125 -0.12423186, 0.40342894 0.15545501 -0.12576179, 0.40297809 0.15545508 -0.12593274, 0.15982559 0.15545335 -0.12249382, -0.0025006495 0.15545225 -0.12199099, -0.28085485 0.15543665 0.12287329, -0.0029792935 0.15545228 -0.1220489, 0.0024993122 0.15545231 -0.12199076, -0.15850079 0.15545133 -0.12199076, 0.0029779263 0.15545231 -0.1220489, 0.002499301 0.15543857 0.12200929, 0.0029779226 0.15543854 0.12206747, -0.0025006942 0.15543851 0.12200929, -0.002979245 0.15543848 0.12206759, -0.16048627 0.15545151 -0.12423177, -0.1856308 0.15545128 -0.12470002, -0.16037078 0.15545139 -0.12470002, -0.18585481 0.15545125 -0.12512694, -0.2811746 0.15543672 0.12251236, -0.16014671 0.15545139 -0.12512679, -0.18617448 0.15545124 -0.12548779, -0.19414669 0.15543719 0.12287329, 0.0024993271 0.15543827 0.12600936, -0.15982696 0.15545148 -0.12548776, -0.1865714 0.15545131 -0.1257617, -0.1585007 0.15543726 0.12600945, -0.18750082 0.15543711 0.12600945, 0.15349936 0.15543933 0.12600936, 0.15849927 0.15543938 0.12600936, 0.18749942 0.15543948 0.12600945, -0.15943024 0.15545151 -0.1257617, -0.18702213 0.1554513 -0.12593274, -0.15897945 0.15545151 -0.12593274, -0.18750082 0.15545136 -0.12599082, -0.28157127 0.15543664 0.12223841, -0.15850067 0.15545149 -0.12599082, -0.19382705 0.15543732 0.12251221, -0.15350078 0.15545128 -0.12199076, -0.15302211 0.15545131 -0.12204881, -0.28202215 0.15543665 0.12206747, -0.15257131 0.15545131 -0.12221976, -0.19343022 0.15543725 0.12223841, -0.15217447 0.1554513 -0.12249382, -0.2825008 0.15543666 0.12200929, -0.19297935 0.15543723 0.12206747, -0.15982699 0.15543729 0.12550639, -0.16014674 0.15543729 0.12514542, -0.18617447 0.15543707 0.12550654, -0.18585473 0.15543702 0.12514542, -0.15943019 0.15543726 0.12578033, 0.0038255937 0.1554383 0.12550654, 0.15217316 0.15543923 0.12550654, 0.0041452833 0.15543836 0.12514542, -0.18657136 0.15543713 0.12578018, 0.0034288503 0.1554383 0.12578033, -0.18702219 0.15543713 0.12595128, -0.19250076 0.15543732 0.12200929, -0.16037081 0.15543744 0.12471865, 0.15185341 0.15543929 0.12514542, 0.0043693595 0.15543842 0.12471856, 0.15257001 0.15543924 0.12578018, -0.18563066 0.15543722 0.12471856, -0.15897945 0.15543729 0.12595128, 0.15162933 0.15543947 0.12471865, -0.16048613 0.15543744 0.1242504, 0.15302071 0.1554393 0.12595113, -0.18551531 0.15543725 0.1242504, 0.0029780157 0.1554383 0.12595113, 0.15151401 0.15543944 0.12425052, 0.0044847317 0.15543848 0.1242504, 0.0044847503 0.1554385 0.12376823, -0.16048618 0.15543744 0.12376834, -0.18551527 0.15543719 0.12376834, 0.28936955 0.1554403 0.12330009, 0.15151395 0.1554395 0.12376823, 0.15162939 0.15543944 0.12330009, 0.0043693483 0.15543851 0.12330009, 0.28914541 0.15544039 0.12287329, -0.16037074 0.15543741 0.12330009, -0.18563072 0.15543725 0.12330009, -0.16014668 0.15543741 0.12287329, -0.18585472 0.15543725 0.1228732, 0.28882578 0.1554403 0.12251236, 0.39562944 0.15544103 0.12330009, 0.28842887 0.15544041 0.12223841, 0.39585355 0.15544108 0.1228732, 0.28797811 0.15544036 0.12206747, -0.4553912 0.15544765 -0.091549888, -0.40382716 0.15544975 -0.12249382, -0.4556587 0.15544771 -0.09243156, 0.39617327 0.15544108 0.12251236, -0.40414691 0.15544972 -0.12285475, -0.45609292 0.15544777 -0.093243971, -0.40343031 0.15544975 -0.12221991, 0.39657006 0.15544111 0.12223853, -0.40437087 0.1554497 -0.12328158, 0.1598257 0.15543929 0.12550639, 0.18585341 0.15543945 0.12514542, 0.1601454 0.15543929 0.12514542, 0.18617316 0.15543945 0.12550639, 0.15942878 0.15543941 0.12578018, 0.18657002 0.15543947 0.12578018, -0.40297946 0.15544972 -0.1220489, 0.18562926 0.15543975 0.12471865, 0.16036946 0.15543947 0.12471865, -0.40448624 0.15544976 -0.12374978, 0.158978 0.15543941 0.12595128, 0.18702081 0.15543948 0.12595113, 0.18551393 0.15543969 0.12425052, 0.16048478 0.15543947 0.1242504, 0.18551396 0.15543967 0.12376823, 0.16048485 0.15543947 0.12376834, 0.18562937 0.15543967 0.12330009, -0.40448627 0.15544984 -0.12423186, 0.16036946 0.15543947 0.12330009, 0.18585336 0.15543973 0.1228732, -0.40437099 0.15544988 -0.12470002, 0.16014534 0.15543953 0.12287329, -0.40414679 0.15544985 -0.12512679, -0.40382704 0.15544979 -0.12548779, -0.40343031 0.15544984 -0.1257617, 0.21049935 0.15444267 0.070909247, 0.20987719 0.15444273 0.070984945, 0.2092911 0.15444273 0.071207151, 0.2087753 0.15444258 0.07156302, 0.20835976 0.15444264 0.072032407, 0.20806828 0.15444271 0.072587326, 0.20791832 0.15444268 0.073196009, 0.20791833 0.15444258 0.073822603, 0.20806831 0.15444252 0.074431255, 0.20835964 0.15444252 0.074986205, 0.20877522 0.15444246 0.075455502, 0.20929115 0.15444244 0.075811461, 0.20987716 0.15444247 0.076033667, 0.21049941 0.15444234 0.076109096, 0.21049944 0.15445104 -0.076090887, 0.20987722 0.15445098 -0.076015189, 0.20929109 0.15445103 -0.075793013, 0.20877531 0.15445101 -0.075436965, 0.20835966 0.15445095 -0.074967846, 0.20806834 0.15445095 -0.074412778, 0.20791838 0.15445082 -0.073804095, 0.20791838 0.15445082 -0.073177323, 0.2080684 0.1544508 -0.072568849, 0.2083597 0.15445079 -0.072013751, 0.20877531 0.15445074 -0.071544573, 0.20929115 0.15445074 -0.071188584, 0.20987718 0.15445074 -0.070966318, 0.21049941 0.15445068 -0.070890978, 0.36699948 0.15445203 -0.076090887, 0.3663772 0.1544521 -0.076015189, 0.36579117 0.15445204 -0.075792894, 0.36527535 0.15445203 -0.075436786, 0.36485973 0.15445197 -0.074967846, 0.36456838 0.15445189 -0.074412778, 0.36441836 0.15445195 -0.073804095, 0.36441836 0.15445195 -0.073177531, 0.36456844 0.15445168 -0.07256864, 0.36485973 0.15445177 -0.07201384, 0.36527541 0.15445167 -0.071544573, 0.36579117 0.15445174 -0.071188673, 0.3663772 0.15445185 -0.070966378, 0.36699942 0.15445177 -0.070890978, 0.36699948 0.15444368 0.070909247, 0.3663772 0.15444376 0.070984796, 0.36579123 0.1544437 0.071207002, 0.36527535 0.15444361 0.07156302, 0.36485967 0.15444368 0.072032407, 0.3645685 0.15444362 0.072587326, 0.36441842 0.15444355 0.0731958, 0.36441842 0.15444364 0.073822603, 0.3645685 0.15444343 0.074431255, 0.36485967 0.15444346 0.074986205, 0.36527535 0.15444344 0.075455502, 0.36579117 0.15444352 0.075811461, 0.36637715 0.1544435 0.076033667, 0.36699948 0.15444349 0.076109365, -0.21050081 0.15444002 0.070909247, -0.21112299 0.15443999 0.070984945, -0.21170911 0.15444002 0.071207002, -0.21222484 0.15443993 0.07156311, -0.21264052 0.15443993 0.072032198, -0.21293181 0.15443991 0.072587326, -0.21308185 0.15443999 0.0731958, -0.21308181 0.1544399 0.073822603, -0.21293192 0.15443985 0.074431255, -0.21264055 0.15443978 0.074986205, -0.21222487 0.15443972 0.075455502, -0.21170907 0.15443978 0.075811461, -0.21112302 0.15443979 0.076033667, -0.21050087 0.15443982 0.076109156, -0.21050084 0.15444842 -0.076090649, -0.21112296 0.1544483 -0.076015189, -0.21170922 0.15444839 -0.075793013, -0.21222493 0.1544483 -0.075436965, -0.21264058 0.1544482 -0.074967936, -0.21293178 0.15444824 -0.074412778, -0.21308187 0.15444818 -0.073804334, -0.21308181 0.15444818 -0.073177323, -0.21293172 0.15444803 -0.072568849, -0.21264052 0.15444799 -0.072013751, -0.2122249 0.15444803 -0.071544573, -0.21170905 0.15444799 -0.071188584, -0.21112293 0.15444799 -0.070966318, -0.21050081 0.15444811 -0.070890978, -0.36700097 0.15444741 -0.076090887, -0.36762309 0.15444738 -0.076015189, -0.36820915 0.15444733 -0.075792745, -0.36872497 0.15444726 -0.075436965, -0.36914077 0.15444732 -0.074967727, -0.36943194 0.15444717 -0.074412778, -0.36958197 0.15444723 -0.073804334, -0.36958197 0.15444723 -0.073177323, -0.36943185 0.15444706 -0.072568849, -0.36914062 0.15444712 -0.072013751, -0.36872503 0.15444712 -0.071544573, -0.36820915 0.15444711 -0.071188584, -0.36762318 0.15444717 -0.070966318, -0.36700085 0.154447 -0.070890978, -0.36700085 0.154439 0.070909247, -0.36762306 0.15443899 0.070984945, -0.36820915 0.15443897 0.071207002, -0.36872494 0.15443897 0.07156302, -0.36914062 0.15443902 0.072032556, -0.36943188 0.15443897 0.072587326, -0.36958191 0.15443894 0.0731958, -0.36958194 0.15443893 0.073822603, -0.369432 0.15443888 0.074431255, -0.36914068 0.15443878 0.074986205, -0.36872503 0.15443878 0.075455353, -0.36820915 0.15443876 0.075811461, -0.36762309 0.15443881 0.076033667, -0.36700085 0.15443882 0.076109156, -0.36527261 0.15443878 0.074702129, -0.36456993 0.1544389 0.074431255, -0.36503732 0.15443878 0.074253872, -0.36486113 0.15443878 0.074986205, -0.36797675 0.15443897 0.071649775, -0.36750343 0.15443903 0.071470484, -0.36839348 0.15443878 0.075081155, -0.36700085 0.154439 0.071409449, -0.3687292 0.15443881 0.074702129, -0.36441979 0.15443896 0.073822603, -0.36491618 0.15443891 0.073762521, -0.36797678 0.15443881 0.075368837, -0.3689644 0.15443879 0.074253872, -0.36750343 0.15443873 0.075548276, -0.36908555 0.15443896 0.073762521, -0.36441991 0.15443905 0.073196009, -0.36491618 0.15443891 0.07325609, -0.36503735 0.15443894 0.072764829, -0.36700085 0.15443878 0.075609371, -0.36637864 0.15443876 0.076033667, -0.36908555 0.15443896 0.07325609, -0.3664982 0.154439 0.071470484, -0.36637864 0.15443903 0.070984796, -0.36649832 0.15443876 0.075548276, -0.36456993 0.15443899 0.072587326, -0.36527261 0.15443899 0.072316274, -0.3689644 0.15443891 0.07276459, -0.366025 0.15443906 0.071649775, -0.36579254 0.154439 0.071207002, -0.36486113 0.15443899 0.072032407, -0.3656083 0.154439 0.071937397, -0.36579254 0.15443879 0.075811461, -0.36527666 0.15443894 0.07156311, -0.366025 0.15443884 0.075368837, -0.3687292 0.15443906 0.072316274, -0.36527666 0.15443873 0.075455502, -0.36560825 0.15443876 0.075081065, -0.36839351 0.15443902 0.071937397, -0.36700097 0.15343881 0.075609162, -0.36750346 0.15343884 0.075548127, -0.36797675 0.15343876 0.075368598, -0.36839345 0.15343882 0.075081065, -0.3687292 0.15343884 0.07470198, -0.3689644 0.15343882 0.074253783, -0.36908552 0.15343896 0.073762521, -0.36908552 0.15343896 0.07325609, -0.36896443 0.15343897 0.072764799, -0.36872914 0.15343902 0.072316274, -0.36839345 0.15343902 0.071937308, -0.36797675 0.15343903 0.071649775, -0.36750335 0.153439 0.071470127, -0.36700085 0.15343897 0.071409211, -0.20806977 0.15444003 0.072587326, -0.20877251 0.15443997 0.072316274, -0.20853725 0.15443996 0.07276459, -0.20836107 0.15444005 0.072032407, -0.21189326 0.15443993 0.071937397, -0.21100333 0.15443978 0.075548276, -0.21147671 0.15443979 0.075368837, -0.21222906 0.15443996 0.072316274, -0.21050075 0.15443979 0.075609371, -0.2079197 0.15443993 0.0731958, -0.20841606 0.15443994 0.07325609, -0.21147668 0.15443999 0.071649775, -0.21246421 0.15443987 0.072764829, -0.21100336 0.15444002 0.071470484, -0.20999825 0.15443976 0.075548276, -0.21258542 0.1544399 0.07325609, -0.21050084 0.15444008 0.0714093, -0.2079197 0.15443997 0.073822603, -0.20841607 0.15443994 0.073762521, -0.21258542 0.1544399 0.073762521, -0.20999824 0.15444002 0.071470335, -0.20987859 0.15444002 0.070984945, -0.20987858 0.15443976 0.076033667, -0.20952488 0.15443982 0.075368837, -0.21246432 0.15443976 0.074254021, -0.20806985 0.15443985 0.074431285, -0.2085373 0.15443984 0.074253872, -0.2092925 0.15443997 0.071207002, -0.20929252 0.15443976 0.075811461, -0.2091082 0.15443973 0.075081155, -0.20836106 0.15443981 0.074986354, -0.20877257 0.15443979 0.074702129, -0.2095249 0.15444008 0.071649775, -0.20877662 0.15443973 0.075455502, -0.21222901 0.15443975 0.074702129, -0.20877668 0.15444009 0.07156302, -0.20910831 0.15444003 0.071937397, -0.21189329 0.15443978 0.075081155, -0.21050078 0.15343983 0.075609371, -0.21100333 0.15343979 0.075548276, -0.21147656 0.15343972 0.075368837, -0.21189328 0.1534398 0.075081155, -0.21222906 0.1534398 0.074702129, -0.21246427 0.15343976 0.074253783, -0.21258539 0.15343994 0.073762521, -0.21258539 0.15343994 0.07325609, -0.21246432 0.15343997 0.072764799, -0.21222901 0.15344 0.072316125, -0.21189335 0.15344003 0.071937397, -0.21147668 0.15344 0.071649626, -0.21100333 0.15343997 0.071470335, -0.21050072 0.15343995 0.0714093, -0.20836107 0.15444812 -0.072013751, -0.20806971 0.15444808 -0.072568849, -0.20877251 0.15444814 -0.072298005, -0.20853721 0.15444809 -0.072746173, -0.21147671 0.15444832 -0.075350121, -0.21100336 0.15444835 -0.075529709, -0.21189329 0.15444799 -0.071918949, -0.21222904 0.15444806 -0.072297797, -0.21050088 0.15444838 -0.075590745, -0.20791969 0.15444814 -0.073177323, -0.20841609 0.15444817 -0.073237643, -0.21147662 0.15444803 -0.071631297, -0.21246427 0.15444812 -0.072746113, -0.21100341 0.15444815 -0.071451768, -0.21258549 0.15444818 -0.073237702, -0.21050081 0.15444811 -0.071390823, -0.20987859 0.15444808 -0.070966318, -0.21258548 0.15444824 -0.073743954, -0.20791973 0.15444823 -0.073804095, -0.20841609 0.15444817 -0.073743895, -0.20853725 0.15444821 -0.074235514, -0.20999829 0.15444814 -0.071451679, -0.21246436 0.15444829 -0.074235514, -0.20999822 0.15444832 -0.075529709, -0.20987858 0.15444835 -0.076015189, -0.2092925 0.15444808 -0.071188584, -0.20806979 0.1544482 -0.074412778, -0.20877251 0.1544482 -0.0746838, -0.20952484 0.1544483 -0.075350121, -0.2092925 0.15444832 -0.075793013, -0.2095249 0.15444814 -0.071631417, -0.20836104 0.15444827 -0.074967667, -0.20910829 0.15444827 -0.075062588, -0.21222901 0.15444817 -0.0746838, -0.20877668 0.15444832 -0.075436786, -0.20877676 0.15444811 -0.071544573, -0.20910828 0.15444814 -0.071919009, -0.21189326 0.15444815 -0.075062588, -0.21050084 0.1534481 -0.071390823, -0.21100336 0.15344812 -0.071451858, -0.21147671 0.15344809 -0.071631417, -0.21189332 0.1534481 -0.071919009, -0.2122291 0.15344819 -0.072298005, -0.2124643 0.15344813 -0.072746173, -0.21258548 0.15344819 -0.073237702, -0.21258548 0.15344822 -0.073743954, -0.21246436 0.15344825 -0.074235514, -0.21222907 0.15344822 -0.0746838, -0.21189333 0.15344822 -0.075062588, -0.21147671 0.15344833 -0.07535027, -0.21100333 0.15344831 -0.075529799, -0.21050072 0.1534483 -0.075590745, -0.36456978 0.15444721 -0.074412778, -0.36527264 0.15444724 -0.074683592, -0.36503738 0.15444729 -0.074235514, -0.3648611 0.1544473 -0.074967727, -0.36839345 0.15444729 -0.075062528, -0.3687292 0.15444718 -0.074683592, -0.36750349 0.15444712 -0.071451679, -0.36797678 0.15444703 -0.071631417, -0.36797681 0.15444724 -0.075350121, -0.36441991 0.1544473 -0.073804095, -0.36491618 0.15444717 -0.073743895, -0.36896434 0.1544472 -0.074235514, -0.36750349 0.15444741 -0.075529799, -0.36649826 0.15444711 -0.071451679, -0.36700085 0.15444703 -0.071390733, -0.36908558 0.15444717 -0.073743954, -0.36700097 0.15444741 -0.075590745, -0.36441985 0.15444717 -0.073177531, -0.36491618 0.15444717 -0.073237643, -0.36637864 0.15444733 -0.076015189, -0.36908552 0.15444715 -0.073237643, -0.36649832 0.15444738 -0.075529799, -0.36896443 0.15444714 -0.072746173, -0.36637864 0.15444703 -0.070966318, -0.36602491 0.15444714 -0.071631417, -0.36579254 0.15444738 -0.075793013, -0.36456981 0.15444712 -0.072568849, -0.36503738 0.15444717 -0.072745904, -0.36579248 0.15444696 -0.071188524, -0.3656083 0.15444712 -0.071918949, -0.366025 0.15444741 -0.075350121, -0.36486104 0.15444697 -0.07201384, -0.36527249 0.15444708 -0.072298005, -0.36527678 0.15444717 -0.071544543, -0.36872911 0.15444709 -0.072298005, -0.36527678 0.15444735 -0.075436786, -0.36560842 0.1544473 -0.075062737, -0.36839348 0.15444712 -0.071918949, -0.36700085 0.15344712 -0.071390823, -0.3675034 0.15344712 -0.071451917, -0.36797675 0.15344706 -0.071631297, -0.36839336 0.15344714 -0.071918949, -0.3687292 0.15344718 -0.072298005, -0.3689644 0.15344712 -0.072746113, -0.36908558 0.15344715 -0.073237702, -0.36908555 0.15344717 -0.073744044, -0.36896434 0.1534472 -0.074235514, -0.3687292 0.1534472 -0.0746838, -0.36839339 0.15344726 -0.075062588, -0.36797675 0.15344732 -0.07535027, -0.36750343 0.15344727 -0.075529918, -0.36700085 0.15344734 -0.075590834, 0.36762163 0.15444355 0.076033667, 0.36820766 0.15444356 0.075811461, 0.3687236 0.15444347 0.075455502, 0.36913922 0.15444355 0.074986205, 0.36943045 0.15444359 0.074431255, 0.36958048 0.15444368 0.073822603, 0.36958054 0.15444362 0.0731958, 0.36943051 0.15444368 0.072587326, 0.36913916 0.15444377 0.072032198, 0.3687236 0.15444371 0.07156302, 0.36820772 0.15444371 0.071207002, 0.36762169 0.1544437 0.070984945, 0.36762169 0.15445179 -0.070966318, 0.36820772 0.15445185 -0.071188584, 0.3687236 0.15445182 -0.071544573, 0.36913916 0.15445186 -0.072013751, 0.36943051 0.15445185 -0.072568849, 0.36958048 0.15445192 -0.073177531, 0.36958048 0.15445191 -0.073804334, 0.36943063 0.15445192 -0.074412778, 0.36913922 0.15445197 -0.074967846, 0.36872375 0.15445206 -0.075436965, 0.36820772 0.15445206 -0.075792894, 0.36762157 0.15445212 -0.076015189, 0.21112166 0.15445077 -0.070966318, 0.21170767 0.15445083 -0.071188584, 0.21222344 0.15445083 -0.071544573, 0.2126392 0.15445077 -0.072013751, 0.21293052 0.15445077 -0.072568849, 0.21308045 0.15445089 -0.073177323, 0.21308045 0.15445089 -0.073804334, 0.21293052 0.15445089 -0.074412778, 0.21263915 0.15445098 -0.074967846, 0.2122235 0.154451 -0.075436965, 0.21170767 0.15445101 -0.075793013, 0.21112165 0.15445104 -0.076015189, 0.21112163 0.15444246 0.076033667, 0.21170773 0.15444246 0.075811461, 0.21222349 0.15444249 0.075455502, 0.21263909 0.15444249 0.074986205, 0.21293056 0.15444246 0.074431255, 0.21308053 0.15444264 0.073822811, 0.21308054 0.15444258 0.0731958, 0.21293041 0.15444273 0.072587326, 0.21263909 0.15444271 0.072032407, 0.21222341 0.15444273 0.07156302, 0.21170765 0.15444271 0.071207002, 0.21112153 0.15444277 0.070984945, 0.39749947 0.15445492 -0.12199079, 0.40249941 0.15445493 -0.12199099, 0.39749953 0.15445502 -0.12599082, 0.39702085 0.15445495 -0.12593265, 0.39657018 0.15445495 -0.1257617, 0.39617333 0.1544549 -0.12548779, 0.39585343 0.15445505 -0.12512694, 0.39562955 0.1544549 -0.12470002, 0.3955141 0.15445487 -0.12423186, 0.39551404 0.15445484 -0.12374969, 0.39562955 0.15445478 -0.12328158, 0.39585343 0.15445484 -0.12285475, 0.39617327 0.1544548 -0.12249382, 0.39657012 0.15445484 -0.12221985, 0.39702085 0.15445471 -0.12204881, 0.40249953 0.15445511 -0.12599082, 0.40297815 0.15445483 -0.1220489, 0.40342894 0.15445481 -0.12221985, 0.40382573 0.15445483 -0.12249382, 0.40414545 0.15445495 -0.12285475, 0.4043695 0.15445495 -0.12328158, 0.40448484 0.15445495 -0.12374978, 0.40448478 0.15445504 -0.12423192, 0.40436944 0.15445507 -0.12470002, 0.40414539 0.15445507 -0.12512694, 0.40382573 0.15445499 -0.12548776, 0.40342894 0.15445501 -0.12576179, 0.40297809 0.15445507 -0.12593274, 0.28749946 0.15445413 -0.12199079, 0.28249946 0.15445405 -0.12199079, 0.28249943 0.15445429 -0.12599082, 0.28202084 0.15445425 -0.12593274, 0.28156999 0.15445425 -0.12576179, 0.28117317 0.15445423 -0.12548776, 0.28085348 0.1544542 -0.12512679, 0.28062937 0.15445428 -0.12470002, 0.28051409 0.15445414 -0.12423186, 0.28051403 0.15445408 -0.12374978, 0.28062943 0.15445414 -0.12328158, 0.28085342 0.15445411 -0.12285475, 0.28117323 0.15445407 -0.12249382, 0.28157005 0.15445407 -0.12221985, 0.2820209 0.15445407 -0.1220489, 0.28749946 0.15445434 -0.12599082, 0.28797808 0.15445414 -0.1220489, 0.2884289 0.15445413 -0.12221985, 0.28882572 0.15445405 -0.12249382, 0.28914541 0.15445408 -0.12285466, 0.28936946 0.15445408 -0.12328158, 0.28948483 0.1544542 -0.12374969, 0.28948486 0.15445432 -0.12423186, 0.28936955 0.1544542 -0.12470002, 0.28914541 0.15445422 -0.12512694, 0.28882572 0.15445429 -0.12548776, 0.28842881 0.15445434 -0.1257617, 0.28797808 0.15445432 -0.12593265, 0.18749936 0.15445347 -0.12199076, 0.19249937 0.15445353 -0.12199079, 0.18749943 0.15445371 -0.12599082, 0.18702072 0.15445364 -0.12593274, 0.18656993 0.15445364 -0.1257617, 0.18617314 0.15445364 -0.12548779, 0.18585347 0.15445361 -0.12512694, 0.18562937 0.15445362 -0.12470002, 0.18551397 0.15445364 -0.12423186, 0.18551397 0.15445353 -0.12374969, 0.18562928 0.15445353 -0.12328158, 0.18585348 0.15445347 -0.12285475, 0.18617313 0.15445347 -0.12249382, 0.18656996 0.15445347 -0.12221985, 0.18702067 0.15445353 -0.1220489, 0.19249937 0.15445374 -0.12599082, 0.19297804 0.1544535 -0.1220489, 0.19342889 0.15445352 -0.12221985, 0.19382565 0.15445352 -0.12249382, 0.19414543 0.15445352 -0.12285475, 0.19436941 0.15445352 -0.12328158, 0.19448479 0.15445358 -0.12374978, 0.19448486 0.15445362 -0.12423186, 0.19436939 0.15445369 -0.12470002, 0.19414535 0.15445367 -0.12512679, 0.19382572 0.15445362 -0.12548779, 0.19342884 0.15445369 -0.1257617, 0.19297807 0.15445364 -0.12593274, 0.15349936 0.15445326 -0.12199079, 0.15849939 0.15445332 -0.12199079, 0.15349935 0.15445353 -0.12599082, 0.15302067 0.15445347 -0.12593265, 0.15256993 0.15445343 -0.12576179, 0.15217313 0.15445346 -0.12548776, 0.15185346 0.15445337 -0.12512679, 0.15162939 0.15445334 -0.12470002, 0.15151401 0.15445337 -0.12423186, 0.15151396 0.15445325 -0.12374969, 0.15162939 0.15445325 -0.12328158, 0.15185338 0.15445331 -0.12285475, 0.15217313 0.15445325 -0.12249382, 0.15256992 0.15445326 -0.12221985, 0.1530208 0.15445325 -0.1220489, 0.15849937 0.15445353 -0.12599082, 0.15897802 0.15445325 -0.12204896, 0.15942878 0.15445329 -0.12221985, 0.15982565 0.15445331 -0.12249382, 0.16014536 0.15445331 -0.12285475, 0.16036946 0.15445331 -0.12328158, 0.16048481 0.15445337 -0.12374978, 0.16048484 0.15445343 -0.12423186, 0.16036941 0.15445346 -0.12470002, 0.16014539 0.15445343 -0.12512679, 0.15982558 0.15445349 -0.12548776, 0.15942882 0.15445346 -0.12576179, 0.15897803 0.15445349 -0.12593274, -0.15850079 0.15445149 -0.12599082, -0.15350077 0.15445153 -0.12599082, -0.15350071 0.15445122 -0.12199079, -0.15302211 0.1544513 -0.12204881, -0.15257122 0.15445128 -0.12221985, -0.15217456 0.15445136 -0.12249382, -0.1518549 0.15445146 -0.12285475, -0.15163079 0.15445137 -0.12328158, -0.15151539 0.15445139 -0.12374978, -0.15151533 0.15445144 -0.12423186, -0.15163073 0.15445144 -0.12470011, -0.15185484 0.15445147 -0.12512694, -0.15217456 0.1544515 -0.12548779, -0.15257135 0.15445149 -0.12576179, -0.15302214 0.15445146 -0.12593265, -0.15850082 0.15445128 -0.12199079, -0.15897945 0.15445146 -0.12593274, -0.15943018 0.1544514 -0.12576179, -0.15982699 0.15445141 -0.12548779, -0.1601468 0.15445141 -0.12512679, -0.1603708 0.15445143 -0.12470002, -0.16048622 0.1544514 -0.12423192, -0.16048619 0.15445127 -0.12374978, -0.16037083 0.15445128 -0.12328179, -0.1601468 0.15445131 -0.12285475, -0.15982708 0.15445131 -0.12249382, -0.15943024 0.15445128 -0.12221985, -0.15897945 0.15445131 -0.1220489, -0.19250073 0.15445125 -0.12599082, -0.18750086 0.15445137 -0.12599082, -0.1875008 0.15445107 -0.12199064, -0.18702212 0.15445107 -0.1220489, -0.18657134 0.15445106 -0.12221985, -0.18617445 0.15445104 -0.12249382, -0.18585481 0.15445116 -0.12285475, -0.18563074 0.15445118 -0.12328158, -0.18551537 0.15445119 -0.12374978, -0.18551533 0.15445121 -0.12423192, -0.18563072 0.15445113 -0.12470002, -0.18585478 0.15445121 -0.12512694, -0.18617457 0.15445128 -0.12548779, -0.18657134 0.15445124 -0.12576179, -0.18702209 0.15445127 -0.12593274, -0.19250076 0.15445104 -0.12199076, -0.19297937 0.15445119 -0.12593274, -0.19343022 0.15445115 -0.12576179, -0.19382702 0.15445115 -0.12548779, -0.19414672 0.15445119 -0.12512679, -0.19437084 0.15445119 -0.12470011, -0.19448617 0.15445116 -0.12423186, -0.1944862 0.15445112 -0.12374978, -0.19437091 0.15445116 -0.12328158, -0.19414678 0.1544511 -0.12285475, -0.19382705 0.15445112 -0.12249385, -0.19343027 0.15445109 -0.12221985, -0.19297947 0.1544511 -0.1220489, -0.2825008 0.15445074 -0.12599082, -0.28750086 0.15445067 -0.12599082, -0.28250083 0.15445043 -0.12199079, -0.28202221 0.15445042 -0.1220489, -0.28157133 0.15445045 -0.12221985, -0.2811746 0.15445054 -0.12249382, -0.28085485 0.15445049 -0.12285466, -0.2806308 0.15445055 -0.12328158, -0.2805154 0.15445049 -0.12374969, -0.28051549 0.15445065 -0.12423186, -0.28063077 0.15445067 -0.12470002, -0.28085494 0.15445065 -0.12512694, -0.2811746 0.15445065 -0.12548779, -0.28157139 0.15445065 -0.12576179, -0.28202221 0.15445068 -0.12593274, -0.2875008 0.15445045 -0.12199076, -0.28797942 0.15445067 -0.12593265, -0.2884303 0.15445061 -0.12576179, -0.28882712 0.15445065 -0.12548779, -0.28914684 0.15445057 -0.12512694, -0.28937095 0.15445063 -0.12470002, -0.28948617 0.15445051 -0.12423186, -0.28948626 0.15445049 -0.12374969, -0.28937078 0.15445036 -0.12328158, -0.28914678 0.15445045 -0.12285466, -0.28882706 0.15445045 -0.12249382, -0.28843021 0.15445045 -0.12221985, -0.28797948 0.15445045 -0.12204881, -0.39750084 0.15444997 -0.12599082, -0.40250096 0.15444998 -0.12599082, -0.39750084 0.1544497 -0.12199076, -0.39702234 0.15444978 -0.1220489, -0.39657143 0.1544497 -0.12221991, -0.3961747 0.15444979 -0.12249382, -0.39585492 0.15444976 -0.12285466, -0.39563081 0.15444973 -0.12328158, -0.3955155 0.15444975 -0.12374978, -0.39551541 0.15444979 -0.12423186, -0.39563093 0.15444991 -0.12470002, -0.39585498 0.15444987 -0.12512679, -0.3961747 0.15444987 -0.12548779, -0.39657137 0.15444988 -0.12576179, -0.39702219 0.1544499 -0.12593274, -0.40250087 0.15444979 -0.12199076, -0.40297943 0.15444984 -0.12593265, -0.40343037 0.15444992 -0.12576179, -0.40382722 0.15444982 -0.12548779, -0.40414691 0.15444984 -0.12512679, -0.40437105 0.15444987 -0.12470002, -0.40448645 0.1544499 -0.12423186, -0.40448639 0.15444973 -0.12374978, -0.40437105 0.15444978 -0.12328158, -0.40414688 0.15444969 -0.12285475, -0.40382719 0.15444975 -0.12249385, -0.40343046 0.15444979 -0.12221985, -0.40297946 0.15444967 -0.1220489, 0.0024993196 0.1544525 -0.12599082, -0.0025007389 0.15445253 -0.12599082, 0.0024992786 0.15445232 -0.12199079, 0.0029778555 0.15445235 -0.1220489, 0.003428746 0.15445229 -0.12221985, 0.0038255267 0.15445235 -0.12249382, 0.0041452423 0.15445237 -0.12285475, 0.0043694302 0.15445232 -0.12328158, 0.0044847019 0.1544524 -0.12374978, 0.0044847801 0.15445238 -0.12423186, 0.004369311 0.1544525 -0.12470002, 0.004145287 0.15445244 -0.12512679, 0.0038255379 0.1544525 -0.12548776, 0.0034287646 0.15445244 -0.1257617, 0.00297793 0.15445244 -0.12593274, -0.0025006309 0.1544522 -0.12199079, -0.0029792264 0.15445241 -0.12593274, -0.0034300759 0.15445241 -0.12576179, -0.0038269721 0.15445243 -0.12548779, -0.0041466877 0.15445246 -0.12512679, -0.0043706819 0.15445231 -0.12470002, -0.0044860803 0.15445234 -0.12423192, -0.004486043 0.15445222 -0.12374978, -0.0043707415 0.15445231 -0.12328158, -0.0041467063 0.15445234 -0.12285475, -0.003826987 0.15445234 -0.12249382, -0.0034301393 0.15445225 -0.12221985, -0.0029793009 0.15445229 -0.1220489, 0.48199952 0.15545601 -0.13401867, 0.48999944 0.15545611 -0.13401867, 0.48199955 0.15443227 -0.13432659, 0.48199949 0.15542033 -0.13448055, 0.48199943 0.15436134 -0.13462706, 0.48199955 0.15531388 -0.13493119, 0.48199955 0.1551394 -0.13536038, 0.48199961 0.1542449 -0.1349131, 0.48199949 0.15402143 -0.13536038, 0.48999956 0.15513934 -0.13536038, 0.48999956 0.1540214 -0.13536038, -0.49000081 0.15544978 -0.13401867, -0.4820008 0.15544988 -0.13401867, -0.48200089 0.1551332 -0.13536038, -0.48200077 0.15423873 -0.1349131, -0.48200086 0.15530774 -0.13493119, -0.48200086 0.15401533 -0.13536038, -0.48200086 0.15435518 -0.13462706, -0.4820008 0.15541412 -0.13448055, -0.48200086 0.15442611 -0.13432659, -0.49000087 0.1540152 -0.13536038, -0.49000087 0.15513314 -0.13536038, -0.49000087 0.15544839 -0.10731922, -0.48999599 0.15544839 -0.10706244, -0.48996392 0.15544827 -0.10679658, -0.48988673 0.15544832 -0.10653804, -0.48975858 0.15544829 -0.10630049, -0.4894152 0.1554482 -0.10590513, -0.49000087 0.15544839 -0.10824071, -0.48995018 0.15544833 -0.10899486, -0.48984763 0.15544841 -0.10935532, -0.4897252 0.15544853 -0.10959665, -0.48954412 0.15544847 -0.10981844, -0.4893069 0.15544838 -0.10999529, -0.48902592 0.15544847 -0.11012028, -0.48851767 0.15544847 -0.11022328, -0.48800096 0.15544853 -0.11024071, -0.49000087 0.15544875 -0.11474077, -0.48998341 0.15544876 -0.11422415, -0.48988038 0.15544862 -0.11371575, -0.48975524 0.15544868 -0.11343475, -0.48957863 0.15544857 -0.11319743, -0.48935688 0.15544862 -0.1130165, -0.48911551 0.15544859 -0.1128941, -0.48875484 0.15544859 -0.11279164, -0.4880009 0.15544863 -0.11274074, -0.47000083 0.15544459 -0.039740637, -0.46998331 0.15544461 -0.039223984, -0.46988043 0.15544458 -0.038715735, -0.46975532 0.15544452 -0.03843458, -0.46957865 0.15544453 -0.038197443, -0.46935675 0.15544453 -0.038016483, -0.46911553 0.15544455 -0.037893876, -0.46875504 0.15544459 -0.037791416, -0.46800092 0.1554445 -0.037740603, -0.46800086 0.15544437 -0.035240665, -0.46851751 0.15544435 -0.035223261, -0.46902594 0.15544435 -0.035120353, -0.46930698 0.15544441 -0.034995332, -0.46954423 0.15544435 -0.034818515, -0.46972513 0.15544435 -0.034596816, -0.46984741 0.15544422 -0.034355387, -0.46995023 0.15544435 -0.033994779, -0.4700008 0.15544425 -0.033240721, 0.4879995 0.15545493 -0.11274074, 0.48851612 0.15545484 -0.11275826, 0.48902449 0.15545492 -0.11286126, 0.48930568 0.15545495 -0.11298619, 0.48954275 0.1554549 -0.11316307, 0.48972377 0.1554549 -0.11338468, 0.48984626 0.15545501 -0.11362617, 0.48994878 0.15545493 -0.11398678, 0.48999959 0.15545499 -0.11474074, 0.48799947 0.15545478 -0.11024071, 0.48875365 0.15545471 -0.11019002, 0.4891142 0.15545473 -0.1100875, 0.48935547 0.15545473 -0.10996519, 0.48957726 0.15545468 -0.10978402, 0.48975405 0.15545473 -0.109547, 0.4898791 0.15545474 -0.10926579, 0.48998198 0.15545473 -0.10875739, 0.48999962 0.15545464 -0.10824071, 0.48999962 0.15545464 -0.10731922, 0.48996255 0.15545462 -0.10679658, 0.48988542 0.1554545 -0.10653804, 0.48975721 0.15545443 -0.10630034, 0.48959172 0.15545452 -0.10609005, 0.48941389 0.15545458 -0.10590492, 0.46799949 0.15545061 -0.037740722, 0.46851626 0.15545057 -0.037758276, 0.46902451 0.15545051 -0.037861034, 0.46930555 0.15545054 -0.037986204, 0.46954277 0.15545063 -0.038163081, 0.46972373 0.15545054 -0.03838481, 0.46984628 0.15545055 -0.038626119, 0.46994886 0.15545055 -0.038986608, 0.46999952 0.15545063 -0.039740726, 0.46999949 0.15545036 -0.033240691, 0.469982 0.15545039 -0.033757433, 0.46987906 0.15545034 -0.034265772, 0.46975401 0.15545036 -0.034546837, 0.46957722 0.15545042 -0.034784093, 0.46935549 0.15545042 -0.034965023, 0.46911421 0.15545037 -0.035087481, 0.46875355 0.15545049 -0.03519012, 0.46799949 0.15545043 -0.035240784, -0.13590688 0.11853452 -0.20633589, 0.12450392 0.11609472 -0.21121977, 0.13590601 0.11853629 -0.20633592, -0.13685568 0.11873459 -0.2059357, 0.12412043 0.10914758 -0.225116, 0.12529826 0.10833658 -0.22673802, 0.1253489 0.10851301 -0.22638552, 0.12517004 0.10813574 -0.22713988, -0.096336007 0.081611335 -0.28019321, -0.097111359 0.07799077 -0.28743559, -0.096214831 0.081391573 -0.28063303, 0.13685483 0.11873636 -0.20593582, 0.12456623 0.1090862 -0.22523861, 0.48980126 0.13894673 -0.16551377, 0.48946723 0.13876285 -0.16588177, 0.48967114 0.13885452 -0.16569839, -0.1378769 0.11884171 -0.20572151, 0.4891766 0.13868341 -0.16604041, 0.13787605 0.1188435 -0.20572151, 0.48992711 0.13910139 -0.16520463, 0.48871973 0.13861634 -0.16617475, 0.4899852 0.13926265 -0.16488229, 0.12659758 0.11032705 -0.22275682, 0.12736921 0.11056011 -0.2222905, 0.12753709 0.11068186 -0.22204705, 0.12714805 0.11045191 -0.22250696, 0.48824957 0.13858292 -0.16624175, 0.126908 0.11037903 -0.22265263, 0.48999962 0.13947023 -0.16446672, 0.48572788 0.14971484 -0.14397444, 0.48539212 0.14954545 -0.14431347, 0.48497555 0.14941689 -0.14457072, 0.12622559 0.11030124 -0.22280844, 0.12770504 0.11084765 -0.22171529, 0.48596302 0.14991532 -0.14357369, -0.48975387 0.13890122 -0.16559254, -0.48957592 0.13879934 -0.16579635, -0.48938736 0.13873 -0.16593479, -0.094272591 0.089195892 -0.26502204, -0.093275383 0.082556054 -0.27830374, -0.092858747 0.082427487 -0.278561, -0.48989338 0.13904011 -0.16531454, 0.48450211 0.14933661 -0.1447313, 0.12585871 0.11029707 -0.22281666, -0.48906007 0.13865487 -0.16608523, -0.48998544 0.13925125 -0.1648923, 0.48399952 0.14930935 -0.14478596, -0.48870972 0.13860896 -0.16617702, 0.12315225 0.10917914 -0.22505285, 0.12499858 0.10794108 -0.22752921, -0.49000075 0.13946392 -0.16446696, -0.48825076 0.13857666 -0.16624175, -0.094072834 0.089296892 -0.2648201, -0.092523061 0.082258001 -0.27890003, 0.48191482 0.15013525 -0.14313371, 0.48191482 0.15036157 -0.14268096, 0.48203596 0.14991538 -0.14357354, 0.48349711 0.14933659 -0.1447313, -0.48227262 0.14970872 -0.14397459, -0.48260844 0.14953926 -0.14431341, -0.48302495 0.14941074 -0.14457072, -0.48203743 0.14990923 -0.14357369, 0.48302367 0.14941691 -0.14457066, -0.094520628 0.089119479 -0.2651751, -0.093748733 0.082636282 -0.27814317, -0.48349825 0.14933036 -0.14473121, 0.48260704 0.14954548 -0.14431347, -0.093932778 0.089416191 -0.26458156, -0.092287779 0.08205758 -0.27930093, -0.48191613 0.15012896 -0.14313392, -0.48400095 0.14930309 -0.14478596, -0.48191622 0.15035529 -0.14268111, 0.12720802 0.11472982 -0.21394993, 0.12687235 0.11456037 -0.21428891, 0.48227125 0.14971492 -0.14397438, -0.48450318 0.1493303 -0.14473121, -0.094802395 0.089071698 -0.26527065, -0.094251283 0.082663521 -0.27808857, 0.12645578 0.11443173 -0.21454616, -0.48497674 0.14941064 -0.14457072, 0.12744331 0.11493021 -0.21354903, 0.13388517 0.1174846 -0.20843948, -0.093860626 0.089546986 -0.26431984, -0.011202291 0.088674925 -0.2660653, -0.011202237 0.089603208 -0.26420844, 0.12598242 0.1143515 -0.21470673, -0.095101535 0.089055404 -0.26530313, -0.094753832 0.082636282 -0.27814317, -0.095227256 0.082556017 -0.27830374, 0.48608422 0.15013514 -0.14313392, 0.48608422 0.15036151 -0.14268111, 0.12756452 0.11515009 -0.21310945, 0.48596302 0.15058139 -0.14224134, 0.48572773 0.15078178 -0.14184044, -0.48539332 0.14953926 -0.14431341, 0.48539209 0.15095124 -0.14150162, 0.48497543 0.15107985 -0.14124416, 0.48450208 0.15116011 -0.14108382, 0.12547982 0.11432413 -0.2147613, -0.093860619 0.08968173 -0.2640503, -0.010820745 0.090515725 -0.26238316, -0.48572901 0.14970867 -0.14397444, 0.11383834 0.10917905 -0.22505282, 0.10896774 0.090725154 -0.26196575, -0.48596436 0.14990912 -0.14357354, 0.12756452 0.1153764 -0.21265657, -0.093932778 0.089812621 -0.2637887, -0.010070864 0.091381371 -0.26065177, 0.11353917 0.10919538 -0.22502027, 0.48349699 0.15116017 -0.14108382, 0.48399958 0.15118732 -0.14102907, 0.48302361 0.15107985 -0.14124428, -0.094072744 0.089931861 -0.26354992, -0.008977985 0.092170663 -0.25907296, 0.48260713 0.15095112 -0.14150162, 0.48227134 0.15078168 -0.14184041, 0.12497725 0.1143515 -0.2147067, 0.48203608 0.15058134 -0.14224155, -0.094272614 0.090032741 -0.2633481, 0.11325743 0.10924315 -0.22492458, 0.095100984 0.090174526 -0.26306695, 0.12744336 0.1155962 -0.2122169, 0.12450393 0.11443168 -0.21454628, -0.48302504 0.15107363 -0.14124407, -0.48260829 0.15094499 -0.14150162, -0.48349828 0.15115395 -0.14108382, -0.48400095 0.15118124 -0.14102907, -0.48450342 0.15115397 -0.14108382, 0.095979214 0.081192322 -0.28103393, 0.095643423 0.081022888 -0.28137279, 0.097110935 0.077991992 -0.28743559, 0.11300945 0.10931966 -0.2247716, -0.48203737 0.15057513 -0.14224134, 0.095226794 0.080894262 -0.28163016, -0.4822726 0.15077557 -0.14184041, 0.12720804 0.11579672 -0.21181579, -0.10626172 0.087817252 -0.26777965, -0.095643841 0.082427479 -0.27856106, 0.096214443 0.081392802 -0.28063285, -0.095979616 0.082257956 -0.27889979, -0.096214809 0.082057536 -0.27930093, 0.11280959 0.10942057 -0.22456978, 0.094801776 0.090158276 -0.26309949, -0.096335918 0.081837736 -0.27974045, -0.48497692 0.15107362 -0.14124428, -0.48539352 0.1509451 -0.14150162, -0.4857291 0.15077558 -0.14184044, 0.094753474 0.080813974 -0.28179073, 0.092999823 0.077991977 -0.28743559, -0.48596433 0.15057507 -0.14224155, -0.48608553 0.15035529 -0.14268102, -0.48608559 0.15012904 -0.14313392, -0.10441533 0.089055315 -0.26530313, 0.09633559 0.081612572 -0.28019345, 0.12408726 0.11456028 -0.21428888, -0.10488316 0.089051247 -0.26531118, -0.10656872 0.088229015 -0.26695597, 0.11266957 0.10953986 -0.22433113, 0.094520055 0.090110503 -0.26319492, 0.094250917 0.08078666 -0.28184533, -0.10534713 0.089026958 -0.26535988, -0.10573068 0.088980108 -0.26545364, 0.1268723 0.11596614 -0.21147712, -0.10661344 0.088436693 -0.26654065, 0.11259747 0.10967073 -0.22406943, 0.09427207 0.090033941 -0.2633481, 0.093748361 0.080813967 -0.28179073, -0.10598817 0.088927299 -0.2655592, -0.10657686 0.088582031 -0.26625001, -0.10620829 0.088859111 -0.26569551, -0.10650557 0.088680699 -0.2660526, -0.10638304 0.088775925 -0.26586229, 0.11383837 0.11029699 -0.22281666, 0.093274951 0.080894276 -0.28163016, 0.12375152 0.11472979 -0.21394993, 0.12645572 0.11609474 -0.21121977, 0.092858315 0.081022933 -0.28137279, 0.092522666 0.081192255 -0.28103393, 0.092287391 0.081392705 -0.28063285, 0.12351633 0.11493018 -0.21354903, 0.12598239 0.11617502 -0.21105923, 0.10626115 0.0878186 -0.26777965, 0.13438781 0.11789635 -0.20761599, 0.096335597 0.081838943 -0.27974051, -0.10862242 0.090430304 -0.26255292, -0.10784454 0.090201303 -0.2630108, -0.10752873 0.090178743 -0.2630558, 0.096214488 0.082058765 -0.27930093, -0.10815296 0.090251133 -0.26291132, 0.12339513 0.11515003 -0.21310945, 0.11353922 0.11028078 -0.22284906, 0.095979244 0.082259148 -0.27889979, -0.10839565 0.090322182 -0.26276904, 0.095643491 0.082428664 -0.278561, 0.095226832 0.082557201 -0.27830374, 0.0921662 0.081612512 -0.28019345, -0.10881859 0.090573907 -0.26226538, -0.10712186 0.0901732 -0.26306695, 0.12547983 0.11620228 -0.21100481, 0.13507137 0.1182522 -0.20690434, -0.10896824 0.090723813 -0.26196569, -0.095101535 0.090173282 -0.26306695, 0.12339514 0.11537632 -0.21265657, 0.11325742 0.11023297 -0.2229446, 0.12497731 0.11617498 -0.21105923, 0.12351629 0.1155962 -0.2122169, 0.1130095 0.11015635 -0.22309782, 0.12375161 0.11579666 -0.211816, -0.11281039 0.10941906 -0.22456978, -0.11301021 0.10931817 -0.2247716, -0.094802387 0.090157069 -0.26309949, -0.11325819 0.10924162 -0.22492458, -0.11267034 0.10953836 -0.22433104, -0.094520614 0.090109274 -0.26319498, -0.11353997 0.10919391 -0.22502027, 0.0089774672 0.086107552 -0.27120095, 0.0075788726 0.085421525 -0.27257317, 0.092999898 0.07715027 -0.28911912, -0.11259823 0.10966919 -0.22406943, 0.005922141 0.084862031 -0.27369231, 0.01007033 0.086896874 -0.26962227, -0.11383907 0.10917757 -0.22505282, -0.11259823 0.10980396 -0.22379993, -0.0075793541 0.09285678 -0.25770056, 0.0040637236 0.084448278 -0.27451992, -0.11267034 0.10993485 -0.22353823, -0.0059226584 0.093416154 -0.25658154, -0.0040642489 0.093829967 -0.2557537, -0.11281046 0.11005415 -0.22329952, 0.010820307 0.08776246 -0.26789069, 0.092166245 0.081838921 -0.27974051, -0.002067524 0.094084136 -0.25524575, 0.10629119 0.088825382 -0.26576567, 0.10654539 0.088634171 -0.26614845, 0.10644058 0.088738367 -0.26594001, 0.0020670439 0.084194228 -0.27502817, -0.11301023 0.11015497 -0.22309782, 0.011201749 0.088675067 -0.26606548, 0.092287377 0.082058743 -0.27930093, 0.093860134 0.089548193 -0.26431984, 0.10611485 0.088892743 -0.26563096, 0.10660145 0.088517115 -0.26638258, -1.6391206e-07 0.084108502 -0.27519947, 0.10582887 0.088963792 -0.26548904, 0.10661148 0.088390507 -0.26663572, 0.011201728 0.089603379 -0.26420844, 0.093860045 0.089683011 -0.2640503, -0.12499926 0.10793948 -0.2275293, -0.12315286 0.10917751 -0.22505285, 0.010820311 0.090515897 -0.26238316, 0.093932226 0.089813791 -0.2637887, -0.12362085 0.10917352 -0.22506075, -0.12530625 0.1083512 -0.2267056, -0.1240847 0.10914925 -0.22510938, -0.12446821 0.10910232 -0.2252032, -0.12535101 0.10855886 -0.22629027, 0.10538295 0.08902514 -0.26536626, 0.10656086 0.088214144 -0.26698846, 0.10643268 0.088013276 -0.26739025, 0.0100703 0.091381527 -0.26065159, 0.094072238 0.08993312 -0.26354992, -0.1247258 0.10904954 -0.22530888, -0.1253144 0.10870424 -0.22599952, -0.12494583 0.10898131 -0.22544526, -0.12524317 0.10880288 -0.22580217, -0.12512061 0.1088981 -0.22561167, 0.0089774225 0.092170715 -0.25907284, 0.11259745 0.10980542 -0.22380008, 0.10786027 0.090204582 -0.26300722, 0.10863183 0.09043768 -0.26254094, 0.10879976 0.090559356 -0.26229745, 0.1084106 0.090329453 -0.26275724, 0.10817065 0.090256602 -0.26290303, 0.0075787138 0.092856869 -0.25770074, 0.11266954 0.10993631 -0.22353832, 0.10748821 0.090178773 -0.26305866, 0.0059221182 0.093416259 -0.25658154, 0.10712134 0.090174615 -0.26306695, 0.10441481 0.0890567 -0.26530313, 0.0040636491 0.093830049 -0.25575382, -0.12735997 0.11055253 -0.22230254, -0.12658225 0.11032362 -0.22276042, -0.12626639 0.11030108 -0.22280546, 0.11280961 0.1100556 -0.22329949, -0.12689054 0.11037324 -0.22266088, -0.12713327 0.11044438 -0.22251867, 0.095101021 0.089056581 -0.26530313, -0.12755622 0.11069616 -0.22201501, -0.12585951 0.11029546 -0.22281666, 0.0020669373 0.094084069 -0.25524575, 0.094753504 0.082637459 -0.27814317, 0.094250873 0.08266481 -0.27808857, 0.094801851 0.089072853 -0.26527059, 0.093748339 0.082637481 -0.27814317, -0.1277058 0.110846 -0.22171529, -0.12408812 0.11455871 -0.21428888, -0.11383907 0.11029549 -0.22281666, -2.8591532e-07 0.094169676 -0.2550742, 0.094520129 0.089120597 -0.2651751, 0.12408718 0.11596608 -0.21147712, 0.093274973 0.082557216 -0.27830374, -0.1237524 0.11472817 -0.21394987, 0.094272077 0.089197174 -0.26502204, 0.092858344 0.082428649 -0.278561, 0.094072238 0.089298092 -0.2648201, -0.12450473 0.11443011 -0.21454616, -0.12351705 0.11492865 -0.21354897, 0.092522614 0.082259193 -0.27889979, 0.093932249 0.089417368 -0.26458156, -0.12497807 0.11434981 -0.21470673, -0.093000248 0.077149078 -0.28911912, -0.1233959 0.11514841 -0.21310945, -0.11353996 0.11027928 -0.22284906, -0.0089779794 0.08610744 -0.27120095, -0.010070821 0.086896688 -0.26962209, -0.0075792912 0.085421458 -0.27257317, -0.0059225773 0.084861986 -0.27369231, -0.0040641758 0.084448226 -0.27451992, -0.0020674183 0.084194198 -0.27502817, -0.12548073 0.11432254 -0.2147613, -0.123396 0.11537476 -0.21265645, -0.11325823 0.1102315 -0.2229446, -0.093000159 0.077990755 -0.28743559, -0.12598319 0.11434981 -0.2147067, -0.12351717 0.11559461 -0.2122169, -0.12645653 0.11443006 -0.21454616, -0.12375244 0.11579509 -0.21181612, -0.092523009 0.081191137 -0.28103393, -0.092858776 0.081021652 -0.28137279, -0.093275405 0.080893084 -0.28163016, -0.12687318 0.11455869 -0.21428891, -0.12408812 0.11596446 -0.21147712, -0.092287824 0.081391685 -0.28063285, -0.093748719 0.080812767 -0.28179073, -0.12720902 0.11472817 -0.21394993, -0.12450471 0.11609308 -0.21121977, -0.092166647 0.081611328 -0.28019321, -0.010820728 0.087762319 -0.26789069, -0.12744422 0.11492862 -0.21354903, -0.094251283 0.080785528 -0.28184539, -0.092166618 0.081837758 -0.27974045, -0.094753847 0.080812789 -0.28179073, 0.12502854 0.10894786 -0.22551526, 0.12528272 0.10875671 -0.22589795, 0.12517792 0.10886078 -0.22568958, 0.1248522 0.10901529 -0.22538073, 0.12533885 0.10863958 -0.2261322, -0.095227212 0.080893077 -0.28163016, -0.13388607 0.11748289 -0.20843948, -0.12645662 0.11609308 -0.21121986, -0.1259833 0.11617351 -0.21105914, -0.12687331 0.11596455 -0.21147712, -0.1272091 0.11579513 -0.211816, -0.12744425 0.11559459 -0.21221705, -0.1275654 0.11537477 -0.21265657, -0.12756537 0.11514844 -0.21310945, -0.095643885 0.081021637 -0.28137279, -0.13438863 0.11789465 -0.20761605, -0.12548065 0.11620075 -0.21100481, -0.095979616 0.08119116 -0.28103393, -0.13507234 0.11825046 -0.20690452, -0.12497815 0.11617342 -0.21105923, -0.12548073 0.11521703 -0.21520849, -0.12497811 0.11524427 -0.21515386, -0.12450476 0.11532459 -0.2149934, -0.12408806 0.11545309 -0.21473606, -0.12375237 0.11562256 -0.21439703, -0.12351717 0.1158231 -0.21399613, -0.123396 0.1160429 -0.21355648, -0.12339597 0.11626926 -0.21310373, -0.12351718 0.11648903 -0.21266402, -0.12375242 0.11668952 -0.21226327, -0.12408813 0.11685894 -0.21192415, -0.1245048 0.11698759 -0.21166699, -0.12497815 0.11706781 -0.21150644, -0.1254808 0.1170952 -0.21145184, 0.094250888 0.081681162 -0.28229243, 0.094753504 0.081708454 -0.28223801, 0.095226869 0.081788689 -0.28207737, 0.095643491 0.081917286 -0.28182006, 0.095979214 0.082086772 -0.28148103, 0.096214414 0.082287252 -0.28108013, 0.096335582 0.082507022 -0.28064042, 0.096335545 0.082733423 -0.28018773, 0.096214332 0.082953222 -0.27974796, 0.095979176 0.083153635 -0.27934706, 0.095643446 0.083323151 -0.27900815, 0.09522678 0.083451718 -0.27875102, 0.094753399 0.083532035 -0.27859044, 0.094250888 0.083559297 -0.27853578, 0.12547977 0.11521868 -0.21520858, 0.12598237 0.11524592 -0.21515386, 0.12645575 0.11532627 -0.2149934, 0.12687238 0.11545481 -0.21473606, 0.12720799 0.11562431 -0.21439703, 0.12744331 0.11582468 -0.21399613, 0.12756449 0.11604455 -0.21355648, 0.12756452 0.11627084 -0.21310373, 0.12744337 0.1164906 -0.21266402, 0.12720808 0.11669111 -0.21226312, 0.12687239 0.11686056 -0.21192415, 0.12645574 0.11698918 -0.21166699, 0.12598239 0.11706935 -0.21150629, 0.12547979 0.11709671 -0.21145184, -0.09425132 0.081679948 -0.28229243, -0.093748733 0.081707254 -0.28223801, -0.093275413 0.081787512 -0.28207737, -0.092858732 0.081916109 -0.28182006, -0.092523023 0.082085595 -0.28148127, -0.092287734 0.082286 -0.28108013, -0.092166595 0.082505815 -0.28064042, -0.09216664 0.082732201 -0.28018773, -0.092287794 0.082951993 -0.27974796, -0.092523031 0.083152458 -0.27934718, -0.092858747 0.083321914 -0.27900815, -0.093275361 0.083450481 -0.27875078, -0.093748719 0.083530799 -0.27859044, -0.094251268 0.083558068 -0.27853578, -2.3003597e-07 0.085002989 -0.27564663, 0.0020669182 0.085088655 -0.27547532, 0.0040636733 0.085342795 -0.27496713, 0.0059221215 0.085756488 -0.27413946, 0.0075788065 0.086315975 -0.27302039, 0.0089774774 0.08700195 -0.27164817, 0.010070316 0.087791301 -0.27006936, 0.010820325 0.088656887 -0.26833791, 0.011201751 0.089569494 -0.26651251, 0.011201737 0.090497836 -0.26465559, 0.010820255 0.091410324 -0.2628302, 0.010070298 0.092275925 -0.26109868, 0.0089773964 0.093065262 -0.25952005, 0.0075787287 0.093751267 -0.25814772, 0.0059220307 0.094310746 -0.25702864, 0.0040636156 0.094724506 -0.25620097, 0.0020669159 0.094978496 -0.2556929, -3.2316822e-07 0.095064163 -0.25552148, 0.48399958 0.15020368 -0.14523287, 0.48450208 0.15023111 -0.1451783, 0.48497543 0.15031131 -0.14501788, 0.485392 0.15043995 -0.14476059, 0.48572782 0.15060934 -0.14442165, 0.48596317 0.15080981 -0.14402066, 0.48608431 0.15102962 -0.14358102, 0.48608431 0.151256 -0.14312823, 0.48596302 0.15147577 -0.14268853, 0.48572776 0.15167618 -0.14228763, 0.48539212 0.15184571 -0.14194869, 0.48497543 0.15197435 -0.14169152, 0.48450211 0.15205452 -0.14153092, 0.48399955 0.15208182 -0.14147623, -0.48400095 0.1501976 -0.14523293, -0.48349833 0.15022488 -0.14517851, -0.48302498 0.15030511 -0.14501788, -0.48260832 0.15043375 -0.14476047, -0.48227257 0.15060309 -0.14442165, -0.48203737 0.15080366 -0.14402075, -0.48191622 0.1510234 -0.1435812, -0.48191622 0.15124984 -0.1431282, -0.48203745 0.15146956 -0.14268853, -0.48227254 0.15166995 -0.14228763, -0.48260835 0.15183945 -0.1419486, -0.48302492 0.15196808 -0.14169128, -0.48349831 0.15204827 -0.14153092, -0.48400101 0.15207569 -0.14147635, 0.077318206 0.14325975 -0.15911765, 0.076144271 0.14450982 -0.156617, 0.098204851 0.14832509 -0.14898603, -0.094272614 0.090927251 -0.26379538, -0.068754084 0.12570429 -0.19423176, -0.064075723 0.12570435 -0.19423179, -0.094520614 0.091003723 -0.26364231, -0.064075768 0.12818852 -0.18926264, 0.07474339 0.14555788 -0.15452062, 0.11383828 0.11119148 -0.22326384, 0.12351625 0.11582467 -0.21399613, 0.12375154 0.11562422 -0.21439703, 0.029783994 0.12570493 -0.19423179, 0.1338852 0.11837909 -0.20888664, 0.13438775 0.11879078 -0.20806302, 0.048789892 0.12544356 -0.19475473, 0.097085625 0.078859255 -0.2879371, 0.12339514 0.11604449 -0.21355648, -0.11301017 0.11021261 -0.22521873, -0.11281039 0.11031349 -0.22501697, -0.095101535 0.091067798 -0.26351416, 0.11353923 0.11117521 -0.22329627, -0.094802417 0.091051504 -0.26354665, -0.11325823 0.11013608 -0.22537194, -0.10896821 0.091618225 -0.26241302, 0.073192134 0.14641738 -0.15280141, -0.1126703 0.11043282 -0.22477837, 0.092999846 0.078859195 -0.2879371, 0.1233952 0.11627081 -0.21310373, -0.11353995 0.1100883 -0.22546743, 0.11325749 0.11112741 -0.22339188, -0.11259823 0.11056371 -0.22451665, -0.07577166 0.12570426 -0.19423179, -0.11383913 0.11007206 -0.22549991, 0.071589582 0.14706896 -0.15149818, -0.1125982 0.11069836 -0.22424714, 0.12351625 0.11649057 -0.21266396, -0.11267036 0.11082928 -0.22398533, 0.023058856 0.12570485 -0.19423176, 0.093748391 0.081708401 -0.28223789, 0.063702129 0.13694954 -0.17173971, 0.055222526 0.14034906 -0.16493975, 0.071857885 0.14088543 -0.16386686, 0.093274914 0.081788734 -0.28207731, 0.092858344 0.081917271 -0.28182006, 0.11867292 0.12570548 -0.19423179, 0.1350714 0.11914663 -0.20735152, 0.135906 0.11943083 -0.20678319, 0.13685475 0.11963081 -0.20638312, 0.069709934 0.14762592 -0.15038411, 0.13787606 0.11973792 -0.20616867, 0.12497723 0.11706941 -0.21150629, 0.092522636 0.082086757 -0.28148103, -0.040976375 0.12818868 -0.18926264, -0.060859375 0.13616423 -0.17330889, -0.04097636 0.13616443 -0.17330889, 0.1245039 0.11698911 -0.21166699, 0.055338971 0.14157465 -0.16248809, 0.071264818 0.14224863 -0.16114019, 0.12408722 0.11686055 -0.21192415, 0.067547373 0.14519271 -0.15525107, 0.064690888 0.14577475 -0.15408687, 0.066194758 0.14555746 -0.15452136, 0.068687908 0.14470315 -0.15623038, 0.11165537 0.12570542 -0.19423179, 0.11300949 0.11105087 -0.22354503, -0.12499923 0.10883394 -0.22797643, 0.092287347 0.08228723 -0.28108013, 0.12375157 0.11669108 -0.21226312, 0.063117258 0.14584051 -0.15395524, -0.12315293 0.11007197 -0.22549991, 0.067730531 0.1480059 -0.14962409, 0.10626116 0.08871305 -0.26822686, -0.12517083 0.10902858 -0.22758703, 0.055749733 0.14278743 -0.16006251, 0.070532635 0.14328074 -0.1590756, 0.069602765 0.14412653 -0.15738367, 0.0921662 0.082506999 -0.28064042, 0.092999861 0.078044757 -0.2895664, -0.12412111 0.1100405 -0.22556297, -0.12534957 0.10940582 -0.22683258, -0.12529893 0.10922945 -0.22718529, 0.056416385 0.14374602 -0.15814491, 0.048789807 0.13694949 -0.17173971, 0.048789784 0.14034896 -0.16493975, -0.12456699 0.10997915 -0.22568573, -0.12533958 0.10953245 -0.22657932, 0.056853138 0.14415801 -0.15732054, -0.12485294 0.10990818 -0.22582774, -0.12528352 0.10964951 -0.22634508, 0.057336338 0.14451413 -0.15660842, 0.092166133 0.082733408 -0.28018773, -0.12502928 0.10984087 -0.2259625, -0.12517871 0.10975367 -0.22613685, 0.062077962 0.14581507 -0.15400626, 0.061057426 0.14572257 -0.15419145, -0.040976375 0.13864864 -0.16833974, -0.060859494 0.1386486 -0.16833974, -0.04097645 0.14557841 -0.15447821, 0.065511107 0.14824417 -0.14914729, 0.058451302 0.14508881 -0.15545885, 0.059670456 0.14547506 -0.15468617, 0.064317718 0.14830145 -0.14903273, 0.092287354 0.08295317 -0.27974808, 0.093860105 0.090442628 -0.26476705, -0.093000159 0.078043535 -0.28956622, -0.0089779384 0.087001897 -0.27164817, -0.010070841 0.087791175 -0.27006936, 0.090602651 0.12570533 -0.19423179, 0.10756177 0.13263512 -0.18037038, -0.0075793574 0.086315885 -0.27302039, -0.0059225531 0.085756421 -0.27413946, -0.0040641967 0.085342683 -0.27496701, -0.0020674388 0.085088655 -0.27547532, 0.11280954 0.11095008 -0.22374676, 0.11266956 0.11083075 -0.22398551, 0.093860075 0.090577453 -0.26449758, -0.12690872 0.11127187 -0.2230999, -0.12714878 0.11134475 -0.22295408, -0.12659833 0.11121975 -0.223204, 0.063117199 0.14832474 -0.14898603, 0.10657629 0.089477845 -0.26669711, 0.10620782 0.089755014 -0.26614261, 0.10650502 0.089576498 -0.2664997, 0.10638245 0.089671679 -0.26630932, 0.093932182 0.090708278 -0.26423597, -0.093000233 0.078858003 -0.28793716, 0.10598762 0.089823171 -0.26600641, -0.12737 0.11145295 -0.22273763, 0.10661294 0.089332506 -0.26698774, -0.11301016 0.11104946 -0.22354494, -0.095654711 0.12570417 -0.19423179, -0.11281038 0.11094861 -0.22374676, 0.10573012 0.089875981 -0.26590085, 0.094072267 0.090827554 -0.2639972, 0.10656817 0.089124903 -0.26740324, -0.12753788 0.11157466 -0.22249417, -0.12622643 0.1111941 -0.22325553, 0.083585195 0.12570524 -0.19423176, 0.1125975 0.11069986 -0.22424714, 0.1125975 0.11056516 -0.22451665, -0.12770587 0.11174048 -0.22216256, -0.12585956 0.11118992 -0.22326384, -0.11383918 0.11119001 -0.22326384, 0.10839507 0.091217995 -0.26321632, 0.10815237 0.091146946 -0.26335853, 0.10862188 0.09132611 -0.26299995, 0.094696246 0.13263503 -0.18037032, 0.10534665 0.089922845 -0.26580703, -0.11353999 0.1111737 -0.22329627, -0.1132582 0.11112593 -0.22339176, 0.107844 0.091097161 -0.26345801, -0.12598322 0.1152443 -0.21515386, 0.10752828 0.091074541 -0.26350302, 0.10881805 0.091469824 -0.26271272, -0.10267222 0.12570409 -0.19423176, 0.073288716 0.12732898 -0.1909837, 0.075140007 0.12826267 -0.1891159, 0.10488266 0.089947134 -0.2657584, -0.12645657 0.11532459 -0.2149934, 0.071344227 0.12659156 -0.19245879, 0.10712136 0.091069028 -0.26351416, 0.10896771 0.091619611 -0.26241302, -0.12687324 0.1154532 -0.21473606, 0.076399408 0.12913463 -0.18737184, 0.10441487 0.089951068 -0.26575035, -0.12720907 0.11562266 -0.21439703, 0.069402508 0.12605625 -0.19352944, -0.12744427 0.1158231 -0.21399613, 0.095101036 0.089951016 -0.26575035, 0.093748286 0.083531991 -0.27859044, 0.094801858 0.08996731 -0.2657178, -0.010820732 0.088656746 -0.26833791, 0.093274906 0.083451733 -0.27875102, 0.094520167 0.090015024 -0.26562238, 0.067528158 0.12570982 -0.19422261, -0.085713223 0.13485663 -0.17592423, 0.092858359 0.083323047 -0.27900815, 0.094272092 0.090091616 -0.26546919, -0.011202282 0.089569353 -0.26651251, 0.077484109 0.13019396 -0.18525292, 0.092522576 0.08315368 -0.27934718, 0.094072253 0.090192527 -0.26526731, 0.0037606303 0.12570477 -0.19423179, -0.0020674849 0.094978534 -0.25569278, 0.094272137 0.090928391 -0.26379526, 0.065638676 0.1255075 -0.19462712, 0.094520077 0.091004908 -0.26364231, 0.093932271 0.090311788 -0.26502883, -0.097085997 0.078857973 -0.28793716, -0.094753861 0.081707247 -0.28223795, -0.062613793 0.14557824 -0.15447839, 0.095100969 0.091068953 -0.26351416, -0.082496837 0.13747165 -0.1706935, 0.078370295 0.1314543 -0.18273188, -0.095227227 0.081787497 -0.28207731, -0.095643885 0.081916094 -0.28182006, -0.13388602 0.11837737 -0.20888664, -0.12645647 0.11698752 -0.21166699, -0.12598321 0.11706781 -0.21150629, -0.12687328 0.11685891 -0.21192415, -0.12720889 0.11668937 -0.21226312, -0.12744427 0.11648901 -0.21266417, -0.1275654 0.11626925 -0.21310373, -0.12756544 0.11604296 -0.21355648, 0.063702166 0.12544365 -0.19475488, -0.095979556 0.08208552 -0.28148127, -0.13438863 0.11878905 -0.20806317, -0.070216164 0.14806244 -0.14950924, -0.0626138 0.1480625 -0.14950924, -0.096214876 0.08228603 -0.28108013, -0.09633597 0.082505792 -0.28064042, -0.13507234 0.11914489 -0.20735152, 0.062218729 0.12547989 -0.19468249, -0.13590683 0.11942904 -0.20678319, -0.13685575 0.11962908 -0.20638289, -0.137877 0.11973621 -0.20616867, 0.12531368 0.10960031 -0.22644679, 0.12494519 0.10987745 -0.22589232, 0.12524247 0.10969894 -0.22624944, 0.12511982 0.10979421 -0.22605895, -0.085713193 0.13995579 -0.16572438, -0.094192781 0.14806221 -0.14950924, -0.077233769 0.14806244 -0.14950909, 0.12472505 0.10994569 -0.225756, -0.10121033 0.14806223 -0.14950897, -0.088929594 0.13747162 -0.17069353, 0.12535024 0.10945491 -0.22673742, 0.12446749 0.10999843 -0.22565047, 0.12530561 0.10924732 -0.22715275, -0.47530088 0.13874164 -0.16814806, -0.47530094 0.15513325 -0.13536038, -0.034251124 0.1257045 -0.19423179, -0.034251213 0.14806262 -0.14950924, -0.026648752 0.12818873 -0.18926264, -0.0029647164 0.14806286 -0.14950924, 0.029783808 0.14806311 -0.14950924, 0.07899449 0.13288668 -0.17986672, 0.079380281 0.13452172 -0.17659621, 0.079491585 0.13616508 -0.17330889, 0.07935176 0.13829893 -0.16904084, 0.078914613 0.14021021 -0.16521774, -0.094272621 0.090090439 -0.26546919, 0.47529945 0.15513936 -0.13536038, 0.023058703 0.14806306 -0.14950924, 0.0037604272 0.14806294 -0.14950924, 0.12713245 0.11134046 -0.22296588, 0.12688974 0.11126941 -0.22310816, 0.12735921 0.11144853 -0.22274975, -0.094072834 0.090191379 -0.26526731, 0.10405289 0.14832498 -0.14898603, -0.094520643 0.090013929 -0.26562238, 0.12408397 0.11004534 -0.22555657, -0.093932763 0.090310648 -0.26502866, 0.12658131 0.11121964 -0.22320764, -0.094802395 0.089966148 -0.2657178, -0.093860693 0.09044148 -0.26476705, 0.12626554 0.11119717 -0.22325264, 0.12755549 0.11159223 -0.22246249, -0.011202258 0.090497665 -0.26465565, 0.06536828 0.12815031 -0.1893407, 0.06282492 0.1279279 -0.18978564, 0.066793218 0.12849665 -0.18864797, 0.064120039 0.1279842 -0.18967308, -0.095101506 0.089949846 -0.26575035, -0.094753824 0.083530754 -0.27859038, -0.095227249 0.083450466 -0.27875078, 0.12362005 0.1100696 -0.22550802, 0.12499849 0.10883556 -0.22797643, -0.093860634 0.090576157 -0.2644974, -0.01082084 0.091410182 -0.2628302, 0.12585866 0.11119156 -0.22326384, 0.12770504 0.11174214 -0.22216256, -0.093932725 0.090707041 -0.26423573, -0.010070884 0.092275769 -0.2610988, 0.12315214 0.11007366 -0.22549991, 0.47529963 0.13874772 -0.16814794, -0.094072804 0.090826318 -0.26399714, 0.053760618 0.12544359 -0.19475473, 0.058631033 0.12589826 -0.19384544, 0.056828897 0.12632731 -0.1929871, 0.060752943 0.12558779 -0.19446661, 0.060934097 0.14826268 -0.14911021, 0.058796152 0.1480546 -0.14952652, 0.056729391 0.14768055 -0.15027438, 0.05503932 0.14720619 -0.15122344, 0.053442691 0.14655629 -0.15252341, 0.052035786 0.14575511 -0.15412618, 0.050833359 0.14482975 -0.15597697, 0.049923945 0.14381047 -0.15801589, 0.049246773 0.14264956 -0.16033791, 0.048893608 0.14150403 -0.16262935, -0.10626172 0.088711798 -0.26822692, -0.095643878 0.083321907 -0.27900827, -0.095979542 0.083152413 -0.27934718, -0.096214883 0.082951993 -0.27974808, -0.096336007 0.082732141 -0.28018773, 0.055624865 0.12675086 -0.19213985, -0.10643321 0.08890631 -0.26783752, -0.10441533 0.089949802 -0.26575035, 0.059484154 0.12822568 -0.1891899, 0.058306992 0.12853269 -0.18857573, 0.061118528 0.12799716 -0.189647, -0.10661197 0.089283556 -0.26708293, -0.10538351 0.089918256 -0.26581347, -0.10656142 0.089107238 -0.26743567, 0.054637827 0.12727407 -0.19109337, 0.11383833 0.1100736 -0.22550006, -0.10660197 0.089410156 -0.26682979, -0.10582942 0.089856923 -0.26593608, 0.057352766 0.12890291 -0.1878352, -0.10654585 0.08952722 -0.2665956, -0.10611531 0.089785904 -0.26607823, -0.10644109 0.089631408 -0.26638728, -0.10629165 0.089718573 -0.26621276, 0.11353919 0.11008981 -0.22546749, -0.0040642992 0.094724454 -0.25620097, -0.026648771 0.12570453 -0.19423179, -0.0059225904 0.094310522 -0.25702864, 0.12497726 0.11524592 -0.21515386, 0.056550823 0.12933925 -0.18696235, 0.11325749 0.11013761 -0.22537194, 0.055924613 0.12982967 -0.1859815, 0.12450394 0.1153262 -0.2149934, 0.1130095 0.11021404 -0.22521876, 0.094801828 0.091052741 -0.26354665, 0.11280957 0.110315 -0.22501697, -0.10817121 0.091149643 -0.26335013, -0.10841116 0.09122245 -0.26320451, -0.10786082 0.091097578 -0.26345432, 0.055325314 0.13053325 -0.18457408, 0.063702114 0.13446537 -0.17670898, 0.1240873 0.11545478 -0.21473627, 0.07236632 0.13466932 -0.17630096, 0.072473988 0.1364267 -0.1727858, 0.07196939 0.13292035 -0.17979927, 0.071371444 0.13161081 -0.18241881, 0.070538931 0.13054752 -0.18454559, 0.069557987 0.12976351 -0.18611391, 0.068239339 0.12905093 -0.18753932, 0.1126696 0.11043426 -0.22477852, -0.10863244 0.091330722 -0.26298809, -0.10880025 0.09145242 -0.26274461, -0.10748884 0.091071889 -0.26350594, 0.078252308 0.14181757 -0.16200264, 0.054848067 0.13153619 -0.18256755, -0.10712184 0.091067642 -0.26351416, 0.054685026 0.1322802 -0.18107973, -0.0075793723 0.093751177 -0.25814772, -0.0089779915 0.09306515 -0.25952005, 0.072438955 0.13770156 -0.17023562, 0.072307669 0.13897514 -0.167688, 0.05463773 0.13302708 -0.17958574, -0.0029645637 0.12818891 -0.18926264, 0.054637812 0.13446522 -0.17670898, 0.092999861 0.077662364 -0.29014975, 0.092999838 0.076895341 -0.28950822, 0.092999876 0.076557472 -0.28982776, 0.092999838 0.077155516 -0.29062921, 0.092999868 0.076154932 -0.29006064, 0.092999861 0.076551661 -0.29097849, 0.092999838 0.075709417 -0.29019439, 0.092999876 0.075883463 -0.291179, 0.09299989 0.075245157 -0.29022139, 0.09299989 0.075187005 -0.29121977, 0.092999846 0.074787214 -0.29014057, 0.092999861 0.074500009 -0.29109842, 0.092999876 0.074360207 -0.28995615, 0.092999883 0.073859617 -0.29082185, 0.095344365 0.073859602 -0.29082197, 0.095344305 0.074360281 -0.28995615, -0.093000188 0.077154323 -0.29062921, -0.093000263 0.076894179 -0.28950822, -0.093000188 0.077661112 -0.29014975, -0.093000151 0.076550439 -0.29097849, -0.093000166 0.07655625 -0.2898277, -0.093000218 0.075882241 -0.291179, -0.093000159 0.07615374 -0.29006064, -0.093000144 0.07518582 -0.29121977, -0.093000218 0.075708285 -0.29019439, -0.093000174 0.074498788 -0.29109842, -0.093000174 0.075243935 -0.29022139, -0.093000151 0.074785933 -0.29014057, -0.093000256 0.073858395 -0.29082197, -0.093000263 0.074359015 -0.28995615, -0.095344685 0.07385841 -0.29082185, -0.095344722 0.074359007 -0.28995627, -0.48450333 0.15204836 -0.14153092, -0.48497674 0.15196808 -0.14169158, -0.48539332 0.15183946 -0.14194869, -0.48572919 0.15167005 -0.14228763, -0.48596451 0.1514696 -0.14268862, -0.48608547 0.15124984 -0.14312823, -0.48608544 0.15102342 -0.1435812, -0.48596445 0.15080354 -0.14402075, -0.48572913 0.15060313 -0.14442168, -0.48539335 0.15043367 -0.14476047, -0.48497674 0.15030508 -0.14501788, -0.48450333 0.15022483 -0.14517851, 0.48349711 0.15205456 -0.14153092, 0.48302361 0.15197432 -0.14169152, 0.48260686 0.15184568 -0.14194869, 0.48227125 0.15167621 -0.14228757, 0.48203608 0.15147574 -0.14268853, 0.48191494 0.151256 -0.14312823, 0.48191491 0.15102959 -0.14358102, 0.48203608 0.15080984 -0.14402075, 0.48227134 0.15060943 -0.14442165, 0.48260695 0.15043995 -0.14476068, 0.48302367 0.15031132 -0.14501788, 0.48349699 0.15023114 -0.14517827, -0.49000075 0.14035842 -0.16491391, -0.48998639 0.1401507 -0.16532935, -0.48992828 0.13998953 -0.16565169, -0.48980239 0.13983496 -0.16596104, -0.48967242 0.1397427 -0.16614555, -0.48946854 0.13965113 -0.16632901, -0.4891777 0.13957167 -0.16648759, -0.48872092 0.13950458 -0.16662185, -0.48825082 0.13947114 -0.16668893, 0.48999968 0.14036466 -0.16491391, 0.48998424 0.1401519 -0.16533957, 0.48989221 0.1399408 -0.16576181, 0.48975262 0.13980187 -0.1660396, 0.48957476 0.13970006 -0.16624354, 0.4893862 0.13963079 -0.16638203, 0.489059 0.13955565 -0.16653226, 0.48870853 0.13950971 -0.16662408, 0.48824963 0.13947736 -0.16668902, -0.099222548 -0.014071763 -0.23882057, -0.10480863 -0.019309811 -0.23579173, -0.091499582 -0.019309744 -0.23579173, -0.097640336 -0.012525901 -0.23971461, -0.097761549 -0.012951344 -0.23946841, -0.091963738 0.064960472 -0.28452134, -0.097840413 0.054363951 -0.2783941, -0.091728359 0.064572364 -0.28429693, 0.10664253 -0.018679783 -0.23615523, 0.10627376 -0.019035704 -0.23594938, 0.1064856 -0.018874563 -0.2360426, 0.1060437 -0.019146651 -0.23588519, 0.10675283 -0.018448025 -0.23628904, -0.099725083 -0.014124639 -0.23878999, 0.10578545 -0.019226 -0.23583926, -0.092084795 0.065385871 -0.28476745, 0.10682786 -0.01810389 -0.23648818, 0.10530005 -0.019296572 -0.23579843, -0.09764035 -0.012087584 -0.23996793, 0.10679794 -0.017391026 -0.23690043, 0.10480958 -0.019308485 -0.23579173, -0.10022758 -0.014071807 -0.23882051, 0.1011184 -0.013666213 -0.23905431, 0.10145413 -0.013338186 -0.23924397, 0.10070175 -0.013915159 -0.23891042, -0.097761534 -0.011662088 -0.24021401, -0.087499611 -0.020845115 -0.23490365, 0.10168938 -0.0129501 -0.23946841, -0.090502679 0.067370176 -0.2859149, -0.090000108 0.067423031 -0.28594542, -0.090975985 0.067214727 -0.28582501, 0.10022841 -0.014070526 -0.23882051, -0.091392651 0.066965759 -0.28568095, 0.10181049 -0.012524553 -0.2397144, -0.088607565 0.066965766 -0.28568113, -0.088271774 0.066637769 -0.28549117, -0.089024149 0.067214765 -0.28582501, -0.089497551 0.067370124 -0.2859149, -0.10070097 -0.013916373 -0.23891042, 0.099725842 -0.014123395 -0.23878999, -0.09172833 0.066637754 -0.28549147, -0.091963574 0.066249728 -0.285267, -0.092084825 0.065824196 -0.28502095, 0.10181053 -0.012086302 -0.23996793, 0.099223323 -0.014070615 -0.23882051, 0.10168937 -0.011660799 -0.24021392, -0.10664122 -0.018681891 -0.23615469, -0.10647885 -0.018881567 -0.23603924, -0.10627206 -0.019037582 -0.23594902, -0.10111759 -0.013667479 -0.23905431, -0.10674383 -0.018472016 -0.23627625, -0.10601792 -0.019157425 -0.2358797, 0.091500469 -0.019308507 -0.23579173, 0.098749965 -0.013915204 -0.23891042, 0.098333269 -0.013666205 -0.23905431, 0.097997591 -0.013338134 -0.23924397, -0.10680719 -0.018241189 -0.23640977, -0.10563056 -0.019258894 -0.23582105, -0.10683618 -0.017815746 -0.23665558, 0.097762331 -0.012950175 -0.23946841, 0.09764111 -0.01252462 -0.2397144, -0.10679708 -0.017392404 -0.23690043, -0.10145334 -0.013339423 -0.23924388, 0.09764117 -0.012086362 -0.23996793, -0.10168858 -0.012951404 -0.23946841, 0.08750049 -0.020844005 -0.2349038, 0.091500513 -0.020844042 -0.2349038, 0.097762316 -0.011660874 -0.24021392, -0.10180972 -0.012525886 -0.2397144, -0.10180976 -0.012087613 -0.23996796, 0.10440002 0.0018181354 -0.24800827, 0.099223241 -0.010540314 -0.240862, 0.099725865 -0.010487527 -0.24089237, 0.10145414 -0.011272751 -0.24043833, 0.10111838 -0.010944672 -0.24062811, -0.10168859 -0.011662126 -0.24021392, 0.10070174 -0.010695703 -0.24077193, 0.10022838 -0.010540321 -0.240862, -0.089821555 0.0039232373 -0.24922623, -0.090061404 0.0036889315 -0.24909057, 0.10352451 0.0032180101 -0.24881776, 0.1039606 0.0029455051 -0.24866019, 0.1037422 0.0031132847 -0.24875717, 0.10413489 0.0027270168 -0.24853383, -0.090358958 0.003511034 -0.24898787, 0.10316599 0.0033154637 -0.24887399, 0.10425929 0.0024739355 -0.24838753, 0.10435075 0.0021467954 -0.24819832, 0.10241157 0.0033635497 -0.24890195, -0.089653559 0.0042004287 -0.24938644, -0.090697095 0.0034000799 -0.24892367, -0.097996801 -0.011273965 -0.24043839, -0.089567088 0.0045043826 -0.24956219, 0.089567609 0.0045054331 -0.24956219, 0.089567557 0.004818514 -0.24974315, 0.10348819 0.0065891221 -0.25076705, 0.10311941 0.0062332526 -0.25056136, 0.10333119 0.0063944533 -0.25065452, 0.10288932 0.006122306 -0.25049728, -0.091056094 0.0033623427 -0.24890195, -0.098332509 -0.010945901 -0.24062799, -0.098749153 -0.010697 -0.24077187, 0.10359852 0.0068208352 -0.25090104, -0.099222526 -0.010541596 -0.240862, 0.10263101 0.0060430244 -0.25045145, -0.089567013 0.0048173741 -0.24974315, 0.08385098 0.050688699 -0.27626795, 0.10367343 0.0071651787 -0.25110012, 0.10214561 0.005972445 -0.25041044, 0.10364354 0.0078779832 -0.25151235, 0.10165512 0.0059605837 -0.2504037, 0.091056563 0.0033635497 -0.24890195, 0.098749921 -0.010695778 -0.24077187, 0.098333269 -0.010944672 -0.24062811, 0.097997531 -0.011272699 -0.24043839, 0.090697631 0.0034012049 -0.24892367, 0.090359516 0.0035122558 -0.24898787, 0.090062007 0.0036900192 -0.24909072, 0.089822181 0.0039243549 -0.24922611, 0.089654118 0.0042015165 -0.24938644, -0.10241097 0.0033622161 -0.24890195, 0.091056608 0.0059605166 -0.25040358, -0.10439939 0.001816839 -0.24800827, -0.1002276 -0.010541633 -0.240862, -0.09972506 -0.010488793 -0.24089237, -0.10070099 -0.010697015 -0.24077193, -0.10111761 -0.010945916 -0.24062811, -0.10145328 -0.011273988 -0.24043833, -0.1027937 0.0033551529 -0.2488979, -0.10426304 0.0024609864 -0.24838071, -0.10317924 0.0033116341 -0.24887256, -0.10348332 0.0032316446 -0.2488264, -0.10411274 0.0027590692 -0.24855314, -0.10375296 0.0031051338 -0.24875323, -0.10396905 0.0029351413 -0.24865498, 0.098596841 0.048305441 -0.27488977, 0.097721368 0.049705245 -0.2756992, 0.098157391 0.049432803 -0.27554178, 0.097939089 0.049600467 -0.27563876, 0.098331749 0.049214289 -0.27541542, 0.097362876 0.049802616 -0.27575558, 0.098456115 0.048961177 -0.27526897, 0.098547637 0.048634093 -0.27507991, -0.10348716 0.0065871403 -0.25076687, -0.10332478 0.0063874796 -0.2506513, -0.10311806 0.0062314942 -0.25056118, 0.096608445 0.049850736 -0.27578354, -0.10358984 0.0067970231 -0.25088805, -0.10286373 0.0061115921 -0.25049174, -0.10365319 0.0070279241 -0.25102156, 0.097684942 0.053076401 -0.27764869, 0.09731622 0.052720487 -0.27744293, 0.097528011 0.052881759 -0.27753615, -0.10247644 0.00601013 -0.25043303, 0.097086161 0.052609656 -0.27737862, 0.097795337 0.05330817 -0.2777828, -0.10368206 0.007453233 -0.25126749, -0.10165454 0.0059592202 -0.25040358, 0.09682785 0.05253027 -0.2773329, -0.10364302 0.0078766644 -0.25151235, -0.091056094 0.0059593245 -0.2504037, 0.097870283 0.053652387 -0.2779817, 0.096342467 0.052459724 -0.27729213, -0.084258854 0.050176147 -0.27597231, -0.090061344 0.0056327879 -0.25021487, -0.089821532 0.0053984225 -0.25007933, 0.097840413 0.054365199 -0.27839392, -0.084019057 0.050410457 -0.27610767, 0.095851988 0.052447826 -0.27728522, 0.085253537 0.049850661 -0.27578354, 0.090697616 0.0059227794 -0.25038177, -0.089653596 0.0051213205 -0.24991898, -0.084556483 0.049998377 -0.27586943, -0.090358943 0.0058106109 -0.25031763, 0.084894523 0.049888451 -0.27580518, 0.090359554 0.0058117956 -0.25031751, -0.08385098 0.050687619 -0.27626812, 0.084556386 0.049999435 -0.27586943, 0.090061933 0.0056339279 -0.25021487, -0.08489456 0.049887359 -0.27580518, -0.09069714 0.0059216544 -0.25038177, 0.08425881 0.050177265 -0.27597231, 0.089822181 0.0053996369 -0.25007921, -0.083764434 0.050991636 -0.27644378, 0.083764449 0.050992712 -0.27644378, 0.084019005 0.050411541 -0.27610767, 0.089654133 0.0051224008 -0.24991898, -0.085253574 0.049849693 -0.27578354, -0.083764434 0.051304683 -0.27662486, 0.083764441 0.051305752 -0.27662474, 0.08385098 0.051609714 -0.27680057, -0.08385092 0.051608574 -0.27680057, 0.087915123 0.06582538 -0.28502095, 0.091728196 0.064573467 -0.28429693, 0.091392413 0.064245462 -0.28410727, 0.090975828 0.063996494 -0.28396326, -0.098596826 0.048304178 -0.27488989, -0.09660843 0.049849562 -0.27578354, 0.09196341 0.064961597 -0.28452134, -0.096991144 0.04984241 -0.27577931, 0.090502456 0.063841105 -0.2838735, -0.09846051 0.048948329 -0.2752623, -0.097376704 0.049798921 -0.27575415, -0.097680733 0.049718957 -0.2757079, 0.092084602 0.06538707 -0.28476745, -0.098310173 0.049246382 -0.27543473, -0.097950459 0.049592506 -0.27563483, 0.089999966 0.063788198 -0.28384298, 0.085253462 0.052447729 -0.27728528, -0.098166496 0.049422454 -0.2755366, 0.08949732 0.063841097 -0.28387344, 0.089024007 0.063996457 -0.28396326, 0.088607326 0.064245448 -0.28410727, 0.084894538 0.052410003 -0.27726346, -0.097684599 0.053074494 -0.27764815, -0.097522214 0.052874815 -0.27753276, -0.097315498 0.0527188 -0.27744263, 0.088271677 0.064573482 -0.28429693, 0.084556416 0.052298985 -0.27719927, -0.097787276 0.053284358 -0.27776963, -0.097061202 0.052598909 -0.27737337, 0.088036403 0.064961538 -0.2845214, 0.08425875 0.052121237 -0.27709645, -0.097850561 0.053515121 -0.27790314, -0.096673906 0.052497473 -0.27731472, -0.097879544 0.053940576 -0.27814925, -0.095852077 0.052446604 -0.27728522, 0.08791519 0.065387025 -0.28476745, 0.084019035 0.051886842 -0.27696091, -0.088607565 0.064244345 -0.28410715, -0.085253529 0.052446637 -0.27728522, -0.084894516 0.052408878 -0.27726346, -0.088271827 0.064572349 -0.28429693, -0.084556423 0.052297983 -0.27719927, -0.089024179 0.063995346 -0.28396326, 0.091392457 0.066966921 -0.28568113, 0.091728136 0.066638947 -0.28549147, -0.08803656 0.064960465 -0.28452134, -0.084258914 0.05212019 -0.27709627, 0.09208452 0.065825373 -0.28502095, 0.091963403 0.066250928 -0.28526688, 0.090975836 0.06721589 -0.28582501, 0.090502456 0.067371309 -0.28591484, -0.089497544 0.063839957 -0.2838735, 0.089999922 0.067424119 -0.28594542, 0.089497343 0.067371301 -0.2859149, 0.089023978 0.067215934 -0.28582501, -0.087915391 0.065385863 -0.28476745, -0.084019065 0.051885795 -0.27696091, 0.088607281 0.066966996 -0.28568095, 0.088271618 0.066638932 -0.28549129, -0.090000093 0.063787103 -0.28384292, -0.087915435 0.065824255 -0.28502095, -0.090502679 0.063839912 -0.2838735, -0.091499664 -0.020845152 -0.2349038, -0.088036507 0.066249713 -0.285267, 0.088036366 0.066250905 -0.285267, -0.090976022 0.063995361 -0.28396326, -0.097996794 -0.013339415 -0.23924397, -0.09833248 -0.013667479 -0.23905431, -0.098749109 -0.013916403 -0.23891042, -0.091392606 0.064244233 -0.28410727, -0.090000078 0.063286483 -0.28470862, -0.089497544 0.06333942 -0.2847392, -0.089024171 0.063494727 -0.28482896, -0.088607527 0.063743785 -0.28497303, -0.088271879 0.064071789 -0.28516269, -0.088036522 0.064459816 -0.28538698, -0.087915376 0.064885393 -0.28563309, -0.087915361 0.065323636 -0.28588665, -0.088036567 0.065749124 -0.28613263, -0.088271856 0.06613718 -0.28635699, -0.088607527 0.066465184 -0.28654665, -0.089024208 0.066714182 -0.28669071, -0.089497492 0.066869564 -0.2867806, -0.090000108 0.066922404 -0.28681111, -0.09972503 -0.014625289 -0.23965569, -0.099222481 -0.014572412 -0.23968621, -0.098749168 -0.014417008 -0.23977612, -0.098332457 -0.014168113 -0.23992001, -0.097996771 -0.01384005 -0.24010973, -0.097761497 -0.013451993 -0.24033414, -0.097640336 -0.013026409 -0.24058031, -0.097640328 -0.012588114 -0.24083363, -0.097761527 -0.012162656 -0.2410797, -0.097996801 -0.011774622 -0.24130403, -0.09833248 -0.01144658 -0.24149381, -0.098749146 -0.011197612 -0.24163763, -0.099222541 -0.011042178 -0.24172755, -0.09972509 -0.010989398 -0.24175821, 0.099725798 -0.014624 -0.2396556, 0.10022846 -0.014571153 -0.23968627, 0.10070175 -0.014415771 -0.23977612, 0.10111843 -0.014166832 -0.23992006, 0.10145414 -0.013838798 -0.24010973, 0.1016894 -0.013450749 -0.2403342, 0.10181057 -0.013025127 -0.2405801, 0.10181054 -0.012586914 -0.24083351, 0.10168934 -0.012161367 -0.2410797, 0.10145411 -0.011773318 -0.24130403, 0.10111842 -0.011445321 -0.24149381, 0.10070177 -0.01119636 -0.24163757, 0.10022838 -0.011040971 -0.24172755, 0.09972579 -0.010988049 -0.24175821, 0.089999937 0.063287646 -0.28470862, 0.090502478 0.063340485 -0.28473914, 0.090975784 0.063495934 -0.28482896, 0.091392472 0.063744903 -0.28497303, 0.091728121 0.064072937 -0.28516269, 0.091963395 0.064461023 -0.28538698, 0.092084631 0.06488651 -0.28563309, 0.092084572 0.065324761 -0.28588665, 0.091963418 0.065750249 -0.28613257, 0.091728114 0.066138305 -0.28635699, 0.091392457 0.066466331 -0.28654665, 0.090975791 0.06671533 -0.28669059, 0.090502471 0.066870682 -0.28678054, 0.089999869 0.066923551 -0.28681111, 0.091500491 -0.021344565 -0.2357695, 0.08750049 -0.021344632 -0.2357695, 0.087500535 -0.021147609 -0.23475043, 0.087500542 -0.021466672 -0.23463242, 0.087500513 -0.021660961 -0.2356218, 0.087500483 -0.021796867 -0.23455153, 0.087500505 -0.021998107 -0.23553129, 0.087500468 -0.022345878 -0.23550092, 0.091500521 -0.022345878 -0.23550092, 0.091500521 -0.021796919 -0.23455153, -0.087499559 -0.021345742 -0.2357695, -0.091499619 -0.021345735 -0.2357695, -0.087499589 -0.021148726 -0.23475043, -0.087499619 -0.021662042 -0.2356218, -0.087499589 -0.021999225 -0.23553129, -0.087499604 -0.021467745 -0.23463257, -0.087499604 -0.022347011 -0.23550074, -0.087499589 -0.02179803 -0.23455153, -0.09149956 -0.021798089 -0.23455153, -0.091499642 -0.022347011 -0.23550074, -0.096608452 0.049348969 -0.27664924, -0.097362831 0.049300838 -0.27662128, -0.097721383 0.049203467 -0.2765649, -0.097938985 0.049098678 -0.27650452, -0.098157436 0.048930977 -0.27640748, -0.098331764 0.048712444 -0.27628112, -0.098456129 0.048459239 -0.27613467, -0.098547563 0.048132163 -0.27594554, -0.098596789 0.047803525 -0.27575547, -0.097840481 0.053863417 -0.27925968, -0.097870342 0.05315055 -0.27884746, -0.097795412 0.052806359 -0.27864826, -0.097685024 0.05257456 -0.27851439, -0.0975281 0.052379861 -0.27840185, -0.097316258 0.052218717 -0.27830863, -0.097086169 0.052107774 -0.27824438, -0.096827962 0.052028432 -0.2781986, -0.096342474 0.051957842 -0.27815765, -0.095852062 0.05194604 -0.27815092, -0.10364304 0.0073760748 -0.25237805, -0.10367286 0.0066632628 -0.25196582, -0.1035979 0.0063189566 -0.25176686, -0.1034876 0.0060873032 -0.25163287, -0.10333063 0.005892612 -0.25152022, -0.10311884 0.0057314336 -0.25142705, -0.1028888 0.0056205392 -0.25136298, -0.10263042 0.005541116 -0.25131696, -0.10214501 0.0054705217 -0.2512762, -0.10165454 0.0054586828 -0.25126928, -0.10241096 0.0028616488 -0.24976759, -0.1031654 0.0028135255 -0.24973966, -0.10352387 0.0027160943 -0.24968345, -0.10374162 0.0026114285 -0.24962287, -0.10396001 0.002443701 -0.24952589, -0.10413425 0.0022251904 -0.24939953, -0.10425877 0.0019721091 -0.24925308, -0.10435019 0.0016449392 -0.24906395, -0.10439944 0.0013162792 -0.2488739, -0.10679711 -0.017893001 -0.23776604, -0.10682692 -0.018605851 -0.23735388, -0.10675204 -0.018950075 -0.2371548, -0.10664168 -0.019181781 -0.23702089, -0.1064847 -0.019376494 -0.2369083, -0.10627291 -0.019537657 -0.23681496, -0.10604286 -0.019648544 -0.23675089, -0.10578457 -0.019727908 -0.23670496, -0.10529906 -0.01979848 -0.23666416, -0.10480863 -0.019810326 -0.23665731, 0.10480952 -0.019808993 -0.23665731, 0.10563139 -0.01975812 -0.23668678, 0.10601868 -0.019656613 -0.2367454, 0.10627304 -0.019536801 -0.23681472, 0.10647973 -0.019380741 -0.23690493, 0.1066421 -0.019181192 -0.23702039, 0.10674474 -0.018971249 -0.23714177, 0.10680817 -0.018740453 -0.23727532, 0.10683698 -0.018315017 -0.23752128, 0.10679791 -0.017891616 -0.23776613, 0.10364355 0.0073773637 -0.25237805, 0.10368259 0.0069539994 -0.25213325, 0.10365374 0.0065286309 -0.25188726, 0.10359032 0.0062977821 -0.25175387, 0.10348765 0.0060879141 -0.25163239, 0.10332531 0.0058882684 -0.251517, 0.10311858 0.0057322457 -0.25142688, 0.10286433 0.0056123212 -0.25135744, 0.10247693 0.0055109337 -0.25129884, 0.10165514 0.0054599643 -0.25126928, 0.10440005 0.0013175756 -0.24887399, 0.10426366 0.001961723 -0.2492464, 0.10411333 0.0022598356 -0.24941875, 0.10396966 0.0024359301 -0.24952067, 0.10375351 0.0026058629 -0.24961893, 0.10348392 0.0027324036 -0.24969216, 0.10317978 0.0028123707 -0.24973826, 0.10279433 0.0028558448 -0.24976359, 0.10241152 0.0028629601 -0.24976765, 0.098596901 0.047804821 -0.27575547, 0.098460525 0.048448969 -0.27612799, 0.098310202 0.048747048 -0.27630037, 0.098166525 0.048923209 -0.27640229, 0.097950414 0.049093109 -0.2765004, 0.097680755 0.049219679 -0.2765736, 0.0973766 0.049299605 -0.27661985, 0.096991174 0.049343113 -0.276645, 0.096608445 0.04935018 -0.27664924, 0.097840391 0.053864639 -0.27925968, 0.09787941 0.053441238 -0.27901489, 0.097850606 0.053015869 -0.27876884, 0.097787172 0.052785084 -0.27863526, 0.097684518 0.052575123 -0.27851391, 0.097522125 0.052375477 -0.27839845, 0.097315401 0.052219495 -0.27830833, 0.097061127 0.052099559 -0.27823901, 0.096673854 0.051998079 -0.2781803, 0.09585198 0.051947206 -0.27815074, 0.091500483 -0.021978714 -0.23452349, -0.091499567 -0.022347115 -0.23450087, 0.091500498 -0.022345886 -0.23450087, 0.091500506 -0.022161968 -0.23450659, -0.091499589 -0.022163182 -0.23450641, -0.091499597 -0.021979898 -0.23452334, 0.081079781 -0.023977265 -0.23450093, 0.081422672 -0.024280973 -0.23450093, 0.081682868 -0.024657972 -0.23450093, 0.080674283 -0.023764417 -0.23450093, 0.081845328 -0.025086217 -0.23450093, 0.080229528 -0.023654833 -0.23450093, 0.081900507 -0.025540948 -0.23450093, 0.091500603 -0.033540905 -0.23450153, 0.079771459 -0.023654804 -0.23450087, 0.090806633 -0.035295382 -0.23450153, 0.091224819 -0.034896791 -0.23450153, 0.091347277 -0.034655549 -0.23450153, 0.091043785 -0.035118595 -0.23450153, 0.090525605 -0.035420462 -0.2345017, 0.091449916 -0.034294941 -0.23450147, 0.090017319 -0.0355234 -0.23450153, 0.089500614 -0.035540909 -0.2345017, 0.081900492 -0.031540915 -0.23450147, 0.081845306 -0.031995632 -0.23450147, 0.081682891 -0.032423891 -0.23450147, 0.081422724 -0.032800831 -0.23450147, 0.081079878 -0.033104606 -0.23450147, 0.080674328 -0.033317499 -0.23450147, 0.080229536 -0.033427067 -0.23450147, 0.079771563 -0.033427104 -0.23450147, 0.0012729429 -0.024414122 -0.23450093, 0.078318104 -0.02465795 -0.23450093, 0.078578353 -0.024281017 -0.23450093, 0.00096615031 -0.024142355 -0.23450093, 0.078921139 -0.02397725 -0.23450093, 0.0015057102 -0.02475141 -0.23450093, 0.078155719 -0.025086224 -0.23450093, 0.00060331821 -0.023951933 -0.23450087, 0.079326779 -0.023764461 -0.23450093, 0.0016510561 -0.025134608 -0.23450093, 0.078100488 -0.025540948 -0.23450093, 0.00020537153 -0.023853838 -0.23450093, 0.0017005093 -0.025541469 -0.23450099, 0.0017004907 -0.031541437 -0.23450147, 0.078100532 -0.031540923 -0.23450132, 0.0016511194 -0.031948283 -0.23450132, 0.078155771 -0.031995624 -0.23450147, 0.0015057884 -0.032331482 -0.23450147, 0.078318179 -0.032423951 -0.23450147, 0.0012729652 -0.03266874 -0.23450132, 0.078578413 -0.032800913 -0.23450147, 0.00096624717 -0.032940514 -0.23450147, 0.078921251 -0.033104621 -0.23450147, 0.00060337409 -0.033130981 -0.23450147, 0.079326853 -0.033317506 -0.23450147, -0.078577347 -0.024282001 -0.23450087, -0.0012719594 -0.024414144 -0.23450093, -0.00096521527 -0.024142385 -0.23450093, -0.07892023 -0.023978263 -0.23450087, -0.00060235336 -0.023951977 -0.23450087, -0.078317188 -0.024658971 -0.23450087, -0.0015047491 -0.024751492 -0.23450093, -0.07932584 -0.023765415 -0.23450087, -0.0002043806 -0.023853883 -0.23450087, -0.078154773 -0.025087245 -0.23450087, -0.0016501173 -0.025134683 -0.23450093, -0.079770558 -0.023655817 -0.23450093, -0.078099504 -0.025541998 -0.23450093, -0.0016995408 -0.025541462 -0.23450093, -0.078099519 -0.031541966 -0.23450132, -0.0016994849 -0.031541467 -0.23450132, -0.0016501062 -0.031948328 -0.23450147, -0.078154728 -0.03199663 -0.23450147, -0.0015047491 -0.032331519 -0.23450147, -0.078317165 -0.032424942 -0.23450147, -0.0012719706 -0.032668754 -0.23450147, -0.07857734 -0.032801896 -0.23450147, -0.00096518174 -0.032940537 -0.23450147, -0.078920178 -0.033105634 -0.23450147, -0.00060227886 -0.033130996 -0.23450147, -0.07932578 -0.033318542 -0.23450147, -0.081899486 -0.025542043 -0.23450099, -0.081844315 -0.02508729 -0.23450093, -0.081681944 -0.024658993 -0.23450093, -0.081421696 -0.024282038 -0.23450093, -0.081078857 -0.023978353 -0.23450087, -0.080673277 -0.023765437 -0.23450093, -0.080228537 -0.023655877 -0.23450087, -0.089499496 -0.035542056 -0.23450153, -0.079770476 -0.03342814 -0.23450147, -0.080228522 -0.03342814 -0.23450147, -0.08067321 -0.033318512 -0.23450147, -0.081078783 -0.033105671 -0.23450147, -0.081421658 -0.032801956 -0.23450147, -0.081681877 -0.032424927 -0.23450147, -0.081844307 -0.031996705 -0.23450132, -0.081899568 -0.031541973 -0.23450147, -0.091499485 -0.033542052 -0.23450147, -0.091482021 -0.034058765 -0.23450147, -0.090253577 -0.035491385 -0.2345017, -0.091379076 -0.034567103 -0.23450153, -0.090614133 -0.035388745 -0.23450153, -0.091253951 -0.034848124 -0.23450153, -0.09085542 -0.03526631 -0.23450153, -0.091077253 -0.035085306 -0.2345017, 0.00020543486 -0.033229068 -0.23450147, -0.0002043508 -0.033229113 -0.23450147, -0.089499474 -0.035542026 -0.2355016, -0.090016216 -0.035524525 -0.2355016, -0.090524495 -0.035421595 -0.2355016, -0.090805538 -0.035296507 -0.23550145, -0.091042697 -0.035119787 -0.2355016, -0.091223739 -0.034897946 -0.2355016, -0.091346219 -0.034656659 -0.23550145, -0.091448791 -0.03429611 -0.23550145, -0.09149956 -0.033542 -0.23550136, 0.091500603 -0.033540905 -0.23550145, 0.091483109 -0.034057587 -0.23550145, 0.091380179 -0.034565918 -0.23550145, 0.091255091 -0.034846917 -0.23550145, 0.091078237 -0.035084084 -0.23550145, 0.090856522 -0.035265103 -0.2355016, 0.090615228 -0.035387605 -0.2355016, 0.09025462 -0.03549017 -0.23550145, 0.089500576 -0.035540849 -0.2355016, -0.091392636 0.06374377 -0.28497285, -0.090975963 0.063494682 -0.28482896, -0.091499619 -0.01981023 -0.23665731, -0.091728359 0.064071804 -0.28516269, -0.091963641 0.064459853 -0.28538698, -0.092084743 0.064885363 -0.28563315, -0.10022759 -0.014572442 -0.23968621, -0.090502597 0.066869527 -0.2867806, -0.090976037 0.066714168 -0.28669071, -0.091392651 0.066465192 -0.28654665, 0.088271596 0.066138282 -0.28635699, -0.100701 -0.014416978 -0.23977612, 0.099223271 -0.01457116 -0.23968621, -0.091728374 0.066137165 -0.28635716, -0.091963649 0.065749094 -0.28613257, -0.09208478 0.065323576 -0.28588665, 0.091500528 -0.019809127 -0.23665731, 0.098749891 -0.014415748 -0.23977612, 0.098333232 -0.014166765 -0.23992001, -0.10111763 -0.014168076 -0.23992001, 0.097997591 -0.013838798 -0.24010967, 0.097762279 -0.013450742 -0.24033414, 0.097641148 -0.013025187 -0.24058031, -0.10145332 -0.01384002 -0.24010973, 0.097641148 -0.012586921 -0.24083363, -0.10168856 -0.013452016 -0.24033411, 0.097762279 -0.012161344 -0.24107961, -0.10180973 -0.013026454 -0.24058031, -0.10180975 -0.012588181 -0.24083363, 0.099223241 -0.011040941 -0.24172755, -0.10168853 -0.012162715 -0.24107961, -0.090061329 0.0031882524 -0.24995641, -0.089821555 0.0034225583 -0.25009185, -0.090358995 0.0030104145 -0.24985357, -0.089653559 0.0036997497 -0.25025213, -0.090697072 0.0028994605 -0.24978943, -0.089567028 0.0040037334 -0.2504279, 0.08956755 0.0040048808 -0.2504279, -0.091056041 0.002861701 -0.24976759, -0.089566976 0.0043167844 -0.25060898, 0.089567579 0.0043178648 -0.25060886, 0.083850935 0.050188173 -0.27713382, 0.098749913 -0.01119633 -0.24163763, 0.09105663 0.0028629228 -0.24976765, 0.098333299 -0.011445314 -0.24149381, 0.097997606 -0.011773378 -0.24130403, 0.090697631 0.0029006526 -0.24978937, 0.090359569 0.0030116141 -0.24985357, 0.090061918 0.0031894892 -0.24995656, 0.089822114 0.0034237653 -0.25009185, 0.089654148 0.0037009194 -0.25025213, 0.09105669 0.0054599345 -0.25126928, -0.10022762 -0.011042222 -0.24172755, -0.10070099 -0.011197641 -0.24163757, -0.10111765 -0.011446513 -0.24149369, -0.10145333 -0.011774637 -0.24130403, -0.091056131 0.0054588169 -0.25126928, -0.090061344 0.0051321909 -0.25108057, -0.084258839 0.049675591 -0.27683783, -0.089821562 0.0048978329 -0.25094491, 0.085253485 0.049350049 -0.27664924, 0.090697661 0.0054222345 -0.25124747, -0.084019057 0.049909923 -0.27697337, -0.089653529 0.0046206713 -0.2507847, 0.084894553 0.049387891 -0.27667087, 0.090359569 0.005311206 -0.25118333, 0.084556416 0.049498845 -0.27673513, -0.090358898 0.0053100139 -0.25118333, -0.084556445 0.04949782 -0.27673513, 0.090061925 0.0051334053 -0.25108039, -0.08385098 0.050187092 -0.27713364, 0.089822151 0.0048990399 -0.25094503, 0.08425878 0.049676698 -0.276838, 0.083764449 0.050492089 -0.27730948, 0.089654103 0.0046217889 -0.2507847, 0.08401902 0.049911011 -0.27697337, -0.09069708 0.0054210424 -0.25124758, -0.084894508 0.049386777 -0.27667087, -0.083764419 0.050491013 -0.27730948, -0.085253537 0.049349107 -0.27664924, -0.083764374 0.050804064 -0.27749056, 0.083764404 0.050805166 -0.27749044, 0.083850943 0.051109094 -0.27766627, -0.08385092 0.051107954 -0.27766627, 0.08791516 0.065324828 -0.28588665, 0.085253477 0.051947139 -0.27815092, 0.08949735 0.063340478 -0.2847392, 0.08902397 0.06349586 -0.28482908, 0.084894545 0.051909372 -0.2781291, 0.088607296 0.063744918 -0.28497303, 0.084556341 0.051798452 -0.27806497, 0.088271618 0.064072885 -0.28516269, 0.088036343 0.06446097 -0.28538698, 0.084258728 0.051620647 -0.27796191, 0.084018983 0.051386315 -0.27782661, 0.087915227 0.064886488 -0.28563315, -0.085253544 0.051946044 -0.27815092, -0.084894583 0.051908351 -0.2781291, -0.084556416 0.051797368 -0.27806497, -0.084258825 0.051619537 -0.27796209, 0.089497343 0.066870674 -0.28678054, 0.089023933 0.066715285 -0.28669059, 0.088607341 0.066466346 -0.28654665, -0.084019005 0.051385205 -0.27782661, -0.09050262 0.063339293 -0.2847392, 0.088036366 0.065750226 -0.28613257, 0.081422672 -0.02428095 -0.23550092, 0.081079789 -0.023977213 -0.23550092, 0.081682943 -0.024657972 -0.23550092, 0.080674231 -0.023764327 -0.23550092, 0.081845306 -0.025086164 -0.23550092, 0.080229513 -0.023654751 -0.23550092, 0.0819005 -0.025540918 -0.23550092, 0.079771429 -0.023654789 -0.23550092, 0.081900537 -0.031540908 -0.23550136, 0.081845313 -0.031995587 -0.23550139, 0.081682928 -0.032423906 -0.23550139, 0.081422724 -0.032800831 -0.23550139, 0.081079856 -0.033104613 -0.23550139, 0.080674358 -0.033317469 -0.23550139, 0.080229573 -0.033427052 -0.23550139, 0.079771534 -0.033427037 -0.23550139, 0.078318104 -0.024657913 -0.23550092, 0.0012729876 -0.024414137 -0.23550092, 0.078578383 -0.02428104 -0.23550092, 0.00096616521 -0.024142332 -0.23550092, 0.078921147 -0.023977213 -0.23550092, 0.078155674 -0.025086164 -0.23550092, 0.00150574 -0.02475141 -0.23550092, 0.00060326606 -0.023951888 -0.23550092, 0.079326756 -0.023764394 -0.23550092, 0.078100532 -0.025540926 -0.23550092, 0.0016511194 -0.025134623 -0.23550092, 0.00020534173 -0.023853771 -0.23550092, 0.0017005168 -0.025541455 -0.23550098, 0.078100532 -0.031540923 -0.23550136, 0.0017005131 -0.031541437 -0.23550136, 0.0016511343 -0.031948254 -0.23550136, 0.078155771 -0.031995624 -0.23550136, 0.078318186 -0.032423899 -0.23550139, 0.0015057847 -0.032331437 -0.23550136, 0.078578413 -0.032800913 -0.23550139, 0.0012729727 -0.032668725 -0.23550139, 0.078921236 -0.033104606 -0.23550136, 0.00096622109 -0.032940447 -0.23550145, 0.079326823 -0.033317477 -0.23550139, 0.00060335174 -0.033130944 -0.23550136, -0.0012719817 -0.024414122 -0.23550092, -0.078577414 -0.024281949 -0.23550092, -0.00096523389 -0.024142399 -0.23550092, -0.07892023 -0.023978263 -0.23550092, -0.00060237199 -0.023951903 -0.23550092, -0.078317188 -0.024658971 -0.23550092, -0.0015047938 -0.02475144 -0.23550092, -0.079325803 -0.023765385 -0.23550092, -0.00020450726 -0.023853779 -0.23550092, -0.078154735 -0.025087215 -0.23550092, -0.0016501434 -0.025134586 -0.23550092, -0.079770505 -0.023655854 -0.23550092, -0.078099564 -0.025541939 -0.23550113, -0.0016995631 -0.025541387 -0.23550098, -0.078099541 -0.031541944 -0.23550139, -0.0016994737 -0.031541459 -0.23550136, -0.0016500764 -0.031948298 -0.23550127, -0.081899501 -0.025541946 -0.23550098, -0.081844345 -0.025087222 -0.23550098, -0.081681974 -0.024658911 -0.23550092, -0.081421681 -0.024282016 -0.23550092, -0.081078902 -0.023978278 -0.23550092, -0.080673292 -0.023765363 -0.23550092, -0.080228604 -0.023655824 -0.23550092, -0.0015047491 -0.032331519 -0.23550127, -0.078154728 -0.03199663 -0.23550136, -0.0012719221 -0.032668762 -0.23550127, -0.078317091 -0.032424957 -0.23550139, -0.00096519291 -0.032940492 -0.23550145, -0.078577347 -0.032801829 -0.23550136, -0.00060227513 -0.033130966 -0.23550139, -0.078920215 -0.033105597 -0.23550136, -0.079325765 -0.033318475 -0.23550145, -0.081899472 -0.031541966 -0.23550127, -0.079770476 -0.033428118 -0.23550145, -0.080228522 -0.033428133 -0.23550145, -0.08067321 -0.033318512 -0.23550145, -0.081078827 -0.033105657 -0.23550145, -0.081421651 -0.032801881 -0.23550145, -0.081681855 -0.032424927 -0.23550136, -0.081844248 -0.031996645 -0.23550139, 0.00020543113 -0.033229053 -0.23550145, -0.0002043508 -0.033229068 -0.23550145, 0.46352085 0.15545234 -0.070548728, 0.46307001 0.15545239 -0.070719823, 0.46267334 0.15545246 -0.070993796, 0.4623535 0.15545242 -0.071354643, 0.46212944 0.1554524 -0.071781501, 0.4620142 0.15545245 -0.072249636, 0.46201417 0.1554524 -0.072731838, 0.46212956 0.15545252 -0.073200002, 0.46235359 0.1554525 -0.073626801, 0.46267334 0.15545252 -0.073987678, 0.46307006 0.15545253 -0.07426165, 0.46352085 0.15545253 -0.074432597, -0.4644796 0.15544638 -0.070548788, -0.46493039 0.15544638 -0.070719734, -0.46532717 0.15544647 -0.070993736, -0.46564689 0.15544648 -0.071354493, -0.46587083 0.15544644 -0.071781442, -0.46598622 0.15544644 -0.072249636, -0.46598622 0.15544644 -0.072731748, -0.46587101 0.15544662 -0.073200092, -0.46564683 0.15544654 -0.07362707, -0.46532717 0.15544666 -0.073987678, -0.46493039 0.1554466 -0.07426165, -0.46447954 0.15544665 -0.074432597, 0.45799956 0.15545031 -0.035240784, 0.4577004 0.15545031 -0.035277143, 0.45741859 0.15545036 -0.035383955, 0.45717061 0.15545031 -0.035555139, 0.45697084 0.15545031 -0.035780683, 0.45683071 0.15545045 -0.036047474, 0.45675859 0.15545051 -0.036340043, 0.45675859 0.15545051 -0.036641374, 0.45683071 0.15545045 -0.036933914, 0.45697078 0.15545043 -0.037200823, 0.45717058 0.15545049 -0.037426487, 0.45741856 0.15545057 -0.037597552, 0.4577004 0.15545049 -0.037704483, 0.45799953 0.15545055 -0.037740603, 0.47799954 0.15545473 -0.11024071, 0.47770032 0.15545467 -0.11027716, 0.47741863 0.15545465 -0.11038397, 0.47717068 0.15545465 -0.11055516, 0.47697076 0.15545468 -0.11078067, 0.47683075 0.15545467 -0.1110474, 0.47675863 0.15545478 -0.11134003, 0.47675863 0.15545478 -0.11164139, 0.47683081 0.15545484 -0.11193429, 0.47697082 0.15545478 -0.11220084, 0.47717068 0.15545478 -0.11242644, 0.47741863 0.15545484 -0.11259754, 0.47770038 0.15545484 -0.11270444, 0.47799954 0.15545484 -0.11274074, 0.47549957 0.13875912 -0.16812573, -0.47550076 0.13875289 -0.16812573, -0.47800085 0.15544875 -0.11274098, -0.47770181 0.15544869 -0.11270444, -0.47742 0.15544865 -0.11259745, -0.47717187 0.15544865 -0.11242644, -0.47697207 0.15544865 -0.11220087, -0.47683218 0.15544865 -0.11193405, -0.47675988 0.15544859 -0.11164148, -0.47675988 0.15544859 -0.11134027, -0.47683218 0.15544853 -0.11104761, -0.47697213 0.15544851 -0.11078082, -0.47717187 0.15544854 -0.11055516, -0.47741994 0.15544857 -0.11038397, -0.47770181 0.1554486 -0.11027716, -0.47800091 0.15544853 -0.11024056, -0.45800075 0.15544458 -0.037740722, -0.45770168 0.15544458 -0.037704363, -0.45741996 0.15544455 -0.037597373, -0.45717195 0.15544464 -0.037426367, -0.45697212 0.15544458 -0.037200853, -0.45683214 0.15544455 -0.036933914, -0.45676008 0.15544464 -0.036641374, -0.45676002 0.15544447 -0.036340013, -0.45683205 0.15544452 -0.036047593, -0.45697212 0.15544447 -0.035780683, -0.4571721 0.15544452 -0.035555139, -0.45742014 0.15544458 -0.035383955, -0.45770165 0.1554445 -0.035276994, -0.45800084 0.15544444 -0.035240665, 0.39749947 0.15444107 0.12200929, 0.40249959 0.15444103 0.12200929, 0.39702079 0.15444107 0.12206747, 0.39657006 0.15444107 0.12223823, 0.39617327 0.15444101 0.12251236, 0.39585343 0.154441 0.1228732, 0.3956295 0.154441 0.12330009, 0.39551404 0.15444101 0.12376834, 0.3955141 0.154441 0.1242504, 0.39562944 0.15444101 0.12471865, 0.39585349 0.15444086 0.12514542, 0.39617327 0.15444076 0.12550639, 0.39657006 0.15444078 0.12578018, 0.39702085 0.15444084 0.12595113, 0.39749953 0.15444078 0.12600936, 0.40249947 0.15444082 0.12600945, 0.40297809 0.15444082 0.12595128, 0.40342894 0.15444086 0.12578033, 0.40382567 0.15444089 0.12550639, 0.40414539 0.15444092 0.12514542, 0.4043695 0.15444103 0.12471856, 0.4044849 0.154441 0.12425052, 0.40448484 0.15444103 0.12376823, 0.4043695 0.15444103 0.12330009, 0.40414545 0.15444112 0.1228732, 0.40382573 0.15444109 0.12251221, 0.40342894 0.15444106 0.12223853, 0.40297815 0.15444109 0.12206759, 0.28249952 0.15444024 0.12200929, 0.2874994 0.15444037 0.12200929, 0.28202081 0.15444031 0.12206747, 0.28157005 0.15444024 0.12223841, 0.28117326 0.15444031 0.12251221, 0.28085342 0.15444031 0.12287329, 0.28062943 0.15444025 0.12330009, 0.28051409 0.15444019 0.12376823, 0.28051409 0.15444019 0.1242504, 0.28062949 0.15444016 0.12471865, 0.28085351 0.15444005 0.12514542, 0.28117332 0.15444003 0.12550639, 0.28157002 0.15444005 0.12578033, 0.28202084 0.15444002 0.12595128, 0.28249943 0.15444005 0.12600945, 0.28749958 0.15444003 0.12600936, 0.28797802 0.15444016 0.12595113, 0.28842893 0.15444013 0.12578018, 0.28882575 0.15444005 0.12550654, 0.28914547 0.15444008 0.12514542, 0.28936955 0.15444022 0.12471856, 0.28948486 0.15444028 0.12425028, 0.28948483 0.15444037 0.12376808, 0.28936952 0.15444022 0.12330009, 0.28914538 0.15444034 0.1228732, 0.28882569 0.15444034 0.12251236, 0.28842878 0.15444043 0.12223823, 0.28797802 0.15444046 0.12206729, 0.18749936 0.15443973 0.12200929, 0.19249934 0.15443973 0.12200929, 0.18702066 0.15443975 0.12206747, 0.18656987 0.15443975 0.12223841, 0.18617316 0.15443964 0.12251236, 0.18585344 0.15443964 0.12287329, 0.18562926 0.15443973 0.12330009, 0.18551399 0.15443964 0.12376823, 0.18551394 0.15443964 0.12425052, 0.18562946 0.15443957 0.12471856, 0.18585353 0.15443943 0.12514542, 0.1861732 0.15443939 0.12550654, 0.18656999 0.15443939 0.12578018, 0.1870207 0.1544394 0.12595113, 0.18749943 0.15443946 0.12600936, 0.19249938 0.15443949 0.12600936, 0.19297808 0.15443942 0.12595095, 0.19342881 0.15443943 0.12578018, 0.19382569 0.15443943 0.12550639, 0.19414538 0.15443945 0.12514542, 0.19436941 0.15443969 0.12471865, 0.19448483 0.15443963 0.1242504, 0.19448477 0.15443967 0.12376808, 0.19436941 0.15443969 0.12330009, 0.19414541 0.15443967 0.12287329, 0.19382572 0.15443967 0.12251236, 0.1934289 0.1544397 0.12223853, 0.19297805 0.15443975 0.12206759, 0.15349936 0.15443954 0.12200929, 0.15849935 0.15443954 0.12200929, 0.15302071 0.15443955 0.12206747, 0.15256989 0.15443954 0.12223841, 0.15217316 0.15443942 0.12251212, 0.15185335 0.15443954 0.1228732, 0.15162933 0.15443945 0.12330009, 0.15151396 0.15443939 0.12376834, 0.15151393 0.15443942 0.1242504, 0.15162939 0.1544393 0.12471856, 0.15185341 0.1544393 0.12514542, 0.15217316 0.15443926 0.12550639, 0.15256993 0.15443918 0.12578, 0.15302074 0.15443926 0.12595113, 0.15349941 0.15443926 0.12600945, 0.15849943 0.15443923 0.12600915, 0.15897799 0.15443929 0.12595113, 0.15942881 0.15443935 0.12578018, 0.15982565 0.15443924 0.12550639, 0.16014536 0.15443933 0.12514542, 0.16036946 0.15443942 0.12471832, 0.16048494 0.15443942 0.12425052, 0.16048479 0.15443948 0.12376823, 0.16036946 0.15443942 0.12330009, 0.16014528 0.15443954 0.1228732, 0.15982565 0.15443948 0.12251221, 0.15942883 0.15443948 0.12223841, 0.15897799 0.15443954 0.12206759, -0.15350077 0.15443729 0.12600936, -0.15850079 0.15443727 0.12600945, -0.15302214 0.15443727 0.12595128, -0.15257129 0.15443729 0.12578033, -0.15217456 0.15443729 0.12550654, -0.15185484 0.15443732 0.12514542, -0.15163073 0.15443747 0.12471856, -0.15151533 0.15443742 0.1242504, -0.15151533 0.1544375 0.12376834, -0.15163076 0.15443751 0.12330009, -0.15185487 0.15443754 0.1228732, -0.15217462 0.15443759 0.12251221, -0.15257123 0.15443747 0.12223841, -0.15302211 0.15443745 0.12206747, -0.15350077 0.15443753 0.12200929, -0.1585007 0.15443745 0.12200929, -0.15897942 0.15443751 0.12206747, -0.15943024 0.15443751 0.12223853, -0.15982702 0.15443748 0.12251221, -0.16014674 0.15443748 0.1228732, -0.16037089 0.15443754 0.12330009, -0.16048615 0.15443736 0.12376823, -0.16048619 0.15443742 0.1242504, -0.16037074 0.15443736 0.12471865, -0.16014674 0.15443723 0.12514542, -0.15982702 0.15443724 0.12550639, -0.15943012 0.15443718 0.12578018, -0.15897942 0.1544373 0.12595113, -0.19250073 0.15443701 0.12600936, -0.18750077 0.15443711 0.12600945, -0.18702221 0.15443718 0.12595113, -0.18657133 0.15443708 0.12578033, -0.18617454 0.15443707 0.12550639, -0.18585482 0.15443707 0.12514542, -0.18563072 0.1544372 0.12471865, -0.18551533 0.1544372 0.1242504, -0.18551533 0.1544372 0.12376823, -0.18563077 0.15443727 0.12329994, -0.18585482 0.15443733 0.1228732, -0.18617457 0.15443727 0.12251212, -0.18657136 0.15443732 0.12223841, -0.18702213 0.1544373 0.12206747, -0.18750075 0.15443724 0.12200929, -0.19250073 0.15443723 0.12200929, -0.19297943 0.15443729 0.12206747, -0.19343022 0.15443726 0.12223841, -0.19382705 0.1544373 0.12251221, -0.19414678 0.1544373 0.12287296, -0.19437075 0.15443715 0.12330009, -0.1944862 0.15443723 0.12376834, -0.19448617 0.15443715 0.12425052, -0.19437084 0.15443721 0.12471865, -0.19414672 0.15443709 0.12514542, -0.19382697 0.15443701 0.12550639, -0.19343024 0.15443708 0.12578018, -0.19297943 0.15443709 0.12595113, -0.2825008 0.15443644 0.12600936, -0.2875008 0.15443641 0.12600945, -0.28202224 0.15443656 0.12595113, -0.28157145 0.15443654 0.12578018, -0.28117457 0.1544365 0.12550639, -0.28085485 0.15443647 0.12514542, -0.28063077 0.15443663 0.12471856, -0.28051537 0.15443663 0.1242504, -0.28051537 0.15443663 0.12376823, -0.28063071 0.15443668 0.12330009, -0.28085482 0.15443663 0.1228732, -0.2811746 0.15443671 0.12251236, -0.28157133 0.15443668 0.12223841, -0.28202218 0.15443662 0.12206747, -0.2825008 0.15443674 0.12200929, -0.2875008 0.15443662 0.12200908, -0.28797948 0.15443666 0.12206747, -0.2884303 0.15443671 0.12223841, -0.28882712 0.15443668 0.12251221, -0.28914678 0.15443662 0.1228732, -0.28937083 0.15443662 0.12330009, -0.28948617 0.15443659 0.12376823, -0.28948623 0.15443654 0.1242504, -0.28937083 0.15443662 0.12471856, -0.28914675 0.15443647 0.12514542, -0.28882709 0.15443651 0.12550654, -0.28843021 0.15443639 0.12578, -0.28797945 0.15443647 0.12595128, -0.40250096 0.15443574 0.12600936, -0.39750084 0.15443572 0.12600936, -0.39702228 0.15443569 0.12595113, -0.39657143 0.15443566 0.12578033, -0.39617464 0.15443574 0.12550639, -0.39585492 0.15443574 0.12514542, -0.39563081 0.1544359 0.12471856, -0.3955155 0.15443595 0.1242504, -0.39551541 0.1544359 0.12376823, -0.39563081 0.1544359 0.12330009, -0.39585492 0.15443593 0.1228732, -0.3961747 0.15443596 0.12251212, -0.39657143 0.15443592 0.12223841, -0.39702231 0.15443596 0.12206747, -0.3975009 0.15443596 0.12200908, -0.40250084 0.15443584 0.12200929, -0.40297958 0.15443595 0.12206759, -0.40343043 0.15443599 0.12223841, -0.40382716 0.15443587 0.12251221, -0.40414688 0.15443586 0.12287296, -0.40437105 0.15443595 0.12330009, -0.40448624 0.15443583 0.12376834, -0.40448636 0.15443589 0.1242504, -0.40437099 0.15443583 0.12471856, -0.40414688 0.15443571 0.12514542, -0.40382719 0.15443575 0.12550639, -0.40343043 0.15443575 0.12578, -0.40297946 0.15443566 0.12595095, 0.0024993196 0.15443826 0.12600945, -0.0025006309 0.15443823 0.12600936, 0.0029779337 0.15443826 0.12595128, 0.0034287609 0.15443832 0.12578, 0.0038254634 0.15443838 0.12550639, 0.0041452162 0.15443838 0.12514542, 0.0043692663 0.1544385 0.12471856, 0.0044847205 0.15443851 0.12425052, 0.0044847205 0.15443851 0.12376834, 0.004369311 0.15443857 0.12330009, 0.004145246 0.15443853 0.1228732, 0.0038255267 0.15443853 0.12251221, 0.0034287386 0.15443856 0.12223853, 0.0029778294 0.15443861 0.12206759, 0.0024993308 0.1544385 0.12200929, -0.0025006719 0.1544385 0.12200929, -0.0029792301 0.15443845 0.12206747, -0.0034300461 0.15443844 0.12223841, -0.0038269684 0.15443848 0.12251221, -0.0041467026 0.15443851 0.1228732, -0.0043706968 0.15443839 0.12330009, -0.0044861026 0.15443839 0.12376808, -0.0044861026 0.15443839 0.1242504, -0.0043707602 0.15443836 0.12471856, -0.0041466989 0.15443833 0.12514542, -0.0038269833 0.1544383 0.12550639, -0.0034301504 0.15443835 0.12578, -0.0029793605 0.15443823 0.12595095, 0.48999956 0.155441 0.13403718, 0.48199955 0.15544094 0.13403709, 0.48199952 0.15441699 0.13434501, 0.48199949 0.15540512 0.13449897, 0.48199949 0.15434606 0.13464554, 0.48199952 0.15529867 0.13494985, 0.48199955 0.15422967 0.13493152, 0.48199949 0.1551241 0.13537879, 0.48199958 0.15400614 0.13537879, 0.48999956 0.15400618 0.13537879, 0.48999962 0.1551241 0.135379, -0.48200089 0.15543468 0.13403688, -0.49000084 0.15543464 0.13403709, -0.48200086 0.15422352 0.13493152, -0.48200086 0.15511805 0.13537879, -0.48200086 0.15433988 0.13464542, -0.48200086 0.15399988 0.13537879, -0.48200086 0.15529253 0.13494964, -0.4820008 0.15441085 0.13434501, -0.4820008 0.15539899 0.13449903, -0.49000087 0.15399994 0.13537879, -0.49000087 0.15511794 0.135379, -0.49000084 0.15543625 0.10733773, -0.48999509 0.15543629 0.10707904, -0.48997328 0.15543628 0.10686745, -0.48988661 0.15543628 0.10655661, -0.48976204 0.15543635 0.10632469, -0.48941514 0.15543631 0.10592355, -0.49000081 0.15543608 0.10825919, -0.48994529 0.15543607 0.10903634, -0.48984319 0.15543616 0.10938515, -0.48972002 0.15543605 0.10962303, -0.48956144 0.15543601 0.10982011, -0.48933747 0.15543613 0.1099958, -0.48906115 0.15543611 0.11012669, -0.48858765 0.15543605 0.11023183, -0.4880009 0.15543611 0.11025928, -0.49000087 0.15543579 0.11475946, -0.48998073 0.15543582 0.11424358, -0.48991439 0.15543593 0.11384679, -0.48983106 0.1554359 0.11360465, -0.48972014 0.1554359 0.11339532, -0.48956153 0.15543592 0.11319859, -0.48936489 0.15543601 0.11304031, -0.48912668 0.1554359 0.11291702, -0.48877773 0.1554359 0.11281483, -0.48800096 0.1554359 0.1127594, -0.4700008 0.1554402 0.039759204, -0.46997342 0.15544023 0.039172575, -0.4698683 0.15544018 0.038699046, -0.46973726 0.15544035 0.038422868, -0.46956161 0.15544024 0.038198546, -0.46936479 0.15544018 0.038040087, -0.46912655 0.1554402 0.037917003, -0.46877778 0.15544024 0.037814841, -0.46800086 0.15544032 0.037759379, -0.4680008 0.15544036 0.035259321, -0.46851656 0.15544046 0.035239235, -0.46891341 0.15544043 0.035172626, -0.4691554 0.15544038 0.035089478, -0.46936485 0.15544046 0.034978375, -0.46956143 0.15544052 0.034819797, -0.46971986 0.15544048 0.034623131, -0.46984318 0.15544039 0.03438513, -0.46994534 0.15544046 0.034036323, -0.47000089 0.15544054 0.033259317, 0.48799947 0.15544219 0.11275934, 0.48851523 0.15544219 0.11277969, 0.48891208 0.15544219 0.11284609, 0.48915419 0.15544213 0.11292906, 0.48936355 0.15544218 0.11304031, 0.48956022 0.1554421 0.11319874, 0.48971859 0.15544216 0.11339568, 0.48984179 0.15544215 0.11363353, 0.48994416 0.15544213 0.11398254, 0.48999956 0.15544209 0.11475946, 0.4879995 0.15544242 0.11025928, 0.48877648 0.15544227 0.11020373, 0.48912528 0.15544231 0.11010157, 0.48936337 0.15544242 0.10997842, 0.48956022 0.15544234 0.10981996, 0.48973605 0.1554424 0.109596, 0.489867 0.15544234 0.1093194, 0.48997197 0.15544243 0.10884602, 0.48999944 0.15544246 0.10825919, 0.48999944 0.15544258 0.10733767, 0.48996124 0.15544257 0.10680901, 0.4898853 0.15544263 0.10655661, 0.48972669 0.15544263 0.10627542, 0.48959282 0.15544261 0.1061108, 0.48941371 0.15544264 0.10592364, 0.46799955 0.15544625 0.037759289, 0.46851525 0.15544626 0.037779495, 0.46891215 0.15544625 0.037845895, 0.46915415 0.15544625 0.037928894, 0.46936354 0.15544625 0.038040087, 0.46956024 0.15544629 0.038198754, 0.46971861 0.15544626 0.038395569, 0.46984175 0.15544625 0.03863363, 0.46994406 0.15544631 0.038982436, 0.46999958 0.15544625 0.039759293, 0.46999952 0.15544656 0.033259317, 0.4699721 0.15544654 0.033846125, 0.4698669 0.15544654 0.034319505, 0.46973595 0.15544656 0.034595832, 0.46956024 0.15544644 0.034820005, 0.46936324 0.15544651 0.034978375, 0.46912524 0.15544651 0.035101667, 0.46877638 0.15544643 0.035203919, 0.46799949 0.15544656 0.03525947, 0.48349711 0.14932033 0.14474906, 0.48999968 0.13945164 0.16448356, 0.48824963 0.13856432 0.16625835, 0.48302367 0.14940064 0.14458869, 0.094072148 0.089268327 0.2648313, 0.094272122 0.089167267 0.26503295, 0.09285827 0.082397297 0.27857137, 0.48191482 0.1501191 0.14315198, 0.48203596 0.14989918 0.14359154, 0.13787611 0.11882024 0.20573609, 0.094520018 0.089090854 0.26518619, 0.093274914 0.082525924 0.27831417, 0.093748286 0.082606152 0.27815342, 0.48399958 0.14929309 0.14480363, 0.48191482 0.15034547 0.14269923, -0.12720901 0.11470415 0.21396415, -0.12687324 0.11453448 0.21430318, -0.1277058 0.11082108 0.22172894, -0.48981687 0.13893504 0.16550399, -0.48929337 0.13868542 0.16600357, -0.48949626 0.13874815 0.16587804, -0.48966074 0.138823 0.16572843, 0.093932241 0.089387648 0.26459259, 0.092522509 0.082227871 0.27891028, 0.092287436 0.082027242 0.27931112, 0.48450223 0.14932036 0.14474906, -0.48991629 0.13905595 0.16526268, -0.1264565 0.11440592 0.21456032, -0.48905215 0.13863495 0.16610439, 0.48497558 0.14940058 0.14458869, -0.48998228 0.13922854 0.16491733, -0.12744421 0.1149046 0.21356325, -0.13388613 0.11745954 0.20845406, -0.48825082 0.13855788 0.16625835, 0.094801903 0.089042932 0.26528186, 0.094250828 0.082633518 0.27809918, -0.49000072 0.13944545 0.16448341, -0.12598325 0.11432573 0.21472077, 0.48539212 0.14952926 0.14433132, 0.093860134 0.08951848 0.26433092, -0.48572907 0.14969246 0.14399244, -0.48539332 0.14952305 0.14433147, 0.011201756 0.088645086 0.26607651, 0.011201707 0.089573726 0.26421958, -0.48497668 0.14939438 0.1445886, -0.12756537 0.11512442 0.21312349, 0.48572782 0.14969864 0.14399244, -0.48596448 0.14989291 0.14359154, -0.4845033 0.14931408 0.14474906, -0.1254807 0.1142984 0.21477501, 0.095100939 0.089026779 0.26531416, 0.48596308 0.14989921 0.14359154, -0.11383907 0.10915229 0.22506614, -0.10896824 0.090694278 0.26197708, -0.12499931 0.10791388 0.22754262, 0.095226765 0.082525879 0.27831417, 0.094753407 0.082606196 0.2781536, -0.12315289 0.10915218 0.22506611, 0.093859993 0.089653306 0.26406145, 0.010820335 0.090486363 0.26239437, -0.48400089 0.14928693 0.14480384, -0.12756535 0.11535084 0.21267094, -0.11353996 0.10916854 0.22503363, -0.48349822 0.14931414 0.14474918, 0.093932234 0.089784138 0.26379973, 0.010070303 0.091352321 0.26066315, -0.12497802 0.1143257 0.21472062, -0.48302501 0.14939451 0.14458869, -0.12585948 0.11027035 0.22283016, 0.094072253 0.089903504 0.26356101, 0.0089774169 0.092141658 0.25908434, -0.48260841 0.14952303 0.14433147, -0.11325818 0.10921637 0.22493802, -0.095101528 0.09014371 0.26307815, -0.1274443 0.11557072 0.21223105, -0.48227265 0.14969255 0.14399256, 0.48203608 0.15056522 0.14225949, 0.094272122 0.090004347 0.26335937, 0.48450217 0.1511443 0.14110161, 0.48399943 0.15117149 0.14104725, -0.12450476 0.11440596 0.21456011, -0.4820374 0.14989303 0.14359139, 0.48349702 0.1511443 0.14110161, 0.48302361 0.15106405 0.14126255, 0.48260701 0.15093532 0.14151965, 0.48227128 0.1507659 0.14185832, -0.11301027 0.10929294 0.22478513, 0.48608419 0.15011904 0.14315175, 0.48608431 0.15034536 0.1426989, 0.48596314 0.15056524 0.14225958, -0.12720898 0.11577125 0.21182998, 0.48572785 0.15076593 0.14185859, 0.485392 0.15093538 0.14151965, 0.48497546 0.15106396 0.14126255, -0.13787705 0.11881859 0.20573609, -0.4845033 0.15113811 0.1411017, -0.48497671 0.15105769 0.14126255, -0.48539343 0.15092917 0.14151965, -0.48572913 0.15075968 0.14185832, -0.11281038 0.10939379 0.22458343, -0.094802327 0.090127483 0.2631107, -0.48596433 0.1505591 0.14225958, -0.4860855 0.15033925 0.1426989, -0.48608556 0.15011288 0.14315175, -0.12408809 0.1145345 0.21430303, 0.10626112 0.087788567 0.26779062, 0.09633556 0.081581026 0.2802037, 0.09633562 0.081807479 0.27975088, 0.096214429 0.082027324 0.27931112, -0.11267041 0.10951315 0.2243446, -0.094520643 0.090079673 0.2632063, 0.095979244 0.082227737 0.27891028, 0.095643423 0.082397312 0.27857137, 0.097110853 0.077959672 0.28744543, -0.12687331 0.11594071 0.21149115, 0.10441476 0.089026868 0.26531416, 0.10649942 0.088075265 0.26721698, -0.48400092 0.15116534 0.14104711, -0.4819161 0.15033923 0.14269899, -0.48203734 0.15055905 0.14225949, -0.1125982 0.10964398 0.22408293, -0.48227257 0.15075967 0.14185859, -0.48260823 0.1509292 0.14151956, -0.094272621 0.090003088 0.26335937, -0.48302501 0.15105781 0.14126228, 0.10538827 0.088994771 0.26537836, -0.48349816 0.15113802 0.1411017, 0.10661358 0.088383839 0.26659995, 0.10658199 0.088234589 0.26689851, 0.10588491 0.088922918 0.26552182, -0.11383915 0.11027043 0.22283016, 0.10659018 0.088525012 0.26631767, -0.12375243 0.11470412 0.213964, 0.1061891 0.088837929 0.26569194, 0.10637572 0.088751301 0.26586509, 0.10650866 0.088648774 0.26607019, -0.12645653 0.11606927 0.21123387, -0.095979676 0.081159562 0.28104424, -0.095643774 0.080989957 0.28138304, -0.097111426 0.077958427 0.28744543, -0.095227137 0.080861308 0.28164029, -0.096214846 0.081360012 0.28064334, -0.094753787 0.080781072 0.28180099, -0.093000226 0.07795836 0.28744543, -0.096336 0.081579834 0.2802037, -0.094251327 0.08075387 0.28185534, -0.12351717 0.11490465 0.2135631, 0.10837768 0.090287685 0.26279306, 0.10822187 0.090239644 0.26288909, 0.10792366 0.090182826 0.26300281, -0.12598327 0.1161496 0.21107335, -0.13438863 0.11787128 0.20763047, -0.12339596 0.11512448 0.21312343, -0.11353998 0.11025418 0.22286285, 0.10862682 0.090405136 0.26255822, -0.093748659 0.080781087 0.28180099, 0.10755739 0.090152383 0.26306379, -0.12548068 0.11617696 0.2110187, -0.13507234 0.11822715 0.20691882, 0.10896763 0.090695679 0.26197708, 0.10712139 0.090145037 0.26307815, 0.095101036 0.09014485 0.26307815, -0.093275405 0.080861375 0.28164029, -0.12339596 0.11535089 0.21267094, -0.11325821 0.11020641 0.22295825, -0.12497804 0.11614961 0.21107335, -0.13590686 0.11851135 0.20635043, -0.12351712 0.11557071 0.21223088, -0.11301029 0.11012988 0.22311138, -0.092858687 0.080990002 0.28138304, -0.12450479 0.11606932 0.21123402, 0.11280958 0.1093953 0.22458328, 0.11300949 0.10929438 0.22478513, 0.09480188 0.09012866 0.2631107, -0.12375237 0.11577125 0.21182998, -0.092523009 0.081159495 0.28104424, 0.11325745 0.10921785 0.22493817, 0.11266954 0.10951455 0.2243446, -0.092287809 0.081360005 0.28064334, 0.094520055 0.090080887 0.2632063, -0.10626172 0.087787181 0.26779062, -0.095227182 0.082524635 0.27831417, -0.095643833 0.082396008 0.27857137, -0.095979519 0.082226485 0.27891028, -0.096214861 0.082026124 0.27931118, -0.096335918 0.081806213 0.27975094, -0.008977918 0.086076953 0.27121192, -0.0075793061 0.085390821 0.27258396, -0.093000308 0.077116653 0.28912908, 0.11353922 0.10917005 0.22503363, 0.11259748 0.10964541 0.22408293, -0.092166647 0.081579819 0.28020346, -0.0059225154 0.084831052 0.27370286, -0.010070791 0.086866289 0.26963311, 0.11383829 0.10915384 0.22506614, 0.11259748 0.10978015 0.22381334, 0.0075788326 0.092827789 0.25771201, -0.0040641609 0.084417291 0.27453065, -0.010820816 0.087732278 0.26790148, -0.092166558 0.081806242 0.27975088, 0.1126696 0.10991105 0.22355174, 0.0059220511 0.09338735 0.25659311, 0.0040636212 0.09380132 0.25576544, 0.11280963 0.11003037 0.22331299, 0.0020668767 0.094055369 0.25525731, -0.0020674337 0.084163263 0.2750386, -0.011202278 0.088644944 0.26607651, -0.092287779 0.082026139 0.27931112, -0.093860611 0.08951728 0.2643311, 0.1130095 0.11013129 0.22311138, -1.9371438e-07 0.084077567 0.27521002, -0.011202207 0.089573495 0.26421976, -0.093860626 0.089652017 0.26406163, -0.10628633 0.088796943 0.26577109, -0.10655391 0.088592246 0.26618052, -0.10644694 0.088702679 0.26595968, 0.12499852 0.10791548 0.22754262, -0.010820787 0.090486199 0.26239437, 0.12315214 0.10915388 0.22506611, 0.12523681 0.1082022 0.22696905, -0.093932658 0.089782909 0.26379973, -0.10606211 0.088878244 0.26560867, -0.10661247 0.088433996 0.26649719, 0.12412579 0.10912171 0.22513019, 0.12535092 0.1085109 0.2263519, 0.12531947 0.10836159 0.22665034, -0.10577977 0.088942051 0.26548105, -0.10656972 0.088201433 0.26696235, 0.12462225 0.10904999 0.22527383, 0.12532754 0.10865204 0.22606967, -0.010070775 0.091352046 0.26066303, -0.094072804 0.089902297 0.26356119, 0.12492655 0.10896502 0.22544371, 0.12511323 0.1088783 0.22561698, 0.12524615 0.10877578 0.22582208, -0.0089780167 0.092141546 0.25908417, -0.11259824 0.10977875 0.22381304, -0.10545942 0.088986427 0.26539218, -0.10819092 0.090230361 0.26290452, -0.10835004 0.090276346 0.26281297, -0.10858174 0.090377584 0.26261032, -0.0075793662 0.092827722 0.25771201, -0.11267041 0.1099097 0.22355174, 0.12711495 0.11041474 0.22254495, 0.12695904 0.11036664 0.22264086, 0.12666097 0.11030986 0.22275461, -0.10785258 0.090172663 0.26302016, -0.1087855 0.090517059 0.26233137, -0.005922569 0.093387157 0.25659299, 0.12736422 0.11053222 0.22230993, 0.12629464 0.11027938 0.2228155, -0.0040642051 0.093801208 0.25576556, -0.10509889 0.089013547 0.26533806, 0.12770508 0.1108228 0.22172894, 0.12585863 0.11027198 0.22283016, -0.11281045 0.11002906 0.22331299, 0.12408726 0.11453617 0.21430303, 0.11383834 0.11027184 0.22283016, -0.0020674346 0.094055317 0.25525725, -0.1071219 0.090143576 0.26307815, -0.10441536 0.089025445 0.26531416, 0.12375158 0.11470571 0.213964, -3.9115477e-07 0.094141126 0.25508606, -0.12408812 0.11594067 0.21149124, -0.095101506 0.089025468 0.26531416, 0.12450396 0.11440745 0.21456005, -0.094251335 0.082632311 0.27809888, -0.094753809 0.082604863 0.27815342, 0.12351627 0.11490623 0.21356325, -0.094802335 0.089041717 0.26528186, -0.093748704 0.08260493 0.27815342, 0.12497734 0.11432724 0.21472077, -0.094520584 0.08908952 0.26518619, -0.093275368 0.082524672 0.27831423, 0.12339514 0.11512604 0.21312343, 0.11353917 0.11025563 0.22286271, -0.094272591 0.08916606 0.26503319, -0.092858776 0.082396016 0.27857137, 0.12547994 0.11429994 0.21477501, 0.092999823 0.077117786 0.28912908, 0.0020669992 0.084163204 0.2750386, -0.094072804 0.089267142 0.26483148, -0.092523113 0.082226634 0.27891028, 0.12339514 0.11535248 0.21267094, 0.11325753 0.1102078 0.22295831, 0.0040637385 0.084417313 0.27453065, 0.0059220605 0.084831305 0.27370286, 0.007578826 0.085390911 0.27258396, 0.0089774765 0.086077034 0.27121192, 0.010070441 0.086866446 0.26963311, -0.093932718 0.089386418 0.26459277, 0.12598249 0.11432718 0.21472077, 0.12351628 0.1155723 0.21223105, 0.092999905 0.077959523 0.28744537, 0.12645578 0.11440747 0.21456011, 0.12375151 0.11577281 0.21183015, 0.092522703 0.08116062 0.28104424, 0.092858292 0.080991253 0.28138328, 0.12687236 0.11453616 0.21430303, 0.12408725 0.11594221 0.21149115, 0.093274921 0.080862626 0.28164053, 0.092287436 0.0813611 0.28064334, 0.12720805 0.11470577 0.213964, 0.12450384 0.11607094 0.21123387, 0.12744346 0.11490624 0.2135631, 0.09374842 0.080782257 0.28180099, 0.0921662 0.081581004 0.2802037, 0.010820255 0.08773239 0.26790148, 0.094250888 0.080755048 0.28185552, 0.092166148 0.081807502 0.27975094, 0.094753474 0.080782384 0.28180099, -0.1250239 0.10892379 0.22552334, -0.12529165 0.10871911 0.22593249, -0.12518452 0.1088295 0.22571187, 0.09522678 0.080862671 0.28164029, 0.13388509 0.11746129 0.20845406, -0.12479974 0.109005 0.2253608, -0.12535004 0.10856077 0.22624896, 0.12756449 0.1151261 0.21312343, 0.12756449 0.11535245 0.21267094, 0.12744337 0.11557233 0.21223088, 0.12720805 0.11577287 0.21182998, 0.12687224 0.11594241 0.21149124, 0.12645574 0.11607092 0.21123402, 0.12598237 0.11615121 0.21107356, -0.12451738 0.10906887 0.22523306, -0.12530732 0.10832822 0.22671424, 0.095643356 0.080991298 0.28138304, 0.13438785 0.11787294 0.20763047, 0.12547985 0.1161785 0.2110187, 0.13507138 0.11822884 0.20691867, 0.12497724 0.11615119 0.21107356, 0.095979169 0.081160754 0.28104424, 0.13590595 0.11851303 0.20635043, -0.12419714 0.10911325 0.22514413, 0.096214429 0.081361212 0.28064334, 0.13685472 0.1187132 0.20595033, -0.13685574 0.11871143 0.20595033, -0.12692858 0.11035712 0.22265671, -0.12708765 0.11040299 0.2225648, -0.12731934 0.11050438 0.2223625, -0.12659022 0.11029943 0.22277211, -0.12752318 0.11064394 0.22208332, -0.12383653 0.10914037 0.22509001, 0.48973328 0.13887519 0.16563652, 0.48958781 0.1387929 0.16580115, 0.48935887 0.13870957 0.16596766, 0.48984733 0.13897309 0.16544066, 0.48910305 0.13865039 0.16608591, 0.48992917 0.13908643 0.16521405, 0.48872855 0.13859954 0.16618775, -0.48191613 0.15011284 0.14315189, 0.48227125 0.14969876 0.14399265, 0.4826071 0.14952925 0.14433132, -0.12548068 0.11519271 0.21522258, -0.12598322 0.11522003 0.21516813, -0.12645648 0.1153003 0.21500756, -0.1268732 0.11542898 0.2147503, -0.12720895 0.11559837 0.21441139, -0.12744424 0.11579903 0.21401037, -0.12756535 0.11601894 0.21357088, -0.12756532 0.11624528 0.21311794, -0.12744421 0.11646508 0.21267848, -0.12720892 0.11666562 0.21227722, -0.12687328 0.11683501 0.21193855, -0.1264565 0.11696365 0.21168114, -0.12598327 0.117044 0.21152081, -0.12548077 0.11707133 0.21146621, 0.094250947 0.081649326 0.28230274, 0.093748316 0.081676632 0.28224814, 0.09327504 0.081756905 0.28208756, 0.092858404 0.081885591 0.28183031, 0.092522711 0.082055047 0.28149152, 0.092287384 0.08225555 0.28109056, 0.092166208 0.082475439 0.28065109, 0.092166141 0.082701877 0.28019816, 0.092287324 0.082921699 0.27975845, 0.092522651 0.083122134 0.27935749, 0.092858404 0.083291605 0.27901876, 0.093274951 0.083420299 0.27876145, 0.093748406 0.083500527 0.27860093, 0.094250858 0.083527885 0.27854645, 0.12547982 0.11519436 0.21522258, 0.12497725 0.11522169 0.21516813, 0.12450393 0.11530198 0.21500735, 0.12408735 0.11543051 0.2147503, 0.12375151 0.11560014 0.21441139, 0.12351622 0.11580068 0.21401037, 0.12339516 0.11602053 0.21357064, 0.12339517 0.11624685 0.21311821, 0.12351632 0.11646673 0.21267812, 0.1237516 0.11666715 0.21227722, 0.12408724 0.11683667 0.21193855, 0.1245039 0.11696532 0.21168114, 0.12497717 0.11704569 0.21152081, 0.1254798 0.11707287 0.21146621, -0.094251335 0.081648156 0.2823028, -0.094753802 0.08167541 0.28224814, -0.095227227 0.081755698 0.2820875, -0.095643893 0.081884503 0.28183031, -0.095979571 0.082053959 0.28149152, -0.096214846 0.08225441 0.28109056, -0.096336007 0.082474291 0.28065109, -0.096336037 0.0827007 0.28019816, -0.096214913 0.082920492 0.27975863, -0.095979616 0.083120972 0.27935749, -0.095643885 0.083290488 0.27901876, -0.095227279 0.083419085 0.27876145, -0.094753869 0.08349935 0.27860093, -0.094251379 0.083526678 0.27854645, -1.9930232e-07 0.084971935 0.27565753, -0.0020673792 0.085057572 0.27548605, -0.0040642861 0.085311778 0.2749778, -0.0059225531 0.085725546 0.27415013, -0.0075793858 0.086285219 0.27303129, -0.0089778937 0.08697138 0.27165896, -0.010070856 0.087760746 0.27008033, -0.010820732 0.088626646 0.26834899, -0.011202222 0.089539252 0.26652366, -0.011202347 0.090467952 0.26466709, -0.010820795 0.091380589 0.26284182, -0.010070825 0.092246324 0.26111025, -0.0089780353 0.093035974 0.25953138, -0.0075793741 0.09372212 0.25815952, -0.0059226649 0.094281673 0.25704038, -0.0040642405 0.094695635 0.25621283, -0.0020674709 0.094949745 0.25570458, -2.6263226e-07 0.095035434 0.25553334, 0.48399952 0.15018739 0.14525105, 0.48349711 0.15021464 0.14519642, 0.48302364 0.15029499 0.14503585, 0.48260695 0.15042368 0.14477859, 0.48227116 0.15059318 0.1444398, 0.48203599 0.1507937 0.14403857, 0.48191485 0.15101351 0.14359902, 0.48191491 0.15123977 0.14314641, 0.48203608 0.15145965 0.14270665, 0.48227128 0.15166016 0.14230584, 0.48260698 0.15182975 0.14196672, 0.48302367 0.15195842 0.14170955, 0.4834969 0.15203863 0.14154913, 0.48399952 0.15206601 0.14149453, -0.48400089 0.15018123 0.14525105, -0.48450339 0.15020855 0.14519642, -0.48497671 0.15028885 0.14503585, -0.48539332 0.15041748 0.14477859, -0.48572904 0.15058692 0.1444398, -0.48596433 0.1507874 0.14403866, -0.48608547 0.15100721 0.14359917, -0.48608553 0.15123363 0.14314629, -0.48596442 0.15145345 0.14270674, -0.48572913 0.1516539 0.14230584, -0.48539343 0.15182354 0.14196675, -0.4849768 0.15195218 0.14170973, -0.48450339 0.15203252 0.14154913, -0.48400095 0.15205975 0.14149453, -0.09979523 0.1423146 0.16098692, -0.095577754 0.14351076 0.15859516, -0.10501755 0.14484948 0.15591781, -0.096840627 0.14167386 0.1622683, 0.0040636891 0.094695657 0.25621283, 0.011608442 0.1290544 0.18750529, 0.0020669317 0.094949767 0.25570464, 0.0084145349 0.13041618 0.18478175, 0.008819364 0.13037273 0.18486856, 0.0079210009 0.13062569 0.18436284, 0.08735051 0.13529529 0.17502607, 0.08564081 0.13689268 0.17183141, 0.081718586 0.13547668 0.17466329, 0.0077925678 0.13075587 0.18410276, 0.083161809 0.13698313 0.17165105, 0.007695144 0.13090172 0.18381108, 0.10178393 0.12889799 0.18781908, 0.10306037 0.12972698 0.18616112, 0.10235973 0.12932023 0.18697457, -0.012953106 0.13901944 0.16757749, -0.01540916 0.14129514 0.16302668, -0.015409138 0.13815635 0.1693034, -0.097085983 0.078825593 0.28794712, -0.094981864 0.1446716 0.15627353, -0.082251288 0.13548803 0.17463841, -0.079824723 0.13832134 0.16897221, -0.086812802 0.13846985 0.16867565, -0.093000129 0.078825518 0.28794712, 0.0040645655 0.13125139 0.18311168, -0.003048446 0.13603756 0.17354058, -0.0035720021 0.13436158 0.17689203, -0.077865332 0.13752827 0.17055859, 0.084240042 0.13854924 0.16851871, -0.079943933 0.13359772 0.17841853, 0.095334105 0.13320431 0.17920761, 0.09144967 0.13535285 0.17491092, 0.093177117 0.13426882 0.17707862, 0.097633891 0.13229758 0.18102072, -0.081553213 0.13921571 0.16718386, -0.093748733 0.081675485 0.28224826, 0.10035624 0.13144937 0.18271686, 0.08046522 0.13846993 0.16867743, 0.081358843 0.14020188 0.16521405, 0.058099631 0.13996159 0.16569422, -0.093275353 0.081755623 0.28208756, -0.083201036 0.14030567 0.16500436, 0.10243329 0.1309236 0.18376817, -0.09453208 0.14584567 0.15392594, -0.10488294 0.14670874 0.15219994, -0.092858702 0.081884429 0.28183031, 0.10459092 0.13046727 0.18468069, -0.091549546 0.13925448 0.16710646, -0.085027099 0.14179571 0.16202472, -0.093464307 0.14151895 0.16257836, 0.0895155 0.13683933 0.17193817, -0.092523023 0.082053944 0.28149152, 0.010605449 0.13037515 0.18486367, 0.01080654 0.13042821 0.18475761, 0.010436261 0.1303523 0.18490945, 0.12770498 0.11171716 0.2221763, 0.1338852 0.11835562 0.20890115, 0.12744345 0.11580068 0.21401037, 0.010708207 0.13039766 0.18481864, 0.12756442 0.11602056 0.21357088, 0.12756452 0.11624691 0.21311794, 0.12744337 0.1164667 0.21267812, -0.092287794 0.08225438 0.28109056, 0.12720805 0.1166673 0.21227722, 0.12687233 0.11683673 0.21193855, 0.12645577 0.11696529 0.21168123, 0.12598227 0.11704563 0.21152081, 0.010990595 0.1305155 0.18458299, 0.010203479 0.13033871 0.18493672, -0.076784439 0.13818485 0.16924565, -0.077401392 0.13788167 0.16985188, -0.10626175 0.088681579 0.26823789, 0.081839234 0.1417094 0.16219939, -0.077858508 0.1316562 0.18230115, -0.066988088 0.13399723 0.17761971, -0.067498289 0.13045111 0.18471085, -0.070847727 0.13023083 0.18515147, -0.09216655 0.082474194 0.28065109, 0.13438776 0.11876737 0.20807777, 0.011117455 0.1306071 0.18440007, -0.020672349 0.14255053 0.16051613, -0.018917982 0.1441199 0.15737797, -0.025409134 0.14262891 0.16035925, -0.018917942 0.14255051 0.16051613, -0.08617229 0.14296433 0.15968762, 0.1350714 0.11912327 0.20736594, -0.092387445 0.14297211 0.15967228, 0.086657472 0.13961585 0.16638599, 0.085931689 0.14117669 0.16326465, 0.086115189 0.14052854 0.16456114, 0.087724037 0.13842613 0.16876502, 0.011258148 0.13076042 0.18409337, -0.065197207 0.13372368 0.17816691, -0.064210162 0.13081101 0.18399154, 0.082007036 0.14334013 0.1589389, 0.055117134 0.14412037 0.15737776, 0.011371588 0.13095665 0.18370141, 0.0075733662 0.13148686 0.18264081, -0.075768031 0.13850805 0.16859947, 0.13590586 0.11940753 0.20679758, -0.0062858928 0.13637644 0.17286302, -0.0060004629 0.13879472 0.16802679, -0.0087424517 0.13635163 0.17291234, 0.085770451 0.14224288 0.16113292, 0.09522678 0.083420306 0.27876145, 0.10626112 0.088682935 0.26823795, 0.095101044 0.089921087 0.26576155, -0.061466053 0.13127281 0.18306787, -0.063479297 0.13336954 0.17887495, 0.09708558 0.0788268 0.28794712, 0.096335575 0.082475483 0.28065109, 0.096335538 0.082701899 0.2801981, 0.096214414 0.082921714 0.27975863, 0.095979206 0.083122164 0.27935755, 0.095643535 0.08329168 0.2790187, 0.13685483 0.11960757 0.20639755, 0.10441478 0.089921258 0.26576132, 0.13787612 0.11971468 0.2061833, 0.081979938 0.1450261 0.15556701, 0.055292629 0.14623895 0.1531413, 0.085643463 0.14396358 0.1576917, 0.011538206 0.13150609 0.18260245, 0.081783734 0.14670999 0.15219994, 0.040555738 0.14623886 0.1531413, -0.087022081 0.14414975 0.15731727, -0.091380134 0.14452758 0.15656157, -0.058905657 0.13186255 0.1818886, 0.086169824 0.14655302 0.15251364, 0.085770696 0.14526376 0.15509175, 0.10656921 0.089097157 0.26740956, 0.10509835 0.089909315 0.26578522, -0.10650923 0.089541823 0.26651734, -0.10618954 0.089731008 0.26613903, -0.10637631 0.089644462 0.26631254, -0.10659082 0.089418143 0.26676494, 0.1054589 0.089882255 0.26583946, 0.47529957 0.15512405 0.135379, -0.10661406 0.089276969 0.26704723, -0.10588533 0.089816004 0.2659691, -0.065870382 0.13468312 0.17624797, -0.074356504 0.13878363 0.16804786, 0.47529963 0.13872881 0.16816483, 0.0075732879 0.14168754 0.16224219, 0.011608388 0.13242841 0.1807579, 0.10577926 0.089837804 0.26592833, 0.0040644668 0.14412001 0.15737776, -0.00260216 0.14411995 0.1573777, -0.0027395338 0.13872924 0.16815792, 0.10661189 0.089329764 0.26694423, -0.005935479 0.1412167 0.16318379, -0.0061109476 0.14545396 0.15471043, -0.0090933852 0.14262907 0.16035925, -0.094356492 0.13117222 0.18326856, -0.082075767 0.13172153 0.18217026, -0.083663322 0.13330746 0.17899884, -0.092127986 0.13347501 0.17866372, -0.0090933908 0.14121674 0.16318379, -0.035935603 0.13886246 0.16789119, -0.059093393 0.13886225 0.16789119, -0.052602142 0.13815618 0.16930328, -0.050607532 0.13792852 0.16975851, -0.049327862 0.13786304 0.16988967, -0.048040662 0.13784218 0.1699308, -0.039444234 0.13745001 0.17071556, -0.087584935 0.14518869 0.15523975, -0.090672426 0.14529637 0.15502416, -0.059093405 0.14011776 0.16538061, -0.039444249 0.14011791 0.16538046, -0.058567151 0.14192253 0.16177152, -0.03944432 0.14192265 0.16177152, 0.036696125 0.14184469 0.1619284, 0.023011936 0.14184454 0.1619284, 0.027573392 0.13988289 0.16585134, -0.015409019 0.13807786 0.16946028, -0.015409103 0.13234967 0.18091486, -0.014089871 0.13718699 0.17124186, -0.012842847 0.1362755 0.17306451, 0.1060616 0.08977399 0.266056, -0.011724895 0.13533157 0.17495231, -0.018917985 0.13234971 0.18091474, -0.0189179 0.13737164 0.17087235, -0.020539921 0.13544813 0.17471899, 0.040731203 0.12874073 0.18813293, 0.040906731 0.13195783 0.18169941, 0.036573056 0.13000998 0.18559442, 0.10655341 0.089488067 0.26662761, 0.040731248 0.13493958 0.17573677, 0.05529261 0.1349397 0.17573677, 0.053277373 0.13539691 0.17482238, 0.049551189 0.13569364 0.17422907, -0.013479345 0.1425506 0.16051613, -0.01540919 0.14411989 0.1573777, -0.015409138 0.14255047 0.16051613, 0.046591692 0.13609719 0.17342187, -0.10505834 0.14098056 0.16365419, -0.10505835 0.13815582 0.16930328, -0.10413558 0.13860601 0.1684029, -0.10312857 0.13901892 0.16757734, -0.1004106 0.13731925 0.17097639, -0.1008478 0.13807735 0.16946028, -0.10505835 0.13784191 0.16993104, -0.10505834 0.13195692 0.18169926, -0.10367996 0.13700329 0.17160822, -0.1023755 0.13614106 0.17333241, -0.10049692 0.13470322 0.17620744, -0.10839156 0.1319568 0.18169926, -0.10839163 0.1372142 0.17118625, -0.10993723 0.13561049 0.17439319, -0.475301 0.15511808 0.135379, 0.10628583 0.08969266 0.2662186, 0.036696136 0.1462388 0.1531413, 0.023011826 0.14623877 0.1531413, 0.10644631 0.089598402 0.26640701, -0.015058357 0.14647391 0.15267064, -0.019093459 0.14647388 0.15267064, -0.10538882 0.089887768 0.26582563, -0.035935543 0.14647388 0.15267064, -0.066286422 0.14655207 0.15251373, -0.084707469 0.14655195 0.15251364, -0.10856713 0.14670865 0.15219973, -0.10658249 0.08912763 0.26734596, -0.06501741 0.13544174 0.17473112, 0.023011981 0.13493943 0.17573677, 0.036696151 0.13493958 0.17573677, 0.024722395 0.13526769 0.17508049, -0.10649996 0.088968359 0.26766425, 0.028824486 0.13573149 0.17415302, 0.031606965 0.1361371 0.17334189, 0.035292633 0.13870589 0.16820498, 0.027573349 0.13870588 0.16820498, 0.034398936 0.13833837 0.16894002, 0.033447213 0.13800141 0.16961376, 0.036520679 0.14160931 0.16239895, 0.041257489 0.14129549 0.16302679, 0.04055576 0.14184475 0.16192864, 0.040029436 0.13988303 0.16585134, 0.047924176 0.13988307 0.16585107, 0.040134456 0.14023553 0.16514622, 0.046726394 0.14038298 0.16485153, 0.045468029 0.14082468 0.16396819, 0.05108209 0.13870609 0.16820489, 0.042310201 0.13870597 0.16820498, 0.044173341 0.13811131 0.16939418, -0.10837816 0.091180652 0.26324022, -0.10792417 0.091075882 0.26344991, -0.10862744 0.091298237 0.26300526, 0.046222538 0.13765496 0.17030673, -0.10822236 0.091132656 0.26333612, -0.062420793 0.13433444 0.17694534, 0.057924245 0.13517515 0.1752658, 0.020555791 0.13493952 0.17573668, 0.055292595 0.14184484 0.1619284, 0.047924224 0.14160934 0.16239916, -0.088040791 0.146238 0.1531413, -0.092863403 0.14553738 0.15454258, -0.091778718 0.14539707 0.15482269, -0.10755789 0.091045395 0.26351076, -0.1089682 0.091588631 0.26242423, -0.057068825 0.13244264 0.18072869, -0.1071219 0.091038041 0.26352543, -0.015343525 0.14530057 0.15501691, -0.10441531 0.089919873 0.26576155, -0.095101491 0.089919955 0.26576155, -0.094802439 0.089936212 0.26572913, -0.055866435 0.13299142 0.17963137, -0.061513532 0.13533017 0.17495434, -0.093748741 0.083499387 0.27860093, 0.023011914 0.12866217 0.18828972, 0.013922799 0.12963045 0.18635304, 0.014494682 0.13028288 0.18504839, 0.013547128 0.12939084 0.18683212, 0.013175657 0.12924755 0.18711887, 0.012698874 0.12913632 0.18734132, 0.012162125 0.12907499 0.18746378, -0.093275435 0.083419099 0.27876145, -0.094520584 0.089983985 0.26563352, 0.0059221126 0.094281718 0.25704038, -0.092858747 0.08329048 0.2790187, -0.094272673 0.090060502 0.26548046, -0.054880355 0.13365808 0.17829822, -0.092523113 0.083121032 0.27935749, -0.094072774 0.090161398 0.26527876, -0.064180695 0.13643533 0.1727442, -0.066286333 0.13878368 0.16804801, -0.092287801 0.082920462 0.27975845, -0.093932711 0.090280749 0.26503986, -0.063479275 0.1374498 0.17071556, -0.093860626 0.090411708 0.2647782, 0.10819051 0.091126196 0.26335186, 0.10858122 0.091273412 0.26305759, 0.10785207 0.091068491 0.26346743, -0.095101491 0.091038048 0.26352543, 0.1083494 0.091172129 0.26326007, 0.10878494 0.091412961 0.26277888, 0.10712132 0.091039404 0.26352543, -0.054051712 0.13452452 0.17656542, -0.060675256 0.13610399 0.17340706, 0.10896769 0.091590062 0.26242423, 0.095100954 0.091039337 0.26352543, 0.023134885 0.13001537 0.18558355, -0.066286325 0.14019611 0.1652237, 0.015292602 0.13180073 0.18201332, 0.026169831 0.12866212 0.18828972, -0.076348104 0.13935471 0.16690619, -0.078143284 0.14004394 0.16552795, -0.053383175 0.13184774 0.18191828, -0.048313253 0.13216871 0.18127646, -0.051952656 0.13263437 0.18034504, 0.023187343 0.13195771 0.18169941, -0.046579584 0.13142474 0.18276428, -0.055288106 0.13106045 0.18349285, -0.049566474 0.1328626 0.17988898, 0.033713676 0.12874065 0.18813275, 0.026169881 0.13015291 0.18530841, -0.044295803 0.13065743 0.18429874, -0.057696745 0.13029681 0.18501975, 0.0075786496 0.093722336 0.25815952, 0.023146905 0.13360372 0.17840783, 0.013405427 0.13206184 0.18149088, -0.050672296 0.13360506 0.17840423, -0.060192741 0.12972093 0.18617155, -0.041775223 0.13000064 0.18561204, 0.019982928 0.13568245 0.17425098, 0.019460566 0.13611536 0.17338531, -0.1252469 0.1096687 0.22626941, -0.12492724 0.10985789 0.22589101, -0.12511389 0.10977122 0.22606419, -0.12532826 0.10954481 0.22651689, -0.053376336 0.13564807 0.1743186, -0.059619717 0.13682213 0.17197071, 0.018801436 0.1365087 0.1725985, -0.12462305 0.10994288 0.22572117, -0.038794048 0.12941715 0.18677898, -0.12535171 0.10940373 0.22679918, -0.061863583 0.12942837 0.18675642, -0.064445078 0.12904502 0.18752263, 0.036696266 0.12874061 0.18813293, 0.033713818 0.13015294 0.18530832, -0.12532018 0.1092543 0.22709776, -0.12412636 0.11001466 0.22557761, -0.12523752 0.10909501 0.22741626, -0.064707451 0.14184403 0.1619284, -0.12711576 0.11130738 0.22299232, -0.12666181 0.11120258 0.22320174, -0.12736505 0.11142488 0.22275709, -0.12696001 0.11125939 0.22308813, -0.035565615 0.12896195 0.18768929, -0.12629557 0.11117209 0.22326277, -0.12770578 0.11171548 0.2221763, -0.052896477 0.13689631 0.1718225, 0.022717908 0.13658765 0.17244078, 0.020731201 0.1386274 0.16836177, -0.12585954 0.11116482 0.22327743, -0.12499933 0.10880826 0.22798984, -0.12315287 0.11004667 0.22551356, -0.47530085 0.13872279 0.16816469, -0.13787703 0.11971295 0.2061833, 0.0437137 0.12874074 0.18813293, 0.0089774253 0.093036026 0.2595315, 0.02621064 0.13681167 0.17199267, 0.0077486821 0.14545408 0.15471055, -0.031900376 0.12858339 0.1884466, 0.020731146 0.13996139 0.16569422, -0.064707495 0.14325643 0.15910397, 0.036520675 0.13180083 0.18201332, 0.03657354 0.1336641 0.17828725, -0.1338861 0.11835391 0.20890115, 0.029457865 0.13716839 0.17127965, -0.11383907 0.11004673 0.22551356, 0.031628713 0.13752431 0.17056797, -0.046986435 0.13384582 0.17792274, -0.042953052 0.13399738 0.17761971, -0.048112877 0.13463151 0.17635159, -0.045511484 0.13313687 0.17934074, -0.043832805 0.13254946 0.18051495, 0.033778481 0.13658124 0.17245378, 0.052134693 0.12866241 0.18828963, 0.094072238 0.090797901 0.26400852, -0.031460613 0.12930173 0.1870098, -0.03174803 0.12895061 0.18771203, -0.11353999 0.11006303 0.22548102, -0.12497812 0.11522004 0.21516813, -0.11325818 0.11011074 0.22538559, 0.032545291 0.13773888 0.17013882, -0.066286415 0.1449827 0.15565194, -0.082568265 0.14314103 0.1593345, -0.0838245 0.14463988 0.15633743, -0.081161432 0.14181754 0.16198109, -0.079781495 0.14087792 0.16385995, -0.041435413 0.13191016 0.18179373, -0.039795071 0.13336971 0.17887495, -0.1245047 0.1153004 0.21500735, -0.038581371 0.1313459 0.18292223, -0.035647586 0.13094461 0.18372463, 0.035853192 0.13717362 0.17126934, -0.11301024 0.11018731 0.22523217, 0.094272092 0.090898715 0.26380664, 0.055292752 0.12866232 0.18828972, 0.052134782 0.13015312 0.18530832, 0.043713823 0.13015302 0.18530832, -0.030941701 0.12974289 0.18612801, -0.11281037 0.11028828 0.22503071, -0.094802342 0.091021843 0.26355797, 0.023187341 0.14404166 0.15753482, -0.12408819 0.11542903 0.2147503, -0.049060937 0.13588738 0.17384006, -0.041787781 0.13488112 0.17585276, -0.049070962 0.13652062 0.17257391, -0.11267038 0.11040758 0.22479187, -0.04878144 0.13533095 0.174953, -0.094520584 0.090974107 0.26365364, 0.037515935 0.13781562 0.16998558, -0.11259821 0.11053844 0.22453021, -0.094272539 0.090897515 0.26380664, 0.040678374 0.13779351 0.1700296, 0.038976751 0.13854907 0.16851871, -0.084463142 0.14572082 0.15417574, -0.11383914 0.11116485 0.22327758, -0.12375244 0.11559851 0.21441139, 0.042503823 0.13709831 0.17141984, -0.038092263 0.13484171 0.17593162, -0.032652922 0.13068695 0.18423988, -0.048713408 0.13720587 0.17120378, -0.040541179 0.13615167 0.17331167, 0.044358894 0.13654508 0.17252611, -0.059093464 0.14506119 0.155495, -0.058742527 0.14317799 0.159261, 0.036169842 0.13988301 0.16585134, 0.036465757 0.14044845 0.16472028, 0.092999928 0.078012183 0.28957635, 0.0020669489 0.085057661 0.27548605, 0.0040637027 0.08531183 0.27497792, 0.0059220991 0.085725673 0.27415037, 0.0075787846 0.086285308 0.27303129, 0.0089775454 0.086971372 0.27165896, 0.010070326 0.087760903 0.27008033, 0.036564581 0.14102837 0.16356088, -0.12351721 0.11579914 0.21401037, -0.093000226 0.078011021 0.28957623, -0.13438869 0.11876577 0.20807774, -0.1135399 0.11114852 0.22330998, -0.12339593 0.11601893 0.21357088, -0.019093363 0.12881877 0.18797581, -0.029619688 0.13054496 0.18452381, -0.13507234 0.11912155 0.20736594, -0.11325818 0.11110075 0.22340523, -0.123396 0.11624534 0.21311794, -0.12351718 0.1164652 0.21267812, 0.092999861 0.0788268 0.28794712, -0.015233664 0.12881878 0.18797581, -0.02663726 0.13399753 0.17761959, -0.03642923 0.13632119 0.17297311, -0.035584681 0.13674381 0.17212768, -0.037139188 0.13578339 0.17404817, -0.10856707 0.12858288 0.1884466, -0.023830168 0.13274211 0.18013038, -0.12375244 0.11666566 0.21227722, -0.1240882 0.11683516 0.21193855, -0.1245048 0.11696375 0.21168114, 0.067222469 0.12866244 0.18828972, -0.12497815 0.117044 0.21152063, -0.025324073 0.13345093 0.17871274, -0.13590695 0.11940575 0.2067977, 0.055117179 0.13172254 0.18217026, 0.064240001 0.12999627 0.18562226, 0.055157915 0.13358012 0.17845528, 0.05515819 0.12993473 0.18574511, -0.13685577 0.11960582 0.20639746, -0.11663727 0.1336831 0.17824711, 0.065818258 0.12936783 0.18687893, -0.11383028 0.13258453 0.18044399, -0.11301018 0.11102425 0.22355859, -0.10488284 0.12858286 0.1884466, -0.037733816 0.13710262 0.17141022, -0.025579549 0.13463405 0.1763467, -0.1149107 0.13315752 0.17929842, -0.11572281 0.13345423 0.17870499, 0.0365206 0.14404181 0.15753482, 0.11300936 0.11018886 0.22523217, 0.11280964 0.11028972 0.22503056, 0.094801784 0.091023177 0.26355815, 0.010820362 0.088626727 0.26834899, -0.092166699 0.082700692 0.2801981, 0.11325742 0.11011231 0.22538547, 0.1126696 0.11040902 0.22479187, 0.094520047 0.090975337 0.26365364, -0.022817701 0.13346939 0.17867605, -0.11176415 0.13406652 0.1774805, 0.011201765 0.089539483 0.26652378, 0.11353925 0.11006448 0.22548102, 0.094753534 0.081676632 0.28224814, 0.11259747 0.11053988 0.22453015, 0.11383836 0.11004826 0.22551356, 0.11259751 0.11067459 0.22426079, 0.067296445 0.1307379 0.18413939, -0.093860634 0.090546444 0.26450884, 0.04069183 0.14096439 0.16368853, 0.040324658 0.14058018 0.16445695, -0.011131199 0.12932286 0.18696781, -0.012777498 0.12991728 0.1857792, -0.1128104 0.11092339 0.22376035, -0.096988015 0.12921059 0.1871915, 0.11266962 0.11080547 0.22399895, 0.095226735 0.081757039 0.2820875, -0.0096196663 0.12866193 0.18828963, -0.097989902 0.13011032 0.1853921, -0.021865904 0.13421282 0.17718928, 0.048709467 0.13728534 0.1710463, -0.099268816 0.13093691 0.18373929, 0.051476259 0.137052 0.17151283, -0.093932793 0.090677306 0.264247, 0.095643356 0.081885703 0.28183031, -0.098558515 0.13114575 0.18332143, 0.055415995 0.13687715 0.17186202, -0.024202654 0.13567179 0.17427172, -0.09503334 0.12959407 0.18642445, -0.09617535 0.12940082 0.18681093, 0.095979244 0.082055122 0.28149146, 0.096214429 0.082255639 0.28109038, -0.097942412 0.13140829 0.18279661, 0.040731251 0.14412022 0.15737776, -0.094072759 0.090796724 0.26400834, -0.092963941 0.12983549 0.18594159, -0.011200778 0.13055643 0.18450107, 0.048450481 0.13988312 0.16585134, 0.051082075 0.1398831 0.16585134, 0.049474847 0.14022925 0.16515909, 0.070175208 0.13160989 0.18239544, 0.058279425 0.13579313 0.17402996, -0.1148686 0.13477729 0.17605911, -0.11523379 0.14090207 0.16381143, -0.11332199 0.13593702 0.17373993, -0.11171309 0.1374484 0.17071794, 0.058874324 0.13637409 0.17286815, -0.097243339 0.13180795 0.1819974, -0.096269131 0.13254574 0.18052171, 0.050555822 0.14051071 0.16459595, 0.059678592 0.13690132 0.17181383, -0.10987385 0.13966753 0.16628014, -0.0098518264 0.13129315 0.18302785, -0.022511717 0.13715409 0.17130746, 0.058099635 0.13862763 0.16836177, 0.057548366 0.13685372 0.17190908, -0.039444253 0.14317808 0.15926082, -0.039444298 0.14506128 0.15549494, -0.11523378 0.14231449 0.16098677, 0.12499855 0.10880981 0.22798993, 0.072427742 0.13245873 0.18069808, 0.12315219 0.11004832 0.22551356, -0.095225938 0.13356368 0.17848624, -0.008627044 0.1322128 0.18118881, 0.12530649 0.10922406 0.22716151, 0.12383571 0.11003646 0.22553717, -0.10942049 0.14031689 0.16498174, 0.12419623 0.1100093 0.22559159, -0.097865239 0.13556635 0.17448144, 0.12534922 0.10945676 0.22669621, 0.12451662 0.10996483 0.22567998, -0.02540921 0.14113799 0.1633407, -0.036110885 0.1416088 0.16239895, 0.12529092 0.10961501 0.22637962, 0.12479898 0.10990092 0.22580777, -0.021015497 0.13879669 0.16802274, -0.10909338 0.14098051 0.16365431, 0.1251837 0.10972546 0.2261589, 0.12502329 0.1098197 0.22597037, -0.0075306129 0.13337508 0.17886461, -0.059268855 0.14647365 0.15267064, 0.049307652 0.14109007 0.16343747, 0.074415118 0.13339677 0.17882241, -0.079268761 0.12889679 0.18781908, -0.1125982 0.11067314 0.22426055, -0.11267029 0.11080401 0.22399901, -0.088135734 0.13017705 0.18525885, -0.022957074 0.14125724 0.16310261, -0.020146886 0.14003542 0.16554569, -0.099173993 0.13780338 0.17000802, -0.036110856 0.14364885 0.15831934, -0.093667664 0.13540041 0.17481326, -0.097689852 0.13744962 0.17071556, -0.0068386551 0.13456282 0.17648925, 0.12692776 0.11125319 0.22310363, 0.12731852 0.11140034 0.22280942, 0.12658945 0.11119549 0.22321941, 0.12708677 0.11129902 0.22301222, 0.12752223 0.11153996 0.22253059, 0.12585866 0.11116641 0.22327743, 0.076361418 0.13455017 0.17651586, -0.080847755 0.13054454 0.18452395, 0.0047659855 0.12952632 0.18656109, -0.0080164094 0.12957226 0.18646903, -0.09945295 0.13904005 0.16753466, 0.0051387008 0.12937213 0.18686955, 0.0044802558 0.12972137 0.18617104, 0.078131884 0.13584512 0.17392637, -0.0065956041 0.13054124 0.18453132, 0.1138384 0.11116627 0.22327743, 0.0057288017 0.12922354 0.18716665, 0.0042893663 0.12993872 0.18573649, 0.0066909213 0.12909766 0.18741845, -0.020496862 0.14129505 0.16302679, -0.092471175 0.13708231 0.17145018, -0.096333683 0.13840029 0.1688145, 0.11353925 0.11115003 0.22330977, 0.094272092 0.090061724 0.26548046, 0.11325756 0.11110219 0.22340523, 0.094072238 0.090162605 0.2652784, -0.099795133 0.14090212 0.16381143, 0.094520107 0.089985162 0.26563352, 0.1259824 0.11522166 0.21516813, -0.098286465 0.14006251 0.16549037, -0.1083917 0.14223614 0.16114388, -0.10843249 0.14484943 0.15591781, 0.093932182 0.090281919 0.26503986, -0.085409112 0.13486031 0.17589359, -0.090061091 0.13580772 0.17399888, 0.12645574 0.11530199 0.21500756, 0.09480188 0.089937359 0.26572919, 0.093860179 0.090412825 0.26477838, 0.011201649 0.090468153 0.26466686, 0.12687241 0.11543053 0.2147503, 0.0040503386 0.13059008 0.18443377, 0.12720805 0.11560005 0.21441127, -0.0053731054 0.13158464 0.18244539, -0.091883913 0.13815778 0.16929926, -0.095241092 0.1394175 0.16678067, 0.079486318 0.13714373 0.17132954, 0.094753414 0.083500624 0.27860093, 0.093860194 0.090547614 0.26450896, 0.010820203 0.09138079 0.26284164, -0.084023669 0.13509212 0.17543019, -0.088686533 0.1371901 0.17123483, -0.019444272 0.14129511 0.16302679, -0.068742491 0.12842602 0.18876047, -0.075935468 0.1296815 0.18624981, 0.00792416 0.12905434 0.18750529, 0.093932241 0.090678543 0.264247, 0.010070261 0.09224657 0.26111025, 0.072989814 0.13052426 0.18456645, 0.093802035 0.13139763 0.18282031, 0.075689033 0.13165912 0.18229724, -0.10505829 0.14223605 0.16114388, 0.091480397 0.1325226 0.18057038, 0.077946834 0.13281576 0.17998423, -0.069225989 0.12907356 0.18746559, -0.0044270363 0.13273187 0.18015127, 0.09633287 0.13041441 0.18478648, 0.070189945 0.12954155 0.18653171, -0.069963433 0.12967314 0.18626679, 0.08929047 0.13383955 0.17793716, 0.080006398 0.13411173 0.17739238, 0.11280961 0.11092484 0.22376035, 0.098968908 0.12959203 0.18643104, -0.087720871 0.13795325 0.16970859, 0.11300948 0.11102566 0.22355844, 0.0080600064 0.13053462 0.18454488, 0.0082383379 0.13046044 0.1846932, 0.09299995 0.074327543 0.28996569, 0.092999876 0.074754521 0.29014993, 0.09299989 0.073826864 0.29083115, 0.092999928 0.075212464 0.29023105, 0.09299989 0.074467197 0.29110819, 0.092999876 0.075676814 0.29020399, 0.09299995 0.07515426 0.29122919, 0.092999831 0.076122358 0.29007018, 0.092999816 0.07585074 0.2911886, 0.092999861 0.076524898 0.28983766, 0.092999876 0.076518878 0.29098827, 0.092999808 0.076862887 0.28951818, 0.092999764 0.077122822 0.29063904, 0.092999801 0.077629879 0.2901597, 0.095344372 0.074327588 0.28996569, 0.095344305 0.073826909 0.29083115, -0.093000144 0.073825613 0.29083115, -0.093000114 0.074753329 0.29015011, -0.093000203 0.074326381 0.28996569, -0.093000144 0.074466035 0.29110819, -0.093000181 0.075152978 0.29122919, -0.093000114 0.075211331 0.29023081, -0.093000114 0.075849488 0.2911886, -0.093000136 0.075675592 0.29020393, -0.093000144 0.076517686 0.29098827, -0.093000188 0.076121107 0.29007018, -0.093000263 0.077121601 0.29063904, -0.093000151 0.076523677 0.28983766, -0.093000256 0.077628538 0.2901597, -0.093000263 0.076861605 0.28951818, -0.095344618 0.073825605 0.29083115, -0.095344737 0.074326426 0.28996569, -0.48349831 0.15203243 0.14154913, -0.48302507 0.15195224 0.14170955, -0.48260838 0.15182361 0.14196675, -0.48227265 0.15165402 0.14230575, -0.48203737 0.15145347 0.14270674, -0.48191622 0.15123364 0.14314629, -0.48191613 0.15100718 0.14359902, -0.4820374 0.15078752 0.1440389, -0.48227265 0.1505869 0.1444398, -0.48260826 0.15041742 0.14477859, -0.48302498 0.15028889 0.145036, -0.48349828 0.1502085 0.14519642, 0.48450217 0.15203865 0.14154916, 0.48497555 0.15195844 0.14170973, 0.48539209 0.15182978 0.14196675, 0.48572779 0.15166017 0.14230575, 0.48596308 0.15145971 0.14270674, 0.48608428 0.15123978 0.14314629, 0.48608431 0.15101352 0.14359902, 0.48596311 0.15079369 0.14403866, 0.48572788 0.15059313 0.1444398, 0.48539212 0.15042366 0.14477859, 0.48497543 0.15029505 0.14503585, 0.48450217 0.15021475 0.14519642, -0.49000072 0.14033985 0.16493069, -0.48992723 0.13996901 0.16567244, -0.48984531 0.13985793 0.16589449, -0.48973241 0.13976184 0.16608702, -0.48958823 0.13968071 0.16624887, -0.48936212 0.13959834 0.16641374, -0.48911026 0.13953964 0.16653122, -0.48873475 0.13948831 0.16663392, -0.48825076 0.13945234 0.16670556, 0.48999962 0.14034605 0.16493092, 0.48998061 0.14012685 0.16536935, 0.48991328 0.13995384 0.16571544, 0.48981461 0.13983467 0.1659535, 0.48966023 0.13972397 0.16617484, 0.48949823 0.13965003 0.16632293, 0.48929921 0.13958789 0.16644727, 0.48906305 0.13953766 0.16654758, 0.48824963 0.13945863 0.16670556, 0.091963433 0.064929612 0.28452975, 0.097840384 0.054333851 0.27840126, 0.091728166 0.064541489 0.28430533, 0.092084602 0.065355062 0.28477579, 0.097641081 -0.012551598 0.23971431, 0.097762384 -0.012977086 0.23946811, 0.091500476 -0.019335061 0.23579063, -0.10663937 -0.01871185 0.23615183, -0.10626908 -0.019066036 0.23594706, -0.10647881 -0.018908232 0.23603831, 0.099725939 -0.014150329 0.23878942, 0.10480952 -0.019335009 0.23579054, 0.099223301 -0.014097422 0.23881997, -0.10674243 -0.018503204 0.23627226, -0.10600818 -0.019187771 0.23587655, -0.10680836 -0.018262297 0.23641171, -0.10562261 -0.019286528 0.23581935, 0.097641088 -0.012113348 0.23996757, -0.10683426 -0.017890543 0.23662685, -0.10480858 -0.019336417 0.23579063, -0.10679705 -0.017419122 0.23689972, -0.10111763 -0.013694331 0.23905383, 0.091392457 0.066934824 0.28568965, 0.090975948 0.067183733 0.28583378, 0.090502486 0.067339182 0.28592354, 0.10022834 -0.014097318 0.23881997, 0.089999929 0.067391992 0.28595388, -0.10145327 -0.013366327 0.23924364, -0.088271767 0.066605642 0.28549993, -0.10070103 -0.01394324 0.23890994, 0.089497313 0.067339174 0.28592354, 0.089023933 0.067183778 0.28583384, 0.088607267 0.066934869 0.28568965, 0.088271618 0.066606864 0.28549993, -0.10168857 -0.012978286 0.23946811, 0.097762309 -0.011687912 0.24021377, 0.087500602 -0.020870484 0.23490252, 0.091728196 0.066606797 0.28549993, -0.10022757 -0.014098704 0.23882012, 0.092084572 0.065793291 0.28502935, 0.091963321 0.06621892 0.28527552, -0.10180971 -0.012552992 0.23971431, 0.10070175 -0.013941959 0.23890994, -0.099725038 -0.014151484 0.23878945, -0.10180974 -0.012114644 0.23996772, -0.099222571 -0.01409854 0.23882012, -0.10168855 -0.011689223 0.24021362, 0.1066444 -0.018703677 0.23615573, 0.10648568 -0.018901162 0.23604156, 0.10627444 -0.019062102 0.23594858, 0.10603901 -0.019175313 0.23588301, 0.10111836 -0.013693035 0.23905383, 0.10675612 -0.018465981 0.23629309, 0.10576047 -0.019258395 0.23583488, -0.091499671 -0.019336209 0.23579063, -0.098749138 -0.013943315 0.23890974, -0.098332517 -0.013694279 0.23905386, 0.10682818 -0.018123567 0.2364911, 0.10534662 -0.019316949 0.235801, -0.097996771 -0.013366282 0.23924385, -0.097761571 -0.012978241 0.23946832, 0.10679795 -0.017417677 0.23689972, 0.10145406 -0.013364971 0.23924352, -0.09764041 -0.012552857 0.23971431, 0.10168938 -0.012976974 0.23946832, -0.09764041 -0.012114614 0.23996757, -0.087499619 -0.020871498 0.23490252, -0.091499612 -0.020871557 0.23490252, 0.10181054 -0.012551591 0.23971416, -0.097761571 -0.011689097 0.24021362, 0.10181054 -0.012113363 0.23996757, 0.10168931 -0.011687845 0.24021362, -0.10439939 0.0017888471 0.24800958, -0.099725015 -0.010515928 0.24089243, -0.10022759 -0.01056876 0.24086176, -0.10070102 -0.010724112 0.24077199, -0.10111761 -0.010973088 0.2406279, -0.10145329 -0.011301145 0.24043818, -0.099222489 -0.010568768 0.24086176, 0.089822158 0.0038962886 0.24922754, 0.090061992 0.0036619157 0.24909224, 0.090359561 0.0034841225 0.24898924, -0.10356739 0.0031712651 0.24880911, -0.10412785 0.00270769 0.24854104, -0.1039881 0.0028871596 0.2486449, -0.10382017 0.0030329227 0.24872895, -0.10329364 0.0032592788 0.24886002, -0.10423877 0.002494514 0.24841757, 0.089654066 0.0041734725 0.24938802, -0.1029025 0.0033178031 0.2488939, -0.10241091 0.0033341497 0.24890341, 0.090697646 0.0033731312 0.2489251, 0.097997569 -0.011299826 0.24043818, 0.089567594 0.0044773668 0.24956386, -0.089566968 0.0044761896 0.24956371, -0.089566983 0.0047892332 0.24974485, -0.10348522 0.0065555274 0.25076663, -0.1031151 0.0062014759 0.25056189, -0.10332479 0.0063593388 0.25065321, 0.09105657 0.0033354387 0.24890341, 0.099223264 -0.010567501 0.24086176, 0.098749965 -0.010722928 0.24077184, 0.098333269 -0.010971814 0.2406279, -0.10358831 0.0067642331 0.2508871, -0.10285413 0.0060796738 0.25049144, 0.08956752 0.0047903508 0.24974485, -0.1036542 0.0070051253 0.25102645, -0.10246859 0.0059809983 0.2504341, -0.10368009 0.0073768497 0.25124174, -0.1016546 0.0059311166 0.25040537, -0.10364294 0.0078483224 0.25151443, -0.091056108 0.0033342987 0.24890341, -0.097996831 -0.011301056 0.24043818, -0.098332435 -0.010973141 0.2406279, -0.098749153 -0.010724127 0.24077184, -0.090697147 0.0033720359 0.24892525, -0.090358943 0.0034829974 0.24898924, -0.090061381 0.0036608502 0.24909215, -0.089821458 0.0038950369 0.24922754, 0.1024115 0.0033355653 0.24890335, -0.089653559 0.0041723251 0.24938811, 0.10440005 0.0017901808 0.24800958, 0.099725813 -0.010514632 0.24089228, 0.1014541 -0.011299849 0.24043818, 0.10111841 -0.010971837 0.2406279, -0.091056064 0.0059311837 0.25040537, 0.10070179 -0.010722898 0.24077184, 0.10022832 -0.010567479 0.24086176, 0.10432839 0.0022114366 0.2482533, 0.10323916 0.0032731444 0.24886717, 0.10421919 0.002541855 0.24844424, 0.10349594 0.0032005459 0.24882521, 0.1040886 0.0027679354 0.24857505, 0.10371714 0.0030996278 0.24876694, 0.10390257 0.0029707104 0.24869244, -0.098596796 0.048273209 0.27489632, -0.097764783 0.049655572 0.27569592, -0.098325349 0.049192023 0.27542794, -0.098185569 0.049371518 0.27553177, -0.098017626 0.049517199 0.27561593, -0.097491108 0.049743637 0.27574682, -0.098436251 0.048978843 0.27530468, -0.097099975 0.049802173 0.27578074, -0.096608452 0.049818538 0.27579021, 0.10348994 0.0065637976 0.25077063, 0.10333123 0.0063662678 0.25065631, 0.10312299 0.0062070638 0.25056428, 0.1028944 0.0060959011 0.25050002, 0.10360178 0.0068013817 0.25090802, 0.1026248 0.0060133934 0.25045204, -0.097684503 0.053042542 0.27765512, -0.09731251 0.052685756 0.27744877, -0.097522214 0.052843641 0.27753985, 0.10367379 0.0071438104 0.2511062, 0.10220066 0.0059510767 0.25041634, -0.097789064 0.053257361 0.27777916, 0.10364345 0.0078497939 0.25151432, 0.10165508 0.0059324503 0.25040537, -0.097051516 0.052563984 0.27737808, 0.091056541 0.0059323832 0.25040519, -0.097854525 0.053505916 0.27792287, -0.096665978 0.052465279 0.2773211, 0.08425878 0.050146207 0.27597904, 0.09006194 0.0056057721 0.25021648, 0.089822091 0.0053714886 0.250081, -0.097877398 0.053868335 0.27813268, -0.095852062 0.052415453 0.27729225, -0.097840369 0.054332506 0.27840114, 0.084019095 0.050380457 0.27611458, 0.089654185 0.0050942749 0.24992062, -0.085253634 0.049818669 0.27578998, -0.090697058 0.0058934018 0.25038356, 0.084556386 0.049968418 0.27587605, 0.090359554 0.0057836026 0.2503193, -0.084894523 0.049856339 0.27581191, 0.08385095 0.050657678 0.27627486, -0.08385092 0.050656591 0.27627486, -0.083764404 0.050960496 0.27645069, -0.090359017 0.0057825297 0.2503193, -0.084556356 0.049967267 0.27587605, -0.090061344 0.0056046247 0.25021654, 0.084894463 0.049857456 0.27581179, 0.090697668 0.0058946311 0.25038362, -0.084258839 0.050145127 0.27597904, -0.089821592 0.0053703114 0.250081, 0.083764412 0.050961629 0.27645069, -0.084019065 0.050379433 0.27611458, -0.089653671 0.0050932467 0.24992077, 0.085253477 0.049819726 0.27579021, 0.083764479 0.051274639 0.27663177, -0.083764404 0.051273536 0.27663177, 0.08385098 0.051578533 0.27680761, -0.083851039 0.051577549 0.27680761, -0.087915376 0.065792099 0.28502941, -0.091728315 0.064540386 0.28430533, -0.091392711 0.064212374 0.28411561, 0.098596826 0.048274502 0.27489632, 0.096608445 0.049819686 0.27578998, 0.098525301 0.048695669 0.27513993, 0.097436115 0.049757347 0.27575409, -0.090976059 0.063963443 0.28397179, 0.098415963 0.049026147 0.27533114, 0.097692773 0.049684804 0.27571195, -0.091963619 0.064928398 0.28452981, 0.098285422 0.049252197 0.27546191, 0.097914085 0.049583834 0.27565378, -0.090502664 0.063807964 0.28388166, 0.09809947 0.049454853 0.27557909, -0.09208484 0.06535393 0.28477585, -0.090000115 0.063755132 0.28385121, -0.085253522 0.052415494 0.27729201, -0.089497559 0.063808031 0.28388166, -0.089024194 0.063963428 0.28397155, -0.088607624 0.064212427 0.28411567, -0.08489453 0.052377734 0.27727044, 0.097686812 0.053047881 0.27765727, 0.09752804 0.052850582 0.27754319, 0.097319767 0.052691381 0.27745092, 0.097091243 0.052580211 0.2773869, -0.088271745 0.064540371 0.28430527, -0.084556416 0.05226681 0.27720618, 0.097798616 0.053285643 0.27779472, 0.096821591 0.052497726 0.27733922, -0.088036627 0.064928457 0.28452981, -0.08425878 0.052088924 0.2771033, 0.097870559 0.053628072 0.27799284, 0.096397474 0.052435402 0.27730298, -0.08791545 0.065353945 0.28477585, 0.095851988 0.052416712 0.27729219, -0.084019065 0.051854651 0.27696788, 0.088607341 0.06421344 0.28411561, 0.085253492 0.052416552 0.27729219, 0.084894508 0.052378856 0.2772702, 0.088271633 0.064541474 0.28430527, 0.08455649 0.052267779 0.27720618, 0.089024015 0.063964538 0.28397173, 0.088036299 0.06492959 0.28452975, 0.084258884 0.052089974 0.27710319, -0.091392659 0.066933692 0.28568965, -0.091728345 0.06660565 0.28549993, -0.091963708 0.066217721 0.28527552, -0.092084818 0.065792099 0.28502941, 0.089497358 0.063809082 0.28388166, -0.090000063 0.067390896 0.28595406, -0.090502635 0.06733802 0.28592336, -0.090976 0.067182742 0.28583354, 0.087915204 0.065354988 0.28477609, 0.084019035 0.051855758 0.27696776, -0.088607565 0.066933639 0.28568965, -0.089024127 0.06718266 0.28583378, -0.089497514 0.067337997 0.2859236, 0.089999929 0.06375628 0.28385121, 0.087915137 0.065793321 0.28502941, 0.090502456 0.063809156 0.28388166, 0.091500491 -0.020870373 0.23490267, 0.088036343 0.066218808 0.28527552, -0.088036478 0.066217586 0.28527552, 0.090975828 0.063964546 0.28397173, 0.097997658 -0.01336509 0.23924352, 0.098333336 -0.013693139 0.23905383, 0.091392472 0.064213455 0.28411561, 0.098749973 -0.013942041 0.23890974, -0.090000048 0.063254543 0.28471678, -0.090502575 0.063307285 0.28474736, -0.090975881 0.063462645 0.28483719, -0.091392577 0.063711666 0.28498131, -0.091728419 0.064039752 0.28517097, -0.091963671 0.064427748 0.2853955, -0.09208478 0.064853236 0.28564161, -0.09208484 0.065291516 0.28589511, -0.091963679 0.065716922 0.28614122, -0.091728374 0.066104911 0.28636563, -0.091392681 0.066432983 0.28655559, -0.090976045 0.066681921 0.28669924, -0.090502694 0.066837251 0.28678894, -0.090000056 0.066890091 0.28681982, -0.09972509 -0.014652237 0.239655, -0.10022761 -0.014599405 0.23968552, -0.10070106 -0.014443979 0.23977543, -0.10111768 -0.014195047 0.23991953, -0.10145339 -0.013866983 0.24010934, -0.10168856 -0.013479076 0.24033366, -0.10180971 -0.013053566 0.24057971, -0.10180973 -0.012615345 0.24083327, -0.1016885 -0.012189895 0.24107923, -0.10145338 -0.011801764 0.24130388, -0.10111764 -0.011473708 0.2414936, -0.10070103 -0.011224784 0.24163754, -0.1002277 -0.011069365 0.24172746, -0.09972506 -0.011016525 0.24175797, 0.099725842 -0.014650993 0.23965515, 0.099223301 -0.014598228 0.23968552, 0.098749973 -0.014442854 0.23977543, 0.098333284 -0.014193855 0.23991953, 0.097997606 -0.013865888 0.24010934, 0.097762324 -0.013477817 0.24033366, 0.0976412 -0.013052315 0.24057971, 0.097641185 -0.012614064 0.24083327, 0.097762324 -0.012188613 0.24107923, 0.097997583 -0.01180052 0.24130379, 0.098333262 -0.011472471 0.24149345, 0.098749883 -0.01122354 0.24163754, 0.099223226 -0.011068128 0.24172746, 0.099725805 -0.011015281 0.24175797, 0.089999951 0.063255668 0.28471678, 0.089497268 0.06330853 0.2847473, 0.08902397 0.063463911 0.28483725, 0.088607386 0.06371288 0.28498125, 0.088271692 0.064040795 0.28517097, 0.088036343 0.064428851 0.28539544, 0.087915182 0.064854421 0.28564149, 0.087915197 0.065292604 0.28589505, 0.088036425 0.065717921 0.2861411, 0.088271603 0.066106066 0.28636557, 0.088607311 0.066434041 0.28655523, 0.089023963 0.06668292 0.28669924, 0.089497335 0.066838399 0.28678906, 0.089999899 0.066891246 0.28681982, 0.091500439 -0.021371104 0.23576809, 0.087500542 -0.021371216 0.23576806, 0.087500475 -0.021823287 0.2345501, 0.08750055 -0.022024691 0.23552977, 0.08750049 -0.022372469 0.2354994, 0.087500483 -0.021493033 0.23463123, 0.087500535 -0.021174021 0.23474924, 0.087500624 -0.021687508 0.23562048, 0.091500379 -0.022372335 0.23549925, 0.091500424 -0.021823205 0.2345501, -0.091499597 -0.021372348 0.23576809, -0.087499693 -0.021372236 0.23576809, -0.087499633 -0.022025712 0.23552994, -0.087499619 -0.02182436 0.2345501, -0.087499596 -0.022373572 0.23549925, -0.087499604 -0.021688595 0.23562028, -0.087499611 -0.021494046 0.23463131, -0.087499551 -0.021175109 0.23474909, -0.091499574 -0.022373617 0.23549961, -0.091499515 -0.021824457 0.23454995, -0.09660849 0.049317859 0.27665567, -0.0974361 0.049255412 0.27661967, -0.097692922 0.049182907 0.27657765, -0.097914115 0.049081966 0.2765193, -0.098099396 0.048953008 0.27644497, -0.098285541 0.048750255 0.27632761, -0.098416075 0.048524212 0.27619684, -0.098525316 0.048193876 0.2760058, -0.098596849 0.047772508 0.27576202, -0.097840413 0.053831887 0.27926683, -0.097870693 0.053126074 0.27885842, -0.097798683 0.052783713 0.27866042, -0.097686961 0.052546039 0.27852297, -0.097528055 0.052348513 0.27840889, -0.097319953 0.052189365 0.2783168, -0.097091243 0.052078154 0.27825236, -0.096821845 0.051995683 0.27820456, -0.096397549 0.051933337 0.27816868, -0.095852062 0.051914688 0.27815795, -0.10364297 0.0073476098 0.25238001, -0.10367321 0.0066418648 0.25197184, -0.10360124 0.0062994361 0.25177372, -0.1034895 0.0060617626 0.25163633, -0.1033306 0.0058642626 0.25152177, -0.10312242 0.0057051256 0.25142998, -0.10289387 0.0055939257 0.25136548, -0.10262424 0.0055114403 0.25131786, -0.10220006 0.0054491237 0.25128168, -0.1016546 0.0054305047 0.25127107, -0.10241096 0.0028335229 0.24976923, -0.10323867 0.0027711093 0.24973287, -0.10349545 0.0026985407 0.24969082, -0.10371662 0.0025976002 0.24963249, -0.10390196 0.0024686158 0.24955787, -0.10408805 0.0022659302 0.2494408, -0.10421861 0.0020398498 0.24930973, -0.10432773 0.0017094538 0.24911882, -0.10439935 0.0012882054 0.24887519, -0.10679707 -0.017919742 0.23776506, -0.10682729 -0.018625617 0.23735701, -0.10675534 -0.018967934 0.23715879, -0.10664353 -0.019205652 0.23702143, -0.10648473 -0.019403145 0.23690717, -0.10627353 -0.019564152 0.23681404, -0.10603815 -0.019677304 0.23674871, -0.10575959 -0.019760422 0.23670055, -0.10534583 -0.019818969 0.23666669, -0.10480869 -0.019836985 0.23665623, 0.1048095 -0.019835614 0.23665611, 0.10562345 -0.019785799 0.23668496, 0.10600901 -0.019687086 0.23674209, 0.10626993 -0.019565366 0.23681252, 0.10647972 -0.019407466 0.23690401, 0.10664203 -0.019208558 0.23701884, 0.10674662 -0.018993668 0.23714329, 0.10681207 -0.018744975 0.23728718, 0.10683492 -0.018382519 0.23749663, 0.10679796 -0.017918348 0.23776506, 0.10364356 0.0073489398 0.25238001, 0.10368051 0.006884858 0.25211143, 0.10365764 0.0065224916 0.25190192, 0.10359218 0.0062737912 0.25175822, 0.10348752 0.0060589388 0.2516337, 0.10332529 0.0058599785 0.25151873, 0.10311566 0.005701974 0.25142735, 0.10285453 0.0055803806 0.25135696, 0.10246907 0.0054816008 0.2512998, 0.10165524 0.0054317042 0.25127089, 0.10440005 0.0012895018 0.24887504, 0.10423934 0.0019951612 0.24928327, 0.10412843 0.0022083372 0.24940647, 0.10398883 0.0023878962 0.2495106, 0.10382079 0.0025335401 0.24959461, 0.10356802 0.0026719049 0.24967469, 0.10329426 0.0027599409 0.24972571, 0.10290306 0.0028184727 0.2497596, 0.10241157 0.0028348565 0.24976911, 0.098596878 0.047773797 0.27576184, 0.098436192 0.048479449 0.27617013, 0.098325312 0.048692565 0.2762934, 0.098185711 0.048872102 0.27639723, 0.098017626 0.049017768 0.27648139, 0.097764827 0.049156114 0.27656162, 0.097491197 0.049244147 0.27661246, 0.097100012 0.049302675 0.27664644, 0.0966084 0.049319062 0.27665591, 0.097840451 0.053833228 0.27926683, 0.097877368 0.053369056 0.27899832, 0.097854525 0.053006608 0.27878881, 0.097789094 0.05275793 0.27864492, 0.097684294 0.052543234 0.27852058, 0.097522117 0.052344125 0.27840543, 0.097312428 0.052186172 0.27831423, 0.097051352 0.052064549 0.27824378, 0.096665949 0.051965743 0.27818668, 0.095851928 0.05191597 0.27815795, 0.091500416 -0.022005059 0.234522, -0.091499493 -0.022006363 0.234522, -0.091499545 -0.022189543 0.23450492, 0.091500513 -0.022188328 0.23450492, 0.091500424 -0.022372216 0.2344995, -0.091499552 -0.02237346 0.2344995, 0.090784959 -0.035334162 0.23449869, 0.091191337 -0.03497307 0.23449869, 0.091021597 -0.035165966 0.23449863, 0.091323949 -0.034737676 0.23449869, 0.090518586 -0.035449229 0.23449863, 0.091419309 -0.034459703 0.23449884, 0.090061307 -0.035542823 0.23449863, 0.091500625 -0.033567309 0.23449884, 0.089500681 -0.035567366 0.23449869, 0.081079811 -0.033130929 0.23449884, 0.081422672 -0.032827169 0.23449884, 0.081682928 -0.032450311 0.23449869, 0.080674283 -0.033343837 0.23449884, 0.081845328 -0.032021977 0.23449884, 0.080229506 -0.033453397 0.23449884, 0.081900507 -0.031567305 0.23449884, 0.079771526 -0.033453494 0.23449869, 0.081900537 -0.02556733 0.23449923, 0.081845298 -0.025112577 0.23449938, 0.081682846 -0.024684325 0.23449938, 0.081422657 -0.024307348 0.23449938, 0.081079818 -0.02400361 0.2344995, 0.080674283 -0.023790792 0.23449923, 0.080229506 -0.023681156 0.23449938, 0.079771407 -0.023681097 0.23449938, 0.0012729988 -0.0326951 0.23449869, 0.078318097 -0.032450244 0.23449869, 0.078578383 -0.032827243 0.23449884, 0.00096616149 -0.032966785 0.23449884, 0.078921154 -0.033130944 0.23449884, 0.0015058219 -0.032357857 0.23449899, 0.078155652 -0.03202194 0.23449899, 0.00060344115 -0.033157401 0.23449869, 0.079326846 -0.033343881 0.23449869, 0.0016511604 -0.031974711 0.23449899, 0.078100562 -0.031567372 0.23449884, 0.00020544603 -0.033255503 0.23449869, 0.0017005131 -0.031567812 0.23449884, 0.078100458 -0.025567263 0.23449923, -0.00020423904 -0.033255532 0.23449884, 0.0017005391 -0.025567845 0.23449938, 0.0016510598 -0.025160968 0.23449923, 0.078155756 -0.025112599 0.23449923, 0.0015057102 -0.024777748 0.23449923, 0.078318045 -0.024684265 0.23449923, 0.0012729168 -0.024440467 0.23449923, 0.078578308 -0.024307363 0.23449938, 0.00096631795 -0.024168849 0.23449938, 0.078921095 -0.024003573 0.2344995, 0.00060329214 -0.023978315 0.23449938, 0.079326756 -0.023790784 0.23449938, -0.078577369 -0.032828197 0.23449899, -0.0012719333 -0.032695144 0.23449884, -0.00096514821 -0.032966904 0.23449869, -0.078920208 -0.033132009 0.23449899, -0.00060224533 -0.033157386 0.23449869, -0.078317195 -0.032451317 0.23449884, -0.0015048161 -0.032357872 0.23449899, -0.079325758 -0.033344865 0.23449884, -0.07815475 -0.032023028 0.23449884, -0.0016501024 -0.031974681 0.23449884, -0.079770483 -0.033454485 0.23449869, -0.078099504 -0.031568326 0.23449899, -0.0016995519 -0.025567845 0.23449923, -0.0016995072 -0.031567872 0.23449899, -0.078099534 -0.025568374 0.23449923, -0.0016501173 -0.025161043 0.23449923, -0.078154758 -0.025113605 0.23449938, -0.0015047975 -0.024777845 0.23449938, -0.07831718 -0.02468536 0.23449923, -0.0012718812 -0.024440579 0.23449938, -0.089499503 -0.035568394 0.23449869, -0.080228567 -0.033454441 0.23449869, -0.080673181 -0.033344902 0.23449884, -0.081078812 -0.033132032 0.23449884, -0.081421621 -0.032828309 0.23449884, -0.081681959 -0.032451294 0.23449899, -0.081844211 -0.032023072 0.23449884, -0.081899554 -0.031568334 0.23449884, -0.078577422 -0.024308331 0.23449938, -0.00096520782 -0.024168812 0.23449923, -0.078920282 -0.024004623 0.23449938, -0.00060228258 -0.023978367 0.23449938, -0.07932584 -0.023791701 0.23449938, -0.091266274 -0.034852766 0.23449863, -0.09066993 -0.035391748 0.23449869, -0.090905242 -0.035259224 0.23449869, -0.091098025 -0.035089336 0.23449869, -0.091381416 -0.034586385 0.23449869, -0.090391934 -0.035487071 0.23449869, -0.091475025 -0.034129143 0.23449863, -0.091499552 -0.033568367 0.23449884, -0.081899554 -0.025568374 0.23449938, -0.081844345 -0.02511362 0.23449923, -0.081682041 -0.024685293 0.23449938, -0.081421696 -0.024308428 0.23449938, -0.081078932 -0.024004683 0.23449938, -0.080673374 -0.023791775 0.23449923, -0.080228619 -0.023682214 0.23449938, -0.079770572 -0.023682229 0.23449938, -0.00020432845 -0.023880333 0.23449938, 0.00020540133 -0.023880228 0.23449938, -0.089499488 -0.035568528 0.23549844, -0.090060182 -0.03554409 0.23549871, -0.090517461 -0.035450548 0.23549859, -0.090783842 -0.035335429 0.23549871, -0.091020428 -0.035167135 0.23549871, -0.091190368 -0.034974277 0.23549871, -0.091322832 -0.034738965 0.23549859, -0.091418192 -0.034460999 0.23549871, -0.09149956 -0.033568509 0.2354988, 0.091500573 -0.033567443 0.23549859, 0.091476128 -0.034128122 0.23549871, 0.091382533 -0.034585401 0.23549871, 0.09126737 -0.034851708 0.23549871, 0.091099247 -0.035088308 0.23549871, 0.090906464 -0.035258219 0.23549859, 0.090670995 -0.035390772 0.23549871, 0.090392992 -0.03548611 0.23549859, 0.089500666 -0.035567418 0.23549859, -0.088271759 0.066104844 0.28636563, 0.091392495 0.063712865 0.28498131, 0.090975821 0.063463867 0.28483725, 0.091500476 -0.019835792 0.23665623, 0.091728106 0.064040914 0.28517097, 0.091963306 0.06442897 0.28539568, 0.092084602 0.064854443 0.28564161, 0.10022841 -0.014598176 0.23968567, 0.091392465 0.066434093 0.28655529, 0.090975821 0.066682994 0.28669924, -0.099222571 -0.01459939 0.23968567, 0.090502501 0.066838384 0.28678906, 0.10070181 -0.014442809 0.23977543, 0.091728091 0.066106088 0.28636563, 0.092084594 0.065292664 0.28589505, 0.091963351 0.065718092 0.2861411, -0.091499582 -0.019836918 0.23665611, -0.098749086 -0.014444061 0.23977543, -0.098332487 -0.014195077 0.23991953, 0.10111836 -0.014193811 0.23991956, -0.097996831 -0.01386705 0.24010922, -0.097761422 -0.013479069 0.24033354, -0.097640388 -0.013053544 0.24057971, -0.097640388 -0.012615293 0.24083327, 0.10145412 -0.013865829 0.24010952, -0.097761564 -0.012189806 0.24107923, 0.10168938 -0.01347778 0.24033366, 0.10181055 -0.013052307 0.24057971, 0.10181048 -0.012613967 0.24083327, -0.099222526 -0.011069387 0.24172746, 0.10168944 -0.012188576 0.24107932, 0.090061963 0.0031612962 0.24995784, 0.089822106 0.0033956692 0.25009346, 0.090359569 0.0029834658 0.24985494, 0.0896542 0.0036727041 0.25025356, 0.090697631 0.0028725192 0.24979068, 0.089567527 0.0039767474 0.25042939, -0.089567028 0.0039755702 0.25042963, 0.091056623 0.0028347 0.24976911, 0.08956752 0.0042897314 0.25061035, -0.089567043 0.0042886138 0.25061053, -0.097996853 -0.011801735 0.24130388, -0.091056041 0.0028335676 0.24976911, -0.098332457 -0.011473738 0.2414936, -0.098749153 -0.011224836 0.24163754, -0.090696998 0.0028712973 0.24979068, -0.090358928 0.0029822737 0.24985494, -0.090061329 0.0031601116 0.24995784, -0.089821555 0.0033943877 0.25009346, -0.089653485 0.0036716461 0.25025374, -0.091056101 0.0054305419 0.25127107, 0.10145418 -0.011800528 0.24130379, 0.10111835 -0.011472404 0.2414936, 0.10070172 -0.01122351 0.24163742, 0.10022833 -0.011068061 0.24172746, 0.091056682 0.0054316446 0.25127089, 0.090061925 0.0051051229 0.25108206, 0.08425878 0.049645584 0.27684474, 0.089822143 0.0048708767 0.25094646, -0.085253522 0.049317926 0.27665591, 0.08401899 0.049879897 0.27698028, 0.089654081 0.0045936555 0.2507863, -0.090697177 0.0053928718 0.25124919, -0.08489456 0.049355656 0.27667761, -0.090358898 0.0052817017 0.25118506, 0.090359502 0.0052829906 0.25118506, 0.084556401 0.049467728 0.27674192, -0.08455646 0.049466763 0.27674174, -0.090061322 0.0051038563 0.25108218, 0.08385098 0.050157025 0.27714056, -0.083851032 0.050155979 0.27714056, -0.083764352 0.050459843 0.27731609, -0.084258914 0.049644541 0.27684468, -0.089821465 0.004869543 0.2509467, 0.090697624 0.0053939968 0.25124919, 0.084894583 0.049356688 0.27667779, -0.084019043 0.04987875 0.27698028, -0.089653492 0.0045923814 0.2507863, 0.083764479 0.05046092 0.27731639, 0.085253462 0.049319025 0.27665567, 0.083764553 0.0507739 0.27749729, -0.083764464 0.050772946 0.27749729, -0.083851025 0.051076781 0.27767313, 0.083850972 0.051077794 0.27767301, -0.087915391 0.065291449 0.28589505, -0.085253514 0.051914696 0.27815795, -0.089497477 0.063307323 0.28474736, -0.089024156 0.063462742 0.28483742, -0.084894523 0.051876936 0.2781359, -0.08860752 0.063711718 0.28498101, -0.084556416 0.051766012 0.27807188, -0.088271804 0.064039722 0.28517097, -0.084258825 0.051588185 0.277969, -0.088036582 0.064427748 0.28539544, -0.087915361 0.064853236 0.28564161, -0.084019043 0.051353887 0.27783346, 0.085253492 0.051915787 0.27815795, 0.084894508 0.051878087 0.2781359, 0.084556431 0.051767036 0.27807188, 0.084258839 0.051589269 0.277969, -0.088607453 0.066432871 0.28655559, -0.089024141 0.06668184 0.28669924, -0.089497492 0.066837259 0.28678894, 0.08401905 0.05135496 0.27783334, 0.090502419 0.063308567 0.28474736, -0.088036507 0.065716818 0.28614122, 0.081422687 -0.032827392 0.2354988, 0.081079863 -0.033131115 0.2354988, 0.081682898 -0.0324504 0.2354988, 0.080674358 -0.033344015 0.2354988, 0.081845284 -0.032022096 0.2354988, 0.080229558 -0.033453569 0.2354988, 0.081900492 -0.03156741 0.2354988, 0.079771511 -0.033453554 0.2354988, 0.081900537 -0.025567472 0.23549904, 0.081845321 -0.025112778 0.2354991, 0.081682913 -0.024684511 0.2354991, 0.081422642 -0.024307474 0.23549925, 0.081079766 -0.024003752 0.23549925, 0.080674216 -0.023790888 0.23549925, 0.080229498 -0.023681305 0.2354991, 0.079771504 -0.023681305 0.23549925, 0.078318238 -0.032450505 0.2354988, 0.0012730397 -0.032695308 0.2354988, 0.078578465 -0.032827429 0.23549871, 0.0009662658 -0.032967038 0.2354988, 0.078921236 -0.03313113 0.2354988, 0.078155823 -0.032022208 0.2354988, 0.0015058592 -0.032358058 0.2354988, 0.00060342625 -0.033157542 0.2354988, 0.079326816 -0.033343993 0.23549871, 0.078100532 -0.031567477 0.23549895, 0.0016511306 -0.031974822 0.2354988, 0.00020546094 -0.03325557 0.2354988, 0.0017005131 -0.031567946 0.23549895, 0.078100488 -0.025567479 0.2354991, 0.0017004311 -0.025567934 0.23549904, 0.078155681 -0.025112718 0.2354991, 0.0016510114 -0.025161058 0.2354991, 0.078318045 -0.024684466 0.2354991, 0.0015057437 -0.024777934 0.2354991, 0.078578413 -0.024307586 0.2354991, 0.0012729168 -0.024440616 0.23549925, 0.078921191 -0.024003766 0.2354991, 0.00096618384 -0.024168886 0.23549925, 0.079326726 -0.023790918 0.2354991, 0.00060330331 -0.023978427 0.23549925, -0.0012718476 -0.032695383 0.2354988, -0.078577384 -0.032828405 0.2354988, -0.00096517801 -0.032967061 0.2354988, -0.078920223 -0.033132143 0.2354988, -0.00060230121 -0.033157527 0.23549871, -0.078317031 -0.032451525 0.2354988, -0.0015047044 -0.032358065 0.2354988, -0.079325683 -0.033345044 0.23549871, -0.000204321 -0.033255607 0.23549871, -0.078154735 -0.032023236 0.23549895, -0.0016500093 -0.031974889 0.2354988, -0.079770386 -0.033454694 0.23549859, -0.078099594 -0.031568423 0.2354988, -0.00169947 -0.025568023 0.2354991, -0.0016995519 -0.031567954 0.2354988, -0.078099512 -0.025568523 0.23549925, -0.0016500838 -0.025161229 0.2354991, -0.078154773 -0.025113754 0.23549925, -0.0015047714 -0.024777979 0.2354991, -0.078317188 -0.024685554 0.2354991, -0.0012720153 -0.024440646 0.2354991, -0.080228515 -0.033454597 0.23549871, -0.080673233 -0.033345006 0.23549871, -0.081078827 -0.03313221 0.23549871, -0.081421651 -0.032828428 0.23549871, -0.081681892 -0.032451488 0.23549871, -0.081844307 -0.032023214 0.23549871, -0.081899457 -0.031568512 0.23549895, -0.078577414 -0.02430854 0.23549925, -0.00096519291 -0.024168983 0.2354991, -0.00060234591 -0.023978442 0.2354994, -0.078920335 -0.024004743 0.23549925, -0.079325862 -0.023791872 0.23549925, -0.081899635 -0.025568448 0.23549904, -0.081844449 -0.025113724 0.2354991, -0.081681944 -0.024685502 0.23549925, -0.081421718 -0.024308547 0.2354991, -0.081078917 -0.024004847 0.2354991, -0.080673285 -0.023791902 0.23549925, -0.080228567 -0.023682334 0.23549925, -0.079770535 -0.023682356 0.2354994, -0.0002043955 -0.023880407 0.23549925, 0.00020529702 -0.023880288 0.23549925, 0.46447822 0.15544431 0.070567504, 0.46492901 0.15544435 0.070738301, 0.46532574 0.15544441 0.071012244, 0.46564552 0.15544434 0.071373299, 0.46586952 0.15544435 0.071800187, 0.46598494 0.1554444 0.072268233, 0.46598491 0.15544435 0.072750553, 0.46586952 0.15544441 0.073218569, 0.46564546 0.15544435 0.073645547, 0.4653258 0.15544429 0.074006543, 0.4649289 0.1554442 0.074280247, 0.46447816 0.1554442 0.074451342, -0.46352232 0.15543841 0.070567355, -0.46307144 0.15543847 0.070738301, -0.46267459 0.15543842 0.071012154, -0.46235493 0.15543839 0.071373209, -0.46213087 0.15543839 0.071799979, -0.46201536 0.15543832 0.072268233, -0.46201554 0.15543844 0.072750404, -0.46213076 0.15543832 0.073218569, -0.46235505 0.15543841 0.073645338, -0.46267474 0.15543841 0.074006394, -0.46307144 0.15543832 0.074280247, -0.46352217 0.15543814 0.074451193, 0.4579995 0.15544638 0.03525947, 0.4579995 0.15544616 0.037759289, 0.45770034 0.15544626 0.037723139, 0.45741859 0.1554462 0.037616238, 0.45717058 0.15544634 0.037444845, 0.45697072 0.15544628 0.03721939, 0.45683071 0.15544628 0.0369526, 0.45675853 0.15544632 0.03666003, 0.45675853 0.15544632 0.03635858, 0.45683077 0.15544638 0.03606616, 0.45697078 0.15544634 0.03579922, 0.45717064 0.1554464 0.035573527, 0.45741859 0.15544638 0.035402521, 0.45770046 0.15544638 0.035295561, 0.47799954 0.15544225 0.11025937, 0.47799948 0.15544209 0.11275934, 0.47770044 0.15544201 0.1127231, 0.47741863 0.1554421 0.1126162, 0.47717062 0.15544209 0.1124451, 0.4769707 0.15544228 0.11221941, 0.47683075 0.15544227 0.11195265, 0.47675863 0.15544227 0.11165999, 0.47675863 0.15544227 0.1113586, 0.47683075 0.15544227 0.11106618, 0.47697082 0.15544225 0.11079927, 0.47717068 0.15544233 0.11057372, 0.47741863 0.15544227 0.11040254, 0.47770038 0.15544233 0.11029573, 0.47549966 0.13874008 0.16814224, -0.47550067 0.13873407 0.16814227, -0.47800085 0.15543601 0.11275934, -0.47800091 0.15543613 0.11025937, -0.47770169 0.15543619 0.11029573, -0.47742 0.1554362 0.11040254, -0.47717205 0.15543616 0.11057363, -0.47697225 0.15543619 0.11079918, -0.47683203 0.1554361 0.11106612, -0.47675988 0.15543611 0.1113586, -0.47675988 0.15543611 0.11165999, -0.47683206 0.15543601 0.11195256, -0.47697207 0.15543596 0.11221953, -0.47717193 0.15543598 0.11244495, -0.47741994 0.15543589 0.11261614, -0.47770169 0.15543589 0.11272301, -0.45800093 0.15544036 0.037759379, -0.45800075 0.15544048 0.035259321, -0.45770165 0.15544054 0.035295561, -0.45741996 0.15544048 0.035402581, -0.4571721 0.15544064 0.035573557, -0.45697209 0.15544046 0.03579922, -0.4568322 0.15544064 0.036066011, -0.45676002 0.15544042 0.03635864, -0.45675996 0.15544036 0.03666003, -0.45683211 0.15544041 0.0369526, -0.45697209 0.15544033 0.03721939, -0.45717189 0.15544026 0.037444994, -0.45741996 0.15544036 0.037616238, -0.45770156 0.15544027 0.03772299, -0.3664982 0.15343897 0.071470127, -0.36602491 0.15343897 0.071649626, -0.3656083 0.15343902 0.071937308, -0.36527261 0.15343899 0.072316274, -0.36503732 0.15343897 0.072764799, -0.36491618 0.15343902 0.07325609, -0.36491618 0.15343902 0.073762521, -0.36503735 0.15343881 0.074253872, -0.36527261 0.15343881 0.07470198, -0.3656083 0.15343878 0.075081065, -0.36602494 0.15343881 0.075368598, -0.36649832 0.15343884 0.075548127, -0.20999819 0.15343991 0.071470335, -0.20952487 0.15344001 0.071649775, -0.2091082 0.15344007 0.071937397, -0.20877251 0.15343998 0.072316274, -0.20853725 0.15343998 0.072764799, -0.20841613 0.15343995 0.07325609, -0.2084161 0.15344 0.073762521, -0.20853734 0.15343992 0.074253872, -0.20877251 0.15343982 0.07470198, -0.20910828 0.15343983 0.075081065, -0.20952481 0.15343976 0.075368837, -0.20999822 0.15343975 0.075548276, -0.20999822 0.15344833 -0.075529918, -0.20952484 0.15344831 -0.075350121, -0.20910828 0.15344833 -0.075062588, -0.20877251 0.15344822 -0.0746838, -0.20853722 0.15344818 -0.074235514, -0.20841607 0.15344821 -0.073743954, -0.208416 0.15344816 -0.073237643, -0.20853722 0.15344818 -0.072746173, -0.20877251 0.1534481 -0.072298005, -0.20910826 0.15344815 -0.071919009, -0.20952488 0.15344813 -0.071631417, -0.20999822 0.15344815 -0.071451858, -0.3664982 0.15344734 -0.075529799, -0.36602494 0.15344736 -0.075350389, -0.36560833 0.15344729 -0.075062737, -0.36527258 0.15344729 -0.0746838, -0.36503735 0.15344727 -0.074235514, -0.36491618 0.15344724 -0.073743954, -0.36491618 0.15344718 -0.073237702, -0.36503735 0.15344715 -0.072746173, -0.36527264 0.1534472 -0.072298005, -0.36560822 0.15344706 -0.071918949, -0.36602491 0.15344711 -0.071631417, -0.36649832 0.15344709 -0.071451917, 0.21222761 0.15445083 -0.072297797, 0.21246298 0.15445083 -0.072746113, 0.20952357 0.15445095 -0.075350121, 0.20999694 0.15445095 -0.075529799, 0.20910685 0.1544508 -0.071918949, 0.20877114 0.1544508 -0.072297797, 0.21258415 0.15445089 -0.073237643, 0.21258405 0.15445095 -0.073743954, 0.20952345 0.15445082 -0.071631297, 0.20853585 0.1544508 -0.072746113, 0.21049944 0.15445104 -0.075590745, 0.20999685 0.15445068 -0.071451768, 0.20841478 0.15445088 -0.073237643, 0.21246302 0.15445089 -0.074235514, 0.2104995 0.15445068 -0.071390823, 0.20841469 0.15445092 -0.073743954, 0.21100196 0.15445098 -0.075529799, 0.21100201 0.15445077 -0.071451858, 0.21222767 0.15445098 -0.074683592, 0.21147536 0.15445101 -0.075350121, 0.21189189 0.154451 -0.075062588, 0.20853588 0.15445089 -0.074235424, 0.21147537 0.15445076 -0.071631417, 0.20877115 0.15445088 -0.0746838, 0.21189193 0.15445083 -0.071918949, 0.20910682 0.15445094 -0.075062588, 0.21049945 0.15345079 -0.071390823, 0.20999683 0.15345079 -0.071451858, 0.20952348 0.15345079 -0.071631536, 0.20910686 0.15345076 -0.071919009, 0.20877114 0.15345082 -0.072298005, 0.20853588 0.15345086 -0.072746173, 0.20841466 0.15345094 -0.073237702, 0.2084147 0.15345088 -0.073743954, 0.20853586 0.15345094 -0.074235514, 0.20877117 0.15345088 -0.0746838, 0.20910683 0.15345088 -0.075062588, 0.2095235 0.15345103 -0.07535027, 0.2099968 0.15345106 -0.075529918, 0.21049938 0.15345107 -0.075590745, 0.21100201 0.15345103 -0.075529918, 0.21147534 0.15345109 -0.075350121, 0.21246296 0.15345089 -0.074235514, 0.21189199 0.153451 -0.075062737, 0.21222772 0.15345097 -0.0746838, 0.21258411 0.15345089 -0.073743954, 0.21100205 0.15345079 -0.071451858, 0.21258412 0.15345097 -0.073237702, 0.2114753 0.15345082 -0.071631417, 0.21246296 0.15345082 -0.072746173, 0.21189196 0.15345082 -0.071918949, 0.2122277 0.15345085 -0.072298005, 0.36872765 0.15444359 0.074702129, 0.36896297 0.15444344 0.074253872, 0.36560693 0.15444353 0.075081065, 0.3660236 0.15444362 0.071649775, 0.36649689 0.15444374 0.071470127, 0.36527124 0.15444353 0.07470198, 0.36908409 0.15444376 0.073762521, 0.36602357 0.15444347 0.075368837, 0.36503589 0.15444349 0.074253872, 0.36908409 0.15444376 0.07325609, 0.36649683 0.15444353 0.075548127, 0.36699948 0.15444368 0.0714093, 0.3649148 0.15444365 0.073762521, 0.36699933 0.1544435 0.075609371, 0.36896297 0.15444373 0.072764799, 0.3649148 0.15444365 0.07325609, 0.367502 0.15444352 0.075548276, 0.36750206 0.15444371 0.071470335, 0.36872765 0.15444376 0.072316274, 0.36503604 0.15444362 0.072764799, 0.36797538 0.15444371 0.071649775, 0.36839202 0.15444376 0.071937397, 0.36797544 0.15444353 0.075368986, 0.3652713 0.15444365 0.072316274, 0.36839196 0.15444355 0.075081155, 0.36560693 0.15444368 0.071937397, 0.36699948 0.15344352 0.075609371, 0.36649689 0.15344352 0.075548276, 0.36602357 0.1534435 0.075368837, 0.36560693 0.15344352 0.075081155, 0.3652713 0.1534435 0.07470198, 0.36503598 0.15344357 0.074253872, 0.3649148 0.15344363 0.073762372, 0.3649148 0.15344368 0.07325606, 0.36503604 0.15344363 0.072764799, 0.36527127 0.15344362 0.072316274, 0.36560693 0.15344366 0.071937308, 0.36602357 0.15344366 0.071649775, 0.36649695 0.15344372 0.071470127, 0.36699942 0.15344378 0.071409211, 0.36797538 0.15344372 0.071649626, 0.36750206 0.15344378 0.071470127, 0.36839202 0.15344372 0.071937308, 0.36872777 0.15344366 0.072316125, 0.36896309 0.15344366 0.072764799, 0.36908415 0.15344369 0.07325606, 0.36908415 0.15344369 0.073762372, 0.36896297 0.15344359 0.074253872, 0.36750212 0.15344346 0.075548276, 0.36797532 0.15344349 0.075368837, 0.36872771 0.15344359 0.074702129, 0.36839202 0.15344352 0.075081155, 0.20999683 0.15444247 0.075548276, 0.20952353 0.15444241 0.075368837, 0.21049933 0.15444241 0.075609371, 0.21246296 0.15444261 0.072764799, 0.21258415 0.15444264 0.07325609, 0.20910682 0.15444268 0.071937397, 0.20877112 0.15444267 0.072316274, 0.20952342 0.15444273 0.071649775, 0.20853579 0.15444274 0.072764799, 0.20999683 0.1544427 0.071470335, 0.21258411 0.15444264 0.073762521, 0.20841467 0.15444267 0.07325609, 0.21049935 0.15444267 0.0714093, 0.21100198 0.15444246 0.075548276, 0.21147542 0.15444246 0.075368837, 0.20841467 0.15444267 0.073762521, 0.21246296 0.15444249 0.074254021, 0.21189199 0.15444243 0.075081155, 0.21100199 0.1544427 0.071470335, 0.2122277 0.15444243 0.074702129, 0.20853584 0.15444252 0.074253872, 0.21147525 0.15444271 0.071649775, 0.20877108 0.15444252 0.074702129, 0.21189195 0.1544427 0.071937457, 0.20910677 0.15444252 0.075081304, 0.21222772 0.15444267 0.072316274, 0.21049936 0.15344252 0.075609371, 0.20999676 0.15344249 0.075548276, 0.20952353 0.15344246 0.075368598, 0.20910685 0.15344244 0.075081065, 0.20877118 0.15344241 0.07470198, 0.20853579 0.15344253 0.074253872, 0.20841472 0.15344265 0.073762521, 0.20841476 0.15344265 0.07325609, 0.20853586 0.15344265 0.07276459, 0.2087712 0.15344265 0.072316125, 0.20910686 0.15344267 0.071937397, 0.20952345 0.15344271 0.071649775, 0.20999683 0.15344265 0.071470335, 0.21049938 0.15344273 0.0714093, 0.21147527 0.15344283 0.071649775, 0.21100199 0.15344274 0.071470335, 0.21246287 0.15344273 0.07276459, 0.21189202 0.15344262 0.071937397, 0.21222767 0.15344276 0.072316125, 0.21258412 0.15344265 0.07325606, 0.21258417 0.15344259 0.073762521, 0.21147534 0.1534425 0.075368837, 0.21246305 0.1534425 0.074253872, 0.21100196 0.15344249 0.075548276, 0.21189204 0.15344247 0.075081155, 0.21222773 0.15344253 0.074702129, 0.40029863 0.15444079 0.12522291, 0.40058038 0.15444088 0.12511621, 0.40082845 0.154441 0.124945, 0.40102819 0.15444097 0.12471937, 0.39999953 0.15444086 0.12525927, 0.39917067 0.15444098 0.12307371, 0.39941862 0.15444101 0.12290253, 0.4011682 0.15444097 0.12445258, 0.39970037 0.15444103 0.12279569, 0.40124026 0.15444106 0.12416004, 0.39999953 0.154441 0.12275933, 0.39917061 0.15444095 0.12494515, 0.39897081 0.154441 0.12471937, 0.39941862 0.15444081 0.12511609, 0.3988308 0.15444095 0.12445258, 0.39970037 0.15444086 0.12522291, 0.39875868 0.15444098 0.12415992, 0.40124038 0.15444103 0.12385871, 0.40116835 0.15444103 0.12356614, 0.40102831 0.154441 0.12329923, 0.40082851 0.154441 0.12307371, 0.4005805 0.154441 0.12290265, 0.40029868 0.154441 0.12279569, 0.39875856 0.154441 0.12385871, 0.3988308 0.154441 0.12356614, 0.39897081 0.15444101 0.12329923, 0.39999953 0.15344107 0.12275924, 0.39970037 0.15344106 0.1227956, 0.39941862 0.153441 0.12290253, 0.39917067 0.15344098 0.12307371, 0.39897075 0.15344097 0.12329923, 0.39883086 0.15344098 0.12356614, 0.39875865 0.15344106 0.12385856, 0.39875874 0.15344098 0.12415992, 0.39883074 0.15344097 0.12445258, 0.39897081 0.15344106 0.12471937, 0.39917061 0.15344098 0.12494482, 0.39941862 0.15344086 0.12511609, 0.39970037 0.15344088 0.12522291, 0.39999953 0.15344085 0.12525915, 0.40082845 0.15344106 0.12307371, 0.4011682 0.15344103 0.12356602, 0.40102825 0.15344098 0.12329923, 0.40029863 0.15344086 0.12522291, 0.40029863 0.15344107 0.1227956, 0.40116826 0.15344098 0.12445258, 0.40124038 0.153441 0.12385871, 0.40124038 0.153441 0.12415992, 0.40058038 0.15344085 0.12511595, 0.40058038 0.15344106 0.12290238, 0.40082839 0.15344106 0.124945, 0.40102825 0.15344098 0.12471937, 0.28529853 0.15444019 0.12522291, 0.28558037 0.15444022 0.12511609, 0.28582832 0.15444025 0.12494515, 0.28602824 0.15444019 0.12471949, 0.28499949 0.15444008 0.12525938, 0.28417054 0.15444031 0.12307359, 0.28441855 0.15444031 0.12290265, 0.28616816 0.15444025 0.1244527, 0.2847003 0.1544403 0.1227956, 0.28624034 0.15444031 0.12415992, 0.28499946 0.15444025 0.12275945, 0.28417048 0.15444028 0.124945, 0.28397068 0.15444025 0.12471949, 0.28441855 0.15444013 0.12511609, 0.28383061 0.15444031 0.12445258, 0.28470024 0.15444015 0.12522303, 0.28624034 0.15444031 0.12385882, 0.28616831 0.15444025 0.12356617, 0.28602824 0.15444031 0.12329923, 0.28375849 0.15444025 0.12415992, 0.28582832 0.1544403 0.12307371, 0.28558031 0.15444036 0.12290253, 0.28529856 0.15444034 0.12279569, 0.28375864 0.15444019 0.12385882, 0.28383067 0.15444034 0.12356614, 0.28397068 0.15444025 0.12329911, 0.28499958 0.15344024 0.12275933, 0.28470036 0.15344036 0.12279569, 0.28441861 0.15344022 0.12290238, 0.28417054 0.15344033 0.12307371, 0.28397071 0.15344033 0.12329923, 0.28383067 0.15344028 0.12356602, 0.28375855 0.15344027 0.12385871, 0.28375855 0.15344033 0.12415992, 0.28383073 0.15344027 0.12445246, 0.2839708 0.15344022 0.12471937, 0.2841706 0.15344027 0.12494482, 0.28441855 0.15344016 0.12511595, 0.28470019 0.15344018 0.1252227, 0.28499946 0.15344015 0.12525927, 0.28529856 0.15344033 0.1227956, 0.28582844 0.15344027 0.12307371, 0.28558043 0.15344028 0.12290253, 0.28602827 0.15344027 0.12329923, 0.28616828 0.15344027 0.12356602, 0.2862404 0.15344025 0.12385871, 0.28624034 0.15344027 0.12415992, 0.28529873 0.15344003 0.12522291, 0.28616831 0.15344024 0.12445246, 0.28602824 0.15344021 0.12471937, 0.28558049 0.15344006 0.12511595, 0.28582844 0.15344021 0.12494482, 0.18999937 0.1544396 0.12525927, 0.18917044 0.15443966 0.12307371, 0.18941849 0.15443972 0.12290253, 0.19116814 0.15443967 0.12445258, 0.19102815 0.15443966 0.12471937, 0.18970026 0.15443969 0.12279569, 0.19124019 0.15443975 0.12416004, 0.18999942 0.15443963 0.12275933, 0.18917044 0.15443966 0.12494515, 0.1889707 0.15443966 0.12471925, 0.18941841 0.15443954 0.12511609, 0.18883063 0.1544396 0.12445258, 0.18970022 0.15443954 0.12522291, 0.18875845 0.15443966 0.12415992, 0.19124025 0.15443973 0.12385871, 0.19116814 0.15443967 0.12356602, 0.19102818 0.1544396 0.12329929, 0.19082826 0.1544397 0.12307371, 0.19058026 0.15443973 0.12290253, 0.19029857 0.15443967 0.12279569, 0.18875851 0.15443969 0.12385856, 0.18883061 0.15443964 0.12356602, 0.18897066 0.15443966 0.12329923, 0.19029853 0.15443954 0.12522291, 0.19058029 0.1544396 0.12511621, 0.19082817 0.15443972 0.124945, 0.18999946 0.1534396 0.12275933, 0.18970022 0.15343973 0.12279569, 0.18941863 0.15343964 0.12290253, 0.18917048 0.15343973 0.12307371, 0.18897066 0.15343973 0.12329923, 0.18883063 0.15343967 0.12356614, 0.18875855 0.15343966 0.12385871, 0.18875848 0.15343973 0.12415992, 0.18883063 0.15343967 0.12445246, 0.18897066 0.15343966 0.12471937, 0.18917055 0.15343964 0.12494482, 0.18941848 0.15343955 0.12511595, 0.1897002 0.1534396 0.12522291, 0.18999939 0.15343955 0.12525938, 0.19029854 0.15343973 0.1227956, 0.19082829 0.15343973 0.12307359, 0.19058032 0.15343967 0.12290238, 0.19102813 0.15343967 0.12329911, 0.19116819 0.15343967 0.12356614, 0.19124025 0.15343972 0.12385871, 0.19124025 0.15343972 0.12415971, 0.19029856 0.15343949 0.12522291, 0.19116819 0.15343963 0.12445258, 0.19102813 0.15343961 0.12471937, 0.19058037 0.15343951 0.12511609, 0.19082832 0.15343961 0.124945, 0.15517053 0.15443945 0.12307371, 0.15541849 0.15443945 0.12290253, 0.15716815 0.15443946 0.12445258, 0.15702808 0.15443946 0.12471949, 0.1557003 0.15443945 0.12279572, 0.15724029 0.15443946 0.12415992, 0.15599939 0.15443945 0.12275933, 0.15517047 0.15443939 0.12494482, 0.15497062 0.15443939 0.12471937, 0.15541849 0.15443933 0.12511609, 0.15483057 0.15443945 0.12445246, 0.15570025 0.1544393 0.12522291, 0.15475845 0.15443945 0.12415971, 0.15724021 0.15443949 0.12385882, 0.15716815 0.15443945 0.12356614, 0.15702808 0.15443946 0.12329923, 0.1568283 0.15443946 0.12307371, 0.15658034 0.15443945 0.12290253, 0.15629852 0.15443945 0.12279569, 0.15599939 0.1544393 0.12525938, 0.15475854 0.15443943 0.12385871, 0.15483057 0.15443954 0.12356614, 0.15497066 0.15443945 0.12329923, 0.15629846 0.15443935 0.12522303, 0.1565803 0.15443932 0.12511609, 0.1568283 0.15443946 0.124945, 0.15599942 0.15343946 0.12275933, 0.15570027 0.15343949 0.12279569, 0.1554185 0.15343952 0.12290253, 0.15517047 0.15343946 0.12307371, 0.15497065 0.15343952 0.12329923, 0.15483066 0.15343949 0.12356602, 0.15475844 0.15343948 0.12385856, 0.15475845 0.15343952 0.12415992, 0.15483063 0.15343945 0.12445246, 0.15497065 0.15343945 0.12471925, 0.15517054 0.1534394 0.12494482, 0.15541849 0.15343934 0.12511609, 0.15570024 0.15343934 0.12522291, 0.15599936 0.15343937 0.12525915, 0.15629856 0.15343949 0.1227956, 0.15682837 0.15343946 0.12307359, 0.15658033 0.15343946 0.12290238, 0.15702814 0.15343946 0.12329911, 0.1571683 0.1534394 0.12356614, 0.15724029 0.15343948 0.12385871, 0.1572403 0.15343948 0.12415971, 0.15629858 0.15343922 0.1252227, 0.15716828 0.15343939 0.12445258, 0.15702805 0.15343948 0.12471937, 0.1565803 0.15343931 0.12511595, 0.15682827 0.15343942 0.12494515, -0.15600076 0.15443726 0.12525915, -0.15570167 0.15443726 0.1252227, -0.15541986 0.15443733 0.12511609, -0.1551719 0.15443745 0.124945, -0.15497205 0.15443748 0.12471937, -0.15682966 0.15443747 0.12307359, -0.15658164 0.15443744 0.12290253, -0.15483209 0.15443751 0.12445258, -0.15629983 0.15443744 0.1227956, -0.15475985 0.15443745 0.12415992, -0.15600079 0.15443754 0.12275945, -0.15682966 0.15443744 0.124945, -0.15702945 0.15443738 0.12471937, -0.15658167 0.15443733 0.12511609, -0.15716961 0.1544375 0.1244527, -0.15475985 0.15443745 0.12385871, -0.15629986 0.15443726 0.12522303, -0.15724164 0.15443744 0.12415992, -0.15483209 0.15443751 0.12356617, -0.15497211 0.15443751 0.12329923, -0.1551719 0.15443751 0.12307371, -0.15541986 0.15443748 0.12290253, -0.15570167 0.15443751 0.12279569, -0.15724164 0.15443744 0.12385871, -0.15716961 0.15443753 0.12356614, -0.15702939 0.15443744 0.12329911, -0.15600076 0.15343753 0.12275933, -0.1562999 0.15343748 0.12279569, -0.1565817 0.15343753 0.12290238, -0.15682966 0.15343751 0.12307371, -0.15702945 0.15343748 0.12329923, -0.15716952 0.15343748 0.12356602, -0.15724167 0.15343745 0.12385871, -0.15724167 0.15343745 0.12415992, -0.15716955 0.15343745 0.12445258, -0.15702945 0.15343742 0.12471925, -0.15682968 0.15343745 0.124945, -0.15658167 0.15343735 0.12511595, -0.1562999 0.15343732 0.1252227, -0.15600073 0.15343735 0.12525927, -0.15570161 0.15343747 0.1227956, -0.15517178 0.15343741 0.12307359, -0.15541986 0.15343753 0.12290253, -0.15497197 0.15343744 0.12329911, -0.15483193 0.15343744 0.12356602, -0.15475991 0.15343753 0.12385871, -0.15475987 0.15343744 0.12415992, -0.15570159 0.15343729 0.12522291, -0.15483204 0.15343747 0.12445258, -0.15497205 0.15343747 0.12471937, -0.15541989 0.15343735 0.12511609, -0.15517184 0.15343747 0.12494482, -0.19000076 0.15443701 0.12525927, -0.18970156 0.15443702 0.12522291, -0.18941993 0.15443707 0.12511621, -0.18917184 0.15443718 0.124945, -0.18897209 0.15443726 0.12471937, -0.19082972 0.15443729 0.12307371, -0.19058165 0.15443724 0.12290253, -0.18883204 0.15443727 0.12445258, -0.19029996 0.15443729 0.12279569, -0.18875992 0.15443724 0.12416004, -0.19000083 0.15443729 0.12275933, -0.19082972 0.15443724 0.12494515, -0.19102956 0.15443726 0.12471949, -0.19058165 0.15443704 0.12511609, -0.19116962 0.1544373 0.12445258, -0.19029993 0.15443711 0.12522291, -0.19124167 0.15443726 0.12415992, -0.18875991 0.15443726 0.12385871, -0.18883204 0.15443727 0.12356614, -0.188972 0.1544372 0.12329923, -0.19124165 0.15443717 0.12385871, -0.18917179 0.15443718 0.12307371, -0.18941987 0.15443727 0.12290265, -0.18970165 0.15443726 0.12279569, -0.19116962 0.15443733 0.12356614, -0.19102956 0.15443729 0.12329923, -0.19000074 0.1534373 0.12275933, -0.19029985 0.15343723 0.12279569, -0.19058162 0.15343729 0.12290253, -0.19082966 0.15343724 0.12307371, -0.19102946 0.15343721 0.12329911, -0.19116953 0.1534373 0.12356614, -0.19124162 0.15343721 0.12385856, -0.19124162 0.15343721 0.12415971, -0.19116953 0.15343723 0.12445246, -0.19102955 0.15343727 0.12471937, -0.19082966 0.15343724 0.124945, -0.19058168 0.15343708 0.12511595, -0.19029991 0.15343709 0.12522291, -0.19000082 0.15343709 0.12525927, -0.18970165 0.15343724 0.12279569, -0.18917182 0.15343724 0.12307371, -0.1894199 0.15343729 0.12290265, -0.18897201 0.15343723 0.12329923, -0.188832 0.15343723 0.12356614, -0.18875989 0.15343724 0.12385871, -0.18875995 0.15343733 0.12415992, -0.18970162 0.15343711 0.12522291, -0.188832 0.15343723 0.12445246, -0.18897209 0.15343724 0.12471937, -0.1894199 0.15343715 0.12511609, -0.18917184 0.15343723 0.124945, -0.2850008 0.15443647 0.12525938, -0.2847017 0.15443644 0.12522303, -0.28441989 0.1544365 0.12511609, -0.28417188 0.15443662 0.124945, -0.28397217 0.15443668 0.12471949, -0.28582978 0.15443668 0.12307371, -0.28558174 0.15443666 0.12290253, -0.28383207 0.15443671 0.1244527, -0.28530002 0.15443671 0.12279569, -0.28375995 0.15443665 0.12415971, -0.28500086 0.15443671 0.12275945, -0.28582972 0.15443659 0.12494482, -0.28602949 0.15443656 0.12471937, -0.28558183 0.15443651 0.12511609, -0.28616968 0.15443666 0.12445258, -0.28529996 0.15443647 0.12522291, -0.28624171 0.1544366 0.12415971, -0.28376001 0.15443671 0.12385882, -0.28383207 0.15443671 0.12356614, -0.28397217 0.15443668 0.12329911, -0.28624165 0.15443659 0.12385871, -0.28417188 0.15443662 0.12307371, -0.28441989 0.15443665 0.12290253, -0.2847017 0.1544366 0.1227956, -0.28616962 0.15443672 0.12356614, -0.28602958 0.15443671 0.12329923, -0.2850008 0.15343665 0.12275933, -0.2852999 0.15343666 0.12279569, -0.28558171 0.15343671 0.12290253, -0.28582969 0.15343669 0.12307371, -0.28602952 0.15343666 0.12329911, -0.28616956 0.15343669 0.12356614, -0.28624162 0.1534366 0.12385856, -0.28624171 0.15343663 0.12415992, -0.28616968 0.15343663 0.12445258, -0.28602943 0.1534366 0.12471925, -0.28582981 0.15343665 0.124945, -0.28558177 0.15343647 0.12511609, -0.28529996 0.15343656 0.12522291, -0.2850008 0.15343648 0.12525915, -0.28470168 0.1534366 0.1227956, -0.28441989 0.15343663 0.12290238, -0.28397202 0.15343663 0.12329911, -0.28417188 0.15343666 0.12307359, -0.2838321 0.1534366 0.12356614, -0.28375995 0.15343672 0.12385871, -0.28375995 0.15343672 0.12415992, -0.28470165 0.15343642 0.1252227, -0.2838321 0.1534366 0.12445258, -0.28441989 0.15343648 0.12511609, -0.28397211 0.1534366 0.12471937, -0.28417197 0.1534366 0.124945, -0.40000096 0.15443578 0.12525927, -0.39970168 0.15443569 0.12522291, -0.39941999 0.15443577 0.12511621, -0.39917204 0.1544359 0.12494515, -0.39897224 0.15443592 0.12471937, -0.40082982 0.15443596 0.12307371, -0.40058187 0.15443598 0.12290253, -0.39883205 0.15443587 0.1244527, -0.4003 0.1544359 0.12279569, -0.39876005 0.15443587 0.12416004, -0.4000009 0.15443589 0.12275933, -0.40082976 0.15443587 0.12494515, -0.40102956 0.15443589 0.12471937, -0.40058178 0.15443578 0.12511609, -0.40116963 0.15443581 0.12445258, -0.39876005 0.15443587 0.12385871, -0.4003 0.15443569 0.12522291, -0.4012416 0.15443584 0.12416004, -0.39883205 0.15443587 0.12356614, -0.39897212 0.1544359 0.12329929, -0.39917204 0.1544359 0.12307371, -0.39942005 0.1544359 0.12290253, -0.39970168 0.1544359 0.12279569, -0.40124172 0.15443589 0.12385871, -0.40116969 0.15443586 0.12356614, -0.40102956 0.15443589 0.12329923, -0.40000078 0.15343586 0.12275924, -0.4003 0.15343587 0.12279569, -0.40058178 0.15343598 0.12290253, -0.40082982 0.15343598 0.12307371, -0.40102956 0.1534359 0.12329923, -0.4011696 0.15343584 0.12356614, -0.40124175 0.15343586 0.12385871, -0.40124175 0.15343586 0.12415971, -0.4011696 0.15343584 0.12445246, -0.40102968 0.15343589 0.12471937, -0.40082976 0.15343583 0.124945, -0.40058187 0.15343584 0.12511609, -0.40030012 0.15343577 0.12522291, -0.40000087 0.15343577 0.12525927, -0.39970168 0.15343589 0.12279569, -0.39941987 0.15343592 0.12290253, -0.39897212 0.15343589 0.12329923, -0.39917195 0.1534359 0.12307371, -0.39883208 0.1534359 0.12356614, -0.39876011 0.15343593 0.12385871, -0.39875987 0.15343592 0.12415992, -0.39970168 0.15343577 0.12522291, -0.39883205 0.15343589 0.12445246, -0.39941999 0.15343566 0.12511609, -0.39897212 0.15343592 0.12471937, -0.3991721 0.15343592 0.124945, -7.1898035e-07 0.15443836 0.12525938, -0.00082950667 0.15443841 0.12307371, -0.00058156624 0.15443844 0.12290253, 0.0011680797 0.15443841 0.12445246, 0.0010281429 0.15443838 0.12471937, -0.00029975921 0.15443841 0.12279572, 0.0012402013 0.15443839 0.12415992, -6.3702396e-07 0.15443845 0.12275933, -0.00082954392 0.15443838 0.124945, -0.0010294206 0.15443844 0.12471937, -0.0005816035 0.15443829 0.12511609, 0.0012402348 0.15443844 0.12385871, -0.0011694506 0.15443838 0.12445258, -0.00029983371 0.15443823 0.12522291, 0.0011680238 0.15443854 0.12356614, 0.0010279939 0.15443854 0.12329923, -0.0012415871 0.15443841 0.12415992, 0.00082815439 0.15443851 0.12307371, 0.00058021024 0.15443848 0.12290253, 0.00029843673 0.15443854 0.12279569, -0.0012416169 0.15443847 0.12385871, -0.0011694506 0.15443838 0.12356614, -0.0010293797 0.15443844 0.12329923, 0.00029846653 0.15443827 0.12522291, 0.00058025867 0.15443824 0.12511609, 0.00082818791 0.15443836 0.124945, -7.2643093e-07 0.15343849 0.12275933, -0.00029984489 0.15343851 0.12279569, -0.00058156624 0.15343848 0.12290238, -0.00082957372 0.15343848 0.12307371, -0.0010293908 0.15343842 0.12329923, -0.0011694133 0.15343845 0.12356614, -0.0012415983 0.15343848 0.12385871, -0.0012415685 0.15343842 0.12415992, -0.0011694431 0.15343848 0.12445258, -0.0010294169 0.15343848 0.12471937, -0.00082958117 0.15343842 0.124945, -0.00058151782 0.15343818 0.12511595, -0.00029980019 0.15343827 0.12522291, -6.3702396e-07 0.15343828 0.12525927, 0.00029845163 0.15343852 0.12279569, 0.00082819164 0.15343855 0.12307371, 0.00058017671 0.15343849 0.12290238, 0.0010280125 0.15343852 0.12329923, 0.0011680871 0.15343851 0.12356602, 0.0012402236 0.15343846 0.12385871, 0.0012401901 0.15343849 0.12415992, 0.00029848143 0.15343828 0.12522291, 0.0011680871 0.15343851 0.12445258, 0.0010280721 0.15343843 0.12471937, 0.00058026612 0.15343828 0.12511609, 0.00082829595 0.15343837 0.12494482, 0.39999953 0.15445481 -0.12274079, 0.39917055 0.15445505 -0.12492646, 0.39941856 0.15445504 -0.12509756, 0.40116826 0.15445481 -0.12354748, 0.40102813 0.15445486 -0.12328069, 0.39970037 0.15445502 -0.12520446, 0.40124044 0.15445492 -0.12384014, 0.39999947 0.15445504 -0.12524076, 0.39917067 0.15445481 -0.12305529, 0.39897069 0.15445498 -0.12328069, 0.39941856 0.15445483 -0.12288399, 0.39883068 0.15445492 -0.12354754, 0.39970037 0.15445484 -0.12277709, 0.39875862 0.15445492 -0.12384005, 0.40124032 0.15445504 -0.12414156, 0.40116832 0.15445492 -0.12443398, 0.40102819 0.15445495 -0.12470095, 0.40082842 0.15445501 -0.12492646, 0.40058044 0.15445504 -0.12509756, 0.40029863 0.15445504 -0.12520452, 0.39875862 0.15445492 -0.12414141, 0.39883068 0.15445502 -0.12443407, 0.39897072 0.15445507 -0.12470095, 0.40029868 0.15445474 -0.12277703, 0.40058038 0.15445486 -0.12288408, 0.40082845 0.15445483 -0.12305529, 0.39999947 0.15345509 -0.12524076, 0.39970031 0.153455 -0.12520452, 0.39941856 0.153455 -0.12509762, 0.39917061 0.15345502 -0.12492646, 0.39897081 0.15345502 -0.12470095, 0.39883071 0.15345503 -0.12443407, 0.39875862 0.15345497 -0.1241415, 0.39875868 0.1534548 -0.1238402, 0.39883074 0.1534548 -0.12354763, 0.39897081 0.15345488 -0.12328069, 0.39917073 0.15345481 -0.12305538, 0.39941862 0.15345483 -0.12288408, 0.39970037 0.1534549 -0.1227773, 0.39999953 0.15345488 -0.12274094, 0.40082857 0.15345493 -0.12492652, 0.40116832 0.15345493 -0.12443407, 0.40102831 0.15345493 -0.12470095, 0.40029868 0.15345488 -0.1227773, 0.40029868 0.15345493 -0.12520461, 0.40116826 0.15345484 -0.12354763, 0.40124044 0.15345493 -0.12414156, 0.40124044 0.15345481 -0.12384014, 0.40058038 0.15345488 -0.12288408, 0.40058044 0.153455 -0.12509771, 0.40082851 0.1534548 -0.12305529, 0.40102825 0.15345484 -0.12328075, 0.28616813 0.15445417 -0.12354754, 0.28602812 0.15445417 -0.12328069, 0.28441855 0.15445426 -0.12509762, 0.2847003 0.15445423 -0.12520452, 0.28624037 0.15445417 -0.12384005, 0.28499946 0.1544542 -0.12524076, 0.2841706 0.15445408 -0.12305529, 0.28397074 0.15445414 -0.12328069, 0.28441855 0.15445414 -0.12288408, 0.28383067 0.15445417 -0.12354763, 0.2847003 0.15445414 -0.12277709, 0.28624031 0.15445423 -0.1241415, 0.28616819 0.15445428 -0.12443398, 0.28602818 0.15445428 -0.12470095, 0.28582832 0.15445425 -0.12492631, 0.28558031 0.15445431 -0.12509756, 0.28529859 0.15445431 -0.12520452, 0.28375855 0.15445414 -0.12384014, 0.28499949 0.1544541 -0.12274079, 0.28375861 0.1544542 -0.1241415, 0.28383067 0.15445426 -0.12443407, 0.28397068 0.15445429 -0.12470086, 0.28417045 0.15445429 -0.12492646, 0.28529856 0.15445408 -0.12277709, 0.28558034 0.15445408 -0.12288399, 0.28582835 0.15445413 -0.12305529, 0.28499952 0.15345423 -0.12524091, 0.2847003 0.15345427 -0.12520461, 0.28441861 0.15345423 -0.12509771, 0.2841706 0.15345427 -0.12492661, 0.28397071 0.15345427 -0.12470095, 0.28383067 0.15345427 -0.12443422, 0.28375855 0.15345423 -0.12414156, 0.28375861 0.15345418 -0.12384014, 0.2838307 0.15345414 -0.12354763, 0.28397074 0.15345415 -0.12328084, 0.2841706 0.15345408 -0.12305529, 0.28441861 0.15345407 -0.12288408, 0.2847003 0.15345415 -0.1227773, 0.28499952 0.15345411 -0.12274079, 0.28529862 0.1534543 -0.12520461, 0.28602824 0.1534543 -0.12470101, 0.28558043 0.15345421 -0.12509771, 0.28582838 0.15345424 -0.12492652, 0.28616825 0.15345423 -0.12443407, 0.28624034 0.15345421 -0.1241415, 0.28624028 0.15345418 -0.12384014, 0.28529856 0.15345415 -0.1227773, 0.28616825 0.15345412 -0.12354763, 0.28602824 0.15345411 -0.12328084, 0.28558037 0.1534541 -0.12288399, 0.28582838 0.15345411 -0.12305529, 0.18999946 0.15445349 -0.12274079, 0.19029856 0.1544535 -0.12277709, 0.19058032 0.1544535 -0.12288399, 0.19082831 0.15445355 -0.12305529, 0.1910281 0.15445358 -0.12328069, 0.18917042 0.15445367 -0.12492631, 0.18941851 0.15445361 -0.12509756, 0.19116819 0.15445349 -0.12354748, 0.18970025 0.15445367 -0.12520446, 0.19124028 0.15445356 -0.12384014, 0.18999943 0.15445361 -0.12524076, 0.18917049 0.15445352 -0.12305529, 0.1889706 0.15445355 -0.12328069, 0.18941851 0.15445349 -0.12288399, 0.18883055 0.15445355 -0.12354754, 0.18970022 0.15445358 -0.12277709, 0.19124027 0.15445362 -0.1241415, 0.19116816 0.15445362 -0.12443407, 0.19102816 0.15445355 -0.12470095, 0.19082832 0.15445362 -0.12492646, 0.19058025 0.15445367 -0.12509756, 0.1902985 0.15445367 -0.12520446, 0.18875846 0.15445355 -0.12384005, 0.18875845 0.15445367 -0.1241415, 0.1888307 0.15445359 -0.12443407, 0.18897063 0.15445369 -0.12470095, 0.1899994 0.15345369 -0.12524076, 0.18970022 0.15345368 -0.12520461, 0.1894186 0.15345362 -0.12509762, 0.18917049 0.15345368 -0.12492652, 0.1889707 0.15345365 -0.12470095, 0.18883063 0.15345362 -0.12443407, 0.18875848 0.15345362 -0.12414156, 0.18875851 0.15345359 -0.12384014, 0.18883063 0.15345359 -0.12354763, 0.18897064 0.15345359 -0.12328069, 0.18917046 0.15345359 -0.12305538, 0.18941861 0.15345347 -0.12288408, 0.18970026 0.15345353 -0.1227773, 0.18999942 0.15345353 -0.12274079, 0.19029857 0.15345363 -0.12520461, 0.19102809 0.15345369 -0.12470095, 0.19058035 0.15345363 -0.12509771, 0.19082829 0.15345362 -0.12492652, 0.19116819 0.15345369 -0.12443407, 0.19124025 0.15345366 -0.12414156, 0.19124027 0.15345357 -0.12384014, 0.19029854 0.15345353 -0.1227773, 0.19116816 0.15345351 -0.12354763, 0.19102821 0.1534535 -0.12328075, 0.19058032 0.15345353 -0.12288399, 0.19082828 0.15345354 -0.12305529, 0.15599944 0.15445328 -0.12274085, 0.1551705 0.15445343 -0.12492646, 0.15541847 0.15445346 -0.12509762, 0.15716818 0.15445328 -0.12354754, 0.15702814 0.15445328 -0.12328069, 0.1557003 0.15445338 -0.12520446, 0.15724024 0.15445335 -0.12384014, 0.15599932 0.15445346 -0.12524076, 0.1551705 0.15445328 -0.12305529, 0.15497065 0.15445332 -0.12328069, 0.15541852 0.15445328 -0.12288399, 0.15483057 0.15445332 -0.12354754, 0.15570024 0.15445328 -0.1227773, 0.15724024 0.15445335 -0.1241415, 0.15716822 0.15445341 -0.12443407, 0.15702809 0.15445343 -0.12470086, 0.15682828 0.1544534 -0.12492631, 0.15658024 0.15445346 -0.12509756, 0.15629853 0.15445343 -0.12520452, 0.15475845 0.15445337 -0.12384014, 0.15475857 0.1544534 -0.1241415, 0.1548306 0.1544534 -0.12443407, 0.15497065 0.15445343 -0.12470095, 0.15629855 0.15445328 -0.12277703, 0.15658034 0.15445328 -0.12288408, 0.1568283 0.15445328 -0.12305529, 0.15599941 0.15345347 -0.12524091, 0.15570021 0.15345341 -0.12520452, 0.1554185 0.15345347 -0.12509771, 0.1551705 0.15345341 -0.12492646, 0.15497068 0.15345347 -0.12470095, 0.15483066 0.15345344 -0.12443422, 0.15475851 0.15345344 -0.12414156, 0.1547585 0.15345335 -0.12384014, 0.15483063 0.15345332 -0.12354763, 0.15497071 0.15345329 -0.12328075, 0.15517052 0.15345329 -0.12305529, 0.15541844 0.15345338 -0.12288399, 0.15570021 0.15345326 -0.12277709, 0.15599936 0.15345338 -0.12274085, 0.15629855 0.15345347 -0.12520452, 0.15702815 0.15345341 -0.12470095, 0.1565803 0.15345348 -0.12509771, 0.1568284 0.15345338 -0.12492652, 0.15716816 0.15345341 -0.12443407, 0.15724027 0.15345341 -0.12414156, 0.15724026 0.15345336 -0.12384014, 0.15629849 0.15345329 -0.12277709, 0.15716818 0.15345329 -0.12354754, 0.15702814 0.15345329 -0.12328069, 0.15658024 0.15345335 -0.12288408, 0.15682831 0.15345331 -0.12305529, -0.1554198 0.15445128 -0.12288399, -0.15517184 0.15445134 -0.12305529, -0.15497205 0.15445131 -0.12328069, -0.15600082 0.1544514 -0.12274079, -0.15682968 0.15445144 -0.12492631, -0.15658166 0.15445144 -0.12509756, -0.15483204 0.15445134 -0.12354748, -0.15629989 0.15445141 -0.12520446, -0.15475985 0.15445134 -0.12384014, -0.15600073 0.15445139 -0.12524076, -0.15682963 0.15445127 -0.12305529, -0.15702949 0.15445131 -0.12328069, -0.15658167 0.15445128 -0.12288408, -0.15716958 0.15445136 -0.12354754, -0.15629983 0.15445128 -0.1227773, -0.15475985 0.15445134 -0.1241415, -0.15483204 0.15445143 -0.12443407, -0.15497205 0.15445143 -0.12470086, -0.15517184 0.15445143 -0.12492631, -0.15541986 0.15445143 -0.12509762, -0.15724161 0.1544513 -0.12384014, -0.15570155 0.1544514 -0.12520461, -0.15724167 0.15445141 -0.1241415, -0.15716955 0.15445141 -0.12443398, -0.15702951 0.15445141 -0.12470086, -0.15570167 0.15445134 -0.12277703, -0.15600076 0.15345146 -0.12524076, -0.15629981 0.15345146 -0.12520452, -0.1565816 0.15345134 -0.12509771, -0.15682966 0.15345146 -0.12492652, -0.15702948 0.15345146 -0.12470095, -0.15716946 0.15345137 -0.12443407, -0.1572416 0.1534514 -0.1241415, -0.1572416 0.15345134 -0.12384014, -0.15716946 0.15345131 -0.12354763, -0.15702948 0.15345137 -0.12328084, -0.15682968 0.15345134 -0.12305529, -0.1565817 0.15345135 -0.12288399, -0.15629983 0.15345129 -0.12277709, -0.15600076 0.15345128 -0.12274079, -0.15570153 0.1534514 -0.12520452, -0.15497208 0.15345147 -0.12470101, -0.15541986 0.1534515 -0.12509762, -0.15517184 0.15345144 -0.12492661, -0.15483204 0.15345147 -0.12443422, -0.15475984 0.15345141 -0.12414156, -0.15475988 0.15345138 -0.12384014, -0.15570164 0.15345131 -0.1227773, -0.15483193 0.15345126 -0.12354763, -0.15497205 0.15345135 -0.12328069, -0.1554198 0.15345129 -0.12288399, -0.15517181 0.15345129 -0.12305529, -0.19000083 0.15445113 -0.12274079, -0.18970172 0.15445112 -0.12277709, -0.18941991 0.1544511 -0.1228839, -0.18917179 0.15445103 -0.12305529, -0.188972 0.15445103 -0.12328069, -0.19082972 0.15445122 -0.12492631, -0.19058168 0.15445121 -0.12509756, -0.18883207 0.15445115 -0.12354754, -0.19029993 0.15445122 -0.12520446, -0.18875991 0.15445113 -0.12384005, -0.19000076 0.15445121 -0.12524076, -0.19082972 0.15445112 -0.12305529, -0.19102955 0.15445112 -0.12328069, -0.19058165 0.15445104 -0.12288399, -0.19116956 0.15445109 -0.12354748, -0.19029993 0.15445115 -0.12277703, -0.18875992 0.15445122 -0.1241415, -0.18883203 0.15445119 -0.12443398, -0.18897204 0.15445119 -0.12470095, -0.18917184 0.15445118 -0.12492646, -0.1894199 0.15445124 -0.12509756, -0.19124167 0.15445109 -0.12384014, -0.18970159 0.15445113 -0.12520452, -0.19124159 0.15445113 -0.1241415, -0.19116959 0.15445122 -0.12443407, -0.19102955 0.15445127 -0.12470086, -0.19000071 0.15345122 -0.12524076, -0.19029984 0.15345119 -0.12520452, -0.19058165 0.15345125 -0.12509762, -0.19082963 0.15345116 -0.12492646, -0.19102943 0.15345114 -0.12470095, -0.1911695 0.15345117 -0.12443407, -0.19124165 0.15345119 -0.1241415, -0.19124168 0.15345117 -0.12384014, -0.19116946 0.153451 -0.12354763, -0.19102952 0.15345111 -0.12328069, -0.1908296 0.15345104 -0.12305529, -0.19058165 0.15345106 -0.12288408, -0.1902999 0.15345113 -0.12277709, -0.19000071 0.15345104 -0.12274085, -0.18970156 0.15345114 -0.12520461, -0.18897209 0.15345128 -0.12470095, -0.18941985 0.15345126 -0.12509771, -0.1891719 0.15345132 -0.12492646, -0.18883188 0.15345114 -0.12443407, -0.18875989 0.15345119 -0.1241415, -0.18875991 0.15345117 -0.12384014, -0.18970174 0.15345117 -0.12277703, -0.188832 0.15345104 -0.12354763, -0.18897203 0.15345104 -0.12328069, -0.1894199 0.15345119 -0.12288399, -0.18917188 0.15345113 -0.12305529, -0.28500086 0.15445054 -0.12274079, -0.28582966 0.15445063 -0.12492646, -0.28558171 0.1544506 -0.12509762, -0.28383201 0.15445051 -0.12354754, -0.28397208 0.15445048 -0.12328075, -0.28529996 0.15445063 -0.12520446, -0.28375992 0.15445051 -0.12384014, -0.28500086 0.15445065 -0.12524076, -0.28582978 0.15445051 -0.12305529, -0.28602958 0.15445054 -0.12328069, -0.28558171 0.15445048 -0.12288399, -0.28616965 0.15445051 -0.12354754, -0.2852999 0.15445039 -0.1227773, -0.28375995 0.1544506 -0.1241415, -0.28383207 0.1544506 -0.12443398, -0.28397214 0.15445065 -0.12470095, -0.28417197 0.15445063 -0.12492631, -0.28441986 0.1544506 -0.12509756, -0.2862418 0.15445049 -0.12384014, -0.28470165 0.1544506 -0.12520452, -0.28624171 0.15445055 -0.1241415, -0.28616971 0.15445064 -0.12443407, -0.28602952 0.15445061 -0.12470095, -0.28470173 0.15445051 -0.12277709, -0.28441983 0.15445042 -0.12288399, -0.28417194 0.15445049 -0.12305529, -0.28500086 0.15345064 -0.12524076, -0.28530002 0.15345073 -0.12520452, -0.28558165 0.15345058 -0.12509762, -0.28582972 0.15345067 -0.12492646, -0.28602958 0.15345059 -0.12470095, -0.28616953 0.15345058 -0.12443422, -0.28624168 0.15345055 -0.12414156, -0.28624168 0.15345055 -0.12384014, -0.28616959 0.1534505 -0.12354763, -0.28602949 0.15345049 -0.12328075, -0.28582972 0.15345052 -0.12305529, -0.28558171 0.15345052 -0.12288408, -0.28529993 0.15345049 -0.1227773, -0.28500083 0.15345043 -0.12274085, -0.28470162 0.15345058 -0.12520452, -0.28441989 0.15345065 -0.12509756, -0.283972 0.15345055 -0.12470095, -0.28417188 0.15345058 -0.12492652, -0.28376001 0.15345061 -0.1241415, -0.28383198 0.15345055 -0.12443407, -0.28375998 0.15345055 -0.12384014, -0.28470165 0.15345044 -0.1227773, -0.28383201 0.15345046 -0.12354754, -0.28441989 0.15345055 -0.12288408, -0.28397214 0.15345046 -0.12328069, -0.28417191 0.15345049 -0.12305529, -0.4000009 0.15444972 -0.12274079, -0.39970163 0.15444967 -0.12277709, -0.39942005 0.15444972 -0.12288399, -0.39917204 0.15444973 -0.12305529, -0.39897212 0.15444973 -0.12328069, -0.40082973 0.15444984 -0.12492631, -0.40058187 0.15444991 -0.12509756, -0.39883205 0.1544497 -0.12354754, -0.40030017 0.1544499 -0.12520446, -0.39876011 0.15444982 -0.12384014, -0.40000096 0.15444992 -0.12524091, -0.40082976 0.1544497 -0.12305509, -0.40102956 0.15444976 -0.12328069, -0.40058187 0.15444982 -0.1228839, -0.40116969 0.15444978 -0.12354763, -0.4003 0.1544497 -0.12277709, -0.4012416 0.15444966 -0.12383996, -0.39876011 0.15444991 -0.1241415, -0.39883211 0.15444988 -0.12443407, -0.39897215 0.15444998 -0.12470095, -0.39917216 0.15444994 -0.12492646, -0.39942017 0.15444998 -0.12509762, -0.39970174 0.15444988 -0.12520461, -0.40124175 0.15444973 -0.1241415, -0.4011696 0.15444981 -0.12443398, -0.40102968 0.15444984 -0.12470086, -0.40000087 0.15344992 -0.12524091, -0.40030015 0.15344994 -0.12520461, -0.40058187 0.15344992 -0.12509783, -0.40082976 0.15344989 -0.12492661, -0.40102956 0.15344982 -0.12470095, -0.40116963 0.15344983 -0.12443407, -0.40124172 0.15344982 -0.1241415, -0.40124175 0.15344968 -0.12384014, -0.40116969 0.15344971 -0.12354754, -0.40102974 0.15344983 -0.12328069, -0.40082982 0.1534498 -0.12305529, -0.40058187 0.15344977 -0.12288399, -0.4003 0.15344971 -0.1227773, -0.40000075 0.1534497 -0.12274085, -0.39970177 0.15344994 -0.12520452, -0.39941999 0.15344986 -0.12509762, -0.39897212 0.15344983 -0.12470095, -0.39917201 0.15344994 -0.12492646, -0.39876005 0.15344983 -0.12414156, -0.39883211 0.15344992 -0.12443407, -0.39876011 0.15344977 -0.1238402, -0.39970163 0.15344973 -0.1227773, -0.39883217 0.15344985 -0.12354763, -0.39941996 0.15344968 -0.1228839, -0.39897218 0.15344983 -0.12328075, -0.3991721 0.1534498 -0.12305538, -7.1898035e-07 0.15445237 -0.1227407, -0.00082966313 0.15445247 -0.12492631, -0.00058162957 0.15445247 -0.12509756, 0.0011680648 0.15445237 -0.12354748, 0.0010280423 0.15445234 -0.12328069, -0.00029981881 0.15445238 -0.12520461, 0.0012401752 0.15445231 -0.12384014, -7.3388151e-07 0.15445246 -0.12524076, -0.00082950667 0.15445223 -0.12305529, -0.0010293461 0.15445223 -0.12328069, -0.00058154017 0.15445223 -0.1228839, -0.0011694804 0.15445232 -0.12354748, 0.001240205 0.15445243 -0.1241415, 0.0011680201 0.15445249 -0.12443407, -0.00029978901 0.15445225 -0.12277703, 0.0010279939 0.15445249 -0.12470095, 0.00082820281 0.15445243 -0.12492646, 0.00058019534 0.15445249 -0.12509762, 0.00029836223 0.15445249 -0.12520446, -0.0012415536 0.15445229 -0.12384005, -0.0012415163 0.15445235 -0.1241415, -0.0011694692 0.15445244 -0.12443398, -0.0010294504 0.15445241 -0.12470086, 0.00029853731 0.15445219 -0.12277703, 0.00058018416 0.15445237 -0.12288399, 0.00082815439 0.15445234 -0.12305529, -6.7055157e-07 0.1534525 -0.12524091, -0.00029978156 0.15345241 -0.12520461, -0.00058157742 0.15345249 -0.12509783, -0.00082963705 0.15345249 -0.12492646, -0.0010294765 0.15345249 -0.12470095, -0.0011695027 0.15345246 -0.12443407, -0.0012415946 0.15345243 -0.12414156, -0.0012415983 0.1534524 -0.12384014, -0.0011695214 0.15345237 -0.12354754, -0.0010294169 0.15345234 -0.12328075, -0.00082958862 0.15345237 -0.12305529, -0.00058162212 0.15345237 -0.12288408, -0.00029987097 0.15345237 -0.1227773, -7.0407918e-07 0.15345238 -0.12274085, 0.00029847398 0.15345247 -0.12520461, 0.0010280758 0.15345243 -0.12470095, 0.00058020279 0.15345247 -0.12509771, 0.00082826614 0.15345244 -0.12492646, 0.0011680573 0.1534525 -0.12443407, 0.0012401938 0.15345244 -0.12414156, 0.001240164 0.1534524 -0.12384014, 0.00029844046 0.15345238 -0.1227773, 0.0011680126 0.15345244 -0.12354754, 0.0010280497 0.15345238 -0.12328069, 0.00058020279 0.15345238 -0.12288408, 0.00082817301 0.15345238 -0.12305529, 0.36872777 0.15445191 -0.0746838, 0.36896297 0.15445198 -0.074235514, 0.36649686 0.15445185 -0.071451858, 0.36602357 0.15445179 -0.071631297, 0.36560687 0.15445197 -0.075062588, 0.36527118 0.15445197 -0.0746838, 0.36908415 0.15445191 -0.073743954, 0.3660236 0.15445197 -0.075350121, 0.36503592 0.15445188 -0.074235424, 0.36699948 0.15445176 -0.071390823, 0.36649695 0.154452 -0.075529709, 0.36491475 0.15445197 -0.073743954, 0.36908415 0.15445191 -0.073237643, 0.36699942 0.15445206 -0.075590745, 0.3649148 0.15445188 -0.073237643, 0.36750194 0.15445207 -0.075529709, 0.36750194 0.15445188 -0.071451858, 0.36797538 0.15445177 -0.071631417, 0.36503598 0.15445179 -0.072746113, 0.36896297 0.15445182 -0.072746113, 0.36872771 0.15445182 -0.072298005, 0.36839202 0.1544518 -0.071919009, 0.36797544 0.15445204 -0.075350121, 0.36527124 0.15445174 -0.072298005, 0.36839193 0.154452 -0.075062737, 0.36560699 0.15445179 -0.071918949, 0.36699948 0.1534518 -0.071390823, 0.36649689 0.15345177 -0.071451858, 0.36602357 0.1534518 -0.071631506, 0.36560696 0.15345179 -0.071919069, 0.3652713 0.15345177 -0.072298005, 0.36503598 0.15345177 -0.072746173, 0.36491472 0.1534519 -0.073237702, 0.36491475 0.15345186 -0.073743954, 0.36503598 0.15345192 -0.074235514, 0.36527124 0.15345192 -0.0746838, 0.36560687 0.15345204 -0.075062737, 0.36602357 0.15345201 -0.075350121, 0.36649695 0.15345207 -0.075529918, 0.36699942 0.15345213 -0.075590834, 0.36750206 0.15345196 -0.075529918, 0.3679755 0.15345201 -0.07535027, 0.36839202 0.15345192 -0.075062856, 0.36872771 0.15345193 -0.0746838, 0.36896309 0.15345189 -0.074235752, 0.36908415 0.15345187 -0.073743954, 0.36908409 0.15345192 -0.073237702, 0.36750206 0.15345183 -0.071451917, 0.36896303 0.15345189 -0.072746173, 0.36797532 0.15345183 -0.071631417, 0.36872771 0.15345183 -0.072298005, 0.36839202 0.15345186 -0.071919009, 0.4110007 -0.035502642 -0.076403722, 0.41100076 -0.035154566 -0.077172384, 0.4110007 -0.03536962 -0.07680659, 0.41100073 -0.035547793 -0.075981572, 0.4110007 -0.034962878 -0.059153631, 0.41100076 -0.035548657 -0.06056793, 0.41100076 -0.035510316 -0.060177758, 0.41100076 -0.035396501 -0.059802517, 0.41100076 -0.035211697 -0.059456781, 0.4110007 -0.035550088 -0.033949956, 0.4110007 -0.034964249 -0.035364047, 0.41100076 -0.035212979 -0.035060897, 0.41100076 -0.035397813 -0.034715101, 0.41100076 -0.035511717 -0.034340039, 0.4110007 -0.03521426 -0.012199268, 0.4110007 -0.035512835 -0.012920246, 0.41100067 -0.03539905 -0.012545213, 0.4110007 -0.0349655 -0.011896238, 0.4110007 -0.035551265 -0.013310537, 0.4110007 -0.035514265 0.012917385, 0.4110007 -0.035215586 0.012196556, 0.4110007 -0.035400465 0.012542203, 0.4110007 -0.035552695 0.013307557, 0.41100064 -0.034966916 0.011893377, 0.41100067 -0.035216868 0.035058007, 0.41100076 -0.035515517 0.03433688, 0.41100064 -0.035401687 0.03471218, 0.4110007 -0.035554007 0.033946857, 0.4110007 -0.034968108 0.035361096, 0.41100064 -0.035403103 0.059799597, 0.41100067 -0.034969509 0.05915086, 0.41100067 -0.035218298 0.05945386, 0.41100082 -0.035555407 0.060564891, 0.4110007 -0.035516948 0.060174659, 0.4110007 -0.035378203 0.076803669, 0.41100076 -0.035556301 0.075978711, 0.41100076 -0.03551133 0.076400742, 0.4110007 -0.035163149 0.077169463, 0.41100034 0.037069902 -0.1338336, 0.41100031 0.036620349 -0.13366379, 0.41100031 0.036224246 -0.13339154, 0.41100022 0.035904661 -0.13303281, 0.41100022 0.037547052 -0.13389148, 0.4109998 0.10787208 -0.13388743, 0.41099951 0.15295593 -0.13388483, 0.41099957 0.15329292 -0.13382427, 0.41099948 0.15312426 -0.13386984, 0.41099957 0.1534555 -0.13375045, 0.41099957 0.15345536 -0.13138069, 0.48250362 0.15088828 -0.14386387, 0.4824113 0.15105565 -0.1435288, 0.48438248 0.15183659 -0.14196692, 0.48399955 0.15185735 -0.14192529, 0.4850606 0.1506063 -0.14442758, 0.48531631 0.15073547 -0.14416932, 0.48241121 0.15122816 -0.14318378, 0.48474315 0.15050834 -0.14462365, 0.48549569 0.15088817 -0.14386387, 0.48438254 0.15044719 -0.14474596, 0.48250356 0.15139557 -0.1428488, 0.48558787 0.15105556 -0.1435288, 0.48399949 0.15042648 -0.14478745, 0.48361665 0.15183648 -0.14196692, 0.48268276 0.15154842 -0.14254339, 0.48558795 0.15122826 -0.14318384, 0.48325598 0.15177539 -0.14208932, 0.48293859 0.15167743 -0.14228506, 0.48361662 0.15044725 -0.14474593, 0.48549563 0.15139553 -0.1428488, 0.48325589 0.15050839 -0.14462365, 0.48531643 0.15154833 -0.14254345, 0.48293868 0.15060641 -0.14442758, 0.4850606 0.1516775 -0.1422853, 0.48268273 0.15073551 -0.14416932, 0.48474315 0.15177542 -0.14208932, 0.48399949 0.15293077 -0.14246173, 0.48438242 0.15290995 -0.14250346, 0.48474315 0.15284874 -0.14262576, 0.48506057 0.1527507 -0.14282174, 0.48531631 0.15262172 -0.14308019, 0.48549566 0.15246899 -0.14338548, 0.48558795 0.15230158 -0.14372049, 0.48558787 0.15212899 -0.14406554, 0.4854956 0.15196162 -0.14440052, 0.48531628 0.15180892 -0.14470597, 0.4850606 0.1516798 -0.14496411, 0.48474324 0.15158179 -0.14516015, 0.48438254 0.1515207 -0.1452827, 0.48399955 0.15149987 -0.1453241, 0.4899995 0.15545614 -0.1347269, 0.47529957 0.15545607 -0.1347269, 0.48999968 0.13957591 -0.16649164, 0.48999956 0.15545447 -0.10649069, 0.46474299 0.1554525 -0.071073964, 0.46438244 0.1554524 -0.070937261, 0.46250346 0.15545252 -0.073058143, 0.4624112 0.15545255 -0.072683707, 0.4650605 0.15545259 -0.073688403, 0.46531627 0.15545253 -0.073399737, 0.46399948 0.15545245 -0.070890769, 0.46474305 0.15545256 -0.07390742, 0.46549556 0.15545256 -0.073058143, 0.4624112 0.15545255 -0.072298005, 0.46438244 0.15545259 -0.074044332, 0.46250352 0.15545245 -0.07192339, 0.46558791 0.15545245 -0.072683647, 0.46361664 0.1554524 -0.070937261, 0.46268275 0.1554524 -0.071581826, 0.46399948 0.15545258 -0.074090734, 0.46325597 0.15545246 -0.071073964, 0.46293852 0.15545242 -0.071293041, 0.46558791 0.15545245 -0.072298005, 0.46361652 0.15545255 -0.074044332, 0.46549556 0.15545253 -0.07192339, 0.46325591 0.15545255 -0.07390748, 0.46531633 0.15545245 -0.071581826, 0.46293864 0.15545253 -0.073688403, 0.46506044 0.15545242 -0.071293041, 0.46268275 0.15545252 -0.073399648, 0.46399948 0.15665248 -0.070890769, 0.46438226 0.15665248 -0.070937142, 0.46474299 0.15665247 -0.071073964, 0.4650605 0.15665248 -0.071293011, 0.46531633 0.15665248 -0.071581736, 0.46549553 0.1566525 -0.07192333, 0.46558782 0.15665238 -0.072297707, 0.46558782 0.15665238 -0.072683409, 0.46549562 0.15665248 -0.073058084, 0.46531621 0.15665254 -0.073399648, 0.46506053 0.1566525 -0.073688284, 0.46474299 0.15665257 -0.07390748, 0.46438238 0.15665257 -0.074044213, 0.46399954 0.15665254 -0.074090585, 0.45706448 0.15545037 -0.036845341, 0.45700681 0.15545034 -0.036611125, 0.4579995 0.15545037 -0.035490736, 0.46999958 0.15545057 -0.037490651, 0.45700678 0.15545039 -0.036370263, 0.45706448 0.15545037 -0.036136165, 0.45776024 0.15545031 -0.035519823, 0.4571766 0.15545031 -0.035922691, 0.45753482 0.15545033 -0.035605296, 0.45733649 0.15545034 -0.035742179, 0.46999958 0.15545042 -0.035490647, 0.45799956 0.15545051 -0.037490651, 0.45776024 0.15545051 -0.037461624, 0.45753476 0.15545049 -0.037376091, 0.45733634 0.15545049 -0.037239119, 0.45717654 0.15545043 -0.037058696, 0.47700679 0.15545486 -0.11137019, 0.47700682 0.15545484 -0.11161135, 0.47799954 0.15545473 -0.11049072, 0.4899995 0.15545489 -0.11249064, 0.47776011 0.15545465 -0.11051975, 0.4775348 0.15545465 -0.11060522, 0.47706446 0.15545478 -0.11113618, 0.47733641 0.15545464 -0.11074226, 0.47717658 0.15545471 -0.11092268, 0.48999956 0.15545473 -0.11049072, 0.47799954 0.15545478 -0.11249088, 0.47776023 0.15545484 -0.11246173, 0.4775348 0.1554548 -0.11237608, 0.47733638 0.15545478 -0.11223935, 0.47717658 0.15545484 -0.11205892, 0.47706452 0.1554548 -0.11184536, 0.48999956 0.15544094 0.13474531, 0.47529957 0.15544084 0.13474531, 0.4899995 0.15544264 0.1065094, 0.46474305 0.15544432 0.073926166, 0.46438232 0.15544435 0.07406278, 0.46506053 0.1554444 0.071311787, 0.46250352 0.15544429 0.071941838, 0.46531639 0.15544428 0.071600392, 0.4624112 0.15544435 0.072316483, 0.46474299 0.1554444 0.071092591, 0.46361652 0.15544435 0.07406278, 0.46399948 0.15544423 0.07410939, 0.46549556 0.15544438 0.071942046, 0.46438238 0.1554444 0.070955768, 0.46558788 0.1554444 0.072316483, 0.4624112 0.15544435 0.072702274, 0.46399948 0.15544437 0.070909396, 0.46325591 0.15544435 0.073926106, 0.46250346 0.15544428 0.0730768, 0.46293846 0.15544435 0.073707059, 0.46558794 0.15544435 0.072702274, 0.46361664 0.15544437 0.070955858, 0.46268275 0.15544428 0.073418155, 0.46549556 0.15544429 0.0730768, 0.46325603 0.15544437 0.071092591, 0.46531621 0.15544435 0.073418245, 0.46293861 0.1554444 0.071311578, 0.46506053 0.1554444 0.073707059, 0.46268275 0.15544428 0.071600452, 0.46399948 0.15664436 0.070909396, 0.46361664 0.15664436 0.070955858, 0.46325603 0.15664431 0.071092591, 0.46293858 0.15664436 0.071311787, 0.46268266 0.15664433 0.071600392, 0.46250352 0.15664436 0.071942046, 0.4624112 0.15664433 0.072316483, 0.4624112 0.15664433 0.072702274, 0.46250346 0.15664431 0.07307671, 0.46268275 0.15664431 0.073418245, 0.46293846 0.15664431 0.073707059, 0.46325594 0.1566442 0.073926196, 0.46361664 0.15664431 0.074062929, 0.46399942 0.15664431 0.07410939, 0.45706448 0.15544626 0.036154583, 0.45700684 0.15544617 0.036388591, 0.45799956 0.15544626 0.037509277, 0.46999946 0.15544644 0.035509482, 0.45700675 0.15544625 0.03662996, 0.45776019 0.15544628 0.03748019, 0.45706442 0.15544628 0.036863759, 0.45753482 0.15544617 0.037394717, 0.45717654 0.15544631 0.037077323, 0.46999946 0.15544635 0.037509248, 0.45733646 0.15544622 0.037257954, 0.45799944 0.15544644 0.035509482, 0.45776013 0.15544644 0.03553836, 0.45753488 0.15544638 0.035623834, 0.4573364 0.15544638 0.035760805, 0.45717654 0.15544638 0.035941288, 0.48558787 0.15103957 0.14354692, 0.4854956 0.15087208 0.1438819, 0.48361665 0.15182075 0.14198507, 0.48399961 0.1518414 0.14194359, 0.48558789 0.15121202 0.14320196, 0.48293847 0.15059021 0.14444585, 0.48268285 0.15071924 0.14418755, 0.48325607 0.15049222 0.14464162, 0.48250344 0.15087204 0.1438819, 0.48361671 0.15043095 0.14476393, 0.48549563 0.15137951 0.14286707, 0.48438242 0.15182075 0.14198507, 0.48241121 0.15103957 0.14354707, 0.48531634 0.15153234 0.14256142, 0.48399949 0.15041021 0.14480542, 0.48474315 0.15175945 0.1421075, 0.48241124 0.15121205 0.14320205, 0.48506045 0.15166143 0.14230336, 0.48438254 0.15043092 0.14476393, 0.48250353 0.1513795 0.14286707, 0.48474315 0.1504921 0.14464162, 0.48268268 0.15153228 0.14256166, 0.4850606 0.15059009 0.14444564, 0.48293868 0.15166135 0.14230336, 0.48531631 0.15071926 0.14418755, 0.48325607 0.1517594 0.1421075, 0.48399946 0.15291473 0.14248015, 0.48361656 0.15289387 0.14252172, 0.48325607 0.15283276 0.14264403, 0.48293859 0.15273467 0.14284007, 0.48268273 0.15260559 0.14309837, 0.48250347 0.15245284 0.14340375, 0.48241121 0.15228529 0.14373873, 0.48241127 0.15211281 0.14408375, 0.48250347 0.15194531 0.14441882, 0.48268268 0.15179253 0.14472415, 0.48293853 0.15166339 0.14498244, 0.48325604 0.15156552 0.14517845, 0.48361671 0.15150425 0.14530061, 0.48399961 0.15148342 0.14534231, 0.48999962 0.13955726 0.16650866, 0.48999956 0.15345448 -0.10649084, 0.48999959 0.15345468 -0.11049084, 0.4899995 0.15345484 -0.11249088, 0.48999956 0.15345597 -0.13189407, 0.48999962 0.15333691 -0.1334336, 0.48999953 0.15298226 -0.13493602, 0.4899995 0.1524004 -0.1363662, 0.48999974 0.13733986 -0.16649179, 0.46999949 0.15345044 -0.035490885, 0.46999952 0.15344648 0.035509065, 0.4899995 0.15544222 0.11250933, 0.48999944 0.15344213 0.11250933, 0.48999956 0.15344113 0.1319124, 0.48999956 0.15332183 0.13345195, 0.48999956 0.15296696 0.13495453, 0.48999938 0.15238521 0.13638462, 0.48999962 0.13732119 0.16650842, 0.46999949 0.15344357 0.086509362, 0.46999949 0.15344627 0.037509248, 0.4899995 0.15344265 0.10650931, 0.4116604 0.10764538 0.13139649, 0.41166756 0.10764734 0.13140051, 0.41166046 0.10766019 -0.13138331, 0.41166756 0.1076621 -0.13138749, 0.41166016 0.12865691 0.13139768, 0.4243066 0.11103727 0.13867147, 0.42430648 0.12865661 0.13867246, 0.41468331 0.1076621 -0.13138749, 0.41220841 0.078790814 -0.13138904, 0.41468343 0.078790888 -0.13138904, 0.41220847 0.076790854 -0.13138904, 0.41468373 0.040211454 -0.13139127, 0.41468343 0.076790854 -0.13138925, 0.41328284 0.03841719 -0.13139139, 0.41233209 0.030097619 -0.12117369, 0.41233215 0.029954776 -0.12096818, 0.41337898 0.029954642 -0.11903866, 0.4132829 0.036901101 -0.12921001, 0.41471013 0.03832832 -0.12863313, 0.4160355 0.039539039 -0.12793289, 0.41729006 0.040475979 -0.12696908, 0.41841403 0.041113108 -0.12581442, 0.46021417 0.07678923 -0.10011341, 0.42031714 0.03956908 -0.12008552, 0.4200938 0.039017662 -0.11970417, 0.41981131 0.038454935 -0.11941476, 0.41937318 0.037716135 -0.11915906, 0.41892982 0.037061349 -0.11903422, 0.45126301 0.076790228 -0.11661015, 0.41931501 0.041419268 -0.12459441, 0.41990098 0.041433603 -0.12353514, 0.42027321 0.04125239 -0.12258811, 0.42046431 0.040939406 -0.12178595, 0.42051715 0.040552944 -0.12113281, 0.42046392 0.040088534 -0.12056263, 0.41328287 0.036886573 0.12921511, 0.41328287 0.038402423 0.13139664, 0.41468379 0.040196702 0.13139684, 0.41337898 0.02994132 0.11904348, 0.41233215 0.029941142 0.12097265, 0.41233215 0.03008391 0.12117817, 0.41681626 0.03456828 0.11936678, 0.41768149 0.035487279 0.11909451, 0.45126301 0.076776996 0.11662008, 0.46021417 0.076778054 0.10012315, 0.41220847 0.078776106 0.13139872, 0.41468325 0.10764742 0.13140054, 0.41220835 0.076776028 0.13139887, 0.41468343 0.078776136 0.13139887, 0.41468355 0.076776028 0.13139872, 0.48361662 0.15152062 -0.1452827, 0.48325595 0.15158181 -0.14516018, 0.48293859 0.15167975 -0.14496411, 0.48268268 0.15180889 -0.14470597, 0.48250356 0.15196152 -0.14440031, 0.48241121 0.15212896 -0.14406534, 0.48241112 0.15230158 -0.14372037, 0.48250362 0.15246899 -0.14338548, 0.48268268 0.15262178 -0.14307998, 0.48293856 0.15275081 -0.14282174, 0.48325589 0.15284875 -0.14262576, 0.48361665 0.15290983 -0.14250346, 0.48361492 0.15297285 -0.1425267, 0.48324227 0.15297693 -0.14266033, 0.48360956 0.15303929 -0.14253591, 0.4832525 0.15163852 -0.1451961, 0.48361486 0.15157709 -0.14531894, 0.48399952 0.15306045 -0.14249365, 0.48325253 0.1529115 -0.14264958, 0.48360953 0.15162413 -0.14536653, 0.48324215 0.15168646 -0.14524187, 0.48238164 0.1524196 -0.14377545, 0.48238167 0.15224384 -0.14412676, 0.48234624 0.15229282 -0.14415623, 0.4829188 0.1517863 -0.14504237, 0.48322561 0.15172322 -0.14529569, 0.48244229 0.15264668 -0.14344831, 0.48229909 0.15251739 -0.14381327, 0.48239794 0.15269667 -0.14345463, 0.48289514 0.15182507 -0.14509167, 0.48234618 0.15247239 -0.14379711, 0.48258984 0.15286022 -0.14312746, 0.48234472 0.15273765 -0.1434526, 0.48262882 0.15195957 -0.144823, 0.48286358 0.15185173 -0.1451446, 0.48258984 0.15198995 -0.14486824, 0.48399952 0.15299381 -0.14248498, 0.48254305 0.15290669 -0.14311455, 0.48239794 0.15215328 -0.14454101, 0.48254302 0.15200748 -0.14491315, 0.48234475 0.1521764 -0.14457531, 0.48356089 0.15168093 -0.1456158, 0.48399949 0.15163407 -0.14572658, 0.48354486 0.15165871 -0.14567722, 0.48399952 0.15165718 -0.14566346, 0.48282591 0.15304939 -0.1428289, 0.48249078 0.15294257 -0.1430922, 0.48278379 0.15309045 -0.14279626, 0.48224264 0.15236165 -0.14420463, 0.48228544 0.15218613 -0.14460523, 0.48314747 0.15320279 -0.14257185, 0.48273963 0.15311947 -0.14275505, 0.48311651 0.15323597 -0.14252241, 0.48357603 0.15168871 -0.14555092, 0.48399955 0.1516656 -0.14559691, 0.48217967 0.15237808 -0.14422132, 0.48240376 0.1523616 -0.14374952, 0.48240376 0.15218833 -0.14409615, 0.48217964 0.15257567 -0.14382611, 0.48211345 0.15238114 -0.14423199, 0.48211351 0.15258598 -0.14382239, 0.48314759 0.15175106 -0.14547576, 0.48311663 0.15173134 -0.14553191, 0.48247561 0.15259016 -0.14343427, 0.48293358 0.15173694 -0.14499922, 0.48358962 0.15168144 -0.14548539, 0.48399952 0.15165921 -0.14553, 0.48262885 0.15280566 -0.14313026, 0.4826583 0.15191771 -0.14477931, 0.48317698 0.15175633 -0.14541538, 0.48244232 0.15211841 -0.1445048, 0.48286363 0.1529984 -0.14285083, 0.48229906 0.15233274 -0.14418246, 0.48278385 0.15186331 -0.14525105, 0.4827396 0.15184765 -0.14529915, 0.48399955 0.15155616 -0.14536063, 0.48317698 0.15315779 -0.14261217, 0.48360094 0.15165949 -0.14542295, 0.48399955 0.15163776 -0.14546628, 0.4835608 0.15327272 -0.14243172, 0.48354486 0.1533085 -0.14237709, 0.48399955 0.15333331 -0.14232765, 0.48224267 0.1525525 -0.14382298, 0.48320353 0.15174684 -0.14535455, 0.48399955 0.15329662 -0.14238401, 0.48249647 0.15252994 -0.14341311, 0.48228535 0.15276754 -0.14344223, 0.482223 0.15278496 -0.1434245, 0.48265824 0.15274569 -0.14312334, 0.4826766 0.15186663 -0.14473955, 0.48282602 0.15186466 -0.14519881, 0.48289517 0.15293993 -0.1428615, 0.48249084 0.15201119 -0.14495523, 0.48243588 0.15200099 -0.14499258, 0.48247567 0.15207332 -0.14446805, 0.4832035 0.15310328 -0.14264123, 0.48399964 0.15160297 -0.14540876, 0.48357597 0.15322544 -0.14247669, 0.48399958 0.15324844 -0.14243068, 0.48267657 0.15268333 -0.14310606, 0.4829188 0.15287718 -0.14286001, 0.48243585 0.15296623 -0.14306147, 0.48249653 0.15202002 -0.14443265, 0.482223 0.1521823 -0.14462973, 0.48322561 0.15304209 -0.1426575, 0.48358956 0.15316881 -0.14251016, 0.48399949 0.15319106 -0.14246558, 0.48293358 0.15281299 -0.14284654, 0.48360088 0.15310571 -0.14253022, 0.48399958 0.15312727 -0.14248697, 0.46361655 0.15665254 -0.074044213, 0.46325597 0.1566525 -0.07390742, 0.46293849 0.15665254 -0.073688403, 0.46268275 0.15665254 -0.073399648, 0.46250352 0.15665247 -0.073058084, 0.46241131 0.15665241 -0.072683409, 0.4624112 0.15665241 -0.072297797, 0.46250346 0.15665251 -0.07192339, 0.46268275 0.15665236 -0.071581736, 0.46293852 0.15665247 -0.071293011, 0.46325591 0.15665239 -0.071073964, 0.46361649 0.15665248 -0.070937142, 0.46361485 0.15671913 -0.07092984, 0.46360943 0.15678264 -0.070908293, 0.46399954 0.1567826 -0.070861056, 0.46325251 0.15671924 -0.071067408, 0.46325257 0.15671931 -0.073914006, 0.46361479 0.1567193 -0.074051514, 0.46399948 0.15671913 -0.07088314, 0.46238169 0.15678264 -0.07229425, 0.46234623 0.15683942 -0.072691396, 0.46234629 0.1568394 -0.072289929, 0.46291885 0.15678264 -0.073710516, 0.4632422 0.15678272 -0.073933706, 0.46322551 0.15683962 -0.073965505, 0.46324214 0.15678255 -0.0710475, 0.46238169 0.15678264 -0.072687164, 0.46244237 0.15683939 -0.071900114, 0.46229896 0.15688695 -0.072284237, 0.4623979 0.15688702 -0.071883276, 0.46289513 0.15683958 -0.073737308, 0.46262893 0.15683958 -0.073436871, 0.46286359 0.15688714 -0.073772922, 0.46258971 0.15688692 -0.071517572, 0.46234462 0.15692271 -0.07186313, 0.46356079 0.15694505 -0.074270621, 0.46399954 0.15695253 -0.074390605, 0.46354482 0.15695256 -0.07433556, 0.46258977 0.15688707 -0.073463634, 0.4639996 0.15694496 -0.074323848, 0.46239784 0.15688705 -0.073098108, 0.46254286 0.1569228 -0.073496088, 0.4623448 0.15692285 -0.073118314, 0.46254292 0.15692271 -0.071485326, 0.46282586 0.15692262 -0.071165904, 0.46249092 0.15694483 -0.071449265, 0.46278378 0.15694478 -0.071118578, 0.46357608 0.15692283 -0.07420896, 0.4639996 0.15692274 -0.074260458, 0.46224263 0.15692271 -0.072703943, 0.46228543 0.15694495 -0.073140696, 0.46217963 0.15694489 -0.072711602, 0.46314758 0.15694478 -0.070867434, 0.46273968 0.15695235 -0.07106851, 0.46311662 0.15695229 -0.070808157, 0.46314761 0.15694496 -0.07411395, 0.46311656 0.15695257 -0.074173048, 0.46217963 0.15694489 -0.072269663, 0.46211335 0.15695243 -0.072719708, 0.46211341 0.15695237 -0.072261766, 0.46240374 0.15671912 -0.072296962, 0.46358958 0.15688713 -0.074153885, 0.46293351 0.15671924 -0.073693976, 0.46399954 0.15688713 -0.074203566, 0.46240368 0.15671928 -0.072684482, 0.46247569 0.1567826 -0.071912959, 0.46317711 0.15692285 -0.074057892, 0.46265832 0.1567827 -0.073416427, 0.46262893 0.15683946 -0.071544513, 0.46244231 0.15683958 -0.07308124, 0.4627839 0.15694495 -0.073862806, 0.46273968 0.15695247 -0.073912814, 0.46286365 0.15688691 -0.071208492, 0.46229908 0.15688697 -0.072697207, 0.46360102 0.15683946 -0.074107721, 0.46399948 0.15683959 -0.07415615, 0.46317711 0.15692267 -0.070923552, 0.46320352 0.15688708 -0.074007496, 0.46224251 0.15692274 -0.072277322, 0.46356094 0.15694483 -0.070710644, 0.46354482 0.15695231 -0.070645824, 0.46399948 0.15695237 -0.0705906, 0.46399954 0.15694483 -0.070657358, 0.46228543 0.15694484 -0.07184051, 0.46222302 0.1569524 -0.071816847, 0.46249649 0.15671913 -0.071920767, 0.46282592 0.15692273 -0.07381545, 0.46267655 0.1567193 -0.073404029, 0.46265832 0.15678258 -0.071564987, 0.46249086 0.15694489 -0.07353206, 0.46243587 0.15695241 -0.073570028, 0.46247566 0.15678272 -0.073068514, 0.46289513 0.15683945 -0.071244076, 0.46360961 0.15678261 -0.074072883, 0.4639996 0.1567827 -0.074120358, 0.4632034 0.15688691 -0.070973977, 0.46357599 0.15692262 -0.070772275, 0.46399948 0.15692262 -0.070720926, 0.46267661 0.1567191 -0.071577445, 0.46243587 0.15695234 -0.071411327, 0.46291879 0.15678258 -0.071270809, 0.46222302 0.15695241 -0.073164299, 0.46249643 0.15671928 -0.073060706, 0.4639996 0.15671928 -0.074098244, 0.46322557 0.15683939 -0.071015939, 0.46358952 0.15688683 -0.070827469, 0.46399954 0.15688695 -0.07077764, 0.46293351 0.15671916 -0.071287498, 0.46360096 0.15683948 -0.070873603, 0.46399954 0.15683943 -0.070825204, 0.47717658 0.15344219 0.11207734, 0.4719035 0.15344204 0.11506064, 0.47733647 0.15344214 0.11225779, 0.47199947 0.15344207 0.11603607, 0.47776017 0.15344205 0.11248012, 0.47799948 0.15344205 0.11250921, 0.47753477 0.15344214 0.11239465, 0.47199953 0.15344104 0.1319124, 0.46553829 0.15344431 0.072322443, 0.46999946 0.15345059 -0.03749086, 0.46999952 0.15345332 -0.086490855, 0.46553817 0.15345241 -0.072303995, 0.45199952 0.15345338 -0.091875598, 0.45199946 0.15344314 0.091894135, 0.45700684 0.15344624 0.036388591, 0.45706442 0.15344629 0.036154583, 0.4570069 0.15345038 -0.036370412, 0.45700672 0.15345041 -0.036611333, 0.45700684 0.15344624 0.036629751, 0.4570646 0.15345037 -0.036136284, 0.47799954 0.15345481 -0.11249088, 0.47199947 0.15345587 -0.13189413, 0.47799948 0.15345469 -0.11049078, 0.4719995 0.15345499 -0.11601774, 0.47776017 0.15345469 -0.11246173, 0.47753492 0.15345484 -0.11237632, 0.4773365 0.15345484 -0.11223949, 0.47190353 0.15345491 -0.11504219, 0.47717658 0.15345481 -0.11205892, 0.47161886 0.15345486 -0.11410441, 0.47706455 0.1534548 -0.11184551, 0.47700679 0.15345474 -0.11161135, 0.47115687 0.15345478 -0.11323993, 0.47700682 0.15345477 -0.11137019, 0.47053501 0.15345475 -0.11248229, 0.47706449 0.15345475 -0.11113618, 0.47717658 0.15345474 -0.11092283, 0.47733641 0.15345468 -0.11074226, 0.4775348 0.15345472 -0.1106054, 0.47776017 0.15345469 -0.1105199, 0.45346394 0.15345371 -0.095411077, 0.45284227 0.15345365 -0.094653413, 0.45238018 0.15345356 -0.093789116, 0.45209554 0.15345363 -0.092851028, 0.46502739 0.15345256 -0.07365106, 0.46527523 0.15345255 -0.073371246, 0.46471989 0.15345253 -0.073863342, 0.46544889 0.15345256 -0.073040351, 0.46437052 0.15345247 -0.073995754, 0.46553817 0.1534525 -0.072677657, 0.46399948 0.1534525 -0.074040875, 0.4636285 0.1534525 -0.073995754, 0.46327922 0.1534525 -0.073863342, 0.46297166 0.15345256 -0.07365106, 0.46272382 0.15345243 -0.073371246, 0.46255025 0.15345243 -0.07304047, 0.46246085 0.15345249 -0.072677657, 0.46246079 0.15345241 -0.072303995, 0.46255025 0.15345247 -0.071941242, 0.46544889 0.15345241 -0.07194145, 0.46527523 0.15345237 -0.071610436, 0.46502742 0.15345237 -0.071330741, 0.46471998 0.15345241 -0.071118459, 0.46437043 0.15345243 -0.070985898, 0.46399945 0.15345243 -0.070940837, 0.46362862 0.15345247 -0.070985898, 0.45799956 0.15345046 -0.03749086, 0.46327922 0.15345247 -0.07111837, 0.46297169 0.15345241 -0.071330741, 0.45776024 0.15345046 -0.037461892, 0.46272382 0.15345243 -0.071610317, 0.45753488 0.1534504 -0.0373763, 0.45733646 0.1534504 -0.037239328, 0.4571766 0.15345046 -0.037058905, 0.4570646 0.15345037 -0.036845431, 0.45799947 0.15344641 0.035509273, 0.45799956 0.15345034 -0.035490885, 0.45776019 0.15344639 0.035538152, 0.45753488 0.15345033 -0.035605296, 0.45776021 0.15345034 -0.035519972, 0.45753482 0.15344639 0.035623625, 0.4573364 0.15344639 0.035760596, 0.45717657 0.15345034 -0.0359229, 0.45733652 0.15345033 -0.035742417, 0.45717648 0.15344641 0.035941049, 0.46502742 0.15344436 0.07134901, 0.46527508 0.15344435 0.071628645, 0.46471992 0.15344432 0.071136788, 0.46544889 0.15344436 0.07195957, 0.4643704 0.15344445 0.071004257, 0.46399957 0.15344436 0.070959315, 0.45799953 0.15344617 0.037509188, 0.46362862 0.15344442 0.071004108, 0.46327922 0.15344444 0.071136788, 0.45776024 0.15344615 0.037480041, 0.46297163 0.15344431 0.07134901, 0.4575347 0.15344624 0.037394717, 0.46272394 0.15344423 0.071628794, 0.45733634 0.15344623 0.037257746, 0.46255019 0.15344433 0.071959481, 0.45717642 0.15344627 0.037077323, 0.46327916 0.15344432 0.073881611, 0.46362871 0.15344419 0.074014142, 0.46399954 0.15344432 0.074059233, 0.46437055 0.1534442 0.074014291, 0.46471989 0.15344419 0.073881611, 0.46502739 0.15344429 0.07366918, 0.46527514 0.15344428 0.073389605, 0.46544883 0.15344425 0.073058888, 0.46553823 0.15344433 0.072696015, 0.47799957 0.15344226 0.11050914, 0.48999956 0.15344226 0.11050914, 0.47776023 0.15344223 0.11053823, 0.4775348 0.15344232 0.11062379, 0.46246085 0.15344432 0.072322443, 0.46246088 0.15344436 0.072696015, 0.46255025 0.15344428 0.073058888, 0.46272382 0.15344428 0.073389664, 0.46297166 0.15344432 0.073669389, 0.45706457 0.15344627 0.036863759, 0.45284215 0.15344302 0.09467195, 0.45346394 0.15344304 0.095429495, 0.45238018 0.15344305 0.093807504, 0.45209554 0.15344313 0.092869565, 0.4770644 0.15344225 0.11115451, 0.47053492 0.15344204 0.1125005, 0.47700688 0.15344219 0.11138864, 0.47717646 0.15344234 0.11094101, 0.47733632 0.15344229 0.11076067, 0.47115687 0.15344201 0.11325826, 0.47700688 0.15344219 0.11162983, 0.47161895 0.15344198 0.11412282, 0.47706464 0.15344222 0.11186381, 0.46433935 0.15341447 0.073887691, 0.46463302 0.15337883 0.073716, 0.46432564 0.15337881 0.073832586, 0.46547195 0.15343682 0.072330311, 0.46532705 0.15341465 0.072005734, 0.46540907 0.15341462 0.07233806, 0.46468887 0.15343679 0.071195945, 0.46433935 0.15341464 0.071130708, 0.46465936 0.15341465 0.071252093, 0.46435457 0.15343687 0.071068987, 0.46435454 0.15343671 0.073949412, 0.46468887 0.15343668 0.073822603, 0.46399948 0.15341461 0.073928818, 0.4639996 0.15343674 0.073992476, 0.4654091 0.15341458 0.07268025, 0.46535262 0.15337889 0.072344765, 0.46494111 0.15341462 0.071446434, 0.46463281 0.15337893 0.071302399, 0.46465936 0.15341462 0.073766425, 0.46535262 0.15337884 0.072673425, 0.46527386 0.15337881 0.07299231, 0.46530548 0.15333135 0.072667703, 0.46490338 0.15337898 0.0714892, 0.46512133 0.15337893 0.071735069, 0.46487179 0.15333138 0.071524605, 0.46430042 0.15321121 0.071288183, 0.46399942 0.1531444 0.071259245, 0.46429864 0.15314439 0.071295634, 0.46522957 0.1533314 0.072975621, 0.46508214 0.15333143 0.071761861, 0.46508223 0.15333134 0.073256448, 0.4651961 0.15327445 0.072963133, 0.46399942 0.15321119 0.071251586, 0.46522948 0.15333143 0.072042927, 0.46505278 0.15327457 0.071782306, 0.46519616 0.15327458 0.072055414, 0.46505269 0.15327443 0.073236093, 0.4648481 0.15327454 0.073467091, 0.4650344 0.15321107 0.073223546, 0.46483338 0.15321103 0.073450401, 0.46430573 0.15327458 0.071266755, 0.46399954 0.15327466 0.071229562, 0.46526989 0.15327451 0.072354898, 0.46517536 0.15321113 0.072063312, 0.4652479 0.15321101 0.07235761, 0.4645839 0.1532111 0.071395621, 0.46458039 0.15314436 0.071402535, 0.46524793 0.15321109 0.072660699, 0.46524039 0.15314431 0.072358593, 0.46524042 0.15314433 0.072659805, 0.46458396 0.15321104 0.073622569, 0.4648284 0.15314431 0.073444709, 0.46458042 0.15314427 0.073616013, 0.46431437 0.15333147 0.071232006, 0.46547195 0.15343682 0.072687939, 0.46498308 0.15343681 0.071398988, 0.46399954 0.15333147 0.071193919, 0.46532729 0.15341456 0.073012456, 0.46459422 0.15327455 0.07137607, 0.46516803 0.15341467 0.071702614, 0.46512124 0.15337889 0.073283508, 0.46527383 0.1533789 0.07202588, 0.46483335 0.15321112 0.071567848, 0.46482846 0.15314433 0.071573481, 0.46487191 0.15333129 0.073493794, 0.46530545 0.15333137 0.072350606, 0.46432564 0.15337892 0.071185723, 0.46399948 0.1533789 0.071146116, 0.4645943 0.15327451 0.073642328, 0.46461084 0.15333149 0.071344271, 0.46526998 0.15327445 0.072663501, 0.46430048 0.15321104 0.073730066, 0.46429878 0.15314433 0.073722884, 0.46517536 0.15321104 0.072955087, 0.4651683 0.15314433 0.072952434, 0.46399957 0.15314427 0.073759153, 0.46399957 0.15321109 0.073766813, 0.46484819 0.15327455 0.071551219, 0.46538636 0.15343674 0.073035225, 0.46522024 0.15343681 0.071666613, 0.46503443 0.15321115 0.071794942, 0.4650282 0.15314439 0.071799144, 0.46516803 0.15341462 0.073315695, 0.46399942 0.15341471 0.071089372, 0.46490335 0.15337881 0.073529258, 0.46461084 0.15333135 0.073674038, 0.46430579 0.15327442 0.073751792, 0.46399948 0.15327446 0.073788837, 0.46522021 0.15343681 0.073351696, 0.46502829 0.15314433 0.073219255, 0.46494105 0.15341459 0.073571876, 0.46516821 0.15314439 0.072065935, 0.4653863 0.15343681 0.071983323, 0.46399948 0.15343685 0.071025982, 0.46431431 0.15333128 0.073786363, 0.46399957 0.15333137 0.073824629, 0.46498314 0.15343675 0.07361947, 0.46399954 0.15337881 0.073872045, 0.46364459 0.15344495 -0.073930964, 0.46331021 0.15344499 -0.073804095, 0.46259007 0.15342276 -0.07266207, 0.46264651 0.15338695 -0.072326496, 0.46264651 0.153387 -0.072655156, 0.46365964 0.15342291 -0.073869422, 0.46399948 0.15342282 -0.073910549, 0.46259007 0.15342276 -0.072319642, 0.46305802 0.15342271 -0.071428075, 0.46333966 0.15342271 -0.071233615, 0.46336612 0.15338689 -0.071283922, 0.46272507 0.153387 -0.07297419, 0.46269366 0.15333953 -0.072649434, 0.46276948 0.15333956 -0.072957352, 0.46309575 0.15338701 -0.071470633, 0.4628779 0.15338692 -0.071716532, 0.46312723 0.15333943 -0.071506247, 0.46399957 0.15344504 -0.073974118, 0.46291688 0.15333967 -0.073238298, 0.46280292 0.15328269 -0.072944656, 0.46369854 0.15321925 -0.071269944, 0.46399951 0.15315244 -0.071240887, 0.46370026 0.15315247 -0.071277216, 0.462917 0.15333952 -0.071743593, 0.46399942 0.15321925 -0.071233466, 0.46276954 0.15333952 -0.07202436, 0.46294636 0.1532826 -0.071763888, 0.46294636 0.15328278 -0.073217884, 0.46280307 0.15328266 -0.072036937, 0.46315095 0.15328275 -0.073448762, 0.46296456 0.1532193 -0.073205188, 0.46316558 0.15321934 -0.073432192, 0.46369329 0.15328263 -0.071248278, 0.46399948 0.15328261 -0.071211293, 0.46272925 0.15328266 -0.072336599, 0.46282381 0.15321918 -0.072044775, 0.46275124 0.15321925 -0.072339401, 0.46341509 0.15321931 -0.07360436, 0.46341872 0.15315248 -0.073597655, 0.46370044 0.15315254 -0.073704466, 0.46341518 0.15321924 -0.071377411, 0.46341857 0.15315245 -0.071384057, 0.46275112 0.15321921 -0.07264252, 0.46275863 0.15315245 -0.072340325, 0.46275863 0.15315245 -0.072641596, 0.46252716 0.15344486 -0.072669581, 0.46368471 0.15333953 -0.071213558, 0.463016 0.15344493 -0.071380541, 0.46252716 0.15344486 -0.072311983, 0.46399954 0.15333953 -0.071175352, 0.46331024 0.15344486 -0.071177378, 0.46267194 0.15342279 -0.072994456, 0.46340486 0.15328266 -0.071357802, 0.46287778 0.15338708 -0.073265031, 0.46283105 0.15342277 -0.071684435, 0.46272507 0.153387 -0.072007611, 0.46316564 0.15321925 -0.07154946, 0.46317068 0.1531525 -0.071555272, 0.46312726 0.15333958 -0.073475435, 0.46269366 0.15333953 -0.072332218, 0.46367332 0.15338702 -0.071167335, 0.46399948 0.153387 -0.071127906, 0.46338826 0.15333953 -0.071326092, 0.46340474 0.15328275 -0.073624, 0.46272913 0.15328261 -0.072645053, 0.4636986 0.1532193 -0.073711947, 0.46399948 0.15315259 -0.073740765, 0.46399957 0.1532193 -0.073748335, 0.46282375 0.15321925 -0.072936878, 0.46283075 0.15315251 -0.072934344, 0.46297085 0.15315254 -0.073200926, 0.46261266 0.15344504 -0.073016867, 0.46315083 0.15328273 -0.071533039, 0.46277893 0.15344484 -0.071648255, 0.46283099 0.15342282 -0.073297486, 0.46296468 0.15321913 -0.071776494, 0.46297082 0.1531525 -0.071780786, 0.46267197 0.15342271 -0.071987405, 0.46309575 0.15338714 -0.073511079, 0.46365964 0.15342271 -0.07111223, 0.46399957 0.15342274 -0.071070924, 0.4633882 0.15333952 -0.07365562, 0.46369329 0.15328275 -0.073733285, 0.46399954 0.15328284 -0.073770627, 0.46277884 0.15344505 -0.073333487, 0.46317065 0.15315248 -0.0734265, 0.46305797 0.1534228 -0.073553547, 0.46283081 0.15315251 -0.072047576, 0.46261269 0.15344492 -0.071965054, 0.46364459 0.15344484 -0.071050718, 0.46336615 0.1533871 -0.073697671, 0.46399948 0.15344496 -0.071007594, 0.46368471 0.15333961 -0.073768035, 0.46399948 0.15333959 -0.07380636, 0.46301594 0.15344505 -0.073600993, 0.46333972 0.15342279 -0.073747948, 0.46367332 0.15338704 -0.073814169, 0.46399957 0.15338708 -0.073853835, 0.47706446 0.15544225 0.11115475, 0.47700676 0.15544227 0.11138891, 0.47799954 0.15544207 0.11250933, 0.48999959 0.15544231 0.11050938, 0.4770067 0.15544225 0.11162983, 0.47776011 0.15544213 0.11248024, 0.4770644 0.15544228 0.11186393, 0.47733638 0.15544227 0.11225791, 0.47753474 0.15544215 0.11239477, 0.47717652 0.15544227 0.11207758, 0.47799948 0.15544231 0.11050938, 0.47776011 0.15544227 0.11053832, 0.4775348 0.15544225 0.11062394, 0.47733638 0.15544227 0.11076091, 0.47717661 0.15544236 0.11094125, 0.4139916 0.030566707 -0.10853292, 0.46021411 0.076788723 -0.089371249, 0.41337904 0.029954076 -0.10829116, 0.4369289 0.026953146 -0.08854498, 0.46123847 0.076788753 -0.088542238, 0.41399163 0.026954055 -0.10710703, 0.4418191 0.026952416 -0.075017795, 0.46612883 0.076787964 -0.075014934, 0.46611604 0.076761276 -0.070995227, 0.44181925 0.026952162 -0.070998028, 0.46612892 0.076787755 -0.070968702, 0.4615413 0.076787785 -0.070995167, 0.46606162 0.076787844 -0.070995167, 0.43625593 0.026952237 -0.070998028, 0.46154132 0.078787714 -0.070995167, 0.47531381 0.12527533 -0.16915278, 0.49149984 0.10807736 -0.13227667, 0.49149978 0.12434866 -0.16716553, 0.47144097 0.09696801 -0.1084566, 0.47391918 0.09049432 -0.09457542, 0.42510819 0.11180601 -0.14027266, 0.42760137 0.10978477 -0.13593857, 0.42630115 0.10943596 -0.13519056, 0.4243066 0.11105286 -0.13865788, 0.42510805 0.12867229 -0.14027162, 0.47531381 0.12867422 -0.1691526, 0.48149976 0.12867387 -0.1618676, 0.4864997 0.12867406 -0.1654924, 0.48699972 0.12867403 -0.1654924, 0.47587606 0.12867393 -0.16370772, 0.48699975 0.1286732 -0.1496426, 0.48149967 0.12867329 -0.15077989, 0.45457664 0.12867075 -0.10928611, 0.42760119 0.12867209 -0.13593741, 0.42353645 0.12867197 -0.13359933, 0.42430648 0.12867212 -0.13865681, 0.42630097 0.12867208 -0.13518958, 0.41175085 0.12867169 -0.13138206, 0.44004759 0.12867023 -0.10224004, 0.4477016 0.12867066 -0.10871206, 0.44490033 0.12867002 -0.097242281, 0.43490031 0.12867001 -0.097242281, 0.41166028 0.12867169 -0.13138206, 0.42849955 0.1451699 -0.097241327, 0.43257222 0.13851829 -0.097241685, 0.43249956 0.13792011 -0.097241923, 0.43278605 0.13908181 -0.097241685, 0.43312833 0.13957782 -0.097241566, 0.43357939 0.13997754 -0.097241566, 0.43411309 0.14025757 -0.097241566, 0.43469831 0.1404018 -0.097241566, 0.43530092 0.14040172 -0.097241566, 0.43257234 0.13732161 -0.097241774, 0.4449003 0.12932138 -0.097242162, 0.44899377 0.12667003 -0.0972424, 0.44490021 0.14177892 -0.097241417, 0.42849973 0.12666997 -0.097242281, 0.45099956 0.14517005 -0.097241327, 0.45099959 0.14504755 -0.097241327, 0.43490037 0.13166995 -0.097241953, 0.4364197 0.13586251 -0.097241923, 0.4449003 0.13166998 -0.097241953, 0.43687084 0.13626228 -0.097241923, 0.43721321 0.13675819 -0.097241923, 0.43588611 0.13558249 -0.097241923, 0.43742698 0.13732164 -0.097241774, 0.43530098 0.13543817 -0.097241923, 0.43749967 0.13792005 -0.097241774, 0.43469831 0.13543828 -0.097241923, 0.43742701 0.13851824 -0.097241566, 0.43411306 0.13558248 -0.097241923, 0.43721315 0.1390819 -0.097241685, 0.43357947 0.13586248 -0.097241923, 0.43687078 0.13957787 -0.097241685, 0.43312839 0.13626212 -0.097241774, 0.43641987 0.13997741 -0.097241685, 0.43278602 0.1367581 -0.097241923, 0.43588614 0.14025746 -0.097241566, 0.43749961 0.13791992 -0.095741555, 0.43742698 0.13732161 -0.095741764, 0.43721327 0.13675813 -0.095741913, 0.43687084 0.13626219 -0.095741913, 0.43641976 0.1358625 -0.095741913, 0.43588611 0.13558236 -0.095741913, 0.43530095 0.13543816 -0.095741913, 0.43469837 0.13543807 -0.095741913, 0.43411312 0.13558236 -0.095741913, 0.43357947 0.13586244 -0.095741913, 0.43312839 0.13626206 -0.095741913, 0.43278608 0.13675798 -0.095741913, 0.43257231 0.13732149 -0.095741913, 0.43249962 0.13791987 -0.095741913, 0.42849949 0.14516988 -0.096029922, 0.42849967 0.12666993 -0.096031114, 0.48649982 0.13167407 -0.16549204, 0.48149967 0.13167384 -0.16186725, 0.48699969 0.13167407 -0.16549204, 0.47531375 0.1316742 -0.1691523, 0.47587588 0.13167396 -0.16370748, 0.48699975 0.13167323 -0.14964236, 0.48149958 0.13167322 -0.15077974, 0.42510799 0.13167231 -0.14027141, 0.42760119 0.13167205 -0.13593726, 0.42430648 0.13167222 -0.13865666, 0.42353651 0.13167188 -0.13359921, 0.426301 0.13167202 -0.13518943, 0.44770154 0.13167067 -0.10871206, 0.41175082 0.13167171 -0.13138188, 0.4400475 0.13167022 -0.10223998, 0.41166028 0.13167164 -0.13138188, 0.41166016 0.15345542 -0.13138069, 0.41300499 0.15145549 -0.13215448, 0.41300502 0.15345544 -0.13215433, 0.41777918 0.1514556 -0.13490076, 0.42430627 0.14957856 -0.13865562, 0.47531363 0.13433287 -0.16915219, 0.42510775 0.14877135 -0.14027043, 0.47199959 0.14451014 -0.14879473, 0.48241732 0.14666325 -0.14448781, 0.48174196 0.14687176 -0.14407082, 0.48119763 0.14714645 -0.14352138, 0.48081622 0.14747147 -0.14287122, 0.48061976 0.14782776 -0.1421584, 0.47181439 0.1438361 -0.15014289, 0.4869996 0.13616279 -0.16549183, 0.49149957 0.1353265 -0.16716479, 0.49149969 0.13616277 -0.16549183, 0.46596184 0.14206484 -0.15368588, 0.46688157 0.14201106 -0.15379341, 0.48472813 0.1465241 -0.14476602, 0.485423 0.14662835 -0.14455782, 0.46518481 0.14218082 -0.15345384, 0.48399958 0.1464888 -0.14483662, 0.46450642 0.14234321 -0.15312885, 0.4719995 0.15040043 -0.13701232, 0.48318484 0.14948955 -0.13883431, 0.4869996 0.15040058 -0.13701256, 0.4806197 0.14819486 -0.14142425, 0.48081616 0.14855109 -0.14071141, 0.48119763 0.14887621 -0.14006145, 0.48174182 0.14915091 -0.13951181, 0.48241732 0.14935948 -0.13909478, 0.43282017 0.15145582 -0.13490076, 0.4277665 0.15108179 -0.13564874, 0.42646626 0.15145566 -0.13490076, 0.4869996 0.1472915 -0.14323129, 0.48658553 0.14702106 -0.14377232, 0.48605183 0.14679655 -0.14422126, 0.47061282 0.14278217 -0.15225084, 0.46974194 0.14241983 -0.15297572, 0.47134024 0.14326943 -0.15127636, 0.48318484 0.1465331 -0.14474808, 0.46882975 0.14218377 -0.15344803, 0.48542282 0.14939451 -0.13902487, 0.48605183 0.14922628 -0.13936134, 0.48658565 0.14900158 -0.13981052, 0.48699966 0.14873125 -0.1403514, 0.48472807 0.14949854 -0.13881655, 0.46785554 0.14204726 -0.15372093, 0.48399964 0.14953387 -0.13874598, 0.48399958 0.1452163 -0.14290945, 0.48346114 0.14524558 -0.14285104, 0.48295388 0.14533158 -0.14267908, 0.4825075 0.14546931 -0.14240332, 0.48214787 0.14565088 -0.1420403, 0.48189574 0.14586569 -0.1416107, 0.48176602 0.14610115 -0.14113958, 0.48176596 0.14634374 -0.1406544, 0.48189589 0.14657924 -0.14018317, 0.48214778 0.14679402 -0.13975377, 0.48250756 0.14697552 -0.13939054, 0.48295394 0.14711331 -0.13911493, 0.48346111 0.14719936 -0.13894294, 0.48399964 0.14722851 -0.13888441, 0.4869996 0.13814339 -0.14964201, 0.48699954 0.1472059 -0.14273281, 0.4869996 0.14719152 -0.14222793, 0.4869996 0.14725208 -0.14183463, 0.4869996 0.14741196 -0.14142509, 0.48699966 0.14798437 -0.1407804, 0.4869996 0.14766192 -0.1410739, 0.48699948 0.15145603 -0.13254024, 0.4869996 0.15133688 -0.13407938, 0.4869996 0.1509822 -0.13558213, 0.48699948 0.15145543 -0.12301396, 0.47199953 0.1514419 0.11603607, 0.47190353 0.15144199 0.11506064, 0.47609171 0.15144223 0.11134095, 0.4719995 0.15144095 0.13255842, 0.4869996 0.15144169 0.1230322, 0.4869996 0.15144107 0.13255842, 0.46011487 0.1514443 0.071035847, 0.45199957 0.15144557 0.048766509, 0.46058032 0.15144432 0.070149019, 0.45987517 0.15145244 -0.072991833, 0.4519996 0.15145327 -0.088201389, 0.46011481 0.15145251 -0.073964223, 0.4714995 0.15145329 -0.085869625, 0.47149953 0.15144363 0.085887894, 0.468124 0.15145239 -0.072991714, 0.46812385 0.1514525 -0.071990147, 0.4719995 0.15145594 -0.13254024, 0.46788427 0.15145239 -0.071017638, 0.46812391 0.15144433 0.072008207, 0.45987511 0.15145232 -0.071990147, 0.468124 0.15144429 0.073009953, 0.4678843 0.1514443 0.071035758, 0.45987508 0.15144423 0.072008267, 0.47199956 0.15145491 -0.11601786, 0.46199957 0.15144582 0.045766369, 0.4619996 0.15145089 -0.045748278, 0.47609162 0.15145485 -0.11132298, 0.47190341 0.15145493 -0.11504228, 0.47161895 0.15145488 -0.11410446, 0.47115687 0.15145466 -0.11324005, 0.47053501 0.15145472 -0.11248253, 0.47609177 0.15145358 -0.090461954, 0.46199945 0.15145108 -0.048748299, 0.46206886 0.15145217 -0.068812206, 0.46300524 0.15145221 -0.068457082, 0.46399957 0.15145221 -0.068336233, 0.4619996 0.15145341 -0.090701386, 0.46499383 0.15145209 -0.068457082, 0.46593037 0.15145226 -0.068812206, 0.46675453 0.15145227 -0.069381192, 0.46741873 0.15145233 -0.0701309, 0.46199957 0.15145323 -0.088201329, 0.45346394 0.15145366 -0.095411226, 0.4519996 0.15145101 -0.048748329, 0.46011484 0.15145232 -0.071017638, 0.4605802 0.1514523 -0.0701309, 0.46124443 0.1514523 -0.069381192, 0.46788424 0.15144429 0.073982343, 0.46741876 0.15144411 0.07486923, 0.45238018 0.15145357 -0.093789265, 0.45284227 0.15145363 -0.09465377, 0.46675453 0.15144405 0.075619087, 0.46593025 0.15144417 0.076188132, 0.4649938 0.15144408 0.076543048, 0.4520956 0.15145348 -0.092851207, 0.4519996 0.15145341 -0.091875747, 0.45199957 0.15145083 -0.045748308, 0.45199957 0.15145338 -0.090701386, 0.46199954 0.15144345 0.088219628, 0.4630053 0.15144405 0.076543048, 0.46399957 0.15144411 0.076663688, 0.45199946 0.15144575 0.045766369, 0.4620688 0.15144405 0.076188132, 0.46124452 0.15144409 0.075618938, 0.46741876 0.15145257 -0.074851111, 0.46675444 0.15145268 -0.075600818, 0.46593025 0.15145268 -0.076169804, 0.46199965 0.15144332 0.090719834, 0.47609162 0.15144347 0.090480104, 0.46741876 0.15144441 0.070149019, 0.46675465 0.15144439 0.069399312, 0.46199962 0.15144561 0.048766509, 0.46788418 0.15145256 -0.073964223, 0.46499386 0.15145262 -0.076524928, 0.46593037 0.15144451 0.068830356, 0.45199946 0.1514433 0.088219628, 0.46058029 0.15144406 0.07486923, 0.46011484 0.15144423 0.073982343, 0.45987514 0.1514443 0.073009953, 0.4639996 0.15145268 -0.076645538, 0.46499392 0.15144451 0.068475202, 0.45199949 0.15144308 0.091893986, 0.45199957 0.15144314 0.090719834, 0.46399954 0.15144457 0.068354473, 0.46300524 0.15145263 -0.076524928, 0.46206874 0.15145263 -0.076169714, 0.4630053 0.15144446 0.068475202, 0.45346394 0.15144305 0.095429465, 0.4520956 0.15144299 0.092869267, 0.45238009 0.15144299 0.093807504, 0.45284215 0.15144299 0.09467186, 0.46124443 0.15145265 -0.075600818, 0.46206877 0.15144451 0.068830356, 0.4705351 0.15144207 0.1125005, 0.47115695 0.15144201 0.11325826, 0.46058035 0.15145247 -0.074851111, 0.46124455 0.15144446 0.069399312, 0.47161904 0.15144199 0.1141227, 0.46399951 0.14944415 0.075508818, 0.46466228 0.14944419 0.075434998, 0.46529236 0.14944413 0.075216308, 0.46585849 0.14944409 0.074863598, 0.46633276 0.14944425 0.074394807, 0.46669176 0.14944425 0.073832735, 0.4669264 0.14949436 0.073288187, 0.46703669 0.14951774 0.072686031, 0.4670063 0.14951134 0.072070137, 0.46688575 0.14948569 0.071607307, 0.46669176 0.14944436 0.071185216, 0.46633288 0.14944437 0.070623353, 0.46585849 0.14944443 0.070154414, 0.46529242 0.14944449 0.069801793, 0.4646624 0.14944448 0.069583043, 0.46399948 0.14944458 0.069509134, 0.46399954 0.14945269 -0.075491056, 0.4632816 0.14945269 -0.075403944, 0.46260536 0.1494526 -0.075147375, 0.46201015 0.1494526 -0.074736729, 0.46153054 0.14945258 -0.074195459, 0.46119449 0.14945248 -0.073554888, 0.46102142 0.14945257 -0.072852716, 0.46102142 0.14945243 -0.072129473, 0.4611946 0.14945237 -0.071427211, 0.4615306 0.14945237 -0.070787027, 0.46201012 0.14945231 -0.070245489, 0.46260545 0.14945228 -0.069834784, 0.46328166 0.14945234 -0.069578275, 0.46399954 0.1494523 -0.069491103, 0.44655845 0.14516953 -0.088201717, 0.44655839 0.14516734 -0.048748717, 0.46669176 0.14945242 -0.071167335, 0.44655845 0.14516975 -0.092236206, 0.46199962 0.1484552 -0.090701595, 0.44655836 0.14516962 -0.090701744, 0.47149956 0.15046659 0.085887805, 0.47149971 0.15047619 -0.085869625, 0.46703672 0.14952587 -0.072667941, 0.4670063 0.14951938 -0.072052106, 0.46199962 0.14844488 0.090719655, 0.46688581 0.1494938 -0.071589246, 0.46199954 0.14844748 0.045766249, 0.46199962 0.14844495 0.088219538, 0.46199962 0.14845258 -0.045748457, 0.44655845 0.1451593 0.09225367, 0.44655839 0.14515954 0.090719447, 0.44655839 0.14515954 0.088219389, 0.46199968 0.14844735 0.04876636, 0.44655839 0.14516191 0.048766062, 0.45125845 0.14616722 -0.045748696, 0.45125851 0.14616202 0.0457661, 0.46199962 0.14845276 -0.048748478, 0.46669176 0.1494526 -0.073814765, 0.46692649 0.14950255 -0.073270217, 0.46199968 0.14845498 -0.088201627, 0.43649957 0.14616218 0.040766165, 0.43476209 0.14616185 0.0457661, 0.43476197 0.14616211 0.042503729, 0.43649957 0.1461668 -0.04074873, 0.43476197 0.14616707 -0.045748696, 0.43476203 0.14616691 -0.042486146, 0.43149966 0.14516719 -0.048748598, 0.43149957 0.14516948 -0.088201717, 0.43149951 0.14516959 -0.090701744, 0.43149957 0.14516978 -0.094241276, 0.43149954 0.14366977 -0.094241396, 0.43149969 0.14366703 -0.045748696, 0.43149963 0.14516701 -0.045748696, 0.41518539 -0.023543447 -0.052008286, 0.41708943 -0.018821418 -0.046746209, 0.41698024 -0.0190368 -0.045757845, 0.4174369 -0.018928126 -0.046136186, 0.41518542 -0.023543999 -0.04250811, 0.41554129 -0.022814423 -0.042564496, 0.41594023 -0.021996528 -0.042767301, 0.41631132 -0.021236032 -0.043106332, 0.41659182 -0.020660609 -0.043483302, 0.41686097 -0.020108968 -0.043977186, 0.41730037 -0.019207761 -0.04531844, 0.41710296 -0.019612819 -0.044591591, 0.41749921 -0.018800169 -0.047010377, 0.41120073 -0.019036919 -0.045757875, 0.41708943 -0.018821284 -0.047769472, 0.41748127 -0.018836901 -0.047897264, 0.41130552 -0.018821374 -0.046746239, 0.41698036 -0.019036695 -0.048757926, 0.41736966 -0.019065693 -0.048842534, 0.41130561 -0.018821329 -0.047769472, 0.41714898 -0.019518346 -0.049779639, 0.4112007 -0.019036785 -0.048757926, 0.4168191 -0.020194441 -0.050626293, 0.4163523 -0.0211512 -0.051361665, 0.41579181 -0.022300273 -0.051842555, 0.41804031 -0.017691657 -0.03593649, 0.41229513 -0.029469401 -0.035937116, 0.41229513 -0.029469043 -0.042508528, 0.41804031 -0.017690405 -0.058579132, 0.41229519 -0.029468089 -0.058579758, 0.4122951 -0.029468492 -0.052008435, 0.41429794 -0.02946952 -0.034137145, 0.41964704 -0.018503502 -0.034136549, 0.41964704 -0.01850456 -0.013121858, 0.41429803 -0.029470637 -0.015501156, 0.414298 -0.029470712 -0.013122454, 0.41429785 -0.029469624 -0.031758413, 0.41279522 -0.032550246 -0.031758651, 0.41279519 -0.032551184 -0.015501395, 0.41429785 -0.029468 -0.060379699, 0.41964707 -0.018501922 -0.060379222, 0.41279522 -0.032547846 -0.075021133, 0.41279513 -0.032548472 -0.062758639, 0.41429791 -0.029467866 -0.06275855, 0.41964707 -0.018501133 -0.075020328, 0.4139919 -0.020068377 -0.088547662, 0.41572359 -0.016518444 -0.088547572, 0.41256726 -0.024196669 -0.086918101, 0.41256741 -0.032547742 -0.075651273, 0.4139919 -0.015643612 -0.090294108, 0.41804019 -0.017693073 -0.011321768, 0.41229519 -0.029470861 -0.011322364, 0.41229519 -0.029472038 0.011320248, 0.41804031 -0.017694294 0.011320785, 0.41773856 -0.017538682 -0.045757845, 0.41773856 -0.017538533 -0.048757926, 0.41429791 -0.029472202 0.013120279, 0.41964707 -0.018506154 0.013120875, 0.41964707 -0.018507332 0.034135625, 0.41429779 -0.029473051 0.031756237, 0.41429794 -0.029473394 0.03413485, 0.41429785 -0.029472247 0.015498862, 0.41279519 -0.032552913 0.015498623, 0.4127951 -0.032553732 0.031756148, 0.41804031 -0.01769571 0.035935596, 0.41229516 -0.029473424 0.03593497, 0.41804031 -0.017697066 0.058578208, 0.41714907 -0.019523993 0.049778685, 0.41681901 -0.020200044 0.05062522, 0.4163523 -0.021156996 0.051360264, 0.41736963 -0.019071251 0.048841491, 0.41579184 -0.022306129 0.051841065, 0.41748127 -0.01884225 0.047896102, 0.41518542 -0.023549289 0.052006558, 0.41229513 -0.02947475 0.058577791, 0.41229519 -0.029474318 0.052006349, 0.41749921 -0.018805459 0.047009483, 0.4174369 -0.018933311 0.046135321, 0.41730049 -0.019212976 0.045317397, 0.41710284 -0.019617826 0.044590607, 0.41686094 -0.020113856 0.043975994, 0.41659182 -0.020665452 0.043481961, 0.41631126 -0.021240741 0.04310514, 0.41594031 -0.022001356 0.042765781, 0.41554126 -0.022819117 0.042563036, 0.41518545 -0.023548827 0.04250659, 0.41229516 -0.029473826 0.042506352, 0.41429788 -0.029474705 0.060377494, 0.41964701 -0.018508762 0.06037809, 0.41429794 -0.029475003 0.062756285, 0.41279528 -0.032556325 0.0750186, 0.41964707 -0.018509716 0.075019285, 0.4127951 -0.03255558 0.062756136, 0.41256738 -0.03255637 0.075648621, 0.41256726 -0.024206445 0.0869167, 0.4139919 -0.020078316 0.0885465, 0.41572359 -0.016528457 0.088546619, 0.41399196 -0.015653774 0.090293512, 0.41357729 -0.01543653 -0.048757777, 0.4144792 -0.013651386 -0.048757657, 0.4209542 0.0010032952 -0.048756823, 0.41864181 -0.015754193 -0.048757926, 0.4130004 0.0060314089 -0.048756436, 0.41300046 0.0050210208 -0.048756644, 0.42523369 0.0043545812 -0.048756644, 0.42810974 0.0029516518 -0.048756823, 0.42605159 0.0060314536 -0.048756465, 0.41300046 0.0060324222 -0.067999199, 0.42605159 0.0060324669 -0.067999199, 0.41300032 0.023951814 -0.067998067, 0.43479267 0.023951933 -0.067998156, 0.42095414 0.0010031462 -0.045756772, 0.41300049 0.0050209165 -0.045756623, 0.41357735 -0.015436739 -0.045757636, 0.41447914 -0.01365155 -0.045757607, 0.41864184 -0.015754268 -0.045757815, 0.41300046 0.0060312003 -0.045756623, 0.42523357 0.0043545365 -0.045756623, 0.42810968 0.0029515624 -0.045756653, 0.42605159 0.0060313195 -0.045756623, 0.41300052 0.0060259849 0.045758143, 0.42605165 0.006026119 0.045758143, 0.4209542 0.00099790096 0.045757994, 0.41300049 0.0050156713 0.045758024, 0.4252336 0.0043492466 0.045758024, 0.42810979 0.0029462874 0.045758024, 0.41864184 -0.015759572 0.045756862, 0.41447908 -0.013656676 0.04575707, 0.41698024 -0.019042015 0.045756713, 0.41357735 -0.015441924 0.04575707, 0.41773865 -0.017543942 0.045756862, 0.41120061 -0.019042 0.045756862, 0.41708937 -0.018826634 0.047768578, 0.41773847 -0.017543942 0.048756823, 0.41698033 -0.019042149 0.048756853, 0.41708937 -0.018826619 0.046745315, 0.42095414 0.00099785626 0.048757896, 0.41300043 0.0050156415 0.048758164, 0.4130004 0.0060259998 0.048758164, 0.42523369 0.004349187 0.048758104, 0.42605156 0.0060260892 0.048758164, 0.42810968 0.0029462874 0.048758104, 0.41447917 -0.013656825 0.048757121, 0.41864178 -0.015759513 0.048756853, 0.41357735 -0.015442044 0.048756912, 0.41120073 -0.019042224 0.048756823, 0.42605162 0.0060248822 0.068000928, 0.41300046 0.0060247928 0.068000928, 0.43479261 0.023944303 0.068001971, 0.41300038 0.023944199 0.06800209, 0.43479261 0.023952186 -0.070998088, 0.42523363 0.0043559223 -0.07099922, 0.42972746 0.0021638125 -0.070999369, 0.44035587 0.023952201 -0.070998088, 0.42052397 -0.016703457 -0.075020269, 0.42052397 -0.016704306 -0.060379222, 0.42972758 0.0021632314 -0.06037803, 0.44035581 0.023952484 -0.075018004, 0.43546546 0.023953184 -0.088545248, 0.41660061 -0.014720783 -0.088547334, 0.4139919 -0.013402894 -0.091178522, 0.41399166 0.023953915 -0.1059228, 0.42810962 0.0029523671 -0.05857794, 0.46212766 0.079989851 -0.069348559, 0.46162203 0.078953341 -0.070995167, 0.46139136 0.078480497 -0.069782719, 0.46280661 0.081381455 -0.068566546, 0.46063158 0.076922536 -0.069849506, 0.45988277 0.075387582 -0.069545612, 0.45733419 0.070162356 -0.061176971, 0.4538759 0.063073412 -0.067995891, 0.45734599 0.070186645 -0.060881808, 0.4573271 0.070147723 -0.061472848, 0.45732465 0.07014291 -0.061769113, 0.45740607 0.070309982 -0.063493684, 0.45764664 0.070803285 -0.06513916, 0.45803532 0.071600035 -0.0666302, 0.45855418 0.072663933 -0.067898259, 0.45917964 0.073946029 -0.068885073, 0.43625596 0.026952013 -0.067997918, 0.4523814 0.07255429 -0.061768964, 0.45238414 0.072559848 -0.062088832, 0.45239249 0.07257694 -0.062408224, 0.45240644 0.072605371 -0.062726691, 0.45256719 0.072935253 -0.064354584, 0.45287094 0.073557824 -0.065872386, 0.45330441 0.074446976 -0.067216411, 0.4538497 0.075564608 -0.06832929, 0.45448318 0.076863438 -0.069163278, 0.45517817 0.078288481 -0.069683775, 0.45590529 0.079778984 -0.069868311, 0.45663351 0.081271842 -0.069709018, 0.45733204 0.08270368 -0.06921275, 0.45758522 0.083222911 -0.068937615, 0.45782816 0.083720922 -0.068617657, 0.45805937 0.084194571 -0.068254933, 0.46310797 0.081999272 -0.068068221, 0.46338484 0.082566857 -0.067500666, 0.45854795 0.085196316 -0.067247495, 0.46363407 0.083077848 -0.066870198, 0.45894653 0.086013377 -0.066051677, 0.46397337 0.083773226 -0.065729931, 0.45924163 0.086617962 -0.064708546, 0.46422285 0.084284812 -0.064474687, 0.45942268 0.086989224 -0.063264087, 0.46437559 0.084597796 -0.06314142, 0.45948377 0.087114275 -0.061768129, 0.46442693 0.084703073 -0.061768368, 0.45372584 0.072764635 -0.058303609, 0.45296648 0.073753506 -0.05731456, 0.45270118 0.073209777 -0.058409318, 0.45251301 0.072823942 -0.059584215, 0.45496199 0.071700305 -0.059368238, 0.45240638 0.072605282 -0.060811117, 0.45606002 0.070948362 -0.060119912, 0.45239249 0.07257688 -0.061129496, 0.45238414 0.072559848 -0.061448976, 0.45204571 0.077020228 -0.060810879, 0.45190364 0.078417584 -0.06112428, 0.45188147 0.078372091 -0.061444595, 0.45194033 0.078492835 -0.060810611, 0.45200714 0.076929823 -0.061394587, 0.45187399 0.078356966 -0.061768606, 0.4521623 0.075548232 -0.060810938, 0.45226485 0.074036866 -0.06118007, 0.41299999 0.063073173 -0.067995891, 0.41300029 0.026951775 -0.067998007, 0.45818624 0.077295125 -0.053772613, 0.46162155 0.07895121 -0.05211626, 0.46086439 0.07739912 -0.053668723, 0.45597288 0.076991677 -0.054076239, 0.4550676 0.076767966 -0.054299816, 0.41299996 0.078951016 -0.052116379, 0.45430622 0.076499715 -0.054568097, 0.41299996 0.078950718 -0.048752442, 0.46162167 0.078951001 -0.048752442, 0.4573321 0.08270286 -0.054323927, 0.45619211 0.080366194 -0.058827415, 0.45658532 0.081172094 -0.053806439, 0.45587721 0.079720646 -0.058771268, 0.45580703 0.079576746 -0.05367361, 0.45503488 0.077993751 -0.053931519, 0.45556542 0.079081595 -0.058887854, 0.45527503 0.078485981 -0.059170559, 0.45502234 0.077968076 -0.05960308, 0.45482227 0.077557832 -0.060160592, 0.45468619 0.077279016 -0.060810879, 0.45894665 0.086012915 -0.057484761, 0.45691946 0.081857279 -0.059785262, 0.45854792 0.085195646 -0.056288972, 0.45805937 0.084193856 -0.055281505, 0.45924148 0.086617664 -0.058828011, 0.45709822 0.082223982 -0.060379222, 0.45942265 0.08698909 -0.060272291, 0.45720994 0.082452759 -0.061052963, 0.45724779 0.082530618 -0.061768368, 0.45720991 0.082452968 -0.062483594, 0.45709831 0.082224071 -0.063157633, 0.45691943 0.081857517 -0.063751683, 0.45349574 0.081681535 -0.058827415, 0.45318088 0.081035912 -0.058771089, 0.45286918 0.08039692 -0.058887675, 0.45257863 0.079801232 -0.059170321, 0.45232591 0.079283386 -0.05960308, 0.45212588 0.078873172 -0.060160533, 0.4519898 0.078594267 -0.060810611, 0.45422304 0.083172828 -0.063751534, 0.45440197 0.083539397 -0.063157514, 0.45451364 0.083768144 -0.062483594, 0.45455149 0.083845809 -0.061768427, 0.45451355 0.08376807 -0.061052963, 0.454402 0.083539248 -0.060378954, 0.45422313 0.083172515 -0.059785262, 0.45619223 0.080366492 -0.06470938, 0.45587721 0.079720944 -0.064765915, 0.45556542 0.079081982 -0.064649329, 0.45468614 0.07727921 -0.062726453, 0.45527497 0.078486294 -0.064366683, 0.45482221 0.077558115 -0.06337662, 0.45502234 0.077968374 -0.063934043, 0.45198983 0.078594372 -0.062726334, 0.45212594 0.078873351 -0.06337662, 0.452326 0.079283625 -0.063934103, 0.45257863 0.07980144 -0.064366534, 0.45286921 0.080397144 -0.064649329, 0.45318088 0.081036299 -0.064765766, 0.45349583 0.081681907 -0.064709321, 0.4316974 0.1534557 -0.13425465, 0.41287076 0.15345559 -0.13425465, 0.42804602 0.15345553 -0.13215433, 0.41237399 0.15345554 -0.13419737, 0.41173396 0.15345554 -0.13402469, 0.42804605 0.15145555 -0.13215433, 0.45326295 0.078790143 -0.11580189, 0.46512967 0.086142823 -0.048751935, 0.46382621 0.083471 -0.057260051, 0.46338284 0.082562089 -0.05603151, 0.46284291 0.081454977 -0.0550244, 0.4641557 0.084146425 -0.058662429, 0.46222684 0.080192268 -0.054277554, 0.46435851 0.084562495 -0.060184911, 0.46155873 0.078822643 -0.053819671, 0.46512967 0.086143628 -0.063803777, 0.41100025 0.036605358 0.13366897, 0.41100031 0.035889685 0.13303788, 0.41100031 0.036209375 0.13339694, 0.41100022 0.037531972 0.13389651, 0.41100031 0.037054837 0.13383909, 0.41099975 0.10785703 0.1339006, 0.41099951 0.15344064 0.13139911, 0.41099948 0.15294094 0.13390319, 0.41099945 0.15327792 0.13384263, 0.41099939 0.15310924 0.13388796, 0.41099945 0.15344046 0.13376872, 0.41300067 -0.035547823 -0.075100526, 0.41294625 -0.035547763 -0.075409427, 0.41298378 -0.035547778 -0.075274184, 0.41299656 -0.035547823 -0.075187519, 0.41273943 -0.035547704 -0.075981572, 0.41300067 -0.035548598 -0.06056793, 0.41300073 -0.035550103 -0.033949748, 0.41300079 -0.035551324 -0.013310537, 0.41301492 -0.035522595 -0.012972429, 0.41304591 -0.035458624 -0.01270853, 0.41300425 -0.035544187 -0.013141021, 0.41300976 -0.035531715 -0.034220681, 0.41302451 -0.035501584 -0.034387872, 0.41304597 -0.035457402 -0.034551665, 0.43279696 0.0050315708 -0.012706235, 0.43290326 0.0052497089 -0.013307437, 0.43286285 0.0051666498 -0.012995258, 0.43291709 0.0052777529 -0.013631597, 0.43291703 0.0052788556 -0.033624157, 0.43286291 0.0051677525 -0.034260496, 0.43290344 0.0052508265 -0.033948317, 0.43279693 0.0050327927 -0.0345494, 0.47549972 0.13652298 -0.16812573, 0.47538522 0.13794538 -0.16975312, 0.475436 0.13790266 -0.16983859, 0.47549966 0.13786317 -0.16991757, 0.47531989 0.1380377 -0.16956846, 0.47529975 0.13813388 -0.16937582, 0.47031969 0.144318 -0.1525334, 0.47102168 0.14470211 -0.15176497, 0.47520903 0.13552794 -0.17011599, 0.47549966 0.13554581 -0.17008035, 0.46945423 0.14400931 -0.15315072, 0.4850274 0.14883429 -0.14349981, 0.48527518 0.14895937 -0.14324971, 0.4847199 0.14873931 -0.14368968, 0.48399958 0.14865984 -0.1438484, 0.47153136 0.14513102 -0.15090708, 0.48362866 0.14868011 -0.14380832, 0.48544899 0.14910725 -0.14295383, 0.46847895 0.14379928 -0.15357079, 0.48437056 0.14868012 -0.14380832, 0.47184649 0.1455733 -0.15002252, 0.46746174 0.14369813 -0.15377323, 0.47196344 0.14588739 -0.14939429, 0.48327938 0.14873929 -0.14368968, 0.4664695 0.14370152 -0.15376656, 0.48255032 0.1491072 -0.14295362, 0.47199962 0.14618704 -0.14879443, 0.48246086 0.14926943 -0.14262922, 0.48272401 0.14895923 -0.14324971, 0.48297188 0.1488342 -0.14349981, 0.46546093 0.14380872 -0.15355201, 0.48553821 0.14926949 -0.14262922, 0.48553833 0.14943647 -0.14229487, 0.4854489 0.14959876 -0.14197038, 0.4852753 0.14974675 -0.14167459, 0.48502743 0.14987181 -0.14142425, 0.48471996 0.14996673 -0.14123447, 0.46450645 0.14402023 -0.15312876, 0.48327923 0.14996669 -0.14123438, 0.47199956 0.1524003 -0.1363665, 0.48362863 0.15002599 -0.14111598, 0.48297173 0.14987174 -0.14142449, 0.48272389 0.14974675 -0.14167459, 0.48255038 0.14959875 -0.14197038, 0.48246089 0.14943656 -0.14229508, 0.4843705 0.15002598 -0.14111598, 0.48399952 0.15004624 -0.14107569, 0.48331028 0.14993355 -0.14128406, 0.48252714 0.14942625 -0.14229883, 0.48261276 0.14958145 -0.14198823, 0.48365989 0.14870992 -0.14368196, 0.48367348 0.14870265 -0.14361642, 0.48399958 0.14868501 -0.14365204, 0.48267213 0.14955154 -0.14199837, 0.48333976 0.14876427 -0.14357315, 0.48336616 0.14875478 -0.1435122, 0.48259017 0.14940289 -0.14229567, 0.48364463 0.14999032 -0.14117058, 0.48365983 0.14994283 -0.14121558, 0.48333979 0.14988862 -0.14132436, 0.48259011 0.14924991 -0.1426018, 0.4826465 0.14936785 -0.14228581, 0.48264661 0.14922094 -0.14257975, 0.48364469 0.14870223 -0.14374684, 0.48399964 0.14869151 -0.14371876, 0.48399967 0.14868312 -0.14378552, 0.48331025 0.14875896 -0.14363338, 0.48305812 0.14980163 -0.14149816, 0.48336616 0.14983419 -0.14135344, 0.48309577 0.14975056 -0.14152034, 0.48272517 0.14907831 -0.14286505, 0.4826937 0.14918102 -0.14255352, 0.48276955 0.14904337 -0.14282887, 0.48287788 0.14964066 -0.14174031, 0.48312733 0.1496923 -0.14153071, 0.48291704 0.1495861 -0.14174317, 0.48291698 0.14891788 -0.14307995, 0.48280302 0.14899822 -0.14279206, 0.4836987 0.14969042 -0.14126574, 0.48399958 0.1496437 -0.1412098, 0.48370039 0.14962748 -0.14124234, 0.48399964 0.14970674 -0.14123301, 0.48276955 0.14946054 -0.14199437, 0.48294643 0.14952609 -0.14173593, 0.48280296 0.14940408 -0.14198025, 0.48294649 0.14887606 -0.14303644, 0.48315093 0.14877285 -0.14324303, 0.48296461 0.148825 -0.14299674, 0.48316571 0.14872357 -0.14319964, 0.48369339 0.14975664 -0.14127468, 0.48399958 0.14977334 -0.14124151, 0.48272911 0.14927009 -0.14224823, 0.48282373 0.14934377 -0.14195888, 0.48275119 0.14921215 -0.14222224, 0.48341516 0.1486465 -0.1433536, 0.48317072 0.14866635 -0.14316483, 0.48341873 0.14858969 -0.14331786, 0.48275119 0.14907655 -0.14249332, 0.48275876 0.14915207 -0.14219321, 0.48275873 0.14901721 -0.14246278, 0.48341519 0.14964232 -0.14136179, 0.48341861 0.14957972 -0.14133783, 0.48252717 0.14926632 -0.14261861, 0.48301598 0.14984275 -0.14146562, 0.48368487 0.14982308 -0.1412691, 0.48399958 0.14984025 -0.14123504, 0.48267198 0.14910129 -0.14289911, 0.48283115 0.14968701 -0.14172752, 0.4834049 0.14970788 -0.14137264, 0.48287788 0.14894836 -0.14312537, 0.48272523 0.14951053 -0.14200063, 0.48316571 0.14956523 -0.14151596, 0.48317066 0.14950301 -0.14149125, 0.48399952 0.15000953 -0.14113207, 0.48269376 0.1493229 -0.14226981, 0.48312721 0.14881171 -0.14329223, 0.48367339 0.14988628 -0.14124916, 0.48399958 0.14990392 -0.14121364, 0.48340496 0.14869443 -0.14339958, 0.48338833 0.14977273 -0.14136975, 0.48272917 0.14913209 -0.1425242, 0.4836987 0.14859834 -0.14344998, 0.48370036 0.14854202 -0.14341353, 0.48399967 0.14852567 -0.14344598, 0.48399958 0.14858203 -0.14348252, 0.48282394 0.14894491 -0.14275666, 0.48283091 0.14888643 -0.14272447, 0.48261276 0.14911112 -0.14292915, 0.48315093 0.14962952 -0.14152949, 0.48277888 0.14972299 -0.14170511, 0.48283106 0.14896581 -0.14317022, 0.48296461 0.14946391 -0.14171885, 0.48297074 0.14940216 -0.14169271, 0.48309579 0.14883825 -0.14334525, 0.48399958 0.14996138 -0.14117883, 0.48338822 0.14873119 -0.1434534, 0.48369339 0.14864546 -0.14349745, 0.48399952 0.14862892 -0.14353083, 0.48277888 0.14896955 -0.14321233, 0.48297083 0.14876726 -0.14296307, 0.48305807 0.14885119 -0.14339937, 0.48283091 0.14928271 -0.14193131, 0.48368469 0.1486809 -0.14355396, 0.48399958 0.14866367 -0.14358814, 0.48301598 0.14884982 -0.14345179, 0.4704456 0.082208395 0.062254205, 0.47289875 0.087245017 -0.073748931, 0.47289869 0.087236792 0.073759899, 0.47305542 0.087557763 0.075155869, 0.47297129 0.08738558 0.074690536, 0.47306159 0.087570518 0.07514821, 0.47280201 0.087038234 0.075104311, 0.47286019 0.087157443 0.075113252, 0.47291163 0.087262958 0.075139716, 0.47295609 0.087354183 0.075183615, 0.41300419 -0.03554818 0.060395494, 0.4130148 -0.035526559 0.060226753, 0.41300073 -0.035555407 0.060564891, 0.47291684 0.087282255 -0.074215278, 0.47280204 0.087046638 -0.075093612, 0.47297129 0.087394029 -0.074679479, 0.46734869 0.075867057 -0.069526508, 0.46754989 0.076279461 -0.069205746, 0.46711949 0.075397208 -0.069727138, 0.46687585 0.074897647 -0.069795325, 0.47291681 0.087274015 0.074226186, 0.46754989 0.076271698 0.069215432, 0.41304594 -0.035462618 0.059963062, 0.47286019 0.087165862 -0.075102344, 0.47291166 0.087271452 -0.075128809, 0.41300073 -0.035556227 0.075097516, 0.43438122 0.0082746744 0.068787172, 0.43454239 0.0086052716 0.069210246, 0.47295615 0.087362692 -0.075172767, 0.47011128 0.081522942 0.063964739, 0.43474376 0.0090180337 0.069531903, 0.47025266 0.08181262 0.063607588, 0.43426958 0.0080459565 0.068287715, 0.47298515 0.087422356 -0.07521759, 0.47303841 0.087531328 -0.075180903, 0.43497321 0.0094884336 0.06973277, 0.47035807 0.082029268 0.063190714, 0.4730497 0.087554529 -0.075154141, 0.47305545 0.087566301 -0.075144961, 0.43521711 0.0099884868 0.069801107, 0.47042349 0.082163095 0.06273295, 0.47306165 0.087579116 -0.075137451, 0.47302559 0.087505266 -0.07522954, 0.4330312 0.0055079013 0.060526982, 0.43294272 0.0053260922 0.060137466, 0.43299261 0.0054282695 0.060325876, 0.47301599 0.087485552 -0.075288251, 0.43288255 0.0052029639 0.059965387, 0.43521714 0.0099962056 -0.069798842, 0.43288258 0.0052096546 -0.059963629, 0.43497321 0.009496212 -0.069730625, 0.41304594 -0.035455957 -0.059965983, 0.43294266 0.0053327978 -0.060135558, 0.4330312 0.005514726 -0.060525373, 0.43299252 0.0054350793 -0.060323998, 0.43426958 0.0080536455 -0.06828554, 0.4343811 0.0082824677 -0.068784937, 0.4130148 -0.035519868 -0.060229585, 0.43454242 0.0086129904 -0.06920822, 0.41300425 -0.035541445 -0.060398415, 0.43474373 0.0090257972 -0.069529638, 0.46687582 0.074889868 0.069804654, 0.46734866 0.075859249 0.069536194, 0.46711949 0.07538937 0.069736615, 0.47298518 0.087413818 0.075228557, 0.47302565 0.087496743 0.075240448, 0.47301602 0.087476969 0.075299457, 0.47303846 0.08752279 0.075191781, 0.47304961 0.087545991 0.075164899, 0.47044563 0.082215339 -0.062244132, 0.47042355 0.082170159 -0.062722638, 0.47035837 0.082036272 -0.063180283, 0.47025272 0.081819758 -0.063597187, 0.47011122 0.081530154 -0.063954785, 0.47549957 0.13791071 -0.17043762, 0.47549966 0.13524827 -0.17043774, 0.47549954 0.13536526 -0.17033471, 0.47549969 0.1354655 -0.17021407, 0.47549966 0.13785312 -0.17031445, 0.47549972 0.1378887 -0.17035832, 0.47549966 0.13793305 -0.17039372, 0.47549966 0.13782719 -0.17026429, 0.47549966 0.13798417 -0.17041807, 0.47549966 0.13781108 -0.17020942, 0.47549966 0.13803473 -0.1704302, 0.47549972 0.13808699 -0.17043214, 0.4754996 0.13780494 -0.17012571, 0.47549966 0.13782139 -0.17002381, 0.41260931 -0.03550306 -0.076402023, 0.41252786 -0.035369024 -0.07680808, 0.41250077 -0.035154596 -0.077172384, 0.41250071 -0.026436687 -0.088934347, 0.41251156 -0.026262507 -0.08913888, 0.4630672 0.077377945 -0.089133129, 0.47275797 0.08706817 -0.075402603, 0.4125008 -0.032471001 -0.0085728616, 0.41250068 -0.03247188 0.0085703284, 0.42989624 0.0031894743 0.010493502, 0.41221502 -0.033057779 0.0099844784, 0.41196766 -0.033564895 0.010491475, 0.41247925 -0.032515973 0.0089876801, 0.41241404 -0.032649398 0.0093940645, 0.41232666 -0.032828912 0.0097105652, 0.41247916 -0.032514945 -0.0089902729, 0.42989627 0.0031907558 -0.010492161, 0.41241407 -0.032648489 -0.0093966573, 0.41232657 -0.03282778 -0.0097132772, 0.41196755 -0.033563718 -0.010494336, 0.41221514 -0.033056691 -0.0099870712, 0.42991754 0.0032413304 -0.010486171, 0.42991766 0.0032400787 0.010487631, 0.42993334 0.0032943636 -0.010467932, 0.42993328 0.0032931119 0.010469303, 0.42994311 0.0033488125 -0.010437801, 0.42994317 0.0033475459 0.010439292, 0.42994604 0.0033781826 0.010417476, 0.42994592 0.0033794045 -0.010416135, 0.42994687 0.0034099668 -0.010390982, 0.42994693 0.0034087449 0.010392442, 0.41250077 -0.032468319 -0.055830106, 0.41250065 -0.032469243 -0.038687035, 0.41221499 -0.033053979 -0.057244554, 0.41732815 -0.022572234 -0.050632462, 0.41232654 -0.032825112 -0.056970641, 0.41297045 -0.031505838 -0.050808534, 0.41297022 -0.031506121 -0.043708548, 0.41196755 -0.033561051 -0.057751551, 0.42989624 0.0031933486 -0.057749644, 0.4175742 -0.022067696 -0.050423399, 0.41825211 -0.020678252 -0.045355484, 0.42989621 0.0031922162 -0.036763802, 0.41798514 -0.021225691 -0.044688776, 0.41765699 -0.021898374 -0.044184789, 0.41842824 -0.020317331 -0.046106204, 0.41726369 -0.022704482 -0.043843463, 0.41851118 -0.020146772 -0.046867087, 0.41851088 -0.020147547 -0.047656283, 0.41842699 -0.020319477 -0.04841657, 0.41827127 -0.020638853 -0.049097285, 0.4180631 -0.021065593 -0.0496649, 0.41221493 -0.033055052 -0.037272796, 0.41782415 -0.0215552 -0.050105676, 0.41235608 -0.032765791 -0.037639186, 0.41679022 -0.023675427 -0.043708131, 0.41196755 -0.033562288 -0.036765829, 0.41244581 -0.032581806 -0.038025662, 0.41248718 -0.032497078 -0.038354889, 0.41679007 -0.023675054 -0.050808206, 0.41247919 -0.032512218 -0.056247637, 0.41241416 -0.032645717 -0.056653991, 0.41704428 -0.023154229 -0.050769672, 0.42991415 0.0032331795 -0.036767855, 0.42991766 0.003243953 -0.057743564, 0.42992827 0.0032760501 -0.036779866, 0.42993334 0.0032968819 -0.057725266, 0.42994115 0.0033361614 -0.03680934, 0.42994314 0.0033513606 -0.057695165, 0.42994601 0.0033818781 -0.05767338, 0.42994687 0.0034113973 -0.036864981, 0.4299469 0.0034125149 -0.057648316, 0.41250041 0.025688469 -0.10983275, 0.41250071 -0.025564104 -0.089603767, 0.41242966 0.026095271 -0.11005066, 0.4123424 0.026276797 -0.11019288, 0.46209568 0.076029688 -0.089567289, 0.41248271 0.025897756 -0.10992979, 0.41250274 -0.025637582 -0.089572951, 0.41250038 0.026954636 -0.11952932, 0.41250029 0.026954308 -0.11169292, 0.49245986 0.10691448 -0.10538112, 0.49270698 0.1071617 -0.10676514, 0.49264526 0.1071 -0.10606585, 0.49227071 0.10672536 -0.10494886, 0.49203479 0.10648932 -0.10454588, 0.47549728 0.089951292 -0.096110269, 0.49270692 0.10716315 -0.13301556, 0.47371539 0.08816807 -0.07707797, 0.47508356 0.089537635 -0.095398441, 0.47486845 0.089322165 -0.095157638, 0.47465888 0.089112714 -0.095007703, 0.4744902 0.088944122 -0.094951168, 0.47437266 0.088826507 -0.094948456, 0.4742606 0.088714555 -0.094977185, 0.46321478 0.077668279 -0.089442089, 0.47332582 0.087778375 -0.076402321, 0.47288159 0.08733435 -0.075745538, 0.47312775 0.087580383 -0.075955942, 0.46291977 0.077373192 -0.089762345, 0.47296712 0.087419778 -0.075496033, 0.46250528 0.076958701 -0.090056196, 0.46198997 0.076443374 -0.090310469, 0.41250995 0.026964337 -0.11972474, 0.41253856 0.026992902 -0.11991836, 0.41248176 0.026935667 -0.11142085, 0.41242579 0.026879817 -0.11115263, 0.41233441 0.026788235 -0.11089562, 0.41250023 0.035904661 -0.13303269, 0.41250029 0.027312472 -0.12067072, 0.41251004 0.027205884 -0.12049942, 0.41253898 0.027117014 -0.12031846, 0.41300032 0.029425159 -0.12278898, 0.4184368 0.034861609 -0.12059225, 0.41300029 0.033873156 -0.12918864, 0.4194369 0.035959885 -0.12032931, 0.41251692 0.036069885 -0.13323988, 0.4125444 0.03618671 -0.13335757, 0.41258425 0.036312565 -0.13346495, 0.41683608 0.037708923 -0.12763865, 0.41752738 0.038358748 -0.12729977, 0.4183518 0.039029002 -0.12674458, 0.41904262 0.039497554 -0.12614556, 0.41996792 0.036642075 -0.12033217, 0.4742783 0.088855788 -0.095370427, 0.42057416 0.037559897 -0.12053557, 0.42094311 0.038266987 -0.12087302, 0.42115352 0.038826182 -0.12128986, 0.42124328 0.039273351 -0.12176795, 0.42122427 0.039639652 -0.12232982, 0.42109177 0.039903194 -0.12295346, 0.47174513 0.095472977 -0.10955895, 0.42085138 0.040051401 -0.12360965, 0.42051861 0.040082246 -0.12426697, 0.42011586 0.040004104 -0.12489675, 0.41966817 0.039833337 -0.12547611, 0.41227058 0.10717303 -0.13388743, 0.41327885 0.10709243 -0.13388743, 0.41294232 0.10699005 -0.13388743, 0.41274729 0.10688876 -0.13388743, 0.41263747 0.10680149 -0.13388751, 0.41256085 0.10670801 -0.13388743, 0.41252086 0.10662587 -0.13388743, 0.41203958 0.10718186 -0.13388743, 0.41250494 0.10656436 -0.13388743, 0.41249979 0.10650204 -0.13388743, 0.41181752 0.10720979 -0.13388743, 0.41151693 0.10728829 -0.13388743, 0.41134757 0.1073644 -0.13388743, 0.41124079 0.10743278 -0.13388743, 0.41250032 0.037547007 -0.13389148, 0.41100892 0.10777645 -0.13388743, 0.41103691 0.10768315 -0.13388743, 0.41108468 0.10759366 -0.13388743, 0.41115275 0.10750963 -0.13388743, 0.41412327 0.10717295 -0.13388751, 0.49199998 0.10696393 -0.13343816, 0.47353327 0.1236088 -0.16912816, 0.49199989 0.12255146 -0.1668606, 0.47178039 0.096275166 -0.11051951, 0.47212827 0.09613058 -0.11020957, 0.47123638 0.096411839 -0.11081277, 0.47242442 0.095896259 -0.10970713, 0.47246984 0.095813453 -0.10952972, 0.47479019 0.089752138 -0.096532747, 0.47086176 0.095505565 -0.11030827, 0.41256943 0.037213802 -0.13386343, 0.4125216 0.037361234 -0.13388281, 0.41250554 0.037454113 -0.13388912, 0.47303462 0.12451503 -0.16957222, 0.47466111 0.12587908 -0.17050768, 0.47471038 0.12624577 -0.17053618, 0.47470781 0.12616059 -0.17053463, 0.4745523 0.12560011 -0.17044519, 0.47438085 0.12533346 -0.17034654, 0.47414985 0.1250889 -0.17021383, 0.47386697 0.1248748 -0.17005102, 0.4734695 0.12466499 -0.16982235, 0.47471038 0.13463353 -0.17053558, 0.47505769 0.12575151 -0.17062701, 0.4752892 0.12580158 -0.17063345, 0.47521678 0.12548429 -0.17057566, 0.47493902 0.12537326 -0.17054532, 0.47489327 0.1258007 -0.17060138, 0.47511229 0.12613121 -0.17066298, 0.47477725 0.12546036 -0.17052965, 0.47318092 0.12406677 -0.16952683, 0.4730953 0.12428436 -0.16957442, 0.47420284 0.12399258 -0.16971077, 0.47340629 0.12371908 -0.16929726, 0.47532591 0.12611814 -0.17065983, 0.4737516 0.12457778 -0.16996111, 0.47384956 0.12440456 -0.16994886, 0.47328666 0.12387475 -0.1694328, 0.47400036 0.12419519 -0.16987769, 0.47424755 0.12495413 -0.17025293, 0.47435442 0.12482597 -0.17026578, 0.47451025 0.12466641 -0.17024271, 0.47471419 0.12449874 -0.1701514, 0.4744857 0.1252301 -0.17039309, 0.47459695 0.12513162 -0.17041735, 0.47475567 0.12500721 -0.17041664, 0.47502753 0.12499611 -0.17041837, 0.47466221 0.12552877 -0.17049693, 0.47477528 0.12583899 -0.17056312, 0.47490308 0.12614559 -0.17062052, 0.41300026 0.037766293 -0.12724252, 0.41300026 0.03645502 -0.12589748, 0.41300029 0.034147993 -0.12870474, 0.41300026 0.036909655 -0.12215255, 0.41300029 0.038007349 -0.12086053, 0.41300026 0.037252054 -0.12058945, 0.41300014 0.038018629 -0.12291797, 0.41300026 0.039237782 -0.12187476, 0.4130002 0.037714899 -0.12257524, 0.4130002 0.039648175 -0.12256442, 0.41300032 0.032891199 -0.1229182, 0.41300029 0.033194885 -0.12257539, 0.41300032 0.02992478 -0.12286137, 0.41300026 0.03868109 -0.12129657, 0.41300029 0.037337929 -0.12231492, 0.41300026 0.036909804 -0.12584229, 0.41300032 0.033852756 -0.12915172, 0.41300032 0.02945438 -0.12282296, 0.41300029 0.033571884 -0.12231536, 0.41300035 0.037337929 -0.12567978, 0.41300023 0.038470998 -0.12685843, 0.41300023 0.037715003 -0.1254196, 0.41300026 0.039069772 -0.12632401, 0.41300029 0.038018703 -0.12507673, 0.41300032 0.033840224 -0.1291113, 0.41300032 0.029492855 -0.122853, 0.41300032 0.033836037 -0.12906845, 0.41300026 0.039530948 -0.12566729, 0.41300023 0.038231596 -0.12467109, 0.41300043 0.033843398 -0.12900899, 0.41300032 0.029557168 -0.1228839, 0.4130002 0.034000278 -0.12215285, 0.41300026 0.035143673 -0.12075238, 0.41300026 0.034454912 -0.12209745, 0.41300026 0.036454856 -0.12209736, 0.41300014 0.039830476 -0.12492271, 0.41300026 0.038341194 -0.12422638, 0.41300038 0.033866778 -0.12894596, 0.41300026 0.033195138 -0.12541981, 0.41300029 0.033906326 -0.12888239, 0.41300014 0.035568669 -0.12061162, 0.41300026 0.032891408 -0.12507696, 0.41300032 0.029653385 -0.12290452, 0.41300038 0.033960596 -0.12882267, 0.41300032 0.033572078 -0.12567993, 0.41300032 0.034026146 -0.1287701, 0.41300035 0.034085974 -0.12873353, 0.41300026 0.029784858 -0.12290008, 0.41300032 0.03267853 -0.12467153, 0.41300026 0.034000367 -0.12584238, 0.41300026 0.03600806 -0.12052615, 0.41300017 0.032568872 -0.12422653, 0.41300023 0.039952502 -0.12412961, 0.41300035 0.03834103 -0.1237682, 0.41300032 0.034455106 -0.1258976, 0.41300014 0.036454812 -0.12049739, 0.41300026 0.032568723 -0.12376855, 0.41300032 0.039890587 -0.12332939, 0.41300026 0.038231432 -0.12332366, 0.41300026 0.032678306 -0.1233239, 0.41661867 0.037766337 -0.12724252, 0.41666609 0.037728161 -0.12726556, 0.41671121 0.037697166 -0.12730058, 0.41675207 0.037674665 -0.12734579, 0.41678646 0.037661806 -0.12739928, 0.41681322 0.037658975 -0.12745853, 0.41683084 0.0376665 -0.12752075, 0.41948083 0.036454856 -0.12049739, 0.4199118 0.036992103 -0.12053891, 0.42032433 0.037578627 -0.12068255, 0.42062649 0.038086668 -0.12090106, 0.42081153 0.038466275 -0.12113293, 0.42094716 0.03883101 -0.12142749, 0.42102137 0.039166734 -0.12178473, 0.42102364 0.039458603 -0.12220059, 0.42093346 0.039713964 -0.12272115, 0.42071632 0.039894447 -0.12334947, 0.42034099 0.039954215 -0.12407239, 0.41972515 0.039827213 -0.12493487, 0.41886371 0.039435148 -0.12583311, 0.41771036 0.038677827 -0.12670101, 0.41821942 0.035143703 -0.12075229, 0.41887689 0.035786957 -0.12056179, 0.43599951 0.14366987 -0.094741479, 0.43611082 0.14366987 -0.094753936, 0.43648705 0.14366983 -0.09513022, 0.43649957 0.14366987 -0.095241353, 0.43899962 0.14366983 -0.095741346, 0.43648699 0.14366989 -0.095352575, 0.43899959 0.14365906 0.095758662, 0.43631136 0.14365909 0.095649585, 0.43639049 0.14365909 0.09557046, 0.43645009 0.14366992 -0.095458284, 0.43645003 0.14365904 0.095475689, 0.43621656 0.14365907 0.09570919, 0.43639049 0.14366993 -0.095553085, 0.43611076 0.1436591 0.095746115, 0.43631133 0.14366993 -0.09563224, 0.43648699 0.1436592 0.09536998, 0.43621656 0.14366992 -0.095691934, 0.43599966 0.14365909 0.095758662, 0.43611076 0.14366989 -0.09572871, 0.43599951 0.14366992 -0.095741346, 0.43649963 0.1436592 0.095258549, 0.43648699 0.1436592 0.095147416, 0.43199956 0.1436698 -0.094741479, 0.43645003 0.14365914 0.095041856, 0.43151203 0.14366981 -0.094352648, 0.43188819 0.14366987 -0.094728962, 0.43639055 0.1436592 0.094946995, 0.43631127 0.1436592 0.094867781, 0.43154904 0.14366983 -0.094458267, 0.43168777 0.14366977 -0.094632402, 0.4362165 0.14365922 0.094808295, 0.43160862 0.14366977 -0.094553247, 0.43178263 0.14366983 -0.094691887, 0.43188819 0.1436592 0.094745979, 0.43178257 0.1436592 0.094709083, 0.43199965 0.14365923 0.094758704, 0.43168774 0.14365926 0.094649598, 0.43160859 0.1436592 0.094570473, 0.43154904 0.1436592 0.094475463, 0.43151203 0.14365925 0.094369844, 0.43149951 0.1436592 0.09425877, 0.4359996 0.1436592 0.094758704, 0.43149963 0.14366189 0.045765802, 0.43611082 0.14365925 0.094771251, 0.43649957 0.14366208 0.040766016, 0.43649957 0.14366677 -0.04074879, 0.43631133 0.1436698 -0.094850585, 0.43639049 0.14366981 -0.09492974, 0.43645015 0.14366986 -0.095024481, 0.43621659 0.14366981 -0.094790831, 0.43257234 0.1385181 -0.095741674, 0.43049958 0.14516978 -0.095741317, 0.43278602 0.1390816 -0.095741674, 0.43312833 0.13957763 -0.095741555, 0.43357944 0.13997731 -0.095741555, 0.43411306 0.14025742 -0.095741555, 0.43599954 0.14516985 -0.095741317, 0.4304997 0.12666984 -0.09574239, 0.43599963 0.12816988 -0.09574236, 0.43599966 0.12666988 -0.09574236, 0.43899971 0.12816982 -0.095742151, 0.4368709 0.1395777 -0.095741555, 0.43641981 0.13997735 -0.095741555, 0.43721312 0.13908182 -0.095741674, 0.43742695 0.13851817 -0.095741555, 0.43469831 0.14040153 -0.095741555, 0.43530092 0.14040172 -0.095741555, 0.43588614 0.14025739 -0.095741674, 0.43645027 0.12815918 0.095040992, 0.43648717 0.12815917 0.095146611, 0.43899962 0.12815909 0.095757887, 0.43149963 0.12816185 0.045765057, 0.43599972 0.12815918 0.09475778, 0.436111 0.12815921 0.094770476, 0.43631145 0.12816979 -0.095633075, 0.43639058 0.12816979 -0.095554069, 0.43649969 0.12815917 0.095257714, 0.43621668 0.12816989 -0.095692739, 0.43648717 0.12815917 0.095368996, 0.43645015 0.12816982 -0.095459118, 0.43611094 0.12816985 -0.095729724, 0.43645015 0.12815902 0.095474645, 0.43648711 0.12816983 -0.095353499, 0.43639061 0.12815909 0.095569447, 0.43631145 0.12815908 0.095648572, 0.43649966 0.12816988 -0.095242307, 0.43621662 0.128159 0.095708296, 0.43648711 0.12816988 -0.095131055, 0.43611088 0.12815903 0.095745131, 0.43645015 0.12816989 -0.095025226, 0.43599969 0.12815903 0.095757648, 0.43639058 0.12816988 -0.094930544, 0.43149966 0.12815928 0.094257906, 0.43199965 0.1281592 0.09475778, 0.43631145 0.12816986 -0.09485139, 0.43151215 0.12815924 0.094369009, 0.43621668 0.12816982 -0.094791666, 0.43178269 0.1281592 0.094708249, 0.43188831 0.1281592 0.094745323, 0.43154916 0.12815918 0.094474629, 0.43168786 0.12815928 0.094648704, 0.43160871 0.1281592 0.094569698, 0.43168804 0.12816978 -0.094633058, 0.43154922 0.12816976 -0.094459161, 0.43178269 0.12816978 -0.094692722, 0.43160871 0.12816978 -0.094553933, 0.43188831 0.12816978 -0.094729766, 0.43151215 0.1281698 -0.094353542, 0.43199968 0.12816982 -0.094742134, 0.43149969 0.1281698 -0.09424226, 0.43599963 0.12816988 -0.094742313, 0.43611094 0.12816985 -0.094754741, 0.43149975 0.12816703 -0.04574953, 0.43649969 0.12816679 -0.040749624, 0.43649974 0.12816218 0.040765181, 0.43631151 0.12815922 0.094866857, 0.43639061 0.12815921 0.094946012, 0.43621668 0.12815922 0.094807342, 0.43149963 0.12666966 -0.090702876, 0.43149963 0.12666985 -0.094242498, 0.43149969 0.12666953 -0.088202938, 0.43149969 0.12666722 -0.04874973, 0.43149975 0.12666704 -0.045749709, 0.44428578 0.12666957 -0.088202819, 0.44428584 0.12666729 -0.04874973, 0.479828 0.11381413 -0.088203654, 0.47149977 0.11682571 -0.075715885, 0.47149983 0.11682412 -0.048750266, 0.47982803 0.096402913 -0.088204578, 0.47149995 0.088074014 -0.075717434, 0.46245167 0.079026237 -0.088205412, 0.47150004 0.08807385 -0.075385317, 0.43899965 0.13020256 0.089795336, 0.43899968 0.12983751 0.089423999, 0.43899962 0.13064168 0.09007512, 0.43899971 0.12956546 0.088979945, 0.43899962 0.12935874 0.088536724, 0.43899968 0.13113248 0.090249047, 0.43899962 0.12923987 0.088224158, 0.43899956 0.14251038 -0.0885479, 0.43899962 0.14227431 -0.089020118, 0.43899956 0.1426442 -0.088219002, 0.43899968 0.14272578 -0.087873295, 0.43899953 0.14275314 -0.087519422, 0.43899959 0.14021729 -0.090291604, 0.4389998 0.13166 -0.090292081, 0.43899968 0.12916747 0.087897763, 0.43899962 0.14072238 -0.090235457, 0.43899962 0.14120284 -0.090069696, 0.43899962 0.14163506 -0.089802459, 0.43899956 0.1419982 -0.089446798, 0.43899959 0.14274326 0.087536469, 0.43899965 0.13164999 0.090308055, 0.43899962 0.12914328 0.087564543, 0.43899962 0.14020708 0.090308502, 0.43899956 0.14071223 0.090252414, 0.43899968 0.14119269 0.090086564, 0.43899962 0.14162503 0.089819536, 0.43899953 0.14198817 0.089463994, 0.43899962 0.14226435 0.089037165, 0.43899959 0.14250037 0.088564947, 0.43899962 0.1426342 0.088236079, 0.43899956 0.14271583 0.08789061, 0.43899962 0.12915315 -0.087548897, 0.43899962 0.12917747 -0.087882146, 0.43899968 0.12924984 -0.088208422, 0.43899968 0.12936865 -0.08852084, 0.43899968 0.12957551 -0.088964209, 0.43899968 0.12984756 -0.089408144, 0.43899968 0.13021259 -0.089779601, 0.4389998 0.13065185 -0.090059415, 0.43899971 0.1311426 -0.090233073, 0.48699975 0.12649071 -0.1496426, 0.48699966 0.12577519 -0.1654924, 0.48699984 0.11122262 -0.13428916, 0.48699984 0.11122164 -0.11690302, 0.45099956 0.14517005 -0.096996501, 0.42810974 0.0029469728 0.035936937, 0.42810979 0.002948314 0.011321977, 0.42972746 0.0021590441 0.013122067, 0.42972746 0.002157867 0.034136608, 0.42810968 0.0029509366 -0.035935298, 0.42972752 0.0021616668 -0.034135357, 0.42972746 0.0021605194 -0.013120636, 0.42810974 0.0029495955 -0.011320576, 0.46196154 0.078787833 -0.070995167, 0.46710449 0.078787684 -0.068968549, 0.46710446 0.078787997 -0.075014845, 0.46154132 0.078788042 -0.075696662, 0.46221417 0.078788713 -0.088205561, 0.46221408 0.078788772 -0.088542178, 0.45721403 0.078788698 -0.08766602, 0.45721415 0.078788713 -0.088205412, 0.46962354 0.083951607 -0.063803986, 0.46962354 0.083950728 -0.048752055, 0.47149989 0.087797508 -0.048751935, 0.47150007 0.087798834 -0.075014278, 0.42052406 -0.016705737 -0.034136549, 0.42052403 -0.016706914 -0.013121709, 0.49149975 0.10807583 -0.10570504, 0.4814955 0.098070338 -0.090704456, 0.46221417 0.078789309 -0.099305287, 0.46221414 0.078788817 -0.090705529, 0.48773697 0.11095408 -0.10006253, 0.49149981 0.11095448 -0.10570489, 0.48149541 0.11321117 -0.090703622, 0.48773691 0.11095597 -0.13371731, 0.49149978 0.11095612 -0.13371731, 0.49149969 0.12577526 -0.16549258, 0.44428572 0.12666973 -0.090702906, 0.41891721 -0.015894026 -0.035936341, 0.41891721 -0.015892714 -0.058579132, 0.41891721 -0.015895352 -0.011321679, 0.41891721 -0.015896693 0.011320844, 0.41266307 0.026954085 -0.10710703, 0.4126631 0.02395393 -0.10592304, 0.41245589 -0.012626946 -0.09148483, 0.4117088 -0.014490336 -0.090749249, 0.43004301 0.14516978 -0.094896749, 0.43016985 0.14516969 -0.094924703, 0.43022564 0.14516976 -0.094958678, 0.43010798 0.14516975 -0.094903722, 0.43033287 0.14516976 -0.095118865, 0.42989305 0.14516978 -0.094936863, 0.43639049 0.14516985 -0.094929501, 0.42999098 0.14516976 -0.094901249, 0.42994043 0.14516976 -0.09491469, 0.43631142 0.14516982 -0.094850346, 0.4362165 0.14516981 -0.094790742, 0.42874947 0.1451699 -0.095596865, 0.43644997 0.14516987 -0.095024392, 0.43648705 0.14516984 -0.095130011, 0.42854285 0.14516976 -0.095826641, 0.42859504 0.14516979 -0.095736042, 0.42866501 0.14516982 -0.095658466, 0.42851052 0.14516981 -0.095926091, 0.43649957 0.14516985 -0.095241204, 0.43648711 0.14516982 -0.095352575, 0.43611082 0.1451699 -0.09572871, 0.43645006 0.14516988 -0.095458284, 0.43639049 0.14516985 -0.095553055, 0.43611082 0.14516982 -0.094753757, 0.4359996 0.14516978 -0.09474127, 0.43631142 0.14516982 -0.09563221, 0.43621656 0.14516987 -0.095691845, 0.43199968 0.14516979 -0.09474127, 0.43151218 0.14516979 -0.094352469, 0.43188831 0.14516975 -0.094728723, 0.43178263 0.14516978 -0.094691679, 0.4315491 0.14516976 -0.094458237, 0.43168786 0.14516975 -0.094632283, 0.43160865 0.14516978 -0.094553038, 0.43027291 0.14516975 -0.095003769, 0.43030918 0.14516979 -0.095058009, 0.43033299 0.12666985 -0.095120087, 0.43030927 0.12666979 -0.095059171, 0.43027297 0.12666978 -0.095004842, 0.43022582 0.12666987 -0.094959661, 0.43017003 0.12666981 -0.094925776, 0.43010813 0.12666975 -0.094904765, 0.43004313 0.12666984 -0.094897792, 0.43631145 0.12666988 -0.095633194, 0.43639061 0.12666988 -0.095554069, 0.43621668 0.12666996 -0.095692918, 0.43645015 0.12666991 -0.095459357, 0.43611088 0.12666987 -0.095729753, 0.43648717 0.12666987 -0.095353648, 0.42989317 0.12666984 -0.094937935, 0.4299911 0.12666985 -0.094902292, 0.42994055 0.12666982 -0.094915763, 0.43649969 0.12666987 -0.095242396, 0.42874971 0.12666984 -0.095598027, 0.43648717 0.12666982 -0.095131204, 0.42851058 0.12666993 -0.095927164, 0.43645015 0.12666982 -0.095025584, 0.42866513 0.12666984 -0.095659509, 0.42859527 0.12666976 -0.095737115, 0.428543 0.12666982 -0.095827624, 0.43199965 0.12666987 -0.094742343, 0.43599972 0.12666982 -0.094742492, 0.43639061 0.12666987 -0.094930574, 0.436111 0.12666988 -0.094754949, 0.43631145 0.12666976 -0.094851568, 0.43621656 0.1266699 -0.094791815, 0.43168789 0.12666985 -0.094633415, 0.43178281 0.12666981 -0.094692871, 0.43188849 0.12666985 -0.094729766, 0.43154928 0.12666975 -0.094459429, 0.43160871 0.12666985 -0.094554111, 0.43151221 0.12666985 -0.094353601, 0.45782813 0.083720163 -0.05491893, 0.45758516 0.083222091 -0.054599062, 0.47199947 0.15333672 -0.1334336, 0.47199956 0.15133679 -0.13407938, 0.47199956 0.15298212 -0.13493602, 0.47199956 0.15098208 -0.13558193, 0.41228887 0.081950828 -0.048752293, 0.41228881 0.081950724 -0.045752332, 0.47150007 0.087797284 -0.045751885, 0.46512973 0.086142644 -0.045751974, 0.46962354 0.083950564 -0.045752123, 0.46649995 0.091037437 -0.045751736, 0.45849738 0.083950922 -0.045752004, 0.46162161 0.078950897 -0.045752332, 0.46282795 0.092828676 -0.045751557, 0.44100001 0.078950718 -0.045752361, 0.44100001 0.083950758 -0.045752123, 0.47149977 0.11682394 -0.045750305, 0.46649978 0.11331546 -0.045750335, 0.43900007 0.083950743 -0.045752123, 0.41858995 0.083950713 -0.045752123, 0.43900004 0.078950763 -0.045752361, 0.41300002 0.078950599 -0.045752361, 0.41299996 0.081950635 -0.045752332, 0.4470506 0.12566711 -0.045749739, 0.43592533 0.12430161 -0.045749858, 0.43149969 0.1256671 -0.045749739, 0.4129999 0.078945413 0.045762196, 0.43900004 0.078945547 0.045762345, 0.46649978 0.11331028 0.045764223, 0.4470506 0.12566194 0.045764908, 0.47149977 0.11681882 0.045764461, 0.47150001 0.087792128 0.045762882, 0.46650001 0.091032192 0.045762941, 0.46962357 0.083945453 0.045762435, 0.46512967 0.086137474 0.045762792, 0.46282795 0.092823461 0.045763031, 0.45849738 0.083945736 0.045762643, 0.46162167 0.078945696 0.045762196, 0.44100001 0.078945622 0.045762345, 0.44100001 0.083945528 0.045762643, 0.41858989 0.083945498 0.045762643, 0.43899992 0.083945647 0.045762643, 0.43592528 0.1242965 0.045764908, 0.43149969 0.12566189 0.045764908, 0.41228881 0.081945449 0.045762345, 0.43149975 0.12666188 0.045764908, 0.41300002 0.081945449 0.045762435, 0.4364998 0.12566666 -0.040749833, 0.43649974 0.1256621 0.040764973, 0.41858992 0.083950803 -0.048752174, 0.4359253 0.12430176 -0.048749909, 0.45849741 0.083945572 0.048762783, 0.41858992 0.083945394 0.048762605, 0.45849738 0.083951041 -0.048752174, 0.46282795 0.092828766 -0.048751578, 0.46649989 0.091037601 -0.048751757, 0.46649978 0.11331566 -0.048750505, 0.4129999 0.081950828 -0.048752174, 0.41266316 0.026953712 -0.10175, 0.4126631 0.023953632 -0.10175021, 0.43614814 0.023952454 -0.075998172, 0.43125603 0.023952127 -0.072998241, 0.43125603 0.023952395 -0.075998172, 0.43270043 0.023952872 -0.085534915, 0.41300032 0.023952037 -0.070998177, 0.43125591 0.026952192 -0.072997913, 0.43125597 0.026952386 -0.075997964, 0.43614811 0.026952475 -0.075997964, 0.43270048 0.026952922 -0.085534647, 0.4130002 0.026952103 -0.070998028, 0.42760107 0.1458627 -0.13593651, 0.42630079 0.14586265 -0.13518853, 0.42776635 0.14600641 -0.13564904, 0.4264662 0.14600638 -0.13490106, 0.46154132 0.076787919 -0.075696662, 0.45721415 0.076788634 -0.087666109, 0.45721412 0.076789305 -0.098036245, 0.44972476 0.076789975 -0.11183889, 0.41220835 0.076790661 -0.1269965, 0.41220847 0.07879056 -0.12699638, 0.45721421 0.078788787 -0.090705529, 0.45721403 0.078789264 -0.098036215, 0.44972473 0.078789935 -0.11183868, 0.4764953 0.11039485 -0.090703741, 0.4764953 0.11039472 -0.088203803, 0.47649541 0.098070294 -0.090704456, 0.4764953 0.098070323 -0.088204488, 0.4613739 0.15694417 0.072509304, 0.46143958 0.1569443 0.073093638, 0.46211332 0.1569443 0.072738364, 0.46211341 0.1569442 0.072280452, 0.46222302 0.15694429 0.071835741, 0.4613739 0.15695237 -0.072490588, 0.46243593 0.1569443 0.071430042, 0.46273962 0.15694429 0.071087256, 0.46399948 0.15695255 -0.075116381, 0.46458384 0.15695252 -0.075050548, 0.4652594 0.15694432 0.07393153, 0.46563655 0.15694414 0.074562296, 0.46605238 0.1569443 0.074146375, 0.46525937 0.15695237 -0.07106851, 0.46488252 0.15694438 0.070827082, 0.46525946 0.15694435 0.071087524, 0.46556315 0.1569443 0.073588952, 0.46636519 0.1569443 0.073648795, 0.46662524 0.15695249 -0.072490588, 0.46556312 0.15695249 -0.071411327, 0.46662524 0.1569443 0.072509393, 0.46488237 0.15695237 -0.070808157, 0.4648824 0.15694419 0.074191913, 0.46513882 0.1569441 0.074875101, 0.46341518 0.15695253 -0.075050458, 0.46143958 0.15695256 -0.073074922, 0.46577606 0.15695246 -0.071816847, 0.465776 0.15694432 0.073183253, 0.4665595 0.15694425 0.073093638, 0.4644542 0.15695229 -0.070645824, 0.46445432 0.15694429 0.070664629, 0.46399957 0.15694441 0.070609435, 0.46286026 0.15695255 -0.074856296, 0.46445417 0.15694408 0.074354157, 0.46458372 0.15694411 0.075069413, 0.46163383 0.15695249 -0.073629931, 0.46588567 0.1569442 0.072738513, 0.46588567 0.15695241 -0.072261766, 0.46236238 0.15695255 -0.074543431, 0.4619467 0.15695257 -0.074127778, 0.46399945 0.15694407 0.074409559, 0.46341524 0.15694407 0.075069413, 0.46399945 0.15694407 0.075135335, 0.46588573 0.1569524 -0.072719648, 0.46655944 0.15695253 -0.073075041, 0.46588564 0.15694432 0.072280452, 0.46354482 0.1569443 0.070664629, 0.46354476 0.15694417 0.074354157, 0.46311656 0.15694435 0.070827082, 0.46286026 0.1569441 0.074875101, 0.46577606 0.1569443 0.071835831, 0.465776 0.15695253 -0.073164299, 0.46636519 0.15695246 -0.073629931, 0.4631165 0.15694429 0.074191764, 0.46556315 0.1569443 0.071430042, 0.46556315 0.15695256 -0.073570028, 0.46236244 0.15694408 0.074562386, 0.46605244 0.15695255 -0.074127778, 0.46273962 0.15694419 0.07393153, 0.4619467 0.15694423 0.074146375, 0.46525952 0.15695257 -0.073912814, 0.46563664 0.15695257 -0.07454358, 0.46243587 0.15694417 0.073588803, 0.46488252 0.15695253 -0.074173048, 0.46163389 0.15694417 0.073648646, 0.46222302 0.15694429 0.073183164, 0.46513882 0.15695253 -0.074856386, 0.4644542 0.15695252 -0.074335441, 0.46614215 0.15696712 0.07421802, 0.46646869 0.15696715 0.073698625, 0.4660981 0.15695009 0.074182972, 0.46641794 0.15695009 0.073674187, 0.46661648 0.15695015 0.073106721, 0.46668378 0.15695009 0.072509304, 0.46399948 0.15694992 0.075193599, 0.46655634 0.15703216 0.073740795, 0.46651545 0.15699489 0.073721036, 0.4662182 0.15703204 0.074278817, 0.46618274 0.15699479 0.074250475, 0.46667138 0.15696724 0.073119268, 0.4667401 0.15696719 0.072509304, 0.46672192 0.15699495 0.073130682, 0.46679196 0.15699491 0.072509304, 0.46676621 0.1570323 0.073140994, 0.46683744 0.15703227 0.072509393, 0.46459684 0.15694989 0.075126484, 0.46399942 0.15696707 0.075249746, 0.46460935 0.15696701 0.07518135, 0.46516421 0.15694991 0.074928001, 0.46463099 0.1570321 0.075276151, 0.4646208 0.15699473 0.075232074, 0.46399948 0.15703201 0.07534726, 0.46399948 0.15699469 0.075301781, 0.46518859 0.15696697 0.074978605, 0.46567312 0.15694997 0.074608132, 0.46523079 0.15703201 0.075066403, 0.46521106 0.15699473 0.075025275, 0.46570817 0.15696701 0.07465221, 0.46576884 0.15703209 0.074728206, 0.46574053 0.15699479 0.074692562, 0.46438953 0.15677455 0.070926979, 0.46477357 0.15683135 0.071034625, 0.464398 0.1568314 0.070892319, 0.46561733 0.15677446 0.072313026, 0.46565282 0.15683137 0.072710082, 0.46565282 0.15683137 0.072308525, 0.46474653 0.15671103 0.073932722, 0.46438947 0.15677449 0.074091777, 0.46475676 0.15677455 0.073952273, 0.4643842 0.15671121 0.070948556, 0.46399957 0.1567746 0.070879683, 0.46399954 0.15671112 0.070901737, 0.46438232 0.15664424 0.074062839, 0.46438411 0.15671106 0.074070081, 0.46438238 0.15664431 0.070955858, 0.46508017 0.15677449 0.073729232, 0.46477345 0.15683135 0.073984191, 0.46474305 0.15664436 0.071092591, 0.46474656 0.15671107 0.071086034, 0.46475688 0.1567746 0.071066365, 0.46561742 0.15677446 0.07270588, 0.46555677 0.15683135 0.071918741, 0.46569994 0.15687883 0.072302952, 0.46560112 0.1568789 0.071901992, 0.46510389 0.15683134 0.073755845, 0.46537006 0.15683137 0.073455438, 0.46513537 0.15687875 0.073791668, 0.46540925 0.15687884 0.071536496, 0.46565434 0.15691465 0.071881846, 0.46540919 0.15687886 0.073482499, 0.46443829 0.1569366 0.074289426, 0.4654561 0.15691461 0.071504101, 0.46399948 0.15693654 0.074342713, 0.46560115 0.15687881 0.073117003, 0.46545604 0.15691465 0.073514685, 0.46565434 0.15691456 0.073137, 0.46517316 0.15691468 0.071184799, 0.46550825 0.15693676 0.07146807, 0.46521524 0.15693675 0.071137175, 0.46442309 0.15691455 0.074227855, 0.46399954 0.15691443 0.074279264, 0.46575639 0.15691461 0.072722659, 0.46571359 0.15693673 0.073159412, 0.46581945 0.15693673 0.072730407, 0.46485147 0.15693679 0.07088609, 0.46581942 0.15693678 0.072288588, 0.46485147 0.15693673 0.074132547, 0.46559528 0.15671113 0.072315589, 0.46506545 0.15671107 0.073712692, 0.46440944 0.15687874 0.07417275, 0.46558788 0.15664436 0.072316483, 0.46558788 0.15664436 0.072702274, 0.4650605 0.15664431 0.073707119, 0.46474299 0.15664431 0.073926166, 0.46559539 0.1567111 0.072703108, 0.46399954 0.1568789 0.074222282, 0.46552339 0.15677448 0.071931675, 0.46534076 0.15677449 0.073435143, 0.4648219 0.15691461 0.074076608, 0.46555671 0.15683137 0.073099867, 0.46521524 0.15693675 0.073881611, 0.46537015 0.1568314 0.071563318, 0.46513543 0.1568789 0.071227148, 0.4657 0.15687886 0.072715744, 0.46399948 0.15671106 0.074116901, 0.46439806 0.15683134 0.074126437, 0.46399942 0.15683135 0.074174777, 0.46482196 0.15691459 0.070942387, 0.46575645 0.15691459 0.072295979, 0.4647955 0.15687886 0.074026093, 0.46443829 0.15693673 0.07072936, 0.46571365 0.15693685 0.071859434, 0.46399954 0.15693685 0.070676193, 0.46517318 0.15691461 0.073834166, 0.46550259 0.15671107 0.071939394, 0.46532252 0.1567111 0.073422655, 0.46531627 0.15664431 0.073418245, 0.46549556 0.15664431 0.071942046, 0.46550825 0.15693672 0.073550835, 0.46534067 0.15677451 0.071583614, 0.46552339 0.15677448 0.07308732, 0.46510395 0.1568314 0.071262792, 0.46399954 0.15677445 0.074139223, 0.46479556 0.1568789 0.070992693, 0.46442303 0.15691468 0.070790991, 0.46399954 0.15691468 0.070739493, 0.46532246 0.15671106 0.07159625, 0.46531627 0.15664434 0.071600452, 0.46508017 0.15677449 0.071289405, 0.46550259 0.15671107 0.073079422, 0.46549556 0.15664434 0.0730768, 0.46440956 0.15687889 0.070846185, 0.46399948 0.15687887 0.070796475, 0.46506545 0.15671107 0.071306095, 0.46506065 0.15664436 0.071311787, 0.46399954 0.15683143 0.07084392, 0.46399954 0.15735629 0.075671479, 0.46470308 0.15735631 0.075592235, 0.46537149 0.15735631 0.075358465, 0.46597102 0.15735634 0.074981764, 0.4664717 0.15735629 0.074480966, 0.46684852 0.15735644 0.073881373, 0.46708241 0.15735652 0.073213086, 0.46716169 0.15735652 0.072509393, 0.4613826 0.15695833 -0.073087767, 0.4613153 0.15695813 -0.072490677, 0.46158114 0.15695831 -0.073655292, 0.46144262 0.15704052 -0.07372199, 0.46148369 0.15700312 -0.073702231, 0.46178076 0.15704049 -0.074259952, 0.46181628 0.15700321 -0.074231699, 0.46185687 0.15697546 -0.074199304, 0.46153024 0.15697546 -0.073679671, 0.4613277 0.1569753 -0.073100463, 0.46125904 0.15697522 -0.072490588, 0.46127716 0.15700307 -0.073112205, 0.46120712 0.157003 -0.072490677, 0.46116167 0.15704034 -0.072490677, 0.46123275 0.1570404 -0.073122129, 0.46399942 0.15704052 -0.075328544, 0.46336797 0.15704057 -0.075257406, 0.46399966 0.15700324 -0.075283155, 0.46399942 0.15695843 -0.075174883, 0.46340218 0.15695836 -0.07510753, 0.46399948 0.15697543 -0.07523118, 0.46338972 0.15697543 -0.075162396, 0.46283481 0.15695836 -0.074909195, 0.46337813 0.1570033 -0.075213149, 0.46281037 0.15697546 -0.07495977, 0.46232593 0.15695831 -0.074589208, 0.46276823 0.15704048 -0.075047389, 0.46278796 0.15700312 -0.07500647, 0.46229073 0.15697546 -0.074633256, 0.46190086 0.15695831 -0.074164256, 0.46223006 0.15704045 -0.074709401, 0.46225849 0.15700324 -0.074673817, 0.46399945 0.15736482 -0.075652823, 0.46329579 0.15736482 -0.075573459, 0.4626275 0.15736482 -0.07533969, 0.46202788 0.1573647 -0.074962839, 0.4615272 0.15736473 -0.07446219, 0.46115059 0.1573647 -0.073862508, 0.46091664 0.15736464 -0.073194221, 0.46083733 0.15736459 -0.072490588, 0.46529233 0.1494523 -0.069783911, 0.46458051 0.14945248 -0.071384326, 0.46585849 0.14945236 -0.070136443, 0.46429875 0.1494524 -0.071277454, 0.46482858 0.14945252 -0.073426798, 0.46585861 0.1494526 -0.074845627, 0.46633276 0.14945257 -0.074376777, 0.46502832 0.1494526 -0.073201194, 0.462971 0.14945248 -0.073201194, 0.46283075 0.14945251 -0.072934404, 0.46458045 0.1494526 -0.073597983, 0.46529239 0.14945261 -0.075198188, 0.46516833 0.14945251 -0.072934344, 0.46429861 0.1494526 -0.073704794, 0.46466228 0.1494527 -0.075416878, 0.46466234 0.1494523 -0.069565162, 0.4639996 0.1494524 -0.071240947, 0.46275872 0.14945242 -0.072641924, 0.46524039 0.14945248 -0.072641924, 0.46399966 0.14945254 -0.073741093, 0.46275872 0.14945242 -0.072340474, 0.46524039 0.14945248 -0.072340474, 0.46370047 0.14945254 -0.073704734, 0.46370041 0.14945248 -0.071277454, 0.46283084 0.14945248 -0.072047815, 0.46297088 0.1494524 -0.071781054, 0.4651683 0.14945242 -0.072047815, 0.46341869 0.14945252 -0.073597983, 0.46341869 0.14945237 -0.071384326, 0.46317062 0.14945237 -0.071555451, 0.46502832 0.1494524 -0.071781054, 0.46633276 0.1494524 -0.070605263, 0.46317071 0.1494526 -0.073426798, 0.46482846 0.1494524 -0.071555451, 0.46429867 0.15315244 -0.071277276, 0.46458045 0.15315239 -0.071384057, 0.4648284 0.15315251 -0.071555272, 0.46502826 0.1531525 -0.071780816, 0.46516833 0.15315244 -0.072047576, 0.46524027 0.15315256 -0.072340325, 0.46524027 0.15315256 -0.072641596, 0.46516833 0.15315247 -0.072934017, 0.46502823 0.15315256 -0.073201135, 0.4648284 0.1531526 -0.0734265, 0.46458039 0.15315254 -0.073597655, 0.46429867 0.15315248 -0.073704526, 0.48137376 0.15248361 -0.14402713, 0.48145005 0.15276453 -0.143465, 0.4866254 0.14006549 -0.16886689, 0.48445424 0.15165873 -0.14567722, 0.4848825 0.15173136 -0.14553191, 0.48525947 0.15184763 -0.14529915, 0.48662531 0.15248361 -0.14402713, 0.48137382 0.13974306 -0.16951181, 0.48525962 0.15311944 -0.14275499, 0.48549113 0.15344992 -0.14209421, 0.48596504 0.15326217 -0.14246972, 0.48556325 0.15296622 -0.14306168, 0.48632452 0.15302934 -0.14293571, 0.4848825 0.1532359 -0.1425222, 0.48493075 0.15358132 -0.14183117, 0.48577619 0.15278482 -0.1434245, 0.48654899 0.15276457 -0.143465, 0.48445424 0.15330851 -0.14237709, 0.48431599 0.15364918 -0.14169557, 0.48588574 0.15258601 -0.14382239, 0.48368293 0.15364924 -0.14169563, 0.48588568 0.15238115 -0.14423202, 0.48306838 0.15358147 -0.14183117, 0.48577604 0.15218234 -0.14462973, 0.48250803 0.15344986 -0.14209421, 0.48556325 0.15200092 -0.14499258, 0.48203406 0.1532622 -0.14246972, 0.48167461 0.15302928 -0.14293571, 0.48283079 0.1460243 -0.14129339, 0.4827587 0.14615507 -0.14103173, 0.48453802 0.14719936 -0.13894294, 0.4842988 0.14676513 -0.13981135, 0.48504525 0.14711332 -0.13911493, 0.48482847 0.14580406 -0.1417339, 0.48504516 0.14533159 -0.14267893, 0.48549166 0.14546934 -0.14240332, 0.4827587 0.14628978 -0.14076228, 0.48399964 0.14678141 -0.13977893, 0.48370036 0.14676525 -0.13981135, 0.48502836 0.14590491 -0.14153214, 0.48585126 0.14565085 -0.1420403, 0.48283085 0.14642063 -0.14050038, 0.48458043 0.14572747 -0.14188693, 0.48453808 0.14524545 -0.14285083, 0.48516831 0.14602427 -0.14129348, 0.48610333 0.14586569 -0.1416107, 0.48297089 0.14653994 -0.14026172, 0.48429868 0.14567974 -0.14198257, 0.48341855 0.14671734 -0.13990696, 0.48524049 0.1461551 -0.14103173, 0.48623326 0.14610116 -0.14113958, 0.48317066 0.14664087 -0.14006008, 0.48399952 0.14566346 -0.14201505, 0.48524049 0.14628977 -0.14076228, 0.48623323 0.14634375 -0.14065443, 0.48370039 0.1456798 -0.14198257, 0.48516831 0.14642067 -0.14050059, 0.48610339 0.14657918 -0.14018328, 0.48341861 0.14572747 -0.14188693, 0.48502836 0.14653988 -0.14026172, 0.48585135 0.14679402 -0.13975377, 0.4831706 0.14580412 -0.1417339, 0.48482856 0.14664075 -0.14006008, 0.4854916 0.14697558 -0.13939066, 0.4829708 0.14590493 -0.14153214, 0.48458058 0.14671732 -0.13990696, 0.48429874 0.14962748 -0.14124234, 0.48458043 0.14957973 -0.14133789, 0.4848285 0.14950308 -0.14149101, 0.48502836 0.14940216 -0.14169271, 0.48516825 0.14928284 -0.14193131, 0.48524049 0.14915207 -0.14219315, 0.48524043 0.14901724 -0.14246257, 0.48516837 0.14888646 -0.14272447, 0.48502836 0.1487672 -0.14296307, 0.48482856 0.14866641 -0.14316486, 0.48458046 0.14858977 -0.14331789, 0.48429883 0.14854194 -0.1434135, 0.46683726 0.15704046 -0.072490796, 0.4671616 0.15736465 -0.072490677, 0.46708241 0.15736474 -0.07319428, 0.46676618 0.15704046 -0.073122129, 0.46684858 0.15736474 -0.073862508, 0.46655628 0.15704042 -0.07372199, 0.46647188 0.1573647 -0.07446219, 0.4662182 0.15704046 -0.07426019, 0.46597108 0.15736464 -0.074962839, 0.4657689 0.15704048 -0.074709401, 0.46537152 0.15736482 -0.07533969, 0.46523085 0.15704048 -0.075047597, 0.46470317 0.15736476 -0.075573549, 0.46463105 0.15704057 -0.075257465, 0.46599939 0.15740207 -0.074998453, 0.46650741 0.15740202 -0.074490413, 0.46654794 0.1574297 -0.074522838, 0.46541366 0.15742977 -0.075427249, 0.46603176 0.15742977 -0.075038984, 0.46606687 0.15744674 -0.075083002, 0.46543822 0.15744688 -0.075477824, 0.46473739 0.15744685 -0.075723305, 0.46475038 0.15745266 -0.075780287, 0.46399954 0.15745278 -0.075864986, 0.46546349 0.15745272 -0.075530842, 0.46399948 0.15744694 -0.075806305, 0.46539125 0.15740208 -0.075380638, 0.46472487 0.15742975 -0.075668409, 0.46399948 0.15742983 -0.075749978, 0.46471325 0.15740211 -0.075617746, 0.46399939 0.15740219 -0.075698093, 0.46723214 0.15744671 -0.073228434, 0.46737376 0.15745243 -0.072490677, 0.46728918 0.15745255 -0.073241428, 0.46731517 0.15744671 -0.072490588, 0.46717724 0.15742972 -0.073215857, 0.46725896 0.15742965 -0.072490677, 0.46698698 0.1574468 -0.073929206, 0.46703961 0.15745263 -0.073954597, 0.46712664 0.15740208 -0.073204383, 0.46720704 0.15740199 -0.072490588, 0.46693611 0.1574298 -0.073904827, 0.46659198 0.1574468 -0.074558035, 0.46663758 0.15745255 -0.074594483, 0.46688947 0.15740207 -0.073882386, 0.46610335 0.15745264 -0.075128809, 0.46095946 0.15744427 0.073973313, 0.45599946 0.15744331 0.090651497, 0.46136138 0.15744419 0.074613109, 0.46070978 0.15744431 0.073260143, 0.46062535 0.15744427 0.072509304, 0.45667365 0.15745363 -0.092855081, 0.45630407 0.15745352 -0.092163518, 0.45607641 0.15745351 -0.091413125, 0.45599952 0.15745339 -0.090632811, 0.47424215 0.15745465 -0.1105323, 0.47375682 0.15745333 -0.087419614, 0.49082789 0.15745445 -0.10449059, 0.45717111 0.15745355 -0.09346129, 0.47245619 0.15745327 -0.085473135, 0.47301069 0.15745333 -0.086510405, 0.49082789 0.15744264 0.10450946, 0.49169502 0.15744264 0.1058072, 0.49132535 0.15744264 0.10511567, 0.49192271 0.15744258 0.1065575, 0.4919996 0.15744255 0.10733782, 0.47498828 0.15745483 -0.1114416, 0.47599956 0.15744199 0.11479391, 0.47599956 0.15744086 0.1345094, 0.49199948 0.15744096 0.1345094, 0.47554275 0.15745486 -0.11247884, 0.49199948 0.15745457 -0.1073191, 0.47588417 0.15744212 0.1136231, 0.47588417 0.15745494 -0.11360441, 0.47554284 0.15744214 0.11249752, 0.47199956 0.1574531 -0.083176896, 0.4759995 0.15745492 -0.11477496, 0.47498849 0.15744226 0.11146016, 0.49199966 0.15745617 -0.13449062, 0.47599956 0.157456 -0.13449065, 0.47424215 0.1574422 0.1105511, 0.47375688 0.15744346 0.08743833, 0.4606252 0.15745239 -0.072490677, 0.47199947 0.15744384 0.083195552, 0.46737376 0.15744431 0.072509304, 0.47211483 0.15745316 -0.084347561, 0.45717111 0.15744308 0.093479916, 0.47301069 0.15744363 0.086529091, 0.47245625 0.15744375 0.085491881, 0.45630398 0.15744318 0.092182264, 0.45667365 0.15744308 0.092873886, 0.45607635 0.15744321 0.09143202, 0.47211483 0.15744366 0.084366217, 0.46610329 0.15744421 0.075147524, 0.46663758 0.15744421 0.074613109, 0.46703956 0.15744431 0.073973313, 0.46546355 0.15744413 0.075549707, 0.46475032 0.15744409 0.075799063, 0.46728924 0.15744433 0.073260292, 0.49169496 0.15745451 -0.10578834, 0.49132553 0.15745451 -0.1050968, 0.46399954 0.15744413 0.07588385, 0.49192265 0.15745457 -0.10653873, 0.46324861 0.1574441 0.075799063, 0.46070978 0.15745254 -0.073241428, 0.46095952 0.15745257 -0.073954597, 0.46253541 0.15744419 0.075549558, 0.46136138 0.15745263 -0.074594483, 0.46189567 0.15745264 -0.075128809, 0.46253541 0.15745263 -0.075530842, 0.4632487 0.15745273 -0.075780287, 0.46189567 0.15744407 0.075147524, 0.46260771 0.15739363 0.075399354, 0.46262747 0.15735629 0.075358465, 0.46199957 0.1573936 0.075017169, 0.46196732 0.15742131 0.0750577, 0.46258524 0.15742134 0.075446263, 0.46327421 0.15742126 0.075687274, 0.46399954 0.15743841 0.07582508, 0.46399942 0.15742128 0.075768903, 0.46326163 0.15743835 0.075742081, 0.46256086 0.15743835 0.075496867, 0.46068385 0.15743846 0.072509304, 0.46328577 0.15739359 0.075636759, 0.46399942 0.15739362 0.075717047, 0.46329585 0.15735634 0.075592235, 0.46091676 0.15735635 0.073213086, 0.46083739 0.15735647 0.072509304, 0.46079198 0.15739368 0.072509304, 0.46076688 0.15743846 0.073247209, 0.46082178 0.1574214 0.073234871, 0.46074 0.1574214 0.072509304, 0.46101215 0.15743849 0.073947981, 0.46087238 0.15739369 0.073223308, 0.46115059 0.15735635 0.073881373, 0.46106282 0.15742141 0.073923543, 0.46140721 0.15743838 0.074576959, 0.46110955 0.15739372 0.073901132, 0.46152723 0.15735629 0.074480966, 0.46145114 0.15742125 0.074541613, 0.46193221 0.15743829 0.075101659, 0.46149173 0.15739363 0.074509308, 0.46202785 0.15735629 0.074981555, 0.46116167 0.15703216 0.072509304, 0.41194519 -0.033615977 -0.01054661, 0.41192892 -0.033668458 -0.010598972, 0.41191655 -0.03376022 -0.010690764, 0.41192678 -0.03384462 -0.010775074, 0.41195819 -0.033917338 -0.010847792, 0.41261318 -0.03496553 -0.011896357, 0.43236682 0.0049244463 -0.012159422, 0.43221536 0.0048551857 -0.012054071, 0.4320721 0.0047715157 -0.011961684, 0.43262038 0.0050037652 -0.012352809, 0.43012366 0.0034607351 -0.010785326, 0.43023935 0.0035796762 -0.010836884, 0.43012667 0.0036346167 -0.010711715, 0.43009019 0.0032887757 -0.010830626, 0.43002781 0.0031265467 -0.010845885, 0.41284385 -0.035226732 -0.012218043, 0.41274413 -0.035134107 -0.012087926, 0.41295633 -0.035308331 -0.012354955, 0.43018743 0.0036050081 -0.010787353, 0.43015209 0.0036222935 -0.010760978, 0.43011549 0.0036401153 -0.010739222, 0.4300448 0.0036745071 -0.010605291, 0.42997035 0.0037108064 -0.010475889, 0.43023926 0.0035758466 0.058095858, 0.4301267 0.0036307573 0.057970718, 0.43018749 0.0036010742 0.058046237, 0.43015209 0.0036183298 0.058019891, 0.43011555 0.0036361814 0.057997987, 0.4300448 0.0036706626 0.057864144, 0.42997035 0.0037069619 0.057734862, 0.42723942 0.0050385743 0.067500725, 0.42983511 0.003772974 0.057391122, 0.42966601 0.0038555861 0.056750968, 0.43017355 0.0036132336 -0.036479607, 0.43012667 0.0036360472 -0.036544219, 0.43011546 0.003641516 -0.036516711, 0.43020764 0.0035966039 -0.036450997, 0.43023929 0.0035811663 -0.03641881, 0.42966607 0.003856644 0.037765309, 0.4299961 0.0036998093 -0.036731169, 0.42983511 0.0037768483 -0.010132149, 0.4298012 0.0037948787 -0.037235662, 0.42966613 0.0038592964 -0.0094921142, 0.42966613 0.0038608164 -0.037763759, 0.43023929 0.0035769045 0.03642045, 0.43020776 0.0035924166 0.036452487, 0.43012676 0.0036318749 0.036545679, 0.43017361 0.0036089718 0.036481187, 0.43011555 0.0036374032 0.03651832, 0.42999622 0.0036955774 0.036732838, 0.43023935 0.0035823286 -0.058094397, 0.43018749 0.0036076307 -0.058044717, 0.43012673 0.0036372989 -0.057969227, 0.43015209 0.0036249161 -0.058018461, 0.43004474 0.0036772639 -0.057862654, 0.43011552 0.0036426783 -0.057996526, 0.42997041 0.0037134886 -0.057733342, 0.43011549 0.0036389232 0.010740593, 0.43023929 0.0035784245 0.010838524, 0.4301267 0.0036334991 0.010713086, 0.43018755 0.0036036968 0.010788783, 0.43015209 0.0036210716 0.010762468, 0.4300448 0.0036732852 0.010606781, 0.42966619 0.0038618296 -0.056749478, 0.42723942 0.0050462335 -0.067499146, 0.42983517 0.0037794113 -0.057389423, 0.42997035 0.0037096441 0.010477319, 0.43011537 0.0036432594 -0.067499354, 0.42966619 0.0038581789 0.0094936043, 0.43011543 0.0036357045 0.067500934, 0.4298352 0.0037756562 0.010133639, 0.4298012 0.0037907064 0.037237003, 0.42974564 0.0038070083 0.056936696, 0.42981303 0.0037476569 0.037405595, 0.42981711 0.0037422478 0.057121947, 0.42988893 0.0036397874 0.057340458, 0.42991343 0.0035870075 0.037084147, 0.42993277 0.0035242438 0.057520792, 0.4299387 0.0034970343 0.036959901, 0.42994693 0.0034060031 0.057650045, 0.42994705 0.0034070909 0.036866531, 0.43230537 0.0048998743 -0.035140052, 0.43246055 0.0049603134 -0.035026893, 0.43207207 0.004772827 -0.035294071, 0.43262038 0.0050050169 -0.034902945, 0.43012372 0.0034622252 -0.036470667, 0.43009028 0.0032902062 -0.036425248, 0.43002781 0.0031279773 -0.036410227, 0.41261324 -0.034964249 -0.035364047, 0.41295639 -0.035307094 -0.03490521, 0.41276291 -0.035152182 -0.035146967, 0.41195816 -0.033915803 -0.036412135, 0.41274413 -0.035131484 -0.059345171, 0.41284388 -0.035224006 -0.059475496, 0.41261312 -0.034962848 -0.059153631, 0.41295639 -0.035305709 -0.059612289, 0.41195816 -0.033914611 -0.058105156, 0.43002793 0.0031291842 -0.058103159, 0.43012378 0.0034633726 -0.05804269, 0.43009028 0.0032913983 -0.058088079, 0.43242702 0.0050050318 -0.059437022, 0.43268743 0.0051437616 -0.059610203, 0.46483836 0.082117781 0.064607278, 0.46552947 0.083534792 0.063741699, 0.46450207 0.081428349 0.065848097, 0.46313792 0.078631446 0.068040833, 0.46375564 0.079898238 0.067378029, 0.46296808 0.078283548 0.068992689, 0.46504685 0.082545355 0.063228384, 0.46565238 0.083786756 0.063431039, 0.46574426 0.083975017 0.063068524, 0.4624691 0.07726045 0.068354622, 0.46259391 0.077516302 0.069445476, 0.46238214 0.077081949 0.069504932, 0.46279314 0.077924937 0.06927152, 0.46511757 0.08269015 0.061778739, 0.46580103 0.084091395 0.062670663, 0.46582028 0.084130764 0.062254354, 0.46178672 0.075861558 0.068302527, 0.46503335 0.082518056 0.060199335, 0.46112865 0.074512497 0.067886963, 0.46478614 0.082010984 0.058711454, 0.4623386 0.076994002 0.052444294, 0.46187514 0.07604377 0.05522652, 0.46119797 0.07465525 0.055607274, 0.46257278 0.077473789 0.05522652, 0.46247822 0.07728003 0.052101687, 0.46325007 0.078862205 0.055607542, 0.46058029 0.073388964 0.05634658, 0.46258754 0.077504352 0.05170618, 0.46386763 0.080128476 0.056346819, 0.46269587 0.077726215 0.05067654, 0.46438983 0.081198722 0.057402149, 0.45559314 0.063164666 0.066272005, 0.45941442 0.070999086 0.06019865, 0.45933029 0.07082653 0.061778143, 0.45966187 0.071506217 0.05871065, 0.46002868 0.072257847 0.066078052, 0.46053153 0.073288694 0.067131534, 0.45964813 0.071477771 0.064784989, 0.45941094 0.070991561 0.063324675, 0.4553698 0.062706754 0.066633448, 0.45510647 0.062167078 0.066882566, 0.45491916 0.06178315 0.066974267, 0.4547309 0.061396822 0.067004189, 0.4281162 0.0068361014 0.069501027, 0.4293209 0.009305656 0.067001119, 0.42906922 0.0087897182 0.066947207, 0.42881316 0.0082648546 0.066774145, 0.42857319 0.0077727437 0.066475883, 0.42773581 0.0060561448 0.069302931, 0.4275696 0.0057153106 0.069064632, 0.42792127 0.0064360201 0.06945087, 0.42743072 0.0054307133 0.068747774, 0.42732623 0.0052166283 0.068368748, 0.42726141 0.0050836354 0.067945972, 0.42837018 0.0073565692 0.066066489, 0.42822042 0.0070498884 0.065578237, 0.42813179 0.0068678409 0.065054491, 0.42810866 0.0068208873 0.064774022, 0.42810136 0.0068059266 0.064500913, 0.46269581 0.077731892 -0.050666586, 0.46386775 0.080134779 -0.056336924, 0.46438983 0.081205219 -0.057391897, 0.46258765 0.077510044 -0.051696405, 0.46478599 0.082017735 -0.058701292, 0.46325007 0.078868464 -0.055597439, 0.46247807 0.077285975 -0.05209206, 0.46582016 0.084137797 -0.062243775, 0.46503344 0.082524791 -0.060188964, 0.46257272 0.077480048 -0.055216834, 0.4623386 0.076999858 -0.052434549, 0.46511748 0.082697228 -0.061768368, 0.46574432 0.083982155 -0.063058212, 0.46580103 0.084098518 -0.062660083, 0.46187517 0.076050028 -0.055216864, 0.46504685 0.082552478 -0.063218072, 0.46552938 0.083542004 -0.063731387, 0.4656525 0.083793804 -0.063420519, 0.46119782 0.074661538 -0.055597678, 0.4648383 0.082125008 -0.064596906, 0.46058017 0.073395371 -0.056337133, 0.46450207 0.0814358 -0.065837726, 0.46296808 0.078291282 -0.068982467, 0.4637557 0.079905719 -0.067368105, 0.46313784 0.078639105 -0.068030909, 0.46246907 0.077268168 -0.068344936, 0.46279317 0.077932745 -0.069261536, 0.46259391 0.07752414 -0.069435909, 0.46238193 0.077089831 -0.069495156, 0.46178675 0.075869232 -0.06829305, 0.46112853 0.074520275 -0.067877725, 0.45559317 0.063172087 -0.06626375, 0.46053153 0.073296294 -0.067122295, 0.46002868 0.072265372 -0.066068962, 0.45964816 0.071485087 -0.06477578, 0.459411 0.070998684 -0.063315585, 0.45933038 0.070833445 -0.061769024, 0.45941451 0.071005702 -0.06018956, 0.45966187 0.071512848 -0.058701888, 0.4553698 0.062714204 -0.066625312, 0.45510659 0.062174618 -0.06687437, 0.45491925 0.06179069 -0.066966012, 0.4547309 0.061404452 -0.066995963, 0.4281013 0.0068131536 -0.064499125, 0.42857304 0.007780239 -0.066473916, 0.42837015 0.0073640347 -0.066064551, 0.42822045 0.0070572644 -0.0655763, 0.42813158 0.0068752617 -0.065052614, 0.42810866 0.0068281442 -0.064772084, 0.42811623 0.0068439245 -0.06949921, 0.42906913 0.0087973028 -0.06694518, 0.42881313 0.0082724392 -0.066772059, 0.4293209 0.0093132257 -0.066998944, 0.42726138 0.0050912499 -0.067944273, 0.42792124 0.0064438283 -0.069449052, 0.42732629 0.0052242279 -0.06836696, 0.42773587 0.0060639232 -0.069301203, 0.42743084 0.0054383576 -0.068746194, 0.4275696 0.0057231337 -0.069062904, 0.46005812 0.072325066 -0.057392314, 0.46005812 0.072318539 0.057401583, 0.46114835 0.074802533 0.055898622, 0.46055993 0.073595971 0.056603149, 0.46058977 0.07352154 0.056525066, 0.46118703 0.074746236 0.05580993, 0.45945063 0.071101546 0.060225263, 0.46360105 0.080011427 0.056668565, 0.46302009 0.078820214 0.055972949, 0.4631035 0.078810722 0.055898979, 0.4642742 0.081074432 0.057546034, 0.46376908 0.080039427 0.056525514, 0.46382862 0.080077112 0.056438401, 0.46186987 0.076061264 0.055337146, 0.45936796 0.070931971 0.061778203, 0.46434194 0.081129387 0.05747582, 0.45946226 0.071210057 0.060250595, 0.45938104 0.071043193 0.061778083, 0.46120393 0.074696273 0.055711195, 0.46035215 0.073808432 0.05674772, 0.46025535 0.073863536 0.056758061, 0.4597728 0.072874099 0.057733074, 0.4598687 0.072816819 0.057724878, 0.45995158 0.072745577 0.057700381, 0.46043807 0.07374306 0.056717202, 0.46350107 0.080022618 0.056717589, 0.46292558 0.078842774 0.056028679, 0.46108946 0.074862346 0.05597277, 0.46050844 0.073671117 0.056668356, 0.4594492 0.07131882 0.060273305, 0.45936903 0.071154505 0.061778083, 0.4641895 0.081036806 0.057608768, 0.46184218 0.07608895 0.05544205, 0.45969373 0.071600139 0.058762684, 0.46369198 0.08001712 0.056603447, 0.46473157 0.081927985 0.058763221, 0.45941165 0.071422681 0.06029214, 0.45933267 0.071260244 0.061778143, 0.46101353 0.074922904 0.05602859, 0.46339694 0.080049962 0.056748107, 0.46329376 0.080092356 0.056758389, 0.46272281 0.078922093 0.056075111, 0.46282479 0.078877345 0.05606325, 0.45970163 0.071700439 0.058811858, 0.46179354 0.076125279 0.055535987, 0.4640924 0.081018209 0.057661369, 0.46255568 0.077467173 0.055337146, 0.45935184 0.071516171 0.060306445, 0.45927343 0.071355462 0.061778143, 0.46465737 0.081860095 0.058812305, 0.45968476 0.07180205 0.058855817, 0.4609243 0.074981079 0.05606313, 0.46082628 0.075033844 0.056074813, 0.46172667 0.076168627 0.055614635, 0.46008322 0.072398871 0.057475254, 0.46398762 0.08101961 0.057700947, 0.46251673 0.077471986 0.05544205, 0.46456698 0.081810743 0.058856413, 0.45927262 0.071594834 0.060315326, 0.45917794 0.071654573 0.060318187, 0.45910028 0.071495086 0.061778143, 0.45919469 0.071435064 0.061778083, 0.46497476 0.082426459 0.060225859, 0.45964447 0.071899697 0.058892623, 0.46505755 0.082595691 0.061778739, 0.46164465 0.076216549 0.055673704, 0.46388036 0.081041157 0.057725355, 0.46377638 0.08108148 0.0577337, 0.46245816 0.077487797 0.055536076, 0.46008486 0.072486177 0.057545379, 0.46446508 0.08178246 0.058893278, 0.46322152 0.078832299 0.055711642, 0.45958242 0.071988717 0.058920339, 0.46489662 0.082350463 0.060251161, 0.46497786 0.082516968 0.06177865, 0.46155161 0.076267049 0.05571048, 0.46145228 0.076317102 0.055722997, 0.46006235 0.072576016 0.057608321, 0.46238288 0.077514008 0.055614695, 0.46059671 0.07345134 0.056437925, 0.46435681 0.081776619 0.058920905, 0.46317181 0.078814819 0.055810288, 0.46480271 0.082293823 0.060273901, 0.46488285 0.082457781 0.061778739, 0.45950171 0.072064459 0.058937564, 0.45940647 0.072123274 0.058943376, 0.46229449 0.077549055 0.055673704, 0.46001717 0.072664037 0.057660773, 0.46424749 0.081793457 0.058938071, 0.46414259 0.081832319 0.058943942, 0.46469787 0.082259372 0.060292885, 0.46477702 0.082421437 0.061778739, 0.46458727 0.082248986 0.06030716, 0.46466571 0.082409367 0.061778739, 0.46219751 0.077591419 0.05571048, 0.46209696 0.07763885 0.055722997, 0.46447647 0.082263067 0.060316071, 0.46455446 0.082422554 0.061778739, 0.46437123 0.082300946 0.060319021, 0.46444899 0.082460061 0.06177865, 0.46039271 0.073649526 0.066766128, 0.46094891 0.074789897 0.067470059, 0.46102434 0.074728146 0.067525283, 0.4629145 0.078602985 0.067669854, 0.46358529 0.079797715 0.067113653, 0.46299663 0.078590736 0.067744955, 0.46003446 0.072518215 0.06587483, 0.46051356 0.073500291 0.066878662, 0.46054265 0.073424369 0.066955671, 0.4624165 0.07726565 0.068138495, 0.46311116 0.078605399 0.067935213, 0.46245363 0.077257574 0.068243816, 0.46005645 0.072427467 0.06593658, 0.46306327 0.078591675 0.06783472, 0.46282104 0.07862778 0.067613259, 0.46339664 0.079808056 0.066995963, 0.46349579 0.079794705 0.067046508, 0.45968029 0.071572259 0.064734325, 0.46005446 0.072339147 0.066005483, 0.46235952 0.077284545 0.068043932, 0.46030718 0.073715299 0.066736117, 0.46021038 0.073770702 0.066725984, 0.46076223 0.074901938 0.067424193, 0.46086019 0.074848935 0.067435995, 0.46178278 0.075882241 0.068192616, 0.45998964 0.072606906 0.065823302, 0.46046272 0.073576644 0.066814646, 0.4627209 0.078663632 0.067578301, 0.46329316 0.079836696 0.066964492, 0.46261922 0.078708738 0.067566261, 0.46228534 0.077313259 0.067965224, 0.45968834 0.07167308 0.064685956, 0.4599241 0.072689027 0.065784588, 0.46319029 0.079879522 0.066953763, 0.46175656 0.075912654 0.068088129, 0.46219799 0.077350318 0.067905977, 0.45967185 0.0717749 0.064642921, 0.45944712 0.071094319 0.063298479, 0.46170935 0.075951725 0.067994311, 0.45984158 0.072760746 0.06576027, 0.46113586 0.074555889 0.067784056, 0.45974562 0.072818086 0.065752253, 0.46210158 0.077393845 0.067868933, 0.46200112 0.077441663 0.067856446, 0.45963147 0.071873069 0.064606979, 0.45945892 0.07120277 0.063273832, 0.46164349 0.075997218 0.067916051, 0.46112019 0.074608058 0.067686453, 0.4595696 0.071962237 0.06457974, 0.46156207 0.076046854 0.0678574, 0.45944571 0.071311772 0.0632516, 0.46108231 0.074666515 0.067598596, 0.45948902 0.072038203 0.064562932, 0.45939383 0.072097003 0.064557299, 0.46054879 0.073352545 0.067041263, 0.45940837 0.071415693 0.063232973, 0.46146959 0.076098263 0.067820564, 0.4613705 0.076148599 0.067808405, 0.45934853 0.071509331 0.063219056, 0.45926937 0.071587861 0.063210472, 0.45917466 0.071647644 0.063207403, 0.46371856 0.079850778 0.067283764, 0.46366087 0.079816684 0.067194089, 0.46438366 0.082326159 0.063118592, 0.45995507 0.084652126 0.061778918, 0.45987734 0.084492877 0.063238636, 0.46419093 0.08193095 0.064393088, 0.45964873 0.084024131 0.064613715, 0.46388009 0.081293866 0.065539733, 0.4592824 0.083273202 0.065823898, 0.46371546 0.080943063 0.06598781, 0.46353164 0.080557182 0.066394582, 0.4587999 0.082283884 0.066798821, 0.45822915 0.081113428 0.067482367, 0.45760307 0.079830259 0.067834124, 0.45695841 0.078508511 0.067834124, 0.45633242 0.077225298 0.067482218, 0.45576158 0.076054946 0.066798463, 0.45527893 0.075065732 0.065823302, 0.45491272 0.074315086 0.064613119, 0.45468414 0.073846385 0.06323804, 0.45460635 0.073687226 0.061778203, 0.46448904 0.082295448 -0.063111052, 0.46419084 0.081938222 -0.064382747, 0.46429583 0.081899583 -0.06438823, 0.46455446 0.082429588 -0.061768427, 0.46438363 0.082333326 -0.06310828, 0.46440551 0.081883296 -0.064403966, 0.46459976 0.082281649 -0.063119069, 0.46466559 0.082416445 -0.061768427, 0.46388021 0.081301123 -0.065529451, 0.46398449 0.081261262 -0.065537199, 0.46444896 0.082467139 -0.061768427, 0.46478301 0.082040161 -0.064549193, 0.46445245 0.08136256 -0.065769181, 0.46470785 0.081970528 -0.064503953, 0.46438274 0.081303924 -0.065703943, 0.46461678 0.081919685 -0.064463481, 0.46429661 0.081263006 -0.065645531, 0.46498802 0.082460389 -0.063193604, 0.46505752 0.082602724 -0.061768368, 0.46451429 0.081890151 -0.064429358, 0.46419802 0.081241727 -0.065596655, 0.46490961 0.082383975 -0.063170418, 0.46497789 0.082523942 -0.061768368, 0.46409222 0.081241131 -0.065559968, 0.4648155 0.082326993 -0.063149586, 0.46488285 0.082464859 -0.061768427, 0.46471044 0.082292229 -0.063132122, 0.46477702 0.08242844 -0.061768427, 0.4609243 0.074987292 -0.056053475, 0.46164465 0.076222867 -0.055664048, 0.46101353 0.074929193 -0.056018725, 0.46350107 0.080028906 -0.056707546, 0.4640924 0.081024736 -0.057651177, 0.46360108 0.08001779 -0.056658611, 0.46082628 0.075040177 -0.056065187, 0.46145216 0.07632336 -0.055713162, 0.4631035 0.078817025 -0.055888847, 0.46369198 0.080023438 -0.056593373, 0.46376911 0.08004573 -0.05651547, 0.46155152 0.076273263 -0.055700794, 0.46050841 0.07367751 -0.056658879, 0.46114835 0.074808747 -0.055889264, 0.46055976 0.073602453 -0.056593791, 0.46317181 0.078821018 -0.055800334, 0.46108943 0.074868664 -0.055963084, 0.45910028 0.07150197 -0.061769024, 0.45917794 0.071661323 -0.060309246, 0.45919478 0.071442008 -0.061769024, 0.46008489 0.072492629 -0.05753617, 0.46059668 0.073457658 -0.056428656, 0.46008334 0.072405428 -0.057466045, 0.46255565 0.077473402 -0.055327192, 0.46058974 0.073527902 -0.056515619, 0.46322152 0.078838572 -0.05570142, 0.46497479 0.082433164 -0.060215428, 0.463397 0.08005622 -0.056738034, 0.46377638 0.081088036 -0.057723418, 0.46388051 0.081047669 -0.057715073, 0.46329382 0.080098644 -0.056748286, 0.46489665 0.082357228 -0.06024079, 0.46398762 0.081026167 -0.057690635, 0.4604381 0.073749408 -0.056707904, 0.46302006 0.078826472 -0.055963084, 0.46480268 0.082300574 -0.06026347, 0.46006241 0.072582513 -0.057599083, 0.46251675 0.077478215 -0.055432096, 0.45969376 0.071606785 -0.058753386, 0.46473157 0.081934601 -0.058752939, 0.46292564 0.078848988 -0.056018665, 0.46469784 0.082266152 -0.060282424, 0.46035215 0.073814794 -0.056738511, 0.46245822 0.077494055 -0.055526122, 0.46025544 0.073869839 -0.056748644, 0.46465725 0.081866771 -0.058802173, 0.46001714 0.072670549 -0.057651564, 0.46186975 0.076067567 -0.055327281, 0.46437114 0.082307696 -0.060308471, 0.46458724 0.0822559 -0.06029667, 0.46282479 0.078883603 -0.056053296, 0.46272293 0.078928396 -0.056064859, 0.45970151 0.071707189 -0.058802769, 0.46238294 0.077520147 -0.055604741, 0.45995158 0.072752118 -0.057691023, 0.46456695 0.081817478 -0.058846131, 0.46184212 0.076095179 -0.055432215, 0.46434203 0.081135884 -0.057465598, 0.45968482 0.071808696 -0.058846727, 0.46447653 0.082269907 -0.06030558, 0.46229446 0.077555284 -0.055663958, 0.45945057 0.071108267 -0.060216084, 0.45936796 0.070938975 -0.061769024, 0.46446505 0.081789151 -0.058882967, 0.46179363 0.076131552 -0.055526391, 0.45986867 0.072823375 -0.05771549, 0.45977268 0.07288067 -0.057724014, 0.4642742 0.081080943 -0.057535782, 0.46120393 0.074702516 -0.055701777, 0.46435681 0.081783295 -0.058910623, 0.45964441 0.071906403 -0.058883384, 0.46219751 0.077597618 -0.055700615, 0.4620969 0.077645063 -0.055713162, 0.45946231 0.071216717 -0.060241386, 0.4641895 0.081043303 -0.057598636, 0.45938095 0.071050197 -0.061769113, 0.46172673 0.07617487 -0.05560495, 0.46382871 0.080083415 -0.056428328, 0.45958227 0.071995437 -0.0589111, 0.46118706 0.074752375 -0.055800483, 0.4594492 0.0713256 -0.060264125, 0.45936903 0.071161419 -0.061769024, 0.46424744 0.081800133 -0.058927789, 0.46414259 0.081839025 -0.058933631, 0.45950171 0.072071135 -0.058928326, 0.4594065 0.072129905 -0.058934107, 0.45941171 0.071429387 -0.06028302, 0.45933262 0.071267337 -0.061769024, 0.45935184 0.071523011 -0.060297236, 0.45927349 0.071362421 -0.061769024, 0.45927259 0.071601599 -0.060306385, 0.45995495 0.084659249 -0.061768249, 0.45987722 0.084499896 -0.060308471, 0.45964876 0.084031001 -0.058933422, 0.45928252 0.083280072 -0.057723209, 0.45879999 0.082290843 -0.056748226, 0.45822906 0.081120536 -0.056064859, 0.45760301 0.079837173 -0.055712983, 0.45695832 0.078515425 -0.055712983, 0.45633242 0.077232271 -0.056065097, 0.45576155 0.076061994 -0.056748644, 0.45527893 0.075072676 -0.057723656, 0.45491272 0.074321985 -0.058934018, 0.45468399 0.073853418 -0.060309038, 0.45460638 0.07369417 -0.061769024, 0.46660623 0.075029135 -0.069495216, 0.43485868 0.010171115 -0.069498911, 0.43494746 0.010127872 -0.069498852, 0.43130925 0.0052863657 -0.06949921, 0.47004446 0.082077265 -0.062244132, 0.47004446 0.082070202 0.062254205, 0.46975377 0.081481397 -0.063731506, 0.46719226 0.076230779 -0.068982705, 0.43175712 0.0059021711 -0.059666082, 0.43205091 0.006306529 -0.060422704, 0.43154329 0.0056079179 -0.059391841, 0.43193081 0.0061411411 -0.060018644, 0.43383816 0.0087666214 -0.068536714, 0.43373689 0.0086272061 -0.06818302, 0.43398556 0.0089696646 -0.0688629, 0.434174 0.0092287958 -0.069137201, 0.43439218 0.0095291883 -0.069339976, 0.43035081 0.0039665997 -0.058193192, 0.43103322 0.0049063563 -0.069445089, 0.4301475 0.0036873817 -0.067959145, 0.43012318 0.0036538243 -0.067726329, 0.43022582 0.0037952513 -0.068339124, 0.43075457 0.0045229942 -0.069270238, 0.43035325 0.0039705634 -0.06869705, 0.43052509 0.0042071044 -0.069007143, 0.4346256 0.0098503977 -0.069460377, 0.43288526 0.0058995336 -0.060422614, 0.43412355 0.0084385574 -0.06818302, 0.4313266 0.0053070039 -0.011916623, 0.43190625 0.0061045885 -0.013631448, 0.43035075 0.0039639771 -0.010935798, 0.43155742 0.0056245774 -0.012218818, 0.4317266 0.0058574677 -0.012576565, 0.43183449 0.0060058385 -0.012948498, 0.4318887 0.0060804337 -0.013289943, 0.43190619 0.0061058551 -0.033624157, 0.43187028 0.0060563236 -0.034111127, 0.43177411 0.005924046 -0.034538493, 0.43163931 0.0057385415 -0.034884587, 0.4314923 0.0055365115 -0.035138175, 0.43132657 0.0053081959 -0.035339251, 0.43035075 0.0039654076 -0.036320105, 0.43277892 0.0056789219 -0.013631597, 0.43277895 0.0056800693 -0.033624157, 0.43194911 0.0050045997 -0.035339043, 0.43194908 0.0050031841 -0.011916623, 0.43230417 0.0052366555 -0.059391841, 0.45917466 0.071654871 -0.063198313, 0.45468405 0.073853567 -0.063228682, 0.45939383 0.072104245 -0.064547971, 0.45491275 0.074322313 -0.064603552, 0.45974562 0.072825417 -0.065742925, 0.45527893 0.075073138 -0.065813974, 0.46021038 0.073778257 -0.066716745, 0.45576155 0.076062486 -0.066788897, 0.46076211 0.074909568 -0.067414865, 0.45633236 0.077232853 -0.067472294, 0.46137053 0.076156318 -0.06779857, 0.45695829 0.078516126 -0.06782411, 0.46200114 0.077449307 -0.06784676, 0.45760301 0.079837844 -0.067823991, 0.46261927 0.078716367 -0.067556366, 0.45822909 0.081121117 -0.067472085, 0.46319029 0.079887062 -0.066943839, 0.45879999 0.08229138 -0.066788629, 0.46353164 0.080564559 -0.066384539, 0.45928249 0.083280519 -0.065813377, 0.46371558 0.080950469 -0.065977409, 0.45964876 0.084031329 -0.064603165, 0.45987737 0.08449997 -0.063228145, 0.45770732 0.080051333 -0.062630609, 0.4576045 0.079840481 -0.06283839, 0.45770729 0.080051228 -0.060906455, 0.45677611 0.078141972 -0.061164454, 0.45685413 0.078302056 -0.060906664, 0.45760456 0.079840302 -0.060698673, 0.45748284 0.079591006 -0.062984064, 0.4577854 0.080211133 -0.061164215, 0.45672736 0.07804215 -0.061457589, 0.45748284 0.079590887 -0.060553089, 0.45734939 0.079317555 -0.063058957, 0.45783409 0.080311164 -0.061457381, 0.45671079 0.078008235 -0.061768606, 0.45734945 0.079317331 -0.060478047, 0.45721197 0.079035893 -0.063058928, 0.45785066 0.080345064 -0.061768517, 0.45672742 0.078042179 -0.062079743, 0.45677605 0.078142077 -0.062372699, 0.45721206 0.079035684 -0.060478047, 0.45783406 0.08031112 -0.062079564, 0.45707858 0.078762397 -0.062984064, 0.45685408 0.078302249 -0.062630668, 0.45707867 0.078762248 -0.060553089, 0.45695695 0.078513071 -0.06283845, 0.45778543 0.080211222 -0.062372699, 0.45695707 0.078512833 -0.060698673, 0.45380619 0.082317919 -0.061768427, 0.45378968 0.082283929 -0.061457232, 0.45374084 0.082184106 -0.061164215, 0.4536629 0.082024008 -0.060906276, 0.45356002 0.081813231 -0.060698494, 0.45343843 0.081563801 -0.060553029, 0.45330492 0.081290409 -0.060477987, 0.45316753 0.081008658 -0.060477987, 0.45303419 0.080735162 -0.060553029, 0.45291248 0.080485776 -0.060698584, 0.4528096 0.080274969 -0.060906455, 0.45273149 0.080115005 -0.061164334, 0.45268282 0.080015093 -0.061457381, 0.45266619 0.079981148 -0.061768517, 0.41194519 -0.033613339 -0.057803825, 0.41192892 -0.033665791 -0.057856336, 0.41191652 -0.033757582 -0.057948127, 0.41192663 -0.033841953 -0.058032528, 0.41193438 -0.033867434 -0.036460623, 0.41192028 -0.03381291 -0.036515132, 0.41192353 -0.033690915 -0.036637053, 0.4919996 0.15713941 -0.13583232, 0.47599962 0.15713932 -0.13583235, 0.47599944 0.15731391 -0.13540323, 0.4919996 0.15731391 -0.13540323, 0.47599956 0.15742025 -0.13495256, 0.4919996 0.15742037 -0.13495256, 0.48591641 0.15417255 -0.14176698, 0.48652521 0.15393135 -0.14224936, 0.48698738 0.15363199 -0.14284818, 0.48519614 0.15434165 -0.14142878, 0.48727587 0.15329191 -0.14352851, 0.4844062 0.15442874 -0.14125462, 0.48737374 0.15293081 -0.14425074, 0.48359281 0.15442869 -0.14125462, 0.48280293 0.15434165 -0.14142878, 0.48208269 0.15417252 -0.14176698, 0.48147386 0.15393139 -0.14224936, 0.4810119 0.15363196 -0.14284797, 0.48072341 0.15329188 -0.14352851, 0.4806253 0.1529308 -0.14425074, 0.49199963 0.1415911 -0.1669334, 0.48737386 0.14130715 -0.16750138, 0.47599974 0.14060886 -0.16889803, 0.48062536 0.1408928 -0.16833006, 0.49210832 0.13944718 -0.16854919, 0.49212143 0.13889304 -0.16859965, 0.47612163 0.13791074 -0.17056407, 0.47610393 0.13861701 -0.17048146, 0.47607949 0.13930942 -0.17022197, 0.48134688 0.13974339 -0.16951384, 0.48132023 0.13974772 -0.16951363, 0.4812772 0.13976274 -0.16950868, 0.48123953 0.13978523 -0.16949825, 0.48120728 0.13981344 -0.16948389, 0.48116171 0.13987216 -0.16944994, 0.47604984 0.13992296 -0.16979669, 0.48098934 0.14017037 -0.16923927, 0.49209064 0.14000162 -0.16838993, 0.48666865 0.14007311 -0.16885875, 0.48670822 0.14008908 -0.16884612, 0.48090425 0.14034261 -0.16908495, 0.48083746 0.14050195 -0.16891532, 0.47602478 0.14031443 -0.16937189, 0.49206296 0.14065647 -0.16803215, 0.48695031 0.14042377 -0.16859891, 0.48704615 0.14061478 -0.16843139, 0.48683748 0.14022061 -0.16875316, 0.48674369 0.14011131 -0.1688296, 0.48678395 0.14014746 -0.16880415, 0.48681322 0.14018279 -0.16877954, 0.48073974 0.14071375 -0.16863792, 0.49203163 0.14119944 -0.16752885, 0.48716184 0.14089018 -0.16813897, 0.47612163 0.13468201 -0.1705641, 0.49212179 0.12528437 -0.16860031, 0.47533098 0.12624584 -0.17066194, 0.47533086 0.1346335 -0.17066137, 0.47608098 0.13791069 -0.17056827, 0.47599962 0.13479678 -0.17057161, 0.47604033 0.13791068 -0.17057063, 0.47599962 0.13791071 -0.17057161, 0.47529033 0.1346336 -0.17066555, 0.47529045 0.1262458 -0.17066602, 0.47524968 0.13463351 -0.17066805, 0.47524977 0.12624587 -0.1706685, 0.47520903 0.13463359 -0.17066889, 0.47520906 0.12624586 -0.17066933, 0.48116162 0.15256214 -0.14406644, 0.48083737 0.15285218 -0.14421149, 0.48092923 0.15319063 -0.14353462, 0.48124421 0.15286592 -0.14345892, 0.48119959 0.15350929 -0.14289699, 0.48148665 0.15315185 -0.14288686, 0.48163271 0.15378977 -0.14233597, 0.48187521 0.15340374 -0.14238317, 0.48220327 0.15401588 -0.14188381, 0.48238742 0.15360655 -0.14197738, 0.48287818 0.15417434 -0.14156695, 0.48299319 0.15374878 -0.1416931, 0.48361835 0.15425593 -0.14140351, 0.48365739 0.153822 -0.14154656, 0.48438069 0.15425596 -0.14140351, 0.48434159 0.15382186 -0.14154656, 0.48512086 0.15417434 -0.14156695, 0.48500583 0.15374875 -0.14169295, 0.48579594 0.15401585 -0.14188381, 0.48561171 0.15360652 -0.14197738, 0.48636648 0.15378973 -0.14233576, 0.48612371 0.15340362 -0.14238317, 0.48679951 0.15350936 -0.14289708, 0.48651239 0.15315183 -0.14288683, 0.48706988 0.15319067 -0.14353462, 0.48675498 0.15286596 -0.14345892, 0.48716179 0.15285218 -0.14421149, 0.48683742 0.15256216 -0.14406644, 0.49201658 0.12273306 -0.1671937, 0.49203378 0.12296197 -0.1675099, 0.49205938 0.12340029 -0.16794099, 0.49208292 0.12392284 -0.16827713, 0.49210456 0.12456211 -0.16851379, 0.47222206 0.15742794 -0.083176896, 0.47222206 0.15741861 0.083195791, 0.47243342 0.15735401 -0.083176896, 0.47243351 0.15734467 0.083195791, 0.47262308 0.15723489 -0.083176896, 0.4726229 0.15722559 0.083195552, 0.47278127 0.15707661 -0.083176896, 0.4727813 0.15706721 0.083195552, 0.47290048 0.15688697 -0.083176896, 0.47290057 0.15687762 0.083195791, 0.47297451 0.15667564 -0.083176896, 0.47297439 0.15666629 0.083195552, 0.47299942 0.15645309 -0.083176896, 0.47299948 0.15644374 0.083195552, 0.4729996 0.15006185 0.083195314, 0.4729996 0.1500712 -0.083177283, 0.47309563 0.15645321 -0.084152326, 0.4731358 0.15010615 -0.084335998, 0.47338024 0.15645313 -0.085090354, 0.47354674 0.15021113 -0.085451707, 0.47384217 0.15645333 -0.08595477, 0.47396022 0.15031676 -0.086124137, 0.47446397 0.15645339 -0.086712316, 0.474464 0.15044542 -0.086712912, 0.49153504 0.15645444 -0.10378359, 0.48860142 0.15345423 -0.10085006, 0.4915351 0.15345436 -0.1037838, 0.49299952 0.15345457 -0.10731946, 0.49299958 0.15645452 -0.1073191, 0.4929035 0.15645458 -0.10634349, 0.49290356 0.1534545 -0.10634385, 0.49261883 0.15645452 -0.10540591, 0.49261895 0.1534545 -0.10540591, 0.49215677 0.15645446 -0.10454126, 0.49215686 0.15345442 -0.10454141, 0.49299964 0.14069672 -0.16648628, 0.49299952 0.15624505 -0.13538496, 0.49299958 0.13911736 -0.16212474, 0.49299958 0.15636137 -0.13509901, 0.49299952 0.15311205 -0.13391908, 0.49299952 0.15643239 -0.13479845, 0.49299961 0.15337002 -0.13276644, 0.49299952 0.15645614 -0.13449062, 0.49299958 0.15345588 -0.13157441, 0.4929997 0.12371606 -0.16685309, 0.49299973 0.12528434 -0.1676078, 0.4929997 0.12345771 -0.16643809, 0.4929997 0.12404098 -0.16717504, 0.4929997 0.12439235 -0.16739775, 0.49299982 0.12477662 -0.16754209, 0.4929997 0.12503213 -0.16759171, 0.4929997 0.12591484 -0.16315408, 0.49299973 0.12546435 -0.16263516, 0.4929997 0.12644759 -0.16357084, 0.49299973 0.12511554 -0.16203652, 0.49299976 0.12705043 -0.16387747, 0.4929997 0.12771115 -0.1640663, 0.4929997 0.12840128 -0.16412936, 0.49299964 0.13889292 -0.16760696, 0.49299964 0.13587491 -0.164129, 0.49299964 0.13936456 -0.16755043, 0.4929997 0.13982716 -0.16737543, 0.49299964 0.13654795 -0.16406892, 0.49299964 0.14023736 -0.16708936, 0.4929997 0.13719375 -0.16388859, 0.49299961 0.14049932 -0.16680418, 0.49299964 0.13778594 -0.16359566, 0.49299982 0.1078703 -0.13301568, 0.4929997 0.13831261 -0.16319712, 0.4929997 0.13876262 -0.16269992, 0.49299979 0.1121705 -0.13427968, 0.49299979 0.11178014 -0.13323109, 0.49299982 0.11153701 -0.13207532, 0.49299988 0.11145586 -0.13088252, 0.49299982 0.1078687 -0.10676514, 0.49299988 0.1114545 -0.1067649, 0.49299955 0.15269867 -0.13495828, 0.49265549 0.13738902 -0.16295345, 0.49247387 0.13771799 -0.16254766, 0.49248028 0.13732491 -0.16284986, 0.49297681 0.13767432 -0.16341506, 0.49263719 0.13814583 -0.16223772, 0.49245411 0.13804989 -0.16216575, 0.49242225 0.13830662 -0.16171966, 0.49261543 0.13841245 -0.16177233, 0.49278989 0.13827179 -0.16233225, 0.4927769 0.13855436 -0.1618434, 0.49290451 0.13842151 -0.16244434, 0.49289849 0.13872513 -0.16192888, 0.49297547 0.1385874 -0.16256879, 0.49297413 0.13891615 -0.16202413, 0.4928582 0.13796604 -0.16281863, 0.4928008 0.13747118 -0.16308655, 0.49290958 0.13756779 -0.16324268, 0.49265769 0.12685212 -0.16293572, 0.49247667 0.12737197 -0.16305955, 0.49248365 0.12691775 -0.16283284, 0.49297711 0.12656122 -0.16339229, 0.4926385 0.12785174 -0.16330953, 0.49245593 0.12787375 -0.16319151, 0.49242225 0.12840115 -0.16322313, 0.49261543 0.12840123 -0.16334139, 0.49279073 0.12782288 -0.16346429, 0.4927769 0.12840119 -0.16350003, 0.49290487 0.12778871 -0.16364788, 0.49289861 0.12840122 -0.16369103, 0.49297568 0.12775104 -0.16385151, 0.49297407 0.12840129 -0.16390453, 0.4928591 0.12723778 -0.16340111, 0.49280214 0.12676819 -0.16306742, 0.49291024 0.12666976 -0.16322203, 0.49290413 0.11145452 -0.10579096, 0.49290472 0.10779257 -0.10579418, 0.49262035 0.11145447 -0.10485421, 0.49261916 0.10756411 -0.10485159, 0.49215961 0.11145435 -0.10399072, 0.49215961 0.10719641 -0.10399087, 0.48865643 0.11145414 -0.098738089, 0.47384021 0.088875175 -0.07652311, 0.47383997 0.11681192 -0.076521382, 0.47299984 0.087683499 -0.073748842, 0.47301617 0.08772333 -0.074151263, 0.47299972 0.11717644 -0.073747113, 0.47309494 0.11713518 -0.074718133, 0.4730649 0.08784309 -0.074551687, 0.4731454 0.08804141 -0.074946269, 0.47338042 0.11701132 -0.075660661, 0.47331563 0.088245407 -0.075496629, 0.47354856 0.088525236 -0.076025918, 0.47299996 0.087675169 0.073759899, 0.47299972 0.11716817 0.073761329, 0.48799959 0.13460025 -0.16116045, 0.49242231 0.1358749 -0.16322266, 0.48799959 0.13524804 -0.16108535, 0.49245423 0.13638885 -0.16319235, 0.49247381 0.13687894 -0.1630664, 0.48799965 0.13586786 -0.16085453, 0.48799965 0.13636258 -0.16051982, 0.48799971 0.13673219 -0.16013272, 0.48799953 0.1368947 -0.15990154, 0.48799965 0.13703193 -0.15965731, 0.48799962 0.15219773 -0.12916227, 0.4879995 0.15239121 -0.12829755, 0.48799959 0.15188766 -0.1299416, 0.48799959 0.15245575 -0.12740369, 0.48799977 0.12803499 -0.16058944, 0.48799974 0.12901676 -0.16107355, 0.48799971 0.12760223 -0.16015922, 0.48799971 0.12850146 -0.16088338, 0.48799953 0.13890544 -0.14687763, 0.48799971 0.1293651 -0.16113921, 0.48799971 0.12725057 -0.159591, 0.48799953 0.15245527 -0.11977415, 0.48799968 0.1259158 -0.14703821, 0.48799983 0.11245514 -0.11817609, 0.48799977 0.11245574 -0.12646888, 0.48799986 0.11299171 -0.12901689, 0.48799959 0.12971498 -0.16116069, 0.48799959 0.12687297 -0.14833345, 0.48799968 0.12650865 -0.14797451, 0.48799977 0.126187 -0.14753707, 0.48799971 0.12726906 -0.14860122, 0.48799959 0.12768397 -0.14877082, 0.48799971 0.12810394 -0.14884154, 0.48799968 0.12820548 -0.14884414, 0.48799989 0.112564 -0.12765832, 0.48799974 0.1127405 -0.12836836, 0.48799965 0.1363959 -0.14884375, 0.48799971 0.13678125 -0.14880444, 0.48799965 0.13717207 -0.14868383, 0.48799959 0.13772902 -0.14836217, 0.48799959 0.13828333 -0.14783432, 0.48789975 0.12812749 -0.14840652, 0.48777929 0.12820546 -0.1482179, 0.48777971 0.1281378 -0.14821674, 0.48789969 0.12820546 -0.14840819, 0.48797441 0.1281161 -0.1486185, 0.48797438 0.12820546 -0.1486205, 0.49199986 0.11245587 -0.1308824, 0.48799983 0.11245507 -0.11736985, 0.49199983 0.11245452 -0.1067649, 0.48799983 0.11245507 -0.11682124, 0.48799983 0.11245507 -0.11631201, 0.49192312 0.11245453 -0.10598572, 0.49132764 0.11245438 -0.10454549, 0.49169633 0.11245441 -0.1052364, 0.48799977 0.11245413 -0.099555627, 0.49169502 0.15245451 -0.10578848, 0.4919996 0.15245458 -0.10731946, 0.49192271 0.15245453 -0.106539, 0.49132541 0.15245456 -0.10509713, 0.49082795 0.15245444 -0.10449098, 0.48799956 0.15245427 -0.1016625, 0.48799959 0.15245521 -0.1177655, 0.48799953 0.15245527 -0.11836629, 0.48799953 0.15245527 -0.11897136, 0.4919996 0.1524559 -0.13157441, 0.44403842 0.14309238 0.044759676, 0.44412622 0.14311133 0.040250316, 0.44416374 0.14311901 0.044565126, 0.44426677 0.14314108 0.040406242, 0.4441354 0.1431195 -0.071021035, 0.44403395 0.14309815 -0.075693712, 0.44415393 0.14312367 -0.075502113, 0.44402531 0.14309601 -0.070834979, 0.4439604 0.14307563 0.044978276, 0.44402099 0.14308895 0.04006727, 0.48799953 0.15244189 0.1177838, 0.48465714 0.15173115 0.11193632, 0.48482797 0.1517674 0.11177681, 0.48495728 0.15179494 0.1115806, 0.44395924 0.14308217 -0.075908139, 0.44393393 0.14307 0.045209214, 0.44395593 0.14307503 0.039865658, 0.48445445 0.15168804 0.11205073, 0.443957 0.14308144 -0.070629135, 0.44393393 0.14307041 0.039654657, 0.48503789 0.15181215 0.11135872, 0.44393393 0.14307676 -0.076134041, 0.48423123 0.15164047 0.11211298, 0.46980754 0.14857683 0.015738592, 0.46982914 0.14858179 0.011594996, 0.4699477 0.14860681 0.015939668, 0.4439339 0.14307655 -0.070413008, 0.48506531 0.15181795 0.11112376, 0.46966961 0.14855112 -0.047953442, 0.46973237 0.14856462 -0.051953182, 0.46983531 0.14858642 -0.047794268, 0.48399979 0.15159121 0.1121199, 0.46962342 0.14853776 0.015578613, 0.46965909 0.14854559 0.011754528, 0.48377338 0.15154298 0.11207102, 0.46995774 0.14860912 0.011399105, 0.4700354 0.14862531 0.016169772, 0.46987292 0.14859469 -0.052109346, 0.46996072 0.1486131 -0.047599956, 0.48356456 0.15149859 0.11196895, 0.46956268 0.14852862 -0.051831022, 0.46940657 0.14849162 0.015469745, 0.4694573 0.14850259 0.011869088, 0.46947214 0.14850913 -0.048069492, 0.47003797 0.14862631 0.011177644, 0.47006527 0.14863166 0.016414985, 0.46997812 0.14861706 -0.052292213, 0.47003886 0.14862958 -0.047381267, 0.46917012 0.14844131 0.015418485, 0.46923479 0.14845525 0.011932001, 0.46937159 0.14848784 -0.051747903, 0.46925399 0.14846262 -0.048135415, 0.46902671 0.14841434 -0.04814823, 0.46880278 0.14836664 -0.048106924, 0.48506525 0.15181819 0.10702057, 0.48799959 0.15244284 0.10168068, 0.4847416 0.15174928 0.10627742, 0.48487845 0.15177849 0.10643278, 0.4849807 0.15180025 0.10661389, 0.47004321 0.14863089 -0.052493826, 0.47006533 0.14863525 -0.04715018, 0.48504391 0.1518137 0.1068127, 0.47006527 0.14863208 0.010943487, 0.4444229 0.14318109 -0.078967378, 0.44519264 0.14334509 -0.082917169, 0.44540113 0.14338937 -0.083009109, 0.47006524 0.1486356 -0.052704796, 0.46900409 0.14840612 0.011939898, 0.44496885 0.14329742 -0.082876727, 0.44474217 0.14324929 -0.082890317, 0.44472525 0.14324224 -0.025215939, 0.44488439 0.1432765 -0.028736696, 0.44509879 0.14332208 -0.028754577, 0.44467142 0.14323112 -0.028766945, 0.44452465 0.14320293 -0.082956865, 0.44451153 0.1431969 -0.025146827, 0.48480362 0.15176275 0.10198332, 0.44447008 0.1431883 -0.028844252, 0.48487386 0.15177776 0.10189523, 0.44431883 0.14315584 -0.025029495, 0.44425744 0.14314595 -0.078844503, 0.44432804 0.14316097 -0.083072856, 0.48457623 0.15171424 0.10615455, 0.48463759 0.15172739 0.10211624, 0.44415724 0.14312145 -0.0248705, 0.44428989 0.14315005 -0.028964475, 0.44412068 0.1431168 -0.078689173, 0.44416276 0.143126 -0.083232239, 0.48492301 0.15178818 0.1017933, 0.48444754 0.151687 0.10220946, 0.44414005 0.1431181 -0.029122189, 0.4440355 0.14309557 -0.024678126, 0.44449857 0.14319061 0.036573574, 0.44467536 0.14322852 0.032924876, 0.44470865 0.14323528 0.036501929, 0.44492897 0.14328225 0.036480293, 0.44401848 0.14309505 -0.078508094, 0.44403794 0.14309935 -0.083426312, 0.44514856 0.14332889 0.036509976, 0.44402739 0.14309411 -0.029309645, 0.48494825 0.15179357 0.10168265, 0.48494831 0.15179363 0.10156904, 0.48800519 0.15244403 0.10161678, 0.44395962 0.14307937 -0.024462178, 0.44396025 0.14308293 -0.083644465, 0.44447309 0.14318535 0.032848313, 0.44430977 0.14315052 0.036691979, 0.48424232 0.15164335 0.10225929, 0.44395757 0.14307931 -0.029517636, 0.48492333 0.15178825 0.10145818, 0.48802021 0.15244713 0.10156928, 0.44393393 0.14307383 -0.024234489, 0.48803368 0.15245005 0.10154463, 0.4442921 0.14314686 0.03272815, 0.4439339 0.14307424 -0.029736266, 0.48403159 0.15159865 0.10226275, 0.44415188 0.14311692 0.036850736, 0.48487452 0.15177798 0.10135601, 0.48805067 0.15245369 0.10152365, 0.4441413 0.14311473 0.032570288, 0.44403282 0.1430916 0.03704159, 0.48480427 0.15176299 0.10126783, 0.44402802 0.14309064 0.032382414, 0.44395897 0.14307575 0.037255093, 0.48382494 0.15155466 0.10221998, 0.48363209 0.15151364 0.10213293, 0.47443387 0.14955707 0.090897039, 0.44110253 0.14247504 -0.087457135, 0.44395533 0.14308152 -0.078309253, 0.4439339 0.14307699 -0.078101322, 0.44393393 0.14307049 0.037480041, 0.44395766 0.1430759 0.032173887, 0.44393381 0.14307597 -0.06065838, 0.44393381 0.14307618 -0.062722549, 0.44438931 0.14317435 -0.086633161, 0.48356456 0.15151122 -0.11195098, 0.44423458 0.14314131 -0.086509183, 0.44410717 0.14311424 -0.086356029, 0.44401219 0.14309405 -0.086179927, 0.44395366 0.14308158 -0.085987911, 0.44393384 0.14307638 -0.068395212, 0.44393399 0.14307739 -0.085787877, 0.44393393 0.14307733 -0.083875105, 0.47396508 0.14945742 0.087437883, 0.44110253 0.14246516 0.087474361, 0.44393396 0.14306916 0.060675517, 0.44393393 0.14306943 0.055047229, 0.47397223 0.1494589 0.090554222, 0.47413674 0.14949396 0.090653285, 0.44393387 0.14307073 0.031954512, 0.4439339 0.14306965 0.052941009, 0.47429112 0.14952679 0.090767726, 0.4439339 0.14306994 0.04735212, 0.47309729 0.14927286 0.086338863, 0.44393405 0.14307088 0.029753432, 0.44393387 0.14307117 0.024251625, 0.4439339 0.14307137 0.022029802, 0.44393396 0.14307161 0.016546026, 0.44393387 0.14307174 0.014308915, 0.44393387 0.14307204 0.0088374764, 0.4439339 0.14307222 0.0065912157, 0.44393399 0.1430725 0.0011260062, 0.44393381 0.14307272 -0.0011088103, 0.44393399 0.14307292 -0.0065739006, 0.44393393 0.14307304 -0.0088202804, 0.44393393 0.14307345 -0.014291778, 0.44393393 0.14307353 -0.01652886, 0.44393387 0.14307377 -0.022012606, 0.4439339 0.14307441 -0.031937346, 0.4439339 0.14307471 -0.037462875, 0.4439339 0.14307483 -0.039637491, 0.44393381 0.14307517 -0.045192078, 0.4439339 0.14307526 -0.047335044, 0.4439339 0.14307556 -0.052923903, 0.44393387 0.14307564 -0.055029973, 0.47249958 0.1491458 0.085043773, 0.46984515 0.14858106 0.083983079, 0.47227976 0.14909911 0.084122226, 0.47220764 0.14909314 -0.083177283, 0.47220775 0.14908369 0.083195314, 0.47006533 0.14863366 -0.019986048, 0.47006533 0.14863399 -0.025469735, 0.47006533 0.14863424 -0.029043511, 0.47006521 0.14863452 -0.034545317, 0.47006533 0.14863467 -0.038098142, 0.47006527 0.14863512 -0.043623731, 0.46968588 0.14854704 0.084141776, 0.47006521 0.1486358 -0.056199566, 0.47006533 0.14863601 -0.061788514, 0.47006521 0.14863627 -0.065246418, 0.47006521 0.14863653 -0.070874795, 0.46996525 0.14860655 0.083791509, 0.47006521 0.14863352 -0.016397104, 0.47006533 0.14863314 -0.010925606, 0.47006527 0.14863309 -0.0073273331, 0.47006527 0.14863268 -0.0018621534, 0.46949539 0.14850655 0.084259793, 0.47006527 0.14863253 0.001880005, 0.47006533 0.14863214 0.0073452145, 0.46965006 0.14854744 -0.057017282, 0.46981224 0.14858225 -0.061117247, 0.46982357 0.14858444 -0.056857511, 0.47006521 0.14863148 0.020003781, 0.47006521 0.14863123 0.025487646, 0.47006527 0.14863093 0.029061332, 0.47006524 0.14863069 0.034563139, 0.47003999 0.14862248 0.083576962, 0.47006533 0.14863037 0.038115993, 0.47006533 0.14863011 0.043641612, 0.47006533 0.14862992 0.047167942, 0.47006524 0.1486297 0.052722558, 0.4694443 0.1485038 -0.057130411, 0.46963105 0.14854361 -0.060957447, 0.47006533 0.14862938 0.056217268, 0.47006521 0.14862905 0.061806247, 0.47006533 0.14862894 0.065264121, 0.4697102 0.14855669 0.0065744072, 0.46984383 0.14858542 0.0025137216, 0.46985972 0.1485886 0.0067318827, 0.47006521 0.14862862 0.070892707, 0.46867251 0.14834054 -0.075196639, 0.44449744 0.14319606 -0.06362839, 0.44532672 0.14337274 -0.06748946, 0.44528571 0.14336355 -0.059734181, 0.4694607 0.14850794 -0.069950685, 0.46871355 0.14834873 -0.066170529, 0.46863398 0.14833276 -0.084219411, 0.44445893 0.14318831 -0.0712993, 0.44536522 0.14338142 -0.075247869, 0.46928385 0.14846155 0.084330574, 0.4696835 0.1485513 0.002672568, 0.46950182 0.14851716 -0.079057738, 0.468757 0.14835742 -0.057140753, 0.44458178 0.14321312 -0.048276171, 0.44524226 0.14335389 -0.051982597, 0.44519648 0.1433437 -0.044235364, 0.44453841 0.14320435 -0.055954084, 0.46941736 0.1484981 -0.060847208, 0.46927398 0.14846617 -0.033563867, 0.46890029 0.14838645 -0.03002508, 0.46994993 0.14861149 -0.061317459, 0.46995518 0.14861247 -0.056660309, 0.46885055 0.14837635 -0.039068595, 0.44467548 0.14323221 -0.032907739, 0.44514862 0.14333312 -0.036492482, 0.47006518 0.14862785 0.08335115, 0.46932378 0.14847718 -0.042653337, 0.46953061 0.14851843 0.0064538866, 0.44462752 0.14322248 -0.040594265, 0.483632 0.1515251 -0.10211466, 0.46906212 0.14841442 0.08435072, 0.46921816 0.14845565 -0.057190433, 0.46898457 0.14840592 -0.057194129, 0.47397235 0.14946903 -0.090536579, 0.46996468 0.14861107 0.002321884, 0.48457626 0.15172608 -0.10613631, 0.4699721 0.14861237 0.0069191307, 0.44449735 0.14318891 0.063645676, 0.46867248 0.14833203 0.075214341, 0.44532672 0.14336506 0.067506567, 0.46946079 0.1485001 0.069968447, 0.44528559 0.14335689 0.059751287, 0.46871349 0.14834115 0.066188559, 0.4688417 0.14836755 0.084318802, 0.44445887 0.14318028 0.071316376, 0.46863404 0.14832334 0.084237054, 0.44536513 0.14337286 0.075265005, 0.46950182 0.14850831 0.0790755, 0.44458184 0.14320773 0.048293367, 0.46875691 0.1483511 0.057158604, 0.44524226 0.14334804 0.051999912, 0.46937159 0.1484821 0.051765874, 0.44519654 0.14333877 0.04425256, 0.46880272 0.14836127 0.048124686, 0.44453833 0.14319806 0.055971459, 0.470036 0.14862975 -0.061545655, 0.47003731 0.14862995 -0.056436673, 0.46941736 0.14849141 0.060865, 0.46927395 0.14846244 0.033581451, 0.44509894 0.14331874 0.028771982, 0.46890035 0.14838299 0.030042991, 0.46885058 0.14837202 0.039086327, 0.46949223 0.1485105 0.0027902275, 0.46932375 0.14847241 0.042671129, 0.44462755 0.14321779 0.04061155, 0.4693296 0.14847565 0.0063764602, 0.44442287 0.14317216 0.078984633, 0.44540116 0.14337993 0.083026394, 0.4700653 0.14862803 0.079981104, 0.44472525 0.14323942 0.025233343, 0.47003976 0.14862709 0.0021066815, 0.47004163 0.14862724 0.0071269125, 0.47004029 0.14862278 0.079756424, 0.46911696 0.14843047 0.0063456446, 0.46927986 0.14846538 0.0028604418, 0.44492903 0.14328641 -0.036462918, 0.46905726 0.14841801 0.0028796643, 0.4696902 0.14854831 0.079193994, 0.46970072 0.14855079 0.075087383, 0.46984777 0.14858188 0.079352543, 0.44470856 0.1432395 -0.036484525, 0.44467142 0.14322779 0.028784141, 0.44488445 0.14327325 0.028753921, 0.46985409 0.14858338 0.074929222, 0.46996644 0.14860711 0.079543158, 0.46951702 0.14851165 0.07520698, 0.444473 0.14318913 -0.032830939, 0.44449857 0.14319478 -0.036556616, 0.44446996 0.14318505 0.028861418, 0.44451138 0.14319406 0.025163934, 0.46996936 0.14860792 0.074740395, 0.44431874 0.14315306 0.025046602, 0.44428992 0.14314678 0.02898179, 0.44430977 0.1431547 -0.036674872, 0.4442921 0.14315058 -0.032710806, 0.46931174 0.14846809 0.075281933, 0.47004092 0.1486232 0.074529991, 0.44413996 0.14311478 0.029139623, 0.44415721 0.14311865 0.024887607, 0.44415185 0.14312102 -0.03683345, 0.4441413 0.14311855 -0.032552943, 0.4690955 0.14842209 0.075308695, 0.44402739 0.14309077 0.029326871, 0.44403535 0.14309283 0.024695173, 0.44403294 0.14309575 -0.037024423, 0.47006512 0.14862838 0.074308589, 0.44402802 0.14309444 -0.032365248, 0.46887895 0.14837596 0.075285628, 0.44395766 0.1430795 -0.032156691, 0.44395903 0.14307998 -0.037237808, 0.44395956 0.1430766 0.024479255, 0.44395757 0.14307585 0.029534921, 0.46966147 0.14854279 0.070083156, 0.46981198 0.14857498 0.065935597, 0.46983057 0.14857875 0.070242837, 0.46963081 0.14853643 0.066095486, 0.46994993 0.14860436 0.065735564, 0.46995848 0.14860597 0.070438132, 0.46941707 0.14849091 0.066205636, 0.46922261 0.14845198 0.024497166, 0.44504744 0.14330837 0.021039441, 0.46895161 0.1483945 0.020994201, 0.47003591 0.14862278 0.065507188, 0.47003815 0.14862289 0.070658997, 0.46918353 0.14844117 0.066259369, 0.46894434 0.14839031 0.06625329, 0.46968362 0.14855149 -0.0026548356, 0.4697102 0.14855754 -0.0065565556, 0.46984383 0.14858554 -0.00249587, 0.46985969 0.14858928 -0.0067142695, 0.46996468 0.14861137 -0.0023040026, 0.46953067 0.1485192 -0.0064360946, 0.46949226 0.14851078 -0.0027724355, 0.4699721 0.14861308 -0.0069013983, 0.47003976 0.14862731 -0.0020889491, 0.46932957 0.14847642 -0.006358549, 0.44497249 0.14329603 -0.044194087, 0.46927986 0.1484656 -0.00284262, 0.47004172 0.14862792 -0.0071091205, 0.44474524 0.14324769 -0.044206724, 0.4691169 0.1484312 -0.0063278526, 0.46905735 0.14841822 -0.0028616637, 0.44452706 0.14320125 -0.044272885, 0.44443646 0.14318177 -0.040511325, 0.44438937 0.14316468 0.086650208, 0.44423452 0.14313172 0.08652626, 0.44410712 0.14310457 0.086373195, 0.44401219 0.14308444 0.086197034, 0.46981207 0.14858241 -0.065917715, 0.46983066 0.14858662 -0.070224956, 0.46994987 0.1486118 -0.065717533, 0.44395372 0.14307193 0.086005226, 0.44393393 0.1430677 0.085805073, 0.44457701 0.14320828 0.021090284, 0.44477645 0.14325087 0.017536357, 0.44480917 0.1432576 0.021035269, 0.46963078 0.14854388 -0.066077545, 0.46966156 0.14855067 -0.070065573, 0.44455141 0.14320296 0.01747562, 0.46995848 0.14861384 -0.070420489, 0.47003588 0.14863016 -0.065489247, 0.44436476 0.14316301 0.021201, 0.44393393 0.14306788 0.083892241, 0.44434676 0.14315937 0.017362103, 0.46941712 0.14849839 -0.066187814, 0.44418493 0.14312479 0.02136071, 0.46918353 0.14844875 -0.066241369, 0.46894422 0.1483978 -0.066235647, 0.47003821 0.1486308 -0.070641115, 0.44396028 0.14307345 0.08366169, 0.44417414 0.14312264 0.017202303, 0.44404826 0.14309576 0.021560356, 0.44432953 0.14315926 -0.044388637, 0.44426683 0.14314561 -0.040389016, 0.44396284 0.14307763 0.021788016, 0.44404328 0.14309485 0.017005399, 0.44396168 0.14307757 0.016782358, 0.46981212 0.1485754 0.061135158, 0.46982366 0.14857803 0.056875482, 0.46994993 0.14860465 0.061335251, 0.44416371 0.14312397 -0.04454799, 0.44412622 0.14311573 -0.040232733, 0.46963099 0.14853688 0.060975268, 0.46965006 0.14854112 0.057035223, 0.4440383 0.14309742 -0.044742331, 0.46995524 0.14860609 0.056678072, 0.470036 0.14862284 0.061563507, 0.44402099 0.14309338 -0.040049985, 0.44395602 0.14307949 -0.039848462, 0.44396043 0.14308074 -0.044960901, 0.46944442 0.1484973 0.057148382, 0.47003743 0.14862353 0.056454524, 0.44499508 0.14329761 0.013312653, 0.46921819 0.14844917 0.057208255, 0.46898463 0.14839955 0.057211831, 0.44432798 0.14315166 0.08309029, 0.44452465 0.14319357 0.082973883, 0.44474223 0.1432398 0.082907692, 0.44496903 0.14328799 0.082894012, 0.44519249 0.14333576 0.082934305, 0.44416276 0.14311659 0.083249435, 0.44425747 0.14313702 0.078861549, 0.44476438 0.14324853 0.013320401, 0.44482902 0.14326251 0.0098338276, 0.46965918 0.1485469 -0.011736855, 0.46980748 0.14857857 -0.015720591, 0.46982914 0.14858305 -0.011577204, 0.44403797 0.14308992 0.083443537, 0.44412071 0.14310783 0.078706458, 0.46945736 0.14850388 -0.011851296, 0.46962336 0.1485395 -0.015560791, 0.46994773 0.14860855 -0.015921846, 0.46995777 0.1486104 -0.011381283, 0.44401839 0.14308612 0.07852523, 0.46923482 0.14845657 -0.011914209, 0.46940657 0.14849329 -0.015451923, 0.44395527 0.14307269 0.078326538, 0.47003531 0.14862725 -0.016152009, 0.470038 0.14862746 -0.011160001, 0.4439339 0.14306821 0.078118488, 0.44454187 0.14320119 0.013383463, 0.44459268 0.14321215 0.009782657, 0.46917015 0.14844298 -0.015400752, 0.46900415 0.1484075 -0.011922017, 0.44501448 0.14330551 -0.051929459, 0.44437575 0.14316602 0.0096737295, 0.44434008 0.14315827 0.013497725, 0.44478098 0.1432557 -0.051933065, 0.44393393 0.14306824 0.076151475, 0.44419163 0.14312693 0.0095137507, 0.44417006 0.14312217 0.013657406, 0.44455484 0.14320759 -0.051992878, 0.44436809 0.14316772 -0.048166081, 0.44405141 0.14309712 0.0093126446, 0.44434914 0.14316379 -0.052106246, 0.44404128 0.14309473 0.013853297, 0.44418696 0.14312921 -0.048006341, 0.44417551 0.14312683 -0.052265897, 0.44396374 0.14307837 0.0090826303, 0.44396114 0.14307758 0.014074638, 0.44404921 0.14309983 -0.047806099, 0.46973228 0.14855888 0.051970944, 0.46983546 0.14858106 0.047812119, 0.46987289 0.14858884 0.052127108, 0.4440439 0.14309889 -0.052463308, 0.44396314 0.14308153 -0.047577813, 0.46956271 0.14852279 0.051848844, 0.46966961 0.14854576 0.047971264, 0.44396177 0.14308158 -0.052686945, 0.46996078 0.14860772 0.047617778, 0.46997812 0.14861126 0.052310064, 0.46970063 0.14855933 -0.075069651, 0.46984783 0.14859073 -0.079334691, 0.46985409 0.1485918 -0.074911341, 0.44494176 0.14328676 0.0055914968, 0.46947211 0.14850377 0.048087254, 0.4695169 0.1485202 -0.075189218, 0.4696902 0.14855722 -0.079175994, 0.4700388 0.14862429 0.047399178, 0.47004321 0.14862499 0.052511647, 0.46996641 0.14861616 -0.079525426, 0.46996936 0.14861639 -0.074722394, 0.46931174 0.1484766 -0.075264052, 0.46925405 0.14845727 0.048153326, 0.4690955 0.14843063 -0.075290874, 0.4688789 0.14838448 -0.075267836, 0.47004029 0.1486318 -0.079738691, 0.47004095 0.14863165 -0.074512079, 0.46902665 0.14840898 0.048166171, 0.47006521 0.14863682 -0.074290767, 0.44431338 0.143149 0.075360492, 0.44450375 0.14318956 0.075242624, 0.44471535 0.14323457 0.075171664, 0.44493702 0.14328168 0.075151548, 0.44515741 0.14332862 0.075183377, 0.44428232 0.14314266 0.071195439, 0.47006533 0.14863703 -0.079963282, 0.44415411 0.14311516 0.075519249, 0.4441354 0.14311147 0.071038231, 0.44403389 0.14308961 0.075710729, 0.44402528 0.14308794 0.070852265, 0.44395927 0.1430736 0.075925186, 0.44471928 0.14323939 0.0056106001, 0.44488212 0.14327431 0.0021253973, 0.44395697 0.14307341 0.070646271, 0.44450691 0.14319418 0.0056808144, 0.44466954 0.14322898 0.0020947605, 0.44393393 0.14306857 0.070430234, 0.44431555 0.1431534 0.0057985932, 0.44446856 0.14318617 0.0020173043, 0.44428894 0.14314805 0.0018966943, 0.44415534 0.14311936 0.0059574395, 0.44413933 0.14311625 0.001739189, 0.44403452 0.14309368 0.0061494261, 0.46981418 0.14858031 -0.020654991, 0.46982509 0.14858292 -0.024813369, 0.46995088 0.14860949 -0.020455346, 0.44402704 0.14309232 0.0015518218, 0.44395936 0.14307764 0.0063643605, 0.46965241 0.14854619 -0.024653718, 0.4696345 0.14854206 -0.020814821, 0.46995595 0.14861079 -0.025010332, 0.44393393 0.14306873 0.068412289, 0.47003624 0.14862756 -0.020227924, 0.47006521 0.14863728 -0.083332971, 0.46942213 0.14849685 -0.020925537, 0.46944779 0.14850263 -0.024540111, 0.47003758 0.14862812 -0.025233284, 0.47003993 0.1486319 -0.08355923, 0.4722797 0.1491086 -0.084104463, 0.46918991 0.14844754 -0.020980492, 0.46922266 0.14845477 -0.024479315, 0.46895164 0.14839685 -0.020976439, 0.46996522 0.14861615 -0.083773598, 0.44395748 0.14307751 0.0013442487, 0.46984509 0.14859058 -0.083965018, 0.46970707 0.148554 0.042867944, 0.46984729 0.14858399 0.038745329, 0.46985784 0.14858605 0.043025807, 0.47249949 0.14915535 -0.085025862, 0.46968946 0.14855038 0.038904116, 0.46952602 0.14851551 0.04274781, 0.46968582 0.14855668 -0.084123924, 0.46996632 0.14860937 0.038554266, 0.46997124 0.1486102 0.043213591, 0.46949539 0.1485161 -0.084241852, 0.47309721 0.14928254 -0.08632116, 0.46950063 0.14851026 0.039022431, 0.47004029 0.14862509 0.038341001, 0.47004142 0.14862521 0.043422118, 0.46929058 0.14846559 0.039094135, 0.46928379 0.14847116 -0.084312752, 0.44505489 0.14331448 -0.059669212, 0.46907014 0.14841865 0.039115801, 0.46906209 0.14842385 -0.084332779, 0.44448218 0.14318542 0.067513958, 0.4446874 0.14322905 0.067439064, 0.44490352 0.14327517 0.067412242, 0.44481561 0.14326355 -0.059663281, 0.44512025 0.14332119 0.06743516, 0.44429848 0.14314635 0.067633614, 0.44430894 0.14314881 0.06352739, 0.44414502 0.1431137 0.067791715, 0.44415134 0.14311525 0.063368425, 0.44458205 0.14321388 -0.059717044, 0.44403264 0.14308992 0.063177779, 0.44436836 0.14316827 -0.059827045, 0.44402978 0.14308913 0.067980632, 0.44433758 0.14316167 -0.055839345, 0.44395894 0.14307441 0.062964514, 0.44395813 0.14307386 0.068191037, 0.48805067 0.15246513 -0.10150571, 0.48487452 0.15178926 -0.10133784, 0.4880338 0.15246144 -0.10152642, 0.44393381 0.14306907 0.062739864, 0.4848043 0.1517743 -0.10124953, 0.48802003 0.15245865 -0.10155089, 0.48492333 0.15179963 -0.10144, 0.48800519 0.15245551 -0.10159855, 0.48494834 0.15180504 -0.10155074, 0.44494182 0.14328739 -0.0055743605, 0.44488218 0.1432745 -0.0021082908, 0.47396502 0.14946732 -0.087420061, 0.47443387 0.14956726 -0.090879247, 0.44471931 0.14324005 -0.0055934042, 0.44466951 0.14322917 -0.002077505, 0.47429124 0.14953682 -0.090749785, 0.44416848 0.14312562 -0.055679694, 0.44418713 0.14312989 -0.059986994, 0.44450685 0.14319482 -0.0056637377, 0.44446859 0.14318642 -0.0019999295, 0.44428894 0.14314821 -0.0018794984, 0.44431558 0.14315413 -0.0057812482, 0.48494819 0.15180501 -0.10166432, 0.47413686 0.14950396 -0.090635225, 0.44415531 0.14312001 -0.0059403032, 0.44413942 0.14311644 -0.0017219335, 0.46884176 0.14837708 -0.084301099, 0.44403443 0.14309438 -0.0061320812, 0.44402722 0.14309245 -0.0015348345, 0.48492292 0.15179966 -0.10177504, 0.44395939 0.14307842 -0.0063471645, 0.48487383 0.15178922 -0.10187708, 0.44395748 0.14307764 -0.0013270527, 0.44404066 0.1430985 -0.05548431, 0.44404927 0.14310049 -0.060187176, 0.46970925 0.14855853 -0.029815271, 0.46984193 0.14858705 -0.033909306, 0.46985933 0.1485904 -0.029657558, 0.48480359 0.15177435 -0.10196529, 0.4439632 0.14308216 -0.060415521, 0.44396096 0.14308146 -0.055263475, 0.44436833 0.14316157 0.05984439, 0.44458216 0.14320709 0.05973427, 0.44481578 0.14325678 0.059680417, 0.44505492 0.14330773 0.059686229, 0.4695293 0.14852019 -0.029935613, 0.46968037 0.14855263 -0.033750162, 0.44418716 0.14312305 0.060004368, 0.44433752 0.14315535 0.055856451, 0.4699637 0.1486129 -0.034101591, 0.46997181 0.14861436 -0.029470071, 0.46932772 0.14847742 -0.030012831, 0.46948767 0.14851169 -0.033633098, 0.46968037 0.14854874 0.033768311, 0.46970925 0.14855519 0.029833063, 0.4698419 0.1485832 0.033927068, 0.46985912 0.1485872 0.02967535, 0.46996388 0.14860906 0.034119591, 0.47003964 0.14862902 -0.034317479, 0.46952918 0.1485168 0.029953405, 0.47004154 0.14862929 -0.02926214, 0.46911469 0.14843208 -0.0300432, 0.46948773 0.14850788 0.03365083, 0.46997181 0.14861101 0.029488012, 0.47003958 0.14862515 0.03433542, 0.46932784 0.14847401 0.030030593, 0.47004166 0.14862588 0.029280052, 0.44404933 0.14309375 0.060204282, 0.44416854 0.14311941 0.055697039, 0.46911466 0.14842866 0.030060992, 0.44396326 0.14307542 0.060432747, 0.44404069 0.14309217 0.055501416, 0.48463753 0.15173894 -0.10209797, 0.48474175 0.15176132 -0.10625921, 0.48487845 0.1517904 -0.10641445, 0.44396093 0.1430752 0.05528082, 0.48444757 0.15169854 -0.10219152, 0.48424232 0.15165482 -0.10224099, 0.48403156 0.15161002 -0.10224445, 0.48382506 0.151566 -0.10220174, 0.44482899 0.14326367 -0.0098167211, 0.44499502 0.14329909 -0.013295427, 0.48498076 0.15181211 -0.10659562, 0.48504388 0.15182561 -0.10679446, 0.48506528 0.15183017 -0.10700236, 0.44459262 0.14321326 -0.0097654313, 0.44476435 0.14325003 -0.013303116, 0.44437572 0.14316723 -0.0096565336, 0.44454187 0.14320262 -0.013366088, 0.44512033 0.1433288 -0.067418054, 0.44490364 0.14328274 -0.067395195, 0.44419166 0.14312796 -0.0094966143, 0.44434002 0.14315972 -0.013480529, 0.4446874 0.14323662 -0.067421868, 0.4440515 0.14309806 -0.0092955977, 0.44416991 0.1431236 -0.01364018, 0.44430891 0.14315592 -0.063509926, 0.44448218 0.14319302 -0.067496762, 0.44415131 0.14312239 -0.063351229, 0.44429845 0.143154 -0.067616418, 0.44396386 0.14307943 -0.0090653747, 0.44404131 0.1430963 -0.01383616, 0.44403264 0.14309709 -0.063160494, 0.44414505 0.14312133 -0.067774519, 0.44396111 0.14307921 -0.014057383, 0.44395885 0.14308146 -0.062947229, 0.44402975 0.14309672 -0.067963436, 0.44455487 0.1432018 0.052010283, 0.44478089 0.1432499 0.051950052, 0.4450146 0.14329961 0.051946685, 0.44395825 0.1430815 -0.068173751, 0.44434908 0.14315805 0.052123204, 0.44436806 0.14316234 0.048183456, 0.4441869 0.14312382 0.048023269, 0.46968934 0.1485548 -0.038886204, 0.46970704 0.14855884 -0.042850181, 0.46984735 0.14858837 -0.038727567, 0.44417539 0.14312108 0.052283153, 0.44404924 0.14309449 0.047823414, 0.46985796 0.14859083 -0.043008015, 0.46996632 0.14861372 -0.038536683, 0.48506516 0.15183046 -0.11110558, 0.44404402 0.143093 0.052480534, 0.46950051 0.14851467 -0.039004609, 0.46952602 0.14852028 -0.042730018, 0.44396171 0.14307556 0.052704051, 0.44396317 0.14307615 0.047595158, 0.46997121 0.14861497 -0.04319568, 0.47004008 0.1486294 -0.038323179, 0.46965247 0.14854343 0.02467148, 0.46981427 0.14857796 0.020672813, 0.46982518 0.14858013 0.024831221, 0.46929052 0.14846997 -0.039076373, 0.46907011 0.14842305 -0.039098158, 0.47004148 0.14862995 -0.043404296, 0.46944776 0.14849982 0.024558052, 0.4696345 0.14853962 0.020832792, 0.4699508 0.14860705 0.020473197, 0.46995592 0.14860797 0.025028095, 0.46942207 0.14849451 0.020943329, 0.47003621 0.14862524 0.020245716, 0.47003749 0.14862527 0.025251135, 0.46918991 0.1484451 0.020998284, 0.44477662 0.14325278 -0.017519221, 0.44504741 0.14331077 -0.021022215, 0.44480926 0.14326003 -0.021018073, 0.44455126 0.14320496 -0.017458454, 0.44457701 0.14321057 -0.021072969, 0.44436473 0.14316548 -0.021183684, 0.4443467 0.14316143 -0.017344937, 0.48503789 0.15182467 -0.11134051, 0.48495716 0.15180752 -0.11156227, 0.48482791 0.15178001 -0.1117586, 0.48465714 0.15174367 -0.1119182, 0.48445436 0.15170059 -0.1120324, 0.48423123 0.15165302 -0.11209486, 0.48399985 0.15160379 -0.11210178, 0.48377338 0.15155561 -0.1120529, 0.44418493 0.14312723 -0.021343544, 0.44417396 0.14312461 -0.017185196, 0.4440482 0.1430981 -0.021543309, 0.44404313 0.14309679 -0.016988173, 0.44515753 0.14333719 -0.075165942, 0.44493702 0.1432903 -0.075134382, 0.44396168 0.14307943 -0.016765222, 0.44396296 0.14307997 -0.021770641, 0.44471529 0.14324312 -0.075154528, 0.444527 0.14319627 0.044289991, 0.44474521 0.1432427 0.04422392, 0.44497249 0.14329118 0.044211283, 0.44450375 0.14319806 -0.075225189, 0.44428226 0.14315076 -0.071178153, 0.44431341 0.14315757 -0.075343207, 0.44432953 0.14315431 0.044405982, 0.44443646 0.14317721 0.040528461, 0.46898744 0.11932257 0.047778353, 0.46948907 0.11914083 0.051316574, 0.46920082 0.11924537 0.047813758, 0.44435659 0.12822996 0.07124646, 0.44435129 0.12823169 0.075050309, 0.44454965 0.12816001 0.074976042, 0.46941611 0.11916742 0.047796473, 0.46962199 0.11909308 0.047727391, 0.44419178 0.12829615 -0.044268444, 0.44415289 0.12830995 -0.040360972, 0.44432136 0.12824908 -0.040482447, 0.4440361 0.12835246 -0.044427559, 0.4440273 0.12834913 0.07096909, 0.4441736 0.12829599 0.075169548, 0.44417724 0.12829484 0.0711274, 0.47009155 0.11892296 0.051860318, 0.4701567 0.11889943 0.052065358, 0.4701539 0.11890063 0.047042742, 0.47017863 0.11889169 0.046814546, 0.48480013 0.11361201 -0.11069836, 0.4849588 0.11355467 -0.11053906, 0.44401285 0.1283606 -0.040203944, 0.48507866 0.11351123 -0.11034511, 0.44391462 0.12838989 0.070779189, 0.44402513 0.12834965 0.075327709, 0.44391868 0.12839498 -0.044620231, 0.48461106 0.1136805 -0.11081459, 0.48515332 0.11348423 -0.11012696, 0.44391361 0.12838997 0.075517222, 0.47017863 0.11889145 0.05228053, 0.44384566 0.1284214 -0.044836298, 0.44390789 0.12839866 -0.040018633, 0.48440182 0.11375614 -0.11088119, 0.44384459 0.12841526 0.070567116, 0.44384289 0.1284221 -0.039813653, 0.48517868 0.11347508 -0.10989641, 0.4438208 0.12842385 0.070343718, 0.44384423 0.12841509 0.075728163, 0.4438208 0.12843038 -0.045064315, 0.48418391 0.11383498 -0.11089478, 0.4438208 0.12843005 -0.03959842, 0.4438208 0.12842365 0.075950429, 0.48396891 0.1139127 -0.11085434, 0.48376837 0.11398517 -0.11076252, 0.46992823 0.11898573 -0.015543476, 0.46995386 0.11897632 -0.01147531, 0.47006437 0.11893657 -0.015745386, 0.46979186 0.11903492 -0.011634693, 0.4697493 0.11905046 -0.015383735, 0.47007635 0.11893196 -0.011279896, 0.47014967 0.11890581 -0.015976563, 0.4695994 0.11910453 -0.01174964, 0.46953896 0.1191266 -0.015275702, 0.48517874 0.11347486 -0.10577179, 0.48515651 0.11348286 -0.10555647, 0.48509136 0.11350638 -0.10535096, 0.48498604 0.11354449 -0.10516559, 0.47015259 0.11890438 -0.011059538, 0.47017869 0.11889519 -0.016223088, 0.44459763 0.12814546 0.025220856, 0.44469115 0.12811141 0.028660432, 0.44492462 0.12802689 0.028672978, 0.46938702 0.11918141 -0.011814073, 0.46930996 0.11920933 -0.015226021, 0.44438854 0.12822108 0.025154188, 0.44446176 0.12819436 0.028709665, 0.47017863 0.1188949 -0.010826454, 0.46916649 0.11926119 -0.01182352, 0.44432288 0.12824169 0.078906193, 0.44499967 0.12799692 0.082705393, 0.44519946 0.12792447 0.082787737, 0.44419938 0.12828951 0.02503787, 0.44425118 0.12827052 0.028817669, 0.44478753 0.1280736 0.082673088, 0.44457397 0.12815088 0.082692847, 0.48484555 0.11359529 -0.1050082, 0.48496649 0.11355141 -0.10075326, 0.44404066 0.12834693 0.024878725, 0.44407186 0.12833543 0.028977409, 0.48467663 0.11365645 -0.1048872, 0.48481277 0.11360697 -0.10091226, 0.44437018 0.12822448 0.082763359, 0.48508242 0.11350948 -0.10056157, 0.44392076 0.12839022 0.024684712, 0.44393536 0.12838471 0.029179499, 0.44418672 0.12829082 0.082881108, 0.4846293 0.11367328 -0.10102995, 0.44415399 0.1283028 0.078784868, 0.48515424 0.11348349 -0.100347, 0.444033 0.12834635 0.083039775, 0.4844254 0.11374711 -0.10110058, 0.44384989 0.12841564 0.029410943, 0.44384608 0.12841731 0.024466559, 0.44401351 0.12835366 0.078627869, 0.48517871 0.11347452 -0.10012047, 0.44391716 0.12838826 0.083231762, 0.44390813 0.12839197 0.078442231, 0.44382086 0.12842612 0.029657826, 0.4438208 0.12842651 0.024236068, 0.48421195 0.11382423 -0.10112019, 0.44384512 0.12841441 0.08344619, 0.48399988 0.11390097 -0.10108779, 0.44384298 0.12841552 0.078237012, 0.48380005 0.11397317 -0.10100518, 0.44475994 0.12809025 -0.036352083, 0.44455326 0.12816481 -0.032886043, 0.44496897 0.12801462 -0.036376879, 0.44455084 0.12816584 -0.036377445, 0.48800302 0.11245292 -0.099474356, 0.48517868 0.11347456 -0.099346325, 0.48801246 0.11244959 -0.099402562, 0.48805031 0.11243585 -0.099288657, 0.4851391 0.11348888 -0.098937824, 0.48807853 0.11242555 -0.099246666, 0.4880282 0.11244383 -0.099340692, 0.44435236 0.12823765 -0.036451593, 0.44435433 0.12823668 -0.032812133, 0.48502189 0.11353122 -0.098546788, 0.48811284 0.1124132 -0.099215105, 0.48483208 0.11359979 -0.09818925, 0.48204529 0.11460754 -0.094010577, 0.44417563 0.12830131 -0.032693133, 0.48183945 0.11468194 -0.093751714, 0.44417432 0.12830202 -0.036570832, 0.44402644 0.12835528 -0.032534823, 0.44116452 0.12938361 0.087564543, 0.44402555 0.12835585 -0.036729142, 0.4438208 0.12842448 0.060511038, 0.44382092 0.12842421 0.062664494, 0.4438208 0.12842312 0.085697159, 0.44384137 0.12841564 0.08590509, 0.44390222 0.12839362 0.086103991, 0.44400057 0.12835798 0.086285308, 0.4441323 0.1283104 0.086440668, 0.4438208 0.12842314 0.083672687, 0.44391418 0.12839584 -0.032344922, 0.46979043 0.11903168 0.056611583, 0.46986821 0.11900325 0.06055446, 0.46995291 0.11897291 0.05645211, 0.4438208 0.12842406 0.068229541, 0.47675636 0.11652012 -0.087220028, 0.47686014 0.11648253 -0.087109193, 0.48132041 0.1148697 -0.093362227, 0.44391373 0.12839626 -0.036918536, 0.44382086 0.12842348 0.078021482, 0.46999958 0.11895573 0.060709909, 0.44116399 0.12938383 0.087599143, 0.44429144 0.12825276 0.086563572, 0.48376843 0.11397272 0.11077653, 0.47663191 0.11656518 -0.087303475, 0.47007605 0.11892834 0.056256577, 0.48799971 0.11244211 0.11632563, 0.44384441 0.12842113 -0.032133475, 0.47233996 0.11810844 0.073761538, 0.47233996 0.11811678 -0.073747024, 0.47017854 0.11889121 0.055802181, 0.4697096 0.11906061 0.060431525, 0.44384435 0.12842138 -0.037129894, 0.47693828 0.11645429 -0.086976543, 0.47017863 0.11889194 0.043265983, 0.47017863 0.11889216 0.037824675, 0.47017863 0.11889246 0.034254178, 0.47017857 0.11889264 0.02883248, 0.47017875 0.11889285 0.025244609, 0.46959725 0.11910152 0.056726441, 0.47017875 0.11889322 0.019837901, 0.47017863 0.1188934 0.016237363, 0.44382086 0.12842958 -0.031910643, 0.47017869 0.1188937 0.010840878, 0.47649303 0.11661533 -0.087355569, 0.47017857 0.11889406 0.0072329193, 0.4438208 0.12843004 -0.0373521, 0.47017857 0.1188942 0.0018413514, 0.47017863 0.11889449 -0.0018268973, 0.47009751 0.1189203 0.06089063, 0.47017857 0.11889473 -0.0072185248, 0.47015259 0.11890066 0.05603604, 0.47017863 0.1188955 -0.019823417, 0.47698689 0.11643672 -0.086828813, 0.47017863 0.11889574 -0.025230274, 0.47017857 0.11889608 -0.028817996, 0.47017857 0.11889623 -0.034239754, 0.47017863 0.11889656 -0.037810132, 0.46983567 0.11901876 -0.0064460486, 0.46996668 0.11897114 -0.0024593025, 0.46998009 0.11896649 -0.0066039413, 0.47017863 0.11889675 -0.043251917, 0.47017854 0.11889695 -0.046800002, 0.47017863 0.11889739 -0.052265897, 0.46953031 0.11912552 0.060346261, 0.47017863 0.11889747 -0.055787697, 0.46894619 0.11933704 0.056752726, 0.46916321 0.11925854 0.056799009, 0.44116449 0.12939349 -0.087548897, 0.46938428 0.11917852 0.056790099, 0.4438208 0.12842478 0.054982945, 0.44382077 0.12842493 0.052794412, 0.46981332 0.11902665 -0.0026181787, 0.4438208 0.1284253 0.04729943, 0.47634694 0.11666818 -0.08737345, 0.46966234 0.11908145 -0.006325826, 0.4438208 0.1284253 0.045079842, 0.4438208 0.12842572 0.039613977, 0.4438208 0.12842576 0.037367538, 0.47008225 0.11892931 -0.0022676438, 0.4438208 0.12842602 0.031926021, 0.47015819 0.11889841 0.061089233, 0.47700325 0.11643085 -0.086673453, 0.4438208 0.12842673 0.02195026, 0.44382077 0.12842695 0.016543612, 0.4438208 0.12842703 0.014245138, 0.47008857 0.11892727 -0.0067913979, 0.44382077 0.12842742 0.008848682, 0.4438208 0.12842749 0.0065425783, 0.4438208 0.12842789 0.0011510402, 0.47698948 0.11643574 -0.086530551, 0.48159555 0.11477023 -0.093533531, 0.4438208 0.12842794 -0.001135394, 0.44382086 0.12842815 -0.0065269619, 0.44382074 0.12842837 -0.0088329762, 0.47017863 0.11889091 0.061296776, 0.46963021 0.11909284 -0.0027358979, 0.44382086 0.12842859 -0.014229551, 0.46946827 0.11915162 -0.0062489659, 0.44382074 0.12842882 -0.016527906, 0.4438208 0.12842904 -0.021934703, 0.4438208 0.12842917 -0.024220541, 0.4438208 0.12842955 -0.029642209, 0.47620073 0.11672111 -0.087356344, 0.47015432 0.11890329 -0.0020532459, 0.44382086 0.12843041 -0.047283962, 0.47694841 0.11645064 -0.086393699, 0.47015586 0.11890292 -0.006999597, 0.44382077 0.12843083 -0.052778825, 0.4438208 0.12843098 -0.054967508, 0.44382074 0.12843134 -0.060495451, 0.46956977 0.11911845 -0.069365337, 0.44509283 0.12797114 -0.059559658, 0.46890685 0.11935803 -0.06570895, 0.44439217 0.12822476 -0.063568607, 0.46886921 0.1193721 -0.07467635, 0.44513029 0.12795798 -0.067294464, 0.47202748 0.1182301 -0.079500362, 0.44435647 0.1282381 -0.071230903, 0.47606161 0.11677136 -0.087305412, 0.4451659 0.12794556 -0.07503207, 0.46942654 0.11916654 -0.0028067082, 0.46948901 0.11914667 -0.05130206, 0.44501194 0.12799956 -0.044100687, 0.46898758 0.1193279 -0.047763839, 0.44446924 0.12819606 -0.048234656, 0.46894625 0.1193433 -0.056738272, 0.44505319 0.12798497 -0.051828161, 0.46926323 0.11922576 -0.0062187761, 0.46953028 0.11913227 -0.060331747, 0.44442961 0.12821075 -0.05590333, 0.44432285 0.12825064 -0.078890637, 0.44519949 0.12793379 -0.082772449, 0.44455323 0.12816104 0.032901362, 0.44475999 0.12808602 0.036367729, 0.44496909 0.12801047 0.036392376, 0.44459769 0.12814829 -0.02520524, 0.46907476 0.11929525 -0.029802784, 0.44492462 0.12803018 -0.028657392, 0.46944621 0.11916162 -0.042276338, 0.46903047 0.11931182 -0.038785592, 0.44451037 0.12818068 -0.040562227, 0.46940181 0.11917713 -0.033254996, 0.44509271 0.12796441 0.059575126, 0.46956977 0.1191107 0.069379762, 0.4689067 0.11935078 0.065723613, 0.44435421 0.12823305 0.03282769, 0.4445509 0.12816161 0.036392882, 0.46886912 0.11936374 0.074690983, 0.44439211 0.12821764 0.063583985, 0.44513029 0.12795042 0.067309842, 0.47202739 0.11822113 0.079514667, 0.47606167 0.11676152 0.087319598, 0.44516584 0.12793715 0.075047687, 0.47688201 0.1164746 -0.086268529, 0.44501194 0.12799457 0.044116125, 0.44446906 0.12819073 0.048250213, 0.44505316 0.1279792 0.051843837, 0.44442961 0.12820445 0.055918768, 0.48380008 0.11396182 0.10101916, 0.44417563 0.12829766 0.032708749, 0.44435236 0.12823348 0.03646706, 0.48132041 0.11485921 0.093376234, 0.46921334 0.11924368 -0.0028265566, 0.46907476 0.11929192 0.029817268, 0.46944603 0.11915687 0.04229106, 0.46903041 0.11930755 0.038799927, 0.44451049 0.12817606 0.040577784, 0.46940181 0.11917344 0.033269629, 0.48467645 0.11364463 0.10490097, 0.44402638 0.12835164 0.03255029, 0.44417435 0.12829785 0.036586359, 0.4439142 0.12839219 0.032360628, 0.44402561 0.1283516 0.036744639, 0.47334823 0.11775216 -0.077076182, 0.47282341 0.11794229 -0.080182746, 0.47259912 0.11802338 -0.079904512, 0.47233078 0.11812039 -0.079674408, 0.47279677 0.11795165 -0.076043442, 0.44391388 0.12839212 0.036934182, 0.44384447 0.12841748 0.032149002, 0.44469115 0.12811467 -0.028645024, 0.44446191 0.12819764 -0.028694257, 0.46975651 0.11905126 -0.074591026, 0.47245413 0.11807555 -0.074912295, 0.46993253 0.11898753 -0.074431136, 0.44384435 0.12841721 0.037145212, 0.47006646 0.11893906 -0.074230328, 0.46954921 0.11912622 -0.07470049, 0.44425115 0.12827381 -0.028802142, 0.44438854 0.12822387 -0.025138721, 0.47015005 0.11890875 -0.07400091, 0.46932289 0.11920801 -0.074752644, 0.44407198 0.12833862 -0.028961971, 0.44419959 0.12829223 -0.025022641, 0.47017863 0.11889848 -0.07375662, 0.46909156 0.1192918 -0.074744299, 0.44393533 0.12838809 -0.029163823, 0.44404075 0.12834971 -0.024863079, 0.47017863 0.11889829 -0.070301041, 0.47015122 0.1189082 -0.070061311, 0.44384989 0.12841898 -0.029395327, 0.44392079 0.12839313 -0.024669304, 0.44384611 0.12842004 -0.024451151, 0.4699412 0.1189841 -0.069636926, 0.46994272 0.11898336 -0.065435722, 0.47007045 0.11893745 -0.069835618, 0.46977097 0.11904573 -0.069477066, 0.46977338 0.11904462 -0.065595582, 0.47007117 0.11893693 -0.065237477, 0.46957293 0.11911716 -0.065707758, 0.4693563 0.11919311 -0.024238065, 0.44487932 0.12804614 -0.020942643, 0.46912017 0.11927836 -0.020815447, 0.47015139 0.11890796 -0.065012202, 0.46935314 0.11919658 -0.065765724, 0.46977326 0.11903736 0.065609917, 0.46994135 0.11897635 0.06965144, 0.4699426 0.1189761 0.065450206, 0.47017863 0.11889805 -0.064773276, 0.46912685 0.11927845 -0.065766081, 0.46957293 0.11910982 0.065722004, 0.46977106 0.11903784 0.069491699, 0.47017863 0.11889784 -0.061282322, 0.47007051 0.11892954 0.069850042, 0.47007111 0.11892965 0.065251902, 0.46981338 0.11902639 0.0026325732, 0.46983561 0.11901805 0.0064606518, 0.46996686 0.11897083 0.0024737567, 0.46912667 0.11927107 0.065780595, 0.46935317 0.11918911 0.065780148, 0.46998003 0.1189658 0.0066182762, 0.47008237 0.118929 0.0022821873, 0.46966228 0.11908077 0.0063402802, 0.47015122 0.11890025 0.070075944, 0.47015139 0.11890067 0.065026805, 0.46963015 0.11909264 0.0027505308, 0.47008851 0.11892667 0.0068059117, 0.47015426 0.11890301 0.0020676404, 0.46946833 0.11915095 0.0062633008, 0.46942666 0.11916621 0.0028212517, 0.47015581 0.11890222 0.0070139617, 0.44479868 0.1280717 0.04408066, 0.46926323 0.1192251 0.0062333494, 0.46921334 0.11924337 0.0028409511, 0.4445833 0.12814964 0.044097856, 0.47017863 0.11889073 0.064787701, 0.47017869 0.1188903 0.070315585, 0.44464305 0.12813145 -0.017520115, 0.44465193 0.12812844 -0.020941541, 0.44443092 0.12820832 -0.020998523, 0.44429132 0.12826255 -0.086548045, 0.44116399 0.12939371 -0.087583765, 0.44413224 0.12832004 -0.086425051, 0.444424 0.12821065 -0.017461464, 0.44384137 0.12842527 -0.085889742, 0.44382074 0.12843266 -0.085681751, 0.44422922 0.12828124 -0.021110103, 0.44437745 0.12822406 0.044166937, 0.44390211 0.12840329 -0.086088732, 0.44400063 0.12836763 -0.086269692, 0.44422427 0.12828289 -0.01734893, 0.44432139 0.12824447 0.040497795, 0.44405863 0.12834303 -0.021270052, 0.44419178 0.12829119 0.04428421, 0.46986821 0.11901002 -0.060539916, 0.469953 0.11897917 -0.056437656, 0.46999946 0.1189626 -0.060695484, 0.44405568 0.12834385 -0.01718919, 0.44415286 0.12830541 0.040376619, 0.44392911 0.12838991 -0.021468684, 0.46979037 0.119038 -0.056597248, 0.46970943 0.11906748 -0.060417011, 0.44403622 0.12834744 0.044443265, 0.47007599 0.11893472 -0.056242123, 0.44401273 0.12835626 0.04021959, 0.47009751 0.11892723 -0.060876265, 0.44392774 0.12839019 -0.016991243, 0.44384828 0.1284191 -0.021694705, 0.46959725 0.1191078 -0.056711957, 0.44391862 0.12838987 0.044635788, 0.44390783 0.12839411 0.040034339, 0.47015253 0.11890694 -0.056021348, 0.47015813 0.11890526 -0.061074808, 0.44384789 0.12841897 -0.016766444, 0.46938422 0.11918488 -0.056775436, 0.4438456 0.12841621 0.044851914, 0.44384286 0.1284177 0.03982906, 0.46916321 0.11926483 -0.056784466, 0.4438208 0.12843263 -0.083657101, 0.44384524 0.12842375 -0.083430842, 0.44483286 0.12806253 -0.013232574, 0.47017863 0.11889026 0.073771015, 0.47015014 0.11890051 0.074015483, 0.4724541 0.11806709 0.07492651, 0.4700664 0.11893085 0.074244842, 0.46993253 0.11897919 0.074445561, 0.46975648 0.11904284 0.07460545, 0.47279671 0.11794309 0.076057866, 0.46979192 0.11903356 0.011649206, 0.46992806 0.11898415 0.015558019, 0.46995392 0.118975 0.011489615, 0.46974924 0.11904879 0.0153981, 0.46959946 0.1191031 0.011764154, 0.47006437 0.1189349 0.015759781, 0.46954915 0.11911783 0.074714735, 0.47007641 0.11893068 0.01129438, 0.44499967 0.1280061 -0.082690075, 0.44478762 0.12808274 -0.082657531, 0.44457403 0.12816004 -0.0826772, 0.44437024 0.12823382 -0.082747653, 0.4695389 0.1191249 0.015290096, 0.44418687 0.12830018 -0.082865581, 0.46938708 0.11917993 0.011828288, 0.47014961 0.11890389 0.015991077, 0.47015265 0.11890312 0.011074141, 0.4441539 0.12831183 -0.078769401, 0.44403309 0.12835565 -0.083024368, 0.46930996 0.11920767 0.015240416, 0.46916643 0.11925976 0.011838034, 0.44401351 0.12836254 -0.078612283, 0.44391719 0.1283976 -0.083216146, 0.44461235 0.12814228 -0.01324223, 0.44468933 0.12811427 -0.0098299533, 0.44390813 0.12840073 -0.078426823, 0.44439992 0.12821905 -0.013306394, 0.44446042 0.12819715 -0.0097804815, 0.44384292 0.12842429 -0.078221425, 0.44425014 0.1282731 -0.0096723884, 0.44420752 0.12828867 -0.013421282, 0.44382077 0.12843226 -0.078005865, 0.44404557 0.12834731 -0.013580933, 0.44407123 0.12833783 -0.009512648, 0.472599 0.11801443 0.079919115, 0.47282338 0.11793323 0.080197111, 0.47334823 0.11774352 0.077090606, 0.44393501 0.12838705 -0.0093107671, 0.44392309 0.12839167 -0.013776258, 0.4723306 0.11811142 0.079688832, 0.44382074 0.12843217 -0.075934604, 0.46909162 0.11928329 0.074758962, 0.46932301 0.11919959 0.074767217, 0.44384983 0.12841783 -0.0090795606, 0.44384679 0.12841924 -0.013996497, 0.44483629 0.12805764 0.051797524, 0.46984664 0.11901726 -0.051503405, 0.46996334 0.11897489 -0.047436699, 0.46998671 0.11896665 -0.051660404, 0.44461522 0.12813756 0.051806346, 0.46980771 0.11903124 -0.047595844, 0.46967813 0.11907829 -0.05138208, 0.47008076 0.11893246 -0.047244236, 0.47009155 0.11892878 -0.051845774, 0.47688201 0.116465 0.086282834, 0.44478619 0.12807898 -0.005527392, 0.46962205 0.11909844 -0.047712907, 0.47015384 0.11890593 -0.047028109, 0.47015658 0.11890535 -0.052050754, 0.46941611 0.11917283 -0.047782049, 0.44428995 0.12825549 0.048164859, 0.44440228 0.12821467 0.051870093, 0.46920082 0.11925068 -0.047799245, 0.44420913 0.12828454 0.051984861, 0.46994075 0.11897923 0.020502701, 0.46994367 0.11897793 0.024583504, 0.47007033 0.11893249 0.02030389, 0.44413123 0.12831289 0.048041955, 0.4449673 0.12801729 -0.074958995, 0.44475842 0.12809296 -0.074934795, 0.44454962 0.12816848 -0.074960425, 0.44435135 0.12824009 -0.075034842, 0.46977499 0.11903891 0.024423763, 0.46977022 0.11904088 0.020662531, 0.47007173 0.1189315 0.024781451, 0.44417718 0.12830296 -0.071112052, 0.4441736 0.12830447 -0.075154051, 0.44404653 0.1283433 0.052144513, 0.4701511 0.11890323 0.020077959, 0.44399992 0.12836044 0.047886834, 0.44473621 0.12809689 -0.0021351725, 0.44402733 0.12835723 -0.070953742, 0.44402525 0.12835816 -0.075312361, 0.4445729 0.1281561 -0.0055473, 0.46956858 0.11911385 0.020774201, 0.46957543 0.11911115 0.02431111, 0.48811287 0.1124021 0.099228755, 0.47694847 0.11644098 0.086407885, 0.47015157 0.11890265 0.02500616, 0.44391456 0.12839788 -0.070763573, 0.44391361 0.12839851 -0.075501695, 0.46935639 0.11919038 0.024252698, 0.46912017 0.11927602 0.02083002, 0.46934751 0.11919376 0.020831183, 0.44436935 0.12822978 -0.0056181103, 0.44453111 0.12817103 -0.0021050423, 0.44384423 0.12842362 -0.075712666, 0.44384459 0.12842326 -0.070551619, 0.4439235 0.12838784 0.052340105, 0.44418606 0.12829606 -0.0057358593, 0.44433722 0.12824117 -0.0020281225, 0.44390193 0.12839584 0.047705814, 0.4438208 0.12843181 -0.07032837, 0.44403276 0.12835152 -0.0058947653, 0.44416383 0.12830387 -0.0019079298, 0.44391707 0.1283934 -0.0060864538, 0.44401935 0.12835607 -0.0017501265, 0.44384524 0.1284194 -0.0063009113, 0.44391087 0.12839535 -0.0015625805, 0.44384691 0.12841545 0.052560762, 0.44384363 0.1284197 -0.0013542026, 0.44384125 0.12841786 0.047507003, 0.4438208 0.12843166 -0.068214133, 0.46982393 0.11902496 -0.042469248, 0.46982518 0.11902437 -0.038591459, 0.46997312 0.11897102 -0.042627558, 0.46997383 0.11897053 -0.038433328, 0.47008529 0.11893047 -0.042817429, 0.46964517 0.11908959 -0.042350098, 0.46964714 0.11908881 -0.038710639, 0.48183945 0.11467139 0.09376578, 0.47008559 0.11893018 -0.038243666, 0.47015503 0.11890532 -0.043028906, 0.48204535 0.11459693 0.094024494, 0.46944854 0.11916056 -0.038784906, 0.48159555 0.11475961 0.093547627, 0.47698936 0.1164261 0.086544767, 0.47015509 0.11890498 -0.038032427, 0.47700331 0.11642106 0.086687639, 0.47620079 0.11671123 0.087370858, 0.47634706 0.11665826 0.087387666, 0.4692395 0.11923614 -0.038810179, 0.47649315 0.11660548 0.087369666, 0.47663197 0.11655524 0.08731769, 0.47675636 0.11651026 0.087234244, 0.47686014 0.11647271 0.087123349, 0.47693822 0.11644442 0.086990938, 0.47698683 0.11642702 0.086843118, 0.48483208 0.11358874 0.098203227, 0.48502186 0.11352004 0.098560765, 0.48807847 0.11241458 0.099260405, 0.44490781 0.1280385 -0.067226365, 0.44467655 0.12812214 -0.067218289, 0.44445035 0.12820385 -0.067270264, 0.44424289 0.12827896 -0.067379788, 0.44478616 0.12807834 0.0055430084, 0.44473621 0.1280966 0.0021507293, 0.44420204 0.12829347 -0.063452795, 0.44406685 0.12834273 -0.067539528, 0.44457284 0.12815554 0.0055628568, 0.44404224 0.1283513 -0.063293472, 0.48513907 0.11347777 0.098951802, 0.48805031 0.11242479 0.099302426, 0.44393304 0.12839106 -0.067740396, 0.48802811 0.11243284 0.099354371, 0.48801234 0.1124385 0.09941639, 0.4445312 0.1281708 0.0021207184, 0.44436932 0.12822907 0.0056333691, 0.44392154 0.12839498 -0.063099101, 0.4438493 0.1284214 -0.067969754, 0.44433722 0.12824094 0.0020436794, 0.44418606 0.12829535 0.0057513863, 0.44384632 0.12842211 -0.062880263, 0.44416395 0.12830362 0.0019233674, 0.4440327 0.12835084 0.0059101731, 0.4438208 0.12843139 -0.062648878, 0.44401935 0.12835588 0.0017656535, 0.48517868 0.11346328 0.099360153, 0.48800302 0.11244184 0.099488243, 0.46992752 0.11898354 0.029512748, 0.46995881 0.1189719 0.03361164, 0.47006407 0.11893401 0.029310808, 0.48799974 0.11244307 0.099569485, 0.46980003 0.11902936 0.033452228, 0.46974829 0.11904831 0.029672638, 0.47007868 0.11892854 0.033805534, 0.47014955 0.11890317 0.029079303, 0.48517874 0.11346319 0.10013445, 0.46953753 0.11912458 0.029780433, 0.4696109 0.11909775 0.033336207, 0.48515436 0.11347204 0.10036094, 0.48508236 0.11349806 0.10057555, 0.44391719 0.12839268 0.0061018616, 0.44391093 0.12839507 0.0015780181, 0.47015336 0.11890158 0.034023687, 0.48496643 0.11353996 0.10076727, 0.46930835 0.11920741 0.029829755, 0.44384512 0.12841867 0.0063163191, 0.44384357 0.12841952 0.0013698786, 0.46979991 0.11903319 -0.033437744, 0.46992752 0.11898677 -0.029498205, 0.46995875 0.11897579 -0.033597097, 0.46961096 0.11910148 -0.033321604, 0.46974829 0.11905164 -0.029658064, 0.47006407 0.11893746 -0.029296264, 0.47007862 0.11893238 -0.033790991, 0.46953759 0.11912784 -0.029765949, 0.44487271 0.12804402 0.059517995, 0.47014955 0.11890653 -0.029064879, 0.4701533 0.11890547 -0.034009203, 0.46930835 0.11921075 -0.029815182, 0.44464627 0.12812588 0.059518471, 0.44422844 0.12827729 0.05580698, 0.44442657 0.12820543 0.059576556, 0.44487277 0.12805067 -0.059502557, 0.44464633 0.12813255 -0.059502885, 0.44442645 0.12821212 -0.059560969, 0.44422612 0.12827793 0.059688523, 0.44405815 0.12833892 0.05564709, 0.44422612 0.12828459 -0.059673056, 0.44422847 0.12828349 -0.055791393, 0.44405684 0.12833914 0.059848502, 0.44392899 0.12838563 0.055448487, 0.44405809 0.12834516 -0.055631652, 0.44405678 0.12834588 -0.059832886, 0.44392827 0.12838565 0.060046688, 0.44384819 0.12841479 0.055222735, 0.44392827 0.12839235 -0.06003125, 0.44392887 0.12839191 -0.05543299, 0.44384813 0.12841456 0.060271874, 0.4438481 0.12842134 -0.060256377, 0.44384822 0.12842093 -0.055207238, 0.44483289 0.12806104 0.013248071, 0.44468942 0.12811312 0.0098456293, 0.4848128 0.11359565 0.10092618, 0.48484552 0.11358352 0.1050223, 0.48498604 0.11353269 0.10517927, 0.48399988 0.11388952 0.10110177, 0.48421189 0.11381291 0.10113417, 0.48442551 0.11373568 0.10111453, 0.44446051 0.12819585 0.0097960383, 0.44461235 0.12814078 0.013257846, 0.4846293 0.11366193 0.10104395, 0.48509136 0.11349455 0.10536493, 0.4442502 0.12827192 0.0096879154, 0.44439998 0.12821761 0.013321832, 0.48515651 0.11347093 0.1055703, 0.44420752 0.12828724 0.013436779, 0.44407138 0.1283367 0.009528026, 0.48517874 0.1134629 0.10578559, 0.44393507 0.12838602 0.0093263537, 0.44404557 0.12834588 0.013596281, 0.44384977 0.12841688 0.0090949684, 0.44392309 0.1283901 0.013791665, 0.44384667 0.12841764 0.014012054, 0.46982515 0.11902007 0.038605973, 0.469973 0.11896636 0.042642042, 0.46997371 0.11896624 0.038447663, 0.46982393 0.11902025 0.042483583, 0.46964708 0.11908449 0.038725212, 0.47008538 0.11892569 0.042832002, 0.48517862 0.11346266 0.10991023, 0.47008565 0.11892584 0.03825824, 0.46964517 0.11908485 0.042364731, 0.44490787 0.12803082 0.067241892, 0.44483629 0.12806353 -0.051782116, 0.44461522 0.12814339 -0.051790908, 0.46944854 0.11915624 0.03879939, 0.44440219 0.12822059 -0.051854625, 0.47015491 0.11890054 0.043043271, 0.47015503 0.11890066 0.03804712, 0.44420901 0.12829044 -0.051969364, 0.44428992 0.12826082 -0.048149392, 0.4692395 0.11923186 0.038824812, 0.44467649 0.12811457 0.067233697, 0.44404653 0.1283492 -0.052128926, 0.44413117 0.12831824 -0.048026487, 0.4444502 0.1281964 0.06728588, 0.46977505 0.1190417 -0.0244091, 0.46994081 0.11898161 -0.020488217, 0.46994373 0.11898069 -0.0245689, 0.46977016 0.11904326 -0.020648077, 0.46957549 0.11911394 -0.024296626, 0.47007024 0.11893475 -0.020289645, 0.4442021 0.12828638 0.063468412, 0.44424284 0.12827139 0.067395106, 0.4700717 0.11893441 -0.024766907, 0.46956846 0.11911623 -0.020759657, 0.4701511 0.11890545 -0.020063534, 0.47015151 0.11890557 -0.024991706, 0.44404224 0.12834418 0.063308969, 0.44406697 0.128335 0.067555144, 0.44399998 0.12836577 -0.047871098, 0.4439235 0.12839368 -0.052324399, 0.46934748 0.11919613 -0.020816609, 0.44392154 0.12838782 0.063114718, 0.44393298 0.12838353 0.067756012, 0.44464305 0.12812942 0.017535523, 0.44487926 0.1280438 0.0209582, 0.44390193 0.12840125 -0.047690347, 0.44384685 0.12842141 -0.052545205, 0.44384632 0.12841503 0.062895879, 0.44384924 0.12841375 0.067985371, 0.44384143 0.12842306 -0.047491655, 0.44465199 0.12812606 0.020956948, 0.44443092 0.12820598 0.02101393, 0.44442397 0.12820867 0.01747705, 0.48396885 0.11390024 0.11086832, 0.48418391 0.11382264 0.11090846, 0.48440179 0.11374365 0.11089517, 0.484611 0.11366805 0.1108285, 0.48479995 0.11359964 0.11071242, 0.48495868 0.11354229 0.11055262, 0.48507872 0.1134989 0.11035888, 0.48515341 0.11347184 0.11014079, 0.44422445 0.12828082 0.017364517, 0.44422919 0.12827891 0.02112563, 0.44405577 0.12834194 0.017204776, 0.44405869 0.12834062 0.021285579, 0.44392774 0.12838824 0.017006829, 0.44392917 0.12838745 0.021484211, 0.44384795 0.12841704 0.01678209, 0.44384834 0.12841664 0.021710321, 0.44496724 0.12800889 0.074974611, 0.46980777 0.11902578 0.047610417, 0.46984655 0.11901149 0.051517949, 0.46996334 0.11896959 0.047451273, 0.46998665 0.11896087 0.051675007, 0.44475827 0.12808456 0.074950203, 0.47008088 0.11892709 0.047258601, 0.46967816 0.11907253 0.051396504, 0.44479856 0.1280767 -0.044065282, 0.44458333 0.1281545 -0.044082388, 0.44437739 0.12822899 -0.04415141, 0.47636303 0.11612092 0.086687461, 0.47635901 0.11612239 0.086646751, 0.4763473 0.11612664 0.08660768, 0.47632834 0.11613347 0.086572036, 0.47636294 0.1161308 -0.086673453, 0.47635832 0.11613245 -0.086717799, 0.47634444 0.1161374 -0.086760119, 0.47632217 0.11614549 -0.086797938, 0.47629246 0.11615627 -0.086829737, 0.47625685 0.1161691 -0.086853608, 0.4762173 0.11618346 -0.086868271, 0.47617546 0.11619857 -0.086873427, 0.47613367 0.11621358 -0.086868539, 0.47609398 0.116228 -0.086853936, 0.47226983 0.11761077 -0.080472305, 0.47190028 0.11774446 -0.080090716, 0.47210154 0.11767174 -0.080263332, 0.4716728 0.11782677 -0.079960063, 0.47635898 0.11613216 -0.086632624, 0.47634736 0.1161363 -0.086593404, 0.47632834 0.11614321 -0.086557731, 0.44477573 0.12755449 -0.067754224, 0.44454882 0.12763664 -0.067716196, 0.44466445 0.1275948 -0.067720249, 0.44443569 0.12767759 -0.067742333, 0.444244 0.12774679 -0.06787689, 0.44433188 0.1277151 -0.067796931, 0.44417706 0.12777115 -0.067977265, 0.44412091 0.12779142 -0.068214133, 0.44413522 0.12778629 -0.068091974, 0.44412085 0.12779158 -0.07032837, 0.44438878 0.12769473 -0.070779666, 0.44416782 0.1277746 -0.070546016, 0.44413278 0.12778731 -0.070440009, 0.44429913 0.12772714 -0.070720181, 0.44422415 0.1277542 -0.070640936, 0.44412097 0.1277879 -0.0065270513, 0.44413319 0.12778351 -0.0064139217, 0.44416907 0.12777054 -0.0063067824, 0.44422689 0.12774968 -0.0062109381, 0.44430357 0.12772183 -0.0061315447, 0.44439521 0.12768875 -0.0060725361, 0.44449696 0.12765191 -0.0060372204, 0.44460365 0.12761328 -0.0060272068, 0.44412091 0.1277881 -0.0088329762, 0.44417807 0.12776747 -0.0090719014, 0.44413549 0.12778284 -0.0089562386, 0.4442462 0.12774277 -0.0091727823, 0.44433564 0.12771048 -0.0092527717, 0.44455525 0.12763102 -0.0093315095, 0.44444069 0.1276724 -0.0093067437, 0.46908066 0.11876012 -0.0067185909, 0.46928015 0.11868796 -0.0067721158, 0.46918318 0.11872306 -0.006733641, 0.46936688 0.11865665 -0.0068323463, 0.46943918 0.11863051 -0.0069112629, 0.46952698 0.11859877 -0.0071091205, 0.46949339 0.11861086 -0.0070049316, 0.46953836 0.11859454 -0.007218346, 0.46903226 0.11877789 -0.011324987, 0.46953842 0.11859481 -0.010826454, 0.46952537 0.1185995 -0.01094304, 0.46924874 0.11869964 -0.011288151, 0.46914259 0.11873803 -0.011320189, 0.46948722 0.11861327 -0.011053219, 0.469345 0.11866476 -0.011230484, 0.46942604 0.11863554 -0.011150882, 0.46953842 0.1185953 -0.019823417, 0.46952471 0.11860029 -0.019943431, 0.46948418 0.118615 -0.020056531, 0.46941951 0.11863843 -0.020155832, 0.46933416 0.11866929 -0.020235762, 0.4692333 0.11870578 -0.020291612, 0.4691228 0.11874571 -0.020320103, 0.46900919 0.11878678 -0.020319417, 0.44413397 0.12778373 -0.014113083, 0.44417202 0.1277699 -0.014003024, 0.44423339 0.12774774 -0.013905302, 0.44431427 0.12771845 -0.013825551, 0.44451675 0.12764518 -0.013735965, 0.44441059 0.12768361 -0.013767913, 0.44412097 0.12778839 -0.01422967, 0.44462702 0.12760529 -0.013731137, 0.44412091 0.12778851 -0.016528025, 0.44417438 0.12776919 -0.016759649, 0.4441345 0.12778366 -0.016647354, 0.44432271 0.12771551 -0.016938552, 0.44423839 0.12774608 -0.016858593, 0.44442257 0.12767947 -0.016994849, 0.4445321 0.12763982 -0.017024055, 0.46910408 0.11875217 -0.015724644, 0.46952388 0.11860038 -0.016099915, 0.46921858 0.11871076 -0.01574932, 0.46932372 0.1186728 -0.015803471, 0.46941313 0.11864039 -0.015883222, 0.46948126 0.11861584 -0.015984312, 0.46953836 0.11859514 -0.016223088, 0.44412091 0.12778881 -0.021934703, 0.44413474 0.12778373 -0.021814689, 0.44417509 0.12776919 -0.021701708, 0.44423994 0.12774573 -0.021602407, 0.44432518 0.12771495 -0.021522418, 0.44442591 0.12767845 -0.021466449, 0.4445366 0.12763846 -0.021438137, 0.44465008 0.12759732 -0.021438673, 0.46942094 0.11863814 -0.024899587, 0.46923682 0.11870465 -0.02476345, 0.4693366 0.11866863 -0.024819776, 0.46948484 0.11861505 -0.02499862, 0.46912739 0.11874434 -0.024734125, 0.46952489 0.1186005 -0.025110975, 0.46953842 0.11859557 -0.025230125, 0.46948114 0.11861661 -0.02905722, 0.46941283 0.11864141 -0.0291581, 0.46952388 0.1186011 -0.028941378, 0.46932319 0.11867364 -0.02923806, 0.46921781 0.11871172 -0.029291973, 0.46910328 0.11875325 -0.029316649, 0.46953842 0.11859581 -0.028817996, 0.46898642 0.11879557 -0.02931042, 0.44412097 0.12778884 -0.02422069, 0.4445093 0.12764844 -0.024712875, 0.44440493 0.12768622 -0.024679676, 0.44417092 0.12777092 -0.024444893, 0.44413361 0.12778442 -0.024335817, 0.44431034 0.12772048 -0.024621591, 0.44423088 0.12774919 -0.02454184, 0.46953836 0.11859633 -0.037810132, 0.46952662 0.11860064 -0.037921444, 0.46949193 0.11861315 -0.038026944, 0.46943596 0.11863336 -0.038121745, 0.46936163 0.11866029 -0.0382009, 0.46927255 0.11869252 -0.038260475, 0.4691734 0.11872841 -0.038297668, 0.4690688 0.11876626 -0.038310245, 0.46896428 0.11880398 -0.038297787, 0.46942842 0.11863589 -0.033918485, 0.46948841 0.11861417 -0.034015462, 0.46934906 0.11866458 -0.033838764, 0.46925464 0.11869879 -0.033780828, 0.46953842 0.11859599 -0.034239754, 0.46915019 0.11873657 -0.033747301, 0.46952572 0.11860076 -0.034124538, 0.44455615 0.12763184 -0.029143587, 0.44433615 0.12771136 -0.029222146, 0.44444153 0.12767327 -0.029168114, 0.44417819 0.12776853 -0.029403076, 0.4442465 0.12774381 -0.029302225, 0.44413555 0.12778394 -0.029518858, 0.44467294 0.12758954 -0.029149905, 0.44412091 0.12778917 -0.029642209, 0.44412097 0.12778941 -0.031910524, 0.44448718 0.12765692 -0.032398239, 0.4443877 0.12769291 -0.032361403, 0.44413278 0.12778513 -0.032022133, 0.44416764 0.12777248 -0.032127842, 0.44429836 0.12772524 -0.032302007, 0.44422373 0.1277522 -0.032222614, 0.46953836 0.11859684 -0.046800181, 0.46952596 0.11860138 -0.046914145, 0.46948954 0.11861454 -0.047022179, 0.46943077 0.11863579 -0.04711847, 0.46935293 0.11866394 -0.047197923, 0.46926007 0.11869755 -0.047256455, 0.46915719 0.11873469 -0.047291026, 0.46904945 0.11877376 -0.047299787, 0.46894291 0.11881223 -0.047281846, 0.4693611 0.11866073 -0.042860553, 0.4695265 0.11860093 -0.043140307, 0.46927163 0.11869314 -0.042800948, 0.46943566 0.11863369 -0.042939708, 0.46949181 0.1186135 -0.043034598, 0.4695383 0.11859658 -0.043251678, 0.46917209 0.11872914 -0.042764112, 0.44448599 0.1276575 -0.036864683, 0.44429764 0.12772578 -0.036961421, 0.44438669 0.12769355 -0.036901817, 0.44459054 0.12761974 -0.036852047, 0.44416741 0.12777291 -0.037135378, 0.44412091 0.12778969 -0.037352219, 0.44413278 0.12778543 -0.037240997, 0.44422337 0.12775266 -0.037040517, 0.44469512 0.12758197 -0.036864534, 0.44412103 0.12778978 -0.03959842, 0.44446573 0.12766515 -0.040080503, 0.44437119 0.12769935 -0.040040389, 0.44413194 0.12778588 -0.039706007, 0.44416448 0.1277741 -0.039808556, 0.44428697 0.12772974 -0.039979711, 0.444217 0.12775519 -0.039901271, 0.44412097 0.12779012 -0.045064494, 0.44413325 0.12778561 -0.044950321, 0.44416988 0.12777247 -0.044842288, 0.44422859 0.12775119 -0.044745997, 0.44430643 0.12772299 -0.044666484, 0.44439933 0.12768944 -0.044607863, 0.4445022 0.12765214 -0.044573411, 0.44460979 0.12761332 -0.044564709, 0.44471648 0.12757467 -0.044582561, 0.46937236 0.11865725 -0.051884547, 0.46919355 0.11872181 -0.051784143, 0.46928814 0.11868778 -0.051823989, 0.46944234 0.11863199 -0.051963106, 0.46949485 0.11861292 -0.05205594, 0.46952733 0.11860117 -0.05215843, 0.4695383 0.11859718 -0.052265897, 0.46948704 0.11861594 -0.056014821, 0.46942559 0.11863823 -0.056112692, 0.46952537 0.11860207 -0.055904523, 0.46934423 0.11866756 -0.056192443, 0.46924773 0.1187025 -0.056249872, 0.46914116 0.11874102 -0.056281582, 0.46903065 0.11878102 -0.056286111, 0.46953836 0.11859734 -0.055787697, 0.46892223 0.11882026 -0.056263104, 0.44412091 0.12779018 -0.047283962, 0.44444522 0.12767296 -0.04775928, 0.44435552 0.12770541 -0.047716722, 0.44413117 0.12778655 -0.047387913, 0.44421056 0.12775786 -0.047577634, 0.44416156 0.12777551 -0.047487184, 0.44427618 0.12773414 -0.047655359, 0.46953836 0.11859785 -0.064773276, 0.46952465 0.11860286 -0.064892724, 0.46948466 0.11861731 -0.065005258, 0.4694204 0.11864056 -0.06510444, 0.46933571 0.11867115 -0.06518434, 0.46923551 0.1187074 -0.065240487, 0.46912572 0.11874723 -0.065269426, 0.46901244 0.11878811 -0.065269664, 0.46890244 0.11882785 -0.065241084, 0.46949789 0.11861232 -0.061079338, 0.46952805 0.1186014 -0.06117864, 0.46944878 0.11863008 -0.060988978, 0.46930388 0.11868258 -0.060849801, 0.4695383 0.11859772 -0.061282322, 0.46921417 0.11871491 -0.060807183, 0.46938321 0.1186538 -0.060911253, 0.44462869 0.12760693 -0.05228056, 0.44441161 0.12768538 -0.052316651, 0.44451806 0.12764691 -0.052284941, 0.4442338 0.12774976 -0.052453861, 0.44431496 0.1277204 -0.05237411, 0.44417223 0.12777193 -0.052551642, 0.44412082 0.12779061 -0.052778825, 0.44413403 0.12778585 -0.052662, 0.44473711 0.12756766 -0.052303568, 0.44412091 0.1277906 -0.054967508, 0.44442537 0.12768057 -0.055435434, 0.44413462 0.12778567 -0.055087462, 0.44417498 0.12777114 -0.055200234, 0.44432476 0.12771702 -0.055379525, 0.44423965 0.12774774 -0.055299625, 0.44440666 0.12768784 -0.063108698, 0.44431153 0.1277222 -0.063050821, 0.44423175 0.12775105 -0.06297113, 0.44417122 0.12777294 -0.062874034, 0.44413361 0.12778658 -0.0627646, 0.44412091 0.12779112 -0.062648878, 0.46941969 0.11864106 -0.069969043, 0.46923396 0.11870822 -0.069833264, 0.46933457 0.11867189 -0.069889203, 0.4694843 0.11861774 -0.070068493, 0.46952465 0.11860311 -0.070181206, 0.46953836 0.11859819 -0.070301041, 0.46952417 0.1186036 -0.073878869, 0.46948221 0.1186187 -0.073993549, 0.46953842 0.11859831 -0.073756561, 0.46888366 0.11883523 -0.074216589, 0.46941534 0.1186429 -0.074093834, 0.46932736 0.11867473 -0.074173823, 0.46922365 0.11871222 -0.07422851, 0.46911052 0.11875315 -0.074254617, 0.46899495 0.11879489 -0.074250475, 0.44442371 0.12768146 -0.060028121, 0.44423893 0.12774822 -0.060164168, 0.44432363 0.1277176 -0.060084239, 0.44417465 0.12777154 -0.060263291, 0.44412091 0.12779103 -0.060495451, 0.4441345 0.12778614 -0.060376003, 0.44453368 0.12764169 -0.059999302, 0.44464687 0.12760065 -0.059998944, 0.4447569 0.1275609 -0.060027525, 0.44437203 0.12770119 -0.078448251, 0.48384902 0.11342378 -0.10056289, 0.44448528 0.12766013 -0.075447693, 0.44429737 0.12772803 -0.075544462, 0.44438621 0.12769586 -0.075484738, 0.44412094 0.1277919 -0.075934872, 0.44413278 0.12778753 -0.075823769, 0.44416729 0.12777506 -0.075718239, 0.4442232 0.12775485 -0.075623557, 0.44458976 0.12762225 -0.075434759, 0.44469413 0.12758455 -0.075447068, 0.44479355 0.12754859 -0.075483397, 0.44412091 0.127792 -0.078005865, 0.44421723 0.12775718 -0.078309104, 0.4441646 0.12777624 -0.07821627, 0.444132 0.1277881 -0.078113511, 0.44428751 0.12773179 -0.078387812, 0.480948 0.11447267 -0.093813434, 0.48149166 0.1142761 -0.094299719, 0.48115435 0.11439806 -0.093941972, 0.48133734 0.11433181 -0.094105616, 0.48427838 0.11326838 -0.0984786, 0.48442081 0.11321689 -0.098746672, 0.48450872 0.11318506 -0.099040076, 0.48453841 0.11317441 -0.099346325, 0.48453835 0.11317447 -0.1001205, 0.48416185 0.11331072 -0.10061066, 0.4840551 0.11334929 -0.10062043, 0.48394892 0.11338763 -0.10060422, 0.48426363 0.11327384 -0.10057525, 0.48449019 0.11319187 -0.1003411, 0.48452613 0.11317886 -0.10023384, 0.48443225 0.11321281 -0.10043694, 0.48435542 0.11324058 -0.10051639, 0.48453835 0.11317495 -0.10989641, 0.48452583 0.11317956 -0.1100118, 0.4844884 0.11319308 -0.11012088, 0.48442844 0.11321475 -0.11021774, 0.48434898 0.11324346 -0.11029731, 0.48425457 0.11327767 -0.11035548, 0.4841499 0.11331542 -0.11038868, 0.48404101 0.11335485 -0.11039554, 0.48393354 0.11339371 -0.11037542, 0.48383328 0.11343001 -0.11032949, 0.4844422 0.11320958 -0.10546862, 0.48428738 0.11326554 -0.10532962, 0.48437187 0.11323495 -0.10539006, 0.48449481 0.1131905 -0.1055616, 0.48452744 0.1131787 -0.10566409, 0.48453853 0.11317469 -0.10577179, 0.44481024 0.12754296 -0.083214715, 0.44460431 0.12761734 -0.083157405, 0.4447104 0.12757899 -0.083173588, 0.44449756 0.12765594 -0.08316727, 0.44439569 0.12769291 -0.083202437, 0.4443039 0.12772608 -0.083261326, 0.44422713 0.12775381 -0.083340839, 0.44416919 0.12777479 -0.083436683, 0.4441331 0.12778781 -0.083543971, 0.44412091 0.12779231 -0.083657309, 0.44412097 0.12779234 -0.085681751, 0.44435611 0.12770736 -0.086114839, 0.44413117 0.12778871 -0.085785732, 0.44421086 0.12775989 -0.085975841, 0.44416156 0.12777776 -0.085885242, 0.44427666 0.12773615 -0.086053327, 0.48447207 0.15221521 -0.10700236, 0.48446146 0.15221299 -0.10689841, 0.48442981 0.15220614 -0.10679887, 0.48437873 0.15219529 -0.10670851, 0.48431048 0.15218082 -0.10663079, 0.48422766 0.15216312 -0.10656939, 0.48372185 0.15205577 -0.11152826, 0.48382619 0.15207802 -0.11157916, 0.48393947 0.15210217 -0.1116036, 0.48405513 0.1521268 -0.11160015, 0.4841668 0.15215048 -0.11156903, 0.48426807 0.15217206 -0.11151181, 0.48435342 0.15219018 -0.11143206, 0.48441809 0.15220401 -0.11133395, 0.48445842 0.15221259 -0.11122309, 0.48447216 0.15221542 -0.11110561, 0.44483635 0.14378045 -0.083375886, 0.44505247 0.14382645 -0.083442047, 0.44494829 0.14380421 -0.083396181, 0.44472307 0.14375636 -0.0833828, 0.44461429 0.14373317 -0.08341594, 0.44451588 0.14371231 -0.083473995, 0.44443342 0.1436947 -0.083553746, 0.44437096 0.14368139 -0.083650693, 0.44433209 0.1436732 -0.08375977, 0.44431886 0.14367034 -0.083875105, 0.44431892 0.14367047 -0.085787877, 0.44454667 0.143719 -0.086210445, 0.44432878 0.1436726 -0.085887775, 0.44435814 0.14367895 -0.085983858, 0.44440553 0.14368901 -0.086071953, 0.44446921 0.14370252 -0.086148366, 0.44503447 0.14382228 -0.07569097, 0.47364166 0.14990984 -0.090979591, 0.47376508 0.14993612 -0.09105359, 0.47398791 0.14998348 -0.091236755, 0.47388086 0.1499607 -0.09113954, 0.48418024 0.15215291 -0.10172008, 0.48427519 0.15217306 -0.10167347, 0.48435825 0.15219072 -0.10160701, 0.48377258 0.15206608 -0.10168175, 0.48386899 0.15208657 -0.10172515, 0.48397234 0.15210856 -0.10174654, 0.48407769 0.15213102 -0.10174485, 0.44436887 0.14368057 -0.075913921, 0.44460383 0.14373057 -0.075679615, 0.44450864 0.14371033 -0.075738624, 0.44442898 0.1436934 -0.075818107, 0.44433162 0.14367266 -0.076021001, 0.44493067 0.14380009 -0.075650051, 0.44482055 0.14377668 -0.075634196, 0.44470957 0.14375313 -0.075644359, 0.4443188 0.14366993 -0.076134011, 0.44431886 0.14367008 -0.078101322, 0.44456339 0.14372219 -0.07853432, 0.44441226 0.14368998 -0.078395173, 0.44432953 0.14367239 -0.078205302, 0.44436118 0.14367913 -0.078304604, 0.44448063 0.14370456 -0.078472838, 0.48454306 0.15205967 -0.10167198, 0.4845559 0.15206245 -0.10160716, 0.48454329 0.15205969 -0.10154237, 0.48472801 0.15192862 -0.10173677, 0.4847537 0.15193404 -0.10160734, 0.48472825 0.15192856 -0.10147794, 0.46947214 0.14902212 -0.079963371, 0.46945968 0.14901946 -0.079850987, 0.46942285 0.14901158 -0.079744384, 0.46936354 0.14899893 -0.079648927, 0.46928465 0.14898218 -0.079569772, 0.46919039 0.1489622 -0.079510525, 0.44442442 0.14369196 -0.068084821, 0.44459313 0.14372787 -0.067945912, 0.44450119 0.14370826 -0.068005666, 0.44469562 0.14374964 -0.067908481, 0.44436684 0.14367966 -0.068179235, 0.44431898 0.1436694 -0.068395212, 0.44433108 0.14367203 -0.068284467, 0.44491211 0.1437957 -0.067906603, 0.44480366 0.14377275 -0.06789504, 0.44501534 0.14381759 -0.067942247, 0.44431886 0.14366969 -0.070413008, 0.44433036 0.14367209 -0.070520982, 0.4445813 0.14372559 -0.070856169, 0.44436452 0.14367935 -0.070623979, 0.44441959 0.14369115 -0.070716962, 0.44449303 0.14370671 -0.070795521, 0.4687565 0.14887016 -0.083776191, 0.46886036 0.14889215 -0.08381708, 0.46897054 0.14891568 -0.083832934, 0.46947214 0.14902227 -0.083332971, 0.46908146 0.14893927 -0.083822921, 0.46918711 0.14896169 -0.083787516, 0.46942213 0.14901167 -0.083553419, 0.4694595 0.14901951 -0.083446071, 0.46928236 0.14898191 -0.083728507, 0.46936202 0.14899895 -0.083648995, 0.46947208 0.14902149 -0.070874795, 0.46945867 0.14901863 -0.07075797, 0.46941873 0.14901021 -0.070647582, 0.4693549 0.14899647 -0.070549712, 0.46927038 0.14897856 -0.07046999, 0.46916994 0.14895721 -0.070412591, 0.44475976 0.14376284 -0.060160801, 0.44499478 0.14381278 -0.060196206, 0.44487938 0.14378834 -0.060163662, 0.44464293 0.14373796 -0.060187772, 0.44453606 0.14371531 -0.060242727, 0.44444552 0.14369607 -0.060322538, 0.44437653 0.14368132 -0.060422763, 0.44433358 0.14367215 -0.060536817, 0.44431883 0.14366914 -0.060658291, 0.44431886 0.14366917 -0.062722549, 0.44433144 0.14367186 -0.062834933, 0.44460067 0.14372914 -0.063175485, 0.44436821 0.14367972 -0.062941507, 0.44442764 0.14369236 -0.063036755, 0.44450647 0.14370914 -0.063116208, 0.46877569 0.14887366 -0.074743763, 0.46947214 0.14902185 -0.074290767, 0.46887895 0.14889556 -0.074779376, 0.46898717 0.14891878 -0.07479085, 0.46945998 0.14901917 -0.074401483, 0.46909535 0.14894165 -0.074777439, 0.46942422 0.14901163 -0.074506596, 0.46919799 0.14896354 -0.074740008, 0.46936658 0.14899935 -0.074601248, 0.46928987 0.14898305 -0.074680164, 0.46947211 0.1490211 -0.061788514, 0.46945751 0.14901796 -0.061667129, 0.46941441 0.14900874 -0.061552897, 0.4693456 0.14899412 -0.061452821, 0.46925506 0.14897484 -0.06137301, 0.46914825 0.1489522 -0.061317995, 0.44474241 0.14375864 -0.052428499, 0.44497317 0.14380786 -0.052453384, 0.44485924 0.14378357 -0.052426681, 0.44462928 0.14373478 -0.05245851, 0.4445264 0.14371291 -0.052514955, 0.44443971 0.14369431 -0.052594885, 0.44437388 0.14368036 -0.052693591, 0.44433275 0.14367171 -0.05280529, 0.44431892 0.14366867 -0.052923903, 0.44431892 0.1436687 -0.055029884, 0.44433233 0.14367166 -0.055146709, 0.44437218 0.14368017 -0.055257216, 0.44443625 0.14369376 -0.055354849, 0.44452089 0.14371172 -0.05543457, 0.44462112 0.14373316 -0.055492058, 0.46879622 0.14887752 -0.065708354, 0.4689118 0.14890195 -0.065741137, 0.46947214 0.14902125 -0.06524621, 0.46945751 0.14901815 -0.065367773, 0.46903136 0.14892751 -0.065743789, 0.46925488 0.14897504 -0.065661892, 0.4691481 0.14895238 -0.065716997, 0.46941435 0.14900908 -0.065482005, 0.46934554 0.14899436 -0.065581992, 0.46947208 0.14902048 -0.052704617, 0.46946117 0.14901817 -0.052599177, 0.46942863 0.14901122 -0.052498445, 0.46937606 0.14900008 -0.052406922, 0.46930584 0.14898512 -0.052328929, 0.46922085 0.14896706 -0.052267775, 0.46912524 0.14894673 -0.052226439, 0.44451663 0.1437103 -0.044790223, 0.44472453 0.14375451 -0.044699267, 0.44461533 0.14373136 -0.044732377, 0.44443384 0.14369263 -0.044869974, 0.44431895 0.1436682 -0.045191959, 0.44437107 0.1436794 -0.044967219, 0.44433212 0.14367101 -0.045076475, 0.44483808 0.14377865 -0.044692919, 0.44495019 0.14380254 -0.044713661, 0.44431886 0.14366832 -0.047335044, 0.44433352 0.14367142 -0.04745625, 0.44437653 0.14368065 -0.047570422, 0.44444537 0.14369532 -0.047670618, 0.44453597 0.14371462 -0.047750548, 0.4446429 0.14373735 -0.047805652, 0.46881798 0.14888161 -0.056670085, 0.46893188 0.1489058 -0.056696787, 0.4694722 0.14902081 -0.056199566, 0.4694581 0.14901784 -0.05631806, 0.46904871 0.14893071 -0.05669485, 0.46916172 0.14895469 -0.056664929, 0.46941715 0.14900911 -0.056429908, 0.46926448 0.14897667 -0.056608453, 0.46935132 0.14899512 -0.056528464, 0.46947211 0.14902011 -0.043623611, 0.46946022 0.14901756 -0.043514058, 0.46942505 0.14901005 -0.043409631, 0.46936849 0.14899795 -0.043315813, 0.46929309 0.14898184 -0.043236986, 0.46920255 0.14896266 -0.043176845, 0.4691014 0.14894108 -0.043138549, 0.46941993 0.14900918 -0.047375038, 0.46945888 0.14901748 -0.047265664, 0.46947217 0.14902028 -0.047150001, 0.46935713 0.14899591 -0.047472104, 0.46917561 0.14895722 -0.047609881, 0.46927437 0.14897814 -0.047551915, 0.46906647 0.14893405 -0.047642872, 0.46895278 0.14890985 -0.04764922, 0.46884084 0.14888597 -0.047628447, 0.44470629 0.14375015 -0.03697376, 0.44492617 0.14379691 -0.036977515, 0.44481644 0.14377354 -0.036962762, 0.4446013 0.14372785 -0.037009612, 0.44450685 0.14370768 -0.037068769, 0.44442782 0.14369103 -0.037148133, 0.44436836 0.14367834 -0.03724362, 0.44433138 0.14367048 -0.037350431, 0.44431886 0.14366774 -0.037462726, 0.44431886 0.14366792 -0.039637491, 0.44466573 0.14374176 -0.040115848, 0.44436243 0.14367725 -0.039843634, 0.44432995 0.14367029 -0.039742902, 0.44457009 0.14372145 -0.040074363, 0.44441512 0.14368841 -0.039935187, 0.44448534 0.1437033 -0.040013149, 0.44490138 0.1437912 -0.029245362, 0.44479421 0.14376846 -0.029236421, 0.44468758 0.14374582 -0.029251561, 0.44458702 0.14372432 -0.029290184, 0.44449696 0.14370532 -0.029350385, 0.44442192 0.14368926 -0.029429182, 0.44436565 0.14367728 -0.029522911, 0.44433072 0.14366983 -0.029626802, 0.44431886 0.14366733 -0.029736236, 0.44431886 0.14366744 -0.031937346, 0.44433066 0.14367007 -0.032047018, 0.44436595 0.14367746 -0.032151207, 0.44442263 0.1436895 -0.032245174, 0.444498 0.14370552 -0.032324091, 0.44458854 0.14372483 -0.032384172, 0.44468969 0.14374629 -0.032422438, 0.46907648 0.1489353 -0.034054533, 0.46918339 0.14895801 -0.034089044, 0.46936056 0.14899574 -0.034227297, 0.4692798 0.14897862 -0.034147874, 0.46942136 0.14900872 -0.034323588, 0.46945927 0.14901683 -0.034431353, 0.46947211 0.14901951 -0.034545198, 0.46886483 0.14889054 -0.038583353, 0.46897456 0.14891389 -0.038598105, 0.46947208 0.14901976 -0.038098142, 0.46945968 0.14901707 -0.038210645, 0.46908489 0.14893743 -0.038587257, 0.46928427 0.1489798 -0.038492218, 0.46918973 0.14895973 -0.038551345, 0.46936318 0.14899659 -0.038412854, 0.46942273 0.1490092 -0.038317218, 0.46947217 0.14901897 -0.025469676, 0.46945837 0.14901605 -0.02535148, 0.46941742 0.14900745 -0.025240049, 0.4693521 0.14899352 -0.025141582, 0.46926567 0.14897509 -0.025061682, 0.46916345 0.14895329 -0.025004908, 0.46905085 0.14892936 -0.024974391, 0.44437611 0.14367905 -0.021777824, 0.44433346 0.14366998 -0.021891519, 0.44444439 0.14369358 -0.021677896, 0.44453427 0.14371279 -0.021598116, 0.44475651 0.14376004 -0.021515295, 0.44464046 0.14373532 -0.021542743, 0.44431886 0.14366688 -0.022012606, 0.44487572 0.14378543 -0.021517321, 0.4443188 0.14366692 -0.024234489, 0.44436964 0.14367782 -0.024456218, 0.44443062 0.14369079 -0.024552509, 0.44433185 0.14366975 -0.024348214, 0.44451132 0.14370798 -0.024631962, 0.44460768 0.14372858 -0.024690613, 0.44471458 0.14375122 -0.024725184, 0.46888968 0.14889535 -0.029534325, 0.4694722 0.14901917 -0.029043511, 0.46899691 0.14891812 -0.029543266, 0.46910337 0.14894088 -0.029528245, 0.46920404 0.14896224 -0.029489532, 0.46936914 0.14899732 -0.029350594, 0.4694604 0.14901672 -0.029152855, 0.46942541 0.1490092 -0.029256806, 0.46929416 0.14898135 -0.029429421, 0.46947205 0.14901845 -0.016397014, 0.46945724 0.1490154 -0.016274467, 0.46941334 0.14900604 -0.01615952, 0.46934325 0.14899109 -0.016058907, 0.46925125 0.1489716 -0.015979037, 0.46914279 0.14894851 -0.015924469, 0.46902457 0.14892331 -0.015898928, 0.444437 0.14369157 -0.013965979, 0.44462293 0.14373115 -0.013828859, 0.44452199 0.14370979 -0.013886198, 0.44473407 0.14375488 -0.013797387, 0.44437265 0.14367791 -0.01406385, 0.44431886 0.14366649 -0.014291778, 0.44433251 0.1436694 -0.014174595, 0.4448494 0.14377941 -0.013793603, 0.44431898 0.14366658 -0.016528741, 0.44433275 0.14366953 -0.016647115, 0.44437355 0.14367822 -0.016758546, 0.44443899 0.14369217 -0.016857132, 0.44452521 0.14371054 -0.016936913, 0.44462773 0.14373228 -0.016993448, 0.44474021 0.14375618 -0.017024025, 0.46891543 0.14890021 -0.020481244, 0.46947208 0.14901875 -0.019986019, 0.46903446 0.14892568 -0.02048333, 0.46915063 0.14895032 -0.020455852, 0.46934661 0.14899209 -0.02032055, 0.46925664 0.14897296 -0.02040045, 0.4694576 0.14901569 -0.020106927, 0.46941504 0.14900655 -0.020220593, 0.46947208 0.14901803 -0.0073272735, 0.46946031 0.1490155 -0.007218197, 0.4694255 0.14900802 -0.0071143955, 0.46936944 0.14899616 -0.0070207864, 0.46929464 0.14898017 -0.0069418401, 0.46920481 0.14896117 -0.0068817586, 0.46910438 0.14893973 -0.0068430454, 0.46899804 0.14891717 -0.0068276674, 0.44450969 0.14370671 -0.0061775595, 0.44433162 0.14366879 -0.0064605325, 0.44460538 0.14372697 -0.0061188191, 0.44442967 0.1436896 -0.0062569827, 0.44436923 0.1436767 -0.0063530952, 0.4447116 0.14374958 -0.0060836524, 0.44431886 0.14366601 -0.006573841, 0.44482285 0.14377327 -0.006074056, 0.44431901 0.14366612 -0.0088201612, 0.44444782 0.1436936 -0.009158358, 0.44453987 0.14371322 -0.0092384666, 0.44437769 0.14367868 -0.0090578943, 0.44464827 0.14373621 -0.0092928261, 0.44433382 0.14366928 -0.0089426786, 0.44476643 0.14376138 -0.0093184561, 0.4689416 0.14890535 -0.011423841, 0.4694722 0.1490182 -0.010925606, 0.46905705 0.14892982 -0.011419877, 0.46916816 0.14895342 -0.011388376, 0.46941835 0.1490068 -0.011153534, 0.46945855 0.14901517 -0.011042699, 0.46926913 0.148975 -0.011331216, 0.46935418 0.14899303 -0.011251405, 0.46947214 0.14901768 -0.0018623024, 0.46947211 0.14901748 0.001880005, 0.46945938 0.14901473 0.0019936115, 0.46942177 0.1490068 0.0021009594, 0.46936151 0.14899388 0.0021970719, 0.46896824 0.14891022 0.002379939, 0.46918559 0.14895663 0.0023350865, 0.46907941 0.14893392 0.0023703128, 0.46928132 0.14897686 0.0022764951, 0.46936145 0.14899412 -0.0021791011, 0.46942174 0.14900699 -0.002083078, 0.46945944 0.14901501 -0.0019754916, 0.46896824 0.14891043 -0.0023619086, 0.46907955 0.14893417 -0.002352491, 0.46918568 0.14895678 -0.0023173839, 0.46928129 0.14897709 -0.0022585839, 0.44479296 0.14376649 0.0016257018, 0.44458622 0.14372239 0.001571551, 0.44468677 0.14374393 0.001610294, 0.44449645 0.14370325 0.0015113801, 0.44442156 0.1436875 0.0014325827, 0.44433066 0.14366804 0.0012351722, 0.44436547 0.1436756 0.0013388544, 0.44431898 0.14366561 0.0011260062, 0.44479296 0.14376667 -0.0016085058, 0.44431892 0.14366566 -0.0011086613, 0.44433066 0.14366816 -0.0012178868, 0.44458616 0.14372262 -0.0015542954, 0.44468677 0.14374408 -0.0015931576, 0.44442159 0.14368774 -0.0014151782, 0.44436547 0.14367571 -0.0013218075, 0.44449639 0.14370354 -0.0014940053, 0.44412094 0.1277876 -0.001135394, 0.44412094 0.1277876 0.001150921, 0.46943232 0.11863247 0.0021576136, 0.46949029 0.11861151 0.0020617098, 0.46935579 0.11866012 0.0022370368, 0.4695262 0.11859849 0.0019544512, 0.46953842 0.11859407 0.0018415898, 0.46905574 0.11876866 0.0023412257, 0.46926412 0.11869329 0.0022958964, 0.46916237 0.11873014 0.0023311824, 0.46952623 0.11859879 -0.0019400269, 0.46949032 0.11861174 -0.0020472258, 0.46953842 0.11859436 -0.0018268973, 0.46943238 0.1186327 -0.0021430701, 0.46935573 0.11866046 -0.0022224635, 0.46905568 0.11876896 -0.002326861, 0.46926415 0.11869353 -0.0022814423, 0.46916237 0.11873034 -0.0023167282, 0.44457868 0.12762186 0.0016508251, 0.44437912 0.12769413 0.0015973002, 0.4444761 0.12765902 0.0016359836, 0.44429246 0.12772545 0.0015371591, 0.44422024 0.1277516 0.0014582127, 0.444166 0.12777118 0.001364544, 0.44413236 0.12778336 0.0012603551, 0.44457862 0.12762214 -0.0016353279, 0.4444761 0.12765925 -0.001620397, 0.44416597 0.12777135 -0.0013489872, 0.44413233 0.12778355 -0.0012450367, 0.44422024 0.12775178 -0.0014428049, 0.44437912 0.12769438 -0.0015818328, 0.44429246 0.12772574 -0.0015218407, 0.4411965 0.12939861 -0.08788763, 0.4878417 0.11253434 -0.11654221, 0.44121492 0.12944536 -0.088188395, 0.48770851 0.11264811 -0.11677195, 0.44122735 0.12953599 -0.088482007, 0.4876096 0.11279365 -0.11700527, 0.44123408 0.12956582 -0.088559374, 0.48750594 0.12669735 -0.14667358, 0.48523852 0.12542281 -0.14079137, 0.48531142 0.12535025 -0.14073746, 0.48536661 0.12527999 -0.14066319, 0.48515165 0.12549362 -0.14082251, 0.48540094 0.12521553 -0.14057283, 0.4850556 0.12555863 -0.1408288, 0.4854126 0.12516055 -0.14047094, 0.4849554 0.12561469 -0.14080997, 0.48485687 0.12565845 -0.14076693, 0.4847649 0.12568782 -0.14070214, 0.48468462 0.12570108 -0.14061923, 0.48541257 0.12379517 -0.13754328, 0.48541 0.12376393 -0.13747276, 0.48514357 0.12363154 -0.1368189, 0.48531136 0.12214658 -0.13386808, 0.48525277 0.12363499 -0.1369781, 0.48523852 0.122219 -0.13392211, 0.48536655 0.1220762 -0.13379376, 0.4853358 0.12366161 -0.13715048, 0.48515165 0.12228981 -0.13395335, 0.48538941 0.12371029 -0.13732941, 0.48540086 0.1220118 -0.13370325, 0.48540238 0.12373556 -0.13740127, 0.4850556 0.12235489 -0.13395937, 0.48541245 0.12195686 -0.13360162, 0.48495549 0.12241094 -0.13394038, 0.48485678 0.12245481 -0.1338975, 0.4847649 0.1224841 -0.13383274, 0.48468465 0.12249744 -0.13374986, 0.48541266 0.12088262 -0.13129844, 0.4851436 0.120719 -0.130574, 0.48530707 0.1184341 -0.12590189, 0.48525289 0.12072255 -0.13073336, 0.48523119 0.11850819 -0.12595542, 0.48536459 0.11836191 -0.12582697, 0.4853358 0.12074924 -0.13090546, 0.48514137 0.11858006 -0.12598453, 0.48538956 0.1207978 -0.13108446, 0.48540053 0.1182958 -0.12573479, 0.48540249 0.120823 -0.13115622, 0.48504239 0.11864576 -0.12598784, 0.48541257 0.11823955 -0.12563114, 0.48541 0.12085137 -0.13122781, 0.48493996 0.11870131 -0.12596484, 0.48483983 0.11874385 -0.12591694, 0.48512933 0.11733237 -0.12329249, 0.48530707 0.11619678 -0.1211044, 0.48524532 0.11733364 -0.12345619, 0.48523131 0.11627091 -0.12115793, 0.48499021 0.11735599 -0.12315004, 0.48536471 0.11612459 -0.12102945, 0.48533323 0.11735986 -0.12363453, 0.48514131 0.11634263 -0.12118705, 0.48540047 0.11605845 -0.12093766, 0.48538956 0.11741002 -0.12382029, 0.4850423 0.11640824 -0.12119038, 0.48483339 0.11740379 -0.12303458, 0.4849399 0.11646403 -0.12116741, 0.48483995 0.11650655 -0.12111966, 0.48541263 0.1160021 -0.12083362, 0.48750603 0.11323683 -0.11781161, 0.48541269 0.11749481 -0.1240343, 0.48540244 0.11743523 -0.12389223, 0.48541006 0.1174636 -0.12396364, 0.48541251 0.11503378 -0.11875741, 0.48541006 0.11500247 -0.11868663, 0.48540232 0.11497419 -0.11861511, 0.4853895 0.11494893 -0.11854319, 0.4853332 0.11489877 -0.11835741, 0.4852452 0.11487262 -0.11817913, 0.48512936 0.11487131 -0.11801545, 0.48752782 0.11302899 -0.1173964, 0.47893319 0.12113655 -0.12284406, 0.48499021 0.11489506 -0.117873, 0.47890046 0.12113567 -0.12279634, 0.47887543 0.12112758 -0.12274475, 0.4791961 0.120785 -0.12245519, 0.47885939 0.12111297 -0.12269087, 0.47913626 0.12081036 -0.12242655, 0.47907501 0.12084365 -0.12241264, 0.47885248 0.1210869 -0.12262525, 0.47886011 0.12105295 -0.12256308, 0.48483339 0.11494263 -0.11775737, 0.47901574 0.12088293 -0.12241466, 0.47888169 0.1210133 -0.12250827, 0.4789618 0.12092581 -0.12243183, 0.47891644 0.12097013 -0.12246369, 0.46901938 0.12355065 -0.11425136, 0.46202275 0.12518618 -0.10804103, 0.46895182 0.12354647 -0.1141486, 0.46890649 0.1235235 -0.11403607, 0.46888596 0.12348337 -0.11392151, 0.46889147 0.12342831 -0.11381145, 0.46892294 0.12336192 -0.11371259, 0.46905392 0.12321122 -0.11357145, 0.46246117 0.12460007 -0.10739277, 0.46914551 0.12313613 -0.11353765, 0.46924752 0.1230673 -0.11353187, 0.46935382 0.12300894 -0.11355434, 0.46945772 0.12296458 -0.11360337, 0.46196827 0.12518433 -0.10796128, 0.46897817 0.12328799 -0.11363088, 0.46189988 0.1251467 -0.10778569, 0.46188834 0.12510315 -0.1076761, 0.46192664 0.12517108 -0.10787521, 0.4622592 0.12469777 -0.10732208, 0.46236125 0.1246424 -0.10734509, 0.46190098 0.1250467 -0.10757278, 0.4621605 0.1247631 -0.10732494, 0.46199474 0.1249087 -0.10740696, 0.46207067 0.12483481 -0.10735382, 0.46193722 0.12498066 -0.10748138, 0.44977894 0.12804809 -0.097172543, 0.44122365 0.12980925 -0.089066759, 0.44971147 0.12804373 -0.097069427, 0.44966605 0.12802079 -0.09695746, 0.44964555 0.12798068 -0.096842691, 0.44965109 0.12792566 -0.096732631, 0.44968247 0.12785926 -0.096633717, 0.4497377 0.12778541 -0.096552059, 0.44981337 0.12770864 -0.096492544, 0.44123408 0.1297227 -0.088895485, 0.44990504 0.12763351 -0.096458837, 0.45000711 0.12756471 -0.096452996, 0.45011327 0.12750636 -0.096475288, 0.4502171 0.127462 -0.096524492, 0.46234956 0.12393434 -0.10718213, 0.46214998 0.1240191 -0.10708664, 0.46194565 0.12412986 -0.10704063, 0.46174824 0.12426056 -0.10704659, 0.46156862 0.1244038 -0.10710426, 0.46141687 0.12455162 -0.10721053, 0.46130171 0.12469563 -0.10735916, 0.46122935 0.12482777 -0.10754226, 0.46120402 0.12494051 -0.10774885, 0.46122709 0.12502787 -0.10796793, 0.4847168 0.12359135 -0.13751163, 0.48472315 0.12360394 -0.13754757, 0.48472703 0.12361804 -0.13758333, 0.48472819 0.1236337 -0.13761862, 0.4847168 0.11482997 -0.11872561, 0.48472324 0.11484255 -0.11876146, 0.484727 0.11485671 -0.11879726, 0.48472831 0.11487238 -0.11883251, 0.47908464 0.12011927 -0.12224455, 0.4789249 0.12018709 -0.12216811, 0.47876158 0.12027572 -0.12213127, 0.47860357 0.12038028 -0.12213616, 0.47845981 0.12049493 -0.12218241, 0.47833851 0.12061313 -0.12226732, 0.47824624 0.12072827 -0.12238626, 0.47818843 0.12083398 -0.12253241, 0.47816807 0.12092425 -0.12269793, 0.47818664 0.12099399 -0.12287302, 0.48471683 0.1206788 -0.13126673, 0.48472318 0.12069143 -0.13130273, 0.484727 0.12070562 -0.13133831, 0.48472837 0.12072124 -0.13137366, 0.48471674 0.11729106 -0.12400256, 0.48472318 0.11730368 -0.12403856, 0.48472711 0.11731793 -0.1240743, 0.48472831 0.1173334 -0.12410955, 0.46906295 0.12284872 -0.11417846, 0.47822958 0.12103304 -0.12301643, 0.47829607 0.12105422 -0.12315415, 0.47838339 0.121057 -0.12328143, 0.48443857 0.11728795 -0.12360965, 0.48468861 0.11726601 -0.12390967, 0.48458669 0.11725219 -0.12373857, 0.48464468 0.1172528 -0.1238205, 0.48451722 0.11726399 -0.12366743, 0.48472825 0.11807808 -0.1257063, 0.48468992 0.12065449 -0.13117729, 0.48459372 0.12063947 -0.1310115, 0.48464844 0.1206412 -0.1310911, 0.48472819 0.12179545 -0.1336769, 0.44982249 0.1273461 -0.097099707, 0.46128079 0.12507638 -0.10814704, 0.46136385 0.12510295 -0.10831927, 0.46147296 0.12510656 -0.10847841, 0.48458675 0.11479111 -0.11846168, 0.48443875 0.11482686 -0.11833267, 0.48451704 0.11480296 -0.11839037, 0.48464465 0.11479169 -0.11854346, 0.48468858 0.11480489 -0.11863263, 0.48472831 0.11584069 -0.12090881, 0.48468995 0.12356696 -0.13742216, 0.48459372 0.12355196 -0.13725655, 0.48464838 0.12355368 -0.13733609, 0.48472822 0.12499908 -0.1405464, 0.46901274 0.12307529 -0.1141374, 0.46900424 0.12304842 -0.11406817, 0.46902454 0.1230077 -0.11400877, 0.46896264 0.12330183 -0.11409627, 0.46906963 0.12296101 -0.11397134, 0.46894553 0.12324831 -0.11395766, 0.46913031 0.12291805 -0.11396359, 0.46898612 0.12316667 -0.1138391, 0.46907648 0.12307334 -0.11376439, 0.46919778 0.12298737 -0.11374854, 0.48494104 0.1218891 -0.13371576, 0.4848983 0.12193669 -0.1337588, 0.48483741 0.12198193 -0.13377087, 0.48515391 0.12198257 -0.13375475, 0.48477113 0.12201524 -0.13375045, 0.48506841 0.12207785 -0.13384031, 0.48494652 0.12216851 -0.13386513, 0.48481396 0.12223502 -0.13382412, 0.48494038 0.11817279 -0.12574653, 0.48489597 0.11822143 -0.12578936, 0.48515263 0.11826725 -0.12578674, 0.48483303 0.11826733 -0.12580012, 0.48506364 0.11836477 -0.1258723, 0.48493758 0.11845644 -0.12589394, 0.44977233 0.1275727 -0.097058579, 0.44976375 0.12754594 -0.0969892, 0.44978413 0.12750508 -0.096929953, 0.44972208 0.12779932 -0.097017542, 0.44982919 0.1274585 -0.096892521, 0.44970503 0.12774576 -0.096878722, 0.44988987 0.12741545 -0.096884653, 0.44974568 0.12766401 -0.096760079, 0.44983587 0.12757082 -0.096685424, 0.44995734 0.12748471 -0.096669689, 0.48494104 0.12509266 -0.14058526, 0.48489836 0.12514031 -0.14062817, 0.48483738 0.1251855 -0.14064036, 0.48515376 0.12518635 -0.14062412, 0.48477119 0.1252189 -0.14061983, 0.48506841 0.1252816 -0.14070983, 0.48494652 0.12537213 -0.14073463, 0.48481396 0.12543876 -0.14069326, 0.48494047 0.11593544 -0.1209491, 0.48489597 0.11598411 -0.12099187, 0.48515251 0.11603005 -0.12098925, 0.48483291 0.11602996 -0.12100272, 0.48506364 0.11612745 -0.12107487, 0.48493764 0.11621915 -0.12109657, 0.44123617 0.12996535 -0.089376435, 0.44123667 0.13016446 -0.089660451, 0.48765287 0.12708269 -0.14748071, 0.44123507 0.13040461 -0.089908823, 0.487708 0.12732187 -0.1477886, 0.44123885 0.13068463 -0.090113387, 0.4877508 0.12760857 -0.14803399, 0.44125393 0.13099751 -0.090262875, 0.48777196 0.12785952 -0.1481602, 0.48777786 0.12799868 -0.14819895, 0.44128534 0.13133156 -0.090347692, 0.4428786 0.13422097 -0.09233062, 0.44129989 0.13166003 -0.090365633, 0.44289348 0.13400437 -0.092349157, 0.44293749 0.13379796 -0.092403784, 0.44300836 0.13361169 -0.092492089, 0.44310275 0.13345435 -0.092609659, 0.44321626 0.13333352 -0.092750892, 0.48589981 0.13436738 -0.14587842, 0.485993 0.13421032 -0.14599408, 0.4877792 0.13639587 -0.14821745, 0.44287857 0.13723108 -0.092330441, 0.44129983 0.14021729 -0.090365276, 0.48578778 0.13448872 -0.14573877, 0.44334367 0.13325477 -0.092909381, 0.44347847 0.133222 -0.093077406, 0.48606279 0.13402508 -0.14608119, 0.48546812 0.13039859 -0.14534111, 0.44129482 0.14041002 -0.090359256, 0.44353881 0.13822962 -0.093152121, 0.48552823 0.13460359 -0.14541577, 0.48566189 0.13456874 -0.14558209, 0.48610613 0.13382016 -0.14613511, 0.48612079 0.13360505 -0.14615323, 0.48612067 0.13139771 -0.14615349, 0.48610416 0.13116947 -0.14613293, 0.48605534 0.1309531 -0.14607216, 0.4859769 0.13076028 -0.1459745, 0.48587301 0.13060118 -0.14584507, 0.4857491 0.13048418 -0.14569081, 0.48561159 0.13041547 -0.14551981, 0.44339398 0.13821523 -0.092971846, 0.44325516 0.13814811 -0.092799112, 0.44312963 0.13803169 -0.092643037, 0.44302437 0.13787259 -0.092511877, 0.44294491 0.13767889 -0.092412934, 0.44289532 0.13746116 -0.092351303, 0.44313201 0.13773043 -0.093444243, 0.48512155 0.13410437 -0.14570804, 0.48534596 0.13107894 -0.14598723, 0.48541772 0.13139772 -0.14607666, 0.48529395 0.13099945 -0.14592271, 0.48538521 0.13117535 -0.14603616, 0.48540965 0.13128354 -0.14606653, 0.48523197 0.130941 -0.14584561, 0.48509142 0.13089819 -0.14567064, 0.4851633 0.13090654 -0.14575996, 0.48541772 0.13360512 -0.14607655, 0.48541054 0.1337126 -0.14606757, 0.48538882 0.13381508 -0.14604057, 0.48535386 0.13390772 -0.145997, 0.48530737 0.13398622 -0.1459391, 0.48525128 0.13404682 -0.14586936, 0.48518834 0.13408688 -0.14579095, 0.44310194 0.13372138 -0.09340696, 0.44297087 0.13377723 -0.093243763, 0.44303459 0.13373777 -0.093323067, 0.4429141 0.13383777 -0.09317331, 0.44283131 0.13400945 -0.093070313, 0.4428668 0.13391635 -0.093114361, 0.44280201 0.13422097 -0.093033656, 0.44280943 0.13411263 -0.093042865, 0.44280192 0.1372312 -0.093033418, 0.44305965 0.13772318 -0.093354121, 0.44281039 0.13734609 -0.093043938, 0.44299021 0.13768961 -0.093267724, 0.44287488 0.13755175 -0.093124077, 0.44292751 0.13763146 -0.093189701, 0.44283512 0.13745497 -0.093074605, 0.44120452 0.1422492 -0.088619515, 0.48754498 0.15211082 -0.11856799, 0.44119462 0.14229929 -0.088500366, 0.4876574 0.15227157 -0.11829786, 0.44119188 0.14240943 -0.088177666, 0.4878144 0.15238793 -0.11803131, 0.44117221 0.14246824 -0.087842539, 0.44111356 0.14247712 -0.08750473, 0.44120458 0.14209384 -0.088929847, 0.44120452 0.14209084 -0.088935837, 0.45076427 0.14300571 -0.097353712, 0.45046577 0.14261821 -0.097808525, 0.45049092 0.14258963 -0.097892538, 0.45052984 0.14256996 -0.0979736, 0.45058164 0.14256009 -0.09804906, 0.48745605 0.1518681 -0.11895828, 0.48508459 0.15031999 -0.11951225, 0.48743185 0.15164861 -0.11937098, 0.45066521 0.1429399 -0.097378984, 0.45058036 0.14286913 -0.097429916, 0.45051488 0.14279726 -0.097502872, 0.45047253 0.142729 -0.097594187, 0.45045587 0.14266816 -0.097698167, 0.48493302 0.15032625 -0.11933739, 0.48529437 0.14163893 -0.13710229, 0.48743185 0.13809893 -0.14647444, 0.48529434 0.14366323 -0.13305284, 0.48529425 0.14011714 -0.14014609, 0.48451865 0.13962951 -0.14028998, 0.48460141 0.13963142 -0.14037485, 0.48469776 0.13964967 -0.14044137, 0.48519889 0.1502827 -0.11971004, 0.48480204 0.13968344 -0.14048593, 0.48490885 0.13973063 -0.14050587, 0.48501214 0.13978863 -0.14050038, 0.48510578 0.13985434 -0.14046948, 0.4847526 0.15030095 -0.11919461, 0.48518458 0.1399239 -0.14041491, 0.48524439 0.13999347 -0.14034005, 0.48528174 0.14005908 -0.14024861, 0.4846634 0.1485751 -0.12255143, 0.46350655 0.14407261 -0.10887827, 0.47190663 0.14488491 -0.11625828, 0.48527011 0.15021576 -0.11991997, 0.46320358 0.14372675 -0.10924555, 0.48504218 0.14184088 -0.13642778, 0.4845185 0.14317556 -0.13319673, 0.47140166 0.14430825 -0.11687021, 0.48529422 0.15012334 -0.12013097, 0.45108646 0.14313658 -0.097437158, 0.48475257 0.14761862 -0.12456022, 0.48529419 0.14905056 -0.12227665, 0.48528048 0.14898983 -0.12238334, 0.48509052 0.14877625 -0.12260719, 0.4850845 0.14763767 -0.12487803, 0.4851754 0.14884833 -0.12255375, 0.48499057 0.14870895 -0.12263434, 0.48493302 0.14764397 -0.12470298, 0.48519894 0.14760025 -0.12507568, 0.48524007 0.14892107 -0.12247761, 0.48477027 0.14860526 -0.12260576, 0.48488149 0.14865083 -0.1226338, 0.48527005 0.14753343 -0.1252857, 0.48529425 0.14744081 -0.12549643, 0.48529437 0.14685582 -0.12666686, 0.48093995 0.14547601 -0.12475918, 0.4808549 0.14540318 -0.12481399, 0.48104048 0.14554393 -0.12473078, 0.48086545 0.14510296 -0.12542529, 0.48137018 0.14567949 -0.12481333, 0.4846634 0.14638032 -0.12694164, 0.48079833 0.14511876 -0.1253217, 0.48075536 0.14515182 -0.1252095, 0.48073944 0.14520024 -0.12509568, 0.48075154 0.14526074 -0.12498756, 0.48079088 0.1453298 -0.12489147, 0.48115024 0.14560285 -0.12473069, 0.48126251 0.145649 -0.12475882, 0.48504218 0.14474238 -0.13062416, 0.48477012 0.14641052 -0.12699576, 0.48488149 0.14645609 -0.12702404, 0.48499051 0.14651431 -0.1270244, 0.48509064 0.14658134 -0.1269971, 0.4851754 0.14665362 -0.12694381, 0.48514941 0.14472127 -0.13078122, 0.48524013 0.14672622 -0.12686776, 0.48522887 0.14467944 -0.1309502, 0.48528048 0.14679512 -0.12677346, 0.4852778 0.14461838 -0.1311246, 0.48529425 0.14454032 -0.13129856, 0.47180143 0.14485525 -0.1162046, 0.47169194 0.1448108 -0.11617632, 0.47158447 0.14475384 -0.11617483, 0.47148535 0.14468816 -0.11620016, 0.4714005 0.14461733 -0.11625083, 0.47133499 0.14454557 -0.1163242, 0.46344185 0.14405432 -0.1088457, 0.46337447 0.14402661 -0.1088288, 0.46330854 0.14399134 -0.1088288, 0.4632484 0.14395052 -0.10884593, 0.46319732 0.14390682 -0.10887872, 0.46315899 0.1438628 -0.10892524, 0.46313533 0.14382143 -0.10898291, 0.46312794 0.14378515 -0.10904776, 0.46316332 0.14373633 -0.1091833, 0.4631376 0.14375617 -0.10911618, 0.47128585 0.14436652 -0.1166297, 0.47131088 0.14433789 -0.11671369, 0.47134984 0.1443183 -0.11679493, 0.47129264 0.14447734 -0.11641534, 0.47127599 0.14441635 -0.11651926, 0.48460132 0.14317742 -0.13328131, 0.48469773 0.14319582 -0.13334812, 0.4848021 0.14322959 -0.13339259, 0.48490897 0.14327677 -0.13341255, 0.48501202 0.14333491 -0.13340707, 0.4851056 0.14340048 -0.13337626, 0.48518458 0.14347009 -0.1333216, 0.48514947 0.14181982 -0.13658483, 0.48524439 0.14353958 -0.13324679, 0.4852289 0.14177802 -0.13675366, 0.48528162 0.14360522 -0.13315524, 0.48527801 0.14171693 -0.13692828, 0.45098141 0.14310703 -0.097383633, 0.4508718 0.14306247 -0.097355291, 0.4506903 0.14325775 -0.098010197, 0.47151044 0.14500593 -0.11683135, 0.48032439 0.14521201 -0.12586747, 0.4845013 0.14485124 -0.13106613, 0.48452237 0.14774922 -0.12529211, 0.48444661 0.14775243 -0.12520488, 0.48435649 0.1477396 -0.12513347, 0.48462728 0.14765081 -0.12560137, 0.48461524 0.14769714 -0.1254961, 0.48457959 0.14773044 -0.12539096, 0.48462728 0.14706562 -0.12677182, 0.48133415 0.14636494 -0.12464343, 0.48111865 0.14630398 -0.12453456, 0.48067448 0.14609388 -0.1244785, 0.48089412 0.14621165 -0.12447821, 0.48047355 0.1459579 -0.12453516, 0.48030362 0.14581214 -0.12464462, 0.48017535 0.14566571 -0.12480007, 0.48009664 0.14552769 -0.12499194, 0.48007247 0.14540651 -0.12520836, 0.4801043 0.14530972 -0.1254357, 0.48019007 0.1452435 -0.12566014, 0.48462731 0.14475027 -0.13140346, 0.48461902 0.14478934 -0.13131656, 0.4845947 0.14481983 -0.13122933, 0.48455486 0.14484079 -0.13114475, 0.4846274 0.14387326 -0.13315754, 0.48471215 0.14686261 -0.12685592, 0.48478171 0.14690429 -0.12684698, 0.48479685 0.14665928 -0.12693997, 0.48483172 0.14695254 -0.12680383, 0.48493621 0.14674287 -0.12692209, 0.48503581 0.14683947 -0.12683581, 0.48465079 0.14364737 -0.13322116, 0.48472118 0.14367445 -0.13324274, 0.48467419 0.14342161 -0.13328449, 0.48478672 0.14371569 -0.13323037, 0.48481503 0.14347561 -0.13332765, 0.48483303 0.14376201 -0.13318722, 0.4849464 0.14355813 -0.13330321, 0.48503876 0.1436508 -0.13321687, 0.47157827 0.14494419 -0.11661424, 0.47151479 0.14490905 -0.11661662, 0.47146425 0.14486679 -0.11664669, 0.47164613 0.14488252 -0.11639707, 0.47143608 0.14482541 -0.11669926, 0.47151923 0.14481212 -0.11640163, 0.47141802 0.1447276 -0.11646228, 0.47136167 0.14464486 -0.1165673, 0.48435649 0.15042216 -0.11976759, 0.48462719 0.15033337 -0.12023576, 0.48461515 0.15037963 -0.12013026, 0.48457953 0.15041298 -0.12002541, 0.48452237 0.15043183 -0.11992644, 0.48444661 0.15043493 -0.11983915, 0.48462722 0.14926055 -0.12238167, 0.4631184 0.14463545 -0.10857628, 0.46329799 0.14470926 -0.10862146, 0.46347037 0.14475814 -0.10870861, 0.46294269 0.14454129 -0.10857652, 0.46278188 0.1444324 -0.10862182, 0.46264604 0.14431581 -0.10870932, 0.4625434 0.14419869 -0.10883369, 0.46248052 0.14408818 -0.1089872, 0.46246114 0.14399134 -0.10916035, 0.46248659 0.143914 -0.10934232, 0.46255526 0.14386103 -0.10952197, 0.46266267 0.1438358 -0.10968779, 0.48461893 0.14188792 -0.1371202, 0.48459467 0.14191844 -0.13703285, 0.48455486 0.14193934 -0.13694842, 0.48450127 0.14194995 -0.13686986, 0.48462725 0.14184895 -0.13720708, 0.4846274 0.14032699 -0.14025088, 0.45075813 0.14319597 -0.097793028, 0.45069465 0.14316081 -0.097795442, 0.45064405 0.14311853 -0.097825602, 0.45082605 0.14313416 -0.097575828, 0.45061585 0.14307718 -0.097878143, 0.45069915 0.14306392 -0.097580567, 0.45059785 0.14297935 -0.097641155, 0.45054153 0.14289662 -0.097746208, 0.48465082 0.14010131 -0.14031442, 0.48472121 0.1401283 -0.14033599, 0.48467419 0.13987544 -0.14037807, 0.48478672 0.14016953 -0.14032395, 0.48481503 0.13992943 -0.14042087, 0.48483297 0.14021584 -0.1402808, 0.48494631 0.14001195 -0.14039679, 0.48503867 0.14010473 -0.14031033, 0.48471215 0.14905734 -0.12246566, 0.48478159 0.14909913 -0.12245671, 0.48479679 0.14885405 -0.12254976, 0.48483151 0.14914736 -0.12241362, 0.48493615 0.14893766 -0.12253208, 0.48503587 0.14903417 -0.12244566, 0.48777065 0.13662018 -0.14818682, 0.44127145 0.14074248 -0.090286717, 0.48775199 0.13684872 -0.14810289, 0.44126189 0.14105596 -0.090152755, 0.48772323 0.13707733 -0.14796422, 0.48768434 0.13730116 -0.14777209, 0.44126198 0.1414666 -0.089859113, 0.48761842 0.13758446 -0.14743827, 0.44125718 0.14183117 -0.089431927, 0.48753116 0.13786194 -0.1469899, 0.48773393 0.15218702 -0.11868931, 0.48788849 0.15230393 -0.1188262, 0.48782894 0.15236413 -0.11822788, 0.48797446 0.15225603 -0.11967461, 0.4879002 0.15206663 -0.11957984, 0.48762187 0.15175508 -0.11942427, 0.48778084 0.15189679 -0.11949508, 0.48762199 0.13820539 -0.14652742, 0.48778075 0.138347 -0.14659832, 0.48790038 0.13851678 -0.14668335, 0.48797461 0.1387061 -0.14677788, 0.48789957 0.13639589 -0.14840771, 0.48797438 0.1363959 -0.14862002, 0.48773411 0.13776548 -0.14739512, 0.48784703 0.13787781 -0.14749049, 0.4879519 0.13804999 -0.14763655, 0.48779503 0.13737519 -0.14786972, 0.48788255 0.13745776 -0.14797844, 0.48782077 0.13713486 -0.14806853, 0.48796293 0.13757934 -0.14813901, 0.48789743 0.13719776 -0.1481825, 0.48783979 0.13688798 -0.14821185, 0.48796764 0.13728943 -0.14834855, 0.48790839 0.13693024 -0.14832939, 0.4879711 0.13699105 -0.14849867, 0.48767307 0.12658574 -0.14672579, 0.48791441 0.12628202 -0.14686741, 0.4878113 0.12644522 -0.14679132, 0.48797819 0.12610288 -0.14695103, 0.48785269 0.1278286 -0.14826883, 0.48791599 0.12779558 -0.14838548, 0.48797348 0.12774824 -0.14855208, 0.48783877 0.12755559 -0.14813675, 0.48790798 0.12749836 -0.14824842, 0.48797095 0.12741601 -0.14840926, 0.48781034 0.12724522 -0.14788152, 0.48789147 0.1271607 -0.14798428, 0.48796585 0.12703694 -0.14813425, 0.48777345 0.12698917 -0.14756121, 0.48787001 0.12688224 -0.14765312, 0.48795918 0.12672246 -0.14779054, 0.48767319 0.11312518 -0.11786358, 0.4878113 0.11298481 -0.11792915, 0.48791453 0.11282143 -0.11800523, 0.48797825 0.11264226 -0.11808877, 0.48791018 0.11268616 -0.11762555, 0.48790428 0.11259621 -0.11724047, 0.48778602 0.11284736 -0.11752419, 0.48777202 0.11271077 -0.11711727, 0.48766729 0.11294766 -0.11745624, 0.4924221 0.1518881 -0.13455309, 0.49242231 0.11299193 -0.13389663, 0.49242231 0.12593693 -0.16165335, 0.49231496 0.11274076 -0.13312952, 0.49219716 0.11256424 -0.13228954, 0.4922924 0.15219805 -0.13363846, 0.49214846 0.15239152 -0.13262369, 0.49245599 0.12618853 -0.16211815, 0.49247664 0.12652025 -0.16251682, 0.47317857 0.15707673 -0.085173801, 0.47352916 0.15723513 -0.086163834, 0.47303227 0.15723518 -0.085234478, 0.47254029 0.15735413 -0.084262833, 0.47233298 0.15742813 -0.08430405, 0.47285709 0.15735419 -0.085306868, 0.47266182 0.15742816 -0.085387662, 0.47391418 0.15742828 -0.087262139, 0.47328854 0.15688717 -0.085128263, 0.47366074 0.15707681 -0.086075976, 0.4737598 0.15688716 -0.086009815, 0.47272632 0.1572351 -0.084225729, 0.47335705 0.15667573 -0.08510004, 0.47382131 0.15667588 -0.085968688, 0.47288164 0.15707664 -0.084194973, 0.47299853 0.15688699 -0.084171727, 0.47307101 0.15667573 -0.084157214, 0.47444627 0.15667595 -0.086730197, 0.4731957 0.15742816 -0.086386785, 0.47337145 0.15735428 -0.086269245, 0.47406358 0.15735428 -0.08711265, 0.47419772 0.15723526 -0.086978778, 0.47430971 0.15707691 -0.086866722, 0.47439393 0.15688725 -0.08678253, 0.49098524 0.15742937 -0.10433327, 0.49113467 0.15735544 -0.1041839, 0.49126872 0.15723635 -0.10404973, 0.49138066 0.15707795 -0.10393785, 0.491465 0.15688829 -0.10385354, 0.49151728 0.15667696 -0.10380121, 0.4922711 0.15723643 -0.1055498, 0.49184379 0.15723629 -0.10475035, 0.49197552 0.15707788 -0.10466252, 0.49241742 0.15707797 -0.10548912, 0.49151048 0.15742943 -0.10497306, 0.49168608 0.15735546 -0.10485564, 0.4926894 0.15707804 -0.10638617, 0.49290052 0.15688854 -0.1073191, 0.49278137 0.15707806 -0.1073191, 0.4925274 0.15688844 -0.10544358, 0.49280629 0.15688841 -0.10636289, 0.49209586 0.1573555 -0.10562228, 0.49253425 0.15723643 -0.10641716, 0.492623 0.15723647 -0.1073191, 0.49190059 0.15742943 -0.10570301, 0.49234822 0.15735558 -0.10645412, 0.49243334 0.15735556 -0.1073191, 0.49214092 0.15742949 -0.10649525, 0.49222207 0.15742943 -0.1073191, 0.49213603 0.15667701 -0.1045552, 0.49207458 0.15688829 -0.10459621, 0.49259582 0.1566771 -0.10541518, 0.49287882 0.15667705 -0.1063485, 0.49297443 0.1566771 -0.1073191, 0.4922221 0.15743102 -0.13449062, 0.49243346 0.15735708 -0.13449062, 0.49262306 0.15723796 -0.13449062, 0.49278149 0.15707964 -0.13449062, 0.49290052 0.15689002 -0.13449062, 0.49297446 0.15667869 -0.13449065, 0.47295457 0.087377235 0.073759899, 0.47295457 0.08738552 -0.073748842, 0.47298861 0.087524518 0.073759899, 0.47298852 0.087532744 -0.073748842, 0.49222216 0.15729016 -0.13539578, 0.4924334 0.15705091 -0.13578804, 0.49222204 0.15711708 -0.13582112, 0.49222204 0.15739553 -0.13494851, 0.49243352 0.15732259 -0.1349373, 0.49243346 0.15721968 -0.13537316, 0.49297446 0.15665223 -0.13483281, 0.4929004 0.15686108 -0.13486536, 0.49297449 0.15657343 -0.13516669, 0.49297452 0.15644409 -0.13548471, 0.49278143 0.15704836 -0.13489442, 0.49290046 0.15677465 -0.13523103, 0.49290052 0.15663311 -0.13557906, 0.492623 0.15720476 -0.13491888, 0.49278137 0.15695532 -0.13528867, 0.49278137 0.15680274 -0.135664, 0.492623 0.15710618 -0.13533692, 0.49262294 0.15694426 -0.13573475, 0.47314522 0.087880448 -0.075005606, 0.47311702 0.087725282 -0.075070009, 0.49222222 0.14156872 -0.1669222, 0.49243352 0.14150254 -0.16688909, 0.49262312 0.14139593 -0.16683613, 0.49278143 0.14125438 -0.16676508, 0.49290058 0.14108475 -0.16668032, 0.49297461 0.14089574 -0.16658582, 0.47338369 0.087844402 -0.076341256, 0.47381589 0.088307589 -0.076917723, 0.47343603 0.087923184 -0.076276556, 0.47320178 0.087686211 -0.075747952, 0.4734697 0.087990344 -0.076226965, 0.4738718 0.088478401 -0.076766595, 0.4732385 0.087753728 -0.07570903, 0.47350612 0.088094726 -0.076157615, 0.47328034 0.087857917 -0.075654522, 0.47353306 0.088284969 -0.076050356, 0.47388002 0.088671267 -0.076632485, 0.4733189 0.088046908 -0.075569704, 0.4730306 0.087513074 -0.075226083, 0.47306964 0.087580889 -0.075197592, 0.47305921 0.087541983 -0.075326517, 0.47300169 0.087461308 -0.075366214, 0.47309789 0.087609664 -0.075296, 0.47311547 0.087685034 -0.075157508, 0.47314295 0.087713942 -0.075253353, 0.47316244 0.087872833 -0.075094536, 0.47314611 0.087606207 -0.075798616, 0.47318855 0.087901905 -0.075186089, 0.49247479 0.140587 -0.16793625, 0.49263746 0.14102331 -0.16738106, 0.49265137 0.14051585 -0.16783796, 0.4924545 0.14111547 -0.16745828, 0.49291101 0.13978535 -0.1678469, 0.49290791 0.14031643 -0.16756271, 0.49297628 0.14019698 -0.16739775, 0.49297693 0.13971129 -0.16766073, 0.49227574 0.14063473 -0.16800217, 0.4922494 0.14117505 -0.16750835, 0.49280494 0.13985226 -0.16801523, 0.49279782 0.14042431 -0.1677116, 0.49297756 0.13930164 -0.1677774, 0.49297056 0.13889292 -0.16784619, 0.4926635 0.13990954 -0.16815911, 0.49291289 0.13933824 -0.16797222, 0.49288532 0.13889305 -0.1680712, 0.49249268 0.13995472 -0.16827257, 0.49280921 0.13937157 -0.16814868, 0.49274862 0.13889298 -0.16826962, 0.49229899 0.13998595 -0.1683508, 0.4926711 0.13940012 -0.16830014, 0.49256846 0.13889313 -0.16842954, 0.49250379 0.13942292 -0.16842057, 0.49235529 0.13889305 -0.1685416, 0.4923138 0.13943884 -0.1685047, 0.49297544 0.14060125 -0.16702606, 0.49290431 0.14076003 -0.16715954, 0.49278983 0.14090303 -0.16727977, 0.49213529 0.10662888 -0.10438569, 0.49219114 0.10679968 -0.10423456, 0.49219945 0.10699251 -0.10410045, 0.4923555 0.12528439 -0.16854249, 0.49256858 0.12528437 -0.16843022, 0.49274865 0.12528434 -0.16827039, 0.49288538 0.12528434 -0.16807221, 0.49297079 0.12528427 -0.1678469, 0.49283132 0.10731313 -0.10676514, 0.49289218 0.10759656 -0.10583539, 0.49298063 0.10767366 -0.10676514, 0.49284074 0.1074083 -0.1058829, 0.49292377 0.10748602 -0.10676514, 0.49275243 0.10723548 -0.10593461, 0.49262694 0.10736544 -0.10493051, 0.49259216 0.10717519 -0.10502373, 0.49251595 0.10700287 -0.10512672, 0.49290773 0.1237815 -0.167504, 0.49297693 0.12429798 -0.16758756, 0.49297637 0.12390792 -0.16734378, 0.49291015 0.1242083 -0.16776775, 0.49248832 0.12400392 -0.16817869, 0.49250141 0.12459366 -0.16838734, 0.49266949 0.12462322 -0.16826858, 0.49266049 0.12405825 -0.1680695, 0.4927974 0.12366752 -0.16764869, 0.49280316 0.12412736 -0.16793068, 0.49229342 0.12396675 -0.16825353, 0.49231052 0.12457308 -0.16847028, 0.49297553 0.12356484 -0.16701235, 0.4926503 0.12357087 -0.16777121, 0.4929046 0.12340495 -0.16714419, 0.49247333 0.12349576 -0.16786645, 0.49297509 0.12339312 -0.16677873, 0.49297467 0.12325615 -0.1665322, 0.49279043 0.12326123 -0.16726305, 0.49227378 0.12344556 -0.16793002, 0.49290273 0.12321584 -0.16689007, 0.4929007 0.12306459 -0.16662143, 0.49278167 0.12289257 -0.16670142, 0.49263844 0.12313996 -0.16736306, 0.49278602 0.12305671 -0.16699038, 0.49245605 0.12304705 -0.16743971, 0.49297753 0.12475179 -0.16775148, 0.49263084 0.12292311 -0.16707443, 0.49262318 0.12274913 -0.16676857, 0.49243364 0.12264128 -0.16681884, 0.4929125 0.12470391 -0.16794442, 0.49280846 0.12466049 -0.16811897, 0.49225119 0.12298696 -0.16748939, 0.49244484 0.1228217 -0.16713797, 0.49223676 0.12275733 -0.1671785, 0.49222225 0.12257424 -0.1668501, 0.49283141 0.1073146 -0.13301565, 0.4929238 0.1074876 -0.13301565, 0.49298069 0.10767514 -0.13301556, 0.49222234 0.10698678 -0.13342752, 0.49243373 0.10705359 -0.13339625, 0.49262339 0.10716166 -0.1333461, 0.49278167 0.10730517 -0.13327901, 0.49290082 0.10747699 -0.13319893, 0.49297476 0.10766862 -0.13310982, 0.47090897 0.095733628 -0.11031865, 0.47097385 0.095949277 -0.11037873, 0.47105297 0.096140921 -0.11048533, 0.47114214 0.09629795 -0.11063264, 0.47170749 0.095511243 -0.10966621, 0.41264543 0.036587536 -0.13364626, 0.47164184 0.095540121 -0.10977589, 0.47154835 0.09555836 -0.10988544, 0.41264859 0.036863759 -0.13377105, 0.47142848 0.095565274 -0.10999225, 0.47123161 0.095556691 -0.11012696, 0.41262311 0.037038967 -0.13382576, 0.47105449 0.095536545 -0.11022256, 0.49256194 0.10705203 -0.13313504, 0.49219981 0.10694979 -0.13335158, 0.49239019 0.10697959 -0.13324882, 0.49256977 0.10710146 -0.13330595, 0.47189769 0.095606461 -0.109524, 0.4719567 0.095734417 -0.10965239, 0.47207439 0.095710531 -0.10950689, 0.471825 0.095632896 -0.10965203, 0.47176877 0.095840588 -0.10992651, 0.4716506 0.09570913 -0.10989521, 0.47210023 0.095815331 -0.10966669, 0.47226793 0.095780358 -0.10950889, 0.47189969 0.095950678 -0.10997783, 0.47225329 0.095874429 -0.1096945, 0.47204044 0.096036911 -0.1100484, 0.47130635 0.095748559 -0.11014675, 0.47139904 0.095922992 -0.11020111, 0.47151995 0.09573324 -0.11000918, 0.47150603 0.096074209 -0.11028717, 0.47162822 0.095882311 -0.11005233, 0.47162357 0.096196741 -0.11040233, 0.47175002 0.096009299 -0.11012004, 0.47188199 0.096110538 -0.1102102, 0.4749901 0.089738011 -0.096446082, 0.47518054 0.089767724 -0.096343532, 0.47535232 0.089839965 -0.096229568, 0.47431603 0.088893116 -0.095358506, 0.47435388 0.08893472 -0.095359728, 0.47439191 0.088980287 -0.09537448, 0.47443005 0.089029819 -0.095402643, 0.47448036 0.089101851 -0.09546198, 0.47456732 0.089244843 -0.09562774, 0.47464934 0.089403868 -0.095866933, 0.47439954 0.088885501 -0.095157519, 0.47445908 0.088947117 -0.095168278, 0.47448066 0.088943243 -0.095061675, 0.47442982 0.088959292 -0.095272318, 0.47452864 0.089073479 -0.095339671, 0.47458109 0.089075863 -0.095232412, 0.47434166 0.088826701 -0.095161125, 0.4742808 0.088748649 -0.095111862, 0.47428682 0.088796079 -0.095243737, 0.47434255 0.088804543 -0.09505932, 0.47441056 0.088872671 -0.095053121, 0.47438076 0.088906109 -0.095259473, 0.47433278 0.088855997 -0.095260516, 0.47499463 0.089467719 -0.095518634, 0.47489032 0.089419648 -0.095634267, 0.47477242 0.089393467 -0.095743373, 0.47480741 0.089275286 -0.095275536, 0.47473487 0.089243576 -0.095389262, 0.47465113 0.089227021 -0.095498577, 0.47462454 0.089088753 -0.095121875, 0.41255668 0.027066469 -0.12018804, 0.41255656 0.027024895 -0.12005444, 0.47486803 0.12624583 -0.17060928, 0.47503588 0.12624589 -0.17065422, 0.47503591 0.1346336 -0.17065375, 0.47486797 0.13463356 -0.17060889, 0.47576919 0.13500892 -0.17054497, 0.475826 0.13791069 -0.17055635, 0.47565767 0.13791062 -0.17051129, 0.4756299 0.13513389 -0.17050092, 0.47510448 0.13955303 -0.16938518, 0.47510803 0.13905583 -0.16974063, 0.47502685 0.13895296 -0.16954519, 0.47549877 0.13815422 -0.17042647, 0.4754304 0.13815059 -0.17038335, 0.47562823 0.13927755 -0.17016138, 0.47564462 0.13863221 -0.17041554, 0.47549167 0.13861412 -0.17034434, 0.47547871 0.13924263 -0.17009522, 0.47524646 0.13847944 -0.1701671, 0.47524795 0.1383068 -0.17020105, 0.47511193 0.13827708 -0.17000403, 0.47500578 0.13960458 -0.16883515, 0.47499964 0.13946068 -0.16884004, 0.47499964 0.13971433 -0.16845094, 0.47511116 0.13843685 -0.16997312, 0.47502485 0.13991341 -0.16855042, 0.47542807 0.13833091 -0.17036019, 0.47530752 0.13814197 -0.17028309, 0.47523105 0.13968281 -0.16952933, 0.4752391 0.13914751 -0.1699145, 0.47524559 0.13856386 -0.17014612, 0.47511098 0.13851495 -0.16995384, 0.47500607 0.1388976 -0.16944017, 0.47499952 0.13877213 -0.16937648, 0.4749997 0.13911691 -0.16916765, 0.47584596 0.13930537 -0.17021422, 0.47586659 0.13864601 -0.17047001, 0.47565374 0.13816036 -0.17049895, 0.47502533 0.1396966 -0.16890453, 0.47502598 0.13940772 -0.16922359, 0.47549626 0.13833728 -0.17040314, 0.47599968 0.13931081 -0.17022465, 0.47602236 0.1386482 -0.17047857, 0.47542551 0.13851386 -0.17032434, 0.47539914 0.13978957 -0.16964824, 0.47541305 0.13922228 -0.17005657, 0.47502759 0.13846 -0.16973712, 0.47510162 0.1398675 -0.16903375, 0.47509858 0.14010243 -0.16864498, 0.47565034 0.13834819 -0.17047553, 0.47607926 0.13930935 -0.17022182, 0.47549319 0.13852321 -0.17036681, 0.47546282 0.13981906 -0.16968088, 0.4754242 0.13860346 -0.17030217, 0.47587788 0.1381651 -0.1705531, 0.47560796 0.13987008 -0.16973762, 0.47522447 0.14002058 -0.16914929, 0.47521779 0.14027211 -0.16872971, 0.47564653 0.13853885 -0.17043833, 0.47582027 0.13991268 -0.16978507, 0.47538754 0.14014745 -0.16924541, 0.47537616 0.14041366 -0.16880049, 0.47587386 0.1383564 -0.17052974, 0.47544953 0.14018276 -0.16927208, 0.47556582 0.14052024 -0.16885386, 0.47586897 0.13855092 -0.17049305, 0.47597113 0.13992313 -0.16979684, 0.47604981 0.13992259 -0.16979624, 0.47559085 0.14024457 -0.16931884, 0.47577706 0.14058636 -0.16888683, 0.47579867 0.14029792 -0.16935931, 0.47500578 0.13932949 -0.16913675, 0.47500631 0.13843036 -0.16962065, 0.47500613 0.13836303 -0.16963674, 0.47499958 0.13840222 -0.16951005, 0.47594705 0.14031312 -0.16937093, 0.47502771 0.1383888 -0.16975431, 0.47502598 0.13832317 -0.16976084, 0.47602516 0.13855253 -0.17050101, 0.47602469 0.14031385 -0.1693715, 0.4751586 0.13820954 -0.17009483, 0.47507754 0.13826618 -0.16993178, 0.47499946 0.15575489 -0.11477502, 0.47499952 0.15645602 -0.13449062, 0.4749994 0.15575609 -0.13479771, 0.47499958 0.15645495 -0.11477502, 0.47499946 0.15643224 -0.13479845, 0.47499952 0.15636121 -0.13509901, 0.47499958 0.15624492 -0.13538511, 0.47490343 0.15645494 -0.11379956, 0.47490343 0.15575501 -0.11379959, 0.47461894 0.15645477 -0.11286144, 0.47461888 0.15575477 -0.11286144, 0.47415689 0.15645471 -0.11199705, 0.47415695 0.15575464 -0.11199705, 0.47353509 0.15645473 -0.1112393, 0.47353509 0.1557547 -0.11123954, 0.45646399 0.15575358 -0.09416844, 0.4564639 0.15645359 -0.094168261, 0.45509562 0.15575345 -0.09160842, 0.4549996 0.15575334 -0.09063296, 0.45499963 0.15645342 -0.09063296, 0.45509562 0.15645342 -0.09160836, 0.45538011 0.15575352 -0.092546359, 0.45538005 0.15645358 -0.092546239, 0.45584223 0.15575352 -0.093410775, 0.45584211 0.15645358 -0.093410626, 0.45499948 0.15644324 0.090651497, 0.45499948 0.15574327 0.090651497, 0.47577697 0.15711699 -0.13582112, 0.4755657 0.1570508 -0.13578789, 0.47537598 0.15694425 -0.13573475, 0.47521767 0.15680262 -0.135664, 0.47509849 0.15663306 -0.13557906, 0.47502461 0.15644392 -0.13548471, 0.47577706 0.15739557 -0.13494854, 0.47577697 0.15743099 -0.13449062, 0.4755657 0.15735693 -0.13449062, 0.4755657 0.15721954 -0.13537301, 0.4755657 0.15732242 -0.1349373, 0.475777 0.15729007 -0.13539578, 0.47502473 0.15667853 -0.13449062, 0.47502467 0.15657327 -0.13516669, 0.47509858 0.15677455 -0.13523115, 0.47502476 0.15665209 -0.13483281, 0.4752177 0.15695517 -0.13528867, 0.47509849 0.15686099 -0.13486536, 0.47509858 0.15688996 -0.13449062, 0.47537604 0.15710612 -0.13533692, 0.47521779 0.15704826 -0.13489468, 0.4752177 0.1570795 -0.13449062, 0.4753761 0.15720466 -0.13491888, 0.47537607 0.15723795 -0.13449062, 0.47577694 0.15742989 -0.11477487, 0.4755657 0.15735586 -0.11477496, 0.47537604 0.15723677 -0.11477502, 0.47521773 0.15707842 -0.11477502, 0.47509852 0.15688881 -0.11477502, 0.47502461 0.15667742 -0.11477502, 0.47482049 0.15707825 -0.11277796, 0.47446987 0.15723662 -0.11178793, 0.47496685 0.15723661 -0.11271738, 0.4743382 0.15707834 -0.11187588, 0.47545865 0.1573558 -0.11368899, 0.47533712 0.15742978 -0.11256389, 0.47566596 0.15742984 -0.11364774, 0.47514191 0.15735576 -0.11264475, 0.47408476 0.15742961 -0.11068951, 0.47471038 0.15688868 -0.11282359, 0.4742392 0.15688869 -0.11194204, 0.47527263 0.15723668 -0.11372598, 0.47464213 0.1566774 -0.11285208, 0.47417763 0.15667737 -0.11198322, 0.47511747 0.1570784 -0.11375682, 0.47500053 0.15688881 -0.1137801, 0.47492805 0.15667734 -0.11379449, 0.47480321 0.15742968 -0.1115651, 0.47462747 0.15735573 -0.11168252, 0.47393534 0.15735562 -0.11083902, 0.47380123 0.15723653 -0.1109731, 0.47368932 0.15707813 -0.11108528, 0.47360498 0.15688865 -0.11116932, 0.47355276 0.15667728 -0.11122166, 0.45701364 0.15742853 -0.093618557, 0.45686427 0.15735461 -0.093767926, 0.45673016 0.15723546 -0.093902126, 0.45661822 0.15707716 -0.094013974, 0.45653388 0.15688758 -0.094098255, 0.45648167 0.1566762 -0.094150648, 0.45572791 0.15723546 -0.092402086, 0.45615533 0.15723544 -0.093201503, 0.45602345 0.15707706 -0.09328936, 0.45558164 0.15707712 -0.092462674, 0.45648864 0.15742847 -0.092978612, 0.45631287 0.15735456 -0.093096033, 0.45530966 0.15707693 -0.091565654, 0.45509854 0.15688731 -0.09063296, 0.45521769 0.15707691 -0.090632811, 0.45547161 0.15688744 -0.092508242, 0.45519277 0.15688732 -0.091589019, 0.45590314 0.1573545 -0.092329636, 0.45546493 0.15723522 -0.091534749, 0.45537606 0.15723523 -0.090632811, 0.45609841 0.15742847 -0.092248693, 0.45565084 0.15735443 -0.091497794, 0.45556575 0.15735434 -0.090632811, 0.4558582 0.1574284 -0.091456518, 0.45577705 0.15742837 -0.090632811, 0.45586303 0.15667613 -0.093396679, 0.45592448 0.1568875 -0.093355671, 0.45540333 0.1566761 -0.092536733, 0.45512024 0.15667596 -0.091603383, 0.45502463 0.15667592 -0.090632811, 0.45577699 0.15741824 0.090651497, 0.45556572 0.15734424 0.090651497, 0.45537606 0.15722516 0.090651497, 0.45521769 0.15706678 0.090651497, 0.4550986 0.15687709 0.090651497, 0.45502463 0.15666583 0.090651497, 0.47296992 0.11741874 -0.073747113, 0.47296998 0.11741036 0.073761329, 0.47288236 0.11764653 -0.073747113, 0.47288224 0.11763832 0.073761329, 0.47274193 0.11784656 -0.073747113, 0.47274217 0.11783814 0.073761329, 0.47255763 0.11800632 -0.073747113, 0.47255775 0.11799806 0.073761538, 0.47384423 0.11702004 -0.076568678, 0.47307721 0.11733888 -0.074736103, 0.47301891 0.11753339 -0.074761584, 0.47292301 0.11771086 -0.074793264, 0.47279337 0.1178644 -0.07483004, 0.472635 0.11798769 -0.074870065, 0.47337127 0.11721678 -0.07569541, 0.47332248 0.11741278 -0.075745001, 0.47381017 0.11721875 -0.076639399, 0.47323629 0.11759135 -0.075807348, 0.47373965 0.11739896 -0.076729849, 0.47311649 0.1177447 -0.075879976, 0.47363588 0.11755228 -0.076836064, 0.47350332 0.11767188 -0.076953486, 0.47296795 0.11786661 -0.075959787, 0.48865014 0.11165845 -0.09876658, 0.48860627 0.111863 -0.098820284, 0.48852384 0.11205287 -0.098897979, 0.48840752 0.11221364 -0.098994747, 0.48826656 0.11233528 -0.099103227, 0.4921388 0.1116769 -0.10400461, 0.4920772 0.11188826 -0.10404567, 0.49197817 0.1120778 -0.10411175, 0.49184629 0.11223626 -0.10419975, 0.49168849 0.11235538 -0.10430478, 0.49151275 0.11242938 -0.10442214, 0.49259719 0.11167702 -0.10486372, 0.49287945 0.1116769 -0.10579585, 0.49252883 0.11188838 -0.10489209, 0.49280697 0.11188832 -0.10581027, 0.49297476 0.11167696 -0.1067649, 0.49214146 0.11242957 -0.10594235, 0.49222246 0.11242956 -0.1067649, 0.4923487 0.11235537 -0.10590108, 0.49243364 0.11235553 -0.10676475, 0.4919019 0.11242937 -0.10515116, 0.49253473 0.11223628 -0.10586412, 0.49262327 0.11223635 -0.1067649, 0.4920972 0.11235538 -0.10507055, 0.49269 0.11207801 -0.10583352, 0.4927817 0.11207792 -0.1067649, 0.49227235 0.11223634 -0.1049981, 0.49290082 0.11188838 -0.1067649, 0.49241886 0.11207795 -0.10493766, 0.49222249 0.11243084 -0.1308824, 0.49243379 0.11235681 -0.1308824, 0.49262336 0.11223777 -0.1308824, 0.49278179 0.11207944 -0.13088252, 0.49290082 0.11188978 -0.1308824, 0.49297476 0.11167839 -0.1308824, 0.49261546 0.11288469 -0.13394664, 0.4927769 0.11274092 -0.13401379, 0.49246392 0.11263146 -0.13298608, 0.49261662 0.11253656 -0.13301308, 0.49274719 0.11241868 -0.13304736, 0.49289861 0.11256778 -0.13409437, 0.49287322 0.11224845 -0.13309626, 0.49296787 0.11202084 -0.13316192, 0.49297413 0.11237447 -0.13418473, 0.49234691 0.11246622 -0.13194765, 0.492529 0.11237772 -0.13195978, 0.49268824 0.11225572 -0.13197647, 0.49284366 0.11206877 -0.13200237, 0.4929609 0.11181094 -0.13203777, 0.49297398 0.12531945 -0.16194128, 0.49289855 0.12551281 -0.16185115, 0.49277684 0.12568596 -0.16177033, 0.49261549 0.12582976 -0.16170321, 0.49265304 0.12643671 -0.16260491, 0.49279931 0.12632892 -0.16271828, 0.49290875 0.12620218 -0.16285165, 0.49297658 0.12606236 -0.1629989, 0.49285311 0.12588914 -0.1623318, 0.49297407 0.13587493 -0.16390406, 0.49289849 0.13587488 -0.16369052, 0.49277684 0.13587488 -0.1634997, 0.49261537 0.13587488 -0.16334088, 0.49265099 0.13692223 -0.16317971, 0.49279812 0.13697828 -0.16332577, 0.49290815 0.13704424 -0.16349791, 0.4929764 0.13711703 -0.16368793, 0.49285254 0.13645467 -0.16355439, 0.4929738 0.1524975 -0.13485758, 0.49289826 0.15230663 -0.1347623, 0.4927766 0.15213588 -0.13467686, 0.49261522 0.1519939 -0.13460593, 0.49222216 0.152481 -0.13157441, 0.49297452 0.15323342 -0.13157441, 0.49234709 0.15244205 -0.13263108, 0.492529 0.15253043 -0.13264404, 0.49243346 0.15255503 -0.13157441, 0.49268818 0.15265235 -0.13266195, 0.492623 0.15267409 -0.13157441, 0.4927814 0.15283248 -0.13157441, 0.49284342 0.15283895 -0.13268901, 0.49290055 0.15302202 -0.13157441, 0.49296069 0.15309653 -0.13272648, 0.49276945 0.15259764 -0.13338868, 0.49280366 0.15254349 -0.13374467, 0.49284041 0.15248254 -0.13409288, 0.49222216 0.15247969 -0.10731946, 0.49243337 0.15255368 -0.10731946, 0.49262309 0.15267277 -0.10731946, 0.49278137 0.15283114 -0.10731946, 0.49290052 0.15302081 -0.10731946, 0.49297452 0.15323213 -0.10731946, 0.49213603 0.15323187 -0.10455547, 0.49151728 0.1532319 -0.10380171, 0.49207461 0.15302059 -0.10459636, 0.49253419 0.15267272 -0.10641752, 0.49209604 0.15255357 -0.10562263, 0.49234825 0.15255359 -0.10645436, 0.49227104 0.15267268 -0.10555001, 0.4909853 0.15247945 -0.10433359, 0.49252746 0.15302059 -0.10544394, 0.49197555 0.1528309 -0.10466273, 0.4924174 0.15283099 -0.10548936, 0.49268943 0.15283105 -0.10638641, 0.49259588 0.15323199 -0.10541569, 0.49280629 0.15302068 -0.10636316, 0.49287882 0.15323205 -0.10634874, 0.49151051 0.15247954 -0.10497339, 0.49113479 0.15255356 -0.10418411, 0.49168622 0.15255353 -0.10485609, 0.49126887 0.15267266 -0.10405, 0.49190071 0.15247959 -0.10570346, 0.49184388 0.15267262 -0.10475074, 0.49138072 0.15283088 -0.10393806, 0.491465 0.15302052 -0.10385381, 0.49214092 0.1524796 -0.10649548, 0.48859546 0.15323025 -0.10087995, 0.48855007 0.15300579 -0.10094889, 0.48846447 0.15280122 -0.10105623, 0.48834434 0.15263623 -0.10119398, 0.48820159 0.1525232 -0.10134839, 0.47446892 0.15021314 -0.086757436, 0.47443402 0.14999357 -0.086838946, 0.47436103 0.14979963 -0.086953238, 0.4742544 0.14964181 -0.087093428, 0.47411987 0.14952888 -0.087252155, 0.47373161 0.15003259 -0.085832551, 0.4736771 0.14981613 -0.085894421, 0.47358009 0.14962339 -0.085979298, 0.47344586 0.14946479 -0.086082891, 0.47328207 0.1493492 -0.086198881, 0.47315419 0.14969306 -0.084776744, 0.47304061 0.14950158 -0.084826663, 0.47288814 0.14934304 -0.084887102, 0.47303563 0.1498616 -0.083960965, 0.47297397 0.14984633 -0.083177283, 0.47270453 0.14922559 -0.084954724, 0.47296184 0.14964792 -0.083979681, 0.47289845 0.14963289 -0.083177283, 0.47284231 0.14945687 -0.084004715, 0.47277677 0.14944199 -0.083177283, 0.47268304 0.14929819 -0.084034994, 0.47261539 0.14928323 -0.083177283, 0.47242233 0.14916496 -0.083177403, 0.47249243 0.14918014 -0.08406876, 0.47297385 0.14983694 0.083195314, 0.47289836 0.1496236 0.083195314, 0.47277677 0.14943263 0.083195224, 0.47261539 0.14927387 0.083195314, 0.4724223 0.14915565 0.083195314, 0.4125157 -0.025864035 -0.089455262, 0.46267983 0.07684049 -0.089368805, 0.41252163 -0.026073143 -0.089310005, 0.41683689 0.037676841 -0.12756105, 0.41683862 0.037690997 -0.12760054, 0.4182708 0.035096288 -0.12076254, 0.41831943 0.035045296 -0.12075658, 0.41836262 0.034993514 -0.12073509, 0.41839769 0.034943879 -0.120699, 0.41842279 0.034899071 -0.12065057, 0.41935286 0.036041155 -0.12046511, 0.41938728 0.03600949 -0.1204292, 0.41941595 0.035981879 -0.12038334, 0.41942742 0.035970047 -0.12035747, 0.41985044 0.036713913 -0.12047978, 0.4198792 0.036694944 -0.1204588, 0.41991368 0.036673054 -0.12042432, 0.41994372 0.036655053 -0.12038179, 0.41995665 0.036647975 -0.12035806, 0.42035845 0.037561178 -0.12067433, 0.4203904 0.037546381 -0.12066169, 0.42042032 0.037533939 -0.12064548, 0.42044851 0.037523717 -0.12062629, 0.4204829 0.037513494 -0.12059577, 0.42051443 0.037507176 -0.12055899, 0.42052853 0.037505656 -0.12053879, 0.42065984 0.038074791 -0.12089248, 0.42069101 0.038065583 -0.12088053, 0.42072049 0.038058698 -0.12086602, 0.42074814 0.038054034 -0.12084888, 0.42078254 0.038050994 -0.12082227, 0.4208149 0.038051844 -0.12079041, 0.42082962 0.038053751 -0.12077288, 0.42084429 0.038458541 -0.12112544, 0.42087528 0.0384534 -0.12111501, 0.42090425 0.038450629 -0.12110235, 0.42093173 0.038450032 -0.12108763, 0.42096612 0.038452327 -0.12106474, 0.42099878 0.038458526 -0.12103756, 0.42101404 0.038463086 -0.12102239, 0.42097995 0.03882736 -0.12142177, 0.42101046 0.038826257 -0.12141351, 0.42103937 0.038827419 -0.12140365, 0.42106685 0.038830638 -0.12139185, 0.42110112 0.038838014 -0.12137346, 0.42113402 0.038849369 -0.1213512, 0.42114946 0.038856536 -0.12133889, 0.42108878 0.039210141 -0.12182839, 0.42111745 0.039215222 -0.12182231, 0.42114481 0.03922233 -0.1218148, 0.42117918 0.039235055 -0.12180232, 0.42121223 0.039251998 -0.12178667, 0.4212279 0.039261922 -0.12177782, 0.42109847 0.039562136 -0.12235521, 0.4211258 0.039572746 -0.12235297, 0.42116031 0.039590314 -0.12234794, 0.42119327 0.039612561 -0.1223404, 0.42120889 0.039625287 -0.12233551, 0.42096677 0.039810181 -0.12294681, 0.42099431 0.039823323 -0.12295075, 0.4210287 0.039844543 -0.12295397, 0.42106149 0.039871216 -0.12295489, 0.4210768 0.039886415 -0.12295456, 0.42072782 0.03994678 -0.12356965, 0.42075557 0.039961264 -0.12357973, 0.42078999 0.03998509 -0.12359174, 0.42082223 0.040015221 -0.1236019, 0.42083704 0.040032178 -0.12360604, 0.42033532 0.039954051 -0.12415667, 0.42036733 0.039960533 -0.12417538, 0.42039737 0.039971277 -0.124193, 0.4204255 0.039985776 -0.12420969, 0.42045975 0.040010899 -0.12423049, 0.42049143 0.040043175 -0.1242498, 0.42050537 0.040061727 -0.12425862, 0.41976061 0.039823204 -0.12496065, 0.41979393 0.039825499 -0.12498645, 0.41982523 0.039833203 -0.12501259, 0.41985407 0.039846078 -0.12503801, 0.41988841 0.039870769 -0.1250708, 0.41991857 0.039904356 -0.12510298, 0.41993114 0.039924204 -0.12511824, 0.41890165 0.039421156 -0.12586318, 0.41893753 0.039415181 -0.12589596, 0.41897053 0.039416417 -0.12593062, 0.41900072 0.039424509 -0.12596641, 0.41903505 0.0394454 -0.12601443, 0.41906258 0.039477855 -0.12606271, 0.41907296 0.039497867 -0.12608571, 0.4182795 0.03894268 -0.12656839, 0.41831371 0.038958222 -0.12662743, 0.41833857 0.038987622 -0.12668784, 0.4183467 0.039006755 -0.12671657, 0.41746637 0.038290232 -0.1270877, 0.41750017 0.038297698 -0.12715791, 0.41752121 0.038321242 -0.12723099, 0.41752622 0.038338259 -0.1272658, 0.41299278 0.03689377 -0.12577756, 0.41297051 0.036878601 -0.12571584, 0.4129706 0.036454991 -0.12576722, 0.41297063 0.038211852 -0.12421058, 0.41293475 0.038155422 -0.12379082, 0.41293469 0.038155496 -0.12420388, 0.41299278 0.03730686 -0.12237416, 0.41299275 0.037307009 -0.12562077, 0.41297057 0.037277505 -0.12556468, 0.41299278 0.036893606 -0.12221749, 0.4129706 0.036878482 -0.12227912, 0.41297051 0.037277386 -0.12243031, 0.4129706 0.038211837 -0.12378405, 0.41293493 0.038056597 -0.12460478, 0.41288728 0.038108274 -0.12419803, 0.41288742 0.038012147 -0.12458788, 0.41297051 0.037628561 -0.12267266, 0.41293481 0.037250921 -0.12248062, 0.41293481 0.037590772 -0.12271516, 0.41288739 0.037825614 -0.12494345, 0.41283047 0.037978798 -0.12457524, 0.41293481 0.037864596 -0.12302427, 0.41288728 0.037559316 -0.12275083, 0.41288736 0.037825555 -0.12305124, 0.41299278 0.036455065 -0.12583072, 0.41276702 0.036839664 -0.12243663, 0.41276702 0.036454856 -0.12238987, 0.41270027 0.036454991 -0.12239747, 0.41283047 0.037796184 -0.12492315, 0.41288736 0.038012087 -0.12340675, 0.41283044 0.03779614 -0.12307154, 0.41270027 0.036837816 -0.12244399, 0.41283047 0.037535712 -0.1252173, 0.41276711 0.037777975 -0.12491061, 0.41283047 0.037978709 -0.12341951, 0.41283047 0.036844879 -0.12241505, 0.41276702 0.037521005 -0.12520082, 0.41283032 0.036454946 -0.12236778, 0.41283047 0.03807275 -0.12380104, 0.41276702 0.037957981 -0.12342735, 0.41276702 0.038050711 -0.1238036, 0.41276714 0.037202075 -0.12542073, 0.41270038 0.037515998 -0.12519498, 0.41270036 0.037198618 -0.12541427, 0.41299281 0.038274884 -0.12421833, 0.41299289 0.03827475 -0.12377651, 0.41276702 0.038050771 -0.12419124, 0.41270033 0.038043186 -0.12380449, 0.41270038 0.038043275 -0.1241902, 0.41276699 0.037201956 -0.12257405, 0.41270024 0.037198454 -0.12258072, 0.41299278 0.037670583 -0.1226251, 0.41297063 0.038109794 -0.12462501, 0.41288739 0.036853492 -0.12238033, 0.41288731 0.036454931 -0.12233205, 0.4129706 0.03791149 -0.12299199, 0.4129349 0.03786476 -0.12497042, 0.41293481 0.038056582 -0.12338991, 0.41283047 0.037212312 -0.12255429, 0.41288736 0.03755942 -0.12524401, 0.41288731 0.03810823 -0.12379666, 0.41276702 0.037520871 -0.12279402, 0.41270021 0.037515908 -0.12279974, 0.4128305 0.037212417 -0.12544055, 0.41293481 0.036864772 -0.12233417, 0.41293481 0.036454812 -0.1222844, 0.41283041 0.038072824 -0.12419389, 0.41276714 0.036839709 -0.12555821, 0.41270027 0.03645502 -0.12559746, 0.41276702 0.03645502 -0.12560521, 0.41288739 0.037228853 -0.1225227, 0.41270038 0.036837921 -0.12555106, 0.41299275 0.03816916 -0.12464733, 0.41276702 0.037958071 -0.12456743, 0.41270027 0.037950978 -0.12456472, 0.41283047 0.037535578 -0.12277754, 0.41299266 0.037963614 -0.12295599, 0.41297051 0.03791149 -0.12500282, 0.41276702 0.037777886 -0.12308426, 0.41270036 0.037771657 -0.12308846, 0.41293493 0.037590876 -0.12527953, 0.4129706 0.038109764 -0.12336992, 0.41297051 0.036454916 -0.12222765, 0.41288731 0.037229061 -0.12547214, 0.41283041 0.036845073 -0.12557979, 0.41283041 0.03645505 -0.12562715, 0.41299278 0.037963763 -0.1250387, 0.41297063 0.037628636 -0.12532209, 0.41270036 0.037771747 -0.12490638, 0.41299281 0.038169026 -0.12334715, 0.41293478 0.0372511 -0.12551422, 0.41270036 0.037950948 -0.12342991, 0.41288731 0.036853582 -0.12561439, 0.41288739 0.036455035 -0.125663, 0.41299278 0.036454901 -0.1221642, 0.41299292 0.037670657 -0.12536953, 0.4129349 0.036864951 -0.12566073, 0.41293481 0.03645502 -0.12571044, 0.41100031 0.036455005 -0.12559746, 0.41100031 0.036837906 -0.12555106, 0.41100022 0.037198707 -0.12541412, 0.41100019 0.037516087 -0.1251951, 0.41100019 0.037771806 -0.12490638, 0.41100022 0.037951052 -0.12456487, 0.41100031 0.038043261 -0.1241902, 0.41100022 0.03804329 -0.12380455, 0.41100031 0.037950873 -0.12343006, 0.41100031 0.037771583 -0.12308867, 0.41100022 0.037515894 -0.12279974, 0.41100031 0.037198424 -0.12258081, 0.41100025 0.036837876 -0.12244399, 0.41100025 0.036454976 -0.12239747, 0.41270038 0.034455001 -0.12559746, 0.41100031 0.034455001 -0.12559761, 0.41100025 0.034454942 -0.12239753, 0.41270018 0.034454927 -0.12239753, 0.41100034 0.034071997 -0.12244408, 0.41270027 0.034072042 -0.12244408, 0.4127003 0.033711389 -0.12258081, 0.41100031 0.033711359 -0.12258081, 0.41270027 0.033393979 -0.12279995, 0.41100022 0.033393964 -0.12279995, 0.41270038 0.033138156 -0.1230887, 0.41100034 0.033138171 -0.1230887, 0.41100025 0.032958969 -0.12343021, 0.41270033 0.032958925 -0.12343021, 0.41100022 0.032866627 -0.12380479, 0.41270038 0.032866597 -0.12380476, 0.41100031 0.032866672 -0.12419064, 0.41270038 0.032866597 -0.12419064, 0.41100022 0.032959044 -0.12456508, 0.41270033 0.032958969 -0.12456508, 0.41100034 0.033138275 -0.12490661, 0.41270038 0.033138275 -0.12490647, 0.41100034 0.033394024 -0.12519534, 0.41270038 0.033394098 -0.12519534, 0.41100031 0.033711419 -0.12541442, 0.41270033 0.033711404 -0.12541433, 0.41100031 0.034072101 -0.12555109, 0.41270038 0.034072101 -0.12555109, 0.41276705 0.034454957 -0.12238996, 0.41283041 0.034454927 -0.12236784, 0.41288733 0.034454957 -0.12233208, 0.41293484 0.034454957 -0.12228461, 0.41297051 0.034454912 -0.12222786, 0.41299281 0.034454942 -0.12216435, 0.4127669 0.034455121 -0.12560521, 0.41283047 0.034455076 -0.12562723, 0.41288742 0.034455031 -0.125663, 0.41293481 0.034455031 -0.12571059, 0.41297063 0.034455031 -0.12576734, 0.41299284 0.034455076 -0.12583084, 0.41299278 0.033603117 -0.12562092, 0.41299269 0.03401646 -0.12577756, 0.41297063 0.034031525 -0.12571602, 0.41297063 0.033632576 -0.12556489, 0.41297063 0.032698005 -0.12378435, 0.41297063 0.03269808 -0.12421082, 0.41293481 0.032754555 -0.12420411, 0.41293493 0.032754451 -0.12379117, 0.41293481 0.03285335 -0.12339027, 0.41288731 0.032801628 -0.12379681, 0.41297051 0.033281416 -0.12532233, 0.41293475 0.033658981 -0.12551437, 0.41293481 0.033319175 -0.12527977, 0.41288739 0.032897726 -0.12340699, 0.41288733 0.033084288 -0.12305139, 0.41283035 0.032931224 -0.12341969, 0.41293472 0.033045366 -0.12497087, 0.41288739 0.033350632 -0.12524413, 0.41288731 0.033084437 -0.12494381, 0.41283038 0.033113688 -0.12307177, 0.41288731 0.032897815 -0.12458824, 0.41283044 0.033113837 -0.1249233, 0.41283041 0.032931283 -0.12457548, 0.41276705 0.034070358 -0.12555836, 0.41283041 0.033374235 -0.12277777, 0.41276702 0.033131957 -0.12308462, 0.4127669 0.033388972 -0.12279432, 0.4128305 0.034065008 -0.12557994, 0.41283044 0.032837182 -0.12419413, 0.41276696 0.032952011 -0.12456773, 0.41276702 0.032859191 -0.12419142, 0.41276702 0.033707887 -0.12257414, 0.41299281 0.032635108 -0.12377669, 0.41299275 0.032635152 -0.12421854, 0.41276693 0.032859176 -0.1238039, 0.41276702 0.033708021 -0.125421, 0.41297051 0.032800123 -0.12337013, 0.41299278 0.03323935 -0.12536977, 0.41288733 0.0340565 -0.1256146, 0.41297045 0.032998562 -0.125003, 0.4128305 0.033697695 -0.12544058, 0.41293481 0.033045217 -0.12302457, 0.41293481 0.032853365 -0.12460501, 0.41288731 0.033350497 -0.12275101, 0.41288742 0.032801688 -0.12419833, 0.41276705 0.033389091 -0.12520085, 0.41283032 0.033697665 -0.12255459, 0.41293481 0.03404507 -0.12566073, 0.41276702 0.034070283 -0.12243684, 0.41283044 0.032837093 -0.12380119, 0.41288739 0.03368102 -0.12547229, 0.41299272 0.032740816 -0.12334751, 0.41276696 0.032951921 -0.1234277, 0.41283044 0.033374429 -0.12521751, 0.41297063 0.032998353 -0.12299232, 0.41299269 0.032946378 -0.12503906, 0.41297054 0.032800242 -0.12462531, 0.41276714 0.033132046 -0.12491076, 0.41293481 0.033319071 -0.12271543, 0.41288731 0.033680961 -0.12252294, 0.41283044 0.034064919 -0.12241526, 0.41299281 0.032946169 -0.12295623, 0.41297063 0.033281237 -0.12267311, 0.41299272 0.032740951 -0.12464769, 0.41293493 0.033658832 -0.12248082, 0.41288731 0.034056365 -0.12238048, 0.41299292 0.033239201 -0.1226254, 0.41297051 0.033632442 -0.12243052, 0.41293469 0.034044951 -0.12233432, 0.41299286 0.033602923 -0.12237446, 0.41297063 0.034031361 -0.12227915, 0.41299263 0.034016162 -0.12221758, 0.41716421 -0.0227786 -0.050518736, 0.41707376 -0.022755757 -0.050438151, 0.41696361 -0.022712305 -0.050399795, 0.41696343 -0.022712216 -0.050400123, 0.41755798 -0.022087216 -0.050369278, 0.41749856 -0.02210775 -0.050271615, 0.41741046 -0.022102609 -0.050197229, 0.41737279 -0.021944031 -0.050087079, 0.41780549 -0.021581352 -0.05005835, 0.41678333 -0.023671716 -0.050741419, 0.41676351 -0.023662046 -0.050677881, 0.41673136 -0.023646355 -0.050621137, 0.41668871 -0.023625582 -0.050573602, 0.41774377 -0.021614894 -0.049972609, 0.41663745 -0.023600563 -0.050537959, 0.41658059 -0.023572788 -0.050515786, 0.41652051 -0.023543507 -0.050508127, 0.417716 -0.021300018 -0.049609289, 0.41765738 -0.021622628 -0.049905673, 0.418042 -0.021097437 -0.049625978, 0.41797867 -0.021143124 -0.049555406, 0.41789356 -0.021162987 -0.049498692, 0.41796243 -0.020837441 -0.049057826, 0.41824815 -0.020675763 -0.049068049, 0.41818354 -0.020731419 -0.049015179, 0.41813287 -0.020517588 -0.048443511, 0.41809961 -0.020761877 -0.048971877, 0.41840252 -0.020359859 -0.04839848, 0.41833705 -0.02042295 -0.048365697, 0.41823259 -0.020330653 -0.047746763, 0.4182539 -0.020461231 -0.048338458, 0.41848576 -0.020189971 -0.047649965, 0.41841951 -0.020256817 -0.047638819, 0.41824979 -0.020298198 -0.047087118, 0.41833693 -0.020299345 -0.047629431, 0.41848609 -0.020189181 -0.046873108, 0.41820467 -0.020383075 -0.046501204, 0.41841993 -0.020256087 -0.046884045, 0.4183372 -0.020298585 -0.046893194, 0.4184038 -0.020357817 -0.046124294, 0.41810623 -0.020567819 -0.045951948, 0.41833803 -0.02042082 -0.046156928, 0.41825491 -0.020459056 -0.046183988, 0.41822925 -0.020714819 -0.045385793, 0.41816476 -0.020769522 -0.045440599, 0.41808066 -0.020798966 -0.045485362, 0.41796347 -0.020835578 -0.045461372, 0.41803694 -0.02110818 -0.044878885, 0.41797373 -0.021153554 -0.044949755, 0.41788855 -0.021173149 -0.045006737, 0.41778848 -0.021164581 -0.045044169, 0.41778824 -0.021164477 -0.045044169, 0.41759267 -0.021531731 -0.044705912, 0.4177812 -0.021540031 -0.044599965, 0.41769499 -0.021549731 -0.044665411, 0.4175927 -0.02153182 -0.044705942, 0.41751254 -0.022079751 -0.044258788, 0.41742459 -0.022075415 -0.044332907, 0.41675523 -0.023103178 -0.044038221, 0.41701606 -0.022613689 -0.04414396, 0.41731909 -0.022045448 -0.044374183, 0.41678336 -0.023672059 -0.043774918, 0.41731894 -0.022045434 -0.044374183, 0.4167634 -0.023662373 -0.043838337, 0.41725105 -0.022715479 -0.043904111, 0.4167313 -0.023646712 -0.0438952, 0.41719425 -0.022718668 -0.044013187, 0.41668865 -0.023625895 -0.043942645, 0.41710401 -0.022697538 -0.044093415, 0.41663751 -0.023600936 -0.043978438, 0.41658056 -0.023573145 -0.044000611, 0.41652057 -0.023543924 -0.044008091, 0.41300064 -0.023543879 -0.044008121, 0.41300061 -0.022766128 -0.044102505, 0.41300064 -0.022033498 -0.044380352, 0.41300052 -0.021388695 -0.04482536, 0.41300061 -0.020869195 -0.04541187, 0.41300061 -0.020504981 -0.046105579, 0.4130007 -0.020317465 -0.046866134, 0.41300064 -0.020317361 -0.047649786, 0.41300076 -0.020504922 -0.048410401, 0.41300061 -0.020868942 -0.049104318, 0.41300064 -0.021388486 -0.049690709, 0.41300061 -0.022033215 -0.050135806, 0.41300061 -0.022765785 -0.050413623, 0.41300061 -0.023543566 -0.050508127, 0.41300067 -0.030759647 -0.044008568, 0.41300073 -0.030759305 -0.050508603, 0.41300061 -0.022660702 -0.048940524, 0.41300061 -0.023088962 -0.049103007, 0.41300064 -0.022283763 -0.048680201, 0.41300064 -0.021980062 -0.048337325, 0.41300061 -0.027803615 -0.048680529, 0.41300067 -0.02810733 -0.048337713, 0.41300067 -0.027426586 -0.048940822, 0.41300061 -0.021767169 -0.047931835, 0.41300076 -0.028320223 -0.047932103, 0.41300067 -0.026998371 -0.049103126, 0.41300067 -0.028429955 -0.047487453, 0.41300076 -0.030967385 -0.0505227, 0.41300067 -0.026543707 -0.04915823, 0.41300073 -0.031374305 -0.050677136, 0.41300067 -0.031310692 -0.043886378, 0.41300067 -0.031374589 -0.043840036, 0.41300067 -0.031286016 -0.050617114, 0.4130007 -0.03116259 -0.050566182, 0.41300067 -0.031225532 -0.04392828, 0.41300064 -0.021657631 -0.047486976, 0.41300067 -0.028429955 -0.04702954, 0.41300064 -0.03100574 -0.043988541, 0.41300064 -0.023543879 -0.045358136, 0.41300055 -0.026543871 -0.045358345, 0.41300061 -0.023089111 -0.045413479, 0.41300064 -0.021657631 -0.047028974, 0.41300061 -0.021767259 -0.046584323, 0.4130007 -0.028320342 -0.046584681, 0.41300067 -0.028107509 -0.046179101, 0.41300067 -0.022660807 -0.045575723, 0.41300067 -0.021980137 -0.046178654, 0.41300064 -0.022283822 -0.045835957, 0.41300067 -0.027803719 -0.045836195, 0.41300064 -0.027426749 -0.045575932, 0.41300067 -0.023543686 -0.049158081, 0.41300064 -0.026998624 -0.045413539, 0.41299313 -0.021723896 -0.04703705, 0.41297099 -0.023120135 -0.048976406, 0.41293523 -0.023133725 -0.048921302, 0.41293529 -0.023543671 -0.048971131, 0.41299319 -0.022691891 -0.04563491, 0.4129709 -0.021888956 -0.046630487, 0.41297096 -0.021786839 -0.04704459, 0.41293529 -0.022747636 -0.048774794, 0.41299316 -0.021829635 -0.046607926, 0.41299316 -0.023105055 -0.04547818, 0.41297099 -0.023120239 -0.045539662, 0.41297099 -0.02272132 -0.045691058, 0.41299316 -0.023104936 -0.049038127, 0.41299316 -0.023543626 -0.049091473, 0.4129709 -0.023543641 -0.049028024, 0.41297093 -0.022721201 -0.048825219, 0.41299316 -0.022691742 -0.048881397, 0.41297096 -0.021786839 -0.047471359, 0.41293511 -0.021843284 -0.047051713, 0.41293511 -0.021843284 -0.047464594, 0.41297096 -0.022370204 -0.045933232, 0.41293508 -0.02274774 -0.045741394, 0.41293517 -0.022407889 -0.045976028, 0.41293517 -0.021942079 -0.047865495, 0.41288775 -0.021890476 -0.047458932, 0.41288781 -0.021986514 -0.047848657, 0.4129352 -0.022133991 -0.046285078, 0.41288766 -0.02243939 -0.046011612, 0.41288772 -0.022173107 -0.04631193, 0.41288772 -0.022173122 -0.048204049, 0.41283083 -0.022019908 -0.047836021, 0.41276729 -0.023159012 -0.045697376, 0.4127675 -0.023543835 -0.045650586, 0.41270065 -0.023543775 -0.045658097, 0.41288772 -0.021986574 -0.046667531, 0.41283083 -0.022202522 -0.046332344, 0.41270065 -0.02316092 -0.045704558, 0.41283074 -0.022202462 -0.048183903, 0.4128308 -0.022019953 -0.046680167, 0.4128308 -0.022462994 -0.048478052, 0.41276741 -0.022220716 -0.048171386, 0.41283083 -0.023153767 -0.045675799, 0.41283089 -0.023543775 -0.045628384, 0.4127675 -0.022477686 -0.048461363, 0.41283074 -0.021925896 -0.047061637, 0.41276738 -0.02204074 -0.046688065, 0.41276744 -0.02194801 -0.047064289, 0.41276735 -0.022796556 -0.048681483, 0.41270065 -0.022482678 -0.04845573, 0.41270062 -0.022800118 -0.048674718, 0.41276726 -0.02279669 -0.045834735, 0.41270074 -0.022800297 -0.045841292, 0.41276744 -0.02194801 -0.047451809, 0.41270065 -0.021955416 -0.047065243, 0.41270074 -0.02195549 -0.047450885, 0.41299313 -0.021723896 -0.047479078, 0.4129931 -0.022328168 -0.045885846, 0.41288766 -0.023145199 -0.04564105, 0.41288769 -0.02354376 -0.045592621, 0.41297096 -0.021888867 -0.047885641, 0.41297099 -0.022087246 -0.046252683, 0.41283086 -0.022786468 -0.045815066, 0.41299316 -0.023543805 -0.045424923, 0.4129352 -0.022133932 -0.048231229, 0.4129352 -0.021942183 -0.046650633, 0.41288775 -0.021890476 -0.047057375, 0.41276741 -0.022477835 -0.046054795, 0.41270074 -0.022482842 -0.046060398, 0.41288775 -0.022439316 -0.048504695, 0.41293517 -0.023133844 -0.045594886, 0.41293517 -0.023543805 -0.045545205, 0.41283086 -0.022786289 -0.048701093, 0.41283074 -0.021925896 -0.047454461, 0.41288775 -0.022769853 -0.045783445, 0.4127675 -0.023158938 -0.04881905, 0.41270062 -0.023160756 -0.048811629, 0.4128308 -0.022463113 -0.046038255, 0.41276738 -0.023543626 -0.048865721, 0.41299316 -0.021829575 -0.047908232, 0.41276738 -0.02204062 -0.047828183, 0.41270062 -0.022047698 -0.047825411, 0.41299316 -0.022035033 -0.046216562, 0.41297108 -0.022087201 -0.048263386, 0.41276741 -0.022220895 -0.046344921, 0.41270077 -0.022227079 -0.046349213, 0.41293529 -0.02240774 -0.048540339, 0.41297099 -0.023543805 -0.045488402, 0.41288772 -0.022769719 -0.048732862, 0.41283086 -0.023153692 -0.048840508, 0.41283086 -0.023543626 -0.048887834, 0.41299319 -0.022034988 -0.048299447, 0.41270074 -0.022226989 -0.048166946, 0.41297099 -0.02237007 -0.048582777, 0.41270065 -0.022047743 -0.046690688, 0.41288769 -0.023145065 -0.048875079, 0.41288772 -0.023543686 -0.048923567, 0.41299316 -0.022327989 -0.048630461, 0.41270065 -0.023543641 -0.04885821, 0.41100064 -0.023543701 -0.04885821, 0.41100064 -0.023160785 -0.048811629, 0.41100067 -0.022800148 -0.048674807, 0.41100067 -0.022482693 -0.04845573, 0.41100064 -0.022226959 -0.048166946, 0.41100058 -0.022047609 -0.047825441, 0.4110007 -0.02195546 -0.047451004, 0.41100067 -0.021955416 -0.047065243, 0.4110007 -0.022047788 -0.046690688, 0.41100058 -0.022226959 -0.046349242, 0.41100064 -0.022482783 -0.046060547, 0.41100058 -0.022800177 -0.0458415, 0.4110007 -0.023160905 -0.045704678, 0.41100064 -0.02354382 -0.045658186, 0.41270065 -0.026543662 -0.04885824, 0.4110007 -0.026543707 -0.04885824, 0.41100064 -0.026543841 -0.045658186, 0.41270074 -0.026543826 -0.045658305, 0.41100064 -0.026926666 -0.045704708, 0.41270077 -0.026926726 -0.045704708, 0.41100064 -0.027287275 -0.045841649, 0.41270077 -0.027287453 -0.045841649, 0.41100064 -0.027604833 -0.046060845, 0.41270077 -0.027604818 -0.046060845, 0.41100061 -0.027860522 -0.046349481, 0.41270077 -0.027860612 -0.046349481, 0.41100061 -0.028039828 -0.046690926, 0.41270068 -0.028039858 -0.046691105, 0.41100061 -0.028132036 -0.047065541, 0.4127008 -0.028132111 -0.047065571, 0.41100064 -0.028132051 -0.047451362, 0.4127008 -0.028132081 -0.047451213, 0.41100064 -0.028039664 -0.047825798, 0.4127008 -0.028039768 -0.047825798, 0.41100061 -0.027860463 -0.048167363, 0.41270068 -0.027860388 -0.048167214, 0.41100064 -0.027604625 -0.048456058, 0.41270074 -0.027604714 -0.048455879, 0.41100064 -0.02728717 -0.048675045, 0.41270068 -0.027287215 -0.048675045, 0.41100076 -0.026926607 -0.048811778, 0.41270068 -0.026926592 -0.048811778, 0.41276753 -0.0265439 -0.045650825, 0.41283086 -0.026543856 -0.045628592, 0.41288772 -0.026543885 -0.04559283, 0.41293523 -0.026543871 -0.045545384, 0.41297105 -0.026543871 -0.045488432, 0.41299331 -0.026543945 -0.045425102, 0.41276744 -0.026543617 -0.04886575, 0.41283068 -0.026543587 -0.048888072, 0.41288778 -0.026543647 -0.048923716, 0.4129352 -0.026543647 -0.04897134, 0.41297093 -0.026543662 -0.049028143, 0.41299319 -0.026543647 -0.049091622, 0.41299316 -0.027395532 -0.048881665, 0.41299316 -0.026982337 -0.049038276, 0.41297093 -0.026967153 -0.048976764, 0.41297102 -0.028300673 -0.047045097, 0.41293523 -0.028244242 -0.047465011, 0.41293523 -0.028244242 -0.047052011, 0.4129931 -0.026982576 -0.045478389, 0.41297099 -0.026967317 -0.04553993, 0.41297099 -0.027366132 -0.048825428, 0.41299316 -0.027395755 -0.045635149, 0.41297105 -0.027717248 -0.048583075, 0.4129352 -0.027339667 -0.048775062, 0.41297099 -0.027366355 -0.045691296, 0.41293517 -0.027679533 -0.048540547, 0.41297102 -0.028300673 -0.047471926, 0.41293523 -0.028145492 -0.046650991, 0.41288772 -0.028197035 -0.047057793, 0.41288772 -0.028101057 -0.046667919, 0.41293523 -0.027953386 -0.048231587, 0.41288772 -0.027648032 -0.048505113, 0.41288778 -0.02791439 -0.048204526, 0.41288778 -0.027914435 -0.046312377, 0.4128308 -0.028067619 -0.046680585, 0.41288778 -0.028100893 -0.047849014, 0.4128308 -0.027884856 -0.048184201, 0.41283089 -0.028067499 -0.047836408, 0.41283089 -0.02788499 -0.046332762, 0.41276744 -0.02692835 -0.04881914, 0.41283086 -0.027624518 -0.046038672, 0.4127675 -0.027866751 -0.046345189, 0.4128308 -0.026933685 -0.048840716, 0.41276753 -0.027609795 -0.046055183, 0.41283092 -0.02816163 -0.047454819, 0.41276744 -0.028046772 -0.047828481, 0.4127675 -0.028139606 -0.047452196, 0.41276753 -0.02729091 -0.045834944, 0.41276747 -0.028139576 -0.047064707, 0.41276741 -0.027290702 -0.048681721, 0.41299316 -0.028363615 -0.047037438, 0.41299322 -0.028363645 -0.047479495, 0.41299319 -0.027759284 -0.04863067, 0.41288766 -0.026942208 -0.048875347, 0.41297093 -0.028198585 -0.046630844, 0.41297093 -0.02800025 -0.048263773, 0.4128308 -0.027300984 -0.048701271, 0.41293535 -0.028145328 -0.047865912, 0.41293517 -0.02795352 -0.046285316, 0.41276741 -0.027609617 -0.048461661, 0.41288781 -0.02764824 -0.046011791, 0.41288772 -0.028197035 -0.04745923, 0.41293508 -0.026953563 -0.04892157, 0.41283086 -0.027301177 -0.045815393, 0.41283092 -0.02816163 -0.047061905, 0.41288772 -0.027317643 -0.048733041, 0.41276738 -0.026928559 -0.045697615, 0.41276753 -0.028046906 -0.046688482, 0.41283074 -0.027624339 -0.048478231, 0.41299319 -0.028257877 -0.046608493, 0.41299319 -0.028052419 -0.048299775, 0.41297099 -0.02800034 -0.04625313, 0.41297102 -0.02819851 -0.047886088, 0.41276738 -0.027866527 -0.048171565, 0.41293523 -0.027679726 -0.045976236, 0.41288778 -0.027317837 -0.045783684, 0.4128308 -0.026933789 -0.045676038, 0.41299319 -0.028052539 -0.04621692, 0.41297099 -0.027717441 -0.045933679, 0.41299316 -0.028257772 -0.047908649, 0.4129352 -0.027339846 -0.045741722, 0.41288772 -0.026942402 -0.045641407, 0.41299331 -0.027759492 -0.045886144, 0.4129352 -0.026953727 -0.045595214, 0.4129847 -0.031471252 -0.043746188, 0.41299453 -0.031434625 -0.043783352, 0.41299132 -0.031449214 -0.050748602, 0.41299832 -0.031411871 -0.050711975, 0.46433923 0.15342276 -0.07111223, 0.46547195 0.15344498 -0.072669581, 0.46468887 0.15344502 -0.073804334, 0.46435443 0.15344504 -0.073931023, 0.46433941 0.15342276 -0.073869422, 0.46432564 0.15338704 -0.071167544, 0.46538636 0.15344499 -0.073016867, 0.46463293 0.15338698 -0.071284041, 0.46532705 0.1534228 -0.072994247, 0.46540901 0.15342276 -0.07266207, 0.46435449 0.15344487 -0.071050718, 0.46465936 0.15342288 -0.073747948, 0.46465936 0.15342271 -0.071233705, 0.46468887 0.15344484 -0.071177468, 0.46540901 0.15342273 -0.072319731, 0.46535262 0.15338697 -0.072655097, 0.46535251 0.15338704 -0.072326496, 0.46527392 0.15338708 -0.072007343, 0.4653053 0.15333955 -0.072332308, 0.46494105 0.15342286 -0.073553547, 0.46463293 0.15338702 -0.073697612, 0.46490338 0.15338708 -0.073511139, 0.46512124 0.15338708 -0.073265031, 0.46487173 0.1533397 -0.073475674, 0.46508214 0.15333965 -0.073238119, 0.46522948 0.15333955 -0.07202436, 0.46508211 0.15333946 -0.071743593, 0.46519598 0.15328269 -0.072037026, 0.46430051 0.15321931 -0.073711887, 0.46505275 0.1532826 -0.071764097, 0.46522948 0.15333955 -0.072957352, 0.46505272 0.15328276 -0.073217884, 0.46484816 0.15328261 -0.071533039, 0.46503451 0.15321918 -0.071776494, 0.46483359 0.15321918 -0.071549639, 0.4651961 0.15328267 -0.072944656, 0.46430579 0.15328269 -0.073733285, 0.46526986 0.15328276 -0.072645053, 0.46517536 0.15321924 -0.072936758, 0.46524787 0.15321928 -0.07264252, 0.46458396 0.15321919 -0.071377411, 0.46458399 0.15321931 -0.07360436, 0.46524787 0.15321928 -0.072339281, 0.46547195 0.15344489 -0.072311983, 0.46498302 0.15344508 -0.073601112, 0.46431434 0.15333952 -0.073768035, 0.46532717 0.15342279 -0.071987405, 0.46516803 0.15342277 -0.073297277, 0.46459422 0.15328269 -0.07362394, 0.46527395 0.15338695 -0.072974101, 0.46512124 0.15338694 -0.071716622, 0.46483338 0.15321937 -0.073432192, 0.46487185 0.15333952 -0.071506307, 0.46530542 0.15333953 -0.072649434, 0.46432567 0.1533871 -0.073814169, 0.46459416 0.15328269 -0.071357802, 0.46461087 0.15333959 -0.07365571, 0.46526989 0.15328266 -0.072336599, 0.46430048 0.15321919 -0.071269855, 0.4651753 0.15321933 -0.072044775, 0.46538627 0.15344501 -0.071965054, 0.4648481 0.1532827 -0.073448762, 0.46522012 0.15344504 -0.073333368, 0.46516812 0.15342276 -0.071684226, 0.46503434 0.15321939 -0.073205188, 0.46490338 0.15338697 -0.071470723, 0.46461084 0.15333953 -0.071326092, 0.4643057 0.15328264 -0.071248367, 0.46522024 0.15344484 -0.071648255, 0.46494111 0.15342268 -0.071428075, 0.46431431 0.15333949 -0.071213648, 0.46498314 0.15344484 -0.0713806, 0.48433933 0.14994296 -0.14121558, 0.48465928 0.14988865 -0.14132436, 0.484633 0.14983413 -0.14135335, 0.48547205 0.14926627 -0.14261852, 0.48524794 0.14907658 -0.14249332, 0.48517546 0.14894499 -0.14275663, 0.48532718 0.14910121 -0.14289911, 0.48540911 0.14924982 -0.14260192, 0.48468891 0.14875908 -0.14363338, 0.48435459 0.14870232 -0.14374675, 0.48433939 0.14870997 -0.14368196, 0.4843258 0.14988622 -0.14124916, 0.48538652 0.14911109 -0.14292918, 0.48435453 0.14999038 -0.14117058, 0.48465943 0.1487643 -0.14357327, 0.48494104 0.14885129 -0.14339937, 0.48463294 0.14875484 -0.1435122, 0.48468876 0.14993361 -0.14128406, 0.48540911 0.14940295 -0.14229567, 0.48535255 0.14922096 -0.14257975, 0.48535255 0.14936794 -0.14228581, 0.48527399 0.14951059 -0.14200063, 0.4853054 0.14932287 -0.14226969, 0.48490337 0.14883834 -0.14334534, 0.48512128 0.14894834 -0.14312537, 0.48487195 0.14881167 -0.14329232, 0.48430058 0.14859834 -0.14344998, 0.48522958 0.14946058 -0.14199431, 0.48508218 0.14891788 -0.14307998, 0.48508227 0.14958605 -0.14174314, 0.48519614 0.14940408 -0.14198025, 0.48522958 0.14904335 -0.14282887, 0.48505273 0.14887609 -0.14303623, 0.48519617 0.14899825 -0.14279203, 0.48505268 0.14952619 -0.14173593, 0.48430583 0.14864542 -0.14349754, 0.48527005 0.14913215 -0.14252411, 0.48484814 0.1496295 -0.14152949, 0.48503444 0.1494638 -0.14171885, 0.48483351 0.14956525 -0.14151584, 0.48458388 0.14964233 -0.14136182, 0.48458388 0.14864653 -0.14335389, 0.48524797 0.14921223 -0.14222221, 0.48547202 0.14942625 -0.14229877, 0.48431447 0.14868084 -0.14355393, 0.48498306 0.14884987 -0.14345177, 0.48532721 0.14955154 -0.14199837, 0.4851681 0.14896588 -0.14317031, 0.48459437 0.14869443 -0.14339967, 0.48527387 0.1490784 -0.14286505, 0.48483351 0.1487235 -0.14319964, 0.48512122 0.14964075 -0.14174031, 0.4853054 0.14918104 -0.14255331, 0.4843258 0.14870265 -0.14361639, 0.48487183 0.14969233 -0.14153092, 0.48461077 0.14873119 -0.1434534, 0.48459426 0.14970793 -0.14137261, 0.48526996 0.1492701 -0.14224811, 0.48430046 0.14969042 -0.14126559, 0.4851754 0.14934376 -0.14195867, 0.48484823 0.14877276 -0.14324279, 0.4853864 0.14958152 -0.1419882, 0.48522022 0.14896956 -0.14321233, 0.48503456 0.14882495 -0.14299674, 0.48516819 0.14968716 -0.14172752, 0.48490337 0.14975068 -0.14152034, 0.48461089 0.14977285 -0.14136975, 0.48430583 0.14975673 -0.14127477, 0.48522028 0.14972313 -0.14170511, 0.48494104 0.14980163 -0.14149816, 0.48431441 0.14982304 -0.1412691, 0.48498318 0.14984281 -0.14146568, 0.48438427 0.15157712 -0.14531894, 0.48475683 0.15168646 -0.14524187, 0.48438963 0.15162422 -0.14536642, 0.48474661 0.15291138 -0.14264967, 0.48438418 0.15297291 -0.1425267, 0.48438945 0.15303928 -0.14253579, 0.48474661 0.15163857 -0.14519601, 0.48561731 0.15224387 -0.14412688, 0.48565286 0.15247239 -0.14379711, 0.48565286 0.15229285 -0.14415623, 0.48475698 0.15297695 -0.14266033, 0.48561737 0.15241961 -0.14377554, 0.48555678 0.15211847 -0.1445048, 0.48570001 0.15233262 -0.14418246, 0.48508027 0.15287706 -0.14286007, 0.48477352 0.15304199 -0.1426575, 0.48510394 0.15294001 -0.14286159, 0.48537022 0.15280566 -0.14313047, 0.4851355 0.1529983 -0.14285107, 0.48540926 0.15286025 -0.14312761, 0.48560122 0.15215343 -0.14454101, 0.48540929 0.15199003 -0.14486824, 0.48565432 0.1521764 -0.14457531, 0.48545602 0.15200742 -0.14491315, 0.48560122 0.15269667 -0.14345463, 0.48545611 0.15290663 -0.14311455, 0.4844383 0.15327287 -0.1424316, 0.48517317 0.1518648 -0.14519881, 0.48550829 0.15201117 -0.14495523, 0.48565444 0.15273766 -0.1434526, 0.48521528 0.15186334 -0.14525105, 0.48442313 0.15322548 -0.14247669, 0.48485148 0.15175104 -0.14547561, 0.48575649 0.1525525 -0.14382298, 0.48571375 0.1527676 -0.14344223, 0.48581937 0.15257569 -0.1438262, 0.48559535 0.15218827 -0.14409615, 0.48559532 0.15236162 -0.14374955, 0.48581937 0.15237811 -0.14422141, 0.48485151 0.15320267 -0.14257164, 0.48506558 0.15281299 -0.14284657, 0.4855234 0.15207329 -0.14446796, 0.48440957 0.15316874 -0.14251037, 0.48534077 0.15274568 -0.14312311, 0.4853701 0.1519596 -0.14482279, 0.48482201 0.15315777 -0.14261214, 0.48555675 0.15264662 -0.14344831, 0.48513547 0.15185174 -0.1451446, 0.4857001 0.15251739 -0.14381321, 0.48521516 0.15309039 -0.14279638, 0.48482201 0.15175629 -0.14541538, 0.4843981 0.15310569 -0.14253016, 0.48443833 0.15168096 -0.14561571, 0.48575652 0.15236162 -0.14420472, 0.48479557 0.15310332 -0.14264123, 0.48550251 0.15202011 -0.14443265, 0.48571357 0.15218619 -0.14460523, 0.48532248 0.15268335 -0.14310606, 0.48517311 0.15304942 -0.1428289, 0.48534074 0.15191774 -0.14477919, 0.48510394 0.1518251 -0.14509167, 0.48552349 0.15259016 -0.14343427, 0.48550817 0.15294263 -0.14309229, 0.48479554 0.1517469 -0.14535455, 0.4844231 0.15168864 -0.14555092, 0.48532251 0.1518667 -0.14473958, 0.48508027 0.1517863 -0.14504237, 0.48550263 0.15252991 -0.14341311, 0.48477355 0.15172324 -0.14529561, 0.48440951 0.15168132 -0.14548559, 0.48506549 0.15173693 -0.14499901, 0.4843981 0.15165944 -0.14542295, 0.46438417 0.15671934 -0.074051514, 0.46474656 0.1567193 -0.073914006, 0.46559528 0.15671916 -0.072296813, 0.46550259 0.15671918 -0.071920708, 0.46581939 0.15694501 -0.072269663, 0.46571359 0.15694489 -0.071840718, 0.46475682 0.15678273 -0.073933706, 0.46552333 0.1567826 -0.071912751, 0.46438959 0.15678261 -0.074072883, 0.46474656 0.15671918 -0.071067408, 0.46438417 0.15671922 -0.0709299, 0.46438953 0.1567826 -0.070908412, 0.46561739 0.15678264 -0.072687164, 0.46565273 0.1568395 -0.072289929, 0.46565273 0.1568395 -0.072691396, 0.46475682 0.15678261 -0.071047589, 0.46561739 0.15678264 -0.07229422, 0.46508017 0.15678258 -0.071270809, 0.46477345 0.15683946 -0.071015939, 0.46555671 0.15683961 -0.073081359, 0.4657 0.15688694 -0.072697029, 0.46510389 0.15683942 -0.071244076, 0.46560106 0.15688711 -0.073098108, 0.46537015 0.15683943 -0.071544573, 0.46513537 0.15688697 -0.071208492, 0.46540919 0.15688708 -0.073463634, 0.46565434 0.15692285 -0.073118314, 0.46443829 0.15694483 -0.070710644, 0.46540913 0.15688695 -0.071517572, 0.46560115 0.15688698 -0.071883276, 0.46545613 0.15692262 -0.071485147, 0.46545604 0.15692283 -0.073495969, 0.46565428 0.15692279 -0.07186304, 0.46517318 0.15692283 -0.07381545, 0.46550825 0.15694506 -0.07353206, 0.46521524 0.15694493 -0.073862806, 0.46442303 0.15692265 -0.070772275, 0.46575645 0.15692277 -0.072277322, 0.46485153 0.15694499 -0.07411395, 0.46559525 0.15671919 -0.072684482, 0.46485153 0.15694487 -0.070867434, 0.46581945 0.15694493 -0.072711542, 0.46506551 0.15671922 -0.071287379, 0.46440938 0.15688694 -0.070827678, 0.46552327 0.15678272 -0.073068514, 0.4653407 0.1567826 -0.071564987, 0.46482202 0.1569227 -0.070923552, 0.46537015 0.15683962 -0.073436812, 0.46555677 0.15683952 -0.071900025, 0.46513543 0.15688707 -0.073772773, 0.46521518 0.1569449 -0.07111837, 0.4657 0.15688694 -0.072284088, 0.46439806 0.15683939 -0.070873603, 0.46482196 0.15692279 -0.074057892, 0.46443829 0.15694502 -0.074270621, 0.46479556 0.15688695 -0.070973977, 0.46575645 0.15692274 -0.072703943, 0.46550259 0.15671931 -0.073060706, 0.46571365 0.15694502 -0.073140696, 0.46517321 0.15692277 -0.071165904, 0.46532246 0.15671913 -0.071577534, 0.46534076 0.15678264 -0.073416427, 0.46510389 0.15683959 -0.073737249, 0.46550819 0.1569449 -0.071449265, 0.46479556 0.15688713 -0.074007496, 0.46442309 0.15692279 -0.07420896, 0.46532241 0.1567193 -0.073404029, 0.46508017 0.15678272 -0.073710576, 0.46477345 0.15683962 -0.073965505, 0.46440944 0.15688702 -0.074153736, 0.46506551 0.15671934 -0.073693886, 0.46439818 0.15683961 -0.074107721, 0.46731517 0.15743855 0.072509393, 0.46725899 0.15742144 0.072509393, 0.46720704 0.15739384 0.072509304, 0.46106282 0.15742968 -0.073904827, 0.46145108 0.15742977 -0.074522838, 0.4614071 0.1574468 -0.074558035, 0.4610121 0.1574468 -0.073929206, 0.46076688 0.15744668 -0.073228434, 0.46068373 0.15744664 -0.072490588, 0.46110961 0.15740202 -0.073882326, 0.46149173 0.15740205 -0.074490502, 0.46082172 0.15742959 -0.073215857, 0.46074003 0.15742961 -0.072490588, 0.46087226 0.15740198 -0.073204324, 0.46079192 0.15740196 -0.072490588, 0.46326175 0.15744688 -0.075723127, 0.46327421 0.15742983 -0.075668409, 0.46256092 0.15744683 -0.075477913, 0.46328571 0.15740205 -0.075617686, 0.4625853 0.15742984 -0.075427249, 0.46193215 0.15744682 -0.075082883, 0.46260777 0.15740211 -0.075380549, 0.4619672 0.15742975 -0.075038984, 0.46199962 0.15740211 -0.074998453, 0.46679184 0.15700312 -0.072490677, 0.4667401 0.15697534 -0.072490677, 0.46668372 0.15695831 -0.072490588, 0.46618274 0.15700313 -0.074231699, 0.46574059 0.15700309 -0.074673757, 0.46614215 0.15697542 -0.074199304, 0.46570817 0.15697546 -0.074633256, 0.46518865 0.1569753 -0.074959829, 0.46567324 0.15695836 -0.074589208, 0.46516427 0.15695831 -0.074909195, 0.4645969 0.15695833 -0.07510753, 0.46521112 0.15700312 -0.0750065, 0.46460935 0.15697542 -0.075162396, 0.46462092 0.15700319 -0.07521306, 0.46661642 0.15695836 -0.073088005, 0.46667138 0.1569754 -0.073100403, 0.46641806 0.15695839 -0.073655292, 0.46672183 0.15700315 -0.073112205, 0.4664686 0.15697543 -0.073679671, 0.46609816 0.15695839 -0.074164346, 0.46651527 0.15700319 -0.073702231, 0.461207 0.15699492 0.072509304, 0.46125892 0.15696718 0.072509304, 0.4613153 0.15695007 0.072509304, 0.48679209 0.15252882 -0.14404975, 0.48674017 0.15250404 -0.14403735, 0.48668382 0.15248874 -0.14402963, 0.48647207 0.15310915 -0.1428891, 0.48199037 0.15328468 -0.14243753, 0.48608974 0.15335689 -0.14239354, 0.4860509 0.15331674 -0.1424119, 0.48642617 0.15307344 -0.14289804, 0.48162267 0.15304652 -0.14291389, 0.48666042 0.15279731 -0.14345057, 0.48152697 0.15310915 -0.1428891, 0.48637626 0.15304652 -0.14291392, 0.48660591 0.15277594 -0.14345513, 0.48128831 0.15282758 -0.143452, 0.48133862 0.15279736 -0.14345057, 0.48131531 0.15248866 -0.14402963, 0.4815729 0.1530735 -0.14289804, 0.48671082 0.15282767 -0.143452, 0.48194817 0.15331662 -0.14241187, 0.48247471 0.15347666 -0.14205392, 0.48190936 0.15335684 -0.14239354, 0.48244271 0.15351255 -0.14201994, 0.48120722 0.15252876 -0.14404975, 0.48304763 0.15361109 -0.14178474, 0.48241323 0.15355654 -0.14199428, 0.4830277 0.15364976 -0.1417454, 0.48367605 0.15368035 -0.1416461, 0.48300937 0.15369631 -0.14171435, 0.48366919 0.15372059 -0.14160399, 0.48432314 0.15368035 -0.1416461, 0.48366281 0.15376845 -0.1415702, 0.48432991 0.15372051 -0.14160378, 0.48495141 0.15361105 -0.14178486, 0.48433608 0.15376839 -0.1415702, 0.48497143 0.15364982 -0.1417454, 0.48552451 0.15347658 -0.14205392, 0.48498979 0.1536963 -0.14171435, 0.48555633 0.15351249 -0.14201994, 0.48600876 0.15328476 -0.14243753, 0.48558596 0.15355645 -0.14199428, 0.48139328 0.15277602 -0.14345513, 0.48125902 0.15250401 -0.14403723, 0.48068383 0.15292561 -0.14424808, 0.4807401 0.15291035 -0.14424057, 0.48079193 0.15288551 -0.14422815, 0.48088515 0.15322883 -0.14354153, 0.48083481 0.15325913 -0.14354275, 0.48721892 0.15328051 -0.14353837, 0.48111349 0.15358765 -0.14288564, 0.48078012 0.15328051 -0.14353837, 0.48693553 0.15361467 -0.14286993, 0.4810636 0.15361466 -0.14286985, 0.4873153 0.15292567 -0.14424808, 0.48683974 0.15355209 -0.14289482, 0.48640046 0.15383671 -0.1423256, 0.4815177 0.15390882 -0.14228161, 0.48643926 0.15387687 -0.14230727, 0.4868857 0.15358774 -0.14288564, 0.48716423 0.15325919 -0.14354275, 0.48725906 0.15291037 -0.14424036, 0.48115936 0.1535521 -0.14289482, 0.48711389 0.15322891 -0.14354153, 0.48720714 0.15288547 -0.14422815, 0.48155978 0.15387689 -0.14230718, 0.48211607 0.15414584 -0.14180727, 0.48159865 0.15383671 -0.1423256, 0.48214796 0.15410987 -0.14184104, 0.48282379 0.15431197 -0.14147516, 0.48217747 0.15406603 -0.14186712, 0.4828437 0.15427323 -0.1415145, 0.4835999 0.15439752 -0.14130385, 0.48286197 0.15422681 -0.14154558, 0.48360667 0.15435727 -0.14134623, 0.48439917 0.15439762 -0.14130385, 0.48361301 0.15430948 -0.14137982, 0.48439237 0.15435739 -0.14134623, 0.48517534 0.154312 -0.14147516, 0.48438606 0.15430954 -0.14137991, 0.48515531 0.15427323 -0.1415145, 0.48588315 0.15414588 -0.14180727, 0.48513702 0.15422675 -0.14154558, 0.4858512 0.15410982 -0.14184116, 0.48648158 0.15390885 -0.14228149, 0.48582169 0.15406604 -0.14186691, 0.42993876 0.0035012364 -0.036958501, 0.42993268 0.0035307258 -0.057519332, 0.42991334 0.0035912544 -0.037082806, 0.42988881 0.0036463886 -0.057338849, 0.42981306 0.0037519038 -0.037403986, 0.42981711 0.0037485659 -0.057120457, 0.42974558 0.0038134754 -0.056935087, 0.4299328 0.0035268813 0.010263309, 0.42993268 0.0035281032 -0.010261759, 0.42988881 0.0036436915 -0.010081485, 0.42988878 0.0036425442 0.010082826, 0.42981717 0.0037459433 -0.0098630935, 0.42981717 0.0037448108 0.0098644346, 0.42974564 0.0038108081 -0.0096775144, 0.42974558 0.0038097203 0.0096790642, 0.42997196 0.0031537563 -0.010769978, 0.42993045 0.0031740814 -0.010683522, 0.42990491 0.003186509 -0.010589853, 0.42996126 0.0036671609 -0.010462895, 0.42998967 0.0035465211 -0.010555044, 0.42995498 0.0034959465 -0.010458782, 0.42993197 0.0035956651 -0.010364965, 0.42986527 0.0037298948 -0.010189787, 0.42994162 0.003285408 -0.010574773, 0.42997447 0.0032929033 -0.010668918, 0.4299579 0.0033792257 -0.010536566, 0.42995974 0.003416568 -0.010515317, 0.43002465 0.0032940507 -0.010755256, 0.42999378 0.0034059584 -0.010631308, 0.42999575 0.0034508407 -0.010610327, 0.43004927 0.0034273565 -0.010717645, 0.43005267 0.003480345 -0.010696635, 0.43004811 0.0035935938 -0.010640904, 0.42997202 0.0031551719 -0.036485955, 0.42993042 0.0031755269 -0.036572471, 0.42990497 0.0031879246 -0.03666614, 0.43002477 0.0032954961 -0.036500588, 0.43004647 0.0034044981 -0.036529943, 0.42997453 0.0032943487 -0.036586925, 0.42999175 0.0033867508 -0.036616221, 0.43005252 0.0035348237 -0.036583439, 0.42993763 0.0032847673 -0.036698833, 0.42999473 0.0034970492 -0.036669537, 0.42995188 0.0033588111 -0.036728606, 0.42995492 0.0034471303 -0.036783382, 0.42997363 0.0036278218 -0.036758915, 0.42993906 0.0035516918 -0.036874905, 0.42990151 0.0036543012 -0.036996499, 0.42997208 0.0031564236 -0.058027282, 0.42993042 0.0031766593 -0.057940975, 0.42990497 0.0031890869 -0.057847157, 0.42994562 0.003447473 -0.057615593, 0.42993265 0.0035308599 -0.057519332, 0.42995659 0.0035022497 -0.057723656, 0.4299331 0.0036035031 -0.057629839, 0.42998925 0.0032965988 -0.057955787, 0.43003163 0.0032963753 -0.058022156, 0.43000999 0.0034161657 -0.057918206, 0.4300569 0.0034321398 -0.057984278, 0.43001235 0.0034638047 -0.057897463, 0.4299598 0.0033840984 -0.057801142, 0.42996156 0.0034218729 -0.057779953, 0.42994604 0.003382057 -0.057673588, 0.42994314 0.0033513606 -0.057695314, 0.42994344 0.0032887757 -0.057839409, 0.43005636 0.0036013871 -0.057907417, 0.4298887 0.0036463141 -0.057338849, 0.43000647 0.0035651028 -0.057842031, 0.4300606 0.003486082 -0.057963237, 0.41305199 -0.035425588 -0.059877649, 0.4328458 0.0051728487 -0.059834316, 0.4130424 -0.03539142 -0.05979152, 0.43277967 0.0051502436 -0.059714451, 0.41301075 -0.035348684 -0.059696749, 0.43273667 0.0051448345 -0.059659913, 0.43267491 0.0049982816 -0.01241304, 0.41301069 -0.035351396 -0.012439355, 0.43272054 0.0049986392 -0.012479737, 0.41304243 -0.035394132 -0.012534246, 0.4327707 0.0050092936 -0.012589321, 0.41305205 -0.035428256 -0.012620166, 0.41299579 -0.035336226 -0.034849212, 0.43269894 0.0049988776 -0.034810111, 0.41302469 -0.035365626 -0.034787908, 0.43275648 0.0050056726 -0.034703895, 0.41304964 -0.035412014 -0.03467916, 0.43278226 0.0050166547 -0.034627929, 0.41227499 0.026424646 -0.1103376, 0.46201783 0.07617037 -0.089718804, 0.41225079 0.02656284 -0.11050485, 0.46197295 0.076289862 -0.089899197, 0.41226801 0.026681945 -0.11068599, 0.46196359 0.076382458 -0.090099618, 0.41229504 0.026738808 -0.11079045, 0.46314761 0.077584848 -0.089335844, 0.46309808 0.077487379 -0.089232102, 0.46265957 0.076946229 -0.089492157, 0.46266079 0.077039063 -0.089625701, 0.46268305 0.077117324 -0.089766666, 0.47291097 0.087359056 -0.07559298, 0.47291788 0.0873584 -0.075517371, 0.47291818 0.087353438 -0.075485423, 0.47291604 0.087345451 -0.07545732, 0.47290286 0.08732143 -0.075430974, 0.4728907 0.087296456 -0.075404838, 0.47287974 0.087270811 -0.07537891, 0.47285771 0.087232187 -0.075370774, 0.47283068 0.087186664 -0.075371459, 0.47279695 0.087131143 -0.075381979, 0.47288796 0.087285161 -0.075383499, 0.47289148 0.087291509 -0.075386301, 0.47289553 0.08729893 -0.075389817, 0.47289905 0.087305099 -0.075393543, 0.47290245 0.087311566 -0.075398102, 0.47290552 0.087317824 -0.075403318, 0.47290811 0.087322921 -0.075408533, 0.47290817 0.087322861 -0.075408682, 0.4729104 0.0873276 -0.075414315, 0.47291264 0.087332249 -0.075421438, 0.47291312 0.087334082 -0.075424388, 0.47291473 0.087338239 -0.075433031, 0.47291526 0.087340057 -0.07543762, 0.47291568 0.087341577 -0.07544218, 0.44096425 0.14244567 0.087474361, 0.4408944 0.14244327 0.087474361, 0.44089434 0.14245318 -0.087457135, 0.44096419 0.14245555 -0.087457135, 0.44103363 0.14245304 0.087474361, 0.44103369 0.14246288 -0.087457135, 0.44089642 0.14244327 0.087536439, 0.43929961 0.14244327 0.087536439, 0.43929961 0.14245312 -0.087519422, 0.4408966 0.14245312 -0.087519363, 0.44090137 0.14244694 -0.087676153, 0.44088921 0.14242873 -0.087831125, 0.43929961 0.14242932 -0.08782728, 0.44084135 0.14235762 -0.08813031, 0.43929955 0.14235839 -0.088127717, 0.44078344 0.14224212 -0.08841379, 0.43929958 0.14224204 -0.08841379, 0.44077224 0.14216127 -0.088575557, 0.43929961 0.14200602 -0.088886008, 0.44077232 0.14200602 -0.088885888, 0.44077227 0.14200406 -0.088889942, 0.44073656 0.14182018 -0.089187309, 0.43929961 0.14176592 -0.089256987, 0.44066706 0.14159241 -0.08944352, 0.43929961 0.14145015 -0.089566335, 0.44059482 0.14132403 -0.089657322, 0.44053802 0.14102077 -0.089822993, 0.43929961 0.14107428 -0.089798674, 0.44050848 0.14069094 -0.089934751, 0.43929949 0.14065646 -0.089942798, 0.4405154 0.14034572 -0.089987382, 0.43929961 0.14021719 -0.089991584, 0.4405202 0.14021727 -0.089991733, 0.44052038 0.13166012 -0.089992121, 0.43929967 0.13166004 -0.089992121, 0.4405058 0.13144113 -0.089979991, 0.44048241 0.1311588 -0.089928225, 0.4392997 0.13121007 -0.089940861, 0.44048613 0.13088772 -0.08983694, 0.43929973 0.1307833 -0.089789733, 0.44053319 0.13051829 -0.089634284, 0.4392997 0.13040136 -0.089546487, 0.44062346 0.13017213 -0.089328721, 0.43929958 0.13008399 -0.089223489, 0.44071737 0.12990513 -0.088951424, 0.43929958 0.12984735 -0.08883737, 0.44072786 0.1298473 -0.08883737, 0.44072786 0.12969056 -0.0885012, 0.43929967 0.12964062 -0.088394031, 0.44073191 0.12964067 -0.088394031, 0.43929958 0.12953718 -0.088122472, 0.44076562 0.12953912 -0.08812879, 0.43929973 0.12947427 -0.087838694, 0.44079971 0.12947664 -0.087854341, 0.43929967 0.12945314 -0.087548897, 0.44082385 0.1294532 -0.087571993, 0.44082436 0.12945311 -0.087548897, 0.44082436 0.12944326 0.087564543, 0.43929967 0.12944324 0.087564722, 0.44104186 0.14246383 -0.087509736, 0.44096938 0.14245585 -0.087514475, 0.44106239 0.14226232 -0.088463232, 0.44092426 0.14224315 -0.088434145, 0.44106591 0.14220066 -0.088595256, 0.44092077 0.14217113 -0.088580385, 0.44106591 0.14204541 -0.088905558, 0.44092077 0.14201589 -0.088890895, 0.44092074 0.14201358 -0.088895485, 0.44106582 0.14204273 -0.088910922, 0.44113672 0.14039186 -0.090202317, 0.44111359 0.14072536 -0.090136275, 0.44092849 0.14070317 -0.09002699, 0.44094768 0.14037441 -0.090084359, 0.44072363 0.14069161 -0.089958683, 0.44073704 0.14035873 -0.090011582, 0.44110802 0.141048 -0.090007439, 0.4409318 0.14102231 -0.089911208, 0.44073936 0.14101318 -0.089848861, 0.44111791 0.14142071 -0.089762613, 0.44095901 0.14139296 -0.08968769, 0.44078907 0.14138392 -0.089635745, 0.44113111 0.14178783 -0.08937417, 0.44099841 0.14176022 -0.089328632, 0.44085965 0.14174816 -0.089294896, 0.44074181 0.14021727 -0.090016559, 0.44095263 0.14021721 -0.090089843, 0.44114164 0.14021726 -0.090208158, 0.44074193 0.13166003 -0.090016946, 0.44095251 0.13166003 -0.090090439, 0.44114169 0.13166015 -0.090208545, 0.44072786 0.13141891 -0.09000288, 0.44093859 0.1313924 -0.090074584, 0.44112754 0.13136281 -0.090191469, 0.44106406 0.12986808 -0.089014784, 0.44109851 0.13012686 -0.089461908, 0.44094834 0.13016239 -0.089400873, 0.4408935 0.12990049 -0.088975862, 0.44078919 0.13017765 -0.08935599, 0.44108427 0.13046223 -0.089798406, 0.44091353 0.13049959 -0.089713201, 0.44108307 0.13073808 -0.089981958, 0.44072852 0.1305155 -0.089655742, 0.44090194 0.13077453 -0.089882389, 0.4410961 0.13104162 -0.090115473, 0.44070271 0.13079259 -0.08981882, 0.44090855 0.13107546 -0.090004966, 0.4407002 0.13109723 -0.089936748, 0.44090387 0.12983324 -0.088844046, 0.44107434 0.12979123 -0.088863477, 0.44090378 0.12967643 -0.088507608, 0.44107431 0.12963445 -0.088527307, 0.44107062 0.12959708 -0.088441119, 0.4409039 0.12963222 -0.088411584, 0.44105318 0.1294267 -0.087579712, 0.44093925 0.12944658 -0.087575749, 0.44093981 0.12944643 -0.087548897, 0.44105372 0.12942646 -0.087548897, 0.44093981 0.1294366 0.087564722, 0.44105366 0.12941667 0.087564543, 0.47508326 0.13541605 -0.17027856, 0.47496441 0.1352613 -0.17040779, 0.47485903 0.1350722 -0.17049651, 0.47477284 0.13485903 -0.17053993, 0.47523895 0.1354083 -0.17030035, 0.47531459 0.13485353 -0.17063849, 0.47501042 0.13525885 -0.17042343, 0.47526756 0.13525066 -0.17045356, 0.47501042 0.13502884 -0.17056553, 0.47529307 0.13506261 -0.17056812, 0.4750104 0.13476872 -0.17063956, 0.47278234 0.087056309 -0.075301424, 0.47279698 0.087049171 -0.075198129, 0.47291067 0.087298289 -0.075310811, 0.47293612 0.08732906 -0.075242147, 0.47294721 0.087382331 -0.075427189, 0.47297576 0.087421 -0.075396731, 0.43276283 0.0056458414 -0.013250098, 0.43271518 0.0055481493 -0.012882933, 0.43263772 0.0053893328 -0.012542948, 0.4325321 0.0053067207 -0.012376651, 0.43257919 0.0053275824 -0.012427196, 0.43261442 0.0053557158 -0.012483194, 0.4323639 0.005244419 -0.012230739, 0.43219921 0.0051646233 -0.01209785, 0.43276283 0.0056470633 -0.034005508, 0.43271521 0.0055493414 -0.034372821, 0.43253216 0.0053079724 -0.034879133, 0.43263763 0.0053905696 -0.034712806, 0.43261433 0.0053568929 -0.034772292, 0.43257925 0.0053288788 -0.034828439, 0.43226448 0.0051997602 -0.035106286, 0.43210307 0.0051100105 -0.035230562, 0.43283957 0.0058060288 -0.060185745, 0.4327811 0.0056856722 -0.059964225, 0.43271026 0.0055407435 -0.059761927, 0.4326798 0.005492419 -0.059702054, 0.43263742 0.0054492056 -0.059646174, 0.43258294 0.0054133534 -0.0595956, 0.43422049 0.0086375177 -0.068617299, 0.43436077 0.0089250505 -0.068985239, 0.43453598 0.0092839003 -0.069264755, 0.43473539 0.0096929818 -0.069439605, 0.4670175 0.075872123 -0.069261655, 0.46681815 0.075463593 -0.069435939, 0.47002518 0.08203797 -0.062660292, 0.46996856 0.081921577 -0.063058212, 0.46987662 0.081733271 -0.063420609, 0.45268282 0.080015093 -0.062079653, 0.45273161 0.080114946 -0.062372699, 0.45280963 0.080275044 -0.062630609, 0.45291254 0.08048588 -0.06283839, 0.4530341 0.080735341 -0.062984064, 0.4531675 0.081008777 -0.063058928, 0.45330504 0.081290454 -0.063058928, 0.45343843 0.08156389 -0.062984064, 0.45356008 0.081813321 -0.06283839, 0.45366278 0.082024142 -0.06263037, 0.45374092 0.082184166 -0.062372521, 0.45378968 0.082284018 -0.062079504, 0.45403662 0.082790241 -0.059253976, 0.45424786 0.083223268 -0.059687391, 0.45194033 0.078492984 -0.062726334, 0.45190361 0.078417704 -0.062413052, 0.45188147 0.078372091 -0.062092468, 0.45379058 0.082285956 -0.058930174, 0.45352057 0.081732228 -0.058729634, 0.45379061 0.082286343 -0.064606622, 0.45352057 0.081732616 -0.064807251, 0.45403662 0.082790539 -0.064282611, 0.45424786 0.083223432 -0.063849166, 0.4521623 0.075548351 -0.062726602, 0.45204571 0.077020183 -0.062726513, 0.45614633 0.083715707 -0.066056922, 0.45519328 0.083473057 -0.064955577, 0.45446604 0.081982121 -0.065913424, 0.45541894 0.082224771 -0.067014679, 0.45541897 0.08222419 -0.056521937, 0.45446613 0.081981614 -0.057623312, 0.45519343 0.083472684 -0.05858101, 0.45614624 0.08371526 -0.057479635, 0.45581269 0.083009854 -0.056915537, 0.45430058 0.08248651 -0.058439389, 0.45485339 0.082774863 -0.058009759, 0.45200709 0.076929912 -0.062142685, 0.45226485 0.074036896 -0.06235756, 0.45581284 0.083010286 -0.06662114, 0.45446745 0.082828686 -0.064877704, 0.4548533 0.082775384 -0.065527037, 0.42776352 0.0075196922 -0.064499065, 0.427652 0.0075322539 -0.064499065, 0.42765206 0.0075250119 0.064501032, 0.42776352 0.0075124949 0.064501032, 0.42786941 0.0074754059 0.064501032, 0.42786932 0.0074825287 -0.064499065, 0.42796439 0.0074154884 0.064501032, 0.42796442 0.0074227154 -0.064499065, 0.42804357 0.0073431581 -0.064499065, 0.42804357 0.007335946 0.064501032, 0.42810309 0.0072480887 -0.064499065, 0.42810303 0.007240817 0.064501032, 0.42813987 0.0071419328 -0.064499065, 0.42813984 0.0071347803 0.064501032, 0.42815202 0.0070304424 -0.064499065, 0.42815205 0.0070232004 0.064501032, 0.42813906 0.0069188625 -0.064499065, 0.42813897 0.0069116354 0.064501032, 0.41100055 0.0075322539 -0.064499065, 0.41100043 0.0075250566 0.064501032, 0.42887148 0.009532392 -0.06649895, 0.4110004 0.0095323324 -0.06649895, 0.42868486 0.009226203 -0.066475347, 0.4110004 0.009087339 -0.066448912, 0.42849305 0.0089118332 -0.066400483, 0.41100049 0.0086645186 -0.066300973, 0.42825919 0.0085283369 -0.066228732, 0.41100046 0.0082852691 -0.066062674, 0.42804712 0.0081803054 -0.06597276, 0.41100049 0.0079685748 -0.065746024, 0.4278726 0.0078942627 -0.065646365, 0.41100049 0.0077302754 -0.0653667, 0.42774722 0.0076884329 -0.065273479, 0.41100043 0.0075824857 -0.064944163, 0.41100016 0.06162329 -0.06649597, 0.45428142 0.061623529 -0.06649597, 0.41100004 0.063037589 -0.065910056, 0.41100004 0.06273447 -0.066158965, 0.45514369 0.063037783 -0.065910205, 0.45489272 0.062626228 -0.066226676, 0.41100004 0.062388733 -0.06634374, 0.4545953 0.062138259 -0.066428617, 0.4110001 0.062013477 -0.066457465, 0.41099992 0.076865241 -0.052080974, 0.46188924 0.076865539 -0.052080974, 0.41099998 0.077113837 -0.051777825, 0.46206552 0.077154741 -0.051714644, 0.41100004 0.077298626 -0.051431999, 0.46217778 0.077338666 -0.051328138, 0.41100004 0.077412426 -0.051056847, 0.46222946 0.077423424 -0.05099903, 0.41099992 0.077450886 -0.050666675, 0.46224639 0.077451155 -0.050666675, 0.41099998 0.077445105 0.05067645, 0.46224648 0.077445433 0.05067654, 0.42906877 0.0088174641 -0.066851094, 0.42930964 0.0093187243 -0.066887692, 0.42882079 0.0083110482 -0.066679552, 0.42794719 0.0075006485 -0.06493099, 0.42805818 0.0074044466 -0.064940408, 0.42858168 0.0085866749 -0.066332296, 0.42835554 0.0081951469 -0.066076264, 0.42845425 0.0081154406 -0.066117004, 0.42867541 0.0085182041 -0.066381916, 0.42826018 0.0072476119 -0.065476373, 0.42816767 0.0069774985 -0.065025404, 0.42825204 0.0071496218 -0.06552501, 0.42905238 0.0088438541 -0.066763267, 0.42927635 0.0093349665 -0.066782072, 0.42817935 0.0070853978 -0.064999536, 0.42781737 0.0075605214 -0.064931735, 0.42881033 0.0083557516 -0.066592917, 0.42824465 0.0073468387 -0.065432623, 0.42847535 0.0086484104 -0.06631048, 0.42816633 0.0071936995 -0.064976409, 0.42902192 0.0088756531 -0.066683516, 0.42922282 0.0093610585 -0.06668742, 0.42820668 0.0074424148 -0.065395787, 0.42878348 0.0084047914 -0.066514447, 0.42812929 0.007297039 -0.064957008, 0.42813632 0.0075435787 -0.065363839, 0.42897904 0.0089113116 -0.066613302, 0.4291518 0.0093956888 -0.066608056, 0.42874154 0.0084564835 -0.06644626, 0.42802832 0.0076369941 -0.065344319, 0.42839476 0.0074411482 -0.065993264, 0.42891452 0.0089571029 -0.066545442, 0.42882538 0.0090124309 -0.066489205, 0.42906651 0.0094372928 -0.066548422, 0.42839742 0.0075238347 -0.065925673, 0.42872515 0.0090676546 -0.066458896, 0.42790222 0.0076993257 -0.065344051, 0.4283784 0.0076085925 -0.065864876, 0.42833921 0.0076919347 -0.065813377, 0.42827007 0.0077826977 -0.065767601, 0.42816633 0.0078708678 -0.065737441, 0.42858937 0.0078385919 -0.066388682, 0.42858556 0.0079027563 -0.066308483, 0.42804617 0.007935524 -0.065732583, 0.42856261 0.0079701692 -0.066236094, 0.42852187 0.0080382824 -0.066173986, 0.4289715 0.0094836056 -0.066511586, 0.42824224 0.0082600266 -0.066063836, 0.45438138 0.061574787 -0.066508517, 0.45447639 0.0615284 -0.066545561, 0.4545615 0.061486989 -0.066605046, 0.45463279 0.06145224 -0.066684201, 0.45468637 0.061426133 -0.066779122, 0.45471957 0.061409846 -0.066884741, 0.45555279 0.063114539 -0.066186532, 0.45549473 0.063069001 -0.066112593, 0.45502406 0.062030837 -0.066810325, 0.45498517 0.062024266 -0.066714123, 0.45492962 0.06202805 -0.066626981, 0.45486012 0.062042087 -0.066552117, 0.45477915 0.062065691 -0.066492423, 0.45468971 0.062098086 -0.066450551, 0.45531377 0.06262134 -0.066572621, 0.45527017 0.062595278 -0.066490844, 0.45521334 0.062579736 -0.0664161, 0.45542136 0.063037485 -0.066045359, 0.45514503 0.062574998 -0.066350445, 0.4553358 0.063021436 -0.065987572, 0.45506743 0.062581033 -0.066295609, 0.45524189 0.063021585 -0.065941796, 0.45498261 0.062598228 -0.066253737, 0.4622983 0.076942295 -0.052357182, 0.46224025 0.076896757 -0.052283421, 0.46216682 0.076865271 -0.052216068, 0.46208128 0.076849282 -0.052158251, 0.46198729 0.076849326 -0.052112564, 0.4624624 0.077500284 -0.050666675, 0.46255702 0.077559322 -0.050666675, 0.46235719 0.077463582 -0.050666586, 0.46247032 0.077292383 -0.051920786, 0.46241015 0.077234939 -0.05186747, 0.46233663 0.077191323 -0.051818386, 0.46225277 0.077162534 -0.051775619, 0.4621613 0.077150151 -0.051740512, 0.46258005 0.077515453 -0.051458701, 0.46263608 0.077637836 -0.050666675, 0.46251854 0.077450812 -0.051425561, 0.46244505 0.077399492 -0.051395044, 0.46236196 0.077362895 -0.051367983, 0.46227211 0.077342182 -0.051345333, 0.46235728 0.07745786 0.05067645, 0.46246248 0.077494577 0.05067645, 0.46255705 0.077553526 0.05067654, 0.46263608 0.07763204 0.05067654, 0.46170938 0.075959399 -0.067984775, 0.46112019 0.074615687 -0.067676857, 0.4617565 0.075920433 -0.068078503, 0.45968834 0.071680337 -0.064676926, 0.45945892 0.071209922 -0.063264683, 0.45944718 0.071101442 -0.063289449, 0.46108228 0.074674129 -0.067589149, 0.45934847 0.071516499 -0.063209966, 0.46245369 0.077265173 -0.068234071, 0.46178278 0.075889856 -0.06818302, 0.45940837 0.071422815 -0.063223943, 0.46086019 0.074856475 -0.067426518, 0.46030721 0.073722884 -0.066726759, 0.45967177 0.071782291 -0.064633831, 0.46039277 0.073657095 -0.0667568, 0.46094903 0.074797541 -0.067460731, 0.4594458 0.07131888 -0.06324251, 0.46164337 0.076004878 -0.067906573, 0.46102434 0.074735686 -0.067515835, 0.46005443 0.072346672 -0.065996125, 0.45968029 0.071579561 -0.064725235, 0.45926932 0.071595058 -0.063201174, 0.4624165 0.077273279 -0.068128809, 0.45963147 0.07188037 -0.064597681, 0.46156207 0.076054484 -0.067847595, 0.46005633 0.072434992 -0.065927342, 0.46235952 0.077292204 -0.068034366, 0.45956954 0.071969584 -0.064570531, 0.46311116 0.078613088 -0.067925319, 0.4637185 0.079858288 -0.067273721, 0.4600344 0.072525695 -0.06586571, 0.46146959 0.076105893 -0.067811117, 0.46054885 0.07336016 -0.067032084, 0.45948896 0.072045535 -0.064553693, 0.4622854 0.077320859 -0.067955449, 0.45998964 0.072614416 -0.065814003, 0.46306327 0.078599304 -0.067824945, 0.46366081 0.079824254 -0.067183957, 0.46054265 0.073431998 -0.066946253, 0.46219799 0.077357948 -0.067896083, 0.45992413 0.072696537 -0.065775111, 0.46299669 0.078598365 -0.067734912, 0.46358529 0.079805285 -0.06710358, 0.4605135 0.07350786 -0.066869363, 0.46210158 0.077401474 -0.067859367, 0.46113586 0.074563518 -0.067774728, 0.46291453 0.078610644 -0.067659959, 0.4634957 0.07980223 -0.067036256, 0.46339673 0.079815507 -0.066985801, 0.45984149 0.072768167 -0.065751269, 0.46282104 0.07863538 -0.067603424, 0.46046266 0.073584229 -0.06680508, 0.46272105 0.078671142 -0.067568377, 0.46329316 0.079844266 -0.066954449, 0.4641706 0.080919161 -0.066133484, 0.46400115 0.080885515 -0.066036209, 0.46381089 0.08091335 -0.065983728, 0.4636912 0.080154151 -0.066780433, 0.4320533 0.0048311949 -0.035325274, 0.43202549 0.0048913807 -0.035343692, 0.43199015 0.0049502701 -0.03534843, 0.43262008 0.0050690025 -0.034920916, 0.43261045 0.0051345378 -0.034927592, 0.43259183 0.0051983744 -0.034922495, 0.43236008 0.0049825162 -0.035118237, 0.43234566 0.0050404668 -0.035130486, 0.43232444 0.0050974488 -0.035132691, 0.43229702 0.0051511228 -0.035124406, 0.43256527 0.0052569956 -0.034906164, 0.43220466 0.0049083382 -0.035226122, 0.43218747 0.0049612075 -0.03524138, 0.43216434 0.0050135553 -0.035247311, 0.43213585 0.0050636232 -0.035243794, 0.43269494 0.0053556561 -0.034708634, 0.43281481 0.005086422 -0.034585848, 0.43261635 0.0052908212 -0.03484349, 0.43264842 0.0052474737 -0.034851804, 0.43266255 0.0053193718 -0.034779295, 0.43267432 0.0052005798 -0.034853473, 0.43270397 0.0052745789 -0.034778729, 0.4327437 0.0053110421 -0.034696445, 0.43269718 0.005140081 -0.034846559, 0.43273693 0.0052244216 -0.034770861, 0.43278179 0.0052590966 -0.034677044, 0.43280694 0.0052025765 -0.034651175, 0.43271044 0.0050677061 -0.034826413, 0.43276426 0.0051589608 -0.034751996, 0.43281808 0.0051439106 -0.0346203, 0.43277663 0.0050808638 -0.034718528, 0.43277213 0.0055138022 -0.03436996, 0.43282005 0.0054675341 -0.034361616, 0.43281969 0.0056111366 -0.034003988, 0.43286699 0.0055637807 -0.033999816, 0.43293962 0.0053422153 -0.033624157, 0.43292534 0.0053130835 -0.033960953, 0.4329327 0.0053787082 -0.033973113, 0.43294734 0.0054088682 -0.033624157, 0.43288329 0.0052267164 -0.03428553, 0.43292508 0.0054445267 -0.033983961, 0.43294027 0.0054757148 -0.033624157, 0.43288907 0.0052892566 -0.034309283, 0.43290278 0.00550735 -0.03399311, 0.43291846 0.0055392236 -0.033624157, 0.43287998 0.0053524077 -0.034330502, 0.43288282 0.0055962801 -0.033624157, 0.43285665 0.0054127723 -0.034348235, 0.43283564 0.0056440383 -0.033624157, 0.43283564 0.0056428462 -0.013631448, 0.43288293 0.0055951625 -0.013631448, 0.4329184 0.0055380464 -0.013631448, 0.43294021 0.0054745823 -0.013631597, 0.43294731 0.0054077506 -0.013631448, 0.43293956 0.005341053 -0.013631597, 0.43281963 0.0056100041 -0.013251677, 0.43277219 0.0055126399 -0.012885675, 0.43282005 0.0054663718 -0.01289393, 0.43286702 0.0055626631 -0.013255909, 0.43281487 0.0050851405 -0.012669906, 0.43288323 0.0052255839 -0.012970075, 0.43288901 0.0052881241 -0.012946352, 0.43281808 0.0051426739 -0.012635425, 0.43292534 0.0053119361 -0.013294682, 0.43288007 0.0053512156 -0.012925044, 0.43280694 0.0052013695 -0.01260446, 0.43293265 0.0053775162 -0.013282523, 0.43285662 0.0054115951 -0.012907371, 0.43278185 0.0052579045 -0.012578592, 0.43292499 0.0054434091 -0.013271824, 0.43274373 0.0053097904 -0.012559161, 0.43290278 0.0055061728 -0.013262734, 0.43269479 0.0053543299 -0.012547091, 0.43262011 0.0050677806 -0.012334809, 0.43266252 0.0053182691 -0.012476429, 0.43270373 0.005273506 -0.012476936, 0.4326165 0.0052895099 -0.012412205, 0.43256536 0.0052556694 -0.012349591, 0.43273678 0.0052232742 -0.012484893, 0.43264827 0.0052462965 -0.012403861, 0.43259194 0.0051969588 -0.012333229, 0.4327642 0.0051577836 -0.012503728, 0.43267432 0.005199343 -0.012402281, 0.43261042 0.0051332861 -0.012328252, 0.43277651 0.0050796419 -0.012537375, 0.43269715 0.0051389039 -0.012409195, 0.43271044 0.0050665587 -0.012429133, 0.43229702 0.005149886 -0.012131199, 0.4323245 0.005096063 -0.012123093, 0.43234572 0.0050391257 -0.012125269, 0.43236014 0.0049811602 -0.012137458, 0.43213603 0.0050623864 -0.012011871, 0.43199024 0.0049488544 -0.011907294, 0.4321644 0.0050122738 -0.012008414, 0.43202552 0.0048900843 -0.011912003, 0.43218753 0.0049598813 -0.012014344, 0.43205336 0.0048298985 -0.011930361, 0.43220469 0.0049069822 -0.012029603, 0.4701077 0.082054764 -0.062243864, 0.4701077 0.082047731 0.062254205, 0.47017449 0.082046852 -0.062244132, 0.47017449 0.082039803 0.062254205, 0.47024131 0.082054034 -0.062244132, 0.47024125 0.08204706 0.062254205, 0.47030485 0.082075834 -0.062244132, 0.47030482 0.082068935 0.062254354, 0.4703618 0.082111463 -0.062244132, 0.47036183 0.082104325 0.062254205, 0.47040954 0.082158685 -0.062243864, 0.47040954 0.082151592 0.062254205, 0.47022456 0.08191143 -0.063104346, 0.47022152 0.082013458 -0.062673911, 0.4701629 0.081893295 -0.063084945, 0.47006801 0.081698835 -0.063459113, 0.46987936 0.081442133 -0.06375356, 0.46994105 0.08143875 -0.063780174, 0.47000423 0.081697792 -0.063438132, 0.47009739 0.081888899 -0.063070431, 0.47038814 0.082114741 -0.062708929, 0.47034103 0.082068697 -0.062695697, 0.47027943 0.081942424 -0.063127354, 0.47028455 0.082034379 -0.062683687, 0.47012749 0.081712544 -0.063487127, 0.46999767 0.081446394 -0.063815549, 0.47032472 0.081984773 -0.063153222, 0.4701798 0.081738248 -0.063520655, 0.47004649 0.081464902 -0.063857749, 0.47022218 0.081774637 -0.063557938, 0.47008497 0.081493333 -0.063904867, 0.46981588 0.081456676 -0.06373702, 0.47008845 0.082015276 -0.062661782, 0.47015497 0.082006931 -0.062666342, 0.4700315 0.081898466 -0.063061342, 0.46993932 0.081709504 -0.063425049, 0.46725458 0.076206043 -0.068988279, 0.467318 0.076191545 -0.069004729, 0.46737957 0.076188117 -0.069031462, 0.46743622 0.076195851 -0.069066748, 0.4674851 0.076214269 -0.069108918, 0.46752363 0.076242626 -0.069156125, 0.46710578 0.075385988 -0.069662318, 0.46732825 0.075842187 -0.069467649, 0.46729529 0.07582517 -0.06941171, 0.46707889 0.075382024 -0.069600835, 0.46707889 0.075846016 -0.069268301, 0.46714047 0.075827509 -0.069287971, 0.46687886 0.075435966 -0.0694433, 0.46666619 0.074999958 -0.069502696, 0.46672314 0.074972108 -0.069524869, 0.46719894 0.075817659 -0.069319353, 0.46693814 0.075413004 -0.069464788, 0.46725148 0.075816914 -0.069361433, 0.46699312 0.075395763 -0.069499508, 0.46677437 0.074947163 -0.069560722, 0.46681711 0.074926421 -0.069608286, 0.46704075 0.075385273 -0.069545612, 0.46684921 0.0749107 -0.069665059, 0.46686909 0.07490097 -0.069728568, 0.43500748 0.010098577 -0.069506422, 0.43506446 0.010070771 -0.069528595, 0.43511561 0.010045886 -0.069564328, 0.43515828 0.010024995 -0.069611773, 0.43519035 0.010009333 -0.069668755, 0.43521038 0.0099995434 -0.069732174, 0.43446901 0.008850053 -0.069007352, 0.43464676 0.0092143118 -0.069290981, 0.43459439 0.0092514455 -0.06927152, 0.43441853 0.0088912547 -0.068990812, 0.43496028 0.009537518 -0.069604471, 0.43493414 0.0095656216 -0.069549277, 0.43427792 0.0086025894 -0.06862171, 0.4341805 0.0084029734 -0.068185642, 0.43472341 0.0091334581 -0.069364503, 0.4348965 0.0095967203 -0.069502905, 0.43469048 0.0091742575 -0.06932278, 0.43450972 0.0088035762 -0.069033876, 0.43497351 0.009514004 -0.069665894, 0.43432668 0.0085584074 -0.068633988, 0.43422827 0.0083564818 -0.068193153, 0.43474385 0.0090937614 -0.069414809, 0.43453851 0.0087542236 -0.069069222, 0.43436489 0.00850676 -0.068653986, 0.43426469 0.0083013326 -0.068205312, 0.43475065 0.0090573132 -0.069470868, 0.43455392 0.0087043643 -0.069111541, 0.43439037 0.0084505379 -0.068680719, 0.43428788 0.0082403868 -0.068221644, 0.4345552 0.0086565167 -0.069158539, 0.43440178 0.0083924234 -0.068712369, 0.43429649 0.0081766844 -0.068241194, 0.43439862 0.008335501 -0.068747774, 0.43429032 0.008113414 -0.068262771, 0.43479452 0.0096620172 -0.069446817, 0.43484923 0.0096294582 -0.069468334, 0.43294212 0.0058638752 -0.060425296, 0.43298998 0.0058173835 -0.060432807, 0.43302646 0.0057622343 -0.060445026, 0.43304938 0.0057013333 -0.060461298, 0.43305817 0.0056376457 -0.060480848, 0.43305188 0.0055744499 -0.060502514, 0.43289664 0.005770728 -0.060189202, 0.43283823 0.0056508631 -0.059968576, 0.43294501 0.0057251602 -0.060199395, 0.43288729 0.0056066513 -0.059981242, 0.43296 0.0053854287 -0.060097501, 0.43289751 0.005257383 -0.059918776, 0.43296281 0.0054418445 -0.060061231, 0.43289813 0.005309239 -0.059876129, 0.43301174 0.0054916441 -0.060293213, 0.43295121 0.0054994673 -0.060028866, 0.43288442 0.0053628385 -0.059837863, 0.43301654 0.0055519193 -0.060264066, 0.43292561 0.0055553764 -0.060001567, 0.4328571 0.0054152161 -0.059805974, 0.43300658 0.0056129247 -0.06023784, 0.4328177 0.0054639131 -0.059781864, 0.43298227 0.0056717545 -0.060216025, 0.43276787 0.0055064708 -0.059766963, 0.4326739 0.0054124296 -0.059636548, 0.43270585 0.0053720474 -0.059634134, 0.43264088 0.0053934306 -0.059607074, 0.43261543 0.0053654313 -0.059578583, 0.43273273 0.0053292811 -0.059638336, 0.43266743 0.005354777 -0.05960159, 0.43264312 0.0053123385 -0.05957146, 0.43269005 0.0053143501 -0.059601858, 0.43266499 0.0052560717 -0.059574589, 0.43275836 0.0052749366 -0.059652045, 0.43271193 0.005263418 -0.059609935, 0.4327769 0.0052107722 -0.059679821, 0.43272942 0.0052027851 -0.059629813, 0.43267992 0.0051991642 -0.059587583, 0.43273672 0.0051448345 -0.059659913, 0.43240836 0.005063355 -0.05940561, 0.43238059 0.0051235408 -0.059387222, 0.43234524 0.0051822513 -0.059382394, 0.43149951 0.14515944 0.090719447, 0.43149954 0.14515914 0.094258949, 0.43149963 0.14515945 0.088219389, 0.43149957 0.14516173 0.048766062, 0.43149966 0.14516188 0.0457661, 0.48438242 0.15150426 0.14530061, 0.48474315 0.15156542 0.1451783, 0.4850606 0.1516635 0.14498232, 0.48531643 0.15179254 0.14472415, 0.4854956 0.15194535 0.14441882, 0.48558798 0.15211274 0.14408375, 0.48558787 0.15228532 0.14373873, 0.48549554 0.1524529 0.14340375, 0.48531631 0.15260561 0.14309837, 0.48506057 0.15273473 0.14284007, 0.48474312 0.15283263 0.14264421, 0.48438239 0.15289387 0.14252172, 0.48537013 0.15194328 0.14484097, 0.48513541 0.15183543 0.14516281, 0.48540929 0.15197375 0.14488645, 0.48540929 0.15284409 0.14314581, 0.48560125 0.15268055 0.14347281, 0.48565429 0.15272161 0.14347078, 0.48510394 0.15180872 0.14510988, 0.48517311 0.15303338 0.14284717, 0.48545611 0.15289041 0.14313294, 0.48550829 0.1529264 0.14311062, 0.48560128 0.15213719 0.1445594, 0.48545608 0.15199119 0.14493133, 0.48521528 0.15307438 0.14281489, 0.48399946 0.15297779 0.14250319, 0.48445424 0.15164234 0.14569534, 0.48399961 0.15164068 0.14568172, 0.48399955 0.15161759 0.14574467, 0.48443824 0.15166458 0.14563392, 0.48488256 0.15171494 0.14554988, 0.48565435 0.15216015 0.14459349, 0.48485154 0.15318665 0.14259015, 0.48488244 0.15321986 0.14254068, 0.48445436 0.15329243 0.1423956, 0.48575649 0.15234546 0.14422284, 0.48571372 0.15216994 0.1446235, 0.48581949 0.15236193 0.14423965, 0.48559543 0.15234549 0.14376782, 0.48561737 0.15222763 0.14414524, 0.48561737 0.15240344 0.14379372, 0.48442307 0.15167232 0.1455691, 0.48399964 0.1516493 0.14561521, 0.48581937 0.15255959 0.14384435, 0.48588571 0.15256992 0.14384057, 0.4857761 0.15276873 0.14344274, 0.48559538 0.15217206 0.14411436, 0.48552337 0.15257402 0.14345266, 0.48565271 0.15245624 0.14381538, 0.48555672 0.15263054 0.14346673, 0.48485163 0.15173467 0.14549388, 0.48525953 0.1518313 0.14531742, 0.48506561 0.15172067 0.14501728, 0.48474666 0.15162221 0.14521416, 0.48475689 0.1516701 0.14526008, 0.48508033 0.15176983 0.14506055, 0.48440951 0.15166494 0.14550366, 0.48537013 0.1527895 0.14314888, 0.48534086 0.15190139 0.14479755, 0.48399964 0.15164264 0.14554821, 0.48513547 0.15298231 0.14286934, 0.48555675 0.15210231 0.14452316, 0.48482206 0.15173991 0.14543365, 0.48521519 0.15184705 0.14526938, 0.48556328 0.15198466 0.14501081, 0.48569992 0.15231653 0.14420094, 0.48482201 0.15314166 0.14263059, 0.4844383 0.15325662 0.14245008, 0.48399952 0.15331717 0.14234604, 0.48439822 0.15164311 0.14544116, 0.48399964 0.15162151 0.1454844, 0.48399949 0.15328059 0.14240251, 0.48575637 0.15253629 0.14384125, 0.48550263 0.15251374 0.14343117, 0.48399958 0.15153977 0.14537884, 0.48571357 0.1527514 0.14346074, 0.4855631 0.1529502 0.14307998, 0.4847956 0.15173049 0.14537261, 0.48532262 0.1518503 0.14475785, 0.48534074 0.15272954 0.1431414, 0.48510402 0.15292382 0.14287998, 0.48517314 0.15184839 0.14521684, 0.48552349 0.15205704 0.14448644, 0.48550829 0.15199485 0.14497338, 0.48577604 0.15216611 0.14464794, 0.48565289 0.15227656 0.14417447, 0.4847956 0.15308721 0.14265953, 0.48442313 0.15320946 0.14249517, 0.48399952 0.15323241 0.14244924, 0.48438963 0.15160778 0.14538462, 0.48399949 0.15158662 0.14542712, 0.48569998 0.15250126 0.14383154, 0.48532251 0.15266718 0.14312433, 0.48477355 0.15170683 0.14531384, 0.48508015 0.15286109 0.14287828, 0.4852595 0.15310338 0.14277349, 0.48550269 0.15200378 0.14445104, 0.48477361 0.15302588 0.14267589, 0.48440945 0.15315266 0.14252864, 0.48399952 0.15317489 0.1424842, 0.48588571 0.15236488 0.14425026, 0.4843843 0.15156069 0.14533712, 0.48506555 0.15279694 0.14286505, 0.4847568 0.15296091 0.14267875, 0.4843981 0.15308954 0.1425487, 0.48399958 0.15311119 0.14250527, 0.48474661 0.15289541 0.14266814, 0.4843896 0.15302315 0.14255418, 0.48399955 0.15304437 0.14251186, 0.48438424 0.15295687 0.14254512, 0.41399154 0.030554503 0.10853751, 0.41337904 0.029941887 0.10829566, 0.46021417 0.07677865 0.089380845, 0.46123853 0.07677874 0.088551983, 0.43692887 0.026943177 0.088549092, 0.41399163 0.026942 0.10711132, 0.44181925 0.026943892 0.075021848, 0.46612892 0.0767795 0.075024679, 0.46611592 0.076753229 0.071004853, 0.44181925 0.026944101 0.071002051, 0.46612886 0.076779693 0.070978478, 0.46606153 0.076779827 0.071004942, 0.46154132 0.076779664 0.071004853, 0.43625605 0.026944205 0.071002051, 0.46154138 0.078779683 0.071004942, 0.42630109 0.10942073 0.135204, 0.42510816 0.11179022 0.14028607, 0.47531375 0.12525639 0.1691681, 0.42760143 0.10976951 0.13595207, 0.49149978 0.12432994 0.16718064, 0.49149987 0.10806242 0.13228981, 0.47144088 0.096955776 0.10846852, 0.47391918 0.090483621 0.094586566, 0.4251081 0.12865646 0.14028718, 0.47531369 0.12865511 0.16916825, 0.42353654 0.12865682 0.13361485, 0.41175094 0.12865694 0.13139768, 0.42630097 0.12865682 0.13520519, 0.47587594 0.12865552 0.16372333, 0.42760113 0.12865689 0.1359532, 0.48149976 0.12865567 0.1618831, 0.4864997 0.12865551 0.16550775, 0.48699975 0.12865549 0.1655079, 0.48699975 0.12865651 0.14965819, 0.4814997 0.12865622 0.15079556, 0.44770172 0.12865838 0.10872783, 0.44004744 0.12865877 0.10225569, 0.45457655 0.1286584 0.10930155, 0.4449003 0.12865902 0.097257838, 0.43490037 0.12865892 0.097257838, 0.48699972 0.13812657 0.14965869, 0.4869996 0.13614419 0.16550826, 0.48699954 0.14727531 0.14324893, 0.48699954 0.1472362 0.14185239, 0.4869996 0.14739613 0.14144282, 0.4869996 0.14717551 0.14224567, 0.48699954 0.14718981 0.1427504, 0.4869996 0.15038516 0.1370302, 0.48699963 0.14796852 0.14079829, 0.4869996 0.14871556 0.14036904, 0.4869996 0.14764608 0.1410916, 0.48699948 0.15096703 0.13560016, 0.4869996 0.15132172 0.13409753, 0.48699963 0.13165645 0.14965819, 0.48699972 0.1316555 0.16550802, 0.48472807 0.14650792 0.14478384, 0.48399961 0.14520022 0.14292692, 0.48453805 0.14522944 0.14286856, 0.48399952 0.14647266 0.1448542, 0.48542294 0.14661212 0.14457534, 0.48504525 0.14531547 0.14269628, 0.4860518 0.14678036 0.14423893, 0.48549154 0.14545335 0.1424209, 0.48658559 0.14700483 0.14378999, 0.48585123 0.14563489 0.14205767, 0.48610339 0.14584987 0.14162828, 0.48623326 0.14608522 0.14115717, 0.48623332 0.14632787 0.14067198, 0.48610333 0.14656344 0.14020087, 0.48585138 0.14677827 0.13977121, 0.48658559 0.14898589 0.13982819, 0.48549178 0.14695986 0.13940804, 0.48605177 0.14921053 0.13937925, 0.48504516 0.14709756 0.13913281, 0.48542282 0.14937884 0.13904275, 0.48453799 0.14718363 0.13896061, 0.48472822 0.14948289 0.13883437, 0.48399967 0.14721288 0.13890217, 0.48399952 0.14951822 0.13876386, 0.48174182 0.14913513 0.13952981, 0.48119757 0.14886044 0.14007889, 0.47199953 0.15038511 0.13703029, 0.43282017 0.15144055 0.13491909, 0.42510787 0.14875558 0.1402881, 0.42776641 0.1510665 0.13566692, 0.42646626 0.15144052 0.13491888, 0.48241732 0.14934374 0.13911267, 0.46450648 0.14232598 0.15314601, 0.47531375 0.13431373 0.16916861, 0.48318475 0.14947383 0.13885249, 0.46529236 0.14214332 0.15351151, 0.46613619 0.14203061 0.15373676, 0.46699962 0.14199309 0.15381198, 0.46800527 0.14204414 0.15370984, 0.46902958 0.14220837 0.15338136, 0.46999595 0.1424918 0.15281464, 0.47082368 0.1428825 0.15203337, 0.47144821 0.14335184 0.15109451, 0.49149963 0.13530777 0.16718112, 0.49149981 0.13614415 0.16550826, 0.48119763 0.14713028 0.14353882, 0.48174188 0.1468555 0.1440884, 0.47199947 0.14449343 0.14881219, 0.48241737 0.14664701 0.14450549, 0.47183701 0.14386067 0.15007712, 0.47196046 0.1441814 0.14943595, 0.48081616 0.14745525 0.14288904, 0.48318478 0.14651687 0.14476575, 0.48061964 0.14781179 0.14217596, 0.4806197 0.14817899 0.14144208, 0.48081616 0.14853531 0.1407292, 0.46699956 0.14367004 0.15381201, 0.46613607 0.14370771 0.15373681, 0.4652923 0.14382036 0.15351151, 0.46450654 0.14400303 0.15314619, 0.42510799 0.13165654 0.14028727, 0.47531363 0.13165514 0.16916846, 0.42430648 0.13165657 0.13867261, 0.42353651 0.13165677 0.13361497, 0.41175091 0.1316568 0.13139792, 0.42630094 0.13165684 0.13520522, 0.47587585 0.13165547 0.16372342, 0.42760119 0.1316568 0.13595335, 0.4814997 0.13165565 0.16188322, 0.4864997 0.13165544 0.16550802, 0.48149958 0.13165624 0.1507958, 0.4477016 0.13165841 0.10872792, 0.44004765 0.1316587 0.10225584, 0.4449003 0.131659 0.097257987, 0.43490037 0.131659 0.097258046, 0.41166028 0.13165684 0.13139792, 0.44490024 0.1417679 0.097258523, 0.41300499 0.15144055 0.13217263, 0.4116601 0.15344062 0.13139902, 0.4130049 0.15344064 0.13217272, 0.41777918 0.15144034 0.13491909, 0.42430627 0.1495629 0.13867368, 0.45099959 0.14503664 0.097258672, 0.45099965 0.14515904 0.097258672, 0.4364197 0.13585161 0.097258165, 0.43588611 0.13557151 0.097258165, 0.43530092 0.13542728 0.097258165, 0.43469831 0.13542721 0.097258165, 0.43411312 0.13557146 0.097258165, 0.43357936 0.13585159 0.097258165, 0.43312833 0.13625121 0.097258165, 0.43641993 0.13996652 0.097258374, 0.4368709 0.13956678 0.097258374, 0.43721321 0.13907088 0.097258165, 0.42849958 0.12665904 0.097257629, 0.43278602 0.13674709 0.097258165, 0.43257222 0.1373107 0.097258165, 0.42849955 0.14515899 0.097258762, 0.43588617 0.14024653 0.097258374, 0.44899371 0.12665917 0.097257629, 0.43742701 0.13850734 0.097258374, 0.4353008 0.14039086 0.097258374, 0.43749955 0.13790902 0.097258165, 0.43742698 0.13731067 0.097258165, 0.43721327 0.13674721 0.097258165, 0.43411306 0.14024656 0.097258523, 0.43469825 0.1403908 0.097258374, 0.4449003 0.12931044 0.097257987, 0.43357947 0.13996644 0.097258374, 0.43687096 0.13625129 0.097258165, 0.43312833 0.13956682 0.097258374, 0.43278602 0.13907082 0.097258374, 0.43257234 0.13850728 0.097258374, 0.43249968 0.13790904 0.097258165, 0.43749955 0.13790911 0.095758155, 0.43742707 0.13850734 0.095758483, 0.43721327 0.13907094 0.095758155, 0.4368709 0.13956687 0.095758483, 0.43641981 0.13996664 0.095758572, 0.435886 0.14024667 0.095758483, 0.43530092 0.14039086 0.095758483, 0.43469825 0.1403908 0.095758483, 0.43411317 0.14024661 0.095758572, 0.43357944 0.13996655 0.095758483, 0.43312824 0.13956687 0.095758483, 0.43278605 0.13907084 0.095758483, 0.43257228 0.13850729 0.095758483, 0.43249956 0.13790904 0.095758483, 0.42849967 0.12665905 0.096046284, 0.42849961 0.14515898 0.096047536, 0.43479255 0.02394411 0.071001783, 0.42523369 0.0043478757 0.071000889, 0.42972746 0.0021557659 0.071000651, 0.44035581 0.023944169 0.071001783, 0.42052403 -0.016711026 0.060378149, 0.42052403 -0.01671192 0.075019434, 0.42972746 0.0021564811 0.060379401, 0.44035581 0.023943961 0.075021759, 0.43546543 0.023943186 0.088548884, 0.41660056 -0.014730737 0.088546738, 0.41399184 -0.013413042 0.091178164, 0.41399166 0.023942024 0.10592665, 0.42810974 0.0029456317 0.05857946, 0.41130564 -0.018826693 0.047768578, 0.41130552 -0.018826589 0.046745315, 0.46280661 0.081373826 0.068576828, 0.46212766 0.079982102 0.069358572, 0.46162218 0.078945294 0.071004942, 0.46139145 0.078472719 0.069792613, 0.46063146 0.076914787 0.069859222, 0.45988277 0.075379789 0.069555148, 0.45732459 0.070135936 0.061778083, 0.4538759 0.063065872 0.068004146, 0.45740607 0.070302814 0.063502684, 0.4576467 0.070795894 0.065148309, 0.45803526 0.07159251 0.066639438, 0.45855418 0.072656304 0.067907467, 0.45917967 0.073938325 0.06889452, 0.45734599 0.07017985 0.060890928, 0.45733413 0.070155561 0.061185911, 0.45732704 0.070140824 0.061481789, 0.43625608 0.026944235 0.06800212, 0.46437559 0.084590599 0.063151911, 0.46442693 0.084696025 0.061778918, 0.45948374 0.087107375 0.061779067, 0.45942277 0.086982086 0.063274756, 0.46422288 0.084277511 0.064485475, 0.45924145 0.086610764 0.064719185, 0.46397337 0.083765849 0.065740123, 0.45894662 0.086006001 0.066062346, 0.46363407 0.083070219 0.066880599, 0.45854792 0.085188687 0.067258134, 0.4633849 0.082559198 0.067510948, 0.45805937 0.084186941 0.068265542, 0.46310797 0.081991628 0.068078652, 0.45782813 0.083713248 0.068628177, 0.4575853 0.083215088 0.068948254, 0.4573321 0.082695872 0.069223389, 0.45663363 0.081264004 0.06971918, 0.45590535 0.079771161 0.069878325, 0.45517823 0.078280553 0.069693759, 0.45448315 0.076855645 0.069173113, 0.45384964 0.075556904 0.068338528, 0.45330453 0.074439287 0.067225799, 0.45287082 0.073550433 0.065881714, 0.45256719 0.072928041 0.064363614, 0.45240629 0.072598264 0.062736139, 0.45238414 0.072552875 0.06209822, 0.4523814 0.072547227 0.061778203, 0.45239249 0.072569922 0.062417522, 0.45204571 0.07701315 0.062736288, 0.45194039 0.078485802 0.062736288, 0.45190355 0.078410611 0.062422886, 0.45188138 0.078365058 0.062102512, 0.45200709 0.076922864 0.06215249, 0.45187399 0.078349859 0.061778501, 0.45216238 0.075541213 0.062736288, 0.45226479 0.074029893 0.062367037, 0.45503494 0.077987626 0.053941414, 0.45506755 0.076761827 0.054309592, 0.45430622 0.076493576 0.054577991, 0.45597282 0.076985553 0.054085895, 0.45818615 0.077289209 0.053782359, 0.45580712 0.079570651 0.053683624, 0.46086442 0.07739307 0.053678468, 0.45658538 0.081165999 0.053816542, 0.46155879 0.078816608 0.053829744, 0.46222678 0.080186173 0.054287657, 0.45733213 0.082696706 0.054334119, 0.45758525 0.083215877 0.054609492, 0.46284285 0.081448764 0.055034831, 0.45782825 0.083713964 0.05492948, 0.45805937 0.084187612 0.055292204, 0.46338281 0.08255589 0.056041911, 0.45854792 0.085189372 0.056299523, 0.46382615 0.083464637 0.057270452, 0.45894662 0.086006343 0.05749552, 0.46415555 0.084139854 0.058673069, 0.45924148 0.086611018 0.058838651, 0.46435848 0.08455576 0.060195342, 0.45942274 0.08698231 0.06028311, 0.41299999 0.063065574 0.068004146, 0.41300038 0.026944131 0.06800212, 0.41299996 0.078945115 0.052126393, 0.45296657 0.073747009 0.057323977, 0.46162161 0.078945354 0.052126482, 0.45372573 0.072758004 0.058313027, 0.45496196 0.071693644 0.059377298, 0.45605996 0.070941702 0.060128972, 0.46162158 0.078945637 0.048762307, 0.41299996 0.078945324 0.048762456, 0.45619205 0.080359638 0.058837697, 0.45587724 0.079713956 0.058781281, 0.45556542 0.079074934 0.058897659, 0.45468614 0.077272296 0.060820594, 0.45251295 0.072817266 0.059593514, 0.4524062 0.072598487 0.060820416, 0.45482221 0.077551201 0.060170427, 0.45270118 0.073203117 0.058418706, 0.45527503 0.07847932 0.059180334, 0.45502234 0.077961415 0.059613004, 0.4569194 0.08185032 0.063761845, 0.45709828 0.082216993 0.063168243, 0.45720997 0.0824458 0.062493935, 0.45724785 0.082523555 0.061778739, 0.45720991 0.082445934 0.061063454, 0.45709831 0.082217112 0.060389295, 0.45691946 0.081850588 0.059795305, 0.45198974 0.078587502 0.060820714, 0.45212582 0.078866407 0.060170576, 0.45232612 0.079276636 0.059613124, 0.45257866 0.079794541 0.059180543, 0.45286921 0.08039023 0.058897778, 0.45318091 0.081029266 0.0587814, 0.45349583 0.081674829 0.058837697, 0.45422313 0.083165824 0.059795335, 0.45440197 0.083532482 0.060389414, 0.45451364 0.08376123 0.061063603, 0.45455152 0.08383882 0.061778739, 0.45451355 0.083761156 0.062493935, 0.45440197 0.083532244 0.063168243, 0.45422304 0.083165705 0.063761964, 0.45619211 0.080359265 0.064719662, 0.45587721 0.079713643 0.064776048, 0.45556542 0.079074711 0.064659312, 0.45527503 0.078479096 0.064376578, 0.45502225 0.077961251 0.063943997, 0.45482227 0.077550918 0.063386545, 0.45468614 0.077272013 0.062736288, 0.45349583 0.081674531 0.064719662, 0.45318088 0.081028983 0.064776167, 0.45286921 0.080389917 0.064659372, 0.45257863 0.079794258 0.064376578, 0.452326 0.079276413 0.063944176, 0.45212582 0.078866169 0.063386545, 0.4519898 0.078587279 0.062736288, 0.41287068 0.15344037 0.13427337, 0.41237405 0.15344037 0.13421555, 0.41173384 0.15344043 0.13404305, 0.42804596 0.15344073 0.13217272, 0.4316974 0.15344052 0.13427337, 0.42804602 0.15144067 0.13217266, 0.45326295 0.078777164 0.11581205, 0.46512967 0.086136505 0.063814953, 0.46512973 0.086137414 0.048762783, 0.43149978 0.12665938 0.090718344, 0.43149969 0.12665924 0.094257846, 0.43149981 0.12665951 0.088218138, 0.43149975 0.12666181 0.048765078, 0.44428572 0.12665966 0.088218138, 0.44428578 0.12666194 0.048765078, 0.47149983 0.11681715 0.075730041, 0.47982791 0.11380419 0.088217393, 0.47149977 0.11681868 0.048764482, 0.47982803 0.096392959 0.088216528, 0.47149995 0.088065401 0.075728461, 0.46245161 0.079016268 0.088215545, 0.47150001 0.088065386 0.075396284, 0.43485865 0.010163382 0.069501296, 0.46660623 0.075021431 0.069504932, 0.43494758 0.010119945 0.069501027, 0.43130922 0.0052785128 0.069500789, 0.41294634 -0.035556316 0.075406507, 0.41273949 -0.035556257 0.075978711, 0.41298392 -0.035556346 0.075271264, 0.4129965 -0.035556331 0.075184658, 0.41300079 -0.035552755 0.013307557, 0.41300067 -0.035553917 0.033946857, 0.41300979 -0.035535604 0.03421779, 0.41302446 -0.035505325 0.03438513, 0.41304594 -0.035461187 0.034548715, 0.41300431 -0.035545617 0.01313816, 0.4130148 -0.035524026 0.012969479, 0.41304591 -0.035460055 0.012705699, 0.43279696 0.0050289184 0.034551188, 0.43290329 0.0052470714 0.033950016, 0.43286279 0.0051639825 0.034262046, 0.43291706 0.0052750409 0.033625856, 0.43291709 0.0052762181 0.013633326, 0.43286282 0.0051652044 0.012996987, 0.43290338 0.0052482784 0.013309106, 0.43279707 0.0050301254 0.012708023, 0.49199975 0.11244115 0.13089626, 0.48799977 0.11244187 0.1181898, 0.48799986 0.11244145 0.12648259, 0.48799983 0.11244196 0.11683516, 0.4919998 0.11244258 0.10677849, 0.48799977 0.11244187 0.11738344, 0.49169618 0.11244258 0.10525002, 0.49132764 0.11244258 0.10455932, 0.49192318 0.11244269 0.10599934, 0.47549966 0.13650404 0.16814198, 0.47532907 0.13799983 0.16962267, 0.47549972 0.1378441 0.16993408, 0.47539428 0.13791761 0.169787, 0.47530666 0.13805677 0.16950871, 0.47529969 0.1381148 0.16939272, 0.47549954 0.13552666 0.17009668, 0.47520891 0.13550891 0.1701325, 0.46780041 0.1437023 0.15374757, 0.48399952 0.15003027 0.14109375, 0.48362869 0.15001015 0.14113404, 0.4854489 0.14909117 0.14297141, 0.46862215 0.14380531 0.15354143, 0.48553839 0.14925334 0.14264713, 0.47199956 0.15238504 0.13638462, 0.48553821 0.14942041 0.14231302, 0.48544887 0.14958286 0.1419885, 0.4852753 0.14973089 0.14169227, 0.46967641 0.14405856 0.15303518, 0.48502743 0.14985599 0.14144243, 0.4847199 0.14995095 0.1412525, 0.4843705 0.15001012 0.14113404, 0.47060588 0.1444384 0.15227534, 0.47132596 0.14491697 0.15131859, 0.48297182 0.14881802 0.14351772, 0.48272392 0.14894316 0.14326762, 0.47199959 0.1461703 0.14881228, 0.47182226 0.14551051 0.15013193, 0.48327938 0.1487231 0.14370753, 0.48255026 0.14909109 0.14297141, 0.48362872 0.14866391 0.14382599, 0.48246095 0.14925338 0.14264713, 0.48399952 0.14864376 0.1438662, 0.48246089 0.14942051 0.14231302, 0.48437056 0.14866388 0.14382599, 0.48255038 0.14958289 0.1419885, 0.48471996 0.1487231 0.14370753, 0.48272386 0.14973094 0.14169227, 0.4850274 0.14881809 0.14351772, 0.4829717 0.14985597 0.14144243, 0.48527518 0.1489431 0.14326738, 0.48327926 0.14995089 0.1412525, 0.48527399 0.14906223 0.14288296, 0.48530543 0.14916499 0.1425712, 0.48522955 0.14902733 0.14284657, 0.48494098 0.14978579 0.14151622, 0.48463294 0.14981832 0.14137129, 0.48490342 0.1497348 0.14153837, 0.48512125 0.14962487 0.14175819, 0.48487186 0.1496764 0.14154889, 0.48508218 0.14890173 0.14309777, 0.4851962 0.14898208 0.14281, 0.48508221 0.14957027 0.14176105, 0.48429874 0.14961156 0.14126019, 0.48399958 0.14969091 0.14125098, 0.48399952 0.14962782 0.14122783, 0.48505273 0.14885992 0.14305402, 0.48484823 0.14875664 0.1432607, 0.48503444 0.14880884 0.14301465, 0.48399958 0.14866683 0.14380299, 0.48522961 0.14944457 0.14201225, 0.48505279 0.14951023 0.14175366, 0.48483351 0.14870733 0.14321731, 0.48519626 0.1493881 0.14199798, 0.48430052 0.14967459 0.14128353, 0.4845804 0.1495638 0.14135577, 0.484584 0.14863034 0.14337157, 0.48458055 0.14857359 0.14333557, 0.48429883 0.14852582 0.14343132, 0.48527005 0.14925404 0.14226614, 0.48517546 0.14932784 0.14197685, 0.48524797 0.14919613 0.14224003, 0.48547199 0.14925027 0.14263643, 0.48547202 0.14941023 0.14231656, 0.48540911 0.1493869 0.14231341, 0.48430583 0.14974079 0.1412928, 0.48399955 0.14975753 0.14125942, 0.48540899 0.1492338 0.14261974, 0.48524788 0.14906052 0.14251111, 0.48524049 0.14900118 0.1424806, 0.4851684 0.14887033 0.14274235, 0.48458394 0.14962652 0.14137961, 0.48482844 0.14948723 0.14150886, 0.48498324 0.14982691 0.14148365, 0.48468891 0.14991778 0.141302, 0.48532727 0.14908513 0.14291705, 0.48535255 0.14920494 0.14259766, 0.48465928 0.14987281 0.14134224, 0.48431438 0.14980718 0.14128722, 0.48512131 0.14893208 0.14314325, 0.48516807 0.14967121 0.14174534, 0.48399952 0.14982434 0.14125301, 0.48487189 0.14879549 0.14331006, 0.48459426 0.14969195 0.14139058, 0.48527405 0.14949462 0.1420183, 0.4853054 0.14930691 0.14228751, 0.48483351 0.14954942 0.14153387, 0.48502836 0.14938626 0.14171077, 0.48459432 0.1486782 0.14341752, 0.48399952 0.14999373 0.1411501, 0.48430052 0.14858231 0.14346765, 0.4839997 0.14850953 0.14346386, 0.48399952 0.14856589 0.14350019, 0.48432568 0.14987043 0.14126711, 0.48399958 0.14988799 0.1412317, 0.48527011 0.14911601 0.14254187, 0.4853864 0.14909495 0.14294697, 0.48517537 0.14892887 0.14277445, 0.48502836 0.14875107 0.14298095, 0.484611 0.14975695 0.14138772, 0.48522019 0.14970724 0.14172296, 0.48516819 0.14894959 0.14318798, 0.48484817 0.14961359 0.14154731, 0.48532721 0.14953563 0.14201643, 0.48490337 0.1488221 0.14336313, 0.4850345 0.14944789 0.14173661, 0.48516837 0.14926703 0.14194946, 0.48461089 0.14871491 0.14347123, 0.48535267 0.14935188 0.14230363, 0.48433927 0.14992709 0.1412337, 0.48399958 0.14994553 0.14119686, 0.48430589 0.14862928 0.14351536, 0.4839997 0.14861271 0.1435485, 0.48522022 0.14895335 0.14323021, 0.4849411 0.14883514 0.14341711, 0.4848285 0.1486502 0.1431825, 0.48538652 0.14956555 0.14200626, 0.48463297 0.14873867 0.14353012, 0.48431441 0.14866465 0.14357184, 0.48399958 0.14864755 0.14360608, 0.48524052 0.14913599 0.14221109, 0.48435447 0.1499745 0.14118852, 0.48498318 0.14883366 0.14346959, 0.4846594 0.14874817 0.14359115, 0.48432574 0.1486865 0.1436343, 0.48399961 0.14866874 0.14366971, 0.48468891 0.14874287 0.14365126, 0.4843393 0.14869384 0.14369954, 0.48399958 0.14867535 0.14373647, 0.48435453 0.14868608 0.14376472, 0.49169508 0.15244266 0.10580681, 0.49192265 0.15244257 0.10655712, 0.49132547 0.15244254 0.10511537, 0.49082789 0.15244271 0.1045091, 0.49199948 0.15244251 0.10733758, 0.48799953 0.15244189 0.1183845, 0.48799953 0.15244183 0.11979245, 0.49199948 0.15244116 0.13159283, 0.48799953 0.15244144 0.12742175, 0.48799953 0.15244183 0.11898948, 0.48799983 0.11272603 0.12838216, 0.48799983 0.11254963 0.12767197, 0.48799977 0.11297715 0.12903054, 0.48799977 0.12589923 0.14705335, 0.48799971 0.13888893 0.1468942, 0.4879995 0.15187313 0.12995984, 0.48799959 0.1358498 0.16087092, 0.48799968 0.13522996 0.1611018, 0.48799959 0.13634452 0.16053627, 0.48799965 0.12723266 0.15960644, 0.48799959 0.13671407 0.1601492, 0.48799953 0.13687667 0.15991805, 0.48799968 0.134582 0.16117667, 0.48799953 0.13701406 0.1596738, 0.48799977 0.12848333 0.16089891, 0.48799977 0.12801687 0.16060482, 0.48799971 0.12899867 0.1610892, 0.48799965 0.1275842 0.16017462, 0.48799977 0.12934689 0.16115497, 0.48799959 0.12969683 0.16117646, 0.48799971 0.13771227 0.14837883, 0.48799956 0.13826661 0.14785086, 0.48799959 0.13715549 0.14870046, 0.48799965 0.13676442 0.14882098, 0.48799968 0.13637914 0.14886026, 0.48799947 0.15237693 0.12831591, 0.48799959 0.15218325 0.12918051, 0.48799971 0.12818874 0.14885975, 0.48799965 0.12808742 0.14885698, 0.48799974 0.12766713 0.14878638, 0.48799965 0.12725236 0.14861666, 0.48799959 0.12685625 0.14834879, 0.48799977 0.12649186 0.14798985, 0.48799974 0.12617023 0.14755256, 0.48797432 0.12809934 0.14863394, 0.48797438 0.12818877 0.14863606, 0.48789957 0.12818877 0.14842378, 0.48789975 0.1281108 0.14842202, 0.48777929 0.12818876 0.14823352, 0.48777977 0.12812106 0.14823221, 0.47549972 0.13789161 0.17045425, 0.47549957 0.13806783 0.17044888, 0.4754996 0.13801011 0.17044605, 0.47549972 0.13795461 0.170431, 0.47549957 0.13790379 0.1704035, 0.47549966 0.13786051 0.17036547, 0.47549966 0.13782676 0.17031918, 0.47549966 0.1352292 0.17045401, 0.47549966 0.13534603 0.17035107, 0.4754996 0.1354464 0.17023052, 0.47549966 0.13780293 0.17026712, 0.47549972 0.13778944 0.17021148, 0.4754996 0.13778554 0.17015369, 0.47549972 0.13779016 0.17009626, 0.4754996 0.13780771 0.17002214, 0.47549963 0.1378241 0.16997765, 0.47565767 0.13789149 0.17052792, 0.4756299 0.13511471 0.17051731, 0.47576928 0.13498971 0.17056106, 0.47582594 0.13789161 0.17057301, 0.47599962 0.13789155 0.17058821, 0.47599977 0.13477752 0.17058812, 0.41250071 -0.035163149 0.077169463, 0.41260925 -0.035511643 0.076398954, 0.41252786 -0.035377622 0.0768051, 0.41250074 -0.02644667 0.08893244, 0.41251156 -0.026272446 0.089137182, 0.4630672 0.077367902 0.089142904, 0.47275797 0.087059617 0.075413421, 0.41250077 -0.032474548 0.055827901, 0.41250077 -0.032473579 0.038684681, 0.41235611 -0.032770112 0.037636682, 0.41679019 -0.023680329 0.04370679, 0.41244587 -0.032586098 0.038023159, 0.41221499 -0.033059284 0.037270352, 0.41726369 -0.02270937 0.043841973, 0.41827127 -0.020644411 0.049095944, 0.42989627 0.0031867921 0.057750985, 0.4180631 -0.021071196 0.049663559, 0.41297045 -0.031511575 0.05080612, 0.41297036 -0.031511113 0.043706194, 0.41196766 -0.033566386 0.036763027, 0.42989621 0.0031880289 0.036765262, 0.41782421 -0.021561027 0.050104305, 0.41765699 -0.021903262 0.044183627, 0.41757417 -0.022073478 0.050422058, 0.41842708 -0.02032496 0.048415229, 0.41732821 -0.022577956 0.050631151, 0.41851094 -0.020152956 0.047655001, 0.4185113 -0.020152077 0.046865836, 0.41842815 -0.020322502 0.046105281, 0.41825202 -0.020683348 0.045354143, 0.41798511 -0.021230802 0.044687286, 0.41221502 -0.033060342 0.057241961, 0.41232654 -0.03283149 0.056968048, 0.41704425 -0.023159981 0.050768271, 0.41679019 -0.023680836 0.050806537, 0.41196766 -0.033567637 0.057748869, 0.4124141 -0.03265211 0.056651607, 0.41247919 -0.032518536 0.056245044, 0.41248724 -0.032501355 0.038352266, 0.41250059 -0.025574163 0.089601979, 0.41250038 0.025676116 0.10983689, 0.46209574 0.07601954 0.089577064, 0.41248271 0.025885388 0.10993357, 0.41242966 0.026082784 0.11005445, 0.4123424 0.026264399 0.11019681, 0.41250274 -0.02564761 0.089571193, 0.41250038 0.026941657 0.1116973, 0.41250032 0.026941299 0.11953346, 0.41253856 0.026979432 0.11992235, 0.41250995 0.026950881 0.11972897, 0.46199006 0.076433197 0.090320215, 0.41242591 0.02686727 0.11115654, 0.41233435 0.026775822 0.11089967, 0.41248176 0.02692312 0.111425, 0.47426066 0.088703886 0.094988331, 0.46291977 0.077363208 0.089772061, 0.46321484 0.077658072 0.089452013, 0.46250531 0.076948553 0.090065911, 0.49270698 0.10714966 0.10677837, 0.49270695 0.10714824 0.13302873, 0.47549734 0.089940399 0.096121386, 0.49245986 0.10690267 0.1053942, 0.49264529 0.10708804 0.10607909, 0.49227071 0.10671352 0.10496186, 0.49203479 0.10647751 0.10455893, 0.47371539 0.088159427 0.077088878, 0.47508362 0.089526847 0.095409349, 0.47486827 0.08931157 0.095168784, 0.47465876 0.08910197 0.095018819, 0.4744902 0.088933378 0.094962195, 0.4743726 0.088815853 0.094959572, 0.47332576 0.087769866 0.076413438, 0.4728817 0.087325722 0.075756505, 0.47312781 0.087571785 0.07596691, 0.47296712 0.087411284 0.075506791, 0.41250035 0.0358897 0.13303788, 0.41250038 0.027298808 0.12067483, 0.41251692 0.036054969 0.13324486, 0.41254416 0.036171839 0.13336273, 0.41258413 0.036297679 0.13347013, 0.41683605 0.037694618 0.12764405, 0.41300032 0.033858642 0.12919353, 0.41752723 0.038344502 0.12730522, 0.41300032 0.029411346 0.12279339, 0.41835192 0.039014637 0.12675007, 0.41251004 0.027192295 0.1205038, 0.41253895 0.027103499 0.12032263, 0.41904262 0.039483204 0.12615122, 0.4184368 0.034848005 0.1205972, 0.41943678 0.035946324 0.12033443, 0.42122427 0.039625823 0.12233542, 0.47174525 0.095460534 0.10957085, 0.42109171 0.039889395 0.12295888, 0.42085129 0.040037572 0.12361516, 0.42051861 0.040068299 0.12427269, 0.42011586 0.039990053 0.12490238, 0.41966829 0.039819106 0.12548159, 0.42057416 0.037546337 0.12054099, 0.4742783 0.088845119 0.095381454, 0.42094311 0.038253307 0.12087841, 0.42115352 0.038812444 0.12129523, 0.42124328 0.039259613 0.12177335, 0.41996798 0.036628559 0.12033729, 0.41683862 0.037676752 0.12760599, 0.41300026 0.033838272 0.12915669, 0.41300026 0.033825815 0.12911601, 0.41683683 0.037662536 0.12756623, 0.41300029 0.033821657 0.12907346, 0.41683075 0.037652269 0.12752591, 0.41256091 0.10669285 0.13390057, 0.41263747 0.10678636 0.1339006, 0.41227058 0.10715784 0.1339006, 0.41274732 0.10687359 0.1339006, 0.41252092 0.10661073 0.13390057, 0.41203949 0.10716677 0.1339006, 0.412505 0.10654923 0.1339006, 0.41294229 0.1069749 0.1339006, 0.41249982 0.10648684 0.13390057, 0.4113476 0.10734929 0.1339006, 0.4112407 0.10741761 0.1339006, 0.41151699 0.1072731 0.1339006, 0.41181764 0.10719465 0.1339006, 0.41327879 0.10707735 0.1339006, 0.41100886 0.10776128 0.13390057, 0.41103688 0.10766795 0.1339006, 0.41108486 0.10757846 0.1339006, 0.41115275 0.10749455 0.1339006, 0.41250032 0.037531927 0.13389666, 0.41412324 0.10715784 0.1339006, 0.47353324 0.12358968 0.16914321, 0.49199983 0.10694902 0.13345142, 0.49199978 0.12253278 0.16687568, 0.47123635 0.096399531 0.11082469, 0.47178042 0.096262693 0.1105314, 0.47212833 0.096118167 0.11022149, 0.47242442 0.095883861 0.10971914, 0.47246993 0.095800996 0.10954143, 0.47479019 0.089741141 0.096543863, 0.47086176 0.095493197 0.11032008, 0.41252163 0.037346184 0.13388796, 0.4125056 0.037438944 0.13389449, 0.41256952 0.037198633 0.13386865, 0.47303465 0.12449607 0.16958727, 0.4747104 0.13461432 0.17055203, 0.47471032 0.12622669 0.17055152, 0.47346953 0.12464602 0.16983758, 0.47466093 0.12585993 0.17052303, 0.47470775 0.12614146 0.17054985, 0.47386691 0.12485574 0.17006616, 0.4745523 0.12558098 0.17046048, 0.47414997 0.12506984 0.17022894, 0.47438082 0.1253144 0.17036186, 0.474868 0.13461432 0.17062519, 0.47486797 0.12622666 0.17062478, 0.47503582 0.13461441 0.17067002, 0.47503594 0.12622669 0.17066954, 0.47520897 0.13461436 0.17068495, 0.47520909 0.12622663 0.17068468, 0.4751395 0.12570962 0.17064427, 0.4750196 0.12531415 0.17055605, 0.47521693 0.12546512 0.17059083, 0.4752892 0.1257823 0.1706488, 0.47511229 0.12611203 0.17067803, 0.47501448 0.12574476 0.17063861, 0.47490314 0.12612633 0.17063598, 0.47489637 0.12537602 0.17055948, 0.47485164 0.12579471 0.1706052, 0.47473663 0.12546462 0.17053543, 0.47466117 0.12585987 0.17052318, 0.47309539 0.12426528 0.1695893, 0.47318086 0.1240478 0.16954209, 0.47532588 0.12609895 0.17067517, 0.47407863 0.12408803 0.16983707, 0.47420284 0.12397338 0.16972564, 0.47340634 0.12370005 0.1693124, 0.47395959 0.12422703 0.16991706, 0.4732866 0.12385564 0.16944797, 0.4738138 0.1244445 0.1699724, 0.47458884 0.12457688 0.17022993, 0.47471419 0.12447961 0.17016684, 0.47446871 0.12468699 0.17026819, 0.47431621 0.12485094 0.17027943, 0.47483537 0.12493186 0.17041756, 0.47502759 0.12497693 0.17043342, 0.47471383 0.12501927 0.17043574, 0.47415024 0.12506922 0.17022918, 0.47455743 0.12514627 0.1704265, 0.47438115 0.12531407 0.17036201, 0.43230549 0.0048958808 0.035141543, 0.43207213 0.004768908 0.03529577, 0.43246067 0.0049562603 0.035028502, 0.43262038 0.0050010979 0.034904703, 0.43012372 0.0034580082 0.036472037, 0.43009028 0.0032859892 0.036426768, 0.43002787 0.00312379 0.036411569, 0.41295633 -0.035311043 0.034902409, 0.41261318 -0.034968168 0.035361156, 0.41276291 -0.035156056 0.035144135, 0.41195813 -0.033919945 0.036409542, 0.41274405 -0.035138175 0.059342548, 0.41261312 -0.034969553 0.05915086, 0.41284373 -0.035230696 0.059472546, 0.41295639 -0.035312414 0.059609607, 0.41195813 -0.033921152 0.058102444, 0.43002787 0.0031226426 0.05810459, 0.43012378 0.0034568757 0.05804421, 0.43009034 0.0032848716 0.058089539, 0.43268743 0.0051369965 0.059611812, 0.43242696 0.0049982965 0.059438601, 0.43207213 0.0047701746 0.011963353, 0.43236682 0.0049231052 0.01216121, 0.43262038 0.0050022602 0.012354478, 0.43221545 0.0048537403 0.012055591, 0.43012372 0.0034596175 0.010786757, 0.43009028 0.0032875538 0.010831937, 0.43002793 0.0031252652 0.010847107, 0.41295639 -0.035309762 0.012352094, 0.41261318 -0.034966931 0.011893526, 0.41284385 -0.035228088 0.012215331, 0.41274405 -0.035135433 0.012084916, 0.41195813 -0.033918411 0.01084508, 0.41300026 0.034071594 0.12873869, 0.41300032 0.033557892 0.12568475, 0.41300032 0.033986151 0.12584721, 0.41300026 0.033891916 0.12888725, 0.41300029 0.033946112 0.12882741, 0.41300026 0.034011662 0.1287751, 0.41300026 0.036895812 0.12215795, 0.41300032 0.037993699 0.12086599, 0.41300026 0.037324131 0.12232028, 0.41300032 0.038667306 0.12130214, 0.41300029 0.033180937 0.12542461, 0.41300029 0.033828989 0.129014, 0.41300029 0.033852294 0.12895082, 0.41300023 0.038456753 0.12686403, 0.41300029 0.037700832 0.12542488, 0.4130002 0.039055467 0.12632968, 0.41300026 0.032877326 0.12508179, 0.41300026 0.036441118 0.12210275, 0.4130002 0.037238508 0.1205949, 0.41300023 0.038004681 0.12508224, 0.4130002 0.039516807 0.12567283, 0.41300026 0.036441281 0.12050278, 0.41300026 0.037752047 0.12724791, 0.41300029 0.037323833 0.12568508, 0.41300026 0.035994485 0.12053125, 0.41300014 0.038217649 0.12467633, 0.41300026 0.039816454 0.12492846, 0.41300026 0.035555139 0.12061657, 0.41300029 0.034441128 0.12210251, 0.41300029 0.035130143 0.12075754, 0.41300029 0.033986405 0.12215765, 0.41300029 0.033558145 0.12232016, 0.41300029 0.032664552 0.124676, 0.41300032 0.029910922 0.12286581, 0.41300026 0.03255491 0.12423156, 0.41300026 0.036895618 0.12584744, 0.41300026 0.03255491 0.12377335, 0.41300038 0.032664508 0.12332858, 0.41300038 0.032877341 0.12292312, 0.41300026 0.03318119 0.12258042, 0.41300029 0.038327232 0.12423195, 0.41300026 0.039938569 0.12413512, 0.41300026 0.034133554 0.12870954, 0.41300026 0.036440909 0.12590276, 0.41300032 0.02977103 0.12290455, 0.41300029 0.029639527 0.12290896, 0.41300029 0.038327232 0.1237738, 0.4130002 0.039876729 0.12333514, 0.41300029 0.029543266 0.12288846, 0.41300023 0.038217649 0.12332915, 0.4130002 0.039634407 0.12256981, 0.41300032 0.029479027 0.12285759, 0.41300023 0.038004771 0.12292336, 0.41300026 0.039224029 0.12188031, 0.41300032 0.03444086 0.12590231, 0.41300026 0.037701011 0.12258054, 0.41300026 0.029440537 0.1228274, 0.41948095 0.036441326 0.12050273, 0.41887698 0.035773426 0.12056686, 0.41821942 0.035130128 0.12075754, 0.41661867 0.037751973 0.12724786, 0.41771036 0.038663581 0.12670653, 0.41886377 0.039420843 0.12583865, 0.41972515 0.039813191 0.12494026, 0.42034099 0.039940298 0.12407793, 0.42071632 0.039880618 0.12335528, 0.42093351 0.039700136 0.12272669, 0.4210237 0.039444804 0.12220611, 0.42102143 0.039153025 0.1217903, 0.42094722 0.038817257 0.12143295, 0.42081144 0.038452566 0.1211385, 0.42062646 0.038073063 0.12090649, 0.42032444 0.037565038 0.12068813, 0.41991195 0.036978528 0.12054418, 0.43588609 0.13557157 0.095758155, 0.43530098 0.13542731 0.095758095, 0.43469843 0.13542721 0.095758155, 0.43411312 0.13557146 0.095758155, 0.43049964 0.12665908 0.095757648, 0.43357947 0.1358515 0.095758155, 0.43312839 0.13625118 0.095758155, 0.4327859 0.13674727 0.095758155, 0.43257228 0.13731076 0.095758155, 0.43599963 0.12665908 0.095757529, 0.43049964 0.14515898 0.095758751, 0.4359996 0.14515899 0.095758751, 0.43742707 0.13731071 0.095758155, 0.4372133 0.13674732 0.095758155, 0.43687096 0.13625129 0.095758155, 0.43641976 0.13585161 0.095758155, 0.46975383 0.081474155 0.06374158, 0.46719235 0.076223046 0.0689926, 0.43373686 0.0086196065 0.068185315, 0.43383816 0.0087589771 0.068538919, 0.43398562 0.0089618266 0.068865046, 0.43417391 0.0092210174 0.069139436, 0.43439218 0.0095214695 0.069342151, 0.43462572 0.0098425001 0.069462523, 0.43103316 0.004898563 0.069446579, 0.4307546 0.0045150816 0.069271669, 0.43052509 0.0041992515 0.069008693, 0.43035337 0.0039628744 0.068698749, 0.43022588 0.0037875921 0.068340406, 0.43014756 0.0036796033 0.067960843, 0.43012318 0.0036463141 0.06772767, 0.43205091 0.0062997341 0.060424581, 0.43193081 0.006134361 0.06002064, 0.43175715 0.0058955401 0.0596679, 0.43154326 0.0056011677 0.05939348, 0.43035078 0.0039599091 0.058194801, 0.43412358 0.0084309876 0.068185106, 0.43288526 0.0058926791 0.060424581, 0.4313266 0.0053043067 0.035340711, 0.4319061 0.0061020106 0.033626005, 0.43035087 0.0039611459 0.036321595, 0.43187025 0.006052494 0.034113005, 0.43177411 0.0059201717 0.034540132, 0.43163925 0.005734548 0.034886315, 0.43149233 0.0055324584 0.035139874, 0.43190616 0.0061031282 0.013633326, 0.4318887 0.0060790032 0.013291821, 0.43183449 0.006004408 0.012950167, 0.43172672 0.0058560967 0.012578502, 0.43155739 0.0056231171 0.012220457, 0.4313266 0.0053055286 0.011918262, 0.43035081 0.003962636 0.010937229, 0.43277892 0.0056762695 0.033625945, 0.43277895 0.005677402 0.013633326, 0.43194908 0.0050006658 0.035340711, 0.43194917 0.0050018579 0.011918262, 0.43230411 0.0052300394 0.05939348, 0.45468408 0.073846623 0.060318366, 0.45491272 0.074315339 0.058943465, 0.45527887 0.075066239 0.057733223, 0.45576155 0.076055542 0.05675815, 0.45633236 0.077225938 0.056074932, 0.45695832 0.078509226 0.055723116, 0.45760301 0.07983093 0.055723116, 0.45822906 0.081114188 0.056075111, 0.45879987 0.082284555 0.056758389, 0.45928249 0.083273664 0.0577337, 0.45964873 0.084024385 0.058944121, 0.4598774 0.084492937 0.060318962, 0.45770738 0.080044359 0.060916558, 0.45760444 0.079833567 0.060708627, 0.45770741 0.08004418 0.062640741, 0.45672736 0.078035265 0.062089577, 0.45677596 0.078135088 0.062382594, 0.4568541 0.078295156 0.062640443, 0.45760441 0.079833373 0.062848523, 0.45778534 0.080204159 0.062382713, 0.4574829 0.079584032 0.060562983, 0.45748284 0.079583913 0.062994018, 0.45783421 0.080304071 0.062089577, 0.45734933 0.07931067 0.060488001, 0.45671079 0.078001276 0.061778501, 0.45734933 0.079310551 0.06306912, 0.45672736 0.078035325 0.061467364, 0.45785066 0.080338106 0.06177865, 0.45721206 0.079028919 0.06048812, 0.45721206 0.079028755 0.06306912, 0.45677605 0.078135163 0.061174408, 0.45707861 0.078755438 0.060562864, 0.45783409 0.08030425 0.061467543, 0.45707861 0.078755319 0.062993899, 0.4568541 0.078295246 0.060916498, 0.45695698 0.078506067 0.060708717, 0.45778534 0.080204353 0.061174706, 0.45695701 0.078505874 0.062848285, 0.45380631 0.082310885 0.061778918, 0.45378968 0.08227694 0.062089935, 0.45374084 0.082177192 0.062382832, 0.45366281 0.082017109 0.06264089, 0.45356002 0.081806272 0.062848672, 0.45343831 0.081556886 0.062994137, 0.45330504 0.081283301 0.06306912, 0.45316765 0.08100161 0.06306912, 0.45303419 0.080728129 0.062994018, 0.45291248 0.080478787 0.062848523, 0.45280972 0.080267921 0.062640741, 0.45273158 0.080107972 0.062382713, 0.45268282 0.080008149 0.062089846, 0.45266631 0.079974174 0.06177865, 0.48699966 0.12647381 0.14965804, 0.48699966 0.12575664 0.16550766, 0.48699984 0.11120754 0.13430254, 0.48699984 0.11120851 0.11691643, 0.45099965 0.14515904 0.097013876, 0.46196154 0.078779787 0.071004942, 0.46154121 0.078779489 0.075706676, 0.46710446 0.078779504 0.075024918, 0.46710446 0.078779936 0.068978563, 0.46221408 0.078778759 0.088215545, 0.45721415 0.078778729 0.087676033, 0.45721415 0.078778729 0.088215545, 0.46221417 0.078778729 0.088551983, 0.47149989 0.087790564 0.075025275, 0.46962357 0.08394441 0.063814655, 0.47149995 0.087792054 0.048762903, 0.46962354 0.083945379 0.048762605, 0.42052403 -0.016708404 0.013121024, 0.42052403 -0.016709596 0.034135625, 0.46221414 0.078778237 0.099315271, 0.46221417 0.078778729 0.090715632, 0.49149981 0.10806392 0.10571824, 0.48149541 0.098060146 0.090716705, 0.48773688 0.11094286 0.10007633, 0.49149993 0.11094256 0.10571848, 0.48149529 0.11320101 0.090717658, 0.49149975 0.11094096 0.13373108, 0.48773685 0.11094084 0.13373108, 0.49149969 0.12575668 0.16550775, 0.44428572 0.12665956 0.090718344, 0.41891721 -0.015899286 0.058578447, 0.41891721 -0.015897974 0.035935596, 0.41266319 0.02694203 0.10711132, 0.41266319 0.023942009 0.10592665, 0.41245577 -0.012637228 0.091484353, 0.4117088 -0.014500365 0.090748772, 0.42874956 0.14515904 0.095614269, 0.42866501 0.14515898 0.095675901, 0.42859498 0.1451589 0.095753476, 0.42854276 0.14515902 0.095844045, 0.42851052 0.14515898 0.095943525, 0.42999092 0.14515916 0.094918594, 0.42994037 0.14515914 0.094932124, 0.42989311 0.1451591 0.094954088, 0.43010801 0.14515913 0.094921276, 0.43004301 0.14515917 0.094914064, 0.43016985 0.1451591 0.094942197, 0.43030909 0.14515917 0.095075563, 0.43027285 0.14515914 0.095021173, 0.43022564 0.14515911 0.094976231, 0.43621659 0.14515916 0.094808385, 0.43631133 0.14515914 0.094867781, 0.43639049 0.14515917 0.094947085, 0.43033281 0.14515916 0.095136449, 0.43645012 0.14515916 0.095041856, 0.43648705 0.14515916 0.095147476, 0.43649963 0.14515916 0.095258757, 0.43648711 0.14515921 0.09536998, 0.43645015 0.14515904 0.095475838, 0.43639049 0.14515902 0.09557052, 0.43631133 0.14515902 0.095649675, 0.43621659 0.14515904 0.095709279, 0.43611088 0.14515892 0.095746294, 0.43199953 0.14515916 0.094758883, 0.43151206 0.14515914 0.094370052, 0.43154904 0.14515917 0.094475672, 0.43160862 0.14515914 0.094570592, 0.43168789 0.14515914 0.094649628, 0.43178257 0.14515916 0.094709143, 0.43188819 0.14515916 0.094745979, 0.43599954 0.14515923 0.094758704, 0.43611076 0.14515917 0.09477134, 0.42994055 0.12665926 0.094931081, 0.42989311 0.12665921 0.094953224, 0.42999104 0.12665926 0.094917461, 0.43004313 0.12665921 0.094912961, 0.43199959 0.12665921 0.09475778, 0.42874965 0.12665911 0.095613405, 0.42851058 0.12665895 0.095942363, 0.42854294 0.12665911 0.095843002, 0.42859522 0.12665905 0.095752433, 0.42866513 0.12665905 0.095674917, 0.4359996 0.12665926 0.094757512, 0.436111 0.12665918 0.094770178, 0.43010801 0.12665927 0.094920114, 0.43033293 0.12665926 0.095135406, 0.436111 0.1266591 0.095745131, 0.43621668 0.1266591 0.095708296, 0.43631145 0.12665898 0.095648572, 0.43639061 0.12665908 0.095569447, 0.43645021 0.1266591 0.095474645, 0.43648717 0.12665918 0.095368817, 0.43030921 0.12665924 0.095074579, 0.43022576 0.12665924 0.094975069, 0.43017003 0.1266592 0.094941065, 0.43649969 0.12665918 0.095257714, 0.43648717 0.12665918 0.095146522, 0.43645015 0.12665917 0.095040932, 0.43639061 0.12665918 0.094945952, 0.43631145 0.12665918 0.094866857, 0.43027297 0.12665924 0.09502019, 0.43621662 0.12665918 0.094807342, 0.43188837 0.12665926 0.094745144, 0.43178269 0.12665923 0.09470816, 0.43168801 0.12665917 0.094648436, 0.43160877 0.12665924 0.094569489, 0.43154916 0.12665924 0.094474629, 0.43151221 0.12665927 0.094369009, 0.45238414 0.072553024 0.061458334, 0.45239237 0.072570071 0.061138883, 0.47199956 0.15332174 0.13345195, 0.47199959 0.15132174 0.13409774, 0.47199953 0.15296693 0.1349545, 0.47199953 0.15096685 0.1356004, 0.41228899 0.08194533 0.048762456, 0.43592545 0.12429632 0.048764929, 0.46282798 0.092823297 0.048763052, 0.46649992 0.091032162 0.048763052, 0.46649984 0.11331013 0.048764214, 0.4129999 0.081945419 0.048762456, 0.41266319 0.026942208 0.10175435, 0.41266319 0.023942262 0.10175405, 0.41300032 0.023943961 0.071001783, 0.43125597 0.02394399 0.073001906, 0.43614814 0.023943841 0.076001868, 0.43125603 0.023943782 0.076001868, 0.43270043 0.023943365 0.085538641, 0.43125609 0.026943967 0.073002085, 0.43125606 0.026943848 0.076002106, 0.43614814 0.026943862 0.076002106, 0.43270037 0.026943341 0.085538849, 0.4130002 0.026943982 0.071002051, 0.42630091 0.14584748 0.13520603, 0.42760104 0.14584741 0.1359541, 0.4264662 0.14599118 0.13491865, 0.42776641 0.14599121 0.13566686, 0.4615413 0.07677944 0.075706437, 0.41220856 0.076776251 0.12700619, 0.45721415 0.07677871 0.087676033, 0.45721415 0.076778173 0.09804602, 0.44972453 0.076777488 0.11184882, 0.41220853 0.078776315 0.12700631, 0.45721415 0.078778625 0.090715632, 0.45721409 0.078778267 0.09804602, 0.44972464 0.078777388 0.11184882, 0.47649524 0.11038467 0.09071742, 0.47649533 0.11038475 0.088217393, 0.47649541 0.098060101 0.090716705, 0.47649541 0.09806022 0.088216648, 0.46260536 0.14944455 0.069852605, 0.46341866 0.14944437 0.071402147, 0.46201012 0.14944446 0.07026349, 0.46502832 0.14944436 0.073219016, 0.46516833 0.14944431 0.072952226, 0.46524039 0.14944436 0.072659507, 0.46524039 0.14944442 0.072358355, 0.4632816 0.14944454 0.069596037, 0.46370041 0.14944437 0.071295336, 0.46399957 0.14944437 0.071258888, 0.46429864 0.14944436 0.071295336, 0.462971 0.14944428 0.073219165, 0.46153054 0.14944424 0.074213132, 0.46119455 0.14944424 0.07357271, 0.46201023 0.14944415 0.07475464, 0.46458042 0.14944431 0.071402147, 0.46317071 0.14944425 0.073444679, 0.46341866 0.14944425 0.073615864, 0.46260533 0.14944421 0.075165495, 0.4651683 0.14944437 0.072065786, 0.46502832 0.14944443 0.071798965, 0.46482843 0.14944439 0.071573243, 0.46283075 0.14944436 0.072952017, 0.46370041 0.14944425 0.073722675, 0.46328157 0.14944413 0.075421765, 0.46275875 0.14944428 0.072659507, 0.46102142 0.14944434 0.072870448, 0.46399948 0.14944427 0.073758915, 0.46275875 0.14944428 0.072358444, 0.46102142 0.14944434 0.072147354, 0.46429864 0.14944436 0.073722467, 0.46283075 0.14944427 0.072065786, 0.46119449 0.14944436 0.071445093, 0.46458042 0.14944431 0.073615655, 0.462971 0.14944428 0.071798965, 0.46153066 0.14944436 0.070804819, 0.4648284 0.14944433 0.073444679, 0.46317059 0.14944437 0.071573243, 0.46370032 0.1531444 0.071295574, 0.46341857 0.15314433 0.071402386, 0.46317062 0.1531444 0.071573481, 0.46297076 0.1531444 0.071799144, 0.46283075 0.15314431 0.072066024, 0.46275866 0.15314426 0.072358593, 0.46275863 0.15314433 0.072659805, 0.46283072 0.15314433 0.072952464, 0.46297076 0.15314431 0.073219255, 0.46317059 0.15314433 0.073444709, 0.46341857 0.15314433 0.073616013, 0.46370038 0.15314427 0.073722884, 0.48654896 0.15274844 0.14348342, 0.48632455 0.15301317 0.14295398, 0.4827396 0.15310335 0.1427734, 0.48250797 0.15343384 0.14211248, 0.48203412 0.15324613 0.14248814, 0.48243591 0.15295002 0.1430801, 0.48167455 0.15301313 0.14295398, 0.48662537 0.15246738 0.14404549, 0.48311657 0.15321973 0.14254068, 0.48306841 0.1535656 0.14184938, 0.48222303 0.15276882 0.14344274, 0.48145008 0.15274836 0.1434833, 0.48354492 0.15329246 0.1423956, 0.48368296 0.15363315 0.14171411, 0.48137382 0.13972403 0.16952856, 0.4831166 0.15171497 0.14555012, 0.48273963 0.15183136 0.14531742, 0.48354498 0.15164235 0.14569546, 0.4813737 0.15246737 0.14404549, 0.48662543 0.14004637 0.16888402, 0.48211348 0.15256979 0.14384057, 0.48431593 0.15363327 0.1417142, 0.48211348 0.15236486 0.14425041, 0.48493078 0.15356551 0.14184965, 0.482223 0.15216611 0.14464794, 0.48549113 0.15343387 0.14211263, 0.48243597 0.15198463 0.14501093, 0.48596495 0.15324613 0.14248826, 0.48516831 0.14600842 0.14131083, 0.48502827 0.14588904 0.1415496, 0.48295397 0.1470976 0.1391326, 0.48317066 0.14662519 0.14007767, 0.48250756 0.14695984 0.13940804, 0.48341867 0.14670166 0.13992463, 0.48524043 0.1461391 0.14104943, 0.48317075 0.14578821 0.14175127, 0.48295406 0.14531542 0.14269651, 0.48250756 0.14545329 0.1424209, 0.48297086 0.14588904 0.1415496, 0.48214784 0.14563486 0.14205767, 0.48341867 0.14571159 0.14190449, 0.48346105 0.14522949 0.1428685, 0.48346117 0.1471837 0.13896061, 0.48370031 0.14674944 0.13982917, 0.48283085 0.14600836 0.14131083, 0.48189583 0.14584975 0.14162819, 0.48370042 0.14566381 0.142, 0.48524049 0.14627399 0.14077987, 0.48275867 0.14613916 0.14104928, 0.48176602 0.14608535 0.14115717, 0.48429874 0.14674936 0.13982899, 0.48399952 0.14676577 0.13979675, 0.48399958 0.14564756 0.1420324, 0.48458055 0.14670165 0.13992454, 0.48275861 0.14627397 0.14077987, 0.48176602 0.14632794 0.14067213, 0.48189574 0.14656349 0.14020096, 0.48516843 0.14640485 0.14051805, 0.48482856 0.14662507 0.14007773, 0.48429883 0.14566381 0.142, 0.48502842 0.14652415 0.14027952, 0.48283088 0.14640482 0.14051805, 0.48214778 0.1467783 0.13977121, 0.48458046 0.14571157 0.14190434, 0.4829708 0.14652427 0.14027952, 0.48482856 0.14578824 0.14175127, 0.48370042 0.14961156 0.14126019, 0.48341879 0.1495637 0.14135586, 0.48317057 0.14948717 0.14150883, 0.48297086 0.14938627 0.14171077, 0.4828307 0.14926705 0.14194946, 0.48275864 0.14913598 0.14221098, 0.48275867 0.14900126 0.1424806, 0.48283085 0.14887036 0.14274241, 0.4829708 0.14875111 0.14298104, 0.48317066 0.14865026 0.1431825, 0.48341873 0.14857355 0.14333557, 0.48370042 0.14852586 0.14343132, 0.46123272 0.15703216 0.073140845, 0.46144268 0.15703216 0.073740587, 0.46178082 0.15703209 0.074278817, 0.46223018 0.15703204 0.074728206, 0.46276817 0.15703204 0.075066254, 0.46336812 0.15703203 0.075276151, 0.47632214 0.11613573 0.086812243, 0.47625688 0.11615939 0.086867794, 0.47629246 0.11614659 0.086843714, 0.47634444 0.11612768 0.086774334, 0.47635826 0.11612269 0.086732015, 0.47617552 0.11618879 0.086887613, 0.47621733 0.11617365 0.086882576, 0.47613373 0.11620392 0.086882815, 0.47609398 0.11621822 0.086868182, 0.47226974 0.11760174 0.080486342, 0.47210154 0.11766262 0.080277696, 0.47190019 0.11773548 0.080105111, 0.47167277 0.1178177 0.079974458, 0.44438884 0.1276866 0.070795283, 0.4442243 0.12774615 0.070656434, 0.44429913 0.12771904 0.070735678, 0.44416785 0.12776659 0.070561484, 0.44413283 0.12777929 0.070455417, 0.44412091 0.12778357 0.070343718, 0.4447757 0.12754689 0.067769751, 0.44466451 0.12758711 0.067735776, 0.44412097 0.1277837 0.068229452, 0.44417709 0.12776344 0.067992792, 0.44413522 0.12777855 0.06810759, 0.44454876 0.12762895 0.067731634, 0.44433209 0.12770745 0.067812428, 0.44424412 0.12773924 0.067892298, 0.44443569 0.12766996 0.067757592, 0.41192666 -0.033845752 0.010772541, 0.41191658 -0.033761397 0.010688052, 0.4119288 -0.033669606 0.01059626, 0.41194507 -0.033617139 0.010543808, 0.4119266 -0.033848494 0.058029726, 0.41191652 -0.033764094 0.057945326, 0.41192886 -0.033672348 0.057853714, 0.41194513 -0.03361991 0.057801172, 0.41192353 -0.033695042 0.036634549, 0.41192028 -0.033817053 0.03651233, 0.41193447 -0.033871561 0.036457941, 0.44460359 0.12761268 0.0060426146, 0.44449699 0.12765123 0.0060526878, 0.44439521 0.12768804 0.0060880929, 0.44430354 0.12772115 0.0061468631, 0.44422689 0.12774897 0.0062264651, 0.44416907 0.12776978 0.0063222498, 0.44413301 0.12778291 0.0064294487, 0.44412091 0.12778725 0.0065425783, 0.44455525 0.12763001 0.0093470961, 0.44433564 0.12770946 0.0092682987, 0.44444081 0.12767147 0.0093220919, 0.44424629 0.12774171 0.0091882497, 0.44417807 0.12776642 0.0090872496, 0.44412097 0.12778707 0.008848533, 0.44413552 0.12778179 0.0089715868, 0.46924886 0.11869834 0.011302575, 0.46903232 0.11877663 0.011339411, 0.46914265 0.11873665 0.011334762, 0.46934512 0.11866346 0.011244997, 0.46942601 0.11863418 0.011165246, 0.46952549 0.11859833 0.010957465, 0.46948728 0.1186121 0.011067733, 0.4695383 0.11859354 0.010840878, 0.4695383 0.11859384 0.0072329193, 0.46908054 0.11875948 0.0067330748, 0.46952695 0.11859807 0.0071234554, 0.46928012 0.11868733 0.0067865998, 0.46918318 0.11872235 0.0067481846, 0.46943918 0.11862977 0.0069256276, 0.46949324 0.11861011 0.0070192665, 0.46936688 0.11865593 0.0068468899, 0.46900913 0.11878444 0.02033402, 0.46912292 0.11874332 0.020334437, 0.46923324 0.1187034 0.020305946, 0.46933421 0.11866695 0.020250335, 0.46941951 0.11863612 0.020170346, 0.46948436 0.11861266 0.020071045, 0.46952459 0.11859812 0.019957915, 0.4695383 0.11859313 0.019837901, 0.4441745 0.12776734 0.016774997, 0.44423851 0.12774412 0.01687409, 0.44432271 0.12771364 0.0169539, 0.44442254 0.12767754 0.017010078, 0.44413447 0.12778182 0.016662672, 0.44412091 0.12778665 0.016543463, 0.44453207 0.12763786 0.017039493, 0.44423333 0.12774615 0.013920739, 0.44417202 0.12776832 0.014018521, 0.44413391 0.12778209 0.014128581, 0.44431427 0.12771688 0.013841107, 0.44412091 0.12778673 0.014245108, 0.44451669 0.12764362 0.013751522, 0.44441053 0.12768212 0.013783529, 0.4446269 0.12760383 0.013746694, 0.46953845 0.11859319 0.016237572, 0.46910414 0.11875042 0.015739039, 0.46921846 0.11870907 0.015763775, 0.46952388 0.11859854 0.016114429, 0.46932372 0.11867101 0.015817896, 0.46941313 0.11863868 0.015897736, 0.46948123 0.11861402 0.015998676, 0.4446502 0.12759486 0.02145429, 0.44453654 0.12763609 0.021453515, 0.44442591 0.12767601 0.021482006, 0.44432512 0.1277125 0.021537915, 0.44423983 0.12774341 0.021617785, 0.44417509 0.12776679 0.021717086, 0.44413465 0.12778144 0.021830156, 0.44412091 0.12778637 0.021950111, 0.46941277 0.11863804 0.029172614, 0.46921787 0.11870858 0.029306516, 0.46932325 0.11867037 0.029252544, 0.46948108 0.11861332 0.029071674, 0.46952388 0.11859782 0.028956011, 0.46910319 0.11874999 0.029331103, 0.46953842 0.11859241 0.028832659, 0.46898648 0.11879218 0.029324785, 0.46953842 0.11859271 0.025244609, 0.46952489 0.11859764 0.025125369, 0.46948496 0.11861213 0.025012985, 0.46923676 0.11870195 0.024777934, 0.46912733 0.11874159 0.024748698, 0.46933669 0.11866581 0.024834082, 0.46942094 0.11863533 0.024913922, 0.44450936 0.12764567 0.024728462, 0.4444049 0.12768354 0.024695083, 0.44423088 0.12774637 0.024557486, 0.44431028 0.12771764 0.024637207, 0.44412091 0.12778613 0.024236009, 0.44417098 0.12776801 0.024460331, 0.44413349 0.12778163 0.024351165, 0.46896425 0.1187997 0.038312271, 0.46906886 0.11876185 0.038324818, 0.46917334 0.11872405 0.038312122, 0.46927252 0.11868826 0.038274929, 0.46936157 0.11865601 0.038215235, 0.46943602 0.11862911 0.03813614, 0.46949187 0.11860885 0.038041636, 0.46952668 0.11859635 0.037935778, 0.4695383 0.11859204 0.037824675, 0.46953836 0.11859231 0.034254238, 0.46948847 0.11861034 0.034029797, 0.46942845 0.11863211 0.03393288, 0.46952572 0.1185969 0.034138873, 0.46934906 0.11866078 0.033853278, 0.46925446 0.11869504 0.033795163, 0.46915004 0.11873277 0.033761784, 0.44448721 0.12765332 0.032413825, 0.44438758 0.12768929 0.032376781, 0.44422373 0.12774855 0.032237992, 0.44429842 0.12772156 0.032317325, 0.44413278 0.12778148 0.03203769, 0.44416749 0.12776886 0.03214328, 0.44412085 0.1277858 0.031926021, 0.44467303 0.12758617 0.029165491, 0.44412085 0.12778588 0.029657587, 0.44455609 0.12762851 0.029159203, 0.44413552 0.12778062 0.029534385, 0.44444141 0.12766996 0.029183641, 0.44433606 0.12770805 0.029237762, 0.44417819 0.12776515 0.029418603, 0.44424644 0.12774047 0.029317513, 0.46894285 0.11880693 0.047296569, 0.46904942 0.11876839 0.047314152, 0.46915707 0.11872949 0.04730536, 0.46926001 0.11869231 0.047271147, 0.46935293 0.11865868 0.047212377, 0.46943071 0.11863054 0.047132984, 0.46948949 0.11860925 0.047036543, 0.46952602 0.11859609 0.04692851, 0.46953842 0.1185915 0.046814695, 0.46953842 0.11859177 0.043266192, 0.46949169 0.11860868 0.043049023, 0.46943566 0.11862895 0.042954102, 0.46952656 0.11859605 0.043154731, 0.46936098 0.11865596 0.042874858, 0.46927175 0.11868826 0.042815462, 0.46917215 0.11872433 0.042778477, 0.44446567 0.12766074 0.040095761, 0.44437125 0.12769485 0.040055916, 0.44421694 0.12775077 0.039916679, 0.44428691 0.12772532 0.039995238, 0.44416443 0.12776969 0.039824083, 0.44413191 0.12778145 0.039721414, 0.44412091 0.1277854 0.039613888, 0.44469509 0.12757781 0.036879852, 0.44412097 0.12778543 0.037367538, 0.44459048 0.12761562 0.036867514, 0.44448599 0.12765333 0.036880419, 0.44416735 0.12776868 0.037150696, 0.44413283 0.12778112 0.037256524, 0.44438675 0.12768927 0.036917284, 0.4442977 0.12772156 0.036976889, 0.44422331 0.12774846 0.037056044, 0.4447166 0.12756959 0.044597909, 0.44460994 0.12760828 0.044580325, 0.44450226 0.12764707 0.044588968, 0.44439927 0.12768432 0.04462339, 0.44430646 0.12771788 0.044682011, 0.44422856 0.12774612 0.044761553, 0.44416985 0.12776729 0.044857785, 0.44413337 0.1277805 0.044965908, 0.44412094 0.12778501 0.045079842, 0.46942559 0.11863191 0.056127205, 0.46924773 0.11869618 0.056264326, 0.46934429 0.1186613 0.056206986, 0.4694871 0.11860973 0.056029364, 0.46952531 0.11859587 0.055918977, 0.46953842 0.11859103 0.055802181, 0.46903065 0.11877474 0.056300506, 0.4691411 0.11873472 0.056296065, 0.46892211 0.11881402 0.05627723, 0.46953842 0.11859132 0.05228065, 0.46928814 0.11868188 0.051838502, 0.46919355 0.11871609 0.051798448, 0.46937248 0.11865135 0.05189918, 0.4694424 0.11862604 0.051977739, 0.46949485 0.11860701 0.052070454, 0.46952739 0.11859532 0.052172884, 0.44444504 0.12766771 0.047775045, 0.44435558 0.12770002 0.047732279, 0.44421038 0.12775253 0.047593132, 0.44427612 0.12772882 0.047670707, 0.44413117 0.12778126 0.04740335, 0.44416144 0.12777027 0.047502622, 0.44412082 0.12778501 0.04729943, 0.46890241 0.11882067 0.065255657, 0.46901241 0.1187809 0.065284148, 0.46912566 0.11873993 0.06528385, 0.46923554 0.11870012 0.065254822, 0.46933565 0.11866391 0.065198794, 0.4694204 0.11863327 0.065118924, 0.46948466 0.1186101 0.065019622, 0.46952477 0.11859557 0.064907297, 0.46953836 0.11859062 0.064787701, 0.46953836 0.1185908 0.061296776, 0.46944883 0.11862323 0.061003342, 0.46938321 0.11864701 0.060925618, 0.46949783 0.11860549 0.061093703, 0.46952811 0.11859451 0.061193123, 0.46930388 0.11867566 0.060864344, 0.46921423 0.1187081 0.060821697, 0.44442537 0.1276743 0.055450872, 0.44423965 0.12774155 0.055315062, 0.4443247 0.12771085 0.055394962, 0.44417492 0.127765 0.055215821, 0.44413468 0.12777948 0.0551029, 0.44412085 0.12778458 0.054982945, 0.44473717 0.12756182 0.052319005, 0.44462869 0.12760103 0.052296028, 0.44412082 0.12778471 0.052794412, 0.44451818 0.12764101 0.052300289, 0.44441167 0.12767954 0.052332237, 0.44417223 0.12776607 0.052567169, 0.44413406 0.12777998 0.052677587, 0.44431511 0.12771443 0.052389726, 0.44423386 0.12774386 0.052469358, 0.44412097 0.127784 0.062664494, 0.44413367 0.12777933 0.062780157, 0.44417134 0.1277658 0.062889621, 0.44423166 0.1277439 0.062986627, 0.4443115 0.12771511 0.063066378, 0.4444066 0.12768063 0.063124195, 0.46941534 0.11863467 0.074108317, 0.46922359 0.11870393 0.074243024, 0.46932724 0.11866654 0.074188098, 0.46911052 0.11874475 0.074269131, 0.46952406 0.11859533 0.073893026, 0.46953836 0.11859009 0.073771015, 0.46948221 0.11861049 0.074007824, 0.46899483 0.11878657 0.074264988, 0.4688836 0.118827 0.074231014, 0.46953836 0.11859021 0.070315585, 0.46933463 0.11866409 0.069903538, 0.46923396 0.11870047 0.069847569, 0.46941969 0.11863323 0.069983557, 0.46948436 0.11860977 0.070082858, 0.46952468 0.11859518 0.07019569, 0.44475684 0.12755427 0.060043022, 0.44412097 0.12778415 0.060510889, 0.44464692 0.12759399 0.060014531, 0.4445338 0.12763493 0.06001462, 0.44413462 0.12777923 0.060391322, 0.44442376 0.12767465 0.060043827, 0.44432363 0.12771091 0.060099766, 0.44423899 0.12774155 0.060179785, 0.44417462 0.12776479 0.060278788, 0.48384917 0.11341229 0.10057677, 0.44437203 0.12769242 0.078463808, 0.44412097 0.12778325 0.078021333, 0.44428745 0.12772307 0.078403071, 0.44421735 0.12774834 0.07832481, 0.4441646 0.12776738 0.078231886, 0.44413206 0.12777926 0.078129128, 0.44416735 0.12776658 0.075733736, 0.44413272 0.12777902 0.075839326, 0.44412091 0.12778327 0.07595022, 0.44422314 0.12774642 0.075638846, 0.44438615 0.12768738 0.075500324, 0.4442974 0.12771954 0.07555972, 0.44458964 0.1276138 0.075450256, 0.44448534 0.12765157 0.075463042, 0.44479349 0.12754002 0.075498804, 0.4446941 0.12757592 0.075462267, 0.48405513 0.11333786 0.1006342, 0.48394898 0.11337627 0.10061811, 0.48426372 0.11326233 0.10058917, 0.48416182 0.11329924 0.10062428, 0.48443231 0.11320145 0.10045077, 0.48435548 0.11322923 0.10053016, 0.48452631 0.11316749 0.10024752, 0.48449025 0.11318049 0.10035492, 0.48453847 0.11316313 0.10013436, 0.48453835 0.11316334 0.099360004, 0.48450872 0.11317398 0.099053755, 0.48442084 0.11320576 0.098760411, 0.48427853 0.1132573 0.09849228, 0.48094806 0.11446212 0.09382768, 0.48149171 0.11426547 0.094314024, 0.48115441 0.11438744 0.093955979, 0.48133737 0.11432125 0.094119772, 0.48383325 0.11341766 0.11034341, 0.48393363 0.11338136 0.11038934, 0.48404109 0.11334249 0.11040939, 0.48415008 0.11330298 0.11040266, 0.48425457 0.11326528 0.1103691, 0.4843491 0.11323108 0.11031123, 0.48442847 0.11320233 0.11023153, 0.48448846 0.11318062 0.11013456, 0.48452574 0.1131672 0.11002563, 0.48453841 0.11316259 0.10990997, 0.48453844 0.11316279 0.10578559, 0.4843719 0.11322312 0.10540397, 0.48428735 0.11325374 0.10534321, 0.48444209 0.1131977 0.10548256, 0.48449466 0.11317861 0.10557543, 0.48452726 0.11316679 0.10567819, 0.44435629 0.12769757 0.086130276, 0.44412097 0.12778284 0.085697159, 0.44427666 0.12772642 0.086068973, 0.44421086 0.12775025 0.085991398, 0.44416156 0.1277681 0.08590059, 0.4441312 0.12777901 0.085801229, 0.44481018 0.1275336 0.083230272, 0.4447104 0.12756963 0.083189145, 0.44460419 0.12760809 0.083173051, 0.44412097 0.12778284 0.083672687, 0.44449753 0.1276467 0.083182678, 0.44413307 0.12777847 0.083559528, 0.44439563 0.12768355 0.083217964, 0.44416916 0.12776543 0.08345224, 0.44430384 0.12771672 0.083276942, 0.44422707 0.12774448 0.083356276, 0.48422766 0.15215108 0.10658742, 0.48431036 0.15216883 0.10664915, 0.48437876 0.15218338 0.10672678, 0.48442981 0.15219428 0.10681723, 0.4844614 0.15220092 0.10691662, 0.4844721 0.15220319 0.10702057, 0.48372173 0.15204334 0.11154647, 0.48393956 0.15208955 0.11162181, 0.48382625 0.15206541 0.11159752, 0.48405516 0.15211409 0.1116185, 0.48416674 0.15213791 0.11158721, 0.48426801 0.15215956 0.11153008, 0.48435354 0.15217766 0.11145033, 0.48441812 0.15219148 0.11135207, 0.48445851 0.15220004 0.11124127, 0.48447207 0.15220299 0.11112376, 0.44454667 0.14370935 0.08622773, 0.44440559 0.14367928 0.086089119, 0.44446921 0.14369288 0.086165652, 0.44435811 0.14366914 0.086001024, 0.44432878 0.14366296 0.08590509, 0.44431886 0.14366083 0.085805073, 0.44505253 0.14381701 0.083459243, 0.44483647 0.14377107 0.083393231, 0.44494829 0.14379492 0.083413258, 0.44431892 0.14366092 0.083892271, 0.44472319 0.14374694 0.083399877, 0.44433209 0.14366379 0.083777145, 0.44461426 0.14372374 0.083433226, 0.44437093 0.143672 0.0836678, 0.444516 0.14370283 0.08349137, 0.4444333 0.14368525 0.083570883, 0.44503453 0.14381364 0.075708166, 0.47364166 0.14989966 0.090997681, 0.48418033 0.15214142 0.1017382, 0.48435834 0.15217917 0.10162522, 0.48427543 0.15216155 0.10169174, 0.48397234 0.15209715 0.10176481, 0.48407763 0.15211961 0.10176308, 0.48386899 0.15207519 0.10174344, 0.48377258 0.1520547 0.10169993, 0.47398797 0.14997318 0.091254666, 0.47376505 0.14992596 0.09107165, 0.47388092 0.14995059 0.09115766, 0.44456336 0.14371322 0.078551605, 0.44432965 0.14366357 0.078222647, 0.44441226 0.1436812 0.078412339, 0.44436118 0.14367032 0.078321978, 0.44448072 0.14369561 0.078490272, 0.44431886 0.14366135 0.078118607, 0.44431904 0.14366131 0.076151475, 0.44493067 0.14379156 0.075667337, 0.44470957 0.14374459 0.075661466, 0.44482049 0.1437681 0.075651482, 0.44436893 0.14367191 0.075931057, 0.44433162 0.14366403 0.076038256, 0.44450867 0.14370182 0.075755879, 0.44460392 0.14372197 0.075696871, 0.44442895 0.14368485 0.075835213, 0.48454332 0.15204826 0.1015607, 0.48455599 0.152051 0.10162543, 0.48454317 0.15204826 0.10169016, 0.48472825 0.15191722 0.10149597, 0.48475373 0.15192261 0.10162567, 0.48472792 0.15191711 0.10175504, 0.46919045 0.14895317 0.079528257, 0.46928468 0.14897318 0.079587385, 0.46936348 0.14898995 0.079666987, 0.46942279 0.1490026 0.079762354, 0.46945959 0.14901045 0.079868838, 0.46947211 0.14901319 0.079981104, 0.44441965 0.14368306 0.070734009, 0.44458133 0.1437175 0.070873454, 0.44449303 0.1436988 0.070812806, 0.44436461 0.14367142 0.070641026, 0.44433042 0.14366415 0.070538267, 0.44431886 0.14366165 0.070430383, 0.44433117 0.14366445 0.068301693, 0.44436678 0.14367206 0.06819661, 0.44431886 0.14366184 0.068412289, 0.44442448 0.14368433 0.068102106, 0.44450116 0.14370067 0.068022862, 0.44459316 0.14372014 0.067963228, 0.4446955 0.14374205 0.067925528, 0.4448038 0.14376502 0.067912444, 0.44491211 0.14378802 0.067923799, 0.44501531 0.14381 0.067959562, 0.4687565 0.14886065 0.083793923, 0.46897063 0.14890616 0.083850637, 0.46886051 0.14888264 0.08383511, 0.46908143 0.14892976 0.083840743, 0.46918717 0.14895217 0.083805338, 0.46928239 0.14897236 0.083746478, 0.46936211 0.14898941 0.083667025, 0.46942219 0.14900216 0.08357133, 0.4694722 0.14901282 0.08335115, 0.4694595 0.14901015 0.083464131, 0.46916991 0.1489493 0.070430532, 0.46927032 0.14897057 0.070487961, 0.4693549 0.14898853 0.070567802, 0.46941873 0.14900233 0.070665374, 0.46945861 0.14901076 0.070775881, 0.46947211 0.14901361 0.070892707, 0.44436821 0.14367263 0.062958732, 0.44460064 0.14372197 0.063192859, 0.44442767 0.14368525 0.063054428, 0.4445065 0.14370199 0.063133582, 0.44433138 0.14366481 0.062852219, 0.44431892 0.14366208 0.062739864, 0.44433358 0.14366539 0.060554221, 0.44437671 0.14367446 0.060439959, 0.44431895 0.1436623 0.060675517, 0.44499478 0.1438062 0.060213462, 0.4448795 0.14378162 0.060180947, 0.44475976 0.14375611 0.060177937, 0.44464305 0.14373122 0.060204998, 0.44453618 0.14370851 0.060259983, 0.44444564 0.14368922 0.060339943, 0.46877578 0.14886513 0.074761584, 0.46898732 0.14891019 0.074808553, 0.46887901 0.14888707 0.074797139, 0.4690955 0.14893319 0.07479535, 0.46919793 0.14895511 0.07475774, 0.46928993 0.14897451 0.074698076, 0.46936652 0.14899088 0.074618921, 0.46942428 0.1490031 0.074524716, 0.46946007 0.14901079 0.074419394, 0.46947214 0.14901341 0.074308738, 0.46914819 0.1489453 0.061335698, 0.46925512 0.14896792 0.061390832, 0.46934563 0.14898726 0.061470792, 0.46941441 0.14900182 0.061570957, 0.46945748 0.14901105 0.061684921, 0.46947205 0.14901412 0.061806396, 0.44433248 0.14366546 0.055164054, 0.44431892 0.1436625 0.055047408, 0.44437227 0.14367393 0.055274233, 0.44443625 0.14368756 0.055372044, 0.44452077 0.1437054 0.055451944, 0.44462112 0.14372687 0.055509374, 0.44431886 0.14366266 0.052941278, 0.44497311 0.14380202 0.05247058, 0.44485918 0.14377771 0.052443936, 0.44474241 0.14375289 0.052445605, 0.44462934 0.14372882 0.052475765, 0.44452649 0.14370699 0.05253236, 0.44443968 0.14368853 0.05261226, 0.44437385 0.14367446 0.052710876, 0.44433281 0.14366575 0.052822664, 0.4689118 0.14889462 0.065758839, 0.46914813 0.14894494 0.065734819, 0.4690313 0.14892015 0.065761879, 0.46934566 0.14898701 0.065600023, 0.469255 0.14896773 0.065680012, 0.46941444 0.1490017 0.065499678, 0.46945748 0.14901097 0.065385565, 0.46879631 0.1488701 0.065726444, 0.46947217 0.14901397 0.0652643, 0.46912527 0.14894091 0.052244082, 0.46922073 0.14896128 0.052285627, 0.46930572 0.14897928 0.0523469, 0.46937591 0.14899425 0.052424803, 0.46942857 0.14900538 0.052516416, 0.46946117 0.14901234 0.052617148, 0.46947211 0.14901476 0.052722558, 0.44444537 0.14369002 0.047687694, 0.44437656 0.1436753 0.047587857, 0.44453594 0.14370924 0.047767863, 0.44433358 0.14366612 0.047473565, 0.44431886 0.143663 0.047352269, 0.44464281 0.14373188 0.047822937, 0.44433209 0.14366589 0.04509376, 0.44437125 0.14367427 0.044984445, 0.44431886 0.14366303 0.045209453, 0.44443381 0.14368756 0.044887349, 0.44451675 0.1437052 0.044807568, 0.44461542 0.14372626 0.044749752, 0.44472453 0.14374945 0.044716612, 0.44483817 0.14377359 0.044710144, 0.44495028 0.1437974 0.044731036, 0.46893182 0.1488996 0.056714579, 0.46916178 0.1489484 0.05668278, 0.46904871 0.14892434 0.056712881, 0.46935126 0.14898877 0.056546375, 0.46926454 0.14897023 0.056626365, 0.46941715 0.14900282 0.05644767, 0.46945813 0.14901152 0.056335911, 0.46881795 0.14887533 0.056688026, 0.46947211 0.14901449 0.056217387, 0.46910137 0.14893624 0.04315652, 0.46920252 0.14895783 0.043194637, 0.46929309 0.14897709 0.043254867, 0.46936855 0.14899321 0.043333635, 0.46942511 0.14900522 0.043427482, 0.46946022 0.14901267 0.043531939, 0.46947214 0.1490152 0.043641612, 0.46917561 0.14895195 0.047627553, 0.46935728 0.14899048 0.047489986, 0.46927437 0.14897285 0.047569677, 0.46906653 0.14892858 0.047660783, 0.46941981 0.14900383 0.04739286, 0.46895278 0.14890453 0.047666952, 0.46945888 0.14901218 0.047283784, 0.46947214 0.14901501 0.047167942, 0.46884084 0.14888065 0.047646418, 0.4446657 0.14373736 0.040133134, 0.44441509 0.14368394 0.039952412, 0.44457018 0.14371696 0.040091708, 0.44448528 0.14369892 0.040030584, 0.4443188 0.1436635 0.039654657, 0.44436243 0.14367278 0.039861009, 0.44432995 0.14366587 0.039760277, 0.44492629 0.14379281 0.036994919, 0.44431886 0.1436635 0.037480041, 0.44470623 0.14374611 0.036990955, 0.44481644 0.14376937 0.036980048, 0.44433144 0.14366625 0.037367538, 0.44460133 0.14372361 0.037026957, 0.44436839 0.14367412 0.037260607, 0.44450685 0.14370351 0.037086114, 0.44442794 0.14368677 0.037165359, 0.44431886 0.14366399 0.029753432, 0.44433072 0.14366643 0.029644147, 0.44436562 0.14367405 0.029540166, 0.44442204 0.14368589 0.029446498, 0.44449696 0.14370188 0.029367581, 0.44458693 0.14372107 0.0293075, 0.44468758 0.14374253 0.029268965, 0.44479415 0.14376514 0.029253617, 0.44490135 0.14378801 0.029262766, 0.44449791 0.14370193 0.032341376, 0.44468972 0.14374271 0.032439843, 0.44458845 0.14372109 0.032401368, 0.44433066 0.14366643 0.032064185, 0.44431886 0.14366385 0.031954512, 0.44436595 0.14367382 0.032168552, 0.4444226 0.14368586 0.032262668, 0.46897462 0.14890958 0.038615987, 0.46928424 0.1489754 0.03850998, 0.4690848 0.14893308 0.038605139, 0.46918985 0.14895532 0.038569286, 0.46945959 0.14901276 0.038228676, 0.46936318 0.14899221 0.038430735, 0.46942267 0.14900497 0.038335189, 0.46886471 0.14888629 0.038601384, 0.46947208 0.14901547 0.038116142, 0.46947208 0.14901559 0.034563139, 0.4690766 0.14893147 0.034072384, 0.46945927 0.14901295 0.034449324, 0.46942142 0.14900491 0.034341201, 0.46918342 0.14895424 0.034106895, 0.4692798 0.14897475 0.034165695, 0.46936053 0.14899197 0.034245059, 0.46905085 0.14892651 0.024992481, 0.46916345 0.14895052 0.025022849, 0.46926579 0.1489722 0.025079533, 0.46935204 0.14899072 0.025159314, 0.46941748 0.14900452 0.025257841, 0.46945828 0.14901318 0.025369301, 0.4694722 0.14901619 0.025487706, 0.4443697 0.14367504 0.024473444, 0.44433179 0.14366695 0.024365798, 0.44443056 0.14368799 0.024569675, 0.44451132 0.14370516 0.024649307, 0.44431892 0.14366423 0.024251625, 0.4446077 0.14372575 0.02470772, 0.44471464 0.14374831 0.024742529, 0.44437602 0.14367664 0.021795198, 0.44444448 0.14369115 0.02169545, 0.44433337 0.14366755 0.021908894, 0.4443188 0.14366448 0.022029802, 0.44464043 0.14373282 0.021560088, 0.4447566 0.14375761 0.021532521, 0.44453433 0.14371035 0.021615312, 0.44487575 0.14378294 0.021534547, 0.46899679 0.14891484 0.029561058, 0.46920404 0.14895889 0.029507414, 0.4691034 0.14893757 0.029545978, 0.46942535 0.14900607 0.029274717, 0.46929404 0.14897813 0.029447272, 0.46936908 0.14899397 0.029368326, 0.46946034 0.1490135 0.029170766, 0.46888968 0.14889202 0.029552266, 0.46947211 0.14901605 0.029061452, 0.46902457 0.14892146 0.015916809, 0.46914282 0.14894661 0.015942439, 0.46925116 0.14896962 0.015996799, 0.46934339 0.14898922 0.016076788, 0.46941337 0.14900412 0.016177282, 0.4694573 0.1490135 0.016292319, 0.46947211 0.14901665 0.016414985, 0.44437355 0.14367636 0.016775683, 0.44462761 0.14373037 0.017010823, 0.44443896 0.14369026 0.016874149, 0.44452533 0.14370863 0.01695402, 0.44433281 0.14366762 0.016664222, 0.44431892 0.14366457 0.016546085, 0.44474021 0.14375433 0.01704134, 0.44437259 0.1436763 0.014081106, 0.44443688 0.14369005 0.013983205, 0.44433254 0.14366785 0.01419194, 0.44452193 0.14370809 0.013903245, 0.44462278 0.14372972 0.013846144, 0.44473401 0.14375328 0.013814762, 0.44431892 0.14366487 0.014309004, 0.4448494 0.14377783 0.013810828, 0.46903446 0.14892331 0.020501152, 0.4692567 0.14897057 0.02041842, 0.46915051 0.148948 0.020473644, 0.46941486 0.14900433 0.020238623, 0.46934649 0.14898977 0.020338371, 0.46945757 0.14901347 0.020124838, 0.46891543 0.14889787 0.020499066, 0.46947208 0.14901648 0.02000396, 0.46899796 0.14891633 0.0068456084, 0.46910441 0.14893891 0.0068608671, 0.46920487 0.14896034 0.0068995804, 0.46929464 0.14897947 0.0069598109, 0.4693695 0.14899537 0.0070387274, 0.46942571 0.14900725 0.0071321875, 0.4694604 0.1490147 0.007236138, 0.4694722 0.1490172 0.0073452145, 0.44433391 0.14366838 0.0089601129, 0.44476637 0.14376035 0.0093357414, 0.44437757 0.14367762 0.0090751797, 0.44444779 0.14369258 0.0091755539, 0.44453987 0.14371213 0.009255603, 0.44464824 0.14373524 0.0093101114, 0.44431886 0.14366518 0.0088374764, 0.4443692 0.14367606 0.0063702911, 0.44442955 0.1436889 0.0062742978, 0.44433168 0.14366804 0.0064777285, 0.44450971 0.14370598 0.0061948448, 0.44460541 0.14372636 0.0061360747, 0.44471166 0.14374895 0.0061008781, 0.4443188 0.14366533 0.0065912157, 0.44482282 0.14377263 0.006091252, 0.4690569 0.14892861 0.011437669, 0.46926907 0.14897379 0.011349186, 0.46916798 0.14895234 0.011406317, 0.46894151 0.14890407 0.011441663, 0.46947214 0.14901696 0.010943487, 0.469354 0.14899193 0.011269286, 0.4694185 0.1490055 0.011171415, 0.46945843 0.14901412 0.01106067, 0.44123405 0.12955587 0.08857511, 0.48760951 0.1127805 0.11701919, 0.44122735 0.12952605 0.088497862, 0.48770851 0.11263491 0.11678578, 0.44121495 0.12943535 0.088203862, 0.48784161 0.11252134 0.11655582, 0.44119653 0.1293886 0.087903365, 0.44977888 0.12803712 0.09718816, 0.44971147 0.12803283 0.097085074, 0.44122359 0.12979929 0.089082673, 0.44966605 0.12800993 0.096972659, 0.44964549 0.12796971 0.096858189, 0.44965115 0.1279148 0.096748069, 0.4496825 0.12784836 0.096649244, 0.44973767 0.1277746 0.096567467, 0.44981346 0.12769775 0.096507862, 0.44123408 0.12971263 0.088911399, 0.44990513 0.12762265 0.096474245, 0.45000711 0.12755384 0.096468374, 0.45011327 0.12749545 0.096490905, 0.45021716 0.12745111 0.09653978, 0.48750603 0.12668079 0.14668904, 0.4847649 0.12567207 0.1407174, 0.48468468 0.12568529 0.14063455, 0.48485684 0.12564272 0.14078222, 0.48495546 0.12559892 0.14082514, 0.4850556 0.12554279 0.14084406, 0.48515156 0.12547775 0.14083771, 0.48523849 0.12540692 0.14080693, 0.48531139 0.12533441 0.14075272, 0.48536655 0.1252642 0.1406783, 0.48540089 0.12519975 0.14058794, 0.48541263 0.12514473 0.14048631, 0.46192673 0.12515891 0.10789032, 0.46188837 0.12509097 0.10769136, 0.46189991 0.12513456 0.1078008, 0.46196821 0.12517223 0.10797669, 0.46190107 0.12503459 0.10758777, 0.46193716 0.12496862 0.10749649, 0.46207061 0.12482275 0.10736905, 0.46199477 0.1248966 0.10742222, 0.48541263 0.12377974 0.13755848, 0.4621605 0.12475102 0.10734035, 0.48541 0.12374851 0.13748787, 0.46236131 0.12463035 0.10736011, 0.4622592 0.12468573 0.10733713, 0.46246108 0.12458798 0.10740779, 0.46202278 0.12517406 0.10805602, 0.46901938 0.12353784 0.11426641, 0.46895173 0.12353353 0.1141635, 0.46890655 0.12351058 0.11405133, 0.46888587 0.12347046 0.11393677, 0.46889147 0.1234155 0.1138265, 0.46892288 0.1233491 0.11372755, 0.46897817 0.12327518 0.11364578, 0.46905383 0.12319839 0.11358638, 0.48514369 0.12361611 0.13683401, 0.48476502 0.12246904 0.13384767, 0.4846848 0.12248218 0.13376458, 0.46914551 0.12312332 0.11355273, 0.4848569 0.12243959 0.13391237, 0.48495546 0.12239574 0.13395531, 0.46924749 0.12305447 0.1135468, 0.48505569 0.12233976 0.13397427, 0.46935371 0.12299612 0.11356913, 0.46945763 0.12295173 0.11361836, 0.48515159 0.1222747 0.1339681, 0.48523852 0.12220392 0.13393705, 0.48525286 0.12361965 0.1369933, 0.4853116 0.12213142 0.13388269, 0.48533574 0.12364621 0.13716553, 0.48536658 0.12206106 0.13380878, 0.48538956 0.12369485 0.13734443, 0.48540097 0.12199667 0.13371821, 0.48540235 0.12372006 0.13741629, 0.48541251 0.12194172 0.13361643, 0.47893322 0.12112281 0.12285875, 0.47887552 0.12111387 0.12275924, 0.47890046 0.12112184 0.12281094, 0.47885245 0.12107302 0.12263988, 0.47885939 0.1210991 0.12270571, 0.47896191 0.12091205 0.12244652, 0.47919616 0.12077118 0.1224698, 0.47901574 0.12086911 0.12242915, 0.47891638 0.12095638 0.12247826, 0.47888184 0.12099953 0.12252314, 0.47886017 0.12103921 0.12257792, 0.48483989 0.11872973 0.12593128, 0.48514369 0.12070432 0.13058867, 0.48493996 0.11868717 0.12597917, 0.48504239 0.11863151 0.12600218, 0.48514131 0.11856587 0.12599899, 0.48523131 0.11849399 0.12596954, 0.48530713 0.1184199 0.12591623, 0.4852528 0.1207078 0.13074787, 0.48536459 0.11834773 0.12584122, 0.4853358 0.12073439 0.13092004, 0.48540044 0.11828165 0.12574933, 0.48538956 0.12078311 0.13109909, 0.48540235 0.1208083 0.13117094, 0.48541251 0.11822541 0.1256455, 0.48541 0.12083651 0.13124244, 0.48483339 0.11738999 0.1230488, 0.48493996 0.11645024 0.12118162, 0.48483983 0.11649285 0.12113382, 0.48504242 0.11639468 0.12120445, 0.48499015 0.11734225 0.12316428, 0.48514125 0.11632904 0.12120141, 0.48523125 0.11625715 0.12117209, 0.48512933 0.11731842 0.12330686, 0.48530716 0.11618307 0.12111856, 0.4852452 0.11731975 0.12347044, 0.48536465 0.11611088 0.12104385, 0.48533306 0.117346 0.1236489, 0.48540047 0.1160448 0.12095167, 0.48538947 0.11739615 0.12383474, 0.487506 0.11322346 0.11782528, 0.4854126 0.11748092 0.12404875, 0.4852452 0.11485921 0.11819319, 0.48512939 0.11485793 0.11802937, 0.4853332 0.11488545 0.1183715, 0.48538962 0.11493552 0.11855747, 0.48540241 0.11496085 0.11862911, 0.48541015 0.11498916 0.11870052, 0.48541263 0.11502042 0.11877133, 0.48541251 0.11598863 0.12084781, 0.48540226 0.11742134 0.12390648, 0.48541 0.11744964 0.12397812, 0.48752782 0.11301576 0.11741032, 0.48499021 0.11488175 0.11788692, 0.48483342 0.11492929 0.11777152, 0.47907498 0.12082987 0.12242736, 0.47913632 0.12079664 0.12244131, 0.48541263 0.12086782 0.13131304, 0.46136385 0.12509072 0.10833417, 0.46147314 0.12509422 0.10849343, 0.46128079 0.12506416 0.10816191, 0.46122709 0.12501574 0.1079831, 0.48471671 0.12357596 0.13752674, 0.48468989 0.12355158 0.13743712, 0.48464835 0.12353835 0.13735105, 0.48459384 0.12353654 0.13727136, 0.48471668 0.11481662 0.11873953, 0.48468855 0.11479153 0.11864664, 0.48464462 0.11477841 0.11855747, 0.48458663 0.11477782 0.11847533, 0.48451716 0.11478961 0.1184044, 0.48443863 0.11481343 0.11834665, 0.47829601 0.1210403 0.12316896, 0.47838327 0.12104318 0.12329604, 0.47822958 0.12101921 0.12303101, 0.47818658 0.1209802 0.12288786, 0.48471668 0.12066408 0.13128124, 0.48468986 0.12063971 0.13119192, 0.48464838 0.12062648 0.13110556, 0.48459381 0.12062468 0.1310261, 0.48471674 0.11727722 0.12401699, 0.48468849 0.11725195 0.12392403, 0.4846445 0.11723897 0.12383483, 0.48458657 0.11723843 0.12375294, 0.48451701 0.11725016 0.12368192, 0.48443872 0.11727412 0.12362398, 0.46906298 0.12283586 0.11419334, 0.48472828 0.12178041 0.13369174, 0.48472318 0.12067659 0.13131733, 0.48472828 0.12070648 0.1313885, 0.484727 0.12069085 0.1313531, 0.47816813 0.12091044 0.12271263, 0.4781884 0.12082019 0.12254731, 0.47824636 0.12071449 0.12240086, 0.47833851 0.12059933 0.12228195, 0.47845992 0.1204811 0.12219693, 0.47860357 0.12036653 0.12215091, 0.47876155 0.12026188 0.12214603, 0.4789249 0.12017317 0.12218286, 0.48472318 0.11728974 0.12405299, 0.484727 0.11730388 0.12408863, 0.48472819 0.118064 0.12572072, 0.48472831 0.11731957 0.12412395, 0.47908461 0.12010548 0.12225913, 0.44982246 0.12733522 0.097115055, 0.46234956 0.1239222 0.1071973, 0.48472822 0.12498343 0.14056148, 0.48472825 0.11582711 0.12092297, 0.48472682 0.1236027 0.13759829, 0.48472315 0.12358844 0.13756259, 0.48472825 0.12361835 0.1376337, 0.46120402 0.1249284 0.10776411, 0.46122941 0.12481555 0.10755725, 0.46130177 0.12468359 0.10737441, 0.46141696 0.12453952 0.10722564, 0.46156865 0.12439176 0.10711943, 0.46174824 0.12424859 0.1070617, 0.46194574 0.12411779 0.10705562, 0.46214998 0.12400696 0.10710166, 0.48472321 0.11482909 0.11877544, 0.48472819 0.11485894 0.11884661, 0.48472697 0.1148434 0.11881126, 0.46913031 0.12290522 0.11397849, 0.46906957 0.1229482 0.11398624, 0.46902448 0.12299483 0.11402382, 0.46919778 0.12297456 0.11376353, 0.46900418 0.1230357 0.11408292, 0.46907625 0.12306061 0.11377929, 0.46901268 0.12306257 0.1141523, 0.468986 0.1231539 0.11385389, 0.46894553 0.12323549 0.11397274, 0.46896261 0.12328903 0.11411132, 0.48477116 0.12200011 0.13376518, 0.48483753 0.12196676 0.1337858, 0.48489842 0.1219216 0.1337734, 0.48481411 0.1222198 0.13383885, 0.48494115 0.12187392 0.13373046, 0.48494664 0.12215319 0.13388006, 0.48506841 0.12206271 0.13385539, 0.48515385 0.12196741 0.13376971, 0.48483303 0.11825316 0.12581454, 0.48489591 0.11820731 0.1258036, 0.48493764 0.11844237 0.12590824, 0.48494044 0.11815853 0.12576078, 0.48506364 0.11835068 0.12588666, 0.48515251 0.11825316 0.12580107, 0.44988993 0.12740459 0.096900091, 0.44982919 0.12744753 0.096907929, 0.44978413 0.12749414 0.096945271, 0.44995725 0.12747395 0.096685097, 0.44976369 0.12753503 0.097004578, 0.4498359 0.1275599 0.096700862, 0.44977233 0.12756182 0.097073898, 0.44974568 0.12765317 0.096775666, 0.44970506 0.12773478 0.096894309, 0.44972208 0.12778845 0.09703286, 0.48477116 0.12520309 0.140635, 0.48483744 0.12516975 0.14065562, 0.4848983 0.1251246 0.14064313, 0.48481402 0.12542292 0.1407087, 0.48494104 0.12507693 0.14060046, 0.4849464 0.12535629 0.14074983, 0.48506841 0.12526582 0.14072491, 0.48515376 0.12517056 0.14063953, 0.48483297 0.11601622 0.12101682, 0.484896 0.11597046 0.12100603, 0.4849377 0.11620542 0.12111069, 0.48494038 0.11592169 0.12096332, 0.4850637 0.1161138 0.12108923, 0.4851526 0.1160163 0.12100355, 0.44082382 0.12944339 0.087587819, 0.44079968 0.12946673 0.087869987, 0.43929967 0.1294644 0.08785437, 0.4407655 0.12952925 0.088144466, 0.43929967 0.12952732 0.088138089, 0.44073197 0.12963067 0.088409767, 0.43929967 0.12963067 0.088409767, 0.43929958 0.12983735 0.088853106, 0.44072789 0.12968054 0.088516876, 0.44072786 0.12983736 0.088853136, 0.44128534 0.13132152 0.090363607, 0.4877778 0.12798193 0.14821456, 0.44125399 0.13098738 0.090278849, 0.48777196 0.12784281 0.14817582, 0.48775107 0.12759179 0.14804946, 0.44123885 0.1306745 0.090129361, 0.48770794 0.12730524 0.1478041, 0.4412351 0.13039456 0.089924708, 0.48765281 0.12706605 0.14749621, 0.44123667 0.13015439 0.089676276, 0.44123608 0.12995534 0.08939217, 0.48561162 0.13039909 0.14553545, 0.48546797 0.13038222 0.14535688, 0.48574898 0.13046789 0.14570667, 0.48587292 0.13058482 0.14586078, 0.44129983 0.14020722 0.090382084, 0.44312975 0.13802136 0.092659459, 0.44302443 0.13786207 0.092528507, 0.4859769 0.13074388 0.14599024, 0.48605537 0.13093667 0.14608799, 0.48610413 0.13115306 0.14614879, 0.48612079 0.13138142 0.14616929, 0.44294479 0.13766846 0.092429504, 0.48777923 0.13637921 0.14823388, 0.44129476 0.14039992 0.090376005, 0.44353876 0.13821909 0.093168601, 0.48552826 0.13458721 0.14543213, 0.44325522 0.13813765 0.092815742, 0.44347855 0.1332114 0.093093678, 0.44289538 0.13745067 0.092367962, 0.44339398 0.13820477 0.092988655, 0.44287851 0.13722071 0.09234713, 0.44287863 0.1342105 0.092346981, 0.44129989 0.13164999 0.090381727, 0.44289359 0.13399385 0.09236522, 0.44293743 0.13378759 0.092419967, 0.44300833 0.13360123 0.092508301, 0.44310275 0.13344401 0.092625812, 0.44321629 0.13332298 0.092767105, 0.44334364 0.13324431 0.092925593, 0.48606282 0.13400865 0.14609729, 0.48610601 0.13380373 0.1461512, 0.485993 0.13419393 0.14601062, 0.48589996 0.13435088 0.1458946, 0.48578775 0.13447228 0.14575501, 0.48566189 0.13455234 0.14559837, 0.48612079 0.13358867 0.14616944, 0.48512146 0.13408802 0.14572404, 0.44313201 0.13771994 0.093460932, 0.48530748 0.1339698 0.14595543, 0.48518842 0.13407053 0.1458074, 0.48525134 0.13403048 0.14588569, 0.48538888 0.1337986 0.14605691, 0.48541039 0.13369623 0.1460837, 0.48535386 0.13389134 0.14601324, 0.48541775 0.13358873 0.14609291, 0.48534593 0.1310627 0.14600323, 0.48529387 0.13098316 0.1459385, 0.48538512 0.13115899 0.14605211, 0.48540965 0.13126715 0.14608254, 0.48523191 0.13092467 0.1458614, 0.48516321 0.13089018 0.14577578, 0.48541778 0.13138144 0.14609291, 0.48509148 0.13088182 0.14568652, 0.44305974 0.13771267 0.093370751, 0.44292751 0.1376209 0.093206272, 0.4429903 0.13767913 0.093284324, 0.44287494 0.13754125 0.093140885, 0.44281039 0.13733567 0.093060359, 0.44283512 0.13744448 0.093091205, 0.44280198 0.1372207 0.093049929, 0.44280204 0.13421051 0.09304975, 0.44310197 0.13371086 0.093422994, 0.44280943 0.13410214 0.093058929, 0.4430345 0.13372731 0.093339249, 0.44286683 0.13390587 0.093130335, 0.4428314 0.13399895 0.093086317, 0.44297084 0.13376676 0.093259797, 0.44291407 0.13382722 0.093189225, 0.4407174 0.12989512 0.0889671, 0.43929967 0.13007392 0.089239344, 0.44062346 0.13016222 0.089344367, 0.43929976 0.13039133 0.089562312, 0.44053325 0.13050817 0.08965005, 0.43929967 0.13077322 0.089805588, 0.44048607 0.13087772 0.089852795, 0.43929961 0.13120005 0.089956716, 0.44048253 0.13114874 0.089944109, 0.44050583 0.13143089 0.089996085, 0.43929955 0.13164996 0.090008005, 0.44052035 0.13164993 0.090008005, 0.44052032 0.14020711 0.090008482, 0.43929961 0.14020708 0.090008602, 0.44111359 0.14246713 0.087521926, 0.44117227 0.14245823 0.087859556, 0.4878144 0.1523747 0.1180497, 0.44119194 0.14239952 0.088194832, 0.4876574 0.15225825 0.1183161, 0.44119462 0.14228927 0.088517532, 0.48754495 0.15209737 0.11858614, 0.44120446 0.14223914 0.088636532, 0.44120446 0.14208087 0.088952884, 0.45066521 0.14292894 0.097396091, 0.45058039 0.14285807 0.097446993, 0.45051491 0.14278637 0.097520068, 0.44120458 0.14208387 0.088946924, 0.4507643 0.14299475 0.097370699, 0.45047256 0.14271802 0.097611323, 0.45087174 0.14305153 0.097372487, 0.45045578 0.14265715 0.097715214, 0.45098135 0.14309606 0.097400829, 0.4504658 0.14260726 0.097825721, 0.45049077 0.14257871 0.097909585, 0.45108646 0.1431257 0.097454473, 0.45052972 0.14255908 0.097990647, 0.45058167 0.14254908 0.098066226, 0.46313533 0.14380921 0.10900019, 0.46350664 0.1440604 0.10889561, 0.46312803 0.14377287 0.10906513, 0.46315891 0.14385054 0.1089427, 0.46319744 0.14389452 0.108896, 0.46324843 0.1439382 0.10886322, 0.46330863 0.1439791 0.10884629, 0.46337447 0.14401439 0.10884608, 0.46344185 0.1440421 0.10886298, 0.46313766 0.14374386 0.10913332, 0.46320373 0.14371432 0.10926293, 0.46316329 0.14372399 0.10920055, 0.47148529 0.14467518 0.11621763, 0.47140047 0.14460424 0.11626844, 0.47133484 0.14453262 0.11634158, 0.47158441 0.14474088 0.11619236, 0.47129253 0.14446422 0.11643268, 0.47169188 0.14479768 0.11619379, 0.47127593 0.14440335 0.11653666, 0.47180143 0.14484218 0.11622219, 0.47128591 0.14435318 0.11664702, 0.47131094 0.14432469 0.116731, 0.4719066 0.14487191 0.1162758, 0.47134992 0.14430502 0.11681201, 0.47140172 0.14429513 0.1168877, 0.48475257 0.15028766 0.11921252, 0.48493311 0.15031289 0.1193554, 0.48745623 0.15185472 0.11897628, 0.48508456 0.15030666 0.11953045, 0.48743185 0.1516352 0.1193891, 0.48527011 0.15020241 0.11993785, 0.48529428 0.15010974 0.12014891, 0.48519889 0.15026917 0.11972798, 0.48075542 0.14513776 0.12522675, 0.48086551 0.14508881 0.12544285, 0.48079816 0.14510462 0.12533914, 0.48073938 0.14518613 0.12511314, 0.48075166 0.14524671 0.12500511, 0.48079097 0.14531584 0.12490906, 0.48085496 0.14538915 0.1248313, 0.48093995 0.14546207 0.12477662, 0.48104033 0.14553 0.12474824, 0.48115018 0.14558883 0.12474813, 0.48126265 0.14563492 0.12477623, 0.4813703 0.14566542 0.12483074, 0.48529425 0.14903668 0.12229465, 0.4852806 0.148976 0.12240134, 0.48477024 0.14859144 0.12262346, 0.48475251 0.14760461 0.12457801, 0.4846634 0.14856127 0.12256934, 0.48488152 0.14863703 0.12265174, 0.48499051 0.14869508 0.12265228, 0.48509052 0.14876236 0.12262513, 0.48493305 0.14762987 0.1247208, 0.48517528 0.14883456 0.1225716, 0.48508453 0.1476236 0.12489568, 0.48524019 0.14890721 0.12249567, 0.48519889 0.14758614 0.12509333, 0.48527017 0.1475192 0.12530328, 0.48529431 0.14742669 0.12551425, 0.48466349 0.14636591 0.12695928, 0.48529425 0.14684148 0.12668441, 0.48504215 0.14472756 0.13064142, 0.48477024 0.14639612 0.1270134, 0.48488164 0.14644176 0.12704159, 0.48499057 0.14649999 0.12704204, 0.48509055 0.14656709 0.12701504, 0.4851754 0.1466392 0.12696145, 0.48524025 0.14671193 0.12688531, 0.48514947 0.14470647 0.13079856, 0.48522896 0.14466467 0.13096724, 0.4852806 0.14678082 0.1267911, 0.48527795 0.14460358 0.13114186, 0.48529419 0.1445255 0.1313159, 0.48460129 0.14316259 0.1332988, 0.48504224 0.14182565 0.13644476, 0.48451862 0.14316066 0.1332138, 0.48469761 0.14318095 0.1333652, 0.48480207 0.14321467 0.1334099, 0.48490897 0.14326192 0.13342984, 0.48501214 0.14331992 0.13342433, 0.48510572 0.1433855 0.13339339, 0.48518455 0.14345512 0.13333888, 0.48514944 0.14180444 0.13660188, 0.48524439 0.14352474 0.13326378, 0.48522893 0.1417626 0.13677077, 0.48528153 0.14359036 0.13317247, 0.4852778 0.14170167 0.13694526, 0.48529425 0.14364836 0.13306983, 0.48529437 0.14162347 0.13711907, 0.48460129 0.13961563 0.14039163, 0.48743191 0.13808241 0.14649104, 0.48451847 0.13961378 0.14030682, 0.48469773 0.13963383 0.14045827, 0.4848021 0.13966769 0.14050274, 0.48490891 0.13971487 0.14052285, 0.48501202 0.13977292 0.14051713, 0.48510563 0.13983861 0.14048631, 0.48518458 0.13990813 0.14043193, 0.48524448 0.13997778 0.14035679, 0.48528171 0.1400433 0.1402656, 0.48529437 0.14010137 0.14016293, 0.45061585 0.14306614 0.097895548, 0.45069042 0.14324674 0.098027393, 0.45064405 0.14310756 0.097842976, 0.45069465 0.14314988 0.097812489, 0.45054159 0.14288561 0.097763255, 0.45075813 0.143185 0.097810373, 0.45059779 0.14296846 0.097658232, 0.45069912 0.14305292 0.097597793, 0.4508259 0.14312321 0.097593114, 0.47143593 0.1448123 0.11671685, 0.47151032 0.1449928 0.11684884, 0.47146419 0.14485362 0.11666425, 0.47151485 0.14489594 0.11663394, 0.47136149 0.14463192 0.11658476, 0.47157821 0.14493108 0.11663152, 0.47141799 0.14471456 0.11647971, 0.47151914 0.14479905 0.11641909, 0.47164604 0.14486942 0.11641471, 0.48450139 0.14483644 0.13108368, 0.48032445 0.1451977 0.12588491, 0.48461905 0.14477459 0.13133402, 0.48462728 0.14473543 0.13142084, 0.48459455 0.14480509 0.13124664, 0.48455486 0.14482591 0.13116224, 0.48462725 0.14385834 0.13317506, 0.48457974 0.14771624 0.12540881, 0.48461527 0.14768289 0.12551369, 0.48462734 0.14763662 0.12561916, 0.48452249 0.14773507 0.12530993, 0.4844467 0.14773817 0.12522243, 0.48435652 0.14772548 0.12515105, 0.48462728 0.14705148 0.12678932, 0.48133412 0.14635099 0.12466107, 0.48111859 0.14628994 0.12455212, 0.48010424 0.14529559 0.12545337, 0.48019001 0.14522943 0.12567757, 0.48007244 0.14539237 0.12522577, 0.48009667 0.14551358 0.12500943, 0.48017535 0.14565173 0.12481762, 0.48030367 0.14579813 0.12466218, 0.48047349 0.145944 0.12455271, 0.48067442 0.14607997 0.12449612, 0.480894 0.14619771 0.12449588, 0.48483166 0.14693826 0.12682141, 0.48478171 0.14689004 0.12686463, 0.48503581 0.14682506 0.12685333, 0.48471209 0.14684823 0.12687348, 0.48493609 0.14672858 0.12693952, 0.48479685 0.14664496 0.12695752, 0.484833 0.14374706 0.13320453, 0.48478675 0.14370069 0.13324769, 0.48503855 0.14363584 0.13323425, 0.48472121 0.14365946 0.13325994, 0.48494616 0.1435432 0.13332056, 0.48465082 0.14363243 0.13323851, 0.48481515 0.14346065 0.1333449, 0.48467413 0.14340673 0.13330181, 0.48435649 0.1504087 0.11978562, 0.48450145 0.1419345 0.13688688, 0.48461917 0.14187242 0.13713725, 0.48462722 0.14183345 0.13722415, 0.48459461 0.14190306 0.13704999, 0.48455495 0.14192395 0.13696547, 0.48462728 0.14031138 0.14026789, 0.4846153 0.1503661 0.12014844, 0.48462728 0.15031984 0.12025385, 0.48457965 0.15039942 0.12004341, 0.48452237 0.15041825 0.11994459, 0.48444667 0.15042146 0.11985709, 0.48462722 0.14924677 0.12239946, 0.46266279 0.14382336 0.10970487, 0.46255523 0.14384867 0.10953911, 0.46248654 0.14390169 0.1093597, 0.46246114 0.14397901 0.10917769, 0.46248049 0.14407595 0.10900457, 0.46254352 0.14418641 0.10885118, 0.46264598 0.14430359 0.10872672, 0.46278194 0.14442016 0.10863923, 0.46294269 0.14452907 0.1085939, 0.46311846 0.14462325 0.1085939, 0.46329796 0.14469698 0.10863875, 0.46347043 0.1447459 0.10872589, 0.48483303 0.14020009 0.14029755, 0.48478675 0.14015374 0.14034079, 0.48503867 0.14008896 0.14032717, 0.48472112 0.14011256 0.14035286, 0.48494622 0.13999623 0.14041354, 0.4846507 0.14008553 0.1403314, 0.48481503 0.13991375 0.14043783, 0.48467419 0.13985969 0.14039482, 0.48483166 0.14913353 0.12243177, 0.48478171 0.14908519 0.12247469, 0.48503581 0.1490204 0.1224636, 0.484712 0.14904337 0.12248372, 0.48493603 0.14892378 0.12254994, 0.48479679 0.14884025 0.12256776, 0.4407835 0.14223211 0.088430867, 0.43929961 0.14234844 0.088144884, 0.44084141 0.1423476 0.088147387, 0.43929958 0.14223208 0.088430867, 0.43929961 0.14241937 0.087844238, 0.44088927 0.14241879 0.087848172, 0.44090131 0.14243707 0.0876932, 0.44077235 0.14215131 0.088592574, 0.43929961 0.14199601 0.088903055, 0.44077227 0.14199601 0.088903055, 0.4875311 0.13784534 0.14700614, 0.44125718 0.1418211 0.089449152, 0.48761842 0.13756777 0.14745472, 0.44126186 0.14145663 0.08987613, 0.48768434 0.13728447 0.14778863, 0.4412618 0.14104578 0.090169773, 0.48772308 0.13706072 0.14798091, 0.48775199 0.13683203 0.14811952, 0.44127133 0.14073226 0.090303764, 0.48777059 0.13660346 0.14820345, 0.44051525 0.14033565 0.09000431, 0.43929955 0.14064644 0.089959607, 0.44050848 0.14068086 0.08995162, 0.43929961 0.14106414 0.089815632, 0.44053808 0.14101067 0.08983992, 0.44059482 0.141314 0.089674219, 0.43929961 0.14144014 0.089583144, 0.44066706 0.14158247 0.089460596, 0.43929961 0.14175592 0.089274034, 0.44073668 0.14181015 0.089204535, 0.44077227 0.14199398 0.088906869, 0.4878884 0.15229069 0.1188444, 0.48773411 0.15217361 0.11870743, 0.48782894 0.15235083 0.11824624, 0.48778072 0.15188348 0.11951329, 0.48762187 0.15174165 0.11944248, 0.48790032 0.15205325 0.11959799, 0.48797438 0.15224247 0.1196927, 0.48797455 0.13868952 0.14679481, 0.48790026 0.1385003 0.14669989, 0.48778093 0.1383304 0.14661501, 0.48762205 0.13818878 0.1465442, 0.48797438 0.13637921 0.14863656, 0.48789966 0.13637914 0.14842413, 0.487982 0.13812336 0.14772938, 0.48793036 0.13798718 0.14761423, 0.48781118 0.13782063 0.14747261, 0.48798597 0.13762534 0.14823817, 0.48794648 0.13753042 0.14811285, 0.48798779 0.13731959 0.14845, 0.48785475 0.13741162 0.14795636, 0.48795322 0.13724844 0.14832102, 0.48768476 0.13728471 0.14778887, 0.48798898 0.13700557 0.14860182, 0.48787317 0.13715878 0.14815877, 0.48795816 0.13695841 0.14847039, 0.48772344 0.13706073 0.14798091, 0.48788682 0.13689859 0.14830433, 0.48797828 0.12608635 0.14696608, 0.48791447 0.12626551 0.14688276, 0.48781118 0.12642869 0.14680646, 0.48798996 0.1277073 0.14865275, 0.4879618 0.12774391 0.14852418, 0.48789626 0.12779039 0.14836024, 0.48798904 0.1273571 0.14850684, 0.48795822 0.12742086 0.14838265, 0.48788634 0.12750183 0.1482247, 0.48798719 0.12695648 0.1482272, 0.48795071 0.12705292 0.14811035, 0.48786613 0.1271739 0.14796348, 0.48798475 0.12662271 0.14787753, 0.48794103 0.1267482 0.14776959, 0.48770806 0.12730511 0.14780413, 0.4878397 0.12690359 0.14763598, 0.48767319 0.12656917 0.14674114, 0.48765293 0.12706612 0.14749621, 0.48797825 0.11262903 0.11810245, 0.48791459 0.11280814 0.118019, 0.4878113 0.11297143 0.11794285, 0.48767319 0.1131119 0.11787747, 0.48766717 0.11293444 0.11746995, 0.48777205 0.11269754 0.11713089, 0.48778597 0.11283401 0.11753811, 0.48790416 0.11258301 0.11725427, 0.48791006 0.11267295 0.11763926, 0.47383991 0.11680332 0.076535448, 0.47354856 0.088516712 0.076036885, 0.47338042 0.11700273 0.075675294, 0.47384027 0.088866577 0.076534078, 0.47331551 0.088236958 0.075507984, 0.4731454 0.088033035 0.074957177, 0.47309491 0.11712672 0.074732348, 0.47306481 0.087834701 0.074562535, 0.47301617 0.08771506 0.07416223, 0.49215961 0.10718463 0.10400416, 0.48865637 0.11144306 0.09875147, 0.49215958 0.11144271 0.10400416, 0.49261916 0.1075523 0.10486458, 0.49262032 0.11144271 0.1048678, 0.49290466 0.10778065 0.10580756, 0.49290413 0.11144255 0.10580455, 0.49299985 0.10785688 0.10677837, 0.49299985 0.11144248 0.10677849, 0.49299958 0.1534411 0.13159283, 0.49299964 0.15644255 0.10733773, 0.49299958 0.15644084 0.1345094, 0.49299952 0.15344252 0.10733767, 0.49299964 0.13934562 0.16756721, 0.49299961 0.13887398 0.16762386, 0.49299964 0.13980839 0.16739221, 0.4929997 0.14021856 0.16710623, 0.49299964 0.14048059 0.16682111, 0.49299961 0.14067796 0.16650318, 0.49299982 0.11215539 0.13429351, 0.49299982 0.10785533 0.13302873, 0.49299976 0.11176515 0.13324483, 0.49299976 0.11152214 0.13208897, 0.49299982 0.11144125 0.13089605, 0.4929997 0.12509735 0.16205154, 0.4929997 0.12343906 0.16645317, 0.49299958 0.13829435 0.16321395, 0.49299958 0.13874435 0.16271676, 0.49299964 0.13776746 0.16361223, 0.49299958 0.13909909 0.16214155, 0.49299964 0.13717531 0.16390504, 0.49299964 0.13652954 0.16408537, 0.49299964 0.13585646 0.16414537, 0.4929997 0.12526545 0.16762291, 0.49299976 0.12838271 0.16414477, 0.4929997 0.12501331 0.16760691, 0.4929997 0.12475784 0.16755734, 0.49299973 0.12437358 0.16741277, 0.4929997 0.1276927 0.16408192, 0.49299949 0.15622975 0.13540383, 0.49299979 0.12402222 0.16719006, 0.4929997 0.12703207 0.16389285, 0.49299973 0.12369743 0.16686822, 0.49299973 0.12642917 0.16358612, 0.49299964 0.12589648 0.16316925, 0.49299976 0.12544596 0.16265024, 0.49299952 0.15268341 0.13497655, 0.49299955 0.15309682 0.13393755, 0.49299952 0.15634607 0.13511793, 0.49299952 0.1564171 0.13481732, 0.49299958 0.15335508 0.1327848, 0.4924542 0.1380316 0.16218244, 0.49242219 0.1382885 0.16173612, 0.49261525 0.13839431 0.16178904, 0.49297678 0.13765584 0.16343175, 0.49248037 0.1373066 0.16286622, 0.49247375 0.13769974 0.16256438, 0.49265549 0.13737069 0.16297017, 0.49297562 0.13856967 0.16258596, 0.49297398 0.138898 0.16204093, 0.49290451 0.13840351 0.16246139, 0.49289843 0.13870706 0.16194548, 0.49279013 0.13825372 0.16234888, 0.49277672 0.1385363 0.16186009, 0.49263772 0.13812795 0.16225447, 0.4928582 0.13794775 0.16283514, 0.49290958 0.13754937 0.16325949, 0.4928008 0.13745293 0.16310309, 0.49245593 0.12785533 0.16320719, 0.49242225 0.12838283 0.16323863, 0.49261525 0.12838283 0.16335689, 0.49297714 0.12654272 0.16340767, 0.49248353 0.12689939 0.16284822, 0.49247667 0.12735365 0.16307496, 0.49265781 0.12683386 0.16295098, 0.4929758 0.1277325 0.16386758, 0.49297401 0.1283828 0.16391991, 0.49290505 0.12777027 0.16366352, 0.49289855 0.12838273 0.16370641, 0.49279091 0.12780438 0.16347991, 0.49277678 0.12838283 0.16351555, 0.49263892 0.12783322 0.16332541, 0.49285915 0.12721926 0.16341649, 0.49291024 0.12665132 0.16323756, 0.49280211 0.12674987 0.16308294, 0.49215683 0.15344274 0.10455988, 0.49153498 0.1534428 0.10380222, 0.49153504 0.15644275 0.10380246, 0.49215683 0.15644272 0.10455991, 0.49261895 0.15344256 0.10542427, 0.49261895 0.15644263 0.10542439, 0.49290344 0.15344261 0.10636233, 0.49290344 0.15644261 0.10636236, 0.48860136 0.15344277 0.10086836, 0.47446397 0.15644361 0.086731181, 0.47446406 0.15043558 0.086730883, 0.47396031 0.150307 0.086142078, 0.47384217 0.15644363 0.085973367, 0.47354671 0.15020157 0.085469618, 0.47338009 0.15644358 0.085109249, 0.47313577 0.15009663 0.084354207, 0.47309551 0.15644366 0.084171221, 0.49242207 0.1518728 0.13457121, 0.49242231 0.13585654 0.16323899, 0.49242243 0.11297683 0.13391049, 0.49242234 0.12591876 0.16166852, 0.49219719 0.11254938 0.13230322, 0.49231488 0.11272582 0.13314326, 0.49214837 0.15237659 0.13264187, 0.49229243 0.15218291 0.13365658, 0.49199954 0.15740515 0.13497122, 0.4759995 0.15740517 0.13497122, 0.49199945 0.15729877 0.13542195, 0.47599956 0.15729865 0.13542195, 0.49199945 0.15712419 0.1358511, 0.47599956 0.15712406 0.1358511, 0.48208275 0.15415661 0.14178543, 0.48147389 0.15391541 0.14226757, 0.48101178 0.15361583 0.14286648, 0.48280302 0.15432577 0.14144705, 0.48072329 0.15327576 0.1435468, 0.48359266 0.15441284 0.14127316, 0.48062527 0.1529146 0.14426897, 0.48440614 0.15441285 0.14127316, 0.48519602 0.15432575 0.14144705, 0.48591635 0.15415667 0.14178543, 0.48652521 0.15391536 0.14226784, 0.48698726 0.15361597 0.14286648, 0.48727575 0.15327577 0.14354692, 0.48737386 0.15291473 0.14426886, 0.47599968 0.14058973 0.16891505, 0.48062536 0.14087391 0.16834711, 0.49199966 0.14157234 0.16695045, 0.48737386 0.14128812 0.16751848, 0.4921082 0.1394282 0.16856591, 0.47610393 0.13859788 0.17049815, 0.49209061 0.13998257 0.16840695, 0.49212158 0.1388739 0.16861631, 0.4761214 0.13789153 0.17058076, 0.48073974 0.14069472 0.16865467, 0.47602472 0.14029536 0.16938864, 0.48083735 0.14048302 0.16893227, 0.47604975 0.13990386 0.16981338, 0.48090419 0.14032359 0.16910182, 0.48098934 0.14015123 0.16925608, 0.48116168 0.13985312 0.16946684, 0.47607931 0.1392903 0.17023872, 0.4812074 0.13979429 0.16950057, 0.48123953 0.13976622 0.16951524, 0.49203154 0.14118053 0.16754578, 0.48716184 0.14087117 0.16815589, 0.48704603 0.14059572 0.16844831, 0.4812772 0.13974352 0.1695254, 0.48132035 0.13972864 0.16953073, 0.48134682 0.13972439 0.16953088, 0.49206296 0.14063758 0.1680492, 0.48695031 0.14040479 0.16861598, 0.48683757 0.1402016 0.16877006, 0.48674375 0.14009224 0.16884644, 0.48670831 0.14006993 0.1688628, 0.48678395 0.14012842 0.1688209, 0.48681316 0.14016379 0.16879652, 0.48666862 0.14005405 0.16887574, 0.47612154 0.1346629 0.17058061, 0.49212155 0.1252654 0.16861545, 0.47533101 0.12622663 0.17067705, 0.47533092 0.13461442 0.17067765, 0.48116165 0.15254594 0.14408468, 0.48083737 0.15283597 0.14422967, 0.48716179 0.15283597 0.14422967, 0.48675498 0.1528497 0.14347719, 0.48683748 0.15254588 0.14408468, 0.4870697 0.15317443 0.14355288, 0.48651236 0.15313578 0.14290525, 0.48679951 0.15349324 0.14291562, 0.48612371 0.15338759 0.14240159, 0.48636648 0.15377374 0.14235424, 0.48561171 0.15359068 0.14199589, 0.48579577 0.15400009 0.14190234, 0.48500583 0.15373282 0.14171134, 0.48512086 0.15415844 0.14158522, 0.48434159 0.15380608 0.14156507, 0.48438081 0.15424001 0.14142202, 0.48365748 0.15380612 0.14156498, 0.48361835 0.15424009 0.14142202, 0.48299325 0.15373287 0.14171149, 0.48287824 0.15415844 0.14158522, 0.48238748 0.15359063 0.1419958, 0.48220327 0.15399997 0.14190234, 0.48187536 0.15338762 0.14240159, 0.48163271 0.15377375 0.14235424, 0.48148671 0.15313578 0.14290525, 0.48119974 0.15349318 0.1429155, 0.48124424 0.15284975 0.14347742, 0.48092923 0.15317445 0.14355312, 0.49210453 0.12454322 0.1685289, 0.49208292 0.12390395 0.16829209, 0.49205953 0.12338129 0.16795598, 0.49203387 0.12294316 0.1675248, 0.49201661 0.12271431 0.16720863, 0.49247381 0.13686074 0.16308294, 0.49245414 0.13637058 0.16320907, 0.49247679 0.12650183 0.1625322, 0.49245593 0.12617028 0.16213332, 0.45584223 0.15574305 0.093429044, 0.45646402 0.15574305 0.094186857, 0.45646393 0.15644304 0.094186857, 0.45584223 0.15644303 0.093429312, 0.45538014 0.15574309 0.092564806, 0.45538005 0.15644321 0.092564985, 0.45509556 0.15574315 0.091626868, 0.45509556 0.15644309 0.091626868, 0.47353515 0.15574218 0.11125825, 0.47353515 0.15644214 0.11125825, 0.47415689 0.1557422 0.11201592, 0.47415689 0.15644215 0.11201592, 0.47461888 0.15644206 0.11288027, 0.47461888 0.155742 0.11288027, 0.47490343 0.15574206 0.11381809, 0.47490343 0.15644208 0.1138183, 0.47499952 0.15644191 0.11479391, 0.47499946 0.155742 0.11479367, 0.47499952 0.15644078 0.1345094, 0.47499946 0.15574081 0.13481613, 0.47499946 0.15641698 0.13481732, 0.47499952 0.15634601 0.13511793, 0.4749994 0.15622967 0.13540359, 0.47499952 0.13969542 0.16846772, 0.47499964 0.13838312 0.16952686, 0.47499964 0.13944168 0.16885673, 0.47499964 0.1390979 0.16918455, 0.47499958 0.13875301 0.16939332, 0.4731786 0.15706709 0.085192695, 0.47272637 0.15722559 0.084244624, 0.47303227 0.15722547 0.085253224, 0.47337148 0.15734455 0.08628796, 0.47266182 0.15741853 0.085406765, 0.47319576 0.15741852 0.086405411, 0.47285709 0.15734464 0.085325822, 0.47406366 0.15734446 0.087131426, 0.47328866 0.15687762 0.085147038, 0.47299853 0.15687761 0.084190413, 0.47288159 0.15706716 0.084213838, 0.47352916 0.15722547 0.086182639, 0.47419772 0.1572254 0.086997375, 0.47430971 0.15706711 0.086885586, 0.47335705 0.15666617 0.085118577, 0.47307095 0.15666619 0.084176019, 0.47366086 0.15706708 0.086094752, 0.47375974 0.15687755 0.086028561, 0.47439405 0.15687752 0.086801186, 0.47444627 0.15666617 0.086748943, 0.47382128 0.1566662 0.085987195, 0.47391424 0.1574184 0.087281212, 0.47233304 0.15741858 0.084323063, 0.47254029 0.15734462 0.084281638, 0.49151728 0.15666534 0.10381998, 0.491465 0.15687671 0.10387231, 0.49138078 0.1570662 0.10395671, 0.49126878 0.15722451 0.1040685, 0.49113485 0.15734364 0.10420261, 0.49098536 0.15741757 0.10435213, 0.4922711 0.15722451 0.10556866, 0.49253419 0.1572244 0.106436, 0.4926894 0.15706612 0.10640503, 0.49241737 0.15706606 0.10550798, 0.49214098 0.15741754 0.1065142, 0.49222204 0.15741755 0.10733782, 0.4924334 0.15734358 0.10733782, 0.49234816 0.15734354 0.10647283, 0.49197546 0.15706608 0.10468124, 0.4925274 0.15687659 0.1054623, 0.49207458 0.15687649 0.10461508, 0.49209598 0.15734358 0.10564111, 0.49184379 0.15722449 0.10476913, 0.49190065 0.15741761 0.10572208, 0.49168614 0.15734366 0.1048746, 0.49151048 0.15741752 0.10499214, 0.49287882 0.15666518 0.10636745, 0.49297449 0.1566651 0.10733767, 0.49280629 0.15687647 0.10638188, 0.49290052 0.15687649 0.10733782, 0.49259576 0.15666518 0.10543405, 0.49278137 0.157066 0.10733773, 0.492623 0.15722439 0.10733773, 0.492136 0.15666518 0.10457395, 0.49297449 0.15666355 0.13450934, 0.49290046 0.15687481 0.1345094, 0.49278137 0.15706439 0.1345094, 0.49262306 0.1572229 0.1345094, 0.4924334 0.15734193 0.1345094, 0.4922221 0.15741576 0.1345094, 0.49222198 0.15738048 0.13496728, 0.4922221 0.15727486 0.13541444, 0.49243352 0.15720448 0.13539179, 0.49243346 0.15730731 0.13495596, 0.4922221 0.15710166 0.13583989, 0.49297449 0.15655817 0.13518544, 0.49297461 0.15642884 0.13550322, 0.49290052 0.15675947 0.13524993, 0.49290052 0.15661785 0.13559799, 0.49297446 0.15663697 0.13485129, 0.49278137 0.15694013 0.1353076, 0.49278137 0.15678741 0.13568266, 0.49290052 0.15684585 0.13488407, 0.49262306 0.15709101 0.13535543, 0.49262306 0.15692909 0.13575344, 0.49278137 0.15703319 0.13491316, 0.4924334 0.15703556 0.13580675, 0.49262312 0.15718959 0.1349376, 0.4731169 0.087716892 0.075080767, 0.4731451 0.087871984 0.075016871, 0.49297455 0.14087689 0.16660281, 0.49290058 0.14106603 0.16669737, 0.49278146 0.14123556 0.1667821, 0.49262303 0.1413773 0.16685291, 0.49243352 0.1414838 0.16690619, 0.49222213 0.14154992 0.16693924, 0.4735333 0.088308245 0.076045677, 0.47332129 0.088069782 0.075567976, 0.47388002 0.088662684 0.076643392, 0.47351965 0.088146076 0.076132134, 0.47387189 0.088469774 0.076777592, 0.47329733 0.087909043 0.075636819, 0.47347537 0.087995082 0.076228455, 0.47381583 0.088298991 0.07692869, 0.47324476 0.087758541 0.075712517, 0.47345069 0.087941796 0.076267079, 0.47321764 0.087704986 0.075742975, 0.47341201 0.08787556 0.076318726, 0.47316632 0.087895721 0.075096115, 0.47319224 0.087924749 0.075187132, 0.47313496 0.087735862 0.075147375, 0.47316197 0.087764934 0.07524164, 0.47307646 0.087585762 0.075203136, 0.47304747 0.087531954 0.075225189, 0.47310463 0.087614566 0.075301245, 0.4730759 0.087560862 0.075324878, 0.47303253 0.087493539 0.075356737, 0.47300157 0.087452829 0.075377181, 0.47317609 0.087638035 0.075783327, 0.49290782 0.14029746 0.16757976, 0.49278966 0.14088421 0.16729663, 0.49279776 0.14040542 0.16772838, 0.49290425 0.14074126 0.16717683, 0.49249265 0.13993581 0.16828959, 0.49247479 0.14056811 0.16795324, 0.49227592 0.14061581 0.16801892, 0.49229896 0.13996693 0.16836764, 0.49297628 0.14017817 0.16741465, 0.49297541 0.14058253 0.16704322, 0.49266347 0.1398906 0.16817589, 0.4926514 0.14049694 0.16785489, 0.49231389 0.13941976 0.16852139, 0.49235541 0.1388739 0.16855846, 0.4928048 0.13983338 0.16803215, 0.49250379 0.13940388 0.16843747, 0.4925684 0.13887404 0.16844605, 0.49291098 0.13976637 0.16786374, 0.4926711 0.13938114 0.16831683, 0.49274859 0.13887398 0.16828631, 0.49297699 0.13969229 0.16767748, 0.49280927 0.13935265 0.16816543, 0.49288532 0.13887399 0.16808812, 0.49291295 0.13931933 0.16798885, 0.49297071 0.1388739 0.16786282, 0.49297753 0.13928267 0.16779421, 0.49224934 0.14115615 0.16752525, 0.49245456 0.14109661 0.16747548, 0.4926374 0.14100459 0.16739796, 0.49219945 0.10698071 0.10411368, 0.49219128 0.10678788 0.10424756, 0.49213529 0.10661708 0.10439895, 0.49297068 0.12526542 0.16786195, 0.49288532 0.12526551 0.16808729, 0.49274865 0.12526542 0.16828556, 0.49256858 0.12526536 0.16844545, 0.49235532 0.12526554 0.16855757, 0.49283132 0.10730119 0.10677837, 0.49275246 0.10722362 0.10594784, 0.49284074 0.10739627 0.1058961, 0.49292377 0.10747409 0.10677837, 0.4928923 0.10758461 0.10584877, 0.49298066 0.10766171 0.10677837, 0.49251583 0.10699101 0.10513987, 0.49259219 0.10716331 0.10503711, 0.49262699 0.10735358 0.10494389, 0.49280331 0.12410845 0.16794537, 0.49280831 0.1246416 0.16813384, 0.49266937 0.12460428 0.16828386, 0.49266055 0.12403928 0.16808461, 0.49247333 0.12347673 0.16788153, 0.49248829 0.12398501 0.16819383, 0.49229333 0.1239479 0.16826828, 0.49227378 0.12342665 0.16794486, 0.49291024 0.12418947 0.16778277, 0.49291259 0.12468494 0.1679595, 0.49265039 0.12355193 0.16778611, 0.49297693 0.12427914 0.16760252, 0.49297753 0.12473299 0.16776679, 0.49225131 0.12296808 0.16750406, 0.49279729 0.1236486 0.16766356, 0.49245593 0.1230282 0.16745467, 0.49290773 0.12376262 0.16751884, 0.49223664 0.12273853 0.16719343, 0.49222228 0.12255545 0.16686521, 0.49263853 0.12312123 0.16737805, 0.49297628 0.12388919 0.16735883, 0.49244475 0.12280294 0.16715299, 0.49243364 0.12262248 0.16683386, 0.49279052 0.12324232 0.16727807, 0.49263093 0.12290432 0.16708918, 0.49262333 0.1227304 0.16678344, 0.49231043 0.12455401 0.16848551, 0.49290466 0.12338617 0.16715939, 0.49250147 0.12457463 0.16840272, 0.49278614 0.12303789 0.16700514, 0.49278161 0.12287386 0.16671668, 0.49297559 0.12354603 0.16702746, 0.49290264 0.12319711 0.16690527, 0.49290064 0.12304582 0.16663645, 0.49297509 0.1233743 0.16679381, 0.49297479 0.12323736 0.16654716, 0.49298066 0.10766028 0.13302873, 0.49292371 0.10747263 0.13302873, 0.49283126 0.1072997 0.13302873, 0.49297476 0.10765366 0.13312276, 0.49290076 0.10746212 0.13321222, 0.49278173 0.10729024 0.13329206, 0.49262327 0.10714675 0.13335912, 0.49243376 0.10703872 0.13340946, 0.49222228 0.10697176 0.13344069, 0.47114214 0.096285462 0.11064477, 0.471053 0.096128494 0.11049719, 0.47097376 0.095936969 0.11039062, 0.47090897 0.095721185 0.11033039, 0.47105467 0.095524132 0.11023445, 0.41262308 0.037023827 0.1338311, 0.47123161 0.095544294 0.11013876, 0.41264847 0.036848709 0.13377638, 0.47142848 0.095552847 0.1100042, 0.47154835 0.095546022 0.10989712, 0.4126454 0.036572397 0.13365145, 0.47164187 0.095527649 0.10978766, 0.47170749 0.095498919 0.10967813, 0.49256197 0.10703699 0.13314815, 0.49219981 0.10693482 0.13336475, 0.49239013 0.10696474 0.13326199, 0.49256977 0.10708663 0.13331933, 0.47162828 0.095869884 0.11006422, 0.4716506 0.095696732 0.10990702, 0.47176877 0.095828235 0.10993837, 0.47226796 0.095768049 0.10952078, 0.47210023 0.095803022 0.10967849, 0.47207442 0.095698133 0.10951875, 0.47225329 0.095862046 0.10970651, 0.4718996 0.09593828 0.10998972, 0.47204062 0.096024439 0.1100602, 0.47195667 0.095722064 0.10966431, 0.47189775 0.095594049 0.1095358, 0.47182494 0.095620513 0.10966392, 0.47162363 0.096184313 0.11041401, 0.47150612 0.096061811 0.11029907, 0.47188208 0.096098125 0.11022244, 0.47139898 0.095910594 0.11021312, 0.47175002 0.095996872 0.11013196, 0.47130635 0.095736086 0.11015864, 0.47151998 0.095720798 0.11002083, 0.47535232 0.089829132 0.096240953, 0.47518054 0.089756802 0.096354708, 0.4749901 0.089727089 0.096457168, 0.47464934 0.089393035 0.095878199, 0.47456738 0.089233935 0.095639035, 0.47448036 0.089091033 0.095473453, 0.47439209 0.088969588 0.095385686, 0.474354 0.088923976 0.095370844, 0.47443005 0.08901915 0.095413968, 0.47431591 0.088882461 0.095369652, 0.4743996 0.088874757 0.095168725, 0.47442976 0.088948637 0.095283523, 0.47438082 0.088895455 0.095270708, 0.47445926 0.088936418 0.095179424, 0.47448066 0.088932559 0.095072761, 0.47462454 0.089078128 0.095132992, 0.47458103 0.089065224 0.095243618, 0.47434178 0.088815987 0.095172241, 0.47428694 0.088785306 0.095254853, 0.47428086 0.088737994 0.095122918, 0.47433284 0.088845327 0.095271721, 0.4744105 0.088862032 0.095064536, 0.47434267 0.088793859 0.095070347, 0.47477242 0.089382589 0.095754579, 0.47489032 0.089408755 0.095645502, 0.47499463 0.089456961 0.095529661, 0.47465125 0.089216143 0.095509812, 0.47473481 0.089232877 0.095400438, 0.47480741 0.089264572 0.095286474, 0.4745287 0.08906287 0.095350817, 0.41255656 0.027011439 0.12005819, 0.41255665 0.027052879 0.12019242, 0.47529051 0.1262265 0.17068119, 0.47524992 0.12622657 0.17068385, 0.47524968 0.13461436 0.17068435, 0.47529033 0.13461435 0.17068176, 0.47604033 0.13789161 0.17058744, 0.47608092 0.13789161 0.1705849, 0.47549698 0.138106 0.17044447, 0.47564501 0.13811122 0.17051484, 0.475914 0.14020817 0.16949229, 0.47599164 0.14021102 0.16949458, 0.47581115 0.13859478 0.17048551, 0.47581884 0.13826866 0.17054765, 0.47599143 0.1382706 0.17056368, 0.47598287 0.13859895 0.17050274, 0.47535381 0.1395563 0.16979475, 0.47536322 0.13908449 0.1700895, 0.47547904 0.13912001 0.17016371, 0.47546661 0.13960598 0.16986082, 0.47502705 0.13885289 0.16960312, 0.47549489 0.13825341 0.17042814, 0.47564241 0.13826242 0.17049842, 0.47502765 0.13841845 0.16975968, 0.47511104 0.13847132 0.16997667, 0.47510859 0.13894804 0.16980286, 0.4757506 0.14018677 0.16947444, 0.47577533 0.13968302 0.16996358, 0.47577718 0.14056739 0.16890375, 0.47556579 0.14050119 0.16887079, 0.47537541 0.138243 0.17034678, 0.47526976 0.13813737 0.17026006, 0.47537699 0.13809976 0.17036261, 0.47563627 0.13858292 0.17043628, 0.47523412 0.13948424 0.16969882, 0.47524032 0.13903266 0.16998042, 0.47604388 0.13918237 0.17029496, 0.47606364 0.13859844 0.17050092, 0.47558638 0.14014228 0.16943736, 0.47560671 0.13965006 0.16991939, 0.47548994 0.13856621 0.17036711, 0.47510579 0.13936718 0.16954289, 0.47524837 0.13822764 0.17022668, 0.47513148 0.13820697 0.17006446, 0.47545061 0.14008471 0.16938962, 0.47537616 0.14039466 0.16881727, 0.47596392 0.13918251 0.17029546, 0.47537163 0.13854674 0.17028736, 0.47534153 0.14002086 0.16933678, 0.47521785 0.14025308 0.16874664, 0.47579435 0.13917366 0.17027675, 0.47502646 0.13923582 0.16936813, 0.47522601 0.13992913 0.16926084, 0.47524595 0.13851814 0.17016985, 0.47510234 0.13978098 0.16913809, 0.47509864 0.14008351 0.16866173, 0.47562233 0.13915099 0.17022918, 0.47502553 0.13961552 0.16900076, 0.47502485 0.1398944 0.16856723, 0.47503534 0.13829091 0.16981752, 0.47594222 0.13969734 0.16998272, 0.47607628 0.13811579 0.1705768, 0.47599503 0.13811608 0.17057966, 0.47607258 0.1382703 0.17056106, 0.47582182 0.1381149 0.17056383, 0.47502473 0.15642872 0.13550322, 0.47509858 0.15661779 0.13559799, 0.47521764 0.15678732 0.13568266, 0.47537604 0.15692897 0.13575347, 0.4755657 0.15703548 0.13580684, 0.475777 0.15710166 0.13583989, 0.475777 0.15727481 0.13541444, 0.47577706 0.15738031 0.13496728, 0.4755657 0.15730716 0.13495596, 0.4755657 0.15720429 0.13539203, 0.47502461 0.15663688 0.13485153, 0.47502461 0.15666334 0.1345094, 0.47509864 0.15684566 0.13488407, 0.47509852 0.15687475 0.1345094, 0.47502461 0.15655795 0.13518544, 0.47521773 0.15703313 0.13491316, 0.47521773 0.15706429 0.1345094, 0.47509858 0.15675941 0.13524981, 0.47537604 0.15718944 0.1349376, 0.47537613 0.15722267 0.1345094, 0.47521761 0.15694 0.1353076, 0.4755657 0.15734181 0.1345094, 0.4753761 0.15709083 0.13535561, 0.475777 0.15741578 0.1345094, 0.47502467 0.15666452 0.11479391, 0.47509849 0.15687591 0.11479367, 0.47521773 0.15706553 0.11479391, 0.47537604 0.15722379 0.11479391, 0.4755657 0.15734304 0.11479391, 0.475777 0.15741691 0.11479391, 0.47482046 0.15706554 0.11279683, 0.47527269 0.15722398 0.11374481, 0.47496673 0.1572239 0.11273624, 0.47462758 0.15734318 0.11170121, 0.47408482 0.15741713 0.11070843, 0.47393537 0.15734319 0.1108578, 0.4748033 0.15741715 0.1115839, 0.47533718 0.15741695 0.11258282, 0.47514203 0.15734306 0.1126637, 0.47471038 0.156876 0.1128424, 0.47500059 0.15687594 0.11379908, 0.4751175 0.15706544 0.11377575, 0.47446999 0.157224 0.11180665, 0.47380126 0.15722404 0.11099179, 0.47464207 0.15666457 0.11287053, 0.47492805 0.15666468 0.11381342, 0.47433826 0.1570657 0.11189483, 0.47368941 0.1570657 0.11110388, 0.4742392 0.15687612 0.11196084, 0.47360513 0.15687604 0.11118813, 0.47417763 0.1566648 0.11200188, 0.47355285 0.1566647 0.11124037, 0.47566602 0.15741695 0.11366652, 0.47545865 0.15734294 0.11370774, 0.45648178 0.15666553 0.094169244, 0.456534 0.15687692 0.09411715, 0.45661828 0.15706643 0.094032839, 0.45673028 0.15722492 0.093920872, 0.45686433 0.15734401 0.093786791, 0.45701376 0.15741798 0.093637332, 0.45572791 0.15722504 0.092420921, 0.45546487 0.15722497 0.091553792, 0.4553096 0.15706661 0.091584489, 0.45558169 0.15706661 0.092481539, 0.45585811 0.15741812 0.091475412, 0.45565084 0.15734407 0.091516539, 0.45602348 0.15706661 0.093308434, 0.45547166 0.15687698 0.092527106, 0.45592448 0.15687701 0.093374357, 0.45590314 0.15734406 0.092348412, 0.45615512 0.157225 0.0932201, 0.45609838 0.157418 0.092267498, 0.45631287 0.15734403 0.093114927, 0.45648864 0.15741803 0.092997536, 0.45512012 0.1566657 0.09162198, 0.45519277 0.15687701 0.091607556, 0.45540324 0.15666568 0.09255527, 0.45586303 0.15666559 0.093415424, 0.4738442 0.11701149 0.076583102, 0.47263512 0.11797914 0.074884638, 0.47279331 0.11785598 0.074844435, 0.47292295 0.11770238 0.074807659, 0.47301897 0.11752491 0.074776009, 0.47307703 0.11733048 0.074750379, 0.47296801 0.11785805 0.075974211, 0.47350326 0.11766322 0.076967701, 0.47311649 0.11773612 0.07589443, 0.47363582 0.11754371 0.076850459, 0.47323641 0.11758271 0.075821832, 0.47373971 0.11739035 0.076744214, 0.47381034 0.11721018 0.076653853, 0.4733226 0.11740422 0.075759366, 0.47337139 0.11720817 0.075709686, 0.48826647 0.11232412 0.099116966, 0.48840755 0.11220266 0.099008575, 0.48852387 0.11204174 0.098911896, 0.48860618 0.11185192 0.098833874, 0.48865011 0.11164722 0.098780349, 0.49151275 0.11241758 0.10443579, 0.49168861 0.11234364 0.1043186, 0.49184629 0.11222446 0.10421334, 0.49197808 0.11206615 0.10412548, 0.49207714 0.11187653 0.10405947, 0.49213874 0.11166516 0.10401835, 0.49297476 0.11166504 0.10677849, 0.49190184 0.11241758 0.10516499, 0.49209708 0.11234358 0.10508431, 0.4921414 0.11241752 0.10595618, 0.49222246 0.11241747 0.10677849, 0.49227238 0.11222449 0.10501193, 0.49234876 0.11234356 0.10591485, 0.49243373 0.11234352 0.10677849, 0.49241874 0.11206621 0.10495125, 0.49253476 0.11222443 0.10587786, 0.4926233 0.1122244 0.10677849, 0.49252883 0.11187655 0.10490571, 0.49269012 0.11206602 0.10584711, 0.49278173 0.11206597 0.10677849, 0.49259722 0.1116651 0.10487758, 0.49280694 0.11187637 0.10582389, 0.49290076 0.11187643 0.10677849, 0.49287945 0.1116651 0.10580944, 0.49297476 0.11166361 0.13089626, 0.49290088 0.11187501 0.13089626, 0.49278161 0.1120647 0.13089626, 0.49262333 0.112223 0.13089626, 0.49243367 0.11234215 0.13089629, 0.49222231 0.11241618 0.13089626, 0.49261555 0.11286956 0.13396056, 0.49277702 0.1127257 0.13402756, 0.49298254 0.11194322 0.13319357, 0.49297413 0.11235929 0.13419835, 0.49293289 0.11211123 0.13314502, 0.49289861 0.11255273 0.13410835, 0.49285349 0.11226578 0.13310058, 0.49272096 0.11243114 0.13305302, 0.49252218 0.11258483 0.13300879, 0.49297878 0.11172447 0.13206117, 0.49291742 0.11191592 0.13203485, 0.49281934 0.11209005 0.13201101, 0.49265584 0.11227001 0.13198636, 0.49241579 0.11242315 0.13196523, 0.49261546 0.12581156 0.16171859, 0.4927769 0.12566772 0.16178559, 0.49289855 0.12549466 0.16186632, 0.49297407 0.12530118 0.16195653, 0.49297684 0.12604365 0.16301452, 0.49290898 0.12618364 0.16286717, 0.49279955 0.12631044 0.1627339, 0.49265349 0.12641807 0.16262053, 0.49285302 0.12587087 0.16234721, 0.49261537 0.13585651 0.16335724, 0.49277678 0.13585645 0.16351591, 0.49289843 0.13585646 0.163707, 0.49297401 0.13585658 0.16392027, 0.49297664 0.13709877 0.16370521, 0.49290827 0.13702594 0.16351472, 0.49279824 0.13696001 0.16334258, 0.49265137 0.13690419 0.16319631, 0.4928526 0.13643613 0.16357087, 0.49261531 0.15197855 0.1346242, 0.49277666 0.15212056 0.13469522, 0.49289837 0.15229137 0.13478048, 0.49297395 0.15248229 0.13487597, 0.49297452 0.15321876 0.13159283, 0.49222207 0.15246627 0.13159283, 0.49297854 0.15315314 0.13275523, 0.49290055 0.15300736 0.13159283, 0.49291721 0.15296189 0.13272743, 0.49281916 0.15278807 0.13270225, 0.49262294 0.15265936 0.13159283, 0.49278146 0.15281762 0.13159283, 0.49265581 0.15260831 0.13267578, 0.49243346 0.15254016 0.13159283, 0.49241588 0.1524553 0.13265346, 0.49280751 0.15263006 0.13341887, 0.4928036 0.15252835 0.13376279, 0.49284038 0.15246737 0.13411112, 0.49297449 0.15322004 0.10733758, 0.49290052 0.15300873 0.10733758, 0.4927814 0.15281913 0.10733758, 0.49262303 0.15266076 0.10733758, 0.49243346 0.15254164 0.10733758, 0.4922221 0.15246758 0.10733767, 0.49241731 0.15281916 0.10550772, 0.49268946 0.15281905 0.10640465, 0.49253419 0.15266071 0.10643564, 0.49287882 0.15322004 0.10636701, 0.49280638 0.15300867 0.10638152, 0.49184382 0.15266076 0.10476898, 0.4911347 0.15254173 0.10420237, 0.49126887 0.15266082 0.10406841, 0.49168614 0.15254173 0.10487436, 0.49227104 0.15266088 0.10556807, 0.49209586 0.15254164 0.10564075, 0.49252746 0.15300874 0.10546206, 0.49197555 0.1528191 0.104681, 0.49138081 0.15281911 0.10395648, 0.49259579 0.15322015 0.10543372, 0.49207461 0.15300879 0.10461484, 0.49146503 0.15300891 0.10387208, 0.49213597 0.15322015 0.10457359, 0.49151736 0.1532203 0.10381983, 0.4909853 0.15246776 0.10435183, 0.49214104 0.15246759 0.10651384, 0.49234828 0.15254161 0.10647263, 0.49190062 0.15246776 0.10572158, 0.49151051 0.15246774 0.10499157, 0.48820165 0.15251175 0.10136677, 0.48834434 0.15262473 0.10121228, 0.48846439 0.15278977 0.10107471, 0.4885501 0.1529943 0.10096721, 0.48859546 0.15321887 0.1008984, 0.47411999 0.14951894 0.087269887, 0.47425446 0.14963187 0.087111339, 0.47436121 0.14978966 0.086971149, 0.47443408 0.14998393 0.086856946, 0.47446898 0.15020324 0.086775526, 0.47328213 0.14933959 0.086216524, 0.47344598 0.14945509 0.086100563, 0.47358009 0.14961369 0.085997328, 0.4736771 0.14980642 0.08591257, 0.47373167 0.15002295 0.085850433, 0.4727045 0.14921601 0.084972635, 0.47288808 0.14933345 0.084904775, 0.47304052 0.14949211 0.084844694, 0.47315413 0.14968356 0.084794894, 0.47249237 0.14917055 0.084086642, 0.47322282 0.14989795 0.084757969, 0.47268289 0.14928868 0.084052816, 0.47284219 0.1494474 0.084022895, 0.47296184 0.14963841 0.083997712, 0.47303569 0.14985207 0.083979145, 0.41252157 -0.026083127 0.089308247, 0.46267992 0.076830477 0.08937858, 0.41251561 -0.025874004 0.089453444, 0.41681322 0.037644699 0.12746377, 0.41678658 0.037647486 0.12740467, 0.41675207 0.037660375 0.12735106, 0.41671118 0.037682906 0.12730588, 0.41666609 0.037713826 0.12727092, 0.41827092 0.035082772 0.12076761, 0.41831943 0.035031766 0.1207618, 0.41836259 0.034979999 0.12074022, 0.41839769 0.034930319 0.12070419, 0.41842291 0.034885436 0.12065558, 0.41942745 0.035956547 0.12036277, 0.41941592 0.035968319 0.12038855, 0.4193874 0.03599596 0.12043442, 0.41935292 0.036027536 0.12047051, 0.41932338 0.036053777 0.12049116, 0.41929114 0.036081642 0.12050591, 0.41925636 0.036111102 0.12051453, 0.41995668 0.036634356 0.12036337, 0.41994387 0.036641479 0.12038697, 0.41991368 0.036659494 0.12042974, 0.4198792 0.036681414 0.12046398, 0.41985047 0.036700398 0.12048484, 0.41981941 0.036721528 0.12050129, 0.41978604 0.036744744 0.12051274, 0.42052856 0.037492052 0.12054409, 0.42051449 0.037493557 0.12056439, 0.42048287 0.037500009 0.12060083, 0.42044851 0.037510157 0.12063168, 0.42042032 0.037520409 0.1206509, 0.4203904 0.037532851 0.12066676, 0.42035845 0.037547603 0.12067939, 0.42074826 0.03804034 0.12085424, 0.42072055 0.038045049 0.1208715, 0.4206911 0.038051888 0.12088598, 0.4206599 0.038061127 0.12089755, 0.42093173 0.038436368 0.12109317, 0.42090425 0.03843689 0.12110795, 0.42087528 0.038439661 0.12112038, 0.42084435 0.038444802 0.12113078, 0.42114952 0.038842887 0.12134437, 0.42113402 0.038835675 0.12135665, 0.42110121 0.038824305 0.12137891, 0.42106679 0.038816959 0.12139739, 0.42103937 0.03881368 0.12140895, 0.42101058 0.038812459 0.12141906, 0.42097995 0.038813621 0.12142695, 0.42122793 0.039248124 0.12178321, 0.42121229 0.039238185 0.12179233, 0.42117921 0.039221272 0.12180783, 0.42114475 0.03920868 0.12182023, 0.42111751 0.039201424 0.12182786, 0.42108878 0.039196387 0.12183391, 0.42105833 0.039193541 0.12183814, 0.42120889 0.039611459 0.12234117, 0.42119339 0.039598718 0.12234591, 0.42116025 0.03957656 0.12235345, 0.42112586 0.039558992 0.12235843, 0.42109856 0.039548323 0.12236072, 0.42106977 0.039539918 0.12236135, 0.42103931 0.039533973 0.12236072, 0.4210768 0.039872572 0.12296008, 0.42106155 0.039857313 0.12296046, 0.4210287 0.0398307 0.12295963, 0.42099437 0.039809391 0.12295641, 0.42096683 0.039796367 0.12295245, 0.42093793 0.039785832 0.12294747, 0.42090726 0.039778069 0.12294091, 0.42083704 0.04001835 0.1236117, 0.42082223 0.040001243 0.12360756, 0.42078993 0.039971322 0.12359737, 0.42075545 0.03994742 0.12358548, 0.42072782 0.039933011 0.12357523, 0.42069837 0.039921805 0.1235639, 0.42066714 0.039913893 0.12355112, 0.42050549 0.04004769 0.12426434, 0.42049143 0.040029109 0.1242554, 0.4204599 0.039996862 0.12423612, 0.4204255 0.039971828 0.12421535, 0.42039743 0.039957285 0.12419866, 0.42036739 0.039946511 0.12418102, 0.42033526 0.039940104 0.12416233, 0.41985404 0.039832041 0.12504338, 0.41982517 0.039819166 0.1250179, 0.41979408 0.039811373 0.12499203, 0.41976061 0.039809167 0.12496613, 0.41906258 0.039463609 0.12606837, 0.41903505 0.03943114 0.12602006, 0.41900072 0.039410263 0.12597202, 0.41897067 0.039402202 0.12593617, 0.41893756 0.039401039 0.12590171, 0.41890177 0.039406955 0.12586878, 0.41834667 0.038992405 0.12672196, 0.41833851 0.038973227 0.12669323, 0.41831371 0.038943946 0.12663291, 0.4182795 0.038928345 0.12657391, 0.41824833 0.038925707 0.12653114, 0.41821304 0.038931504 0.12649117, 0.41817477 0.038945481 0.12645517, 0.41752622 0.038323924 0.12727146, 0.41752121 0.038306862 0.12723644, 0.41750017 0.038283348 0.12716331, 0.41746634 0.038276061 0.127093, 0.41743341 0.038281202 0.12704371, 0.41739544 0.038295761 0.12700011, 0.41735384 0.038319036 0.12696348, 0.4129706 0.036864653 0.12228443, 0.41297063 0.037263572 0.12243561, 0.41293481 0.037237078 0.12248604, 0.41299278 0.038260981 0.1242236, 0.41299278 0.038155109 0.12465285, 0.41293481 0.036851034 0.12233938, 0.41293478 0.036441162 0.12228976, 0.4129706 0.038095847 0.12463032, 0.4129706 0.038198009 0.12421618, 0.41299269 0.037292853 0.12562607, 0.41299281 0.036879659 0.12578286, 0.4129706 0.038198009 0.12378956, 0.41293481 0.038141549 0.12420918, 0.41293469 0.038141474 0.12379648, 0.41299278 0.036879912 0.12222271, 0.41299278 0.036441162 0.12216936, 0.41297063 0.0368644 0.12572117, 0.41297057 0.037263349 0.12556992, 0.4129706 0.036441162 0.12223281, 0.41297057 0.037614509 0.12532745, 0.41293481 0.037236974 0.12551941, 0.41293481 0.03757681 0.1252849, 0.41299278 0.037293032 0.12237944, 0.41270024 0.036823764 0.1255561, 0.4127669 0.036440983 0.12561022, 0.41270027 0.036440909 0.12560274, 0.41293481 0.038042754 0.12339519, 0.41288731 0.038094372 0.12380184, 0.41293481 0.037850797 0.1249759, 0.41288739 0.037545294 0.12524937, 0.41288728 0.037998274 0.12341203, 0.41288739 0.037811711 0.12305664, 0.41283038 0.03796488 0.12342475, 0.41288736 0.037811682 0.12494887, 0.41288731 0.037998274 0.12459315, 0.4128305 0.037782237 0.12492858, 0.41276699 0.036825582 0.12556361, 0.41283044 0.037782297 0.12307705, 0.41283047 0.037521839 0.12278284, 0.41276702 0.037764058 0.12308942, 0.41283047 0.037964806 0.12458061, 0.41276702 0.037507027 0.12279962, 0.41283038 0.036830872 0.12558518, 0.41283041 0.036440939 0.12563239, 0.41283047 0.038058877 0.12419902, 0.41276699 0.037944153 0.12457274, 0.41276699 0.038036883 0.12419654, 0.41276702 0.037187919 0.12542616, 0.41270027 0.037184477 0.12541939, 0.41276702 0.037188172 0.12257935, 0.41270024 0.03750208 0.12280501, 0.41270036 0.037184641 0.12258603, 0.41276699 0.038036883 0.12380908, 0.41270038 0.038029328 0.12419571, 0.41270033 0.038029313 0.12380992, 0.41299275 0.038260937 0.12378182, 0.41299269 0.037656501 0.12537505, 0.41288731 0.03683944 0.12561987, 0.41293469 0.036440954 0.12571551, 0.41288731 0.036440909 0.12566794, 0.4129706 0.038095936 0.12337519, 0.41297063 0.037897587 0.12500812, 0.41283038 0.037198305 0.12544574, 0.41276699 0.037506834 0.12520601, 0.41270027 0.037501827 0.12520041, 0.41293481 0.038042665 0.12461017, 0.41293478 0.037850812 0.12302969, 0.41288731 0.038094372 0.12420346, 0.41288736 0.037545532 0.12275629, 0.41293481 0.036850825 0.12566592, 0.41283038 0.037198484 0.12255956, 0.41283047 0.038058877 0.12380634, 0.41288733 0.03721489 0.12547754, 0.41276711 0.036825791 0.12244199, 0.41270027 0.036823973 0.12244929, 0.41270027 0.036441073 0.12240268, 0.4127669 0.037944153 0.12343262, 0.41270027 0.03793703 0.12343536, 0.41276702 0.036441073 0.12239517, 0.41283038 0.037521541 0.12522255, 0.41299278 0.038155109 0.12335287, 0.41299269 0.037949756 0.125044, 0.41276702 0.037763983 0.12491597, 0.41270027 0.037757754 0.12491162, 0.41297063 0.037897587 0.1229973, 0.41297045 0.036440909 0.12577258, 0.41293481 0.037576929 0.12272052, 0.41288731 0.037215054 0.12252803, 0.4128305 0.036831096 0.1224203, 0.41283047 0.036441088 0.12237285, 0.41299269 0.037949756 0.12296139, 0.41270027 0.037757844 0.12309374, 0.41297051 0.037614748 0.12267803, 0.41270027 0.03793703 0.12457012, 0.41299266 0.036440939 0.12583594, 0.41288731 0.036839664 0.12238549, 0.41288733 0.036441073 0.12233712, 0.41299275 0.037656829 0.12263061, 0.41100031 0.036441088 0.12240283, 0.41100031 0.036823988 0.12244906, 0.41100022 0.037184685 0.12258579, 0.41100022 0.03750211 0.1228051, 0.41100028 0.037757739 0.12309374, 0.41100016 0.037937135 0.12343536, 0.41100016 0.038029432 0.12380992, 0.41100016 0.038029432 0.12419571, 0.41100028 0.037937015 0.12457012, 0.41100016 0.037757844 0.12491162, 0.41100025 0.037501991 0.12520041, 0.41100028 0.037184462 0.12541939, 0.41100019 0.036823794 0.1255561, 0.41100022 0.036440894 0.12560274, 0.41100022 0.034440964 0.12560247, 0.41270038 0.034440786 0.12560247, 0.41100031 0.03405799 0.12555598, 0.4127003 0.034057975 0.12555598, 0.41100028 0.033697367 0.12541912, 0.41270038 0.033697277 0.12541924, 0.41100031 0.033379808 0.12520005, 0.41270038 0.033379853 0.12520014, 0.41100034 0.033124283 0.12491129, 0.41270047 0.033124194 0.12491144, 0.41100022 0.032945007 0.12456988, 0.4127003 0.032944992 0.12456979, 0.41100025 0.032852769 0.12419544, 0.41270038 0.032852679 0.12419535, 0.41100025 0.032852769 0.12380956, 0.41270038 0.032852679 0.12380971, 0.41100022 0.032945096 0.12343504, 0.4127003 0.032944992 0.12343504, 0.41100031 0.033124313 0.12309359, 0.4127003 0.033124283 0.12309359, 0.41100022 0.033380121 0.12280478, 0.41270024 0.033380166 0.12280478, 0.41100025 0.033697531 0.12258579, 0.41270027 0.033697605 0.12258564, 0.41100025 0.034058213 0.12244906, 0.41270027 0.034058183 0.12244894, 0.41100022 0.034441158 0.12240256, 0.41270033 0.034441054 0.12240268, 0.41299278 0.034441113 0.12216936, 0.41297048 0.034441173 0.12223266, 0.41293493 0.034441084 0.12228955, 0.41288739 0.034441099 0.12233712, 0.41283041 0.034441099 0.12237276, 0.41276702 0.034441084 0.12239517, 0.41299281 0.034440964 0.12583579, 0.41297075 0.03444083 0.12577222, 0.41293493 0.034440875 0.12571524, 0.41288739 0.03444089 0.12566791, 0.4128305 0.034440875 0.1256323, 0.41276714 0.034440875 0.1256101, 0.41299292 0.034002125 0.12578259, 0.41297063 0.034017295 0.12572087, 0.41299278 0.033589169 0.12237929, 0.41297063 0.034017533 0.12228422, 0.41297063 0.033618629 0.12243523, 0.41299284 0.033588961 0.12562574, 0.41297057 0.033618391 0.12556969, 0.41297057 0.032684132 0.12421586, 0.41297057 0.032684132 0.12378918, 0.41293481 0.032740608 0.12379597, 0.41297063 0.033267498 0.12267782, 0.41293487 0.033645034 0.12248568, 0.41293493 0.032740533 0.12420879, 0.41293469 0.033305228 0.12272047, 0.41293481 0.032839417 0.12460984, 0.41288731 0.032787725 0.12420319, 0.41288748 0.032883734 0.12459315, 0.41293484 0.033031359 0.12302949, 0.41288733 0.033336714 0.12275593, 0.41288748 0.033070385 0.12305655, 0.41288731 0.033070356 0.12494861, 0.41283032 0.032917291 0.12458025, 0.41276705 0.03405641 0.12244178, 0.41288748 0.032883734 0.12341191, 0.4128305 0.0330998 0.12307678, 0.41283044 0.032917261 0.12342454, 0.4128305 0.0330998 0.12492813, 0.41283041 0.034051165 0.1224203, 0.4128305 0.033360183 0.12522222, 0.41276702 0.033118039 0.12491547, 0.41276714 0.033374906 0.12520562, 0.41283047 0.03282319 0.12380601, 0.41276714 0.032937914 0.12343241, 0.41276702 0.032845303 0.12380876, 0.41276714 0.03369385 0.12542595, 0.41276705 0.033694074 0.1225792, 0.41276714 0.032845214 0.12419628, 0.41299281 0.03262122 0.12422334, 0.41299281 0.03262122 0.12378143, 0.41288731 0.034042537 0.12238549, 0.41299269 0.033225447 0.12263037, 0.41297063 0.03278625 0.12462999, 0.41297063 0.032984525 0.12299715, 0.41283047 0.033683792 0.12255935, 0.41293481 0.033031315 0.12497558, 0.41293493 0.032839388 0.12339507, 0.41276708 0.033375114 0.12279929, 0.41288739 0.033336475 0.12524904, 0.41288731 0.032787725 0.12380172, 0.41293481 0.034031123 0.12233938, 0.4128305 0.033683449 0.12544535, 0.41283047 0.03282319 0.12419881, 0.41288742 0.033667132 0.12252785, 0.41276705 0.034056231 0.12556328, 0.41276714 0.032937914 0.12457241, 0.41299281 0.032726929 0.1246524, 0.41283044 0.033360392 0.1227826, 0.41299281 0.032932356 0.12296106, 0.4127669 0.033118099 0.12308918, 0.41297063 0.03278625 0.12337483, 0.41297075 0.032984406 0.12500773, 0.41293484 0.033305049 0.12528454, 0.41288748 0.033666849 0.12547742, 0.4128305 0.034050852 0.12558486, 0.41299281 0.032932356 0.12504376, 0.41297051 0.033267289 0.12532701, 0.41299281 0.032726929 0.12335242, 0.41299269 0.034002423 0.12222256, 0.41293484 0.03364484 0.12551926, 0.41288733 0.034042254 0.12561966, 0.41299292 0.033225149 0.12537466, 0.41293487 0.034030885 0.12566577, 0.41678336 -0.023676947 0.043773398, 0.41675523 -0.023108065 0.044036523, 0.41676345 -0.023667306 0.043836847, 0.41702011 -0.022742078 0.050411686, 0.41696349 -0.022717923 0.050398603, 0.41712239 -0.022775769 0.050472394, 0.41719738 -0.022786662 0.050569728, 0.41735893 -0.022096127 0.050170377, 0.41737288 -0.021949679 0.050085977, 0.41745737 -0.022114083 0.050229535, 0.41753247 -0.022106335 0.050316826, 0.41770321 -0.021627784 0.049935117, 0.41771603 -0.021305621 0.049608007, 0.41777831 -0.021606922 0.050012365, 0.41678342 -0.023677498 0.05073978, 0.41676351 -0.023667812 0.05067654, 0.41793847 -0.021162018 0.049523816, 0.41796258 -0.020843059 0.049056545, 0.41673136 -0.023652047 0.050619677, 0.41668859 -0.0236312 0.050572023, 0.41663754 -0.023606271 0.05053629, 0.41658053 -0.023578495 0.050514117, 0.41801354 -0.021128997 0.04958792, 0.41652054 -0.023549289 0.050506487, 0.41814378 -0.020755574 0.04899098, 0.41813287 -0.020523056 0.048442289, 0.41821873 -0.020712242 0.049039468, 0.41829735 -0.020450711 0.048349902, 0.41823253 -0.020335957 0.04774572, 0.4183723 -0.020399854 0.048380271, 0.41838011 -0.020286649 0.047632679, 0.41824982 -0.020303518 0.047086015, 0.41845503 -0.020231768 0.047642961, 0.41838041 -0.020285755 0.046887919, 0.41820464 -0.020388305 0.046500102, 0.41845536 -0.02023083 0.046877638, 0.41829851 -0.020448431 0.046170011, 0.41810626 -0.02057302 0.045950815, 0.41837344 -0.02039744 0.04614009, 0.418033 -0.020808548 0.045501575, 0.41796359 -0.020840645 0.04546015, 0.41812477 -0.020792678 0.045463219, 0.41819978 -0.020750314 0.045413151, 0.41783985 -0.021177605 0.045027003, 0.41778827 -0.021169603 0.045043007, 0.4175927 -0.021536827 0.044704571, 0.41793349 -0.021171734 0.04497911, 0.41800842 -0.021139011 0.044914618, 0.41764513 -0.021549374 0.044687971, 0.41774064 -0.021553293 0.044633999, 0.41781572 -0.02153036 0.044558659, 0.41737321 -0.022068471 0.044356838, 0.41731894 -0.022050321 0.044372693, 0.41701618 -0.022618607 0.044142529, 0.41747138 -0.022085756 0.044297799, 0.4175466 -0.022077262 0.044211134, 0.41705057 -0.022683516 0.044117108, 0.41715249 -0.022715852 0.044056281, 0.4172276 -0.022725061 0.043959782, 0.41658053 -0.023578033 0.043999001, 0.41652057 -0.023548812 0.044006601, 0.41663751 -0.023605809 0.043977037, 0.41668862 -0.023630887 0.043941274, 0.4167313 -0.0236516 0.04389368, 0.41300064 -0.022771493 0.050412282, 0.41300064 -0.023549244 0.050506487, 0.41300061 -0.022038847 0.050134525, 0.41300061 -0.021394104 0.049689367, 0.41300061 -0.0208745 0.049102798, 0.41300061 -0.020510286 0.048409209, 0.41300061 -0.020322725 0.047648534, 0.41300067 -0.020322695 0.046865001, 0.41300064 -0.020510226 0.046104327, 0.41300064 -0.020874247 0.045410529, 0.41300061 -0.021393836 0.044824108, 0.41300073 -0.022038534 0.044379011, 0.41300061 -0.022771031 0.044101015, 0.41300061 -0.023548871 0.04400675, 0.41300064 -0.030764595 0.044006214, 0.4130007 -0.030764982 0.0505061, 0.41300067 -0.028325588 0.047930136, 0.41300067 -0.028112665 0.048335686, 0.41300067 -0.028435171 0.047485337, 0.41300064 -0.030973077 0.050520375, 0.41300073 -0.02354899 0.045356557, 0.41300067 -0.026549011 0.045356408, 0.41300058 -0.021985427 0.048336074, 0.41300061 -0.022289187 0.048679009, 0.41300067 -0.022666186 0.048939005, 0.41300064 -0.021772489 0.047930583, 0.41300067 -0.028435171 0.047027215, 0.41300067 -0.028325483 0.046582595, 0.41300061 -0.023094475 0.049101487, 0.41300067 -0.028112739 0.046176925, 0.4130007 -0.027808875 0.045834139, 0.41300061 -0.027431965 0.045573965, 0.41300064 -0.027003646 0.045411602, 0.41300061 -0.021662921 0.047485635, 0.41300067 -0.031010658 0.043986067, 0.41300073 -0.031168267 0.050563917, 0.41300052 -0.023549125 0.049156591, 0.4130007 -0.031291693 0.050614789, 0.4130007 -0.031230494 0.043925777, 0.41300061 -0.021662921 0.047027543, 0.41300067 -0.031380028 0.050674632, 0.4130007 -0.031315669 0.043884054, 0.41300064 -0.021772489 0.046582952, 0.41300076 -0.031379625 0.043837681, 0.41300061 -0.021985322 0.046177313, 0.41300064 -0.022289142 0.045834586, 0.41300064 -0.02654925 0.049156442, 0.41300064 -0.022666022 0.045574412, 0.41300064 -0.023094252 0.045411959, 0.41300061 -0.027003914 0.049101219, 0.41300067 -0.027432129 0.048938736, 0.41300055 -0.027808949 0.048678562, 0.4129709 -0.023125455 0.045538113, 0.4129352 -0.022752985 0.045739874, 0.41293517 -0.02313903 0.045593515, 0.41297087 -0.021792099 0.047043309, 0.41293523 -0.021848589 0.047463223, 0.41293517 -0.021848515 0.047050253, 0.41299316 -0.023110241 0.04547669, 0.41299304 -0.023548961 0.045423403, 0.41299313 -0.022697195 0.048879877, 0.41297099 -0.023125678 0.048975006, 0.41297075 -0.022726685 0.04882367, 0.41297099 -0.02354899 0.045486823, 0.41299328 -0.022697121 0.04563342, 0.41297099 -0.022726506 0.045689359, 0.41297087 -0.022375479 0.048581466, 0.4129352 -0.022753045 0.048773512, 0.41297099 -0.021792144 0.047469988, 0.41293505 -0.021947369 0.046649233, 0.41288778 -0.021895736 0.047055975, 0.41288769 -0.021991774 0.046666011, 0.41293529 -0.022413164 0.048538759, 0.41293517 -0.022139296 0.048229918, 0.41288766 -0.022444621 0.048503265, 0.41270065 -0.02316618 0.048810199, 0.41276741 -0.023549184 0.048863962, 0.41270065 -0.023549184 0.048856601, 0.41288769 -0.022178397 0.048202738, 0.41288772 -0.022178382 0.046310589, 0.4128308 -0.022025257 0.046678677, 0.41283086 -0.022207811 0.046330795, 0.41276726 -0.023164451 0.048817292, 0.41288772 -0.021991774 0.047847286, 0.41283086 -0.022207886 0.048182413, 0.41283074 -0.022025153 0.047834441, 0.41283086 -0.023159176 0.048838988, 0.4128308 -0.02354911 0.048886344, 0.41283083 -0.022468299 0.046036735, 0.41276741 -0.02222608 0.046343669, 0.41276744 -0.022483021 0.046053424, 0.4128308 -0.021931171 0.047452942, 0.41276735 -0.02204594 0.047826543, 0.41276741 -0.02195327 0.047450528, 0.41276741 -0.02280198 0.048679993, 0.41270074 -0.022805482 0.048673406, 0.41276738 -0.02280201 0.045833245, 0.41270071 -0.022488043 0.046059057, 0.41276741 -0.02195327 0.047062859, 0.41270074 -0.021960795 0.047449544, 0.41270074 -0.02196078 0.047063753, 0.41270074 -0.022805482 0.045839921, 0.41299313 -0.021729141 0.047035709, 0.41299313 -0.021729141 0.047477618, 0.41299316 -0.022333398 0.048628941, 0.41288766 -0.023150578 0.048873559, 0.41288772 -0.023549289 0.048922196, 0.41297087 -0.021894157 0.046629176, 0.41297099 -0.022092491 0.048262015, 0.4128308 -0.022791654 0.048699751, 0.41293517 -0.022139251 0.046283707, 0.41276735 -0.022483021 0.048459873, 0.41270062 -0.022488117 0.048454389, 0.4129352 -0.021947369 0.047864124, 0.41288766 -0.022444621 0.046010032, 0.41293517 -0.023139209 0.048919901, 0.41288778 -0.021895736 0.047457591, 0.4129352 -0.023549244 0.048969641, 0.41283092 -0.022791713 0.045813695, 0.41283086 -0.021931261 0.047060147, 0.41288766 -0.022775114 0.048731223, 0.41276741 -0.023164317 0.045695826, 0.41270074 -0.02316609 0.045703188, 0.41270071 -0.023549005 0.045656726, 0.41276738 -0.02204597 0.046686515, 0.41270062 -0.022052988 0.046689317, 0.4127675 -0.02354899 0.045649067, 0.41299325 -0.021834925 0.046606705, 0.41283083 -0.022468373 0.048476562, 0.41299313 -0.022040337 0.048298106, 0.41276741 -0.02222608 0.048169866, 0.41270062 -0.022232279 0.048165575, 0.41297096 -0.022092476 0.046251282, 0.41297087 -0.021894261 0.047884241, 0.4129709 -0.023549125 0.049026385, 0.41293529 -0.022413075 0.045974419, 0.41288778 -0.022775084 0.045782045, 0.41283083 -0.023159012 0.04567425, 0.41283086 -0.02354905 0.045626804, 0.41299328 -0.022040337 0.04621534, 0.41270065 -0.022232279 0.046347871, 0.41297102 -0.02237545 0.04593192, 0.41270074 -0.022053033 0.047824129, 0.41299304 -0.021834835 0.047906891, 0.41299313 -0.023110434 0.049036607, 0.41299316 -0.02354911 0.049089834, 0.41288766 -0.023150414 0.04563944, 0.41288772 -0.023549005 0.04559125, 0.41299316 -0.022333354 0.045884505, 0.41293517 -0.02354899 0.045543894, 0.4110007 -0.023549065 0.045656577, 0.41100067 -0.023166135 0.045703068, 0.41100058 -0.022805467 0.045839921, 0.41100067 -0.022487983 0.046058908, 0.41100067 -0.022232264 0.046347752, 0.41100058 -0.022052974 0.046689317, 0.41100058 -0.021960676 0.047063604, 0.41100058 -0.021960676 0.047449395, 0.41100058 -0.022052944 0.047823921, 0.41100067 -0.022232279 0.048165575, 0.4110007 -0.022488102 0.048454389, 0.41100058 -0.022805512 0.048673406, 0.4110007 -0.023166165 0.048810199, 0.41100067 -0.023549184 0.048856601, 0.41100076 -0.02654925 0.048856422, 0.41270068 -0.026549205 0.048856422, 0.4110007 -0.026932016 0.04880999, 0.4127008 -0.026932001 0.04880999, 0.4110007 -0.027292714 0.048673138, 0.41270068 -0.027292684 0.048673138, 0.41100076 -0.027610153 0.048454091, 0.41270077 -0.027610093 0.048453942, 0.4110007 -0.027865827 0.048165306, 0.41270077 -0.027865887 0.048165306, 0.41100076 -0.028045058 0.047823563, 0.41270074 -0.028045192 0.047823831, 0.41100073 -0.028137356 0.047449097, 0.41270077 -0.028137445 0.047449246, 0.41100073 -0.028137356 0.047063366, 0.41270077 -0.028137445 0.047063604, 0.41100058 -0.028044969 0.046689168, 0.41270077 -0.028045088 0.046689019, 0.41100064 -0.027865767 0.046347514, 0.41270077 -0.027865887 0.046347514, 0.41100058 -0.027610034 0.046058759, 0.41270074 -0.027610034 0.046058759, 0.41100064 -0.027292475 0.045839533, 0.41270086 -0.027292639 0.045839772, 0.41100058 -0.026931897 0.045702949, 0.41270074 -0.026931912 0.045703039, 0.41100064 -0.026549011 0.045656577, 0.41270068 -0.026549026 0.045656577, 0.4129931 -0.026548967 0.045423165, 0.41297102 -0.026549041 0.045486614, 0.4129352 -0.026548952 0.045543596, 0.41288772 -0.026549011 0.045591101, 0.41283086 -0.026549011 0.045626804, 0.41276744 -0.026549026 0.045648918, 0.41299319 -0.026549265 0.049089685, 0.41297093 -0.026549205 0.049026266, 0.4129352 -0.02654925 0.048969343, 0.41288772 -0.02654925 0.048921928, 0.41283086 -0.026549235 0.048886076, 0.41276753 -0.02654925 0.048863873, 0.41299307 -0.026987895 0.049036279, 0.41297093 -0.0269728 0.048974738, 0.41299316 -0.027400911 0.045633122, 0.41297102 -0.026972532 0.045538113, 0.41297102 -0.027371496 0.045689121, 0.4129931 -0.027401194 0.048879728, 0.41297099 -0.027371675 0.048823491, 0.41297102 -0.028305978 0.04746972, 0.41297099 -0.028305992 0.047043011, 0.41293523 -0.028249547 0.047049925, 0.41297108 -0.027722687 0.045931712, 0.41293532 -0.027345031 0.045739576, 0.41293523 -0.028249547 0.047462925, 0.4129352 -0.027684897 0.04597418, 0.41293523 -0.028150752 0.047863826, 0.41288784 -0.02820237 0.047456935, 0.41288781 -0.028106302 0.047846839, 0.41293511 -0.027958795 0.046283379, 0.41288772 -0.027653471 0.046009675, 0.41288778 -0.027919695 0.046310291, 0.41288769 -0.02791971 0.04820241, 0.41283092 -0.028072879 0.047834173, 0.41276744 -0.02693373 0.045695588, 0.41288766 -0.028106302 0.046665713, 0.41283086 -0.027890295 0.046330586, 0.41283086 -0.028072864 0.046678558, 0.4128308 -0.02789025 0.048182115, 0.41283089 -0.026939034 0.045674101, 0.41283092 -0.027629837 0.048476115, 0.41276753 -0.027872086 0.048169628, 0.41276738 -0.027614996 0.048459545, 0.41283086 -0.028166875 0.047059909, 0.41276756 -0.028052106 0.046686307, 0.41276753 -0.028144896 0.047062621, 0.41276738 -0.027296111 0.048679724, 0.41276753 -0.027296096 0.045833007, 0.41276753 -0.028144896 0.047450289, 0.41299334 -0.028368965 0.04747729, 0.41288772 -0.026947543 0.045639172, 0.41299322 -0.028368935 0.047035322, 0.41299307 -0.027764618 0.045884058, 0.41297117 -0.02820392 0.047884122, 0.41297099 -0.028005615 0.046250984, 0.41283086 -0.027306467 0.045813456, 0.41293523 -0.02795881 0.048229471, 0.41293523 -0.028150678 0.046648875, 0.4127675 -0.027615085 0.046053186, 0.41288772 -0.027653545 0.048502877, 0.41288784 -0.02820237 0.047055498, 0.4129352 -0.026958898 0.045593277, 0.41283086 -0.027306527 0.048699394, 0.41283086 -0.028166875 0.047452703, 0.41288778 -0.027322978 0.045781627, 0.41276744 -0.026933953 0.048817173, 0.41276744 -0.028052166 0.047826394, 0.41283089 -0.027629763 0.046036586, 0.41299316 -0.028263181 0.047906414, 0.41299319 -0.028057754 0.046215042, 0.41276753 -0.027872026 0.046343222, 0.41297099 -0.02820383 0.046628609, 0.41297105 -0.02800563 0.048261598, 0.41293523 -0.027684987 0.04853867, 0.41288781 -0.027323037 0.048731104, 0.41283086 -0.026939198 0.04883875, 0.41299319 -0.028057814 0.048297539, 0.41297093 -0.027722672 0.048581138, 0.4129931 -0.028263077 0.046606317, 0.41299319 -0.026987702 0.045476452, 0.41293523 -0.027345166 0.048773065, 0.41288769 -0.026947796 0.048873559, 0.41299331 -0.027764767 0.048628494, 0.41293523 -0.026959166 0.048919454, 0.41299465 -0.031439632 0.043780848, 0.41298473 -0.031476244 0.043743774, 0.41299835 -0.031417578 0.050709322, 0.41299132 -0.031454876 0.050746098, 0.46331015 0.15343681 0.073822603, 0.46365979 0.15341459 0.073887691, 0.46333969 0.15341458 0.073766574, 0.46364456 0.15343685 0.071068987, 0.46305797 0.15341458 0.073571876, 0.46336612 0.15337881 0.073716149, 0.46309575 0.15337883 0.073529348, 0.46258998 0.15341461 0.072338209, 0.46264645 0.15337881 0.072673634, 0.46264663 0.15337881 0.072344974, 0.4633103 0.15343687 0.071195945, 0.46333972 0.15341465 0.071251884, 0.46365967 0.15341467 0.071130708, 0.4625901 0.15341462 0.072680339, 0.46272507 0.1533789 0.07202588, 0.46269369 0.15333141 0.072350696, 0.46276957 0.15333129 0.072042927, 0.46287784 0.15337881 0.073283538, 0.46312726 0.15333137 0.073493794, 0.46369866 0.15321103 0.073730066, 0.46291694 0.15333138 0.073256597, 0.46291694 0.15333132 0.071761712, 0.46280304 0.15327451 0.072055563, 0.4627696 0.1533314 0.072975621, 0.46294627 0.15327446 0.073236093, 0.46280304 0.15327451 0.072963133, 0.4629463 0.15327449 0.071782216, 0.46369329 0.1532744 0.073751763, 0.46315098 0.15327455 0.071551219, 0.46296462 0.15321122 0.071794853, 0.46316561 0.1532111 0.071567908, 0.46272922 0.15327451 0.072663501, 0.46282369 0.15321097 0.072955236, 0.46275112 0.15321112 0.072660699, 0.46341512 0.1532111 0.073622569, 0.46341506 0.1532111 0.071395621, 0.46275121 0.15321103 0.072357759, 0.46368471 0.15333138 0.073786363, 0.46252707 0.15343679 0.07233052, 0.46301588 0.15343681 0.073619559, 0.46252707 0.15343679 0.072687998, 0.46267191 0.15341468 0.072005734, 0.46283105 0.15341458 0.073315844, 0.4634048 0.15327451 0.073642477, 0.46287793 0.1533788 0.071735069, 0.4631657 0.15321109 0.07345061, 0.46272507 0.1533789 0.072992519, 0.46312717 0.15333138 0.071524605, 0.46367332 0.15337881 0.073832586, 0.46269366 0.15333138 0.072667852, 0.46340483 0.15327451 0.07137607, 0.46338817 0.15333128 0.073673829, 0.46272916 0.15327445 0.072354987, 0.46369854 0.1532111 0.071288332, 0.46282381 0.15321109 0.072063223, 0.46315092 0.15327445 0.073467299, 0.46261284 0.15343678 0.071983323, 0.4627789 0.15343678 0.073351696, 0.46296459 0.15321107 0.073223546, 0.46267191 0.15341468 0.073012456, 0.46283105 0.15341471 0.071702614, 0.46309575 0.15337892 0.0714892, 0.46338823 0.15333138 0.071344361, 0.46369329 0.15327458 0.071266606, 0.4627789 0.15343678 0.071666703, 0.46305797 0.15341458 0.071446434, 0.46261266 0.15343681 0.073035225, 0.46336624 0.15337886 0.071302488, 0.46364453 0.15343671 0.073949322, 0.46368474 0.15333141 0.071232006, 0.46301594 0.15343687 0.071398929, 0.46367326 0.15337887 0.071185812, 0.48364457 0.14997444 0.14118837, 0.48331016 0.14991771 0.141302, 0.48333982 0.14987274 0.1413423, 0.48365977 0.14992709 0.1412337, 0.48259002 0.14938693 0.14231353, 0.48259011 0.14923383 0.14261974, 0.48264655 0.14920494 0.14259757, 0.48305818 0.14883503 0.14341711, 0.48336622 0.14873859 0.14353023, 0.48309577 0.14882205 0.14336313, 0.48272517 0.14949466 0.14201845, 0.48269373 0.1493068 0.14228763, 0.48276961 0.14944467 0.14201225, 0.48287782 0.14893217 0.14314328, 0.48312721 0.1487955 0.14331006, 0.48264655 0.14935184 0.14230375, 0.48291689 0.14957026 0.14176105, 0.48280308 0.14938809 0.14199798, 0.48291695 0.14890173 0.14309786, 0.48294634 0.14951029 0.14175381, 0.48276958 0.1490273 0.14284672, 0.48294637 0.14885992 0.14305411, 0.48369864 0.14858223 0.14346765, 0.48280302 0.14898212 0.14281, 0.48315096 0.14961365 0.14154713, 0.48296466 0.14944799 0.14173667, 0.48369327 0.14862934 0.14351536, 0.48316562 0.14954945 0.14153387, 0.48272917 0.14911611 0.14254187, 0.48282373 0.14892897 0.14277445, 0.48275116 0.14906058 0.14251111, 0.48341516 0.14962651 0.14137961, 0.48275116 0.14919613 0.14224018, 0.48341519 0.14863025 0.14337157, 0.48252708 0.14941017 0.14231671, 0.48301598 0.14883365 0.14346959, 0.48333976 0.148748 0.14359115, 0.48368481 0.14866467 0.14357184, 0.48252711 0.14925024 0.14263643, 0.48267207 0.1495357 0.14201643, 0.48331025 0.14874281 0.14365138, 0.4834049 0.14867821 0.14341752, 0.48283109 0.14894959 0.14318798, 0.48287788 0.14962478 0.1417581, 0.48272523 0.14906217 0.14288308, 0.48316562 0.14870736 0.14321731, 0.48312715 0.14967647 0.14154889, 0.48269376 0.14916499 0.1425712, 0.48367345 0.1486865 0.1436343, 0.4834049 0.14969198 0.14139058, 0.48272911 0.14925411 0.14226605, 0.48338833 0.14871493 0.14347123, 0.48369858 0.14967445 0.14128362, 0.4828237 0.14932796 0.14197685, 0.48261273 0.14956555 0.14200644, 0.48315099 0.14875661 0.1432607, 0.48277888 0.14895339 0.1432303, 0.48296455 0.14880893 0.14301465, 0.48283097 0.14967118 0.14174534, 0.48267201 0.14908521 0.14291705, 0.48309568 0.14973474 0.14153828, 0.48365986 0.14869381 0.14369954, 0.4833883 0.14975683 0.14138772, 0.48369324 0.14974079 0.1412928, 0.48277891 0.14970718 0.14172278, 0.48305804 0.14978579 0.14151622, 0.48261276 0.14909503 0.14294706, 0.48364457 0.14868611 0.14376472, 0.48336616 0.14981833 0.14137129, 0.48368469 0.14980733 0.14128722, 0.48301601 0.14982691 0.14148365, 0.48367336 0.14987043 0.14126711, 0.48360959 0.15160777 0.14538462, 0.48360097 0.15164307 0.14544104, 0.48240376 0.15234545 0.14376764, 0.48325258 0.15289542 0.14266802, 0.48361486 0.15295681 0.14254524, 0.48324218 0.15167011 0.14526008, 0.48322555 0.15170677 0.14531384, 0.48249647 0.15251374 0.14343117, 0.48360953 0.1530232 0.14255427, 0.48324227 0.15296084 0.14267884, 0.48247567 0.15257394 0.14345251, 0.48238173 0.15240337 0.14379372, 0.48361495 0.15156068 0.14533712, 0.4823817 0.1522276 0.14414524, 0.4823463 0.15245612 0.14381538, 0.48234618 0.15227653 0.14417447, 0.48291877 0.15286109 0.14287828, 0.48322558 0.15302595 0.14267589, 0.48325253 0.15162215 0.14521416, 0.48244235 0.15210214 0.14452328, 0.48229909 0.15231651 0.14420094, 0.48289511 0.1529239 0.14287998, 0.48262888 0.15278949 0.14314888, 0.48286369 0.15298228 0.14286925, 0.48239782 0.15213722 0.1445594, 0.48258984 0.15197366 0.14488648, 0.48234475 0.15216012 0.14459349, 0.48356092 0.15325673 0.14245008, 0.48258987 0.15284403 0.14314581, 0.482398 0.15268053 0.14347281, 0.48254305 0.15289053 0.14313294, 0.48254296 0.15199117 0.14493133, 0.48234475 0.15272161 0.14347078, 0.48357606 0.15320936 0.14249517, 0.48282596 0.15184833 0.14521693, 0.48249087 0.1519949 0.1449735, 0.48278385 0.15184703 0.14526938, 0.48224264 0.15253623 0.14384125, 0.48228541 0.1527513 0.14346074, 0.48217955 0.1525595 0.14384411, 0.48314759 0.15173467 0.145494, 0.4821797 0.15236184 0.1442398, 0.48314753 0.1531866 0.14259015, 0.48240373 0.15217213 0.14411436, 0.48293361 0.15279688 0.14286496, 0.48358971 0.15315267 0.14252864, 0.48247582 0.15205702 0.14448644, 0.4826583 0.15272959 0.1431414, 0.48317707 0.15314169 0.14263044, 0.48244229 0.15263051 0.14346661, 0.48278385 0.15307435 0.14281489, 0.48262894 0.15194328 0.14484106, 0.48229906 0.1525012 0.14383148, 0.48360094 0.15308955 0.14254855, 0.48286361 0.15183544 0.14516281, 0.48317707 0.15173993 0.14543389, 0.48320338 0.15308718 0.14265953, 0.48224261 0.15234545 0.14422296, 0.48356089 0.15166451 0.14563413, 0.48228544 0.1521699 0.1446235, 0.48249656 0.15200385 0.14445104, 0.48282591 0.15303329 0.14284717, 0.48267666 0.15266718 0.14312433, 0.48265827 0.15190145 0.14479755, 0.48249099 0.1529264 0.14311062, 0.48289517 0.15180887 0.14510988, 0.48320341 0.15173057 0.14537282, 0.48357606 0.15167215 0.1455691, 0.48267666 0.1518503 0.14475785, 0.48291889 0.15176992 0.14506055, 0.48358968 0.15166496 0.14550366, 0.48293349 0.15172058 0.14501728, 0.46361473 0.15671112 0.074070081, 0.46325251 0.15671109 0.071086034, 0.46360949 0.15677454 0.070926771, 0.4632422 0.1567746 0.071066365, 0.46291885 0.1567746 0.071289405, 0.46322557 0.15683134 0.071034625, 0.46325245 0.15671107 0.073932722, 0.4623816 0.15677443 0.07270582, 0.46234623 0.15683129 0.072308525, 0.46234623 0.15683129 0.072710082, 0.46360955 0.15677449 0.074091628, 0.4632422 0.15677437 0.073952422, 0.46238175 0.15677443 0.072313026, 0.46244228 0.15683135 0.073099867, 0.46229902 0.15687877 0.072715953, 0.46239784 0.15687884 0.073116854, 0.46289504 0.15683137 0.071262792, 0.46262893 0.15683135 0.071563318, 0.46286377 0.15687887 0.071227297, 0.46356091 0.15693678 0.07072936, 0.46258977 0.1568789 0.071536407, 0.46258977 0.1568788 0.073482499, 0.46234471 0.1569145 0.073137209, 0.46239784 0.15687884 0.071901992, 0.46254292 0.15691467 0.071504012, 0.46254298 0.15691455 0.073514894, 0.46357599 0.15691459 0.070790991, 0.46234474 0.15691458 0.071881846, 0.46282592 0.15691458 0.073834166, 0.46249068 0.15693673 0.073550776, 0.46278384 0.15693668 0.073881611, 0.46224269 0.15691458 0.072296038, 0.46228555 0.15693678 0.071859583, 0.46217963 0.15693679 0.072288379, 0.46314755 0.15693685 0.07088609, 0.46314761 0.15693669 0.074132547, 0.46217963 0.15693679 0.072730318, 0.46358952 0.15687887 0.070846096, 0.46240368 0.15671112 0.072703108, 0.46293351 0.15671112 0.071306095, 0.46240374 0.15671106 0.072315589, 0.46247572 0.15677443 0.07308732, 0.46317706 0.15691458 0.070942387, 0.46265826 0.15677449 0.071583614, 0.46262893 0.15683135 0.073455438, 0.46278384 0.15693681 0.071137175, 0.46244225 0.1568314 0.071918741, 0.46286365 0.15687875 0.073791459, 0.46360096 0.15683141 0.070892319, 0.46229902 0.15687884 0.072303042, 0.46317711 0.1569145 0.074076608, 0.46320346 0.1568789 0.070992693, 0.46224269 0.15691458 0.072722867, 0.46356088 0.15693654 0.074289426, 0.46228549 0.15693673 0.073159561, 0.46282586 0.15691461 0.071184799, 0.46249649 0.15671109 0.073079422, 0.4626765 0.15671109 0.071596101, 0.46249068 0.15693673 0.07146807, 0.46247563 0.15677454 0.071931377, 0.46265832 0.15677448 0.073435143, 0.46289521 0.15683134 0.073755845, 0.46320346 0.15687884 0.074026093, 0.46357599 0.15691456 0.074227765, 0.4626765 0.15671103 0.073422655, 0.46291891 0.15677436 0.073729381, 0.46249649 0.15671109 0.071939394, 0.46361491 0.1567111 0.070948705, 0.46322551 0.15683135 0.073984191, 0.46358952 0.15687881 0.074172601, 0.46293357 0.15671097 0.073712692, 0.46360102 0.15683125 0.074126646, 0.46693608 0.15742156 0.073923692, 0.46654782 0.15742125 0.074541762, 0.46659186 0.15743841 0.074576959, 0.46698681 0.15743855 0.07394813, 0.46723214 0.15743855 0.073247209, 0.46688941 0.15739377 0.073901132, 0.46650735 0.15739365 0.074509308, 0.4671773 0.15742156 0.073234871, 0.46712658 0.15739383 0.073223099, 0.46473733 0.15743838 0.075742081, 0.46472487 0.15742119 0.075687274, 0.46543813 0.15743832 0.075497016, 0.46471325 0.15739366 0.07563661, 0.46541372 0.15742132 0.075446263, 0.46606687 0.15743835 0.075101808, 0.46539125 0.15739359 0.075399503, 0.4660317 0.15742142 0.075057849, 0.46599945 0.15739365 0.075017318, 0.46232584 0.15694995 0.074608132, 0.46281028 0.15696695 0.074978545, 0.46283484 0.15694991 0.074927941, 0.46340218 0.15695001 0.075126395, 0.4627879 0.1569947 0.075025275, 0.46225849 0.15699476 0.074692562, 0.46229085 0.15696701 0.074652061, 0.46338961 0.156967 0.07518135, 0.46337816 0.15699477 0.075231865, 0.46138254 0.15695004 0.073106721, 0.46132773 0.15696709 0.073119357, 0.46158114 0.15695 0.073674038, 0.46127722 0.15699485 0.073130682, 0.46153036 0.15696709 0.073698476, 0.46190086 0.15695004 0.074182972, 0.46148363 0.15699486 0.073721036, 0.46185693 0.15696704 0.07421802, 0.46181634 0.15699473 0.074250475, 0.48668376 0.15247251 0.14404811, 0.48674008 0.15248783 0.14405559, 0.48679209 0.15251255 0.14406814, 0.48671082 0.15281147 0.14347027, 0.48190939 0.15334073 0.14241181, 0.48152697 0.15309301 0.14290728, 0.48194817 0.15330057 0.14243008, 0.48157302 0.1530574 0.14291646, 0.48660588 0.15275979 0.14347352, 0.4864262 0.15305743 0.14291646, 0.48637637 0.1530305 0.14293231, 0.48131523 0.15247251 0.14404796, 0.48133874 0.15278116 0.14346908, 0.48125902 0.15248775 0.14405559, 0.48666048 0.15278108 0.14346908, 0.48162279 0.15303038 0.14293231, 0.48139328 0.15275975 0.1434734, 0.48600873 0.15326859 0.1424558, 0.48120713 0.1525127 0.14406799, 0.48128825 0.15281142 0.14347027, 0.4864721 0.15309298 0.14290737, 0.48605093 0.15330061 0.14243008, 0.48552439 0.15346046 0.14207219, 0.48608962 0.1533408 0.14241196, 0.4855563 0.15349665 0.14203821, 0.48495135 0.15359522 0.14180328, 0.48558584 0.15354051 0.14201249, 0.48497134 0.153634 0.14176367, 0.4843232 0.15366444 0.14166461, 0.48498982 0.15368035 0.14173256, 0.48432985 0.15370469 0.14162244, 0.48367599 0.1536644 0.14166461, 0.4843362 0.15375242 0.14158885, 0.48366925 0.1537046 0.14162244, 0.48304763 0.15359519 0.14180316, 0.48366293 0.15375248 0.14158885, 0.48302773 0.15363392 0.14176367, 0.48247468 0.15346053 0.1420721, 0.4830094 0.1536804 0.14173256, 0.48244271 0.15349661 0.14203827, 0.4819904 0.15326865 0.1424558, 0.4824132 0.15354054 0.14201249, 0.4807919 0.15286939 0.14424635, 0.4807401 0.15289412 0.14425884, 0.48068377 0.15290937 0.14426635, 0.48078012 0.15326424 0.1435567, 0.4810636 0.1535985 0.14288805, 0.48688567 0.15357172 0.14290409, 0.48721904 0.15326428 0.1435567, 0.48693547 0.15359864 0.14288832, 0.48115945 0.15353598 0.14291309, 0.48159859 0.15382074 0.14234386, 0.48155987 0.15386082 0.14232565, 0.48111346 0.15357152 0.14290409, 0.48716441 0.15324296 0.14356114, 0.48648146 0.15389287 0.14230002, 0.48083481 0.15324287 0.14356123, 0.48731533 0.15290946 0.14426635, 0.48683971 0.15353605 0.14291336, 0.48088512 0.15321264 0.1435598, 0.48711392 0.1532127 0.1435598, 0.48643929 0.15386088 0.14232565, 0.48588309 0.15412991 0.14182593, 0.48640046 0.15382066 0.14234401, 0.48585117 0.15409397 0.14185967, 0.48517528 0.15429612 0.14149357, 0.4858216 0.15405008 0.14188538, 0.48515531 0.15425737 0.14153303, 0.48439917 0.15438165 0.14132248, 0.48513696 0.15421084 0.141564, 0.48439249 0.15434143 0.14136471, 0.48359981 0.15438154 0.14132248, 0.48438612 0.15429357 0.14139841, 0.48360664 0.15434141 0.14136486, 0.4828237 0.15429619 0.14149342, 0.48361292 0.15429361 0.14139841, 0.48284361 0.15425728 0.14153291, 0.48211595 0.15412992 0.14182569, 0.4828622 0.15421087 0.14156382, 0.48214799 0.15409394 0.14185952, 0.48151764 0.15389279 0.14229988, 0.48217735 0.15405002 0.1418853, 0.48725903 0.15289415 0.14425875, 0.48720714 0.15286936 0.14424635, 0.42994592 0.0033754557 0.057675049, 0.42994133 0.0033319294 0.03681083, 0.42994323 0.0033448339 0.057696775, 0.42993337 0.0032904148 0.057726905, 0.42992833 0.0032719076 0.036781356, 0.42991769 0.0032373965 0.057745233, 0.42991421 0.0032290369 0.036769316, 0.42990491 0.0031852871 0.010591224, 0.42993054 0.003172785 0.010685042, 0.42997208 0.0031525344 0.010771409, 0.42996156 0.0034179986 0.01052402, 0.42995653 0.0034984648 0.010467634, 0.43001226 0.00345999 0.010641441, 0.42994604 0.0033781826 0.010417566, 0.42995986 0.0033801645 0.010545269, 0.42994317 0.0033475906 0.010439381, 0.42997733 0.0036894679 0.010494456, 0.42993307 0.0035996437 0.010373816, 0.43000636 0.0035613626 0.010586098, 0.42993268 0.0035269707 0.010263458, 0.42986503 0.0037357211 0.010199174, 0.4298887 0.0036425591 0.010082975, 0.43003157 0.0032925606 0.010766134, 0.42998919 0.003292799 0.010699764, 0.4300569 0.0034281909 0.010728344, 0.43006054 0.0034822375 0.010707274, 0.43000993 0.0034124106 0.010662332, 0.42994347 0.0032849163 0.010583386, 0.4300563 0.0035975873 0.010651663, 0.42990494 0.0031837672 0.036667779, 0.42993048 0.0031712949 0.036573961, 0.42997208 0.0031510592 0.036487296, 0.4299376 0.0032806098 0.036700472, 0.42995194 0.0033546984 0.036730245, 0.42997459 0.0032901615 0.036588535, 0.42995492 0.0034430176 0.036784813, 0.42999181 0.0033824891 0.036617711, 0.43002474 0.0032913089 0.036502168, 0.43004653 0.003400296 0.036531255, 0.42999479 0.0034928769 0.036670849, 0.42993918 0.00354743 0.036876366, 0.43005249 0.0035306662 0.036584929, 0.42997357 0.0036236346 0.036760315, 0.42990145 0.0036501586 0.036998078, 0.42990491 0.0031825751 0.057848647, 0.42993048 0.0031701028 0.057942465, 0.42997208 0.0031498075 0.058028981, 0.4299579 0.0033753812 0.05779548, 0.42997453 0.0032890439 0.057927772, 0.42994162 0.0032815188 0.057833746, 0.43002471 0.0032901466 0.058014289, 0.43004918 0.0034234673 0.057976648, 0.42999378 0.0034020096 0.057890132, 0.42993185 0.0035917759 0.057623819, 0.42996129 0.003663227 0.057721898, 0.42995498 0.0034919381 0.057717696, 0.42995974 0.0034126788 0.057774141, 0.42998967 0.0035425574 0.057814017, 0.42999581 0.0034469664 0.05786936, 0.43004808 0.0035897642 0.057899877, 0.43005267 0.0034765303 0.057955518, 0.43273672 0.0051381588 0.059661701, 0.41301075 -0.035355419 0.059693977, 0.43277964 0.0051434934 0.05971615, 0.4130424 -0.035398155 0.059788659, 0.43284571 0.0051662177 0.059835866, 0.41305199 -0.035432309 0.059874728, 0.41305208 -0.035429686 0.012617454, 0.43277061 0.0050079077 0.012591198, 0.41304243 -0.035395488 0.012531295, 0.43272051 0.0049971491 0.012481466, 0.41301075 -0.035352841 0.012436345, 0.43267491 0.0049967766 0.012414709, 0.43278226 0.0050127506 0.034629568, 0.41304964 -0.035415888 0.034676418, 0.43275648 0.0050017983 0.034705445, 0.41302469 -0.035369441 0.034784988, 0.43269885 0.0049950629 0.034811661, 0.41299579 -0.03534013 0.03484647, 0.41229504 0.026726365 0.11079465, 0.4619635 0.076372266 0.090109482, 0.41226801 0.026669562 0.11068995, 0.46197295 0.076279864 0.089908943, 0.41225091 0.026550382 0.11050878, 0.46201774 0.076160222 0.089728579, 0.41227499 0.026412159 0.11034165, 0.46314767 0.077574819 0.089345798, 0.46309796 0.07747747 0.089241818, 0.46268314 0.077107266 0.089776382, 0.46266079 0.07702899 0.089635476, 0.46265954 0.07693623 0.089501962, 0.47279716 0.087122545 0.075392827, 0.47283077 0.087178111 0.075382367, 0.47285768 0.087223679 0.075381503, 0.47287974 0.087262258 0.075389728, 0.4728907 0.087288007 0.075415596, 0.47290289 0.087312981 0.075441822, 0.47291604 0.087336928 0.075468138, 0.47291809 0.08734493 0.075496182, 0.47291797 0.087349892 0.075528339, 0.47291103 0.087350503 0.075603977, 0.47291571 0.087333128 0.075453028, 0.47291532 0.087331533 0.075448588, 0.47291473 0.08732973 0.075443938, 0.4729133 0.087325558 0.075435147, 0.47291258 0.087323755 0.075432286, 0.47291037 0.087318987 0.075425074, 0.47290811 0.087314382 0.075419292, 0.47290811 0.087314382 0.075419292, 0.47290567 0.087309197 0.075414166, 0.47290251 0.087303013 0.075408891, 0.47289896 0.08729659 0.075404391, 0.47289559 0.087290451 0.075400785, 0.47289148 0.087282985 0.075396881, 0.47288796 0.087276608 0.075394258, 0.44096935 0.14244601 0.087531552, 0.4410418 0.14245401 0.087526664, 0.44106233 0.1422524 0.088480577, 0.44092426 0.14223313 0.08845149, 0.44106585 0.14219068 0.088612124, 0.44092077 0.14216109 0.088597462, 0.44092074 0.14200595 0.088908061, 0.441066 0.14203537 0.088922665, 0.44106591 0.14203273 0.088928089, 0.44092062 0.14200364 0.088912711, 0.44113672 0.14038171 0.090219006, 0.44072363 0.14068148 0.089975819, 0.44073716 0.14034861 0.090028629, 0.44092849 0.1406931 0.090044007, 0.44094768 0.14036429 0.090101197, 0.44111362 0.1407152 0.090153083, 0.44073939 0.14100315 0.089865938, 0.4409318 0.14101234 0.089928225, 0.44110796 0.14103797 0.090024456, 0.44078901 0.1413739 0.089652881, 0.44095895 0.14138293 0.089704767, 0.44111779 0.14141063 0.089779481, 0.44085974 0.14173825 0.089311823, 0.44099835 0.14175025 0.089345679, 0.44113114 0.14177778 0.089391455, 0.44114158 0.14020713 0.090225056, 0.44095251 0.14020714 0.090106711, 0.44074187 0.14020713 0.090033516, 0.44114169 0.13164994 0.09022446, 0.44095269 0.13164984 0.090106353, 0.44074199 0.13164994 0.09003292, 0.44112757 0.13135265 0.090207294, 0.44093853 0.1313823 0.090090498, 0.44072783 0.13140877 0.090018854, 0.44106403 0.12985811 0.089030758, 0.44078901 0.13016772 0.089371637, 0.44089338 0.12989047 0.088991746, 0.44094834 0.13015237 0.089416489, 0.44109848 0.13011675 0.089477763, 0.44072846 0.13050547 0.089671478, 0.44091356 0.13048956 0.089729056, 0.44070268 0.1307825 0.089834675, 0.44108421 0.13045231 0.089814261, 0.44090194 0.13076442 0.089898273, 0.44070026 0.13108709 0.089952454, 0.44108322 0.13072786 0.089997873, 0.44090849 0.13106528 0.090020642, 0.4410961 0.13103147 0.090131298, 0.44107434 0.12978128 0.088879451, 0.4409039 0.1298233 0.088859633, 0.44107437 0.12962444 0.088543162, 0.44090387 0.12966646 0.088523492, 0.44090399 0.12962227 0.088427171, 0.44107065 0.12958708 0.088456884, 0.44093928 0.12943676 0.087591425, 0.44105321 0.12941678 0.087595448, 0.47477272 0.13483991 0.17055617, 0.47485897 0.13505311 0.1705129, 0.47496441 0.13524216 0.17042424, 0.47508326 0.13539691 0.17029496, 0.47523889 0.13538912 0.17031653, 0.47531462 0.13483435 0.17065503, 0.47501057 0.13523972 0.17043974, 0.47526744 0.13523145 0.17046966, 0.47501042 0.13500963 0.17058189, 0.47529307 0.13504341 0.17058466, 0.47501042 0.13474955 0.17065586, 0.47279701 0.087040663 0.075208947, 0.47278234 0.087047726 0.075312242, 0.47293615 0.087320551 0.075252846, 0.47291067 0.087289825 0.075321928, 0.4729473 0.087373778 0.075438008, 0.47297585 0.087412447 0.075407848, 0.43219915 0.005163148 0.01209949, 0.43236393 0.0052429587 0.012232408, 0.43253222 0.0053052306 0.012378231, 0.43261433 0.0053543597 0.012484983, 0.43257919 0.0053261369 0.012428984, 0.43263763 0.005387947 0.012544617, 0.43271518 0.0055467039 0.012884602, 0.43276283 0.0056444108 0.013251975, 0.43261433 0.0053531379 0.034773991, 0.4325321 0.0053040087 0.034880742, 0.43257925 0.00532493 0.034830168, 0.43263766 0.0053866655 0.034714386, 0.43210304 0.005106017 0.03523241, 0.43226454 0.0051959157 0.035108075, 0.43271515 0.0055455565 0.034374312, 0.43276295 0.0056432635 0.034007296, 0.43258297 0.0054067224 0.05959703, 0.43263736 0.0054426342 0.059647813, 0.4326798 0.0054856837 0.059703782, 0.43271029 0.0055340379 0.059763625, 0.4327811 0.0056789368 0.059965923, 0.43283951 0.0057992488 0.060187533, 0.43473551 0.0096850842 0.069441691, 0.43453589 0.0092760921 0.06926693, 0.43436083 0.0089172125 0.068987355, 0.43422055 0.0086299181 0.068619385, 0.46681815 0.075455785 0.069445387, 0.46701744 0.07586433 0.06927143, 0.46987659 0.081726223 0.06343089, 0.46996853 0.08191447 0.063068524, 0.47002524 0.082030863 0.062670663, 0.46222946 0.077417642 0.051008776, 0.41100004 0.077406764 0.051066533, 0.46217778 0.077332884 0.051337823, 0.41100004 0.07729286 0.051441684, 0.46206561 0.077148944 0.051724389, 0.4110001 0.077107936 0.05178763, 0.46188924 0.076859653 0.05209066, 0.41100004 0.07685931 0.05209066, 0.45514363 0.063030347 0.065918431, 0.41100004 0.063030049 0.065918431, 0.45428136 0.061616063 0.066504106, 0.41100007 0.062006012 0.066465631, 0.45459515 0.062130868 0.066436633, 0.41100007 0.061615825 0.066504225, 0.41100004 0.062381193 0.066351995, 0.45489278 0.062618703 0.066234723, 0.41100013 0.062726855 0.066167101, 0.42887154 0.0095248818 0.066501126, 0.4110004 0.0095248669 0.066501275, 0.4110004 0.007575199 0.064946219, 0.42774713 0.0076811314 0.065275505, 0.41100049 0.0077230334 0.065368786, 0.4278726 0.0078868866 0.065648332, 0.4110004 0.0079613477 0.065748081, 0.42804715 0.0081728101 0.065974608, 0.4110004 0.0082778782 0.066064462, 0.42825925 0.0085207671 0.066230789, 0.4110004 0.0086571127 0.06630291, 0.42849305 0.008904323 0.066402212, 0.4110004 0.0090798885 0.066450849, 0.4286848 0.0092186779 0.066477522, 0.45268285 0.080008283 0.061467543, 0.45273158 0.080108076 0.061174527, 0.45280963 0.080268174 0.060916618, 0.45291248 0.080478936 0.060708717, 0.45303413 0.080728427 0.060562983, 0.4531675 0.081001863 0.06048812, 0.45330504 0.08128354 0.060488299, 0.45343831 0.081557065 0.060563132, 0.45356005 0.081806377 0.060708895, 0.45366278 0.082017273 0.060916558, 0.45374092 0.082177311 0.061174706, 0.45378962 0.082277089 0.061467543, 0.45403665 0.082783297 0.064292982, 0.45424777 0.083216369 0.063859835, 0.45190355 0.078410819 0.061134115, 0.45188138 0.078365222 0.061454549, 0.45194027 0.078486025 0.060820714, 0.45379072 0.082278952 0.064616755, 0.45352063 0.081725284 0.064817324, 0.45379055 0.082279295 0.058940485, 0.45352057 0.081725582 0.058739945, 0.45403662 0.08278358 0.059264436, 0.45424786 0.083216518 0.059697911, 0.45204571 0.077013358 0.060820594, 0.45216233 0.075541407 0.060820594, 0.4561463 0.083708212 0.066067681, 0.4551934 0.08346574 0.064965978, 0.45446602 0.081974626 0.065923646, 0.45541903 0.082217172 0.067025319, 0.45541891 0.082217798 0.056532338, 0.45446602 0.081975132 0.057633623, 0.45519334 0.083465964 0.058591679, 0.45614633 0.083708674 0.057490036, 0.4558129 0.083003432 0.056925818, 0.45430058 0.082479894 0.05844982, 0.45485339 0.082768366 0.058020011, 0.45200706 0.076923057 0.061404362, 0.45226488 0.074030057 0.061189547, 0.45581269 0.083002895 0.066631779, 0.45446745 0.082821473 0.064888135, 0.45485342 0.082768038 0.065537229, 0.42874947 0.0084403008 0.066458806, 0.42852983 0.0080194324 0.066185489, 0.42846516 0.0080972761 0.066126093, 0.42868587 0.0085019618 0.066392049, 0.42870617 0.0090699792 0.066458359, 0.42817581 0.0071338117 0.064988986, 0.42813709 0.0072730929 0.064961806, 0.42879859 0.0083729625 0.066553459, 0.42857614 0.0079295337 0.066272005, 0.42797995 0.0076582432 0.065343842, 0.42787817 0.007699728 0.065347895, 0.42789748 0.0075215846 0.064932004, 0.42817262 0.0069945008 0.065021113, 0.42878675 0.0090269893 0.066476181, 0.42854086 0.0086045563 0.066322222, 0.4280712 0.0075982213 0.065351471, 0.42799148 0.0074615777 0.064935341, 0.42906639 0.0094298124 0.066550598, 0.42881998 0.0083132237 0.066661254, 0.42859033 0.0078453422 0.066371694, 0.42886013 0.0089842081 0.066509113, 0.42915174 0.0093882382 0.066610202, 0.42814806 0.0075226724 0.065369621, 0.42806998 0.0073830038 0.064944372, 0.42861855 0.0085542947 0.06634964, 0.42821461 0.0074195415 0.065403119, 0.4289245 0.0089428723 0.06655632, 0.42922288 0.0093535334 0.066689357, 0.42825517 0.0072913319 0.065455094, 0.42802328 0.0079370737 0.065736279, 0.42898697 0.0088976622 0.066626295, 0.42927644 0.0093273669 0.066784129, 0.42812026 0.007892102 0.065734372, 0.42903855 0.0088519901 0.066723242, 0.42906633 0.008815363 0.066832498, 0.42930961 0.0093111992 0.066889748, 0.42825603 0.0071642548 0.065515533, 0.42820731 0.0078331828 0.065747753, 0.42828128 0.0077628791 0.065775111, 0.42834708 0.0076708347 0.065823302, 0.42839038 0.007559821 0.065895453, 0.42822069 0.0082624555 0.066066399, 0.42831203 0.008215338 0.066069946, 0.4289715 0.0094761401 0.066513672, 0.42839739 0.0074520856 0.065979138, 0.42839438 0.0081594437 0.066090092, 0.42779273 0.0075599104 0.064934954, 0.4284552 0.008651197 0.066311702, 0.45471951 0.061402306 0.066892996, 0.45468625 0.061418548 0.066787019, 0.45463279 0.061444655 0.066692337, 0.45456156 0.061479419 0.066613182, 0.45447633 0.061520979 0.066553459, 0.45438138 0.061567336 0.066516533, 0.45555285 0.063107058 0.066194728, 0.45549473 0.06306158 0.06612061, 0.45468953 0.06209068 0.066458717, 0.45477906 0.06205821 0.066500649, 0.45486006 0.062034652 0.066560224, 0.45492965 0.062020555 0.066634879, 0.45498517 0.062016696 0.06672214, 0.45502406 0.062023237 0.066818222, 0.45498255 0.062590778 0.066261783, 0.45524192 0.063014045 0.065950111, 0.45506743 0.062573671 0.066303805, 0.45533589 0.063013941 0.065995678, 0.45514509 0.062567487 0.066358462, 0.45542127 0.063030079 0.066053405, 0.45521334 0.062572181 0.066424236, 0.45527008 0.062587813 0.066499099, 0.45531371 0.062613845 0.066580787, 0.46198747 0.076843381 0.05212234, 0.46208143 0.076843366 0.052168116, 0.46216691 0.076859385 0.052225783, 0.46224031 0.076890826 0.052293167, 0.46229836 0.076936275 0.052366957, 0.46216127 0.077144369 0.051750168, 0.46225274 0.077156827 0.051785335, 0.46233663 0.077185422 0.051828101, 0.46241015 0.077229217 0.051877216, 0.46247038 0.077286512 0.051930532, 0.46227196 0.07733658 0.051355109, 0.46236196 0.077357098 0.051377967, 0.46244505 0.077393755 0.051404849, 0.46251854 0.07744512 0.051435336, 0.46258 0.077509627 0.051468477, 0.46429595 0.081892356 0.064398304, 0.46440545 0.081876129 0.064414278, 0.46409228 0.081233785 0.06557025, 0.46398446 0.081253976 0.065547481, 0.46448895 0.082288399 0.063121215, 0.46459976 0.082274526 0.06312944, 0.46498805 0.082453325 0.063203946, 0.46490958 0.082376793 0.063180789, 0.4648155 0.082319871 0.063159898, 0.4647831 0.082032889 0.064559594, 0.46445242 0.081355184 0.065779313, 0.4647105 0.082285076 0.063142613, 0.46470791 0.081963241 0.064514294, 0.46438274 0.081296757 0.065714225, 0.46461678 0.081912473 0.064473674, 0.46429643 0.081255704 0.065655813, 0.46451429 0.081882894 0.064439729, 0.46419802 0.081234381 0.065607086, 0.46381083 0.080905929 0.065994009, 0.46400103 0.080878079 0.066046342, 0.46417049 0.08091177 0.066143617, 0.46369126 0.080146581 0.066790476, 0.43199018 0.0049462467 0.035350129, 0.43202549 0.004887417 0.035345539, 0.43205342 0.0048272014 0.035326883, 0.4326202 0.0050651282 0.034922555, 0.43261054 0.0051305294 0.034929231, 0.432592 0.0051942766 0.034924194, 0.43229708 0.0051471889 0.035126194, 0.43256539 0.005253002 0.034907892, 0.43232441 0.0050934404 0.035134301, 0.4323459 0.0050364137 0.035132274, 0.43236008 0.0049785525 0.035119876, 0.43213603 0.0050596446 0.035245493, 0.43216437 0.0050095022 0.03524895, 0.43218765 0.0049571544 0.03524287, 0.43220481 0.0049042404 0.035227612, 0.43281478 0.0050825924 0.034587577, 0.4327116 0.0050453395 0.034821138, 0.43270645 0.0050964057 0.034838513, 0.4327763 0.0050572753 0.034709677, 0.43269375 0.0051472485 0.034850225, 0.43277386 0.005111903 0.034736559, 0.4328182 0.0051401109 0.03462179, 0.43266916 0.0052072257 0.034855172, 0.43276039 0.0051670969 0.034757689, 0.43280694 0.0051986873 0.034652874, 0.43278185 0.0052552819 0.034678742, 0.43262878 0.0052716434 0.034848884, 0.43273047 0.0052319169 0.034774825, 0.4327437 0.0053071529 0.034698293, 0.43267849 0.0052999705 0.03478153, 0.43269494 0.005351752 0.034710154, 0.43261436 0.0053530633 0.034773991, 0.43281955 0.0056073964 0.034005806, 0.43288282 0.0055924505 0.033625856, 0.43283567 0.0056402087 0.033625856, 0.43286699 0.0055599511 0.034001663, 0.43277219 0.0055100173 0.034371659, 0.43282005 0.0054637194 0.034363315, 0.43293956 0.0053383112 0.033625856, 0.43288326 0.0052229315 0.034287319, 0.43288901 0.005285427 0.034310982, 0.43292543 0.005309239 0.033962861, 0.4328801 0.0053485483 0.034332201, 0.4329327 0.0053748339 0.033974811, 0.43294731 0.0054051578 0.033625856, 0.43285665 0.0054089427 0.034350023, 0.43292502 0.0054407716 0.033985481, 0.43294016 0.005471915 0.033625945, 0.43290278 0.0055035353 0.033994749, 0.4329184 0.005535394 0.033625945, 0.43293944 0.0053396225 0.013633326, 0.43294731 0.0054062307 0.013633326, 0.4329401 0.0054731667 0.013633326, 0.43291837 0.0055365115 0.013633355, 0.43288285 0.0055936575 0.013633326, 0.43283564 0.0056414157 0.013633326, 0.43277207 0.0055111945 0.012887463, 0.4327437 0.0053083897 0.012560919, 0.43269488 0.0053529888 0.01254867, 0.43282005 0.0054649264 0.012895808, 0.43281955 0.0056085438 0.013253406, 0.43286696 0.0055611432 0.013257608, 0.43292534 0.0053104907 0.013296351, 0.43293265 0.0053761303 0.013284311, 0.43288314 0.0052241236 0.012971953, 0.43281481 0.0050837398 0.012671575, 0.43292502 0.0054419339 0.013273492, 0.43288901 0.0052867383 0.012948141, 0.43281808 0.0051413625 0.012637004, 0.43290269 0.0055046976 0.013264403, 0.43288007 0.0053497851 0.012926802, 0.43280688 0.0051999092 0.012606099, 0.43285662 0.0054101646 0.01290904, 0.43278173 0.0052565038 0.012580469, 0.4326202 0.0050663054 0.012336448, 0.43256542 0.0052542686 0.01235126, 0.43277621 0.0050585717 0.012549475, 0.43277386 0.0051131845 0.012522414, 0.43271145 0.0050465465 0.012438014, 0.43276039 0.0051683038 0.012501374, 0.43270639 0.0050976276 0.012420282, 0.43261045 0.0051318258 0.012329683, 0.43273044 0.0052331835 0.012484178, 0.43269375 0.0051485449 0.012408987, 0.43259189 0.005195573 0.012334928, 0.43267849 0.0053012073 0.012477383, 0.43266928 0.0052084476 0.012403801, 0.4326143 0.005354315 0.012484923, 0.43262872 0.0052728355 0.01241003, 0.43236005 0.0049798042 0.012139186, 0.43234578 0.005037725 0.012126938, 0.4323245 0.0050946474 0.012124762, 0.43229702 0.0051484853 0.012132958, 0.43220478 0.0049055368 0.012031391, 0.43205342 0.004828468 0.01193209, 0.43218753 0.004958421 0.012016043, 0.43202558 0.0048886538 0.011913672, 0.43216437 0.0050108582 0.012010112, 0.43199024 0.0049474984 0.011908874, 0.43213597 0.0050609559 0.012013659, 0.47022453 0.081904382 0.063114718, 0.47006789 0.081691802 0.063469306, 0.47016281 0.081886172 0.063095167, 0.4702214 0.08200638 0.062684193, 0.47009739 0.081881821 0.063080654, 0.47015497 0.081999913 0.062676683, 0.47022223 0.081767455 0.063568011, 0.47008502 0.081486061 0.063915089, 0.47004649 0.081457734 0.063868031, 0.469816 0.08144936 0.063747302, 0.47017983 0.081731096 0.063530788, 0.47027943 0.081935346 0.063137904, 0.47012755 0.081705362 0.063497409, 0.47028455 0.082027256 0.062694028, 0.47032478 0.081977665 0.063163653, 0.47034097 0.082061604 0.06270583, 0.47038808 0.082107604 0.062719002, 0.46993932 0.081702411 0.063435331, 0.47000411 0.081690699 0.063448444, 0.46987948 0.081434995 0.063763842, 0.4700315 0.081891418 0.063071713, 0.46994108 0.081431463 0.063790455, 0.47008839 0.082008287 0.062672094, 0.46999767 0.081439197 0.063825741, 0.46752366 0.076234818 0.0691659, 0.46748507 0.076206505 0.069118604, 0.46743631 0.076187924 0.069076434, 0.4673796 0.076180294 0.06904088, 0.46731791 0.076183826 0.069014564, 0.46725458 0.07619828 0.068997964, 0.46732828 0.075834394 0.069477186, 0.46710578 0.075378075 0.069671884, 0.46707901 0.075374112 0.069610372, 0.46729529 0.075817361 0.069421485, 0.46666631 0.074992135 0.069512352, 0.46687898 0.075428128 0.069452837, 0.46693829 0.075405136 0.069474563, 0.46672317 0.07496427 0.069534406, 0.46707901 0.075838178 0.069277897, 0.46699312 0.075387925 0.069509134, 0.4667744 0.07493937 0.069570258, 0.46714047 0.075819775 0.069297746, 0.46704081 0.075377494 0.069554999, 0.46681699 0.074918583 0.069617614, 0.46719891 0.075809866 0.069329098, 0.46684909 0.074902862 0.069674507, 0.46725145 0.075809106 0.069370881, 0.46686909 0.074893206 0.069737896, 0.43521044 0.009991765 0.06973435, 0.43519041 0.010001495 0.069670901, 0.43515828 0.010017157 0.069614157, 0.43511572 0.010037914 0.069566563, 0.43506452 0.010062888 0.069530711, 0.43500754 0.010090739 0.069508687, 0.43464684 0.0092065036 0.069293156, 0.43441862 0.0088834465 0.068992838, 0.43459439 0.0092436969 0.069273606, 0.43446901 0.0088423491 0.069009528, 0.43440184 0.0083847344 0.068714395, 0.43429646 0.0081689656 0.068243131, 0.43428791 0.0082326829 0.06822367, 0.43439031 0.0084427595 0.068682536, 0.4341805 0.008395344 0.068187729, 0.43479469 0.0096541941 0.069448933, 0.43453842 0.0087465346 0.069071248, 0.43436489 0.0084990412 0.068655953, 0.43450972 0.0087959021 0.069035903, 0.43469059 0.0091664195 0.069324806, 0.43439871 0.008327812 0.0687498, 0.43429035 0.008105725 0.068264708, 0.43484929 0.0096214712 0.06947042, 0.43455389 0.0086966157 0.069113567, 0.43472341 0.0091256648 0.069366679, 0.43489665 0.0095888972 0.06950523, 0.4345552 0.0086487383 0.069160774, 0.43474385 0.0090859234 0.069416896, 0.43493423 0.0095577538 0.069551215, 0.43475077 0.009049505 0.069472894, 0.43496034 0.0095297396 0.069606408, 0.43497363 0.0095061362 0.06966804, 0.43427789 0.0085949004 0.068623528, 0.43432668 0.0085506588 0.068635926, 0.43422827 0.0083487779 0.068195328, 0.43426457 0.0082937032 0.068207487, 0.43305206 0.0055674464 0.060504302, 0.43305823 0.0056308061 0.060482547, 0.43304947 0.0056945235 0.060462967, 0.4330264 0.0057554394 0.060446814, 0.43299004 0.0058105737 0.060434476, 0.43294212 0.0058571547 0.060426995, 0.43283823 0.0056441128 0.059970215, 0.43281761 0.0054572076 0.059783593, 0.43276772 0.00549981 0.059768692, 0.43288729 0.0055999458 0.059982941, 0.43289667 0.0057639629 0.060190991, 0.43294513 0.0057183802 0.060201094, 0.4330118 0.0054848194 0.060294911, 0.43301651 0.005545184 0.060265675, 0.43295985 0.005378738 0.060099199, 0.43289748 0.0052506328 0.059920475, 0.43300647 0.0056063086 0.060239598, 0.43296283 0.0054351836 0.060063109, 0.43289807 0.0053025931 0.059877828, 0.43298224 0.0056649894 0.060217634, 0.432951 0.0054928213 0.060030594, 0.43288442 0.0053560734 0.059839562, 0.43292555 0.0055486709 0.060003534, 0.43285719 0.0054084659 0.059807673, 0.43277946 0.0051880777 0.059690312, 0.43277007 0.0052330792 0.059667364, 0.43273219 0.0051807761 0.059638217, 0.43267983 0.0051925331 0.059589401, 0.43275434 0.0052782446 0.059650674, 0.43272254 0.0052235723 0.059620991, 0.43266496 0.0052494109 0.059576228, 0.43270835 0.0052660406 0.059609607, 0.43264315 0.0053056479 0.059573099, 0.43272728 0.0053322762 0.059638217, 0.43268526 0.0053168088 0.05960305, 0.43268588 0.0053916872 0.059636667, 0.43265089 0.0053730905 0.05960612, 0.43261543 0.0053587556 0.059580281, 0.43234518 0.0051756799 0.059384033, 0.43238053 0.0051168501 0.059388772, 0.4324083 0.0050566196 0.059407309, 0.43900713 0.12923355 0.087888047, 0.43900725 0.12921001 0.087564543, 0.43900725 0.12930383 0.088204965, 0.43902934 0.12936457 0.088186845, 0.43902937 0.12929641 0.087878928, 0.43923292 0.12943575 0.087564543, 0.43900713 0.12941922 0.088508233, 0.43923292 0.12952012 0.088140234, 0.43923292 0.12962385 0.088412747, 0.43916944 0.12949879 0.088146552, 0.43916944 0.1296037 0.088422284, 0.43923292 0.12945691 0.087855473, 0.43911275 0.12946457 0.088156804, 0.43911263 0.12957132 0.088437185, 0.4391695 0.12943497 0.087858662, 0.43916944 0.12941356 0.087564543, 0.43906504 0.12941904 0.088170633, 0.43906513 0.12952825 0.088457331, 0.43911263 0.12939957 0.087863907, 0.43911266 0.1293778 0.087564543, 0.43902931 0.12947662 0.088481471, 0.43906519 0.12935261 0.087870732, 0.43906513 0.12933029 0.087564543, 0.43902934 0.12927347 0.087564543, 0.43900719 0.1292199 -0.087548897, 0.43902934 0.12928329 -0.087548897, 0.43906513 0.12934019 -0.087548897, 0.43911266 0.1293876 -0.087548688, 0.43916944 0.12942348 -0.087548897, 0.43923283 0.12944564 -0.087548897, 0.43923292 0.12983052 0.088856444, 0.43916947 0.12981042 0.088865623, 0.43911266 0.12977798 0.088880882, 0.43906504 0.12973498 0.08890079, 0.43902934 0.12968348 0.088924959, 0.43900725 0.12962599 0.088951692, 0.43900719 0.12931381 -0.088189319, 0.43902934 0.12937455 -0.08817111, 0.43902943 0.12948667 -0.088465884, 0.43900719 0.12924354 -0.08787246, 0.43902934 0.12930627 -0.087863281, 0.43923292 0.12963383 -0.08839725, 0.43900719 0.12942921 -0.088492617, 0.43923298 0.12946686 -0.087839916, 0.43916944 0.12944493 -0.087842926, 0.4392328 0.1295301 -0.088124648, 0.43911266 0.12940954 -0.087848023, 0.4391695 0.12950873 -0.088130906, 0.43916944 0.12961373 -0.088406637, 0.43906519 0.12936254 -0.087855116, 0.43911263 0.12947455 -0.088141188, 0.43911263 0.12958132 -0.088421807, 0.43906513 0.12942901 -0.088154778, 0.43906516 0.12953819 -0.088441715, 0.43902943 0.1311619 0.090122208, 0.43902931 0.13164996 0.09017776, 0.43906513 0.13117459 0.090066895, 0.43923292 0.13006799 0.089243844, 0.43923292 0.13038661 0.089568123, 0.4390651 0.13072367 0.089907035, 0.43911251 0.1311854 0.090020403, 0.43911263 0.13074443 0.089864597, 0.43911266 0.13035013 0.089613065, 0.43916944 0.13076028 0.089832172, 0.43916944 0.13037275 0.089585289, 0.43900725 0.13114762 0.090184078, 0.43900713 0.13164994 0.090241298, 0.43916947 0.13005063 0.089257464, 0.43902931 0.13069877 0.089958146, 0.43906501 0.13032024 0.08965005, 0.43911263 0.1300223 0.089279756, 0.43900713 0.13067093 0.090015128, 0.43902934 0.13028441 0.089694247, 0.43906513 0.12998496 0.089308962, 0.43900719 0.13024454 0.089743569, 0.43902934 0.12994011 0.089343771, 0.43900725 0.12989016 0.089382634, 0.43923298 0.13119832 0.089964017, 0.43923292 0.13164994 0.090015516, 0.4391695 0.13119334 0.089985773, 0.43916944 0.13165 0.090037689, 0.43911251 0.13164991 0.090073332, 0.43923292 0.13076994 0.089812234, 0.43906513 0.13164988 0.090120867, 0.43900725 0.12963594 -0.088935956, 0.43902934 0.12969346 -0.088909104, 0.43906513 0.12974502 -0.088885173, 0.43911266 0.12978806 -0.088865176, 0.4391695 0.12982042 -0.088850006, 0.43923292 0.12984057 -0.088840589, 0.43923283 0.14020714 0.090015993, 0.43916935 0.14020713 0.090038165, 0.43911263 0.14020714 0.090074077, 0.43906507 0.14020711 0.090121374, 0.43902937 0.14020716 0.090178266, 0.43900719 0.14020713 0.090241894, 0.43902937 0.12995008 -0.089328036, 0.43906513 0.12999494 -0.089292869, 0.43923292 0.13120839 -0.089948282, 0.4392328 0.13166007 -0.089999542, 0.43923303 0.13077994 -0.089796379, 0.43906513 0.13033031 -0.089634165, 0.43911266 0.13003229 -0.089263663, 0.43911263 0.13036016 -0.08959721, 0.43911266 0.13075452 -0.089848474, 0.43916953 0.13038266 -0.089569494, 0.43916959 0.13077028 -0.089816436, 0.43900719 0.1299002 -0.089367136, 0.4391695 0.1312035 -0.089969859, 0.43916944 0.13166007 -0.090021834, 0.43902943 0.13029449 -0.089678392, 0.4390651 0.13073374 -0.0898913, 0.43911263 0.13119546 -0.090004668, 0.43911275 0.13166 -0.090057507, 0.43900731 0.13025454 -0.089727595, 0.43902937 0.13070878 -0.089942351, 0.43906516 0.13118462 -0.090050802, 0.43906525 0.13166004 -0.090104893, 0.43900719 0.13068113 -0.089999333, 0.43902937 0.13117199 -0.090106264, 0.43902925 0.13166001 -0.090161875, 0.43900713 0.13115768 -0.090168163, 0.43900713 0.13166001 -0.090225324, 0.43923295 0.13007797 -0.089228198, 0.4391695 0.13006057 -0.089241818, 0.43923292 0.13039665 -0.089552358, 0.43902934 0.14188744 0.08938159, 0.43900716 0.1422046 0.089007393, 0.43902937 0.14214788 0.08897911, 0.43906513 0.14184329 0.089345559, 0.43923274 0.14064807 0.089966998, 0.43923283 0.14200272 0.088906363, 0.43923274 0.14106743 0.089822277, 0.43906504 0.14150974 0.089672312, 0.43911257 0.14180653 0.089315519, 0.43911254 0.14148042 0.089634761, 0.43911263 0.14109227 0.08987473, 0.43916944 0.14145845 0.089606747, 0.43916938 0.14107695 0.089842334, 0.43900719 0.14193653 0.089421704, 0.43916938 0.14065294 0.089988604, 0.43902925 0.14154482 0.089716986, 0.43906507 0.14111257 0.089917645, 0.43911257 0.14066079 0.090023592, 0.43900719 0.14158392 0.089766845, 0.43902937 0.14113691 0.089969024, 0.43906507 0.14067116 0.090069875, 0.43900719 0.14116412 0.090026364, 0.43902937 0.14068373 0.090125307, 0.43900716 0.14069755 0.090187237, 0.43923286 0.14176168 0.089278921, 0.43916944 0.14202255 0.088916287, 0.43916938 0.14177893 0.08929275, 0.43911257 0.14205454 0.088932261, 0.43923277 0.14144476 0.089589313, 0.43906507 0.14209698 0.08895357, 0.43900716 0.14021726 -0.090224937, 0.43902937 0.14021719 -0.090161428, 0.43906507 0.14021727 -0.090104505, 0.43911257 0.14021719 -0.09005706, 0.43916947 0.14021717 -0.090021357, 0.43923274 0.14021729 -0.089999184, 0.43923286 0.14223878 0.088434234, 0.4391695 0.14225867 0.088444009, 0.4391126 0.14229062 0.088460162, 0.43906501 0.14233306 0.088481411, 0.43902937 0.14238396 0.088506952, 0.43900707 0.14244066 0.088535056, 0.43916938 0.1414685 -0.08958964, 0.43916938 0.14108703 -0.089825675, 0.43923274 0.14107746 -0.08980532, 0.43923286 0.14145485 -0.089572176, 0.43902934 0.1406938 -0.090108559, 0.43906504 0.14068128 -0.090052947, 0.43923286 0.1417717 -0.089261636, 0.43923286 0.14201277 -0.088889226, 0.43906507 0.14112264 -0.089900568, 0.43911263 0.14067081 -0.090006575, 0.43911251 0.14110228 -0.089857683, 0.43911254 0.14149049 -0.089617744, 0.43900719 0.14070767 -0.090170279, 0.43916941 0.14178894 -0.089275971, 0.43916935 0.14203264 -0.088899329, 0.43902937 0.14114708 -0.089952007, 0.43906519 0.14151974 -0.089655176, 0.43911257 0.14181659 -0.089298412, 0.43911257 0.1420645 -0.088915184, 0.43900707 0.14117426 -0.090009466, 0.43902937 0.14155489 -0.089699909, 0.43906507 0.14185342 -0.089328393, 0.43906501 0.14210702 -0.088936374, 0.43900719 0.14159404 -0.089749977, 0.43902925 0.14189743 -0.089364395, 0.43902937 0.14215788 -0.088961855, 0.43900719 0.14194658 -0.089404628, 0.43900707 0.14221463 -0.088990286, 0.43923289 0.14065818 -0.08995007, 0.43916944 0.140663 -0.089971766, 0.43900719 0.14257063 0.088215664, 0.43900719 0.14264986 0.087880358, 0.43902934 0.14251027 0.088196561, 0.43902931 0.1425872 0.087870464, 0.43923283 0.14242682 0.087845549, 0.4392328 0.14245078 0.087536439, 0.43916941 0.14244871 0.087848887, 0.43916938 0.14247289 0.087536439, 0.43923286 0.14235561 0.088147148, 0.43911254 0.1424841 0.08785437, 0.43911263 0.14250864 0.087536469, 0.43916941 0.14237677 0.088153705, 0.43906504 0.14253101 0.087861672, 0.43906501 0.14255626 0.087536439, 0.43911251 0.14241078 0.088164672, 0.43902934 0.14261317 0.087536469, 0.43906501 0.14245608 0.088179246, 0.43900704 0.14267662 0.087536439, 0.43900707 0.14245066 -0.088518128, 0.43902937 0.14239399 -0.088489756, 0.43906495 0.14234309 -0.088464364, 0.43911263 0.14230058 -0.088443086, 0.43916944 0.1422686 -0.088427022, 0.43923283 0.14224879 -0.088417158, 0.43900719 0.14268643 -0.087519422, 0.43902931 0.14262302 -0.087519601, 0.43906507 0.14256613 -0.087519422, 0.43911257 0.14251851 -0.087519422, 0.43916944 0.14248286 -0.087519363, 0.43923286 0.14246058 -0.087519273, 0.43923274 0.14236557 -0.088129982, 0.43916938 0.1423867 -0.088136777, 0.43923286 0.14243668 -0.087828413, 0.43911263 0.14242074 -0.088147596, 0.43916944 0.14245871 -0.08783184, 0.43906507 0.14246611 -0.088162169, 0.43911263 0.14249399 -0.087837264, 0.43902925 0.14252017 -0.088179454, 0.4390651 0.14254095 -0.087844625, 0.43900716 0.14258058 -0.088198766, 0.43902934 0.14259715 -0.087853298, 0.43900719 0.14265981 -0.087863192, 0.41299999 0.065780297 -0.069531187, 0.41299996 0.08048664 -0.054823413, 0.41300008 0.065772563 0.0695398, 0.41299996 0.080480516 0.054833487, 0.4130002 0.062236845 0.071004108, 0.41299999 0.081945196 0.051298127, 0.4129999 0.081849158 0.052273616, 0.41300011 0.06321229 0.070908174, 0.41299996 0.081564397 0.053211316, 0.41300014 0.064150274 0.070623592, 0.41299996 0.081102341 0.054075912, 0.41300008 0.065014824 0.070161566, 0.41299996 0.081950933 -0.051287755, 0.41300014 0.062244892 -0.070996001, 0.41300008 0.063220337 -0.07089971, 0.41300011 0.064158291 -0.070615247, 0.41299996 0.065022677 -0.070153132, 0.41299996 0.081108421 -0.05406557, 0.41299996 0.081570432 -0.053201213, 0.41299996 0.08185488 -0.052263126, 0.41300043 0.0080325902 -0.070999011, 0.41300043 0.0080245733 0.071000949, 0.41300049 0.0031577647 -0.067111954, 0.41300043 0.0030323267 -0.065999374, 0.41300043 0.0035276562 -0.068168715, 0.41300049 0.0041233599 -0.069116667, 0.41300043 0.0049151182 -0.069908455, 0.41300046 0.0058631152 -0.070503935, 0.41300043 0.0069200099 -0.070873752, 0.41300049 0.0030248463 0.066000834, 0.41300049 0.0035198629 0.068170205, 0.41300043 0.0041155964 0.069118157, 0.41300043 0.0031501502 0.067113355, 0.41300052 0.0049072355 0.069910184, 0.41300046 0.005855158 0.070505723, 0.41300046 0.0069120675 0.07087563, 0.41357735 -0.015435889 -0.060650304, 0.41447923 -0.0136507 -0.060650304, 0.41357729 -0.015442699 0.060649708, 0.41447908 -0.013657436 0.060649708, 0.41518417 -0.016246825 -0.074228004, 0.41608587 -0.014461592 -0.074228004, 0.41608596 -0.014469907 0.074227557, 0.41518417 -0.016255051 0.074227408, 0.41608593 -0.014462262 -0.062450215, 0.41608593 -0.014469355 0.062449649, 0.41447908 -0.013656005 0.033864543, 0.41608599 -0.014467672 0.032064423, 0.41447917 -0.013654873 0.013392404, 0.41608593 -0.014466614 0.015192226, 0.41447911 -0.013653398 -0.01339291, 0.41608593 -0.01446493 -0.015192881, 0.41447917 -0.013652265 -0.033865109, 0.41608587 -0.014463916 -0.032065138, 0.41518423 -0.016247481 -0.062450215, 0.41518423 -0.016254544 0.06244947, 0.41357735 -0.015441239 0.033864334, 0.41518423 -0.016252905 0.032064423, 0.41518423 -0.016251832 0.015192136, 0.41357735 -0.015440062 0.013392285, 0.41357729 -0.015438527 -0.01339291, 0.41518417 -0.016250089 -0.015192881, 0.41357729 -0.01543735 -0.033865228, 0.41518417 -0.01624915 -0.032065138, 0.47534749 0.13797118 -0.1702749, 0.47526959 0.13805678 -0.1702287, 0.47534588 0.13802773 -0.17030524, 0.47527274 0.13800158 -0.17019801, 0.47508171 0.13813213 -0.16986303, 0.47502708 0.138243 -0.16972031, 0.47507152 0.13818178 -0.16989173, 0.47518733 0.13805921 -0.16959493, 0.47523278 0.13814066 -0.1693794, 0.47516942 0.13816045 -0.16938917, 0.47545156 0.13804612 -0.17039992, 0.47513816 0.13808304 -0.1696171, 0.47535136 0.13807537 -0.17032276, 0.47500721 0.13834253 -0.16948022, 0.47534525 0.13791476 -0.16983525, 0.47514924 0.13816497 -0.17007814, 0.47507116 0.13822345 -0.16991283, 0.4752861 0.13797785 -0.16970776, 0.47522292 0.13799079 -0.16973828, 0.47528455 0.13792445 -0.16987668, 0.47502932 0.13828571 -0.16945176, 0.47511119 0.13807301 -0.1698222, 0.47507364 0.13814025 -0.16965915, 0.47504088 0.1381962 -0.16969408, 0.4753181 0.13789883 -0.17010419, 0.47517881 0.13800654 -0.16998117, 0.47529265 0.13793673 -0.17014693, 0.47520837 0.13796949 -0.16994481, 0.4754459 0.13799751 -0.17038397, 0.47514674 0.13812096 -0.17005755, 0.47514328 0.138037 -0.16979183, 0.47510701 0.13810568 -0.16963492, 0.47536466 0.1379049 -0.17022182, 0.4752501 0.13804376 -0.16957428, 0.47534367 0.13787606 -0.17006911, 0.4752374 0.13794656 -0.16991596, 0.47517398 0.13801399 -0.16976862, 0.4754464 0.13793938 -0.17035417, 0.47515342 0.13806857 -0.17002742, 0.47538754 0.13786663 -0.17017616, 0.47538587 0.13785587 -0.17001973, 0.47541079 0.1378441 -0.17013799, 0.47546038 0.13787189 -0.17029931, 0.4754408 0.13785015 -0.16996564, 0.47544935 0.13782509 -0.17008381, 0.47527441 0.13810322 -0.17024736, 0.47547981 0.13783333 -0.17025067, 0.47502342 0.13828243 -0.16974084, 0.47506514 0.13823499 -0.16942646, 0.47511259 0.13819242 -0.16940515, 0.47500858 0.15568283 -0.13478042, 0.47503391 0.15561652 -0.13476492, 0.4750711 0.15556152 -0.13475169, 0.47511986 0.15551578 -0.13474096, 0.4751766 0.15548238 -0.13473313, 0.4752368 0.15546274 -0.13472836, 0.47526857 0.15545765 -0.13472719, 0.47500703 0.15568812 -0.11477502, 0.47502932 0.15562476 -0.11477517, 0.47506496 0.15556785 -0.11477502, 0.47511241 0.15552035 -0.11477502, 0.47516939 0.15548457 -0.11477502, 0.47523275 0.15546238 -0.11477502, 0.47429809 0.15548439 -0.11190279, 0.47369996 0.15546218 -0.11107449, 0.47365519 0.15548432 -0.11111943, 0.47477588 0.15548442 -0.11279668, 0.47483447 0.15546229 -0.11277233, 0.47435072 0.15546227 -0.11186753, 0.47464642 0.15562454 -0.11285023, 0.47493267 0.15562481 -0.11379372, 0.47496757 0.15556778 -0.1137868, 0.47467944 0.15556772 -0.11283641, 0.47425082 0.15552016 -0.11193444, 0.47361496 0.15552023 -0.1111597, 0.47472325 0.15552023 -0.11281841, 0.47462586 0.15568802 -0.11285858, 0.47491077 0.1556882 -0.11379816, 0.47421125 0.15556768 -0.11196075, 0.47358137 0.15556759 -0.11119317, 0.47418162 0.15562464 -0.1119809, 0.47355607 0.15562454 -0.11121835, 0.47416317 0.15568791 -0.11199294, 0.47354046 0.15568793 -0.11123405, 0.47513232 0.15546238 -0.11375396, 0.47507003 0.15548456 -0.11376642, 0.47501412 0.15552035 -0.11377756, 0.45646933 0.15568681 -0.094162986, 0.45648506 0.15562344 -0.094147488, 0.45651034 0.1555665 -0.094122157, 0.45654398 0.15551904 -0.09408848, 0.45658407 0.15548328 -0.094048277, 0.45662883 0.1554611 -0.094003603, 0.45548448 0.15551902 -0.092503086, 0.45520636 0.15551898 -0.091586396, 0.45515975 0.15556642 -0.091595516, 0.45586702 0.15562341 -0.093394265, 0.45540765 0.1556233 -0.092534915, 0.45538703 0.15568677 -0.092543378, 0.45584837 0.15568677 -0.093406484, 0.45553705 0.15548317 -0.09248127, 0.45526221 0.15548313 -0.09157519, 0.45589659 0.15556648 -0.093374386, 0.45544055 0.15556648 -0.092521265, 0.45559564 0.15546109 -0.092457041, 0.45532438 0.15546103 -0.091562852, 0.45593616 0.15551902 -0.093347952, 0.45598343 0.15548328 -0.093316451, 0.45603618 0.1554611 -0.093281165, 0.45510301 0.15568665 -0.09160687, 0.45500705 0.15568659 -0.090632811, 0.45512477 0.1556233 -0.091602489, 0.45502934 0.1556233 -0.09063296, 0.45506492 0.15556642 -0.09063296, 0.45511249 0.15551884 -0.09063296, 0.45516941 0.1554831 -0.09063296, 0.45523265 0.15546097 -0.09063296, 0.45500705 0.15567653 0.090651497, 0.45502922 0.15561311 0.090651497, 0.45506498 0.15555623 0.090651497, 0.45511243 0.15550873 0.090651497, 0.45516935 0.15547296 0.090651497, 0.45523277 0.15545087 0.090651497, 0.45512471 0.15561296 0.091621146, 0.45510301 0.15567634 0.091625556, 0.45540753 0.15561293 0.092553481, 0.45538703 0.15567634 0.092562124, 0.45553705 0.15547279 0.092500016, 0.45598337 0.15547277 0.093335196, 0.45593616 0.15550852 0.093366459, 0.45646933 0.15567626 0.094181642, 0.45548442 0.15550856 0.092521831, 0.45515975 0.15555608 0.091614231, 0.45544055 0.15555601 0.092539772, 0.45559552 0.15545061 0.092475608, 0.45603612 0.15545061 0.093299761, 0.45520636 0.15550861 0.091604933, 0.45526209 0.15547286 0.091593668, 0.45532426 0.15545075 0.091581419, 0.45584854 0.15567622 0.093425319, 0.45648494 0.15561292 0.094165787, 0.45586699 0.15561295 0.093412623, 0.45651028 0.15555599 0.094140753, 0.45589653 0.15555599 0.093393072, 0.45654383 0.15550855 0.094107226, 0.4565841 0.15547274 0.094066814, 0.45662889 0.15545055 0.094021901, 0.47370002 0.15544978 0.11109324, 0.47365519 0.15547189 0.11113806, 0.4736149 0.15550765 0.11117812, 0.47358134 0.15555516 0.11121173, 0.47355616 0.15561201 0.11123727, 0.47354051 0.15567543 0.11125292, 0.47507003 0.15547174 0.11378498, 0.47523269 0.15544966 0.11479367, 0.47516939 0.15547171 0.11479367, 0.47477585 0.15547171 0.11281539, 0.47483441 0.15544951 0.11279105, 0.47513214 0.15544958 0.11377262, 0.47464639 0.15561195 0.11286877, 0.47418144 0.15561204 0.11199911, 0.47421131 0.15555508 0.11197947, 0.47467938 0.15555502 0.11285533, 0.47501418 0.15550746 0.11379622, 0.47511247 0.15550743 0.11479367, 0.47472331 0.15550748 0.11283706, 0.4746258 0.15567532 0.11287735, 0.47416314 0.15567537 0.11201166, 0.47496757 0.15555494 0.11380543, 0.47506496 0.15555494 0.11479367, 0.47493264 0.15561196 0.11381243, 0.47502926 0.15561184 0.11479367, 0.47491089 0.15567523 0.11381678, 0.47500697 0.1556752 0.11479367, 0.47435078 0.15544966 0.11188598, 0.47429809 0.15547188 0.11192138, 0.47425088 0.15550762 0.11195301, 0.47526863 0.15544245 0.13474591, 0.4752368 0.15544745 0.13474704, 0.4751766 0.15546718 0.13475163, 0.47511992 0.1555005 0.13475938, 0.47507125 0.15554637 0.1347702, 0.47503397 0.15560129 0.13478334, 0.47500852 0.15566762 0.13479896, 0.47523287 0.13812162 0.16939588, 0.47516945 0.13814142 0.1694058, 0.47511259 0.13817331 0.16942181, 0.47506514 0.13821585 0.16944323, 0.47502944 0.13826677 0.16946842, 0.47500721 0.1383234 0.16949691, 0.47542998 0.13781515 0.17015626, 0.47540736 0.1378244 0.17007221, 0.47545612 0.13780235 0.17011826, 0.47532293 0.13791408 0.16981633, 0.47536448 0.13791534 0.16979508, 0.47537926 0.1378378 0.17010783, 0.47525409 0.13800961 0.16962294, 0.47532347 0.13790318 0.17019765, 0.47527805 0.13792498 0.17014624, 0.47531044 0.13788038 0.17009549, 0.47504851 0.1381602 0.16974874, 0.47507992 0.13810559 0.16971384, 0.47535375 0.13785848 0.17014422, 0.47525695 0.13792685 0.16985796, 0.47518674 0.13802671 0.16964807, 0.47540632 0.13783558 0.17019479, 0.47525799 0.137987 0.17019512, 0.47512946 0.13806573 0.16999494, 0.4751555 0.13800687 0.16995154, 0.47503635 0.13820137 0.16977249, 0.47547534 0.13779774 0.17019354, 0.47525397 0.13803475 0.17022271, 0.47512165 0.13811047 0.17002146, 0.47522369 0.13794215 0.169883, 0.47515249 0.13804297 0.1696644, 0.47503176 0.13824536 0.16979565, 0.47545347 0.13781799 0.17023383, 0.47519317 0.1379635 0.16990988, 0.4751209 0.13806424 0.16968311, 0.47537854 0.1378805 0.17025097, 0.47546408 0.13784289 0.16993998, 0.47530505 0.13796611 0.17024805, 0.47525802 0.13808544 0.17024468, 0.4751223 0.13815807 0.17004485, 0.47542676 0.13783778 0.16997059, 0.47530201 0.13801463 0.17027541, 0.47542778 0.13786308 0.1702918, 0.47546414 0.13781781 0.17001079, 0.47536209 0.1379443 0.17030276, 0.47530666 0.13806613 0.17029668, 0.47547618 0.13784808 0.17032681, 0.4753671 0.13784571 0.17002736, 0.47536001 0.13799371 0.17033009, 0.47533745 0.13785951 0.17006086, 0.47541311 0.1379275 0.1703447, 0.47536489 0.13804628 0.17035042, 0.47529659 0.13800706 0.16961132, 0.47541156 0.1379775 0.17037185, 0.475463 0.1379132 0.1703804, 0.47546193 0.13796367 0.17040725, 0.47541675 0.13803078 0.1703914, 0.47546712 0.13801762 0.17042612, -0.4110001 0.036265314 0.13386779, -0.4110001 0.036040559 0.13378279, -0.41100007 0.035842508 0.13364656, -0.41100019 0.035682917 0.13346712, -0.4110001 0.036503837 0.13389651, -0.4110001 0.038325071 0.13201244, -0.41100052 0.10735171 0.1339006, -0.41100094 0.15327263 0.13384254, -0.41100082 0.15310387 0.13388796, -0.41100082 0.15293553 0.13390319, -0.41100088 0.15343539 0.132019, -0.411001 0.15343526 0.13376866, -0.4110001 0.03605561 -0.13377751, -0.41100007 0.035697728 -0.13346209, -0.4110001 0.035857603 -0.13364162, -0.4110001 0.036280364 -0.13386263, -0.4110001 0.036518887 -0.13389148, -0.4110001 0.038339943 -0.13200726, -0.41100052 0.10736687 -0.13388743, -0.41100082 0.15295057 -0.13388483, -0.41100082 0.1534501 -0.13200061, -0.41100085 0.15328768 -0.13382427, -0.41100088 0.15311895 -0.13386984, -0.41100082 0.15345024 -0.13375045, -0.41099963 -0.035561606 0.076308563, -0.41099963 -0.035366014 0.076902673, -0.41099963 -0.035472944 0.076720163, -0.41099966 -0.03553921 0.076519147, -0.41099966 -0.035539508 0.062255934, -0.41099966 -0.035560787 0.062461153, -0.41099963 -0.035558492 0.062392369, -0.41099975 -0.035551295 0.062323704, -0.41099963 -0.035556823 0.032119527, -0.41099963 -0.035537913 0.032255903, -0.41099963 -0.035549656 0.032187924, -0.41099963 -0.035559162 0.032050744, -0.41099963 -0.035548538 0.012566403, -0.41099966 -0.035558105 0.012703761, -0.41099963 -0.035555705 0.012634948, -0.41099966 -0.035536766 0.012498513, -0.41099963 -0.035556644 -0.012706891, -0.41099957 -0.03553538 -0.012501463, -0.41099963 -0.035547107 -0.012569323, -0.41099963 -0.035554275 -0.012637839, -0.41099975 -0.035534129 -0.032258853, -0.41099963 -0.035553187 -0.032122359, -0.41099963 -0.03554602 -0.032190904, -0.41099963 -0.035555497 -0.032053486, -0.41099963 -0.035551503 -0.06239526, -0.41099963 -0.035532504 -0.062258795, -0.41099963 -0.035544306 -0.062326744, -0.41099966 -0.035553753 -0.062464193, -0.41099963 -0.035464436 -0.076723173, -0.41099963 -0.035553053 -0.076311573, -0.41099963 -0.035530671 -0.076522067, -0.41099966 -0.035357356 -0.076905683, -0.48558918 0.15099671 -0.14363451, -0.4855893 0.15116926 -0.14328946, -0.48293993 0.1505474 -0.14453323, -0.48400101 0.15179837 -0.14203082, -0.48268399 0.15067647 -0.14427485, -0.48325729 0.15044935 -0.14472924, -0.48250493 0.15082921 -0.14396949, -0.48549691 0.1513367 -0.14295442, -0.48438376 0.15177765 -0.14207233, -0.48361799 0.15038814 -0.14485149, -0.48531762 0.15148933 -0.14264913, -0.48474446 0.15171647 -0.14219494, -0.4824124 0.15099666 -0.14363442, -0.48506203 0.15161854 -0.14239071, -0.48400092 0.15036741 -0.14489301, -0.48241255 0.15116926 -0.14328946, -0.48438376 0.1503882 -0.14485149, -0.48250487 0.15133661 -0.14295463, -0.48474437 0.15044935 -0.14472903, -0.48268396 0.15148935 -0.14264913, -0.48506191 0.15054731 -0.14453299, -0.4829399 0.15161851 -0.14239071, -0.48531762 0.15067646 -0.14427485, -0.48325729 0.15171644 -0.14219473, -0.48549682 0.15082923 -0.14396949, -0.48361802 0.1517776 -0.14207233, -0.48400089 0.15242448 -0.14234392, -0.48361784 0.15240368 -0.14238544, -0.48325738 0.15234257 -0.14250775, -0.48293993 0.15224457 -0.14270373, -0.48268402 0.15211549 -0.14296193, -0.48250481 0.15196283 -0.1432675, -0.48241246 0.1517953 -0.14360248, -0.48241243 0.15162279 -0.14394732, -0.48250481 0.1514553 -0.14428245, -0.48268402 0.15130267 -0.14458795, -0.48293993 0.15117355 -0.14484616, -0.48325735 0.15107563 -0.1450422, -0.4836179 0.15101442 -0.14516439, -0.48400095 0.15099362 -0.14520608, -0.47530094 0.15544999 -0.1347269, -0.49000087 0.15544988 -0.1347269, -0.49000087 0.13956976 -0.16649164, -0.48438376 0.15176156 0.14209066, -0.48400095 0.15178239 0.14204909, -0.48506194 0.1505312 0.14455126, -0.48241255 0.15098055 0.14365257, -0.48241258 0.15115312 0.14330758, -0.48531774 0.15066029 0.14429305, -0.48474449 0.15043321 0.14474724, -0.48549691 0.15081298 0.14398755, -0.48438385 0.15037197 0.14486955, -0.48250487 0.15132053 0.1429726, -0.4855893 0.15098053 0.14365269, -0.48361805 0.15176153 0.14209066, -0.48400086 0.15035124 0.14491118, -0.48268422 0.1514733 0.14266704, -0.48558927 0.1511531 0.14330767, -0.48325735 0.15170041 0.142213, -0.48294008 0.15160242 0.14240883, -0.48361787 0.15037189 0.14486955, -0.48549691 0.15132055 0.14297269, -0.48325723 0.15043315 0.14474724, -0.48531762 0.15147322 0.14266704, -0.48293999 0.15053113 0.14455126, -0.48506188 0.15160236 0.14240895, -0.48268399 0.15066029 0.14429305, -0.48474446 0.15170039 0.14221285, -0.48250476 0.15081298 0.14398767, -0.48400095 0.15240844 0.14236216, -0.48438373 0.15238759 0.14240371, -0.48474437 0.15232649 0.14252625, -0.48506179 0.15222846 0.14272191, -0.48531762 0.15209934 0.14298035, -0.48549679 0.15194657 0.14328565, -0.48558921 0.15177913 0.1436206, -0.4855893 0.15160662 0.14396583, -0.48549691 0.15143913 0.14430077, -0.48531774 0.15128648 0.14460613, -0.48506191 0.15115722 0.14486443, -0.48474446 0.15105921 0.14506005, -0.48438376 0.15099803 0.14518259, -0.48400086 0.15097734 0.14522432, -0.49000087 0.15543462 0.13474531, -0.475301 0.1554348 0.13474531, -0.49000075 0.13955094 0.16650866, -0.49000087 0.1554482 -0.10649069, -0.46474442 0.15544651 -0.073907599, -0.46438381 0.15544662 -0.074044332, -0.46250483 0.15544648 -0.07192339, -0.46241257 0.15544648 -0.072298005, -0.46506184 0.15544644 -0.071293011, -0.46361807 0.15544656 -0.074044332, -0.46400079 0.1554466 -0.074090734, -0.46531758 0.15544647 -0.071581736, -0.46474442 0.15544651 -0.071074054, -0.4654969 0.15544645 -0.07192339, -0.46241257 0.15544648 -0.072683647, -0.46438384 0.15544645 -0.070937142, -0.46558914 0.1554464 -0.072298005, -0.46325728 0.1554466 -0.073907599, -0.46400079 0.15544638 -0.07089068, -0.46250483 0.1554466 -0.073058084, -0.46293983 0.15544663 -0.073688403, -0.46268407 0.15544662 -0.073399737, -0.46558928 0.15544643 -0.072683647, -0.46361801 0.1554464 -0.070937261, -0.46549702 0.15544659 -0.073058143, -0.46325728 0.15544644 -0.071074054, -0.46531758 0.1554466 -0.073399737, -0.46293983 0.15544648 -0.071293041, -0.46506187 0.15544654 -0.073688492, -0.46268418 0.15544654 -0.071581945, -0.46400079 0.15614647 -0.07089068, -0.46361795 0.15614653 -0.070937142, -0.46325734 0.15614653 -0.071073964, -0.46293989 0.15614653 -0.071292982, -0.46268412 0.15614647 -0.071581945, -0.46250501 0.15614653 -0.07192339, -0.46241263 0.15614651 -0.072298005, -0.46241263 0.15614662 -0.072683409, -0.46250483 0.15614659 -0.073058084, -0.46268418 0.15614663 -0.073399648, -0.46293989 0.15614668 -0.073688343, -0.4632574 0.15614662 -0.07390748, -0.46361801 0.15614659 -0.074044332, -0.46400085 0.15614662 -0.074090585, -0.47706586 0.15544862 -0.11113612, -0.47700807 0.15544859 -0.11137019, -0.47800085 0.15544875 -0.11249064, -0.47776166 0.15544865 -0.11246173, -0.49000087 0.15544845 -0.11049078, -0.47700825 0.15544869 -0.11161135, -0.47753617 0.15544865 -0.11237608, -0.49000087 0.15544857 -0.11249064, -0.47706586 0.15544868 -0.11184551, -0.47733787 0.1554487 -0.11223935, -0.47717801 0.15544865 -0.1120588, -0.47800076 0.1554485 -0.11049078, -0.47776166 0.1554486 -0.11051975, -0.47753617 0.1554486 -0.11060522, -0.47733781 0.15544857 -0.11074226, -0.47717801 0.1554486 -0.11092268, -0.45706585 0.15544449 -0.036136165, -0.45700815 0.15544449 -0.036370173, -0.45800075 0.15544458 -0.037490651, -0.45776168 0.15544462 -0.037461564, -0.47000092 0.15544441 -0.035490736, -0.45700815 0.15544449 -0.036611184, -0.45753613 0.15544459 -0.037376091, -0.45706585 0.15544449 -0.036845371, -0.47000089 0.15544452 -0.03749077, -0.45733771 0.15544464 -0.037239239, -0.45717791 0.15544458 -0.037058637, -0.45800093 0.15544453 -0.035490736, -0.45776162 0.15544452 -0.035519734, -0.45753607 0.15544446 -0.035605296, -0.45733777 0.15544447 -0.035742179, -0.45717788 0.15544447 -0.035922691, -0.49000081 0.15543629 0.10650931, -0.46250489 0.15543835 0.07307671, -0.46241251 0.15543839 0.072702125, -0.46400079 0.15543841 0.070909247, -0.46361801 0.15543844 0.070955768, -0.46506193 0.15543823 0.073707059, -0.46531758 0.15543832 0.073418155, -0.46241251 0.15543839 0.072316274, -0.46474442 0.15543827 0.073926166, -0.46549693 0.15543838 0.0730768, -0.46325728 0.15543838 0.071092591, -0.46250495 0.15543844 0.071942046, -0.46438375 0.15543821 0.07406278, -0.46293989 0.1554385 0.071311787, -0.46268418 0.15543839 0.071600392, -0.46558931 0.15543835 0.072702125, -0.46400079 0.15543821 0.07410939, -0.46558931 0.15543835 0.072316274, -0.46361786 0.1554382 0.07406278, -0.4654969 0.15543841 0.071942046, -0.46325734 0.15543827 0.073926106, -0.46531758 0.1554385 0.071600452, -0.46293983 0.1554383 0.07370697, -0.46506187 0.15543847 0.071311578, -0.46268407 0.15543835 0.073418155, -0.4647446 0.15543845 0.071092591, -0.46438381 0.15543842 0.070955768, -0.46400079 0.15613844 0.070909247, -0.46438384 0.15613844 0.070955768, -0.46474445 0.15613844 0.071092591, -0.46506187 0.15613833 0.071311787, -0.46531758 0.15613833 0.071600452, -0.46549693 0.15613835 0.071942046, -0.46558926 0.15613833 0.072316274, -0.46558926 0.15613833 0.072702363, -0.46549702 0.1561383 0.0730768, -0.46531758 0.15613826 0.073418245, -0.46506187 0.15613823 0.073707059, -0.46474454 0.15613833 0.073926166, -0.46438381 0.15613832 0.074062839, -0.46400079 0.15613832 0.074109539, -0.47706583 0.15543599 0.11186408, -0.47700813 0.15543599 0.11162992, -0.47800076 0.1554361 0.11050938, -0.47776148 0.15543608 0.11053847, -0.4900009 0.15543588 0.11250933, -0.47700807 0.15543607 0.11138891, -0.47753626 0.15543616 0.11062379, -0.47706577 0.15543608 0.11115475, -0.47733772 0.15543611 0.11076091, -0.47717783 0.15543608 0.11094113, -0.49000087 0.15543605 0.11050938, -0.47800073 0.15543588 0.11250933, -0.4777616 0.15543599 0.11248039, -0.47753617 0.15543596 0.11239477, -0.47733787 0.15543613 0.11225779, -0.47717789 0.15543607 0.11207743, -0.49000099 0.15343633 0.10650931, -0.49000081 0.15343603 0.11050926, -0.49000087 0.1534359 0.11250933, -0.49000081 0.15343459 0.13427337, -0.49000075 0.13731493 0.16650842, -0.47000089 0.15343761 0.086509362, -0.49000099 0.15344867 -0.11249088, -0.49000099 0.15344986 -0.13425495, -0.49000075 0.13733363 -0.16649176, -0.47000095 0.1534473 -0.086490706, -0.4700008 0.15344451 -0.037490651, -0.41247287 0.029435992 0.12071301, -0.41337875 0.029435992 0.11904334, -0.41337872 0.029436544 0.10818096, -0.48361784 0.15099797 0.14518259, -0.48325726 0.15105917 0.14506029, -0.48293996 0.15115729 0.14486431, -0.48268414 0.15128633 0.14460613, -0.48250476 0.15143906 0.14430057, -0.48241249 0.15160659 0.14396583, -0.48241252 0.15177915 0.1436206, -0.48250481 0.15194656 0.14328565, -0.48268417 0.15209933 0.14298035, -0.48293987 0.15222847 0.142722, -0.48325723 0.15232643 0.14252593, -0.48361787 0.15238763 0.14240371, -0.48259112 0.15233786 0.14302789, -0.48234603 0.15221524 0.14335276, -0.48254433 0.1523843 0.14301492, -0.48263022 0.15143694 0.14472295, -0.48289651 0.15130273 0.14499177, -0.48286495 0.15132923 0.14504476, -0.48259103 0.15146741 0.14476822, -0.48239926 0.15217431 0.14335479, -0.48282734 0.15252699 0.14272915, -0.48249212 0.1524203 0.1429926, -0.48278525 0.15256824 0.14269672, -0.48239917 0.15163097 0.14444138, -0.48254427 0.15148498 0.14481325, -0.48354623 0.15113609 0.14557745, -0.48400089 0.15113457 0.14556362, -0.48400092 0.15111138 0.14562677, -0.48234606 0.15165392 0.14447533, -0.48356214 0.15115847 0.1455159, -0.48311788 0.15120879 0.14543222, -0.4831489 0.15268043 0.14247216, -0.48311794 0.15271363 0.1424226, -0.48354623 0.15278627 0.14227735, -0.48224401 0.15183929 0.14410494, -0.48228675 0.15166375 0.1445054, -0.48218098 0.15185565 0.14412163, -0.48240504 0.15183926 0.14364956, -0.4824051 0.15166596 0.14399631, -0.48238307 0.15172145 0.1440271, -0.48357731 0.15116605 0.14545093, -0.48400074 0.1511431 0.14549695, -0.48218098 0.15205327 0.14372636, -0.48211464 0.15206356 0.14372264, -0.48222432 0.15226258 0.14332487, -0.48238307 0.15189716 0.14367555, -0.48247704 0.15206784 0.14333464, -0.48234764 0.15194987 0.14369737, -0.48244366 0.1521243 0.14334874, -0.48314896 0.15122856 0.14537598, -0.48274097 0.15132515 0.1451994, -0.48293498 0.15121435 0.14489911, -0.48325387 0.15111603 0.14509605, -0.48324361 0.15116388 0.14514227, -0.4829202 0.15126379 0.1449423, -0.48359093 0.15115875 0.14538549, -0.48263022 0.15228331 0.14303078, -0.48265955 0.15139522 0.14467929, -0.48400074 0.15113653 0.1454301, -0.48317838 0.15123376 0.14531584, -0.48286495 0.15247612 0.14275132, -0.48244369 0.15159599 0.14440514, -0.48317835 0.15263548 0.14251246, -0.48278517 0.15134075 0.145151, -0.48243728 0.15147848 0.14489292, -0.48230034 0.15181026 0.1440828, -0.48356214 0.15275057 0.14233197, -0.48400089 0.15281101 0.14222805, -0.48400077 0.15277439 0.14228453, -0.48360232 0.15113701 0.14532305, -0.48400077 0.15111528 0.1453663, -0.48224387 0.15202996 0.14372323, -0.48249778 0.15200748 0.14331315, -0.48400092 0.15103367 0.14526089, -0.48320487 0.15122421 0.1452546, -0.48228675 0.15224519 0.14334275, -0.48243728 0.15244392 0.14296208, -0.48267797 0.15134414 0.1446398, -0.48265973 0.15222333 0.14302327, -0.48282719 0.15134224 0.14509882, -0.48289639 0.15241769 0.14276208, -0.48247707 0.15155081 0.14436843, -0.48249203 0.15148869 0.14485548, -0.48222432 0.15165983 0.14452989, -0.48320481 0.15258104 0.14254127, -0.48234764 0.15177043 0.14405654, -0.48361084 0.15110156 0.14526664, -0.48400098 0.15108046 0.14530911, -0.48357728 0.15270318 0.14237724, -0.48400089 0.15272619 0.14233114, -0.48230043 0.1519949 0.14371346, -0.48322693 0.15120061 0.14519571, -0.48267797 0.15216093 0.14300631, -0.48292014 0.15235485 0.14276017, -0.48274091 0.15259714 0.14265524, -0.48322693 0.15251966 0.14255787, -0.48249772 0.15149759 0.14433287, -0.48359099 0.15264651 0.14241053, -0.48400095 0.15266883 0.14236604, -0.48211476 0.15185873 0.14413224, -0.48293483 0.15229061 0.14274694, -0.48361605 0.15105453 0.14521895, -0.48324361 0.15245464 0.14256074, -0.48360226 0.15258338 0.14243044, -0.48400095 0.152605 0.14238726, -0.48325393 0.15238918 0.14255013, -0.48361069 0.15251699 0.14243625, -0.48400095 0.15253815 0.14239372, -0.48361614 0.15245049 0.1424271, -0.48400098 0.15247151 0.1423855, -0.46361789 0.15613832 0.074062839, -0.46325728 0.15613832 0.073926166, -0.46293983 0.15613835 0.07370697, -0.46268407 0.15613833 0.073418245, -0.46250483 0.15613835 0.0730768, -0.46241257 0.15613835 0.072702125, -0.46241257 0.15613835 0.072316274, -0.46250495 0.15613844 0.071942046, -0.46268412 0.15613845 0.071600392, -0.46293995 0.15613849 0.071311787, -0.46325728 0.15613845 0.071092591, -0.46361807 0.15613845 0.070955768, -0.46361089 0.15626855 0.070926771, -0.46400085 0.15632549 0.070843831, -0.46400091 0.1562687 0.070879474, -0.46240506 0.15620507 0.072702959, -0.46325389 0.15620509 0.073932722, -0.4624978 0.15620513 0.073079422, -0.46360245 0.15632555 0.070892319, -0.46247712 0.15626857 0.07308732, -0.46324357 0.15626867 0.071066365, -0.463227 0.15632553 0.071034625, -0.46238306 0.15626857 0.07270582, -0.4636161 0.15620507 0.074070081, -0.4636108 0.15626845 0.074091777, -0.4632436 0.15626851 0.073952422, -0.46238306 0.15626857 0.072313026, -0.46234766 0.15632553 0.072710082, -0.46234766 0.15632553 0.072308525, -0.46361616 0.15620521 0.070948556, -0.46400079 0.15620521 0.070901647, -0.46325389 0.15620527 0.071086034, -0.4629201 0.15626845 0.073729232, -0.46322685 0.15632538 0.073984191, -0.4628965 0.15632536 0.073755845, -0.46244374 0.15632555 0.07191883, -0.46230039 0.15637298 0.072302893, -0.46239933 0.15637299 0.071901992, -0.46263018 0.15632538 0.073455438, -0.46286497 0.1563729 0.073791459, -0.46259102 0.15637286 0.073482499, -0.46259114 0.15637292 0.071536407, -0.46234608 0.15640871 0.071881846, -0.46356216 0.15643063 0.074289277, -0.46400079 0.15643819 0.07440947, -0.46354613 0.15643814 0.074354067, -0.46400085 0.15643069 0.074342713, -0.46239933 0.15637299 0.073116854, -0.46254417 0.15640852 0.073514685, -0.46234605 0.15640864 0.073137, -0.46254435 0.1564087 0.071504012, -0.4628273 0.15640864 0.071184799, -0.46249208 0.15643091 0.07146807, -0.46278527 0.15643093 0.071137175, -0.46357742 0.15640858 0.074227765, -0.46400079 0.15640852 0.074279055, -0.46224406 0.15640864 0.072722659, -0.4622868 0.15643086 0.073159412, -0.462181 0.15643083 0.072730258, -0.46314892 0.15643089 0.07088609, -0.46274099 0.15643847 0.071087107, -0.46311799 0.15643844 0.070827082, -0.462181 0.15643083 0.072288379, -0.46211478 0.15643838 0.072738364, -0.46211478 0.15643838 0.072280452, -0.46314892 0.15643077 0.074132755, -0.46311781 0.15643825 0.074191555, -0.46240523 0.15620525 0.072315589, -0.46293485 0.15620509 0.073712692, -0.46359107 0.1563729 0.07417275, -0.46400085 0.15637287 0.074222282, -0.46247712 0.15626857 0.071931377, -0.46265972 0.15626857 0.073434934, -0.46317846 0.15640865 0.074076369, -0.4626303 0.15632556 0.071563318, -0.46244368 0.15632552 0.073099867, -0.46278521 0.1564308 0.073881611, -0.46274099 0.15643832 0.07393153, -0.46400091 0.15620509 0.074116901, -0.46230045 0.1563729 0.072715655, -0.462865 0.15637298 0.071227148, -0.4636023 0.15632536 0.074126437, -0.46400091 0.15632541 0.074174777, -0.46317849 0.15640873 0.070942238, -0.46320486 0.15637289 0.074026093, -0.46224406 0.15640874 0.072295979, -0.4635621 0.15643094 0.070729211, -0.46354619 0.15643837 0.070664629, -0.46400085 0.15643844 0.070609435, -0.46400085 0.15643087 0.070676193, -0.46228668 0.15643086 0.071859434, -0.46222433 0.15643837 0.071835741, -0.4624978 0.15620521 0.071939394, -0.4628273 0.15640861 0.073834166, -0.46267784 0.15620509 0.073422655, -0.46265969 0.15626861 0.071583465, -0.46249208 0.15643083 0.073550835, -0.46243712 0.15643828 0.073588803, -0.46289644 0.15632549 0.071262792, -0.46400079 0.15626855 0.074139223, -0.46320486 0.15637298 0.070992693, -0.46357736 0.1564088 0.070790842, -0.46400091 0.15640874 0.070739344, -0.46267793 0.15620518 0.071596101, -0.4624373 0.15643837 0.071430042, -0.46292016 0.15626866 0.071289405, -0.46222439 0.15643832 0.073183015, -0.46359107 0.15637304 0.070846185, -0.46400079 0.15637299 0.070796475, -0.46293494 0.15620518 0.071306095, -0.45200095 0.15344764 -0.091875598, -0.45346528 0.15344785 -0.095411226, -0.47053641 0.15344869 -0.11248229, -0.4711583 0.15344872 -0.11323993, -0.47700825 0.15344866 -0.11137034, -0.47700825 0.15344866 -0.11161135, -0.47162035 0.15344879 -0.11410446, -0.47706589 0.15344869 -0.11184536, -0.47717795 0.15344866 -0.11205898, -0.47190472 0.15344884 -0.11504228, -0.47800091 0.15343596 0.11250944, -0.47733784 0.15344858 -0.11223949, -0.47200099 0.15344895 -0.11601774, -0.4777616 0.15344866 -0.11246179, -0.47800085 0.15344864 -0.11249088, -0.47753617 0.15344869 -0.11237626, -0.47200087 0.15344991 -0.13425465, -0.45200095 0.15343735 0.091894135, -0.45700821 0.1534445 -0.036370263, -0.45706582 0.15344447 -0.036136165, -0.45700821 0.15344042 0.036388591, -0.45700821 0.15344039 0.036629751, -0.45700821 0.1534445 -0.036611333, -0.45706585 0.15344039 0.036154553, -0.46553966 0.15344654 -0.072303995, -0.47000089 0.15344025 0.037509188, -0.46553963 0.15343839 0.072322443, -0.47800088 0.15343626 0.11050926, -0.47200096 0.15343484 0.13427337, -0.47200099 0.15343596 0.11603607, -0.47776148 0.1534359 0.11248012, -0.47753611 0.15343596 0.11239477, -0.47733781 0.15343615 0.11225779, -0.47190484 0.15343596 0.11506079, -0.47717807 0.15343614 0.11207743, -0.47162035 0.15343601 0.1141227, -0.47706589 0.15343609 0.11186381, -0.47700819 0.15343609 0.11162983, -0.4711583 0.15343596 0.11325826, -0.47700819 0.15343609 0.11138864, -0.47053632 0.15343596 0.1125005, -0.47706589 0.15343609 0.11115451, -0.47717801 0.15343617 0.11094113, -0.47733781 0.15343615 0.11076076, -0.47753623 0.15343614 0.11062379, -0.47776166 0.15343617 0.11053832, -0.45346531 0.15343715 0.095429495, -0.45284343 0.15343712 0.09467195, -0.45238146 0.15343729 0.093807533, -0.45209703 0.15343735 0.092869565, -0.46502876 0.15343836 0.07366918, -0.46527639 0.15343831 0.073389605, -0.46472123 0.15343831 0.073881611, -0.46545014 0.15343834 0.073058888, -0.46437183 0.15343836 0.074014142, -0.4655396 0.15343843 0.072696015, -0.46400088 0.15343836 0.074059233, -0.46363005 0.15343836 0.074014291, -0.46328065 0.15343846 0.073881611, -0.46297303 0.1534384 0.073669389, -0.46272537 0.1534384 0.073389605, -0.46255168 0.1534384 0.073058888, -0.46246222 0.15343842 0.072696015, -0.46246222 0.15343842 0.072322443, -0.46255171 0.15343837 0.071959481, -0.46545011 0.15343839 0.071959481, -0.46527642 0.15343836 0.071628794, -0.46502873 0.1534384 0.07134892, -0.46472114 0.15343839 0.071136579, -0.46437189 0.15343843 0.071004257, -0.46400079 0.15343839 0.070959315, -0.46362996 0.15343842 0.071004257, -0.45800093 0.15344043 0.037509188, -0.46328056 0.15343837 0.071136579, -0.46297303 0.1534384 0.07134901, -0.45776173 0.15344039 0.037480161, -0.46272537 0.1534384 0.071628794, -0.45753619 0.15344042 0.037394568, -0.45733783 0.15344045 0.037257716, -0.45717785 0.15344043 0.037077233, -0.45706591 0.15344042 0.036863729, -0.4700008 0.15344034 0.035509065, -0.45800087 0.15344448 -0.035490885, -0.47000083 0.15344438 -0.035490885, -0.4580009 0.15344062 0.035509273, -0.45776162 0.15344451 -0.035519823, -0.45776162 0.15344056 0.03553836, -0.45733783 0.15344059 0.035760596, -0.45753619 0.15344456 -0.035605296, -0.4575361 0.15344062 0.035623834, -0.45733771 0.15344448 -0.035742298, -0.45717791 0.15344054 0.035941079, -0.45717791 0.15344438 -0.0359229, -0.46502879 0.15344647 -0.071330741, -0.46527657 0.15344648 -0.071610317, -0.46472123 0.15344653 -0.071118459, -0.46545011 0.15344654 -0.071941242, -0.46437183 0.15344651 -0.070985928, -0.46400079 0.15344644 -0.070941046, -0.4580009 0.15344466 -0.03749077, -0.46363011 0.15344657 -0.070985898, -0.46328053 0.15344645 -0.071118459, -0.45776162 0.15344451 -0.037461773, -0.45753619 0.15344463 -0.03737615, -0.46297303 0.15344647 -0.071330741, -0.46272537 0.1534465 -0.071610317, -0.4573378 0.15344466 -0.037239358, -0.46255168 0.15344651 -0.071941242, -0.45717791 0.15344459 -0.037058905, -0.46328056 0.15344658 -0.073863342, -0.46363005 0.15344663 -0.073995695, -0.46400085 0.15344654 -0.074040756, -0.46437174 0.15344654 -0.073995814, -0.46472117 0.15344654 -0.073863342, -0.46502873 0.15344657 -0.07365118, -0.46527651 0.15344657 -0.073371425, -0.4654502 0.15344653 -0.0730405, -0.46553966 0.15344654 -0.072677657, -0.49000096 0.15344833 -0.10649084, -0.47800082 0.15344855 -0.11049084, -0.49000081 0.15344848 -0.11049084, -0.47776166 0.15344861 -0.11051975, -0.47753623 0.15344855 -0.11060537, -0.46246216 0.15344653 -0.072303995, -0.46246216 0.15344653 -0.072677657, -0.46255168 0.15344651 -0.07304047, -0.46272525 0.15344657 -0.073371425, -0.46297303 0.15344656 -0.07365106, -0.45706579 0.15344457 -0.036845371, -0.45209706 0.15344779 -0.092851028, -0.45238146 0.15344778 -0.093789145, -0.47706595 0.15344857 -0.1111363, -0.47717795 0.15344848 -0.11092286, -0.47733787 0.15344857 -0.11074226, -0.45284346 0.15344787 -0.094653562, -0.46434078 0.15341695 -0.073869422, -0.46463433 0.1533812 -0.073697671, -0.46432725 0.1533812 -0.073814169, -0.46547341 0.15343907 -0.072311983, -0.4653284 0.15341681 -0.071987405, -0.46541032 0.15341677 -0.072319731, -0.46469018 0.15343893 -0.071177587, -0.46434066 0.15341677 -0.07111223, -0.46466079 0.15341675 -0.071233615, -0.4643558 0.15343894 -0.071050718, -0.4643558 0.15343906 -0.073931023, -0.46469021 0.15343909 -0.073804095, -0.46400073 0.15341686 -0.073910818, -0.46400073 0.15343903 -0.073974118, -0.46541032 0.15341677 -0.07266213, -0.46535397 0.15338108 -0.072326496, -0.46494231 0.15341671 -0.071428075, -0.46463427 0.15338106 -0.071283922, -0.46466067 0.15341686 -0.073747948, -0.46535382 0.15338105 -0.072655216, -0.46527538 0.15338111 -0.07297419, -0.46530673 0.15333354 -0.072649494, -0.46490473 0.15338105 -0.071470723, -0.46512255 0.153381 -0.071716622, -0.46487316 0.15333354 -0.071506366, -0.46430182 0.15321331 -0.071270004, -0.46400088 0.15314654 -0.071240887, -0.46430007 0.15314646 -0.071277276, -0.46523091 0.15333362 -0.072957352, -0.4650836 0.15333359 -0.071743593, -0.46508345 0.1533336 -0.073238119, -0.46519753 0.15327674 -0.072944656, -0.46400085 0.15321329 -0.071233466, -0.46523079 0.15333359 -0.07202436, -0.46505412 0.15327662 -0.071763828, -0.46519753 0.15327674 -0.072037026, -0.46505418 0.15327676 -0.073217884, -0.46484947 0.15327677 -0.073448762, -0.46503595 0.15321341 -0.073205188, -0.46483478 0.15321334 -0.073432192, -0.46430716 0.15327664 -0.071248367, -0.46400079 0.15327664 -0.071211293, -0.4652712 0.1532767 -0.072336599, -0.46517667 0.15321326 -0.072044775, -0.46524915 0.15321328 -0.072339281, -0.46458527 0.15321328 -0.071377411, -0.46458185 0.15314654 -0.071384057, -0.46524924 0.15321332 -0.07264252, -0.46524176 0.15314652 -0.072340325, -0.46524176 0.15314652 -0.072641596, -0.46458527 0.15321343 -0.07360436, -0.46482977 0.15314661 -0.0734265, -0.46458185 0.15314667 -0.073597535, -0.46431562 0.15333341 -0.071213707, -0.46547341 0.15343907 -0.072669581, -0.46498439 0.15343894 -0.0713806, -0.46400076 0.15333346 -0.071175441, -0.46532837 0.15341683 -0.072994336, -0.46459556 0.15327667 -0.071357802, -0.4651694 0.15341677 -0.071684435, -0.46512255 0.15338117 -0.073265031, -0.46527526 0.15338105 -0.072007671, -0.46483478 0.15321326 -0.071549729, -0.46482977 0.15314643 -0.071555361, -0.46487322 0.15333363 -0.073475435, -0.46530679 0.1533335 -0.072332308, -0.46432725 0.15338111 -0.071167544, -0.46400079 0.15338099 -0.071127906, -0.46459553 0.15327676 -0.073623881, -0.46461204 0.15333341 -0.071326151, -0.4652712 0.1532767 -0.072645113, -0.46430179 0.15321343 -0.073711708, -0.46430001 0.15314662 -0.073704526, -0.46517667 0.15321326 -0.072936878, -0.46516976 0.15314654 -0.072934076, -0.46400073 0.15314661 -0.073740765, -0.46400079 0.15321335 -0.073748454, -0.4648495 0.15327662 -0.071533039, -0.46538779 0.15343912 -0.073016867, -0.46522158 0.15343904 -0.071648255, -0.46503583 0.15321325 -0.071776494, -0.46502969 0.15314652 -0.071780786, -0.46516934 0.15341683 -0.073297486, -0.46400079 0.15341677 -0.071071014, -0.46490476 0.15338115 -0.073511079, -0.46461222 0.15333365 -0.07365562, -0.46430716 0.1532768 -0.073733434, -0.46400085 0.15327676 -0.073770627, -0.46522161 0.15343907 -0.073333368, -0.46502963 0.15314661 -0.073200926, -0.46494246 0.15341692 -0.073553547, -0.46516976 0.15314651 -0.072047576, -0.46538776 0.15343896 -0.071965054, -0.46400085 0.15343894 -0.071007714, -0.46431568 0.15333369 -0.073768035, -0.46400079 0.15333362 -0.07380636, -0.46498442 0.15343907 -0.073601112, -0.46400091 0.15338114 -0.073853716, -0.46366102 0.15340869 0.073887691, -0.46400085 0.15337287 0.073872253, -0.46400079 0.15340863 0.073928818, -0.46252844 0.15343083 0.07233052, -0.46331152 0.15343089 0.071195945, -0.46367463 0.15337285 0.073832735, -0.46261403 0.1534308 0.071983173, -0.46364602 0.15343095 0.071069136, -0.4636611 0.15340872 0.071130618, -0.46334106 0.15340868 0.073766574, -0.46336743 0.15337288 0.073716149, -0.46267328 0.15340865 0.072005495, -0.46259138 0.15340868 0.07233806, -0.46364596 0.15343089 0.073949322, -0.46400097 0.15343086 0.073992565, -0.46334112 0.15340874 0.071251884, -0.46259138 0.15340868 0.072680339, -0.46264789 0.1533729 0.072344765, -0.46264789 0.1533729 0.072673425, -0.46305925 0.15340869 0.071446285, -0.46336749 0.15337302 0.071302488, -0.46331146 0.1534308 0.073822603, -0.46272656 0.15337294 0.072992519, -0.46269503 0.15332547 0.072667703, -0.46309716 0.15337293 0.071489051, -0.46287921 0.15337296 0.071735069, -0.4631286 0.15332545 0.071524605, -0.46277094 0.15332539 0.072975621, -0.46291825 0.15332539 0.073256448, -0.46280426 0.15326843 0.072962984, -0.46369988 0.15320508 0.071288183, -0.46400079 0.15313838 0.071259245, -0.46370167 0.15313843 0.071295485, -0.46291822 0.15332541 0.071761712, -0.46400079 0.15320514 0.071251586, -0.46277094 0.15332539 0.072042927, -0.4629477 0.15326865 0.071782216, -0.4629477 0.15326865 0.073236093, -0.46280435 0.15326855 0.072055414, -0.46315226 0.15326852 0.073467091, -0.462966 0.15320511 0.073223546, -0.46316695 0.15320511 0.073450401, -0.46369466 0.15326862 0.071266755, -0.46400073 0.1532685 0.071229562, -0.4627305 0.15326855 0.072354987, -0.46282503 0.15320511 0.072063223, -0.46275252 0.15320514 0.07235761, -0.46341655 0.15320513 0.073622569, -0.46317211 0.15313846 0.073444918, -0.46342003 0.15313837 0.073616013, -0.4634164 0.15320508 0.071395621, -0.46342 0.15313838 0.071402386, -0.46275252 0.15320519 0.072660699, -0.46276 0.15313847 0.072358593, -0.46276 0.15313843 0.072659805, -0.46252844 0.15343083 0.072687998, -0.46368614 0.1533255 0.071232006, -0.46301731 0.15343085 0.071398929, -0.46400079 0.15332544 0.071193919, -0.46267328 0.15340862 0.073012456, -0.46340618 0.15326858 0.07137607, -0.46283242 0.15340874 0.071702614, -0.46287921 0.15337288 0.073283538, -0.46272656 0.15337294 0.072025791, -0.46316692 0.15320523 0.071567848, -0.46317193 0.15313835 0.071573481, -0.46269503 0.15332547 0.072350606, -0.4631286 0.15332541 0.073493853, -0.46367469 0.15337296 0.071185812, -0.46400085 0.15337302 0.071146265, -0.46340618 0.15326847 0.073642328, -0.46338961 0.15332538 0.071344271, -0.4627305 0.15326855 0.072663501, -0.46369988 0.15320508 0.073730066, -0.46370187 0.15313841 0.073722914, -0.46400091 0.15313834 0.073759153, -0.46282503 0.15320511 0.072954878, -0.46400085 0.15320511 0.073766813, -0.46283203 0.15313832 0.072952434, -0.46261403 0.1534308 0.073035225, -0.46315223 0.15326861 0.071551219, -0.46278027 0.15343089 0.071666703, -0.46283242 0.15340866 0.073315695, -0.46296585 0.15320508 0.071794853, -0.46297219 0.15313847 0.071799144, -0.46400076 0.15340869 0.071089372, -0.46309716 0.15337293 0.073529258, -0.46338961 0.15332541 0.073673829, -0.46369466 0.15326862 0.073751792, -0.46400091 0.15326861 0.073788837, -0.46278021 0.15343076 0.073351696, -0.46297231 0.15313841 0.073219404, -0.4630594 0.15340863 0.073571876, -0.46283203 0.15313832 0.072065935, -0.46400091 0.15343092 0.071025982, -0.46368608 0.15332533 0.073786363, -0.46400079 0.15332539 0.073824629, -0.46301731 0.15343085 0.07361947, -0.45706579 0.1554403 0.036863759, -0.45700824 0.15544041 0.036629751, -0.45776179 0.15544058 0.03553836, -0.45800093 0.15544054 0.035509273, -0.47000083 0.15544023 0.037509248, -0.45700821 0.15544045 0.036388591, -0.45753613 0.15544054 0.035623834, -0.47000089 0.15544036 0.035509482, -0.45706591 0.15544045 0.036154792, -0.45733771 0.15544049 0.035760596, -0.45717791 0.15544052 0.035941049, -0.45800093 0.15544036 0.037509277, -0.45776168 0.15544041 0.037480161, -0.45753613 0.15544035 0.037394717, -0.45733774 0.1554403 0.037257954, -0.45717782 0.15544039 0.037077323, -0.46017045 0.076228231 0.10014091, -0.41399431 0.03005214 0.10842489, -0.46017054 0.076228917 0.08937715, -0.46006045 0.076231271 0.048262134, -0.46408075 0.076230541 0.061083749, -0.46408075 0.076231256 0.048262134, -0.46206471 0.076230288 0.065113559, -0.46608517 0.076230407 0.06288363, -0.4600603 0.076230302 0.063313738, -0.46608517 0.076229721 0.075024679, -0.4620648 0.076229796 0.074147806, -0.46119097 0.076228946 0.088551745, -0.45717058 0.076229081 0.087675318, -0.45717058 0.076228485 0.098063633, -0.44968125 0.076227784 0.11186634, -0.45121935 0.076227367 0.1166376, -0.43528709 0.076227456 0.11768217, -0.41220874 0.076226935 0.13100611, -0.41291234 0.07622689 0.1321146, -0.41220883 0.076226816 0.13170989, -0.41328266 0.038290441 0.13196276, -0.41291207 0.038394406 0.13211243, -0.41520748 -0.016729981 0.048257127, -0.41790181 -0.018049493 0.048257127, -0.41748139 -0.018907696 0.04825671, -0.41191396 -0.018907622 0.048256651, -0.41608724 -0.01493378 0.048257127, -0.43469283 0.024440005 0.048259392, -0.41878149 -0.016253442 0.048257127, -0.43871322 0.024439931 0.048259392, -0.43469274 0.026439846 0.048259392, -0.43969285 0.026439905 0.048259392, -0.46650031 0.092538238 0.048262998, -0.47150049 0.091379523 0.048262998, -0.46506032 0.078231215 0.048262253, -0.46006033 0.078231201 0.048262134, -0.46650058 0.1128042 0.04826428, -0.47150061 0.1163127 0.048264429, -0.44428685 0.12615618 0.048264995, -0.43150076 0.1261563 0.048264995, -0.41736275 -0.019149944 0.049042955, -0.41716963 -0.019544467 0.049807891, -0.41583231 -0.022274762 0.051831827, -0.41790184 -0.018050179 0.061078265, -0.41520709 -0.023551479 0.052006438, -0.4163855 -0.021145657 0.051352575, -0.4168244 -0.020249158 0.050671205, -0.41229883 -0.029489323 0.061077669, -0.41229883 -0.029488906 0.05200623, -0.41430315 -0.029489547 0.062877551, -0.41951838 -0.018842191 0.062878147, -0.41279873 -0.032561585 0.0750186, -0.41279873 -0.032560915 0.064255968, -0.41430306 -0.029489666 0.064256415, -0.41951832 -0.018842876 0.075019434, -0.4139939 -0.020130038 0.0885465, -0.41557106 -0.016910285 0.088546619, -0.41257027 -0.024238527 0.086919025, -0.41257021 -0.032561675 0.07565029, -0.41399404 -0.016137928 0.09012793, -0.44428685 0.12615384 0.08871828, -0.48016232 0.11317745 0.088717446, -0.47150066 0.1163111 0.075730041, -0.48016211 0.096220285 0.088716373, -0.4715004 0.087559417 0.075728372, -0.46217069 0.078228965 0.088715538, -0.46217069 0.078228965 0.088551983, -0.4715004 0.087559417 0.075395897, -0.43150079 0.12615393 0.08871834, -0.46506032 0.078230545 0.061083749, -0.4620648 0.078230307 0.065113798, -0.46706459 0.078230247 0.06288363, -0.4600603 0.078230307 0.063313738, -0.46706471 0.078229636 0.075024679, -0.4620648 0.078229889 0.074148014, -0.45717075 0.078229025 0.087675318, -0.45717058 0.078228951 0.088715538, -0.44169721 0.026438341 0.075021848, -0.44169721 0.026438996 0.062880769, -0.43680289 0.026437506 0.088549092, -0.41399416 0.026436687 0.10699259, -0.41328269 0.03667374 0.12963615, -0.41460463 0.03799589 0.12910216, -0.4159877 0.039265394 0.1283804, -0.41729423 0.040259093 0.1274022, -0.41849622 0.040972009 0.12621285, -0.420912 0.039834276 0.12012319, -0.42071363 0.039200485 0.11957641, -0.42042106 0.038532436 0.11915411, -0.42005986 0.037858129 0.11884968, -0.4195126 0.036986366 0.11860387, -0.41913173 0.036444649 0.11852627, -0.41948566 0.041355208 0.12494077, -0.42022595 0.041426137 0.12367855, -0.42069706 0.041237146 0.12253822, -0.42093405 0.04086946 0.1215723, -0.42099187 0.040401772 0.12079252, -0.43969283 0.02643916 0.061080888, -0.41878149 -0.016254112 0.061078444, -0.43871316 0.024439216 0.061080888, -0.42039797 -0.017046049 0.062878355, -0.44071761 0.024439037 0.06288062, -0.44071755 0.024438292 0.075021818, -0.42039809 -0.017046764 0.075019434, -0.43582341 0.024437547 0.088549033, -0.41645077 -0.015114069 0.088546738, -0.41399404 -0.013910919 0.091010168, -0.41399428 0.024436668 0.10620044, -0.41163501 0.037883893 0.13137777, -0.43150067 0.1261538 0.090718225, -0.43150067 0.12765363 0.094257906, -0.43150067 0.12615362 0.094257906, -0.43150079 0.12765639 0.046472296, -0.43150067 0.12615632 0.046472207, -0.4129996 -0.035561547 0.075176701, -0.41297236 -0.035561547 0.075331166, -0.41299126 -0.035561591 0.075263515, -0.41299757 -0.035561591 0.075220272, -0.41261879 -0.035561591 0.076308563, -0.4129996 -0.035560906 0.06246303, -0.4129996 -0.035560936 0.062461153, -0.4129996 -0.035559177 0.032050535, -0.4129996 -0.035559207 0.032048807, -0.4129996 -0.03555806 0.012705699, -0.4129996 -0.03555809 0.012703732, -0.4129996 -0.035556659 -0.01270853, -0.46288338 0.066287711 -0.012702778, -0.41299957 -0.035555542 -0.032051548, -0.46376291 0.068083391 -0.012003049, -0.47276708 0.086467534 -0.032044753, -0.46349552 0.067537472 -0.012385145, -0.46319726 0.066928566 -0.012622491, -0.47289851 0.086736023 -0.031981245, -0.47283426 0.086604714 -0.032032117, -0.47286943 0.086676598 -0.032011375, -0.46398631 0.068539426 -0.011495188, -0.46415439 0.068882495 -0.010887071, -0.4642587 0.069095463 -0.010209188, -0.46429405 0.069167659 -0.0094954818, -0.46288338 0.066286281 0.01271148, -0.46415439 0.068881199 0.010895833, -0.472767 0.086463854 0.032055721, -0.4642587 0.0690943 0.010218129, -0.46398631 0.068538129 0.011504039, -0.46376291 0.068082049 0.012011841, -0.46349552 0.067536011 0.012393817, -0.46319732 0.066927195 0.012631133, -0.47283414 0.086600959 0.032043085, -0.47289851 0.086732432 0.031992123, -0.47286931 0.086672843 0.032022342, -0.46429399 0.069166556 0.0095044225, -0.47276711 0.0864622 0.062469944, -0.47281852 0.086567387 0.062477008, -0.47289848 0.086730719 0.062533394, -0.47286293 0.086657807 0.062498525, -0.47289848 0.086730152 0.07375975, -0.47291675 0.086767256 0.074226961, -0.47283283 0.086596042 0.075183615, -0.47297141 0.086878777 0.074692056, -0.47288623 0.086704969 0.075193807, -0.4729346 0.086803526 0.075225398, -0.47304633 0.087031633 0.075175121, -0.4730536 0.087046623 0.075161293, -0.47295681 0.086849138 0.075250968, -0.47303405 0.087006763 0.075208858, -0.47297719 0.086890578 0.075284168, -0.47306195 0.087063745 0.075150833, -0.47302249 0.0869831 0.07526134, -0.47299471 0.086926505 0.075324491, -0.47300905 0.086955488 0.075371906, -0.47550067 0.13649793 0.16814198, -0.42839295 0.15343514 0.13427313, -0.41287214 0.15343519 0.13427337, -0.42446992 0.1534352 0.13217266, -0.41237539 0.15343519 0.13421555, -0.41300634 0.15343542 0.13217272, -0.41173515 0.15343514 0.13404302, -0.41163576 0.15343535 0.13138421, -0.47539037 0.13800706 0.16959582, -0.47543994 0.13795465 0.1697007, -0.47550073 0.13790789 0.16979443, -0.47532946 0.13811399 0.1693822, -0.47530088 0.13828954 0.16903122, -0.47107944 0.14448723 0.15216576, -0.46860316 0.14356525 0.15400992, -0.46955827 0.14378507 0.15356992, -0.47156808 0.14491607 0.15130831, -0.48400095 0.14858478 0.14397191, -0.48362985 0.14860491 0.14393161, -0.48502865 0.14875904 0.1436231, -0.48527649 0.14888412 0.14337321, -0.48362991 0.14995116 0.14123954, -0.48400092 0.1499714 0.14119925, -0.48472109 0.1486641 0.143813, -0.48553953 0.1491943 0.14275275, -0.48545006 0.14903216 0.14307724, -0.48553964 0.14936149 0.14241837, -0.48545015 0.14952381 0.14209394, -0.48527658 0.14967193 0.14179815, -0.48502865 0.14979699 0.14154769, -0.48472115 0.14989179 0.14135803, -0.48437184 0.14995116 0.14123954, -0.48437199 0.14860496 0.14393161, -0.47186574 0.14535639 0.15042804, -0.46760002 0.14345136 0.15423752, -0.47196892 0.14565131 0.14983808, -0.48328066 0.14866419 0.143813, -0.46661437 0.14344083 0.15425853, -0.48246211 0.14919439 0.14275275, -0.47200084 0.14593361 0.14927347, -0.48246214 0.14936154 0.14241828, -0.48255172 0.14903219 0.14307712, -0.48272535 0.14888422 0.143373, -0.48297307 0.14875904 0.1436231, -0.46560481 0.14353283 0.15407468, -0.47550067 0.13541915 0.17029957, -0.46464062 0.14372942 0.15368162, -0.48328066 0.14989193 0.14135803, -0.48297304 0.14979699 0.14154778, -0.48272526 0.14967194 0.14179815, -0.48255163 0.14952381 0.14209394, -0.47040057 0.14410029 0.15293966, -0.48364598 0.14862713 0.1438701, -0.48366103 0.14863485 0.14380525, -0.48400083 0.14861639 0.143842, -0.48331162 0.14985877 0.14140736, -0.48331165 0.1486838 0.14375652, -0.4833411 0.14868918 0.14369677, -0.48364601 0.14991549 0.14129414, -0.48366114 0.14986812 0.14133932, -0.4825913 0.14917479 0.14272512, -0.48264787 0.14929281 0.14240937, -0.48264799 0.14914598 0.14270319, -0.48334101 0.1498138 0.14144765, -0.48259133 0.1493279 0.14241914, -0.48272663 0.14900334 0.14298846, -0.48269507 0.14910604 0.14267673, -0.48305947 0.14972684 0.14162172, -0.48336756 0.14975925 0.14147674, -0.48309708 0.14967582 0.1416439, -0.48277089 0.14896832 0.14295219, -0.48287922 0.14956585 0.14186381, -0.48312864 0.14961737 0.14165436, -0.48291823 0.14884268 0.14320327, -0.48280427 0.14892314 0.1429155, -0.48294786 0.14880095 0.14315973, -0.48400095 0.14860784 0.14390884, -0.4829182 0.14951119 0.14186694, -0.48369986 0.14961554 0.14138924, -0.48400092 0.14956881 0.14133348, -0.48370174 0.14955254 0.14136587, -0.48400104 0.14963193 0.14135645, -0.48277095 0.14938553 0.14211787, -0.48294771 0.14945121 0.14185931, -0.48315224 0.14869756 0.14336608, -0.48296589 0.14874986 0.14312004, -0.48316699 0.1486484 0.14332317, -0.48280412 0.1493289 0.14210378, -0.48369467 0.14968188 0.14139833, -0.48400083 0.14969854 0.14136495, -0.48273054 0.14919509 0.14237167, -0.48282498 0.14926875 0.14208247, -0.48341659 0.14857137 0.14347719, -0.48317191 0.14859115 0.14328812, -0.48341995 0.1485147 0.1434413, -0.4827525 0.14913715 0.14234568, -0.48275259 0.14900155 0.14261676, -0.48276007 0.14907707 0.14231671, -0.48275986 0.14894222 0.14258586, -0.48252848 0.14919131 0.14274205, -0.48252839 0.14935115 0.14242221, -0.48341656 0.1495675 0.14148532, -0.48342004 0.14950472 0.14146148, -0.48301739 0.14976791 0.14158927, -0.48368603 0.14974834 0.1413926, -0.48267341 0.14902623 0.14302267, -0.48400095 0.14976537 0.14135863, -0.48283234 0.14961222 0.14185075, -0.48287922 0.14887317 0.14324857, -0.48340628 0.14963299 0.14149605, -0.48272654 0.14943554 0.14212386, -0.48312873 0.14873657 0.14341582, -0.48316699 0.14949049 0.14163949, -0.48317203 0.1494282 0.14161445, -0.48400098 0.14993474 0.1412553, -0.48269489 0.14924775 0.14239325, -0.48340628 0.14861937 0.14352296, -0.48367471 0.1498114 0.14137278, -0.48400083 0.14982919 0.14133732, -0.48369989 0.14852326 0.14357339, -0.48370171 0.14846678 0.14353679, -0.48400083 0.14845066 0.14356934, -0.48273051 0.14905716 0.14264764, -0.48338959 0.14969803 0.14149319, -0.48400089 0.14850695 0.14360581, -0.48282495 0.14886989 0.1428801, -0.48283198 0.14881139 0.14284803, -0.48261401 0.14903606 0.14305268, -0.48278022 0.14964816 0.1418284, -0.48283234 0.1488906 0.1432936, -0.48315221 0.14955464 0.14165281, -0.48267323 0.14947656 0.14212193, -0.48296598 0.14938892 0.14184223, -0.48297209 0.14932731 0.14181627, -0.48309705 0.14876315 0.14346875, -0.48400089 0.14988655 0.14130248, -0.48338953 0.14865611 0.14357673, -0.48369458 0.14857028 0.14362098, -0.48400095 0.1485537 0.14365412, -0.48278016 0.1488944 0.14333557, -0.4830595 0.14877605 0.14352275, -0.48297215 0.1486921 0.14308645, -0.48261395 0.14950643 0.14211179, -0.48283207 0.14920792 0.1420549, -0.48336756 0.1486797 0.1436355, -0.48368615 0.14860573 0.14367728, -0.48400086 0.14858861 0.1437117, -0.48301739 0.14877474 0.14357521, -0.48367459 0.14862755 0.14373983, -0.48400095 0.14860986 0.14377524, -0.47550073 0.13732643 0.17045401, -0.47550067 0.1353292 0.17045401, -0.47550073 0.13789122 0.1702287, -0.47550073 0.13793048 0.17027353, -0.47550067 0.13775782 0.17042162, -0.47550067 0.13797876 0.17030795, -0.47550073 0.13786273 0.17017661, -0.47550073 0.13802829 0.1703275, -0.47550067 0.13807575 0.1703359, -0.47550079 0.13812438 0.17033525, -0.47550091 0.1378597 0.16991393, -0.47550067 0.13783936 0.17002831, -0.47550067 0.13784465 0.17011394, -0.41255388 -0.035539359 0.076518342, -0.41251323 -0.035472691 0.076720908, -0.41249964 -0.035365969 0.076902673, -0.4124997 -0.026329845 0.089137062, -0.46302098 0.07681644 0.089142784, -0.47281092 0.086606801 0.075338081, -0.41249964 -0.032486528 0.0090345293, -0.41249964 -0.032485515 -0.0090370625, -0.41235623 -0.032778233 -0.0097441524, -0.42608958 -0.0047398955 -0.010113761, -0.41188738 -0.03373538 -0.010701403, -0.41241232 -0.032663882 -0.0096072406, -0.41245613 -0.032574296 -0.0094491094, -0.42603484 -0.0048516393 -0.0099617988, -0.42616287 -0.0045901537 -0.010246918, -0.41248879 -0.032507583 -0.0092456788, -0.42601076 -0.0049006492 -0.0098473877, -0.42600253 -0.0049175322 -0.0097727925, -0.42629263 -0.0043250471 -0.010406837, -0.42599979 -0.0049229413 -0.0096998066, -0.42651084 -0.0038797706 -0.010572121, -0.42599979 -0.0049241483 0.0097004026, -0.41248882 -0.032508537 0.0092432648, -0.42600241 -0.0049187839 0.0097732395, -0.41245613 -0.032575309 0.0094463974, -0.4260107 -0.0049018413 0.0098478943, -0.41241232 -0.032665014 0.0096047074, -0.42603484 -0.0048527718 0.0099623948, -0.41235623 -0.032779455 0.0097416788, -0.42608958 -0.0047409832 0.010114327, -0.41188738 -0.033736631 0.01069878, -0.42699984 -0.0028824657 0.010700449, -0.42651084 -0.0038809478 0.010572568, -0.42629269 -0.0043261498 0.010407433, -0.42616284 -0.0045913756 0.010247454, -0.4269999 -0.0028813034 -0.010699496, -0.41249964 -0.032489389 0.058791891, -0.4124997 -0.032488018 0.035720274, -0.41245624 -0.032578155 0.059203818, -0.4170678 -0.023162454 0.050768241, -0.41248879 -0.032511413 0.059000447, -0.41241232 -0.032667756 0.059362128, -0.41759995 -0.022075981 0.050422058, -0.41735265 -0.022580609 0.050630912, -0.41235611 -0.032782272 0.05949904, -0.41785082 -0.02156353 0.050104156, -0.41828066 -0.020686045 0.045354143, -0.47289857 0.0908245 0.034270033, -0.41801256 -0.02123335 0.044687286, -0.41768306 -0.021905869 0.044183627, -0.41198882 -0.033532247 0.060248986, -0.47289842 0.090822965 0.0602559, -0.41845748 -0.020325124 0.046105072, -0.41809073 -0.021073833 0.049663559, -0.41296908 -0.03153047 0.05080612, -0.41296908 -0.031530112 0.043706194, -0.41854092 -0.020154625 0.046865836, -0.41854057 -0.020155519 0.047655001, -0.41845626 -0.020327613 0.048415229, -0.41242704 -0.032636344 0.03519626, -0.41728821 -0.022712037 0.043841973, -0.41235623 -0.032780856 0.035013303, -0.41198885 -0.033530846 0.034263119, -0.4124721 -0.032544225 0.035389587, -0.41681269 -0.023682937 0.043706581, -0.41249287 -0.032501891 0.035554215, -0.41829982 -0.020647034 0.049095944, -0.41681272 -0.023683399 0.050806507, -0.41249934 -0.02631174 0.089161649, -0.4124997 -0.025688946 0.089571342, -0.41249999 0.025804758 0.10996924, -0.41249064 -0.025875479 0.089497343, -0.41249117 0.025908753 0.11001752, -0.4620437 0.075461686 0.089577064, -0.41250005 0.026435986 0.11984687, -0.41250002 0.026436463 0.11089893, -0.4924607 0.10639632 0.1053942, -0.49270776 0.10664338 0.10677837, -0.49264601 0.10658173 0.10607909, -0.49227145 0.10620718 0.10496186, -0.49203554 0.10597122 0.10455893, -0.47549775 0.089434192 0.096121386, -0.49270776 0.10664189 0.13302858, -0.47371581 0.087653399 0.077088878, -0.47426125 0.088197827 0.094988331, -0.47439858 0.088335082 0.094957486, -0.47454384 0.088480502 0.094973639, -0.47469535 0.088631943 0.095038339, -0.47485068 0.088787332 0.095152661, -0.47506008 0.088996723 0.095378205, -0.47528419 0.089220569 0.095711276, -0.47294155 0.086879194 0.075670436, -0.47333291 0.087270513 0.07642667, -0.47313729 0.087074876 0.075989619, -0.47294441 0.08688201 0.075661048, -0.46316811 0.077105075 0.089451894, -0.47297743 0.086915135 0.075539187, -0.46292982 0.076866776 0.089719966, -0.46260649 0.07654351 0.089971766, -0.46193758 0.075874537 0.090320215, -0.41250393 0.026439935 0.119936, -0.412496 0.02643244 0.11080895, -0.4124839 0.02642037 0.11071987, -0.41250008 0.035682768 0.13346712, -0.41250005 0.0266148 0.12041749, -0.41299999 0.028622389 0.12238504, -0.4125044 0.026564017 0.12033646, -0.41887385 0.034496292 0.1200123, -0.41300002 0.033645898 0.12961455, -0.41988549 0.035659507 0.11982204, -0.41250113 0.035709307 0.13350375, -0.41673058 0.037376553 0.12810783, -0.41736919 0.037983805 0.1278045, -0.4181096 0.038611934 0.12734409, -0.41904753 0.039287761 0.12658773, -0.42072025 0.036818787 0.11995126, -0.47427881 0.08833912 0.095381454, -0.42121187 0.037664264 0.1202624, -0.42169008 0.038948298 0.12122883, -0.42164108 0.039718762 0.12242819, -0.42145842 0.039938107 0.12307991, -0.47174588 0.09495452 0.10957085, -0.4211807 0.040050268 0.12375341, -0.42082173 0.040055335 0.12442221, -0.42040059 0.039961413 0.12506329, -0.41977805 0.039705843 0.12584303, -0.41227147 0.1066526 0.1339006, -0.41327944 0.10657206 0.13390057, -0.41294315 0.10646966 0.1339006, -0.41274819 0.10636842 0.1339006, -0.41263822 0.10628104 0.13390057, -0.41256157 0.10618754 0.13390057, -0.41252163 0.10610542 0.13390057, -0.41204026 0.10666147 0.13390057, -0.41250578 0.10604388 0.13390057, -0.41250053 0.1059815 0.13390057, -0.4118183 0.10668927 0.13390057, -0.41151783 0.10676783 0.1339006, -0.41134849 0.1068439 0.13390057, -0.41124141 0.10691233 0.13390057, -0.41250008 0.036624104 0.13389666, -0.4124909 0.036503747 0.13389651, -0.41100958 0.107256 0.1339006, -0.41103756 0.10716265 0.13390057, -0.41108537 0.10707314 0.13390057, -0.41115355 0.10698929 0.1339006, -0.41412404 0.10665256 0.1339006, -0.49200064 0.1064427 0.13345118, -0.47353423 0.12308374 0.16914307, -0.49200055 0.12202631 0.16687559, -0.47178099 0.09575662 0.11053132, -0.47212896 0.095612109 0.11022149, -0.47123703 0.095893413 0.11082469, -0.47242495 0.095377818 0.10971926, -0.47247055 0.095295101 0.10954152, -0.47479072 0.089234993 0.096543863, -0.47086245 0.094987124 0.11032017, -0.47303557 0.12398991 0.16958727, -0.47466204 0.12535378 0.17052303, -0.47471133 0.12572053 0.17055152, -0.47470877 0.12563536 0.17055, -0.47455326 0.12507488 0.17046063, -0.47438183 0.12480827 0.17036171, -0.47415096 0.12456366 0.17022894, -0.4738678 0.12434964 0.17006616, -0.47347048 0.1241398 0.16983758, -0.47471157 0.13460828 0.17055203, -0.4748942 0.12527545 0.17061661, -0.47466326 0.12500346 0.17051224, -0.47477636 0.12531371 0.17057835, -0.47505867 0.12522623 0.17064239, -0.47529021 0.1252763 0.17064865, -0.47521791 0.12495908 0.17059083, -0.47494003 0.12484787 0.17056032, -0.47511324 0.12560587 0.1706783, -0.47477821 0.12493502 0.17054497, -0.47318193 0.12354161 0.16954194, -0.47309628 0.12375921 0.1695893, -0.47420385 0.12346731 0.16972564, -0.47340715 0.12319395 0.16931216, -0.47532681 0.12559281 0.17067517, -0.47375265 0.12405263 0.16997607, -0.47385055 0.12387931 0.169964, -0.47328743 0.12334953 0.16944776, -0.47400144 0.12366988 0.16989268, -0.47424862 0.12442896 0.17026819, -0.47435546 0.12430081 0.17028092, -0.47451106 0.12414122 0.17025785, -0.47471514 0.12397349 0.17016663, -0.47448662 0.12470481 0.17040808, -0.47459796 0.12460631 0.17043252, -0.47475675 0.12448195 0.17043199, -0.47502854 0.12447074 0.17043327, -0.47490412 0.12562031 0.17063598, -0.4627519 0.066350654 0.012357935, -0.46126691 0.067078143 0.010704413, -0.41291878 -0.035390243 0.012352094, -0.46303108 0.066920862 0.012286171, -0.46138433 0.067317903 0.010674223, -0.46329644 0.067462489 0.01207529, -0.46149597 0.067545652 0.010585502, -0.46353436 0.067948535 0.011735424, -0.4615961 0.067750171 0.01044251, -0.46373329 0.068354353 0.011283711, -0.46167961 0.067920685 0.010252699, -0.46388271 0.068659589 0.01074253, -0.46174249 0.068049043 0.01002492, -0.46397558 0.068849236 0.01013957, -0.4617815 0.068128839 0.0097713619, -0.46179476 0.068155915 0.0095042139, -0.46400693 0.068913549 0.0095045716, -0.46400705 0.068914607 -0.0094955713, -0.46179476 0.068156973 -0.0094955713, -0.41300002 0.037821934 0.1237738, -0.41300008 0.039862275 0.12323965, -0.41300002 0.037712306 0.12332906, -0.41300008 0.039932877 0.12415399, -0.41300002 0.032159239 0.12332858, -0.41300002 0.032372072 0.12292312, -0.41300011 0.02912195 0.12245755, -0.41300002 0.036390528 0.12215795, -0.41300005 0.03684707 0.12010778, -0.41300017 0.035935894 0.12210275, -0.41300011 0.035935983 0.12000276, -0.41300002 0.037433997 0.12771161, -0.41300014 0.03593564 0.12590276, -0.41300002 0.03392081 0.12913083, -0.41300008 0.039585248 0.12236546, -0.41300005 0.037499502 0.12292336, -0.41300002 0.033935562 0.12590231, -0.41300002 0.036818832 0.12232043, -0.41300005 0.037710324 0.12041788, -0.41300002 0.032675892 0.12258042, -0.41300008 0.039116278 0.12157704, -0.41300002 0.037195697 0.12258054, -0.41299999 0.0363902 0.12584744, -0.41300005 0.038480178 0.12091626, -0.41300002 0.033625454 0.12957765, -0.41299999 0.02865155 0.12241895, -0.41300002 0.033052891 0.12232016, -0.41300005 0.036818579 0.12568493, -0.41300005 0.038239345 0.12727268, -0.41299996 0.033612952 0.12953733, -0.41299999 0.028690085 0.12244894, -0.41300002 0.033608794 0.12949429, -0.41300002 0.037195548 0.12542488, -0.41300005 0.038923651 0.12666188, -0.41299999 0.028754309 0.12248017, -0.41300005 0.037499368 0.12508212, -0.41300005 0.039450854 0.12591164, -0.41300002 0.037712306 0.12467645, -0.41300002 0.03363952 0.12937175, -0.41300002 0.032675624 0.12542461, -0.41300002 0.03361626 0.12943511, -0.41300002 0.032371998 0.12508179, -0.41299999 0.02885057 0.12250055, -0.41300002 0.033481076 0.12215756, -0.41300002 0.034766451 0.12017752, -0.41300002 0.033679143 0.12930851, -0.41300002 0.033052623 0.12568463, -0.41300002 0.033935741 0.12210228, -0.41300002 0.033733428 0.12924866, -0.41300002 0.033798948 0.129196, -0.41300002 0.03215915 0.124676, -0.41300014 0.028982103 0.12249626, -0.41300002 0.033858865 0.12915967, -0.41300002 0.033480868 0.12584721, -0.41300008 0.039793327 0.12506066, -0.41300002 0.037821889 0.12423195, -0.41300002 0.032049567 0.12423144, -0.41300002 0.035149902 0.12008063, -0.41300002 0.035541013 0.12002195, -0.41300002 0.032049596 0.12377335, -0.41651323 0.037434027 0.1277114, -0.41656062 0.037395805 0.12773432, -0.41660574 0.037364826 0.12776943, -0.41664663 0.037342355 0.12781481, -0.41668126 0.037329495 0.12786813, -0.41670784 0.037326649 0.12792741, -0.41672531 0.037334219 0.12798981, -0.41975206 0.035935983 0.12000276, -0.42021856 0.036521658 0.12004568, -0.42066744 0.037159875 0.12019469, -0.42102632 0.03775999 0.12044288, -0.42124695 0.038209617 0.12071194, -0.4214085 0.038642004 0.12105711, -0.42149574 0.039039329 0.12147917, -0.42149577 0.039382607 0.12197329, -0.42138323 0.039678901 0.12259249, -0.42111641 0.039880335 0.12333979, -0.42066011 0.039931059 0.12419499, -0.4199203 0.039750829 0.12520455, -0.41887137 0.039236277 0.1262622, -0.41766033 0.038408294 0.12714706, -0.41866043 0.03476271 0.12017836, -0.41866282 0.034760922 0.12017898, -0.41865906 0.03476359 0.12017821, -0.41865876 0.034763679 0.12017836, -0.418657 0.034764379 0.120178, -0.4186545 0.034765244 0.12017776, -0.41865256 0.03476575 0.12017776, -0.41864964 0.034766153 0.1201774, -0.41864794 0.034766406 0.1201774, -0.41864452 0.034766421 0.1201774, -0.45738032 0.067078128 0.010704264, -0.44386086 0.039476395 0.010702714, -0.44137213 0.037527665 0.010702714, -0.42588565 0.012063801 0.010701433, -0.4262338 0.011753857 0.010701284, -0.42659393 0.011236116 0.010701194, -0.44179171 0.037580445 0.010702714, -0.42555061 0.012246847 0.010701194, -0.42527154 0.012329966 0.010701194, -0.42688131 0.010487378 0.010701194, -0.44224045 0.037745818 0.010702625, -0.4110001 0.037527874 0.010702625, -0.42499986 0.012356207 0.010701284, -0.42699993 0.0095278025 0.010701284, -0.44269246 0.038025036 0.010702863, -0.4431189 0.038404509 0.010702714, -0.44353452 0.038917154 0.010702714, -0.41099992 0.012356326 0.010701284, -0.45741835 0.06815584 0.0095044225, -0.45741835 0.068156987 -0.0094955713, -0.45738354 0.067734867 0.010455742, -0.4576138 0.06781292 0.010382071, -0.45742169 0.067812905 0.010382071, -0.45757571 0.067734927 0.010455742, -0.45766667 0.067920715 0.010252699, -0.45747456 0.067920715 0.010252491, -0.45740023 0.06798473 0.010153189, -0.45753744 0.068049088 0.01002501, -0.45740771 0.068062723 0.0099924654, -0.45772961 0.068049043 0.01002501, -0.4574137 0.068117395 0.0098229498, -0.4575707 0.068117216 0.0098229498, -0.45776287 0.068117112 0.0098228604, -0.45738146 0.067338452 0.010669008, -0.45748189 0.067543507 0.010586724, -0.45738241 0.067543477 0.010586843, -0.45738092 0.067221642 0.010693982, -0.45738757 0.06781292 0.010382161, -0.45739213 0.067883298 0.010302082, -0.42599991 0.0095278621 0.0097011477, -0.42599991 0.0092791617 0.0093977898, -0.42599991 0.0090944171 0.0090522617, -0.42599991 0.0089805871 0.0086769909, -0.42599991 0.0089421868 0.0082868487, -0.42599994 0.008943066 -0.0082847625, -0.42599991 0.008981511 -0.0086749643, -0.42599988 0.0090954006 -0.0090501159, -0.42600003 0.0092802495 -0.0093958229, -0.42599991 0.0095289946 -0.0096988529, -0.4390007 0.12765348 0.095757648, -0.43631253 0.12765352 0.095648572, -0.43639162 0.12765349 0.095569447, -0.43621758 0.12765341 0.095708296, -0.43645111 0.12765341 0.095474705, -0.43648806 0.1276536 0.095369086, -0.43611196 0.12765346 0.095745131, -0.43158504 0.12766163 -0.046179101, -0.43153876 0.12766157 -0.046265349, -0.43164712 0.12766162 -0.046103165, -0.43650058 0.1276536 0.095257714, -0.43600065 0.12765352 0.095757887, -0.43150076 0.12766162 -0.046456859, -0.43635425 0.1276613 -0.041396067, -0.43151036 0.12766163 -0.046359167, -0.43648806 0.1276536 0.095146522, -0.4365007 0.12765655 0.041057989, -0.43900084 0.12766431 -0.09574236, -0.43650064 0.12766117 -0.041042492, -0.43649104 0.12766112 -0.041140094, -0.43645099 0.12765352 0.095040932, -0.43646276 0.12766127 -0.041233823, -0.43641654 0.12766133 -0.041320279, -0.4363915 0.1276536 0.094945952, -0.43631247 0.12766434 -0.09485139, -0.43639162 0.12766439 -0.094930544, -0.43631235 0.12765354 0.094866857, -0.4362177 0.1276643 -0.094791785, -0.43621758 0.12765357 0.094807491, -0.43645111 0.12766419 -0.095025584, -0.43611196 0.12766425 -0.09475483, -0.43648818 0.12766433 -0.095131055, -0.4365007 0.12766439 -0.095242307, -0.43600065 0.12766431 -0.094742134, -0.43188947 0.12765364 0.094745144, -0.43178371 0.12765361 0.09470816, -0.43200067 0.12765363 0.09475778, -0.43648824 0.12766427 -0.095353648, -0.43645126 0.12766431 -0.095459267, -0.43639162 0.12766428 -0.095554069, -0.43631256 0.12766431 -0.095633194, -0.4316889 0.12765363 0.094648436, -0.43155017 0.12765363 0.094474748, -0.43160975 0.12765363 0.094569698, -0.4362177 0.1276643 -0.095692888, -0.43611196 0.12766425 -0.095729753, -0.43600067 0.12765369 0.09475778, -0.43151328 0.12765363 0.094368979, -0.43600065 0.12766431 -0.09574227, -0.4361119 0.12765357 0.094770178, -0.43150058 0.12766431 -0.09424226, -0.43200055 0.12766418 -0.094742343, -0.4315103 0.12765627 0.046374574, -0.43164712 0.12765627 0.046118751, -0.43153876 0.12765631 0.046280727, -0.43158504 0.12765642 0.046194449, -0.43178374 0.12766421 -0.094692841, -0.4318895 0.12766433 -0.094729766, -0.43635419 0.12765653 0.041411683, -0.43151319 0.1276643 -0.094353542, -0.43160978 0.12766431 -0.094554082, -0.43155017 0.12766427 -0.094459161, -0.43641648 0.12765649 0.041335747, -0.43168893 0.12766431 -0.094633237, -0.43646267 0.12765649 0.04124932, -0.4364911 0.12765653 0.041155502, -0.43050069 0.12615344 0.095757529, -0.43600067 0.12615357 0.095757529, -0.43687204 0.13574563 0.095758155, -0.43642095 0.13534604 0.095758155, -0.4372144 0.13624166 0.095758155, -0.43588737 0.13506587 0.095758155, -0.43742809 0.13680516 0.095758155, -0.43530229 0.13492182 0.095758155, -0.43750069 0.13740347 0.095758155, -0.43469939 0.13492176 0.095758095, -0.43411431 0.1350659 0.095758095, -0.43358061 0.13534601 0.095758155, -0.43312952 0.13574569 0.095758155, -0.43278715 0.1362417 0.095758155, -0.43687201 0.13906129 0.095758155, -0.43900082 0.1431535 0.095758572, -0.43642095 0.13946095 0.095758155, -0.43721455 0.13856526 0.095758483, -0.43742809 0.13800177 0.095758155, -0.43257341 0.13680518 0.095758155, -0.43250069 0.13740358 0.095758155, -0.43469948 0.13988534 0.095758483, -0.4360007 0.14315352 0.095758662, -0.43411425 0.13974105 0.095758483, -0.43530211 0.13988535 0.095758483, -0.43588737 0.13974102 0.095758483, -0.43257341 0.13800186 0.095758483, -0.43050078 0.14465345 0.095758751, -0.43278718 0.1385653 0.095758155, -0.4331294 0.13906132 0.095758483, -0.43358064 0.13946092 0.095758483, -0.43600079 0.14465353 0.095758751, -0.43750069 0.13740347 0.097258165, -0.43742809 0.13680509 0.097258165, -0.43721452 0.13624163 0.097258165, -0.43687204 0.13574563 0.097258165, -0.43642095 0.13534604 0.097258165, -0.43588737 0.13506587 0.097258165, -0.43530205 0.13492166 0.097258165, -0.43469939 0.1349217 0.097258165, -0.43411431 0.1350659 0.097258165, -0.43358061 0.13534601 0.097258046, -0.4331294 0.13574564 0.097258165, -0.43278715 0.13624163 0.097258165, -0.43257341 0.13680518 0.097258165, -0.43250069 0.13740341 0.097258165, -0.43011728 0.14465368 0.09507902, -0.43018594 0.14465363 0.095105663, -0.43032691 0.14465365 0.095269635, -0.43000081 0.14465366 0.095073208, -0.4300442 0.14465359 0.095070079, -0.42995813 0.1446536 0.095082626, -0.45100078 0.14465332 0.097258762, -0.44655958 0.14465363 0.092238054, -0.45100078 0.14465332 0.096987084, -0.42991751 0.14465371 0.095098183, -0.43639168 0.14465351 0.094947085, -0.44655958 0.14465378 0.090719327, -0.43631247 0.14465356 0.09486796, -0.42878938 0.14465344 0.095624045, -0.43621781 0.14465362 0.094808385, -0.43645123 0.14465354 0.095041856, -0.43648818 0.14465351 0.095147476, -0.42850068 0.14465347 0.09607704, -0.42851362 0.14465345 0.095964834, -0.42855135 0.14465347 0.095858052, -0.4286122 0.14465347 0.095762774, -0.42869309 0.14465353 0.095683262, -0.43650088 0.14465363 0.095258757, -0.4285008 0.14465342 0.097258672, -0.43648836 0.14465366 0.09536998, -0.43611193 0.14465342 0.095746294, -0.43645123 0.14465341 0.095475689, -0.43639162 0.14465341 0.09557052, -0.43150079 0.14465396 0.090719447, -0.43611202 0.1446536 0.09477134, -0.43600085 0.14465366 0.094758883, -0.43631247 0.14465342 0.095649675, -0.43621781 0.14465341 0.095709279, -0.43200067 0.14465359 0.094758704, -0.4315007 0.14465365 0.09425877, -0.43188962 0.14465371 0.094746247, -0.43155029 0.14465366 0.094475463, -0.43151346 0.14465377 0.094370052, -0.43168923 0.14465365 0.094649628, -0.43178383 0.1446536 0.094709083, -0.43160996 0.14465371 0.094570473, -0.43024591 0.1446536 0.095148042, -0.43029401 0.14465365 0.095203593, -0.4302938 0.12615359 0.095202759, -0.43032673 0.12615363 0.095268652, -0.43024579 0.12615365 0.095146939, -0.43018577 0.12615365 0.095104292, -0.43011704 0.12615356 0.095078155, -0.43004408 0.12615356 0.095068917, -0.4315007 0.14315364 0.09425877, -0.43150079 0.14465396 0.088719204, -0.43150082 0.14315632 0.046473041, -0.43150082 0.14465629 0.048266038, -0.43150082 0.14465633 0.046473369, -0.46200085 0.14794919 -0.090701744, -0.48079309 0.15194878 -0.11425887, -0.480793 0.15194766 -0.095161811, -0.47150102 0.14997019 -0.085869625, -0.46200094 0.14794913 -0.088701591, -0.44655958 0.14466403 -0.092220709, -0.44655961 0.14466393 -0.090701744, -0.46200097 0.14794689 -0.048248395, -0.44655958 0.14466153 -0.048248693, -0.44655964 0.14466386 -0.088701919, -0.45125952 0.14565618 0.046266004, -0.45125958 0.14566143 -0.046248659, -0.46200094 0.14794676 -0.04624851, -0.46200082 0.14794151 0.046266243, -0.46200097 0.14793916 0.088719472, -0.44655958 0.1446562 0.048266158, -0.46200088 0.14794151 0.048266307, -0.47150087 0.14996055 0.085887805, -0.46200079 0.14793906 0.090719596, -0.48079297 0.15193708 0.09517999, -0.480793 0.15193586 0.11427696, -0.44655964 0.1446539 0.088719234, -0.43635437 0.14566126 -0.041395083, -0.43431523 0.14566156 -0.046248659, -0.43431529 0.14566146 -0.043434158, -0.4364166 0.14566126 -0.041319296, -0.43646279 0.14566126 -0.04123278, -0.43649116 0.14566121 -0.041139051, -0.4365007 0.14566115 -0.041041389, -0.43650082 0.14565669 0.041059181, -0.43649116 0.14565657 0.041156456, -0.43646279 0.14565663 0.041250363, -0.4364166 0.14565663 0.04133682, -0.43635437 0.14565656 0.041412517, -0.43431526 0.1456563 0.046266064, -0.43431523 0.1456565 0.043451592, -0.47115809 0.15194874 -0.11324005, -0.47053638 0.15194862 -0.11248253, -0.45988595 0.15194638 -0.069650516, -0.45200083 0.15194519 -0.048248276, -0.46068522 0.15194626 -0.06874831, -0.45903721 0.15193838 0.073111758, -0.45200077 0.15193745 0.088719711, -0.45932576 0.15193819 0.074282125, -0.47162017 0.15194882 -0.11410446, -0.45932582 0.15194644 -0.070718005, -0.4720009 0.15193491 0.13391884, -0.48650089 0.15193468 0.13391884, -0.48650083 0.15193549 0.12038042, -0.47190472 0.15194881 -0.11504228, -0.47200081 0.15194888 -0.11601786, -0.48650077 0.15194902 -0.12036224, -0.45903721 0.15193836 0.071906343, -0.47200099 0.15193595 0.11603607, -0.45903736 0.15194659 -0.071888432, -0.47190472 0.15193595 0.11506064, -0.47200081 0.15194984 -0.1339009, -0.48650089 0.15194978 -0.13390093, -0.47162017 0.15193596 0.11412252, -0.47150102 0.15193774 0.085887894, -0.47150078 0.15194719 -0.085869595, -0.46896431 0.15193823 0.071906343, -0.46867597 0.15193839 0.070736125, -0.46896431 0.1519464 -0.071888313, -0.4689644 0.15194659 -0.073093548, -0.46896428 0.15193833 0.073111668, -0.46867597 0.15194644 -0.070718005, -0.47115818 0.15193601 0.11325811, -0.46200088 0.15194513 -0.046248302, -0.46200085 0.15193991 0.046266541, -0.47053638 0.15193595 0.1125005, -0.46867594 0.15194657 -0.074263915, -0.46811578 0.15194671 -0.075331405, -0.46731636 0.15194665 -0.076233342, -0.46200082 0.15193978 0.048266456, -0.46167728 0.15193863 0.068081811, -0.46280423 0.1519386 0.067654505, -0.46632442 0.15194674 -0.076918319, -0.46400073 0.1519386 0.06750907, -0.46519741 0.15194677 -0.077345684, -0.46519741 0.1519386 0.067654505, -0.46632442 0.15193857 0.06808196, -0.46731648 0.15193854 0.068766579, -0.46811566 0.15193853 0.069668874, -0.46200079 0.15193741 0.090719655, -0.46200085 0.15193747 0.088719711, -0.45346537 0.1519372 0.095429376, -0.45200077 0.15193978 0.048266456, -0.45932582 0.15193851 0.070736125, -0.45988593 0.15193859 0.069668874, -0.46068534 0.15193871 0.06876649, -0.4523814 0.15193725 0.093807206, -0.45284334 0.15193717 0.09467186, -0.45200083 0.15193726 0.091893837, -0.45209703 0.15193726 0.092869267, -0.45200083 0.15194514 -0.046248302, -0.45200083 0.15193988 0.046266541, -0.46811584 0.15193817 0.075349525, -0.46731633 0.15193808 0.076251581, -0.46632442 0.15193808 0.076936349, -0.468676 0.1519382 0.074282274, -0.46811566 0.15194632 -0.069650605, -0.4673163 0.15194622 -0.06874831, -0.46200085 0.15194514 -0.048248276, -0.46200085 0.15194741 -0.088701531, -0.46280429 0.15194686 -0.077345684, -0.46400076 0.15194683 -0.077491, -0.45200077 0.1519374 0.090719834, -0.46167719 0.15194669 -0.076918319, -0.46632457 0.15194628 -0.068063572, -0.46519741 0.15193808 0.077363864, -0.46200085 0.15194759 -0.090701327, -0.46519753 0.15194622 -0.067636207, -0.46400073 0.15193801 0.077509031, -0.4520008 0.15194744 -0.088701531, -0.46068522 0.15194668 -0.076233491, -0.45988593 0.15194672 -0.075331405, -0.45932573 0.15194665 -0.074264005, -0.45903745 0.15194666 -0.073093638, -0.46400076 0.15194616 -0.067490891, -0.46280435 0.15193821 0.077363864, -0.45200083 0.15194763 -0.091875747, -0.45200083 0.15194763 -0.090701386, -0.46167728 0.15193821 0.076936349, -0.46280423 0.15194623 -0.067636207, -0.45238137 0.15194778 -0.093789265, -0.45209706 0.15194778 -0.092851207, -0.46068528 0.15193823 0.076251611, -0.46167728 0.15194622 -0.068063721, -0.45988593 0.1519382 0.075349525, -0.45346537 0.15194786 -0.095411226, -0.45284346 0.15194786 -0.094653621, -0.4648788 0.15144679 -0.076904491, -0.46400076 0.1499467 -0.075491056, -0.46468377 0.15044668 -0.075923905, -0.46553156 0.15094672 -0.076186404, -0.46468371 0.15044633 -0.069058314, -0.46539509 0.14994636 -0.069834784, -0.46471879 0.14994636 -0.069578156, -0.46400088 0.14994641 -0.069491103, -0.4655315 0.1509463 -0.068795517, -0.46487883 0.1514463 -0.06807752, -0.46682933 0.1509466 -0.075319365, -0.46539515 0.1499467 -0.075147226, -0.46599016 0.14994659 -0.07473655, -0.46646985 0.14994662 -0.074195221, -0.46769655 0.15094657 -0.074021652, -0.46680602 0.1499466 -0.073554829, -0.46697903 0.14994653 -0.072852716, -0.46800083 0.15094651 -0.072490856, -0.46697903 0.14994653 -0.072129473, -0.46769634 0.15094641 -0.070960388, -0.46680605 0.14994653 -0.071427122, -0.46646985 0.14994648 -0.070786849, -0.46682936 0.15094636 -0.069662556, -0.46599025 0.14994641 -0.070245489, -0.46471879 0.1499467 -0.075403914, -0.46247008 0.1509385 0.068813547, -0.46117252 0.15093862 0.069680527, -0.4626067 0.14993863 0.069852605, -0.46331808 0.15043814 0.075941727, -0.463283 0.1499382 0.075421914, -0.46260658 0.14993821 0.075165495, -0.46400073 0.14993814 0.075509027, -0.46247008 0.15093808 0.076204821, -0.46312299 0.15143818 0.07692267, -0.46331811 0.15043864 0.069076195, -0.46328294 0.14993858 0.069596186, -0.46400091 0.14993866 0.069509134, -0.46312296 0.15143862 0.068095639, -0.46117243 0.15093817 0.075337276, -0.46201155 0.14993818 0.07475464, -0.46153182 0.14993826 0.074213132, -0.4603053 0.1509383 0.074039921, -0.4611958 0.1499383 0.073572859, -0.4610227 0.1499384 0.072870597, -0.4600009 0.15093845 0.072509155, -0.4610227 0.1499384 0.072147354, -0.46030545 0.15093845 0.070978448, -0.4611958 0.14993848 0.071444944, -0.46153197 0.14993846 0.070804819, -0.46201149 0.14993839 0.070263579, -0.48650074 0.1311502 0.14903589, -0.48650068 0.13613796 0.16550826, -0.48650065 0.13114926 0.16550802, -0.4865008 0.13760556 0.14903615, -0.48650086 0.14599967 0.14578755, -0.48650074 0.14562535 0.1441593, -0.48650086 0.14548519 0.143337, -0.48650077 0.14540574 0.14250337, -0.48650086 0.14987297 0.13804175, -0.48650089 0.14897746 0.13842596, -0.48650077 0.14809713 0.13884129, -0.48650086 0.14748271 0.13916801, -0.48650089 0.14688918 0.1395369, -0.48602107 0.14515568 0.14300372, -0.48541942 0.14496531 0.14338447, -0.48644316 0.14562511 0.1443008, -0.48529086 0.14534849 0.1448537, -0.48473218 0.1448462 0.14362241, -0.48400071 0.14480583 0.14370348, -0.48400089 0.14570011 0.14638661, -0.48571095 0.14583495 0.14611684, -0.48486903 0.14573397 0.14631881, -0.48247012 0.14869471 0.13816188, -0.48167726 0.1499164 0.13795485, -0.4811725 0.148307 0.13893749, -0.48260686 0.14733572 0.1386442, -0.48331794 0.14505947 0.14431404, -0.48328283 0.14484477 0.14362536, -0.48260668 0.14495946 0.14339601, -0.48247012 0.14538909 0.14477278, -0.48312297 0.14551523 0.14563836, -0.48280421 0.14576504 0.14625679, -0.4816772 0.14595632 0.14587425, -0.48331794 0.14813007 0.1381736, -0.48328283 0.14745034 0.13841505, -0.48400074 0.14748926 0.13833703, -0.48400089 0.15017274 0.13744269, -0.48312289 0.14946315 0.13774361, -0.48280421 0.15010779 0.13757266, -0.48117235 0.1457769 0.14399718, -0.48201147 0.14514312 0.14302863, -0.48153177 0.1453853 0.14254414, -0.48068529 0.14626254 0.1452619, -0.47988585 0.1466659 0.14445521, -0.48030534 0.14635737 0.14283656, -0.48119578 0.14567177 0.14197163, -0.48102275 0.14598583 0.14134346, -0.4793258 0.14714341 0.14350055, -0.4790374 0.14766684 0.14245369, -0.48000094 0.14704213 0.1414672, -0.4810228 0.14630936 0.14069669, -0.47903734 0.148206 0.14137568, -0.4803054 0.14772673 0.14009835, -0.4811959 0.14662351 0.14006872, -0.48153189 0.14690988 0.13949583, -0.47932574 0.14872947 0.1403289, -0.47988597 0.14920673 0.13937427, -0.48201147 0.1471519 0.13901164, -0.48068526 0.14961033 0.13856749, -0.42850068 0.12615348 0.097257629, -0.42850068 0.12615348 0.096076205, -0.49150077 0.13530143 0.16718112, -0.49150077 0.13613787 0.1655084, -0.47531486 0.13430764 0.16916861, -0.47200081 0.14425656 0.14927347, -0.42242131 0.14952323 0.13874228, -0.46464071 0.14205249 0.15368135, -0.42773157 0.15193513 0.13391884, -0.42519587 0.15193504 0.13391884, -0.47062364 0.14253333 0.15271939, -0.46976212 0.14217213 0.15344162, -0.47134474 0.14301844 0.15174936, -0.46886042 0.14193565 0.15391468, -0.46789762 0.14179674 0.15419234, -0.47181603 0.14358316 0.15061994, -0.46693411 0.14175652 0.15427293, -0.46602228 0.14180472 0.15417685, -0.46528897 0.14190742 0.15397142, -0.48486909 0.15013869 0.13751049, -0.48571092 0.15003791 0.13771255, -0.42242131 0.13115117 0.138741, -0.47531483 0.1311492 0.16916846, -0.42577025 0.15193529 0.13292055, -0.42446989 0.15193526 0.13217263, -0.48150077 0.1311496 0.16188346, -0.4758769 0.13114938 0.16372342, -0.48150069 0.1311501 0.15079577, -0.42491427 0.13115133 0.13440709, -0.42161962 0.13115133 0.13712628, -0.42353758 0.13115138 0.13361485, -0.42361417 0.13115139 0.13365917, -0.44770268 0.13115266 0.10872792, -0.41171947 0.13115166 0.13143121, -0.44490147 0.13115332 0.097257987, -0.44004858 0.13115308 0.10225584, -0.43490133 0.13115337 0.097257987, -0.44490144 0.14125662 0.097258523, -0.43649116 0.14316122 -0.04113932, -0.43650079 0.14316124 -0.041041657, -0.43900082 0.14316429 -0.095741346, -0.43650082 0.14315663 0.041059032, -0.43631253 0.14316429 -0.09563227, -0.4363918 0.14316432 -0.095553175, -0.43645123 0.14316419 -0.095458433, -0.43621764 0.14316426 -0.095691934, -0.43648836 0.14316429 -0.095352665, -0.43611196 0.14316431 -0.095728889, -0.43650088 0.14316432 -0.095241353, -0.43158507 0.14315636 0.046195194, -0.43153885 0.1431563 0.0462818, -0.43164721 0.14315626 0.046119496, -0.4360007 0.14316431 -0.095741317, -0.43151048 0.14315632 0.046375528, -0.43635437 0.14315656 0.041412428, -0.43648836 0.14316429 -0.09513022, -0.43649119 0.14315656 0.041156456, -0.4364627 0.14315656 0.041250125, -0.43641654 0.14315656 0.04133673, -0.43645123 0.14316429 -0.095024601, -0.4363918 0.14316432 -0.09492974, -0.43631244 0.14315361 0.094867751, -0.43639162 0.14315358 0.094946787, -0.43631256 0.14316428 -0.094850585, -0.43621793 0.14315371 0.094808295, -0.43621787 0.14316431 -0.094790831, -0.4364512 0.14315358 0.095041856, -0.43611193 0.14315358 0.094771162, -0.43648818 0.14315359 0.095147327, -0.43600085 0.14315365 0.094758704, -0.43650088 0.1431537 0.095258549, -0.43188959 0.14316432 -0.094728962, -0.43178377 0.14316431 -0.094692037, -0.43200079 0.14316435 -0.094741479, -0.43648836 0.1431537 0.095369652, -0.43645123 0.1431535 0.09547548, -0.43639174 0.14315359 0.095570281, -0.43631256 0.14315352 0.095649496, -0.43160996 0.14316431 -0.094553277, -0.43155032 0.14316435 -0.094458386, -0.43168902 0.14316432 -0.094632432, -0.43621781 0.14315352 0.09570919, -0.43150088 0.14316431 -0.094241515, -0.43611211 0.14315352 0.095746085, -0.4360007 0.14316431 -0.094741479, -0.43151328 0.14316429 -0.094352767, -0.43150076 0.14316155 -0.046455815, -0.43611202 0.14316426 -0.094753936, -0.43200064 0.14315365 0.094758704, -0.43151048 0.14316161 -0.046358392, -0.43164721 0.14316149 -0.04610239, -0.43153891 0.14316158 -0.046264574, -0.43158504 0.14316158 -0.046178088, -0.4317838 0.14315362 0.094709083, -0.43188956 0.14315376 0.094745979, -0.43635428 0.14316124 -0.041395143, -0.43151334 0.14315371 0.094369844, -0.43160984 0.14315362 0.094570473, -0.43155023 0.14315365 0.094475463, -0.43641666 0.14316134 -0.041319445, -0.43168899 0.14315373 0.094649598, -0.43646279 0.14316128 -0.041233078, -0.43900076 0.12970696 -0.089779601, -0.4390007 0.12934193 -0.089408144, -0.43900073 0.13014621 -0.090059415, -0.43900073 0.12906986 -0.088964269, -0.43900084 0.12886314 -0.08852084, -0.4390007 0.130637 -0.090233281, -0.43900067 0.12874418 -0.088208541, -0.43900076 0.14199476 0.088564947, -0.43900076 0.14175871 0.089037046, -0.43900082 0.14212856 0.088236079, -0.43900082 0.14221016 0.087890729, -0.43900076 0.14223768 0.087536439, -0.43900064 0.12867181 -0.087882236, -0.43900076 0.13970146 0.090308651, -0.4390007 0.13114427 0.090308055, -0.43900076 0.14020661 0.090252414, -0.43900064 0.14068702 0.090086564, -0.43900084 0.13115449 -0.090292081, -0.43900076 0.14111951 0.089819655, -0.43900076 0.14148256 0.089463934, -0.43900064 0.12864749 -0.087548956, -0.43900082 0.14224751 -0.087519422, -0.43900076 0.13971163 -0.090291604, -0.43900082 0.14021686 -0.090235457, -0.43900079 0.14069726 -0.090069637, -0.43900079 0.14112951 -0.089802518, -0.43900079 0.14149256 -0.089446917, -0.43900076 0.14176868 -0.089020118, -0.43900079 0.14200483 -0.088547841, -0.43900076 0.1421386 -0.088219061, -0.43900084 0.14222018 -0.087873295, -0.4390007 0.12863761 0.087564334, -0.43900084 0.12866192 0.087897763, -0.4390007 0.12873425 0.088224158, -0.4390007 0.12885311 0.088536486, -0.4390007 0.12905984 0.088979945, -0.4390007 0.12933196 0.089423761, -0.4390007 0.12969685 0.089795336, -0.43900073 0.13013604 0.09007524, -0.4390007 0.1306269 0.090249047, -0.45100081 0.14451753 0.097258762, -0.41229883 -0.029487893 0.033434942, -0.4122988 -0.029488415 0.042506352, -0.41430306 -0.029487818 0.031634971, -0.41430312 -0.029487669 0.029256478, -0.41790184 -0.018049449 0.046256915, -0.41707557 -0.019736245 0.044426665, -0.41790181 -0.018048748 0.033435687, -0.41671962 -0.020462871 0.043647781, -0.41733167 -0.019213468 0.045321003, -0.41628611 -0.021347851 0.043048516, -0.41748148 -0.018907547 0.046256915, -0.41580895 -0.022321939 0.042668357, -0.41550502 -0.022942439 0.04254581, -0.415207 -0.023550898 0.04250659, -0.41951832 -0.018839359 0.013120964, -0.41430303 -0.029486939 0.015498832, -0.41430309 -0.02948679 0.013120279, -0.41279873 -0.032558963 0.02925624, -0.41279885 -0.032558173 0.015498832, -0.41951832 -0.018840373 0.031635627, -0.41790181 -0.018047437 0.011320844, -0.41229883 -0.029486611 0.011320099, -0.4122988 -0.029485419 -0.011322483, -0.41790181 -0.018046245 -0.011321768, -0.41430306 -0.029485375 -0.013122454, -0.41951832 -0.018837929 -0.013121858, -0.41951832 -0.018836796 -0.031636491, -0.41430318 -0.029484361 -0.029258475, -0.41430321 -0.029484227 -0.031637177, -0.41430318 -0.029485196 -0.015501037, -0.41279873 -0.032556444 -0.015501395, -0.41279873 -0.03255567 -0.029258832, -0.41790184 -0.018044978 -0.033436522, -0.41229883 -0.029484138 -0.033437118, -0.41790181 -0.018044218 -0.046257809, -0.41733167 -0.019208401 -0.045322105, -0.41748148 -0.018902332 -0.046257839, -0.4170756 -0.019731179 -0.044427916, -0.41671962 -0.020457983 -0.043648914, -0.41628614 -0.021342993 -0.043049946, -0.41580895 -0.022317097 -0.042669848, -0.41550496 -0.0229377 -0.04254739, -0.41520706 -0.023546144 -0.042508081, -0.4122988 -0.029483631 -0.042508617, -0.41520759 -0.016729802 0.046256915, -0.41608724 -0.014933854 0.046257064, -0.41191381 -0.018907651 0.046256915, -0.41878149 -0.016253337 0.046257064, -0.43469283 0.024440005 0.046259329, -0.43871316 0.024439976 0.046259329, -0.43469286 0.026439965 0.046259537, -0.43969283 0.026439965 0.046259537, -0.46650046 0.092538357 0.046263084, -0.47150049 0.091379523 0.046263084, -0.47150061 0.11631276 0.046264544, -0.46650055 0.11280414 0.046264276, -0.44705155 0.12515618 0.046265021, -0.43412212 0.12515636 0.046265021, -0.43669727 0.026441678 0.017202094, -0.44067118 0.026441902 0.012202099, -0.44169727 0.026441813 0.013123497, -0.44169727 0.026440799 0.03163819, -0.43669727 0.026440963 0.029408082, -0.43969285 0.02644065 0.033438012, -0.43469286 0.026440859 0.031207994, -0.41966036 0.026441798 0.017201975, -0.41299996 0.026441932 0.012202099, -0.41299996 0.026441932 0.013356701, -0.44062993 0.038563162 0.012202725, -0.45459667 0.067078054 0.012204364, -0.4605749 0.06707795 0.012204394, -0.41300008 0.038563281 0.012202725, -0.41300005 0.041442186 0.0093243867, -0.44203982 0.041442037 0.0093241185, -0.41300005 0.041443199 -0.0093184561, -0.44203982 0.04144299 -0.0093185455, -0.43969163 0.024441734 0.01220189, -0.4366971 0.02444157 0.017201975, -0.44071761 0.024441868 0.013123348, -0.44071755 0.024440825 0.031638131, -0.43669713 0.024440929 0.029408023, -0.43871316 0.024440646 0.033438012, -0.43469274 0.024440825 0.031207994, -0.41966033 0.02444163 0.017201915, -0.41299996 0.024441957 0.01220189, -0.41299996 0.024441957 0.013356552, -0.42450002 0.011320651 0.012201205, -0.41299987 0.011320665 0.012201056, -0.42449978 -0.0065742582 0.012200221, -0.42450002 0.0084422082 0.0093224198, -0.41299984 0.0084421188 0.0093224198, -0.4244999 0.0084430426 -0.0093203634, -0.41299987 0.008443132 -0.0093203038, -0.4244999 0.011322051 -0.012198791, -0.41299987 0.011322096 -0.012198791, -0.41299996 0.024443343 -0.012198076, -0.43969163 0.024443254 -0.012198195, -0.42449981 -0.0065728575 -0.012199864, -0.44062993 0.038564593 -0.012197241, -0.41300002 0.038564697 -0.012197241, -0.41299996 0.026443377 -0.012198076, -0.46057498 0.067079455 -0.012195662, -0.45459667 0.067079484 -0.012195721, -0.44067129 0.026443318 -0.012197956, -0.4196603 0.02644363 -0.017197981, -0.41299996 0.026443481 -0.013352647, -0.43669727 0.026443586 -0.017197981, -0.44169721 0.026443318 -0.013119325, -0.43969283 0.02644445 -0.033434048, -0.43669727 0.026444301 -0.029404059, -0.43469274 0.026444316 -0.03120397, -0.44169727 0.026444376 -0.031633958, -0.43469283 0.02644518 -0.046255395, -0.43969291 0.02644524 -0.046255395, -0.4196603 0.024443686 -0.01719813, -0.41299996 0.024443388 -0.013352737, -0.44071755 0.024443313 -0.013119325, -0.4366971 0.024443567 -0.017197981, -0.4366971 0.024444193 -0.029404119, -0.43871316 0.024444371 -0.033434048, -0.43469289 0.024444327 -0.03120409, -0.44071755 0.024444282 -0.031633958, -0.43469271 0.024445117 -0.046255425, -0.43871328 0.024445191 -0.046255425, -0.43635419 0.12515658 0.041411445, -0.434122 0.12515646 0.043643609, -0.43641642 0.12515661 0.041335598, -0.43646261 0.12515654 0.04124932, -0.4364911 0.12515654 0.041155413, -0.43650073 0.1251566 0.041057989, -0.44705155 0.12516147 -0.046249732, -0.43650076 0.12516122 -0.041042641, -0.43649113 0.12516119 -0.041140154, -0.43646264 0.12516128 -0.041233972, -0.43641642 0.12516123 -0.041320488, -0.43635419 0.12516125 -0.041396186, -0.43412223 0.12516166 -0.046249732, -0.43412206 0.12516135 -0.04362841, -0.41878149 -0.016252682 0.033435687, -0.42039797 -0.017044261 0.031635627, -0.42039797 -0.017043248 0.013121024, -0.41878149 -0.016251415 0.011320844, -0.42449993 -0.004576534 0.011321679, -0.47150046 0.091380283 0.033441857, -0.47150049 0.091383994 -0.033430383, -0.47150055 0.08728826 0.031641707, -0.47150061 0.087291807 -0.031630501, -0.47150061 0.11631793 -0.046250299, -0.47150046 0.091384664 -0.04625164, -0.41878146 -0.016250119 -0.011321768, -0.42449978 -0.0045753568 -0.011321023, -0.4615362 0.06694749 -0.013116971, -0.46252945 0.068975151 -0.012326822, -0.46222737 0.068358555 -0.01275833, -0.46189073 0.067671135 -0.013026103, -0.4627817 0.069490135 -0.011753425, -0.46297148 0.069877505 -0.011066779, -0.46308926 0.07011798 -0.010301396, -0.46312925 0.070199475 -0.0094954818, -0.4615362 0.066946045 0.013125613, -0.46312925 0.070198372 0.0095045716, -0.46308914 0.070116758 0.010310307, -0.46297148 0.069876239 0.01107572, -0.4627817 0.069488704 0.011762336, -0.46252945 0.068973765 0.012335613, -0.46222734 0.068357065 0.012767181, -0.46189073 0.067669705 0.013034806, -0.47150043 0.087285653 0.075025305, -0.47150049 0.087286472 0.062884346, -0.47150046 0.091378763 0.061084494, -0.49150065 0.12382355 0.16718064, -0.49150065 0.12525031 0.16550766, -0.49150059 0.11043456 0.13373108, -0.49150059 0.10755613 0.13228954, -0.49150074 0.11043634 0.10571848, -0.49150059 0.10755764 0.10571824, -0.47531465 0.12475021 0.16916795, -0.47144154 0.096449807 0.1084684, -0.47391972 0.089977607 0.094586566, -0.42242113 0.1105639 0.13873996, -0.42491421 0.10854304 0.13440581, -0.42361405 0.10819444 0.13365777, -0.42161933 0.10981101 0.1371253, -0.41291252 0.10747576 0.13211627, -0.42242113 0.12915128 0.138741, -0.47531471 0.12914917 0.16916825, -0.48150077 0.12914957 0.1618831, -0.48650065 0.12914923 0.1655079, -0.47587702 0.12914947 0.16372333, -0.48650077 0.12915029 0.14903589, -0.48150077 0.12915015 0.15079556, -0.42491427 0.12915139 0.13440688, -0.42353752 0.12915145 0.13361497, -0.42161962 0.12915136 0.13712604, -0.42361405 0.12915133 0.13365917, -0.44770268 0.12915261 0.10872783, -0.41171947 0.12915172 0.13143121, -0.44490138 0.12915336 0.097257987, -0.44004846 0.12915316 0.10225569, -0.43490127 0.12915348 0.097257838, -0.45321944 0.078227565 0.11582957, -0.41291246 0.078226835 0.13211481, -0.48650071 0.12600133 0.14903568, -0.48650071 0.12525024 0.16550766, -0.48650065 0.11088207 0.13469057, -0.48650053 0.11088322 0.1166098, -0.48773757 0.11043474 0.13373105, -0.48773757 0.11043659 0.10007618, -0.48149595 0.097553954 0.090716705, -0.46217075 0.078228444 0.099332795, -0.46217057 0.078228846 0.090715632, -0.48149601 0.11269478 0.09071742, -0.44428685 0.12615377 0.090718344, -0.44899473 0.12615331 0.097257629, -0.44490138 0.12880474 0.097257629, -0.41266415 0.026436776 0.10699259, -0.41266418 0.024436757 0.10620071, -0.41268182 -0.013268247 0.091264829, -0.41202897 -0.015175283 0.090509042, -0.41220877 0.078226835 0.13170995, -0.41300634 0.15093537 0.13217266, -0.41563177 0.15093523 0.1336828, -0.42161974 0.14921276 0.13712747, -0.42360139 0.15093517 0.1336828, -0.42446989 0.15093522 0.13217263, -0.46069446 0.067358315 0.01218842, -0.4608722 0.06784685 0.012081757, -0.46104136 0.068308368 0.01187788, -0.46119508 0.068724081 0.011583284, -0.46132758 0.069079608 0.011207327, -0.46143207 0.069357634 0.010766372, -0.46150449 0.069549039 0.010275021, -0.46153483 0.069628954 0.0098945946, -0.4615449 0.069655821 0.0095045716, -0.46154502 0.069656953 -0.0094955713, -0.41196018 -0.018813059 0.046920165, -0.41196015 -0.018813118 0.047593579, -0.45585909 0.069656998 -0.0094955713, -0.45585909 0.069655895 0.0095045716, -0.4610354 0.069357648 0.010766372, -0.46097472 0.069079652 0.011207417, -0.45575467 0.069442555 0.010580912, -0.46118411 0.069357619 0.010766283, -0.46112338 0.069079652 0.011207417, -0.46138838 0.069357693 0.010766372, -0.46107832 0.069548875 0.010274872, -0.45583227 0.069601133 0.010058537, -0.46122715 0.06954892 0.010274872, -0.46143135 0.06954886 0.010274693, -0.46109655 0.069628865 0.0098945946, -0.46124533 0.069628879 0.0098945051, -0.46144965 0.069628894 0.0098945946, -0.45508876 0.067720249 0.01211904, -0.45491114 0.067720354 0.012119427, -0.45532617 0.067720264 0.01211904, -0.45520464 0.068308368 0.01187773, -0.45520845 0.068327293 0.011866912, -0.4554421 0.068308368 0.01187773, -0.45552686 0.068724126 0.011583284, -0.4554452 0.068810701 0.011504874, -0.45560196 0.069079667 0.011207327, -0.45562157 0.069170848 0.011082247, -0.46069887 0.067720205 0.01211904, -0.46081492 0.068308353 0.01187788, -0.46096352 0.068308368 0.01187773, -0.4608995 0.068723977 0.011583284, -0.46104828 0.068724066 0.011583194, -0.45520845 0.068328664 -0.011858121, -0.4549112 0.067721814 -0.012110785, -0.4554452 0.068811953 -0.011496022, -0.45562163 0.069172159 -0.011073545, -0.45575467 0.069443733 -0.010571912, -0.45583233 0.069602251 -0.010049686, -0.43530214 0.1398852 0.097258374, -0.43742809 0.13800161 0.097258165, -0.43721452 0.13856515 0.097258165, -0.43687198 0.1390612 0.097258374, -0.43642089 0.13946089 0.097258374, -0.43588737 0.13974102 0.097258523, -0.43257347 0.13800173 0.097258165, -0.43278718 0.1385653 0.097258374, -0.4331294 0.13906132 0.097258523, -0.43358067 0.13946091 0.097258523, -0.43411431 0.13974096 0.097258523, -0.43469945 0.13988517 0.097258374, -0.43000057 0.1261536 0.095072284, -0.42995802 0.12615359 0.095081553, -0.43631247 0.12615348 0.095648453, -0.43639162 0.12615348 0.095569298, -0.42991725 0.12615357 0.095097139, -0.4362177 0.12615339 0.095708087, -0.43645123 0.12615351 0.095474556, -0.43648818 0.1261536 0.095368817, -0.42878941 0.12615351 0.095623121, -0.43611202 0.12615353 0.095744923, -0.42855135 0.12615353 0.095857188, -0.42851344 0.12615356 0.09596388, -0.42869285 0.12615351 0.095682487, -0.42861214 0.12615347 0.095761582, -0.43200067 0.12615362 0.09475778, -0.4365007 0.12615357 0.095257714, -0.43600065 0.12615365 0.094757512, -0.43611202 0.12615365 0.094770178, -0.43648818 0.12615363 0.095146522, -0.43645111 0.12615359 0.095040753, -0.43639162 0.12615365 0.094945952, -0.43631253 0.1261536 0.094866857, -0.4362177 0.12615359 0.094807312, -0.43178377 0.12615365 0.09470816, -0.43188944 0.12615363 0.094745144, -0.4316889 0.12615362 0.094648436, -0.43155017 0.12615363 0.094474629, -0.43160975 0.12615362 0.094569489, -0.43151319 0.12615362 0.094368979, -0.43164721 0.14470837 0.046119556, -0.43155557 0.14467573 0.046245858, -0.43151447 0.1446612 0.0463572, -0.4315969 0.1446905 0.046178564, -0.43157485 0.12612803 0.046210185, -0.43164697 0.12610042 0.046118632, -0.4315249 0.12614702 0.046318039, -0.43150666 0.12615398 0.046394929, -0.41266418 0.026436806 0.10563813, -0.41266418 0.024436757 0.10563804, -0.4366971 0.024438888 0.065110579, -0.43469286 0.024439096 0.063310608, -0.43669713 0.024438486 0.074144945, -0.43246791 0.02443774 0.08583428, -0.43469271 0.026438951 0.063310876, -0.43669727 0.026438981 0.065110788, -0.43669727 0.026438519 0.074144945, -0.43246806 0.026437834 0.085834339, -0.42491439 0.14687985 0.13440783, -0.42361429 0.14687993 0.13365988, -0.42577025 0.14778408 0.1329204, -0.4244701 0.14778414 0.13217242, -0.41220883 0.078226849 0.13100652, -0.4571707 0.078228861 0.090715721, -0.45717064 0.078228414 0.098063841, -0.44968113 0.078227788 0.11186643, -0.43528697 0.078227475 0.11768217, -0.47649607 0.10918637 0.09071742, -0.47649613 0.1091865 0.088717178, -0.47649604 0.099625126 0.090716764, -0.47649607 0.099625275 0.08871673, -0.4645851 0.1564382 0.075069502, -0.46445563 0.15643819 0.074354127, -0.46514016 0.15643819 0.074874952, -0.46137509 0.15644649 -0.072490677, -0.46144104 0.15644655 -0.073075041, -0.46211478 0.15644655 -0.072719797, -0.46211478 0.1564465 -0.072261766, -0.46222433 0.15644646 -0.071816906, -0.46243724 0.1564465 -0.071411386, -0.46526089 0.15644671 -0.073912814, -0.46563801 0.15644659 -0.07454358, -0.46605378 0.15644653 -0.074127868, -0.46556458 0.15644661 -0.073570028, -0.4663665 0.1564465 -0.07362999, -0.46274102 0.15644655 -0.07106851, -0.46526077 0.15643838 0.071087524, -0.46526089 0.1564464 -0.07106851, -0.46662661 0.15644647 -0.072490588, -0.46400085 0.15643814 0.075135186, -0.46137512 0.15643835 0.072509304, -0.46488395 0.15644671 -0.074173048, -0.46514013 0.1564467 -0.074856386, -0.46662676 0.15643835 0.072509304, -0.46556452 0.15643828 0.071429834, -0.46488395 0.15643844 0.070826992, -0.46577737 0.15644643 -0.073164299, -0.46656069 0.15644647 -0.073075041, -0.46488389 0.15644637 -0.070808157, -0.46445552 0.15644637 -0.070645824, -0.46445563 0.15644661 -0.074335441, -0.46458521 0.15644671 -0.075050727, -0.4634167 0.15643822 0.075069413, -0.46588698 0.15644641 -0.072719648, -0.46577749 0.15643835 0.071835741, -0.46144101 0.15643832 0.073093638, -0.46445557 0.15643843 0.07066448, -0.46400085 0.15644637 -0.0705906, -0.46400079 0.15644656 -0.074390605, -0.46286163 0.1564382 0.074875101, -0.46341673 0.15644668 -0.075050548, -0.46400079 0.15644664 -0.075116381, -0.46163532 0.15643838 0.073648646, -0.46588704 0.15643834 0.072280452, -0.46588704 0.15644649 -0.072261557, -0.46354631 0.15644661 -0.074335441, -0.46236369 0.15643814 0.074562296, -0.46286163 0.15644662 -0.074856386, -0.46194807 0.15643837 0.074146584, -0.46577749 0.1564464 -0.071817115, -0.46588698 0.15643835 0.072738364, -0.46656069 0.15643825 0.073093638, -0.46354622 0.15644635 -0.070645824, -0.46311799 0.15644668 -0.074173048, -0.46556458 0.15644647 -0.071411327, -0.46236381 0.15644661 -0.07454358, -0.46577743 0.15643828 0.073183164, -0.46636662 0.15643831 0.073648646, -0.46274099 0.15644656 -0.073912814, -0.46311799 0.15644637 -0.070808277, -0.46556464 0.15643835 0.073588803, -0.46194807 0.15644661 -0.074127778, -0.4660539 0.15643835 0.074146375, -0.4624373 0.15644661 -0.073570028, -0.46526071 0.15643826 0.07393153, -0.46563807 0.15643822 0.074562296, -0.46163529 0.15644671 -0.07362999, -0.46222433 0.15644656 -0.073164448, -0.46488389 0.15643831 0.074191764, -0.46570954 0.15646948 -0.074633256, -0.46618405 0.15649705 -0.074231699, -0.46614355 0.1564694 -0.074199423, -0.46577039 0.15653449 -0.074709401, -0.4657419 0.15649724 -0.074673817, -0.46647003 0.15646943 -0.07367976, -0.46609968 0.15645243 -0.074164256, -0.46641919 0.15645228 -0.073655292, -0.46661779 0.15645231 -0.073088005, -0.46668509 0.15645228 -0.072490677, -0.46655771 0.15653434 -0.07372199, -0.46651676 0.15649697 -0.073702231, -0.46621957 0.15653434 -0.074259952, -0.46667281 0.15646943 -0.073100463, -0.46674135 0.15646932 -0.072490677, -0.46672323 0.15649709 -0.073112205, -0.46679327 0.15649691 -0.072490677, -0.46683869 0.15653434 -0.072490677, -0.46676752 0.15653434 -0.073122129, -0.46400085 0.15645245 -0.075174883, -0.46459815 0.15645246 -0.07510753, -0.46400091 0.1564696 -0.07523118, -0.46461073 0.15646958 -0.075162485, -0.46516559 0.15645245 -0.074909076, -0.46463251 0.15653457 -0.075257406, -0.46462226 0.15649725 -0.07521306, -0.46400079 0.15653458 -0.075328544, -0.46400079 0.15649723 -0.075283155, -0.4651899 0.15646946 -0.074959829, -0.46567449 0.1564524 -0.074589446, -0.46523225 0.15653448 -0.075047597, -0.46521261 0.15649721 -0.075006589, -0.46438548 0.15621324 -0.0709299, -0.46400085 0.15627655 -0.070861056, -0.46400079 0.15621315 -0.07088314, -0.464748 0.15621343 -0.073914006, -0.46438387 0.15614663 -0.074044332, -0.4643856 0.15621342 -0.074051514, -0.46438369 0.15614644 -0.070937142, -0.46508175 0.15627684 -0.073710516, -0.46475837 0.1562769 -0.073933825, -0.46477494 0.15633373 -0.073965505, -0.46474442 0.15614645 -0.071073875, -0.4643909 0.15627672 -0.070908293, -0.46474794 0.15621325 -0.071067408, -0.46475825 0.15627661 -0.071047649, -0.4656187 0.15627673 -0.07229422, -0.4656187 0.15627673 -0.072687164, -0.4656541 0.15633349 -0.072691396, -0.4655582 0.15633348 -0.071900114, -0.46570134 0.15638103 -0.072284088, -0.46560249 0.15638095 -0.071883336, -0.46510527 0.15633371 -0.073737368, -0.46537158 0.1563337 -0.073436752, -0.46513674 0.15638116 -0.073772922, -0.4656541 0.15633349 -0.072289929, -0.46541074 0.15638106 -0.073463634, -0.46541065 0.15638097 -0.071517572, -0.46565574 0.15641673 -0.07186313, -0.46443975 0.15643908 -0.074270621, -0.46545747 0.15641673 -0.071485147, -0.46400091 0.15643913 -0.074323848, -0.46560261 0.1563811 -0.073098049, -0.46545747 0.15641691 -0.073495969, -0.46565574 0.15641689 -0.073118314, -0.46517441 0.15641668 -0.071165904, -0.46550953 0.15643884 -0.071449324, -0.46521655 0.15643895 -0.071118459, -0.46442458 0.15641694 -0.07420896, -0.46400079 0.15641691 -0.074260548, -0.46575779 0.15641676 -0.072703943, -0.46571496 0.15643908 -0.073140696, -0.46582082 0.15643905 -0.072711602, -0.46485278 0.15643886 -0.070867434, -0.46582082 0.1564389 -0.072269782, -0.46485281 0.15643902 -0.07411404, -0.46559671 0.15621321 -0.072296813, -0.46506688 0.15621331 -0.073693976, -0.46441093 0.15638123 -0.074153885, -0.46558928 0.15614648 -0.072298005, -0.46558928 0.15614648 -0.072683409, -0.46506187 0.15614668 -0.073688403, -0.4647446 0.15614668 -0.07390742, -0.46559671 0.15621321 -0.072684392, -0.46400085 0.15638116 -0.074203566, -0.46552464 0.15627661 -0.071912959, -0.46534219 0.15627684 -0.073416427, -0.46482345 0.15641692 -0.074057892, -0.46555817 0.15633357 -0.07308124, -0.46521661 0.15643905 -0.073863015, -0.46537146 0.15633355 -0.071544573, -0.46513674 0.15638091 -0.071208581, -0.46570134 0.15638103 -0.072697029, -0.46400091 0.15621331 -0.074098244, -0.46439952 0.1563337 -0.074107721, -0.46400079 0.15633361 -0.074156269, -0.46482342 0.15641673 -0.070923552, -0.46575776 0.15641677 -0.072277322, -0.46479693 0.15638125 -0.074007377, -0.46443966 0.1564388 -0.070710644, -0.4657149 0.1564389 -0.071840718, -0.46400079 0.15643883 -0.070657358, -0.46517465 0.15641695 -0.073815301, -0.46550396 0.15621325 -0.071920767, -0.46532395 0.15621334 -0.073404029, -0.4653177 0.15614671 -0.073399648, -0.46549693 0.15614651 -0.07192333, -0.46550956 0.15643902 -0.07353206, -0.46534202 0.15627664 -0.071564987, -0.46552464 0.15627684 -0.073068514, -0.46510527 0.15633346 -0.071244135, -0.46439102 0.1562769 -0.074072883, -0.46400097 0.15627685 -0.074120298, -0.46479693 0.15638095 -0.070973888, -0.46442452 0.15641668 -0.070772275, -0.46400079 0.15641661 -0.070720866, -0.46532393 0.15621324 -0.071577445, -0.46531764 0.15614651 -0.071581736, -0.4650816 0.15627672 -0.071270809, -0.46550393 0.15621324 -0.073060706, -0.46549693 0.15614659 -0.073058084, -0.46477488 0.15633339 -0.071015939, -0.46441084 0.15638092 -0.070827469, -0.46400079 0.15638091 -0.07077764, -0.46506694 0.15621327 -0.071287379, -0.46506187 0.15614645 -0.071293011, -0.46439949 0.15633345 -0.070873484, -0.46400085 0.15633342 -0.070825204, -0.46400079 0.15685871 -0.075652823, -0.4647046 0.15685885 -0.075573429, -0.46537289 0.15685879 -0.07533969, -0.46597239 0.15685865 -0.074962959, -0.46647319 0.15685871 -0.07446219, -0.46684989 0.1568587 -0.073862508, -0.46708384 0.15685862 -0.07319428, -0.46716312 0.15685867 -0.072490677, -0.46223149 0.156526 0.074727997, -0.46181765 0.1564887 0.074250475, -0.46225989 0.15648867 0.074692562, -0.46229222 0.15646105 0.074652061, -0.46185833 0.15646121 0.07421802, -0.46153173 0.15646122 0.073698267, -0.46190211 0.1564441 0.074182972, -0.46158257 0.15644427 0.073674187, -0.46400079 0.15644392 0.075193807, -0.46138391 0.15644416 0.073106721, -0.46131673 0.15644424 0.072509304, -0.46144399 0.15652616 0.073740587, -0.461485 0.15648891 0.073721036, -0.46178219 0.15652604 0.074278817, -0.46132907 0.15646121 0.073119268, -0.46126029 0.15646121 0.072509304, -0.46127853 0.15648891 0.073130682, -0.46120843 0.15648885 0.072509244, -0.46123424 0.15652624 0.073140845, -0.46116301 0.1565263 0.072509304, -0.46340361 0.15644397 0.075126395, -0.46400085 0.15646103 0.075249746, -0.4633911 0.15646103 0.07518135, -0.46283621 0.15644391 0.074927941, -0.46336934 0.156526 0.075276151, -0.46337953 0.15648875 0.075232074, -0.46400079 0.15652598 0.07534726, -0.46400085 0.15648869 0.075301632, -0.4628118 0.15646103 0.074978545, -0.46232724 0.15644391 0.074608132, -0.4627696 0.15652601 0.075066254, -0.46278936 0.15648873 0.075025275, -0.46400079 0.1568502 0.075671479, -0.46329722 0.15685022 0.075592235, -0.46262881 0.15685022 0.075358227, -0.46202937 0.15685035 0.074981764, -0.46152857 0.15685025 0.074481115, -0.46115199 0.15685049 0.073881373, -0.4609181 0.15685047 0.073213086, -0.46083876 0.15685053 0.072509304, -0.46297216 0.14993843 0.073219255, -0.46283206 0.14993833 0.072952226, -0.465395 0.14993857 0.069852456, -0.46458182 0.14993843 0.071402296, -0.46482971 0.14993839 0.071573332, -0.46599028 0.14993843 0.070263579, -0.46482971 0.14993829 0.073444679, -0.46539521 0.14993826 0.075165495, -0.46599028 0.14993826 0.07475464, -0.46502963 0.14993839 0.073219165, -0.46646985 0.14993834 0.074213102, -0.46458182 0.14993836 0.073615864, -0.46471876 0.14993818 0.075421914, -0.46516964 0.1499384 0.072952017, -0.46680588 0.14993836 0.07357271, -0.46430001 0.1499383 0.073722675, -0.46275994 0.14993836 0.072659507, -0.46524173 0.14993836 0.072659597, -0.46697903 0.14993848 0.072870597, -0.46471879 0.14993855 0.069596186, -0.46429995 0.14993839 0.071295485, -0.46400073 0.14993827 0.073759064, -0.46400073 0.14993839 0.071259245, -0.46524173 0.14993836 0.072358444, -0.46697903 0.14993848 0.072147354, -0.46370173 0.14993843 0.071295485, -0.46680582 0.14993834 0.071445003, -0.46370164 0.1499384 0.073722884, -0.46276006 0.14993836 0.072358593, -0.46342006 0.14993845 0.071402296, -0.46516964 0.1499384 0.072065577, -0.46646988 0.14993848 0.070804819, -0.46283206 0.14993833 0.072065786, -0.46341997 0.14993836 0.073615655, -0.46317199 0.1499383 0.071573332, -0.46297207 0.1499384 0.071798965, -0.46502951 0.14993839 0.071799144, -0.4631719 0.14993836 0.073444709, -0.46429998 0.15313843 0.071295574, -0.46458188 0.15313847 0.071402386, -0.46482983 0.15313847 0.071573481, -0.46502963 0.15313846 0.071799144, -0.46516964 0.15313834 0.072066024, -0.46524176 0.15313838 0.072358593, -0.46524179 0.15313837 0.072659805, -0.46516967 0.15313832 0.072952434, -0.46502957 0.15313835 0.073219255, -0.46482977 0.15313834 0.073444709, -0.46458182 0.15313834 0.073616013, -0.46430007 0.15313837 0.073722884, -0.4814513 0.15224217 0.14336525, -0.48167601 0.15250699 0.14283587, -0.48526075 0.15259719 0.14265524, -0.48549247 0.15292779 0.14199464, -0.48596618 0.15273988 0.14237012, -0.48556462 0.15244389 0.14296199, -0.48632583 0.15250696 0.14283596, -0.48488393 0.15271361 0.1424226, -0.48493198 0.15305936 0.14173163, -0.48137513 0.15196116 0.14392756, -0.48577738 0.15226255 0.1433246, -0.48655036 0.15224224 0.14336525, -0.48445562 0.15278621 0.14227735, -0.48431739 0.15312703 0.14159609, -0.48588702 0.15206362 0.14372246, -0.48662657 0.15196113 0.14392756, -0.48662648 0.13948111 0.16888402, -0.48445559 0.15113619 0.14557745, -0.48488376 0.15120871 0.14543213, -0.48526087 0.15132524 0.14519928, -0.48368433 0.15312709 0.14159597, -0.48137501 0.13915883 0.16952856, -0.48588702 0.15185879 0.14413224, -0.48306975 0.1530593 0.14173152, -0.48577738 0.15165976 0.14452989, -0.48250923 0.15292783 0.1419947, -0.48556456 0.15147844 0.1448928, -0.48203546 0.15273991 0.14237024, -0.48482978 0.14572914 0.14185707, -0.48502949 0.14582998 0.14165519, -0.48297215 0.14582999 0.14165519, -0.4845818 0.14565261 0.1420099, -0.48283213 0.14594944 0.14141645, -0.48516962 0.14594933 0.14141645, -0.48473224 0.14744888 0.13841791, -0.48429993 0.14669041 0.13993461, -0.4845818 0.14664264 0.14003046, -0.48429999 0.14560466 0.14210574, -0.48541945 0.14732975 0.13865592, -0.48524177 0.1460802 0.1411549, -0.48276004 0.14608029 0.14115499, -0.48400083 0.14558855 0.14213814, -0.4840008 0.14670666 0.13990213, -0.48524174 0.1462149 0.14088537, -0.48275998 0.14621498 0.14088537, -0.48370165 0.14669038 0.13993476, -0.48370168 0.1456047 0.14210556, -0.48283198 0.14634582 0.14062388, -0.48297209 0.1464652 0.1403849, -0.48516956 0.14634585 0.14062367, -0.48341981 0.14664261 0.14003025, -0.48317185 0.14656599 0.14018343, -0.48341998 0.14565261 0.14201008, -0.48502967 0.14646523 0.14038505, -0.48317203 0.14572921 0.14185689, -0.48602107 0.14713944 0.13903643, -0.48482972 0.14656603 0.14018328, -0.48429996 0.14955249 0.14136581, -0.48458186 0.14950484 0.14146139, -0.48482969 0.14942829 0.14161445, -0.48502955 0.14932731 0.14181636, -0.48516968 0.14920788 0.1420549, -0.48524174 0.14907703 0.14231671, -0.4852418 0.14894228 0.14258613, -0.48516962 0.14881144 0.14284776, -0.48502949 0.148692 0.1430863, -0.48482981 0.14859121 0.14328812, -0.48458171 0.14851458 0.1434411, -0.48430011 0.14846689 0.14353703, -0.48529094 0.14873542 0.13808091, -0.46553168 0.15093817 0.076204613, -0.46682936 0.15093817 0.075337484, -0.46468371 0.15043856 0.069076285, -0.46553156 0.15093848 0.068813547, -0.46487874 0.15143856 0.068095639, -0.46468368 0.15043816 0.075941727, -0.4648788 0.15143803 0.0769227, -0.46682933 0.15093848 0.069680527, -0.46769649 0.15093844 0.070978448, -0.46800095 0.15093841 0.072509155, -0.46769637 0.1509382 0.074039772, -0.46716306 0.15685041 0.072509304, -0.46683872 0.15652622 0.072509304, -0.46676752 0.15652612 0.073140845, -0.46708384 0.15685044 0.073213086, -0.46684995 0.15685049 0.073881373, -0.46655777 0.15652612 0.073740587, -0.46647325 0.15685029 0.074480817, -0.46621966 0.15652597 0.074278817, -0.46597245 0.15685031 0.074981555, -0.46577027 0.15652598 0.074728206, -0.46537289 0.15685038 0.075358465, -0.46523228 0.1565261 0.075066075, -0.46470454 0.15685034 0.075592265, -0.46463236 0.15652591 0.075276002, -0.46539268 0.15688761 0.075399354, -0.4660008 0.15688759 0.075017169, -0.46603307 0.15691528 0.0750577, -0.46541515 0.15691538 0.075446114, -0.46472618 0.15691523 0.075687125, -0.46400079 0.15693232 0.07582505, -0.46400079 0.15691534 0.075768903, -0.46473879 0.15693237 0.075742051, -0.46543959 0.15693238 0.075496867, -0.46729061 0.15693836 0.073260382, -0.46731663 0.15693261 0.072509304, -0.46737516 0.15693833 0.072509393, -0.46471465 0.15688755 0.07563661, -0.46400085 0.15688756 0.075717047, -0.46720868 0.15688784 0.072509304, -0.46723345 0.15693253 0.07324715, -0.46704099 0.1569383 0.073973402, -0.46717876 0.15691549 0.073234662, -0.46726033 0.15691552 0.072509304, -0.4669883 0.15693252 0.073947981, -0.46663901 0.15693811 0.074613109, -0.46712801 0.1568878 0.073223099, -0.4669376 0.1569155 0.073923543, -0.4665933 0.15693241 0.07457681, -0.46610478 0.15693812 0.075147524, -0.46689081 0.15688771 0.073901132, -0.46654913 0.15691531 0.074541554, -0.4660683 0.15693249 0.075101808, -0.46546492 0.15693811 0.075549558, -0.46650863 0.15688759 0.074509308, -0.46475175 0.15693814 0.075799093, -0.46400085 0.15693815 0.075883701, -0.45600101 0.15693749 0.090651497, -0.46062672 0.1569384 0.072509244, -0.46071139 0.15693842 0.073260382, -0.46096078 0.15693834 0.073973313, -0.4613629 0.15693823 0.074613199, -0.47211614 0.15693763 0.084366217, -0.46189705 0.15693821 0.075147524, -0.4625369 0.15693823 0.075549707, -0.46325001 0.15693817 0.075799063, -0.46071133 0.15694663 -0.073241428, -0.45600104 0.15694769 -0.090632811, -0.46096072 0.15694658 -0.073954687, -0.46062675 0.15694658 -0.072490677, -0.4916966 0.15694828 -0.10578819, -0.49200097 0.15694831 -0.10731895, -0.49192405 0.15694818 -0.10653864, -0.49132687 0.1569483 -0.1050968, -0.49082935 0.15694812 -0.10449074, -0.47600096 0.15694886 -0.11477502, -0.47600088 0.15694985 -0.13437264, -0.49200085 0.15694985 -0.13437261, -0.47424355 0.15693621 0.11055119, -0.47375831 0.15693736 0.08743833, -0.49082935 0.15693632 0.10450961, -0.47588563 0.15694876 -0.11360441, -0.4571726 0.15693729 0.093479976, -0.47245768 0.15693761 0.085491881, -0.47301224 0.15693763 0.086529151, -0.45667511 0.15693726 0.092873886, -0.45630553 0.15693735 0.092182264, -0.45607778 0.15693727 0.09143202, -0.47554424 0.1569487 -0.11247884, -0.47498962 0.15693606 0.11146016, -0.47498968 0.15694873 -0.11144139, -0.47200084 0.15693755 0.083195552, -0.47554424 0.15693592 0.11249764, -0.47424367 0.15694858 -0.11053215, -0.49200079 0.15693614 0.10733767, -0.47375819 0.15694723 -0.087419614, -0.47588563 0.15693583 0.11362337, -0.47600088 0.1569359 0.11479391, -0.49200085 0.15693466 0.13439159, -0.47600088 0.15693471 0.13439138, -0.47200093 0.15694706 -0.083176807, -0.46737519 0.15694655 -0.072490588, -0.45717266 0.15694784 -0.093461171, -0.47301215 0.15694721 -0.086510286, -0.47245765 0.15694714 -0.085473135, -0.45630538 0.15694769 -0.092163518, -0.45667502 0.15694785 -0.092855081, -0.45607784 0.15694758 -0.091413185, -0.47211623 0.15694717 -0.084347472, -0.46663916 0.15694655 -0.074594393, -0.46610472 0.15694669 -0.075128779, -0.46546495 0.15694673 -0.075530842, -0.46704099 0.15694651 -0.073954687, -0.4647519 0.15694672 -0.075780347, -0.46729049 0.15694651 -0.073241368, -0.46400085 0.15694679 -0.075864986, -0.49169654 0.15693638 0.1058072, -0.49132684 0.15693632 0.10511567, -0.46325001 0.15694667 -0.075780287, -0.4625369 0.15694666 -0.075530842, -0.46189705 0.15694657 -0.075128779, -0.49192408 0.15693636 0.1065575, -0.46136281 0.15694657 -0.074594483, -0.462001 0.15689607 -0.074998453, -0.46152866 0.1568587 -0.07446219, -0.46149313 0.15689608 -0.074490413, -0.46145251 0.1569238 -0.074522957, -0.46258676 0.15692391 -0.075427249, -0.46196863 0.15692377 -0.075038984, -0.46193346 0.15694085 -0.075083002, -0.46256223 0.15694091 -0.075477913, -0.46326306 0.15694095 -0.075723305, -0.46400079 0.15694097 -0.075806484, -0.46260914 0.1568962 -0.075380549, -0.46262899 0.15685885 -0.075339511, -0.46202931 0.15685876 -0.074962959, -0.46327564 0.15692389 -0.075668409, -0.46400085 0.15692386 -0.075750098, -0.46328712 0.15689613 -0.075617746, -0.46400079 0.15689614 -0.075698271, -0.46329728 0.15685885 -0.075573429, -0.46076828 0.15694082 -0.073228493, -0.4606851 0.15694082 -0.072490796, -0.46082321 0.15692376 -0.073215947, -0.46074143 0.15692367 -0.072490796, -0.46101359 0.15694086 -0.073929206, -0.46087369 0.15689602 -0.073204383, -0.46091804 0.15685877 -0.07319437, -0.46083879 0.15685868 -0.072490677, -0.46079329 0.15689598 -0.072490588, -0.46106425 0.15692376 -0.073904827, -0.46140841 0.15694085 -0.074558035, -0.46111107 0.15689608 -0.073882326, -0.46115193 0.15685871 -0.073862657, -0.46116301 0.15653439 -0.072490677, -0.41295108 -0.035467252 0.012429133, -0.41293779 -0.035427108 0.012389049, -0.41296014 -0.035536677 0.012498602, -0.41196629 -0.03358449 0.060301229, -0.41194996 -0.033636928 0.060353652, -0.41193745 -0.033728763 0.060445562, -0.41194746 -0.033813104 0.060529754, -0.41197881 -0.033885807 0.060602441, -0.41291878 -0.035393104 0.062109604, -0.41295108 -0.035470054 0.062186465, -0.41293782 -0.035429895 0.06214644, -0.41296008 -0.035539582 0.062255993, -0.47263548 0.086526647 0.062116399, -0.47263554 0.08995299 0.060609385, -0.4129549 -0.035485163 0.032308742, -0.41291878 -0.035391435 0.032402501, -0.41294095 -0.035435989 0.032357767, -0.41296014 -0.035537794 0.032256052, -0.41197881 -0.033884287 0.033909515, -0.41195521 -0.033835858 0.033958122, -0.41194117 -0.033781365 0.034012482, -0.4119446 -0.033659473 0.034134582, -0.47263542 0.086528242 0.032409415, -0.47263554 0.089954421 0.033916429, -0.49200079 0.15661794 0.13573293, -0.47600096 0.15661801 0.13573308, -0.47600091 0.15679266 0.13530393, -0.49200085 0.15679251 0.13530378, -0.47600093 0.15689896 0.13485326, -0.49200085 0.15689889 0.13485326, -0.48591766 0.15365043 0.14166723, -0.48652664 0.15340909 0.14214967, -0.48698863 0.1531097 0.14274837, -0.48519737 0.15381956 0.14132915, -0.48727712 0.15276958 0.14342879, -0.48440769 0.15390666 0.14115514, -0.48737517 0.15240839 0.14415096, -0.48359415 0.15390654 0.14115499, -0.48280439 0.15381953 0.14132915, -0.48208404 0.15365048 0.14166714, -0.48147532 0.15340912 0.14214982, -0.48101315 0.15310982 0.14274846, -0.48072466 0.15276965 0.14342879, -0.48062667 0.15240833 0.14415111, -0.49200073 0.14100702 0.16695045, -0.48737511 0.14072289 0.16751833, -0.47600076 0.14002471 0.16891505, -0.48062655 0.14030866 0.16834711, -0.49210945 0.13886297 0.16856609, -0.49212274 0.1383087 0.16861631, -0.47612259 0.13732634 0.17058061, -0.47610518 0.13803267 0.17049815, -0.47608063 0.13872527 0.17023872, -0.48134807 0.13915919 0.16953059, -0.48132148 0.13916348 0.16953059, -0.48127827 0.13917832 0.1695254, -0.48124072 0.13920112 0.16951524, -0.48120859 0.13922916 0.16950057, -0.48116288 0.13928795 0.16946684, -0.47605112 0.13933885 0.16981338, -0.48099053 0.13958612 0.16925608, -0.4920918 0.13941735 0.16840695, -0.48666981 0.13948873 0.16887553, -0.48670951 0.13950469 0.1688628, -0.48090553 0.13975832 0.16910194, -0.48083851 0.13991767 0.16893227, -0.47602597 0.13973024 0.16938864, -0.49206412 0.14007232 0.16804902, -0.4869515 0.13983947 0.16861616, -0.48704734 0.14003049 0.16844831, -0.48683873 0.13963634 0.16876991, -0.48674491 0.13952699 0.16884644, -0.4867852 0.13956326 0.1688209, -0.48681423 0.13959846 0.16879629, -0.48074096 0.1401296 0.16865467, -0.49203268 0.14061512 0.16754554, -0.48716295 0.14030603 0.16815574, -0.47612265 0.1352786 0.17058061, -0.49212262 0.12475915 0.16861533, -0.47533202 0.1257205 0.17067714, -0.47533193 0.13507743 0.17067765, -0.47552589 0.1351731 0.17065404, -0.47575632 0.13523889 0.17062555, -0.47601286 0.1352718 0.1705942, -0.47529158 0.12572059 0.17068134, -0.4752101 0.13499786 0.17068522, -0.47525075 0.12572052 0.17068379, -0.47521007 0.1257205 0.17068456, -0.47608221 0.13732643 0.17058475, -0.47604159 0.13732649 0.17058729, -0.47600237 0.13527487 0.17058812, -0.47600064 0.13732639 0.17058821, -0.47600076 0.13527492 0.17058812, -0.48116305 0.15203974 0.14396642, -0.48083875 0.15232977 0.14411156, -0.48124549 0.15234351 0.14335917, -0.48093066 0.15266833 0.14343487, -0.48148805 0.15262964 0.14278699, -0.48120096 0.15298709 0.14279737, -0.4818767 0.15288147 0.1422836, -0.48163399 0.15326759 0.14223622, -0.48238882 0.15308449 0.14187779, -0.4822045 0.15349373 0.14178397, -0.48299453 0.15322657 0.14159347, -0.48287961 0.15365225 0.1414672, -0.48365876 0.15329972 0.14144696, -0.48361978 0.15373382 0.14130415, -0.48434296 0.15329994 0.14144705, -0.48438206 0.1537338 0.141304, -0.48500711 0.15322658 0.14159347, -0.48512229 0.15365233 0.14146711, -0.48561293 0.15308437 0.14187779, -0.48579711 0.15349379 0.14178397, -0.48612514 0.15288138 0.14228366, -0.48636782 0.15326771 0.14223613, -0.4865137 0.15262958 0.14278699, -0.48680079 0.15298697 0.14279748, -0.48675632 0.15234362 0.14335917, -0.48707119 0.15266824 0.14343487, -0.48683879 0.1520398 0.14396642, -0.4871631 0.1523298 0.14411156, -0.49201757 0.12220803 0.16720863, -0.4920347 0.12243678 0.1675248, -0.49206039 0.12287505 0.16795598, -0.49208388 0.12339759 0.16829221, -0.49210557 0.12403686 0.16852866, -0.47582623 0.13527867 0.17057274, -0.47582719 0.1373264 0.17057286, -0.47565761 0.13529527 0.17052744, -0.47565886 0.13732645 0.17052777, -0.4759995 0.13876137 0.17022301, -0.4760063 0.13858739 0.17030998, -0.47585186 0.13858268 0.17029984, -0.47584587 0.13875557 0.17021225, -0.47561529 0.13912326 0.16989405, -0.47562853 0.1387271 0.17015956, -0.47548983 0.13869432 0.17009954, -0.4754993 0.13826945 0.17029293, -0.47550073 0.13817973 0.17032419, -0.4754214 0.13825303 0.17024563, -0.47547933 0.13908079 0.1698391, -0.47523984 0.13859364 0.16991435, -0.47524187 0.13844092 0.16999336, -0.47510991 0.13835832 0.16981481, -0.47510901 0.13849995 0.16974179, -0.47510216 0.13933405 0.16897948, -0.47504127 0.13898571 0.16915666, -0.47504032 0.13920297 0.16888754, -0.47509989 0.13951837 0.168662, -0.47510454 0.13910276 0.16926841, -0.47586849 0.13803175 0.17049412, -0.47539577 0.13935778 0.16951187, -0.47523484 0.13895173 0.16967301, -0.47522971 0.1392425 0.16940166, -0.47540474 0.1390499 0.16979943, -0.47564647 0.13801862 0.17043974, -0.47504207 0.13873208 0.16938971, -0.47504279 0.13842109 0.16959675, -0.47501031 0.13848872 0.16938241, -0.47501019 0.13864163 0.16927312, -0.47582933 0.13916151 0.16994359, -0.47564015 0.1382917 0.17035674, -0.47546902 0.13939452 0.16954683, -0.47541675 0.13850845 0.17013918, -0.47533238 0.1382298 0.17017876, -0.47522444 0.13949068 0.16908954, -0.47521898 0.13968793 0.16874646, -0.47549376 0.13852946 0.17018475, -0.47598103 0.1391705 0.16995509, -0.47602457 0.13803388 0.1705025, -0.47560233 0.13944538 0.16959532, -0.47538659 0.13962077 0.16918091, -0.47537729 0.13982959 0.16881727, -0.47510669 0.13883236 0.16951893, -0.47541341 0.1386703 0.17005523, -0.47581288 0.13949224 0.16964017, -0.47545823 0.13966236 0.16921024, -0.47556695 0.13993615 0.16887064, -0.47500995 0.13887993 0.16905598, -0.47500074 0.13878222 0.16896276, -0.47586069 0.13831066 0.17041095, -0.47558886 0.13972051 0.16925107, -0.47577825 0.14000237 0.16890343, -0.47563317 0.1385581 0.17024638, -0.47579566 0.1397758 0.16928981, -0.47594365 0.13979182 0.16930126, -0.47500983 0.1390847 0.16880448, -0.4750008 0.13897522 0.16872759, -0.47500077 0.13913028 0.16846772, -0.47502601 0.13932933 0.16856723, -0.47520062 0.13828905 0.1700031, -0.47510466 0.13835408 0.16980542, -0.47500083 0.13855782 0.16916533, -0.47500083 0.15593585 0.11479367, -0.47500083 0.15593471 0.13439138, -0.47500083 0.15573587 0.11479367, -0.47500089 0.15573479 0.13481633, -0.47500086 0.15591086 0.13469906, -0.47500086 0.15583993 0.13499971, -0.47500083 0.15572357 0.13528566, -0.47490475 0.15573588 0.1138183, -0.47490481 0.15593591 0.11381809, -0.47462031 0.15573587 0.11288022, -0.47462025 0.15593596 0.11288027, -0.47415826 0.15573616 0.1120158, -0.47415814 0.15593612 0.11201592, -0.47353655 0.15573616 0.11125825, -0.47353646 0.15593621 0.11125813, -0.45646533 0.15573725 0.094187036, -0.45646539 0.15593724 0.094186857, -0.45509693 0.15573724 0.091626808, -0.45500079 0.15573733 0.090651259, -0.45500091 0.15593745 0.090651497, -0.45509693 0.15593724 0.091626868, -0.45538148 0.15573725 0.092564985, -0.45538148 0.15593727 0.092564985, -0.45584354 0.15573719 0.093429312, -0.4558436 0.15593728 0.093429312, -0.45500094 0.15594758 -0.09063296, -0.45500094 0.15574755 -0.09063296, -0.47577843 0.15659566 0.13572182, -0.47556701 0.15652952 0.13568874, -0.47537747 0.1564229 0.13563521, -0.47521916 0.15628131 0.13556461, -0.47510007 0.15611175 0.13547985, -0.47502598 0.15592267 0.13538532, -0.47577837 0.15687431 0.13484927, -0.47556701 0.15669821 0.13527371, -0.47556698 0.15680121 0.13483791, -0.47577849 0.15676871 0.13529642, -0.47556698 0.15683575 0.13439132, -0.47502604 0.15615734 0.13439138, -0.47502604 0.15605199 0.13506763, -0.47510001 0.15625335 0.13513176, -0.47502604 0.15613085 0.13473348, -0.47521904 0.15643398 0.13518949, -0.47510004 0.15633972 0.13476582, -0.47509986 0.15636866 0.13439138, -0.47537747 0.15658475 0.13523747, -0.47521916 0.15652712 0.13479514, -0.47521904 0.15655832 0.13439138, -0.47537747 0.15668347 0.13481943, -0.47537747 0.1567166 0.13439138, -0.47577831 0.15690961 0.13439132, -0.47577837 0.15691085 0.11479367, -0.47556695 0.1568369 0.11479367, -0.47537741 0.15671775 0.11479391, -0.47521904 0.15655938 0.11479391, -0.47509989 0.15636979 0.11479367, -0.47502598 0.15615842 0.11479391, -0.47482178 0.15655942 0.11279677, -0.47433969 0.15655968 0.11189468, -0.4744713 0.15671791 0.1118065, -0.47545996 0.15683684 0.11370771, -0.47566751 0.1569109 0.11366652, -0.47514328 0.15683696 0.1126637, -0.47533861 0.1569109 0.11258276, -0.47471175 0.15636988 0.11284254, -0.47424069 0.15637007 0.11196075, -0.47527418 0.15671775 0.11374499, -0.47496817 0.15671778 0.11273633, -0.47464344 0.15615854 0.11287053, -0.47417918 0.15615875 0.11200188, -0.47511873 0.15655945 0.11377575, -0.4750019 0.15636989 0.11379893, -0.4749293 0.15615845 0.11381327, -0.4735541 0.15615866 0.11124022, -0.47480467 0.15691087 0.1115839, -0.47408614 0.1569111 0.11070843, -0.47462907 0.1568372 0.11170121, -0.47393674 0.15683712 0.1108578, -0.47380283 0.15671799 0.11099179, -0.4736906 0.15655954 0.11110388, -0.47360644 0.15637016 0.11118813, -0.45701519 0.15691218 0.093637332, -0.4568657 0.15683821 0.093786791, -0.45673153 0.156719 0.093920872, -0.45661965 0.15656069 0.094032839, -0.45653543 0.15637116 0.09411715, -0.4564831 0.15615976 0.094169244, -0.45572942 0.1567191 0.092420921, -0.45615658 0.15671909 0.093220398, -0.456025 0.15656079 0.093308195, -0.45649001 0.15691213 0.092997387, -0.45631444 0.15683831 0.093114927, -0.45531088 0.15656073 0.091584489, -0.45509997 0.1563714 0.090651497, -0.455219 0.15656091 0.090651497, -0.45547301 0.15637113 0.092527017, -0.45519403 0.15637125 0.091607556, -0.45558316 0.15656073 0.092481539, -0.45590457 0.15683828 0.092348412, -0.4554663 0.15671912 0.091553673, -0.45537731 0.15671918 0.090651497, -0.45609984 0.15691222 0.092267498, -0.45565221 0.15683824 0.09151648, -0.45556703 0.15683849 0.090651497, -0.4558596 0.15691228 0.091475353, -0.45577839 0.15691236 0.090651497, -0.45502588 0.15615994 0.090651497, -0.45586446 0.15615979 0.093415424, -0.45592591 0.15637119 0.093374357, -0.45540461 0.15615983 0.09255521, -0.45512149 0.15615988 0.09162198, -0.45577833 0.15692249 -0.09063296, -0.45556709 0.15684864 -0.09063296, -0.45537737 0.15672949 -0.09063296, -0.45521909 0.15657111 -0.09063296, -0.45509994 0.15638156 -0.09063296, -0.45502588 0.15617014 -0.09063296, -0.47222346 0.15691252 0.083195552, -0.47222355 0.156922 -0.083177045, -0.47243473 0.15683867 0.083195552, -0.47243479 0.15684809 -0.083176896, -0.47262439 0.15671946 0.083195552, -0.47262439 0.15672897 -0.083176896, -0.4727827 0.15656111 0.083195552, -0.47278288 0.15657064 -0.083177045, -0.47290185 0.1563715 0.083195552, -0.47290185 0.15638098 -0.083176896, -0.47297579 0.15616016 0.083195552, -0.47297591 0.15616961 -0.083177045, -0.47300094 0.15593763 0.083195552, -0.47300091 0.1559471 -0.083176896, -0.47300082 0.14956519 -0.083177403, -0.47300091 0.14955582 0.083195224, -0.47309694 0.15593757 0.084171131, -0.47313705 0.14959058 0.084354207, -0.47338149 0.15593754 0.085109249, -0.4735482 0.14969544 0.085469469, -0.47384354 0.15593761 0.085973367, -0.47396162 0.14980096 0.086142078, -0.47446534 0.15593752 0.086731061, -0.47446531 0.1499296 0.086730793, -0.49153647 0.15593651 0.10380222, -0.48860291 0.15293665 0.1008686, -0.49153635 0.15293641 0.10380201, -0.49300089 0.15293621 0.10733767, -0.49300089 0.15593621 0.10733767, -0.49290478 0.15593629 0.10636236, -0.49290478 0.15293626 0.10636233, -0.49262041 0.15593626 0.10542439, -0.49262038 0.15293635 0.10542439, -0.4921582 0.15593633 0.10455991, -0.4921582 0.15293635 0.10455976, -0.49300078 0.1385338 0.16214131, -0.49300086 0.15572353 0.13528581, -0.49300084 0.15217718 0.13485865, -0.49300081 0.14011267 0.16650318, -0.49300084 0.15583983 0.13499971, -0.49300086 0.1525906 0.13381948, -0.49300084 0.15591085 0.13469906, -0.49300084 0.15284875 0.1326669, -0.49300084 0.15593466 0.13439138, -0.49300089 0.1529348 0.13147457, -0.49300069 0.12319103 0.16686808, -0.49300066 0.12475915 0.16762291, -0.49300069 0.1229327 0.1664529, -0.49300066 0.12351598 0.16719024, -0.49300066 0.12386727 0.16741277, -0.49300072 0.12425162 0.16755734, -0.49300072 0.12450702 0.16760691, -0.49300078 0.12539025 0.16316937, -0.49300072 0.12493975 0.16265045, -0.49300066 0.12592287 0.16358601, -0.49300069 0.12459114 0.16205169, -0.49300069 0.1265257 0.16389285, -0.49300072 0.12718637 0.16408192, -0.49300066 0.12787649 0.16414498, -0.49300084 0.1383087 0.16762386, -0.49300084 0.13529119 0.16414537, -0.49300075 0.13878013 0.16756712, -0.49300089 0.13924299 0.16739221, -0.49300072 0.13596424 0.16408513, -0.49300084 0.13965335 0.16710623, -0.49300078 0.13661008 0.16390525, -0.49300075 0.13991532 0.16682096, -0.49300078 0.13720211 0.16361214, -0.49300072 0.10734904 0.13302873, -0.49300089 0.13772905 0.1632136, -0.49300092 0.13817908 0.16271676, -0.4930006 0.11164904 0.13429327, -0.4930006 0.11125888 0.13324483, -0.4930006 0.11101587 0.13208897, -0.49300057 0.11093481 0.13089626, -0.49300057 0.10735047 0.10677837, -0.49300066 0.11093622 0.10677849, -0.49265674 0.13680539 0.16297017, -0.492475 0.13713449 0.16256414, -0.4924815 0.13674124 0.16286613, -0.49297807 0.13709053 0.16343175, -0.49263841 0.13756217 0.1622542, -0.49245539 0.13746628 0.16218255, -0.49242359 0.13772322 0.16173612, -0.49261656 0.13782895 0.16178904, -0.49279103 0.13768825 0.16234885, -0.49277797 0.13797092 0.16186009, -0.49290562 0.1378379 0.16246103, -0.49289957 0.13814175 0.16194533, -0.49297673 0.13800384 0.16258536, -0.49297521 0.13833259 0.16204081, -0.49285939 0.13738239 0.16283499, -0.4928019 0.13688765 0.16310309, -0.49291065 0.13698411 0.16325937, -0.4926587 0.12632751 0.1629511, -0.49247769 0.12684739 0.16307496, -0.49248448 0.12639314 0.1628481, -0.49297819 0.12603655 0.16340767, -0.49263942 0.12732692 0.16332506, -0.49245694 0.12734902 0.16320704, -0.49242339 0.12787651 0.16323854, -0.49261633 0.12787658 0.16335677, -0.49279168 0.12729827 0.16347979, -0.49277785 0.12787651 0.16351555, -0.49290594 0.12726413 0.16366325, -0.49289945 0.12787645 0.16370641, -0.4929767 0.12722629 0.16386698, -0.49297503 0.12787649 0.16391991, -0.49286011 0.12671298 0.16341649, -0.49280313 0.12624361 0.16308294, -0.49291119 0.12614501 0.16323756, -0.49290487 0.11093624 0.10580455, -0.49290541 0.10727443 0.10580765, -0.49262115 0.1109363 0.10486783, -0.49261996 0.10704601 0.10486473, -0.49216032 0.11093631 0.10400416, -0.49216023 0.10667832 0.10400401, -0.4886573 0.11093675 0.098751679, -0.47384074 0.088360563 0.076534078, -0.47384092 0.11629726 0.076535538, -0.47300041 0.087169975 0.073759899, -0.47301665 0.087209821 0.074162915, -0.47300062 0.11666207 0.073761329, -0.47309586 0.11662062 0.074732348, -0.47306556 0.087329268 0.074563935, -0.47314632 0.087527469 0.074959204, -0.47338137 0.11649673 0.075675085, -0.47331655 0.087731451 0.075509235, -0.47354946 0.088011056 0.076037511, -0.47300044 0.090967 -0.060862526, -0.47300041 0.08717832 -0.073748842, -0.47300044 0.090735495 -0.061050668, -0.47300044 0.090517208 -0.0611846, -0.47300044 0.090270862 -0.06130524, -0.47300071 0.11667041 -0.073747113, -0.47300044 0.091269657 -0.060244575, -0.47300044 0.091251239 -0.060400799, -0.47300047 0.09119457 -0.060557559, -0.47300053 0.091099635 -0.060712412, -0.47300047 0.090264067 0.061316565, -0.47300044 0.087170571 0.062676981, -0.4730005 0.091268227 -0.034258619, -0.47300044 0.091250226 -0.034105048, -0.47300053 0.091246381 0.034116462, -0.47300047 0.091191709 0.033962116, -0.47300044 0.091195479 -0.033950731, -0.47300044 0.090510383 0.061195984, -0.4730005 0.090728745 0.061061934, -0.47300032 0.090960175 0.060873643, -0.47300053 0.091244385 0.060412183, -0.47300047 0.091262937 0.0602559, -0.47300032 0.09118776 0.060569063, -0.47300032 0.09109278 0.060723737, -0.47300047 0.091264367 0.034270123, -0.47300041 0.087172329 0.031848684, -0.47300044 0.090269268 -0.033198223, -0.47300041 0.087175876 -0.031837717, -0.47300047 0.090265572 0.033209488, -0.47300047 0.090804979 0.033518389, -0.47300044 0.091056183 0.033754036, -0.47300044 0.090808704 -0.033506885, -0.47300047 0.091059968 -0.033742562, -0.47300041 0.087177649 -0.062666073, -0.48800078 0.13401683 0.16117658, -0.49242344 0.13529114 0.16323899, -0.48800084 0.13466479 0.16110156, -0.49245521 0.13580522 0.16320883, -0.49247494 0.13629533 0.16308294, -0.48800072 0.13528457 0.16087092, -0.48800084 0.13577931 0.16053627, -0.48800084 0.13614896 0.16014935, -0.4880009 0.13631143 0.15991805, -0.4880009 0.13644864 0.1596738, -0.48800081 0.15167703 0.12906249, -0.4880009 0.15187058 0.12819798, -0.4880009 0.15136671 0.12984167, -0.4880009 0.15193519 0.12730385, -0.48800066 0.12751064 0.16060506, -0.48800066 0.1284925 0.1610892, -0.48800066 0.12707797 0.16017462, -0.48800078 0.12797716 0.16089891, -0.4880009 0.13832571 0.14689182, -0.48800084 0.15193553 0.11967589, -0.48800066 0.12884071 0.16115497, -0.48800066 0.12672634 0.15960644, -0.48800072 0.12539294 0.14705335, -0.48800057 0.1119356 0.11818995, -0.48800054 0.11193511 0.12648259, -0.48800066 0.1124709 0.12903069, -0.48800066 0.12919053 0.16117631, -0.48800066 0.12634991 0.14834879, -0.48800066 0.12598559 0.14798985, -0.48800078 0.12566404 0.14755259, -0.48800084 0.12674607 0.14861666, -0.48800066 0.127161 0.14878638, -0.48800066 0.12758103 0.14885698, -0.48800078 0.12768254 0.14885975, -0.48800066 0.11204335 0.12767215, -0.48800066 0.11221978 0.12838216, -0.48800072 0.13581327 0.14886026, -0.48800072 0.13619901 0.14882083, -0.48800078 0.1365902 0.1487001, -0.48800078 0.13714777 0.14837812, -0.48800072 0.13770254 0.14784966, -0.48790085 0.12760454 0.14842202, -0.4877803 0.12768249 0.14823346, -0.48778072 0.12761487 0.14823209, -0.48790061 0.12768257 0.14842375, -0.48797545 0.12759306 0.14863394, -0.48797539 0.12768246 0.14863606, -0.49200055 0.1119348 0.13089629, -0.48800078 0.11193575 0.11738344, -0.49200055 0.11193623 0.10677849, -0.48800078 0.11193575 0.11683516, -0.4880006 0.11193575 0.11632563, -0.4916971 0.11193635 0.10524999, -0.49192384 0.11193626 0.10599943, -0.49132845 0.11193635 0.10455932, -0.4880006 0.11193676 0.099569485, -0.49082938 0.15193631 0.10450925, -0.49169651 0.15193631 0.1058069, -0.49132672 0.15193629 0.10511522, -0.49192402 0.15193631 0.10655712, -0.4880009 0.15193656 0.10168062, -0.49200091 0.15193629 0.10733749, -0.48800093 0.15193562 0.11766674, -0.48800093 0.15193562 0.11826657, -0.48800084 0.15193559 0.1188717, -0.49200076 0.15193483 0.13147457, -0.4700402 0.14811838 0.047333106, -0.47004446 0.14811899 0.052440241, -0.47006667 0.14812398 0.047102019, -0.44412255 0.14260235 0.078702703, -0.44403902 0.14258422 0.083433047, -0.44416365 0.1426108 0.083239213, -0.46997914 0.14810508 0.05223842, -0.44393507 0.14256939 -0.045181736, -0.44393504 0.14256917 -0.039632335, -0.44395718 0.14257388 -0.039843842, -0.47006661 0.14812368 0.052651629, -0.4698081 0.14807248 -0.015649334, -0.46983111 0.14807713 -0.011510119, -0.46994856 0.14810243 -0.015850678, -0.44402012 0.14258058 0.078521237, -0.4439615 0.14256774 0.083651111, -0.48800084 0.15194893 -0.11764868, -0.48465908 0.15123756 -0.11181484, -0.4848296 0.1512738 -0.11165525, -0.48495859 0.15130129 -0.11145912, -0.48445663 0.15119453 -0.1119294, -0.46962327 0.14803314 -0.015489444, -0.46966162 0.14804111 -0.011669651, -0.46995944 0.1481044 -0.011314377, -0.47003654 0.14812116 -0.01608108, -0.44472861 0.1427342 0.025228277, -0.4448835 0.14276698 0.028743848, -0.44509771 0.14281259 0.028761461, -0.48503917 0.15131846 -0.11123751, -0.48423356 0.15114702 -0.11199151, -0.4694601 0.14799823 -0.0117843, -0.46940598 0.1479869 -0.015380725, -0.44467089 0.14272171 0.028774515, -0.44451436 0.14268866 0.025159284, -0.4700394 0.14812143 -0.011093244, -0.48506656 0.15132414 -0.11100267, -0.47006661 0.14812756 -0.016326562, -0.48400247 0.15109792 -0.11199878, -0.48377618 0.15104976 -0.11195038, -0.44447002 0.14267901 0.02885212, -0.44432116 0.14264753 0.025042251, -0.48356721 0.15100534 -0.11184897, -0.46923813 0.14795104 -0.011847511, -0.46916911 0.14793649 -0.015330061, -0.44429028 0.14264086 0.028972402, -0.44415906 0.14261316 0.024883106, -0.47006673 0.14812717 -0.010859236, -0.44393501 0.14256279 0.070425496, -0.44110376 0.14195953 0.087475166, -0.44393501 0.14256257 0.076140508, -0.44395667 0.14256713 0.078322247, -0.44393522 0.1425626 0.078114048, -0.44414064 0.14260899 0.029130086, -0.4439351 0.14256337 0.062734976, -0.44393501 0.14256297 0.068401679, -0.44403687 0.14258713 0.024690434, -0.46900779 0.14790207 -0.011855856, -0.44393516 0.14256355 0.060664967, -0.48356718 0.15099272 0.11186694, -0.44439206 0.14265935 0.086646542, -0.44423684 0.1426263 0.086522803, -0.44410887 0.14259902 0.08636938, -0.44401371 0.14257881 0.086193189, -0.44395494 0.14256635 0.086000934, -0.44402841 0.14258505 0.029317275, -0.44393501 0.14256208 0.085800365, -0.44396085 0.14257096 0.024474308, -0.44393504 0.14256214 0.083881602, -0.48506668 0.15132402 -0.10689329, -0.48800084 0.15194806 -0.1016625, -0.4847419 0.1512548 -0.10614909, -0.4848792 0.15128407 -0.10630439, -0.44110373 0.1419694 -0.087458119, -0.44393501 0.1425703 -0.06064783, -0.48498163 0.1513059 -0.1064858, -0.44393501 0.14257 -0.055024996, -0.48504505 0.15131943 -0.10668491, -0.44393507 0.14256983 -0.052913532, -0.44393504 0.14256951 -0.047330126, -0.44393501 0.14256899 -0.037452593, -0.44393507 0.14256868 -0.031932101, -0.44393516 0.14256857 -0.029726252, -0.44395876 0.14257023 0.029524907, -0.4439351 0.14256826 -0.024229035, -0.44393501 0.14256817 -0.022002652, -0.44393507 0.1425678 -0.016523227, -0.44393501 0.14256768 -0.014282092, -0.44393513 0.14256735 -0.0088146478, -0.44393525 0.14256735 -0.006564334, -0.44393501 0.14256541 0.02424638, -0.44393501 0.14256696 -0.0011028796, -0.44393501 0.14256684 0.0011201352, -0.44393501 0.14256655 0.0065814406, -0.44393513 0.14256644 0.0088316351, -0.44393513 0.1425661 0.014299229, -0.44393513 0.14256592 0.016540393, -0.44393504 0.14256564 0.022019997, -0.44393501 0.14256513 0.029743358, -0.44393501 0.14256512 0.031949177, -0.44393513 0.14256473 0.037469789, -0.44393504 0.14256462 0.039649531, -0.44393513 0.14256431 0.045198902, -0.4439351 0.14256421 0.047347233, -0.44393507 0.14256392 0.052930668, -0.44393507 0.14256379 0.055042073, -0.47220895 0.14857769 0.083195314, -0.47220895 0.148587 -0.083177403, -0.47006667 0.14812255 0.07082136, -0.4700667 0.14812292 0.065198526, -0.47006661 0.14812309 0.061735168, -0.47006658 0.14812347 0.056151465, -0.47006667 0.14812416 0.043570653, -0.47006667 0.14812446 0.038049772, -0.47006661 0.14812467 0.034492478, -0.47006667 0.14812499 0.028995171, -0.47006673 0.14812514 0.025416896, -0.47006661 0.14812553 0.01993759, -0.47006661 0.14812568 0.016344413, -0.48478904 0.15126462 -0.10191073, -0.47006652 0.14812593 0.010877028, -0.47006652 0.14812614 0.0072748512, -0.47006652 0.14812638 0.0018134266, -0.48457611 0.15121958 -0.1060264, -0.48470807 0.15124735 -0.10198288, -0.47006661 0.14812669 -0.0017956048, -0.47006658 0.14812692 -0.0072570592, -0.47006661 0.1481277 -0.019919828, -0.47006676 0.14812811 -0.025399044, -0.47006661 0.14812827 -0.028977528, -0.47006664 0.14812852 -0.034474596, -0.44449851 0.14268874 -0.03654699, -0.44467881 0.14272697 -0.032902941, -0.44470814 0.14273341 -0.036474749, -0.47006664 0.1481287 -0.038032308, -0.44492826 0.14278021 -0.036452785, -0.47006667 0.14812905 -0.043552831, -0.48485252 0.15127811 -0.10182218, -0.4451476 0.14282681 -0.036481664, -0.47006661 0.14812922 -0.047084287, -0.47006646 0.14812951 -0.052633747, -0.47006664 0.14812972 -0.056133673, -0.47006673 0.14813003 -0.061717525, -0.47006655 0.14813018 -0.065180734, -0.47006661 0.14813057 -0.070803538, -0.46867561 0.14782639 0.07514964, -0.44450036 0.14268352 0.063641444, -0.44532618 0.1428591 0.067495003, -0.44528493 0.14285062 0.059740022, -0.46946004 0.14799365 0.069896355, -0.46871668 0.14783567 0.066123381, -0.46863702 0.14781775 0.084172413, -0.44446167 0.14267491 0.071312413, -0.44536462 0.14286681 0.075253591, -0.44447604 0.14268376 -0.032826647, -0.48489565 0.15128733 -0.10172166, -0.46950117 0.14800176 0.07900317, -0.46876028 0.14784558 0.057093635, -0.444585 0.14270248 0.048289165, -0.44524142 0.14284189 0.051988706, -0.44519565 0.14283265 0.044241443, -0.46937081 0.14797565 0.051694259, -0.46880594 0.14785573 0.048059508, -0.44454145 0.14269271 0.055967256, -0.46941659 0.14798488 0.060793355, -0.46927288 0.14795582 0.033510253, -0.46890393 0.14787747 0.029977217, -0.4688541 0.14786646 0.039020792, -0.44467881 0.14272322 0.032920077, -0.44514772 0.14282288 0.036499009, -0.48451403 0.15120608 -0.10208975, -0.46932277 0.14796594 0.042599723, -0.44431022 0.14264868 -0.036665365, -0.44463089 0.14271255 0.040606871, -0.4836624 0.15101345 0.10204671, -0.44442579 0.14266685 0.078980729, -0.4454008 0.14287403 0.083014742, -0.47276393 0.14869541 0.089828476, -0.48457605 0.15120776 0.10604452, -0.44450036 0.14269067 -0.063624337, -0.4686757 0.14783494 -0.075131968, -0.44532612 0.14286669 -0.067478016, -0.4849163 0.15129165 -0.10161386, -0.46946025 0.14800163 -0.069878563, -0.44528511 0.14285748 -0.059722856, -0.46871671 0.14784314 -0.066105798, -0.44446167 0.14268295 -0.071295485, -0.4686369 0.14782718 -0.08415468, -0.47276393 0.14870548 -0.089810595, -0.44536468 0.14287533 -0.075236157, -0.44429454 0.1426452 -0.032706514, -0.46950123 0.14801075 -0.078985497, -0.444585 0.14270799 -0.04827188, -0.46876022 0.14785184 -0.057075664, -0.44524148 0.14284776 -0.05197145, -0.46937069 0.14798138 -0.051676258, -0.44519556 0.14283755 -0.044224456, -0.46880594 0.14786111 -0.048041776, -0.4445416 0.14269905 -0.055950031, -0.46941665 0.14799176 -0.060775474, -0.46927291 0.14795962 -0.03349255, -0.44509774 0.14281586 -0.028744206, -0.46890381 0.1478809 -0.029959455, -0.48430154 0.15116099 -0.10214947, -0.44415262 0.14261515 -0.036824003, -0.46885404 0.14787067 -0.039003268, -0.46932277 0.14797078 -0.04258199, -0.48491347 0.15129116 -0.10150413, -0.48800665 0.1519493 -0.10159867, -0.44463089 0.1427172 -0.040589824, -0.48802146 0.15195242 -0.1015511, -0.44442573 0.14267562 -0.078963563, -0.48366234 0.15102485 -0.10202853, -0.44540086 0.14288338 -0.082997397, -0.44472876 0.14273719 -0.025211051, -0.44414327 0.14261301 -0.032548651, -0.48488721 0.15128554 -0.10139768, -0.48803505 0.15195528 -0.10152657, -0.44403386 0.14259002 -0.037014648, -0.48408124 0.15111408 -0.10215925, -0.4440296 0.14258885 -0.032360569, -0.4848389 0.15127531 -0.10129981, -0.48805213 0.15195893 -0.10150571, -0.44396004 0.1425743 -0.037228033, -0.46965227 0.14803527 0.056968644, -0.46981266 0.14806916 0.061063007, -0.46982545 0.14807215 0.056808993, -0.44395903 0.1425738 -0.032151803, -0.48477095 0.15126088 -0.10121472, -0.46944696 0.14799163 0.057081982, -0.46963096 0.14803059 0.060903177, -0.48386461 0.151068 -0.10211824, -0.47508875 0.14920032 -0.091532722, -0.46995074 0.14809856 0.061263278, -0.46995687 0.14810008 0.056611732, -0.46922114 0.14794359 0.057142362, -0.46898773 0.14789394 0.057146117, -0.47003719 0.14811699 0.061491981, -0.47003874 0.14811751 0.056388453, -0.47396636 0.14896122 -0.087420061, -0.47359279 0.14888191 -0.09030582, -0.47437027 0.14904737 -0.09088172, -0.47309849 0.14877656 -0.08632116, -0.44492838 0.14277603 0.036469981, -0.47250086 0.14864923 -0.085025862, -0.46984676 0.14808455 -0.083899096, -0.47228089 0.14860252 -0.084104374, -0.46971044 0.14805122 -0.0064854771, -0.46984586 0.14807983 -0.0024284273, -0.4698604 0.14808305 -0.006643042, -0.46968594 0.14804572 -0.0025874227, -0.46968776 0.1480507 -0.084058002, -0.46996674 0.14811008 -0.083707765, -0.46953043 0.14801289 -0.0063648969, -0.44470814 0.14272928 0.036492154, -0.46949765 0.14801036 -0.084176019, -0.46996626 0.14810534 -0.0022367984, -0.46997306 0.14810704 -0.0068302602, -0.47004119 0.14812584 -0.083493456, -0.44449851 0.14268468 0.036564186, -0.44447595 0.14268002 0.032843754, -0.46928638 0.14796533 -0.084247068, -0.46949509 0.14800508 -0.0027052313, -0.46932891 0.14796998 -0.0062878877, -0.47004116 0.14812136 -0.0020221919, -0.47004288 0.14812192 -0.007038638, -0.44431016 0.14264451 0.036682442, -0.44429454 0.14264145 0.03272371, -0.47006658 0.14813122 -0.083267644, -0.46906492 0.14791827 -0.084267452, -0.46911588 0.14792462 -0.0062575489, -0.46928307 0.1479601 -0.0027758032, -0.46884456 0.14787135 -0.0842361, -0.44415256 0.14261101 0.03684099, -0.44414309 0.14260928 0.032565758, -0.47006661 0.14813113 -0.079892114, -0.4440296 0.14258507 0.032377973, -0.44403389 0.14258581 0.037031963, -0.46906093 0.14791277 -0.0027952641, -0.47004133 0.14812571 -0.079667047, -0.44395897 0.14257009 0.03216885, -0.44396022 0.14257014 0.03724511, -0.44467095 0.14272498 -0.028757438, -0.44488356 0.14277029 -0.028726682, -0.44446993 0.14268234 -0.028834924, -0.44451433 0.14269152 -0.025142118, -0.46969038 0.14805102 -0.079103813, -0.4697026 0.14805335 -0.075003639, -0.46984842 0.14808461 -0.079262361, -0.44429019 0.14264411 -0.028955206, -0.44432119 0.14265046 -0.025025085, -0.46985584 0.14808594 -0.074845329, -0.46996745 0.14811005 -0.079453304, -0.44415921 0.14261594 -0.024866059, -0.44414076 0.14261223 -0.02911292, -0.46951923 0.14801438 -0.075123027, -0.46997088 0.14811036 -0.074656561, -0.44402841 0.14258842 -0.029300049, -0.44403681 0.14258991 -0.024673328, -0.46931443 0.14797078 -0.075198397, -0.47004232 0.14812554 -0.074446455, -0.46909836 0.1479248 -0.075225189, -0.44395879 0.1425736 -0.029507861, -0.44396091 0.14257376 -0.024457201, -0.4700667 0.14813077 -0.074225321, -0.46888182 0.14787878 -0.075202778, -0.46966153 0.14804438 -0.069993392, -0.46981391 0.14807655 -0.065851435, -0.46983102 0.14808044 -0.070153072, -0.46922159 0.14794816 -0.024408475, -0.44504634 0.14280455 -0.021012023, -0.46895534 0.14789139 -0.020910457, -0.46963289 0.14803791 -0.066011384, -0.4699513 0.14810574 -0.065651372, -0.46995941 0.14810774 -0.070348606, -0.44497177 0.14278501 0.044200912, -0.44474486 0.14273675 0.044213995, -0.46941951 0.14799254 -0.066121683, -0.47003728 0.14812407 -0.065423444, -0.4700394 0.14812474 -0.070569739, -0.44452694 0.14269035 0.044280306, -0.44443938 0.14267187 0.04052417, -0.46918637 0.14794299 -0.066175655, -0.469686 0.14804557 0.0026052147, -0.46971038 0.14805053 0.0065029711, -0.46984574 0.14807954 0.0024463683, -0.46981385 0.14806905 0.065869227, -0.46983108 0.14807245 0.070170596, -0.46995136 0.14809847 0.065669462, -0.46986037 0.14808229 0.0066606849, -0.46894726 0.14789213 -0.06617029, -0.46996626 0.14810513 0.0022546202, -0.46963295 0.14803053 0.066029087, -0.46966144 0.14803632 0.070010915, -0.46953043 0.14801224 0.0063828379, -0.46949509 0.14800486 0.0027231425, -0.46995935 0.14809977 0.070366338, -0.47003728 0.14811674 0.065441117, -0.469973 0.14810631 0.006848231, -0.4700411 0.14812103 0.0020398051, -0.46941966 0.14798522 0.066139325, -0.46918634 0.14793554 0.066193566, -0.46932891 0.14796934 0.0063055605, -0.46894735 0.14788479 0.066188112, -0.46928313 0.14795978 0.0027934462, -0.4700394 0.14811684 0.070587352, -0.47004285 0.14812116 0.0070562512, -0.44432986 0.14264843 0.044396296, -0.46911588 0.14792399 0.0062752813, -0.44426915 0.14263563 0.040402099, -0.46906096 0.14791255 0.0028131157, -0.4441644 0.14261326 0.04455559, -0.44412804 0.14260581 0.040245965, -0.44457677 0.14270455 -0.0210637, -0.44478002 0.14274757 -0.017514154, -0.44480833 0.14275376 -0.021008387, -0.44455448 0.14269961 -0.017453566, -0.44403934 0.14258657 0.044749752, -0.44402254 0.14258334 0.04006283, -0.4439573 0.14256938 0.039860919, -0.44396147 0.14257 0.044968143, -0.44436485 0.14265946 -0.021174625, -0.44439209 0.14266899 -0.086629376, -0.44423676 0.14263591 -0.086505398, -0.44410887 0.1426087 -0.086352304, -0.4440138 0.14258851 -0.086175874, -0.44395491 0.1425759 -0.085983589, -0.44393507 0.14257172 -0.085783318, -0.44434908 0.14265592 -0.017340198, -0.44418547 0.14262131 -0.021334365, -0.44417599 0.14261909 -0.017180577, -0.44404927 0.14259242 -0.021534011, -0.44396412 0.14257428 -0.021761313, -0.4440448 0.14259116 -0.016983375, -0.44393501 0.14257163 -0.083864287, -0.44396302 0.14257379 -0.016760036, -0.4439615 0.14257722 -0.083633855, -0.46981266 0.14807607 -0.061045274, -0.46982557 0.14807853 -0.056791201, -0.46995077 0.14810538 -0.061245486, -0.44499382 0.14279293 -0.013285384, -0.46963087 0.1480374 -0.060885385, -0.46965218 0.14804171 -0.056951091, -0.46995687 0.14810646 -0.056593969, -0.47003713 0.14812382 -0.061474279, -0.46944693 0.14799787 -0.05706431, -0.47003868 0.14812389 -0.05637075, -0.46922106 0.14794993 -0.05712451, -0.46898773 0.14790031 -0.057128385, -0.46966159 0.14803982 0.011687502, -0.46980801 0.14807072 0.015667155, -0.46983105 0.14807588 0.011527732, -0.46946004 0.14799695 0.011802033, -0.46962333 0.14803147 0.015507206, -0.44432858 0.14265527 -0.083062634, -0.44452503 0.14269705 -0.082946643, -0.44474229 0.14274327 -0.082879737, -0.44496873 0.14279148 -0.082865909, -0.44519225 0.14283903 -0.082905963, -0.44501382 0.14279357 0.051936224, -0.4447636 0.14274387 -0.013293728, -0.44483259 0.14275838 -0.0098112375, -0.44478059 0.14274392 0.051940039, -0.44416356 0.14262018 -0.083222225, -0.44425979 0.1426404 -0.078840807, -0.46994862 0.14810072 0.01586841, -0.46995944 0.14810321 0.01133205, -0.4445549 0.14269586 0.052000239, -0.44437078 0.14265692 0.048179254, -0.46923807 0.14794962 0.011865363, -0.46940592 0.14798519 0.015398487, -0.44434956 0.14265215 0.052113488, -0.44403905 0.14259365 -0.083415851, -0.44412264 0.14261122 -0.078685328, -0.47003654 0.1481193 0.016098842, -0.4441891 0.14261825 0.048019394, -0.4700394 0.14812018 0.011110887, -0.44417623 0.14261529 0.052273408, -0.44405094 0.14258887 0.047818914, -0.46916917 0.14793484 0.015347824, -0.44401997 0.14258936 -0.078504041, -0.46900764 0.14790057 0.011873469, -0.44404483 0.14258729 0.05247049, -0.44396454 0.14257053 0.047590271, -0.44454145 0.14269659 -0.01335679, -0.44459572 0.14270802 -0.0097603053, -0.4439629 0.1425699 0.052693918, -0.44395658 0.1425759 -0.078304961, -0.46970263 0.14804491 0.075021222, -0.46984836 0.14807568 0.079280272, -0.46985576 0.14807744 0.074863151, -0.46969029 0.1480421 0.079121426, -0.44434011 0.14265385 -0.013471588, -0.44437835 0.14266165 -0.0096518546, -0.46951914 0.14800584 0.075140908, -0.44393513 0.14257123 -0.078096792, -0.44419363 0.14262249 -0.0094919056, -0.4699674 0.14810093 0.079471126, -0.46997091 0.14810203 0.074674442, -0.44417068 0.14261772 -0.01363121, -0.46931425 0.14796223 0.075216159, -0.44405308 0.14259246 -0.0092905611, -0.46909836 0.14791635 0.075242832, -0.46888188 0.14787027 0.075220302, -0.44404218 0.14259046 -0.013826981, -0.44396508 0.14257376 -0.0090600997, -0.44396242 0.14257355 -0.014047936, -0.47004151 0.14811665 0.07968466, -0.44393501 0.14257114 -0.076123431, -0.47004229 0.14811718 0.074464425, -0.47006658 0.14812246 0.074243054, -0.44494072 0.14278121 -0.0055645853, -0.47006661 0.14812207 0.079909727, -0.46973246 0.14805847 -0.051881179, -0.46983731 0.14808053 -0.047727749, -0.46987352 0.1480885 -0.052037463, -0.46956235 0.14802215 -0.05175899, -0.46967179 0.14804539 -0.047887072, -0.46996245 0.14810711 -0.047533497, -0.46997908 0.14811091 -0.052220568, -0.46947488 0.14800344 -0.048003063, -0.47004005 0.14812352 -0.047315225, -0.47004446 0.14812489 -0.05242227, -0.46925691 0.14795706 -0.048069403, -0.46902993 0.14790876 -0.048082635, -0.4447186 0.1427339 -0.0055842251, -0.44488576 0.14276925 -0.0021026284, -0.44431391 0.14265175 -0.075333104, -0.44450411 0.14269218 -0.075215086, -0.44471541 0.14273721 -0.075144038, -0.44450662 0.14268883 -0.0056546479, -0.44467279 0.14272393 -0.0020721704, -0.44493684 0.14278425 -0.075123623, -0.44515708 0.14283112 -0.075154975, -0.47006652 0.14812179 0.083285466, -0.44431585 0.14264825 -0.0057726055, -0.44447124 0.14268109 -0.0019949824, -0.44415489 0.1426179 -0.07549192, -0.44428465 0.1426452 -0.071174517, -0.44429126 0.14264271 -0.0018746108, -0.44403481 0.14259228 -0.07568343, -0.44413725 0.14261386 -0.07101734, -0.44415602 0.14261426 -0.0059314519, -0.44396037 0.14257655 -0.07589744, -0.44402668 0.14259027 -0.070831135, -0.44414124 0.14261082 -0.0017168969, -0.47004125 0.14811642 0.083511516, -0.47228101 0.14859305 0.084122226, -0.44403544 0.14258857 -0.0061232895, -0.44395831 0.14257583 -0.070624784, -0.46981618 0.14807214 0.020605698, -0.46982571 0.14807393 0.024759665, -0.46995237 0.14810114 0.020406112, -0.46996662 0.14810057 0.083725587, -0.46965244 0.14803699 0.024599925, -0.44393501 0.14257084 -0.070408389, -0.46963689 0.14803401 0.020765468, -0.46984676 0.14807509 0.083917007, -0.47250089 0.14863968 0.085043743, -0.46995685 0.14810184 0.024956927, -0.47003755 0.14811933 0.020179167, -0.46968761 0.1480412 0.084075704, -0.44402865 0.14258686 -0.0015295893, -0.44396061 0.14257261 -0.006337896, -0.4694472 0.14799339 0.024486467, -0.4694975 0.14800078 0.084193841, -0.47309843 0.14876685 0.086338863, -0.46942496 0.1479889 0.020876542, -0.47003868 0.14811929 0.025180116, -0.46919328 0.14793962 0.020931855, -0.46922153 0.14794537 0.024426118, -0.46895525 0.14788903 0.020928398, -0.46928626 0.14795586 0.08426477, -0.44395885 0.14257206 -0.0013215691, -0.44393501 0.14257072 -0.068384483, -0.44505438 0.14280157 0.05967547, -0.44481537 0.14275078 0.059670106, -0.46970716 0.14805253 -0.042778328, -0.4698492 0.14808257 -0.038660809, -0.46985844 0.14808473 -0.042936251, -0.46969146 0.14804904 -0.038819566, -0.46952561 0.14801385 -0.042658284, -0.44458213 0.14270127 0.059724078, -0.44434014 0.14264998 0.055852666, -0.44436857 0.14265577 0.059834138, -0.4699679 0.14810783 -0.038469926, -0.4699721 0.14810885 -0.043124214, -0.46950307 0.14800891 -0.038937852, -0.47004154 0.14812347 -0.038256899, -0.47004268 0.14812399 -0.043333128, -0.4880521 0.1519475 0.10152365, -0.4848389 0.15126382 0.10131775, -0.48803511 0.15194382 0.10154463, -0.48477104 0.15124936 0.10123311, -0.46929339 0.14796421 -0.039010093, -0.48488721 0.15127404 0.10141601, -0.48802146 0.15194091 0.10156928, -0.48800668 0.15193786 0.10161678, -0.48491341 0.15127972 0.10152237, -0.47396633 0.14895131 0.087437883, -0.47508863 0.14918993 0.091550574, -0.46907339 0.1479174 -0.039032236, -0.48491627 0.15128031 0.10163213, -0.44417068 0.14261384 0.055693015, -0.44418791 0.14261736 0.059994325, -0.44448233 0.14268711 -0.067486748, -0.44468728 0.14273067 -0.067411497, -0.4743703 0.14903721 0.090899661, -0.44490328 0.1427767 -0.067384675, -0.44511989 0.14282285 -0.067407206, -0.44431141 0.14265043 -0.063506082, -0.48489571 0.15127584 0.10173969, -0.44494066 0.14278045 0.0055817217, -0.44429898 0.14264813 -0.067606285, -0.47359279 0.14887179 0.090323821, -0.44488573 0.14276907 0.0021195859, -0.44415316 0.14261679 -0.063347533, -0.44414589 0.14261544 -0.067764387, -0.44471851 0.14273322 0.005601421, -0.4848527 0.15126681 0.10184051, -0.44467279 0.14272377 0.0020894259, -0.44403422 0.14259157 -0.063156232, -0.44404224 0.14258654 0.055497274, -0.4440504 0.14258805 0.060194179, -0.4440307 0.14259103 -0.067953214, -0.44447127 0.14268084 0.0020121485, -0.44450656 0.14268811 0.0056719929, -0.44396019 0.14257577 -0.062942818, -0.48478901 0.15125319 0.10192861, -0.44395939 0.14257589 -0.068163469, -0.44431567 0.14264749 0.0057897121, -0.44429132 0.14264247 0.0018917471, -0.44393504 0.14257053 -0.062717751, -0.46906492 0.14790876 0.084285185, -0.4441559 0.14261357 0.0059485584, -0.46884462 0.14786185 0.084253773, -0.44414118 0.14261062 0.0017340332, -0.44396228 0.14256951 0.0552762, -0.44396436 0.14256975 0.060422376, -0.44403541 0.14258783 0.006140247, -0.44402862 0.14258668 0.0015466362, -0.44396058 0.1425719 0.0063549429, -0.44395885 0.1425719 0.0013385564, -0.46971139 0.14804928 0.029765978, -0.4698424 0.14807697 0.033855364, -0.46986097 0.14808118 0.029608592, -0.46953174 0.14801118 0.029886588, -0.46968034 0.14804247 0.033696249, -0.46996471 0.14810301 0.034047946, -0.46997324 0.14810507 0.029421255, -0.46933073 0.14796838 0.029964045, -0.46948719 0.14800137 0.033579096, -0.47004074 0.14811918 0.034264252, -0.47004288 0.1481199 0.029213473, -0.46911806 0.14792308 0.02999495, -0.48470801 0.15123595 0.102001, -0.48474187 0.15124288 0.10616718, -0.48487914 0.15127213 0.10632266, -0.44436857 0.14266239 -0.05981721, -0.44458202 0.14270784 -0.059706941, -0.44481525 0.14275752 -0.05965285, -0.44505438 0.14280835 -0.059658393, -0.48451409 0.15119466 0.10210805, -0.48430154 0.15114945 0.10216786, -0.48408124 0.15110257 0.10217737, -0.48386458 0.15105648 0.10213624, -0.44418785 0.14262405 -0.05997701, -0.44434008 0.14265619 -0.055835322, -0.48498175 0.15129399 0.10650407, -0.48504516 0.15130754 0.10670318, -0.46968034 0.14804627 -0.033678666, -0.46971139 0.14805268 -0.029748425, -0.46984252 0.14808086 -0.03383781, -0.48506659 0.15131199 0.10691141, -0.46986097 0.14808452 -0.0295908, -0.46996459 0.14810677 -0.034030333, -0.46953174 0.14801453 -0.029868707, -0.46948722 0.14800519 -0.033561483, -0.4699733 0.14810844 -0.029403552, -0.47004077 0.14812292 -0.03424646, -0.44511989 0.14281522 0.067424312, -0.44405028 0.14259474 -0.060177162, -0.44417056 0.14262007 -0.055675849, -0.44490328 0.14276911 0.067401633, -0.4693307 0.14797172 -0.029946312, -0.44483259 0.14275725 0.009828344, -0.44499382 0.14279132 0.013302639, -0.47004294 0.14812326 -0.029195771, -0.44468728 0.14272304 0.067428783, -0.46911791 0.14792643 -0.029976949, -0.4445959 0.14270695 0.0097776204, -0.44476357 0.1427424 0.013310984, -0.44431135 0.14264336 0.063523367, -0.44448242 0.14267947 0.067503914, -0.44415334 0.14260969 0.063364729, -0.44429895 0.14264052 0.067623481, -0.44396439 0.14257659 -0.06040515, -0.44404218 0.14259279 -0.055480018, -0.44437835 0.14266066 0.009668842, -0.44454154 0.14269517 0.013374284, -0.44403422 0.14258447 0.063173428, -0.44414583 0.14260797 0.067781702, -0.44396242 0.14257589 -0.055259123, -0.4441936 0.14262138 0.0095091015, -0.44434008 0.14265232 0.013488844, -0.44396022 0.14256869 0.062960044, -0.44403085 0.14258346 0.06797041, -0.44395933 0.14256817 0.068180516, -0.44405308 0.14259149 0.0093076974, -0.44417056 0.1426162 0.013648376, -0.48506662 0.1513118 0.11102094, -0.44396517 0.14257278 0.0090772957, -0.44404224 0.14258894 0.013844207, -0.44396225 0.14257184 0.014065132, -0.46969157 0.14804474 0.038837209, -0.46970722 0.1480477 0.04279615, -0.46984902 0.14807813 0.038678601, -0.46985853 0.14807993 0.042953864, -0.4699679 0.14810351 0.038487807, -0.46952567 0.14800914 0.042676017, -0.4695031 0.14800465 0.038955674, -0.46997213 0.14810413 0.043142095, -0.47004163 0.14811915 0.038274541, -0.4692935 0.14795998 0.039027706, -0.46907344 0.14791317 0.039049879, -0.4700425 0.14811905 0.043351069, -0.44455478 0.14270167 -0.051983252, -0.44478059 0.14274982 -0.051922813, -0.44501379 0.14279933 -0.051918849, -0.44434947 0.14265797 -0.052096382, -0.4443709 0.14266236 -0.048162058, -0.4441891 0.14262366 -0.048002049, -0.44417623 0.14262119 -0.052256122, -0.44405091 0.14259426 -0.047802016, -0.4440448 0.1425931 -0.052453384, -0.48503926 0.15130594 0.11125563, -0.48495862 0.15128879 0.11147724, -0.48482966 0.1512613 0.11167322, -0.48465899 0.15122502 0.11183296, -0.48445663 0.15118201 0.11194713, -0.44396454 0.14257579 -0.047573194, -0.48423356 0.15113451 0.11200963, -0.4840025 0.15108533 0.11201699, -0.44396293 0.14257579 -0.052676663, -0.48377615 0.15103725 0.1119685, -0.44478002 0.14274569 0.017531022, -0.44504637 0.14280215 0.021029159, -0.46965244 0.14803985 -0.024582133, -0.46981618 0.14807449 -0.020587936, -0.46982571 0.14807679 -0.024742022, -0.44480848 0.14275149 0.021025673, -0.44515705 0.14282265 0.075172022, -0.46944717 0.14799622 -0.024469003, -0.46963683 0.14803632 -0.020747855, -0.44457677 0.14270218 0.021080896, -0.46995237 0.14810358 -0.020388648, -0.46995687 0.14810461 -0.024939135, -0.44455445 0.14269762 0.017470792, -0.44493666 0.14277565 0.075140908, -0.46942502 0.14799127 -0.02085878, -0.44471544 0.14272866 0.075161293, -0.47003755 0.14812173 -0.020161405, -0.44436482 0.14265706 0.021191791, -0.47003871 0.14812207 -0.025162324, -0.44434914 0.14265405 0.017357394, -0.46919316 0.14794192 -0.020914093, -0.44450402 0.14268366 0.075232312, -0.44428465 0.14263725 0.071191445, -0.44431397 0.14264318 0.07535027, -0.44418553 0.14261898 0.02135174, -0.44417605 0.14261714 0.017197475, -0.44413742 0.14260592 0.071034327, -0.44415489 0.1426094 0.075509027, -0.44404927 0.14258997 0.021551028, -0.44404477 0.14258926 0.017000511, -0.44402668 0.14258234 0.070848122, -0.44403476 0.14258376 0.075700507, -0.44396034 0.14256801 0.075914547, -0.44395831 0.14256783 0.070641771, -0.44396287 0.14257184 0.016777202, -0.44396412 0.14257184 0.021778271, -0.44519225 0.1428296 0.08292298, -0.444527 0.14269526 -0.04426308, -0.44474491 0.14274167 -0.04419677, -0.44497189 0.14278995 -0.044183686, -0.44496879 0.14278208 0.082883045, -0.44432989 0.14265333 -0.04437907, -0.44443929 0.14267656 -0.040507063, -0.46967164 0.14803997 0.047904864, -0.46973243 0.14805272 0.05189918, -0.46983725 0.14807519 0.047745511, -0.44474229 0.14273384 0.082896814, -0.46987358 0.14808263 0.052055195, -0.4441644 0.14261822 -0.044538483, -0.44426918 0.14264032 -0.040384904, -0.46996245 0.14810188 0.047551289, -0.46956226 0.14801641 0.051776871, -0.44452497 0.14268769 0.082963631, -0.44425991 0.14263155 0.078858092, -0.44432858 0.14264585 0.083079919, -0.4694747 0.14799801 0.048020855, -0.4440392 0.14259158 -0.044732615, -0.44412813 0.14261019 -0.040228888, -0.44396147 0.14257509 -0.044950798, -0.4440226 0.14258781 -0.040045425, -0.46925682 0.1479516 0.048087135, -0.46902987 0.14790334 0.048100248, -0.44458434 0.12764382 0.044098005, -0.44451153 0.12767045 0.040577695, -0.44479963 0.12756599 0.04408066, -0.44437847 0.12771836 0.044166937, -0.44384742 0.12791647 -0.062880203, -0.44382182 0.12792601 -0.068214133, -0.44385037 0.1279157 -0.067969903, -0.44405684 0.12783816 -0.01718919, -0.44393024 0.12788412 -0.021468684, -0.44405967 0.1278372 -0.021270052, -0.44392893 0.12788452 -0.016991243, -0.44384938 0.12791339 -0.021694705, -0.44432244 0.12773876 0.040497795, -0.443849 0.12791328 -0.016766444, -0.44419268 0.12778543 0.04428412, -0.48480076 0.11309341 0.11071227, -0.48495957 0.11303601 0.11055262, -0.44382182 0.12792304 -0.016528144, -0.44382182 0.12792332 -0.021934703, -0.48507959 0.11299266 0.11035882, -0.48376939 0.11347912 -0.11076249, -0.48800069 0.11194889 -0.11631186, -0.48396978 0.11340646 -0.11085449, -0.48418471 0.11332867 -0.11089464, -0.48440275 0.11324988 -0.11088119, -0.48461184 0.11317423 -0.11081444, -0.48480079 0.11310595 -0.11069845, -0.48461184 0.11316188 0.1108285, -0.44415382 0.12779975 0.040376619, -0.48495951 0.11304848 -0.11053921, -0.48507947 0.11300507 -0.11034535, -0.44403705 0.12784176 0.044443265, -0.4851543 0.11297815 -0.11012696, -0.48517951 0.11296885 -0.10989641, -0.4880006 0.11194785 -0.099555627, -0.48515421 0.11296572 0.11014079, -0.4440138 0.12785052 0.04021959, -0.48440287 0.11323752 0.11089517, -0.46980861 0.11852516 -0.047595844, -0.46984753 0.11851135 -0.051503405, -0.46996424 0.11846879 -0.047436699, -0.44391957 0.12788424 0.044635817, -0.48517951 0.11295655 0.10991023, -0.46998754 0.11846069 -0.051660404, -0.47008166 0.11842629 -0.047244236, -0.48418477 0.11331628 0.11090846, -0.44384649 0.12791052 0.044851914, -0.4439089 0.12788849 0.040034339, -0.46967897 0.11857222 -0.051382169, -0.44384396 0.127912 0.03982918, -0.46962285 0.11859226 -0.047713086, -0.48396978 0.11339408 0.11086805, -0.44382176 0.12791952 0.045079991, -0.4837693 0.11346653 0.11077641, -0.47009251 0.11842278 -0.051845774, -0.47015479 0.1183999 -0.047028109, -0.46898848 0.11882186 -0.047763839, -0.4694899 0.11864069 -0.05130218, -0.46920177 0.11874472 -0.047799185, -0.44382182 0.12791991 0.039613888, -0.46941695 0.11866678 -0.047782049, -0.46992907 0.11847813 0.01555787, -0.46995488 0.11846907 0.011489615, -0.47006521 0.11842875 0.015759781, -0.47015753 0.11839919 -0.052050933, -0.47017953 0.11839089 -0.046800181, -0.46979287 0.11852758 0.011649206, -0.4697502 0.11854275 0.0153981, -0.47007725 0.11842455 0.01129438, -0.47015059 0.11839792 0.015991077, -0.44435754 0.1277324 -0.071230993, -0.44496825 0.12751165 -0.074959144, -0.44516703 0.12743978 -0.075032011, -0.47017956 0.11839125 -0.052266076, -0.46960029 0.11859706 0.011764154, -0.48517939 0.11295669 0.10578559, -0.48515746 0.11296475 0.10557009, -0.48509219 0.11298832 0.10536493, -0.46953985 0.11861883 0.015290096, -0.48498687 0.11302648 0.10517927, -0.44475934 0.1275873 -0.074934855, -0.47015357 0.11839706 0.011074141, -0.47017953 0.11838736 0.016237512, -0.46938798 0.11867391 0.011828288, -0.46931085 0.11870159 0.015240386, -0.44455054 0.1276627 -0.074960366, -0.47017953 0.11838773 0.010840878, -0.44417831 0.12779723 -0.071112052, -0.44435236 0.1277345 -0.075034961, -0.46916738 0.11875378 0.011838034, -0.44417468 0.12779886 -0.075154051, -0.44402841 0.12785141 -0.070953742, -0.44402632 0.12785248 -0.075312242, -0.44391552 0.12789214 -0.070763573, -0.44391456 0.12789288 -0.075501755, -0.4438456 0.1279175 -0.070551619, -0.48484638 0.11307721 0.10502209, -0.48496726 0.11303371 0.10076727, -0.44459876 0.12764268 -0.025205389, -0.44469205 0.1276089 -0.028645024, -0.4449259 0.12752448 -0.028657511, -0.4846774 0.11313844 0.10490091, -0.48481369 0.1130894 0.10092618, -0.4438453 0.12791796 -0.075712666, -0.44382188 0.12792614 -0.07032837, -0.44382188 0.12792642 -0.075934753, -0.44438955 0.12771825 -0.025138721, -0.44446301 0.12769182 -0.028694257, -0.48508307 0.11299188 0.10057555, -0.48463008 0.11315571 0.10104395, -0.48515508 0.11296582 0.10036094, -0.48442635 0.11322936 0.10111441, -0.44420063 0.12778659 -0.025022641, -0.4442521 0.12776814 -0.028802142, -0.48517951 0.11295697 0.10013436, -0.48421267 0.11330663 0.10113417, -0.44407287 0.12783292 -0.028961971, -0.44404176 0.12784395 -0.024863198, -0.48400083 0.11338343 0.10110186, -0.48380092 0.11345567 0.10101928, -0.44476083 0.12758029 0.03636761, -0.44455454 0.12765533 0.032901362, -0.44496992 0.12750468 0.036392376, -0.44393638 0.12788229 -0.029163823, -0.44455186 0.12765586 0.036392853, -0.48800382 0.11193559 0.099488035, -0.48517951 0.11295709 0.099360004, -0.48801333 0.11193225 0.09941639, -0.44392183 0.12788737 -0.024669304, -0.48805097 0.11191848 0.099302307, -0.48513982 0.11297147 0.098951802, -0.48807937 0.1119083 0.099260315, -0.48802915 0.11192653 0.099354371, -0.44432393 0.12774493 -0.078890637, -0.44500065 0.12750037 -0.082690075, -0.44520047 0.12742813 -0.082772449, -0.4438509 0.12791322 -0.029395327, -0.48502269 0.11301391 0.098560765, -0.4881137 0.11189584 0.099228755, -0.44435516 0.12772731 0.032827601, -0.44435343 0.12772773 0.03646706, -0.44478869 0.12757702 -0.08265765, -0.44384721 0.12791446 -0.024451032, -0.48483285 0.11308251 0.098203227, -0.48204616 0.11409076 0.094024494, -0.48184034 0.11416529 0.09376578, -0.44417658 0.12779193 0.032708511, -0.44417545 0.12779222 0.036586359, -0.44457498 0.12765433 -0.0826772, -0.44382182 0.12792379 -0.029642209, -0.44382182 0.12792349 -0.02422069, -0.44437125 0.12772807 -0.082747653, -0.44402751 0.12784596 0.03255029, -0.44402662 0.12784594 0.036744639, -0.44415501 0.1278061 -0.078769401, -0.44418767 0.1277944 -0.082865581, -0.44391522 0.12788656 0.032360628, -0.4439148 0.12788635 0.036934182, -0.4767572 0.11600412 0.087234244, -0.47686097 0.11596657 0.087123349, -0.48132131 0.1143529 0.093376234, -0.4440144 0.12785687 -0.078612283, -0.44403401 0.12784998 -0.083024368, -0.4766328 0.11604913 0.08731769, -0.44384542 0.12791169 0.032148942, -0.44384542 0.12791152 0.037145421, -0.47693917 0.11593829 0.086990938, -0.47649404 0.11609936 0.087369666, -0.44382182 0.12792033 0.031926021, -0.44391826 0.12789194 -0.083216146, -0.44382182 0.12792 0.037367538, -0.44390926 0.12789492 -0.078426674, -0.47698769 0.11592096 0.086843118, -0.44384632 0.12791803 -0.083430842, -0.46983656 0.118512 0.0064605623, -0.46996769 0.11846481 0.0024738759, -0.46998104 0.11845975 0.0066183656, -0.47634795 0.11615221 0.087387666, -0.44384387 0.12791863 -0.078221425, -0.46981418 0.11852026 0.0026325136, -0.46966314 0.11857471 0.0063402802, -0.47700411 0.115915 0.086687639, -0.47008321 0.11842297 0.0022822767, -0.47699019 0.11591996 0.086544767, -0.48159644 0.11425355 0.093547627, -0.47008952 0.11842053 0.0068059117, -0.46979135 0.11853197 -0.056597039, -0.46986917 0.11850408 -0.060540035, -0.46995375 0.11847308 -0.056437656, -0.46963114 0.11858657 0.0027504712, -0.46946922 0.11864486 0.0062633008, -0.47000045 0.11845657 -0.060695484, -0.47620162 0.11620517 0.087370619, -0.47007695 0.11842872 -0.056242123, -0.47015509 0.11839704 0.0020675808, -0.47694921 0.11593491 0.086407885, -0.47015679 0.11839622 0.0070141703, -0.46971044 0.11856142 -0.060417011, -0.46959808 0.11860177 -0.056712046, -0.46942744 0.11866017 0.0028211325, -0.47606251 0.11625537 0.087319598, -0.469264 0.11871907 0.0062333196, -0.47009841 0.11842109 -0.060876265, -0.4701536 0.11840095 -0.056021348, -0.47017953 0.11838821 0.0018413514, -0.47688279 0.11595884 0.086282715, -0.47017953 0.11838803 0.0072329193, -0.46953112 0.1186263 -0.060332015, -0.4689472 0.11883734 -0.056738272, -0.46916416 0.11875883 -0.056784466, -0.46938527 0.1186789 -0.056775704, -0.44116554 0.12888786 -0.087548897, -0.44382182 0.1279265 -0.078005865, -0.44382188 0.12792562 -0.060495451, -0.44382182 0.12792566 -0.062648967, -0.46921417 0.11873737 0.0028411299, -0.44382182 0.12792692 -0.085681751, -0.44384244 0.12791964 -0.085889742, -0.47015902 0.11839923 -0.061074808, -0.44390324 0.12789759 -0.086088732, -0.47017953 0.11839147 -0.055787697, -0.44400164 0.12786204 -0.086269692, -0.44413307 0.12781437 -0.086425141, -0.44382182 0.12792683 -0.083657309, -0.47017953 0.11839178 -0.06128259, -0.473349 0.11723755 0.077090457, -0.47282425 0.11742719 0.08019723, -0.47259989 0.11750838 0.079918876, -0.44116491 0.12888806 -0.087583765, -0.47233149 0.11760537 0.079688832, -0.4442924 0.12775679 -0.086548224, -0.47202834 0.11771514 0.079514667, -0.47234079 0.11761068 -0.073747113, -0.47234073 0.11760244 0.073761329, -0.47279778 0.11743709 0.076057717, -0.47017959 0.11839081 -0.043251678, -0.47017941 0.11839043 -0.037810341, -0.47017956 0.11839023 -0.034239754, -0.47017941 0.11838993 -0.028818086, -0.47017959 0.1183898 -0.025230274, -0.47017953 0.11838938 -0.019823566, -0.47017959 0.11838928 -0.016223088, -0.44455448 0.12765916 -0.032886043, -0.44476095 0.12758452 -0.036352083, -0.44497004 0.12750897 -0.036376879, -0.47017953 0.11838886 -0.010826632, -0.47017953 0.11838874 -0.0072185248, -0.47017953 0.11838844 -0.0018268973, -0.47017947 0.11838725 0.019837901, -0.47017959 0.11838695 0.025244609, -0.44435528 0.12773107 -0.032812133, -0.44455186 0.12766008 -0.036377475, -0.47017953 0.11838667 0.02883248, -0.47017959 0.11838646 0.034254178, -0.47017953 0.11838618 0.037824675, -0.46975747 0.11853679 0.07460545, -0.47245491 0.11756094 0.074926451, -0.44469211 0.12760568 0.028660551, -0.44459876 0.12763982 0.025220856, -0.4449257 0.12752116 0.028673038, -0.47017953 0.118386 0.043265983, -0.44446287 0.12768851 0.028709814, -0.47017953 0.1183857 0.046814546, -0.47017959 0.11838552 0.05228053, -0.46993348 0.11847314 0.074445412, -0.47017953 0.11838517 0.055802092, -0.44116554 0.12887795 0.087564334, -0.44382182 0.12791875 0.060510889, -0.44382182 0.127919 0.054982945, -0.44382182 0.12791927 0.052794412, -0.4438217 0.12791942 0.04729943, -0.4441767 0.12779565 -0.032693133, -0.44435337 0.12773195 -0.036451712, -0.47006735 0.11842485 0.074244842, -0.44382188 0.12792052 0.029657587, -0.44382182 0.12792075 0.024236009, -0.44382182 0.12792093 0.021950111, -0.46955013 0.11861183 0.074714735, -0.44382188 0.12792125 0.016543463, -0.44382182 0.1279213 0.014245108, -0.44382188 0.12792167 0.008848533, -0.47015104 0.11839452 0.074015334, -0.44382182 0.12792176 0.0065425783, -0.44402763 0.12784971 -0.032534823, -0.44417527 0.12779631 -0.036570832, -0.44382182 0.12792213 0.0011511296, -0.44382188 0.12792227 -0.001135543, -0.44425204 0.12776484 0.028817669, -0.44438949 0.12771541 0.02515386, -0.44382182 0.12792255 -0.0065270513, -0.44382182 0.12792262 -0.0088330656, -0.44382188 0.12792297 -0.01422967, -0.46932405 0.11869362 0.074767068, -0.44382188 0.12792398 -0.031910732, -0.44382182 0.1279242 -0.037352249, -0.44391516 0.12789023 -0.032344922, -0.44402662 0.12785004 -0.036729142, -0.44382182 0.12792431 -0.03959842, -0.44382182 0.12792462 -0.045064494, -0.44382182 0.1279248 -0.047283962, -0.44382188 0.12792513 -0.052778825, -0.47017953 0.11838423 0.073771015, -0.44382182 0.12792522 -0.054967508, -0.46957067 0.11860479 0.069379762, -0.44509372 0.12745874 0.059575126, -0.46890759 0.11884472 0.065723434, -0.44407287 0.12782961 0.028977588, -0.44420055 0.12778378 0.025038108, -0.44439313 0.12771195 0.063584104, -0.4688701 0.11885777 0.074690923, -0.44513154 0.12744476 0.067309842, -0.44435742 0.12772432 0.071246251, -0.44516686 0.12743132 0.075047687, -0.4694899 0.11863483 0.051316515, -0.4450129 0.12748884 0.044116125, -0.46898839 0.11881645 0.047778383, -0.46909264 0.11877735 0.074758962, -0.44447023 0.127685 0.048250213, -0.46894714 0.11883095 0.056752726, -0.44505426 0.12747358 0.051843837, -0.46953118 0.11861947 0.060346261, -0.44443065 0.12769882 0.055918857, -0.44432378 0.12773602 0.078906193, -0.4452005 0.12741877 0.082787737, -0.46907553 0.11878589 0.029817268, -0.46944699 0.11865088 0.042290851, -0.46903136 0.11880152 0.038799927, -0.4439148 0.12789062 -0.036918655, -0.46940276 0.11866745 0.03326948, -0.44509378 0.12746541 -0.059559599, -0.46957073 0.11861242 -0.069365337, -0.46890774 0.11885215 -0.06570898, -0.44393638 0.12787902 0.02917935, -0.44404176 0.1278412 0.024878666, -0.46887019 0.11886628 -0.07467626, -0.44439307 0.12771903 -0.063568696, -0.44513133 0.1274523 -0.067294434, -0.47606257 0.11626531 -0.087305412, -0.44384542 0.1279154 -0.032133475, -0.47202829 0.11772405 -0.079500154, -0.44501284 0.1274938 -0.044100687, -0.47017956 0.11838433 0.070315585, -0.4444702 0.12769033 -0.048234567, -0.44505426 0.12747934 -0.05182825, -0.44443074 0.12770505 -0.05590333, -0.4838008 0.11346708 -0.10100533, -0.47015199 0.11839417 0.070075855, -0.48132136 0.1143634 -0.093362376, -0.46907553 0.11878923 -0.029802784, -0.46944693 0.11865561 -0.042276427, -0.4690313 0.11880575 -0.038785413, -0.44451144 0.12767495 -0.040562227, -0.46940276 0.11867121 -0.033254996, -0.4438453 0.12791584 -0.037129775, -0.4846774 0.11315025 -0.1048872, -0.44392183 0.12788463 0.024684563, -0.44385079 0.12790997 0.029410943, -0.44384721 0.1279116 0.024466559, -0.46994218 0.11847028 0.06965135, -0.46994349 0.11847006 0.065450206, -0.47007141 0.11842357 0.069850042, -0.46977201 0.11853184 0.069491521, -0.46977422 0.11853132 0.065609917, -0.470072 0.11842355 0.065251902, -0.46957389 0.1186038 0.065722004, -0.47015223 0.11839458 0.065026805, -0.46935406 0.11868313 0.065779999, -0.47017953 0.11838475 0.064787701, -0.46935728 0.11868443 0.024252549, -0.44488028 0.12753808 0.0209582, -0.46912095 0.11876991 0.020829961, -0.46912757 0.11876495 0.065780744, -0.47017953 0.11838499 0.061296776, -0.46981421 0.11852051 -0.0026181787, -0.46983662 0.11851276 -0.0064462274, -0.46996775 0.1184651 -0.0024591833, -0.46998104 0.11846052 -0.0066040307, -0.47008339 0.11842336 -0.0022676438, -0.46966323 0.11857544 -0.0063259453, -0.46977422 0.11853865 -0.065595582, -0.46994218 0.1184781 -0.069637075, -0.46994355 0.11847737 -0.065435722, -0.46963105 0.11858687 -0.0027361065, -0.47008952 0.1184213 -0.0067914277, -0.47015509 0.11839728 -0.0020532459, -0.46957389 0.1186112 -0.065707758, -0.46977195 0.11853966 -0.069477066, -0.47007146 0.1184314 -0.069835678, -0.470072 0.1184309 -0.065237388, -0.46946916 0.11864558 -0.0062489659, -0.46942744 0.11866046 -0.0028066188, -0.46912763 0.11877254 -0.065766171, -0.469354 0.1186906 -0.065765813, -0.47015676 0.11839697 -0.0069997162, -0.47015217 0.11840227 -0.07006143, -0.47015229 0.11840181 -0.065012172, -0.46926412 0.11871977 -0.0062187761, -0.44116506 0.12887822 0.087599143, -0.46921411 0.11873762 -0.002826646, -0.44429234 0.1277471 0.086563572, -0.44413319 0.12780479 0.086440668, -0.44384247 0.12790993 0.085905209, -0.44382188 0.12791739 0.085697308, -0.44390324 0.12788792 0.08610402, -0.44400167 0.12785237 0.086285308, -0.44465294 0.12762032 0.020956948, -0.44464418 0.12762377 0.017535523, -0.44443199 0.12770025 0.021013871, -0.44442502 0.12770304 0.017476901, -0.44423035 0.12777321 0.02112563, -0.46986917 0.11849718 0.06055437, -0.46995386 0.11846676 0.05645211, -0.47000048 0.11844973 0.060709611, -0.44479957 0.12757097 -0.044065282, -0.44422534 0.12777521 0.017364368, -0.46971038 0.11855458 0.060431525, -0.46979135 0.11852565 0.056611583, -0.44405964 0.12783493 0.021285549, -0.4445844 0.12764882 -0.044082537, -0.47007689 0.11842225 0.056256458, -0.44405678 0.12783615 0.017204627, -0.47009835 0.11841424 0.06089063, -0.44393006 0.12788177 0.021484211, -0.47017953 0.1183919 -0.064773276, -0.47017956 0.11839224 -0.07030116, -0.46959808 0.11859544 0.056726381, -0.47015342 0.11839458 0.056035802, -0.47015902 0.11839233 0.061089233, -0.4439289 0.12788251 0.017006829, -0.44384924 0.12791091 0.021710321, -0.46938515 0.11867249 0.056790009, -0.44432238 0.12774335 -0.040482327, -0.44437858 0.12772331 -0.04415141, -0.44384906 0.12791145 0.016781911, -0.44419286 0.1277905 -0.044268593, -0.44415393 0.12780434 -0.040360972, -0.46916404 0.11875249 0.056799009, -0.44403708 0.12784676 -0.044427708, -0.44382182 0.12791742 0.083672658, -0.4440138 0.12785491 -0.040203974, -0.44384632 0.12790862 0.08344619, -0.44391975 0.12788931 -0.044620231, -0.4439089 0.12789288 -0.040018633, -0.44384667 0.12791565 -0.044836357, -0.4438439 0.12791641 -0.039813653, -0.44483399 0.12755536 0.013248071, -0.47017941 0.11839239 -0.07375668, -0.44500074 0.1274911 0.082705423, -0.44478852 0.12756784 0.082672998, -0.47015104 0.11840269 -0.07400091, -0.47245488 0.11756946 -0.074912295, -0.44457504 0.12764511 0.082692727, -0.44437113 0.12771878 0.08276324, -0.44418779 0.12778512 0.082881227, -0.46979287 0.11852887 -0.011634693, -0.46992907 0.1184798 -0.015543595, -0.46995476 0.11847016 -0.01147531, -0.47006741 0.11843315 -0.074230418, -0.46975034 0.11854449 -0.015383735, -0.44403401 0.12784062 0.083039805, -0.44415501 0.1277972 0.078784868, -0.46960029 0.11859849 -0.011749849, -0.47006527 0.11843053 -0.015745386, -0.47007728 0.11842594 -0.011279896, -0.46993336 0.11848149 -0.074431136, -0.46975747 0.1185452 -0.074591026, -0.47279772 0.11744566 -0.076043621, -0.46953985 0.11862056 -0.015275702, -0.4440144 0.127848 0.078627869, -0.46938786 0.11867528 -0.011814073, -0.44391826 0.12788251 0.083231762, -0.47015062 0.11839981 -0.015976772, -0.47015354 0.11839834 -0.011059538, -0.46931085 0.11870332 -0.015226111, -0.44390908 0.12788615 0.07844238, -0.46916735 0.11875507 -0.01182352, -0.46955013 0.11862028 -0.07470049, -0.44384405 0.12790987 0.078236863, -0.44461343 0.12763512 0.013257727, -0.44469038 0.12760735 0.0098456293, -0.44382188 0.1279178 0.078021333, -0.44440094 0.12771189 0.013321891, -0.44446149 0.12769029 0.0097958893, -0.4442513 0.12776633 0.0096879154, -0.44382182 0.12791789 0.075950429, -0.44420853 0.12778156 0.013436899, -0.44407234 0.12783106 0.009528026, -0.44404659 0.12784012 0.01359649, -0.44393614 0.12788031 0.0093262047, -0.4439241 0.12788437 0.013791665, -0.44385096 0.12791124 0.0090949684, -0.44384772 0.127912 0.014012054, -0.46984753 0.11850557 0.051517949, -0.46996412 0.1184635 0.047451153, -0.46998754 0.11845496 0.051674828, -0.46980855 0.11851981 0.047610298, -0.47260001 0.11751738 -0.079904512, -0.47282419 0.11743627 -0.080182716, -0.47334912 0.11724621 -0.077076331, -0.46967897 0.1185665 0.051396623, -0.47233149 0.11761443 -0.079674408, -0.47008166 0.11842099 0.047258601, -0.47009256 0.11841698 0.051860318, -0.46909258 0.11878578 -0.074744299, -0.4693239 0.11870213 -0.074752644, -0.46962282 0.11858699 0.047727391, -0.47015467 0.11839458 0.047042623, -0.47015747 0.11839338 0.052065358, -0.46941695 0.11866137 0.047796473, -0.44483724 0.12755771 -0.051782116, -0.44478717 0.12757263 0.00554277, -0.44461623 0.12763773 -0.051791057, -0.46920177 0.11873935 0.047813788, -0.47688279 0.11596854 -0.086268529, -0.44496825 0.12750316 0.074974611, -0.44475928 0.12757872 0.074950412, -0.44455054 0.12765433 0.074976042, -0.4443523 0.12772599 0.07505025, -0.44417468 0.12779027 0.075169638, -0.44417831 0.12778921 0.071127549, -0.46994165 0.11847557 -0.020488217, -0.46994457 0.11847465 -0.024569049, -0.47007117 0.11842869 -0.020289555, -0.44429094 0.12775521 -0.048149392, -0.44440308 0.1277148 -0.051854625, -0.44402632 0.12784399 0.075327799, -0.44402832 0.12784342 0.07096909, -0.46977103 0.11853716 -0.020648167, -0.46977589 0.11853567 -0.0244091, -0.47007269 0.1184285 -0.024766907, -0.47015199 0.11839937 -0.020063534, -0.4439145 0.12788424 0.075517222, -0.44391552 0.12788421 0.07077904, -0.44421005 0.12778471 -0.051969424, -0.44473723 0.12759089 0.0021507293, -0.4441323 0.12781264 -0.048026487, -0.44457385 0.12764974 0.0055628568, -0.44384554 0.12790954 0.070567206, -0.46956933 0.11861011 -0.020759657, -0.46957633 0.11860789 -0.024296626, -0.44384539 0.12790939 0.075728014, -0.47015241 0.11839965 -0.024991706, -0.46912101 0.11877234 -0.020815447, -0.46935728 0.11868718 -0.024238214, -0.4693484 0.11869013 -0.020816639, -0.44404739 0.12784345 -0.052129015, -0.44382167 0.12791811 0.070343718, -0.44437024 0.12772337 0.0056336075, -0.44453222 0.12766506 0.002120778, -0.44400093 0.12786001 -0.047871098, -0.48811355 0.11190696 -0.099215105, -0.44418707 0.12778971 0.0057513863, -0.44433826 0.12773529 0.0020436794, -0.47694919 0.11594446 -0.086393699, -0.44403365 0.12784515 0.0059102327, -0.44416484 0.12779795 0.0019233674, -0.44391814 0.12788698 0.0061017424, -0.44402051 0.12785025 0.0017656535, -0.44391194 0.1278895 0.0015781373, -0.44384623 0.12791295 0.0063163191, -0.44382182 0.1279183 0.068229303, -0.44392452 0.12788801 -0.052324489, -0.44384471 0.12791379 0.0013698786, -0.44390306 0.1278955 -0.047690347, -0.46982476 0.11851425 0.042483583, -0.46982601 0.11851403 0.038605973, -0.46997389 0.11846039 0.042642042, -0.46997467 0.11846021 0.038447514, -0.47008619 0.11841974 0.042831793, -0.44384781 0.12791568 -0.052545324, -0.46964613 0.1185789 0.042364731, -0.46964797 0.11857836 0.038725212, -0.44384232 0.12791735 -0.047491655, -0.47008643 0.11841975 0.03825824, -0.47015592 0.11839446 0.04304339, -0.46944949 0.1186502 0.03879939, -0.47015598 0.1183947 0.038047001, -0.46924052 0.11872587 0.038824722, -0.4449088 0.12752511 0.067241892, -0.4446775 0.12760884 0.067233667, -0.44445133 0.12769069 0.06728588, -0.44424394 0.12776572 0.067395106, -0.44420299 0.12778069 0.063468412, -0.44406787 0.12782933 0.067555144, -0.48184034 0.11417575 -0.093751833, -0.44404319 0.12783852 0.063308969, -0.4820461 0.11410128 -0.094010726, -0.44393411 0.1278778 0.067756012, -0.44478706 0.12757324 -0.0055274814, -0.44392249 0.12788218 0.063114688, -0.44473729 0.12759112 -0.0021352619, -0.44385043 0.12790808 0.067985371, -0.48159638 0.11426403 -0.093533531, -0.47699019 0.11592962 -0.086530551, -0.44457379 0.12765045 -0.0055473894, -0.44384742 0.12790932 0.06289573, -0.44453219 0.12766528 -0.0021051615, -0.4770042 0.11592469 -0.086673453, -0.47620162 0.11621502 -0.087356403, -0.44437024 0.12772405 -0.0056181103, -0.47634789 0.11616203 -0.087373629, -0.4764941 0.11610924 -0.087355569, -0.44382182 0.1279186 0.062664345, -0.47663292 0.11605909 -0.087303475, -0.47675732 0.11601408 -0.087220028, -0.47686097 0.11597642 -0.087109312, -0.44433823 0.12773542 -0.0020281225, -0.47693929 0.11594823 -0.086976632, -0.47698769 0.11593057 -0.086828902, -0.44418716 0.12779029 -0.0057358593, -0.44416478 0.12779824 -0.0019079298, -0.48483297 0.11309363 -0.098189279, -0.44403365 0.12784582 -0.0058946759, -0.48502269 0.11302505 -0.098546788, -0.48807937 0.11191943 -0.099246785, -0.44402048 0.12785044 -0.0017501265, -0.46992841 0.11848088 -0.029498324, -0.46995959 0.11846979 -0.033597097, -0.47006491 0.11843137 -0.029296413, -0.46974918 0.11854561 -0.029658154, -0.4698008 0.1185272 -0.033437863, -0.48513982 0.11298262 -0.098937944, -0.488051 0.11192963 -0.099288598, -0.48802903 0.11193755 -0.099340484, -0.48801321 0.11194329 -0.099402562, -0.47007957 0.11842641 -0.03379105, -0.47015056 0.11840048 -0.029064879, -0.46961191 0.11859556 -0.033321753, -0.46953842 0.11862186 -0.029765949, -0.44391802 0.12788764 -0.0060863644, -0.44391182 0.12788965 -0.0015626401, -0.47015414 0.11839943 -0.034009144, -0.46930921 0.11870471 -0.029815271, -0.48517939 0.11296818 -0.099346414, -0.48800379 0.11194673 -0.099474385, -0.4438462 0.12791362 -0.0063007921, -0.4698008 0.11852334 0.033452228, -0.46992844 0.11847749 0.029512748, -0.46995959 0.11846599 0.03361164, -0.48517948 0.11296824 -0.10012047, -0.44384477 0.12791404 -0.0013543516, -0.46974924 0.11854239 0.029672638, -0.46961185 0.11859182 0.033336148, -0.48515505 0.11297704 -0.100347, -0.48508298 0.11300327 -0.10056157, -0.470065 0.1184281 0.029310808, -0.4700796 0.1184226 0.033805534, -0.46953845 0.11861852 0.029780492, -0.47015056 0.11839725 0.029079363, -0.4701542 0.11839564 0.034023687, -0.48496735 0.1130452 -0.10075326, -0.46930918 0.11870135 0.029829666, -0.44487372 0.12753831 0.059517995, -0.44464722 0.12762026 0.059518471, -0.44442761 0.12769975 0.059576347, -0.44422713 0.12777221 0.059688523, -0.44422948 0.12777157 0.055807069, -0.44405779 0.1278335 0.059848472, -0.44405916 0.12783316 0.055646971, -0.4439294 0.12787998 0.060046688, -0.44392994 0.12787995 0.055448487, -0.4438493 0.12790912 0.055222735, -0.44384912 0.1279089 0.060271874, -0.44487372 0.12754506 -0.059502617, -0.44464722 0.1276269 -0.059502885, -0.44483399 0.12755679 -0.013232574, -0.44422939 0.1277779 -0.055791542, -0.44442752 0.1277065 -0.059560969, -0.44469038 0.12760852 -0.0098302811, -0.44422713 0.1277788 -0.059673294, -0.44405919 0.12783942 -0.055631652, -0.44446152 0.12769134 -0.0097804815, -0.44461337 0.12763651 -0.01324223, -0.44425127 0.12776752 -0.0096725672, -0.44440094 0.12771343 -0.013306394, -0.44405785 0.12784019 -0.059832886, -0.44393012 0.12788615 -0.05543296, -0.44420853 0.12778309 -0.013421401, -0.44407237 0.12783201 -0.009512499, -0.44392946 0.12788673 -0.06003125, -0.44384924 0.12791532 -0.055207148, -0.44393602 0.12788126 -0.0093107671, -0.44404653 0.12784156 -0.013580784, -0.44384912 0.12791561 -0.060256436, -0.44385096 0.12791225 -0.0090795606, -0.44392416 0.12788604 -0.013776168, -0.44384769 0.12791358 -0.013996497, -0.48481372 0.11310077 -0.10091235, -0.48484635 0.1130891 -0.10500847, -0.48498687 0.11303836 -0.10516535, -0.44483736 0.12755202 0.051797524, -0.48400071 0.11339487 -0.10108779, -0.44461623 0.12763183 0.051806346, -0.48421285 0.11331816 -0.10112013, -0.44440317 0.12770902 0.051870063, -0.48442635 0.11324075 -0.10110064, -0.48463014 0.11316717 -0.10103016, -0.46982601 0.11851829 -0.038591459, -0.46997389 0.1184652 -0.042627558, -0.46997467 0.11846448 -0.038433209, -0.48509216 0.11300018 -0.10535096, -0.46982482 0.11851905 -0.042469248, -0.48515743 0.11297669 -0.1055562, -0.44421008 0.12777881 0.051984772, -0.44429091 0.12774976 0.04816474, -0.46964797 0.11858276 -0.038710758, -0.47008625 0.11842449 -0.042817369, -0.48517951 0.11296859 -0.10577179, -0.44404754 0.12783772 0.052144513, -0.44413224 0.12780726 0.048041955, -0.47008654 0.11842412 -0.038243666, -0.46964613 0.11858366 -0.042350218, -0.46944955 0.11865459 -0.038784817, -0.47015592 0.11839923 -0.043028906, -0.46977589 0.11853288 0.024423763, -0.46994165 0.1184732 0.020502701, -0.46994463 0.11847189 0.024583384, -0.469771 0.11853491 0.020662531, -0.47015607 0.11839901 -0.038032547, -0.46957633 0.11860517 0.024311259, -0.47007117 0.11842629 0.02030395, -0.46924046 0.1187302 -0.038810149, -0.47007254 0.11842559 0.024781391, -0.46956936 0.11860785 0.020774201, -0.47015205 0.11839716 0.020077989, -0.47015247 0.11839679 0.02500616, -0.44392458 0.12788214 0.052339926, -0.44400093 0.12785457 0.047886744, -0.4693484 0.11868778 0.020831183, -0.44490877 0.12753278 -0.067226365, -0.44384784 0.12790985 0.052560762, -0.44390309 0.12789012 0.047705665, -0.44467756 0.12761648 -0.06721817, -0.44384232 0.12791201 0.047507003, -0.44445124 0.12769827 -0.067270383, -0.44464421 0.12762566 -0.017520115, -0.44488034 0.12754045 -0.020942643, -0.44420305 0.12778783 -0.063452795, -0.44424394 0.12777331 -0.067379698, -0.444653 0.12762268 -0.020941541, -0.44404331 0.12784564 -0.063293561, -0.44406787 0.12783687 -0.067539677, -0.44442508 0.12770495 -0.017461553, -0.44443205 0.12770264 -0.020998523, -0.44392243 0.12788928 -0.063099101, -0.44393411 0.12788545 -0.067740396, -0.4442254 0.12777717 -0.01734902, -0.44423041 0.12777565 -0.021110073, -0.47636387 0.11562462 -0.086673453, -0.47635993 0.11562599 -0.086632714, -0.47634831 0.11563024 -0.086593613, -0.47632924 0.1156372 -0.08655782, -0.47636387 0.11561482 0.086687639, -0.47635922 0.11561653 0.086732015, -0.47634545 0.11562166 0.086774334, -0.47632298 0.11562958 0.086812004, -0.4762933 0.11564039 0.086843744, -0.47625783 0.11565329 0.086867556, -0.47621819 0.11566761 0.086882576, -0.47617635 0.11568259 0.086887673, -0.47613451 0.11569773 0.086882815, -0.47609487 0.11571214 0.086868122, -0.44417813 0.12725782 0.067992941, -0.44424501 0.12723358 0.067892447, -0.44433317 0.12720177 0.067812458, -0.44412199 0.12727804 0.068229303, -0.44413623 0.12727293 0.068107501, -0.44477668 0.12704125 0.067769751, -0.4444367 0.12716427 0.067757592, -0.4445498 0.12712337 0.067731634, -0.44466546 0.12708151 0.067735776, -0.44412193 0.12727788 0.070343718, -0.44422522 0.12724057 0.070656434, -0.44416884 0.12726088 0.070561484, -0.44413379 0.12727365 0.070455417, -0.44430012 0.12721337 0.070735589, -0.44438979 0.12718102 0.070795283, -0.47167358 0.11731164 0.079974338, -0.47210237 0.11715657 0.080277815, -0.47190115 0.11722934 0.080104992, -0.47227058 0.11709574 0.080486462, -0.47632918 0.11562744 0.086572036, -0.47634813 0.11562046 0.08660768, -0.47635987 0.11561634 0.086646751, -0.44412199 0.12728155 0.0065425783, -0.44413412 0.12727712 0.0064294487, -0.44417009 0.1272641 0.0063220412, -0.44422784 0.12724318 0.0062261969, -0.44430456 0.12721546 0.0061468035, -0.44439623 0.12718233 0.0060879439, -0.44449797 0.12714556 0.0060526878, -0.44460461 0.1271069 0.0060426146, -0.44412199 0.12728143 0.008848533, -0.44433656 0.1272037 0.0092681497, -0.44424722 0.1272361 0.0091882497, -0.44417912 0.12726071 0.0090872496, -0.44455612 0.12712424 0.0093469471, -0.44444174 0.12716566 0.0093220919, -0.44413638 0.12727617 0.0089715868, -0.46908149 0.11825337 0.0067330748, -0.46944001 0.1181238 0.0069256276, -0.46928105 0.11818126 0.0067864507, -0.46936777 0.11814985 0.0068466812, -0.46953931 0.11808781 0.0072329193, -0.46918413 0.11821631 0.0067479759, -0.46949419 0.11810413 0.0070194155, -0.46952793 0.11809203 0.0071234554, -0.46903327 0.11827068 0.011339411, -0.46953931 0.11808766 0.010840788, -0.46914348 0.11823073 0.011334673, -0.46924958 0.11819233 0.011302426, -0.46942696 0.11812833 0.011165395, -0.46952644 0.11809234 0.010957465, -0.46948811 0.11810605 0.011067733, -0.46934596 0.11815761 0.011244997, -0.46953931 0.11808722 0.019837901, -0.46952561 0.11809216 0.019957915, -0.46948507 0.11810668 0.020071045, -0.46942046 0.11813013 0.020170376, -0.46933499 0.11816089 0.020250157, -0.4692342 0.1181974 0.020305946, -0.46912369 0.11823727 0.020334437, -0.46901006 0.11827847 0.020333812, -0.44441155 0.12717634 0.01378347, -0.44423428 0.12724045 0.01392065, -0.44431525 0.12721114 0.013840899, -0.44413486 0.12727641 0.014128432, -0.44417313 0.12726264 0.014018372, -0.44451776 0.12713802 0.013751283, -0.44462803 0.12709802 0.013746485, -0.44412199 0.12728108 0.014245108, -0.44412205 0.12728104 0.016543463, -0.44432375 0.12720792 0.0169539, -0.44423947 0.1272385 0.01687409, -0.44417545 0.12726161 0.016774997, -0.44442353 0.12717186 0.017010078, -0.44413558 0.12727614 0.016662702, -0.44453302 0.12713221 0.017039493, -0.46910498 0.11824442 0.015739039, -0.46948215 0.11810794 0.015998676, -0.46932462 0.11816503 0.015817747, -0.46941409 0.11813268 0.015897706, -0.46953925 0.11808726 0.016237572, -0.46921948 0.11820307 0.015763775, -0.46952471 0.11809249 0.01611422, -0.44412193 0.12728065 0.021950111, -0.44413576 0.12727574 0.021830335, -0.44417611 0.12726101 0.021717086, -0.44424096 0.12723762 0.021617934, -0.44432616 0.12720685 0.021537945, -0.4444271 0.12717038 0.021482185, -0.44453743 0.12713033 0.021453515, -0.44465128 0.12708925 0.02145429, -0.46942177 0.11812924 0.024913922, -0.46923766 0.11819576 0.024777785, -0.46933743 0.1181598 0.024834082, -0.46953925 0.11808679 0.025244609, -0.4691281 0.11823553 0.024748608, -0.46948579 0.1181061 0.025012985, -0.46952572 0.11809167 0.025125369, -0.46952471 0.11809175 0.028955832, -0.46948203 0.11810729 0.029071674, -0.46953925 0.11808656 0.02883248, -0.46941361 0.11813189 0.029172614, -0.46921876 0.1182024 0.029306546, -0.46932408 0.11816435 0.029252723, -0.46910408 0.1182439 0.029331282, -0.4689872 0.11828615 0.029324785, -0.44412199 0.12728056 0.024236009, -0.44451037 0.12713997 0.024728462, -0.44440582 0.12717785 0.024695054, -0.44413462 0.12727581 0.024351135, -0.44431132 0.12721194 0.024637207, -0.44423196 0.12724075 0.024557307, -0.44417199 0.12726246 0.024460331, -0.4695392 0.118086 0.037824616, -0.46952757 0.11809036 0.037935778, -0.46949282 0.11810286 0.038041338, -0.46943679 0.11812302 0.03813614, -0.46936262 0.11814997 0.038215235, -0.46927342 0.11818217 0.038274929, -0.46917424 0.11821809 0.038311973, -0.46906969 0.11825588 0.038324818, -0.4689652 0.11829369 0.038312271, -0.46942934 0.11812614 0.03393288, -0.46925548 0.11818895 0.033794954, -0.46934995 0.11815484 0.033853278, -0.46953931 0.11808631 0.034254029, -0.46915087 0.1182268 0.033761784, -0.4694894 0.11810437 0.034029797, -0.46952668 0.11809094 0.034138873, -0.44444254 0.12716424 0.02918376, -0.44424751 0.12723483 0.029317513, -0.44433701 0.12720244 0.029237732, -0.4445571 0.12712277 0.029159173, -0.44413647 0.12727502 0.029534385, -0.44417909 0.12725952 0.029418483, -0.44467399 0.12708057 0.029165372, -0.44412205 0.12728022 0.029657587, -0.44412199 0.12728007 0.031926021, -0.4444882 0.12714759 0.032413766, -0.44413385 0.12727575 0.032037601, -0.4441686 0.12726313 0.032143369, -0.44438866 0.12718356 0.03237693, -0.44429937 0.12721582 0.032317325, -0.44422463 0.12724279 0.032237992, -0.46953925 0.11808555 0.046814546, -0.46952674 0.11809 0.04692851, -0.46949026 0.11810324 0.047036543, -0.46943167 0.11812457 0.047132984, -0.46935365 0.11815263 0.047212526, -0.46926102 0.11818627 0.047271237, -0.46915796 0.1182234 0.047305509, -0.46905026 0.11826232 0.047313944, -0.46894363 0.11830088 0.04729642, -0.46936193 0.11814998 0.042874858, -0.4691731 0.11821835 0.042778626, -0.46927246 0.11818226 0.042815313, -0.46943656 0.11812307 0.042954102, -0.46949264 0.11810276 0.043049023, -0.46952751 0.11809011 0.043154731, -0.46953925 0.11808582 0.043266192, -0.4446961 0.12707213 0.036879852, -0.44448695 0.12714766 0.036880419, -0.44459143 0.12710987 0.036867514, -0.44438761 0.12718366 0.036917284, -0.44429868 0.12721582 0.036977038, -0.44422427 0.12724268 0.037056044, -0.44416848 0.12726298 0.037150905, -0.44413373 0.12727544 0.037256524, -0.44412199 0.12727979 0.037367627, -0.44412199 0.12727979 0.039613977, -0.4444668 0.12715502 0.040095761, -0.44437221 0.12718916 0.040055916, -0.44413292 0.12727575 0.039721623, -0.44421783 0.12724498 0.039916679, -0.4441655 0.12726405 0.039823934, -0.4442879 0.12721966 0.039995238, -0.44412193 0.12727931 0.045079991, -0.44413429 0.12727477 0.044965878, -0.44417086 0.12726159 0.044857785, -0.44422951 0.1272403 0.044761583, -0.44430736 0.12721215 0.044682011, -0.44440025 0.12717853 0.04462339, -0.44450322 0.12714142 0.044588819, -0.44461086 0.12710258 0.044580325, -0.44471762 0.12706392 0.044597909, -0.46928909 0.11817589 0.051838502, -0.46953925 0.11808528 0.052280322, -0.4691945 0.11821003 0.051798567, -0.46937335 0.11814544 0.05189918, -0.46944335 0.1181201 0.051977739, -0.4694958 0.11810103 0.052070335, -0.46952829 0.11808935 0.052172884, -0.4695262 0.11808975 0.055918857, -0.46948799 0.1181037 0.056029364, -0.46953925 0.11808506 0.055802181, -0.46942636 0.11812589 0.056127205, -0.46934527 0.1181553 0.056207016, -0.46924868 0.11819023 0.056264326, -0.46914205 0.11822866 0.056296065, -0.4690316 0.11826871 0.056300506, -0.46892315 0.11830798 0.056277439, -0.44412199 0.12727924 0.04729943, -0.44444621 0.12716188 0.047775045, -0.44416246 0.12726454 0.047502622, -0.44413224 0.12727553 0.04740347, -0.44435647 0.12719439 0.04773207, -0.44427714 0.12722304 0.047670707, -0.44421163 0.12724689 0.047593132, -0.46953914 0.11808452 0.064787701, -0.46952555 0.11808953 0.06490697, -0.46948549 0.11810401 0.065019622, -0.46942124 0.11812718 0.065118775, -0.4693366 0.11815785 0.065198675, -0.46923646 0.11819413 0.065254912, -0.46912643 0.11823379 0.06528385, -0.46901318 0.11827479 0.065284148, -0.46890339 0.11831465 0.065255657, -0.46938404 0.11814097 0.060925618, -0.46949884 0.11809948 0.061093703, -0.46930465 0.11816965 0.060864344, -0.46944961 0.11811718 0.061003342, -0.46953925 0.11808486 0.061296776, -0.46921518 0.11820213 0.060821697, -0.46952906 0.11808851 0.061193123, -0.44451919 0.12713543 0.052300289, -0.44431609 0.12720878 0.052389398, -0.44441265 0.12717386 0.052332237, -0.44417334 0.12726046 0.05256708, -0.44412199 0.12727906 0.052794412, -0.44413507 0.12727429 0.052677587, -0.44423476 0.12723814 0.052469358, -0.4446297 0.12709534 0.052296028, -0.44473818 0.12705606 0.052319005, -0.44412199 0.12727877 0.054982945, -0.44442639 0.12716873 0.055450872, -0.44413552 0.12727375 0.055102691, -0.44417605 0.12725919 0.055215761, -0.44432575 0.12720503 0.055394962, -0.44424057 0.12723587 0.055314973, -0.44440761 0.12717496 0.063124076, -0.4443126 0.12720935 0.063066378, -0.44423261 0.12723821 0.062986627, -0.44417229 0.12726009 0.062889352, -0.44413465 0.12727372 0.062780157, -0.44412199 0.12727836 0.062664345, -0.46942064 0.11812732 0.069983557, -0.46948525 0.11810377 0.070082858, -0.46933553 0.11815812 0.069903567, -0.46952555 0.11808923 0.070195541, -0.46953925 0.11808422 0.070315585, -0.46923482 0.11819446 0.069847569, -0.46952495 0.11808917 0.073893175, -0.46948323 0.11810443 0.074007824, -0.46953914 0.11808395 0.073770955, -0.46941629 0.11812864 0.074108317, -0.46888444 0.11832096 0.074230835, -0.46932819 0.1181604 0.074188307, -0.4692246 0.11819795 0.074243024, -0.46911153 0.11823873 0.074269101, -0.46899578 0.11828056 0.074264988, -0.44475788 0.12704854 0.060043052, -0.44453478 0.12712927 0.06001462, -0.44464794 0.12708826 0.060014531, -0.44442478 0.12716901 0.060043499, -0.44423988 0.12723586 0.060179785, -0.44432464 0.12720536 0.060099766, -0.44417569 0.12725917 0.060278788, -0.44412205 0.12727861 0.060510889, -0.44413558 0.12727359 0.060391322, -0.44437298 0.1271867 0.078463808, -0.48384985 0.1129062 0.10057677, -0.44421843 0.12724279 0.078324661, -0.44416562 0.12726173 0.078231826, -0.44428861 0.12721731 0.078402922, -0.48149249 0.11375937 0.094313726, -0.48115522 0.11388138 0.093955979, -0.48133811 0.11381514 0.094119772, -0.48094887 0.11395594 0.093827352, -0.48452705 0.11266127 0.10024752, -0.48443314 0.11269532 0.10045077, -0.48453918 0.11265694 0.10013436, -0.48449114 0.1126743 0.10035492, -0.48435637 0.11272307 0.10053016, -0.48416266 0.11279313 0.10062443, -0.48426446 0.11275624 0.10058917, -0.48405588 0.11283174 0.10063405, -0.48394987 0.11287008 0.1006179, -0.48427925 0.11275114 0.098492548, -0.48442155 0.11269955 0.098760501, -0.4845095 0.11266775 0.099053755, -0.48453918 0.11265706 0.099360004, -0.44459075 0.12710811 0.075450227, -0.44438723 0.12718171 0.075500235, -0.44448629 0.12714575 0.075462952, -0.44422415 0.12724069 0.075638846, -0.44429842 0.12721388 0.075559929, -0.44416824 0.12726082 0.075733736, -0.44412208 0.12727763 0.07595022, -0.44413373 0.12727341 0.075839117, -0.44469514 0.12707028 0.075462207, -0.44479465 0.12703444 0.075498804, -0.44412208 0.12727763 0.078021333, -0.44413301 0.12727359 0.078129128, -0.48453933 0.11265649 0.10990997, -0.48452666 0.11266093 0.11002548, -0.48448935 0.11267443 0.11013444, -0.4844293 0.11269625 0.11023153, -0.48434994 0.11272487 0.11031123, -0.48425522 0.11275896 0.1103691, -0.48415083 0.1127969 0.11040266, -0.48404196 0.11283632 0.11040933, -0.48393434 0.11287513 0.11038934, -0.48383421 0.11291143 0.11034332, -0.48444292 0.11269145 0.10548256, -0.48428816 0.11274746 0.1053433, -0.48437268 0.11271682 0.10540389, -0.48449567 0.11267251 0.10557543, -0.48452812 0.11266066 0.10567795, -0.48453921 0.11265659 0.10578559, -0.44481125 0.12702774 0.083230272, -0.44460526 0.12710236 0.083172783, -0.44471124 0.12706386 0.083188996, -0.44449851 0.12714091 0.083182678, -0.44439664 0.12717777 0.083217964, -0.44430497 0.12721103 0.083276793, -0.44422802 0.12723877 0.083356276, -0.44417021 0.12725972 0.083451971, -0.44413421 0.12727275 0.083559528, -0.44412199 0.12727721 0.083672687, -0.44412199 0.12727711 0.085697159, -0.44416276 0.1272624 0.08590059, -0.4441323 0.12727341 0.085801229, -0.44435725 0.12719195 0.086130276, -0.44427767 0.12722081 0.086069122, -0.44421181 0.12724462 0.085991248, -0.48447353 0.15169707 0.10691141, -0.48446271 0.15169479 0.10680737, -0.48443112 0.15168802 0.10670768, -0.48437992 0.15167721 0.10661711, -0.48431122 0.1516625 0.10653938, -0.48422819 0.1516448 0.10647796, -0.44483706 0.14326523 0.083382294, -0.44505307 0.1433112 0.083448038, -0.44494882 0.14328901 0.08340241, -0.44472361 0.14324108 0.083389327, -0.44461513 0.14321807 0.083422706, -0.4445169 0.14319709 0.08348082, -0.44443437 0.14317951 0.083560422, -0.44437203 0.14316636 0.08365725, -0.4443334 0.14315815 0.083766326, -0.44432011 0.14315519 0.083881363, -0.44432011 0.14315519 0.085800394, -0.44435957 0.14316355 0.085996732, -0.44440702 0.14317365 0.086085066, -0.44433013 0.14315738 0.08590059, -0.44447097 0.14318725 0.086161569, -0.44454864 0.14320382 0.086223468, -0.48372388 0.15153727 0.11144395, -0.48382813 0.15155944 0.11149453, -0.4844735 0.15169671 0.11102079, -0.48394147 0.15158351 0.11151882, -0.48405692 0.15160805 0.11151512, -0.48441955 0.15168534 0.11124907, -0.48445976 0.15169397 0.11113821, -0.48416847 0.15163186 0.11148404, -0.48426968 0.15165338 0.11142693, -0.484355 0.15167159 0.11134703, -0.47243416 0.14913651 0.090271935, -0.44503483 0.14330781 0.075697049, -0.44482109 0.14326234 0.075640813, -0.44493112 0.14328572 0.075656369, -0.44471028 0.14323874 0.075651035, -0.44460472 0.14321634 0.07568644, -0.44450951 0.14319608 0.075745538, -0.44443002 0.14317913 0.075824842, -0.44437 0.14316636 0.075920537, -0.44433275 0.14315839 0.076027736, -0.44432023 0.1431558 0.076140508, -0.44432008 0.14315568 0.078113869, -0.44433096 0.14315799 0.078218237, -0.44436261 0.14316477 0.078317598, -0.44441387 0.14317557 0.078408167, -0.44448248 0.1431901 0.07848601, -0.44456545 0.14320774 0.078547284, -0.47322166 0.14930394 0.090742454, -0.47464272 0.14960608 0.091908053, -0.47396031 0.14946091 0.091289744, -0.48390314 0.15157594 0.10165821, -0.48401156 0.15159895 0.10167851, -0.48380205 0.15155442 0.10161318, -0.48412153 0.15162233 0.10167377, -0.48432496 0.1516657 0.10159041, -0.48422796 0.15164503 0.10164393, -0.48450071 0.15153268 0.10167377, -0.48452204 0.15153722 0.10160424, -0.48451236 0.15153509 0.10153244, -0.48467657 0.1513997 0.10175718, -0.48471913 0.15140873 0.10161807, -0.48469982 0.15140465 0.10147418, -0.46947345 0.14850719 0.079909727, -0.46946093 0.14850447 0.079797193, -0.46942395 0.14849663 0.079690591, -0.46936426 0.1484839 0.079595014, -0.46928534 0.14846715 0.07951571, -0.46919075 0.14844695 0.079456553, -0.4448041 0.14325914 0.067901626, -0.44501558 0.14330417 0.067948535, -0.44491246 0.14328219 0.067913041, -0.44469622 0.14323623 0.067915305, -0.44459388 0.14321442 0.067952886, -0.444502 0.14319488 0.068012431, -0.44442549 0.1431786 0.068091586, -0.44436789 0.14316639 0.068185791, -0.44433215 0.14315863 0.068291023, -0.44432023 0.14315625 0.068401679, -0.44432023 0.14315607 0.070425585, -0.44433162 0.14315854 0.070533827, -0.44449478 0.14319311 0.070808515, -0.44436607 0.14316578 0.070636734, -0.44442117 0.14317749 0.070729867, -0.44458342 0.14321195 0.070869103, -0.46875873 0.14835478 0.083729044, -0.4688625 0.14837679 0.083769664, -0.46947345 0.14850695 0.083285466, -0.46897268 0.14840032 0.083785221, -0.46908343 0.14842387 0.083775118, -0.46918896 0.14844637 0.083739743, -0.46942344 0.1484962 0.083505467, -0.46946079 0.14850414 0.083398357, -0.46928403 0.1484666 0.083680734, -0.46936354 0.1484835 0.083601251, -0.44499508 0.14330025 0.060202643, -0.44487983 0.14327571 0.060170248, -0.44476023 0.14325026 0.060167566, -0.44464365 0.14322546 0.060194448, -0.44453692 0.14320275 0.060249731, -0.44444647 0.14318357 0.060329571, -0.44437787 0.14316894 0.060429588, -0.44433475 0.14315972 0.060543671, -0.44432017 0.14315668 0.060665026, -0.44432011 0.14315636 0.062735096, -0.44433275 0.14315906 0.06284751, -0.4446027 0.14321654 0.063188359, -0.44436958 0.14316691 0.062954351, -0.44442931 0.14317967 0.063049808, -0.44450834 0.14319639 0.063129142, -0.46917033 0.14844316 0.070358977, -0.46927112 0.14846452 0.070416316, -0.46941993 0.14849617 0.070593819, -0.46935582 0.14848258 0.070495948, -0.46947339 0.14850761 0.07082136, -0.46946001 0.14850475 0.070704326, -0.46877801 0.14835949 0.074696407, -0.4688811 0.14838137 0.074731901, -0.46947345 0.14850752 0.074242875, -0.4689894 0.14840449 0.074743077, -0.46909732 0.14842743 0.074729428, -0.46942571 0.14849718 0.074458763, -0.46946144 0.14850473 0.07435374, -0.46919975 0.14844915 0.074692056, -0.46929157 0.14846866 0.074632123, -0.46936801 0.14848492 0.074553177, -0.46947342 0.1485081 0.061735168, -0.46945879 0.14850493 0.061613455, -0.46941563 0.14849581 0.061499313, -0.46934631 0.14848109 0.061398938, -0.46925575 0.14846197 0.061319008, -0.46914843 0.14843902 0.061264202, -0.44474283 0.14324702 0.052435473, -0.44497326 0.14329608 0.052459791, -0.44485953 0.14327188 0.052433267, -0.44462994 0.14322297 0.052465513, -0.4445273 0.14320128 0.052522138, -0.44444075 0.14318277 0.052602038, -0.44437504 0.14316878 0.052700713, -0.44433409 0.14316007 0.052812383, -0.4443202 0.14315715 0.052930698, -0.44432008 0.14315686 0.055042192, -0.44433367 0.14315978 0.055159286, -0.44437376 0.14316829 0.055269673, -0.44443777 0.14318182 0.055367723, -0.44452253 0.14319994 0.055447444, -0.44462326 0.14322127 0.055504635, -0.46879843 0.14836435 0.065661058, -0.4689137 0.14838889 0.065693244, -0.46947345 0.14850804 0.065198377, -0.46945894 0.14850497 0.065319911, -0.4690333 0.14841434 0.065695986, -0.46914992 0.14843914 0.065669045, -0.46925667 0.14846183 0.06561394, -0.46934715 0.14848115 0.065533951, -0.46941587 0.14849572 0.065433875, -0.46947339 0.14850871 0.052651629, -0.46946239 0.14850642 0.052545741, -0.4694297 0.14849944 0.052445129, -0.46937689 0.14848809 0.052353367, -0.46930647 0.14847311 0.052275255, -0.46922138 0.1484551 0.052214339, -0.46912557 0.14843462 0.052172884, -0.44472501 0.14324358 0.044706598, -0.44495034 0.14329156 0.044720426, -0.44483843 0.14326772 0.044699922, -0.44461608 0.14322045 0.044739529, -0.44451755 0.14319947 0.044797793, -0.44443479 0.14318173 0.044877335, -0.44437215 0.14316851 0.044974223, -0.4443334 0.1431603 0.045083538, -0.44432008 0.14315741 0.045199141, -0.44432014 0.14315733 0.047347084, -0.44437793 0.14316963 0.047583118, -0.4444471 0.14318427 0.047683105, -0.44433478 0.14316042 0.047468677, -0.44453797 0.14320369 0.047763243, -0.44464508 0.14322644 0.04781805, -0.4688203 0.14836951 0.05662258, -0.46893412 0.14839371 0.056648985, -0.46947339 0.14850844 0.056151584, -0.46905071 0.14841852 0.056647107, -0.46916363 0.14844258 0.056616858, -0.46941862 0.14849688 0.056381747, -0.4694595 0.14850552 0.056270078, -0.46926624 0.14846438 0.056560323, -0.4693529 0.14848283 0.056480244, -0.4694733 0.14850914 0.043570682, -0.46946153 0.1485067 0.043460861, -0.46942624 0.14849918 0.043356344, -0.46936941 0.14848708 0.043262288, -0.46929368 0.14847083 0.043183371, -0.46920303 0.14845167 0.043123379, -0.46910164 0.14843008 0.043085113, -0.4694213 0.14849785 0.04732649, -0.46946034 0.14850621 0.047217622, -0.46947345 0.14850898 0.047102019, -0.46927616 0.14846693 0.047503367, -0.46935871 0.14848456 0.047423556, -0.46906856 0.14842275 0.047594503, -0.4691776 0.14844607 0.047561333, -0.46895513 0.14839871 0.047601238, -0.46884316 0.14837486 0.047580704, -0.44442889 0.14318094 0.037155554, -0.44481677 0.14326356 0.036970094, -0.44470671 0.14324011 0.036981091, -0.4446018 0.14321773 0.037017033, -0.44450763 0.1431978 0.037076339, -0.4443326 0.14316043 0.037357494, -0.44436944 0.14316836 0.037250832, -0.44432008 0.14315787 0.037469879, -0.44492641 0.14328684 0.036984369, -0.44432026 0.14315788 0.039649531, -0.44466797 0.14323182 0.040128246, -0.4445723 0.14321144 0.04008691, -0.44433117 0.14316015 0.0397553, -0.44441664 0.14317827 0.039947823, -0.44436392 0.14316712 0.039856121, -0.44448698 0.14319327 0.040025696, -0.4449015 0.14328198 0.029252335, -0.4447943 0.14325926 0.029243931, -0.44468787 0.14323653 0.029259041, -0.44458756 0.14321515 0.029297724, -0.44449762 0.14319606 0.029358044, -0.44442284 0.14318022 0.029436901, -0.44436678 0.14316823 0.029530391, -0.44433185 0.14316083 0.029634282, -0.44432014 0.14315835 0.029743597, -0.44432017 0.14315818 0.031949356, -0.44442418 0.14318024 0.032257542, -0.4444997 0.14319636 0.032336488, -0.44436732 0.14316817 0.032163516, -0.44433206 0.14316075 0.032059178, -0.44469205 0.14323725 0.032434568, -0.4445906 0.14321561 0.03239648, -0.46907657 0.14842528 0.034001276, -0.46918359 0.14844793 0.034035847, -0.46936136 0.14848584 0.034173891, -0.46928051 0.14846863 0.034094289, -0.46946046 0.14850689 0.034378365, -0.46942258 0.14849883 0.034270123, -0.46947333 0.14850964 0.034492329, -0.46886709 0.14838044 0.038535401, -0.46947339 0.14850946 0.038049981, -0.46897691 0.14840381 0.038550064, -0.46908686 0.14842714 0.038539007, -0.46946093 0.14850681 0.038162425, -0.46919185 0.14844953 0.038502976, -0.4694241 0.14849895 0.03826873, -0.46928602 0.14846963 0.03844367, -0.46936473 0.14848627 0.038364455, -0.4694733 0.14851016 0.025416836, -0.4694595 0.14850725 0.02529867, -0.46941862 0.14849851 0.025186881, -0.46935302 0.14848456 0.025088325, -0.46926636 0.14846608 0.025008485, -0.46916375 0.14844427 0.024951711, -0.46905085 0.14842024 0.024921581, -0.44444525 0.14318535 0.021685854, -0.44464087 0.14322698 0.021550372, -0.44453496 0.1432045 0.021605864, -0.44437709 0.14317086 0.021785423, -0.44475666 0.14325173 0.021522745, -0.44433454 0.14316183 0.021899149, -0.44432023 0.14315881 0.022019997, -0.44487569 0.14327697 0.021524504, -0.44432023 0.14315869 0.02424638, -0.44437101 0.14316942 0.024468556, -0.44443217 0.14318241 0.024564728, -0.44433311 0.14316137 0.024360344, -0.44460991 0.14322026 0.024702832, -0.44451326 0.14319965 0.024644271, -0.44471696 0.14324303 0.024737403, -0.46889213 0.14838623 0.029486284, -0.46947345 0.14850996 0.028995171, -0.46899921 0.14840899 0.029494926, -0.46942684 0.14850011 0.029208288, -0.46946159 0.14850743 0.029104456, -0.46910542 0.14843158 0.029479519, -0.46920606 0.14845298 0.029440865, -0.46937072 0.14848816 0.029301807, -0.46929577 0.14847223 0.029380783, -0.46947339 0.14851066 0.016344413, -0.46945843 0.14850751 0.016221866, -0.46941444 0.14849816 0.016106561, -0.46934411 0.1484832 0.016005829, -0.46925166 0.14846352 0.01592584, -0.46914297 0.14844039 0.015871629, -0.46902457 0.14841518 0.015846208, -0.44462344 0.14322367 0.013836607, -0.44484958 0.14327195 0.013800845, -0.44473442 0.14324729 0.013805106, -0.44452253 0.14320226 0.013893917, -0.44443789 0.1431842 0.013973817, -0.4443737 0.14317057 0.014071599, -0.44433379 0.1431621 0.014182195, -0.44432017 0.1431592 0.014299229, -0.44432011 0.14315906 0.016540393, -0.44433403 0.14316204 0.016658857, -0.44444051 0.14318463 0.016869023, -0.44437501 0.1431708 0.016770557, -0.44452712 0.14320309 0.016949013, -0.4446297 0.14322491 0.017005637, -0.44474259 0.1432489 0.017035708, -0.46891785 0.14839225 0.020433083, -0.46947339 0.14851047 0.019937649, -0.46903685 0.14841758 0.020434603, -0.46945897 0.14850739 0.020058349, -0.46915263 0.14844215 0.020407096, -0.46925864 0.14846477 0.020351604, -0.46941641 0.14849834 0.020171836, -0.46934828 0.14848392 0.020271793, -0.46947339 0.14851126 0.0072750002, -0.46946159 0.14850871 0.0071655661, -0.46942669 0.14850125 0.0070615858, -0.46937042 0.1484893 0.0069679171, -0.46929538 0.14847326 0.0068890005, -0.46920547 0.1484542 0.0068289191, -0.46910468 0.14843282 0.0067901462, -0.4689981 0.14841013 0.0067750365, -0.4444305 0.14318314 0.0062650591, -0.44437015 0.14317022 0.0063607544, -0.44451037 0.14320008 0.0061855167, -0.44433287 0.14316231 0.006468311, -0.44432017 0.14315972 0.0065814406, -0.44460586 0.14322044 0.0061267167, -0.44482288 0.14326657 0.0060815364, -0.44471183 0.14324299 0.00609155, -0.44432008 0.14315943 0.0088318437, -0.44433495 0.1431627 0.0089545399, -0.44465032 0.14322974 0.0093046278, -0.44437912 0.14317206 0.0090696961, -0.44444939 0.14318706 0.0091705173, -0.44454178 0.14320667 0.0092502683, -0.44476891 0.14325498 0.0093301684, -0.46894404 0.14839841 0.011375293, -0.46947339 0.14851102 0.010877028, -0.46905926 0.14842293 0.01137121, -0.4691703 0.14844646 0.01133965, -0.469271 0.14846797 0.01128228, -0.46945992 0.14850812 0.010994062, -0.46941993 0.14849962 0.01110442, -0.46935567 0.14848594 0.01120232, -0.46947339 0.14851148 0.0018134266, -0.46947339 0.14851168 -0.0017956048, -0.46942338 0.14850105 -0.0020163208, -0.469363 0.14848827 -0.0021122545, -0.46946079 0.14850903 -0.0019090325, -0.46897069 0.14840475 -0.002295509, -0.46918777 0.148451 -0.0022503287, -0.46908173 0.1484284 -0.0022857338, -0.46928307 0.14847125 -0.0021917075, -0.46942332 0.14850079 0.0020341128, -0.4694607 0.14850874 0.0019268245, -0.46936309 0.14848799 0.0021299571, -0.46897072 0.14840455 0.0023133308, -0.46908173 0.14842817 0.0023035556, -0.46918777 0.1484507 0.0022682101, -0.46928313 0.14847097 0.0022094399, -0.44458809 0.14321712 -0.0015489608, -0.44479558 0.14326125 -0.0016027838, -0.44468907 0.14323853 -0.001587525, -0.44449821 0.143198 -0.0014886111, -0.44442329 0.14318199 -0.0014098138, -0.44433188 0.14316259 -0.001212135, -0.44436684 0.14317007 -0.0013161451, -0.44432011 0.14316007 -0.0011028796, -0.44479552 0.14326112 0.0016198605, -0.4443202 0.14316002 0.0011201352, -0.444332 0.14316246 0.0012294501, -0.44458824 0.14321694 0.0015660673, -0.44468892 0.14323834 0.001604721, -0.44442323 0.14318186 0.0014272183, -0.44436684 0.14316982 0.0013334006, -0.44449821 0.14319779 0.0015060157, -0.44412199 0.12728199 -0.0011357218, -0.44412199 0.12728192 0.0011511296, -0.46952698 0.1180927 -0.0019400269, -0.46953925 0.11808832 -0.0018270165, -0.46949109 0.11810572 -0.0020473152, -0.46905658 0.11826293 -0.002326861, -0.46943334 0.11812659 -0.0021431595, -0.46935663 0.11815438 -0.0022224635, -0.46926504 0.11818755 -0.0022814423, -0.46916327 0.11822435 -0.0023167878, -0.46952713 0.11809251 0.0019544512, -0.46949115 0.1181055 0.0020617694, -0.46953925 0.1180881 0.0018413514, -0.46905658 0.11826269 0.0023411959, -0.46943334 0.11812644 0.0021576136, -0.46935663 0.11815414 0.0022368878, -0.46926495 0.11818722 0.0022958964, -0.46916333 0.11822417 0.0023311824, -0.44447711 0.1271535 -0.001620397, -0.44429341 0.1272199 -0.0015216917, -0.44438019 0.12718867 -0.0015818328, -0.44457966 0.12711646 -0.0016354769, -0.44422135 0.12724613 -0.0014428049, -0.44416696 0.12726571 -0.0013489872, -0.44413331 0.12727784 -0.0012450367, -0.44457972 0.12711631 0.0016508251, -0.44447711 0.12715337 0.0016358644, -0.44416693 0.12726556 0.001364544, -0.44413331 0.12727769 0.0012602955, -0.44422117 0.12724584 0.0014582127, -0.44438019 0.12718843 0.0015973002, -0.4442935 0.12721978 0.0015371293, -0.4411976 0.12888293 0.087903246, -0.48784247 0.11201513 0.116556, -0.4412159 0.12892972 0.088203862, -0.48770922 0.11212875 0.11678578, -0.44122842 0.12902041 0.088497862, -0.48761043 0.11227433 0.11701904, -0.44123498 0.12905011 0.088574752, -0.4875069 0.12617458 0.14668892, -0.48523954 0.12490073 0.14080681, -0.48531258 0.12482828 0.14075272, -0.48536757 0.1247579 0.1406783, -0.48515281 0.12497152 0.14083771, -0.48540196 0.12469348 0.1405877, -0.48505667 0.12503661 0.14084406, -0.48541346 0.12463848 0.14048605, -0.48495644 0.12509267 0.14082514, -0.48485783 0.12513651 0.14078222, -0.48476592 0.12516586 0.1407174, -0.48468575 0.12517917 0.1406344, -0.48541346 0.12327345 0.1375583, -0.48541096 0.12324226 0.13748772, -0.48514453 0.12310998 0.13683401, -0.48531246 0.12162523 0.13388284, -0.48525357 0.12311341 0.1369931, -0.48523957 0.12169768 0.13393696, -0.48536757 0.12155488 0.13380878, -0.48533669 0.12313999 0.13716544, -0.4851526 0.12176843 0.13396795, -0.48539039 0.12318859 0.13734443, -0.48540187 0.12149043 0.13371821, -0.48540321 0.12321392 0.13741638, -0.48505649 0.12183355 0.13397424, -0.48541346 0.12143549 0.13361628, -0.4849565 0.12188961 0.13395531, -0.48485783 0.12193352 0.13391237, -0.48476577 0.1219628 0.13384752, -0.48468566 0.12197609 0.13376458, -0.4854134 0.12036161 0.13131304, -0.48514438 0.12019815 0.13058893, -0.48530811 0.11791362 0.12591623, -0.48525372 0.12020157 0.13074787, -0.48523214 0.11798771 0.12596954, -0.48536548 0.1178415 0.12584122, -0.48533675 0.12022822 0.13092034, -0.48514232 0.11805961 0.12599899, -0.48539039 0.1202769 0.13109894, -0.4854013 0.11777546 0.12574933, -0.48540333 0.12030213 0.13117097, -0.48504326 0.11812527 0.12600206, -0.48541346 0.11771907 0.12564538, -0.48541099 0.12033035 0.13124244, -0.48494083 0.11818083 0.12597917, -0.48484072 0.11822337 0.12593128, -0.48513034 0.11681233 0.12330665, -0.48530814 0.11567689 0.12111856, -0.48524618 0.11681361 0.12347044, -0.48523208 0.11575089 0.12117209, -0.48499104 0.11683598 0.12316428, -0.48536548 0.11560468 0.12104361, -0.48533407 0.11683983 0.12364875, -0.4851422 0.11582285 0.12120141, -0.48540124 0.11553851 0.12095167, -0.48539039 0.11688998 0.12383474, -0.48504326 0.11588846 0.12120463, -0.48483428 0.11688377 0.12304889, -0.48494068 0.11594415 0.12118162, -0.48484072 0.11598656 0.12113382, -0.4854134 0.11548238 0.1208479, -0.4875069 0.11271721 0.11782528, -0.48541346 0.11697467 0.12404875, -0.48540333 0.11691514 0.1239066, -0.48541078 0.11694343 0.12397812, -0.4854134 0.11451414 0.11877133, -0.48541093 0.11448288 0.11870076, -0.48540315 0.11445457 0.11862911, -0.48539037 0.11442941 0.11855747, -0.48533389 0.11437923 0.1183715, -0.48524606 0.11435308 0.11819299, -0.48513028 0.1143517 0.11802919, -0.48752874 0.1125095 0.11741017, -0.47893402 0.12061664 0.12285875, -0.48499104 0.1143754 0.11788674, -0.47919711 0.12026504 0.1224698, -0.47890142 0.12061562 0.12281094, -0.47913721 0.12029047 0.12244131, -0.47886023 0.120593 0.12270571, -0.47885349 0.12056692 0.12263988, -0.47887644 0.12060763 0.12275933, -0.47907594 0.12032376 0.12242736, -0.48483422 0.11442319 0.11777152, -0.47901663 0.12036286 0.12242915, -0.47891721 0.12045017 0.12247826, -0.47896281 0.12040582 0.12244652, -0.47888264 0.12049332 0.12252305, -0.47886097 0.12053308 0.12257792, -0.46902034 0.12303187 0.11426626, -0.46144286 0.12470728 0.10733305, -0.46895278 0.12302752 0.11416341, -0.46890739 0.12300465 0.11405118, -0.46888688 0.12296447 0.11393665, -0.46889254 0.12290956 0.11382641, -0.46892381 0.12284304 0.11372755, -0.46897915 0.12276921 0.11364578, -0.46141008 0.12470618 0.10728525, -0.46138522 0.12469818 0.10723348, -0.46905485 0.12269244 0.11358626, -0.46170574 0.12435554 0.10694404, -0.46914658 0.1226173 0.1135527, -0.46924853 0.12254843 0.11354657, -0.46935478 0.1224902 0.11356913, -0.46945864 0.12244581 0.11361836, -0.46164587 0.12438104 0.10691546, -0.46136907 0.12468365 0.10717995, -0.461362 0.12465744 0.10711409, -0.46136963 0.12462352 0.10705216, -0.46152538 0.12445347 0.10690345, -0.4615846 0.12441421 0.10690163, -0.4614259 0.12454078 0.10695253, -0.46147153 0.12449637 0.10692073, -0.46139142 0.12458399 0.10699721, -0.44977996 0.12753139 0.09718816, -0.44122455 0.12929353 0.089082673, -0.44971246 0.12752712 0.097084954, -0.44966713 0.12750423 0.096972987, -0.4496465 0.12746404 0.096858189, -0.44965214 0.12740913 0.096748188, -0.44968346 0.12734261 0.096649244, -0.44973868 0.12726879 0.096567467, -0.44981453 0.12719204 0.096507862, -0.44123513 0.12920693 0.08891128, -0.44990611 0.1271169 0.096474245, -0.45000818 0.12704806 0.096468374, -0.45011428 0.12698971 0.096490905, -0.45021823 0.12694542 0.09653981, -0.46159425 0.12368992 0.10673331, -0.46143451 0.12375773 0.1066568, -0.4612712 0.12384637 0.10662006, -0.46111318 0.123951 0.10662495, -0.46096945 0.12406562 0.10667123, -0.46084812 0.12418383 0.10675611, -0.46075603 0.12429895 0.10687496, -0.46069816 0.12440464 0.10702141, -0.46067789 0.12449493 0.10718678, -0.46069625 0.12456466 0.10736214, -0.4847177 0.12306966 0.13752659, -0.48472401 0.12308225 0.13756259, -0.48472789 0.1230965 0.13759829, -0.4847292 0.12311207 0.13763349, -0.48471773 0.1143104 0.11873953, -0.48472396 0.11432301 0.11877562, -0.48472783 0.1143371 0.11881126, -0.48472914 0.11435278 0.11884661, -0.47892579 0.11966708 0.12218271, -0.47908542 0.11959939 0.12225913, -0.47876236 0.11975572 0.12214585, -0.47860447 0.11986037 0.12215091, -0.47846064 0.11997485 0.12219693, -0.47833946 0.12009318 0.12228201, -0.4782472 0.12020834 0.12240075, -0.47818932 0.12031403 0.12254731, -0.47816911 0.12040427 0.12271239, -0.47818759 0.12047412 0.12288786, -0.48471773 0.12015791 0.13128136, -0.48472401 0.1201705 0.13131733, -0.48472786 0.12018462 0.1313531, -0.48472917 0.12020025 0.1313885, -0.48471779 0.11677088 0.1240169, -0.48472401 0.11678354 0.1240529, -0.48472786 0.11679764 0.12408854, -0.48472929 0.11681332 0.12412395, -0.46906397 0.12232992 0.11419334, -0.47823048 0.12051299 0.12303106, -0.47829691 0.12053427 0.12316884, -0.47838423 0.12053709 0.12329628, -0.48443946 0.11676784 0.12362398, -0.48468944 0.11674586 0.12392388, -0.48451796 0.11674397 0.12368168, -0.4845874 0.11673209 0.12375294, -0.4846454 0.11673272 0.12383495, -0.48472914 0.11755772 0.12572072, -0.48469067 0.12013353 0.13119192, -0.48459455 0.12011844 0.13102625, -0.48464933 0.12012023 0.13110565, -0.48472914 0.12127404 0.13369174, -0.44982353 0.12682948 0.097114876, -0.46073923 0.12460354 0.10750516, -0.46080562 0.1246248 0.10764287, -0.46089292 0.12462752 0.10777043, -0.48458746 0.11427155 0.11847545, -0.48443958 0.1143073 0.11834665, -0.4845179 0.11428343 0.1184044, -0.48464549 0.11427227 0.11855747, -0.4846895 0.11428541 0.11864664, -0.48472914 0.11532089 0.12092297, -0.48469082 0.12304543 0.13743712, -0.48459467 0.12303028 0.13727136, -0.48464945 0.12303211 0.13735096, -0.4847292 0.12447716 0.14056148, -0.46901384 0.12255646 0.1141523, -0.46900514 0.12252972 0.11408292, -0.46902549 0.12248884 0.11402367, -0.46896353 0.12278304 0.11411141, -0.46907052 0.12244214 0.11398624, -0.46894649 0.12272948 0.11397256, -0.46913123 0.12239918 0.11397834, -0.46898708 0.12264788 0.11385389, -0.46907714 0.12255456 0.11377929, -0.46919873 0.12246859 0.11376353, -0.48494199 0.12136769 0.13373046, -0.48489934 0.12141541 0.1337734, -0.48483828 0.12146056 0.13378565, -0.48515487 0.12146129 0.13376947, -0.48477212 0.12149385 0.13376518, -0.48506936 0.12155661 0.13385539, -0.48494747 0.12164705 0.13387997, -0.48481497 0.12171367 0.13383873, -0.48494139 0.11765225 0.12576078, -0.48489693 0.11770107 0.1258036, -0.48515347 0.11774698 0.12580107, -0.48483381 0.11774686 0.12581442, -0.48506448 0.11784439 0.12588666, -0.48493847 0.11793607 0.12590812, -0.44977334 0.12705603 0.097073898, -0.44976476 0.12702928 0.097004935, -0.44978514 0.12698837 0.096945271, -0.44972315 0.12728271 0.097032979, -0.44983009 0.12694179 0.096907839, -0.44970599 0.12722905 0.096894309, -0.44989094 0.1268988 0.096899912, -0.44974664 0.12714735 0.096775666, -0.44983682 0.12705423 0.096700862, -0.44995841 0.12696823 0.096685097, -0.48494217 0.12457076 0.14060046, -0.48489937 0.1246184 0.14064299, -0.4848384 0.12466365 0.14065553, -0.48515484 0.12466428 0.14063929, -0.48477197 0.12469685 0.140635, -0.48506948 0.12475957 0.14072491, -0.48494747 0.12485006 0.14074983, -0.48481497 0.12491664 0.14070855, -0.48494121 0.11541539 0.12096326, -0.48489693 0.11546429 0.12100603, -0.48515341 0.11551003 0.12100355, -0.48483381 0.11550996 0.12101699, -0.48506448 0.11560759 0.12108923, -0.48493868 0.11569929 0.12111081, -0.44123712 0.12944964 0.08939217, -0.44123778 0.12964861 0.089676127, -0.48765376 0.12655976 0.14749633, -0.44123602 0.12988879 0.089924768, -0.48770905 0.12679899 0.1478041, -0.44123983 0.13016884 0.090129092, -0.48775199 0.1270856 0.14804934, -0.44125503 0.13048169 0.09027873, -0.487773 0.12733662 0.1481757, -0.48777881 0.12747571 0.14821453, -0.44128653 0.13081588 0.090363607, -0.44287959 0.13370484 0.092346832, -0.4413009 0.13114424 0.090381607, -0.44289455 0.13348813 0.09236522, -0.44293842 0.13328186 0.092419967, -0.44300932 0.13309559 0.092508391, -0.44310391 0.13293824 0.092625812, -0.44321737 0.13281734 0.092767105, -0.48590121 0.13378836 0.14589478, -0.48599431 0.13363145 0.14601062, -0.48778042 0.13581319 0.14823408, -0.44287965 0.13671163 0.09234713, -0.48578921 0.13390975 0.14575531, -0.44130099 0.13970146 0.090382084, -0.44334474 0.13273859 0.092925593, -0.44347963 0.13270575 0.093093678, -0.48606393 0.1334462 0.14609753, -0.48546904 0.12987609 0.145357, -0.44129622 0.13989297 0.090376005, -0.48552987 0.13402489 0.14543246, -0.44354048 0.13771024 0.093169376, -0.48566338 0.13398989 0.14559887, -0.48610708 0.1332413 0.14615105, -0.48612186 0.13302647 0.14616944, -0.48612186 0.13087511 0.14616929, -0.48610517 0.13064677 0.14614879, -0.48605654 0.13043047 0.14608799, -0.48597798 0.13023765 0.14599024, -0.48587397 0.13007858 0.14586093, -0.48575023 0.12996149 0.14570667, -0.48561278 0.12989283 0.14553545, -0.44339553 0.13769595 0.092989042, -0.44325653 0.13762882 0.092816189, -0.44313124 0.13751273 0.092660055, -0.44302574 0.13735338 0.092528746, -0.44294605 0.13715956 0.092429444, -0.44289663 0.13694178 0.092367873, -0.48512283 0.13352567 0.14572428, -0.4431335 0.13721095 0.093461201, -0.48529485 0.1304768 0.14593865, -0.48516425 0.13038397 0.14577578, -0.48523301 0.13041827 0.1458614, -0.485347 0.13055636 0.14600323, -0.48538613 0.13065274 0.14605211, -0.48541063 0.13076094 0.14608254, -0.48541883 0.13087514 0.14609276, -0.48509243 0.13037553 0.14568652, -0.48541895 0.1330265 0.146093, -0.48538992 0.13323626 0.14605691, -0.48535493 0.1333289 0.14601345, -0.48541155 0.13313393 0.1460837, -0.48530847 0.1334074 0.14595564, -0.48518971 0.13350816 0.14580749, -0.48525247 0.13346814 0.14588581, -0.44310308 0.13320528 0.093422994, -0.44297192 0.133261 0.093259797, -0.44303557 0.1332217 0.093339279, -0.44291517 0.13332157 0.093189225, -0.44283238 0.13349335 0.093086317, -0.44280311 0.13370486 0.09304975, -0.44281051 0.13359649 0.093058929, -0.4428679 0.1334002 0.093130335, -0.44280311 0.13671163 0.093049929, -0.44306096 0.13720378 0.0933709, -0.44281152 0.13682669 0.093060359, -0.4428362 0.13693559 0.093091205, -0.44299147 0.13717026 0.093284592, -0.44287619 0.13703254 0.093140885, -0.44292888 0.13711217 0.09320657, -0.44120538 0.14173372 0.088634953, -0.48754588 0.15159151 0.11846833, -0.44119552 0.1417836 0.088517144, -0.48765841 0.15175214 0.11819853, -0.44119278 0.14189368 0.088194564, -0.48781568 0.15186848 0.11793245, -0.44117308 0.14195248 0.087859616, -0.44111457 0.14196156 0.087522253, -0.48600772 0.13855378 0.14289533, -0.48743227 0.13751867 0.14648817, -0.48608658 0.13862328 0.14284076, -0.48614648 0.13869277 0.14276575, -0.48618385 0.13875847 0.14267446, -0.48619652 0.13881649 0.14257179, -0.48556593 0.14873634 0.12206094, -0.45964387 0.14322218 0.10537253, -0.46800873 0.14402661 0.11270748, -0.4593412 0.14287664 0.10573982, -0.4859446 0.14054176 0.13885258, -0.46750417 0.14345053 0.11331974, -0.48542041 0.14187816 0.13561966, -0.44727603 0.14229757 0.09399803, -0.48565319 0.15046123 0.11870481, -0.48565319 0.14777999 0.12406673, -0.44120541 0.1415758 0.088950619, -0.48542032 0.13832949 0.14271592, -0.44677144 0.14172156 0.094610438, -0.48583421 0.15048653 0.11884765, -0.48745683 0.15134844 0.11885907, -0.4859862 0.15048036 0.11902268, -0.48610106 0.15044276 0.11922051, -0.48743236 0.15112869 0.11927216, -0.48617241 0.15037589 0.11943056, -0.48619667 0.15028328 0.11964191, -0.48619667 0.1492112 0.12178524, -0.4861829 0.14915055 0.12189175, -0.48599297 0.14893724 0.12211566, -0.48598614 0.14779912 0.12438418, -0.4860779 0.1490093 0.12206231, -0.4858931 0.14887021 0.12214305, -0.48583421 0.14780539 0.12420942, -0.48610094 0.14776157 0.12458239, -0.48614252 0.14908196 0.12198614, -0.48567292 0.14876656 0.1221147, -0.48578411 0.14881207 0.12214257, -0.48617241 0.14769469 0.12479244, -0.48619655 0.14760211 0.12500347, -0.48619667 0.1467738 0.12665986, -0.47829399 0.14471276 0.12233178, -0.47823361 0.14467211 0.12234877, -0.47835979 0.14474811 0.12233163, -0.47818276 0.14462844 0.1223817, -0.47814432 0.14458458 0.12242831, -0.47812298 0.14447784 0.12261881, -0.4781135 0.14450678 0.12255071, -0.47812089 0.14454316 0.12248589, -0.47814873 0.14445801 0.12268625, -0.4784272 0.14477576 0.12234847, -0.47818908 0.14444837 0.12274827, -0.47849169 0.14479406 0.12238099, -0.48556599 0.14629899 0.12693523, -0.4859446 0.14376782 0.13240154, -0.48567286 0.14632913 0.12698911, -0.4857842 0.1463746 0.12701707, -0.48589304 0.14643265 0.1270173, -0.485993 0.14649977 0.12699018, -0.48607787 0.14657186 0.12693666, -0.48605162 0.14374663 0.13255842, -0.48614243 0.14664434 0.12686063, -0.48613116 0.14370468 0.13272713, -0.4861829 0.14671308 0.12676631, -0.48617998 0.14364363 0.13290139, -0.48619661 0.14356557 0.13307531, -0.46790358 0.1439968 0.11265408, -0.46779406 0.14395244 0.11262591, -0.46768656 0.14389573 0.11262439, -0.46758768 0.14383011 0.11264987, -0.46750304 0.14375946 0.11270083, -0.46743757 0.14368787 0.112774, -0.45930082 0.14288618 0.10567783, -0.4592751 0.14290601 0.10561033, -0.4592655 0.14293495 0.10554241, -0.45927295 0.14297135 0.10547747, -0.45929638 0.14301267 0.10541998, -0.45933494 0.14305656 0.10537328, -0.45938578 0.14310029 0.10534038, -0.45944598 0.14314088 0.1053233, -0.45951176 0.14317624 0.1053233, -0.4595792 0.14320388 0.1053399, -0.46738836 0.14350894 0.11307926, -0.46741328 0.14348021 0.11316319, -0.46745244 0.14346056 0.11324422, -0.46739513 0.14361955 0.11286505, -0.46737841 0.14355871 0.11296891, -0.48550305 0.14188004 0.13570444, -0.48559931 0.14189817 0.13577105, -0.48570383 0.14193179 0.13581569, -0.48581073 0.14197889 0.13583557, -0.48591387 0.14203693 0.13583, -0.48600772 0.14210248 0.13579901, -0.48608682 0.14217207 0.13574471, -0.48605174 0.1405205 0.13900946, -0.48614642 0.14224148 0.13566928, -0.48613128 0.1404786 0.13917838, -0.48618379 0.14230718 0.13557823, -0.4861801 0.1404175 0.13935278, -0.48619661 0.14236514 0.13547568, -0.48619661 0.14033949 0.1395265, -0.44717094 0.14226803 0.093944773, -0.44706133 0.14222355 0.09391661, -0.4469538 0.1421667 0.093915328, -0.44120541 0.14157782 0.088946655, -0.44665551 0.14177991 0.094370052, -0.44668046 0.14175119 0.094453886, -0.44671956 0.14173158 0.094535068, -0.44685486 0.14210108 0.09394066, -0.44677019 0.1420304 0.093991384, -0.44670472 0.14195879 0.094064698, -0.44666231 0.14189056 0.094155744, -0.44664547 0.14182967 0.094259605, -0.48550293 0.13833132 0.14280055, -0.48559925 0.13834956 0.14286746, -0.4857038 0.13838312 0.1429119, -0.48581073 0.13843027 0.14293201, -0.48591396 0.13848819 0.14292623, -0.44688082 0.14241901 0.094571874, -0.46761358 0.14414808 0.11328112, -0.48540369 0.14387719 0.13284381, -0.47764823 0.14455785 0.12319066, -0.48552987 0.14781243 0.12510873, -0.48551777 0.14785892 0.12500323, -0.48548204 0.14789231 0.12489806, -0.48542461 0.1479111 0.12479924, -0.4853487 0.14791431 0.12471174, -0.48525813 0.14790158 0.12464033, -0.48552975 0.14698422 0.126765, -0.47845557 0.14547938 0.12221076, -0.47792795 0.14526282 0.12207983, -0.47810361 0.14535692 0.12207927, -0.47828308 0.14543065 0.12212385, -0.47776732 0.14515415 0.12212507, -0.47763148 0.14503768 0.12221293, -0.47752908 0.1449208 0.12233712, -0.47746608 0.14481042 0.12249057, -0.47744673 0.14471351 0.12266375, -0.47747228 0.14463632 0.1228454, -0.47754064 0.14458317 0.12302469, -0.48549715 0.14384568 0.13300674, -0.48545736 0.14386667 0.13292198, -0.48552975 0.14377616 0.13318057, -0.48552147 0.14381516 0.13309388, -0.48552972 0.14257573 0.13558094, -0.48561451 0.146781 0.12684898, -0.48568425 0.14682274 0.12683998, -0.48569939 0.14657779 0.12693308, -0.48573402 0.14687096 0.12679689, -0.48583856 0.14666131 0.12691496, -0.48593828 0.14675765 0.12682863, -0.48555306 0.14234982 0.13564415, -0.48562351 0.1423768 0.13566597, -0.48557618 0.1421241 0.13570754, -0.48568913 0.14241794 0.13565363, -0.48571715 0.14217792 0.13575082, -0.48573536 0.14246432 0.13561042, -0.4858484 0.14226031 0.13572626, -0.48594096 0.14235291 0.13563986, -0.46768108 0.14408623 0.11306389, -0.46761772 0.14405109 0.11306618, -0.46756718 0.14400899 0.1130967, -0.46774861 0.14402434 0.11284684, -0.46753898 0.1439677 0.11314918, -0.46762177 0.14395414 0.11285149, -0.46752059 0.14386977 0.11291207, -0.46746424 0.14378712 0.11301704, -0.48525819 0.15058279 0.11927868, -0.48548195 0.15057355 0.1195363, -0.48542455 0.15059236 0.11943747, -0.48534873 0.15059552 0.11934997, -0.48551768 0.15054014 0.11964156, -0.48552972 0.15049377 0.11974718, -0.48552972 0.14942177 0.12189068, -0.45925543 0.14378504 0.1050707, -0.45943514 0.14385869 0.10511552, -0.45960757 0.14390746 0.10520233, -0.45907989 0.14369091 0.10507132, -0.45891938 0.14358239 0.10511671, -0.4587836 0.14346591 0.10520445, -0.45868117 0.14334892 0.10532878, -0.45861807 0.14323844 0.105482, -0.45859876 0.14314166 0.10565533, -0.45862427 0.14306433 0.10583709, -0.45869288 0.14301142 0.10601638, -0.45880041 0.14298603 0.10618217, -0.48549703 0.14061956 0.13945772, -0.48545736 0.14064051 0.13937344, -0.48540363 0.14065114 0.13929476, -0.48552972 0.14054994 0.13963176, -0.48552147 0.14058901 0.13954471, -0.48552978 0.13902701 0.14267732, -0.44694838 0.14235725 0.094354585, -0.4468849 0.14232218 0.09435688, -0.44683433 0.14227998 0.094387129, -0.44701585 0.14229545 0.094137594, -0.44680607 0.14223865 0.09443979, -0.44688907 0.14222521 0.094142184, -0.4467878 0.14214081 0.094202921, -0.44673145 0.1420581 0.094307736, -0.485553 0.1388012 0.14274062, -0.48562333 0.13882807 0.14276208, -0.48557621 0.13857536 0.14280392, -0.48568907 0.13886929 0.14274983, -0.48571709 0.13862917 0.14284693, -0.48573527 0.13891557 0.14270674, -0.48584837 0.13871153 0.14282264, -0.48594096 0.13880424 0.14273633, -0.48561463 0.1492185 0.12197472, -0.48568431 0.14926019 0.12196554, -0.48569939 0.14901516 0.12205876, -0.48573399 0.14930858 0.12192239, -0.48583868 0.14909887 0.12204073, -0.48593828 0.14919522 0.12195458, -0.48777178 0.13603774 0.14820336, -0.44127274 0.14022595 0.090303764, -0.48775294 0.1362666 0.14811902, -0.44126332 0.14053981 0.090169564, -0.48772398 0.13649544 0.14798017, -0.48768523 0.13671972 0.14778779, -0.44126353 0.14095117 0.089875564, -0.48761904 0.13700321 0.1474535, -0.44125876 0.14131609 0.089447841, -0.48753163 0.13728121 0.14700435, -0.48773503 0.15166749 0.11858942, -0.48788959 0.15178432 0.11872657, -0.48783055 0.15184477 0.11812823, -0.48797581 0.15173605 0.11957599, -0.48790133 0.1515467 0.11948116, -0.48762271 0.15123507 0.11932553, -0.48778158 0.15137686 0.11939634, -0.48762262 0.13762516 0.14654134, -0.48778167 0.13776682 0.14661215, -0.4879013 0.13793662 0.14669727, -0.48797557 0.13812609 0.14679195, -0.48790076 0.13581325 0.14842413, -0.48797545 0.13581325 0.14863656, -0.48773494 0.13718437 0.14741014, -0.48784795 0.13729694 0.14750539, -0.48795292 0.1374692 0.14765163, -0.4877958 0.13679376 0.14788543, -0.48788342 0.13687624 0.14799415, -0.48782185 0.13655314 0.14808472, -0.487964 0.13699797 0.14815469, -0.48789844 0.13661601 0.14819871, -0.48784086 0.13630576 0.14822809, -0.48796871 0.13670762 0.14836438, -0.48790953 0.13634808 0.14834578, -0.48797217 0.13640918 0.14851509, -0.48767415 0.12606296 0.14674114, -0.48791543 0.12575921 0.14688276, -0.48781219 0.12592247 0.14680661, -0.48797914 0.1255801 0.1469662, -0.48785374 0.12730567 0.14828445, -0.48791698 0.12727252 0.14840101, -0.48797461 0.12722524 0.14856742, -0.48783985 0.12703271 0.14815246, -0.48790896 0.1269756 0.1482638, -0.48797199 0.12689313 0.14842461, -0.48781139 0.12672234 0.14789708, -0.4878926 0.12663773 0.14799963, -0.48796687 0.12651406 0.14814968, -0.48777452 0.12646613 0.14757656, -0.48787114 0.12635925 0.14766859, -0.48796025 0.12619957 0.14780591, -0.48767409 0.1126056 0.11787747, -0.48781213 0.11246508 0.11794294, -0.48791522 0.11230175 0.11801915, -0.48797897 0.11212274 0.11810245, -0.48791096 0.11216672 0.11763923, -0.48790497 0.11207685 0.11725427, -0.48778695 0.11232778 0.11753793, -0.48777288 0.11219136 0.11713071, -0.48766813 0.11242826 0.11746992, -0.4924235 0.15136647 0.13445325, -0.49242327 0.11247043 0.13391058, -0.49242339 0.1254124 0.16166852, -0.49231556 0.11221954 0.13314326, -0.49219796 0.11204308 0.13230322, -0.49229378 0.15167674 0.13353856, -0.49214968 0.15187025 0.13252364, -0.49245694 0.12566395 0.16213332, -0.49247769 0.1259957 0.1625322, -0.47297081 0.11690442 0.073761538, -0.4729709 0.11691268 -0.073747113, -0.47288328 0.11714049 -0.073747352, -0.47288319 0.11713226 0.073761329, -0.47274294 0.1173404 -0.073747113, -0.472743 0.11733213 0.073761538, -0.47255835 0.11750022 -0.073747113, -0.47255841 0.11749205 0.073761329, -0.47384509 0.11650546 0.076583102, -0.47307798 0.11682445 0.074750379, -0.47301984 0.11701889 0.0747758, -0.47292385 0.11719638 0.074807599, -0.47279426 0.11734989 0.074844345, -0.47263595 0.11747308 0.074884489, -0.47337225 0.11670215 0.075709656, -0.47381103 0.11670402 0.076653704, -0.47332349 0.11689827 0.075759217, -0.47323719 0.11707661 0.075821593, -0.47374061 0.11688425 0.076744065, -0.47311741 0.11723013 0.075894371, -0.47363675 0.11703761 0.076850429, -0.47350407 0.11715718 0.076967701, -0.47296885 0.11735204 0.075974062, -0.48865095 0.111141 0.09878017, -0.48860696 0.11134556 0.098833784, -0.48852473 0.11153552 0.098911747, -0.48840842 0.11169632 0.099008575, -0.48826739 0.11181791 0.099116966, -0.49213955 0.11115885 0.10401835, -0.49207801 0.1113703 0.10405932, -0.49197879 0.11155979 0.1041254, -0.49184713 0.11171818 0.10421334, -0.49168941 0.11183725 0.10431845, -0.4915137 0.11191124 0.10443579, -0.49259785 0.11115877 0.10487731, -0.49288017 0.11115874 0.10580944, -0.49280766 0.11137019 0.10582389, -0.49252972 0.11137022 0.10490571, -0.49214229 0.11191119 0.10595618, -0.49222311 0.11191119 0.10677849, -0.49234948 0.11183722 0.10591485, -0.49243444 0.11183724 0.10677849, -0.49190268 0.11191128 0.1051649, -0.4925355 0.1117181 0.10587786, -0.49262401 0.11171798 0.10677849, -0.49209806 0.11183727 0.10508417, -0.49269077 0.11155967 0.10584711, -0.49278244 0.11155969 0.10677849, -0.49227318 0.11171819 0.10501172, -0.49290168 0.11137018 0.10677849, -0.49241969 0.11155987 0.10495125, -0.49297556 0.11115865 0.10677849, -0.49222317 0.11190969 0.13089605, -0.49243453 0.11183579 0.13089605, -0.49262413 0.11171669 0.13089605, -0.49278244 0.11155833 0.13089605, -0.49290147 0.11136863 0.13089626, -0.49297556 0.11115736 0.13089605, -0.49261633 0.11236328 0.1339605, -0.49277773 0.11221944 0.13402756, -0.49246472 0.11211003 0.13299949, -0.4926174 0.11201529 0.133027, -0.49274805 0.11189727 0.13306113, -0.49289933 0.11204635 0.13410814, -0.49287406 0.11172725 0.13311, -0.49297503 0.11185293 0.13419835, -0.49296871 0.11149961 0.13317545, -0.49234763 0.11194499 0.13196142, -0.49252984 0.11185646 0.13197358, -0.49268892 0.11173454 0.13199036, -0.49284431 0.11154766 0.13201599, -0.49296147 0.11128969 0.13205139, -0.49297503 0.12479484 0.16195653, -0.49289942 0.1249883 0.16186632, -0.49277779 0.12516139 0.16178559, -0.49261636 0.12530521 0.16171847, -0.49265382 0.12591214 0.16261996, -0.49280033 0.12580433 0.16273366, -0.4929097 0.12567766 0.16286696, -0.49297768 0.12553786 0.16301416, -0.49285406 0.1253646 0.1623473, -0.49297509 0.13529107 0.16392027, -0.49289957 0.1352911 0.163707, -0.49277797 0.13529117 0.16351591, -0.49261642 0.13529108 0.16335724, -0.49265209 0.13633868 0.16319607, -0.49279919 0.13639456 0.16334234, -0.49290934 0.1364605 0.16351436, -0.49297747 0.13653322 0.16370438, -0.49285349 0.13587092 0.16357075, -0.49297526 0.15197587 0.13475795, -0.49289969 0.15178508 0.13466246, -0.49277803 0.15161426 0.13457699, -0.4926165 0.15147232 0.13450618, -0.49222347 0.15196003 0.13147457, -0.4929758 0.15271232 0.1314746, -0.4923484 0.15192093 0.13253124, -0.49253044 0.15200925 0.13254423, -0.49243471 0.15203388 0.13147457, -0.49268946 0.15213117 0.13256188, -0.49262455 0.15215302 0.13147457, -0.49278271 0.15231143 0.13147457, -0.49284473 0.15231772 0.13258938, -0.49290189 0.15250091 0.13147457, -0.49296203 0.1525753 0.13262685, -0.49277082 0.15207623 0.13328902, -0.49280486 0.15202208 0.13364474, -0.49284169 0.15196106 0.13399334, -0.49222347 0.15196145 0.10733758, -0.49243471 0.15203531 0.10733767, -0.49262443 0.15215442 0.10733758, -0.49278274 0.15231283 0.10733767, -0.49290189 0.15250234 0.10733767, -0.49297586 0.15271376 0.10733767, -0.4924188 0.15231295 0.10550778, -0.49197683 0.15231289 0.104681, -0.4918451 0.15215454 0.10476898, -0.49227247 0.15215452 0.10556822, -0.49213737 0.15271382 0.10457359, -0.49151877 0.15271401 0.10381983, -0.49146643 0.15250255 0.10387222, -0.49207601 0.15250243 0.10461487, -0.49253553 0.15215454 0.10643564, -0.49234971 0.1520353 0.10647248, -0.49209723 0.15203539 0.10564075, -0.49252889 0.15250252 0.10546221, -0.49269089 0.15231276 0.10640453, -0.49259725 0.15271376 0.10543381, -0.49280772 0.15250239 0.10638143, -0.49288025 0.15271381 0.10636722, -0.49151179 0.15196143 0.10499157, -0.49098673 0.15196151 0.10435183, -0.49168754 0.15203539 0.10487436, -0.49113607 0.15203528 0.10420217, -0.49190193 0.15196136 0.1057217, -0.49127012 0.15215449 0.10406826, -0.49138215 0.15231286 0.10395627, -0.49214226 0.15196142 0.10651372, -0.48859665 0.15271261 0.10089828, -0.48855153 0.1524882 0.10096721, -0.48846582 0.15228356 0.10107456, -0.48834553 0.15211853 0.10121213, -0.48820302 0.15200558 0.10136653, -0.47447029 0.14969718 0.086775407, -0.47443518 0.14947788 0.086856946, -0.4743624 0.14928371 0.086971149, -0.47425571 0.14912581 0.087111339, -0.47412118 0.1490128 0.087269887, -0.47373301 0.14951685 0.085850433, -0.47367844 0.1493005 0.08591257, -0.47358149 0.14910761 0.085997328, -0.47344729 0.14894904 0.086100563, -0.47328323 0.14883341 0.086216524, -0.47315541 0.14917752 0.084794775, -0.4730418 0.14898595 0.084844694, -0.47288942 0.1488274 0.084904775, -0.47303692 0.14934607 0.083979145, -0.47297528 0.14933093 0.083195224, -0.47270581 0.14870991 0.084972486, -0.47296324 0.14913239 0.083997712, -0.47289973 0.14911748 0.083195224, -0.4728435 0.14894129 0.084022745, -0.47277805 0.14892659 0.083195314, -0.47268417 0.14878261 0.084052816, -0.47261661 0.14876786 0.083195224, -0.47242364 0.14864963 0.083195224, -0.47249356 0.14866447 0.084086642, -0.47297516 0.1493402 -0.083177403, -0.47289976 0.1491269 -0.083177283, -0.47277817 0.14893593 -0.083177283, -0.47261658 0.14877723 -0.083177403, -0.47242364 0.14865908 -0.083177403, -0.47254178 0.15683861 0.084281638, -0.4728584 0.15683864 0.085325614, -0.47266325 0.15691254 0.085406408, -0.47233447 0.1569126 0.084322914, -0.47328994 0.15637144 0.085147038, -0.47376123 0.1563715 0.086028561, -0.47366214 0.15656109 0.086094752, -0.47391558 0.15691228 0.087281063, -0.47317994 0.15656112 0.085192695, -0.47272769 0.15671949 0.084244803, -0.47303364 0.15671942 0.085253224, -0.47335842 0.15616013 0.085118577, -0.47382277 0.15616016 0.085987434, -0.47288296 0.15656111 0.084213838, -0.47299984 0.15637155 0.084190384, -0.47307238 0.15616021 0.084176019, -0.47319707 0.15691251 0.086405411, -0.47406504 0.15683842 0.087131515, -0.47337291 0.15683857 0.086288169, -0.47419909 0.15671919 0.086997584, -0.47353056 0.15671948 0.086182937, -0.47431108 0.15656097 0.086885437, -0.47439545 0.15637149 0.086801276, -0.47444776 0.15616013 0.086748943, -0.49098656 0.15691119 0.10435213, -0.4911361 0.15683724 0.10420261, -0.49127021 0.15671813 0.1040685, -0.49138221 0.15655978 0.10395657, -0.49146637 0.15637037 0.10387231, -0.49151877 0.15615903 0.10381998, -0.49227247 0.15671811 0.10556851, -0.49184516 0.15671816 0.10476913, -0.49197686 0.1565598 0.10468124, -0.4924188 0.15655982 0.10550798, -0.49151167 0.15691122 0.10499214, -0.49168754 0.1568373 0.1048746, -0.49269089 0.15655982 0.10640489, -0.49290195 0.15637012 0.10733773, -0.49278274 0.15655969 0.10733773, -0.49252877 0.15637024 0.1054623, -0.49280772 0.15637016 0.10638167, -0.49209711 0.15683721 0.10564099, -0.49253556 0.15671813 0.106436, -0.49262455 0.15671815 0.10733773, -0.49190214 0.15691128 0.10572194, -0.49234974 0.1568373 0.10647283, -0.4924348 0.1568373 0.10733773, -0.49214229 0.15691118 0.10651411, -0.49222347 0.15691127 0.10733773, -0.4921374 0.15615891 0.10457374, -0.49207595 0.15637027 0.10461508, -0.49259725 0.15615886 0.10543405, -0.49288043 0.15615886 0.10636725, -0.49297598 0.15615888 0.10733773, -0.49222338 0.15690954 0.13439132, -0.49243483 0.15683563 0.13439132, -0.49262446 0.15671642 0.13439132, -0.49278274 0.15655813 0.13439132, -0.49290177 0.15636851 0.13439138, -0.49297583 0.15615721 0.13439132, -0.49222356 0.15676865 0.13529654, -0.49222338 0.15687414 0.13484927, -0.4924348 0.15680106 0.13483791, -0.49243483 0.1566982 0.13527371, -0.49297586 0.1559225 0.13538532, -0.49297586 0.15613073 0.13473348, -0.49290189 0.15633956 0.13476582, -0.49297586 0.15605183 0.13506742, -0.49290189 0.15611157 0.13547985, -0.49278268 0.15652686 0.13479514, -0.49290204 0.15625323 0.13513176, -0.49278286 0.15628123 0.1355647, -0.49262443 0.1566834 0.13481958, -0.49278271 0.15643378 0.13518937, -0.49262437 0.15642287 0.13563521, -0.49262443 0.15658468 0.13523747, -0.49243489 0.1565294 0.13568874, -0.49222353 0.1565956 0.13572188, -0.49222347 0.14098465 0.16693927, -0.49243471 0.14091848 0.16690634, -0.49262437 0.14081182 0.16685282, -0.49278268 0.14067037 0.1667821, -0.49290183 0.14050071 0.16669728, -0.49297586 0.1403117 0.16660281, -0.49247602 0.14000285 0.16795324, -0.49263874 0.14043927 0.16739796, -0.49265257 0.13993166 0.16785489, -0.49291202 0.13920109 0.16786374, -0.49290901 0.13973221 0.16757967, -0.49297759 0.13961285 0.16741465, -0.49297825 0.13912706 0.16767745, -0.49227706 0.1400506 0.1680191, -0.49225065 0.14059079 0.16752525, -0.49245578 0.14053133 0.16747533, -0.49280596 0.13926813 0.16803201, -0.49279907 0.13984013 0.16772838, -0.49297854 0.13871735 0.16779421, -0.49297175 0.13830863 0.16786282, -0.49266455 0.13932541 0.1681758, -0.49291405 0.138754 0.167989, -0.49288651 0.1383087 0.16808788, -0.49249381 0.13937058 0.16828962, -0.49281034 0.13878727 0.16816534, -0.49274972 0.13830872 0.16828631, -0.4923003 0.13940161 0.16836764, -0.49267229 0.13881594 0.16831683, -0.49256966 0.1383087 0.16844605, -0.49250495 0.13883862 0.1684372, -0.49235651 0.13830867 0.16855846, -0.49231496 0.1388545 0.16852157, -0.49297658 0.14001717 0.16704307, -0.49290535 0.14017604 0.16717659, -0.49279085 0.14031884 0.16729663, -0.49235639 0.12475902 0.16855757, -0.49256945 0.12475906 0.16844536, -0.49274972 0.12475911 0.16828547, -0.49288633 0.12475906 0.16808729, -0.49297169 0.12475914 0.16786195, -0.49290872 0.12325636 0.16751884, -0.49297786 0.12377271 0.16760252, -0.49297735 0.12338279 0.16735883, -0.49291134 0.12368312 0.16778277, -0.49248937 0.12347873 0.16819368, -0.49250248 0.12406838 0.16840239, -0.49267051 0.12409793 0.16828386, -0.49266154 0.12353306 0.16808461, -0.49279839 0.12314239 0.16766356, -0.49280414 0.12360212 0.16794537, -0.49229446 0.12344153 0.16826828, -0.49231157 0.12404774 0.16848533, -0.49297658 0.12303971 0.16702722, -0.49265131 0.12304567 0.16778611, -0.49290559 0.12287991 0.1671593, -0.49247441 0.12297048 0.16788153, -0.4929761 0.12286802 0.16679372, -0.49297562 0.12273104 0.16654707, -0.49279132 0.12273614 0.16727792, -0.49227485 0.12292035 0.16794486, -0.49290356 0.12269078 0.166905, -0.49290177 0.12253948 0.16663645, -0.49263951 0.12261496 0.16737805, -0.49278691 0.12253161 0.16700505, -0.4927825 0.12236756 0.16671653, -0.492457 0.12252207 0.16745467, -0.49297839 0.12422654 0.16776656, -0.49291357 0.12417872 0.1679595, -0.49263182 0.12239797 0.16708918, -0.49262416 0.12222406 0.16678329, -0.49280933 0.12413521 0.16813384, -0.4922522 0.12246169 0.16750418, -0.49244559 0.12229665 0.16715299, -0.4924345 0.12211618 0.16683386, -0.49222335 0.12204915 0.16686521, -0.4922376 0.12223227 0.16719328, -0.49222305 0.10646537 0.13344066, -0.49243447 0.10653245 0.13340934, -0.49262407 0.1066405 0.13335903, -0.49278253 0.106784 0.13329206, -0.49290159 0.10695569 0.13321204, -0.4929755 0.10714734 0.13312276, -0.47499064 0.089220896 0.096457168, -0.4922004 0.10642858 0.13336472, -0.47518116 0.089250728 0.096354559, -0.4923909 0.10645841 0.13326184, -0.47535285 0.089322969 0.096240833, -0.4925628 0.10653067 0.13314833, -0.49283198 0.10679348 0.13302873, -0.49292448 0.10696618 0.13302858, -0.49298134 0.10715394 0.13302858, -0.49257055 0.10658039 0.13331933, -0.49283198 0.10679491 0.10677828, -0.49292448 0.10696779 0.10677837, -0.49298146 0.10715538 0.10677837, -0.49213591 0.10611074 0.10439895, -0.49219182 0.10628158 0.10424732, -0.49289295 0.10707825 0.10584877, -0.49284157 0.10689002 0.1058961, -0.49275324 0.10671738 0.10594784, -0.49262777 0.1068473 0.10494374, -0.49220017 0.10647435 0.10411368, -0.4925929 0.10665703 0.10503696, -0.49251667 0.10648468 0.10513996, -0.47381631 0.087792918 0.07692869, -0.47387221 0.087963745 0.076777592, -0.47388056 0.088156566 0.076643392, -0.47329384 0.087301552 0.075835899, -0.47310486 0.087078586 0.075449124, -0.47326055 0.087236345 0.075875506, -0.47334504 0.08745265 0.075755075, -0.4731968 0.087294653 0.07535319, -0.47314012 0.087144062 0.075417474, -0.47343031 0.087378263 0.07642217, -0.47336689 0.087614313 0.075681642, -0.4732255 0.087455496 0.075294331, -0.47348332 0.087462291 0.076352105, -0.47351363 0.08752723 0.076303318, -0.47355703 0.087678671 0.07620357, -0.47356918 0.087841749 0.076114014, -0.47307041 0.087072328 0.075182244, -0.47306839 0.087041616 0.075330332, -0.47304592 0.086992562 0.075493768, -0.47298118 0.08691892 0.075523481, -0.47310418 0.087107003 0.075301096, -0.47312948 0.087222919 0.075126931, -0.47311774 0.087210417 0.075083092, -0.47316208 0.087257683 0.075241402, -0.47316137 0.08738327 0.075076416, -0.47314599 0.087366223 0.0750186, -0.47319248 0.087418258 0.075186446, -0.47320399 0.087151155 0.07593213, -0.47295466 0.086871341 0.062579408, -0.47295466 0.086870953 0.07375975, -0.47298899 0.087019563 0.062627748, -0.4729889 0.087018788 0.07375975, -0.45719719 0.068131223 0.0095044225, -0.45719728 0.068132311 -0.0094956309, -0.45698705 0.068058148 0.0095045716, -0.45698693 0.068059146 -0.0094955713, -0.45679799 0.067941308 -0.0094956309, -0.45679796 0.06794022 0.0095044225, -0.4566398 0.067784578 -0.0094956309, -0.45663998 0.067783579 0.0095044225, -0.45652035 0.067596897 -0.0094955713, -0.45652035 0.06759584 0.0095044225, -0.45647994 0.067514122 -0.0096957535, -0.45649806 0.067551434 -0.0096591562, -0.45648986 0.06753464 -0.0096797198, -0.45650473 0.067565024 -0.0096355528, -0.45651713 0.067590192 -0.0095617324, -0.45651951 0.067595199 -0.0095290095, -0.45647982 0.067512885 0.0097044557, -0.45648971 0.067533344 0.0096884519, -0.45649806 0.067550212 0.0096680075, -0.45650467 0.067563772 0.0096441656, -0.45651713 0.067589179 0.0095705837, -0.45651951 0.067594066 0.0095378011, -0.44310448 0.040206537 -0.0093310028, -0.44296294 0.039917424 -0.009697184, -0.4431946 0.04039064 -0.0089442581, -0.4432362 0.040475368 -0.0086152703, -0.44324979 0.040503114 -0.008282885, -0.44324967 0.040502116 0.0082886368, -0.44323608 0.040474325 0.0086208433, -0.44319466 0.040389672 0.0089500099, -0.44310459 0.040205613 0.0093364865, -0.44296286 0.039916307 0.0097028464, -0.44235179 0.039943039 -0.0082830042, -0.44235179 0.039942071 0.0082886368, -0.44257292 0.039966747 0.0082886368, -0.44257292 0.039967716 -0.0082830042, -0.44278321 0.040039927 0.0082886368, -0.44278318 0.040040925 -0.008282885, -0.44297215 0.040157706 0.0082886368, -0.44297212 0.040158689 -0.008282885, -0.44313022 0.040314466 0.0082886368, -0.44313022 0.04031536 -0.0082830936, -0.4110001 0.039943203 -0.0082830936, -0.4110001 0.039942279 0.0082886368, -0.44206473 0.039649159 0.0089956671, -0.44215056 0.039736718 0.0088955313, -0.4110001 0.039649263 0.0089956671, -0.4110001 0.039773688 0.0088440627, -0.44222388 0.039811462 0.0087826103, -0.4110001 0.039866075 0.0086712986, -0.44229463 0.039883763 0.008624807, -0.4110001 0.039922968 0.0084834546, -0.4423376 0.039927617 0.0084575564, -0.44137219 0.03823483 0.010409907, -0.4110001 0.038235068 0.010409817, -0.45688227 0.067987517 0.0096884519, -0.45672324 0.067847043 0.0097721964, -0.45687059 0.067948356 0.0098415762, -0.45673469 0.067877561 0.0096513182, -0.45661166 0.067742854 0.0096113235, -0.45699349 0.067783743 0.010295019, -0.45684206 0.067846224 0.010057107, -0.45682052 0.06776005 0.010172352, -0.45701221 0.067891389 0.010159716, -0.45702639 0.067963719 0.010035381, -0.45685768 0.067903519 0.0099529177, -0.45671073 0.06781286 0.009858951, -0.45660153 0.067720354 0.00969778, -0.45669547 0.067769945 0.0099387914, -0.45667326 0.067704991 0.010028705, -0.45659053 0.067695931 0.0097576231, -0.45718351 0.067775279 0.010390744, -0.45657787 0.067666814 0.0098103136, -0.45655835 0.067621633 0.0098707527, -0.45722845 0.068115607 0.0097492784, -0.45721915 0.068058044 0.0099536031, -0.45704904 0.06806764 0.0097215325, -0.45720914 0.067991212 0.010102734, -0.45703819 0.06801942 0.0099028498, -0.45719758 0.06790401 0.010242417, -0.44248268 0.039890677 0.0086600929, -0.44258019 0.039809451 0.0089347512, -0.44266257 0.039931282 0.0087062269, -0.44270286 0.039990976 0.0084990412, -0.44286796 0.040071338 0.0085267872, -0.44282863 0.04000403 0.0087611824, -0.44252428 0.039942443 0.0084757656, -0.44226083 0.03961648 0.0090590864, -0.44301531 0.040067971 0.0092248172, -0.44288227 0.039801359 0.0095484108, -0.44276604 0.039710537 0.0094006211, -0.44289491 0.039953724 0.0091183335, -0.44261929 0.039647862 0.0092661232, -0.44309825 0.0402347 0.0088906437, -0.44274804 0.039866373 0.0090204626, -0.44297549 0.040106282 0.0088232905, -0.44244859 0.039616108 0.00915052, -0.44313881 0.040315822 0.0085914284, -0.44239756 0.039784789 0.0088646263, -0.44301483 0.040180564 0.008557722, -0.45722094 0.067598119 0.010545358, -0.45720661 0.067300603 0.010663614, -0.45719984 0.067166358 0.010683909, -0.45704606 0.067638949 0.010465756, -0.45701936 0.067378432 0.01058732, -0.4570072 0.06726025 0.010614052, -0.45686924 0.06765838 0.010342374, -0.45683292 0.067448169 0.01045455, -0.45681646 0.067352742 0.010483041, -0.45671853 0.067650899 0.010190234, -0.45664391 0.067634642 0.01008974, -0.45668018 0.067496702 0.010282025, -0.45666298 0.067426845 0.010307506, -0.45660821 0.067515075 0.010165051, -0.45659211 0.06746085 0.010186329, -0.45653585 0.067487627 0.010049298, -0.4565455 0.0675883 0.0099098533, -0.45650092 0.067546397 0.0097879916, -0.45652202 0.067526907 0.0099520236, -0.45650008 0.067504272 0.0099124759, -0.45649007 0.067522123 0.0098053366, -0.45648503 0.067510948 0.0098102242, -0.44247845 0.039117232 0.010000661, -0.44189912 0.038504958 0.010258004, -0.44162044 0.038323954 0.010349229, -0.44149169 0.038268149 0.010383442, -0.44366106 0.039574206 0.01067768, -0.44347128 0.03966713 0.010603771, -0.44330093 0.039750651 0.010484502, -0.44315881 0.039820358 0.010326371, -0.44305179 0.039872721 0.01013656, -0.44298539 0.03990528 0.0099254698, -0.44176084 0.037705511 0.01069437, -0.44137213 0.037722796 0.010683522, -0.44217703 0.037875131 0.010692254, -0.44173202 0.037823021 0.010670885, -0.44137213 0.037910357 0.010626629, -0.4421173 0.037996843 0.01066269, -0.44237846 0.038443878 0.010554686, -0.44196042 0.038316518 0.010474697, -0.44203466 0.038165301 0.010586992, -0.44226995 0.038588837 0.010412261, -0.4419162 0.038406953 0.0103793, -0.44220838 0.038670823 0.010293141, -0.44169173 0.037987053 0.010610834, -0.44165462 0.038137972 0.010521665, -0.44137216 0.03808327 0.010534242, -0.4416315 0.038231507 0.010444626, -0.44304663 0.038598239 0.010685697, -0.44291779 0.038715482 0.010636315, -0.4427447 0.038873076 0.010508373, -0.44259533 0.038154557 0.010689393, -0.4426032 0.039002419 0.010323003, -0.44250375 0.038276672 0.010651961, -0.44253036 0.039069176 0.010171369, -0.4110001 0.038083524 0.010534242, -0.4110001 0.037910521 0.01062654, -0.4110001 0.03772299 0.010683522, -0.41250256 0.035863116 0.13366432, -0.41249233 0.036049068 0.1337872, -0.41248026 0.036257058 0.13386576, -0.41248029 0.036379471 0.1338888, -0.47170812 0.094992846 0.10967825, -0.47164243 0.09502162 0.10978766, -0.47154894 0.09503983 0.109897, -0.47142896 0.095046848 0.1100042, -0.47123221 0.095038205 0.11013876, -0.47105509 0.095018089 0.1102346, -0.47432449 0.088384897 0.09536849, -0.47435418 0.088417664 0.095370844, -0.47430167 0.088361219 0.095372722, -0.47444668 0.088535249 0.095430091, -0.47189817 0.095088065 0.1095358, -0.47451594 0.088639647 0.095529988, -0.47439387 0.088465273 0.095386252, -0.47207502 0.095192119 0.10951875, -0.47464314 0.088873193 0.09585543, -0.47226831 0.095262006 0.10952078, -0.47195727 0.095216036 0.10966443, -0.47182557 0.095114499 0.10966407, -0.4717693 0.095322281 0.10993837, -0.47165114 0.095190763 0.10990702, -0.47210082 0.095296979 0.10967849, -0.47090957 0.095215157 0.11033057, -0.47190019 0.095432267 0.10998984, -0.47225377 0.095355853 0.10970639, -0.4720411 0.09551847 0.11006032, -0.47130692 0.095229998 0.11015864, -0.47097439 0.095430806 0.11039053, -0.47139975 0.095404536 0.11021303, -0.47152039 0.095214814 0.11002098, -0.4711428 0.095779419 0.11064468, -0.47150669 0.095555723 0.11029907, -0.47105366 0.095622391 0.11049719, -0.47162884 0.09536396 0.11006422, -0.47162411 0.095678285 0.11041413, -0.47175065 0.095490858 0.11013196, -0.47188273 0.095592201 0.11022232, -0.41099992 0.01216121 0.010682091, -0.42499998 0.012161136 0.010682091, -0.41099992 0.011973634 0.010625198, -0.42499998 0.011973545 0.010625198, -0.41099992 0.011800706 0.010532722, -0.42499998 0.011800691 0.010532811, -0.41099992 0.011649266 0.010408387, -0.42499986 0.011649042 0.010408387, -0.42499998 0.010235086 0.0089940876, -0.41099992 0.010235026 0.0089940876, -0.42677739 0.0095277727 0.010675922, -0.42656615 0.0095277727 0.010601982, -0.42637649 0.0095277727 0.010482803, -0.42621818 0.0095277727 0.010324493, -0.42609894 0.0095278621 0.010134831, -0.42602506 0.0095279515 0.0099235922, -0.42597488 0.0091646314 0.0082868487, -0.42597485 0.0091656148 -0.0082847625, -0.42590094 0.0093759149 0.0082868487, -0.42590091 0.0093769431 -0.0082847625, -0.42578176 0.0095656216 0.0082868487, -0.42578176 0.009566471 -0.0082847625, -0.42562345 0.0097238868 0.0082868487, -0.42562345 0.0097249001 -0.0082847625, -0.42543387 0.0098441541 -0.0082845837, -0.4254339 0.0098431855 0.0082868487, -0.42522243 0.0099179894 -0.0082847625, -0.42522243 0.0099170655 0.0082868487, -0.42499998 0.0099431425 -0.0082846731, -0.42499995 0.009942174 0.0082868487, -0.41099989 0.009943217 -0.0082846731, -0.41099992 0.0099422634 0.0082868487, -0.41099992 0.010110676 0.0088424534, -0.42499995 0.010110676 0.0088424534, -0.41099992 0.010018304 0.0086696297, -0.42499998 0.010018215 0.0086696297, -0.41099992 0.0099614412 0.0084819943, -0.42499998 0.0099613518 0.0084819943, -0.42516902 0.011806875 0.010547385, -0.42532757 0.011745632 0.010537699, -0.42519668 0.01195018 0.010623321, -0.42538109 0.011885136 0.010618344, -0.42599964 0.011792839 0.010691419, -0.42575768 0.0119932 0.010692701, -0.4255996 0.011747345 0.010607824, -0.42543891 0.012035489 0.010672554, -0.42569172 0.011890575 0.010669008, -0.425262 0.011574909 0.010383591, -0.42529383 0.011657879 0.010467872, -0.42513493 0.011629656 0.01040186, -0.42515174 0.011716172 0.0104817, -0.42591086 0.011696741 0.01066412, -0.42551497 0.011615872 0.010516867, -0.42506674 0.011644349 0.010406807, -0.42578766 0.01156339 0.010593399, -0.42628789 0.011438593 0.010689244, -0.42554712 0.011303365 0.010293141, -0.42546263 0.011534438 0.010438696, -0.42541394 0.011458799 0.010344878, -0.42616925 0.011354551 0.01065518, -0.4256759 0.011442617 0.010488823, -0.42560822 0.011369497 0.010399446, -0.42600587 0.011239052 0.010567173, -0.42657927 0.010845542 0.01068534, -0.4258621 0.011137411 0.01043795, -0.42642331 0.010783762 0.010639772, -0.42587224 0.010565221 0.010046765, -0.42577863 0.011078402 0.010328874, -0.42570713 0.011027813 0.01020135, -0.42621258 0.010700136 0.010521337, -0.42603675 0.010630459 0.010349765, -0.42524746 0.012213469 0.010694131, -0.42594305 0.010593295 0.010207996, -0.42522636 0.012103841 0.010674223, -0.42548016 0.012142941 0.010693744, -0.42562345 0.0097473711 0.008524552, -0.4254339 0.0099268556 0.0087076575, -0.42543387 0.0098643005 0.0085013956, -0.42562345 0.0098166913 0.0087529272, -0.42597488 0.0094641745 0.0092742592, -0.42597488 0.0096851885 0.0095437616, -0.42590094 0.0096399635 0.0091570467, -0.42590094 0.0094952732 0.0088862032, -0.42578179 0.0097976029 0.0090515763, -0.42578179 0.0096703917 0.0088135153, -0.42578176 0.0095920861 0.0085554272, -0.42597488 0.0092999339 0.0089670271, -0.42590094 0.0094060451 0.0085922629, -0.42597488 0.0091988146 0.0086336285, -0.42522243 0.010089844 0.0088562816, -0.42522243 0.010217309 0.0090116113, -0.4254339 0.010165021 0.0090640634, -0.4254339 0.010028377 0.0088975579, -0.42562345 0.010080814 0.009148255, -0.42522243 0.0099951327 0.0086791664, -0.42562345 0.0099292696 0.0089637786, -0.42578176 0.009968847 0.0092601925, -0.42522243 0.0099367797 0.0084868819, -0.42590094 0.0098347217 0.009394154, -0.47506616 0.13489623 0.17067479, -0.47492412 0.1347878 0.17064349, -0.47486892 0.12572047 0.17062472, -0.47503689 0.12572049 0.17066939, -0.41246077 0.026105791 0.11015604, -0.41244885 0.026251405 0.11031948, -0.41245425 0.026348829 0.11048992, -0.41246566 0.026391581 0.11060269, -0.41249183 -0.026188359 0.089299962, -0.41248503 -0.026041582 0.089412943, -0.46196565 0.075602189 0.089728579, -0.46192095 0.075721577 0.089908943, -0.46191123 0.0758138 0.090109333, -0.46263155 0.076276347 0.089378461, -0.46305186 0.076925278 0.089241996, -0.46310124 0.077022254 0.089345679, -0.46263427 0.076552287 0.089776382, -0.4626123 0.07647416 0.089635357, -0.46261117 0.076381907 0.089502081, -0.47295418 0.086886466 0.075533226, -0.47291449 0.086827353 0.075463012, -0.47288257 0.086762279 0.075394168, -0.47285885 0.086691797 0.075327352, -0.47288108 0.086731434 0.075328246, -0.47290301 0.086770862 0.075334474, -0.47292009 0.086801857 0.075344101, -0.47293192 0.08682394 0.075355157, -0.4729428 0.086844176 0.075369701, -0.47295144 0.086861312 0.075389132, -0.47295794 0.086875543 0.075414881, -0.47296062 0.086883962 0.0754437, -0.47296044 0.086887479 0.075473621, -0.41298196 -0.035549417 0.032189682, -0.41299516 -0.035556585 0.032121047, -0.41298199 -0.035548285 0.012564763, -0.41299519 -0.035555586 0.012633458, -0.41298196 -0.035551146 0.062322274, -0.41299519 -0.035558388 0.062390789, -0.41251266 0.026462376 0.12007536, -0.41251275 0.026503876 0.12020911, -0.41673145 0.037344426 0.12802996, -0.41673324 0.037358657 0.12806951, -0.41885921 0.034530431 0.12006868, -0.41973856 0.035780296 0.11999144, -0.41871241 0.034714788 0.12018515, -0.4187589 0.034666523 0.12017633, -0.41977039 0.035754666 0.11997594, -0.41979972 0.035730943 0.11995511, -0.41880038 0.03461796 0.12015332, -0.41983441 0.035702452 0.11991908, -0.41883439 0.034571692 0.12011649, -0.41986328 0.035678297 0.11987473, -0.41987523 0.035668269 0.11984943, -0.42025369 0.03649804 0.12003918, -0.42028669 0.036476776 0.12002738, -0.42031744 0.036457673 0.12001102, -0.42034608 0.03644073 0.11999036, -0.42038077 0.036421388 0.11995615, -0.42041093 0.036406279 0.11991502, -0.42042407 0.036400393 0.11989202, -0.42070156 0.037141949 0.12018634, -0.42073348 0.037126496 0.12017371, -0.42076358 0.037113458 0.1201575, -0.42079169 0.037102744 0.12013806, -0.42082635 0.037091628 0.12010695, -0.42085764 0.037084565 0.12007, -0.42087168 0.037082613 0.12004937, -0.42105994 0.037747666 0.120434, -0.42109114 0.03773807 0.12042217, -0.42112058 0.037730798 0.12040736, -0.42114833 0.037725702 0.12038983, -0.42118308 0.037722141 0.12036277, -0.42121497 0.037722453 0.12033091, -0.42122981 0.037724152 0.12031309, -0.42144105 0.038638115 0.12105121, -0.42147169 0.038636953 0.12104322, -0.4215005 0.038637996 0.12103309, -0.42152795 0.038641125 0.12102117, -0.42156261 0.038648546 0.12100257, -0.42159519 0.038659662 0.1209804, -0.4216108 0.0386668 0.12096815, -0.42152837 0.039039299 0.12147631, -0.42155883 0.039041609 0.12147142, -0.42158759 0.039046362 0.1214651, -0.42161486 0.039053187 0.121457, -0.42164955 0.039065436 0.121444, -0.42168221 0.039081603 0.12142749, -0.42169783 0.039091259 0.12141849, -0.42151579 0.039633542 0.12243848, -0.42154309 0.039645463 0.12243913, -0.42157778 0.039665192 0.12243797, -0.42161044 0.039689392 0.12243439, -0.42162594 0.039703339 0.12243177, -0.42136154 0.039853916 0.12306727, -0.42139634 0.03987658 0.12307398, -0.42142865 0.039904371 0.12307812, -0.42144385 0.039920315 0.12307931, -0.42108554 0.039957955 0.12371589, -0.42112026 0.039982513 0.12373032, -0.42115209 0.04001303 0.12374316, -0.42116675 0.040030628 0.12374844, -0.42063871 0.039927095 0.12430383, -0.42067084 0.039933145 0.12432347, -0.420701 0.039943606 0.12434219, -0.42072925 0.039958015 0.12436007, -0.42076394 0.039983407 0.12438248, -0.42079493 0.040015727 0.12440334, -0.42080894 0.040034443 0.124413, -0.41995603 0.039745837 0.12523089, -0.41998968 0.039747238 0.12525795, -0.42002088 0.039754361 0.1252849, -0.42004988 0.039766818 0.12531175, -0.42008469 0.039791435 0.12534688, -0.42011413 0.039824799 0.12538053, -0.42012677 0.039844766 0.12539683, -0.41890988 0.039220423 0.12629269, -0.41894624 0.039212734 0.12632667, -0.41897967 0.039212525 0.12636246, -0.41901013 0.039219469 0.12639989, -0.41904467 0.039239541 0.12645088, -0.4190715 0.039271355 0.1265014, -0.41908124 0.039291173 0.12652586, -0.41800913 0.038531244 0.12710918, -0.41804096 0.038531184 0.12715469, -0.41807529 0.038544223 0.12721853, -0.41809878 0.038571656 0.12728287, -0.41810575 0.038590223 0.12731384, -0.41731021 0.037918717 0.12758698, -0.41734427 0.037924767 0.12765975, -0.4173643 0.037947044 0.12773402, -0.41736856 0.037963629 0.12776969, -0.41297036 0.036359191 0.12572117, -0.41293457 0.03593564 0.1257156, -0.41297036 0.035935611 0.12577243, -0.41299254 0.037755623 0.1237819, -0.41299257 0.037649825 0.12335275, -0.41299254 0.036787763 0.12237944, -0.41293469 0.036345482 0.12566589, -0.41297036 0.037590578 0.12337531, -0.41299269 0.036374584 0.12222271, -0.41297051 0.036359429 0.12228422, -0.41297039 0.03675808 0.12556981, -0.41293457 0.036731631 0.12551941, -0.41297036 0.037692621 0.12378933, -0.41297036 0.037692621 0.12421618, -0.41293457 0.037636146 0.12379624, -0.41299251 0.036374271 0.12578286, -0.41299251 0.035935521 0.125836, -0.41297051 0.036758289 0.12243555, -0.41299254 0.03678748 0.12562592, -0.41293457 0.037636191 0.12420918, -0.41297051 0.037109435 0.12267803, -0.41293466 0.036731929 0.12248589, -0.41293457 0.037071675 0.12272047, -0.41293469 0.037537396 0.12461029, -0.41288719 0.037589028 0.12420346, -0.41293466 0.037345529 0.12302957, -0.41288719 0.037040234 0.12275614, -0.41288719 0.037306428 0.12305664, -0.41276687 0.036320537 0.1224419, -0.41276687 0.035935774 0.12239493, -0.41270012 0.035935849 0.12240268, -0.41288719 0.037492931 0.12459348, -0.41288716 0.037306383 0.12494873, -0.41283032 0.037459552 0.12458061, -0.41269997 0.036318719 0.12244929, -0.41288719 0.037493035 0.12341227, -0.41283041 0.037277117 0.12307705, -0.41283026 0.037459612 0.12342475, -0.41283029 0.037276909 0.12492858, -0.41283035 0.036325932 0.1224203, -0.41283032 0.035935804 0.12237285, -0.41283029 0.037016317 0.12522255, -0.4127669 0.0372587 0.12491597, -0.41283029 0.037553564 0.12380634, -0.4127669 0.037438899 0.12343262, -0.41276687 0.037531585 0.12380908, -0.4127669 0.03700158 0.12520601, -0.41276687 0.036682606 0.12542616, -0.4127 0.036996558 0.12520026, -0.4127669 0.036682889 0.12257935, -0.41269997 0.036679327 0.12258603, -0.41269997 0.036679119 0.12541927, -0.41276687 0.037531465 0.12419654, -0.41270012 0.037524119 0.12380992, -0.41270012 0.037524119 0.12419571, -0.41288719 0.036334395 0.12238558, -0.41299254 0.037151545 0.12263061, -0.41299254 0.037755549 0.1242236, -0.41288719 0.035935864 0.12233712, -0.41297051 0.037590608 0.12463032, -0.41297036 0.037392318 0.1229973, -0.41283026 0.036693126 0.1225598, -0.41293457 0.037345454 0.12497579, -0.41293469 0.037537396 0.12339522, -0.41276687 0.037001848 0.12279953, -0.41270015 0.036996797 0.12280501, -0.41288719 0.037589103 0.12380184, -0.41288719 0.03704004 0.12524937, -0.41293466 0.036345735 0.12233938, -0.41293469 0.035935864 0.12228964, -0.41283032 0.036692932 0.12544574, -0.41283029 0.037553564 0.12419917, -0.41288719 0.036709845 0.12252803, -0.41276687 0.036320269 0.12556361, -0.41269997 0.035935521 0.12560259, -0.41276687 0.035935521 0.12561034, -0.41283029 0.037016526 0.12278284, -0.41270012 0.036318511 0.1255561, -0.41276687 0.03743878 0.12457274, -0.41269997 0.037431702 0.12457, -0.41299254 0.037649885 0.12465273, -0.41299269 0.037444606 0.1229613, -0.41276702 0.037258804 0.12308954, -0.41270012 0.037252575 0.12309374, -0.41297036 0.037392199 0.12500812, -0.41297048 0.035935819 0.12223278, -0.4129346 0.037071481 0.1252849, -0.41288719 0.036709547 0.12547742, -0.41283029 0.036325574 0.12558518, -0.41283026 0.035935491 0.12563251, -0.41299257 0.037444487 0.125044, -0.41270012 0.037252516 0.12491162, -0.41297036 0.037109137 0.12532733, -0.41270012 0.037431777 0.12343527, -0.41299254 0.035935774 0.12216936, -0.41288719 0.036334187 0.12561975, -0.41288719 0.035935521 0.12566806, -0.41299254 0.037151247 0.12537493, -0.41100007 0.035935611 0.12560247, -0.41100019 0.03631866 0.1255561, -0.4110001 0.036679164 0.12541927, -0.4110001 0.036996618 0.12520026, -0.41100019 0.037252635 0.12491144, -0.4110001 0.037431777 0.12457, -0.41100025 0.037524119 0.12419556, -0.4110001 0.037524164 0.12380992, -0.4110001 0.037431806 0.12343527, -0.41100007 0.037252575 0.12309374, -0.4110001 0.036996812 0.12280501, -0.41100013 0.036679342 0.12258579, -0.41100013 0.036318719 0.12244906, -0.4110001 0.035935864 0.12240268, -0.41270009 0.033935592 0.12560247, -0.41100007 0.033935621 0.12560247, -0.41100007 0.033935741 0.12240256, -0.41270012 0.03355287 0.12244906, -0.41100004 0.0335529 0.12244894, -0.41269997 0.033935726 0.12240268, -0.41269997 0.033192217 0.12258579, -0.41100007 0.033192262 0.12258579, -0.41270009 0.032874838 0.12280478, -0.41100007 0.032874823 0.12280466, -0.41270009 0.032618925 0.12309347, -0.41100004 0.03261897 0.12309347, -0.41269997 0.032439739 0.12343504, -0.41100004 0.032439709 0.12343504, -0.41269997 0.032347456 0.12380956, -0.41100004 0.032347396 0.12380971, -0.41269997 0.032347456 0.12419535, -0.41100004 0.032347322 0.12419544, -0.41270009 0.032439694 0.12456979, -0.41100004 0.032439709 0.12456988, -0.41269997 0.032618955 0.12491129, -0.41100004 0.032618925 0.12491132, -0.41270012 0.032874599 0.12520014, -0.41100007 0.032874599 0.12520005, -0.41270009 0.033192009 0.12541924, -0.4110001 0.033192083 0.12541924, -0.41269997 0.033552676 0.12555598, -0.4110001 0.033552691 0.12555598, -0.41276696 0.033935875 0.12239493, -0.41283026 0.03393577 0.12237276, -0.41288716 0.03393583 0.12233712, -0.41293457 0.03393577 0.12228955, -0.41297033 0.033935726 0.12223266, -0.41299251 0.033935815 0.12216927, -0.41276684 0.033935606 0.1256101, -0.41283026 0.033935577 0.1256323, -0.41288716 0.033935651 0.12566791, -0.41293466 0.033935562 0.12571524, -0.41297048 0.033935562 0.12577243, -0.41299251 0.033935651 0.12583579, -0.41297045 0.033512309 0.12228419, -0.41293454 0.033525839 0.12233938, -0.41299251 0.033083633 0.12562563, -0.41297033 0.033113226 0.12243547, -0.41293457 0.03313975 0.12248568, -0.41299251 0.032115921 0.12422334, -0.41299251 0.032221571 0.1246524, -0.41297036 0.033512071 0.12572084, -0.41297048 0.033113077 0.1255696, -0.41297033 0.032280877 0.12462999, -0.41299251 0.033496931 0.12578247, -0.41297033 0.032178819 0.12421586, -0.41299251 0.033497065 0.12222256, -0.41299251 0.033083826 0.12237929, -0.41297033 0.032178819 0.12378906, -0.41293454 0.032235205 0.12420894, -0.41293457 0.03223528 0.12379597, -0.41293469 0.032334149 0.12339498, -0.41288713 0.032282412 0.1238016, -0.41297045 0.032762006 0.12532718, -0.41293469 0.033139586 0.12551926, -0.41293463 0.032799676 0.12528454, -0.41293469 0.032526016 0.12497558, -0.41288716 0.032831237 0.12524916, -0.41288725 0.032565132 0.12494852, -0.41288713 0.032378599 0.12341188, -0.41288725 0.032565147 0.12305655, -0.41283026 0.032411933 0.12342454, -0.41276684 0.033550873 0.12556328, -0.41288713 0.032378525 0.124593, -0.41283026 0.032594487 0.12492831, -0.41283026 0.032411933 0.12458037, -0.41283026 0.032594487 0.12307678, -0.41283026 0.032855079 0.1227826, -0.41276684 0.032612756 0.12308918, -0.41283026 0.033545583 0.12558486, -0.41283026 0.032317922 0.12419881, -0.41276684 0.03243272 0.12457241, -0.41276684 0.032869861 0.12279929, -0.41276687 0.032339886 0.12419628, -0.41276684 0.033188745 0.1225792, -0.41276687 0.032339886 0.12380876, -0.41276684 0.033188567 0.12542595, -0.41299251 0.032115921 0.12378143, -0.41299251 0.032719955 0.12537454, -0.41288713 0.033537045 0.12561966, -0.41297045 0.032280952 0.12337483, -0.41297033 0.032479063 0.12500785, -0.41283026 0.033178225 0.12544535, -0.41293469 0.032526031 0.12302949, -0.41293457 0.032334104 0.12460984, -0.41276687 0.032869592 0.12520553, -0.41288713 0.032282412 0.12420307, -0.41288716 0.032831445 0.12275593, -0.41293469 0.033525735 0.12566577, -0.41283026 0.033178419 0.12255935, -0.41288713 0.033161581 0.1254773, -0.41283026 0.032317922 0.1238059, -0.41276684 0.033551112 0.12244178, -0.41283026 0.0328549 0.12522198, -0.41276687 0.03243278 0.12343241, -0.41299251 0.032221615 0.12335251, -0.41299251 0.032426968 0.12504376, -0.41297048 0.032479182 0.12299715, -0.41276684 0.032612756 0.12491547, -0.41293457 0.032799914 0.12272035, -0.41288713 0.033161774 0.12252785, -0.41283026 0.033545792 0.12242021, -0.41299251 0.032427043 0.12296106, -0.41297045 0.03276217 0.1226777, -0.41288713 0.033537209 0.12238549, -0.41299251 0.032720163 0.12263037, -0.41718856 -0.022786722 0.050517187, -0.41709831 -0.022763804 0.050436869, -0.41698816 -0.022720084 0.050398305, -0.41698793 -0.022720113 0.050398603, -0.41758373 -0.022095531 0.050367936, -0.41752413 -0.022115842 0.050270215, -0.41743615 -0.022110611 0.050195828, -0.41739896 -0.021951795 0.050085977, -0.41783217 -0.021589562 0.05005689, -0.41680592 -0.023680001 0.05073978, -0.41678599 -0.023670301 0.05067654, -0.4167538 -0.023654595 0.050619677, -0.41671124 -0.023633674 0.050572023, -0.41777056 -0.021622986 0.049971327, -0.41666013 -0.023608655 0.05053629, -0.41660315 -0.023580745 0.050514057, -0.41654328 -0.023551315 0.050506487, -0.41774362 -0.021307752 0.049608007, -0.41768405 -0.021630585 0.049904451, -0.41806975 -0.021105617 0.049624696, -0.41800663 -0.021151021 0.049554214, -0.41792151 -0.02117081 0.0494975, -0.41799113 -0.02084519 0.049056426, -0.41827664 -0.020683855 0.049066797, -0.41821215 -0.020739391 0.049013928, -0.41816226 -0.020525143 0.04844214, -0.41812828 -0.020769671 0.048970684, -0.41843182 -0.020367816 0.048397407, -0.41836628 -0.020430654 0.048364297, -0.41826233 -0.020338148 0.04774572, -0.41828313 -0.020468816 0.048337236, -0.41851526 -0.020197853 0.047648832, -0.41844913 -0.020264581 0.047637478, -0.41827962 -0.020305648 0.047085926, -0.41836658 -0.0203069 0.047628388, -0.41851562 -0.020196959 0.046872064, -0.41823432 -0.020390466 0.046500102, -0.41844958 -0.020263702 0.046883032, -0.418367 -0.020306006 0.046892211, -0.41843304 -0.020365477 0.046123251, -0.41813546 -0.020575091 0.045950815, -0.41836733 -0.020428345 0.046155587, -0.41828436 -0.020466492 0.046182528, -0.4182578 -0.020722404 0.045384303, -0.41819319 -0.020777076 0.045439258, -0.41810927 -0.020806402 0.045483813, -0.41799214 -0.020842865 0.04546015, -0.41806462 -0.021115765 0.044877633, -0.41800132 -0.021161035 0.044948474, -0.41791636 -0.02118054 0.045005456, -0.41781622 -0.021171764 0.045043007, -0.41781622 -0.021171764 0.045043007, -0.41761976 -0.021538958 0.044704571, -0.41780812 -0.021547586 0.044598505, -0.41772202 -0.021557078 0.04466407, -0.41761974 -0.021539092 0.04470472, -0.41753832 -0.022087142 0.044257298, -0.41745046 -0.022082612 0.044331416, -0.41677895 -0.023110285 0.044036523, -0.41704074 -0.022620827 0.044142649, -0.41734508 -0.022052541 0.044372842, -0.41680601 -0.023679525 0.043773398, -0.41734484 -0.022052541 0.044372603, -0.41678599 -0.023669824 0.043836847, -0.41727564 -0.022722915 0.043902561, -0.41675395 -0.023654133 0.043893471, -0.41721871 -0.022726014 0.044011638, -0.41671112 -0.023633286 0.043941066, -0.41712859 -0.022704795 0.044091985, -0.41666022 -0.023608178 0.043977037, -0.41660312 -0.023580283 0.043998852, -0.41654328 -0.023550987 0.044006601, -0.41299966 -0.023550987 0.044006601, -0.41299966 -0.022773191 0.044101164, -0.41299966 -0.022040606 0.044379011, -0.41299969 -0.021395922 0.04482381, -0.41299966 -0.020876348 0.045410529, -0.41299966 -0.020512402 0.046104088, -0.41299972 -0.020324871 0.046865001, -0.41299972 -0.020324871 0.047648534, -0.41299966 -0.020512372 0.048409209, -0.41299966 -0.020876586 0.049102798, -0.41299966 -0.02139622 0.049689367, -0.41299966 -0.022041023 0.050134525, -0.41299966 -0.022773609 0.050412282, -0.41299966 -0.023551404 0.050506487, -0.41299957 -0.03078559 0.044006363, -0.4129996 -0.030786008 0.050506219, -0.41299954 -0.022291288 0.04867886, -0.41299966 -0.021987498 0.048336074, -0.41299966 -0.02177465 0.047930583, -0.41299966 -0.021665022 0.047485635, -0.41299963 -0.02781111 0.048678741, -0.41299966 -0.02811487 0.048335806, -0.41299966 -0.027434275 0.048938736, -0.41299963 -0.028327703 0.047930136, -0.41299966 -0.021665022 0.047027752, -0.41299966 -0.02700606 0.049101338, -0.41299966 -0.026551113 0.045356408, -0.41299966 -0.023551077 0.045356646, -0.41299966 -0.023096383 0.045411959, -0.41299963 -0.028437331 0.047485247, -0.41299963 -0.030993134 0.050520375, -0.41299966 -0.026551336 0.049156442, -0.4129996 -0.02177462 0.046582952, -0.41299966 -0.021987379 0.046177313, -0.41299984 -0.022668138 0.045574412, -0.41299969 -0.022291213 0.045834526, -0.41299963 -0.031398535 0.050674304, -0.4129996 -0.031334311 0.043884441, -0.41299963 -0.031398118 0.043838128, -0.41299963 -0.031310394 0.050614223, -0.4129996 -0.03118746 0.050563797, -0.4129996 -0.031249568 0.043926015, -0.41299963 -0.028437331 0.047027215, -0.41299963 -0.031030566 0.043986365, -0.41299963 -0.028327674 0.046582595, -0.4129996 -0.02811484 0.046176925, -0.41299966 -0.027811095 0.045834437, -0.41299966 -0.027434081 0.045573965, -0.41299966 -0.02355139 0.04915677, -0.41299954 -0.027005836 0.045411602, -0.41299966 -0.023096651 0.049101487, -0.41299966 -0.022668347 0.048938885, -0.41296995 -0.023127809 0.048974976, -0.41293421 -0.023141444 0.048919722, -0.41293421 -0.02355136 0.048969641, -0.41299209 -0.022699147 0.045633569, -0.41297004 -0.02272886 0.04882367, -0.41293421 -0.022755206 0.048773423, -0.41299215 -0.021731243 0.047035828, -0.41299218 -0.021836981 0.046606705, -0.41297013 -0.021896318 0.046629086, -0.4129923 -0.023112252 0.04547669, -0.41297013 -0.023127511 0.045538321, -0.41297001 -0.021794245 0.047043338, -0.41296998 -0.022728592 0.045689359, -0.41299221 -0.023112625 0.049036607, -0.41299215 -0.02355127 0.049089834, -0.41297001 -0.021794245 0.047469988, -0.41293433 -0.021850675 0.047050253, -0.41293421 -0.02185075 0.047463223, -0.41297001 -0.023551419 0.049026385, -0.41299215 -0.022699401 0.048879877, -0.4129701 -0.022377461 0.04593192, -0.41293433 -0.022755086 0.045739874, -0.41293421 -0.022415265 0.045974627, -0.41293427 -0.0219495 0.047864124, -0.4128868 -0.021897867 0.047457591, -0.4128868 -0.02199395 0.047847405, -0.41293433 -0.022141337 0.046283528, -0.4128868 -0.022446707 0.046010032, -0.41288689 -0.022180423 0.04631044, -0.41276655 -0.023166418 0.045695826, -0.41276664 -0.023551062 0.045648947, -0.41269976 -0.023551121 0.045656577, -0.41288683 -0.022180617 0.048202857, -0.41282991 -0.022027344 0.04783465, -0.4128868 -0.02199389 0.046666041, -0.41282994 -0.022209838 0.046330795, -0.41269976 -0.023168221 0.045703188, -0.41282991 -0.022209972 0.048182413, -0.41282994 -0.022027344 0.046678677, -0.41282997 -0.022470489 0.048476562, -0.41276655 -0.022228241 0.048169866, -0.41283002 -0.023161039 0.04567425, -0.41282991 -0.023551092 0.045626894, -0.41282991 -0.021933317 0.047060147, -0.41276652 -0.022048071 0.046686515, -0.41276649 -0.022485226 0.048459873, -0.41276655 -0.021955281 0.047062889, -0.41276649 -0.022804111 0.048679993, -0.41269973 -0.022490188 0.04845427, -0.41269961 -0.022807598 0.048673376, -0.41276652 -0.022804007 0.045833245, -0.41269964 -0.022807553 0.045839921, -0.41276652 -0.021955386 0.047450677, -0.41269964 -0.021962836 0.047063753, -0.41269967 -0.021962866 0.047449395, -0.41299209 -0.021731287 0.047477618, -0.41299218 -0.022335455 0.045884505, -0.41288677 -0.0231525 0.04563944, -0.41288689 -0.023551077 0.045591131, -0.41297001 -0.021896377 0.047884241, -0.41297013 -0.022094563 0.046251312, -0.41282991 -0.02279374 0.045813695, -0.4129343 -0.021949485 0.046649322, -0.41299215 -0.023551062 0.045423314, -0.41293421 -0.022141561 0.048229709, -0.41288695 -0.021897763 0.047055975, -0.41276652 -0.022485092 0.046053424, -0.41269976 -0.022490159 0.046058908, -0.41288683 -0.022446707 0.048503175, -0.4129343 -0.023141161 0.045593426, -0.4129343 -0.023551121 0.045543805, -0.41282991 -0.022793874 0.048699751, -0.41282991 -0.021933362 0.04745315, -0.4128868 -0.022777125 0.045782045, -0.41276649 -0.023166642 0.048817411, -0.41282991 -0.022470385 0.046036884, -0.41269964 -0.02316834 0.048810259, -0.41276652 -0.02355127 0.048863962, -0.41276652 -0.022048071 0.047826692, -0.41269961 -0.022055179 0.047823921, -0.41299218 -0.021836981 0.047906891, -0.41299221 -0.022042334 0.046215191, -0.41297004 -0.022094697 0.048262015, -0.41276664 -0.022228077 0.046343669, -0.41269973 -0.022234365 0.046347752, -0.41293421 -0.02241534 0.048538968, -0.41296998 -0.023551121 0.045486823, -0.4128868 -0.022777215 0.048731223, -0.41282997 -0.023161352 0.048839197, -0.41282991 -0.02355133 0.048886523, -0.41299209 -0.022042423 0.048298106, -0.41269964 -0.022234425 0.048165575, -0.41297001 -0.022377625 0.048581466, -0.41269976 -0.022055104 0.046689168, -0.4128868 -0.023152784 0.048873559, -0.4128868 -0.02355136 0.048922196, -0.41299215 -0.022335514 0.048628941, -0.41269973 -0.02355127 0.048856601, -0.41099969 -0.0235513 0.04885672, -0.41099972 -0.023168266 0.048810199, -0.41099969 -0.022807553 0.048673376, -0.41099975 -0.022490144 0.048454389, -0.41099975 -0.02223438 0.048165455, -0.41099972 -0.022055164 0.047823921, -0.41099972 -0.021962896 0.047449395, -0.41099972 -0.021962896 0.047063604, -0.41099972 -0.022055104 0.046689168, -0.41099963 -0.022234365 0.046347752, -0.41099975 -0.022490084 0.046058908, -0.41099969 -0.022807553 0.045839921, -0.41099972 -0.023168266 0.045703068, -0.41099969 -0.023551196 0.045656577, -0.41269973 -0.026551291 0.048856422, -0.41099969 -0.026551276 0.048856422, -0.41099972 -0.026551127 0.045656577, -0.41269955 -0.026934102 0.045703039, -0.41099969 -0.026934057 0.045702949, -0.41269961 -0.026551113 0.045656428, -0.41269973 -0.027294666 0.045839533, -0.4109998 -0.027294606 0.045839474, -0.41269973 -0.027612135 0.046058759, -0.41099969 -0.02761212 0.046058759, -0.41269973 -0.027867928 0.046347514, -0.41099969 -0.027867839 0.046347424, -0.41269973 -0.028047174 0.046689019, -0.41099969 -0.028047115 0.046688929, -0.41269958 -0.028139502 0.047063455, -0.41099969 -0.028139502 0.047063455, -0.41269958 -0.028139502 0.047449127, -0.41099969 -0.028139502 0.047449127, -0.41269973 -0.028047189 0.047823682, -0.41099966 -0.02804713 0.047823682, -0.41269973 -0.027867973 0.048165306, -0.41099969 -0.027867973 0.048165306, -0.41269973 -0.027612194 0.048453942, -0.41099969 -0.027612165 0.048453942, -0.4126997 -0.027294695 0.048672929, -0.41099969 -0.02729477 0.048673138, -0.41269961 -0.026934162 0.04880999, -0.41099969 -0.026934162 0.04880999, -0.41276649 -0.026551142 0.045648828, -0.41282991 -0.026551113 0.045626804, -0.41288677 -0.026551142 0.045591101, -0.41293421 -0.026551127 0.045543447, -0.4129701 -0.026551083 0.045486614, -0.41299215 -0.026551142 0.045423165, -0.41276649 -0.026551276 0.048863873, -0.41282991 -0.026551351 0.048886076, -0.41288677 -0.026551306 0.048922047, -0.41293427 -0.026551336 0.048969403, -0.4129701 -0.026551276 0.049026236, -0.41299215 -0.026551291 0.049089685, -0.41299215 -0.028371051 0.04747729, -0.41299215 -0.027403265 0.048879728, -0.41296998 -0.026974708 0.045538113, -0.4129701 -0.027373582 0.04568921, -0.41293427 -0.027347207 0.045739785, -0.41297007 -0.028206021 0.047883973, -0.41297007 -0.028308183 0.04746972, -0.41293433 -0.026961073 0.045593277, -0.41299215 -0.028265342 0.047906414, -0.41299215 -0.026990041 0.049036279, -0.4129701 -0.026974872 0.048974738, -0.4129701 -0.027373776 0.048823491, -0.41299215 -0.026989803 0.045476541, -0.41299209 -0.027403086 0.045633122, -0.41296998 -0.028308153 0.047043011, -0.41293415 -0.028251708 0.047462806, -0.41293418 -0.028251678 0.047049925, -0.41296992 -0.027724847 0.048581019, -0.41293433 -0.027347237 0.048773065, -0.41293418 -0.027687162 0.04853867, -0.41293424 -0.028152794 0.046648875, -0.41288677 -0.028204456 0.047055706, -0.41293415 -0.027960882 0.048229471, -0.41288677 -0.027655512 0.048502877, -0.41288665 -0.028108433 0.046665713, -0.41288677 -0.027921811 0.048202559, -0.41276649 -0.02693598 0.048817173, -0.41288677 -0.027921751 0.046310201, -0.41282985 -0.02807495 0.046678558, -0.41282988 -0.027892351 0.046330586, -0.41288677 -0.028108373 0.047847018, -0.41282988 -0.027892411 0.048182115, -0.41282985 -0.02807495 0.047834143, -0.41282991 -0.026941329 0.048838869, -0.41282991 -0.027631834 0.046036735, -0.41276649 -0.027874097 0.046343222, -0.41282988 -0.028169066 0.047452703, -0.41276646 -0.028054208 0.047826305, -0.41276649 -0.028146982 0.047450021, -0.41276646 -0.027617186 0.046053186, -0.41276649 -0.027298242 0.048679724, -0.41276649 -0.027298152 0.045833156, -0.41276649 -0.028146982 0.047062621, -0.41299215 -0.028371051 0.047035322, -0.41299212 -0.027766824 0.048628494, -0.41288689 -0.026949808 0.04887341, -0.41297007 -0.028206021 0.046628878, -0.4129701 -0.028007701 0.048261538, -0.41282991 -0.027308568 0.048699275, -0.41293418 -0.028152883 0.047863707, -0.41293415 -0.027960882 0.04628323, -0.41276649 -0.027617231 0.048459545, -0.41288677 -0.027655512 0.046009824, -0.41288677 -0.028204471 0.047456935, -0.41293421 -0.026961312 0.048919573, -0.41282991 -0.027308509 0.045813546, -0.41282988 -0.028168976 0.047059998, -0.41288677 -0.027325228 0.048731104, -0.41276649 -0.026935846 0.045695677, -0.41282988 -0.027631909 0.048476115, -0.41276646 -0.028054208 0.046686307, -0.41299215 -0.028265253 0.046606317, -0.41299212 -0.02805993 0.048297659, -0.41276646 -0.027874142 0.048169628, -0.41296992 -0.028007761 0.046250984, -0.41293418 -0.027687073 0.04597418, -0.41288677 -0.027325079 0.045781627, -0.41282991 -0.02694118 0.045674011, -0.41299212 -0.028059855 0.046215042, -0.4129701 -0.027724698 0.045931712, -0.41288677 -0.026949674 0.045639291, -0.41299227 -0.027766749 0.045884266, -0.41298351 -0.031495109 0.043744013, -0.41299352 -0.031458303 0.043781176, -0.41299024 -0.031473696 0.050745949, -0.41299725 -0.03143622 0.050709233, -0.46434066 0.15340863 0.071130618, -0.46547344 0.15343088 0.072687998, -0.46524927 0.15320516 0.072660699, -0.4651767 0.15320513 0.072955087, -0.46432725 0.153373 0.071185812, -0.46532828 0.15340862 0.073012456, -0.46541029 0.15340868 0.07268025, -0.46469018 0.15343077 0.073822603, -0.46435592 0.1534308 0.073949322, -0.46434066 0.15340863 0.07388778, -0.46466073 0.15340872 0.071251884, -0.46463433 0.153373 0.071302488, -0.46538797 0.15343088 0.073035225, -0.46435583 0.15343092 0.071068987, -0.4646607 0.15340857 0.073766425, -0.46494249 0.15340872 0.073571876, -0.46463433 0.15337296 0.073716, -0.46469018 0.15343088 0.071195796, -0.46541044 0.15340872 0.07233806, -0.465354 0.15337296 0.072673634, -0.46535397 0.153373 0.072344974, -0.46527532 0.15337302 0.07202588, -0.46530679 0.15332542 0.072350606, -0.46490481 0.15337297 0.073529258, -0.46512255 0.15337293 0.073283538, -0.46487319 0.15332541 0.073493704, -0.46430179 0.1532051 0.073730215, -0.46523079 0.15332545 0.072042778, -0.4650836 0.15332541 0.073256448, -0.46508345 0.15332545 0.071761861, -0.46519756 0.15326868 0.072055563, -0.46523091 0.15332545 0.072975621, -0.46505412 0.15326847 0.073236093, -0.46519753 0.15326855 0.072962984, -0.46505412 0.1532685 0.071782306, -0.46430716 0.15326853 0.073751763, -0.46484944 0.15326858 0.071551308, -0.46503574 0.15320519 0.071794942, -0.46483478 0.15320517 0.071567848, -0.46527126 0.15326847 0.072663501, -0.46458527 0.15320514 0.071395621, -0.46458527 0.15320508 0.073622569, -0.46524915 0.15320523 0.072357759, -0.46547332 0.1534308 0.07233052, -0.46431568 0.15332539 0.073786363, -0.46498439 0.15343085 0.07361947, -0.46532843 0.15340863 0.072005495, -0.46516937 0.15340859 0.073315695, -0.46459565 0.15326858 0.073642328, -0.46527526 0.15337293 0.07299231, -0.46483481 0.15320513 0.07345061, -0.46512261 0.15337296 0.071734861, -0.46487319 0.15332541 0.071524605, -0.46530679 0.15332542 0.072667703, -0.46432719 0.1533729 0.073832735, -0.46461222 0.15332539 0.073673829, -0.4645955 0.15326861 0.07137616, -0.46527126 0.15326858 0.072354987, -0.46430185 0.15320523 0.071288183, -0.46517682 0.15320522 0.072063223, -0.46484944 0.15326847 0.073467091, -0.46538785 0.15343101 0.071983323, -0.46522146 0.15343086 0.073351696, -0.46503583 0.1532051 0.073223546, -0.4651694 0.15340872 0.071702614, -0.4649047 0.15337296 0.071489051, -0.4646121 0.15332539 0.071344271, -0.46430713 0.15326861 0.071266755, -0.46522161 0.15343088 0.071666703, -0.46494243 0.15340871 0.071446285, -0.46431562 0.15332545 0.071232036, -0.46498439 0.15343085 0.071398988, -0.48435581 0.14991543 0.14129414, -0.48469028 0.14985874 0.14140736, -0.48434061 0.14986803 0.14133932, -0.4846606 0.14981368 0.14144765, -0.4854103 0.14932792 0.14241914, -0.4854103 0.14917487 0.14272545, -0.48535398 0.14914602 0.14270319, -0.48494235 0.14877605 0.14352287, -0.48463425 0.14867955 0.14363565, -0.48490462 0.14876306 0.14346884, -0.48527518 0.14943556 0.14212386, -0.48530665 0.14924785 0.1423931, -0.48523083 0.14938557 0.14211775, -0.48466071 0.14868906 0.14369656, -0.48512253 0.14887306 0.14324857, -0.48487318 0.14873655 0.1434157, -0.48508343 0.14884268 0.14320327, -0.48535398 0.14929295 0.14240919, -0.48430184 0.14852326 0.14357327, -0.48523071 0.14896822 0.14295231, -0.48505417 0.14880095 0.14315988, -0.48508349 0.14951119 0.14186667, -0.4851974 0.14932905 0.14210372, -0.48505405 0.14945129 0.14185931, -0.48484942 0.14955465 0.14165296, -0.48503587 0.14938903 0.14184241, -0.4851974 0.14892307 0.1429155, -0.4843072 0.14857036 0.14362098, -0.48483482 0.14949042 0.14163934, -0.48527119 0.14905712 0.14264749, -0.48517659 0.14887002 0.1428801, -0.48458531 0.14956746 0.14148526, -0.48524919 0.14900163 0.14261676, -0.48458531 0.14857137 0.1434771, -0.48524925 0.14913714 0.14234568, -0.48547322 0.14935111 0.14242233, -0.48498431 0.14877461 0.14357521, -0.48431578 0.14860564 0.14367722, -0.4854733 0.14919129 0.14274214, -0.48469019 0.1486838 0.14375661, -0.48532858 0.14947662 0.14212193, -0.48516926 0.14889055 0.14329375, -0.48459563 0.14861935 0.14352296, -0.4851225 0.14956577 0.14186381, -0.48527518 0.1490033 0.14298855, -0.4848347 0.14864841 0.14332293, -0.48487324 0.14961745 0.14165451, -0.48432702 0.14862753 0.14373983, -0.4853068 0.14910604 0.14267682, -0.48459563 0.14963299 0.14149605, -0.4852713 0.1491951 0.14237167, -0.48461217 0.14865603 0.14357673, -0.48430181 0.14961554 0.14138915, -0.48517674 0.14926876 0.14208235, -0.48538771 0.14950648 0.14211179, -0.48484939 0.14869764 0.14336629, -0.48522156 0.14889432 0.14333583, -0.48516938 0.14961222 0.14185093, -0.48503584 0.14874984 0.14312004, -0.48532841 0.14902622 0.14302267, -0.48490462 0.14967579 0.1416439, -0.4843407 0.14863481 0.14380516, -0.48461226 0.14969796 0.14149319, -0.48430714 0.14968184 0.14139833, -0.48522156 0.1496482 0.14182858, -0.48494247 0.14972687 0.14162146, -0.48538771 0.14903596 0.14305268, -0.48435587 0.14862724 0.14387025, -0.48463437 0.14975923 0.14147688, -0.48431566 0.14974831 0.1413926, -0.48498437 0.14976797 0.14158927, -0.48432702 0.1498114 0.14137278, -0.48439083 0.15110162 0.1452664, -0.48439941 0.15113696 0.14532314, -0.48474783 0.1523892 0.14255001, -0.48438558 0.15245059 0.1424271, -0.48439088 0.15251695 0.14243604, -0.48477486 0.15120058 0.14519571, -0.48559663 0.15183927 0.14364956, -0.48550394 0.1520074 0.14331315, -0.48552465 0.15206774 0.1433344, -0.48561865 0.15189722 0.1436757, -0.48438546 0.15105446 0.14521895, -0.48561865 0.15172151 0.1440271, -0.48565421 0.15194996 0.14369737, -0.48565418 0.15177031 0.14405645, -0.4847582 0.15245458 0.14256074, -0.48475817 0.15116386 0.14514203, -0.48474783 0.15111588 0.14509605, -0.4850817 0.15235488 0.14276017, -0.4847748 0.15251972 0.14255787, -0.48510522 0.15241769 0.14276196, -0.48555818 0.15159602 0.14440514, -0.48570141 0.15181021 0.1440828, -0.48560265 0.15163103 0.14444138, -0.48537162 0.15228331 0.14303051, -0.48513684 0.15247615 0.14275132, -0.48541072 0.15233782 0.14302789, -0.48541054 0.15146741 0.14476846, -0.48565575 0.15165398 0.14447521, -0.48443964 0.15275054 0.14233197, -0.48545736 0.15148494 0.14481317, -0.48560265 0.15217438 0.14335479, -0.48545739 0.15238421 0.1430148, -0.48517445 0.15134218 0.14509882, -0.4855096 0.15148881 0.14485539, -0.48565564 0.15221524 0.14335264, -0.48442435 0.15270314 0.14237715, -0.48521659 0.15134066 0.145151, -0.48575786 0.15202998 0.14372323, -0.48571497 0.15224516 0.14334248, -0.48582059 0.15205325 0.14372636, -0.4848527 0.15122847 0.14537571, -0.48582071 0.15185566 0.14412151, -0.48485282 0.15268043 0.14247216, -0.48559666 0.15166585 0.14399631, -0.48506689 0.15229073 0.14274694, -0.48441085 0.1526465 0.14241053, -0.48552465 0.15155084 0.14436816, -0.48534209 0.1522233 0.14302336, -0.48482344 0.15263553 0.14251257, -0.48555794 0.15212426 0.14334874, -0.48537162 0.15143695 0.14472304, -0.48521665 0.15256822 0.14269672, -0.48513681 0.15132931 0.14504476, -0.48570132 0.15199497 0.14371346, -0.48439941 0.15258338 0.14243044, -0.48482332 0.15123364 0.14531563, -0.48479694 0.15258099 0.14254127, -0.48575792 0.15183926 0.14410494, -0.48443964 0.15115845 0.1455159, -0.485715 0.15166366 0.14450528, -0.48550385 0.15149763 0.14433287, -0.48517442 0.15252705 0.14272891, -0.48532379 0.15216097 0.14300631, -0.48534197 0.15139517 0.14467953, -0.48550966 0.15242027 0.1429926, -0.48510537 0.15130273 0.14499186, -0.48479685 0.15122427 0.1452546, -0.48442435 0.15116611 0.14545093, -0.48532394 0.15134415 0.1446398, -0.48508161 0.15126374 0.14494239, -0.48441079 0.15115882 0.14538549, -0.48506692 0.15121441 0.14489911, -0.46439084 0.15626855 0.074091867, -0.46559671 0.15620512 0.072315589, -0.4655247 0.15626851 0.071931466, -0.46561876 0.15626855 0.072313026, -0.46474791 0.15620522 0.071085826, -0.46438569 0.15620519 0.070948556, -0.46439949 0.15632537 0.074126437, -0.46439087 0.15626861 0.070926771, -0.46475831 0.15626851 0.073952422, -0.46477491 0.15632541 0.073984191, -0.4655039 0.15620509 0.071939185, -0.4643856 0.1562051 0.07407029, -0.46475825 0.15626857 0.071066365, -0.46508154 0.15626861 0.071289405, -0.46477482 0.15632549 0.071034417, -0.46474788 0.15620509 0.073932633, -0.46561876 0.15626855 0.07270582, -0.46565416 0.1563254 0.072308525, -0.46565416 0.1563254 0.072710082, -0.46555814 0.1563254 0.073099867, -0.46570137 0.15637287 0.072715744, -0.46510532 0.15632544 0.071262792, -0.46537146 0.15632538 0.071563318, -0.4651368 0.1563729 0.071227148, -0.46443966 0.15643087 0.070729211, -0.46560252 0.15637286 0.073116854, -0.46541068 0.15637276 0.073482499, -0.46565571 0.15640858 0.073137209, -0.46541062 0.15637287 0.071536407, -0.46560252 0.15637298 0.071901992, -0.46545747 0.15640858 0.071504012, -0.46565565 0.15640864 0.071881995, -0.46442449 0.15640874 0.070790991, -0.46545747 0.15640858 0.073514685, -0.46517459 0.15640859 0.073834166, -0.46550962 0.15643077 0.073550835, -0.46521652 0.15643091 0.073881611, -0.46575767 0.15640864 0.072295979, -0.46571496 0.15643081 0.071859434, -0.4658207 0.15643083 0.072288379, -0.4648529 0.15643072 0.074132517, -0.46485296 0.15643089 0.07088609, -0.46582076 0.15643087 0.072730318, -0.4644109 0.15637298 0.070845947, -0.46559665 0.156205 0.072703108, -0.46506694 0.1562051 0.071306095, -0.46534219 0.15626855 0.071583614, -0.46482351 0.15640882 0.070942387, -0.4655247 0.15626851 0.07308732, -0.46537146 0.15632534 0.073455438, -0.46555814 0.1563254 0.071918741, -0.46521667 0.1564309 0.071137384, -0.46570137 0.15637287 0.072302952, -0.4651368 0.1563729 0.073791459, -0.46439952 0.15632547 0.07089217, -0.46479699 0.15637299 0.070992693, -0.46482345 0.15640861 0.074076578, -0.4657577 0.15640862 0.072722659, -0.46443966 0.15643074 0.074289426, -0.46571496 0.15643081 0.073159412, -0.46517453 0.1564087 0.071184829, -0.4655039 0.15620509 0.073079422, -0.4653239 0.15620512 0.071596101, -0.46550968 0.15643087 0.07146807, -0.46534219 0.15626855 0.073435143, -0.46510527 0.15632537 0.073756054, -0.46479699 0.15637289 0.074026302, -0.46442452 0.15640858 0.074227765, -0.4653239 0.15620512 0.073422655, -0.46508157 0.15626849 0.073729232, -0.46441087 0.15637286 0.074172601, -0.46506688 0.15620509 0.073712692, -0.46731663 0.15694065 -0.072490677, -0.46726033 0.15692361 -0.072490588, -0.46720856 0.15689594 -0.072490588, -0.46106425 0.15691556 0.073923334, -0.46145254 0.1569154 0.074541762, -0.46140853 0.15693238 0.07457681, -0.46101353 0.15693256 0.073947981, -0.46076819 0.15693256 0.07324715, -0.46068513 0.15693262 0.072509244, -0.46111098 0.15688781 0.073901132, -0.46149313 0.15688762 0.074509308, -0.46082321 0.15691553 0.073234662, -0.46074143 0.15691552 0.072509393, -0.46087369 0.1568878 0.073223099, -0.46079335 0.15688786 0.072509393, -0.46326309 0.1569325 0.075742051, -0.46327552 0.15691526 0.075687096, -0.46256223 0.15693232 0.075496867, -0.46328712 0.15688761 0.075636759, -0.46258661 0.15691534 0.075446114, -0.46193352 0.15693237 0.075101808, -0.4626092 0.15688756 0.075399354, -0.46196857 0.15691534 0.0750577, -0.46200097 0.15688762 0.075017169, -0.46679327 0.15648893 0.072509304, -0.46674141 0.15646125 0.072509393, -0.46668515 0.15644413 0.072509304, -0.46516562 0.15644395 0.074927941, -0.46459821 0.15644397 0.075126395, -0.46521249 0.15648872 0.075025305, -0.46574184 0.15648869 0.074692562, -0.46570957 0.15646107 0.074652061, -0.46518993 0.15646106 0.074978545, -0.46461073 0.15646112 0.07518144, -0.46462226 0.15648867 0.075232074, -0.46661785 0.15644413 0.073106721, -0.46667275 0.15646121 0.073119268, -0.46641916 0.15644409 0.073674038, -0.46672329 0.15648891 0.073130682, -0.46646997 0.15646115 0.073698476, -0.46609965 0.1564441 0.074182972, -0.46651688 0.15648882 0.073721036, -0.46614346 0.15646119 0.07421802, -0.46567449 0.15644389 0.074608162, -0.46618414 0.15648867 0.074250475, -0.46120855 0.15649708 -0.072490796, -0.46126032 0.15646946 -0.072490588, -0.46131665 0.15645227 -0.072490796, -0.48679343 0.1520064 0.14394997, -0.48674136 0.15198155 0.1439376, -0.48668513 0.15196635 0.14392994, -0.48647341 0.15258683 0.14278935, -0.4812896 0.15230532 0.14335217, -0.48120853 0.15200636 0.14394997, -0.48609105 0.15283455 0.1422938, -0.48126021 0.15198153 0.1439376, -0.48133996 0.15227494 0.14335074, -0.48605207 0.15279439 0.1423123, -0.48642752 0.15255123 0.14279853, -0.48157433 0.15255132 0.14279847, -0.48139468 0.1522537 0.14335524, -0.4816241 0.15252429 0.14281429, -0.48666182 0.15227497 0.14335082, -0.48637769 0.15252423 0.14281429, -0.48660722 0.15225364 0.14335538, -0.4819918 0.15276249 0.14233769, -0.48671219 0.15230531 0.14335217, -0.48152831 0.15258688 0.14278911, -0.4819496 0.15279444 0.14231215, -0.48247615 0.15295447 0.14195408, -0.48191085 0.15283459 0.1422938, -0.48244423 0.15299049 0.14192019, -0.48304906 0.15308896 0.14168526, -0.4824146 0.1530343 0.14189447, -0.48302901 0.15312776 0.14164583, -0.48367721 0.15315822 0.14154674, -0.48301062 0.15317418 0.14161454, -0.48367056 0.15319844 0.14150403, -0.48432431 0.15315817 0.14154674, -0.4836643 0.15324624 0.14147092, -0.48433122 0.15319848 0.1415043, -0.48495278 0.15308897 0.14168517, -0.48433748 0.15324624 0.14147092, -0.48497269 0.15312771 0.14164583, -0.4855257 0.15295437 0.14195408, -0.4849911 0.15317424 0.14161481, -0.48555765 0.15299039 0.14192019, -0.48601004 0.15276244 0.14233778, -0.48558721 0.15303436 0.14189447, -0.4813166 0.15196629 0.14392982, -0.48068514 0.15240313 0.14414833, -0.48074129 0.1523879 0.14414074, -0.48079327 0.1523632 0.14412819, -0.48716569 0.15273686 0.14344312, -0.48731652 0.15240327 0.14414833, -0.48726037 0.1523879 0.14414074, -0.48111483 0.1530655 0.14278589, -0.4807815 0.15275811 0.14343856, -0.48106506 0.15309246 0.14277019, -0.48688713 0.15306555 0.14278589, -0.4869369 0.15309241 0.14277031, -0.48722026 0.15275815 0.14343868, -0.48151913 0.15338674 0.14218186, -0.48711529 0.15270646 0.14344178, -0.48720852 0.15236315 0.14412819, -0.4811607 0.15302996 0.14279519, -0.48684117 0.15302981 0.14279501, -0.48088652 0.15270659 0.14344178, -0.48083612 0.15273684 0.14344312, -0.48156109 0.15335463 0.14220764, -0.48211727 0.15362386 0.14170779, -0.48159996 0.15331449 0.14222585, -0.48214933 0.15358777 0.14174156, -0.48282519 0.15378998 0.14137568, -0.48217866 0.15354386 0.14176728, -0.4828451 0.15375109 0.14141501, -0.48360124 0.15387554 0.14120437, -0.4828634 0.15370455 0.14144598, -0.48360804 0.15383525 0.14124678, -0.48440066 0.15387543 0.14120422, -0.4836143 0.15378739 0.1412804, -0.48439375 0.15383513 0.14124678, -0.48517662 0.15378991 0.14137541, -0.48438752 0.1537874 0.14128034, -0.48515669 0.15375118 0.14141501, -0.48588446 0.15362374 0.14170779, -0.48513827 0.15370467 0.14144598, -0.48585251 0.15358776 0.14174156, -0.4864828 0.15338656 0.14218186, -0.48582301 0.1535439 0.14176728, -0.48644063 0.15335464 0.14220764, -0.48640177 0.15331447 0.14222585, -0.4729636 0.086897016 0.075530007, -0.47297242 0.086907744 0.075526699, -0.47287172 0.086694241 0.075283363, -0.47288075 0.086698607 0.075238779, -0.47282308 0.08660084 0.075287506, -0.47283047 0.086597234 0.075235859, -0.47277883 0.090428367 0.034020767, -0.47283164 0.090603113 0.034080669, -0.47288254 0.090771571 0.034176216, -0.47288987 0.090795502 0.034200653, -0.47286966 0.090728715 0.034144118, -0.47289807 0.09082295 0.034254178, -0.47289675 0.090818346 0.034238085, -0.47289437 0.090810657 0.034221992, -0.47281417 0.09054397 0.060467526, -0.47286826 0.090722978 0.060384408, -0.47288635 0.090782985 0.060337737, -0.47289366 0.090806901 0.060307726, -0.47289714 0.090818182 0.060284391, -0.47289816 0.090821818 0.060270146, -0.47275832 0.086466432 0.062372342, -0.47273278 0.086478889 0.062278524, -0.4726913 0.086499169 0.062192097, -0.46280769 0.066323295 0.012433633, -0.46284917 0.06630294 0.012519941, -0.46287477 0.066290453 0.012613758, -0.46367624 0.067991629 0.011862025, -0.46381512 0.068380177 0.011330858, -0.46361104 0.067963555 0.011794671, -0.46336678 0.067464724 0.012143627, -0.46372756 0.068031639 0.011935547, -0.46394408 0.068473861 0.011443153, -0.46388641 0.068420574 0.01138474, -0.46342468 0.067478135 0.012221351, -0.4630945 0.066908687 0.0123602, -0.46346822 0.067502096 0.01230599, -0.46314445 0.066905648 0.012444481, -0.46317914 0.066911921 0.012536034, -0.46406391 0.068888247 0.010156259, -0.46409622 0.0689542 0.0095045716, -0.46414247 0.068943575 0.010175571, -0.46417579 0.069011554 0.0095045716, -0.46396855 0.068693563 0.010775313, -0.46420828 0.069013104 0.010196403, -0.46424255 0.069083199 0.0095044225, -0.46404436 0.068743244 0.010812983, -0.46410713 0.068806604 0.010853633, -0.46424249 0.069084287 -0.0094955713, -0.46417561 0.069012567 -0.0094955713, -0.46409622 0.068955287 -0.0094955713, -0.47275832 0.086468101 0.032153115, -0.47273287 0.086480603 0.032246932, -0.47269142 0.086500913 0.032333568, -0.4742873 0.088279292 0.095254853, -0.47428146 0.088231906 0.095122829, -0.4743574 0.088302046 0.095067874, -0.47441086 0.088355586 0.095064595, -0.47446021 0.088476166 0.095297828, -0.47455049 0.088582397 0.095372394, -0.47460809 0.088587567 0.095264629, -0.47449616 0.088468462 0.095192596, -0.47439983 0.088368386 0.095168725, -0.47452426 0.088469878 0.095084742, -0.47435433 0.088322163 0.095170215, -0.47438106 0.088389069 0.095270559, -0.47434342 0.0883497 0.095270351, -0.47499523 0.088950768 0.095529661, -0.47489074 0.088902593 0.095645294, -0.47477284 0.08887656 0.095754579, -0.47479215 0.088742301 0.095270112, -0.47472206 0.088712111 0.09538348, -0.47465637 0.088603973 0.095153347, -0.47464135 0.08869645 0.095493123, -0.47295451 0.086872965 0.031946167, -0.47295463 0.086876631 -0.03193529, -0.47298905 0.087021291 0.031898007, -0.47298899 0.087024882 -0.03188692, -0.47291064 0.086771876 0.032061562, -0.4728674 0.086680651 0.032095149, -0.47286305 0.0867057 0.03216134, -0.47291055 0.086815953 0.032129392, -0.47281694 0.086581901 0.032131776, -0.47284958 0.086734325 0.03222464, -0.47289836 0.086863682 0.032193407, -0.47282711 0.086766124 0.032284603, -0.47273836 0.086653128 0.032357439, -0.47280279 0.086600542 0.032212064, -0.47277647 0.086624444 0.032287851, -0.47298899 0.087066352 0.03196691, -0.47295454 0.086962372 0.032083377, -0.47297624 0.090177417 0.033409819, -0.47290468 0.090093553 0.033600375, -0.4727892 0.090018019 0.033772156, -0.47297412 0.091031685 0.034206823, -0.47293809 0.090899438 0.034167334, -0.47294191 0.090923682 0.034222826, -0.4729723 0.091006413 0.034133121, -0.47299343 0.091116726 0.034097716, -0.47299269 0.091078237 0.034016177, -0.4729698 0.090968981 0.034068421, -0.47299376 0.091142669 0.03419058, -0.47298899 0.091113165 0.034270123, -0.4728741 0.090514153 0.03390868, -0.47294348 0.090607479 0.03378658, -0.47291163 0.090739548 0.034017757, -0.47298607 0.090706468 0.033656821, -0.47296056 0.090840876 0.033933118, -0.47293204 0.090863109 0.034118697, -0.47299036 0.09094657 0.033845231, -0.47295466 0.090965405 0.034270123, -0.47298899 0.091111735 0.0602559, -0.47295484 0.090963975 0.0602559, -0.47298834 0.090835989 0.060777411, -0.4729909 0.090982169 0.060641363, -0.47296312 0.090875506 0.060561553, -0.47295275 0.090733305 0.060668424, -0.47282797 0.090240896 0.060702994, -0.4727892 0.090016589 0.060753897, -0.4728947 0.090635613 0.060564563, -0.47292238 0.090324476 0.060855582, -0.47290459 0.090092123 0.060925618, -0.47298065 0.090415254 0.061022028, -0.4729763 0.090175942 0.061116055, -0.47294217 0.090923622 0.060297951, -0.47294024 0.090911448 0.060332909, -0.47297436 0.0910317 0.060312107, -0.4729735 0.091019183 0.06035848, -0.47293165 0.090859398 0.06040974, -0.47299394 0.091142774 0.060326532, -0.47299355 0.091129765 0.060384855, -0.47296962 0.090965211 0.06046097, -0.4729175 0.090772882 0.06048508, -0.47299263 0.091074392 0.060513929, -0.47291061 0.086770132 0.062463894, -0.47289848 0.086862028 0.062332228, -0.47282711 0.086764455 0.062240854, -0.47291055 0.086814344 0.062396422, -0.47281694 0.086580202 0.062393919, -0.47280291 0.086598888 0.062313661, -0.47277644 0.086622775 0.062237814, -0.47273847 0.086651444 0.062168136, -0.47298899 0.087064683 0.062558725, -0.47295463 0.086960658 0.062442437, -0.44089565 0.14194751 -0.087458029, -0.44089556 0.14193766 0.087475285, -0.44096541 0.1419401 0.087475285, -0.44096544 0.14194992 -0.087458029, -0.44103494 0.14194736 0.087475166, -0.44103488 0.1419573 -0.087458119, -0.4408977 0.14194749 -0.087519422, -0.43930081 0.14194751 -0.087519601, -0.43930081 0.14193764 0.087536469, -0.44089779 0.14193767 0.087536439, -0.44090232 0.14193137 0.0876932, -0.44089034 0.14191315 0.087848172, -0.43930081 0.14191371 0.087844357, -0.44084254 0.14184201 0.088147387, -0.43930084 0.14184286 0.088144884, -0.44078499 0.14172645 0.088430867, -0.43930081 0.14172649 0.088430867, -0.44077405 0.14164618 0.088591352, -0.43930078 0.14149036 0.088903055, -0.44077399 0.14149036 0.088903055, -0.44077405 0.14148906 0.088905677, -0.4407388 0.14130522 0.08920373, -0.43930084 0.14125027 0.089274153, -0.44066918 0.14107719 0.089460239, -0.43930081 0.14093447 0.089583263, -0.44059679 0.14080851 0.089674219, -0.44053963 0.14050491 0.08983992, -0.43930084 0.14055856 0.089815632, -0.4405098 0.14017488 0.08995162, -0.43930084 0.14014079 0.089959607, -0.44051662 0.13982917 0.090004489, -0.43930075 0.13970152 0.090008602, -0.44052151 0.13970152 0.090008482, -0.44052133 0.1311442 0.090007886, -0.43930078 0.13114427 0.090008005, -0.44050679 0.13092521 0.089995846, -0.44048348 0.13064311 0.089944109, -0.43930075 0.13069436 0.089956716, -0.44048721 0.13037197 0.089852795, -0.43930072 0.13026761 0.089805439, -0.44053426 0.13000253 0.08965002, -0.43930075 0.12988566 0.089562312, -0.44062442 0.12965646 0.089344576, -0.43930075 0.12956834 0.089239225, -0.44071841 0.12938946 0.088967279, -0.43930072 0.12933168 0.088853106, -0.44072881 0.12933163 0.088853106, -0.44072887 0.12917496 0.088516816, -0.43930072 0.12912498 0.088409886, -0.44073316 0.12912497 0.088409767, -0.43930069 0.12902161 0.088138089, -0.44076666 0.12902355 0.088144407, -0.43930072 0.12895872 0.08785437, -0.44080082 0.12896103 0.087869987, -0.43930069 0.12893766 0.087564543, -0.44082478 0.12893769 0.087587699, -0.44082546 0.12893766 0.087564543, -0.43930069 0.12894744 -0.087548897, -0.44082537 0.12894747 -0.087548897, -0.44104281 0.14194822 0.087526903, -0.44097063 0.14194037 0.08753179, -0.44106343 0.14174676 0.0884801, -0.4409256 0.14172758 0.088451251, -0.44106698 0.14168547 0.088610753, -0.44092214 0.14165607 0.08859624, -0.44106701 0.14152962 0.088922605, -0.44092211 0.14150019 0.088908061, -0.44092211 0.14149863 0.088910922, -0.44106701 0.14152789 0.088926181, -0.44113806 0.13987477 0.090219095, -0.4411149 0.14020881 0.090153322, -0.44092974 0.14018683 0.090044007, -0.44094881 0.13985755 0.090101227, -0.44072497 0.14017531 0.089975938, -0.44073823 0.13984199 0.090028629, -0.44110945 0.14053199 0.090024337, -0.44093335 0.14050643 0.089928225, -0.44074097 0.1404973 0.089866027, -0.4411194 0.14090526 0.089779124, -0.44096065 0.14087769 0.089704379, -0.44079104 0.14086869 0.089652523, -0.44113281 0.14127272 0.089390263, -0.44100013 0.14124516 0.089344367, -0.44086167 0.14123321 0.089310989, -0.44074309 0.13970141 0.090033367, -0.44095373 0.13970144 0.090106651, -0.44114277 0.13970146 0.090224937, -0.44074291 0.1311442 0.09003292, -0.4409537 0.13114436 0.090106204, -0.44114265 0.13114424 0.09022437, -0.44072878 0.13090314 0.090018705, -0.44093964 0.13087657 0.090090498, -0.4411287 0.13084693 0.090207204, -0.44106507 0.12935248 0.089030579, -0.44109949 0.12961106 0.089477643, -0.44094923 0.12964669 0.089416608, -0.44089457 0.12938477 0.088991866, -0.44079012 0.12966201 0.089371666, -0.44108528 0.12994651 0.08981429, -0.44091454 0.12998378 0.089728817, -0.44108412 0.13022216 0.089997873, -0.44072956 0.12999974 0.089671597, -0.44090292 0.13025865 0.089898214, -0.44109714 0.13052583 0.090131119, -0.4407039 0.13027677 0.089834526, -0.44090953 0.13055961 0.090020642, -0.44070134 0.13058136 0.089952394, -0.44090495 0.12931755 0.088859633, -0.44107544 0.12927553 0.088879362, -0.44090489 0.12916069 0.088523492, -0.44107541 0.12911876 0.088543043, -0.44107166 0.12908134 0.088456884, -0.44090509 0.12911664 0.088427052, -0.4410542 0.12891121 0.087595448, -0.44094047 0.12893119 0.087591395, -0.44094089 0.1289309 0.087564334, -0.44105473 0.128911 0.087564543, -0.44094077 0.12894075 -0.087548897, -0.44105473 0.12892078 -0.087548897, -0.43150076 0.14466411 -0.090701833, -0.43150076 0.14466423 -0.094241396, -0.43150088 0.14466394 -0.088701829, -0.43150088 0.14466169 -0.048248693, -0.43150088 0.14466158 -0.046455815, -0.4865008 0.13762225 -0.14901979, -0.48650071 0.13615659 -0.16549183, -0.48650092 0.146016 -0.14576997, -0.48650095 0.14550138 -0.14331947, -0.48650077 0.14542183 -0.14248584, -0.48650074 0.1456416 -0.14414187, -0.48650089 0.14899299 -0.13840838, -0.48650077 0.14988855 -0.13802393, -0.48650077 0.14811282 -0.13882346, -0.48650077 0.14749838 -0.13915034, -0.48650086 0.14690508 -0.13951929, -0.48650089 0.13116693 -0.14902009, -0.48650065 0.13116781 -0.16549204, -0.48602113 0.14715511 -0.13901909, -0.48541963 0.14734548 -0.13863809, -0.48571089 0.15005329 -0.13769428, -0.4852908 0.14875101 -0.13806324, -0.48473224 0.14746444 -0.13840003, -0.48400083 0.14750496 -0.13831921, -0.48400086 0.15018822 -0.13742463, -0.48486912 0.15015422 -0.13749261, -0.483123 0.1494787 -0.13772567, -0.48247012 0.14871044 -0.13814421, -0.48167709 0.14993206 -0.13793691, -0.48331794 0.14507569 -0.14429672, -0.48260674 0.14497562 -0.1433786, -0.48328289 0.144861 -0.14360805, -0.48400089 0.14482191 -0.14368601, -0.48247012 0.1454054 -0.1447552, -0.48312297 0.14553155 -0.14562114, -0.48400083 0.14571658 -0.14636911, -0.48280424 0.14578147 -0.14623915, -0.48167714 0.14597264 -0.14585684, -0.48117241 0.14832267 -0.13891979, -0.48260662 0.14735124 -0.13862653, -0.48201135 0.14716759 -0.13899405, -0.48153189 0.14692561 -0.13947816, -0.47988591 0.14922245 -0.1393563, -0.48068523 0.14962587 -0.1385494, -0.4803054 0.14774245 -0.14008053, -0.48119593 0.14663918 -0.14005105, -0.48102275 0.1463251 -0.14067908, -0.47903737 0.14822191 -0.14135794, -0.47932592 0.14874525 -0.14031096, -0.48000088 0.14705798 -0.14144973, -0.48102275 0.14600179 -0.14132603, -0.4790372 0.14768283 -0.14243589, -0.48030528 0.14637336 -0.14281888, -0.4811959 0.14568764 -0.14195408, -0.48153189 0.14540142 -0.14252685, -0.47988597 0.14668229 -0.14443745, -0.47932574 0.14715955 -0.14348276, -0.48117253 0.14579313 -0.14397956, -0.48201147 0.14515938 -0.1430112, -0.48068514 0.14627881 -0.14524443, -0.48331806 0.14814568 -0.13815571, -0.48328286 0.14746596 -0.13839717, -0.48280424 0.15012321 -0.13755448, -0.48438385 0.15101446 -0.14516439, -0.48474434 0.15107553 -0.14504214, -0.48506203 0.1511735 -0.14484616, -0.4853175 0.15130261 -0.14458795, -0.48549682 0.15145531 -0.14428245, -0.48558921 0.15162283 -0.14394753, -0.48558924 0.15179534 -0.14360248, -0.48549679 0.1519628 -0.1432675, -0.48531774 0.15211558 -0.14296193, -0.48506203 0.15224469 -0.14270379, -0.48474437 0.15234259 -0.14250781, -0.48438385 0.15240373 -0.14238544, -0.48438564 0.1524667 -0.1424088, -0.48474786 0.15240517 -0.14253159, -0.48475841 0.15247075 -0.14254232, -0.48561874 0.15191332 -0.14365752, -0.48565423 0.1517866 -0.14403827, -0.48565426 0.15196615 -0.1436791, -0.4847478 0.15113238 -0.14507793, -0.48438558 0.15107085 -0.14520098, -0.48439083 0.15111786 -0.14524855, -0.48439088 0.1525331 -0.14241798, -0.4847582 0.15118024 -0.14512385, -0.48561871 0.15173768 -0.14400898, -0.48508164 0.15127997 -0.14492433, -0.48477486 0.15121697 -0.14517759, -0.48555815 0.15214051 -0.14333029, -0.48570126 0.15201119 -0.14369516, -0.48560262 0.15219054 -0.1433364, -0.48510525 0.15131883 -0.14497359, -0.48541063 0.15235402 -0.14300938, -0.48565581 0.15223151 -0.14333455, -0.48537156 0.15145323 -0.14470477, -0.48513684 0.15134551 -0.14502658, -0.48541072 0.15148371 -0.14475022, -0.48400095 0.15248758 -0.14236696, -0.48545739 0.15240043 -0.14299674, -0.48443961 0.1511748 -0.14549769, -0.48400095 0.15112773 -0.14560844, -0.48445556 0.15115245 -0.14555909, -0.48400095 0.15115091 -0.14554541, -0.48560253 0.15164724 -0.14442311, -0.48545736 0.15150125 -0.1447951, -0.48565564 0.15167013 -0.1444573, -0.48517445 0.15254316 -0.14271085, -0.4855096 0.15243648 -0.14297424, -0.48521671 0.15258433 -0.14267845, -0.48442435 0.15118238 -0.1454329, -0.48400074 0.15115942 -0.14547883, -0.4857578 0.15185541 -0.14408661, -0.48571506 0.15167999 -0.14448728, -0.48485282 0.15269651 -0.14245389, -0.48526081 0.1526133 -0.14263697, -0.48488384 0.1527296 -0.14240436, -0.4858208 0.15187183 -0.14410339, -0.4858208 0.15206957 -0.14370809, -0.48588702 0.15187497 -0.14411397, -0.48588702 0.15207982 -0.14370434, -0.48485273 0.15124479 -0.1453578, -0.48488376 0.1512251 -0.14541389, -0.48559681 0.15185539 -0.14363144, -0.48559663 0.15168205 -0.14397813, -0.48552468 0.15208393 -0.14331622, -0.48506689 0.15123065 -0.14488102, -0.48441076 0.15117511 -0.1453674, -0.48400074 0.15115288 -0.14541207, -0.48537168 0.15229954 -0.1430123, -0.48534197 0.15141144 -0.14466129, -0.48482338 0.15125012 -0.14529757, -0.48555815 0.15161224 -0.14438675, -0.4851369 0.1524922 -0.14273305, -0.48521647 0.15135698 -0.14513312, -0.48526064 0.15134147 -0.14518137, -0.48400083 0.15104999 -0.14524268, -0.48570123 0.15182653 -0.14406441, -0.4848235 0.15265159 -0.14249407, -0.48439941 0.15115324 -0.14530481, -0.48400089 0.15113169 -0.1453483, -0.4857578 0.1520462 -0.14370503, -0.4844397 0.15276663 -0.14231355, -0.4844557 0.15280238 -0.14225908, -0.48400095 0.15282716 -0.1422096, -0.48479685 0.15124056 -0.14523648, -0.48400095 0.15279055 -0.14226599, -0.48571497 0.15226132 -0.14332427, -0.48577735 0.15227871 -0.14330645, -0.48550397 0.1520237 -0.14329489, -0.48517445 0.1513584 -0.14508079, -0.48532385 0.15136036 -0.1446216, -0.48534212 0.15223949 -0.14300509, -0.48550972 0.15150501 -0.14483728, -0.48556456 0.15149467 -0.14487465, -0.48552468 0.15156704 -0.14435025, -0.48510525 0.1524338 -0.14274357, -0.48400095 0.15109678 -0.14529105, -0.48479694 0.1525971 -0.1425233, -0.48442444 0.15271929 -0.14235897, -0.48400095 0.1527423 -0.14231275, -0.48532394 0.15217716 -0.14298801, -0.48508167 0.15237096 -0.14274205, -0.48556474 0.15246008 -0.14294361, -0.48550382 0.15151384 -0.14431484, -0.48577741 0.15167606 -0.1445118, -0.4847748 0.15253581 -0.14253969, -0.48441085 0.15266249 -0.14239235, -0.48400089 0.15268488 -0.14234777, -0.48506701 0.15230694 -0.14272876, -0.48439941 0.15259936 -0.14241226, -0.48400089 0.15262106 -0.14236899, -0.48400092 0.15255424 -0.14237542, -0.41328266 0.036688343 -0.12963106, -0.4132826 0.038305178 -0.13195731, -0.41337875 0.029449359 -0.11903886, -0.41328263 0.029449344 -0.11921583, -0.41328263 0.03025946 -0.12038113, -0.41729739 0.034273908 -0.11875887, -0.4180496 0.035101444 -0.11856334, -0.45121941 0.076240599 -0.11662783, -0.46017048 0.076239511 -0.10013129, -0.46006051 0.076236695 -0.048252568, -0.46408087 0.07623744 -0.061073855, -0.46006033 0.076237485 -0.063303843, -0.46408075 0.076236725 -0.048252568, -0.46206471 0.076237619 -0.065103754, -0.46608517 0.076237485 -0.062873855, -0.46608517 0.076238155 -0.075014934, -0.4620648 0.07623814 -0.07413815, -0.41220871 0.076241657 -0.13099648, -0.41291234 0.076241642 -0.1321048, -0.41220871 0.076241657 -0.13170017, -0.46119103 0.076238945 -0.088542238, -0.45717067 0.076238915 -0.087665513, -0.46017048 0.076238915 -0.089367256, -0.43528694 0.076240778 -0.11767228, -0.45717067 0.076239511 -0.098053947, -0.44968113 0.076240301 -0.11185656, -0.41291207 0.038409248 -0.13210715, -0.44428685 0.12616159 -0.048249707, -0.46650058 0.11280967 -0.048250511, -0.47150072 0.11631812 -0.048250422, -0.47150043 0.091384858 -0.048251584, -0.46650046 0.092543662 -0.048251584, -0.46506041 0.078236625 -0.048252568, -0.46006039 0.078236625 -0.048252419, -0.43969285 0.026445299 -0.048255399, -0.43469286 0.026445329 -0.048255399, -0.41878146 -0.016248047 -0.048257723, -0.43871316 0.024445191 -0.048255399, -0.43469286 0.02444534 -0.048255399, -0.41608736 -0.014928415 -0.048257723, -0.41520759 -0.016724557 -0.048257723, -0.41748151 -0.018902272 -0.048258051, -0.41790181 -0.018044055 -0.048257872, -0.41191396 -0.018902212 -0.048258051, -0.4315007 0.12616169 -0.048249707, -0.41716963 -0.019538909 -0.049808964, -0.41790181 -0.018043384 -0.061079249, -0.4168244 -0.020243436 -0.050672248, -0.41638535 -0.02113995 -0.051353768, -0.41736275 -0.019144401 -0.049043998, -0.41583231 -0.022268966 -0.051833227, -0.41520709 -0.023545578 -0.052008137, -0.41229883 -0.029482588 -0.061079755, -0.4122988 -0.02948305 -0.052008376, -0.41430315 -0.029482469 -0.062879875, -0.41951832 -0.018835098 -0.06287916, -0.41430306 -0.029482394 -0.065258369, -0.41279885 -0.032553598 -0.065258816, -0.41279873 -0.032553166 -0.075021133, -0.41951832 -0.018834442 -0.075020328, -0.41257021 -0.032553121 -0.075652823, -0.41257036 -0.024228767 -0.086920634, -0.41399387 -0.020120025 -0.088547662, -0.41557106 -0.016900271 -0.088547572, -0.4139939 -0.016127735 -0.090128496, -0.47150078 0.11631972 -0.075715914, -0.44428688 0.12616383 -0.088702902, -0.48016229 0.11318734 -0.088703588, -0.48016223 0.096230283 -0.088704452, -0.47150043 0.087567866 -0.075717553, -0.46217063 0.07823889 -0.088705614, -0.46217063 0.07823889 -0.088542089, -0.47150043 0.087567866 -0.07538487, -0.4315007 0.12616393 -0.088702902, -0.46506041 0.07823731 -0.061073765, -0.46006051 0.078237489 -0.063303843, -0.46206471 0.078237593 -0.065103754, -0.46706471 0.078237474 -0.062873676, -0.46706471 0.078238055 -0.075014934, -0.46206477 0.078238055 -0.07413815, -0.4571707 0.078238845 -0.087665454, -0.45717058 0.078238949 -0.088705614, -0.44169727 0.026446104 -0.062876657, -0.44169721 0.026446775 -0.075017795, -0.41399431 0.030064359 -0.10842036, -0.41337872 0.029448763 -0.10817657, -0.43680286 0.026447505 -0.088545248, -0.41399431 0.026448756 -0.10698853, -0.43969294 0.026446 -0.061076567, -0.4277316 0.15195021 -0.1339009, -0.42242128 0.14953892 -0.13872416, -0.42519587 0.15195023 -0.1339009, -0.46464068 0.14206976 -0.15366416, -0.47531471 0.13432665 -0.1691523, -0.46538949 0.14190702 -0.15398957, -0.46618694 0.14180698 -0.15418963, -0.46700072 0.14177363 -0.15425639, -0.4680064 0.14182475 -0.15415408, -0.46903092 0.14198898 -0.15382557, -0.48571095 0.14585139 -0.14609943, -0.46999717 0.14227213 -0.15325899, -0.47082499 0.14266285 -0.15247755, -0.47144938 0.14313221 -0.15153877, -0.49150077 0.13532014 -0.16716479, -0.49150071 0.13615657 -0.16549183, -0.47196165 0.14396144 -0.14988001, -0.47200081 0.14427325 -0.14925627, -0.47183803 0.14364079 -0.15052114, -0.48486903 0.14575054 -0.14630117, -0.46700075 0.14345066 -0.15425618, -0.46618691 0.14348395 -0.15418963, -0.46538958 0.14358413 -0.15398951, -0.46464065 0.14374676 -0.15366416, -0.42242119 0.13116689 -0.13872524, -0.47531483 0.13116819 -0.16915239, -0.42577013 0.1519502 -0.13290249, -0.4244701 0.15195014 -0.13215448, -0.42161956 0.1311667 -0.13711043, -0.42353767 0.13116646 -0.13359921, -0.41171953 0.13116653 -0.13141535, -0.42361417 0.13116649 -0.1336434, -0.47587699 0.13116778 -0.16370748, -0.42491436 0.13116655 -0.13439123, -0.48150069 0.13116762 -0.16186734, -0.48150077 0.13116707 -0.15077989, -0.44770268 0.13116488 -0.10871206, -0.44004861 0.13116466 -0.10223998, -0.44490138 0.13116436 -0.097242162, -0.43490142 0.13116443 -0.097242162, -0.44490144 0.1412674 -0.097241566, -0.41300637 0.15095019 -0.13215448, -0.41163573 0.15345019 -0.13136576, -0.41300634 0.15345022 -0.13215433, -0.41563171 0.15095022 -0.13366465, -0.42161971 0.14922813 -0.13710938, -0.42161947 0.10982648 -0.13711186, -0.41171947 0.12916647 -0.13141553, -0.42161962 0.1291668 -0.13711064, -0.41291252 0.10749057 -0.1321031, -0.41291237 0.078241646 -0.13210465, -0.41220871 0.078241557 -0.13170017, -0.41163498 0.037898719 -0.13137235, -0.42361394 0.10820939 -0.13364451, -0.42242113 0.11057958 -0.13872643, -0.47531471 0.12476926 -0.16915278, -0.42491421 0.10855822 -0.13439251, -0.49150071 0.12384237 -0.16716553, -0.49150059 0.10757096 -0.13227667, -0.47144148 0.096462011 -0.1084566, -0.47391966 0.089988187 -0.09457545, -0.42242113 0.12916683 -0.13872524, -0.4753148 0.12916823 -0.1691526, -0.42353764 0.12916659 -0.1335993, -0.42361417 0.12916662 -0.1336434, -0.47587696 0.12916782 -0.1637076, -0.42491436 0.12916651 -0.13439132, -0.48150066 0.12916769 -0.1618676, -0.4865008 0.12916787 -0.16549219, -0.48650077 0.12916698 -0.14902024, -0.48150066 0.12916709 -0.15077989, -0.4477028 0.12916496 -0.10871206, -0.44490138 0.12916434 -0.097242281, -0.44004849 0.12916465 -0.10224016, -0.43490145 0.12916444 -0.097242281, -0.41878146 -0.016248807 -0.033436313, -0.41878149 -0.016248137 -0.04625769, -0.42039797 -0.017041802 -0.013121799, -0.42039797 -0.017040804 -0.031636491, -0.41878149 -0.016247302 -0.061079159, -0.43871316 0.024445951 -0.061076894, -0.42039797 -0.017038956 -0.062879041, -0.44071758 0.024446085 -0.062876806, -0.44071758 0.024446651 -0.075018004, -0.42039797 -0.017038345 -0.075020209, -0.43582329 0.024447501 -0.088545248, -0.41645071 -0.01510413 -0.088547334, -0.41399404 -0.013900712 -0.091010347, -0.41399428 0.024448648 -0.10619675, -0.46650043 0.11280946 -0.046250507, -0.46650049 0.092543527 -0.04625164, -0.41608724 -0.014928609 -0.04625769, -0.41520759 -0.016724557 -0.046257839, -0.41191384 -0.018902406 -0.046257839, -0.42850086 0.14466436 -0.096059814, -0.42878965 0.14466439 -0.09560661, -0.42869309 0.14466436 -0.095665827, -0.42861223 0.14466435 -0.09574537, -0.42855147 0.14466426 -0.095840648, -0.42851368 0.14466436 -0.09594731, -0.43600082 0.14466426 -0.095741346, -0.43050095 0.14466435 -0.095741317, -0.4285008 0.14466438 -0.097241417, -0.43018594 0.14466424 -0.095088288, -0.43011731 0.14466427 -0.095061824, -0.43004426 0.14466436 -0.095052645, -0.43000078 0.14466426 -0.095055863, -0.43621781 0.1446643 -0.094790742, -0.43631259 0.14466421 -0.094850436, -0.4363918 0.14466426 -0.094929591, -0.43024603 0.14466433 -0.095130607, -0.43029395 0.14466433 -0.095186517, -0.42995825 0.14466432 -0.095065251, -0.43645123 0.1446642 -0.095024362, -0.4364883 0.14466427 -0.095130101, -0.43650088 0.14466426 -0.095241323, -0.43648836 0.1446643 -0.095352665, -0.43645123 0.1446642 -0.095458284, -0.43032697 0.14466432 -0.095252112, -0.42991748 0.14466433 -0.095080778, -0.45100084 0.14466424 -0.097241417, -0.4363918 0.14466426 -0.095553175, -0.43631265 0.14466433 -0.09563227, -0.43621781 0.1446642 -0.095691934, -0.43611208 0.14466427 -0.095728889, -0.45100084 0.14466424 -0.096969649, -0.43155029 0.14466426 -0.094458237, -0.4315134 0.14466432 -0.094352648, -0.43168899 0.14466423 -0.094632193, -0.43160984 0.14466423 -0.094553038, -0.43178383 0.14466426 -0.094691679, -0.43188956 0.1446642 -0.094728872, -0.43200079 0.14466424 -0.094741359, -0.43600082 0.14466426 -0.09474127, -0.43611214 0.14466427 -0.094753906, -0.42995813 0.12616427 -0.095066324, -0.42991734 0.12616429 -0.095081612, -0.43000066 0.12616429 -0.095056936, -0.4300442 0.1261643 -0.095053688, -0.42850065 0.1261643 -0.096061006, -0.42850065 0.12616442 -0.0972424, -0.45321944 0.078240544 -0.11581971, -0.43150067 0.12616399 -0.090702876, -0.4315007 0.12616423 -0.094242498, -0.43150058 0.1261615 -0.046456859, -0.41297254 -0.035553068 -0.075334206, -0.41261885 -0.035553023 -0.076311573, -0.4129996 -0.035553083 -0.075179681, -0.41299111 -0.035553098 -0.075266585, -0.41299757 -0.035553083 -0.075223222, -0.41299957 -0.035553813 -0.06246613, -0.4129996 -0.035553798 -0.062464193, -0.41299957 -0.035555542 -0.032053486, -0.41299957 -0.035556555 -0.012706742, -0.47297707 0.086899117 -0.075273141, -0.47302258 0.086991653 -0.075250283, -0.47299483 0.086935103 -0.075313583, -0.47300902 0.086964056 -0.075360999, -0.47293457 0.086812019 -0.07521458, -0.47303417 0.087015331 -0.07519789, -0.47295693 0.086857691 -0.075240001, -0.4730463 0.087040171 -0.075164065, -0.47297135 0.086887255 -0.074681297, -0.4730536 0.087055206 -0.075150475, -0.47306207 0.087072328 -0.075139984, -0.47288623 0.086713433 -0.07518287, -0.47283292 0.086604521 -0.075172767, -0.4729169 0.086775661 -0.074216202, -0.47289836 0.086738348 -0.073748842, -0.472767 0.086469248 -0.062459156, -0.47286269 0.08666493 -0.062487707, -0.47289836 0.086737767 -0.062522724, -0.47281849 0.086574435 -0.062466219, -0.49200049 0.11194949 -0.13088252, -0.48800054 0.11194892 -0.11817609, -0.48800066 0.11194944 -0.12646888, -0.48800057 0.1119488 -0.11682124, -0.49200055 0.11194824 -0.1067649, -0.48800057 0.1119488 -0.11736964, -0.49192396 0.11194818 -0.1059856, -0.49169704 0.11194815 -0.1052364, -0.49132839 0.11194806 -0.10454534, -0.47550085 0.13651694 -0.16812573, -0.41173515 0.15345028 -0.13402461, -0.41287211 0.15345031 -0.13425495, -0.41237536 0.15345031 -0.13419737, -0.42446998 0.15345006 -0.13215433, -0.42839298 0.15345022 -0.13425465, -0.47530082 0.13830853 -0.16901447, -0.47550067 0.13792686 -0.16977774, -0.47539267 0.13802324 -0.16958503, -0.47533181 0.13812706 -0.16937755, -0.47530738 0.13821726 -0.16919698, -0.47550067 0.13543828 -0.17028321, -0.48400086 0.14998718 -0.14118131, -0.48362988 0.14996698 -0.1412216, -0.48545012 0.14904831 -0.14305921, -0.48553953 0.14921039 -0.14273484, -0.48553964 0.1493775 -0.14240049, -0.48545009 0.1495398 -0.142076, -0.48527649 0.14968781 -0.14177997, -0.46780148 0.14348289 -0.15419175, -0.48502886 0.14981289 -0.1415299, -0.48472115 0.1499078 -0.14133991, -0.48437181 0.14996698 -0.1412216, -0.46862331 0.14358595 -0.15398566, -0.46967778 0.14383908 -0.15347938, -0.47060716 0.14421891 -0.1527196, -0.47132716 0.14469722 -0.15176265, -0.48297304 0.14877529 -0.14360543, -0.48272532 0.14890042 -0.14335512, -0.47200075 0.14595039 -0.14925607, -0.47182348 0.14529051 -0.1505758, -0.48328066 0.14868046 -0.14379509, -0.48255169 0.14904828 -0.14305942, -0.48362994 0.1486211 -0.14391373, -0.48246211 0.14921048 -0.14273484, -0.48400095 0.148601 -0.14395399, -0.48246208 0.1493775 -0.14240049, -0.48437193 0.14862102 -0.14391373, -0.48255152 0.1495398 -0.142076, -0.48472115 0.14868033 -0.1437953, -0.48272529 0.14968775 -0.14177997, -0.48502865 0.14877519 -0.14360543, -0.48297304 0.14981283 -0.14152987, -0.48527637 0.14890024 -0.14335512, -0.48328054 0.14990778 -0.14133991, -0.48434058 0.14865103 -0.14378737, -0.48463425 0.14869575 -0.14361782, -0.48432705 0.1486437 -0.14372201, -0.4854103 0.14919084 -0.14270745, -0.48535386 0.14930891 -0.14239152, -0.48535392 0.14916202 -0.14268537, -0.48435578 0.14864324 -0.14385237, -0.48400095 0.14863259 -0.14382441, -0.48400086 0.14862408 -0.14389099, -0.48469025 0.14987464 -0.14138947, -0.48435572 0.14993136 -0.14127611, -0.48494235 0.14974275 -0.14160378, -0.48466071 0.14982966 -0.14142998, -0.48463419 0.14977513 -0.14145885, -0.4846901 0.1487 -0.14373894, -0.4846606 0.14870518 -0.14367886, -0.48541033 0.14934392 -0.14240132, -0.4852753 0.14901936 -0.14297079, -0.48530665 0.14912198 -0.14265914, -0.4852308 0.14898445 -0.14293428, -0.48490462 0.14969161 -0.14162596, -0.4851225 0.14958163 -0.14184584, -0.48487312 0.1496333 -0.14163633, -0.48508349 0.14952706 -0.14184876, -0.48508337 0.14885889 -0.14318557, -0.48519745 0.14893919 -0.1428975, -0.48430184 0.14963135 -0.14137127, -0.48400095 0.14958471 -0.14131542, -0.48429996 0.14956839 -0.14134796, -0.48505428 0.14881712 -0.14314185, -0.48400071 0.14964776 -0.14133857, -0.48523071 0.14940158 -0.14209993, -0.48505408 0.14946719 -0.14184149, -0.48519742 0.14934506 -0.14208587, -0.48484936 0.14871375 -0.14334841, -0.4850359 0.14876606 -0.14310236, -0.4848347 0.14866452 -0.14330526, -0.48430699 0.14969769 -0.14138035, -0.48400071 0.14971432 -0.14134698, -0.48527119 0.14921108 -0.1423537, -0.48517662 0.14928479 -0.14206453, -0.48524925 0.14915317 -0.14232786, -0.4845852 0.14858747 -0.14345919, -0.48482978 0.14860727 -0.14327036, -0.48524925 0.14901763 -0.1425987, -0.4852418 0.14909308 -0.14229853, -0.48524171 0.14895834 -0.14256819, -0.4845852 0.14958331 -0.14146732, -0.48458186 0.14952064 -0.14144351, -0.48458174 0.14853077 -0.14342351, -0.4854733 0.14920734 -0.14272426, -0.48498431 0.1497837 -0.14157124, -0.48431557 0.14976414 -0.14137472, -0.4854733 0.14936712 -0.14240445, -0.48400089 0.1497813 -0.14134045, -0.48532841 0.14904229 -0.1430047, -0.48516938 0.14962809 -0.1418329, -0.4845956 0.14964886 -0.14147823, -0.48527527 0.14945163 -0.14210622, -0.48483473 0.14950636 -0.14162146, -0.48482969 0.14944407 -0.14159666, -0.48512256 0.14888926 -0.14323099, -0.48487321 0.14875275 -0.1433977, -0.48530671 0.14926383 -0.14237522, -0.48400098 0.14995059 -0.14123745, -0.48432711 0.14982738 -0.14135458, -0.4840008 0.14984491 -0.14131926, -0.48459545 0.14863543 -0.1435052, -0.48527113 0.14907315 -0.14262961, -0.48461214 0.14971384 -0.14147516, -0.48430172 0.14853945 -0.14355536, -0.48429996 0.14848299 -0.14351903, -0.48517665 0.148886 -0.14286225, -0.48516965 0.14882745 -0.14282988, -0.48400089 0.14846683 -0.14355154, -0.48400086 0.14852317 -0.14358814, -0.48484936 0.14957049 -0.14163481, -0.4853878 0.14905216 -0.14303465, -0.48522159 0.14966401 -0.14181052, -0.48503587 0.14940482 -0.14182435, -0.48502952 0.14934321 -0.14179833, -0.48516926 0.14890677 -0.14327572, -0.48532844 0.14949258 -0.14210398, -0.48490456 0.1487793 -0.14345081, -0.48434064 0.14988394 -0.14132129, -0.48400086 0.14990242 -0.14128427, -0.4846122 0.14867218 -0.14355887, -0.48430702 0.14858645 -0.14360295, -0.48400089 0.14857 -0.14363624, -0.48522162 0.14891043 -0.14331789, -0.48502949 0.14870815 -0.1430686, -0.48516956 0.14922386 -0.14203702, -0.48494226 0.14879216 -0.1435049, -0.48538771 0.14952247 -0.14209385, -0.48431566 0.14862187 -0.14365955, -0.48400101 0.14860491 -0.14369376, -0.48498437 0.14879087 -0.14355718, -0.48400089 0.14862609 -0.14375745, -0.49192399 0.1519483 -0.106539, -0.49200079 0.1519482 -0.10731946, -0.49169645 0.15194823 -0.10578869, -0.49132684 0.15194824 -0.10509713, -0.49082938 0.15194811 -0.10449098, -0.4880009 0.15194896 -0.11824827, -0.4880009 0.15194908 -0.11965747, -0.49200082 0.15194961 -0.13145639, -0.48800093 0.15194945 -0.12728556, -0.4880009 0.15194902 -0.11885349, -0.48800078 0.11223429 -0.12836851, -0.4880006 0.11205773 -0.12765832, -0.48800078 0.11248542 -0.12901689, -0.48800072 0.12540951 -0.14703824, -0.48800081 0.13834217 -0.14687516, -0.48800093 0.15138148 -0.12982355, -0.4880009 0.13530269 -0.16085453, -0.48800081 0.13468294 -0.16108535, -0.4880009 0.13579741 -0.16051988, -0.48800072 0.12674434 -0.159591, -0.48800084 0.13616697 -0.16013272, -0.4880009 0.13632949 -0.15990134, -0.48800078 0.13403495 -0.16116054, -0.48800084 0.13646661 -0.15965717, -0.48800075 0.12799525 -0.16088338, -0.48800078 0.12752876 -0.16058944, -0.48800075 0.12851065 -0.16107355, -0.48800078 0.12709615 -0.16015927, -0.48800072 0.12885882 -0.16113921, -0.48800069 0.12920864 -0.16116069, -0.48800078 0.13716443 -0.14836155, -0.48800072 0.13771923 -0.14783297, -0.48800072 0.13660689 -0.14868377, -0.48800072 0.1362157 -0.14880441, -0.48800072 0.13582996 -0.14884387, -0.48800102 0.15188503 -0.12817965, -0.48800084 0.15169147 -0.12904416, -0.48800078 0.12769923 -0.14884414, -0.48800066 0.12759772 -0.14884154, -0.48800066 0.12717769 -0.14877079, -0.48800072 0.12676272 -0.14860122, -0.48800066 0.1263666 -0.14833345, -0.48800072 0.12600222 -0.14797451, -0.48800072 0.1256806 -0.14753707, -0.48797539 0.12760977 -0.1486185, -0.48797542 0.12769926 -0.1486205, -0.48790053 0.12769909 -0.14840819, -0.48790085 0.12762123 -0.14840667, -0.4877803 0.12769918 -0.1482179, -0.48778066 0.12763147 -0.14821674, -0.47550067 0.137777 -0.17040493, -0.47550067 0.13813446 -0.1703196, -0.47550067 0.13806958 -0.17031614, -0.47550085 0.1380138 -0.17029907, -0.47550073 0.13796833 -0.17027228, -0.47550067 0.13792957 -0.17023645, -0.4755007 0.13789858 -0.17019369, -0.47550067 0.13787648 -0.17014568, -0.47550079 0.13786335 -0.17009483, -0.47550073 0.13734557 -0.17043762, -0.47550067 0.13785808 -0.17004226, -0.47550073 0.13786229 -0.16997184, -0.47550067 0.13787948 -0.16989492, -0.47550067 0.13790064 -0.16983537, -0.47550073 0.13534825 -0.17043771, -0.47550067 0.13819884 -0.17030762, -0.47565889 0.13734563 -0.17051129, -0.47565752 0.13531449 -0.17051102, -0.47582719 0.13734566 -0.17055635, -0.47582611 0.13529786 -0.17055647, -0.47600076 0.13734558 -0.17057161, -0.47600076 0.13529399 -0.17057173, -0.41249964 -0.035357282 -0.076905593, -0.41255388 -0.035530716 -0.076521173, -0.41251311 -0.035464033 -0.076723769, -0.4124997 -0.026319817 -0.089138761, -0.46302098 0.076826423 -0.089133129, -0.47281101 0.086615324 -0.075327352, -0.41249964 -0.032483965 -0.035722867, -0.41249964 -0.032482713 -0.058794424, -0.4124929 -0.032497853 -0.035556808, -0.41681257 -0.02367802 -0.043708131, -0.4124721 -0.032540202 -0.035392299, -0.41728821 -0.02270709 -0.043843463, -0.41242713 -0.032632187 -0.035198912, -0.41768304 -0.021900982 -0.044184968, -0.41829985 -0.020641357 -0.049097285, -0.47289854 0.09082973 -0.060244575, -0.41809073 -0.0210682 -0.049664751, -0.41785088 -0.021557823 -0.050105676, -0.41235623 -0.032776937 -0.035015866, -0.41296896 -0.031525165 -0.043708518, -0.41296896 -0.031524763 -0.050808534, -0.41198885 -0.033526972 -0.034265861, -0.47289851 0.0908283 -0.034258857, -0.41845626 -0.020322129 -0.04841648, -0.41801253 -0.021228299 -0.044688657, -0.41854054 -0.02015017 -0.047656283, -0.41854089 -0.02014938 -0.046867087, -0.41845748 -0.020319879 -0.046106413, -0.41235611 -0.032775611 -0.059501454, -0.41759989 -0.022070318 -0.050423399, -0.41241229 -0.032661095 -0.059364542, -0.41735286 -0.022574753 -0.050632462, -0.41245613 -0.03257148 -0.059206173, -0.4170678 -0.023156732 -0.050769672, -0.41198885 -0.033525512 -0.060251668, -0.41248879 -0.032504737 -0.05900307, -0.41681269 -0.023677617 -0.050808206, -0.41828066 -0.020680889 -0.045355484, -0.41249931 -0.026301712 -0.089163497, -0.4124997 -0.025678918 -0.089573041, -0.41250002 0.025817111 -0.10996519, -0.41249064 -0.025865525 -0.08949928, -0.4620437 0.075471759 -0.089567289, -0.41249129 0.025921226 -0.11001323, -0.41249999 0.026448861 -0.11089478, -0.41250002 0.026449546 -0.11984266, -0.46193746 0.075884566 -0.090310469, -0.41250408 0.02645351 -0.11993222, -0.412496 0.026444867 -0.11080502, -0.41248378 0.026432708 -0.11071573, -0.47426119 0.088208452 -0.094977334, -0.4626064 0.076553524 -0.08996205, -0.46292982 0.076876894 -0.08971031, -0.46316823 0.077115193 -0.089442089, -0.49270764 0.10665531 -0.10676523, -0.49270764 0.10665676 -0.13301556, -0.4754979 0.089445069 -0.096110269, -0.49246064 0.10640824 -0.10538112, -0.49264601 0.10659365 -0.10606609, -0.49227145 0.1062191 -0.10494886, -0.49203554 0.10598303 -0.10454588, -0.47371581 0.087662041 -0.07707797, -0.4743984 0.088345736 -0.094946429, -0.4745439 0.088491127 -0.094962493, -0.47469535 0.088642612 -0.095027611, -0.4748508 0.088798046 -0.095141426, -0.47506019 0.089007378 -0.095367327, -0.47528413 0.089231357 -0.095700189, -0.47333291 0.087279156 -0.076415852, -0.47294155 0.086887777 -0.075659469, -0.47313735 0.087083429 -0.075978503, -0.47294441 0.086890578 -0.07565029, -0.47297749 0.086923689 -0.075528279, -0.41250008 0.035697773 -0.13346221, -0.41250014 0.026628345 -0.12041362, -0.41673058 0.037391007 -0.12810238, -0.41250101 0.035724282 -0.13349853, -0.41300002 0.033660531 -0.12960978, -0.41736934 0.03799817 -0.12779914, -0.41810963 0.038626283 -0.12733848, -0.41300011 0.028636172 -0.12238093, -0.4125044 0.026577622 -0.12033223, -0.41904759 0.039302081 -0.12658216, -0.41887385 0.034509733 -0.12000732, -0.42164096 0.039732546 -0.12242256, -0.47174564 0.094966874 -0.10955904, -0.42145857 0.039951995 -0.12307449, -0.4211807 0.040064096 -0.12374778, -0.42082173 0.040069371 -0.12441663, -0.42040068 0.039975494 -0.12505756, -0.4197782 0.039720029 -0.12583743, -0.42121178 0.037677735 -0.12025698, -0.47427893 0.088349715 -0.095370546, -0.42169008 0.038961947 -0.12122332, -0.41988546 0.035673022 -0.11981682, -0.42072025 0.036832228 -0.1199462, -0.41673315 0.037373066 -0.12806429, -0.41300002 0.033640087 -0.12957276, -0.41300002 0.03362757 -0.12953235, -0.41673139 0.037358746 -0.12802465, -0.41300002 0.033623427 -0.1294895, -0.41672534 0.037348628 -0.12798415, -0.41256168 0.10620275 -0.13388751, -0.41263822 0.10629615 -0.13388743, -0.41227141 0.10666767 -0.13388751, -0.41274807 0.10638347 -0.13388751, -0.4125216 0.10612054 -0.13388751, -0.41204041 0.10667662 -0.13388743, -0.41250589 0.10605909 -0.13388751, -0.41294315 0.10648482 -0.13388743, -0.41250053 0.1059967 -0.13388751, -0.41134849 0.10685909 -0.13388751, -0.41124156 0.1069275 -0.13388743, -0.41151786 0.10678296 -0.13388743, -0.4118183 0.10670438 -0.13388743, -0.41327959 0.10658722 -0.13388751, -0.41100958 0.10727115 -0.13388743, -0.41103768 0.10717782 -0.13388751, -0.41108549 0.1070883 -0.13388751, -0.41115364 0.10700442 -0.13388743, -0.41250008 0.036639288 -0.13389148, -0.41249105 0.036518872 -0.13389148, -0.41412401 0.10666767 -0.13388751, -0.47353423 0.12310269 -0.16912816, -0.49200049 0.10645755 -0.13343816, -0.49200061 0.12204508 -0.1668608, -0.47123706 0.095905811 -0.11081301, -0.47178105 0.095768988 -0.11051933, -0.47212896 0.095624506 -0.11020957, -0.47242495 0.095390216 -0.10970734, -0.47247046 0.095307425 -0.10952948, -0.47479072 0.089245945 -0.096532837, -0.47086242 0.094999507 -0.11030827, -0.4730356 0.12400904 -0.16957222, -0.47471151 0.13462746 -0.17053558, -0.47471145 0.12573968 -0.17053603, -0.47347048 0.12415893 -0.16982247, -0.47466198 0.12537299 -0.17050768, -0.47470871 0.12565447 -0.17053463, -0.47386792 0.12436874 -0.17005102, -0.47455344 0.12509401 -0.17044522, -0.47415099 0.12458275 -0.17021383, -0.47438186 0.12482746 -0.17034666, -0.4748691 0.12573972 -0.17060925, -0.47492412 0.13480701 -0.17062701, -0.47503689 0.12573962 -0.17065422, -0.47506616 0.13491544 -0.17065836, -0.4752101 0.12573966 -0.17066933, -0.47521016 0.13501708 -0.17066871, -0.47514042 0.12522277 -0.17062892, -0.47502074 0.12482716 -0.17054094, -0.47521788 0.12497833 -0.17057584, -0.47529027 0.12529552 -0.17063345, -0.47511318 0.12562507 -0.17066298, -0.47501543 0.12525788 -0.17062332, -0.47490409 0.12563941 -0.17062052, -0.47489741 0.12488917 -0.17054431, -0.47485271 0.12530786 -0.17058994, -0.47473764 0.1249778 -0.17052035, -0.47466215 0.12537295 -0.17050783, -0.47309628 0.1237783 -0.16957442, -0.47318196 0.1235607 -0.16952704, -0.47532687 0.12561205 -0.17065983, -0.4740797 0.12360127 -0.16982208, -0.47420382 0.12348637 -0.16971065, -0.4734073 0.12321298 -0.16929744, -0.47396067 0.12374003 -0.1699021, -0.47328767 0.12336871 -0.1694328, -0.47381476 0.12395751 -0.16995727, -0.47458985 0.12408996 -0.17021506, -0.47471532 0.12399264 -0.17015161, -0.47446981 0.12420006 -0.17025314, -0.4743171 0.12436385 -0.17026438, -0.47483641 0.12444505 -0.17040251, -0.47502851 0.12448993 -0.17041837, -0.47471467 0.12453231 -0.17042066, -0.47415137 0.12458226 -0.17021398, -0.47455835 0.12465939 -0.17041145, -0.47438225 0.12482707 -0.17034696, -0.46126691 0.067079321 -0.010695651, -0.4627519 0.066352084 -0.012349352, -0.41291878 -0.035388872 -0.012354955, -0.4639757 0.068850473 -0.01013051, -0.46178153 0.068129972 -0.0097626001, -0.46174243 0.068050295 -0.010016307, -0.46388271 0.0686609 -0.010733739, -0.46167958 0.067921877 -0.010243848, -0.46373323 0.068355694 -0.01127483, -0.46159598 0.067751288 -0.010433897, -0.46353456 0.067949876 -0.011726573, -0.46149591 0.067546979 -0.0105768, -0.46329641 0.067463979 -0.012066588, -0.46138427 0.067319095 -0.010665551, -0.46303108 0.066922292 -0.012277678, -0.41300002 0.033813417 -0.12919115, -0.41299996 0.033495024 -0.12584238, -0.41300002 0.033873394 -0.12915458, -0.41300014 0.033935308 -0.12912558, -0.41299999 0.028665379 -0.12241475, -0.41300017 0.037209585 -0.12257524, -0.41300017 0.036832616 -0.12231509, -0.41300005 0.038493782 -0.12091084, -0.41300002 0.028703898 -0.12244482, -0.41300002 0.033066839 -0.12567993, -0.41300014 0.033654168 -0.12936674, -0.41300002 0.033693731 -0.12930344, -0.41300002 0.033747926 -0.1292436, -0.41300002 0.036404327 -0.12215276, -0.41300002 0.037723809 -0.12041251, -0.41300002 0.033630848 -0.12943004, -0.41300002 0.03268984 -0.1254199, -0.41300002 0.032386079 -0.12507696, -0.41300014 0.035949603 -0.12209745, -0.41300002 0.03686063 -0.12010257, -0.41300002 0.035949424 -0.11999755, -0.41300005 0.03825368 -0.12726723, -0.41300005 0.037209705 -0.1254196, -0.41300005 0.038937896 -0.12665652, -0.41300002 0.035554469 -0.1200171, -0.41300002 0.03751342 -0.12507682, -0.41300005 0.03946507 -0.12590583, -0.41300002 0.037448242 -0.12770616, -0.41300002 0.036832735 -0.12567984, -0.41300002 0.037726253 -0.12467118, -0.41300008 0.039807409 -0.12505509, -0.41300002 0.036404446 -0.12584229, -0.41300002 0.037835836 -0.12422644, -0.41300002 0.035163388 -0.12007551, -0.41300005 0.039946795 -0.12414841, -0.41300002 0.033949643 -0.12209745, -0.41300014 0.034780055 -0.12017234, -0.41300002 0.03306666 -0.12231536, -0.41300014 0.033494964 -0.12215276, -0.41300002 0.032063559 -0.12422667, -0.41300002 0.029135734 -0.12245308, -0.41299996 0.032063469 -0.12376864, -0.41300002 0.035949752 -0.12589748, -0.41300002 0.032173112 -0.1233239, -0.41300002 0.032386005 -0.1229182, -0.41300002 0.032689705 -0.12257533, -0.41299999 0.032173172 -0.12467153, -0.41299999 0.028995797 -0.12249188, -0.41300005 0.037835792 -0.1237684, -0.41300008 0.039876193 -0.12323399, -0.41300014 0.037726164 -0.12332354, -0.41300005 0.039599001 -0.12235959, -0.41300014 0.028864473 -0.12249632, -0.41300005 0.037513331 -0.12291797, -0.41300005 0.039130002 -0.12157162, -0.41299999 0.028768137 -0.12247588, -0.41300002 0.033949733 -0.1258976, -0.41975206 0.035949513 -0.11999746, -0.41865256 0.034779176 -0.12017255, -0.4186545 0.034778684 -0.12017278, -0.418657 0.03477791 -0.12017302, -0.41864964 0.034779683 -0.12017243, -0.41865864 0.03477715 -0.12017329, -0.41864794 0.034779847 -0.12017234, -0.41865888 0.034777045 -0.12017329, -0.41866043 0.034776136 -0.12017353, -0.41864452 0.034779951 -0.12017225, -0.41866282 0.034774363 -0.12017421, -0.41651323 0.037448272 -0.12770616, -0.41766042 0.03842257 -0.12714143, -0.41887131 0.039250582 -0.12625666, -0.4199203 0.039765045 -0.12519883, -0.42066023 0.039945036 -0.12418954, -0.42111653 0.039894238 -0.12333421, -0.42138323 0.03969267 -0.12258704, -0.42149577 0.039396375 -0.12196763, -0.42149565 0.039052978 -0.12147386, -0.42140856 0.038655609 -0.12105171, -0.42124686 0.038223043 -0.12070642, -0.42102629 0.03777346 -0.12043746, -0.42066744 0.037173375 -0.12018923, -0.42021853 0.036535084 -0.1200407, -0.44386083 0.039477542 -0.01069741, -0.45738044 0.067079335 -0.010695651, -0.4110001 0.037529081 -0.010697499, -0.42499998 0.012357429 -0.01069878, -0.41099992 0.012357473 -0.01069878, -0.4413721 0.037528858 -0.010697499, -0.42527154 0.012331173 -0.01069878, -0.42555073 0.012248084 -0.01069878, -0.42588571 0.012065053 -0.010698661, -0.4262338 0.011755079 -0.010698661, -0.44179174 0.037581682 -0.01069741, -0.42659393 0.011237428 -0.01069878, -0.44224045 0.037746996 -0.01069741, -0.42688131 0.010488555 -0.010699019, -0.44269243 0.038026199 -0.01069741, -0.42699993 0.0095290244 -0.010698929, -0.44311902 0.038405746 -0.01069741, -0.44353458 0.038918346 -0.010697231, -0.45757076 0.068118274 -0.0098141283, -0.45741376 0.068118587 -0.0098141879, -0.4574078 0.06806387 -0.0099836439, -0.45777431 0.068118289 -0.0098141283, -0.4575375 0.06805031 -0.010016307, -0.45740023 0.067985907 -0.010144457, -0.45774093 0.068050206 -0.010016486, -0.4574745 0.067921847 -0.010243848, -0.45739213 0.06788449 -0.010293141, -0.45742181 0.067814082 -0.010373458, -0.45738751 0.067814067 -0.010373458, -0.45738354 0.067736074 -0.010446981, -0.45767799 0.067921847 -0.010243848, -0.45762527 0.067814052 -0.010373309, -0.45758718 0.067736089 -0.010446981, -0.45738244 0.067538768 -0.010581091, -0.45749047 0.067538783 -0.010581091, -0.4573814 0.067315966 -0.010666326, -0.43642095 0.13947174 -0.095741555, -0.43687204 0.13907209 -0.095741674, -0.43721455 0.13857616 -0.095741764, -0.4358874 0.13975194 -0.095741555, -0.43742809 0.13801256 -0.095741764, -0.43530223 0.13989618 -0.095741555, -0.43750075 0.13741429 -0.095741764, -0.43469954 0.13989612 -0.095741555, -0.43411431 0.13975193 -0.095741555, -0.43358067 0.13947177 -0.095741674, -0.43312958 0.13907218 -0.095741674, -0.43278721 0.13857616 -0.095741555, -0.43257344 0.13801256 -0.095741764, -0.43250075 0.13741434 -0.095741764, -0.43742821 0.13681602 -0.095741764, -0.43721452 0.13625252 -0.095741913, -0.43687204 0.13575642 -0.095741764, -0.43642095 0.13535683 -0.095741913, -0.43588731 0.1350767 -0.095741913, -0.43530214 0.13493256 -0.095742002, -0.43469939 0.13493249 -0.095741913, -0.43411431 0.13507669 -0.095741764, -0.43050078 0.12616436 -0.09574236, -0.43358061 0.13535687 -0.095741913, -0.4331294 0.13575652 -0.095741913, -0.43278721 0.13625246 -0.095741913, -0.43257341 0.13681597 -0.095741913, -0.43600062 0.12616426 -0.095742151, -0.43750077 0.13741447 -0.097241923, -0.43742815 0.13801265 -0.097241685, -0.43721452 0.13857624 -0.097241685, -0.43687207 0.13907219 -0.097241566, -0.43642107 0.13947196 -0.097241566, -0.43588719 0.1397519 -0.097241685, -0.43530229 0.13989624 -0.097241566, -0.43469939 0.13989626 -0.097241566, -0.43411425 0.13975196 -0.097241566, -0.43358061 0.13947186 -0.097241566, -0.4331294 0.13907222 -0.097241685, -0.43278709 0.13857618 -0.097241774, -0.43257341 0.13801265 -0.097241923, -0.43250069 0.13741437 -0.097241774, -0.48650089 0.12601809 -0.14902045, -0.48650077 0.12526898 -0.16549258, -0.48650056 0.11089729 -0.13467686, -0.48650062 0.11089629 -0.11659651, -0.45100078 0.1445284 -0.097241417, -0.47150049 0.087293521 -0.0628732, -0.47150049 0.087294176 -0.075014278, -0.46217057 0.078239441 -0.099323019, -0.46217057 0.078239039 -0.090705648, -0.49150059 0.10756953 -0.10570498, -0.48149595 0.097564146 -0.090704456, -0.47150055 0.091385558 -0.06107302, -0.48773763 0.11044779 -0.10006268, -0.49150056 0.11044821 -0.10570489, -0.48149616 0.11270504 -0.090703622, -0.49150062 0.11044975 -0.13371731, -0.4877376 0.11044976 -0.13371731, -0.42447001 0.15095016 -0.13215448, -0.42360133 0.15095022 -0.13366465, -0.49150071 0.12526894 -0.16549258, -0.44428688 0.12616394 -0.090702906, -0.44899487 0.12616432 -0.0972424, -0.44490147 0.12881567 -0.097242281, -0.41266418 0.026448816 -0.10698853, -0.41266415 0.024448678 -0.10619651, -0.41268182 -0.013257876 -0.091264978, -0.412029 -0.015165195 -0.090509668, -0.46069446 0.067359746 -0.012179717, -0.46153483 0.069630146 -0.0098857135, -0.46150437 0.069550216 -0.010265931, -0.46143213 0.069358841 -0.010757521, -0.46132758 0.069080785 -0.011198536, -0.46119502 0.068725377 -0.011574581, -0.46104133 0.068309784 -0.011869028, -0.4608722 0.067848295 -0.012073025, -0.41196018 -0.018807709 -0.047594473, -0.41196018 -0.018807769 -0.046921238, -0.46099427 0.069171995 -0.011073545, -0.46105435 0.069443792 -0.010572121, -0.46114305 0.069171995 -0.011073545, -0.46120301 0.069443792 -0.010572061, -0.46091762 0.068811849 -0.011496022, -0.45554492 0.068811893 -0.011495933, -0.46106628 0.068811879 -0.011496022, -0.46081853 0.068328574 -0.01185821, -0.45544589 0.068328604 -0.011858061, -0.46096733 0.068328515 -0.01185821, -0.46072355 0.067848235 -0.012072667, -0.45535094 0.067848355 -0.012072667, -0.46062896 0.067359775 -0.01217936, -0.45525613 0.067359805 -0.01217936, -0.45511344 0.06784831 -0.012072667, -0.45501879 0.067359805 -0.01217936, -0.46109024 0.069602281 -0.010049865, -0.46123901 0.069602326 -0.010049686, -0.43642089 0.13535692 -0.097241923, -0.43257347 0.13681614 -0.097241774, -0.43312952 0.13575664 -0.097241774, -0.43278715 0.13625267 -0.097241923, -0.43742815 0.13681607 -0.097241923, -0.43721452 0.1362526 -0.097241923, -0.43687198 0.13575654 -0.097241923, -0.43588731 0.13507682 -0.097241923, -0.43530211 0.13493259 -0.097241923, -0.43469939 0.13493259 -0.097241923, -0.43411431 0.13507687 -0.097241923, -0.43358073 0.13535707 -0.097241923, -0.4360007 0.12616424 -0.094742492, -0.43200067 0.12616432 -0.094742343, -0.42855138 0.12616436 -0.095841691, -0.42851344 0.12616426 -0.095948502, -0.43611196 0.12616418 -0.094754949, -0.42861214 0.12616432 -0.095746413, -0.42869285 0.12616438 -0.0956669, -0.42878935 0.12616424 -0.095607832, -0.43611193 0.12616424 -0.095729753, -0.43621776 0.12616429 -0.095692888, -0.43631253 0.12616433 -0.095633194, -0.43639162 0.12616436 -0.095554277, -0.43645111 0.12616421 -0.095459357, -0.43648824 0.12616433 -0.095353648, -0.43011716 0.1261643 -0.095062807, -0.43032679 0.12616435 -0.095253274, -0.4365007 0.12616421 -0.095242307, -0.43648818 0.12616424 -0.095131204, -0.43645123 0.12616426 -0.095025584, -0.43018582 0.12616423 -0.095089331, -0.43639162 0.12616421 -0.094930574, -0.43631253 0.12616423 -0.094851568, -0.4362177 0.12616418 -0.094791815, -0.4302938 0.12616429 -0.09518759, -0.43024573 0.12616423 -0.0951318, -0.43155032 0.12616438 -0.09445931, -0.43168902 0.12616436 -0.094633415, -0.4316099 0.12616433 -0.094554111, -0.43178383 0.12616435 -0.094692901, -0.4315134 0.12616439 -0.094353542, -0.43188956 0.12616435 -0.094729766, -0.4315252 0.14467022 -0.046301767, -0.4315069 0.14466375 -0.046378538, -0.43157503 0.14468792 -0.046193793, -0.43164721 0.14471355 -0.04610233, -0.43151429 0.12615639 -0.046341047, -0.43155023 0.12614277 -0.046240136, -0.43159339 0.12612624 -0.046166852, -0.43164715 0.12610564 -0.046103314, -0.41266415 0.026448667 -0.10563393, -0.41266415 0.024448618 -0.10563393, -0.43469271 0.02444613 -0.063306794, -0.4366971 0.024446219 -0.065106735, -0.4366971 0.024446756 -0.074141279, -0.43246803 0.024447396 -0.085830286, -0.43469286 0.026446164 -0.063306645, -0.43669713 0.026446179 -0.065106735, -0.43669713 0.026446775 -0.07414104, -0.43246791 0.026447445 -0.085830286, -0.42361429 0.14689502 -0.13364224, -0.42491445 0.14689511 -0.13439049, -0.42446986 0.14779882 -0.13215475, -0.42577025 0.14779907 -0.13290255, -0.41220874 0.078241646 -0.13099636, -0.4571707 0.078239068 -0.090705529, -0.45717058 0.078239456 -0.098053858, -0.44968113 0.078240305 -0.11185656, -0.43528697 0.078240708 -0.11767222, -0.47649613 0.1091965 -0.088703856, -0.47649601 0.10919651 -0.090704009, -0.47649607 0.099635229 -0.088704333, -0.47649595 0.099635258 -0.090704456, -0.46260667 0.14994636 -0.069834784, -0.46342003 0.14994647 -0.071384266, -0.46317187 0.14994647 -0.071555451, -0.46201143 0.14994638 -0.070245489, -0.46516973 0.14994653 -0.072934344, -0.46524182 0.14994653 -0.072641715, -0.46328294 0.14994636 -0.069578156, -0.4637017 0.14994648 -0.071277454, -0.46317202 0.14994666 -0.073426709, -0.46260661 0.14994672 -0.075147375, -0.46201152 0.14994672 -0.07473655, -0.46430004 0.14994648 -0.071277365, -0.46400073 0.14994648 -0.071240947, -0.46297228 0.14994666 -0.073201135, -0.461532 0.14994673 -0.074195459, -0.46341997 0.14994654 -0.073597983, -0.463283 0.14994672 -0.075403944, -0.46524182 0.14994653 -0.072340384, -0.46283218 0.14994659 -0.072934344, -0.4611958 0.14994664 -0.073554888, -0.46458191 0.14994648 -0.071384266, -0.46370167 0.1499466 -0.073704705, -0.46516964 0.14994644 -0.072047636, -0.46482983 0.1499465 -0.071555451, -0.46275997 0.14994648 -0.072641626, -0.46102265 0.14994654 -0.072852716, -0.4650296 0.14994648 -0.071780846, -0.46400076 0.14994654 -0.073741034, -0.46275997 0.14994648 -0.072340325, -0.4610227 0.14994654 -0.072129473, -0.46119592 0.14994653 -0.071427211, -0.46429998 0.1499466 -0.073704705, -0.462832 0.14994651 -0.072047636, -0.46153194 0.14994642 -0.070786849, -0.46458182 0.14994662 -0.073597685, -0.4629721 0.14994648 -0.071780846, -0.46482977 0.14994659 -0.073426709, -0.46502963 0.14994662 -0.073201135, -0.46370175 0.15314646 -0.071277276, -0.46341997 0.15314649 -0.071384266, -0.4631719 0.15314642 -0.071555272, -0.4629721 0.15314648 -0.071780786, -0.46283212 0.15314654 -0.072047576, -0.46275991 0.15314649 -0.072340325, -0.46275991 0.15314649 -0.072641596, -0.46283212 0.15314654 -0.072934017, -0.46297213 0.15314664 -0.073201135, -0.46317193 0.15314659 -0.0734265, -0.46342 0.15314659 -0.073597685, -0.46370173 0.15314665 -0.073704526, -0.48655036 0.15225841 -0.14334698, -0.48632589 0.15252303 -0.14281775, -0.48274094 0.15261333 -0.14263697, -0.48250929 0.15294378 -0.14197619, -0.48203546 0.15275601 -0.14235173, -0.48662657 0.1519774 -0.14390905, -0.48243707 0.15246001 -0.14294381, -0.48167595 0.15252301 -0.14281766, -0.48311788 0.15272966 -0.14240439, -0.48306987 0.15307529 -0.14171307, -0.48222438 0.15227865 -0.14330648, -0.48145133 0.15225837 -0.14334719, -0.48137501 0.13917784 -0.16951193, -0.48311803 0.15122521 -0.14541389, -0.48274091 0.15134148 -0.14518137, -0.48354626 0.15115252 -0.14555909, -0.48354629 0.15280235 -0.14225908, -0.48368439 0.153143 -0.14157771, -0.48137513 0.15197732 -0.14390905, -0.48662648 0.13950019 -0.1688671, -0.4821147 0.15207984 -0.14370434, -0.48431742 0.15314296 -0.14157762, -0.48211476 0.15187497 -0.14411397, -0.48493209 0.15307523 -0.1417131, -0.48222443 0.15167606 -0.14451171, -0.48549268 0.15294372 -0.14197619, -0.48243722 0.1514947 -0.14487456, -0.48596621 0.15275593 -0.14235173, -0.48502952 0.14584585 -0.14163755, -0.48516953 0.14596525 -0.14139907, -0.48602107 0.14517173 -0.14298637, -0.48524174 0.14609605 -0.14113732, -0.48317191 0.14658175 -0.1401657, -0.48341984 0.14665826 -0.14001258, -0.48524168 0.14623082 -0.1408679, -0.48317197 0.14574507 -0.14183952, -0.48297206 0.14584592 -0.14163776, -0.48341992 0.14566854 -0.14199267, -0.48283207 0.14596529 -0.14139892, -0.48400083 0.14672247 -0.13988443, -0.48370156 0.14670607 -0.13991697, -0.48370168 0.14562084 -0.14208813, -0.48429996 0.14670606 -0.13991703, -0.48276004 0.14609616 -0.14113756, -0.48458174 0.14665829 -0.14001258, -0.48400083 0.14560452 -0.14212067, -0.48482975 0.1465819 -0.14016564, -0.48516956 0.14636153 -0.14060621, -0.48502949 0.14648095 -0.14036746, -0.48276004 0.14623086 -0.1408679, -0.48430005 0.14562075 -0.14208819, -0.48473224 0.14486246 -0.14360483, -0.4828321 0.14636169 -0.14060621, -0.4845818 0.1456686 -0.14199264, -0.48541948 0.14498147 -0.14336692, -0.48297209 0.14648087 -0.14036746, -0.48482981 0.14574508 -0.14183946, -0.48370171 0.14956841 -0.14134796, -0.48342001 0.14952055 -0.14144345, -0.483172 0.14944407 -0.14159663, -0.48297209 0.14934321 -0.14179833, -0.48283204 0.14922383 -0.14203702, -0.48275998 0.14909302 -0.14229874, -0.48275986 0.14895827 -0.14256819, -0.48283198 0.14882746 -0.14283009, -0.48297212 0.14870819 -0.14306869, -0.48317209 0.14860742 -0.14327045, -0.48341998 0.14853086 -0.14342351, -0.48370165 0.14848299 -0.14351912, -0.48529086 0.14536475 -0.14483638, -0.46312296 0.15144625 -0.0680774, -0.46331808 0.15044631 -0.069058314, -0.46247008 0.15094639 -0.068795517, -0.46331808 0.15044665 -0.075923905, -0.4624702 0.15094675 -0.076186493, -0.46312293 0.15144679 -0.076904491, -0.46117246 0.15094638 -0.069662645, -0.46030536 0.15094648 -0.070960358, -0.46000084 0.15094645 -0.072491124, -0.46030536 0.15094659 -0.074021801, -0.46117249 0.15094675 -0.075319603, -0.46123418 0.15653439 -0.073122248, -0.46144405 0.15653445 -0.07372199, -0.46178225 0.15653449 -0.074259952, -0.46223155 0.15653445 -0.074709401, -0.4627696 0.15653458 -0.075047478, -0.46336934 0.15653451 -0.075257286, -0.44416884 0.12726885 -0.070545956, -0.44422522 0.1272485 -0.070641026, -0.44430012 0.1272213 -0.070720181, -0.44413364 0.12728153 -0.070440009, -0.44412199 0.12728587 -0.070328459, -0.44438979 0.12718891 -0.070779666, -0.44417819 0.12726536 -0.067977384, -0.4441362 0.12728055 -0.068092182, -0.44412205 0.12728578 -0.068214133, -0.44433299 0.12720934 -0.067796931, -0.44424504 0.12724115 -0.06787692, -0.44477668 0.12704889 -0.067754224, -0.4444367 0.12717186 -0.067742333, -0.44454989 0.12713096 -0.067716315, -0.44466546 0.12708917 -0.067720249, -0.47617635 0.11569236 -0.086873427, -0.47609493 0.11572196 -0.086853936, -0.47613457 0.1157075 -0.086868748, -0.47621831 0.11567731 -0.086868361, -0.47625777 0.11566295 -0.086853489, -0.47632298 0.11563936 -0.086798146, -0.47629336 0.11565015 -0.086829737, -0.47634539 0.1156313 -0.086760119, -0.47635922 0.11562625 -0.086717948, -0.47167376 0.11732069 -0.079960063, -0.47227058 0.11710474 -0.080472067, -0.47210243 0.11716564 -0.080263302, -0.47190115 0.1172384 -0.080090925, -0.41296014 -0.035535306 -0.012501314, -0.41295108 -0.035465777 -0.012431934, -0.41293785 -0.035425603 -0.012391791, -0.41291878 -0.03538616 -0.062112436, -0.41296014 -0.035532534 -0.062258855, -0.41295108 -0.03546302 -0.062189177, -0.41293779 -0.035422876 -0.062149182, -0.41197881 -0.033879012 -0.060605243, -0.41194749 -0.033806339 -0.060532525, -0.41193745 -0.033721954 -0.060448244, -0.41194999 -0.033630148 -0.060356334, -0.41196629 -0.03357771 -0.060303912, -0.47263551 0.086533636 -0.062105522, -0.47263554 0.089959815 -0.06059821, -0.4119446 -0.033655614 -0.034137145, -0.41194117 -0.033777654 -0.034015194, -0.41195518 -0.033832014 -0.033960715, -0.41197881 -0.033880487 -0.033912316, -0.41291878 -0.035387844 -0.032405153, -0.4129549 -0.035481483 -0.032311425, -0.41294095 -0.035432354 -0.032360658, -0.41296002 -0.035534263 -0.032258853, -0.47263548 0.086531922 -0.032398447, -0.47263554 0.089958295 -0.033905253, -0.44460464 0.12710766 -0.0060273558, -0.444498 0.12714623 -0.0060373694, -0.44439617 0.12718306 -0.0060725361, -0.44430456 0.12721619 -0.0061315447, -0.44422805 0.12724389 -0.0062108487, -0.44417003 0.12726489 -0.0063068718, -0.44413415 0.12727788 -0.0064141005, -0.44412205 0.12728232 -0.0065272301, -0.44417912 0.12726171 -0.0090719014, -0.44424722 0.12723711 -0.0091727823, -0.44433668 0.12720479 -0.0092527717, -0.44455615 0.12712525 -0.0093315989, -0.44444174 0.12716667 -0.0093067437, -0.44413638 0.12727718 -0.0089562386, -0.44412199 0.12728241 -0.0088329762, -0.46942684 0.11812945 -0.011150822, -0.46924967 0.11819369 -0.011288241, -0.4693459 0.11815874 -0.011230573, -0.46952632 0.11809348 -0.01094304, -0.46948811 0.11810729 -0.011053219, -0.46953914 0.11808871 -0.010826454, -0.46914348 0.11823192 -0.011320189, -0.46903309 0.11827174 -0.011325076, -0.46953925 0.11808859 -0.0072185248, -0.46908158 0.11825415 -0.0067185909, -0.46918419 0.11821707 -0.006733641, -0.46949419 0.11810483 -0.0070049912, -0.46952793 0.11809275 -0.0071090311, -0.46928117 0.11818202 -0.0067721754, -0.46944001 0.1181245 -0.0069112629, -0.46936783 0.11815062 -0.0068322867, -0.46900997 0.11828074 -0.020319507, -0.46912375 0.11823966 -0.020320103, -0.46923426 0.11819978 -0.020291582, -0.46933508 0.11816323 -0.020235762, -0.4694204 0.11813244 -0.020155922, -0.46948507 0.11810894 -0.020056531, -0.46952561 0.11809422 -0.019943431, -0.46953925 0.11808927 -0.019823447, -0.44417539 0.12726343 -0.016759738, -0.44423941 0.12724037 -0.016858712, -0.44432369 0.12720984 -0.016938582, -0.44442359 0.12717386 -0.0169947, -0.44413546 0.12727791 -0.016647324, -0.44412199 0.12728283 -0.016528025, -0.44453302 0.12713413 -0.017024055, -0.44423428 0.12724198 -0.013905391, -0.44417307 0.12726419 -0.014003024, -0.44413486 0.127278 -0.014112934, -0.44441161 0.12717795 -0.013768062, -0.44431534 0.12721272 -0.013825551, -0.44451776 0.12713954 -0.013735965, -0.44462815 0.12709965 -0.013731137, -0.44412205 0.12728275 -0.01422967, -0.46953925 0.11808918 -0.016223207, -0.46910504 0.11824621 -0.015724644, -0.46921948 0.11820473 -0.015749469, -0.46948215 0.11810978 -0.015984312, -0.46952471 0.11809435 -0.016099915, -0.46932462 0.11816679 -0.015803471, -0.46941403 0.11813441 -0.015883341, -0.44465116 0.12709169 -0.021438673, -0.44453749 0.1271328 -0.021438137, -0.44442704 0.12717272 -0.021466658, -0.44432607 0.12720911 -0.021522418, -0.44424093 0.12724008 -0.021602407, -0.44417608 0.12726353 -0.021701708, -0.44413564 0.12727806 -0.021814689, -0.44412199 0.12728311 -0.021934703, -0.46941361 0.11813523 -0.029158249, -0.46948206 0.11811066 -0.02905713, -0.46932408 0.11816773 -0.02923806, -0.46952471 0.11809506 -0.028941527, -0.46921888 0.11820586 -0.029291973, -0.46910402 0.11824718 -0.029316649, -0.46953931 0.11808982 -0.028817996, -0.46898732 0.1182895 -0.02931042, -0.46953931 0.11808966 -0.025230125, -0.46952567 0.11809447 -0.025110975, -0.46948573 0.11810888 -0.02499862, -0.46942189 0.11813214 -0.024899587, -0.46933743 0.11816262 -0.024819747, -0.46923772 0.11819874 -0.024763599, -0.4691281 0.11823834 -0.024734214, -0.44451043 0.12714277 -0.024713084, -0.44431123 0.12721474 -0.024621591, -0.44417182 0.12726516 -0.024445012, -0.4442319 0.12724344 -0.024541989, -0.44440588 0.12718056 -0.024679676, -0.44413468 0.12727869 -0.024335817, -0.44412199 0.12728328 -0.024220541, -0.46896514 0.11829796 -0.038297907, -0.46906969 0.11826017 -0.038310245, -0.46917424 0.11822239 -0.038297549, -0.46927342 0.11818652 -0.038260505, -0.46936247 0.11815427 -0.0382009, -0.46943673 0.11812736 -0.038121805, -0.46949276 0.11810711 -0.038027093, -0.46952751 0.11809459 -0.037921444, -0.46953931 0.11809042 -0.037810251, -0.46953925 0.11809012 -0.034239903, -0.46952662 0.11809471 -0.034124538, -0.46948931 0.11810818 -0.034015462, -0.46942934 0.11812985 -0.033918485, -0.46934995 0.11815865 -0.033838853, -0.46925542 0.11819276 -0.033780679, -0.46915087 0.11823066 -0.03374745, -0.4444882 0.12715119 -0.032398447, -0.44429937 0.1272195 -0.032302007, -0.44438878 0.12718727 -0.032361493, -0.4442248 0.12724657 -0.032222763, -0.44416878 0.12726685 -0.032127991, -0.44413385 0.12727953 -0.032022223, -0.44412205 0.12728377 -0.031910732, -0.44467384 0.12708388 -0.029149905, -0.44412187 0.12728356 -0.029642299, -0.4445571 0.12712602 -0.029143676, -0.44413641 0.12727827 -0.029518947, -0.44433707 0.12720568 -0.029222235, -0.44417909 0.12726279 -0.029403165, -0.44444248 0.12716754 -0.029168323, -0.44424739 0.12723812 -0.029302225, -0.46894372 0.11830625 -0.047281846, -0.46905026 0.11826761 -0.047299787, -0.46915802 0.11822876 -0.047291026, -0.4692609 0.11819145 -0.047256455, -0.46935371 0.11815785 -0.047197923, -0.46943167 0.1181298 -0.04711847, -0.46949026 0.11810842 -0.047022179, -0.4695268 0.11809526 -0.046914145, -0.46953914 0.11809076 -0.046800002, -0.46953925 0.11809061 -0.043251708, -0.46927246 0.11818703 -0.042800978, -0.4691731 0.11822316 -0.042764112, -0.46936199 0.11815473 -0.042860553, -0.4694365 0.11812779 -0.042939708, -0.4694927 0.11810754 -0.043034509, -0.46952745 0.11809491 -0.043140307, -0.4444668 0.12715946 -0.040080443, -0.44437227 0.12719356 -0.040040448, -0.44421801 0.12724949 -0.039901271, -0.44428793 0.12722403 -0.039979711, -0.44413295 0.12728012 -0.039706007, -0.44416544 0.12726836 -0.039808556, -0.44412199 0.12728412 -0.03959842, -0.44469598 0.12707625 -0.036864534, -0.44412199 0.12728399 -0.0373521, -0.44413367 0.1272797 -0.037240997, -0.44459149 0.12711403 -0.036852047, -0.44448695 0.12715182 -0.036864892, -0.44416848 0.12726718 -0.037135497, -0.4443877 0.12718774 -0.036901966, -0.44422442 0.12724687 -0.037040725, -0.44429865 0.12721999 -0.036961362, -0.4447175 0.12706898 -0.044582561, -0.44461086 0.12710755 -0.044564888, -0.44450316 0.12714648 -0.044573471, -0.44440034 0.12718375 -0.044608042, -0.44430748 0.12721731 -0.044666603, -0.44422963 0.12724541 -0.044745997, -0.44417086 0.12726663 -0.044842318, -0.44413444 0.12727991 -0.044950351, -0.44412184 0.12728439 -0.045064494, -0.46942636 0.1181322 -0.056112632, -0.46924874 0.11819658 -0.056249872, -0.46934518 0.11816165 -0.056192443, -0.46952626 0.11809598 -0.055904672, -0.46953931 0.11809127 -0.055787817, -0.46948794 0.11810996 -0.056014821, -0.46914217 0.11823508 -0.05628182, -0.46903154 0.11827515 -0.056286111, -0.46892315 0.1183143 -0.056263104, -0.46953925 0.11809118 -0.052265897, -0.46952817 0.11809513 -0.052158579, -0.46949574 0.11810686 -0.052056089, -0.46944329 0.11812587 -0.051963195, -0.46937332 0.1181512 -0.051884636, -0.46928909 0.11818175 -0.051824108, -0.46919456 0.11821584 -0.051784143, -0.444446 0.12716728 -0.04775928, -0.4442772 0.12722844 -0.047655359, -0.44416252 0.12726986 -0.047487184, -0.44421151 0.12725219 -0.047577575, -0.44412205 0.12728451 -0.047284082, -0.44435647 0.12719974 -0.047716722, -0.44413224 0.12728083 -0.047387883, -0.46890345 0.11832197 -0.065241084, -0.4690133 0.11828215 -0.065269664, -0.46912655 0.11824115 -0.065269426, -0.46923646 0.11820146 -0.065240487, -0.4693366 0.11816518 -0.06518434, -0.46942133 0.11813459 -0.06510444, -0.46948564 0.1181114 -0.065005496, -0.46952561 0.11809686 -0.064892724, -0.46953931 0.11809196 -0.064773276, -0.46953931 0.11809172 -0.06128259, -0.46944967 0.1181241 -0.060988888, -0.46938404 0.11814776 -0.060911343, -0.46949878 0.11810634 -0.061079428, -0.46930471 0.1181765 -0.060849801, -0.469529 0.11809535 -0.061178729, -0.46921512 0.11820891 -0.060807183, -0.44442633 0.12717488 -0.055435434, -0.4442406 0.12724207 -0.055299625, -0.44432575 0.12721132 -0.055379525, -0.44417608 0.12726547 -0.055200234, -0.4441357 0.12728 -0.055087253, -0.44412187 0.12728491 -0.054967567, -0.44473818 0.12706196 -0.052303568, -0.44462964 0.12710111 -0.05228056, -0.44412205 0.12728491 -0.052778885, -0.44451919 0.12714122 -0.052284941, -0.44441262 0.1271797 -0.052316651, -0.44417325 0.12726624 -0.052551731, -0.44413498 0.12728015 -0.052662, -0.44431606 0.12721461 -0.05237411, -0.44423476 0.12724401 -0.052453861, -0.44412184 0.12728541 -0.062648967, -0.44413468 0.12728079 -0.062764481, -0.44417217 0.12726712 -0.062874153, -0.44423261 0.12724529 -0.06297113, -0.4443126 0.12721643 -0.063050821, -0.44440749 0.1271821 -0.063108787, -0.46952507 0.11809759 -0.07387875, -0.46953931 0.11809245 -0.07375662, -0.46948311 0.11811264 -0.073993549, -0.46941623 0.11813693 -0.074093893, -0.46888462 0.11832923 -0.074216709, -0.46932831 0.11816876 -0.074173823, -0.4692246 0.11820622 -0.0742286, -0.46911141 0.11824706 -0.074254617, -0.46899578 0.11828902 -0.074250475, -0.46953925 0.11809215 -0.07030116, -0.46952555 0.11809708 -0.070181265, -0.46948519 0.11811168 -0.070068434, -0.4694207 0.11813505 -0.069969192, -0.46933541 0.11816582 -0.069889203, -0.46923479 0.11820224 -0.069833264, -0.44475785 0.1270552 -0.060027525, -0.44464794 0.127095 -0.059999034, -0.44412199 0.1272853 -0.060495451, -0.44453475 0.12713607 -0.059999302, -0.44442478 0.12717569 -0.060028389, -0.44417569 0.12726583 -0.060263291, -0.44413558 0.12728044 -0.060376063, -0.44432464 0.12721203 -0.060084328, -0.44423994 0.12724264 -0.060164317, -0.44437298 0.12719546 -0.078448251, -0.48384991 0.11291765 -0.10056312, -0.48449108 0.11268568 -0.10034128, -0.48426458 0.11276762 -0.10057534, -0.48443314 0.11270666 -0.10043697, -0.48435637 0.11273445 -0.10051651, -0.48452708 0.11267255 -0.1002339, -0.48453927 0.11266823 -0.1001205, -0.48405597 0.1128431 -0.10062043, -0.48416269 0.11280446 -0.10061066, -0.48394993 0.11288156 -0.10060416, -0.48453918 0.11266814 -0.099346325, -0.4845095 0.1126789 -0.099040076, -0.48442158 0.11271062 -0.098746672, -0.4842793 0.11276218 -0.098478481, -0.48149237 0.11376989 -0.094299957, -0.48133817 0.11382577 -0.094105706, -0.48115531 0.11389187 -0.093942121, -0.48094887 0.11396644 -0.093813643, -0.44421831 0.12725154 -0.078309104, -0.44428858 0.12722608 -0.078387812, -0.44416562 0.12727046 -0.078216419, -0.44412199 0.12728629 -0.078005865, -0.44413313 0.12728237 -0.078113601, -0.44479445 0.12704287 -0.075483397, -0.44412205 0.12728621 -0.075934753, -0.44469514 0.1270788 -0.075447068, -0.44459069 0.12711665 -0.075434759, -0.44448629 0.12715429 -0.075447664, -0.44416836 0.12726933 -0.075718418, -0.44413364 0.12728195 -0.075823769, -0.44438723 0.12719017 -0.075484827, -0.4442983 0.12722234 -0.075544462, -0.44422421 0.12724929 -0.075623497, -0.48383424 0.11292385 -0.11032943, -0.48393446 0.11288765 -0.11037563, -0.48404187 0.11284871 -0.11039554, -0.48415089 0.11280935 -0.11038868, -0.48425525 0.11277136 -0.11035572, -0.48434994 0.11273724 -0.11029746, -0.48442933 0.11270863 -0.11021774, -0.48448935 0.11268689 -0.11012088, -0.48452672 0.1126734 -0.1100118, -0.4845393 0.11266883 -0.10989641, -0.48453924 0.11266851 -0.10577179, -0.48437265 0.11272877 -0.10539006, -0.48428825 0.11275932 -0.1053295, -0.48444289 0.11270329 -0.10546862, -0.48449555 0.11268428 -0.1055616, -0.48452827 0.11267257 -0.10566409, -0.44435731 0.12720171 -0.086114839, -0.44412199 0.1272867 -0.085681751, -0.44427767 0.12723042 -0.086053327, -0.44421181 0.12725429 -0.085975841, -0.44416264 0.12727204 -0.085885152, -0.4441323 0.12728307 -0.085785851, -0.44481125 0.1270372 -0.083214864, -0.44471136 0.12707329 -0.083173588, -0.44460526 0.12711172 -0.083157495, -0.44412202 0.12728664 -0.083657309, -0.44449857 0.12715028 -0.08316727, -0.44413415 0.12728217 -0.083543971, -0.44439676 0.12718722 -0.083202437, -0.44417021 0.12726907 -0.083436683, -0.44430497 0.12722041 -0.083261326, -0.44422808 0.1272482 -0.083340839, -0.48422819 0.15165679 -0.10645963, -0.48431119 0.15167442 -0.10652111, -0.48437983 0.15168901 -0.10659884, -0.48443106 0.15169987 -0.10668953, -0.48446271 0.15170667 -0.1067891, -0.48447341 0.15170899 -0.10689329, -0.44440708 0.14318338 -0.086067632, -0.44435945 0.14317325 -0.085979447, -0.44447103 0.14319696 -0.086144194, -0.44433013 0.14316697 -0.085883453, -0.4443202 0.1431649 -0.085783318, -0.4445487 0.14321354 -0.086206302, -0.44432026 0.1431648 -0.083864287, -0.44505295 0.14332062 -0.083430842, -0.44494876 0.14329831 -0.083385184, -0.44483706 0.14327469 -0.083365127, -0.44472358 0.14325051 -0.083371952, -0.44461522 0.14322741 -0.08340542, -0.44451681 0.14320646 -0.083463386, -0.44443449 0.14318898 -0.083543137, -0.44437215 0.14317584 -0.083640173, -0.44433334 0.14316757 -0.083749101, -0.48382813 0.15157202 -0.11147641, -0.48416853 0.15164448 -0.11146604, -0.48394135 0.15159601 -0.11150084, -0.48405704 0.15162064 -0.11149715, -0.48426968 0.1516659 -0.11140881, -0.48441955 0.15169783 -0.11123078, -0.48435494 0.15168408 -0.11132891, -0.4844597 0.15170629 -0.11112009, -0.48372391 0.15154983 -0.11142574, -0.48447341 0.15170921 -0.11100267, -0.44503495 0.14331645 -0.075679883, -0.47243416 0.14914659 -0.090254262, -0.44441387 0.14318433 -0.07839103, -0.44456545 0.14321665 -0.078530267, -0.44448251 0.14319895 -0.078468755, -0.44436261 0.14317353 -0.078300461, -0.4443309 0.14316674 -0.078200772, -0.44432023 0.14316444 -0.078096583, -0.44432014 0.14316425 -0.076123431, -0.44493106 0.14329423 -0.075639084, -0.44482109 0.14327084 -0.075623497, -0.44471017 0.14324719 -0.0756336, -0.44460455 0.14322485 -0.075669274, -0.44450966 0.14320455 -0.075728193, -0.44443005 0.14318767 -0.075807676, -0.44437 0.14317481 -0.075903252, -0.44433278 0.14316694 -0.076010302, -0.48380211 0.15156586 -0.10159521, -0.48401156 0.15161042 -0.10166042, -0.48390311 0.1515874 -0.10164009, -0.48412174 0.15163395 -0.10165553, -0.47396019 0.14947122 -0.091271743, -0.47464272 0.14961646 -0.091890261, -0.47322169 0.14931417 -0.090724602, -0.48432496 0.15167721 -0.10157214, -0.48422796 0.15165654 -0.10162567, -0.48451236 0.15154655 -0.10151412, -0.48452201 0.15154867 -0.1015863, -0.4845008 0.15154423 -0.10165553, -0.48469985 0.15141602 -0.10145588, -0.48471922 0.15142027 -0.1016001, -0.48467657 0.1514111 -0.10173889, -0.46919075 0.14845593 -0.079438731, -0.46928528 0.14847608 -0.079497799, -0.46936435 0.14849284 -0.079577133, -0.46942395 0.14850557 -0.079672739, -0.46946087 0.14851341 -0.07977958, -0.46947348 0.14851619 -0.079892114, -0.44436595 0.14317369 -0.070619687, -0.44433165 0.14316639 -0.070516601, -0.4444212 0.14318547 -0.070712671, -0.44449475 0.14320113 -0.070791349, -0.44432017 0.14316393 -0.070408389, -0.44458351 0.14322002 -0.070851907, -0.44432008 0.14316377 -0.068384483, -0.44501558 0.14331177 -0.06793125, -0.44491252 0.14328972 -0.067895845, -0.44480416 0.14326678 -0.06788443, -0.44469625 0.14324382 -0.06789811, -0.44459376 0.14322203 -0.067935541, -0.44450203 0.14320254 -0.067995384, -0.44442549 0.14318618 -0.068074301, -0.44436792 0.14317392 -0.068168953, -0.44433215 0.14316644 -0.068273976, -0.46897259 0.14840974 -0.083767459, -0.46918884 0.14845583 -0.083721831, -0.46908337 0.14843333 -0.083757237, -0.469284 0.14847605 -0.083662823, -0.46942362 0.14850569 -0.083487794, -0.46936351 0.14849287 -0.083583429, -0.46875858 0.14836425 -0.083711222, -0.4694733 0.14851628 -0.083267644, -0.46886238 0.14838625 -0.083751753, -0.46946079 0.14851357 -0.083380535, -0.4443202 0.14316347 -0.06064783, -0.44433483 0.14316662 -0.060526565, -0.44437769 0.14317565 -0.060412332, -0.44444641 0.14319028 -0.060312435, -0.44453701 0.14320953 -0.060232446, -0.44464365 0.14323224 -0.060177281, -0.44476014 0.14325701 -0.06015034, -0.44487977 0.14328238 -0.060153112, -0.44499508 0.14330699 -0.060185239, -0.44442931 0.14318676 -0.063032493, -0.44460282 0.14322366 -0.063170984, -0.4445084 0.14320363 -0.063111857, -0.44436958 0.1431741 -0.062937006, -0.44433272 0.14316621 -0.062830284, -0.44432017 0.14316359 -0.062717751, -0.46888107 0.14838973 -0.07471405, -0.46919981 0.14845754 -0.074674085, -0.46898931 0.14841278 -0.074725255, -0.4690972 0.14843574 -0.074711815, -0.46942571 0.14850564 -0.074440822, -0.46929157 0.148477 -0.074614421, -0.46936804 0.14849333 -0.074535385, -0.46877792 0.14836772 -0.074678525, -0.46947327 0.14851573 -0.074225381, -0.46946138 0.1485132 -0.074335888, -0.46947339 0.14851555 -0.070803538, -0.46917033 0.14845109 -0.070340946, -0.46941987 0.14850415 -0.070576146, -0.46945983 0.14851263 -0.070686653, -0.46927106 0.1484725 -0.070398286, -0.46935567 0.14849044 -0.070478275, -0.46914855 0.14844598 -0.06124641, -0.46925569 0.14846863 -0.061301365, -0.46934643 0.14848807 -0.061381355, -0.46941563 0.14850272 -0.061481491, -0.46945879 0.14851189 -0.061595753, -0.46947345 0.14851515 -0.061717466, -0.44443777 0.14318806 -0.055350557, -0.4443737 0.14317445 -0.055252418, -0.44452253 0.14320613 -0.055430278, -0.44433376 0.14316598 -0.055141971, -0.44432017 0.14316307 -0.055024996, -0.44462326 0.14322753 -0.055487528, -0.44432017 0.14316304 -0.052913532, -0.44497326 0.14330198 -0.052442566, -0.44485953 0.1432777 -0.052416191, -0.44474271 0.14325295 -0.052418217, -0.44462997 0.14322886 -0.052448377, -0.4445273 0.14320707 -0.052505031, -0.44444063 0.14318855 -0.052584872, -0.44437513 0.14317472 -0.052683488, -0.44433403 0.14316592 -0.052795157, -0.46891388 0.14839622 -0.065675572, -0.46914986 0.14844647 -0.065651163, -0.4690333 0.14842166 -0.065678194, -0.46934703 0.1484883 -0.06551598, -0.46925673 0.14846918 -0.065596059, -0.46945879 0.14851214 -0.065302119, -0.46941593 0.14850304 -0.065416083, -0.46879849 0.14837159 -0.065643266, -0.46947345 0.14851537 -0.065180734, -0.46912557 0.14844052 -0.052155122, -0.46922132 0.14846095 -0.052196398, -0.46930647 0.14847898 -0.052257553, -0.46937683 0.1484939 -0.052335605, -0.46942964 0.14850526 -0.052427158, -0.46946236 0.14851215 -0.052528039, -0.46947333 0.14851452 -0.052633867, -0.44444713 0.1431897 -0.047666058, -0.44437793 0.1431749 -0.047565922, -0.44453791 0.143209 -0.047745898, -0.44433483 0.14316568 -0.047451571, -0.44432011 0.14316268 -0.047329858, -0.44464502 0.14323179 -0.047800854, -0.44432017 0.14316258 -0.045181736, -0.44495037 0.14329652 -0.044703111, -0.44483829 0.14327268 -0.044682696, -0.44472492 0.14324871 -0.044689223, -0.44461596 0.14322548 -0.044722393, -0.44451752 0.14320444 -0.044780418, -0.44443479 0.14318684 -0.044860199, -0.44437224 0.14317361 -0.044957116, -0.4443334 0.14316536 -0.045066312, -0.46905074 0.14842489 -0.056629196, -0.46926624 0.1484707 -0.056542292, -0.46916357 0.1484489 -0.056599006, -0.46893397 0.14840002 -0.056631222, -0.4693529 0.14848915 -0.056462541, -0.46945944 0.14851178 -0.056252137, -0.46941856 0.14850311 -0.056363836, -0.46882024 0.14837584 -0.056604758, -0.46947345 0.14851488 -0.056133881, -0.46910161 0.14843488 -0.04306747, -0.46920305 0.14845642 -0.043105498, -0.46929374 0.14847572 -0.043165609, -0.46936932 0.14849183 -0.043244585, -0.46942624 0.14850406 -0.043338373, -0.46946153 0.14851154 -0.043443009, -0.46947345 0.14851411 -0.043552831, -0.46942139 0.14850324 -0.047308907, -0.46935871 0.1484898 -0.047406003, -0.46927616 0.14847226 -0.047485575, -0.46947345 0.14851429 -0.047084257, -0.46917751 0.14845131 -0.047543749, -0.46946016 0.14851144 -0.047199681, -0.46895501 0.148404 -0.047583446, -0.46906856 0.14842817 -0.04757677, -0.46884319 0.14838025 -0.047562972, -0.44466797 0.14323625 -0.040110961, -0.44433117 0.14316462 -0.039738014, -0.44441673 0.14318289 -0.039930478, -0.44436383 0.14317152 -0.039838955, -0.44448712 0.14319779 -0.04000859, -0.44457218 0.14321582 -0.040069744, -0.44432029 0.14316225 -0.039632335, -0.44492638 0.14329103 -0.036967292, -0.44432011 0.1431621 -0.037452593, -0.44481668 0.14326762 -0.03695263, -0.44450769 0.14320213 -0.037058905, -0.44470662 0.14324424 -0.036963835, -0.4446018 0.14322205 -0.036999628, -0.44433269 0.14316477 -0.037340298, -0.44442877 0.14318529 -0.037138358, -0.44436947 0.14317259 -0.037233636, -0.44432011 0.14316168 -0.029726252, -0.44433179 0.14316413 -0.029617056, -0.44436669 0.14317152 -0.029513225, -0.44442293 0.14318359 -0.029419497, -0.44449762 0.14319934 -0.029340699, -0.44458744 0.14321856 -0.029280558, -0.44468799 0.14323993 -0.029241785, -0.44479439 0.14326254 -0.029226378, -0.44490141 0.14328532 -0.029235229, -0.44442424 0.14318392 -0.032240376, -0.44436738 0.14317183 -0.03214632, -0.44449976 0.14320001 -0.032319292, -0.44469205 0.14324094 -0.032417551, -0.4445906 0.14321937 -0.032379374, -0.44433203 0.14316434 -0.032041892, -0.44432023 0.1431618 -0.031932011, -0.46886709 0.14838479 -0.038517758, -0.46908695 0.14843152 -0.038521186, -0.46897677 0.14840801 -0.038532183, -0.4691917 0.14845382 -0.038485184, -0.46928594 0.14847384 -0.038425937, -0.46936479 0.1484907 -0.038346574, -0.4694241 0.14850335 -0.038251027, -0.46946087 0.14851102 -0.038144514, -0.46947345 0.14851384 -0.038032308, -0.46947333 0.14851351 -0.034474596, -0.46907657 0.14842908 -0.033983484, -0.46946052 0.1485108 -0.034360424, -0.46918377 0.14845189 -0.034018084, -0.46936142 0.14848965 -0.034156099, -0.46942258 0.14850271 -0.03425239, -0.46928039 0.14847232 -0.034076497, -0.46905082 0.14842314 -0.02490373, -0.46916378 0.14844707 -0.024934068, -0.46926638 0.14846896 -0.024990693, -0.46935293 0.14848728 -0.025070533, -0.46941856 0.14850123 -0.025169238, -0.46945944 0.14850995 -0.025280669, -0.4694733 0.14851302 -0.025399193, -0.44443217 0.14318527 -0.024547562, -0.44460991 0.14322312 -0.024685577, -0.44451326 0.14320253 -0.024627045, -0.44437101 0.14317222 -0.024451211, -0.44433311 0.14316417 -0.024343237, -0.44432023 0.1431614 -0.024229035, -0.44471699 0.14324585 -0.024720028, -0.44437721 0.14317335 -0.021768376, -0.44444531 0.14318785 -0.021668509, -0.4443346 0.14316423 -0.021881774, -0.44453493 0.14320688 -0.021588579, -0.44464085 0.14322935 -0.021533147, -0.44475666 0.14325406 -0.02150552, -0.44432017 0.14316122 -0.022002652, -0.44487569 0.1432793 -0.021507308, -0.46899924 0.1484123 -0.029477224, -0.46920606 0.14845636 -0.029423103, -0.46910557 0.14843492 -0.029461876, -0.46929577 0.14847538 -0.029363021, -0.46937072 0.14849144 -0.029284105, -0.4694618 0.14851087 -0.029086456, -0.46942678 0.14850333 -0.029190406, -0.46889219 0.14838956 -0.029468492, -0.46947345 0.14851327 -0.028977379, -0.46902475 0.14841703 -0.015828237, -0.46914312 0.14844222 -0.015853658, -0.46925181 0.14846537 -0.015907988, -0.46934426 0.14848512 -0.015987977, -0.46941438 0.14849994 -0.016088501, -0.46945843 0.14850934 -0.016203985, -0.46947333 0.1485125 -0.016326681, -0.44444063 0.14318658 -0.016851917, -0.4446297 0.14322683 -0.016988412, -0.44452724 0.14320506 -0.016931787, -0.44437498 0.14317265 -0.01675342, -0.44433403 0.14316389 -0.016641721, -0.44432008 0.14316091 -0.016523376, -0.44474271 0.14325082 -0.017018691, -0.44432029 0.14316082 -0.014282003, -0.44484952 0.14327349 -0.013783559, -0.44473436 0.14324893 -0.013787881, -0.44462344 0.14322527 -0.013819441, -0.44452253 0.14320387 -0.013876811, -0.44443795 0.14318587 -0.013956532, -0.44437379 0.14317225 -0.014054403, -0.44433376 0.14316373 -0.01416482, -0.46903676 0.14841983 -0.020416781, -0.46925849 0.148467 -0.020333901, -0.46915266 0.14844453 -0.020389244, -0.46941647 0.14850064 -0.020154253, -0.46934825 0.14848614 -0.020253971, -0.46945897 0.14850965 -0.020040616, -0.46891776 0.1483945 -0.020415112, -0.46947339 0.14851269 -0.019919828, -0.46899804 0.14841083 -0.0067572445, -0.46910456 0.14843342 -0.0067725033, -0.46920529 0.14845489 -0.0068109781, -0.46929538 0.1484741 -0.0068712085, -0.46937045 0.1484901 -0.0069499761, -0.4694266 0.14850195 -0.0070437938, -0.46946159 0.14850946 -0.0071477741, -0.46947342 0.14851198 -0.0072570592, -0.44437915 0.14317302 -0.0090525895, -0.44465044 0.1432308 -0.0092874914, -0.44444931 0.14318793 -0.009153232, -0.44454178 0.14320768 -0.009233281, -0.44433501 0.1431637 -0.008937344, -0.44432014 0.14316055 -0.0088146478, -0.44476876 0.14325601 -0.009312883, -0.44433293 0.14316311 -0.0064509362, -0.4443703 0.14317106 -0.0063437074, -0.44432014 0.14316037 -0.0065642446, -0.44443059 0.14318392 -0.0062478632, -0.44451049 0.14320086 -0.0061683804, -0.44482288 0.1432672 -0.0060645193, -0.44471195 0.14324373 -0.0060741454, -0.44460583 0.14322113 -0.0061094612, -0.46927106 0.14846921 -0.011264309, -0.46941993 0.14850087 -0.011086777, -0.46935561 0.14848718 -0.011184558, -0.46945995 0.14850929 -0.01097618, -0.46894404 0.14839961 -0.01135762, -0.46947339 0.14851227 -0.010859236, -0.46905932 0.14842422 -0.011353388, -0.4691703 0.14844778 -0.011321679, -0.44123515 0.12906016 -0.088559374, -0.48761028 0.11228739 -0.11700527, -0.4412283 0.12903039 -0.088482007, -0.48770928 0.11214189 -0.11677216, -0.4412159 0.12893966 -0.088188156, -0.48784238 0.11202805 -0.11654221, -0.4411976 0.1288929 -0.087887421, -0.44977996 0.12754233 -0.097172633, -0.44971243 0.12753806 -0.097069636, -0.44122469 0.12930356 -0.089066759, -0.4496671 0.12751514 -0.09695746, -0.44964653 0.12747502 -0.0968429, -0.44965214 0.12742007 -0.096732751, -0.44968358 0.12735364 -0.096633717, -0.44973877 0.12727973 -0.096552089, -0.44981435 0.12720288 -0.096492544, -0.44123515 0.12921697 -0.088895485, -0.44990617 0.12712775 -0.096458927, -0.45000818 0.127059 -0.096452966, -0.45011434 0.12700064 -0.096475169, -0.45021826 0.12695625 -0.096524492, -0.4875069 0.12619112 -0.14667378, -0.48476598 0.1251817 -0.14070232, -0.48468566 0.12519494 -0.14061923, -0.48485789 0.1251523 -0.14076717, -0.48495653 0.12510844 -0.14080997, -0.48505661 0.1250525 -0.1408288, -0.48515272 0.12498739 -0.14082272, -0.4852396 0.12491657 -0.14079158, -0.48531243 0.124844 -0.14073755, -0.48536757 0.12477373 -0.14066322, -0.4854019 0.12470928 -0.14057283, -0.48541346 0.12465432 -0.14047106, -0.46138522 0.12471028 -0.10721849, -0.46136212 0.12466954 -0.10709904, -0.46136913 0.12469569 -0.1071647, -0.46141022 0.12471835 -0.10727014, -0.46136984 0.12463567 -0.10703702, -0.46139145 0.12459597 -0.1069821, -0.46142605 0.12455288 -0.10693751, -0.46147147 0.12450856 -0.10690556, -0.46164587 0.12439306 -0.10690044, -0.46152547 0.12446553 -0.1068884, -0.46158478 0.12442628 -0.10688661, -0.46144292 0.12471929 -0.10731803, -0.46170583 0.12436767 -0.10692893, -0.48541346 0.12328897 -0.13754348, -0.48541099 0.12325767 -0.13747267, -0.46902034 0.12304468 -0.11425151, -0.46895278 0.12304033 -0.1141486, -0.46890748 0.12301756 -0.11403622, -0.46888688 0.12297727 -0.11392151, -0.46889254 0.12292238 -0.11381145, -0.46892381 0.12285586 -0.11371259, -0.46897915 0.12278207 -0.11363088, -0.46905485 0.12270525 -0.11357136, -0.48514459 0.12312546 -0.13681908, -0.4847658 0.12197779 -0.13383274, -0.48468566 0.12199117 -0.13374986, -0.46914658 0.12263012 -0.11353765, -0.48485777 0.12194853 -0.1338975, -0.48495653 0.12190467 -0.1339405, -0.46924856 0.12256125 -0.11353187, -0.48505652 0.1218486 -0.13395937, -0.46935466 0.12250294 -0.11355434, -0.46945861 0.12245861 -0.11360337, -0.4851526 0.12178351 -0.13395302, -0.48523948 0.1217128 -0.13392211, -0.48525372 0.12312886 -0.1369781, -0.48531246 0.12164029 -0.13386811, -0.48533675 0.12315544 -0.13715048, -0.48536742 0.12156995 -0.13379385, -0.48539045 0.1232041 -0.13732941, -0.4854019 0.1215055 -0.1337034, -0.48540324 0.1232294 -0.13740127, -0.48541346 0.12145054 -0.13360162, -0.4788765 0.12062149 -0.12274455, -0.47885343 0.12058072 -0.12262525, -0.47886023 0.12060687 -0.12269087, -0.47890136 0.12062946 -0.12279634, -0.47886106 0.12054685 -0.12256317, -0.47891724 0.120464 -0.12246378, -0.47888276 0.12050727 -0.12250827, -0.47896275 0.12041965 -0.12243195, -0.47907594 0.12033752 -0.12241264, -0.47901663 0.12037669 -0.12241445, -0.47913715 0.12030424 -0.12242655, -0.479197 0.12027879 -0.12245528, -0.47893402 0.12063047 -0.12284406, -0.4848406 0.11823758 -0.12591715, -0.48514435 0.12021288 -0.130574, -0.48494074 0.1181951 -0.12596484, -0.48504332 0.11813952 -0.12598772, -0.48514232 0.1180739 -0.12598453, -0.4852322 0.11800195 -0.12595542, -0.48530802 0.11792788 -0.12590189, -0.48525372 0.12021634 -0.13073324, -0.48536548 0.1178557 -0.12582697, -0.48533663 0.12024298 -0.13090555, -0.48540136 0.11778967 -0.12573479, -0.48539045 0.12029168 -0.13108446, -0.48540321 0.12031685 -0.13115631, -0.48541346 0.11773331 -0.12563105, -0.48541096 0.12034516 -0.13122781, -0.48483428 0.1168976 -0.12303458, -0.48494086 0.11595777 -0.12116762, -0.48484072 0.11600021 -0.12111966, -0.48504332 0.11590217 -0.12119038, -0.48499104 0.11684981 -0.12315004, -0.48514226 0.11583656 -0.12118731, -0.48523223 0.11576471 -0.12115808, -0.48513034 0.11682615 -0.12329249, -0.4853082 0.11569056 -0.1211044, -0.48524621 0.11682752 -0.12345619, -0.48536554 0.11561842 -0.1210296, -0.48533401 0.11685364 -0.12363465, -0.4854013 0.1155522 -0.12093766, -0.48539039 0.11690375 -0.12382041, -0.4875069 0.11273052 -0.11781161, -0.4854134 0.11698872 -0.12403436, -0.48524609 0.11436638 -0.11817913, -0.48513025 0.11436506 -0.11801545, -0.48533401 0.11439256 -0.11835741, -0.48539045 0.11444271 -0.11854331, -0.48540315 0.11446789 -0.11861511, -0.4854109 0.11449629 -0.11868651, -0.48541346 0.11452754 -0.11875732, -0.48541352 0.11549594 -0.12083371, -0.48540315 0.11692901 -0.12389229, -0.48541096 0.11695747 -0.12396364, -0.48752865 0.11252263 -0.11739631, -0.48499104 0.11438875 -0.117873, -0.48483416 0.1144364 -0.11775737, -0.4854134 0.12037638 -0.13129844, -0.46080568 0.12463692 -0.10762797, -0.46089301 0.1246397 -0.10775517, -0.46073925 0.12461562 -0.10749005, -0.46069637 0.12457678 -0.10734691, -0.48471785 0.12308517 -0.13751163, -0.48469082 0.12306075 -0.13742216, -0.48464933 0.12304744 -0.13733609, -0.48459473 0.12304577 -0.13725655, -0.48471773 0.11432377 -0.11872549, -0.4846895 0.11429872 -0.11863263, -0.4846454 0.11428557 -0.11854355, -0.48458752 0.11428487 -0.11846168, -0.4845179 0.11429681 -0.11839043, -0.48443958 0.11432067 -0.11833282, -0.47838423 0.12055096 -0.12328143, -0.47829691 0.1205481 -0.12315409, -0.47823051 0.12052678 -0.12301643, -0.47818762 0.12048791 -0.12287317, -0.4847177 0.12017262 -0.13126673, -0.48469064 0.12014823 -0.13117729, -0.48464927 0.12013493 -0.1310911, -0.48459467 0.1201333 -0.1310115, -0.48471758 0.11678477 -0.12400265, -0.48468944 0.11675976 -0.12390967, -0.48464546 0.11674663 -0.12382059, -0.48458746 0.11674598 -0.12373863, -0.4845179 0.11675784 -0.12366743, -0.48443946 0.11678167 -0.12360965, -0.4847241 0.12018527 -0.13130273, -0.48472789 0.12019938 -0.1313384, -0.4847292 0.12128913 -0.1336769, -0.48472917 0.12021507 -0.13137366, -0.46906379 0.12234268 -0.11417846, -0.47816905 0.12041815 -0.12269793, -0.47818932 0.12032786 -0.12253247, -0.47824717 0.12022218 -0.12238626, -0.4783394 0.12010701 -0.12226732, -0.47846085 0.11998877 -0.12218241, -0.47860441 0.11987421 -0.12213607, -0.47876245 0.1197696 -0.12213127, -0.47892585 0.1196809 -0.12216811, -0.48472407 0.11679751 -0.12403844, -0.48472914 0.11682722 -0.12410955, -0.48472795 0.11681165 -0.12407415, -0.48472914 0.11757185 -0.1257063, -0.47908559 0.11961314 -0.12224455, -0.48472413 0.12309779 -0.13754757, -0.4847292 0.12312755 -0.13761862, -0.48472789 0.12311198 -0.13758333, -0.4847292 0.12449285 -0.1405464, -0.44982359 0.1268404 -0.097099707, -0.46067774 0.12450694 -0.10717176, -0.46069807 0.12441657 -0.1070063, -0.46075606 0.1243109 -0.10686015, -0.46084812 0.12419577 -0.10674106, -0.46096945 0.12407754 -0.10665606, -0.4611133 0.12396295 -0.10661004, -0.4612712 0.1238583 -0.10660516, -0.46143451 0.12376966 -0.10664199, -0.46159431 0.12370194 -0.10671829, -0.48472396 0.11433636 -0.11876146, -0.48472914 0.11533451 -0.1209089, -0.48472914 0.11436613 -0.11883251, -0.48472792 0.11435062 -0.11879726, -0.46913141 0.12241213 -0.11396359, -0.46907061 0.12245505 -0.11397134, -0.46902546 0.12250166 -0.11400877, -0.46919873 0.12248141 -0.11374854, -0.46900514 0.12254253 -0.11406817, -0.46907726 0.12256745 -0.11376418, -0.46901369 0.12256929 -0.1141374, -0.46898702 0.12266067 -0.11383896, -0.46894649 0.12274241 -0.11395766, -0.46896347 0.12279585 -0.1140963, -0.48477203 0.12150899 -0.13375045, -0.48483828 0.12147561 -0.13377105, -0.48489919 0.12143038 -0.1337588, -0.48481491 0.12172876 -0.1338238, -0.48494199 0.12138267 -0.13371576, -0.48494738 0.12166218 -0.13386525, -0.48506948 0.12157163 -0.13384037, -0.48515484 0.12147635 -0.13375475, -0.4848339 0.11776108 -0.12580021, -0.48489693 0.11771521 -0.12578936, -0.48493853 0.11795028 -0.12589394, -0.48494133 0.11766644 -0.12574644, -0.48506457 0.1178586 -0.1258723, -0.4851535 0.11776115 -0.12578674, -0.44989085 0.12690979 -0.096884653, -0.44983023 0.12695274 -0.096892521, -0.44978514 0.12699935 -0.096929953, -0.44995838 0.1269791 -0.096669719, -0.44976473 0.12704013 -0.0969892, -0.44983694 0.12706517 -0.096685424, -0.44977346 0.12706704 -0.097058579, -0.4497467 0.12715837 -0.096760079, -0.44970608 0.12724006 -0.096878901, -0.44972309 0.12729356 -0.097017542, -0.48477212 0.12471272 -0.14061983, -0.48483846 0.12467946 -0.14064036, -0.48489931 0.12463416 -0.14062797, -0.48481497 0.1249325 -0.1406935, -0.48494211 0.12458657 -0.14058526, -0.48494753 0.12486586 -0.14073463, -0.48506942 0.12477534 -0.14070983, -0.48515484 0.12468012 -0.14062412, -0.48483399 0.11552377 -0.12100284, -0.48489693 0.11547787 -0.12099202, -0.48493871 0.11571293 -0.12109666, -0.48494133 0.11542915 -0.12094919, -0.48506454 0.11562127 -0.12107508, -0.48515341 0.11552374 -0.12098931, -0.44082478 0.12894754 -0.087572083, -0.4408007 0.12897097 -0.087854341, -0.43930075 0.12896866 -0.087838873, -0.44076654 0.12903342 -0.088128701, -0.43930081 0.12903161 -0.088122472, -0.44073308 0.12913489 -0.08839415, -0.43930072 0.12913494 -0.08839415, -0.43930086 0.1293418 -0.08883737, -0.44072881 0.12918483 -0.0885012, -0.4407289 0.12934172 -0.08883737, -0.44128656 0.13082598 -0.090347633, -0.48777881 0.1274924 -0.14819895, -0.44125503 0.13049187 -0.090262875, -0.487773 0.12735331 -0.14816035, -0.48775208 0.12710232 -0.14803399, -0.44123986 0.13017891 -0.090113506, -0.48770896 0.12681563 -0.14778866, -0.44123608 0.12989889 -0.089908823, -0.48765382 0.12657639 -0.14748071, -0.44123772 0.12965877 -0.089660302, -0.44123712 0.12945957 -0.089376524, -0.48561278 0.12990928 -0.14551987, -0.48546919 0.1298925 -0.14534111, -0.48575014 0.12997784 -0.14569081, -0.48587397 0.13009492 -0.14584507, -0.48597813 0.13025416 -0.1459745, -0.48605654 0.13044687 -0.14607216, -0.48610523 0.13066314 -0.14613293, -0.48612186 0.13089162 -0.14615349, -0.4413009 0.13971154 -0.090365276, -0.44313124 0.13752319 -0.092643246, -0.44302568 0.13736381 -0.092512146, -0.4877803 0.13582988 -0.14821734, -0.44129613 0.13990313 -0.090359107, -0.48552987 0.13404128 -0.14541648, -0.44294605 0.13717005 -0.092412993, -0.44354048 0.13772063 -0.093152657, -0.44347963 0.13271625 -0.093077466, -0.44325659 0.13763939 -0.092799559, -0.44289663 0.13695225 -0.092351422, -0.44339547 0.13770641 -0.092972443, -0.44287965 0.13672212 -0.092330441, -0.44287965 0.13371529 -0.09233062, -0.44130096 0.13115445 -0.090365872, -0.44289461 0.13349864 -0.092349276, -0.44293854 0.13329235 -0.092403784, -0.44300941 0.13310608 -0.092492089, -0.44310388 0.13294873 -0.092609659, -0.44321731 0.1328278 -0.092751071, -0.44334465 0.13274913 -0.092909381, -0.48606393 0.13346253 -0.14608131, -0.48610717 0.1332577 -0.14613511, -0.48599413 0.13364778 -0.14599444, -0.48590115 0.13380471 -0.14587866, -0.48578915 0.13392615 -0.14573921, -0.48566332 0.13400619 -0.14558287, -0.48612174 0.13304278 -0.14615335, -0.48512277 0.13354208 -0.14570831, -0.4431335 0.13722149 -0.093444481, -0.4853085 0.13342376 -0.14593939, -0.48518953 0.13352454 -0.1457914, -0.48525244 0.1334845 -0.1458696, -0.48538998 0.13325267 -0.14604075, -0.48541149 0.13315015 -0.14606757, -0.48535499 0.13334522 -0.14599727, -0.48541883 0.1330428 -0.14607655, -0.48523298 0.13043466 -0.14584561, -0.48516428 0.13040034 -0.14576013, -0.48529503 0.13049316 -0.14592274, -0.48534697 0.13057275 -0.14598723, -0.48538628 0.13066933 -0.14603616, -0.48541048 0.13077728 -0.14606653, -0.48541906 0.13089162 -0.14607666, -0.48509252 0.13039209 -0.14567067, -0.44306108 0.13721427 -0.09335427, -0.44292888 0.1371226 -0.09318985, -0.44299147 0.13718072 -0.093267933, -0.44281146 0.13683715 -0.093043938, -0.44287607 0.13704291 -0.093124375, -0.44283614 0.13694604 -0.093074694, -0.44280311 0.13672212 -0.093033418, -0.44280311 0.13371536 -0.093033656, -0.44310302 0.13321571 -0.09340705, -0.44283259 0.1335039 -0.093070164, -0.44281048 0.13360702 -0.093042895, -0.44303557 0.13323213 -0.093323126, -0.44297192 0.1332716 -0.093243763, -0.44286796 0.13341072 -0.093114302, -0.44291514 0.13333206 -0.093173072, -0.44071832 0.12939945 -0.088951632, -0.43930089 0.12957841 -0.089223608, -0.44062445 0.12966651 -0.089328721, -0.43930089 0.12989578 -0.089546427, -0.44053423 0.13001254 -0.089634284, -0.43930075 0.13027762 -0.089789733, -0.44048715 0.13038203 -0.089836881, -0.43930069 0.13070448 -0.089940861, -0.44048357 0.13065317 -0.089928284, -0.44050685 0.13093545 -0.089979991, -0.43930084 0.13115446 -0.089991972, -0.44052133 0.1311544 -0.089991972, -0.43930075 0.13971159 -0.089991733, -0.44052145 0.13971163 -0.089991584, -0.44111454 0.14197138 -0.087504938, -0.44117311 0.14196244 -0.087842539, -0.48781571 0.15188172 -0.11791418, -0.44119284 0.14190379 -0.088177517, -0.48765847 0.1517655 -0.11818038, -0.44119558 0.14179358 -0.088500068, -0.48754576 0.15160473 -0.11845018, -0.44120541 0.14174375 -0.088617936, -0.44120544 0.14158584 -0.088933811, -0.44685489 0.14211163 -0.093923613, -0.44677022 0.14204098 -0.093974367, -0.44670478 0.14196934 -0.094047561, -0.44120541 0.14158787 -0.088929757, -0.44695389 0.14217727 -0.093898192, -0.44666246 0.1419012 -0.094138846, -0.44706133 0.1422341 -0.093899652, -0.44664568 0.14184041 -0.094242588, -0.44717094 0.14227851 -0.093927845, -0.44665554 0.14179046 -0.094353005, -0.44668046 0.14176185 -0.094437048, -0.44727591 0.14230807 -0.093981043, -0.44671953 0.14174214 -0.09451808, -0.44677147 0.14173211 -0.09459354, -0.45927519 0.14291792 -0.10559331, -0.45934126 0.14288847 -0.10572277, -0.45930079 0.14289799 -0.10566054, -0.45926556 0.14294688 -0.10552509, -0.45927286 0.14298323 -0.10546027, -0.45929655 0.14302464 -0.10540269, -0.45933488 0.14306852 -0.10535608, -0.45938578 0.14311209 -0.10532306, -0.45944601 0.14315285 -0.10530622, -0.45951191 0.14318827 -0.1053059, -0.45957923 0.14321582 -0.1053227, -0.45964387 0.14323398 -0.10535525, -0.46758762 0.14384279 -0.11263268, -0.46750286 0.14377213 -0.1126834, -0.46743745 0.14370041 -0.11275668, -0.46768665 0.14390847 -0.11260723, -0.4673951 0.14363223 -0.11284797, -0.46779409 0.14396521 -0.11260848, -0.46737841 0.14357138 -0.11295162, -0.46790358 0.14400962 -0.11263688, -0.46738824 0.14352159 -0.11306207, -0.46741328 0.14349297 -0.11314593, -0.46800867 0.14403923 -0.11269008, -0.46745238 0.14347328 -0.11322711, -0.46750411 0.1434633 -0.11330245, -0.47823372 0.14468591 -0.1223314, -0.47814435 0.14459836 -0.12241076, -0.47818288 0.1446422 -0.12236433, -0.47829399 0.14472662 -0.12231441, -0.47835991 0.14476189 -0.12231405, -0.47811362 0.1445207 -0.12253331, -0.47812083 0.14455697 -0.12246843, -0.47842726 0.14478955 -0.12233086, -0.47814879 0.14447172 -0.12266885, -0.47812304 0.14449164 -0.12260149, -0.47849175 0.14480783 -0.12236349, -0.47818902 0.1444623 -0.12273093, -0.48565331 0.15047461 -0.11868675, -0.48583424 0.15050001 -0.11882956, -0.48745665 0.15136172 -0.11884101, -0.48598617 0.15049377 -0.11900453, -0.486101 0.15045613 -0.1192023, -0.48617241 0.15038924 -0.11941247, -0.48743236 0.15114208 -0.11925413, -0.48619667 0.15029673 -0.11962371, -0.48619664 0.14922501 -0.12176745, -0.4861829 0.14916441 -0.12187417, -0.48567289 0.14878036 -0.12209694, -0.48565319 0.14779393 -0.12404896, -0.48556596 0.14875019 -0.12204309, -0.48578414 0.14882579 -0.12212487, -0.48589313 0.14888386 -0.12212525, -0.48599297 0.14895107 -0.12209789, -0.48583421 0.14781934 -0.12419157, -0.4860779 0.14902312 -0.12204446, -0.4859862 0.14781313 -0.12436657, -0.48614243 0.14909562 -0.12196831, -0.48610094 0.14777552 -0.12456448, -0.48617235 0.14770856 -0.12477468, -0.48619655 0.14761603 -0.12498592, -0.48556599 0.14631322 -0.12691759, -0.48619655 0.14678796 -0.12664206, -0.48594454 0.14378269 -0.13238417, -0.48567292 0.14634345 -0.12697147, -0.48578423 0.1463889 -0.12699945, -0.48589304 0.14644697 -0.12699984, -0.48599294 0.14651398 -0.12697251, -0.48607787 0.14658611 -0.12691902, -0.48605171 0.14376163 -0.13254108, -0.4861424 0.14665855 -0.12684293, -0.48613119 0.1437197 -0.13270991, -0.48618272 0.14672731 -0.1267489, -0.48618016 0.14365856 -0.13288437, -0.48550293 0.14189522 -0.13568731, -0.48594454 0.14055744 -0.13883574, -0.48542044 0.14189343 -0.1356024, -0.48559931 0.14191343 -0.1357538, -0.48570386 0.14194708 -0.13579841, -0.48581073 0.14199415 -0.13581856, -0.48591396 0.1420521 -0.1358128, -0.48600772 0.14211774 -0.13578196, -0.4860867 0.14218724 -0.13572733, -0.48605171 0.1405362 -0.13899262, -0.48614642 0.14225674 -0.13565238, -0.48613113 0.1404943 -0.13916154, -0.48618388 0.14232245 -0.13556094, -0.48618013 0.14043324 -0.13933595, -0.48619652 0.1423804 -0.13545848, -0.48619658 0.14035513 -0.13950951, -0.48550317 0.13834731 -0.14278407, -0.48743233 0.1375353 -0.14647157, -0.48542044 0.13834558 -0.14269944, -0.48559931 0.13836561 -0.14285062, -0.4857038 0.13839917 -0.14289518, -0.48581073 0.1384463 -0.14291523, -0.48591399 0.13850422 -0.14290963, -0.48600772 0.13856995 -0.14287873, -0.4860867 0.13863932 -0.14282428, -0.48614642 0.13870881 -0.14274926, -0.48618385 0.13877454 -0.14265777, -0.48619661 0.13883248 -0.14255519, -0.48619661 0.1435805 -0.13305812, -0.44680607 0.14224918 -0.094422594, -0.44688085 0.14242962 -0.094554558, -0.44683436 0.1422905 -0.094370291, -0.44688487 0.14233275 -0.094339862, -0.4467316 0.14206879 -0.094290599, -0.44694829 0.1423678 -0.094337359, -0.44678789 0.14215139 -0.094185755, -0.44688895 0.14223576 -0.094125077, -0.44701591 0.1423059 -0.094120279, -0.46753904 0.14398041 -0.11313169, -0.46761367 0.14416093 -0.11326359, -0.46756706 0.14402166 -0.11307941, -0.46761766 0.14406374 -0.11304905, -0.46746421 0.14379983 -0.11299966, -0.46768114 0.14409895 -0.11304663, -0.46752062 0.1438825 -0.11289464, -0.46762177 0.14396694 -0.11283414, -0.46774855 0.14403704 -0.11282925, -0.48540375 0.14389212 -0.13282634, -0.47764829 0.14457163 -0.12317319, -0.48549721 0.14386062 -0.13298927, -0.48552158 0.14383002 -0.13307644, -0.48552987 0.14379109 -0.13316335, -0.48545739 0.14388165 -0.1329049, -0.48552969 0.14259088 -0.13556381, -0.48548195 0.14790624 -0.1248803, -0.48551765 0.14787285 -0.12498532, -0.48552975 0.14782661 -0.12509115, -0.48525807 0.14791554 -0.12462269, -0.48542455 0.14792511 -0.12478153, -0.48534867 0.14792822 -0.12469395, -0.48552987 0.14699858 -0.12674744, -0.4784556 0.14549321 -0.12219317, -0.47754082 0.14459702 -0.12300743, -0.47747216 0.14465007 -0.12282799, -0.47744682 0.14472742 -0.12264629, -0.47746614 0.14482419 -0.12247322, -0.47752896 0.14493464 -0.12231974, -0.47763148 0.14505149 -0.12219541, -0.47776732 0.14516798 -0.1221077, -0.47792795 0.14527665 -0.12206219, -0.47810361 0.14537075 -0.12206183, -0.47828308 0.14544442 -0.12210627, -0.48573402 0.14688531 -0.12677942, -0.48568425 0.14683704 -0.12682255, -0.48593828 0.14677197 -0.12681098, -0.48561451 0.14679532 -0.12683152, -0.48583862 0.14667556 -0.12689744, -0.48569939 0.14659213 -0.12691532, -0.4857353 0.14247951 -0.13559328, -0.48568919 0.14243315 -0.13563637, -0.48594096 0.14236811 -0.13562281, -0.48562342 0.14239199 -0.13564862, -0.48584843 0.1422755 -0.13570918, -0.485553 0.14236513 -0.13562717, -0.48571706 0.14219309 -0.13573362, -0.48557618 0.14213932 -0.13569055, -0.48525807 0.15059619 -0.1192605, -0.48549703 0.14063527 -0.13944097, -0.48552153 0.14060465 -0.13952811, -0.48552969 0.14056566 -0.13961492, -0.4854573 0.14065625 -0.13935639, -0.48540375 0.14066678 -0.13927792, -0.48552969 0.13904309 -0.14266057, -0.48548195 0.15058692 -0.11951832, -0.48551768 0.15055351 -0.11962326, -0.48552975 0.15050726 -0.11972897, -0.48542467 0.15060569 -0.11941953, -0.48534873 0.15060881 -0.11933176, -0.48552972 0.14943554 -0.12187274, -0.45880029 0.14299789 -0.10616489, -0.45869282 0.14302328 -0.10599934, -0.45862427 0.14307639 -0.10581981, -0.45859876 0.14315358 -0.10563801, -0.45861819 0.1432505 -0.10546507, -0.45868114 0.14336087 -0.1053115, -0.45878354 0.14347787 -0.10518716, -0.45891929 0.14359422 -0.10509954, -0.45907989 0.14370283 -0.10505389, -0.45925549 0.14379695 -0.10505365, -0.45943514 0.14387056 -0.10509823, -0.45960757 0.14391933 -0.1051849, -0.48573527 0.13893166 -0.14268996, -0.48568907 0.13888526 -0.1427332, -0.48594078 0.13882014 -0.14271958, -0.48562333 0.13884409 -0.14274545, -0.48584828 0.13872756 -0.14280595, -0.48555294 0.13881725 -0.14272387, -0.48571703 0.1386452 -0.1428303, -0.48557612 0.13859132 -0.14278723, -0.48573399 0.14932223 -0.12190469, -0.48568425 0.14927399 -0.12194784, -0.48593825 0.14920892 -0.12193663, -0.48561463 0.1492323 -0.12195678, -0.48583856 0.14911251 -0.12202273, -0.48569939 0.14902899 -0.12204091, -0.44078511 0.14173651 -0.08841379, -0.43930081 0.14185278 -0.088127837, -0.44084251 0.14185198 -0.08813031, -0.43930081 0.14173648 -0.08841379, -0.43930081 0.14192362 -0.087827191, -0.44089031 0.14192311 -0.087831125, -0.44090256 0.14194134 -0.087676153, -0.44077399 0.14165625 -0.088574126, -0.43930081 0.14150041 -0.088885888, -0.44077396 0.1415004 -0.088885769, -0.4412587 0.14132603 -0.089430794, -0.48753169 0.13729778 -0.14698769, -0.48761904 0.13701989 -0.14743684, -0.44126347 0.14096116 -0.089858517, -0.48768517 0.1367362 -0.14777125, -0.44126329 0.14054993 -0.090152606, -0.48772404 0.13651212 -0.14796375, -0.48775294 0.13628329 -0.14810278, -0.44127271 0.14023605 -0.090286866, -0.48777169 0.13605452 -0.14818679, -0.4405165 0.13983926 -0.089987412, -0.43930081 0.14015086 -0.089942798, -0.44050977 0.14018489 -0.089934811, -0.43930081 0.14056855 -0.089798614, -0.44053969 0.140515 -0.089823052, -0.44059679 0.14081858 -0.089657292, -0.43930081 0.14094448 -0.089566335, -0.44066918 0.14108726 -0.089443281, -0.43930081 0.14126027 -0.089256868, -0.44073868 0.14131519 -0.089186534, -0.44077393 0.14149904 -0.088888571, -0.48788968 0.15179782 -0.11870833, -0.48773506 0.1516809 -0.11857136, -0.48783052 0.15185811 -0.1181099, -0.4877817 0.15139015 -0.11937819, -0.48762277 0.15124848 -0.11930759, -0.4879013 0.15156004 -0.11946313, -0.48797569 0.15174951 -0.11955781, -0.48797569 0.1381427 -0.1467752, -0.48790124 0.13795321 -0.14668061, -0.48778155 0.13778339 -0.14659573, -0.48762262 0.13764167 -0.14652477, -0.48797545 0.13582994 -0.14862002, -0.48790076 0.13582994 -0.14840771, -0.48798314 0.13757591 -0.14771153, -0.48793152 0.13743964 -0.14759593, -0.48781198 0.13727289 -0.14745446, -0.48798707 0.13707735 -0.14822091, -0.48794755 0.1369824 -0.14809538, -0.48798892 0.13677128 -0.14843313, -0.48785588 0.13686354 -0.14793886, -0.48795435 0.13670006 -0.14830412, -0.48768547 0.13673647 -0.14777149, -0.48799011 0.13645686 -0.14858513, -0.48787424 0.13661034 -0.14814176, -0.48795921 0.13640964 -0.14845373, -0.48772445 0.13651219 -0.14796378, -0.48788777 0.13634989 -0.14828767, -0.48797914 0.12559663 -0.14695103, -0.48791543 0.12577578 -0.14686729, -0.48781219 0.12593904 -0.14679126, -0.48799112 0.12721777 -0.14863731, -0.48796281 0.12725432 -0.14850856, -0.48789737 0.12730089 -0.14834465, -0.48799011 0.12686746 -0.14849164, -0.48795918 0.1269314 -0.14836706, -0.48788729 0.12701222 -0.14820944, -0.48798814 0.12646677 -0.14821197, -0.48795173 0.12656327 -0.14809488, -0.48786706 0.12668419 -0.14794804, -0.48798579 0.12613308 -0.14786206, -0.48794201 0.12625834 -0.14775424, -0.48770919 0.12681553 -0.14778878, -0.48784062 0.12641387 -0.14762057, -0.48767415 0.12607948 -0.14672567, -0.48765406 0.12657633 -0.14748062, -0.48797899 0.11213602 -0.11808877, -0.48791537 0.11231527 -0.11800523, -0.48781213 0.11247839 -0.11792915, -0.48767406 0.11261894 -0.1178637, -0.4876681 0.11244147 -0.11745624, -0.48777282 0.11220457 -0.11711727, -0.48778683 0.11234106 -0.11752419, -0.48790506 0.11209001 -0.11724047, -0.48791096 0.11217995 -0.11762567, -0.47384092 0.1163058 -0.076521471, -0.47354937 0.088019609 -0.076026663, -0.47338137 0.11650525 -0.07566081, -0.47384074 0.088369131 -0.076522902, -0.47331646 0.087740034 -0.075498238, -0.47314647 0.087535948 -0.074948177, -0.47309574 0.11662899 -0.074718133, -0.47306564 0.087337732 -0.074552998, -0.47301668 0.087218106 -0.074151978, -0.49216035 0.10669017 -0.10399099, -0.48865727 0.11094788 -0.09873791, -0.49216041 0.1109481 -0.10399072, -0.4926199 0.1070579 -0.10485159, -0.49262109 0.11094812 -0.10485421, -0.49290541 0.1072863 -0.10579418, -0.49290481 0.1109482 -0.10579072, -0.49300072 0.10736245 -0.10676514, -0.49300069 0.11094828 -0.1067649, -0.49300086 0.15294963 -0.13145639, -0.49300089 0.1559483 -0.1073191, -0.49300089 0.15594977 -0.13437264, -0.49300084 0.15294828 -0.10731946, -0.49300078 0.13879906 -0.16755043, -0.49300078 0.13832754 -0.16760699, -0.49300081 0.13926181 -0.16737546, -0.49300078 0.13967198 -0.16708948, -0.49300081 0.13993396 -0.16680418, -0.49300078 0.14013132 -0.16648631, -0.49300069 0.12295148 -0.16643809, -0.4930006 0.10736388 -0.13301556, -0.49300072 0.12460926 -0.16203652, -0.49300069 0.11166427 -0.13427968, -0.49300069 0.11127391 -0.13323109, -0.49300069 0.11103071 -0.13207532, -0.4930006 0.11094958 -0.1308824, -0.49300084 0.13774736 -0.16319714, -0.49300072 0.1381973 -0.16269992, -0.49300078 0.13722049 -0.16359566, -0.49300075 0.13855202 -0.16212486, -0.49300072 0.13662848 -0.1638888, -0.49300078 0.13598272 -0.16406892, -0.49300078 0.13530956 -0.16412885, -0.49300072 0.12477809 -0.16760771, -0.49300066 0.12789501 -0.16412936, -0.49300066 0.1245259 -0.16759171, -0.49300069 0.12427041 -0.16754226, -0.49300072 0.12388602 -0.16739775, -0.49300072 0.12720478 -0.1640663, -0.49300095 0.15573885 -0.13526709, -0.49300072 0.12353477 -0.16717516, -0.49300072 0.12654421 -0.16387747, -0.49300072 0.12320969 -0.1668532, -0.49300072 0.12594122 -0.16357084, -0.49300072 0.12540843 -0.16315399, -0.49300066 0.12495799 -0.16263516, -0.49300089 0.15219237 -0.13484032, -0.49300084 0.15260571 -0.13380124, -0.49300095 0.15585519 -0.13498105, -0.49300095 0.15592612 -0.13468044, -0.49300086 0.15286371 -0.13264848, -0.49245521 0.13748452 -0.16216575, -0.49242344 0.1377414 -0.16171966, -0.49261639 0.13784719 -0.16177259, -0.49297804 0.13710894 -0.16341506, -0.49248144 0.13675947 -0.16284977, -0.49247488 0.13715275 -0.16254766, -0.49265662 0.13682368 -0.16295345, -0.49297684 0.13802268 -0.16256924, -0.49297512 0.13835074 -0.16202421, -0.49290571 0.13785635 -0.16244458, -0.49289957 0.13815987 -0.16192888, -0.49279132 0.1377068 -0.1623324, -0.49277791 0.13798903 -0.1618434, -0.49263889 0.13758077 -0.16223799, -0.49285933 0.13740067 -0.16281863, -0.49291065 0.13700248 -0.16324268, -0.49280187 0.13690592 -0.16308655, -0.49245694 0.12736732 -0.16319151, -0.49242339 0.12789489 -0.16322313, -0.49261642 0.12789489 -0.16334139, -0.49297813 0.12605496 -0.16339229, -0.49248454 0.1264115 -0.16283257, -0.49247769 0.12686576 -0.16305955, -0.49265879 0.1263458 -0.16293572, -0.49297681 0.12724453 -0.16385208, -0.49297509 0.12789494 -0.16390453, -0.49290594 0.12728247 -0.1636482, -0.49289945 0.12789491 -0.16369103, -0.49279207 0.12731659 -0.16346453, -0.49277782 0.12789492 -0.16350003, -0.49264014 0.12734534 -0.16331004, -0.49286011 0.12673141 -0.16340099, -0.49291119 0.12616335 -0.16322218, -0.49280313 0.1262619 -0.16306742, -0.49215826 0.1529481 -0.10454164, -0.49153641 0.15294804 -0.1037838, -0.49153653 0.15594812 -0.10378359, -0.4921582 0.15594813 -0.10454141, -0.49262038 0.15294816 -0.10540591, -0.49262029 0.15594818 -0.10540591, -0.4929049 0.15294823 -0.10634409, -0.49290475 0.15594825 -0.10634358, -0.48860273 0.15294793 -0.10085006, -0.4744654 0.15594731 -0.086712465, -0.47446522 0.14993924 -0.086712912, -0.4739615 0.14981066 -0.086124167, -0.4738436 0.15594724 -0.08595477, -0.47354811 0.14970501 -0.085451707, -0.47338146 0.15594719 -0.085090354, -0.47313705 0.14960004 -0.084336147, -0.473097 0.15594718 -0.084152415, -0.49242356 0.15138172 -0.13443507, -0.49242339 0.13530956 -0.16322266, -0.49242327 0.1124856 -0.13389663, -0.49242339 0.1254306 -0.16165335, -0.49219796 0.11205792 -0.13228954, -0.49231568 0.11223453 -0.13312952, -0.49214986 0.15188518 -0.1325057, -0.49229386 0.15169169 -0.1335205, -0.47600088 0.15691414 -0.13483445, -0.49200091 0.15691423 -0.13483445, -0.47600082 0.1568078 -0.13528521, -0.49200091 0.15680778 -0.13528521, -0.47600096 0.15663344 -0.13571422, -0.49200085 0.15663318 -0.13571422, -0.48208418 0.15366644 -0.14164896, -0.48147532 0.15342528 -0.14213128, -0.48101315 0.15312579 -0.14273016, -0.48280445 0.15383546 -0.14131077, -0.48072451 0.15278576 -0.14341043, -0.48359415 0.15392236 -0.14113651, -0.48062673 0.15242466 -0.14413263, -0.4844076 0.15392259 -0.14113651, -0.48519731 0.15383539 -0.14131074, -0.48591757 0.15366629 -0.14164896, -0.48652655 0.15342513 -0.14213128, -0.48698869 0.15312578 -0.14273019, -0.48727709 0.15278579 -0.14341052, -0.48737508 0.1524246 -0.14413275, -0.4760007 0.14004371 -0.16889803, -0.48062658 0.14032766 -0.16833009, -0.49200067 0.14102574 -0.1669334, -0.48737517 0.14074187 -0.16750138, -0.49210951 0.13888198 -0.1685494, -0.47610506 0.13805184 -0.17048149, -0.49209177 0.13943633 -0.16839008, -0.49212253 0.13832769 -0.16859965, -0.47612259 0.13734563 -0.1705641, -0.48074111 0.14014865 -0.16863792, -0.47602591 0.13974929 -0.16937189, -0.48083866 0.13993677 -0.16891532, -0.476051 0.13935784 -0.16979669, -0.48090538 0.13977729 -0.16908504, -0.48099059 0.13960519 -0.16923927, -0.481163 0.13930698 -0.16944994, -0.47608051 0.13874432 -0.17022197, -0.48120859 0.1392483 -0.16948389, -0.48124054 0.1392201 -0.16949825, -0.49203274 0.14063406 -0.16752885, -0.48716292 0.14032489 -0.16813897, -0.48704731 0.1400494 -0.16843139, -0.48127845 0.13919744 -0.16950868, -0.48132148 0.13918243 -0.16951381, -0.48134807 0.13917823 -0.16951396, -0.49206415 0.14009117 -0.16803192, -0.48695138 0.13985851 -0.16859902, -0.48683861 0.13965535 -0.16875316, -0.48674497 0.13954613 -0.16882975, -0.48670945 0.13952377 -0.16884612, -0.4867852 0.13958228 -0.16880415, -0.48681423 0.1396175 -0.16877963, -0.48666966 0.13950779 -0.16885875, -0.47612265 0.13529773 -0.17056431, -0.49212262 0.12477812 -0.16860031, -0.47533205 0.13509668 -0.17066132, -0.47601286 0.13529097 -0.17057778, -0.47575638 0.13525809 -0.17060925, -0.47552589 0.1351923 -0.17063753, -0.47533199 0.12573974 -0.17066179, -0.47600231 0.13529395 -0.17057173, -0.48116305 0.15205593 -0.1439483, -0.48083881 0.15234597 -0.14409344, -0.48716301 0.15234604 -0.14409344, -0.48675621 0.15235971 -0.14334096, -0.48683879 0.15205599 -0.14394842, -0.48707113 0.15268436 -0.1434166, -0.4865137 0.15264574 -0.14276884, -0.48680076 0.15300311 -0.14277898, -0.48612505 0.15289745 -0.14226516, -0.48636785 0.15328364 -0.14221795, -0.48561296 0.1531004 -0.14185937, -0.4857972 0.15350975 -0.14176576, -0.48500732 0.15324251 -0.14157505, -0.48512226 0.15366825 -0.14144893, -0.48434302 0.15331578 -0.14142857, -0.48438215 0.15374973 -0.1412857, -0.48365882 0.15331578 -0.14142857, -0.48361984 0.15374978 -0.14128573, -0.48299459 0.15324254 -0.14157505, -0.48287964 0.15366821 -0.14144893, -0.48238882 0.15310034 -0.14185937, -0.4822045 0.15350971 -0.14176579, -0.48187673 0.1528974 -0.14226516, -0.48163405 0.15328367 -0.14221795, -0.48148814 0.15264566 -0.14276873, -0.48120096 0.15300307 -0.14277889, -0.48124537 0.15235966 -0.14334096, -0.48093066 0.15268452 -0.1434166, -0.49210551 0.12405586 -0.16851379, -0.49208364 0.12341647 -0.16827713, -0.49206033 0.122894 -0.16794096, -0.49203464 0.12245567 -0.1675099, -0.49201754 0.12222676 -0.1671937, -0.49247488 0.13631359 -0.1630664, -0.49245527 0.1358235 -0.16319261, -0.49247769 0.12601389 -0.16251682, -0.49245694 0.12568228 -0.16211815, -0.45584354 0.15574774 -0.093410626, -0.45646539 0.15574774 -0.09416844, -0.45646521 0.15594767 -0.094168261, -0.45584354 0.15594776 -0.093410775, -0.45538148 0.15574768 -0.092546239, -0.45538148 0.15594772 -0.09254615, -0.45509693 0.15574761 -0.09160836, -0.45509693 0.15594772 -0.091608271, -0.47353646 0.15574859 -0.11123954, -0.47353646 0.15594862 -0.11123954, -0.47415826 0.1557487 -0.11199705, -0.47415835 0.15594871 -0.11199705, -0.47462031 0.15574868 -0.11286162, -0.47462031 0.15594871 -0.11286162, -0.47490475 0.15574874 -0.11379959, -0.47490481 0.15594873 -0.11379956, -0.47500083 0.15574878 -0.11477496, -0.47500083 0.15594882 -0.11477502, -0.47500086 0.15594991 -0.13437264, -0.47500095 0.15574993 -0.13479771, -0.47500089 0.15592614 -0.13468044, -0.47500089 0.15585522 -0.13498105, -0.47500083 0.15573883 -0.13526709, -0.47500077 0.13914931 -0.16845094, -0.47500071 0.13857687 -0.16914858, -0.47500077 0.13899422 -0.16871084, -0.47500077 0.1388012 -0.16894604, -0.47604153 0.13734557 -0.17057078, -0.47608206 0.13734561 -0.17056827, -0.47595951 0.13878126 -0.1702048, -0.47604606 0.13860729 -0.1702918, -0.47519121 0.1390821 -0.16949008, -0.47532579 0.13865642 -0.16997518, -0.47531545 0.13917674 -0.16959502, -0.47596607 0.13860743 -0.1702923, -0.4754487 0.13961665 -0.16927145, -0.47546205 0.13925308 -0.16968001, -0.47560045 0.13930248 -0.16973497, -0.47556689 0.13995519 -0.16885386, -0.47537735 0.13984865 -0.16880064, -0.4757967 0.13859893 -0.17027347, -0.47580487 0.1383269 -0.17038517, -0.47597566 0.13833307 -0.17040335, -0.47558367 0.13967647 -0.16931663, -0.47548622 0.13828629 -0.170269, -0.47533187 0.13824901 -0.17016174, -0.47563121 0.13830999 -0.17033677, -0.47510025 0.13898055 -0.16937707, -0.47519729 0.13858838 -0.16985022, -0.47510344 0.13851465 -0.16971485, -0.47579065 0.13877097 -0.17018582, -0.47504243 0.13844046 -0.16957857, -0.47530642 0.1395255 -0.16920237, -0.47521898 0.13970695 -0.16872971, -0.47562429 0.13857681 -0.17022608, -0.4750272 0.1388426 -0.16922374, -0.47518563 0.13941373 -0.16911794, -0.47509989 0.13953748 -0.16864498, -0.47548082 0.13854653 -0.17016046, -0.47561944 0.13874556 -0.17013918, -0.47509751 0.13929383 -0.16902722, -0.47502586 0.1393483 -0.16855042, -0.47547701 0.13871089 -0.17007546, -0.47502658 0.13913153 -0.16890456, -0.47532865 0.1384986 -0.17005704, -0.47520009 0.13830844 -0.16998552, -0.47601163 0.13935836 -0.16979711, -0.47593316 0.13935684 -0.16979544, -0.47519901 0.13843861 -0.16992752, -0.47510406 0.13837363 -0.1697873, -0.47576734 0.13933989 -0.16977672, -0.47606486 0.1380526 -0.17048411, -0.47598711 0.13974908 -0.16937174, -0.47598407 0.13805299 -0.17048614, -0.47590956 0.13974574 -0.16936921, -0.47605595 0.13833275 -0.17040206, -0.47577828 0.14002134 -0.16888683, -0.47581232 0.13804889 -0.1704687, -0.47563744 0.13803698 -0.17041962, -0.47574693 0.13972302 -0.16935204, -0.47502604 0.15593798 -0.13536669, -0.47509989 0.1561269 -0.13546111, -0.47521916 0.15629657 -0.13554598, -0.47537741 0.1564382 -0.13561679, -0.47556695 0.1565448 -0.13567002, -0.47577843 0.15661092 -0.1357031, -0.47577843 0.15678391 -0.13527776, -0.47577837 0.15688953 -0.13483052, -0.47556698 0.15681632 -0.13481899, -0.47556698 0.15671356 -0.13525529, -0.47577834 0.1569248 -0.13437264, -0.47502586 0.15614593 -0.13471501, -0.4750261 0.15617248 -0.13437264, -0.47509995 0.15635477 -0.13474734, -0.47509989 0.15638384 -0.13437264, -0.47502598 0.15606715 -0.13504894, -0.47521916 0.15654215 -0.13477673, -0.4752191 0.15657334 -0.13437264, -0.47510001 0.15626857 -0.13511313, -0.47537741 0.15669867 -0.13480087, -0.47537747 0.15673171 -0.13437264, -0.4752191 0.15644915 -0.13517071, -0.47556695 0.1568509 -0.13437264, -0.47537747 0.15660004 -0.1352189, -0.47502598 0.15617131 -0.11477502, -0.47510001 0.15638275 -0.11477502, -0.4752191 0.15657231 -0.11477502, -0.47537741 0.15673062 -0.11477502, -0.47556698 0.15684985 -0.11477502, -0.47577837 0.15692379 -0.11477502, -0.47482178 0.15657207 -0.11277817, -0.47527409 0.15673061 -0.11372592, -0.47496819 0.15673055 -0.11271738, -0.47511885 0.15657231 -0.11375682, -0.47462907 0.15684965 -0.11168276, -0.47408611 0.15692352 -0.11068963, -0.47393671 0.15684961 -0.11083902, -0.47533858 0.15692361 -0.11256401, -0.47480473 0.15692362 -0.1115651, -0.47514331 0.1568497 -0.1126449, -0.47471178 0.15638258 -0.11282359, -0.47500196 0.15638269 -0.1137801, -0.47447136 0.15673056 -0.11178778, -0.47380283 0.15673038 -0.1109731, -0.4746435 0.15617117 -0.11285208, -0.47492936 0.15617137 -0.11379449, -0.47433969 0.15657219 -0.11187588, -0.47369072 0.15657207 -0.11108528, -0.47424063 0.15638264 -0.11194204, -0.4736065 0.15638259 -0.11116947, -0.47417906 0.15617122 -0.11198328, -0.47355428 0.15617122 -0.11122166, -0.47566739 0.15692361 -0.1136478, -0.47546008 0.15684973 -0.11368899, -0.45648316 0.15617028 -0.094150648, -0.45653549 0.1563817 -0.094098255, -0.45661971 0.15657128 -0.094014063, -0.45673168 0.15672959 -0.093902126, -0.4568657 0.15684873 -0.093768016, -0.45701513 0.15692261 -0.093618616, -0.4557294 0.15672955 -0.092402086, -0.4554663 0.15672949 -0.091534749, -0.45531097 0.15657116 -0.091565743, -0.45558307 0.15657121 -0.092462793, -0.45585957 0.15692255 -0.091456577, -0.4556523 0.15684862 -0.091497794, -0.45602506 0.15657122 -0.09328936, -0.45547292 0.15638162 -0.092508301, -0.45592591 0.15638162 -0.093355671, -0.45590448 0.15684868 -0.092329785, -0.4561567 0.15672958 -0.093201503, -0.45609984 0.15692267 -0.092248693, -0.45631433 0.15684868 -0.093096033, -0.45649001 0.15692265 -0.092978761, -0.45512161 0.15617016 -0.091603383, -0.45519415 0.15638153 -0.091589019, -0.45540461 0.15617025 -0.092536733, -0.45586446 0.15617038 -0.093396679, -0.47384512 0.11651401 -0.076568857, -0.47263601 0.11748156 -0.074870065, -0.47279426 0.11735824 -0.074829921, -0.47292387 0.1172048 -0.074793324, -0.47301981 0.11702736 -0.074761584, -0.47307804 0.11683282 -0.074736223, -0.47296882 0.11736064 -0.075959906, -0.47350416 0.11716579 -0.076953396, -0.47311732 0.11723869 -0.075879917, -0.47363672 0.11704625 -0.076836303, -0.47374064 0.11689283 -0.076729849, -0.47323713 0.11708516 -0.075807407, -0.47332343 0.1169067 -0.075745001, -0.47381112 0.11671264 -0.076639399, -0.47337219 0.11671069 -0.07569541, -0.48826727 0.11182895 -0.099103227, -0.4884083 0.11170748 -0.098994747, -0.48852476 0.11154665 -0.098897979, -0.48860708 0.11135663 -0.098820403, -0.48865098 0.11115216 -0.09876661, -0.49151358 0.11192299 -0.10442214, -0.49168935 0.11184908 -0.10430478, -0.49184713 0.11172996 -0.10419975, -0.49197879 0.11157148 -0.10411166, -0.49207801 0.11138198 -0.10404561, -0.49213952 0.11117066 -0.10400461, -0.49288017 0.11117066 -0.10579585, -0.49290147 0.11138211 -0.1067649, -0.49297562 0.11117077 -0.10676505, -0.49280772 0.11138202 -0.10581027, -0.49259797 0.11117066 -0.10486372, -0.49252972 0.11138202 -0.10489188, -0.49222311 0.11192319 -0.10676505, -0.49190268 0.11192308 -0.10515116, -0.49209806 0.11184914 -0.10507049, -0.49214229 0.1119231 -0.10594235, -0.49227318 0.11172999 -0.1049981, -0.49234948 0.11184914 -0.10590108, -0.4924345 0.11184914 -0.1067649, -0.49241954 0.11157157 -0.10493742, -0.49253556 0.11173005 -0.10586412, -0.4926241 0.11173007 -0.1067649, -0.49269077 0.11157161 -0.10583337, -0.49278244 0.11157164 -0.1067649, -0.49297553 0.11117209 -0.13088252, -0.49290162 0.11138351 -0.13088252, -0.49278244 0.11157304 -0.13088252, -0.49262407 0.11173141 -0.13088252, -0.49243444 0.11185052 -0.1308824, -0.49222311 0.11192447 -0.1308824, -0.49261627 0.11237836 -0.1339467, -0.49277773 0.11223458 -0.13401379, -0.49298337 0.11145186 -0.13318004, -0.49297503 0.11186807 -0.13418473, -0.49293354 0.11161982 -0.13313164, -0.49289933 0.11206149 -0.13409437, -0.4928543 0.11177447 -0.13308693, -0.49272165 0.11193979 -0.13303928, -0.49252298 0.11209327 -0.13299493, -0.49297956 0.11123295 -0.13204755, -0.49291819 0.1114244 -0.13202132, -0.49281999 0.11159851 -0.13199748, -0.49265659 0.11177865 -0.13197269, -0.49241647 0.11193165 -0.1319517, -0.49261639 0.1253234 -0.16170321, -0.49277785 0.12517951 -0.16177033, -0.49289951 0.12500656 -0.16185115, -0.49297512 0.12481306 -0.16194151, -0.49297768 0.12555556 -0.1629995, -0.49291003 0.12569571 -0.1628518, -0.49280053 0.12582251 -0.16271849, -0.49265435 0.12593004 -0.16260515, -0.49285406 0.12538283 -0.16233192, -0.49261639 0.13530952 -0.16334088, -0.49277791 0.13530955 -0.1634997, -0.49289957 0.13530944 -0.16369052, -0.49297509 0.13530946 -0.16390406, -0.49297771 0.13655198 -0.1636885, -0.4929094 0.13647898 -0.16349815, -0.49279937 0.13641308 -0.16332613, -0.49265254 0.13635702 -0.16317995, -0.49285355 0.13588937 -0.16355465, -0.49261653 0.15148756 -0.13448791, -0.49277809 0.15162946 -0.13455884, -0.49289969 0.15180027 -0.13464431, -0.49297538 0.1519912 -0.13473989, -0.49297592 0.15272719 -0.13145639, -0.49222344 0.15197483 -0.13145639, -0.49297974 0.15266167 -0.13261895, -0.49291858 0.15247047 -0.13259117, -0.49278268 0.15232614 -0.13145639, -0.49290204 0.15251586 -0.13145639, -0.49282041 0.15229659 -0.13256587, -0.49262446 0.15216789 -0.13145639, -0.4926571 0.15211697 -0.13253953, -0.49243489 0.15204872 -0.13145639, -0.49241719 0.15196387 -0.13251723, -0.49280891 0.15213877 -0.13328247, -0.49280486 0.15203713 -0.13362671, -0.49284169 0.15197612 -0.13397492, -0.4929758 0.1527258 -0.10731946, -0.49290195 0.15251435 -0.10731946, -0.49278274 0.15232478 -0.10731946, -0.49262443 0.1521665 -0.10731946, -0.49243477 0.15204737 -0.10731946, -0.49222347 0.15197344 -0.10731922, -0.4924188 0.15232487 -0.10548936, -0.49269089 0.15232471 -0.1063865, -0.49253556 0.15216647 -0.10641752, -0.49227247 0.15216635 -0.10555001, -0.49288031 0.15272568 -0.10634889, -0.49280778 0.15251435 -0.1063634, -0.4918451 0.15216632 -0.10475062, -0.49113613 0.15204719 -0.10418423, -0.49127027 0.15216638 -0.10405, -0.49209729 0.15204729 -0.10562243, -0.49168754 0.15204719 -0.10485609, -0.49252895 0.15251435 -0.10544394, -0.49197683 0.15232469 -0.10466276, -0.49138215 0.15232466 -0.10393806, -0.49259707 0.15272568 -0.10541545, -0.49207577 0.15251413 -0.10459648, -0.49146637 0.15251414 -0.10385381, -0.49213746 0.15272558 -0.10455547, -0.49151877 0.15272559 -0.10380144, -0.49214226 0.15197334 -0.10649548, -0.49234962 0.15204731 -0.10645436, -0.49190208 0.15197334 -0.10570346, -0.49151179 0.15197323 -0.10497339, -0.49098665 0.15197317 -0.10433359, -0.48820302 0.152017 -0.10134856, -0.48834565 0.15213004 -0.10119398, -0.48846576 0.15229501 -0.10105641, -0.48855132 0.15249948 -0.10094889, -0.48859665 0.15272394 -0.10087995, -0.47412118 0.14902276 -0.087252155, -0.47425571 0.14913569 -0.087093666, -0.47436246 0.14929359 -0.086953148, -0.47443518 0.14948756 -0.086839184, -0.47447029 0.14970694 -0.086757258, -0.47328326 0.14884317 -0.086198881, -0.47344723 0.14895876 -0.086082891, -0.4735814 0.14911729 -0.085979298, -0.47367847 0.14931008 -0.085894421, -0.47373301 0.14952663 -0.085832551, -0.47270581 0.14871943 -0.084954724, -0.47288939 0.14883685 -0.084887102, -0.47304192 0.14899552 -0.084826812, -0.47315547 0.14918709 -0.084776953, -0.47249356 0.14867398 -0.08406876, -0.47322401 0.14940143 -0.08473976, -0.47268417 0.14879212 -0.084035233, -0.47284347 0.14895071 -0.084004864, -0.47296312 0.14914189 -0.08397983, -0.473037 0.14935549 -0.083960965, -0.47317991 0.15657063 -0.085174039, -0.47288314 0.15657064 -0.084194973, -0.47272775 0.15672904 -0.084225729, -0.47303364 0.156729 -0.085234478, -0.47337294 0.15684827 -0.086269364, -0.47391561 0.15692209 -0.087262347, -0.47406507 0.15684821 -0.087112769, -0.47266322 0.15692209 -0.0853879, -0.4731971 0.15692218 -0.086386785, -0.4728584 0.1568481 -0.085306987, -0.47329006 0.15638103 -0.085128412, -0.47299981 0.15638103 -0.084171817, -0.4735305 0.15672907 -0.086164072, -0.47419909 0.15672912 -0.086978778, -0.47335842 0.15616967 -0.08510004, -0.47307238 0.15616971 -0.084157303, -0.47366211 0.1565707 -0.086075947, -0.47431114 0.15657063 -0.08686693, -0.47376123 0.15638116 -0.086009815, -0.47439536 0.15638116 -0.08678247, -0.47382268 0.15616986 -0.085968688, -0.47444758 0.15616979 -0.086730197, -0.47233436 0.15692207 -0.08430405, -0.47254175 0.15684809 -0.084262922, -0.49151877 0.15617068 -0.10380132, -0.49146637 0.15638204 -0.10385354, -0.49138215 0.15657158 -0.10393785, -0.4912703 0.15673003 -0.10404979, -0.4911361 0.15684904 -0.1041839, -0.49098673 0.15692303 -0.10433327, -0.49227265 0.15673001 -0.1055498, -0.49269095 0.15657173 -0.10638617, -0.49241874 0.15657164 -0.10548912, -0.49214235 0.15692317 -0.10649548, -0.49222341 0.15692328 -0.1073191, -0.49243477 0.15684932 -0.10731922, -0.49234959 0.15684918 -0.10645412, -0.49197686 0.1565716 -0.10466252, -0.49207583 0.15638198 -0.10459636, -0.49252877 0.1563821 -0.10544358, -0.49209732 0.1568491 -0.10562228, -0.49253556 0.15673015 -0.10641702, -0.49184516 0.15672997 -0.10475035, -0.49190196 0.15692316 -0.10570295, -0.49168754 0.1568491 -0.10485588, -0.4915117 0.15692307 -0.10497321, -0.4928802 0.1561708 -0.1063485, -0.49297586 0.15617083 -0.1073191, -0.49280778 0.1563821 -0.10636301, -0.49290189 0.1563822 -0.1073191, -0.49259707 0.15617082 -0.10541518, -0.49278268 0.15657184 -0.1073191, -0.49262437 0.15673015 -0.1073191, -0.4921374 0.15617061 -0.1045552, -0.49297586 0.15617229 -0.13437264, -0.49290186 0.15638359 -0.13437264, -0.49278271 0.15657325 -0.13437264, -0.49262446 0.15673168 -0.13437264, -0.49243474 0.15685077 -0.13437264, -0.49222335 0.15692469 -0.13437264, -0.49222353 0.15688945 -0.13483052, -0.49222353 0.15678383 -0.13527776, -0.49243483 0.15671344 -0.13525529, -0.4924348 0.15681632 -0.13481919, -0.4929758 0.15593773 -0.13536669, -0.49297592 0.15606704 -0.13504867, -0.49290195 0.15626833 -0.13511313, -0.49290189 0.15612681 -0.13546126, -0.49297586 0.15614593 -0.13471486, -0.49278271 0.15644903 -0.13517086, -0.49278283 0.15629645 -0.13554589, -0.49290177 0.1563547 -0.13474734, -0.49262446 0.15659989 -0.1352189, -0.49262443 0.15643819 -0.13561679, -0.49278274 0.15654206 -0.13477673, -0.49243483 0.15654455 -0.13567002, -0.49262446 0.15669848 -0.13480087, -0.4922235 0.15661088 -0.1357031, -0.49297577 0.1403304 -0.16658582, -0.49290177 0.14051938 -0.16668032, -0.49278262 0.140689 -0.16676508, -0.49262437 0.14083058 -0.16683592, -0.49243477 0.14093716 -0.16688909, -0.49222326 0.14100334 -0.1669222, -0.49290892 0.13975111 -0.16756283, -0.49290553 0.14019473 -0.16715969, -0.49279094 0.14033768 -0.16727994, -0.49279889 0.13985901 -0.1677116, -0.49249372 0.1393895 -0.16827257, -0.49247584 0.14002173 -0.16793625, -0.49227691 0.14006944 -0.16800217, -0.49230018 0.13942066 -0.1683508, -0.49297735 0.1396316 -0.16739775, -0.49297661 0.14003582 -0.16702618, -0.49266446 0.13934423 -0.16815926, -0.49265257 0.13995053 -0.16783796, -0.49231493 0.13887353 -0.1685047, -0.49235639 0.13832761 -0.16854168, -0.49280596 0.13928697 -0.16801523, -0.49250513 0.13885763 -0.16842045, -0.49256954 0.13832764 -0.16842954, -0.49291208 0.13921997 -0.1678469, -0.49267226 0.13883488 -0.16830014, -0.49274972 0.1383276 -0.16826965, -0.49297819 0.13914591 -0.16766094, -0.49281037 0.1388063 -0.16814877, -0.49288639 0.13832763 -0.1680712, -0.49291399 0.13877301 -0.16797222, -0.49297184 0.13832761 -0.1678461, -0.49297875 0.13873626 -0.1677774, -0.49225053 0.14060967 -0.16750835, -0.49245569 0.14055015 -0.16745828, -0.49263862 0.14045791 -0.16738091, -0.49297166 0.12477808 -0.1678469, -0.49288633 0.12477802 -0.16807221, -0.49274966 0.12477802 -0.16827039, -0.49256954 0.12477809 -0.16843022, -0.49235633 0.12477809 -0.16854237, -0.49280414 0.12362096 -0.16793068, -0.49280933 0.12415408 -0.16811897, -0.49267045 0.12411682 -0.16826878, -0.49266154 0.12355193 -0.1680695, -0.49247432 0.12298939 -0.16786645, -0.49248925 0.12349761 -0.16817869, -0.49229431 0.12346038 -0.16825353, -0.49227464 0.12293926 -0.16793002, -0.49291119 0.12370197 -0.16776775, -0.49291357 0.12419756 -0.16794442, -0.49265125 0.12306453 -0.16777121, -0.49297783 0.12379162 -0.16758756, -0.49297848 0.12424546 -0.1677516, -0.49225214 0.12248065 -0.16748939, -0.49279824 0.12316118 -0.16764863, -0.49245688 0.12254071 -0.16743992, -0.49290857 0.12327522 -0.16750415, -0.4922376 0.12225103 -0.16717862, -0.49222317 0.12206785 -0.16685019, -0.49263951 0.12263359 -0.16736306, -0.49297726 0.12340155 -0.16734408, -0.49244568 0.12231538 -0.16713811, -0.49243441 0.1221348 -0.16681884, -0.49279132 0.12275486 -0.16726305, -0.49263176 0.12241675 -0.16707443, -0.49262425 0.12224287 -0.16676857, -0.49231151 0.12406667 -0.1684704, -0.49290559 0.12289865 -0.16714419, -0.49250242 0.12408732 -0.16838734, -0.49278685 0.12255035 -0.16699038, -0.4927825 0.1223864 -0.16670157, -0.49297664 0.12305844 -0.16701244, -0.49290356 0.1227095 -0.16689007, -0.49290153 0.12255818 -0.16662143, -0.4929761 0.12288673 -0.1667787, -0.49297562 0.12274976 -0.1665322, -0.49297556 0.1071623 -0.1331095, -0.49290147 0.10697064 -0.13319899, -0.49278244 0.10679884 -0.13327901, -0.49262413 0.10665545 -0.1333461, -0.49243441 0.10654743 -0.13339637, -0.49222311 0.1064804 -0.13342752, -0.49256268 0.10654558 -0.13313504, -0.47535279 0.089333832 -0.096229717, -0.4923909 0.10647328 -0.13324897, -0.47518119 0.089261651 -0.096343532, -0.49220046 0.10644352 -0.13335158, -0.47499064 0.089231864 -0.096446052, -0.49298134 0.10716876 -0.13301556, -0.49292448 0.10698123 -0.13301556, -0.49283198 0.10680835 -0.13301568, -0.49257043 0.10659516 -0.13330601, -0.49298134 0.10716732 -0.10676514, -0.49292433 0.1069797 -0.10676529, -0.49283198 0.10680684 -0.10676514, -0.49213603 0.10612254 -0.10438596, -0.49219194 0.10629342 -0.10423456, -0.49275324 0.10672927 -0.10593461, -0.49284157 0.10690197 -0.10588311, -0.49289295 0.10709022 -0.10583554, -0.49251673 0.10649665 -0.10512693, -0.4925929 0.1066689 -0.10502385, -0.49220017 0.10648616 -0.10410045, -0.49262777 0.1068591 -0.10493074, -0.47388056 0.088165134 -0.076632574, -0.47387221 0.087972313 -0.076766685, -0.47381631 0.087801591 -0.076917872, -0.47334501 0.087461144 -0.075744256, -0.47322547 0.087464035 -0.075283363, -0.47336683 0.087622821 -0.075670734, -0.47329378 0.087310195 -0.075825021, -0.47319689 0.087303266 -0.075342372, -0.47314012 0.087152556 -0.075406656, -0.47326055 0.087244928 -0.075864658, -0.47310489 0.087087154 -0.075437918, -0.47356907 0.087850288 -0.076103285, -0.47320399 0.087159693 -0.075921312, -0.47304609 0.087001145 -0.075483099, -0.473557 0.087687269 -0.076192722, -0.47351363 0.087535799 -0.076292351, -0.47348335 0.087470889 -0.076341256, -0.47343031 0.087386787 -0.076411352, -0.47316146 0.087391794 -0.075065508, -0.47311774 0.087218881 -0.075072125, -0.47314614 0.087374747 -0.075007632, -0.47319248 0.087426811 -0.075175628, -0.47312945 0.087231398 -0.075116113, -0.47316208 0.087266207 -0.075230435, -0.47307044 0.087080896 -0.075171217, -0.47310427 0.087115586 -0.075290278, -0.47306836 0.08705017 -0.075319275, -0.47298115 0.086927414 -0.075512722, -0.47298899 0.087027013 -0.073748931, -0.47298911 0.087026715 -0.062616929, -0.47295475 0.086879224 -0.073748931, -0.47295475 0.086878419 -0.062568501, -0.44233757 0.03992863 -0.0084519833, -0.4110001 0.039923981 -0.0084782094, -0.44229457 0.039884701 -0.008619234, -0.4110001 0.039867088 -0.008665666, -0.44222388 0.039812446 -0.0087770075, -0.4110001 0.039774612 -0.0088384897, -0.44215056 0.039737731 -0.0088899583, -0.4110001 0.039650351 -0.0089900941, -0.44206473 0.039650112 -0.0089900941, -0.4413721 0.038235947 -0.010404423, -0.4110001 0.038236141 -0.010404423, -0.45678154 0.067893535 -0.0097930282, -0.45676866 0.067854956 -0.0098903924, -0.45665875 0.067787454 -0.0097265691, -0.45664683 0.067758232 -0.0098000318, -0.45671499 0.06772615 -0.010065719, -0.45675305 0.067806244 -0.0099806637, -0.45685819 0.067769483 -0.010193929, -0.45663241 0.06772235 -0.0098665506, -0.45679322 0.067927554 -0.0096583813, -0.45697096 0.067996725 -0.0098712295, -0.45698225 0.06804134 -0.0097005516, -0.45719317 0.068110064 -0.0097355396, -0.45695856 0.067945302 -0.0099961609, -0.45694378 0.067878827 -0.010113254, -0.45699552 0.067785114 -0.010287747, -0.45718351 0.068054229 -0.0099360794, -0.45653477 0.067597643 -0.0098206848, -0.45717314 0.067989647 -0.010082468, -0.45716107 0.067905232 -0.010219559, -0.45717135 0.067778081 -0.010377184, -0.45740762 0.068063766 -0.0099837631, -0.45740017 0.067986175 -0.010144547, -0.45739201 0.067884609 -0.01029323, -0.45658484 0.067706525 -0.00959225, -0.45666972 0.067813784 -0.009622559, -0.45657524 0.067685977 -0.009669587, -0.45656499 0.067663848 -0.0097224563, -0.45655319 0.067637965 -0.0097679049, -0.45661131 0.067667753 -0.0099422187, -0.44309825 0.040235624 -0.0088848323, -0.44289497 0.039954692 -0.0091125816, -0.44297549 0.040107295 -0.0088176578, -0.44301483 0.040181577 -0.0085521489, -0.44286796 0.040072262 -0.0085210949, -0.44282863 0.040004954 -0.0087555498, -0.44313881 0.040316746 -0.0085858554, -0.44226095 0.039617479 -0.009053573, -0.44239753 0.039785773 -0.0088589638, -0.44258019 0.039810374 -0.0089291781, -0.44261929 0.039648876 -0.0092605203, -0.44244859 0.039617077 -0.0091450363, -0.44248268 0.039891571 -0.0086544603, -0.44274804 0.039867386 -0.0090147108, -0.44266257 0.039932296 -0.0087005943, -0.44276616 0.039711565 -0.0093950778, -0.44252428 0.039943382 -0.0084701031, -0.44301531 0.040069029 -0.0092192441, -0.44288224 0.039802447 -0.0095428377, -0.44270286 0.039991975 -0.0084935278, -0.45717064 0.067181915 -0.010668024, -0.45716071 0.067610338 -0.010516956, -0.45697251 0.067278564 -0.010586724, -0.45679656 0.067363843 -0.01045607, -0.45697799 0.067646071 -0.010418996, -0.45683733 0.067656532 -0.010309175, -0.45665279 0.067433178 -0.010283455, -0.45669404 0.06764549 -0.010153726, -0.45654908 0.067482546 -0.010078445, -0.4565244 0.067572102 -0.0098504871, -0.4564977 0.067506552 -0.0098907799, -0.44149169 0.038269371 -0.010378018, -0.44162041 0.038325146 -0.010343894, -0.44189912 0.038506046 -0.010252759, -0.44247839 0.039118364 -0.0099951774, -0.44298539 0.039906383 -0.0099196881, -0.44305179 0.039873868 -0.010131106, -0.44315884 0.039821476 -0.010320589, -0.44330093 0.039751828 -0.010479078, -0.44347116 0.039668411 -0.010598287, -0.44366106 0.039575458 -0.010672197, -0.44237846 0.03844516 -0.010549292, -0.44203469 0.038166448 -0.010581508, -0.44226989 0.038589999 -0.010407016, -0.44163162 0.038232729 -0.010439292, -0.4419162 0.038408101 -0.010373905, -0.4413721 0.038084522 -0.010528907, -0.44165465 0.038139179 -0.010516182, -0.4413721 0.037911594 -0.010621205, -0.44196051 0.038317665 -0.010469303, -0.44250378 0.038277984 -0.010646448, -0.4421173 0.037998036 -0.010657385, -0.442177 0.037876382 -0.010686979, -0.44259545 0.038155869 -0.010683998, -0.44169161 0.037988231 -0.010605499, -0.44173199 0.037824258 -0.01066573, -0.44137213 0.037724018 -0.010678038, -0.44176096 0.037706703 -0.010689154, -0.44253033 0.039070413 -0.010165915, -0.44260317 0.039003611 -0.010317519, -0.44274482 0.038874283 -0.010502949, -0.44220835 0.038671985 -0.010287657, -0.44291776 0.038716659 -0.010630921, -0.44304663 0.038599461 -0.010680214, -0.41100022 0.037724242 -0.010678187, -0.4110001 0.037911728 -0.010621145, -0.4110001 0.038084686 -0.010528818, -0.41248015 0.036394536 -0.13388352, -0.41248026 0.036272183 -0.13386036, -0.41249231 0.036064148 -0.13378207, -0.41250256 0.035878167 -0.1336592, -0.47105512 0.095030487 -0.11022256, -0.47123221 0.095050648 -0.11012696, -0.47142893 0.095059261 -0.10999225, -0.47154903 0.095052212 -0.10988544, -0.47164246 0.095034003 -0.10977592, -0.47170803 0.09500517 -0.10966645, -0.47226831 0.095274389 -0.10950898, -0.47464326 0.088883996 -0.095844314, -0.47207493 0.095204428 -0.10950707, -0.47451594 0.088650391 -0.095518872, -0.47189829 0.095100462 -0.109524, -0.47444668 0.088545978 -0.095418975, -0.47439381 0.088475868 -0.095375195, -0.47435418 0.088428333 -0.095359728, -0.47432449 0.088395506 -0.095357791, -0.47430161 0.088371858 -0.095361754, -0.47210076 0.095309287 -0.1096666, -0.47190019 0.095444635 -0.10997783, -0.4720411 0.095530853 -0.11004822, -0.47225374 0.09536837 -0.1096945, -0.4719573 0.095228374 -0.10965239, -0.47176918 0.095334634 -0.10992657, -0.47182554 0.095126837 -0.10965203, -0.47165123 0.095203161 -0.10989521, -0.47090948 0.095227554 -0.11031847, -0.4711428 0.095791891 -0.11063264, -0.47162408 0.095690668 -0.11040233, -0.47105357 0.095634773 -0.11048533, -0.47150669 0.09556812 -0.11028729, -0.47097453 0.095443189 -0.11037873, -0.47188264 0.095604554 -0.1102102, -0.47139975 0.095416933 -0.11020146, -0.47175056 0.095503181 -0.11012004, -0.47130689 0.095242321 -0.11014675, -0.47162873 0.095376357 -0.11005245, -0.47152039 0.095227212 -0.11000918, -0.42499998 0.011650309 -0.010405913, -0.41100004 0.011650413 -0.010405853, -0.42499995 0.011801898 -0.010530248, -0.41099992 0.011801913 -0.010530338, -0.42499998 0.011974797 -0.010622635, -0.41099992 0.011974841 -0.010622844, -0.42499998 0.012162372 -0.010679558, -0.41099992 0.012162343 -0.010679558, -0.42499998 0.010236099 -0.0089917034, -0.41099992 0.01023607 -0.0089918822, -0.42602506 0.0095290095 -0.009921506, -0.42609906 0.0095290393 -0.010132745, -0.42621818 0.0095289946 -0.010322407, -0.42637649 0.0095289946 -0.010480776, -0.42656615 0.0095289946 -0.010599807, -0.42677751 0.0095289946 -0.010673806, -0.42499995 0.0099623203 -0.0084796995, -0.41099992 0.0099624097 -0.0084796995, -0.42499998 0.010019228 -0.0086674541, -0.41099992 0.010019258 -0.0086673647, -0.42499986 0.010111555 -0.0088403076, -0.41099992 0.010111645 -0.0088403076, -0.4251968 0.011951447 -0.010620937, -0.42543891 0.012036696 -0.01067017, -0.42538121 0.011886403 -0.01061593, -0.4254626 0.011535689 -0.010436371, -0.42560819 0.011370659 -0.010397062, -0.42554715 0.011304542 -0.010290727, -0.42532757 0.011746809 -0.010535344, -0.4255996 0.011748657 -0.01060544, -0.42551497 0.011617064 -0.010514662, -0.42506674 0.011645511 -0.010404333, -0.42548016 0.012144133 -0.01069127, -0.42524746 0.012214676 -0.010691747, -0.42522636 0.012105048 -0.010671869, -0.42567602 0.011443779 -0.010486349, -0.42569163 0.011891708 -0.010666594, -0.4257876 0.011564553 -0.010591015, -0.42570707 0.011028916 -0.010198817, -0.42577851 0.01107955 -0.010326698, -0.42587224 0.010566399 -0.010044649, -0.42575768 0.011994407 -0.010690317, -0.42586222 0.011138633 -0.010435596, -0.42591083 0.011697993 -0.010661587, -0.42599964 0.01179406 -0.010689065, -0.42600581 0.011240289 -0.010564819, -0.4259432 0.010594547 -0.01020582, -0.42616931 0.011355862 -0.010652706, -0.42603675 0.01063174 -0.010347351, -0.42628804 0.0114398 -0.01068674, -0.42621258 0.010701448 -0.010519221, -0.42642346 0.010784924 -0.010637388, -0.42657927 0.010846779 -0.010683015, -0.42515177 0.011717379 -0.010479257, -0.42513508 0.011630893 -0.010399446, -0.42516914 0.011808097 -0.010544851, -0.42529395 0.01165919 -0.010465518, -0.42526212 0.01157622 -0.010381088, -0.425414 0.011459947 -0.010342553, -0.42562345 0.0099302381 -0.0089615434, -0.42562345 0.010081753 -0.0091459602, -0.42578176 0.0099698603 -0.0092580169, -0.4254339 0.01002939 -0.0088952333, -0.42562345 0.0098176301 -0.0087509006, -0.42543387 0.00992769 -0.0087051839, -0.42597485 0.0091997981 -0.0086314529, -0.42590094 0.0094070584 -0.0085902065, -0.42590094 0.0094961971 -0.0088839978, -0.42578179 0.0095930547 -0.0085532516, -0.42578176 0.0096713305 -0.0088115782, -0.42578179 0.0097986013 -0.0090494901, -0.42590094 0.009835735 -0.0093921274, -0.42597491 0.0093009323 -0.0089650005, -0.42590094 0.0096408874 -0.0091547817, -0.42597485 0.0096863806 -0.0095414966, -0.42597488 0.0094651878 -0.0092721432, -0.42522246 0.0099376887 -0.0084847063, -0.4254339 0.0098652691 -0.0084991306, -0.42522246 0.0099961162 -0.0086768717, -0.42562345 0.00974828 -0.008522436, -0.42522246 0.010090739 -0.0088542551, -0.42522255 0.010218382 -0.0090094358, -0.42543387 0.010165989 -0.0090618581, -0.4752914 0.12573968 -0.17066602, -0.47525081 0.12573966 -0.1706685, -0.41246578 0.026404008 -0.11059891, -0.41245428 0.026361302 -0.11048578, -0.41244894 0.026263848 -0.11031519, -0.41246092 0.026118279 -0.11015181, -0.41248515 -0.026031509 -0.08941485, -0.41249177 -0.026178375 -0.08930172, -0.46191126 0.075823963 -0.090099618, -0.46192095 0.07573165 -0.089899346, -0.46196577 0.075612307 -0.089718655, -0.46263155 0.07628642 -0.089368805, -0.46310124 0.077032328 -0.089336023, -0.46305186 0.076935351 -0.089232281, -0.46261111 0.076391906 -0.089492157, -0.46261224 0.076484218 -0.089625701, -0.46263427 0.076562226 -0.089766726, -0.47285879 0.086700201 -0.075316533, -0.47288257 0.086770847 -0.075383261, -0.47291461 0.086835921 -0.075452045, -0.4729543 0.086895049 -0.075522169, -0.47296041 0.086896062 -0.075462565, -0.47296068 0.08689265 -0.075432733, -0.47295797 0.086884171 -0.075404152, -0.47295144 0.08686991 -0.075378284, -0.47294271 0.086852729 -0.075358972, -0.47293201 0.086832464 -0.07534419, -0.47292009 0.08681041 -0.075333163, -0.47290301 0.086779416 -0.075323567, -0.47288111 0.086739972 -0.075317517, -0.41299507 -0.035553053 -0.032123908, -0.41298184 -0.035545811 -0.032192573, -0.41299516 -0.035554141 -0.012636289, -0.41298196 -0.035546795 -0.012567744, -0.41299519 -0.03555128 -0.062393501, -0.41298184 -0.035544127 -0.062325045, -0.4125129 0.026517406 -0.12020503, -0.41251269 0.026475936 -0.12007113, -0.41670769 0.037340939 -0.12792213, -0.41668126 0.03734374 -0.12786289, -0.41664663 0.0373566 -0.12780936, -0.41660589 0.03737919 -0.12776424, -0.41656056 0.037410215 -0.12772916, -0.4188593 0.034543961 -0.12006377, -0.41987532 0.035681814 -0.11984415, -0.4198634 0.035691887 -0.1198694, -0.41883439 0.034585148 -0.12011151, -0.41983452 0.035716012 -0.11991389, -0.41880029 0.034631416 -0.12014826, -0.41979972 0.035744384 -0.11994998, -0.41875878 0.034679934 -0.12017138, -0.41977051 0.035768196 -0.11997096, -0.41973859 0.035793841 -0.11998649, -0.41871241 0.034728318 -0.1201802, -0.41970438 0.035821199 -0.119996, -0.42034608 0.036454171 -0.11998494, -0.42031744 0.036471203 -0.1200058, -0.42028672 0.036490232 -0.12002222, -0.42025369 0.03651157 -0.12003429, -0.42079169 0.0371162 -0.12013273, -0.4207634 0.037127003 -0.12015219, -0.42073348 0.037140027 -0.1201684, -0.42070153 0.037155375 -0.12018104, -0.42121488 0.037735879 -0.12032564, -0.42122966 0.037737623 -0.12030779, -0.42118296 0.037735656 -0.12035747, -0.42114824 0.037739128 -0.12038462, -0.42112046 0.037744224 -0.12040199, -0.42109114 0.037751511 -0.1204166, -0.42105982 0.037761182 -0.12042861, -0.42161068 0.038680404 -0.12096255, -0.42159519 0.038673311 -0.12097509, -0.42156261 0.038662165 -0.12099726, -0.42152795 0.038654819 -0.12101577, -0.42150053 0.03865163 -0.12102778, -0.42147169 0.038650587 -0.12103768, -0.42144105 0.038651735 -0.1210459, -0.42168221 0.039095238 -0.12142216, -0.4216494 0.039079115 -0.12143825, -0.42161474 0.039066702 -0.12145169, -0.42158753 0.039060026 -0.12145959, -0.42155868 0.039055243 -0.121466, -0.42152831 0.039052829 -0.12147088, -0.42162594 0.039717138 -0.12242596, -0.42161044 0.039703161 -0.12242888, -0.42157775 0.039678961 -0.12243228, -0.42154309 0.039659292 -0.12243356, -0.42151579 0.039647281 -0.12243293, -0.42148679 0.03963773 -0.12243114, -0.42145619 0.039630711 -0.12242769, -0.42144391 0.039934218 -0.12307365, -0.42142865 0.039918199 -0.12307246, -0.42139634 0.039890394 -0.12306808, -0.42136154 0.039867729 -0.1230617, -0.421334 0.03985405 -0.12305547, -0.42130503 0.039843187 -0.12304811, -0.42127404 0.0398352 -0.12303944, -0.42116675 0.040044457 -0.12374277, -0.42115209 0.040026888 -0.12373729, -0.4211202 0.039996386 -0.1237248, -0.42108557 0.039971799 -0.12371035, -0.42105779 0.039957285 -0.12369843, -0.42102823 0.039946139 -0.12368535, -0.42099673 0.03993839 -0.12367092, -0.420809 0.040048525 -0.12440737, -0.42079505 0.040029719 -0.12439783, -0.42076394 0.039997354 -0.12437688, -0.42072925 0.039972022 -0.12435447, -0.420701 0.039957613 -0.12433656, -0.42067096 0.039947286 -0.12431784, -0.42063877 0.039941072 -0.12429832, -0.42004985 0.039781004 -0.12530608, -0.42002088 0.039768532 -0.12527941, -0.41998968 0.039761335 -0.12525235, -0.41995603 0.039759964 -0.1252255, -0.41907153 0.03928563 -0.12649594, -0.41904467 0.039253876 -0.12644528, -0.41901013 0.039233714 -0.12639423, -0.41897985 0.03922683 -0.12635694, -0.41894624 0.039227039 -0.12632091, -0.41890988 0.039234802 -0.12628718, -0.41810566 0.038604453 -0.12730835, -0.41809863 0.038585916 -0.12727736, -0.41807529 0.038558543 -0.12721287, -0.41804096 0.03854546 -0.12714912, -0.4180091 0.038545594 -0.12710379, -0.41797307 0.038554281 -0.12706228, -0.41793367 0.038571581 -0.12702583, -0.41736874 0.037978023 -0.12776433, -0.41736439 0.037961394 -0.12772857, -0.41734424 0.037939101 -0.1276543, -0.41731033 0.037933096 -0.12758167, -0.41727707 0.037939712 -0.1275316, -0.41723862 0.037955493 -0.12748756, -0.41719636 0.037980303 -0.12745117, -0.41297036 0.037123352 -0.12532218, -0.41297033 0.036772132 -0.12556468, -0.4129346 0.036745772 -0.12551422, -0.41293469 0.037359536 -0.12497042, -0.41288719 0.037054092 -0.12524413, -0.41288719 0.037320375 -0.12494357, -0.41293472 0.037551239 -0.12338991, -0.41288719 0.037602976 -0.12379669, -0.41288728 0.037506863 -0.12340675, -0.41288719 0.037320286 -0.12305133, -0.41283032 0.037473366 -0.1234196, -0.41283035 0.037290916 -0.12307172, -0.41299251 0.035949588 -0.1221642, -0.41293457 0.037085623 -0.12527974, -0.4127 0.036332622 -0.12555106, -0.41276687 0.035949767 -0.12560521, -0.41270012 0.035949767 -0.12559746, -0.41288733 0.037507057 -0.12458809, -0.41283032 0.037290916 -0.12492315, -0.41283029 0.037030265 -0.12277763, -0.41276702 0.037272662 -0.12308426, -0.41276687 0.036334485 -0.12555821, -0.41276687 0.037015647 -0.12279417, -0.41283032 0.0374735 -0.12457545, -0.41283029 0.036339775 -0.12557979, -0.41283029 0.035949782 -0.12562715, -0.41283032 0.037567481 -0.12419386, -0.41276702 0.037452757 -0.12456743, -0.4127669 0.037545547 -0.12419124, -0.41276702 0.036696732 -0.12257405, -0.41270015 0.037010625 -0.12279974, -0.41270012 0.036693156 -0.12258072, -0.4127669 0.037545443 -0.1238036, -0.41270015 0.037538111 -0.12419029, -0.41276687 0.036696821 -0.12542073, -0.41270012 0.03669332 -0.12541427, -0.41270015 0.037538022 -0.12380449, -0.41299254 0.037769496 -0.12377651, -0.41297051 0.037706628 -0.12421079, -0.41297051 0.037706628 -0.12378405, -0.41299269 0.037769616 -0.12421833, -0.41299254 0.037165493 -0.12536974, -0.41297051 0.037604466 -0.12336992, -0.41293469 0.037650138 -0.12379096, -0.41299254 0.036801726 -0.12562077, -0.41288719 0.036348313 -0.12561451, -0.41288719 0.035949767 -0.12566279, -0.41297051 0.037406236 -0.12500285, -0.41283035 0.036707059 -0.12544055, -0.41293469 0.037551343 -0.12460481, -0.41293472 0.037359357 -0.12302433, -0.41288731 0.037054047 -0.12275086, -0.4127669 0.037015736 -0.12520061, -0.41270012 0.037010759 -0.12519498, -0.41288728 0.03760308 -0.12419803, -0.41293457 0.036359638 -0.12566073, -0.41283038 0.036707059 -0.12255429, -0.41293466 0.035949722 -0.12571044, -0.41283032 0.037567481 -0.12380095, -0.41276687 0.036334366 -0.12243672, -0.41270012 0.036332548 -0.12244399, -0.41270009 0.035949677 -0.12239753, -0.41276687 0.035949588 -0.12238996, -0.4127669 0.037452638 -0.12342735, -0.41270015 0.037445635 -0.12342997, -0.41288719 0.036723688 -0.12547229, -0.41299254 0.037663713 -0.1233473, -0.41299251 0.03745845 -0.1250387, -0.41297051 0.037406147 -0.12299202, -0.41283032 0.037030444 -0.12521715, -0.4127669 0.037272662 -0.12491061, -0.41270015 0.037266538 -0.12490638, -0.41297051 0.03760457 -0.12462501, -0.41293469 0.037085548 -0.12271522, -0.41297036 0.036373258 -0.12571584, -0.41297048 0.035949722 -0.12576734, -0.41293466 0.037650168 -0.12420391, -0.41288725 0.036723644 -0.12252279, -0.41283038 0.036339745 -0.12241505, -0.41283029 0.035949662 -0.12236778, -0.41299269 0.037458435 -0.12295602, -0.41270012 0.037266389 -0.12308867, -0.41297051 0.037123248 -0.12267275, -0.41270015 0.037445724 -0.12456487, -0.41299254 0.037663832 -0.12464748, -0.41293466 0.036745623 -0.12248076, -0.41299254 0.036388472 -0.12577735, -0.41299251 0.035949767 -0.12583064, -0.41288719 0.036348224 -0.12238042, -0.41288719 0.035949603 -0.12233208, -0.41299266 0.037165314 -0.12262525, -0.41297051 0.036772132 -0.1224304, -0.41293469 0.036359593 -0.12233432, -0.41293457 0.035949633 -0.12228449, -0.41299251 0.036801547 -0.12237437, -0.41297051 0.036373258 -0.12227912, -0.41297051 0.035949677 -0.12222786, -0.41299254 0.036388338 -0.12221758, -0.4110001 0.035949603 -0.12239747, -0.41100007 0.036332548 -0.12244399, -0.41100007 0.036693156 -0.12258072, -0.4110001 0.03701064 -0.12279974, -0.4110001 0.037266403 -0.12308867, -0.4110001 0.03744565 -0.12343006, -0.4110001 0.037538037 -0.12380449, -0.41100013 0.037538126 -0.1241902, -0.4110001 0.037445724 -0.12456487, -0.4110001 0.037266552 -0.12490638, -0.4110001 0.037010774 -0.1251951, -0.4110001 0.03669332 -0.12541427, -0.4110001 0.036332682 -0.12555106, -0.41100007 0.035949722 -0.12559746, -0.41100004 0.033949763 -0.12559761, -0.41270009 0.033949748 -0.12559761, -0.41100007 0.033566788 -0.12555109, -0.41270009 0.033566788 -0.12555109, -0.41100004 0.03320618 -0.12541457, -0.41269997 0.033206135 -0.12541442, -0.41100004 0.032888815 -0.12519534, -0.41269997 0.03288877 -0.12519534, -0.41100016 0.032633036 -0.12490661, -0.41270009 0.032632902 -0.12490661, -0.41100004 0.032453731 -0.12456511, -0.41269997 0.032453671 -0.12456508, -0.41100004 0.032361418 -0.12419064, -0.41269997 0.032361344 -0.12419043, -0.41100004 0.032361269 -0.12380476, -0.41270009 0.032361314 -0.12380476, -0.41100007 0.032453567 -0.12343021, -0.41270009 0.032453611 -0.12343021, -0.41100007 0.032632858 -0.1230887, -0.41270009 0.032632753 -0.1230887, -0.41100007 0.032888636 -0.12279995, -0.41270009 0.032888666 -0.12279995, -0.41100004 0.033206031 -0.12258084, -0.41269997 0.033206016 -0.12258084, -0.41100007 0.033566698 -0.12244414, -0.41270009 0.033566743 -0.12244408, -0.41100007 0.033949658 -0.12239753, -0.41270009 0.033949643 -0.12239753, -0.41299251 0.033949673 -0.12216435, -0.41297045 0.033949628 -0.12222786, -0.41293469 0.033949643 -0.12228461, -0.41288716 0.033949569 -0.12233208, -0.41283026 0.033949614 -0.12236784, -0.41276684 0.033949643 -0.12239011, -0.41299251 0.033949748 -0.12583084, -0.41297048 0.033949688 -0.12576734, -0.41293466 0.033949688 -0.12571044, -0.41288713 0.033949748 -0.125663, -0.41283026 0.033949733 -0.12562723, -0.41276684 0.033949748 -0.12560521, -0.41297033 0.032192722 -0.12421094, -0.41297048 0.032192752 -0.12378441, -0.41293457 0.032249138 -0.1237912, -0.41297048 0.032776013 -0.12267311, -0.41297045 0.033127174 -0.12243055, -0.41293469 0.033153623 -0.12248091, -0.41293454 0.032813683 -0.12271546, -0.41293466 0.032348081 -0.12460501, -0.41288716 0.032296315 -0.12419848, -0.41288713 0.032392502 -0.12458812, -0.41293454 0.032249153 -0.12420411, -0.41288716 0.032579079 -0.12494381, -0.41283026 0.032425895 -0.12457548, -0.41293454 0.032539845 -0.12302478, -0.41288713 0.032845199 -0.12275101, -0.41288713 0.032578975 -0.12305148, -0.41276687 0.03356488 -0.12243684, -0.41283026 0.032608435 -0.1249233, -0.41288725 0.032392457 -0.12340699, -0.41283026 0.032608315 -0.12307198, -0.41283026 0.032425806 -0.12341975, -0.41283026 0.032869041 -0.12521751, -0.41276684 0.032626763 -0.12491091, -0.41276687 0.032883748 -0.12520085, -0.41283026 0.03355962 -0.1224155, -0.41276684 0.033202648 -0.125421, -0.41283026 0.03233175 -0.12380119, -0.41276684 0.032446608 -0.1234277, -0.41276687 0.032353833 -0.1238039, -0.41276684 0.032353908 -0.12419142, -0.41276684 0.033202574 -0.12257428, -0.41299251 0.032129839 -0.12421863, -0.41299251 0.032129735 -0.12377675, -0.41299251 0.032733962 -0.12262546, -0.41288716 0.033551052 -0.12238069, -0.41299263 0.033097699 -0.12237437, -0.41297033 0.032294869 -0.12462531, -0.41297033 0.03249307 -0.12299232, -0.41293454 0.032539979 -0.12497066, -0.41283026 0.033192202 -0.12255459, -0.41293457 0.032347932 -0.1233903, -0.41288713 0.032845333 -0.12524436, -0.41276684 0.032883599 -0.12279437, -0.41288716 0.032296315 -0.12379698, -0.41283026 0.033192381 -0.12544058, -0.41293469 0.033539653 -0.12233441, -0.41276687 0.033565059 -0.12555836, -0.41283026 0.032331869 -0.12419413, -0.41288713 0.033175588 -0.12252314, -0.41276684 0.032446697 -0.12456773, -0.41299251 0.032235637 -0.12464793, -0.41283026 0.032868907 -0.12277777, -0.41297033 0.032493129 -0.125003, -0.41299251 0.032440916 -0.12295638, -0.41276684 0.032626644 -0.12308462, -0.41297045 0.032294765 -0.12337013, -0.41293454 0.032813817 -0.12527977, -0.41297048 0.033526108 -0.12227915, -0.41288716 0.033175752 -0.12547229, -0.41283026 0.03355971 -0.12557994, -0.41299251 0.032440975 -0.12503906, -0.41297033 0.032776132 -0.12532233, -0.41299251 0.032235458 -0.1233476, -0.41293457 0.033153698 -0.12551425, -0.41299251 0.033510804 -0.12221773, -0.41288716 0.033551186 -0.12561451, -0.41299251 0.032734036 -0.12536977, -0.41297033 0.033127293 -0.12556489, -0.41293469 0.033539787 -0.12566091, -0.41299251 0.033097804 -0.12562083, -0.41297048 0.033526197 -0.12571608, -0.41299251 0.033511072 -0.12577756, -0.41680583 -0.023674697 -0.043774888, -0.41677907 -0.023105413 -0.044038221, -0.41678602 -0.023664922 -0.043838218, -0.41704455 -0.022738561 -0.050413117, -0.41698807 -0.022714347 -0.050399974, -0.41714683 -0.022772476 -0.050473914, -0.4172217 -0.022783473 -0.050571188, -0.41738492 -0.02209267 -0.050171867, -0.41739896 -0.021946177 -0.050087079, -0.417483 -0.02211082 -0.050230965, -0.41755828 -0.022103205 -0.050318375, -0.41772991 -0.021624535 -0.049936518, -0.41774362 -0.021302238 -0.049609408, -0.41780502 -0.021603793 -0.050013766, -0.41680589 -0.023674339 -0.050741419, -0.41678599 -0.023664579 -0.050678, -0.41796622 -0.021158844 -0.049525008, -0.41799113 -0.020839587 -0.049057826, -0.4167538 -0.023648858 -0.050621137, -0.41671124 -0.023627952 -0.050573602, -0.4166601 -0.023602873 -0.050537959, -0.41660312 -0.023575008 -0.050515786, -0.41804129 -0.021125868 -0.049589261, -0.41654328 -0.023545653 -0.050508127, -0.4181723 -0.020752236 -0.048992172, -0.4181622 -0.020519748 -0.04844366, -0.41824725 -0.020709053 -0.049040541, -0.41832659 -0.020447522 -0.048351273, -0.4182623 -0.020332724 -0.047746852, -0.41840142 -0.020396873 -0.048381612, -0.41840962 -0.02028352 -0.047633931, -0.41827968 -0.020300388 -0.047087148, -0.41848454 -0.020228744 -0.047644123, -0.41841003 -0.02028273 -0.046888933, -0.41823432 -0.020385221 -0.046501204, -0.41848487 -0.020228073 -0.04687877, -0.41832775 -0.020445392 -0.046171173, -0.41813546 -0.020569906 -0.045951799, -0.41840261 -0.020394608 -0.046141133, -0.41806167 -0.020805508 -0.045502827, -0.41799214 -0.020837769 -0.045461521, -0.41815332 -0.020789847 -0.045464352, -0.41822812 -0.020747662 -0.045414165, -0.41786769 -0.021174699 -0.045028254, -0.41781631 -0.021166682 -0.045044169, -0.41761976 -0.021533892 -0.044705704, -0.41796118 -0.021168962 -0.044980273, -0.41803619 -0.021136343 -0.044915751, -0.41767243 -0.021546528 -0.044689253, -0.41776767 -0.021550581 -0.044635281, -0.41784269 -0.021527871 -0.04456, -0.41739908 -0.022065774 -0.044358179, -0.4173449 -0.02204752 -0.044374064, -0.41704088 -0.02261582 -0.044144109, -0.41749734 -0.022083193 -0.04429926, -0.41757232 -0.022074893 -0.044212356, -0.41707519 -0.022680894 -0.044118598, -0.41717702 -0.022713333 -0.044057772, -0.41725197 -0.022722751 -0.043961123, -0.41660312 -0.023575336 -0.044000611, -0.4165433 -0.023545995 -0.044008091, -0.41666013 -0.023603231 -0.043978617, -0.41671112 -0.023628369 -0.043942764, -0.41675395 -0.023649171 -0.04389517, -0.41299984 -0.022767857 -0.050413713, -0.41299966 -0.023545668 -0.050508216, -0.41299969 -0.022035375 -0.050135806, -0.41299966 -0.021390617 -0.049690709, -0.41299984 -0.020870969 -0.049104199, -0.41299966 -0.020506948 -0.04841055, -0.41299969 -0.020319492 -0.047649607, -0.41299969 -0.020319581 -0.046866283, -0.41299969 -0.020507127 -0.046105579, -0.41299969 -0.020871371 -0.045411661, -0.4129996 -0.021390885 -0.04482542, -0.41299966 -0.022035703 -0.044380352, -0.41299966 -0.022768229 -0.044102505, -0.41299966 -0.0235461 -0.044008091, -0.4129996 -0.030780718 -0.044008538, -0.4129996 -0.030780345 -0.050508603, -0.41299978 -0.022662863 -0.045575723, -0.41299969 -0.023091331 -0.045413479, -0.41299969 -0.023545995 -0.045358136, -0.41299966 -0.026545793 -0.04915832, -0.41299966 -0.027000532 -0.049103126, -0.41299966 -0.027428761 -0.048940673, -0.41299966 -0.02780579 -0.048680529, -0.4129996 -0.028109446 -0.048337653, -0.41299963 -0.028322354 -0.047932103, -0.41299969 -0.021982104 -0.048337445, -0.41299969 -0.022285894 -0.048680201, -0.41299966 -0.022662804 -0.048940524, -0.41299966 -0.028432027 -0.047487423, -0.41299966 -0.021769226 -0.047931835, -0.4129996 -0.030987412 -0.0505227, -0.41299966 -0.023091063 -0.049103007, -0.41299978 -0.026545957 -0.045358375, -0.41299966 -0.021659672 -0.047487184, -0.41299966 -0.023545802 -0.04915823, -0.41299966 -0.021659672 -0.047028974, -0.41299966 -0.021769345 -0.046584293, -0.41299966 -0.028432027 -0.04702954, -0.41299966 -0.028322503 -0.046584681, -0.41299963 -0.02810955 -0.046179101, -0.41299981 -0.021982193 -0.046178684, -0.41299963 -0.027805865 -0.045836166, -0.41299954 -0.02742891 -0.045576081, -0.41299963 -0.027000681 -0.045413569, -0.41299963 -0.031025708 -0.043988571, -0.41299978 -0.022285894 -0.045835957, -0.41299963 -0.031181782 -0.050566003, -0.41299963 -0.031304687 -0.050616696, -0.4129996 -0.031244621 -0.04392837, -0.4129996 -0.031392798 -0.050676569, -0.4129996 -0.031329393 -0.043886825, -0.4129996 -0.0313932 -0.043840602, -0.41297013 -0.022372156 -0.048582926, -0.41293421 -0.022749722 -0.048774943, -0.41293433 -0.022409901 -0.048540309, -0.41293427 -0.021944195 -0.046650633, -0.4128868 -0.021892563 -0.047057226, -0.4128868 -0.021988645 -0.046667501, -0.41293436 -0.022136107 -0.048231229, -0.41288683 -0.022441387 -0.048504695, -0.41288695 -0.022175208 -0.04631193, -0.41282991 -0.022022098 -0.046680287, -0.41283002 -0.022204608 -0.046332344, -0.4128868 -0.022175148 -0.048204049, -0.41299215 -0.023545966 -0.045424923, -0.4128868 -0.021988556 -0.047848657, -0.41282994 -0.022204563 -0.048183903, -0.41282991 -0.022021994 -0.047835991, -0.41276649 -0.023161083 -0.04881905, -0.41276652 -0.023545817 -0.048865542, -0.41269976 -0.023545787 -0.04885824, -0.41282991 -0.022465214 -0.046038255, -0.41276649 -0.022222906 -0.046344921, -0.41269973 -0.023162872 -0.048811629, -0.41276667 -0.022479892 -0.046054915, -0.41282991 -0.023155794 -0.048840508, -0.41282991 -0.023545861 -0.048887923, -0.41282994 -0.021928042 -0.047454461, -0.41276652 -0.022042707 -0.047828063, -0.41276664 -0.022798792 -0.045834735, -0.41269973 -0.022484884 -0.046060428, -0.41276649 -0.021950036 -0.047451809, -0.41269967 -0.022802383 -0.0458415, -0.41276652 -0.021950081 -0.047064289, -0.41269964 -0.021957561 -0.047451004, -0.41269964 -0.021957561 -0.047065124, -0.41299209 -0.021725982 -0.04703705, -0.41299215 -0.021725923 -0.047479078, -0.41297013 -0.021788925 -0.047471359, -0.41276652 -0.022798672 -0.048681483, -0.41269964 -0.022802249 -0.048674926, -0.41297013 -0.02178891 -0.047044799, -0.41299221 -0.02233012 -0.048630312, -0.4129701 -0.022723302 -0.048825219, -0.41297013 -0.021891013 -0.046630487, -0.41293436 -0.021845415 -0.047051713, -0.41299215 -0.022693783 -0.048881277, -0.4128868 -0.023147181 -0.048875198, -0.4128868 -0.023545817 -0.048923716, -0.41297013 -0.022089332 -0.048263535, -0.41283002 -0.022788376 -0.048701093, -0.41293433 -0.022136137 -0.046285078, -0.4129343 -0.021944121 -0.047865614, -0.41288692 -0.022441402 -0.046011612, -0.41276667 -0.022479713 -0.048461363, -0.41269976 -0.022484794 -0.048455581, -0.4128868 -0.021892563 -0.047458783, -0.41299215 -0.023545787 -0.049091473, -0.41283002 -0.02278851 -0.045815185, -0.41293418 -0.023135796 -0.048921213, -0.41293427 -0.023545772 -0.048971131, -0.41282994 -0.021928042 -0.047061637, -0.41276649 -0.023161203 -0.045697376, -0.41269964 -0.023163006 -0.045704558, -0.41269964 -0.023545906 -0.045658186, -0.41288677 -0.022771746 -0.048732862, -0.41276652 -0.023545936 -0.045650765, -0.41276655 -0.022042781 -0.046688065, -0.41269979 -0.022049829 -0.046690866, -0.41299233 -0.021831766 -0.046608046, -0.4129701 -0.022089332 -0.046252772, -0.41299218 -0.022037029 -0.048299447, -0.41282991 -0.02246514 -0.048478052, -0.41276652 -0.022222802 -0.048171267, -0.41269964 -0.022229031 -0.048167095, -0.41297013 -0.021890983 -0.047885761, -0.41293436 -0.022409961 -0.045975968, -0.41297001 -0.023122266 -0.048976615, -0.41297001 -0.023545787 -0.049028024, -0.41293433 -0.021845385 -0.047464594, -0.4128868 -0.02277191 -0.045783505, -0.41282991 -0.023155913 -0.045675799, -0.41282991 -0.023545891 -0.045628384, -0.41299233 -0.022037104 -0.046216711, -0.41297016 -0.02237232 -0.04593344, -0.41269961 -0.02222912 -0.046349213, -0.4129923 -0.021831587 -0.047908232, -0.41269967 -0.02204977 -0.047825441, -0.41293433 -0.022749871 -0.045741394, -0.41288689 -0.023147315 -0.04564105, -0.41288677 -0.023545846 -0.04559274, -0.41299215 -0.023107037 -0.049038097, -0.41299218 -0.022330254 -0.045885876, -0.4129701 -0.022723407 -0.045691118, -0.4129343 -0.023135975 -0.045595005, -0.41293433 -0.023545921 -0.045545205, -0.41299215 -0.022693917 -0.04563491, -0.4129701 -0.023122355 -0.045539692, -0.41296998 -0.023545966 -0.045488432, -0.41299218 -0.023107186 -0.04547821, -0.41099972 -0.023545951 -0.045658186, -0.41099972 -0.023163036 -0.045704678, -0.41099972 -0.022802368 -0.045841441, -0.41099972 -0.022484899 -0.046060428, -0.41099975 -0.02222915 -0.046349391, -0.41099975 -0.022049859 -0.046690866, -0.41099975 -0.021957517 -0.047065243, -0.41099975 -0.021957576 -0.047451004, -0.41099975 -0.022049785 -0.047825411, -0.41099975 -0.022229075 -0.048167095, -0.41099972 -0.022484794 -0.04845573, -0.41099969 -0.022802249 -0.048674718, -0.41099969 -0.023162857 -0.0488116, -0.41099972 -0.023545817 -0.048858061, -0.41269973 -0.026545778 -0.04885821, -0.41099969 -0.026545689 -0.048858389, -0.41099969 -0.026928678 -0.048811898, -0.41269961 -0.026928708 -0.048811898, -0.41099969 -0.027289256 -0.048675045, -0.41269973 -0.027289286 -0.048675045, -0.41099969 -0.027606741 -0.048456058, -0.41269961 -0.02760677 -0.048455909, -0.41099969 -0.027862534 -0.048167363, -0.41269955 -0.027862594 -0.048167363, -0.41099969 -0.02804178 -0.047825798, -0.41269961 -0.028041869 -0.047825798, -0.41099969 -0.028134197 -0.047451362, -0.41269958 -0.028134257 -0.047451362, -0.41099969 -0.028134167 -0.047065571, -0.41269958 -0.028134257 -0.047065541, -0.41099969 -0.028041869 -0.046691135, -0.41269973 -0.028041929 -0.046691105, -0.41099966 -0.027862653 -0.046349451, -0.41269961 -0.027862713 -0.0463496, -0.41099969 -0.027606934 -0.046060666, -0.41269961 -0.027606919 -0.046060875, -0.41099969 -0.02728945 -0.045841679, -0.4126997 -0.02728948 -0.045841649, -0.41099969 -0.026928857 -0.045704886, -0.41269961 -0.026928857 -0.045704886, -0.41099969 -0.026545897 -0.045658335, -0.41269973 -0.026545897 -0.045658305, -0.41299215 -0.026545987 -0.045425102, -0.4129701 -0.026545852 -0.045488551, -0.41293421 -0.026545942 -0.045545414, -0.41288677 -0.026545867 -0.045592859, -0.41282991 -0.026545972 -0.045628592, -0.41276649 -0.026545867 -0.045650825, -0.41299215 -0.026545808 -0.049091622, -0.41296998 -0.026545808 -0.049028113, -0.41293418 -0.026545748 -0.04897134, -0.41288677 -0.026545823 -0.048923716, -0.41282991 -0.026545748 -0.048887923, -0.41276649 -0.026545778 -0.048865899, -0.41297007 -0.028302819 -0.047471747, -0.41293427 -0.028246313 -0.047051892, -0.41293427 -0.028246313 -0.047464833, -0.41293427 -0.028147414 -0.047865912, -0.41288677 -0.028199151 -0.047459111, -0.41296998 -0.027719572 -0.045933649, -0.41293421 -0.027342007 -0.045741722, -0.41293427 -0.027681798 -0.045976207, -0.41288677 -0.028103068 -0.047849014, -0.41293427 -0.027955607 -0.046285316, -0.41288677 -0.027650267 -0.046011791, -0.41288674 -0.027916461 -0.048204377, -0.41282991 -0.02806963 -0.047836259, -0.41282991 -0.027887031 -0.048184201, -0.41288677 -0.027916521 -0.046312377, -0.41288677 -0.028103143 -0.046667919, -0.41282985 -0.027887151 -0.046332702, -0.41276649 -0.0269306 -0.045697495, -0.41282979 -0.0276265 -0.048478231, -0.41276649 -0.027868718 -0.048171595, -0.41282988 -0.028069764 -0.046680495, -0.41282991 -0.02693592 -0.045675859, -0.41276649 -0.027611777 -0.048461542, -0.41276649 -0.027292833 -0.048681572, -0.41282988 -0.028163761 -0.047061905, -0.41276646 -0.028048962 -0.046688274, -0.41276649 -0.028141677 -0.047064707, -0.41276649 -0.028141573 -0.047452196, -0.41276661 -0.027292982 -0.045834973, -0.41299212 -0.028365731 -0.047479376, -0.41299212 -0.028365701 -0.047037318, -0.41297007 -0.028302819 -0.047044978, -0.41299215 -0.027761564 -0.045886025, -0.41296995 -0.027368456 -0.045691296, -0.41288677 -0.026944473 -0.045641229, -0.41299212 -0.027397871 -0.045635149, -0.41296992 -0.028200701 -0.047886059, -0.41293418 -0.027955562 -0.048231587, -0.41296998 -0.028002426 -0.046252951, -0.41282991 -0.027303353 -0.045815393, -0.4129343 -0.028147578 -0.046650991, -0.41288677 -0.027650237 -0.048505113, -0.41276649 -0.027611926 -0.046055183, -0.41288677 -0.028199151 -0.047057584, -0.41293427 -0.026955798 -0.045595244, -0.41282991 -0.027303174 -0.048701391, -0.41282988 -0.028163761 -0.04745467, -0.41276637 -0.026930541 -0.048819199, -0.41276649 -0.028048858 -0.047828332, -0.41288677 -0.027319923 -0.045783713, -0.41299215 -0.028259948 -0.0479085, -0.41296995 -0.028002352 -0.048263773, -0.41299209 -0.028054699 -0.04621695, -0.41282991 -0.027626634 -0.046038494, -0.4129701 -0.028200716 -0.046630844, -0.41276649 -0.027868852 -0.046345189, -0.41293418 -0.027681679 -0.048540547, -0.4129701 -0.026969418 -0.045539901, -0.41288677 -0.027319744 -0.048733041, -0.41282991 -0.026935831 -0.048840687, -0.41299215 -0.02805452 -0.048299775, -0.41296998 -0.027719423 -0.048583254, -0.41299215 -0.028260037 -0.046608284, -0.41293415 -0.027341828 -0.048775151, -0.41288677 -0.026944354 -0.048875347, -0.41299209 -0.026984751 -0.045478627, -0.41299215 -0.027761474 -0.04863067, -0.41296992 -0.027368352 -0.048825428, -0.41293418 -0.026955754 -0.04892157, -0.41299209 -0.027397767 -0.048881665, -0.41296998 -0.026969403 -0.048976764, -0.41299215 -0.026984528 -0.049038276, -0.41299352 -0.031453416 -0.04378365, -0.41298351 -0.031490207 -0.043746397, -0.41299725 -0.031430557 -0.050711498, -0.41299021 -0.031467929 -0.050748333, -0.46331146 0.15343903 -0.073804334, -0.4636611 0.1534169 -0.073869422, -0.46334112 0.1534169 -0.073747948, -0.46364602 0.15343896 -0.071050718, -0.4630594 0.15341684 -0.073553696, -0.46336743 0.15338115 -0.073697612, -0.46309707 0.15338111 -0.073511139, -0.46259138 0.15341678 -0.072319642, -0.46264789 0.15338102 -0.072655097, -0.46264789 0.15338102 -0.072326556, -0.46331149 0.15343891 -0.071177587, -0.46334109 0.15341678 -0.071233705, -0.46366104 0.15341677 -0.07111223, -0.46259138 0.15341678 -0.07266207, -0.46272644 0.15338102 -0.072007671, -0.46269503 0.15333351 -0.072332308, -0.46277091 0.15333362 -0.07202445, -0.46287921 0.15338114 -0.073265031, -0.46312854 0.15333362 -0.073475435, -0.46370009 0.15321341 -0.073711708, -0.46291819 0.15333353 -0.073238119, -0.46291825 0.15333351 -0.071743593, -0.46280429 0.15327668 -0.072036937, -0.46277091 0.15333362 -0.072957352, -0.4629477 0.15327674 -0.073217884, -0.46280429 0.15327668 -0.072944656, -0.4629477 0.1532767 -0.071763888, -0.46369469 0.15327677 -0.073733285, -0.46315232 0.15327662 -0.07153298, -0.46296591 0.15321323 -0.071776494, -0.46316692 0.15321323 -0.071549639, -0.46273056 0.15327676 -0.072645053, -0.46282503 0.15321328 -0.072936758, -0.46275255 0.15321329 -0.07264252, -0.46341655 0.15321335 -0.073604301, -0.46341652 0.15321317 -0.071377411, -0.46275243 0.15321322 -0.072339281, -0.46368608 0.15333362 -0.073768094, -0.46252847 0.15343897 -0.072312072, -0.46301734 0.15343907 -0.073600993, -0.46252847 0.15343897 -0.072669581, -0.46267328 0.15341678 -0.071987405, -0.4628323 0.15341683 -0.073297486, -0.46340623 0.15327679 -0.073624, -0.46287927 0.15338106 -0.071716532, -0.46316692 0.15321328 -0.073432192, -0.46272644 0.15338109 -0.07297419, -0.46312854 0.15333354 -0.071506247, -0.4636746 0.15338114 -0.073814258, -0.46269497 0.15333357 -0.072649434, -0.46340618 0.15327662 -0.071357802, -0.46338961 0.15333368 -0.07365562, -0.46273056 0.15327676 -0.07233654, -0.4637 0.15321329 -0.071269944, -0.46282503 0.15321328 -0.072044775, -0.46315226 0.15327676 -0.073448762, -0.46261409 0.15343894 -0.071964845, -0.46278021 0.15343907 -0.073333487, -0.46296591 0.15321337 -0.073205188, -0.46267328 0.15341678 -0.072994456, -0.46283236 0.15341672 -0.071684435, -0.46309707 0.153381 -0.071470633, -0.46338961 0.1533335 -0.071326151, -0.46369466 0.15327662 -0.071248367, -0.46278027 0.15343896 -0.071648255, -0.46305928 0.15341677 -0.071428254, -0.46261403 0.15343896 -0.073016748, -0.46336743 0.153381 -0.071284041, -0.46364602 0.15343907 -0.073931023, -0.46368608 0.15333351 -0.071213707, -0.46301731 0.15343896 -0.071380541, -0.4636746 0.15338102 -0.071167544, -0.48331168 0.1487 -0.143739, -0.48366112 0.14865108 -0.14378755, -0.48334107 0.14870533 -0.14367886, -0.48364598 0.14993128 -0.14127611, -0.48305935 0.14879224 -0.14350499, -0.48336759 0.1486959 -0.14361806, -0.48309711 0.1487793 -0.14345078, -0.48259136 0.14934394 -0.14240129, -0.48264787 0.14916196 -0.14268537, -0.48264778 0.14930895 -0.14239143, -0.48366106 0.1498839 -0.1413212, -0.48331159 0.1498746 -0.14138968, -0.48334104 0.14982966 -0.14142998, -0.48259139 0.14919086 -0.14270733, -0.48272645 0.14945157 -0.14210601, -0.48269501 0.14926387 -0.14237531, -0.48277101 0.14940156 -0.14209993, -0.48287919 0.14888932 -0.14323078, -0.48312858 0.14875273 -0.14339785, -0.48370004 0.14853945 -0.14355536, -0.48291838 0.14885893 -0.1431856, -0.48291823 0.14952703 -0.14184864, -0.48280424 0.149345 -0.14208587, -0.48277083 0.14898446 -0.14293428, -0.48294777 0.14881721 -0.14314206, -0.48280424 0.14893916 -0.14289768, -0.48294765 0.14946708 -0.14184149, -0.48369464 0.14858654 -0.14360319, -0.48315224 0.14957049 -0.14163481, -0.48296598 0.14940475 -0.14182435, -0.4831669 0.14950629 -0.14162137, -0.48273051 0.14907314 -0.14262961, -0.48282501 0.14888592 -0.14286228, -0.48275253 0.14901772 -0.1425987, -0.48341659 0.14858763 -0.14345931, -0.48341641 0.14958332 -0.14146732, -0.48275244 0.14915319 -0.14232786, -0.48368618 0.14862198 -0.14365946, -0.48252833 0.14936724 -0.14240445, -0.48301739 0.14879091 -0.1435573, -0.48252836 0.14920728 -0.14272426, -0.48267326 0.14949256 -0.14210398, -0.48283237 0.14890686 -0.14327572, -0.48340628 0.14863555 -0.1435052, -0.48287916 0.14958179 -0.14184575, -0.48316696 0.14866464 -0.14330532, -0.48272666 0.14901938 -0.14297079, -0.48312855 0.14963332 -0.14163633, -0.48367459 0.14864369 -0.14372201, -0.48269489 0.14912198 -0.14265893, -0.48340631 0.14964887 -0.14147802, -0.48338959 0.14867227 -0.14355905, -0.48273045 0.14921105 -0.1423537, -0.48370001 0.1496314 -0.14137127, -0.48282501 0.14928479 -0.14206453, -0.48315224 0.14871396 -0.14334841, -0.48261398 0.14952251 -0.14209382, -0.48278016 0.14891052 -0.14331789, -0.48296601 0.14876607 -0.14310236, -0.48267335 0.1490424 -0.1430047, -0.4828324 0.14962813 -0.1418329, -0.48309687 0.14969163 -0.14162596, -0.4833895 0.14971383 -0.14147536, -0.48369452 0.14969772 -0.14138038, -0.48278016 0.1496641 -0.14181073, -0.48305935 0.14974269 -0.14160378, -0.48261404 0.14905217 -0.14303465, -0.4833675 0.14977516 -0.14145885, -0.48364595 0.14864334 -0.14385237, -0.48368603 0.14976415 -0.14137466, -0.48301727 0.14978376 -0.14157124, -0.48367473 0.1498273 -0.14135458, -0.48361611 0.15107086 -0.14520092, -0.4832539 0.15113232 -0.14507784, -0.48325387 0.15240525 -0.14253174, -0.48361614 0.15246661 -0.1424088, -0.48361084 0.15253308 -0.14241798, -0.48238304 0.15173762 -0.14400895, -0.48234764 0.15196617 -0.1436791, -0.48234758 0.15178657 -0.14403827, -0.48292014 0.15237089 -0.14274205, -0.4832435 0.15247068 -0.14254232, -0.48322698 0.15253577 -0.14253946, -0.48238316 0.15191334 -0.14365752, -0.48324355 0.15118028 -0.14512385, -0.48361084 0.15111795 -0.1452484, -0.48244363 0.15161225 -0.14438675, -0.48230043 0.15182658 -0.14406441, -0.48289648 0.15243383 -0.14274357, -0.48263019 0.15229943 -0.14301239, -0.48286495 0.15249224 -0.14273305, -0.48239931 0.15164711 -0.14442311, -0.48259103 0.15148363 -0.14475022, -0.482346 0.15167019 -0.1444573, -0.48259115 0.15235391 -0.14300938, -0.48356214 0.15276663 -0.14231355, -0.48239914 0.15219045 -0.1433364, -0.48254424 0.1524004 -0.14299653, -0.48254424 0.15150121 -0.14479519, -0.48234609 0.15223148 -0.14333458, -0.48357731 0.15271929 -0.14235877, -0.48282725 0.15135852 -0.1450807, -0.48249212 0.15150495 -0.14483728, -0.48278514 0.15135701 -0.14513312, -0.48224393 0.15204616 -0.14370497, -0.48228681 0.15226141 -0.14332427, -0.48218104 0.15206946 -0.14370809, -0.48314896 0.15124483 -0.14535756, -0.48218104 0.15187187 -0.14410339, -0.48314893 0.1526964 -0.14245377, -0.4824051 0.15168209 -0.14397813, -0.48293492 0.15230685 -0.14272852, -0.48359093 0.15266258 -0.14239235, -0.48240513 0.1518555 -0.14363135, -0.48265958 0.15223947 -0.14300509, -0.48317832 0.15265158 -0.14249419, -0.48247701 0.15156707 -0.14435001, -0.48244363 0.15214047 -0.14333029, -0.48263025 0.15145323 -0.14470477, -0.4827852 0.1525842 -0.14267845, -0.48230043 0.15201117 -0.14369516, -0.48286495 0.15134555 -0.14502652, -0.48360226 0.15259945 -0.14241226, -0.48317832 0.15125002 -0.14529757, -0.48320487 0.15259703 -0.1425233, -0.4822439 0.15185539 -0.14408661, -0.4835622 0.15117481 -0.14549769, -0.48228672 0.15167986 -0.14448722, -0.48282728 0.1525432 -0.142711, -0.48249781 0.1515139 -0.14431463, -0.48267803 0.15217711 -0.14298804, -0.48249218 0.15243635 -0.14297412, -0.48247707 0.15208396 -0.14331622, -0.48265961 0.1514115 -0.14466117, -0.48289642 0.15131892 -0.14497359, -0.48320478 0.15124062 -0.1452366, -0.48357719 0.15118244 -0.1454329, -0.48267794 0.1513603 -0.1446216, -0.48292014 0.15127994 -0.14492433, -0.48249787 0.15202376 -0.14329489, -0.48322698 0.15121703 -0.14517759, -0.48359105 0.15117519 -0.1453674, -0.48293492 0.15123065 -0.14488117, -0.48360229 0.15115336 -0.14530481, -0.46361616 0.15621337 -0.074051514, -0.46325389 0.15621324 -0.071067199, -0.46361086 0.15627666 -0.070908293, -0.46324357 0.15627661 -0.0710475, -0.46325389 0.15621339 -0.073914006, -0.46292022 0.15627678 -0.071270809, -0.46322688 0.15633346 -0.071015939, -0.46361092 0.15627679 -0.074072883, -0.46324366 0.15627691 -0.073933706, -0.46238306 0.15627672 -0.072687164, -0.46238312 0.15627673 -0.07229425, -0.46234766 0.15633364 -0.072289988, -0.46289662 0.1563336 -0.071244076, -0.4626303 0.15633354 -0.071544513, -0.46286514 0.15638109 -0.071208581, -0.46244374 0.15633367 -0.073081359, -0.46234766 0.15633364 -0.072691485, -0.46230054 0.15638109 -0.072697148, -0.46239933 0.15638113 -0.073098049, -0.4625912 0.15638104 -0.071517572, -0.46259114 0.15638109 -0.073463634, -0.46234605 0.15641692 -0.073118314, -0.46254438 0.15641685 -0.073496088, -0.4635621 0.15643887 -0.070710555, -0.46239939 0.15638104 -0.071883276, -0.46254444 0.15641679 -0.071485326, -0.46234623 0.1564168 -0.07186313, -0.46357736 0.1564167 -0.070772186, -0.46282735 0.15641686 -0.07381545, -0.46249208 0.15643904 -0.073532119, -0.46278518 0.15643908 -0.073862895, -0.462244 0.15641688 -0.072277322, -0.4622868 0.15643896 -0.071840718, -0.46218106 0.15643904 -0.072269782, -0.46314892 0.15643883 -0.070867375, -0.46314892 0.15643904 -0.07411395, -0.46218112 0.15643902 -0.072711602, -0.46359095 0.15638091 -0.070827678, -0.46240506 0.15621334 -0.072684482, -0.46240523 0.15621333 -0.072296962, -0.46293488 0.1562133 -0.071287498, -0.46265969 0.15627673 -0.071565047, -0.46247706 0.15627685 -0.073068514, -0.46317843 0.15641676 -0.070923552, -0.46263024 0.15633366 -0.073436871, -0.46278521 0.15643899 -0.071118459, -0.46244362 0.15633358 -0.071900234, -0.46286505 0.15638117 -0.073772922, -0.46360227 0.15633345 -0.070873603, -0.46230054 0.15638109 -0.072284237, -0.46317849 0.15641692 -0.074057952, -0.46224406 0.1564168 -0.072704062, -0.46320486 0.15638091 -0.070973888, -0.4635621 0.15643904 -0.074270621, -0.46228668 0.15643904 -0.073140755, -0.46249783 0.1562133 -0.073060706, -0.4628273 0.15641679 -0.071166113, -0.46267793 0.15621325 -0.071577623, -0.46249214 0.15643893 -0.071449324, -0.46265969 0.15627673 -0.073416427, -0.46247706 0.15627673 -0.071912959, -0.46289644 0.15633367 -0.073737368, -0.46320483 0.15638113 -0.074007496, -0.46357742 0.15641692 -0.07420902, -0.46267793 0.15621333 -0.073404029, -0.46292022 0.15627679 -0.073710516, -0.46249783 0.1562133 -0.071920708, -0.46361613 0.15621324 -0.0709299, -0.46322706 0.15633373 -0.073965505, -0.46359101 0.15638116 -0.074154004, -0.46293482 0.15621337 -0.073693976, -0.46360227 0.15633363 -0.074107721, -0.4669376 0.15692371 -0.073904827, -0.46654913 0.15692365 -0.074522838, -0.46659312 0.1569408 -0.074558035, -0.46698827 0.15694083 -0.073929265, -0.46723345 0.15694073 -0.073228493, -0.46689078 0.15689597 -0.073882326, -0.4665086 0.15689597 -0.074490502, -0.46717867 0.1569237 -0.073215857, -0.4671281 0.15689594 -0.073204383, -0.4647387 0.15694095 -0.075723305, -0.46472624 0.15692391 -0.075668409, -0.46543959 0.15694097 -0.075478062, -0.4647148 0.15689625 -0.075617746, -0.46541512 0.15692383 -0.075427249, -0.46606824 0.15694085 -0.075083002, -0.46539271 0.15689619 -0.075380638, -0.46603319 0.1569238 -0.075039044, -0.46600097 0.15689607 -0.074998453, -0.46181771 0.1564972 -0.074231699, -0.46225992 0.15649723 -0.074673876, -0.46185824 0.15646946 -0.074199423, -0.46229222 0.15646951 -0.074633345, -0.4628118 0.15646948 -0.074959829, -0.4623273 0.15645245 -0.074589208, -0.46283612 0.15645242 -0.074909195, -0.46340373 0.15645246 -0.07510753, -0.46278936 0.15649721 -0.07500647, -0.4633911 0.15646955 -0.075162396, -0.46337953 0.1564972 -0.07521306, -0.46138391 0.15645243 -0.073088005, -0.4613291 0.15646946 -0.073100463, -0.46158257 0.15645246 -0.073655292, -0.46127859 0.15649703 -0.073112205, -0.46153185 0.15646948 -0.073679671, -0.46190229 0.15645246 -0.074164346, -0.461485 0.15649712 -0.073702231, -0.48668513 0.15198255 -0.14391191, -0.48674133 0.15199777 -0.14391942, -0.48679322 0.15202262 -0.14393173, -0.4816241 0.15254036 -0.14279588, -0.48139465 0.15226975 -0.14333721, -0.48671219 0.15232147 -0.14333405, -0.48152831 0.15260288 -0.14277108, -0.48666179 0.1522911 -0.14333282, -0.48191085 0.15285061 -0.14227553, -0.48194954 0.15281048 -0.14229386, -0.48157436 0.1525673 -0.14278023, -0.48660722 0.15226977 -0.14333721, -0.48642749 0.15256722 -0.14278032, -0.48637769 0.15254033 -0.14279588, -0.48131654 0.15198258 -0.1439117, -0.4813399 0.15229112 -0.14333282, -0.48126024 0.15199777 -0.14391942, -0.48601016 0.15277854 -0.14231957, -0.48120853 0.15202251 -0.14393161, -0.48128965 0.15232146 -0.14333396, -0.48647341 0.1526029 -0.14277108, -0.4860521 0.15281042 -0.14229386, -0.4855257 0.15297034 -0.1419359, -0.48609093 0.15285066 -0.14227553, -0.48555782 0.15300635 -0.1419019, -0.48495296 0.15310493 -0.14166676, -0.48558727 0.15305021 -0.14187627, -0.48497286 0.15314372 -0.14162739, -0.48432443 0.15317412 -0.14152823, -0.48499119 0.15319023 -0.14159633, -0.48433122 0.15321434 -0.141486, -0.4836773 0.15317418 -0.14152823, -0.48433754 0.15326217 -0.14145239, -0.48367056 0.15321425 -0.14148591, -0.48304901 0.15310498 -0.14166676, -0.48366424 0.15326211 -0.14145239, -0.48302913 0.15314373 -0.14162739, -0.48247609 0.15297036 -0.14193569, -0.48301059 0.15319011 -0.14159624, -0.4824442 0.15300639 -0.14190193, -0.48199174 0.15277852 -0.14231952, -0.48241457 0.15305024 -0.14187606, -0.48079327 0.15237936 -0.14411007, -0.48074141 0.15240425 -0.14412256, -0.48068506 0.15241949 -0.14413033, -0.4808864 0.1527227 -0.14342351, -0.48083606 0.15275297 -0.1434247, -0.48116073 0.15304591 -0.1427768, -0.48111483 0.15308145 -0.14276762, -0.48684111 0.15304595 -0.14277686, -0.48716572 0.15275303 -0.1434247, -0.48688704 0.15308154 -0.14276768, -0.48711529 0.15272263 -0.14342351, -0.48731652 0.15241942 -0.14413027, -0.48644069 0.15337072 -0.14218922, -0.48693675 0.15310843 -0.14275192, -0.48648271 0.15340261 -0.1421635, -0.48588458 0.15363969 -0.14168926, -0.4864018 0.15333049 -0.14220758, -0.48585257 0.1536037 -0.14172323, -0.48517662 0.15380576 -0.14135714, -0.48582298 0.15355983 -0.14174889, -0.4851566 0.15376702 -0.14139639, -0.4844006 0.15389138 -0.14118598, -0.48513845 0.15372062 -0.14142756, -0.48439381 0.15385109 -0.14122851, -0.4836013 0.15389134 -0.14118595, -0.48438767 0.1538033 -0.14126189, -0.48360795 0.15385106 -0.14122851, -0.48282519 0.15380581 -0.14135714, -0.48361436 0.1538033 -0.1412621, -0.4828451 0.15376696 -0.1413966, -0.48211741 0.15363969 -0.14168926, -0.48286346 0.15372044 -0.14142756, -0.48214933 0.15360381 -0.14172323, -0.48151925 0.15340266 -0.14216338, -0.48217878 0.15355983 -0.14174886, -0.48156103 0.15337065 -0.14218922, -0.48106489 0.15310843 -0.14275183, -0.48159999 0.15333055 -0.14220758, -0.48722026 0.15277435 -0.14342041, -0.4872604 0.15240429 -0.14412262, -0.48078138 0.15277426 -0.14342041, -0.48720846 0.1523793 -0.14411007, -0.47297251 0.086916417 -0.075515911, -0.47296357 0.086905539 -0.07551904, -0.47288087 0.086707145 -0.075227961, -0.47287169 0.086702779 -0.075272664, -0.47282305 0.086609378 -0.075276747, -0.47283047 0.086605802 -0.075224951, -0.47289807 0.090826824 -0.034242854, -0.47289675 0.090822235 -0.034226701, -0.47289434 0.090814471 -0.034210607, -0.47288981 0.090799361 -0.034189031, -0.47288254 0.0907754 -0.034164891, -0.4728696 0.090732515 -0.034132704, -0.47283164 0.090606943 -0.034069315, -0.47277883 0.090432242 -0.034009352, -0.47289816 0.090828553 -0.060258821, -0.47289699 0.090824917 -0.060273066, -0.47289369 0.090813771 -0.06029661, -0.47288635 0.090789735 -0.060326532, -0.47286826 0.090729713 -0.060373381, -0.4728142 0.09055078 -0.060456142, -0.47269145 0.086506307 -0.062181309, -0.47273278 0.086486012 -0.062267736, -0.47275832 0.086473465 -0.062361613, -0.4628748 0.066291884 -0.012605175, -0.46284923 0.066304415 -0.012511507, -0.46280757 0.066324711 -0.01242505, -0.46396855 0.068694815 -0.010766611, -0.46381524 0.068381503 -0.011322007, -0.46394411 0.068475112 -0.011434421, -0.4637275 0.068033025 -0.011926755, -0.46367624 0.06799306 -0.011853322, -0.46388641 0.068421841 -0.011375889, -0.46404436 0.068744466 -0.010804161, -0.46406397 0.068889365 -0.010147408, -0.46410707 0.06880784 -0.010844842, -0.46414247 0.068944693 -0.01016663, -0.46420816 0.069014251 -0.010187522, -0.4630945 0.066910118 -0.012351498, -0.46314439 0.066907063 -0.012435988, -0.46336678 0.067466065 -0.012134895, -0.46317914 0.066913292 -0.012527332, -0.46342477 0.067479536 -0.012212768, -0.46361104 0.067964986 -0.01178582, -0.4634681 0.067503497 -0.012297377, -0.47269133 0.086504579 -0.032322749, -0.47273281 0.086484253 -0.032236233, -0.47275832 0.086471811 -0.032142416, -0.47428146 0.088242516 -0.095111862, -0.47428736 0.088289976 -0.095243737, -0.47434345 0.088360384 -0.095259205, -0.47438097 0.088399649 -0.095259473, -0.47452417 0.088480532 -0.095073685, -0.47465637 0.088614613 -0.095142409, -0.47460809 0.088598236 -0.095253512, -0.47449625 0.088479131 -0.095181867, -0.47439983 0.088379055 -0.095157638, -0.47446012 0.088486761 -0.095286891, -0.47435433 0.088332817 -0.095159158, -0.4744108 0.088366196 -0.09505333, -0.47435758 0.08831273 -0.095056936, -0.47477284 0.088887349 -0.095743373, -0.47489086 0.0889135 -0.095634267, -0.47499523 0.088961557 -0.095518634, -0.47464135 0.088707238 -0.095481887, -0.47472215 0.088722914 -0.095372573, -0.47455058 0.088593155 -0.095361188, -0.47479215 0.08875303 -0.095259085, -0.47291055 0.086775482 -0.032050863, -0.47284949 0.08673799 -0.032213882, -0.47291064 0.086819708 -0.032118425, -0.47289836 0.086867407 -0.0321825, -0.47282711 0.086769834 -0.032273754, -0.47273839 0.086656839 -0.032346442, -0.47286296 0.086709425 -0.032150462, -0.47277644 0.086628094 -0.032277122, -0.4728674 0.086684287 -0.032084361, -0.47280279 0.086604238 -0.032201275, -0.47281694 0.086585522 -0.032120839, -0.47298899 0.087069988 -0.031956062, -0.47295463 0.086965993 -0.032072291, -0.4727892 0.090021908 -0.033761039, -0.47290459 0.090097308 -0.033589348, -0.47297618 0.090181217 -0.033398643, -0.47297427 0.091035575 -0.034195557, -0.4729934 0.091120496 -0.034086332, -0.47299376 0.091146544 -0.034179464, -0.47297233 0.091010198 -0.034121677, -0.47293797 0.090903148 -0.034155861, -0.47293207 0.090866923 -0.034107313, -0.47296971 0.090972856 -0.034057006, -0.47294191 0.090927556 -0.034211263, -0.47295475 0.090969235 -0.034258857, -0.47298604 0.090710223 -0.033645645, -0.47294354 0.090611234 -0.033775195, -0.47299024 0.09095037 -0.033833876, -0.47287416 0.090517923 -0.033897415, -0.4729605 0.090844646 -0.033921853, -0.4729926 0.091081977 -0.034004912, -0.47291166 0.090743318 -0.034006342, -0.47298899 0.09111692 -0.034258857, -0.47295466 0.090970635 -0.060244575, -0.47298899 0.091118351 -0.060244575, -0.47295275 0.09074004 -0.060657218, -0.47296312 0.090882286 -0.060550228, -0.4729909 0.090988964 -0.0606298, -0.47298828 0.090842798 -0.060766026, -0.47289461 0.090642348 -0.060553357, -0.47291753 0.090779662 -0.060473606, -0.47298068 0.090422079 -0.061010554, -0.47297624 0.090182722 -0.061104968, -0.47292241 0.090331227 -0.060844496, -0.47290459 0.090098858 -0.060914293, -0.47282797 0.090247646 -0.060691759, -0.4727892 0.090023413 -0.060742691, -0.47299391 0.091149464 -0.060315326, -0.47299364 0.09113656 -0.06037347, -0.47297421 0.091038495 -0.060300782, -0.47297338 0.091025874 -0.060347334, -0.4729926 0.091081217 -0.060502604, -0.47294214 0.090930343 -0.060286835, -0.47294024 0.090918243 -0.060321644, -0.47296956 0.090971932 -0.060449764, -0.47293171 0.090866312 -0.060398504, -0.47291055 0.086821377 -0.062385544, -0.47282717 0.086771488 -0.062230065, -0.47289857 0.08686918 -0.06232132, -0.47291064 0.086777329 -0.062453106, -0.47277644 0.086629748 -0.062226906, -0.4727385 0.086658478 -0.062157348, -0.47280279 0.086605847 -0.062302694, -0.47281694 0.086587295 -0.06238313, -0.47295472 0.086967796 -0.062431499, -0.47298899 0.087071776 -0.062547758, -0.44097063 0.14195026 -0.087514535, -0.4410429 0.14195815 -0.087509736, -0.44106343 0.14175668 -0.088462934, -0.44092557 0.14173751 -0.088434145, -0.44092223 0.14166608 -0.088579223, -0.44106701 0.14169545 -0.088593826, -0.44092217 0.14151022 -0.088890895, -0.44106701 0.14153969 -0.088905558, -0.44106686 0.14153779 -0.088909104, -0.44092223 0.14150859 -0.088893995, -0.441138 0.13988492 -0.090202168, -0.44072494 0.14018534 -0.089958891, -0.44073817 0.13985221 -0.090011731, -0.44092971 0.14019692 -0.090027139, -0.44094884 0.13986763 -0.090084568, -0.44111493 0.14021887 -0.090136454, -0.44074097 0.14050733 -0.08984898, -0.44093335 0.1405165 -0.089911208, -0.44110933 0.14054203 -0.09000732, -0.44079089 0.14087875 -0.089635596, -0.44096068 0.14088769 -0.089687303, -0.44111931 0.1409153 -0.089762166, -0.4408617 0.14124323 -0.089294091, -0.44100013 0.14125523 -0.089327678, -0.44113284 0.14128283 -0.089373246, -0.44114283 0.1397116 -0.090208039, -0.4409537 0.13971163 -0.090089902, -0.44074303 0.1397116 -0.090016469, -0.44114271 0.13115439 -0.090208545, -0.4409537 0.13115445 -0.09009023, -0.44074303 0.13115439 -0.090016946, -0.44112867 0.13085708 -0.090191469, -0.44093972 0.13088673 -0.090074673, -0.44072881 0.13091323 -0.09000288, -0.44106498 0.12936248 -0.089014933, -0.44079012 0.12967196 -0.08935599, -0.44089451 0.12939472 -0.088976011, -0.44094929 0.12965675 -0.089400753, -0.44109949 0.12962104 -0.089461997, -0.44072965 0.13000986 -0.089655623, -0.4409146 0.12999389 -0.089713141, -0.44070378 0.13028692 -0.089818761, -0.44108528 0.12995659 -0.089798406, -0.44090298 0.13026875 -0.089882389, -0.44070131 0.13059144 -0.089936748, -0.44108412 0.13023236 -0.089982018, -0.44090956 0.13056974 -0.090004966, -0.44109705 0.13053589 -0.090115473, -0.44107538 0.12928548 -0.088863537, -0.44090495 0.12932749 -0.088844046, -0.44107547 0.12912874 -0.088527307, -0.44090492 0.12917075 -0.088507816, -0.44090492 0.12912658 -0.088411763, -0.44107172 0.12909135 -0.088441119, -0.44094032 0.12894097 -0.087575749, -0.44105414 0.128921 -0.087579712, -0.4390083 0.12873784 -0.087872669, -0.43903038 0.12880063 -0.08786352, -0.4390305 0.1287777 -0.087548897, -0.43903044 0.12886888 -0.088171199, -0.43900836 0.12871435 -0.087548956, -0.43900815 0.12880816 -0.088189319, -0.43900827 0.12892362 -0.088492647, -0.43923393 0.12902437 -0.088124767, -0.43923399 0.12912816 -0.088397309, -0.43917066 0.12900315 -0.088130906, -0.43917066 0.12910806 -0.088406876, -0.43923396 0.12896128 -0.087839916, -0.43923399 0.12893993 -0.087548688, -0.43911368 0.12896892 -0.088141069, -0.43911368 0.12907556 -0.088421807, -0.43917051 0.12893932 -0.087843135, -0.43917051 0.12891774 -0.087548897, -0.4390662 0.12892334 -0.088154897, -0.4390662 0.12903261 -0.088441715, -0.43911365 0.12890388 -0.087848261, -0.43911365 0.12888204 -0.087548897, -0.4390305 0.1289811 -0.088465884, -0.4390662 0.1288569 -0.087855116, -0.43906608 0.12883452 -0.087548897, -0.43900833 0.12870446 0.087564334, -0.43903032 0.12876771 0.087564543, -0.43906608 0.12882465 0.087564543, -0.43911365 0.12887217 0.087564543, -0.43917051 0.12890789 0.087564543, -0.43923408 0.12893015 0.087564543, -0.43923408 0.129335 -0.088840589, -0.43917054 0.12931475 -0.088850006, -0.43911365 0.12928243 -0.088865176, -0.4390662 0.12923928 -0.088885173, -0.43903047 0.12918779 -0.088909104, -0.4390083 0.1291303 -0.088936076, -0.4390083 0.12879823 0.088204965, -0.4390305 0.12885892 0.088186845, -0.4390083 0.12891367 0.088508233, -0.43900833 0.12872802 0.087888047, -0.43903044 0.12879074 0.087878928, -0.43923399 0.12911819 0.088412747, -0.43923399 0.12895131 0.087855473, -0.43917051 0.12892935 0.087858662, -0.43923396 0.12901439 0.088140234, -0.43917063 0.1290981 0.088422284, -0.43911371 0.12889406 0.087863669, -0.43917066 0.12899324 0.088146552, -0.43911368 0.12906569 0.088437185, -0.43906614 0.128847 0.087870732, -0.43911371 0.12895896 0.088156804, -0.43906632 0.12902261 0.088457331, -0.4390662 0.12891337 0.088170484, -0.43903047 0.12897107 0.088481471, -0.43917066 0.12987706 -0.089569494, -0.43923411 0.13027437 -0.089796379, -0.43923399 0.12989098 -0.089552358, -0.4390305 0.13066633 -0.090106264, -0.4390305 0.13115445 -0.090161875, -0.43906623 0.1311544 -0.090105042, -0.43906632 0.13067913 -0.090050921, -0.43923399 0.13115445 -0.089999691, -0.43923396 0.12957242 -0.089228198, -0.43906632 0.13022815 -0.08989118, -0.43911356 0.13068987 -0.090004757, -0.43911371 0.13024901 -0.089848623, -0.43911368 0.12985456 -0.089597538, -0.43917051 0.13026455 -0.089816436, -0.43900836 0.1306521 -0.090168163, -0.43900836 0.13115443 -0.090225473, -0.43917051 0.12955502 -0.089241877, -0.43903044 0.13020317 -0.0899425, -0.4390662 0.12982464 -0.089634374, -0.43911371 0.12952678 -0.089263901, -0.43900836 0.1301755 -0.089999422, -0.4390305 0.12978889 -0.089678392, -0.43906617 0.12948935 -0.089293018, -0.43900818 0.12974884 -0.089727804, -0.4390305 0.12944447 -0.089328066, -0.43900818 0.12939443 -0.089367196, -0.43923411 0.13070285 -0.089948162, -0.43917051 0.13069782 -0.089969948, -0.43917066 0.13115449 -0.090021953, -0.43911365 0.13115445 -0.090057626, -0.43900818 0.12912031 0.088951692, -0.4390305 0.12917781 0.088924751, -0.4390662 0.12922941 0.08890079, -0.43911365 0.12927242 0.088880762, -0.43917063 0.12930478 0.088865623, -0.43923405 0.12932494 0.088856295, -0.43923399 0.13971159 -0.089999184, -0.43917057 0.13971162 -0.090021446, -0.43911365 0.13971154 -0.09005712, -0.43906626 0.13971159 -0.090104595, -0.43903053 0.13971165 -0.090161428, -0.43900841 0.13971166 -0.090224847, -0.43917054 0.13025457 0.08983238, -0.43917054 0.12986699 0.089585409, -0.43923396 0.12988093 0.089568123, -0.43923396 0.1302643 0.089812353, -0.4390305 0.12943447 0.089343771, -0.43906632 0.12947927 0.089308843, -0.43923393 0.13069269 0.089964017, -0.43923393 0.13114424 0.090015516, -0.43906608 0.12981446 0.08965002, -0.43911365 0.12951671 0.089279518, -0.43911359 0.1298445 0.089612916, -0.43911356 0.13023889 0.089864448, -0.43900815 0.12938447 0.089382634, -0.43917051 0.13068762 0.089985713, -0.43917054 0.13114433 0.090037808, -0.43903035 0.12977877 0.089694008, -0.43906608 0.130218 0.089907035, -0.43911359 0.13067967 0.090020403, -0.4391135 0.13114424 0.090073332, -0.43900818 0.12973885 0.089743569, -0.43903038 0.13019307 0.089958146, -0.43906608 0.13066892 0.090066895, -0.43906617 0.13114424 0.090120867, -0.43900818 0.13016529 0.090015069, -0.43903044 0.13065617 0.090122208, -0.43903038 0.13114429 0.09017776, -0.4390083 0.13064195 0.090184078, -0.43900821 0.1311442 0.090241298, -0.43923396 0.12956235 0.089243844, -0.43917057 0.12954494 0.089257464, -0.43917063 0.14058132 -0.089825526, -0.43917063 0.14096284 -0.089589581, -0.43923405 0.14094914 -0.089572117, -0.43923402 0.14057176 -0.08980532, -0.43903056 0.14139183 -0.089364395, -0.43903056 0.1416523 -0.088961974, -0.43906626 0.14160144 -0.088936433, -0.43906623 0.14134778 -0.089328393, -0.43923417 0.14015259 -0.08995007, -0.4390662 0.14101419 -0.089655176, -0.43911377 0.1413109 -0.089298472, -0.43911377 0.14098495 -0.089617684, -0.43911377 0.1405966 -0.089857683, -0.43900827 0.14144087 -0.089404628, -0.43900827 0.14170891 -0.088990286, -0.43917057 0.14015737 -0.089971766, -0.43903062 0.1410493 -0.089699909, -0.43906626 0.14061689 -0.089900568, -0.43911359 0.14016514 -0.090006575, -0.43900824 0.14108832 -0.089749977, -0.43903062 0.14064148 -0.089952007, -0.43906617 0.14017566 -0.090052947, -0.43900827 0.14066857 -0.090009347, -0.43903056 0.14018822 -0.09010841, -0.43900838 0.14020208 -0.090170279, -0.43923405 0.14126609 -0.089261636, -0.43923411 0.14150718 -0.088889226, -0.43917057 0.14128327 -0.089275703, -0.43917075 0.14152695 -0.08889924, -0.43911377 0.14155896 -0.088915333, -0.43900824 0.13970144 0.090241894, -0.4390305 0.13970152 0.090178266, -0.43906614 0.1397014 0.090121374, -0.43911365 0.1397014 0.090073928, -0.43917057 0.13970152 0.090038165, -0.43923402 0.13970146 0.090015993, -0.43923405 0.14174311 -0.088417158, -0.43917063 0.141763 -0.088427022, -0.43911365 0.14179498 -0.088443086, -0.43906632 0.14183745 -0.088464364, -0.43903053 0.14188839 -0.088489756, -0.43900844 0.14194509 -0.088518128, -0.43917066 0.14095269 0.089606747, -0.4391706 0.14057119 0.089842334, -0.43923399 0.14056177 0.089822397, -0.43923405 0.14093907 0.089589193, -0.4390305 0.14017799 0.090125307, -0.43906626 0.14016555 0.090069875, -0.43923402 0.14125611 0.089278921, -0.43923405 0.14149708 0.088906363, -0.4390662 0.14060691 0.089917526, -0.43911359 0.14015511 0.090023473, -0.43911377 0.14058653 0.08987473, -0.43911377 0.14097479 0.089634761, -0.43900836 0.14019199 0.090187237, -0.43917063 0.14127323 0.089292869, -0.43917063 0.14151683 0.088916406, -0.43903038 0.14063135 0.089969024, -0.43906632 0.14100412 0.089672312, -0.4391138 0.14130093 0.08931528, -0.43911377 0.1415489 0.088932261, -0.43900821 0.14065841 0.090026125, -0.43903056 0.14103922 0.089716986, -0.43906635 0.14133766 0.089345679, -0.43906626 0.1415914 0.088953719, -0.43900838 0.14107826 0.089766845, -0.43903044 0.14138171 0.08938159, -0.43903056 0.14164224 0.08897911, -0.43900824 0.14143081 0.089421704, -0.43900827 0.14169893 0.089007363, -0.43923402 0.14014237 0.089967057, -0.43917063 0.14014721 0.089988604, -0.43923405 0.14193107 -0.087828383, -0.43923405 0.14195499 -0.087519422, -0.43917063 0.14195313 -0.08783184, -0.43917063 0.14197716 -0.087519422, -0.43923417 0.14186001 -0.088129982, -0.4391138 0.14198832 -0.087837324, -0.43911377 0.14201297 -0.087519422, -0.43917057 0.14188117 -0.088136628, -0.43906626 0.14203531 -0.087844744, -0.43906623 0.14206041 -0.087519601, -0.43911377 0.14191517 -0.088147596, -0.43903056 0.14209157 -0.087853298, -0.43903053 0.14211734 -0.087519363, -0.43906626 0.14196035 -0.088162169, -0.43900827 0.14215416 -0.087863192, -0.43900841 0.1421807 -0.087519422, -0.43903056 0.14201456 -0.088179454, -0.43900838 0.142075 -0.088198766, -0.43900827 0.14193501 0.088535056, -0.43903056 0.14187832 0.088506952, -0.43906626 0.14182737 0.088481411, -0.43911362 0.14178495 0.088460162, -0.43917057 0.14175306 0.088444069, -0.43923402 0.14173315 0.088434234, -0.43900844 0.14217088 0.087536469, -0.43903056 0.14210738 0.087536439, -0.43906617 0.14205049 0.087536439, -0.43911368 0.142003 0.087536439, -0.43917063 0.14196734 0.087536439, -0.43923405 0.14194508 0.087536469, -0.43900827 0.1421442 0.087880239, -0.43900827 0.14206494 0.088215664, -0.43903056 0.14200464 0.088196501, -0.43903044 0.14208151 0.087870464, -0.43923405 0.14184996 0.088147298, -0.43917063 0.14187106 0.088153705, -0.43923402 0.14192119 0.087845549, -0.43911377 0.14190519 0.088164672, -0.43917063 0.14194307 0.087848887, -0.43906617 0.14195035 0.088179246, -0.4391138 0.14197843 0.087854519, -0.43906623 0.14202538 0.087861672, -0.41300008 0.039393276 -0.014197215, -0.4129999 0.010493755 -0.014198884, -0.41299984 0.0064433366 -0.010148838, -0.41299996 0.0064421445 0.010150537, -0.41300002 0.010492191 0.01420112, -0.41300002 0.039391622 0.014202788, -0.41300008 0.043442115 0.010152712, -0.4130002 0.043443322 -0.010146812, -0.41682407 -0.01751484 -0.07454516, -0.41682401 -0.017515436 -0.064121678, -0.41520759 -0.016723782 -0.062321737, -0.41608724 -0.0149277 -0.062321648, -0.41770384 -0.015719339 -0.064121678, -0.41770384 -0.015718728 -0.074545011, -0.41520759 -0.016725466 -0.032193765, -0.41682407 -0.017517298 -0.030393943, -0.41520759 -0.016726524 -0.012564287, -0.41682407 -0.017518133 -0.014364347, -0.41520759 -0.016727909 0.012563542, -0.41682407 -0.017519802 0.014363512, -0.41682401 -0.017520756 0.03039296, -0.41520748 -0.016729146 0.03219299, -0.41770384 -0.015724629 0.030393109, -0.41608736 -0.014932975 0.032193288, -0.41770381 -0.015723705 0.014363512, -0.41608724 -0.014931887 0.01256378, -0.41608724 -0.014930457 -0.012564287, -0.41770384 -0.015722081 -0.014364257, -0.41770384 -0.015721232 -0.030393735, -0.41608724 -0.014929339 -0.032193765, -0.41682407 -0.017523259 0.074544266, -0.41770384 -0.015727133 0.074544266, -0.41608736 -0.014934659 0.062321171, -0.41770384 -0.015726492 0.064120904, -0.41520759 -0.016730756 0.062320843, -0.41682419 -0.017522514 0.064120904, -0.47511813 0.13817841 0.1694542, -0.47511378 0.1383481 0.16906036, -0.47506639 0.13839054 0.16908161, -0.47525355 0.13807108 0.17006214, -0.47517154 0.13816261 0.16995423, -0.47525242 0.13811567 0.17008545, -0.4750751 0.13822591 0.16948591, -0.47517511 0.13812016 0.16993065, -0.47515127 0.13815464 0.16943596, -0.47517076 0.13831615 0.16904436, -0.47534296 0.13813546 0.1702051, -0.47525969 0.13816939 0.17010693, -0.4750084 0.13849819 0.16913532, -0.47536048 0.13819197 0.1702164, -0.47508821 0.13823456 0.16975139, -0.47503349 0.13835523 0.16955839, -0.47508803 0.13828233 0.16977535, -0.47503045 0.13844147 0.16910692, -0.47503853 0.13831083 0.16953544, -0.47526243 0.13798216 0.16981326, -0.47515884 0.13809064 0.16965507, -0.47523069 0.13800825 0.16984396, -0.47519186 0.13806544 0.16963087, -0.47509533 0.13819516 0.16972919, -0.47504938 0.13827468 0.16951524, -0.47526824 0.13801105 0.17002125, -0.47519794 0.13813207 0.16941594, -0.47523406 0.13829628 0.16903444, -0.47519276 0.1380628 0.16989236, -0.47519043 0.13826661 0.16999568, -0.47509748 0.13833213 0.16979708, -0.47533417 0.13807978 0.17018561, -0.47511753 0.13814192 0.16969492, -0.47547135 0.13815948 0.17031051, -0.47550067 0.13815233 0.17033111, -0.4752619 0.13811596 0.16939579, -0.47530851 0.13795969 0.16977639, -0.47523943 0.1380426 0.16960339, -0.47517619 0.13821392 0.16997729, -0.47533384 0.13803336 0.17016278, -0.47530249 0.13795449 0.16996719, -0.47545427 0.13810094 0.1703039, -0.47537294 0.1379482 0.16973491, -0.47530481 0.13802816 0.16957335, -0.47534552 0.13797113 0.17012031, -0.47527641 0.1382242 0.17012171, -0.47533217 0.1379281 0.16993164, -0.47544488 0.13804305 0.17028718, -0.4753758 0.13790645 0.1698878, -0.47544321 0.1379948 0.17026533, -0.47503707 0.13840209 0.1695814, -0.4753761 0.13791302 0.17006154, -0.47540334 0.13788673 0.17002185, -0.47545177 0.13793023 0.17022179, -0.47543707 0.13789755 0.16983722, -0.47544384 0.13786598 0.1699724, -0.47547725 0.13787076 0.17015828, -0.47500989 0.1556616 0.13479896, -0.47503528 0.15559523 0.13478334, -0.47507238 0.15554039 0.1347702, -0.47512129 0.15549454 0.13475938, -0.47517797 0.15546113 0.13475163, -0.47523811 0.15544142 0.13474704, -0.47527006 0.15543641 0.13474591, -0.47500846 0.15566911 0.11479367, -0.47503057 0.15560564 0.11479367, -0.47506648 0.15554883 0.11479367, -0.4751139 0.15550134 0.11479367, -0.47517067 0.15546571 0.11479367, -0.475234 0.15544336 0.11479367, -0.47468084 0.155549 0.11285533, -0.474969 0.15554889 0.11380543, -0.47501567 0.15550143 0.11379622, -0.47429952 0.15546593 0.11192138, -0.47365656 0.15546584 0.11113797, -0.47361621 0.15550159 0.11117826, -0.47477719 0.15546572 0.11281525, -0.47483596 0.15544355 0.11279105, -0.4743523 0.15544367 0.11188625, -0.47464773 0.15560588 0.11286877, -0.47493401 0.15560579 0.11381243, -0.47425228 0.15550162 0.11195289, -0.47358274 0.15554912 0.11121173, -0.47472471 0.1555015 0.11283697, -0.47462732 0.15566929 0.11287735, -0.47491214 0.15566911 0.11381672, -0.4742128 0.15554914 0.11197947, -0.47355741 0.15560602 0.11123712, -0.47418287 0.1556059 0.11199911, -0.47354171 0.15566933 0.11125277, -0.47416458 0.15566936 0.11201157, -0.47370139 0.15544371 0.11109312, -0.47513363 0.15544347 0.11377273, -0.47507146 0.15546563 0.11378498, -0.45647058 0.15567045 0.094181642, -0.45648637 0.15560709 0.094166085, -0.45651171 0.15555027 0.094140753, -0.45654526 0.15550266 0.094107226, -0.45658556 0.15546696 0.094066814, -0.45663023 0.15544474 0.0940222, -0.45548579 0.15550269 0.092521653, -0.45516106 0.15555021 0.091614231, -0.45544192 0.15555017 0.092539772, -0.45586812 0.15560707 0.093412623, -0.4558498 0.15567049 0.093425319, -0.45538858 0.1556706 0.092562124, -0.4554089 0.15560707 0.092553481, -0.45553836 0.15546697 0.092500046, -0.45520768 0.15550271 0.091604933, -0.45526358 0.15546699 0.091593817, -0.45589799 0.15555029 0.093393072, -0.45559701 0.15544477 0.092475608, -0.45532575 0.15544477 0.091581419, -0.45593747 0.15550266 0.093366608, -0.4559848 0.15546696 0.093335196, -0.45603749 0.15544477 0.093299821, -0.45523414 0.15544495 0.090651497, -0.45510432 0.15567048 0.091625556, -0.45500836 0.15567061 0.090651497, -0.45512617 0.15560707 0.091621146, -0.45503053 0.15560731 0.090651259, -0.45506629 0.15555032 0.090651497, -0.45511374 0.15550278 0.090651497, -0.45517072 0.15546715 0.090651259, -0.45500836 0.15568073 -0.09063296, -0.45503053 0.15561743 -0.09063296, -0.45506647 0.15556057 -0.09063296, -0.45511386 0.15551308 -0.09063296, -0.45517072 0.15547739 -0.09063296, -0.45523414 0.15545513 -0.09063296, -0.45512614 0.15561749 -0.091602489, -0.45538858 0.15568098 -0.092543498, -0.45510435 0.15568085 -0.09160699, -0.4554089 0.15561754 -0.092534915, -0.45553848 0.15547749 -0.09248127, -0.45598474 0.15547745 -0.093316361, -0.45593747 0.15551314 -0.093347952, -0.4564707 0.15568098 -0.094162986, -0.45548585 0.15551315 -0.092503086, -0.45516106 0.15556057 -0.091595396, -0.45544198 0.15556069 -0.092521325, -0.45559701 0.15545522 -0.092457041, -0.45603749 0.15545525 -0.093281046, -0.45520774 0.15551308 -0.091586396, -0.45526358 0.15547732 -0.09157519, -0.45532581 0.15545514 -0.091562733, -0.45584974 0.15568092 -0.093406484, -0.4564864 0.15561761 -0.094147459, -0.4558681 0.15561761 -0.093394265, -0.45651159 0.15556066 -0.094122157, -0.45589802 0.1555607 -0.093374267, -0.45654526 0.1555133 -0.09408848, -0.45658547 0.1554774 -0.094048187, -0.4566302 0.15545529 -0.094003603, -0.47370139 0.15545614 -0.11107449, -0.47365651 0.15547828 -0.1111194, -0.47361627 0.1555142 -0.11115955, -0.47358271 0.1555616 -0.11119317, -0.47355741 0.1556185 -0.11121835, -0.47354171 0.15568182 -0.11123405, -0.47507146 0.15547845 -0.11376642, -0.47477725 0.15547837 -0.11279668, -0.47483584 0.15545627 -0.11277233, -0.47513354 0.15545636 -0.11375396, -0.47464779 0.15561861 -0.11285014, -0.47418299 0.15561864 -0.11198066, -0.47421271 0.15556164 -0.11196075, -0.47468075 0.15556166 -0.11283661, -0.47501549 0.15551424 -0.11377756, -0.47517079 0.15547848 -0.11477502, -0.4751139 0.15551427 -0.11477502, -0.47472471 0.15551414 -0.11281841, -0.47462729 0.15568185 -0.11285876, -0.47416452 0.15568185 -0.11199306, -0.474969 0.15556176 -0.11378686, -0.47506639 0.15556177 -0.11477502, -0.47493395 0.15561865 -0.11379386, -0.47503051 0.15561877 -0.11477502, -0.47491214 0.15568194 -0.11379822, -0.47500849 0.1556821 -0.11477496, -0.47435221 0.15545616 -0.11186753, -0.4742994 0.15547834 -0.11190279, -0.47425216 0.15551414 -0.11193429, -0.47523418 0.15545635 -0.11477502, -0.47526994 0.15545161 -0.13472719, -0.47523811 0.15545666 -0.13472836, -0.47517803 0.15547635 -0.13473298, -0.47512123 0.15550976 -0.13474096, -0.47507235 0.15555546 -0.13475184, -0.47503528 0.15561041 -0.13476492, -0.47500989 0.15567671 -0.13478042, -0.475234 0.13831535 -0.1690179, -0.4751707 0.13833517 -0.1690277, -0.4751136 0.13836715 -0.1690437, -0.47506636 0.13840963 -0.1690651, -0.47503045 0.1384605 -0.16909032, -0.47500834 0.13851717 -0.16911878, -0.47546318 0.13802592 -0.17027308, -0.47546497 0.13797824 -0.17024659, -0.47507858 0.13823928 -0.16947107, -0.47512361 0.13819167 -0.1694387, -0.47541937 0.13799271 -0.17020942, -0.47541687 0.13803957 -0.17023601, -0.47542784 0.13812731 -0.1702664, -0.47533163 0.13807012 -0.17015363, -0.47505996 0.13826981 -0.16948996, -0.47534141 0.13815518 -0.17018674, -0.47547433 0.13811481 -0.17030193, -0.47536847 0.13792452 -0.16996075, -0.47529581 0.13798359 -0.16976981, -0.4753975 0.13790871 -0.16992812, -0.47543105 0.13788995 -0.16996743, -0.47546253 0.13789649 -0.1698661, -0.47522557 0.13806738 -0.16959251, -0.47518554 0.13815455 -0.16940837, -0.47525606 0.13813411 -0.16938458, -0.47529784 0.13804844 -0.16955818, -0.47504535 0.13830532 -0.16951053, -0.47534284 0.1379472 -0.16999413, -0.47526404 0.13800013 -0.16979565, -0.47519299 0.13808416 -0.16961195, -0.47515336 0.13817097 -0.16942264, -0.47523555 0.13802257 -0.16982292, -0.47540316 0.13790557 -0.17000203, -0.47517622 0.13823284 -0.1699609, -0.47508752 0.13830198 -0.16975732, -0.47509134 0.13822909 -0.16971956, -0.47516331 0.1381059 -0.16963325, -0.47517315 0.13815467 -0.16992365, -0.47537863 0.13792826 -0.17003737, -0.4754082 0.13796838 -0.16969971, -0.47503442 0.13837279 -0.16954638, -0.47530806 0.1380042 -0.17005242, -0.47536668 0.13796745 -0.16972221, -0.47519544 0.13807705 -0.16987239, -0.47511986 0.13815728 -0.16967373, -0.47529694 0.13804242 -0.17008106, -0.47518134 0.13811292 -0.16989817, -0.47547856 0.13787164 -0.17007627, -0.47510299 0.13819048 -0.16969614, -0.47534573 0.13798578 -0.17009784, -0.47519991 0.1383083 -0.16998555, -0.47510418 0.13837349 -0.1697873, -0.47545648 0.13789417 -0.17011453, -0.47529206 0.13808711 -0.17010753, -0.47533569 0.13802467 -0.17012696, -0.47529754 0.13813041 -0.16937484, -0.47542772 0.13795272 -0.17017926, -0.47530088 0.13817063 -0.17014183, -0.4754723 0.13793775 -0.17021601, -0.47534022 0.1380468 -0.16954257, -0.47532842 0.13825019 -0.17015807, 0.15799935 0.15545134 -0.086990669, -0.15800068 0.15544921 -0.086990669, 0.1571994 0.1554416 0.086209401, 0.00029938295 0.15544061 0.086209282, 0.15799946 0.15544142 0.087009177, 0.1571994 0.15545131 -0.086190686, -0.00050066784 0.1554406 0.086209282, -0.15720075 0.15543957 0.086209282, -0.15800074 0.15543942 0.087009177, 0.00029929355 0.1554503 -0.086190805, -0.00050064921 0.15545022 -0.086190805, -0.15720072 0.15544923 -0.086190805, -0.00050075352 0.15344062 0.086209282, -0.00050070882 0.15345031 -0.086190805, -0.15320075 0.15344501 -0.011490867, -0.13570072 0.15344512 -0.011490688, -0.1572008 0.15344931 -0.086190894, -0.15320075 0.15344322 0.020509258, -0.15720074 0.15343955 0.086209282, -0.13570072 0.1534434 0.020509049, 0.00029936433 0.15344058 0.086209103, 0.00029939413 0.15345024 -0.086190805, 0.13569941 0.15344743 -0.02049081, 0.15719944 0.15345122 -0.086190894, 0.1531993 0.15344763 -0.02049084, 0.13569939 0.15344566 0.011509165, 0.1571995 0.15344156 0.086209103, 0.1531994 0.15344577 0.011509165, 0.13569936 0.15544569 0.011509314, 0.15319929 0.15544578 0.011509165, 0.15514937 0.15644515 0.022509322, 0.13374928 0.1564451 0.022509322, 0.1551493 0.15644777 -0.022490725, 0.1337494 0.15644756 -0.022490725, 0.15514936 0.15794775 -0.022490725, 0.15514928 0.15794522 0.0225095, 0.13374935 0.15794761 -0.022490457, 0.13374926 0.15794513 0.0225095, 0.13424936 0.15844747 -0.021990463, 0.13424942 0.15844505 0.022009626, 0.15464935 0.15844516 0.022009626, 0.15464938 0.15844756 -0.021990463, -0.26286069 0.15644431 -0.011014089, -0.26104969 0.15644436 -0.01057981, -0.25918874 0.15644425 -0.01050742, -0.25734955 0.15644436 -0.010799155, -0.25560245 0.1564444 -0.011444345, -0.25401482 0.15644443 -0.012417868, -0.25264776 0.15644458 -0.013682261, -0.25155351 0.15644456 -0.015189186, -0.25077417 0.1564447 -0.016880676, -0.25034007 0.15644488 -0.018691823, -0.2502676 0.15644503 -0.02055268, -0.25055933 0.15644512 -0.02239199, -0.2512044 0.15644509 -0.024138913, -0.25217792 0.15644524 -0.025726572, -0.25344247 0.15644526 -0.027093902, -0.25313881 0.15644546 -0.030612484, -0.24724182 0.15644498 -0.020249382, -0.2537204 0.1564455 -0.030953154, -0.25385806 0.15644427 -0.0089534372, -0.25327224 0.15644424 -0.0092869848, -0.26578116 0.15644415 -0.0090281516, -0.27225551 0.15644477 -0.020406023, -0.26622942 0.15644543 -0.030694351, -0.26564345 0.15644543 -0.03102766, -0.26636288 0.15644416 -0.0093689412, -0.24724607 0.15644494 -0.019575343, -0.2722598 0.15644474 -0.019731924, -0.25313875 0.15844549 -0.030612335, -0.25019029 0.15844521 -0.025430873, -0.24724184 0.15844493 -0.020249352, -0.24724607 0.15844491 -0.019575253, -0.24943793 0.15844475 -0.016163692, -0.25025925 0.1584447 -0.014430985, -0.24893011 0.15844488 -0.018012777, -0.24875101 0.15844491 -0.019921765, -0.2489062 0.158445 -0.021832749, -0.24939087 0.15844518 -0.023688093, -0.26564351 0.15844545 -0.03102766, -0.25968203 0.15844554 -0.030990377, -0.25372043 0.15844551 -0.030953154, -0.26622948 0.15844549 -0.030694351, -0.26676854 0.15844524 -0.028461084, -0.26519108 0.1584453 -0.029551014, -0.26813301 0.15844533 -0.0271139, -0.26344839 0.15844542 -0.030350581, -0.26159313 0.15844551 -0.030835137, -0.26924255 0.15844516 -0.025549993, -0.2668741 0.15844437 -0.011608377, -0.26531023 0.15879187 -0.010498896, -0.2669597 0.15879206 -0.011682048, -0.26531032 0.15844427 -0.010498896, -0.26822129 0.15844434 -0.012972578, -0.26836368 0.15879214 -0.013148084, -0.2693114 0.15844452 -0.014550224, -0.26947424 0.15879217 -0.014847174, -0.27011082 0.15844461 -0.016293064, -0.27025387 0.15879241 -0.016721472, -0.27059552 0.15844469 -0.018148199, -0.27067563 0.15879244 -0.018707082, -0.27075061 0.15844485 -0.020059422, -0.27072552 0.15879259 -0.020736262, -0.2705715 0.15844485 -0.02196829, -0.27040157 0.15879264 -0.022740379, -0.27006367 0.15844499 -0.023817465, -0.26971498 0.15879291 -0.024650589, -0.26868907 0.15879288 -0.026402071, -0.26735869 0.15879291 -0.027935252, -0.26576933 0.15879303 -0.029197887, -0.26397499 0.15879311 -0.03014718, -0.26203677 0.15879317 -0.030750349, -0.26002076 0.15879318 -0.030987248, -0.25799552 0.15879318 -0.030849561, -0.25777295 0.15844557 -0.030811325, -0.25603011 0.15879321 -0.030342057, -0.25592396 0.15844551 -0.030303374, -0.25419125 0.15879318 -0.029482231, -0.25419137 0.15844539 -0.029482231, -0.26733044 0.15891428 -0.027905568, -0.26865575 0.15891421 -0.026378199, -0.26860222 0.15896975 -0.026339754, -0.26728484 0.15896997 -0.027858123, -0.26688972 0.15896904 -0.011762634, -0.26527444 0.1589447 -0.010559931, -0.26525632 0.15896893 -0.010591015, -0.26734588 0.15887707 -0.02792187, -0.26686332 0.15898505 -0.011793151, -0.26867399 0.1588771 -0.026391432, -0.26693282 0.15891334 -0.011712953, -0.26571092 0.15897 -0.02910848, -0.26725695 0.15898585 -0.027829006, -0.26568887 0.15898594 -0.029074803, -0.26528963 0.15891331 -0.010534152, -0.26694754 0.15887627 -0.011696056, -0.2653009 0.15887618 -0.01051484, -0.26530787 0.15883505 -0.010502949, -0.26574692 0.15891442 -0.029163733, -0.26827994 0.15896903 -0.013214573, -0.26824841 0.15898502 -0.013239637, -0.2657592 0.15887734 -0.029182449, -0.26523587 0.15898493 -0.010625824, -0.26393393 0.15897003 -0.030048475, -0.26391849 0.15898603 -0.030011311, -0.26833168 0.15891349 -0.013173446, -0.2683492 0.15887633 -0.013159618, -0.2639592 0.15891442 -0.030109271, -0.26937976 0.15896907 -0.014897212, -0.26934418 0.15898508 -0.014916047, -0.26396796 0.15887737 -0.030130014, -0.26943812 0.15891358 -0.014866456, -0.2620146 0.15897012 -0.030645862, -0.26200619 0.15898594 -0.030606374, -0.26945788 0.15887642 -0.014855877, -0.26202831 0.15891451 -0.030710205, -0.27015188 0.15896933 -0.016753212, -0.27011338 0.15898535 -0.016765282, -0.2620329 0.15887737 -0.030732378, -0.27021471 0.15891367 -0.016733781, -0.26001814 0.15897012 -0.030880556, -0.26001713 0.15898612 -0.030840024, -0.27023616 0.15887654 -0.016727105, -0.26001969 0.15891445 -0.030946121, -0.27056959 0.15896946 -0.018719569, -0.27052954 0.15898536 -0.018724248, -0.26002035 0.15887737 -0.030968651, -0.27063504 0.1589137 -0.018711969, -0.25801262 0.15897015 -0.03074418, -0.258019 0.15898617 -0.030704364, -0.27065721 0.15887663 -0.018709287, -0.25800207 0.1589146 -0.03080906, -0.27061895 0.15896952 -0.02072911, -0.27057865 0.15898544 -0.020726517, -0.25799856 0.15887749 -0.030831322, -0.25606623 0.15897015 -0.030241594, -0.25607982 0.15898606 -0.030203685, -0.27068463 0.15891391 -0.02073361, -0.25424531 0.15897003 -0.029390082, -0.25422719 0.15894592 -0.029421076, -0.27070698 0.15887675 -0.020735189, -0.25604394 0.15891448 -0.030303463, -0.25421211 0.15891448 -0.029446825, -0.27029809 0.15896955 -0.022713616, -0.27025905 0.15898561 -0.022703543, -0.25420073 0.15887737 -0.029466256, -0.25603631 0.15887734 -0.030324712, -0.27036193 0.15891397 -0.022730008, -0.25419363 0.15883625 -0.029478177, -0.27038363 0.1588769 -0.02273564, -0.26961818 0.1589697 -0.024605229, -0.26958176 0.15898573 -0.024588212, -0.26967785 0.15891409 -0.024633124, -0.26969823 0.15887702 -0.024642721, -0.26856938 0.15898573 -0.02631624, -0.2542657 0.15898605 -0.029355273, -0.26506653 0.15965877 -0.025969014, -0.26370731 0.15965876 -0.02694355, -0.26217523 0.15965891 -0.02761431, -0.26475808 0.15923186 -0.011441723, -0.26427743 0.15945637 -0.012262329, -0.26746163 0.15927163 -0.014028683, -0.26625237 0.15965819 -0.01532875, -0.26707944 0.15965825 -0.016782418, -0.26514098 0.15965813 -0.014078841, -0.26963165 0.159159 -0.017469659, -0.26758626 0.15965834 -0.018376246, -0.26379409 0.15965804 -0.013087496, -0.25832227 0.15927246 -0.029632077, -0.25723115 0.15965891 -0.027583227, -0.25886485 0.15965888 -0.027941331, -0.26053724 0.15965888 -0.027951702, -0.26238504 0.15915975 -0.029841885, -0.26775065 0.15965831 -0.020040616, -0.2675654 0.15965845 -0.021702722, -0.26703873 0.15965864 -0.023289904, -0.25570753 0.15965888 -0.026893422, -0.25522438 0.15945733 -0.027718529, -0.26619336 0.1596587 -0.02473323, -0.25474361 0.15923297 -0.028539404, -0.25263825 0.15898597 -0.028187975, -0.25436065 0.15965876 -0.025902107, -0.25125322 0.15898591 -0.026741341, -0.25621703 0.15943857 -0.011675134, -0.25749549 0.1589849 -0.009374693, -0.25558314 0.15898493 -0.0099698752, -0.25381282 0.15898502 -0.010906264, -0.25579426 0.15965804 -0.013037428, -0.25732628 0.15965798 -0.012366667, -0.25076953 0.15943906 -0.020975605, -0.24892291 0.15898551 -0.01925467, -0.24897213 0.15898566 -0.021256849, -0.24938829 0.15898576 -0.023215726, -0.25191537 0.15965858 -0.021604821, -0.25175092 0.15965843 -0.019940391, -0.25896433 0.15965798 -0.012029275, -0.25948456 0.15898493 -0.0091410726, -0.26063672 0.15965798 -0.012039796, -0.26148263 0.15898484 -0.0092767328, -0.25443509 0.15965824 -0.014011994, -0.25224474 0.15898511 -0.012151971, -0.2634218 0.15898499 -0.0097772926, -0.26227042 0.15965796 -0.012397781, -0.25330815 0.15965819 -0.015247837, -0.25093225 0.15898515 -0.013664618, -0.24991997 0.15898529 -0.015392914, -0.25246301 0.15965839 -0.016690865, -0.24924256 0.15898541 -0.017277583, -0.25193617 0.1596584 -0.018278375, -0.25242212 0.15965861 -0.02319856, -0.25015739 0.15898579 -0.02506505, -0.25324938 0.15965876 -0.024652109, -0.25570759 0.15894529 -0.026893422, -0.25436071 0.15894517 -0.025902018, -0.25324926 0.15894513 -0.024652109, -0.2524223 0.15894511 -0.023198709, -0.25191537 0.15894493 -0.021604821, -0.25175098 0.15894485 -0.019940481, -0.25193617 0.15894485 -0.018278256, -0.25246295 0.15894479 -0.016690955, -0.25330815 0.15894452 -0.015247837, -0.25443509 0.15894461 -0.014012083, -0.25579426 0.15894452 -0.013037428, -0.25732639 0.15894458 -0.012366608, -0.25896433 0.15894443 -0.012029156, -0.26063684 0.15894447 -0.012039527, -0.26227048 0.15894443 -0.012397721, -0.26379415 0.15894446 -0.013087496, -0.27225986 0.15844479 -0.019731775, -0.27225557 0.15844485 -0.020405933, -0.26357761 0.15844432 -0.0096776336, -0.26578107 0.15844414 -0.0090280622, -0.26172873 0.15844424 -0.0091698319, -0.26636294 0.15844421 -0.0093686134, -0.25981966 0.15844426 -0.0089907795, -0.25385818 0.1584443 -0.0089534372, -0.25605342 0.15844437 -0.0096305162, -0.25790843 0.15844417 -0.0091459602, -0.25431058 0.15844434 -0.010430053, -0.25327227 0.15844434 -0.0092869252, -0.25273308 0.15844443 -0.011520013, -0.25136873 0.15844452 -0.012867227, -0.25262758 0.15844539 -0.02837275, -0.25128028 0.15844533 -0.027008489, -0.25254187 0.158793 -0.028298929, -0.25113788 0.15879305 -0.026832774, -0.25002733 0.15879294 -0.025133833, -0.24924786 0.15879288 -0.023259476, -0.24882598 0.15879276 -0.021274045, -0.24877602 0.15879251 -0.019244686, -0.24910004 0.15879253 -0.017240778, -0.24978665 0.15879229 -0.015330657, -0.2508125 0.1587922 -0.013578907, -0.25214294 0.15879223 -0.012045845, -0.25373235 0.15879217 -0.010783061, -0.25552663 0.15879202 -0.0098337978, -0.2574648 0.15879197 -0.0092305988, -0.2594808 0.15879193 -0.0089939088, -0.26150611 0.15879202 -0.0091314167, -0.26347151 0.15879202 -0.0096388608, -0.26514098 0.15894455 -0.01407896, -0.26625237 0.15894461 -0.015328869, -0.26707938 0.15894464 -0.016782418, -0.26758632 0.15894474 -0.018376127, -0.26775065 0.15894485 -0.020040527, -0.26756534 0.15894486 -0.021702662, -0.26703873 0.15894499 -0.023289993, -0.26619348 0.15894511 -0.024733201, -0.26506659 0.1589452 -0.025969014, -0.26370737 0.15894526 -0.026943639, -0.26217529 0.15894523 -0.02761434, -0.26053724 0.15894529 -0.027951792, -0.25886485 0.15894529 -0.027941331, -0.25723103 0.15894517 -0.027583435, -0.25327876 0.1589451 -0.024344102, -0.25247231 0.15894504 -0.022794679, -0.2586365 0.15894443 -0.012270585, -0.26752523 0.15894488 -0.02062206, -0.25694665 0.15894449 -0.012712106, -0.26718977 0.15894499 -0.02233617, -0.25440982 0.15894523 -0.025674924, -0.26038238 0.15894443 -0.012215957, -0.25539729 0.15894452 -0.013518468, -0.2558085 0.1589452 -0.026720956, -0.26209649 0.15894443 -0.01255165, -0.26648131 0.15894507 -0.023932651, -0.25406632 0.15894462 -0.014649376, -0.26543531 0.15894508 -0.025331452, -0.25740513 0.15894526 -0.027429536, -0.263693 0.15894443 -0.013260022, -0.25302032 0.15894465 -0.016048208, -0.26410428 0.15894519 -0.02646254, -0.2591193 0.15894532 -0.027764902, -0.26509181 0.15894458 -0.014305934, -0.2523118 0.15894473 -0.017644897, -0.26255491 0.15894525 -0.02726908, -0.260865 0.15894523 -0.027710631, -0.2662228 0.15894453 -0.015637144, -0.2519764 0.15894479 -0.019359007, -0.26702932 0.15894465 -0.017186269, -0.25203088 0.15894499 -0.021104738, -0.26747081 0.15894465 -0.01887618, -0.263693 0.15969718 -0.013260022, -0.26509181 0.15969732 -0.014305934, -0.26622286 0.15969735 -0.015637025, -0.26702932 0.15969746 -0.017186329, -0.26747087 0.15969753 -0.01887624, -0.26752517 0.15969768 -0.020621911, -0.26718965 0.1596977 -0.02233611, -0.26648125 0.15969786 -0.023932651, -0.26543531 0.15969789 -0.025331452, -0.26410422 0.15969792 -0.02646251, -0.26255503 0.15969807 -0.027268991, -0.26086506 0.15969804 -0.027710542, -0.25911924 0.15969804 -0.027764902, -0.25740519 0.15969813 -0.027429327, -0.25580856 0.15969804 -0.026720837, -0.26185676 0.16034597 -0.021910831, -0.26221004 0.160346 -0.021430805, -0.25975093 0.16044493 -0.019990459, -0.26482603 0.16002546 -0.022912934, -0.26378098 0.16018197 -0.022293851, -0.26377758 0.16018143 -0.022307321, -0.26250073 0.16032407 -0.018459782, -0.26355258 0.16021323 -0.01786755, -0.26354402 0.16021359 -0.017857477, -0.26481614 0.160026 -0.022922978, -0.26249853 0.16032396 -0.018454, -0.26377735 0.16018149 -0.022308275, -0.26377299 0.16018112 -0.022320554, -0.26341578 0.15979958 -0.013733402, -0.26250449 0.16032432 -0.018473372, -0.26355308 0.16021332 -0.017868146, -0.26356307 0.16021284 -0.017877713, -0.26141152 0.16034599 -0.022306517, -0.26480731 0.16002627 -0.022933915, -0.26376322 0.16018102 -0.022340611, -0.25969794 0.16034576 -0.02284427, -0.25842962 0.16036174 -0.022246078, -0.25969705 0.16034567 -0.022844568, -0.2637333 0.15998158 -0.015304193, -0.25968376 0.16034552 -0.022848204, -0.26313773 0.15989438 -0.014208063, -0.26285902 0.15998161 -0.014683679, -0.2597107 0.16034588 -0.022841886, -0.26353911 0.16002594 -0.015532628, -0.2627075 0.16002598 -0.014942631, -0.26250556 0.16008134 -0.015287295, -0.26479873 0.16002651 -0.022947177, -0.26230338 0.16013296 -0.015632406, -0.25966468 0.16034487 -0.022856519, -0.2631869 0.16018105 -0.023123458, -0.25966313 0.16034481 -0.022857115, -0.26498988 0.16000664 -0.022886083, -0.26500389 0.16000418 -0.022893503, -0.2625052 0.16032438 -0.01847671, -0.25973293 0.16034603 -0.022840515, -0.26502767 0.15999995 -0.02291064, -0.26250783 0.1603249 -0.018495694, -0.26357964 0.16021194 -0.0178902, -0.26276198 0.1601806 -0.016447082, -0.26210096 0.16018066 -0.015977994, -0.26358095 0.16021186 -0.017891154, -0.26503178 0.1599991 -0.022914365, -0.25965098 0.16034424 -0.022864118, -0.2644867 0.15998177 -0.016066924, -0.25963959 0.16034368 -0.022872254, -0.25968775 0.16021374 -0.024344578, -0.25970116 0.16032431 -0.023137137, -0.25968757 0.16032451 -0.023133531, -0.2596353 0.16034341 -0.022875711, -0.26222792 0.16034584 -0.018580899, -0.26194552 0.16034584 -0.018172249, -0.26071158 0.16040087 -0.018350169, -0.2595633 0.16000423 -0.025990948, -0.25956401 0.16000637 -0.025976852, -0.25956371 0.16000271 -0.026000962, -0.25956401 0.16000211 -0.026005164, -0.26256773 0.16021368 -0.016675696, -0.26194933 0.16021371 -0.016236827, -0.26174733 0.1602543 -0.016581878, -0.25956801 0.1599988 -0.026027426, -0.25968841 0.16021375 -0.02434428, -0.26154503 0.16029096 -0.0169269, -0.25957033 0.15999767 -0.026035532, -0.25962302 0.16034254 -0.022887424, -0.25957206 0.15999678 -0.026041016, -0.25711384 0.1601125 -0.024492547, -0.26250818 0.16032538 -0.018509641, -0.26359305 0.16021103 -0.017898068, -0.25957754 0.15999487 -0.026054248, -0.2595847 0.1599929 -0.026067659, -0.25967452 0.16021329 -0.024348393, -0.25961378 0.1603418 -0.022898093, -0.25968459 0.16032463 -0.023132637, -0.25966665 0.1603252 -0.023125425, -0.25961116 0.16034158 -0.02290155, -0.26333156 0.16018067 -0.017023727, -0.26425561 0.16002606 -0.016258225, -0.25970158 0.16021407 -0.024341956, -0.25970754 0.16032428 -0.023138419, -0.25971505 0.16032419 -0.023139402, -0.26429537 0.15998213 -0.024133965, -0.26333442 0.15998213 -0.024988517, -0.25960574 0.16034093 -0.022909448, -0.25965533 0.16021243 -0.02435638, -0.25958875 0.15999192 -0.026073948, -0.25959721 0.15999025 -0.026085451, -0.26250812 0.16032547 -0.018511668, -0.25960621 0.15998885 -0.026095375, -0.25960681 0.15998879 -0.026095971, -0.2617906 0.16032371 -0.017590091, -0.2596238 0.1599865 -0.026110783, -0.25963381 0.15998563 -0.026117548, -0.2596356 0.15998536 -0.026118711, -0.25959507 0.16033944 -0.022929028, -0.26134285 0.16032377 -0.017272398, -0.25964811 0.15998448 -0.026125386, -0.26250723 0.16032594 -0.018523827, -0.26360568 0.16021018 -0.017903939, -0.26361117 0.16020977 -0.017906055, -0.25959376 0.16033927 -0.022932217, -0.26509598 0.15998176 -0.016948923, -0.26221696 0.15998226 -0.025624409, -0.25965396 0.16021231 -0.024357066, -0.25965431 0.16032568 -0.02311869, -0.25958994 0.16033849 -0.02294229, -0.25972351 0.16021419 -0.024340376, -0.25973114 0.1603241 -0.023140445, -0.26224032 0.16034567 -0.018599436, -0.26099184 0.15998232 -0.026013955, -0.26089367 0.16034603 -0.022601232, -0.2603865 0.16032407 -0.023075536, -0.26608244 0.15983841 -0.016932502, -0.26504979 0.16000226 -0.017147318, -0.26504138 0.16000363 -0.017152593, -0.26505318 0.16000155 -0.017144904, -0.26507059 0.15999821 -0.017130241, -0.26504132 0.15999714 -0.022924677, -0.25958613 0.16033754 -0.022955671, -0.26507631 0.15999709 -0.01712431, -0.26508024 0.15999627 -0.01711987, -0.26508895 0.15999433 -0.017108455, -0.26509675 0.15999241 -0.017095819, -0.26510039 0.15999141 -0.017088905, -0.26510599 0.15998968 -0.017075822, -0.26511016 0.15998831 -0.017063275, -0.262503 0.16032699 -0.018546, -0.26511034 0.15998814 -0.017062232, -0.26511469 0.15998605 -0.017040059, -0.26362702 0.16020855 -0.017910853, -0.26511553 0.15998501 -0.017028347, -0.2595841 0.16033685 -0.022965863, -0.26511553 0.15998484 -0.017025933, -0.25964186 0.16021158 -0.024364129, -0.26511517 0.15998384 -0.017011777, -0.2596527 0.16032571 -0.023117766, -0.25964257 0.16032615 -0.023110762, -0.26511261 0.15998283 -0.01699315, -0.26511177 0.15998265 -0.016989604, -0.26510814 0.15998225 -0.016975984, -0.25963047 0.16021067 -0.024372056, -0.26510617 0.15998206 -0.016970292, -0.26510313 0.15998191 -0.016962931, -0.25958249 0.16033593 -0.022978082, -0.26411816 0.16021106 -0.020286098, -0.26499417 0.16001102 -0.017170325, -0.26498458 0.16001233 -0.017171755, -0.2650077 0.160009 -0.017167076, -0.26241109 0.1603366 -0.018647119, -0.26240143 0.16033736 -0.018650547, -0.26242247 0.16033572 -0.018642232, -0.26243487 0.16033477 -0.018635675, -0.26244238 0.16033402 -0.018630877, -0.26032588 0.16034609 -0.022781894, -0.26244661 0.16033363 -0.018628016, -0.26246372 0.16033202 -0.018613443, -0.26246902 0.16033147 -0.01860787, -0.26247337 0.16033104 -0.018602982, -0.26248184 0.16033009 -0.018591776, -0.26248953 0.16032915 -0.018579289, -0.25958207 0.16033489 -0.022992, -0.26365462 0.16020611 -0.017914757, -0.25962582 0.16021022 -0.024375781, -0.25962558 0.16032732 -0.02309595, -0.26250282 0.16032702 -0.018546596, -0.2624785 0.16032824 -0.021450326, -0.26360914 0.16020806 -0.022116855, -0.26498017 0.16001293 -0.017172351, -0.26378533 0.16019002 -0.017849997, -0.26369503 0.16019927 -0.022127733, -0.26370963 0.16019748 -0.022135332, -0.26367739 0.16020131 -0.022121325, -0.26367363 0.16020176 -0.022120073, -0.26365986 0.16020322 -0.022117034, -0.2636458 0.16020462 -0.022115186, -0.26376715 0.16018873 -0.022196189, -0.26493725 0.16001421 -0.022873208, -0.26364276 0.16020498 -0.022115096, -0.25958237 0.1603342 -0.02300103, -0.26362327 0.16020679 -0.022115186, -0.26504746 0.15999588 -0.022932217, -0.26240036 0.16033629 -0.021369502, -0.26241532 0.160335 -0.021377251, -0.26238289 0.16033749 -0.021363273, -0.26237902 0.16033785 -0.021361992, -0.26505002 0.15999517 -0.022935703, -0.26367715 0.16020399 -0.017914101, -0.25958291 0.1603339 -0.023006156, -0.26249871 0.16032776 -0.018559232, -0.26364079 0.16020736 -0.017913327, -0.26368067 0.16020352 -0.017913595, -0.26369104 0.1602025 -0.017911926, -0.26370463 0.16020092 -0.017908707, -0.2637147 0.16019979 -0.017905131, -0.26372567 0.16019851 -0.017900631, -0.26497182 0.16000944 -0.022879526, -0.2596139 0.160209 -0.024387076, -0.25962517 0.1603273 -0.023095652, -0.25961605 0.16032806 -0.02308552, -0.26373824 0.16019702 -0.017894045, -0.26496843 0.16000986 -0.022878543, -0.25958684 0.16033217 -0.023028329, -0.26374605 0.16019592 -0.017889127, -0.26495454 0.16001195 -0.022875264, -0.26374993 0.16019541 -0.017886266, -0.26494047 0.16001379 -0.022873655, -0.26376715 0.16019298 -0.017871842, -0.26377264 0.16019213 -0.01786612, -0.25960478 0.16020784 -0.024397656, -0.25958911 0.16033161 -0.02303575, -0.26377681 0.16019148 -0.017861232, -0.2624931 0.1603286 -0.018572226, -0.2636455 0.16020694 -0.017913863, -0.26375547 0.16019093 -0.022177026, -0.26375327 0.16019122 -0.022174165, -0.25960764 0.16032881 -0.023074374, -0.26374665 0.16019233 -0.022166029, -0.25959113 0.16033126 -0.02304177, -0.26373693 0.16019374 -0.022155985, -0.26373336 0.16019428 -0.022152677, -0.26247683 0.1603286 -0.021446481, -0.26247266 0.16032919 -0.021437541, -0.2624608 0.16033062 -0.021418527, -0.26245895 0.16033076 -0.021415964, -0.25959656 0.16033033 -0.023054674, -0.26245198 0.16033152 -0.021407619, -0.2624422 0.16033253 -0.021397397, -0.26243904 0.16033286 -0.021394625, -0.25960168 0.16020739 -0.02440156, -0.26023135 0.16043383 -0.019170091, -0.26018044 0.15983906 -0.027008876, -0.25971231 0.15998226 -0.026140317, -0.2622489 0.16034558 -0.0186093, -0.2596657 0.15998343 -0.026132658, -0.25959668 0.1602066 -0.024408892, -0.25960353 0.16032931 -0.023067787, -0.2622495 0.16034557 -0.018609986, -0.25966898 0.15998325 -0.026133642, -0.26225951 0.16034523 -0.018619671, -0.25968263 0.15998277 -0.026137099, -0.25968871 0.1599825 -0.026138291, -0.26227579 0.16034469 -0.018632069, -0.25969645 0.15998241 -0.026139453, -0.26227745 0.16034463 -0.018633053, -0.26506171 0.15999228 -0.022954866, -0.26506534 0.15999123 -0.022962436, -0.26506755 0.15999067 -0.022967473, -0.25958595 0.16020444 -0.0244288, -0.26228967 0.16034415 -0.018639997, -0.25958446 0.16020408 -0.024432167, -0.25958082 0.16020298 -0.024441704, -0.26507202 0.15998903 -0.022980556, -0.25957689 0.16020146 -0.024455264, -0.26507565 0.15998742 -0.022996143, -0.25957462 0.16020024 -0.024465993, -0.2650767 0.15998685 -0.023002431, -0.25957325 0.16019908 -0.024477437, -0.2614952 0.16021413 -0.023975477, -0.26228562 0.16021413 -0.02352567, -0.26158634 0.16032401 -0.022550568, -0.26101401 0.16032401 -0.022876039, -0.25957277 0.16019756 -0.024491772, -0.26359525 0.16020915 -0.022119746, -0.26248309 0.16032749 -0.021463558, -0.26248714 0.1603266 -0.021480247, -0.26360759 0.16020823 -0.022117034, -0.25957307 0.16019642 -0.024501041, -0.26159641 0.16034579 -0.017818913, -0.26119116 0.16034576 -0.017531291, -0.25957349 0.16019595 -0.024505749, -0.26217642 0.1603238 -0.017980829, -0.26310048 0.16021374 -0.017215267, -0.26357409 0.16021085 -0.022127226, -0.26248792 0.16032639 -0.021485433, -0.26248929 0.1603258 -0.02149941, -0.25957748 0.1601935 -0.024527952, -0.26062855 0.16021416 -0.024250939, -0.26379225 0.16018061 -0.017690673, -0.26483527 0.16002601 -0.017097041, -0.26501855 0.16000727 -0.017163411, -0.26502874 0.16000566 -0.017159119, -0.2635614 0.16021174 -0.022133306, -0.26248929 0.16032523 -0.021513477, -0.25957975 0.16019261 -0.024535522, -0.2637994 0.16018075 -0.01770483, -0.26484761 0.16002581 -0.017115518, -0.26354942 0.1602125 -0.022140786, -0.25958171 0.16019198 -0.024541512, -0.26248923 0.16032523 -0.021515504, -0.26230106 0.16034275 -0.021361843, -0.26232377 0.16034234 -0.018652663, -0.26230738 0.16034323 -0.018647924, -0.26354346 0.16021277 -0.022145018, -0.2595872 0.16019061 -0.024554476, -0.26380238 0.1601809 -0.01771225, -0.26248667 0.1603246 -0.02153565, -0.26380441 0.16018099 -0.017717883, -0.26231322 0.16034213 -0.021359131, -0.26233748 0.16034162 -0.018655434, -0.26485631 0.16002536 -0.017125621, -0.26485673 0.16002545 -0.017126188, -0.25959417 0.16018909 -0.024567708, -0.26353177 0.16021341 -0.022154793, -0.26231471 0.16034199 -0.021358743, -0.26248333 0.16032438 -0.02154927, -0.26380816 0.16018134 -0.017731562, -0.26234171 0.16034129 -0.018655822, -0.26486674 0.16002484 -0.017135665, -0.26227978 0.16034392 -0.021369174, -0.26230237 0.16034347 -0.018645898, -0.26380894 0.16018154 -0.01773487, -0.26227954 0.16034389 -0.021369174, -0.26352188 0.16021371 -0.022164926, -0.26248303 0.16032431 -0.021550074, -0.26232877 0.1603412 -0.021357104, -0.26352182 0.16021386 -0.022165075, -0.26381156 0.1601823 -0.017753735, -0.26235148 0.16034079 -0.018656597, -0.2624788 0.16032417 -0.021562293, -0.26488337 0.1600236 -0.01714851, -0.26351309 0.16021404 -0.022175804, -0.26488444 0.16002354 -0.017149225, -0.26226708 0.16034445 -0.021375433, -0.26246896 0.16032396 -0.02158244, -0.26234838 0.16033989 -0.021356955, -0.26381186 0.16018304 -0.017767802, -0.26237389 0.16033919 -0.018655911, -0.26489648 0.1600225 -0.017156139, -0.26225504 0.16034488 -0.021382675, -0.26350436 0.16021407 -0.022188857, -0.2638118 0.1601831 -0.017770067, -0.26235124 0.1603398 -0.021357194, -0.26407358 0.16002637 -0.023932025, -0.26237693 0.16033907 -0.018655553, -0.26224902 0.16034511 -0.021386966, -0.2638109 0.16018385 -0.017781958, -0.26490906 0.16002133 -0.01716207, -0.26315972 0.16002651 -0.024744585, -0.26491508 0.16002075 -0.017164156, -0.26246044 0.16018105 -0.023769423, -0.26236525 0.16033882 -0.021358982, -0.26238784 0.16033828 -0.018653736, -0.2622374 0.16034544 -0.021396652, -0.26505753 0.15998212 -0.023098722, -0.26506737 0.15998238 -0.023078814, -0.26507172 0.15998277 -0.023066178, -0.26507184 0.15998271 -0.023065731, -0.26507518 0.15998326 -0.02305235, -0.2650778 0.15998447 -0.023031518, -0.26507798 0.15998463 -0.023030296, -0.26380673 0.16018552 -0.01780425, -0.26507792 0.15998566 -0.023016259, -0.26493022 0.1600191 -0.017168894, -0.25967863 0.16002595 -0.02584444, -0.25969186 0.16018146 -0.024637178, -0.25967833 0.16018185 -0.024633572, -0.26380643 0.16018549 -0.017804816, -0.25967899 0.16002592 -0.02584444, -0.26380232 0.16018662 -0.017817631, -0.25966528 0.16002533 -0.025848135, -0.25967517 0.16018197 -0.024632528, -0.25965741 0.1601828 -0.024625376, -0.26222768 0.16034573 -0.021406814, -0.26494399 0.16001755 -0.017171398, -0.25969222 0.16002634 -0.025841817, -0.25969812 0.1601814 -0.024638429, -0.25970575 0.16018133 -0.024639383, -0.26222745 0.16034582 -0.021406874, -0.26379678 0.16018789 -0.017830595, -0.26494941 0.16001685 -0.017172232, -0.26495776 0.16001584 -0.017172799, -0.2622188 0.16034591 -0.021417633, -0.25964573 0.16002411 -0.02585642, -0.25964478 0.16002408 -0.025856927, -0.25964502 0.16018358 -0.0246187, -0.26379314 0.16018862 -0.017837629, -0.25971428 0.16002655 -0.025840387, -0.25972185 0.16018116 -0.024640307, -0.26068917 0.16018116 -0.024544701, -0.25963262 0.16002303 -0.025863841, -0.25964335 0.1601837 -0.024617538, -0.25963327 0.16018441 -0.024610892, -0.25962135 0.16002187 -0.025871739, -0.25961635 0.16002128 -0.025875941, -0.25961617 0.16018599 -0.024595961, -0.26296517 0.16021411 -0.022921249, -0.2596049 0.16001967 -0.025886491, -0.26207849 0.16032398 -0.022112772, -0.25961575 0.16018602 -0.024595514, -0.25960675 0.16018716 -0.02458559, -0.25959578 0.16001812 -0.02589722, -0.25959221 0.16001743 -0.02590166, -0.25959828 0.16018841 -0.024574116, -0.25958762 0.16001648 -0.025908425, -0.25957695 0.1600135 -0.025928214, -0.25957498 0.1600129 -0.025932446, -0.25957158 0.16001153 -0.025941268, -0.26488963 0.16001996 -0.022877797, -0.26377752 0.1601862 -0.022222057, -0.2637814 0.16018501 -0.022238269, -0.25956771 0.16000962 -0.025954589, -0.26490214 0.16001859 -0.022875234, -0.26377293 0.16018742 -0.022208825, -0.25956532 0.16000789 -0.025966153, -0.26490363 0.16001837 -0.022874936, -0.26486841 0.16002212 -0.022885278, -0.26378235 0.16018456 -0.022243813, -0.26378354 0.16018371 -0.02225782, -0.26491776 0.16001672 -0.022873238, -0.26377109 0.16018784 -0.022204295, -0.26209679 0.16002652 -0.025349364, -0.26161554 0.16018105 -0.024250165, -0.26485559 0.16002333 -0.022891626, -0.26378354 0.16018286 -0.022271708, -0.26248863 0.16032383 -0.018432483, -0.26353154 0.16021377 -0.017839089, -0.26484355 0.16002423 -0.022899106, -0.26249573 0.16032392 -0.018446699, -0.26378354 0.1601828 -0.022273466, -0.26093128 0.16002658 -0.025720105, -0.26483783 0.1600247 -0.022903129, -0.26285896 0.15894449 -0.014683947, -0.26373336 0.15894455 -0.015304193, -0.26448664 0.15894468 -0.016066924, -0.26509604 0.15894461 -0.016948923, -0.26210096 0.15894464 -0.015978083, -0.26276204 0.15894461 -0.016447291, -0.26333162 0.15894467 -0.017023906, -0.26379225 0.15894464 -0.017690673, -0.26370957 0.15894489 -0.022135332, -0.26373652 0.15894496 -0.022155479, -0.26375827 0.15894496 -0.022181168, -0.26377377 0.15894498 -0.022211, -0.26378217 0.15894493 -0.022243336, -0.26378331 0.15894501 -0.022277012, -0.26377681 0.15894496 -0.022309974, -0.26376316 0.15894496 -0.022340611, -0.26500386 0.15894493 -0.022893623, -0.26503083 0.15894502 -0.02291353, -0.26505253 0.15894507 -0.02293916, -0.26506808 0.15894502 -0.022969052, -0.26507655 0.15894504 -0.023001537, -0.26507756 0.15894499 -0.023035184, -0.26507112 0.15894496 -0.023068056, -0.26505753 0.15894496 -0.023098812, -0.26241532 0.15894493 -0.02137734, -0.26244214 0.1589449 -0.021397397, -0.2624639 0.15894489 -0.021423116, -0.26247951 0.15894489 -0.021452799, -0.26248786 0.15894486 -0.021485284, -0.26248893 0.1589449 -0.021518961, -0.26248255 0.15894493 -0.021551922, -0.26246896 0.15894493 -0.02158244, -0.26134297 0.15894476 -0.017272487, -0.26179066 0.15894467 -0.017590299, -0.26217648 0.15894479 -0.017980859, -0.26248863 0.15894476 -0.018432632, -0.25468501 0.16002214 -0.022974923, -0.25578353 0.16018456 -0.022355154, -0.25577083 0.1601837 -0.022349343, -0.25578889 0.16018501 -0.022357181, -0.25560543 0.1602141 -0.021308735, -0.25674888 0.1603239 -0.020945087, -0.25661609 0.16032393 -0.020300165, -0.25542197 0.16021404 -0.020418003, -0.25468579 0.16002309 -0.022963271, -0.25417599 0.16002634 -0.02176334, -0.25512335 0.16018099 -0.020447657, -0.25392923 0.16002637 -0.020565525, -0.25531951 0.16018102 -0.021399692, -0.25389007 0.15998209 -0.021854326, -0.25363061 0.15998206 -0.020594999, -0.25203082 0.15969774 -0.021104828, -0.25710252 0.16032597 -0.018336579, -0.25712368 0.16032702 -0.018329278, -0.25601551 0.16020977 -0.017689392, -0.2572737 0.16034591 -0.021400109, -0.25703487 0.16034597 -0.02085422, -0.25601628 0.16021015 -0.017695203, -0.25728092 0.16034591 -0.021414295, -0.25468078 0.16002004 -0.022997096, -0.25580493 0.16018635 -0.02236183, -0.25710216 0.16032594 -0.018336788, -0.25601766 0.16021106 -0.017709032, -0.25468048 0.1600199 -0.02299802, -0.26058695 0.1601806 -0.01541613, -0.26178601 0.16002598 -0.014505818, -0.26080266 0.16002586 -0.014235869, -0.25467637 0.16001847 -0.023010477, -0.25581852 0.16018744 -0.022364512, -0.2597799 0.1601806 -0.015340433, -0.25708976 0.16032541 -0.018342867, -0.25467077 0.1600168 -0.023023859, -0.25582334 0.16018796 -0.022365257, -0.25583246 0.16018882 -0.022365853, -0.25601766 0.16021189 -0.017723069, -0.25466719 0.1600159 -0.023030624, -0.25707772 0.16032496 -0.018350169, -0.2560176 0.16021198 -0.017724648, -0.25973466 0.1603241 -0.016844735, -0.25974813 0.16021337 -0.015637383, -0.25973454 0.16021296 -0.015633836, -0.25973549 0.16032413 -0.016844377, -0.25963876 0.16000544 -0.014001325, -0.25963834 0.16000403 -0.013991222, -0.25694659 0.15969726 -0.012711987, -0.25707176 0.16032469 -0.01835455, -0.25963905 0.16000609 -0.014005288, -0.25972137 0.16032434 -0.01684846, -0.25973144 0.16021279 -0.015632734, -0.25971362 0.16021198 -0.015625581, -0.25601503 0.16021287 -0.017745242, -0.25964305 0.16000941 -0.01402761, -0.25974837 0.1603239 -0.016842052, -0.25975445 0.16021347 -0.015638575, -0.25976208 0.16021359 -0.015639558, -0.25247225 0.15969777 -0.022794679, -0.26136848 0.16018052 -0.015630856, -0.2570602 0.16032426 -0.018364295, -0.2597023 0.16032496 -0.016856536, -0.25601164 0.16021335 -0.017758772, -0.25391373 0.15998185 -0.018053457, -0.25444409 0.15998179 -0.016882196, -0.25302038 0.1596975 -0.016048297, -0.25231192 0.15969755 -0.017644808, -0.25716206 0.1603308 -0.021622851, -0.25715896 0.16033056 -0.021623328, -0.25582942 0.16018558 -0.017571136, -0.25471744 0.16001907 -0.016915724, -0.25472119 0.16002078 -0.016931191, -0.25717285 0.16033149 -0.021621272, -0.25718662 0.16033258 -0.021617755, -0.25719616 0.16033331 -0.021614507, -0.25720754 0.16033417 -0.021609709, -0.25722 0.16033527 -0.021603003, -0.25722751 0.16033584 -0.021598294, -0.25970075 0.16032514 -0.016857281, -0.25970122 0.16021132 -0.015618667, -0.25723174 0.16033623 -0.021595404, -0.25724885 0.16033778 -0.02158083, -0.25725415 0.16033846 -0.021575347, -0.25725839 0.16033885 -0.021570459, -0.25726697 0.16033977 -0.021559164, -0.25727466 0.16034067 -0.021546766, -0.25727829 0.16034119 -0.021539703, -0.25728378 0.16034195 -0.021526828, -0.25728789 0.16034271 -0.021513984, -0.25728819 0.16034278 -0.021513388, -0.25729242 0.16034389 -0.021491215, -0.25729325 0.16034435 -0.021479264, -0.25729331 0.16034441 -0.021477237, -0.25729296 0.16034493 -0.021463171, -0.25729027 0.16034541 -0.021444038, -0.2597706 0.1603238 -0.016840443, -0.25977793 0.16021359 -0.015640602, -0.25728962 0.16034546 -0.021440998, -0.25728586 0.16034576 -0.021427259, -0.25728378 0.16034584 -0.021421388, -0.26053295 0.16021363 -0.015711412, -0.25968859 0.16032553 -0.016864285, -0.25969943 0.16021115 -0.015617773, -0.25968954 0.16021043 -0.015610799, -0.2558417 0.16018659 -0.017568454, -0.25471297 0.16001764 -0.016902491, -0.25327876 0.15969788 -0.024343982, -0.25445381 0.15998462 -0.023083284, -0.254437 0.15998338 -0.023070589, -0.25445482 0.15998471 -0.023083881, -0.25446692 0.15998569 -0.023090795, -0.2544795 0.15998691 -0.023096845, -0.25705037 0.16032407 -0.01837422, -0.2544854 0.15998748 -0.02309911, -0.25450066 0.15998912 -0.02310361, -0.25451443 0.15999076 -0.023106322, -0.25451973 0.15999135 -0.023107067, -0.25452814 0.1599924 -0.023107752, -0.25601146 0.16021335 -0.017759457, -0.25705001 0.16032402 -0.018374458, -0.2596772 0.16032621 -0.016872332, -0.25713655 0.16032903 -0.021623984, -0.25585493 0.160191 -0.022365287, -0.25585851 0.16019128 -0.022364959, -0.25600711 0.16021362 -0.017771944, -0.25586882 0.1601924 -0.022363231, -0.2608566 0.15998158 -0.013940707, -0.26209649 0.15969718 -0.01255165, -0.26038232 0.1596972 -0.012216076, -0.25588241 0.16019386 -0.022359923, -0.25589254 0.16019501 -0.022356316, -0.25590345 0.16019639 -0.022351697, -0.25704148 0.16032395 -0.018385187, -0.25591591 0.16019782 -0.0223452, -0.25978932 0.1599817 -0.013840541, -0.25592378 0.1601989 -0.022340313, -0.25592777 0.1601994 -0.022337452, -0.25594494 0.16020188 -0.022322938, -0.25595042 0.16020271 -0.022317395, -0.25595465 0.16020341 -0.022312507, -0.25596312 0.16020477 -0.022301212, -0.25599727 0.16021386 -0.017792001, -0.25462356 0.16000661 -0.023079589, -0.25462011 0.16000602 -0.023082063, -0.25464097 0.16000998 -0.023065105, -0.25464675 0.16001119 -0.023059115, -0.25465068 0.16001201 -0.023054555, -0.25465921 0.16001391 -0.023043349, -0.25597003 0.16021408 -0.02214177, -0.25701299 0.16032395 -0.021548405, -0.2544097 0.15969798 -0.025674924, -0.25455055 0.15999527 -0.023107156, -0.2545549 0.15999591 -0.02310662, -0.25967285 0.16032639 -0.016875789, -0.25967249 0.16020876 -0.015596196, -0.25584325 0.16018665 -0.017568216, -0.25456449 0.15999724 -0.023105189, -0.25457802 0.15999918 -0.023101941, -0.25458893 0.16000083 -0.023098305, -0.26189032 0.15998167 -0.014224753, -0.25459918 0.16000248 -0.023093924, -0.2546117 0.16000454 -0.023087308, -0.25580809 0.16018394 -0.017578498, -0.25472215 0.16002138 -0.01693739, -0.25932112 0.1598382 -0.012971982, -0.25863656 0.1596972 -0.012270436, -0.25597718 0.16021398 -0.022155985, -0.25976726 0.15998182 -0.013842091, -0.25703266 0.16032383 -0.018398538, -0.25975403 0.15998223 -0.013844594, -0.25975367 0.15998229 -0.013844594, -0.25974032 0.15998277 -0.013848498, -0.25702545 0.1603241 -0.021566913, -0.25972083 0.15998408 -0.013856515, -0.25971994 0.15998414 -0.013857111, -0.2547234 0.16002256 -0.016951337, -0.25970778 0.15998513 -0.013864025, -0.25969651 0.15998632 -0.013871923, -0.25969133 0.15998691 -0.013876215, -0.25967994 0.15998861 -0.013887033, -0.25585726 0.1601879 -0.017566487, -0.25471082 0.16001692 -0.016897425, -0.25967082 0.15999013 -0.013897404, -0.25966057 0.16032726 -0.01688759, -0.2596719 0.16020869 -0.015595809, -0.25966296 0.16020769 -0.015585646, -0.25966725 0.15999079 -0.013901934, -0.25562218 0.16021384 -0.018620268, -0.25470725 0.16001597 -0.016889915, -0.25966266 0.15999177 -0.01390861, -0.25965187 0.15999469 -0.013928309, -0.25965002 0.15999538 -0.013932541, -0.25964662 0.1599966 -0.013941392, -0.25964269 0.15999857 -0.013954774, -0.25964037 0.16000029 -0.013966188, -0.25963894 0.1600019 -0.013977155, -0.25974408 0.16018102 -0.015344515, -0.25975767 0.16002545 -0.014137283, -0.25974402 0.16002497 -0.014133826, -0.25735685 0.16021085 -0.016325817, -0.25963792 0.16020286 -0.015541539, -0.2596359 0.16020218 -0.015535817, -0.25964329 0.16020423 -0.015554681, -0.25965044 0.16020569 -0.015567794, -0.25598016 0.16021395 -0.022163227, -0.25469556 0.16001296 -0.016870752, -0.25469294 0.16001236 -0.016867176, -0.2546868 0.16001093 -0.016859785, -0.25539729 0.15969726 -0.013518319, -0.25467721 0.16000906 -0.016849622, -0.25974467 0.160181 -0.015344486, -0.25406632 0.15969743 -0.014649525, -0.25467297 0.16000822 -0.016845718, -0.25726494 0.16033736 -0.01836507, -0.25962457 0.1603376 -0.017028466, -0.25973073 0.16018152 -0.015348569, -0.25587687 0.16018982 -0.017566249, -0.25963274 0.16033038 -0.016929403, -0.25964335 0.16032892 -0.016909614, -0.25963143 0.16033068 -0.016932234, -0.25962761 0.16033137 -0.016942397, -0.25962368 0.16033226 -0.016955987, -0.25962165 0.1603331 -0.016966209, -0.25962016 0.1603339 -0.01697816, -0.25961962 0.16033497 -0.016992226, -0.25961998 0.1603356 -0.017001286, -0.25579545 0.16018304 -0.017584696, -0.2596204 0.16033602 -0.017006174, -0.26084676 0.16032383 -0.017037258, -0.25964531 0.16001055 -0.014035687, -0.25363865 0.15998198 -0.019309387, -0.25197646 0.15969768 -0.019359007, -0.25964722 0.16001144 -0.01404129, -0.25722292 0.1603336 -0.018337026, -0.25723812 0.16033489 -0.018344715, -0.25598219 0.16021377 -0.022169128, -0.25965258 0.16001339 -0.014054403, -0.25720569 0.16033229 -0.018330708, -0.25974074 0.16002482 -0.014132842, -0.2597231 0.16002375 -0.01412572, -0.25720176 0.16033199 -0.018329516, -0.25965145 0.16032806 -0.01689814, -0.25718799 0.16033104 -0.018326506, -0.25472334 0.1600236 -0.016965166, -0.25717404 0.16033013 -0.018324748, -0.25717112 0.16032994 -0.018324479, -0.25703397 0.16032432 -0.021576777, -0.25715145 0.16032863 -0.018324748, -0.25703463 0.16032434 -0.021577463, -0.25713745 0.16032782 -0.018326327, -0.2559289 0.1601954 -0.017579183, -0.25594369 0.16019727 -0.017586634, -0.25591144 0.16019347 -0.017572567, -0.25590768 0.16019303 -0.017571464, -0.25975779 0.16018079 -0.015342012, -0.25589392 0.16019148 -0.017568365, -0.25976375 0.16002563 -0.014138564, -0.25587991 0.16019011 -0.017566696, -0.2597715 0.16002578 -0.014139548, -0.25964221 0.16019037 -0.015429005, -0.25726178 0.16033697 -0.018361971, -0.25600699 0.16020742 -0.017660156, -0.25964066 0.16019082 -0.015432373, -0.25964871 0.16032827 -0.016901597, -0.25965455 0.16020641 -0.015574232, -0.25963697 0.16019183 -0.015441999, -0.25600508 0.16020694 -0.017655656, -0.25963309 0.16019332 -0.015455499, -0.25971153 0.16018239 -0.015356556, -0.2560012 0.16020611 -0.017647311, -0.25963095 0.16019452 -0.015466198, -0.25598595 0.16021341 -0.022182778, -0.25598946 0.16020396 -0.017628297, -0.25962952 0.16019577 -0.015477553, -0.25598738 0.16020364 -0.017625347, -0.2559807 0.16020255 -0.01761736, -0.25704458 0.16032457 -0.021587059, -0.25962898 0.16019732 -0.015491828, -0.25597104 0.16020098 -0.017607227, -0.25962928 0.16019836 -0.015501395, -0.25596735 0.16020048 -0.017603919, -0.25962976 0.1601989 -0.015505895, -0.25963375 0.16020128 -0.015528098, -0.25341913 0.15983887 -0.023048595, -0.25578335 0.1601823 -0.017592207, -0.25441805 0.15998247 -0.023050472, -0.25440565 0.1599822 -0.023032203, -0.25442675 0.15998286 -0.023060545, -0.25442711 0.15998277 -0.023060992, -0.25598666 0.16021334 -0.022186056, -0.25472328 0.16002363 -0.016966596, -0.25971028 0.16018246 -0.015357271, -0.25971076 0.1600228 -0.014118895, -0.25978735 0.16002584 -0.014140621, -0.25727478 0.16033834 -0.018375054, -0.25962666 0.16033822 -0.017035827, -0.25962874 0.16033858 -0.017041847, -0.25598922 0.16021243 -0.022204921, -0.25969806 0.16018319 -0.015364304, -0.25970879 0.16002265 -0.014117822, -0.2596989 0.16002163 -0.014111057, -0.25706097 0.16032523 -0.021599457, -0.25706258 0.16032529 -0.0216005, -0.25577757 0.16018206 -0.017596468, -0.25968668 0.16018412 -0.015372172, -0.25472072 0.16002488 -0.016987219, -0.25728169 0.1603391 -0.018383577, -0.2559897 0.16021183 -0.022219047, -0.25707474 0.16032577 -0.021607473, -0.25968209 0.1601845 -0.015375957, -0.25968185 0.16001943 -0.014096126, -0.25728348 0.16033922 -0.018386021, -0.25963411 0.1603395 -0.01705493, -0.25967017 0.16018578 -0.015387282, -0.25598958 0.16021168 -0.022221223, -0.25968125 0.1600194 -0.01409553, -0.25967231 0.16001791 -0.014085636, -0.25598869 0.16021089 -0.022233173, -0.2570875 0.16032641 -0.021613374, -0.25709245 0.16032659 -0.021615222, -0.25576583 0.1601814 -0.017606124, -0.25729528 0.16034073 -0.018405125, -0.25964114 0.16034043 -0.017067924, -0.25964531 0.16034098 -0.017074481, -0.25471726 0.16002545 -0.017000809, -0.25966111 0.16018704 -0.015397802, -0.25965807 0.16018745 -0.015401736, -0.25966385 0.16001624 -0.014074221, -0.25598451 0.16020927 -0.022255138, -0.2571089 0.16032755 -0.02162011, -0.25729957 0.16034135 -0.018414006, -0.25965294 0.1601882 -0.015409216, -0.2596598 0.16001529 -0.014067635, -0.25730106 0.16034153 -0.018417969, -0.25965372 0.16034183 -0.017085686, -0.25598428 0.16020928 -0.02225621, -0.25598016 0.16020821 -0.022268817, -0.25712261 0.16032828 -0.021622673, -0.25575599 0.16018109 -0.017616168, -0.25730589 0.1603424 -0.018430993, -0.25966266 0.16034251 -0.017095909, -0.25966325 0.1603426 -0.017096058, -0.2547172 0.16002554 -0.017001256, -0.25454751 0.15998957 -0.016810313, -0.25453511 0.15998822 -0.016812935, -0.25575581 0.16018111 -0.017616406, -0.254549 0.15998979 -0.016810074, -0.25597456 0.16020688 -0.022281751, -0.25712684 0.16032845 -0.021623299, -0.25451383 0.15998599 -0.016820446, -0.25471273 0.16002579 -0.017013803, -0.25730982 0.16034321 -0.018447682, -0.25968012 0.16034359 -0.017111078, -0.25574717 0.1601809 -0.017627135, -0.25470296 0.16002612 -0.017033681, -0.25456306 0.15999144 -0.016808495, -0.25450096 0.15998483 -0.016826764, -0.25458261 0.15999398 -0.016808286, -0.25448897 0.15998389 -0.016834006, -0.2573106 0.16034341 -0.018452927, -0.25597098 0.16020626 -0.022288725, -0.25458577 0.15999427 -0.016808495, -0.2539368 0.16002625 -0.019342467, -0.25533757 0.16018084 -0.018525854, -0.25419858 0.16002622 -0.01814796, -0.25448337 0.15998349 -0.016838089, -0.25573841 0.16018072 -0.017640397, -0.25731197 0.16034406 -0.018466845, -0.25969037 0.16034415 -0.017117843, -0.2545999 0.1599963 -0.016810313, -0.25447145 0.15998274 -0.016848072, -0.25461385 0.15999827 -0.016813561, -0.25461718 0.15999874 -0.016814455, -0.25446156 0.15998223 -0.016858116, -0.25445268 0.15998188 -0.016868964, -0.2603173 0.16032377 -0.016891822, -0.26126406 0.16021371 -0.01591216, -0.25463513 0.16000155 -0.016821399, -0.25464931 0.16000387 -0.016828641, -0.25466636 0.16002646 -0.022883609, -0.25570938 0.16018111 -0.022290245, -0.25467339 0.16002634 -0.022897795, -0.25572178 0.16018131 -0.022308663, -0.25676116 0.16032389 -0.01899825, -0.25512943 0.16018087 -0.019475445, -0.25467643 0.16002616 -0.022905186, -0.2546784 0.16002606 -0.022910908, -0.25573042 0.16018158 -0.022318646, -0.2557309 0.16018155 -0.022319332, -0.25542757 0.16021389 -0.019508556, -0.26074228 0.16034573 -0.017318413, -0.26026329 0.16034576 -0.017186925, -0.25976875 0.16034576 -0.017140493, -0.25975254 0.16034567 -0.01713945, -0.25468221 0.16002551 -0.022924557, -0.25574085 0.16018194 -0.022328809, -0.25662026 0.16032396 -0.019641563, -0.25468305 0.16002539 -0.022928014, -0.25468555 0.16002432 -0.022946581, -0.25575736 0.16018283 -0.022341356, -0.25575867 0.16018286 -0.022342458, -0.2596918 0.16034418 -0.017118827, -0.25970414 0.16034466 -0.017125532, -0.25972214 0.16034517 -0.017132804, -0.25601164 0.16020858 -0.017673388, -0.25972512 0.16034535 -0.017133728, -0.25973871 0.16034552 -0.017137334, -0.25974503 0.16034558 -0.017138585, -0.25731191 0.16034472 -0.018482849, -0.25730935 0.16034526 -0.018503085, -0.25731203 0.16034459 -0.018481031, -0.25713584 0.16032773 -0.018326595, -0.25468597 0.16002338 -0.022960737, -0.25730142 0.16034576 -0.018529996, -0.25729159 0.16034579 -0.018550053, -0.25730583 0.16034552 -0.018517658, -0.25730601 0.16034558 -0.018516675, -0.25704584 0.1603459 -0.019092813, -0.25691834 0.16034597 -0.019674793, -0.25691447 0.16034594 -0.020270661, -0.257238 0.15894476 -0.018344894, -0.25726488 0.15894482 -0.01836507, -0.25728658 0.15894474 -0.01839067, -0.25730214 0.15894476 -0.018420383, -0.2573106 0.15894474 -0.018452778, -0.25731161 0.15894477 -0.018486306, -0.25730518 0.15894482 -0.018519327, -0.25729164 0.15894479 -0.018550053, -0.25464931 0.15894467 -0.016828671, -0.25467625 0.15894474 -0.016848668, -0.25469801 0.1589447 -0.016874298, -0.25471351 0.15894474 -0.016904131, -0.25472203 0.15894476 -0.016936526, -0.25472304 0.15894473 -0.016970202, -0.2547166 0.15894473 -0.017003074, -0.2547029 0.1589447 -0.017033741, -0.25594369 0.1589447 -0.017586663, -0.25597063 0.15894473 -0.01760678, -0.25599232 0.15894476 -0.01763241, -0.25600782 0.1589447 -0.017662182, -0.25601634 0.15894473 -0.017694727, -0.25601736 0.1589447 -0.017728254, -0.25601098 0.1589448 -0.017761067, -0.25599721 0.15894473 -0.017791882, -0.25978735 0.15894446 -0.014140621, -0.2608026 0.15894446 -0.014235869, -0.26178595 0.15894452 -0.014505967, -0.26270744 0.15894453 -0.014942631, -0.26053295 0.15894455 -0.015711412, -0.25977799 0.15894455 -0.015640602, -0.26126412 0.15894464 -0.015912279, -0.26194921 0.15894455 -0.016236916, -0.26026323 0.1589447 -0.017187014, -0.25976864 0.15894467 -0.017140642, -0.26074234 0.1589447 -0.017318502, -0.26119116 0.15894467 -0.017531291, -0.25977054 0.1589447 -0.016840562, -0.26031718 0.1589447 -0.016891822, -0.2608467 0.15894467 -0.017037287, -0.25962076 0.15894467 -0.016971633, -0.25962058 0.1589447 -0.017007723, -0.2596297 0.15894471 -0.016936526, -0.25964668 0.15894471 -0.016904578, -0.25973281 0.15894473 -0.017135993, -0.25967082 0.15894467 -0.016877756, -0.25969902 0.15894461 -0.017122969, -0.25970075 0.15894473 -0.016857311, -0.2597346 0.15894471 -0.016844735, -0.25966945 0.15894471 -0.017102227, -0.25964561 0.1589447 -0.017074957, -0.25962898 0.15894471 -0.017043009, -0.26159647 0.15894473 -0.017818913, -0.26194552 0.1589448 -0.018172249, -0.26222798 0.1589448 -0.018581018, -0.26241615 0.15894476 -0.018645301, -0.26244757 0.15894477 -0.018627331, -0.2623814 0.15894479 -0.018654987, -0.26250252 0.15894473 -0.018466011, -0.26234522 0.15894476 -0.018656269, -0.26230982 0.15894476 -0.018648759, -0.26250818 0.15894479 -0.018501744, -0.26227728 0.15894474 -0.018633083, -0.26224944 0.15894479 -0.018610075, -0.26250497 0.15894479 -0.018537834, -0.2624934 0.15894474 -0.018572077, -0.26247385 0.15894476 -0.018602297, -0.26207843 0.15894485 -0.022112772, -0.26158634 0.15894496 -0.022550568, -0.26101401 0.15894496 -0.022876069, -0.26038638 0.15894493 -0.023075655, -0.25973114 0.15894505 -0.023140594, -0.26221004 0.15894488 -0.021430984, -0.26223019 0.1589449 -0.021403983, -0.2622557 0.15894488 -0.021382347, -0.26228556 0.15894493 -0.021366879, -0.2623181 0.1589449 -0.021358386, -0.2623516 0.15894489 -0.021357194, -0.26238456 0.15894489 -0.02136369, -0.26185682 0.15894493 -0.021910682, -0.26141158 0.15894496 -0.022306696, -0.26089373 0.15894502 -0.022601381, -0.26032588 0.15894496 -0.022781894, -0.25973293 0.15894493 -0.022840515, -0.25958326 0.15894505 -0.022971466, -0.25958309 0.15894508 -0.023007616, -0.25959221 0.15894508 -0.022936478, -0.25969526 0.15894502 -0.023135945, -0.25960913 0.15894514 -0.022904411, -0.25963333 0.15894505 -0.022877529, -0.25966153 0.15894505 -0.023123011, -0.25966325 0.15894508 -0.022857204, -0.25969699 0.15894499 -0.022844568, -0.25963196 0.15894511 -0.023102, -0.25960806 0.15894505 -0.02307494, -0.25959143 0.15894508 -0.023042753, -0.26429531 0.15894499 -0.024134174, -0.26333436 0.15894499 -0.024988517, -0.26221702 0.15894517 -0.025624409, -0.26099184 0.15894517 -0.026013955, -0.25971231 0.15894517 -0.026140556, -0.26479873 0.1589451 -0.022947177, -0.26481867 0.1589449 -0.022920415, -0.26484439 0.15894502 -0.02289854, -0.26487425 0.15894502 -0.022882923, -0.26490659 0.15894493 -0.022874489, -0.26494023 0.15894496 -0.022873506, -0.26497319 0.15894499 -0.022879824, -0.26407352 0.15894493 -0.023932055, -0.26315966 0.15894507 -0.024744585, -0.26209673 0.1589452 -0.025349572, -0.26093128 0.15894517 -0.025720254, -0.25971428 0.15894514 -0.025840387, -0.25956425 0.1589452 -0.026007637, -0.25956455 0.15894523 -0.025971368, -0.25957337 0.15894517 -0.02593638, -0.25959042 0.15894517 -0.025904283, -0.25967649 0.15894517 -0.026135817, -0.25964281 0.1589452 -0.026122674, -0.25961468 0.15894523 -0.025877461, -0.25964448 0.15894514 -0.025857225, -0.25961301 0.15894514 -0.026102021, -0.25967839 0.1589452 -0.02584444, -0.25958928 0.1589452 -0.026074901, -0.25957271 0.15894517 -0.026042774, -0.26318696 0.15894505 -0.023123458, -0.26246038 0.15894498 -0.023769453, -0.26161554 0.15894505 -0.024250284, -0.26068917 0.15894511 -0.024544969, -0.25972179 0.15894514 -0.024640545, -0.26350448 0.15894505 -0.022189036, -0.2635245 0.15894496 -0.022162214, -0.26355013 0.15894489 -0.022140399, -0.26357988 0.15894493 -0.022124872, -0.26361242 0.15894492 -0.022116438, -0.26364598 0.15894498 -0.022115186, -0.26367894 0.15894498 -0.022121772, -0.26296529 0.15894505 -0.022921279, -0.26228568 0.15894502 -0.02352564, -0.26149514 0.15894496 -0.023975477, -0.26062855 0.15894502 -0.024251178, -0.25972357 0.15894513 -0.024340525, -0.25957361 0.15894513 -0.024507627, -0.25957397 0.15894517 -0.024471477, -0.25958273 0.15894508 -0.024436519, -0.25959978 0.15894514 -0.024404541, -0.25968584 0.15894508 -0.024635956, -0.25962386 0.15894513 -0.02437754, -0.25965217 0.15894513 -0.024622753, -0.25965378 0.15894513 -0.024357334, -0.25962254 0.15894508 -0.02460213, -0.25968769 0.15894514 -0.024344578, -0.25959876 0.15894517 -0.02457495, -0.25958207 0.15894514 -0.024542674, -0.25977996 0.15894467 -0.015340552, -0.26058683 0.15894458 -0.015416399, -0.26136848 0.1589445 -0.015630946, -0.25963002 0.15894462 -0.015507713, -0.25963023 0.15894464 -0.015471682, -0.25963905 0.15894461 -0.015436396, -0.25965604 0.15894461 -0.015404716, -0.25974217 0.15894461 -0.015636101, -0.25968018 0.15894458 -0.015377745, -0.25970837 0.15894456 -0.015623018, -0.2597101 0.15894458 -0.01535739, -0.25974396 0.15894461 -0.015344754, -0.25967881 0.15894461 -0.015602335, -0.25965503 0.15894464 -0.015575066, -0.2596384 0.15894455 -0.015542969, -0.26256773 0.15894461 -0.016675815, -0.26310059 0.15894464 -0.017215416, -0.26353154 0.15894464 -0.017839059, -0.26375124 0.15894462 -0.017885372, -0.26371989 0.15894464 -0.017903253, -0.26368502 0.15894467 -0.017913118, -0.2636489 0.15894474 -0.0179144, -0.26380631 0.15894476 -0.017724052, -0.26361349 0.15894467 -0.017906889, -0.2638118 0.15894467 -0.017759845, -0.26358095 0.15894468 -0.017891154, -0.26355305 0.15894467 -0.017868146, -0.2638087 0.15894461 -0.017795935, -0.26379701 0.15894461 -0.017830059, -0.26377746 0.15894461 -0.017860427, -0.25978932 0.15894452 -0.013840541, -0.26085666 0.15894452 -0.013940707, -0.26189038 0.15894458 -0.014224753, -0.25963929 0.15894449 -0.014007643, -0.25963947 0.15894449 -0.013971671, -0.25964835 0.15894444 -0.013936654, -0.25966546 0.15894449 -0.013904706, -0.25975153 0.15894455 -0.014135942, -0.2596896 0.15894449 -0.013877735, -0.2597194 0.15894446 -0.01385735, -0.25971779 0.15894455 -0.014123067, -0.25975338 0.15894455 -0.013844743, -0.25968817 0.15894452 -0.014102325, -0.25966433 0.15894444 -0.014075145, -0.25964776 0.15894446 -0.014042869, -0.26353911 0.15894453 -0.015532628, -0.26425561 0.15894461 -0.016258344, -0.26483527 0.1589447 -0.01709725, -0.26505497 0.15894467 -0.017143622, -0.26502356 0.15894467 -0.017161384, -0.26498875 0.15894464 -0.017171249, -0.26495266 0.15894461 -0.017172441, -0.26510993 0.15894465 -0.016982302, -0.26511565 0.15894467 -0.017017856, -0.26491725 0.15894461 -0.01716508, -0.26488468 0.15894467 -0.017149433, -0.26511237 0.15894465 -0.017053977, -0.26485679 0.15894467 -0.017126337, -0.26510081 0.15894467 -0.017088309, -0.2650812 0.15894464 -0.017118677, -0.25570932 0.15894505 -0.022290364, -0.25531951 0.15894493 -0.021399692, -0.25512341 0.15894498 -0.020447746, -0.25512949 0.15894482 -0.019475594, -0.25533751 0.15894482 -0.018525943, -0.25573847 0.15894476 -0.017640397, -0.25592908 0.15894499 -0.022336617, -0.25589767 0.15894501 -0.02235432, -0.25586292 0.15894511 -0.022364214, -0.25597009 0.15894502 -0.022141919, -0.25582674 0.15894502 -0.022365466, -0.25598404 0.15894499 -0.022175297, -0.25579134 0.15894508 -0.022358045, -0.25598958 0.15894499 -0.022211, -0.25575879 0.15894504 -0.022342458, -0.25573084 0.15894496 -0.022319421, -0.25598648 0.15894499 -0.022246942, -0.25597486 0.1589451 -0.022281244, -0.25595531 0.15894505 -0.022311732, -0.25560549 0.15894496 -0.021308735, -0.25542185 0.15894493 -0.020418182, -0.25542751 0.1589448 -0.019508883, -0.2556223 0.15894479 -0.018620357, -0.25575849 0.15894471 -0.017613426, -0.25578406 0.15894465 -0.01759176, -0.25581393 0.15894465 -0.017576322, -0.25584641 0.1589447 -0.017567769, -0.25588003 0.15894473 -0.017566696, -0.25591293 0.15894476 -0.017573014, -0.25440565 0.1589451 -0.023032203, -0.25389007 0.15894499 -0.021854326, -0.25363067 0.15894498 -0.020595029, -0.25363871 0.15894495 -0.019309446, -0.25391379 0.15894482 -0.018053547, -0.25444409 0.15894473 -0.016882196, -0.25462535 0.15894502 -0.023078397, -0.25459394 0.15894505 -0.023096278, -0.25455919 0.1589451 -0.023106053, -0.25466636 0.15894502 -0.022883847, -0.25452307 0.1589451 -0.023107424, -0.25468031 0.15894505 -0.022916988, -0.2544876 0.15894504 -0.023100004, -0.25445506 0.15894504 -0.023084149, -0.25468597 0.1589451 -0.02295284, -0.25442722 0.1589451 -0.023061141, -0.25468275 0.15894502 -0.022988901, -0.25467107 0.15894504 -0.023023024, -0.25465164 0.15894504 -0.023053572, -0.25417587 0.1589449 -0.021763489, -0.25392917 0.15894495 -0.020565674, -0.25393686 0.15894485 -0.019342676, -0.25419858 0.15894485 -0.01814796, -0.25446424 0.15894467 -0.016855344, -0.25448981 0.15894471 -0.016833529, -0.25451961 0.15894473 -0.016818061, -0.25455204 0.15894461 -0.016809598, -0.25458565 0.15894468 -0.016808644, -0.25461861 0.15894468 -0.016814962, -0.25701305 0.15894502 -0.021548465, -0.256749 0.1589449 -0.020945236, -0.25661609 0.15894493 -0.020300314, -0.2566202 0.15894485 -0.019641653, -0.2567611 0.15894476 -0.018998399, -0.25703272 0.15894476 -0.018398538, -0.2572014 0.15894499 -0.02161257, -0.25723282 0.15894496 -0.021594658, -0.25716653 0.1589449 -0.021622464, -0.25727382 0.15894505 -0.021400109, -0.25713047 0.15894496 -0.021623746, -0.25728777 0.15894496 -0.021433398, -0.25709507 0.15894499 -0.021616146, -0.25729331 0.15894496 -0.02146925, -0.25706246 0.15894493 -0.0216005, -0.25703457 0.1589449 -0.021577522, -0.25729021 0.15894499 -0.021505132, -0.25727859 0.15894496 -0.021539286, -0.25725904 0.15894499 -0.021569714, -0.25703487 0.1589449 -0.020854309, -0.25691471 0.15894496 -0.020270661, -0.25691834 0.15894482 -0.019675031, -0.25704584 0.15894479 -0.019092813, -0.25705275 0.15894476 -0.018371597, -0.25707838 0.15894476 -0.018349782, -0.25710818 0.15894473 -0.018334374, -0.25714073 0.15894476 -0.018325821, -0.25717422 0.1589447 -0.018324777, -0.2572073 0.15894476 -0.018331304, -0.25221679 0.15896913 -0.012122884, -0.2508994 0.15896915 -0.013641104, -0.25261185 0.15897009 -0.028218493, -0.25217125 0.15891351 -0.012075379, -0.25084594 0.15891358 -0.013602838, -0.25215581 0.15887636 -0.012059078, -0.2508277 0.15887651 -0.013589725, -0.25256869 0.15891431 -0.028268114, -0.25379077 0.15896904 -0.010872468, -0.25255415 0.15887728 -0.028285101, -0.25375476 0.15891346 -0.010817394, -0.25122163 0.15896997 -0.026766375, -0.25374249 0.15887636 -0.010798678, -0.25556758 0.15896896 -0.0099325031, -0.25117007 0.1589143 -0.026807413, -0.25115255 0.15887722 -0.02682133, -0.25554243 0.15891337 -0.0098716766, -0.2501218 0.15896991 -0.025083914, -0.25553378 0.15887618 -0.0098510832, -0.25748697 0.15896893 -0.0093351454, -0.25006351 0.15891421 -0.025114611, -0.25004372 0.15887704 -0.02512525, -0.25747338 0.15891325 -0.0092708915, -0.2493498 0.1589698 -0.023227766, -0.25746873 0.15887612 -0.0092489272, -0.24928704 0.15891418 -0.023247346, -0.25948343 0.15896888 -0.0091006607, -0.24926554 0.15887702 -0.023253992, -0.25948182 0.15891322 -0.0090348572, -0.24893218 0.15896976 -0.021261528, -0.25948134 0.15887618 -0.0090124458, -0.24886674 0.15891407 -0.021269247, -0.26148906 0.15896893 -0.0092369169, -0.2488445 0.15887694 -0.021271899, -0.26149955 0.15891328 -0.0091719478, -0.24888265 0.15896951 -0.019251958, -0.26150313 0.15887615 -0.0091498643, -0.24881706 0.15891388 -0.019247457, -0.26343545 0.15896903 -0.0097395033, -0.24879459 0.15887679 -0.019245818, -0.2634578 0.15891331 -0.0096774548, -0.24920343 0.15896946 -0.01726751, -0.26346532 0.15887628 -0.0096563548, -0.24913976 0.15891379 -0.017251119, -0.24911804 0.15887669 -0.017245427, -0.24988344 0.15896934 -0.015375718, -0.24982393 0.15891373 -0.015347824, -0.2498035 0.15887651 -0.015338436, -0.26605085 0.15994358 0.0024094731, -0.25345078 0.1599436 0.0024095327, -0.24893825 0.17494255 0.02203162, -0.24949369 0.17494237 0.023984209, -0.25039852 0.17494231 0.025801197, -0.25162187 0.17494228 0.027421013, -0.25312188 0.17494209 0.028788671, -0.25484785 0.17494208 0.029857025, -0.25674063 0.17494211 0.030590579, -0.25873598 0.17494206 0.030963525, -0.26076582 0.17494202 0.030963525, -0.26276118 0.17494205 0.030590579, -0.26465395 0.174942 0.029857025, -0.26637992 0.17494217 0.028788671, -0.26788017 0.17494221 0.027421013, -0.26910329 0.17494224 0.025801107, -0.27000818 0.17494234 0.023984209, -0.2705636 0.17494243 0.022031799, -0.24710026 0.16034338 0.0086027235, -0.24724559 0.16034336 0.0082194954, -0.24747829 0.16034333 0.0078822523, -0.24778512 0.16034332 0.0076105744, -0.24814795 0.16034342 0.0074200779, -0.24854584 0.16034342 0.0073220581, -0.24895579 0.16034347 0.0073220879, -0.24935368 0.16034344 0.0074200779, -0.24971657 0.16034341 0.0076105744, -0.25002339 0.16034341 0.0078822523, -0.25025609 0.16034332 0.008219704, -0.25040153 0.16034338 0.0086027235, -0.24710028 0.16034219 0.030602768, -0.24724558 0.1603422 0.0302196, -0.2474784 0.1603422 0.029882297, -0.24778512 0.1603422 0.029610619, -0.24814799 0.16034216 0.029420033, -0.24854583 0.16034213 0.029321954, -0.24895573 0.16034216 0.029321954, -0.24935365 0.16034216 0.029420033, -0.24971645 0.1603421 0.029610619, -0.25002328 0.16034214 0.029882297, -0.25025603 0.1603421 0.0302196, -0.25040153 0.1603421 0.030602589, -0.26910028 0.16034201 0.030602917, -0.26924559 0.16034201 0.030219659, -0.26947841 0.16034211 0.029882416, -0.26978514 0.16034195 0.029610619, -0.27014795 0.16034195 0.029420033, -0.27054587 0.16034198 0.029321805, -0.27095583 0.1603421 0.029321954, -0.27135369 0.16034208 0.029420033, -0.27171651 0.16034207 0.029610619, -0.27202335 0.16034207 0.029882297, -0.27225611 0.16034192 0.030219451, -0.27240154 0.16034201 0.030602768, -0.26910025 0.16034323 0.0086027235, -0.26924554 0.16034326 0.0082194954, -0.26947841 0.16034336 0.0078823417, -0.2697852 0.16034324 0.0076105744, -0.27014795 0.16034329 0.0074200779, -0.2705459 0.16034329 0.0073222071, -0.27095571 0.16034332 0.0073220581, -0.27135357 0.16034326 0.0074200779, -0.27171656 0.16034323 0.0076105744, -0.27202323 0.16034317 0.0078822523, -0.27225605 0.16034317 0.0082194954, -0.27240142 0.16034314 0.0086026341, -0.13570079 0.15544522 -0.011490867, -0.15320075 0.15544504 -0.011490688, -0.13375078 0.15644585 -0.022490725, -0.15515077 0.15644568 -0.022490725, -0.15515079 0.15644318 0.022509322, -0.13375071 0.15644334 0.022509322, -0.15515083 0.15794322 0.022509322, -0.15515079 0.15794572 -0.022490576, -0.1337508 0.15794335 0.0225095, -0.13375069 0.1579458 -0.022490457, -0.13425076 0.15844569 -0.021990463, -0.13425077 0.15844335 0.022009626, -0.15465081 0.15844563 -0.021990463, -0.15465076 0.15844321 0.022009626, 0.098204963 0.14787775 -0.14876248, 0.083585195 0.12525804 -0.19400816, 0.090602748 0.12525809 -0.19400807, 0.094696261 0.13218781 -0.18014674, 0.10756178 0.1321879 -0.18014674, 0.11165536 0.12525822 -0.19400807, 0.11867292 0.12525827 -0.19400816, 0.10405289 0.14787778 -0.14876248, 0.10142133 0.14264776 -0.15922387, 0.10083655 0.14264774 -0.15922387, 0.096158259 0.13467206 -0.17517762, 0.10609984 0.13467215 -0.17517777, 0.10609975 0.13511936 -0.17540114, 0.096158303 0.13511926 -0.17540114, 0.10142134 0.14309503 -0.15944736, 0.10083661 0.14309503 -0.15944751, 0.048789792 0.13650228 -0.17151608, 0.048789855 0.12499632 -0.19453125, 0.053760625 0.12499626 -0.19453125, 0.054637782 0.12682685 -0.19086964, 0.055624854 0.12630361 -0.19191648, 0.056828946 0.12588003 -0.1927637, 0.058630947 0.12545101 -0.1936218, 0.060752902 0.12514061 -0.19424276, 0.062218778 0.12503257 -0.19445886, 0.063702196 0.12499632 -0.19453125, 0.065638676 0.12506029 -0.19440357, 0.067528151 0.12526254 -0.19399895, 0.069402404 0.12560904 -0.19330598, 0.071344197 0.12614432 -0.19223537, 0.073288761 0.12688172 -0.19076018, 0.075140007 0.12781557 -0.18889235, 0.076399386 0.12868741 -0.1871482, 0.077484094 0.12974678 -0.18502928, 0.07837034 0.13100709 -0.18250833, 0.078994565 0.13243946 -0.17964308, 0.079380237 0.13407448 -0.17637257, 0.079491556 0.13571799 -0.17308538, 0.079351731 0.13785172 -0.16881727, 0.078914702 0.13976294 -0.16499422, 0.078252338 0.14137028 -0.16177891, 0.077318251 0.14281259 -0.15889405, 0.076144263 0.14406259 -0.15639372, 0.074743435 0.14511067 -0.15429704, 0.073192164 0.14597014 -0.15257777, 0.071589522 0.1466217 -0.15127461, 0.069709949 0.14717871 -0.15016042, 0.067730576 0.14755867 -0.14940055, 0.065511093 0.14779696 -0.14892365, 0.064317755 0.14785412 -0.14880921, 0.063117146 0.1478776 -0.14876248, 0.060934044 0.14781547 -0.14888673, 0.058796138 0.14760748 -0.14930288, 0.056729455 0.14723338 -0.15005095, 0.055039365 0.14675891 -0.1509998, 0.053442664 0.14610903 -0.1522999, 0.052035801 0.14530781 -0.15390255, 0.050833408 0.14438254 -0.15575354, 0.049923919 0.14336324 -0.15779217, 0.049246777 0.14220238 -0.1601146, 0.048893578 0.14105682 -0.16240571, 0.04878974 0.1399018 -0.16471623, 0.055222478 0.13990185 -0.16471623, 0.055338986 0.14112747 -0.16226445, 0.055749733 0.14234009 -0.1598389, 0.05641643 0.14329877 -0.15792133, 0.056853075 0.14371085 -0.15709706, 0.057336397 0.1440669 -0.15638478, 0.058451254 0.14464161 -0.15523522, 0.059670422 0.14502785 -0.15446259, 0.061057419 0.14527532 -0.15396778, 0.062077999 0.14536788 -0.15378265, 0.063117176 0.14539334 -0.15373175, 0.064690903 0.14532754 -0.15386339, 0.066194803 0.14511028 -0.15429787, 0.067547381 0.14474556 -0.15502743, 0.068687864 0.144256 -0.15600671, 0.069602795 0.14367932 -0.15716012, 0.070532635 0.14283353 -0.15885206, 0.071264841 0.14180142 -0.16091667, 0.071857966 0.1404382 -0.16364332, 0.072307564 0.13852799 -0.16746436, 0.072438948 0.13725425 -0.17001213, 0.07247401 0.13597935 -0.17256226, 0.07236632 0.13422208 -0.17607738, 0.071969382 0.13247317 -0.17957573, 0.071371451 0.1311636 -0.18219514, 0.070538983 0.13010031 -0.1843221, 0.069558002 0.12931633 -0.1858903, 0.068239391 0.12860368 -0.1873156, 0.066793256 0.12804937 -0.18842433, 0.065368347 0.12770304 -0.18911733, 0.064120002 0.12753691 -0.18944944, 0.062824942 0.12748067 -0.1895621, 0.061118577 0.12754986 -0.18942355, 0.059484251 0.12777841 -0.18896626, 0.058307081 0.12808548 -0.18835209, 0.057352703 0.12845568 -0.18761171, 0.056550812 0.12889197 -0.18673871, 0.055924613 0.12938252 -0.18575786, 0.055325374 0.13008595 -0.18435051, 0.05484803 0.13108906 -0.18234406, 0.054685008 0.13183296 -0.180856, 0.054637775 0.1325798 -0.17936222, 0.054637767 0.134018 -0.17648526, 0.063702099 0.13401809 -0.17648526, 0.063702069 0.13650233 -0.17151608, 0.02305872 0.14761579 -0.1492856, 0.023058876 0.12525764 -0.19400816, 0.029784009 0.12525772 -0.19400816, 0.029783826 0.14761595 -0.1492856, -0.026648741 0.12774146 -0.18903889, -0.026648708 0.12525731 -0.19400816, 0.0037605725 0.12525749 -0.19400816, 0.0037605092 0.14761567 -0.1492856, -0.0029646419 0.14761564 -0.1492856, -0.0029645767 0.12774169 -0.18903889, -0.064075775 0.12774137 -0.18903889, -0.064075723 0.12525713 -0.19400816, -0.034251101 0.12525731 -0.19400807, -0.034251183 0.1476154 -0.1492856, -0.062613785 0.14761525 -0.1492856, -0.06261377 0.14513102 -0.15425472, -0.04097636 0.14513114 -0.15425472, -0.040976401 0.13820145 -0.16811614, -0.060859445 0.13820133 -0.16811614, -0.060859386 0.13571708 -0.17308526, -0.040976375 0.13571724 -0.17308538, -0.040976338 0.1277415 -0.18903889, -0.10267219 0.12525687 -0.19400807, -0.088929668 0.13702446 -0.17047001, -0.095654681 0.12525693 -0.19400807, -0.085713193 0.13440944 -0.17570062, -0.075771615 0.12525705 -0.19400807, -0.068754047 0.12525707 -0.19400807, -0.082496852 0.13702449 -0.17046987, -0.070216157 0.14761515 -0.1492856, -0.077233799 0.14761522 -0.1492856, -0.085713193 0.13950861 -0.16550075, -0.094192781 0.147615 -0.1492856, -0.10121033 0.14761502 -0.1492856, -0.10839176 0.14178894 0.16092049, -0.11523376 0.14186725 0.16076337, -0.10843252 0.14440227 0.15569411, -0.10856713 0.1462615 0.15197603, -0.1048829 0.14626151 0.15197603, -0.10501754 0.14440225 0.15569426, -0.10505834 0.14178894 0.16092025, -0.099795163 0.14186741 0.16076316, -0.099795215 0.14045496 0.16358756, -0.10505836 0.14053336 0.16343068, -0.1050584 0.13770865 0.16907977, -0.10413549 0.13815878 0.16817926, -0.1031285 0.13857178 0.16735362, -0.10041057 0.13687207 0.17075263, -0.097865306 0.13511929 0.17425765, -0.10049689 0.13425599 0.17598395, -0.10237551 0.13569376 0.1731088, -0.10367997 0.13655606 0.17138474, -0.10505837 0.13739482 0.16970725, -0.10505836 0.13150966 0.18147589, -0.10488276 0.12813555 0.18822326, -0.10856698 0.12813552 0.1882232, -0.10839163 0.13150959 0.18147574, -0.10839161 0.13676693 0.17096256, -0.10993721 0.13516326 0.17416961, -0.11176417 0.13361931 0.17725693, -0.11383025 0.13213728 0.18022035, -0.11491063 0.13271032 0.17907478, -0.11572281 0.13300702 0.1784815, -0.1166373 0.13323592 0.17802371, -0.11486857 0.13433015 0.17583539, -0.113322 0.13548975 0.17351647, -0.11171305 0.13700116 0.17049418, -0.10987378 0.1392203 0.1660565, -0.1094205 0.13986957 0.16475804, -0.10909344 0.14053328 0.16343068, -0.11523383 0.14045483 0.16358779, 0.036696233 0.12829342 0.18790905, 0.033713765 0.1282934 0.1879092, 0.033713758 0.1297057 0.18508483, 0.026169835 0.12970576 0.18508483, 0.026169864 0.12821493 0.18806617, 0.023011995 0.12821484 0.18806617, 0.023134844 0.12956819 0.18535997, 0.023187445 0.13151041 0.18147574, 0.023146909 0.13315654 0.17818429, 0.023011982 0.13449228 0.17551304, 0.036696184 0.13449237 0.17551304, 0.03657357 0.13321686 0.17806353, 0.036520697 0.13135368 0.1817895, 0.036573075 0.12956274 0.18537079, 0.026169889 0.1308043 0.18288802, 0.026169829 0.13331532 0.1778668, 0.033713814 0.13080432 0.18288802, 0.033713713 0.13331532 0.1778668, 0.033713754 0.13125153 0.18311156, 0.026169825 0.13125154 0.18311177, 0.026169885 0.13376245 0.17809062, 0.033713825 0.13376243 0.17809047, 0.055292726 0.12821501 0.18806617, 0.052134752 0.1282151 0.18806617, 0.052134752 0.12970591 0.18508472, 0.043713808 0.12970571 0.18508472, 0.043713734 0.12829351 0.1879092, 0.040731322 0.12829345 0.18790905, 0.040906716 0.13151054 0.18147574, 0.040731311 0.13449234 0.17551304, 0.055292703 0.13449246 0.17551304, 0.055157896 0.13313296 0.17823173, 0.055117261 0.13127527 0.18194641, 0.055158146 0.12948763 0.18552147, 0.043713778 0.13080443 0.18288802, 0.043713666 0.13331546 0.1778668, 0.052134812 0.13080448 0.18288802, 0.052134767 0.13331544 0.1778668, 0.05213473 0.13125166 0.18311177, 0.043713711 0.13125163 0.18311177, 0.043713696 0.13376254 0.17809047, 0.05213476 0.1337626 0.17809038, 0.019982899 0.13523529 0.17402737, 0.020555794 0.13449232 0.17551304, 0.019460551 0.13566817 0.17316161, 0.018801384 0.13606152 0.17237486, 0.02271785 0.13614044 0.17221715, 0.026210567 0.13636449 0.1717691, 0.029457947 0.13672115 0.1710562, 0.031628676 0.13707709 0.17034419, 0.032545343 0.13729167 0.1699153, 0.033447221 0.1375542 0.16938986, 0.03439898 0.13789113 0.16871639, 0.035292573 0.13825867 0.16798125, 0.027573295 0.13825861 0.16798134, 0.020731183 0.13818015 0.16813813, 0.020731149 0.13951421 0.16547047, 0.027573345 0.13943568 0.16562746, 0.036169857 0.13943574 0.16562746, 0.036465794 0.14000121 0.16449673, 0.036564626 0.1405811 0.1633371, 0.036520667 0.14116213 0.16217552, 0.041257568 0.14084828 0.16280307, 0.040691908 0.14051718 0.16346489, 0.040324606 0.14013302 0.16423307, 0.04013449 0.13978836 0.16492258, 0.040029455 0.1394358 0.16562746, 0.047924161 0.13943586 0.1656277, 0.046726376 0.1399357 0.16462789, 0.045468077 0.14037743 0.16374467, 0.047924269 0.14116214 0.16217552, 0.049307644 0.14064305 0.16321371, 0.050555766 0.14006364 0.16437246, 0.04947485 0.13978207 0.16493534, 0.048450489 0.13943587 0.16562746, 0.051082093 0.13943583 0.16562746, 0.058099631 0.13951442 0.16547059, 0.058099605 0.1381804 0.16813813, 0.051082067 0.13825881 0.16798134, 0.042310126 0.13825881 0.16798134, 0.044173241 0.13766415 0.16917048, 0.046222538 0.13720784 0.17008312, 0.048709501 0.13683806 0.17082252, 0.051476307 0.13660473 0.17128907, 0.055416074 0.13643 0.17163844, 0.057548355 0.13640665 0.17168535, 0.059678577 0.13645428 0.17159055, 0.058874253 0.13592695 0.17264457, 0.058279414 0.13534589 0.17380632, 0.057924274 0.13472782 0.17504232, 0.053277418 0.1349497 0.1745988, 0.049551163 0.13524649 0.17400528, 0.046591707 0.13564995 0.17319833, 0.044358905 0.13609788 0.17230247, 0.042503886 0.13665111 0.17119621, 0.040678401 0.13734627 0.16980629, 0.038976815 0.1381018 0.16829525, 0.037515838 0.13736847 0.16976188, 0.035853181 0.13672653 0.17104556, 0.033778511 0.13613401 0.17223014, 0.031606954 0.13568991 0.1731181, 0.028824417 0.13528429 0.17392932, 0.024722366 0.13482054 0.1748568, -0.015409132 0.1377092 0.16907977, -0.012953075 0.13857244 0.16735376, -0.0087424926 0.13590442 0.17268871, -0.011724891 0.13488436 0.17472862, -0.012842875 0.13582832 0.17284094, -0.014089828 0.13673972 0.1710182, -0.015409132 0.13763061 0.16923653, -0.015409097 0.13190252 0.18069126, -0.015233677 0.12837163 0.18775232, -0.019093329 0.12837157 0.18775232, -0.018917933 0.13190249 0.18069111, -0.01891795 0.13692451 0.17064895, -0.020539915 0.13500088 0.17449515, -0.021865876 0.13376558 0.1769657, -0.022817668 0.13302208 0.17845248, -0.02383012 0.13229494 0.17990659, -0.025324043 0.13300365 0.1784891, -0.0266372 0.13355032 0.17739607, -0.025579682 0.13418689 0.17612316, -0.024202716 0.13522461 0.17404808, -0.022511799 0.13670696 0.17108382, -0.021015434 0.13834938 0.16779919, -0.020146877 0.13958818 0.16532205, -0.019444242 0.14084786 0.16280328, -0.020496858 0.14084786 0.16280328, -0.022957087 0.14080997 0.16287898, -0.025409086 0.14069086 0.16311692, -0.02540914 0.14218166 0.16013573, -0.020672347 0.14210328 0.16029264, -0.01891797 0.14210325 0.16029249, -0.018917888 0.14367262 0.15715434, -0.019093409 0.14602672 0.15244697, -0.015058326 0.1460267 0.15244688, -0.015343629 0.14485335 0.15479328, -0.015409175 0.1436727 0.15715422, -0.015409164 0.14210328 0.16029249, -0.013479345 0.1421033 0.16029249, -0.0090933815 0.1421818 0.16013576, -0.0090933573 0.1407695 0.16296004, -0.015409186 0.14084795 0.16280307, 0.040555723 0.14579165 0.15291749, 0.055292569 0.14579174 0.15291779, 0.055117138 0.14367315 0.15715434, 0.055292599 0.1413976 0.16170476, 0.040555734 0.14139757 0.16170476, 0.040731199 0.14367309 0.15715434, 0.043713611 0.14249603 0.15950803, 0.043713629 0.14469309 0.15511443, 0.052134696 0.14249605 0.15950797, 0.052134722 0.14469314 0.15511443, 0.052134715 0.14294326 0.15973161, 0.04371367 0.14294322 0.15973161, 0.04371357 0.14514036 0.15533815, 0.052134663 0.14514036 0.15533806, 0.036696129 0.14579162 0.15291749, 0.023011839 0.14579159 0.15291749, 0.036520623 0.14359465 0.15731128, 0.03669605 0.14139754 0.16170476, 0.023011914 0.14139736 0.16170476, 0.023187358 0.14359444 0.15731122, 0.02616979 0.14249593 0.15950803, 0.026169829 0.14469296 0.15511443, 0.033713605 0.14249597 0.15950797, 0.033713609 0.14469303 0.15511443, 0.033713691 0.1429431 0.15973161, 0.026169693 0.1429432 0.15973161, 0.026169753 0.14514026 0.15533789, 0.033713616 0.14514031 0.15533806, 0.067222483 0.12821519 0.18806617, 0.065818317 0.12892061 0.18665539, 0.064239971 0.12954907 0.18539862, 0.067296438 0.13029073 0.18391572, 0.070175089 0.13116267 0.18217193, 0.072427757 0.13201149 0.1804743, 0.074415132 0.1329495 0.17859878, 0.076361381 0.13410294 0.17629223, 0.078132011 0.1353979 0.17370273, 0.079486318 0.13669646 0.17110585, 0.080465138 0.13802284 0.16845365, 0.08135888 0.13975467 0.16499053, 0.081839211 0.14126223 0.16197599, 0.082007095 0.14289291 0.15871511, 0.081979953 0.1445788 0.15534328, 0.081783779 0.14626276 0.15197603, 0.086169794 0.14610581 0.15229, 0.085770711 0.14481661 0.15486787, 0.085643485 0.14351639 0.15746816, 0.08577048 0.14179561 0.16090904, 0.085931689 0.14072959 0.16304113, 0.08611507 0.14008132 0.16433726, 0.086657554 0.13916861 0.16616236, 0.087724067 0.13797893 0.16854165, 0.089515515 0.13639212 0.17171468, 0.091449715 0.13490576 0.17468704, 0.093176983 0.1338217 0.17685474, 0.095334195 0.13275716 0.17898397, 0.097633839 0.13185042 0.18079709, 0.10035623 0.13100222 0.18249322, 0.10243341 0.13047644 0.18354468, 0.10459105 0.13001999 0.18445723, 0.10306031 0.12927973 0.18593748, 0.10235967 0.12887307 0.18675084, 0.10178388 0.12845089 0.18759547, 0.098968737 0.12914485 0.1862074, 0.096332796 0.12996723 0.18456267, 0.093802005 0.13095048 0.1825967, 0.091480337 0.13207543 0.18034671, 0.089290492 0.13339233 0.17771353, 0.087350495 0.1348481 0.17480244, 0.085640736 0.13644564 0.17160793, 0.084240042 0.13810208 0.16829513, 0.083161853 0.1365359 0.17142735, 0.081718601 0.13502946 0.17443956, 0.080006346 0.13366458 0.17716889, 0.0779467 0.13236867 0.17976038, 0.075688958 0.13121191 0.18207343, 0.072989859 0.13007717 0.18434288, 0.070189975 0.12909436 0.18630786, -0.059268795 0.14602634 0.15244697, -0.035935514 0.14602661 0.15244712, -0.036110938 0.1432018 0.15809585, -0.0361109 0.14116159 0.16217564, -0.035935525 0.13841528 0.16766734, -0.059093393 0.13841507 0.16766734, -0.066286422 0.13833646 0.16782437, -0.066286363 0.1397489 0.16500007, -0.059093397 0.13967058 0.16515683, -0.039444309 0.13967076 0.16515683, -0.03944432 0.14147547 0.16154788, -0.058567129 0.14147535 0.16154788, -0.064707406 0.14139682 0.16170476, -0.064707458 0.14280921 0.15888037, -0.05874262 0.14273083 0.15903725, -0.039444268 0.1427308 0.15903725, -0.039444279 0.14461413 0.1552714, -0.059093371 0.14461398 0.15527131, -0.066286393 0.14453539 0.15542825, -0.066286422 0.14610484 0.15229009, -0.092863485 0.14509019 0.15431894, -0.094532035 0.14539848 0.15370201, -0.091778718 0.14494997 0.15459915, -0.090672396 0.14484914 0.15480079, -0.091380134 0.14408043 0.15633793, -0.092387445 0.14252487 0.15944873, -0.093464307 0.14107168 0.16235457, -0.095241114 0.13897026 0.16655694, -0.09633366 0.13795307 0.16859077, -0.097689867 0.13700241 0.17049183, -0.099173978 0.13735619 0.16978438, -0.10084779 0.13763013 0.16923653, -0.099452905 0.13859302 0.1673113, -0.098286495 0.13961539 0.16526665, -0.09684062 0.14122662 0.16204463, -0.095577784 0.14306355 0.15837143, -0.094981983 0.14422451 0.15604983, -0.086812772 0.13802257 0.16845213, -0.09154956 0.13880724 0.16688274, -0.087720901 0.13750598 0.16948487, -0.088686436 0.13674286 0.17101108, -0.090061031 0.13536049 0.17377533, -0.092127986 0.13302785 0.17843999, -0.094356559 0.13072513 0.18304493, -0.08207579 0.13127437 0.18194641, -0.083663434 0.13286042 0.17877509, -0.085409202 0.13441317 0.17567016, -0.084023669 0.13464497 0.17520647, -0.082251228 0.13504082 0.17441477, -0.079943955 0.13315061 0.17819481, -0.077858433 0.13120902 0.18207751, -0.075935416 0.12923425 0.18602623, -0.07926885 0.12844968 0.18759547, -0.080847718 0.13009745 0.18430032, -0.088135675 0.12972978 0.18503509, -0.092963941 0.12938827 0.1857179, -0.095033303 0.12914684 0.18620081, -0.096175417 0.12895361 0.18658711, -0.096988 0.12876338 0.18696766, -0.097989962 0.12966317 0.18516837, -0.099268839 0.13048962 0.1835158, -0.098558687 0.13069864 0.18309782, -0.097942404 0.13096106 0.18257298, -0.097243361 0.13136068 0.1817738, -0.096269101 0.13209862 0.18029822, -0.095225945 0.1331165 0.17826281, -0.093667701 0.13495326 0.17458977, -0.092471093 0.13663507 0.17122655, -0.091883935 0.13771063 0.16907571, -0.084707499 0.14610472 0.15229, -0.088040888 0.1457909 0.15291749, -0.084463172 0.14527363 0.15395202, -0.0838245 0.14419264 0.15611373, -0.082568243 0.14269382 0.15911077, -0.081161439 0.14137037 0.16175734, -0.079781525 0.14043075 0.16363643, -0.078143299 0.13959673 0.16530429, -0.076348133 0.13890758 0.16668247, -0.074356563 0.13833651 0.16782455, -0.075767972 0.13806076 0.16837572, -0.076784424 0.1377376 0.16902195, -0.077401429 0.13743454 0.16962837, -0.077865332 0.13708106 0.17033504, -0.079824716 0.13787416 0.16874884, -0.081553228 0.13876855 0.16696046, -0.083201036 0.13985848 0.16478051, -0.085027188 0.14134856 0.16180108, -0.08617235 0.14251716 0.15946423, -0.087022074 0.14370257 0.15709354, -0.087584898 0.14474139 0.1550162, 0.0077487044 0.14500681 0.15448685, -0.0061109476 0.14500675 0.15448685, 0.0075733215 0.14124039 0.16201864, 0.0075734034 0.13103959 0.18241714, 0.0076951496 0.13045451 0.18358745, 0.0077925865 0.13030863 0.183879, 0.0079210214 0.13017854 0.18413909, 0.0080599561 0.13008752 0.18432139, 0.0082383733 0.13001326 0.18446957, 0.0084144864 0.12996897 0.18455805, 0.0088193808 0.12992555 0.18464492, 0.010203466 0.12989147 0.18471296, 0.010436386 0.12990509 0.18468581, 0.010605438 0.12992795 0.18464004, 0.010708211 0.12995048 0.18459521, 0.010806469 0.12998109 0.18453412, 0.010990618 0.13006841 0.18435951, 0.011117423 0.13015996 0.18417658, 0.011258183 0.13031319 0.18386988, 0.01137162 0.13050941 0.18347763, 0.011538126 0.13105889 0.18237866, 0.011608422 0.13198116 0.18053426, 0.013405461 0.13161466 0.18126728, 0.015292708 0.13135342 0.18178962, 0.0144947 0.1298357 0.18482475, 0.013922786 0.12918317 0.18612932, 0.013547041 0.12894371 0.18660839, 0.013175689 0.12880027 0.18689524, 0.012698866 0.12868914 0.18711771, 0.012162155 0.12862778 0.18724032, 0.011608487 0.12860715 0.18728156, 0.0079242513 0.12860712 0.18728156, 0.0066909548 0.12865052 0.1871949, 0.0057288297 0.12877637 0.18694304, 0.0051386077 0.12892497 0.186646, 0.0047660675 0.1290791 0.18633761, 0.0044802334 0.12927416 0.18594725, 0.0042892974 0.12949157 0.18551274, 0.0040503107 0.13014302 0.1842102, 0.0040646419 0.13080418 0.18288802, 0.0040644705 0.14367279 0.15715443, -0.0026021563 0.14367273 0.15715434, -0.0027394257 0.13828203 0.1679344, -0.0030484423 0.13559029 0.17331685, -0.0035719108 0.13391428 0.1766683, -0.0044270623 0.13228464 0.17992745, -0.0053731631 0.1311374 0.18222155, -0.006595619 0.13009411 0.18430783, -0.0080164634 0.1291251 0.18624543, -0.0096196439 0.12821472 0.18806617, -0.011131208 0.1288757 0.18674417, -0.012777537 0.12947014 0.18555544, -0.011200765 0.13010937 0.18427737, -0.0098517369 0.13084593 0.18280442, -0.0086270738 0.13176562 0.18096508, -0.0075306389 0.13292788 0.17864089, -0.006838588 0.13411558 0.17626561, -0.0062858891 0.13592923 0.1726393, -0.0060004257 0.13834757 0.16780291, -0.0059355311 0.14076954 0.16296016, -0.059619687 0.13637486 0.17174722, -0.063479334 0.13700265 0.17049204, -0.060675245 0.13565673 0.17318349, -0.061513539 0.1348829 0.17473064, -0.062420882 0.13388729 0.17672186, -0.063479356 0.13292244 0.17865123, -0.065197237 0.13327646 0.17794327, -0.066988118 0.13355002 0.17739607, -0.065870427 0.13423592 0.17602436, -0.06501741 0.13499455 0.1745076, -0.064180709 0.13598812 0.17252062, -0.052602176 0.13770895 0.16907959, -0.050607499 0.1374813 0.16953509, -0.049327824 0.13741583 0.16966586, -0.04804071 0.13739508 0.16970725, -0.048713408 0.13675871 0.17097993, -0.049070913 0.13607344 0.17235027, -0.049060941 0.13544017 0.17361669, -0.048781492 0.13488379 0.17472951, -0.048112817 0.13418433 0.1761279, -0.046986371 0.13339867 0.17769895, -0.045511499 0.13268965 0.1791171, -0.043832771 0.13210228 0.18029155, -0.041435409 0.1314629 0.18157004, -0.038581386 0.13089871 0.18269847, -0.035647549 0.13049746 0.18350099, -0.032652896 0.13023965 0.18401645, -0.029619701 0.13009784 0.18430017, -0.030941665 0.12929556 0.18590425, -0.031460572 0.12885448 0.18678601, -0.031748027 0.12850335 0.18748839, -0.031900279 0.12813605 0.1882232, -0.03556554 0.12851471 0.18746565, -0.038794011 0.12896991 0.18655537, -0.041775268 0.12955344 0.18538834, -0.044295829 0.13021022 0.18407504, -0.046579555 0.13097756 0.18254076, -0.048313208 0.13172147 0.18105282, -0.049566507 0.13241544 0.17966534, -0.050672296 0.13315782 0.17818059, -0.051952682 0.13218735 0.18012144, -0.053383134 0.1314005 0.18169473, -0.055288155 0.13061327 0.18326916, -0.057696737 0.12984952 0.18479596, -0.060192686 0.12927362 0.18594773, -0.061863553 0.12898116 0.18653269, -0.064445131 0.12859794 0.18729894, -0.068742484 0.12797901 0.18853705, -0.069225959 0.12862641 0.18724202, -0.069963433 0.12922587 0.18604325, -0.070847742 0.12978351 0.1849279, -0.067498274 0.13000396 0.18448712, -0.064210191 0.13036379 0.18376778, -0.061466113 0.13082564 0.1828443, -0.05890559 0.13141534 0.18166481, -0.057068758 0.13199541 0.18050496, -0.05586642 0.13254419 0.17940785, -0.054880355 0.13321081 0.17807461, -0.054051694 0.13407728 0.1763417, -0.053376358 0.13520098 0.1740949, -0.052896477 0.13644922 0.17159896, -0.03944426 0.13700289 0.17049204, -0.037733816 0.13665538 0.17118643, -0.035584632 0.13629669 0.17190407, -0.036429241 0.1358739 0.1727493, -0.037139159 0.13533621 0.17382456, -0.038092263 0.1343945 0.17570798, -0.039795198 0.13292259 0.17865135, -0.04295297 0.13355017 0.17739607, -0.041787796 0.13443391 0.17562918, -0.040541127 0.13570443 0.17308812 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 2, 1, 3, -1, 3, 4, 5, -1, 1, 4, 3, -1, 5, 6, 7, -1, 4, 6, 5, -1, 7, 8, 9, -1, 6, 8, 7, -1, 9, 10, 11, -1, 8, 10, 9, -1, 11, 12, 13, -1, 10, 12, 11, -1, 13, 14, 15, -1, 12, 14, 13, -1, 15, 16, 17, -1, 14, 16, 15, -1, 17, 18, 19, -1, 16, 18, 17, -1, 19, 20, 21, -1, 18, 20, 19, -1, 21, 22, 23, -1, 20, 22, 21, -1, 23, 24, 25, -1, 22, 24, 23, -1, 25, 26, 27, -1, 24, 26, 25, -1, 28, 29, 30, -1, 30, 29, 31, -1, 31, 32, 33, -1, 29, 32, 31, -1, 33, 34, 35, -1, 32, 34, 33, -1, 35, 36, 37, -1, 34, 36, 35, -1, 37, 38, 39, -1, 36, 38, 37, -1, 39, 40, 41, -1, 38, 40, 39, -1, 41, 42, 43, -1, 40, 42, 41, -1, 43, 44, 45, -1, 42, 44, 43, -1, 45, 46, 47, -1, 44, 46, 45, -1, 47, 48, 49, -1, 46, 48, 47, -1, 49, 50, 51, -1, 48, 50, 49, -1, 51, 52, 53, -1, 50, 52, 51, -1, 53, 54, 55, -1, 52, 54, 53, -1, 56, 57, 58, -1, 58, 57, 59, -1, 59, 60, 61, -1, 57, 60, 59, -1, 61, 62, 63, -1, 60, 62, 61, -1, 63, 64, 65, -1, 62, 64, 63, -1, 65, 66, 67, -1, 64, 66, 65, -1, 67, 68, 69, -1, 66, 68, 67, -1, 69, 70, 71, -1, 68, 70, 69, -1, 71, 72, 73, -1, 70, 72, 71, -1, 73, 74, 75, -1, 72, 74, 73, -1, 75, 76, 77, -1, 74, 76, 75, -1, 77, 78, 79, -1, 76, 78, 77, -1, 79, 80, 81, -1, 78, 80, 79, -1, 81, 82, 83, -1, 80, 82, 81, -1, 84, 85, 86, -1, 86, 85, 87, -1, 87, 88, 89, -1, 85, 88, 87, -1, 89, 90, 91, -1, 88, 90, 89, -1, 91, 92, 93, -1, 90, 92, 91, -1, 93, 94, 95, -1, 92, 94, 93, -1, 95, 96, 97, -1, 94, 96, 95, -1, 97, 98, 99, -1, 96, 98, 97, -1, 99, 100, 101, -1, 98, 100, 99, -1, 101, 102, 103, -1, 100, 102, 101, -1, 103, 104, 105, -1, 102, 104, 103, -1, 105, 106, 107, -1, 104, 106, 105, -1, 107, 108, 109, -1, 106, 108, 107, -1, 109, 110, 111, -1, 108, 110, 109, -1, 112, 113, 114, -1, 114, 113, 115, -1, 115, 116, 117, -1, 113, 116, 115, -1, 117, 118, 119, -1, 116, 118, 117, -1, 119, 120, 121, -1, 118, 120, 119, -1, 121, 122, 123, -1, 120, 122, 121, -1, 123, 124, 125, -1, 122, 124, 123, -1, 125, 126, 127, -1, 124, 126, 125, -1, 127, 128, 129, -1, 126, 128, 127, -1, 129, 130, 131, -1, 128, 130, 129, -1, 131, 132, 133, -1, 130, 132, 131, -1, 133, 134, 135, -1, 132, 134, 133, -1, 135, 136, 137, -1, 134, 136, 135, -1, 137, 138, 139, -1, 136, 138, 137, -1, 140, 141, 142, -1, 142, 141, 143, -1, 143, 144, 145, -1, 141, 144, 143, -1, 145, 146, 147, -1, 144, 146, 145, -1, 147, 148, 149, -1, 146, 148, 147, -1, 149, 150, 151, -1, 148, 150, 149, -1, 151, 152, 153, -1, 150, 152, 151, -1, 153, 154, 155, -1, 152, 154, 153, -1, 155, 156, 157, -1, 154, 156, 155, -1, 157, 158, 159, -1, 156, 158, 157, -1, 159, 160, 161, -1, 158, 160, 159, -1, 161, 162, 163, -1, 160, 162, 161, -1, 163, 164, 165, -1, 162, 164, 163, -1, 165, 166, 167, -1, 164, 166, 165, -1, 168, 169, 170, -1, 170, 169, 171, -1, 171, 172, 173, -1, 169, 172, 171, -1, 173, 174, 175, -1, 172, 174, 173, -1, 175, 176, 177, -1, 174, 176, 175, -1, 177, 178, 179, -1, 176, 178, 177, -1, 179, 180, 181, -1, 178, 180, 179, -1, 181, 182, 183, -1, 180, 182, 181, -1, 183, 184, 185, -1, 182, 184, 183, -1, 185, 186, 187, -1, 184, 186, 185, -1, 187, 188, 189, -1, 186, 188, 187, -1, 189, 190, 191, -1, 188, 190, 189, -1, 191, 192, 193, -1, 190, 192, 191, -1, 193, 194, 195, -1, 192, 194, 193, -1, 195, 196, 197, -1, 194, 196, 195, -1, 197, 198, 199, -1, 196, 198, 197, -1, 198, 200, 199, -1, 199, 200, 201, -1, 202, 203, 204, -1, 204, 203, 205, -1, 205, 206, 207, -1, 203, 206, 205, -1, 207, 208, 209, -1, 206, 208, 207, -1, 209, 210, 211, -1, 208, 210, 209, -1, 211, 212, 213, -1, 210, 212, 211, -1, 213, 214, 215, -1, 212, 214, 213, -1, 215, 216, 217, -1, 214, 216, 215, -1, 217, 218, 219, -1, 216, 218, 217, -1, 219, 220, 221, -1, 218, 220, 219, -1, 221, 222, 223, -1, 220, 222, 221, -1, 223, 224, 225, -1, 222, 224, 223, -1, 225, 226, 227, -1, 224, 226, 225, -1, 227, 228, 229, -1, 226, 228, 227, -1, 230, 231, 232, -1, 232, 231, 233, -1, 233, 234, 235, -1, 231, 234, 233, -1, 235, 236, 237, -1, 234, 236, 235, -1, 237, 238, 239, -1, 236, 238, 237, -1, 239, 240, 241, -1, 238, 240, 239, -1, 241, 242, 243, -1, 240, 242, 241, -1, 243, 244, 245, -1, 242, 244, 243, -1, 245, 246, 247, -1, 244, 246, 245, -1, 247, 248, 249, -1, 246, 248, 247, -1, 249, 250, 251, -1, 248, 250, 249, -1, 251, 252, 253, -1, 250, 252, 251, -1, 253, 254, 255, -1, 252, 254, 253, -1, 255, 256, 257, -1, 254, 256, 255, -1, 258, 259, 260, -1, 260, 259, 261, -1, 261, 262, 263, -1, 259, 262, 261, -1, 263, 264, 265, -1, 262, 264, 263, -1, 265, 266, 267, -1, 264, 266, 265, -1, 267, 268, 269, -1, 266, 268, 267, -1, 269, 270, 271, -1, 268, 270, 269, -1, 271, 272, 273, -1, 270, 272, 271, -1, 273, 274, 275, -1, 272, 274, 273, -1, 275, 276, 277, -1, 274, 276, 275, -1, 277, 278, 279, -1, 276, 278, 277, -1, 279, 280, 281, -1, 278, 280, 279, -1, 281, 282, 283, -1, 280, 282, 281, -1, 283, 284, 285, -1, 282, 284, 283, -1, 285, 286, 287, -1, 284, 286, 285, -1, 287, 288, 289, -1, 286, 288, 287, -1, 288, 290, 289, -1, 289, 290, 291, -1, 292, 293, 294, -1, 294, 293, 295, -1, 295, 296, 297, -1, 293, 296, 295, -1, 297, 298, 299, -1, 296, 298, 297, -1, 299, 300, 301, -1, 298, 300, 299, -1, 301, 302, 303, -1, 300, 302, 301, -1, 303, 304, 305, -1, 302, 304, 303, -1, 305, 306, 307, -1, 304, 306, 305, -1, 307, 308, 309, -1, 306, 308, 307, -1, 309, 310, 311, -1, 308, 310, 309, -1, 311, 312, 313, -1, 310, 312, 311, -1, 313, 314, 315, -1, 312, 314, 313, -1, 315, 316, 317, -1, 314, 316, 315, -1, 317, 318, 319, -1, 316, 318, 317, -1, 320, 321, 322, -1, 322, 321, 323, -1, 323, 324, 325, -1, 321, 324, 323, -1, 325, 326, 327, -1, 324, 326, 325, -1, 327, 328, 329, -1, 326, 328, 327, -1, 329, 330, 331, -1, 328, 330, 329, -1, 331, 332, 333, -1, 330, 332, 331, -1, 333, 334, 335, -1, 332, 334, 333, -1, 335, 336, 337, -1, 334, 336, 335, -1, 337, 338, 339, -1, 336, 338, 337, -1, 339, 340, 341, -1, 338, 340, 339, -1, 341, 342, 343, -1, 340, 342, 341, -1, 343, 344, 345, -1, 342, 344, 343, -1, 345, 346, 347, -1, 344, 346, 345, -1, 348, 349, 350, -1, 350, 349, 351, -1, 351, 352, 353, -1, 349, 352, 351, -1, 353, 354, 355, -1, 352, 354, 353, -1, 355, 356, 357, -1, 354, 356, 355, -1, 357, 358, 359, -1, 356, 358, 357, -1, 359, 360, 361, -1, 358, 360, 359, -1, 361, 362, 363, -1, 360, 362, 361, -1, 363, 364, 365, -1, 362, 364, 363, -1, 365, 366, 367, -1, 364, 366, 365, -1, 367, 368, 369, -1, 366, 368, 367, -1, 369, 370, 371, -1, 368, 370, 369, -1, 371, 372, 373, -1, 370, 372, 371, -1, 373, 374, 375, -1, 372, 374, 373, -1, 376, 377, 378, -1, 378, 377, 379, -1, 379, 380, 381, -1, 377, 380, 379, -1, 381, 382, 383, -1, 380, 382, 381, -1, 383, 384, 385, -1, 382, 384, 383, -1, 385, 386, 387, -1, 384, 386, 385, -1, 387, 388, 389, -1, 386, 388, 387, -1, 389, 390, 391, -1, 388, 390, 389, -1, 391, 392, 393, -1, 390, 392, 391, -1, 393, 394, 395, -1, 392, 394, 393, -1, 395, 396, 397, -1, 394, 396, 395, -1, 397, 398, 399, -1, 396, 398, 397, -1, 399, 400, 401, -1, 398, 400, 399, -1, 401, 402, 403, -1, 400, 402, 401, -1, 404, 405, 406, -1, 406, 405, 407, -1, 407, 408, 409, -1, 405, 408, 407, -1, 409, 410, 411, -1, 408, 410, 409, -1, 411, 412, 413, -1, 410, 412, 411, -1, 413, 414, 415, -1, 412, 414, 413, -1, 415, 416, 417, -1, 414, 416, 415, -1, 417, 418, 419, -1, 416, 418, 417, -1, 419, 420, 421, -1, 418, 420, 419, -1, 421, 422, 423, -1, 420, 422, 421, -1, 423, 424, 425, -1, 422, 424, 423, -1, 425, 426, 427, -1, 424, 426, 425, -1, 427, 428, 429, -1, 426, 428, 427, -1, 429, 430, 431, -1, 428, 430, 429, -1, 432, 433, 434, -1, 434, 433, 435, -1, 435, 436, 437, -1, 433, 436, 435, -1, 437, 438, 439, -1, 436, 438, 437, -1, 439, 440, 441, -1, 438, 440, 439, -1, 441, 442, 443, -1, 440, 442, 441, -1, 443, 444, 445, -1, 442, 444, 443, -1, 445, 446, 447, -1, 444, 446, 445, -1, 447, 448, 449, -1, 446, 448, 447, -1, 449, 450, 451, -1, 448, 450, 449, -1, 451, 452, 453, -1, 450, 452, 451, -1, 453, 454, 455, -1, 452, 454, 453, -1, 455, 456, 457, -1, 454, 456, 455, -1, 457, 458, 459, -1, 456, 458, 457, -1, 460, 461, 462, -1, 463, 461, 460, -1, 464, 465, 466, -1, 467, 465, 464, -1, 468, 469, 470, -1, 471, 469, 468, -1, 472, 473, 474, -1, 475, 473, 472, -1, 476, 284, 282, -1, 477, 478, 479, -1, 480, 478, 477, -1, 44, 42, 481, -1, 440, 438, 467, -1, 482, 483, 484, -1, 481, 42, 485, -1, 486, 483, 482, -1, 321, 278, 324, -1, 324, 278, 326, -1, 487, 465, 488, -1, 488, 465, 489, -1, 489, 465, 490, -1, 280, 278, 321, -1, 490, 465, 491, -1, 486, 492, 483, -1, 491, 465, 493, -1, 493, 465, 494, -1, 494, 465, 495, -1, 495, 465, 376, -1, 486, 496, 492, -1, 497, 286, 498, -1, 498, 286, 499, -1, 500, 463, 501, -1, 499, 286, 284, -1, 501, 463, 502, -1, 473, 471, 496, -1, 502, 463, 503, -1, 487, 463, 465, -1, 504, 463, 505, -1, 42, 40, 485, -1, 496, 471, 492, -1, 503, 463, 506, -1, 506, 463, 487, -1, 507, 463, 508, -1, 508, 463, 509, -1, 509, 463, 510, -1, 510, 463, 511, -1, 512, 513, 514, -1, 511, 463, 504, -1, 505, 463, 500, -1, 368, 366, 473, -1, 438, 436, 467, -1, 515, 516, 463, -1, 463, 516, 465, -1, 473, 370, 368, -1, 515, 517, 516, -1, 518, 519, 520, -1, 514, 519, 518, -1, 366, 364, 473, -1, 517, 521, 516, -1, 326, 276, 328, -1, 513, 519, 514, -1, 473, 372, 370, -1, 522, 523, 517, -1, 517, 523, 521, -1, 40, 38, 485, -1, 465, 467, 432, -1, 520, 461, 475, -1, 364, 362, 473, -1, 465, 432, 524, -1, 475, 461, 525, -1, 465, 524, 376, -1, 485, 38, 526, -1, 376, 524, 377, -1, 278, 276, 326, -1, 473, 475, 374, -1, 497, 288, 286, -1, 374, 475, 527, -1, 527, 475, 430, -1, 519, 461, 520, -1, 527, 430, 428, -1, 461, 463, 528, -1, 528, 463, 529, -1, 525, 461, 530, -1, 473, 374, 372, -1, 529, 463, 531, -1, 530, 461, 532, -1, 531, 463, 507, -1, 532, 461, 533, -1, 534, 288, 535, -1, 535, 288, 497, -1, 436, 433, 467, -1, 362, 360, 473, -1, 433, 432, 467, -1, 38, 36, 526, -1, 473, 358, 471, -1, 250, 248, 536, -1, 526, 36, 537, -1, 360, 358, 473, -1, 536, 252, 250, -1, 538, 252, 536, -1, 358, 356, 471, -1, 36, 34, 537, -1, 536, 246, 539, -1, 537, 34, 540, -1, 356, 354, 471, -1, 248, 246, 536, -1, 538, 254, 252, -1, 328, 274, 330, -1, 354, 352, 471, -1, 276, 274, 328, -1, 534, 290, 288, -1, 246, 244, 539, -1, 538, 256, 254, -1, 244, 242, 539, -1, 539, 242, 541, -1, 542, 543, 538, -1, 538, 543, 256, -1, 544, 422, 545, -1, 242, 240, 541, -1, 424, 422, 544, -1, 132, 130, 471, -1, 76, 74, 90, -1, 545, 422, 344, -1, 90, 74, 92, -1, 92, 74, 94, -1, 546, 426, 544, -1, 471, 134, 132, -1, 544, 426, 424, -1, 90, 78, 76, -1, 542, 547, 543, -1, 344, 420, 346, -1, 85, 78, 88, -1, 88, 78, 90, -1, 422, 420, 344, -1, 130, 128, 471, -1, 541, 238, 548, -1, 527, 428, 546, -1, 240, 238, 541, -1, 546, 428, 426, -1, 471, 136, 134, -1, 549, 550, 542, -1, 542, 550, 547, -1, 420, 418, 346, -1, 94, 72, 52, -1, 52, 72, 54, -1, 346, 418, 551, -1, 238, 236, 548, -1, 74, 72, 94, -1, 128, 126, 471, -1, 352, 138, 471, -1, 471, 138, 136, -1, 552, 553, 549, -1, 349, 138, 352, -1, 549, 553, 550, -1, 85, 80, 78, -1, 126, 124, 471, -1, 72, 70, 54, -1, 54, 70, 554, -1, 348, 555, 349, -1, 349, 555, 138, -1, 552, 556, 553, -1, 557, 556, 552, -1, 558, 559, 348, -1, 348, 559, 555, -1, 85, 82, 80, -1, 560, 561, 558, -1, 558, 561, 559, -1, 562, 82, 84, -1, 84, 82, 85, -1, 560, 563, 561, -1, 564, 563, 560, -1, 554, 68, 565, -1, 564, 566, 563, -1, 70, 68, 554, -1, 562, 567, 82, -1, 203, 192, 206, -1, 565, 66, 568, -1, 68, 66, 565, -1, 270, 222, 272, -1, 569, 570, 562, -1, 562, 570, 567, -1, 206, 190, 208, -1, 66, 64, 568, -1, 568, 64, 571, -1, 192, 190, 206, -1, 222, 220, 272, -1, 569, 572, 570, -1, 202, 194, 203, -1, 272, 220, 274, -1, 203, 194, 192, -1, 573, 310, 574, -1, 118, 160, 120, -1, 575, 572, 569, -1, 312, 310, 573, -1, 64, 62, 571, -1, 270, 224, 222, -1, 571, 62, 576, -1, 120, 158, 122, -1, 160, 158, 120, -1, 577, 194, 202, -1, 290, 314, 573, -1, 208, 188, 210, -1, 534, 314, 290, -1, 575, 578, 572, -1, 573, 314, 312, -1, 113, 162, 116, -1, 579, 578, 580, -1, 190, 188, 208, -1, 116, 162, 118, -1, 580, 578, 575, -1, 118, 162, 160, -1, 576, 60, 581, -1, 122, 156, 124, -1, 158, 156, 122, -1, 62, 60, 576, -1, 579, 582, 578, -1, 220, 218, 274, -1, 529, 582, 579, -1, 577, 196, 194, -1, 274, 218, 330, -1, 581, 57, 583, -1, 113, 164, 162, -1, 310, 308, 574, -1, 584, 196, 577, -1, 124, 154, 471, -1, 60, 57, 581, -1, 210, 186, 212, -1, 529, 531, 582, -1, 156, 154, 124, -1, 583, 56, 585, -1, 188, 186, 210, -1, 268, 226, 270, -1, 212, 186, 586, -1, 270, 226, 224, -1, 587, 166, 112, -1, 57, 56, 583, -1, 112, 166, 113, -1, 113, 166, 164, -1, 534, 316, 314, -1, 418, 316, 551, -1, 585, 504, 505, -1, 56, 504, 585, -1, 416, 316, 418, -1, 584, 198, 196, -1, 551, 316, 534, -1, 259, 198, 588, -1, 258, 198, 259, -1, 587, 589, 166, -1, 588, 198, 584, -1, 590, 216, 591, -1, 330, 216, 332, -1, 218, 216, 330, -1, 332, 216, 590, -1, 258, 200, 198, -1, 308, 306, 574, -1, 592, 593, 587, -1, 574, 306, 594, -1, 587, 593, 589, -1, 34, 20, 540, -1, 586, 184, 480, -1, 268, 228, 226, -1, 186, 184, 586, -1, 416, 318, 316, -1, 595, 596, 592, -1, 234, 597, 236, -1, 592, 596, 593, -1, 236, 597, 548, -1, 258, 597, 200, -1, 414, 318, 416, -1, 548, 597, 258, -1, 184, 182, 480, -1, 478, 182, 598, -1, 595, 599, 596, -1, 20, 18, 540, -1, 540, 18, 600, -1, 591, 214, 601, -1, 602, 599, 595, -1, 480, 182, 478, -1, 216, 214, 591, -1, 306, 304, 594, -1, 603, 604, 602, -1, 29, 22, 32, -1, 32, 22, 34, -1, 602, 604, 599, -1, 34, 22, 20, -1, 231, 605, 234, -1, 234, 605, 597, -1, 598, 180, 606, -1, 591, 601, 603, -1, 268, 607, 228, -1, 603, 601, 604, -1, 18, 16, 600, -1, 182, 180, 598, -1, 600, 16, 608, -1, 414, 609, 318, -1, 606, 178, 610, -1, 180, 178, 606, -1, 611, 612, 230, -1, 29, 24, 22, -1, 230, 612, 231, -1, 231, 612, 605, -1, 214, 212, 601, -1, 601, 212, 586, -1, 611, 613, 612, -1, 608, 14, 614, -1, 615, 613, 611, -1, 16, 14, 608, -1, 304, 302, 594, -1, 610, 176, 616, -1, 140, 469, 141, -1, 617, 26, 28, -1, 141, 469, 144, -1, 28, 26, 29, -1, 144, 469, 146, -1, 178, 176, 610, -1, 146, 469, 148, -1, 148, 469, 150, -1, 150, 469, 152, -1, 152, 469, 154, -1, 29, 26, 24, -1, 154, 469, 471, -1, 618, 619, 615, -1, 615, 619, 613, -1, 268, 620, 607, -1, 14, 12, 614, -1, 614, 12, 168, -1, 414, 621, 609, -1, 176, 174, 616, -1, 618, 622, 619, -1, 412, 621, 414, -1, 617, 623, 26, -1, 616, 172, 624, -1, 625, 626, 627, -1, 174, 172, 616, -1, 12, 10, 168, -1, 168, 10, 169, -1, 628, 629, 625, -1, 630, 629, 628, -1, 625, 629, 626, -1, 631, 632, 633, -1, 633, 632, 617, -1, 630, 467, 629, -1, 469, 467, 630, -1, 617, 632, 623, -1, 412, 634, 621, -1, 635, 340, 636, -1, 410, 634, 412, -1, 268, 266, 620, -1, 505, 637, 631, -1, 620, 266, 638, -1, 340, 338, 636, -1, 302, 639, 594, -1, 636, 338, 640, -1, 631, 637, 632, -1, 300, 639, 302, -1, 635, 342, 340, -1, 641, 342, 635, -1, 300, 298, 639, -1, 338, 336, 640, -1, 505, 500, 637, -1, 640, 336, 642, -1, 266, 643, 638, -1, 410, 644, 634, -1, 545, 344, 641, -1, 641, 344, 342, -1, 336, 334, 642, -1, 408, 644, 410, -1, 645, 104, 646, -1, 642, 334, 564, -1, 564, 334, 566, -1, 104, 102, 646, -1, 298, 296, 639, -1, 566, 332, 590, -1, 646, 102, 557, -1, 645, 106, 104, -1, 266, 647, 643, -1, 405, 106, 648, -1, 648, 106, 645, -1, 334, 332, 566, -1, 405, 648, 408, -1, 404, 106, 405, -1, 102, 100, 557, -1, 557, 100, 556, -1, 408, 648, 644, -1, 404, 108, 106, -1, 649, 108, 404, -1, 100, 98, 556, -1, 556, 98, 650, -1, 651, 396, 0, -1, 649, 110, 108, -1, 461, 110, 533, -1, 533, 110, 649, -1, 0, 394, 1, -1, 1, 394, 4, -1, 650, 96, 652, -1, 396, 394, 0, -1, 98, 96, 650, -1, 653, 398, 651, -1, 461, 654, 110, -1, 651, 398, 396, -1, 652, 94, 655, -1, 394, 392, 4, -1, 4, 392, 6, -1, 96, 94, 652, -1, 461, 656, 654, -1, 657, 400, 653, -1, 653, 400, 398, -1, 461, 658, 656, -1, 6, 390, 8, -1, 392, 390, 6, -1, 657, 402, 400, -1, 659, 402, 657, -1, 461, 660, 658, -1, 390, 388, 8, -1, 8, 388, 10, -1, 461, 661, 660, -1, 266, 264, 647, -1, 10, 388, 169, -1, 452, 450, 469, -1, 140, 454, 469, -1, 647, 264, 662, -1, 662, 264, 663, -1, 664, 665, 659, -1, 461, 528, 661, -1, 659, 665, 402, -1, 296, 666, 639, -1, 469, 454, 452, -1, 667, 666, 292, -1, 292, 666, 293, -1, 293, 666, 296, -1, 450, 448, 469, -1, 388, 386, 169, -1, 469, 448, 467, -1, 140, 456, 454, -1, 264, 262, 663, -1, 663, 262, 668, -1, 169, 386, 172, -1, 668, 262, 669, -1, 172, 386, 624, -1, 667, 670, 666, -1, 671, 672, 664, -1, 664, 672, 665, -1, 673, 456, 140, -1, 674, 670, 675, -1, 675, 670, 667, -1, 448, 446, 467, -1, 624, 384, 676, -1, 386, 384, 624, -1, 430, 475, 677, -1, 677, 475, 678, -1, 673, 458, 456, -1, 678, 475, 679, -1, 679, 475, 680, -1, 680, 475, 681, -1, 681, 475, 682, -1, 682, 475, 683, -1, 502, 503, 671, -1, 683, 475, 525, -1, 684, 458, 673, -1, 685, 48, 618, -1, 618, 48, 622, -1, 674, 686, 670, -1, 446, 444, 467, -1, 671, 503, 672, -1, 687, 686, 674, -1, 676, 382, 688, -1, 262, 259, 669, -1, 384, 382, 676, -1, 684, 689, 458, -1, 669, 259, 588, -1, 690, 689, 684, -1, 444, 442, 467, -1, 48, 46, 622, -1, 688, 380, 691, -1, 691, 380, 524, -1, 382, 380, 688, -1, 622, 46, 692, -1, 690, 479, 689, -1, 477, 479, 690, -1, 655, 50, 685, -1, 442, 440, 467, -1, 685, 50, 48, -1, 380, 377, 524, -1, 476, 282, 693, -1, 693, 282, 694, -1, 694, 282, 695, -1, 687, 552, 686, -1, 692, 44, 481, -1, 557, 552, 687, -1, 695, 280, 696, -1, 696, 280, 320, -1, 320, 280, 321, -1, 46, 44, 692, -1, 282, 280, 695, -1, 655, 52, 50, -1, 499, 284, 697, -1, 94, 52, 655, -1, 697, 284, 476, -1, 285, 698, 283, -1, 699, 700, 701, -1, 43, 45, 702, -1, 699, 703, 700, -1, 439, 441, 464, -1, 43, 702, 704, -1, 705, 706, 707, -1, 705, 707, 708, -1, 279, 323, 325, -1, 279, 325, 327, -1, 466, 709, 710, -1, 466, 710, 711, -1, 466, 711, 712, -1, 279, 281, 323, -1, 466, 712, 713, -1, 714, 705, 708, -1, 466, 713, 715, -1, 466, 715, 716, -1, 466, 716, 717, -1, 466, 717, 378, -1, 718, 705, 714, -1, 287, 719, 720, -1, 287, 720, 721, -1, 460, 722, 723, -1, 287, 721, 285, -1, 460, 723, 724, -1, 468, 474, 718, -1, 460, 709, 466, -1, 460, 725, 726, -1, 41, 43, 704, -1, 460, 727, 728, -1, 468, 718, 714, -1, 460, 728, 709, -1, 460, 729, 730, -1, 460, 730, 731, -1, 732, 733, 734, -1, 460, 731, 735, -1, 460, 735, 736, -1, 460, 736, 725, -1, 460, 726, 722, -1, 460, 724, 727, -1, 367, 369, 474, -1, 437, 439, 464, -1, 737, 466, 738, -1, 737, 460, 466, -1, 371, 474, 369, -1, 739, 734, 740, -1, 739, 740, 741, -1, 742, 737, 738, -1, 365, 367, 474, -1, 277, 327, 329, -1, 743, 737, 742, -1, 739, 732, 734, -1, 373, 474, 371, -1, 744, 742, 745, -1, 744, 743, 742, -1, 39, 41, 704, -1, 464, 466, 434, -1, 462, 472, 746, -1, 363, 365, 474, -1, 434, 466, 747, -1, 462, 741, 472, -1, 747, 466, 378, -1, 747, 378, 379, -1, 39, 704, 748, -1, 277, 279, 327, -1, 460, 462, 749, -1, 289, 719, 287, -1, 460, 749, 750, -1, 460, 750, 751, -1, 460, 751, 729, -1, 472, 474, 375, -1, 462, 739, 741, -1, 472, 375, 752, -1, 462, 746, 753, -1, 375, 474, 373, -1, 472, 752, 431, -1, 462, 753, 754, -1, 431, 752, 429, -1, 462, 754, 755, -1, 289, 756, 757, -1, 289, 757, 719, -1, 435, 437, 464, -1, 361, 363, 474, -1, 434, 435, 464, -1, 37, 39, 748, -1, 359, 474, 468, -1, 37, 748, 758, -1, 359, 361, 474, -1, 249, 251, 759, -1, 253, 760, 759, -1, 253, 759, 251, -1, 357, 359, 468, -1, 247, 759, 761, -1, 35, 758, 762, -1, 355, 357, 468, -1, 247, 249, 759, -1, 35, 37, 758, -1, 255, 760, 253, -1, 275, 329, 331, -1, 353, 355, 468, -1, 275, 277, 329, -1, 291, 756, 289, -1, 245, 247, 761, -1, 257, 760, 255, -1, 243, 245, 761, -1, 243, 761, 763, -1, 764, 765, 760, -1, 764, 760, 257, -1, 241, 243, 763, -1, 423, 766, 767, -1, 768, 765, 764, -1, 423, 425, 766, -1, 131, 133, 468, -1, 75, 77, 91, -1, 423, 767, 345, -1, 75, 91, 93, -1, 75, 93, 95, -1, 427, 769, 766, -1, 135, 468, 133, -1, 427, 766, 425, -1, 79, 91, 77, -1, 421, 345, 347, -1, 79, 87, 89, -1, 79, 89, 91, -1, 421, 423, 345, -1, 239, 763, 770, -1, 129, 131, 468, -1, 429, 752, 769, -1, 239, 241, 763, -1, 429, 769, 427, -1, 137, 468, 135, -1, 771, 765, 768, -1, 771, 772, 765, -1, 419, 421, 347, -1, 73, 95, 53, -1, 73, 53, 55, -1, 73, 75, 95, -1, 237, 239, 770, -1, 419, 347, 773, -1, 127, 129, 468, -1, 139, 353, 468, -1, 139, 468, 137, -1, 774, 775, 772, -1, 774, 772, 771, -1, 139, 351, 353, -1, 81, 87, 79, -1, 125, 127, 468, -1, 71, 55, 776, -1, 777, 350, 351, -1, 777, 351, 139, -1, 778, 779, 775, -1, 71, 73, 55, -1, 778, 775, 774, -1, 780, 781, 350, -1, 780, 350, 777, -1, 83, 87, 81, -1, 782, 783, 781, -1, 782, 781, 780, -1, 83, 784, 86, -1, 83, 86, 87, -1, 785, 783, 782, -1, 785, 786, 783, -1, 69, 71, 776, -1, 69, 776, 787, -1, 788, 786, 785, -1, 789, 784, 83, -1, 193, 205, 207, -1, 67, 787, 790, -1, 67, 69, 787, -1, 223, 271, 273, -1, 791, 792, 784, -1, 791, 784, 789, -1, 191, 207, 209, -1, 65, 67, 790, -1, 65, 790, 793, -1, 191, 193, 207, -1, 221, 223, 273, -1, 794, 792, 791, -1, 195, 204, 205, -1, 221, 273, 275, -1, 311, 795, 796, -1, 161, 119, 121, -1, 195, 205, 193, -1, 794, 797, 792, -1, 311, 313, 795, -1, 63, 65, 793, -1, 225, 271, 223, -1, 63, 793, 798, -1, 159, 121, 123, -1, 159, 161, 121, -1, 195, 799, 204, -1, 315, 291, 795, -1, 189, 209, 211, -1, 315, 756, 291, -1, 800, 797, 794, -1, 315, 795, 313, -1, 163, 115, 117, -1, 800, 801, 802, -1, 189, 191, 209, -1, 163, 117, 119, -1, 800, 802, 797, -1, 163, 119, 161, -1, 61, 798, 803, -1, 157, 123, 125, -1, 157, 159, 123, -1, 61, 63, 798, -1, 804, 801, 800, -1, 219, 221, 275, -1, 804, 750, 801, -1, 197, 799, 195, -1, 219, 275, 331, -1, 59, 803, 805, -1, 165, 115, 163, -1, 309, 311, 796, -1, 197, 806, 799, -1, 155, 125, 468, -1, 59, 61, 803, -1, 187, 211, 213, -1, 751, 750, 804, -1, 155, 157, 125, -1, 58, 805, 807, -1, 187, 189, 211, -1, 227, 269, 271, -1, 187, 213, 808, -1, 227, 271, 225, -1, 167, 809, 114, -1, 58, 59, 805, -1, 167, 114, 115, -1, 167, 115, 165, -1, 317, 756, 315, -1, 317, 419, 773, -1, 725, 807, 726, -1, 725, 58, 807, -1, 199, 806, 197, -1, 317, 417, 419, -1, 317, 773, 756, -1, 199, 261, 810, -1, 199, 260, 261, -1, 811, 809, 167, -1, 199, 810, 806, -1, 217, 812, 813, -1, 217, 331, 333, -1, 217, 219, 331, -1, 217, 333, 812, -1, 201, 260, 199, -1, 307, 309, 796, -1, 814, 815, 809, -1, 185, 187, 808, -1, 307, 796, 816, -1, 814, 809, 811, -1, 185, 808, 703, -1, 229, 269, 227, -1, 817, 237, 770, -1, 319, 417, 317, -1, 818, 819, 815, -1, 818, 815, 814, -1, 817, 235, 237, -1, 817, 260, 201, -1, 21, 35, 762, -1, 319, 415, 417, -1, 817, 770, 260, -1, 183, 699, 820, -1, 19, 21, 762, -1, 821, 819, 818, -1, 19, 762, 822, -1, 215, 813, 823, -1, 821, 824, 819, -1, 183, 703, 699, -1, 215, 217, 813, -1, 305, 307, 816, -1, 183, 185, 703, -1, 23, 31, 33, -1, 825, 826, 824, -1, 23, 33, 35, -1, 825, 824, 821, -1, 827, 233, 235, -1, 23, 35, 21, -1, 827, 235, 817, -1, 181, 820, 828, -1, 823, 813, 826, -1, 829, 269, 229, -1, 17, 19, 822, -1, 823, 826, 825, -1, 17, 822, 830, -1, 181, 183, 820, -1, 831, 415, 319, -1, 179, 828, 832, -1, 179, 181, 828, -1, 833, 834, 232, -1, 25, 31, 23, -1, 833, 232, 233, -1, 833, 233, 827, -1, 213, 215, 823, -1, 213, 823, 808, -1, 15, 830, 835, -1, 836, 837, 834, -1, 836, 834, 833, -1, 15, 17, 830, -1, 303, 305, 816, -1, 177, 832, 838, -1, 27, 839, 30, -1, 470, 142, 143, -1, 27, 30, 31, -1, 470, 143, 145, -1, 470, 145, 147, -1, 470, 147, 149, -1, 470, 149, 151, -1, 470, 151, 153, -1, 177, 179, 832, -1, 470, 153, 155, -1, 27, 31, 25, -1, 470, 155, 468, -1, 840, 841, 837, -1, 840, 837, 836, -1, 842, 269, 829, -1, 13, 15, 835, -1, 13, 835, 170, -1, 843, 415, 831, -1, 175, 177, 838, -1, 844, 839, 27, -1, 845, 841, 840, -1, 843, 413, 415, -1, 173, 838, 846, -1, 847, 848, 849, -1, 11, 13, 170, -1, 173, 175, 838, -1, 11, 170, 171, -1, 850, 851, 852, -1, 850, 848, 847, -1, 850, 852, 848, -1, 853, 854, 855, -1, 853, 855, 839, -1, 464, 470, 851, -1, 464, 851, 850, -1, 853, 839, 844, -1, 856, 413, 843, -1, 341, 857, 858, -1, 856, 411, 413, -1, 859, 726, 854, -1, 267, 269, 842, -1, 859, 854, 853, -1, 267, 842, 860, -1, 339, 341, 858, -1, 861, 303, 816, -1, 339, 858, 862, -1, 861, 301, 303, -1, 343, 857, 341, -1, 343, 863, 857, -1, 299, 301, 861, -1, 722, 726, 859, -1, 337, 339, 862, -1, 337, 862, 864, -1, 865, 267, 860, -1, 866, 411, 856, -1, 345, 767, 863, -1, 345, 863, 343, -1, 335, 337, 864, -1, 866, 409, 411, -1, 105, 867, 868, -1, 335, 864, 786, -1, 335, 786, 788, -1, 103, 105, 868, -1, 297, 299, 861, -1, 333, 788, 812, -1, 103, 868, 779, -1, 107, 867, 105, -1, 869, 267, 865, -1, 107, 407, 870, -1, 107, 870, 867, -1, 333, 335, 788, -1, 870, 407, 409, -1, 107, 406, 407, -1, 870, 409, 866, -1, 101, 779, 778, -1, 101, 103, 779, -1, 109, 406, 107, -1, 109, 871, 406, -1, 99, 778, 872, -1, 397, 873, 2, -1, 99, 101, 778, -1, 111, 871, 109, -1, 111, 462, 755, -1, 111, 755, 871, -1, 395, 2, 3, -1, 395, 3, 5, -1, 97, 872, 874, -1, 395, 397, 2, -1, 97, 99, 872, -1, 399, 875, 873, -1, 876, 462, 111, -1, 399, 873, 397, -1, 393, 395, 5, -1, 95, 874, 877, -1, 393, 5, 7, -1, 95, 97, 874, -1, 878, 462, 876, -1, 401, 879, 875, -1, 401, 875, 399, -1, 880, 462, 878, -1, 391, 7, 9, -1, 391, 393, 7, -1, 881, 462, 880, -1, 403, 882, 879, -1, 403, 879, 401, -1, 389, 391, 9, -1, 389, 9, 11, -1, 883, 462, 881, -1, 265, 267, 869, -1, 389, 11, 171, -1, 451, 453, 470, -1, 455, 142, 470, -1, 265, 869, 884, -1, 885, 886, 882, -1, 265, 884, 887, -1, 885, 882, 403, -1, 749, 462, 883, -1, 888, 297, 861, -1, 455, 470, 453, -1, 888, 889, 294, -1, 888, 294, 295, -1, 888, 295, 297, -1, 449, 451, 470, -1, 387, 389, 171, -1, 449, 470, 464, -1, 457, 142, 455, -1, 263, 265, 887, -1, 387, 171, 173, -1, 263, 887, 890, -1, 387, 173, 846, -1, 263, 890, 891, -1, 892, 889, 888, -1, 893, 894, 886, -1, 457, 895, 142, -1, 892, 896, 897, -1, 892, 897, 889, -1, 893, 886, 885, -1, 447, 449, 464, -1, 385, 846, 898, -1, 472, 431, 899, -1, 472, 899, 900, -1, 459, 895, 457, -1, 472, 900, 901, -1, 385, 387, 846, -1, 472, 901, 902, -1, 727, 894, 893, -1, 472, 902, 903, -1, 472, 903, 904, -1, 727, 724, 894, -1, 472, 904, 905, -1, 472, 905, 746, -1, 459, 906, 895, -1, 49, 907, 841, -1, 908, 896, 892, -1, 445, 447, 464, -1, 383, 898, 909, -1, 908, 910, 896, -1, 261, 263, 891, -1, 383, 385, 898, -1, 49, 841, 845, -1, 911, 906, 459, -1, 261, 891, 810, -1, 911, 912, 906, -1, 443, 445, 464, -1, 47, 49, 845, -1, 381, 909, 913, -1, 381, 913, 747, -1, 381, 383, 909, -1, 47, 845, 914, -1, 701, 912, 911, -1, 701, 700, 912, -1, 51, 877, 907, -1, 441, 443, 464, -1, 379, 381, 747, -1, 51, 907, 49, -1, 283, 698, 915, -1, 283, 915, 916, -1, 283, 916, 917, -1, 45, 47, 914, -1, 775, 910, 908, -1, 775, 779, 910, -1, 45, 914, 702, -1, 281, 917, 918, -1, 281, 918, 322, -1, 281, 322, 323, -1, 281, 283, 917, -1, 53, 877, 51, -1, 285, 721, 919, -1, 53, 95, 877, -1, 285, 919, 698, -1, 851, 469, 630, -1, 851, 470, 469, -1, 852, 630, 628, -1, 852, 851, 630, -1, 848, 628, 625, -1, 848, 852, 628, -1, 849, 625, 627, -1, 849, 848, 625, -1, 847, 627, 626, -1, 847, 849, 627, -1, 850, 626, 629, -1, 850, 847, 626, -1, 464, 629, 467, -1, 464, 850, 629, -1, 738, 465, 516, -1, 738, 466, 465, -1, 742, 516, 521, -1, 742, 738, 516, -1, 745, 521, 523, -1, 745, 742, 521, -1, 744, 523, 522, -1, 744, 745, 523, -1, 743, 522, 517, -1, 743, 744, 522, -1, 737, 517, 515, -1, 737, 743, 517, -1, 460, 515, 463, -1, 460, 737, 515, -1, 739, 461, 519, -1, 739, 462, 461, -1, 732, 519, 513, -1, 732, 739, 519, -1, 733, 513, 512, -1, 733, 732, 513, -1, 734, 512, 514, -1, 734, 733, 512, -1, 740, 514, 518, -1, 740, 734, 514, -1, 741, 518, 520, -1, 741, 740, 518, -1, 472, 520, 475, -1, 472, 741, 520, -1, 718, 473, 496, -1, 718, 474, 473, -1, 705, 496, 486, -1, 705, 718, 496, -1, 706, 486, 482, -1, 706, 705, 486, -1, 707, 482, 484, -1, 707, 706, 482, -1, 708, 484, 483, -1, 708, 707, 484, -1, 714, 483, 492, -1, 714, 708, 483, -1, 468, 492, 471, -1, 468, 714, 492, -1, 458, 689, 459, -1, 459, 689, 911, -1, 911, 479, 701, -1, 689, 479, 911, -1, 701, 478, 699, -1, 479, 478, 701, -1, 699, 598, 820, -1, 478, 598, 699, -1, 820, 606, 828, -1, 598, 606, 820, -1, 828, 610, 832, -1, 606, 610, 828, -1, 832, 616, 838, -1, 610, 616, 832, -1, 838, 624, 846, -1, 616, 624, 838, -1, 846, 676, 898, -1, 624, 676, 846, -1, 898, 688, 909, -1, 676, 688, 898, -1, 909, 691, 913, -1, 688, 691, 909, -1, 913, 524, 747, -1, 691, 524, 913, -1, 747, 432, 434, -1, 524, 432, 747, -1, 430, 677, 431, -1, 431, 677, 899, -1, 899, 678, 900, -1, 677, 678, 899, -1, 900, 679, 901, -1, 678, 679, 900, -1, 901, 680, 902, -1, 679, 680, 901, -1, 902, 681, 903, -1, 680, 681, 902, -1, 903, 682, 904, -1, 681, 682, 903, -1, 904, 683, 905, -1, 682, 683, 904, -1, 905, 525, 746, -1, 683, 525, 905, -1, 746, 530, 753, -1, 525, 530, 746, -1, 753, 532, 754, -1, 530, 532, 753, -1, 754, 533, 755, -1, 532, 533, 754, -1, 755, 649, 871, -1, 533, 649, 755, -1, 871, 404, 406, -1, 649, 404, 871, -1, 402, 665, 403, -1, 403, 665, 885, -1, 885, 672, 893, -1, 665, 672, 885, -1, 893, 503, 727, -1, 672, 503, 893, -1, 727, 506, 728, -1, 503, 506, 727, -1, 728, 487, 709, -1, 506, 487, 728, -1, 709, 488, 710, -1, 487, 488, 709, -1, 710, 489, 711, -1, 488, 489, 710, -1, 711, 490, 712, -1, 489, 490, 711, -1, 712, 491, 713, -1, 490, 491, 712, -1, 713, 493, 715, -1, 491, 493, 713, -1, 715, 494, 716, -1, 493, 494, 715, -1, 716, 495, 717, -1, 494, 495, 716, -1, 717, 376, 378, -1, 495, 376, 717, -1, 374, 527, 375, -1, 375, 527, 752, -1, 752, 546, 769, -1, 527, 546, 752, -1, 769, 544, 766, -1, 546, 544, 769, -1, 766, 545, 767, -1, 544, 545, 766, -1, 767, 641, 863, -1, 545, 641, 767, -1, 863, 635, 857, -1, 641, 635, 863, -1, 857, 636, 858, -1, 635, 636, 857, -1, 858, 640, 862, -1, 636, 640, 858, -1, 862, 642, 864, -1, 640, 642, 862, -1, 864, 564, 786, -1, 642, 564, 864, -1, 786, 560, 783, -1, 564, 560, 786, -1, 783, 558, 781, -1, 560, 558, 783, -1, 781, 348, 350, -1, 558, 348, 781, -1, 346, 551, 347, -1, 347, 551, 773, -1, 773, 534, 756, -1, 551, 534, 773, -1, 756, 535, 757, -1, 534, 535, 756, -1, 757, 497, 719, -1, 535, 497, 757, -1, 719, 498, 720, -1, 497, 498, 719, -1, 720, 499, 721, -1, 498, 499, 720, -1, 721, 697, 919, -1, 499, 697, 721, -1, 919, 476, 698, -1, 697, 476, 919, -1, 698, 693, 915, -1, 476, 693, 698, -1, 915, 694, 916, -1, 693, 694, 915, -1, 916, 695, 917, -1, 694, 695, 916, -1, 917, 696, 918, -1, 695, 696, 917, -1, 918, 320, 322, -1, 696, 320, 918, -1, 318, 609, 319, -1, 319, 609, 831, -1, 831, 621, 843, -1, 609, 621, 831, -1, 843, 634, 856, -1, 621, 634, 843, -1, 856, 644, 866, -1, 634, 644, 856, -1, 866, 648, 870, -1, 644, 648, 866, -1, 870, 645, 867, -1, 648, 645, 870, -1, 867, 646, 868, -1, 645, 646, 867, -1, 868, 557, 779, -1, 646, 557, 868, -1, 779, 687, 910, -1, 557, 687, 779, -1, 910, 674, 896, -1, 687, 674, 910, -1, 896, 675, 897, -1, 674, 675, 896, -1, 897, 667, 889, -1, 675, 667, 897, -1, 889, 292, 294, -1, 667, 292, 889, -1, 290, 573, 291, -1, 291, 573, 795, -1, 795, 574, 796, -1, 573, 574, 795, -1, 796, 594, 816, -1, 574, 594, 796, -1, 816, 639, 861, -1, 594, 639, 816, -1, 861, 666, 888, -1, 639, 666, 861, -1, 888, 670, 892, -1, 666, 670, 888, -1, 892, 686, 908, -1, 670, 686, 892, -1, 908, 552, 775, -1, 686, 552, 908, -1, 775, 549, 772, -1, 552, 549, 775, -1, 772, 542, 765, -1, 549, 542, 772, -1, 765, 538, 760, -1, 542, 538, 765, -1, 760, 536, 759, -1, 538, 536, 760, -1, 759, 539, 761, -1, 536, 539, 759, -1, 761, 541, 763, -1, 539, 541, 761, -1, 763, 548, 770, -1, 541, 548, 763, -1, 548, 258, 770, -1, 770, 258, 260, -1, 256, 543, 257, -1, 257, 543, 764, -1, 764, 547, 768, -1, 543, 547, 764, -1, 768, 550, 771, -1, 547, 550, 768, -1, 771, 553, 774, -1, 550, 553, 771, -1, 774, 556, 778, -1, 553, 556, 774, -1, 778, 650, 872, -1, 556, 650, 778, -1, 872, 652, 874, -1, 650, 652, 872, -1, 874, 655, 877, -1, 652, 655, 874, -1, 877, 685, 907, -1, 655, 685, 877, -1, 907, 618, 841, -1, 685, 618, 907, -1, 841, 615, 837, -1, 618, 615, 841, -1, 837, 611, 834, -1, 615, 611, 837, -1, 834, 230, 232, -1, 611, 230, 834, -1, 228, 607, 229, -1, 229, 607, 829, -1, 829, 620, 842, -1, 607, 620, 829, -1, 842, 638, 860, -1, 620, 638, 842, -1, 860, 643, 865, -1, 638, 643, 860, -1, 865, 647, 869, -1, 643, 647, 865, -1, 869, 662, 884, -1, 647, 662, 869, -1, 884, 663, 887, -1, 662, 663, 884, -1, 887, 668, 890, -1, 663, 668, 887, -1, 890, 669, 891, -1, 668, 669, 890, -1, 891, 588, 810, -1, 669, 588, 891, -1, 810, 584, 806, -1, 588, 584, 810, -1, 806, 577, 799, -1, 584, 577, 806, -1, 799, 202, 204, -1, 577, 202, 799, -1, 200, 597, 201, -1, 201, 597, 817, -1, 817, 605, 827, -1, 597, 605, 817, -1, 827, 612, 833, -1, 605, 612, 827, -1, 833, 613, 836, -1, 612, 613, 833, -1, 836, 619, 840, -1, 613, 619, 836, -1, 840, 622, 845, -1, 619, 622, 840, -1, 845, 692, 914, -1, 622, 692, 845, -1, 914, 481, 702, -1, 692, 481, 914, -1, 702, 485, 704, -1, 481, 485, 702, -1, 704, 526, 748, -1, 485, 526, 704, -1, 748, 537, 758, -1, 526, 537, 748, -1, 758, 540, 762, -1, 537, 540, 758, -1, 762, 600, 822, -1, 540, 600, 762, -1, 822, 608, 830, -1, 600, 608, 822, -1, 830, 614, 835, -1, 608, 614, 830, -1, 614, 168, 835, -1, 835, 168, 170, -1, 166, 589, 167, -1, 167, 589, 811, -1, 811, 593, 814, -1, 589, 593, 811, -1, 814, 596, 818, -1, 593, 596, 814, -1, 818, 599, 821, -1, 596, 599, 818, -1, 821, 604, 825, -1, 599, 604, 821, -1, 825, 601, 823, -1, 604, 601, 825, -1, 823, 586, 808, -1, 601, 586, 823, -1, 808, 480, 703, -1, 586, 480, 808, -1, 703, 477, 700, -1, 480, 477, 703, -1, 700, 690, 912, -1, 477, 690, 700, -1, 912, 684, 906, -1, 690, 684, 912, -1, 906, 673, 895, -1, 684, 673, 906, -1, 895, 140, 142, -1, 673, 140, 895, -1, 138, 555, 139, -1, 139, 555, 777, -1, 777, 559, 780, -1, 555, 559, 777, -1, 780, 561, 782, -1, 559, 561, 780, -1, 782, 563, 785, -1, 561, 563, 782, -1, 785, 566, 788, -1, 563, 566, 785, -1, 788, 590, 812, -1, 566, 590, 788, -1, 812, 591, 813, -1, 590, 591, 812, -1, 813, 603, 826, -1, 591, 603, 813, -1, 826, 602, 824, -1, 603, 602, 826, -1, 824, 595, 819, -1, 602, 595, 824, -1, 819, 592, 815, -1, 595, 592, 819, -1, 815, 587, 809, -1, 592, 587, 815, -1, 809, 112, 114, -1, 587, 112, 809, -1, 110, 654, 111, -1, 111, 654, 876, -1, 876, 656, 878, -1, 654, 656, 876, -1, 878, 658, 880, -1, 656, 658, 878, -1, 880, 660, 881, -1, 658, 660, 880, -1, 881, 661, 883, -1, 660, 661, 881, -1, 883, 528, 749, -1, 661, 528, 883, -1, 749, 529, 750, -1, 528, 529, 749, -1, 750, 579, 801, -1, 529, 579, 750, -1, 801, 580, 802, -1, 579, 580, 801, -1, 802, 575, 797, -1, 580, 575, 802, -1, 797, 569, 792, -1, 575, 569, 797, -1, 792, 562, 784, -1, 569, 562, 792, -1, 784, 84, 86, -1, 562, 84, 784, -1, 82, 567, 83, -1, 83, 567, 789, -1, 789, 570, 791, -1, 567, 570, 789, -1, 791, 572, 794, -1, 570, 572, 791, -1, 794, 578, 800, -1, 572, 578, 794, -1, 800, 582, 804, -1, 578, 582, 800, -1, 804, 531, 751, -1, 582, 531, 804, -1, 751, 507, 729, -1, 531, 507, 751, -1, 729, 508, 730, -1, 507, 508, 729, -1, 730, 509, 731, -1, 508, 509, 730, -1, 731, 510, 735, -1, 509, 510, 731, -1, 735, 511, 736, -1, 510, 511, 735, -1, 736, 504, 725, -1, 511, 504, 736, -1, 725, 56, 58, -1, 504, 56, 725, -1, 54, 554, 55, -1, 55, 554, 776, -1, 776, 565, 787, -1, 554, 565, 776, -1, 787, 568, 790, -1, 565, 568, 787, -1, 790, 571, 793, -1, 568, 571, 790, -1, 793, 576, 798, -1, 571, 576, 793, -1, 798, 581, 803, -1, 576, 581, 798, -1, 803, 583, 805, -1, 581, 583, 803, -1, 805, 585, 807, -1, 583, 585, 805, -1, 807, 505, 726, -1, 585, 505, 807, -1, 726, 631, 854, -1, 505, 631, 726, -1, 854, 633, 855, -1, 631, 633, 854, -1, 855, 617, 839, -1, 633, 617, 855, -1, 839, 28, 30, -1, 617, 28, 839, -1, 26, 623, 27, -1, 27, 623, 844, -1, 844, 632, 853, -1, 623, 632, 844, -1, 853, 637, 859, -1, 632, 637, 853, -1, 859, 500, 722, -1, 637, 500, 859, -1, 722, 501, 723, -1, 500, 501, 722, -1, 723, 502, 724, -1, 501, 502, 723, -1, 724, 671, 894, -1, 502, 671, 724, -1, 894, 664, 886, -1, 671, 664, 894, -1, 886, 659, 882, -1, 664, 659, 886, -1, 882, 657, 879, -1, 659, 657, 882, -1, 879, 653, 875, -1, 657, 653, 879, -1, 875, 651, 873, -1, 653, 651, 875, -1, 873, 0, 2, -1, 651, 0, 873, -1, 920, 921, 922, -1, 922, 921, 923, -1, 923, 924, 925, -1, 921, 924, 923, -1, 925, 926, 927, -1, 924, 926, 925, -1, 927, 928, 929, -1, 926, 928, 927, -1, 929, 930, 931, -1, 928, 930, 929, -1, 931, 932, 933, -1, 930, 932, 931, -1, 933, 934, 935, -1, 932, 934, 933, -1, 935, 936, 937, -1, 934, 936, 935, -1, 937, 938, 939, -1, 936, 938, 937, -1, 939, 940, 941, -1, 938, 940, 939, -1, 941, 942, 943, -1, 940, 942, 941, -1, 943, 944, 945, -1, 942, 944, 943, -1, 945, 946, 947, -1, 944, 946, 945, -1, 948, 949, 950, -1, 950, 949, 951, -1, 951, 952, 953, -1, 949, 952, 951, -1, 953, 954, 955, -1, 952, 954, 953, -1, 955, 956, 957, -1, 954, 956, 955, -1, 957, 958, 959, -1, 956, 958, 957, -1, 959, 960, 961, -1, 958, 960, 959, -1, 961, 962, 963, -1, 960, 962, 961, -1, 963, 964, 965, -1, 962, 964, 963, -1, 965, 966, 967, -1, 964, 966, 965, -1, 967, 968, 969, -1, 966, 968, 967, -1, 969, 970, 971, -1, 968, 970, 969, -1, 971, 972, 973, -1, 970, 972, 971, -1, 973, 974, 975, -1, 972, 974, 973, -1, 976, 977, 978, -1, 978, 977, 979, -1, 979, 980, 981, -1, 977, 980, 979, -1, 981, 982, 983, -1, 980, 982, 981, -1, 983, 984, 985, -1, 982, 984, 983, -1, 985, 986, 987, -1, 984, 986, 985, -1, 987, 988, 989, -1, 986, 988, 987, -1, 989, 990, 991, -1, 988, 990, 989, -1, 991, 992, 993, -1, 990, 992, 991, -1, 993, 994, 995, -1, 992, 994, 993, -1, 995, 996, 997, -1, 994, 996, 995, -1, 997, 998, 999, -1, 996, 998, 997, -1, 999, 1000, 1001, -1, 998, 1000, 999, -1, 1001, 1002, 1003, -1, 1000, 1002, 1001, -1, 1004, 1005, 1006, -1, 1006, 1005, 1007, -1, 1007, 1008, 1009, -1, 1005, 1008, 1007, -1, 1009, 1010, 1011, -1, 1008, 1010, 1009, -1, 1011, 1012, 1013, -1, 1010, 1012, 1011, -1, 1013, 1014, 1015, -1, 1012, 1014, 1013, -1, 1015, 1016, 1017, -1, 1014, 1016, 1015, -1, 1017, 1018, 1019, -1, 1016, 1018, 1017, -1, 1019, 1020, 1021, -1, 1018, 1020, 1019, -1, 1021, 1022, 1023, -1, 1020, 1022, 1021, -1, 1023, 1024, 1025, -1, 1022, 1024, 1023, -1, 1025, 1026, 1027, -1, 1024, 1026, 1025, -1, 1027, 1028, 1029, -1, 1026, 1028, 1027, -1, 1029, 1030, 1031, -1, 1028, 1030, 1029, -1, 1032, 1033, 1034, -1, 1034, 1033, 1035, -1, 1035, 1036, 1037, -1, 1033, 1036, 1035, -1, 1037, 1038, 1039, -1, 1036, 1038, 1037, -1, 1039, 1040, 1041, -1, 1038, 1040, 1039, -1, 1041, 1042, 1043, -1, 1040, 1042, 1041, -1, 1043, 1044, 1045, -1, 1042, 1044, 1043, -1, 1045, 1046, 1047, -1, 1044, 1046, 1045, -1, 1047, 1048, 1049, -1, 1046, 1048, 1047, -1, 1049, 1050, 1051, -1, 1048, 1050, 1049, -1, 1051, 1052, 1053, -1, 1050, 1052, 1051, -1, 1053, 1054, 1055, -1, 1052, 1054, 1053, -1, 1055, 1056, 1057, -1, 1054, 1056, 1055, -1, 1057, 1058, 1059, -1, 1056, 1058, 1057, -1, 1060, 1061, 1062, -1, 1062, 1061, 1063, -1, 1063, 1064, 1065, -1, 1061, 1064, 1063, -1, 1065, 1066, 1067, -1, 1064, 1066, 1065, -1, 1067, 1068, 1069, -1, 1066, 1068, 1067, -1, 1069, 1070, 1071, -1, 1068, 1070, 1069, -1, 1071, 1072, 1073, -1, 1070, 1072, 1071, -1, 1073, 1074, 1075, -1, 1072, 1074, 1073, -1, 1075, 1076, 1077, -1, 1074, 1076, 1075, -1, 1077, 1078, 1079, -1, 1076, 1078, 1077, -1, 1079, 1080, 1081, -1, 1078, 1080, 1079, -1, 1081, 1082, 1083, -1, 1080, 1082, 1081, -1, 1083, 1084, 1085, -1, 1082, 1084, 1083, -1, 1085, 1086, 1087, -1, 1084, 1086, 1085, -1, 1088, 1089, 1090, -1, 1090, 1089, 1091, -1, 1091, 1092, 1093, -1, 1089, 1092, 1091, -1, 1093, 1094, 1095, -1, 1092, 1094, 1093, -1, 1095, 1096, 1097, -1, 1094, 1096, 1095, -1, 1097, 1098, 1099, -1, 1096, 1098, 1097, -1, 1099, 1100, 1101, -1, 1098, 1100, 1099, -1, 1101, 1102, 1103, -1, 1100, 1102, 1101, -1, 1103, 1104, 1105, -1, 1102, 1104, 1103, -1, 1105, 1106, 1107, -1, 1104, 1106, 1105, -1, 1107, 1108, 1109, -1, 1106, 1108, 1107, -1, 1109, 1110, 1111, -1, 1108, 1110, 1109, -1, 1111, 1112, 1113, -1, 1110, 1112, 1111, -1, 1113, 1114, 1115, -1, 1112, 1114, 1113, -1, 1116, 1117, 1118, -1, 1118, 1117, 1119, -1, 1119, 1120, 1121, -1, 1117, 1120, 1119, -1, 1121, 1122, 1123, -1, 1120, 1122, 1121, -1, 1123, 1124, 1125, -1, 1122, 1124, 1123, -1, 1125, 1126, 1127, -1, 1124, 1126, 1125, -1, 1127, 1128, 1129, -1, 1126, 1128, 1127, -1, 1129, 1130, 1131, -1, 1128, 1130, 1129, -1, 1131, 1132, 1133, -1, 1130, 1132, 1131, -1, 1133, 1134, 1135, -1, 1132, 1134, 1133, -1, 1135, 1136, 1137, -1, 1134, 1136, 1135, -1, 1137, 1138, 1139, -1, 1136, 1138, 1137, -1, 1139, 1140, 1141, -1, 1138, 1140, 1139, -1, 1141, 1142, 1143, -1, 1140, 1142, 1141, -1, 1144, 1145, 1146, -1, 1147, 1145, 1144, -1, 1148, 1149, 1150, -1, 1148, 1151, 1149, -1, 1152, 1153, 1154, -1, 1155, 1153, 1152, -1, 1156, 1157, 1158, -1, 1159, 1157, 1156, -1, 1160, 1114, 1112, -1, 1145, 1147, 1161, -1, 1145, 1161, 1162, -1, 1145, 1162, 1163, -1, 1161, 1147, 1164, -1, 1165, 1166, 1167, -1, 1165, 1168, 1166, -1, 1169, 1157, 1155, -1, 1166, 1157, 1169, -1, 1170, 1157, 1168, -1, 1168, 1157, 1166, -1, 1052, 1050, 1157, -1, 1157, 1054, 1052, -1, 1050, 1048, 1157, -1, 1157, 1056, 1054, -1, 1048, 1046, 1157, -1, 1157, 1058, 1056, -1, 1114, 1159, 1171, -1, 1171, 1159, 1172, -1, 1046, 1044, 1157, -1, 1172, 1159, 1173, -1, 1173, 1159, 1174, -1, 1174, 1159, 1175, -1, 1175, 1159, 1176, -1, 1176, 1159, 1177, -1, 1177, 1159, 1178, -1, 1157, 1042, 1155, -1, 1044, 1042, 1157, -1, 1179, 1180, 1159, -1, 1181, 1180, 1179, -1, 1042, 1040, 1155, -1, 1040, 1038, 1155, -1, 1182, 1183, 1184, -1, 1038, 1036, 1155, -1, 1184, 1145, 1180, -1, 1159, 1145, 1178, -1, 1180, 1145, 1159, -1, 1183, 1145, 1184, -1, 1178, 1145, 1185, -1, 1185, 1145, 1186, -1, 1186, 1145, 1187, -1, 1089, 996, 1092, -1, 996, 994, 1092, -1, 1092, 994, 1094, -1, 1089, 998, 996, -1, 1088, 998, 1089, -1, 968, 966, 1155, -1, 994, 992, 1094, -1, 1094, 992, 1096, -1, 1155, 970, 968, -1, 966, 964, 1155, -1, 1088, 1000, 998, -1, 1188, 1000, 1088, -1, 1155, 972, 970, -1, 1096, 990, 1189, -1, 1189, 990, 1190, -1, 992, 990, 1096, -1, 964, 962, 1155, -1, 1145, 1002, 1187, -1, 1188, 1002, 1000, -1, 1187, 1002, 1188, -1, 1155, 974, 972, -1, 1033, 974, 1036, -1, 1190, 988, 1191, -1, 990, 988, 1190, -1, 1036, 974, 1155, -1, 962, 960, 1155, -1, 1033, 1192, 974, -1, 1145, 1193, 1002, -1, 1032, 1192, 1033, -1, 1194, 1195, 1032, -1, 1145, 1196, 1193, -1, 1032, 1195, 1192, -1, 1145, 1197, 1196, -1, 1198, 1199, 1194, -1, 1194, 1199, 1195, -1, 1198, 1200, 1199, -1, 1201, 1200, 1198, -1, 1145, 1202, 1197, -1, 1201, 1203, 1200, -1, 1189, 1203, 1201, -1, 1145, 1204, 1202, -1, 1189, 1190, 1203, -1, 1145, 1163, 1204, -1, 982, 1024, 984, -1, 954, 938, 956, -1, 956, 938, 958, -1, 1024, 1022, 984, -1, 940, 938, 954, -1, 952, 942, 954, -1, 954, 942, 940, -1, 958, 936, 960, -1, 938, 936, 958, -1, 980, 1026, 982, -1, 952, 944, 942, -1, 982, 1026, 1024, -1, 1022, 1020, 984, -1, 984, 1020, 986, -1, 949, 944, 952, -1, 960, 934, 1155, -1, 936, 934, 960, -1, 980, 1028, 1026, -1, 948, 946, 949, -1, 976, 1028, 977, -1, 977, 1028, 980, -1, 949, 946, 944, -1, 988, 1018, 1191, -1, 1020, 1018, 986, -1, 986, 1018, 988, -1, 948, 1205, 946, -1, 1206, 1205, 948, -1, 1191, 1018, 1207, -1, 976, 1030, 1028, -1, 1208, 1209, 1210, -1, 1210, 1209, 1206, -1, 1206, 1209, 1205, -1, 1207, 1016, 1211, -1, 1018, 1016, 1207, -1, 1211, 1016, 1212, -1, 1208, 1213, 1209, -1, 1214, 1213, 1208, -1, 1215, 1216, 1217, -1, 1217, 1216, 976, -1, 976, 1216, 1030, -1, 1214, 1218, 1213, -1, 1219, 1220, 1214, -1, 1221, 1222, 1215, -1, 1215, 1222, 1216, -1, 1214, 1220, 1218, -1, 1191, 1207, 1219, -1, 1219, 1207, 1220, -1, 1221, 1223, 1222, -1, 1224, 1225, 1221, -1, 1221, 1225, 1223, -1, 920, 1153, 921, -1, 921, 1153, 924, -1, 1224, 1226, 1225, -1, 924, 1153, 926, -1, 1162, 1226, 1227, -1, 926, 1153, 928, -1, 1227, 1226, 1224, -1, 928, 1153, 930, -1, 930, 1153, 932, -1, 932, 1153, 934, -1, 934, 1153, 1155, -1, 1162, 1161, 1226, -1, 1228, 1229, 1230, -1, 1229, 1231, 1232, -1, 1153, 1231, 1228, -1, 1228, 1231, 1229, -1, 1231, 1148, 1233, -1, 1153, 1148, 1231, -1, 1136, 1134, 1153, -1, 1153, 1138, 1136, -1, 920, 1138, 1153, -1, 1153, 1132, 1148, -1, 1134, 1132, 1153, -1, 1234, 1140, 920, -1, 1012, 1080, 1014, -1, 920, 1140, 1138, -1, 1080, 1078, 1014, -1, 1132, 1130, 1148, -1, 1212, 1078, 1235, -1, 1016, 1078, 1212, -1, 1236, 1142, 1234, -1, 1014, 1078, 1016, -1, 1234, 1142, 1140, -1, 1012, 1082, 1080, -1, 1130, 1128, 1148, -1, 1010, 1082, 1012, -1, 1078, 1076, 1235, -1, 1237, 1238, 1236, -1, 1236, 1238, 1142, -1, 1128, 1126, 1148, -1, 1237, 1239, 1238, -1, 1240, 1239, 1237, -1, 1010, 1084, 1082, -1, 1008, 1084, 1010, -1, 1126, 1124, 1148, -1, 1076, 1074, 1235, -1, 1241, 1242, 1240, -1, 1240, 1242, 1239, -1, 1235, 1074, 1243, -1, 1243, 1074, 1244, -1, 1124, 1122, 1148, -1, 1211, 1212, 1241, -1, 1008, 1086, 1084, -1, 1241, 1212, 1242, -1, 1005, 1086, 1008, -1, 1122, 1120, 1148, -1, 1074, 1072, 1244, -1, 1244, 1072, 1245, -1, 1120, 1117, 1148, -1, 1005, 1246, 1086, -1, 1117, 1116, 1148, -1, 1004, 1246, 1005, -1, 1072, 1070, 1245, -1, 1004, 1247, 1246, -1, 1070, 1068, 1245, -1, 1245, 1068, 1248, -1, 1249, 1106, 1250, -1, 1248, 1066, 1251, -1, 1250, 1106, 1252, -1, 1068, 1066, 1248, -1, 1066, 1064, 1251, -1, 1108, 1106, 1249, -1, 1251, 1064, 1253, -1, 1254, 1110, 1249, -1, 1249, 1110, 1108, -1, 1064, 1061, 1253, -1, 1253, 1061, 1255, -1, 1106, 1104, 1252, -1, 1160, 1112, 1254, -1, 1254, 1112, 1110, -1, 1252, 1102, 1256, -1, 1256, 1102, 1257, -1, 1104, 1102, 1252, -1, 1102, 1100, 1257, -1, 1247, 1147, 1258, -1, 1258, 1147, 1259, -1, 1259, 1147, 1260, -1, 1004, 1147, 1247, -1, 1164, 1147, 1261, -1, 1261, 1147, 1262, -1, 1262, 1147, 1263, -1, 1263, 1147, 1264, -1, 1264, 1147, 1265, -1, 1265, 1147, 1004, -1, 1260, 1151, 1266, -1, 1100, 1098, 1257, -1, 1266, 1151, 1267, -1, 1267, 1151, 1268, -1, 1257, 1098, 1269, -1, 1268, 1151, 1270, -1, 1269, 1098, 1189, -1, 1270, 1151, 1271, -1, 1271, 1151, 1272, -1, 1272, 1151, 1273, -1, 1273, 1151, 1060, -1, 1147, 1151, 1260, -1, 1147, 1274, 1151, -1, 1151, 1274, 1275, -1, 1098, 1096, 1189, -1, 1276, 1277, 1147, -1, 1278, 1277, 1276, -1, 1147, 1279, 1274, -1, 1277, 1279, 1147, -1, 1151, 1148, 1116, -1, 1151, 1116, 1255, -1, 1151, 1255, 1060, -1, 1060, 1255, 1061, -1, 1157, 1159, 1058, -1, 1058, 1159, 1160, -1, 1160, 1159, 1114, -1, 1280, 1144, 1149, -1, 1097, 1099, 1281, -1, 1280, 1149, 1282, -1, 1283, 1284, 1285, -1, 1286, 1144, 1280, -1, 1287, 1284, 1283, -1, 1286, 1280, 1288, -1, 1286, 1289, 1290, -1, 1286, 1290, 1144, -1, 1150, 1149, 1118, -1, 1118, 1149, 1291, -1, 1291, 1149, 1062, -1, 1291, 1062, 1063, -1, 1144, 1146, 1292, -1, 1292, 1146, 1293, -1, 1293, 1146, 1294, -1, 1144, 1292, 1295, -1, 1156, 1158, 1059, -1, 1156, 1059, 1296, -1, 1156, 1296, 1115, -1, 1115, 1296, 1113, -1, 1158, 1297, 1287, -1, 1158, 1283, 1298, -1, 1158, 1298, 1152, -1, 1158, 1287, 1283, -1, 1051, 1053, 1158, -1, 1055, 1158, 1053, -1, 1049, 1051, 1158, -1, 1057, 1158, 1055, -1, 1047, 1049, 1158, -1, 1059, 1158, 1057, -1, 1045, 1047, 1158, -1, 1156, 1115, 1299, -1, 1156, 1299, 1300, -1, 1156, 1300, 1301, -1, 1156, 1301, 1302, -1, 1156, 1302, 1303, -1, 1156, 1303, 1304, -1, 1043, 1158, 1152, -1, 1156, 1304, 1305, -1, 1156, 1305, 1306, -1, 1043, 1045, 1158, -1, 1041, 1043, 1152, -1, 1307, 1308, 1309, -1, 1307, 1309, 1156, -1, 1039, 1041, 1152, -1, 1037, 1039, 1152, -1, 1310, 1311, 1312, -1, 1146, 1312, 1307, -1, 1146, 1156, 1306, -1, 1146, 1307, 1156, -1, 1146, 1310, 1312, -1, 1146, 1306, 1313, -1, 1146, 1313, 1314, -1, 1146, 1314, 1315, -1, 997, 1091, 1093, -1, 995, 997, 1093, -1, 995, 1093, 1095, -1, 999, 1091, 997, -1, 967, 969, 1152, -1, 971, 1152, 969, -1, 999, 1090, 1091, -1, 993, 995, 1095, -1, 993, 1095, 1097, -1, 965, 967, 1152, -1, 973, 1152, 971, -1, 1001, 1090, 999, -1, 1001, 1316, 1090, -1, 991, 1281, 1317, -1, 963, 965, 1152, -1, 991, 993, 1097, -1, 991, 1097, 1281, -1, 975, 1152, 973, -1, 975, 1035, 1037, -1, 1003, 1146, 1315, -1, 975, 1037, 1152, -1, 961, 963, 1152, -1, 1003, 1316, 1001, -1, 1003, 1315, 1316, -1, 989, 1317, 1318, -1, 989, 991, 1317, -1, 1319, 1034, 1035, -1, 1319, 1035, 975, -1, 1320, 1146, 1003, -1, 1321, 1322, 1034, -1, 1323, 1146, 1320, -1, 1321, 1034, 1319, -1, 1324, 1325, 1322, -1, 1326, 1146, 1323, -1, 1324, 1322, 1321, -1, 1327, 1325, 1324, -1, 1327, 1328, 1325, -1, 1329, 1146, 1326, -1, 1330, 1328, 1327, -1, 1330, 1281, 1328, -1, 1331, 1146, 1329, -1, 1317, 1281, 1330, -1, 1294, 1146, 1331, -1, 939, 955, 957, -1, 939, 941, 955, -1, 943, 953, 955, -1, 1025, 983, 985, -1, 943, 955, 941, -1, 937, 957, 959, -1, 937, 939, 957, -1, 945, 951, 953, -1, 1023, 1025, 985, -1, 945, 953, 943, -1, 935, 961, 1152, -1, 935, 937, 959, -1, 935, 959, 961, -1, 1027, 981, 983, -1, 947, 950, 951, -1, 1027, 983, 1025, -1, 947, 951, 945, -1, 1021, 985, 987, -1, 1021, 1023, 985, -1, 1332, 1333, 950, -1, 1029, 981, 1027, -1, 1029, 979, 981, -1, 1029, 978, 979, -1, 1332, 950, 947, -1, 1334, 1335, 1333, -1, 1019, 989, 1318, -1, 1334, 1336, 1335, -1, 1019, 987, 989, -1, 1334, 1333, 1332, -1, 1019, 1318, 1337, -1, 1019, 1021, 987, -1, 1338, 1336, 1334, -1, 1338, 1339, 1336, -1, 1031, 978, 1029, -1, 1017, 1019, 1337, -1, 1017, 1337, 1340, -1, 1017, 1340, 1341, -1, 1342, 1339, 1338, -1, 1343, 978, 1031, -1, 1343, 1344, 978, -1, 1343, 1345, 1344, -1, 1346, 1347, 1339, -1, 1346, 1339, 1342, -1, 1337, 1347, 1346, -1, 1337, 1318, 1347, -1, 1348, 1345, 1343, -1, 1349, 1345, 1348, -1, 1349, 1350, 1345, -1, 1154, 933, 935, -1, 1351, 1350, 1349, -1, 1154, 931, 933, -1, 1154, 929, 931, -1, 1154, 927, 929, -1, 1351, 1352, 1350, -1, 1154, 925, 927, -1, 1351, 1353, 1352, -1, 1154, 923, 925, -1, 1154, 922, 923, -1, 1154, 935, 1152, -1, 1354, 1353, 1351, -1, 1354, 1293, 1353, -1, 1355, 1356, 1357, -1, 1292, 1293, 1354, -1, 1358, 1356, 1355, -1, 1358, 1154, 1356, -1, 1358, 1355, 1359, -1, 1150, 1358, 1360, -1, 1150, 1154, 1358, -1, 1135, 1137, 1154, -1, 1139, 1154, 1137, -1, 1139, 922, 1154, -1, 1133, 1154, 1150, -1, 1133, 1135, 1154, -1, 1141, 1361, 922, -1, 1141, 922, 1139, -1, 1131, 1133, 1150, -1, 1081, 1013, 1015, -1, 1143, 1362, 1361, -1, 1143, 1361, 1141, -1, 1129, 1131, 1150, -1, 1079, 1081, 1015, -1, 1079, 1017, 1341, -1, 1363, 1364, 1362, -1, 1079, 1015, 1017, -1, 1079, 1341, 1365, -1, 1363, 1362, 1143, -1, 1083, 1013, 1081, -1, 1127, 1129, 1150, -1, 1083, 1011, 1013, -1, 1366, 1367, 1364, -1, 1366, 1364, 1363, -1, 1077, 1079, 1365, -1, 1125, 1127, 1150, -1, 1368, 1369, 1367, -1, 1368, 1367, 1366, -1, 1085, 1011, 1083, -1, 1123, 1125, 1150, -1, 1085, 1009, 1011, -1, 1341, 1340, 1369, -1, 1341, 1369, 1368, -1, 1075, 1077, 1365, -1, 1121, 1123, 1150, -1, 1075, 1365, 1370, -1, 1075, 1370, 1371, -1, 1087, 1009, 1085, -1, 1119, 1121, 1150, -1, 1087, 1007, 1009, -1, 1073, 1075, 1371, -1, 1118, 1119, 1150, -1, 1073, 1371, 1372, -1, 1373, 1007, 1087, -1, 1373, 1006, 1007, -1, 1071, 1073, 1372, -1, 1374, 1006, 1373, -1, 1069, 1071, 1372, -1, 1107, 1375, 1376, -1, 1107, 1376, 1377, -1, 1069, 1372, 1378, -1, 1107, 1109, 1375, -1, 1067, 1069, 1378, -1, 1111, 1379, 1375, -1, 1067, 1378, 1380, -1, 1111, 1375, 1109, -1, 1065, 1067, 1380, -1, 1065, 1380, 1381, -1, 1105, 1107, 1377, -1, 1113, 1296, 1379, -1, 1113, 1379, 1111, -1, 1103, 1377, 1382, -1, 1103, 1382, 1383, -1, 1063, 1065, 1381, -1, 1063, 1381, 1291, -1, 1103, 1105, 1377, -1, 1101, 1103, 1383, -1, 1144, 1374, 1384, -1, 1144, 1384, 1385, -1, 1099, 1383, 1386, -1, 1144, 1385, 1387, -1, 1099, 1386, 1281, -1, 1099, 1101, 1383, -1, 1144, 1006, 1374, -1, 1144, 1388, 1006, -1, 1144, 1389, 1388, -1, 1144, 1390, 1389, -1, 1144, 1391, 1390, -1, 1144, 1392, 1391, -1, 1144, 1295, 1392, -1, 1149, 1387, 1393, -1, 1149, 1393, 1394, -1, 1149, 1394, 1395, -1, 1149, 1395, 1396, -1, 1149, 1396, 1397, -1, 1149, 1397, 1398, -1, 1149, 1398, 1399, -1, 1149, 1399, 1062, -1, 1149, 1144, 1387, -1, 1356, 1153, 1228, -1, 1356, 1154, 1153, -1, 1357, 1228, 1230, -1, 1357, 1356, 1228, -1, 1355, 1230, 1229, -1, 1355, 1357, 1230, -1, 1359, 1229, 1232, -1, 1359, 1355, 1229, -1, 1358, 1232, 1231, -1, 1358, 1359, 1232, -1, 1360, 1231, 1233, -1, 1360, 1358, 1231, -1, 1150, 1233, 1148, -1, 1150, 1360, 1233, -1, 1282, 1151, 1275, -1, 1282, 1149, 1151, -1, 1280, 1275, 1274, -1, 1280, 1282, 1275, -1, 1288, 1274, 1279, -1, 1288, 1280, 1274, -1, 1286, 1279, 1277, -1, 1286, 1288, 1279, -1, 1289, 1277, 1278, -1, 1289, 1286, 1277, -1, 1290, 1278, 1276, -1, 1290, 1289, 1278, -1, 1144, 1276, 1147, -1, 1144, 1290, 1276, -1, 1310, 1145, 1183, -1, 1310, 1146, 1145, -1, 1311, 1183, 1182, -1, 1311, 1310, 1183, -1, 1312, 1182, 1184, -1, 1312, 1311, 1182, -1, 1307, 1184, 1180, -1, 1307, 1312, 1184, -1, 1308, 1180, 1181, -1, 1308, 1307, 1180, -1, 1309, 1181, 1179, -1, 1309, 1308, 1181, -1, 1156, 1179, 1159, -1, 1156, 1309, 1179, -1, 1297, 1157, 1170, -1, 1297, 1158, 1157, -1, 1287, 1170, 1168, -1, 1287, 1297, 1170, -1, 1284, 1168, 1165, -1, 1284, 1287, 1168, -1, 1285, 1165, 1167, -1, 1285, 1284, 1165, -1, 1283, 1167, 1166, -1, 1283, 1285, 1167, -1, 1298, 1166, 1169, -1, 1298, 1283, 1166, -1, 1152, 1169, 1155, -1, 1152, 1298, 1169, -1, 1142, 1238, 1143, -1, 1143, 1238, 1363, -1, 1363, 1239, 1366, -1, 1238, 1239, 1363, -1, 1366, 1242, 1368, -1, 1239, 1242, 1366, -1, 1368, 1212, 1341, -1, 1242, 1212, 1368, -1, 1341, 1235, 1365, -1, 1212, 1235, 1341, -1, 1365, 1243, 1370, -1, 1235, 1243, 1365, -1, 1370, 1244, 1371, -1, 1243, 1244, 1370, -1, 1371, 1245, 1372, -1, 1244, 1245, 1371, -1, 1372, 1248, 1378, -1, 1245, 1248, 1372, -1, 1378, 1251, 1380, -1, 1248, 1251, 1378, -1, 1380, 1253, 1381, -1, 1251, 1253, 1380, -1, 1381, 1255, 1291, -1, 1253, 1255, 1381, -1, 1291, 1116, 1118, -1, 1255, 1116, 1291, -1, 1114, 1171, 1115, -1, 1115, 1171, 1299, -1, 1299, 1172, 1300, -1, 1171, 1172, 1299, -1, 1300, 1173, 1301, -1, 1172, 1173, 1300, -1, 1301, 1174, 1302, -1, 1173, 1174, 1301, -1, 1302, 1175, 1303, -1, 1174, 1175, 1302, -1, 1303, 1176, 1304, -1, 1175, 1176, 1303, -1, 1304, 1177, 1305, -1, 1176, 1177, 1304, -1, 1305, 1178, 1306, -1, 1177, 1178, 1305, -1, 1306, 1185, 1313, -1, 1178, 1185, 1306, -1, 1313, 1186, 1314, -1, 1185, 1186, 1313, -1, 1314, 1187, 1315, -1, 1186, 1187, 1314, -1, 1315, 1188, 1316, -1, 1187, 1188, 1315, -1, 1316, 1088, 1090, -1, 1188, 1088, 1316, -1, 1086, 1246, 1087, -1, 1087, 1246, 1373, -1, 1373, 1247, 1374, -1, 1246, 1247, 1373, -1, 1374, 1258, 1384, -1, 1247, 1258, 1374, -1, 1384, 1259, 1385, -1, 1258, 1259, 1384, -1, 1385, 1260, 1387, -1, 1259, 1260, 1385, -1, 1387, 1266, 1393, -1, 1260, 1266, 1387, -1, 1393, 1267, 1394, -1, 1266, 1267, 1393, -1, 1394, 1268, 1395, -1, 1267, 1268, 1394, -1, 1395, 1270, 1396, -1, 1268, 1270, 1395, -1, 1396, 1271, 1397, -1, 1270, 1271, 1396, -1, 1397, 1272, 1398, -1, 1271, 1272, 1397, -1, 1398, 1273, 1399, -1, 1272, 1273, 1398, -1, 1399, 1060, 1062, -1, 1273, 1060, 1399, -1, 1058, 1160, 1059, -1, 1059, 1160, 1296, -1, 1296, 1254, 1379, -1, 1160, 1254, 1296, -1, 1379, 1249, 1375, -1, 1254, 1249, 1379, -1, 1375, 1250, 1376, -1, 1249, 1250, 1375, -1, 1376, 1252, 1377, -1, 1250, 1252, 1376, -1, 1377, 1256, 1382, -1, 1252, 1256, 1377, -1, 1382, 1257, 1383, -1, 1256, 1257, 1382, -1, 1383, 1269, 1386, -1, 1257, 1269, 1383, -1, 1386, 1189, 1281, -1, 1269, 1189, 1386, -1, 1281, 1201, 1328, -1, 1189, 1201, 1281, -1, 1328, 1198, 1325, -1, 1201, 1198, 1328, -1, 1325, 1194, 1322, -1, 1198, 1194, 1325, -1, 1322, 1032, 1034, -1, 1194, 1032, 1322, -1, 1030, 1216, 1031, -1, 1031, 1216, 1343, -1, 1343, 1222, 1348, -1, 1216, 1222, 1343, -1, 1348, 1223, 1349, -1, 1222, 1223, 1348, -1, 1349, 1225, 1351, -1, 1223, 1225, 1349, -1, 1351, 1226, 1354, -1, 1225, 1226, 1351, -1, 1354, 1161, 1292, -1, 1226, 1161, 1354, -1, 1292, 1164, 1295, -1, 1161, 1164, 1292, -1, 1295, 1261, 1392, -1, 1164, 1261, 1295, -1, 1392, 1262, 1391, -1, 1261, 1262, 1392, -1, 1391, 1263, 1390, -1, 1262, 1263, 1391, -1, 1390, 1264, 1389, -1, 1263, 1264, 1390, -1, 1389, 1265, 1388, -1, 1264, 1265, 1389, -1, 1388, 1004, 1006, -1, 1265, 1004, 1388, -1, 1002, 1193, 1003, -1, 1003, 1193, 1320, -1, 1320, 1196, 1323, -1, 1193, 1196, 1320, -1, 1323, 1197, 1326, -1, 1196, 1197, 1323, -1, 1326, 1202, 1329, -1, 1197, 1202, 1326, -1, 1329, 1204, 1331, -1, 1202, 1204, 1329, -1, 1331, 1163, 1294, -1, 1204, 1163, 1331, -1, 1294, 1162, 1293, -1, 1163, 1162, 1294, -1, 1293, 1227, 1353, -1, 1162, 1227, 1293, -1, 1353, 1224, 1352, -1, 1227, 1224, 1353, -1, 1352, 1221, 1350, -1, 1224, 1221, 1352, -1, 1350, 1215, 1345, -1, 1221, 1215, 1350, -1, 1345, 1217, 1344, -1, 1215, 1217, 1345, -1, 1344, 976, 978, -1, 1217, 976, 1344, -1, 974, 1192, 975, -1, 975, 1192, 1319, -1, 1319, 1195, 1321, -1, 1192, 1195, 1319, -1, 1321, 1199, 1324, -1, 1195, 1199, 1321, -1, 1324, 1200, 1327, -1, 1199, 1200, 1324, -1, 1327, 1203, 1330, -1, 1200, 1203, 1327, -1, 1330, 1190, 1317, -1, 1203, 1190, 1330, -1, 1317, 1191, 1318, -1, 1190, 1191, 1317, -1, 1318, 1219, 1347, -1, 1191, 1219, 1318, -1, 1347, 1214, 1339, -1, 1219, 1214, 1347, -1, 1339, 1208, 1336, -1, 1214, 1208, 1339, -1, 1336, 1210, 1335, -1, 1208, 1210, 1336, -1, 1335, 1206, 1333, -1, 1210, 1206, 1335, -1, 1333, 948, 950, -1, 1206, 948, 1333, -1, 946, 1205, 947, -1, 947, 1205, 1332, -1, 1332, 1209, 1334, -1, 1205, 1209, 1332, -1, 1334, 1213, 1338, -1, 1209, 1213, 1334, -1, 1338, 1218, 1342, -1, 1213, 1218, 1338, -1, 1342, 1220, 1346, -1, 1218, 1220, 1342, -1, 1346, 1207, 1337, -1, 1220, 1207, 1346, -1, 1337, 1211, 1340, -1, 1207, 1211, 1337, -1, 1340, 1241, 1369, -1, 1211, 1241, 1340, -1, 1369, 1240, 1367, -1, 1241, 1240, 1369, -1, 1367, 1237, 1364, -1, 1240, 1237, 1367, -1, 1364, 1236, 1362, -1, 1237, 1236, 1364, -1, 1362, 1234, 1361, -1, 1236, 1234, 1362, -1, 1361, 920, 922, -1, 1234, 920, 1361, -1, 1400, 1401, 1402, -1, 1400, 1402, 1403, -1, 1404, 1405, 1406, -1, 1404, 1406, 1407, -1, 1408, 1409, 1410, -1, 1408, 1410, 1411, -1, 1412, 1413, 1414, -1, 1412, 1414, 1415, -1, 1416, 1417, 1418, -1, 1419, 1420, 1417, -1, 1421, 1422, 1423, -1, 1419, 1417, 1416, -1, 1424, 1423, 1425, -1, 1403, 1426, 1421, -1, 1403, 1421, 1423, -1, 1404, 1423, 1424, -1, 1404, 1403, 1423, -1, 1427, 1403, 1404, -1, 1427, 1428, 1403, -1, 1400, 1428, 1429, -1, 1400, 1429, 1430, -1, 1400, 1403, 1428, -1, 1431, 1432, 1433, -1, 1431, 1433, 1434, -1, 1435, 1436, 1431, -1, 1435, 1434, 1400, -1, 1435, 1431, 1434, -1, 1413, 1400, 1430, -1, 1413, 1435, 1400, -1, 1437, 1438, 1439, -1, 1440, 1441, 1438, -1, 1440, 1437, 1442, -1, 1440, 1438, 1437, -1, 1410, 1407, 1441, -1, 1410, 1441, 1440, -1, 1443, 1404, 1407, -1, 1443, 1427, 1404, -1, 1443, 1407, 1410, -1, 1444, 1443, 1410, -1, 1445, 1430, 1427, -1, 1445, 1413, 1430, -1, 1445, 1427, 1443, -1, 1409, 1446, 1444, -1, 1409, 1444, 1410, -1, 1409, 1445, 1446, -1, 1414, 1413, 1445, -1, 1414, 1445, 1409, -1, 1447, 1414, 1409, -1, 1420, 1447, 1409, -1, 1420, 1409, 1417, -1, 1448, 1449, 1450, -1, 1451, 1452, 1453, -1, 1450, 1454, 1455, -1, 1449, 1454, 1450, -1, 1455, 1454, 1456, -1, 1453, 1457, 1458, -1, 1459, 1402, 1452, -1, 1452, 1402, 1453, -1, 1453, 1405, 1457, -1, 1402, 1405, 1453, -1, 1402, 1460, 1405, -1, 1461, 1460, 1402, -1, 1461, 1401, 1462, -1, 1462, 1401, 1463, -1, 1402, 1401, 1461, -1, 1464, 1465, 1466, -1, 1467, 1465, 1464, -1, 1466, 1468, 1401, -1, 1469, 1468, 1465, -1, 1465, 1468, 1466, -1, 1401, 1412, 1463, -1, 1468, 1412, 1401, -1, 1470, 1471, 1472, -1, 1471, 1473, 1474, -1, 1475, 1473, 1470, -1, 1470, 1473, 1471, -1, 1406, 1411, 1475, -1, 1475, 1411, 1473, -1, 1405, 1476, 1406, -1, 1460, 1476, 1405, -1, 1406, 1476, 1411, -1, 1476, 1477, 1411, -1, 1463, 1478, 1460, -1, 1412, 1478, 1463, -1, 1460, 1478, 1476, -1, 1412, 1415, 1478, -1, 1479, 1408, 1477, -1, 1477, 1408, 1411, -1, 1478, 1408, 1479, -1, 1415, 1408, 1478, -1, 1408, 1450, 1455, -1, 1415, 1450, 1408, -1, 1457, 1404, 1424, -1, 1457, 1405, 1404, -1, 1458, 1424, 1425, -1, 1458, 1457, 1424, -1, 1453, 1425, 1423, -1, 1453, 1458, 1425, -1, 1451, 1423, 1422, -1, 1451, 1453, 1423, -1, 1452, 1422, 1421, -1, 1452, 1451, 1422, -1, 1459, 1421, 1426, -1, 1459, 1452, 1421, -1, 1402, 1426, 1403, -1, 1402, 1459, 1426, -1, 1473, 1410, 1440, -1, 1473, 1411, 1410, -1, 1474, 1440, 1442, -1, 1474, 1473, 1440, -1, 1471, 1442, 1437, -1, 1471, 1474, 1442, -1, 1472, 1437, 1439, -1, 1472, 1471, 1437, -1, 1470, 1439, 1438, -1, 1470, 1472, 1439, -1, 1475, 1438, 1441, -1, 1475, 1470, 1438, -1, 1406, 1441, 1407, -1, 1406, 1475, 1441, -1, 1415, 1414, 1447, -1, 1450, 1447, 1420, -1, 1450, 1415, 1447, -1, 1448, 1420, 1419, -1, 1448, 1450, 1420, -1, 1449, 1419, 1416, -1, 1449, 1448, 1419, -1, 1454, 1416, 1418, -1, 1454, 1449, 1416, -1, 1456, 1418, 1417, -1, 1456, 1454, 1418, -1, 1455, 1417, 1409, -1, 1455, 1456, 1417, -1, 1408, 1455, 1409, -1, 1401, 1400, 1434, -1, 1466, 1434, 1433, -1, 1466, 1401, 1434, -1, 1464, 1433, 1432, -1, 1464, 1466, 1433, -1, 1467, 1432, 1431, -1, 1467, 1464, 1432, -1, 1465, 1431, 1436, -1, 1465, 1467, 1431, -1, 1469, 1436, 1435, -1, 1469, 1465, 1436, -1, 1468, 1469, 1435, -1, 1412, 1435, 1413, -1, 1412, 1468, 1435, -1, 1427, 1461, 1428, -1, 1460, 1461, 1427, -1, 1461, 1462, 1428, -1, 1462, 1429, 1428, -1, 1429, 1463, 1430, -1, 1462, 1463, 1429, -1, 1427, 1430, 1460, -1, 1430, 1463, 1460, -1, 1444, 1446, 1477, -1, 1446, 1479, 1477, -1, 1477, 1443, 1444, -1, 1477, 1476, 1443, -1, 1476, 1445, 1443, -1, 1476, 1478, 1445, -1, 1445, 1479, 1446, -1, 1478, 1479, 1445, -1, 1480, 1481, 1482, -1, 1481, 1483, 1482, -1, 1482, 1484, 1485, -1, 1483, 1484, 1482, -1, 1485, 1486, 1487, -1, 1484, 1486, 1485, -1, 1487, 1488, 1489, -1, 1486, 1488, 1487, -1, 1489, 1490, 1491, -1, 1488, 1490, 1489, -1, 1491, 1492, 1493, -1, 1490, 1492, 1491, -1, 1493, 1494, 1495, -1, 1492, 1494, 1493, -1, 1495, 1496, 1497, -1, 1494, 1496, 1495, -1, 1497, 1498, 1499, -1, 1496, 1498, 1497, -1, 1499, 1500, 1501, -1, 1498, 1500, 1499, -1, 1501, 1502, 1503, -1, 1500, 1502, 1501, -1, 1503, 1504, 1505, -1, 1502, 1504, 1503, -1, 1505, 1506, 1507, -1, 1504, 1506, 1505, -1, 1480, 1482, 1508, -1, 1508, 1482, 1509, -1, 1509, 1485, 1510, -1, 1482, 1485, 1509, -1, 1510, 1487, 1511, -1, 1485, 1487, 1510, -1, 1511, 1489, 1512, -1, 1487, 1489, 1511, -1, 1512, 1491, 1513, -1, 1489, 1491, 1512, -1, 1513, 1493, 1514, -1, 1491, 1493, 1513, -1, 1514, 1495, 1515, -1, 1493, 1495, 1514, -1, 1515, 1497, 1516, -1, 1495, 1497, 1515, -1, 1516, 1499, 1517, -1, 1497, 1499, 1516, -1, 1517, 1501, 1518, -1, 1499, 1501, 1517, -1, 1518, 1503, 1519, -1, 1501, 1503, 1518, -1, 1519, 1505, 1520, -1, 1503, 1505, 1519, -1, 1520, 1507, 1521, -1, 1505, 1507, 1520, -1, 1522, 1523, 1524, -1, 1525, 1526, 1527, -1, 1528, 1524, 1529, -1, 1528, 1522, 1524, -1, 1530, 1529, 1531, -1, 1530, 1528, 1529, -1, 1532, 1533, 1534, -1, 1532, 1534, 1535, -1, 1536, 1535, 1537, -1, 1536, 1537, 1538, -1, 1539, 1526, 1525, -1, 1536, 1532, 1535, -1, 1539, 1540, 1541, -1, 1539, 1525, 1540, -1, 1542, 1543, 1533, -1, 1544, 1545, 1546, -1, 1542, 1533, 1532, -1, 1544, 1530, 1531, -1, 1547, 1538, 1548, -1, 1547, 1536, 1538, -1, 1544, 1531, 1545, -1, 1549, 1550, 1543, -1, 1551, 1552, 1526, -1, 1549, 1543, 1542, -1, 1551, 1553, 1552, -1, 1551, 1554, 1553, -1, 1551, 1526, 1539, -1, 1555, 1547, 1548, -1, 1556, 1539, 1541, -1, 1557, 1550, 1549, -1, 1558, 1555, 1548, -1, 1559, 1550, 1557, -1, 1560, 1558, 1548, -1, 1561, 1550, 1559, -1, 1562, 1563, 1544, -1, 1562, 1564, 1563, -1, 1562, 1544, 1546, -1, 1562, 1565, 1564, -1, 1566, 1567, 1568, -1, 1566, 1569, 1567, -1, 1570, 1571, 1565, -1, 1570, 1565, 1562, -1, 1572, 1566, 1568, -1, 1572, 1568, 1573, -1, 1574, 1575, 1571, -1, 1574, 1571, 1570, -1, 1576, 1572, 1573, -1, 1577, 1576, 1573, -1, 1577, 1573, 1575, -1, 1578, 1575, 1574, -1, 1578, 1577, 1575, -1, 1566, 1539, 1569, -1, 1569, 1539, 1556, -1, 1579, 1580, 1581, -1, 1579, 1581, 1582, -1, 1583, 1584, 1585, -1, 1583, 1586, 1584, -1, 1587, 1583, 1585, -1, 1587, 1588, 1589, -1, 1587, 1585, 1588, -1, 1590, 1591, 1586, -1, 1590, 1592, 1591, -1, 1590, 1586, 1583, -1, 1593, 1587, 1589, -1, 1593, 1589, 1594, -1, 1593, 1594, 1595, -1, 1596, 1597, 1592, -1, 1596, 1598, 1597, -1, 1596, 1592, 1590, -1, 1599, 1600, 1601, -1, 1599, 1595, 1600, -1, 1599, 1593, 1595, -1, 1602, 1603, 1598, -1, 1602, 1598, 1596, -1, 1604, 1599, 1601, -1, 1604, 1601, 1605, -1, 1606, 1603, 1602, -1, 1606, 1561, 1603, -1, 1607, 1608, 1609, -1, 1486, 1606, 1610, -1, 1611, 1609, 1604, -1, 1611, 1604, 1605, -1, 1611, 1607, 1609, -1, 1488, 1610, 1612, -1, 1488, 1486, 1610, -1, 1613, 1608, 1607, -1, 1484, 1561, 1606, -1, 1484, 1606, 1486, -1, 1614, 1560, 1548, -1, 1614, 1611, 1605, -1, 1614, 1605, 1560, -1, 1490, 1488, 1612, -1, 1615, 1616, 1608, -1, 1615, 1608, 1613, -1, 1492, 1490, 1612, -1, 1617, 1492, 1612, -1, 1618, 1616, 1615, -1, 1619, 1620, 1614, -1, 1619, 1614, 1548, -1, 1621, 1550, 1561, -1, 1621, 1483, 1481, -1, 1621, 1484, 1483, -1, 1621, 1561, 1484, -1, 1622, 1620, 1619, -1, 1494, 1492, 1617, -1, 1623, 1616, 1618, -1, 1624, 1621, 1481, -1, 1625, 1621, 1624, -1, 1626, 1616, 1623, -1, 1627, 1619, 1628, -1, 1627, 1622, 1619, -1, 1496, 1494, 1617, -1, 1629, 1626, 1623, -1, 1630, 1625, 1624, -1, 1630, 1631, 1625, -1, 1632, 1627, 1628, -1, 1632, 1628, 1633, -1, 1634, 1498, 1496, -1, 1634, 1496, 1617, -1, 1635, 1632, 1633, -1, 1636, 1626, 1629, -1, 1637, 1631, 1630, -1, 1637, 1638, 1631, -1, 1639, 1632, 1635, -1, 1500, 1498, 1634, -1, 1640, 1639, 1635, -1, 1641, 1638, 1637, -1, 1642, 1626, 1636, -1, 1643, 1642, 1636, -1, 1644, 1641, 1637, -1, 1645, 1639, 1640, -1, 1645, 1646, 1639, -1, 1647, 1641, 1644, -1, 1648, 1642, 1643, -1, 1649, 1502, 1500, -1, 1649, 1500, 1634, -1, 1650, 1646, 1645, -1, 1651, 1644, 1652, -1, 1651, 1647, 1644, -1, 1653, 1646, 1650, -1, 1504, 1502, 1649, -1, 1546, 1653, 1650, -1, 1580, 1652, 1654, -1, 1580, 1651, 1652, -1, 1655, 1653, 1546, -1, 1656, 1642, 1648, -1, 1656, 1648, 1657, -1, 1581, 1580, 1654, -1, 1658, 1656, 1657, -1, 1659, 1655, 1546, -1, 1545, 1659, 1546, -1, 1660, 1661, 1506, -1, 1660, 1506, 1504, -1, 1660, 1504, 1649, -1, 1662, 1663, 1664, -1, 1662, 1658, 1663, -1, 1662, 1656, 1658, -1, 1579, 1665, 1666, -1, 1579, 1667, 1665, -1, 1579, 1582, 1667, -1, 1668, 1666, 1661, -1, 1668, 1661, 1660, -1, 1668, 1554, 1579, -1, 1668, 1579, 1666, -1, 1669, 1664, 1670, -1, 1669, 1662, 1664, -1, 1553, 1554, 1668, -1, 1531, 1669, 1670, -1, 1531, 1670, 1545, -1, 1671, 1672, 1673, -1, 1674, 1671, 1673, -1, 1675, 1672, 1671, -1, 1676, 1673, 1677, -1, 1676, 1674, 1673, -1, 1678, 1679, 1672, -1, 1678, 1672, 1675, -1, 1680, 1676, 1677, -1, 1681, 1679, 1678, -1, 1523, 1677, 1524, -1, 1523, 1680, 1677, -1, 1527, 1526, 1679, -1, 1527, 1679, 1681, -1, 1682, 1557, 1683, -1, 1557, 1549, 1683, -1, 1683, 1542, 1684, -1, 1549, 1542, 1683, -1, 1684, 1532, 1685, -1, 1542, 1532, 1684, -1, 1685, 1536, 1686, -1, 1532, 1536, 1685, -1, 1686, 1547, 1687, -1, 1536, 1547, 1686, -1, 1687, 1555, 1688, -1, 1547, 1555, 1687, -1, 1688, 1558, 1689, -1, 1555, 1558, 1688, -1, 1689, 1560, 1690, -1, 1558, 1560, 1689, -1, 1690, 1605, 1691, -1, 1560, 1605, 1690, -1, 1691, 1601, 1692, -1, 1605, 1601, 1691, -1, 1692, 1600, 1693, -1, 1601, 1600, 1692, -1, 1693, 1595, 1694, -1, 1600, 1595, 1693, -1, 1694, 1594, 1695, -1, 1595, 1594, 1694, -1, 1682, 1683, 1696, -1, 1696, 1683, 1697, -1, 1697, 1684, 1698, -1, 1683, 1684, 1697, -1, 1698, 1685, 1699, -1, 1684, 1685, 1698, -1, 1699, 1686, 1700, -1, 1685, 1686, 1699, -1, 1700, 1687, 1701, -1, 1686, 1687, 1700, -1, 1701, 1688, 1702, -1, 1687, 1688, 1701, -1, 1702, 1689, 1703, -1, 1688, 1689, 1702, -1, 1703, 1690, 1704, -1, 1689, 1690, 1703, -1, 1704, 1691, 1705, -1, 1690, 1691, 1704, -1, 1705, 1692, 1706, -1, 1691, 1692, 1705, -1, 1706, 1693, 1707, -1, 1692, 1693, 1706, -1, 1707, 1694, 1708, -1, 1693, 1694, 1707, -1, 1708, 1695, 1709, -1, 1694, 1695, 1708, -1, 1710, 1618, 1711, -1, 1618, 1615, 1711, -1, 1711, 1613, 1712, -1, 1615, 1613, 1711, -1, 1712, 1607, 1713, -1, 1613, 1607, 1712, -1, 1713, 1611, 1714, -1, 1607, 1611, 1713, -1, 1714, 1614, 1715, -1, 1611, 1614, 1714, -1, 1715, 1620, 1716, -1, 1614, 1620, 1715, -1, 1716, 1622, 1717, -1, 1620, 1622, 1716, -1, 1717, 1627, 1718, -1, 1622, 1627, 1717, -1, 1718, 1632, 1719, -1, 1627, 1632, 1718, -1, 1719, 1639, 1720, -1, 1632, 1639, 1719, -1, 1720, 1646, 1721, -1, 1639, 1646, 1720, -1, 1721, 1653, 1722, -1, 1722, 1653, 1723, -1, 1646, 1653, 1721, -1, 1653, 1655, 1723, -1, 1710, 1711, 1724, -1, 1724, 1711, 1725, -1, 1725, 1712, 1726, -1, 1711, 1712, 1725, -1, 1726, 1713, 1727, -1, 1712, 1713, 1726, -1, 1727, 1714, 1728, -1, 1713, 1714, 1727, -1, 1728, 1715, 1729, -1, 1714, 1715, 1728, -1, 1729, 1716, 1730, -1, 1715, 1716, 1729, -1, 1730, 1717, 1731, -1, 1716, 1717, 1730, -1, 1731, 1718, 1732, -1, 1717, 1718, 1731, -1, 1732, 1719, 1733, -1, 1718, 1719, 1732, -1, 1733, 1720, 1734, -1, 1719, 1720, 1733, -1, 1734, 1721, 1735, -1, 1720, 1721, 1734, -1, 1735, 1722, 1736, -1, 1721, 1722, 1735, -1, 1736, 1723, 1737, -1, 1722, 1723, 1736, -1, 1738, 1681, 1739, -1, 1681, 1678, 1739, -1, 1739, 1675, 1740, -1, 1678, 1675, 1739, -1, 1740, 1671, 1741, -1, 1675, 1671, 1740, -1, 1741, 1674, 1742, -1, 1671, 1674, 1741, -1, 1742, 1676, 1743, -1, 1674, 1676, 1742, -1, 1743, 1680, 1744, -1, 1676, 1680, 1743, -1, 1744, 1523, 1745, -1, 1680, 1523, 1744, -1, 1745, 1522, 1746, -1, 1523, 1522, 1745, -1, 1746, 1528, 1747, -1, 1522, 1528, 1746, -1, 1747, 1530, 1748, -1, 1528, 1530, 1747, -1, 1748, 1544, 1749, -1, 1530, 1544, 1748, -1, 1749, 1563, 1750, -1, 1750, 1563, 1751, -1, 1544, 1563, 1749, -1, 1563, 1564, 1751, -1, 1738, 1739, 1752, -1, 1752, 1739, 1753, -1, 1753, 1740, 1754, -1, 1739, 1740, 1753, -1, 1754, 1741, 1755, -1, 1740, 1741, 1754, -1, 1755, 1742, 1756, -1, 1741, 1742, 1755, -1, 1756, 1743, 1757, -1, 1742, 1743, 1756, -1, 1757, 1744, 1758, -1, 1743, 1744, 1757, -1, 1758, 1745, 1759, -1, 1744, 1745, 1758, -1, 1759, 1746, 1760, -1, 1745, 1746, 1759, -1, 1760, 1747, 1761, -1, 1746, 1747, 1760, -1, 1761, 1748, 1762, -1, 1747, 1748, 1761, -1, 1762, 1749, 1763, -1, 1748, 1749, 1762, -1, 1763, 1750, 1764, -1, 1749, 1750, 1763, -1, 1764, 1751, 1765, -1, 1750, 1751, 1764, -1, 1610, 1766, 1767, -1, 1610, 1606, 1766, -1, 1612, 1767, 1768, -1, 1612, 1610, 1767, -1, 1617, 1768, 1769, -1, 1617, 1612, 1768, -1, 1634, 1769, 1770, -1, 1634, 1617, 1769, -1, 1649, 1770, 1771, -1, 1649, 1634, 1770, -1, 1660, 1771, 1772, -1, 1660, 1649, 1771, -1, 1668, 1772, 1773, -1, 1668, 1660, 1772, -1, 1553, 1773, 1774, -1, 1553, 1668, 1773, -1, 1552, 1774, 1775, -1, 1552, 1553, 1774, -1, 1526, 1775, 1776, -1, 1526, 1552, 1775, -1, 1679, 1776, 1777, -1, 1679, 1526, 1776, -1, 1672, 1777, 1778, -1, 1672, 1679, 1777, -1, 1673, 1778, 1779, -1, 1673, 1672, 1778, -1, 1677, 1779, 1780, -1, 1677, 1673, 1779, -1, 1524, 1780, 1781, -1, 1524, 1677, 1780, -1, 1529, 1524, 1781, -1, 1529, 1781, 1782, -1, 1531, 1782, 1783, -1, 1531, 1529, 1782, -1, 1566, 1784, 1539, -1, 1539, 1784, 1785, -1, 1786, 1546, 1787, -1, 1562, 1546, 1786, -1, 1580, 1788, 1789, -1, 1579, 1788, 1580, -1, 1790, 1621, 1791, -1, 1550, 1621, 1790, -1, 1792, 1619, 1548, -1, 1793, 1619, 1792, -1, 1761, 1762, 1794, -1, 1795, 1785, 1796, -1, 1797, 1785, 1795, -1, 1798, 1785, 1797, -1, 1799, 1785, 1798, -1, 1800, 1785, 1801, -1, 1801, 1785, 1799, -1, 1785, 1802, 1796, -1, 1803, 1699, 1804, -1, 1805, 1699, 1803, -1, 1806, 1807, 1800, -1, 1808, 1807, 1806, -1, 1800, 1807, 1785, -1, 1809, 1700, 1810, -1, 1804, 1700, 1809, -1, 1699, 1700, 1804, -1, 1811, 1698, 1805, -1, 1807, 1812, 1785, -1, 1790, 1698, 1811, -1, 1805, 1698, 1699, -1, 1810, 1701, 1792, -1, 1700, 1701, 1810, -1, 1790, 1697, 1698, -1, 1701, 1702, 1792, -1, 1790, 1696, 1697, -1, 1702, 1703, 1792, -1, 1813, 1784, 1814, -1, 1802, 1784, 1813, -1, 1790, 1815, 1696, -1, 1785, 1784, 1802, -1, 1703, 1704, 1792, -1, 1816, 1786, 1765, -1, 1817, 1786, 1816, -1, 1818, 1786, 1787, -1, 1794, 1786, 1818, -1, 1763, 1786, 1762, -1, 1764, 1786, 1763, -1, 1765, 1786, 1764, -1, 1762, 1786, 1794, -1, 1790, 1819, 1815, -1, 1704, 1705, 1792, -1, 1817, 1820, 1786, -1, 1814, 1821, 1822, -1, 1790, 1823, 1819, -1, 1784, 1821, 1814, -1, 1705, 1706, 1792, -1, 1821, 1824, 1822, -1, 1817, 1825, 1820, -1, 1826, 1825, 1817, -1, 1824, 1827, 1822, -1, 1822, 1827, 1826, -1, 1826, 1828, 1825, -1, 1827, 1828, 1826, -1, 1829, 1830, 1831, -1, 1832, 1830, 1829, -1, 1833, 1830, 1832, -1, 1830, 1834, 1831, -1, 1835, 1834, 1709, -1, 1831, 1834, 1835, -1, 1833, 1836, 1830, -1, 1837, 1836, 1833, -1, 1838, 1836, 1837, -1, 1834, 1839, 1709, -1, 1708, 1839, 1707, -1, 1709, 1839, 1708, -1, 1838, 1840, 1836, -1, 1841, 1840, 1838, -1, 1842, 1840, 1841, -1, 1706, 1843, 1792, -1, 1839, 1843, 1707, -1, 1707, 1843, 1706, -1, 1790, 1844, 1823, -1, 1842, 1844, 1840, -1, 1823, 1844, 1842, -1, 1790, 1845, 1844, -1, 1843, 1846, 1792, -1, 1847, 1793, 1846, -1, 1846, 1793, 1792, -1, 1845, 1791, 1848, -1, 1790, 1791, 1845, -1, 1847, 1727, 1793, -1, 1791, 1511, 1848, -1, 1727, 1728, 1793, -1, 1848, 1512, 1849, -1, 1511, 1512, 1848, -1, 1850, 1726, 1847, -1, 1847, 1726, 1727, -1, 1791, 1510, 1511, -1, 1728, 1729, 1793, -1, 1512, 1513, 1849, -1, 1850, 1725, 1726, -1, 1791, 1509, 1510, -1, 1729, 1730, 1793, -1, 1849, 1514, 1851, -1, 1513, 1514, 1849, -1, 1791, 1508, 1509, -1, 1852, 1724, 1850, -1, 1850, 1724, 1725, -1, 1730, 1731, 1793, -1, 1514, 1515, 1851, -1, 1852, 1853, 1724, -1, 1791, 1854, 1508, -1, 1731, 1732, 1793, -1, 1793, 1732, 1855, -1, 1515, 1516, 1851, -1, 1852, 1856, 1853, -1, 1857, 1858, 1791, -1, 1859, 1858, 1857, -1, 1791, 1858, 1854, -1, 1732, 1733, 1855, -1, 1860, 1733, 1861, -1, 1855, 1733, 1860, -1, 1859, 1862, 1858, -1, 1863, 1862, 1859, -1, 1852, 1864, 1856, -1, 1856, 1864, 1865, -1, 1516, 1866, 1851, -1, 1517, 1866, 1516, -1, 1733, 1734, 1861, -1, 1517, 1518, 1866, -1, 1864, 1867, 1865, -1, 1734, 1868, 1861, -1, 1862, 1869, 1870, -1, 1863, 1869, 1862, -1, 1518, 1519, 1866, -1, 1864, 1871, 1867, -1, 1735, 1872, 1734, -1, 1734, 1872, 1868, -1, 1869, 1873, 1870, -1, 1735, 1874, 1872, -1, 1870, 1875, 1876, -1, 1873, 1875, 1870, -1, 1864, 1877, 1871, -1, 1878, 1877, 1879, -1, 1871, 1877, 1878, -1, 1520, 1880, 1519, -1, 1521, 1880, 1520, -1, 1519, 1880, 1866, -1, 1881, 1789, 1882, -1, 1876, 1789, 1881, -1, 1875, 1789, 1876, -1, 1736, 1787, 1735, -1, 1737, 1787, 1736, -1, 1883, 1787, 1737, -1, 1884, 1787, 1883, -1, 1885, 1787, 1884, -1, 1735, 1787, 1874, -1, 1877, 1886, 1879, -1, 1887, 1886, 1888, -1, 1879, 1886, 1887, -1, 1889, 1890, 1521, -1, 1521, 1890, 1880, -1, 1891, 1788, 1889, -1, 1892, 1788, 1891, -1, 1893, 1788, 1892, -1, 1894, 1788, 1893, -1, 1882, 1788, 1894, -1, 1889, 1788, 1890, -1, 1789, 1788, 1882, -1, 1886, 1895, 1888, -1, 1888, 1895, 1885, -1, 1885, 1895, 1787, -1, 1788, 1896, 1890, -1, 1895, 1818, 1787, -1, 1896, 1808, 1806, -1, 1897, 1808, 1788, -1, 1788, 1808, 1896, -1, 1755, 1756, 1898, -1, 1899, 1754, 1898, -1, 1898, 1754, 1755, -1, 1898, 1757, 1900, -1, 1756, 1757, 1898, -1, 1899, 1753, 1754, -1, 1757, 1758, 1900, -1, 1801, 1752, 1899, -1, 1899, 1752, 1753, -1, 1900, 1759, 1901, -1, 1758, 1759, 1900, -1, 1801, 1799, 1752, -1, 1759, 1760, 1901, -1, 1760, 1761, 1901, -1, 1901, 1761, 1794, -1, 1794, 1902, 1903, -1, 1794, 1818, 1902, -1, 1901, 1903, 1904, -1, 1901, 1794, 1903, -1, 1900, 1904, 1905, -1, 1900, 1901, 1904, -1, 1898, 1905, 1906, -1, 1898, 1900, 1905, -1, 1899, 1906, 1907, -1, 1899, 1898, 1906, -1, 1801, 1907, 1908, -1, 1801, 1899, 1907, -1, 1800, 1908, 1909, -1, 1800, 1801, 1908, -1, 1806, 1909, 1910, -1, 1806, 1800, 1909, -1, 1896, 1910, 1911, -1, 1896, 1806, 1910, -1, 1890, 1911, 1912, -1, 1890, 1896, 1911, -1, 1880, 1912, 1913, -1, 1880, 1890, 1912, -1, 1866, 1913, 1914, -1, 1866, 1880, 1913, -1, 1851, 1914, 1915, -1, 1851, 1866, 1914, -1, 1849, 1915, 1916, -1, 1849, 1851, 1915, -1, 1848, 1916, 1917, -1, 1848, 1849, 1916, -1, 1845, 1848, 1917, -1, 1845, 1917, 1918, -1, 1912, 1911, 1919, -1, 1920, 1917, 1921, -1, 1922, 1923, 1924, -1, 1925, 1926, 1927, -1, 1928, 1917, 1916, -1, 1929, 1917, 1928, -1, 1930, 1931, 1932, -1, 1921, 1917, 1929, -1, 1933, 1910, 1934, -1, 1935, 1936, 1937, -1, 1911, 1910, 1933, -1, 1937, 1938, 1935, -1, 1920, 1918, 1917, -1, 1939, 1918, 1920, -1, 1935, 1940, 1936, -1, 1938, 1941, 1935, -1, 1934, 1909, 1942, -1, 1923, 1943, 1924, -1, 1930, 1944, 1931, -1, 1941, 1945, 1935, -1, 1910, 1909, 1934, -1, 1946, 1947, 1939, -1, 1948, 1944, 1930, -1, 1945, 1949, 1935, -1, 1943, 1950, 1924, -1, 1939, 1947, 1918, -1, 1951, 1952, 1953, -1, 1954, 1952, 1951, -1, 1955, 1952, 1954, -1, 1942, 1908, 1956, -1, 1949, 1957, 1935, -1, 1958, 1952, 1955, -1, 1959, 1952, 1958, -1, 1960, 1952, 1959, -1, 1961, 1952, 1960, -1, 1909, 1908, 1942, -1, 1962, 1963, 1946, -1, 1957, 1964, 1935, -1, 1948, 1965, 1944, -1, 1966, 1965, 1948, -1, 1967, 1965, 1966, -1, 1946, 1963, 1947, -1, 1950, 1968, 1924, -1, 1969, 1970, 1962, -1, 1971, 1972, 1973, -1, 1962, 1970, 1963, -1, 1956, 1907, 1974, -1, 1968, 1975, 1924, -1, 1908, 1907, 1956, -1, 1969, 1976, 1970, -1, 1974, 1906, 1977, -1, 1907, 1906, 1974, -1, 1977, 1905, 1978, -1, 1906, 1905, 1977, -1, 1979, 1980, 1969, -1, 1969, 1980, 1976, -1, 1981, 1982, 1983, -1, 1984, 1982, 1981, -1, 1978, 1904, 1985, -1, 1905, 1904, 1978, -1, 1984, 1986, 1982, -1, 1987, 1988, 1979, -1, 1982, 1989, 1983, -1, 1979, 1988, 1980, -1, 1990, 1903, 1991, -1, 1985, 1903, 1990, -1, 1904, 1903, 1985, -1, 1989, 1992, 1983, -1, 1993, 1992, 1994, -1, 1983, 1992, 1993, -1, 1992, 1995, 1994, -1, 1965, 1996, 1997, -1, 1967, 1996, 1965, -1, 1998, 1999, 1967, -1, 1995, 1921, 1994, -1, 1967, 1999, 1996, -1, 1996, 2000, 1997, -1, 1994, 1921, 1929, -1, 2001, 2002, 1998, -1, 1998, 2002, 1999, -1, 2003, 2004, 2005, -1, 1926, 2006, 2007, -1, 2000, 2008, 1997, -1, 2009, 2008, 2010, -1, 1926, 2011, 2006, -1, 1997, 2008, 2009, -1, 2012, 2013, 2001, -1, 2014, 2015, 2003, -1, 2003, 2015, 2004, -1, 2001, 2013, 2002, -1, 2004, 2016, 2005, -1, 2005, 2016, 2017, -1, 2008, 2018, 2010, -1, 2019, 2020, 2012, -1, 2021, 2022, 2014, -1, 2023, 2024, 2025, -1, 2012, 2020, 2013, -1, 2014, 2022, 2015, -1, 2016, 2026, 2017, -1, 2017, 2026, 2027, -1, 2018, 2028, 2010, -1, 2027, 2026, 2029, -1, 2024, 2030, 2025, -1, 2010, 2028, 2031, -1, 2025, 2030, 2032, -1, 2033, 2034, 2019, -1, 2035, 2034, 2033, -1, 2021, 2036, 2022, -1, 2023, 2037, 2024, -1, 2038, 2037, 2023, -1, 2019, 2034, 2020, -1, 2039, 2036, 2021, -1, 2030, 2040, 2032, -1, 2032, 2040, 2041, -1, 2028, 2042, 2031, -1, 2029, 2043, 1902, -1, 2031, 2042, 2044, -1, 2038, 2045, 2037, -1, 2026, 2043, 2029, -1, 2035, 2046, 2034, -1, 2047, 2048, 2039, -1, 2039, 2048, 2036, -1, 1902, 2049, 1903, -1, 2042, 2050, 2044, -1, 2043, 2049, 1902, -1, 2044, 2050, 2051, -1, 2040, 2052, 2041, -1, 1953, 2053, 2035, -1, 2035, 2053, 2046, -1, 2047, 2054, 2048, -1, 2055, 2054, 1987, -1, 1964, 2056, 1935, -1, 1988, 2054, 2047, -1, 1935, 2056, 2057, -1, 1987, 2054, 1988, -1, 1964, 2058, 2056, -1, 2059, 2058, 1964, -1, 2049, 2060, 1903, -1, 2050, 2061, 2051, -1, 2051, 2061, 2062, -1, 2056, 2063, 2057, -1, 1991, 2060, 2064, -1, 1903, 2060, 1991, -1, 2065, 2066, 2055, -1, 2055, 2066, 2054, -1, 2038, 2067, 2045, -1, 2060, 2068, 2064, -1, 2069, 2067, 2038, -1, 2065, 2070, 2066, -1, 2052, 2071, 2041, -1, 2059, 2071, 2058, -1, 2072, 2070, 2065, -1, 2041, 2071, 2059, -1, 2063, 2073, 2057, -1, 2074, 2075, 2052, -1, 2052, 2075, 2071, -1, 2073, 2076, 2057, -1, 2069, 2077, 2067, -1, 2078, 2077, 2069, -1, 2079, 2080, 2081, -1, 2082, 2080, 2079, -1, 2053, 2080, 2082, -1, 2074, 2083, 2075, -1, 2084, 2080, 2085, -1, 2086, 2080, 2084, -1, 2087, 2080, 2086, -1, 2088, 2080, 2087, -1, 2081, 2080, 2088, -1, 1953, 2080, 2053, -1, 1952, 2080, 1953, -1, 2074, 2089, 2083, -1, 2076, 2090, 2057, -1, 2091, 2092, 1972, -1, 2093, 2092, 2091, -1, 2094, 2095, 2092, -1, 2096, 2097, 2098, -1, 2099, 2097, 2096, -1, 2080, 1924, 2100, -1, 2070, 2097, 2099, -1, 2080, 2100, 2085, -1, 2101, 2097, 2102, -1, 2089, 2103, 2083, -1, 2100, 1924, 2104, -1, 2105, 2097, 2101, -1, 2104, 1924, 2106, -1, 2072, 2097, 2070, -1, 2106, 1924, 2061, -1, 2107, 2097, 2105, -1, 2061, 1924, 2108, -1, 2098, 2097, 2107, -1, 2061, 2108, 2109, -1, 2061, 2109, 2062, -1, 2108, 1924, 2110, -1, 2110, 1924, 1975, -1, 1935, 2072, 2111, -1, 1935, 2111, 2112, -1, 1935, 2112, 1986, -1, 1935, 1986, 2113, -1, 1935, 2113, 2114, -1, 1935, 2114, 1940, -1, 2111, 2072, 2115, -1, 2113, 1986, 2116, -1, 2115, 2072, 2117, -1, 2118, 2119, 2120, -1, 2116, 1986, 1984, -1, 2121, 1952, 2122, -1, 2121, 2122, 2123, -1, 2121, 2123, 2124, -1, 2122, 1952, 2125, -1, 2125, 1952, 2126, -1, 2126, 1952, 2127, -1, 2127, 1952, 2128, -1, 2118, 2129, 2119, -1, 2128, 1952, 2130, -1, 2078, 1928, 2077, -1, 2128, 2130, 2131, -1, 2128, 2131, 2132, -1, 2128, 2132, 2133, -1, 2130, 1952, 2134, -1, 1929, 1928, 2078, -1, 2134, 1952, 2135, -1, 2135, 1952, 1961, -1, 2136, 2119, 2137, -1, 2137, 2119, 2129, -1, 2120, 2138, 2118, -1, 2118, 2138, 2139, -1, 2097, 2057, 2140, -1, 2090, 2141, 2057, -1, 2097, 2140, 2142, -1, 2097, 2142, 2143, -1, 2121, 2124, 2144, -1, 2097, 2143, 2064, -1, 2097, 2064, 2145, -1, 2097, 2145, 2146, -1, 2097, 2146, 2147, -1, 2089, 2148, 2103, -1, 2097, 2147, 2102, -1, 2144, 2149, 2121, -1, 2140, 2057, 2150, -1, 2145, 2064, 2151, -1, 2150, 2057, 2152, -1, 2151, 2064, 2153, -1, 2152, 2057, 2154, -1, 2153, 2064, 2068, -1, 1972, 1926, 2091, -1, 2091, 1926, 1924, -1, 1924, 1926, 2121, -1, 2121, 1926, 2119, -1, 2119, 1926, 2120, -1, 2120, 1926, 2057, -1, 2149, 2155, 2121, -1, 2057, 1926, 1935, -1, 1935, 1926, 2007, -1, 1925, 2156, 1926, -1, 1926, 2156, 2011, -1, 2141, 2157, 2057, -1, 2011, 2092, 2093, -1, 2011, 2093, 2080, -1, 2011, 2080, 1952, -1, 2011, 1952, 2136, -1, 2011, 2136, 2138, -1, 2011, 2138, 2097, -1, 2155, 2158, 2121, -1, 2011, 2097, 2072, -1, 2011, 2072, 2006, -1, 2095, 1973, 1972, -1, 2095, 1972, 2092, -1, 2158, 2159, 2121, -1, 2148, 2160, 2103, -1, 2103, 2160, 2161, -1, 2159, 2162, 2121, -1, 2157, 2154, 2057, -1, 2162, 2163, 2121, -1, 2161, 2164, 2165, -1, 2160, 2164, 2161, -1, 2156, 2166, 2011, -1, 2165, 2167, 2168, -1, 2138, 2136, 2139, -1, 2139, 2136, 2137, -1, 2164, 2167, 2165, -1, 2163, 1924, 2121, -1, 2133, 2169, 2128, -1, 2170, 2072, 2065, -1, 2171, 2072, 2170, -1, 2128, 2169, 2172, -1, 2173, 2072, 2171, -1, 2174, 2072, 2173, -1, 2175, 2072, 2174, -1, 2176, 2072, 2175, -1, 2177, 2072, 2176, -1, 2117, 2072, 2177, -1, 2169, 2178, 2172, -1, 2179, 2178, 2180, -1, 2172, 2178, 2179, -1, 2168, 2181, 2182, -1, 2167, 2181, 2168, -1, 2178, 2183, 2180, -1, 2181, 2184, 2182, -1, 2183, 2185, 2180, -1, 2182, 2184, 2186, -1, 2180, 2185, 2187, -1, 2185, 2188, 2187, -1, 2186, 2189, 2190, -1, 2184, 2189, 2186, -1, 2187, 2188, 2191, -1, 2189, 1990, 2190, -1, 2191, 1967, 1966, -1, 2188, 1967, 2191, -1, 2190, 1990, 1991, -1, 2163, 2192, 1924, -1, 2193, 2192, 2163, -1, 2193, 2194, 2192, -1, 2192, 2195, 1924, -1, 2196, 1914, 2197, -1, 2193, 2198, 2194, -1, 2199, 2198, 2193, -1, 2195, 2200, 1924, -1, 2201, 1915, 2196, -1, 2196, 1915, 1914, -1, 1914, 1913, 2197, -1, 2202, 2203, 2199, -1, 2197, 1913, 2204, -1, 2199, 2203, 2198, -1, 2200, 1922, 1924, -1, 1928, 1916, 2201, -1, 2201, 1916, 1915, -1, 2205, 1932, 2202, -1, 2204, 1912, 1919, -1, 1930, 1932, 2205, -1, 1913, 1912, 2204, -1, 2202, 1932, 2203, -1, 1919, 1911, 1933, -1, 2206, 2160, 2148, -1, 2206, 2207, 2160, -1, 2208, 2148, 2089, -1, 2208, 2206, 2148, -1, 2209, 2089, 2074, -1, 2209, 2208, 2089, -1, 2210, 2074, 2052, -1, 2210, 2209, 2074, -1, 2211, 2052, 2040, -1, 2211, 2210, 2052, -1, 2212, 2040, 2030, -1, 2212, 2211, 2040, -1, 2213, 2030, 2024, -1, 2213, 2212, 2030, -1, 2214, 2024, 2037, -1, 2214, 2213, 2024, -1, 2215, 2037, 2045, -1, 2215, 2214, 2037, -1, 2216, 2045, 2067, -1, 2216, 2215, 2045, -1, 2217, 2067, 2077, -1, 2217, 2216, 2067, -1, 2218, 2077, 1928, -1, 2218, 2217, 2077, -1, 2219, 1928, 2201, -1, 2219, 2218, 1928, -1, 2220, 2201, 2196, -1, 2220, 2219, 2201, -1, 2221, 2196, 2197, -1, 2221, 2220, 2196, -1, 2222, 2221, 2197, -1, 2222, 2197, 2204, -1, 2223, 1994, 1929, -1, 2224, 1929, 2078, -1, 2224, 2223, 1929, -1, 2225, 2078, 2069, -1, 2225, 2224, 2078, -1, 2226, 2069, 2038, -1, 2226, 2225, 2069, -1, 2227, 2038, 2023, -1, 2227, 2226, 2038, -1, 2228, 2023, 2025, -1, 2228, 2227, 2023, -1, 2229, 2025, 2032, -1, 2229, 2228, 2025, -1, 2230, 2032, 2041, -1, 2230, 2229, 2032, -1, 2231, 2041, 2059, -1, 2231, 2230, 2041, -1, 2232, 2059, 1964, -1, 2232, 2231, 2059, -1, 2233, 1964, 1957, -1, 2233, 2232, 1964, -1, 2234, 1957, 1949, -1, 2234, 2233, 1957, -1, 2235, 1949, 1945, -1, 2235, 2234, 1949, -1, 2236, 2235, 1945, -1, 2237, 2186, 2190, -1, 2237, 2238, 2186, -1, 2239, 2190, 1991, -1, 2239, 2237, 2190, -1, 2240, 1991, 2064, -1, 2240, 2239, 1991, -1, 2241, 2064, 2143, -1, 2241, 2240, 2064, -1, 2242, 2143, 2142, -1, 2242, 2241, 2143, -1, 2243, 2142, 2140, -1, 2243, 2242, 2142, -1, 2244, 2140, 2150, -1, 2244, 2243, 2140, -1, 2245, 2150, 2152, -1, 2245, 2244, 2150, -1, 2246, 2152, 2154, -1, 2246, 2245, 2152, -1, 2247, 2154, 2157, -1, 2247, 2246, 2154, -1, 2248, 2157, 2141, -1, 2248, 2247, 2157, -1, 2249, 2141, 2090, -1, 2249, 2248, 2141, -1, 2250, 2090, 2076, -1, 2250, 2249, 2090, -1, 2251, 2098, 2107, -1, 2251, 2252, 2098, -1, 2253, 2107, 2105, -1, 2253, 2251, 2107, -1, 2254, 2105, 2101, -1, 2254, 2253, 2105, -1, 2255, 2101, 2102, -1, 2255, 2254, 2101, -1, 2256, 2102, 2147, -1, 2256, 2255, 2102, -1, 2257, 2147, 2146, -1, 2257, 2256, 2147, -1, 2258, 2146, 2145, -1, 2258, 2257, 2146, -1, 2259, 2145, 2151, -1, 2259, 2258, 2145, -1, 2260, 2151, 2153, -1, 2260, 2259, 2151, -1, 2261, 2153, 2068, -1, 2261, 2260, 2153, -1, 2262, 2068, 2060, -1, 2262, 2261, 2068, -1, 2263, 2060, 2049, -1, 2263, 2262, 2060, -1, 2264, 2049, 2043, -1, 2264, 2263, 2049, -1, 2265, 2173, 2171, -1, 2265, 2266, 2173, -1, 2267, 2171, 2170, -1, 2267, 2265, 2171, -1, 2268, 2170, 2065, -1, 2268, 2267, 2170, -1, 2269, 2065, 2055, -1, 2269, 2268, 2065, -1, 2270, 2055, 1987, -1, 2270, 2269, 2055, -1, 2271, 1987, 1979, -1, 2271, 2270, 1987, -1, 2272, 1979, 1969, -1, 2272, 2271, 1979, -1, 2273, 1969, 1962, -1, 2273, 2272, 1969, -1, 2274, 1962, 1946, -1, 2274, 2273, 1962, -1, 2275, 1946, 1939, -1, 2275, 2274, 1946, -1, 2276, 1939, 1920, -1, 2276, 2275, 1939, -1, 2277, 1920, 1921, -1, 2277, 2276, 1920, -1, 2278, 1921, 1995, -1, 2278, 2277, 1921, -1, 2279, 2010, 2031, -1, 2279, 2280, 2010, -1, 2281, 2031, 2044, -1, 2281, 2279, 2031, -1, 2282, 2044, 2051, -1, 2282, 2281, 2044, -1, 2283, 2051, 2062, -1, 2283, 2282, 2051, -1, 2284, 2062, 2109, -1, 2284, 2283, 2062, -1, 2285, 2109, 2108, -1, 2285, 2284, 2109, -1, 2286, 2108, 2110, -1, 2286, 2285, 2108, -1, 2287, 2110, 1975, -1, 2287, 2286, 2110, -1, 2288, 1975, 1968, -1, 2288, 2287, 1975, -1, 2289, 1968, 1950, -1, 2289, 2288, 1968, -1, 2290, 1950, 1943, -1, 2290, 2289, 1950, -1, 2291, 1943, 1923, -1, 2291, 2290, 1943, -1, 2292, 1923, 1922, -1, 2292, 2291, 1923, -1, 2293, 2180, 2187, -1, 2293, 2294, 2180, -1, 2295, 2187, 2191, -1, 2295, 2293, 2187, -1, 2296, 2191, 1966, -1, 2296, 2295, 2191, -1, 2297, 1966, 1948, -1, 2297, 2296, 1966, -1, 2298, 1948, 1930, -1, 2298, 2297, 1948, -1, 2299, 1930, 2205, -1, 2299, 2298, 1930, -1, 2300, 2205, 2202, -1, 2300, 2299, 2205, -1, 2301, 2202, 2199, -1, 2301, 2300, 2202, -1, 2302, 2199, 2193, -1, 2302, 2301, 2199, -1, 2303, 2193, 2163, -1, 2303, 2302, 2193, -1, 2304, 2163, 2162, -1, 2304, 2303, 2163, -1, 2305, 2162, 2159, -1, 2305, 2304, 2162, -1, 2306, 2159, 2158, -1, 2306, 2305, 2159, -1, 2307, 2081, 2088, -1, 2307, 2308, 2081, -1, 2309, 2088, 2087, -1, 2309, 2307, 2088, -1, 2310, 2087, 2086, -1, 2310, 2309, 2087, -1, 2311, 2086, 2084, -1, 2311, 2310, 2086, -1, 2312, 2084, 2085, -1, 2312, 2311, 2084, -1, 2313, 2085, 2100, -1, 2313, 2312, 2085, -1, 2314, 2100, 2104, -1, 2314, 2313, 2100, -1, 2315, 2104, 2106, -1, 2315, 2314, 2104, -1, 2316, 2106, 2061, -1, 2316, 2315, 2106, -1, 2317, 2061, 2050, -1, 2317, 2316, 2061, -1, 2318, 2050, 2042, -1, 2318, 2317, 2050, -1, 2319, 2042, 2028, -1, 2319, 2318, 2042, -1, 2320, 2028, 2018, -1, 2320, 2319, 2028, -1, 2321, 1955, 1954, -1, 2321, 2322, 1955, -1, 2323, 1954, 1951, -1, 2323, 2321, 1954, -1, 2324, 1951, 1953, -1, 2324, 2323, 1951, -1, 2325, 1953, 2035, -1, 2325, 2324, 1953, -1, 2326, 2035, 2033, -1, 2326, 2325, 2035, -1, 2327, 2033, 2019, -1, 2327, 2326, 2033, -1, 2328, 2019, 2012, -1, 2328, 2327, 2019, -1, 2329, 2012, 2001, -1, 2329, 2328, 2012, -1, 2330, 2001, 1998, -1, 2330, 2329, 2001, -1, 2331, 1998, 1967, -1, 2331, 2330, 1998, -1, 2332, 1967, 2188, -1, 2332, 2331, 1967, -1, 2333, 2188, 2185, -1, 2333, 2332, 2188, -1, 2334, 2185, 2183, -1, 2334, 2333, 2185, -1, 2335, 2336, 2337, -1, 2338, 2339, 2340, -1, 2340, 2339, 2341, -1, 2342, 2339, 2338, -1, 2343, 2344, 2345, -1, 2346, 2344, 2343, -1, 2336, 2347, 2337, -1, 2342, 2348, 2339, -1, 2349, 2350, 2351, -1, 2347, 2352, 2337, -1, 2349, 2353, 2350, -1, 2342, 2354, 2348, -1, 2349, 2355, 2353, -1, 2356, 2354, 2357, -1, 2357, 2354, 2342, -1, 2349, 2358, 2355, -1, 2352, 2359, 2337, -1, 2356, 2360, 2354, -1, 2356, 2361, 2360, -1, 2362, 2361, 2356, -1, 2362, 2363, 2361, -1, 2364, 2363, 2362, -1, 2364, 2365, 2363, -1, 2366, 2365, 2364, -1, 2367, 2368, 2369, -1, 2370, 2368, 2367, -1, 2371, 2368, 2370, -1, 2372, 2368, 2371, -1, 2373, 2368, 2372, -1, 2374, 2368, 2373, -1, 2369, 2368, 2375, -1, 2344, 2376, 2377, -1, 2344, 2378, 2376, -1, 2379, 2380, 2381, -1, 2381, 2380, 2359, -1, 2344, 2382, 2378, -1, 2337, 2383, 2384, -1, 2380, 2383, 2359, -1, 2346, 2385, 2344, -1, 2344, 2385, 2382, -1, 2359, 2383, 2337, -1, 2386, 2387, 2379, -1, 2379, 2387, 2380, -1, 2346, 2388, 2385, -1, 2368, 2388, 2346, -1, 2383, 2389, 2384, -1, 2368, 2390, 2388, -1, 2391, 2392, 2386, -1, 2386, 2392, 2387, -1, 2389, 2393, 2384, -1, 2394, 2395, 2391, -1, 2391, 2395, 2392, -1, 2393, 2396, 2384, -1, 2394, 2397, 2395, -1, 2396, 2398, 2384, -1, 2399, 2400, 2401, -1, 2402, 2403, 2404, -1, 2401, 2400, 2394, -1, 2405, 2403, 2402, -1, 2406, 2403, 2405, -1, 2407, 2403, 2406, -1, 2394, 2400, 2397, -1, 2408, 2409, 2410, -1, 2411, 2412, 2399, -1, 2403, 2409, 2408, -1, 2399, 2412, 2400, -1, 2411, 2413, 2412, -1, 2409, 2414, 2415, -1, 2416, 2417, 2411, -1, 2411, 2417, 2413, -1, 2403, 2414, 2409, -1, 2407, 2414, 2403, -1, 2407, 2418, 2414, -1, 2419, 2418, 2407, -1, 2420, 2418, 2419, -1, 2421, 2418, 2420, -1, 2422, 2423, 2416, -1, 2424, 2418, 2421, -1, 2416, 2423, 2417, -1, 2415, 2425, 2426, -1, 2415, 2427, 2425, -1, 2414, 2428, 2415, -1, 2415, 2428, 2427, -1, 2427, 2429, 2430, -1, 2431, 2432, 2433, -1, 2434, 2432, 2431, -1, 2358, 2432, 2434, -1, 2349, 2432, 2358, -1, 2384, 2435, 2436, -1, 2437, 2435, 2438, -1, 2398, 2435, 2384, -1, 2427, 2439, 2429, -1, 2436, 2435, 2437, -1, 2440, 2435, 2441, -1, 2441, 2435, 2442, -1, 2442, 2435, 2398, -1, 2427, 2443, 2439, -1, 2444, 2445, 2446, -1, 2446, 2445, 2447, -1, 2447, 2445, 2432, -1, 2448, 2449, 2450, -1, 2435, 2449, 2448, -1, 2445, 2451, 2432, -1, 2435, 2452, 2449, -1, 2435, 2453, 2452, -1, 2428, 2454, 2427, -1, 2427, 2454, 2443, -1, 2455, 2156, 2451, -1, 2451, 2156, 2432, -1, 2435, 2456, 2453, -1, 2435, 2457, 2456, -1, 2428, 2458, 2454, -1, 2458, 2459, 2454, -1, 2424, 2460, 2418, -1, 2368, 2460, 2390, -1, 2390, 2460, 2424, -1, 2435, 2461, 2457, -1, 2458, 2462, 2459, -1, 2440, 2463, 2435, -1, 2458, 2464, 2462, -1, 2435, 2463, 2461, -1, 2465, 2463, 2440, -1, 2465, 2466, 2463, -1, 2458, 2467, 2464, -1, 2468, 2466, 2465, -1, 2468, 2469, 2466, -1, 2470, 2469, 2468, -1, 2470, 2471, 2469, -1, 2472, 2473, 2474, -1, 2475, 2473, 2476, -1, 2476, 2473, 2477, -1, 2477, 2473, 2472, -1, 2478, 2479, 2368, -1, 2480, 2481, 2482, -1, 2483, 2481, 2484, -1, 2368, 2485, 2478, -1, 2484, 2481, 2486, -1, 2374, 2485, 2368, -1, 2486, 2481, 2480, -1, 2368, 2487, 2460, -1, 2488, 2489, 2470, -1, 2479, 2487, 2368, -1, 2470, 2489, 2471, -1, 2490, 2491, 2374, -1, 2471, 2489, 2492, -1, 2492, 2489, 2493, -1, 2493, 2489, 2483, -1, 2483, 2489, 2481, -1, 2374, 2491, 2485, -1, 2423, 1925, 2494, -1, 2494, 1925, 2495, -1, 2495, 1925, 2496, -1, 2496, 1925, 2497, -1, 2497, 1925, 2488, -1, 2487, 2498, 2460, -1, 2488, 1925, 2489, -1, 2366, 1925, 2365, -1, 2499, 2500, 2490, -1, 2365, 1925, 2422, -1, 2156, 1925, 2366, -1, 2422, 1925, 2423, -1, 2490, 2500, 2491, -1, 2498, 2501, 2460, -1, 2489, 2502, 2503, -1, 2433, 2504, 2499, -1, 2505, 2506, 2507, -1, 2507, 2506, 1925, -1, 2432, 2504, 2433, -1, 2499, 2504, 2500, -1, 2489, 2506, 2502, -1, 1925, 2506, 2489, -1, 2506, 2508, 2502, -1, 2501, 2509, 2460, -1, 2156, 2510, 2432, -1, 2432, 2510, 2504, -1, 2460, 2511, 2512, -1, 2509, 2511, 2460, -1, 2156, 2513, 2510, -1, 2156, 2514, 2513, -1, 2156, 2515, 2514, -1, 2473, 2516, 2517, -1, 2156, 2518, 2515, -1, 2156, 2519, 2518, -1, 2467, 2384, 2436, -1, 2458, 2384, 2467, -1, 2473, 2438, 2516, -1, 2437, 2438, 2475, -1, 2475, 2438, 2473, -1, 2520, 2521, 2522, -1, 2522, 2521, 2511, -1, 2511, 2521, 2512, -1, 2522, 2523, 2520, -1, 2524, 2523, 2522, -1, 2521, 2525, 2512, -1, 2526, 2527, 2524, -1, 2524, 2527, 2523, -1, 2525, 2528, 2512, -1, 2529, 2530, 2526, -1, 2526, 2530, 2527, -1, 2528, 2531, 2512, -1, 2529, 2532, 2530, -1, 2533, 2532, 2529, -1, 2531, 2534, 2512, -1, 2533, 2535, 2532, -1, 2536, 2535, 2533, -1, 2534, 2537, 2512, -1, 2538, 2539, 2540, -1, 2540, 2539, 2536, -1, 2536, 2539, 2535, -1, 2538, 2541, 2539, -1, 2538, 2542, 2541, -1, 2519, 2542, 2543, -1, 2543, 2542, 2538, -1, 2156, 2544, 2519, -1, 2519, 2544, 2542, -1, 2156, 2366, 2544, -1, 2545, 2546, 2537, -1, 2512, 2547, 2337, -1, 2537, 2547, 2512, -1, 2546, 2547, 2537, -1, 2548, 2549, 2545, -1, 2545, 2549, 2546, -1, 2547, 2335, 2337, -1, 2340, 2341, 2548, -1, 2548, 2341, 2549, -1, 2486, 2550, 2551, -1, 2486, 2480, 2550, -1, 2484, 2551, 2552, -1, 2484, 2486, 2551, -1, 2483, 2552, 2553, -1, 2483, 2484, 2552, -1, 2493, 2553, 2554, -1, 2493, 2483, 2553, -1, 2492, 2554, 2555, -1, 2492, 2493, 2554, -1, 2471, 2555, 2556, -1, 2471, 2492, 2555, -1, 2469, 2556, 2557, -1, 2469, 2471, 2556, -1, 2466, 2557, 2558, -1, 2466, 2558, 2559, -1, 2466, 2469, 2557, -1, 2463, 2559, 2560, -1, 2463, 2560, 2561, -1, 2463, 2466, 2559, -1, 2461, 2561, 2562, -1, 2461, 2463, 2561, -1, 2457, 2562, 2563, -1, 2457, 2563, 2564, -1, 2457, 2461, 2562, -1, 2456, 2564, 2565, -1, 2456, 2457, 2564, -1, 2367, 2566, 2567, -1, 2367, 2369, 2566, -1, 2370, 2367, 2567, -1, 2371, 2567, 2568, -1, 2371, 2370, 2567, -1, 2468, 2569, 2570, -1, 2470, 2570, 2571, -1, 2470, 2468, 2570, -1, 2488, 2571, 2572, -1, 2488, 2470, 2571, -1, 2497, 2572, 2573, -1, 2497, 2488, 2572, -1, 2496, 2573, 2574, -1, 2496, 2497, 2573, -1, 2495, 2574, 2575, -1, 2495, 2496, 2574, -1, 2494, 2575, 2576, -1, 2494, 2495, 2575, -1, 2423, 2576, 2577, -1, 2423, 2494, 2576, -1, 2417, 2577, 2578, -1, 2417, 2423, 2577, -1, 2413, 2578, 2579, -1, 2413, 2417, 2578, -1, 2412, 2579, 2580, -1, 2412, 2413, 2579, -1, 2400, 2412, 2580, -1, 2397, 2580, 2581, -1, 2397, 2400, 2580, -1, 2395, 2581, 2582, -1, 2395, 2397, 2581, -1, 2391, 2583, 2584, -1, 2394, 2584, 2585, -1, 2394, 2391, 2584, -1, 2401, 2585, 2586, -1, 2401, 2394, 2585, -1, 2399, 2586, 2587, -1, 2399, 2401, 2586, -1, 2411, 2587, 2588, -1, 2411, 2399, 2587, -1, 2416, 2588, 2589, -1, 2416, 2411, 2588, -1, 2422, 2589, 2590, -1, 2422, 2416, 2589, -1, 2365, 2590, 2591, -1, 2365, 2422, 2590, -1, 2363, 2591, 2592, -1, 2363, 2365, 2591, -1, 2361, 2592, 2593, -1, 2361, 2363, 2592, -1, 2360, 2593, 2594, -1, 2360, 2361, 2593, -1, 2354, 2360, 2594, -1, 2348, 2594, 2595, -1, 2348, 2354, 2594, -1, 2339, 2595, 2596, -1, 2339, 2348, 2595, -1, 2338, 2597, 2598, -1, 2342, 2598, 2599, -1, 2342, 2338, 2598, -1, 2357, 2599, 2600, -1, 2357, 2342, 2599, -1, 2356, 2600, 2601, -1, 2356, 2357, 2600, -1, 2362, 2601, 2602, -1, 2362, 2356, 2601, -1, 2364, 2602, 2603, -1, 2364, 2362, 2602, -1, 2366, 2603, 2604, -1, 2366, 2364, 2603, -1, 2544, 2604, 2605, -1, 2544, 2366, 2604, -1, 2542, 2605, 2606, -1, 2542, 2544, 2605, -1, 2541, 2606, 2607, -1, 2541, 2542, 2606, -1, 2539, 2607, 2608, -1, 2539, 2541, 2607, -1, 2535, 2539, 2608, -1, 2532, 2608, 2609, -1, 2532, 2535, 2608, -1, 2530, 2609, 2610, -1, 2530, 2532, 2609, -1, 2529, 2611, 2612, -1, 2533, 2612, 2613, -1, 2533, 2529, 2612, -1, 2536, 2613, 2614, -1, 2536, 2533, 2613, -1, 2540, 2614, 2615, -1, 2540, 2536, 2614, -1, 2538, 2615, 2616, -1, 2538, 2540, 2615, -1, 2543, 2616, 2617, -1, 2543, 2538, 2616, -1, 2519, 2617, 2618, -1, 2519, 2543, 2617, -1, 2518, 2618, 2619, -1, 2518, 2519, 2618, -1, 2515, 2619, 2620, -1, 2515, 2518, 2619, -1, 2514, 2620, 2621, -1, 2514, 2515, 2620, -1, 2513, 2621, 2622, -1, 2513, 2514, 2621, -1, 2510, 2513, 2622, -1, 2504, 2622, 2623, -1, 2504, 2510, 2622, -1, 2500, 2623, 2624, -1, 2500, 2504, 2623, -1, 2625, 2626, 2627, -1, 2628, 2629, 2630, -1, 2631, 2632, 2633, -1, 2633, 2632, 2634, -1, 2635, 2636, 2626, -1, 2637, 2638, 2639, -1, 2639, 2638, 2629, -1, 2640, 2641, 2642, -1, 2643, 2641, 2640, -1, 2632, 2644, 2634, -1, 2634, 2644, 2645, -1, 2646, 2647, 2637, -1, 2648, 2647, 2646, -1, 2637, 2647, 2638, -1, 2649, 2650, 2651, -1, 2649, 2652, 2650, -1, 2635, 2653, 2636, -1, 2654, 2653, 2635, -1, 2649, 2655, 2652, -1, 2648, 2656, 2647, -1, 1973, 2656, 2648, -1, 2649, 2657, 2655, -1, 2644, 2658, 2645, -1, 1973, 2659, 2656, -1, 2660, 2661, 2662, -1, 2654, 2663, 2653, -1, 2664, 2663, 2654, -1, 2665, 2663, 2664, -1, 2658, 2666, 2645, -1, 2645, 2666, 2667, -1, 2665, 2668, 2663, -1, 2666, 2669, 2667, -1, 2670, 2671, 2672, -1, 2673, 2674, 2675, -1, 2676, 2671, 2677, -1, 2678, 2674, 2673, -1, 2677, 2671, 2679, -1, 2679, 2671, 2680, -1, 2680, 2671, 2681, -1, 2682, 2683, 2665, -1, 2681, 2671, 2684, -1, 2665, 2683, 2668, -1, 2684, 2671, 2685, -1, 2685, 2671, 2670, -1, 2678, 2686, 2674, -1, 2672, 2687, 2688, -1, 2671, 2687, 2672, -1, 2689, 2690, 2691, -1, 2669, 2692, 2667, -1, 2661, 2693, 2662, -1, 2694, 2693, 2661, -1, 2695, 2693, 2694, -1, 2691, 2696, 2697, -1, 2698, 2693, 2695, -1, 2690, 2696, 2691, -1, 2699, 2693, 2698, -1, 2700, 2693, 2699, -1, 2701, 2693, 2700, -1, 2678, 2702, 2686, -1, 2641, 2703, 2704, -1, 2689, 2705, 2690, -1, 2641, 2706, 2703, -1, 2697, 2707, 2708, -1, 2678, 2709, 2702, -1, 2696, 2707, 2697, -1, 2641, 2710, 2706, -1, 2689, 2711, 2705, -1, 2712, 2711, 2689, -1, 2713, 2711, 2712, -1, 2707, 2714, 2708, -1, 2708, 2714, 2715, -1, 2715, 2714, 2716, -1, 2678, 2717, 2709, -1, 2713, 2718, 2711, -1, 2678, 2719, 2717, -1, 2687, 2720, 2688, -1, 2714, 2721, 2716, -1, 2722, 2723, 2678, -1, 2678, 2723, 2719, -1, 2724, 2725, 2713, -1, 2726, 2725, 2724, -1, 2643, 2727, 2728, -1, 2713, 2725, 2718, -1, 2722, 2729, 2723, -1, 2730, 2729, 2722, -1, 2728, 2731, 2643, -1, 2720, 2732, 2688, -1, 2643, 2733, 2727, -1, 2730, 2734, 2729, -1, 2726, 2735, 2725, -1, 2736, 2734, 2730, -1, 2737, 2738, 2726, -1, 2739, 2738, 2737, -1, 2726, 2738, 2735, -1, 2693, 2740, 2643, -1, 2732, 2741, 2688, -1, 2643, 2740, 2733, -1, 2643, 2742, 2641, -1, 2739, 2743, 2738, -1, 2731, 2742, 2643, -1, 2744, 2745, 2739, -1, 2746, 2747, 2748, -1, 2749, 2747, 2746, -1, 2739, 2745, 2743, -1, 2750, 2747, 2749, -1, 2751, 2747, 2750, -1, 2752, 2747, 2751, -1, 2753, 2747, 2752, -1, 2710, 2747, 2753, -1, 2641, 2747, 2710, -1, 2742, 2747, 2641, -1, 2741, 2754, 2688, -1, 2693, 2755, 2740, -1, 2659, 2756, 2744, -1, 2757, 2758, 2759, -1, 2744, 2756, 2745, -1, 2760, 2758, 2761, -1, 1973, 2756, 2659, -1, 2762, 2763, 2764, -1, 2761, 2758, 2765, -1, 2766, 2763, 2762, -1, 2765, 2758, 2757, -1, 2767, 2763, 2766, -1, 2768, 2763, 2767, -1, 2769, 2770, 2692, -1, 2771, 2770, 2769, -1, 2772, 2770, 2771, -1, 2692, 2770, 2667, -1, 2754, 2773, 2688, -1, 2774, 2770, 2736, -1, 2667, 2770, 2774, -1, 2734, 2770, 2775, -1, 2736, 2770, 2734, -1, 2775, 2770, 2776, -1, 2693, 2777, 2755, -1, 2776, 2770, 2778, -1, 1973, 2779, 2756, -1, 2778, 2770, 2760, -1, 2760, 2770, 2758, -1, 2763, 2780, 2781, -1, 2770, 2782, 2758, -1, 2777, 2783, 2755, -1, 2784, 2095, 2772, -1, 2785, 2095, 2784, -1, 2786, 2095, 2785, -1, 2683, 2095, 2786, -1, 2787, 2095, 2682, -1, 2682, 2095, 2683, -1, 2788, 2095, 2787, -1, 2693, 2789, 2777, -1, 2790, 2095, 2788, -1, 2772, 2095, 2770, -1, 2768, 2791, 2763, -1, 2748, 2791, 2768, -1, 2763, 2791, 2780, -1, 2792, 2793, 2794, -1, 2793, 2795, 2794, -1, 2794, 2795, 2095, -1, 2795, 2770, 2095, -1, 2796, 2797, 1973, -1, 1973, 2095, 2779, -1, 2779, 2095, 2790, -1, 2798, 2716, 2799, -1, 2799, 2716, 2800, -1, 2800, 2716, 2801, -1, 2801, 2716, 2721, -1, 2801, 2721, 2802, -1, 2747, 2671, 2676, -1, 2649, 2796, 2657, -1, 2747, 2676, 2803, -1, 2747, 2803, 2791, -1, 2804, 2796, 2805, -1, 2747, 2791, 2748, -1, 2806, 2796, 2804, -1, 2807, 2796, 2806, -1, 2657, 2796, 2807, -1, 2808, 2796, 2649, -1, 2809, 2810, 2811, -1, 2701, 2812, 2693, -1, 2813, 2812, 2701, -1, 2693, 2812, 2789, -1, 2789, 2812, 2814, -1, 2813, 2815, 2812, -1, 2805, 2815, 2813, -1, 2805, 2816, 2815, -1, 2817, 2818, 2819, -1, 2819, 2820, 2821, -1, 2822, 2823, 2824, -1, 2803, 2823, 2822, -1, 2818, 2820, 2819, -1, 2821, 2820, 2802, -1, 2823, 2825, 2826, -1, 2817, 2827, 2818, -1, 2823, 2828, 2825, -1, 2820, 2801, 2802, -1, 2829, 2830, 2817, -1, 2831, 2830, 2829, -1, 2817, 2830, 2827, -1, 2823, 2832, 2828, -1, 2816, 2833, 2834, -1, 2833, 2835, 2834, -1, 2834, 2835, 2836, -1, 2831, 2837, 2830, -1, 2796, 2838, 2805, -1, 2816, 2838, 2833, -1, 2805, 2838, 2816, -1, 2835, 2839, 2836, -1, 2840, 2841, 2831, -1, 2842, 2841, 2840, -1, 2796, 2843, 2838, -1, 2831, 2841, 2837, -1, 2844, 2845, 2797, -1, 2842, 2846, 2841, -1, 2839, 2847, 2836, -1, 2845, 2848, 2797, -1, 2796, 2849, 2843, -1, 2850, 2851, 2842, -1, 2842, 2851, 2846, -1, 2803, 2852, 2823, -1, 2823, 2852, 2832, -1, 2848, 1973, 2797, -1, 2850, 2853, 2851, -1, 2847, 2854, 2836, -1, 2855, 2853, 2850, -1, 2856, 2853, 2855, -1, 2796, 2857, 2849, -1, 2856, 2858, 2853, -1, 2796, 2859, 2857, -1, 2779, 2858, 2856, -1, 2803, 2676, 2852, -1, 2779, 2790, 2858, -1, 2860, 2861, 2854, -1, 2862, 2861, 2860, -1, 2854, 2861, 2836, -1, 2796, 2863, 2859, -1, 2862, 2864, 2861, -1, 1973, 2865, 2796, -1, 2796, 2865, 2863, -1, 2866, 2867, 2868, -1, 2864, 2869, 2861, -1, 2867, 2870, 2868, -1, 2868, 2870, 2871, -1, 2864, 2872, 2869, -1, 2866, 2873, 2867, -1, 2874, 2873, 2866, -1, 2870, 2875, 2871, -1, 1973, 2876, 2865, -1, 2871, 2875, 2799, -1, 2872, 2877, 2869, -1, 2874, 2878, 2873, -1, 2879, 2877, 2872, -1, 2880, 2878, 2874, -1, 2881, 2878, 2880, -1, 2875, 2882, 2799, -1, 2881, 2883, 2878, -1, 1973, 2884, 2876, -1, 2881, 2885, 2883, -1, 1973, 2648, 2884, -1, 2886, 2885, 2881, -1, 2887, 2885, 2886, -1, 2888, 2889, 2879, -1, 2887, 2890, 2885, -1, 2879, 2889, 2877, -1, 2891, 2890, 2887, -1, 2891, 2892, 2890, -1, 2893, 2892, 2891, -1, 2893, 2894, 2892, -1, 2895, 2896, 2893, -1, 2788, 2896, 2895, -1, 2893, 2896, 2894, -1, 2788, 2787, 2896, -1, 2888, 2716, 2889, -1, 2897, 2672, 2898, -1, 2882, 2798, 2799, -1, 2899, 2798, 2882, -1, 2898, 2672, 2900, -1, 2901, 2798, 2899, -1, 2902, 2798, 2901, -1, 2903, 2798, 2902, -1, 2670, 2672, 2897, -1, 2904, 2798, 2903, -1, 2672, 2905, 2906, -1, 2907, 2722, 2908, -1, 2909, 2910, 2716, -1, 2716, 2911, 2909, -1, 2910, 2912, 2716, -1, 2811, 2678, 2773, -1, 2810, 2678, 2811, -1, 2773, 2678, 2688, -1, 2908, 2678, 2810, -1, 2722, 2678, 2908, -1, 2716, 2913, 2911, -1, 2912, 2914, 2716, -1, 2915, 2916, 2798, -1, 2888, 2917, 2716, -1, 2716, 2917, 2913, -1, 2904, 2918, 2798, -1, 2914, 2715, 2716, -1, 2798, 2918, 2915, -1, 2919, 2920, 2888, -1, 2916, 2921, 2798, -1, 2888, 2920, 2917, -1, 2922, 2923, 2904, -1, 2625, 2923, 2922, -1, 2904, 2923, 2918, -1, 2672, 2688, 2905, -1, 2921, 2924, 2798, -1, 2798, 2924, 2925, -1, 2628, 2630, 2919, -1, 2625, 2627, 2923, -1, 2919, 2630, 2920, -1, 2924, 2631, 2925, -1, 2925, 2631, 2633, -1, 2926, 2626, 2625, -1, 2635, 2626, 2926, -1, 2639, 2629, 2628, -1, 2765, 2927, 2928, -1, 2765, 2757, 2927, -1, 2761, 2928, 2929, -1, 2761, 2765, 2928, -1, 2760, 2929, 2930, -1, 2760, 2761, 2929, -1, 2778, 2930, 2931, -1, 2778, 2760, 2930, -1, 2776, 2931, 2932, -1, 2776, 2778, 2931, -1, 2775, 2932, 2933, -1, 2775, 2776, 2932, -1, 2734, 2933, 2934, -1, 2734, 2775, 2933, -1, 2729, 2934, 2935, -1, 2729, 2935, 2936, -1, 2729, 2734, 2934, -1, 2723, 2936, 2937, -1, 2723, 2937, 2938, -1, 2723, 2729, 2936, -1, 2719, 2938, 2939, -1, 2719, 2939, 2940, -1, 2719, 2723, 2938, -1, 2717, 2940, 2941, -1, 2717, 2719, 2940, -1, 2709, 2941, 2942, -1, 2709, 2717, 2941, -1, 2694, 2943, 2944, -1, 2694, 2661, 2943, -1, 2695, 2694, 2944, -1, 2698, 2944, 2945, -1, 2698, 2695, 2944, -1, 2919, 2946, 2947, -1, 2919, 2888, 2946, -1, 2628, 2947, 2948, -1, 2628, 2919, 2947, -1, 2639, 2948, 2949, -1, 2639, 2628, 2948, -1, 2637, 2949, 2950, -1, 2637, 2639, 2949, -1, 2646, 2950, 2951, -1, 2646, 2637, 2950, -1, 2648, 2951, 2952, -1, 2648, 2646, 2951, -1, 2884, 2952, 2953, -1, 2884, 2648, 2952, -1, 2876, 2953, 2954, -1, 2876, 2884, 2953, -1, 2865, 2954, 2955, -1, 2865, 2876, 2954, -1, 2863, 2955, 2956, -1, 2863, 2865, 2955, -1, 2859, 2956, 2957, -1, 2859, 2863, 2956, -1, 2857, 2957, 2958, -1, 2857, 2859, 2957, -1, 2849, 2958, 2959, -1, 2849, 2857, 2958, -1, 2724, 2960, 2961, -1, 2724, 2713, 2960, -1, 2726, 2961, 2962, -1, 2726, 2724, 2961, -1, 2737, 2962, 2963, -1, 2737, 2726, 2962, -1, 2739, 2963, 2964, -1, 2739, 2737, 2963, -1, 2744, 2964, 2965, -1, 2744, 2739, 2964, -1, 2659, 2965, 2966, -1, 2659, 2744, 2965, -1, 2656, 2966, 2967, -1, 2656, 2659, 2966, -1, 2647, 2967, 2968, -1, 2647, 2656, 2967, -1, 2638, 2968, 2969, -1, 2638, 2647, 2968, -1, 2629, 2969, 2970, -1, 2629, 2638, 2969, -1, 2630, 2970, 2971, -1, 2630, 2629, 2970, -1, 2920, 2971, 2972, -1, 2920, 2630, 2971, -1, 2917, 2972, 2973, -1, 2917, 2920, 2972, -1, 2840, 2974, 2975, -1, 2840, 2831, 2974, -1, 2842, 2975, 2976, -1, 2842, 2840, 2975, -1, 2850, 2976, 2977, -1, 2850, 2842, 2976, -1, 2855, 2977, 2978, -1, 2855, 2850, 2977, -1, 2856, 2978, 2979, -1, 2856, 2855, 2978, -1, 2779, 2979, 2980, -1, 2779, 2856, 2979, -1, 2756, 2980, 2981, -1, 2756, 2779, 2980, -1, 2745, 2981, 2982, -1, 2745, 2756, 2981, -1, 2743, 2982, 2983, -1, 2743, 2745, 2982, -1, 2738, 2983, 2984, -1, 2738, 2743, 2983, -1, 2735, 2984, 2985, -1, 2735, 2738, 2984, -1, 2725, 2985, 2986, -1, 2725, 2735, 2985, -1, 2718, 2986, 2987, -1, 2718, 2725, 2986, -1, 2886, 2988, 2989, -1, 2886, 2881, 2988, -1, 2887, 2989, 2990, -1, 2887, 2886, 2989, -1, 2891, 2990, 2991, -1, 2891, 2887, 2990, -1, 2893, 2991, 2992, -1, 2893, 2891, 2991, -1, 2895, 2992, 2993, -1, 2895, 2893, 2992, -1, 2788, 2993, 2994, -1, 2788, 2895, 2993, -1, 2790, 2994, 2995, -1, 2790, 2788, 2994, -1, 2858, 2995, 2996, -1, 2858, 2790, 2995, -1, 2853, 2996, 2997, -1, 2853, 2858, 2996, -1, 2851, 2997, 2998, -1, 2851, 2853, 2997, -1, 2846, 2998, 2999, -1, 2846, 2851, 2998, -1, 2841, 2999, 3000, -1, 2841, 2846, 2999, -1, 2837, 3000, 3001, -1, 2837, 2841, 3000, -1, 2926, 3002, 3003, -1, 2926, 2625, 3002, -1, 2635, 3003, 3004, -1, 2635, 2926, 3003, -1, 2654, 3004, 3005, -1, 2654, 2635, 3004, -1, 2664, 3005, 3006, -1, 2664, 2654, 3005, -1, 2665, 3006, 3007, -1, 2665, 2664, 3006, -1, 2682, 3007, 3008, -1, 2682, 2665, 3007, -1, 2787, 3008, 3009, -1, 2787, 2682, 3008, -1, 2896, 3009, 3010, -1, 2896, 2787, 3009, -1, 2894, 3010, 3011, -1, 2894, 2896, 3010, -1, 2892, 3011, 3012, -1, 2892, 2894, 3011, -1, 2890, 3012, 3013, -1, 2890, 2892, 3012, -1, 2885, 3013, 3014, -1, 2885, 2890, 3013, -1, 2883, 3014, 3015, -1, 2883, 2885, 3014, -1, 2769, 3016, 3017, -1, 2769, 2692, 3016, -1, 2771, 3017, 3018, -1, 2771, 2769, 3017, -1, 2772, 3018, 3019, -1, 2772, 2771, 3018, -1, 2784, 3019, 3020, -1, 2784, 2772, 3019, -1, 2785, 3020, 3021, -1, 2785, 2784, 3020, -1, 2786, 3021, 3022, -1, 2786, 2785, 3021, -1, 2683, 3022, 3023, -1, 2683, 2786, 3022, -1, 2668, 3023, 3024, -1, 2668, 2683, 3023, -1, 2663, 3024, 3025, -1, 2663, 2668, 3024, -1, 2653, 3025, 3026, -1, 2653, 2663, 3025, -1, 2636, 3026, 3027, -1, 2636, 2653, 3026, -1, 2626, 3027, 3028, -1, 2626, 2636, 3027, -1, 2627, 3028, 3029, -1, 2627, 2626, 3028, -1, 3030, 3031, 3032, -1, 3032, 3033, 3030, -1, 3034, 3035, 3033, -1, 3035, 3036, 3037, -1, 3038, 3039, 3036, -1, 3040, 3041, 3042, -1, 3043, 3044, 3031, -1, 3045, 3046, 3044, -1, 3044, 3046, 3031, -1, 3047, 3048, 3046, -1, 3047, 3049, 3048, -1, 3049, 3050, 3051, -1, 3052, 3053, 3045, -1, 3054, 3053, 3052, -1, 3045, 3053, 3046, -1, 3055, 3056, 2349, -1, 3057, 2432, 3056, -1, 3036, 3056, 3037, -1, 3037, 3056, 3040, -1, 3040, 3056, 3041, -1, 3041, 3056, 3054, -1, 3054, 3056, 3053, -1, 3053, 3056, 3055, -1, 2432, 2349, 3056, -1, 3048, 3032, 3031, -1, 3048, 3031, 3046, -1, 3035, 3038, 3036, -1, 3031, 3040, 3058, -1, 3031, 3058, 3043, -1, 3058, 3040, 3042, -1, 3037, 3030, 3033, -1, 3037, 3033, 3035, -1, 3047, 3055, 3049, -1, 3049, 3055, 3050, -1, 3050, 3055, 2349, -1, 3059, 3060, 3061, -1, 3061, 3062, 3059, -1, 3061, 3063, 3062, -1, 3060, 3064, 3061, -1, 3050, 3065, 3051, -1, 3065, 3066, 3051, -1, 3066, 3067, 3051, -1, 3061, 3068, 3063, -1, 3069, 3070, 3068, -1, 3071, 3070, 3069, -1, 3070, 3072, 3068, -1, 3068, 3072, 3063, -1, 3070, 3073, 3072, -1, 3074, 3075, 3070, -1, 3076, 3075, 3074, -1, 3070, 3075, 3073, -1, 3069, 3051, 3071, -1, 3071, 3051, 3067, -1, 3077, 3078, 3079, -1, 3080, 3078, 3081, -1, 3081, 3078, 3082, -1, 3082, 3078, 3077, -1, 3083, 3084, 3080, -1, 3080, 3084, 3078, -1, 3085, 3086, 3087, -1, 3086, 3088, 3087, -1, 3087, 3089, 3083, -1, 3083, 3089, 3084, -1, 3088, 3089, 3087, -1, 3089, 3090, 3084, -1, 3089, 3091, 3090, -1, 3091, 3092, 3090, -1, 3093, 3034, 3094, -1, 3094, 3034, 3092, -1, 3093, 3035, 3034, -1, 3034, 3090, 3092, -1, 3095, 3096, 3097, -1, 3096, 3098, 3097, -1, 3097, 3048, 3049, -1, 3098, 3048, 3097, -1, 3099, 3100, 3032, -1, 3101, 3100, 3099, -1, 3102, 3100, 3101, -1, 3100, 3033, 3032, -1, 3103, 3104, 3105, -1, 3105, 3106, 3103, -1, 3107, 3108, 3106, -1, 2481, 3109, 3110, -1, 2489, 3111, 3109, -1, 3112, 3113, 3114, -1, 3112, 3115, 3113, -1, 3115, 3116, 3117, -1, 3118, 3119, 3104, -1, 3104, 3119, 3114, -1, 3120, 3121, 3116, -1, 3122, 3123, 3121, -1, 3109, 3121, 3110, -1, 3110, 3121, 3118, -1, 3118, 3121, 3119, -1, 3119, 3121, 3120, -1, 3123, 3116, 3121, -1, 3113, 3105, 3104, -1, 3113, 3104, 3114, -1, 2481, 2489, 3109, -1, 3112, 3120, 3115, -1, 3115, 3120, 3116, -1, 3110, 3103, 3106, -1, 3110, 3106, 3108, -1, 3110, 3108, 2481, -1, 3124, 3125, 3126, -1, 3126, 3127, 3124, -1, 3126, 3128, 3127, -1, 3125, 3129, 3126, -1, 3116, 3130, 3117, -1, 3130, 3131, 3117, -1, 3131, 3132, 3117, -1, 3126, 3133, 3128, -1, 3134, 3135, 3132, -1, 3135, 3136, 3133, -1, 3134, 3136, 3135, -1, 3136, 3137, 3133, -1, 3133, 3137, 3128, -1, 3138, 3139, 3136, -1, 3140, 3139, 3138, -1, 3136, 3139, 3137, -1, 3140, 3141, 3139, -1, 3135, 3117, 3132, -1, 3142, 3143, 3144, -1, 3145, 3143, 3146, -1, 3146, 3143, 3147, -1, 3147, 3143, 3142, -1, 3148, 3149, 3150, -1, 3149, 3151, 3150, -1, 3151, 3152, 3150, -1, 3152, 3153, 3150, -1, 3150, 3154, 3145, -1, 3145, 3154, 3143, -1, 3153, 3154, 3150, -1, 3153, 3155, 3154, -1, 3153, 3156, 3155, -1, 3157, 3107, 3158, -1, 3158, 3107, 3159, -1, 3157, 3108, 3107, -1, 3107, 3155, 3156, -1, 3107, 3156, 3159, -1, 3160, 2166, 2156, -1, 3160, 2156, 2455, -1, 3161, 2455, 2451, -1, 3161, 3160, 2455, -1, 3162, 2451, 2445, -1, 3162, 3161, 2451, -1, 3163, 2445, 2444, -1, 3163, 3162, 2445, -1, 3164, 2444, 2446, -1, 3164, 2446, 2447, -1, 3164, 3163, 2444, -1, 3165, 2447, 2432, -1, 3165, 3164, 2447, -1, 3057, 3165, 2432, -1, 3166, 3111, 2489, -1, 3166, 2489, 2503, -1, 3167, 2503, 2502, -1, 3167, 3166, 2503, -1, 3168, 2502, 2508, -1, 3168, 3167, 2502, -1, 3169, 2508, 2506, -1, 3169, 3168, 2508, -1, 3170, 2506, 2505, -1, 3170, 3169, 2506, -1, 3171, 2505, 2507, -1, 3171, 3170, 2505, -1, 1927, 2507, 1925, -1, 1927, 3171, 2507, -1, 3126, 3172, 3173, -1, 3174, 3061, 3064, -1, 3175, 3061, 3174, -1, 3126, 3176, 3172, -1, 3175, 3177, 3061, -1, 3178, 3175, 3174, -1, 3178, 3174, 3179, -1, 3178, 3179, 3180, -1, 3178, 3180, 3181, -1, 3126, 3129, 3176, -1, 3178, 3181, 3182, -1, 3178, 3182, 3183, -1, 3178, 3183, 3184, -1, 3178, 3184, 3185, -1, 3186, 3172, 3187, -1, 3187, 3172, 3188, -1, 3188, 3172, 3189, -1, 3189, 3172, 3190, -1, 3190, 3172, 3191, -1, 3191, 3172, 3192, -1, 3192, 3172, 3193, -1, 3193, 3172, 3176, -1, 3185, 3176, 3079, -1, 3079, 3176, 3194, -1, 3194, 3176, 3195, -1, 3195, 3176, 3196, -1, 3196, 3176, 3197, -1, 3197, 3176, 3198, -1, 3198, 3176, 3199, -1, 3199, 3176, 3129, -1, 3193, 3184, 3192, -1, 3192, 3184, 3183, -1, 3187, 3174, 3144, -1, 3144, 3174, 3200, -1, 3200, 3174, 3201, -1, 3201, 3174, 3202, -1, 3202, 3174, 3203, -1, 3203, 3174, 3204, -1, 3204, 3174, 3205, -1, 3205, 3174, 3064, -1, 3179, 3188, 3180, -1, 3180, 3188, 3189, -1, 3078, 3185, 3079, -1, 3078, 3178, 3185, -1, 3078, 3206, 3178, -1, 3182, 3181, 3191, -1, 3191, 3181, 3190, -1, 3187, 3143, 3186, -1, 3186, 3143, 3207, -1, 3187, 3144, 3143, -1, 3208, 3209, 3205, -1, 3210, 3209, 3208, -1, 3211, 3209, 3210, -1, 3212, 3209, 3211, -1, 3213, 3214, 3215, -1, 3216, 3214, 3213, -1, 3214, 3217, 3215, -1, 3215, 3204, 3209, -1, 3209, 3204, 3205, -1, 3217, 3204, 3215, -1, 3218, 3219, 3203, -1, 3220, 3219, 3218, -1, 3221, 3219, 3220, -1, 3222, 3219, 3221, -1, 3223, 3224, 3225, -1, 3224, 3226, 3225, -1, 3225, 3202, 3219, -1, 3219, 3202, 3203, -1, 3225, 3227, 3202, -1, 3226, 3227, 3225, -1, 3228, 3229, 3230, -1, 3229, 3231, 3230, -1, 3230, 3232, 3201, -1, 3231, 3232, 3230, -1, 3233, 3234, 3235, -1, 3235, 3200, 3232, -1, 3232, 3200, 3201, -1, 3236, 3237, 3234, -1, 3234, 3237, 3235, -1, 3235, 3237, 3200, -1, 3238, 3239, 3240, -1, 3239, 3241, 3240, -1, 3240, 3242, 3199, -1, 3241, 3242, 3240, -1, 3242, 3243, 3199, -1, 3244, 3245, 3243, -1, 3246, 3245, 3244, -1, 3245, 3247, 3243, -1, 3243, 3198, 3199, -1, 3247, 3198, 3243, -1, 3248, 3249, 3250, -1, 3249, 3251, 3250, -1, 3250, 3252, 3197, -1, 3251, 3252, 3250, -1, 3253, 3254, 3255, -1, 3255, 3254, 3256, -1, 3254, 3257, 3256, -1, 3256, 3196, 3252, -1, 3252, 3196, 3197, -1, 3257, 3196, 3256, -1, 3258, 3259, 3260, -1, 3259, 3261, 3260, -1, 3260, 3262, 3195, -1, 3261, 3262, 3260, -1, 3263, 3264, 3265, -1, 3265, 3264, 3266, -1, 3266, 3194, 3262, -1, 3262, 3194, 3195, -1, 3264, 3267, 3266, -1, 3266, 3267, 3194, -1, 3106, 3105, 3268, -1, 3105, 3269, 3268, -1, 3269, 3270, 3268, -1, 3270, 3271, 3268, -1, 3268, 3272, 3106, -1, 3272, 3107, 3106, -1, 3207, 3143, 3273, -1, 3143, 3274, 3273, -1, 3275, 3107, 3276, -1, 3155, 3107, 3275, -1, 3107, 3272, 3276, -1, 3277, 3143, 3154, -1, 3278, 3143, 3277, -1, 3278, 3274, 3143, -1, 3279, 3271, 3280, -1, 3271, 3281, 3268, -1, 3279, 3281, 3271, -1, 3281, 3279, 3282, -1, 3279, 3283, 3282, -1, 3268, 3281, 3272, -1, 3280, 3284, 3279, -1, 3282, 3272, 3281, -1, 3276, 3272, 3282, -1, 3283, 3285, 3282, -1, 3286, 3285, 3283, -1, 3287, 3288, 3289, -1, 3290, 3287, 3291, -1, 3292, 3293, 3294, -1, 3295, 3288, 3287, -1, 3296, 3294, 3293, -1, 3297, 3291, 3298, -1, 3297, 3298, 3299, -1, 3300, 3292, 3294, -1, 3301, 3294, 3296, -1, 3297, 3290, 3291, -1, 3302, 3288, 3295, -1, 3303, 3300, 3294, -1, 3304, 3297, 3299, -1, 3305, 3294, 3301, -1, 3306, 3288, 3302, -1, 3307, 3294, 3305, -1, 3308, 3299, 3309, -1, 3308, 3304, 3299, -1, 3310, 3294, 3307, -1, 3311, 3288, 3306, -1, 3312, 3308, 3309, -1, 3312, 3309, 3313, -1, 3314, 3288, 3311, -1, 3289, 3294, 3310, -1, 3315, 3313, 3316, -1, 3315, 3316, 3317, -1, 3315, 3312, 3313, -1, 3318, 3288, 3314, -1, 3319, 3315, 3317, -1, 3320, 3288, 3318, -1, 3321, 3288, 3320, -1, 3322, 3288, 3321, -1, 3285, 3323, 3324, -1, 3285, 3324, 3325, -1, 3285, 3325, 3326, -1, 3285, 3326, 3327, -1, 3285, 3327, 3328, -1, 3285, 3328, 3329, -1, 3285, 3329, 3303, -1, 3285, 3317, 3330, -1, 3285, 3330, 3331, -1, 3285, 3331, 3323, -1, 3285, 3303, 3294, -1, 3286, 3317, 3285, -1, 3286, 3332, 3333, -1, 3286, 3333, 3334, -1, 3286, 3334, 3319, -1, 3286, 3319, 3317, -1, 3288, 3294, 3289, -1, 3286, 3322, 3335, -1, 3286, 3335, 3336, -1, 3286, 3336, 3337, -1, 3286, 3337, 3338, -1, 3287, 3289, 3291, -1, 3286, 3288, 3322, -1, 3286, 3338, 3339, -1, 3286, 3339, 3340, -1, 3286, 3340, 3332, -1, 3341, 3305, 3342, -1, 3342, 3301, 3343, -1, 3305, 3301, 3342, -1, 3343, 3296, 3344, -1, 3301, 3296, 3343, -1, 3344, 3293, 3345, -1, 3296, 3293, 3344, -1, 3345, 3292, 3346, -1, 3293, 3292, 3345, -1, 3346, 3300, 3347, -1, 3292, 3300, 3346, -1, 3347, 3303, 3348, -1, 3300, 3303, 3347, -1, 3348, 3329, 3349, -1, 3303, 3329, 3348, -1, 3349, 3328, 3350, -1, 3329, 3328, 3349, -1, 3350, 3327, 3351, -1, 3328, 3327, 3350, -1, 3351, 3326, 3352, -1, 3327, 3326, 3351, -1, 3352, 3325, 3353, -1, 3326, 3325, 3352, -1, 3353, 3324, 3354, -1, 3325, 3324, 3353, -1, 3324, 3323, 3354, -1, 3355, 3306, 3356, -1, 3356, 3302, 3357, -1, 3306, 3302, 3356, -1, 3357, 3295, 3358, -1, 3302, 3295, 3357, -1, 3358, 3287, 3359, -1, 3295, 3287, 3358, -1, 3359, 3290, 3360, -1, 3287, 3290, 3359, -1, 3360, 3297, 3361, -1, 3290, 3297, 3360, -1, 3361, 3304, 3362, -1, 3297, 3304, 3361, -1, 3362, 3308, 3363, -1, 3304, 3308, 3362, -1, 3363, 3312, 3364, -1, 3308, 3312, 3363, -1, 3364, 3315, 3365, -1, 3312, 3315, 3364, -1, 3365, 3319, 3366, -1, 3315, 3319, 3365, -1, 3366, 3334, 3367, -1, 3319, 3334, 3366, -1, 3367, 3333, 3368, -1, 3334, 3333, 3367, -1, 3333, 3332, 3368, -1, 3368, 3332, 3369, -1, 3369, 3340, 3370, -1, 3332, 3340, 3369, -1, 3370, 3339, 3371, -1, 3340, 3339, 3370, -1, 3371, 3338, 3372, -1, 3339, 3338, 3371, -1, 3372, 3337, 3373, -1, 3338, 3337, 3372, -1, 3373, 3336, 3374, -1, 3337, 3336, 3373, -1, 3374, 3335, 3375, -1, 3336, 3335, 3374, -1, 3375, 3322, 3376, -1, 3335, 3322, 3375, -1, 3376, 3321, 3377, -1, 3322, 3321, 3376, -1, 3377, 3320, 3378, -1, 3321, 3320, 3377, -1, 3378, 3318, 3379, -1, 3320, 3318, 3378, -1, 3379, 3314, 3380, -1, 3318, 3314, 3379, -1, 3380, 3311, 3355, -1, 3314, 3311, 3380, -1, 3311, 3306, 3355, -1, 3354, 3323, 3381, -1, 3381, 3331, 3382, -1, 3323, 3331, 3381, -1, 3382, 3330, 3383, -1, 3331, 3330, 3382, -1, 3383, 3317, 3384, -1, 3330, 3317, 3383, -1, 3384, 3316, 3385, -1, 3317, 3316, 3384, -1, 3385, 3313, 3386, -1, 3316, 3313, 3385, -1, 3386, 3309, 3387, -1, 3313, 3309, 3386, -1, 3387, 3299, 3388, -1, 3309, 3299, 3387, -1, 3388, 3298, 3389, -1, 3299, 3298, 3388, -1, 3389, 3291, 3390, -1, 3298, 3291, 3389, -1, 3390, 3289, 3391, -1, 3291, 3289, 3390, -1, 3391, 3310, 3392, -1, 3289, 3310, 3391, -1, 3392, 3307, 3341, -1, 3310, 3307, 3392, -1, 3307, 3305, 3341, -1, 3393, 3279, 3284, -1, 3283, 3279, 3393, -1, 3393, 3394, 3395, -1, 3284, 3394, 3393, -1, 3394, 3280, 3273, -1, 3394, 3284, 3280, -1, 3276, 3282, 3285, -1, 3393, 3286, 3283, -1, 3273, 3274, 3394, -1, 3277, 3155, 3275, -1, 3277, 3154, 3155, -1, 3285, 3294, 3275, -1, 3285, 3275, 3276, -1, 3395, 3286, 3393, -1, 3288, 3286, 3395, -1, 3278, 3394, 3274, -1, 3395, 3394, 3278, -1, 3277, 3275, 3294, -1, 3288, 3395, 3278, -1, 3277, 3288, 3278, -1, 3294, 3288, 3277, -1, 3390, 3391, 3389, -1, 3391, 3392, 3389, -1, 3341, 3342, 3392, -1, 3387, 3385, 3386, -1, 3388, 3385, 3387, -1, 3343, 3345, 3342, -1, 3344, 3345, 3343, -1, 3384, 3382, 3383, -1, 3382, 3354, 3381, -1, 3385, 3354, 3384, -1, 3389, 3354, 3388, -1, 3392, 3354, 3389, -1, 3342, 3354, 3392, -1, 3345, 3354, 3342, -1, 3388, 3354, 3385, -1, 3384, 3354, 3382, -1, 3346, 3349, 3345, -1, 3347, 3349, 3346, -1, 3348, 3349, 3347, -1, 3345, 3349, 3354, -1, 3354, 3352, 3353, -1, 3350, 3351, 3349, -1, 3349, 3351, 3354, -1, 3354, 3351, 3352, -1, 3378, 3379, 3377, -1, 3379, 3380, 3377, -1, 3355, 3356, 3380, -1, 3375, 3373, 3374, -1, 3376, 3373, 3375, -1, 3357, 3359, 3356, -1, 3358, 3359, 3357, -1, 3372, 3370, 3371, -1, 3370, 3368, 3369, -1, 3373, 3368, 3372, -1, 3377, 3368, 3376, -1, 3380, 3368, 3377, -1, 3356, 3368, 3380, -1, 3359, 3368, 3356, -1, 3376, 3368, 3373, -1, 3372, 3368, 3370, -1, 3360, 3363, 3359, -1, 3361, 3363, 3360, -1, 3362, 3363, 3361, -1, 3359, 3363, 3368, -1, 3368, 3366, 3367, -1, 3364, 3365, 3363, -1, 3363, 3365, 3368, -1, 3368, 3365, 3366, -1, 3396, 3123, 3122, -1, 3396, 3122, 3397, -1, 3398, 3397, 3399, -1, 3398, 3396, 3397, -1, 3400, 3399, 3401, -1, 3400, 3398, 3399, -1, 2797, 3401, 3402, -1, 2797, 3400, 3401, -1, 2844, 3402, 3403, -1, 2844, 2797, 3402, -1, 2845, 3403, 3404, -1, 2845, 2844, 3403, -1, 2848, 3404, 1971, -1, 2848, 2845, 3404, -1, 1973, 2848, 1971, -1, 2794, 2095, 2094, -1, 2794, 2094, 3405, -1, 2792, 3405, 3406, -1, 2792, 2794, 3405, -1, 2793, 3406, 3407, -1, 2793, 2792, 3406, -1, 2795, 3407, 3408, -1, 2795, 2793, 3407, -1, 3409, 3408, 3410, -1, 3409, 2795, 3408, -1, 3411, 3410, 3412, -1, 3411, 3409, 3410, -1, 3413, 3412, 3039, -1, 3413, 3411, 3412, -1, 3038, 3413, 3039, -1, 3414, 3061, 3177, -1, 3415, 3061, 3414, -1, 3051, 3416, 3049, -1, 3049, 3416, 3097, -1, 3068, 3061, 3417, -1, 3415, 3418, 3061, -1, 3061, 3418, 3417, -1, 3416, 3051, 3419, -1, 3051, 3420, 3419, -1, 3051, 3069, 3420, -1, 3421, 3415, 3414, -1, 3422, 3421, 3414, -1, 3423, 3421, 3422, -1, 3424, 3423, 3425, -1, 3421, 3423, 3424, -1, 3423, 3422, 3426, -1, 3424, 3415, 3421, -1, 3418, 3415, 3424, -1, 3427, 3428, 3424, -1, 3427, 3424, 3425, -1, 3429, 3430, 3431, -1, 3432, 3429, 3431, -1, 3432, 3431, 3433, -1, 3434, 3435, 3430, -1, 3436, 3427, 3429, -1, 3437, 3430, 3435, -1, 3438, 3433, 3439, -1, 3438, 3432, 3433, -1, 3440, 3434, 3430, -1, 3441, 3430, 3437, -1, 3442, 3427, 3436, -1, 3443, 3440, 3430, -1, 3444, 3439, 3445, -1, 3444, 3438, 3439, -1, 3446, 3430, 3441, -1, 3447, 3427, 3442, -1, 3448, 3444, 3445, -1, 3448, 3445, 3449, -1, 3450, 3430, 3446, -1, 3451, 3427, 3447, -1, 3452, 3430, 3450, -1, 3453, 3449, 3454, -1, 3453, 3448, 3449, -1, 3455, 3427, 3451, -1, 3431, 3430, 3452, -1, 3456, 3454, 3457, -1, 3456, 3457, 3458, -1, 3456, 3453, 3454, -1, 3459, 3427, 3455, -1, 3460, 3456, 3458, -1, 3461, 3427, 3459, -1, 3462, 3427, 3461, -1, 3463, 3427, 3462, -1, 3464, 3465, 3466, -1, 3464, 3466, 3467, -1, 3464, 3467, 3468, -1, 3464, 3468, 3469, -1, 3464, 3469, 3470, -1, 3464, 3470, 3471, -1, 3464, 3471, 3443, -1, 3464, 3458, 3472, -1, 3464, 3472, 3473, -1, 3464, 3473, 3465, -1, 3464, 3443, 3430, -1, 3428, 3458, 3464, -1, 3428, 3474, 3475, -1, 3428, 3475, 3476, -1, 3428, 3476, 3460, -1, 3428, 3460, 3458, -1, 3428, 3427, 3463, -1, 3428, 3463, 3477, -1, 3428, 3477, 3478, -1, 3428, 3478, 3479, -1, 3428, 3479, 3480, -1, 3428, 3480, 3481, -1, 3428, 3481, 3482, -1, 3428, 3482, 3474, -1, 3429, 3427, 3430, -1, 3446, 3441, 3483, -1, 3483, 3441, 3484, -1, 3484, 3437, 3485, -1, 3441, 3437, 3484, -1, 3485, 3435, 3486, -1, 3437, 3435, 3485, -1, 3486, 3434, 3487, -1, 3435, 3434, 3486, -1, 3487, 3440, 3488, -1, 3434, 3440, 3487, -1, 3488, 3443, 3489, -1, 3440, 3443, 3488, -1, 3489, 3471, 3490, -1, 3443, 3471, 3489, -1, 3490, 3470, 3491, -1, 3471, 3470, 3490, -1, 3491, 3469, 3492, -1, 3470, 3469, 3491, -1, 3492, 3468, 3493, -1, 3469, 3468, 3492, -1, 3493, 3467, 3494, -1, 3468, 3467, 3493, -1, 3494, 3466, 3495, -1, 3467, 3466, 3494, -1, 3495, 3465, 3496, -1, 3466, 3465, 3495, -1, 3447, 3442, 3497, -1, 3497, 3442, 3498, -1, 3498, 3436, 3499, -1, 3442, 3436, 3498, -1, 3499, 3429, 3500, -1, 3436, 3429, 3499, -1, 3500, 3432, 3501, -1, 3429, 3432, 3500, -1, 3501, 3438, 3502, -1, 3432, 3438, 3501, -1, 3502, 3444, 3503, -1, 3438, 3444, 3502, -1, 3503, 3448, 3504, -1, 3444, 3448, 3503, -1, 3504, 3453, 3505, -1, 3448, 3453, 3504, -1, 3505, 3456, 3506, -1, 3453, 3456, 3505, -1, 3506, 3460, 3507, -1, 3456, 3460, 3506, -1, 3507, 3476, 3508, -1, 3460, 3476, 3507, -1, 3508, 3475, 3509, -1, 3476, 3475, 3508, -1, 3509, 3474, 3510, -1, 3475, 3474, 3509, -1, 3474, 3482, 3510, -1, 3510, 3482, 3511, -1, 3511, 3481, 3512, -1, 3482, 3481, 3511, -1, 3512, 3480, 3513, -1, 3481, 3480, 3512, -1, 3513, 3479, 3514, -1, 3480, 3479, 3513, -1, 3514, 3478, 3515, -1, 3479, 3478, 3514, -1, 3515, 3477, 3516, -1, 3478, 3477, 3515, -1, 3516, 3463, 3517, -1, 3477, 3463, 3516, -1, 3517, 3462, 3518, -1, 3463, 3462, 3517, -1, 3518, 3461, 3519, -1, 3462, 3461, 3518, -1, 3519, 3459, 3520, -1, 3461, 3459, 3519, -1, 3520, 3455, 3521, -1, 3459, 3455, 3520, -1, 3521, 3451, 3522, -1, 3455, 3451, 3521, -1, 3522, 3447, 3497, -1, 3451, 3447, 3522, -1, 3465, 3473, 3496, -1, 3496, 3473, 3523, -1, 3523, 3472, 3524, -1, 3473, 3472, 3523, -1, 3524, 3458, 3525, -1, 3472, 3458, 3524, -1, 3525, 3457, 3526, -1, 3458, 3457, 3525, -1, 3526, 3454, 3527, -1, 3457, 3454, 3526, -1, 3527, 3449, 3528, -1, 3454, 3449, 3527, -1, 3528, 3445, 3529, -1, 3449, 3445, 3528, -1, 3529, 3439, 3530, -1, 3445, 3439, 3529, -1, 3530, 3433, 3531, -1, 3439, 3433, 3530, -1, 3531, 3431, 3532, -1, 3433, 3431, 3531, -1, 3532, 3452, 3533, -1, 3431, 3452, 3532, -1, 3533, 3450, 3534, -1, 3452, 3450, 3533, -1, 3534, 3446, 3483, -1, 3450, 3446, 3534, -1, 3535, 3423, 3426, -1, 3425, 3423, 3535, -1, 3536, 3535, 3537, -1, 3535, 3426, 3537, -1, 3537, 3095, 3097, -1, 3095, 3426, 3422, -1, 3537, 3426, 3095, -1, 3424, 3428, 3418, -1, 3425, 3535, 3427, -1, 3537, 3097, 3416, -1, 3420, 3068, 3417, -1, 3420, 3069, 3068, -1, 3428, 3464, 3417, -1, 3428, 3417, 3418, -1, 3430, 3427, 3535, -1, 3430, 3535, 3536, -1, 3419, 3537, 3416, -1, 3536, 3537, 3419, -1, 3417, 3464, 3420, -1, 3430, 3536, 3419, -1, 3464, 3430, 3419, -1, 3464, 3419, 3420, -1, 3532, 3530, 3531, -1, 3533, 3534, 3532, -1, 3532, 3534, 3530, -1, 3530, 3527, 3529, -1, 3529, 3527, 3528, -1, 3534, 3527, 3530, -1, 3527, 3525, 3526, -1, 3487, 3488, 3486, -1, 3486, 3488, 3485, -1, 3485, 3488, 3484, -1, 3483, 3523, 3534, -1, 3525, 3523, 3524, -1, 3534, 3523, 3527, -1, 3527, 3523, 3525, -1, 3483, 3496, 3523, -1, 3484, 3495, 3483, -1, 3483, 3495, 3496, -1, 3490, 3491, 3489, -1, 3489, 3491, 3488, -1, 3488, 3491, 3484, -1, 3484, 3491, 3495, -1, 3495, 3493, 3494, -1, 3492, 3493, 3491, -1, 3491, 3493, 3495, -1, 3520, 3518, 3519, -1, 3521, 3522, 3520, -1, 3520, 3522, 3518, -1, 3518, 3515, 3517, -1, 3517, 3515, 3516, -1, 3522, 3515, 3518, -1, 3515, 3513, 3514, -1, 3501, 3502, 3500, -1, 3500, 3502, 3499, -1, 3499, 3502, 3498, -1, 3497, 3511, 3522, -1, 3513, 3511, 3512, -1, 3522, 3511, 3515, -1, 3515, 3511, 3513, -1, 3497, 3510, 3511, -1, 3498, 3509, 3497, -1, 3497, 3509, 3510, -1, 3504, 3505, 3503, -1, 3503, 3505, 3502, -1, 3502, 3505, 3498, -1, 3498, 3505, 3509, -1, 3509, 3507, 3508, -1, 3506, 3507, 3505, -1, 3505, 3507, 3509, -1, 3538, 3539, 3540, -1, 3541, 3539, 3538, -1, 3113, 3539, 3541, -1, 3115, 3539, 3113, -1, 3542, 3115, 3117, -1, 3539, 3115, 3542, -1, 3173, 3543, 3126, -1, 3126, 3543, 3544, -1, 3545, 3117, 3135, -1, 3117, 3546, 3542, -1, 3545, 3546, 3117, -1, 3547, 3126, 3544, -1, 3547, 3548, 3126, -1, 3548, 3133, 3126, -1, 3549, 3540, 3550, -1, 3540, 3551, 3550, -1, 3540, 3539, 3551, -1, 3550, 3551, 3552, -1, 3551, 3553, 3552, -1, 3542, 3551, 3539, -1, 3550, 3554, 3549, -1, 3546, 3551, 3542, -1, 3553, 3551, 3546, -1, 3555, 3553, 3556, -1, 3552, 3553, 3555, -1, 3557, 3558, 3559, -1, 3557, 3560, 3561, -1, 3557, 3559, 3560, -1, 3562, 3563, 3564, -1, 3565, 3566, 3558, -1, 3567, 3564, 3563, -1, 3568, 3557, 3561, -1, 3569, 3562, 3564, -1, 3568, 3561, 3570, -1, 3571, 3564, 3567, -1, 3572, 3566, 3565, -1, 3573, 3568, 3570, -1, 3574, 3569, 3564, -1, 3575, 3564, 3571, -1, 3576, 3566, 3572, -1, 3577, 3574, 3564, -1, 3578, 3573, 3570, -1, 3579, 3564, 3575, -1, 3578, 3570, 3580, -1, 3581, 3566, 3576, -1, 3582, 3564, 3579, -1, 3583, 3584, 3585, -1, 3583, 3580, 3584, -1, 3583, 3578, 3580, -1, 3559, 3564, 3582, -1, 3586, 3566, 3581, -1, 3587, 3583, 3585, -1, 3588, 3566, 3586, -1, 3589, 3585, 3590, -1, 3589, 3587, 3585, -1, 3589, 3590, 3555, -1, 3591, 3566, 3588, -1, 3592, 3566, 3591, -1, 3593, 3566, 3592, -1, 3555, 3594, 3595, -1, 3555, 3596, 3594, -1, 3555, 3590, 3596, -1, 3555, 3597, 3577, -1, 3555, 3598, 3597, -1, 3555, 3599, 3598, -1, 3555, 3600, 3599, -1, 3555, 3601, 3600, -1, 3555, 3595, 3601, -1, 3555, 3577, 3564, -1, 3556, 3602, 3603, -1, 3556, 3604, 3602, -1, 3556, 3605, 3604, -1, 3556, 3606, 3605, -1, 3556, 3607, 3606, -1, 3556, 3608, 3607, -1, 3556, 3593, 3608, -1, 3556, 3609, 3589, -1, 3556, 3610, 3609, -1, 3556, 3603, 3610, -1, 3556, 3566, 3593, -1, 3556, 3589, 3555, -1, 3558, 3566, 3564, -1, 3558, 3564, 3559, -1, 3576, 3572, 3611, -1, 3611, 3572, 3612, -1, 3612, 3565, 3613, -1, 3572, 3565, 3612, -1, 3613, 3558, 3614, -1, 3565, 3558, 3613, -1, 3614, 3557, 3615, -1, 3558, 3557, 3614, -1, 3615, 3568, 3616, -1, 3557, 3568, 3615, -1, 3616, 3573, 3617, -1, 3568, 3573, 3616, -1, 3617, 3578, 3618, -1, 3573, 3578, 3617, -1, 3618, 3583, 3619, -1, 3578, 3583, 3618, -1, 3619, 3587, 3620, -1, 3583, 3587, 3619, -1, 3620, 3589, 3621, -1, 3587, 3589, 3620, -1, 3621, 3609, 3622, -1, 3589, 3609, 3621, -1, 3622, 3610, 3623, -1, 3609, 3610, 3622, -1, 3623, 3603, 3624, -1, 3610, 3603, 3623, -1, 3575, 3571, 3625, -1, 3625, 3571, 3626, -1, 3626, 3567, 3627, -1, 3571, 3567, 3626, -1, 3627, 3563, 3628, -1, 3567, 3563, 3627, -1, 3628, 3562, 3629, -1, 3563, 3562, 3628, -1, 3629, 3569, 3630, -1, 3562, 3569, 3629, -1, 3630, 3574, 3631, -1, 3569, 3574, 3630, -1, 3631, 3577, 3632, -1, 3574, 3577, 3631, -1, 3632, 3597, 3633, -1, 3577, 3597, 3632, -1, 3633, 3598, 3634, -1, 3597, 3598, 3633, -1, 3634, 3599, 3635, -1, 3598, 3599, 3634, -1, 3635, 3600, 3636, -1, 3599, 3600, 3635, -1, 3636, 3601, 3637, -1, 3600, 3601, 3636, -1, 3637, 3595, 3638, -1, 3601, 3595, 3637, -1, 3595, 3594, 3638, -1, 3638, 3594, 3639, -1, 3639, 3596, 3640, -1, 3594, 3596, 3639, -1, 3640, 3590, 3641, -1, 3596, 3590, 3640, -1, 3641, 3585, 3642, -1, 3590, 3585, 3641, -1, 3642, 3584, 3643, -1, 3585, 3584, 3642, -1, 3643, 3580, 3644, -1, 3584, 3580, 3643, -1, 3644, 3570, 3645, -1, 3580, 3570, 3644, -1, 3645, 3561, 3646, -1, 3570, 3561, 3645, -1, 3646, 3560, 3647, -1, 3561, 3560, 3646, -1, 3647, 3559, 3648, -1, 3560, 3559, 3647, -1, 3648, 3582, 3649, -1, 3559, 3582, 3648, -1, 3649, 3579, 3650, -1, 3582, 3579, 3649, -1, 3650, 3575, 3625, -1, 3579, 3575, 3650, -1, 3603, 3602, 3624, -1, 3624, 3602, 3651, -1, 3651, 3604, 3652, -1, 3602, 3604, 3651, -1, 3652, 3605, 3653, -1, 3604, 3605, 3652, -1, 3653, 3606, 3654, -1, 3605, 3606, 3653, -1, 3654, 3607, 3655, -1, 3606, 3607, 3654, -1, 3655, 3608, 3656, -1, 3607, 3608, 3655, -1, 3656, 3593, 3657, -1, 3608, 3593, 3656, -1, 3657, 3592, 3658, -1, 3593, 3592, 3657, -1, 3658, 3591, 3659, -1, 3592, 3591, 3658, -1, 3659, 3588, 3660, -1, 3591, 3588, 3659, -1, 3660, 3586, 3661, -1, 3588, 3586, 3660, -1, 3661, 3581, 3662, -1, 3586, 3581, 3661, -1, 3662, 3576, 3611, -1, 3581, 3576, 3662, -1, 3552, 3554, 3550, -1, 3663, 3554, 3552, -1, 3554, 3664, 3665, -1, 3663, 3664, 3554, -1, 3665, 3549, 3554, -1, 3543, 3549, 3665, -1, 3556, 3553, 3546, -1, 3552, 3555, 3663, -1, 3665, 3544, 3543, -1, 3548, 3135, 3133, -1, 3545, 3135, 3548, -1, 3556, 3545, 3566, -1, 3546, 3545, 3556, -1, 3664, 3663, 3555, -1, 3664, 3555, 3564, -1, 3664, 3544, 3665, -1, 3547, 3544, 3664, -1, 3566, 3545, 3548, -1, 3547, 3664, 3564, -1, 3548, 3547, 3564, -1, 3548, 3564, 3566, -1, 3623, 3624, 3622, -1, 3622, 3624, 3621, -1, 3621, 3624, 3620, -1, 3620, 3624, 3619, -1, 3619, 3617, 3618, -1, 3624, 3616, 3619, -1, 3619, 3616, 3617, -1, 3651, 3652, 3624, -1, 3652, 3653, 3624, -1, 3616, 3614, 3615, -1, 3624, 3614, 3616, -1, 3653, 3654, 3624, -1, 3654, 3655, 3624, -1, 3614, 3612, 3613, -1, 3624, 3612, 3614, -1, 3612, 3662, 3611, -1, 3624, 3662, 3612, -1, 3657, 3658, 3656, -1, 3656, 3658, 3655, -1, 3655, 3658, 3624, -1, 3662, 3660, 3661, -1, 3659, 3660, 3658, -1, 3658, 3660, 3624, -1, 3624, 3660, 3662, -1, 3637, 3638, 3636, -1, 3636, 3638, 3635, -1, 3635, 3638, 3634, -1, 3634, 3638, 3633, -1, 3633, 3631, 3632, -1, 3638, 3630, 3633, -1, 3633, 3630, 3631, -1, 3639, 3640, 3638, -1, 3640, 3641, 3638, -1, 3630, 3628, 3629, -1, 3638, 3628, 3630, -1, 3641, 3642, 3638, -1, 3642, 3643, 3638, -1, 3628, 3626, 3627, -1, 3638, 3626, 3628, -1, 3626, 3650, 3625, -1, 3638, 3650, 3626, -1, 3645, 3646, 3644, -1, 3644, 3646, 3643, -1, 3643, 3646, 3638, -1, 3650, 3648, 3649, -1, 3647, 3648, 3646, -1, 3646, 3648, 3638, -1, 3638, 3648, 3650, -1, 3666, 3206, 3078, -1, 3667, 3206, 3666, -1, 3033, 3100, 3034, -1, 3034, 3100, 3668, -1, 3078, 3669, 3666, -1, 3084, 3670, 3078, -1, 3078, 3670, 3669, -1, 3668, 3671, 3034, -1, 3034, 3672, 3090, -1, 3671, 3672, 3034, -1, 3667, 3666, 3673, -1, 3674, 3667, 3673, -1, 3675, 3667, 3674, -1, 3673, 3676, 3674, -1, 3677, 3676, 3673, -1, 3678, 3675, 3674, -1, 3669, 3673, 3666, -1, 3677, 3673, 3669, -1, 3679, 3677, 3680, -1, 3676, 3677, 3679, -1, 3681, 3679, 3682, -1, 3683, 3681, 3682, -1, 3683, 3682, 3684, -1, 3685, 3686, 3679, -1, 3687, 3688, 3681, -1, 3689, 3679, 3686, -1, 3690, 3683, 3684, -1, 3691, 3685, 3679, -1, 3690, 3692, 3693, -1, 3690, 3684, 3692, -1, 3694, 3679, 3689, -1, 3695, 3688, 3687, -1, 3696, 3691, 3679, -1, 3697, 3690, 3693, -1, 3698, 3679, 3694, -1, 3699, 3688, 3695, -1, 3700, 3679, 3698, -1, 3701, 3697, 3693, -1, 3701, 3693, 3702, -1, 3703, 3688, 3699, -1, 3704, 3679, 3700, -1, 3705, 3701, 3702, -1, 3705, 3706, 3707, -1, 3705, 3702, 3706, -1, 3682, 3679, 3704, -1, 3708, 3688, 3703, -1, 3709, 3705, 3707, -1, 3710, 3688, 3708, -1, 3711, 3707, 3712, -1, 3711, 3709, 3707, -1, 3713, 3688, 3710, -1, 3714, 3688, 3713, -1, 3715, 3688, 3714, -1, 3680, 3716, 3717, -1, 3680, 3718, 3716, -1, 3680, 3712, 3718, -1, 3680, 3719, 3696, -1, 3680, 3720, 3719, -1, 3680, 3721, 3720, -1, 3680, 3722, 3721, -1, 3680, 3723, 3722, -1, 3680, 3724, 3723, -1, 3680, 3717, 3724, -1, 3680, 3696, 3679, -1, 3725, 3726, 3727, -1, 3725, 3728, 3726, -1, 3725, 3729, 3728, -1, 3725, 3730, 3729, -1, 3725, 3731, 3730, -1, 3725, 3732, 3731, -1, 3725, 3715, 3732, -1, 3725, 3711, 3712, -1, 3725, 3733, 3711, -1, 3725, 3734, 3733, -1, 3725, 3727, 3734, -1, 3725, 3688, 3715, -1, 3725, 3712, 3680, -1, 3681, 3688, 3679, -1, 3699, 3695, 3735, -1, 3735, 3695, 3736, -1, 3736, 3687, 3737, -1, 3695, 3687, 3736, -1, 3737, 3681, 3738, -1, 3687, 3681, 3737, -1, 3738, 3683, 3739, -1, 3681, 3683, 3738, -1, 3739, 3690, 3740, -1, 3683, 3690, 3739, -1, 3740, 3697, 3741, -1, 3690, 3697, 3740, -1, 3741, 3701, 3742, -1, 3697, 3701, 3741, -1, 3742, 3705, 3743, -1, 3701, 3705, 3742, -1, 3743, 3709, 3744, -1, 3705, 3709, 3743, -1, 3744, 3711, 3745, -1, 3709, 3711, 3744, -1, 3745, 3733, 3746, -1, 3711, 3733, 3745, -1, 3746, 3734, 3747, -1, 3733, 3734, 3746, -1, 3747, 3727, 3748, -1, 3734, 3727, 3747, -1, 3698, 3694, 3749, -1, 3749, 3694, 3750, -1, 3750, 3689, 3751, -1, 3694, 3689, 3750, -1, 3751, 3686, 3752, -1, 3689, 3686, 3751, -1, 3752, 3685, 3753, -1, 3686, 3685, 3752, -1, 3753, 3691, 3754, -1, 3685, 3691, 3753, -1, 3754, 3696, 3755, -1, 3691, 3696, 3754, -1, 3755, 3719, 3756, -1, 3696, 3719, 3755, -1, 3756, 3720, 3757, -1, 3719, 3720, 3756, -1, 3757, 3721, 3758, -1, 3720, 3721, 3757, -1, 3758, 3722, 3759, -1, 3721, 3722, 3758, -1, 3759, 3723, 3760, -1, 3722, 3723, 3759, -1, 3760, 3724, 3761, -1, 3723, 3724, 3760, -1, 3761, 3717, 3762, -1, 3724, 3717, 3761, -1, 3717, 3716, 3762, -1, 3762, 3716, 3763, -1, 3763, 3718, 3764, -1, 3716, 3718, 3763, -1, 3764, 3712, 3765, -1, 3718, 3712, 3764, -1, 3765, 3707, 3766, -1, 3712, 3707, 3765, -1, 3766, 3706, 3767, -1, 3707, 3706, 3766, -1, 3767, 3702, 3768, -1, 3706, 3702, 3767, -1, 3768, 3693, 3769, -1, 3702, 3693, 3768, -1, 3769, 3692, 3770, -1, 3693, 3692, 3769, -1, 3770, 3684, 3771, -1, 3692, 3684, 3770, -1, 3771, 3682, 3772, -1, 3684, 3682, 3771, -1, 3772, 3704, 3773, -1, 3682, 3704, 3772, -1, 3773, 3700, 3774, -1, 3704, 3700, 3773, -1, 3774, 3698, 3749, -1, 3700, 3698, 3774, -1, 3727, 3726, 3748, -1, 3748, 3726, 3775, -1, 3775, 3728, 3776, -1, 3726, 3728, 3775, -1, 3776, 3729, 3777, -1, 3728, 3729, 3776, -1, 3777, 3730, 3778, -1, 3729, 3730, 3777, -1, 3778, 3731, 3779, -1, 3730, 3731, 3778, -1, 3779, 3732, 3780, -1, 3731, 3732, 3779, -1, 3780, 3715, 3781, -1, 3732, 3715, 3780, -1, 3781, 3714, 3782, -1, 3715, 3714, 3781, -1, 3782, 3713, 3783, -1, 3714, 3713, 3782, -1, 3783, 3710, 3784, -1, 3713, 3710, 3783, -1, 3784, 3708, 3785, -1, 3710, 3708, 3784, -1, 3785, 3703, 3786, -1, 3708, 3703, 3785, -1, 3786, 3699, 3735, -1, 3703, 3699, 3786, -1, 3676, 3678, 3674, -1, 3787, 3678, 3676, -1, 3788, 3789, 3787, -1, 3787, 3789, 3678, -1, 3100, 3102, 3789, -1, 3102, 3678, 3789, -1, 3102, 3675, 3678, -1, 3669, 3680, 3677, -1, 3679, 3787, 3676, -1, 3668, 3100, 3789, -1, 3672, 3084, 3090, -1, 3670, 3084, 3672, -1, 3680, 3670, 3725, -1, 3669, 3670, 3680, -1, 3788, 3787, 3679, -1, 3788, 3679, 3688, -1, 3788, 3668, 3789, -1, 3671, 3668, 3788, -1, 3672, 3725, 3670, -1, 3671, 3788, 3688, -1, 3672, 3671, 3688, -1, 3672, 3688, 3725, -1, 3745, 3743, 3744, -1, 3746, 3747, 3745, -1, 3745, 3747, 3743, -1, 3743, 3740, 3742, -1, 3742, 3740, 3741, -1, 3747, 3740, 3743, -1, 3740, 3738, 3739, -1, 3778, 3779, 3777, -1, 3777, 3779, 3776, -1, 3776, 3779, 3775, -1, 3748, 3736, 3747, -1, 3738, 3736, 3737, -1, 3747, 3736, 3740, -1, 3740, 3736, 3738, -1, 3748, 3735, 3736, -1, 3775, 3786, 3748, -1, 3748, 3786, 3735, -1, 3781, 3782, 3780, -1, 3780, 3782, 3779, -1, 3779, 3782, 3775, -1, 3775, 3782, 3786, -1, 3786, 3784, 3785, -1, 3783, 3784, 3782, -1, 3782, 3784, 3786, -1, 3759, 3757, 3758, -1, 3760, 3761, 3759, -1, 3759, 3761, 3757, -1, 3757, 3754, 3756, -1, 3756, 3754, 3755, -1, 3761, 3754, 3757, -1, 3754, 3752, 3753, -1, 3766, 3767, 3765, -1, 3765, 3767, 3764, -1, 3764, 3767, 3763, -1, 3762, 3750, 3761, -1, 3752, 3750, 3751, -1, 3761, 3750, 3754, -1, 3754, 3750, 3752, -1, 3762, 3749, 3750, -1, 3763, 3774, 3762, -1, 3762, 3774, 3749, -1, 3769, 3770, 3768, -1, 3768, 3770, 3767, -1, 3767, 3770, 3763, -1, 3763, 3770, 3774, -1, 3774, 3772, 3773, -1, 3771, 3772, 3770, -1, 3770, 3772, 3774, -1, 3790, 3052, 3045, -1, 3790, 3791, 3052, -1, 3792, 3041, 3054, -1, 3792, 3054, 3793, -1, 3042, 3794, 3795, -1, 3042, 3795, 3058, -1, 3796, 3044, 3043, -1, 3796, 3797, 3044, -1, 3058, 3795, 3043, -1, 3043, 3795, 3796, -1, 3041, 3792, 3042, -1, 3042, 3792, 3794, -1, 3052, 3791, 3054, -1, 3054, 3791, 3793, -1, 3044, 3797, 3045, -1, 3045, 3797, 3790, -1, 3798, 3799, 3800, -1, 3798, 3801, 3799, -1, 3802, 3803, 3797, -1, 3804, 3797, 3803, -1, 3805, 3802, 3797, -1, 3806, 3797, 3804, -1, 3807, 3805, 3797, -1, 3808, 3797, 3806, -1, 3809, 3798, 3800, -1, 3810, 3807, 3797, -1, 3811, 3797, 3808, -1, 3792, 3800, 3812, -1, 3792, 3809, 3800, -1, 3792, 3813, 3809, -1, 3792, 3814, 3813, -1, 3792, 3815, 3814, -1, 3792, 3816, 3815, -1, 3792, 3817, 3816, -1, 3792, 3818, 3817, -1, 3794, 3819, 3795, -1, 3794, 3812, 3820, -1, 3794, 3820, 3821, -1, 3794, 3821, 3822, -1, 3794, 3822, 3823, -1, 3794, 3823, 3819, -1, 3794, 3792, 3812, -1, 3824, 3799, 3825, -1, 3824, 3825, 3826, -1, 3824, 3826, 3827, -1, 3824, 3827, 3828, -1, 3829, 3830, 3831, -1, 3831, 3830, 3832, -1, 3832, 3830, 3833, -1, 3833, 3830, 3834, -1, 3834, 3830, 3835, -1, 3792, 3793, 3818, -1, 3818, 3793, 3836, -1, 3836, 3793, 3837, -1, 3837, 3793, 3838, -1, 3837, 3838, 3839, -1, 3840, 3790, 3797, -1, 3840, 3797, 3811, -1, 3841, 3790, 3840, -1, 3842, 3811, 3843, -1, 3842, 3840, 3811, -1, 3844, 3790, 3841, -1, 3845, 3843, 3846, -1, 3845, 3842, 3843, -1, 3847, 3790, 3844, -1, 3848, 3790, 3847, -1, 3830, 3846, 3849, -1, 3830, 3845, 3846, -1, 3830, 3850, 3835, -1, 3830, 3851, 3850, -1, 3830, 3852, 3851, -1, 3830, 3853, 3852, -1, 3830, 3854, 3853, -1, 3830, 3849, 3854, -1, 3855, 3790, 3848, -1, 3791, 3790, 3855, -1, 3791, 3855, 3856, -1, 3791, 3856, 3857, -1, 3791, 3857, 3858, -1, 3859, 3860, 3861, -1, 3859, 3861, 3862, -1, 3863, 3859, 3862, -1, 3863, 3862, 3824, -1, 3864, 3858, 3860, -1, 3864, 3860, 3859, -1, 3865, 3863, 3824, -1, 3866, 3858, 3864, -1, 3866, 3791, 3858, -1, 3867, 3865, 3824, -1, 3868, 3791, 3866, -1, 3869, 3867, 3824, -1, 3870, 3791, 3868, -1, 3871, 3869, 3824, -1, 3872, 3793, 3791, -1, 3872, 3791, 3870, -1, 3873, 3871, 3824, -1, 3874, 3793, 3872, -1, 3875, 3873, 3824, -1, 3876, 3793, 3874, -1, 3877, 3793, 3876, -1, 3878, 3793, 3877, -1, 3879, 3793, 3878, -1, 3838, 3793, 3879, -1, 3880, 3881, 3882, -1, 3880, 3882, 3883, -1, 3884, 3882, 3881, -1, 3884, 3885, 3882, -1, 3886, 3883, 3887, -1, 3886, 3880, 3883, -1, 3888, 3885, 3884, -1, 3888, 3889, 3885, -1, 3890, 3810, 3797, -1, 3890, 3886, 3887, -1, 3890, 3887, 3810, -1, 3891, 3889, 3888, -1, 3891, 3892, 3889, -1, 3893, 3892, 3891, -1, 3893, 3894, 3892, -1, 3893, 3895, 3894, -1, 3896, 3895, 3893, -1, 3896, 3835, 3895, -1, 3834, 3835, 3896, -1, 3796, 3897, 3890, -1, 3796, 3898, 3897, -1, 3796, 3899, 3898, -1, 3796, 3900, 3899, -1, 3796, 3901, 3900, -1, 3796, 3902, 3901, -1, 3796, 3890, 3797, -1, 3829, 3902, 3796, -1, 3829, 3903, 3902, -1, 3829, 3904, 3903, -1, 3829, 3905, 3904, -1, 3829, 3906, 3905, -1, 3829, 3907, 3906, -1, 3829, 3908, 3907, -1, 3829, 3909, 3908, -1, 3829, 3831, 3909, -1, 3910, 3829, 3796, -1, 3911, 3910, 3796, -1, 3912, 3911, 3796, -1, 3795, 3913, 3914, -1, 3795, 3914, 3912, -1, 3795, 3912, 3796, -1, 3915, 3913, 3795, -1, 3916, 3915, 3795, -1, 3828, 3875, 3824, -1, 3917, 3918, 3875, -1, 3917, 3875, 3828, -1, 3919, 3920, 3918, -1, 3919, 3921, 3920, -1, 3919, 3918, 3917, -1, 3922, 3923, 3921, -1, 3922, 3921, 3919, -1, 3924, 3923, 3922, -1, 3925, 3926, 3923, -1, 3925, 3923, 3924, -1, 3927, 3928, 3926, -1, 3927, 3926, 3925, -1, 3837, 3839, 3928, -1, 3837, 3928, 3927, -1, 3799, 3929, 3825, -1, 3799, 3930, 3929, -1, 3799, 3931, 3930, -1, 3799, 3932, 3931, -1, 3799, 3933, 3932, -1, 3799, 3801, 3933, -1, 3819, 3916, 3795, -1, 3934, 3935, 3921, -1, 3921, 3935, 3920, -1, 3920, 3936, 3918, -1, 3935, 3936, 3920, -1, 3918, 3937, 3875, -1, 3936, 3937, 3918, -1, 3875, 3938, 3873, -1, 3937, 3938, 3875, -1, 3873, 3939, 3871, -1, 3938, 3939, 3873, -1, 3871, 3940, 3869, -1, 3939, 3940, 3871, -1, 3869, 3941, 3867, -1, 3940, 3941, 3869, -1, 3867, 3942, 3865, -1, 3941, 3942, 3867, -1, 3865, 3943, 3863, -1, 3942, 3943, 3865, -1, 3863, 3944, 3859, -1, 3943, 3944, 3863, -1, 3859, 3945, 3864, -1, 3944, 3945, 3859, -1, 3864, 3946, 3866, -1, 3945, 3946, 3864, -1, 3866, 3947, 3868, -1, 3946, 3947, 3866, -1, 3948, 3949, 3798, -1, 3798, 3949, 3801, -1, 3801, 3950, 3933, -1, 3949, 3950, 3801, -1, 3933, 3951, 3932, -1, 3950, 3951, 3933, -1, 3932, 3952, 3931, -1, 3951, 3952, 3932, -1, 3931, 3953, 3930, -1, 3952, 3953, 3931, -1, 3930, 3954, 3929, -1, 3953, 3954, 3930, -1, 3929, 3955, 3825, -1, 3954, 3955, 3929, -1, 3825, 3956, 3826, -1, 3955, 3956, 3825, -1, 3826, 3957, 3827, -1, 3956, 3957, 3826, -1, 3827, 3958, 3828, -1, 3957, 3958, 3827, -1, 3828, 3959, 3917, -1, 3958, 3959, 3828, -1, 3917, 3960, 3919, -1, 3959, 3960, 3917, -1, 3919, 3961, 3922, -1, 3960, 3961, 3919, -1, 3962, 3963, 3903, -1, 3903, 3963, 3902, -1, 3902, 3964, 3901, -1, 3963, 3964, 3902, -1, 3901, 3965, 3900, -1, 3964, 3965, 3901, -1, 3900, 3966, 3899, -1, 3965, 3966, 3900, -1, 3899, 3967, 3898, -1, 3966, 3967, 3899, -1, 3898, 3968, 3897, -1, 3967, 3968, 3898, -1, 3897, 3969, 3890, -1, 3968, 3969, 3897, -1, 3890, 3970, 3886, -1, 3969, 3970, 3890, -1, 3886, 3971, 3880, -1, 3970, 3971, 3886, -1, 3880, 3972, 3881, -1, 3971, 3972, 3880, -1, 3881, 3973, 3884, -1, 3972, 3973, 3881, -1, 3884, 3974, 3888, -1, 3973, 3974, 3884, -1, 3888, 3975, 3891, -1, 3974, 3975, 3888, -1, 3976, 3977, 3892, -1, 3892, 3977, 3889, -1, 3889, 3978, 3885, -1, 3977, 3978, 3889, -1, 3885, 3979, 3882, -1, 3978, 3979, 3885, -1, 3882, 3980, 3883, -1, 3979, 3980, 3882, -1, 3883, 3981, 3887, -1, 3980, 3981, 3883, -1, 3887, 3982, 3810, -1, 3981, 3982, 3887, -1, 3810, 3983, 3807, -1, 3982, 3983, 3810, -1, 3807, 3984, 3805, -1, 3983, 3984, 3807, -1, 3805, 3985, 3802, -1, 3984, 3985, 3805, -1, 3802, 3986, 3803, -1, 3985, 3986, 3802, -1, 3803, 3987, 3804, -1, 3986, 3987, 3803, -1, 3804, 3988, 3806, -1, 3987, 3988, 3804, -1, 3806, 3989, 3808, -1, 3988, 3989, 3806, -1, 3990, 3991, 3824, -1, 3991, 3799, 3824, -1, 3916, 3992, 3993, -1, 3819, 3992, 3916, -1, 3830, 3994, 3995, -1, 3830, 3829, 3994, -1, 3996, 3855, 3848, -1, 3997, 3855, 3996, -1, 3989, 3998, 3808, -1, 3808, 3998, 3811, -1, 3811, 3999, 3843, -1, 3998, 3999, 3811, -1, 3843, 4000, 3846, -1, 3999, 4000, 3843, -1, 3846, 4001, 3849, -1, 4000, 4001, 3846, -1, 3849, 4002, 3854, -1, 4001, 4002, 3849, -1, 3854, 4003, 3853, -1, 4002, 4003, 3854, -1, 3853, 4004, 3852, -1, 4003, 4004, 3853, -1, 3852, 4005, 3851, -1, 4004, 4005, 3852, -1, 3851, 4006, 3850, -1, 4005, 4006, 3851, -1, 3850, 4007, 3835, -1, 4006, 4007, 3850, -1, 3835, 4008, 3895, -1, 4007, 4008, 3835, -1, 3895, 4009, 3894, -1, 4008, 4009, 3895, -1, 3894, 3976, 3892, -1, 4009, 3976, 3894, -1, 3975, 4010, 3891, -1, 3891, 4010, 3893, -1, 3893, 4011, 3896, -1, 4010, 4011, 3893, -1, 3896, 4012, 3834, -1, 4011, 4012, 3896, -1, 3834, 4013, 3833, -1, 4012, 4013, 3834, -1, 3833, 4014, 3832, -1, 4013, 4014, 3833, -1, 3832, 4015, 3831, -1, 4014, 4015, 3832, -1, 3831, 4016, 3909, -1, 4015, 4016, 3831, -1, 3909, 4017, 3908, -1, 4016, 4017, 3909, -1, 3908, 4018, 3907, -1, 4017, 4018, 3908, -1, 3907, 4019, 3906, -1, 4018, 4019, 3907, -1, 3906, 4020, 3905, -1, 4019, 4020, 3906, -1, 3905, 4021, 3904, -1, 4020, 4021, 3905, -1, 3904, 3962, 3903, -1, 4021, 3962, 3904, -1, 3961, 4022, 3922, -1, 3922, 4022, 3924, -1, 3924, 4023, 3925, -1, 4022, 4023, 3924, -1, 3925, 4024, 3927, -1, 4023, 4024, 3925, -1, 3927, 4025, 3837, -1, 4024, 4025, 3927, -1, 3837, 4026, 3836, -1, 4025, 4026, 3837, -1, 3836, 4027, 3818, -1, 4026, 4027, 3836, -1, 3818, 4028, 3817, -1, 4027, 4028, 3818, -1, 3817, 4029, 3816, -1, 4028, 4029, 3817, -1, 3816, 4030, 3815, -1, 4029, 4030, 3816, -1, 3815, 4031, 3814, -1, 4030, 4031, 3815, -1, 3814, 4032, 3813, -1, 4031, 4032, 3814, -1, 3813, 4033, 3809, -1, 4032, 4033, 3813, -1, 3809, 3948, 3798, -1, 4033, 3948, 3809, -1, 3947, 4034, 3868, -1, 3868, 4034, 3870, -1, 3870, 4035, 3872, -1, 4034, 4035, 3870, -1, 3872, 4036, 3874, -1, 4035, 4036, 3872, -1, 3874, 4037, 3876, -1, 4036, 4037, 3874, -1, 3876, 4038, 3877, -1, 4037, 4038, 3876, -1, 3877, 4039, 3878, -1, 4038, 4039, 3877, -1, 3878, 4040, 3879, -1, 4039, 4040, 3878, -1, 3879, 4041, 3838, -1, 4040, 4041, 3879, -1, 3838, 4042, 3839, -1, 4041, 4042, 3838, -1, 3839, 4043, 3928, -1, 4042, 4043, 3839, -1, 3928, 4044, 3926, -1, 4043, 4044, 3928, -1, 3926, 4045, 3923, -1, 4044, 4045, 3926, -1, 3923, 3934, 3921, -1, 4045, 3934, 3923, -1, 3830, 3995, 3845, -1, 3845, 4046, 3842, -1, 3995, 4046, 3845, -1, 3842, 4047, 3840, -1, 4046, 4047, 3842, -1, 3840, 4048, 3841, -1, 4047, 4048, 3840, -1, 3841, 4049, 3844, -1, 4048, 4049, 3841, -1, 3844, 4050, 3847, -1, 4049, 4050, 3844, -1, 3847, 4051, 3848, -1, 4050, 4051, 3847, -1, 4051, 3996, 3848, -1, 3855, 4052, 3856, -1, 3997, 4052, 3855, -1, 3856, 4053, 3857, -1, 4052, 4053, 3856, -1, 3857, 4054, 3858, -1, 4053, 4054, 3857, -1, 3858, 4055, 3860, -1, 4054, 4055, 3858, -1, 3860, 4056, 3861, -1, 4055, 4056, 3860, -1, 3861, 4057, 3862, -1, 4056, 4057, 3861, -1, 3862, 3990, 3824, -1, 4057, 3990, 3862, -1, 3799, 4058, 3800, -1, 3991, 4058, 3799, -1, 3800, 4059, 3812, -1, 4058, 4059, 3800, -1, 3812, 4060, 3820, -1, 4059, 4060, 3812, -1, 3820, 4061, 3821, -1, 4060, 4061, 3820, -1, 3821, 4062, 3822, -1, 4061, 4062, 3821, -1, 3822, 4063, 3823, -1, 4062, 4063, 3822, -1, 3823, 3992, 3819, -1, 4063, 3992, 3823, -1, 3916, 4064, 3915, -1, 3993, 4064, 3916, -1, 3915, 4065, 3913, -1, 4064, 4065, 3915, -1, 3913, 4066, 3914, -1, 4065, 4066, 3913, -1, 3914, 4067, 3912, -1, 4066, 4067, 3914, -1, 3912, 4068, 3911, -1, 4067, 4068, 3912, -1, 3911, 4069, 3910, -1, 4068, 4069, 3911, -1, 3910, 3994, 3829, -1, 4069, 3994, 3910, -1, 4066, 4065, 4067, -1, 4065, 4064, 4067, -1, 3993, 3994, 4064, -1, 4067, 3994, 4068, -1, 4068, 3994, 4069, -1, 4064, 3994, 4067, -1, 4061, 4060, 4062, -1, 4062, 4060, 4063, -1, 4060, 4059, 4063, -1, 3992, 3991, 3993, -1, 4058, 3991, 4059, -1, 4063, 3991, 3992, -1, 3993, 3991, 3994, -1, 4059, 3991, 4063, -1, 3995, 4050, 4046, -1, 4046, 4050, 4047, -1, 4047, 4050, 4048, -1, 4048, 4050, 4049, -1, 4050, 3996, 4051, -1, 3995, 3996, 4050, -1, 3996, 3990, 3997, -1, 3994, 3990, 3995, -1, 3991, 3990, 3994, -1, 3995, 3990, 3996, -1, 3997, 4053, 4052, -1, 3990, 4053, 3997, -1, 4057, 4056, 3990, -1, 3990, 4056, 4053, -1, 4053, 4055, 4054, -1, 4056, 4055, 4053, -1, 3938, 3940, 3939, -1, 3934, 4045, 3935, -1, 3940, 3942, 3941, -1, 3938, 3942, 3940, -1, 3935, 4044, 3936, -1, 4045, 4044, 3935, -1, 3937, 3943, 3938, -1, 3938, 3943, 3942, -1, 3936, 4043, 3937, -1, 4044, 4043, 3936, -1, 4041, 4040, 4042, -1, 3943, 3947, 3944, -1, 3944, 3947, 3945, -1, 3945, 3947, 3946, -1, 4043, 3947, 3937, -1, 3937, 3947, 3943, -1, 4039, 4038, 4040, -1, 4040, 4038, 4042, -1, 3947, 4035, 4034, -1, 4037, 4036, 4038, -1, 4042, 4036, 4043, -1, 4043, 4036, 3947, -1, 4038, 4036, 4042, -1, 3947, 4036, 4035, -1, 3952, 3954, 3953, -1, 3948, 4033, 3949, -1, 3949, 4032, 3950, -1, 4033, 4032, 3949, -1, 3955, 3957, 3956, -1, 3950, 4031, 3951, -1, 4032, 4031, 3950, -1, 4029, 4028, 4030, -1, 4030, 3961, 4031, -1, 3951, 3961, 3952, -1, 3954, 3961, 3955, -1, 3957, 3961, 3958, -1, 3958, 3961, 3959, -1, 3959, 3961, 3960, -1, 4031, 3961, 3951, -1, 3952, 3961, 3954, -1, 3955, 3961, 3957, -1, 4028, 3961, 4030, -1, 4028, 4027, 3961, -1, 3961, 4023, 4022, -1, 4026, 4025, 4027, -1, 4027, 4025, 3961, -1, 4025, 4024, 3961, -1, 3961, 4024, 4023, -1, 3965, 3968, 3966, -1, 3966, 3968, 3967, -1, 3963, 3962, 3964, -1, 4021, 4020, 3962, -1, 3962, 4020, 3964, -1, 3969, 3971, 3970, -1, 3964, 4019, 3965, -1, 4020, 4019, 3964, -1, 3969, 3972, 3971, -1, 4017, 4016, 4018, -1, 4018, 4016, 4019, -1, 3965, 4016, 3968, -1, 4019, 4016, 3965, -1, 3973, 3975, 3974, -1, 3968, 4015, 3969, -1, 4016, 4015, 3968, -1, 3975, 4011, 4010, -1, 3972, 4011, 3973, -1, 3973, 4011, 3975, -1, 4014, 4013, 4015, -1, 4015, 4012, 3969, -1, 3969, 4012, 3972, -1, 3972, 4012, 4011, -1, 4013, 4012, 4015, -1, 3979, 3982, 3980, -1, 3980, 3982, 3981, -1, 3977, 3976, 3978, -1, 4009, 4008, 3976, -1, 3976, 4008, 3978, -1, 3983, 3985, 3984, -1, 3978, 4007, 3979, -1, 4008, 4007, 3978, -1, 3983, 3986, 3985, -1, 4005, 4004, 4006, -1, 4006, 4004, 4007, -1, 3979, 4004, 3982, -1, 4007, 4004, 3979, -1, 3987, 3989, 3988, -1, 3982, 4003, 3983, -1, 4004, 4003, 3982, -1, 3989, 3999, 3998, -1, 3986, 3999, 3987, -1, 3987, 3999, 3989, -1, 4002, 4001, 4003, -1, 4003, 4000, 3983, -1, 3983, 4000, 3986, -1, 3986, 4000, 3999, -1, 4001, 4000, 4003, -1, 4070, 4071, 4072, -1, 4070, 4072, 2080, -1, 4073, 4070, 2080, -1, 4074, 4075, 4076, -1, 2093, 4076, 4077, -1, 2093, 4077, 4073, -1, 2093, 4073, 2080, -1, 2093, 4074, 4076, -1, 4078, 1924, 2080, -1, 4078, 2080, 4072, -1, 4079, 4072, 4071, -1, 4079, 4078, 4072, -1, 4080, 4071, 4070, -1, 4080, 4079, 4071, -1, 4081, 4070, 4073, -1, 4081, 4080, 4070, -1, 4082, 4077, 4076, -1, 4083, 4076, 4075, -1, 4083, 4082, 4076, -1, 4084, 4075, 4074, -1, 4084, 4083, 4075, -1, 4085, 4074, 2093, -1, 4085, 4084, 4074, -1, 2091, 4085, 2093, -1, 4083, 4084, 4085, -1, 4083, 4085, 2091, -1, 4082, 4083, 2091, -1, 4078, 4079, 4080, -1, 1924, 4080, 4081, -1, 1924, 4081, 4082, -1, 1924, 4082, 2091, -1, 1924, 4078, 4080, -1, 4086, 4087, 4088, -1, 4089, 4088, 4090, -1, 4089, 4086, 4088, -1, 4091, 4090, 4092, -1, 4091, 4089, 4090, -1, 4093, 4092, 4094, -1, 4093, 4091, 4092, -1, 4095, 4094, 3121, -1, 4095, 4093, 4094, -1, 3109, 4095, 3121, -1, 1926, 1972, 4096, -1, 4097, 4096, 4098, -1, 4097, 1926, 4096, -1, 4099, 4098, 4100, -1, 4099, 4097, 4098, -1, 4101, 4099, 4100, -1, 4102, 4100, 4103, -1, 4102, 4101, 4100, -1, 3109, 4091, 4093, -1, 3109, 4093, 4095, -1, 4089, 4091, 3109, -1, 4086, 4089, 3109, -1, 3111, 4104, 4105, -1, 3111, 4105, 4086, -1, 3111, 4086, 3109, -1, 3166, 4106, 4104, -1, 3166, 4104, 3111, -1, 3167, 4107, 4106, -1, 3167, 4106, 3166, -1, 4108, 4107, 3167, -1, 3168, 4108, 3167, -1, 4109, 3168, 3169, -1, 4109, 4108, 3168, -1, 4110, 3169, 3170, -1, 4110, 4109, 3169, -1, 4111, 3171, 1927, -1, 4111, 3170, 3171, -1, 4111, 4110, 3170, -1, 4102, 4111, 1927, -1, 4097, 4099, 4101, -1, 4097, 4101, 4102, -1, 1926, 4097, 4102, -1, 1927, 1926, 4102, -1, 4092, 3121, 4094, -1, 4090, 3121, 4092, -1, 4088, 3121, 4090, -1, 4100, 4098, 4096, -1, 4087, 3121, 4088, -1, 4103, 4096, 1972, -1, 4103, 4100, 4096, -1, 3122, 3121, 4087, -1, 4112, 3122, 4087, -1, 4113, 3404, 3403, -1, 4113, 1971, 3404, -1, 4113, 4103, 1971, -1, 4114, 3397, 3122, -1, 4114, 3122, 4112, -1, 4115, 3403, 3402, -1, 4115, 4113, 3403, -1, 4116, 3399, 3397, -1, 4116, 3397, 4114, -1, 4117, 3402, 3401, -1, 4117, 4115, 3402, -1, 4118, 3399, 4116, -1, 4119, 3401, 3399, -1, 4119, 3399, 4118, -1, 4119, 4117, 3401, -1, 1972, 1971, 4103, -1, 4110, 4113, 4115, -1, 4110, 4111, 4113, -1, 4109, 4115, 4117, -1, 4109, 4110, 4115, -1, 4108, 4117, 4119, -1, 4108, 4109, 4117, -1, 4107, 4119, 4118, -1, 4107, 4108, 4119, -1, 4106, 4118, 4116, -1, 4106, 4107, 4118, -1, 4104, 4116, 4114, -1, 4104, 4106, 4116, -1, 4105, 4114, 4112, -1, 4105, 4104, 4114, -1, 4120, 4121, 4122, -1, 4123, 4124, 4125, -1, 4126, 4124, 4123, -1, 4127, 4128, 4086, -1, 4129, 4130, 4120, -1, 4086, 4131, 4127, -1, 4120, 4130, 4121, -1, 4124, 4132, 4125, -1, 4128, 4133, 4086, -1, 4086, 4134, 4131, -1, 4129, 4135, 4130, -1, 4136, 4135, 4129, -1, 4133, 4137, 4086, -1, 4105, 4138, 4086, -1, 4086, 4138, 4134, -1, 4139, 4140, 4136, -1, 4136, 4140, 4135, -1, 4137, 4141, 4086, -1, 4105, 4142, 4138, -1, 4139, 4143, 4140, -1, 4141, 4144, 4086, -1, 4145, 4146, 4147, -1, 4105, 4148, 4142, -1, 4147, 4146, 4139, -1, 4139, 4146, 4143, -1, 4105, 4149, 4148, -1, 4150, 4151, 4145, -1, 4145, 4151, 4146, -1, 4105, 4152, 4149, -1, 4150, 4153, 4151, -1, 4105, 4154, 4152, -1, 4155, 4156, 4150, -1, 4105, 4157, 4154, -1, 4150, 4156, 4153, -1, 4105, 4158, 4157, -1, 4105, 4159, 4158, -1, 4160, 4161, 4162, -1, 4162, 4161, 4163, -1, 4164, 4165, 4166, -1, 4162, 4167, 4160, -1, 4166, 4165, 4168, -1, 4168, 4165, 4144, -1, 4166, 4169, 4164, -1, 4170, 4167, 4162, -1, 4171, 4169, 4166, -1, 4161, 4172, 4163, -1, 4163, 4172, 4173, -1, 4165, 4174, 4144, -1, 4144, 4174, 4086, -1, 4170, 4175, 4167, -1, 4171, 4176, 4169, -1, 4177, 4175, 4178, -1, 4178, 4175, 4170, -1, 4179, 4176, 4171, -1, 4174, 4180, 4086, -1, 4172, 4181, 4173, -1, 4173, 4181, 4182, -1, 4179, 4183, 4176, -1, 4177, 4184, 4175, -1, 4185, 4184, 4177, -1, 4186, 4183, 4179, -1, 4180, 4187, 4086, -1, 4186, 4188, 4183, -1, 4185, 4189, 4184, -1, 4190, 4188, 4186, -1, 4191, 4192, 4185, -1, 4185, 4192, 4189, -1, 4190, 4193, 4188, -1, 4191, 4194, 4192, -1, 4195, 4193, 4190, -1, 4196, 4194, 4191, -1, 4195, 4197, 4193, -1, 4196, 4198, 4194, -1, 4199, 4197, 4195, -1, 4200, 4198, 4196, -1, 4199, 4201, 4197, -1, 4200, 4202, 4198, -1, 4159, 4201, 4203, -1, 4203, 4201, 4199, -1, 4204, 4202, 4200, -1, 4105, 4205, 4159, -1, 4159, 4205, 4201, -1, 4204, 4206, 4202, -1, 4105, 4207, 4205, -1, 4208, 4206, 4204, -1, 4209, 4210, 4211, -1, 4211, 4210, 4212, -1, 4212, 4210, 4213, -1, 4211, 4214, 4209, -1, 4215, 4216, 4217, -1, 4218, 4214, 4211, -1, 4219, 4216, 4215, -1, 4213, 4220, 4221, -1, 4210, 4220, 4213, -1, 4218, 4222, 4214, -1, 4223, 4224, 4215, -1, 4215, 4224, 4219, -1, 4225, 4222, 4218, -1, 4217, 4226, 4227, -1, 4220, 4228, 4221, -1, 4216, 4226, 4217, -1, 4229, 4230, 4225, -1, 4231, 4232, 4223, -1, 4225, 4230, 4222, -1, 4223, 4232, 4224, -1, 4187, 4233, 4086, -1, 4227, 4233, 4187, -1, 4226, 4233, 4227, -1, 4234, 4235, 4236, -1, 4236, 4235, 4229, -1, 4229, 4235, 4230, -1, 4237, 4238, 4239, -1, 4239, 4238, 4231, -1, 4231, 4238, 4232, -1, 4234, 4240, 4235, -1, 4233, 4241, 4086, -1, 4237, 4242, 4238, -1, 4243, 4244, 4234, -1, 4234, 4244, 4240, -1, 4245, 4246, 4247, -1, 4247, 4246, 4243, -1, 4248, 4249, 4237, -1, 4243, 4246, 4244, -1, 4237, 4249, 4242, -1, 4250, 4251, 4245, -1, 4252, 4253, 4248, -1, 4248, 4253, 4249, -1, 4245, 4251, 4246, -1, 4250, 4254, 4251, -1, 4252, 4255, 4253, -1, 4256, 4255, 4252, -1, 4256, 4257, 4255, -1, 4258, 4257, 4256, -1, 4258, 4259, 4257, -1, 4260, 4259, 4258, -1, 4261, 4262, 4263, -1, 4264, 4262, 4261, -1, 4265, 4266, 4267, -1, 4267, 4266, 4261, -1, 4261, 4266, 4264, -1, 4263, 4268, 4269, -1, 4269, 4268, 4270, -1, 4262, 4268, 4263, -1, 4265, 4271, 4266, -1, 4272, 4273, 4274, -1, 4274, 4273, 4275, -1, 4275, 4273, 4276, -1, 4277, 4271, 4265, -1, 4274, 4278, 4272, -1, 4268, 4279, 4270, -1, 4277, 4280, 4271, -1, 4281, 4278, 4282, -1, 4282, 4278, 4274, -1, 4283, 4280, 4277, -1, 4273, 4284, 4276, -1, 4281, 4285, 4278, -1, 4286, 4287, 4283, -1, 4283, 4287, 4280, -1, 4284, 4288, 4276, -1, 4276, 4288, 4241, -1, 4241, 4288, 4086, -1, 4281, 4289, 4285, -1, 4290, 4291, 4286, -1, 4292, 4289, 4293, -1, 4293, 4289, 4281, -1, 4286, 4291, 4287, -1, 4288, 4294, 4086, -1, 4295, 4296, 4290, -1, 4292, 4297, 4289, -1, 4290, 4296, 4291, -1, 4295, 4298, 4296, -1, 4292, 4299, 4297, -1, 4300, 4299, 4292, -1, 4295, 4301, 4298, -1, 4302, 4301, 4303, -1, 4303, 4301, 4295, -1, 4304, 4305, 4300, -1, 4300, 4305, 4299, -1, 4302, 4306, 4301, -1, 4307, 4308, 4309, -1, 4309, 4308, 4304, -1, 4304, 4308, 4305, -1, 4307, 4310, 4308, -1, 4311, 4312, 4307, -1, 4307, 4312, 4310, -1, 4313, 4314, 4315, -1, 4315, 4314, 4316, -1, 4314, 4317, 4316, -1, 4316, 4317, 4318, -1, 4313, 4319, 4314, -1, 4320, 4319, 4313, -1, 4317, 4321, 4318, -1, 4322, 4323, 4324, -1, 4324, 4323, 4325, -1, 4320, 4326, 4319, -1, 4327, 4326, 4320, -1, 4324, 4328, 4322, -1, 4329, 4328, 4324, -1, 4330, 4331, 4327, -1, 4327, 4331, 4326, -1, 4325, 4332, 4333, -1, 4323, 4332, 4325, -1, 4330, 4334, 4331, -1, 4335, 4334, 4330, -1, 4336, 4337, 4329, -1, 4329, 4337, 4328, -1, 4294, 4338, 4086, -1, 4332, 4338, 4333, -1, 4333, 4338, 4294, -1, 4339, 4340, 4335, -1, 4335, 4340, 4334, -1, 4341, 4342, 4336, -1, 4339, 4343, 4340, -1, 4336, 4342, 4337, -1, 4344, 4343, 4339, -1, 4338, 4125, 4086, -1, 4345, 4346, 4344, -1, 4344, 4346, 4343, -1, 4347, 4348, 4341, -1, 4341, 4348, 4342, -1, 4345, 4349, 4346, -1, 4350, 4351, 4347, -1, 4347, 4351, 4348, -1, 4352, 4353, 4350, -1, 4350, 4353, 4351, -1, 4354, 4355, 4352, -1, 4352, 4355, 4353, -1, 4356, 4357, 4354, -1, 4354, 4357, 4355, -1, 4358, 4087, 4359, -1, 4359, 4087, 4360, -1, 4360, 4087, 4361, -1, 4361, 4087, 4362, -1, 4362, 4087, 4363, -1, 4363, 4087, 4364, -1, 4364, 4087, 4365, -1, 4365, 4087, 4321, -1, 4221, 4087, 4181, -1, 4228, 4087, 4221, -1, 4132, 4087, 4125, -1, 4356, 4366, 4357, -1, 4321, 4087, 4318, -1, 4318, 4087, 4367, -1, 4367, 4087, 4279, -1, 4368, 4366, 4356, -1, 4279, 4087, 4270, -1, 4270, 4087, 4228, -1, 4181, 4087, 4182, -1, 4125, 4087, 4086, -1, 4182, 4087, 4132, -1, 4349, 4112, 4369, -1, 4369, 4112, 4370, -1, 4370, 4112, 4371, -1, 4371, 4112, 4372, -1, 4372, 4112, 4373, -1, 4373, 4112, 4374, -1, 4374, 4112, 4375, -1, 4375, 4112, 4358, -1, 4376, 4112, 4345, -1, 4345, 4112, 4349, -1, 4358, 4112, 4087, -1, 4105, 4112, 4207, -1, 4207, 4112, 4260, -1, 4260, 4112, 4259, -1, 4259, 4112, 4311, -1, 4311, 4112, 4312, -1, 4312, 4112, 4368, -1, 4368, 4112, 4366, -1, 4366, 4112, 4155, -1, 4155, 4112, 4156, -1, 4156, 4112, 4208, -1, 4208, 4112, 4206, -1, 4206, 4112, 4250, -1, 4250, 4112, 4254, -1, 4254, 4112, 4302, -1, 4302, 4112, 4306, -1, 4306, 4112, 4376, -1, 4122, 4377, 4378, -1, 4378, 4377, 4379, -1, 4379, 4126, 4123, -1, 4377, 4126, 4379, -1, 4122, 4121, 4377, -1, 4358, 4359, 4380, -1, 4380, 4359, 4381, -1, 4381, 4360, 4382, -1, 4359, 4360, 4381, -1, 4382, 4361, 4383, -1, 4360, 4361, 4382, -1, 4383, 4362, 4384, -1, 4361, 4362, 4383, -1, 4384, 4363, 4385, -1, 4362, 4363, 4384, -1, 4385, 4364, 4386, -1, 4363, 4364, 4385, -1, 4386, 4365, 4387, -1, 4364, 4365, 4386, -1, 4387, 4321, 4388, -1, 4365, 4321, 4387, -1, 4388, 4317, 4389, -1, 4321, 4317, 4388, -1, 4389, 4314, 4390, -1, 4317, 4314, 4389, -1, 4390, 4319, 4391, -1, 4314, 4319, 4390, -1, 4391, 4326, 4392, -1, 4319, 4326, 4391, -1, 4392, 4331, 4393, -1, 4326, 4331, 4392, -1, 4327, 4320, 4394, -1, 4394, 4320, 4395, -1, 4395, 4313, 4396, -1, 4320, 4313, 4395, -1, 4396, 4315, 4397, -1, 4313, 4315, 4396, -1, 4397, 4316, 4398, -1, 4315, 4316, 4397, -1, 4398, 4318, 4399, -1, 4316, 4318, 4398, -1, 4399, 4367, 4400, -1, 4318, 4367, 4399, -1, 4400, 4279, 4401, -1, 4367, 4279, 4400, -1, 4401, 4268, 4402, -1, 4279, 4268, 4401, -1, 4402, 4262, 4403, -1, 4268, 4262, 4402, -1, 4403, 4264, 4404, -1, 4262, 4264, 4403, -1, 4404, 4266, 4405, -1, 4264, 4266, 4404, -1, 4405, 4271, 4406, -1, 4266, 4271, 4405, -1, 4406, 4280, 4407, -1, 4271, 4280, 4406, -1, 4277, 4265, 4408, -1, 4408, 4265, 4409, -1, 4409, 4267, 4410, -1, 4265, 4267, 4409, -1, 4410, 4261, 4411, -1, 4267, 4261, 4410, -1, 4411, 4263, 4412, -1, 4261, 4263, 4411, -1, 4412, 4269, 4413, -1, 4263, 4269, 4412, -1, 4413, 4270, 4414, -1, 4269, 4270, 4413, -1, 4414, 4228, 4415, -1, 4270, 4228, 4414, -1, 4415, 4220, 4416, -1, 4228, 4220, 4415, -1, 4416, 4210, 4417, -1, 4220, 4210, 4416, -1, 4417, 4209, 4418, -1, 4210, 4209, 4417, -1, 4418, 4214, 4419, -1, 4209, 4214, 4418, -1, 4419, 4222, 4420, -1, 4214, 4222, 4419, -1, 4420, 4230, 4421, -1, 4222, 4230, 4420, -1, 4177, 4178, 4422, -1, 4422, 4178, 4423, -1, 4423, 4170, 4424, -1, 4178, 4170, 4423, -1, 4424, 4162, 4425, -1, 4170, 4162, 4424, -1, 4425, 4163, 4426, -1, 4162, 4163, 4425, -1, 4426, 4173, 4427, -1, 4163, 4173, 4426, -1, 4427, 4182, 4428, -1, 4173, 4182, 4427, -1, 4428, 4132, 4429, -1, 4182, 4132, 4428, -1, 4429, 4124, 4430, -1, 4132, 4124, 4429, -1, 4430, 4126, 4431, -1, 4124, 4126, 4430, -1, 4431, 4377, 4432, -1, 4126, 4377, 4431, -1, 4432, 4121, 4433, -1, 4377, 4121, 4432, -1, 4433, 4130, 4434, -1, 4121, 4130, 4433, -1, 4434, 4135, 4435, -1, 4130, 4135, 4434, -1, 4129, 4120, 4436, -1, 4436, 4120, 4437, -1, 4437, 4122, 4438, -1, 4120, 4122, 4437, -1, 4438, 4378, 4439, -1, 4122, 4378, 4438, -1, 4439, 4379, 4440, -1, 4378, 4379, 4439, -1, 4440, 4123, 4441, -1, 4379, 4123, 4440, -1, 4441, 4125, 4442, -1, 4123, 4125, 4441, -1, 4442, 4338, 4443, -1, 4125, 4338, 4442, -1, 4443, 4332, 4444, -1, 4338, 4332, 4443, -1, 4444, 4323, 4445, -1, 4332, 4323, 4444, -1, 4445, 4322, 4446, -1, 4323, 4322, 4445, -1, 4446, 4328, 4447, -1, 4322, 4328, 4446, -1, 4447, 4337, 4448, -1, 4328, 4337, 4447, -1, 4448, 4342, 4449, -1, 4337, 4342, 4448, -1, 4293, 4281, 4450, -1, 4450, 4281, 4451, -1, 4451, 4282, 4452, -1, 4281, 4282, 4451, -1, 4452, 4274, 4453, -1, 4282, 4274, 4452, -1, 4453, 4275, 4454, -1, 4274, 4275, 4453, -1, 4454, 4276, 4455, -1, 4275, 4276, 4454, -1, 4455, 4241, 4456, -1, 4276, 4241, 4455, -1, 4456, 4233, 4457, -1, 4241, 4233, 4456, -1, 4457, 4226, 4458, -1, 4233, 4226, 4457, -1, 4458, 4216, 4459, -1, 4226, 4216, 4458, -1, 4459, 4219, 4460, -1, 4216, 4219, 4459, -1, 4460, 4224, 4461, -1, 4219, 4224, 4460, -1, 4461, 4232, 4462, -1, 4224, 4232, 4461, -1, 4462, 4238, 4463, -1, 4232, 4238, 4462, -1, 4239, 4231, 4464, -1, 4464, 4231, 4465, -1, 4465, 4223, 4466, -1, 4231, 4223, 4465, -1, 4466, 4215, 4467, -1, 4223, 4215, 4466, -1, 4467, 4217, 4468, -1, 4215, 4217, 4467, -1, 4468, 4227, 4469, -1, 4217, 4227, 4468, -1, 4469, 4187, 4470, -1, 4227, 4187, 4469, -1, 4470, 4180, 4471, -1, 4187, 4180, 4470, -1, 4471, 4174, 4472, -1, 4180, 4174, 4471, -1, 4472, 4165, 4473, -1, 4174, 4165, 4472, -1, 4473, 4164, 4474, -1, 4165, 4164, 4473, -1, 4474, 4169, 4475, -1, 4164, 4169, 4474, -1, 4475, 4176, 4476, -1, 4169, 4176, 4475, -1, 4476, 4183, 4477, -1, 4176, 4183, 4476, -1, 4186, 4179, 4478, -1, 4478, 4179, 4479, -1, 4479, 4171, 4480, -1, 4179, 4171, 4479, -1, 4480, 4166, 4481, -1, 4171, 4166, 4480, -1, 4481, 4168, 4482, -1, 4166, 4168, 4481, -1, 4482, 4144, 4483, -1, 4168, 4144, 4482, -1, 4483, 4141, 4484, -1, 4144, 4141, 4483, -1, 4484, 4137, 4485, -1, 4141, 4137, 4484, -1, 4485, 4133, 4486, -1, 4137, 4133, 4485, -1, 4486, 4128, 4487, -1, 4133, 4128, 4486, -1, 4487, 4127, 4488, -1, 4128, 4127, 4487, -1, 4488, 4131, 4489, -1, 4127, 4131, 4488, -1, 4489, 4134, 4490, -1, 4131, 4134, 4489, -1, 4490, 4138, 4491, -1, 4134, 4138, 4490, -1, 4229, 4225, 4492, -1, 4492, 4225, 4493, -1, 4493, 4218, 4494, -1, 4225, 4218, 4493, -1, 4494, 4211, 4495, -1, 4218, 4211, 4494, -1, 4495, 4212, 4496, -1, 4211, 4212, 4495, -1, 4496, 4213, 4497, -1, 4212, 4213, 4496, -1, 4497, 4221, 4498, -1, 4213, 4221, 4497, -1, 4498, 4181, 4499, -1, 4221, 4181, 4498, -1, 4499, 4172, 4500, -1, 4181, 4172, 4499, -1, 4500, 4161, 4501, -1, 4172, 4161, 4500, -1, 4501, 4160, 4502, -1, 4161, 4160, 4501, -1, 4502, 4167, 4503, -1, 4160, 4167, 4502, -1, 4503, 4175, 4504, -1, 4167, 4175, 4503, -1, 4504, 4184, 4505, -1, 4175, 4184, 4504, -1, 4341, 4336, 4506, -1, 4506, 4336, 4507, -1, 4507, 4329, 4508, -1, 4336, 4329, 4507, -1, 4508, 4324, 4509, -1, 4329, 4324, 4508, -1, 4509, 4325, 4510, -1, 4324, 4325, 4509, -1, 4510, 4333, 4511, -1, 4325, 4333, 4510, -1, 4511, 4294, 4512, -1, 4333, 4294, 4511, -1, 4512, 4288, 4513, -1, 4294, 4288, 4512, -1, 4513, 4284, 4514, -1, 4288, 4284, 4513, -1, 4514, 4273, 4515, -1, 4284, 4273, 4514, -1, 4515, 4272, 4516, -1, 4273, 4272, 4515, -1, 4516, 4278, 4517, -1, 4272, 4278, 4516, -1, 4517, 4285, 4518, -1, 4278, 4285, 4517, -1, 4518, 4289, 4519, -1, 4285, 4289, 4518, -1, 4289, 4297, 4519, -1, 4519, 4297, 4520, -1, 4520, 4299, 4521, -1, 4297, 4299, 4520, -1, 4521, 4305, 4522, -1, 4299, 4305, 4521, -1, 4522, 4308, 4523, -1, 4305, 4308, 4522, -1, 4523, 4310, 4524, -1, 4308, 4310, 4523, -1, 4524, 4312, 4525, -1, 4310, 4312, 4524, -1, 4525, 4368, 4526, -1, 4312, 4368, 4525, -1, 4526, 4356, 4527, -1, 4368, 4356, 4526, -1, 4527, 4354, 4528, -1, 4356, 4354, 4527, -1, 4528, 4352, 4529, -1, 4354, 4352, 4528, -1, 4529, 4350, 4530, -1, 4352, 4350, 4529, -1, 4530, 4347, 4531, -1, 4350, 4347, 4530, -1, 4531, 4341, 4506, -1, 4347, 4341, 4531, -1, 4184, 4189, 4505, -1, 4505, 4189, 4532, -1, 4532, 4192, 4533, -1, 4189, 4192, 4532, -1, 4533, 4194, 4534, -1, 4192, 4194, 4533, -1, 4534, 4198, 4535, -1, 4194, 4198, 4534, -1, 4535, 4202, 4536, -1, 4198, 4202, 4535, -1, 4536, 4206, 4537, -1, 4202, 4206, 4536, -1, 4537, 4250, 4538, -1, 4206, 4250, 4537, -1, 4538, 4245, 4539, -1, 4250, 4245, 4538, -1, 4539, 4247, 4540, -1, 4245, 4247, 4539, -1, 4540, 4243, 4541, -1, 4247, 4243, 4540, -1, 4541, 4234, 4542, -1, 4243, 4234, 4541, -1, 4542, 4236, 4543, -1, 4234, 4236, 4542, -1, 4543, 4229, 4492, -1, 4236, 4229, 4543, -1, 4138, 4142, 4491, -1, 4491, 4142, 4544, -1, 4544, 4148, 4545, -1, 4142, 4148, 4544, -1, 4545, 4149, 4546, -1, 4148, 4149, 4545, -1, 4546, 4152, 4547, -1, 4149, 4152, 4546, -1, 4547, 4154, 4548, -1, 4152, 4154, 4547, -1, 4548, 4157, 4549, -1, 4154, 4157, 4548, -1, 4549, 4158, 4550, -1, 4157, 4158, 4549, -1, 4550, 4159, 4551, -1, 4158, 4159, 4550, -1, 4551, 4203, 4552, -1, 4159, 4203, 4551, -1, 4552, 4199, 4553, -1, 4203, 4199, 4552, -1, 4553, 4195, 4554, -1, 4199, 4195, 4553, -1, 4554, 4190, 4555, -1, 4195, 4190, 4554, -1, 4555, 4186, 4478, -1, 4190, 4186, 4555, -1, 4183, 4188, 4477, -1, 4477, 4188, 4556, -1, 4556, 4193, 4557, -1, 4188, 4193, 4556, -1, 4557, 4197, 4558, -1, 4193, 4197, 4557, -1, 4558, 4201, 4559, -1, 4197, 4201, 4558, -1, 4559, 4205, 4560, -1, 4201, 4205, 4559, -1, 4560, 4207, 4561, -1, 4205, 4207, 4560, -1, 4561, 4260, 4562, -1, 4207, 4260, 4561, -1, 4562, 4258, 4563, -1, 4260, 4258, 4562, -1, 4563, 4256, 4564, -1, 4258, 4256, 4563, -1, 4564, 4252, 4565, -1, 4256, 4252, 4564, -1, 4565, 4248, 4566, -1, 4252, 4248, 4565, -1, 4566, 4237, 4567, -1, 4248, 4237, 4566, -1, 4567, 4239, 4464, -1, 4237, 4239, 4567, -1, 4238, 4242, 4463, -1, 4463, 4242, 4568, -1, 4568, 4249, 4569, -1, 4242, 4249, 4568, -1, 4569, 4253, 4570, -1, 4249, 4253, 4569, -1, 4570, 4255, 4571, -1, 4253, 4255, 4570, -1, 4571, 4257, 4572, -1, 4255, 4257, 4571, -1, 4572, 4259, 4573, -1, 4257, 4259, 4572, -1, 4573, 4311, 4574, -1, 4259, 4311, 4573, -1, 4574, 4307, 4575, -1, 4311, 4307, 4574, -1, 4575, 4309, 4576, -1, 4307, 4309, 4575, -1, 4576, 4304, 4577, -1, 4309, 4304, 4576, -1, 4577, 4300, 4578, -1, 4304, 4300, 4577, -1, 4578, 4292, 4579, -1, 4300, 4292, 4578, -1, 4579, 4293, 4450, -1, 4292, 4293, 4579, -1, 4342, 4348, 4449, -1, 4449, 4348, 4580, -1, 4580, 4351, 4581, -1, 4348, 4351, 4580, -1, 4581, 4353, 4582, -1, 4351, 4353, 4581, -1, 4582, 4355, 4583, -1, 4353, 4355, 4582, -1, 4583, 4357, 4584, -1, 4355, 4357, 4583, -1, 4584, 4366, 4585, -1, 4357, 4366, 4584, -1, 4585, 4155, 4586, -1, 4366, 4155, 4585, -1, 4586, 4150, 4587, -1, 4155, 4150, 4586, -1, 4587, 4145, 4588, -1, 4150, 4145, 4587, -1, 4588, 4147, 4589, -1, 4145, 4147, 4588, -1, 4589, 4139, 4590, -1, 4147, 4139, 4589, -1, 4590, 4136, 4591, -1, 4139, 4136, 4590, -1, 4591, 4129, 4436, -1, 4136, 4129, 4591, -1, 4135, 4140, 4435, -1, 4435, 4140, 4592, -1, 4592, 4143, 4593, -1, 4140, 4143, 4592, -1, 4593, 4146, 4594, -1, 4143, 4146, 4593, -1, 4594, 4151, 4595, -1, 4146, 4151, 4594, -1, 4595, 4153, 4596, -1, 4151, 4153, 4595, -1, 4596, 4156, 4597, -1, 4153, 4156, 4596, -1, 4597, 4208, 4598, -1, 4156, 4208, 4597, -1, 4598, 4204, 4599, -1, 4208, 4204, 4598, -1, 4599, 4200, 4600, -1, 4204, 4200, 4599, -1, 4600, 4196, 4601, -1, 4200, 4196, 4600, -1, 4601, 4191, 4602, -1, 4196, 4191, 4601, -1, 4602, 4185, 4603, -1, 4191, 4185, 4602, -1, 4603, 4177, 4422, -1, 4185, 4177, 4603, -1, 4230, 4235, 4421, -1, 4421, 4235, 4604, -1, 4604, 4240, 4605, -1, 4235, 4240, 4604, -1, 4605, 4244, 4606, -1, 4240, 4244, 4605, -1, 4606, 4246, 4607, -1, 4244, 4246, 4606, -1, 4607, 4251, 4608, -1, 4246, 4251, 4607, -1, 4608, 4254, 4609, -1, 4251, 4254, 4608, -1, 4609, 4302, 4610, -1, 4254, 4302, 4609, -1, 4610, 4303, 4611, -1, 4302, 4303, 4610, -1, 4611, 4295, 4612, -1, 4303, 4295, 4611, -1, 4612, 4290, 4613, -1, 4295, 4290, 4612, -1, 4613, 4286, 4614, -1, 4290, 4286, 4613, -1, 4614, 4283, 4615, -1, 4286, 4283, 4614, -1, 4615, 4277, 4408, -1, 4283, 4277, 4615, -1, 4280, 4287, 4407, -1, 4407, 4287, 4616, -1, 4616, 4291, 4617, -1, 4287, 4291, 4616, -1, 4617, 4296, 4618, -1, 4291, 4296, 4617, -1, 4618, 4298, 4619, -1, 4296, 4298, 4618, -1, 4619, 4301, 4620, -1, 4298, 4301, 4619, -1, 4620, 4306, 4621, -1, 4301, 4306, 4620, -1, 4621, 4376, 4622, -1, 4306, 4376, 4621, -1, 4622, 4345, 4623, -1, 4376, 4345, 4622, -1, 4623, 4344, 4624, -1, 4345, 4344, 4623, -1, 4624, 4339, 4625, -1, 4344, 4339, 4624, -1, 4625, 4335, 4626, -1, 4339, 4335, 4625, -1, 4626, 4330, 4627, -1, 4335, 4330, 4626, -1, 4627, 4327, 4394, -1, 4330, 4327, 4627, -1, 4331, 4334, 4393, -1, 4393, 4334, 4628, -1, 4628, 4340, 4629, -1, 4334, 4340, 4628, -1, 4629, 4343, 4630, -1, 4340, 4343, 4629, -1, 4630, 4346, 4631, -1, 4343, 4346, 4630, -1, 4631, 4349, 4632, -1, 4346, 4349, 4631, -1, 4632, 4369, 4633, -1, 4349, 4369, 4632, -1, 4633, 4370, 4634, -1, 4369, 4370, 4633, -1, 4634, 4371, 4635, -1, 4370, 4371, 4634, -1, 4635, 4372, 4636, -1, 4371, 4372, 4635, -1, 4636, 4373, 4637, -1, 4372, 4373, 4636, -1, 4637, 4374, 4638, -1, 4373, 4374, 4637, -1, 4638, 4375, 4639, -1, 4374, 4375, 4638, -1, 4639, 4358, 4380, -1, 4375, 4358, 4639, -1, 4390, 4388, 4389, -1, 4392, 4393, 4391, -1, 4388, 4386, 4387, -1, 4388, 4385, 4386, -1, 4628, 4629, 4393, -1, 4393, 4629, 4391, -1, 4391, 4630, 4390, -1, 4629, 4630, 4391, -1, 4385, 4383, 4384, -1, 4390, 4383, 4388, -1, 4388, 4383, 4385, -1, 4631, 4632, 4630, -1, 4382, 4380, 4381, -1, 4634, 4635, 4633, -1, 4633, 4635, 4632, -1, 4380, 4638, 4639, -1, 4382, 4638, 4380, -1, 4383, 4637, 4382, -1, 4636, 4637, 4635, -1, 4632, 4637, 4630, -1, 4390, 4637, 4383, -1, 4630, 4637, 4390, -1, 4635, 4637, 4632, -1, 4382, 4637, 4638, -1, 4403, 4401, 4402, -1, 4406, 4407, 4405, -1, 4616, 4617, 4407, -1, 4407, 4617, 4405, -1, 4400, 4398, 4399, -1, 4405, 4618, 4404, -1, 4617, 4618, 4405, -1, 4404, 4619, 4403, -1, 4618, 4619, 4404, -1, 4620, 4621, 4619, -1, 4403, 4621, 4401, -1, 4619, 4621, 4403, -1, 4401, 4394, 4400, -1, 4398, 4394, 4397, -1, 4397, 4394, 4396, -1, 4396, 4394, 4395, -1, 4400, 4394, 4398, -1, 4621, 4394, 4401, -1, 4621, 4622, 4394, -1, 4394, 4626, 4627, -1, 4623, 4624, 4622, -1, 4622, 4624, 4394, -1, 4624, 4625, 4394, -1, 4394, 4625, 4626, -1, 4417, 4415, 4416, -1, 4420, 4421, 4419, -1, 4417, 4414, 4415, -1, 4604, 4605, 4421, -1, 4421, 4605, 4419, -1, 4414, 4412, 4413, -1, 4417, 4412, 4414, -1, 4419, 4606, 4418, -1, 4605, 4606, 4419, -1, 4418, 4411, 4417, -1, 4417, 4411, 4412, -1, 4608, 4609, 4607, -1, 4410, 4408, 4409, -1, 4408, 4614, 4615, -1, 4410, 4614, 4408, -1, 4611, 4612, 4610, -1, 4610, 4612, 4609, -1, 4609, 4612, 4607, -1, 4411, 4613, 4410, -1, 4607, 4613, 4606, -1, 4606, 4613, 4418, -1, 4418, 4613, 4411, -1, 4410, 4613, 4614, -1, 4612, 4613, 4607, -1, 4431, 4429, 4430, -1, 4434, 4435, 4433, -1, 4431, 4428, 4429, -1, 4592, 4593, 4435, -1, 4435, 4593, 4433, -1, 4428, 4426, 4427, -1, 4431, 4426, 4428, -1, 4433, 4594, 4432, -1, 4593, 4594, 4433, -1, 4432, 4425, 4431, -1, 4431, 4425, 4426, -1, 4596, 4597, 4595, -1, 4424, 4422, 4423, -1, 4422, 4602, 4603, -1, 4424, 4602, 4422, -1, 4599, 4600, 4598, -1, 4598, 4600, 4597, -1, 4597, 4600, 4595, -1, 4425, 4601, 4424, -1, 4595, 4601, 4594, -1, 4594, 4601, 4432, -1, 4432, 4601, 4425, -1, 4600, 4601, 4595, -1, 4424, 4601, 4602, -1, 4445, 4443, 4444, -1, 4449, 4580, 4448, -1, 4448, 4581, 4447, -1, 4580, 4581, 4448, -1, 4442, 4440, 4441, -1, 4584, 4585, 4583, -1, 4447, 4436, 4446, -1, 4446, 4436, 4445, -1, 4443, 4436, 4442, -1, 4440, 4436, 4439, -1, 4439, 4436, 4438, -1, 4438, 4436, 4437, -1, 4583, 4436, 4582, -1, 4582, 4436, 4581, -1, 4445, 4436, 4443, -1, 4442, 4436, 4440, -1, 4581, 4436, 4447, -1, 4585, 4436, 4583, -1, 4585, 4586, 4436, -1, 4436, 4590, 4591, -1, 4587, 4588, 4586, -1, 4586, 4588, 4436, -1, 4588, 4589, 4436, -1, 4436, 4589, 4590, -1, 4460, 4458, 4459, -1, 4461, 4462, 4460, -1, 4460, 4462, 4458, -1, 4463, 4568, 4462, -1, 4569, 4570, 4568, -1, 4571, 4572, 4570, -1, 4570, 4572, 4568, -1, 4458, 4450, 4457, -1, 4457, 4450, 4456, -1, 4456, 4450, 4455, -1, 4455, 4450, 4454, -1, 4454, 4450, 4453, -1, 4453, 4450, 4452, -1, 4452, 4450, 4451, -1, 4573, 4450, 4572, -1, 4568, 4450, 4462, -1, 4462, 4450, 4458, -1, 4572, 4450, 4568, -1, 4573, 4574, 4450, -1, 4574, 4575, 4450, -1, 4450, 4578, 4579, -1, 4575, 4576, 4450, -1, 4450, 4577, 4578, -1, 4576, 4577, 4450, -1, 4474, 4472, 4473, -1, 4475, 4476, 4474, -1, 4474, 4476, 4472, -1, 4477, 4556, 4476, -1, 4557, 4558, 4556, -1, 4559, 4560, 4558, -1, 4558, 4560, 4556, -1, 4472, 4464, 4471, -1, 4471, 4464, 4470, -1, 4470, 4464, 4469, -1, 4469, 4464, 4468, -1, 4468, 4464, 4467, -1, 4467, 4464, 4466, -1, 4466, 4464, 4465, -1, 4561, 4464, 4560, -1, 4556, 4464, 4476, -1, 4476, 4464, 4472, -1, 4560, 4464, 4556, -1, 4561, 4562, 4464, -1, 4562, 4563, 4464, -1, 4464, 4566, 4567, -1, 4563, 4564, 4464, -1, 4464, 4565, 4566, -1, 4564, 4565, 4464, -1, 4488, 4486, 4487, -1, 4489, 4490, 4488, -1, 4488, 4490, 4486, -1, 4486, 4484, 4485, -1, 4491, 4544, 4490, -1, 4486, 4483, 4484, -1, 4545, 4546, 4544, -1, 4483, 4481, 4482, -1, 4547, 4548, 4546, -1, 4546, 4548, 4544, -1, 4481, 4479, 4480, -1, 4490, 4479, 4486, -1, 4486, 4479, 4483, -1, 4483, 4479, 4481, -1, 4479, 4555, 4478, -1, 4544, 4555, 4490, -1, 4490, 4555, 4479, -1, 4550, 4551, 4549, -1, 4549, 4551, 4548, -1, 4548, 4551, 4544, -1, 4544, 4551, 4555, -1, 4555, 4553, 4554, -1, 4552, 4553, 4551, -1, 4551, 4553, 4555, -1, 4501, 4499, 4500, -1, 4504, 4505, 4503, -1, 4501, 4498, 4499, -1, 4532, 4533, 4505, -1, 4505, 4533, 4503, -1, 4498, 4496, 4497, -1, 4501, 4496, 4498, -1, 4503, 4534, 4502, -1, 4533, 4534, 4503, -1, 4502, 4495, 4501, -1, 4501, 4495, 4496, -1, 4536, 4537, 4535, -1, 4494, 4492, 4493, -1, 4492, 4542, 4543, -1, 4494, 4542, 4492, -1, 4539, 4540, 4538, -1, 4538, 4540, 4537, -1, 4537, 4540, 4535, -1, 4495, 4541, 4494, -1, 4535, 4541, 4534, -1, 4534, 4541, 4502, -1, 4502, 4541, 4495, -1, 4540, 4541, 4535, -1, 4494, 4541, 4542, -1, 4515, 4513, 4514, -1, 4518, 4519, 4517, -1, 4515, 4512, 4513, -1, 4520, 4521, 4519, -1, 4519, 4521, 4517, -1, 4512, 4510, 4511, -1, 4515, 4510, 4512, -1, 4517, 4522, 4516, -1, 4521, 4522, 4517, -1, 4516, 4509, 4515, -1, 4515, 4509, 4510, -1, 4524, 4525, 4523, -1, 4508, 4506, 4507, -1, 4506, 4530, 4531, -1, 4508, 4530, 4506, -1, 4527, 4528, 4526, -1, 4526, 4528, 4525, -1, 4525, 4528, 4523, -1, 4509, 4529, 4508, -1, 4523, 4529, 4522, -1, 4522, 4529, 4516, -1, 4516, 4529, 4509, -1, 4528, 4529, 4523, -1, 4508, 4529, 4530, -1, 3056, 3036, 4640, -1, 4641, 4640, 4642, -1, 4641, 3056, 4640, -1, 4643, 4642, 4644, -1, 4643, 4641, 4642, -1, 4645, 4644, 4646, -1, 4645, 4643, 4644, -1, 4647, 4646, 4648, -1, 4647, 4645, 4646, -1, 4649, 4647, 4648, -1, 4650, 4651, 4652, -1, 4650, 4653, 4651, -1, 4654, 4652, 4655, -1, 4654, 4650, 4652, -1, 4656, 4655, 4657, -1, 4656, 4654, 4655, -1, 2011, 4657, 2092, -1, 2011, 4656, 4657, -1, 4658, 4659, 4660, -1, 4661, 4662, 4663, -1, 4660, 4659, 4664, -1, 4665, 4666, 4667, -1, 4661, 4668, 4662, -1, 4658, 4669, 4659, -1, 4670, 4671, 4648, -1, 4672, 4668, 4661, -1, 4673, 4669, 4658, -1, 4648, 4674, 4670, -1, 4671, 4675, 4648, -1, 4648, 4676, 4674, -1, 4672, 4677, 4668, -1, 4678, 4679, 4673, -1, 4680, 4677, 4672, -1, 4673, 4679, 4669, -1, 4675, 4681, 4648, -1, 4648, 4682, 4676, -1, 4680, 4683, 4677, -1, 4684, 4682, 4648, -1, 4685, 4683, 4680, -1, 4678, 4686, 4679, -1, 4681, 4687, 4648, -1, 4688, 4686, 4678, -1, 4684, 4689, 4682, -1, 4690, 4691, 4685, -1, 4685, 4691, 4683, -1, 4687, 4692, 4648, -1, 4684, 4693, 4689, -1, 4694, 4695, 4688, -1, 4690, 4696, 4691, -1, 4688, 4695, 4686, -1, 4684, 4697, 4693, -1, 4698, 4699, 4694, -1, 4694, 4699, 4695, -1, 4684, 4700, 4697, -1, 4701, 4702, 4698, -1, 4684, 4703, 4700, -1, 4698, 4702, 4699, -1, 4684, 4704, 4703, -1, 4705, 4706, 4701, -1, 4701, 4706, 4702, -1, 4667, 4649, 4648, -1, 4707, 4649, 4708, -1, 4709, 4649, 4710, -1, 4708, 4649, 4711, -1, 4711, 4649, 4712, -1, 4712, 4649, 4713, -1, 4713, 4649, 4714, -1, 4714, 4649, 4715, -1, 4715, 4649, 4716, -1, 4716, 4649, 4709, -1, 4717, 4649, 4666, -1, 4684, 4718, 4704, -1, 4710, 4649, 4719, -1, 4719, 4649, 4720, -1, 4720, 4649, 4721, -1, 4666, 4649, 4667, -1, 4722, 4649, 4723, -1, 4724, 4649, 4717, -1, 4721, 4649, 4725, -1, 4725, 4649, 4726, -1, 4684, 4727, 4718, -1, 4723, 4649, 4724, -1, 4726, 4649, 4722, -1, 4696, 4728, 4729, -1, 4729, 4728, 4730, -1, 4730, 4728, 4731, -1, 4731, 4728, 4732, -1, 4732, 4728, 4733, -1, 4733, 4728, 4734, -1, 4734, 4728, 4735, -1, 4735, 4728, 4707, -1, 4736, 4728, 4690, -1, 4737, 4738, 4739, -1, 4690, 4728, 4696, -1, 4739, 4738, 4740, -1, 4707, 4728, 4649, -1, 4684, 4728, 4741, -1, 4684, 4741, 4742, -1, 4684, 4742, 4743, -1, 4684, 4743, 4744, -1, 4684, 4744, 4745, -1, 4740, 4746, 4747, -1, 4741, 4728, 4748, -1, 4748, 4728, 4749, -1, 4749, 4728, 4705, -1, 4738, 4746, 4740, -1, 4705, 4728, 4706, -1, 4706, 4728, 4750, -1, 4750, 4728, 4751, -1, 4751, 4728, 4752, -1, 4752, 4728, 4753, -1, 4753, 4728, 4754, -1, 4755, 4756, 4757, -1, 4754, 4728, 4758, -1, 4757, 4756, 4759, -1, 4758, 4728, 4760, -1, 4759, 4756, 4692, -1, 4760, 4728, 4761, -1, 4761, 4728, 4736, -1, 4737, 4762, 4738, -1, 4747, 4763, 4717, -1, 4746, 4763, 4747, -1, 4757, 4764, 4755, -1, 4737, 4765, 4762, -1, 4766, 4764, 4757, -1, 4692, 4767, 4648, -1, 4756, 4767, 4692, -1, 4768, 4765, 4737, -1, 4763, 4724, 4717, -1, 4769, 4770, 4766, -1, 4766, 4770, 4764, -1, 4768, 4771, 4765, -1, 4767, 4772, 4648, -1, 4773, 4771, 4768, -1, 4774, 4775, 4776, -1, 4776, 4775, 4769, -1, 4769, 4775, 4770, -1, 4777, 4778, 4779, -1, 4779, 4778, 4773, -1, 4772, 4780, 4648, -1, 4773, 4778, 4771, -1, 4774, 4781, 4775, -1, 4777, 4782, 4778, -1, 4783, 4784, 4785, -1, 4785, 4784, 4774, -1, 4774, 4784, 4781, -1, 4786, 4787, 4788, -1, 4788, 4787, 4777, -1, 4777, 4787, 4782, -1, 4783, 4789, 4784, -1, 4786, 4790, 4787, -1, 4791, 4790, 4786, -1, 4727, 4792, 4793, -1, 4793, 4792, 4783, -1, 4783, 4792, 4789, -1, 4750, 4794, 4791, -1, 4791, 4794, 4790, -1, 4684, 4795, 4727, -1, 4750, 4751, 4794, -1, 4727, 4795, 4792, -1, 4684, 4745, 4795, -1, 4796, 4797, 4798, -1, 4798, 4797, 4799, -1, 4798, 4800, 4796, -1, 4801, 4802, 4803, -1, 4804, 4802, 4801, -1, 4805, 4800, 4798, -1, 4797, 4806, 4799, -1, 4799, 4806, 4807, -1, 4807, 4806, 4723, -1, 4805, 4808, 4800, -1, 4809, 4810, 4801, -1, 4801, 4810, 4804, -1, 4802, 4811, 4803, -1, 4812, 4808, 4813, -1, 4813, 4808, 4805, -1, 4803, 4811, 4814, -1, 4809, 4815, 4810, -1, 4806, 4722, 4723, -1, 4812, 4816, 4808, -1, 4817, 4815, 4809, -1, 4811, 4818, 4814, -1, 4780, 4818, 4648, -1, 4814, 4818, 4780, -1, 4817, 4819, 4815, -1, 4812, 4820, 4816, -1, 4821, 4820, 4822, -1, 4822, 4820, 4812, -1, 4823, 4819, 4817, -1, 4818, 4824, 4648, -1, 4823, 4825, 4819, -1, 4821, 4826, 4820, -1, 4827, 4825, 4823, -1, 4827, 4828, 4825, -1, 4821, 4829, 4826, -1, 4830, 4829, 4821, -1, 4831, 4828, 4827, -1, 4831, 4832, 4828, -1, 4830, 4833, 4829, -1, 4834, 4833, 4830, -1, 4835, 4832, 4831, -1, 4835, 4836, 4832, -1, 4834, 4837, 4833, -1, 4752, 4837, 4838, -1, 4838, 4837, 4834, -1, 4839, 4836, 4835, -1, 4752, 4753, 4837, -1, 4839, 4840, 4836, -1, 4841, 4840, 4839, -1, 4841, 4743, 4840, -1, 4744, 4743, 4841, -1, 4842, 4843, 4844, -1, 4844, 4843, 4845, -1, 4844, 4846, 4842, -1, 4847, 4848, 4849, -1, 4849, 4848, 4850, -1, 4851, 4846, 4844, -1, 4850, 4848, 4852, -1, 4843, 4853, 4845, -1, 4845, 4853, 4854, -1, 4849, 4855, 4847, -1, 4851, 4856, 4846, -1, 4857, 4855, 4858, -1, 4858, 4855, 4849, -1, 4859, 4856, 4851, -1, 4848, 4860, 4852, -1, 4853, 4725, 4854, -1, 4852, 4860, 4824, -1, 4854, 4725, 4726, -1, 4857, 4861, 4855, -1, 4859, 4862, 4856, -1, 4824, 4863, 4648, -1, 4864, 4862, 4859, -1, 4860, 4863, 4824, -1, 4864, 4865, 4862, -1, 4857, 4866, 4861, -1, 4867, 4865, 4864, -1, 4868, 4866, 4857, -1, 4863, 4869, 4648, -1, 4867, 4870, 4865, -1, 4871, 4870, 4867, -1, 4868, 4872, 4866, -1, 4873, 4872, 4868, -1, 4871, 4874, 4870, -1, 4875, 4874, 4871, -1, 4876, 4877, 4873, -1, 4873, 4877, 4872, -1, 4875, 4878, 4874, -1, 4879, 4878, 4875, -1, 4880, 4881, 4882, -1, 4882, 4881, 4876, -1, 4876, 4881, 4877, -1, 4879, 4883, 4878, -1, 4884, 4883, 4879, -1, 4885, 4886, 4880, -1, 4880, 4886, 4881, -1, 4884, 4758, 4883, -1, 4754, 4758, 4884, -1, 4885, 4887, 4886, -1, 4742, 4741, 4885, -1, 4885, 4741, 4887, -1, 4888, 4889, 4890, -1, 4889, 4891, 4890, -1, 4890, 4891, 4892, -1, 4888, 4893, 4889, -1, 4894, 4893, 4888, -1, 4895, 4896, 4897, -1, 4898, 4896, 4895, -1, 4891, 4899, 4892, -1, 4892, 4899, 4900, -1, 4901, 4902, 4895, -1, 4894, 4903, 4893, -1, 4895, 4902, 4898, -1, 4904, 4903, 4894, -1, 4897, 4905, 4906, -1, 4896, 4905, 4897, -1, 4899, 4720, 4900, -1, 4900, 4720, 4721, -1, 4901, 4907, 4902, -1, 4904, 4908, 4903, -1, 4909, 4907, 4901, -1, 4905, 4910, 4906, -1, 4869, 4910, 4648, -1, 4906, 4910, 4869, -1, 4911, 4912, 4904, -1, 4904, 4912, 4908, -1, 4909, 4913, 4907, -1, 4914, 4913, 4909, -1, 4910, 4667, 4648, -1, 4915, 4916, 4911, -1, 4911, 4916, 4912, -1, 4914, 4917, 4913, -1, 4918, 4917, 4914, -1, 4915, 4919, 4916, -1, 4918, 4920, 4917, -1, 4921, 4919, 4922, -1, 4922, 4919, 4915, -1, 4923, 4920, 4918, -1, 4921, 4924, 4919, -1, 4923, 4925, 4920, -1, 4926, 4925, 4923, -1, 4927, 4928, 4921, -1, 4921, 4928, 4924, -1, 4926, 4929, 4925, -1, 4930, 4929, 4926, -1, 4760, 4761, 4927, -1, 4930, 4931, 4929, -1, 4927, 4761, 4928, -1, 4932, 4931, 4930, -1, 4932, 4749, 4931, -1, 4748, 4749, 4932, -1, 4933, 4934, 4935, -1, 4935, 4934, 4936, -1, 4936, 4937, 4710, -1, 4934, 4937, 4936, -1, 4938, 4939, 4933, -1, 4940, 4941, 4942, -1, 4933, 4939, 4934, -1, 4942, 4941, 4943, -1, 4937, 4709, 4710, -1, 4942, 4664, 4940, -1, 4938, 4944, 4939, -1, 4660, 4664, 4942, -1, 4663, 4944, 4938, -1, 4943, 4665, 4945, -1, 4945, 4665, 4667, -1, 4941, 4665, 4943, -1, 4663, 4662, 4944, -1, 4707, 4708, 4946, -1, 4946, 4708, 4947, -1, 4947, 4711, 4948, -1, 4708, 4711, 4947, -1, 4948, 4712, 4949, -1, 4711, 4712, 4948, -1, 4949, 4713, 4950, -1, 4712, 4713, 4949, -1, 4950, 4714, 4951, -1, 4713, 4714, 4950, -1, 4951, 4715, 4952, -1, 4714, 4715, 4951, -1, 4952, 4716, 4953, -1, 4715, 4716, 4952, -1, 4953, 4709, 4954, -1, 4716, 4709, 4953, -1, 4954, 4937, 4955, -1, 4709, 4937, 4954, -1, 4955, 4934, 4956, -1, 4937, 4934, 4955, -1, 4956, 4939, 4957, -1, 4934, 4939, 4956, -1, 4957, 4944, 4958, -1, 4939, 4944, 4957, -1, 4958, 4662, 4959, -1, 4944, 4662, 4958, -1, 4663, 4938, 4960, -1, 4960, 4938, 4961, -1, 4961, 4933, 4962, -1, 4938, 4933, 4961, -1, 4962, 4935, 4963, -1, 4933, 4935, 4962, -1, 4963, 4936, 4964, -1, 4935, 4936, 4963, -1, 4964, 4710, 4965, -1, 4936, 4710, 4964, -1, 4965, 4719, 4966, -1, 4710, 4719, 4965, -1, 4966, 4720, 4967, -1, 4719, 4720, 4966, -1, 4967, 4899, 4968, -1, 4720, 4899, 4967, -1, 4968, 4891, 4969, -1, 4899, 4891, 4968, -1, 4969, 4889, 4970, -1, 4891, 4889, 4969, -1, 4970, 4893, 4971, -1, 4889, 4893, 4970, -1, 4971, 4903, 4972, -1, 4893, 4903, 4971, -1, 4972, 4908, 4973, -1, 4903, 4908, 4972, -1, 4904, 4894, 4974, -1, 4974, 4894, 4975, -1, 4975, 4888, 4976, -1, 4894, 4888, 4975, -1, 4976, 4890, 4977, -1, 4888, 4890, 4976, -1, 4977, 4892, 4978, -1, 4890, 4892, 4977, -1, 4978, 4900, 4979, -1, 4892, 4900, 4978, -1, 4979, 4721, 4980, -1, 4900, 4721, 4979, -1, 4980, 4725, 4981, -1, 4721, 4725, 4980, -1, 4981, 4853, 4982, -1, 4725, 4853, 4981, -1, 4982, 4843, 4983, -1, 4853, 4843, 4982, -1, 4983, 4842, 4984, -1, 4843, 4842, 4983, -1, 4984, 4846, 4985, -1, 4842, 4846, 4984, -1, 4985, 4856, 4986, -1, 4846, 4856, 4985, -1, 4986, 4862, 4987, -1, 4856, 4862, 4986, -1, 4864, 4859, 4988, -1, 4988, 4859, 4989, -1, 4989, 4851, 4990, -1, 4859, 4851, 4989, -1, 4990, 4844, 4991, -1, 4851, 4844, 4990, -1, 4991, 4845, 4992, -1, 4844, 4845, 4991, -1, 4992, 4854, 4993, -1, 4845, 4854, 4992, -1, 4993, 4726, 4994, -1, 4854, 4726, 4993, -1, 4994, 4722, 4995, -1, 4726, 4722, 4994, -1, 4995, 4806, 4996, -1, 4722, 4806, 4995, -1, 4996, 4797, 4997, -1, 4806, 4797, 4996, -1, 4997, 4796, 4998, -1, 4797, 4796, 4997, -1, 4998, 4800, 4999, -1, 4796, 4800, 4998, -1, 4999, 4808, 5000, -1, 4800, 4808, 4999, -1, 5000, 4816, 5001, -1, 4808, 4816, 5000, -1, 4773, 4768, 5002, -1, 5002, 4768, 5003, -1, 5003, 4737, 5004, -1, 4768, 4737, 5003, -1, 5004, 4739, 5005, -1, 4737, 4739, 5004, -1, 5005, 4740, 5006, -1, 4739, 4740, 5005, -1, 5006, 4747, 5007, -1, 4740, 4747, 5006, -1, 5007, 4717, 5008, -1, 4747, 4717, 5007, -1, 5008, 4666, 5009, -1, 4717, 4666, 5008, -1, 5009, 4665, 5010, -1, 4666, 4665, 5009, -1, 5010, 4941, 5011, -1, 4665, 4941, 5010, -1, 5011, 4940, 5012, -1, 4941, 4940, 5011, -1, 5012, 4664, 5013, -1, 4940, 4664, 5012, -1, 5013, 4659, 5014, -1, 4664, 4659, 5013, -1, 5014, 4669, 5015, -1, 4659, 4669, 5014, -1, 4673, 4658, 5016, -1, 5016, 4658, 5017, -1, 5017, 4660, 5018, -1, 4658, 4660, 5017, -1, 5018, 4942, 5019, -1, 4660, 4942, 5018, -1, 5019, 4943, 5020, -1, 4942, 4943, 5019, -1, 5020, 4945, 5021, -1, 4943, 4945, 5020, -1, 5021, 4667, 5022, -1, 4945, 4667, 5021, -1, 5022, 4910, 5023, -1, 4667, 4910, 5022, -1, 5023, 4905, 5024, -1, 4910, 4905, 5023, -1, 5024, 4896, 5025, -1, 4905, 4896, 5024, -1, 5025, 4898, 5026, -1, 4896, 4898, 5025, -1, 5026, 4902, 5027, -1, 4898, 4902, 5026, -1, 5027, 4907, 5028, -1, 4902, 4907, 5027, -1, 5028, 4913, 5029, -1, 4907, 4913, 5028, -1, 4868, 4857, 5030, -1, 5030, 4857, 5031, -1, 5031, 4858, 5032, -1, 4857, 4858, 5031, -1, 5032, 4849, 5033, -1, 4858, 4849, 5032, -1, 5033, 4850, 5034, -1, 4849, 4850, 5033, -1, 5034, 4852, 5035, -1, 4850, 4852, 5034, -1, 5035, 4824, 5036, -1, 4852, 4824, 5035, -1, 5036, 4818, 5037, -1, 4824, 4818, 5036, -1, 5037, 4811, 5038, -1, 4818, 4811, 5037, -1, 5038, 4802, 5039, -1, 4811, 4802, 5038, -1, 5039, 4804, 5040, -1, 4802, 4804, 5039, -1, 5040, 4810, 5041, -1, 4804, 4810, 5040, -1, 5041, 4815, 5042, -1, 4810, 4815, 5041, -1, 5042, 4819, 5043, -1, 4815, 4819, 5042, -1, 4823, 4817, 5044, -1, 5044, 4817, 5045, -1, 5045, 4809, 5046, -1, 4817, 4809, 5045, -1, 5046, 4801, 5047, -1, 4809, 4801, 5046, -1, 5047, 4803, 5048, -1, 4801, 4803, 5047, -1, 5048, 4814, 5049, -1, 4803, 4814, 5048, -1, 5049, 4780, 5050, -1, 4814, 4780, 5049, -1, 5050, 4772, 5051, -1, 4780, 4772, 5050, -1, 5051, 4767, 5052, -1, 4772, 4767, 5051, -1, 5052, 4756, 5053, -1, 4767, 4756, 5052, -1, 5053, 4755, 5054, -1, 4756, 4755, 5053, -1, 5054, 4764, 5055, -1, 4755, 4764, 5054, -1, 5055, 4770, 5056, -1, 4764, 4770, 5055, -1, 5056, 4775, 5057, -1, 4770, 4775, 5056, -1, 4776, 4769, 5058, -1, 5058, 4769, 5059, -1, 5059, 4766, 5060, -1, 4769, 4766, 5059, -1, 5060, 4757, 5061, -1, 4766, 4757, 5060, -1, 5061, 4759, 5062, -1, 4757, 4759, 5061, -1, 5062, 4692, 5063, -1, 4759, 4692, 5062, -1, 5063, 4687, 5064, -1, 4692, 4687, 5063, -1, 5064, 4681, 5065, -1, 4687, 4681, 5064, -1, 5065, 4675, 5066, -1, 4681, 4675, 5065, -1, 5066, 4671, 5067, -1, 4675, 4671, 5066, -1, 5067, 4670, 5068, -1, 4671, 4670, 5067, -1, 5068, 4674, 5069, -1, 4670, 4674, 5068, -1, 5069, 4676, 5070, -1, 4674, 4676, 5069, -1, 5070, 4682, 5071, -1, 4676, 4682, 5070, -1, 4914, 4909, 5072, -1, 5072, 4909, 5073, -1, 5073, 4901, 5074, -1, 4909, 4901, 5073, -1, 5074, 4895, 5075, -1, 4901, 4895, 5074, -1, 5075, 4897, 5076, -1, 4895, 4897, 5075, -1, 5076, 4906, 5077, -1, 4897, 4906, 5076, -1, 5077, 4869, 5078, -1, 4906, 4869, 5077, -1, 5078, 4863, 5079, -1, 4869, 4863, 5078, -1, 5079, 4860, 5080, -1, 4863, 4860, 5079, -1, 5080, 4848, 5081, -1, 4860, 4848, 5080, -1, 5081, 4847, 5082, -1, 4848, 4847, 5081, -1, 5082, 4855, 5083, -1, 4847, 4855, 5082, -1, 5083, 4861, 5084, -1, 4855, 4861, 5083, -1, 5084, 4866, 5085, -1, 4861, 4866, 5084, -1, 4812, 4813, 5086, -1, 5086, 4813, 5087, -1, 5087, 4805, 5088, -1, 4813, 4805, 5087, -1, 5088, 4798, 5089, -1, 4805, 4798, 5088, -1, 5089, 4799, 5090, -1, 4798, 4799, 5089, -1, 5090, 4807, 5091, -1, 4799, 4807, 5090, -1, 5091, 4723, 5092, -1, 4807, 4723, 5091, -1, 5092, 4724, 5093, -1, 4723, 4724, 5092, -1, 5093, 4763, 5094, -1, 4724, 4763, 5093, -1, 5094, 4746, 5095, -1, 4763, 4746, 5094, -1, 5095, 4738, 5096, -1, 4746, 4738, 5095, -1, 5096, 4762, 5097, -1, 4738, 4762, 5096, -1, 5097, 4765, 5098, -1, 4762, 4765, 5097, -1, 5098, 4771, 5099, -1, 4765, 4771, 5098, -1, 5100, 4684, 5101, -1, 5100, 4728, 4684, -1, 5102, 5101, 5103, -1, 5102, 5100, 5101, -1, 5104, 5103, 5105, -1, 5104, 5102, 5103, -1, 5106, 5105, 5107, -1, 5106, 5104, 5105, -1, 5108, 5107, 5109, -1, 5108, 5106, 5107, -1, 5110, 5109, 5111, -1, 5110, 5108, 5109, -1, 5112, 5111, 5113, -1, 5112, 5110, 5111, -1, 4643, 3056, 4641, -1, 4645, 3056, 4643, -1, 4650, 4654, 4656, -1, 4650, 4656, 2011, -1, 4649, 4645, 4647, -1, 4649, 3056, 4645, -1, 4653, 4650, 2011, -1, 3057, 3056, 4649, -1, 4728, 3057, 4649, -1, 5112, 3160, 3161, -1, 5112, 2166, 3160, -1, 5112, 4653, 2166, -1, 5100, 3165, 3057, -1, 5100, 3057, 4728, -1, 5110, 3161, 3162, -1, 5110, 5112, 3161, -1, 5108, 3162, 3163, -1, 5108, 5110, 3162, -1, 5102, 3164, 3165, -1, 5102, 3165, 5100, -1, 5104, 3164, 5102, -1, 5106, 3163, 3164, -1, 5106, 3164, 5104, -1, 5106, 5108, 3163, -1, 2011, 2166, 4653, -1, 3036, 4644, 4642, -1, 3036, 4642, 4640, -1, 4648, 4646, 4644, -1, 4648, 4644, 3036, -1, 3039, 5101, 4684, -1, 3039, 4684, 4648, -1, 3039, 4648, 3036, -1, 3412, 5103, 5101, -1, 3412, 5101, 3039, -1, 3410, 5105, 5103, -1, 3410, 5103, 3412, -1, 5107, 5105, 3410, -1, 3408, 5107, 3410, -1, 5109, 3408, 3407, -1, 5109, 5107, 3408, -1, 5111, 3407, 3406, -1, 5111, 5109, 3407, -1, 5113, 3405, 2094, -1, 5113, 3406, 3405, -1, 5113, 5111, 3406, -1, 4651, 5113, 2094, -1, 4657, 4655, 4652, -1, 2092, 4652, 4651, -1, 2092, 4657, 4652, -1, 2094, 2092, 4651, -1, 4771, 4778, 5099, -1, 5099, 4778, 5114, -1, 5114, 4782, 5115, -1, 4778, 4782, 5114, -1, 5115, 4787, 5116, -1, 4782, 4787, 5115, -1, 5116, 4790, 5117, -1, 4787, 4790, 5116, -1, 5117, 4794, 5118, -1, 4790, 4794, 5117, -1, 5118, 4751, 5119, -1, 4794, 4751, 5118, -1, 5119, 4752, 5120, -1, 4751, 4752, 5119, -1, 5120, 4838, 5121, -1, 4752, 4838, 5120, -1, 5121, 4834, 5122, -1, 4838, 4834, 5121, -1, 5122, 4830, 5123, -1, 4834, 4830, 5122, -1, 5123, 4821, 5124, -1, 4830, 4821, 5123, -1, 5124, 4822, 5125, -1, 4821, 4822, 5124, -1, 5125, 4812, 5086, -1, 4822, 4812, 5125, -1, 4866, 4872, 5085, -1, 5085, 4872, 5126, -1, 5126, 4877, 5127, -1, 4872, 4877, 5126, -1, 5127, 4881, 5128, -1, 4877, 4881, 5127, -1, 5128, 4886, 5129, -1, 4881, 4886, 5128, -1, 5129, 4887, 5130, -1, 4886, 4887, 5129, -1, 5130, 4741, 5131, -1, 4887, 4741, 5130, -1, 5131, 4748, 5132, -1, 4741, 4748, 5131, -1, 5132, 4932, 5133, -1, 4748, 4932, 5132, -1, 5133, 4930, 5134, -1, 4932, 4930, 5133, -1, 5134, 4926, 5135, -1, 4930, 4926, 5134, -1, 5135, 4923, 5136, -1, 4926, 4923, 5135, -1, 5136, 4918, 5137, -1, 4923, 4918, 5136, -1, 5137, 4914, 5072, -1, 4918, 4914, 5137, -1, 4682, 4689, 5071, -1, 5071, 4689, 5138, -1, 5138, 4693, 5139, -1, 4689, 4693, 5138, -1, 5139, 4697, 5140, -1, 4693, 4697, 5139, -1, 5140, 4700, 5141, -1, 4697, 4700, 5140, -1, 5141, 4703, 5142, -1, 4700, 4703, 5141, -1, 5142, 4704, 5143, -1, 4703, 4704, 5142, -1, 5143, 4718, 5144, -1, 4704, 4718, 5143, -1, 5144, 4727, 5145, -1, 4718, 4727, 5144, -1, 5145, 4793, 5146, -1, 4727, 4793, 5145, -1, 5146, 4783, 5147, -1, 4793, 4783, 5146, -1, 5147, 4785, 5148, -1, 4783, 4785, 5147, -1, 5148, 4774, 5149, -1, 4785, 4774, 5148, -1, 5149, 4776, 5058, -1, 4774, 4776, 5149, -1, 4775, 4781, 5057, -1, 5057, 4781, 5150, -1, 5150, 4784, 5151, -1, 4781, 4784, 5150, -1, 5151, 4789, 5152, -1, 4784, 4789, 5151, -1, 5152, 4792, 5153, -1, 4789, 4792, 5152, -1, 5153, 4795, 5154, -1, 4792, 4795, 5153, -1, 5154, 4745, 5155, -1, 4795, 4745, 5154, -1, 5155, 4744, 5156, -1, 4745, 4744, 5155, -1, 5156, 4841, 5157, -1, 4744, 4841, 5156, -1, 5157, 4839, 5158, -1, 4841, 4839, 5157, -1, 5158, 4835, 5159, -1, 4839, 4835, 5158, -1, 5159, 4831, 5160, -1, 4835, 4831, 5159, -1, 5160, 4827, 5161, -1, 4831, 4827, 5160, -1, 5161, 4823, 5044, -1, 4827, 4823, 5161, -1, 4819, 4825, 5043, -1, 5043, 4825, 5162, -1, 5162, 4828, 5163, -1, 4825, 4828, 5162, -1, 5163, 4832, 5164, -1, 4828, 4832, 5163, -1, 5164, 4836, 5165, -1, 4832, 4836, 5164, -1, 5165, 4840, 5166, -1, 4836, 4840, 5165, -1, 5166, 4743, 5167, -1, 4840, 4743, 5166, -1, 5167, 4742, 5168, -1, 4743, 4742, 5167, -1, 5168, 4885, 5169, -1, 4742, 4885, 5168, -1, 5169, 4880, 5170, -1, 4885, 4880, 5169, -1, 5170, 4882, 5171, -1, 4880, 4882, 5170, -1, 5171, 4876, 5172, -1, 4882, 4876, 5171, -1, 5172, 4873, 5173, -1, 4876, 4873, 5172, -1, 5173, 4868, 5030, -1, 4873, 4868, 5173, -1, 4913, 4917, 5029, -1, 5029, 4917, 5174, -1, 5174, 4920, 5175, -1, 4917, 4920, 5174, -1, 5175, 4925, 5176, -1, 4920, 4925, 5175, -1, 5176, 4929, 5177, -1, 4925, 4929, 5176, -1, 5177, 4931, 5178, -1, 4929, 4931, 5177, -1, 5178, 4749, 5179, -1, 4931, 4749, 5178, -1, 5179, 4705, 5180, -1, 4749, 4705, 5179, -1, 5180, 4701, 5181, -1, 4705, 4701, 5180, -1, 5181, 4698, 5182, -1, 4701, 4698, 5181, -1, 5182, 4694, 5183, -1, 4698, 4694, 5182, -1, 5183, 4688, 5184, -1, 4694, 4688, 5183, -1, 5184, 4678, 5185, -1, 4688, 4678, 5184, -1, 5185, 4673, 5016, -1, 4678, 4673, 5185, -1, 4669, 4679, 5015, -1, 5015, 4679, 5186, -1, 5186, 4686, 5187, -1, 4679, 4686, 5186, -1, 5187, 4695, 5188, -1, 4686, 4695, 5187, -1, 5188, 4699, 5189, -1, 4695, 4699, 5188, -1, 5189, 4702, 5190, -1, 4699, 4702, 5189, -1, 5190, 4706, 5191, -1, 4702, 4706, 5190, -1, 5191, 4750, 5192, -1, 4706, 4750, 5191, -1, 5192, 4791, 5193, -1, 4750, 4791, 5192, -1, 5193, 4786, 5194, -1, 4791, 4786, 5193, -1, 5194, 4788, 5195, -1, 4786, 4788, 5194, -1, 5195, 4777, 5196, -1, 4788, 4777, 5195, -1, 5196, 4779, 5197, -1, 4777, 4779, 5196, -1, 5197, 4773, 5002, -1, 4779, 4773, 5197, -1, 4816, 4820, 5001, -1, 5001, 4820, 5198, -1, 5198, 4826, 5199, -1, 4820, 4826, 5198, -1, 5199, 4829, 5200, -1, 4826, 4829, 5199, -1, 5200, 4833, 5201, -1, 4829, 4833, 5200, -1, 5201, 4837, 5202, -1, 4833, 4837, 5201, -1, 5202, 4753, 5203, -1, 4837, 4753, 5202, -1, 5203, 4754, 5204, -1, 4753, 4754, 5203, -1, 5204, 4884, 5205, -1, 4754, 4884, 5204, -1, 5205, 4879, 5206, -1, 4884, 4879, 5205, -1, 5206, 4875, 5207, -1, 4879, 4875, 5206, -1, 5207, 4871, 5208, -1, 4875, 4871, 5207, -1, 5208, 4867, 5209, -1, 4871, 4867, 5208, -1, 5209, 4864, 4988, -1, 4867, 4864, 5209, -1, 4862, 4865, 4987, -1, 4987, 4865, 5210, -1, 5210, 4870, 5211, -1, 4865, 4870, 5210, -1, 5211, 4874, 5212, -1, 4870, 4874, 5211, -1, 5212, 4878, 5213, -1, 4874, 4878, 5212, -1, 5213, 4883, 5214, -1, 4878, 4883, 5213, -1, 5214, 4758, 5215, -1, 4883, 4758, 5214, -1, 5215, 4760, 5216, -1, 4758, 4760, 5215, -1, 5216, 4927, 5217, -1, 4760, 4927, 5216, -1, 5217, 4921, 5218, -1, 4927, 4921, 5217, -1, 5218, 4922, 5219, -1, 4921, 4922, 5218, -1, 5219, 4915, 5220, -1, 4922, 4915, 5219, -1, 5220, 4911, 5221, -1, 4915, 4911, 5220, -1, 5221, 4904, 4974, -1, 4911, 4904, 5221, -1, 4908, 4912, 4973, -1, 4973, 4912, 5222, -1, 5222, 4916, 5223, -1, 4912, 4916, 5222, -1, 5223, 4919, 5224, -1, 4916, 4919, 5223, -1, 5224, 4924, 5225, -1, 4919, 4924, 5224, -1, 5225, 4928, 5226, -1, 4924, 4928, 5225, -1, 5226, 4761, 5227, -1, 4928, 4761, 5226, -1, 5227, 4736, 5228, -1, 4761, 4736, 5227, -1, 5228, 4690, 5229, -1, 4736, 4690, 5228, -1, 5229, 4685, 5230, -1, 4690, 4685, 5229, -1, 5230, 4680, 5231, -1, 4685, 4680, 5230, -1, 5231, 4672, 5232, -1, 4680, 4672, 5231, -1, 5232, 4661, 5233, -1, 4672, 4661, 5232, -1, 5233, 4663, 4960, -1, 4661, 4663, 5233, -1, 4662, 4668, 4959, -1, 4959, 4668, 5234, -1, 5234, 4677, 5235, -1, 4668, 4677, 5234, -1, 5235, 4683, 5236, -1, 4677, 4683, 5235, -1, 5236, 4691, 5237, -1, 4683, 4691, 5236, -1, 5237, 4696, 5238, -1, 4691, 4696, 5237, -1, 5238, 4729, 5239, -1, 4696, 4729, 5238, -1, 5239, 4730, 5240, -1, 4729, 4730, 5239, -1, 5240, 4731, 5241, -1, 4730, 4731, 5240, -1, 5241, 4732, 5242, -1, 4731, 4732, 5241, -1, 5242, 4733, 5243, -1, 4732, 4733, 5242, -1, 5243, 4734, 5244, -1, 4733, 4734, 5243, -1, 5244, 4735, 5245, -1, 4734, 4735, 5244, -1, 5245, 4707, 4946, -1, 4735, 4707, 5245, -1, 4956, 4954, 4955, -1, 4957, 4958, 4956, -1, 4956, 4953, 4954, -1, 4958, 4953, 4956, -1, 4959, 5234, 4958, -1, 5235, 5236, 5234, -1, 4952, 4949, 4951, -1, 4951, 4949, 4950, -1, 5237, 5238, 5236, -1, 4953, 4947, 4952, -1, 4949, 4947, 4948, -1, 4958, 4947, 4953, -1, 4952, 4947, 4949, -1, 5236, 5239, 5234, -1, 5238, 5239, 5236, -1, 4947, 5245, 4946, -1, 5240, 5245, 5239, -1, 5234, 5245, 4958, -1, 4958, 5245, 4947, -1, 5239, 5245, 5234, -1, 5245, 5243, 5244, -1, 5242, 5243, 5241, -1, 5241, 5243, 5240, -1, 5240, 5243, 5245, -1, 4970, 4968, 4969, -1, 4971, 4972, 4970, -1, 4970, 4967, 4968, -1, 4972, 4973, 4970, -1, 4970, 4973, 4967, -1, 4973, 4966, 4967, -1, 5223, 5224, 5222, -1, 5222, 5224, 4973, -1, 4966, 4963, 4965, -1, 4965, 4963, 4964, -1, 5225, 5226, 5224, -1, 4963, 4961, 4962, -1, 4973, 4961, 4966, -1, 4966, 4961, 4963, -1, 5224, 5227, 4973, -1, 5226, 5227, 5224, -1, 5227, 5228, 4973, -1, 4961, 5233, 4960, -1, 4973, 5233, 4961, -1, 5228, 5233, 4973, -1, 5233, 5231, 5232, -1, 5230, 5231, 5229, -1, 5229, 5231, 5228, -1, 5228, 5231, 5233, -1, 4984, 4982, 4983, -1, 4985, 4986, 4984, -1, 4984, 4981, 4982, -1, 4986, 4987, 4984, -1, 4984, 4987, 4981, -1, 4987, 4980, 4981, -1, 5211, 5212, 5210, -1, 5210, 5212, 4987, -1, 4980, 4977, 4979, -1, 4979, 4977, 4978, -1, 5213, 5214, 5212, -1, 4977, 4975, 4976, -1, 4987, 4975, 4980, -1, 4980, 4975, 4977, -1, 5212, 5215, 4987, -1, 5214, 5215, 5212, -1, 5215, 5216, 4987, -1, 4975, 5221, 4974, -1, 4987, 5221, 4975, -1, 5216, 5221, 4987, -1, 5221, 5219, 5220, -1, 5218, 5219, 5217, -1, 5217, 5219, 5216, -1, 5216, 5219, 5221, -1, 4998, 4996, 4997, -1, 4999, 5000, 4998, -1, 4998, 4995, 4996, -1, 5000, 5001, 4998, -1, 4998, 5001, 4995, -1, 5001, 4994, 4995, -1, 5199, 5200, 5198, -1, 5198, 5200, 5001, -1, 4994, 4991, 4993, -1, 4993, 4991, 4992, -1, 5201, 5202, 5200, -1, 4991, 4989, 4990, -1, 5001, 4989, 4994, -1, 4994, 4989, 4991, -1, 5200, 5203, 5001, -1, 5202, 5203, 5200, -1, 5203, 5204, 5001, -1, 4989, 5209, 4988, -1, 5001, 5209, 4989, -1, 5204, 5209, 5001, -1, 5209, 5207, 5208, -1, 5206, 5207, 5205, -1, 5205, 5207, 5204, -1, 5204, 5207, 5209, -1, 5012, 5009, 5011, -1, 5011, 5009, 5010, -1, 5015, 5186, 5014, -1, 5014, 5187, 5013, -1, 5186, 5187, 5014, -1, 5008, 5006, 5007, -1, 5013, 5188, 5012, -1, 5187, 5188, 5013, -1, 5009, 5005, 5008, -1, 5012, 5005, 5009, -1, 5008, 5005, 5006, -1, 5190, 5191, 5189, -1, 5189, 5191, 5188, -1, 5003, 5197, 5002, -1, 5004, 5196, 5003, -1, 5003, 5196, 5197, -1, 5193, 5194, 5192, -1, 5005, 5195, 5004, -1, 5192, 5195, 5191, -1, 5188, 5195, 5012, -1, 5012, 5195, 5005, -1, 5194, 5195, 5192, -1, 5191, 5195, 5188, -1, 5004, 5195, 5196, -1, 5026, 5023, 5025, -1, 5025, 5023, 5024, -1, 5029, 5174, 5028, -1, 5028, 5175, 5027, -1, 5174, 5175, 5028, -1, 5022, 5020, 5021, -1, 5027, 5176, 5026, -1, 5175, 5176, 5027, -1, 5023, 5019, 5022, -1, 5026, 5019, 5023, -1, 5022, 5019, 5020, -1, 5178, 5179, 5177, -1, 5177, 5179, 5176, -1, 5017, 5185, 5016, -1, 5018, 5184, 5017, -1, 5017, 5184, 5185, -1, 5181, 5182, 5180, -1, 5019, 5183, 5018, -1, 5180, 5183, 5179, -1, 5176, 5183, 5026, -1, 5026, 5183, 5019, -1, 5182, 5183, 5180, -1, 5179, 5183, 5176, -1, 5018, 5183, 5184, -1, 5039, 5037, 5038, -1, 5042, 5043, 5041, -1, 5162, 5163, 5043, -1, 5043, 5163, 5041, -1, 5036, 5034, 5035, -1, 5166, 5167, 5165, -1, 5041, 5030, 5040, -1, 5040, 5030, 5039, -1, 5037, 5030, 5036, -1, 5034, 5030, 5033, -1, 5033, 5030, 5032, -1, 5032, 5030, 5031, -1, 5165, 5030, 5164, -1, 5164, 5030, 5163, -1, 5039, 5030, 5037, -1, 5036, 5030, 5034, -1, 5163, 5030, 5041, -1, 5167, 5030, 5165, -1, 5167, 5168, 5030, -1, 5030, 5172, 5173, -1, 5169, 5170, 5168, -1, 5168, 5170, 5030, -1, 5170, 5171, 5030, -1, 5030, 5171, 5172, -1, 5053, 5051, 5052, -1, 5056, 5057, 5055, -1, 5150, 5151, 5057, -1, 5057, 5151, 5055, -1, 5051, 5048, 5050, -1, 5050, 5048, 5049, -1, 5053, 5048, 5051, -1, 5054, 5047, 5053, -1, 5053, 5047, 5048, -1, 5055, 5046, 5054, -1, 5054, 5046, 5047, -1, 5154, 5155, 5153, -1, 5046, 5044, 5045, -1, 5044, 5160, 5161, -1, 5151, 5160, 5055, -1, 5055, 5160, 5046, -1, 5046, 5160, 5044, -1, 5157, 5158, 5156, -1, 5156, 5158, 5155, -1, 5155, 5158, 5153, -1, 5153, 5159, 5152, -1, 5152, 5159, 5151, -1, 5151, 5159, 5160, -1, 5158, 5159, 5153, -1, 5068, 5066, 5067, -1, 5068, 5065, 5066, -1, 5070, 5071, 5069, -1, 5138, 5139, 5071, -1, 5071, 5139, 5069, -1, 5069, 5140, 5068, -1, 5139, 5140, 5069, -1, 5065, 5061, 5064, -1, 5064, 5061, 5063, -1, 5063, 5061, 5062, -1, 5068, 5061, 5065, -1, 5141, 5142, 5140, -1, 5142, 5143, 5140, -1, 5060, 5058, 5059, -1, 5058, 5148, 5149, -1, 5060, 5148, 5058, -1, 5061, 5147, 5060, -1, 5146, 5147, 5145, -1, 5145, 5147, 5144, -1, 5144, 5147, 5143, -1, 5140, 5147, 5068, -1, 5068, 5147, 5061, -1, 5143, 5147, 5140, -1, 5060, 5147, 5148, -1, 5082, 5079, 5081, -1, 5081, 5079, 5080, -1, 5085, 5126, 5084, -1, 5084, 5127, 5083, -1, 5126, 5127, 5084, -1, 5078, 5076, 5077, -1, 5083, 5128, 5082, -1, 5127, 5128, 5083, -1, 5079, 5075, 5078, -1, 5082, 5075, 5079, -1, 5078, 5075, 5076, -1, 5130, 5131, 5129, -1, 5129, 5131, 5128, -1, 5073, 5137, 5072, -1, 5074, 5136, 5073, -1, 5073, 5136, 5137, -1, 5133, 5134, 5132, -1, 5075, 5135, 5074, -1, 5132, 5135, 5131, -1, 5128, 5135, 5082, -1, 5082, 5135, 5075, -1, 5134, 5135, 5132, -1, 5131, 5135, 5128, -1, 5074, 5135, 5136, -1, 5096, 5093, 5095, -1, 5095, 5093, 5094, -1, 5099, 5114, 5098, -1, 5098, 5115, 5097, -1, 5114, 5115, 5098, -1, 5092, 5090, 5091, -1, 5097, 5116, 5096, -1, 5115, 5116, 5097, -1, 5092, 5089, 5090, -1, 5118, 5119, 5117, -1, 5117, 5119, 5116, -1, 5093, 5086, 5092, -1, 5089, 5086, 5088, -1, 5088, 5086, 5087, -1, 5116, 5086, 5096, -1, 5096, 5086, 5093, -1, 5092, 5086, 5089, -1, 5086, 5124, 5125, -1, 5121, 5122, 5120, -1, 5120, 5123, 5119, -1, 5116, 5123, 5086, -1, 5119, 5123, 5116, -1, 5122, 5123, 5120, -1, 5086, 5123, 5124, -1, 5246, 5247, 2006, -1, 5248, 5249, 5246, -1, 5248, 5246, 2006, -1, 5250, 5251, 5252, -1, 2072, 5252, 5253, -1, 2072, 5253, 5248, -1, 2072, 5248, 2006, -1, 2072, 5250, 5252, -1, 5254, 2007, 2006, -1, 5254, 2006, 5247, -1, 5255, 5247, 5246, -1, 5255, 5254, 5247, -1, 5256, 5246, 5249, -1, 5256, 5255, 5246, -1, 5257, 5249, 5248, -1, 5257, 5256, 5249, -1, 5258, 5253, 5252, -1, 5259, 5252, 5251, -1, 5259, 5258, 5252, -1, 5260, 5251, 5250, -1, 5260, 5259, 5251, -1, 5261, 5250, 2072, -1, 5261, 5260, 5250, -1, 1935, 5261, 2072, -1, 5259, 5260, 5261, -1, 5259, 5261, 1935, -1, 5258, 5259, 1935, -1, 5257, 5258, 1935, -1, 2007, 5254, 5255, -1, 2007, 5255, 5256, -1, 2007, 5256, 5257, -1, 2007, 5257, 1935, -1, 3174, 5262, 5263, -1, 5264, 3174, 5263, -1, 5265, 5264, 5266, -1, 5265, 3174, 5264, -1, 5267, 5268, 5269, -1, 3179, 5267, 5270, -1, 3179, 5270, 5271, -1, 3179, 5268, 5267, -1, 3179, 3174, 5265, -1, 3179, 5265, 5268, -1, 5272, 3188, 3179, -1, 5272, 3179, 5271, -1, 5273, 5271, 5270, -1, 5273, 5272, 5271, -1, 5274, 5270, 5267, -1, 5274, 5273, 5270, -1, 5275, 5267, 5269, -1, 5275, 5274, 5267, -1, 5276, 5269, 5268, -1, 5276, 5275, 5269, -1, 5277, 5266, 5264, -1, 5277, 5265, 5266, -1, 5277, 5278, 5265, -1, 5279, 5264, 5263, -1, 5279, 5277, 5264, -1, 5280, 5263, 5262, -1, 5280, 5279, 5263, -1, 5281, 5262, 3174, -1, 5281, 5280, 5262, -1, 3187, 5281, 3174, -1, 3188, 5272, 5273, -1, 5274, 3188, 5273, -1, 5276, 5274, 5275, -1, 5276, 3188, 5274, -1, 5279, 5278, 5277, -1, 3187, 5279, 5280, -1, 3187, 5280, 5281, -1, 3187, 5278, 5279, -1, 3187, 3188, 5276, -1, 3187, 5276, 5278, -1, 5276, 5265, 5278, -1, 5276, 5268, 5265, -1, 5282, 5283, 5284, -1, 5282, 5285, 5283, -1, 5282, 5286, 5285, -1, 5287, 5284, 5288, -1, 5287, 5282, 5284, -1, 5289, 5288, 5290, -1, 5289, 5287, 5288, -1, 5291, 5290, 3172, -1, 5291, 5289, 5290, -1, 3186, 5291, 3172, -1, 3280, 5292, 5293, -1, 3280, 5293, 5294, -1, 3280, 5294, 5295, -1, 5296, 3280, 5295, -1, 5297, 5292, 3280, -1, 5298, 3280, 5296, -1, 5299, 5297, 3280, -1, 5300, 5301, 5302, -1, 5303, 5300, 5302, -1, 5291, 3273, 5289, -1, 3271, 5303, 5302, -1, 3207, 3273, 5291, -1, 3186, 3207, 5291, -1, 3273, 3280, 5289, -1, 5289, 3280, 5287, -1, 5287, 3280, 5282, -1, 5282, 3280, 5286, -1, 5286, 3280, 5298, -1, 3280, 3271, 5302, -1, 3280, 5302, 5299, -1, 3269, 3105, 3113, -1, 3269, 3113, 3541, -1, 3270, 3541, 3538, -1, 3270, 3269, 3541, -1, 3271, 3538, 3540, -1, 3271, 3270, 3538, -1, 5303, 3540, 5304, -1, 5303, 3271, 3540, -1, 5300, 5304, 5305, -1, 5300, 5303, 5304, -1, 5301, 5305, 5306, -1, 5301, 5300, 5305, -1, 5302, 5306, 5307, -1, 5302, 5301, 5306, -1, 3543, 5290, 5288, -1, 3173, 3172, 5290, -1, 3173, 5290, 3543, -1, 3549, 5308, 5309, -1, 3549, 5309, 5310, -1, 3549, 5310, 5311, -1, 5312, 3549, 5311, -1, 5313, 3549, 5312, -1, 5314, 3549, 5313, -1, 5315, 3549, 5314, -1, 5305, 5307, 5306, -1, 3540, 5305, 5304, -1, 3540, 5307, 5305, -1, 3540, 3549, 5315, -1, 3540, 5315, 5307, -1, 3549, 3543, 5288, -1, 3549, 5288, 5284, -1, 3549, 5284, 5283, -1, 3549, 5283, 5285, -1, 3549, 5285, 5308, -1, 5298, 5285, 5286, -1, 5308, 5285, 5298, -1, 5297, 5299, 5315, -1, 5297, 5315, 5314, -1, 5292, 5314, 5313, -1, 5292, 5297, 5314, -1, 5293, 5313, 5312, -1, 5293, 5292, 5313, -1, 5294, 5312, 5311, -1, 5294, 5293, 5312, -1, 5295, 5311, 5310, -1, 5295, 5294, 5311, -1, 5296, 5310, 5309, -1, 5296, 5295, 5310, -1, 5298, 5309, 5308, -1, 5298, 5296, 5309, -1, 5316, 5317, 5318, -1, 5319, 5320, 5321, -1, 5322, 5323, 5324, -1, 5321, 5320, 5325, -1, 5324, 5323, 5326, -1, 5321, 5327, 5319, -1, 5316, 5328, 5317, -1, 5329, 5330, 5299, -1, 5299, 5331, 5329, -1, 5332, 5328, 5316, -1, 5333, 5327, 5321, -1, 5334, 5335, 5336, -1, 5330, 5337, 5299, -1, 5320, 5338, 5325, -1, 5325, 5338, 5339, -1, 5299, 5340, 5331, -1, 5323, 5335, 5326, -1, 5326, 5335, 5334, -1, 5333, 5341, 5327, -1, 5337, 5342, 5299, -1, 5343, 5344, 5345, -1, 5302, 5346, 5299, -1, 5332, 5347, 5328, -1, 5348, 5341, 5333, -1, 5349, 5347, 5350, -1, 5299, 5346, 5340, -1, 5350, 5347, 5332, -1, 5338, 5351, 5339, -1, 5335, 5352, 5336, -1, 5342, 5353, 5299, -1, 5345, 5354, 5355, -1, 5339, 5351, 5356, -1, 5336, 5352, 5299, -1, 5344, 5354, 5345, -1, 5302, 5357, 5346, -1, 5358, 5359, 5343, -1, 5348, 5360, 5341, -1, 5353, 5361, 5299, -1, 5362, 5360, 5348, -1, 5349, 5363, 5347, -1, 5343, 5359, 5344, -1, 5302, 5364, 5357, -1, 5355, 5365, 5366, -1, 5349, 5367, 5363, -1, 5354, 5365, 5355, -1, 5368, 5369, 5358, -1, 5362, 5370, 5360, -1, 5371, 5367, 5349, -1, 5302, 5372, 5364, -1, 5373, 5370, 5374, -1, 5374, 5370, 5362, -1, 5358, 5369, 5359, -1, 5371, 5375, 5367, -1, 5302, 5376, 5372, -1, 5377, 5375, 5378, -1, 5378, 5375, 5371, -1, 5368, 5379, 5369, -1, 5373, 5380, 5370, -1, 5302, 5381, 5376, -1, 5377, 5382, 5375, -1, 5368, 5383, 5379, -1, 5384, 5383, 5368, -1, 5373, 5385, 5380, -1, 5377, 5386, 5382, -1, 5302, 5387, 5381, -1, 5388, 5385, 5373, -1, 5389, 5386, 5377, -1, 5302, 5390, 5387, -1, 5384, 5391, 5383, -1, 5392, 5391, 5384, -1, 5389, 5393, 5386, -1, 5388, 5394, 5385, -1, 5395, 5394, 5388, -1, 5302, 5396, 5390, -1, 5397, 5393, 5389, -1, 5392, 5398, 5391, -1, 5399, 5398, 5392, -1, 5400, 5401, 5395, -1, 5395, 5401, 5394, -1, 5399, 5402, 5398, -1, 5403, 5404, 5400, -1, 5405, 5402, 5399, -1, 5400, 5404, 5401, -1, 5406, 5407, 5408, -1, 5405, 5409, 5402, -1, 5410, 5409, 5405, -1, 5408, 5411, 5361, -1, 5407, 5411, 5408, -1, 5412, 5413, 5414, -1, 5414, 5413, 5415, -1, 5416, 5417, 5406, -1, 5406, 5417, 5407, -1, 5413, 5418, 5415, -1, 5361, 5419, 5299, -1, 5415, 5418, 5420, -1, 5411, 5419, 5361, -1, 5412, 5421, 5413, -1, 5422, 5423, 5416, -1, 5416, 5423, 5417, -1, 5424, 5421, 5412, -1, 5418, 5425, 5420, -1, 5419, 5426, 5299, -1, 5427, 5428, 5429, -1, 5429, 5428, 5430, -1, 5431, 5428, 5427, -1, 5432, 5433, 5434, -1, 5434, 5433, 5422, -1, 5422, 5433, 5423, -1, 5365, 5315, 5366, -1, 5435, 5315, 5351, -1, 5424, 5436, 5421, -1, 5437, 5315, 5438, -1, 5439, 5440, 5441, -1, 5366, 5315, 5437, -1, 5441, 5440, 5427, -1, 5426, 5442, 5299, -1, 5351, 5315, 5356, -1, 5427, 5440, 5431, -1, 5438, 5315, 5443, -1, 5425, 5444, 5420, -1, 5420, 5444, 5352, -1, 5445, 5315, 5446, -1, 5352, 5444, 5299, -1, 5447, 5315, 5445, -1, 5430, 5448, 5449, -1, 5450, 5451, 5432, -1, 5432, 5451, 5433, -1, 5428, 5448, 5430, -1, 5452, 5315, 5453, -1, 5453, 5315, 5454, -1, 5454, 5315, 5455, -1, 5455, 5315, 5456, -1, 5457, 5458, 5459, -1, 5456, 5315, 5460, -1, 5459, 5458, 5424, -1, 5460, 5315, 5461, -1, 5461, 5315, 5462, -1, 5463, 5464, 5439, -1, 5424, 5458, 5436, -1, 5462, 5315, 5365, -1, 5356, 5315, 5465, -1, 5443, 5315, 5435, -1, 5439, 5464, 5440, -1, 5446, 5315, 5299, -1, 5465, 5315, 5447, -1, 5466, 5467, 5450, -1, 5444, 5468, 5299, -1, 5410, 5307, 5409, -1, 5409, 5307, 5469, -1, 5448, 5470, 5449, -1, 5450, 5467, 5451, -1, 5469, 5307, 5471, -1, 5471, 5307, 5472, -1, 5472, 5307, 5473, -1, 5473, 5307, 5474, -1, 5474, 5307, 5475, -1, 5475, 5307, 5476, -1, 5476, 5307, 5452, -1, 5452, 5307, 5315, -1, 5457, 5477, 5458, -1, 5478, 5307, 5410, -1, 5479, 5307, 5478, -1, 5302, 5307, 5480, -1, 5463, 5481, 5464, -1, 5482, 5483, 5466, -1, 5302, 5480, 5484, -1, 5466, 5483, 5467, -1, 5302, 5484, 5485, -1, 5302, 5485, 5404, -1, 5302, 5404, 5403, -1, 5302, 5403, 5486, -1, 5302, 5486, 5487, -1, 5463, 5488, 5481, -1, 5302, 5487, 5489, -1, 5302, 5489, 5490, -1, 5302, 5490, 5491, -1, 5482, 5492, 5483, -1, 5302, 5491, 5493, -1, 5302, 5493, 5494, -1, 5495, 5496, 5457, -1, 5302, 5494, 5497, -1, 5498, 5488, 5463, -1, 5457, 5496, 5477, -1, 5302, 5497, 5393, -1, 5396, 5492, 5482, -1, 5302, 5393, 5499, -1, 5302, 5499, 5500, -1, 5302, 5500, 5501, -1, 5480, 5307, 5502, -1, 5499, 5393, 5397, -1, 5502, 5307, 5479, -1, 5503, 5504, 5505, -1, 5396, 5506, 5492, -1, 5505, 5504, 5498, -1, 5507, 5508, 5509, -1, 5302, 5506, 5396, -1, 5509, 5508, 5495, -1, 5498, 5504, 5488, -1, 5495, 5508, 5496, -1, 5302, 5510, 5506, -1, 5511, 5512, 5507, -1, 5503, 5513, 5504, -1, 5507, 5512, 5508, -1, 5302, 5501, 5510, -1, 5503, 5514, 5513, -1, 5515, 5514, 5516, -1, 5516, 5514, 5503, -1, 5511, 5517, 5512, -1, 5485, 5518, 5515, -1, 5515, 5518, 5514, -1, 5497, 5494, 5511, -1, 5511, 5494, 5517, -1, 5485, 5484, 5518, -1, 5519, 5520, 5521, -1, 5520, 5522, 5521, -1, 5521, 5522, 5523, -1, 5519, 5524, 5520, -1, 5523, 5525, 5526, -1, 5522, 5525, 5523, -1, 5527, 5528, 5529, -1, 5519, 5530, 5524, -1, 5531, 5530, 5519, -1, 5532, 5528, 5527, -1, 5527, 5533, 5532, -1, 5442, 5534, 5299, -1, 5526, 5534, 5442, -1, 5535, 5536, 5537, -1, 5525, 5534, 5526, -1, 5537, 5536, 5538, -1, 5537, 5539, 5535, -1, 5540, 5533, 5527, -1, 5529, 5541, 5542, -1, 5543, 5544, 5531, -1, 5531, 5544, 5530, -1, 5528, 5541, 5529, -1, 5545, 5539, 5546, -1, 5546, 5539, 5537, -1, 5534, 5336, 5299, -1, 5540, 5547, 5533, -1, 5538, 5548, 5549, -1, 5549, 5548, 5550, -1, 5543, 5551, 5544, -1, 5536, 5548, 5538, -1, 5552, 5551, 5543, -1, 5553, 5547, 5540, -1, 5542, 5554, 5468, -1, 5555, 5556, 5545, -1, 5468, 5554, 5299, -1, 5545, 5556, 5539, -1, 5541, 5554, 5542, -1, 5557, 5558, 5552, -1, 5559, 5558, 5557, -1, 5548, 5560, 5550, -1, 5553, 5561, 5547, -1, 5552, 5558, 5551, -1, 5562, 5561, 5553, -1, 5563, 5564, 5555, -1, 5555, 5564, 5556, -1, 5554, 5446, 5299, -1, 5559, 5565, 5558, -1, 5566, 5567, 5562, -1, 5562, 5567, 5561, -1, 5568, 5569, 5563, -1, 5570, 5571, 5559, -1, 5563, 5569, 5564, -1, 5559, 5571, 5565, -1, 5566, 5572, 5567, -1, 5573, 5574, 5568, -1, 5575, 5572, 5566, -1, 5576, 5577, 5570, -1, 5568, 5574, 5569, -1, 5570, 5577, 5571, -1, 5575, 5578, 5572, -1, 5501, 5500, 5576, -1, 5579, 5580, 5573, -1, 5576, 5500, 5577, -1, 5573, 5580, 5574, -1, 5581, 5578, 5575, -1, 5581, 5582, 5578, -1, 5579, 5583, 5580, -1, 5584, 5582, 5581, -1, 5585, 5586, 5587, -1, 5587, 5586, 5579, -1, 5584, 5588, 5582, -1, 5579, 5586, 5583, -1, 5589, 5588, 5584, -1, 5585, 5590, 5586, -1, 5589, 5491, 5588, -1, 5591, 5592, 5593, -1, 5493, 5491, 5589, -1, 5593, 5594, 5595, -1, 5592, 5594, 5593, -1, 5596, 5597, 5591, -1, 5591, 5597, 5592, -1, 5595, 5598, 5599, -1, 5594, 5598, 5595, -1, 5600, 5601, 5596, -1, 5596, 5601, 5597, -1, 5598, 5602, 5599, -1, 5599, 5602, 5336, -1, 5603, 5604, 5605, -1, 5606, 5607, 5608, -1, 5609, 5607, 5606, -1, 5600, 5610, 5601, -1, 5602, 5611, 5336, -1, 5604, 5612, 5605, -1, 5613, 5614, 5606, -1, 5605, 5612, 5615, -1, 5606, 5614, 5609, -1, 5616, 5617, 5600, -1, 5607, 5618, 5608, -1, 5603, 5619, 5604, -1, 5608, 5618, 5620, -1, 5600, 5617, 5610, -1, 5613, 5621, 5614, -1, 5622, 5619, 5603, -1, 5623, 5621, 5613, -1, 5624, 5625, 5616, -1, 5618, 5445, 5620, -1, 5620, 5445, 5446, -1, 5616, 5625, 5617, -1, 5615, 5626, 5627, -1, 5612, 5626, 5615, -1, 5623, 5628, 5621, -1, 5622, 5629, 5619, -1, 5630, 5631, 5624, -1, 5632, 5628, 5623, -1, 5624, 5631, 5625, -1, 5633, 5629, 5622, -1, 5626, 5435, 5627, -1, 5470, 5435, 5449, -1, 5449, 5435, 5351, -1, 5632, 5634, 5628, -1, 5550, 5435, 5470, -1, 5630, 5635, 5631, -1, 5560, 5435, 5550, -1, 5636, 5635, 5630, -1, 5637, 5634, 5632, -1, 5627, 5435, 5560, -1, 5633, 5638, 5629, -1, 5636, 5639, 5635, -1, 5637, 5640, 5634, -1, 5641, 5639, 5636, -1, 5642, 5640, 5637, -1, 5643, 5638, 5644, -1, 5644, 5638, 5633, -1, 5641, 5645, 5639, -1, 5643, 5646, 5638, -1, 5499, 5645, 5641, -1, 5642, 5647, 5640, -1, 5648, 5646, 5643, -1, 5649, 5647, 5642, -1, 5648, 5650, 5646, -1, 5499, 5651, 5645, -1, 5649, 5652, 5647, -1, 5653, 5650, 5648, -1, 5654, 5652, 5649, -1, 5653, 5655, 5650, -1, 5656, 5657, 5654, -1, 5658, 5655, 5653, -1, 5654, 5657, 5652, -1, 5658, 5659, 5655, -1, 5490, 5489, 5656, -1, 5656, 5489, 5657, -1, 5660, 5659, 5658, -1, 5661, 5662, 5663, -1, 5664, 5662, 5661, -1, 5660, 5665, 5659, -1, 5666, 5665, 5660, -1, 5667, 5668, 5661, -1, 5661, 5668, 5664, -1, 5484, 5480, 5585, -1, 5663, 5669, 5670, -1, 5666, 5480, 5665, -1, 5662, 5669, 5663, -1, 5585, 5480, 5590, -1, 5590, 5480, 5666, -1, 5671, 5672, 5667, -1, 5667, 5672, 5668, -1, 5673, 5674, 5675, -1, 5670, 5676, 5611, -1, 5669, 5676, 5670, -1, 5677, 5674, 5673, -1, 5611, 5676, 5336, -1, 5678, 5679, 5673, -1, 5680, 5681, 5682, -1, 5682, 5681, 5671, -1, 5673, 5679, 5677, -1, 5671, 5681, 5672, -1, 5675, 5683, 5684, -1, 5674, 5683, 5675, -1, 5676, 5334, 5336, -1, 5680, 5685, 5681, -1, 5686, 5687, 5678, -1, 5678, 5687, 5679, -1, 5688, 5689, 5690, -1, 5691, 5689, 5688, -1, 5689, 5692, 5690, -1, 5684, 5465, 5447, -1, 5690, 5692, 5693, -1, 5683, 5465, 5684, -1, 5691, 5694, 5689, -1, 5695, 5696, 5680, -1, 5680, 5696, 5685, -1, 5697, 5698, 5686, -1, 5686, 5698, 5687, -1, 5692, 5699, 5693, -1, 5693, 5699, 5443, -1, 5700, 5701, 5695, -1, 5691, 5702, 5694, -1, 5695, 5701, 5696, -1, 5703, 5704, 5697, -1, 5697, 5704, 5698, -1, 5705, 5702, 5691, -1, 5699, 5438, 5443, -1, 5700, 5706, 5701, -1, 5707, 5706, 5700, -1, 5705, 5708, 5702, -1, 5709, 5710, 5703, -1, 5703, 5710, 5704, -1, 5711, 5708, 5705, -1, 5712, 5713, 5707, -1, 5707, 5713, 5706, -1, 5709, 5714, 5710, -1, 5711, 5715, 5708, -1, 5716, 5715, 5711, -1, 5717, 5714, 5709, -1, 5651, 5718, 5712, -1, 5499, 5718, 5651, -1, 5719, 5715, 5716, -1, 5712, 5718, 5713, -1, 5717, 5720, 5714, -1, 5721, 5720, 5717, -1, 5722, 5723, 5719, -1, 5719, 5723, 5715, -1, 5721, 5724, 5720, -1, 5499, 5397, 5718, -1, 5725, 5724, 5721, -1, 5722, 5726, 5723, -1, 5727, 5726, 5722, -1, 5725, 5486, 5724, -1, 5487, 5486, 5725, -1, 5727, 5728, 5726, -1, 5318, 5729, 5324, -1, 5730, 5731, 5727, -1, 5502, 5731, 5730, -1, 5727, 5731, 5728, -1, 5729, 5322, 5324, -1, 5318, 5317, 5729, -1, 5502, 5479, 5731, -1, 5463, 5439, 5732, -1, 5732, 5439, 5733, -1, 5733, 5441, 5734, -1, 5439, 5441, 5733, -1, 5734, 5427, 5735, -1, 5441, 5427, 5734, -1, 5735, 5429, 5736, -1, 5427, 5429, 5735, -1, 5736, 5430, 5737, -1, 5429, 5430, 5736, -1, 5737, 5449, 5738, -1, 5430, 5449, 5737, -1, 5738, 5351, 5739, -1, 5449, 5351, 5738, -1, 5739, 5338, 5740, -1, 5351, 5338, 5739, -1, 5740, 5320, 5741, -1, 5338, 5320, 5740, -1, 5741, 5319, 5742, -1, 5320, 5319, 5741, -1, 5742, 5327, 5743, -1, 5319, 5327, 5742, -1, 5743, 5341, 5744, -1, 5327, 5341, 5743, -1, 5744, 5360, 5745, -1, 5341, 5360, 5744, -1, 5459, 5424, 5746, -1, 5746, 5424, 5747, -1, 5747, 5412, 5748, -1, 5424, 5412, 5747, -1, 5748, 5414, 5749, -1, 5412, 5414, 5748, -1, 5749, 5415, 5750, -1, 5414, 5415, 5749, -1, 5750, 5420, 5751, -1, 5415, 5420, 5750, -1, 5751, 5352, 5752, -1, 5420, 5352, 5751, -1, 5752, 5335, 5753, -1, 5352, 5335, 5752, -1, 5753, 5323, 5754, -1, 5335, 5323, 5753, -1, 5754, 5322, 5755, -1, 5323, 5322, 5754, -1, 5755, 5729, 5756, -1, 5322, 5729, 5755, -1, 5756, 5317, 5757, -1, 5729, 5317, 5756, -1, 5757, 5328, 5758, -1, 5317, 5328, 5757, -1, 5758, 5347, 5759, -1, 5328, 5347, 5758, -1, 5452, 5453, 5760, -1, 5760, 5453, 5761, -1, 5761, 5454, 5762, -1, 5453, 5454, 5761, -1, 5762, 5455, 5763, -1, 5454, 5455, 5762, -1, 5763, 5456, 5764, -1, 5455, 5456, 5763, -1, 5764, 5460, 5765, -1, 5456, 5460, 5764, -1, 5765, 5461, 5766, -1, 5460, 5461, 5765, -1, 5766, 5462, 5767, -1, 5461, 5462, 5766, -1, 5767, 5365, 5768, -1, 5462, 5365, 5767, -1, 5768, 5354, 5769, -1, 5365, 5354, 5768, -1, 5769, 5344, 5770, -1, 5354, 5344, 5769, -1, 5770, 5359, 5771, -1, 5344, 5359, 5770, -1, 5771, 5369, 5772, -1, 5359, 5369, 5771, -1, 5772, 5379, 5773, -1, 5369, 5379, 5772, -1, 5644, 5633, 5774, -1, 5774, 5633, 5775, -1, 5775, 5622, 5776, -1, 5633, 5622, 5775, -1, 5776, 5603, 5777, -1, 5622, 5603, 5776, -1, 5777, 5605, 5778, -1, 5603, 5605, 5777, -1, 5778, 5615, 5779, -1, 5605, 5615, 5778, -1, 5779, 5627, 5780, -1, 5615, 5627, 5779, -1, 5780, 5560, 5781, -1, 5627, 5560, 5780, -1, 5781, 5548, 5782, -1, 5560, 5548, 5781, -1, 5782, 5536, 5783, -1, 5548, 5536, 5782, -1, 5783, 5535, 5784, -1, 5536, 5535, 5783, -1, 5784, 5539, 5785, -1, 5535, 5539, 5784, -1, 5785, 5556, 5786, -1, 5539, 5556, 5785, -1, 5786, 5564, 5787, -1, 5556, 5564, 5786, -1, 5555, 5545, 5788, -1, 5788, 5545, 5789, -1, 5789, 5546, 5790, -1, 5545, 5546, 5789, -1, 5790, 5537, 5791, -1, 5546, 5537, 5790, -1, 5791, 5538, 5792, -1, 5537, 5538, 5791, -1, 5792, 5549, 5793, -1, 5538, 5549, 5792, -1, 5793, 5550, 5794, -1, 5549, 5550, 5793, -1, 5794, 5470, 5795, -1, 5550, 5470, 5794, -1, 5795, 5448, 5796, -1, 5470, 5448, 5795, -1, 5796, 5428, 5797, -1, 5448, 5428, 5796, -1, 5797, 5431, 5798, -1, 5428, 5431, 5797, -1, 5798, 5440, 5799, -1, 5431, 5440, 5798, -1, 5799, 5464, 5800, -1, 5440, 5464, 5799, -1, 5800, 5481, 5801, -1, 5464, 5481, 5800, -1, 5697, 5686, 5802, -1, 5802, 5686, 5803, -1, 5803, 5678, 5804, -1, 5686, 5678, 5803, -1, 5804, 5673, 5805, -1, 5678, 5673, 5804, -1, 5805, 5675, 5806, -1, 5673, 5675, 5805, -1, 5806, 5684, 5807, -1, 5675, 5684, 5806, -1, 5807, 5447, 5808, -1, 5684, 5447, 5807, -1, 5808, 5445, 5809, -1, 5447, 5445, 5808, -1, 5809, 5618, 5810, -1, 5445, 5618, 5809, -1, 5810, 5607, 5811, -1, 5618, 5607, 5810, -1, 5811, 5609, 5812, -1, 5607, 5609, 5811, -1, 5812, 5614, 5813, -1, 5609, 5614, 5812, -1, 5813, 5621, 5814, -1, 5614, 5621, 5813, -1, 5814, 5628, 5815, -1, 5621, 5628, 5814, -1, 5632, 5623, 5816, -1, 5816, 5623, 5817, -1, 5817, 5613, 5818, -1, 5623, 5613, 5817, -1, 5818, 5606, 5819, -1, 5613, 5606, 5818, -1, 5819, 5608, 5820, -1, 5606, 5608, 5819, -1, 5820, 5620, 5821, -1, 5608, 5620, 5820, -1, 5821, 5446, 5822, -1, 5620, 5446, 5821, -1, 5822, 5554, 5823, -1, 5446, 5554, 5822, -1, 5823, 5541, 5824, -1, 5554, 5541, 5823, -1, 5824, 5528, 5825, -1, 5541, 5528, 5824, -1, 5825, 5532, 5826, -1, 5528, 5532, 5825, -1, 5826, 5533, 5827, -1, 5532, 5533, 5826, -1, 5827, 5547, 5828, -1, 5533, 5547, 5827, -1, 5828, 5561, 5829, -1, 5547, 5561, 5828, -1, 5350, 5332, 5830, -1, 5830, 5332, 5831, -1, 5831, 5316, 5832, -1, 5332, 5316, 5831, -1, 5832, 5318, 5833, -1, 5316, 5318, 5832, -1, 5833, 5324, 5834, -1, 5318, 5324, 5833, -1, 5834, 5326, 5835, -1, 5324, 5326, 5834, -1, 5835, 5334, 5836, -1, 5326, 5334, 5835, -1, 5836, 5676, 5837, -1, 5334, 5676, 5836, -1, 5837, 5669, 5838, -1, 5676, 5669, 5837, -1, 5838, 5662, 5839, -1, 5669, 5662, 5838, -1, 5839, 5664, 5840, -1, 5662, 5664, 5839, -1, 5840, 5668, 5841, -1, 5664, 5668, 5840, -1, 5841, 5672, 5842, -1, 5668, 5672, 5841, -1, 5842, 5681, 5843, -1, 5672, 5681, 5842, -1, 5682, 5671, 5844, -1, 5844, 5671, 5845, -1, 5845, 5667, 5846, -1, 5671, 5667, 5845, -1, 5846, 5661, 5847, -1, 5667, 5661, 5846, -1, 5847, 5663, 5848, -1, 5661, 5663, 5847, -1, 5848, 5670, 5849, -1, 5663, 5670, 5848, -1, 5849, 5611, 5850, -1, 5670, 5611, 5849, -1, 5850, 5602, 5851, -1, 5611, 5602, 5850, -1, 5851, 5598, 5852, -1, 5602, 5598, 5851, -1, 5852, 5594, 5853, -1, 5598, 5594, 5852, -1, 5853, 5592, 5854, -1, 5594, 5592, 5853, -1, 5854, 5597, 5855, -1, 5592, 5597, 5854, -1, 5855, 5601, 5856, -1, 5597, 5601, 5855, -1, 5856, 5610, 5857, -1, 5601, 5610, 5856, -1, 5434, 5422, 5858, -1, 5858, 5422, 5859, -1, 5859, 5416, 5860, -1, 5422, 5416, 5859, -1, 5860, 5406, 5861, -1, 5416, 5406, 5860, -1, 5861, 5408, 5862, -1, 5406, 5408, 5861, -1, 5862, 5361, 5863, -1, 5408, 5361, 5862, -1, 5863, 5353, 5864, -1, 5361, 5353, 5863, -1, 5864, 5342, 5865, -1, 5353, 5342, 5864, -1, 5865, 5337, 5866, -1, 5342, 5337, 5865, -1, 5866, 5330, 5867, -1, 5337, 5330, 5866, -1, 5867, 5329, 5868, -1, 5330, 5329, 5867, -1, 5868, 5331, 5869, -1, 5329, 5331, 5868, -1, 5869, 5340, 5870, -1, 5331, 5340, 5869, -1, 5870, 5346, 5871, -1, 5340, 5346, 5870, -1, 5362, 5348, 5872, -1, 5872, 5348, 5873, -1, 5873, 5333, 5874, -1, 5348, 5333, 5873, -1, 5874, 5321, 5875, -1, 5333, 5321, 5874, -1, 5875, 5325, 5876, -1, 5321, 5325, 5875, -1, 5876, 5339, 5877, -1, 5325, 5339, 5876, -1, 5877, 5356, 5878, -1, 5339, 5356, 5877, -1, 5878, 5465, 5879, -1, 5356, 5465, 5878, -1, 5879, 5683, 5880, -1, 5465, 5683, 5879, -1, 5880, 5674, 5881, -1, 5683, 5674, 5880, -1, 5881, 5677, 5882, -1, 5674, 5677, 5881, -1, 5882, 5679, 5883, -1, 5677, 5679, 5882, -1, 5883, 5687, 5884, -1, 5679, 5687, 5883, -1, 5884, 5698, 5885, -1, 5687, 5698, 5884, -1, 5562, 5553, 5886, -1, 5886, 5553, 5887, -1, 5887, 5540, 5888, -1, 5553, 5540, 5887, -1, 5888, 5527, 5889, -1, 5540, 5527, 5888, -1, 5889, 5529, 5890, -1, 5527, 5529, 5889, -1, 5890, 5542, 5891, -1, 5529, 5542, 5890, -1, 5891, 5468, 5892, -1, 5542, 5468, 5891, -1, 5892, 5444, 5893, -1, 5468, 5444, 5892, -1, 5893, 5425, 5894, -1, 5444, 5425, 5893, -1, 5894, 5418, 5895, -1, 5425, 5418, 5894, -1, 5895, 5413, 5896, -1, 5418, 5413, 5895, -1, 5896, 5421, 5897, -1, 5413, 5421, 5896, -1, 5897, 5436, 5898, -1, 5421, 5436, 5897, -1, 5898, 5458, 5899, -1, 5436, 5458, 5898, -1, 5900, 5901, 5433, -1, 5433, 5901, 5423, -1, 5423, 5902, 5417, -1, 5901, 5902, 5423, -1, 5417, 5903, 5407, -1, 5902, 5903, 5417, -1, 5407, 5904, 5411, -1, 5903, 5904, 5407, -1, 5411, 5905, 5419, -1, 5904, 5905, 5411, -1, 5419, 5906, 5426, -1, 5905, 5906, 5419, -1, 5426, 5907, 5442, -1, 5906, 5907, 5426, -1, 5442, 5908, 5526, -1, 5907, 5908, 5442, -1, 5526, 5909, 5523, -1, 5908, 5909, 5526, -1, 5523, 5910, 5521, -1, 5909, 5910, 5523, -1, 5521, 5911, 5519, -1, 5910, 5911, 5521, -1, 5519, 5912, 5531, -1, 5911, 5912, 5519, -1, 5531, 5913, 5543, -1, 5912, 5913, 5531, -1, 5914, 5915, 5544, -1, 5544, 5915, 5530, -1, 5530, 5916, 5524, -1, 5915, 5916, 5530, -1, 5524, 5917, 5520, -1, 5916, 5917, 5524, -1, 5520, 5918, 5522, -1, 5917, 5918, 5520, -1, 5522, 5919, 5525, -1, 5918, 5919, 5522, -1, 5525, 5920, 5534, -1, 5919, 5920, 5525, -1, 5534, 5921, 5336, -1, 5920, 5921, 5534, -1, 5336, 5922, 5599, -1, 5921, 5922, 5336, -1, 5599, 5923, 5595, -1, 5922, 5923, 5599, -1, 5595, 5924, 5593, -1, 5923, 5924, 5595, -1, 5593, 5925, 5591, -1, 5924, 5925, 5593, -1, 5591, 5926, 5596, -1, 5925, 5926, 5591, -1, 5596, 5927, 5600, -1, 5926, 5927, 5596, -1, 5928, 5929, 5638, -1, 5638, 5929, 5629, -1, 5629, 5930, 5619, -1, 5929, 5930, 5629, -1, 5619, 5931, 5604, -1, 5930, 5931, 5619, -1, 5604, 5932, 5612, -1, 5931, 5932, 5604, -1, 5612, 5933, 5626, -1, 5932, 5933, 5612, -1, 5626, 5934, 5435, -1, 5933, 5934, 5626, -1, 5435, 5935, 5443, -1, 5934, 5935, 5435, -1, 5443, 5936, 5693, -1, 5935, 5936, 5443, -1, 5693, 5937, 5690, -1, 5936, 5937, 5693, -1, 5690, 5938, 5688, -1, 5937, 5938, 5690, -1, 5688, 5939, 5691, -1, 5938, 5939, 5688, -1, 5691, 5940, 5705, -1, 5939, 5940, 5691, -1, 5705, 5941, 5711, -1, 5940, 5941, 5705, -1, 5942, 5943, 5708, -1, 5708, 5943, 5702, -1, 5702, 5944, 5694, -1, 5943, 5944, 5702, -1, 5694, 5945, 5689, -1, 5944, 5945, 5694, -1, 5689, 5946, 5692, -1, 5945, 5946, 5689, -1, 5692, 5947, 5699, -1, 5946, 5947, 5692, -1, 5699, 5948, 5438, -1, 5947, 5948, 5699, -1, 5438, 5949, 5437, -1, 5948, 5949, 5438, -1, 5437, 5950, 5366, -1, 5949, 5950, 5437, -1, 5366, 5951, 5355, -1, 5950, 5951, 5366, -1, 5355, 5952, 5345, -1, 5951, 5952, 5355, -1, 5345, 5953, 5343, -1, 5952, 5953, 5345, -1, 5343, 5954, 5358, -1, 5953, 5954, 5343, -1, 5358, 5955, 5368, -1, 5954, 5955, 5358, -1, 5955, 5956, 5368, -1, 5368, 5956, 5384, -1, 5384, 5957, 5392, -1, 5956, 5957, 5384, -1, 5392, 5958, 5399, -1, 5957, 5958, 5392, -1, 5399, 5959, 5405, -1, 5958, 5959, 5399, -1, 5405, 5960, 5410, -1, 5959, 5960, 5405, -1, 5410, 5961, 5478, -1, 5960, 5961, 5410, -1, 5478, 5962, 5479, -1, 5961, 5962, 5478, -1, 5479, 5963, 5731, -1, 5962, 5963, 5479, -1, 5731, 5964, 5728, -1, 5963, 5964, 5731, -1, 5728, 5965, 5726, -1, 5964, 5965, 5728, -1, 5726, 5966, 5723, -1, 5965, 5966, 5726, -1, 5723, 5967, 5715, -1, 5966, 5967, 5723, -1, 5715, 5942, 5708, -1, 5967, 5942, 5715, -1, 5941, 5968, 5711, -1, 5711, 5968, 5716, -1, 5716, 5969, 5719, -1, 5968, 5969, 5716, -1, 5719, 5970, 5722, -1, 5969, 5970, 5719, -1, 5722, 5971, 5727, -1, 5970, 5971, 5722, -1, 5727, 5972, 5730, -1, 5971, 5972, 5727, -1, 5730, 5973, 5502, -1, 5972, 5973, 5730, -1, 5502, 5974, 5480, -1, 5973, 5974, 5502, -1, 5480, 5975, 5665, -1, 5974, 5975, 5480, -1, 5665, 5976, 5659, -1, 5975, 5976, 5665, -1, 5659, 5977, 5655, -1, 5976, 5977, 5659, -1, 5655, 5978, 5650, -1, 5977, 5978, 5655, -1, 5650, 5979, 5646, -1, 5978, 5979, 5650, -1, 5646, 5928, 5638, -1, 5979, 5928, 5646, -1, 5927, 5980, 5600, -1, 5600, 5980, 5616, -1, 5616, 5981, 5624, -1, 5980, 5981, 5616, -1, 5624, 5982, 5630, -1, 5981, 5982, 5624, -1, 5630, 5983, 5636, -1, 5982, 5983, 5630, -1, 5636, 5984, 5641, -1, 5983, 5984, 5636, -1, 5641, 5985, 5499, -1, 5984, 5985, 5641, -1, 5499, 5986, 5500, -1, 5985, 5986, 5499, -1, 5500, 5987, 5577, -1, 5986, 5987, 5500, -1, 5577, 5988, 5571, -1, 5987, 5988, 5577, -1, 5571, 5989, 5565, -1, 5988, 5989, 5571, -1, 5565, 5990, 5558, -1, 5989, 5990, 5565, -1, 5558, 5991, 5551, -1, 5990, 5991, 5558, -1, 5551, 5914, 5544, -1, 5991, 5914, 5551, -1, 5913, 5992, 5543, -1, 5543, 5992, 5552, -1, 5552, 5993, 5557, -1, 5992, 5993, 5552, -1, 5557, 5994, 5559, -1, 5993, 5994, 5557, -1, 5559, 5995, 5570, -1, 5994, 5995, 5559, -1, 5570, 5996, 5576, -1, 5995, 5996, 5570, -1, 5576, 5997, 5501, -1, 5996, 5997, 5576, -1, 5501, 5998, 5510, -1, 5997, 5998, 5501, -1, 5510, 5999, 5506, -1, 5998, 5999, 5510, -1, 5506, 6000, 5492, -1, 5999, 6000, 5506, -1, 5492, 6001, 5483, -1, 6000, 6001, 5492, -1, 5483, 6002, 5467, -1, 6001, 6002, 5483, -1, 5467, 6003, 5451, -1, 6002, 6003, 5467, -1, 5451, 5900, 5433, -1, 6003, 5900, 5451, -1, 5458, 5477, 5899, -1, 5899, 5477, 6004, -1, 6004, 5496, 6005, -1, 5477, 5496, 6004, -1, 6005, 5508, 6006, -1, 5496, 5508, 6005, -1, 6006, 5512, 6007, -1, 5508, 5512, 6006, -1, 6007, 5517, 6008, -1, 5512, 5517, 6007, -1, 6008, 5494, 6009, -1, 5517, 5494, 6008, -1, 6009, 5493, 6010, -1, 5494, 5493, 6009, -1, 6010, 5589, 6011, -1, 5493, 5589, 6010, -1, 6011, 5584, 6012, -1, 5589, 5584, 6011, -1, 6012, 5581, 6013, -1, 5584, 5581, 6012, -1, 6013, 5575, 6014, -1, 5581, 5575, 6013, -1, 6014, 5566, 6015, -1, 5575, 5566, 6014, -1, 6015, 5562, 5886, -1, 5566, 5562, 6015, -1, 5698, 5704, 5885, -1, 5885, 5704, 6016, -1, 6016, 5710, 6017, -1, 5704, 5710, 6016, -1, 6017, 5714, 6018, -1, 5710, 5714, 6017, -1, 6018, 5720, 6019, -1, 5714, 5720, 6018, -1, 6019, 5724, 6020, -1, 5720, 5724, 6019, -1, 6020, 5486, 6021, -1, 5724, 5486, 6020, -1, 6021, 5403, 6022, -1, 5486, 5403, 6021, -1, 6022, 5400, 6023, -1, 5403, 5400, 6022, -1, 6023, 5395, 6024, -1, 5400, 5395, 6023, -1, 6024, 5388, 6025, -1, 5395, 5388, 6024, -1, 6025, 5373, 6026, -1, 5388, 5373, 6025, -1, 6026, 5374, 6027, -1, 5373, 5374, 6026, -1, 6027, 5362, 5872, -1, 5374, 5362, 6027, -1, 5346, 5357, 5871, -1, 5871, 5357, 6028, -1, 6028, 5364, 6029, -1, 5357, 5364, 6028, -1, 6029, 5372, 6030, -1, 5364, 5372, 6029, -1, 6030, 5376, 6031, -1, 5372, 5376, 6030, -1, 6031, 5381, 6032, -1, 5376, 5381, 6031, -1, 6032, 5387, 6033, -1, 5381, 5387, 6032, -1, 6033, 5390, 6034, -1, 5387, 5390, 6033, -1, 6034, 5396, 6035, -1, 5390, 5396, 6034, -1, 6035, 5482, 6036, -1, 5396, 5482, 6035, -1, 6036, 5466, 6037, -1, 5482, 5466, 6036, -1, 6037, 5450, 6038, -1, 5466, 5450, 6037, -1, 6038, 5432, 6039, -1, 5450, 5432, 6038, -1, 6039, 5434, 5858, -1, 5432, 5434, 6039, -1, 5610, 5617, 5857, -1, 5857, 5617, 6040, -1, 6040, 5625, 6041, -1, 5617, 5625, 6040, -1, 6041, 5631, 6042, -1, 5625, 5631, 6041, -1, 6042, 5635, 6043, -1, 5631, 5635, 6042, -1, 6043, 5639, 6044, -1, 5635, 5639, 6043, -1, 6044, 5645, 6045, -1, 5639, 5645, 6044, -1, 6045, 5651, 6046, -1, 5645, 5651, 6045, -1, 6046, 5712, 6047, -1, 5651, 5712, 6046, -1, 6047, 5707, 6048, -1, 5712, 5707, 6047, -1, 6048, 5700, 6049, -1, 5707, 5700, 6048, -1, 6049, 5695, 6050, -1, 5700, 5695, 6049, -1, 6050, 5680, 6051, -1, 5695, 5680, 6050, -1, 6051, 5682, 5844, -1, 5680, 5682, 6051, -1, 5681, 5685, 5843, -1, 5843, 5685, 6052, -1, 6052, 5696, 6053, -1, 5685, 5696, 6052, -1, 6053, 5701, 6054, -1, 5696, 5701, 6053, -1, 6054, 5706, 6055, -1, 5701, 5706, 6054, -1, 6055, 5713, 6056, -1, 5706, 5713, 6055, -1, 6056, 5718, 6057, -1, 5713, 5718, 6056, -1, 6057, 5397, 6058, -1, 5718, 5397, 6057, -1, 6058, 5389, 6059, -1, 5397, 5389, 6058, -1, 6059, 5377, 6060, -1, 5389, 5377, 6059, -1, 6060, 5378, 6061, -1, 5377, 5378, 6060, -1, 6061, 5371, 6062, -1, 5378, 5371, 6061, -1, 6062, 5349, 6063, -1, 5371, 5349, 6062, -1, 6063, 5350, 5830, -1, 5349, 5350, 6063, -1, 5561, 5567, 5829, -1, 5829, 5567, 6064, -1, 6064, 5572, 6065, -1, 5567, 5572, 6064, -1, 6065, 5578, 6066, -1, 5572, 5578, 6065, -1, 6066, 5582, 6067, -1, 5578, 5582, 6066, -1, 6067, 5588, 6068, -1, 5582, 5588, 6067, -1, 6068, 5491, 6069, -1, 5588, 5491, 6068, -1, 6069, 5490, 6070, -1, 5491, 5490, 6069, -1, 6070, 5656, 6071, -1, 5490, 5656, 6070, -1, 6071, 5654, 6072, -1, 5656, 5654, 6071, -1, 6072, 5649, 6073, -1, 5654, 5649, 6072, -1, 6073, 5642, 6074, -1, 5649, 5642, 6073, -1, 6074, 5637, 6075, -1, 5642, 5637, 6074, -1, 6075, 5632, 5816, -1, 5637, 5632, 6075, -1, 5628, 5634, 5815, -1, 5815, 5634, 6076, -1, 6076, 5640, 6077, -1, 5634, 5640, 6076, -1, 6077, 5647, 6078, -1, 5640, 5647, 6077, -1, 6078, 5652, 6079, -1, 5647, 5652, 6078, -1, 6079, 5657, 6080, -1, 5652, 5657, 6079, -1, 6080, 5489, 6081, -1, 5657, 5489, 6080, -1, 6081, 5487, 6082, -1, 5489, 5487, 6081, -1, 6082, 5725, 6083, -1, 5487, 5725, 6082, -1, 6083, 5721, 6084, -1, 5725, 5721, 6083, -1, 6084, 5717, 6085, -1, 5721, 5717, 6084, -1, 6085, 5709, 6086, -1, 5717, 5709, 6085, -1, 6086, 5703, 6087, -1, 5709, 5703, 6086, -1, 6087, 5697, 5802, -1, 5703, 5697, 6087, -1, 5481, 5488, 5801, -1, 5801, 5488, 6088, -1, 6088, 5504, 6089, -1, 5488, 5504, 6088, -1, 6089, 5513, 6090, -1, 5504, 5513, 6089, -1, 6090, 5514, 6091, -1, 5513, 5514, 6090, -1, 6091, 5518, 6092, -1, 5514, 5518, 6091, -1, 6092, 5484, 6093, -1, 5518, 5484, 6092, -1, 6093, 5585, 6094, -1, 5484, 5585, 6093, -1, 6094, 5587, 6095, -1, 5585, 5587, 6094, -1, 6095, 5579, 6096, -1, 5587, 5579, 6095, -1, 6096, 5573, 6097, -1, 5579, 5573, 6096, -1, 6097, 5568, 6098, -1, 5573, 5568, 6097, -1, 6098, 5563, 6099, -1, 5568, 5563, 6098, -1, 6099, 5555, 5788, -1, 5563, 5555, 6099, -1, 5564, 5569, 5787, -1, 5787, 5569, 6100, -1, 6100, 5574, 6101, -1, 5569, 5574, 6100, -1, 6101, 5580, 6102, -1, 5574, 5580, 6101, -1, 6102, 5583, 6103, -1, 5580, 5583, 6102, -1, 6103, 5586, 6104, -1, 5583, 5586, 6103, -1, 6104, 5590, 6105, -1, 5586, 5590, 6104, -1, 6105, 5666, 6106, -1, 5590, 5666, 6105, -1, 6106, 5660, 6107, -1, 5666, 5660, 6106, -1, 6107, 5658, 6108, -1, 5660, 5658, 6107, -1, 6108, 5653, 6109, -1, 5658, 5653, 6108, -1, 6109, 5648, 6110, -1, 5653, 5648, 6109, -1, 6110, 5643, 6111, -1, 5648, 5643, 6110, -1, 6111, 5644, 5774, -1, 5643, 5644, 6111, -1, 5379, 5383, 5773, -1, 5773, 5383, 6112, -1, 6112, 5391, 6113, -1, 5383, 5391, 6112, -1, 6113, 5398, 6114, -1, 5391, 5398, 6113, -1, 6114, 5402, 6115, -1, 5398, 5402, 6114, -1, 6115, 5409, 6116, -1, 5402, 5409, 6115, -1, 6116, 5469, 6117, -1, 5409, 5469, 6116, -1, 6117, 5471, 6118, -1, 5469, 5471, 6117, -1, 6118, 5472, 6119, -1, 5471, 5472, 6118, -1, 6119, 5473, 6120, -1, 5472, 5473, 6119, -1, 6120, 5474, 6121, -1, 5473, 5474, 6120, -1, 6121, 5475, 6122, -1, 5474, 5475, 6121, -1, 6122, 5476, 6123, -1, 5475, 5476, 6122, -1, 6123, 5452, 5760, -1, 5476, 5452, 6123, -1, 5347, 5363, 5759, -1, 5759, 5363, 6124, -1, 6124, 5367, 6125, -1, 5363, 5367, 6124, -1, 6125, 5375, 6126, -1, 5367, 5375, 6125, -1, 6126, 5382, 6127, -1, 5375, 5382, 6126, -1, 6127, 5386, 6128, -1, 5382, 5386, 6127, -1, 6128, 5393, 6129, -1, 5386, 5393, 6128, -1, 6129, 5497, 6130, -1, 5393, 5497, 6129, -1, 6130, 5511, 6131, -1, 5497, 5511, 6130, -1, 6131, 5507, 6132, -1, 5511, 5507, 6131, -1, 6132, 5509, 6133, -1, 5507, 5509, 6132, -1, 6133, 5495, 6134, -1, 5509, 5495, 6133, -1, 6134, 5457, 6135, -1, 5495, 5457, 6134, -1, 6135, 5459, 5746, -1, 5457, 5459, 6135, -1, 5360, 5370, 5745, -1, 5745, 5370, 6136, -1, 6136, 5380, 6137, -1, 5370, 5380, 6136, -1, 6137, 5385, 6138, -1, 5380, 5385, 6137, -1, 6138, 5394, 6139, -1, 5385, 5394, 6138, -1, 6139, 5401, 6140, -1, 5394, 5401, 6139, -1, 6140, 5404, 6141, -1, 5401, 5404, 6140, -1, 6141, 5485, 6142, -1, 5404, 5485, 6141, -1, 6142, 5515, 6143, -1, 5485, 5515, 6142, -1, 6143, 5516, 6144, -1, 5515, 5516, 6143, -1, 6144, 5503, 6145, -1, 5516, 5503, 6144, -1, 6145, 5505, 6146, -1, 5503, 5505, 6145, -1, 6146, 5498, 6147, -1, 5505, 5498, 6146, -1, 6147, 5463, 5732, -1, 5498, 5463, 6147, -1, 5742, 5739, 5741, -1, 5741, 5739, 5740, -1, 5745, 6136, 5744, -1, 5744, 6137, 5743, -1, 6136, 6137, 5744, -1, 5738, 5736, 5737, -1, 5743, 6138, 5742, -1, 6137, 6138, 5743, -1, 5739, 5735, 5738, -1, 5742, 5735, 5739, -1, 5738, 5735, 5736, -1, 6140, 6141, 6139, -1, 6139, 6141, 6138, -1, 5733, 6147, 5732, -1, 5734, 6146, 5733, -1, 5733, 6146, 6147, -1, 6143, 6144, 6142, -1, 5735, 6145, 5734, -1, 6142, 6145, 6141, -1, 6138, 6145, 5742, -1, 5742, 6145, 5735, -1, 6144, 6145, 6142, -1, 6141, 6145, 6138, -1, 5734, 6145, 6146, -1, 5756, 5753, 5755, -1, 5755, 5753, 5754, -1, 5759, 6124, 5758, -1, 5758, 6125, 5757, -1, 6124, 6125, 5758, -1, 5752, 5750, 5751, -1, 5757, 6126, 5756, -1, 6125, 6126, 5757, -1, 6128, 6129, 6127, -1, 6127, 6129, 6126, -1, 5753, 5746, 5752, -1, 5750, 5746, 5749, -1, 5749, 5746, 5748, -1, 5748, 5746, 5747, -1, 6126, 5746, 5756, -1, 5756, 5746, 5753, -1, 5752, 5746, 5750, -1, 6129, 5746, 6126, -1, 6129, 6130, 5746, -1, 5746, 6134, 6135, -1, 6131, 6132, 6130, -1, 6130, 6132, 5746, -1, 6132, 6133, 5746, -1, 5746, 6133, 6134, -1, 5770, 5768, 5769, -1, 5770, 5767, 5768, -1, 5772, 5773, 5771, -1, 6112, 6113, 5773, -1, 5773, 6113, 5771, -1, 5771, 6114, 5770, -1, 6113, 6114, 5771, -1, 5767, 5763, 5766, -1, 5766, 5763, 5765, -1, 5765, 5763, 5764, -1, 5770, 5763, 5767, -1, 6115, 6116, 6114, -1, 6116, 6117, 6114, -1, 5762, 5760, 5761, -1, 5760, 6122, 6123, -1, 5762, 6122, 5760, -1, 5763, 6121, 5762, -1, 6120, 6121, 6119, -1, 6119, 6121, 6118, -1, 6118, 6121, 6117, -1, 6114, 6121, 5770, -1, 5770, 6121, 5763, -1, 6117, 6121, 6114, -1, 5762, 6121, 6122, -1, 5783, 5781, 5782, -1, 5786, 5787, 5785, -1, 6100, 6101, 5787, -1, 5787, 6101, 5785, -1, 5780, 5778, 5779, -1, 6104, 6105, 6103, -1, 5785, 5774, 5784, -1, 5784, 5774, 5783, -1, 5781, 5774, 5780, -1, 5778, 5774, 5777, -1, 5777, 5774, 5776, -1, 5776, 5774, 5775, -1, 6103, 5774, 6102, -1, 6102, 5774, 6101, -1, 5783, 5774, 5781, -1, 5780, 5774, 5778, -1, 6101, 5774, 5785, -1, 6105, 5774, 6103, -1, 6105, 6106, 5774, -1, 5774, 6110, 6111, -1, 6107, 6108, 6106, -1, 6106, 6108, 5774, -1, 6108, 6109, 5774, -1, 5774, 6109, 6110, -1, 5797, 5795, 5796, -1, 5800, 5801, 5799, -1, 6088, 6089, 5801, -1, 5801, 6089, 5799, -1, 5795, 5792, 5794, -1, 5794, 5792, 5793, -1, 5797, 5792, 5795, -1, 5798, 5791, 5797, -1, 5797, 5791, 5792, -1, 5799, 5790, 5798, -1, 5798, 5790, 5791, -1, 6092, 6093, 6091, -1, 5790, 5788, 5789, -1, 5788, 6098, 6099, -1, 6089, 6098, 5799, -1, 5799, 6098, 5790, -1, 5790, 6098, 5788, -1, 6095, 6096, 6094, -1, 6094, 6096, 6093, -1, 6093, 6096, 6091, -1, 6091, 6097, 6090, -1, 6090, 6097, 6089, -1, 6089, 6097, 6098, -1, 6096, 6097, 6091, -1, 5812, 5809, 5811, -1, 5811, 5809, 5810, -1, 5815, 6076, 5814, -1, 5814, 6077, 5813, -1, 6076, 6077, 5814, -1, 5808, 5806, 5807, -1, 5813, 6078, 5812, -1, 6077, 6078, 5813, -1, 5809, 5805, 5808, -1, 5812, 5805, 5809, -1, 5808, 5805, 5806, -1, 6080, 6081, 6079, -1, 6079, 6081, 6078, -1, 5803, 6087, 5802, -1, 5804, 6086, 5803, -1, 5803, 6086, 6087, -1, 6083, 6084, 6082, -1, 5805, 6085, 5804, -1, 6082, 6085, 6081, -1, 6078, 6085, 5812, -1, 5812, 6085, 5805, -1, 6084, 6085, 6082, -1, 6081, 6085, 6078, -1, 5804, 6085, 6086, -1, 5826, 5823, 5825, -1, 5825, 5823, 5824, -1, 5829, 6064, 5828, -1, 5828, 6065, 5827, -1, 6064, 6065, 5828, -1, 5822, 5820, 5821, -1, 5827, 6066, 5826, -1, 6065, 6066, 5827, -1, 5823, 5819, 5822, -1, 5826, 5819, 5823, -1, 5822, 5819, 5820, -1, 6068, 6069, 6067, -1, 6067, 6069, 6066, -1, 5817, 6075, 5816, -1, 5818, 6074, 5817, -1, 5817, 6074, 6075, -1, 6071, 6072, 6070, -1, 5819, 6073, 5818, -1, 6070, 6073, 6069, -1, 6066, 6073, 5826, -1, 5826, 6073, 5819, -1, 6072, 6073, 6070, -1, 6069, 6073, 6066, -1, 5818, 6073, 6074, -1, 5840, 5838, 5839, -1, 5841, 5842, 5840, -1, 5840, 5837, 5838, -1, 5843, 6052, 5842, -1, 6053, 6054, 6052, -1, 5835, 5833, 5834, -1, 6055, 6056, 6054, -1, 6056, 6057, 6054, -1, 5837, 5830, 5836, -1, 5836, 5830, 5835, -1, 5833, 5830, 5832, -1, 5832, 5830, 5831, -1, 6052, 5830, 5842, -1, 5842, 5830, 5840, -1, 5840, 5830, 5837, -1, 6054, 5830, 6052, -1, 5835, 5830, 5833, -1, 6057, 5830, 6054, -1, 6057, 6058, 5830, -1, 6058, 6059, 5830, -1, 5830, 6062, 6063, -1, 6060, 6061, 6059, -1, 6059, 6061, 5830, -1, 5830, 6061, 6062, -1, 5854, 5852, 5853, -1, 5855, 5856, 5854, -1, 5854, 5851, 5852, -1, 5857, 6040, 5856, -1, 6041, 6042, 6040, -1, 5849, 5847, 5848, -1, 6043, 6044, 6042, -1, 6044, 6045, 6042, -1, 5851, 5844, 5850, -1, 5850, 5844, 5849, -1, 5847, 5844, 5846, -1, 5846, 5844, 5845, -1, 6040, 5844, 5856, -1, 5856, 5844, 5854, -1, 5854, 5844, 5851, -1, 6042, 5844, 6040, -1, 5849, 5844, 5847, -1, 6045, 5844, 6042, -1, 6045, 6046, 5844, -1, 6046, 6047, 5844, -1, 5844, 6050, 6051, -1, 6048, 6049, 6047, -1, 6047, 6049, 5844, -1, 5844, 6049, 6050, -1, 5868, 5866, 5867, -1, 5869, 5870, 5868, -1, 5868, 5865, 5866, -1, 5870, 5865, 5868, -1, 5871, 6028, 5870, -1, 6029, 6030, 6028, -1, 5864, 5861, 5863, -1, 5863, 5861, 5862, -1, 6031, 6032, 6030, -1, 5865, 5859, 5864, -1, 5861, 5859, 5860, -1, 5870, 5859, 5865, -1, 5864, 5859, 5861, -1, 6030, 6033, 6028, -1, 6032, 6033, 6030, -1, 5859, 6039, 5858, -1, 6034, 6039, 6033, -1, 6028, 6039, 5870, -1, 5870, 6039, 5859, -1, 6033, 6039, 6028, -1, 6039, 6037, 6038, -1, 6036, 6037, 6035, -1, 6035, 6037, 6034, -1, 6034, 6037, 6039, -1, 5882, 5879, 5881, -1, 5881, 5879, 5880, -1, 5885, 6016, 5884, -1, 5884, 6017, 5883, -1, 6016, 6017, 5884, -1, 5878, 5876, 5877, -1, 5883, 6018, 5882, -1, 6017, 6018, 5883, -1, 5879, 5875, 5878, -1, 5882, 5875, 5879, -1, 5878, 5875, 5876, -1, 6020, 6021, 6019, -1, 6019, 6021, 6018, -1, 5873, 6027, 5872, -1, 5874, 6026, 5873, -1, 5873, 6026, 6027, -1, 6023, 6024, 6022, -1, 5875, 6025, 5874, -1, 6022, 6025, 6021, -1, 6018, 6025, 5882, -1, 5882, 6025, 5875, -1, 6024, 6025, 6022, -1, 6021, 6025, 6018, -1, 5874, 6025, 6026, -1, 5896, 5893, 5895, -1, 5895, 5893, 5894, -1, 5899, 6004, 5898, -1, 5898, 6005, 5897, -1, 6004, 6005, 5898, -1, 5892, 5890, 5891, -1, 5897, 6006, 5896, -1, 6005, 6006, 5897, -1, 5893, 5889, 5892, -1, 5896, 5889, 5893, -1, 5892, 5889, 5890, -1, 6008, 6009, 6007, -1, 6007, 6009, 6006, -1, 5887, 6015, 5886, -1, 5888, 6014, 5887, -1, 5887, 6014, 6015, -1, 6011, 6012, 6010, -1, 5889, 6013, 5888, -1, 6010, 6013, 6009, -1, 6006, 6013, 5896, -1, 5896, 6013, 5889, -1, 6012, 6013, 6010, -1, 6009, 6013, 6006, -1, 5888, 6013, 6014, -1, 5903, 5902, 5904, -1, 5902, 5901, 5904, -1, 5904, 5907, 5905, -1, 5905, 5907, 5906, -1, 5900, 6003, 5901, -1, 5907, 5909, 5908, -1, 5904, 5909, 5907, -1, 6001, 6000, 6002, -1, 6002, 6000, 6003, -1, 5909, 5911, 5910, -1, 5901, 5912, 5904, -1, 5904, 5912, 5909, -1, 5909, 5912, 5911, -1, 5912, 5992, 5913, -1, 6003, 5992, 5901, -1, 5901, 5992, 5912, -1, 5997, 5996, 5998, -1, 5992, 5995, 5993, -1, 5998, 5995, 5999, -1, 5999, 5995, 6000, -1, 6000, 5995, 6003, -1, 6003, 5995, 5992, -1, 5996, 5995, 5998, -1, 5995, 5994, 5993, -1, 5917, 5916, 5918, -1, 5916, 5915, 5918, -1, 5918, 5921, 5919, -1, 5919, 5921, 5920, -1, 5914, 5991, 5915, -1, 5921, 5923, 5922, -1, 5918, 5923, 5921, -1, 5989, 5988, 5990, -1, 5990, 5988, 5991, -1, 5923, 5925, 5924, -1, 5915, 5926, 5918, -1, 5918, 5926, 5923, -1, 5923, 5926, 5925, -1, 5926, 5980, 5927, -1, 5991, 5980, 5915, -1, 5915, 5980, 5926, -1, 5985, 5984, 5986, -1, 5980, 5983, 5981, -1, 5986, 5983, 5987, -1, 5987, 5983, 5988, -1, 5988, 5983, 5991, -1, 5991, 5983, 5980, -1, 5984, 5983, 5986, -1, 5983, 5982, 5981, -1, 5930, 5933, 5931, -1, 5931, 5933, 5932, -1, 5929, 5928, 5930, -1, 5933, 5936, 5934, -1, 5934, 5936, 5935, -1, 5979, 5978, 5928, -1, 5936, 5938, 5937, -1, 5930, 5939, 5933, -1, 5933, 5939, 5936, -1, 5936, 5939, 5938, -1, 5976, 5975, 5977, -1, 5977, 5975, 5978, -1, 5930, 5940, 5939, -1, 5928, 5941, 5930, -1, 5978, 5941, 5928, -1, 5930, 5941, 5940, -1, 5978, 5968, 5941, -1, 5973, 5972, 5974, -1, 5974, 5972, 5975, -1, 5975, 5969, 5978, -1, 5972, 5969, 5975, -1, 5978, 5969, 5968, -1, 5971, 5970, 5972, -1, 5972, 5970, 5969, -1, 5944, 5947, 5945, -1, 5945, 5947, 5946, -1, 5947, 5950, 5948, -1, 5948, 5950, 5949, -1, 5950, 5952, 5951, -1, 5944, 5953, 5947, -1, 5947, 5953, 5950, -1, 5950, 5953, 5952, -1, 5964, 5963, 5965, -1, 5965, 5963, 5966, -1, 5942, 5954, 5943, -1, 5943, 5954, 5944, -1, 5944, 5954, 5953, -1, 5967, 5956, 5942, -1, 5954, 5956, 5955, -1, 5942, 5956, 5954, -1, 5961, 5960, 5962, -1, 5962, 5960, 5963, -1, 5966, 5957, 5967, -1, 5963, 5957, 5966, -1, 5967, 5957, 5956, -1, 5960, 5957, 5963, -1, 5959, 5958, 5960, -1, 5960, 5958, 5957, -1, 6148, 3175, 3178, -1, 6148, 3178, 6149, -1, 6150, 6149, 6151, -1, 6150, 6148, 6149, -1, 6152, 6151, 6153, -1, 6152, 6150, 6151, -1, 6154, 6153, 6155, -1, 6154, 6152, 6153, -1, 6156, 6155, 6157, -1, 6156, 6154, 6155, -1, 3414, 6148, 6150, -1, 3177, 3175, 6148, -1, 3177, 6148, 3414, -1, 3422, 6158, 6159, -1, 3422, 6159, 6160, -1, 3422, 6160, 6161, -1, 6162, 3422, 6161, -1, 6163, 3422, 6162, -1, 6164, 3422, 6163, -1, 6165, 3422, 6164, -1, 6166, 6167, 6168, -1, 6169, 6167, 6166, -1, 3095, 6167, 6169, -1, 3095, 3422, 6165, -1, 3095, 6165, 6167, -1, 3422, 3414, 6150, -1, 3422, 6150, 6152, -1, 3422, 6152, 6154, -1, 3422, 6154, 6156, -1, 3422, 6156, 6158, -1, 6167, 6170, 6171, -1, 6168, 6171, 6172, -1, 6168, 6167, 6171, -1, 6166, 6172, 6173, -1, 6166, 6168, 6172, -1, 6169, 6173, 3102, -1, 6169, 6166, 6173, -1, 3095, 3102, 3101, -1, 3095, 6169, 3102, -1, 3096, 3095, 3101, -1, 3098, 3101, 3099, -1, 3098, 3096, 3101, -1, 3048, 3099, 3032, -1, 3048, 3098, 3099, -1, 3675, 6174, 6175, -1, 3675, 6175, 6176, -1, 3675, 6176, 6177, -1, 6178, 3675, 6177, -1, 6179, 6174, 3675, -1, 6180, 3675, 6178, -1, 6181, 6179, 3675, -1, 6172, 6171, 6170, -1, 6149, 3667, 6151, -1, 3102, 6173, 6172, -1, 3102, 6172, 6170, -1, 3206, 3667, 6149, -1, 3178, 3206, 6149, -1, 3667, 3675, 6151, -1, 6151, 3675, 6153, -1, 6153, 3675, 6155, -1, 6155, 3675, 6157, -1, 6157, 3675, 6180, -1, 3675, 3102, 6170, -1, 3675, 6170, 6181, -1, 6182, 6183, 6184, -1, 6185, 6186, 6187, -1, 6188, 6186, 6185, -1, 6189, 6186, 6188, -1, 6190, 6183, 6191, -1, 6192, 6193, 6194, -1, 6191, 6183, 6182, -1, 6195, 6196, 6197, -1, 6193, 6198, 6194, -1, 6199, 6200, 6181, -1, 6201, 6202, 6203, -1, 6194, 6198, 6204, -1, 6205, 6196, 6195, -1, 6181, 6206, 6199, -1, 6190, 6207, 6183, -1, 6192, 6208, 6193, -1, 6187, 6209, 6181, -1, 6200, 6210, 6181, -1, 6211, 6208, 6192, -1, 6186, 6209, 6187, -1, 6181, 6212, 6206, -1, 6198, 6213, 6204, -1, 6190, 6214, 6207, -1, 6204, 6213, 6215, -1, 6210, 6216, 6181, -1, 6217, 6218, 6219, -1, 6219, 6218, 6205, -1, 6181, 6220, 6212, -1, 6221, 6214, 6222, -1, 6205, 6218, 6196, -1, 6170, 6220, 6181, -1, 6222, 6214, 6190, -1, 6223, 6224, 6211, -1, 6211, 6224, 6208, -1, 6216, 6225, 6181, -1, 6170, 6226, 6220, -1, 6217, 6227, 6218, -1, 6221, 6228, 6214, -1, 6225, 6229, 6181, -1, 6223, 6230, 6224, -1, 6170, 6231, 6226, -1, 6217, 6232, 6227, -1, 6221, 6233, 6228, -1, 6234, 6232, 6235, -1, 6235, 6232, 6217, -1, 6170, 6236, 6231, -1, 6237, 6233, 6221, -1, 6234, 6238, 6232, -1, 6223, 6239, 6230, -1, 6240, 6239, 6223, -1, 6237, 6241, 6233, -1, 6170, 6242, 6236, -1, 6243, 6241, 6244, -1, 6244, 6241, 6237, -1, 6240, 6245, 6239, -1, 6234, 6246, 6238, -1, 6170, 6247, 6242, -1, 6248, 6246, 6249, -1, 6249, 6246, 6234, -1, 6250, 6245, 6240, -1, 6251, 6252, 6243, -1, 6243, 6252, 6241, -1, 6248, 6253, 6246, -1, 6250, 6254, 6245, -1, 6170, 6255, 6247, -1, 6256, 6254, 6250, -1, 6251, 6257, 6252, -1, 6258, 6259, 6256, -1, 6256, 6259, 6254, -1, 6260, 6261, 6258, -1, 6258, 6261, 6259, -1, 6170, 6262, 6255, -1, 6170, 6263, 6262, -1, 6264, 6265, 6266, -1, 6266, 6265, 6267, -1, 6268, 6265, 6264, -1, 6269, 6270, 6264, -1, 6271, 6272, 6273, -1, 6264, 6270, 6268, -1, 6274, 6275, 6276, -1, 6273, 6277, 6229, -1, 6265, 6278, 6267, -1, 6272, 6277, 6273, -1, 6275, 6279, 6276, -1, 6280, 6281, 6271, -1, 6282, 6283, 6284, -1, 6284, 6283, 6269, -1, 6271, 6281, 6272, -1, 6285, 6286, 6287, -1, 6269, 6283, 6270, -1, 6287, 6286, 6274, -1, 6213, 6165, 6215, -1, 6229, 6288, 6181, -1, 6289, 6165, 6290, -1, 6274, 6286, 6275, -1, 6267, 6291, 6209, -1, 6292, 6165, 6181, -1, 6276, 6293, 6294, -1, 6277, 6288, 6229, -1, 6295, 6165, 6289, -1, 6296, 6165, 6292, -1, 6202, 6165, 6203, -1, 6279, 6293, 6276, -1, 6278, 6291, 6267, -1, 6297, 6165, 6296, -1, 6209, 6291, 6181, -1, 6203, 6165, 6298, -1, 6299, 6300, 6280, -1, 6301, 6165, 6295, -1, 6215, 6165, 6301, -1, 6280, 6300, 6281, -1, 6302, 6165, 6303, -1, 6303, 6165, 6304, -1, 6285, 6305, 6286, -1, 6282, 6306, 6283, -1, 6304, 6165, 6307, -1, 6307, 6165, 6308, -1, 6308, 6165, 6309, -1, 6288, 6310, 6181, -1, 6309, 6165, 6311, -1, 6294, 6312, 6313, -1, 6298, 6165, 6297, -1, 6311, 6165, 6314, -1, 6314, 6165, 6213, -1, 6291, 6315, 6181, -1, 6290, 6165, 6202, -1, 6316, 6167, 6260, -1, 6317, 6318, 6319, -1, 6320, 6167, 6316, -1, 6319, 6318, 6299, -1, 6260, 6167, 6261, -1, 6293, 6312, 6294, -1, 6299, 6318, 6300, -1, 6321, 6322, 6282, -1, 6261, 6167, 6323, -1, 6302, 6167, 6165, -1, 6282, 6322, 6306, -1, 6323, 6167, 6324, -1, 6324, 6167, 6325, -1, 6325, 6167, 6326, -1, 6327, 6328, 6285, -1, 6326, 6167, 6329, -1, 6310, 6330, 6181, -1, 6329, 6167, 6331, -1, 6285, 6328, 6305, -1, 6331, 6167, 6332, -1, 6332, 6167, 6302, -1, 6170, 6167, 6333, -1, 6333, 6167, 6334, -1, 6335, 6336, 6317, -1, 6334, 6167, 6337, -1, 6337, 6167, 6248, -1, 6248, 6167, 6253, -1, 6253, 6167, 6338, -1, 6317, 6336, 6318, -1, 6338, 6167, 6339, -1, 6339, 6167, 6340, -1, 6341, 6342, 6321, -1, 6340, 6167, 6343, -1, 6343, 6167, 6344, -1, 6321, 6342, 6322, -1, 6344, 6167, 6345, -1, 6345, 6167, 6346, -1, 6347, 6348, 6327, -1, 6346, 6167, 6349, -1, 6349, 6167, 6251, -1, 6251, 6167, 6257, -1, 6327, 6348, 6328, -1, 6257, 6167, 6350, -1, 6350, 6167, 6351, -1, 6352, 6353, 6335, -1, 6350, 6351, 6354, -1, 6351, 6167, 6355, -1, 6335, 6353, 6336, -1, 6355, 6167, 6320, -1, 6356, 6357, 6341, -1, 6358, 6359, 6347, -1, 6341, 6357, 6342, -1, 6347, 6359, 6348, -1, 6360, 6361, 6352, -1, 6352, 6361, 6353, -1, 6362, 6363, 6356, -1, 6356, 6363, 6357, -1, 6364, 6365, 6358, -1, 6358, 6365, 6359, -1, 6366, 6363, 6362, -1, 6263, 6367, 6360, -1, 6360, 6367, 6361, -1, 6368, 6369, 6364, -1, 6366, 6370, 6363, -1, 6263, 6371, 6367, -1, 6364, 6369, 6365, -1, 6338, 6370, 6366, -1, 6170, 6371, 6263, -1, 6350, 6372, 6373, -1, 6170, 6374, 6371, -1, 6368, 6372, 6369, -1, 6373, 6372, 6368, -1, 6338, 6339, 6370, -1, 6170, 6333, 6374, -1, 6350, 6354, 6372, -1, 6375, 6376, 6377, -1, 6378, 6379, 6380, -1, 6377, 6376, 6381, -1, 6382, 6379, 6378, -1, 6377, 6383, 6375, -1, 6384, 6383, 6377, -1, 6385, 6386, 6378, -1, 6378, 6386, 6382, -1, 6376, 6387, 6381, -1, 6388, 6389, 6390, -1, 6391, 6389, 6388, -1, 6380, 6392, 6393, -1, 6381, 6387, 6394, -1, 6379, 6392, 6380, -1, 6384, 6395, 6383, -1, 6385, 6396, 6386, -1, 6397, 6395, 6384, -1, 6398, 6399, 6388, -1, 6388, 6399, 6391, -1, 6400, 6396, 6385, -1, 6390, 6401, 6402, -1, 6389, 6401, 6390, -1, 6315, 6403, 6181, -1, 6387, 6404, 6394, -1, 6393, 6403, 6315, -1, 6392, 6403, 6393, -1, 6398, 6405, 6399, -1, 6330, 6404, 6181, -1, 6394, 6404, 6330, -1, 6397, 6406, 6395, -1, 6407, 6406, 6397, -1, 6408, 6405, 6398, -1, 6409, 6410, 6400, -1, 6400, 6410, 6396, -1, 6402, 6411, 6412, -1, 6401, 6411, 6402, -1, 6403, 6292, 6181, -1, 6404, 6187, 6181, -1, 6413, 6414, 6408, -1, 6415, 6416, 6409, -1, 6407, 6417, 6406, -1, 6418, 6417, 6407, -1, 6408, 6414, 6405, -1, 6409, 6416, 6410, -1, 6413, 6419, 6414, -1, 6420, 6419, 6413, -1, 6421, 6422, 6415, -1, 6423, 6424, 6418, -1, 6425, 6424, 6423, -1, 6415, 6422, 6416, -1, 6418, 6424, 6417, -1, 6426, 6427, 6420, -1, 6421, 6428, 6422, -1, 6420, 6427, 6419, -1, 6429, 6428, 6421, -1, 6430, 6431, 6425, -1, 6425, 6431, 6424, -1, 6426, 6432, 6427, -1, 6433, 6432, 6426, -1, 6430, 6434, 6431, -1, 6435, 6436, 6429, -1, 6429, 6436, 6428, -1, 6433, 6437, 6432, -1, 6430, 6438, 6434, -1, 6435, 6439, 6436, -1, 6440, 6438, 6430, -1, 6441, 6437, 6433, -1, 6442, 6439, 6435, -1, 6440, 6334, 6438, -1, 6333, 6334, 6440, -1, 6443, 6444, 6441, -1, 6441, 6444, 6437, -1, 6442, 6343, 6439, -1, 6340, 6343, 6442, -1, 6445, 6446, 6443, -1, 6443, 6446, 6444, -1, 6447, 6448, 6449, -1, 6449, 6450, 6451, -1, 6448, 6450, 6449, -1, 6452, 6453, 6447, -1, 6454, 6455, 6456, -1, 6456, 6455, 6457, -1, 6447, 6453, 6448, -1, 6456, 6458, 6454, -1, 6451, 6459, 6460, -1, 6450, 6459, 6451, -1, 6461, 6458, 6456, -1, 6462, 6463, 6452, -1, 6464, 6465, 6466, -1, 6455, 6467, 6457, -1, 6457, 6467, 6468, -1, 6452, 6463, 6453, -1, 6460, 6469, 6187, -1, 6465, 6470, 6466, -1, 6459, 6469, 6460, -1, 6466, 6470, 6471, -1, 6461, 6472, 6458, -1, 6473, 6472, 6461, -1, 6462, 6474, 6463, -1, 6468, 6296, 6292, -1, 6467, 6296, 6468, -1, 6469, 6475, 6187, -1, 6476, 6477, 6464, -1, 6464, 6477, 6465, -1, 6478, 6479, 6462, -1, 6480, 6481, 6473, -1, 6473, 6481, 6472, -1, 6462, 6479, 6474, -1, 6471, 6482, 6483, -1, 6470, 6482, 6471, -1, 6478, 6484, 6479, -1, 6485, 6484, 6478, -1, 6486, 6487, 6480, -1, 6480, 6487, 6481, -1, 6488, 6489, 6476, -1, 6476, 6489, 6477, -1, 6482, 6290, 6483, -1, 6312, 6290, 6313, -1, 6490, 6491, 6485, -1, 6411, 6290, 6412, -1, 6492, 6493, 6486, -1, 6485, 6491, 6484, -1, 6486, 6493, 6487, -1, 6313, 6290, 6202, -1, 6412, 6290, 6312, -1, 6483, 6290, 6411, -1, 6494, 6495, 6490, -1, 6488, 6496, 6489, -1, 6497, 6498, 6492, -1, 6490, 6495, 6491, -1, 6492, 6498, 6493, -1, 6499, 6496, 6500, -1, 6500, 6496, 6488, -1, 6494, 6501, 6495, -1, 6502, 6501, 6494, -1, 6503, 6504, 6497, -1, 6505, 6506, 6499, -1, 6497, 6504, 6498, -1, 6499, 6506, 6496, -1, 6337, 6507, 6502, -1, 6505, 6508, 6506, -1, 6502, 6507, 6501, -1, 6509, 6510, 6503, -1, 6503, 6510, 6504, -1, 6511, 6508, 6505, -1, 6337, 6512, 6507, -1, 6511, 6513, 6508, -1, 6344, 6345, 6509, -1, 6514, 6513, 6511, -1, 6509, 6345, 6510, -1, 6514, 6515, 6513, -1, 6516, 6515, 6514, -1, 6516, 6517, 6515, -1, 6518, 6519, 6520, -1, 6521, 6517, 6516, -1, 6520, 6519, 6522, -1, 6520, 6523, 6518, -1, 6521, 6351, 6517, -1, 6354, 6351, 6445, -1, 6446, 6351, 6521, -1, 6445, 6351, 6446, -1, 6524, 6523, 6520, -1, 6519, 6525, 6522, -1, 6526, 6527, 6528, -1, 6522, 6525, 6529, -1, 6530, 6527, 6526, -1, 6524, 6531, 6523, -1, 6532, 6533, 6526, -1, 6534, 6531, 6524, -1, 6526, 6533, 6530, -1, 6525, 6535, 6529, -1, 6528, 6536, 6537, -1, 6475, 6535, 6187, -1, 6529, 6535, 6475, -1, 6527, 6536, 6528, -1, 6534, 6538, 6531, -1, 6539, 6540, 6532, -1, 6541, 6538, 6534, -1, 6532, 6540, 6533, -1, 6535, 6185, 6187, -1, 6542, 6543, 6544, -1, 6545, 6543, 6542, -1, 6541, 6546, 6538, -1, 6537, 6298, 6297, -1, 6536, 6298, 6537, -1, 6544, 6547, 6548, -1, 6549, 6546, 6541, -1, 6543, 6547, 6544, -1, 6550, 6551, 6545, -1, 6552, 6553, 6539, -1, 6539, 6553, 6540, -1, 6549, 6554, 6546, -1, 6545, 6551, 6543, -1, 6548, 6555, 6289, -1, 6556, 6554, 6549, -1, 6547, 6555, 6548, -1, 6557, 6558, 6552, -1, 6552, 6558, 6553, -1, 6556, 6559, 6554, -1, 6550, 6560, 6551, -1, 6555, 6295, 6289, -1, 6561, 6559, 6556, -1, 6562, 6563, 6557, -1, 6564, 6565, 6550, -1, 6557, 6563, 6558, -1, 6561, 6566, 6559, -1, 6550, 6565, 6560, -1, 6567, 6566, 6561, -1, 6562, 6568, 6563, -1, 6569, 6568, 6562, -1, 6570, 6571, 6564, -1, 6572, 6571, 6570, -1, 6567, 6573, 6566, -1, 6564, 6571, 6565, -1, 6569, 6574, 6568, -1, 6575, 6573, 6567, -1, 6576, 6574, 6569, -1, 6337, 6577, 6512, -1, 6572, 6578, 6571, -1, 6579, 6578, 6572, -1, 6575, 6577, 6573, -1, 6576, 6580, 6574, -1, 6512, 6577, 6575, -1, 6581, 6580, 6576, -1, 6337, 6248, 6577, -1, 6582, 6583, 6579, -1, 6581, 6349, 6580, -1, 6579, 6583, 6578, -1, 6346, 6349, 6581, -1, 6584, 6585, 6582, -1, 6582, 6585, 6583, -1, 6355, 6586, 6584, -1, 6584, 6586, 6585, -1, 6355, 6320, 6586, -1, 6587, 6588, 6589, -1, 6590, 6588, 6587, -1, 6591, 6592, 6593, -1, 6593, 6592, 6594, -1, 6594, 6592, 6595, -1, 6596, 6597, 6587, -1, 6593, 6184, 6591, -1, 6587, 6597, 6590, -1, 6589, 6189, 6188, -1, 6588, 6189, 6589, -1, 6596, 6197, 6597, -1, 6182, 6184, 6593, -1, 6592, 6201, 6595, -1, 6595, 6201, 6203, -1, 6195, 6197, 6596, -1, 6327, 6285, 6598, -1, 6598, 6285, 6599, -1, 6599, 6287, 6600, -1, 6285, 6287, 6599, -1, 6600, 6274, 6601, -1, 6287, 6274, 6600, -1, 6601, 6276, 6602, -1, 6274, 6276, 6601, -1, 6602, 6294, 6603, -1, 6276, 6294, 6602, -1, 6603, 6313, 6604, -1, 6294, 6313, 6603, -1, 6604, 6202, 6605, -1, 6313, 6202, 6604, -1, 6605, 6201, 6606, -1, 6202, 6201, 6605, -1, 6606, 6592, 6607, -1, 6201, 6592, 6606, -1, 6607, 6591, 6608, -1, 6592, 6591, 6607, -1, 6608, 6184, 6609, -1, 6591, 6184, 6608, -1, 6609, 6183, 6610, -1, 6184, 6183, 6609, -1, 6610, 6207, 6611, -1, 6183, 6207, 6610, -1, 6282, 6284, 6612, -1, 6612, 6284, 6613, -1, 6613, 6269, 6614, -1, 6284, 6269, 6613, -1, 6614, 6264, 6615, -1, 6269, 6264, 6614, -1, 6615, 6266, 6616, -1, 6264, 6266, 6615, -1, 6616, 6267, 6617, -1, 6266, 6267, 6616, -1, 6617, 6209, 6618, -1, 6267, 6209, 6617, -1, 6618, 6186, 6619, -1, 6209, 6186, 6618, -1, 6619, 6189, 6620, -1, 6186, 6189, 6619, -1, 6620, 6588, 6621, -1, 6189, 6588, 6620, -1, 6621, 6590, 6622, -1, 6588, 6590, 6621, -1, 6622, 6597, 6623, -1, 6590, 6597, 6622, -1, 6623, 6197, 6624, -1, 6597, 6197, 6623, -1, 6624, 6196, 6625, -1, 6197, 6196, 6624, -1, 6413, 6408, 6626, -1, 6626, 6408, 6627, -1, 6627, 6398, 6628, -1, 6408, 6398, 6627, -1, 6628, 6388, 6629, -1, 6398, 6388, 6628, -1, 6629, 6390, 6630, -1, 6388, 6390, 6629, -1, 6630, 6402, 6631, -1, 6390, 6402, 6630, -1, 6631, 6412, 6632, -1, 6402, 6412, 6631, -1, 6632, 6312, 6633, -1, 6412, 6312, 6632, -1, 6633, 6293, 6634, -1, 6312, 6293, 6633, -1, 6634, 6279, 6635, -1, 6293, 6279, 6634, -1, 6635, 6275, 6636, -1, 6279, 6275, 6635, -1, 6636, 6286, 6637, -1, 6275, 6286, 6636, -1, 6637, 6305, 6638, -1, 6286, 6305, 6637, -1, 6638, 6328, 6639, -1, 6305, 6328, 6638, -1, 6500, 6488, 6640, -1, 6640, 6488, 6641, -1, 6641, 6476, 6642, -1, 6488, 6476, 6641, -1, 6642, 6464, 6643, -1, 6476, 6464, 6642, -1, 6643, 6466, 6644, -1, 6464, 6466, 6643, -1, 6644, 6471, 6645, -1, 6466, 6471, 6644, -1, 6645, 6483, 6646, -1, 6471, 6483, 6645, -1, 6646, 6411, 6647, -1, 6483, 6411, 6646, -1, 6647, 6401, 6648, -1, 6411, 6401, 6647, -1, 6648, 6389, 6649, -1, 6401, 6389, 6648, -1, 6649, 6391, 6650, -1, 6389, 6391, 6649, -1, 6650, 6399, 6651, -1, 6391, 6399, 6650, -1, 6651, 6405, 6652, -1, 6399, 6405, 6651, -1, 6652, 6414, 6653, -1, 6405, 6414, 6652, -1, 6302, 6303, 6654, -1, 6654, 6303, 6655, -1, 6655, 6304, 6656, -1, 6303, 6304, 6655, -1, 6656, 6307, 6657, -1, 6304, 6307, 6656, -1, 6657, 6308, 6658, -1, 6307, 6308, 6657, -1, 6658, 6309, 6659, -1, 6308, 6309, 6658, -1, 6659, 6311, 6660, -1, 6309, 6311, 6659, -1, 6660, 6314, 6661, -1, 6311, 6314, 6660, -1, 6661, 6213, 6662, -1, 6314, 6213, 6661, -1, 6662, 6198, 6663, -1, 6213, 6198, 6662, -1, 6663, 6193, 6664, -1, 6198, 6193, 6663, -1, 6664, 6208, 6665, -1, 6193, 6208, 6664, -1, 6665, 6224, 6666, -1, 6208, 6224, 6665, -1, 6666, 6230, 6667, -1, 6224, 6230, 6666, -1, 6480, 6473, 6668, -1, 6668, 6473, 6669, -1, 6669, 6461, 6670, -1, 6473, 6461, 6669, -1, 6670, 6456, 6671, -1, 6461, 6456, 6670, -1, 6671, 6457, 6672, -1, 6456, 6457, 6671, -1, 6672, 6468, 6673, -1, 6457, 6468, 6672, -1, 6673, 6292, 6674, -1, 6468, 6292, 6673, -1, 6674, 6403, 6675, -1, 6292, 6403, 6674, -1, 6675, 6392, 6676, -1, 6403, 6392, 6675, -1, 6676, 6379, 6677, -1, 6392, 6379, 6676, -1, 6677, 6382, 6678, -1, 6379, 6382, 6677, -1, 6678, 6386, 6679, -1, 6382, 6386, 6678, -1, 6679, 6396, 6680, -1, 6386, 6396, 6679, -1, 6680, 6410, 6681, -1, 6396, 6410, 6680, -1, 6552, 6539, 6682, -1, 6682, 6539, 6683, -1, 6683, 6532, 6684, -1, 6539, 6532, 6683, -1, 6684, 6526, 6685, -1, 6532, 6526, 6684, -1, 6685, 6528, 6686, -1, 6526, 6528, 6685, -1, 6686, 6537, 6687, -1, 6528, 6537, 6686, -1, 6687, 6297, 6688, -1, 6537, 6297, 6687, -1, 6688, 6296, 6689, -1, 6297, 6296, 6688, -1, 6689, 6467, 6690, -1, 6296, 6467, 6689, -1, 6690, 6455, 6691, -1, 6467, 6455, 6690, -1, 6691, 6454, 6692, -1, 6455, 6454, 6691, -1, 6692, 6458, 6693, -1, 6454, 6458, 6692, -1, 6693, 6472, 6694, -1, 6458, 6472, 6693, -1, 6694, 6481, 6695, -1, 6472, 6481, 6694, -1, 6205, 6195, 6696, -1, 6696, 6195, 6697, -1, 6697, 6596, 6698, -1, 6195, 6596, 6697, -1, 6698, 6587, 6699, -1, 6596, 6587, 6698, -1, 6699, 6589, 6700, -1, 6587, 6589, 6699, -1, 6700, 6188, 6701, -1, 6589, 6188, 6700, -1, 6701, 6185, 6702, -1, 6188, 6185, 6701, -1, 6702, 6535, 6703, -1, 6185, 6535, 6702, -1, 6703, 6525, 6704, -1, 6535, 6525, 6703, -1, 6704, 6519, 6705, -1, 6525, 6519, 6704, -1, 6705, 6518, 6706, -1, 6519, 6518, 6705, -1, 6706, 6523, 6707, -1, 6518, 6523, 6706, -1, 6707, 6531, 6708, -1, 6523, 6531, 6707, -1, 6708, 6538, 6709, -1, 6531, 6538, 6708, -1, 6541, 6534, 6710, -1, 6710, 6534, 6711, -1, 6711, 6524, 6712, -1, 6534, 6524, 6711, -1, 6712, 6520, 6713, -1, 6524, 6520, 6712, -1, 6713, 6522, 6714, -1, 6520, 6522, 6713, -1, 6714, 6529, 6715, -1, 6522, 6529, 6714, -1, 6715, 6475, 6716, -1, 6529, 6475, 6715, -1, 6716, 6469, 6717, -1, 6475, 6469, 6716, -1, 6717, 6459, 6718, -1, 6469, 6459, 6717, -1, 6718, 6450, 6719, -1, 6459, 6450, 6718, -1, 6719, 6448, 6720, -1, 6450, 6448, 6719, -1, 6720, 6453, 6721, -1, 6448, 6453, 6720, -1, 6721, 6463, 6722, -1, 6453, 6463, 6721, -1, 6722, 6474, 6723, -1, 6463, 6474, 6722, -1, 6319, 6299, 6724, -1, 6724, 6299, 6725, -1, 6725, 6280, 6726, -1, 6299, 6280, 6725, -1, 6726, 6271, 6727, -1, 6280, 6271, 6726, -1, 6727, 6273, 6728, -1, 6271, 6273, 6727, -1, 6728, 6229, 6729, -1, 6273, 6229, 6728, -1, 6729, 6225, 6730, -1, 6229, 6225, 6729, -1, 6730, 6216, 6731, -1, 6225, 6216, 6730, -1, 6731, 6210, 6732, -1, 6216, 6210, 6731, -1, 6732, 6200, 6733, -1, 6210, 6200, 6732, -1, 6733, 6199, 6734, -1, 6200, 6199, 6733, -1, 6734, 6206, 6735, -1, 6199, 6206, 6734, -1, 6735, 6212, 6736, -1, 6206, 6212, 6735, -1, 6736, 6220, 6737, -1, 6212, 6220, 6736, -1, 6409, 6400, 6738, -1, 6738, 6400, 6739, -1, 6739, 6385, 6740, -1, 6400, 6385, 6739, -1, 6740, 6378, 6741, -1, 6385, 6378, 6740, -1, 6741, 6380, 6742, -1, 6378, 6380, 6741, -1, 6742, 6393, 6743, -1, 6380, 6393, 6742, -1, 6743, 6315, 6744, -1, 6393, 6315, 6743, -1, 6744, 6291, 6745, -1, 6315, 6291, 6744, -1, 6745, 6278, 6746, -1, 6291, 6278, 6745, -1, 6746, 6265, 6747, -1, 6278, 6265, 6746, -1, 6747, 6268, 6748, -1, 6265, 6268, 6747, -1, 6748, 6270, 6749, -1, 6268, 6270, 6748, -1, 6749, 6283, 6750, -1, 6270, 6283, 6749, -1, 6750, 6306, 6751, -1, 6283, 6306, 6750, -1, 6190, 6191, 6752, -1, 6752, 6191, 6753, -1, 6753, 6182, 6754, -1, 6191, 6182, 6753, -1, 6754, 6593, 6755, -1, 6182, 6593, 6754, -1, 6755, 6594, 6756, -1, 6593, 6594, 6755, -1, 6756, 6595, 6757, -1, 6594, 6595, 6756, -1, 6757, 6203, 6758, -1, 6595, 6203, 6757, -1, 6758, 6298, 6759, -1, 6203, 6298, 6758, -1, 6759, 6536, 6760, -1, 6298, 6536, 6759, -1, 6760, 6527, 6761, -1, 6536, 6527, 6760, -1, 6761, 6530, 6762, -1, 6527, 6530, 6761, -1, 6762, 6533, 6763, -1, 6530, 6533, 6762, -1, 6763, 6540, 6764, -1, 6533, 6540, 6763, -1, 6764, 6553, 6765, -1, 6540, 6553, 6764, -1, 6223, 6211, 6766, -1, 6766, 6211, 6767, -1, 6767, 6192, 6768, -1, 6211, 6192, 6767, -1, 6768, 6194, 6769, -1, 6192, 6194, 6768, -1, 6769, 6204, 6770, -1, 6194, 6204, 6769, -1, 6770, 6215, 6771, -1, 6204, 6215, 6770, -1, 6771, 6301, 6772, -1, 6215, 6301, 6771, -1, 6772, 6295, 6773, -1, 6301, 6295, 6772, -1, 6773, 6555, 6774, -1, 6295, 6555, 6773, -1, 6774, 6547, 6775, -1, 6555, 6547, 6774, -1, 6775, 6543, 6776, -1, 6547, 6543, 6775, -1, 6776, 6551, 6777, -1, 6543, 6551, 6776, -1, 6777, 6560, 6778, -1, 6551, 6560, 6777, -1, 6778, 6565, 6779, -1, 6560, 6565, 6778, -1, 6564, 6550, 6780, -1, 6780, 6550, 6781, -1, 6781, 6545, 6782, -1, 6550, 6545, 6781, -1, 6782, 6542, 6783, -1, 6545, 6542, 6782, -1, 6783, 6544, 6784, -1, 6542, 6544, 6783, -1, 6784, 6548, 6785, -1, 6544, 6548, 6784, -1, 6785, 6289, 6786, -1, 6548, 6289, 6785, -1, 6786, 6290, 6787, -1, 6289, 6290, 6786, -1, 6787, 6482, 6788, -1, 6290, 6482, 6787, -1, 6788, 6470, 6789, -1, 6482, 6470, 6788, -1, 6789, 6465, 6790, -1, 6470, 6465, 6789, -1, 6790, 6477, 6791, -1, 6465, 6477, 6790, -1, 6791, 6489, 6792, -1, 6477, 6489, 6791, -1, 6792, 6496, 6793, -1, 6489, 6496, 6792, -1, 6462, 6452, 6794, -1, 6794, 6452, 6795, -1, 6795, 6447, 6796, -1, 6452, 6447, 6795, -1, 6796, 6449, 6797, -1, 6447, 6449, 6796, -1, 6797, 6451, 6798, -1, 6449, 6451, 6797, -1, 6798, 6460, 6799, -1, 6451, 6460, 6798, -1, 6799, 6187, 6800, -1, 6460, 6187, 6799, -1, 6800, 6404, 6801, -1, 6187, 6404, 6800, -1, 6801, 6387, 6802, -1, 6404, 6387, 6801, -1, 6802, 6376, 6803, -1, 6387, 6376, 6802, -1, 6803, 6375, 6804, -1, 6376, 6375, 6803, -1, 6804, 6383, 6805, -1, 6375, 6383, 6804, -1, 6805, 6395, 6806, -1, 6383, 6395, 6805, -1, 6806, 6406, 6807, -1, 6395, 6406, 6806, -1, 6407, 6397, 6808, -1, 6808, 6397, 6809, -1, 6809, 6384, 6810, -1, 6397, 6384, 6809, -1, 6810, 6377, 6811, -1, 6384, 6377, 6810, -1, 6811, 6381, 6812, -1, 6377, 6381, 6811, -1, 6812, 6394, 6813, -1, 6381, 6394, 6812, -1, 6813, 6330, 6814, -1, 6394, 6330, 6813, -1, 6814, 6310, 6815, -1, 6330, 6310, 6814, -1, 6815, 6288, 6816, -1, 6310, 6288, 6815, -1, 6816, 6277, 6817, -1, 6288, 6277, 6816, -1, 6817, 6272, 6818, -1, 6277, 6272, 6817, -1, 6818, 6281, 6819, -1, 6272, 6281, 6818, -1, 6819, 6300, 6820, -1, 6281, 6300, 6819, -1, 6820, 6318, 6821, -1, 6300, 6318, 6820, -1, 6159, 6158, 6180, -1, 6159, 6180, 6178, -1, 6160, 6178, 6177, -1, 6160, 6159, 6178, -1, 6161, 6177, 6176, -1, 6161, 6160, 6177, -1, 6162, 6176, 6175, -1, 6162, 6161, 6176, -1, 6163, 6175, 6174, -1, 6163, 6162, 6175, -1, 6164, 6174, 6179, -1, 6164, 6163, 6174, -1, 6165, 6179, 6181, -1, 6165, 6164, 6179, -1, 6156, 6180, 6158, -1, 6157, 6180, 6156, -1, 6318, 6336, 6821, -1, 6821, 6336, 6822, -1, 6822, 6353, 6823, -1, 6336, 6353, 6822, -1, 6823, 6361, 6824, -1, 6353, 6361, 6823, -1, 6824, 6367, 6825, -1, 6361, 6367, 6824, -1, 6825, 6371, 6826, -1, 6367, 6371, 6825, -1, 6826, 6374, 6827, -1, 6371, 6374, 6826, -1, 6827, 6333, 6828, -1, 6374, 6333, 6827, -1, 6828, 6440, 6829, -1, 6333, 6440, 6828, -1, 6829, 6430, 6830, -1, 6440, 6430, 6829, -1, 6830, 6425, 6831, -1, 6430, 6425, 6830, -1, 6831, 6423, 6832, -1, 6425, 6423, 6831, -1, 6832, 6418, 6833, -1, 6423, 6418, 6832, -1, 6833, 6407, 6808, -1, 6418, 6407, 6833, -1, 6406, 6417, 6807, -1, 6807, 6417, 6834, -1, 6834, 6424, 6835, -1, 6417, 6424, 6834, -1, 6835, 6431, 6836, -1, 6424, 6431, 6835, -1, 6836, 6434, 6837, -1, 6431, 6434, 6836, -1, 6837, 6438, 6838, -1, 6434, 6438, 6837, -1, 6838, 6334, 6839, -1, 6438, 6334, 6838, -1, 6839, 6337, 6840, -1, 6334, 6337, 6839, -1, 6840, 6502, 6841, -1, 6337, 6502, 6840, -1, 6841, 6494, 6842, -1, 6502, 6494, 6841, -1, 6842, 6490, 6843, -1, 6494, 6490, 6842, -1, 6843, 6485, 6844, -1, 6490, 6485, 6843, -1, 6844, 6478, 6845, -1, 6485, 6478, 6844, -1, 6845, 6462, 6794, -1, 6478, 6462, 6845, -1, 6496, 6506, 6793, -1, 6793, 6506, 6846, -1, 6846, 6508, 6847, -1, 6506, 6508, 6846, -1, 6847, 6513, 6848, -1, 6508, 6513, 6847, -1, 6848, 6515, 6849, -1, 6513, 6515, 6848, -1, 6849, 6517, 6850, -1, 6515, 6517, 6849, -1, 6850, 6351, 6851, -1, 6517, 6351, 6850, -1, 6851, 6355, 6852, -1, 6351, 6355, 6851, -1, 6852, 6584, 6853, -1, 6355, 6584, 6852, -1, 6853, 6582, 6854, -1, 6584, 6582, 6853, -1, 6854, 6579, 6855, -1, 6582, 6579, 6854, -1, 6855, 6572, 6856, -1, 6579, 6572, 6855, -1, 6856, 6570, 6857, -1, 6572, 6570, 6856, -1, 6857, 6564, 6780, -1, 6570, 6564, 6857, -1, 6565, 6571, 6779, -1, 6779, 6571, 6858, -1, 6858, 6578, 6859, -1, 6571, 6578, 6858, -1, 6859, 6583, 6860, -1, 6578, 6583, 6859, -1, 6860, 6585, 6861, -1, 6583, 6585, 6860, -1, 6861, 6586, 6862, -1, 6585, 6586, 6861, -1, 6862, 6320, 6863, -1, 6586, 6320, 6862, -1, 6863, 6316, 6864, -1, 6320, 6316, 6863, -1, 6864, 6260, 6865, -1, 6316, 6260, 6864, -1, 6865, 6258, 6866, -1, 6260, 6258, 6865, -1, 6866, 6256, 6867, -1, 6258, 6256, 6866, -1, 6867, 6250, 6868, -1, 6256, 6250, 6867, -1, 6868, 6240, 6869, -1, 6250, 6240, 6868, -1, 6869, 6223, 6766, -1, 6240, 6223, 6869, -1, 6553, 6558, 6765, -1, 6765, 6558, 6870, -1, 6870, 6563, 6871, -1, 6558, 6563, 6870, -1, 6871, 6568, 6872, -1, 6563, 6568, 6871, -1, 6872, 6574, 6873, -1, 6568, 6574, 6872, -1, 6873, 6580, 6874, -1, 6574, 6580, 6873, -1, 6874, 6349, 6875, -1, 6580, 6349, 6874, -1, 6875, 6251, 6876, -1, 6349, 6251, 6875, -1, 6876, 6243, 6877, -1, 6251, 6243, 6876, -1, 6877, 6244, 6878, -1, 6243, 6244, 6877, -1, 6878, 6237, 6879, -1, 6244, 6237, 6878, -1, 6879, 6221, 6880, -1, 6237, 6221, 6879, -1, 6880, 6222, 6881, -1, 6221, 6222, 6880, -1, 6881, 6190, 6752, -1, 6222, 6190, 6881, -1, 6306, 6322, 6751, -1, 6751, 6322, 6882, -1, 6882, 6342, 6883, -1, 6322, 6342, 6882, -1, 6883, 6357, 6884, -1, 6342, 6357, 6883, -1, 6884, 6363, 6885, -1, 6357, 6363, 6884, -1, 6885, 6370, 6886, -1, 6363, 6370, 6885, -1, 6886, 6339, 6887, -1, 6370, 6339, 6886, -1, 6887, 6340, 6888, -1, 6339, 6340, 6887, -1, 6888, 6442, 6889, -1, 6340, 6442, 6888, -1, 6889, 6435, 6890, -1, 6442, 6435, 6889, -1, 6890, 6429, 6891, -1, 6435, 6429, 6890, -1, 6891, 6421, 6892, -1, 6429, 6421, 6891, -1, 6892, 6415, 6893, -1, 6421, 6415, 6892, -1, 6893, 6409, 6738, -1, 6415, 6409, 6893, -1, 6220, 6226, 6737, -1, 6737, 6226, 6894, -1, 6894, 6231, 6895, -1, 6226, 6231, 6894, -1, 6895, 6236, 6896, -1, 6231, 6236, 6895, -1, 6896, 6242, 6897, -1, 6236, 6242, 6896, -1, 6897, 6247, 6898, -1, 6242, 6247, 6897, -1, 6898, 6255, 6899, -1, 6247, 6255, 6898, -1, 6899, 6262, 6900, -1, 6255, 6262, 6899, -1, 6900, 6263, 6901, -1, 6262, 6263, 6900, -1, 6901, 6360, 6902, -1, 6263, 6360, 6901, -1, 6902, 6352, 6903, -1, 6360, 6352, 6902, -1, 6903, 6335, 6904, -1, 6352, 6335, 6903, -1, 6904, 6317, 6905, -1, 6335, 6317, 6904, -1, 6905, 6319, 6724, -1, 6317, 6319, 6905, -1, 6474, 6479, 6723, -1, 6723, 6479, 6906, -1, 6906, 6484, 6907, -1, 6479, 6484, 6906, -1, 6907, 6491, 6908, -1, 6484, 6491, 6907, -1, 6908, 6495, 6909, -1, 6491, 6495, 6908, -1, 6909, 6501, 6910, -1, 6495, 6501, 6909, -1, 6910, 6507, 6911, -1, 6501, 6507, 6910, -1, 6911, 6512, 6912, -1, 6507, 6512, 6911, -1, 6912, 6575, 6913, -1, 6512, 6575, 6912, -1, 6913, 6567, 6914, -1, 6575, 6567, 6913, -1, 6914, 6561, 6915, -1, 6567, 6561, 6914, -1, 6915, 6556, 6916, -1, 6561, 6556, 6915, -1, 6916, 6549, 6917, -1, 6556, 6549, 6916, -1, 6917, 6541, 6710, -1, 6549, 6541, 6917, -1, 6538, 6546, 6709, -1, 6709, 6546, 6918, -1, 6918, 6554, 6919, -1, 6546, 6554, 6918, -1, 6919, 6559, 6920, -1, 6554, 6559, 6919, -1, 6920, 6566, 6921, -1, 6559, 6566, 6920, -1, 6921, 6573, 6922, -1, 6566, 6573, 6921, -1, 6922, 6577, 6923, -1, 6573, 6577, 6922, -1, 6923, 6248, 6924, -1, 6577, 6248, 6923, -1, 6924, 6249, 6925, -1, 6248, 6249, 6924, -1, 6925, 6234, 6926, -1, 6249, 6234, 6925, -1, 6926, 6235, 6927, -1, 6234, 6235, 6926, -1, 6927, 6217, 6928, -1, 6235, 6217, 6927, -1, 6928, 6219, 6929, -1, 6217, 6219, 6928, -1, 6929, 6205, 6696, -1, 6219, 6205, 6929, -1, 6481, 6487, 6695, -1, 6695, 6487, 6930, -1, 6930, 6493, 6931, -1, 6487, 6493, 6930, -1, 6931, 6498, 6932, -1, 6493, 6498, 6931, -1, 6932, 6504, 6933, -1, 6498, 6504, 6932, -1, 6933, 6510, 6934, -1, 6504, 6510, 6933, -1, 6934, 6345, 6935, -1, 6510, 6345, 6934, -1, 6935, 6346, 6936, -1, 6345, 6346, 6935, -1, 6936, 6581, 6937, -1, 6346, 6581, 6936, -1, 6937, 6576, 6938, -1, 6581, 6576, 6937, -1, 6938, 6569, 6939, -1, 6576, 6569, 6938, -1, 6939, 6562, 6940, -1, 6569, 6562, 6939, -1, 6940, 6557, 6941, -1, 6562, 6557, 6940, -1, 6941, 6552, 6682, -1, 6557, 6552, 6941, -1, 6410, 6416, 6681, -1, 6681, 6416, 6942, -1, 6942, 6422, 6943, -1, 6416, 6422, 6942, -1, 6943, 6428, 6944, -1, 6422, 6428, 6943, -1, 6944, 6436, 6945, -1, 6428, 6436, 6944, -1, 6945, 6439, 6946, -1, 6436, 6439, 6945, -1, 6946, 6343, 6947, -1, 6439, 6343, 6946, -1, 6947, 6344, 6948, -1, 6343, 6344, 6947, -1, 6948, 6509, 6949, -1, 6344, 6509, 6948, -1, 6949, 6503, 6950, -1, 6509, 6503, 6949, -1, 6950, 6497, 6951, -1, 6503, 6497, 6950, -1, 6951, 6492, 6952, -1, 6497, 6492, 6951, -1, 6952, 6486, 6953, -1, 6492, 6486, 6952, -1, 6953, 6480, 6668, -1, 6486, 6480, 6953, -1, 6230, 6239, 6667, -1, 6667, 6239, 6954, -1, 6954, 6245, 6955, -1, 6239, 6245, 6954, -1, 6955, 6254, 6956, -1, 6245, 6254, 6955, -1, 6956, 6259, 6957, -1, 6254, 6259, 6956, -1, 6957, 6261, 6958, -1, 6259, 6261, 6957, -1, 6958, 6323, 6959, -1, 6261, 6323, 6958, -1, 6959, 6324, 6960, -1, 6323, 6324, 6959, -1, 6960, 6325, 6961, -1, 6324, 6325, 6960, -1, 6961, 6326, 6962, -1, 6325, 6326, 6961, -1, 6962, 6329, 6963, -1, 6326, 6329, 6962, -1, 6963, 6331, 6964, -1, 6329, 6331, 6963, -1, 6964, 6332, 6965, -1, 6331, 6332, 6964, -1, 6965, 6302, 6654, -1, 6332, 6302, 6965, -1, 6414, 6419, 6653, -1, 6653, 6419, 6966, -1, 6966, 6427, 6967, -1, 6419, 6427, 6966, -1, 6967, 6432, 6968, -1, 6427, 6432, 6967, -1, 6968, 6437, 6969, -1, 6432, 6437, 6968, -1, 6969, 6444, 6970, -1, 6437, 6444, 6969, -1, 6970, 6446, 6971, -1, 6444, 6446, 6970, -1, 6971, 6521, 6972, -1, 6446, 6521, 6971, -1, 6972, 6516, 6973, -1, 6521, 6516, 6972, -1, 6973, 6514, 6974, -1, 6516, 6514, 6973, -1, 6974, 6511, 6975, -1, 6514, 6511, 6974, -1, 6975, 6505, 6976, -1, 6511, 6505, 6975, -1, 6976, 6499, 6977, -1, 6505, 6499, 6976, -1, 6977, 6500, 6640, -1, 6499, 6500, 6977, -1, 6328, 6348, 6639, -1, 6639, 6348, 6978, -1, 6978, 6359, 6979, -1, 6348, 6359, 6978, -1, 6979, 6365, 6980, -1, 6359, 6365, 6979, -1, 6980, 6369, 6981, -1, 6365, 6369, 6980, -1, 6981, 6372, 6982, -1, 6369, 6372, 6981, -1, 6982, 6354, 6983, -1, 6372, 6354, 6982, -1, 6983, 6445, 6984, -1, 6354, 6445, 6983, -1, 6984, 6443, 6985, -1, 6445, 6443, 6984, -1, 6985, 6441, 6986, -1, 6443, 6441, 6985, -1, 6986, 6433, 6987, -1, 6441, 6433, 6986, -1, 6987, 6426, 6988, -1, 6433, 6426, 6987, -1, 6988, 6420, 6989, -1, 6426, 6420, 6988, -1, 6989, 6413, 6626, -1, 6420, 6413, 6989, -1, 6196, 6218, 6625, -1, 6625, 6218, 6990, -1, 6990, 6227, 6991, -1, 6218, 6227, 6990, -1, 6991, 6232, 6992, -1, 6227, 6232, 6991, -1, 6992, 6238, 6993, -1, 6232, 6238, 6992, -1, 6993, 6246, 6994, -1, 6238, 6246, 6993, -1, 6994, 6253, 6995, -1, 6246, 6253, 6994, -1, 6995, 6338, 6996, -1, 6253, 6338, 6995, -1, 6996, 6366, 6997, -1, 6338, 6366, 6996, -1, 6997, 6362, 6998, -1, 6366, 6362, 6997, -1, 6998, 6356, 6999, -1, 6362, 6356, 6998, -1, 6999, 6341, 7000, -1, 6356, 6341, 6999, -1, 7000, 6321, 7001, -1, 6341, 6321, 7000, -1, 7001, 6282, 6612, -1, 6321, 6282, 7001, -1, 6207, 6214, 6611, -1, 6611, 6214, 7002, -1, 7002, 6228, 7003, -1, 6214, 6228, 7002, -1, 7003, 6233, 7004, -1, 6228, 6233, 7003, -1, 7004, 6241, 7005, -1, 6233, 6241, 7004, -1, 7005, 6252, 7006, -1, 6241, 6252, 7005, -1, 7006, 6257, 7007, -1, 6252, 6257, 7006, -1, 7007, 6350, 7008, -1, 6257, 6350, 7007, -1, 7008, 6373, 7009, -1, 6350, 6373, 7008, -1, 7009, 6368, 7010, -1, 6373, 6368, 7009, -1, 7010, 6364, 7011, -1, 6368, 6364, 7010, -1, 7011, 6358, 7012, -1, 6364, 6358, 7011, -1, 7012, 6347, 7013, -1, 6358, 6347, 7012, -1, 7013, 6327, 6598, -1, 6347, 6327, 7013, -1, 6607, 6605, 6606, -1, 6610, 6611, 6609, -1, 6609, 6611, 6608, -1, 6608, 6611, 6607, -1, 6607, 6611, 6605, -1, 6611, 6604, 6605, -1, 7002, 7003, 6611, -1, 6604, 6602, 6603, -1, 6611, 6602, 6604, -1, 7003, 7004, 6611, -1, 6611, 6601, 6602, -1, 7004, 7005, 6611, -1, 7006, 7007, 7005, -1, 7005, 7007, 6611, -1, 6600, 6598, 6599, -1, 7007, 7008, 6611, -1, 6598, 7012, 7013, -1, 6600, 7012, 6598, -1, 7009, 7010, 7008, -1, 7008, 7010, 6611, -1, 6601, 7011, 6600, -1, 6611, 7011, 6601, -1, 7010, 7011, 6611, -1, 6600, 7011, 7012, -1, 6621, 6619, 6620, -1, 6624, 6625, 6623, -1, 6990, 6991, 6625, -1, 6625, 6991, 6623, -1, 6619, 6616, 6618, -1, 6618, 6616, 6617, -1, 6621, 6616, 6619, -1, 6623, 6992, 6622, -1, 6991, 6992, 6623, -1, 6622, 6615, 6621, -1, 6621, 6615, 6616, -1, 6994, 6995, 6993, -1, 6614, 6612, 6613, -1, 6612, 7000, 7001, -1, 6614, 7000, 6612, -1, 6997, 6998, 6996, -1, 6996, 6998, 6995, -1, 6995, 6998, 6993, -1, 6615, 6999, 6614, -1, 6993, 6999, 6992, -1, 6992, 6999, 6622, -1, 6622, 6999, 6615, -1, 6998, 6999, 6993, -1, 6614, 6999, 7000, -1, 6636, 6634, 6635, -1, 6637, 6638, 6636, -1, 6636, 6639, 6634, -1, 6638, 6639, 6636, -1, 6634, 6631, 6633, -1, 6633, 6631, 6632, -1, 6639, 6631, 6634, -1, 6979, 6980, 6978, -1, 6978, 6980, 6639, -1, 6631, 6629, 6630, -1, 6981, 6982, 6980, -1, 6980, 6982, 6639, -1, 6629, 6627, 6628, -1, 6631, 6627, 6629, -1, 6627, 6989, 6626, -1, 6631, 6989, 6627, -1, 6984, 6985, 6983, -1, 6983, 6985, 6982, -1, 6639, 6985, 6631, -1, 6982, 6985, 6639, -1, 6631, 6985, 6989, -1, 6989, 6987, 6988, -1, 6986, 6987, 6985, -1, 6985, 6987, 6989, -1, 6650, 6648, 6649, -1, 6651, 6652, 6650, -1, 6650, 6653, 6648, -1, 6652, 6653, 6650, -1, 6648, 6645, 6647, -1, 6647, 6645, 6646, -1, 6653, 6645, 6648, -1, 6967, 6968, 6966, -1, 6966, 6968, 6653, -1, 6645, 6643, 6644, -1, 6969, 6970, 6968, -1, 6968, 6970, 6653, -1, 6643, 6641, 6642, -1, 6645, 6641, 6643, -1, 6641, 6977, 6640, -1, 6645, 6977, 6641, -1, 6972, 6973, 6971, -1, 6971, 6973, 6970, -1, 6653, 6973, 6645, -1, 6970, 6973, 6653, -1, 6645, 6973, 6977, -1, 6977, 6975, 6976, -1, 6974, 6975, 6973, -1, 6973, 6975, 6977, -1, 6664, 6662, 6663, -1, 6665, 6666, 6664, -1, 6664, 6666, 6662, -1, 6667, 6954, 6666, -1, 6662, 6659, 6661, -1, 6661, 6659, 6660, -1, 6955, 6956, 6954, -1, 6659, 6657, 6658, -1, 6957, 6958, 6956, -1, 6956, 6958, 6954, -1, 6657, 6655, 6656, -1, 6666, 6655, 6662, -1, 6662, 6655, 6659, -1, 6659, 6655, 6657, -1, 6655, 6965, 6654, -1, 6954, 6965, 6666, -1, 6666, 6965, 6655, -1, 6960, 6961, 6959, -1, 6959, 6961, 6958, -1, 6958, 6961, 6954, -1, 6954, 6961, 6965, -1, 6965, 6963, 6964, -1, 6962, 6963, 6961, -1, 6961, 6963, 6965, -1, 6677, 6675, 6676, -1, 6680, 6681, 6679, -1, 6942, 6943, 6681, -1, 6681, 6943, 6679, -1, 6675, 6672, 6674, -1, 6674, 6672, 6673, -1, 6677, 6672, 6675, -1, 6679, 6944, 6678, -1, 6943, 6944, 6679, -1, 6678, 6671, 6677, -1, 6677, 6671, 6672, -1, 6946, 6947, 6945, -1, 6670, 6668, 6669, -1, 6668, 6952, 6953, -1, 6670, 6952, 6668, -1, 6949, 6950, 6948, -1, 6948, 6950, 6947, -1, 6947, 6950, 6945, -1, 6671, 6951, 6670, -1, 6945, 6951, 6944, -1, 6944, 6951, 6678, -1, 6678, 6951, 6671, -1, 6950, 6951, 6945, -1, 6670, 6951, 6952, -1, 6691, 6689, 6690, -1, 6694, 6695, 6693, -1, 6930, 6931, 6695, -1, 6695, 6931, 6693, -1, 6689, 6686, 6688, -1, 6688, 6686, 6687, -1, 6691, 6686, 6689, -1, 6693, 6932, 6692, -1, 6931, 6932, 6693, -1, 6692, 6685, 6691, -1, 6691, 6685, 6686, -1, 6934, 6935, 6933, -1, 6684, 6682, 6683, -1, 6682, 6940, 6941, -1, 6684, 6940, 6682, -1, 6937, 6938, 6936, -1, 6936, 6938, 6935, -1, 6935, 6938, 6933, -1, 6685, 6939, 6684, -1, 6933, 6939, 6932, -1, 6932, 6939, 6692, -1, 6692, 6939, 6685, -1, 6938, 6939, 6933, -1, 6684, 6939, 6940, -1, 6705, 6703, 6704, -1, 6708, 6709, 6707, -1, 6918, 6919, 6709, -1, 6709, 6919, 6707, -1, 6702, 6700, 6701, -1, 6707, 6920, 6706, -1, 6919, 6920, 6707, -1, 6706, 6921, 6705, -1, 6920, 6921, 6706, -1, 6922, 6923, 6921, -1, 6705, 6923, 6703, -1, 6921, 6923, 6705, -1, 6703, 6696, 6702, -1, 6700, 6696, 6699, -1, 6699, 6696, 6698, -1, 6698, 6696, 6697, -1, 6702, 6696, 6700, -1, 6923, 6696, 6703, -1, 6923, 6924, 6696, -1, 6696, 6928, 6929, -1, 6925, 6926, 6924, -1, 6924, 6926, 6696, -1, 6926, 6927, 6696, -1, 6696, 6927, 6928, -1, 6719, 6717, 6718, -1, 6722, 6723, 6721, -1, 6906, 6907, 6723, -1, 6723, 6907, 6721, -1, 6717, 6714, 6716, -1, 6716, 6714, 6715, -1, 6719, 6714, 6717, -1, 6721, 6908, 6720, -1, 6907, 6908, 6721, -1, 6720, 6713, 6719, -1, 6719, 6713, 6714, -1, 6910, 6911, 6909, -1, 6712, 6710, 6711, -1, 6713, 6916, 6712, -1, 6710, 6916, 6917, -1, 6712, 6916, 6710, -1, 6913, 6914, 6912, -1, 6912, 6914, 6911, -1, 6911, 6914, 6909, -1, 6909, 6915, 6908, -1, 6908, 6915, 6720, -1, 6720, 6915, 6713, -1, 6713, 6915, 6916, -1, 6914, 6915, 6909, -1, 6734, 6732, 6733, -1, 6736, 6737, 6735, -1, 6732, 6729, 6731, -1, 6731, 6729, 6730, -1, 6894, 6895, 6737, -1, 6737, 6895, 6735, -1, 6735, 6896, 6734, -1, 6895, 6896, 6735, -1, 6729, 6727, 6728, -1, 6734, 6727, 6732, -1, 6732, 6727, 6729, -1, 6897, 6898, 6896, -1, 6726, 6724, 6725, -1, 6900, 6901, 6899, -1, 6899, 6901, 6898, -1, 6724, 6904, 6905, -1, 6726, 6904, 6724, -1, 6727, 6903, 6726, -1, 6902, 6903, 6901, -1, 6898, 6903, 6896, -1, 6734, 6903, 6727, -1, 6896, 6903, 6734, -1, 6901, 6903, 6898, -1, 6726, 6903, 6904, -1, 6747, 6745, 6746, -1, 6750, 6751, 6749, -1, 6882, 6883, 6751, -1, 6751, 6883, 6749, -1, 6745, 6742, 6744, -1, 6744, 6742, 6743, -1, 6747, 6742, 6745, -1, 6749, 6884, 6748, -1, 6883, 6884, 6749, -1, 6748, 6741, 6747, -1, 6747, 6741, 6742, -1, 6886, 6887, 6885, -1, 6740, 6738, 6739, -1, 6738, 6892, 6893, -1, 6740, 6892, 6738, -1, 6889, 6890, 6888, -1, 6888, 6890, 6887, -1, 6887, 6890, 6885, -1, 6741, 6891, 6740, -1, 6885, 6891, 6884, -1, 6884, 6891, 6748, -1, 6748, 6891, 6741, -1, 6890, 6891, 6885, -1, 6740, 6891, 6892, -1, 6761, 6759, 6760, -1, 6764, 6765, 6763, -1, 6870, 6871, 6765, -1, 6765, 6871, 6763, -1, 6759, 6756, 6758, -1, 6758, 6756, 6757, -1, 6761, 6756, 6759, -1, 6763, 6872, 6762, -1, 6871, 6872, 6763, -1, 6762, 6755, 6761, -1, 6761, 6755, 6756, -1, 6874, 6875, 6873, -1, 6754, 6752, 6753, -1, 6752, 6880, 6881, -1, 6754, 6880, 6752, -1, 6877, 6878, 6876, -1, 6876, 6878, 6875, -1, 6875, 6878, 6873, -1, 6755, 6879, 6754, -1, 6873, 6879, 6872, -1, 6872, 6879, 6762, -1, 6762, 6879, 6755, -1, 6878, 6879, 6873, -1, 6754, 6879, 6880, -1, 6776, 6777, 6775, -1, 6777, 6778, 6775, -1, 6774, 6772, 6773, -1, 6779, 6858, 6778, -1, 6772, 6770, 6771, -1, 6860, 6861, 6859, -1, 6859, 6861, 6858, -1, 6778, 6861, 6775, -1, 6858, 6861, 6778, -1, 6770, 6768, 6769, -1, 6770, 6767, 6768, -1, 6775, 6863, 6774, -1, 6862, 6863, 6861, -1, 6774, 6863, 6772, -1, 6861, 6863, 6775, -1, 6767, 6869, 6766, -1, 6770, 6869, 6767, -1, 6864, 6865, 6863, -1, 6863, 6865, 6772, -1, 6869, 6866, 6868, -1, 6772, 6866, 6770, -1, 6865, 6866, 6772, -1, 6770, 6866, 6869, -1, 6866, 6867, 6868, -1, 6790, 6791, 6789, -1, 6791, 6792, 6789, -1, 6788, 6786, 6787, -1, 6793, 6846, 6792, -1, 6786, 6784, 6785, -1, 6848, 6849, 6847, -1, 6847, 6849, 6846, -1, 6792, 6849, 6789, -1, 6846, 6849, 6792, -1, 6784, 6782, 6783, -1, 6784, 6781, 6782, -1, 6789, 6851, 6788, -1, 6850, 6851, 6849, -1, 6788, 6851, 6786, -1, 6849, 6851, 6789, -1, 6781, 6857, 6780, -1, 6784, 6857, 6781, -1, 6852, 6853, 6851, -1, 6851, 6853, 6786, -1, 6857, 6854, 6856, -1, 6786, 6854, 6784, -1, 6853, 6854, 6786, -1, 6784, 6854, 6857, -1, 6854, 6855, 6856, -1, 6805, 6802, 6804, -1, 6804, 6802, 6803, -1, 6802, 6800, 6801, -1, 6807, 6834, 6806, -1, 6802, 6799, 6800, -1, 6799, 6797, 6798, -1, 6806, 6796, 6805, -1, 6805, 6796, 6802, -1, 6802, 6796, 6799, -1, 6799, 6796, 6797, -1, 6837, 6838, 6836, -1, 6836, 6838, 6835, -1, 6796, 6794, 6795, -1, 6834, 6794, 6806, -1, 6806, 6794, 6796, -1, 6840, 6841, 6839, -1, 6839, 6841, 6838, -1, 6838, 6841, 6835, -1, 6794, 6844, 6845, -1, 6835, 6844, 6834, -1, 6834, 6844, 6794, -1, 6841, 6844, 6835, -1, 6842, 6843, 6841, -1, 6841, 6843, 6844, -1, 6819, 6816, 6818, -1, 6818, 6816, 6817, -1, 6816, 6814, 6815, -1, 6821, 6822, 6820, -1, 6816, 6813, 6814, -1, 6813, 6811, 6812, -1, 6819, 6810, 6816, -1, 6816, 6810, 6813, -1, 6813, 6810, 6811, -1, 6825, 6826, 6824, -1, 6824, 6826, 6823, -1, 6820, 6809, 6819, -1, 6819, 6809, 6810, -1, 6822, 6808, 6820, -1, 6820, 6808, 6809, -1, 6822, 6833, 6808, -1, 6828, 6829, 6827, -1, 6827, 6829, 6826, -1, 6826, 6829, 6823, -1, 6823, 6832, 6822, -1, 6829, 6832, 6823, -1, 6822, 6832, 6833, -1, 6830, 6831, 6829, -1, 6829, 6831, 6832, -1, 3176, 3185, 7014, -1, 7015, 7014, 7016, -1, 7015, 3176, 7014, -1, 7017, 7016, 7018, -1, 7017, 7015, 7016, -1, 7019, 7018, 7020, -1, 7019, 7017, 7018, -1, 7021, 7020, 7022, -1, 7021, 7019, 7020, -1, 7023, 7021, 7022, -1, 7024, 7025, 7026, -1, 7027, 7026, 7028, -1, 7027, 7024, 7026, -1, 7029, 7028, 7030, -1, 7029, 7027, 7028, -1, 7031, 7030, 7032, -1, 7031, 7029, 7030, -1, 7033, 7032, 3184, -1, 7033, 7031, 7032, -1, 3193, 7033, 3184, -1, 7021, 3176, 7015, -1, 7021, 7015, 7017, -1, 7021, 7017, 7019, -1, 7023, 3176, 7021, -1, 7033, 7027, 7029, -1, 7033, 7029, 7031, -1, 3193, 7024, 7027, -1, 3193, 7027, 7033, -1, 3193, 3176, 7023, -1, 3193, 7023, 7024, -1, 7026, 3184, 7032, -1, 7026, 7032, 7030, -1, 7026, 7030, 7028, -1, 7025, 3184, 7026, -1, 7014, 7020, 7018, -1, 7014, 7018, 7016, -1, 3185, 7022, 7020, -1, 3185, 7020, 7014, -1, 3185, 3184, 7025, -1, 3185, 7025, 7022, -1, 7023, 7025, 7024, -1, 7023, 7022, 7025, -1, 7034, 3055, 7035, -1, 7036, 7034, 7037, -1, 7036, 7037, 7038, -1, 7036, 3055, 7034, -1, 7039, 3055, 7036, -1, 3053, 3055, 7039, -1, 7040, 3053, 7039, -1, 7041, 7039, 7042, -1, 7041, 7042, 7043, -1, 7041, 7040, 7039, -1, 3046, 3053, 7040, -1, 7044, 7040, 7041, -1, 7044, 3046, 7040, -1, 7045, 7041, 7043, -1, 7045, 7044, 7041, -1, 7046, 7043, 7042, -1, 7046, 7045, 7043, -1, 7047, 7042, 7039, -1, 7047, 7046, 7042, -1, 7048, 7047, 7039, -1, 7049, 7036, 7038, -1, 7049, 7050, 7036, -1, 7051, 7038, 7037, -1, 7051, 7049, 7038, -1, 7052, 7037, 7034, -1, 7052, 7051, 7037, -1, 7053, 7034, 7035, -1, 7053, 7052, 7034, -1, 3047, 7035, 3055, -1, 3047, 7053, 7035, -1, 3047, 7051, 7052, -1, 3047, 7052, 7053, -1, 7050, 7049, 7051, -1, 7050, 7051, 3047, -1, 7045, 7046, 7047, -1, 7045, 7047, 7048, -1, 3046, 7044, 7045, -1, 3046, 7048, 7050, -1, 3046, 7050, 3047, -1, 3046, 7045, 7048, -1, 7048, 7036, 7050, -1, 7039, 7036, 7048, -1, 7054, 3040, 7055, -1, 7056, 3040, 7054, -1, 7057, 7056, 7058, -1, 7057, 3040, 7056, -1, 7059, 3040, 7057, -1, 3037, 3040, 7059, -1, 7060, 7059, 7061, -1, 7062, 7063, 3037, -1, 7062, 7059, 7060, -1, 7062, 3037, 7059, -1, 3030, 3037, 7063, -1, 7064, 7063, 7062, -1, 7064, 3030, 7063, -1, 7065, 7062, 7060, -1, 7065, 7064, 7062, -1, 7066, 7060, 7061, -1, 7066, 7065, 7060, -1, 7067, 7061, 7059, -1, 7067, 7066, 7061, -1, 7068, 7067, 7059, -1, 7069, 7057, 7058, -1, 7069, 7070, 7057, -1, 7071, 7058, 7056, -1, 7071, 7069, 7058, -1, 7072, 7056, 7054, -1, 7072, 7071, 7056, -1, 7073, 7054, 7055, -1, 7073, 7072, 7054, -1, 3031, 7055, 3040, -1, 3031, 7073, 7055, -1, 3031, 7071, 7072, -1, 3031, 7072, 7073, -1, 7070, 7069, 7071, -1, 7070, 7071, 3031, -1, 7068, 7070, 3031, -1, 3030, 7064, 7065, -1, 3030, 7065, 7066, -1, 3030, 7066, 7067, -1, 3030, 7067, 7068, -1, 3030, 7068, 3031, -1, 7068, 7057, 7070, -1, 7059, 7057, 7068, -1, 7074, 7075, 7076, -1, 7077, 7074, 7076, -1, 7078, 7076, 3110, -1, 7078, 7077, 7076, -1, 7079, 7080, 7081, -1, 7079, 7081, 7082, -1, 3118, 7083, 7079, -1, 3118, 7082, 7078, -1, 3118, 7078, 3110, -1, 3118, 7079, 7082, -1, 7084, 3103, 3110, -1, 7084, 3110, 7076, -1, 7085, 7076, 7075, -1, 7085, 7084, 7076, -1, 7086, 7075, 7074, -1, 7086, 7085, 7075, -1, 7087, 7074, 7077, -1, 7087, 7086, 7074, -1, 7088, 7077, 7078, -1, 7088, 7087, 7077, -1, 7089, 7082, 7081, -1, 7089, 7090, 7082, -1, 7091, 7081, 7080, -1, 7091, 7089, 7081, -1, 7092, 7080, 7079, -1, 7092, 7091, 7080, -1, 7093, 7079, 7083, -1, 7093, 7092, 7079, -1, 3104, 7083, 3118, -1, 3104, 7093, 7083, -1, 7086, 7084, 7085, -1, 7087, 7084, 7086, -1, 7088, 3103, 7084, -1, 7088, 7084, 7087, -1, 3104, 7088, 7090, -1, 3104, 3103, 7088, -1, 7092, 7090, 7089, -1, 7092, 7089, 7091, -1, 7092, 7093, 3104, -1, 7092, 3104, 7090, -1, 7088, 7082, 7090, -1, 7078, 7082, 7088, -1, 3119, 7094, 7095, -1, 3119, 7095, 7096, -1, 7097, 7094, 3119, -1, 7098, 7097, 3119, -1, 7099, 7098, 3119, -1, 7100, 7101, 7102, -1, 7103, 7102, 7099, -1, 7103, 7100, 7102, -1, 3120, 7099, 3119, -1, 3120, 7103, 7099, -1, 7104, 3114, 3119, -1, 7104, 7096, 7095, -1, 7104, 3119, 7096, -1, 7105, 7104, 7095, -1, 7106, 7095, 7094, -1, 7106, 7105, 7095, -1, 7107, 7094, 7097, -1, 7107, 7106, 7094, -1, 7108, 7097, 7098, -1, 7108, 7107, 7097, -1, 7109, 7099, 7102, -1, 7110, 7102, 7101, -1, 7110, 7109, 7102, -1, 7111, 7101, 7100, -1, 7111, 7110, 7101, -1, 7112, 7100, 7103, -1, 7112, 7111, 7100, -1, 7113, 7103, 3120, -1, 7113, 7112, 7103, -1, 3112, 7113, 3120, -1, 7105, 3114, 7104, -1, 7106, 3114, 7105, -1, 7107, 3114, 7106, -1, 7108, 3114, 7107, -1, 7109, 3114, 7108, -1, 3112, 3114, 7109, -1, 7113, 3112, 7109, -1, 7112, 7109, 7110, -1, 7112, 7110, 7111, -1, 7112, 7113, 7109, -1, 7108, 7099, 7109, -1, 7098, 7099, 7108, -1, 7114, 7115, 2136, -1, 7116, 7117, 7114, -1, 7116, 7114, 2136, -1, 7118, 7119, 7120, -1, 7118, 7120, 7121, -1, 1952, 7121, 7116, -1, 1952, 7118, 7121, -1, 1952, 7116, 2136, -1, 2119, 2136, 7115, -1, 7122, 7115, 7114, -1, 7122, 2119, 7115, -1, 7123, 7114, 7117, -1, 7123, 7122, 7114, -1, 7124, 7117, 7116, -1, 7124, 7123, 7117, -1, 7125, 7124, 7116, -1, 7126, 7121, 7120, -1, 7127, 7120, 7119, -1, 7127, 7126, 7120, -1, 7128, 7119, 7118, -1, 7128, 7127, 7119, -1, 7129, 7118, 1952, -1, 7129, 7128, 7118, -1, 2121, 7129, 1952, -1, 7128, 7129, 2121, -1, 7127, 7128, 2121, -1, 7126, 7127, 2121, -1, 7122, 7123, 7124, -1, 2119, 7124, 7125, -1, 2119, 7125, 7126, -1, 2119, 7126, 2121, -1, 2119, 7122, 7124, -1, 7130, 7131, 7132, -1, 7130, 7132, 7133, -1, 7130, 7133, 2097, -1, 2138, 7134, 7135, -1, 2138, 7135, 7136, -1, 2138, 7136, 7137, -1, 2138, 7137, 7130, -1, 2138, 7130, 2097, -1, 2057, 2097, 7133, -1, 7138, 7133, 7132, -1, 7138, 2057, 7133, -1, 7139, 7138, 7132, -1, 7140, 7132, 7131, -1, 7140, 7139, 7132, -1, 7141, 7131, 7130, -1, 7141, 7140, 7131, -1, 7142, 7137, 7136, -1, 7143, 7136, 7135, -1, 7143, 7142, 7136, -1, 7144, 7135, 7134, -1, 7144, 7143, 7135, -1, 7145, 7134, 2138, -1, 7145, 7144, 7134, -1, 2120, 7145, 2138, -1, 7144, 7145, 2120, -1, 7143, 7144, 2120, -1, 7142, 7143, 2120, -1, 7138, 7139, 7140, -1, 2057, 7140, 7141, -1, 2057, 7141, 7142, -1, 2057, 7142, 2120, -1, 2057, 7138, 7140, -1, 3182, 7146, 7147, -1, 7148, 3182, 7147, -1, 7149, 3182, 7148, -1, 7150, 3182, 7149, -1, 7151, 7152, 7153, -1, 3183, 7154, 7155, -1, 3183, 7155, 7152, -1, 3183, 7152, 7151, -1, 3183, 3182, 7150, -1, 3183, 7150, 7154, -1, 7156, 3192, 3183, -1, 7156, 3183, 7151, -1, 7157, 7151, 7153, -1, 7157, 7156, 7151, -1, 7158, 7153, 7152, -1, 7158, 7157, 7153, -1, 7159, 7152, 7155, -1, 7159, 7158, 7152, -1, 7160, 7155, 7154, -1, 7160, 7159, 7155, -1, 7161, 7150, 7149, -1, 7162, 7149, 7148, -1, 7162, 7161, 7149, -1, 7163, 7148, 7147, -1, 7163, 7162, 7148, -1, 7164, 7163, 7147, -1, 7165, 7147, 7146, -1, 7165, 7164, 7147, -1, 3191, 7146, 3182, -1, 3191, 7165, 7146, -1, 3192, 7156, 7157, -1, 7158, 3192, 7157, -1, 7159, 3192, 7158, -1, 7160, 3192, 7159, -1, 7164, 7162, 7163, -1, 3191, 7161, 7162, -1, 3191, 7164, 7165, -1, 3191, 7162, 7164, -1, 3191, 3192, 7160, -1, 3191, 7160, 7161, -1, 7160, 7154, 7161, -1, 7161, 7154, 7150, -1, 7166, 7167, 7168, -1, 7169, 7167, 7166, -1, 7170, 3180, 7167, -1, 7170, 7167, 7169, -1, 7171, 7172, 7173, -1, 7171, 7173, 7174, -1, 7171, 7174, 7175, -1, 3181, 7172, 7171, -1, 3181, 3180, 7170, -1, 3181, 7170, 7172, -1, 7176, 3190, 3181, -1, 7176, 3181, 7171, -1, 7177, 7171, 7175, -1, 7177, 7176, 7171, -1, 7178, 7175, 7174, -1, 7178, 7177, 7175, -1, 7179, 7174, 7173, -1, 7179, 7178, 7174, -1, 7180, 7173, 7172, -1, 7180, 7179, 7173, -1, 7181, 7170, 7169, -1, 7182, 7169, 7166, -1, 7182, 7181, 7169, -1, 7183, 7166, 7168, -1, 7183, 7182, 7166, -1, 7184, 7168, 7167, -1, 7184, 7183, 7168, -1, 7185, 7184, 7167, -1, 3189, 7167, 3180, -1, 3189, 7185, 7167, -1, 7178, 7176, 7177, -1, 7179, 7176, 7178, -1, 7180, 3190, 7176, -1, 7180, 7176, 7179, -1, 7184, 7181, 7182, -1, 7184, 7182, 7183, -1, 3189, 7184, 7185, -1, 3189, 7181, 7184, -1, 3189, 3190, 7180, -1, 3189, 7180, 7181, -1, 7180, 7170, 7181, -1, 7180, 7172, 7170, -1, 2491, 2500, 2624, -1, 2491, 2624, 7186, -1, 2485, 7186, 7187, -1, 2485, 2491, 7186, -1, 2478, 7187, 7188, -1, 2478, 2485, 7187, -1, 2479, 7188, 7189, -1, 2479, 2478, 7188, -1, 2487, 7189, 7190, -1, 2487, 2479, 7189, -1, 2498, 7190, 7191, -1, 2498, 2487, 7190, -1, 2501, 7191, 7192, -1, 2501, 2498, 7191, -1, 2509, 7192, 7193, -1, 2509, 2501, 7192, -1, 2511, 7193, 7194, -1, 2511, 2509, 7193, -1, 2522, 7194, 7195, -1, 2522, 2511, 7194, -1, 2524, 7195, 7196, -1, 2524, 2522, 7195, -1, 2526, 7196, 7197, -1, 2526, 2524, 7196, -1, 2529, 7197, 2611, -1, 2529, 2526, 7197, -1, 7187, 7198, 7188, -1, 2616, 7199, 7200, -1, 2616, 7201, 7199, -1, 2616, 2615, 7201, -1, 7186, 7198, 7187, -1, 7186, 7202, 7198, -1, 7186, 7203, 7202, -1, 7204, 7195, 7194, -1, 2617, 2616, 7200, -1, 7204, 7205, 7195, -1, 2624, 7203, 7186, -1, 7206, 7196, 7195, -1, 7206, 7195, 7205, -1, 2618, 7207, 7208, -1, 2618, 7200, 7207, -1, 7209, 7194, 7193, -1, 2618, 2617, 7200, -1, 7209, 7204, 7194, -1, 2623, 7210, 7203, -1, 7211, 2611, 7197, -1, 7211, 7197, 7196, -1, 2623, 7203, 2624, -1, 7211, 7196, 7206, -1, 2619, 7208, 7212, -1, 2619, 2618, 7208, -1, 2622, 7213, 7210, -1, 7214, 7193, 7192, -1, 2622, 7215, 7213, -1, 7214, 7209, 7193, -1, 2622, 7210, 2623, -1, 2620, 2619, 7212, -1, 2621, 7212, 7215, -1, 2621, 7215, 2622, -1, 2621, 2620, 7212, -1, 7216, 2611, 7211, -1, 7217, 7192, 7191, -1, 7217, 7214, 7192, -1, 7218, 2612, 2611, -1, 7218, 2611, 7216, -1, 7219, 7191, 7190, -1, 7219, 7217, 7191, -1, 7220, 2613, 2612, -1, 7220, 2612, 7218, -1, 7221, 7190, 7189, -1, 7221, 7219, 7190, -1, 7222, 2613, 7220, -1, 7222, 2614, 2613, -1, 7188, 7223, 7221, -1, 7188, 7221, 7189, -1, 7201, 2614, 7222, -1, 7198, 7223, 7188, -1, 2615, 2614, 7201, -1, 7216, 7211, 7224, -1, 7224, 7211, 7225, -1, 7225, 7206, 7226, -1, 7211, 7206, 7225, -1, 7226, 7205, 7227, -1, 7206, 7205, 7226, -1, 7227, 7204, 7228, -1, 7205, 7204, 7227, -1, 7228, 7209, 7229, -1, 7204, 7209, 7228, -1, 7229, 7214, 7230, -1, 7209, 7214, 7229, -1, 7230, 7217, 7231, -1, 7214, 7217, 7230, -1, 7231, 7219, 7232, -1, 7217, 7219, 7231, -1, 7232, 7221, 7233, -1, 7219, 7221, 7232, -1, 7233, 7223, 7234, -1, 7221, 7223, 7233, -1, 7234, 7198, 7235, -1, 7223, 7198, 7234, -1, 7235, 7202, 7236, -1, 7198, 7202, 7235, -1, 7236, 7203, 7237, -1, 7202, 7203, 7236, -1, 7203, 7210, 7237, -1, 7237, 7210, 7238, -1, 7238, 7213, 7239, -1, 7210, 7213, 7238, -1, 7239, 7215, 7240, -1, 7213, 7215, 7239, -1, 7240, 7212, 7241, -1, 7215, 7212, 7240, -1, 7241, 7208, 7242, -1, 7212, 7208, 7241, -1, 7242, 7207, 7243, -1, 7208, 7207, 7242, -1, 7243, 7200, 7244, -1, 7207, 7200, 7243, -1, 7244, 7199, 7245, -1, 7200, 7199, 7244, -1, 7245, 7201, 7246, -1, 7199, 7201, 7245, -1, 7246, 7222, 7247, -1, 7201, 7222, 7246, -1, 7247, 7220, 7248, -1, 7222, 7220, 7247, -1, 7248, 7218, 7249, -1, 7220, 7218, 7248, -1, 7249, 7216, 7224, -1, 7218, 7216, 7249, -1, 7234, 7232, 7233, -1, 7236, 7237, 7235, -1, 7232, 7230, 7231, -1, 7235, 7238, 7234, -1, 7234, 7238, 7232, -1, 7237, 7238, 7235, -1, 7239, 7240, 7238, -1, 7241, 7242, 7240, -1, 7240, 7242, 7238, -1, 7230, 7224, 7229, -1, 7229, 7224, 7228, -1, 7228, 7224, 7227, -1, 7227, 7224, 7226, -1, 7226, 7224, 7225, -1, 7232, 7224, 7230, -1, 7238, 7224, 7232, -1, 7242, 7224, 7238, -1, 7244, 7245, 7243, -1, 7243, 7245, 7242, -1, 7242, 7245, 7224, -1, 7224, 7248, 7249, -1, 7245, 7246, 7224, -1, 7224, 7247, 7248, -1, 7246, 7247, 7224, -1, 2527, 2530, 2610, -1, 2527, 2610, 7250, -1, 2523, 7250, 7251, -1, 2523, 2527, 7250, -1, 2520, 7251, 7252, -1, 2520, 2523, 7251, -1, 2521, 7252, 7253, -1, 2521, 2520, 7252, -1, 2525, 7253, 7254, -1, 2525, 2521, 7253, -1, 2528, 7254, 7255, -1, 2528, 2525, 7254, -1, 2531, 7255, 7256, -1, 2531, 2528, 7255, -1, 2534, 7256, 7257, -1, 2534, 2531, 7256, -1, 2537, 7257, 7258, -1, 2537, 2534, 7257, -1, 2545, 7258, 7259, -1, 2545, 2537, 7258, -1, 2548, 7259, 7260, -1, 2548, 2545, 7259, -1, 2340, 7260, 7261, -1, 2340, 2548, 7260, -1, 2338, 7261, 2597, -1, 2338, 2340, 7261, -1, 7262, 7263, 7252, -1, 2601, 2600, 7264, -1, 7251, 7262, 7252, -1, 7265, 7259, 7258, -1, 7265, 7266, 7259, -1, 7267, 7260, 7259, -1, 7267, 7259, 7266, -1, 7268, 7258, 7257, -1, 7268, 7265, 7258, -1, 2602, 7269, 7270, -1, 2602, 7264, 7269, -1, 2602, 2601, 7264, -1, 7271, 7261, 7260, -1, 7271, 7260, 7267, -1, 7250, 7262, 7251, -1, 7250, 7272, 7262, -1, 7273, 7257, 7256, -1, 7273, 7268, 7257, -1, 2603, 2602, 7270, -1, 2610, 7274, 7275, -1, 7276, 2597, 7261, -1, 2610, 7275, 7272, -1, 2610, 7272, 7250, -1, 7276, 7261, 7271, -1, 7277, 7256, 7255, -1, 2604, 7278, 7279, -1, 2604, 7270, 7278, -1, 7277, 7273, 7256, -1, 2604, 2603, 7270, -1, 7280, 2598, 2597, -1, 2609, 7274, 2610, -1, 7280, 2597, 7276, -1, 2605, 7279, 7281, -1, 2605, 2604, 7279, -1, 2608, 7282, 7274, -1, 2608, 7283, 7282, -1, 7284, 7255, 7254, -1, 2608, 7274, 2609, -1, 7284, 7277, 7255, -1, 2606, 2605, 7281, -1, 7285, 2599, 2598, -1, 2607, 7281, 7283, -1, 2607, 2606, 7281, -1, 7285, 2598, 7280, -1, 2607, 7283, 2608, -1, 7286, 7254, 7253, -1, 7286, 7284, 7254, -1, 7287, 2599, 7285, -1, 7287, 2600, 2599, -1, 7252, 7263, 7286, -1, 7252, 7286, 7253, -1, 7264, 2600, 7287, -1, 7276, 7271, 7288, -1, 7288, 7271, 7289, -1, 7289, 7267, 7290, -1, 7271, 7267, 7289, -1, 7290, 7266, 7291, -1, 7267, 7266, 7290, -1, 7291, 7265, 7292, -1, 7266, 7265, 7291, -1, 7292, 7268, 7293, -1, 7265, 7268, 7292, -1, 7293, 7273, 7294, -1, 7268, 7273, 7293, -1, 7294, 7277, 7295, -1, 7273, 7277, 7294, -1, 7295, 7284, 7296, -1, 7277, 7284, 7295, -1, 7296, 7286, 7297, -1, 7284, 7286, 7296, -1, 7297, 7263, 7298, -1, 7286, 7263, 7297, -1, 7298, 7262, 7299, -1, 7263, 7262, 7298, -1, 7299, 7272, 7300, -1, 7262, 7272, 7299, -1, 7300, 7275, 7301, -1, 7272, 7275, 7300, -1, 7275, 7274, 7301, -1, 7301, 7274, 7302, -1, 7302, 7282, 7303, -1, 7274, 7282, 7302, -1, 7303, 7283, 7304, -1, 7282, 7283, 7303, -1, 7304, 7281, 7305, -1, 7283, 7281, 7304, -1, 7305, 7279, 7306, -1, 7281, 7279, 7305, -1, 7306, 7278, 7307, -1, 7279, 7278, 7306, -1, 7307, 7270, 7308, -1, 7278, 7270, 7307, -1, 7308, 7269, 7309, -1, 7270, 7269, 7308, -1, 7309, 7264, 7310, -1, 7269, 7264, 7309, -1, 7310, 7287, 7311, -1, 7264, 7287, 7310, -1, 7311, 7285, 7312, -1, 7287, 7285, 7311, -1, 7312, 7280, 7313, -1, 7285, 7280, 7312, -1, 7313, 7276, 7288, -1, 7280, 7276, 7313, -1, 7300, 7301, 7299, -1, 7299, 7301, 7298, -1, 7298, 7301, 7297, -1, 7297, 7301, 7296, -1, 7296, 7294, 7295, -1, 7301, 7294, 7296, -1, 7301, 7293, 7294, -1, 7302, 7303, 7301, -1, 7303, 7304, 7301, -1, 7293, 7291, 7292, -1, 7304, 7305, 7301, -1, 7305, 7306, 7301, -1, 7291, 7289, 7290, -1, 7293, 7289, 7291, -1, 7289, 7313, 7288, -1, 7301, 7313, 7293, -1, 7293, 7313, 7289, -1, 7308, 7309, 7307, -1, 7307, 7309, 7306, -1, 7301, 7309, 7313, -1, 7306, 7309, 7301, -1, 7313, 7311, 7312, -1, 7310, 7311, 7309, -1, 7309, 7311, 7313, -1, 2341, 2339, 2596, -1, 2341, 2596, 7314, -1, 2549, 7314, 7315, -1, 2549, 2341, 7314, -1, 2546, 7315, 7316, -1, 2546, 2549, 7315, -1, 2547, 7316, 7317, -1, 2547, 2546, 7316, -1, 2335, 7317, 7318, -1, 2335, 2547, 7317, -1, 2336, 7318, 7319, -1, 2336, 2335, 7318, -1, 2347, 7319, 7320, -1, 2347, 2336, 7319, -1, 2352, 7320, 7321, -1, 2352, 2347, 7320, -1, 2359, 7321, 7322, -1, 2359, 2352, 7321, -1, 2381, 7322, 7323, -1, 2381, 2359, 7322, -1, 2379, 7323, 7324, -1, 2379, 2381, 7323, -1, 2386, 7324, 7325, -1, 2386, 2379, 7324, -1, 2391, 7325, 2583, -1, 2391, 2386, 7325, -1, 7326, 7327, 7316, -1, 2587, 2586, 7328, -1, 7315, 7326, 7316, -1, 7329, 7323, 7322, -1, 7329, 7330, 7323, -1, 7331, 7324, 7323, -1, 7331, 7323, 7330, -1, 7332, 7322, 7321, -1, 7332, 7329, 7322, -1, 7333, 7325, 7324, -1, 7333, 7324, 7331, -1, 2588, 7334, 7335, -1, 2588, 7328, 7334, -1, 7336, 7321, 7320, -1, 2588, 2587, 7328, -1, 7336, 7332, 7321, -1, 7337, 2583, 7325, -1, 7314, 7326, 7315, -1, 7314, 7338, 7326, -1, 7314, 7339, 7338, -1, 7337, 7325, 7333, -1, 7340, 7320, 7319, -1, 7340, 7336, 7320, -1, 2589, 2588, 7335, -1, 7341, 2584, 2583, -1, 7341, 2583, 7337, -1, 2596, 7339, 7314, -1, 2590, 7342, 7343, -1, 2590, 7335, 7342, -1, 2590, 2589, 7335, -1, 7344, 7319, 7318, -1, 2595, 7345, 7339, -1, 7344, 7340, 7319, -1, 2595, 7339, 2596, -1, 7346, 2585, 2584, -1, 2591, 7343, 7347, -1, 2591, 2590, 7343, -1, 7346, 2584, 7341, -1, 2594, 7348, 7345, -1, 7349, 7318, 7317, -1, 2594, 7350, 7348, -1, 7349, 7344, 7318, -1, 2594, 7345, 2595, -1, 2592, 2591, 7347, -1, 7351, 2585, 7346, -1, 2593, 7347, 7350, -1, 2593, 7350, 2594, -1, 7351, 2586, 2585, -1, 2593, 2592, 7347, -1, 7316, 7327, 7349, -1, 7316, 7349, 7317, -1, 7328, 2586, 7351, -1, 7337, 7333, 7352, -1, 7352, 7333, 7353, -1, 7353, 7331, 7354, -1, 7333, 7331, 7353, -1, 7354, 7330, 7355, -1, 7331, 7330, 7354, -1, 7355, 7329, 7356, -1, 7330, 7329, 7355, -1, 7356, 7332, 7357, -1, 7329, 7332, 7356, -1, 7357, 7336, 7358, -1, 7332, 7336, 7357, -1, 7358, 7340, 7359, -1, 7336, 7340, 7358, -1, 7359, 7344, 7360, -1, 7340, 7344, 7359, -1, 7360, 7349, 7361, -1, 7344, 7349, 7360, -1, 7361, 7327, 7362, -1, 7349, 7327, 7361, -1, 7362, 7326, 7363, -1, 7327, 7326, 7362, -1, 7363, 7338, 7364, -1, 7326, 7338, 7363, -1, 7364, 7339, 7365, -1, 7338, 7339, 7364, -1, 7339, 7345, 7365, -1, 7365, 7345, 7366, -1, 7366, 7348, 7367, -1, 7345, 7348, 7366, -1, 7367, 7350, 7368, -1, 7348, 7350, 7367, -1, 7368, 7347, 7369, -1, 7350, 7347, 7368, -1, 7369, 7343, 7370, -1, 7347, 7343, 7369, -1, 7370, 7342, 7371, -1, 7343, 7342, 7370, -1, 7371, 7335, 7372, -1, 7342, 7335, 7371, -1, 7372, 7334, 7373, -1, 7335, 7334, 7372, -1, 7373, 7328, 7374, -1, 7334, 7328, 7373, -1, 7374, 7351, 7375, -1, 7328, 7351, 7374, -1, 7375, 7346, 7376, -1, 7351, 7346, 7375, -1, 7376, 7341, 7377, -1, 7346, 7341, 7376, -1, 7377, 7337, 7352, -1, 7341, 7337, 7377, -1, 7362, 7363, 7361, -1, 7363, 7364, 7361, -1, 7365, 7366, 7364, -1, 7361, 7357, 7360, -1, 7360, 7357, 7359, -1, 7359, 7357, 7358, -1, 7364, 7357, 7361, -1, 7357, 7355, 7356, -1, 7364, 7355, 7357, -1, 7368, 7369, 7367, -1, 7367, 7369, 7366, -1, 7355, 7353, 7354, -1, 7364, 7353, 7355, -1, 7353, 7377, 7352, -1, 7366, 7377, 7364, -1, 7364, 7377, 7353, -1, 7372, 7373, 7371, -1, 7371, 7373, 7370, -1, 7377, 7374, 7376, -1, 7370, 7374, 7369, -1, 7369, 7374, 7366, -1, 7366, 7374, 7377, -1, 7373, 7374, 7370, -1, 7374, 7375, 7376, -1, 2392, 2395, 2582, -1, 2392, 2582, 7378, -1, 2387, 7378, 7379, -1, 2387, 2392, 7378, -1, 2380, 7379, 7380, -1, 2380, 2387, 7379, -1, 2383, 7380, 7381, -1, 2383, 2380, 7380, -1, 2389, 7381, 7382, -1, 2389, 2383, 7381, -1, 2393, 7382, 7383, -1, 2393, 2389, 7382, -1, 2396, 7383, 7384, -1, 2396, 2393, 7383, -1, 2398, 7384, 7385, -1, 2398, 2396, 7384, -1, 2442, 7385, 7386, -1, 2442, 2398, 7385, -1, 2441, 7386, 7387, -1, 2441, 2442, 7386, -1, 2440, 7387, 7388, -1, 2440, 2441, 7387, -1, 2465, 7388, 7389, -1, 2465, 2440, 7388, -1, 2468, 7389, 2569, -1, 2468, 2465, 7389, -1, 7390, 7391, 7380, -1, 2573, 2572, 7392, -1, 7379, 7390, 7380, -1, 7393, 7387, 7386, -1, 7393, 7394, 7387, -1, 7395, 7388, 7387, -1, 7395, 7387, 7394, -1, 7396, 7386, 7385, -1, 7396, 7393, 7386, -1, 7397, 7389, 7388, -1, 7397, 7388, 7395, -1, 2574, 7398, 7399, -1, 2574, 7392, 7398, -1, 7400, 7385, 7384, -1, 2574, 2573, 7392, -1, 7400, 7396, 7385, -1, 7401, 2569, 7389, -1, 7378, 7390, 7379, -1, 7378, 7402, 7390, -1, 7378, 7403, 7402, -1, 7401, 7389, 7397, -1, 7404, 7384, 7383, -1, 7404, 7400, 7384, -1, 2575, 2574, 7399, -1, 7405, 2570, 2569, -1, 7405, 2569, 7401, -1, 2582, 7403, 7378, -1, 2576, 7406, 7407, -1, 2576, 7399, 7406, -1, 2576, 2575, 7399, -1, 7408, 7383, 7382, -1, 2581, 7409, 7403, -1, 7408, 7404, 7383, -1, 2581, 7403, 2582, -1, 7410, 2571, 2570, -1, 2577, 7407, 7411, -1, 2577, 2576, 7407, -1, 7410, 2570, 7405, -1, 2580, 7412, 7409, -1, 7413, 7382, 7381, -1, 2580, 7414, 7412, -1, 7413, 7408, 7382, -1, 2580, 7409, 2581, -1, 2578, 2577, 7411, -1, 7415, 2571, 7410, -1, 2579, 7411, 7414, -1, 2579, 7414, 2580, -1, 7415, 2572, 2571, -1, 2579, 2578, 7411, -1, 7380, 7391, 7413, -1, 7380, 7413, 7381, -1, 7392, 2572, 7415, -1, 7401, 7397, 7416, -1, 7416, 7397, 7417, -1, 7417, 7395, 7418, -1, 7397, 7395, 7417, -1, 7418, 7394, 7419, -1, 7395, 7394, 7418, -1, 7419, 7393, 7420, -1, 7394, 7393, 7419, -1, 7420, 7396, 7421, -1, 7393, 7396, 7420, -1, 7421, 7400, 7422, -1, 7396, 7400, 7421, -1, 7422, 7404, 7423, -1, 7400, 7404, 7422, -1, 7423, 7408, 7424, -1, 7404, 7408, 7423, -1, 7424, 7413, 7425, -1, 7408, 7413, 7424, -1, 7425, 7391, 7426, -1, 7413, 7391, 7425, -1, 7426, 7390, 7427, -1, 7391, 7390, 7426, -1, 7427, 7402, 7428, -1, 7390, 7402, 7427, -1, 7428, 7403, 7429, -1, 7402, 7403, 7428, -1, 7403, 7409, 7429, -1, 7429, 7409, 7430, -1, 7430, 7412, 7431, -1, 7409, 7412, 7430, -1, 7431, 7414, 7432, -1, 7412, 7414, 7431, -1, 7432, 7411, 7433, -1, 7414, 7411, 7432, -1, 7433, 7407, 7434, -1, 7411, 7407, 7433, -1, 7434, 7406, 7435, -1, 7407, 7406, 7434, -1, 7435, 7399, 7436, -1, 7406, 7399, 7435, -1, 7436, 7398, 7437, -1, 7399, 7398, 7436, -1, 7437, 7392, 7438, -1, 7398, 7392, 7437, -1, 7438, 7415, 7439, -1, 7392, 7415, 7438, -1, 7439, 7410, 7440, -1, 7415, 7410, 7439, -1, 7440, 7405, 7441, -1, 7410, 7405, 7440, -1, 7441, 7401, 7416, -1, 7405, 7401, 7441, -1, 7426, 7427, 7425, -1, 7427, 7428, 7425, -1, 7429, 7430, 7428, -1, 7425, 7421, 7424, -1, 7424, 7421, 7423, -1, 7423, 7421, 7422, -1, 7428, 7421, 7425, -1, 7421, 7419, 7420, -1, 7428, 7419, 7421, -1, 7432, 7433, 7431, -1, 7431, 7433, 7430, -1, 7419, 7417, 7418, -1, 7428, 7417, 7419, -1, 7417, 7441, 7416, -1, 7430, 7441, 7428, -1, 7428, 7441, 7417, -1, 7436, 7437, 7435, -1, 7435, 7437, 7434, -1, 7441, 7438, 7440, -1, 7434, 7438, 7433, -1, 7433, 7438, 7430, -1, 7430, 7438, 7441, -1, 7437, 7438, 7434, -1, 7438, 7439, 7440, -1, 2923, 2627, 3029, -1, 2923, 3029, 7442, -1, 2918, 7442, 7443, -1, 2918, 2923, 7442, -1, 2915, 7443, 7444, -1, 2915, 2918, 7443, -1, 2916, 7444, 7445, -1, 2916, 2915, 7444, -1, 2921, 7445, 7446, -1, 2921, 2916, 7445, -1, 2924, 7446, 7447, -1, 2924, 2921, 7446, -1, 2631, 7447, 7448, -1, 2631, 2924, 7447, -1, 2632, 7448, 7449, -1, 2632, 2631, 7448, -1, 2644, 7449, 7450, -1, 2644, 2632, 7449, -1, 2658, 7450, 7451, -1, 2658, 2644, 7450, -1, 2666, 7451, 7452, -1, 2666, 2658, 7451, -1, 2669, 7452, 7453, -1, 2669, 2666, 7452, -1, 2692, 7453, 3016, -1, 2692, 2669, 7453, -1, 7454, 3025, 7455, -1, 3026, 3025, 7454, -1, 7456, 7452, 7451, -1, 7457, 7452, 7456, -1, 7444, 7458, 7445, -1, 7445, 7459, 7446, -1, 7458, 7459, 7445, -1, 7443, 7460, 7444, -1, 7444, 7460, 7458, -1, 7446, 7461, 7447, -1, 7459, 7461, 7446, -1, 7455, 3024, 7462, -1, 7462, 3024, 7463, -1, 7442, 7464, 7443, -1, 3025, 3024, 7455, -1, 7443, 7464, 7460, -1, 7447, 7465, 7448, -1, 7461, 7465, 7447, -1, 7466, 7453, 7457, -1, 3029, 7467, 7442, -1, 7457, 7453, 7452, -1, 7442, 7467, 7464, -1, 7463, 3023, 7468, -1, 3024, 3023, 7463, -1, 7448, 7469, 7449, -1, 7466, 3016, 7453, -1, 7465, 7469, 7448, -1, 7470, 3016, 7471, -1, 7471, 3016, 7466, -1, 3028, 7472, 3029, -1, 3029, 7472, 7467, -1, 7468, 3022, 7473, -1, 3023, 3022, 7468, -1, 7470, 3017, 3016, -1, 7449, 7474, 7450, -1, 7469, 7474, 7449, -1, 7473, 3021, 7475, -1, 3022, 3021, 7473, -1, 3027, 7476, 3028, -1, 3028, 7476, 7472, -1, 7477, 3018, 7470, -1, 7470, 3018, 3017, -1, 3021, 3020, 7475, -1, 7474, 7478, 7450, -1, 7475, 3019, 7479, -1, 7479, 3019, 7477, -1, 3020, 3019, 7475, -1, 7477, 3019, 3018, -1, 3027, 7454, 7476, -1, 3026, 7454, 3027, -1, 7478, 7451, 7450, -1, 7456, 7451, 7478, -1, 7471, 7466, 7480, -1, 7480, 7466, 7481, -1, 7481, 7457, 7482, -1, 7466, 7457, 7481, -1, 7482, 7456, 7483, -1, 7457, 7456, 7482, -1, 7483, 7478, 7484, -1, 7456, 7478, 7483, -1, 7484, 7474, 7485, -1, 7478, 7474, 7484, -1, 7485, 7469, 7486, -1, 7474, 7469, 7485, -1, 7486, 7465, 7487, -1, 7469, 7465, 7486, -1, 7487, 7461, 7488, -1, 7465, 7461, 7487, -1, 7488, 7459, 7489, -1, 7461, 7459, 7488, -1, 7489, 7458, 7490, -1, 7459, 7458, 7489, -1, 7490, 7460, 7491, -1, 7458, 7460, 7490, -1, 7491, 7464, 7492, -1, 7460, 7464, 7491, -1, 7492, 7467, 7493, -1, 7464, 7467, 7492, -1, 7467, 7472, 7493, -1, 7493, 7472, 7494, -1, 7494, 7476, 7495, -1, 7472, 7476, 7494, -1, 7495, 7454, 7496, -1, 7476, 7454, 7495, -1, 7496, 7455, 7497, -1, 7454, 7455, 7496, -1, 7497, 7462, 7498, -1, 7455, 7462, 7497, -1, 7498, 7463, 7499, -1, 7462, 7463, 7498, -1, 7499, 7468, 7500, -1, 7463, 7468, 7499, -1, 7500, 7473, 7501, -1, 7468, 7473, 7500, -1, 7501, 7475, 7502, -1, 7473, 7475, 7501, -1, 7502, 7479, 7503, -1, 7475, 7479, 7502, -1, 7503, 7477, 7504, -1, 7479, 7477, 7503, -1, 7504, 7470, 7505, -1, 7477, 7470, 7504, -1, 7505, 7471, 7480, -1, 7470, 7471, 7505, -1, 7490, 7488, 7489, -1, 7492, 7493, 7491, -1, 7488, 7486, 7487, -1, 7493, 7494, 7491, -1, 7486, 7484, 7485, -1, 7486, 7483, 7484, -1, 7497, 7498, 7496, -1, 7496, 7498, 7495, -1, 7491, 7481, 7490, -1, 7483, 7481, 7482, -1, 7490, 7481, 7488, -1, 7488, 7481, 7486, -1, 7494, 7481, 7491, -1, 7486, 7481, 7483, -1, 7481, 7505, 7480, -1, 7494, 7505, 7481, -1, 7500, 7501, 7499, -1, 7499, 7501, 7498, -1, 7495, 7504, 7494, -1, 7498, 7504, 7495, -1, 7494, 7504, 7505, -1, 7501, 7504, 7498, -1, 7502, 7503, 7501, -1, 7501, 7503, 7504, -1, 2878, 2883, 3015, -1, 2878, 3015, 7506, -1, 2873, 7506, 7507, -1, 2873, 2878, 7506, -1, 2867, 7507, 7508, -1, 2867, 2873, 7507, -1, 2870, 7508, 7509, -1, 2870, 2867, 7508, -1, 2875, 7509, 7510, -1, 2875, 2870, 7509, -1, 2882, 7510, 7511, -1, 2882, 2875, 7510, -1, 2899, 7511, 7512, -1, 2899, 2882, 7511, -1, 2901, 7512, 7513, -1, 2901, 2899, 7512, -1, 2902, 7513, 7514, -1, 2902, 2901, 7513, -1, 2903, 7514, 7515, -1, 2903, 2902, 7514, -1, 2904, 7515, 7516, -1, 2904, 2903, 7515, -1, 2922, 7516, 7517, -1, 2922, 2904, 7516, -1, 2625, 7517, 3002, -1, 2625, 2922, 7517, -1, 3012, 3011, 7518, -1, 7519, 7516, 7520, -1, 7520, 7516, 7515, -1, 7508, 7521, 7509, -1, 7509, 7522, 7510, -1, 7521, 7522, 7509, -1, 7507, 7523, 7508, -1, 7508, 7523, 7521, -1, 7510, 7524, 7511, -1, 7522, 7524, 7510, -1, 7518, 3010, 7525, -1, 3015, 7526, 7506, -1, 7525, 3010, 7527, -1, 7506, 7526, 7507, -1, 7507, 7526, 7523, -1, 3011, 3010, 7518, -1, 7511, 7528, 7512, -1, 7524, 7528, 7511, -1, 3015, 7529, 7526, -1, 7512, 7530, 7513, -1, 7519, 7517, 7516, -1, 7531, 7517, 7519, -1, 7528, 7530, 7512, -1, 3014, 7532, 3015, -1, 3010, 3009, 7527, -1, 3015, 7532, 7529, -1, 7531, 3002, 7517, -1, 7533, 3002, 7531, -1, 7513, 7534, 7514, -1, 7530, 7534, 7513, -1, 7527, 3008, 7535, -1, 3009, 3008, 7527, -1, 3013, 7536, 3014, -1, 3014, 7536, 7532, -1, 7537, 3003, 7533, -1, 7533, 3003, 3002, -1, 7535, 3007, 7538, -1, 7534, 7539, 7514, -1, 3008, 3007, 7535, -1, 3013, 7540, 7536, -1, 7541, 3004, 7537, -1, 7537, 3004, 3003, -1, 3012, 7540, 3013, -1, 7538, 3006, 7542, -1, 3007, 3006, 7538, -1, 7542, 3005, 7543, -1, 7543, 3005, 7541, -1, 7541, 3005, 3004, -1, 3006, 3005, 7542, -1, 7539, 7515, 7514, -1, 7520, 7515, 7539, -1, 3012, 7518, 7540, -1, 7533, 7531, 7544, -1, 7544, 7531, 7545, -1, 7545, 7519, 7546, -1, 7531, 7519, 7545, -1, 7546, 7520, 7547, -1, 7519, 7520, 7546, -1, 7547, 7539, 7548, -1, 7520, 7539, 7547, -1, 7548, 7534, 7549, -1, 7539, 7534, 7548, -1, 7549, 7530, 7550, -1, 7534, 7530, 7549, -1, 7550, 7528, 7551, -1, 7530, 7528, 7550, -1, 7551, 7524, 7552, -1, 7528, 7524, 7551, -1, 7552, 7522, 7553, -1, 7524, 7522, 7552, -1, 7553, 7521, 7554, -1, 7522, 7521, 7553, -1, 7554, 7523, 7555, -1, 7521, 7523, 7554, -1, 7555, 7526, 7556, -1, 7523, 7526, 7555, -1, 7556, 7529, 7557, -1, 7526, 7529, 7556, -1, 7529, 7532, 7557, -1, 7557, 7532, 7558, -1, 7558, 7536, 7559, -1, 7532, 7536, 7558, -1, 7559, 7540, 7560, -1, 7536, 7540, 7559, -1, 7560, 7518, 7561, -1, 7540, 7518, 7560, -1, 7561, 7525, 7562, -1, 7518, 7525, 7561, -1, 7562, 7527, 7563, -1, 7525, 7527, 7562, -1, 7563, 7535, 7564, -1, 7527, 7535, 7563, -1, 7564, 7538, 7565, -1, 7535, 7538, 7564, -1, 7565, 7542, 7566, -1, 7538, 7542, 7565, -1, 7566, 7543, 7567, -1, 7542, 7543, 7566, -1, 7567, 7541, 7568, -1, 7543, 7541, 7567, -1, 7568, 7537, 7569, -1, 7541, 7537, 7568, -1, 7569, 7533, 7544, -1, 7537, 7533, 7569, -1, 7556, 7557, 7555, -1, 7555, 7557, 7554, -1, 7554, 7557, 7553, -1, 7553, 7557, 7552, -1, 7552, 7557, 7551, -1, 7557, 7550, 7551, -1, 7558, 7559, 7557, -1, 7550, 7548, 7549, -1, 7557, 7548, 7550, -1, 7559, 7560, 7557, -1, 7557, 7547, 7548, -1, 7560, 7561, 7557, -1, 7557, 7546, 7547, -1, 7561, 7562, 7557, -1, 7557, 7545, 7546, -1, 7562, 7563, 7557, -1, 7563, 7564, 7557, -1, 7545, 7569, 7544, -1, 7557, 7569, 7545, -1, 7564, 7565, 7557, -1, 7557, 7568, 7569, -1, 7566, 7567, 7565, -1, 7565, 7567, 7557, -1, 7557, 7567, 7568, -1, 2830, 2837, 3001, -1, 2830, 3001, 7570, -1, 2827, 7570, 7571, -1, 2827, 2830, 7570, -1, 2818, 7571, 7572, -1, 2818, 2827, 7571, -1, 2820, 7572, 7573, -1, 2820, 2818, 7572, -1, 2801, 7573, 7574, -1, 2801, 2820, 7573, -1, 2800, 7574, 7575, -1, 2800, 2801, 7574, -1, 2799, 7575, 7576, -1, 2799, 2800, 7575, -1, 2871, 7576, 7577, -1, 2871, 2799, 7576, -1, 2868, 7577, 7578, -1, 2868, 2871, 7577, -1, 2866, 7578, 7579, -1, 2866, 2868, 7578, -1, 2874, 7579, 7580, -1, 2874, 2866, 7579, -1, 2880, 7580, 7581, -1, 2880, 2874, 7580, -1, 2881, 7581, 2988, -1, 2881, 2880, 7581, -1, 7582, 2997, 7583, -1, 2998, 2997, 7582, -1, 7584, 7580, 7579, -1, 7585, 7580, 7584, -1, 7572, 7586, 7573, -1, 7573, 7587, 7574, -1, 7586, 7587, 7573, -1, 7571, 7588, 7572, -1, 7572, 7588, 7586, -1, 7574, 7589, 7575, -1, 7587, 7589, 7574, -1, 7583, 2996, 7590, -1, 7590, 2996, 7591, -1, 7570, 7592, 7571, -1, 2997, 2996, 7583, -1, 7571, 7592, 7588, -1, 7575, 7593, 7576, -1, 7589, 7593, 7575, -1, 7594, 7581, 7585, -1, 3001, 7595, 7570, -1, 7585, 7581, 7580, -1, 7570, 7595, 7592, -1, 7591, 2995, 7596, -1, 2996, 2995, 7591, -1, 7576, 7597, 7577, -1, 7594, 2988, 7581, -1, 7593, 7597, 7576, -1, 7598, 2988, 7594, -1, 3000, 7599, 3001, -1, 3001, 7599, 7595, -1, 7596, 2994, 7600, -1, 2995, 2994, 7596, -1, 7601, 2989, 7598, -1, 7577, 7602, 7578, -1, 7598, 2989, 2988, -1, 7597, 7602, 7577, -1, 7600, 2993, 7603, -1, 2994, 2993, 7600, -1, 2999, 7604, 3000, -1, 3000, 7604, 7599, -1, 7605, 2990, 7601, -1, 7601, 2990, 2989, -1, 2993, 2992, 7603, -1, 7602, 7606, 7578, -1, 7603, 2991, 7607, -1, 7607, 2991, 7605, -1, 2992, 2991, 7603, -1, 2999, 7582, 7604, -1, 7605, 2991, 2990, -1, 2998, 7582, 2999, -1, 7606, 7579, 7578, -1, 7584, 7579, 7606, -1, 7598, 7594, 7608, -1, 7608, 7594, 7609, -1, 7609, 7585, 7610, -1, 7594, 7585, 7609, -1, 7610, 7584, 7611, -1, 7585, 7584, 7610, -1, 7611, 7606, 7612, -1, 7584, 7606, 7611, -1, 7612, 7602, 7613, -1, 7606, 7602, 7612, -1, 7613, 7597, 7614, -1, 7602, 7597, 7613, -1, 7614, 7593, 7615, -1, 7597, 7593, 7614, -1, 7615, 7589, 7616, -1, 7593, 7589, 7615, -1, 7616, 7587, 7617, -1, 7589, 7587, 7616, -1, 7617, 7586, 7618, -1, 7587, 7586, 7617, -1, 7618, 7588, 7619, -1, 7586, 7588, 7618, -1, 7619, 7592, 7620, -1, 7588, 7592, 7619, -1, 7620, 7595, 7621, -1, 7592, 7595, 7620, -1, 7595, 7599, 7621, -1, 7621, 7599, 7622, -1, 7622, 7604, 7623, -1, 7599, 7604, 7622, -1, 7623, 7582, 7624, -1, 7604, 7582, 7623, -1, 7624, 7583, 7625, -1, 7582, 7583, 7624, -1, 7625, 7590, 7626, -1, 7583, 7590, 7625, -1, 7626, 7591, 7627, -1, 7590, 7591, 7626, -1, 7627, 7596, 7628, -1, 7591, 7596, 7627, -1, 7628, 7600, 7629, -1, 7596, 7600, 7628, -1, 7629, 7603, 7630, -1, 7600, 7603, 7629, -1, 7630, 7607, 7631, -1, 7603, 7607, 7630, -1, 7631, 7605, 7632, -1, 7607, 7605, 7631, -1, 7632, 7601, 7633, -1, 7605, 7601, 7632, -1, 7633, 7598, 7608, -1, 7601, 7598, 7633, -1, 7620, 7621, 7619, -1, 7619, 7621, 7618, -1, 7618, 7621, 7617, -1, 7617, 7621, 7616, -1, 7616, 7621, 7615, -1, 7621, 7614, 7615, -1, 7622, 7623, 7621, -1, 7614, 7612, 7613, -1, 7621, 7612, 7614, -1, 7623, 7624, 7621, -1, 7621, 7611, 7612, -1, 7624, 7625, 7621, -1, 7621, 7610, 7611, -1, 7625, 7626, 7621, -1, 7621, 7609, 7610, -1, 7626, 7627, 7621, -1, 7627, 7628, 7621, -1, 7609, 7633, 7608, -1, 7621, 7633, 7609, -1, 7628, 7629, 7621, -1, 7621, 7632, 7633, -1, 7630, 7631, 7629, -1, 7629, 7631, 7621, -1, 7621, 7631, 7632, -1, 2711, 2718, 2987, -1, 2711, 2987, 7634, -1, 2705, 7634, 7635, -1, 2705, 2711, 7634, -1, 2690, 7635, 7636, -1, 2690, 2705, 7635, -1, 2696, 7636, 7637, -1, 2696, 2690, 7636, -1, 2707, 7637, 7638, -1, 2707, 2696, 7637, -1, 2714, 7638, 7639, -1, 2714, 2707, 7638, -1, 2721, 7639, 7640, -1, 2721, 2714, 7639, -1, 2802, 7640, 7641, -1, 2802, 2721, 7640, -1, 2821, 7641, 7642, -1, 2821, 2802, 7641, -1, 2819, 7642, 7643, -1, 2819, 2821, 7642, -1, 2817, 7643, 7644, -1, 2817, 2819, 7643, -1, 2829, 7644, 7645, -1, 2829, 2817, 7644, -1, 2831, 7645, 2974, -1, 2831, 2829, 7645, -1, 7646, 2983, 7647, -1, 2984, 2983, 7646, -1, 7648, 7644, 7643, -1, 7649, 7644, 7648, -1, 7636, 7650, 7637, -1, 7637, 7651, 7638, -1, 7650, 7651, 7637, -1, 7635, 7652, 7636, -1, 7636, 7652, 7650, -1, 7638, 7653, 7639, -1, 7651, 7653, 7638, -1, 7647, 2982, 7654, -1, 7654, 2982, 7655, -1, 7634, 7656, 7635, -1, 2983, 2982, 7647, -1, 7635, 7656, 7652, -1, 7639, 7657, 7640, -1, 7653, 7657, 7639, -1, 7658, 7645, 7649, -1, 2987, 7659, 7634, -1, 7649, 7645, 7644, -1, 7634, 7659, 7656, -1, 7655, 2981, 7660, -1, 2982, 2981, 7655, -1, 7640, 7661, 7641, -1, 7658, 2974, 7645, -1, 7657, 7661, 7640, -1, 7662, 2974, 7658, -1, 2986, 7663, 2987, -1, 2987, 7663, 7659, -1, 7660, 2980, 7664, -1, 2981, 2980, 7660, -1, 7665, 2975, 7662, -1, 7641, 7666, 7642, -1, 7662, 2975, 2974, -1, 7661, 7666, 7641, -1, 7664, 2979, 7667, -1, 2980, 2979, 7664, -1, 2985, 7668, 2986, -1, 2986, 7668, 7663, -1, 7669, 2976, 7665, -1, 7665, 2976, 2975, -1, 2979, 2978, 7667, -1, 7666, 7670, 7642, -1, 7667, 2977, 7671, -1, 7671, 2977, 7669, -1, 2978, 2977, 7667, -1, 2985, 7646, 7668, -1, 7669, 2977, 2976, -1, 2984, 7646, 2985, -1, 7670, 7643, 7642, -1, 7648, 7643, 7670, -1, 7662, 7658, 7672, -1, 7672, 7658, 7673, -1, 7673, 7649, 7674, -1, 7658, 7649, 7673, -1, 7674, 7648, 7675, -1, 7649, 7648, 7674, -1, 7675, 7670, 7676, -1, 7648, 7670, 7675, -1, 7676, 7666, 7677, -1, 7670, 7666, 7676, -1, 7677, 7661, 7678, -1, 7666, 7661, 7677, -1, 7678, 7657, 7679, -1, 7661, 7657, 7678, -1, 7679, 7653, 7680, -1, 7657, 7653, 7679, -1, 7680, 7651, 7681, -1, 7653, 7651, 7680, -1, 7681, 7650, 7682, -1, 7651, 7650, 7681, -1, 7682, 7652, 7683, -1, 7650, 7652, 7682, -1, 7683, 7656, 7684, -1, 7652, 7656, 7683, -1, 7684, 7659, 7685, -1, 7656, 7659, 7684, -1, 7659, 7663, 7685, -1, 7685, 7663, 7686, -1, 7686, 7668, 7687, -1, 7663, 7668, 7686, -1, 7687, 7646, 7688, -1, 7668, 7646, 7687, -1, 7688, 7647, 7689, -1, 7646, 7647, 7688, -1, 7689, 7654, 7690, -1, 7647, 7654, 7689, -1, 7690, 7655, 7691, -1, 7654, 7655, 7690, -1, 7691, 7660, 7692, -1, 7655, 7660, 7691, -1, 7692, 7664, 7693, -1, 7660, 7664, 7692, -1, 7693, 7667, 7694, -1, 7664, 7667, 7693, -1, 7694, 7671, 7695, -1, 7667, 7671, 7694, -1, 7695, 7669, 7696, -1, 7671, 7669, 7695, -1, 7696, 7665, 7697, -1, 7669, 7665, 7696, -1, 7697, 7662, 7672, -1, 7665, 7662, 7697, -1, 7681, 7679, 7680, -1, 7684, 7685, 7683, -1, 7683, 7685, 7682, -1, 7682, 7685, 7681, -1, 7681, 7685, 7679, -1, 7685, 7678, 7679, -1, 7685, 7677, 7678, -1, 7686, 7687, 7685, -1, 7685, 7676, 7677, -1, 7685, 7675, 7676, -1, 7688, 7689, 7687, -1, 7687, 7689, 7685, -1, 7675, 7673, 7674, -1, 7685, 7673, 7675, -1, 7690, 7691, 7689, -1, 7689, 7691, 7685, -1, 7691, 7692, 7685, -1, 7673, 7697, 7672, -1, 7685, 7697, 7673, -1, 7685, 7696, 7697, -1, 7693, 7694, 7692, -1, 7692, 7694, 7685, -1, 7685, 7694, 7696, -1, 7694, 7695, 7696, -1, 2913, 2917, 2973, -1, 2913, 2973, 7698, -1, 2911, 7698, 7699, -1, 2911, 2913, 7698, -1, 2909, 7699, 7700, -1, 2909, 2911, 7699, -1, 2910, 7700, 7701, -1, 2910, 2909, 7700, -1, 2912, 7701, 7702, -1, 2912, 2910, 7701, -1, 2914, 7702, 7703, -1, 2914, 2912, 7702, -1, 2715, 7703, 7704, -1, 2715, 2914, 7703, -1, 2708, 7704, 7705, -1, 2708, 2715, 7704, -1, 2697, 7705, 7706, -1, 2697, 2708, 7705, -1, 2691, 7706, 7707, -1, 2691, 2697, 7706, -1, 2689, 7707, 7708, -1, 2689, 2691, 7707, -1, 2712, 7708, 7709, -1, 2712, 2689, 7708, -1, 2713, 7709, 2960, -1, 2713, 2712, 7709, -1, 7710, 2969, 7711, -1, 2970, 2969, 7710, -1, 7712, 7708, 7707, -1, 7700, 7713, 7701, -1, 7714, 7708, 7712, -1, 7701, 7715, 7702, -1, 7713, 7715, 7701, -1, 7699, 7716, 7700, -1, 7700, 7716, 7713, -1, 7711, 2968, 7717, -1, 7702, 7718, 7703, -1, 7717, 2968, 7719, -1, 7715, 7718, 7702, -1, 2969, 2968, 7711, -1, 7698, 7720, 7699, -1, 7699, 7720, 7716, -1, 7721, 7709, 7714, -1, 7703, 7722, 7704, -1, 7714, 7709, 7708, -1, 7718, 7722, 7703, -1, 7719, 2967, 7723, -1, 2968, 2967, 7719, -1, 2973, 7724, 7698, -1, 7698, 7724, 7720, -1, 7721, 2960, 7709, -1, 7725, 2960, 7726, -1, 7726, 2960, 7721, -1, 7723, 2966, 7727, -1, 7704, 7728, 7705, -1, 2967, 2966, 7723, -1, 7722, 7728, 7704, -1, 2972, 7729, 2973, -1, 2973, 7729, 7724, -1, 7725, 2961, 2960, -1, 7727, 2965, 7730, -1, 2966, 2965, 7727, -1, 7705, 7731, 7706, -1, 7732, 2962, 7725, -1, 7725, 2962, 2961, -1, 7728, 7731, 7705, -1, 2971, 7733, 2972, -1, 2965, 2964, 7730, -1, 2972, 7733, 7729, -1, 7730, 2963, 7734, -1, 7734, 2963, 7732, -1, 2964, 2963, 7730, -1, 7732, 2963, 2962, -1, 7731, 7735, 7706, -1, 2971, 7710, 7733, -1, 2970, 7710, 2971, -1, 7735, 7707, 7706, -1, 7712, 7707, 7735, -1, 7726, 7721, 7736, -1, 7736, 7721, 7737, -1, 7737, 7714, 7738, -1, 7721, 7714, 7737, -1, 7738, 7712, 7739, -1, 7714, 7712, 7738, -1, 7739, 7735, 7740, -1, 7712, 7735, 7739, -1, 7740, 7731, 7741, -1, 7735, 7731, 7740, -1, 7741, 7728, 7742, -1, 7731, 7728, 7741, -1, 7742, 7722, 7743, -1, 7728, 7722, 7742, -1, 7743, 7718, 7744, -1, 7722, 7718, 7743, -1, 7744, 7715, 7745, -1, 7718, 7715, 7744, -1, 7745, 7713, 7746, -1, 7715, 7713, 7745, -1, 7746, 7716, 7747, -1, 7713, 7716, 7746, -1, 7747, 7720, 7748, -1, 7716, 7720, 7747, -1, 7748, 7724, 7749, -1, 7720, 7724, 7748, -1, 7724, 7729, 7749, -1, 7749, 7729, 7750, -1, 7750, 7733, 7751, -1, 7729, 7733, 7750, -1, 7751, 7710, 7752, -1, 7733, 7710, 7751, -1, 7752, 7711, 7753, -1, 7710, 7711, 7752, -1, 7753, 7717, 7754, -1, 7711, 7717, 7753, -1, 7754, 7719, 7755, -1, 7717, 7719, 7754, -1, 7755, 7723, 7756, -1, 7719, 7723, 7755, -1, 7756, 7727, 7757, -1, 7723, 7727, 7756, -1, 7757, 7730, 7758, -1, 7727, 7730, 7757, -1, 7758, 7734, 7759, -1, 7730, 7734, 7758, -1, 7759, 7732, 7760, -1, 7734, 7732, 7759, -1, 7760, 7725, 7761, -1, 7732, 7725, 7760, -1, 7761, 7726, 7736, -1, 7725, 7726, 7761, -1, 7748, 7749, 7747, -1, 7747, 7749, 7746, -1, 7746, 7749, 7745, -1, 7745, 7749, 7744, -1, 7744, 7749, 7743, -1, 7749, 7742, 7743, -1, 7749, 7741, 7742, -1, 7750, 7751, 7749, -1, 7749, 7740, 7741, -1, 7749, 7739, 7740, -1, 7752, 7753, 7751, -1, 7751, 7753, 7749, -1, 7753, 7754, 7749, -1, 7739, 7737, 7738, -1, 7754, 7755, 7749, -1, 7755, 7756, 7749, -1, 7737, 7761, 7736, -1, 7739, 7761, 7737, -1, 7761, 7758, 7760, -1, 7757, 7758, 7756, -1, 7749, 7758, 7739, -1, 7756, 7758, 7749, -1, 7739, 7758, 7761, -1, 7758, 7759, 7760, -1, 2843, 2849, 2959, -1, 2843, 2959, 7762, -1, 2838, 7762, 7763, -1, 2838, 2843, 7762, -1, 2833, 7763, 7764, -1, 2833, 2838, 7763, -1, 2835, 7764, 7765, -1, 2835, 2833, 7764, -1, 2839, 7765, 7766, -1, 2839, 2835, 7765, -1, 2847, 7766, 7767, -1, 2847, 2839, 7766, -1, 2854, 7767, 7768, -1, 2854, 2847, 7767, -1, 2860, 7768, 7769, -1, 2860, 2854, 7768, -1, 2862, 7769, 7770, -1, 2862, 2860, 7769, -1, 2864, 7770, 7771, -1, 2864, 2862, 7770, -1, 2872, 7771, 7772, -1, 2872, 2864, 7771, -1, 2879, 7772, 7773, -1, 2879, 2872, 7772, -1, 2888, 7773, 2946, -1, 2888, 2879, 7773, -1, 7774, 2955, 7775, -1, 2956, 2955, 7774, -1, 7776, 7772, 7771, -1, 7764, 7777, 7765, -1, 7778, 7772, 7776, -1, 7765, 7779, 7766, -1, 7777, 7779, 7765, -1, 7763, 7780, 7764, -1, 7764, 7780, 7777, -1, 7775, 2954, 7781, -1, 7766, 7782, 7767, -1, 7781, 2954, 7783, -1, 7779, 7782, 7766, -1, 2955, 2954, 7775, -1, 7762, 7784, 7763, -1, 7763, 7784, 7780, -1, 7785, 7773, 7778, -1, 7767, 7786, 7768, -1, 7778, 7773, 7772, -1, 7782, 7786, 7767, -1, 7783, 2953, 7787, -1, 2954, 2953, 7783, -1, 2959, 7788, 7762, -1, 7762, 7788, 7784, -1, 7785, 2946, 7773, -1, 7789, 2946, 7790, -1, 7790, 2946, 7785, -1, 7787, 2952, 7791, -1, 7768, 7792, 7769, -1, 2953, 2952, 7787, -1, 7786, 7792, 7768, -1, 2958, 7793, 2959, -1, 2959, 7793, 7788, -1, 7789, 2947, 2946, -1, 7791, 2951, 7794, -1, 2952, 2951, 7791, -1, 7769, 7795, 7770, -1, 7796, 2948, 7789, -1, 7789, 2948, 2947, -1, 7792, 7795, 7769, -1, 2957, 7797, 2958, -1, 2951, 2950, 7794, -1, 2958, 7797, 7793, -1, 7794, 2949, 7798, -1, 7798, 2949, 7796, -1, 2950, 2949, 7794, -1, 7796, 2949, 2948, -1, 7795, 7799, 7770, -1, 2957, 7774, 7797, -1, 2956, 7774, 2957, -1, 7799, 7771, 7770, -1, 7776, 7771, 7799, -1, 7790, 7785, 7800, -1, 7800, 7785, 7801, -1, 7801, 7778, 7802, -1, 7785, 7778, 7801, -1, 7802, 7776, 7803, -1, 7778, 7776, 7802, -1, 7803, 7799, 7804, -1, 7776, 7799, 7803, -1, 7804, 7795, 7805, -1, 7799, 7795, 7804, -1, 7805, 7792, 7806, -1, 7795, 7792, 7805, -1, 7806, 7786, 7807, -1, 7792, 7786, 7806, -1, 7807, 7782, 7808, -1, 7786, 7782, 7807, -1, 7808, 7779, 7809, -1, 7782, 7779, 7808, -1, 7809, 7777, 7810, -1, 7779, 7777, 7809, -1, 7810, 7780, 7811, -1, 7777, 7780, 7810, -1, 7811, 7784, 7812, -1, 7780, 7784, 7811, -1, 7812, 7788, 7813, -1, 7784, 7788, 7812, -1, 7788, 7793, 7813, -1, 7813, 7793, 7814, -1, 7814, 7797, 7815, -1, 7793, 7797, 7814, -1, 7815, 7774, 7816, -1, 7797, 7774, 7815, -1, 7816, 7775, 7817, -1, 7774, 7775, 7816, -1, 7817, 7781, 7818, -1, 7775, 7781, 7817, -1, 7818, 7783, 7819, -1, 7781, 7783, 7818, -1, 7819, 7787, 7820, -1, 7783, 7787, 7819, -1, 7820, 7791, 7821, -1, 7787, 7791, 7820, -1, 7821, 7794, 7822, -1, 7791, 7794, 7821, -1, 7822, 7798, 7823, -1, 7794, 7798, 7822, -1, 7823, 7796, 7824, -1, 7798, 7796, 7823, -1, 7824, 7789, 7825, -1, 7796, 7789, 7824, -1, 7825, 7790, 7800, -1, 7789, 7790, 7825, -1, 7812, 7813, 7811, -1, 7811, 7813, 7810, -1, 7810, 7813, 7809, -1, 7809, 7813, 7808, -1, 7808, 7813, 7807, -1, 7813, 7806, 7807, -1, 7813, 7805, 7806, -1, 7814, 7815, 7813, -1, 7813, 7804, 7805, -1, 7813, 7803, 7804, -1, 7816, 7817, 7815, -1, 7815, 7817, 7813, -1, 7817, 7818, 7813, -1, 7803, 7801, 7802, -1, 7818, 7819, 7813, -1, 7819, 7820, 7813, -1, 7801, 7825, 7800, -1, 7803, 7825, 7801, -1, 7825, 7822, 7824, -1, 7821, 7822, 7820, -1, 7813, 7822, 7803, -1, 7820, 7822, 7813, -1, 7803, 7822, 7825, -1, 7822, 7823, 7824, -1, 2334, 2183, 2178, -1, 7826, 2178, 2169, -1, 7826, 2334, 2178, -1, 7827, 2169, 2133, -1, 7827, 7826, 2169, -1, 7828, 2133, 2132, -1, 7828, 7827, 2133, -1, 7829, 2132, 2131, -1, 7829, 7828, 2132, -1, 7830, 2131, 2130, -1, 7830, 7829, 2131, -1, 7831, 2130, 2134, -1, 7831, 7830, 2130, -1, 7832, 2134, 2135, -1, 7832, 7831, 2134, -1, 7833, 2135, 1961, -1, 7833, 7832, 2135, -1, 7834, 1961, 1960, -1, 7834, 7833, 1961, -1, 7835, 1960, 1959, -1, 7835, 7834, 1960, -1, 7836, 1959, 1958, -1, 7836, 7835, 1959, -1, 7837, 1958, 1955, -1, 7837, 7836, 1958, -1, 2322, 7837, 1955, -1, 7838, 2320, 2018, -1, 7838, 2018, 2008, -1, 7839, 2008, 2000, -1, 7839, 7838, 2008, -1, 7840, 2000, 1996, -1, 7840, 7839, 2000, -1, 7841, 1996, 1999, -1, 7841, 7840, 1996, -1, 7842, 1999, 2002, -1, 7842, 7841, 1999, -1, 7843, 2002, 2013, -1, 7843, 7842, 2002, -1, 7844, 2013, 2020, -1, 7844, 7843, 2013, -1, 7845, 2020, 2034, -1, 7845, 7844, 2020, -1, 7846, 2034, 2046, -1, 7846, 7845, 2034, -1, 7847, 2046, 2053, -1, 7847, 7846, 2046, -1, 7848, 2053, 2082, -1, 7848, 7847, 2053, -1, 7849, 2082, 2079, -1, 7849, 7848, 2082, -1, 2308, 2079, 2081, -1, 2308, 7849, 2079, -1, 7850, 2306, 2158, -1, 7850, 2158, 2155, -1, 7851, 2155, 2149, -1, 7851, 7850, 2155, -1, 7852, 2149, 2144, -1, 7852, 7851, 2149, -1, 7853, 2144, 2124, -1, 7853, 7852, 2144, -1, 7854, 2124, 2123, -1, 7854, 7853, 2124, -1, 7855, 2123, 2122, -1, 7855, 7854, 2123, -1, 7856, 2122, 2125, -1, 7856, 7855, 2122, -1, 7857, 2125, 2126, -1, 7857, 7856, 2125, -1, 7858, 2126, 2127, -1, 7858, 7857, 2126, -1, 7859, 2127, 2128, -1, 7859, 7858, 2127, -1, 7860, 2128, 2172, -1, 7860, 7859, 2128, -1, 7861, 2172, 2179, -1, 7861, 7860, 2172, -1, 2294, 2179, 2180, -1, 2294, 7861, 2179, -1, 2292, 1922, 2200, -1, 7862, 2200, 2195, -1, 7862, 2292, 2200, -1, 7863, 2195, 2192, -1, 7863, 7862, 2195, -1, 7864, 2192, 2194, -1, 7864, 7863, 2192, -1, 7865, 2194, 2198, -1, 7865, 7864, 2194, -1, 7866, 2198, 2203, -1, 7866, 7865, 2198, -1, 7867, 2203, 1932, -1, 7867, 7866, 2203, -1, 7868, 1932, 1931, -1, 7868, 7867, 1932, -1, 7869, 1931, 1944, -1, 7869, 7868, 1931, -1, 7870, 1944, 1965, -1, 7870, 7869, 1944, -1, 7871, 1965, 1997, -1, 7871, 7870, 1965, -1, 7872, 1997, 2009, -1, 7872, 7871, 1997, -1, 7873, 2009, 2010, -1, 7873, 7872, 2009, -1, 2280, 7873, 2010, -1, 7874, 7875, 7876, -1, 7877, 7878, 7879, -1, 7880, 7881, 7882, -1, 7880, 7882, 7874, -1, 5257, 7883, 7884, -1, 5257, 7885, 7883, -1, 4102, 7886, 7887, -1, 4102, 7888, 7889, -1, 4102, 7890, 7888, -1, 7891, 7892, 7893, -1, 4102, 5257, 7884, -1, 7891, 7893, 7894, -1, 4102, 7884, 7886, -1, 4102, 7887, 7890, -1, 7895, 7896, 7892, -1, 7897, 7898, 7881, -1, 7897, 7881, 7880, -1, 7895, 7892, 7891, -1, 7899, 7877, 7896, -1, 7899, 7896, 7895, -1, 7900, 7877, 7899, -1, 7901, 5253, 2268, -1, 7902, 7903, 7904, -1, 7905, 2269, 2270, -1, 7905, 2268, 2269, -1, 7905, 7901, 2268, -1, 7906, 5253, 7901, -1, 7907, 7903, 7902, -1, 7906, 7130, 5253, -1, 7908, 7907, 7902, -1, 7909, 7907, 7908, -1, 7910, 7909, 7908, -1, 7911, 7905, 2270, -1, 7912, 7130, 7906, -1, 7913, 7910, 7914, -1, 7913, 7909, 7910, -1, 7915, 7913, 7914, -1, 7916, 2270, 2271, -1, 7916, 7911, 2270, -1, 7917, 7918, 7919, -1, 7920, 7921, 7898, -1, 7922, 7915, 7918, -1, 7920, 7897, 7923, -1, 7920, 7924, 7925, -1, 7920, 7925, 7926, -1, 7920, 7926, 7927, -1, 7920, 7927, 7928, -1, 7922, 7918, 7917, -1, 2252, 7130, 7912, -1, 7920, 7928, 7929, -1, 7920, 7929, 7921, -1, 7930, 7913, 7915, -1, 7930, 7915, 7922, -1, 7920, 7898, 7897, -1, 7931, 7920, 7923, -1, 7932, 7878, 7877, -1, 7932, 7877, 7900, -1, 7933, 2272, 2273, -1, 7933, 2271, 2272, -1, 7934, 7931, 7923, -1, 7935, 7878, 7932, -1, 7936, 7931, 7934, -1, 7933, 7916, 2271, -1, 7937, 7936, 7934, -1, 7938, 7878, 7935, -1, 7939, 7936, 7937, -1, 7940, 7939, 7937, -1, 7941, 7878, 7938, -1, 7942, 7939, 7940, -1, 7943, 7878, 7941, -1, 2251, 7130, 2252, -1, 7944, 7913, 7930, -1, 7945, 7933, 2273, -1, 7870, 2296, 2297, -1, 7946, 7944, 7930, -1, 7946, 7947, 7948, -1, 7946, 7948, 7949, -1, 7946, 7949, 7950, -1, 7870, 7871, 2296, -1, 7946, 7950, 7951, -1, 7946, 7951, 7952, -1, 7946, 7952, 7944, -1, 2253, 7130, 2251, -1, 7953, 2274, 2275, -1, 7953, 2273, 2274, -1, 5112, 7943, 7954, -1, 7953, 7945, 2273, -1, 5112, 7878, 7943, -1, 2254, 7130, 2253, -1, 7955, 7956, 7946, -1, 7869, 7870, 2297, -1, 7869, 2297, 2298, -1, 7957, 7946, 7956, -1, 7958, 7953, 2275, -1, 2255, 7130, 2254, -1, 7959, 7955, 7946, -1, 7960, 7946, 7957, -1, 7961, 7959, 7946, -1, 7962, 7946, 7960, -1, 7963, 7961, 7946, -1, 7868, 7869, 2298, -1, 7868, 2298, 2299, -1, 7964, 7946, 7962, -1, 5258, 7965, 7966, -1, 7967, 7968, 7969, -1, 5258, 7970, 7965, -1, 5258, 7971, 7970, -1, 5258, 7972, 7971, -1, 5258, 2236, 7972, -1, 5258, 2235, 2236, -1, 5258, 2234, 2235, -1, 5258, 2233, 2234, -1, 7973, 7946, 7964, -1, 4111, 4102, 7889, -1, 7974, 7969, 7975, -1, 4111, 7889, 7976, -1, 4111, 7976, 7977, -1, 7974, 7967, 7969, -1, 7978, 7946, 7973, -1, 7979, 7975, 7980, -1, 7979, 7974, 7975, -1, 7867, 7868, 2299, -1, 7867, 2299, 2300, -1, 7981, 7979, 7980, -1, 7981, 7980, 7982, -1, 7981, 7982, 7983, -1, 7984, 2263, 2264, -1, 7984, 2262, 2263, -1, 7984, 2261, 2262, -1, 7984, 2260, 2261, -1, 7984, 2259, 2260, -1, 7984, 2258, 2259, -1, 7984, 2257, 2258, -1, 7984, 2256, 2257, -1, 7984, 2255, 2256, -1, 7866, 7867, 2300, -1, 7866, 2300, 2301, -1, 7865, 2301, 2302, -1, 4653, 7947, 7946, -1, 7985, 2227, 2228, -1, 7865, 7866, 2301, -1, 4653, 7954, 7986, -1, 7985, 2226, 2227, -1, 4653, 7986, 7947, -1, 4653, 5112, 7954, -1, 4653, 7978, 7987, -1, 7985, 7988, 2226, -1, 4653, 7946, 7978, -1, 7864, 2302, 2303, -1, 5248, 7987, 7989, -1, 5248, 7989, 7990, -1, 7864, 7865, 2302, -1, 5248, 4653, 7987, -1, 7991, 7992, 7993, -1, 7991, 7993, 7994, -1, 7995, 7985, 2228, -1, 7991, 7994, 7996, -1, 7991, 7996, 7997, -1, 7991, 7997, 7998, -1, 7991, 7998, 7963, -1, 7991, 7999, 7992, -1, 8000, 7995, 2228, -1, 8000, 2228, 2229, -1, 8001, 2229, 2230, -1, 8001, 8000, 2229, -1, 8002, 2231, 2232, -1, 8002, 2230, 2231, -1, 8003, 8004, 8005, -1, 8003, 8005, 8006, -1, 8002, 8001, 2230, -1, 5253, 4653, 5248, -1, 8007, 8002, 2232, -1, 8008, 8009, 8004, -1, 8010, 2280, 2279, -1, 8010, 2279, 2281, -1, 8008, 8004, 8003, -1, 8010, 2281, 2282, -1, 8010, 2282, 2283, -1, 8010, 2283, 2284, -1, 8010, 2284, 2285, -1, 8010, 2285, 2286, -1, 8011, 7991, 8009, -1, 8010, 2286, 2287, -1, 8012, 2232, 2233, -1, 8010, 2287, 2288, -1, 8012, 2233, 5258, -1, 8011, 8009, 8008, -1, 8012, 8007, 2232, -1, 8013, 7991, 8011, -1, 8014, 8012, 5258, -1, 8015, 8016, 8017, -1, 8015, 8017, 8018, -1, 8019, 8017, 8016, -1, 8019, 8020, 8021, -1, 8019, 8021, 8017, -1, 8022, 8023, 8024, -1, 8025, 8020, 8019, -1, 8026, 8023, 8022, -1, 8025, 7983, 8020, -1, 8027, 7983, 8025, -1, 8028, 8026, 8022, -1, 8029, 8026, 8028, -1, 8030, 8029, 8028, -1, 8031, 8029, 8030, -1, 8032, 8031, 8030, -1, 8033, 2245, 2246, -1, 8033, 2244, 2245, -1, 8033, 2243, 2244, -1, 8033, 2242, 2243, -1, 8033, 2241, 2242, -1, 8033, 2240, 2241, -1, 8033, 2239, 2240, -1, 8033, 2237, 2239, -1, 8034, 7999, 7991, -1, 8033, 2238, 2237, -1, 8034, 8035, 7999, -1, 8034, 7991, 8013, -1, 8036, 8035, 8034, -1, 8036, 8037, 8035, -1, 7141, 8038, 8014, -1, 7141, 2250, 8038, -1, 7141, 2249, 2250, -1, 7141, 2248, 2249, -1, 8039, 8037, 8036, -1, 7141, 8014, 5258, -1, 8040, 7983, 8027, -1, 7141, 2247, 2248, -1, 7141, 2246, 2247, -1, 8039, 8041, 8037, -1, 8040, 7981, 7983, -1, 8042, 8040, 8027, -1, 8043, 8041, 8039, -1, 8044, 8040, 8042, -1, 8043, 8045, 8041, -1, 8046, 8040, 8044, -1, 8047, 7116, 7137, -1, 8048, 8046, 8044, -1, 8047, 7137, 8049, -1, 8050, 8045, 8043, -1, 8051, 8046, 8048, -1, 8052, 8051, 8048, -1, 8053, 8051, 8052, -1, 8054, 8053, 8052, -1, 7834, 7835, 7121, -1, 7836, 7121, 7835, -1, 7833, 7834, 8055, -1, 8056, 8031, 8032, -1, 7837, 7121, 7836, -1, 7832, 7833, 8055, -1, 2322, 7121, 7837, -1, 4081, 2288, 2289, -1, 4081, 2289, 2290, -1, 4081, 2290, 2291, -1, 4081, 2291, 2292, -1, 4081, 2304, 7126, -1, 4081, 2292, 7862, -1, 7831, 7832, 8055, -1, 4081, 7862, 7863, -1, 4081, 7863, 7864, -1, 4081, 2303, 2304, -1, 4081, 8010, 2288, -1, 2321, 7121, 2322, -1, 4081, 7864, 2303, -1, 7830, 7831, 8055, -1, 2323, 7121, 2321, -1, 7829, 7830, 8055, -1, 7828, 7829, 8055, -1, 7827, 7828, 8055, -1, 8057, 8058, 8059, -1, 8057, 8060, 8058, -1, 8061, 8062, 5253, -1, 8061, 5253, 8063, -1, 8064, 5253, 8062, -1, 8065, 8057, 8059, -1, 8066, 8061, 8063, -1, 7826, 7827, 8055, -1, 8065, 8059, 8067, -1, 8068, 5253, 8064, -1, 8069, 8065, 8067, -1, 8069, 8067, 8070, -1, 8071, 8066, 8063, -1, 8072, 8069, 8070, -1, 8072, 8070, 8073, -1, 2266, 5253, 8068, -1, 2334, 7826, 8055, -1, 8074, 8071, 8063, -1, 4103, 4082, 4081, -1, 2265, 5253, 2266, -1, 8075, 8074, 8063, -1, 8076, 8077, 8078, -1, 2267, 5253, 2265, -1, 8079, 8078, 8080, -1, 8081, 8075, 8063, -1, 8079, 8076, 8078, -1, 2268, 5253, 2267, -1, 8082, 8073, 8077, -1, 8082, 8077, 8076, -1, 8083, 8080, 8084, -1, 8085, 8081, 8063, -1, 8083, 8079, 8080, -1, 8086, 8072, 8073, -1, 8086, 8073, 8082, -1, 8087, 8085, 8063, -1, 8088, 8072, 8086, -1, 7125, 8089, 8090, -1, 8091, 8072, 8088, -1, 8092, 8087, 8063, -1, 8093, 8056, 8032, -1, 8094, 8095, 4082, -1, 7125, 8090, 7142, -1, 7858, 7859, 8096, -1, 8097, 8072, 8091, -1, 7860, 8096, 7859, -1, 8098, 8094, 4082, -1, 8098, 4082, 4103, -1, 8099, 8072, 8097, -1, 7857, 7858, 8096, -1, 8100, 8098, 4103, -1, 7861, 8096, 7860, -1, 8101, 8072, 8099, -1, 2278, 8092, 8063, -1, 7856, 7857, 8096, -1, 8102, 8072, 8101, -1, 8103, 8072, 8102, -1, 4073, 7121, 2323, -1, 4073, 2323, 2324, -1, 2294, 8096, 7861, -1, 8104, 8105, 8106, -1, 7855, 7856, 8096, -1, 8107, 8105, 8104, -1, 8107, 8108, 8105, -1, 7854, 7855, 8096, -1, 8109, 8108, 8107, -1, 8110, 8111, 8112, -1, 8110, 8113, 8111, -1, 8110, 8103, 8113, -1, 8110, 8100, 4103, -1, 8109, 8114, 8108, -1, 8110, 8115, 8100, -1, 8110, 8116, 8115, -1, 8110, 8117, 8116, -1, 7853, 7854, 8096, -1, 8110, 8118, 8117, -1, 8110, 8119, 8118, -1, 8110, 8120, 8119, -1, 8110, 8112, 8120, -1, 8121, 8114, 8109, -1, 8122, 8123, 8110, -1, 8121, 8093, 8114, -1, 8124, 8110, 8123, -1, 8125, 8122, 8110, -1, 8126, 8110, 8124, -1, 7847, 4073, 2324, -1, 7847, 2324, 2325, -1, 8127, 8110, 4103, -1, 7846, 7847, 2325, -1, 8127, 8125, 8110, -1, 8128, 8129, 8130, -1, 8131, 8128, 8130, -1, 7846, 2325, 2326, -1, 8132, 8110, 8126, -1, 7848, 4073, 7847, -1, 8133, 8127, 4103, -1, 8134, 4103, 4113, -1, 8135, 8128, 8131, -1, 8134, 8133, 4103, -1, 8136, 8135, 8131, -1, 8137, 8134, 4113, -1, 7845, 7846, 2326, -1, 7845, 2326, 2327, -1, 8138, 8135, 8136, -1, 7849, 4073, 7848, -1, 8139, 8138, 8136, -1, 7844, 7845, 2327, -1, 8140, 8138, 8139, -1, 7844, 2327, 2328, -1, 8141, 8110, 8132, -1, 8142, 8093, 8121, -1, 2308, 4073, 7849, -1, 8142, 8056, 8093, -1, 8143, 8056, 8142, -1, 7843, 7844, 2328, -1, 8143, 8144, 8056, -1, 7843, 2328, 2329, -1, 8145, 8146, 8147, -1, 8148, 8147, 8141, -1, 8148, 8145, 8147, -1, 8149, 8144, 8143, -1, 2307, 4073, 2308, -1, 8150, 8148, 8141, -1, 8149, 8151, 8144, -1, 8152, 8141, 8132, -1, 8152, 8150, 8141, -1, 8153, 8150, 8152, -1, 8154, 8151, 8149, -1, 8155, 8153, 8152, -1, 8154, 8156, 8151, -1, 7842, 7843, 2329, -1, 8157, 8153, 8155, -1, 8158, 8157, 8155, -1, 7842, 2329, 2330, -1, 8159, 8157, 8158, -1, 8160, 8156, 8154, -1, 8161, 8159, 8158, -1, 8160, 8162, 8156, -1, 8163, 8159, 8161, -1, 8164, 8163, 8161, -1, 7126, 2304, 2305, -1, 7126, 2305, 2306, -1, 7126, 2306, 7850, -1, 7126, 7850, 7851, -1, 7126, 7851, 7852, -1, 7126, 7852, 7853, -1, 8165, 8140, 8139, -1, 2309, 4073, 2307, -1, 7841, 7842, 2330, -1, 7841, 2330, 2331, -1, 4077, 4651, 4073, -1, 2310, 4073, 2309, -1, 8166, 8167, 8168, -1, 7840, 7841, 2331, -1, 8166, 8169, 8167, -1, 8170, 8166, 8168, -1, 8170, 8168, 8171, -1, 8172, 8173, 8139, -1, 2311, 4073, 2310, -1, 8174, 8171, 8175, -1, 8176, 8139, 8173, -1, 8174, 8170, 8171, -1, 8177, 8175, 8178, -1, 8177, 8174, 8175, -1, 8179, 8172, 8139, -1, 8180, 8177, 8178, -1, 8180, 8137, 4113, -1, 8180, 8181, 8137, -1, 8180, 8182, 8181, -1, 8180, 8183, 8182, -1, 8180, 8178, 8183, -1, 8184, 8139, 8176, -1, 8185, 8177, 8180, -1, 4081, 4073, 8186, -1, 4081, 8186, 8010, -1, 4077, 4082, 8187, -1, 8187, 4082, 8188, -1, 8188, 4082, 8018, -1, 8018, 4082, 8189, -1, 8189, 4082, 8190, -1, 8190, 4082, 8191, -1, 8192, 8179, 8139, -1, 8191, 4082, 8193, -1, 8193, 4082, 8084, -1, 8084, 4082, 8083, -1, 8083, 4082, 8194, -1, 8194, 4082, 8095, -1, 4077, 8187, 8195, -1, 8018, 8189, 8015, -1, 4077, 8195, 8196, -1, 4077, 8196, 8197, -1, 4077, 8197, 8198, -1, 4077, 8198, 8199, -1, 8200, 8139, 8184, -1, 4077, 8199, 8201, -1, 8063, 7984, 2278, -1, 2278, 7984, 2277, -1, 2277, 7984, 2276, -1, 2276, 7984, 2275, -1, 2275, 7984, 2264, -1, 2275, 2264, 8202, -1, 2275, 8202, 8203, -1, 2275, 8203, 7958, -1, 8033, 7966, 2238, -1, 2238, 7966, 8204, -1, 8204, 7966, 8205, -1, 8205, 7966, 7988, -1, 7988, 7966, 2223, -1, 7988, 2223, 2224, -1, 7988, 2224, 2225, -1, 8206, 8165, 8139, -1, 7988, 2225, 2226, -1, 8206, 8139, 8200, -1, 8055, 8186, 2334, -1, 2334, 8186, 2333, -1, 2333, 8186, 2332, -1, 2332, 8186, 2331, -1, 2331, 8186, 2320, -1, 2331, 2320, 7838, -1, 2331, 7838, 7839, -1, 2331, 7839, 7840, -1, 8010, 8096, 2294, -1, 8010, 2294, 2293, -1, 8010, 2293, 2295, -1, 8010, 2295, 2296, -1, 8010, 2296, 2280, -1, 2280, 2296, 7873, -1, 7873, 2296, 7872, -1, 7872, 2296, 7871, -1, 7920, 8207, 7924, -1, 8208, 7878, 5112, -1, 8208, 5112, 5113, -1, 7946, 7991, 7963, -1, 8209, 8165, 8206, -1, 8139, 7887, 8192, -1, 8209, 8210, 8165, -1, 7977, 8180, 4111, -1, 4111, 8180, 4113, -1, 8110, 8072, 8103, -1, 7141, 7130, 7984, -1, 7984, 7130, 2255, -1, 7141, 7984, 8033, -1, 8186, 4073, 2311, -1, 7141, 8033, 2246, -1, 7137, 7142, 8090, -1, 7137, 8090, 8049, -1, 8186, 2311, 2312, -1, 8186, 2312, 2313, -1, 8186, 2313, 2314, -1, 8186, 2314, 2315, -1, 7125, 7116, 8047, -1, 8186, 2315, 2316, -1, 7125, 8047, 8089, -1, 8211, 8210, 8209, -1, 8186, 2316, 2317, -1, 7121, 7126, 8096, -1, 8211, 8212, 8210, -1, 8186, 2317, 2318, -1, 8096, 7126, 7853, -1, 8186, 2318, 2319, -1, 7121, 8096, 8055, -1, 8186, 2319, 2320, -1, 7121, 8055, 7834, -1, 5257, 5248, 8213, -1, 8213, 5248, 8214, -1, 8214, 5248, 8050, -1, 8050, 5248, 8045, -1, 8045, 5248, 8215, -1, 8215, 5248, 7990, -1, 5257, 8213, 8216, -1, 5257, 8216, 8217, -1, 5257, 8217, 8162, -1, 5257, 8162, 8218, -1, 8218, 8162, 8160, -1, 5257, 8218, 8219, -1, 5257, 8219, 8220, -1, 8221, 8212, 8211, -1, 5257, 8220, 8222, -1, 5257, 8222, 8223, -1, 8221, 8224, 8212, -1, 5257, 8223, 8225, -1, 5257, 8225, 8226, -1, 5257, 8226, 7885, -1, 5253, 5258, 8063, -1, 8063, 5258, 7966, -1, 4651, 4653, 5253, -1, 8227, 8208, 5113, -1, 4651, 5253, 7130, -1, 4651, 7130, 7137, -1, 4651, 7137, 7116, -1, 4651, 7116, 7121, -1, 8227, 8228, 8208, -1, 4651, 7121, 4073, -1, 4102, 4103, 7126, -1, 7126, 4103, 4081, -1, 8229, 8208, 8228, -1, 4102, 7126, 7125, -1, 4102, 7125, 7142, -1, 8225, 8224, 8221, -1, 4102, 7142, 7141, -1, 8225, 8223, 8224, -1, 4102, 7141, 5258, -1, 4102, 5258, 5257, -1, 8230, 5113, 4651, -1, 8230, 8227, 5113, -1, 8231, 8208, 8229, -1, 8232, 8230, 4651, -1, 8233, 8208, 8231, -1, 8234, 8232, 4651, -1, 7887, 8235, 8192, -1, 7887, 8236, 8235, -1, 7887, 8237, 8236, -1, 7887, 8238, 8237, -1, 7887, 8239, 8238, -1, 7887, 8240, 8239, -1, 7887, 8241, 8240, -1, 7887, 8242, 8241, -1, 7887, 8243, 8242, -1, 7887, 7886, 8243, -1, 8244, 8208, 8233, -1, 8244, 8233, 8245, -1, 8244, 8246, 8208, -1, 8247, 8244, 8245, -1, 8248, 8247, 8245, -1, 8249, 8247, 8248, -1, 8250, 8249, 8248, -1, 8251, 8249, 8250, -1, 8252, 8253, 8254, -1, 8252, 8255, 8253, -1, 8256, 8251, 8250, -1, 8257, 8251, 8256, -1, 8258, 8259, 8255, -1, 8258, 8255, 8252, -1, 8260, 8261, 8262, -1, 8263, 8264, 8261, -1, 8263, 8261, 8260, -1, 8265, 8266, 8264, -1, 8265, 8264, 8263, -1, 8267, 8258, 8268, -1, 8267, 8268, 8266, -1, 8267, 8259, 8258, -1, 8267, 8266, 8265, -1, 8269, 8270, 8271, -1, 8272, 8271, 8273, -1, 8272, 8269, 8271, -1, 8274, 8275, 8276, -1, 8277, 8272, 8273, -1, 8277, 8273, 8278, -1, 8279, 8274, 8276, -1, 8280, 8277, 8278, -1, 8280, 8278, 8281, -1, 8282, 8274, 8279, -1, 8283, 8280, 8281, -1, 8284, 8282, 8279, -1, 8285, 8282, 8284, -1, 8286, 8287, 8285, -1, 8286, 8285, 8284, -1, 8288, 7887, 8259, -1, 8288, 8259, 8267, -1, 8289, 8290, 8291, -1, 8292, 7887, 8288, -1, 8289, 8291, 8293, -1, 8294, 7887, 8292, -1, 8207, 8234, 4651, -1, 8207, 8295, 8296, -1, 8207, 8296, 8297, -1, 8207, 8297, 8298, -1, 8207, 8298, 8299, -1, 8207, 8299, 8300, -1, 8207, 8300, 8234, -1, 8301, 7887, 8294, -1, 8302, 8289, 8293, -1, 8302, 8283, 8281, -1, 8302, 8293, 8283, -1, 8302, 8281, 8295, -1, 8302, 8295, 8207, -1, 8303, 8207, 4651, -1, 8304, 7887, 8301, -1, 8305, 4651, 4077, -1, 8305, 8303, 4651, -1, 8306, 7887, 8304, -1, 8307, 8207, 8303, -1, 7890, 7887, 8306, -1, 8308, 8305, 4077, -1, 8309, 8287, 8286, -1, 8310, 8207, 8307, -1, 8201, 8308, 4077, -1, 8311, 8207, 8310, -1, 8312, 8207, 8311, -1, 8313, 8207, 8312, -1, 7977, 8309, 8286, -1, 7977, 8314, 8309, -1, 7977, 8315, 8314, -1, 7977, 8316, 8315, -1, 7977, 7976, 8316, -1, 7977, 8286, 8317, -1, 8318, 8207, 8313, -1, 8319, 8207, 8318, -1, 8320, 8321, 7966, -1, 8322, 8207, 8319, -1, 8323, 7966, 8321, -1, 8324, 8320, 7966, -1, 8325, 8207, 8322, -1, 7924, 8207, 8325, -1, 8326, 7966, 8323, -1, 8327, 8324, 7966, -1, 2223, 7966, 8326, -1, 8328, 8327, 7966, -1, 7876, 7875, 8198, -1, 8329, 8328, 7966, -1, 8197, 7876, 8198, -1, 7965, 8329, 7966, -1, 7874, 7882, 7875, -1, 8330, 7962, 8331, -1, 8331, 7960, 8332, -1, 7962, 7960, 8331, -1, 8332, 7957, 8333, -1, 7960, 7957, 8332, -1, 8333, 7956, 8334, -1, 7957, 7956, 8333, -1, 8334, 7955, 8335, -1, 7956, 7955, 8334, -1, 8335, 7959, 8336, -1, 7955, 7959, 8335, -1, 8336, 7961, 8337, -1, 7959, 7961, 8336, -1, 8337, 7963, 8338, -1, 7961, 7963, 8337, -1, 8338, 7998, 8339, -1, 7963, 7998, 8338, -1, 8339, 7997, 8340, -1, 7998, 7997, 8339, -1, 8340, 7996, 8341, -1, 7997, 7996, 8340, -1, 8341, 7994, 8342, -1, 7996, 7994, 8341, -1, 8342, 7993, 8343, -1, 7994, 7993, 8342, -1, 7993, 7992, 8343, -1, 8344, 8311, 8345, -1, 8345, 8310, 8346, -1, 8311, 8310, 8345, -1, 8346, 8307, 8347, -1, 8310, 8307, 8346, -1, 8347, 8303, 8348, -1, 8307, 8303, 8347, -1, 8348, 8305, 8349, -1, 8303, 8305, 8348, -1, 8349, 8308, 8350, -1, 8305, 8308, 8349, -1, 8350, 8201, 8351, -1, 8308, 8201, 8350, -1, 8351, 8199, 8352, -1, 8201, 8199, 8351, -1, 8352, 8198, 8353, -1, 8199, 8198, 8352, -1, 8353, 7875, 8354, -1, 8198, 7875, 8353, -1, 8354, 7882, 8355, -1, 7875, 7882, 8354, -1, 8355, 7881, 8356, -1, 7882, 7881, 8355, -1, 8356, 7898, 8357, -1, 7881, 7898, 8356, -1, 7898, 7921, 8357, -1, 8358, 8241, 8359, -1, 8359, 8242, 8360, -1, 8241, 8242, 8359, -1, 8360, 8243, 8361, -1, 8242, 8243, 8360, -1, 8361, 7886, 8362, -1, 8243, 7886, 8361, -1, 8362, 7884, 8363, -1, 7886, 7884, 8362, -1, 8363, 7883, 8364, -1, 7884, 7883, 8363, -1, 8364, 7885, 8365, -1, 7883, 7885, 8364, -1, 8365, 8226, 8366, -1, 7885, 8226, 8365, -1, 8366, 8225, 8367, -1, 8226, 8225, 8366, -1, 8367, 8221, 8368, -1, 8225, 8221, 8367, -1, 8368, 8211, 8369, -1, 8221, 8211, 8368, -1, 8369, 8209, 8370, -1, 8211, 8209, 8369, -1, 8370, 8206, 8371, -1, 8209, 8206, 8370, -1, 8206, 8200, 8371, -1, 8117, 8118, 8372, -1, 8372, 8118, 8373, -1, 8373, 8119, 8374, -1, 8118, 8119, 8373, -1, 8374, 8120, 8375, -1, 8119, 8120, 8374, -1, 8375, 8112, 8376, -1, 8120, 8112, 8375, -1, 8376, 8111, 8377, -1, 8112, 8111, 8376, -1, 8377, 8113, 8378, -1, 8111, 8113, 8377, -1, 8378, 8103, 8379, -1, 8113, 8103, 8378, -1, 8379, 8102, 8380, -1, 8103, 8102, 8379, -1, 8380, 8101, 8381, -1, 8102, 8101, 8380, -1, 8381, 8099, 8382, -1, 8101, 8099, 8381, -1, 8382, 8097, 8383, -1, 8099, 8097, 8382, -1, 8383, 8091, 8384, -1, 8097, 8091, 8383, -1, 8384, 8088, 8385, -1, 8091, 8088, 8384, -1, 8386, 8387, 7966, -1, 8386, 7966, 8033, -1, 8388, 8389, 8390, -1, 8391, 8392, 8393, -1, 8394, 8395, 8396, -1, 8397, 8398, 8399, -1, 8396, 8395, 8400, -1, 8401, 8402, 8397, -1, 8398, 8402, 8403, -1, 8397, 8402, 8398, -1, 8401, 8404, 8402, -1, 8388, 8405, 8389, -1, 8395, 8406, 8400, -1, 8400, 8406, 8407, -1, 8387, 8408, 8409, -1, 1123, 8410, 8411, -1, 8412, 8413, 8414, -1, 8388, 8410, 8405, -1, 8415, 8413, 8416, -1, 8411, 8410, 8388, -1, 8417, 8413, 8415, -1, 8418, 8413, 8417, -1, 8419, 8413, 8418, -1, 8420, 8421, 8401, -1, 8387, 8422, 8408, -1, 439, 8422, 8387, -1, 8416, 8413, 8423, -1, 8406, 8424, 8407, -1, 8401, 8425, 8420, -1, 8407, 8424, 8426, -1, 8427, 8413, 8412, -1, 8428, 8413, 8427, -1, 8424, 8429, 8426, -1, 8430, 8413, 8428, -1, 8421, 8431, 8401, -1, 8432, 8413, 8433, -1, 8423, 8413, 8432, -1, 8434, 8413, 8419, -1, 8435, 8413, 8434, -1, 8426, 8429, 8436, -1, 8437, 8413, 8435, -1, 8401, 8438, 8425, -1, 8414, 8413, 8437, -1, 8429, 8439, 8436, -1, 8401, 8440, 8404, -1, 8431, 8440, 8401, -1, 439, 8441, 8422, -1, 8436, 8439, 8442, -1, 437, 8441, 439, -1, 8401, 8443, 8438, -1, 8444, 8445, 8446, -1, 8439, 8447, 8442, -1, 8440, 8448, 8404, -1, 437, 8449, 8441, -1, 8442, 8447, 8450, -1, 435, 8449, 437, -1, 8451, 8445, 8444, -1, 8404, 8452, 8453, -1, 8447, 8454, 8450, -1, 8448, 8452, 8404, -1, 8444, 8455, 8451, -1, 8450, 8454, 8456, -1, 8452, 8457, 8453, -1, 435, 8458, 8449, -1, 434, 8458, 435, -1, 8453, 8457, 8459, -1, 8459, 8460, 8461, -1, 8446, 8462, 8463, -1, 8454, 8464, 8456, -1, 8456, 8464, 8465, -1, 747, 8466, 434, -1, 8457, 8460, 8459, -1, 8460, 8467, 8461, -1, 8461, 8467, 8468, -1, 8445, 8462, 8446, -1, 8464, 8469, 8465, -1, 8465, 8469, 8470, -1, 434, 8466, 8458, -1, 1123, 8471, 8410, -1, 747, 8472, 8466, -1, 913, 8472, 747, -1, 8463, 8473, 8474, -1, 8474, 8473, 8475, -1, 1121, 8471, 1123, -1, 8392, 8476, 8393, -1, 8462, 8473, 8463, -1, 1119, 8477, 1121, -1, 8401, 8478, 8443, -1, 1121, 8477, 8471, -1, 1119, 8479, 8477, -1, 1118, 8479, 1119, -1, 8473, 8480, 8475, -1, 1118, 8481, 8479, -1, 8475, 8482, 8483, -1, 8480, 8482, 8475, -1, 1291, 8481, 1118, -1, 1291, 8484, 8481, -1, 8483, 8485, 8486, -1, 8486, 8485, 8487, -1, 1381, 8484, 1291, -1, 8482, 8485, 8483, -1, 901, 8488, 902, -1, 1316, 8489, 1090, -1, 8490, 8489, 8491, -1, 8492, 8488, 901, -1, 8485, 8493, 8487, -1, 8491, 8489, 1301, -1, 8494, 8489, 8490, -1, 8495, 8489, 8494, -1, 8496, 8489, 8495, -1, 8487, 8497, 8498, -1, 8498, 8497, 8499, -1, 1301, 8489, 1302, -1, 1302, 8489, 1303, -1, 1303, 8489, 1304, -1, 871, 8488, 406, -1, 8493, 8497, 8487, -1, 1304, 8489, 1305, -1, 755, 8488, 871, -1, 1305, 8489, 1306, -1, 754, 8488, 755, -1, 1306, 8489, 1313, -1, 753, 8488, 754, -1, 1313, 8489, 1314, -1, 746, 8488, 753, -1, 1314, 8489, 1315, -1, 905, 8488, 746, -1, 8497, 8500, 8499, -1, 1315, 8489, 1316, -1, 904, 8488, 905, -1, 903, 8488, 904, -1, 902, 8488, 903, -1, 8492, 8501, 8488, -1, 1380, 8502, 1381, -1, 8503, 8501, 8504, -1, 8499, 8505, 8506, -1, 1381, 8502, 8484, -1, 8507, 8501, 8492, -1, 8508, 8501, 8507, -1, 8500, 8505, 8499, -1, 8504, 8501, 8508, -1, 8509, 8501, 8503, -1, 8510, 8501, 8509, -1, 8511, 8501, 8510, -1, 8512, 8501, 8511, -1, 8513, 8501, 8512, -1, 8514, 8501, 8513, -1, 8515, 8501, 8514, -1, 8516, 8501, 8515, -1, 8430, 8517, 8413, -1, 838, 8518, 846, -1, 8467, 8519, 8468, -1, 8520, 8519, 8467, -1, 8521, 8519, 8520, -1, 8522, 8519, 8521, -1, 8523, 8519, 8522, -1, 8518, 8524, 846, -1, 8523, 369, 8519, -1, 846, 8524, 898, -1, 8525, 369, 8523, -1, 369, 367, 8519, -1, 832, 8526, 838, -1, 8527, 8528, 8529, -1, 838, 8526, 8518, -1, 8525, 371, 369, -1, 8530, 371, 8525, -1, 8531, 8528, 8532, -1, 8533, 8528, 8531, -1, 8534, 8528, 8533, -1, 8535, 8528, 8534, -1, 367, 365, 8519, -1, 8536, 8528, 8535, -1, 8537, 8528, 8536, -1, 8529, 8528, 8537, -1, 898, 8538, 909, -1, 8524, 8538, 898, -1, 8530, 373, 371, -1, 8539, 373, 8530, -1, 365, 363, 8519, -1, 828, 8540, 832, -1, 832, 8540, 8526, -1, 8541, 375, 8539, -1, 913, 8542, 8472, -1, 8538, 8542, 909, -1, 8539, 375, 373, -1, 8543, 8544, 8545, -1, 8546, 8544, 8543, -1, 363, 361, 8519, -1, 8430, 1053, 8517, -1, 909, 8542, 913, -1, 8547, 1053, 8430, -1, 8548, 752, 8541, -1, 8541, 752, 375, -1, 8528, 8549, 8532, -1, 828, 8550, 8540, -1, 361, 359, 8519, -1, 8551, 8549, 8552, -1, 1053, 1051, 8517, -1, 8532, 8549, 8551, -1, 8553, 1055, 8547, -1, 8528, 8554, 8549, -1, 8542, 8555, 8472, -1, 8545, 8554, 8528, -1, 8548, 769, 752, -1, 8544, 8554, 8545, -1, 8472, 8555, 8556, -1, 8556, 8555, 8557, -1, 359, 357, 8519, -1, 8547, 1055, 1053, -1, 1051, 1049, 8517, -1, 8552, 8558, 8559, -1, 8555, 8560, 8557, -1, 8549, 8558, 8552, -1, 8557, 8560, 8561, -1, 8553, 1057, 1055, -1, 8562, 1057, 8553, -1, 8559, 8563, 8564, -1, 8558, 8563, 8559, -1, 357, 355, 8519, -1, 1049, 1047, 8517, -1, 8564, 8565, 8496, -1, 8560, 8566, 8561, -1, 8563, 8565, 8564, -1, 8561, 8567, 8568, -1, 8565, 8569, 8496, -1, 8562, 1059, 1057, -1, 8496, 8569, 8489, -1, 355, 353, 8519, -1, 8570, 1059, 8562, -1, 8566, 8567, 8561, -1, 8568, 8571, 8572, -1, 353, 351, 8519, -1, 1047, 1045, 8517, -1, 8567, 8571, 8568, -1, 8570, 1296, 1059, -1, 1372, 8573, 1378, -1, 8572, 8574, 8575, -1, 8576, 1296, 8570, -1, 8575, 8574, 8476, -1, 351, 350, 8519, -1, 8571, 8574, 8572, -1, 1045, 1043, 8517, -1, 8574, 8577, 8476, -1, 1378, 8578, 1380, -1, 8573, 8578, 1378, -1, 8579, 1379, 8576, -1, 8576, 1379, 1296, -1, 1043, 1041, 8517, -1, 1372, 8580, 8573, -1, 8579, 1375, 1379, -1, 1371, 8580, 1372, -1, 8581, 8582, 8583, -1, 1380, 8584, 8502, -1, 1041, 1039, 8517, -1, 8578, 8584, 1380, -1, 1371, 8585, 8580, -1, 1039, 1037, 8517, -1, 8583, 8586, 8587, -1, 1370, 8585, 1371, -1, 8584, 8588, 8502, -1, 8582, 8586, 8583, -1, 8502, 8588, 8589, -1, 8590, 8591, 8581, -1, 8589, 8588, 8592, -1, 1037, 1035, 8517, -1, 8581, 8591, 8582, -1, 8587, 8593, 8594, -1, 1035, 1034, 8517, -1, 1370, 8595, 8585, -1, 1365, 8595, 1370, -1, 8586, 8593, 8587, -1, 8588, 8596, 8592, -1, 8592, 8596, 8597, -1, 8590, 8598, 8591, -1, 8594, 8599, 8600, -1, 8596, 8601, 8597, -1, 8597, 8601, 8602, -1, 8593, 8599, 8594, -1, 8590, 8603, 8598, -1, 8478, 8603, 8590, -1, 8601, 8604, 8602, -1, 8600, 8605, 8548, -1, 8599, 8605, 8600, -1, 8604, 8606, 8602, -1, 8602, 8606, 8607, -1, 397, 395, 699, -1, 820, 395, 828, -1, 699, 395, 820, -1, 8606, 8608, 8607, -1, 769, 8605, 766, -1, 8548, 8605, 769, -1, 8609, 8610, 8611, -1, 8607, 8608, 8612, -1, 8613, 8610, 8609, -1, 8608, 8614, 8612, -1, 766, 8615, 767, -1, 8610, 8616, 8611, -1, 8612, 8614, 8617, -1, 8605, 8615, 766, -1, 8615, 8618, 767, -1, 8614, 8619, 8617, -1, 828, 393, 8550, -1, 8611, 8616, 8620, -1, 8617, 8619, 8621, -1, 767, 8618, 863, -1, 8622, 8623, 8613, -1, 8613, 8623, 8610, -1, 1365, 8624, 8595, -1, 8618, 8625, 863, -1, 8550, 393, 8626, -1, 395, 393, 828, -1, 863, 8625, 857, -1, 8620, 8627, 8628, -1, 8616, 8627, 8620, -1, 8625, 8629, 857, -1, 857, 8629, 858, -1, 8622, 8630, 8623, -1, 8626, 391, 8631, -1, 8627, 8632, 8628, -1, 858, 8633, 862, -1, 8629, 8633, 858, -1, 393, 391, 8626, -1, 8633, 8634, 862, -1, 8628, 8632, 8635, -1, 391, 389, 8631, -1, 8636, 8637, 8622, -1, 8631, 389, 8638, -1, 8622, 8637, 8630, -1, 8635, 8639, 8579, -1, 8632, 8639, 8635, -1, 389, 387, 8638, -1, 8638, 387, 8640, -1, 8579, 8641, 1375, -1, 8639, 8641, 8579, -1, 1375, 8642, 1376, -1, 387, 385, 8640, -1, 8640, 385, 8643, -1, 8641, 8642, 1375, -1, 1376, 8644, 1377, -1, 8642, 8644, 1376, -1, 1377, 8645, 1382, -1, 8643, 383, 8646, -1, 385, 383, 8643, -1, 8644, 8645, 1377, -1, 1382, 8647, 1383, -1, 1081, 1079, 1368, -1, 1368, 1079, 1341, -1, 8645, 8647, 1382, -1, 1383, 8648, 1386, -1, 8647, 8648, 1383, -1, 8624, 1077, 8649, -1, 1365, 1077, 8624, -1, 1341, 1077, 1365, -1, 1079, 1077, 1341, -1, 8649, 1075, 8650, -1, 1077, 1075, 8649, -1, 8648, 8651, 1386, -1, 8650, 1073, 8652, -1, 8653, 8654, 8655, -1, 1075, 1073, 8650, -1, 8654, 8656, 8657, -1, 8652, 1071, 8658, -1, 8653, 8656, 8654, -1, 8659, 8393, 8653, -1, 1073, 1071, 8652, -1, 8660, 8388, 8661, -1, 8662, 8663, 8664, -1, 8661, 8388, 8665, -1, 8653, 8393, 8656, -1, 8658, 1069, 8666, -1, 8664, 8663, 8667, -1, 8668, 8669, 8670, -1, 8664, 8671, 8662, -1, 1071, 1069, 8658, -1, 8672, 8671, 8664, -1, 8673, 8671, 8672, -1, 8413, 8411, 8388, -1, 8663, 8674, 8667, -1, 8666, 1067, 8675, -1, 1069, 1067, 8666, -1, 8676, 8677, 8678, -1, 8670, 8677, 8676, -1, 8517, 8411, 8413, -1, 8667, 8674, 8679, -1, 8673, 8680, 8671, -1, 8669, 8677, 8670, -1, 8681, 8680, 8673, -1, 8668, 8682, 8669, -1, 8674, 8683, 8679, -1, 1067, 1065, 8675, -1, 8678, 8684, 8685, -1, 8686, 8683, 8687, -1, 8679, 8683, 8686, -1, 8688, 8689, 8690, -1, 8677, 8684, 8678, -1, 8691, 8689, 8688, -1, 8692, 8693, 8688, -1, 8681, 8694, 8680, -1, 8695, 8696, 8668, -1, 8668, 8696, 8682, -1, 8688, 8693, 8691, -1, 8683, 8697, 8687, -1, 8689, 8698, 8690, -1, 8690, 8698, 8699, -1, 8697, 8700, 8687, -1, 8684, 8701, 8685, -1, 8702, 8703, 8692, -1, 8704, 8705, 8695, -1, 8687, 8700, 8706, -1, 8692, 8703, 8693, -1, 8695, 8705, 8696, -1, 8516, 8707, 8501, -1, 8698, 8708, 8699, -1, 8685, 8709, 8710, -1, 8700, 8707, 8706, -1, 8699, 8708, 8711, -1, 8706, 8707, 8516, -1, 8702, 8529, 8703, -1, 8527, 8529, 8702, -1, 8701, 8709, 8685, -1, 8707, 8712, 8501, -1, 8708, 8713, 8711, -1, 8710, 8714, 8715, -1, 8709, 8714, 8710, -1, 8711, 8713, 8716, -1, 8712, 8717, 8501, -1, 8519, 8387, 8468, -1, 1087, 8718, 1373, -1, 1373, 8718, 1374, -1, 1374, 8718, 1384, -1, 1384, 8718, 1385, -1, 1385, 8718, 1387, -1, 8468, 8387, 8719, -1, 1387, 8718, 1393, -1, 1393, 8718, 1394, -1, 1394, 8718, 1395, -1, 713, 8386, 715, -1, 1395, 8718, 1396, -1, 712, 8386, 713, -1, 1396, 8718, 1397, -1, 711, 8386, 712, -1, 710, 8386, 711, -1, 709, 8386, 710, -1, 728, 8386, 709, -1, 727, 8386, 728, -1, 893, 8386, 727, -1, 885, 8386, 893, -1, 403, 8386, 885, -1, 1398, 8720, 1399, -1, 8720, 8721, 1399, -1, 1399, 8721, 1062, -1, 1398, 8722, 8720, -1, 1397, 8722, 1398, -1, 8721, 8723, 1062, -1, 8724, 8725, 8388, -1, 8388, 8725, 8665, -1, 8388, 8726, 8724, -1, 1062, 8723, 1063, -1, 8665, 8727, 8728, -1, 8718, 8729, 1397, -1, 1397, 8729, 8722, -1, 8725, 8727, 8665, -1, 8723, 8730, 1063, -1, 8501, 8444, 8488, -1, 8488, 8444, 8386, -1, 8388, 8731, 8726, -1, 1063, 8730, 1065, -1, 1065, 8730, 8675, -1, 8728, 8732, 8733, -1, 8718, 8734, 8729, -1, 8727, 8732, 8728, -1, 8675, 8735, 8736, -1, 8730, 8735, 8675, -1, 378, 8737, 379, -1, 8388, 8738, 8731, -1, 8735, 8739, 8736, -1, 8736, 8739, 8740, -1, 8733, 8741, 8742, -1, 8732, 8741, 8733, -1, 8737, 8743, 379, -1, 379, 8743, 381, -1, 8742, 8744, 8745, -1, 8740, 8746, 8747, -1, 8745, 8744, 8748, -1, 8741, 8744, 8742, -1, 378, 8749, 8737, -1, 453, 451, 8387, -1, 717, 8749, 378, -1, 8739, 8746, 8740, -1, 8747, 8750, 8751, -1, 383, 8752, 8646, -1, 8746, 8750, 8747, -1, 8744, 8753, 8748, -1, 8743, 8752, 381, -1, 8387, 455, 453, -1, 381, 8752, 383, -1, 8750, 8754, 8751, -1, 8751, 8754, 8755, -1, 8755, 8756, 8757, -1, 8754, 8756, 8755, -1, 451, 449, 8387, -1, 8757, 8756, 8758, -1, 717, 8759, 8749, -1, 716, 8759, 717, -1, 8748, 8760, 8761, -1, 8756, 8762, 8758, -1, 8753, 8760, 8748, -1, 8646, 8763, 8764, -1, 8718, 8765, 8734, -1, 8752, 8763, 8646, -1, 8718, 8766, 8765, -1, 8761, 8767, 8768, -1, 8387, 457, 455, -1, 8768, 8767, 8769, -1, 716, 8770, 8759, -1, 8760, 8767, 8761, -1, 715, 8770, 716, -1, 8763, 8771, 8764, -1, 8718, 8772, 8766, -1, 8764, 8771, 8773, -1, 449, 447, 8387, -1, 8767, 8774, 8769, -1, 8771, 8775, 8773, -1, 8387, 459, 457, -1, 8773, 8775, 8776, -1, 8769, 8777, 8778, -1, 8774, 8777, 8769, -1, 447, 445, 8387, -1, 8775, 8779, 8776, -1, 8776, 8779, 8780, -1, 8779, 8781, 8780, -1, 8780, 8781, 8782, -1, 8782, 8781, 8783, -1, 8781, 8784, 8783, -1, 445, 443, 8387, -1, 8783, 8784, 8785, -1, 8784, 8786, 8785, -1, 8785, 8786, 8787, -1, 1137, 1135, 8411, -1, 8786, 8788, 8787, -1, 8444, 8789, 8386, -1, 715, 8789, 8770, -1, 8386, 8789, 715, -1, 443, 441, 8387, -1, 8444, 8790, 8789, -1, 8411, 1139, 1137, -1, 8569, 8791, 8489, -1, 8489, 8791, 8718, -1, 8444, 8792, 8790, -1, 8718, 8791, 8772, -1, 8444, 8793, 8792, -1, 8388, 8794, 8738, -1, 8772, 8795, 8796, -1, 1135, 1133, 8411, -1, 441, 439, 8387, -1, 8791, 8795, 8772, -1, 8796, 8797, 8798, -1, 8795, 8797, 8796, -1, 8411, 1141, 1139, -1, 8797, 8799, 8798, -1, 8798, 8799, 8800, -1, 8388, 8801, 8794, -1, 8800, 8802, 8803, -1, 8803, 8802, 8804, -1, 8799, 8802, 8800, -1, 1133, 1131, 8411, -1, 8444, 8805, 8793, -1, 8805, 8806, 8793, -1, 8793, 8806, 8807, -1, 8807, 8806, 8808, -1, 8411, 1143, 1141, -1, 8444, 8809, 8805, -1, 8810, 8811, 8812, -1, 8813, 8811, 8810, -1, 8388, 8814, 8801, -1, 8806, 8815, 8808, -1, 8808, 8815, 8816, -1, 1131, 1129, 8411, -1, 8444, 8817, 8809, -1, 8811, 8818, 8812, -1, 8812, 8819, 8802, -1, 8820, 8819, 8762, -1, 8762, 8819, 8758, -1, 8815, 8821, 8816, -1, 8804, 8819, 8822, -1, 8822, 8819, 8823, -1, 8823, 8819, 8824, -1, 8816, 8821, 8825, -1, 8802, 8819, 8804, -1, 8824, 8819, 8826, -1, 8826, 8819, 8827, -1, 8827, 8819, 8820, -1, 8818, 8819, 8812, -1, 8388, 8828, 8814, -1, 8444, 8388, 8829, -1, 8715, 425, 8830, -1, 8444, 8829, 8831, -1, 1129, 1127, 8411, -1, 8444, 8831, 8455, -1, 8829, 8388, 8832, -1, 8444, 8833, 8817, -1, 8832, 8388, 8834, -1, 8834, 8388, 8660, -1, 8413, 8501, 8835, -1, 8413, 8835, 8836, -1, 8413, 8836, 8433, -1, 8835, 8501, 8837, -1, 8837, 8501, 8838, -1, 8838, 8501, 8717, -1, 8821, 8839, 8825, -1, 8489, 8517, 1090, -1, 1090, 8517, 1091, -1, 1091, 8517, 1093, -1, 8825, 8839, 8840, -1, 1093, 8517, 1095, -1, 1095, 8517, 1034, -1, 1095, 1034, 1322, -1, 1095, 1322, 1325, -1, 1095, 1325, 1328, -1, 8411, 8718, 1087, -1, 8714, 425, 8715, -1, 8411, 1087, 1085, -1, 8411, 1085, 1083, -1, 8411, 1083, 1081, -1, 8839, 8841, 8840, -1, 8411, 1081, 1143, -1, 1143, 1081, 1363, -1, 8840, 8841, 8842, -1, 1363, 1081, 1366, -1, 1366, 1081, 1368, -1, 8488, 8519, 350, -1, 8830, 423, 8843, -1, 8488, 350, 781, -1, 8488, 781, 783, -1, 8488, 783, 786, -1, 8488, 786, 406, -1, 425, 423, 8830, -1, 406, 786, 407, -1, 8841, 8844, 8842, -1, 407, 786, 409, -1, 409, 786, 411, -1, 8842, 8844, 8845, -1, 8387, 8386, 403, -1, 8387, 403, 401, -1, 8387, 401, 399, -1, 8387, 399, 397, -1, 8387, 397, 459, -1, 459, 397, 911, -1, 8846, 427, 8714, -1, 911, 397, 701, -1, 701, 397, 699, -1, 8401, 8528, 8847, -1, 1127, 1125, 8411, -1, 8401, 8847, 8694, -1, 8844, 8848, 8845, -1, 8401, 8694, 8681, -1, 8845, 8848, 8849, -1, 8401, 8681, 8850, -1, 8401, 8850, 8851, -1, 8401, 8851, 8705, -1, 8401, 8705, 8704, -1, 8401, 8704, 8603, -1, 8401, 8603, 8478, -1, 8714, 427, 425, -1, 8847, 8528, 8852, -1, 8852, 8528, 8853, -1, 8853, 8528, 8854, -1, 8854, 8528, 8636, -1, 8848, 8855, 8849, -1, 8636, 8528, 8637, -1, 8849, 8855, 8856, -1, 8637, 8528, 8527, -1, 8856, 8857, 8858, -1, 8819, 8393, 8758, -1, 8843, 421, 8859, -1, 8758, 8393, 8619, -1, 8619, 8393, 8621, -1, 8621, 8393, 8469, -1, 8469, 8393, 8470, -1, 8470, 8393, 8777, -1, 8855, 8857, 8856, -1, 8777, 8393, 8778, -1, 8778, 8393, 8505, -1, 8505, 8393, 8506, -1, 8506, 8393, 8860, -1, 423, 421, 8843, -1, 8860, 8393, 8858, -1, 8858, 8393, 8788, -1, 8788, 8393, 8787, -1, 1125, 1123, 8411, -1, 8857, 8860, 8858, -1, 8787, 8393, 8577, -1, 8577, 8393, 8476, -1, 8861, 429, 8846, -1, 8444, 8862, 8833, -1, 8444, 8863, 8862, -1, 8846, 429, 427, -1, 8859, 419, 8864, -1, 8444, 8865, 8863, -1, 421, 419, 8859, -1, 8866, 431, 8861, -1, 8444, 8867, 8865, -1, 8444, 8446, 8867, -1, 8861, 431, 429, -1, 8864, 417, 8868, -1, 419, 417, 8864, -1, 8869, 899, 8866, -1, 8866, 899, 431, -1, 8634, 415, 862, -1, 8868, 415, 8634, -1, 417, 415, 8868, -1, 8870, 8871, 8872, -1, 8872, 8871, 8873, -1, 8872, 8874, 8870, -1, 8875, 8876, 8877, -1, 8878, 8874, 8872, -1, 8879, 8876, 8875, -1, 8880, 8874, 8878, -1, 8881, 900, 8869, -1, 8869, 900, 899, -1, 8871, 8882, 8873, -1, 8877, 8883, 8884, -1, 8876, 8883, 8877, -1, 8879, 8885, 8876, -1, 8873, 8882, 8886, -1, 8880, 8887, 8874, -1, 8883, 8888, 8884, -1, 8882, 8889, 8886, -1, 8879, 8890, 8885, -1, 8886, 8889, 8891, -1, 8892, 8890, 8879, -1, 415, 413, 862, -1, 862, 413, 864, -1, 8888, 8893, 8884, -1, 8894, 8893, 8895, -1, 8884, 8893, 8894, -1, 8880, 8850, 8887, -1, 8851, 8850, 8880, -1, 8889, 8896, 8891, -1, 8892, 8852, 8890, -1, 8847, 8852, 8892, -1, 8891, 8896, 8897, -1, 8716, 1109, 8898, -1, 8893, 8899, 8895, -1, 8881, 901, 900, -1, 8492, 901, 8881, -1, 1109, 1107, 8898, -1, 8899, 8900, 8895, -1, 864, 411, 786, -1, 413, 411, 864, -1, 8901, 8900, 8423, -1, 8895, 8900, 8901, -1, 8898, 1107, 8902, -1, 8716, 1111, 1109, -1, 8896, 8903, 8897, -1, 8900, 8416, 8423, -1, 8713, 1111, 8716, -1, 8897, 8903, 8904, -1, 8903, 8905, 8904, -1, 8904, 8905, 8906, -1, 8902, 1105, 8907, -1, 1107, 1105, 8902, -1, 8713, 1113, 1111, -1, 8908, 1113, 8713, -1, 8905, 8503, 8906, -1, 8906, 8503, 8504, -1, 8907, 1103, 8909, -1, 1105, 1103, 8907, -1, 8908, 1115, 1113, -1, 8910, 1115, 8908, -1, 8909, 1101, 8911, -1, 1103, 1101, 8909, -1, 8912, 8913, 8914, -1, 8910, 1299, 1115, -1, 8915, 1299, 8910, -1, 8914, 8916, 8917, -1, 8913, 8916, 8914, -1, 1101, 1099, 8911, -1, 8911, 1099, 8651, -1, 8912, 8918, 8913, -1, 8651, 1099, 1386, -1, 8719, 8918, 8912, -1, 8919, 1300, 8915, -1, 8387, 8918, 8719, -1, 8915, 1300, 1299, -1, 8917, 8920, 8659, -1, 8916, 8920, 8917, -1, 1099, 1097, 1386, -1, 1386, 1097, 1281, -1, 1281, 1097, 1328, -1, 8921, 8922, 8923, -1, 8924, 8922, 8921, -1, 8491, 1301, 8919, -1, 8925, 8926, 8921, -1, 8387, 8927, 8918, -1, 8921, 8926, 8924, -1, 8919, 1301, 1300, -1, 1097, 1095, 1328, -1, 8923, 8928, 8929, -1, 8920, 8930, 8659, -1, 8922, 8928, 8923, -1, 8931, 8932, 8925, -1, 8925, 8932, 8926, -1, 8929, 8933, 8934, -1, 8928, 8933, 8929, -1, 8387, 8409, 8927, -1, 8853, 8854, 8931, -1, 8931, 8854, 8932, -1, 8933, 8935, 8934, -1, 8934, 8935, 8936, -1, 8935, 8937, 8936, -1, 8930, 8938, 8659, -1, 8659, 8938, 8393, -1, 8936, 8937, 8939, -1, 8937, 8940, 8939, -1, 8938, 8941, 8393, -1, 8939, 8940, 8942, -1, 8940, 8412, 8942, -1, 8941, 8943, 8393, -1, 8942, 8412, 8414, -1, 8388, 8390, 8828, -1, 8943, 8944, 8393, -1, 8944, 8945, 8393, -1, 8828, 8394, 8396, -1, 8945, 8391, 8393, -1, 8390, 8394, 8828, -1, 1034, 1035, 8946, -1, 8946, 1035, 8947, -1, 8947, 1037, 8948, -1, 1035, 1037, 8947, -1, 8948, 1039, 8949, -1, 1037, 1039, 8948, -1, 8949, 1041, 8950, -1, 1039, 1041, 8949, -1, 8950, 1043, 8951, -1, 1041, 1043, 8950, -1, 8951, 1045, 8952, -1, 1043, 1045, 8951, -1, 8952, 1047, 8953, -1, 1045, 1047, 8952, -1, 8953, 1049, 8954, -1, 1047, 1049, 8953, -1, 8954, 1051, 8955, -1, 1049, 1051, 8954, -1, 8955, 1053, 8956, -1, 1051, 1053, 8955, -1, 8956, 1055, 8957, -1, 1053, 1055, 8956, -1, 8957, 1057, 8958, -1, 1055, 1057, 8957, -1, 8958, 1059, 8959, -1, 1057, 1059, 8958, -1, 1118, 1119, 8960, -1, 8960, 1119, 8961, -1, 8961, 1121, 8962, -1, 1119, 1121, 8961, -1, 8962, 1123, 8963, -1, 1121, 1123, 8962, -1, 8963, 1125, 8964, -1, 1123, 1125, 8963, -1, 8964, 1127, 8965, -1, 1125, 1127, 8964, -1, 8965, 1129, 8966, -1, 1127, 1129, 8965, -1, 8966, 1131, 8967, -1, 1129, 1131, 8966, -1, 8967, 1133, 8968, -1, 1131, 1133, 8967, -1, 8968, 1135, 8969, -1, 1133, 1135, 8968, -1, 8969, 1137, 8970, -1, 1135, 1137, 8969, -1, 8970, 1139, 8971, -1, 1137, 1139, 8970, -1, 8971, 1141, 8972, -1, 1139, 1141, 8971, -1, 8972, 1143, 8973, -1, 1141, 1143, 8972, -1, 8974, 1062, 8975, -1, 8975, 1063, 8976, -1, 1062, 1063, 8975, -1, 8976, 1065, 8977, -1, 1063, 1065, 8976, -1, 8977, 1067, 8978, -1, 1065, 1067, 8977, -1, 8978, 1069, 8979, -1, 1067, 1069, 8978, -1, 8979, 1071, 8980, -1, 1069, 1071, 8979, -1, 8980, 1073, 8981, -1, 1071, 1073, 8980, -1, 8981, 1075, 8982, -1, 1073, 1075, 8981, -1, 8982, 1077, 8983, -1, 1075, 1077, 8982, -1, 8983, 1079, 8984, -1, 1077, 1079, 8983, -1, 8984, 1081, 8985, -1, 1079, 1081, 8984, -1, 8985, 1083, 8986, -1, 1081, 1083, 8985, -1, 8986, 1085, 8987, -1, 1083, 1085, 8986, -1, 1085, 1087, 8987, -1, 1090, 1091, 8988, -1, 8988, 1091, 8989, -1, 8989, 1093, 8990, -1, 1091, 1093, 8989, -1, 8990, 1095, 8991, -1, 1093, 1095, 8990, -1, 8991, 1097, 8992, -1, 1095, 1097, 8991, -1, 8992, 1099, 8993, -1, 1097, 1099, 8992, -1, 8993, 1101, 8994, -1, 1099, 1101, 8993, -1, 8994, 1103, 8995, -1, 1101, 1103, 8994, -1, 8995, 1105, 8996, -1, 1103, 1105, 8995, -1, 8996, 1107, 8997, -1, 1105, 1107, 8996, -1, 8997, 1109, 8998, -1, 1107, 1109, 8997, -1, 8998, 1111, 8999, -1, 1109, 1111, 8998, -1, 8999, 1113, 9000, -1, 1111, 1113, 8999, -1, 9000, 1115, 9001, -1, 1113, 1115, 9000, -1, 406, 407, 9002, -1, 9002, 407, 9003, -1, 9003, 409, 9004, -1, 407, 409, 9003, -1, 9004, 411, 9005, -1, 409, 411, 9004, -1, 9005, 413, 9006, -1, 411, 413, 9005, -1, 9006, 415, 9007, -1, 413, 415, 9006, -1, 9007, 417, 9008, -1, 415, 417, 9007, -1, 9008, 419, 9009, -1, 417, 419, 9008, -1, 9009, 421, 9010, -1, 419, 421, 9009, -1, 9010, 423, 9011, -1, 421, 423, 9010, -1, 9011, 425, 9012, -1, 423, 425, 9011, -1, 9012, 427, 9013, -1, 425, 427, 9012, -1, 9013, 429, 9014, -1, 427, 429, 9013, -1, 9014, 431, 9015, -1, 429, 431, 9014, -1, 9016, 378, 9017, -1, 9017, 379, 9018, -1, 378, 379, 9017, -1, 9018, 381, 9019, -1, 379, 381, 9018, -1, 9019, 383, 9020, -1, 381, 383, 9019, -1, 9020, 385, 9021, -1, 383, 385, 9020, -1, 9021, 387, 9022, -1, 385, 387, 9021, -1, 9022, 389, 9023, -1, 387, 389, 9022, -1, 9023, 391, 9024, -1, 389, 391, 9023, -1, 9024, 393, 9025, -1, 391, 393, 9024, -1, 9025, 395, 9026, -1, 393, 395, 9025, -1, 9026, 397, 9027, -1, 395, 397, 9026, -1, 9027, 399, 9028, -1, 397, 399, 9027, -1, 399, 401, 9028, -1, 9028, 403, 9029, -1, 401, 403, 9028, -1, 434, 435, 9030, -1, 9030, 435, 9031, -1, 9031, 437, 9032, -1, 435, 437, 9031, -1, 9032, 439, 9033, -1, 437, 439, 9032, -1, 9033, 441, 9034, -1, 439, 441, 9033, -1, 9034, 443, 9035, -1, 441, 443, 9034, -1, 9035, 445, 9036, -1, 443, 445, 9035, -1, 9036, 447, 9037, -1, 445, 447, 9036, -1, 9037, 449, 9038, -1, 447, 449, 9037, -1, 9038, 451, 9039, -1, 449, 451, 9038, -1, 9039, 453, 9040, -1, 451, 453, 9039, -1, 9040, 455, 9041, -1, 453, 455, 9040, -1, 9041, 457, 9042, -1, 455, 457, 9041, -1, 9042, 459, 9043, -1, 457, 459, 9042, -1, 9044, 350, 9045, -1, 9045, 351, 9046, -1, 350, 351, 9045, -1, 9046, 353, 9047, -1, 351, 353, 9046, -1, 9047, 355, 9048, -1, 353, 355, 9047, -1, 9048, 357, 9049, -1, 355, 357, 9048, -1, 9049, 359, 9050, -1, 357, 359, 9049, -1, 9050, 361, 9051, -1, 359, 361, 9050, -1, 9051, 363, 9052, -1, 361, 363, 9051, -1, 9052, 365, 9053, -1, 363, 365, 9052, -1, 9053, 367, 9054, -1, 365, 367, 9053, -1, 9054, 369, 9055, -1, 367, 369, 9054, -1, 9055, 371, 9056, -1, 369, 371, 9055, -1, 9056, 373, 9057, -1, 371, 373, 9056, -1, 373, 375, 9057, -1, 9058, 9059, 9060, -1, 9061, 9059, 9058, -1, 9062, 9063, 9046, -1, 9063, 9045, 9046, -1, 9054, 9064, 9053, -1, 9063, 9065, 9045, -1, 9053, 9066, 9052, -1, 9060, 9067, 9068, -1, 9064, 9066, 9053, -1, 9059, 9067, 9060, -1, 9055, 9069, 9054, -1, 9054, 9069, 9064, -1, 9052, 9070, 9051, -1, 9066, 9070, 9052, -1, 9065, 9044, 9045, -1, 9056, 9071, 9055, -1, 9055, 9071, 9069, -1, 9070, 9072, 9051, -1, 9068, 9073, 9074, -1, 9074, 9073, 9075, -1, 9067, 9073, 9068, -1, 9057, 9076, 9056, -1, 9056, 9076, 9071, -1, 9057, 9077, 9076, -1, 9051, 9078, 9050, -1, 9072, 9078, 9051, -1, 9079, 9080, 9065, -1, 9065, 9080, 9044, -1, 9077, 9081, 9076, -1, 9075, 9082, 9083, -1, 9073, 9082, 9075, -1, 9050, 9084, 9049, -1, 9085, 9086, 9079, -1, 9078, 9084, 9050, -1, 9079, 9086, 9080, -1, 9083, 9087, 9088, -1, 9077, 9089, 9081, -1, 9082, 9087, 9083, -1, 9088, 9090, 9085, -1, 9087, 9090, 9088, -1, 9085, 9090, 9086, -1, 9089, 9091, 9081, -1, 9049, 9092, 9048, -1, 9084, 9092, 9049, -1, 9089, 9093, 9091, -1, 9093, 9094, 9091, -1, 9092, 9095, 9048, -1, 9095, 9047, 9048, -1, 9094, 9061, 9058, -1, 9093, 9061, 9094, -1, 9095, 9062, 9047, -1, 9062, 9046, 9047, -1, 9096, 9097, 9076, -1, 9076, 9097, 9071, -1, 9071, 9098, 9069, -1, 9097, 9098, 9071, -1, 9069, 9099, 9064, -1, 9098, 9099, 9069, -1, 9064, 9100, 9066, -1, 9099, 9100, 9064, -1, 9066, 9101, 9070, -1, 9100, 9101, 9066, -1, 9070, 9102, 9072, -1, 9101, 9102, 9070, -1, 9072, 9103, 9078, -1, 9102, 9103, 9072, -1, 9078, 9104, 9084, -1, 9103, 9104, 9078, -1, 9084, 9105, 9092, -1, 9104, 9105, 9084, -1, 9092, 9106, 9095, -1, 9105, 9106, 9092, -1, 9095, 9107, 9062, -1, 9106, 9107, 9095, -1, 9062, 9108, 9063, -1, 9107, 9108, 9062, -1, 9063, 9109, 9065, -1, 9108, 9109, 9063, -1, 9110, 9111, 9112, -1, 9110, 9113, 9111, -1, 9114, 9005, 9006, -1, 9014, 9115, 9116, -1, 9014, 9116, 9013, -1, 9117, 9006, 9007, -1, 9117, 9114, 9006, -1, 9118, 9115, 9014, -1, 9119, 9112, 9120, -1, 9119, 9110, 9112, -1, 9121, 9004, 9005, -1, 9121, 9005, 9114, -1, 9122, 9007, 9008, -1, 9122, 9117, 9007, -1, 9123, 9003, 9004, -1, 9123, 9004, 9121, -1, 9015, 9124, 9118, -1, 9125, 9122, 9008, -1, 9015, 9118, 9014, -1, 9009, 9125, 9008, -1, 9126, 9002, 9003, -1, 9126, 9003, 9123, -1, 9127, 9120, 9128, -1, 9127, 9119, 9120, -1, 9129, 9125, 9009, -1, 9130, 9131, 9002, -1, 9130, 9002, 9126, -1, 9010, 9129, 9009, -1, 9132, 9133, 9124, -1, 9132, 9124, 9015, -1, 9134, 9129, 9010, -1, 9135, 9128, 9136, -1, 9137, 9131, 9130, -1, 9135, 9127, 9128, -1, 9138, 9139, 9133, -1, 9138, 9133, 9132, -1, 9140, 9136, 9141, -1, 9140, 9135, 9136, -1, 9142, 9137, 9130, -1, 9143, 9141, 9139, -1, 9011, 9134, 9010, -1, 9143, 9140, 9141, -1, 9144, 9134, 9011, -1, 9143, 9139, 9138, -1, 9145, 9137, 9142, -1, 9146, 9145, 9142, -1, 9012, 9144, 9011, -1, 9012, 9147, 9144, -1, 9113, 9146, 9111, -1, 9113, 9145, 9146, -1, 9013, 9147, 9012, -1, 9013, 9116, 9147, -1, 9118, 9148, 9115, -1, 9115, 9149, 9116, -1, 9148, 9149, 9115, -1, 9116, 9150, 9147, -1, 9149, 9150, 9116, -1, 9147, 9151, 9144, -1, 9150, 9151, 9147, -1, 9144, 9152, 9134, -1, 9151, 9152, 9144, -1, 9134, 9153, 9129, -1, 9152, 9153, 9134, -1, 9129, 9154, 9125, -1, 9153, 9154, 9129, -1, 9125, 9155, 9122, -1, 9154, 9155, 9125, -1, 9122, 9156, 9117, -1, 9155, 9156, 9122, -1, 9117, 9157, 9114, -1, 9156, 9157, 9117, -1, 9114, 9158, 9121, -1, 9157, 9158, 9114, -1, 9121, 9159, 9123, -1, 9158, 9159, 9121, -1, 9123, 9160, 9126, -1, 9159, 9160, 9123, -1, 9160, 9161, 9126, -1, 9162, 9163, 9164, -1, 9164, 9163, 9165, -1, 9166, 9167, 9018, -1, 9026, 9168, 9025, -1, 9167, 9017, 9018, -1, 9025, 9169, 9024, -1, 9168, 9169, 9025, -1, 9167, 9170, 9017, -1, 9165, 9171, 9172, -1, 9163, 9171, 9165, -1, 9027, 9173, 9026, -1, 9026, 9173, 9168, -1, 9024, 9174, 9023, -1, 9169, 9174, 9024, -1, 9028, 9175, 9027, -1, 9027, 9175, 9173, -1, 9174, 9176, 9023, -1, 9170, 9016, 9017, -1, 9029, 9177, 9028, -1, 9028, 9177, 9175, -1, 9029, 9178, 9177, -1, 9023, 9179, 9022, -1, 9172, 9180, 9181, -1, 9181, 9180, 9182, -1, 9171, 9180, 9172, -1, 9176, 9179, 9023, -1, 9178, 9183, 9177, -1, 9022, 9184, 9021, -1, 9179, 9184, 9022, -1, 9185, 9186, 9170, -1, 9170, 9186, 9016, -1, 9178, 9187, 9183, -1, 9182, 9188, 9189, -1, 9180, 9188, 9182, -1, 9190, 9191, 9185, -1, 9185, 9191, 9186, -1, 9187, 9192, 9183, -1, 9189, 9193, 9194, -1, 9188, 9193, 9189, -1, 9021, 9195, 9020, -1, 9184, 9195, 9021, -1, 9194, 9196, 9190, -1, 9193, 9196, 9194, -1, 9190, 9196, 9191, -1, 9187, 9197, 9192, -1, 9197, 9198, 9192, -1, 9195, 9199, 9020, -1, 9199, 9019, 9020, -1, 9198, 9162, 9164, -1, 9197, 9162, 9198, -1, 9199, 9166, 9019, -1, 9166, 9018, 9019, -1, 9200, 9201, 9177, -1, 9177, 9201, 9175, -1, 9175, 9202, 9173, -1, 9201, 9202, 9175, -1, 9173, 9203, 9168, -1, 9202, 9203, 9173, -1, 9168, 9204, 9169, -1, 9203, 9204, 9168, -1, 9169, 9205, 9174, -1, 9204, 9205, 9169, -1, 9174, 9206, 9176, -1, 9205, 9206, 9174, -1, 9176, 9207, 9179, -1, 9206, 9207, 9176, -1, 9179, 9208, 9184, -1, 9207, 9208, 9179, -1, 9184, 9209, 9195, -1, 9208, 9209, 9184, -1, 9195, 9210, 9199, -1, 9209, 9210, 9195, -1, 9199, 9211, 9166, -1, 9210, 9211, 9199, -1, 9166, 9212, 9167, -1, 9211, 9212, 9166, -1, 9167, 9213, 9170, -1, 9212, 9213, 9167, -1, 9214, 9215, 9216, -1, 9214, 9217, 9215, -1, 9218, 9033, 9034, -1, 9219, 9034, 9035, -1, 9042, 9220, 9221, -1, 9042, 9221, 9041, -1, 9219, 9218, 9034, -1, 9222, 9032, 9033, -1, 9223, 9216, 9224, -1, 9223, 9214, 9216, -1, 9222, 9033, 9218, -1, 9225, 9035, 9036, -1, 9225, 9219, 9035, -1, 9226, 9030, 9031, -1, 9226, 9031, 9032, -1, 9043, 9227, 9228, -1, 9226, 9032, 9222, -1, 9043, 9228, 9220, -1, 9043, 9220, 9042, -1, 9229, 9225, 9036, -1, 9037, 9229, 9036, -1, 9230, 9030, 9226, -1, 9231, 9224, 9232, -1, 9233, 9030, 9230, -1, 9231, 9223, 9224, -1, 9234, 9229, 9037, -1, 9235, 9233, 9230, -1, 9236, 9037, 9038, -1, 9237, 9238, 9227, -1, 9237, 9227, 9043, -1, 9236, 9234, 9037, -1, 9239, 9233, 9235, -1, 9240, 9232, 9241, -1, 9240, 9231, 9232, -1, 9242, 9243, 9238, -1, 9242, 9238, 9237, -1, 9244, 9239, 9235, -1, 9245, 9241, 9246, -1, 9245, 9240, 9241, -1, 9039, 9236, 9038, -1, 9247, 9246, 9243, -1, 9248, 9236, 9039, -1, 9247, 9243, 9242, -1, 9247, 9245, 9246, -1, 9249, 9239, 9244, -1, 9250, 9249, 9244, -1, 9040, 9248, 9039, -1, 9040, 9251, 9248, -1, 9217, 9249, 9250, -1, 9217, 9250, 9215, -1, 9041, 9251, 9040, -1, 9041, 9221, 9251, -1, 9252, 9253, 9228, -1, 9228, 9253, 9220, -1, 9220, 9254, 9221, -1, 9253, 9254, 9220, -1, 9221, 9255, 9251, -1, 9254, 9255, 9221, -1, 9251, 9256, 9248, -1, 9255, 9256, 9251, -1, 9248, 9257, 9236, -1, 9256, 9257, 9248, -1, 9236, 9258, 9234, -1, 9257, 9258, 9236, -1, 9234, 9259, 9229, -1, 9258, 9259, 9234, -1, 9229, 9260, 9225, -1, 9259, 9260, 9229, -1, 9225, 9261, 9219, -1, 9260, 9261, 9225, -1, 9219, 9262, 9218, -1, 9261, 9262, 9219, -1, 9218, 9263, 9222, -1, 9262, 9263, 9218, -1, 9222, 9264, 9226, -1, 9263, 9264, 9222, -1, 9226, 9265, 9230, -1, 9264, 9265, 9226, -1, 375, 752, 9057, -1, 9057, 752, 9077, -1, 9077, 769, 9089, -1, 752, 769, 9077, -1, 9089, 766, 9093, -1, 769, 766, 9089, -1, 9093, 767, 9061, -1, 766, 767, 9093, -1, 9061, 863, 9059, -1, 767, 863, 9061, -1, 9059, 857, 9067, -1, 863, 857, 9059, -1, 9067, 858, 9073, -1, 857, 858, 9067, -1, 9073, 862, 9082, -1, 858, 862, 9073, -1, 9082, 864, 9087, -1, 862, 864, 9082, -1, 9087, 786, 9090, -1, 864, 786, 9087, -1, 9090, 783, 9086, -1, 786, 783, 9090, -1, 9086, 781, 9080, -1, 783, 781, 9086, -1, 9080, 350, 9044, -1, 781, 350, 9080, -1, 9043, 459, 9237, -1, 9237, 911, 9242, -1, 459, 911, 9237, -1, 9242, 701, 9247, -1, 911, 701, 9242, -1, 9247, 699, 9245, -1, 701, 699, 9247, -1, 9245, 820, 9240, -1, 699, 820, 9245, -1, 9240, 828, 9231, -1, 820, 828, 9240, -1, 9231, 832, 9223, -1, 828, 832, 9231, -1, 9223, 838, 9214, -1, 832, 838, 9223, -1, 9214, 846, 9217, -1, 838, 846, 9214, -1, 9217, 898, 9249, -1, 846, 898, 9217, -1, 9249, 909, 9239, -1, 898, 909, 9249, -1, 9239, 913, 9233, -1, 909, 913, 9239, -1, 9233, 747, 9030, -1, 913, 747, 9233, -1, 747, 434, 9030, -1, 9029, 403, 9178, -1, 9178, 885, 9187, -1, 403, 885, 9178, -1, 9187, 893, 9197, -1, 885, 893, 9187, -1, 9197, 727, 9162, -1, 893, 727, 9197, -1, 9162, 728, 9163, -1, 727, 728, 9162, -1, 9163, 709, 9171, -1, 728, 709, 9163, -1, 9171, 710, 9180, -1, 709, 710, 9171, -1, 9180, 711, 9188, -1, 710, 711, 9180, -1, 9188, 712, 9193, -1, 711, 712, 9188, -1, 9193, 713, 9196, -1, 712, 713, 9193, -1, 9196, 715, 9191, -1, 713, 715, 9196, -1, 9191, 716, 9186, -1, 715, 716, 9191, -1, 9186, 717, 9016, -1, 716, 717, 9186, -1, 717, 378, 9016, -1, 9015, 431, 9132, -1, 9132, 899, 9138, -1, 431, 899, 9132, -1, 9138, 900, 9143, -1, 899, 900, 9138, -1, 9143, 901, 9140, -1, 900, 901, 9143, -1, 9140, 902, 9135, -1, 901, 902, 9140, -1, 9135, 903, 9127, -1, 902, 903, 9135, -1, 9127, 904, 9119, -1, 903, 904, 9127, -1, 9119, 905, 9110, -1, 904, 905, 9119, -1, 9110, 746, 9113, -1, 905, 746, 9110, -1, 9113, 753, 9145, -1, 746, 753, 9113, -1, 9145, 754, 9137, -1, 753, 754, 9145, -1, 9137, 755, 9131, -1, 754, 755, 9137, -1, 9131, 871, 9002, -1, 755, 871, 9131, -1, 871, 406, 9002, -1, 8387, 8519, 8063, -1, 8387, 8063, 7966, -1, 8519, 8488, 7984, -1, 8519, 7984, 8063, -1, 7984, 8386, 8033, -1, 8488, 8386, 7984, -1, 1115, 1299, 9001, -1, 9001, 1299, 9266, -1, 9266, 1300, 9267, -1, 1299, 1300, 9266, -1, 9267, 1301, 9268, -1, 1300, 1301, 9267, -1, 9268, 1302, 9269, -1, 1301, 1302, 9268, -1, 9269, 1303, 9270, -1, 1302, 1303, 9269, -1, 9270, 1304, 9271, -1, 1303, 1304, 9270, -1, 9271, 1305, 9272, -1, 1304, 1305, 9271, -1, 9272, 1306, 9273, -1, 1305, 1306, 9272, -1, 9273, 1313, 9274, -1, 1306, 1313, 9273, -1, 9274, 1314, 9275, -1, 1313, 1314, 9274, -1, 9275, 1315, 9276, -1, 1314, 1315, 9275, -1, 9276, 1316, 9277, -1, 1315, 1316, 9276, -1, 9277, 1090, 8988, -1, 1316, 1090, 9277, -1, 8987, 1087, 9278, -1, 9278, 1373, 9279, -1, 1087, 1373, 9278, -1, 9279, 1374, 9280, -1, 1373, 1374, 9279, -1, 9280, 1384, 9281, -1, 1374, 1384, 9280, -1, 9281, 1385, 9282, -1, 1384, 1385, 9281, -1, 9282, 1387, 9283, -1, 1385, 1387, 9282, -1, 9283, 1393, 9284, -1, 1387, 1393, 9283, -1, 9284, 1394, 9285, -1, 1393, 1394, 9284, -1, 9285, 1395, 9286, -1, 1394, 1395, 9285, -1, 9286, 1396, 9287, -1, 1395, 1396, 9286, -1, 9287, 1397, 9288, -1, 1396, 1397, 9287, -1, 9288, 1398, 9289, -1, 1397, 1398, 9288, -1, 9289, 1399, 8974, -1, 1398, 1399, 9289, -1, 1399, 1062, 8974, -1, 1143, 1363, 8973, -1, 8973, 1363, 9290, -1, 9290, 1366, 9291, -1, 1363, 1366, 9290, -1, 9291, 1368, 9292, -1, 1366, 1368, 9291, -1, 9292, 1341, 9293, -1, 1368, 1341, 9292, -1, 9293, 1365, 9294, -1, 1341, 1365, 9293, -1, 9294, 1370, 9295, -1, 1365, 1370, 9294, -1, 9295, 1371, 9296, -1, 1370, 1371, 9295, -1, 9296, 1372, 9297, -1, 1371, 1372, 9296, -1, 9297, 1378, 9298, -1, 1372, 1378, 9297, -1, 9298, 1380, 9299, -1, 1378, 1380, 9298, -1, 9299, 1381, 9300, -1, 1380, 1381, 9299, -1, 9300, 1291, 9301, -1, 1381, 1291, 9300, -1, 9301, 1118, 8960, -1, 1291, 1118, 9301, -1, 1059, 1296, 8959, -1, 8959, 1296, 9302, -1, 9302, 1379, 9303, -1, 1296, 1379, 9302, -1, 9303, 1375, 9304, -1, 1379, 1375, 9303, -1, 9304, 1376, 9305, -1, 1375, 1376, 9304, -1, 9305, 1377, 9306, -1, 1376, 1377, 9305, -1, 9306, 1382, 9307, -1, 1377, 1382, 9306, -1, 9307, 1383, 9308, -1, 1382, 1383, 9307, -1, 9308, 1386, 9309, -1, 1383, 1386, 9308, -1, 9309, 1281, 9310, -1, 1386, 1281, 9309, -1, 9310, 1328, 9311, -1, 1281, 1328, 9310, -1, 9311, 1325, 9312, -1, 1328, 1325, 9311, -1, 9312, 1322, 9313, -1, 1325, 1322, 9312, -1, 9313, 1034, 8946, -1, 1322, 1034, 9313, -1, 8517, 8186, 8055, -1, 8517, 8489, 8186, -1, 8186, 8718, 8010, -1, 8489, 8718, 8186, -1, 8010, 8411, 8096, -1, 8718, 8411, 8010, -1, 8096, 8517, 8055, -1, 8411, 8517, 8096, -1, 8049, 8413, 8047, -1, 8501, 8413, 8049, -1, 8388, 8090, 8089, -1, 8388, 8444, 8090, -1, 8765, 9314, 8734, -1, 9315, 9314, 8765, -1, 9316, 8756, 9317, -1, 8762, 8756, 9316, -1, 9317, 8754, 9318, -1, 8756, 8754, 9317, -1, 9318, 8750, 9319, -1, 8754, 8750, 9318, -1, 9319, 8746, 9320, -1, 8750, 8746, 9319, -1, 9320, 8739, 9321, -1, 8746, 8739, 9320, -1, 9321, 8735, 9322, -1, 8739, 8735, 9321, -1, 9322, 8730, 9323, -1, 8735, 8730, 9322, -1, 9323, 8723, 9324, -1, 8730, 8723, 9323, -1, 9324, 8721, 9325, -1, 8723, 8721, 9324, -1, 9325, 8720, 9326, -1, 8721, 8720, 9325, -1, 9326, 8722, 9327, -1, 8720, 8722, 9326, -1, 9327, 8729, 9328, -1, 8722, 8729, 9327, -1, 9328, 8734, 9314, -1, 8729, 8734, 9328, -1, 9316, 8820, 8762, -1, 9316, 9329, 8820, -1, 9315, 8766, 9330, -1, 8765, 8766, 9315, -1, 9330, 8772, 9331, -1, 8766, 8772, 9330, -1, 9331, 8796, 9332, -1, 8772, 8796, 9331, -1, 9332, 8798, 9333, -1, 8796, 8798, 9332, -1, 9333, 8800, 9334, -1, 8798, 8800, 9333, -1, 9334, 8803, 9335, -1, 8800, 8803, 9334, -1, 9335, 8804, 9336, -1, 8803, 8804, 9335, -1, 9336, 8822, 9337, -1, 8804, 8822, 9336, -1, 9337, 8823, 9338, -1, 8822, 8823, 9337, -1, 9338, 8824, 9339, -1, 8823, 8824, 9338, -1, 9339, 8826, 9340, -1, 8824, 8826, 9339, -1, 9340, 8827, 9341, -1, 8826, 8827, 9340, -1, 9341, 8820, 9329, -1, 8827, 8820, 9341, -1, 9342, 8595, 8624, -1, 9342, 9343, 8595, -1, 9344, 8614, 9345, -1, 8619, 8614, 9344, -1, 9345, 8608, 9346, -1, 8614, 8608, 9345, -1, 9346, 8606, 9347, -1, 8608, 8606, 9346, -1, 9347, 8604, 9348, -1, 8606, 8604, 9347, -1, 9348, 8601, 9349, -1, 8604, 8601, 9348, -1, 9349, 8596, 9350, -1, 8601, 8596, 9349, -1, 9350, 8588, 9351, -1, 8596, 8588, 9350, -1, 9351, 8584, 9352, -1, 8588, 8584, 9351, -1, 9352, 8578, 9353, -1, 8584, 8578, 9352, -1, 9353, 8573, 9354, -1, 8578, 8573, 9353, -1, 9354, 8580, 9355, -1, 8573, 8580, 9354, -1, 9355, 8585, 9356, -1, 9356, 8585, 9343, -1, 8580, 8585, 9355, -1, 8585, 8595, 9343, -1, 8619, 9357, 8758, -1, 9344, 9357, 8619, -1, 9342, 8649, 9358, -1, 8624, 8649, 9342, -1, 9358, 8650, 9359, -1, 8649, 8650, 9358, -1, 9359, 8652, 9360, -1, 8650, 8652, 9359, -1, 9360, 8658, 9361, -1, 8652, 8658, 9360, -1, 9361, 8666, 9362, -1, 8658, 8666, 9361, -1, 9362, 8675, 9363, -1, 8666, 8675, 9362, -1, 9363, 8736, 9364, -1, 8675, 8736, 9363, -1, 9364, 8740, 9365, -1, 8736, 8740, 9364, -1, 9365, 8747, 9366, -1, 8740, 8747, 9365, -1, 9366, 8751, 9367, -1, 8747, 8751, 9366, -1, 9367, 8755, 9368, -1, 8751, 8755, 9367, -1, 9368, 8757, 9369, -1, 8755, 8757, 9368, -1, 9369, 8758, 9357, -1, 8757, 8758, 9369, -1, 8471, 9370, 8410, -1, 9371, 9370, 8471, -1, 9372, 8464, 9373, -1, 8469, 8464, 9372, -1, 9373, 8454, 9374, -1, 8464, 8454, 9373, -1, 9374, 8447, 9375, -1, 8454, 8447, 9374, -1, 9375, 8439, 9376, -1, 8447, 8439, 9375, -1, 9376, 8429, 9377, -1, 8439, 8429, 9376, -1, 9377, 8424, 9378, -1, 8429, 8424, 9377, -1, 9378, 8406, 9379, -1, 8424, 8406, 9378, -1, 9379, 8395, 9380, -1, 8406, 8395, 9379, -1, 9380, 8394, 9381, -1, 8395, 8394, 9380, -1, 9381, 8390, 9382, -1, 8394, 8390, 9381, -1, 9382, 8389, 9383, -1, 8390, 8389, 9382, -1, 9383, 8405, 9384, -1, 9384, 8405, 9370, -1, 8389, 8405, 9383, -1, 8405, 8410, 9370, -1, 8469, 9385, 8621, -1, 9372, 9385, 8469, -1, 9371, 8477, 9386, -1, 8471, 8477, 9371, -1, 9386, 8479, 9387, -1, 8477, 8479, 9386, -1, 9387, 8481, 9388, -1, 8479, 8481, 9387, -1, 9388, 8484, 9389, -1, 8481, 8484, 9388, -1, 9389, 8502, 9390, -1, 8484, 8502, 9389, -1, 9390, 8589, 9391, -1, 8502, 8589, 9390, -1, 9391, 8592, 9392, -1, 8589, 8592, 9391, -1, 9392, 8597, 9393, -1, 8592, 8597, 9392, -1, 9393, 8602, 9394, -1, 8597, 8602, 9393, -1, 9394, 8607, 9395, -1, 8602, 8607, 9394, -1, 9395, 8612, 9396, -1, 8607, 8612, 9395, -1, 9396, 8617, 9397, -1, 8612, 8617, 9396, -1, 9397, 8621, 9385, -1, 8617, 8621, 9397, -1, 8794, 9398, 8738, -1, 9399, 9398, 8794, -1, 9400, 8774, 9401, -1, 8777, 8774, 9400, -1, 9401, 8767, 9402, -1, 8774, 8767, 9401, -1, 9402, 8760, 9403, -1, 8767, 8760, 9402, -1, 9403, 8753, 9404, -1, 8760, 8753, 9403, -1, 9404, 8744, 9405, -1, 8753, 8744, 9404, -1, 9405, 8741, 9406, -1, 8744, 8741, 9405, -1, 9406, 8732, 9407, -1, 8741, 8732, 9406, -1, 9407, 8727, 9408, -1, 8732, 8727, 9407, -1, 9408, 8725, 9409, -1, 8727, 8725, 9408, -1, 9409, 8724, 9410, -1, 8725, 8724, 9409, -1, 9410, 8726, 9411, -1, 8724, 8726, 9410, -1, 9411, 8731, 9412, -1, 9412, 8731, 9398, -1, 8726, 8731, 9411, -1, 8731, 8738, 9398, -1, 8777, 9413, 8470, -1, 9400, 9413, 8777, -1, 9399, 8794, 9414, -1, 9414, 8801, 9415, -1, 8794, 8801, 9414, -1, 9415, 8814, 9416, -1, 8801, 8814, 9415, -1, 9416, 8828, 9417, -1, 8814, 8828, 9416, -1, 9417, 8396, 9418, -1, 8828, 8396, 9417, -1, 9418, 8400, 9419, -1, 8396, 8400, 9418, -1, 9419, 8407, 9420, -1, 8400, 8407, 9419, -1, 9420, 8426, 9421, -1, 8407, 8426, 9420, -1, 9421, 8436, 9422, -1, 8426, 8436, 9421, -1, 9422, 8442, 9423, -1, 8436, 8442, 9422, -1, 9423, 8450, 9424, -1, 8442, 8450, 9423, -1, 9424, 8456, 9425, -1, 8450, 8456, 9424, -1, 8456, 8465, 9425, -1, 9425, 8470, 9413, -1, 8465, 8470, 9425, -1, 9426, 8506, 8860, -1, 9426, 9427, 8506, -1, 9428, 8863, 9429, -1, 8862, 8863, 9428, -1, 9429, 8865, 9430, -1, 8863, 8865, 9429, -1, 9430, 8867, 9431, -1, 8865, 8867, 9430, -1, 9431, 8446, 9432, -1, 8867, 8446, 9431, -1, 9432, 8463, 9433, -1, 8446, 8463, 9432, -1, 9433, 8474, 9434, -1, 8463, 8474, 9433, -1, 9434, 8475, 9435, -1, 8474, 8475, 9434, -1, 9435, 8483, 9436, -1, 8475, 8483, 9435, -1, 9436, 8486, 9437, -1, 8483, 8486, 9436, -1, 9437, 8487, 9438, -1, 8486, 8487, 9437, -1, 9438, 8498, 9439, -1, 8487, 8498, 9438, -1, 9439, 8499, 9440, -1, 8498, 8499, 9439, -1, 9440, 8506, 9427, -1, 8499, 8506, 9440, -1, 8862, 9441, 8833, -1, 9428, 9441, 8862, -1, 9426, 8857, 9442, -1, 8860, 8857, 9426, -1, 9442, 8855, 9443, -1, 8857, 8855, 9442, -1, 9443, 8848, 9444, -1, 8855, 8848, 9443, -1, 9444, 8844, 9445, -1, 8848, 8844, 9444, -1, 9445, 8841, 9446, -1, 8844, 8841, 9445, -1, 9446, 8839, 9447, -1, 8841, 8839, 9446, -1, 9447, 8821, 9448, -1, 8839, 8821, 9447, -1, 9448, 8815, 9449, -1, 8821, 8815, 9448, -1, 9449, 8806, 9450, -1, 8815, 8806, 9449, -1, 9450, 8805, 9451, -1, 8806, 8805, 9450, -1, 9451, 8809, 9452, -1, 8805, 8809, 9451, -1, 9452, 8817, 9453, -1, 9453, 8817, 9441, -1, 8809, 8817, 9452, -1, 8817, 8833, 9441, -1, 9454, 8858, 8788, -1, 9454, 9455, 8858, -1, 9456, 8790, 9457, -1, 8789, 8790, 9456, -1, 9457, 8792, 9458, -1, 8790, 8792, 9457, -1, 9458, 8793, 9459, -1, 8792, 8793, 9458, -1, 9459, 8807, 9460, -1, 8793, 8807, 9459, -1, 9460, 8808, 9461, -1, 8807, 8808, 9460, -1, 9461, 8816, 9462, -1, 8808, 8816, 9461, -1, 9462, 8825, 9463, -1, 8816, 8825, 9462, -1, 9463, 8840, 9464, -1, 8825, 8840, 9463, -1, 9464, 8842, 9465, -1, 8840, 8842, 9464, -1, 9465, 8845, 9466, -1, 8842, 8845, 9465, -1, 9466, 8849, 9467, -1, 8845, 8849, 9466, -1, 9467, 8856, 9468, -1, 8849, 8856, 9467, -1, 9468, 8858, 9455, -1, 8856, 8858, 9468, -1, 8789, 9469, 8770, -1, 9456, 9469, 8789, -1, 9454, 8786, 9470, -1, 8788, 8786, 9454, -1, 9470, 8784, 9471, -1, 8786, 8784, 9470, -1, 9471, 8781, 9472, -1, 8784, 8781, 9471, -1, 9472, 8779, 9473, -1, 8781, 8779, 9472, -1, 9473, 8775, 9474, -1, 8779, 8775, 9473, -1, 9474, 8771, 9475, -1, 8775, 8771, 9474, -1, 9475, 8763, 9476, -1, 8771, 8763, 9475, -1, 9476, 8752, 9477, -1, 8763, 8752, 9476, -1, 9477, 8743, 9478, -1, 8752, 8743, 9477, -1, 9478, 8737, 9479, -1, 8743, 8737, 9478, -1, 9479, 8749, 9480, -1, 8737, 8749, 9479, -1, 9480, 8759, 9481, -1, 9481, 8759, 9469, -1, 8749, 8759, 9480, -1, 8759, 8770, 9469, -1, 8577, 9482, 8787, -1, 9483, 9482, 8577, -1, 9484, 8631, 9485, -1, 8626, 8631, 9484, -1, 9485, 8638, 9486, -1, 8631, 8638, 9485, -1, 9486, 8640, 9487, -1, 8638, 8640, 9486, -1, 9487, 8643, 9488, -1, 8640, 8643, 9487, -1, 9488, 8646, 9489, -1, 8643, 8646, 9488, -1, 9489, 8764, 9490, -1, 8646, 8764, 9489, -1, 9490, 8773, 9491, -1, 8764, 8773, 9490, -1, 9491, 8776, 9492, -1, 8773, 8776, 9491, -1, 9492, 8780, 9493, -1, 8776, 8780, 9492, -1, 9493, 8782, 9494, -1, 8780, 8782, 9493, -1, 9494, 8783, 9495, -1, 8782, 8783, 9494, -1, 9495, 8785, 9496, -1, 9496, 8785, 9482, -1, 8783, 8785, 9495, -1, 8785, 8787, 9482, -1, 8626, 9497, 8550, -1, 9484, 9497, 8626, -1, 9483, 8574, 9498, -1, 8577, 8574, 9483, -1, 9498, 8571, 9499, -1, 8574, 8571, 9498, -1, 9499, 8567, 9500, -1, 8571, 8567, 9499, -1, 9500, 8566, 9501, -1, 8567, 8566, 9500, -1, 9501, 8560, 9502, -1, 8566, 8560, 9501, -1, 9502, 8555, 9503, -1, 8560, 8555, 9502, -1, 9503, 8542, 9504, -1, 8555, 8542, 9503, -1, 9504, 8538, 9505, -1, 8542, 8538, 9504, -1, 9505, 8524, 9506, -1, 8538, 8524, 9505, -1, 9506, 8518, 9507, -1, 8524, 8518, 9506, -1, 9507, 8526, 9508, -1, 8518, 8526, 9507, -1, 9508, 8540, 9509, -1, 8526, 8540, 9508, -1, 9509, 8550, 9497, -1, 8540, 8550, 9509, -1, 8392, 9510, 8476, -1, 9511, 9510, 8392, -1, 9512, 8422, 9513, -1, 8408, 8422, 9512, -1, 9513, 8441, 9514, -1, 8422, 8441, 9513, -1, 9514, 8449, 9515, -1, 8441, 8449, 9514, -1, 9515, 8458, 9516, -1, 8449, 8458, 9515, -1, 9516, 8466, 9517, -1, 8458, 8466, 9516, -1, 9517, 8472, 9518, -1, 8466, 8472, 9517, -1, 9518, 8556, 9519, -1, 8472, 8556, 9518, -1, 9519, 8557, 9520, -1, 8556, 8557, 9519, -1, 9520, 8561, 9521, -1, 8557, 8561, 9520, -1, 9521, 8568, 9522, -1, 8561, 8568, 9521, -1, 9522, 8572, 9523, -1, 8568, 8572, 9522, -1, 9523, 8575, 9524, -1, 8572, 8575, 9523, -1, 9524, 8476, 9510, -1, 8575, 8476, 9524, -1, 8408, 9525, 8409, -1, 9512, 9525, 8408, -1, 9511, 8391, 9526, -1, 8392, 8391, 9511, -1, 9526, 8945, 9527, -1, 8391, 8945, 9526, -1, 9527, 8944, 9528, -1, 8945, 8944, 9527, -1, 9528, 8943, 9529, -1, 8944, 8943, 9528, -1, 9529, 8941, 9530, -1, 8943, 8941, 9529, -1, 9530, 8938, 9531, -1, 8941, 8938, 9530, -1, 9531, 8930, 9532, -1, 8938, 8930, 9531, -1, 9532, 8920, 9533, -1, 8930, 8920, 9532, -1, 9533, 8916, 9534, -1, 8920, 8916, 9533, -1, 9534, 8913, 9535, -1, 8916, 8913, 9534, -1, 9535, 8918, 9536, -1, 8913, 8918, 9535, -1, 9536, 8927, 9537, -1, 9537, 8927, 9525, -1, 8918, 8927, 9536, -1, 8927, 8409, 9525, -1, 8505, 9538, 8778, -1, 9539, 9538, 8505, -1, 9540, 8834, 9541, -1, 8832, 8834, 9540, -1, 9541, 8660, 9542, -1, 8834, 8660, 9541, -1, 9542, 8661, 9543, -1, 8660, 8661, 9542, -1, 9543, 8665, 9544, -1, 8661, 8665, 9543, -1, 9544, 8728, 9545, -1, 8665, 8728, 9544, -1, 9545, 8733, 9546, -1, 8728, 8733, 9545, -1, 9546, 8742, 9547, -1, 8733, 8742, 9546, -1, 9547, 8745, 9548, -1, 8742, 8745, 9547, -1, 9548, 8748, 9549, -1, 8745, 8748, 9548, -1, 9549, 8761, 9550, -1, 8748, 8761, 9549, -1, 9550, 8768, 9551, -1, 8761, 8768, 9550, -1, 9551, 8769, 9552, -1, 9552, 8769, 9538, -1, 8768, 8769, 9551, -1, 8769, 8778, 9538, -1, 9540, 8829, 8832, -1, 9540, 9553, 8829, -1, 9539, 8500, 9554, -1, 8505, 8500, 9539, -1, 9554, 8497, 9555, -1, 8500, 8497, 9554, -1, 9555, 8493, 9556, -1, 8497, 8493, 9555, -1, 9556, 8485, 9557, -1, 8493, 8485, 9556, -1, 9557, 8482, 9558, -1, 8485, 8482, 9557, -1, 9558, 8480, 9559, -1, 8482, 8480, 9558, -1, 9559, 8473, 9560, -1, 8480, 8473, 9559, -1, 9560, 8462, 9561, -1, 8473, 8462, 9560, -1, 9561, 8445, 9562, -1, 8462, 8445, 9561, -1, 9562, 8451, 9563, -1, 8445, 8451, 9562, -1, 9563, 8455, 9564, -1, 8451, 8455, 9563, -1, 9564, 8831, 9565, -1, 9565, 8831, 9553, -1, 8455, 8831, 9564, -1, 8831, 8829, 9553, -1, 8185, 9566, 9567, -1, 8185, 8180, 9566, -1, 9566, 9568, 9569, -1, 8180, 9568, 9566, -1, 9569, 9570, 9571, -1, 9571, 9570, 9572, -1, 9568, 9570, 9569, -1, 9570, 9573, 9572, -1, 9573, 9574, 9572, -1, 9574, 9575, 9572, -1, 9574, 9576, 9575, -1, 7977, 9577, 9578, -1, 7977, 8317, 9577, -1, 9579, 9580, 9581, -1, 9582, 9580, 9579, -1, 9581, 9583, 9584, -1, 9580, 9583, 9581, -1, 9584, 9585, 9578, -1, 9583, 9585, 9584, -1, 9585, 7977, 9578, -1, 9586, 9579, 9587, -1, 9586, 9582, 9579, -1, 9588, 8258, 9589, -1, 9589, 8252, 9590, -1, 8258, 8252, 9589, -1, 9590, 8254, 9591, -1, 8252, 8254, 9590, -1, 9591, 8253, 9592, -1, 8254, 8253, 9591, -1, 9592, 8255, 9593, -1, 8253, 8255, 9592, -1, 8255, 8259, 9593, -1, 8268, 9594, 8266, -1, 8266, 9595, 8264, -1, 9594, 9595, 8266, -1, 8264, 9596, 8261, -1, 9595, 9596, 8264, -1, 8261, 9597, 8262, -1, 9596, 9597, 8261, -1, 8262, 9598, 8260, -1, 9597, 9598, 8262, -1, 8260, 9599, 8263, -1, 9598, 9599, 8260, -1, 8263, 9600, 8265, -1, 9599, 9600, 8263, -1, 8265, 9601, 8267, -1, 9600, 9601, 8265, -1, 9601, 9602, 8267, -1, 9603, 8286, 9604, -1, 9604, 8284, 9605, -1, 8286, 8284, 9604, -1, 9605, 8279, 9606, -1, 8284, 8279, 9605, -1, 9606, 8276, 9607, -1, 8279, 8276, 9606, -1, 9607, 8275, 9608, -1, 8276, 8275, 9607, -1, 9608, 8274, 9609, -1, 8275, 8274, 9608, -1, 9609, 8282, 9610, -1, 8274, 8282, 9609, -1, 9610, 8285, 9611, -1, 8282, 8285, 9610, -1, 8285, 8287, 9611, -1, 9612, 8139, 9613, -1, 9613, 8136, 9614, -1, 8139, 8136, 9613, -1, 9614, 8131, 9615, -1, 8136, 8131, 9614, -1, 9615, 8130, 9616, -1, 8131, 8130, 9615, -1, 9616, 8129, 9617, -1, 8130, 8129, 9616, -1, 9617, 8128, 9618, -1, 8129, 8128, 9617, -1, 9618, 8135, 9619, -1, 8128, 8135, 9618, -1, 9619, 8138, 9620, -1, 8135, 8138, 9619, -1, 8138, 8140, 9620, -1, 9621, 8121, 9622, -1, 9622, 8109, 9623, -1, 8121, 8109, 9622, -1, 9623, 8107, 9624, -1, 8109, 8107, 9623, -1, 9624, 8104, 9625, -1, 8107, 8104, 9624, -1, 9625, 8106, 9626, -1, 8104, 8106, 9625, -1, 9626, 8105, 9627, -1, 8106, 8105, 9626, -1, 9627, 8108, 9628, -1, 8105, 8108, 9627, -1, 9628, 8114, 9629, -1, 8108, 8114, 9628, -1, 8114, 8093, 9629, -1, 9630, 8175, 9631, -1, 9631, 8171, 9632, -1, 8175, 8171, 9631, -1, 9632, 8168, 9633, -1, 8171, 8168, 9632, -1, 9633, 8167, 9634, -1, 8168, 8167, 9633, -1, 9634, 8169, 9635, -1, 8167, 8169, 9634, -1, 9635, 8166, 9636, -1, 8169, 8166, 9635, -1, 9636, 8170, 9637, -1, 8166, 8170, 9636, -1, 9637, 8174, 9638, -1, 8170, 8174, 9637, -1, 8174, 8177, 9638, -1, 8152, 9639, 8155, -1, 8155, 9640, 8158, -1, 9639, 9640, 8155, -1, 8158, 9641, 8161, -1, 9640, 9641, 8158, -1, 8161, 9642, 8164, -1, 9641, 9642, 8161, -1, 8164, 9643, 8163, -1, 9642, 9643, 8164, -1, 8163, 9644, 8159, -1, 9643, 9644, 8163, -1, 8159, 9645, 8157, -1, 9644, 9645, 8159, -1, 8157, 9646, 8153, -1, 9645, 9646, 8157, -1, 9646, 9647, 8153, -1, 8150, 9648, 8148, -1, 8145, 9649, 8146, -1, 8148, 9649, 8145, -1, 9648, 9649, 8148, -1, 8146, 9650, 8147, -1, 9649, 9650, 8146, -1, 9650, 9651, 8147, -1, 8147, 9652, 8141, -1, 9651, 9652, 8147, -1, 9652, 9653, 8141, -1, 9654, 8070, 9655, -1, 9655, 8067, 9656, -1, 8070, 8067, 9655, -1, 9656, 8059, 9657, -1, 8067, 8059, 9656, -1, 9657, 8058, 9658, -1, 8059, 8058, 9657, -1, 9658, 8060, 9659, -1, 8058, 8060, 9658, -1, 9659, 8057, 9660, -1, 8060, 8057, 9659, -1, 9660, 8065, 9661, -1, 8057, 8065, 9660, -1, 9661, 8069, 9662, -1, 8065, 8069, 9661, -1, 8069, 8072, 9662, -1, 9663, 8040, 9664, -1, 9664, 8046, 9665, -1, 8040, 8046, 9664, -1, 9665, 8051, 9666, -1, 8046, 8051, 9665, -1, 9666, 8053, 9667, -1, 8051, 8053, 9666, -1, 9667, 8054, 9668, -1, 8053, 8054, 9667, -1, 9668, 8052, 9669, -1, 8054, 8052, 9668, -1, 9669, 8048, 9670, -1, 8052, 8048, 9669, -1, 9670, 8044, 9671, -1, 8048, 8044, 9670, -1, 8044, 8042, 9671, -1, 9573, 9570, 9580, -1, 9580, 9570, 9583, -1, 9583, 9568, 9585, -1, 9570, 9568, 9583, -1, 9585, 8180, 7977, -1, 9568, 8180, 9585, -1, 9672, 9673, 9674, -1, 9675, 9672, 9674, -1, 9676, 9677, 9678, -1, 9676, 9679, 9677, -1, 9680, 9681, 9682, -1, 9675, 9674, 9683, -1, 9676, 9678, 9684, -1, 9685, 9686, 9687, -1, 9688, 9675, 9683, -1, 9689, 9686, 9685, -1, 9688, 9683, 9690, -1, 9691, 9689, 9685, -1, 9692, 9689, 9691, -1, 9693, 9692, 9691, -1, 9694, 9695, 9696, -1, 9694, 9697, 9695, -1, 9698, 9692, 9693, -1, 9694, 9699, 9697, -1, 9700, 9698, 9693, -1, 9701, 9702, 9700, -1, 9703, 9700, 9702, -1, 9704, 9696, 9705, -1, 9706, 9701, 9700, -1, 9704, 9694, 9696, -1, 9707, 9708, 9709, -1, 9710, 9711, 9712, -1, 9713, 9707, 9709, -1, 9714, 9700, 9703, -1, 9715, 9704, 9705, -1, 9713, 9709, 9716, -1, 9717, 9713, 9716, -1, 9718, 9700, 9714, -1, 9717, 9716, 9719, -1, 9720, 9721, 9679, -1, 9720, 9679, 9676, -1, 9722, 9717, 9719, -1, 9722, 9719, 9723, -1, 9724, 9712, 9725, -1, 9690, 9726, 9727, -1, 9690, 9728, 9726, -1, 9729, 9700, 9718, -1, 9690, 9698, 9728, -1, 9690, 9727, 9574, -1, 9730, 9731, 9723, -1, 9729, 9698, 9700, -1, 9690, 9574, 9573, -1, 9732, 9723, 9731, -1, 9724, 9710, 9712, -1, 9733, 9723, 9688, -1, 9733, 9730, 9723, -1, 9734, 9698, 9729, -1, 9735, 9736, 9711, -1, 9737, 9722, 9723, -1, 9737, 9723, 9732, -1, 9735, 9711, 9710, -1, 9738, 9698, 9734, -1, 9739, 9724, 9725, -1, 9739, 9725, 9740, -1, 9741, 9733, 9688, -1, 9742, 9722, 9737, -1, 9743, 9741, 9688, -1, 9744, 9745, 9705, -1, 9746, 9698, 9738, -1, 9747, 9722, 9742, -1, 9748, 9749, 9736, -1, 9750, 9705, 9745, -1, 9748, 9736, 9735, -1, 9728, 9698, 9746, -1, 9751, 9722, 9747, -1, 9752, 9744, 9705, -1, 9752, 9705, 9753, -1, 9754, 9755, 9756, -1, 9754, 9739, 9740, -1, 9754, 9740, 9755, -1, 9757, 9705, 9750, -1, 9758, 9759, 9749, -1, 9758, 9760, 9759, -1, 9576, 9761, 9706, -1, 9576, 9762, 9761, -1, 9758, 9749, 9748, -1, 9763, 9752, 9753, -1, 9576, 9764, 9762, -1, 9576, 9765, 9764, -1, 9766, 9722, 9751, -1, 9576, 9767, 9765, -1, 9576, 9768, 9767, -1, 9576, 9769, 9768, -1, 9770, 9705, 9757, -1, 9576, 9706, 9700, -1, 9771, 9756, 9772, -1, 9773, 9722, 9766, -1, 9774, 9721, 9720, -1, 9771, 9754, 9756, -1, 9774, 9775, 9721, -1, 9776, 9722, 9773, -1, 9777, 9763, 9753, -1, 9778, 9772, 9779, -1, 9778, 9771, 9772, -1, 9780, 9775, 9774, -1, 9574, 9769, 9576, -1, 9574, 9781, 9782, -1, 9574, 9783, 9781, -1, 9784, 9779, 9785, -1, 9574, 9786, 9783, -1, 9574, 9787, 9786, -1, 9788, 9715, 9705, -1, 9574, 9789, 9787, -1, 9574, 9727, 9789, -1, 9574, 9782, 9769, -1, 9788, 9705, 9770, -1, 9784, 9778, 9779, -1, 9790, 9784, 9785, -1, 9791, 9775, 9780, -1, 9791, 9792, 9775, -1, 9793, 9777, 9753, -1, 9794, 9715, 9788, -1, 9582, 9795, 9796, -1, 9582, 9797, 9795, -1, 9582, 9798, 9797, -1, 9582, 9743, 9688, -1, 9582, 9799, 9798, -1, 9800, 9801, 9802, -1, 9803, 9792, 9791, -1, 9582, 9804, 9743, -1, 9805, 9802, 9801, -1, 9582, 9806, 9804, -1, 9807, 9793, 9753, -1, 9582, 9796, 9806, -1, 9580, 9582, 9688, -1, 9808, 9809, 9760, -1, 9810, 9800, 9802, -1, 9808, 9811, 9809, -1, 9808, 9812, 9811, -1, 9586, 9799, 9582, -1, 9808, 9681, 9680, -1, 9813, 9814, 9792, -1, 9586, 9722, 9776, -1, 9808, 9815, 9812, -1, 9586, 9816, 9799, -1, 9808, 9680, 9815, -1, 9586, 9817, 9816, -1, 9808, 9760, 9758, -1, 9586, 9818, 9817, -1, 9819, 9820, 9802, -1, 9586, 9821, 9818, -1, 9586, 9822, 9821, -1, 9819, 9802, 9805, -1, 9586, 9823, 9822, -1, 9586, 9776, 9823, -1, 9824, 9808, 9758, -1, 9813, 9792, 9803, -1, 9573, 9580, 9688, -1, 9573, 9688, 9690, -1, 9825, 9810, 9802, -1, 9826, 9715, 9794, -1, 9827, 9808, 9824, -1, 9827, 9828, 9808, -1, 9829, 9830, 9814, -1, 9831, 9820, 9819, -1, 9832, 9828, 9827, -1, 9829, 9814, 9813, -1, 9833, 9828, 9832, -1, 9834, 9807, 9753, -1, 9833, 9835, 9828, -1, 9836, 9837, 9830, -1, 9838, 9820, 9831, -1, 9839, 9835, 9833, -1, 9839, 9840, 9835, -1, 9836, 9830, 9829, -1, 9841, 9842, 9840, -1, 9841, 9843, 9842, -1, 9841, 9840, 9839, -1, 9844, 9715, 9826, -1, 9845, 9820, 9838, -1, 9844, 9826, 9846, -1, 9847, 9834, 9753, -1, 9848, 9820, 9845, -1, 9849, 9820, 9848, -1, 9850, 9820, 9849, -1, 9851, 9844, 9846, -1, 9852, 9847, 9753, -1, 9853, 9825, 9802, -1, 9852, 9753, 9854, -1, 9853, 9855, 9825, -1, 9856, 9857, 9858, -1, 9853, 9859, 9855, -1, 9856, 9860, 9857, -1, 9861, 9862, 9844, -1, 9853, 9863, 9859, -1, 9856, 9864, 9860, -1, 9853, 9865, 9863, -1, 9853, 9866, 9865, -1, 9861, 9844, 9851, -1, 9867, 9820, 9850, -1, 9868, 9858, 9869, -1, 9868, 9856, 9858, -1, 9870, 9854, 9871, -1, 9870, 9852, 9854, -1, 9872, 9869, 9873, -1, 9874, 9875, 9862, -1, 9872, 9868, 9869, -1, 9874, 9862, 9861, -1, 9876, 9870, 9871, -1, 9876, 9871, 9674, -1, 9877, 9878, 9875, -1, 9877, 9875, 9874, -1, 9673, 9876, 9674, -1, 9879, 9878, 9877, -1, 9880, 9881, 9873, -1, 9880, 9873, 9882, -1, 9883, 9873, 9881, -1, 9883, 9872, 9873, -1, 9884, 9882, 9885, -1, 9884, 9880, 9882, -1, 9886, 9872, 9883, -1, 9887, 9888, 9889, -1, 9890, 9790, 9785, -1, 9890, 9885, 9790, -1, 9891, 9889, 9888, -1, 9890, 9884, 9885, -1, 9892, 9889, 9820, -1, 9892, 9887, 9889, -1, 9893, 9872, 9886, -1, 9894, 9785, 9895, -1, 9892, 9820, 9867, -1, 9894, 9890, 9785, -1, 9896, 9889, 9891, -1, 9897, 9898, 9899, -1, 9897, 9895, 9898, -1, 9897, 9894, 9895, -1, 9900, 9897, 9899, -1, 9901, 9867, 9902, -1, 9900, 9899, 9903, -1, 9904, 9905, 9906, -1, 9901, 9892, 9867, -1, 9907, 9889, 9896, -1, 9908, 9900, 9903, -1, 9909, 9910, 9911, -1, 9912, 9913, 9905, -1, 9909, 9902, 9910, -1, 9912, 9905, 9904, -1, 9909, 9901, 9902, -1, 9914, 9889, 9907, -1, 9915, 9916, 9913, -1, 9917, 9909, 9911, -1, 9915, 9913, 9912, -1, 9917, 9911, 9918, -1, 9919, 9872, 9893, -1, 9920, 9919, 9893, -1, 9921, 9917, 9918, -1, 9921, 9918, 9922, -1, 9923, 9919, 9920, -1, 9923, 9924, 9919, -1, 9925, 9924, 9923, -1, 9926, 9924, 9925, -1, 9926, 9927, 9924, -1, 9928, 9929, 9916, -1, 9928, 9930, 9929, -1, 9931, 9922, 9932, -1, 9931, 9921, 9922, -1, 9933, 9934, 9927, -1, 9933, 9927, 9926, -1, 9928, 9916, 9915, -1, 9935, 9936, 9934, -1, 9935, 9937, 9936, -1, 9935, 9934, 9933, -1, 9938, 9931, 9932, -1, 9938, 9932, 9837, -1, 9938, 9836, 9939, -1, 9940, 9941, 9942, -1, 9940, 9943, 9941, -1, 9940, 9944, 9943, -1, 9938, 9837, 9836, -1, 9945, 9938, 9939, -1, 9945, 9939, 9946, -1, 9947, 9940, 9942, -1, 9947, 9942, 9775, -1, 9948, 9945, 9946, -1, 9949, 9947, 9775, -1, 9950, 9853, 9930, -1, 9950, 9930, 9928, -1, 9951, 9948, 9946, -1, 9952, 9953, 9954, -1, 9951, 9946, 9955, -1, 9952, 9956, 9953, -1, 9952, 9957, 9956, -1, 9958, 9853, 9950, -1, 9959, 9954, 9960, -1, 9961, 9951, 9955, -1, 9958, 9962, 9866, -1, 9961, 9955, 9878, -1, 9958, 9963, 9962, -1, 9959, 9952, 9954, -1, 9958, 9866, 9853, -1, 9964, 9963, 9958, -1, 9961, 9878, 9879, -1, 9964, 9965, 9963, -1, 9966, 9959, 9960, -1, 9967, 9960, 9968, -1, 9969, 9961, 9879, -1, 9970, 9965, 9964, -1, 9969, 9879, 9971, -1, 9970, 9972, 9965, -1, 9973, 9967, 9968, -1, 9974, 9972, 9970, -1, 9974, 9975, 9972, -1, 9976, 9975, 9974, -1, 9977, 9960, 9967, -1, 9978, 9973, 9968, -1, 9976, 9979, 9975, -1, 9980, 9979, 9976, -1, 9980, 9910, 9979, -1, 9981, 9966, 9960, -1, 9911, 9910, 9980, -1, 9981, 9960, 9977, -1, 9982, 9889, 9914, -1, 9983, 9968, 9984, -1, 9792, 9949, 9775, -1, 9983, 9978, 9968, -1, 9982, 9985, 9986, -1, 9982, 9987, 9985, -1, 9982, 9988, 9987, -1, 9982, 9989, 9988, -1, 9982, 9990, 9989, -1, 9982, 9914, 9990, -1, 9991, 9966, 9981, -1, 9992, 9984, 9993, -1, 9992, 9983, 9984, -1, 9994, 9982, 9986, -1, 9995, 9966, 9991, -1, 9996, 9992, 9993, -1, 9996, 9993, 9908, -1, 9997, 9966, 9995, -1, 9998, 9903, 9969, -1, 9998, 9908, 9903, -1, 9998, 9996, 9908, -1, 9999, 10000, 9994, -1, 10001, 9994, 10000, -1, 10002, 9966, 9997, -1, 10003, 9969, 9971, -1, 10003, 9998, 9969, -1, 10003, 9971, 9673, -1, 10004, 9999, 9994, -1, 10005, 9994, 10001, -1, 10006, 9966, 10002, -1, 10007, 10003, 9673, -1, 10008, 9986, 10009, -1, 10008, 9994, 9986, -1, 10008, 10004, 9994, -1, 10010, 9966, 10006, -1, 10011, 9994, 10005, -1, 10012, 10008, 10009, -1, 10012, 10009, 9755, -1, 10013, 9681, 9994, -1, 10013, 9994, 10011, -1, 10014, 10015, 10016, -1, 9740, 10012, 9755, -1, 10017, 10015, 10014, -1, 10017, 10018, 10015, -1, 10019, 9681, 10013, -1, 10020, 10021, 10022, -1, 9684, 9678, 10018, -1, 10020, 10023, 10021, -1, 10020, 10024, 10023, -1, 10020, 10025, 10024, -1, 10020, 10026, 10025, -1, 10020, 10027, 10026, -1, 10020, 10010, 10027, -1, 10028, 9681, 10019, -1, 9684, 10018, 10017, -1, 10020, 9966, 10010, -1, 10029, 10020, 10022, -1, 10029, 10022, 10030, -1, 10031, 9681, 10028, -1, 10032, 10029, 10030, -1, 10032, 10030, 10033, -1, 9682, 9681, 10031, -1, 9672, 10033, 10007, -1, 9672, 10032, 10033, -1, 9672, 10007, 9673, -1, 9991, 9981, 10034, -1, 10034, 9981, 10035, -1, 10035, 9977, 10036, -1, 9981, 9977, 10035, -1, 10036, 9967, 10037, -1, 9977, 9967, 10036, -1, 10037, 9973, 10038, -1, 9967, 9973, 10037, -1, 10038, 9978, 10039, -1, 9973, 9978, 10038, -1, 10039, 9983, 10040, -1, 9978, 9983, 10039, -1, 10040, 9992, 10041, -1, 9983, 9992, 10040, -1, 10041, 9996, 10042, -1, 9992, 9996, 10041, -1, 10042, 9998, 10043, -1, 9996, 9998, 10042, -1, 10043, 10003, 10044, -1, 9998, 10003, 10043, -1, 10044, 10007, 10045, -1, 10003, 10007, 10044, -1, 10045, 10033, 10046, -1, 10046, 10033, 10047, -1, 10007, 10033, 10045, -1, 10033, 10030, 10047, -1, 10048, 9831, 10049, -1, 10049, 9819, 10050, -1, 9831, 9819, 10049, -1, 10050, 9805, 10051, -1, 9819, 9805, 10050, -1, 10051, 9801, 10052, -1, 9805, 9801, 10051, -1, 10052, 9800, 10053, -1, 9801, 9800, 10052, -1, 10053, 9810, 10054, -1, 9800, 9810, 10053, -1, 10054, 9825, 10055, -1, 9810, 9825, 10054, -1, 10055, 9855, 10056, -1, 9825, 9855, 10055, -1, 10056, 9859, 10057, -1, 9855, 9859, 10056, -1, 10057, 9863, 10058, -1, 9859, 9863, 10057, -1, 10058, 9865, 10059, -1, 9863, 9865, 10058, -1, 10059, 9866, 10060, -1, 9865, 9866, 10059, -1, 10060, 9962, 10061, -1, 9866, 9962, 10060, -1, 9962, 9963, 10061, -1, 9770, 9757, 10062, -1, 10062, 9757, 10063, -1, 10063, 9750, 10064, -1, 9757, 9750, 10063, -1, 10064, 9745, 10065, -1, 9750, 9745, 10064, -1, 10065, 9744, 10066, -1, 9745, 9744, 10065, -1, 10066, 9752, 10067, -1, 9744, 9752, 10066, -1, 10067, 9763, 10068, -1, 9752, 9763, 10067, -1, 10068, 9777, 10069, -1, 9763, 9777, 10068, -1, 10069, 9793, 10070, -1, 9777, 9793, 10069, -1, 10070, 9807, 10071, -1, 9793, 9807, 10070, -1, 10071, 9834, 10072, -1, 9807, 9834, 10071, -1, 10072, 9847, 10073, -1, 9834, 9847, 10072, -1, 10073, 9852, 10074, -1, 10074, 9852, 10075, -1, 9847, 9852, 10073, -1, 9852, 9870, 10075, -1, 10011, 10005, 10076, -1, 10076, 10005, 10077, -1, 10077, 10001, 10078, -1, 10005, 10001, 10077, -1, 10078, 10000, 10079, -1, 10001, 10000, 10078, -1, 10079, 9999, 10080, -1, 10000, 9999, 10079, -1, 10080, 10004, 10081, -1, 9999, 10004, 10080, -1, 10081, 10008, 10082, -1, 10004, 10008, 10081, -1, 10082, 10012, 10083, -1, 10008, 10012, 10082, -1, 10083, 9740, 10084, -1, 10012, 9740, 10083, -1, 10084, 9725, 10085, -1, 9740, 9725, 10084, -1, 10085, 9712, 10086, -1, 9725, 9712, 10085, -1, 10086, 9711, 10087, -1, 9712, 9711, 10086, -1, 10087, 9736, 10088, -1, 10088, 9736, 10089, -1, 9711, 9736, 10087, -1, 9736, 9749, 10089, -1, 10090, 9914, 10091, -1, 10091, 9907, 10092, -1, 9914, 9907, 10091, -1, 10092, 9896, 10093, -1, 9907, 9896, 10092, -1, 10093, 9891, 10094, -1, 9896, 9891, 10093, -1, 10094, 9888, 10095, -1, 9891, 9888, 10094, -1, 10095, 9887, 10096, -1, 9888, 9887, 10095, -1, 10096, 9892, 10097, -1, 9887, 9892, 10096, -1, 10097, 9901, 10098, -1, 9892, 9901, 10097, -1, 10098, 9909, 10099, -1, 9901, 9909, 10098, -1, 10099, 9917, 10100, -1, 9909, 9917, 10099, -1, 10100, 9921, 10101, -1, 9917, 9921, 10100, -1, 10101, 9931, 10102, -1, 9921, 9931, 10101, -1, 10102, 9938, 10103, -1, 9931, 9938, 10102, -1, 10103, 9945, 10104, -1, 9938, 9945, 10103, -1, 10104, 9948, 10105, -1, 9945, 9948, 10104, -1, 10105, 9951, 10106, -1, 9948, 9951, 10105, -1, 9951, 9961, 10106, -1, 9961, 9969, 10106, -1, 10106, 9969, 10107, -1, 10108, 9718, 10109, -1, 9718, 9714, 10109, -1, 10109, 9703, 10110, -1, 9714, 9703, 10109, -1, 10110, 9702, 10111, -1, 9703, 9702, 10110, -1, 10111, 9701, 10112, -1, 9702, 9701, 10111, -1, 10112, 9706, 10113, -1, 9701, 9706, 10112, -1, 10113, 9761, 10114, -1, 9706, 9761, 10113, -1, 10114, 9762, 10115, -1, 9761, 9762, 10114, -1, 10115, 9764, 10116, -1, 9762, 9764, 10115, -1, 10116, 9765, 10117, -1, 9764, 9765, 10116, -1, 10117, 9767, 10118, -1, 9765, 9767, 10117, -1, 10118, 9768, 10119, -1, 9767, 9768, 10118, -1, 10119, 9769, 10120, -1, 9768, 9769, 10119, -1, 10120, 9782, 10121, -1, 9769, 9782, 10120, -1, 9742, 9737, 10122, -1, 10122, 9737, 10123, -1, 10123, 9732, 10124, -1, 9737, 9732, 10123, -1, 10124, 9731, 10125, -1, 9732, 9731, 10124, -1, 10125, 9730, 10126, -1, 9731, 9730, 10125, -1, 10126, 9733, 10127, -1, 9730, 9733, 10126, -1, 10127, 9741, 10128, -1, 9733, 9741, 10127, -1, 10128, 9743, 10129, -1, 9741, 9743, 10128, -1, 10129, 9804, 10130, -1, 9743, 9804, 10129, -1, 10130, 9806, 10131, -1, 9804, 9806, 10130, -1, 10131, 9796, 10132, -1, 9806, 9796, 10131, -1, 10132, 9795, 10133, -1, 9796, 9795, 10132, -1, 10133, 9797, 10134, -1, 10134, 9797, 10135, -1, 9795, 9797, 10133, -1, 9797, 9798, 10135, -1, 10136, 10137, 10138, -1, 10139, 10140, 10141, -1, 10142, 10140, 10139, -1, 10140, 10143, 10141, -1, 10137, 10144, 10138, -1, 10145, 10146, 10147, -1, 10104, 10148, 10103, -1, 10073, 10074, 10149, -1, 10149, 10074, 10150, -1, 10103, 10148, 10151, -1, 10051, 10052, 10152, -1, 10145, 10153, 10146, -1, 10154, 10155, 10156, -1, 10157, 10153, 10145, -1, 10152, 10050, 10051, -1, 10156, 10155, 10158, -1, 10156, 10159, 10154, -1, 10160, 10159, 10156, -1, 10074, 10075, 10150, -1, 10144, 10161, 10138, -1, 10052, 10053, 10152, -1, 10155, 10162, 10158, -1, 10158, 10162, 10142, -1, 10163, 10049, 10152, -1, 10157, 10164, 10153, -1, 10152, 10049, 10050, -1, 10160, 10165, 10159, -1, 10166, 10164, 10157, -1, 10140, 10167, 10168, -1, 10162, 10167, 10142, -1, 10142, 10167, 10140, -1, 10053, 10054, 10152, -1, 10160, 10169, 10165, -1, 10161, 10170, 10138, -1, 10167, 10171, 10168, -1, 10163, 10048, 10049, -1, 10166, 10172, 10164, -1, 10171, 10173, 10168, -1, 10104, 10174, 10148, -1, 10163, 10175, 10048, -1, 10105, 10174, 10104, -1, 10176, 10177, 10178, -1, 10163, 10179, 10175, -1, 10163, 10180, 10179, -1, 10150, 10181, 10182, -1, 10182, 10181, 10183, -1, 10183, 10181, 10184, -1, 10170, 10185, 10138, -1, 10184, 10181, 10186, -1, 10075, 10181, 10150, -1, 10187, 10181, 10075, -1, 10163, 10188, 10180, -1, 10189, 10190, 10191, -1, 10192, 10181, 10187, -1, 10178, 10193, 10194, -1, 10195, 10181, 10192, -1, 10143, 10190, 10189, -1, 10177, 10193, 10178, -1, 10196, 10197, 10198, -1, 10199, 10197, 10196, -1, 10166, 10200, 10172, -1, 10201, 10200, 10166, -1, 10160, 10202, 10169, -1, 10163, 10203, 10188, -1, 10204, 10200, 10195, -1, 10199, 10205, 10197, -1, 10172, 10200, 10204, -1, 10195, 10200, 10181, -1, 10202, 10206, 10169, -1, 10185, 10207, 10138, -1, 10055, 10208, 10054, -1, 10056, 10208, 10055, -1, 10057, 10208, 10056, -1, 10058, 10208, 10057, -1, 10059, 10208, 10058, -1, 10209, 10206, 10202, -1, 10193, 10210, 10194, -1, 10054, 10208, 10152, -1, 10211, 10210, 10212, -1, 10194, 10210, 10211, -1, 10163, 10213, 10203, -1, 10094, 10095, 10214, -1, 10209, 10215, 10206, -1, 10216, 10215, 10217, -1, 10217, 10215, 10209, -1, 10210, 10218, 10212, -1, 10214, 10093, 10094, -1, 10212, 10218, 10199, -1, 10219, 10220, 10177, -1, 10214, 10096, 10163, -1, 10216, 10221, 10215, -1, 10222, 10221, 10216, -1, 10199, 10223, 10205, -1, 10163, 10096, 10213, -1, 10218, 10223, 10199, -1, 10095, 10096, 10214, -1, 10214, 10092, 10093, -1, 10222, 10224, 10221, -1, 10225, 10224, 10222, -1, 10223, 10226, 10205, -1, 10213, 10097, 10227, -1, 10225, 10228, 10224, -1, 10229, 10228, 10225, -1, 10230, 10226, 10231, -1, 10232, 10233, 10234, -1, 10205, 10226, 10230, -1, 10207, 10235, 10138, -1, 10096, 10097, 10213, -1, 10214, 10091, 10092, -1, 10226, 10236, 10231, -1, 10231, 10236, 10237, -1, 10235, 10238, 10138, -1, 10097, 10098, 10227, -1, 10227, 10098, 10239, -1, 10239, 10098, 10240, -1, 10214, 10241, 10090, -1, 10214, 10090, 10091, -1, 10242, 10241, 10243, -1, 10200, 10244, 10245, -1, 10246, 10241, 10242, -1, 10247, 10241, 10246, -1, 10248, 10241, 10247, -1, 10201, 10244, 10200, -1, 10249, 10241, 10248, -1, 10090, 10241, 10249, -1, 10250, 10244, 10201, -1, 10251, 10244, 10250, -1, 10240, 10099, 10252, -1, 10253, 10254, 10255, -1, 10098, 10099, 10240, -1, 10238, 10256, 10138, -1, 10257, 10258, 10259, -1, 10259, 10258, 10260, -1, 10252, 10100, 10261, -1, 10241, 10262, 10243, -1, 10257, 10263, 10258, -1, 10099, 10100, 10252, -1, 10254, 10264, 10255, -1, 10265, 10263, 10257, -1, 10266, 10267, 10268, -1, 10265, 10269, 10263, -1, 10261, 10101, 10270, -1, 10173, 10267, 10168, -1, 10100, 10101, 10261, -1, 10268, 10267, 10173, -1, 10271, 10269, 10265, -1, 10255, 10272, 10273, -1, 10251, 10274, 10244, -1, 10264, 10272, 10255, -1, 10275, 10274, 10251, -1, 10276, 10274, 10275, -1, 10273, 10277, 10278, -1, 10272, 10277, 10273, -1, 10278, 10037, 10279, -1, 10280, 10281, 10282, -1, 10244, 10283, 10245, -1, 10037, 10038, 10279, -1, 10278, 10036, 10037, -1, 10038, 10039, 10279, -1, 10278, 10035, 10036, -1, 10271, 10284, 10269, -1, 10277, 10035, 10278, -1, 10279, 10040, 10285, -1, 10039, 10040, 10279, -1, 10277, 10034, 10035, -1, 10285, 10041, 10286, -1, 10281, 10287, 10282, -1, 10040, 10041, 10285, -1, 10277, 10288, 10034, -1, 10282, 10289, 10290, -1, 10287, 10289, 10282, -1, 10286, 10291, 10266, -1, 10266, 10291, 10267, -1, 10041, 10042, 10286, -1, 10292, 10293, 10274, -1, 10271, 10294, 10284, -1, 10286, 10042, 10291, -1, 10208, 10294, 10271, -1, 10277, 10295, 10288, -1, 10274, 10296, 10292, -1, 10290, 10297, 10298, -1, 10079, 10080, 10262, -1, 10289, 10297, 10290, -1, 10042, 10043, 10291, -1, 10262, 10078, 10079, -1, 10277, 10299, 10295, -1, 10293, 10300, 10274, -1, 10208, 10301, 10294, -1, 10043, 10044, 10291, -1, 10277, 10302, 10299, -1, 10274, 10303, 10296, -1, 10044, 10045, 10291, -1, 10080, 10081, 10262, -1, 10277, 10304, 10302, -1, 10060, 10305, 10059, -1, 10061, 10305, 10060, -1, 10059, 10305, 10208, -1, 10208, 10305, 10301, -1, 10262, 10077, 10078, -1, 10045, 10046, 10291, -1, 10262, 10082, 10243, -1, 10306, 10307, 10061, -1, 10243, 10082, 10308, -1, 10061, 10307, 10305, -1, 10309, 10310, 10306, -1, 10081, 10082, 10262, -1, 10276, 10311, 10274, -1, 10262, 10076, 10077, -1, 10274, 10311, 10303, -1, 10306, 10310, 10307, -1, 10267, 10312, 10168, -1, 10313, 10314, 10309, -1, 10308, 10083, 10315, -1, 10082, 10083, 10308, -1, 10309, 10314, 10310, -1, 10300, 10316, 10274, -1, 10317, 10318, 10313, -1, 10105, 10319, 10174, -1, 10313, 10318, 10314, -1, 10320, 10319, 10107, -1, 10321, 10322, 10323, -1, 10106, 10319, 10105, -1, 10276, 10322, 10311, -1, 10239, 10324, 10317, -1, 10107, 10319, 10106, -1, 10323, 10322, 10276, -1, 10317, 10324, 10318, -1, 10325, 10326, 10262, -1, 10262, 10326, 10076, -1, 10233, 10327, 10234, -1, 10239, 10240, 10324, -1, 10083, 10084, 10315, -1, 10297, 10328, 10298, -1, 10190, 10329, 10233, -1, 10316, 10330, 10274, -1, 10233, 10329, 10327, -1, 10325, 10331, 10326, -1, 10325, 10332, 10331, -1, 10277, 10333, 10304, -1, 10334, 10333, 10335, -1, 10336, 10333, 10334, -1, 10337, 10333, 10336, -1, 10338, 10333, 10337, -1, 10339, 10333, 10338, -1, 10340, 10333, 10339, -1, 10304, 10333, 10340, -1, 10321, 10341, 10322, -1, 10325, 10342, 10332, -1, 10335, 10343, 10047, -1, 10333, 10343, 10335, -1, 10327, 10344, 10345, -1, 10325, 10346, 10342, -1, 10325, 10347, 10346, -1, 10046, 10348, 10291, -1, 10343, 10348, 10047, -1, 10270, 10349, 10321, -1, 10047, 10348, 10046, -1, 10348, 10350, 10291, -1, 10350, 10351, 10291, -1, 10321, 10349, 10341, -1, 10351, 10352, 10291, -1, 10353, 10354, 10355, -1, 10355, 10354, 10356, -1, 10357, 10358, 10359, -1, 10353, 10360, 10354, -1, 10291, 10361, 10362, -1, 10363, 10360, 10353, -1, 10352, 10361, 10291, -1, 10363, 10364, 10360, -1, 10365, 10364, 10363, -1, 10366, 10367, 10352, -1, 10352, 10367, 10361, -1, 10368, 10369, 10370, -1, 10370, 10369, 10371, -1, 10148, 10372, 10219, -1, 10138, 10274, 10330, -1, 10138, 10330, 10373, -1, 10138, 10373, 10374, -1, 10138, 10374, 10375, -1, 10138, 10375, 10376, -1, 10138, 10376, 10377, -1, 10087, 10378, 10086, -1, 10367, 10379, 10138, -1, 10367, 10138, 10256, -1, 10367, 10256, 10372, -1, 10367, 10372, 10380, -1, 10367, 10380, 10381, -1, 10367, 10381, 10371, -1, 10367, 10371, 10369, -1, 10367, 10369, 10345, -1, 10367, 10345, 10344, -1, 10367, 10344, 10359, -1, 10367, 10359, 10358, -1, 10382, 10383, 10384, -1, 10367, 10358, 10361, -1, 10086, 10385, 10085, -1, 10138, 10379, 10386, -1, 10378, 10385, 10086, -1, 10219, 10151, 10148, -1, 10176, 10219, 10177, -1, 10319, 10381, 10174, -1, 10174, 10381, 10380, -1, 10140, 10329, 10143, -1, 10087, 10387, 10378, -1, 10143, 10329, 10190, -1, 10329, 10344, 10327, -1, 10088, 10387, 10087, -1, 10365, 10388, 10364, -1, 10085, 10389, 10084, -1, 10385, 10389, 10085, -1, 10383, 10390, 10384, -1, 10088, 10391, 10387, -1, 10089, 10391, 10088, -1, 10389, 10392, 10084, -1, 10390, 10393, 10384, -1, 10384, 10393, 10394, -1, 10315, 10392, 10395, -1, 10084, 10392, 10315, -1, 10396, 10397, 10398, -1, 10399, 10397, 10396, -1, 10089, 10400, 10391, -1, 10401, 10400, 10089, -1, 10402, 10400, 10401, -1, 10365, 10403, 10388, -1, 10404, 10403, 10365, -1, 10395, 10405, 10406, -1, 10394, 10407, 10408, -1, 10392, 10405, 10395, -1, 10393, 10407, 10394, -1, 10406, 10409, 10410, -1, 10405, 10409, 10406, -1, 10404, 10411, 10403, -1, 10412, 10186, 10379, -1, 10409, 10413, 10410, -1, 10101, 10414, 10270, -1, 10415, 10414, 10416, -1, 10417, 10414, 10415, -1, 10349, 10414, 10417, -1, 10270, 10414, 10349, -1, 10219, 10372, 10220, -1, 10418, 10372, 10256, -1, 10419, 10372, 10418, -1, 10420, 10372, 10419, -1, 10421, 10372, 10420, -1, 10422, 10372, 10421, -1, 10065, 10066, 10408, -1, 10423, 10372, 10422, -1, 10424, 10372, 10423, -1, 10425, 10372, 10424, -1, 10426, 10372, 10425, -1, 10427, 10372, 10426, -1, 10220, 10372, 10427, -1, 10325, 10428, 10347, -1, 10186, 10386, 10379, -1, 10429, 10428, 10402, -1, 10181, 10386, 10186, -1, 10408, 10064, 10065, -1, 10430, 10428, 10429, -1, 10431, 10428, 10430, -1, 10432, 10428, 10431, -1, 10414, 10433, 10416, -1, 10347, 10428, 10432, -1, 10402, 10428, 10400, -1, 10066, 10067, 10408, -1, 10408, 10067, 10149, -1, 10434, 10435, 10428, -1, 10428, 10435, 10400, -1, 10408, 10063, 10064, -1, 10436, 10437, 10438, -1, 10439, 10440, 10441, -1, 10067, 10068, 10149, -1, 10441, 10440, 10434, -1, 10434, 10440, 10435, -1, 10408, 10062, 10063, -1, 10414, 10442, 10433, -1, 10298, 10443, 10404, -1, 10444, 10445, 10439, -1, 10437, 10446, 10438, -1, 10439, 10445, 10440, -1, 10404, 10443, 10411, -1, 10447, 10448, 10444, -1, 10101, 10151, 10414, -1, 10068, 10069, 10149, -1, 10444, 10448, 10445, -1, 10449, 10450, 10447, -1, 10447, 10450, 10448, -1, 10298, 10451, 10443, -1, 10452, 10453, 10320, -1, 10102, 10151, 10101, -1, 10454, 10453, 10452, -1, 10103, 10151, 10102, -1, 10320, 10453, 10319, -1, 10408, 10455, 10062, -1, 10446, 10456, 10438, -1, 10407, 10455, 10408, -1, 10298, 10457, 10451, -1, 10328, 10457, 10298, -1, 10069, 10070, 10149, -1, 10456, 10458, 10438, -1, 10407, 10459, 10455, -1, 10328, 10460, 10457, -1, 10070, 10071, 10149, -1, 10461, 10462, 10328, -1, 10463, 10464, 10465, -1, 10466, 10467, 10458, -1, 10397, 10467, 10398, -1, 10458, 10467, 10438, -1, 10328, 10462, 10460, -1, 10407, 10468, 10459, -1, 10469, 10467, 10470, -1, 10471, 10467, 10469, -1, 10472, 10467, 10471, -1, 10473, 10467, 10472, -1, 10474, 10467, 10473, -1, 10475, 10467, 10474, -1, 10398, 10467, 10475, -1, 10323, 10476, 10461, -1, 10464, 10477, 10465, -1, 10438, 10467, 10397, -1, 10461, 10476, 10462, -1, 10465, 10478, 10479, -1, 10071, 10072, 10149, -1, 10377, 10480, 10138, -1, 10477, 10478, 10465, -1, 10466, 10481, 10467, -1, 10482, 10160, 10156, -1, 10479, 10160, 10482, -1, 10323, 10276, 10476, -1, 10478, 10160, 10479, -1, 10481, 10483, 10467, -1, 10453, 10368, 10370, -1, 10484, 10368, 10454, -1, 10485, 10368, 10484, -1, 10467, 10176, 10470, -1, 10407, 10145, 10468, -1, 10454, 10368, 10453, -1, 10486, 10176, 10487, -1, 10470, 10176, 10486, -1, 10468, 10145, 10147, -1, 10483, 10488, 10467, -1, 10480, 10136, 10138, -1, 10370, 10371, 10489, -1, 10176, 10178, 10487, -1, 10072, 10073, 10149, -1, 10488, 10490, 10467, -1, 10410, 10141, 10485, -1, 10413, 10141, 10410, -1, 10139, 10141, 10413, -1, 10485, 10141, 10368, -1, 10163, 9889, 10214, -1, 9820, 9889, 10163, -1, 9889, 10491, 10214, -1, 9889, 10492, 10491, -1, 10493, 10494, 10492, -1, 10492, 10494, 10491, -1, 10495, 10496, 10493, -1, 10493, 10496, 10494, -1, 10497, 10498, 10495, -1, 10495, 10498, 10496, -1, 10499, 10500, 10497, -1, 10497, 10500, 10498, -1, 10501, 10502, 10499, -1, 10499, 10502, 10500, -1, 10503, 10504, 10501, -1, 10501, 10504, 10502, -1, 10505, 10504, 10506, -1, 10504, 10503, 10506, -1, 9802, 9820, 10152, -1, 9820, 10163, 10152, -1, 10507, 10508, 10509, -1, 10510, 10511, 10507, -1, 10507, 10511, 10508, -1, 10241, 9982, 10262, -1, 10509, 9982, 10241, -1, 10508, 9982, 10509, -1, 10512, 10513, 10510, -1, 10510, 10513, 10511, -1, 10514, 10515, 10512, -1, 10512, 10515, 10513, -1, 10516, 10517, 10514, -1, 10514, 10517, 10515, -1, 9982, 9994, 10262, -1, 10516, 10518, 10517, -1, 10519, 10520, 10516, -1, 10516, 10520, 10518, -1, 10519, 10521, 10520, -1, 10521, 10522, 10520, -1, 9994, 10325, 10262, -1, 9681, 10325, 9994, -1, 9798, 9799, 10135, -1, 10135, 9799, 10523, -1, 10523, 9816, 10524, -1, 9799, 9816, 10523, -1, 10524, 9817, 10525, -1, 9816, 9817, 10524, -1, 10525, 9818, 10526, -1, 9817, 9818, 10525, -1, 10526, 9821, 10527, -1, 9818, 9821, 10526, -1, 10527, 9822, 10528, -1, 9821, 9822, 10527, -1, 10528, 9823, 10529, -1, 9822, 9823, 10528, -1, 10529, 9776, 10530, -1, 9823, 9776, 10529, -1, 10530, 9773, 10531, -1, 9776, 9773, 10530, -1, 10531, 9766, 10532, -1, 9773, 9766, 10531, -1, 10532, 9751, 10533, -1, 9766, 9751, 10532, -1, 10533, 9747, 10534, -1, 9751, 9747, 10533, -1, 10534, 9742, 10122, -1, 9747, 9742, 10534, -1, 10121, 9782, 10535, -1, 10535, 9781, 10536, -1, 9782, 9781, 10535, -1, 9781, 9783, 10536, -1, 10536, 9786, 10537, -1, 9783, 9786, 10536, -1, 10537, 9787, 10538, -1, 10538, 9787, 10539, -1, 9786, 9787, 10537, -1, 9787, 9789, 10539, -1, 10539, 9727, 10540, -1, 9789, 9727, 10539, -1, 10540, 9726, 10541, -1, 9727, 9726, 10540, -1, 10541, 9728, 10542, -1, 10542, 9728, 10543, -1, 9726, 9728, 10541, -1, 9728, 9746, 10543, -1, 10543, 9738, 10544, -1, 9746, 9738, 10543, -1, 10544, 9734, 10545, -1, 10545, 9734, 10546, -1, 9738, 9734, 10544, -1, 9734, 9729, 10546, -1, 10546, 9718, 10108, -1, 9729, 9718, 10546, -1, 10020, 10029, 10333, -1, 10333, 10029, 10343, -1, 10343, 10032, 10348, -1, 10029, 10032, 10343, -1, 10348, 9672, 10350, -1, 10032, 9672, 10348, -1, 10351, 9675, 10352, -1, 10350, 9675, 10351, -1, 9672, 9675, 10350, -1, 9675, 9688, 10352, -1, 10186, 9690, 10184, -1, 9690, 9683, 10184, -1, 10184, 9674, 10183, -1, 9683, 9674, 10184, -1, 10183, 9871, 10182, -1, 9674, 9871, 10183, -1, 10182, 9854, 10150, -1, 9871, 9854, 10182, -1, 10150, 9753, 10149, -1, 9854, 9753, 10150, -1, 10547, 10548, 9722, -1, 9722, 10548, 9717, -1, 9717, 10549, 9713, -1, 10548, 10549, 9717, -1, 9713, 10550, 9707, -1, 10549, 10550, 9713, -1, 9707, 10551, 9708, -1, 10550, 10551, 9707, -1, 9708, 10552, 9709, -1, 10551, 10552, 9708, -1, 9709, 10553, 9716, -1, 10552, 10553, 9709, -1, 9716, 10554, 9719, -1, 10553, 10554, 9716, -1, 9719, 10555, 9723, -1, 10554, 10555, 9719, -1, 9966, 10277, 9959, -1, 9959, 10272, 9952, -1, 10277, 10272, 9959, -1, 10272, 10264, 9952, -1, 9952, 10254, 9957, -1, 10264, 10254, 9952, -1, 9957, 10253, 9956, -1, 10254, 10253, 9957, -1, 9953, 10255, 9954, -1, 9956, 10255, 9953, -1, 10253, 10255, 9956, -1, 9954, 10273, 9960, -1, 10255, 10273, 9954, -1, 10273, 10278, 9960, -1, 9920, 10206, 9923, -1, 9925, 10215, 9926, -1, 9923, 10215, 9925, -1, 10206, 10215, 9923, -1, 9926, 10221, 9933, -1, 10215, 10221, 9926, -1, 9933, 10224, 9935, -1, 10221, 10224, 9933, -1, 9935, 10228, 9937, -1, 10224, 10228, 9935, -1, 9937, 10229, 9936, -1, 10228, 10229, 9937, -1, 9936, 10225, 9934, -1, 10229, 10225, 9936, -1, 9934, 10222, 9927, -1, 10225, 10222, 9934, -1, 9927, 10216, 9924, -1, 10222, 10216, 9927, -1, 10216, 10217, 9924, -1, 9924, 10209, 9919, -1, 10217, 10209, 9924, -1, 10209, 10202, 9919, -1, 9872, 10160, 9868, -1, 9868, 10478, 9856, -1, 10160, 10478, 9868, -1, 10478, 10477, 9856, -1, 9856, 10464, 9864, -1, 10477, 10464, 9856, -1, 9864, 10463, 9860, -1, 10464, 10463, 9864, -1, 9857, 10465, 9858, -1, 9860, 10465, 9857, -1, 10463, 10465, 9860, -1, 9858, 10479, 9869, -1, 10465, 10479, 9858, -1, 10479, 10482, 9869, -1, 9824, 10435, 9827, -1, 9832, 10440, 9833, -1, 9827, 10440, 9832, -1, 10435, 10440, 9827, -1, 9833, 10445, 9839, -1, 10440, 10445, 9833, -1, 9839, 10448, 9841, -1, 10445, 10448, 9839, -1, 9841, 10450, 9843, -1, 10448, 10450, 9841, -1, 9843, 10449, 9842, -1, 10450, 10449, 9843, -1, 9842, 10447, 9840, -1, 10449, 10447, 9842, -1, 9840, 10444, 9835, -1, 10447, 10444, 9840, -1, 9835, 10439, 9828, -1, 10444, 10439, 9835, -1, 10439, 10441, 9828, -1, 9828, 10434, 9808, -1, 10441, 10434, 9828, -1, 10434, 10428, 9808, -1, 9853, 10208, 9930, -1, 9929, 10271, 9916, -1, 9930, 10271, 9929, -1, 10208, 10271, 9930, -1, 9916, 10265, 9913, -1, 10271, 10265, 9916, -1, 9913, 10257, 9905, -1, 10265, 10257, 9913, -1, 9905, 10259, 9906, -1, 10257, 10259, 9905, -1, 9906, 10260, 9904, -1, 10259, 10260, 9906, -1, 9904, 10258, 9912, -1, 10260, 10258, 9904, -1, 9912, 10263, 9915, -1, 10258, 10263, 9912, -1, 9915, 10269, 9928, -1, 10263, 10269, 9915, -1, 10269, 10284, 9928, -1, 9928, 10294, 9950, -1, 10284, 10294, 9928, -1, 10294, 10301, 9950, -1, 9949, 10297, 9947, -1, 9947, 10289, 9940, -1, 10297, 10289, 9947, -1, 10289, 10287, 9940, -1, 9940, 10281, 9944, -1, 10287, 10281, 9940, -1, 9944, 10280, 9943, -1, 10281, 10280, 9944, -1, 9941, 10282, 9942, -1, 9943, 10282, 9941, -1, 10280, 10282, 9943, -1, 9942, 10290, 9775, -1, 10282, 10290, 9942, -1, 10290, 10298, 9775, -1, 9721, 10404, 9679, -1, 9677, 10365, 9678, -1, 9679, 10365, 9677, -1, 10404, 10365, 9679, -1, 9678, 10363, 10018, -1, 10365, 10363, 9678, -1, 10018, 10353, 10015, -1, 10363, 10353, 10018, -1, 10015, 10355, 10016, -1, 10353, 10355, 10015, -1, 10016, 10356, 10014, -1, 10355, 10356, 10016, -1, 10014, 10354, 10017, -1, 10356, 10354, 10014, -1, 10017, 10360, 9684, -1, 10354, 10360, 10017, -1, 9684, 10364, 9676, -1, 10360, 10364, 9684, -1, 10364, 10388, 9676, -1, 9676, 10403, 9720, -1, 10388, 10403, 9676, -1, 10403, 10411, 9720, -1, 9715, 10407, 9704, -1, 9704, 10393, 9694, -1, 10407, 10393, 9704, -1, 10393, 10390, 9694, -1, 9694, 10383, 9699, -1, 10390, 10383, 9694, -1, 9699, 10382, 9697, -1, 10383, 10382, 9699, -1, 9695, 10384, 9696, -1, 9697, 10384, 9695, -1, 10382, 10384, 9697, -1, 9696, 10394, 9705, -1, 10384, 10394, 9696, -1, 10394, 10408, 9705, -1, 9700, 9693, 10556, -1, 10556, 9693, 10557, -1, 10557, 9691, 10558, -1, 9693, 9691, 10557, -1, 10558, 9685, 10559, -1, 9691, 9685, 10558, -1, 10559, 9687, 10560, -1, 9685, 9687, 10559, -1, 10560, 9686, 10561, -1, 9687, 9686, 10560, -1, 10561, 9689, 10562, -1, 9686, 9689, 10561, -1, 10562, 9692, 10563, -1, 9689, 9692, 10562, -1, 10563, 9698, 10564, -1, 9692, 9698, 10563, -1, 10520, 10503, 10518, -1, 10518, 10501, 10517, -1, 10503, 10501, 10518, -1, 10517, 10499, 10515, -1, 10501, 10499, 10517, -1, 10515, 10497, 10513, -1, 10499, 10497, 10515, -1, 10513, 10495, 10511, -1, 10497, 10495, 10513, -1, 10511, 10493, 10508, -1, 10495, 10493, 10511, -1, 10508, 10492, 9982, -1, 10493, 10492, 10508, -1, 10492, 9889, 9982, -1, 10565, 10566, 10567, -1, 10568, 10569, 10567, -1, 10570, 10571, 10572, -1, 10573, 10574, 10575, -1, 10576, 10574, 10573, -1, 10577, 10576, 10573, -1, 10578, 10566, 10565, -1, 10579, 10576, 10577, -1, 10580, 10571, 10570, -1, 10581, 10579, 10577, -1, 10582, 10579, 10581, -1, 10583, 10568, 10567, -1, 10584, 10582, 10581, -1, 10584, 10585, 10582, -1, 10586, 10566, 10578, -1, 10587, 10585, 10584, -1, 10588, 10587, 10584, -1, 10589, 10585, 10587, -1, 10590, 10567, 10591, -1, 10592, 10588, 10584, -1, 10590, 10583, 10567, -1, 10520, 10593, 10594, -1, 10520, 10595, 10593, -1, 10596, 10585, 10589, -1, 10520, 10597, 10595, -1, 10598, 10592, 10584, -1, 10520, 10599, 10600, -1, 10520, 10601, 10599, -1, 10520, 10602, 10601, -1, 10520, 10594, 10602, -1, 10603, 10566, 10586, -1, 10604, 10585, 10596, -1, 10520, 10600, 10503, -1, 10522, 10605, 10597, -1, 10522, 10606, 10605, -1, 10522, 10607, 10606, -1, 10608, 10598, 10584, -1, 10522, 10580, 10607, -1, 10522, 10571, 10580, -1, 10522, 10597, 10520, -1, 10609, 10585, 10604, -1, 10610, 10608, 10584, -1, 10611, 10612, 10613, -1, 10614, 10566, 10603, -1, 10615, 10611, 10613, -1, 10615, 10613, 10616, -1, 10617, 10585, 10609, -1, 10617, 10618, 10619, -1, 10617, 10609, 10618, -1, 10620, 10617, 10619, -1, 10621, 10616, 10622, -1, 10621, 10615, 10616, -1, 10623, 10621, 10622, -1, 10623, 10622, 10566, -1, 10624, 10617, 10620, -1, 10625, 10617, 10624, -1, 10626, 10614, 10627, -1, 10626, 10566, 10614, -1, 10626, 10623, 10566, -1, 10628, 10617, 10625, -1, 10629, 10626, 10627, -1, 10630, 10631, 10617, -1, 10632, 10630, 10617, -1, 10632, 10617, 10628, -1, 10633, 10626, 10629, -1, 10634, 10626, 10633, -1, 10635, 10636, 10637, -1, 10635, 10610, 10584, -1, 10635, 10638, 10610, -1, 10635, 10639, 10638, -1, 10640, 10626, 10634, -1, 10635, 10641, 10639, -1, 10635, 10642, 10641, -1, 10635, 10637, 10642, -1, 10643, 10644, 10591, -1, 10645, 10646, 10647, -1, 10645, 10648, 10646, -1, 10649, 10590, 10591, -1, 10650, 10651, 10648, -1, 10650, 10652, 10651, -1, 10649, 10591, 10644, -1, 10650, 10648, 10645, -1, 10653, 10635, 10652, -1, 10653, 10636, 10635, -1, 10653, 10652, 10650, -1, 10654, 10643, 10591, -1, 10655, 10590, 10649, -1, 10655, 10656, 10590, -1, 10657, 10658, 10659, -1, 10657, 10654, 10591, -1, 10660, 10661, 10662, -1, 10657, 10591, 10658, -1, 10663, 10661, 10660, -1, 10664, 10656, 10655, -1, 10664, 10665, 10656, -1, 10664, 10666, 10665, -1, 10667, 10663, 10660, -1, 10664, 10668, 10666, -1, 10669, 10663, 10667, -1, 10670, 10659, 10671, -1, 10670, 10657, 10659, -1, 10672, 10669, 10667, -1, 10673, 10669, 10672, -1, 10674, 10675, 10673, -1, 10674, 10673, 10672, -1, 10676, 10636, 10653, -1, 10676, 10677, 10636, -1, 10676, 10678, 10677, -1, 10676, 10679, 10678, -1, 10680, 10632, 10679, -1, 10680, 10679, 10676, -1, 10681, 10630, 10632, -1, 10681, 10632, 10680, -1, 10682, 10630, 10681, -1, 10683, 10630, 10682, -1, 10684, 10630, 10683, -1, 10685, 10668, 10664, -1, 10658, 10630, 10684, -1, 10686, 10675, 10674, -1, 10687, 10626, 10640, -1, 10687, 10688, 10689, -1, 10687, 10690, 10688, -1, 10687, 10691, 10690, -1, 10687, 10692, 10691, -1, 10687, 10668, 10685, -1, 10687, 10640, 10692, -1, 10687, 10689, 10668, -1, 10693, 10687, 10685, -1, 10694, 10687, 10693, -1, 10694, 10693, 10695, -1, 10696, 10694, 10695, -1, 10697, 10694, 10696, -1, 10698, 10697, 10696, -1, 10699, 10697, 10698, -1, 10700, 10686, 10674, -1, 10701, 10702, 10703, -1, 10701, 10704, 10702, -1, 10705, 10704, 10701, -1, 10705, 10706, 10704, -1, 10705, 10707, 10706, -1, 10708, 10709, 10710, -1, 10711, 10707, 10705, -1, 10711, 10700, 10707, -1, 10712, 10710, 10713, -1, 10712, 10708, 10710, -1, 10714, 10712, 10713, -1, 10715, 10716, 10717, -1, 10714, 10713, 10718, -1, 10719, 10716, 10715, -1, 10720, 10719, 10715, -1, 10721, 10718, 10722, -1, 10721, 10714, 10718, -1, 10723, 10719, 10720, -1, 10724, 10722, 10725, -1, 10724, 10721, 10722, -1, 10726, 10723, 10720, -1, 10727, 10723, 10726, -1, 10728, 10729, 10730, -1, 10731, 10727, 10726, -1, 10732, 10728, 10730, -1, 10731, 10733, 10727, -1, 10734, 10735, 10686, -1, 10732, 10730, 10736, -1, 10734, 10686, 10700, -1, 10734, 10700, 10711, -1, 10737, 10738, 10729, -1, 10739, 10740, 10735, -1, 10737, 10729, 10728, -1, 10741, 10670, 10671, -1, 10739, 10735, 10734, -1, 10741, 10736, 10670, -1, 10742, 10743, 10740, -1, 10741, 10732, 10736, -1, 10742, 10740, 10739, -1, 10744, 10738, 10737, -1, 10744, 10745, 10738, -1, 10746, 10747, 10743, -1, 10746, 10743, 10742, -1, 10748, 10671, 10749, -1, 10750, 10751, 10747, -1, 10748, 10741, 10671, -1, 10750, 10747, 10746, -1, 10752, 10725, 10745, -1, 10671, 10751, 10750, -1, 10671, 10659, 10751, -1, 10752, 10745, 10744, -1, 10753, 10754, 10755, -1, 10753, 10749, 10754, -1, 10753, 10748, 10749, -1, 10756, 10755, 10757, -1, 10756, 10753, 10755, -1, 10758, 10759, 10731, -1, 10760, 10731, 10759, -1, 10761, 10725, 10752, -1, 10761, 10724, 10725, -1, 10761, 10752, 10762, -1, 10763, 10758, 10731, -1, 10764, 10761, 10762, -1, 10765, 10733, 10731, -1, 10766, 10761, 10764, -1, 10765, 10731, 10760, -1, 10766, 10764, 10767, -1, 10768, 10766, 10767, -1, 10769, 10763, 10731, -1, 10770, 10766, 10768, -1, 10771, 10770, 10768, -1, 10772, 10773, 10733, -1, 10774, 10770, 10771, -1, 10772, 10733, 10765, -1, 10775, 10773, 10772, -1, 10776, 10773, 10775, -1, 10777, 10778, 10773, -1, 10777, 10773, 10776, -1, 10779, 10780, 10781, -1, 10782, 10783, 10778, -1, 10782, 10778, 10777, -1, 10784, 10781, 10785, -1, 10784, 10779, 10781, -1, 10786, 10783, 10782, -1, 10786, 10787, 10783, -1, 10788, 10785, 10789, -1, 10788, 10784, 10785, -1, 10790, 10789, 10791, -1, 10792, 10793, 10787, -1, 10790, 10788, 10789, -1, 10792, 10787, 10786, -1, 10571, 10790, 10791, -1, 10757, 10793, 10792, -1, 10757, 10755, 10793, -1, 10794, 10795, 10796, -1, 10797, 10796, 10798, -1, 10797, 10794, 10796, -1, 10799, 10795, 10794, -1, 10506, 10800, 10801, -1, 10802, 10798, 10803, -1, 10506, 10769, 10731, -1, 10802, 10797, 10798, -1, 10506, 10804, 10769, -1, 10506, 10805, 10804, -1, 10506, 10801, 10805, -1, 10503, 10806, 10800, -1, 10503, 10807, 10806, -1, 10808, 10795, 10799, -1, 10503, 10809, 10807, -1, 10503, 10810, 10809, -1, 10503, 10811, 10810, -1, 10812, 10803, 10813, -1, 10503, 10814, 10811, -1, 10812, 10802, 10803, -1, 10503, 10815, 10814, -1, 10503, 10800, 10506, -1, 10816, 10791, 10795, -1, 10591, 10630, 10658, -1, 10816, 10795, 10808, -1, 10817, 10813, 10756, -1, 10817, 10756, 10757, -1, 10817, 10812, 10813, -1, 10818, 10571, 10791, -1, 10567, 10819, 10591, -1, 10818, 10791, 10816, -1, 10820, 10817, 10757, -1, 10820, 10757, 10821, -1, 10822, 10571, 10818, -1, 10600, 10815, 10503, -1, 10823, 10824, 10567, -1, 10600, 10820, 10821, -1, 10600, 10821, 10815, -1, 10825, 10567, 10824, -1, 10569, 10823, 10567, -1, 10826, 10571, 10822, -1, 10565, 10567, 10825, -1, 10572, 10571, 10826, -1, 10827, 10816, 10828, -1, 10828, 10808, 10829, -1, 10816, 10808, 10828, -1, 10829, 10799, 10830, -1, 10808, 10799, 10829, -1, 10830, 10794, 10831, -1, 10799, 10794, 10830, -1, 10831, 10797, 10832, -1, 10794, 10797, 10831, -1, 10832, 10802, 10833, -1, 10797, 10802, 10832, -1, 10833, 10812, 10834, -1, 10802, 10812, 10833, -1, 10834, 10817, 10835, -1, 10812, 10817, 10834, -1, 10835, 10820, 10836, -1, 10817, 10820, 10835, -1, 10836, 10600, 10837, -1, 10820, 10600, 10836, -1, 10837, 10599, 10838, -1, 10600, 10599, 10837, -1, 10838, 10601, 10839, -1, 10599, 10601, 10838, -1, 10839, 10602, 10840, -1, 10601, 10602, 10839, -1, 10602, 10594, 10840, -1, 10841, 10578, 10842, -1, 10842, 10565, 10843, -1, 10578, 10565, 10842, -1, 10843, 10825, 10844, -1, 10565, 10825, 10843, -1, 10844, 10824, 10845, -1, 10825, 10824, 10844, -1, 10845, 10823, 10846, -1, 10824, 10823, 10845, -1, 10846, 10569, 10847, -1, 10823, 10569, 10846, -1, 10847, 10568, 10848, -1, 10569, 10568, 10847, -1, 10848, 10583, 10849, -1, 10568, 10583, 10848, -1, 10849, 10590, 10850, -1, 10583, 10590, 10849, -1, 10850, 10656, 10851, -1, 10590, 10656, 10850, -1, 10851, 10665, 10852, -1, 10656, 10665, 10851, -1, 10852, 10666, 10853, -1, 10665, 10666, 10852, -1, 10853, 10668, 10854, -1, 10666, 10668, 10853, -1, 10668, 10689, 10854, -1, 10604, 10596, 10855, -1, 10855, 10596, 10856, -1, 10856, 10589, 10857, -1, 10596, 10589, 10856, -1, 10857, 10587, 10858, -1, 10589, 10587, 10857, -1, 10858, 10588, 10859, -1, 10587, 10588, 10858, -1, 10859, 10592, 10860, -1, 10588, 10592, 10859, -1, 10860, 10598, 10861, -1, 10592, 10598, 10860, -1, 10861, 10608, 10862, -1, 10598, 10608, 10861, -1, 10862, 10610, 10863, -1, 10608, 10610, 10862, -1, 10863, 10638, 10864, -1, 10610, 10638, 10863, -1, 10864, 10639, 10865, -1, 10638, 10639, 10864, -1, 10865, 10641, 10866, -1, 10639, 10641, 10865, -1, 10866, 10642, 10867, -1, 10867, 10642, 10868, -1, 10641, 10642, 10866, -1, 10642, 10637, 10868, -1, 10869, 10772, 10870, -1, 10870, 10765, 10871, -1, 10772, 10765, 10870, -1, 10871, 10760, 10872, -1, 10765, 10760, 10871, -1, 10872, 10759, 10873, -1, 10760, 10759, 10872, -1, 10873, 10758, 10874, -1, 10759, 10758, 10873, -1, 10874, 10763, 10875, -1, 10758, 10763, 10874, -1, 10875, 10769, 10876, -1, 10763, 10769, 10875, -1, 10876, 10804, 10877, -1, 10769, 10804, 10876, -1, 10877, 10805, 10878, -1, 10804, 10805, 10877, -1, 10878, 10801, 10879, -1, 10805, 10801, 10878, -1, 10879, 10800, 10880, -1, 10801, 10800, 10879, -1, 10880, 10806, 10881, -1, 10800, 10806, 10880, -1, 10806, 10807, 10881, -1, 10881, 10809, 10882, -1, 10807, 10809, 10881, -1, 10631, 10630, 10883, -1, 10630, 10884, 10883, -1, 10885, 10884, 10630, -1, 10886, 10887, 10885, -1, 10885, 10887, 10884, -1, 10888, 10889, 10886, -1, 10886, 10889, 10887, -1, 10888, 10890, 10889, -1, 10891, 10888, 10892, -1, 10890, 10888, 10891, -1, 10591, 10819, 10893, -1, 10819, 10894, 10893, -1, 10893, 10895, 10591, -1, 10896, 10895, 10893, -1, 10897, 10898, 10896, -1, 10896, 10898, 10895, -1, 10899, 10900, 10897, -1, 10897, 10900, 10898, -1, 10899, 10901, 10900, -1, 10902, 10901, 10899, -1, 10762, 10903, 10764, -1, 10767, 10904, 10768, -1, 10764, 10904, 10767, -1, 10903, 10904, 10764, -1, 10768, 10905, 10771, -1, 10904, 10905, 10768, -1, 10905, 10906, 10771, -1, 10774, 10907, 10770, -1, 10771, 10907, 10774, -1, 10906, 10907, 10771, -1, 10770, 10908, 10766, -1, 10907, 10908, 10770, -1, 10908, 10909, 10766, -1, 10766, 10910, 10761, -1, 10909, 10910, 10766, -1, 10910, 10911, 10761, -1, 10571, 10912, 10790, -1, 10790, 10913, 10788, -1, 10912, 10913, 10790, -1, 10788, 10914, 10784, -1, 10913, 10914, 10788, -1, 10784, 10915, 10779, -1, 10914, 10915, 10784, -1, 10779, 10916, 10780, -1, 10915, 10916, 10779, -1, 10780, 10917, 10781, -1, 10916, 10917, 10780, -1, 10781, 10918, 10785, -1, 10917, 10918, 10781, -1, 10785, 10919, 10789, -1, 10918, 10919, 10785, -1, 10789, 10920, 10791, -1, 10919, 10920, 10789, -1, 10920, 10921, 10791, -1, 10724, 10922, 10721, -1, 10721, 10923, 10714, -1, 10922, 10923, 10721, -1, 10714, 10924, 10712, -1, 10923, 10924, 10714, -1, 10712, 10925, 10708, -1, 10924, 10925, 10712, -1, 10708, 10926, 10709, -1, 10925, 10926, 10708, -1, 10709, 10927, 10710, -1, 10926, 10927, 10709, -1, 10710, 10928, 10713, -1, 10927, 10928, 10710, -1, 10713, 10929, 10718, -1, 10928, 10929, 10713, -1, 10718, 10930, 10722, -1, 10929, 10930, 10718, -1, 10930, 10931, 10722, -1, 10685, 10932, 10693, -1, 10695, 10933, 10696, -1, 10693, 10933, 10695, -1, 10932, 10933, 10693, -1, 10696, 10934, 10698, -1, 10933, 10934, 10696, -1, 10934, 10935, 10698, -1, 10699, 10936, 10697, -1, 10698, 10936, 10699, -1, 10935, 10936, 10698, -1, 10697, 10937, 10694, -1, 10936, 10937, 10697, -1, 10937, 10938, 10694, -1, 10694, 10939, 10687, -1, 10938, 10939, 10694, -1, 10939, 10940, 10687, -1, 10626, 10941, 10623, -1, 10623, 10942, 10621, -1, 10941, 10942, 10623, -1, 10621, 10943, 10615, -1, 10942, 10943, 10621, -1, 10615, 10944, 10611, -1, 10943, 10944, 10615, -1, 10611, 10945, 10612, -1, 10944, 10945, 10611, -1, 10612, 10946, 10613, -1, 10945, 10946, 10612, -1, 10613, 10947, 10616, -1, 10946, 10947, 10613, -1, 10616, 10948, 10622, -1, 10947, 10948, 10616, -1, 10622, 10949, 10566, -1, 10948, 10949, 10622, -1, 10949, 10950, 10566, -1, 10585, 10951, 10582, -1, 10582, 10952, 10579, -1, 10951, 10952, 10582, -1, 10579, 10953, 10576, -1, 10952, 10953, 10579, -1, 10576, 10954, 10574, -1, 10953, 10954, 10576, -1, 10574, 10955, 10575, -1, 10954, 10955, 10574, -1, 10575, 10956, 10573, -1, 10955, 10956, 10575, -1, 10573, 10957, 10577, -1, 10956, 10957, 10573, -1, 10577, 10958, 10581, -1, 10957, 10958, 10577, -1, 10581, 10959, 10584, -1, 10958, 10959, 10581, -1, 10959, 10960, 10584, -1, 10961, 10674, 10962, -1, 10962, 10672, 10963, -1, 10674, 10672, 10962, -1, 10963, 10667, 10964, -1, 10672, 10667, 10963, -1, 10964, 10660, 10965, -1, 10667, 10660, 10964, -1, 10965, 10662, 10966, -1, 10660, 10662, 10965, -1, 10966, 10661, 10967, -1, 10662, 10661, 10966, -1, 10967, 10663, 10968, -1, 10661, 10663, 10967, -1, 10968, 10669, 10969, -1, 10663, 10669, 10968, -1, 10969, 10673, 10970, -1, 10669, 10673, 10969, -1, 10673, 10675, 10970, -1, 10635, 10971, 10652, -1, 10651, 10972, 10648, -1, 10652, 10972, 10651, -1, 10971, 10972, 10652, -1, 10648, 10973, 10646, -1, 10972, 10973, 10648, -1, 10973, 10974, 10646, -1, 10647, 10975, 10645, -1, 10646, 10975, 10647, -1, 10974, 10975, 10646, -1, 10645, 10976, 10650, -1, 10975, 10976, 10645, -1, 10976, 10977, 10650, -1, 10650, 10978, 10653, -1, 10977, 10978, 10650, -1, 10978, 10979, 10653, -1, 10700, 10980, 10707, -1, 10706, 10981, 10704, -1, 10707, 10981, 10706, -1, 10980, 10981, 10707, -1, 10704, 10982, 10702, -1, 10981, 10982, 10704, -1, 10982, 10983, 10702, -1, 10703, 10984, 10701, -1, 10702, 10984, 10703, -1, 10983, 10984, 10702, -1, 10701, 10985, 10705, -1, 10984, 10985, 10701, -1, 10985, 10986, 10705, -1, 10705, 10987, 10711, -1, 10986, 10987, 10705, -1, 10987, 10988, 10711, -1, 10989, 10731, 10990, -1, 10990, 10726, 10991, -1, 10731, 10726, 10990, -1, 10991, 10720, 10992, -1, 10726, 10720, 10991, -1, 10992, 10715, 10993, -1, 10720, 10715, 10992, -1, 10993, 10717, 10994, -1, 10715, 10717, 10993, -1, 10994, 10716, 10995, -1, 10717, 10716, 10994, -1, 10995, 10719, 10996, -1, 10716, 10719, 10995, -1, 10996, 10723, 10997, -1, 10719, 10723, 10996, -1, 10997, 10727, 10998, -1, 10723, 10727, 10997, -1, 10727, 10733, 10998, -1, 10888, 10999, 10892, -1, 11000, 11001, 11002, -1, 11003, 11002, 10999, -1, 11003, 11000, 11002, -1, 11004, 11003, 10999, -1, 10900, 10999, 10888, -1, 10900, 11004, 10999, -1, 10901, 11004, 10900, -1, 10898, 10888, 10886, -1, 10898, 10886, 10885, -1, 10898, 10900, 10888, -1, 10895, 10885, 10630, -1, 10895, 10898, 10885, -1, 10591, 10895, 10630, -1, 11005, 11006, 11001, -1, 11007, 11001, 11006, -1, 11008, 11005, 11001, -1, 11009, 11001, 11007, -1, 11010, 11008, 11001, -1, 11011, 11001, 11009, -1, 11011, 11012, 11001, -1, 11013, 11010, 11001, -1, 11014, 11015, 11016, -1, 11014, 11017, 11015, -1, 11018, 11014, 11016, -1, 11018, 11016, 11019, -1, 11020, 11018, 11019, -1, 11020, 11019, 11012, -1, 11021, 11020, 11012, -1, 11022, 11012, 11011, -1, 11022, 11021, 11012, -1, 11023, 11021, 11022, -1, 11024, 11021, 11023, -1, 11025, 11021, 11024, -1, 11026, 11021, 11025, -1, 11027, 11021, 11026, -1, 11028, 11021, 11027, -1, 11029, 11021, 11028, -1, 11030, 11031, 11032, -1, 11033, 11032, 11034, -1, 11033, 11030, 11032, -1, 11035, 11036, 11031, -1, 11035, 11031, 11030, -1, 11037, 11034, 11038, -1, 11037, 11033, 11034, -1, 11039, 11040, 11036, -1, 11039, 11036, 11035, -1, 11041, 11038, 11013, -1, 11041, 11013, 11001, -1, 11041, 11037, 11038, -1, 11042, 11040, 11039, -1, 11043, 11044, 11040, -1, 11043, 11040, 11042, -1, 11045, 11046, 11044, -1, 11045, 11044, 11043, -1, 11047, 11046, 11045, -1, 11047, 11048, 11046, -1, 11049, 11048, 11047, -1, 11049, 11050, 11048, -1, 11051, 11050, 11049, -1, 11051, 11052, 11050, -1, 11053, 11052, 11051, -1, 11053, 11054, 11052, -1, 11055, 11056, 11057, -1, 11058, 11055, 11057, -1, 11058, 11057, 11059, -1, 11060, 11056, 11055, -1, 11060, 11061, 11056, -1, 11062, 11059, 11063, -1, 11062, 11058, 11059, -1, 11064, 11061, 11060, -1, 11064, 11065, 11061, -1, 11066, 11062, 11063, -1, 11067, 11065, 11064, -1, 11067, 11068, 11065, -1, 11069, 11068, 11067, -1, 11069, 11070, 11068, -1, 11069, 11071, 11070, -1, 11072, 11071, 11069, -1, 11072, 11073, 11071, -1, 11074, 11073, 11072, -1, 11074, 11075, 11073, -1, 11076, 11075, 11074, -1, 11076, 11077, 11075, -1, 11078, 11077, 11076, -1, 11078, 11079, 11077, -1, 11080, 11079, 11078, -1, 11000, 11081, 11082, -1, 11000, 11082, 11083, -1, 11000, 11083, 11084, -1, 11000, 11084, 11085, -1, 11000, 11085, 11086, -1, 11000, 11086, 11087, -1, 11000, 11087, 11066, -1, 11000, 11066, 11063, -1, 11000, 11063, 11041, -1, 11000, 11041, 11001, -1, 11088, 11089, 11090, -1, 11088, 11090, 11091, -1, 11088, 11091, 11092, -1, 11088, 11092, 11093, -1, 11088, 11093, 11094, -1, 11088, 11094, 11095, -1, 11088, 11095, 11096, -1, 11097, 11096, 11081, -1, 11097, 11081, 11000, -1, 11097, 11088, 11096, -1, 11098, 11088, 11097, -1, 11099, 11088, 11098, -1, 11100, 11099, 11098, -1, 11101, 11099, 11100, -1, 11102, 11101, 11100, -1, 11103, 11101, 11102, -1, 11104, 11103, 11102, -1, 11088, 11021, 11029, -1, 11088, 11029, 11054, -1, 11088, 11054, 11105, -1, 11105, 11054, 11053, -1, 11088, 11105, 11106, -1, 11088, 11106, 11079, -1, 11088, 11079, 11089, -1, 11089, 11079, 11080, -1, 11107, 11088, 11108, -1, 11108, 11099, 11109, -1, 11088, 11099, 11108, -1, 11109, 11101, 11110, -1, 11099, 11101, 11109, -1, 11110, 11103, 11111, -1, 11101, 11103, 11110, -1, 11111, 11104, 11112, -1, 11103, 11104, 11111, -1, 11112, 11102, 11113, -1, 11104, 11102, 11112, -1, 11113, 11100, 11114, -1, 11102, 11100, 11113, -1, 11114, 11098, 11115, -1, 11100, 11098, 11114, -1, 11098, 11097, 11115, -1, 11116, 11012, 11117, -1, 11117, 11019, 11118, -1, 11012, 11019, 11117, -1, 11118, 11016, 11119, -1, 11019, 11016, 11118, -1, 11119, 11015, 11120, -1, 11016, 11015, 11119, -1, 11120, 11017, 11121, -1, 11015, 11017, 11120, -1, 11121, 11014, 11122, -1, 11017, 11014, 11121, -1, 11122, 11018, 11123, -1, 11014, 11018, 11122, -1, 11123, 11020, 11124, -1, 11018, 11020, 11123, -1, 11020, 11021, 11124, -1, 9581, 10367, 9579, -1, 8393, 9584, 9578, -1, 9571, 9572, 10379, -1, 9571, 10379, 10367, -1, 9571, 10367, 9581, -1, 9569, 9581, 9584, -1, 9569, 9571, 9581, -1, 8819, 9569, 9584, -1, 8819, 9584, 8393, -1, 9566, 9569, 8819, -1, 10504, 10519, 10516, -1, 10502, 10516, 10514, -1, 10502, 10504, 10516, -1, 10500, 10514, 10512, -1, 10500, 10502, 10514, -1, 10498, 10512, 10510, -1, 10498, 10500, 10512, -1, 10496, 10510, 10507, -1, 10496, 10498, 10510, -1, 10494, 10496, 10507, -1, 10491, 10507, 10509, -1, 10491, 10494, 10507, -1, 10214, 10509, 10241, -1, 10214, 10491, 10509, -1, 10890, 10899, 10889, -1, 10889, 10897, 10887, -1, 10899, 10897, 10889, -1, 10897, 10896, 10887, -1, 10887, 10893, 10884, -1, 10896, 10893, 10887, -1, 10912, 11125, 11126, -1, 11127, 10842, 10843, -1, 10950, 10842, 11127, -1, 10954, 10956, 10955, -1, 10912, 11128, 11125, -1, 10953, 10957, 10954, -1, 10954, 10957, 10956, -1, 10846, 10847, 11127, -1, 10912, 11129, 11128, -1, 10953, 10958, 10957, -1, 10950, 10841, 10842, -1, 10953, 10952, 10958, -1, 10952, 10959, 10958, -1, 10912, 11130, 11129, -1, 10952, 10951, 10959, -1, 10951, 10960, 10959, -1, 10847, 10848, 11127, -1, 10951, 10858, 10960, -1, 10858, 10859, 10960, -1, 10951, 10857, 10858, -1, 10859, 10860, 10960, -1, 10950, 11131, 10841, -1, 10951, 10856, 10857, -1, 10860, 10861, 10960, -1, 10848, 10849, 11127, -1, 10951, 10855, 10856, -1, 11132, 10519, 10840, -1, 11127, 10849, 10893, -1, 11133, 10519, 11132, -1, 11134, 10519, 11133, -1, 10861, 10862, 10960, -1, 11135, 10519, 10504, -1, 10837, 10519, 10836, -1, 10838, 10519, 10837, -1, 10839, 10519, 10838, -1, 10840, 10519, 10839, -1, 10950, 11136, 11131, -1, 10951, 11137, 10855, -1, 10836, 10519, 11135, -1, 11138, 10521, 11134, -1, 11139, 10521, 11138, -1, 11140, 10521, 11139, -1, 10862, 10863, 10960, -1, 11130, 10521, 11140, -1, 10912, 10521, 11130, -1, 11134, 10521, 10519, -1, 10945, 10944, 10946, -1, 10946, 10944, 10947, -1, 10951, 11141, 11137, -1, 11142, 11141, 11143, -1, 11137, 11141, 11142, -1, 10950, 11144, 11136, -1, 10944, 10943, 10947, -1, 10947, 10943, 10948, -1, 11141, 11145, 11143, -1, 11141, 11146, 11145, -1, 10943, 10942, 10948, -1, 10948, 10942, 10949, -1, 11141, 11147, 11146, -1, 11144, 10941, 11148, -1, 11141, 11149, 11147, -1, 10950, 10941, 11144, -1, 10942, 10941, 10949, -1, 10949, 10941, 10950, -1, 10883, 10884, 11141, -1, 10941, 11150, 11148, -1, 11141, 11151, 11149, -1, 10884, 11151, 11141, -1, 10941, 11152, 11150, -1, 10863, 10971, 10960, -1, 10941, 11153, 11152, -1, 11154, 10971, 10868, -1, 10864, 10971, 10863, -1, 10865, 10971, 10864, -1, 10866, 10971, 10865, -1, 10941, 11155, 11153, -1, 10867, 10971, 10866, -1, 10868, 10971, 10867, -1, 10973, 10975, 10974, -1, 10972, 10976, 10973, -1, 10973, 10976, 10975, -1, 11156, 11157, 10893, -1, 10972, 10977, 10976, -1, 10893, 11158, 11156, -1, 10972, 10978, 10977, -1, 10971, 10978, 10972, -1, 10849, 11158, 10893, -1, 11154, 10979, 10971, -1, 10971, 10979, 10978, -1, 11157, 11159, 10893, -1, 10849, 11160, 11158, -1, 10850, 11160, 10849, -1, 10967, 10965, 10966, -1, 10893, 11161, 11162, -1, 11159, 11161, 10893, -1, 10968, 10964, 10967, -1, 10850, 11163, 11160, -1, 10967, 10964, 10965, -1, 10851, 11163, 10850, -1, 10852, 11163, 10851, -1, 10853, 11163, 10852, -1, 10968, 10963, 10964, -1, 11161, 11164, 11162, -1, 10968, 10969, 10963, -1, 11162, 11164, 11165, -1, 11165, 11164, 11166, -1, 10969, 10962, 10963, -1, 10969, 10970, 10962, -1, 10970, 10961, 10962, -1, 11167, 11168, 11154, -1, 11169, 11168, 11167, -1, 11170, 11168, 11169, -1, 11154, 11168, 10979, -1, 11151, 11171, 11170, -1, 11170, 11171, 11168, -1, 11151, 11172, 11171, -1, 10884, 11172, 11151, -1, 10884, 11173, 11172, -1, 10884, 11174, 11173, -1, 10884, 11175, 11174, -1, 10884, 11162, 11175, -1, 10970, 11176, 10961, -1, 10853, 10932, 11163, -1, 10941, 10940, 11155, -1, 11177, 10940, 10854, -1, 11178, 10940, 11177, -1, 11179, 10940, 11178, -1, 11180, 10940, 11179, -1, 11155, 10940, 11180, -1, 10853, 10940, 10932, -1, 10854, 10940, 10853, -1, 10940, 10939, 10932, -1, 10939, 10933, 10932, -1, 10939, 10938, 10933, -1, 10938, 10937, 10933, -1, 10933, 10937, 10934, -1, 11176, 10980, 10961, -1, 10937, 10936, 10934, -1, 10934, 10936, 10935, -1, 10982, 10984, 10983, -1, 10982, 10985, 10984, -1, 10981, 10985, 10982, -1, 10981, 10986, 10985, -1, 10980, 10987, 10981, -1, 10981, 10987, 10986, -1, 10980, 10988, 10987, -1, 10926, 10925, 10927, -1, 10927, 10925, 10928, -1, 10995, 10993, 10994, -1, 10928, 10924, 10929, -1, 10925, 10924, 10928, -1, 10995, 10992, 10993, -1, 10996, 10992, 10995, -1, 10996, 10991, 10992, -1, 10929, 10923, 10930, -1, 10924, 10923, 10929, -1, 10996, 10997, 10991, -1, 10997, 10990, 10991, -1, 10931, 10922, 11181, -1, 10930, 10922, 10931, -1, 10923, 10922, 10930, -1, 10997, 10998, 10990, -1, 11182, 11183, 11184, -1, 10998, 10989, 10990, -1, 11176, 11185, 10980, -1, 11186, 11185, 11176, -1, 10980, 11185, 10988, -1, 11184, 11187, 11188, -1, 11186, 11189, 11185, -1, 11190, 11189, 11186, -1, 11183, 11187, 11184, -1, 11190, 11191, 11189, -1, 11192, 11193, 11182, -1, 11194, 11191, 11190, -1, 11182, 11193, 11183, -1, 11188, 11195, 11164, -1, 11196, 11197, 11194, -1, 11166, 11195, 11198, -1, 11164, 11195, 11166, -1, 11194, 11197, 11191, -1, 11187, 11195, 11188, -1, 11199, 11200, 11196, -1, 11201, 11202, 11192, -1, 11196, 11200, 11197, -1, 11192, 11202, 11193, -1, 11165, 11166, 11199, -1, 11199, 11166, 11200, -1, 11195, 11203, 11198, -1, 11181, 11204, 11201, -1, 11201, 11204, 11202, -1, 11198, 11205, 11206, -1, 11203, 11205, 11198, -1, 11207, 11208, 11209, -1, 11206, 11208, 11207, -1, 11205, 11208, 11206, -1, 10872, 10873, 10989, -1, 10989, 10871, 10872, -1, 10873, 10874, 10989, -1, 10998, 10870, 10989, -1, 10989, 10870, 10871, -1, 11204, 10911, 10903, -1, 10922, 10911, 11181, -1, 11181, 10911, 11204, -1, 10911, 10910, 10903, -1, 10874, 10875, 10989, -1, 10910, 10904, 10903, -1, 11210, 10869, 10998, -1, 10910, 10909, 10904, -1, 10998, 10869, 10870, -1, 10909, 10908, 10904, -1, 10904, 10908, 10905, -1, 10908, 10907, 10905, -1, 10905, 10907, 10906, -1, 11210, 11211, 10869, -1, 11210, 11212, 11211, -1, 11213, 11214, 11210, -1, 11210, 11214, 11212, -1, 11215, 11216, 11213, -1, 11213, 11216, 11214, -1, 11215, 11217, 11216, -1, 11218, 11217, 11215, -1, 10916, 10915, 10917, -1, 10917, 10915, 10918, -1, 11219, 11220, 11218, -1, 11218, 11220, 11217, -1, 10915, 10914, 10918, -1, 10918, 10914, 10919, -1, 11207, 11209, 11219, -1, 11219, 11209, 11220, -1, 10914, 10913, 10919, -1, 10919, 10913, 10920, -1, 10913, 10912, 10920, -1, 10920, 10912, 10921, -1, 11221, 10830, 11222, -1, 11222, 10831, 11223, -1, 10879, 10505, 10878, -1, 10830, 10831, 11222, -1, 11221, 10829, 10830, -1, 10875, 10505, 10989, -1, 10876, 10505, 10875, -1, 10877, 10505, 10876, -1, 10878, 10505, 10877, -1, 10880, 10504, 10879, -1, 11223, 10832, 11224, -1, 10881, 10504, 10880, -1, 10882, 10504, 10881, -1, 10831, 10832, 11223, -1, 11225, 10504, 10882, -1, 11226, 10504, 11225, -1, 11227, 10504, 11226, -1, 11135, 10504, 11227, -1, 10879, 10504, 10505, -1, 11221, 10828, 10829, -1, 11224, 10833, 11228, -1, 10884, 10893, 11162, -1, 10832, 10833, 11224, -1, 10921, 10827, 11221, -1, 11221, 10827, 10828, -1, 10894, 11127, 10893, -1, 11228, 10834, 11208, -1, 10833, 10834, 11228, -1, 11208, 10834, 11209, -1, 10912, 11229, 10921, -1, 10921, 11229, 10827, -1, 10834, 10835, 11209, -1, 11209, 10835, 11230, -1, 10844, 10845, 11127, -1, 10912, 11126, 11229, -1, 11127, 10843, 10844, -1, 10835, 10836, 11230, -1, 11230, 10836, 11135, -1, 10845, 10846, 11127, -1, 10891, 11116, 10890, -1, 11231, 11232, 10890, -1, 10890, 11233, 11231, -1, 11232, 11234, 10890, -1, 10890, 11235, 11233, -1, 11234, 11236, 10890, -1, 10890, 11237, 11235, -1, 11236, 11238, 10890, -1, 11120, 11121, 11119, -1, 11119, 11122, 11118, -1, 11121, 11122, 11119, -1, 11118, 11123, 11117, -1, 11122, 11123, 11118, -1, 11117, 11124, 11116, -1, 11123, 11124, 11117, -1, 11116, 11239, 10890, -1, 10890, 11239, 11237, -1, 11124, 11239, 11116, -1, 11124, 11240, 11239, -1, 11124, 11241, 11240, -1, 11124, 11242, 11241, -1, 11124, 11243, 11242, -1, 11124, 11244, 11243, -1, 11124, 11245, 11244, -1, 11124, 11246, 11245, -1, 11247, 11248, 11249, -1, 11249, 11250, 11251, -1, 11248, 11250, 11249, -1, 11252, 11253, 11247, -1, 11247, 11253, 11248, -1, 11251, 11254, 11255, -1, 11250, 11254, 11251, -1, 11256, 11257, 11252, -1, 11252, 11257, 11253, -1, 11255, 11258, 11238, -1, 11238, 11258, 10890, -1, 11254, 11258, 11255, -1, 11256, 11259, 11257, -1, 11260, 11261, 11256, -1, 11256, 11261, 11259, -1, 11260, 11262, 11261, -1, 11263, 11262, 11260, -1, 11264, 11265, 11263, -1, 11263, 11265, 11262, -1, 11266, 11267, 11264, -1, 11264, 11267, 11265, -1, 11268, 11269, 11266, -1, 11266, 11269, 11267, -1, 11270, 11271, 11268, -1, 11268, 11271, 11269, -1, 11272, 11273, 11274, -1, 11273, 11275, 11274, -1, 11274, 11275, 11276, -1, 11272, 11277, 11273, -1, 11278, 11277, 11272, -1, 11275, 11279, 11276, -1, 11276, 11279, 11280, -1, 11278, 11281, 11277, -1, 11282, 11281, 11278, -1, 11279, 11283, 11280, -1, 11282, 11284, 11281, -1, 11285, 11284, 11282, -1, 11285, 11286, 11284, -1, 11287, 11286, 11285, -1, 11288, 11286, 11287, -1, 11289, 10899, 11290, -1, 11290, 10899, 11291, -1, 11291, 10899, 11292, -1, 11292, 10899, 11293, -1, 11293, 10899, 11294, -1, 11294, 10899, 11295, -1, 11295, 10899, 11283, -1, 11283, 10899, 11280, -1, 11280, 10899, 11258, -1, 11258, 10899, 10890, -1, 11296, 11297, 11288, -1, 11288, 11297, 11286, -1, 11298, 11299, 11296, -1, 11296, 11299, 11297, -1, 11300, 11301, 11298, -1, 11298, 11301, 11299, -1, 11302, 11303, 11300, -1, 11300, 11303, 11301, -1, 11302, 11304, 11303, -1, 11289, 11305, 10899, -1, 11305, 11115, 10899, -1, 10899, 11115, 10902, -1, 11305, 11107, 11115, -1, 11306, 11107, 11307, -1, 11307, 11107, 11308, -1, 11308, 11107, 11309, -1, 11309, 11107, 11310, -1, 11310, 11107, 11311, -1, 11311, 11107, 11312, -1, 11312, 11107, 11305, -1, 11107, 11108, 11115, -1, 11108, 11114, 11115, -1, 11108, 11109, 11114, -1, 11109, 11113, 11114, -1, 11109, 11110, 11113, -1, 11110, 11112, 11113, -1, 11110, 11111, 11112, -1, 11124, 11107, 11246, -1, 11246, 11107, 11270, -1, 11270, 11107, 11313, -1, 11270, 11313, 11271, -1, 11313, 11107, 11314, -1, 11314, 11107, 11302, -1, 11302, 11107, 11306, -1, 11302, 11306, 11304, -1, 11042, 11039, 11259, -1, 11259, 11039, 11257, -1, 11257, 11035, 11253, -1, 11039, 11035, 11257, -1, 11253, 11030, 11248, -1, 11035, 11030, 11253, -1, 11248, 11033, 11250, -1, 11030, 11033, 11248, -1, 11250, 11037, 11254, -1, 11033, 11037, 11250, -1, 11254, 11041, 11258, -1, 11037, 11041, 11254, -1, 11258, 11063, 11280, -1, 11041, 11063, 11258, -1, 11280, 11059, 11276, -1, 11063, 11059, 11280, -1, 11276, 11057, 11274, -1, 11059, 11057, 11276, -1, 11274, 11056, 11272, -1, 11057, 11056, 11274, -1, 11272, 11061, 11278, -1, 11056, 11061, 11272, -1, 11278, 11065, 11282, -1, 11061, 11065, 11278, -1, 11282, 11068, 11285, -1, 11065, 11068, 11282, -1, 11067, 11064, 11284, -1, 11284, 11064, 11281, -1, 11281, 11060, 11277, -1, 11064, 11060, 11281, -1, 11277, 11055, 11273, -1, 11060, 11055, 11277, -1, 11273, 11058, 11275, -1, 11055, 11058, 11273, -1, 11275, 11062, 11279, -1, 11058, 11062, 11275, -1, 11279, 11066, 11283, -1, 11062, 11066, 11279, -1, 11283, 11087, 11295, -1, 11066, 11087, 11283, -1, 11295, 11086, 11294, -1, 11087, 11086, 11295, -1, 11294, 11085, 11293, -1, 11086, 11085, 11294, -1, 11293, 11084, 11292, -1, 11085, 11084, 11293, -1, 11292, 11083, 11291, -1, 11084, 11083, 11292, -1, 11291, 11082, 11290, -1, 11083, 11082, 11291, -1, 11290, 11081, 11289, -1, 11082, 11081, 11290, -1, 11011, 11009, 11237, -1, 11237, 11009, 11235, -1, 11235, 11007, 11233, -1, 11009, 11007, 11235, -1, 11233, 11006, 11231, -1, 11007, 11006, 11233, -1, 11231, 11005, 11232, -1, 11006, 11005, 11231, -1, 11232, 11008, 11234, -1, 11005, 11008, 11232, -1, 11234, 11010, 11236, -1, 11008, 11010, 11234, -1, 11236, 11013, 11238, -1, 11010, 11013, 11236, -1, 11238, 11038, 11255, -1, 11013, 11038, 11238, -1, 11255, 11034, 11251, -1, 11038, 11034, 11255, -1, 11251, 11032, 11249, -1, 11034, 11032, 11251, -1, 11249, 11031, 11247, -1, 11032, 11031, 11249, -1, 11247, 11036, 11252, -1, 11031, 11036, 11247, -1, 11252, 11040, 11256, -1, 11036, 11040, 11252, -1, 10809, 10810, 10882, -1, 10882, 10810, 11225, -1, 11225, 10811, 11226, -1, 10810, 10811, 11225, -1, 11226, 10814, 11227, -1, 10811, 10814, 11226, -1, 11227, 10815, 11135, -1, 10814, 10815, 11227, -1, 11135, 10821, 11230, -1, 10815, 10821, 11135, -1, 11230, 10757, 11209, -1, 10821, 10757, 11230, -1, 11209, 10792, 11220, -1, 10757, 10792, 11209, -1, 11220, 10786, 11217, -1, 10792, 10786, 11220, -1, 11217, 10782, 11216, -1, 10786, 10782, 11217, -1, 11216, 10777, 11214, -1, 10782, 10777, 11216, -1, 11214, 10776, 11212, -1, 10777, 10776, 11214, -1, 11212, 10775, 11211, -1, 10776, 10775, 11212, -1, 11211, 10772, 10869, -1, 10775, 10772, 11211, -1, 10637, 10636, 10868, -1, 10868, 10636, 11154, -1, 11154, 10677, 11167, -1, 10636, 10677, 11154, -1, 11167, 10678, 11169, -1, 10677, 10678, 11167, -1, 11169, 10679, 11170, -1, 10678, 10679, 11169, -1, 11170, 10632, 11151, -1, 10679, 10632, 11170, -1, 11151, 10628, 11149, -1, 10632, 10628, 11151, -1, 11149, 10625, 11147, -1, 10628, 10625, 11149, -1, 11147, 10624, 11146, -1, 10625, 10624, 11147, -1, 11146, 10620, 11145, -1, 10624, 10620, 11146, -1, 11145, 10619, 11143, -1, 10620, 10619, 11145, -1, 11143, 10618, 11142, -1, 10619, 10618, 11143, -1, 11142, 10609, 11137, -1, 10618, 10609, 11142, -1, 11137, 10604, 10855, -1, 10609, 10604, 11137, -1, 10689, 10688, 10854, -1, 10854, 10688, 11177, -1, 11177, 10690, 11178, -1, 10688, 10690, 11177, -1, 11178, 10691, 11179, -1, 10690, 10691, 11178, -1, 11179, 10692, 11180, -1, 10691, 10692, 11179, -1, 11180, 10640, 11155, -1, 10692, 10640, 11180, -1, 11155, 10634, 11153, -1, 10640, 10634, 11155, -1, 11153, 10633, 11152, -1, 10634, 10633, 11153, -1, 11152, 10629, 11150, -1, 10633, 10629, 11152, -1, 11150, 10627, 11148, -1, 10629, 10627, 11150, -1, 11148, 10614, 11144, -1, 10627, 10614, 11148, -1, 11144, 10603, 11136, -1, 10614, 10603, 11144, -1, 11136, 10586, 11131, -1, 10603, 10586, 11136, -1, 11131, 10578, 10841, -1, 10586, 10578, 11131, -1, 10594, 10593, 10840, -1, 10840, 10593, 11132, -1, 11132, 10595, 11133, -1, 10593, 10595, 11132, -1, 11133, 10597, 11134, -1, 10595, 10597, 11133, -1, 11134, 10605, 11138, -1, 10597, 10605, 11134, -1, 11138, 10606, 11139, -1, 10605, 10606, 11138, -1, 11139, 10607, 11140, -1, 10606, 10607, 11139, -1, 11140, 10580, 11130, -1, 10607, 10580, 11140, -1, 11130, 10570, 11129, -1, 10580, 10570, 11130, -1, 11129, 10572, 11128, -1, 10570, 10572, 11129, -1, 11128, 10826, 11125, -1, 10572, 10826, 11128, -1, 11125, 10822, 11126, -1, 10826, 10822, 11125, -1, 11126, 10818, 11229, -1, 10822, 10818, 11126, -1, 11229, 10816, 10827, -1, 10818, 10816, 11229, -1, 10107, 9969, 10320, -1, 9969, 9903, 10320, -1, 10320, 9899, 10452, -1, 9903, 9899, 10320, -1, 10452, 9898, 10454, -1, 9899, 9898, 10452, -1, 10454, 9895, 10484, -1, 9898, 9895, 10454, -1, 10484, 9785, 10485, -1, 9895, 9785, 10484, -1, 10485, 9779, 10410, -1, 9785, 9779, 10485, -1, 10410, 9772, 10406, -1, 9779, 9772, 10410, -1, 10406, 9756, 10395, -1, 9772, 9756, 10406, -1, 10395, 9755, 10315, -1, 9756, 9755, 10395, -1, 10315, 10009, 10308, -1, 9755, 10009, 10315, -1, 10308, 9986, 10243, -1, 10009, 9986, 10308, -1, 10243, 9985, 10242, -1, 9986, 9985, 10243, -1, 10242, 9987, 10246, -1, 9985, 9987, 10242, -1, 10246, 9988, 10247, -1, 9987, 9988, 10246, -1, 10247, 9989, 10248, -1, 9988, 9989, 10247, -1, 9989, 9990, 10248, -1, 10248, 9990, 10249, -1, 9990, 9914, 10249, -1, 10249, 9914, 10090, -1, 9749, 9759, 10089, -1, 10089, 9759, 10401, -1, 10401, 9760, 10402, -1, 9759, 9760, 10401, -1, 10402, 9809, 10429, -1, 9760, 9809, 10402, -1, 10429, 9811, 10430, -1, 9809, 9811, 10429, -1, 10430, 9812, 10431, -1, 9811, 9812, 10430, -1, 10431, 9815, 10432, -1, 9812, 9815, 10431, -1, 10432, 9680, 10347, -1, 9815, 9680, 10432, -1, 10347, 9682, 10346, -1, 9680, 9682, 10347, -1, 10346, 10031, 10342, -1, 9682, 10031, 10346, -1, 10342, 10028, 10332, -1, 10031, 10028, 10342, -1, 10332, 10019, 10331, -1, 10028, 10019, 10332, -1, 10331, 10013, 10326, -1, 10019, 10013, 10331, -1, 10326, 10011, 10076, -1, 10013, 10011, 10326, -1, 10075, 9870, 10187, -1, 10187, 9876, 10192, -1, 9870, 9876, 10187, -1, 10192, 9673, 10195, -1, 9876, 9673, 10192, -1, 10195, 9971, 10204, -1, 9673, 9971, 10195, -1, 10204, 9879, 10172, -1, 9971, 9879, 10204, -1, 10172, 9877, 10164, -1, 9879, 9877, 10172, -1, 10164, 9874, 10153, -1, 9877, 9874, 10164, -1, 10153, 9861, 10146, -1, 9874, 9861, 10153, -1, 10146, 9851, 10147, -1, 9861, 9851, 10146, -1, 10147, 9846, 10468, -1, 9851, 9846, 10147, -1, 10468, 9826, 10459, -1, 9846, 9826, 10468, -1, 10459, 9794, 10455, -1, 9826, 9794, 10459, -1, 10455, 9788, 10062, -1, 9794, 9788, 10455, -1, 9788, 9770, 10062, -1, 9963, 9965, 10061, -1, 10061, 9965, 10306, -1, 10306, 9972, 10309, -1, 9965, 9972, 10306, -1, 10309, 9975, 10313, -1, 9972, 9975, 10309, -1, 10313, 9979, 10317, -1, 9975, 9979, 10313, -1, 10317, 9910, 10239, -1, 9979, 9910, 10317, -1, 10239, 9902, 10227, -1, 9910, 9902, 10239, -1, 10227, 9867, 10213, -1, 9902, 9867, 10227, -1, 10213, 9850, 10203, -1, 9867, 9850, 10213, -1, 10203, 9849, 10188, -1, 9850, 9849, 10203, -1, 10188, 9848, 10180, -1, 9849, 9848, 10188, -1, 10180, 9845, 10179, -1, 9848, 9845, 10180, -1, 10179, 9838, 10175, -1, 9845, 9838, 10179, -1, 10175, 9831, 10048, -1, 9838, 9831, 10175, -1, 10047, 10030, 10335, -1, 10335, 10022, 10334, -1, 10030, 10022, 10335, -1, 10334, 10021, 10336, -1, 10022, 10021, 10334, -1, 10336, 10023, 10337, -1, 10021, 10023, 10336, -1, 10337, 10024, 10338, -1, 10023, 10024, 10337, -1, 10338, 10025, 10339, -1, 10024, 10025, 10338, -1, 10339, 10026, 10340, -1, 10025, 10026, 10339, -1, 10340, 10027, 10304, -1, 10026, 10027, 10340, -1, 10304, 10010, 10302, -1, 10027, 10010, 10304, -1, 10302, 10006, 10299, -1, 10010, 10006, 10302, -1, 10299, 10002, 10295, -1, 10006, 10002, 10299, -1, 10295, 9997, 10288, -1, 10002, 9997, 10295, -1, 10288, 9995, 10034, -1, 9997, 9995, 10288, -1, 9995, 9991, 10034, -1, 8088, 8086, 8385, -1, 8385, 8086, 11315, -1, 11315, 8082, 11316, -1, 8086, 8082, 11315, -1, 11316, 8076, 11317, -1, 8082, 8076, 11316, -1, 11317, 8079, 11318, -1, 8076, 8079, 11317, -1, 11318, 8083, 11319, -1, 8079, 8083, 11318, -1, 11319, 8194, 11320, -1, 8083, 8194, 11319, -1, 11320, 8095, 11321, -1, 8194, 8095, 11320, -1, 11321, 8094, 11322, -1, 8095, 8094, 11321, -1, 11322, 8098, 11323, -1, 8094, 8098, 11322, -1, 11323, 8100, 11324, -1, 8098, 8100, 11323, -1, 11324, 8115, 11325, -1, 8100, 8115, 11324, -1, 11325, 8116, 11326, -1, 8115, 8116, 11325, -1, 11326, 8117, 8372, -1, 8116, 8117, 11326, -1, 8200, 8184, 8371, -1, 8371, 8184, 11327, -1, 11327, 8176, 11328, -1, 8184, 8176, 11327, -1, 11328, 8173, 11329, -1, 8176, 8173, 11328, -1, 11329, 8172, 11330, -1, 8173, 8172, 11329, -1, 11330, 8179, 11331, -1, 8172, 8179, 11330, -1, 11331, 8192, 11332, -1, 8179, 8192, 11331, -1, 11332, 8235, 11333, -1, 8192, 8235, 11332, -1, 11333, 8236, 11334, -1, 8235, 8236, 11333, -1, 11334, 8237, 11335, -1, 8236, 8237, 11334, -1, 11335, 8238, 11336, -1, 8237, 8238, 11335, -1, 11336, 8239, 11337, -1, 8238, 8239, 11336, -1, 11337, 8240, 11338, -1, 8239, 8240, 11337, -1, 11338, 8241, 8358, -1, 8240, 8241, 11338, -1, 11339, 8042, 8027, -1, 11339, 9671, 8042, -1, 8027, 8025, 11339, -1, 11339, 8025, 11340, -1, 11340, 8019, 11341, -1, 8025, 8019, 11340, -1, 11341, 8016, 11342, -1, 8019, 8016, 11341, -1, 11342, 8015, 11343, -1, 8016, 8015, 11342, -1, 11343, 8189, 11344, -1, 8015, 8189, 11343, -1, 11344, 8190, 11345, -1, 8189, 8190, 11344, -1, 11345, 8191, 11346, -1, 8190, 8191, 11345, -1, 11346, 8193, 11347, -1, 8191, 8193, 11346, -1, 11347, 8084, 11348, -1, 8193, 8084, 11347, -1, 11348, 8080, 11349, -1, 8084, 8080, 11348, -1, 11349, 8078, 11350, -1, 8080, 8078, 11349, -1, 11350, 8077, 11351, -1, 8078, 8077, 11350, -1, 11351, 8073, 11352, -1, 8077, 8073, 11351, -1, 8070, 11352, 8073, -1, 9654, 11352, 8070, -1, 11353, 8152, 8132, -1, 11353, 9639, 8152, -1, 8132, 8126, 11353, -1, 11353, 8126, 11354, -1, 11354, 8124, 11355, -1, 8126, 8124, 11354, -1, 11355, 8123, 11356, -1, 8124, 8123, 11355, -1, 11356, 8122, 11357, -1, 8123, 8122, 11356, -1, 11357, 8125, 11358, -1, 8122, 8125, 11357, -1, 11358, 8127, 11359, -1, 8125, 8127, 11358, -1, 11359, 8133, 11360, -1, 8127, 8133, 11359, -1, 11360, 8134, 11361, -1, 8133, 8134, 11360, -1, 11361, 8137, 11362, -1, 8134, 8137, 11361, -1, 11362, 8181, 11363, -1, 8137, 8181, 11362, -1, 11363, 8182, 11364, -1, 8181, 8182, 11363, -1, 11364, 8183, 11365, -1, 8182, 8183, 11364, -1, 11365, 8178, 11366, -1, 8183, 8178, 11365, -1, 9630, 11366, 8178, -1, 9630, 8178, 8175, -1, 11367, 10564, 9698, -1, 10412, 11367, 9698, -1, 9690, 10412, 9698, -1, 10186, 10412, 9690, -1, 10408, 9753, 9705, -1, 10408, 10149, 9753, -1, 10145, 9715, 9844, -1, 10145, 10407, 9715, -1, 9844, 9862, 10145, -1, 10145, 9862, 10157, -1, 10157, 9862, 10166, -1, 10166, 9875, 10201, -1, 9862, 9875, 10166, -1, 10201, 9878, 10250, -1, 9875, 9878, 10201, -1, 10250, 9955, 10251, -1, 9878, 9955, 10250, -1, 10251, 9946, 10275, -1, 9955, 9946, 10251, -1, 10275, 9939, 10276, -1, 9946, 9939, 10275, -1, 10276, 9836, 10476, -1, 9939, 9836, 10276, -1, 10476, 9829, 10462, -1, 9836, 9829, 10476, -1, 10462, 9813, 10460, -1, 9829, 9813, 10462, -1, 10460, 9803, 10457, -1, 9813, 9803, 10460, -1, 10457, 9791, 10451, -1, 9803, 9791, 10457, -1, 10451, 9780, 10443, -1, 9791, 9780, 10451, -1, 9780, 9774, 10443, -1, 10411, 10443, 9774, -1, 10411, 9774, 9720, -1, 9775, 10404, 9721, -1, 10298, 10404, 9775, -1, 10328, 9949, 9792, -1, 10328, 10297, 9949, -1, 10328, 9792, 10461, -1, 9792, 9814, 10461, -1, 10461, 9830, 10323, -1, 9814, 9830, 10461, -1, 10323, 9837, 10321, -1, 9830, 9837, 10323, -1, 10321, 9932, 10270, -1, 9837, 9932, 10321, -1, 10270, 9922, 10261, -1, 9932, 9922, 10270, -1, 10261, 9918, 10252, -1, 9922, 9918, 10261, -1, 10252, 9911, 10240, -1, 9918, 9911, 10252, -1, 10240, 9980, 10324, -1, 9911, 9980, 10240, -1, 10324, 9976, 10318, -1, 9980, 9976, 10324, -1, 10318, 9974, 10314, -1, 9976, 9974, 10318, -1, 10314, 9970, 10310, -1, 9974, 9970, 10314, -1, 10310, 9964, 10307, -1, 9970, 9964, 10310, -1, 10307, 9958, 10305, -1, 9964, 9958, 10307, -1, 10301, 10305, 9958, -1, 10301, 9958, 9950, -1, 9802, 10208, 9853, -1, 10152, 10208, 9802, -1, 10989, 10505, 10506, -1, 10989, 10506, 10731, -1, 11210, 10733, 10773, -1, 11210, 10998, 10733, -1, 10773, 10778, 11210, -1, 11210, 10778, 11213, -1, 11213, 10778, 11215, -1, 11215, 10783, 11218, -1, 10778, 10783, 11215, -1, 11218, 10787, 11219, -1, 10783, 10787, 11218, -1, 11219, 10793, 11207, -1, 10787, 10793, 11219, -1, 11207, 10755, 11206, -1, 10793, 10755, 11207, -1, 11206, 10754, 11198, -1, 10755, 10754, 11206, -1, 11198, 10749, 11166, -1, 10754, 10749, 11198, -1, 11166, 10671, 11200, -1, 10749, 10671, 11166, -1, 11200, 10750, 11197, -1, 10671, 10750, 11200, -1, 11197, 10746, 11191, -1, 10750, 10746, 11197, -1, 11191, 10742, 11189, -1, 10746, 10742, 11191, -1, 11189, 10739, 11185, -1, 10742, 10739, 11189, -1, 10739, 10734, 11185, -1, 10711, 11185, 10734, -1, 10988, 11185, 10711, -1, 10961, 10700, 10674, -1, 10961, 10980, 10700, -1, 11176, 10675, 10686, -1, 11176, 10970, 10675, -1, 10686, 10735, 11176, -1, 11176, 10735, 11186, -1, 11186, 10735, 11190, -1, 11190, 10740, 11194, -1, 10735, 10740, 11190, -1, 11194, 10743, 11196, -1, 10740, 10743, 11194, -1, 11196, 10747, 11199, -1, 10743, 10747, 11196, -1, 11199, 10751, 11165, -1, 10747, 10751, 11199, -1, 11165, 10659, 11162, -1, 10751, 10659, 11165, -1, 11162, 10658, 11175, -1, 10659, 10658, 11162, -1, 11175, 10684, 11174, -1, 10658, 10684, 11175, -1, 11174, 10683, 11173, -1, 10684, 10683, 11174, -1, 11173, 10682, 11172, -1, 10683, 10682, 11173, -1, 11172, 10681, 11171, -1, 10682, 10681, 11172, -1, 11171, 10680, 11168, -1, 10681, 10680, 11171, -1, 10680, 10676, 11168, -1, 10653, 11168, 10676, -1, 10979, 11168, 10653, -1, 10960, 10635, 10584, -1, 10960, 10971, 10635, -1, 11141, 10585, 10617, -1, 11141, 10951, 10585, -1, 10631, 11141, 10617, -1, 10883, 11141, 10631, -1, 10999, 10891, 10892, -1, 11002, 10891, 10999, -1, 11001, 10891, 11002, -1, 11012, 10891, 11001, -1, 11116, 10891, 11012, -1, 11107, 11021, 11088, -1, 11107, 11124, 11021, -1, 11000, 11115, 11097, -1, 10902, 11115, 11000, -1, 10902, 11004, 10901, -1, 10902, 11003, 11004, -1, 10902, 11000, 11003, -1, 10567, 10894, 10819, -1, 11127, 10894, 10567, -1, 10950, 11127, 10567, -1, 10950, 10567, 10566, -1, 10940, 10626, 10687, -1, 10940, 10941, 10626, -1, 10664, 10932, 10685, -1, 11163, 10932, 10664, -1, 11163, 10664, 11160, -1, 10664, 10655, 11160, -1, 11160, 10649, 11158, -1, 10655, 10649, 11160, -1, 11158, 10644, 11156, -1, 10649, 10644, 11158, -1, 11156, 10643, 11157, -1, 10644, 10643, 11156, -1, 11157, 10654, 11159, -1, 10643, 10654, 11157, -1, 11159, 10657, 11161, -1, 10654, 10657, 11159, -1, 11161, 10670, 11164, -1, 10657, 10670, 11161, -1, 11164, 10736, 11188, -1, 10670, 10736, 11164, -1, 11188, 10730, 11184, -1, 10736, 10730, 11188, -1, 11184, 10729, 11182, -1, 10730, 10729, 11184, -1, 11182, 10738, 11192, -1, 10729, 10738, 11182, -1, 11192, 10745, 11201, -1, 10738, 10745, 11192, -1, 11201, 10725, 11181, -1, 10745, 10725, 11201, -1, 10931, 11181, 10725, -1, 10931, 10725, 10722, -1, 10761, 10922, 10724, -1, 10911, 10922, 10761, -1, 10752, 10903, 10762, -1, 11204, 10903, 10752, -1, 11204, 10752, 11202, -1, 11202, 10744, 11193, -1, 10752, 10744, 11202, -1, 11193, 10737, 11183, -1, 10744, 10737, 11193, -1, 11183, 10728, 11187, -1, 10737, 10728, 11183, -1, 11187, 10732, 11195, -1, 10728, 10732, 11187, -1, 11195, 10741, 11203, -1, 10732, 10741, 11195, -1, 11203, 10748, 11205, -1, 10741, 10748, 11203, -1, 11205, 10753, 11208, -1, 10748, 10753, 11205, -1, 11208, 10756, 11228, -1, 10753, 10756, 11208, -1, 11228, 10813, 11224, -1, 10756, 10813, 11228, -1, 11224, 10803, 11223, -1, 10813, 10803, 11224, -1, 11223, 10798, 11222, -1, 10803, 10798, 11223, -1, 11222, 10796, 11221, -1, 10798, 10796, 11222, -1, 10796, 10795, 11221, -1, 10921, 11221, 10795, -1, 10921, 10795, 10791, -1, 10522, 10912, 10571, -1, 10521, 10912, 10522, -1, 10428, 10325, 9681, -1, 10428, 9681, 9808, -1, 9758, 10435, 9824, -1, 10400, 10435, 9758, -1, 9758, 9748, 10400, -1, 10400, 9748, 10391, -1, 10391, 9735, 10387, -1, 9748, 9735, 10391, -1, 10387, 9710, 10378, -1, 9735, 9710, 10387, -1, 10378, 9724, 10385, -1, 9710, 9724, 10378, -1, 10385, 9739, 10389, -1, 9724, 9739, 10385, -1, 10389, 9754, 10392, -1, 9739, 9754, 10389, -1, 10392, 9771, 10405, -1, 9754, 9771, 10392, -1, 10405, 9778, 10409, -1, 9771, 9778, 10405, -1, 10409, 9784, 10413, -1, 9778, 9784, 10409, -1, 10413, 9790, 10139, -1, 9784, 9790, 10413, -1, 10139, 9885, 10142, -1, 9790, 9885, 10139, -1, 10142, 9882, 10158, -1, 9885, 9882, 10142, -1, 10158, 9873, 10156, -1, 9882, 9873, 10158, -1, 9869, 10156, 9873, -1, 10482, 10156, 9869, -1, 9919, 10160, 9872, -1, 10202, 10160, 9919, -1, 10169, 9920, 9893, -1, 10169, 10206, 9920, -1, 10169, 9893, 10165, -1, 9893, 9886, 10165, -1, 10165, 9883, 10159, -1, 9886, 9883, 10165, -1, 10159, 9881, 10154, -1, 9883, 9881, 10159, -1, 10154, 9880, 10155, -1, 9881, 9880, 10154, -1, 10155, 9884, 10162, -1, 9880, 9884, 10155, -1, 10162, 9890, 10167, -1, 9884, 9890, 10162, -1, 10167, 9894, 10171, -1, 9890, 9894, 10167, -1, 10171, 9897, 10173, -1, 9894, 9897, 10171, -1, 10173, 9900, 10268, -1, 9897, 9900, 10173, -1, 10268, 9908, 10266, -1, 9900, 9908, 10268, -1, 10266, 9993, 10286, -1, 9908, 9993, 10266, -1, 10286, 9984, 10285, -1, 9993, 9984, 10286, -1, 10285, 9968, 10279, -1, 9984, 9968, 10285, -1, 9960, 10279, 9968, -1, 10278, 10279, 9960, -1, 10020, 10277, 9966, -1, 10333, 10277, 10020, -1, 10366, 10352, 9688, -1, 9723, 11368, 10366, -1, 9723, 10366, 9688, -1, 10555, 11368, 9723, -1, 11369, 8287, 8309, -1, 11369, 9611, 8287, -1, 11369, 8309, 11370, -1, 8309, 8314, 11370, -1, 11370, 8315, 11371, -1, 8314, 8315, 11370, -1, 11371, 8316, 11372, -1, 8315, 8316, 11371, -1, 11372, 7976, 11373, -1, 8316, 7976, 11372, -1, 11373, 7889, 11374, -1, 7976, 7889, 11373, -1, 11374, 7888, 11375, -1, 7889, 7888, 11374, -1, 11375, 7890, 11376, -1, 7888, 7890, 11375, -1, 11376, 8306, 11377, -1, 7890, 8306, 11376, -1, 11377, 8304, 11378, -1, 8306, 8304, 11377, -1, 11378, 8301, 11379, -1, 8304, 8301, 11378, -1, 11379, 8294, 11380, -1, 8301, 8294, 11379, -1, 11380, 8292, 11381, -1, 8294, 8292, 11380, -1, 11381, 8288, 11382, -1, 8292, 8288, 11381, -1, 9602, 11382, 8288, -1, 9602, 8288, 8267, -1, 8165, 9620, 8140, -1, 11383, 9620, 8165, -1, 11383, 8165, 11384, -1, 8165, 8210, 11384, -1, 11384, 8212, 11385, -1, 11385, 8212, 11386, -1, 8210, 8212, 11384, -1, 11386, 8224, 11387, -1, 8212, 8224, 11386, -1, 11387, 8223, 11388, -1, 8224, 8223, 11387, -1, 11388, 8222, 11389, -1, 8223, 8222, 11388, -1, 11389, 8220, 11390, -1, 8222, 8220, 11389, -1, 11390, 8219, 11391, -1, 8220, 8219, 11390, -1, 11391, 8218, 11392, -1, 8219, 8218, 11391, -1, 11392, 8160, 11393, -1, 8218, 8160, 11392, -1, 11393, 8154, 11394, -1, 8160, 8154, 11393, -1, 11394, 8149, 11395, -1, 8154, 8149, 11394, -1, 11395, 8143, 11396, -1, 8149, 8143, 11395, -1, 8143, 8142, 11396, -1, 9621, 11396, 8142, -1, 9621, 8142, 8121, -1, 11260, 11256, 11044, -1, 11044, 11256, 11040, -1, 11044, 11046, 11260, -1, 11260, 11046, 11263, -1, 11263, 11048, 11264, -1, 11046, 11048, 11263, -1, 11264, 11050, 11266, -1, 11048, 11050, 11264, -1, 11266, 11052, 11268, -1, 11050, 11052, 11266, -1, 11268, 11054, 11270, -1, 11052, 11054, 11268, -1, 11270, 11029, 11246, -1, 11054, 11029, 11270, -1, 11246, 11028, 11245, -1, 11029, 11028, 11246, -1, 11245, 11027, 11244, -1, 11028, 11027, 11245, -1, 11244, 11026, 11243, -1, 11027, 11026, 11244, -1, 11243, 11025, 11242, -1, 11026, 11025, 11243, -1, 11242, 11024, 11241, -1, 11025, 11024, 11242, -1, 11241, 11023, 11240, -1, 11024, 11023, 11241, -1, 11240, 11022, 11239, -1, 11023, 11022, 11240, -1, 11237, 11022, 11011, -1, 11237, 11239, 11022, -1, 11305, 11289, 11096, -1, 11096, 11289, 11081, -1, 11096, 11095, 11305, -1, 11305, 11095, 11312, -1, 11312, 11094, 11311, -1, 11095, 11094, 11312, -1, 11311, 11093, 11310, -1, 11094, 11093, 11311, -1, 11310, 11092, 11309, -1, 11093, 11092, 11310, -1, 11309, 11091, 11308, -1, 11092, 11091, 11309, -1, 11308, 11090, 11307, -1, 11091, 11090, 11308, -1, 11307, 11089, 11306, -1, 11090, 11089, 11307, -1, 11306, 11080, 11304, -1, 11089, 11080, 11306, -1, 11304, 11078, 11303, -1, 11080, 11078, 11304, -1, 11303, 11076, 11301, -1, 11078, 11076, 11303, -1, 11301, 11074, 11299, -1, 11076, 11074, 11301, -1, 11299, 11072, 11297, -1, 11074, 11072, 11299, -1, 11297, 11069, 11286, -1, 11072, 11069, 11297, -1, 11284, 11069, 11067, -1, 11284, 11286, 11069, -1, 11287, 11285, 11070, -1, 11070, 11285, 11068, -1, 11287, 11070, 11288, -1, 11288, 11071, 11296, -1, 11070, 11071, 11288, -1, 11296, 11073, 11298, -1, 11071, 11073, 11296, -1, 11298, 11075, 11300, -1, 11073, 11075, 11298, -1, 11300, 11077, 11302, -1, 11075, 11077, 11300, -1, 11302, 11079, 11314, -1, 11077, 11079, 11302, -1, 11314, 11106, 11313, -1, 11079, 11106, 11314, -1, 11313, 11105, 11271, -1, 11106, 11105, 11313, -1, 11271, 11053, 11269, -1, 11105, 11053, 11271, -1, 11269, 11051, 11267, -1, 11053, 11051, 11269, -1, 11267, 11049, 11265, -1, 11051, 11049, 11267, -1, 11265, 11047, 11262, -1, 11049, 11047, 11265, -1, 11262, 11045, 11261, -1, 11047, 11045, 11262, -1, 11045, 11043, 11261, -1, 11259, 11043, 11042, -1, 11259, 11261, 11043, -1, 8090, 8501, 8049, -1, 8444, 8501, 8090, -1, 8047, 8388, 8089, -1, 8413, 8388, 8047, -1, 8494, 11397, 11398, -1, 8494, 8490, 11397, -1, 8490, 8491, 11397, -1, 11397, 8491, 11399, -1, 11399, 8919, 11400, -1, 8491, 8919, 11399, -1, 11400, 8915, 11401, -1, 8919, 8915, 11400, -1, 11401, 8910, 11402, -1, 8915, 8910, 11401, -1, 11402, 8908, 11403, -1, 8910, 8908, 11402, -1, 11403, 8713, 11404, -1, 8908, 8713, 11403, -1, 11404, 8708, 11405, -1, 8713, 8708, 11404, -1, 11405, 8698, 11406, -1, 8708, 8698, 11405, -1, 11406, 8689, 11407, -1, 8698, 8689, 11406, -1, 11407, 8691, 11408, -1, 8689, 8691, 11407, -1, 11408, 8693, 11409, -1, 8691, 8693, 11408, -1, 11409, 8703, 11410, -1, 8693, 8703, 11409, -1, 11410, 8529, 11411, -1, 8703, 8529, 11410, -1, 11411, 8537, 11412, -1, 8529, 8537, 11411, -1, 8537, 8536, 11412, -1, 11412, 8536, 11413, -1, 11413, 8535, 11414, -1, 8536, 8535, 11413, -1, 11414, 8534, 11415, -1, 8535, 8534, 11414, -1, 11415, 8533, 11416, -1, 8534, 8533, 11415, -1, 11416, 8531, 11417, -1, 8533, 8531, 11416, -1, 11417, 8532, 11418, -1, 8531, 8532, 11417, -1, 11418, 8551, 11419, -1, 8532, 8551, 11418, -1, 11419, 8552, 11420, -1, 8551, 8552, 11419, -1, 11420, 8559, 11421, -1, 8552, 8559, 11420, -1, 11421, 8564, 11422, -1, 8559, 8564, 11421, -1, 11422, 8496, 11423, -1, 8564, 8496, 11422, -1, 11423, 8495, 11424, -1, 8496, 8495, 11423, -1, 11424, 8494, 11398, -1, 8495, 8494, 11424, -1, 8651, 11425, 11426, -1, 8651, 8648, 11425, -1, 8648, 8647, 11425, -1, 11425, 8647, 11427, -1, 11427, 8645, 11428, -1, 8647, 8645, 11427, -1, 11428, 8644, 11429, -1, 8645, 8644, 11428, -1, 11429, 8642, 11430, -1, 8644, 8642, 11429, -1, 11430, 8641, 11431, -1, 8642, 8641, 11430, -1, 11431, 8639, 11432, -1, 8641, 8639, 11431, -1, 11432, 8632, 11433, -1, 8639, 8632, 11432, -1, 11433, 8627, 11434, -1, 8632, 8627, 11433, -1, 11434, 8616, 11435, -1, 8627, 8616, 11434, -1, 11435, 8610, 11436, -1, 8616, 8610, 11435, -1, 11436, 8623, 11437, -1, 8610, 8623, 11436, -1, 11437, 8630, 11438, -1, 8623, 8630, 11437, -1, 11438, 8637, 11439, -1, 8630, 8637, 11438, -1, 11439, 8527, 11440, -1, 8637, 8527, 11439, -1, 8527, 8702, 11440, -1, 11441, 8702, 11442, -1, 11440, 8702, 11441, -1, 11442, 8692, 11443, -1, 8702, 8692, 11442, -1, 11443, 8688, 11444, -1, 8692, 8688, 11443, -1, 11444, 8690, 11445, -1, 8688, 8690, 11444, -1, 11445, 8699, 11446, -1, 8690, 8699, 11445, -1, 11446, 8711, 11447, -1, 8699, 8711, 11446, -1, 11447, 8716, 11448, -1, 8711, 8716, 11447, -1, 11448, 8898, 11449, -1, 8716, 8898, 11448, -1, 11449, 8902, 11450, -1, 8898, 8902, 11449, -1, 11450, 8907, 11451, -1, 8902, 8907, 11450, -1, 11451, 8909, 11452, -1, 8907, 8909, 11451, -1, 11452, 8911, 11426, -1, 8909, 8911, 11452, -1, 8911, 8651, 11426, -1, 8547, 11453, 11454, -1, 8547, 8430, 11453, -1, 8430, 8428, 11453, -1, 11453, 8428, 11455, -1, 11455, 8427, 11456, -1, 8428, 8427, 11455, -1, 11456, 8412, 11457, -1, 8427, 8412, 11456, -1, 11457, 8940, 11458, -1, 8412, 8940, 11457, -1, 11458, 8937, 11459, -1, 8940, 8937, 11458, -1, 11459, 8935, 11460, -1, 8937, 8935, 11459, -1, 11460, 8933, 11461, -1, 8935, 8933, 11460, -1, 11461, 8928, 11462, -1, 8933, 8928, 11461, -1, 11462, 8922, 11463, -1, 8928, 8922, 11462, -1, 11463, 8924, 11464, -1, 8922, 8924, 11463, -1, 11464, 8926, 11465, -1, 8924, 8926, 11464, -1, 11465, 8932, 11466, -1, 8926, 8932, 11465, -1, 11466, 8854, 11467, -1, 8932, 8854, 11466, -1, 11467, 8636, 11468, -1, 8854, 8636, 11467, -1, 8636, 8622, 11468, -1, 11469, 8622, 11470, -1, 11468, 8622, 11469, -1, 11470, 8613, 11471, -1, 8622, 8613, 11470, -1, 11471, 8609, 11472, -1, 8613, 8609, 11471, -1, 11472, 8611, 11473, -1, 8609, 8611, 11472, -1, 11473, 8620, 11474, -1, 8611, 8620, 11473, -1, 11474, 8628, 11475, -1, 8620, 8628, 11474, -1, 11475, 8635, 11476, -1, 8628, 8635, 11475, -1, 11476, 8579, 11477, -1, 8635, 8579, 11476, -1, 11477, 8576, 11478, -1, 8579, 8576, 11477, -1, 11478, 8570, 11479, -1, 8576, 8570, 11478, -1, 11479, 8562, 11480, -1, 8570, 8562, 11479, -1, 11480, 8553, 11454, -1, 8562, 8553, 11480, -1, 8553, 8547, 11454, -1, 8434, 11481, 11482, -1, 8434, 8419, 11481, -1, 8419, 8418, 11481, -1, 11481, 8418, 11483, -1, 11483, 8417, 11484, -1, 8418, 8417, 11483, -1, 11484, 8415, 11485, -1, 8417, 8415, 11484, -1, 11485, 8416, 11486, -1, 8415, 8416, 11485, -1, 11486, 8900, 11487, -1, 8416, 8900, 11486, -1, 11487, 8899, 11488, -1, 8900, 8899, 11487, -1, 11488, 8893, 11489, -1, 8899, 8893, 11488, -1, 11489, 8888, 11490, -1, 8893, 8888, 11489, -1, 11490, 8883, 11491, -1, 8888, 8883, 11490, -1, 11491, 8876, 11492, -1, 8883, 8876, 11491, -1, 11492, 8885, 11493, -1, 8876, 8885, 11492, -1, 11493, 8890, 11494, -1, 8885, 8890, 11493, -1, 11494, 8852, 11495, -1, 8890, 8852, 11494, -1, 11495, 8853, 11496, -1, 8852, 8853, 11495, -1, 8853, 8931, 11496, -1, 11496, 8931, 11497, -1, 11497, 8925, 11498, -1, 8931, 8925, 11497, -1, 11498, 8921, 11499, -1, 8925, 8921, 11498, -1, 11499, 8923, 11500, -1, 8921, 8923, 11499, -1, 11500, 8929, 11501, -1, 8923, 8929, 11500, -1, 11501, 8934, 11502, -1, 8929, 8934, 11501, -1, 11502, 8936, 11503, -1, 8934, 8936, 11502, -1, 11503, 8939, 11504, -1, 8936, 8939, 11503, -1, 11504, 8942, 11505, -1, 8939, 8942, 11504, -1, 11505, 8414, 11506, -1, 8942, 8414, 11505, -1, 11506, 8437, 11507, -1, 8414, 8437, 11506, -1, 11507, 8435, 11508, -1, 8437, 8435, 11507, -1, 11508, 8434, 11482, -1, 8435, 8434, 11508, -1, 8850, 11509, 11510, -1, 8850, 8681, 11509, -1, 8681, 8673, 11509, -1, 11509, 8673, 11511, -1, 11511, 8672, 11512, -1, 8673, 8672, 11511, -1, 11512, 8664, 11513, -1, 8672, 8664, 11512, -1, 11513, 8667, 11514, -1, 8664, 8667, 11513, -1, 11514, 8679, 11515, -1, 8667, 8679, 11514, -1, 11515, 8686, 11516, -1, 8679, 8686, 11515, -1, 11516, 8687, 11517, -1, 8686, 8687, 11516, -1, 11517, 8706, 11518, -1, 8687, 8706, 11517, -1, 11518, 8516, 11519, -1, 8706, 8516, 11518, -1, 11519, 8515, 11520, -1, 8516, 8515, 11519, -1, 11520, 8514, 11521, -1, 8515, 8514, 11520, -1, 11521, 8513, 11522, -1, 8514, 8513, 11521, -1, 11522, 8512, 11523, -1, 8513, 8512, 11522, -1, 11523, 8511, 11524, -1, 8512, 8511, 11523, -1, 8511, 8510, 11524, -1, 11524, 8510, 11525, -1, 11525, 8509, 11526, -1, 8510, 8509, 11525, -1, 11526, 8503, 11527, -1, 8509, 8503, 11526, -1, 11527, 8905, 11528, -1, 8503, 8905, 11527, -1, 11528, 8903, 11529, -1, 8905, 8903, 11528, -1, 11529, 8896, 11530, -1, 8903, 8896, 11529, -1, 11530, 8889, 11531, -1, 8896, 8889, 11530, -1, 11531, 8882, 11532, -1, 8889, 8882, 11531, -1, 11532, 8871, 11533, -1, 8882, 8871, 11532, -1, 11533, 8870, 11534, -1, 8871, 8870, 11533, -1, 11534, 8874, 11535, -1, 8870, 8874, 11534, -1, 11535, 8887, 11536, -1, 8874, 8887, 11535, -1, 11536, 8850, 11510, -1, 8887, 8850, 11536, -1, 11537, 8851, 11538, -1, 8705, 8851, 11537, -1, 8851, 8880, 11538, -1, 11538, 8880, 11539, -1, 11539, 8878, 11540, -1, 8880, 8878, 11539, -1, 11540, 8872, 11541, -1, 8878, 8872, 11540, -1, 11541, 8873, 11542, -1, 8872, 8873, 11541, -1, 11542, 8886, 11543, -1, 8873, 8886, 11542, -1, 11543, 8891, 11544, -1, 8886, 8891, 11543, -1, 11544, 8897, 11545, -1, 8891, 8897, 11544, -1, 11545, 8904, 11546, -1, 8897, 8904, 11545, -1, 11546, 8906, 11547, -1, 8904, 8906, 11546, -1, 11547, 8504, 11548, -1, 8906, 8504, 11547, -1, 11548, 8508, 11549, -1, 8504, 8508, 11548, -1, 11549, 8507, 11550, -1, 8508, 8507, 11549, -1, 11550, 8492, 11551, -1, 8507, 8492, 11550, -1, 11551, 8881, 11552, -1, 8492, 8881, 11551, -1, 8881, 8869, 11552, -1, 11552, 8869, 11553, -1, 11553, 8866, 11554, -1, 8869, 8866, 11553, -1, 11554, 8861, 11555, -1, 8866, 8861, 11554, -1, 11555, 8846, 11556, -1, 8861, 8846, 11555, -1, 11556, 8714, 11557, -1, 8846, 8714, 11556, -1, 11557, 8709, 11558, -1, 8714, 8709, 11557, -1, 11558, 8701, 11559, -1, 8709, 8701, 11558, -1, 11559, 8684, 11560, -1, 8701, 8684, 11559, -1, 11560, 8677, 11561, -1, 8684, 8677, 11560, -1, 11561, 8669, 11562, -1, 8677, 8669, 11561, -1, 11562, 8682, 11563, -1, 8669, 8682, 11562, -1, 11563, 8696, 11564, -1, 8682, 8696, 11563, -1, 11564, 8705, 11537, -1, 8696, 8705, 11564, -1, 8603, 11565, 11566, -1, 8603, 8704, 11565, -1, 8704, 8695, 11565, -1, 11567, 8695, 11568, -1, 11565, 8695, 11567, -1, 11568, 8668, 11569, -1, 8695, 8668, 11568, -1, 11569, 8670, 11570, -1, 8668, 8670, 11569, -1, 11570, 8676, 11571, -1, 8670, 8676, 11570, -1, 11571, 8678, 11572, -1, 8676, 8678, 11571, -1, 11572, 8685, 11573, -1, 8678, 8685, 11572, -1, 11573, 8710, 11574, -1, 8685, 8710, 11573, -1, 11574, 8715, 11575, -1, 8710, 8715, 11574, -1, 11575, 8830, 11576, -1, 8715, 8830, 11575, -1, 11576, 8843, 11577, -1, 8830, 8843, 11576, -1, 11577, 8859, 11578, -1, 8843, 8859, 11577, -1, 11578, 8864, 11579, -1, 8859, 8864, 11578, -1, 8864, 8868, 11579, -1, 8868, 11580, 11579, -1, 8868, 8634, 11580, -1, 8634, 8633, 11580, -1, 11580, 8633, 11581, -1, 11581, 8629, 11582, -1, 8633, 8629, 11581, -1, 11582, 8625, 11583, -1, 8629, 8625, 11582, -1, 11583, 8618, 11584, -1, 8625, 8618, 11583, -1, 11584, 8615, 11585, -1, 8618, 8615, 11584, -1, 11585, 8605, 11586, -1, 8615, 8605, 11585, -1, 11586, 8599, 11587, -1, 8605, 8599, 11586, -1, 11587, 8593, 11588, -1, 8599, 8593, 11587, -1, 11588, 8586, 11589, -1, 8593, 8586, 11588, -1, 11589, 8582, 11590, -1, 8586, 8582, 11589, -1, 11590, 8591, 11591, -1, 8582, 8591, 11590, -1, 11591, 8598, 11592, -1, 8591, 8598, 11591, -1, 11592, 8603, 11566, -1, 8598, 8603, 11592, -1, 11593, 8478, 11594, -1, 8443, 8478, 11593, -1, 11594, 8478, 11595, -1, 11595, 8590, 11596, -1, 8478, 8590, 11595, -1, 11596, 8581, 11597, -1, 8590, 8581, 11596, -1, 11597, 8583, 11598, -1, 8581, 8583, 11597, -1, 11598, 8587, 11599, -1, 8583, 8587, 11598, -1, 11599, 8594, 11600, -1, 8587, 8594, 11599, -1, 11600, 8600, 11601, -1, 8594, 8600, 11600, -1, 11601, 8548, 11602, -1, 8600, 8548, 11601, -1, 11602, 8541, 11603, -1, 8548, 8541, 11602, -1, 11603, 8539, 11604, -1, 8541, 8539, 11603, -1, 11604, 8530, 11605, -1, 8539, 8530, 11604, -1, 11605, 8525, 11606, -1, 8530, 8525, 11605, -1, 11606, 8523, 11607, -1, 8525, 8523, 11606, -1, 8523, 8522, 11607, -1, 11607, 8521, 11608, -1, 8522, 8521, 11607, -1, 8521, 8520, 11608, -1, 11608, 8520, 11609, -1, 11609, 8467, 11610, -1, 8520, 8467, 11609, -1, 11610, 8460, 11611, -1, 8467, 8460, 11610, -1, 11611, 8457, 11612, -1, 8460, 8457, 11611, -1, 11612, 8452, 11613, -1, 8457, 8452, 11612, -1, 11613, 8448, 11614, -1, 8452, 8448, 11613, -1, 11614, 8440, 11615, -1, 8448, 8440, 11614, -1, 11615, 8431, 11616, -1, 8440, 8431, 11615, -1, 11616, 8421, 11617, -1, 8431, 8421, 11616, -1, 11617, 8420, 11618, -1, 8421, 8420, 11617, -1, 11618, 8425, 11619, -1, 8420, 8425, 11618, -1, 11619, 8438, 11620, -1, 8425, 8438, 11619, -1, 11620, 8443, 11593, -1, 8438, 8443, 11620, -1, 8694, 11621, 11622, -1, 8694, 8847, 11621, -1, 8847, 8892, 11621, -1, 11621, 8892, 11623, -1, 11623, 8879, 11624, -1, 8892, 8879, 11623, -1, 11624, 8875, 11625, -1, 8879, 8875, 11624, -1, 11625, 8877, 11626, -1, 8875, 8877, 11625, -1, 11626, 8884, 11627, -1, 8877, 8884, 11626, -1, 11627, 8894, 11628, -1, 8884, 8894, 11627, -1, 11628, 8895, 11629, -1, 8894, 8895, 11628, -1, 11629, 8901, 11630, -1, 8895, 8901, 11629, -1, 11630, 8423, 11631, -1, 8901, 8423, 11630, -1, 11631, 8432, 11632, -1, 8423, 8432, 11631, -1, 11632, 8433, 11633, -1, 8432, 8433, 11632, -1, 11633, 8836, 11634, -1, 8433, 8836, 11633, -1, 11634, 8835, 11635, -1, 8836, 8835, 11634, -1, 11635, 8837, 11636, -1, 8835, 8837, 11635, -1, 8837, 8838, 11636, -1, 11636, 8838, 11637, -1, 11637, 8717, 11638, -1, 8838, 8717, 11637, -1, 11638, 8712, 11639, -1, 8717, 8712, 11638, -1, 11639, 8707, 11640, -1, 8712, 8707, 11639, -1, 11640, 8700, 11641, -1, 8707, 8700, 11640, -1, 11641, 8697, 11642, -1, 8700, 8697, 11641, -1, 11642, 8683, 11643, -1, 8697, 8683, 11642, -1, 11643, 8674, 11644, -1, 8683, 8674, 11643, -1, 11644, 8663, 11645, -1, 8674, 8663, 11644, -1, 11645, 8662, 11646, -1, 8663, 8662, 11645, -1, 11646, 8671, 11647, -1, 8662, 8671, 11646, -1, 11647, 8680, 11648, -1, 8671, 8680, 11647, -1, 11648, 8694, 11622, -1, 8680, 8694, 11648, -1, 11649, 11650, 8246, -1, 8246, 11650, 8208, -1, 8208, 11650, 11651, -1, 11651, 11652, 11653, -1, 11650, 11652, 11651, -1, 11653, 11654, 11655, -1, 11652, 11654, 11653, -1, 11655, 11656, 11657, -1, 11654, 11656, 11655, -1, 11656, 11658, 11657, -1, 11656, 11659, 11658, -1, 11660, 7879, 7878, -1, 11660, 11661, 7879, -1, 11662, 11663, 11664, -1, 11665, 11663, 11662, -1, 11664, 11666, 11667, -1, 11663, 11666, 11664, -1, 11666, 11668, 11667, -1, 11667, 11660, 7878, -1, 11668, 11660, 11667, -1, 11669, 11663, 11665, -1, 11670, 11663, 11669, -1, 7915, 11671, 11672, -1, 7918, 11673, 11674, -1, 7918, 11672, 11673, -1, 7918, 7915, 11672, -1, 7919, 11674, 11675, -1, 7919, 7918, 11674, -1, 7917, 7919, 11675, -1, 7922, 11675, 11676, -1, 7922, 7917, 11675, -1, 7930, 7922, 11676, -1, 11677, 7914, 7910, -1, 11678, 7910, 7908, -1, 11678, 11677, 7910, -1, 11679, 7908, 7902, -1, 11679, 11678, 7908, -1, 11680, 7902, 7904, -1, 11680, 11679, 7902, -1, 11681, 7904, 7903, -1, 11681, 11680, 7904, -1, 11682, 7903, 7907, -1, 11682, 11681, 7903, -1, 11683, 7907, 7909, -1, 11683, 11682, 7907, -1, 11684, 7909, 7913, -1, 11684, 11683, 7909, -1, 11685, 11684, 7913, -1, 7877, 11686, 11687, -1, 7896, 11687, 11688, -1, 7896, 7877, 11687, -1, 7892, 11689, 11690, -1, 7892, 11688, 11689, -1, 7892, 7896, 11688, -1, 7893, 11690, 11691, -1, 7893, 7892, 11690, -1, 7894, 11691, 11692, -1, 7894, 7893, 11691, -1, 7891, 11692, 11693, -1, 7891, 7894, 11692, -1, 7895, 11693, 11694, -1, 7895, 7891, 11693, -1, 7899, 11694, 11695, -1, 7899, 7895, 11694, -1, 7900, 7899, 11695, -1, 7991, 11696, 11697, -1, 8009, 11697, 11698, -1, 8009, 7991, 11697, -1, 8004, 11698, 11699, -1, 8004, 8009, 11698, -1, 8005, 11699, 11700, -1, 8005, 8004, 11699, -1, 8006, 11700, 11701, -1, 8006, 8005, 11700, -1, 8003, 11701, 11702, -1, 8003, 8006, 11701, -1, 8008, 11702, 11703, -1, 8008, 8003, 11702, -1, 8011, 11703, 11704, -1, 8011, 8008, 11703, -1, 8013, 8011, 11704, -1, 8031, 11705, 11706, -1, 8029, 11706, 11707, -1, 8029, 8031, 11706, -1, 8026, 11708, 11709, -1, 8026, 11707, 11708, -1, 8026, 8029, 11707, -1, 8023, 11709, 11710, -1, 8023, 8026, 11709, -1, 8024, 11710, 11711, -1, 8024, 8023, 11710, -1, 8022, 11711, 11712, -1, 8022, 8024, 11711, -1, 8028, 11712, 11713, -1, 8028, 8022, 11712, -1, 8030, 11713, 11714, -1, 8030, 8028, 11713, -1, 8032, 8030, 11714, -1, 8245, 11715, 11716, -1, 8248, 11716, 11717, -1, 8248, 8245, 11716, -1, 8250, 11718, 11719, -1, 8250, 11717, 11718, -1, 8250, 8248, 11717, -1, 8256, 11719, 11720, -1, 8256, 8250, 11719, -1, 8257, 11720, 11721, -1, 8257, 8256, 11720, -1, 8251, 11721, 11722, -1, 8251, 8257, 11721, -1, 8249, 11722, 11723, -1, 8249, 8251, 11722, -1, 8247, 11723, 11724, -1, 8247, 8249, 11723, -1, 8244, 8247, 11724, -1, 11725, 8281, 8278, -1, 11726, 8278, 8273, -1, 11726, 11725, 8278, -1, 11727, 8273, 8271, -1, 11727, 11726, 8273, -1, 11728, 8271, 8270, -1, 11728, 11727, 8271, -1, 11729, 8270, 8269, -1, 11729, 11728, 8270, -1, 11730, 8269, 8272, -1, 11730, 11729, 8269, -1, 11731, 8272, 8277, -1, 11731, 11730, 8272, -1, 11732, 8277, 8280, -1, 11732, 11731, 8277, -1, 11733, 11732, 8280, -1, 11734, 8283, 8293, -1, 11735, 8291, 8290, -1, 11735, 8293, 8291, -1, 11735, 11734, 8293, -1, 11736, 8290, 8289, -1, 11736, 11735, 8290, -1, 11737, 11736, 8289, -1, 11738, 8289, 8302, -1, 11738, 11737, 8289, -1, 11739, 11738, 8302, -1, 7923, 11740, 11741, -1, 7934, 11741, 11742, -1, 7934, 7923, 11741, -1, 7937, 11743, 11744, -1, 7937, 11742, 11743, -1, 7937, 7934, 11742, -1, 7940, 11744, 11745, -1, 7940, 7937, 11744, -1, 7942, 11745, 11746, -1, 7942, 7940, 11745, -1, 7939, 11746, 11747, -1, 7939, 7942, 11746, -1, 7936, 11747, 11748, -1, 7936, 7939, 11747, -1, 7931, 11748, 11749, -1, 7931, 7936, 11748, -1, 7920, 7931, 11749, -1, 7981, 11750, 11751, -1, 7979, 11751, 11752, -1, 7979, 7981, 11751, -1, 7974, 11752, 11753, -1, 7974, 7979, 11752, -1, 7967, 11753, 11754, -1, 7967, 7974, 11753, -1, 7968, 11754, 11755, -1, 7968, 7967, 11754, -1, 7969, 11755, 11756, -1, 7969, 7968, 11755, -1, 7975, 11756, 11757, -1, 7975, 7969, 11756, -1, 7980, 11757, 11758, -1, 7980, 7975, 11757, -1, 7982, 7980, 11758, -1, 7878, 8208, 11667, -1, 11667, 11651, 11664, -1, 8208, 11651, 11667, -1, 11664, 11653, 11662, -1, 11651, 11653, 11664, -1, 11653, 11655, 11662, -1, 11759, 11760, 11761, -1, 11759, 11761, 11762, -1, 11763, 11764, 11765, -1, 11766, 11767, 11768, -1, 11769, 11770, 11764, -1, 11769, 11771, 11770, -1, 11772, 11760, 11759, -1, 11773, 11766, 11768, -1, 11774, 11775, 11776, -1, 11777, 11778, 11779, -1, 11777, 11779, 11780, -1, 11781, 11782, 11783, -1, 11784, 11760, 11772, -1, 11785, 11778, 11777, -1, 11786, 11776, 11775, -1, 11785, 11787, 11778, -1, 11788, 11760, 11784, -1, 11789, 11787, 11785, -1, 11790, 11774, 11776, -1, 11781, 11763, 11782, -1, 11790, 11776, 11791, -1, 11792, 11787, 11789, -1, 11793, 11794, 11771, -1, 11795, 11792, 11789, -1, 11796, 11776, 11786, -1, 11793, 11771, 11769, -1, 11797, 11760, 11788, -1, 11798, 11781, 11783, -1, 11799, 11800, 11795, -1, 11798, 11801, 11802, -1, 11803, 11795, 11800, -1, 11804, 11790, 11791, -1, 11805, 11760, 11797, -1, 11806, 11799, 11795, -1, 11798, 11783, 11801, -1, 11807, 11795, 11803, -1, 11808, 11776, 11796, -1, 11809, 11794, 11793, -1, 11810, 11760, 11805, -1, 11811, 11812, 11813, -1, 11809, 11814, 11815, -1, 11809, 11815, 11794, -1, 11811, 11813, 11816, -1, 11817, 11798, 11802, -1, 11817, 11802, 11818, -1, 11819, 11795, 11807, -1, 11820, 11804, 11791, -1, 11821, 11812, 11811, -1, 11822, 11792, 11795, -1, 11822, 11795, 11819, -1, 11823, 11817, 11818, -1, 11823, 11818, 11824, -1, 11825, 11776, 11808, -1, 11826, 11792, 11822, -1, 11825, 11827, 11776, -1, 11828, 11824, 11829, -1, 11830, 11792, 11826, -1, 11831, 11832, 11812, -1, 11831, 11812, 11821, -1, 11833, 11820, 11791, -1, 11834, 11792, 11830, -1, 11828, 11823, 11824, -1, 11657, 11835, 11773, -1, 11836, 11828, 11829, -1, 11657, 11837, 11838, -1, 11657, 11773, 11768, -1, 11839, 11827, 11825, -1, 11840, 11792, 11834, -1, 11657, 11838, 11841, -1, 11657, 11841, 11842, -1, 11657, 11842, 11843, -1, 11657, 11843, 11844, -1, 11657, 11844, 11835, -1, 11655, 11657, 11768, -1, 11845, 11832, 11831, -1, 11658, 11810, 11846, -1, 11658, 11846, 11847, -1, 11658, 11847, 11848, -1, 11849, 11833, 11791, -1, 11658, 11848, 11850, -1, 11658, 11850, 11851, -1, 11658, 11851, 11852, -1, 11658, 11852, 11837, -1, 11658, 11760, 11810, -1, 11658, 11837, 11657, -1, 11662, 11655, 11768, -1, 11662, 11768, 11853, -1, 11669, 11854, 11855, -1, 11669, 11855, 11856, -1, 11669, 11856, 11857, -1, 11858, 11859, 11832, -1, 11669, 11857, 11860, -1, 11669, 11860, 11861, -1, 11858, 11832, 11845, -1, 11669, 11861, 11862, -1, 11669, 11862, 11806, -1, 11669, 11806, 11795, -1, 11863, 11827, 11839, -1, 11864, 11814, 11809, -1, 11864, 11865, 11866, -1, 11864, 11866, 11867, -1, 11868, 11869, 11859, -1, 11864, 11867, 11870, -1, 11864, 11870, 11871, -1, 11864, 11871, 11814, -1, 11864, 11872, 11865, -1, 11868, 11859, 11858, -1, 11873, 11849, 11791, -1, 11874, 11864, 11809, -1, 11665, 11854, 11669, -1, 11874, 11875, 11864, -1, 11665, 11876, 11854, -1, 11665, 11877, 11878, -1, 11879, 11869, 11868, -1, 11665, 11878, 11880, -1, 11665, 11880, 11881, -1, 11879, 11882, 11869, -1, 11665, 11881, 11883, -1, 11884, 11875, 11874, -1, 11665, 11883, 11885, -1, 11665, 11885, 11876, -1, 11884, 11886, 11887, -1, 11884, 11887, 11875, -1, 11888, 11886, 11884, -1, 11889, 11827, 11863, -1, 11888, 11890, 11886, -1, 11889, 11863, 11891, -1, 11892, 11890, 11888, -1, 11892, 11893, 11894, -1, 11892, 11894, 11890, -1, 11895, 11873, 11791, -1, 11896, 11897, 11898, -1, 11899, 11898, 11897, -1, 11900, 11896, 11898, -1, 11901, 11902, 11898, -1, 11901, 11898, 11899, -1, 11903, 11900, 11898, -1, 11904, 11902, 11901, -1, 11905, 11889, 11891, -1, 11906, 11907, 11908, -1, 11909, 11895, 11791, -1, 11909, 11791, 11910, -1, 11911, 11912, 11889, -1, 11913, 11906, 11908, -1, 11911, 11889, 11905, -1, 11914, 11902, 11904, -1, 11913, 11908, 11915, -1, 11916, 11909, 11910, -1, 11916, 11910, 11917, -1, 11918, 11915, 11919, -1, 11918, 11919, 11920, -1, 11918, 11913, 11915, -1, 11921, 11902, 11914, -1, 11922, 11923, 11912, -1, 11922, 11912, 11911, -1, 11924, 11917, 11925, -1, 11924, 11916, 11917, -1, 11926, 11927, 11923, -1, 11926, 11923, 11922, -1, 11928, 11902, 11921, -1, 11929, 11924, 11925, -1, 11930, 11931, 11920, -1, 11930, 11920, 11932, -1, 11933, 11927, 11926, -1, 11934, 11902, 11928, -1, 11935, 11920, 11931, -1, 11935, 11918, 11920, -1, 11936, 11930, 11932, -1, 11937, 11902, 11934, -1, 11936, 11932, 11938, -1, 11939, 11940, 11941, -1, 11939, 11941, 11942, -1, 11939, 11942, 11943, -1, 11939, 11943, 11944, -1, 11939, 11944, 11903, -1, 11939, 11903, 11898, -1, 11945, 11946, 11947, -1, 11948, 11918, 11935, -1, 11949, 11836, 11829, -1, 11949, 11938, 11836, -1, 11950, 11902, 11937, -1, 11951, 11947, 11946, -1, 11949, 11936, 11938, -1, 11952, 11947, 11902, -1, 11953, 11918, 11948, -1, 11952, 11902, 11950, -1, 11954, 11829, 11955, -1, 11952, 11945, 11947, -1, 11954, 11949, 11829, -1, 11956, 11947, 11951, -1, 11957, 11950, 11958, -1, 11959, 11955, 11960, -1, 11959, 11960, 11961, -1, 11959, 11954, 11955, -1, 11957, 11952, 11950, -1, 11962, 11961, 11963, -1, 11962, 11959, 11961, -1, 11964, 11947, 11956, -1, 11965, 11958, 11966, -1, 11965, 11966, 11967, -1, 11968, 11962, 11963, -1, 11965, 11957, 11958, -1, 11969, 11947, 11964, -1, 11970, 11967, 11971, -1, 11970, 11965, 11967, -1, 11972, 11973, 11974, -1, 11975, 11918, 11953, -1, 11976, 11970, 11971, -1, 11977, 11978, 11975, -1, 11976, 11971, 11979, -1, 11977, 11975, 11953, -1, 11980, 11981, 11973, -1, 11980, 11973, 11972, -1, 11982, 11978, 11977, -1, 11982, 11983, 11984, -1, 11985, 11986, 11981, -1, 11982, 11984, 11978, -1, 11985, 11981, 11980, -1, 11987, 11983, 11982, -1, 11987, 11988, 11983, -1, 11989, 11976, 11979, -1, 11989, 11979, 11990, -1, 11991, 11988, 11987, -1, 11991, 11992, 11993, -1, 11991, 11993, 11988, -1, 11994, 11990, 11882, -1, 11994, 11989, 11990, -1, 11994, 11879, 11995, -1, 11996, 11986, 11985, -1, 11994, 11882, 11879, -1, 11997, 11998, 11999, -1, 12000, 11994, 11995, -1, 12000, 11995, 12001, -1, 12002, 12003, 12004, -1, 12005, 11997, 11999, -1, 12005, 11999, 12006, -1, 12007, 12000, 12001, -1, 12008, 12004, 12009, -1, 12008, 12002, 12004, -1, 12010, 12007, 12001, -1, 12011, 11939, 11986, -1, 12012, 12009, 12013, -1, 12010, 12001, 12014, -1, 12012, 12008, 12009, -1, 12011, 11986, 11996, -1, 12015, 12013, 12016, -1, 12017, 12010, 12014, -1, 12018, 12005, 12006, -1, 12017, 12014, 11927, -1, 12018, 12006, 11812, -1, 12017, 11927, 11933, -1, 12019, 11939, 12011, -1, 12020, 12015, 12016, -1, 12021, 11933, 12022, -1, 12023, 11940, 11939, -1, 12024, 12013, 12015, -1, 12021, 12017, 11933, -1, 12023, 11939, 12019, -1, 12023, 12025, 12026, -1, 12023, 12026, 11940, -1, 12027, 12020, 12016, -1, 12028, 12025, 12023, -1, 12028, 12029, 12025, -1, 12030, 12012, 12013, -1, 12030, 12013, 12024, -1, 12031, 12032, 12029, -1, 12033, 12016, 12034, -1, 12031, 12029, 12028, -1, 12033, 12027, 12016, -1, 12035, 12036, 12032, -1, 12035, 12032, 12031, -1, 12037, 12012, 12030, -1, 12038, 11969, 12039, -1, 12040, 12041, 12036, -1, 12042, 12034, 12043, -1, 12038, 12039, 12044, -1, 12038, 12044, 12045, -1, 12040, 12036, 12035, -1, 12038, 12045, 12046, -1, 12042, 12033, 12034, -1, 12038, 12046, 12047, -1, 12038, 12047, 12048, -1, 12049, 11966, 12041, -1, 12049, 12041, 12040, -1, 12050, 12012, 12037, -1, 12038, 11947, 11969, -1, 12051, 12043, 11968, -1, 12052, 12038, 12048, -1, 11967, 11966, 12049, -1, 12051, 12042, 12043, -1, 11832, 12018, 11812, -1, 12053, 12012, 12050, -1, 12054, 12051, 11968, -1, 12054, 11963, 12021, -1, 12055, 12056, 12052, -1, 12054, 11968, 11963, -1, 12057, 12012, 12053, -1, 12058, 12021, 12022, -1, 12059, 12052, 12056, -1, 12060, 12055, 12052, -1, 12058, 12054, 12021, -1, 12061, 12012, 12057, -1, 12062, 12022, 11929, -1, 12062, 12058, 12022, -1, 12062, 11929, 11925, -1, 12063, 12012, 12061, -1, 12064, 12052, 12059, -1, 12065, 12048, 12066, -1, 12065, 12052, 12048, -1, 12065, 12060, 12052, -1, 12067, 12052, 12064, -1, 12068, 12066, 11801, -1, 12068, 12065, 12066, -1, 12069, 11872, 12052, -1, 12069, 12052, 12067, -1, 12070, 12071, 12072, -1, 11783, 12068, 11801, -1, 12073, 11872, 12069, -1, 12074, 12012, 12063, -1, 12075, 12076, 12071, -1, 12075, 12071, 12070, -1, 12074, 12063, 12077, -1, 12074, 12077, 12078, -1, 12074, 12078, 12079, -1, 12074, 12079, 12080, -1, 12074, 12080, 12081, -1, 12074, 12081, 12082, -1, 12074, 12082, 12083, -1, 12084, 12085, 12076, -1, 12084, 12076, 12075, -1, 12086, 11872, 12073, -1, 12087, 12074, 12083, -1, 12087, 12083, 12088, -1, 12089, 12088, 12090, -1, 12089, 12087, 12088, -1, 12091, 11872, 12086, -1, 12092, 12062, 11925, -1, 12092, 12090, 12062, -1, 12093, 12085, 12084, -1, 12092, 12089, 12090, -1, 12094, 11872, 12091, -1, 12095, 11925, 12096, -1, 12097, 12098, 12099, -1, 12095, 12092, 11925, -1, 11768, 12096, 11853, -1, 11768, 12095, 12096, -1, 11865, 11872, 12094, -1, 12100, 12099, 12101, -1, 12100, 12097, 12099, -1, 12102, 12085, 12093, -1, 12102, 11813, 12085, -1, 12103, 12104, 12105, -1, 12106, 12103, 12105, -1, 12106, 12105, 12107, -1, 11827, 12101, 11776, -1, 11827, 12100, 12101, -1, 12108, 12107, 12109, -1, 11764, 11770, 11765, -1, 12108, 12106, 12107, -1, 11816, 11813, 12102, -1, 11760, 12108, 12109, -1, 11853, 11792, 11840, -1, 11760, 12109, 11761, -1, 11853, 11877, 11665, -1, 11853, 11665, 11662, -1, 11853, 11840, 12110, -1, 12111, 12112, 11761, -1, 11853, 12110, 11877, -1, 11762, 11761, 12112, -1, 11763, 11765, 11782, -1, 11767, 12111, 11761, -1, 11767, 11761, 11768, -1, 12113, 11808, 12114, -1, 12114, 11796, 12115, -1, 11808, 11796, 12114, -1, 12115, 11786, 12116, -1, 11796, 11786, 12115, -1, 12116, 11775, 12117, -1, 11786, 11775, 12116, -1, 12117, 11774, 12118, -1, 11775, 11774, 12117, -1, 12118, 11790, 12119, -1, 11774, 11790, 12118, -1, 12119, 11804, 12120, -1, 11790, 11804, 12119, -1, 12120, 11820, 12121, -1, 11804, 11820, 12120, -1, 12121, 11833, 12122, -1, 11820, 11833, 12121, -1, 12122, 11849, 12123, -1, 11833, 11849, 12122, -1, 12123, 11873, 12124, -1, 11849, 11873, 12123, -1, 12124, 11895, 12125, -1, 11873, 11895, 12124, -1, 11895, 11909, 12125, -1, 12125, 11916, 12126, -1, 11909, 11916, 12125, -1, 12067, 12064, 12127, -1, 12128, 12064, 12129, -1, 12127, 12064, 12128, -1, 12129, 12059, 12130, -1, 12064, 12059, 12129, -1, 12130, 12056, 12131, -1, 12059, 12056, 12130, -1, 12131, 12055, 12132, -1, 12056, 12055, 12131, -1, 12132, 12060, 12133, -1, 12055, 12060, 12132, -1, 12133, 12065, 12134, -1, 12060, 12065, 12133, -1, 12134, 12068, 12135, -1, 12065, 12068, 12134, -1, 12135, 11783, 12136, -1, 12068, 11783, 12135, -1, 12136, 11782, 12137, -1, 11783, 11782, 12136, -1, 12137, 11765, 12138, -1, 11782, 11765, 12137, -1, 12138, 11770, 12139, -1, 11765, 11770, 12138, -1, 11770, 11771, 12139, -1, 12139, 11794, 12140, -1, 11771, 11794, 12139, -1, 12141, 12037, 12142, -1, 12142, 12030, 12143, -1, 12037, 12030, 12142, -1, 12143, 12024, 12144, -1, 12030, 12024, 12143, -1, 12144, 12015, 12145, -1, 12024, 12015, 12144, -1, 12145, 12020, 12146, -1, 12015, 12020, 12145, -1, 12146, 12027, 12147, -1, 12020, 12027, 12146, -1, 12147, 12033, 12148, -1, 12027, 12033, 12147, -1, 12148, 12042, 12149, -1, 12033, 12042, 12148, -1, 12149, 12051, 12150, -1, 12042, 12051, 12149, -1, 12150, 12054, 12151, -1, 12051, 12054, 12150, -1, 12151, 12058, 12152, -1, 12054, 12058, 12151, -1, 12152, 12062, 12153, -1, 12058, 12062, 12152, -1, 12062, 12090, 12153, -1, 12153, 12088, 12154, -1, 12090, 12088, 12153, -1, 11904, 11901, 12155, -1, 12156, 11901, 12157, -1, 12155, 11901, 12156, -1, 12157, 11899, 12158, -1, 11901, 11899, 12157, -1, 12158, 11897, 12159, -1, 11899, 11897, 12158, -1, 12159, 11896, 12160, -1, 11897, 11896, 12159, -1, 12160, 11900, 12161, -1, 11896, 11900, 12160, -1, 12161, 11903, 12162, -1, 11900, 11903, 12161, -1, 12162, 11944, 12163, -1, 11903, 11944, 12162, -1, 12163, 11943, 12164, -1, 11944, 11943, 12163, -1, 12164, 11942, 12165, -1, 11943, 11942, 12164, -1, 12165, 11941, 12166, -1, 11942, 11941, 12165, -1, 12166, 11940, 12167, -1, 11941, 11940, 12166, -1, 11940, 12026, 12167, -1, 12167, 12025, 12168, -1, 12026, 12025, 12167, -1, 12169, 11969, 12170, -1, 11969, 11964, 12170, -1, 12170, 11956, 12171, -1, 11964, 11956, 12170, -1, 12171, 11951, 12172, -1, 11956, 11951, 12171, -1, 12172, 11946, 12173, -1, 11951, 11946, 12172, -1, 12173, 11945, 12174, -1, 11946, 11945, 12173, -1, 12174, 11952, 12175, -1, 11945, 11952, 12174, -1, 12175, 11957, 12176, -1, 11952, 11957, 12175, -1, 12176, 11965, 12177, -1, 11957, 11965, 12176, -1, 12177, 11970, 12178, -1, 11965, 11970, 12177, -1, 12178, 11976, 12179, -1, 11970, 11976, 12178, -1, 12179, 11989, 12180, -1, 11976, 11989, 12179, -1, 12180, 11994, 12181, -1, 11989, 11994, 12180, -1, 12181, 12000, 12182, -1, 11994, 12000, 12181, -1, 12182, 12007, 12183, -1, 12000, 12007, 12182, -1, 12183, 12010, 12184, -1, 12007, 12010, 12183, -1, 12010, 12017, 12184, -1, 12184, 12017, 12185, -1, 12017, 12021, 12185, -1, 12185, 12021, 12186, -1, 11772, 11759, 12187, -1, 12187, 11759, 12188, -1, 12188, 11759, 12189, -1, 12189, 11762, 12190, -1, 11759, 11762, 12189, -1, 12190, 12112, 12191, -1, 11762, 12112, 12190, -1, 12191, 12111, 12192, -1, 12112, 12111, 12191, -1, 12192, 11767, 12193, -1, 12111, 11767, 12192, -1, 12193, 11766, 12194, -1, 11767, 11766, 12193, -1, 12194, 11773, 12195, -1, 11766, 11773, 12194, -1, 12195, 11835, 12196, -1, 11773, 11835, 12195, -1, 12196, 11844, 12197, -1, 11835, 11844, 12196, -1, 12197, 11843, 12198, -1, 11844, 11843, 12197, -1, 12198, 11842, 12199, -1, 11843, 11842, 12198, -1, 11842, 11841, 12199, -1, 12199, 11838, 12200, -1, 11841, 11838, 12199, -1, 11819, 11807, 12201, -1, 12201, 11807, 12202, -1, 12202, 11807, 12203, -1, 12203, 11803, 12204, -1, 11807, 11803, 12203, -1, 12204, 11800, 12205, -1, 11803, 11800, 12204, -1, 12205, 11799, 12206, -1, 11800, 11799, 12205, -1, 12206, 11806, 12207, -1, 11799, 11806, 12206, -1, 12207, 11862, 12208, -1, 11806, 11862, 12207, -1, 12208, 11861, 12209, -1, 11862, 11861, 12208, -1, 12209, 11860, 12210, -1, 11861, 11860, 12209, -1, 12210, 11857, 12211, -1, 11860, 11857, 12210, -1, 12211, 11856, 12212, -1, 11857, 11856, 12211, -1, 12212, 11855, 12213, -1, 11856, 11855, 12212, -1, 11855, 11854, 12213, -1, 12213, 11876, 12214, -1, 11854, 11876, 12213, -1, 12215, 12216, 12217, -1, 12218, 12216, 12215, -1, 12219, 12220, 12221, -1, 12222, 12223, 12224, -1, 12225, 12226, 12227, -1, 12224, 12223, 12228, -1, 12227, 12226, 12229, -1, 12223, 12230, 12228, -1, 12231, 12232, 12233, -1, 12234, 12235, 12236, -1, 12158, 12159, 12237, -1, 12237, 12157, 12158, -1, 12159, 12160, 12237, -1, 12216, 12238, 12217, -1, 12237, 12156, 12157, -1, 12239, 12240, 12241, -1, 12242, 12156, 12237, -1, 12243, 12244, 12245, -1, 12160, 12161, 12237, -1, 12239, 12246, 12240, -1, 12226, 12247, 12229, -1, 12248, 12246, 12239, -1, 12242, 12155, 12156, -1, 12249, 12250, 12251, -1, 12252, 12250, 12249, -1, 12240, 12253, 12241, -1, 12242, 12254, 12155, -1, 12252, 12255, 12250, -1, 12256, 12257, 12258, -1, 12242, 12259, 12254, -1, 12253, 12260, 12241, -1, 12255, 12261, 12250, -1, 12217, 12262, 12263, -1, 12242, 12264, 12259, -1, 12238, 12262, 12217, -1, 12153, 12265, 12152, -1, 12231, 12265, 12232, -1, 12152, 12265, 12231, -1, 12266, 12267, 12268, -1, 12250, 12265, 12269, -1, 12241, 12267, 12266, -1, 12242, 12270, 12264, -1, 12261, 12265, 12250, -1, 12260, 12267, 12241, -1, 12271, 12272, 12273, -1, 12274, 12275, 12276, -1, 12277, 12272, 12271, -1, 12276, 12275, 12278, -1, 12278, 12275, 12279, -1, 12279, 12275, 12280, -1, 12242, 12281, 12270, -1, 12280, 12275, 12282, -1, 12282, 12275, 12283, -1, 12283, 12275, 12284, -1, 12284, 12275, 12285, -1, 12273, 12286, 12287, -1, 12272, 12286, 12273, -1, 12246, 12288, 12289, -1, 12161, 12290, 12237, -1, 12257, 12291, 12258, -1, 12166, 12290, 12165, -1, 12165, 12290, 12164, -1, 12164, 12290, 12163, -1, 12163, 12290, 12162, -1, 12292, 12293, 12248, -1, 12162, 12290, 12161, -1, 12294, 12293, 12295, -1, 12242, 12296, 12281, -1, 12275, 12297, 12285, -1, 12248, 12293, 12246, -1, 12285, 12297, 12154, -1, 12295, 12293, 12292, -1, 12286, 12298, 12287, -1, 12299, 12300, 12301, -1, 12302, 12300, 12299, -1, 12267, 12303, 12268, -1, 12154, 12304, 12153, -1, 12268, 12303, 12305, -1, 12153, 12304, 12265, -1, 12297, 12304, 12154, -1, 12306, 12307, 12308, -1, 12309, 12307, 12306, -1, 12298, 12310, 12287, -1, 12294, 12311, 12293, -1, 12312, 12311, 12294, -1, 12258, 12313, 12314, -1, 12291, 12313, 12258, -1, 12230, 12315, 12316, -1, 12287, 12315, 12223, -1, 12223, 12315, 12230, -1, 12310, 12315, 12287, -1, 12246, 12317, 12288, -1, 12304, 12318, 12265, -1, 12319, 12320, 12321, -1, 12309, 12322, 12307, -1, 12269, 12322, 12309, -1, 12321, 12320, 12234, -1, 12323, 12324, 12325, -1, 12326, 12327, 12312, -1, 12328, 12324, 12329, -1, 12329, 12324, 12330, -1, 12330, 12324, 12331, -1, 12331, 12324, 12332, -1, 12312, 12327, 12311, -1, 12332, 12324, 12333, -1, 12333, 12324, 12323, -1, 12318, 12334, 12265, -1, 12324, 12335, 12325, -1, 12334, 12336, 12265, -1, 12314, 12337, 12338, -1, 12313, 12337, 12314, -1, 12265, 12339, 12269, -1, 12269, 12339, 12322, -1, 12315, 12340, 12316, -1, 12338, 12341, 12342, -1, 12337, 12341, 12338, -1, 12303, 12343, 12305, -1, 12305, 12343, 12344, -1, 12326, 12345, 12327, -1, 12339, 12346, 12347, -1, 12348, 12349, 12324, -1, 12350, 12351, 12352, -1, 12324, 12349, 12335, -1, 12265, 12346, 12339, -1, 12353, 12351, 12350, -1, 12336, 12346, 12265, -1, 12348, 12354, 12349, -1, 12336, 12355, 12346, -1, 12356, 12357, 12353, -1, 12358, 12359, 12293, -1, 12360, 12355, 12336, -1, 12361, 12316, 12362, -1, 12293, 12359, 12246, -1, 12348, 12363, 12354, -1, 12243, 12364, 12365, -1, 12246, 12359, 12317, -1, 12243, 12365, 12366, -1, 12353, 12357, 12351, -1, 12367, 12363, 12348, -1, 12243, 12366, 12244, -1, 12368, 12369, 12370, -1, 12371, 12372, 12373, -1, 12371, 12373, 12374, -1, 12234, 12375, 12235, -1, 12376, 12377, 12378, -1, 12376, 12378, 12379, -1, 12376, 12379, 12380, -1, 12320, 12375, 12234, -1, 12376, 12380, 12381, -1, 12376, 12381, 12382, -1, 12344, 12383, 12384, -1, 12385, 12386, 12387, -1, 12387, 12386, 12388, -1, 12343, 12383, 12344, -1, 12389, 12390, 12391, -1, 12392, 12393, 12394, -1, 12394, 12393, 12395, -1, 12367, 12396, 12363, -1, 12395, 12393, 12397, -1, 12398, 12399, 12400, -1, 12401, 12402, 12403, -1, 12404, 12396, 12367, -1, 12405, 12406, 12407, -1, 12405, 12407, 12408, -1, 12409, 12410, 12411, -1, 12405, 12408, 12412, -1, 12413, 12414, 12415, -1, 12416, 12417, 12418, -1, 12419, 12420, 12421, -1, 12421, 12420, 12422, -1, 12422, 12420, 12423, -1, 12424, 12425, 12426, -1, 12355, 12427, 12341, -1, 12355, 12341, 12346, -1, 12341, 12427, 12342, -1, 12404, 12428, 12396, -1, 12342, 12427, 12429, -1, 12429, 12427, 12430, -1, 12431, 12428, 12404, -1, 12430, 12427, 12432, -1, 12432, 12427, 12433, -1, 12356, 12434, 12357, -1, 12433, 12427, 12435, -1, 12435, 12427, 12436, -1, 12436, 12427, 12437, -1, 12437, 12427, 12263, -1, 12263, 12427, 12438, -1, 12439, 12434, 12356, -1, 12358, 12440, 12359, -1, 12441, 12442, 12443, -1, 12444, 12434, 12439, -1, 12443, 12442, 12445, -1, 12445, 12442, 12446, -1, 12340, 12362, 12316, -1, 12447, 12448, 12449, -1, 12449, 12448, 12450, -1, 12451, 12452, 12453, -1, 12454, 12455, 12456, -1, 12456, 12455, 12457, -1, 12456, 12457, 12458, -1, 12459, 12460, 12461, -1, 12462, 12463, 12464, -1, 12459, 12461, 12465, -1, 12466, 12463, 12462, -1, 12345, 12467, 12327, -1, 12468, 12407, 12406, -1, 12443, 12469, 12441, -1, 12470, 12453, 12471, -1, 12300, 12433, 12301, -1, 12262, 12472, 12263, -1, 12301, 12433, 12435, -1, 12473, 12472, 12262, -1, 12474, 12472, 12473, -1, 12384, 12472, 12474, -1, 12383, 12472, 12384, -1, 12463, 12475, 12464, -1, 12464, 12475, 12476, -1, 12345, 12477, 12467, -1, 12475, 12478, 12476, -1, 12410, 12370, 12479, -1, 12409, 12370, 12410, -1, 12444, 12480, 12434, -1, 12375, 12368, 12370, -1, 12320, 12368, 12375, -1, 12290, 12480, 12444, -1, 12290, 12481, 12480, -1, 12166, 12481, 12290, -1, 12168, 12481, 12167, -1, 12167, 12481, 12166, -1, 12168, 12482, 12481, -1, 12467, 12483, 12484, -1, 12485, 12482, 12168, -1, 12477, 12483, 12467, -1, 12219, 12486, 12220, -1, 12487, 12486, 12488, -1, 12489, 12486, 12487, -1, 12490, 12486, 12489, -1, 12491, 12486, 12490, -1, 12492, 12486, 12491, -1, 12493, 12494, 12485, -1, 12220, 12486, 12492, -1, 12485, 12494, 12482, -1, 12472, 12437, 12263, -1, 12495, 12486, 12219, -1, 12496, 12497, 12493, -1, 12493, 12497, 12494, -1, 12483, 12498, 12484, -1, 12499, 12500, 12496, -1, 12496, 12500, 12497, -1, 12501, 12502, 12440, -1, 12503, 12504, 12499, -1, 12505, 12502, 12501, -1, 12499, 12504, 12500, -1, 12440, 12502, 12359, -1, 12503, 12506, 12504, -1, 12507, 12508, 12509, -1, 12478, 12510, 12476, -1, 12511, 12508, 12507, -1, 12508, 12512, 12509, -1, 12509, 12512, 12513, -1, 12484, 12514, 12515, -1, 12498, 12514, 12484, -1, 12512, 12516, 12513, -1, 12513, 12516, 12517, -1, 12486, 12518, 12488, -1, 12502, 12519, 12359, -1, 12488, 12518, 12520, -1, 12495, 12521, 12486, -1, 12522, 12519, 12523, -1, 12359, 12519, 12522, -1, 12524, 12525, 12526, -1, 12518, 12527, 12520, -1, 12524, 12528, 12525, -1, 12529, 12528, 12524, -1, 12370, 12369, 12479, -1, 12479, 12369, 12432, -1, 12525, 12530, 12526, -1, 12495, 12531, 12521, -1, 12521, 12531, 12532, -1, 12529, 12533, 12528, -1, 12534, 12533, 12529, -1, 12535, 12531, 12495, -1, 12527, 12536, 12520, -1, 12536, 12469, 12520, -1, 12520, 12469, 12537, -1, 12530, 12538, 12526, -1, 12539, 12540, 12534, -1, 12537, 12541, 12362, -1, 12534, 12540, 12533, -1, 12469, 12541, 12537, -1, 12541, 12542, 12362, -1, 12543, 12544, 12545, -1, 12546, 12544, 12543, -1, 12515, 12547, 12548, -1, 12542, 12549, 12362, -1, 12514, 12547, 12515, -1, 12546, 12550, 12544, -1, 12539, 12551, 12540, -1, 12552, 12550, 12546, -1, 12553, 12551, 12539, -1, 12554, 12551, 12553, -1, 12549, 12361, 12362, -1, 12535, 12555, 12531, -1, 12548, 12377, 12505, -1, 12505, 12377, 12502, -1, 12531, 12556, 12532, -1, 12536, 12441, 12469, -1, 12557, 12558, 12552, -1, 12559, 12558, 12557, -1, 12519, 12560, 12523, -1, 12552, 12558, 12550, -1, 12561, 12562, 12563, -1, 12564, 12562, 12561, -1, 12554, 12565, 12551, -1, 12181, 12565, 12554, -1, 12563, 12566, 12567, -1, 12555, 12401, 12403, -1, 12535, 12401, 12555, -1, 12562, 12566, 12563, -1, 12548, 12568, 12377, -1, 12569, 12570, 12549, -1, 12566, 12571, 12567, -1, 12572, 12573, 12559, -1, 12547, 12568, 12548, -1, 12549, 12570, 12361, -1, 12559, 12573, 12558, -1, 12574, 12575, 12427, -1, 12535, 12576, 12401, -1, 12577, 12576, 12535, -1, 12569, 12578, 12570, -1, 12519, 12385, 12560, -1, 12369, 12579, 12432, -1, 12181, 12580, 12565, -1, 12116, 12117, 12567, -1, 12183, 12580, 12182, -1, 12182, 12580, 12181, -1, 12570, 12581, 12361, -1, 12567, 12115, 12116, -1, 12560, 12582, 12523, -1, 12117, 12118, 12567, -1, 12583, 12402, 12584, -1, 12403, 12402, 12583, -1, 12567, 12118, 12585, -1, 12567, 12114, 12115, -1, 12118, 12119, 12585, -1, 12578, 12448, 12570, -1, 12568, 12378, 12377, -1, 12567, 12113, 12114, -1, 12586, 12448, 12578, -1, 12476, 12587, 12572, -1, 12586, 12588, 12448, -1, 12589, 12590, 12591, -1, 12592, 12590, 12589, -1, 12572, 12587, 12573, -1, 12593, 12590, 12592, -1, 12442, 12594, 12446, -1, 12119, 12120, 12585, -1, 12577, 12595, 12576, -1, 12596, 12595, 12577, -1, 12580, 12597, 12598, -1, 12581, 12390, 12361, -1, 12476, 12599, 12587, -1, 12567, 12600, 12113, -1, 12571, 12600, 12567, -1, 12581, 12391, 12390, -1, 12510, 12601, 12476, -1, 12588, 12602, 12448, -1, 12582, 12603, 12523, -1, 12476, 12601, 12599, -1, 12602, 12450, 12448, -1, 12120, 12121, 12585, -1, 12604, 12603, 12605, -1, 12606, 12603, 12604, -1, 12607, 12603, 12606, -1, 12523, 12603, 12607, -1, 12402, 12405, 12584, -1, 12584, 12405, 12442, -1, 12608, 12609, 12593, -1, 12571, 12610, 12600, -1, 12611, 12609, 12608, -1, 12612, 12609, 12611, -1, 12405, 12613, 12442, -1, 12593, 12609, 12590, -1, 12442, 12613, 12594, -1, 12510, 12614, 12601, -1, 12385, 12387, 12560, -1, 12615, 12616, 12596, -1, 12121, 12122, 12585, -1, 12596, 12616, 12595, -1, 12576, 12617, 12618, -1, 12595, 12617, 12576, -1, 12580, 12619, 12597, -1, 12510, 12620, 12614, -1, 12621, 12620, 12510, -1, 12361, 12622, 12579, -1, 12390, 12622, 12361, -1, 12571, 12623, 12610, -1, 12624, 12625, 12626, -1, 12621, 12627, 12620, -1, 12628, 12625, 12624, -1, 12591, 12625, 12628, -1, 12590, 12625, 12591, -1, 12629, 12627, 12621, -1, 12405, 12630, 12613, -1, 12122, 12123, 12585, -1, 12629, 12631, 12627, -1, 12632, 12631, 12629, -1, 12630, 12633, 12634, -1, 12603, 12436, 12605, -1, 12635, 12436, 12437, -1, 12605, 12436, 12635, -1, 12405, 12633, 12630, -1, 12571, 12636, 12623, -1, 12623, 12636, 12637, -1, 12405, 12638, 12633, -1, 12612, 12639, 12609, -1, 12640, 12639, 12612, -1, 12641, 12642, 12381, -1, 12626, 12642, 12641, -1, 12123, 12124, 12585, -1, 12625, 12642, 12626, -1, 12405, 12643, 12638, -1, 12579, 12430, 12432, -1, 12582, 12644, 12603, -1, 12645, 12644, 12582, -1, 12622, 12430, 12579, -1, 12646, 12647, 12391, -1, 12169, 12648, 12649, -1, 12649, 12648, 12650, -1, 12650, 12648, 12651, -1, 12651, 12648, 12652, -1, 12652, 12648, 12653, -1, 12653, 12648, 12654, -1, 12405, 12412, 12643, -1, 12647, 12655, 12391, -1, 12636, 12656, 12637, -1, 12657, 12648, 12169, -1, 12642, 12382, 12381, -1, 12124, 12125, 12585, -1, 12585, 12125, 12658, -1, 12659, 12660, 12636, -1, 12636, 12660, 12656, -1, 12125, 12126, 12658, -1, 12619, 12661, 12662, -1, 12183, 12661, 12580, -1, 12184, 12661, 12183, -1, 12658, 12126, 12663, -1, 12580, 12661, 12619, -1, 12664, 12665, 12659, -1, 12655, 12451, 12391, -1, 12659, 12665, 12660, -1, 12664, 12666, 12665, -1, 12648, 12667, 12654, -1, 12451, 12389, 12391, -1, 12184, 12668, 12661, -1, 12662, 12669, 12640, -1, 12670, 12669, 12671, -1, 12672, 12669, 12670, -1, 12639, 12669, 12672, -1, 12640, 12669, 12639, -1, 12126, 12673, 12663, -1, 12661, 12674, 12662, -1, 12666, 12673, 12675, -1, 12675, 12673, 12676, -1, 12676, 12673, 12677, -1, 12615, 12678, 12616, -1, 12677, 12673, 12679, -1, 12662, 12680, 12669, -1, 12679, 12673, 12126, -1, 12674, 12680, 12662, -1, 12663, 12673, 12681, -1, 12682, 12683, 12684, -1, 12685, 12683, 12682, -1, 12616, 12683, 12685, -1, 12686, 12687, 12575, -1, 12681, 12687, 12686, -1, 12616, 12688, 12683, -1, 12673, 12689, 12681, -1, 12678, 12688, 12616, -1, 12681, 12689, 12687, -1, 12690, 12691, 12664, -1, 12692, 12376, 12382, -1, 12671, 12376, 12692, -1, 12666, 12691, 12673, -1, 12664, 12691, 12666, -1, 12669, 12693, 12671, -1, 12687, 12694, 12695, -1, 12689, 12694, 12687, -1, 12130, 12131, 12667, -1, 12451, 12453, 12389, -1, 12173, 12174, 12657, -1, 12657, 12172, 12173, -1, 12667, 12129, 12130, -1, 12131, 12132, 12667, -1, 12174, 12175, 12657, -1, 12453, 12696, 12389, -1, 12657, 12175, 12242, -1, 12242, 12175, 12296, -1, 12667, 12128, 12129, -1, 12667, 12133, 12654, -1, 12673, 12424, 12689, -1, 12697, 12698, 12517, -1, 12657, 12171, 12172, -1, 12132, 12133, 12667, -1, 12517, 12698, 12699, -1, 12654, 12133, 12700, -1, 12175, 12176, 12296, -1, 12296, 12176, 12701, -1, 12517, 12702, 12697, -1, 12516, 12702, 12517, -1, 12698, 12703, 12699, -1, 12667, 12127, 12128, -1, 12699, 12703, 12704, -1, 12661, 12398, 12674, -1, 12674, 12398, 12705, -1, 12424, 12706, 12689, -1, 12133, 12134, 12700, -1, 12657, 12170, 12171, -1, 12700, 12134, 12707, -1, 12176, 12177, 12701, -1, 12701, 12177, 12503, -1, 12516, 12708, 12702, -1, 12503, 12177, 12506, -1, 12328, 12709, 12667, -1, 12615, 12710, 12678, -1, 12703, 12710, 12704, -1, 12704, 12710, 12615, -1, 12667, 12709, 12127, -1, 12134, 12135, 12707, -1, 12516, 12711, 12708, -1, 12657, 12169, 12170, -1, 12710, 12712, 12678, -1, 12683, 12468, 12684, -1, 12684, 12468, 12406, -1, 12713, 12468, 12683, -1, 12506, 12178, 12714, -1, 12452, 12458, 12453, -1, 12177, 12178, 12506, -1, 12715, 12458, 12452, -1, 12716, 12458, 12715, -1, 12456, 12458, 12716, -1, 12668, 12717, 12718, -1, 12719, 12720, 12690, -1, 12712, 12721, 12678, -1, 12690, 12720, 12691, -1, 12328, 12722, 12709, -1, 12184, 12723, 12668, -1, 12186, 12723, 12185, -1, 12185, 12723, 12184, -1, 12720, 12724, 12691, -1, 12668, 12723, 12717, -1, 12424, 12426, 12706, -1, 12398, 12725, 12705, -1, 12726, 12459, 12465, -1, 12691, 12727, 12420, -1, 12728, 12459, 12726, -1, 12724, 12727, 12691, -1, 12714, 12179, 12729, -1, 12328, 12730, 12722, -1, 12178, 12179, 12714, -1, 12727, 12731, 12420, -1, 12728, 12732, 12459, -1, 12693, 12733, 12671, -1, 12720, 12734, 12735, -1, 12328, 12736, 12730, -1, 12328, 12737, 12736, -1, 12731, 12738, 12420, -1, 12453, 12739, 12696, -1, 12729, 12180, 12740, -1, 12179, 12180, 12729, -1, 12718, 12393, 12668, -1, 12720, 12741, 12734, -1, 12718, 12742, 12393, -1, 12739, 12429, 12696, -1, 12328, 12329, 12737, -1, 12180, 12181, 12740, -1, 12743, 12744, 12745, -1, 12468, 12746, 12747, -1, 12748, 12749, 12687, -1, 12750, 12749, 12748, -1, 12751, 12749, 12750, -1, 12713, 12746, 12468, -1, 12687, 12749, 12575, -1, 12747, 12746, 12752, -1, 12458, 12471, 12453, -1, 12753, 12423, 12738, -1, 12738, 12423, 12420, -1, 12754, 12423, 12753, -1, 12744, 12755, 12745, -1, 12398, 12400, 12725, -1, 12746, 12756, 12752, -1, 12751, 12757, 12749, -1, 12742, 12758, 12393, -1, 12739, 12342, 12429, -1, 12671, 12759, 12376, -1, 12732, 12760, 12459, -1, 12733, 12759, 12671, -1, 12761, 12760, 12732, -1, 12762, 12763, 12645, -1, 12756, 12760, 12761, -1, 12645, 12763, 12644, -1, 12749, 12764, 12575, -1, 12516, 12765, 12711, -1, 12575, 12764, 12427, -1, 12746, 12766, 12756, -1, 12765, 12767, 12711, -1, 12754, 12768, 12423, -1, 12758, 12769, 12393, -1, 12770, 12771, 12765, -1, 12765, 12771, 12767, -1, 12757, 12772, 12749, -1, 12770, 12773, 12771, -1, 12768, 12774, 12423, -1, 12775, 12776, 12770, -1, 12770, 12776, 12773, -1, 12759, 12777, 12376, -1, 12376, 12777, 12778, -1, 12779, 12780, 12775, -1, 12781, 12777, 12759, -1, 12772, 12782, 12749, -1, 12775, 12780, 12776, -1, 12783, 12784, 12779, -1, 12779, 12784, 12780, -1, 12785, 12397, 12769, -1, 12769, 12397, 12393, -1, 12756, 12258, 12760, -1, 12744, 12470, 12755, -1, 12786, 12435, 12436, -1, 12787, 12470, 12471, -1, 12755, 12470, 12787, -1, 12258, 12470, 12744, -1, 12766, 12788, 12756, -1, 12720, 12789, 12741, -1, 12790, 12789, 12791, -1, 12791, 12789, 12719, -1, 12741, 12789, 12792, -1, 12781, 12793, 12777, -1, 12719, 12789, 12720, -1, 12781, 12794, 12793, -1, 12417, 12795, 12418, -1, 12796, 12301, 12435, -1, 12778, 12301, 12796, -1, 12777, 12301, 12778, -1, 12768, 12797, 12774, -1, 12797, 12798, 12774, -1, 12785, 12799, 12397, -1, 12774, 12798, 12417, -1, 12800, 12801, 12802, -1, 12417, 12798, 12795, -1, 12803, 12801, 12800, -1, 12416, 12413, 12415, -1, 12802, 12804, 12805, -1, 12801, 12804, 12802, -1, 12788, 12806, 12756, -1, 12789, 12807, 12792, -1, 12723, 12808, 12809, -1, 12258, 12314, 12470, -1, 12418, 12810, 12416, -1, 12804, 12274, 12805, -1, 12723, 12811, 12808, -1, 12808, 12812, 12809, -1, 12806, 12813, 12756, -1, 12809, 12812, 12814, -1, 12805, 12144, 12815, -1, 12723, 12816, 12811, -1, 12144, 12145, 12815, -1, 12812, 12817, 12814, -1, 12805, 12143, 12144, -1, 12145, 12146, 12815, -1, 12186, 12818, 12723, -1, 12723, 12818, 12816, -1, 12794, 12819, 12793, -1, 12805, 12142, 12143, -1, 12274, 12142, 12805, -1, 12798, 12820, 12821, -1, 12797, 12820, 12798, -1, 12815, 12147, 12822, -1, 12138, 12823, 12137, -1, 12146, 12147, 12815, -1, 12274, 12141, 12142, -1, 12822, 12148, 12824, -1, 12823, 12825, 12137, -1, 12137, 12825, 12136, -1, 12147, 12148, 12822, -1, 12810, 12826, 12416, -1, 12416, 12826, 12413, -1, 12138, 12827, 12823, -1, 12274, 12828, 12141, -1, 12829, 12826, 12810, -1, 12139, 12827, 12138, -1, 12830, 12831, 12764, -1, 12148, 12149, 12824, -1, 12825, 12832, 12136, -1, 12136, 12832, 12135, -1, 12373, 12833, 12374, -1, 12374, 12833, 12834, -1, 12274, 12835, 12828, -1, 12140, 12836, 12139, -1, 12139, 12836, 12827, -1, 12832, 12837, 12135, -1, 12135, 12837, 12707, -1, 12707, 12837, 12838, -1, 12274, 12839, 12835, -1, 12817, 12840, 12814, -1, 12274, 12841, 12839, -1, 12814, 12840, 12842, -1, 12799, 12321, 12397, -1, 12820, 12843, 12821, -1, 12821, 12843, 12844, -1, 12140, 12325, 12836, -1, 12813, 12845, 12756, -1, 12323, 12325, 12846, -1, 12846, 12325, 12140, -1, 12274, 12276, 12841, -1, 12837, 12847, 12838, -1, 12838, 12847, 12848, -1, 12849, 12850, 12833, -1, 12833, 12850, 12834, -1, 12794, 12851, 12819, -1, 12631, 12852, 12790, -1, 12789, 12852, 12853, -1, 12790, 12852, 12789, -1, 12181, 12852, 12740, -1, 12740, 12852, 12632, -1, 12632, 12852, 12631, -1, 12221, 12854, 12186, -1, 12186, 12854, 12818, -1, 12847, 12855, 12848, -1, 12848, 12855, 12856, -1, 12855, 12596, 12856, -1, 12857, 12858, 12859, -1, 12856, 12596, 12577, -1, 12215, 12217, 12860, -1, 12858, 12861, 12859, -1, 12840, 12243, 12842, -1, 12859, 12861, 12862, -1, 12852, 12863, 12853, -1, 12864, 12243, 12245, -1, 12842, 12243, 12864, -1, 12831, 12438, 12764, -1, 12764, 12438, 12427, -1, 12857, 12865, 12858, -1, 12843, 12266, 12844, -1, 12866, 12865, 12857, -1, 12826, 12218, 12215, -1, 12829, 12218, 12826, -1, 12863, 12867, 12853, -1, 12799, 12319, 12321, -1, 12861, 12868, 12862, -1, 12853, 12295, 12292, -1, 12867, 12295, 12853, -1, 12862, 12868, 12869, -1, 12870, 12871, 12721, -1, 12239, 12872, 12849, -1, 12866, 12871, 12865, -1, 12849, 12872, 12850, -1, 12721, 12871, 12678, -1, 12239, 12241, 12872, -1, 12678, 12871, 12866, -1, 12266, 12268, 12844, -1, 12868, 12225, 12869, -1, 12869, 12225, 12227, -1, 12824, 12231, 12873, -1, 12873, 12231, 12870, -1, 12152, 12231, 12151, -1, 12151, 12231, 12150, -1, 12150, 12231, 12149, -1, 12181, 12554, 12852, -1, 12874, 12222, 12224, -1, 12870, 12231, 12871, -1, 12875, 12222, 12874, -1, 12149, 12231, 12824, -1, 12756, 12256, 12258, -1, 12845, 12256, 12756, -1, 12221, 12220, 12854, -1, 12876, 12877, 12878, -1, 12879, 12880, 12877, -1, 12877, 12880, 12878, -1, 12881, 12882, 12879, -1, 12879, 12882, 12880, -1, 12052, 12667, 12038, -1, 12883, 12884, 12881, -1, 12881, 12884, 12882, -1, 12885, 12886, 12883, -1, 12883, 12886, 12884, -1, 12038, 12648, 12887, -1, 12667, 12648, 12038, -1, 12887, 12888, 12885, -1, 12885, 12888, 12886, -1, 12648, 12889, 12887, -1, 12887, 12889, 12888, -1, 12878, 12890, 12876, -1, 12891, 12890, 12878, -1, 12052, 12328, 12667, -1, 11872, 12328, 12052, -1, 12892, 12893, 12894, -1, 12895, 12893, 12892, -1, 12896, 12897, 12895, -1, 12895, 12897, 12893, -1, 12898, 12899, 12896, -1, 12896, 12899, 12897, -1, 12900, 12901, 12898, -1, 12898, 12901, 12899, -1, 12902, 12903, 12900, -1, 12900, 12903, 12901, -1, 12903, 12904, 12905, -1, 12902, 12904, 12903, -1, 12905, 12657, 11947, -1, 12904, 12657, 12905, -1, 11947, 12242, 11902, -1, 12657, 12242, 11947, -1, 12906, 12894, 12907, -1, 12892, 12894, 12906, -1, 11898, 11902, 12237, -1, 11902, 12242, 12237, -1, 11876, 11885, 12214, -1, 12214, 11885, 12908, -1, 12908, 11885, 12909, -1, 11885, 11883, 12909, -1, 12909, 11881, 12910, -1, 12910, 11881, 12911, -1, 11883, 11881, 12909, -1, 11881, 11880, 12911, -1, 12911, 11878, 12912, -1, 11880, 11878, 12911, -1, 12912, 11877, 12913, -1, 12913, 11877, 12914, -1, 11878, 11877, 12912, -1, 11877, 12110, 12914, -1, 12914, 11840, 12915, -1, 12110, 11840, 12914, -1, 12915, 11834, 12916, -1, 12916, 11834, 12917, -1, 11840, 11834, 12915, -1, 11834, 11830, 12917, -1, 12917, 11826, 12918, -1, 12918, 11826, 12919, -1, 11830, 11826, 12917, -1, 11826, 11822, 12919, -1, 12919, 11819, 12201, -1, 11822, 11819, 12919, -1, 11838, 11837, 12200, -1, 12200, 11837, 12920, -1, 12920, 11837, 12921, -1, 11837, 11852, 12921, -1, 12921, 11851, 12922, -1, 12922, 11851, 12923, -1, 11852, 11851, 12921, -1, 11851, 11850, 12923, -1, 12923, 11848, 12924, -1, 11850, 11848, 12923, -1, 12924, 11847, 12925, -1, 12925, 11847, 12926, -1, 11848, 11847, 12924, -1, 11847, 11846, 12926, -1, 12926, 11810, 12927, -1, 11846, 11810, 12926, -1, 12927, 11805, 12928, -1, 12928, 11805, 12929, -1, 11810, 11805, 12927, -1, 11805, 11797, 12929, -1, 12929, 11788, 12930, -1, 12930, 11788, 12931, -1, 11797, 11788, 12929, -1, 11788, 11784, 12931, -1, 12931, 11772, 12187, -1, 11784, 11772, 12931, -1, 12575, 11853, 12686, -1, 11853, 12096, 12686, -1, 12686, 11925, 12681, -1, 12096, 11925, 12686, -1, 12681, 11917, 12663, -1, 11925, 11917, 12681, -1, 12663, 11910, 12658, -1, 12658, 11910, 12585, -1, 11917, 11910, 12663, -1, 11910, 11791, 12585, -1, 12275, 12074, 12297, -1, 12297, 12087, 12304, -1, 12074, 12087, 12297, -1, 12304, 12089, 12318, -1, 12087, 12089, 12304, -1, 12318, 12092, 12334, -1, 12089, 12092, 12318, -1, 12334, 12095, 12336, -1, 12092, 12095, 12334, -1, 12095, 11768, 12336, -1, 12932, 11795, 11789, -1, 12933, 11789, 11785, -1, 12933, 12932, 11789, -1, 12934, 11785, 11777, -1, 12934, 12933, 11785, -1, 12935, 11777, 11780, -1, 12935, 12934, 11777, -1, 12936, 11780, 11779, -1, 12936, 12935, 11780, -1, 12937, 11779, 11778, -1, 12937, 12936, 11779, -1, 12938, 11778, 11787, -1, 12938, 12937, 11778, -1, 12939, 11787, 11792, -1, 12939, 12938, 11787, -1, 12940, 12939, 11792, -1, 12567, 11776, 12101, -1, 12563, 12101, 12099, -1, 12563, 12567, 12101, -1, 12561, 12099, 12098, -1, 12561, 12563, 12099, -1, 12564, 12098, 12097, -1, 12564, 12561, 12098, -1, 12562, 12097, 12100, -1, 12562, 12564, 12097, -1, 12566, 12100, 11827, -1, 12566, 12562, 12100, -1, 12571, 12566, 11827, -1, 12573, 11816, 12102, -1, 12558, 12093, 12084, -1, 12558, 12102, 12093, -1, 12558, 12573, 12102, -1, 12550, 12084, 12075, -1, 12550, 12558, 12084, -1, 12544, 12075, 12070, -1, 12544, 12550, 12075, -1, 12545, 12070, 12072, -1, 12545, 12544, 12070, -1, 12543, 12072, 12071, -1, 12543, 12545, 12072, -1, 12546, 12071, 12076, -1, 12546, 12543, 12071, -1, 12552, 12076, 12085, -1, 12552, 12546, 12076, -1, 12557, 12552, 12085, -1, 12559, 12085, 11813, -1, 12559, 12557, 12085, -1, 12572, 12559, 11813, -1, 12476, 11812, 12006, -1, 12464, 12006, 11999, -1, 12464, 12476, 12006, -1, 12462, 11999, 11998, -1, 12462, 12464, 11999, -1, 12466, 11998, 11997, -1, 12466, 12462, 11998, -1, 12463, 11997, 12005, -1, 12463, 12466, 11997, -1, 12475, 12005, 12018, -1, 12475, 12463, 12005, -1, 12478, 12475, 12018, -1, 12480, 12019, 12011, -1, 12434, 11996, 11985, -1, 12434, 12011, 11996, -1, 12434, 12480, 12011, -1, 12357, 11985, 11980, -1, 12357, 12434, 11985, -1, 12351, 11980, 11972, -1, 12351, 12357, 11980, -1, 12352, 11972, 11974, -1, 12352, 12351, 11972, -1, 12350, 11974, 11973, -1, 12350, 12352, 11974, -1, 12353, 11973, 11981, -1, 12353, 12350, 11973, -1, 12356, 11981, 11986, -1, 12356, 12353, 11981, -1, 12439, 12356, 11986, -1, 12444, 11986, 11939, -1, 12444, 12439, 11986, -1, 12290, 12444, 11939, -1, 12324, 11864, 11875, -1, 12348, 11887, 11886, -1, 12348, 11875, 11887, -1, 12348, 12324, 11875, -1, 12367, 11886, 11890, -1, 12367, 12348, 11886, -1, 12404, 11890, 11894, -1, 12404, 12367, 11890, -1, 12431, 11894, 11893, -1, 12431, 12404, 11894, -1, 12428, 11893, 11892, -1, 12428, 12431, 11893, -1, 12396, 11892, 11888, -1, 12396, 12428, 11892, -1, 12363, 11888, 11884, -1, 12363, 12396, 11888, -1, 12354, 12363, 11884, -1, 12349, 11884, 11874, -1, 12349, 12354, 11884, -1, 12335, 12349, 11874, -1, 12513, 11919, 11915, -1, 12509, 11915, 11908, -1, 12509, 12513, 11915, -1, 12507, 11908, 11907, -1, 12507, 12509, 11908, -1, 12511, 11907, 11906, -1, 12511, 12507, 11907, -1, 12508, 11906, 11913, -1, 12508, 12511, 11906, -1, 12512, 11913, 11918, -1, 12512, 12508, 11913, -1, 12516, 12512, 11918, -1, 12765, 11975, 11978, -1, 12770, 11984, 11983, -1, 12770, 11978, 11984, -1, 12770, 12765, 11978, -1, 12775, 11983, 11988, -1, 12775, 12770, 11983, -1, 12779, 11988, 11993, -1, 12779, 12775, 11988, -1, 12783, 11993, 11992, -1, 12783, 12779, 11993, -1, 12784, 11992, 11991, -1, 12784, 12783, 11992, -1, 12780, 11991, 11987, -1, 12780, 12784, 11991, -1, 12776, 11987, 11982, -1, 12776, 12780, 11987, -1, 12773, 12776, 11982, -1, 12771, 11982, 11977, -1, 12771, 12773, 11982, -1, 12767, 12771, 11977, -1, 12805, 12013, 12009, -1, 12802, 12009, 12004, -1, 12802, 12805, 12009, -1, 12800, 12004, 12003, -1, 12800, 12802, 12004, -1, 12803, 12003, 12002, -1, 12803, 12800, 12003, -1, 12801, 12002, 12008, -1, 12801, 12803, 12002, -1, 12804, 12008, 12012, -1, 12804, 12801, 12008, -1, 12274, 12804, 12012, -1, 11760, 12941, 12942, -1, 12108, 12942, 12943, -1, 12108, 11760, 12942, -1, 12106, 12943, 12944, -1, 12106, 12108, 12943, -1, 12103, 12944, 12945, -1, 12103, 12106, 12944, -1, 12104, 12945, 12946, -1, 12104, 12103, 12945, -1, 12105, 12946, 12947, -1, 12105, 12104, 12946, -1, 12107, 12947, 12948, -1, 12107, 12105, 12947, -1, 12109, 12948, 12949, -1, 12109, 12107, 12948, -1, 11761, 12109, 12949, -1, 11947, 12038, 12905, -1, 12905, 12887, 12903, -1, 12038, 12887, 12905, -1, 12903, 12885, 12901, -1, 12887, 12885, 12903, -1, 12901, 12883, 12899, -1, 12885, 12883, 12901, -1, 12899, 12881, 12897, -1, 12883, 12881, 12899, -1, 12897, 12879, 12893, -1, 12881, 12879, 12897, -1, 12893, 12877, 12894, -1, 12879, 12877, 12893, -1, 12877, 12876, 12894, -1, 12950, 12951, 12952, -1, 12953, 12951, 12950, -1, 12954, 12955, 12956, -1, 12957, 12958, 12959, -1, 12960, 12961, 12962, -1, 12963, 12958, 12957, -1, 12963, 12964, 12958, -1, 12965, 12964, 12963, -1, 12966, 12964, 12965, -1, 12967, 12954, 12956, -1, 12968, 12966, 12965, -1, 12969, 12966, 12968, -1, 12970, 12969, 12968, -1, 12971, 12969, 12970, -1, 12876, 12972, 12973, -1, 12876, 12973, 12974, -1, 12975, 12961, 12960, -1, 12876, 12974, 12976, -1, 12977, 12971, 12970, -1, 12876, 12978, 12894, -1, 12979, 12969, 12971, -1, 12876, 12976, 12980, -1, 12876, 12980, 12981, -1, 12876, 12981, 12982, -1, 12876, 12982, 12983, -1, 12876, 12983, 12978, -1, 12984, 12977, 12970, -1, 12985, 12956, 12986, -1, 12890, 12987, 12972, -1, 12985, 12967, 12956, -1, 12988, 12969, 12979, -1, 12890, 12951, 12953, -1, 12890, 12972, 12876, -1, 12890, 12953, 12989, -1, 12890, 12989, 12990, -1, 12890, 12990, 12987, -1, 12991, 12984, 12970, -1, 12992, 12961, 12975, -1, 12993, 12969, 12988, -1, 12994, 12991, 12970, -1, 12995, 12969, 12993, -1, 12996, 12994, 12970, -1, 12997, 12998, 12999, -1, 12997, 12999, 13000, -1, 13001, 12961, 12992, -1, 13002, 12997, 13000, -1, 13002, 13000, 13003, -1, 13004, 12995, 13005, -1, 13004, 13005, 13006, -1, 13004, 12969, 12995, -1, 13007, 13002, 13003, -1, 13007, 13003, 13008, -1, 13009, 13004, 13006, -1, 13010, 13004, 13009, -1, 13011, 13001, 13012, -1, 13013, 13004, 13010, -1, 13011, 12961, 13001, -1, 13011, 13008, 12961, -1, 13011, 13007, 13008, -1, 13014, 13011, 13012, -1, 13015, 13004, 13013, -1, 13016, 13017, 13004, -1, 13018, 13011, 13014, -1, 13019, 13016, 13004, -1, 13019, 13004, 13015, -1, 13020, 13011, 13018, -1, 13021, 13011, 13020, -1, 13022, 12996, 12970, -1, 13022, 13023, 13024, -1, 13022, 13024, 13025, -1, 13022, 13025, 13026, -1, 13022, 13026, 13027, -1, 13022, 13027, 12996, -1, 13022, 13028, 13023, -1, 13029, 13030, 12986, -1, 13031, 12986, 13030, -1, 13031, 12985, 12986, -1, 13032, 13033, 13034, -1, 13032, 13034, 13035, -1, 13036, 13033, 13032, -1, 13036, 13037, 13033, -1, 13038, 13029, 12986, -1, 13039, 13037, 13036, -1, 13039, 13022, 13037, -1, 13040, 13028, 13022, -1, 13041, 12985, 13031, -1, 13041, 13042, 12985, -1, 13040, 13022, 13039, -1, 13043, 13044, 13045, -1, 13043, 13038, 12986, -1, 13043, 12986, 13016, -1, 13043, 13016, 13044, -1, 13046, 13047, 13048, -1, 13049, 13050, 13051, -1, 13049, 13051, 13052, -1, 13049, 13052, 13042, -1, 13049, 13042, 13041, -1, 13053, 13047, 13046, -1, 13053, 13054, 13047, -1, 13055, 13043, 13045, -1, 13056, 13054, 13053, -1, 13057, 13054, 13056, -1, 13058, 13057, 13056, -1, 13059, 13057, 13058, -1, 13060, 13059, 13058, -1, 13061, 13062, 13063, -1, 13061, 13063, 13064, -1, 13061, 13064, 13028, -1, 13061, 13028, 13040, -1, 13065, 13019, 13062, -1, 13065, 13062, 13061, -1, 13066, 13016, 13019, -1, 13066, 13019, 13065, -1, 13067, 13016, 13066, -1, 13068, 13016, 13067, -1, 13069, 13050, 13049, -1, 13070, 13016, 13068, -1, 13044, 13016, 13070, -1, 13071, 13011, 13021, -1, 13071, 13050, 13069, -1, 13071, 13072, 13050, -1, 13071, 13021, 13073, -1, 13071, 13073, 13074, -1, 13075, 13059, 13060, -1, 13071, 13074, 13076, -1, 13071, 13076, 13077, -1, 13071, 13077, 13072, -1, 13078, 13071, 13069, -1, 13079, 13078, 13069, -1, 13080, 13078, 13079, -1, 13081, 13080, 13079, -1, 13082, 13080, 13081, -1, 13083, 13082, 13081, -1, 13084, 13082, 13083, -1, 13085, 13075, 13060, -1, 13086, 13087, 13088, -1, 13086, 13088, 13089, -1, 13090, 13087, 13086, -1, 13090, 13091, 13087, -1, 13092, 13091, 13090, -1, 13092, 13085, 13091, -1, 13093, 13085, 13092, -1, 13094, 13095, 13096, -1, 13094, 13096, 13097, -1, 13098, 13097, 13099, -1, 13098, 13094, 13097, -1, 13100, 13101, 13102, -1, 13103, 13099, 13104, -1, 13103, 13098, 13099, -1, 13105, 13101, 13100, -1, 13106, 13104, 13107, -1, 13105, 13108, 13101, -1, 13106, 13107, 13109, -1, 13106, 13103, 13104, -1, 13110, 13108, 13105, -1, 13110, 13111, 13108, -1, 13112, 13113, 13114, -1, 13115, 13111, 13110, -1, 13116, 13111, 13115, -1, 13117, 13116, 13115, -1, 13118, 13112, 13114, -1, 13118, 13114, 13119, -1, 13120, 13085, 13093, -1, 13120, 13121, 13075, -1, 13122, 13123, 13113, -1, 13122, 13113, 13112, -1, 13120, 13075, 13085, -1, 13124, 13121, 13120, -1, 13125, 13045, 13126, -1, 13125, 13126, 13127, -1, 13124, 13128, 13121, -1, 13125, 13119, 13055, -1, 13125, 13118, 13119, -1, 13125, 13055, 13045, -1, 13129, 13130, 13128, -1, 13129, 13128, 13124, -1, 13131, 13132, 13123, -1, 13131, 13123, 13122, -1, 13133, 13134, 13130, -1, 13133, 13130, 13129, -1, 13135, 13125, 13127, -1, 13136, 13137, 13134, -1, 13136, 13134, 13133, -1, 13138, 13109, 13132, -1, 13126, 13045, 13137, -1, 13138, 13132, 13131, -1, 13126, 13137, 13136, -1, 13139, 13127, 13140, -1, 13139, 13135, 13127, -1, 13141, 13142, 13143, -1, 13141, 13140, 13142, -1, 13141, 13139, 13140, -1, 13144, 13145, 13117, -1, 13146, 13138, 13147, -1, 13146, 13109, 13138, -1, 13146, 13106, 13109, -1, 13148, 13146, 13147, -1, 13149, 13148, 13147, -1, 13150, 13117, 13145, -1, 13151, 13148, 13149, -1, 13152, 13151, 13149, -1, 13153, 13144, 13117, -1, 13154, 13151, 13152, -1, 13155, 13154, 13152, -1, 13156, 13116, 13117, -1, 13157, 13154, 13155, -1, 13156, 13117, 13150, -1, 13158, 13153, 13117, -1, 13159, 13160, 13116, -1, 13159, 13116, 13156, -1, 13161, 13160, 13159, -1, 13162, 13160, 13161, -1, 13163, 13164, 13160, -1, 13163, 13160, 13162, -1, 13165, 13166, 13167, -1, 13165, 13167, 13168, -1, 13169, 13170, 13164, -1, 13169, 13164, 13163, -1, 13171, 13168, 13172, -1, 13171, 13165, 13168, -1, 13173, 13174, 13170, -1, 13173, 13170, 13169, -1, 13175, 13172, 13176, -1, 13175, 13171, 13172, -1, 13177, 13174, 13173, -1, 12951, 13176, 13178, -1, 13177, 13179, 13174, -1, 12951, 13175, 13176, -1, 13180, 13181, 13182, -1, 13143, 13179, 13177, -1, 13143, 13142, 13179, -1, 13183, 13182, 13184, -1, 13183, 13180, 13182, -1, 13185, 13181, 13180, -1, 13186, 13184, 13187, -1, 12907, 13188, 13189, -1, 12907, 13189, 13190, -1, 13186, 13183, 13184, -1, 12907, 13190, 13191, -1, 12907, 13191, 13158, -1, 13192, 13181, 13185, -1, 12907, 13158, 13117, -1, 12894, 13193, 13194, -1, 12894, 13194, 13195, -1, 12894, 13195, 13188, -1, 13196, 13187, 13197, -1, 12894, 13188, 12907, -1, 12894, 12978, 13198, -1, 12894, 13198, 13199, -1, 12894, 13199, 13200, -1, 12894, 13200, 13193, -1, 13196, 13186, 13187, -1, 13201, 13178, 13181, -1, 13201, 13181, 13192, -1, 13202, 13197, 13141, -1, 13202, 13196, 13197, -1, 13202, 13141, 13143, -1, 13203, 13178, 13201, -1, 12956, 13204, 12986, -1, 13203, 12951, 13178, -1, 13205, 13143, 13206, -1, 13205, 13206, 12978, -1, 13205, 13202, 13143, -1, 13207, 12951, 13203, -1, 12983, 13205, 12978, -1, 13208, 13209, 12956, -1, 13210, 12951, 13207, -1, 13211, 12956, 13209, -1, 12952, 12951, 13210, -1, 12955, 13208, 12956, -1, 12962, 12956, 13211, -1, 12962, 12961, 12956, -1, 13212, 13159, 13213, -1, 13213, 13156, 13214, -1, 13159, 13156, 13213, -1, 13214, 13150, 13215, -1, 13156, 13150, 13214, -1, 13215, 13145, 13216, -1, 13150, 13145, 13215, -1, 13216, 13144, 13217, -1, 13145, 13144, 13216, -1, 13217, 13153, 13218, -1, 13144, 13153, 13217, -1, 13218, 13158, 13219, -1, 13153, 13158, 13218, -1, 13219, 13191, 13220, -1, 13158, 13191, 13219, -1, 13220, 13190, 13221, -1, 13191, 13190, 13220, -1, 13221, 13189, 13222, -1, 13190, 13189, 13221, -1, 13222, 13188, 13223, -1, 13189, 13188, 13222, -1, 13223, 13195, 13224, -1, 13188, 13195, 13223, -1, 13224, 13194, 13225, -1, 13195, 13194, 13224, -1, 13194, 13193, 13225, -1, 12993, 12988, 13226, -1, 13226, 12988, 13227, -1, 13227, 12979, 13228, -1, 12988, 12979, 13227, -1, 13228, 12971, 13229, -1, 12979, 12971, 13228, -1, 13229, 12977, 13230, -1, 12971, 12977, 13229, -1, 13230, 12984, 13231, -1, 12977, 12984, 13230, -1, 13231, 12991, 13232, -1, 12984, 12991, 13231, -1, 13232, 12994, 13233, -1, 12991, 12994, 13232, -1, 13233, 12996, 13234, -1, 12994, 12996, 13233, -1, 13234, 13027, 13235, -1, 12996, 13027, 13234, -1, 13235, 13026, 13236, -1, 13027, 13026, 13235, -1, 13236, 13025, 13237, -1, 13026, 13025, 13236, -1, 13238, 13024, 13239, -1, 13237, 13024, 13238, -1, 13025, 13024, 13237, -1, 13024, 13023, 13239, -1, 12960, 12962, 13240, -1, 13240, 12962, 13241, -1, 13241, 13211, 13242, -1, 12962, 13211, 13241, -1, 13242, 13209, 13243, -1, 13211, 13209, 13242, -1, 13243, 13208, 13244, -1, 13209, 13208, 13243, -1, 13244, 12955, 13245, -1, 13208, 12955, 13244, -1, 13245, 12954, 13246, -1, 12955, 12954, 13245, -1, 13246, 12967, 13247, -1, 12954, 12967, 13246, -1, 13247, 12985, 13248, -1, 12967, 12985, 13247, -1, 13248, 13042, 13249, -1, 12985, 13042, 13248, -1, 13249, 13052, 13250, -1, 13042, 13052, 13249, -1, 13250, 13051, 13251, -1, 13052, 13051, 13250, -1, 13252, 13050, 13253, -1, 13251, 13050, 13252, -1, 13051, 13050, 13251, -1, 13050, 13072, 13253, -1, 13254, 13201, 13255, -1, 13255, 13192, 13256, -1, 13201, 13192, 13255, -1, 13256, 13185, 13257, -1, 13192, 13185, 13256, -1, 13257, 13180, 13258, -1, 13185, 13180, 13257, -1, 13258, 13183, 13259, -1, 13180, 13183, 13258, -1, 13259, 13186, 13260, -1, 13183, 13186, 13259, -1, 13260, 13196, 13261, -1, 13186, 13196, 13260, -1, 13261, 13202, 13262, -1, 13196, 13202, 13261, -1, 13262, 13205, 13263, -1, 13202, 13205, 13262, -1, 13263, 12983, 13264, -1, 13205, 12983, 13263, -1, 13264, 12982, 13265, -1, 12983, 12982, 13264, -1, 12982, 12981, 13265, -1, 13265, 12980, 13266, -1, 12981, 12980, 13265, -1, 13266, 12976, 13267, -1, 12980, 12976, 13266, -1, 12986, 13268, 13269, -1, 13204, 13268, 12986, -1, 13270, 13271, 13272, -1, 13273, 13271, 13270, -1, 13274, 13275, 13273, -1, 13273, 13275, 13271, -1, 12986, 13269, 13274, -1, 13274, 13269, 13275, -1, 13272, 13276, 13270, -1, 13276, 13277, 13270, -1, 13017, 13016, 13278, -1, 13016, 13279, 13278, -1, 13280, 13281, 13282, -1, 13283, 13284, 13280, -1, 13280, 13284, 13281, -1, 13279, 13285, 13283, -1, 13283, 13285, 13284, -1, 13279, 13016, 13285, -1, 13286, 13282, 13287, -1, 13282, 13281, 13287, -1, 13288, 13093, 13092, -1, 13289, 13092, 13090, -1, 13289, 13288, 13092, -1, 13290, 13090, 13086, -1, 13290, 13289, 13090, -1, 13291, 13086, 13089, -1, 13291, 13290, 13086, -1, 13292, 13089, 13088, -1, 13292, 13291, 13089, -1, 13293, 13088, 13087, -1, 13293, 13292, 13088, -1, 13294, 13087, 13091, -1, 13294, 13293, 13087, -1, 13295, 13091, 13085, -1, 13295, 13294, 13091, -1, 13296, 13295, 13085, -1, 13297, 13117, 13115, -1, 13298, 13115, 13110, -1, 13298, 13297, 13115, -1, 13299, 13110, 13105, -1, 13299, 13298, 13110, -1, 13300, 13105, 13100, -1, 13300, 13299, 13105, -1, 13301, 13100, 13102, -1, 13301, 13300, 13100, -1, 13302, 13102, 13101, -1, 13302, 13301, 13102, -1, 13303, 13101, 13108, -1, 13303, 13302, 13101, -1, 13304, 13108, 13111, -1, 13304, 13303, 13108, -1, 13305, 13111, 13116, -1, 13305, 13304, 13111, -1, 13306, 13305, 13116, -1, 13307, 13060, 13058, -1, 13308, 13058, 13056, -1, 13308, 13307, 13058, -1, 13309, 13056, 13053, -1, 13309, 13308, 13056, -1, 13310, 13053, 13046, -1, 13310, 13309, 13053, -1, 13311, 13046, 13048, -1, 13311, 13310, 13046, -1, 13312, 13048, 13047, -1, 13312, 13311, 13048, -1, 13313, 13047, 13054, -1, 13313, 13312, 13047, -1, 13314, 13054, 13057, -1, 13314, 13313, 13054, -1, 13315, 13057, 13059, -1, 13315, 13314, 13057, -1, 13316, 13315, 13059, -1, 13317, 13040, 13039, -1, 13318, 13039, 13036, -1, 13318, 13317, 13039, -1, 13319, 13036, 13032, -1, 13319, 13318, 13036, -1, 13320, 13032, 13035, -1, 13320, 13319, 13032, -1, 13321, 13035, 13034, -1, 13321, 13320, 13035, -1, 13322, 13034, 13033, -1, 13322, 13321, 13034, -1, 13323, 13033, 13037, -1, 13323, 13322, 13033, -1, 13324, 13037, 13022, -1, 13324, 13323, 13037, -1, 13325, 13324, 13022, -1, 13326, 12970, 12968, -1, 13327, 12968, 12965, -1, 13327, 13326, 12968, -1, 13328, 12965, 12963, -1, 13328, 13327, 12965, -1, 13329, 12963, 12957, -1, 13329, 13328, 12963, -1, 13330, 12957, 12959, -1, 13330, 13329, 12957, -1, 13331, 12959, 12958, -1, 13331, 13330, 12959, -1, 13332, 12958, 12964, -1, 13332, 13331, 12958, -1, 13333, 12964, 12966, -1, 13333, 13332, 12964, -1, 13334, 12966, 12969, -1, 13334, 13333, 12966, -1, 13335, 13334, 12969, -1, 13336, 12961, 13008, -1, 13337, 13008, 13003, -1, 13337, 13336, 13008, -1, 13338, 13003, 13000, -1, 13338, 13337, 13003, -1, 13339, 13000, 12999, -1, 13339, 13338, 13000, -1, 13340, 12999, 12998, -1, 13340, 13339, 12999, -1, 13341, 12998, 12997, -1, 13341, 13340, 12998, -1, 13342, 12997, 13002, -1, 13342, 13341, 12997, -1, 13343, 13002, 13007, -1, 13343, 13342, 13002, -1, 13344, 13007, 13011, -1, 13344, 13343, 13007, -1, 13345, 13344, 13011, -1, 13106, 13346, 13347, -1, 13103, 13347, 13348, -1, 13103, 13106, 13347, -1, 13098, 13348, 13349, -1, 13098, 13103, 13348, -1, 13094, 13349, 13350, -1, 13094, 13098, 13349, -1, 13095, 13350, 13351, -1, 13095, 13094, 13350, -1, 13096, 13351, 13352, -1, 13096, 13095, 13351, -1, 13097, 13352, 13353, -1, 13097, 13096, 13352, -1, 13099, 13353, 13354, -1, 13099, 13097, 13353, -1, 13104, 13354, 13355, -1, 13104, 13099, 13354, -1, 13107, 13104, 13355, -1, 13356, 13071, 13078, -1, 13357, 13078, 13080, -1, 13357, 13356, 13078, -1, 13358, 13080, 13082, -1, 13358, 13357, 13080, -1, 13359, 13082, 13084, -1, 13359, 13358, 13082, -1, 13360, 13084, 13083, -1, 13360, 13359, 13084, -1, 13361, 13083, 13081, -1, 13361, 13360, 13083, -1, 13362, 13081, 13079, -1, 13362, 13361, 13081, -1, 13363, 13079, 13069, -1, 13363, 13362, 13079, -1, 13364, 13363, 13069, -1, 13365, 13146, 13148, -1, 13366, 13148, 13151, -1, 13366, 13365, 13148, -1, 13367, 13151, 13154, -1, 13367, 13366, 13151, -1, 13368, 13154, 13157, -1, 13368, 13367, 13154, -1, 13369, 13157, 13155, -1, 13369, 13368, 13157, -1, 13370, 13155, 13152, -1, 13370, 13369, 13155, -1, 13371, 13152, 13149, -1, 13371, 13370, 13152, -1, 13372, 13149, 13147, -1, 13372, 13371, 13149, -1, 13373, 13372, 13147, -1, 12951, 13374, 13375, -1, 13175, 13375, 13376, -1, 13175, 12951, 13375, -1, 13171, 13376, 13377, -1, 13171, 13175, 13376, -1, 13165, 13377, 13378, -1, 13165, 13171, 13377, -1, 13166, 13378, 13379, -1, 13166, 13165, 13378, -1, 13167, 13379, 13380, -1, 13167, 13166, 13379, -1, 13168, 13380, 13381, -1, 13168, 13167, 13380, -1, 13172, 13381, 13382, -1, 13172, 13168, 13381, -1, 13176, 13382, 13383, -1, 13176, 13172, 13382, -1, 13178, 13176, 13383, -1, 13384, 13270, 13277, -1, 13285, 12986, 13274, -1, 13285, 13016, 12986, -1, 13284, 13274, 13273, -1, 13284, 13285, 13274, -1, 13281, 13273, 13270, -1, 13281, 13284, 13273, -1, 13385, 13287, 13281, -1, 13385, 13270, 13384, -1, 13385, 13281, 13270, -1, 13386, 13387, 13388, -1, 13386, 13384, 13387, -1, 13386, 13385, 13384, -1, 13389, 13386, 13388, -1, 13390, 13391, 13392, -1, 13393, 13391, 13390, -1, 13394, 13393, 13390, -1, 13395, 13393, 13394, -1, 13396, 13395, 13394, -1, 13397, 13395, 13396, -1, 13398, 13397, 13396, -1, 13399, 13400, 13398, -1, 13401, 13398, 13400, -1, 13402, 13399, 13398, -1, 13403, 13398, 13401, -1, 13404, 13402, 13398, -1, 13405, 13397, 13398, -1, 13405, 13398, 13403, -1, 13406, 13404, 13398, -1, 13407, 13397, 13405, -1, 13407, 13388, 13397, -1, 13408, 13388, 13407, -1, 13409, 13388, 13408, -1, 13410, 13388, 13409, -1, 13411, 13388, 13410, -1, 13412, 13388, 13411, -1, 13413, 13388, 13412, -1, 13414, 13388, 13413, -1, 13415, 13416, 13417, -1, 13418, 13417, 13419, -1, 13418, 13415, 13417, -1, 13420, 13421, 13416, -1, 13420, 13416, 13415, -1, 13422, 13419, 13423, -1, 13422, 13418, 13419, -1, 13424, 13425, 13421, -1, 13424, 13421, 13420, -1, 13426, 13423, 13406, -1, 13426, 13406, 13398, -1, 13426, 13422, 13423, -1, 13427, 13428, 13425, -1, 13427, 13425, 13424, -1, 13429, 13426, 13398, -1, 13430, 13428, 13427, -1, 13431, 13432, 13428, -1, 13431, 13428, 13430, -1, 13433, 13434, 13432, -1, 13433, 13432, 13431, -1, 13435, 13434, 13433, -1, 13435, 13436, 13434, -1, 13437, 13436, 13435, -1, 13437, 13438, 13436, -1, 13439, 13438, 13437, -1, 13439, 13440, 13438, -1, 13441, 13442, 13443, -1, 13444, 13441, 13443, -1, 13444, 13443, 13445, -1, 13446, 13442, 13441, -1, 13446, 13447, 13442, -1, 13448, 13444, 13445, -1, 13448, 13445, 13429, -1, 13449, 13447, 13446, -1, 13449, 13450, 13447, -1, 13451, 13448, 13429, -1, 13452, 13453, 13454, -1, 13452, 13454, 13450, -1, 13452, 13450, 13449, -1, 13455, 13453, 13452, -1, 13455, 13456, 13453, -1, 13457, 13456, 13455, -1, 13457, 13458, 13456, -1, 13459, 13458, 13457, -1, 13459, 13460, 13458, -1, 13461, 13462, 13451, -1, 13461, 13463, 13462, -1, 13461, 13464, 13463, -1, 13461, 13465, 13464, -1, 13461, 13466, 13465, -1, 13461, 13467, 13466, -1, 13461, 13468, 13467, -1, 13461, 13451, 13429, -1, 13461, 13429, 13398, -1, 13469, 13460, 13459, -1, 13469, 13470, 13460, -1, 13471, 13472, 13470, -1, 13471, 13470, 13469, -1, 13473, 13472, 13471, -1, 13474, 13475, 13476, -1, 13474, 13476, 13477, -1, 13478, 13475, 13474, -1, 13478, 13479, 13475, -1, 13480, 13479, 13478, -1, 13480, 13461, 13479, -1, 13481, 13468, 13461, -1, 13481, 13482, 13468, -1, 13481, 13461, 13480, -1, 13389, 13483, 13482, -1, 13389, 13484, 13483, -1, 13389, 13485, 13484, -1, 13389, 13486, 13485, -1, 13389, 13487, 13486, -1, 13389, 13488, 13487, -1, 13389, 13489, 13488, -1, 13389, 13482, 13481, -1, 13389, 13388, 13489, -1, 13489, 13388, 13473, -1, 13473, 13388, 13490, -1, 13490, 13388, 13491, -1, 13491, 13388, 13439, -1, 13439, 13388, 13414, -1, 13473, 13490, 13472, -1, 13439, 13414, 13440, -1, 13461, 13492, 13493, -1, 13479, 13493, 13494, -1, 13479, 13461, 13493, -1, 13475, 13494, 13495, -1, 13475, 13479, 13494, -1, 13476, 13495, 13496, -1, 13476, 13475, 13495, -1, 13477, 13496, 13497, -1, 13477, 13476, 13496, -1, 13474, 13497, 13498, -1, 13474, 13477, 13497, -1, 13478, 13498, 13499, -1, 13478, 13474, 13498, -1, 13480, 13499, 13500, -1, 13480, 13478, 13499, -1, 13481, 13480, 13500, -1, 13397, 13501, 13502, -1, 13395, 13502, 13503, -1, 13395, 13397, 13502, -1, 13393, 13503, 13504, -1, 13393, 13395, 13503, -1, 13391, 13504, 13505, -1, 13391, 13393, 13504, -1, 13392, 13505, 13506, -1, 13392, 13391, 13505, -1, 13390, 13506, 13507, -1, 13390, 13392, 13506, -1, 13394, 13507, 13508, -1, 13394, 13390, 13507, -1, 13396, 13508, 13509, -1, 13396, 13394, 13508, -1, 13398, 13396, 13509, -1, 11668, 8401, 11660, -1, 12427, 11666, 11663, -1, 8528, 8401, 11668, -1, 11652, 11650, 8528, -1, 11652, 11668, 11666, -1, 11652, 8528, 11668, -1, 11654, 11652, 11666, -1, 11654, 11666, 12427, -1, 12355, 11654, 12427, -1, 11656, 11654, 12355, -1, 12648, 12657, 12904, -1, 12889, 12904, 12902, -1, 12889, 12648, 12904, -1, 12888, 12902, 12900, -1, 12888, 12889, 12902, -1, 12886, 12900, 12898, -1, 12886, 12888, 12900, -1, 12884, 12898, 12896, -1, 12884, 12886, 12898, -1, 12882, 12896, 12895, -1, 12882, 12884, 12896, -1, 12880, 12895, 12892, -1, 12880, 12882, 12895, -1, 12878, 12880, 12892, -1, 13269, 13279, 13275, -1, 13275, 13283, 13271, -1, 13279, 13283, 13275, -1, 13271, 13280, 13272, -1, 13283, 13280, 13271, -1, 13280, 13282, 13272, -1, 13510, 13263, 12892, -1, 13262, 13263, 13510, -1, 13374, 13511, 13512, -1, 13244, 13245, 13513, -1, 13331, 13329, 13330, -1, 13513, 13241, 13242, -1, 13331, 13332, 13329, -1, 13336, 13241, 13513, -1, 13374, 13514, 13511, -1, 13332, 13328, 13329, -1, 13332, 13333, 13328, -1, 13245, 13246, 13513, -1, 13333, 13327, 13328, -1, 13374, 13515, 13514, -1, 13333, 13334, 13327, -1, 13336, 13240, 13241, -1, 13334, 13326, 13327, -1, 13374, 13516, 13515, -1, 13335, 13326, 13334, -1, 13246, 13247, 13513, -1, 13335, 13229, 13326, -1, 13229, 13230, 13326, -1, 13335, 13228, 13229, -1, 13230, 13231, 13326, -1, 13336, 13517, 13240, -1, 13335, 13227, 13228, -1, 13231, 13232, 13326, -1, 13335, 13226, 13227, -1, 13232, 13233, 13326, -1, 13513, 13248, 13269, -1, 13247, 13248, 13513, -1, 13518, 12878, 13519, -1, 13335, 13520, 13226, -1, 13519, 12878, 13521, -1, 13521, 12878, 13267, -1, 13263, 12878, 12892, -1, 13336, 13522, 13517, -1, 13233, 13234, 13326, -1, 13267, 12878, 13266, -1, 13266, 12878, 13265, -1, 13265, 12878, 13264, -1, 13264, 12878, 13263, -1, 13523, 12891, 13518, -1, 13374, 12891, 13516, -1, 13518, 12891, 12878, -1, 13516, 12891, 13524, -1, 13524, 12891, 13525, -1, 13525, 12891, 13523, -1, 13335, 13526, 13520, -1, 13520, 13526, 13527, -1, 13527, 13526, 13528, -1, 13340, 13341, 13339, -1, 13336, 13529, 13522, -1, 13526, 13530, 13528, -1, 13339, 13342, 13338, -1, 13341, 13342, 13339, -1, 13526, 13531, 13530, -1, 13338, 13343, 13337, -1, 13342, 13343, 13338, -1, 13526, 13532, 13531, -1, 13337, 13344, 13336, -1, 13343, 13344, 13337, -1, 13526, 13533, 13532, -1, 13278, 13279, 13526, -1, 13529, 13345, 13534, -1, 13336, 13345, 13529, -1, 13344, 13345, 13336, -1, 13526, 13535, 13533, -1, 13345, 13536, 13534, -1, 13279, 13535, 13526, -1, 13345, 13537, 13536, -1, 13239, 13325, 13238, -1, 13238, 13325, 13237, -1, 13237, 13325, 13236, -1, 13236, 13325, 13235, -1, 13235, 13325, 13234, -1, 13345, 13538, 13537, -1, 13539, 13325, 13239, -1, 13234, 13325, 13326, -1, 13345, 13540, 13538, -1, 13322, 13320, 13321, -1, 13322, 13319, 13320, -1, 13323, 13319, 13322, -1, 13541, 13542, 13269, -1, 13248, 13543, 13269, -1, 13323, 13318, 13319, -1, 13324, 13318, 13323, -1, 13539, 13317, 13325, -1, 13269, 13543, 13541, -1, 13324, 13317, 13318, -1, 13325, 13317, 13324, -1, 13542, 13544, 13269, -1, 13249, 13545, 13248, -1, 13248, 13545, 13543, -1, 13312, 13310, 13311, -1, 13312, 13313, 13310, -1, 13313, 13309, 13310, -1, 13544, 13546, 13269, -1, 13279, 13546, 13547, -1, 13269, 13546, 13279, -1, 13313, 13314, 13309, -1, 13249, 13548, 13545, -1, 13252, 13548, 13251, -1, 13251, 13548, 13250, -1, 13250, 13548, 13249, -1, 13314, 13308, 13309, -1, 13314, 13315, 13308, -1, 13546, 13549, 13547, -1, 13547, 13549, 13550, -1, 13316, 13307, 13315, -1, 13315, 13307, 13308, -1, 13551, 13552, 13553, -1, 13553, 13552, 13554, -1, 13554, 13552, 13539, -1, 13539, 13552, 13317, -1, 13551, 13555, 13552, -1, 13535, 13555, 13551, -1, 13279, 13556, 13535, -1, 13535, 13556, 13555, -1, 13279, 13557, 13556, -1, 13279, 13558, 13557, -1, 13279, 13559, 13558, -1, 13279, 13547, 13559, -1, 13316, 13560, 13307, -1, 13252, 13364, 13548, -1, 13345, 13356, 13540, -1, 13252, 13356, 13364, -1, 13253, 13356, 13252, -1, 13540, 13356, 13561, -1, 13561, 13356, 13562, -1, 13562, 13356, 13563, -1, 13563, 13356, 13564, -1, 13564, 13356, 13253, -1, 13356, 13363, 13364, -1, 13363, 13357, 13362, -1, 13356, 13357, 13363, -1, 13362, 13358, 13361, -1, 13357, 13358, 13362, -1, 13358, 13359, 13361, -1, 13560, 13296, 13307, -1, 13359, 13360, 13361, -1, 13293, 13291, 13292, -1, 13293, 13290, 13291, -1, 13294, 13290, 13293, -1, 13294, 13289, 13290, -1, 13295, 13289, 13294, -1, 13295, 13288, 13289, -1, 13296, 13288, 13295, -1, 13351, 13350, 13352, -1, 13302, 13300, 13301, -1, 13352, 13349, 13353, -1, 13302, 13303, 13300, -1, 13350, 13349, 13352, -1, 13303, 13299, 13300, -1, 13353, 13348, 13354, -1, 13303, 13304, 13299, -1, 13349, 13348, 13353, -1, 13304, 13298, 13299, -1, 13354, 13347, 13355, -1, 13348, 13347, 13354, -1, 13304, 13305, 13298, -1, 13355, 13346, 13565, -1, 13347, 13346, 13355, -1, 13566, 13567, 13568, -1, 13306, 13297, 13305, -1, 13305, 13297, 13298, -1, 13560, 13569, 13296, -1, 13296, 13569, 13288, -1, 13568, 13570, 13571, -1, 13572, 13569, 13560, -1, 13567, 13570, 13568, -1, 13572, 13573, 13569, -1, 13574, 13573, 13572, -1, 13575, 13576, 13566, -1, 13566, 13576, 13567, -1, 13574, 13577, 13573, -1, 13578, 13577, 13574, -1, 13571, 13579, 13549, -1, 13549, 13579, 13550, -1, 13580, 13579, 13581, -1, 13550, 13579, 13580, -1, 13578, 13582, 13577, -1, 13570, 13579, 13571, -1, 13583, 13582, 13578, -1, 13584, 13585, 13575, -1, 13575, 13585, 13576, -1, 13583, 13586, 13582, -1, 13587, 13586, 13583, -1, 13579, 13588, 13581, -1, 13587, 13580, 13586, -1, 13550, 13580, 13587, -1, 13565, 13589, 13584, -1, 13584, 13589, 13585, -1, 13581, 13590, 13591, -1, 13588, 13590, 13581, -1, 13592, 13593, 13594, -1, 13591, 13593, 13592, -1, 13590, 13593, 13591, -1, 13215, 13216, 13297, -1, 13297, 13214, 13215, -1, 13216, 13217, 13297, -1, 13306, 13213, 13297, -1, 13589, 13365, 13373, -1, 13346, 13365, 13565, -1, 13565, 13365, 13589, -1, 13297, 13213, 13214, -1, 13365, 13372, 13373, -1, 13217, 13218, 13297, -1, 13365, 13366, 13372, -1, 13372, 13366, 13371, -1, 13595, 13212, 13306, -1, 13366, 13367, 13371, -1, 13371, 13367, 13370, -1, 13306, 13212, 13213, -1, 13367, 13368, 13370, -1, 13368, 13369, 13370, -1, 13595, 13596, 13212, -1, 13595, 13597, 13596, -1, 13598, 13599, 13595, -1, 13595, 13599, 13597, -1, 13600, 13601, 13598, -1, 13598, 13601, 13599, -1, 13379, 13378, 13380, -1, 13380, 13377, 13381, -1, 13378, 13377, 13380, -1, 13602, 13603, 13600, -1, 13600, 13603, 13601, -1, 13381, 13376, 13382, -1, 13377, 13376, 13381, -1, 13602, 13604, 13603, -1, 13605, 13604, 13602, -1, 13382, 13375, 13383, -1, 13376, 13375, 13382, -1, 13375, 13374, 13383, -1, 13605, 13594, 13604, -1, 13592, 13594, 13605, -1, 13606, 13257, 13607, -1, 13607, 13258, 13608, -1, 13257, 13258, 13607, -1, 13606, 13256, 13257, -1, 13222, 12906, 13221, -1, 13221, 12906, 13220, -1, 13220, 12906, 13219, -1, 13219, 12906, 13218, -1, 13258, 13259, 13608, -1, 13608, 13259, 13609, -1, 13218, 12906, 13297, -1, 13225, 12892, 13224, -1, 13224, 12892, 13223, -1, 13223, 12892, 13222, -1, 13222, 12892, 12906, -1, 13510, 12892, 13610, -1, 13606, 13255, 13256, -1, 13610, 12892, 13611, -1, 13611, 12892, 13612, -1, 13612, 12892, 13225, -1, 13259, 13260, 13609, -1, 13609, 13260, 13613, -1, 13383, 13254, 13606, -1, 13606, 13254, 13255, -1, 13260, 13261, 13613, -1, 13613, 13261, 13593, -1, 13268, 13513, 13269, -1, 13593, 13261, 13594, -1, 13374, 13614, 13383, -1, 13383, 13614, 13254, -1, 13261, 13262, 13594, -1, 13594, 13262, 13615, -1, 13615, 13262, 13510, -1, 13374, 13512, 13614, -1, 13243, 13244, 13513, -1, 13513, 13242, 13243, -1, 13505, 13504, 13506, -1, 13504, 13507, 13506, -1, 13504, 13503, 13507, -1, 13503, 13508, 13507, -1, 13503, 13502, 13508, -1, 13502, 13509, 13508, -1, 13502, 13501, 13509, -1, 13616, 13617, 13509, -1, 13509, 13618, 13616, -1, 13617, 13619, 13509, -1, 13509, 13620, 13618, -1, 13619, 13621, 13509, -1, 13501, 13622, 13509, -1, 13509, 13622, 13620, -1, 13621, 13623, 13509, -1, 13501, 13272, 13622, -1, 13276, 13272, 13501, -1, 13272, 13624, 13622, -1, 13272, 13625, 13624, -1, 13272, 13626, 13625, -1, 13272, 13627, 13626, -1, 13272, 13628, 13627, -1, 13272, 13629, 13628, -1, 13272, 13630, 13629, -1, 13272, 13631, 13630, -1, 13632, 13633, 13634, -1, 13634, 13635, 13636, -1, 13633, 13635, 13634, -1, 13637, 13638, 13632, -1, 13632, 13638, 13633, -1, 13636, 13639, 13640, -1, 13635, 13639, 13636, -1, 13641, 13642, 13637, -1, 13637, 13642, 13638, -1, 13640, 13643, 13623, -1, 13639, 13643, 13640, -1, 13623, 13643, 13509, -1, 13641, 13644, 13642, -1, 13645, 13646, 13641, -1, 13641, 13646, 13644, -1, 13647, 13648, 13645, -1, 13645, 13648, 13646, -1, 13649, 13650, 13647, -1, 13647, 13650, 13648, -1, 13651, 13652, 13649, -1, 13649, 13652, 13650, -1, 13653, 13654, 13651, -1, 13651, 13654, 13652, -1, 13655, 13656, 13653, -1, 13653, 13656, 13654, -1, 13657, 13658, 13659, -1, 13658, 13660, 13659, -1, 13659, 13660, 13661, -1, 13657, 13662, 13658, -1, 13663, 13662, 13657, -1, 13660, 13664, 13661, -1, 13661, 13664, 13665, -1, 13663, 13666, 13662, -1, 13667, 13666, 13663, -1, 13664, 13668, 13665, -1, 13667, 13669, 13666, -1, 13670, 13669, 13671, -1, 13671, 13669, 13667, -1, 13670, 13672, 13669, -1, 13673, 13672, 13670, -1, 13673, 13674, 13672, -1, 13675, 13674, 13673, -1, 13675, 13676, 13674, -1, 13677, 13676, 13675, -1, 13643, 13492, 13509, -1, 13678, 13492, 13668, -1, 13679, 13492, 13678, -1, 13680, 13492, 13679, -1, 13681, 13492, 13680, -1, 13682, 13492, 13681, -1, 13668, 13492, 13665, -1, 13683, 13492, 13682, -1, 13684, 13492, 13683, -1, 13665, 13492, 13643, -1, 13677, 13685, 13676, -1, 13686, 13685, 13677, -1, 13687, 13688, 13686, -1, 13686, 13688, 13685, -1, 13687, 13689, 13688, -1, 13495, 13497, 13496, -1, 13494, 13498, 13495, -1, 13495, 13498, 13497, -1, 13493, 13499, 13494, -1, 13494, 13499, 13498, -1, 13493, 13500, 13499, -1, 13492, 13500, 13493, -1, 13684, 13500, 13492, -1, 13684, 13282, 13500, -1, 13690, 13282, 13684, -1, 13691, 13282, 13690, -1, 13692, 13282, 13691, -1, 13693, 13282, 13692, -1, 13694, 13282, 13693, -1, 13695, 13282, 13694, -1, 13696, 13282, 13695, -1, 13697, 13282, 13696, -1, 13282, 13286, 13500, -1, 13272, 13282, 13697, -1, 13272, 13697, 13689, -1, 13272, 13689, 13698, -1, 13272, 13698, 13699, -1, 13272, 13699, 13656, -1, 13272, 13656, 13631, -1, 13698, 13689, 13687, -1, 13631, 13656, 13655, -1, 13453, 13456, 13670, -1, 13670, 13456, 13673, -1, 13673, 13458, 13675, -1, 13456, 13458, 13673, -1, 13675, 13460, 13677, -1, 13458, 13460, 13675, -1, 13677, 13470, 13686, -1, 13460, 13470, 13677, -1, 13686, 13472, 13687, -1, 13470, 13472, 13686, -1, 13687, 13490, 13698, -1, 13472, 13490, 13687, -1, 13698, 13491, 13699, -1, 13490, 13491, 13698, -1, 13699, 13439, 13656, -1, 13491, 13439, 13699, -1, 13656, 13437, 13654, -1, 13439, 13437, 13656, -1, 13654, 13435, 13652, -1, 13437, 13435, 13654, -1, 13652, 13433, 13650, -1, 13435, 13433, 13652, -1, 13650, 13431, 13648, -1, 13433, 13431, 13650, -1, 13648, 13430, 13646, -1, 13431, 13430, 13648, -1, 13482, 13483, 13690, -1, 13690, 13483, 13691, -1, 13691, 13484, 13692, -1, 13483, 13484, 13691, -1, 13692, 13485, 13693, -1, 13484, 13485, 13692, -1, 13693, 13486, 13694, -1, 13485, 13486, 13693, -1, 13694, 13487, 13695, -1, 13486, 13487, 13694, -1, 13695, 13488, 13696, -1, 13487, 13488, 13695, -1, 13696, 13489, 13697, -1, 13488, 13489, 13696, -1, 13697, 13473, 13689, -1, 13489, 13473, 13697, -1, 13689, 13471, 13688, -1, 13473, 13471, 13689, -1, 13688, 13469, 13685, -1, 13471, 13469, 13688, -1, 13685, 13459, 13676, -1, 13469, 13459, 13685, -1, 13676, 13457, 13674, -1, 13674, 13457, 13672, -1, 13459, 13457, 13676, -1, 13457, 13455, 13672, -1, 13428, 13432, 13645, -1, 13645, 13432, 13647, -1, 13647, 13434, 13649, -1, 13432, 13434, 13647, -1, 13649, 13436, 13651, -1, 13434, 13436, 13649, -1, 13651, 13438, 13653, -1, 13436, 13438, 13651, -1, 13653, 13440, 13655, -1, 13438, 13440, 13653, -1, 13655, 13414, 13631, -1, 13440, 13414, 13655, -1, 13631, 13413, 13630, -1, 13414, 13413, 13631, -1, 13630, 13412, 13629, -1, 13413, 13412, 13630, -1, 13629, 13411, 13628, -1, 13412, 13411, 13629, -1, 13628, 13410, 13627, -1, 13411, 13410, 13628, -1, 13627, 13409, 13626, -1, 13410, 13409, 13627, -1, 13626, 13408, 13625, -1, 13625, 13408, 13624, -1, 13409, 13408, 13626, -1, 13408, 13407, 13624, -1, 13267, 12976, 13521, -1, 13521, 12974, 13519, -1, 12976, 12974, 13521, -1, 13519, 12973, 13518, -1, 12974, 12973, 13519, -1, 13518, 12972, 13523, -1, 12973, 12972, 13518, -1, 13523, 12987, 13525, -1, 12972, 12987, 13523, -1, 13525, 12990, 13524, -1, 12987, 12990, 13525, -1, 13524, 12989, 13516, -1, 12990, 12989, 13524, -1, 13516, 12953, 13515, -1, 12989, 12953, 13516, -1, 13515, 12950, 13514, -1, 12953, 12950, 13515, -1, 13514, 12952, 13511, -1, 12950, 12952, 13514, -1, 13511, 13210, 13512, -1, 12952, 13210, 13511, -1, 13512, 13207, 13614, -1, 13210, 13207, 13512, -1, 13614, 13203, 13254, -1, 13207, 13203, 13614, -1, 13203, 13201, 13254, -1, 13253, 13072, 13564, -1, 13564, 13077, 13563, -1, 13072, 13077, 13564, -1, 13563, 13076, 13562, -1, 13077, 13076, 13563, -1, 13562, 13074, 13561, -1, 13076, 13074, 13562, -1, 13561, 13073, 13540, -1, 13074, 13073, 13561, -1, 13540, 13021, 13538, -1, 13073, 13021, 13540, -1, 13538, 13020, 13537, -1, 13021, 13020, 13538, -1, 13537, 13018, 13536, -1, 13020, 13018, 13537, -1, 13536, 13014, 13534, -1, 13018, 13014, 13536, -1, 13534, 13012, 13529, -1, 13014, 13012, 13534, -1, 13529, 13001, 13522, -1, 13012, 13001, 13529, -1, 13522, 12992, 13517, -1, 13001, 12992, 13522, -1, 13517, 12975, 13240, -1, 12992, 12975, 13517, -1, 12975, 12960, 13240, -1, 13023, 13028, 13239, -1, 13239, 13028, 13539, -1, 13539, 13064, 13554, -1, 13028, 13064, 13539, -1, 13554, 13063, 13553, -1, 13064, 13063, 13554, -1, 13553, 13062, 13551, -1, 13063, 13062, 13553, -1, 13551, 13019, 13535, -1, 13062, 13019, 13551, -1, 13535, 13015, 13533, -1, 13019, 13015, 13535, -1, 13533, 13013, 13532, -1, 13015, 13013, 13533, -1, 13532, 13010, 13531, -1, 13013, 13010, 13532, -1, 13531, 13009, 13530, -1, 13010, 13009, 13531, -1, 13530, 13006, 13528, -1, 13009, 13006, 13530, -1, 13528, 13005, 13527, -1, 13006, 13005, 13528, -1, 13527, 12995, 13520, -1, 13005, 12995, 13527, -1, 13520, 12993, 13226, -1, 12995, 12993, 13520, -1, 13225, 13193, 13612, -1, 13612, 13200, 13611, -1, 13193, 13200, 13612, -1, 13611, 13199, 13610, -1, 13200, 13199, 13611, -1, 13610, 13198, 13510, -1, 13199, 13198, 13610, -1, 13510, 12978, 13615, -1, 13198, 12978, 13510, -1, 13615, 13206, 13594, -1, 12978, 13206, 13615, -1, 13594, 13143, 13604, -1, 13206, 13143, 13594, -1, 13604, 13177, 13603, -1, 13143, 13177, 13604, -1, 13603, 13173, 13601, -1, 13177, 13173, 13603, -1, 13601, 13169, 13599, -1, 13173, 13169, 13601, -1, 13599, 13163, 13597, -1, 13169, 13163, 13599, -1, 13597, 13162, 13596, -1, 13163, 13162, 13597, -1, 13596, 13161, 13212, -1, 13162, 13161, 13596, -1, 13161, 13159, 13212, -1, 12021, 11963, 12186, -1, 12186, 11963, 12221, -1, 12221, 11961, 12219, -1, 11963, 11961, 12221, -1, 12219, 11960, 12495, -1, 11961, 11960, 12219, -1, 12495, 11955, 12535, -1, 11960, 11955, 12495, -1, 12535, 11829, 12577, -1, 11955, 11829, 12535, -1, 12577, 11824, 12856, -1, 11829, 11824, 12577, -1, 12856, 11818, 12848, -1, 11824, 11818, 12856, -1, 12848, 11802, 12838, -1, 11818, 11802, 12848, -1, 12838, 11801, 12707, -1, 11802, 11801, 12838, -1, 12707, 12066, 12700, -1, 11801, 12066, 12707, -1, 12700, 12048, 12654, -1, 12066, 12048, 12700, -1, 12654, 12047, 12653, -1, 12048, 12047, 12654, -1, 12653, 12046, 12652, -1, 12047, 12046, 12653, -1, 12652, 12045, 12651, -1, 12046, 12045, 12652, -1, 12651, 12044, 12650, -1, 12045, 12044, 12651, -1, 12044, 12039, 12650, -1, 12650, 12039, 12649, -1, 12039, 11969, 12649, -1, 12649, 11969, 12169, -1, 12025, 12029, 12168, -1, 12168, 12029, 12485, -1, 12485, 12032, 12493, -1, 12029, 12032, 12485, -1, 12493, 12036, 12496, -1, 12032, 12036, 12493, -1, 12496, 12041, 12499, -1, 12036, 12041, 12496, -1, 12499, 11966, 12503, -1, 12041, 11966, 12499, -1, 12503, 11958, 12701, -1, 11966, 11958, 12503, -1, 12701, 11950, 12296, -1, 11958, 11950, 12701, -1, 12296, 11937, 12281, -1, 11950, 11937, 12296, -1, 12281, 11934, 12270, -1, 11937, 11934, 12281, -1, 12270, 11928, 12264, -1, 11934, 11928, 12270, -1, 12264, 11921, 12259, -1, 11928, 11921, 12264, -1, 12259, 11914, 12254, -1, 11921, 11914, 12259, -1, 12254, 11904, 12155, -1, 11914, 11904, 12254, -1, 12154, 12088, 12285, -1, 12285, 12083, 12284, -1, 12088, 12083, 12285, -1, 12284, 12082, 12283, -1, 12083, 12082, 12284, -1, 12283, 12081, 12282, -1, 12082, 12081, 12283, -1, 12282, 12080, 12280, -1, 12081, 12080, 12282, -1, 12280, 12079, 12279, -1, 12080, 12079, 12280, -1, 12279, 12078, 12278, -1, 12079, 12078, 12279, -1, 12278, 12077, 12276, -1, 12078, 12077, 12278, -1, 12276, 12063, 12841, -1, 12077, 12063, 12276, -1, 12841, 12061, 12839, -1, 12063, 12061, 12841, -1, 12839, 12057, 12835, -1, 12061, 12057, 12839, -1, 12835, 12053, 12828, -1, 12057, 12053, 12835, -1, 12828, 12050, 12141, -1, 12053, 12050, 12828, -1, 12050, 12037, 12141, -1, 11794, 11815, 12140, -1, 12140, 11815, 12846, -1, 12846, 11814, 12323, -1, 11815, 11814, 12846, -1, 12323, 11871, 12333, -1, 11814, 11871, 12323, -1, 12333, 11870, 12332, -1, 11871, 11870, 12333, -1, 12332, 11867, 12331, -1, 11870, 11867, 12332, -1, 12331, 11866, 12330, -1, 11867, 11866, 12331, -1, 12330, 11865, 12329, -1, 11866, 11865, 12330, -1, 12329, 12094, 12737, -1, 11865, 12094, 12329, -1, 12737, 12091, 12736, -1, 12094, 12091, 12737, -1, 12736, 12086, 12730, -1, 12091, 12086, 12736, -1, 12730, 12073, 12722, -1, 12086, 12073, 12730, -1, 12722, 12069, 12709, -1, 12073, 12069, 12722, -1, 12709, 12067, 12127, -1, 12069, 12067, 12709, -1, 12126, 11916, 12679, -1, 11916, 11924, 12679, -1, 12679, 11929, 12677, -1, 11924, 11929, 12679, -1, 12677, 12022, 12676, -1, 11929, 12022, 12677, -1, 12676, 11933, 12675, -1, 12022, 11933, 12676, -1, 12675, 11926, 12666, -1, 11933, 11926, 12675, -1, 12666, 11922, 12665, -1, 11926, 11922, 12666, -1, 12665, 11911, 12660, -1, 11922, 11911, 12665, -1, 12660, 11905, 12656, -1, 11911, 11905, 12660, -1, 12656, 11891, 12637, -1, 11905, 11891, 12656, -1, 12637, 11863, 12623, -1, 11891, 11863, 12637, -1, 12623, 11839, 12610, -1, 11863, 11839, 12623, -1, 12610, 11825, 12600, -1, 11839, 11825, 12610, -1, 12600, 11808, 12113, -1, 11825, 11808, 12600, -1, 8357, 7921, 13700, -1, 13700, 7929, 13701, -1, 7921, 7929, 13700, -1, 13701, 7928, 13702, -1, 7929, 7928, 13701, -1, 7928, 7927, 13702, -1, 13702, 7926, 13703, -1, 7927, 7926, 13702, -1, 13703, 7925, 13704, -1, 7926, 7925, 13703, -1, 13704, 7924, 13705, -1, 7925, 7924, 13704, -1, 13705, 8325, 13706, -1, 7924, 8325, 13705, -1, 13706, 8322, 13707, -1, 8325, 8322, 13706, -1, 13707, 8319, 13708, -1, 8322, 8319, 13707, -1, 13708, 8318, 13709, -1, 13709, 8318, 13710, -1, 8319, 8318, 13708, -1, 13710, 8313, 13711, -1, 8318, 8313, 13710, -1, 13711, 8312, 8344, -1, 8313, 8312, 13711, -1, 8312, 8311, 8344, -1, 8343, 7992, 13712, -1, 13712, 7999, 13713, -1, 7992, 7999, 13712, -1, 13713, 8035, 13714, -1, 7999, 8035, 13713, -1, 8035, 8037, 13714, -1, 13714, 8041, 13715, -1, 8037, 8041, 13714, -1, 13715, 8045, 13716, -1, 8041, 8045, 13715, -1, 13716, 8215, 13717, -1, 8045, 8215, 13716, -1, 13717, 7990, 13718, -1, 8215, 7990, 13717, -1, 13718, 7989, 13719, -1, 7990, 7989, 13718, -1, 13719, 7987, 13720, -1, 7989, 7987, 13719, -1, 13720, 7978, 13721, -1, 7987, 7978, 13720, -1, 13721, 7973, 13722, -1, 13722, 7973, 13723, -1, 7978, 7973, 13721, -1, 7973, 7964, 13723, -1, 13723, 7962, 8330, -1, 7964, 7962, 13723, -1, 7983, 7982, 11758, -1, 7983, 11758, 13724, -1, 13725, 7880, 13726, -1, 7897, 7880, 13725, -1, 13726, 7874, 13727, -1, 7880, 7874, 13726, -1, 13727, 7876, 13728, -1, 7874, 7876, 13727, -1, 13728, 8197, 13729, -1, 7876, 8197, 13728, -1, 13729, 8196, 13730, -1, 8197, 8196, 13729, -1, 13730, 8195, 13731, -1, 8196, 8195, 13730, -1, 13731, 8187, 13732, -1, 8195, 8187, 13731, -1, 13732, 8188, 13733, -1, 8187, 8188, 13732, -1, 13733, 8018, 13734, -1, 8188, 8018, 13733, -1, 13734, 8017, 13735, -1, 8018, 8017, 13734, -1, 13735, 8021, 13736, -1, 8017, 8021, 13735, -1, 13736, 8020, 13737, -1, 8021, 8020, 13736, -1, 13737, 7983, 13724, -1, 8020, 7983, 13737, -1, 7923, 13725, 11740, -1, 7923, 7897, 13725, -1, 13738, 8281, 11725, -1, 8295, 8281, 13738, -1, 13739, 8231, 13740, -1, 8233, 8231, 13739, -1, 13740, 8229, 13741, -1, 8231, 8229, 13740, -1, 13741, 8228, 13742, -1, 8229, 8228, 13741, -1, 13742, 8227, 13743, -1, 8228, 8227, 13742, -1, 13743, 8230, 13744, -1, 8227, 8230, 13743, -1, 13744, 8232, 13745, -1, 8230, 8232, 13744, -1, 13745, 8234, 13746, -1, 8232, 8234, 13745, -1, 13746, 8300, 13747, -1, 8234, 8300, 13746, -1, 13747, 8299, 13748, -1, 8300, 8299, 13747, -1, 13748, 8298, 13749, -1, 8299, 8298, 13748, -1, 13749, 8297, 13750, -1, 8298, 8297, 13749, -1, 13751, 8296, 13738, -1, 13750, 8296, 13751, -1, 8297, 8296, 13750, -1, 8296, 8295, 13738, -1, 11715, 8233, 13739, -1, 8245, 8233, 11715, -1, 13752, 11761, 12949, -1, 12360, 11761, 13752, -1, 11768, 12360, 12336, -1, 11768, 11761, 12360, -1, 12012, 12074, 12275, -1, 12012, 12275, 12274, -1, 12016, 12013, 12805, -1, 12016, 12805, 12815, -1, 12711, 11953, 12708, -1, 12708, 11948, 12702, -1, 11953, 11948, 12708, -1, 12702, 11935, 12697, -1, 11948, 11935, 12702, -1, 12697, 11931, 12698, -1, 11935, 11931, 12697, -1, 12698, 11930, 12703, -1, 11931, 11930, 12698, -1, 12703, 11936, 12710, -1, 11930, 11936, 12703, -1, 12710, 11949, 12712, -1, 11936, 11949, 12710, -1, 12712, 11954, 12721, -1, 11949, 11954, 12712, -1, 12721, 11959, 12870, -1, 11954, 11959, 12721, -1, 12870, 11962, 12873, -1, 11959, 11962, 12870, -1, 12873, 11968, 12824, -1, 11962, 11968, 12873, -1, 12824, 12043, 12822, -1, 11968, 12043, 12824, -1, 12822, 12034, 12815, -1, 12043, 12034, 12822, -1, 12034, 12016, 12815, -1, 11977, 12711, 12767, -1, 11977, 11953, 12711, -1, 11918, 11975, 12765, -1, 11918, 12765, 12516, -1, 11920, 11919, 12513, -1, 11920, 12513, 12517, -1, 12325, 11809, 12836, -1, 12836, 11793, 12827, -1, 11809, 11793, 12836, -1, 12827, 11769, 12823, -1, 11793, 11769, 12827, -1, 12823, 11764, 12825, -1, 11769, 11764, 12823, -1, 12825, 11763, 12832, -1, 11764, 11763, 12825, -1, 12832, 11781, 12837, -1, 11763, 11781, 12832, -1, 12837, 11798, 12847, -1, 11781, 11798, 12837, -1, 12847, 11817, 12855, -1, 11798, 11817, 12847, -1, 12855, 11823, 12596, -1, 11817, 11823, 12855, -1, 12596, 11828, 12615, -1, 11823, 11828, 12596, -1, 12615, 11836, 12704, -1, 11828, 11836, 12615, -1, 11836, 11938, 12704, -1, 12704, 11932, 12699, -1, 11938, 11932, 12704, -1, 12699, 11920, 12517, -1, 11932, 11920, 12699, -1, 11874, 12325, 12335, -1, 11874, 11809, 12325, -1, 11872, 11864, 12324, -1, 11872, 12324, 12328, -1, 13374, 12890, 12891, -1, 12951, 12890, 13374, -1, 13606, 13178, 13383, -1, 13181, 13178, 13606, -1, 13589, 13131, 13585, -1, 13138, 13131, 13589, -1, 13585, 13122, 13576, -1, 13131, 13122, 13585, -1, 13576, 13112, 13567, -1, 13122, 13112, 13576, -1, 13567, 13118, 13570, -1, 13112, 13118, 13567, -1, 13570, 13125, 13579, -1, 13118, 13125, 13570, -1, 13579, 13135, 13588, -1, 13125, 13135, 13579, -1, 13588, 13139, 13590, -1, 13135, 13139, 13588, -1, 13590, 13141, 13593, -1, 13139, 13141, 13590, -1, 13593, 13197, 13613, -1, 13141, 13197, 13593, -1, 13613, 13187, 13609, -1, 13197, 13187, 13613, -1, 13609, 13184, 13608, -1, 13187, 13184, 13609, -1, 13607, 13182, 13606, -1, 13608, 13182, 13607, -1, 13184, 13182, 13608, -1, 13182, 13181, 13606, -1, 13147, 13589, 13373, -1, 13147, 13138, 13589, -1, 13346, 13146, 13365, -1, 13106, 13146, 13346, -1, 13565, 13107, 13355, -1, 13109, 13107, 13565, -1, 13548, 13041, 13545, -1, 13049, 13041, 13548, -1, 13545, 13031, 13543, -1, 13041, 13031, 13545, -1, 13543, 13030, 13541, -1, 13031, 13030, 13543, -1, 13541, 13029, 13542, -1, 13030, 13029, 13541, -1, 13542, 13038, 13544, -1, 13029, 13038, 13542, -1, 13544, 13043, 13546, -1, 13038, 13043, 13544, -1, 13546, 13055, 13549, -1, 13043, 13055, 13546, -1, 13549, 13119, 13571, -1, 13055, 13119, 13549, -1, 13571, 13114, 13568, -1, 13119, 13114, 13571, -1, 13568, 13113, 13566, -1, 13114, 13113, 13568, -1, 13566, 13123, 13575, -1, 13113, 13123, 13566, -1, 13575, 13132, 13584, -1, 13123, 13132, 13575, -1, 13584, 13109, 13565, -1, 13132, 13109, 13584, -1, 13069, 13548, 13364, -1, 13069, 13049, 13548, -1, 13345, 13071, 13356, -1, 13011, 13071, 13345, -1, 13513, 12961, 13336, -1, 12956, 12961, 13513, -1, 13204, 12956, 13513, -1, 13204, 13513, 13268, -1, 13387, 13276, 13388, -1, 13384, 13276, 13387, -1, 13277, 13276, 13384, -1, 13501, 13388, 13276, -1, 13397, 13388, 13501, -1, 13492, 13398, 13509, -1, 13461, 13398, 13492, -1, 13389, 13481, 13500, -1, 13389, 13500, 13286, -1, 13286, 13287, 13385, -1, 13286, 13385, 13386, -1, 13286, 13386, 13389, -1, 13004, 13017, 13278, -1, 13004, 13278, 13526, -1, 13335, 13004, 13526, -1, 12969, 13004, 13335, -1, 13325, 12970, 13326, -1, 13022, 12970, 13325, -1, 13061, 13040, 13317, -1, 13061, 13317, 13552, -1, 13560, 13075, 13572, -1, 13572, 13121, 13574, -1, 13075, 13121, 13572, -1, 13574, 13128, 13578, -1, 13121, 13128, 13574, -1, 13578, 13130, 13583, -1, 13128, 13130, 13578, -1, 13583, 13134, 13587, -1, 13130, 13134, 13583, -1, 13587, 13137, 13550, -1, 13134, 13137, 13587, -1, 13550, 13045, 13547, -1, 13137, 13045, 13550, -1, 13547, 13044, 13559, -1, 13045, 13044, 13547, -1, 13559, 13070, 13558, -1, 13044, 13070, 13559, -1, 13558, 13068, 13557, -1, 13070, 13068, 13558, -1, 13557, 13067, 13556, -1, 13068, 13067, 13557, -1, 13556, 13066, 13555, -1, 13067, 13066, 13556, -1, 13555, 13065, 13552, -1, 13066, 13065, 13555, -1, 13065, 13061, 13552, -1, 13316, 13075, 13560, -1, 13059, 13075, 13316, -1, 13085, 13060, 13307, -1, 13085, 13307, 13296, -1, 13120, 13093, 13288, -1, 13120, 13288, 13569, -1, 13595, 13164, 13598, -1, 13160, 13164, 13595, -1, 13598, 13170, 13600, -1, 13164, 13170, 13598, -1, 13600, 13174, 13602, -1, 13170, 13174, 13600, -1, 13602, 13179, 13605, -1, 13174, 13179, 13602, -1, 13605, 13142, 13592, -1, 13179, 13142, 13605, -1, 13592, 13140, 13591, -1, 13142, 13140, 13592, -1, 13591, 13127, 13581, -1, 13140, 13127, 13591, -1, 13581, 13126, 13580, -1, 13127, 13126, 13581, -1, 13580, 13136, 13586, -1, 13126, 13136, 13580, -1, 13586, 13133, 13582, -1, 13136, 13133, 13586, -1, 13582, 13129, 13577, -1, 13133, 13129, 13582, -1, 13577, 13124, 13573, -1, 13129, 13124, 13577, -1, 13573, 13120, 13569, -1, 13124, 13120, 13573, -1, 13306, 13160, 13595, -1, 13116, 13160, 13306, -1, 12907, 13117, 13297, -1, 12907, 13297, 12906, -1, 12290, 11898, 12237, -1, 11939, 11898, 12290, -1, 12023, 12019, 12480, -1, 12023, 12480, 12481, -1, 12510, 11859, 12621, -1, 11832, 11859, 12510, -1, 12621, 11869, 12629, -1, 11859, 11869, 12621, -1, 12629, 11882, 12632, -1, 11869, 11882, 12629, -1, 12632, 11990, 12740, -1, 11882, 11990, 12632, -1, 12740, 11979, 12729, -1, 11990, 11979, 12740, -1, 12729, 11971, 12714, -1, 11979, 11971, 12729, -1, 12714, 11967, 12506, -1, 11971, 11967, 12714, -1, 12506, 12049, 12504, -1, 11967, 12049, 12506, -1, 12504, 12040, 12500, -1, 12049, 12040, 12504, -1, 12500, 12035, 12497, -1, 12040, 12035, 12500, -1, 12497, 12031, 12494, -1, 12035, 12031, 12497, -1, 12482, 12028, 12481, -1, 12494, 12028, 12482, -1, 12031, 12028, 12494, -1, 12028, 12023, 12481, -1, 12018, 12510, 12478, -1, 12018, 11832, 12510, -1, 11813, 11812, 12476, -1, 11813, 12476, 12572, -1, 12587, 11816, 12573, -1, 11811, 11816, 12587, -1, 12636, 11912, 12659, -1, 11889, 11912, 12636, -1, 12659, 11923, 12664, -1, 11912, 11923, 12659, -1, 12664, 11927, 12690, -1, 11923, 11927, 12664, -1, 12690, 12014, 12719, -1, 11927, 12014, 12690, -1, 12719, 12001, 12791, -1, 12014, 12001, 12719, -1, 12791, 11995, 12790, -1, 12001, 11995, 12791, -1, 12790, 11879, 12631, -1, 11995, 11879, 12790, -1, 12631, 11868, 12627, -1, 11879, 11868, 12631, -1, 12627, 11858, 12620, -1, 11868, 11858, 12627, -1, 12620, 11845, 12614, -1, 11858, 11845, 12620, -1, 12614, 11831, 12601, -1, 11845, 11831, 12614, -1, 12599, 11821, 12587, -1, 12601, 11821, 12599, -1, 11831, 11821, 12601, -1, 11821, 11811, 12587, -1, 11827, 12636, 12571, -1, 11827, 11889, 12636, -1, 11791, 12567, 12585, -1, 11791, 11776, 12567, -1, 12574, 11853, 12575, -1, 11792, 12574, 13753, -1, 11792, 13753, 12940, -1, 11792, 11853, 12574, -1, 7932, 11695, 13754, -1, 7932, 7900, 11695, -1, 13755, 7952, 13756, -1, 7944, 7952, 13755, -1, 13756, 7951, 13757, -1, 7952, 7951, 13756, -1, 13757, 7950, 13758, -1, 7951, 7950, 13757, -1, 13758, 7949, 13759, -1, 7950, 7949, 13758, -1, 13759, 7948, 13760, -1, 7949, 7948, 13759, -1, 13760, 7947, 13761, -1, 7948, 7947, 13760, -1, 13761, 7986, 13762, -1, 7947, 7986, 13761, -1, 13762, 7954, 13763, -1, 7986, 7954, 13762, -1, 13763, 7943, 13764, -1, 7954, 7943, 13763, -1, 13764, 7941, 13765, -1, 7943, 7941, 13764, -1, 13765, 7938, 13766, -1, 7941, 7938, 13765, -1, 13766, 7935, 13767, -1, 7938, 7935, 13766, -1, 13767, 7932, 13754, -1, 7935, 7932, 13767, -1, 7913, 13755, 11685, -1, 7913, 7944, 13755, -1, 8034, 8013, 11704, -1, 8034, 11704, 13768, -1, 13769, 8144, 13770, -1, 8056, 8144, 13769, -1, 13770, 8151, 13771, -1, 8144, 8151, 13770, -1, 13771, 8156, 13772, -1, 8151, 8156, 13771, -1, 13772, 8162, 13773, -1, 8156, 8162, 13772, -1, 13773, 8217, 13774, -1, 8162, 8217, 13773, -1, 13774, 8216, 13775, -1, 8217, 8216, 13774, -1, 13775, 8213, 13776, -1, 8216, 8213, 13775, -1, 13776, 8214, 13777, -1, 8213, 8214, 13776, -1, 13777, 8050, 13778, -1, 8214, 8050, 13777, -1, 13778, 8043, 13779, -1, 8050, 8043, 13778, -1, 13779, 8039, 13780, -1, 8043, 8039, 13779, -1, 13780, 8036, 13781, -1, 8039, 8036, 13780, -1, 13781, 8034, 13768, -1, 8036, 8034, 13781, -1, 11705, 8056, 13769, -1, 8031, 8056, 11705, -1, 13425, 13645, 13641, -1, 13425, 13428, 13645, -1, 13622, 13403, 13620, -1, 13405, 13403, 13622, -1, 13620, 13401, 13618, -1, 13403, 13401, 13620, -1, 13618, 13400, 13616, -1, 13401, 13400, 13618, -1, 13616, 13399, 13617, -1, 13400, 13399, 13616, -1, 13617, 13402, 13619, -1, 13399, 13402, 13617, -1, 13619, 13404, 13621, -1, 13402, 13404, 13619, -1, 13621, 13406, 13623, -1, 13404, 13406, 13621, -1, 13623, 13423, 13640, -1, 13406, 13423, 13623, -1, 13640, 13419, 13636, -1, 13423, 13419, 13640, -1, 13636, 13417, 13634, -1, 13419, 13417, 13636, -1, 13634, 13416, 13632, -1, 13417, 13416, 13634, -1, 13632, 13421, 13637, -1, 13637, 13421, 13641, -1, 13416, 13421, 13632, -1, 13421, 13425, 13641, -1, 13407, 13405, 13624, -1, 13624, 13405, 13622, -1, 13468, 13690, 13684, -1, 13468, 13482, 13690, -1, 13669, 13452, 13666, -1, 13666, 13449, 13662, -1, 13452, 13449, 13666, -1, 13662, 13446, 13658, -1, 13449, 13446, 13662, -1, 13658, 13441, 13660, -1, 13446, 13441, 13658, -1, 13660, 13444, 13664, -1, 13441, 13444, 13660, -1, 13664, 13448, 13668, -1, 13444, 13448, 13664, -1, 13668, 13451, 13678, -1, 13448, 13451, 13668, -1, 13678, 13462, 13679, -1, 13451, 13462, 13678, -1, 13679, 13463, 13680, -1, 13462, 13463, 13679, -1, 13680, 13464, 13681, -1, 13463, 13464, 13680, -1, 13681, 13465, 13682, -1, 13464, 13465, 13681, -1, 13682, 13466, 13683, -1, 13465, 13466, 13682, -1, 13683, 13467, 13684, -1, 13466, 13467, 13683, -1, 13467, 13468, 13684, -1, 13455, 13669, 13672, -1, 13455, 13452, 13669, -1, 13454, 13453, 13671, -1, 13671, 13453, 13670, -1, 13644, 13427, 13642, -1, 13642, 13424, 13638, -1, 13427, 13424, 13642, -1, 13638, 13420, 13633, -1, 13424, 13420, 13638, -1, 13633, 13415, 13635, -1, 13420, 13415, 13633, -1, 13635, 13418, 13639, -1, 13415, 13418, 13635, -1, 13639, 13422, 13643, -1, 13418, 13422, 13639, -1, 13643, 13426, 13665, -1, 13422, 13426, 13643, -1, 13665, 13429, 13661, -1, 13426, 13429, 13665, -1, 13661, 13445, 13659, -1, 13429, 13445, 13661, -1, 13659, 13443, 13657, -1, 13445, 13443, 13659, -1, 13657, 13442, 13663, -1, 13443, 13442, 13657, -1, 13663, 13447, 13667, -1, 13442, 13447, 13663, -1, 13667, 13450, 13671, -1, 13447, 13450, 13667, -1, 13450, 13454, 13671, -1, 13430, 13427, 13646, -1, 13646, 13427, 13644, -1, 9065, 9109, 9079, -1, 9079, 13782, 9085, -1, 9109, 13782, 9079, -1, 9085, 13783, 9088, -1, 13782, 13783, 9085, -1, 9088, 13784, 9083, -1, 13783, 13784, 9088, -1, 9083, 13785, 9075, -1, 13784, 13785, 9083, -1, 9075, 13786, 9074, -1, 13785, 13786, 9075, -1, 9074, 13787, 9068, -1, 13786, 13787, 9074, -1, 9068, 13788, 9060, -1, 13787, 13788, 9068, -1, 9060, 13789, 9058, -1, 13788, 13789, 9060, -1, 9058, 13790, 9094, -1, 13789, 13790, 9058, -1, 9094, 13791, 9091, -1, 13790, 13791, 9094, -1, 9091, 13792, 9081, -1, 13791, 13792, 9091, -1, 9081, 13793, 9076, -1, 13792, 13793, 9081, -1, 13793, 9096, 9076, -1, 9161, 13794, 9126, -1, 9126, 13794, 9130, -1, 9130, 13795, 9142, -1, 13794, 13795, 9130, -1, 9142, 13796, 9146, -1, 13795, 13796, 9142, -1, 9146, 13797, 9111, -1, 13796, 13797, 9146, -1, 9111, 13798, 9112, -1, 13797, 13798, 9111, -1, 9112, 13799, 9120, -1, 13798, 13799, 9112, -1, 9120, 13800, 9128, -1, 13799, 13800, 9120, -1, 9128, 13801, 9136, -1, 13800, 13801, 9128, -1, 9136, 13802, 9141, -1, 13801, 13802, 9136, -1, 9141, 13803, 9139, -1, 13802, 13803, 9141, -1, 9139, 13804, 9133, -1, 13803, 13804, 9139, -1, 9133, 13805, 9124, -1, 13804, 13805, 9133, -1, 9124, 9148, 9118, -1, 13805, 9148, 9124, -1, 9213, 13806, 9170, -1, 9170, 13806, 9185, -1, 9185, 13807, 9190, -1, 13806, 13807, 9185, -1, 9190, 13808, 9194, -1, 13807, 13808, 9190, -1, 9194, 13809, 9189, -1, 13808, 13809, 9194, -1, 9189, 13810, 9182, -1, 13809, 13810, 9189, -1, 9182, 13811, 9181, -1, 13810, 13811, 9182, -1, 9181, 13812, 9172, -1, 13811, 13812, 9181, -1, 9172, 13813, 9165, -1, 13812, 13813, 9172, -1, 9165, 13814, 9164, -1, 13813, 13814, 9165, -1, 9164, 13815, 9198, -1, 13814, 13815, 9164, -1, 9198, 13816, 9192, -1, 13815, 13816, 9198, -1, 9192, 13817, 9183, -1, 13816, 13817, 9192, -1, 9183, 9200, 9177, -1, 13817, 9200, 9183, -1, 9265, 13818, 9230, -1, 9230, 13818, 9235, -1, 9235, 13819, 9244, -1, 13818, 13819, 9235, -1, 9244, 13820, 9250, -1, 13819, 13820, 9244, -1, 9250, 13821, 9215, -1, 13820, 13821, 9250, -1, 9215, 13822, 9216, -1, 13821, 13822, 9215, -1, 9216, 13823, 9224, -1, 13822, 13823, 9216, -1, 9224, 13824, 9232, -1, 13823, 13824, 9224, -1, 9232, 13825, 9241, -1, 13824, 13825, 9232, -1, 9241, 13826, 9246, -1, 13825, 13826, 9241, -1, 9246, 13827, 9243, -1, 13826, 13827, 9246, -1, 9243, 13828, 9238, -1, 13827, 13828, 9243, -1, 9238, 13829, 9227, -1, 13828, 13829, 9238, -1, 9227, 9252, 9228, -1, 13829, 9252, 9227, -1, 2278, 1995, 1992, -1, 8092, 1992, 1989, -1, 8092, 2278, 1992, -1, 8087, 1989, 1982, -1, 8087, 8092, 1989, -1, 8085, 1982, 1986, -1, 8085, 8087, 1982, -1, 8081, 1986, 2112, -1, 8081, 8085, 1986, -1, 8075, 2112, 2111, -1, 8075, 8081, 2112, -1, 8074, 2111, 2115, -1, 8074, 8075, 2111, -1, 8071, 2115, 2117, -1, 8071, 8074, 2115, -1, 8066, 2117, 2177, -1, 8066, 8071, 2117, -1, 8061, 2177, 2176, -1, 8061, 8066, 2177, -1, 8062, 2176, 2175, -1, 8062, 8061, 2176, -1, 8064, 8062, 2175, -1, 8068, 2175, 2174, -1, 8068, 8064, 2175, -1, 2266, 2174, 2173, -1, 2266, 8068, 2174, -1, 2264, 2043, 2026, -1, 8202, 2026, 2016, -1, 8202, 2264, 2026, -1, 8203, 2016, 2004, -1, 8203, 8202, 2016, -1, 7958, 2004, 2015, -1, 7958, 8203, 2004, -1, 7953, 2015, 2022, -1, 7953, 7958, 2015, -1, 7945, 2022, 2036, -1, 7945, 7953, 2022, -1, 7933, 2036, 2048, -1, 7933, 7945, 2036, -1, 7916, 2048, 2054, -1, 7916, 7933, 2048, -1, 7911, 2054, 2066, -1, 7911, 7916, 2054, -1, 7905, 2066, 2070, -1, 7905, 7911, 2066, -1, 7901, 2070, 2099, -1, 7901, 7905, 2070, -1, 7906, 7901, 2099, -1, 7912, 2099, 2096, -1, 7912, 7906, 2099, -1, 2252, 2096, 2098, -1, 2252, 7912, 2096, -1, 2250, 2076, 2073, -1, 8038, 2073, 2063, -1, 8038, 2250, 2073, -1, 8014, 2063, 2056, -1, 8014, 8038, 2063, -1, 8012, 2056, 2058, -1, 8012, 8014, 2056, -1, 8007, 2058, 2071, -1, 8007, 8012, 2058, -1, 8002, 2071, 2075, -1, 8002, 8007, 2071, -1, 8001, 2075, 2083, -1, 8001, 8002, 2075, -1, 8000, 2083, 2103, -1, 8000, 8001, 2083, -1, 7995, 8000, 2103, -1, 7985, 2161, 2165, -1, 7985, 2103, 2161, -1, 7985, 7995, 2103, -1, 7988, 7985, 2165, -1, 8205, 2165, 2168, -1, 8205, 7988, 2165, -1, 8204, 2168, 2182, -1, 8204, 8205, 2168, -1, 2238, 2182, 2186, -1, 2238, 8204, 2182, -1, 2236, 1945, 1941, -1, 7972, 1941, 1938, -1, 7972, 2236, 1941, -1, 7971, 1938, 1937, -1, 7971, 7972, 1938, -1, 7970, 1937, 1936, -1, 7970, 7971, 1937, -1, 7965, 1936, 1940, -1, 7965, 7970, 1936, -1, 8329, 1940, 2114, -1, 8329, 7965, 1940, -1, 8328, 2114, 2113, -1, 8328, 8329, 2114, -1, 8327, 2113, 2116, -1, 8327, 8328, 2113, -1, 8324, 2116, 1984, -1, 8324, 8327, 2116, -1, 8320, 8324, 1984, -1, 8321, 1981, 1983, -1, 8321, 1984, 1981, -1, 8321, 8320, 1984, -1, 8323, 8321, 1983, -1, 8326, 1983, 1993, -1, 8326, 8323, 1983, -1, 2223, 1993, 1994, -1, 2223, 8326, 1993, -1, 13830, 9294, 13831, -1, 9293, 9294, 13830, -1, 13832, 8961, 8962, -1, 13833, 8961, 13832, -1, 8971, 13834, 8970, -1, 8970, 13835, 8969, -1, 13831, 9295, 13836, -1, 9294, 9295, 13831, -1, 13834, 13835, 8970, -1, 9295, 13837, 13836, -1, 8972, 13838, 8971, -1, 8971, 13838, 13834, -1, 8969, 13839, 8968, -1, 13835, 13839, 8969, -1, 13840, 8960, 13833, -1, 13833, 8960, 8961, -1, 8973, 13841, 8972, -1, 8972, 13841, 13838, -1, 8968, 13842, 8967, -1, 13839, 13842, 8968, -1, 13837, 9296, 13843, -1, 9295, 9296, 13837, -1, 8973, 13844, 13841, -1, 8967, 13845, 8966, -1, 13846, 9301, 13840, -1, 13842, 13845, 8967, -1, 13840, 9301, 8960, -1, 9290, 13847, 8973, -1, 13843, 9297, 13848, -1, 8973, 13847, 13844, -1, 9296, 9297, 13843, -1, 13845, 8965, 8966, -1, 13849, 9300, 13846, -1, 13846, 9300, 9301, -1, 13848, 9298, 13850, -1, 9297, 9298, 13848, -1, 13845, 13851, 8965, -1, 13850, 9299, 13849, -1, 9298, 9299, 13850, -1, 13849, 9299, 9300, -1, 9290, 9291, 13847, -1, 9291, 13852, 13847, -1, 13851, 8964, 8965, -1, 13851, 13853, 8964, -1, 9291, 9292, 13852, -1, 9292, 13854, 13852, -1, 13853, 8963, 8964, -1, 13855, 8963, 13853, -1, 13854, 9293, 13830, -1, 9292, 9293, 13854, -1, 13855, 8962, 8963, -1, 13832, 8962, 13855, -1, 13844, 13856, 13841, -1, 13841, 13857, 13838, -1, 13856, 13857, 13841, -1, 13838, 13858, 13834, -1, 13857, 13858, 13838, -1, 13834, 13859, 13835, -1, 13858, 13859, 13834, -1, 13835, 13860, 13839, -1, 13859, 13860, 13835, -1, 13839, 13861, 13842, -1, 13860, 13861, 13839, -1, 13842, 13862, 13845, -1, 13861, 13862, 13842, -1, 13845, 13863, 13851, -1, 13862, 13863, 13845, -1, 13851, 13864, 13853, -1, 13863, 13864, 13851, -1, 13853, 13865, 13855, -1, 13864, 13865, 13853, -1, 13855, 13866, 13832, -1, 13865, 13866, 13855, -1, 13832, 13867, 13833, -1, 13866, 13867, 13832, -1, 13833, 13868, 13840, -1, 13867, 13868, 13833, -1, 13868, 13869, 13840, -1, 13865, 13864, 13866, -1, 13866, 13864, 13867, -1, 13867, 13863, 13868, -1, 13864, 13863, 13867, -1, 13868, 13870, 13869, -1, 13860, 13859, 13861, -1, 13861, 13858, 13862, -1, 13859, 13858, 13861, -1, 13871, 13872, 13873, -1, 13873, 13872, 13874, -1, 13862, 13857, 13863, -1, 13863, 13857, 13868, -1, 13858, 13857, 13862, -1, 13870, 13875, 13871, -1, 13871, 13875, 13872, -1, 13875, 13876, 13877, -1, 13856, 13876, 13857, -1, 13857, 13876, 13868, -1, 13868, 13876, 13870, -1, 13870, 13876, 13875, -1, 13877, 13878, 13879, -1, 13876, 13878, 13877, -1, 13879, 13880, 13881, -1, 13878, 13880, 13879, -1, 13869, 13870, 13840, -1, 13840, 13870, 13846, -1, 13846, 13871, 13849, -1, 13870, 13871, 13846, -1, 13849, 13873, 13850, -1, 13871, 13873, 13849, -1, 13850, 13874, 13848, -1, 13873, 13874, 13850, -1, 13848, 13872, 13843, -1, 13874, 13872, 13848, -1, 13843, 13875, 13837, -1, 13872, 13875, 13843, -1, 13837, 13877, 13836, -1, 13875, 13877, 13837, -1, 13836, 13879, 13831, -1, 13877, 13879, 13836, -1, 13831, 13881, 13830, -1, 13879, 13881, 13831, -1, 13830, 13880, 13854, -1, 13881, 13880, 13830, -1, 13854, 13878, 13852, -1, 13880, 13878, 13854, -1, 13852, 13876, 13847, -1, 13878, 13876, 13852, -1, 13847, 13856, 13844, -1, 13876, 13856, 13847, -1, 13882, 9270, 13883, -1, 9269, 9270, 13882, -1, 8999, 13884, 8998, -1, 13885, 8989, 8990, -1, 13886, 8989, 13885, -1, 8998, 13887, 8997, -1, 13884, 13887, 8998, -1, 13883, 9271, 13888, -1, 9270, 9271, 13883, -1, 9000, 13889, 8999, -1, 8999, 13889, 13884, -1, 8997, 13890, 8996, -1, 13887, 13890, 8997, -1, 9271, 13891, 13888, -1, 9000, 13892, 13889, -1, 13893, 8988, 13886, -1, 8996, 13894, 8995, -1, 13890, 13894, 8996, -1, 13886, 8988, 8989, -1, 9001, 13895, 9000, -1, 9000, 13895, 13892, -1, 13891, 9272, 13896, -1, 9271, 9272, 13891, -1, 8995, 13897, 8994, -1, 13894, 13897, 8995, -1, 9266, 13898, 9001, -1, 9001, 13898, 13895, -1, 13899, 9277, 13893, -1, 13897, 8993, 8994, -1, 13893, 9277, 8988, -1, 13896, 9273, 13900, -1, 13897, 13901, 8993, -1, 9272, 9273, 13896, -1, 9266, 9267, 13898, -1, 13902, 9276, 13899, -1, 13899, 9276, 9277, -1, 13900, 9274, 13903, -1, 9273, 9274, 13900, -1, 9267, 13904, 13898, -1, 13903, 9275, 13902, -1, 9274, 9275, 13903, -1, 13902, 9275, 9276, -1, 13901, 8992, 8993, -1, 13901, 13905, 8992, -1, 9267, 9268, 13904, -1, 9268, 13906, 13904, -1, 13905, 8991, 8992, -1, 13907, 8991, 13905, -1, 13906, 9269, 13882, -1, 9268, 9269, 13906, -1, 13907, 8990, 8991, -1, 13885, 8990, 13907, -1, 13895, 13908, 13892, -1, 13892, 13909, 13889, -1, 13908, 13909, 13892, -1, 13889, 13910, 13884, -1, 13909, 13910, 13889, -1, 13884, 13911, 13887, -1, 13910, 13911, 13884, -1, 13887, 13912, 13890, -1, 13911, 13912, 13887, -1, 13890, 13913, 13894, -1, 13912, 13913, 13890, -1, 13894, 13914, 13897, -1, 13913, 13914, 13894, -1, 13897, 13915, 13901, -1, 13914, 13915, 13897, -1, 13901, 13916, 13905, -1, 13915, 13916, 13901, -1, 13905, 13917, 13907, -1, 13916, 13917, 13905, -1, 13907, 13918, 13885, -1, 13917, 13918, 13907, -1, 13885, 13919, 13886, -1, 13918, 13919, 13885, -1, 13886, 13920, 13893, -1, 13919, 13920, 13886, -1, 13920, 13921, 13893, -1, 13918, 13921, 13919, -1, 13919, 13921, 13920, -1, 13921, 13922, 13923, -1, 13918, 13922, 13921, -1, 13918, 13924, 13922, -1, 13916, 13925, 13917, -1, 13917, 13925, 13918, -1, 13918, 13925, 13924, -1, 13916, 13926, 13925, -1, 13915, 13927, 13916, -1, 13916, 13927, 13926, -1, 13909, 13908, 13910, -1, 13914, 13928, 13915, -1, 13915, 13928, 13927, -1, 13912, 13929, 13913, -1, 13913, 13929, 13914, -1, 13914, 13929, 13928, -1, 13930, 13931, 13908, -1, 13912, 13932, 13929, -1, 13910, 13933, 13911, -1, 13911, 13933, 13912, -1, 13908, 13933, 13910, -1, 13931, 13933, 13908, -1, 13912, 13933, 13932, -1, 13921, 13923, 13893, -1, 13893, 13923, 13899, -1, 13899, 13922, 13902, -1, 13923, 13922, 13899, -1, 13902, 13924, 13903, -1, 13922, 13924, 13902, -1, 13903, 13925, 13900, -1, 13924, 13925, 13903, -1, 13900, 13926, 13896, -1, 13925, 13926, 13900, -1, 13896, 13927, 13891, -1, 13926, 13927, 13896, -1, 13891, 13928, 13888, -1, 13927, 13928, 13891, -1, 13888, 13929, 13883, -1, 13928, 13929, 13888, -1, 13883, 13932, 13882, -1, 13929, 13932, 13883, -1, 13882, 13933, 13906, -1, 13932, 13933, 13882, -1, 13906, 13931, 13904, -1, 13933, 13931, 13906, -1, 13904, 13930, 13898, -1, 13931, 13930, 13904, -1, 13898, 13908, 13895, -1, 13930, 13908, 13898, -1, 13934, 13935, 8957, -1, 8958, 13934, 8957, -1, 13936, 13934, 8958, -1, 9308, 13937, 13938, -1, 9308, 9309, 13937, -1, 13939, 8948, 8949, -1, 13940, 8949, 8950, -1, 13940, 13939, 8949, -1, 13941, 8947, 8948, -1, 8959, 13936, 8958, -1, 13941, 8948, 13939, -1, 13942, 8950, 8951, -1, 13942, 13940, 8950, -1, 13943, 8947, 13941, -1, 9307, 13938, 13944, -1, 9307, 9308, 13938, -1, 13945, 8951, 8952, -1, 13945, 13942, 8951, -1, 13946, 8946, 8947, -1, 13946, 8947, 13943, -1, 9302, 13947, 13936, -1, 9302, 13948, 13947, -1, 9302, 13936, 8959, -1, 13949, 8952, 8953, -1, 13949, 13945, 8952, -1, 9306, 13944, 13950, -1, 9306, 9307, 13944, -1, 9303, 13951, 13948, -1, 13952, 9313, 8946, -1, 9303, 13948, 9302, -1, 13952, 8946, 13946, -1, 9305, 13950, 13953, -1, 9305, 9306, 13950, -1, 13954, 8953, 8954, -1, 9304, 9305, 13953, -1, 9304, 13953, 13951, -1, 9304, 13951, 9303, -1, 13954, 13949, 8953, -1, 9312, 9313, 13952, -1, 13955, 9312, 13952, -1, 13956, 8954, 8955, -1, 13956, 13954, 8954, -1, 9311, 9312, 13955, -1, 13957, 9311, 13955, -1, 13958, 13956, 8955, -1, 8956, 13958, 8955, -1, 9310, 13957, 13959, -1, 9310, 9311, 13957, -1, 13935, 13958, 8956, -1, 8957, 13935, 8956, -1, 9309, 9310, 13959, -1, 9309, 13959, 13937, -1, 13960, 13961, 13936, -1, 13936, 13961, 13934, -1, 13934, 13962, 13935, -1, 13961, 13962, 13934, -1, 13935, 13963, 13958, -1, 13962, 13963, 13935, -1, 13958, 13964, 13956, -1, 13963, 13964, 13958, -1, 13956, 13965, 13954, -1, 13964, 13965, 13956, -1, 13954, 13966, 13949, -1, 13965, 13966, 13954, -1, 13949, 13967, 13945, -1, 13966, 13967, 13949, -1, 13945, 13968, 13942, -1, 13967, 13968, 13945, -1, 13942, 13969, 13940, -1, 13968, 13969, 13942, -1, 13940, 13970, 13939, -1, 13969, 13970, 13940, -1, 13939, 13971, 13941, -1, 13970, 13971, 13939, -1, 13941, 13972, 13943, -1, 13971, 13972, 13941, -1, 13943, 13973, 13946, -1, 13972, 13973, 13943, -1, 13969, 13968, 13970, -1, 13970, 13968, 13971, -1, 13968, 13967, 13971, -1, 13971, 13973, 13972, -1, 13967, 13973, 13971, -1, 13973, 13974, 13975, -1, 13964, 13963, 13965, -1, 13965, 13962, 13966, -1, 13963, 13962, 13965, -1, 13974, 13976, 13977, -1, 13977, 13976, 13978, -1, 13973, 13979, 13974, -1, 13974, 13979, 13976, -1, 13961, 13960, 13962, -1, 13966, 13960, 13967, -1, 13967, 13960, 13973, -1, 13962, 13960, 13966, -1, 13960, 13980, 13973, -1, 13973, 13980, 13979, -1, 13980, 13981, 13982, -1, 13983, 13981, 13960, -1, 13960, 13981, 13980, -1, 13982, 13984, 13985, -1, 13981, 13984, 13982, -1, 13973, 13975, 13946, -1, 13946, 13975, 13952, -1, 13952, 13974, 13955, -1, 13975, 13974, 13952, -1, 13955, 13977, 13957, -1, 13974, 13977, 13955, -1, 13957, 13978, 13959, -1, 13977, 13978, 13957, -1, 13959, 13976, 13937, -1, 13978, 13976, 13959, -1, 13937, 13979, 13938, -1, 13976, 13979, 13937, -1, 13938, 13980, 13944, -1, 13979, 13980, 13938, -1, 13944, 13982, 13950, -1, 13980, 13982, 13944, -1, 13950, 13985, 13953, -1, 13982, 13985, 13950, -1, 13953, 13984, 13951, -1, 13985, 13984, 13953, -1, 13951, 13981, 13948, -1, 13984, 13981, 13951, -1, 13948, 13983, 13947, -1, 13981, 13983, 13948, -1, 13947, 13960, 13936, -1, 13983, 13960, 13947, -1, 13986, 11412, 13987, -1, 13987, 11412, 13988, -1, 13988, 11412, 13989, -1, 11411, 11412, 13990, -1, 13991, 13992, 11397, -1, 11412, 13993, 13989, -1, 13992, 13994, 11397, -1, 11412, 13995, 13993, -1, 11413, 13995, 11412, -1, 13994, 13996, 11397, -1, 11413, 11414, 13995, -1, 13997, 13998, 11411, -1, 11411, 13999, 13997, -1, 11414, 11415, 13995, -1, 13998, 14000, 11411, -1, 11415, 11416, 13995, -1, 11411, 14001, 13999, -1, 11411, 14002, 11410, -1, 11410, 14002, 11409, -1, 11409, 14002, 11408, -1, 11408, 14002, 11407, -1, 11407, 14002, 11406, -1, 11406, 14002, 11405, -1, 11416, 11417, 13995, -1, 13995, 11418, 14003, -1, 14000, 14002, 11411, -1, 11417, 11418, 13995, -1, 13996, 11398, 11397, -1, 14003, 11398, 14004, -1, 14004, 11398, 14005, -1, 11411, 13990, 14001, -1, 14005, 11398, 14006, -1, 14006, 11398, 14007, -1, 14007, 11398, 14008, -1, 11405, 14009, 11404, -1, 14008, 11398, 13996, -1, 11404, 14009, 11403, -1, 11403, 14009, 11402, -1, 11402, 14009, 11401, -1, 11401, 14009, 11400, -1, 14002, 14009, 11405, -1, 11418, 11419, 14003, -1, 14003, 11424, 11398, -1, 14009, 11399, 11400, -1, 11419, 11420, 14003, -1, 14003, 11423, 11424, -1, 11420, 11421, 14003, -1, 14003, 11422, 11423, -1, 11421, 11422, 14003, -1, 14009, 11397, 11399, -1, 14010, 11397, 14009, -1, 14010, 14011, 11397, -1, 14011, 13991, 11397, -1, 13990, 11412, 13986, -1, 13996, 13994, 14012, -1, 14012, 13994, 14013, -1, 14013, 13992, 14014, -1, 13994, 13992, 14013, -1, 14014, 13991, 14015, -1, 13992, 13991, 14014, -1, 14015, 14011, 14016, -1, 13991, 14011, 14015, -1, 14016, 14010, 14017, -1, 14011, 14010, 14016, -1, 14017, 14009, 14018, -1, 14010, 14009, 14017, -1, 14018, 14002, 14019, -1, 14009, 14002, 14018, -1, 14019, 14000, 14020, -1, 14002, 14000, 14019, -1, 14020, 13998, 14021, -1, 14000, 13998, 14020, -1, 14021, 13997, 14022, -1, 13998, 13997, 14021, -1, 14022, 13999, 14023, -1, 13997, 13999, 14022, -1, 14023, 14001, 14024, -1, 13999, 14001, 14023, -1, 14024, 13990, 14025, -1, 14001, 13990, 14024, -1, 14016, 14017, 14015, -1, 14019, 14020, 14018, -1, 14018, 14020, 14017, -1, 14021, 14022, 14020, -1, 14017, 14022, 14015, -1, 14020, 14022, 14017, -1, 14015, 14023, 14014, -1, 14022, 14023, 14015, -1, 14026, 14027, 14028, -1, 14014, 14024, 14013, -1, 14023, 14024, 14014, -1, 14013, 14025, 14012, -1, 14024, 14025, 14013, -1, 14012, 14029, 14030, -1, 14025, 14029, 14012, -1, 14027, 14031, 14032, -1, 14032, 14031, 14033, -1, 14026, 14031, 14027, -1, 14030, 14034, 14035, -1, 14029, 14034, 14030, -1, 14035, 14036, 14026, -1, 14031, 14036, 14037, -1, 14034, 14036, 14035, -1, 14026, 14036, 14031, -1, 13990, 13986, 14025, -1, 14025, 13986, 14029, -1, 14029, 13987, 14034, -1, 13986, 13987, 14029, -1, 14034, 13988, 14036, -1, 13987, 13988, 14034, -1, 14036, 13989, 14037, -1, 13988, 13989, 14036, -1, 14037, 13993, 14031, -1, 13989, 13993, 14037, -1, 14031, 13995, 14033, -1, 13993, 13995, 14031, -1, 14033, 14003, 14032, -1, 13995, 14003, 14033, -1, 14032, 14004, 14027, -1, 14003, 14004, 14032, -1, 14027, 14005, 14028, -1, 14004, 14005, 14027, -1, 14028, 14006, 14026, -1, 14005, 14006, 14028, -1, 14026, 14007, 14035, -1, 14006, 14007, 14026, -1, 14035, 14008, 14030, -1, 14007, 14008, 14035, -1, 14030, 13996, 14012, -1, 14008, 13996, 14030, -1, 14038, 11440, 14039, -1, 14039, 11440, 14040, -1, 14040, 11440, 14041, -1, 11439, 11440, 14042, -1, 14043, 14044, 11425, -1, 11440, 14045, 14041, -1, 14044, 14046, 11425, -1, 11440, 14047, 14045, -1, 11441, 14047, 11440, -1, 14046, 14048, 11425, -1, 11441, 11442, 14047, -1, 14049, 14050, 11439, -1, 11442, 11443, 14047, -1, 11439, 14051, 14049, -1, 11443, 11444, 14047, -1, 11444, 11445, 14047, -1, 14050, 14052, 11439, -1, 11445, 11446, 14047, -1, 11439, 14053, 14051, -1, 14054, 11426, 14055, -1, 14055, 11426, 14056, -1, 11439, 14057, 11438, -1, 14056, 11426, 14058, -1, 11438, 14057, 11437, -1, 14058, 11426, 14059, -1, 11437, 14057, 11436, -1, 14059, 11426, 14060, -1, 11436, 14057, 11435, -1, 14060, 11426, 14048, -1, 11435, 14057, 11434, -1, 14048, 11426, 11425, -1, 11434, 14057, 11433, -1, 11433, 14057, 11432, -1, 14047, 11447, 14054, -1, 11446, 11447, 14047, -1, 14052, 14057, 11439, -1, 14054, 11452, 11426, -1, 11447, 11448, 14054, -1, 11439, 14042, 14053, -1, 14054, 11451, 11452, -1, 11432, 14061, 11431, -1, 11431, 14061, 11430, -1, 11430, 14061, 11429, -1, 11429, 14061, 11428, -1, 14057, 14061, 11432, -1, 11448, 11449, 14054, -1, 11449, 11450, 14054, -1, 14061, 11427, 11428, -1, 14054, 11450, 11451, -1, 14061, 11425, 11427, -1, 14062, 11425, 14061, -1, 14062, 14063, 11425, -1, 14063, 14043, 11425, -1, 14042, 11440, 14038, -1, 14048, 14046, 14064, -1, 14064, 14046, 14065, -1, 14065, 14044, 14066, -1, 14046, 14044, 14065, -1, 14066, 14043, 14067, -1, 14044, 14043, 14066, -1, 14067, 14063, 14068, -1, 14043, 14063, 14067, -1, 14068, 14062, 14069, -1, 14063, 14062, 14068, -1, 14069, 14061, 14070, -1, 14062, 14061, 14069, -1, 14070, 14057, 14071, -1, 14061, 14057, 14070, -1, 14071, 14052, 14072, -1, 14057, 14052, 14071, -1, 14072, 14050, 14073, -1, 14052, 14050, 14072, -1, 14073, 14049, 14074, -1, 14050, 14049, 14073, -1, 14074, 14051, 14075, -1, 14049, 14051, 14074, -1, 14075, 14053, 14076, -1, 14051, 14053, 14075, -1, 14076, 14042, 14077, -1, 14053, 14042, 14076, -1, 14068, 14065, 14067, -1, 14067, 14065, 14066, -1, 14065, 14078, 14064, -1, 14078, 14079, 14080, -1, 14065, 14081, 14078, -1, 14068, 14081, 14065, -1, 14078, 14081, 14079, -1, 14069, 14082, 14068, -1, 14068, 14082, 14081, -1, 14075, 14076, 14074, -1, 14074, 14076, 14073, -1, 14070, 14083, 14069, -1, 14069, 14083, 14082, -1, 14071, 14084, 14070, -1, 14070, 14084, 14083, -1, 14077, 14085, 14076, -1, 14076, 14085, 14073, -1, 14072, 14086, 14071, -1, 14071, 14086, 14084, -1, 14073, 14087, 14072, -1, 14085, 14087, 14073, -1, 14072, 14087, 14086, -1, 14088, 14089, 14085, -1, 14085, 14089, 14087, -1, 14042, 14038, 14077, -1, 14077, 14038, 14085, -1, 14085, 14039, 14088, -1, 14038, 14039, 14085, -1, 14088, 14040, 14089, -1, 14039, 14040, 14088, -1, 14089, 14041, 14087, -1, 14040, 14041, 14089, -1, 14087, 14045, 14086, -1, 14041, 14045, 14087, -1, 14086, 14047, 14084, -1, 14045, 14047, 14086, -1, 14084, 14054, 14083, -1, 14047, 14054, 14084, -1, 14083, 14055, 14082, -1, 14054, 14055, 14083, -1, 14082, 14056, 14081, -1, 14055, 14056, 14082, -1, 14081, 14058, 14079, -1, 14056, 14058, 14081, -1, 14079, 14059, 14080, -1, 14058, 14059, 14079, -1, 14080, 14060, 14078, -1, 14059, 14060, 14080, -1, 14078, 14048, 14064, -1, 14060, 14048, 14078, -1, 11467, 11468, 14090, -1, 14091, 14092, 11453, -1, 11468, 14093, 14094, -1, 14092, 14095, 11453, -1, 11468, 14096, 14093, -1, 11469, 14096, 11468, -1, 14095, 14097, 11453, -1, 11469, 11470, 14096, -1, 14098, 14099, 11467, -1, 11467, 14100, 14098, -1, 11470, 11471, 14096, -1, 11471, 11472, 14096, -1, 14099, 14101, 11467, -1, 11472, 11473, 14096, -1, 11467, 14102, 14100, -1, 11473, 11474, 14096, -1, 11467, 14103, 11466, -1, 14097, 11454, 11453, -1, 11466, 14103, 11465, -1, 11465, 14103, 11464, -1, 14104, 11454, 14105, -1, 11464, 14103, 11463, -1, 14105, 11454, 14106, -1, 11463, 14103, 11462, -1, 14106, 11454, 14107, -1, 11462, 14103, 11461, -1, 14107, 11454, 14108, -1, 11461, 14103, 11460, -1, 14108, 11454, 14109, -1, 14109, 11454, 14097, -1, 14101, 14103, 11467, -1, 14096, 11475, 14104, -1, 11474, 11475, 14096, -1, 14104, 11480, 11454, -1, 11467, 14090, 14102, -1, 11475, 11476, 14104, -1, 11460, 14110, 11459, -1, 11459, 14110, 11458, -1, 11458, 14110, 11457, -1, 11457, 14110, 11456, -1, 14103, 14110, 11460, -1, 14104, 11479, 11480, -1, 11476, 11477, 14104, -1, 14110, 11455, 11456, -1, 14104, 11478, 11479, -1, 11477, 11478, 14104, -1, 14110, 11453, 11455, -1, 14111, 11453, 14110, -1, 14111, 14112, 11453, -1, 14112, 14091, 11453, -1, 14090, 11468, 14113, -1, 14113, 11468, 14114, -1, 14114, 11468, 14115, -1, 14115, 11468, 14094, -1, 14097, 14095, 14116, -1, 14116, 14095, 14117, -1, 14117, 14092, 14118, -1, 14095, 14092, 14117, -1, 14118, 14091, 14119, -1, 14092, 14091, 14118, -1, 14119, 14112, 14120, -1, 14091, 14112, 14119, -1, 14120, 14111, 14121, -1, 14112, 14111, 14120, -1, 14121, 14110, 14122, -1, 14111, 14110, 14121, -1, 14122, 14103, 14123, -1, 14110, 14103, 14122, -1, 14123, 14101, 14124, -1, 14103, 14101, 14123, -1, 14124, 14099, 14125, -1, 14101, 14099, 14124, -1, 14125, 14098, 14126, -1, 14099, 14098, 14125, -1, 14126, 14100, 14127, -1, 14098, 14100, 14126, -1, 14127, 14102, 14128, -1, 14100, 14102, 14127, -1, 14128, 14090, 14129, -1, 14102, 14090, 14128, -1, 14120, 14117, 14119, -1, 14119, 14117, 14118, -1, 14117, 14130, 14116, -1, 14120, 14130, 14117, -1, 14130, 14131, 14132, -1, 14130, 14133, 14131, -1, 14120, 14133, 14130, -1, 14121, 14134, 14120, -1, 14120, 14134, 14133, -1, 14127, 14128, 14126, -1, 14126, 14128, 14125, -1, 14122, 14135, 14121, -1, 14121, 14135, 14134, -1, 14123, 14136, 14122, -1, 14122, 14136, 14135, -1, 14129, 14137, 14128, -1, 14128, 14137, 14125, -1, 14124, 14138, 14123, -1, 14123, 14138, 14136, -1, 14125, 14139, 14124, -1, 14137, 14139, 14125, -1, 14124, 14139, 14138, -1, 14140, 14141, 14137, -1, 14137, 14141, 14139, -1, 14090, 14113, 14129, -1, 14129, 14113, 14137, -1, 14137, 14114, 14140, -1, 14113, 14114, 14137, -1, 14140, 14115, 14141, -1, 14114, 14115, 14140, -1, 14141, 14094, 14139, -1, 14115, 14094, 14141, -1, 14139, 14093, 14138, -1, 14094, 14093, 14139, -1, 14138, 14096, 14136, -1, 14093, 14096, 14138, -1, 14136, 14104, 14135, -1, 14096, 14104, 14136, -1, 14135, 14105, 14134, -1, 14104, 14105, 14135, -1, 14134, 14106, 14133, -1, 14105, 14106, 14134, -1, 14133, 14107, 14131, -1, 14106, 14107, 14133, -1, 14131, 14108, 14132, -1, 14107, 14108, 14131, -1, 14132, 14109, 14130, -1, 14108, 14109, 14132, -1, 14130, 14097, 14116, -1, 14109, 14097, 14130, -1, 14142, 14143, 11481, -1, 11496, 14144, 14145, -1, 14143, 14146, 11481, -1, 11496, 14147, 14144, -1, 11497, 14147, 11496, -1, 14146, 14148, 11481, -1, 11497, 11498, 14147, -1, 14149, 14150, 11495, -1, 11495, 14151, 14149, -1, 11498, 11499, 14147, -1, 11499, 11500, 14147, -1, 11500, 11501, 14147, -1, 14150, 14152, 11495, -1, 11495, 14153, 14151, -1, 11501, 11502, 14147, -1, 11495, 14154, 11494, -1, 14155, 11482, 14156, -1, 11494, 14154, 11493, -1, 14156, 11482, 14157, -1, 11493, 14154, 11492, -1, 14157, 11482, 14158, -1, 11492, 14154, 11491, -1, 14158, 11482, 14159, -1, 11491, 14154, 11490, -1, 14159, 11482, 14160, -1, 11490, 14154, 11489, -1, 14160, 11482, 14148, -1, 11489, 14154, 11488, -1, 14148, 11482, 11481, -1, 14147, 11503, 14155, -1, 14152, 14154, 11495, -1, 11502, 11503, 14147, -1, 14155, 11508, 11482, -1, 11495, 14161, 14153, -1, 11503, 11504, 14155, -1, 11488, 14162, 11487, -1, 11487, 14162, 11486, -1, 11486, 14162, 11485, -1, 11485, 14162, 11484, -1, 14155, 11507, 11508, -1, 14154, 14162, 11488, -1, 11504, 11505, 14155, -1, 14162, 11483, 11484, -1, 11505, 11506, 14155, -1, 14155, 11506, 11507, -1, 14162, 11481, 11483, -1, 14163, 11481, 14162, -1, 14163, 14164, 11481, -1, 14164, 14142, 11481, -1, 14161, 11496, 14165, -1, 14165, 11496, 14166, -1, 14166, 11496, 14167, -1, 14167, 11496, 14145, -1, 11495, 11496, 14161, -1, 14148, 14146, 14168, -1, 14168, 14146, 14169, -1, 14169, 14143, 14170, -1, 14146, 14143, 14169, -1, 14170, 14142, 14171, -1, 14143, 14142, 14170, -1, 14171, 14164, 14172, -1, 14142, 14164, 14171, -1, 14172, 14163, 14173, -1, 14164, 14163, 14172, -1, 14173, 14162, 14174, -1, 14163, 14162, 14173, -1, 14174, 14154, 14175, -1, 14162, 14154, 14174, -1, 14175, 14152, 14176, -1, 14154, 14152, 14175, -1, 14176, 14150, 14177, -1, 14152, 14150, 14176, -1, 14177, 14149, 14178, -1, 14150, 14149, 14177, -1, 14178, 14151, 14179, -1, 14149, 14151, 14178, -1, 14179, 14153, 14180, -1, 14151, 14153, 14179, -1, 14180, 14161, 14181, -1, 14153, 14161, 14180, -1, 14172, 14169, 14171, -1, 14171, 14169, 14170, -1, 14169, 14182, 14168, -1, 14172, 14182, 14169, -1, 14182, 14183, 14184, -1, 14182, 14185, 14183, -1, 14172, 14185, 14182, -1, 14173, 14186, 14172, -1, 14172, 14186, 14185, -1, 14179, 14180, 14178, -1, 14178, 14180, 14177, -1, 14174, 14187, 14173, -1, 14173, 14187, 14186, -1, 14175, 14188, 14174, -1, 14174, 14188, 14187, -1, 14181, 14189, 14180, -1, 14180, 14189, 14177, -1, 14176, 14190, 14175, -1, 14175, 14190, 14188, -1, 14177, 14191, 14176, -1, 14189, 14191, 14177, -1, 14176, 14191, 14190, -1, 14192, 14193, 14189, -1, 14189, 14193, 14191, -1, 14161, 14165, 14181, -1, 14181, 14165, 14189, -1, 14189, 14166, 14192, -1, 14165, 14166, 14189, -1, 14192, 14167, 14193, -1, 14166, 14167, 14192, -1, 14193, 14145, 14191, -1, 14167, 14145, 14193, -1, 14191, 14144, 14190, -1, 14145, 14144, 14191, -1, 14190, 14147, 14188, -1, 14144, 14147, 14190, -1, 14188, 14155, 14187, -1, 14147, 14155, 14188, -1, 14187, 14156, 14186, -1, 14155, 14156, 14187, -1, 14186, 14157, 14185, -1, 14156, 14157, 14186, -1, 14185, 14158, 14183, -1, 14157, 14158, 14185, -1, 14183, 14159, 14184, -1, 14158, 14159, 14183, -1, 14184, 14160, 14182, -1, 14159, 14160, 14184, -1, 14182, 14148, 14168, -1, 14160, 14148, 14182, -1, 14194, 11509, 14195, -1, 14195, 11509, 14196, -1, 14196, 11509, 14197, -1, 14197, 11509, 14198, -1, 11510, 11509, 14194, -1, 14199, 14200, 11524, -1, 11509, 14201, 14198, -1, 14200, 14202, 11524, -1, 11509, 14203, 14201, -1, 11511, 14203, 11509, -1, 14202, 14204, 11524, -1, 11511, 11512, 14203, -1, 14205, 14206, 11510, -1, 11510, 14207, 14205, -1, 11512, 11513, 14203, -1, 11513, 11514, 14203, -1, 14206, 14208, 11510, -1, 11514, 11515, 14203, -1, 14203, 11516, 14209, -1, 11510, 14210, 14207, -1, 11510, 14211, 11536, -1, 11536, 14211, 11535, -1, 11535, 14211, 11534, -1, 11534, 14211, 11533, -1, 11515, 11516, 14203, -1, 11533, 14211, 11532, -1, 11532, 14211, 11531, -1, 14209, 11523, 14212, -1, 14212, 11523, 14213, -1, 14213, 11523, 14214, -1, 14214, 11523, 14215, -1, 14215, 11523, 14216, -1, 14216, 11523, 14204, -1, 14208, 14211, 11510, -1, 14204, 11523, 11524, -1, 11516, 11517, 14209, -1, 11510, 14194, 14210, -1, 14209, 11522, 11523, -1, 11531, 14217, 11530, -1, 11530, 14217, 11529, -1, 11529, 14217, 11528, -1, 11528, 14217, 11527, -1, 11527, 14217, 11526, -1, 11517, 11518, 14209, -1, 14211, 14217, 11531, -1, 14209, 11521, 11522, -1, 14217, 11525, 11526, -1, 11518, 11519, 14209, -1, 14209, 11520, 11521, -1, 11519, 11520, 14209, -1, 14217, 11524, 11525, -1, 14218, 11524, 14217, -1, 14218, 14219, 11524, -1, 14219, 14199, 11524, -1, 14204, 14202, 14220, -1, 14220, 14202, 14221, -1, 14221, 14200, 14222, -1, 14202, 14200, 14221, -1, 14222, 14199, 14223, -1, 14200, 14199, 14222, -1, 14223, 14219, 14224, -1, 14199, 14219, 14223, -1, 14224, 14218, 14225, -1, 14219, 14218, 14224, -1, 14225, 14217, 14226, -1, 14218, 14217, 14225, -1, 14226, 14211, 14227, -1, 14217, 14211, 14226, -1, 14227, 14208, 14228, -1, 14211, 14208, 14227, -1, 14228, 14206, 14229, -1, 14208, 14206, 14228, -1, 14229, 14205, 14230, -1, 14206, 14205, 14229, -1, 14230, 14207, 14231, -1, 14205, 14207, 14230, -1, 14231, 14210, 14232, -1, 14207, 14210, 14231, -1, 14232, 14194, 14233, -1, 14210, 14194, 14232, -1, 14224, 14221, 14223, -1, 14223, 14221, 14222, -1, 14221, 14234, 14220, -1, 14224, 14234, 14221, -1, 14234, 14235, 14236, -1, 14234, 14237, 14235, -1, 14224, 14237, 14234, -1, 14225, 14238, 14224, -1, 14224, 14238, 14237, -1, 14231, 14232, 14230, -1, 14230, 14232, 14229, -1, 14226, 14239, 14225, -1, 14225, 14239, 14238, -1, 14227, 14240, 14226, -1, 14226, 14240, 14239, -1, 14233, 14241, 14232, -1, 14232, 14241, 14229, -1, 14228, 14242, 14227, -1, 14227, 14242, 14240, -1, 14229, 14243, 14228, -1, 14241, 14243, 14229, -1, 14228, 14243, 14242, -1, 14244, 14245, 14241, -1, 14241, 14245, 14243, -1, 14194, 14195, 14233, -1, 14233, 14195, 14241, -1, 14241, 14196, 14244, -1, 14195, 14196, 14241, -1, 14244, 14197, 14245, -1, 14196, 14197, 14244, -1, 14245, 14198, 14243, -1, 14197, 14198, 14245, -1, 14243, 14201, 14242, -1, 14198, 14201, 14243, -1, 14242, 14203, 14240, -1, 14201, 14203, 14242, -1, 14240, 14209, 14239, -1, 14203, 14209, 14240, -1, 14239, 14212, 14238, -1, 14209, 14212, 14239, -1, 14238, 14213, 14237, -1, 14212, 14213, 14238, -1, 14237, 14214, 14235, -1, 14213, 14214, 14237, -1, 14235, 14215, 14236, -1, 14214, 14215, 14235, -1, 14236, 14216, 14234, -1, 14215, 14216, 14236, -1, 14234, 14204, 14220, -1, 14216, 14204, 14234, -1, 14246, 11538, 14247, -1, 14247, 11538, 14248, -1, 14248, 11538, 14249, -1, 14249, 11538, 14250, -1, 11537, 11538, 14246, -1, 14251, 14252, 11552, -1, 11538, 14253, 14250, -1, 14252, 14254, 11552, -1, 11538, 14255, 14253, -1, 11539, 14255, 11538, -1, 14254, 14256, 11552, -1, 14257, 14258, 11537, -1, 11539, 11540, 14255, -1, 11537, 14259, 14257, -1, 14258, 14260, 11537, -1, 11540, 11541, 14255, -1, 11537, 14261, 14259, -1, 11537, 14262, 11564, -1, 11541, 11542, 14255, -1, 11564, 14262, 11563, -1, 11563, 14262, 11562, -1, 11562, 14262, 11561, -1, 11561, 14262, 11560, -1, 11560, 14262, 11559, -1, 11542, 11543, 14255, -1, 14255, 11544, 14263, -1, 14260, 14262, 11537, -1, 11543, 11544, 14255, -1, 11537, 14246, 14261, -1, 14263, 11551, 14264, -1, 14264, 11551, 14265, -1, 11559, 14266, 11558, -1, 14265, 11551, 14267, -1, 11558, 14266, 11557, -1, 14267, 11551, 14268, -1, 11557, 14266, 11556, -1, 14268, 11551, 14269, -1, 11556, 14266, 11555, -1, 14256, 11551, 11552, -1, 11555, 14266, 11554, -1, 14269, 11551, 14256, -1, 14262, 14266, 11559, -1, 11544, 11545, 14263, -1, 14266, 11553, 11554, -1, 14263, 11550, 11551, -1, 11545, 11546, 14263, -1, 14263, 11549, 11550, -1, 11546, 11547, 14263, -1, 14263, 11548, 11549, -1, 11547, 11548, 14263, -1, 14266, 11552, 11553, -1, 14270, 11552, 14266, -1, 14270, 14271, 11552, -1, 14271, 14251, 11552, -1, 14256, 14254, 14272, -1, 14272, 14254, 14273, -1, 14273, 14252, 14274, -1, 14254, 14252, 14273, -1, 14274, 14251, 14275, -1, 14252, 14251, 14274, -1, 14275, 14271, 14276, -1, 14251, 14271, 14275, -1, 14276, 14270, 14277, -1, 14271, 14270, 14276, -1, 14277, 14266, 14278, -1, 14270, 14266, 14277, -1, 14278, 14262, 14279, -1, 14266, 14262, 14278, -1, 14279, 14260, 14280, -1, 14262, 14260, 14279, -1, 14280, 14258, 14281, -1, 14260, 14258, 14280, -1, 14281, 14257, 14282, -1, 14258, 14257, 14281, -1, 14282, 14259, 14283, -1, 14257, 14259, 14282, -1, 14283, 14261, 14284, -1, 14259, 14261, 14283, -1, 14284, 14246, 14285, -1, 14261, 14246, 14284, -1, 14276, 14273, 14275, -1, 14275, 14273, 14274, -1, 14273, 14286, 14272, -1, 14276, 14286, 14273, -1, 14286, 14287, 14288, -1, 14286, 14289, 14287, -1, 14276, 14289, 14286, -1, 14277, 14290, 14276, -1, 14276, 14290, 14289, -1, 14283, 14284, 14282, -1, 14282, 14284, 14281, -1, 14278, 14291, 14277, -1, 14277, 14291, 14290, -1, 14279, 14292, 14278, -1, 14278, 14292, 14291, -1, 14285, 14293, 14284, -1, 14284, 14293, 14281, -1, 14280, 14294, 14279, -1, 14279, 14294, 14292, -1, 14281, 14295, 14280, -1, 14293, 14295, 14281, -1, 14280, 14295, 14294, -1, 14296, 14297, 14293, -1, 14293, 14297, 14295, -1, 14246, 14247, 14285, -1, 14285, 14247, 14293, -1, 14293, 14248, 14296, -1, 14247, 14248, 14293, -1, 14296, 14249, 14297, -1, 14248, 14249, 14296, -1, 14297, 14250, 14295, -1, 14249, 14250, 14297, -1, 14295, 14253, 14294, -1, 14250, 14253, 14295, -1, 14294, 14255, 14292, -1, 14253, 14255, 14294, -1, 14292, 14263, 14291, -1, 14255, 14263, 14292, -1, 14291, 14264, 14290, -1, 14263, 14264, 14291, -1, 14290, 14265, 14289, -1, 14264, 14265, 14290, -1, 14289, 14267, 14287, -1, 14265, 14267, 14289, -1, 14287, 14268, 14288, -1, 14267, 14268, 14287, -1, 14288, 14269, 14286, -1, 14268, 14269, 14288, -1, 14286, 14256, 14272, -1, 14269, 14256, 14286, -1, 14298, 11565, 14299, -1, 14299, 11565, 14300, -1, 14300, 11565, 14301, -1, 14301, 11565, 14302, -1, 11566, 11565, 14298, -1, 14303, 14304, 11580, -1, 11565, 14305, 14302, -1, 14304, 14306, 11580, -1, 11565, 14307, 14305, -1, 11567, 14307, 11565, -1, 14306, 14308, 11580, -1, 14309, 14310, 11566, -1, 11567, 11568, 14307, -1, 11566, 14311, 14309, -1, 14310, 14312, 11566, -1, 11568, 11569, 14307, -1, 11566, 14313, 14311, -1, 11566, 14314, 11592, -1, 11569, 11570, 14307, -1, 11592, 14314, 11591, -1, 11591, 14314, 11590, -1, 11590, 14314, 11589, -1, 11589, 14314, 11588, -1, 11588, 14314, 11587, -1, 11570, 11571, 14307, -1, 14307, 11572, 14315, -1, 14312, 14314, 11566, -1, 11571, 11572, 14307, -1, 11566, 14298, 14313, -1, 14315, 11579, 14316, -1, 14316, 11579, 14317, -1, 11587, 14318, 11586, -1, 14317, 11579, 14319, -1, 11586, 14318, 11585, -1, 14319, 11579, 14320, -1, 11585, 14318, 11584, -1, 14320, 11579, 14321, -1, 11584, 14318, 11583, -1, 14308, 11579, 11580, -1, 11583, 14318, 11582, -1, 14321, 11579, 14308, -1, 14314, 14318, 11587, -1, 11572, 11573, 14315, -1, 14318, 11581, 11582, -1, 14315, 11578, 11579, -1, 11573, 11574, 14315, -1, 14315, 11577, 11578, -1, 11574, 11575, 14315, -1, 14315, 11576, 11577, -1, 11575, 11576, 14315, -1, 14318, 11580, 11581, -1, 14322, 11580, 14318, -1, 14322, 14323, 11580, -1, 14323, 14303, 11580, -1, 14308, 14306, 14324, -1, 14324, 14306, 14325, -1, 14325, 14304, 14326, -1, 14306, 14304, 14325, -1, 14326, 14303, 14327, -1, 14304, 14303, 14326, -1, 14327, 14323, 14328, -1, 14303, 14323, 14327, -1, 14328, 14322, 14329, -1, 14323, 14322, 14328, -1, 14329, 14318, 14330, -1, 14322, 14318, 14329, -1, 14330, 14314, 14331, -1, 14318, 14314, 14330, -1, 14331, 14312, 14332, -1, 14314, 14312, 14331, -1, 14332, 14310, 14333, -1, 14312, 14310, 14332, -1, 14333, 14309, 14334, -1, 14310, 14309, 14333, -1, 14334, 14311, 14335, -1, 14309, 14311, 14334, -1, 14335, 14313, 14336, -1, 14311, 14313, 14335, -1, 14336, 14298, 14337, -1, 14313, 14298, 14336, -1, 14328, 14326, 14327, -1, 14326, 14324, 14325, -1, 14326, 14338, 14324, -1, 14326, 14339, 14338, -1, 14339, 14340, 14341, -1, 14328, 14340, 14326, -1, 14326, 14340, 14339, -1, 14334, 14335, 14333, -1, 14329, 14342, 14328, -1, 14328, 14342, 14340, -1, 14330, 14343, 14329, -1, 14329, 14343, 14342, -1, 14331, 14344, 14330, -1, 14330, 14344, 14343, -1, 14337, 14345, 14336, -1, 14336, 14345, 14335, -1, 14332, 14346, 14331, -1, 14331, 14346, 14344, -1, 14345, 14347, 14335, -1, 14333, 14348, 14332, -1, 14335, 14348, 14333, -1, 14332, 14348, 14346, -1, 14347, 14348, 14335, -1, 14347, 14349, 14348, -1, 14298, 14299, 14337, -1, 14337, 14299, 14345, -1, 14345, 14300, 14347, -1, 14299, 14300, 14345, -1, 14347, 14301, 14349, -1, 14300, 14301, 14347, -1, 14349, 14302, 14348, -1, 14301, 14302, 14349, -1, 14348, 14305, 14346, -1, 14302, 14305, 14348, -1, 14346, 14307, 14344, -1, 14305, 14307, 14346, -1, 14344, 14315, 14343, -1, 14307, 14315, 14344, -1, 14343, 14316, 14342, -1, 14315, 14316, 14343, -1, 14342, 14317, 14340, -1, 14316, 14317, 14342, -1, 14340, 14319, 14341, -1, 14317, 14319, 14340, -1, 14341, 14320, 14339, -1, 14319, 14320, 14341, -1, 14339, 14321, 14338, -1, 14320, 14321, 14339, -1, 14338, 14308, 14324, -1, 14321, 14308, 14338, -1, 14350, 11594, 14351, -1, 14351, 11594, 14352, -1, 14352, 11594, 14353, -1, 14353, 11594, 14354, -1, 11593, 11594, 14350, -1, 14355, 14356, 11608, -1, 11594, 14357, 14354, -1, 14356, 14358, 11608, -1, 11595, 14359, 11594, -1, 11594, 14359, 14357, -1, 14358, 14360, 11608, -1, 11595, 11596, 14359, -1, 14361, 14362, 11593, -1, 11593, 14363, 14361, -1, 11596, 11597, 14359, -1, 11597, 11598, 14359, -1, 11598, 11599, 14359, -1, 14362, 14364, 11593, -1, 14359, 11600, 14365, -1, 11599, 11600, 14359, -1, 11593, 14366, 14363, -1, 11593, 14367, 11620, -1, 11620, 14367, 11619, -1, 14365, 11607, 14368, -1, 11619, 14367, 11618, -1, 14368, 11607, 14369, -1, 11618, 14367, 11617, -1, 14369, 11607, 14370, -1, 11617, 14367, 11616, -1, 14370, 11607, 14371, -1, 11616, 14367, 11615, -1, 14371, 11607, 14372, -1, 14372, 11607, 14360, -1, 14360, 11607, 11608, -1, 11600, 11601, 14365, -1, 14364, 14367, 11593, -1, 14365, 11606, 11607, -1, 11593, 14350, 14366, -1, 11601, 11602, 14365, -1, 11615, 14373, 11614, -1, 11614, 14373, 11613, -1, 11613, 14373, 11612, -1, 14365, 11605, 11606, -1, 11612, 14373, 11611, -1, 11611, 14373, 11610, -1, 14367, 14373, 11615, -1, 11602, 11603, 14365, -1, 14373, 11609, 11610, -1, 14365, 11604, 11605, -1, 11603, 11604, 14365, -1, 14373, 11608, 11609, -1, 14374, 11608, 14373, -1, 14374, 14375, 11608, -1, 14375, 14355, 11608, -1, 14360, 14358, 14376, -1, 14376, 14358, 14377, -1, 14377, 14356, 14378, -1, 14358, 14356, 14377, -1, 14378, 14355, 14379, -1, 14356, 14355, 14378, -1, 14379, 14375, 14380, -1, 14355, 14375, 14379, -1, 14380, 14374, 14381, -1, 14375, 14374, 14380, -1, 14381, 14373, 14382, -1, 14374, 14373, 14381, -1, 14382, 14367, 14383, -1, 14373, 14367, 14382, -1, 14383, 14364, 14384, -1, 14367, 14364, 14383, -1, 14384, 14362, 14385, -1, 14364, 14362, 14384, -1, 14385, 14361, 14386, -1, 14362, 14361, 14385, -1, 14386, 14363, 14387, -1, 14361, 14363, 14386, -1, 14387, 14366, 14388, -1, 14363, 14366, 14387, -1, 14388, 14350, 14389, -1, 14366, 14350, 14388, -1, 14380, 14378, 14379, -1, 14378, 14376, 14377, -1, 14378, 14390, 14376, -1, 14378, 14391, 14390, -1, 14391, 14392, 14393, -1, 14380, 14392, 14378, -1, 14378, 14392, 14391, -1, 14386, 14387, 14385, -1, 14381, 14394, 14380, -1, 14380, 14394, 14392, -1, 14382, 14395, 14381, -1, 14381, 14395, 14394, -1, 14383, 14396, 14382, -1, 14382, 14396, 14395, -1, 14389, 14397, 14388, -1, 14388, 14397, 14387, -1, 14384, 14398, 14383, -1, 14383, 14398, 14396, -1, 14397, 14399, 14387, -1, 14385, 14400, 14384, -1, 14387, 14400, 14385, -1, 14384, 14400, 14398, -1, 14399, 14400, 14387, -1, 14399, 14401, 14400, -1, 14350, 14351, 14389, -1, 14389, 14351, 14397, -1, 14397, 14352, 14399, -1, 14351, 14352, 14397, -1, 14399, 14353, 14401, -1, 14352, 14353, 14399, -1, 14401, 14354, 14400, -1, 14353, 14354, 14401, -1, 14400, 14357, 14398, -1, 14354, 14357, 14400, -1, 14398, 14359, 14396, -1, 14357, 14359, 14398, -1, 14396, 14365, 14395, -1, 14359, 14365, 14396, -1, 14395, 14368, 14394, -1, 14365, 14368, 14395, -1, 14394, 14369, 14392, -1, 14368, 14369, 14394, -1, 14392, 14370, 14393, -1, 14369, 14370, 14392, -1, 14393, 14371, 14391, -1, 14370, 14371, 14393, -1, 14391, 14372, 14390, -1, 14371, 14372, 14391, -1, 14390, 14360, 14376, -1, 14372, 14360, 14390, -1, 11622, 11621, 14402, -1, 14403, 14404, 11636, -1, 11621, 14405, 14406, -1, 14404, 14407, 11636, -1, 11621, 14408, 14405, -1, 11623, 14408, 11621, -1, 14407, 14409, 11636, -1, 11623, 11624, 14408, -1, 14410, 14411, 11622, -1, 11624, 11625, 14408, -1, 11622, 14412, 14410, -1, 11625, 11626, 14408, -1, 11626, 11627, 14408, -1, 14408, 11628, 14413, -1, 14411, 14414, 11622, -1, 11627, 11628, 14408, -1, 11622, 14415, 14412, -1, 14413, 11635, 14416, -1, 14416, 11635, 14417, -1, 11622, 14418, 11648, -1, 14417, 11635, 14419, -1, 11648, 14418, 11647, -1, 14419, 11635, 14420, -1, 11647, 14418, 11646, -1, 14420, 11635, 14421, -1, 11646, 14418, 11645, -1, 14421, 11635, 14409, -1, 11645, 14418, 11644, -1, 14409, 11635, 11636, -1, 11644, 14418, 11643, -1, 11628, 11629, 14413, -1, 14414, 14418, 11622, -1, 14413, 11634, 11635, -1, 11629, 11630, 14413, -1, 11622, 14402, 14415, -1, 11643, 14422, 11642, -1, 11642, 14422, 11641, -1, 14413, 11633, 11634, -1, 11641, 14422, 11640, -1, 11640, 14422, 11639, -1, 11639, 14422, 11638, -1, 11630, 11631, 14413, -1, 14418, 14422, 11643, -1, 11631, 11632, 14413, -1, 14413, 11632, 11633, -1, 14422, 11637, 11638, -1, 14422, 11636, 11637, -1, 14423, 11636, 14422, -1, 14423, 14424, 11636, -1, 14424, 14403, 11636, -1, 14402, 11621, 14425, -1, 14425, 11621, 14426, -1, 14426, 11621, 14427, -1, 14427, 11621, 14406, -1, 14409, 14407, 14428, -1, 14428, 14407, 14429, -1, 14429, 14404, 14430, -1, 14407, 14404, 14429, -1, 14430, 14403, 14431, -1, 14404, 14403, 14430, -1, 14431, 14424, 14432, -1, 14403, 14424, 14431, -1, 14432, 14423, 14433, -1, 14424, 14423, 14432, -1, 14433, 14422, 14434, -1, 14423, 14422, 14433, -1, 14434, 14418, 14435, -1, 14422, 14418, 14434, -1, 14435, 14414, 14436, -1, 14418, 14414, 14435, -1, 14436, 14411, 14437, -1, 14414, 14411, 14436, -1, 14437, 14410, 14438, -1, 14411, 14410, 14437, -1, 14438, 14412, 14439, -1, 14410, 14412, 14438, -1, 14439, 14415, 14440, -1, 14412, 14415, 14439, -1, 14440, 14402, 14441, -1, 14415, 14402, 14440, -1, 14432, 14429, 14431, -1, 14431, 14429, 14430, -1, 14429, 14442, 14428, -1, 14432, 14442, 14429, -1, 14442, 14443, 14444, -1, 14442, 14445, 14443, -1, 14432, 14445, 14442, -1, 14433, 14446, 14432, -1, 14432, 14446, 14445, -1, 14439, 14440, 14438, -1, 14438, 14440, 14437, -1, 14434, 14447, 14433, -1, 14433, 14447, 14446, -1, 14435, 14448, 14434, -1, 14434, 14448, 14447, -1, 14441, 14449, 14440, -1, 14440, 14449, 14437, -1, 14436, 14450, 14435, -1, 14435, 14450, 14448, -1, 14437, 14451, 14436, -1, 14449, 14451, 14437, -1, 14436, 14451, 14450, -1, 14452, 14453, 14449, -1, 14449, 14453, 14451, -1, 14402, 14425, 14441, -1, 14441, 14425, 14449, -1, 14449, 14426, 14452, -1, 14425, 14426, 14449, -1, 14452, 14427, 14453, -1, 14426, 14427, 14452, -1, 14453, 14406, 14451, -1, 14427, 14406, 14453, -1, 14451, 14405, 14450, -1, 14406, 14405, 14451, -1, 14450, 14408, 14448, -1, 14405, 14408, 14450, -1, 14448, 14413, 14447, -1, 14408, 14413, 14448, -1, 14447, 14416, 14446, -1, 14413, 14416, 14447, -1, 14446, 14417, 14445, -1, 14416, 14417, 14446, -1, 14445, 14419, 14443, -1, 14417, 14419, 14445, -1, 14443, 14420, 14444, -1, 14419, 14420, 14443, -1, 14444, 14421, 14442, -1, 14420, 14421, 14444, -1, 14442, 14409, 14428, -1, 14421, 14409, 14442, -1, 9314, 9315, 14454, -1, 14455, 14456, 9316, -1, 9315, 14457, 14458, -1, 14456, 14459, 9316, -1, 9315, 14460, 14457, -1, 9330, 14460, 9315, -1, 14459, 14461, 9316, -1, 9330, 9331, 14460, -1, 14462, 14463, 9314, -1, 9314, 14464, 14462, -1, 9331, 9332, 14460, -1, 14463, 14465, 9314, -1, 9332, 9333, 14460, -1, 9314, 14466, 14464, -1, 9323, 14467, 9322, -1, 9333, 9334, 14460, -1, 9324, 14467, 9323, -1, 9325, 14467, 9324, -1, 9326, 14467, 9325, -1, 9327, 14467, 9326, -1, 9328, 14467, 9327, -1, 9314, 14467, 9328, -1, 9334, 9335, 14460, -1, 14465, 14467, 9314, -1, 14461, 9329, 9316, -1, 14468, 9329, 14469, -1, 14469, 9329, 14470, -1, 14470, 9329, 14471, -1, 9314, 14454, 14466, -1, 14471, 9329, 14472, -1, 14472, 9329, 14473, -1, 14473, 9329, 14461, -1, 9319, 14474, 9318, -1, 9320, 14474, 9319, -1, 9321, 14474, 9320, -1, 9322, 14474, 9321, -1, 14460, 9336, 14468, -1, 14467, 14474, 9322, -1, 9335, 9336, 14460, -1, 14468, 9341, 9329, -1, 14474, 9317, 9318, -1, 9336, 9337, 14468, -1, 14468, 9340, 9341, -1, 9337, 9338, 14468, -1, 14468, 9339, 9340, -1, 9338, 9339, 14468, -1, 14474, 9316, 9317, -1, 14475, 9316, 14474, -1, 14475, 14476, 9316, -1, 14476, 14455, 9316, -1, 14454, 9315, 14477, -1, 14477, 9315, 14478, -1, 14478, 9315, 14479, -1, 14479, 9315, 14458, -1, 14461, 14459, 14480, -1, 14480, 14459, 14481, -1, 14481, 14456, 14482, -1, 14459, 14456, 14481, -1, 14482, 14455, 14483, -1, 14456, 14455, 14482, -1, 14483, 14476, 14484, -1, 14455, 14476, 14483, -1, 14484, 14475, 14485, -1, 14476, 14475, 14484, -1, 14485, 14474, 14486, -1, 14475, 14474, 14485, -1, 14486, 14467, 14487, -1, 14474, 14467, 14486, -1, 14487, 14465, 14488, -1, 14467, 14465, 14487, -1, 14488, 14463, 14489, -1, 14465, 14463, 14488, -1, 14489, 14462, 14490, -1, 14463, 14462, 14489, -1, 14490, 14464, 14491, -1, 14462, 14464, 14490, -1, 14491, 14466, 14492, -1, 14464, 14466, 14491, -1, 14492, 14454, 14493, -1, 14466, 14454, 14492, -1, 14484, 14485, 14483, -1, 14486, 14487, 14485, -1, 14487, 14488, 14485, -1, 14489, 14490, 14488, -1, 14485, 14490, 14483, -1, 14488, 14490, 14485, -1, 14483, 14491, 14482, -1, 14490, 14491, 14483, -1, 14494, 14495, 14496, -1, 14482, 14492, 14481, -1, 14491, 14492, 14482, -1, 14481, 14493, 14480, -1, 14492, 14493, 14481, -1, 14480, 14497, 14498, -1, 14493, 14497, 14480, -1, 14495, 14499, 14500, -1, 14500, 14499, 14501, -1, 14498, 14502, 14503, -1, 14497, 14502, 14498, -1, 14503, 14504, 14494, -1, 14499, 14504, 14505, -1, 14502, 14504, 14503, -1, 14494, 14504, 14495, -1, 14495, 14504, 14499, -1, 14454, 14477, 14493, -1, 14493, 14477, 14497, -1, 14497, 14478, 14502, -1, 14477, 14478, 14497, -1, 14502, 14479, 14504, -1, 14478, 14479, 14502, -1, 14504, 14458, 14505, -1, 14479, 14458, 14504, -1, 14505, 14457, 14499, -1, 14458, 14457, 14505, -1, 14499, 14460, 14501, -1, 14457, 14460, 14499, -1, 14501, 14468, 14500, -1, 14460, 14468, 14501, -1, 14500, 14469, 14495, -1, 14468, 14469, 14500, -1, 14495, 14470, 14496, -1, 14469, 14470, 14495, -1, 14496, 14471, 14494, -1, 14470, 14471, 14496, -1, 14494, 14472, 14503, -1, 14471, 14472, 14494, -1, 14503, 14473, 14498, -1, 14472, 14473, 14503, -1, 14498, 14461, 14480, -1, 14473, 14461, 14498, -1, 9342, 14506, 14507, -1, 14508, 14509, 9344, -1, 9342, 14510, 14506, -1, 9358, 14510, 9342, -1, 14509, 14511, 9344, -1, 9358, 9359, 14510, -1, 14512, 14513, 9343, -1, 9359, 9360, 14510, -1, 9343, 14514, 14512, -1, 9360, 9361, 14510, -1, 9361, 9362, 14510, -1, 14513, 14515, 9343, -1, 9362, 9363, 14510, -1, 9343, 14516, 14514, -1, 14517, 9357, 14518, -1, 14518, 9357, 14519, -1, 14519, 9357, 14520, -1, 14520, 9357, 14521, -1, 14521, 9357, 14522, -1, 14522, 9357, 14511, -1, 9351, 14523, 9350, -1, 14511, 9357, 9344, -1, 9352, 14523, 9351, -1, 9353, 14523, 9352, -1, 9354, 14523, 9353, -1, 9355, 14523, 9354, -1, 14510, 9364, 14517, -1, 9356, 14523, 9355, -1, 9343, 14523, 9356, -1, 9363, 9364, 14510, -1, 14515, 14523, 9343, -1, 14517, 9369, 9357, -1, 9364, 9365, 14517, -1, 9343, 14524, 14516, -1, 14517, 9368, 9369, -1, 9347, 14525, 9346, -1, 9348, 14525, 9347, -1, 9349, 14525, 9348, -1, 9350, 14525, 9349, -1, 14523, 14525, 9350, -1, 9365, 9366, 14517, -1, 9366, 9367, 14517, -1, 14517, 9367, 9368, -1, 14525, 9345, 9346, -1, 14525, 9344, 9345, -1, 14526, 9344, 14525, -1, 14526, 14527, 9344, -1, 14527, 14528, 9344, -1, 14524, 9342, 14529, -1, 14529, 9342, 14530, -1, 14530, 9342, 14531, -1, 14531, 9342, 14507, -1, 9343, 9342, 14524, -1, 14528, 14508, 9344, -1, 14511, 14509, 14532, -1, 14532, 14509, 14533, -1, 14533, 14508, 14534, -1, 14509, 14508, 14533, -1, 14534, 14528, 14535, -1, 14508, 14528, 14534, -1, 14535, 14527, 14536, -1, 14528, 14527, 14535, -1, 14536, 14526, 14537, -1, 14527, 14526, 14536, -1, 14537, 14525, 14538, -1, 14526, 14525, 14537, -1, 14538, 14523, 14539, -1, 14525, 14523, 14538, -1, 14539, 14515, 14540, -1, 14523, 14515, 14539, -1, 14540, 14513, 14541, -1, 14515, 14513, 14540, -1, 14541, 14512, 14542, -1, 14513, 14512, 14541, -1, 14542, 14514, 14543, -1, 14512, 14514, 14542, -1, 14543, 14516, 14544, -1, 14514, 14516, 14543, -1, 14544, 14524, 14545, -1, 14516, 14524, 14544, -1, 14536, 14534, 14535, -1, 14536, 14533, 14534, -1, 14533, 14546, 14532, -1, 14546, 14547, 14548, -1, 14548, 14547, 14549, -1, 14542, 14543, 14541, -1, 14537, 14550, 14536, -1, 14533, 14550, 14546, -1, 14536, 14550, 14533, -1, 14546, 14550, 14547, -1, 14543, 14544, 14541, -1, 14538, 14551, 14537, -1, 14537, 14551, 14550, -1, 14539, 14552, 14538, -1, 14538, 14552, 14551, -1, 14545, 14553, 14544, -1, 14540, 14554, 14539, -1, 14539, 14554, 14552, -1, 14541, 14555, 14540, -1, 14556, 14555, 14553, -1, 14544, 14555, 14541, -1, 14553, 14555, 14544, -1, 14540, 14555, 14554, -1, 14556, 14557, 14555, -1, 14524, 14529, 14545, -1, 14545, 14529, 14553, -1, 14553, 14530, 14556, -1, 14529, 14530, 14553, -1, 14556, 14531, 14557, -1, 14530, 14531, 14556, -1, 14557, 14507, 14555, -1, 14531, 14507, 14557, -1, 14555, 14506, 14554, -1, 14507, 14506, 14555, -1, 14554, 14510, 14552, -1, 14506, 14510, 14554, -1, 14552, 14517, 14551, -1, 14510, 14517, 14552, -1, 14551, 14518, 14550, -1, 14517, 14518, 14551, -1, 14550, 14519, 14547, -1, 14518, 14519, 14550, -1, 14547, 14520, 14549, -1, 14519, 14520, 14547, -1, 14549, 14521, 14548, -1, 14520, 14521, 14549, -1, 14548, 14522, 14546, -1, 14521, 14522, 14548, -1, 14546, 14511, 14532, -1, 14522, 14511, 14546, -1, 14558, 9371, 14559, -1, 14559, 9371, 14560, -1, 14560, 9371, 14561, -1, 14561, 9371, 14562, -1, 9370, 9371, 14558, -1, 14563, 14564, 9372, -1, 9371, 14565, 14562, -1, 14564, 14566, 9372, -1, 9371, 14567, 14565, -1, 9386, 14567, 9371, -1, 14566, 14568, 9372, -1, 9386, 9387, 14567, -1, 14569, 14570, 9370, -1, 9387, 9388, 14567, -1, 9370, 14571, 14569, -1, 9388, 9389, 14567, -1, 9389, 9390, 14567, -1, 14570, 14572, 9370, -1, 9390, 9391, 14567, -1, 9370, 14573, 14571, -1, 14574, 9385, 14575, -1, 14575, 9385, 14576, -1, 14576, 9385, 14577, -1, 14577, 9385, 14578, -1, 14578, 9385, 14579, -1, 14579, 9385, 14568, -1, 14568, 9385, 9372, -1, 9379, 14580, 9378, -1, 9380, 14580, 9379, -1, 9381, 14580, 9380, -1, 9382, 14580, 9381, -1, 14567, 9392, 14574, -1, 9383, 14580, 9382, -1, 9384, 14580, 9383, -1, 9391, 9392, 14567, -1, 9370, 14580, 9384, -1, 14574, 9397, 9385, -1, 14572, 14580, 9370, -1, 9392, 9393, 14574, -1, 9370, 14558, 14573, -1, 9375, 14581, 9374, -1, 14574, 9396, 9397, -1, 9376, 14581, 9375, -1, 9377, 14581, 9376, -1, 9378, 14581, 9377, -1, 14580, 14581, 9378, -1, 9393, 9394, 14574, -1, 9394, 9395, 14574, -1, 14574, 9395, 9396, -1, 14581, 9373, 9374, -1, 14581, 9372, 9373, -1, 14582, 9372, 14581, -1, 14582, 14583, 9372, -1, 14583, 14563, 9372, -1, 14568, 14566, 14584, -1, 14584, 14566, 14585, -1, 14585, 14564, 14586, -1, 14566, 14564, 14585, -1, 14586, 14563, 14587, -1, 14564, 14563, 14586, -1, 14587, 14583, 14588, -1, 14563, 14583, 14587, -1, 14588, 14582, 14589, -1, 14583, 14582, 14588, -1, 14589, 14581, 14590, -1, 14582, 14581, 14589, -1, 14590, 14580, 14591, -1, 14581, 14580, 14590, -1, 14591, 14572, 14592, -1, 14580, 14572, 14591, -1, 14592, 14570, 14593, -1, 14572, 14570, 14592, -1, 14593, 14569, 14594, -1, 14570, 14569, 14593, -1, 14594, 14571, 14595, -1, 14569, 14571, 14594, -1, 14595, 14573, 14596, -1, 14571, 14573, 14595, -1, 14596, 14558, 14597, -1, 14573, 14558, 14596, -1, 14588, 14586, 14587, -1, 14588, 14585, 14586, -1, 14585, 14598, 14584, -1, 14589, 14599, 14588, -1, 14598, 14599, 14600, -1, 14600, 14599, 14601, -1, 14588, 14599, 14585, -1, 14585, 14599, 14598, -1, 14594, 14595, 14593, -1, 14589, 14602, 14599, -1, 14595, 14596, 14593, -1, 14590, 14603, 14589, -1, 14589, 14603, 14602, -1, 14591, 14604, 14590, -1, 14590, 14604, 14603, -1, 14597, 14605, 14596, -1, 14593, 14606, 14592, -1, 14592, 14606, 14591, -1, 14591, 14606, 14604, -1, 14596, 14607, 14593, -1, 14605, 14607, 14596, -1, 14593, 14607, 14606, -1, 14608, 14609, 14605, -1, 14605, 14609, 14607, -1, 14558, 14559, 14597, -1, 14597, 14559, 14605, -1, 14605, 14560, 14608, -1, 14559, 14560, 14605, -1, 14608, 14561, 14609, -1, 14560, 14561, 14608, -1, 14609, 14562, 14607, -1, 14561, 14562, 14609, -1, 14607, 14565, 14606, -1, 14562, 14565, 14607, -1, 14606, 14567, 14604, -1, 14565, 14567, 14606, -1, 14604, 14574, 14603, -1, 14567, 14574, 14604, -1, 14603, 14575, 14602, -1, 14574, 14575, 14603, -1, 14602, 14576, 14599, -1, 14575, 14576, 14602, -1, 14599, 14577, 14601, -1, 14576, 14577, 14599, -1, 14601, 14578, 14600, -1, 14577, 14578, 14601, -1, 14600, 14579, 14598, -1, 14578, 14579, 14600, -1, 14598, 14568, 14584, -1, 14579, 14568, 14598, -1, 9398, 9399, 14610, -1, 14611, 14612, 9400, -1, 9399, 14613, 14614, -1, 14612, 14615, 9400, -1, 9399, 14616, 14613, -1, 9414, 14616, 9399, -1, 14615, 14617, 9400, -1, 9414, 9415, 14616, -1, 14618, 14619, 9398, -1, 9415, 9416, 14616, -1, 9398, 14620, 14618, -1, 9416, 9417, 14616, -1, 9417, 9418, 14616, -1, 14619, 14621, 9398, -1, 9418, 9419, 14616, -1, 9398, 14622, 14620, -1, 14623, 9413, 14624, -1, 14624, 9413, 14625, -1, 14625, 9413, 14626, -1, 14626, 9413, 14627, -1, 14627, 9413, 14628, -1, 14628, 9413, 14617, -1, 14617, 9413, 9400, -1, 9407, 14629, 9406, -1, 9408, 14629, 9407, -1, 9409, 14629, 9408, -1, 14616, 9420, 14623, -1, 9410, 14629, 9409, -1, 9411, 14629, 9410, -1, 9419, 9420, 14616, -1, 9412, 14629, 9411, -1, 9398, 14629, 9412, -1, 14623, 9425, 9413, -1, 14621, 14629, 9398, -1, 9420, 9421, 14623, -1, 9398, 14610, 14622, -1, 14623, 9424, 9425, -1, 9403, 14630, 9402, -1, 9404, 14630, 9403, -1, 9405, 14630, 9404, -1, 9406, 14630, 9405, -1, 14629, 14630, 9406, -1, 9421, 9422, 14623, -1, 9422, 9423, 14623, -1, 14623, 9423, 9424, -1, 14630, 9401, 9402, -1, 14630, 9400, 9401, -1, 14631, 9400, 14630, -1, 14631, 14632, 9400, -1, 14632, 14611, 9400, -1, 14610, 9399, 14633, -1, 14633, 9399, 14634, -1, 14634, 9399, 14635, -1, 14635, 9399, 14614, -1, 14617, 14615, 14636, -1, 14636, 14615, 14637, -1, 14637, 14612, 14638, -1, 14615, 14612, 14637, -1, 14638, 14611, 14639, -1, 14612, 14611, 14638, -1, 14639, 14632, 14640, -1, 14611, 14632, 14639, -1, 14640, 14631, 14641, -1, 14632, 14631, 14640, -1, 14641, 14630, 14642, -1, 14631, 14630, 14641, -1, 14642, 14629, 14643, -1, 14630, 14629, 14642, -1, 14643, 14621, 14644, -1, 14629, 14621, 14643, -1, 14644, 14619, 14645, -1, 14621, 14619, 14644, -1, 14645, 14618, 14646, -1, 14619, 14618, 14645, -1, 14646, 14620, 14647, -1, 14618, 14620, 14646, -1, 14647, 14622, 14648, -1, 14620, 14622, 14647, -1, 14648, 14610, 14649, -1, 14622, 14610, 14648, -1, 14640, 14638, 14639, -1, 14640, 14637, 14638, -1, 14637, 14650, 14636, -1, 14641, 14651, 14640, -1, 14650, 14651, 14652, -1, 14652, 14651, 14653, -1, 14640, 14651, 14637, -1, 14637, 14651, 14650, -1, 14646, 14647, 14645, -1, 14641, 14654, 14651, -1, 14647, 14648, 14645, -1, 14642, 14655, 14641, -1, 14641, 14655, 14654, -1, 14643, 14656, 14642, -1, 14642, 14656, 14655, -1, 14649, 14657, 14648, -1, 14645, 14658, 14644, -1, 14644, 14658, 14643, -1, 14643, 14658, 14656, -1, 14648, 14659, 14645, -1, 14657, 14659, 14648, -1, 14645, 14659, 14658, -1, 14660, 14661, 14657, -1, 14657, 14661, 14659, -1, 14610, 14633, 14649, -1, 14649, 14633, 14657, -1, 14657, 14634, 14660, -1, 14633, 14634, 14657, -1, 14660, 14635, 14661, -1, 14634, 14635, 14660, -1, 14661, 14614, 14659, -1, 14635, 14614, 14661, -1, 14659, 14613, 14658, -1, 14614, 14613, 14659, -1, 14658, 14616, 14656, -1, 14613, 14616, 14658, -1, 14656, 14623, 14655, -1, 14616, 14623, 14656, -1, 14655, 14624, 14654, -1, 14623, 14624, 14655, -1, 14654, 14625, 14651, -1, 14624, 14625, 14654, -1, 14651, 14626, 14653, -1, 14625, 14626, 14651, -1, 14653, 14627, 14652, -1, 14626, 14627, 14653, -1, 14652, 14628, 14650, -1, 14627, 14628, 14652, -1, 14650, 14617, 14636, -1, 14628, 14617, 14650, -1, 14662, 9428, 14663, -1, 14663, 9428, 14664, -1, 9441, 9428, 14665, -1, 14666, 14667, 9426, -1, 9428, 14668, 14664, -1, 14667, 14669, 9426, -1, 9429, 14670, 9428, -1, 9428, 14670, 14668, -1, 14669, 14671, 9426, -1, 9429, 9430, 14670, -1, 14672, 14673, 9441, -1, 9430, 9431, 14670, -1, 9441, 14674, 14672, -1, 9431, 9432, 14670, -1, 9432, 9433, 14670, -1, 14673, 14675, 9441, -1, 9433, 9434, 14670, -1, 9441, 14676, 14674, -1, 14677, 9427, 14678, -1, 14678, 9427, 14679, -1, 14679, 9427, 14680, -1, 14680, 9427, 14681, -1, 9448, 14682, 9447, -1, 14681, 9427, 14683, -1, 9449, 14682, 9448, -1, 14683, 9427, 14671, -1, 9450, 14682, 9449, -1, 14671, 9427, 9426, -1, 9451, 14682, 9450, -1, 9452, 14682, 9451, -1, 9453, 14682, 9452, -1, 9441, 14682, 9453, -1, 14670, 9435, 14677, -1, 14675, 14682, 9441, -1, 9434, 9435, 14670, -1, 14677, 9440, 9427, -1, 9441, 14665, 14676, -1, 9435, 9436, 14677, -1, 9444, 14684, 9443, -1, 9445, 14684, 9444, -1, 9446, 14684, 9445, -1, 14677, 9439, 9440, -1, 9447, 14684, 9446, -1, 14682, 14684, 9447, -1, 9436, 9437, 14677, -1, 14684, 9442, 9443, -1, 9437, 9438, 14677, -1, 14677, 9438, 9439, -1, 14684, 9426, 9442, -1, 14685, 9426, 14684, -1, 14685, 14686, 9426, -1, 14686, 14666, 9426, -1, 14665, 9428, 14687, -1, 14687, 9428, 14662, -1, 14671, 14669, 14688, -1, 14688, 14669, 14689, -1, 14689, 14667, 14690, -1, 14669, 14667, 14689, -1, 14690, 14666, 14691, -1, 14667, 14666, 14690, -1, 14691, 14686, 14692, -1, 14666, 14686, 14691, -1, 14692, 14685, 14693, -1, 14686, 14685, 14692, -1, 14693, 14684, 14694, -1, 14685, 14684, 14693, -1, 14694, 14682, 14695, -1, 14684, 14682, 14694, -1, 14695, 14675, 14696, -1, 14682, 14675, 14695, -1, 14696, 14673, 14697, -1, 14675, 14673, 14696, -1, 14697, 14672, 14698, -1, 14673, 14672, 14697, -1, 14698, 14674, 14699, -1, 14672, 14674, 14698, -1, 14699, 14676, 14700, -1, 14674, 14676, 14699, -1, 14700, 14665, 14701, -1, 14676, 14665, 14700, -1, 14692, 14690, 14691, -1, 14692, 14689, 14690, -1, 14689, 14702, 14688, -1, 14693, 14703, 14692, -1, 14702, 14703, 14704, -1, 14704, 14703, 14705, -1, 14692, 14703, 14689, -1, 14689, 14703, 14702, -1, 14698, 14699, 14697, -1, 14693, 14706, 14703, -1, 14699, 14700, 14697, -1, 14694, 14707, 14693, -1, 14693, 14707, 14706, -1, 14695, 14708, 14694, -1, 14694, 14708, 14707, -1, 14701, 14709, 14700, -1, 14697, 14710, 14696, -1, 14696, 14710, 14695, -1, 14695, 14710, 14708, -1, 14700, 14711, 14697, -1, 14709, 14711, 14700, -1, 14697, 14711, 14710, -1, 14712, 14713, 14709, -1, 14709, 14713, 14711, -1, 14665, 14687, 14701, -1, 14701, 14687, 14709, -1, 14709, 14662, 14712, -1, 14687, 14662, 14709, -1, 14712, 14663, 14713, -1, 14662, 14663, 14712, -1, 14713, 14664, 14711, -1, 14663, 14664, 14713, -1, 14711, 14668, 14710, -1, 14664, 14668, 14711, -1, 14710, 14670, 14708, -1, 14668, 14670, 14710, -1, 14708, 14677, 14707, -1, 14670, 14677, 14708, -1, 14707, 14678, 14706, -1, 14677, 14678, 14707, -1, 14706, 14679, 14703, -1, 14678, 14679, 14706, -1, 14703, 14680, 14705, -1, 14679, 14680, 14703, -1, 14705, 14681, 14704, -1, 14680, 14681, 14705, -1, 14704, 14683, 14702, -1, 14681, 14683, 14704, -1, 14702, 14671, 14688, -1, 14683, 14671, 14702, -1, 14714, 9456, 14715, -1, 14715, 9456, 14716, -1, 14716, 9456, 14717, -1, 14717, 9456, 14718, -1, 9469, 9456, 14714, -1, 14719, 14720, 9454, -1, 9456, 14721, 14718, -1, 14720, 14722, 9454, -1, 9457, 14723, 9456, -1, 9456, 14723, 14721, -1, 14722, 14724, 9454, -1, 9457, 9458, 14723, -1, 14725, 14726, 9469, -1, 9469, 14727, 14725, -1, 9458, 9459, 14723, -1, 9459, 9460, 14723, -1, 9460, 9461, 14723, -1, 14726, 14728, 9469, -1, 9461, 9462, 14723, -1, 9469, 14729, 14727, -1, 14730, 9455, 14731, -1, 14731, 9455, 14732, -1, 14732, 9455, 14733, -1, 14733, 9455, 14734, -1, 9477, 14735, 9476, -1, 14734, 9455, 14736, -1, 9478, 14735, 9477, -1, 14736, 9455, 14724, -1, 9479, 14735, 9478, -1, 14724, 9455, 9454, -1, 9480, 14735, 9479, -1, 9481, 14735, 9480, -1, 9469, 14735, 9481, -1, 14728, 14735, 9469, -1, 14723, 9463, 14730, -1, 9462, 9463, 14723, -1, 14730, 9468, 9455, -1, 9469, 14714, 14729, -1, 9463, 9464, 14730, -1, 9472, 14737, 9471, -1, 9473, 14737, 9472, -1, 9474, 14737, 9473, -1, 9475, 14737, 9474, -1, 14730, 9467, 9468, -1, 9476, 14737, 9475, -1, 14735, 14737, 9476, -1, 9464, 9465, 14730, -1, 14737, 9470, 9471, -1, 9465, 9466, 14730, -1, 14730, 9466, 9467, -1, 14737, 9454, 9470, -1, 14738, 9454, 14737, -1, 14738, 14739, 9454, -1, 14739, 14719, 9454, -1, 14724, 14722, 14740, -1, 14740, 14722, 14741, -1, 14741, 14720, 14742, -1, 14722, 14720, 14741, -1, 14742, 14719, 14743, -1, 14720, 14719, 14742, -1, 14743, 14739, 14744, -1, 14719, 14739, 14743, -1, 14744, 14738, 14745, -1, 14739, 14738, 14744, -1, 14745, 14737, 14746, -1, 14738, 14737, 14745, -1, 14746, 14735, 14747, -1, 14737, 14735, 14746, -1, 14747, 14728, 14748, -1, 14735, 14728, 14747, -1, 14748, 14726, 14749, -1, 14728, 14726, 14748, -1, 14749, 14725, 14750, -1, 14726, 14725, 14749, -1, 14750, 14727, 14751, -1, 14725, 14727, 14750, -1, 14751, 14729, 14752, -1, 14727, 14729, 14751, -1, 14752, 14714, 14753, -1, 14729, 14714, 14752, -1, 14744, 14742, 14743, -1, 14744, 14741, 14742, -1, 14741, 14754, 14740, -1, 14745, 14755, 14744, -1, 14754, 14755, 14756, -1, 14756, 14755, 14757, -1, 14744, 14755, 14741, -1, 14741, 14755, 14754, -1, 14750, 14751, 14749, -1, 14745, 14758, 14755, -1, 14751, 14752, 14749, -1, 14746, 14759, 14745, -1, 14745, 14759, 14758, -1, 14747, 14760, 14746, -1, 14746, 14760, 14759, -1, 14753, 14761, 14752, -1, 14749, 14762, 14748, -1, 14748, 14762, 14747, -1, 14747, 14762, 14760, -1, 14752, 14763, 14749, -1, 14761, 14763, 14752, -1, 14749, 14763, 14762, -1, 14764, 14765, 14761, -1, 14761, 14765, 14763, -1, 14714, 14715, 14753, -1, 14753, 14715, 14761, -1, 14761, 14716, 14764, -1, 14715, 14716, 14761, -1, 14764, 14717, 14765, -1, 14716, 14717, 14764, -1, 14765, 14718, 14763, -1, 14717, 14718, 14765, -1, 14763, 14721, 14762, -1, 14718, 14721, 14763, -1, 14762, 14723, 14760, -1, 14721, 14723, 14762, -1, 14760, 14730, 14759, -1, 14723, 14730, 14760, -1, 14759, 14731, 14758, -1, 14730, 14731, 14759, -1, 14758, 14732, 14755, -1, 14731, 14732, 14758, -1, 14755, 14733, 14757, -1, 14732, 14733, 14755, -1, 14757, 14734, 14756, -1, 14733, 14734, 14757, -1, 14756, 14736, 14754, -1, 14734, 14736, 14756, -1, 14754, 14724, 14740, -1, 14736, 14724, 14754, -1, 9497, 9484, 14766, -1, 14767, 14768, 9483, -1, 9484, 14769, 14770, -1, 14768, 14771, 9483, -1, 9485, 14772, 9484, -1, 9484, 14772, 14769, -1, 14771, 14773, 9483, -1, 9485, 9486, 14772, -1, 14774, 14775, 9497, -1, 9486, 9487, 14772, -1, 9497, 14776, 14774, -1, 9487, 9488, 14772, -1, 9488, 9489, 14772, -1, 14775, 14777, 9497, -1, 9489, 9490, 14772, -1, 9497, 14778, 14776, -1, 14779, 9482, 14780, -1, 14780, 9482, 14781, -1, 14781, 9482, 14782, -1, 14782, 9482, 14783, -1, 9504, 14784, 9503, -1, 14783, 9482, 14785, -1, 9505, 14784, 9504, -1, 14785, 9482, 14773, -1, 9506, 14784, 9505, -1, 14773, 9482, 9483, -1, 9507, 14784, 9506, -1, 9508, 14784, 9507, -1, 9509, 14784, 9508, -1, 9497, 14784, 9509, -1, 14772, 9491, 14779, -1, 14777, 14784, 9497, -1, 9490, 9491, 14772, -1, 14779, 9496, 9482, -1, 9497, 14766, 14778, -1, 9491, 9492, 14779, -1, 9500, 14786, 9499, -1, 9501, 14786, 9500, -1, 9502, 14786, 9501, -1, 14779, 9495, 9496, -1, 9503, 14786, 9502, -1, 14784, 14786, 9503, -1, 9492, 9493, 14779, -1, 14786, 9498, 9499, -1, 9493, 9494, 14779, -1, 14779, 9494, 9495, -1, 14786, 9483, 9498, -1, 14787, 9483, 14786, -1, 14787, 14788, 9483, -1, 14788, 14767, 9483, -1, 14766, 9484, 14789, -1, 14789, 9484, 14790, -1, 14790, 9484, 14791, -1, 14791, 9484, 14770, -1, 14773, 14771, 14792, -1, 14792, 14771, 14793, -1, 14793, 14768, 14794, -1, 14771, 14768, 14793, -1, 14794, 14767, 14795, -1, 14768, 14767, 14794, -1, 14795, 14788, 14796, -1, 14767, 14788, 14795, -1, 14796, 14787, 14797, -1, 14788, 14787, 14796, -1, 14797, 14786, 14798, -1, 14787, 14786, 14797, -1, 14798, 14784, 14799, -1, 14786, 14784, 14798, -1, 14799, 14777, 14800, -1, 14784, 14777, 14799, -1, 14800, 14775, 14801, -1, 14777, 14775, 14800, -1, 14801, 14774, 14802, -1, 14775, 14774, 14801, -1, 14802, 14776, 14803, -1, 14774, 14776, 14802, -1, 14803, 14778, 14804, -1, 14776, 14778, 14803, -1, 14804, 14766, 14805, -1, 14778, 14766, 14804, -1, 14796, 14794, 14795, -1, 14793, 14806, 14792, -1, 14794, 14807, 14793, -1, 14793, 14807, 14806, -1, 14800, 14801, 14799, -1, 14797, 14808, 14796, -1, 14807, 14808, 14809, -1, 14796, 14808, 14794, -1, 14794, 14808, 14807, -1, 14802, 14803, 14801, -1, 14798, 14810, 14797, -1, 14808, 14810, 14811, -1, 14797, 14810, 14808, -1, 14799, 14812, 14798, -1, 14798, 14812, 14810, -1, 14805, 14813, 14804, -1, 14801, 14814, 14799, -1, 14799, 14814, 14812, -1, 14804, 14815, 14803, -1, 14813, 14815, 14804, -1, 14801, 14816, 14814, -1, 14803, 14816, 14801, -1, 14815, 14816, 14803, -1, 14815, 14817, 14816, -1, 14766, 14789, 14805, -1, 14805, 14789, 14813, -1, 14813, 14790, 14815, -1, 14789, 14790, 14813, -1, 14815, 14791, 14817, -1, 14790, 14791, 14815, -1, 14817, 14770, 14816, -1, 14791, 14770, 14817, -1, 14816, 14769, 14814, -1, 14770, 14769, 14816, -1, 14814, 14772, 14812, -1, 14769, 14772, 14814, -1, 14812, 14779, 14810, -1, 14772, 14779, 14812, -1, 14810, 14780, 14811, -1, 14779, 14780, 14810, -1, 14811, 14781, 14808, -1, 14780, 14781, 14811, -1, 14808, 14782, 14809, -1, 14781, 14782, 14808, -1, 14809, 14783, 14807, -1, 14782, 14783, 14809, -1, 14807, 14785, 14806, -1, 14783, 14785, 14807, -1, 14806, 14773, 14792, -1, 14785, 14773, 14806, -1, 14818, 9512, 14819, -1, 14819, 9512, 14820, -1, 14820, 9512, 14821, -1, 14821, 9512, 14822, -1, 9525, 9512, 14818, -1, 14823, 14824, 9511, -1, 9512, 14825, 14822, -1, 14824, 14826, 9511, -1, 9513, 14827, 9512, -1, 9512, 14827, 14825, -1, 14826, 14828, 9511, -1, 9513, 9514, 14827, -1, 14829, 14830, 9525, -1, 9525, 14831, 14829, -1, 9514, 9515, 14827, -1, 14830, 14832, 9525, -1, 9515, 9516, 14827, -1, 9525, 14833, 14831, -1, 9516, 9517, 14827, -1, 9532, 14834, 9531, -1, 9533, 14834, 9532, -1, 9534, 14834, 9533, -1, 9535, 14834, 9534, -1, 9536, 14834, 9535, -1, 9537, 14834, 9536, -1, 9525, 14834, 9537, -1, 14832, 14834, 9525, -1, 9517, 9518, 14827, -1, 14835, 9510, 14836, -1, 14836, 9510, 14837, -1, 14837, 9510, 14838, -1, 14838, 9510, 14839, -1, 14839, 9510, 14840, -1, 9525, 14818, 14833, -1, 14828, 9510, 9511, -1, 14840, 9510, 14828, -1, 9528, 14841, 9527, -1, 9529, 14841, 9528, -1, 9530, 14841, 9529, -1, 14827, 9519, 14835, -1, 9531, 14841, 9530, -1, 14834, 14841, 9531, -1, 9518, 9519, 14827, -1, 14835, 9524, 9510, -1, 14841, 9526, 9527, -1, 9519, 9520, 14835, -1, 14835, 9523, 9524, -1, 9520, 9521, 14835, -1, 9521, 9522, 14835, -1, 14835, 9522, 9523, -1, 14841, 9511, 9526, -1, 14842, 9511, 14841, -1, 14842, 14843, 9511, -1, 14843, 14823, 9511, -1, 14828, 14826, 14844, -1, 14844, 14826, 14845, -1, 14845, 14824, 14846, -1, 14826, 14824, 14845, -1, 14846, 14823, 14847, -1, 14824, 14823, 14846, -1, 14847, 14843, 14848, -1, 14823, 14843, 14847, -1, 14848, 14842, 14849, -1, 14843, 14842, 14848, -1, 14849, 14841, 14850, -1, 14842, 14841, 14849, -1, 14850, 14834, 14851, -1, 14841, 14834, 14850, -1, 14851, 14832, 14852, -1, 14834, 14832, 14851, -1, 14852, 14830, 14853, -1, 14832, 14830, 14852, -1, 14853, 14829, 14854, -1, 14830, 14829, 14853, -1, 14854, 14831, 14855, -1, 14829, 14831, 14854, -1, 14855, 14833, 14856, -1, 14831, 14833, 14855, -1, 14856, 14818, 14857, -1, 14833, 14818, 14856, -1, 14848, 14846, 14847, -1, 14845, 14858, 14844, -1, 14846, 14859, 14845, -1, 14845, 14859, 14858, -1, 14852, 14853, 14851, -1, 14849, 14860, 14848, -1, 14859, 14860, 14861, -1, 14848, 14860, 14846, -1, 14846, 14860, 14859, -1, 14854, 14855, 14853, -1, 14850, 14862, 14849, -1, 14860, 14862, 14863, -1, 14849, 14862, 14860, -1, 14851, 14864, 14850, -1, 14850, 14864, 14862, -1, 14857, 14865, 14856, -1, 14853, 14866, 14851, -1, 14851, 14866, 14864, -1, 14856, 14867, 14855, -1, 14865, 14867, 14856, -1, 14855, 14868, 14853, -1, 14853, 14868, 14866, -1, 14867, 14868, 14855, -1, 14867, 14869, 14868, -1, 14818, 14819, 14857, -1, 14857, 14819, 14865, -1, 14865, 14820, 14867, -1, 14819, 14820, 14865, -1, 14867, 14821, 14869, -1, 14820, 14821, 14867, -1, 14869, 14822, 14868, -1, 14821, 14822, 14869, -1, 14868, 14825, 14866, -1, 14822, 14825, 14868, -1, 14866, 14827, 14864, -1, 14825, 14827, 14866, -1, 14864, 14835, 14862, -1, 14827, 14835, 14864, -1, 14862, 14836, 14863, -1, 14835, 14836, 14862, -1, 14863, 14837, 14860, -1, 14836, 14837, 14863, -1, 14860, 14838, 14861, -1, 14837, 14838, 14860, -1, 14861, 14839, 14859, -1, 14838, 14839, 14861, -1, 14859, 14840, 14858, -1, 14839, 14840, 14859, -1, 14858, 14828, 14844, -1, 14840, 14828, 14858, -1, 9553, 9540, 14870, -1, 14871, 14872, 9539, -1, 9540, 14873, 14874, -1, 14872, 14875, 9539, -1, 9540, 14876, 14873, -1, 9541, 14876, 9540, -1, 14875, 14877, 9539, -1, 9541, 9542, 14876, -1, 14878, 14879, 9553, -1, 9542, 9543, 14876, -1, 9553, 14880, 14878, -1, 9543, 9544, 14876, -1, 9544, 9545, 14876, -1, 14879, 14881, 9553, -1, 9545, 9546, 14876, -1, 14882, 9538, 14883, -1, 9553, 14884, 14880, -1, 14883, 9538, 14885, -1, 14885, 9538, 14886, -1, 14886, 9538, 14887, -1, 14887, 9538, 14888, -1, 14888, 9538, 14877, -1, 14877, 9538, 9539, -1, 9560, 14889, 9559, -1, 9561, 14889, 9560, -1, 9562, 14889, 9561, -1, 14876, 9547, 14882, -1, 9563, 14889, 9562, -1, 9546, 9547, 14876, -1, 9564, 14889, 9563, -1, 9565, 14889, 9564, -1, 9553, 14889, 9565, -1, 14881, 14889, 9553, -1, 14882, 9552, 9538, -1, 9547, 9548, 14882, -1, 9553, 14870, 14884, -1, 14882, 9551, 9552, -1, 9556, 14890, 9555, -1, 9557, 14890, 9556, -1, 9558, 14890, 9557, -1, 9559, 14890, 9558, -1, 9548, 9549, 14882, -1, 14889, 14890, 9559, -1, 14882, 9550, 9551, -1, 9549, 9550, 14882, -1, 14890, 9554, 9555, -1, 14890, 9539, 9554, -1, 14891, 9539, 14890, -1, 14891, 14892, 9539, -1, 14892, 14871, 9539, -1, 14870, 9540, 14893, -1, 14893, 9540, 14894, -1, 14894, 9540, 14895, -1, 14895, 9540, 14874, -1, 14877, 14875, 14896, -1, 14896, 14875, 14897, -1, 14897, 14872, 14898, -1, 14875, 14872, 14897, -1, 14898, 14871, 14899, -1, 14872, 14871, 14898, -1, 14899, 14892, 14900, -1, 14871, 14892, 14899, -1, 14900, 14891, 14901, -1, 14892, 14891, 14900, -1, 14901, 14890, 14902, -1, 14891, 14890, 14901, -1, 14902, 14889, 14903, -1, 14890, 14889, 14902, -1, 14903, 14881, 14904, -1, 14889, 14881, 14903, -1, 14904, 14879, 14905, -1, 14881, 14879, 14904, -1, 14905, 14878, 14906, -1, 14879, 14878, 14905, -1, 14906, 14880, 14907, -1, 14878, 14880, 14906, -1, 14907, 14884, 14908, -1, 14880, 14884, 14907, -1, 14908, 14870, 14909, -1, 14884, 14870, 14908, -1, 14900, 14898, 14899, -1, 14900, 14897, 14898, -1, 14897, 14910, 14896, -1, 14901, 14911, 14900, -1, 14910, 14911, 14912, -1, 14912, 14911, 14913, -1, 14900, 14911, 14897, -1, 14897, 14911, 14910, -1, 14906, 14907, 14905, -1, 14901, 14914, 14911, -1, 14907, 14908, 14905, -1, 14902, 14915, 14901, -1, 14901, 14915, 14914, -1, 14903, 14916, 14902, -1, 14902, 14916, 14915, -1, 14909, 14917, 14908, -1, 14905, 14918, 14904, -1, 14904, 14918, 14903, -1, 14903, 14918, 14916, -1, 14908, 14919, 14905, -1, 14917, 14919, 14908, -1, 14905, 14919, 14918, -1, 14920, 14921, 14917, -1, 14917, 14921, 14919, -1, 14870, 14893, 14909, -1, 14909, 14893, 14917, -1, 14917, 14894, 14920, -1, 14893, 14894, 14917, -1, 14920, 14895, 14921, -1, 14894, 14895, 14920, -1, 14921, 14874, 14919, -1, 14895, 14874, 14921, -1, 14919, 14873, 14918, -1, 14874, 14873, 14919, -1, 14918, 14876, 14916, -1, 14873, 14876, 14918, -1, 14916, 14882, 14915, -1, 14876, 14882, 14916, -1, 14915, 14883, 14914, -1, 14882, 14883, 14915, -1, 14914, 14885, 14911, -1, 14883, 14885, 14914, -1, 14911, 14886, 14913, -1, 14885, 14886, 14911, -1, 14913, 14887, 14912, -1, 14886, 14887, 14913, -1, 14912, 14888, 14910, -1, 14887, 14888, 14912, -1, 14910, 14877, 14896, -1, 14888, 14877, 14910, -1, 9105, 9104, 9106, -1, 9106, 9108, 9107, -1, 9104, 9103, 9106, -1, 9106, 9109, 9108, -1, 9103, 9109, 9106, -1, 9109, 13783, 13782, -1, 9100, 9099, 9101, -1, 9101, 9099, 9102, -1, 9102, 9098, 9103, -1, 9103, 9098, 9109, -1, 9099, 9098, 9102, -1, 13784, 13786, 13785, -1, 9098, 9097, 9109, -1, 13783, 13787, 13784, -1, 13784, 13787, 13786, -1, 13783, 13788, 13787, -1, 9096, 13793, 9097, -1, 9097, 13793, 9109, -1, 13788, 13791, 13789, -1, 13789, 13791, 13790, -1, 13792, 13791, 13793, -1, 9109, 13791, 13783, -1, 13793, 13791, 9109, -1, 13783, 13791, 13788, -1, 9157, 9159, 9158, -1, 9156, 9155, 9157, -1, 9159, 9161, 9160, -1, 9157, 9161, 9159, -1, 9161, 13795, 13794, -1, 9153, 9152, 9154, -1, 9154, 9152, 9155, -1, 9155, 9152, 9157, -1, 9157, 9152, 9161, -1, 13795, 13797, 13796, -1, 9161, 13797, 13795, -1, 9151, 9150, 9152, -1, 9152, 9150, 9161, -1, 9150, 9149, 9161, -1, 13797, 13799, 13798, -1, 9148, 13805, 9149, -1, 9149, 13805, 9161, -1, 13805, 13804, 9161, -1, 13799, 13802, 13800, -1, 13800, 13802, 13801, -1, 9161, 13802, 13797, -1, 13797, 13802, 13799, -1, 13804, 13802, 9161, -1, 13804, 13803, 13802, -1, 9209, 9211, 9210, -1, 9209, 9212, 9211, -1, 9208, 9207, 9209, -1, 9212, 13806, 9213, -1, 9205, 9204, 9206, -1, 9206, 9204, 9207, -1, 9207, 9204, 9209, -1, 13806, 13809, 13807, -1, 13807, 13809, 13808, -1, 9203, 9202, 9204, -1, 9209, 9201, 9212, -1, 9204, 9201, 9209, -1, 9202, 9201, 9204, -1, 13809, 13811, 13810, -1, 9200, 13817, 9201, -1, 9212, 13817, 13806, -1, 9201, 13817, 9212, -1, 13811, 13814, 13812, -1, 13812, 13814, 13813, -1, 13816, 13814, 13817, -1, 13806, 13814, 13809, -1, 13809, 13814, 13811, -1, 13817, 13814, 13806, -1, 13816, 13815, 13814, -1, 9261, 9260, 9262, -1, 9262, 9264, 9263, -1, 9260, 9259, 9262, -1, 9264, 13818, 9265, -1, 9257, 9256, 9258, -1, 13818, 13820, 13819, -1, 9258, 9255, 9259, -1, 9259, 9255, 9262, -1, 9256, 9255, 9258, -1, 9254, 9253, 9255, -1, 9262, 9253, 9264, -1, 9255, 9253, 9262, -1, 13820, 13823, 13821, -1, 13821, 13823, 13822, -1, 9252, 13829, 9253, -1, 9264, 13829, 13818, -1, 9253, 13829, 9264, -1, 13823, 13827, 13824, -1, 13824, 13827, 13825, -1, 13825, 13827, 13826, -1, 13828, 13827, 13829, -1, 13818, 13827, 13820, -1, 13820, 13827, 13823, -1, 13829, 13827, 13818, -1, 9285, 9286, 14922, -1, 9285, 14922, 14923, -1, 14924, 14925, 8985, -1, 8986, 14924, 8985, -1, 14926, 8976, 8977, -1, 14927, 8977, 8978, -1, 9284, 14923, 14928, -1, 14927, 14926, 8977, -1, 9284, 9285, 14923, -1, 14929, 8975, 8976, -1, 14929, 8976, 14926, -1, 14930, 8978, 8979, -1, 14930, 14927, 8978, -1, 8987, 14931, 14924, -1, 8987, 14924, 8986, -1, 14932, 8974, 8975, -1, 14932, 8975, 14929, -1, 14933, 8979, 8980, -1, 14933, 14930, 8979, -1, 9283, 14928, 14934, -1, 9283, 9284, 14928, -1, 14935, 8974, 14932, -1, 9289, 8974, 14935, -1, 14936, 8980, 8981, -1, 14936, 14933, 8980, -1, 14937, 9289, 14935, -1, 9278, 14938, 14931, -1, 9278, 14939, 14938, -1, 9278, 14931, 8987, -1, 14940, 8981, 8982, -1, 9282, 14934, 14941, -1, 14940, 14936, 8981, -1, 9282, 9283, 14934, -1, 9288, 9289, 14937, -1, 9279, 14939, 9278, -1, 9281, 14941, 14942, -1, 9281, 9282, 14941, -1, 9280, 14943, 14939, -1, 14944, 9288, 14937, -1, 9280, 14942, 14943, -1, 9280, 9281, 14942, -1, 9280, 14939, 9279, -1, 14945, 8982, 8983, -1, 14945, 14940, 8982, -1, 9287, 9288, 14944, -1, 14946, 9287, 14944, -1, 14947, 14945, 8983, -1, 8984, 14947, 8983, -1, 9286, 9287, 14946, -1, 9286, 14946, 14922, -1, 14925, 14947, 8984, -1, 8985, 14925, 8984, -1, 14948, 14949, 14931, -1, 14931, 14949, 14924, -1, 14924, 14950, 14925, -1, 14949, 14950, 14924, -1, 14925, 14951, 14947, -1, 14950, 14951, 14925, -1, 14947, 14952, 14945, -1, 14951, 14952, 14947, -1, 14945, 14953, 14940, -1, 14952, 14953, 14945, -1, 14940, 14954, 14936, -1, 14953, 14954, 14940, -1, 14936, 14955, 14933, -1, 14954, 14955, 14936, -1, 14933, 14956, 14930, -1, 14955, 14956, 14933, -1, 14930, 14957, 14927, -1, 14956, 14957, 14930, -1, 14927, 14958, 14926, -1, 14957, 14958, 14927, -1, 14926, 14959, 14929, -1, 14958, 14959, 14926, -1, 14929, 14960, 14932, -1, 14959, 14960, 14929, -1, 14932, 14961, 14935, -1, 14960, 14961, 14932, -1, 14960, 14962, 14961, -1, 14959, 14963, 14960, -1, 14960, 14963, 14962, -1, 14958, 14964, 14959, -1, 14959, 14964, 14963, -1, 14957, 14965, 14958, -1, 14958, 14965, 14964, -1, 14956, 14966, 14957, -1, 14957, 14966, 14965, -1, 14955, 14967, 14956, -1, 14956, 14967, 14966, -1, 14954, 14968, 14955, -1, 14955, 14968, 14967, -1, 14948, 14969, 14949, -1, 14953, 14970, 14954, -1, 14954, 14970, 14968, -1, 14949, 14971, 14950, -1, 14969, 14971, 14949, -1, 14952, 14972, 14953, -1, 14953, 14972, 14970, -1, 14950, 14973, 14951, -1, 14951, 14973, 14952, -1, 14971, 14973, 14950, -1, 14952, 14973, 14972, -1, 14961, 14962, 14935, -1, 14935, 14962, 14937, -1, 14937, 14963, 14944, -1, 14962, 14963, 14937, -1, 14944, 14964, 14946, -1, 14963, 14964, 14944, -1, 14946, 14965, 14922, -1, 14964, 14965, 14946, -1, 14922, 14966, 14923, -1, 14965, 14966, 14922, -1, 14923, 14967, 14928, -1, 14966, 14967, 14923, -1, 14928, 14968, 14934, -1, 14967, 14968, 14928, -1, 14934, 14970, 14941, -1, 14968, 14970, 14934, -1, 14941, 14972, 14942, -1, 14970, 14972, 14941, -1, 14942, 14973, 14943, -1, 14972, 14973, 14942, -1, 14943, 14971, 14939, -1, 14973, 14971, 14943, -1, 14939, 14969, 14938, -1, 14971, 14969, 14939, -1, 14938, 14948, 14931, -1, 14969, 14948, 14938, -1, 14974, 14975, 14976, -1, 14977, 3129, 14975, -1, 14977, 14975, 14974, -1, 14978, 14979, 14980, -1, 14978, 14980, 14981, -1, 14978, 14981, 14982, -1, 3199, 14979, 14978, -1, 3199, 3129, 14979, -1, 14979, 3129, 14977, -1, 14983, 3198, 14984, -1, 14983, 14984, 14985, -1, 14983, 14985, 14986, -1, 14983, 14986, 14987, -1, 14988, 14989, 14990, -1, 14991, 14992, 14989, -1, 14991, 14989, 14988, -1, 3197, 14992, 14991, -1, 3197, 3198, 14983, -1, 3197, 14983, 14992, -1, 14993, 14994, 14995, -1, 14996, 3196, 14997, -1, 14996, 14997, 14994, -1, 14996, 14994, 14993, -1, 14998, 14999, 15000, -1, 14998, 15001, 14999, -1, 15002, 15001, 14998, -1, 3195, 15001, 15002, -1, 3195, 3196, 15001, -1, 15001, 3196, 14996, -1, 15003, 15004, 15005, -1, 15006, 3194, 15004, -1, 15006, 15003, 15007, -1, 15006, 15004, 15003, -1, 15008, 15009, 15010, -1, 15011, 15009, 15008, -1, 3079, 15009, 15011, -1, 3079, 3194, 15009, -1, 15009, 3194, 15006, -1, 15012, 15013, 15014, -1, 15012, 15014, 15015, -1, 15016, 15015, 3116, -1, 15016, 15012, 15015, -1, 15017, 15016, 3116, -1, 3123, 15018, 15017, -1, 15019, 15020, 15018, -1, 15021, 15019, 15018, -1, 3396, 15018, 3123, -1, 3398, 15021, 15018, -1, 3398, 15018, 3396, -1, 3400, 15021, 3398, -1, 15022, 3400, 2797, -1, 15022, 15021, 3400, -1, 3116, 3123, 15017, -1, 10542, 10543, 15023, -1, 15024, 10542, 15023, -1, 10120, 15025, 10119, -1, 15026, 15025, 10120, -1, 15027, 10110, 10111, -1, 10541, 10542, 15024, -1, 15028, 10111, 10112, -1, 10541, 15024, 15029, -1, 15028, 15027, 10111, -1, 15030, 10109, 10110, -1, 15030, 10110, 15027, -1, 10121, 15026, 10120, -1, 15031, 10112, 10113, -1, 15031, 15028, 10112, -1, 15032, 10108, 10109, -1, 15032, 10109, 15030, -1, 10540, 15029, 15033, -1, 15034, 10113, 10114, -1, 10540, 10541, 15029, -1, 15034, 15031, 10113, -1, 10535, 15026, 10121, -1, 15035, 10108, 15032, -1, 10535, 15036, 15026, -1, 10539, 10540, 15033, -1, 10539, 15033, 15037, -1, 15038, 10114, 10115, -1, 15038, 15034, 10114, -1, 10536, 15039, 15036, -1, 10536, 15036, 10535, -1, 10538, 15037, 15040, -1, 10538, 10539, 15037, -1, 15041, 10546, 10108, -1, 10537, 15040, 15039, -1, 10537, 10538, 15040, -1, 10537, 15039, 10536, -1, 15041, 10108, 15035, -1, 15042, 10115, 10116, -1, 15042, 15038, 10115, -1, 15043, 10545, 10546, -1, 15043, 10546, 15041, -1, 15044, 10116, 10117, -1, 15044, 15042, 10116, -1, 15045, 10544, 10545, -1, 15045, 10545, 15043, -1, 15046, 15044, 10117, -1, 10118, 15046, 10117, -1, 15047, 10544, 15045, -1, 10543, 10544, 15047, -1, 15048, 15046, 10118, -1, 10119, 15048, 10118, -1, 15023, 10543, 15047, -1, 15025, 15048, 10119, -1, 15026, 15049, 15025, -1, 15025, 15050, 15048, -1, 15049, 15050, 15025, -1, 15048, 15051, 15046, -1, 15050, 15051, 15048, -1, 15046, 15052, 15044, -1, 15051, 15052, 15046, -1, 15044, 15053, 15042, -1, 15052, 15053, 15044, -1, 15042, 15054, 15038, -1, 15053, 15054, 15042, -1, 15038, 15055, 15034, -1, 15054, 15055, 15038, -1, 15034, 15056, 15031, -1, 15055, 15056, 15034, -1, 15056, 15057, 15031, -1, 15031, 15058, 15028, -1, 15057, 15058, 15031, -1, 15028, 15059, 15027, -1, 15058, 15059, 15028, -1, 15027, 15060, 15030, -1, 15059, 15060, 15027, -1, 15030, 15061, 15032, -1, 15032, 15061, 15035, -1, 15060, 15061, 15030, -1, 15061, 15062, 15035, -1, 9572, 9575, 15063, -1, 15064, 10379, 9572, -1, 15063, 15064, 9572, -1, 10561, 15065, 10560, -1, 10559, 10560, 15065, -1, 10562, 15065, 10561, -1, 10558, 10559, 15065, -1, 10557, 10558, 15065, -1, 15065, 10556, 10557, -1, 10564, 15065, 10563, -1, 10563, 15065, 10562, -1, 9566, 15063, 9567, -1, 8819, 15064, 9566, -1, 15064, 15063, 9566, -1, 15066, 9649, 9648, -1, 9650, 9649, 15066, -1, 9651, 9650, 15066, -1, 9652, 9651, 15066, -1, 15066, 9653, 9652, -1, 8384, 15067, 8383, -1, 8384, 15068, 15067, -1, 11321, 11322, 15069, -1, 11321, 15069, 15070, -1, 15071, 8374, 8375, -1, 8385, 15068, 8384, -1, 15072, 8375, 8376, -1, 8385, 15073, 15068, -1, 15072, 15071, 8375, -1, 15074, 8373, 8374, -1, 15074, 8374, 15071, -1, 15075, 8376, 8377, -1, 15075, 15072, 8376, -1, 11320, 15070, 15076, -1, 15077, 8372, 8373, -1, 11320, 11321, 15070, -1, 11320, 15076, 15078, -1, 15077, 8373, 15074, -1, 15079, 8377, 8378, -1, 15079, 15075, 8377, -1, 11315, 15080, 15073, -1, 11315, 15073, 8385, -1, 8379, 15079, 8378, -1, 11319, 15078, 15081, -1, 11319, 11320, 15078, -1, 15082, 8372, 15077, -1, 11316, 15080, 11315, -1, 11316, 15083, 15080, -1, 11326, 8372, 15082, -1, 11318, 15081, 15084, -1, 15085, 15079, 8379, -1, 11318, 11319, 15081, -1, 11317, 15084, 15083, -1, 15086, 11326, 15082, -1, 11317, 15083, 11316, -1, 11317, 11318, 15084, -1, 8380, 15085, 8379, -1, 15087, 15085, 8380, -1, 11325, 11326, 15086, -1, 15088, 11325, 15086, -1, 8381, 15087, 8380, -1, 15089, 15087, 8381, -1, 11324, 11325, 15088, -1, 15090, 11324, 15088, -1, 8382, 15089, 8381, -1, 8382, 15091, 15089, -1, 11323, 15090, 15092, -1, 11323, 11324, 15090, -1, 8383, 15091, 8382, -1, 8383, 15067, 15091, -1, 11322, 11323, 15092, -1, 11322, 15092, 15069, -1, 15073, 15093, 15068, -1, 15068, 15094, 15067, -1, 15093, 15094, 15068, -1, 15067, 15095, 15091, -1, 15094, 15095, 15067, -1, 15091, 15096, 15089, -1, 15095, 15096, 15091, -1, 15089, 15097, 15087, -1, 15096, 15097, 15089, -1, 15087, 15098, 15085, -1, 15097, 15098, 15087, -1, 15085, 15099, 15079, -1, 15098, 15099, 15085, -1, 15079, 15100, 15075, -1, 15099, 15100, 15079, -1, 15075, 15101, 15072, -1, 15100, 15101, 15075, -1, 15072, 15102, 15071, -1, 15101, 15102, 15072, -1, 15071, 15103, 15074, -1, 15102, 15103, 15071, -1, 15074, 15104, 15077, -1, 15103, 15104, 15074, -1, 15077, 15105, 15082, -1, 15104, 15105, 15077, -1, 15105, 15106, 15082, -1, 11346, 15107, 15108, -1, 11339, 15109, 9671, -1, 15110, 9661, 9662, -1, 15110, 9660, 9661, -1, 15110, 9659, 9660, -1, 15110, 9658, 9659, -1, 9657, 9658, 15110, -1, 11345, 15111, 15112, -1, 11345, 15108, 15111, -1, 11345, 11346, 15108, -1, 9656, 9657, 15110, -1, 11340, 15113, 15109, -1, 11340, 15109, 11339, -1, 11344, 15112, 15114, -1, 11344, 11345, 15112, -1, 11341, 15115, 15113, -1, 11341, 15113, 11340, -1, 11343, 15114, 15116, -1, 11343, 11344, 15114, -1, 9668, 15117, 9667, -1, 11342, 15116, 15115, -1, 11342, 15115, 11341, -1, 11342, 11343, 15116, -1, 9666, 9667, 15117, -1, 15110, 15118, 9654, -1, 15110, 9654, 9655, -1, 15110, 9655, 9656, -1, 15109, 15117, 9671, -1, 9671, 15117, 9670, -1, 9669, 15117, 9668, -1, 9665, 9666, 15117, -1, 9670, 15117, 9669, -1, 9664, 9665, 15117, -1, 9663, 9664, 15117, -1, 15118, 11352, 9654, -1, 11351, 11352, 15118, -1, 15119, 11351, 15118, -1, 11350, 11351, 15119, -1, 15120, 11350, 15119, -1, 11349, 11350, 15120, -1, 15121, 11349, 15120, -1, 11348, 11349, 15121, -1, 11348, 15121, 15122, -1, 11347, 11348, 15122, -1, 11347, 15122, 15107, -1, 11346, 11347, 15107, -1, 15123, 11360, 15124, -1, 11353, 15125, 9639, -1, 15126, 9637, 9638, -1, 15126, 9636, 9637, -1, 15126, 9635, 9636, -1, 15126, 9634, 9635, -1, 9633, 9634, 15126, -1, 11359, 11360, 15123, -1, 9632, 9633, 15126, -1, 11354, 15127, 15125, -1, 11354, 15128, 15127, -1, 11354, 15125, 11353, -1, 11358, 15123, 15129, -1, 11358, 11359, 15123, -1, 11355, 15130, 15128, -1, 11355, 15128, 11354, -1, 11357, 15129, 15131, -1, 11357, 11358, 15129, -1, 9642, 15132, 9643, -1, 11356, 15131, 15130, -1, 11356, 15130, 11355, -1, 11356, 11357, 15131, -1, 9644, 9643, 15132, -1, 15126, 15133, 9630, -1, 15126, 9630, 9631, -1, 15126, 9631, 9632, -1, 15125, 15132, 9639, -1, 9639, 15132, 9640, -1, 9641, 15132, 9642, -1, 9645, 9644, 15132, -1, 9640, 15132, 9641, -1, 9646, 9645, 15132, -1, 9647, 9646, 15132, -1, 15133, 11366, 9630, -1, 11365, 11366, 15133, -1, 15134, 11365, 15133, -1, 15135, 11365, 15134, -1, 15135, 11364, 11365, -1, 15136, 11363, 11364, -1, 15136, 11364, 15135, -1, 15137, 11363, 15136, -1, 11362, 11363, 15137, -1, 15138, 11362, 15137, -1, 11361, 11362, 15138, -1, 15124, 11361, 15138, -1, 11360, 11361, 15124, -1, 11650, 11649, 15139, -1, 15140, 8528, 11650, -1, 15139, 15140, 11650, -1, 11736, 11737, 15141, -1, 11735, 11736, 15141, -1, 11734, 11735, 15141, -1, 11739, 15141, 11738, -1, 11738, 15141, 11737, -1, 13711, 15142, 13710, -1, 13711, 15143, 15142, -1, 15144, 13702, 13703, -1, 8351, 8352, 15145, -1, 15146, 13703, 13704, -1, 8351, 15145, 15147, -1, 15146, 15144, 13703, -1, 15148, 13701, 13702, -1, 15148, 13702, 15144, -1, 8344, 15149, 15150, -1, 15151, 13704, 13705, -1, 8344, 15150, 15143, -1, 15151, 15146, 13704, -1, 8344, 15143, 13711, -1, 15152, 13700, 13701, -1, 15152, 13701, 15148, -1, 8350, 8351, 15147, -1, 15153, 15151, 13705, -1, 8350, 15147, 15154, -1, 13706, 15153, 13705, -1, 15155, 8357, 13700, -1, 15155, 13700, 15152, -1, 8345, 15156, 15149, -1, 8345, 15149, 8344, -1, 8356, 8357, 15155, -1, 8349, 15154, 15157, -1, 8349, 8350, 15154, -1, 8346, 15158, 15156, -1, 15159, 15153, 13706, -1, 8346, 15156, 8345, -1, 15160, 8356, 15155, -1, 8348, 15157, 15161, -1, 8348, 8349, 15157, -1, 13707, 15159, 13706, -1, 8347, 15161, 15158, -1, 8347, 15158, 8346, -1, 8347, 8348, 15161, -1, 15162, 15159, 13707, -1, 8355, 8356, 15160, -1, 15163, 8355, 15160, -1, 13708, 15162, 13707, -1, 15164, 15162, 13708, -1, 8354, 8355, 15163, -1, 15165, 8354, 15163, -1, 13709, 15164, 13708, -1, 13709, 15166, 15164, -1, 8353, 8354, 15165, -1, 8353, 15165, 15167, -1, 13710, 15166, 13709, -1, 13710, 15142, 15166, -1, 8352, 8353, 15167, -1, 8352, 15167, 15145, -1, 15168, 15169, 15155, -1, 15155, 15169, 15160, -1, 15160, 15170, 15163, -1, 15169, 15170, 15160, -1, 15163, 15171, 15165, -1, 15170, 15171, 15163, -1, 15165, 15172, 15167, -1, 15171, 15172, 15165, -1, 15167, 15173, 15145, -1, 15172, 15173, 15167, -1, 15145, 15174, 15147, -1, 15173, 15174, 15145, -1, 15147, 15175, 15154, -1, 15174, 15175, 15147, -1, 15154, 15176, 15157, -1, 15175, 15176, 15154, -1, 15157, 15177, 15161, -1, 15176, 15177, 15157, -1, 15161, 15178, 15158, -1, 15177, 15178, 15161, -1, 15158, 15179, 15156, -1, 15178, 15179, 15158, -1, 15156, 15180, 15149, -1, 15179, 15180, 15156, -1, 15149, 15181, 15150, -1, 15180, 15181, 15149, -1, 13732, 13733, 15182, -1, 13732, 15182, 15183, -1, 13725, 15184, 11740, -1, 15185, 11754, 11753, -1, 15185, 11753, 11752, -1, 15185, 11752, 11751, -1, 15185, 11751, 11750, -1, 11755, 11754, 15185, -1, 13731, 13732, 15183, -1, 13731, 15183, 15186, -1, 11756, 11755, 15185, -1, 13726, 15184, 13725, -1, 11757, 11756, 15185, -1, 13726, 15187, 15184, -1, 13730, 13731, 15186, -1, 13730, 15186, 15188, -1, 13727, 15187, 13726, -1, 13727, 15189, 15187, -1, 13729, 15188, 15190, -1, 11744, 15191, 11745, -1, 13729, 13730, 15188, -1, 11746, 11745, 15191, -1, 13728, 15190, 15192, -1, 13728, 15192, 15189, -1, 13728, 15189, 13727, -1, 13728, 13729, 15190, -1, 15185, 15193, 11758, -1, 15185, 11758, 11757, -1, 15184, 15191, 11740, -1, 11743, 15191, 11744, -1, 11740, 15191, 11741, -1, 11741, 15191, 11742, -1, 11747, 11746, 15191, -1, 11742, 15191, 11743, -1, 11748, 11747, 15191, -1, 11749, 11748, 15191, -1, 15193, 13724, 11758, -1, 13737, 13724, 15193, -1, 15194, 13737, 15193, -1, 13736, 13737, 15194, -1, 15195, 13736, 15194, -1, 13735, 13736, 15195, -1, 15196, 13735, 15195, -1, 13734, 15196, 15197, -1, 13734, 13735, 15196, -1, 13733, 13734, 15197, -1, 13733, 15197, 15182, -1, 15198, 12927, 15199, -1, 12199, 15200, 12198, -1, 15201, 15200, 12199, -1, 12926, 12927, 15198, -1, 12926, 15198, 15202, -1, 15203, 12189, 12190, -1, 15204, 12190, 12191, -1, 12200, 15201, 12199, -1, 15204, 15203, 12190, -1, 15205, 12188, 12189, -1, 15205, 12189, 15203, -1, 15206, 12191, 12192, -1, 15206, 15204, 12191, -1, 15207, 12187, 12188, -1, 12925, 12926, 15202, -1, 15207, 12188, 15205, -1, 12925, 15202, 15208, -1, 12920, 15209, 15201, -1, 12920, 15201, 12200, -1, 15210, 12192, 12193, -1, 15210, 15206, 12192, -1, 12924, 15208, 15211, -1, 12924, 12925, 15208, -1, 15212, 12187, 15207, -1, 12921, 15209, 12920, -1, 12921, 15213, 15209, -1, 15214, 12193, 12194, -1, 12923, 12924, 15211, -1, 12923, 15211, 15215, -1, 12922, 15215, 15213, -1, 12922, 12923, 15215, -1, 15214, 15210, 12193, -1, 12922, 15213, 12921, -1, 15216, 12931, 12187, -1, 15216, 12187, 15212, -1, 15217, 12194, 12195, -1, 15217, 15214, 12194, -1, 15218, 12930, 12931, -1, 15218, 12931, 15216, -1, 15219, 12195, 12196, -1, 15219, 15217, 12195, -1, 15220, 12929, 12930, -1, 15220, 12930, 15218, -1, 15221, 15219, 12196, -1, 12197, 15221, 12196, -1, 15222, 12929, 15220, -1, 12928, 12929, 15222, -1, 15223, 15221, 12197, -1, 12198, 15223, 12197, -1, 15199, 12928, 15222, -1, 15200, 15223, 12198, -1, 12927, 12928, 15199, -1, 15201, 15224, 15200, -1, 15224, 15225, 15200, -1, 15200, 15226, 15223, -1, 15225, 15226, 15200, -1, 15223, 15227, 15221, -1, 15226, 15227, 15223, -1, 15221, 15228, 15219, -1, 15227, 15228, 15221, -1, 15219, 15229, 15217, -1, 15228, 15229, 15219, -1, 15217, 15230, 15214, -1, 15229, 15230, 15217, -1, 15214, 15231, 15210, -1, 15230, 15231, 15214, -1, 15210, 15232, 15206, -1, 15231, 15232, 15210, -1, 15206, 15233, 15204, -1, 15232, 15233, 15206, -1, 15204, 15234, 15203, -1, 15233, 15234, 15204, -1, 15203, 15235, 15205, -1, 15234, 15235, 15203, -1, 15207, 15236, 15212, -1, 15205, 15236, 15207, -1, 15235, 15236, 15205, -1, 15236, 15237, 15212, -1, 11656, 12355, 15140, -1, 15139, 11659, 11656, -1, 15140, 15139, 11656, -1, 15238, 12948, 12947, -1, 15238, 12947, 12946, -1, 12945, 15238, 12946, -1, 12944, 15238, 12945, -1, 12943, 15238, 12944, -1, 15238, 12949, 12948, -1, 12941, 15238, 12942, -1, 12942, 15238, 12943, -1, 15239, 15066, 8150, -1, 8150, 8153, 15239, -1, 15066, 9648, 8150, -1, 8153, 15240, 15239, -1, 9647, 15132, 8153, -1, 8153, 15132, 15240, -1, 15126, 8177, 15241, -1, 15126, 9638, 8177, -1, 8177, 15242, 15241, -1, 15243, 8185, 15244, -1, 15242, 8185, 15243, -1, 15244, 9576, 15245, -1, 8185, 9576, 15244, -1, 9567, 15063, 8185, -1, 8185, 9575, 9576, -1, 15063, 9575, 8185, -1, 15245, 9700, 15246, -1, 10556, 15065, 9700, -1, 9700, 15065, 15246, -1, 9576, 9700, 15245, -1, 8177, 8185, 15242, -1, 8040, 15117, 15247, -1, 9663, 15117, 8040, -1, 7981, 8040, 15247, -1, 15248, 7981, 15247, -1, 15185, 11750, 7981, -1, 15185, 7981, 15248, -1, 15249, 8244, 11724, -1, 15250, 8244, 15249, -1, 15250, 15251, 8244, -1, 11649, 8246, 15139, -1, 15251, 15252, 8246, -1, 8246, 11659, 15139, -1, 8246, 11658, 11659, -1, 15252, 15253, 8246, -1, 8246, 15253, 11658, -1, 15253, 15254, 11658, -1, 11760, 15238, 12941, -1, 11760, 15255, 15238, -1, 11760, 11658, 15254, -1, 8246, 8244, 15251, -1, 15254, 15255, 11760, -1, 7920, 15256, 8207, -1, 15191, 7920, 11749, -1, 15257, 7920, 15191, -1, 15257, 15256, 7920, -1, 8302, 15141, 11739, -1, 15258, 15141, 8302, -1, 15256, 8302, 8207, -1, 15256, 15258, 8302, -1, 15259, 2782, 2770, -1, 15260, 2782, 15259, -1, 2796, 2808, 15261, -1, 2808, 15262, 15261, -1, 15260, 15259, 15263, -1, 15264, 15263, 15265, -1, 15264, 15260, 15263, -1, 15266, 15267, 15268, -1, 15262, 15267, 15266, -1, 2808, 15267, 15262, -1, 15269, 15270, 15271, -1, 15270, 2649, 15272, -1, 15269, 2649, 15270, -1, 2808, 2649, 15267, -1, 15267, 2649, 15269, -1, 15273, 15274, 15275, -1, 2943, 15273, 15275, -1, 2944, 2943, 15275, -1, 2945, 2944, 15275, -1, 15272, 15276, 15277, -1, 15270, 15277, 15278, -1, 15270, 15278, 15279, -1, 15270, 15279, 15280, -1, 15270, 15272, 15277, -1, 15281, 15282, 15283, -1, 15281, 15283, 15284, -1, 15281, 15284, 15285, -1, 15281, 15285, 15286, -1, 15281, 15286, 2945, -1, 15281, 2945, 15275, -1, 15287, 15280, 15288, -1, 15287, 15288, 15289, -1, 15287, 15289, 15290, -1, 15287, 15290, 15291, -1, 15287, 15291, 15292, -1, 15287, 15292, 15293, -1, 15287, 15293, 15282, -1, 15287, 15282, 15281, -1, 15287, 15270, 15280, -1, 2927, 15294, 15295, -1, 2927, 15295, 15296, -1, 2928, 2927, 15296, -1, 2929, 2928, 15296, -1, 2930, 2929, 15296, -1, 15297, 15298, 15299, -1, 15300, 15297, 15299, -1, 15301, 15297, 15300, -1, 15302, 2931, 2930, -1, 15302, 2932, 2931, -1, 15302, 2933, 2932, -1, 15302, 2934, 2933, -1, 15302, 2935, 2934, -1, 15302, 2936, 2935, -1, 15302, 2937, 2936, -1, 15302, 2930, 15296, -1, 15303, 2938, 2937, -1, 15303, 2939, 2938, -1, 15303, 2937, 15302, -1, 15303, 15297, 15301, -1, 15303, 15301, 2942, -1, 15303, 2942, 2941, -1, 15303, 2941, 2940, -1, 15303, 2940, 2939, -1, 15260, 15304, 2782, -1, 15305, 15304, 15260, -1, 15304, 15306, 2782, -1, 15305, 15307, 15304, -1, 15306, 2758, 2782, -1, 15308, 15296, 15306, -1, 15306, 15296, 2758, -1, 15296, 15295, 2758, -1, 15062, 15309, 15035, -1, 15035, 15309, 15041, -1, 15041, 15310, 15043, -1, 15309, 15310, 15041, -1, 15043, 15311, 15045, -1, 15310, 15311, 15043, -1, 15045, 15312, 15047, -1, 15311, 15312, 15045, -1, 15047, 15313, 15023, -1, 15312, 15313, 15047, -1, 15023, 15314, 15024, -1, 15313, 15314, 15023, -1, 15024, 15315, 15029, -1, 15314, 15315, 15024, -1, 15029, 15316, 15033, -1, 15315, 15316, 15029, -1, 15033, 15317, 15037, -1, 15316, 15317, 15033, -1, 15037, 15318, 15040, -1, 15317, 15318, 15037, -1, 15040, 15319, 15039, -1, 15318, 15319, 15040, -1, 15039, 15320, 15036, -1, 15319, 15320, 15039, -1, 15036, 15049, 15026, -1, 15320, 15049, 15036, -1, 15321, 15322, 15323, -1, 15324, 15309, 15325, -1, 15321, 15323, 15326, -1, 15321, 15327, 15322, -1, 15324, 15325, 15328, -1, 15324, 15328, 15329, -1, 15330, 15331, 15332, -1, 15333, 15329, 15334, -1, 15335, 15336, 15337, -1, 15333, 15334, 15338, -1, 15335, 15339, 15336, -1, 15340, 15337, 15341, -1, 15342, 15338, 15343, -1, 15342, 15343, 15344, -1, 15049, 15320, 15345, -1, 15340, 15341, 15346, -1, 15347, 15348, 15349, -1, 15350, 15351, 15352, -1, 15350, 15353, 15351, -1, 15354, 15346, 15355, -1, 15354, 15355, 15356, -1, 15347, 15344, 15348, -1, 15357, 15349, 15358, -1, 15359, 15360, 15361, -1, 15362, 15363, 15353, -1, 15357, 15358, 15364, -1, 15362, 15353, 15350, -1, 15359, 15356, 15360, -1, 15365, 15366, 15331, -1, 15367, 15368, 15369, -1, 15367, 15364, 15368, -1, 15365, 15315, 15314, -1, 15370, 15352, 15371, -1, 15365, 15314, 15366, -1, 15365, 15331, 15330, -1, 15372, 15339, 15335, -1, 15373, 15311, 15310, -1, 15370, 15350, 15352, -1, 15373, 15329, 15333, -1, 15374, 15363, 15362, -1, 15373, 15324, 15329, -1, 15373, 15310, 15324, -1, 15374, 15375, 15363, -1, 15372, 15330, 15339, -1, 15376, 15337, 15340, -1, 15377, 15333, 15338, -1, 15376, 15335, 15337, -1, 15377, 15338, 15342, -1, 15378, 15350, 15370, -1, 15379, 15342, 15344, -1, 15379, 15344, 15347, -1, 15380, 15340, 15346, -1, 15378, 15362, 15350, -1, 15380, 15346, 15354, -1, 15381, 15349, 15357, -1, 15382, 15371, 15383, -1, 15309, 15062, 15384, -1, 15381, 15347, 15349, -1, 15385, 15354, 15356, -1, 15382, 15370, 15371, -1, 15386, 15387, 15375, -1, 15385, 15356, 15359, -1, 15386, 15375, 15374, -1, 15388, 15389, 15390, -1, 15388, 15361, 15389, -1, 15388, 15359, 15361, -1, 15391, 15357, 15364, -1, 15392, 15374, 15362, -1, 15388, 15390, 15393, -1, 15391, 15364, 15367, -1, 15394, 15316, 15315, -1, 15395, 15369, 15396, -1, 15394, 15315, 15365, -1, 15392, 15362, 15378, -1, 15394, 15330, 15372, -1, 15394, 15365, 15330, -1, 15395, 15367, 15369, -1, 15397, 15335, 15376, -1, 15398, 15312, 15311, -1, 15399, 15378, 15370, -1, 15398, 15311, 15373, -1, 15399, 15370, 15382, -1, 15398, 15373, 15333, -1, 15398, 15333, 15377, -1, 15397, 15372, 15335, -1, 15400, 15376, 15340, -1, 15401, 15383, 15402, -1, 15403, 15377, 15342, -1, 15403, 15342, 15379, -1, 15400, 15340, 15380, -1, 15401, 15382, 15383, -1, 15404, 15380, 15354, -1, 15332, 15379, 15347, -1, 15328, 15405, 15387, -1, 15332, 15347, 15381, -1, 15328, 15387, 15386, -1, 15334, 15374, 15392, -1, 15404, 15354, 15385, -1, 15406, 15393, 15407, -1, 15336, 15381, 15357, -1, 15334, 15386, 15374, -1, 15406, 15385, 15359, -1, 15336, 15357, 15391, -1, 15406, 15388, 15393, -1, 15406, 15359, 15388, -1, 15408, 15316, 15394, -1, 15408, 15317, 15316, -1, 15408, 15394, 15372, -1, 15408, 15372, 15397, -1, 15341, 15391, 15367, -1, 15343, 15392, 15378, -1, 15341, 15367, 15395, -1, 15343, 15378, 15399, -1, 15409, 15397, 15376, -1, 15348, 15399, 15382, -1, 15409, 15376, 15400, -1, 15355, 15396, 15410, -1, 15348, 15382, 15401, -1, 15355, 15395, 15396, -1, 15411, 15313, 15312, -1, 15411, 15312, 15398, -1, 15358, 15402, 15412, -1, 15413, 15400, 15380, -1, 15411, 15398, 15377, -1, 15413, 15380, 15404, -1, 15411, 15377, 15403, -1, 15358, 15401, 15402, -1, 15414, 15407, 15415, -1, 15325, 15405, 15328, -1, 15414, 15406, 15407, -1, 15325, 15384, 15405, -1, 15414, 15404, 15385, -1, 15331, 15403, 15379, -1, 15331, 15379, 15332, -1, 15325, 15309, 15384, -1, 15414, 15385, 15406, -1, 15416, 15317, 15408, -1, 15416, 15318, 15317, -1, 15416, 15397, 15409, -1, 15329, 15328, 15386, -1, 15339, 15332, 15381, -1, 15329, 15386, 15334, -1, 15416, 15408, 15397, -1, 15339, 15381, 15336, -1, 15322, 15409, 15400, -1, 15322, 15400, 15413, -1, 15337, 15336, 15391, -1, 15337, 15391, 15341, -1, 15338, 15392, 15343, -1, 15338, 15334, 15392, -1, 15417, 15413, 15404, -1, 15344, 15399, 15348, -1, 15417, 15415, 15418, -1, 15417, 15404, 15414, -1, 15417, 15414, 15415, -1, 15344, 15343, 15399, -1, 15327, 15319, 15318, -1, 15327, 15318, 15416, -1, 15346, 15341, 15395, -1, 15346, 15395, 15355, -1, 15327, 15416, 15409, -1, 15327, 15409, 15322, -1, 15323, 15322, 15413, -1, 15356, 15410, 15360, -1, 15349, 15348, 15401, -1, 15323, 15418, 15326, -1, 15349, 15401, 15358, -1, 15356, 15355, 15410, -1, 15323, 15413, 15417, -1, 15366, 15314, 15313, -1, 15364, 15412, 15368, -1, 15323, 15417, 15418, -1, 15321, 15326, 15345, -1, 15366, 15313, 15411, -1, 15321, 15345, 15320, -1, 15366, 15411, 15403, -1, 15364, 15358, 15412, -1, 15321, 15320, 15319, -1, 15366, 15403, 15331, -1, 15321, 15319, 15327, -1, 15330, 15332, 15339, -1, 15324, 15310, 15309, -1, 15106, 15419, 15082, -1, 15082, 15419, 15086, -1, 15086, 15420, 15088, -1, 15419, 15420, 15086, -1, 15088, 15421, 15090, -1, 15420, 15421, 15088, -1, 15090, 15422, 15092, -1, 15421, 15422, 15090, -1, 15092, 15423, 15069, -1, 15422, 15423, 15092, -1, 15069, 15424, 15070, -1, 15423, 15424, 15069, -1, 15070, 15425, 15076, -1, 15424, 15425, 15070, -1, 15076, 15426, 15078, -1, 15425, 15426, 15076, -1, 15078, 15427, 15081, -1, 15426, 15427, 15078, -1, 15081, 15428, 15084, -1, 15427, 15428, 15081, -1, 15084, 15429, 15083, -1, 15428, 15429, 15084, -1, 15083, 15430, 15080, -1, 15429, 15430, 15083, -1, 15080, 15093, 15073, -1, 15430, 15093, 15080, -1, 15431, 15432, 15433, -1, 15431, 15429, 15434, -1, 15435, 15419, 15436, -1, 15431, 15433, 15437, -1, 15431, 15437, 15093, -1, 15431, 15430, 15429, -1, 15438, 15439, 15440, -1, 15431, 15093, 15430, -1, 15441, 15442, 15443, -1, 15431, 15434, 15444, -1, 15431, 15444, 15432, -1, 15438, 15445, 15439, -1, 15446, 15447, 15448, -1, 15441, 15443, 15449, -1, 15450, 15449, 15451, -1, 15446, 15440, 15447, -1, 15452, 15448, 15453, -1, 15454, 15455, 15456, -1, 15450, 15451, 15457, -1, 15454, 15458, 15455, -1, 15459, 15457, 15460, -1, 15459, 15460, 15461, -1, 15452, 15453, 15462, -1, 15463, 15462, 15464, -1, 15463, 15464, 15465, -1, 15466, 15467, 15458, -1, 15466, 15458, 15454, -1, 15468, 15461, 15469, -1, 15468, 15469, 15470, -1, 15471, 15472, 15473, -1, 15471, 15465, 15472, -1, 15474, 15456, 15475, -1, 15476, 15477, 15478, -1, 15476, 15470, 15477, -1, 15474, 15454, 15456, -1, 15479, 15445, 15438, -1, 15480, 15467, 15466, -1, 15479, 15425, 15424, -1, 15481, 15421, 15420, -1, 15480, 15482, 15467, -1, 15481, 15435, 15442, -1, 15479, 15424, 15483, -1, 15479, 15483, 15445, -1, 15481, 15442, 15441, -1, 15484, 15440, 15446, -1, 15481, 15420, 15435, -1, 15485, 15454, 15474, -1, 15484, 15438, 15440, -1, 15486, 15449, 15450, -1, 15486, 15441, 15449, -1, 15487, 15446, 15448, -1, 15485, 15466, 15454, -1, 15487, 15448, 15452, -1, 15488, 15450, 15457, -1, 15489, 15475, 15490, -1, 15488, 15457, 15459, -1, 15491, 15462, 15463, -1, 15489, 15474, 15475, -1, 15492, 15459, 15461, -1, 15493, 15494, 15482, -1, 15492, 15461, 15468, -1, 15491, 15452, 15462, -1, 15493, 15482, 15480, -1, 15495, 15465, 15471, -1, 15495, 15463, 15465, -1, 15496, 15480, 15466, -1, 15497, 15470, 15476, -1, 15498, 15499, 15500, -1, 15497, 15468, 15470, -1, 15496, 15466, 15485, -1, 15498, 15473, 15499, -1, 15498, 15471, 15473, -1, 15498, 15500, 15501, -1, 15502, 15478, 15503, -1, 15504, 15425, 15479, -1, 15502, 15476, 15478, -1, 15505, 15485, 15474, -1, 15505, 15474, 15489, -1, 15506, 15422, 15421, -1, 15504, 15426, 15425, -1, 15506, 15421, 15481, -1, 15504, 15438, 15484, -1, 15506, 15481, 15441, -1, 15504, 15479, 15438, -1, 15506, 15441, 15486, -1, 15507, 15484, 15446, -1, 15508, 15490, 15509, -1, 15508, 15489, 15490, -1, 15510, 15450, 15488, -1, 15507, 15446, 15487, -1, 15510, 15486, 15450, -1, 15511, 15487, 15452, -1, 15512, 15513, 15494, -1, 15512, 15494, 15493, -1, 15511, 15452, 15491, -1, 15439, 15459, 15492, -1, 15439, 15488, 15459, -1, 15443, 15493, 15480, -1, 15514, 15463, 15495, -1, 15443, 15480, 15496, -1, 15514, 15491, 15463, -1, 15447, 15492, 15468, -1, 15451, 15485, 15505, -1, 15447, 15468, 15497, -1, 15515, 15501, 15516, -1, 15453, 15497, 15476, -1, 15515, 15498, 15501, -1, 15451, 15496, 15485, -1, 15515, 15495, 15471, -1, 15460, 15489, 15508, -1, 15515, 15471, 15498, -1, 15517, 15484, 15507, -1, 15517, 15427, 15426, -1, 15453, 15476, 15502, -1, 15460, 15505, 15489, -1, 15517, 15504, 15484, -1, 15517, 15426, 15504, -1, 15464, 15503, 15518, -1, 15519, 15507, 15487, -1, 15469, 15509, 15520, -1, 15464, 15502, 15503, -1, 15519, 15487, 15511, -1, 15521, 15423, 15422, -1, 15469, 15508, 15509, -1, 15436, 15419, 15106, -1, 15521, 15422, 15506, -1, 15521, 15506, 15486, -1, 15436, 15522, 15513, -1, 15521, 15486, 15510, -1, 15436, 15106, 15522, -1, 15436, 15513, 15512, -1, 15523, 15511, 15491, -1, 15523, 15491, 15514, -1, 15445, 15510, 15488, -1, 15524, 15516, 15525, -1, 15445, 15488, 15439, -1, 15442, 15512, 15493, -1, 15524, 15514, 15495, -1, 15524, 15495, 15515, -1, 15524, 15515, 15516, -1, 15440, 15439, 15492, -1, 15442, 15493, 15443, -1, 15440, 15492, 15447, -1, 15526, 15428, 15427, -1, 15526, 15507, 15519, -1, 15526, 15517, 15507, -1, 15449, 15443, 15496, -1, 15526, 15427, 15517, -1, 15449, 15496, 15451, -1, 15448, 15447, 15497, -1, 15448, 15497, 15453, -1, 15457, 15505, 15460, -1, 15444, 15519, 15511, -1, 15444, 15511, 15523, -1, 15457, 15451, 15505, -1, 15527, 15525, 15528, -1, 15527, 15524, 15525, -1, 15527, 15523, 15514, -1, 15461, 15460, 15508, -1, 15527, 15514, 15524, -1, 15462, 15453, 15502, -1, 15462, 15502, 15464, -1, 15461, 15508, 15469, -1, 15434, 15429, 15428, -1, 15434, 15428, 15526, -1, 15465, 15518, 15472, -1, 15434, 15526, 15519, -1, 15470, 15520, 15477, -1, 15434, 15519, 15444, -1, 15432, 15528, 15433, -1, 15465, 15464, 15518, -1, 15483, 15424, 15423, -1, 15470, 15469, 15520, -1, 15435, 15420, 15419, -1, 15432, 15527, 15528, -1, 15483, 15521, 15510, -1, 15432, 15444, 15523, -1, 15435, 15436, 15512, -1, 15432, 15523, 15527, -1, 15483, 15510, 15445, -1, 15483, 15423, 15521, -1, 15435, 15512, 15442, -1, 15529, 15530, 15531, -1, 15530, 15532, 15531, -1, 15533, 15532, 15534, -1, 15535, 15532, 15533, -1, 15531, 15532, 15535, -1, 15534, 15536, 15251, -1, 15532, 15536, 15534, -1, 15256, 15257, 15537, -1, 15538, 15539, 15540, -1, 15541, 15542, 15543, -1, 15541, 15543, 15544, -1, 15541, 15544, 15545, -1, 15541, 15545, 15546, -1, 15543, 15542, 15547, -1, 15545, 15544, 15548, -1, 15242, 15549, 15241, -1, 15550, 15549, 15242, -1, 15240, 15551, 15239, -1, 15550, 15552, 15549, -1, 15549, 15552, 15553, -1, 15553, 15552, 15554, -1, 15554, 15552, 15555, -1, 15552, 15556, 15555, -1, 15555, 15556, 15557, -1, 15556, 15558, 15557, -1, 15557, 15558, 15559, -1, 15559, 15558, 15560, -1, 15558, 15561, 15560, -1, 15560, 15561, 15562, -1, 15561, 15563, 15562, -1, 15562, 15563, 15564, -1, 15564, 15563, 15565, -1, 15565, 15563, 15566, -1, 15566, 15563, 15567, -1, 15551, 15539, 15239, -1, 15567, 15539, 15568, -1, 15568, 15539, 15551, -1, 15563, 15539, 15567, -1, 15563, 15569, 15539, -1, 15570, 15571, 15569, -1, 15571, 15572, 15569, -1, 15572, 15541, 15569, -1, 15569, 15541, 15539, -1, 15573, 15574, 15539, -1, 15539, 15575, 15573, -1, 15574, 15576, 15539, -1, 15539, 15577, 15575, -1, 15576, 15578, 15539, -1, 15539, 15579, 15577, -1, 15578, 15540, 15539, -1, 15539, 15580, 15579, -1, 15541, 15581, 15539, -1, 15539, 15581, 15580, -1, 15541, 15582, 15581, -1, 15541, 15583, 15582, -1, 15541, 15584, 15583, -1, 15541, 15585, 15584, -1, 15541, 15586, 15585, -1, 15541, 15587, 15586, -1, 15588, 15538, 15540, -1, 15589, 15538, 15588, -1, 15590, 15538, 15589, -1, 15591, 15538, 15590, -1, 15592, 15538, 15591, -1, 15593, 15538, 15592, -1, 15594, 15595, 15593, -1, 15596, 15595, 15594, -1, 15593, 15595, 15538, -1, 15597, 15598, 15596, -1, 15596, 15598, 15595, -1, 15599, 15600, 15597, -1, 15597, 15600, 15598, -1, 15587, 15601, 15599, -1, 15599, 15601, 15600, -1, 15587, 15602, 15601, -1, 15541, 15602, 15587, -1, 15541, 15603, 15602, -1, 15541, 15546, 15603, -1, 15247, 15604, 15248, -1, 15605, 15604, 15247, -1, 15605, 15606, 15604, -1, 15607, 15606, 15608, -1, 15608, 15606, 15605, -1, 15607, 15609, 15606, -1, 15607, 15610, 15609, -1, 15611, 15610, 15612, -1, 15612, 15610, 15607, -1, 15611, 15613, 15610, -1, 15611, 15544, 15613, -1, 15548, 15544, 15611, -1, 15614, 15615, 15257, -1, 15257, 15616, 15614, -1, 15615, 15617, 15257, -1, 15257, 15618, 15616, -1, 15617, 15537, 15257, -1, 15257, 15619, 15618, -1, 15620, 15619, 15257, -1, 15620, 15621, 15619, -1, 15620, 15622, 15621, -1, 15623, 15622, 15620, -1, 15623, 15624, 15622, -1, 15625, 15624, 15623, -1, 15625, 15626, 15624, -1, 15627, 15626, 15625, -1, 15627, 15628, 15626, -1, 15629, 15628, 15627, -1, 15630, 15256, 15631, -1, 15631, 15256, 15632, -1, 15632, 15256, 15633, -1, 15633, 15256, 15634, -1, 15634, 15256, 15635, -1, 15635, 15256, 15636, -1, 15636, 15256, 15637, -1, 15637, 15256, 15638, -1, 15638, 15256, 15537, -1, 15258, 15639, 15640, -1, 15256, 15639, 15258, -1, 15256, 15641, 15639, -1, 15256, 15642, 15641, -1, 15628, 15542, 15643, -1, 15643, 15542, 15644, -1, 15644, 15542, 15645, -1, 15645, 15542, 15646, -1, 15646, 15542, 15647, -1, 15647, 15542, 15630, -1, 15630, 15542, 15256, -1, 15648, 15542, 15629, -1, 15547, 15542, 15648, -1, 15629, 15542, 15628, -1, 15534, 15251, 15250, -1, 15649, 15650, 15651, -1, 15651, 15650, 15652, -1, 15652, 15650, 15542, -1, 15542, 15650, 15256, -1, 15653, 15654, 15655, -1, 15656, 15654, 15653, -1, 15657, 15654, 15656, -1, 15642, 15654, 15657, -1, 15650, 15654, 15256, -1, 15256, 15654, 15642, -1, 15654, 15658, 15655, -1, 15655, 15658, 15659, -1, 15658, 15660, 15659, -1, 15661, 15660, 15529, -1, 15659, 15660, 15661, -1, 15660, 15530, 15529, -1, 15662, 15663, 15664, -1, 15665, 15666, 15667, -1, 15668, 15669, 15670, -1, 15668, 15618, 15671, -1, 15672, 15634, 15673, -1, 15672, 15674, 15675, -1, 15672, 15675, 15632, -1, 15672, 15632, 15633, -1, 15676, 15667, 15677, -1, 15678, 15670, 15679, -1, 15672, 15633, 15634, -1, 15672, 15662, 15674, -1, 15672, 15673, 15680, -1, 15676, 15677, 15681, -1, 15672, 15680, 15662, -1, 15682, 15681, 15683, -1, 15678, 15679, 15684, -1, 15685, 15684, 15686, -1, 15687, 15688, 15689, -1, 15682, 15683, 15690, -1, 15685, 15686, 15691, -1, 15692, 15690, 15693, -1, 15687, 15694, 15688, -1, 15695, 15691, 15696, -1, 15695, 15696, 15697, -1, 15692, 15693, 15698, -1, 15699, 15698, 15700, -1, 15699, 15700, 15701, -1, 15702, 15703, 15694, -1, 15702, 15694, 15687, -1, 15704, 15705, 15706, -1, 15704, 15697, 15705, -1, 15707, 15689, 15708, -1, 15709, 15710, 15711, -1, 15712, 15701, 15713, -1, 15712, 15713, 15714, -1, 15707, 15687, 15689, -1, 15709, 15706, 15710, -1, 15715, 15703, 15702, -1, 15716, 15665, 15667, -1, 15717, 15668, 15670, -1, 15715, 15718, 15703, -1, 15716, 15638, 15537, -1, 15717, 15614, 15616, -1, 15716, 15667, 15676, -1, 15717, 15616, 15668, -1, 15716, 15537, 15665, -1, 15717, 15670, 15678, -1, 15719, 15676, 15681, -1, 15720, 15702, 15687, -1, 15721, 15678, 15684, -1, 15719, 15681, 15682, -1, 15721, 15684, 15685, -1, 15722, 15682, 15690, -1, 15722, 15690, 15692, -1, 15720, 15687, 15707, -1, 15723, 15691, 15695, -1, 15724, 15707, 15708, -1, 15724, 15708, 15725, -1, 15723, 15685, 15691, -1, 15726, 15692, 15698, -1, 15727, 15695, 15697, -1, 15727, 15697, 15704, -1, 15728, 15729, 15718, -1, 15726, 15698, 15699, -1, 15728, 15718, 15715, -1, 15730, 15699, 15701, -1, 15731, 15702, 15720, -1, 15732, 15704, 15706, -1, 15731, 15715, 15702, -1, 15732, 15706, 15709, -1, 15730, 15701, 15712, -1, 15733, 15714, 15734, -1, 15735, 15711, 15736, -1, 15733, 15734, 15737, -1, 15733, 15737, 15738, -1, 15733, 15712, 15714, -1, 15735, 15709, 15711, -1, 15739, 15720, 15707, -1, 15740, 15716, 15676, -1, 15739, 15707, 15724, -1, 15740, 15637, 15638, -1, 15741, 15615, 15614, -1, 15740, 15638, 15716, -1, 15741, 15614, 15717, -1, 15742, 15725, 15743, -1, 15741, 15717, 15678, -1, 15740, 15676, 15719, -1, 15741, 15678, 15721, -1, 15742, 15724, 15725, -1, 15744, 15682, 15722, -1, 15666, 15721, 15685, -1, 15666, 15685, 15723, -1, 15744, 15719, 15682, -1, 15669, 15745, 15729, -1, 15746, 15722, 15692, -1, 15669, 15729, 15728, -1, 15746, 15692, 15726, -1, 15677, 15695, 15727, -1, 15677, 15723, 15695, -1, 15679, 15715, 15731, -1, 15679, 15728, 15715, -1, 15683, 15727, 15704, -1, 15747, 15726, 15699, -1, 15683, 15704, 15732, -1, 15747, 15699, 15730, -1, 15748, 15733, 15738, -1, 15686, 15731, 15720, -1, 15748, 15738, 15749, -1, 15686, 15720, 15739, -1, 15748, 15730, 15712, -1, 15748, 15712, 15733, -1, 15696, 15739, 15724, -1, 15693, 15709, 15735, -1, 15750, 15636, 15637, -1, 15750, 15637, 15740, -1, 15693, 15732, 15709, -1, 15750, 15740, 15719, -1, 15700, 15736, 15751, -1, 15696, 15724, 15742, -1, 15750, 15719, 15744, -1, 15752, 15722, 15746, -1, 15705, 15743, 15753, -1, 15752, 15744, 15722, -1, 15700, 15735, 15736, -1, 15754, 15615, 15741, -1, 15705, 15742, 15743, -1, 15754, 15617, 15615, -1, 15754, 15721, 15666, -1, 15754, 15741, 15721, -1, 15671, 15618, 15619, -1, 15671, 15755, 15745, -1, 15671, 15619, 15755, -1, 15663, 15746, 15726, -1, 15671, 15745, 15669, -1, 15663, 15726, 15747, -1, 15756, 15749, 15757, -1, 15667, 15666, 15723, -1, 15667, 15723, 15677, -1, 15670, 15728, 15679, -1, 15756, 15747, 15730, -1, 15756, 15748, 15749, -1, 15756, 15730, 15748, -1, 15670, 15669, 15728, -1, 15681, 15677, 15727, -1, 15681, 15727, 15683, -1, 15758, 15635, 15636, -1, 15758, 15636, 15750, -1, 15684, 15731, 15686, -1, 15758, 15750, 15744, -1, 15758, 15744, 15752, -1, 15684, 15679, 15731, -1, 15690, 15683, 15732, -1, 15690, 15732, 15693, -1, 15680, 15752, 15746, -1, 15691, 15686, 15739, -1, 15680, 15746, 15663, -1, 15691, 15739, 15696, -1, 15664, 15756, 15757, -1, 15698, 15693, 15735, -1, 15664, 15757, 15759, -1, 15664, 15747, 15756, -1, 15664, 15663, 15747, -1, 15697, 15696, 15742, -1, 15697, 15742, 15705, -1, 15698, 15735, 15700, -1, 15706, 15753, 15710, -1, 15673, 15634, 15635, -1, 15673, 15635, 15758, -1, 15701, 15751, 15713, -1, 15673, 15758, 15752, -1, 15673, 15752, 15680, -1, 15701, 15700, 15751, -1, 15662, 15759, 15674, -1, 15706, 15705, 15753, -1, 15665, 15537, 15617, -1, 15668, 15671, 15669, -1, 15662, 15664, 15759, -1, 15665, 15617, 15754, -1, 15662, 15680, 15663, -1, 15665, 15754, 15666, -1, 15668, 15616, 15618, -1, 15760, 15581, 15761, -1, 15762, 15763, 15764, -1, 15760, 15765, 15766, -1, 15762, 15767, 15763, -1, 15768, 15769, 15770, -1, 15771, 15772, 15773, -1, 15768, 15770, 15774, -1, 15775, 15774, 15776, -1, 15579, 15580, 15777, -1, 15771, 15764, 15772, -1, 15778, 15773, 15779, -1, 15780, 15781, 15782, -1, 15775, 15776, 15783, -1, 15780, 15784, 15781, -1, 15785, 15783, 15786, -1, 15778, 15779, 15787, -1, 15785, 15786, 15788, -1, 15789, 15787, 15790, -1, 15789, 15790, 15791, -1, 15792, 15793, 15784, -1, 15792, 15784, 15780, -1, 15794, 15788, 15795, -1, 15794, 15795, 15796, -1, 15797, 15798, 15799, -1, 15800, 15782, 15801, -1, 15797, 15791, 15798, -1, 15802, 15803, 15804, -1, 15802, 15796, 15803, -1, 15800, 15780, 15782, -1, 15805, 15767, 15762, -1, 15806, 15793, 15792, -1, 15805, 15585, 15586, -1, 15807, 15597, 15596, -1, 15805, 15586, 15808, -1, 15806, 15809, 15793, -1, 15805, 15808, 15767, -1, 15807, 15810, 15769, -1, 15811, 15764, 15771, -1, 15807, 15769, 15768, -1, 15807, 15596, 15810, -1, 15811, 15762, 15764, -1, 15812, 15780, 15800, -1, 15813, 15771, 15773, -1, 15814, 15774, 15775, -1, 15814, 15768, 15774, -1, 15813, 15773, 15778, -1, 15812, 15792, 15780, -1, 15815, 15775, 15783, -1, 15816, 15801, 15817, -1, 15818, 15778, 15787, -1, 15815, 15783, 15785, -1, 15818, 15787, 15789, -1, 15816, 15800, 15801, -1, 15819, 15785, 15788, -1, 15820, 15821, 15809, -1, 15819, 15788, 15794, -1, 15820, 15809, 15806, -1, 15822, 15806, 15792, -1, 15823, 15791, 15797, -1, 15823, 15789, 15791, -1, 15824, 15796, 15802, -1, 15825, 15799, 15826, -1, 15825, 15797, 15799, -1, 15824, 15794, 15796, -1, 15822, 15792, 15812, -1, 15825, 15826, 15827, -1, 15828, 15829, 15830, -1, 15828, 15804, 15829, -1, 15831, 15805, 15762, -1, 15831, 15762, 15811, -1, 15831, 15584, 15585, -1, 15831, 15585, 15805, -1, 15828, 15802, 15804, -1, 15832, 15812, 15800, -1, 15832, 15800, 15816, -1, 15833, 15599, 15597, -1, 15833, 15597, 15807, -1, 15834, 15771, 15813, -1, 15833, 15807, 15768, -1, 15833, 15768, 15814, -1, 15835, 15817, 15836, -1, 15835, 15816, 15817, -1, 15834, 15811, 15771, -1, 15837, 15775, 15815, -1, 15837, 15814, 15775, -1, 15838, 15778, 15818, -1, 15838, 15813, 15778, -1, 15839, 15840, 15821, -1, 15839, 15821, 15820, -1, 15763, 15785, 15819, -1, 15763, 15815, 15785, -1, 15770, 15820, 15806, -1, 15841, 15818, 15789, -1, 15841, 15789, 15823, -1, 15770, 15806, 15822, -1, 15842, 15827, 15843, -1, 15772, 15819, 15794, -1, 15776, 15812, 15832, -1, 15772, 15794, 15824, -1, 15842, 15823, 15797, -1, 15842, 15825, 15827, -1, 15779, 15824, 15802, -1, 15842, 15797, 15825, -1, 15776, 15822, 15812, -1, 15844, 15583, 15584, -1, 15786, 15816, 15835, -1, 15844, 15811, 15834, -1, 15844, 15584, 15831, -1, 15779, 15802, 15828, -1, 15844, 15831, 15811, -1, 15786, 15832, 15816, -1, 15790, 15830, 15845, -1, 15846, 15834, 15813, -1, 15846, 15813, 15838, -1, 15790, 15828, 15830, -1, 15795, 15836, 15847, -1, 15848, 15587, 15599, -1, 15795, 15835, 15836, -1, 15848, 15599, 15833, -1, 15849, 15594, 15593, -1, 15850, 15838, 15818, -1, 15848, 15833, 15814, -1, 15850, 15818, 15841, -1, 15848, 15814, 15837, -1, 15849, 15851, 15840, -1, 15849, 15593, 15851, -1, 15849, 15840, 15839, -1, 15852, 15843, 15853, -1, 15767, 15837, 15815, -1, 15767, 15815, 15763, -1, 15852, 15842, 15843, -1, 15852, 15823, 15842, -1, 15852, 15841, 15823, -1, 15769, 15839, 15820, -1, 15854, 15582, 15583, -1, 15764, 15763, 15819, -1, 15764, 15819, 15772, -1, 15769, 15820, 15770, -1, 15854, 15583, 15844, -1, 15854, 15844, 15834, -1, 15854, 15834, 15846, -1, 15774, 15770, 15822, -1, 15774, 15822, 15776, -1, 15773, 15772, 15824, -1, 15773, 15824, 15779, -1, 15855, 15846, 15838, -1, 15855, 15838, 15850, -1, 15783, 15832, 15786, -1, 15856, 15853, 15857, -1, 15783, 15776, 15832, -1, 15856, 15852, 15853, -1, 15856, 15850, 15841, -1, 15856, 15841, 15852, -1, 15788, 15786, 15835, -1, 15787, 15779, 15828, -1, 15761, 15581, 15582, -1, 15787, 15828, 15790, -1, 15788, 15835, 15795, -1, 15761, 15582, 15854, -1, 15791, 15845, 15798, -1, 15761, 15854, 15846, -1, 15761, 15846, 15855, -1, 15765, 15855, 15850, -1, 15765, 15857, 15766, -1, 15791, 15790, 15845, -1, 15796, 15847, 15803, -1, 15808, 15586, 15587, -1, 15765, 15850, 15856, -1, 15808, 15848, 15837, -1, 15796, 15795, 15847, -1, 15810, 15596, 15594, -1, 15765, 15856, 15857, -1, 15808, 15837, 15767, -1, 15760, 15766, 15777, -1, 15808, 15587, 15848, -1, 15810, 15849, 15839, -1, 15760, 15777, 15580, -1, 15760, 15855, 15765, -1, 15810, 15839, 15769, -1, 15760, 15761, 15855, -1, 15760, 15580, 15581, -1, 15810, 15594, 15849, -1, 13746, 15858, 15859, -1, 13739, 15860, 11715, -1, 15861, 11729, 11730, -1, 15861, 11730, 11731, -1, 15861, 11731, 11732, -1, 15861, 11732, 11733, -1, 13745, 13746, 15859, -1, 13745, 15859, 15862, -1, 11728, 11729, 15861, -1, 11727, 11728, 15861, -1, 13740, 15860, 13739, -1, 11726, 11727, 15861, -1, 13740, 15863, 15860, -1, 13744, 13745, 15862, -1, 13744, 15862, 15864, -1, 13741, 15863, 13740, -1, 13741, 15865, 15866, -1, 13741, 15866, 15863, -1, 13743, 15864, 15867, -1, 13743, 13744, 15864, -1, 11719, 15249, 11720, -1, 13742, 15867, 15865, -1, 11721, 11720, 15249, -1, 13742, 15865, 13741, -1, 13742, 13743, 15867, -1, 15861, 15868, 11725, -1, 15861, 11725, 11726, -1, 15860, 15249, 11715, -1, 11715, 15249, 11716, -1, 11716, 15249, 11717, -1, 11718, 15249, 11719, -1, 11722, 11721, 15249, -1, 11717, 15249, 11718, -1, 11723, 11722, 15249, -1, 11724, 11723, 15249, -1, 15868, 13738, 11725, -1, 13751, 13738, 15868, -1, 15869, 13751, 15868, -1, 13750, 13751, 15869, -1, 15870, 13750, 15869, -1, 13749, 13750, 15870, -1, 15871, 13749, 15870, -1, 13748, 15871, 15872, -1, 13748, 13749, 15871, -1, 13747, 13748, 15872, -1, 13747, 15872, 15858, -1, 13746, 13747, 15858, -1, 8072, 8110, 15539, -1, 15538, 8072, 15539, -1, 15110, 9662, 8072, -1, 15110, 8072, 15538, -1, 15287, 15271, 15270, -1, 15281, 15873, 15874, -1, 15275, 15873, 15281, -1, 15275, 15875, 15873, -1, 15874, 15876, 15877, -1, 15874, 15873, 15876, -1, 15873, 15878, 15876, -1, 15879, 15877, 15876, -1, 15879, 15880, 15877, -1, 15881, 15879, 15882, -1, 15880, 15881, 15883, -1, 15880, 15879, 15881, -1, 15884, 15885, 15881, -1, 15882, 15884, 15881, -1, 15886, 15884, 15882, -1, 15886, 15887, 15884, -1, 15885, 15883, 15881, -1, 15888, 15889, 15890, -1, 15891, 15892, 15889, -1, 15893, 15894, 15888, -1, 15888, 15894, 15889, -1, 15889, 15894, 15891, -1, 15894, 15895, 15891, -1, 15896, 15266, 15895, -1, 15895, 15266, 15891, -1, 15896, 15262, 15266, -1, 15888, 15897, 15893, -1, 15898, 15897, 15888, -1, 15899, 15898, 15900, -1, 15899, 15900, 15901, -1, 15902, 15898, 15899, -1, 15903, 15899, 15901, -1, 15904, 15899, 15903, -1, 15897, 15898, 15902, -1, 15905, 15904, 15903, -1, 15906, 15897, 15902, -1, 15907, 15908, 15909, -1, 15910, 15908, 15907, -1, 15911, 15907, 15912, -1, 15913, 15911, 15912, -1, 15913, 15912, 15905, -1, 15914, 15911, 15913, -1, 15911, 15910, 15907, -1, 15915, 15908, 15910, -1, 15912, 15904, 15905, -1, 15915, 15261, 15262, -1, 15915, 15262, 15896, -1, 15908, 15915, 15896, -1, 15916, 15917, 15918, -1, 15916, 15919, 15917, -1, 15916, 15920, 15919, -1, 15916, 15921, 15920, -1, 15916, 15922, 15921, -1, 15916, 15923, 15922, -1, 15916, 15924, 15923, -1, 15916, 15918, 15925, -1, 15926, 15927, 15913, -1, 15916, 15928, 15924, -1, 15916, 15925, 15929, -1, 15916, 15930, 15928, -1, 15914, 15913, 15927, -1, 15928, 15930, 15931, -1, 15929, 15932, 15914, -1, 15929, 15914, 15927, -1, 15933, 15934, 15932, -1, 15933, 15935, 15934, -1, 15936, 15934, 15935, -1, 15937, 15933, 15932, -1, 15938, 15928, 15934, -1, 15938, 15934, 15936, -1, 15939, 15937, 15932, -1, 15940, 15928, 15938, -1, 15941, 15939, 15932, -1, 15942, 15928, 15940, -1, 15943, 15941, 15932, -1, 15944, 15928, 15942, -1, 15945, 15943, 15932, -1, 15946, 15928, 15944, -1, 15947, 15932, 15929, -1, 15947, 15945, 15932, -1, 15948, 15928, 15946, -1, 15949, 15947, 15929, -1, 15950, 15928, 15948, -1, 15925, 15949, 15929, -1, 15924, 15928, 15950, -1, 15940, 15938, 15951, -1, 15951, 15938, 15952, -1, 15952, 15936, 15953, -1, 15938, 15936, 15952, -1, 15953, 15935, 15954, -1, 15936, 15935, 15953, -1, 15954, 15933, 15955, -1, 15935, 15933, 15954, -1, 15955, 15937, 15956, -1, 15933, 15937, 15955, -1, 15956, 15939, 15957, -1, 15937, 15939, 15956, -1, 15957, 15941, 15958, -1, 15939, 15941, 15957, -1, 15958, 15943, 15959, -1, 15941, 15943, 15958, -1, 15959, 15945, 15960, -1, 15943, 15945, 15959, -1, 15960, 15947, 15961, -1, 15945, 15947, 15960, -1, 15961, 15949, 15962, -1, 15947, 15949, 15961, -1, 15962, 15925, 15963, -1, 15949, 15925, 15962, -1, 15963, 15918, 15964, -1, 15925, 15918, 15963, -1, 15965, 15929, 15966, -1, 15965, 15916, 15929, -1, 15967, 15968, 15969, -1, 15970, 15968, 15967, -1, 15970, 15971, 15968, -1, 15968, 15972, 15969, -1, 15968, 15973, 15972, -1, 15970, 15974, 15971, -1, 15974, 15975, 15971, -1, 15976, 15977, 15978, -1, 15973, 15979, 15972, -1, 15976, 15980, 15977, -1, 15977, 15981, 15979, -1, 15979, 15934, 15972, -1, 15981, 15934, 15979, -1, 15981, 15932, 15934, -1, 15976, 15982, 15980, -1, 15980, 15981, 15977, -1, 15983, 15982, 15984, -1, 15985, 15983, 15984, -1, 15986, 15982, 15976, -1, 15986, 15984, 15982, -1, 15987, 15986, 15976, -1, 15988, 15989, 15974, -1, 15988, 15974, 15970, -1, 15990, 15991, 15992, -1, 15990, 15992, 15993, -1, 15990, 15993, 15994, -1, 15990, 15994, 15995, -1, 15990, 15996, 15991, -1, 15997, 15998, 15999, -1, 15988, 15998, 15997, -1, 16000, 15988, 16001, -1, 16002, 15997, 16003, -1, 16004, 15988, 16000, -1, 16005, 15997, 16002, -1, 16006, 15988, 16004, -1, 16007, 16008, 16009, -1, 16007, 15990, 15995, -1, 16007, 15995, 16010, -1, 16007, 16010, 16011, -1, 16007, 16011, 16012, -1, 16007, 16012, 16013, -1, 16007, 16013, 16014, -1, 16007, 16014, 16008, -1, 15989, 16006, 16015, -1, 15989, 15988, 16006, -1, 16016, 15989, 16015, -1, 16017, 16016, 16015, -1, 15997, 16018, 16019, -1, 15997, 16019, 16020, -1, 15997, 16020, 16003, -1, 16021, 15988, 15997, -1, 16022, 15988, 16021, -1, 16023, 16005, 16024, -1, 16023, 15997, 16005, -1, 16023, 16021, 15997, -1, 16025, 15988, 16022, -1, 16009, 16026, 16027, -1, 16009, 16027, 16028, -1, 16009, 16028, 16029, -1, 16030, 16026, 16009, -1, 16031, 15988, 16025, -1, 15996, 16024, 15991, -1, 15996, 16023, 16024, -1, 16032, 16030, 16009, -1, 16001, 15988, 16031, -1, 16008, 16032, 16009, -1, 16024, 16033, 16034, -1, 16024, 16005, 16033, -1, 15991, 16034, 16035, -1, 15991, 16024, 16034, -1, 15992, 16035, 16036, -1, 15992, 15991, 16035, -1, 15993, 16036, 16037, -1, 15993, 15992, 16036, -1, 15994, 16037, 16038, -1, 15994, 15993, 16037, -1, 15995, 16038, 16039, -1, 15995, 15994, 16038, -1, 16010, 16039, 16040, -1, 16010, 15995, 16039, -1, 16011, 16040, 16041, -1, 16011, 16010, 16040, -1, 16012, 16041, 16042, -1, 16012, 16011, 16041, -1, 16013, 16042, 16043, -1, 16013, 16012, 16042, -1, 16014, 16043, 16044, -1, 16014, 16013, 16043, -1, 16008, 16045, 16046, -1, 16008, 16044, 16045, -1, 16008, 16014, 16044, -1, 16032, 16008, 16046, -1, 15972, 15997, 15969, -1, 16047, 15997, 15972, -1, 16018, 15997, 16047, -1, 16048, 16018, 16047, -1, 16049, 16048, 16047, -1, 16050, 16049, 16047, -1, 16051, 16050, 16047, -1, 16009, 16029, 16052, -1, 16009, 16052, 16053, -1, 16054, 16055, 16056, -1, 16054, 16056, 16009, -1, 16054, 16009, 16053, -1, 16047, 16057, 16054, -1, 16047, 16054, 16053, -1, 16047, 16053, 16051, -1, 16058, 16059, 16060, -1, 16061, 16062, 16063, -1, 16064, 16065, 16066, -1, 16067, 16068, 16069, -1, 16061, 16058, 16062, -1, 16070, 16071, 16072, -1, 16072, 16071, 16073, -1, 16074, 16054, 16057, -1, 16073, 16071, 16075, -1, 16075, 16071, 16076, -1, 16077, 16068, 16067, -1, 16076, 16071, 16078, -1, 16075, 16076, 16079, -1, 16080, 16065, 16064, -1, 16081, 16074, 16057, -1, 16075, 16079, 16082, -1, 16075, 16082, 16083, -1, 16084, 16081, 16057, -1, 16085, 16081, 16084, -1, 16086, 16085, 16084, -1, 16087, 16086, 16084, -1, 16088, 16087, 16084, -1, 16089, 16088, 16084, -1, 16090, 16091, 16092, -1, 16090, 16092, 16093, -1, 16094, 16088, 16089, -1, 16090, 16093, 16095, -1, 16090, 16095, 16096, -1, 16094, 16089, 16070, -1, 16090, 16096, 16097, -1, 16090, 16097, 16098, -1, 16090, 16098, 16075, -1, 16099, 16094, 16070, -1, 16100, 16088, 16094, -1, 16083, 16090, 16075, -1, 16101, 16077, 16102, -1, 16101, 16102, 16103, -1, 16101, 16103, 16104, -1, 16101, 16104, 16091, -1, 16071, 16105, 16078, -1, 16101, 16091, 16090, -1, 16071, 16106, 16105, -1, 16101, 16068, 16077, -1, 16107, 16108, 16100, -1, 16071, 16109, 16106, -1, 16071, 16110, 16109, -1, 16071, 16111, 16110, -1, 16112, 16107, 16100, -1, 16113, 16100, 16094, -1, 16082, 16114, 16083, -1, 16113, 16112, 16100, -1, 16115, 16113, 16094, -1, 16116, 16111, 16071, -1, 16116, 16117, 16118, -1, 16119, 16114, 16082, -1, 16116, 16120, 16117, -1, 16116, 16121, 16120, -1, 16122, 16123, 16070, -1, 16116, 16118, 16111, -1, 16124, 16070, 16123, -1, 16125, 16116, 16071, -1, 16125, 16071, 16126, -1, 16127, 16128, 16129, -1, 16130, 16122, 16070, -1, 16131, 16099, 16070, -1, 16132, 16129, 16128, -1, 16131, 16070, 16124, -1, 16133, 16065, 16080, -1, 16133, 16121, 16116, -1, 16079, 16127, 16129, -1, 16072, 16130, 16070, -1, 16133, 16134, 16121, -1, 16079, 16129, 16082, -1, 16133, 16135, 16134, -1, 16133, 16136, 16135, -1, 16133, 16080, 16136, -1, 16137, 16099, 16131, -1, 16138, 16129, 16132, -1, 16139, 16140, 16125, -1, 16141, 16129, 16138, -1, 16142, 16099, 16137, -1, 16143, 16099, 16142, -1, 16144, 16129, 16141, -1, 16145, 16146, 16139, -1, 16145, 16147, 16146, -1, 16145, 16148, 16147, -1, 16149, 16068, 16099, -1, 16145, 16139, 16125, -1, 16150, 16065, 16129, -1, 16150, 16129, 16144, -1, 16149, 16099, 16143, -1, 16151, 16126, 16060, -1, 16151, 16125, 16126, -1, 16151, 16145, 16125, -1, 16152, 16151, 16060, -1, 16153, 16068, 16149, -1, 16154, 16065, 16150, -1, 16155, 16152, 16060, -1, 16069, 16068, 16153, -1, 16059, 16155, 16060, -1, 16066, 16065, 16154, -1, 16058, 16060, 16062, -1, 16118, 16156, 16157, -1, 16111, 16157, 16158, -1, 16111, 16118, 16157, -1, 16110, 16158, 16159, -1, 16110, 16111, 16158, -1, 16109, 16159, 16160, -1, 16109, 16110, 16159, -1, 16106, 16160, 16161, -1, 16106, 16109, 16160, -1, 16105, 16161, 16162, -1, 16105, 16106, 16161, -1, 16078, 16162, 16163, -1, 16078, 16105, 16162, -1, 16076, 16163, 16164, -1, 16076, 16164, 16165, -1, 16076, 16078, 16163, -1, 16079, 16165, 16166, -1, 16079, 16076, 16165, -1, 16127, 16166, 16167, -1, 16127, 16079, 16166, -1, 16128, 16167, 16168, -1, 16128, 16127, 16167, -1, 16132, 16168, 16169, -1, 16132, 16128, 16168, -1, 16138, 16169, 16170, -1, 16138, 16132, 16169, -1, 16141, 16170, 16171, -1, 16141, 16138, 16170, -1, 16142, 16172, 16173, -1, 16142, 16137, 16172, -1, 16143, 16173, 16174, -1, 16143, 16142, 16173, -1, 16149, 16174, 16175, -1, 16149, 16143, 16174, -1, 16153, 16175, 16176, -1, 16153, 16149, 16175, -1, 16069, 16176, 16177, -1, 16069, 16153, 16176, -1, 16067, 16177, 16178, -1, 16067, 16069, 16177, -1, 16077, 16178, 16179, -1, 16077, 16067, 16178, -1, 16102, 16179, 16180, -1, 16102, 16077, 16179, -1, 16103, 16180, 16181, -1, 16103, 16102, 16180, -1, 16104, 16181, 16182, -1, 16104, 16103, 16181, -1, 16091, 16182, 16183, -1, 16091, 16104, 16182, -1, 16092, 16184, 16185, -1, 16092, 16183, 16184, -1, 16092, 16091, 16183, -1, 16093, 16092, 16185, -1, 16186, 16187, 16188, -1, 16189, 16190, 16084, -1, 16189, 16191, 16190, -1, 16192, 16193, 16194, -1, 16192, 16194, 16195, -1, 16196, 16060, 16126, -1, 16192, 16195, 16197, -1, 16196, 16126, 16192, -1, 16192, 16197, 16163, -1, 16163, 16197, 16164, -1, 16164, 16197, 16165, -1, 16165, 16197, 16198, -1, 16199, 16196, 16192, -1, 16198, 16197, 16200, -1, 16161, 16199, 16192, -1, 16162, 16161, 16192, -1, 16163, 16162, 16192, -1, 16201, 16060, 16196, -1, 16202, 16201, 16196, -1, 16203, 16161, 16166, -1, 16203, 16199, 16161, -1, 16204, 16166, 16165, -1, 16198, 16204, 16165, -1, 16205, 16166, 16204, -1, 16205, 16203, 16166, -1, 16206, 16207, 16198, -1, 16206, 16198, 16200, -1, 16188, 16187, 16208, -1, 16197, 16208, 16200, -1, 16197, 16188, 16208, -1, 16193, 16209, 16210, -1, 16193, 16210, 16194, -1, 16211, 16209, 16193, -1, 16190, 16193, 16089, -1, 16190, 16211, 16193, -1, 16084, 16190, 16089, -1, 16186, 16209, 16211, -1, 16186, 16188, 16209, -1, 16212, 16213, 16207, -1, 16214, 16213, 16212, -1, 16215, 16207, 16206, -1, 16215, 16212, 16207, -1, 16216, 16217, 16215, -1, 16216, 16215, 16206, -1, 16186, 16218, 16187, -1, 16219, 16218, 16186, -1, 16220, 16221, 16222, -1, 16219, 16220, 16222, -1, 16223, 16218, 16219, -1, 16223, 16219, 16222, -1, 16224, 16218, 16223, -1, 15934, 16047, 15972, -1, 15934, 15928, 16047, -1, 2703, 2706, 16225, -1, 16226, 16227, 16228, -1, 2762, 16229, 16230, -1, 2766, 16230, 16231, -1, 2766, 2762, 16230, -1, 2767, 16232, 16233, -1, 2767, 16231, 16232, -1, 2767, 2766, 16231, -1, 2768, 16233, 16234, -1, 2768, 2767, 16233, -1, 16228, 16227, 16235, -1, 2748, 16236, 16235, -1, 2748, 16234, 16236, -1, 2748, 2768, 16234, -1, 16237, 16226, 16228, -1, 2746, 16235, 16227, -1, 2746, 2748, 16235, -1, 16238, 2746, 16227, -1, 16239, 16226, 16237, -1, 16240, 16239, 16237, -1, 2749, 16238, 16241, -1, 2749, 2746, 16238, -1, 16242, 16240, 16243, -1, 16242, 16239, 16240, -1, 16244, 2749, 16241, -1, 2750, 2749, 16244, -1, 16245, 16242, 16243, -1, 16246, 2750, 16244, -1, 2751, 16246, 16242, -1, 2751, 2750, 16246, -1, 2751, 16242, 16245, -1, 2752, 2751, 16245, -1, 2752, 16245, 16247, -1, 2753, 16247, 16248, -1, 2753, 2752, 16247, -1, 2710, 16248, 16249, -1, 2710, 2753, 16248, -1, 2706, 16249, 16225, -1, 2706, 2710, 16249, -1, 16250, 16236, 16234, -1, 16234, 16233, 16250, -1, 16250, 16235, 16236, -1, 16233, 16232, 16250, -1, 16250, 16228, 16235, -1, 16232, 16231, 16250, -1, 16250, 16237, 16228, -1, 16231, 16230, 16250, -1, 16230, 16229, 16250, -1, 16229, 16251, 16250, -1, 16229, 16252, 16251, -1, 16249, 16253, 16225, -1, 16248, 16253, 16249, -1, 16247, 16253, 16248, -1, 16245, 16253, 16247, -1, 16243, 16253, 16245, -1, 16240, 16253, 16243, -1, 16225, 16254, 16255, -1, 16253, 16254, 16225, -1, 16250, 16253, 16237, -1, 16237, 16253, 16240, -1, 16256, 16257, 16250, -1, 16256, 16250, 16251, -1, 16258, 16259, 16260, -1, 16261, 16262, 16263, -1, 16261, 16263, 16259, -1, 16257, 16256, 16261, -1, 16257, 16261, 16259, -1, 16257, 16259, 16258, -1, 16253, 16264, 16254, -1, 16265, 16264, 16253, -1, 16266, 16267, 16268, -1, 16265, 16268, 16264, -1, 16269, 16266, 16268, -1, 16269, 16268, 16265, -1, 16270, 16269, 16271, -1, 16272, 16269, 16270, -1, 16273, 16269, 16272, -1, 16266, 16269, 16273, -1, 16274, 16270, 16271, -1, 16275, 16260, 16276, -1, 16258, 16260, 16275, -1, 16275, 16277, 16278, -1, 16275, 16276, 16277, -1, 16226, 16279, 16227, -1, 16280, 16279, 16226, -1, 16239, 16280, 16226, -1, 16242, 16280, 16239, -1, 16278, 16281, 16282, -1, 16278, 16277, 16281, -1, 16283, 16284, 16285, -1, 16286, 16287, 16288, -1, 16286, 16288, 16284, -1, 16282, 16281, 16286, -1, 16282, 16286, 16284, -1, 16282, 16284, 16283, -1, 16285, 16289, 16283, -1, 16290, 16289, 16285, -1, 16291, 16292, 16293, -1, 16293, 16294, 16291, -1, 16291, 16295, 16292, -1, 16294, 16296, 16291, -1, 16291, 16297, 16295, -1, 16296, 16298, 16291, -1, 16298, 16299, 16291, -1, 16298, 16300, 16299, -1, 16301, 16289, 16302, -1, 16302, 16289, 16303, -1, 16303, 16289, 16304, -1, 16304, 16289, 16305, -1, 16305, 16289, 16306, -1, 16306, 16289, 16307, -1, 16307, 16289, 16308, -1, 16308, 16289, 16309, -1, 16309, 16289, 16310, -1, 16310, 16290, 16311, -1, 16289, 16290, 16310, -1, 16291, 16289, 16301, -1, 16291, 16301, 16297, -1, 16291, 16312, 16313, -1, 16291, 16299, 16312, -1, 16314, 16315, 16316, -1, 16314, 16317, 16315, -1, 16313, 16312, 16314, -1, 16313, 16314, 16316, -1, 16318, 16316, 16315, -1, 16318, 16319, 16316, -1, 16319, 16320, 16316, -1, 16320, 16321, 16316, -1, 16321, 16320, 16322, -1, 16246, 16323, 16242, -1, 16323, 16280, 16242, -1, 16324, 16325, 16326, -1, 16327, 16325, 16328, -1, 16327, 16329, 16325, -1, 16325, 16330, 16326, -1, 16329, 16330, 16325, -1, 16327, 16331, 16329, -1, 16246, 16325, 16323, -1, 16323, 16325, 16324, -1, 16331, 16332, 16333, -1, 16327, 16332, 16331, -1, 16334, 16333, 16332, -1, 16334, 16335, 16333, -1, 16328, 16336, 16337, -1, 16328, 16325, 16336, -1, 16338, 16238, 16227, -1, 16279, 16338, 16227, -1, 16336, 16339, 16340, -1, 16336, 16341, 16337, -1, 16342, 16341, 16336, -1, 16343, 16336, 16340, -1, 16343, 16342, 16336, -1, 16344, 16341, 16342, -1, 16336, 16238, 16338, -1, 16336, 16338, 16339, -1, 16345, 16341, 16344, -1, 16345, 16344, 16346, -1, 16347, 16348, 16345, -1, 16349, 16345, 16346, -1, 16349, 16347, 16345, -1, 16350, 16347, 16349, -1, 16351, 16352, 16347, -1, 16351, 16347, 16350, -1, 16353, 16354, 16355, -1, 16353, 16356, 16354, -1, 16356, 16347, 16354, -1, 16354, 16347, 16352, -1, 16357, 16358, 16359, -1, 16355, 16358, 16357, -1, 16360, 16355, 16357, -1, 16353, 16355, 16360, -1, 16348, 16361, 16362, -1, 16348, 16347, 16361, -1, 16362, 16361, 16363, -1, 16363, 16364, 16365, -1, 16361, 16364, 16363, -1, 16361, 16366, 16364, -1, 16367, 16368, 16361, -1, 16361, 16368, 16366, -1, 16369, 16359, 16358, -1, 16370, 16359, 16369, -1, 16361, 16370, 16369, -1, 16361, 16369, 16367, -1, 16365, 16371, 16372, -1, 16365, 16372, 16363, -1, 16371, 16373, 16374, -1, 16372, 16371, 16374, -1, 16375, 16333, 16335, -1, 16331, 16333, 16329, -1, 16375, 16376, 16333, -1, 16333, 16376, 16329, -1, 16377, 16375, 16378, -1, 16376, 16375, 16377, -1, 16377, 16379, 16380, -1, 16377, 16380, 16381, -1, 16382, 16377, 16378, -1, 16382, 16379, 16377, -1, 16379, 16383, 16384, -1, 16379, 16382, 16383, -1, 16383, 16385, 16384, -1, 16386, 16385, 16383, -1, 16387, 16330, 16329, -1, 16376, 16377, 16381, -1, 16376, 16381, 16387, -1, 16329, 16376, 16387, -1, 16388, 16389, 16390, -1, 16391, 16389, 16388, -1, 16389, 15887, 16390, -1, 15887, 16392, 16390, -1, 15887, 16393, 16392, -1, 16394, 16395, 16396, -1, 16397, 16395, 16394, -1, 16398, 16395, 16397, -1, 16399, 16395, 16398, -1, 16400, 16395, 16399, -1, 16401, 16395, 16400, -1, 16402, 16395, 16401, -1, 16403, 16395, 16402, -1, 16393, 16395, 16403, -1, 16395, 15886, 16404, -1, 15887, 15886, 16393, -1, 16393, 15886, 16395, -1, 16398, 16405, 16406, -1, 16398, 16406, 16407, -1, 16398, 16407, 16408, -1, 16399, 16408, 16409, -1, 16399, 16398, 16408, -1, 16400, 16409, 16410, -1, 16400, 16399, 16409, -1, 16401, 16410, 16411, -1, 16401, 16400, 16410, -1, 16402, 16411, 16412, -1, 16402, 16401, 16411, -1, 16403, 16412, 16413, -1, 16403, 16402, 16412, -1, 16393, 16413, 16414, -1, 16393, 16403, 16413, -1, 16392, 16414, 16415, -1, 16392, 16393, 16414, -1, 16390, 16415, 16416, -1, 16390, 16392, 16415, -1, 16388, 16416, 16417, -1, 16388, 16417, 16418, -1, 16388, 16390, 16416, -1, 16391, 16418, 16419, -1, 16391, 16419, 16420, -1, 16391, 16388, 16418, -1, 16421, 16391, 16420, -1, 16422, 16420, 16423, -1, 16422, 16421, 16420, -1, 16424, 16423, 16425, -1, 16424, 16422, 16423, -1, 16426, 16425, 16427, -1, 16426, 16424, 16425, -1, 16428, 16427, 16429, -1, 16428, 16426, 16427, -1, 16430, 16429, 16431, -1, 16430, 16428, 16429, -1, 16432, 16430, 16431, -1, 16433, 16434, 16435, -1, 16436, 16433, 16435, -1, 16437, 16433, 16436, -1, 16438, 16437, 16436, -1, 16439, 16438, 16440, -1, 16439, 16437, 16438, -1, 16394, 16440, 16441, -1, 16394, 16396, 16439, -1, 16394, 16439, 16440, -1, 16397, 16441, 16405, -1, 16397, 16394, 16441, -1, 16398, 16397, 16405, -1, 16442, 16443, 16444, -1, 16442, 16445, 16443, -1, 16446, 16444, 16447, -1, 16446, 16448, 16442, -1, 16446, 16442, 16444, -1, 16449, 16447, 16405, -1, 16449, 16440, 16438, -1, 16449, 16441, 16440, -1, 16449, 16405, 16441, -1, 16449, 16438, 16448, -1, 16449, 16446, 16447, -1, 16449, 16448, 16446, -1, 16450, 16404, 16451, -1, 16450, 16395, 16404, -1, 16452, 16453, 16454, -1, 16455, 16453, 16452, -1, 16456, 16453, 16455, -1, 16395, 16434, 16433, -1, 16395, 16433, 16437, -1, 16395, 16437, 16439, -1, 16395, 16439, 16396, -1, 16457, 16456, 16458, -1, 16457, 16458, 16434, -1, 16457, 16453, 16456, -1, 16450, 16457, 16434, -1, 16450, 16434, 16395, -1, 16459, 16460, 16453, -1, 16457, 16459, 16453, -1, 16461, 16462, 16463, -1, 16463, 16464, 16465, -1, 16465, 16464, 16466, -1, 16462, 16464, 16463, -1, 16466, 16467, 16458, -1, 16464, 16467, 16466, -1, 16467, 16468, 16458, -1, 16468, 16469, 16458, -1, 16470, 16434, 16469, -1, 16469, 16434, 16458, -1, 16471, 16435, 16470, -1, 16470, 16435, 16434, -1, 16471, 16436, 16435, -1, 16471, 16438, 16436, -1, 16472, 16473, 16474, -1, 16474, 16473, 16475, -1, 16476, 16477, 16472, -1, 16472, 16477, 16473, -1, 16478, 16479, 16476, -1, 16476, 16479, 16477, -1, 16431, 16480, 16478, -1, 16429, 16480, 16431, -1, 16478, 16480, 16479, -1, 16427, 16481, 16429, -1, 16429, 16481, 16480, -1, 16425, 16482, 16427, -1, 16427, 16482, 16481, -1, 16423, 16483, 16425, -1, 16425, 16483, 16482, -1, 16423, 16420, 16483, -1, 16462, 16484, 16485, -1, 16464, 16485, 16486, -1, 16464, 16462, 16485, -1, 16467, 16486, 16487, -1, 16467, 16464, 16486, -1, 16468, 16487, 16488, -1, 16468, 16467, 16487, -1, 16469, 16488, 16489, -1, 16469, 16468, 16488, -1, 16470, 16489, 16490, -1, 16470, 16469, 16489, -1, 16471, 16470, 16490, -1, 16483, 16491, 16492, -1, 16482, 16492, 16493, -1, 16482, 16483, 16492, -1, 16481, 16493, 16494, -1, 16481, 16482, 16493, -1, 16480, 16494, 16495, -1, 16480, 16481, 16494, -1, 16479, 16480, 16495, -1, 16477, 16495, 16496, -1, 16477, 16479, 16495, -1, 16473, 16496, 16497, -1, 16473, 16477, 16496, -1, 16417, 16416, 16498, -1, 16498, 16415, 16499, -1, 16416, 16415, 16498, -1, 16499, 16414, 16500, -1, 16415, 16414, 16499, -1, 16501, 16409, 16408, -1, 16500, 16413, 16502, -1, 16414, 16413, 16500, -1, 16503, 16410, 16501, -1, 16501, 16410, 16409, -1, 16502, 16412, 16504, -1, 16413, 16412, 16502, -1, 16504, 16411, 16503, -1, 16412, 16411, 16504, -1, 16503, 16411, 16410, -1, 16501, 16505, 16506, -1, 16503, 16506, 16507, -1, 16503, 16501, 16506, -1, 16504, 16507, 16508, -1, 16504, 16503, 16507, -1, 16502, 16508, 16509, -1, 16502, 16504, 16508, -1, 16500, 16509, 16510, -1, 16500, 16502, 16509, -1, 16499, 16500, 16510, -1, 16498, 16510, 16511, -1, 16498, 16499, 16510, -1, 16512, 16513, 16514, -1, 16515, 15985, 16513, -1, 16516, 15985, 16515, -1, 16513, 15985, 16514, -1, 16516, 15021, 15985, -1, 15021, 15983, 15985, -1, 15021, 15022, 15983, -1, 16517, 16017, 16015, -1, 15986, 16017, 16517, -1, 15984, 15986, 16517, -1, 16518, 15266, 15268, -1, 15891, 15266, 16518, -1, 15272, 2651, 15276, -1, 2649, 2651, 15272, -1, 16519, 16453, 16460, -1, 16519, 16520, 16521, -1, 16521, 16522, 16519, -1, 16519, 16522, 16453, -1, 16519, 16523, 16520, -1, 16522, 16524, 16453, -1, 16519, 16525, 16523, -1, 16524, 16526, 16453, -1, 16526, 16454, 16453, -1, 16525, 16527, 16432, -1, 16519, 16527, 16525, -1, 16527, 16430, 16432, -1, 16527, 16428, 16430, -1, 16527, 16426, 16428, -1, 16527, 16424, 16426, -1, 16424, 16391, 16421, -1, 16424, 16421, 16422, -1, 16528, 16529, 16530, -1, 16531, 3035, 16529, -1, 16531, 16528, 16532, -1, 16531, 16529, 16528, -1, 16533, 3035, 16531, -1, 16534, 2795, 3409, -1, 16535, 3413, 3038, -1, 16535, 3411, 3413, -1, 16535, 3038, 16533, -1, 16536, 16535, 16537, -1, 16538, 3409, 3411, -1, 16538, 16534, 3409, -1, 16538, 3411, 16535, -1, 16538, 16535, 16536, -1, 3038, 3035, 16533, -1, 16539, 16540, 16541, -1, 16539, 16541, 16542, -1, 14977, 16543, 16540, -1, 14977, 16540, 16539, -1, 14979, 16539, 16544, -1, 14979, 14977, 16539, -1, 14992, 16545, 16546, -1, 14992, 14983, 16545, -1, 16547, 16546, 16548, -1, 16549, 16546, 16547, -1, 16550, 16551, 16545, -1, 16551, 16552, 16545, -1, 16546, 16553, 16548, -1, 16553, 16554, 16555, -1, 16546, 16556, 16553, -1, 16553, 16556, 16554, -1, 16545, 16557, 16546, -1, 16546, 16557, 16556, -1, 16557, 16558, 16559, -1, 16552, 16560, 16545, -1, 16545, 16560, 16557, -1, 16557, 16560, 16558, -1, 15065, 10564, 15246, -1, 10564, 16561, 15246, -1, 10564, 11367, 16561, -1, 15066, 15239, 8141, -1, 9653, 15066, 8141, -1, 15539, 8141, 15239, -1, 8110, 8141, 15539, -1, 16562, 16563, 16564, -1, 16565, 16562, 16564, -1, 16566, 16565, 16564, -1, 11367, 16566, 16564, -1, 10412, 16566, 11367, -1, 16567, 16568, 16561, -1, 16561, 16568, 15246, -1, 16569, 16561, 16570, -1, 16561, 16571, 16567, -1, 16572, 16573, 15246, -1, 15246, 16574, 16572, -1, 16575, 16576, 16577, -1, 16568, 16576, 15246, -1, 15246, 16576, 16575, -1, 16573, 16578, 15246, -1, 16561, 16579, 16571, -1, 15246, 16580, 16574, -1, 16576, 16581, 16577, -1, 15246, 16575, 16580, -1, 16561, 16582, 16579, -1, 16577, 16583, 16584, -1, 16581, 16583, 16577, -1, 16561, 16585, 16582, -1, 16586, 16587, 16588, -1, 16589, 16587, 16586, -1, 16590, 16587, 16589, -1, 16584, 16587, 16590, -1, 16583, 16587, 16584, -1, 16561, 16591, 16585, -1, 16592, 15245, 16578, -1, 16593, 15245, 16592, -1, 16594, 15245, 16593, -1, 16569, 16591, 16561, -1, 16595, 15245, 16594, -1, 16596, 15245, 16595, -1, 16597, 15245, 16596, -1, 16569, 16598, 16591, -1, 16578, 15245, 15246, -1, 16599, 16600, 16601, -1, 16601, 16600, 15245, -1, 16602, 16600, 16599, -1, 16603, 16600, 16602, -1, 16604, 16600, 16603, -1, 16605, 16600, 16604, -1, 16597, 16606, 15245, -1, 16588, 16600, 16605, -1, 16587, 16600, 16588, -1, 16569, 16513, 16598, -1, 16598, 16513, 16512, -1, 16606, 16607, 15245, -1, 16607, 16601, 15245, -1, 16608, 16599, 16601, -1, 16609, 16604, 16610, -1, 16611, 16612, 16613, -1, 16609, 16610, 16614, -1, 16611, 16615, 16616, -1, 16609, 16614, 16617, -1, 16608, 16618, 16619, -1, 16611, 16616, 16612, -1, 16608, 16619, 16620, -1, 16621, 16622, 16623, -1, 16608, 16601, 16618, -1, 16624, 16625, 16626, -1, 16624, 16626, 16575, -1, 16624, 16577, 16584, -1, 16624, 16575, 16577, -1, 16624, 16584, 16627, -1, 16621, 16617, 16622, -1, 16628, 16620, 16629, -1, 16624, 16611, 16625, -1, 16624, 16627, 16615, -1, 16624, 16615, 16611, -1, 16628, 16629, 16630, -1, 16631, 16632, 16633, -1, 16634, 16630, 16635, -1, 16631, 16623, 16632, -1, 16634, 16635, 16636, -1, 16637, 16633, 16638, -1, 16639, 16640, 16641, -1, 16639, 16642, 16640, -1, 16643, 16644, 16645, -1, 16637, 16638, 16646, -1, 16643, 16636, 16644, -1, 16647, 16646, 16648, -1, 16647, 16648, 16649, -1, 16650, 16651, 16642, -1, 16652, 16645, 16653, -1, 16652, 16653, 16654, -1, 16650, 16642, 16639, -1, 16655, 16656, 16657, -1, 16658, 16659, 16660, -1, 16658, 16654, 16659, -1, 16661, 16641, 16662, -1, 16655, 16649, 16656, -1, 16663, 16609, 16617, -1, 16661, 16639, 16641, -1, 16664, 16602, 16599, -1, 16665, 16651, 16650, -1, 16663, 16588, 16605, -1, 16664, 16608, 16620, -1, 16663, 16605, 16609, -1, 16665, 16666, 16651, -1, 16663, 16617, 16621, -1, 16664, 16599, 16608, -1, 16664, 16620, 16628, -1, 16667, 16623, 16631, -1, 16668, 16628, 16630, -1, 16668, 16630, 16634, -1, 16669, 16639, 16661, -1, 16667, 16621, 16623, -1, 16670, 16633, 16637, -1, 16670, 16631, 16633, -1, 16669, 16650, 16639, -1, 16671, 16634, 16636, -1, 16671, 16636, 16643, -1, 16672, 16662, 16673, -1, 16601, 16607, 16674, -1, 16675, 16645, 16652, -1, 16676, 16637, 16646, -1, 16676, 16646, 16647, -1, 16675, 16643, 16645, -1, 16672, 16661, 16662, -1, 16677, 16678, 16666, -1, 16679, 16647, 16649, -1, 16677, 16666, 16665, -1, 16680, 16665, 16650, -1, 16681, 16652, 16654, -1, 16679, 16649, 16655, -1, 16682, 16683, 16684, -1, 16681, 16654, 16658, -1, 16682, 16657, 16683, -1, 16682, 16655, 16657, -1, 16680, 16650, 16669, -1, 16682, 16684, 16685, -1, 16686, 16660, 16687, -1, 16688, 16621, 16667, -1, 16689, 16669, 16661, -1, 16688, 16663, 16621, -1, 16686, 16658, 16660, -1, 16689, 16661, 16672, -1, 16688, 16586, 16588, -1, 16690, 16603, 16602, -1, 16688, 16588, 16663, -1, 16690, 16602, 16664, -1, 16690, 16628, 16668, -1, 16691, 16667, 16631, -1, 16690, 16664, 16628, -1, 16692, 16673, 16693, -1, 16692, 16672, 16673, -1, 16614, 16668, 16634, -1, 16691, 16631, 16670, -1, 16614, 16634, 16671, -1, 16694, 16670, 16637, -1, 16619, 16695, 16678, -1, 16694, 16637, 16676, -1, 16622, 16671, 16643, -1, 16619, 16678, 16677, -1, 16622, 16643, 16675, -1, 16629, 16665, 16680, -1, 16629, 16677, 16665, -1, 16696, 16647, 16679, -1, 16696, 16676, 16647, -1, 16632, 16675, 16652, -1, 16632, 16652, 16681, -1, 16697, 16685, 16698, -1, 16697, 16679, 16655, -1, 16697, 16682, 16685, -1, 16635, 16680, 16669, -1, 16635, 16669, 16689, -1, 16697, 16655, 16682, -1, 16699, 16586, 16688, -1, 16699, 16589, 16586, -1, 16638, 16681, 16658, -1, 16644, 16689, 16672, -1, 16638, 16658, 16686, -1, 16699, 16688, 16667, -1, 16699, 16667, 16691, -1, 16644, 16672, 16692, -1, 16648, 16687, 16700, -1, 16648, 16686, 16687, -1, 16701, 16670, 16694, -1, 16653, 16693, 16702, -1, 16701, 16691, 16670, -1, 16610, 16604, 16603, -1, 16653, 16692, 16693, -1, 16610, 16668, 16614, -1, 16610, 16603, 16690, -1, 16618, 16695, 16619, -1, 16610, 16690, 16668, -1, 16618, 16674, 16695, -1, 16618, 16601, 16674, -1, 16616, 16676, 16696, -1, 16616, 16694, 16676, -1, 16703, 16698, 16704, -1, 16617, 16614, 16671, -1, 16617, 16671, 16622, -1, 16703, 16697, 16698, -1, 16620, 16619, 16677, -1, 16703, 16696, 16679, -1, 16620, 16677, 16629, -1, 16703, 16679, 16697, -1, 16705, 16590, 16589, -1, 16623, 16622, 16675, -1, 16705, 16589, 16699, -1, 16623, 16675, 16632, -1, 16705, 16699, 16691, -1, 16705, 16691, 16701, -1, 16630, 16680, 16635, -1, 16630, 16629, 16680, -1, 16615, 16701, 16694, -1, 16636, 16689, 16644, -1, 16633, 16632, 16681, -1, 16633, 16681, 16638, -1, 16615, 16694, 16616, -1, 16636, 16635, 16689, -1, 16612, 16704, 16613, -1, 16612, 16703, 16704, -1, 16612, 16616, 16696, -1, 16612, 16696, 16703, -1, 16646, 16638, 16686, -1, 16645, 16644, 16692, -1, 16646, 16686, 16648, -1, 16645, 16692, 16653, -1, 16627, 16584, 16590, -1, 16649, 16700, 16656, -1, 16654, 16702, 16659, -1, 16627, 16590, 16705, -1, 16627, 16705, 16701, -1, 16627, 16701, 16615, -1, 16649, 16648, 16700, -1, 16654, 16653, 16702, -1, 16611, 16613, 16625, -1, 16609, 16605, 16604, -1, 16706, 16707, 16708, -1, 16709, 16710, 16711, -1, 16712, 16710, 16713, -1, 16713, 16710, 16714, -1, 16714, 16710, 16715, -1, 16715, 16710, 16709, -1, 16716, 16717, 16718, -1, 16719, 16720, 16721, -1, 16707, 16720, 16719, -1, 16722, 16720, 16723, -1, 16724, 16720, 16722, -1, 16725, 16720, 16724, -1, 16712, 16726, 16710, -1, 16723, 16720, 16707, -1, 16727, 16708, 16712, -1, 16717, 16728, 16718, -1, 16720, 16729, 16721, -1, 16729, 16730, 16721, -1, 16712, 16708, 16726, -1, 16731, 16732, 16733, -1, 16730, 16734, 16721, -1, 16727, 16735, 16708, -1, 16733, 16736, 16731, -1, 16735, 16737, 16708, -1, 16731, 16738, 16732, -1, 16739, 16740, 16734, -1, 16736, 16741, 16731, -1, 16737, 16742, 16708, -1, 16734, 16740, 16743, -1, 16734, 16744, 16721, -1, 16743, 16744, 16734, -1, 16741, 16745, 16731, -1, 16742, 16746, 16708, -1, 16744, 16747, 16721, -1, 16739, 16748, 16740, -1, 16749, 16750, 16751, -1, 16746, 16706, 16708, -1, 16739, 16752, 16748, -1, 16749, 16753, 16750, -1, 16718, 16753, 16731, -1, 16539, 16720, 16754, -1, 16539, 16755, 16544, -1, 16738, 16753, 16749, -1, 16539, 16754, 16756, -1, 16754, 16720, 16725, -1, 16544, 16755, 16757, -1, 16728, 16753, 16718, -1, 16712, 16731, 16745, -1, 16731, 16753, 16738, -1, 16758, 16759, 16760, -1, 16755, 16759, 16758, -1, 16539, 16761, 16755, -1, 16755, 16761, 16759, -1, 16539, 16762, 16761, -1, 16763, 16544, 16757, -1, 16539, 16764, 16762, -1, 16765, 16544, 16763, -1, 16539, 16766, 16764, -1, 16767, 16712, 16745, -1, 16727, 16712, 16768, -1, 16768, 16712, 16769, -1, 16769, 16712, 16767, -1, 16539, 16756, 16766, -1, 16770, 16771, 16772, -1, 16715, 16773, 16770, -1, 16770, 16773, 16771, -1, 16715, 16774, 16773, -1, 16775, 16707, 16706, -1, 16776, 16707, 16775, -1, 16777, 16707, 16776, -1, 16778, 16707, 16777, -1, 16779, 16707, 16778, -1, 16715, 16709, 16774, -1, 16723, 16707, 16779, -1, 16780, 16781, 16782, -1, 16780, 16782, 16783, -1, 16784, 16780, 16783, -1, 16784, 16785, 16780, -1, 16786, 16780, 16785, -1, 16787, 16783, 16570, -1, 16787, 16784, 16783, -1, 16788, 16780, 16786, -1, 16789, 16787, 16570, -1, 16790, 16780, 16788, -1, 16791, 16780, 16790, -1, 16792, 16789, 16570, -1, 16793, 16792, 16570, -1, 16564, 16793, 16570, -1, 16561, 16564, 16570, -1, 11367, 16564, 16561, -1, 16794, 16795, 16796, -1, 16543, 16794, 16796, -1, 16540, 16796, 16797, -1, 16540, 16797, 16798, -1, 16540, 16543, 16796, -1, 16799, 16540, 16798, -1, 16800, 16540, 16799, -1, 3256, 3252, 16801, -1, 3256, 16801, 16802, -1, 16801, 16803, 16802, -1, 16804, 16803, 16805, -1, 16802, 16803, 16806, -1, 16806, 16803, 16807, -1, 16807, 16803, 16808, -1, 16808, 16803, 16804, -1, 16809, 16810, 16801, -1, 16811, 16810, 16809, -1, 16812, 16810, 16811, -1, 16801, 16810, 16803, -1, 16813, 16810, 16814, -1, 16814, 16810, 16812, -1, 16803, 16810, 16815, -1, 16816, 16815, 16817, -1, 16816, 16803, 16815, -1, 16818, 16817, 16819, -1, 16818, 16816, 16817, -1, 16820, 16818, 16819, -1, 16821, 16819, 16822, -1, 16821, 16822, 16823, -1, 16821, 16820, 16819, -1, 16824, 16821, 16823, -1, 3243, 16825, 16826, -1, 3243, 3242, 16825, -1, 16827, 16828, 16829, -1, 16826, 16825, 16830, -1, 16826, 16830, 16831, -1, 16832, 16833, 16827, -1, 16827, 16833, 16828, -1, 16828, 16833, 16834, -1, 16835, 16836, 16837, -1, 16838, 16837, 16836, -1, 16839, 16836, 16835, -1, 16840, 16838, 16836, -1, 16841, 16833, 16836, -1, 16841, 16836, 16839, -1, 16842, 16833, 16841, -1, 16843, 16833, 16842, -1, 16844, 16833, 16843, -1, 16845, 16833, 16844, -1, 16846, 16840, 16836, -1, 16847, 16833, 16845, -1, 16848, 16849, 16840, -1, 16848, 16840, 16846, -1, 16850, 16846, 16836, -1, 16851, 16849, 16848, -1, 16852, 16849, 16851, -1, 16826, 16849, 16852, -1, 16834, 16833, 16847, -1, 16831, 16849, 16826, -1, 16825, 16853, 16830, -1, 16854, 16853, 16825, -1, 16855, 16853, 16854, -1, 16829, 16828, 16856, -1, 16829, 16856, 16853, -1, 16829, 16853, 16855, -1, 16857, 16833, 16858, -1, 16857, 16836, 16833, -1, 16859, 16858, 16860, -1, 16859, 16857, 16858, -1, 16861, 16860, 16862, -1, 16861, 16862, 16863, -1, 16861, 16859, 16860, -1, 16864, 16863, 16865, -1, 16864, 16861, 16863, -1, 3129, 3125, 16797, -1, 16796, 3129, 16797, -1, 14975, 3129, 16796, -1, 3128, 3137, 16866, -1, 3128, 16866, 16867, -1, 16868, 16869, 16870, -1, 16871, 16868, 16870, -1, 16866, 16871, 16870, -1, 16867, 16866, 16870, -1, 16872, 16867, 16870, -1, 3136, 3134, 16873, -1, 3136, 16873, 16874, -1, 16875, 16876, 16877, -1, 16878, 16876, 16875, -1, 16879, 16876, 16878, -1, 16880, 16881, 16876, -1, 16880, 16876, 16879, -1, 16882, 16883, 16880, -1, 16882, 16884, 16883, -1, 16882, 16885, 16884, -1, 16882, 16886, 16885, -1, 16882, 16887, 16886, -1, 16882, 16888, 16887, -1, 16882, 16880, 16879, -1, 16889, 16882, 16890, -1, 16889, 16888, 16882, -1, 16891, 16890, 16892, -1, 16891, 16889, 16890, -1, 16893, 16888, 16889, -1, 16894, 16891, 16892, -1, 16895, 16888, 16893, -1, 16896, 16888, 16895, -1, 16873, 16897, 16898, -1, 16874, 16898, 16896, -1, 16874, 16873, 16898, -1, 16899, 16874, 16896, -1, 16900, 16899, 16896, -1, 16901, 16900, 16896, -1, 16898, 16888, 16896, -1, 3116, 15015, 16902, -1, 16903, 3116, 16902, -1, 3130, 3116, 16903, -1, 16904, 16903, 16905, -1, 16903, 16906, 16905, -1, 16906, 16907, 16905, -1, 16903, 16908, 16906, -1, 16907, 16909, 16905, -1, 16903, 16902, 16908, -1, 16910, 16911, 16902, -1, 16911, 16912, 16902, -1, 16902, 16913, 16908, -1, 16912, 16913, 16902, -1, 16912, 16914, 16913, -1, 16912, 16915, 16914, -1, 16912, 16916, 16915, -1, 16917, 16918, 16909, -1, 16919, 16918, 16917, -1, 16920, 16918, 16919, -1, 16921, 16918, 16920, -1, 16922, 16918, 16921, -1, 16923, 16918, 16922, -1, 16909, 16918, 16905, -1, 16924, 16925, 16923, -1, 16926, 16925, 16924, -1, 16927, 16925, 16926, -1, 16928, 16925, 16927, -1, 16923, 16925, 16918, -1, 16912, 16925, 16916, -1, 16916, 16925, 16929, -1, 16929, 16925, 16928, -1, 16930, 16931, 16932, -1, 16930, 16932, 16933, -1, 16934, 16930, 16933, -1, 16935, 16930, 16934, -1, 16936, 16937, 16930, -1, 16936, 16930, 16935, -1, 16938, 16937, 16936, -1, 16939, 16940, 16937, -1, 16939, 16937, 16938, -1, 16941, 16940, 16939, -1, 16942, 16941, 16939, -1, 16943, 16942, 16939, -1, 15016, 16939, 16944, -1, 15016, 16943, 16939, -1, 15016, 15017, 16945, -1, 15016, 16945, 16946, -1, 15016, 16946, 16947, -1, 15016, 16947, 16948, -1, 15016, 16948, 16943, -1, 16930, 16949, 16931, -1, 16950, 16951, 16952, -1, 16953, 16950, 16954, -1, 16955, 16951, 16950, -1, 16955, 16950, 16953, -1, 16956, 16954, 16950, -1, 16957, 16956, 16950, -1, 16958, 16957, 16950, -1, 16949, 16951, 16955, -1, 16930, 16951, 16949, -1, 16944, 16959, 16960, -1, 16944, 16960, 16961, -1, 16944, 16961, 16962, -1, 16939, 16959, 16944, -1, 15018, 16963, 15017, -1, 16964, 16965, 16966, -1, 16967, 16965, 16964, -1, 16968, 16965, 16967, -1, 16969, 16965, 16968, -1, 16970, 16965, 16969, -1, 16971, 16965, 16970, -1, 16963, 16965, 16971, -1, 15018, 16972, 16963, -1, 16963, 16972, 16965, -1, 16973, 16974, 16975, -1, 16973, 16975, 16976, -1, 16973, 16977, 16978, -1, 16973, 16978, 16974, -1, 16973, 16976, 16979, -1, 16973, 16979, 16977, -1, 16971, 16980, 16981, -1, 16971, 16981, 16963, -1, 16982, 16951, 16983, -1, 16984, 16974, 16978, -1, 16985, 16971, 16970, -1, 16986, 16987, 16980, -1, 16986, 16980, 16971, -1, 16986, 16985, 16970, -1, 16986, 16971, 16985, -1, 16988, 16983, 16987, -1, 16988, 16982, 16983, -1, 16988, 16987, 16986, -1, 16989, 16969, 16968, -1, 16989, 16970, 16969, -1, 16990, 16970, 16989, -1, 16990, 16986, 16970, -1, 16991, 16992, 16982, -1, 16991, 16988, 16986, -1, 16991, 16982, 16988, -1, 16991, 16986, 16990, -1, 16993, 16968, 16967, -1, 16993, 16989, 16968, -1, 16994, 16990, 16989, -1, 16994, 16989, 16993, -1, 16995, 16996, 16992, -1, 16995, 16990, 16994, -1, 16995, 16992, 16991, -1, 16995, 16991, 16990, -1, 16997, 16993, 16967, -1, 16979, 16994, 16993, -1, 16979, 16993, 16997, -1, 16976, 16975, 16996, -1, 16976, 16996, 16995, -1, 16976, 16995, 16994, -1, 16976, 16994, 16979, -1, 16998, 16964, 16966, -1, 16998, 16967, 16964, -1, 16998, 16966, 16999, -1, 16998, 16997, 16967, -1, 16977, 16999, 16978, -1, 16977, 16998, 16999, -1, 16977, 16979, 16997, -1, 16977, 16997, 16998, -1, 17000, 17001, 17002, -1, 17003, 17004, 17005, -1, 17006, 17007, 17008, -1, 17009, 17007, 17006, -1, 17010, 17011, 17012, -1, 17008, 17013, 17014, -1, 17007, 17013, 17008, -1, 17014, 17013, 17004, -1, 17000, 17015, 17001, -1, 16906, 16908, 17016, -1, 16906, 17016, 17017, -1, 17011, 17018, 17012, -1, 17000, 17019, 17015, -1, 17020, 17019, 17000, -1, 17020, 17021, 17019, -1, 17020, 17022, 17021, -1, 17022, 17023, 17021, -1, 17024, 17025, 17016, -1, 17026, 17025, 17024, -1, 17023, 17027, 17028, -1, 17022, 17027, 17023, -1, 17016, 17025, 17017, -1, 17029, 17030, 17026, -1, 17026, 17030, 17025, -1, 17031, 17032, 17018, -1, 17033, 17032, 17031, -1, 17034, 17032, 17033, -1, 17018, 17032, 17012, -1, 17028, 17035, 17036, -1, 17027, 17035, 17028, -1, 17037, 17038, 17029, -1, 17039, 17038, 17037, -1, 17034, 17040, 17032, -1, 17030, 17041, 17042, -1, 17029, 17041, 17030, -1, 17038, 17041, 17029, -1, 17043, 17044, 17039, -1, 17045, 17044, 17043, -1, 17046, 17044, 17045, -1, 17039, 17044, 17038, -1, 17047, 17048, 17012, -1, 17042, 17048, 17047, -1, 17041, 17048, 17042, -1, 17046, 17049, 17044, -1, 17002, 17049, 17046, -1, 17034, 17050, 17040, -1, 17048, 17051, 17012, -1, 17036, 17052, 17053, -1, 17035, 17052, 17036, -1, 17002, 17054, 17049, -1, 17034, 17055, 17050, -1, 17051, 17056, 17012, -1, 17053, 17057, 17058, -1, 17052, 17057, 17053, -1, 17056, 17059, 17012, -1, 17003, 17005, 17034, -1, 17034, 17005, 17055, -1, 17059, 17010, 17012, -1, 17058, 17009, 17006, -1, 17057, 17009, 17058, -1, 17014, 17004, 17003, -1, 17002, 17001, 17054, -1, 17060, 17002, 17046, -1, 17061, 17046, 17045, -1, 17061, 17060, 17046, -1, 17062, 17045, 17043, -1, 17062, 17061, 17045, -1, 17063, 17043, 17039, -1, 17063, 17062, 17043, -1, 17064, 17039, 17037, -1, 17064, 17063, 17039, -1, 17065, 17037, 17029, -1, 17065, 17064, 17037, -1, 17066, 17029, 17026, -1, 17066, 17065, 17029, -1, 17067, 17055, 17068, -1, 17068, 17005, 17069, -1, 17055, 17005, 17068, -1, 17070, 17004, 17071, -1, 17069, 17004, 17070, -1, 17005, 17004, 17069, -1, 17071, 17013, 17072, -1, 17004, 17013, 17071, -1, 17073, 17007, 17074, -1, 17072, 17007, 17073, -1, 17013, 17007, 17072, -1, 17074, 17009, 17075, -1, 17007, 17009, 17074, -1, 17076, 17057, 17077, -1, 17075, 17057, 17076, -1, 17009, 17057, 17075, -1, 17077, 17052, 17078, -1, 17057, 17052, 17077, -1, 17078, 17035, 17079, -1, 17052, 17035, 17078, -1, 17035, 17027, 17079, -1, 17079, 17022, 17080, -1, 17027, 17022, 17079, -1, 17022, 17020, 17080, -1, 17020, 17060, 17080, -1, 17020, 17000, 17060, -1, 17032, 17040, 17081, -1, 17081, 17040, 17082, -1, 17040, 17050, 17082, -1, 17082, 17055, 17067, -1, 17050, 17055, 17082, -1, 17012, 17032, 17081, -1, 17000, 17002, 17060, -1, 16223, 17083, 17084, -1, 17085, 17086, 17087, -1, 17086, 17088, 17087, -1, 17089, 17090, 17091, -1, 17088, 17092, 17087, -1, 17091, 17093, 17089, -1, 17089, 17094, 17090, -1, 17092, 17095, 17087, -1, 17089, 17096, 17094, -1, 17095, 17097, 17087, -1, 17093, 17098, 17089, -1, 17097, 17099, 17087, -1, 17089, 17100, 17096, -1, 17099, 17101, 17087, -1, 17101, 17102, 17087, -1, 17098, 17103, 17089, -1, 17103, 17104, 17089, -1, 17083, 16222, 17105, -1, 16223, 16222, 17083, -1, 17104, 17106, 17089, -1, 17107, 17108, 16222, -1, 16222, 17108, 17105, -1, 17106, 17109, 17089, -1, 17109, 17110, 17089, -1, 17111, 17112, 17107, -1, 17110, 17113, 17089, -1, 17114, 17112, 17111, -1, 17108, 17112, 17115, -1, 17107, 17112, 17108, -1, 17116, 17117, 17118, -1, 17117, 17119, 17118, -1, 17120, 17121, 17119, -1, 17119, 17121, 17118, -1, 17121, 17122, 17118, -1, 17118, 17123, 17124, -1, 17122, 17123, 17118, -1, 17123, 17125, 17124, -1, 17126, 17125, 17113, -1, 17124, 17125, 17126, -1, 17113, 17125, 17089, -1, 17125, 17127, 17089, -1, 17127, 17128, 17089, -1, 17128, 17087, 17089, -1, 16223, 17087, 17128, -1, 17129, 17130, 17087, -1, 17130, 17131, 17087, -1, 16223, 17132, 17087, -1, 17087, 17132, 17129, -1, 16223, 17084, 17132, -1, 17131, 17085, 17087, -1, 17133, 17134, 15964, -1, 17135, 17134, 17133, -1, 17136, 17134, 17135, -1, 17137, 17134, 17136, -1, 17138, 17134, 17137, -1, 17139, 17134, 17102, -1, 17102, 17134, 17138, -1, 17134, 17140, 15964, -1, 17141, 17140, 17142, -1, 15954, 15955, 17143, -1, 17143, 15953, 15954, -1, 17143, 15956, 17141, -1, 15955, 15956, 17143, -1, 17143, 15952, 15953, -1, 15956, 15957, 17141, -1, 17143, 15951, 15952, -1, 15957, 15958, 17141, -1, 17141, 15959, 17140, -1, 15958, 15959, 17141, -1, 15959, 15960, 17140, -1, 15960, 15961, 17140, -1, 15961, 15962, 17140, -1, 17144, 17087, 17145, -1, 17146, 17087, 17144, -1, 17147, 17087, 17146, -1, 15951, 17087, 17147, -1, 17143, 17087, 15951, -1, 15962, 15963, 17140, -1, 15963, 15964, 17140, -1, 17148, 17102, 17138, -1, 17149, 17102, 17148, -1, 17150, 17102, 17149, -1, 17145, 17102, 17150, -1, 17087, 17102, 17145, -1, 17151, 17152, 17153, -1, 17154, 17155, 17156, -1, 17157, 17158, 17143, -1, 17152, 17159, 17153, -1, 17143, 17160, 17157, -1, 17159, 17161, 17153, -1, 17158, 17162, 17143, -1, 17143, 17163, 17160, -1, 17161, 17164, 17153, -1, 17162, 17165, 17143, -1, 17164, 17166, 17153, -1, 17143, 17141, 17163, -1, 17166, 17167, 17153, -1, 17165, 17168, 17143, -1, 17167, 17169, 17153, -1, 17168, 17170, 17143, -1, 17169, 17171, 17153, -1, 17170, 17172, 17143, -1, 17171, 17173, 17153, -1, 17172, 17174, 17143, -1, 17155, 17175, 17176, -1, 17174, 17177, 17143, -1, 17154, 17175, 17155, -1, 17175, 17178, 17176, -1, 17177, 17179, 17143, -1, 17176, 17180, 17181, -1, 17182, 17183, 17178, -1, 17184, 17183, 17182, -1, 17178, 17183, 17176, -1, 17176, 17183, 17180, -1, 17185, 17186, 17187, -1, 17188, 17186, 17185, -1, 17189, 17190, 17191, -1, 17187, 17190, 17189, -1, 17186, 17190, 17187, -1, 17191, 17192, 17193, -1, 17190, 17192, 17191, -1, 17194, 17195, 17179, -1, 17193, 17195, 17194, -1, 17192, 17195, 17193, -1, 17179, 17195, 17143, -1, 17195, 17196, 17143, -1, 17196, 17153, 17143, -1, 17197, 17153, 17196, -1, 17154, 17153, 17197, -1, 17198, 17199, 17153, -1, 17154, 17200, 17153, -1, 17153, 17200, 17198, -1, 17199, 17151, 17153, -1, 17154, 17156, 17200, -1, 17201, 17192, 17202, -1, 17203, 17192, 17201, -1, 17195, 17204, 17205, -1, 17195, 17192, 17203, -1, 17195, 17203, 17204, -1, 17204, 17203, 17206, -1, 17204, 17206, 17207, -1, 17206, 17208, 17209, -1, 17207, 17209, 17210, -1, 17207, 17206, 17209, -1, 17209, 17208, 17211, -1, 17209, 17211, 17212, -1, 17211, 17213, 17212, -1, 17213, 17214, 17212, -1, 17215, 17216, 17153, -1, 17153, 17217, 17215, -1, 17216, 17218, 17153, -1, 17218, 17219, 17153, -1, 17153, 17220, 17217, -1, 17219, 17221, 17153, -1, 17222, 17087, 17223, -1, 17224, 17087, 17222, -1, 17225, 17087, 17224, -1, 17226, 17087, 17225, -1, 17227, 17087, 17228, -1, 17221, 17229, 17153, -1, 17230, 17087, 17227, -1, 17231, 17087, 17230, -1, 17232, 17087, 17231, -1, 17233, 17087, 17232, -1, 17223, 17087, 17233, -1, 17228, 17087, 17143, -1, 17089, 17087, 17234, -1, 17153, 17235, 17220, -1, 17234, 17087, 17226, -1, 17229, 17236, 17153, -1, 17153, 17089, 17235, -1, 17089, 17237, 17235, -1, 17089, 17238, 17237, -1, 17089, 17239, 17238, -1, 17089, 17240, 17239, -1, 17089, 17241, 17240, -1, 17089, 17242, 17241, -1, 17089, 17243, 17242, -1, 17089, 17244, 17243, -1, 17089, 17245, 17244, -1, 17089, 17234, 17245, -1, 17236, 17246, 17153, -1, 17247, 17143, 17246, -1, 17248, 17143, 17247, -1, 17249, 17143, 17248, -1, 17250, 17143, 17249, -1, 17251, 17143, 17250, -1, 17252, 17143, 17251, -1, 17253, 17143, 17252, -1, 17254, 17143, 17253, -1, 17228, 17143, 17254, -1, 17246, 17143, 17153, -1, 16192, 16070, 16193, -1, 16071, 16070, 16192, -1, 16070, 16089, 16193, -1, 17255, 15901, 17256, -1, 17257, 17255, 17256, -1, 15903, 15901, 17255, -1, 17258, 17255, 17257, -1, 15930, 17259, 15931, -1, 2764, 16251, 16252, -1, 16256, 2763, 16261, -1, 16251, 2763, 16256, -1, 2764, 2763, 16251, -1, 15273, 2662, 15274, -1, 2660, 2662, 15273, -1, 17260, 16350, 16349, -1, 17261, 17262, 17263, -1, 17261, 17263, 17260, -1, 17264, 17265, 17266, -1, 17264, 17266, 17267, -1, 16342, 16343, 17264, -1, 16342, 17264, 17267, -1, 16349, 16342, 17260, -1, 17260, 16342, 17261, -1, 17261, 16342, 17267, -1, 15887, 16389, 17268, -1, 17268, 17269, 17270, -1, 17271, 15887, 17268, -1, 17271, 17268, 17270, -1, 17272, 17271, 17270, -1, 17273, 17272, 17270, -1, 17274, 17271, 17272, -1, 17275, 17274, 17272, -1, 17276, 17277, 17278, -1, 17279, 17270, 17269, -1, 17279, 17269, 17276, -1, 17279, 17276, 17278, -1, 17280, 17281, 17266, -1, 17265, 17280, 17266, -1, 16273, 2640, 16266, -1, 16266, 2642, 16267, -1, 2640, 2642, 16266, -1, 16262, 2780, 16263, -1, 2781, 2780, 16262, -1, 17282, 15892, 17283, -1, 15889, 15892, 17282, -1, 17284, 17285, 15892, -1, 15892, 17285, 17283, -1, 17209, 17212, 17214, -1, 17209, 17214, 17279, -1, 17210, 17279, 17278, -1, 17210, 17209, 17279, -1, 17286, 17287, 17282, -1, 17286, 17282, 17283, -1, 17288, 17286, 17283, -1, 17287, 17289, 17290, -1, 17286, 17289, 17287, -1, 15986, 15987, 16017, -1, 15998, 15890, 17291, -1, 15999, 15998, 17291, -1, 17290, 15890, 15889, -1, 17290, 17291, 15890, -1, 17287, 15889, 17282, -1, 17287, 17290, 15889, -1, 15890, 15898, 15888, -1, 15998, 15898, 15890, -1, 15998, 15970, 15898, -1, 15998, 15988, 15970, -1, 17257, 17290, 17289, -1, 17257, 17256, 17291, -1, 17257, 17291, 17290, -1, 15901, 17291, 17256, -1, 15969, 15999, 17291, -1, 15969, 17291, 15901, -1, 15967, 15901, 15900, -1, 15967, 15969, 15901, -1, 15997, 15999, 15969, -1, 17258, 17257, 17289, -1, 17288, 17258, 17286, -1, 17292, 17258, 17288, -1, 17289, 17286, 17258, -1, 15905, 17255, 17258, -1, 15927, 15905, 17258, -1, 15926, 15905, 15927, -1, 17292, 15927, 17258, -1, 15905, 15903, 17255, -1, 15931, 17259, 16084, -1, 16189, 16084, 17259, -1, 15928, 15931, 16084, -1, 16047, 16084, 16057, -1, 16047, 15928, 16084, -1, 15891, 16518, 17284, -1, 15891, 17284, 15892, -1, 17273, 17270, 17213, -1, 17270, 17214, 17213, -1, 17270, 17279, 17214, -1, 16267, 2641, 16268, -1, 2642, 2641, 16267, -1, 2763, 2781, 16262, -1, 2763, 16262, 16261, -1, 16343, 17293, 17264, -1, 16330, 17294, 16343, -1, 16387, 17294, 16330, -1, 16343, 17294, 17293, -1, 2791, 16259, 16263, -1, 2791, 16263, 2780, -1, 17295, 17296, 17261, -1, 17267, 17295, 17261, -1, 16259, 2791, 16260, -1, 2791, 16276, 16260, -1, 16281, 2803, 16286, -1, 16277, 2803, 16281, -1, 2791, 2803, 16276, -1, 16276, 2803, 16277, -1, 16268, 2641, 16264, -1, 2641, 16254, 16264, -1, 16254, 2704, 16255, -1, 2641, 2704, 16254, -1, 2643, 16273, 16272, -1, 2643, 2640, 16273, -1, 15875, 15878, 15873, -1, 2693, 17297, 15875, -1, 15875, 17297, 15878, -1, 2693, 17298, 17297, -1, 16386, 17299, 16385, -1, 17298, 17299, 16386, -1, 17300, 16270, 16274, -1, 16270, 2643, 16272, -1, 17300, 2643, 16270, -1, 2693, 2643, 17300, -1, 2693, 17300, 17299, -1, 2693, 17299, 17298, -1, 15274, 2662, 15275, -1, 15275, 2693, 15875, -1, 2662, 2693, 15275, -1, 17293, 17265, 17264, -1, 17280, 17265, 17293, -1, 16381, 16380, 17294, -1, 16381, 17294, 16387, -1, 17266, 17295, 17267, -1, 17266, 17281, 17295, -1, 2762, 2764, 16252, -1, 16229, 2762, 16252, -1, 2703, 16225, 16255, -1, 2703, 16255, 2704, -1, 2698, 2945, 15286, -1, 2699, 15286, 15285, -1, 2699, 2698, 15286, -1, 2700, 15284, 15283, -1, 2700, 15285, 15284, -1, 2700, 2699, 15285, -1, 2701, 15282, 15293, -1, 2701, 15283, 15282, -1, 2701, 2700, 15283, -1, 2813, 15292, 15291, -1, 2813, 15293, 15292, -1, 2813, 2701, 15293, -1, 2805, 15291, 15290, -1, 2805, 2813, 15291, -1, 2804, 15290, 15289, -1, 2804, 2805, 15290, -1, 2806, 15289, 15288, -1, 2806, 2804, 15289, -1, 2807, 15288, 15280, -1, 2807, 2806, 15288, -1, 2657, 15280, 15279, -1, 2657, 2807, 15280, -1, 2655, 15279, 15278, -1, 2655, 2657, 15279, -1, 2652, 2655, 15278, -1, 15277, 2652, 15278, -1, 2650, 2652, 15277, -1, 2661, 2660, 15273, -1, 2661, 15273, 2943, -1, 2650, 15277, 15276, -1, 2651, 2650, 15276, -1, 17301, 17302, 17303, -1, 17301, 17304, 17302, -1, 17301, 17303, 17305, -1, 15930, 16189, 17259, -1, 17306, 17301, 17305, -1, 17307, 16191, 16189, -1, 17306, 17308, 17301, -1, 17306, 17309, 17308, -1, 17307, 17310, 16191, -1, 17134, 17306, 17305, -1, 17311, 16191, 17310, -1, 17312, 17306, 17134, -1, 17313, 17307, 16189, -1, 17314, 17313, 16189, -1, 17315, 17316, 17317, -1, 17318, 17315, 17317, -1, 15965, 17312, 17134, -1, 15965, 17317, 17312, -1, 15965, 17318, 17317, -1, 17319, 17314, 16189, -1, 15916, 15965, 17134, -1, 15916, 17134, 17139, -1, 17320, 17319, 16189, -1, 15930, 15916, 17139, -1, 15930, 17139, 17321, -1, 17322, 16189, 15930, -1, 17322, 17320, 16189, -1, 17323, 17322, 15930, -1, 16220, 17311, 17324, -1, 16220, 17324, 17325, -1, 16220, 16191, 17311, -1, 17326, 17323, 15930, -1, 17327, 17326, 15930, -1, 17321, 17327, 15930, -1, 17328, 16220, 17325, -1, 16221, 16220, 17328, -1, 17329, 17328, 17330, -1, 17329, 16221, 17328, -1, 17331, 17332, 17329, -1, 17331, 17329, 17330, -1, 17333, 17332, 17331, -1, 17334, 17332, 17333, -1, 17305, 17335, 17336, -1, 17305, 17303, 17335, -1, 17337, 17305, 17336, -1, 17338, 17336, 17335, -1, 17338, 17337, 17336, -1, 17339, 17335, 17303, -1, 17339, 17338, 17335, -1, 17340, 17303, 17302, -1, 17340, 17339, 17303, -1, 17341, 17302, 17304, -1, 17341, 17340, 17302, -1, 17342, 17304, 17301, -1, 17342, 17341, 17304, -1, 17343, 17342, 17301, -1, 17344, 15927, 17345, -1, 17343, 17339, 17340, -1, 17343, 17340, 17341, -1, 17346, 15927, 17344, -1, 17343, 17341, 17342, -1, 17347, 17345, 15927, -1, 17348, 15927, 17346, -1, 17349, 15927, 17292, -1, 17349, 17347, 15927, -1, 17350, 17337, 17339, -1, 17350, 17339, 17343, -1, 17350, 17140, 17337, -1, 17350, 17343, 17351, -1, 17350, 17351, 17352, -1, 15966, 15929, 17140, -1, 17353, 17349, 17292, -1, 17354, 17140, 17350, -1, 17355, 17353, 17292, -1, 17354, 15966, 17140, -1, 17354, 17356, 15966, -1, 17357, 17355, 17292, -1, 17358, 17356, 17354, -1, 17358, 17359, 17360, -1, 17358, 17360, 17356, -1, 17201, 17361, 17362, -1, 17363, 17357, 17292, -1, 17201, 17362, 17364, -1, 17365, 17363, 17292, -1, 17201, 17364, 17292, -1, 17201, 17202, 17361, -1, 15929, 15927, 17142, -1, 17366, 17365, 17292, -1, 17142, 15927, 17348, -1, 17364, 17366, 17292, -1, 17367, 17368, 17369, -1, 17370, 17371, 17367, -1, 17372, 17369, 17361, -1, 17372, 17367, 17369, -1, 17372, 17370, 17367, -1, 17202, 17372, 17361, -1, 15929, 17142, 17140, -1, 17339, 17337, 17338, -1, 16346, 16342, 16349, -1, 16344, 16342, 16346, -1, 17276, 16519, 17277, -1, 17276, 16527, 16519, -1, 16424, 16527, 17276, -1, 17269, 16424, 17276, -1, 16391, 16424, 17269, -1, 17268, 16391, 17269, -1, 16389, 16391, 17268, -1, 16432, 16431, 16478, -1, 16525, 16478, 16476, -1, 16525, 16432, 16478, -1, 16523, 16476, 16472, -1, 16523, 16525, 16476, -1, 16520, 16472, 16474, -1, 16520, 16523, 16472, -1, 16521, 16474, 16475, -1, 16521, 16520, 16474, -1, 16522, 16475, 17373, -1, 16522, 17373, 17374, -1, 16522, 16521, 16475, -1, 16524, 17374, 16461, -1, 16524, 16461, 16463, -1, 16524, 16522, 17374, -1, 16526, 16524, 16463, -1, 16454, 16463, 16465, -1, 16454, 16526, 16463, -1, 16452, 16465, 16466, -1, 16452, 16454, 16465, -1, 16455, 16452, 16466, -1, 16456, 16455, 16466, -1, 16458, 16456, 16466, -1, 16081, 15550, 16074, -1, 15552, 15550, 16081, -1, 16074, 17375, 17376, -1, 15550, 17375, 16074, -1, 17376, 17377, 17378, -1, 17375, 17377, 17376, -1, 17378, 16600, 16007, -1, 17377, 16600, 17378, -1, 16007, 16587, 15990, -1, 16600, 16587, 16007, -1, 16598, 16015, 16006, -1, 16598, 16512, 16015, -1, 16512, 16517, 16015, -1, 16512, 16514, 16517, -1, 16139, 15542, 16140, -1, 15542, 16133, 16140, -1, 15542, 16065, 16133, -1, 16115, 15541, 16113, -1, 16068, 15541, 16115, -1, 16101, 15541, 16068, -1, 15542, 15541, 16101, -1, 15542, 16101, 16114, -1, 15542, 16114, 16119, -1, 15542, 16119, 16065, -1, 16100, 15563, 16088, -1, 15569, 15563, 16100, -1, 16514, 15985, 16517, -1, 16517, 15985, 15984, -1, 17205, 17379, 17380, -1, 17204, 17379, 17205, -1, 17381, 17382, 17383, -1, 17381, 17384, 17382, -1, 17382, 17385, 17386, -1, 17382, 17387, 17385, -1, 17384, 17387, 17382, -1, 17385, 17388, 17386, -1, 17385, 17389, 17388, -1, 17390, 17391, 17381, -1, 17381, 17391, 17384, -1, 17392, 17393, 17394, -1, 17393, 17395, 17394, -1, 17393, 17396, 17395, -1, 17393, 17380, 17396, -1, 17390, 17397, 17391, -1, 17398, 17399, 17393, -1, 17393, 17399, 17380, -1, 17399, 17205, 17380, -1, 17398, 17391, 17397, -1, 17397, 17399, 17398, -1, 17395, 17400, 17401, -1, 17395, 17401, 17394, -1, 17402, 17403, 17404, -1, 17404, 17405, 17402, -1, 17405, 17406, 17402, -1, 17407, 17408, 17405, -1, 17406, 17408, 17409, -1, 17405, 17408, 17406, -1, 17408, 17410, 17409, -1, 17408, 17411, 17410, -1, 17410, 17412, 17413, -1, 17411, 17412, 17410, -1, 17401, 17414, 17415, -1, 17416, 17414, 17417, -1, 17417, 17418, 17419, -1, 17414, 17418, 17417, -1, 17420, 17418, 17414, -1, 17401, 17400, 17414, -1, 17414, 17400, 17420, -1, 17417, 17403, 17416, -1, 17402, 17416, 17403, -1, 17386, 17412, 17411, -1, 17388, 17412, 17386, -1, 17421, 17399, 17397, -1, 17422, 17397, 17403, -1, 17422, 17421, 17397, -1, 17417, 17422, 17403, -1, 17408, 17386, 17411, -1, 17382, 17386, 17408, -1, 17381, 17383, 17407, -1, 17381, 17407, 17405, -1, 17405, 17390, 17381, -1, 17404, 17390, 17405, -1, 17403, 17390, 17404, -1, 17403, 17397, 17390, -1, 17383, 17382, 17408, -1, 17383, 17408, 17407, -1, 17423, 17398, 17393, -1, 17423, 17424, 17398, -1, 17413, 17425, 17410, -1, 17415, 17425, 17413, -1, 17426, 17425, 17415, -1, 17414, 17426, 17415, -1, 17389, 17385, 17427, -1, 17392, 17413, 17389, -1, 17392, 17415, 17413, -1, 17392, 17389, 17427, -1, 17423, 17393, 17392, -1, 17423, 17392, 17427, -1, 17428, 17385, 17387, -1, 17428, 17427, 17385, -1, 17429, 17387, 17384, -1, 17429, 17428, 17387, -1, 17391, 17430, 17429, -1, 17391, 17429, 17384, -1, 17398, 17430, 17391, -1, 17424, 17430, 17398, -1, 16519, 17278, 17277, -1, 17429, 17278, 16519, -1, 17427, 16519, 16460, -1, 17428, 16519, 17427, -1, 17428, 17429, 16519, -1, 17430, 17210, 17278, -1, 17430, 17278, 17429, -1, 17423, 17427, 16460, -1, 16459, 17423, 16460, -1, 17431, 17423, 16459, -1, 17379, 17423, 17431, -1, 17207, 17210, 17430, -1, 17204, 17424, 17423, -1, 17204, 17207, 17424, -1, 17204, 17423, 17379, -1, 17430, 17424, 17207, -1, 16216, 16218, 16224, -1, 16216, 16224, 16217, -1, 16101, 16216, 16114, -1, 16101, 16218, 16216, -1, 16208, 16083, 16200, -1, 16090, 16083, 16208, -1, 16101, 16090, 16208, -1, 16101, 16208, 16187, -1, 16218, 16101, 16187, -1, 16200, 16114, 16206, -1, 16083, 16114, 16200, -1, 16114, 16216, 16206, -1, 16336, 16241, 16238, -1, 16325, 16244, 16336, -1, 16336, 16244, 16241, -1, 16325, 16246, 16244, -1, 16326, 16330, 16343, -1, 16326, 16343, 16340, -1, 17432, 17297, 17298, -1, 17432, 17298, 17433, -1, 16378, 17434, 16382, -1, 16375, 17434, 16378, -1, 16335, 17435, 16375, -1, 16375, 17435, 17434, -1, 17435, 17436, 17434, -1, 17437, 16383, 17434, -1, 17434, 16383, 16382, -1, 16335, 16334, 17435, -1, 16334, 17438, 17435, -1, 2783, 2777, 17438, -1, 17437, 17433, 16383, -1, 17433, 16386, 16383, -1, 17433, 17298, 16386, -1, 2777, 17435, 17438, -1, 2777, 17439, 17435, -1, 2789, 17439, 2777, -1, 17439, 17440, 17436, -1, 17439, 17436, 17435, -1, 17440, 17441, 17434, -1, 17440, 17434, 17436, -1, 17441, 17442, 17437, -1, 17441, 17437, 17434, -1, 17442, 17432, 17433, -1, 17442, 17433, 17437, -1, 15886, 15882, 15879, -1, 17441, 15886, 15879, -1, 17439, 16404, 15886, -1, 17439, 15886, 17441, -1, 17440, 17439, 17441, -1, 15876, 17441, 15879, -1, 17442, 17441, 15876, -1, 16451, 16404, 17439, -1, 17443, 16451, 17439, -1, 2789, 2814, 17443, -1, 17432, 17442, 15876, -1, 15878, 17432, 15876, -1, 17297, 17432, 15878, -1, 17439, 2789, 17443, -1, 15914, 15981, 15911, -1, 15932, 15981, 15914, -1, 15911, 15980, 15910, -1, 15981, 15980, 15911, -1, 15970, 15900, 15898, -1, 15970, 15967, 15900, -1, 15905, 15926, 15913, -1, 15904, 15968, 15899, -1, 15973, 15968, 15904, -1, 15912, 15973, 15904, -1, 15979, 15973, 15912, -1, 15907, 15979, 15912, -1, 15977, 15979, 15907, -1, 15909, 15895, 15894, -1, 15906, 15909, 15894, -1, 15978, 15907, 15909, -1, 15978, 15977, 15907, -1, 15975, 15978, 15909, -1, 15975, 15909, 15906, -1, 17444, 17445, 15978, -1, 17444, 15978, 15975, -1, 15971, 15906, 15902, -1, 15971, 15975, 15906, -1, 15899, 15971, 15902, -1, 15968, 15971, 15899, -1, 17446, 17447, 17444, -1, 17447, 17445, 17444, -1, 15974, 17444, 15975, -1, 15989, 17444, 15974, -1, 17444, 16016, 17446, -1, 15989, 16016, 17444, -1, 17445, 15976, 15978, -1, 17445, 15987, 15976, -1, 16017, 17445, 17447, -1, 16017, 15987, 17445, -1, 17446, 16016, 17447, -1, 16016, 16017, 17447, -1, 15893, 15906, 15894, -1, 15897, 15906, 15893, -1, 15909, 15896, 15895, -1, 15909, 15908, 15896, -1, 15885, 15880, 15883, -1, 15885, 15884, 15880, -1, 15884, 17448, 15880, -1, 17448, 15877, 15880, -1, 15877, 17449, 15874, -1, 17448, 17449, 15877, -1, 15874, 17450, 15281, -1, 17449, 17450, 15874, -1, 17450, 17451, 15281, -1, 17451, 15287, 15281, -1, 17452, 15271, 17451, -1, 17451, 15271, 15287, -1, 17452, 15269, 15271, -1, 17453, 15267, 15269, -1, 17453, 15269, 17452, -1, 15887, 17271, 17448, -1, 15887, 17448, 15884, -1, 17448, 17274, 17449, -1, 17271, 17274, 17448, -1, 17454, 17455, 17450, -1, 17449, 17454, 17450, -1, 17275, 17454, 17449, -1, 17274, 17275, 17449, -1, 17455, 17456, 17451, -1, 17455, 17451, 17450, -1, 17456, 17453, 17452, -1, 17456, 17452, 17451, -1, 17455, 17454, 17285, -1, 17455, 17285, 17284, -1, 17456, 17455, 17284, -1, 16518, 17456, 17284, -1, 15268, 17453, 17456, -1, 15268, 17456, 16518, -1, 15267, 17453, 15268, -1, 17361, 17193, 17362, -1, 17191, 17193, 17361, -1, 17105, 17325, 17083, -1, 17328, 17325, 17105, -1, 16094, 16099, 16211, -1, 16094, 16211, 16190, -1, 16115, 16220, 16219, -1, 16115, 16219, 16068, -1, 16099, 16068, 16211, -1, 16211, 16068, 16186, -1, 16068, 16219, 16186, -1, 16115, 16094, 16190, -1, 16115, 16190, 16191, -1, 16220, 16115, 16191, -1, 17273, 17213, 17272, -1, 17201, 17457, 17458, -1, 17201, 17458, 17203, -1, 17457, 17459, 17460, -1, 17457, 17460, 17458, -1, 17459, 17454, 17275, -1, 17459, 17275, 17460, -1, 17211, 17460, 17213, -1, 17213, 17275, 17272, -1, 17460, 17275, 17213, -1, 17211, 17458, 17460, -1, 17211, 17208, 17458, -1, 17208, 17206, 17458, -1, 17203, 17458, 17206, -1, 17459, 17283, 17285, -1, 17459, 17285, 17454, -1, 17457, 17288, 17283, -1, 17457, 17283, 17459, -1, 17292, 17288, 17457, -1, 17457, 17201, 17292, -1, 15117, 15109, 15247, -1, 15247, 15109, 15605, -1, 15608, 15605, 15109, -1, 15608, 15109, 15113, -1, 15607, 15113, 15115, -1, 15607, 15608, 15113, -1, 15612, 15115, 15116, -1, 15612, 15607, 15115, -1, 15611, 15116, 15114, -1, 15611, 15612, 15116, -1, 15548, 15114, 15112, -1, 15548, 15611, 15114, -1, 15545, 15112, 15111, -1, 15545, 15548, 15112, -1, 15546, 15111, 15108, -1, 15546, 15545, 15111, -1, 15603, 15108, 15107, -1, 15603, 15546, 15108, -1, 15602, 15107, 15122, -1, 15602, 15603, 15107, -1, 15601, 15122, 15121, -1, 15601, 15602, 15122, -1, 15600, 15121, 15120, -1, 15600, 15601, 15121, -1, 15598, 15120, 15119, -1, 15598, 15600, 15120, -1, 15595, 15119, 15118, -1, 15595, 15598, 15119, -1, 15595, 15110, 15538, -1, 15118, 15110, 15595, -1, 15132, 15551, 15240, -1, 15132, 15125, 15551, -1, 15549, 15126, 15241, -1, 15133, 15126, 15549, -1, 15551, 15125, 15127, -1, 15568, 15127, 15128, -1, 15568, 15551, 15127, -1, 15567, 15128, 15130, -1, 15567, 15568, 15128, -1, 15566, 15130, 15131, -1, 15566, 15567, 15130, -1, 15565, 15566, 15131, -1, 15564, 15131, 15129, -1, 15564, 15565, 15131, -1, 15562, 15129, 15123, -1, 15562, 15123, 15124, -1, 15562, 15564, 15129, -1, 15560, 15124, 15138, -1, 15560, 15562, 15124, -1, 15559, 15560, 15138, -1, 15557, 15138, 15137, -1, 15557, 15137, 15136, -1, 15557, 15559, 15138, -1, 15555, 15136, 15135, -1, 15555, 15557, 15136, -1, 15554, 15135, 15134, -1, 15554, 15555, 15135, -1, 15553, 15134, 15133, -1, 15553, 15554, 15134, -1, 15549, 15553, 15133, -1, 17461, 17462, 17463, -1, 17461, 17464, 17465, -1, 17461, 17463, 17464, -1, 17466, 15472, 15518, -1, 17466, 15518, 15503, -1, 17467, 17461, 17465, -1, 17466, 15503, 15478, -1, 17466, 15478, 15477, -1, 17468, 17461, 17467, -1, 17469, 15455, 17470, -1, 17471, 17472, 17473, -1, 17474, 17475, 17476, -1, 17477, 17473, 17478, -1, 17477, 17471, 17473, -1, 17479, 17480, 17474, -1, 17479, 17476, 17481, -1, 17479, 17474, 17476, -1, 17482, 17475, 17474, -1, 17483, 17484, 17472, -1, 17485, 15456, 15455, -1, 17483, 17472, 17471, -1, 17485, 15455, 17469, -1, 17486, 17466, 15477, -1, 17487, 17480, 17479, -1, 17486, 15477, 15520, -1, 17488, 17478, 17489, -1, 17490, 17475, 17482, -1, 17488, 17477, 17478, -1, 17490, 17491, 17475, -1, 17490, 17492, 17491, -1, 17493, 15456, 17485, -1, 17494, 17495, 17484, -1, 17493, 15475, 15456, -1, 17494, 17484, 17483, -1, 17496, 17486, 15520, -1, 17497, 17489, 17481, -1, 17496, 15520, 15509, -1, 17498, 17487, 17479, -1, 17497, 17488, 17489, -1, 17499, 15475, 17493, -1, 17499, 15490, 15475, -1, 15500, 17492, 17490, -1, 17500, 15509, 15490, -1, 17501, 17502, 17503, -1, 17500, 15490, 17499, -1, 17501, 17503, 17495, -1, 17500, 17496, 15509, -1, 17466, 17461, 17468, -1, 17504, 17479, 17505, -1, 17466, 17468, 15472, -1, 17501, 17495, 17494, -1, 17504, 17498, 17479, -1, 17506, 17497, 17481, -1, 15499, 17507, 17492, -1, 17508, 17502, 17501, -1, 15499, 17509, 17507, -1, 15499, 17492, 15500, -1, 17510, 17502, 17508, -1, 17511, 17506, 17481, -1, 17512, 17505, 17513, -1, 17512, 17504, 17505, -1, 15473, 17509, 15499, -1, 17514, 17510, 17508, -1, 17515, 17511, 17481, -1, 17516, 17512, 17513, -1, 17517, 17510, 17514, -1, 17518, 17516, 17513, -1, 15472, 17468, 17509, -1, 17519, 17517, 17514, -1, 15472, 17509, 15473, -1, 17476, 17515, 17481, -1, 17520, 17517, 17519, -1, 17521, 17516, 17518, -1, 17522, 17521, 17518, -1, 17523, 17520, 17519, -1, 17524, 17521, 17522, -1, 17525, 17520, 17523, -1, 17525, 17523, 17526, -1, 17527, 17524, 17522, -1, 17528, 17524, 17527, -1, 17462, 17525, 17526, -1, 17462, 17526, 17463, -1, 17470, 15455, 17528, -1, 17470, 17528, 17527, -1, 17529, 17530, 17531, -1, 17531, 17530, 17532, -1, 17481, 17533, 17534, -1, 17489, 17533, 17481, -1, 17478, 17533, 17489, -1, 17532, 17533, 17478, -1, 17535, 17495, 17503, -1, 17536, 17537, 17538, -1, 17538, 17537, 17539, -1, 17539, 17537, 17529, -1, 17529, 17537, 17530, -1, 17534, 17540, 17541, -1, 17530, 17540, 17532, -1, 17533, 17540, 17534, -1, 17532, 17540, 17533, -1, 17541, 17542, 17543, -1, 17544, 17542, 17536, -1, 17530, 17542, 17540, -1, 17543, 17542, 17544, -1, 17536, 17542, 17537, -1, 17540, 17542, 17541, -1, 17537, 17542, 17530, -1, 17544, 17545, 17543, -1, 17535, 17546, 17495, -1, 17547, 17548, 17535, -1, 17535, 17548, 17546, -1, 17495, 17549, 17484, -1, 17546, 17549, 17495, -1, 17550, 17551, 17552, -1, 17553, 17551, 17547, -1, 17552, 17551, 17553, -1, 17547, 17551, 17548, -1, 17546, 17554, 17549, -1, 17548, 17554, 17546, -1, 17484, 17555, 17472, -1, 17549, 17555, 17484, -1, 17556, 17557, 17550, -1, 17550, 17557, 17551, -1, 17548, 17557, 17554, -1, 17551, 17557, 17548, -1, 17554, 17558, 17549, -1, 17549, 17558, 17555, -1, 17472, 17531, 17473, -1, 17555, 17531, 17472, -1, 17559, 17560, 17556, -1, 17557, 17560, 17554, -1, 17554, 17560, 17558, -1, 17556, 17560, 17557, -1, 17558, 17529, 17555, -1, 17555, 17529, 17531, -1, 17473, 17532, 17478, -1, 17531, 17532, 17473, -1, 17538, 17539, 17559, -1, 17560, 17539, 17558, -1, 17558, 17539, 17529, -1, 17559, 17539, 17560, -1, 17561, 17562, 17563, -1, 17564, 17565, 17566, -1, 17567, 17568, 17569, -1, 17570, 17571, 17572, -1, 17567, 17573, 17574, -1, 17570, 17572, 15168, -1, 17570, 15168, 17575, -1, 17576, 17569, 17577, -1, 17570, 17575, 17578, -1, 17570, 17561, 17571, -1, 17570, 17579, 17580, -1, 17564, 17581, 17565, -1, 17570, 17578, 17579, -1, 17570, 17580, 17561, -1, 17582, 17583, 17584, -1, 17576, 17577, 17585, -1, 17586, 17585, 17587, -1, 17582, 17566, 17583, -1, 17588, 17584, 17589, -1, 17586, 17587, 17590, -1, 17591, 17501, 17494, -1, 17588, 17589, 17592, -1, 17591, 17593, 17501, -1, 17594, 17590, 17595, -1, 17594, 17595, 17596, -1, 17597, 17592, 17598, -1, 17597, 17598, 17599, -1, 17600, 17601, 17593, -1, 17602, 17596, 17603, -1, 17602, 17603, 17604, -1, 17600, 17593, 17591, -1, 17605, 17599, 17476, -1, 17606, 17497, 17506, -1, 17607, 17494, 17483, -1, 17605, 17476, 17475, -1, 17606, 17604, 17497, -1, 17607, 17591, 17494, -1, 17608, 17581, 17564, -1, 17609, 17567, 17569, -1, 17610, 17601, 17600, -1, 17608, 17611, 17612, -1, 17609, 17613, 17614, -1, 17608, 17615, 17581, -1, 17609, 17614, 17567, -1, 17610, 17616, 17601, -1, 17608, 17612, 17615, -1, 17617, 17564, 17566, -1, 17609, 17569, 17576, -1, 17617, 17566, 17582, -1, 17618, 17576, 17585, -1, 17619, 17600, 17591, -1, 17618, 17585, 17586, -1, 17620, 17590, 17594, -1, 17620, 17586, 17590, -1, 17619, 17591, 17607, -1, 17621, 17607, 17483, -1, 17621, 17483, 17471, -1, 17622, 17582, 17584, -1, 17622, 17584, 17588, -1, 17623, 17588, 17592, -1, 17624, 17594, 17596, -1, 17573, 15181, 17625, -1, 17626, 17627, 17616, -1, 17624, 17596, 17602, -1, 17623, 17592, 17597, -1, 17626, 17616, 17610, -1, 17628, 17599, 17605, -1, 17629, 17602, 17604, -1, 17630, 17600, 17619, -1, 17629, 17604, 17606, -1, 17630, 17610, 17600, -1, 17628, 17597, 17599, -1, 17631, 17475, 17491, -1, 17632, 17506, 17511, -1, 17631, 17491, 17492, -1, 17631, 17492, 17633, -1, 17632, 17606, 17506, -1, 17634, 17619, 17607, -1, 17631, 17605, 17475, -1, 17635, 17608, 17564, -1, 17636, 17637, 17613, -1, 17635, 17638, 17611, -1, 17636, 17613, 17609, -1, 17634, 17607, 17621, -1, 17635, 17611, 17608, -1, 17636, 17576, 17618, -1, 17636, 17609, 17576, -1, 17639, 17471, 17477, -1, 17635, 17564, 17617, -1, 17640, 17582, 17622, -1, 17640, 17617, 17582, -1, 17641, 17618, 17586, -1, 17639, 17621, 17471, -1, 17641, 17586, 17620, -1, 17642, 17622, 17588, -1, 17642, 17588, 17623, -1, 17568, 17643, 17627, -1, 17565, 17594, 17624, -1, 17565, 17620, 17594, -1, 17568, 17627, 17626, -1, 17577, 17610, 17630, -1, 17583, 17624, 17602, -1, 17577, 17626, 17610, -1, 17583, 17602, 17629, -1, 17587, 17630, 17619, -1, 17644, 17623, 17597, -1, 17644, 17597, 17628, -1, 17645, 17631, 17633, -1, 17645, 17633, 17646, -1, 17645, 17628, 17605, -1, 17587, 17619, 17634, -1, 17645, 17605, 17631, -1, 17647, 17635, 17617, -1, 17589, 17606, 17632, -1, 17647, 17648, 17638, -1, 17589, 17629, 17606, -1, 17647, 17638, 17635, -1, 17598, 17511, 17515, -1, 17595, 17634, 17621, -1, 17647, 17617, 17640, -1, 17595, 17621, 17639, -1, 17603, 17639, 17477, -1, 17603, 17477, 17488, -1, 17598, 17632, 17511, -1, 17649, 17640, 17622, -1, 17649, 17622, 17642, -1, 17650, 17651, 17637, -1, 17650, 17637, 17636, -1, 17650, 17636, 17618, -1, 17650, 17618, 17641, -1, 17574, 17625, 17643, -1, 17574, 17573, 17625, -1, 17574, 17643, 17568, -1, 17562, 17642, 17623, -1, 17562, 17623, 17644, -1, 17581, 17641, 17620, -1, 17652, 17646, 17653, -1, 17581, 17620, 17565, -1, 17569, 17626, 17577, -1, 17652, 17645, 17646, -1, 17652, 17644, 17628, -1, 17652, 17628, 17645, -1, 17569, 17568, 17626, -1, 17566, 17624, 17583, -1, 17566, 17565, 17624, -1, 17654, 17655, 17648, -1, 17585, 17577, 17630, -1, 17654, 17648, 17647, -1, 17654, 17647, 17640, -1, 17585, 17630, 17587, -1, 17654, 17640, 17649, -1, 17584, 17583, 17629, -1, 17584, 17629, 17589, -1, 17580, 17649, 17642, -1, 17590, 17634, 17595, -1, 17590, 17587, 17634, -1, 17580, 17642, 17562, -1, 17563, 17653, 17656, -1, 17592, 17589, 17632, -1, 17563, 17652, 17653, -1, 17563, 17562, 17644, -1, 17596, 17639, 17603, -1, 17563, 17644, 17652, -1, 17596, 17595, 17639, -1, 17592, 17632, 17598, -1, 17579, 17649, 17580, -1, 17604, 17488, 17497, -1, 17599, 17515, 17476, -1, 17579, 17578, 17655, -1, 17579, 17655, 17654, -1, 17579, 17654, 17649, -1, 17599, 17598, 17515, -1, 17561, 17656, 17571, -1, 17604, 17603, 17488, -1, 17567, 17574, 17568, -1, 17615, 17612, 17651, -1, 17561, 17563, 17656, -1, 17615, 17651, 17650, -1, 17615, 17650, 17641, -1, 17567, 17614, 17573, -1, 17561, 17580, 17562, -1, 17615, 17641, 17581, -1, 17657, 17550, 17552, -1, 17657, 17658, 17550, -1, 17550, 17659, 17556, -1, 17658, 17659, 17550, -1, 17556, 17660, 17559, -1, 17659, 17660, 17556, -1, 17559, 17661, 17538, -1, 17660, 17661, 17559, -1, 17538, 17662, 17536, -1, 17661, 17662, 17538, -1, 17536, 17663, 17544, -1, 17662, 17663, 17536, -1, 17663, 17545, 17544, -1, 17663, 17664, 17545, -1, 17486, 17665, 17666, -1, 17667, 17665, 17486, -1, 17668, 17669, 17670, -1, 17670, 17669, 17671, -1, 17672, 17669, 17673, -1, 17671, 17669, 17672, -1, 17666, 17674, 17675, -1, 17665, 17674, 17666, -1, 17673, 17674, 17667, -1, 17667, 17674, 17665, -1, 17675, 17676, 17677, -1, 17677, 17676, 17678, -1, 17678, 17676, 17679, -1, 17679, 17676, 17668, -1, 17668, 17676, 17669, -1, 17674, 17676, 17675, -1, 17669, 17676, 17673, -1, 17673, 17676, 17674, -1, 17680, 17681, 17682, -1, 17486, 17666, 17466, -1, 17683, 17684, 17469, -1, 17469, 17684, 17485, -1, 17485, 17684, 17493, -1, 17685, 17686, 17683, -1, 17683, 17686, 17684, -1, 17493, 17687, 17499, -1, 17684, 17687, 17493, -1, 17682, 17688, 17685, -1, 17685, 17688, 17686, -1, 17681, 17688, 17682, -1, 17684, 17689, 17687, -1, 17686, 17689, 17684, -1, 17499, 17690, 17500, -1, 17687, 17690, 17499, -1, 17691, 17692, 17681, -1, 17681, 17692, 17688, -1, 17686, 17692, 17689, -1, 17688, 17692, 17686, -1, 17689, 17693, 17687, -1, 17687, 17693, 17690, -1, 17500, 17694, 17496, -1, 17690, 17694, 17500, -1, 17695, 17696, 17691, -1, 17692, 17696, 17689, -1, 17691, 17696, 17692, -1, 17689, 17696, 17693, -1, 17690, 17672, 17694, -1, 17693, 17672, 17690, -1, 17496, 17667, 17486, -1, 17694, 17667, 17496, -1, 17670, 17671, 17695, -1, 17695, 17671, 17696, -1, 17696, 17671, 17693, -1, 17693, 17671, 17672, -1, 17672, 17673, 17694, -1, 17694, 17673, 17667, -1, 17697, 17698, 17680, -1, 17680, 17698, 17681, -1, 17681, 17699, 17691, -1, 17698, 17699, 17681, -1, 17691, 17700, 17695, -1, 17699, 17700, 17691, -1, 17695, 17701, 17670, -1, 17700, 17701, 17695, -1, 17670, 17702, 17668, -1, 17701, 17702, 17670, -1, 17668, 17703, 17679, -1, 17702, 17703, 17668, -1, 17679, 17704, 17678, -1, 17703, 17704, 17679, -1, 17705, 17706, 17707, -1, 17705, 17708, 17706, -1, 17709, 17710, 17711, -1, 17712, 17711, 16209, -1, 17712, 17709, 17711, -1, 16177, 17713, 17714, -1, 16177, 16176, 17713, -1, 17715, 17716, 17710, -1, 17715, 17710, 17709, -1, 17717, 17712, 16209, -1, 17718, 17719, 17716, -1, 17718, 17716, 17715, -1, 17720, 17721, 17708, -1, 17720, 17708, 17705, -1, 16178, 17714, 17722, -1, 17723, 17717, 16209, -1, 16178, 16177, 17714, -1, 16185, 17721, 17720, -1, 17724, 16172, 17719, -1, 17724, 17719, 17718, -1, 16179, 17722, 17725, -1, 17726, 16209, 16188, -1, 16179, 16178, 17722, -1, 17726, 17723, 16209, -1, 16184, 17721, 16185, -1, 17727, 16173, 16172, -1, 16184, 17728, 17721, -1, 17727, 16172, 17724, -1, 16180, 17725, 17729, -1, 16180, 17729, 17730, -1, 16180, 16179, 17725, -1, 17731, 17726, 16188, -1, 17732, 16174, 16173, -1, 16183, 17733, 17728, -1, 16183, 17728, 16184, -1, 17732, 16173, 17727, -1, 16181, 16180, 17730, -1, 16182, 17730, 17734, -1, 16182, 17734, 17733, -1, 16182, 16181, 17730, -1, 17735, 16188, 17736, -1, 16182, 17733, 16183, -1, 17735, 17731, 16188, -1, 17737, 16175, 16174, -1, 17737, 16174, 17732, -1, 17738, 17735, 17736, -1, 17707, 17738, 17736, -1, 17706, 17738, 17707, -1, 16176, 17737, 17713, -1, 16176, 16175, 17737, -1, 17721, 15781, 17708, -1, 17708, 17739, 17706, -1, 15781, 17739, 17708, -1, 17706, 17740, 17738, -1, 17739, 17740, 17706, -1, 17738, 17741, 17735, -1, 17740, 17741, 17738, -1, 17735, 17742, 17731, -1, 17741, 17742, 17735, -1, 17731, 17743, 17726, -1, 17742, 17743, 17731, -1, 17726, 17744, 17723, -1, 17743, 17744, 17726, -1, 17723, 17745, 17717, -1, 17744, 17745, 17723, -1, 17717, 17746, 17712, -1, 17745, 17746, 17717, -1, 17712, 17747, 17709, -1, 17746, 17747, 17712, -1, 17709, 17748, 17715, -1, 17747, 17748, 17709, -1, 17715, 17749, 17718, -1, 17748, 17749, 17715, -1, 17718, 17750, 17724, -1, 17749, 17750, 17718, -1, 17750, 15826, 17724, -1, 15826, 15799, 17724, -1, 17724, 15799, 17727, -1, 17727, 15798, 17732, -1, 15799, 15798, 17727, -1, 17732, 15845, 17737, -1, 15798, 15845, 17732, -1, 17737, 15830, 17713, -1, 15845, 15830, 17737, -1, 17713, 15829, 17714, -1, 15830, 15829, 17713, -1, 17714, 15804, 17722, -1, 15829, 15804, 17714, -1, 17722, 15803, 17725, -1, 15804, 15803, 17722, -1, 17725, 15847, 17729, -1, 15803, 15847, 17725, -1, 17729, 15836, 17730, -1, 15847, 15836, 17729, -1, 17730, 15817, 17734, -1, 15836, 15817, 17730, -1, 17734, 15801, 17733, -1, 15817, 15801, 17734, -1, 17733, 15782, 17728, -1, 15801, 15782, 17733, -1, 17728, 15781, 17721, -1, 15782, 15781, 17728, -1, 17751, 17752, 15369, -1, 17751, 15369, 15368, -1, 17751, 15368, 15412, -1, 15402, 17751, 15412, -1, 17753, 15351, 17754, -1, 17753, 17754, 17755, -1, 17753, 17755, 17756, -1, 17753, 17756, 17757, -1, 17758, 15351, 17753, -1, 17758, 15383, 15371, -1, 17758, 15371, 15352, -1, 17758, 15352, 15351, -1, 17759, 17760, 17761, -1, 17758, 17751, 15402, -1, 17758, 15402, 15383, -1, 17762, 17761, 17763, -1, 17762, 17759, 17761, -1, 17764, 17765, 17760, -1, 17764, 17760, 17759, -1, 17766, 17763, 17767, -1, 17766, 17762, 17763, -1, 17768, 17769, 17765, -1, 17768, 17765, 17764, -1, 17770, 17767, 17757, -1, 17770, 17766, 17767, -1, 15390, 17771, 17769, -1, 15390, 17769, 17768, -1, 17772, 17770, 17757, -1, 15389, 17773, 17771, -1, 15389, 17771, 15390, -1, 17774, 17772, 17757, -1, 15361, 17773, 15389, -1, 17775, 17773, 15361, -1, 17776, 17774, 17757, -1, 15360, 17775, 15361, -1, 17756, 17776, 17757, -1, 17777, 17775, 15360, -1, 15410, 17777, 15360, -1, 17778, 15410, 15396, -1, 17778, 17777, 15410, -1, 17752, 15396, 15369, -1, 17752, 17778, 15396, -1, 16038, 16037, 17779, -1, 16038, 17779, 17780, -1, 17781, 17782, 17783, -1, 17784, 17785, 17786, -1, 16039, 17780, 17787, -1, 16039, 16038, 17780, -1, 16046, 17788, 17782, -1, 16046, 17789, 17788, -1, 17790, 17786, 17791, -1, 16046, 17782, 17781, -1, 17790, 17784, 17786, -1, 16040, 17787, 17792, -1, 17793, 17794, 17785, -1, 16040, 16039, 17787, -1, 17793, 17785, 17784, -1, 16045, 17789, 16046, -1, 17795, 17791, 17796, -1, 16041, 17792, 17797, -1, 17795, 17790, 17791, -1, 16041, 16040, 17792, -1, 17798, 16033, 17794, -1, 16044, 17799, 17789, -1, 17798, 17794, 17793, -1, 16044, 17789, 16045, -1, 17800, 17796, 17801, -1, 16042, 17797, 17802, -1, 16042, 16041, 17797, -1, 17800, 17795, 17796, -1, 16043, 17802, 17799, -1, 16043, 16042, 17802, -1, 16043, 17799, 16044, -1, 17803, 16033, 17798, -1, 17804, 17801, 17805, -1, 17804, 17800, 17801, -1, 17806, 16034, 16033, -1, 17806, 16033, 17803, -1, 17807, 17805, 17808, -1, 17807, 17804, 17805, -1, 17809, 16035, 16034, -1, 17809, 16034, 17806, -1, 17810, 17808, 17811, -1, 17810, 17807, 17808, -1, 17812, 16036, 16035, -1, 17812, 16035, 17809, -1, 17813, 17810, 17811, -1, 17814, 17813, 17811, -1, 17815, 16036, 17812, -1, 17816, 17813, 17814, -1, 16037, 16036, 17815, -1, 17779, 16037, 17815, -1, 17783, 17816, 17814, -1, 17783, 17782, 17816, -1, 16640, 17817, 17788, -1, 17788, 17817, 17782, -1, 17782, 17818, 17816, -1, 17817, 17818, 17782, -1, 17816, 17819, 17813, -1, 17818, 17819, 17816, -1, 17813, 17820, 17810, -1, 17819, 17820, 17813, -1, 17810, 17821, 17807, -1, 17820, 17821, 17810, -1, 17807, 17822, 17804, -1, 17821, 17822, 17807, -1, 17804, 17823, 17800, -1, 17822, 17823, 17804, -1, 17800, 17824, 17795, -1, 17823, 17824, 17800, -1, 17795, 17825, 17790, -1, 17824, 17825, 17795, -1, 17790, 17826, 17784, -1, 17825, 17826, 17790, -1, 17784, 17827, 17793, -1, 17826, 17827, 17784, -1, 17793, 17828, 17798, -1, 17827, 17828, 17793, -1, 17798, 16684, 17803, -1, 17828, 16684, 17798, -1, 16093, 16185, 17720, -1, 16095, 17720, 17705, -1, 16095, 16093, 17720, -1, 16096, 17705, 17707, -1, 16096, 16095, 17705, -1, 16097, 17707, 17736, -1, 16097, 16096, 17707, -1, 16098, 17736, 16188, -1, 16098, 16097, 17736, -1, 16075, 16188, 16197, -1, 16075, 16098, 16188, -1, 16073, 16195, 16194, -1, 16073, 16197, 16195, -1, 16073, 16075, 16197, -1, 16072, 16194, 16210, -1, 16072, 16073, 16194, -1, 16130, 16210, 16209, -1, 16130, 16072, 16210, -1, 16122, 16209, 17711, -1, 16122, 16130, 16209, -1, 16123, 17711, 17710, -1, 16123, 16122, 17711, -1, 16124, 17710, 17716, -1, 16124, 16123, 17710, -1, 16131, 17716, 17719, -1, 16131, 16124, 17716, -1, 16137, 17719, 16172, -1, 16137, 16131, 17719, -1, 16030, 16032, 16046, -1, 16030, 16046, 17781, -1, 16026, 17781, 17783, -1, 16026, 16030, 17781, -1, 16027, 17783, 17814, -1, 16027, 16026, 17783, -1, 16028, 17814, 17811, -1, 16028, 16027, 17814, -1, 16052, 17811, 17808, -1, 16052, 16029, 16028, -1, 16052, 16028, 17811, -1, 16053, 17808, 17805, -1, 16053, 16052, 17808, -1, 16051, 17805, 17801, -1, 16051, 16053, 17805, -1, 16050, 17801, 17796, -1, 16050, 16051, 17801, -1, 16049, 17796, 17791, -1, 16049, 16050, 17796, -1, 16048, 16049, 17791, -1, 16019, 17791, 17786, -1, 16019, 16018, 16048, -1, 16019, 16048, 17791, -1, 16020, 17786, 17785, -1, 16020, 16019, 17786, -1, 16003, 17785, 17794, -1, 16003, 16020, 17785, -1, 16002, 17794, 16033, -1, 16002, 16003, 17794, -1, 16005, 16002, 16033, -1, 17664, 17829, 17545, -1, 17664, 17830, 17829, -1, 17830, 17831, 17829, -1, 17829, 17831, 17832, -1, 17832, 17833, 17834, -1, 17831, 17833, 17832, -1, 17834, 17835, 17836, -1, 17833, 17835, 17834, -1, 17836, 17837, 17838, -1, 17835, 17837, 17836, -1, 17838, 17839, 17840, -1, 17837, 17839, 17838, -1, 17840, 17841, 17842, -1, 17839, 17841, 17840, -1, 17842, 17697, 17680, -1, 17841, 17697, 17842, -1, 17843, 17835, 17844, -1, 17843, 17844, 17845, -1, 17846, 17847, 17848, -1, 17846, 17848, 17849, -1, 17850, 17851, 17852, -1, 17850, 17853, 17851, -1, 17850, 17852, 17854, -1, 17850, 17849, 17853, -1, 17855, 17839, 17837, -1, 17855, 17837, 17843, -1, 17855, 17843, 17847, -1, 17855, 17847, 17846, -1, 17856, 17854, 17857, -1, 17856, 17846, 17849, -1, 17856, 17850, 17854, -1, 17856, 17849, 17850, -1, 17858, 17857, 17859, -1, 17858, 17841, 17839, -1, 17858, 17846, 17856, -1, 17858, 17859, 17841, -1, 17858, 17839, 17855, -1, 17858, 17856, 17857, -1, 17858, 17855, 17846, -1, 17697, 17841, 17859, -1, 17860, 17861, 17862, -1, 17860, 17863, 17861, -1, 17864, 17865, 17863, -1, 17864, 17863, 17860, -1, 17866, 17862, 17867, -1, 17866, 17860, 17862, -1, 17868, 17831, 17830, -1, 17868, 17830, 17869, -1, 17868, 17869, 17865, -1, 17868, 17865, 17864, -1, 17870, 17860, 17866, -1, 17870, 17864, 17860, -1, 17871, 17867, 17872, -1, 17871, 17866, 17867, -1, 17873, 17833, 17831, -1, 17873, 17864, 17870, -1, 17873, 17831, 17868, -1, 17873, 17868, 17864, -1, 17845, 17870, 17866, -1, 17845, 17866, 17871, -1, 17848, 17872, 17874, -1, 17848, 17871, 17872, -1, 17844, 17835, 17833, -1, 17844, 17873, 17870, -1, 17844, 17870, 17845, -1, 17844, 17833, 17873, -1, 17847, 17845, 17871, -1, 17847, 17871, 17848, -1, 17849, 17874, 17853, -1, 17849, 17848, 17874, -1, 17843, 17837, 17835, -1, 17843, 17845, 17847, -1, 17875, 17876, 17877, -1, 17878, 17876, 17875, -1, 17879, 17876, 17878, -1, 17880, 17881, 17882, -1, 17880, 17882, 17883, -1, 17884, 17885, 17886, -1, 17887, 17880, 17883, -1, 17887, 17885, 17884, -1, 17887, 17888, 17889, -1, 17887, 17889, 17885, -1, 17890, 17891, 17892, -1, 17890, 17893, 17891, -1, 17890, 17894, 17893, -1, 17887, 17883, 17888, -1, 17895, 17884, 17886, -1, 17896, 17897, 17898, -1, 17896, 17898, 17894, -1, 17899, 17895, 17886, -1, 17899, 17886, 17900, -1, 17901, 17896, 17894, -1, 17902, 17899, 17900, -1, 17903, 17894, 17890, -1, 17903, 17901, 17894, -1, 17904, 17851, 17853, -1, 17905, 17902, 17900, -1, 17904, 17853, 17874, -1, 17906, 17903, 17890, -1, 17907, 17905, 17900, -1, 17904, 17874, 17872, -1, 17904, 17872, 17867, -1, 17904, 17867, 17862, -1, 17904, 17862, 17861, -1, 17908, 17905, 17907, -1, 17909, 17906, 17890, -1, 17910, 17909, 17890, -1, 17883, 17876, 17879, -1, 17883, 17879, 17911, -1, 17912, 17904, 17861, -1, 17912, 17861, 17913, -1, 17852, 17851, 17904, -1, 17914, 17852, 17904, -1, 17915, 17909, 17910, -1, 17915, 17916, 17917, -1, 17915, 17910, 17916, -1, 17918, 17919, 17915, -1, 17920, 17918, 17915, -1, 17876, 17915, 17917, -1, 17876, 17920, 17915, -1, 17876, 17917, 17921, -1, 17922, 17912, 17923, -1, 17924, 17923, 17912, -1, 17925, 17912, 17922, -1, 17926, 17912, 17925, -1, 17927, 17924, 17912, -1, 17928, 17886, 17929, -1, 17913, 17927, 17912, -1, 17930, 17912, 17926, -1, 17930, 17921, 17912, -1, 17930, 17876, 17921, -1, 17900, 17928, 17931, -1, 17900, 17886, 17928, -1, 17883, 17914, 17888, -1, 17932, 17876, 17930, -1, 17883, 17911, 17933, -1, 17883, 17933, 17934, -1, 17935, 17876, 17932, -1, 17883, 17934, 17936, -1, 17883, 17936, 17937, -1, 17883, 17937, 17938, -1, 17883, 17938, 17939, -1, 17940, 17876, 17935, -1, 17883, 17939, 17852, -1, 17883, 17852, 17914, -1, 17877, 17876, 17940, -1, 17941, 17942, 17943, -1, 17941, 17944, 17945, -1, 17941, 17943, 17944, -1, 17946, 17947, 17948, -1, 17946, 17949, 17947, -1, 17946, 17945, 17950, -1, 17946, 17950, 17949, -1, 17878, 17951, 17879, -1, 17952, 17948, 17953, -1, 17952, 17946, 17948, -1, 17952, 17954, 17941, -1, 17952, 17953, 17954, -1, 17952, 17941, 17945, -1, 17952, 17945, 17946, -1, 17955, 17956, 17957, -1, 17657, 17954, 17953, -1, 17958, 17878, 17875, -1, 17958, 17951, 17878, -1, 17959, 17960, 17951, -1, 17959, 17951, 17958, -1, 17961, 17875, 17877, -1, 17961, 17958, 17875, -1, 17962, 17963, 17955, -1, 17962, 17957, 17960, -1, 17962, 17955, 17957, -1, 17962, 17960, 17959, -1, 17964, 17958, 17961, -1, 17964, 17959, 17958, -1, 17965, 17877, 17940, -1, 17965, 17961, 17877, -1, 17966, 17967, 17963, -1, 17966, 17963, 17962, -1, 17966, 17962, 17959, -1, 17966, 17959, 17964, -1, 17968, 17964, 17961, -1, 17968, 17961, 17965, -1, 17969, 17940, 17935, -1, 17969, 17965, 17940, -1, 17970, 17971, 17967, -1, 17970, 17966, 17964, -1, 17970, 17967, 17966, -1, 17970, 17964, 17968, -1, 17944, 17965, 17969, -1, 17944, 17968, 17965, -1, 17950, 17935, 17932, -1, 17950, 17969, 17935, -1, 17943, 17942, 17971, -1, 17943, 17971, 17970, -1, 17943, 17970, 17968, -1, 17943, 17968, 17944, -1, 17945, 17944, 17969, -1, 17945, 17969, 17950, -1, 17949, 17932, 17930, -1, 17949, 17930, 17947, -1, 17949, 17950, 17932, -1, 17941, 17954, 17942, -1, 17704, 17972, 17678, -1, 17704, 17956, 17972, -1, 17803, 16684, 17806, -1, 16684, 16683, 17806, -1, 17806, 16657, 17809, -1, 16683, 16657, 17806, -1, 17809, 16656, 17812, -1, 16657, 16656, 17809, -1, 17812, 16700, 17815, -1, 16656, 16700, 17812, -1, 17815, 16687, 17779, -1, 16700, 16687, 17815, -1, 17779, 16660, 17780, -1, 16687, 16660, 17779, -1, 17780, 16659, 17787, -1, 16660, 16659, 17780, -1, 17787, 16702, 17792, -1, 16659, 16702, 17787, -1, 17792, 16693, 17797, -1, 16702, 16693, 17792, -1, 17797, 16673, 17802, -1, 16693, 16673, 17797, -1, 17802, 16662, 17799, -1, 16673, 16662, 17802, -1, 17799, 16641, 17789, -1, 16662, 16641, 17799, -1, 17789, 16640, 17788, -1, 16641, 16640, 17789, -1, 17305, 17337, 17140, -1, 17134, 17305, 17140, -1, 17351, 17343, 17301, -1, 17351, 17301, 17308, -1, 17352, 17308, 17309, -1, 17352, 17309, 17306, -1, 17352, 17351, 17308, -1, 17350, 17352, 17306, -1, 17306, 17312, 17354, -1, 17306, 17354, 17350, -1, 15918, 15917, 15964, -1, 15964, 15917, 17133, -1, 17133, 15919, 17135, -1, 15917, 15919, 17133, -1, 17135, 15920, 17136, -1, 15919, 15920, 17135, -1, 17136, 15921, 17137, -1, 15920, 15921, 17136, -1, 17137, 15922, 17138, -1, 15921, 15922, 17137, -1, 17138, 15923, 17148, -1, 15922, 15923, 17138, -1, 17148, 15924, 17149, -1, 15923, 15924, 17148, -1, 17149, 15950, 17150, -1, 15924, 15950, 17149, -1, 17150, 15948, 17145, -1, 15950, 15948, 17150, -1, 17145, 15946, 17144, -1, 15948, 15946, 17145, -1, 17144, 15944, 17146, -1, 15946, 15944, 17144, -1, 17146, 15942, 17147, -1, 15944, 15942, 17146, -1, 17147, 15940, 15951, -1, 15942, 15940, 17147, -1, 3250, 16813, 16814, -1, 3250, 17973, 16813, -1, 3197, 17974, 3250, -1, 3250, 17974, 17973, -1, 3197, 17975, 17974, -1, 3197, 17976, 17975, -1, 3197, 17977, 17976, -1, 3197, 14991, 17977, -1, 14991, 17978, 17977, -1, 17979, 17980, 17981, -1, 17982, 17979, 17981, -1, 17983, 17984, 17985, -1, 17986, 17984, 17983, -1, 17987, 17981, 17984, -1, 17987, 17982, 17981, -1, 17987, 17984, 17986, -1, 17988, 17978, 17989, -1, 17990, 17987, 17977, -1, 17990, 17977, 17978, -1, 17990, 17978, 17988, -1, 17990, 17982, 17987, -1, 17984, 17991, 17985, -1, 17991, 17992, 17985, -1, 17992, 17993, 17985, -1, 17994, 17993, 17995, -1, 17985, 17993, 17994, -1, 17996, 17997, 17998, -1, 17998, 17997, 17999, -1, 17999, 17997, 18000, -1, 17997, 18001, 18000, -1, 18000, 18002, 18003, -1, 18001, 18002, 18000, -1, 18002, 18004, 18003, -1, 18004, 18005, 18003, -1, 18006, 18007, 18008, -1, 18009, 18007, 18006, -1, 18010, 18007, 18009, -1, 18005, 18011, 18003, -1, 17993, 18012, 17995, -1, 17995, 18012, 18013, -1, 18007, 18012, 18008, -1, 18008, 18012, 17993, -1, 18013, 18014, 18015, -1, 18012, 18014, 18013, -1, 18014, 18016, 18015, -1, 18017, 18018, 18019, -1, 18018, 18020, 18019, -1, 18019, 18021, 18022, -1, 18020, 18021, 18019, -1, 18023, 18024, 18025, -1, 18024, 18026, 18025, -1, 18027, 18028, 18029, -1, 18025, 18028, 18027, -1, 18021, 18030, 18022, -1, 18026, 18028, 18025, -1, 18031, 18032, 18033, -1, 18033, 18032, 18034, -1, 18034, 18032, 18030, -1, 18032, 18035, 18030, -1, 18036, 18037, 18016, -1, 18038, 18037, 18036, -1, 18029, 18037, 18038, -1, 18028, 18037, 18029, -1, 18030, 18039, 18022, -1, 18035, 18039, 18030, -1, 18028, 18040, 18037, -1, 18037, 18003, 18011, -1, 18037, 18011, 18041, -1, 18037, 18041, 18015, -1, 18037, 18015, 18016, -1, 18042, 18000, 18003, -1, 18039, 18043, 18022, -1, 18022, 18043, 18044, -1, 18044, 18041, 18011, -1, 18043, 18041, 18044, -1, 18011, 18005, 18045, -1, 18046, 18047, 18048, -1, 18046, 18045, 18047, -1, 18046, 18011, 18045, -1, 18049, 18048, 18050, -1, 18049, 18046, 18048, -1, 18051, 18050, 18052, -1, 18051, 18049, 18050, -1, 18053, 18051, 18052, -1, 18054, 18055, 18056, -1, 18055, 18057, 18056, -1, 18010, 18058, 18007, -1, 18010, 18059, 18058, -1, 18056, 18060, 18010, -1, 18057, 18060, 18056, -1, 18010, 18060, 18059, -1, 18061, 18062, 18063, -1, 18064, 18062, 18061, -1, 18060, 18062, 18064, -1, 18057, 18062, 18060, -1, 18065, 18066, 18067, -1, 18067, 18068, 18069, -1, 18066, 18068, 18067, -1, 18068, 18070, 18069, -1, 18071, 18023, 18025, -1, 18072, 18023, 18071, -1, 18070, 18023, 18072, -1, 18070, 18073, 18023, -1, 18070, 18074, 18073, -1, 18068, 18074, 18070, -1, 18075, 18076, 18077, -1, 18078, 18079, 18080, -1, 18081, 18082, 18076, -1, 18081, 18083, 18082, -1, 18081, 18076, 18075, -1, 18084, 18085, 18086, -1, 18084, 18087, 18085, -1, 18084, 18080, 18087, -1, 18084, 18078, 18080, -1, 18088, 18089, 18083, -1, 18088, 18090, 18089, -1, 18088, 18083, 18081, -1, 18091, 18084, 18086, -1, 18092, 18090, 18088, -1, 18093, 18091, 18086, -1, 18094, 18090, 18092, -1, 18095, 18096, 18097, -1, 18095, 18098, 18096, -1, 18099, 18100, 18098, -1, 18099, 18098, 18095, -1, 18101, 18095, 18097, -1, 18102, 18103, 18100, -1, 18102, 18100, 18099, -1, 18104, 18105, 18103, -1, 18104, 18094, 18105, -1, 18104, 18103, 18102, -1, 18106, 18107, 18108, -1, 18106, 18109, 18107, -1, 18106, 18110, 18111, -1, 18106, 18112, 18110, -1, 18106, 18113, 18112, -1, 18106, 18108, 18113, -1, 18114, 18106, 18111, -1, 18115, 18111, 18093, -1, 18115, 18093, 18086, -1, 18115, 18114, 18111, -1, 18116, 18115, 18086, -1, 18117, 18116, 18086, -1, 18118, 18117, 18086, -1, 18118, 18119, 18117, -1, 18120, 18119, 18118, -1, 18121, 18120, 18118, -1, 18122, 18121, 18118, -1, 18122, 18123, 18124, -1, 18122, 18125, 18123, -1, 18122, 18118, 18125, -1, 18126, 18122, 18124, -1, 18127, 18122, 18126, -1, 18128, 18122, 18127, -1, 18003, 18129, 18122, -1, 18003, 18130, 18129, -1, 18003, 18122, 18128, -1, 18131, 18130, 18003, -1, 18132, 18131, 18003, -1, 18133, 18132, 18003, -1, 18134, 18094, 18104, -1, 18135, 18136, 18134, -1, 18135, 18134, 18137, -1, 18138, 18094, 18134, -1, 18138, 18134, 18136, -1, 18139, 18135, 18137, -1, 18139, 18137, 18140, -1, 18141, 18090, 18094, -1, 18141, 18094, 18138, -1, 18141, 18138, 18142, -1, 18143, 18139, 18140, -1, 18143, 18140, 18144, -1, 18145, 18141, 18142, -1, 18145, 18146, 18147, -1, 18145, 18147, 18141, -1, 18148, 18143, 18144, -1, 18149, 18146, 18145, -1, 18149, 18150, 18151, -1, 18149, 18151, 18146, -1, 18152, 18148, 18144, -1, 18153, 18150, 18149, -1, 18154, 18152, 18144, -1, 18155, 18150, 18153, -1, 18156, 18157, 18158, -1, 18159, 18156, 18158, -1, 18160, 18156, 18159, -1, 18161, 18160, 18159, -1, 18162, 18161, 18159, -1, 18163, 18162, 18159, -1, 18164, 18162, 18163, -1, 18165, 18166, 18167, -1, 18165, 18167, 18168, -1, 18165, 18168, 18169, -1, 18165, 18169, 18170, -1, 18165, 18170, 18171, -1, 18165, 18171, 18172, -1, 18173, 18166, 18165, -1, 18174, 18162, 18164, -1, 18174, 18166, 18173, -1, 18174, 18164, 18166, -1, 18175, 18162, 18174, -1, 18176, 18162, 18175, -1, 18177, 18133, 18003, -1, 18037, 18178, 18179, -1, 18037, 18179, 18180, -1, 18037, 18180, 18181, -1, 18037, 18181, 18182, -1, 18037, 18182, 18177, -1, 18037, 18177, 18003, -1, 18183, 18184, 18185, -1, 18183, 18185, 18178, -1, 18183, 18176, 18186, -1, 18183, 18186, 18184, -1, 18187, 18178, 18037, -1, 18188, 18183, 18178, -1, 18189, 18178, 18187, -1, 18190, 18188, 18178, -1, 18191, 18178, 18189, -1, 18192, 18190, 18178, -1, 18192, 18178, 18191, -1, 18183, 18162, 18176, -1, 18144, 18165, 18193, -1, 18193, 18165, 18172, -1, 18144, 18193, 18154, -1, 18106, 18095, 18194, -1, 18194, 18095, 18101, -1, 18106, 18194, 18109, -1, 18195, 18196, 18197, -1, 18195, 18197, 18198, -1, 18199, 18107, 18109, -1, 18200, 18201, 18202, -1, 18203, 18204, 18205, -1, 18206, 18096, 18098, -1, 18199, 18207, 18107, -1, 18203, 18205, 18208, -1, 18209, 18210, 18207, -1, 18206, 18211, 18096, -1, 18212, 18213, 18214, -1, 18107, 18207, 18108, -1, 18212, 18214, 18215, -1, 18212, 18216, 18217, -1, 18209, 18207, 18199, -1, 18218, 18201, 18200, -1, 18212, 18215, 18216, -1, 18218, 18219, 18201, -1, 18220, 18221, 18196, -1, 18222, 18223, 18210, -1, 18220, 18196, 18195, -1, 18222, 18210, 18209, -1, 18224, 18204, 18203, -1, 18225, 18198, 18211, -1, 18226, 18109, 18194, -1, 18224, 18227, 18204, -1, 18225, 18211, 18206, -1, 18226, 18199, 18109, -1, 18228, 18094, 18092, -1, 18229, 18230, 18223, -1, 18228, 18208, 18094, -1, 18231, 18221, 18220, -1, 18231, 18217, 18221, -1, 18229, 18223, 18222, -1, 18232, 18233, 18234, -1, 18232, 18234, 18235, -1, 18236, 18209, 18199, -1, 18232, 18219, 18218, -1, 18237, 18198, 18225, -1, 18232, 18235, 18219, -1, 18237, 18195, 18198, -1, 18236, 18199, 18226, -1, 18238, 18200, 18227, -1, 18238, 18227, 18224, -1, 18239, 18098, 18100, -1, 18240, 18241, 18230, -1, 18242, 18203, 18208, -1, 18239, 18206, 18098, -1, 18240, 18230, 18229, -1, 18243, 18222, 18209, -1, 18244, 18213, 18212, -1, 18242, 18208, 18228, -1, 18244, 18245, 18213, -1, 18244, 18212, 18217, -1, 18244, 18217, 18231, -1, 18243, 18209, 18236, -1, 18246, 18220, 18195, -1, 18247, 18194, 18101, -1, 18248, 18218, 18200, -1, 18248, 18200, 18238, -1, 18246, 18195, 18237, -1, 18247, 18226, 18194, -1, 18249, 18225, 18206, -1, 18250, 18224, 18203, -1, 18251, 18252, 18253, -1, 18249, 18206, 18239, -1, 18251, 18254, 18241, -1, 18251, 18253, 18254, -1, 18250, 18203, 18242, -1, 18251, 18241, 18240, -1, 18255, 18092, 18088, -1, 18256, 18222, 18243, -1, 18255, 18088, 18257, -1, 18258, 18220, 18246, -1, 18256, 18229, 18222, -1, 18255, 18228, 18092, -1, 18258, 18231, 18220, -1, 18259, 18260, 18233, -1, 18261, 18225, 18249, -1, 18262, 18226, 18247, -1, 18259, 18232, 18218, -1, 18259, 18218, 18248, -1, 18259, 18233, 18232, -1, 18262, 18236, 18226, -1, 18263, 18224, 18250, -1, 18261, 18237, 18225, -1, 18264, 18100, 18103, -1, 18264, 18239, 18100, -1, 18265, 18229, 18256, -1, 18265, 18240, 18229, -1, 18263, 18238, 18224, -1, 18266, 18257, 18267, -1, 18268, 18269, 18245, -1, 18270, 18243, 18236, -1, 18268, 18245, 18244, -1, 18266, 18255, 18257, -1, 18268, 18244, 18231, -1, 18266, 18242, 18228, -1, 18268, 18231, 18258, -1, 18266, 18228, 18255, -1, 18271, 18246, 18237, -1, 18270, 18236, 18262, -1, 18272, 18101, 18097, -1, 18271, 18237, 18261, -1, 18273, 18248, 18238, -1, 18272, 18247, 18101, -1, 18274, 18249, 18239, -1, 18273, 18238, 18263, -1, 18275, 18267, 18276, -1, 18274, 18239, 18264, -1, 18277, 18240, 18265, -1, 18277, 18251, 18240, -1, 18275, 18250, 18242, -1, 18277, 18278, 18252, -1, 18279, 18246, 18271, -1, 18277, 18252, 18251, -1, 18275, 18266, 18267, -1, 18279, 18258, 18246, -1, 18275, 18242, 18266, -1, 18280, 18256, 18243, -1, 18280, 18243, 18270, -1, 18281, 18282, 18260, -1, 18281, 18259, 18248, -1, 18281, 18248, 18273, -1, 18281, 18260, 18259, -1, 18283, 18276, 18284, -1, 18202, 18249, 18274, -1, 18197, 18247, 18272, -1, 18202, 18261, 18249, -1, 18197, 18262, 18247, -1, 18283, 18250, 18275, -1, 18283, 18263, 18250, -1, 18283, 18275, 18276, -1, 18205, 18103, 18105, -1, 18205, 18264, 18103, -1, 18285, 18284, 18286, -1, 18216, 18265, 18256, -1, 18287, 18258, 18279, -1, 18285, 18273, 18263, -1, 18216, 18256, 18280, -1, 18285, 18283, 18284, -1, 18287, 18288, 18269, -1, 18285, 18263, 18283, -1, 18287, 18269, 18268, -1, 18289, 18282, 18281, -1, 18287, 18268, 18258, -1, 18289, 18286, 18290, -1, 18196, 18262, 18197, -1, 18289, 18290, 18291, -1, 18289, 18291, 18282, -1, 18201, 18261, 18202, -1, 18289, 18285, 18286, -1, 18289, 18281, 18273, -1, 18196, 18270, 18262, -1, 18289, 18273, 18285, -1, 18201, 18271, 18261, -1, 18211, 18097, 18096, -1, 18204, 18264, 18205, -1, 18211, 18272, 18097, -1, 18204, 18274, 18264, -1, 18215, 18278, 18277, -1, 18219, 18271, 18201, -1, 18219, 18279, 18271, -1, 18215, 18214, 18278, -1, 18215, 18265, 18216, -1, 18215, 18277, 18265, -1, 18221, 18280, 18270, -1, 18227, 18202, 18274, -1, 18227, 18274, 18204, -1, 18221, 18270, 18196, -1, 18198, 18197, 18272, -1, 18198, 18272, 18211, -1, 18208, 18105, 18094, -1, 18208, 18205, 18105, -1, 18217, 18280, 18221, -1, 18217, 18216, 18280, -1, 18235, 18288, 18287, -1, 18235, 18234, 18288, -1, 18235, 18279, 18219, -1, 18235, 18287, 18279, -1, 18200, 18202, 18227, -1, 18292, 18291, 18290, -1, 18293, 18294, 18295, -1, 18296, 18297, 18298, -1, 18299, 18300, 18301, -1, 18302, 18303, 18304, -1, 18299, 18301, 18305, -1, 18302, 18306, 18303, -1, 18307, 18308, 18309, -1, 18310, 18110, 18112, -1, 18307, 18309, 18296, -1, 18310, 18311, 18110, -1, 18312, 18298, 18306, -1, 18312, 18306, 18302, -1, 18313, 18314, 18315, -1, 18313, 18315, 18316, -1, 18313, 18316, 18294, -1, 18317, 18084, 18091, -1, 18313, 18294, 18293, -1, 18317, 18304, 18084, -1, 18318, 18300, 18299, -1, 18318, 18319, 18300, -1, 18320, 18321, 18308, -1, 18320, 18322, 18321, -1, 18320, 18308, 18307, -1, 18323, 18296, 18298, -1, 18324, 18305, 18311, -1, 18323, 18298, 18312, -1, 18324, 18311, 18310, -1, 18325, 18319, 18318, -1, 18322, 18326, 18321, -1, 18325, 18293, 18319, -1, 18327, 18302, 18304, -1, 18327, 18304, 18317, -1, 18328, 18296, 18323, -1, 18329, 18299, 18305, -1, 18328, 18307, 18296, -1, 18329, 18305, 18324, -1, 18330, 18112, 18113, -1, 18331, 18312, 18302, -1, 18331, 18302, 18327, -1, 18330, 18310, 18112, -1, 18330, 18113, 18207, -1, 18332, 18314, 18313, -1, 18333, 18091, 18093, -1, 18332, 18334, 18314, -1, 18332, 18313, 18293, -1, 18333, 18317, 18091, -1, 18332, 18293, 18325, -1, 18335, 18336, 18322, -1, 18337, 18318, 18299, -1, 18335, 18320, 18307, -1, 18335, 18307, 18328, -1, 18337, 18299, 18329, -1, 18335, 18322, 18320, -1, 18338, 18207, 18210, -1, 18339, 18312, 18331, -1, 18339, 18323, 18312, -1, 18338, 18324, 18310, -1, 18338, 18330, 18207, -1, 18338, 18310, 18330, -1, 18340, 18317, 18333, -1, 18341, 18318, 18337, -1, 18340, 18327, 18317, -1, 18341, 18325, 18318, -1, 18342, 18323, 18339, -1, 18343, 18210, 18223, -1, 18342, 18328, 18323, -1, 18343, 18338, 18210, -1, 18344, 18331, 18327, -1, 18343, 18329, 18324, -1, 18343, 18324, 18338, -1, 18207, 18113, 18108, -1, 18345, 18346, 18334, -1, 18345, 18334, 18332, -1, 18344, 18327, 18340, -1, 18345, 18332, 18325, -1, 18347, 18093, 18111, -1, 18345, 18325, 18341, -1, 18348, 18223, 18230, -1, 18347, 18333, 18093, -1, 18348, 18329, 18343, -1, 18348, 18337, 18329, -1, 18348, 18343, 18223, -1, 18349, 18335, 18328, -1, 18349, 18350, 18336, -1, 18349, 18336, 18335, -1, 18351, 18230, 18241, -1, 18349, 18328, 18342, -1, 18295, 18331, 18344, -1, 18351, 18341, 18337, -1, 18295, 18339, 18331, -1, 18351, 18348, 18230, -1, 18351, 18337, 18348, -1, 18352, 18241, 18254, -1, 18352, 18254, 18253, -1, 18352, 18253, 18353, -1, 18301, 18340, 18333, -1, 18352, 18353, 18346, -1, 18352, 18346, 18345, -1, 18352, 18341, 18351, -1, 18301, 18333, 18347, -1, 18352, 18345, 18341, -1, 18352, 18351, 18241, -1, 18294, 18339, 18295, -1, 18294, 18342, 18339, -1, 18303, 18079, 18078, -1, 18300, 18340, 18301, -1, 18300, 18344, 18340, -1, 18303, 18354, 18079, -1, 18311, 18111, 18110, -1, 18311, 18347, 18111, -1, 18306, 18355, 18354, -1, 18306, 18354, 18303, -1, 18316, 18315, 18350, -1, 18316, 18350, 18349, -1, 18316, 18349, 18342, -1, 18316, 18342, 18294, -1, 18298, 18297, 18355, -1, 18319, 18344, 18300, -1, 18298, 18355, 18306, -1, 18304, 18078, 18084, -1, 18319, 18295, 18344, -1, 18305, 18347, 18311, -1, 18305, 18301, 18347, -1, 18304, 18303, 18078, -1, 18296, 18309, 18297, -1, 18293, 18295, 18319, -1, 18292, 18356, 18357, -1, 18357, 18356, 18358, -1, 18358, 18359, 18360, -1, 18356, 18359, 18358, -1, 18360, 18361, 18362, -1, 18359, 18361, 18360, -1, 18361, 18363, 18362, -1, 18362, 18364, 18365, -1, 18363, 18364, 18362, -1, 18365, 18326, 18366, -1, 18364, 18326, 18365, -1, 18366, 18322, 18367, -1, 18326, 18322, 18366, -1, 18367, 18336, 18368, -1, 18322, 18336, 18367, -1, 18368, 18350, 18369, -1, 18336, 18350, 18368, -1, 18369, 18315, 18370, -1, 18350, 18315, 18369, -1, 18370, 18314, 18371, -1, 18315, 18314, 18370, -1, 18371, 18334, 18372, -1, 18314, 18334, 18371, -1, 18372, 18346, 18373, -1, 18334, 18346, 18372, -1, 18373, 18353, 18374, -1, 18346, 18353, 18373, -1, 18353, 18253, 18374, -1, 18375, 18376, 18377, -1, 18375, 18378, 18379, -1, 18375, 18377, 18380, -1, 18375, 18381, 18382, -1, 18375, 18380, 18381, -1, 18376, 18383, 18384, -1, 18385, 18379, 18378, -1, 18386, 18153, 18149, -1, 18386, 18155, 18153, -1, 18386, 18387, 18155, -1, 18388, 18389, 18387, -1, 18388, 18387, 18386, -1, 18390, 18391, 18389, -1, 18390, 18389, 18388, -1, 18392, 18149, 18145, -1, 18392, 18145, 18393, -1, 18392, 18386, 18149, -1, 18394, 18395, 18391, -1, 18394, 18391, 18390, -1, 18396, 18393, 18397, -1, 18396, 18388, 18386, -1, 18396, 18392, 18393, -1, 18396, 18386, 18392, -1, 18380, 18398, 18395, -1, 18380, 18395, 18394, -1, 18399, 18397, 18400, -1, 18399, 18396, 18397, -1, 18399, 18390, 18388, -1, 18399, 18388, 18396, -1, 18377, 18384, 18398, -1, 18377, 18398, 18380, -1, 18377, 18376, 18384, -1, 18401, 18400, 18402, -1, 18401, 18399, 18400, -1, 18401, 18394, 18390, -1, 18401, 18390, 18399, -1, 18381, 18402, 18382, -1, 18381, 18394, 18401, -1, 18381, 18401, 18402, -1, 18381, 18380, 18394, -1, 18375, 18382, 18378, -1, 18375, 18379, 18376, -1, 18403, 18404, 18405, -1, 18406, 18407, 18408, -1, 18403, 18409, 18410, -1, 18411, 18412, 18413, -1, 18403, 18410, 18414, -1, 18403, 18414, 18404, -1, 18415, 18416, 18417, -1, 18411, 18413, 18418, -1, 18415, 18419, 18416, -1, 18420, 18421, 18422, -1, 18423, 18424, 18425, -1, 18426, 18139, 18143, -1, 18423, 18427, 18424, -1, 18426, 18428, 18139, -1, 18142, 18393, 18145, -1, 18429, 18393, 18142, -1, 18430, 18431, 18432, -1, 18430, 18433, 18431, -1, 18434, 18397, 18393, -1, 18430, 18435, 18406, -1, 18430, 18432, 18435, -1, 18436, 18405, 18419, -1, 18434, 18393, 18429, -1, 18436, 18419, 18415, -1, 18437, 18408, 18412, -1, 18437, 18412, 18411, -1, 18438, 18400, 18397, -1, 18439, 18417, 18427, -1, 18439, 18427, 18423, -1, 18440, 18418, 18428, -1, 18440, 18428, 18426, -1, 18438, 18397, 18434, -1, 18441, 18425, 18193, -1, 18442, 18142, 18138, -1, 18441, 18193, 18172, -1, 18443, 18406, 18408, -1, 18442, 18429, 18142, -1, 18443, 18408, 18437, -1, 18444, 18402, 18400, -1, 18445, 18403, 18405, -1, 18445, 18405, 18436, -1, 18446, 18411, 18418, -1, 18444, 18400, 18438, -1, 18445, 18409, 18403, -1, 18446, 18418, 18440, -1, 18445, 18447, 18409, -1, 18448, 18429, 18442, -1, 18449, 18417, 18439, -1, 18449, 18415, 18417, -1, 18450, 18143, 18148, -1, 18448, 18434, 18429, -1, 18451, 18385, 18378, -1, 18450, 18426, 18143, -1, 18452, 18402, 18444, -1, 18452, 18382, 18402, -1, 18453, 18454, 18433, -1, 18455, 18423, 18425, -1, 18453, 18433, 18430, -1, 18455, 18425, 18441, -1, 18453, 18430, 18406, -1, 18453, 18406, 18443, -1, 18456, 18437, 18411, -1, 18457, 18436, 18415, -1, 18456, 18411, 18446, -1, 18458, 18438, 18434, -1, 18458, 18434, 18448, -1, 18457, 18415, 18449, -1, 18459, 18440, 18426, -1, 18460, 18138, 18136, -1, 18461, 18439, 18423, -1, 18459, 18426, 18450, -1, 18460, 18442, 18138, -1, 18462, 18378, 18382, -1, 18463, 18437, 18456, -1, 18461, 18423, 18455, -1, 18464, 18171, 18465, -1, 18463, 18443, 18437, -1, 18462, 18451, 18378, -1, 18464, 18172, 18171, -1, 18462, 18382, 18452, -1, 18464, 18441, 18172, -1, 18466, 18444, 18438, -1, 18467, 18440, 18459, -1, 18467, 18446, 18440, -1, 18468, 18445, 18436, -1, 18466, 18438, 18458, -1, 18468, 18469, 18447, -1, 18468, 18447, 18445, -1, 18470, 18442, 18460, -1, 18468, 18436, 18457, -1, 18470, 18448, 18442, -1, 18471, 18148, 18152, -1, 18471, 18450, 18148, -1, 18472, 18444, 18466, -1, 18473, 18449, 18439, -1, 18472, 18452, 18444, -1, 18473, 18439, 18461, -1, 18474, 18475, 18454, -1, 18476, 18441, 18464, -1, 18474, 18454, 18453, -1, 18477, 18458, 18448, -1, 18476, 18455, 18441, -1, 18474, 18453, 18443, -1, 18476, 18465, 18478, -1, 18474, 18443, 18463, -1, 18479, 18456, 18446, -1, 18476, 18464, 18465, -1, 18479, 18446, 18467, -1, 18477, 18448, 18470, -1, 18480, 18136, 18135, -1, 18481, 18457, 18449, -1, 18482, 18459, 18450, -1, 18480, 18460, 18136, -1, 18481, 18449, 18473, -1, 18482, 18450, 18471, -1, 18483, 18478, 18484, -1, 18485, 18462, 18452, -1, 18485, 18486, 18451, -1, 18404, 18456, 18479, -1, 18483, 18461, 18455, -1, 18404, 18463, 18456, -1, 18485, 18452, 18472, -1, 18485, 18451, 18462, -1, 18483, 18476, 18478, -1, 18407, 18458, 18477, -1, 18483, 18455, 18476, -1, 18416, 18467, 18459, -1, 18487, 18488, 18469, -1, 18487, 18469, 18468, -1, 18407, 18466, 18458, -1, 18487, 18468, 18457, -1, 18487, 18457, 18481, -1, 18416, 18459, 18482, -1, 18413, 18460, 18480, -1, 18489, 18484, 18490, -1, 18413, 18470, 18460, -1, 18489, 18473, 18461, -1, 18424, 18152, 18154, -1, 18489, 18483, 18484, -1, 18489, 18461, 18483, -1, 18424, 18471, 18152, -1, 18435, 18466, 18407, -1, 18491, 18490, 18492, -1, 18414, 18463, 18404, -1, 18491, 18481, 18473, -1, 18414, 18410, 18475, -1, 18435, 18472, 18466, -1, 18491, 18489, 18490, -1, 18412, 18470, 18413, -1, 18414, 18475, 18474, -1, 18491, 18473, 18489, -1, 18414, 18474, 18463, -1, 18493, 18481, 18491, -1, 18493, 18422, 18421, -1, 18493, 18492, 18422, -1, 18493, 18421, 18488, -1, 18493, 18491, 18492, -1, 18419, 18467, 18416, -1, 18412, 18477, 18470, -1, 18493, 18488, 18487, -1, 18493, 18487, 18481, -1, 18419, 18479, 18467, -1, 18428, 18135, 18139, -1, 18427, 18471, 18424, -1, 18465, 18171, 18170, -1, 18428, 18480, 18135, -1, 18427, 18482, 18471, -1, 18432, 18485, 18472, -1, 18405, 18404, 18479, -1, 18432, 18431, 18486, -1, 18432, 18472, 18435, -1, 18432, 18486, 18485, -1, 18405, 18479, 18419, -1, 18408, 18477, 18412, -1, 18417, 18482, 18427, -1, 18408, 18407, 18477, -1, 18418, 18480, 18428, -1, 18417, 18416, 18482, -1, 18418, 18413, 18480, -1, 18425, 18154, 18193, -1, 18406, 18435, 18407, -1, 18425, 18424, 18154, -1, 18494, 18385, 18495, -1, 18385, 18451, 18495, -1, 18495, 18486, 18496, -1, 18451, 18486, 18495, -1, 18496, 18431, 18497, -1, 18486, 18431, 18496, -1, 18497, 18433, 18498, -1, 18431, 18433, 18497, -1, 18498, 18454, 18499, -1, 18433, 18454, 18498, -1, 18499, 18475, 18500, -1, 18454, 18475, 18499, -1, 18500, 18410, 18501, -1, 18475, 18410, 18500, -1, 18501, 18409, 18502, -1, 18410, 18409, 18501, -1, 18502, 18447, 18503, -1, 18409, 18447, 18502, -1, 18503, 18469, 18504, -1, 18447, 18469, 18503, -1, 18504, 18488, 18505, -1, 18469, 18488, 18504, -1, 18505, 18421, 18506, -1, 18506, 18421, 18507, -1, 18488, 18421, 18505, -1, 18421, 18420, 18507, -1, 18508, 18509, 18510, -1, 18162, 18509, 18508, -1, 18509, 18183, 18511, -1, 18162, 18183, 18509, -1, 18090, 18512, 18513, -1, 18141, 18512, 18090, -1, 18150, 18155, 18514, -1, 18157, 18515, 18155, -1, 18155, 18515, 18514, -1, 18157, 18156, 18515, -1, 18516, 18517, 18518, -1, 18519, 18517, 18516, -1, 18520, 18511, 18521, -1, 18522, 18511, 18520, -1, 18523, 18511, 18522, -1, 18524, 18511, 18523, -1, 18525, 18040, 18028, -1, 18518, 18040, 18525, -1, 18521, 18040, 18517, -1, 18517, 18040, 18518, -1, 18511, 18040, 18521, -1, 18511, 18526, 18040, -1, 18040, 18527, 18528, -1, 18040, 18529, 18527, -1, 18526, 18530, 18040, -1, 18040, 18531, 18529, -1, 18530, 18532, 18040, -1, 18040, 18532, 18531, -1, 18509, 18511, 18533, -1, 18533, 18511, 18524, -1, 18534, 18521, 18517, -1, 18535, 18521, 18534, -1, 18536, 18537, 18538, -1, 18539, 18537, 18536, -1, 18540, 18537, 18539, -1, 18541, 18537, 18540, -1, 18542, 18537, 18541, -1, 18537, 17993, 18538, -1, 18537, 18543, 17993, -1, 18544, 18545, 18543, -1, 18545, 18546, 18543, -1, 18546, 18547, 18543, -1, 18547, 18548, 18543, -1, 18548, 18549, 18543, -1, 18543, 18008, 17993, -1, 18549, 18008, 18543, -1, 18550, 18543, 18537, -1, 18551, 18543, 18550, -1, 18549, 18548, 18552, -1, 18536, 18538, 18553, -1, 18518, 18525, 18554, -1, 18420, 18555, 18507, -1, 18507, 18555, 18556, -1, 18556, 18557, 18558, -1, 18555, 18557, 18556, -1, 18558, 18559, 18560, -1, 18557, 18559, 18558, -1, 18560, 18561, 18562, -1, 18559, 18561, 18560, -1, 18562, 18563, 18564, -1, 18561, 18563, 18562, -1, 18564, 18565, 18566, -1, 18563, 18565, 18564, -1, 18566, 18567, 18568, -1, 18565, 18567, 18566, -1, 18568, 18569, 18570, -1, 18567, 18569, 18568, -1, 18570, 18571, 18572, -1, 18569, 18571, 18570, -1, 18572, 18573, 18574, -1, 18571, 18573, 18572, -1, 18573, 18575, 18574, -1, 18574, 18383, 18576, -1, 18575, 18383, 18574, -1, 18576, 18376, 18577, -1, 18383, 18376, 18576, -1, 18577, 18379, 18494, -1, 18376, 18379, 18577, -1, 18379, 18385, 18494, -1, 18572, 18578, 18579, -1, 18572, 18574, 18578, -1, 18580, 18497, 18498, -1, 18505, 18581, 18582, -1, 18583, 18498, 18499, -1, 18505, 18582, 18504, -1, 18583, 18580, 18498, -1, 18570, 18579, 18584, -1, 18570, 18572, 18579, -1, 18585, 18496, 18497, -1, 18585, 18497, 18580, -1, 18506, 18581, 18505, -1, 18506, 18586, 18581, -1, 18587, 18499, 18500, -1, 18587, 18583, 18499, -1, 18568, 18584, 18588, -1, 18568, 18570, 18584, -1, 18589, 18495, 18496, -1, 18589, 18496, 18585, -1, 18507, 18590, 18586, -1, 18507, 18586, 18506, -1, 18591, 18500, 18501, -1, 18591, 18587, 18500, -1, 18566, 18588, 18592, -1, 18593, 18577, 18494, -1, 18593, 18494, 18495, -1, 18566, 18568, 18588, -1, 18593, 18495, 18589, -1, 18556, 18594, 18590, -1, 18556, 18595, 18594, -1, 18596, 18501, 18502, -1, 18556, 18590, 18507, -1, 18596, 18591, 18501, -1, 18597, 18576, 18577, -1, 18564, 18592, 18598, -1, 18597, 18577, 18593, -1, 18564, 18566, 18592, -1, 18558, 18599, 18595, -1, 18600, 18502, 18503, -1, 18600, 18596, 18502, -1, 18558, 18595, 18556, -1, 18562, 18598, 18601, -1, 18562, 18564, 18598, -1, 18602, 18576, 18597, -1, 18574, 18576, 18602, -1, 18560, 18601, 18599, -1, 18560, 18562, 18601, -1, 18560, 18599, 18558, -1, 18603, 18600, 18503, -1, 18578, 18574, 18602, -1, 18504, 18603, 18503, -1, 18504, 18582, 18603, -1, 18604, 18593, 18605, -1, 18593, 18589, 18605, -1, 18605, 18585, 18606, -1, 18589, 18585, 18605, -1, 18606, 18580, 18607, -1, 18585, 18580, 18606, -1, 18607, 18583, 18608, -1, 18580, 18583, 18607, -1, 18608, 18587, 18609, -1, 18583, 18587, 18608, -1, 18609, 18591, 18610, -1, 18587, 18591, 18609, -1, 18610, 18596, 18611, -1, 18591, 18596, 18610, -1, 18611, 18600, 18612, -1, 18596, 18600, 18611, -1, 18612, 18603, 18613, -1, 18600, 18603, 18612, -1, 18613, 18582, 18614, -1, 18603, 18582, 18613, -1, 18614, 18581, 18615, -1, 18582, 18581, 18614, -1, 18615, 18586, 18616, -1, 18581, 18586, 18615, -1, 18616, 18590, 18617, -1, 18586, 18590, 18616, -1, 3240, 16832, 16827, -1, 3240, 18618, 16832, -1, 3199, 18619, 3240, -1, 3240, 18619, 18618, -1, 3199, 18620, 18619, -1, 3199, 18621, 18620, -1, 3199, 18069, 18621, -1, 3199, 14978, 18069, -1, 14978, 18067, 18069, -1, 14984, 18064, 18061, -1, 3198, 18064, 14984, -1, 3198, 18622, 18064, -1, 3198, 18623, 18622, -1, 3247, 18624, 3198, -1, 3198, 18624, 18623, -1, 3247, 16850, 18624, -1, 3247, 16846, 16850, -1, 18625, 18626, 18627, -1, 18628, 18627, 18629, -1, 18628, 18625, 18627, -1, 18630, 18629, 17908, -1, 18630, 18628, 18629, -1, 17907, 18630, 17908, -1, 18631, 18625, 18632, -1, 18633, 18632, 18625, -1, 18634, 18625, 18631, -1, 18635, 18633, 18625, -1, 18636, 18625, 18634, -1, 18637, 18635, 18625, -1, 18638, 18625, 18636, -1, 18626, 18638, 18639, -1, 18626, 18625, 18638, -1, 18640, 18626, 18639, -1, 18641, 18626, 18640, -1, 18642, 18626, 18641, -1, 18643, 18626, 18642, -1, 18644, 18626, 18643, -1, 18645, 18637, 18625, -1, 18646, 18637, 18645, -1, 18647, 18644, 18648, -1, 18647, 18626, 18644, -1, 18649, 18650, 18651, -1, 18649, 18651, 18652, -1, 17758, 18652, 18653, -1, 17758, 18653, 18654, -1, 18655, 18654, 18653, -1, 18656, 18655, 18653, -1, 18657, 18656, 18653, -1, 18658, 18657, 18653, -1, 18659, 18653, 18660, -1, 18659, 18658, 18653, -1, 17753, 18649, 18652, -1, 17753, 18652, 17758, -1, 18661, 18659, 18660, -1, 18662, 17753, 18663, -1, 18662, 18663, 18664, -1, 18662, 18649, 17753, -1, 18665, 18661, 18660, -1, 18666, 18660, 18667, -1, 18666, 18665, 18660, -1, 18668, 18669, 18670, -1, 18668, 18671, 18669, -1, 18668, 18664, 18672, -1, 18668, 18672, 18673, -1, 18668, 18673, 18674, -1, 18668, 18674, 18671, -1, 18668, 18662, 18664, -1, 18675, 18667, 18647, -1, 18675, 18666, 18667, -1, 18648, 18675, 18647, -1, 18676, 18670, 18677, -1, 18676, 18668, 18670, -1, 18646, 18676, 18677, -1, 18645, 18676, 18646, -1, 18678, 18650, 18679, -1, 18678, 18679, 18680, -1, 18681, 18678, 18680, -1, 18651, 18650, 18678, -1, 18682, 18678, 18683, -1, 18682, 18651, 18678, -1, 18684, 18682, 18683, -1, 18685, 18684, 18683, -1, 18686, 18680, 18687, -1, 18686, 18681, 18680, -1, 18688, 18687, 18689, -1, 18688, 18686, 18687, -1, 18690, 18689, 18691, -1, 18690, 18688, 18689, -1, 18661, 18666, 18659, -1, 18665, 18666, 18661, -1, 18666, 18692, 18659, -1, 18666, 18693, 18692, -1, 18693, 18694, 18692, -1, 18692, 18694, 18695, -1, 18695, 18696, 18697, -1, 18694, 18696, 18695, -1, 18697, 18698, 18699, -1, 18696, 18698, 18697, -1, 18699, 18700, 18701, -1, 18698, 18700, 18699, -1, 18701, 18702, 18703, -1, 18700, 18702, 18701, -1, 18703, 18704, 18705, -1, 18702, 18704, 18703, -1, 18705, 18706, 18707, -1, 18704, 18706, 18705, -1, 18707, 18708, 18709, -1, 18706, 18708, 18707, -1, 18709, 18710, 18711, -1, 18708, 18710, 18709, -1, 18711, 18712, 18713, -1, 18710, 18712, 18711, -1, 18713, 18714, 18715, -1, 18712, 18714, 18713, -1, 18715, 18716, 18717, -1, 18714, 18716, 18715, -1, 18717, 18718, 18719, -1, 18716, 18718, 18717, -1, 18718, 18677, 18719, -1, 18670, 18669, 18677, -1, 18677, 18671, 18719, -1, 18669, 18671, 18677, -1, 18720, 16952, 16951, -1, 18720, 16951, 16982, -1, 18721, 18720, 16982, -1, 18722, 16982, 16992, -1, 18722, 18721, 16982, -1, 18723, 16992, 16996, -1, 18723, 18722, 16992, -1, 18724, 16996, 16975, -1, 18724, 16975, 16974, -1, 18724, 18723, 16996, -1, 18679, 16974, 16984, -1, 18679, 16984, 18680, -1, 18679, 18724, 16974, -1, 15569, 16100, 16108, -1, 15570, 16108, 16107, -1, 15570, 15569, 16108, -1, 15571, 16107, 16112, -1, 15571, 15570, 16107, -1, 15572, 16112, 16113, -1, 15572, 15571, 16112, -1, 15541, 15572, 16113, -1, 16081, 16085, 15552, -1, 15552, 16085, 15556, -1, 15556, 16085, 15558, -1, 15558, 16086, 15561, -1, 16085, 16086, 15558, -1, 15561, 16087, 15563, -1, 16086, 16087, 15561, -1, 16087, 16088, 15563, -1, 18725, 17904, 17912, -1, 18725, 17912, 18726, -1, 18727, 18726, 18728, -1, 18727, 18725, 18726, -1, 18729, 18728, 18730, -1, 18729, 18727, 18728, -1, 18731, 18730, 18732, -1, 18731, 18729, 18730, -1, 18733, 18732, 18734, -1, 18733, 18731, 18732, -1, 18735, 18734, 18736, -1, 18735, 18733, 18734, -1, 18737, 18736, 18738, -1, 18737, 18735, 18736, -1, 18737, 18739, 18740, -1, 18737, 18738, 18739, -1, 18737, 18740, 18741, -1, 18741, 18742, 18743, -1, 18740, 18742, 18741, -1, 18743, 18744, 18745, -1, 18742, 18744, 18743, -1, 18745, 18746, 18747, -1, 18744, 18746, 18745, -1, 18746, 18748, 18747, -1, 18749, 18750, 18751, -1, 18750, 18747, 18748, -1, 18749, 18747, 18750, -1, 18752, 18753, 18754, -1, 18755, 18754, 18756, -1, 18755, 18752, 18754, -1, 18757, 18756, 18758, -1, 18757, 18755, 18756, -1, 18759, 18758, 18749, -1, 18759, 18757, 18758, -1, 18751, 18759, 18749, -1, 18760, 18761, 18762, -1, 18761, 18763, 18764, -1, 18763, 18765, 18764, -1, 18766, 18767, 18768, -1, 18764, 18767, 18766, -1, 18765, 18767, 18764, -1, 18768, 18753, 18752, -1, 18767, 18753, 18768, -1, 18769, 18770, 18771, -1, 18772, 18770, 18769, -1, 18773, 18770, 18772, -1, 18774, 18770, 18773, -1, 18775, 18770, 18774, -1, 18776, 18777, 18771, -1, 18770, 18778, 18771, -1, 18771, 18778, 18776, -1, 18777, 18779, 18771, -1, 18770, 18780, 18778, -1, 18770, 18781, 18780, -1, 18770, 18782, 18781, -1, 18770, 18783, 18782, -1, 18783, 18784, 18782, -1, 18785, 18786, 18783, -1, 18783, 18787, 18784, -1, 18786, 18788, 18783, -1, 18783, 18789, 18787, -1, 18788, 18790, 18783, -1, 18783, 18791, 18789, -1, 18790, 18760, 18783, -1, 18783, 18760, 18791, -1, 18779, 18792, 18771, -1, 18760, 18793, 18791, -1, 18760, 18794, 18793, -1, 18760, 18762, 18794, -1, 18779, 18795, 18792, -1, 18795, 18796, 18792, -1, 18796, 18797, 18792, -1, 18797, 18798, 18792, -1, 18798, 18799, 18792, -1, 18798, 18800, 18799, -1, 18801, 18761, 18764, -1, 18762, 18761, 18801, -1, 18802, 18803, 18804, -1, 18791, 18793, 18805, -1, 18806, 18807, 18803, -1, 18806, 18808, 18807, -1, 18806, 18809, 18808, -1, 18810, 18811, 18809, -1, 18810, 18809, 18806, -1, 18812, 18813, 18811, -1, 18812, 18811, 18810, -1, 18814, 18794, 18762, -1, 18814, 18793, 18794, -1, 18814, 18815, 18813, -1, 18814, 18762, 18815, -1, 18814, 18813, 18812, -1, 18816, 18802, 18817, -1, 18816, 18817, 18818, -1, 18816, 18818, 18805, -1, 18816, 18810, 18806, -1, 18816, 18793, 18814, -1, 18816, 18806, 18803, -1, 18816, 18814, 18812, -1, 18816, 18803, 18802, -1, 18816, 18805, 18793, -1, 18816, 18812, 18810, -1, 18819, 18820, 18821, -1, 18778, 18780, 18822, -1, 18823, 18824, 18820, -1, 18823, 18825, 18824, -1, 18823, 18826, 18825, -1, 18827, 18828, 18826, -1, 18827, 18826, 18823, -1, 18829, 18830, 18828, -1, 18829, 18828, 18827, -1, 18831, 18781, 18782, -1, 18831, 18780, 18781, -1, 18831, 18832, 18830, -1, 18831, 18782, 18832, -1, 18831, 18830, 18829, -1, 18833, 18819, 18834, -1, 18833, 18834, 18835, -1, 18833, 18835, 18822, -1, 18833, 18827, 18823, -1, 18833, 18780, 18831, -1, 18833, 18823, 18820, -1, 18833, 18831, 18829, -1, 18833, 18820, 18819, -1, 18833, 18822, 18780, -1, 18833, 18829, 18827, -1, 18799, 18800, 18836, -1, 18837, 18836, 18838, -1, 18837, 18799, 18836, -1, 18839, 18838, 18840, -1, 18839, 18837, 18838, -1, 18841, 18839, 18840, -1, 18840, 18842, 18841, -1, 18842, 18843, 18841, -1, 18842, 18844, 18843, -1, 18845, 18846, 18847, -1, 18847, 18846, 18848, -1, 18846, 18849, 18848, -1, 18848, 18850, 18851, -1, 18849, 18850, 18848, -1, 18850, 18852, 18851, -1, 18851, 18853, 18844, -1, 18852, 18853, 18851, -1, 18853, 18843, 18844, -1, 18847, 18854, 18845, -1, 18847, 18855, 18854, -1, 18856, 18857, 18858, -1, 18857, 18859, 18858, -1, 18858, 18860, 18861, -1, 18859, 18860, 18858, -1, 18861, 18804, 18862, -1, 18860, 18804, 18861, -1, 18862, 18803, 18863, -1, 18804, 18803, 18862, -1, 18863, 18807, 18864, -1, 18803, 18807, 18863, -1, 18864, 18808, 18865, -1, 18807, 18808, 18864, -1, 18866, 18867, 18868, -1, 18867, 18869, 18868, -1, 18870, 18871, 18872, -1, 18873, 18871, 18870, -1, 18865, 18868, 18874, -1, 18872, 18875, 18876, -1, 18877, 18874, 18869, -1, 18869, 18874, 18868, -1, 18871, 18875, 18872, -1, 18878, 18879, 18880, -1, 18878, 18880, 18881, -1, 18875, 18882, 18876, -1, 18861, 18862, 18858, -1, 18862, 18863, 18858, -1, 18858, 18864, 18856, -1, 18863, 18864, 18858, -1, 18864, 18865, 18856, -1, 18876, 18883, 18884, -1, 18884, 18885, 18876, -1, 18876, 18886, 18883, -1, 18885, 18878, 18876, -1, 18876, 18887, 18886, -1, 18876, 18888, 18887, -1, 18856, 18889, 18882, -1, 18882, 18889, 18876, -1, 18876, 18889, 18888, -1, 18865, 18889, 18856, -1, 18878, 18881, 18876, -1, 18881, 18890, 18891, -1, 18881, 18880, 18890, -1, 18865, 18892, 18889, -1, 18865, 18893, 18892, -1, 18865, 18894, 18893, -1, 18865, 18895, 18894, -1, 18865, 18896, 18895, -1, 18865, 18874, 18896, -1, 18897, 18898, 18899, -1, 18897, 18900, 18898, -1, 18901, 18902, 18900, -1, 18901, 18900, 18897, -1, 18889, 18902, 18901, -1, 18888, 18889, 18901, -1, 18880, 18879, 18903, -1, 18904, 18905, 18879, -1, 18906, 18905, 18904, -1, 18907, 18905, 18906, -1, 18879, 18905, 18903, -1, 18908, 18909, 18910, -1, 18905, 18909, 18908, -1, 18907, 18909, 18905, -1, 18907, 18911, 18909, -1, 18912, 18913, 18914, -1, 18915, 18913, 18912, -1, 18916, 18913, 18915, -1, 18917, 18913, 18916, -1, 18917, 18918, 18913, -1, 18918, 18919, 18913, -1, 18919, 18920, 18913, -1, 18920, 18877, 18913, -1, 18869, 18921, 18877, -1, 18877, 18921, 18913, -1, 18922, 18923, 18924, -1, 18924, 18923, 18925, -1, 18926, 18927, 18928, -1, 18929, 18927, 18926, -1, 18930, 18931, 18922, -1, 18922, 18931, 18923, -1, 18932, 18933, 18934, -1, 18934, 18935, 18932, -1, 18929, 18936, 18927, -1, 18937, 18938, 18930, -1, 18932, 18939, 18933, -1, 18930, 18938, 18931, -1, 18940, 18936, 18929, -1, 18937, 18941, 18938, -1, 18935, 18942, 18932, -1, 18940, 18943, 18936, -1, 18932, 18944, 18939, -1, 18945, 18946, 18947, -1, 18948, 18943, 18940, -1, 18942, 18949, 18932, -1, 18950, 18951, 18952, -1, 18932, 18953, 18944, -1, 18954, 18955, 18945, -1, 18945, 18955, 18946, -1, 18932, 18956, 18953, -1, 18947, 18957, 18958, -1, 18951, 18959, 18952, -1, 18946, 18957, 18947, -1, 18952, 18959, 18960, -1, 18932, 18961, 18956, -1, 18950, 18962, 18951, -1, 18963, 18964, 18954, -1, 18954, 18964, 18955, -1, 18965, 18962, 18950, -1, 18957, 18966, 18958, -1, 18958, 18966, 18967, -1, 18959, 18968, 18960, -1, 18960, 18968, 18969, -1, 18970, 18971, 18963, -1, 18963, 18971, 18964, -1, 18965, 18972, 18962, -1, 18973, 18972, 18965, -1, 18974, 18972, 18973, -1, 18975, 18972, 18974, -1, 18976, 18977, 18949, -1, 18978, 18977, 18979, -1, 18979, 18977, 18980, -1, 18969, 18981, 18982, -1, 18980, 18977, 18983, -1, 18983, 18977, 18976, -1, 18968, 18981, 18969, -1, 18966, 18984, 18967, -1, 18949, 18977, 18932, -1, 18985, 18986, 18987, -1, 18981, 18988, 18982, -1, 18970, 18989, 18971, -1, 18985, 18990, 18986, -1, 18985, 18991, 18990, -1, 18992, 18993, 18994, -1, 18992, 18995, 18993, -1, 18985, 18996, 18991, -1, 18997, 18995, 18992, -1, 18978, 18998, 18977, -1, 18997, 18999, 18995, -1, 18998, 19000, 18977, -1, 19001, 18999, 18997, -1, 19002, 19003, 18985, -1, 19004, 19005, 18978, -1, 18978, 19005, 18998, -1, 18985, 19003, 18996, -1, 19006, 19007, 19001, -1, 19008, 19009, 19002, -1, 19001, 19007, 18999, -1, 19000, 19010, 18977, -1, 19002, 19009, 19003, -1, 19004, 19011, 19005, -1, 19006, 19012, 19007, -1, 19013, 19012, 19006, -1, 19014, 19015, 19016, -1, 19016, 19015, 19017, -1, 19018, 19019, 19008, -1, 19017, 19015, 19020, -1, 19013, 19021, 19012, -1, 19010, 19022, 18977, -1, 19008, 19019, 19009, -1, 18977, 19023, 19024, -1, 19025, 19021, 19013, -1, 19018, 19026, 19019, -1, 19022, 19023, 18977, -1, 19014, 19027, 19015, -1, 19028, 19027, 19014, -1, 19004, 19029, 19011, -1, 19025, 19030, 19021, -1, 19024, 19031, 19032, -1, 19033, 19030, 19025, -1, 19032, 19031, 19034, -1, 19028, 19035, 19027, -1, 19023, 19031, 19024, -1, 19033, 19036, 19030, -1, 19004, 19037, 19029, -1, 19038, 19035, 19028, -1, 19031, 19039, 19034, -1, 19034, 19039, 19040, -1, 19038, 19041, 19035, -1, 19042, 19041, 19038, -1, 19039, 19043, 19040, -1, 19042, 19044, 19041, -1, 19045, 19044, 19042, -1, 19004, 19046, 19037, -1, 19004, 19047, 19046, -1, 19043, 19048, 19040, -1, 18948, 19049, 18943, -1, 19050, 19049, 19018, -1, 19051, 19049, 19050, -1, 19052, 19053, 19045, -1, 19054, 19049, 19055, -1, 19045, 19053, 19044, -1, 18943, 19049, 19051, -1, 19018, 19049, 19026, -1, 19056, 19049, 19057, -1, 19058, 19049, 19056, -1, 19059, 19049, 19058, -1, 19060, 19049, 19059, -1, 19061, 19049, 19060, -1, 19055, 19049, 19062, -1, 19063, 19049, 19061, -1, 19064, 19049, 19063, -1, 19026, 19049, 19064, -1, 19062, 19049, 18948, -1, 19048, 19065, 19040, -1, 19057, 19049, 18918, -1, 19066, 19049, 19067, -1, 19067, 19049, 19068, -1, 19069, 19065, 19070, -1, 19052, 19071, 19053, -1, 19068, 19049, 19072, -1, 19070, 19065, 19073, -1, 19072, 19049, 19074, -1, 19073, 19065, 19048, -1, 19074, 19049, 18937, -1, 18937, 19049, 18941, -1, 18941, 19049, 19052, -1, 19069, 19075, 19065, -1, 19052, 19049, 19071, -1, 19071, 19049, 19076, -1, 19076, 19049, 19077, -1, 19077, 19049, 19078, -1, 19078, 19049, 19079, -1, 19079, 19049, 19080, -1, 19080, 19049, 19081, -1, 19081, 19049, 19082, -1, 19082, 19049, 19083, -1, 19083, 19049, 19084, -1, 19084, 19049, 19085, -1, 19085, 19049, 19086, -1, 19086, 19049, 19087, -1, 19087, 19049, 19088, -1, 19088, 19049, 19089, -1, 19089, 19049, 19033, -1, 19033, 19049, 19036, -1, 19036, 19049, 19090, -1, 19090, 19049, 19091, -1, 19091, 19049, 19092, -1, 19092, 19049, 19093, -1, 19093, 19049, 19094, -1, 19094, 19049, 19095, -1, 19095, 19049, 19096, -1, 19097, 19098, 19099, -1, 19096, 19049, 19054, -1, 19100, 19101, 19102, -1, 19100, 19102, 19103, -1, 19100, 19103, 19104, -1, 19100, 19104, 19105, -1, 19100, 19105, 19106, -1, 19100, 19106, 19107, -1, 19100, 19107, 18982, -1, 19100, 18982, 18988, -1, 19097, 19108, 19098, -1, 19100, 18988, 19109, -1, 19100, 19109, 19110, -1, 19100, 19110, 19111, -1, 19100, 19111, 19112, -1, 19098, 19113, 19099, -1, 19102, 19101, 19114, -1, 19114, 19101, 19115, -1, 19115, 19101, 19116, -1, 19116, 19101, 19117, -1, 19075, 19118, 19097, -1, 19117, 19101, 19119, -1, 19119, 19101, 19120, -1, 19121, 19122, 19123, -1, 19120, 19101, 18984, -1, 18984, 19101, 18967, -1, 18967, 19101, 19124, -1, 19097, 19118, 19108, -1, 19124, 19101, 19125, -1, 19125, 19101, 19126, -1, 19126, 19101, 19127, -1, 19099, 19128, 19101, -1, 19127, 19101, 19129, -1, 19129, 19101, 19130, -1, 19130, 19101, 19131, -1, 19131, 19101, 19132, -1, 19133, 19134, 19121, -1, 19113, 19128, 19099, -1, 19132, 19101, 19135, -1, 19135, 19101, 19136, -1, 19136, 19101, 19137, -1, 19138, 19139, 19140, -1, 19137, 19101, 19141, -1, 19121, 19134, 19122, -1, 19142, 19143, 19144, -1, 19145, 19146, 19147, -1, 19148, 19149, 19150, -1, 19075, 19151, 19118, -1, 19138, 19152, 19139, -1, 19144, 19153, 19142, -1, 19154, 19155, 19156, -1, 19157, 18972, 18975, -1, 19147, 19158, 19145, -1, 19156, 19159, 19154, -1, 18994, 19160, 19161, -1, 19123, 19162, 19163, -1, 19164, 19165, 19166, -1, 19128, 19167, 19101, -1, 19166, 19168, 19164, -1, 19169, 19152, 19138, -1, 18975, 19170, 19157, -1, 19122, 19162, 19123, -1, 19171, 18985, 18987, -1, 19069, 19172, 19075, -1, 19173, 19159, 19133, -1, 19174, 19159, 19173, -1, 19150, 19175, 19148, -1, 19154, 19159, 19174, -1, 19075, 19172, 19151, -1, 19139, 19176, 19140, -1, 19161, 18992, 18994, -1, 18987, 19177, 19171, -1, 19140, 19176, 19178, -1, 19179, 19180, 19181, -1, 19182, 19183, 19184, -1, 19133, 19159, 19134, -1, 19069, 19185, 19172, -1, 19186, 19187, 19188, -1, 19188, 19187, 19069, -1, 19189, 19181, 19180, -1, 19190, 19191, 19192, -1, 19193, 19194, 19195, -1, 19196, 19184, 19183, -1, 19163, 19197, 19198, -1, 19199, 19192, 19191, -1, 19200, 19201, 19202, -1, 19162, 19197, 19163, -1, 19069, 19187, 19185, -1, 19015, 19203, 19020, -1, 19169, 19204, 19152, -1, 19205, 19020, 19203, -1, 19206, 19195, 19194, -1, 19207, 19204, 19169, -1, 19208, 19047, 19209, -1, 19209, 19047, 19004, -1, 19167, 19210, 19101, -1, 19211, 19202, 19201, -1, 19198, 19110, 19109, -1, 19176, 19212, 19178, -1, 19178, 19212, 19213, -1, 19210, 19214, 19101, -1, 19197, 19110, 19198, -1, 19215, 19216, 19207, -1, 19207, 19216, 19204, -1, 19212, 19119, 19213, -1, 19213, 19119, 19120, -1, 19165, 19217, 19166, -1, 19215, 19218, 19216, -1, 19219, 19220, 19221, -1, 19165, 19222, 19217, -1, 19223, 19211, 19224, -1, 19224, 19211, 19201, -1, 19221, 19225, 19226, -1, 19220, 19225, 19221, -1, 19189, 19227, 19219, -1, 19228, 19229, 19165, -1, 19219, 19227, 19220, -1, 19230, 19231, 19223, -1, 19223, 19231, 19211, -1, 19165, 19229, 19222, -1, 19225, 19232, 19226, -1, 19230, 19233, 19231, -1, 19226, 19232, 19214, -1, 19234, 19233, 19230, -1, 19228, 19235, 19229, -1, 19236, 19235, 19228, -1, 19189, 19237, 19227, -1, 19214, 19238, 19101, -1, 19239, 19240, 19234, -1, 19232, 19238, 19214, -1, 19234, 19240, 19233, -1, 19236, 19241, 19235, -1, 19242, 19241, 19236, -1, 19189, 19243, 19237, -1, 19244, 19245, 19239, -1, 19242, 19246, 19241, -1, 19238, 19247, 19101, -1, 19248, 19246, 19242, -1, 19239, 19245, 19240, -1, 19189, 19249, 19243, -1, 19250, 19251, 19248, -1, 19244, 19252, 19245, -1, 19248, 19251, 19246, -1, 19189, 19180, 19249, -1, 19253, 19252, 19244, -1, 19247, 19141, 19101, -1, 19090, 19091, 19250, -1, 19250, 19091, 19251, -1, 19253, 19077, 19252, -1, 19076, 19077, 19253, -1, 19254, 19255, 19256, -1, 19182, 19257, 19254, -1, 19254, 19257, 19255, -1, 19256, 19258, 19259, -1, 19255, 19258, 19256, -1, 19182, 19260, 19257, -1, 19261, 19262, 19263, -1, 19259, 19264, 19265, -1, 19258, 19264, 19259, -1, 19182, 19266, 19260, -1, 19265, 19137, 19141, -1, 19264, 19137, 19265, -1, 19182, 19267, 19266, -1, 19182, 19184, 19267, -1, 19268, 19269, 19270, -1, 19269, 19271, 19270, -1, 19270, 19271, 19272, -1, 19268, 19273, 19269, -1, 19274, 19273, 19268, -1, 19271, 19275, 19272, -1, 19272, 19275, 19276, -1, 19274, 19277, 19273, -1, 19170, 19278, 19157, -1, 19279, 19277, 19274, -1, 19275, 19280, 19276, -1, 19276, 19280, 19117, -1, 19170, 19281, 19278, -1, 19279, 19282, 19277, -1, 19283, 19282, 19279, -1, 19170, 19284, 19281, -1, 19285, 19284, 19170, -1, 19280, 19116, 19117, -1, 19286, 19066, 19287, -1, 19287, 19066, 19288, -1, 19288, 19066, 19289, -1, 19290, 19291, 19292, -1, 19289, 19066, 19293, -1, 19293, 19066, 19294, -1, 18961, 19066, 19286, -1, 18932, 19066, 18961, -1, 19295, 19296, 19297, -1, 19297, 19296, 19262, -1, 19298, 19299, 19290, -1, 19262, 19296, 19263, -1, 19295, 19300, 19296, -1, 19290, 19299, 19291, -1, 19292, 19301, 19302, -1, 19303, 19300, 19295, -1, 19291, 19301, 19292, -1, 19298, 19146, 19299, -1, 19066, 19304, 19294, -1, 19303, 19305, 19300, -1, 19306, 19146, 19298, -1, 19307, 19305, 19303, -1, 19308, 19146, 19306, -1, 19309, 19146, 19308, -1, 19147, 19146, 19309, -1, 19301, 19310, 19302, -1, 19302, 19310, 19111, -1, 19066, 19311, 19304, -1, 19307, 19312, 19305, -1, 19313, 19312, 19307, -1, 19285, 19314, 19284, -1, 19315, 19314, 19285, -1, 19316, 19317, 19313, -1, 19313, 19317, 19312, -1, 19310, 19112, 19111, -1, 19078, 19318, 19316, -1, 19316, 19318, 19317, -1, 19078, 19079, 19318, -1, 19319, 19320, 19321, -1, 19315, 19322, 19314, -1, 19323, 19322, 19315, -1, 19324, 19325, 19319, -1, 19319, 19325, 19320, -1, 19323, 19326, 19322, -1, 19321, 19327, 19328, -1, 19329, 19326, 19323, -1, 19330, 19331, 19329, -1, 19320, 19327, 19321, -1, 19199, 19332, 19324, -1, 19324, 19332, 19325, -1, 19329, 19331, 19326, -1, 19330, 19093, 19331, -1, 19328, 19333, 19136, -1, 18970, 19334, 18989, -1, 19092, 19093, 19330, -1, 19327, 19333, 19328, -1, 19199, 19335, 19332, -1, 19333, 19135, 19136, -1, 19199, 19336, 19335, -1, 19199, 19191, 19336, -1, 19337, 19208, 19338, -1, 19338, 19208, 19339, -1, 19339, 19208, 19340, -1, 19340, 19208, 19341, -1, 19341, 19208, 19209, -1, 19342, 19343, 19337, -1, 19337, 19343, 19208, -1, 19344, 19345, 19334, -1, 19334, 19345, 18989, -1, 19346, 19347, 19348, -1, 19349, 19350, 19342, -1, 19342, 19350, 19343, -1, 19351, 19352, 19346, -1, 19346, 19352, 19347, -1, 19348, 19353, 19354, -1, 19311, 19355, 19349, -1, 19066, 19355, 19311, -1, 19349, 19355, 19350, -1, 19347, 19353, 19348, -1, 19356, 19357, 19351, -1, 19351, 19357, 19352, -1, 19066, 19358, 19355, -1, 19353, 19359, 19354, -1, 19354, 19359, 19360, -1, 19066, 19361, 19358, -1, 19362, 19363, 19344, -1, 19344, 19363, 19345, -1, 19356, 19364, 19357, -1, 19365, 19364, 19356, -1, 19359, 19114, 19360, -1, 19360, 19114, 19115, -1, 19155, 19366, 19156, -1, 19362, 19367, 19363, -1, 19368, 19367, 19362, -1, 19155, 19369, 19366, -1, 19066, 19370, 19361, -1, 19368, 19371, 19367, -1, 19372, 19371, 19368, -1, 19155, 19373, 19369, -1, 19374, 19373, 19155, -1, 19372, 19375, 19371, -1, 19374, 19376, 19373, -1, 19377, 19375, 19372, -1, 19378, 19376, 19374, -1, 19378, 19379, 19376, -1, 19377, 19380, 19375, -1, 19381, 19380, 19377, -1, 19382, 19379, 19378, -1, 19383, 19384, 19385, -1, 19382, 19386, 19379, -1, 19387, 19386, 19382, -1, 19381, 19081, 19380, -1, 19080, 19081, 19381, -1, 19388, 19389, 19383, -1, 19383, 19389, 19384, -1, 19387, 19390, 19386, -1, 19094, 19390, 19387, -1, 19385, 19391, 19392, -1, 19393, 19394, 19395, -1, 19384, 19391, 19385, -1, 19215, 19396, 19218, -1, 19388, 19397, 19389, -1, 19398, 19399, 19393, -1, 19193, 19397, 19388, -1, 19393, 19399, 19394, -1, 19391, 19400, 19392, -1, 19392, 19400, 19401, -1, 19395, 19402, 19403, -1, 19394, 19402, 19395, -1, 19404, 19153, 19398, -1, 19193, 19405, 19397, -1, 19406, 19153, 19404, -1, 19407, 19153, 19406, -1, 19142, 19153, 19407, -1, 19400, 19131, 19401, -1, 19398, 19153, 19399, -1, 19401, 19131, 19132, -1, 19094, 19095, 19390, -1, 19403, 19408, 19409, -1, 19193, 19410, 19405, -1, 19402, 19408, 19403, -1, 19193, 19195, 19410, -1, 19408, 19100, 19409, -1, 19411, 19100, 19112, -1, 19412, 19186, 19413, -1, 19409, 19100, 19411, -1, 19413, 19186, 19414, -1, 19414, 19186, 19415, -1, 19415, 19186, 19416, -1, 19416, 19186, 19188, -1, 19412, 19417, 19186, -1, 19418, 19100, 19408, -1, 19419, 19417, 19412, -1, 19419, 19420, 19417, -1, 19421, 19420, 19419, -1, 19421, 19422, 19420, -1, 19423, 19422, 19421, -1, 19424, 19425, 19396, -1, 19396, 19425, 19218, -1, 19423, 19426, 19422, -1, 19370, 19426, 19423, -1, 19427, 19428, 19424, -1, 19424, 19428, 19425, -1, 19370, 19429, 19426, -1, 19066, 19429, 19370, -1, 19430, 19431, 19427, -1, 19427, 19431, 19428, -1, 19430, 19432, 19431, -1, 19433, 19432, 19430, -1, 19433, 19434, 19432, -1, 19435, 19434, 19433, -1, 19436, 19437, 19438, -1, 19435, 19439, 19434, -1, 19440, 19439, 19435, -1, 19436, 19441, 19437, -1, 19442, 19441, 19436, -1, 19437, 19443, 19438, -1, 19066, 19444, 19429, -1, 19438, 19443, 19445, -1, 19418, 19446, 19100, -1, 19447, 19448, 19442, -1, 19442, 19448, 19441, -1, 19445, 19449, 19102, -1, 19443, 19449, 19445, -1, 19100, 19450, 19451, -1, 19452, 19453, 19447, -1, 19454, 19453, 19452, -1, 19446, 19450, 19100, -1, 19447, 19453, 19448, -1, 19450, 19455, 19451, -1, 19440, 19456, 19439, -1, 19082, 19456, 19440, -1, 19449, 19103, 19102, -1, 19455, 19457, 19451, -1, 19458, 19459, 19460, -1, 19451, 19457, 19461, -1, 19458, 19462, 19459, -1, 19082, 19083, 19456, -1, 19463, 19462, 19458, -1, 19457, 19464, 19461, -1, 19460, 19465, 19466, -1, 19461, 19467, 19468, -1, 19459, 19465, 19460, -1, 19463, 19469, 19462, -1, 19464, 19467, 19461, -1, 19205, 19469, 19463, -1, 19465, 19470, 19466, -1, 19466, 19470, 19471, -1, 19205, 19472, 19469, -1, 19470, 19129, 19471, -1, 19467, 19473, 19468, -1, 19471, 19129, 19130, -1, 19158, 19474, 19145, -1, 19205, 19475, 19472, -1, 19473, 19476, 19468, -1, 19205, 19203, 19475, -1, 19477, 19179, 19478, -1, 19478, 19179, 19479, -1, 19158, 19480, 19474, -1, 19479, 19179, 19481, -1, 19481, 19179, 19181, -1, 19482, 19483, 19477, -1, 19477, 19483, 19179, -1, 19484, 19485, 19482, -1, 19158, 19486, 19480, -1, 19482, 19485, 19483, -1, 19484, 19487, 19485, -1, 19158, 19488, 19486, -1, 19489, 19487, 19484, -1, 19490, 19488, 19158, -1, 19489, 19491, 19487, -1, 19492, 19491, 19489, -1, 19493, 19494, 19495, -1, 19492, 19496, 19491, -1, 19497, 19494, 19493, -1, 19444, 19496, 19492, -1, 19498, 19499, 19500, -1, 19066, 19496, 19444, -1, 19495, 19499, 19498, -1, 19494, 19499, 19495, -1, 19500, 19501, 18917, -1, 19283, 19502, 19282, -1, 19503, 19502, 19283, -1, 19499, 19501, 19500, -1, 19504, 19505, 19493, -1, 19493, 19505, 19497, -1, 19503, 19506, 19502, -1, 19507, 19506, 19503, -1, 19504, 19508, 19505, -1, 19509, 19510, 19490, -1, 19507, 19511, 19506, -1, 19512, 19511, 19507, -1, 19490, 19510, 19488, -1, 19066, 19067, 19496, -1, 19513, 19514, 19512, -1, 19512, 19514, 19511, -1, 19501, 19515, 18917, -1, 19504, 19516, 19508, -1, 19513, 19517, 19514, -1, 19518, 19517, 19513, -1, 19468, 19175, 19504, -1, 19476, 19175, 19468, -1, 19504, 19175, 19516, -1, 19519, 19175, 19476, -1, 19518, 19520, 19517, -1, 19148, 19175, 19519, -1, 19521, 19520, 19518, -1, 19515, 19522, 18917, -1, 19521, 19523, 19520, -1, 19522, 19524, 18917, -1, 19525, 19523, 19521, -1, 19526, 19527, 19509, -1, 19509, 19527, 19510, -1, 19525, 19085, 19523, -1, 19084, 19085, 19525, -1, 19528, 19529, 19530, -1, 19524, 19531, 18917, -1, 19526, 19532, 19527, -1, 19533, 19532, 19526, -1, 19534, 19196, 19535, -1, 19535, 19196, 19536, -1, 19536, 19196, 19537, -1, 19537, 19196, 19183, -1, 19538, 19539, 19528, -1, 19528, 19539, 19529, -1, 19533, 19054, 19532, -1, 19540, 19541, 19534, -1, 19529, 19542, 19530, -1, 19096, 19054, 19533, -1, 19534, 19541, 19196, -1, 19530, 19542, 19543, -1, 19544, 19545, 19538, -1, 19546, 19547, 19548, -1, 19538, 19545, 19539, -1, 19547, 19549, 19548, -1, 19548, 19549, 19550, -1, 19542, 19551, 19543, -1, 19546, 19552, 19547, -1, 19543, 19551, 19553, -1, 19554, 19160, 19544, -1, 19161, 19160, 19554, -1, 19555, 19552, 19546, -1, 19544, 19160, 19545, -1, 19549, 19556, 19550, -1, 19550, 19556, 19557, -1, 19551, 19105, 19553, -1, 19200, 19558, 19555, -1, 19553, 19105, 19104, -1, 19555, 19558, 19552, -1, 19557, 19559, 19127, -1, 19556, 19559, 19557, -1, 19560, 19561, 19540, -1, 19540, 19561, 19541, -1, 19200, 19562, 19558, -1, 19559, 19126, 19127, -1, 19563, 19564, 19560, -1, 19565, 19566, 19531, -1, 19560, 19564, 19561, -1, 19531, 19566, 18917, -1, 19200, 19202, 19562, -1, 19566, 19567, 18917, -1, 19565, 19177, 19566, -1, 19067, 19568, 19563, -1, 19569, 19177, 19565, -1, 19570, 19177, 19569, -1, 19571, 19177, 19570, -1, 19563, 19568, 19564, -1, 19572, 19177, 19571, -1, 19171, 19177, 19572, -1, 19573, 19574, 19365, -1, 19567, 19575, 18917, -1, 19067, 19068, 19568, -1, 19365, 19574, 19364, -1, 19575, 19576, 18917, -1, 19576, 19577, 18917, -1, 19578, 19579, 19573, -1, 19573, 19579, 19574, -1, 19580, 19581, 19578, -1, 19578, 19581, 19579, -1, 19143, 19582, 19144, -1, 19143, 19583, 19582, -1, 19584, 19585, 19580, -1, 19580, 19585, 19581, -1, 19143, 19586, 19583, -1, 19587, 19588, 19584, -1, 19589, 19590, 19143, -1, 19584, 19588, 19585, -1, 19143, 19590, 19586, -1, 19591, 19592, 19589, -1, 19589, 19592, 19590, -1, 19593, 19594, 19587, -1, 19595, 19596, 19591, -1, 19591, 19596, 19592, -1, 19587, 19594, 19588, -1, 19593, 19597, 19594, -1, 19086, 19597, 19593, -1, 19598, 19599, 19595, -1, 19600, 19190, 19601, -1, 19601, 19190, 19602, -1, 19602, 19190, 19192, -1, 19595, 19599, 19596, -1, 19086, 19087, 19597, -1, 19055, 19603, 19598, -1, 19604, 19605, 19600, -1, 19598, 19603, 19599, -1, 19600, 19605, 19190, -1, 19604, 19606, 19605, -1, 19607, 19608, 19609, -1, 19610, 19606, 19604, -1, 19055, 19062, 19603, -1, 19610, 19611, 19606, -1, 19609, 19612, 19613, -1, 19608, 19612, 19609, -1, 19577, 19614, 18917, -1, 19615, 19611, 19610, -1, 19616, 19617, 19607, -1, 19618, 19619, 19615, -1, 19615, 19619, 19611, -1, 19607, 19617, 19608, -1, 19612, 19620, 19613, -1, 19072, 19074, 19618, -1, 19613, 19620, 19621, -1, 19618, 19074, 19619, -1, 19622, 19623, 19624, -1, 19625, 19168, 19616, -1, 19626, 19168, 19625, -1, 19164, 19168, 19626, -1, 19616, 19168, 19617, -1, 19620, 19627, 19621, -1, 19628, 19629, 19622, -1, 19622, 19629, 19623, -1, 19621, 19627, 19106, -1, 19623, 19630, 19624, -1, 19624, 19630, 19631, -1, 19628, 19632, 19629, -1, 19261, 19632, 19628, -1, 19627, 19107, 19106, -1, 19630, 19633, 19631, -1, 19631, 19633, 19634, -1, 19261, 19635, 19632, -1, 19633, 19124, 19634, -1, 19634, 19124, 19125, -1, 19636, 19637, 19454, -1, 19261, 19263, 19635, -1, 19454, 19637, 19453, -1, 19636, 19638, 19637, -1, 19639, 19640, 19636, -1, 19636, 19640, 19638, -1, 19639, 19641, 19640, -1, 19642, 19641, 19639, -1, 19643, 18918, 19614, -1, 19644, 18918, 19643, -1, 19645, 18918, 19644, -1, 19646, 18918, 19645, -1, 19647, 18918, 19646, -1, 19648, 18918, 19647, -1, 19649, 18918, 19648, -1, 19650, 18918, 19649, -1, 19057, 18918, 19650, -1, 19614, 18918, 18917, -1, 19642, 19651, 19641, -1, 19652, 19651, 19642, -1, 19652, 19653, 19651, -1, 19654, 19653, 19652, -1, 19149, 19655, 19150, -1, 19149, 19656, 19655, -1, 19657, 19658, 19654, -1, 19654, 19658, 19653, -1, 19149, 19659, 19656, -1, 19660, 19206, 19661, -1, 19661, 19206, 19662, -1, 19662, 19206, 19194, -1, 19657, 19089, 19658, -1, 19088, 19089, 19657, -1, 19149, 19663, 19659, -1, 19664, 19665, 19149, -1, 19666, 19667, 19660, -1, 19660, 19667, 19206, -1, 19149, 19665, 19663, -1, 19664, 18928, 19665, -1, 18924, 18925, 19666, -1, 19666, 18925, 19667, -1, 18926, 18928, 19664, -1, 19668, 19669, 19670, -1, 19671, 19672, 19673, -1, 19670, 19669, 19674, -1, 19674, 19669, 19675, -1, 19676, 19677, 19678, -1, 19679, 19677, 19676, -1, 19680, 19681, 19682, -1, 19683, 19684, 19685, -1, 19685, 19684, 19686, -1, 19682, 19681, 19672, -1, 18907, 19687, 19688, -1, 19679, 19689, 19677, -1, 19688, 19690, 18907, -1, 19691, 19692, 19680, -1, 19693, 19689, 19679, -1, 18907, 19694, 19687, -1, 19680, 19692, 19681, -1, 19690, 19695, 18907, -1, 19691, 19696, 19692, -1, 19684, 19697, 19686, -1, 19698, 19699, 19693, -1, 18907, 19700, 19694, -1, 19693, 19699, 19689, -1, 19701, 19696, 19691, -1, 19698, 19702, 19699, -1, 19695, 19703, 18907, -1, 19704, 19705, 19701, -1, 19706, 19702, 19698, -1, 18907, 19707, 19700, -1, 19701, 19705, 19696, -1, 19706, 19708, 19702, -1, 19704, 19709, 19705, -1, 18907, 19710, 19707, -1, 18907, 19711, 19710, -1, 19712, 19713, 19714, -1, 19712, 19715, 19713, -1, 19716, 19715, 19712, -1, 19714, 19717, 19718, -1, 19713, 19717, 19714, -1, 19716, 19719, 19715, -1, 19720, 19719, 19716, -1, 19721, 18911, 19703, -1, 19722, 18911, 19721, -1, 19723, 18911, 19722, -1, 19724, 18911, 19723, -1, 19718, 19725, 19726, -1, 19727, 19728, 19729, -1, 19717, 19725, 19718, -1, 19703, 18911, 18907, -1, 19720, 19730, 19719, -1, 19731, 19730, 19720, -1, 19732, 19733, 19727, -1, 19725, 19734, 19726, -1, 19727, 19733, 19728, -1, 19731, 19735, 19730, -1, 19736, 19737, 19738, -1, 19739, 19740, 19732, -1, 19736, 19741, 19737, -1, 19732, 19740, 19733, -1, 19736, 19742, 19741, -1, 19743, 19744, 19724, -1, 19745, 19746, 19739, -1, 19724, 19744, 18911, -1, 19739, 19746, 19740, -1, 19747, 19748, 19743, -1, 19736, 19749, 19742, -1, 19743, 19748, 19744, -1, 19744, 19750, 18911, -1, 19751, 19752, 19745, -1, 19736, 19753, 19749, -1, 19745, 19752, 19746, -1, 19747, 19754, 19748, -1, 19755, 19753, 19736, -1, 19750, 19756, 18911, -1, 19755, 19757, 19753, -1, 19747, 19758, 19754, -1, 19751, 19759, 19752, -1, 19760, 19759, 19751, -1, 19761, 19757, 19755, -1, 19756, 19762, 18911, -1, 19761, 19763, 19757, -1, 19764, 19763, 19761, -1, 19760, 19765, 19759, -1, 19766, 19765, 19760, -1, 19747, 19767, 19758, -1, 19764, 19768, 19763, -1, 19747, 19769, 19767, -1, 19770, 19768, 19764, -1, 19747, 19771, 19769, -1, 19772, 19773, 19774, -1, 19775, 19773, 19772, -1, 19776, 19777, 19778, -1, 18911, 19777, 19776, -1, 19762, 19777, 18911, -1, 19779, 19780, 19781, -1, 19782, 19780, 19779, -1, 19778, 19780, 19782, -1, 19777, 19780, 19778, -1, 19783, 19784, 19775, -1, 19781, 19785, 19786, -1, 19780, 19785, 19781, -1, 19775, 19784, 19773, -1, 19785, 19787, 19786, -1, 19787, 19788, 19786, -1, 19783, 19789, 19784, -1, 19788, 19790, 19786, -1, 19791, 19789, 19783, -1, 19791, 19792, 19789, -1, 19704, 19793, 19709, -1, 19794, 19792, 19791, -1, 19795, 19793, 19796, -1, 19797, 19793, 19798, -1, 19798, 19793, 19799, -1, 19799, 19793, 19800, -1, 19800, 19793, 19801, -1, 19802, 19793, 19797, -1, 19768, 19793, 19802, -1, 19794, 19803, 19792, -1, 19770, 19793, 19768, -1, 19804, 19805, 19806, -1, 19807, 19793, 19704, -1, 19808, 19809, 19810, -1, 19811, 19803, 19794, -1, 19796, 19793, 19807, -1, 19812, 19793, 19770, -1, 19709, 19793, 19812, -1, 19805, 19813, 19806, -1, 19793, 19814, 19801, -1, 19815, 19814, 19816, -1, 19810, 19817, 19808, -1, 19801, 19814, 19815, -1, 19806, 19813, 19818, -1, 19816, 19814, 19819, -1, 19811, 19820, 19803, -1, 19821, 19822, 19823, -1, 19823, 19822, 19697, -1, 19804, 19824, 19805, -1, 19825, 19820, 19811, -1, 19697, 19822, 19686, -1, 19809, 19826, 19810, -1, 19686, 19822, 19827, -1, 19827, 19822, 19828, -1, 19828, 19822, 19829, -1, 19829, 19822, 19830, -1, 19830, 19822, 19831, -1, 19832, 19824, 19804, -1, 19831, 19822, 19833, -1, 19833, 19822, 19834, -1, 19825, 19835, 19820, -1, 19834, 19822, 19836, -1, 19810, 19837, 19817, -1, 19836, 19822, 19838, -1, 19839, 19835, 19825, -1, 19838, 19822, 19840, -1, 19840, 19822, 19841, -1, 19813, 19842, 19818, -1, 19841, 19822, 19843, -1, 19843, 19822, 19734, -1, 19818, 19842, 19844, -1, 19734, 19822, 19726, -1, 19726, 19822, 19845, -1, 19826, 19846, 19810, -1, 19845, 19822, 19847, -1, 19847, 19822, 19848, -1, 19848, 19822, 19849, -1, 19849, 19822, 19850, -1, 19851, 19852, 19853, -1, 19850, 19822, 19854, -1, 19854, 19822, 19855, -1, 19855, 19822, 19856, -1, 19832, 19857, 19824, -1, 19856, 19822, 19858, -1, 19859, 19857, 19860, -1, 19861, 19793, 19795, -1, 19860, 19857, 19862, -1, 19861, 19795, 19863, -1, 19862, 19857, 19832, -1, 19861, 19863, 19864, -1, 19851, 19865, 19852, -1, 19861, 19864, 19866, -1, 19810, 19867, 19837, -1, 19868, 19865, 19851, -1, 19861, 19866, 19869, -1, 19861, 19869, 19870, -1, 19861, 19870, 19871, -1, 19852, 19872, 19853, -1, 19861, 19871, 19873, -1, 19861, 19873, 19765, -1, 19842, 19874, 19844, -1, 19846, 19875, 19810, -1, 19861, 19765, 19766, -1, 19861, 19766, 19876, -1, 19844, 19874, 19823, -1, 19861, 19876, 19877, -1, 19861, 19877, 19878, -1, 19853, 19872, 19879, -1, 19861, 19878, 19880, -1, 19861, 19880, 19881, -1, 19861, 19881, 19882, -1, 19810, 19883, 19884, -1, 19861, 19882, 19885, -1, 19875, 19883, 19810, -1, 19861, 19885, 19886, -1, 19861, 19886, 19887, -1, 19874, 19888, 19823, -1, 19868, 19889, 19865, -1, 19861, 19887, 19890, -1, 19891, 19889, 19868, -1, 19861, 19890, 19892, -1, 19861, 19892, 19893, -1, 19861, 19893, 19894, -1, 19861, 19894, 19895, -1, 19861, 19895, 19835, -1, 19810, 19896, 19867, -1, 19861, 19835, 19839, -1, 19872, 19897, 19879, -1, 19861, 19839, 19708, -1, 19861, 19708, 19706, -1, 19861, 19706, 19898, -1, 19790, 19899, 19786, -1, 19879, 19897, 19900, -1, 19861, 19898, 19901, -1, 19884, 19899, 19790, -1, 19861, 19901, 19902, -1, 19883, 19899, 19884, -1, 19861, 19902, 19903, -1, 19904, 19905, 19906, -1, 19907, 19908, 19909, -1, 19910, 19909, 19908, -1, 19911, 19912, 19913, -1, 19913, 19912, 19810, -1, 19891, 19914, 19889, -1, 19915, 19916, 19917, -1, 19918, 19919, 19920, -1, 19810, 19912, 19896, -1, 19921, 19914, 19891, -1, 19922, 19920, 19919, -1, 19923, 19906, 19905, -1, 19924, 19771, 19925, -1, 19926, 19927, 19928, -1, 19925, 19771, 19747, -1, 19929, 19930, 19931, -1, 19932, 19774, 19933, -1, 19897, 19841, 19900, -1, 19934, 19917, 19916, -1, 19935, 19931, 19930, -1, 19773, 19933, 19774, -1, 19900, 19841, 19843, -1, 19936, 19937, 19938, -1, 19939, 19940, 19926, -1, 19941, 19942, 19943, -1, 19943, 19944, 19941, -1, 19926, 19940, 19927, -1, 19945, 19671, 19946, -1, 19899, 19947, 19786, -1, 19948, 19669, 19668, -1, 19859, 19949, 19950, -1, 19950, 19857, 19859, -1, 19938, 19951, 19936, -1, 19952, 19736, 19738, -1, 19953, 19954, 19939, -1, 19946, 19955, 19945, -1, 19921, 19956, 19914, -1, 19957, 19727, 19729, -1, 19928, 19958, 19959, -1, 19939, 19954, 19940, -1, 19668, 19960, 19948, -1, 19729, 19961, 19957, -1, 19959, 19926, 19928, -1, 19738, 19962, 19952, -1, 19963, 19964, 19953, -1, 19953, 19964, 19954, -1, 19965, 19966, 19963, -1, 19947, 19967, 19786, -1, 19968, 19967, 19947, -1, 19969, 19967, 19968, -1, 19970, 19967, 19969, -1, 19963, 19966, 19964, -1, 19910, 19967, 19970, -1, 19910, 19971, 19967, -1, 19965, 19972, 19966, -1, 19973, 19972, 19965, -1, 19974, 19929, 19931, -1, 19975, 19929, 19974, -1, 19971, 19976, 19977, -1, 19977, 19976, 19978, -1, 19973, 19979, 19972, -1, 19873, 19979, 19973, -1, 19978, 19980, 19977, -1, 19910, 19981, 19971, -1, 19971, 19981, 19976, -1, 19982, 19983, 19975, -1, 19977, 19984, 19822, -1, 19980, 19984, 19977, -1, 19975, 19983, 19929, -1, 19873, 19871, 19979, -1, 19910, 19985, 19981, -1, 19986, 19987, 19982, -1, 19984, 19988, 19822, -1, 19982, 19987, 19983, -1, 19910, 19989, 19985, -1, 19990, 19991, 19986, -1, 19910, 19908, 19989, -1, 19986, 19991, 19987, -1, 19988, 19992, 19822, -1, 19992, 19993, 19822, -1, 19994, 19995, 19990, -1, 19990, 19995, 19991, -1, 19994, 19996, 19995, -1, 19895, 19996, 19994, -1, 19997, 19998, 19999, -1, 20000, 20001, 19997, -1, 19997, 20001, 19998, -1, 19895, 19894, 19996, -1, 19999, 20002, 19993, -1, 19998, 20002, 19999, -1, 20000, 20003, 20001, -1, 19904, 20003, 20000, -1, 20004, 20005, 20006, -1, 19993, 20007, 19822, -1, 20002, 20007, 19993, -1, 19904, 20008, 20003, -1, 20009, 20010, 20011, -1, 20007, 20012, 19822, -1, 19904, 20013, 20008, -1, 19904, 19906, 20013, -1, 20014, 20015, 20009, -1, 20012, 20016, 19822, -1, 20009, 20015, 20010, -1, 20011, 20017, 20018, -1, 20019, 20020, 20021, -1, 20010, 20017, 20011, -1, 19938, 19937, 20022, -1, 20022, 19937, 20023, -1, 20023, 19937, 20014, -1, 20020, 20024, 20021, -1, 20021, 20024, 20025, -1, 20014, 19937, 20015, -1, 20019, 20026, 20020, -1, 20018, 20027, 20028, -1, 20017, 20027, 20018, -1, 20029, 20026, 20019, -1, 20024, 20030, 20025, -1, 20025, 20030, 20031, -1, 20029, 20032, 20026, -1, 20033, 20032, 20029, -1, 20030, 20034, 20031, -1, 20031, 20034, 19840, -1, 19960, 20035, 19948, -1, 20033, 20036, 20032, -1, 20037, 20036, 20033, -1, 19960, 20038, 20035, -1, 20034, 19838, 19840, -1, 20039, 19821, 19888, -1, 20040, 19821, 20027, -1, 20028, 19821, 20039, -1, 20005, 20041, 20006, -1, 20027, 19821, 20028, -1, 20042, 20041, 20005, -1, 20043, 20041, 20042, -1, 19888, 19821, 19823, -1, 20044, 20045, 20046, -1, 19711, 20045, 20044, -1, 18907, 20045, 19711, -1, 20043, 20047, 20041, -1, 20045, 19861, 20046, -1, 20048, 19861, 20049, -1, 20050, 20047, 20043, -1, 19960, 20051, 20038, -1, 20052, 19861, 20048, -1, 20053, 19861, 20052, -1, 20046, 19861, 20053, -1, 20050, 20054, 20047, -1, 20055, 20051, 19960, -1, 20056, 20054, 20050, -1, 20055, 20057, 20051, -1, 20058, 20059, 20060, -1, 20056, 20061, 20054, -1, 20062, 20057, 20055, -1, 20063, 20061, 20056, -1, 20058, 20064, 20059, -1, 20065, 20064, 20058, -1, 20062, 20066, 20057, -1, 20059, 20067, 20060, -1, 20068, 20066, 20062, -1, 20060, 20067, 20069, -1, 20063, 20070, 20061, -1, 20071, 20070, 20063, -1, 19922, 20072, 20065, -1, 20065, 20072, 20064, -1, 20068, 20073, 20066, -1, 20074, 20073, 20068, -1, 20069, 20075, 20076, -1, 19893, 20077, 20071, -1, 20067, 20075, 20069, -1, 20071, 20077, 20070, -1, 19922, 20078, 20072, -1, 20074, 20079, 20073, -1, 20080, 20079, 20074, -1, 20016, 19858, 19822, -1, 20075, 19858, 20076, -1, 20080, 19869, 20079, -1, 19893, 19892, 20077, -1, 19870, 19869, 20080, -1, 20076, 19858, 20016, -1, 19922, 20081, 20078, -1, 19861, 20082, 20049, -1, 19861, 20083, 20082, -1, 19731, 20084, 19735, -1, 20040, 20085, 19821, -1, 19821, 20086, 20087, -1, 19922, 19919, 20081, -1, 20085, 20086, 19821, -1, 20086, 20088, 20087, -1, 20088, 20089, 20087, -1, 20087, 20090, 20091, -1, 20089, 20090, 20087, -1, 20092, 20093, 20094, -1, 20092, 20095, 20093, -1, 20096, 20095, 20092, -1, 20093, 20097, 20094, -1, 20090, 20098, 20091, -1, 20094, 20097, 20099, -1, 20100, 19924, 19925, -1, 20101, 19924, 20100, -1, 20102, 19924, 20101, -1, 20103, 19924, 20102, -1, 20096, 20104, 20095, -1, 20105, 19924, 20103, -1, 20106, 20104, 20096, -1, 20097, 20107, 20099, -1, 20099, 20107, 20108, -1, 20105, 20109, 19924, -1, 20110, 20109, 20105, -1, 20106, 20111, 20104, -1, 20112, 20111, 20106, -1, 20107, 19834, 20108, -1, 20110, 20113, 20109, -1, 20108, 19834, 19836, -1, 20114, 20113, 20110, -1, 20115, 20116, 20084, -1, 20084, 20116, 19735, -1, 20114, 20117, 20113, -1, 20118, 20119, 20115, -1, 20083, 20117, 20114, -1, 20115, 20119, 20116, -1, 20083, 20120, 20117, -1, 20118, 20121, 20119, -1, 19861, 20120, 20083, -1, 20122, 20121, 20118, -1, 19861, 20123, 20120, -1, 20124, 20125, 20122, -1, 20126, 20127, 20128, -1, 20122, 20125, 20121, -1, 20124, 20129, 20125, -1, 20130, 20129, 20124, -1, 20128, 20131, 20126, -1, 19861, 20132, 20123, -1, 20091, 19944, 20128, -1, 19941, 19944, 20133, -1, 20133, 19944, 20134, -1, 20134, 19944, 20098, -1, 20098, 19944, 20091, -1, 20130, 20135, 20129, -1, 20136, 20135, 20130, -1, 20128, 19944, 20131, -1, 20136, 19887, 20135, -1, 19890, 19887, 20136, -1, 19949, 20137, 19950, -1, 20138, 20139, 20140, -1, 19949, 20141, 20137, -1, 20138, 20142, 20139, -1, 20143, 20142, 20138, -1, 20140, 20144, 20145, -1, 20127, 20146, 20128, -1, 20139, 20144, 20140, -1, 19921, 20147, 19956, -1, 19915, 20148, 20143, -1, 20143, 20148, 20142, -1, 20145, 20149, 20150, -1, 20144, 20149, 20145, -1, 19915, 20151, 20148, -1, 20152, 20153, 19949, -1, 19949, 20153, 20141, -1, 20150, 19855, 19856, -1, 20149, 19855, 20150, -1, 19915, 20154, 20151, -1, 19915, 19917, 20154, -1, 20152, 20155, 20153, -1, 20156, 20157, 20158, -1, 20159, 20155, 20152, -1, 20160, 19911, 19913, -1, 20161, 19911, 20160, -1, 20162, 19911, 20161, -1, 20163, 19911, 20162, -1, 20156, 20164, 20157, -1, 20165, 20164, 20156, -1, 20157, 20166, 20158, -1, 20163, 20167, 19911, -1, 20168, 20167, 20163, -1, 20159, 20169, 20155, -1, 20158, 20166, 20170, -1, 20171, 20169, 20159, -1, 20147, 20172, 19956, -1, 20168, 20173, 20167, -1, 20174, 20173, 20168, -1, 20175, 20172, 20147, -1, 20176, 20177, 20165, -1, 20146, 20178, 20128, -1, 20165, 20177, 20164, -1, 20179, 20178, 20146, -1, 20166, 20180, 20170, -1, 20170, 20180, 19833, -1, 20174, 20181, 20173, -1, 20182, 20181, 20174, -1, 20176, 20183, 20177, -1, 20184, 20183, 20185, -1, 20185, 20183, 20176, -1, 20186, 20187, 20175, -1, 20175, 20187, 20172, -1, 20188, 20189, 20182, -1, 20180, 19831, 19833, -1, 20171, 20190, 20169, -1, 20182, 20189, 20181, -1, 20191, 20192, 20186, -1, 20186, 20192, 20187, -1, 20193, 20190, 20171, -1, 19861, 20194, 20132, -1, 20195, 20196, 20191, -1, 20188, 20194, 20189, -1, 20132, 20194, 20188, -1, 20191, 20196, 20192, -1, 20197, 20198, 20195, -1, 20195, 20198, 20196, -1, 20199, 20200, 20197, -1, 20193, 20201, 20190, -1, 20197, 20200, 20198, -1, 19886, 20202, 20199, -1, 20203, 20201, 20193, -1, 20199, 20202, 20200, -1, 19861, 20204, 20194, -1, 19886, 19885, 20202, -1, 20203, 19864, 20201, -1, 19866, 19864, 20203, -1, 20205, 20206, 20207, -1, 20207, 20208, 20209, -1, 20206, 20208, 20207, -1, 20210, 20211, 20205, -1, 20205, 20211, 20206, -1, 20179, 20212, 20178, -1, 20209, 20213, 20214, -1, 20212, 20215, 20178, -1, 20208, 20213, 20209, -1, 19932, 20216, 20210, -1, 20210, 20216, 20211, -1, 20179, 20217, 20212, -1, 20218, 20217, 20179, -1, 20214, 20219, 19854, -1, 20213, 20219, 20214, -1, 20220, 19955, 20218, -1, 19945, 19955, 20221, -1, 20221, 19955, 20222, -1, 19932, 20223, 20216, -1, 20222, 19955, 20224, -1, 20224, 19955, 20225, -1, 20225, 19955, 20226, -1, 20226, 19955, 20227, -1, 20219, 19850, 19854, -1, 20227, 19955, 20228, -1, 20228, 19955, 20229, -1, 20229, 19955, 20220, -1, 20218, 19955, 20217, -1, 19932, 19933, 20223, -1, 20215, 20230, 20178, -1, 20178, 20231, 20232, -1, 20233, 19907, 19909, -1, 20234, 19907, 20233, -1, 20235, 19907, 20234, -1, 20236, 19907, 20235, -1, 20037, 20237, 20036, -1, 20230, 20231, 20178, -1, 20238, 20237, 20037, -1, 20236, 20239, 19907, -1, 20240, 20239, 20236, -1, 20238, 20241, 20237, -1, 20240, 20242, 20239, -1, 20232, 20243, 20244, -1, 20231, 20243, 20232, -1, 20245, 20242, 20240, -1, 20244, 20243, 20246, -1, 20246, 20243, 20247, -1, 20248, 20241, 20238, -1, 20248, 20249, 20241, -1, 20245, 20250, 20242, -1, 20251, 20250, 20245, -1, 20252, 20249, 20248, -1, 20252, 20253, 20249, -1, 20204, 20254, 20251, -1, 20251, 20254, 20250, -1, 20255, 20253, 20252, -1, 20255, 20256, 20253, -1, 20204, 20257, 20254, -1, 20258, 20256, 20255, -1, 19861, 20257, 20204, -1, 20247, 20259, 20260, -1, 20261, 20262, 20263, -1, 20260, 20259, 20264, -1, 20261, 20265, 20262, -1, 20243, 20259, 20247, -1, 20266, 20265, 20261, -1, 20263, 20267, 20268, -1, 20259, 20269, 20264, -1, 20262, 20267, 20263, -1, 20270, 20271, 20266, -1, 20266, 20271, 20265, -1, 20269, 20272, 20264, -1, 20272, 20273, 20264, -1, 20258, 20274, 20256, -1, 20275, 20274, 20258, -1, 20267, 20276, 20268, -1, 20268, 20276, 19830, -1, 20273, 20277, 20264, -1, 20270, 19961, 20271, -1, 19957, 19961, 20278, -1, 20278, 19961, 20270, -1, 19861, 19903, 20257, -1, 20276, 19829, 19830, -1, 20275, 20279, 20274, -1, 20280, 20279, 20275, -1, 20280, 19881, 20279, -1, 19882, 19881, 20280, -1, 20281, 20282, 20283, -1, 20284, 20285, 20281, -1, 20281, 20285, 20282, -1, 20283, 20286, 20287, -1, 20282, 20286, 20283, -1, 19935, 20288, 20284, -1, 20284, 20288, 20285, -1, 19951, 20289, 19936, -1, 20287, 20290, 20291, -1, 20286, 20290, 20287, -1, 19935, 20292, 20288, -1, 20291, 19848, 19849, -1, 20290, 19848, 20291, -1, 19951, 20293, 20289, -1, 20294, 20295, 19951, -1, 19935, 19930, 20292, -1, 19951, 20295, 20293, -1, 20296, 19923, 19905, -1, 20297, 19923, 20296, -1, 20298, 19923, 20297, -1, 20294, 20299, 20295, -1, 20300, 20299, 20294, -1, 20301, 20302, 20298, -1, 20300, 20303, 20299, -1, 20304, 20303, 20300, -1, 20298, 20302, 19923, -1, 20301, 20305, 20302, -1, 20306, 20305, 20301, -1, 20304, 20307, 20303, -1, 20308, 20307, 20304, -1, 20309, 20310, 20306, -1, 20308, 20311, 20307, -1, 19863, 20311, 20308, -1, 20306, 20310, 20305, -1, 19863, 19795, 20311, -1, 20312, 20313, 20309, -1, 20112, 20314, 20111, -1, 20309, 20313, 20310, -1, 20315, 20314, 20112, -1, 20316, 20317, 20277, -1, 19903, 19902, 20312, -1, 20312, 19902, 20313, -1, 20277, 20318, 20264, -1, 20317, 20318, 20277, -1, 19952, 19962, 20319, -1, 20319, 19962, 20320, -1, 20320, 19962, 20321, -1, 20322, 20323, 20315, -1, 20321, 19962, 20324, -1, 20324, 19962, 20316, -1, 20315, 20323, 20314, -1, 20316, 19962, 20317, -1, 20318, 20325, 20264, -1, 20326, 20327, 20322, -1, 20322, 20327, 20323, -1, 20325, 20328, 20264, -1, 20326, 20329, 20327, -1, 20330, 20329, 20326, -1, 20328, 20331, 20264, -1, 20332, 20333, 20330, -1, 20330, 20333, 20329, -1, 20334, 20335, 20332, -1, 20332, 20335, 20333, -1, 19880, 20336, 20334, -1, 20334, 20336, 20335, -1, 19880, 19878, 20336, -1, 20337, 20338, 20339, -1, 20337, 20340, 20338, -1, 20341, 20340, 20337, -1, 20338, 20342, 20339, -1, 20331, 20343, 20264, -1, 20339, 20342, 20344, -1, 20341, 20345, 20340, -1, 19942, 20346, 19943, -1, 20347, 19918, 19920, -1, 20348, 19918, 20347, -1, 20349, 20345, 20341, -1, 20350, 19918, 20348, -1, 20342, 20351, 20344, -1, 20344, 20351, 20352, -1, 20349, 19958, 20345, -1, 20353, 20354, 20350, -1, 19959, 19958, 20355, -1, 19942, 20356, 20346, -1, 20355, 19958, 20349, -1, 20350, 20354, 19918, -1, 20351, 19827, 20352, -1, 20357, 20358, 20353, -1, 20352, 19827, 19828, -1, 20353, 20358, 20354, -1, 19942, 20359, 20356, -1, 20360, 20361, 20362, -1, 20360, 20363, 20361, -1, 20364, 20363, 20360, -1, 20361, 20365, 20362, -1, 20366, 20367, 19942, -1, 20362, 20365, 20368, -1, 19942, 20367, 20359, -1, 20364, 20369, 20363, -1, 20004, 20369, 20364, -1, 20365, 20370, 20368, -1, 20368, 20370, 20371, -1, 20372, 20373, 20366, -1, 20366, 20373, 20367, -1, 20357, 20374, 20358, -1, 20375, 20374, 20357, -1, 20004, 20376, 20369, -1, 20377, 20378, 20372, -1, 20370, 19845, 20371, -1, 20371, 19845, 19847, -1, 20372, 20378, 20373, -1, 20379, 20380, 20184, -1, 20375, 20381, 20374, -1, 20382, 20381, 20375, -1, 20184, 20380, 20183, -1, 20383, 20384, 20377, -1, 20004, 20006, 20376, -1, 20377, 20384, 20378, -1, 20382, 20385, 20381, -1, 19901, 20385, 20382, -1, 20379, 20386, 20380, -1, 19901, 19898, 20385, -1, 19796, 19807, 20383, -1, 20383, 19807, 20384, -1, 20379, 20387, 20386, -1, 20388, 20387, 20379, -1, 19816, 19819, 20389, -1, 20389, 19819, 20390, -1, 20390, 19819, 20391, -1, 20391, 19819, 20392, -1, 20392, 19819, 20393, -1, 20393, 19819, 20394, -1, 20394, 19819, 20395, -1, 20395, 19819, 20396, -1, 20396, 19819, 20343, -1, 20397, 20398, 20388, -1, 20343, 19819, 20264, -1, 20388, 20398, 20387, -1, 20399, 20400, 20397, -1, 20397, 20400, 20398, -1, 20401, 20402, 20399, -1, 20399, 20402, 20400, -1, 20403, 20404, 20401, -1, 20401, 20404, 20402, -1, 19877, 19876, 20403, -1, 20403, 19876, 20404, -1, 19671, 20405, 19946, -1, 20406, 20407, 20408, -1, 20407, 20409, 20408, -1, 19671, 20410, 20405, -1, 20408, 20409, 20411, -1, 20406, 20412, 20407, -1, 20413, 19934, 19916, -1, 20414, 19934, 20413, -1, 20415, 19934, 20414, -1, 19675, 20412, 20406, -1, 19671, 19673, 20410, -1, 20415, 19678, 19934, -1, 20411, 19683, 19685, -1, 19676, 19678, 20415, -1, 20409, 19683, 20411, -1, 19682, 19672, 19671, -1, 19675, 19669, 20412, -1, 20416, 20220, 20417, -1, 20417, 20218, 20418, -1, 20220, 20218, 20417, -1, 20418, 20179, 20419, -1, 20218, 20179, 20418, -1, 20179, 20146, 20419, -1, 20420, 19875, 20421, -1, 20421, 19846, 20422, -1, 19875, 19846, 20421, -1, 20422, 19826, 20423, -1, 19846, 19826, 20422, -1, 20423, 19809, 20424, -1, 19826, 19809, 20423, -1, 20424, 19808, 20425, -1, 19809, 19808, 20424, -1, 20425, 19817, 20426, -1, 19808, 19817, 20425, -1, 20426, 19837, 20427, -1, 19817, 19837, 20426, -1, 19837, 19867, 20427, -1, 20427, 19896, 20428, -1, 19867, 19896, 20427, -1, 20428, 19912, 20429, -1, 19896, 19912, 20428, -1, 20430, 20431, 20432, -1, 20430, 20433, 20431, -1, 20420, 20421, 20434, -1, 20421, 20422, 20434, -1, 20434, 20423, 20435, -1, 20422, 20423, 20434, -1, 20424, 20425, 20423, -1, 20423, 20426, 20435, -1, 20425, 20426, 20423, -1, 20427, 20428, 20426, -1, 20426, 20428, 20435, -1, 20436, 20429, 20430, -1, 20435, 20429, 20436, -1, 20430, 20429, 20433, -1, 20428, 20429, 20435, -1, 20437, 20438, 20439, -1, 20440, 20441, 20442, -1, 20438, 20441, 20440, -1, 20437, 20441, 20438, -1, 20437, 20443, 20441, -1, 20443, 20444, 20445, -1, 20437, 20444, 20443, -1, 20437, 20446, 20444, -1, 20433, 20447, 20437, -1, 20437, 20447, 20446, -1, 20446, 20448, 20449, -1, 20447, 20448, 20446, -1, 20450, 20451, 20447, -1, 20447, 20451, 20448, -1, 20429, 20447, 20433, -1, 20452, 19886, 20453, -1, 20453, 20199, 20454, -1, 19886, 20199, 20453, -1, 20454, 20197, 20455, -1, 20199, 20197, 20454, -1, 20455, 20195, 20456, -1, 20197, 20195, 20455, -1, 20456, 20191, 20457, -1, 20195, 20191, 20456, -1, 20457, 20186, 20458, -1, 20191, 20186, 20457, -1, 20186, 20175, 20458, -1, 20458, 20147, 20459, -1, 20175, 20147, 20458, -1, 20454, 20455, 20456, -1, 20458, 20456, 20457, -1, 20452, 20453, 20454, -1, 20452, 20454, 20456, -1, 20452, 20456, 20458, -1, 20459, 20452, 20458, -1, 20460, 20452, 20459, -1, 20461, 20462, 20460, -1, 20463, 20461, 20460, -1, 20464, 20463, 20460, -1, 20465, 20466, 20464, -1, 20465, 20460, 20459, -1, 20465, 20464, 20460, -1, 20467, 20465, 20459, -1, 20468, 20467, 20469, -1, 20470, 20467, 20468, -1, 20471, 20467, 20470, -1, 20472, 20471, 20473, -1, 20472, 20467, 20471, -1, 20474, 20467, 20472, -1, 20475, 20465, 20467, -1, 20475, 20467, 20474, -1, 20476, 20475, 20474, -1, 20477, 20475, 20476, -1, 20478, 20479, 20475, -1, 20480, 20475, 20477, -1, 20481, 20478, 20475, -1, 20482, 20475, 20480, -1, 20482, 20481, 20475, -1, 20147, 19921, 20459, -1, 20459, 19921, 20467, -1, 20460, 19886, 20452, -1, 19887, 19886, 20460, -1, 20467, 19891, 20469, -1, 19921, 19891, 20467, -1, 20469, 19868, 20468, -1, 19891, 19868, 20469, -1, 20468, 19851, 20470, -1, 19868, 19851, 20468, -1, 20470, 19853, 20471, -1, 19851, 19853, 20470, -1, 20471, 19879, 20473, -1, 19853, 19879, 20471, -1, 20473, 19900, 20472, -1, 19879, 19900, 20473, -1, 20472, 19843, 20474, -1, 19900, 19843, 20472, -1, 20465, 20116, 20466, -1, 20466, 20119, 20464, -1, 20116, 20119, 20466, -1, 20119, 20121, 20464, -1, 20464, 20125, 20463, -1, 20121, 20125, 20464, -1, 20463, 20129, 20461, -1, 20125, 20129, 20463, -1, 20461, 20135, 20462, -1, 20129, 20135, 20461, -1, 20462, 19887, 20460, -1, 20135, 19887, 20462, -1, 19843, 20476, 20474, -1, 19843, 19734, 20476, -1, 19735, 20465, 20475, -1, 19735, 20116, 20465, -1, 20476, 19725, 20477, -1, 19734, 19725, 20476, -1, 20477, 19717, 20480, -1, 19725, 19717, 20477, -1, 20480, 19713, 20482, -1, 19717, 19713, 20480, -1, 20482, 19715, 20481, -1, 19713, 19715, 20482, -1, 20481, 19719, 20478, -1, 19715, 19719, 20481, -1, 20478, 19730, 20479, -1, 19719, 19730, 20478, -1, 20479, 19735, 20475, -1, 19730, 19735, 20479, -1, 20483, 20370, 20484, -1, 19845, 20370, 20483, -1, 20484, 20365, 20485, -1, 20370, 20365, 20484, -1, 20485, 20361, 20486, -1, 20365, 20361, 20485, -1, 20486, 20363, 20487, -1, 20487, 20363, 20488, -1, 20361, 20363, 20486, -1, 20488, 20369, 20489, -1, 20363, 20369, 20488, -1, 20369, 20376, 20489, -1, 20489, 20006, 20490, -1, 20376, 20006, 20489, -1, 20491, 20492, 20493, -1, 20491, 20493, 20494, -1, 20495, 20494, 20496, -1, 20497, 20494, 20495, -1, 20497, 20491, 20494, -1, 20498, 20497, 20495, -1, 20499, 20497, 20498, -1, 20500, 20501, 20499, -1, 20502, 20503, 20500, -1, 20504, 20500, 20499, -1, 20504, 20502, 20500, -1, 20505, 20499, 20498, -1, 20505, 20504, 20499, -1, 20506, 20505, 20498, -1, 20507, 20508, 20509, -1, 20507, 20509, 20510, -1, 20507, 20510, 20511, -1, 20512, 20506, 20508, -1, 20512, 20508, 20507, -1, 20490, 20505, 20506, -1, 20490, 20506, 20512, -1, 20483, 20490, 20512, -1, 20489, 20490, 20483, -1, 20484, 20489, 20483, -1, 20487, 20484, 20485, -1, 20487, 20488, 20489, -1, 20487, 20489, 20484, -1, 20486, 20487, 20485, -1, 20006, 20505, 20490, -1, 20006, 20041, 20505, -1, 19726, 20483, 20512, -1, 19726, 19845, 20483, -1, 20505, 20041, 20504, -1, 20504, 20047, 20502, -1, 20041, 20047, 20504, -1, 20502, 20054, 20503, -1, 20047, 20054, 20502, -1, 20503, 20061, 20500, -1, 20054, 20061, 20503, -1, 20500, 20070, 20501, -1, 20061, 20070, 20500, -1, 20070, 20077, 20501, -1, 20501, 19892, 20499, -1, 20077, 19892, 20501, -1, 19731, 19720, 20506, -1, 20506, 19720, 20508, -1, 20508, 19716, 20509, -1, 19720, 19716, 20508, -1, 20509, 19712, 20510, -1, 19716, 19712, 20509, -1, 20510, 19714, 20511, -1, 19712, 19714, 20510, -1, 20511, 19718, 20507, -1, 19714, 19718, 20511, -1, 20507, 19726, 20512, -1, 19718, 19726, 20507, -1, 19892, 19890, 20499, -1, 20499, 19890, 20497, -1, 20084, 20506, 20498, -1, 20084, 19731, 20506, -1, 20497, 19890, 20491, -1, 19890, 20136, 20491, -1, 20491, 20130, 20492, -1, 20136, 20130, 20491, -1, 20492, 20124, 20493, -1, 20130, 20124, 20492, -1, 20493, 20122, 20494, -1, 20124, 20122, 20493, -1, 20494, 20118, 20496, -1, 20122, 20118, 20494, -1, 20496, 20115, 20495, -1, 20118, 20115, 20496, -1, 20495, 20084, 20498, -1, 20115, 20084, 20495, -1, 20513, 19893, 20514, -1, 20514, 20071, 20515, -1, 19893, 20071, 20514, -1, 20515, 20063, 20516, -1, 20071, 20063, 20515, -1, 20516, 20056, 20517, -1, 20063, 20056, 20516, -1, 20517, 20050, 20518, -1, 20056, 20050, 20517, -1, 20518, 20043, 20519, -1, 20050, 20043, 20518, -1, 20043, 20042, 20519, -1, 20519, 20005, 20520, -1, 20042, 20005, 20519, -1, 20521, 20522, 20523, -1, 20524, 20525, 20521, -1, 20521, 20525, 20522, -1, 20526, 20527, 20524, -1, 20524, 20527, 20525, -1, 20528, 20529, 20530, -1, 20531, 20532, 20529, -1, 20529, 20532, 20530, -1, 20530, 20533, 20534, -1, 20532, 20533, 20530, -1, 20534, 20535, 20527, -1, 20527, 20535, 20525, -1, 20533, 20535, 20534, -1, 20519, 20517, 20518, -1, 20515, 20513, 20514, -1, 20516, 20513, 20515, -1, 20517, 20513, 20516, -1, 20520, 20513, 20519, -1, 20519, 20513, 20517, -1, 20520, 20536, 20513, -1, 20525, 20537, 20520, -1, 20535, 20537, 20525, -1, 20520, 20537, 20536, -1, 20537, 20538, 20536, -1, 20536, 20539, 20540, -1, 20538, 20541, 20536, -1, 20536, 20541, 20539, -1, 20541, 20542, 20539, -1, 20520, 20004, 20525, -1, 20005, 20004, 20520, -1, 19894, 19893, 20513, -1, 19894, 20513, 20536, -1, 20525, 20364, 20522, -1, 20004, 20364, 20525, -1, 20522, 20360, 20523, -1, 20364, 20360, 20522, -1, 20523, 20362, 20521, -1, 20521, 20362, 20524, -1, 20360, 20362, 20523, -1, 20524, 20368, 20526, -1, 20362, 20368, 20524, -1, 20368, 20371, 20526, -1, 20526, 19847, 20527, -1, 20371, 19847, 20526, -1, 19929, 19983, 20537, -1, 20537, 19983, 20538, -1, 20538, 19987, 20541, -1, 19983, 19987, 20538, -1, 20541, 19991, 20542, -1, 19987, 19991, 20541, -1, 20542, 19995, 20539, -1, 19991, 19995, 20542, -1, 20539, 19996, 20540, -1, 19995, 19996, 20539, -1, 20540, 19894, 20536, -1, 19996, 19894, 20540, -1, 20527, 19848, 20534, -1, 19847, 19848, 20527, -1, 19930, 19929, 20537, -1, 19930, 20537, 20535, -1, 20534, 20290, 20530, -1, 19848, 20290, 20534, -1, 20530, 20286, 20528, -1, 20290, 20286, 20530, -1, 20528, 20282, 20529, -1, 20286, 20282, 20528, -1, 20529, 20285, 20531, -1, 20282, 20285, 20529, -1, 20531, 20288, 20532, -1, 20285, 20288, 20531, -1, 20532, 20292, 20533, -1, 20288, 20292, 20532, -1, 20533, 19930, 20535, -1, 20292, 19930, 20533, -1, 20543, 20219, 20544, -1, 19850, 20219, 20543, -1, 20544, 20213, 20545, -1, 20219, 20213, 20544, -1, 20545, 20208, 20546, -1, 20213, 20208, 20545, -1, 20546, 20206, 20547, -1, 20208, 20206, 20546, -1, 20547, 20211, 20548, -1, 20206, 20211, 20547, -1, 20548, 20216, 20549, -1, 20211, 20216, 20548, -1, 20549, 20223, 20550, -1, 20216, 20223, 20549, -1, 20550, 19933, 20551, -1, 20223, 19933, 20550, -1, 20552, 20553, 20554, -1, 20553, 20555, 20554, -1, 20555, 20556, 20557, -1, 20558, 20556, 20553, -1, 20553, 20556, 20555, -1, 20544, 20545, 20543, -1, 20546, 20547, 20545, -1, 20547, 20548, 20545, -1, 20548, 20549, 20545, -1, 20543, 20551, 20556, -1, 20550, 20551, 20549, -1, 20556, 20551, 20557, -1, 20545, 20551, 20543, -1, 20549, 20551, 20545, -1, 20559, 20560, 20561, -1, 20560, 20562, 20563, -1, 20559, 20564, 20560, -1, 20560, 20564, 20562, -1, 20565, 20566, 20559, -1, 20559, 20566, 20564, -1, 20565, 20567, 20566, -1, 20557, 20568, 20565, -1, 20551, 20568, 20557, -1, 20565, 20568, 20567, -1, 20567, 20569, 20570, -1, 20568, 20569, 20567, -1, 20569, 20571, 20570, -1, 20572, 20573, 20569, -1, 20569, 20573, 20571, -1, 19933, 19773, 20568, -1, 19933, 20568, 20551, -1, 19849, 19850, 20543, -1, 19849, 20543, 20556, -1, 20568, 19773, 20569, -1, 20569, 19784, 20572, -1, 19773, 19784, 20569, -1, 20572, 19789, 20573, -1, 19784, 19789, 20572, -1, 20573, 19792, 20571, -1, 19789, 19792, 20573, -1, 20571, 19803, 20570, -1, 19792, 19803, 20571, -1, 19803, 19820, 20570, -1, 20570, 19835, 20567, -1, 19820, 19835, 20570, -1, 19935, 20284, 20557, -1, 20557, 20284, 20555, -1, 20555, 20281, 20554, -1, 20554, 20281, 20552, -1, 20284, 20281, 20555, -1, 20552, 20283, 20553, -1, 20281, 20283, 20552, -1, 20553, 20287, 20558, -1, 20283, 20287, 20553, -1, 20558, 20291, 20556, -1, 20287, 20291, 20558, -1, 20291, 19849, 20556, -1, 19835, 19895, 20566, -1, 19835, 20566, 20567, -1, 20565, 19935, 20557, -1, 19931, 19935, 20565, -1, 20566, 19994, 20564, -1, 19895, 19994, 20566, -1, 20564, 19990, 20562, -1, 20562, 19990, 20563, -1, 19994, 19990, 20564, -1, 20563, 19986, 20560, -1, 19990, 19986, 20563, -1, 20560, 19982, 20561, -1, 19986, 19982, 20560, -1, 20561, 19975, 20559, -1, 19982, 19975, 20561, -1, 19975, 19974, 20559, -1, 20559, 19931, 20565, -1, 19974, 19931, 20559, -1, 20574, 20149, 20575, -1, 19855, 20149, 20574, -1, 20575, 20144, 20576, -1, 20149, 20144, 20575, -1, 20576, 20139, 20577, -1, 20144, 20139, 20576, -1, 20577, 20142, 20578, -1, 20139, 20142, 20577, -1, 20578, 20148, 20579, -1, 20142, 20148, 20578, -1, 20579, 20151, 20580, -1, 20148, 20151, 20579, -1, 20580, 20154, 20581, -1, 20151, 20154, 20580, -1, 20581, 19917, 20582, -1, 20154, 19917, 20581, -1, 20583, 20584, 20585, -1, 20586, 20584, 20583, -1, 20587, 20584, 20586, -1, 20585, 20588, 20589, -1, 20584, 20588, 20585, -1, 20575, 20576, 20574, -1, 20576, 20577, 20574, -1, 20578, 20579, 20577, -1, 20577, 20579, 20574, -1, 20579, 20580, 20574, -1, 20574, 20582, 20588, -1, 20581, 20582, 20580, -1, 20588, 20582, 20589, -1, 20580, 20582, 20574, -1, 20590, 20591, 20592, -1, 20593, 20591, 20590, -1, 20594, 20595, 20596, -1, 20597, 20595, 20594, -1, 20591, 20595, 20597, -1, 20598, 20595, 20593, -1, 20593, 20595, 20591, -1, 20598, 20599, 20595, -1, 20589, 20600, 20598, -1, 20582, 20600, 20589, -1, 20598, 20600, 20599, -1, 20599, 20601, 20602, -1, 20600, 20601, 20599, -1, 20603, 20604, 20605, -1, 20602, 20604, 20603, -1, 20601, 20604, 20602, -1, 19917, 19934, 20600, -1, 19917, 20600, 20582, -1, 20588, 19855, 20574, -1, 19854, 19855, 20588, -1, 20600, 19678, 20601, -1, 19934, 19678, 20600, -1, 20601, 19677, 20604, -1, 19678, 19677, 20601, -1, 20604, 19689, 20605, -1, 20605, 19689, 20603, -1, 19677, 19689, 20604, -1, 20603, 19699, 20602, -1, 19689, 19699, 20603, -1, 19699, 19702, 20602, -1, 20602, 19708, 20599, -1, 19702, 19708, 20602, -1, 19932, 20210, 20589, -1, 20589, 20210, 20585, -1, 20585, 20205, 20583, -1, 20210, 20205, 20585, -1, 20583, 20207, 20586, -1, 20205, 20207, 20583, -1, 20586, 20209, 20587, -1, 20207, 20209, 20586, -1, 20587, 20214, 20584, -1, 20209, 20214, 20587, -1, 20584, 19854, 20588, -1, 20214, 19854, 20584, -1, 20599, 19839, 20595, -1, 19708, 19839, 20599, -1, 20598, 19932, 20589, -1, 19774, 19932, 20598, -1, 20595, 19825, 20596, -1, 19839, 19825, 20595, -1, 20596, 19811, 20594, -1, 19825, 19811, 20596, -1, 20594, 19794, 20597, -1, 19811, 19794, 20594, -1, 20597, 19791, 20591, -1, 19794, 19791, 20597, -1, 20591, 19783, 20592, -1, 19791, 19783, 20591, -1, 20592, 19775, 20590, -1, 19783, 19775, 20592, -1, 20590, 19772, 20593, -1, 19775, 19772, 20590, -1, 20593, 19774, 20598, -1, 19772, 19774, 20593, -1, 20606, 19706, 20607, -1, 20607, 19698, 20608, -1, 19706, 19698, 20607, -1, 20608, 19693, 20609, -1, 19698, 19693, 20608, -1, 20609, 19679, 20610, -1, 19693, 19679, 20609, -1, 20610, 19676, 20611, -1, 19679, 19676, 20610, -1, 19676, 20415, 20611, -1, 20611, 20414, 20612, -1, 20415, 20414, 20611, -1, 20612, 20413, 20613, -1, 20414, 20413, 20612, -1, 20613, 19916, 20614, -1, 20413, 19916, 20613, -1, 20615, 20616, 20617, -1, 20618, 20616, 20615, -1, 20619, 20616, 20618, -1, 20619, 20620, 20616, -1, 20620, 20621, 20616, -1, 20622, 20623, 20624, -1, 20623, 20625, 20624, -1, 20626, 20627, 20625, -1, 20624, 20628, 20629, -1, 20625, 20628, 20624, -1, 20627, 20628, 20625, -1, 20629, 20630, 20621, -1, 20621, 20630, 20616, -1, 20628, 20630, 20629, -1, 20614, 20612, 20613, -1, 20614, 20611, 20612, -1, 20614, 20610, 20611, -1, 20614, 20609, 20610, -1, 20609, 20607, 20608, -1, 20614, 20607, 20609, -1, 20614, 20606, 20607, -1, 20614, 20631, 20606, -1, 20616, 20632, 20614, -1, 20630, 20632, 20616, -1, 20614, 20632, 20631, -1, 20632, 20633, 20631, -1, 20634, 20635, 20636, -1, 20631, 20635, 20634, -1, 20633, 20635, 20631, -1, 20633, 20637, 20635, -1, 20614, 19915, 20616, -1, 19916, 19915, 20614, -1, 20631, 19706, 20606, -1, 19898, 19706, 20631, -1, 20616, 20143, 20617, -1, 19915, 20143, 20616, -1, 20617, 20138, 20615, -1, 20143, 20138, 20617, -1, 20615, 20140, 20618, -1, 20138, 20140, 20615, -1, 20618, 20145, 20619, -1, 20619, 20145, 20620, -1, 20140, 20145, 20618, -1, 20145, 20150, 20620, -1, 20620, 19856, 20621, -1, 20150, 19856, 20620, -1, 19918, 20354, 20632, -1, 20632, 20354, 20633, -1, 20633, 20354, 20637, -1, 20354, 20358, 20637, -1, 20637, 20374, 20635, -1, 20358, 20374, 20637, -1, 20635, 20381, 20636, -1, 20374, 20381, 20635, -1, 20636, 20385, 20634, -1, 20381, 20385, 20636, -1, 20634, 19898, 20631, -1, 20385, 19898, 20634, -1, 20621, 19858, 20629, -1, 19856, 19858, 20621, -1, 19919, 19918, 20632, -1, 19919, 20632, 20630, -1, 20629, 20075, 20624, -1, 20624, 20075, 20622, -1, 19858, 20075, 20629, -1, 20622, 20067, 20623, -1, 20075, 20067, 20622, -1, 20623, 20059, 20625, -1, 20067, 20059, 20623, -1, 20625, 20064, 20626, -1, 20059, 20064, 20625, -1, 20626, 20072, 20627, -1, 20064, 20072, 20626, -1, 20627, 20078, 20628, -1, 20072, 20078, 20627, -1, 20078, 20081, 20628, -1, 20628, 19919, 20630, -1, 20081, 19919, 20628, -1, 20638, 20012, 20639, -1, 20639, 20007, 20640, -1, 20012, 20007, 20639, -1, 20640, 20002, 20641, -1, 20007, 20002, 20640, -1, 20641, 19998, 20642, -1, 20002, 19998, 20641, -1, 20642, 20001, 20643, -1, 19998, 20001, 20642, -1, 20643, 20003, 20644, -1, 20001, 20003, 20643, -1, 20644, 20008, 20645, -1, 20003, 20008, 20644, -1, 20008, 20013, 20645, -1, 20645, 19906, 20646, -1, 20013, 19906, 20645, -1, 20647, 20648, 20649, -1, 20650, 20651, 20652, -1, 20653, 20651, 20650, -1, 20649, 20651, 20653, -1, 20648, 20651, 20649, -1, 20641, 20642, 20640, -1, 20643, 20644, 20642, -1, 20644, 20645, 20642, -1, 20638, 20646, 20651, -1, 20639, 20646, 20638, -1, 20640, 20646, 20639, -1, 20651, 20646, 20652, -1, 20642, 20646, 20640, -1, 20645, 20646, 20642, -1, 20654, 20655, 20656, -1, 20655, 20657, 20658, -1, 20659, 20660, 20661, -1, 20657, 20660, 20659, -1, 20662, 20660, 20654, -1, 20654, 20660, 20655, -1, 20655, 20660, 20657, -1, 20662, 20663, 20660, -1, 20652, 20664, 20662, -1, 20663, 20664, 20665, -1, 20646, 20664, 20652, -1, 20662, 20664, 20663, -1, 20664, 20666, 20665, -1, 20667, 20668, 20664, -1, 20664, 20668, 20666, -1, 19906, 19923, 20664, -1, 19906, 20664, 20646, -1, 20016, 20012, 20638, -1, 20016, 20638, 20651, -1, 20664, 19923, 20667, -1, 20667, 20302, 20668, -1, 19923, 20302, 20667, -1, 20668, 20305, 20666, -1, 20302, 20305, 20668, -1, 20666, 20310, 20665, -1, 20305, 20310, 20666, -1, 20310, 20313, 20665, -1, 20665, 19902, 20663, -1, 20313, 19902, 20665, -1, 19922, 20065, 20652, -1, 20652, 20065, 20650, -1, 20650, 20058, 20653, -1, 20065, 20058, 20650, -1, 20653, 20060, 20649, -1, 20058, 20060, 20653, -1, 20649, 20069, 20647, -1, 20060, 20069, 20649, -1, 20647, 20076, 20648, -1, 20648, 20076, 20651, -1, 20069, 20076, 20647, -1, 20076, 20016, 20651, -1, 19902, 19901, 20660, -1, 19902, 20660, 20663, -1, 20662, 19922, 20652, -1, 19920, 19922, 20662, -1, 20660, 19901, 20661, -1, 20661, 20382, 20659, -1, 19901, 20382, 20661, -1, 20659, 20375, 20657, -1, 20382, 20375, 20659, -1, 20657, 20357, 20658, -1, 20375, 20357, 20657, -1, 20658, 20353, 20655, -1, 20357, 20353, 20658, -1, 20655, 20350, 20656, -1, 20353, 20350, 20655, -1, 20656, 20348, 20654, -1, 20350, 20348, 20656, -1, 20348, 20347, 20654, -1, 20654, 19920, 20662, -1, 20347, 19920, 20654, -1, 20669, 19907, 20670, -1, 19907, 20239, 20670, -1, 20670, 20242, 20671, -1, 20239, 20242, 20670, -1, 20671, 20250, 20672, -1, 20242, 20250, 20671, -1, 20672, 20254, 20673, -1, 20250, 20254, 20672, -1, 20673, 20257, 20674, -1, 20254, 20257, 20673, -1, 20675, 20676, 20677, -1, 20678, 20676, 20675, -1, 20678, 20679, 20676, -1, 20679, 20680, 20676, -1, 20681, 20682, 20683, -1, 20683, 20684, 20680, -1, 20685, 20684, 20682, -1, 20686, 20684, 20685, -1, 20687, 20684, 20686, -1, 20688, 20684, 20687, -1, 20689, 20684, 20688, -1, 20682, 20684, 20683, -1, 20680, 20684, 20676, -1, 20690, 20691, 20692, -1, 20693, 20694, 20695, -1, 20691, 20694, 20693, -1, 20696, 20694, 20690, -1, 20697, 20694, 20696, -1, 20698, 20694, 20697, -1, 20690, 20694, 20691, -1, 20698, 20674, 20694, -1, 20676, 20669, 20698, -1, 20684, 20669, 20676, -1, 20698, 20669, 20674, -1, 20669, 20670, 20674, -1, 20673, 20671, 20672, -1, 20674, 20671, 20673, -1, 20670, 20671, 20674, -1, 20257, 19903, 20694, -1, 20257, 20694, 20674, -1, 19908, 19907, 20669, -1, 19908, 20669, 20684, -1, 20694, 19903, 20695, -1, 20695, 20312, 20693, -1, 19903, 20312, 20695, -1, 20693, 20309, 20691, -1, 20312, 20309, 20693, -1, 20691, 20306, 20692, -1, 20309, 20306, 20691, -1, 20692, 20301, 20690, -1, 20306, 20301, 20692, -1, 20690, 20298, 20696, -1, 20301, 20298, 20690, -1, 20298, 20297, 20696, -1, 20696, 20296, 20697, -1, 20297, 20296, 20696, -1, 20697, 19905, 20698, -1, 20296, 19905, 20697, -1, 20683, 19988, 20681, -1, 20681, 19984, 20682, -1, 19988, 19984, 20681, -1, 20682, 19980, 20685, -1, 19984, 19980, 20682, -1, 20685, 19978, 20686, -1, 19980, 19978, 20685, -1, 20686, 19976, 20687, -1, 19978, 19976, 20686, -1, 19976, 19981, 20687, -1, 20687, 19985, 20688, -1, 19981, 19985, 20687, -1, 20688, 19989, 20689, -1, 19985, 19989, 20688, -1, 20689, 19908, 20684, -1, 19989, 19908, 20689, -1, 20698, 19904, 20676, -1, 19905, 19904, 20698, -1, 19992, 19988, 20683, -1, 19992, 20683, 20680, -1, 20676, 19904, 20677, -1, 20677, 20000, 20675, -1, 19904, 20000, 20677, -1, 20675, 19997, 20678, -1, 20000, 19997, 20675, -1, 20678, 19999, 20679, -1, 19997, 19999, 20678, -1, 19999, 19993, 20679, -1, 20679, 19992, 20680, -1, 19993, 19992, 20679, -1, 20447, 20167, 20450, -1, 19911, 20167, 20447, -1, 20450, 20173, 20451, -1, 20167, 20173, 20450, -1, 20451, 20181, 20448, -1, 20173, 20181, 20451, -1, 20448, 20189, 20449, -1, 20181, 20189, 20448, -1, 20449, 20194, 20446, -1, 20189, 20194, 20449, -1, 20446, 20204, 20444, -1, 20194, 20204, 20446, -1, 20429, 19911, 20447, -1, 19912, 19911, 20429, -1, 20444, 20204, 20445, -1, 20445, 20251, 20443, -1, 20204, 20251, 20445, -1, 20443, 20245, 20441, -1, 20251, 20245, 20443, -1, 20441, 20240, 20442, -1, 20245, 20240, 20441, -1, 20442, 20236, 20440, -1, 20240, 20236, 20442, -1, 20440, 20235, 20438, -1, 20236, 20235, 20440, -1, 20438, 20234, 20439, -1, 20235, 20234, 20438, -1, 20234, 20233, 20439, -1, 20439, 19909, 20437, -1, 20233, 19909, 20439, -1, 19947, 19899, 20436, -1, 20436, 19899, 20435, -1, 20435, 19883, 20434, -1, 19899, 19883, 20435, -1, 20434, 19875, 20420, -1, 19883, 19875, 20434, -1, 19909, 19910, 20433, -1, 19909, 20433, 20437, -1, 19968, 19947, 20436, -1, 19968, 20436, 20430, -1, 20433, 19970, 20431, -1, 19910, 19970, 20433, -1, 20431, 19969, 20432, -1, 19970, 19969, 20431, -1, 20432, 19968, 20430, -1, 19969, 19968, 20432, -1, 19771, 20699, 20700, -1, 19771, 19924, 20699, -1, 20701, 20702, 20703, -1, 20704, 20705, 20706, -1, 20704, 20706, 20707, -1, 20704, 20707, 20702, -1, 20704, 20701, 20708, -1, 20704, 20702, 20701, -1, 20709, 20704, 20708, -1, 20710, 20704, 20709, -1, 20711, 20704, 20710, -1, 20712, 20713, 20714, -1, 20712, 20714, 20711, -1, 20715, 20712, 20711, -1, 20699, 20711, 20710, -1, 20699, 20715, 20711, -1, 20716, 20699, 20710, -1, 20717, 20716, 20718, -1, 20717, 20718, 20719, -1, 20700, 20717, 20720, -1, 20700, 20720, 20721, -1, 20700, 20721, 20722, -1, 20700, 20722, 20723, -1, 20700, 20699, 20716, -1, 20700, 20716, 20717, -1, 20724, 20700, 20723, -1, 20725, 20726, 20727, -1, 20728, 20725, 20727, -1, 20729, 20724, 20730, -1, 20731, 20732, 20728, -1, 20731, 20727, 20700, -1, 20731, 20700, 20724, -1, 20731, 20724, 20729, -1, 20731, 20728, 20727, -1, 20699, 19924, 20715, -1, 20715, 20109, 20712, -1, 19924, 20109, 20715, -1, 20712, 20113, 20713, -1, 20109, 20113, 20712, -1, 20113, 20117, 20713, -1, 20713, 20120, 20714, -1, 20117, 20120, 20713, -1, 20714, 20123, 20711, -1, 20120, 20123, 20714, -1, 19762, 19756, 20724, -1, 20724, 19756, 20730, -1, 20730, 19756, 20729, -1, 20729, 19750, 20731, -1, 19756, 19750, 20729, -1, 20731, 19744, 20732, -1, 19750, 19744, 20731, -1, 20732, 19748, 20728, -1, 19744, 19748, 20732, -1, 20728, 19754, 20725, -1, 19748, 19754, 20728, -1, 20725, 19758, 20726, -1, 19754, 19758, 20725, -1, 20726, 19767, 20727, -1, 19758, 19767, 20726, -1, 20727, 19769, 20700, -1, 19767, 19769, 20727, -1, 19769, 19771, 20700, -1, 20123, 20132, 20711, -1, 20711, 20132, 20704, -1, 20723, 19762, 20724, -1, 19777, 19762, 20723, -1, 20704, 20188, 20705, -1, 20132, 20188, 20704, -1, 20705, 20182, 20706, -1, 20188, 20182, 20705, -1, 20706, 20174, 20707, -1, 20182, 20174, 20706, -1, 20707, 20168, 20702, -1, 20174, 20168, 20707, -1, 20702, 20163, 20703, -1, 20168, 20163, 20702, -1, 20703, 20162, 20701, -1, 20163, 20162, 20703, -1, 20701, 20161, 20708, -1, 20162, 20161, 20701, -1, 20708, 20160, 20709, -1, 20161, 20160, 20708, -1, 20709, 19913, 20710, -1, 20160, 19913, 20709, -1, 20720, 19787, 20721, -1, 19787, 19785, 20721, -1, 20721, 19780, 20722, -1, 19785, 19780, 20721, -1, 20722, 19777, 20723, -1, 19780, 19777, 20722, -1, 19913, 20716, 20710, -1, 19913, 19810, 20716, -1, 20717, 19787, 20720, -1, 19788, 19787, 20717, -1, 20716, 19884, 20718, -1, 19810, 19884, 20716, -1, 20718, 19790, 20719, -1, 19884, 19790, 20718, -1, 20719, 19788, 20717, -1, 19790, 19788, 20719, -1, 20733, 19695, 20734, -1, 19703, 19695, 20733, -1, 20734, 19690, 20735, -1, 19695, 19690, 20734, -1, 20735, 19688, 20736, -1, 20736, 19688, 20737, -1, 19690, 19688, 20735, -1, 20737, 19687, 20738, -1, 19688, 19687, 20737, -1, 20738, 19694, 20739, -1, 19687, 19694, 20738, -1, 20739, 19700, 20740, -1, 19694, 19700, 20739, -1, 20740, 19707, 20741, -1, 19700, 19707, 20740, -1, 19707, 19710, 20741, -1, 20741, 19711, 20742, -1, 19710, 19711, 20741, -1, 20743, 20744, 20745, -1, 20743, 20746, 20744, -1, 20746, 20747, 20744, -1, 20747, 20748, 20744, -1, 20735, 20736, 20734, -1, 20737, 20738, 20736, -1, 20739, 20740, 20738, -1, 20738, 20740, 20736, -1, 20736, 20741, 20734, -1, 20740, 20741, 20736, -1, 20733, 20742, 20748, -1, 20734, 20742, 20733, -1, 20748, 20742, 20744, -1, 20741, 20742, 20734, -1, 20749, 20750, 20751, -1, 20749, 20752, 20750, -1, 20749, 20753, 20752, -1, 20749, 20754, 20753, -1, 20749, 20755, 20754, -1, 20749, 20756, 20755, -1, 20749, 20757, 20756, -1, 20749, 20758, 20757, -1, 20749, 20759, 20758, -1, 20744, 20760, 20749, -1, 20742, 20760, 20744, -1, 20749, 20760, 20759, -1, 20761, 20762, 20763, -1, 20759, 20762, 20761, -1, 20759, 20764, 20762, -1, 20760, 20764, 20759, -1, 19711, 20044, 20760, -1, 19711, 20760, 20742, -1, 19721, 19703, 20733, -1, 19721, 20733, 20748, -1, 20760, 20044, 20764, -1, 20764, 20046, 20762, -1, 20044, 20046, 20764, -1, 20046, 20053, 20762, -1, 20762, 20052, 20763, -1, 20053, 20052, 20762, -1, 20763, 20048, 20761, -1, 20052, 20048, 20763, -1, 20761, 20049, 20759, -1, 20048, 20049, 20761, -1, 20744, 19747, 20745, -1, 19747, 19743, 20745, -1, 20745, 19724, 20743, -1, 19743, 19724, 20745, -1, 20743, 19723, 20746, -1, 19724, 19723, 20743, -1, 20746, 19722, 20747, -1, 19723, 19722, 20746, -1, 20747, 19721, 20748, -1, 19722, 19721, 20747, -1, 20759, 20082, 20758, -1, 20049, 20082, 20759, -1, 19925, 19747, 20744, -1, 19925, 20744, 20749, -1, 20758, 20082, 20757, -1, 20757, 20083, 20756, -1, 20082, 20083, 20757, -1, 20756, 20114, 20755, -1, 20083, 20114, 20756, -1, 20755, 20110, 20754, -1, 20114, 20110, 20755, -1, 20754, 20105, 20753, -1, 20110, 20105, 20754, -1, 20753, 20103, 20752, -1, 20105, 20103, 20753, -1, 20752, 20102, 20750, -1, 20103, 20102, 20752, -1, 20750, 20101, 20751, -1, 20102, 20101, 20750, -1, 20101, 20100, 20751, -1, 20751, 19925, 20749, -1, 20100, 19925, 20751, -1, 20765, 19576, 20766, -1, 19577, 19576, 20765, -1, 20766, 19575, 20767, -1, 19576, 19575, 20766, -1, 20767, 19567, 20768, -1, 19575, 19567, 20767, -1, 20768, 19566, 20769, -1, 19567, 19566, 20768, -1, 20769, 19177, 20770, -1, 19566, 19177, 20769, -1, 20770, 20768, 20769, -1, 20767, 20768, 20770, -1, 20765, 20766, 20767, -1, 20765, 20767, 20770, -1, 20771, 20772, 20773, -1, 20771, 20773, 20774, -1, 20771, 20774, 20775, -1, 20771, 20775, 20776, -1, 20771, 20776, 20777, -1, 20771, 20777, 20778, -1, 20771, 20778, 20779, -1, 20771, 20779, 20780, -1, 20771, 20780, 20765, -1, 20771, 20765, 20770, -1, 20781, 20782, 20783, -1, 20784, 20782, 20781, -1, 20785, 20782, 20784, -1, 20786, 20782, 20785, -1, 20787, 20782, 20786, -1, 20788, 20782, 20787, -1, 20789, 20782, 20788, -1, 20790, 20782, 20789, -1, 20791, 20782, 20790, -1, 20792, 20791, 20793, -1, 20792, 20793, 20794, -1, 20792, 20770, 20782, -1, 20792, 20771, 20770, -1, 20792, 20782, 20791, -1, 20795, 20792, 20794, -1, 20796, 20792, 20795, -1, 19177, 18987, 20770, -1, 20770, 18987, 20782, -1, 20780, 19577, 20765, -1, 19614, 19577, 20780, -1, 20782, 18986, 20783, -1, 18987, 18986, 20782, -1, 20783, 18990, 20781, -1, 18986, 18990, 20783, -1, 20781, 18991, 20784, -1, 18990, 18991, 20781, -1, 20784, 18996, 20785, -1, 18991, 18996, 20784, -1, 20785, 19003, 20786, -1, 20786, 19003, 20787, -1, 18996, 19003, 20785, -1, 20787, 19009, 20788, -1, 19003, 19009, 20787, -1, 20788, 19019, 20789, -1, 19009, 19019, 20788, -1, 19019, 19026, 20789, -1, 20789, 19064, 20790, -1, 19026, 19064, 20789, -1, 20771, 19057, 20772, -1, 20772, 19650, 20773, -1, 19057, 19650, 20772, -1, 20773, 19649, 20774, -1, 19650, 19649, 20773, -1, 20774, 19648, 20775, -1, 19649, 19648, 20774, -1, 20775, 19647, 20776, -1, 19648, 19647, 20775, -1, 20776, 19646, 20777, -1, 19647, 19646, 20776, -1, 20777, 19645, 20778, -1, 19646, 19645, 20777, -1, 20778, 19644, 20779, -1, 19645, 19644, 20778, -1, 20779, 19643, 20780, -1, 19644, 19643, 20779, -1, 19643, 19614, 20780, -1, 19064, 19063, 20790, -1, 20790, 19063, 20791, -1, 20792, 19057, 20771, -1, 19056, 19057, 20792, -1, 20791, 19061, 20793, -1, 19063, 19061, 20791, -1, 20793, 19060, 20794, -1, 19061, 19060, 20793, -1, 20794, 19059, 20795, -1, 19060, 19059, 20794, -1, 20795, 19058, 20796, -1, 19059, 19058, 20795, -1, 20796, 19056, 20792, -1, 19058, 19056, 20796, -1, 19175, 20797, 20798, -1, 19175, 19150, 20797, -1, 20799, 20800, 20801, -1, 20802, 20803, 20804, -1, 20798, 20800, 20799, -1, 20805, 20806, 20807, -1, 20805, 20807, 20808, -1, 20805, 20808, 20802, -1, 20805, 20804, 20800, -1, 20805, 20802, 20804, -1, 20809, 20810, 20811, -1, 20809, 20811, 20812, -1, 20813, 20814, 20815, -1, 20813, 20815, 20816, -1, 20813, 20816, 20810, -1, 20813, 20810, 20809, -1, 20817, 20797, 20814, -1, 20817, 20814, 20813, -1, 20818, 20797, 20817, -1, 20819, 20798, 20797, -1, 20819, 20797, 20818, -1, 20820, 20821, 20822, -1, 20823, 20818, 20821, -1, 20823, 20819, 20818, -1, 20823, 20821, 20820, -1, 20819, 20805, 20800, -1, 20819, 20800, 20798, -1, 20800, 19505, 20801, -1, 19505, 19508, 20801, -1, 20801, 19516, 20799, -1, 20799, 19516, 20798, -1, 19508, 19516, 20801, -1, 19516, 19175, 20798, -1, 20797, 19655, 20814, -1, 19150, 19655, 20797, -1, 20814, 19656, 20815, -1, 19655, 19656, 20814, -1, 20815, 19659, 20816, -1, 19656, 19659, 20815, -1, 20816, 19663, 20810, -1, 19659, 19663, 20816, -1, 20810, 19665, 20811, -1, 19663, 19665, 20810, -1, 20811, 18928, 20812, -1, 19665, 18928, 20811, -1, 20812, 18927, 20809, -1, 18928, 18927, 20812, -1, 20809, 18936, 20813, -1, 18927, 18936, 20809, -1, 20813, 18943, 20817, -1, 18936, 18943, 20813, -1, 20804, 19505, 20800, -1, 19497, 19505, 20804, -1, 18943, 19051, 20817, -1, 20817, 19051, 20818, -1, 20824, 20825, 20804, -1, 20804, 20826, 19497, -1, 20825, 20826, 20804, -1, 19531, 20827, 20804, -1, 19515, 20827, 19522, -1, 19522, 20827, 19524, -1, 19524, 20827, 19531, -1, 20804, 20827, 20824, -1, 19501, 20828, 19515, -1, 20827, 20828, 20824, -1, 19515, 20828, 20827, -1, 20824, 20828, 20825, -1, 19497, 20829, 19494, -1, 19494, 20829, 19499, -1, 19499, 20829, 19501, -1, 19501, 20829, 20828, -1, 20825, 20829, 20826, -1, 20828, 20829, 20825, -1, 20826, 20829, 19497, -1, 20818, 19050, 20821, -1, 19051, 19050, 20818, -1, 20821, 19018, 20822, -1, 19050, 19018, 20821, -1, 20822, 19008, 20820, -1, 19018, 19008, 20822, -1, 20820, 19002, 20823, -1, 19008, 19002, 20820, -1, 20823, 18985, 20819, -1, 19002, 18985, 20823, -1, 19171, 19572, 20805, -1, 20805, 19572, 20806, -1, 20806, 19571, 20807, -1, 19572, 19571, 20806, -1, 20807, 19570, 20808, -1, 19571, 19570, 20807, -1, 20808, 19569, 20802, -1, 19570, 19569, 20808, -1, 20802, 19565, 20803, -1, 20803, 19565, 20804, -1, 19569, 19565, 20802, -1, 19565, 19531, 20804, -1, 18985, 19171, 20819, -1, 20819, 19171, 20805, -1, 20830, 19408, 20831, -1, 19418, 19408, 20830, -1, 20831, 19402, 20832, -1, 19408, 19402, 20831, -1, 20832, 19394, 20833, -1, 19402, 19394, 20832, -1, 20833, 19399, 20834, -1, 19394, 19399, 20833, -1, 20834, 19153, 20835, -1, 19399, 19153, 20834, -1, 20836, 20837, 20838, -1, 20836, 20839, 20837, -1, 20840, 20841, 20836, -1, 20842, 20841, 20840, -1, 20839, 20843, 20844, -1, 20836, 20843, 20839, -1, 20841, 20843, 20836, -1, 20841, 20845, 20843, -1, 20841, 20846, 20845, -1, 20847, 20848, 20846, -1, 20849, 20848, 20847, -1, 20850, 20848, 20849, -1, 20851, 20848, 20850, -1, 20846, 20848, 20845, -1, 20848, 20835, 20845, -1, 20834, 20832, 20833, -1, 20834, 20831, 20832, -1, 20835, 20830, 20834, -1, 20834, 20830, 20831, -1, 20848, 20852, 20835, -1, 20835, 20852, 20830, -1, 20853, 20854, 20852, -1, 20852, 20855, 20830, -1, 20854, 20856, 20852, -1, 20856, 20857, 20852, -1, 20855, 20858, 20859, -1, 20852, 20858, 20855, -1, 20857, 20860, 20852, -1, 20852, 20861, 20858, -1, 20860, 20861, 20852, -1, 19153, 19144, 20845, -1, 19153, 20845, 20835, -1, 19446, 19418, 20830, -1, 19446, 20830, 20855, -1, 20845, 19582, 20843, -1, 19144, 19582, 20845, -1, 20843, 19583, 20844, -1, 19582, 19583, 20843, -1, 20844, 19586, 20839, -1, 19583, 19586, 20844, -1, 20839, 19590, 20837, -1, 19586, 19590, 20839, -1, 20837, 19592, 20838, -1, 19590, 19592, 20837, -1, 20838, 19596, 20836, -1, 19592, 19596, 20838, -1, 20836, 19599, 20840, -1, 19596, 19599, 20836, -1, 20840, 19603, 20842, -1, 19599, 19603, 20840, -1, 20842, 19062, 20841, -1, 19603, 19062, 20842, -1, 20852, 19148, 20853, -1, 20853, 19519, 20854, -1, 19148, 19519, 20853, -1, 20854, 19476, 20856, -1, 19519, 19476, 20854, -1, 20856, 19473, 20857, -1, 19476, 19473, 20856, -1, 20857, 19467, 20860, -1, 19473, 19467, 20857, -1, 20860, 19464, 20861, -1, 19467, 19464, 20860, -1, 20861, 19457, 20858, -1, 19464, 19457, 20861, -1, 20858, 19455, 20859, -1, 19457, 19455, 20858, -1, 20859, 19450, 20855, -1, 19455, 19450, 20859, -1, 19450, 19446, 20855, -1, 19062, 18948, 20846, -1, 19062, 20846, 20841, -1, 19149, 19148, 20852, -1, 19149, 20852, 20848, -1, 20846, 18940, 20847, -1, 18948, 18940, 20846, -1, 20847, 18929, 20849, -1, 18940, 18929, 20847, -1, 20849, 18926, 20850, -1, 18929, 18926, 20849, -1, 20850, 19664, 20851, -1, 18926, 19664, 20850, -1, 20851, 19149, 20848, -1, 19664, 19149, 20851, -1, 20862, 19310, 20863, -1, 19112, 19310, 20862, -1, 20863, 19301, 20864, -1, 19310, 19301, 20863, -1, 20864, 19291, 20865, -1, 19301, 19291, 20864, -1, 20865, 19299, 20866, -1, 19291, 19299, 20865, -1, 20866, 19146, 20867, -1, 19299, 19146, 20866, -1, 20868, 20869, 20870, -1, 20871, 20869, 20868, -1, 20872, 20869, 20871, -1, 20873, 20869, 20872, -1, 20874, 20869, 20873, -1, 20875, 20869, 20874, -1, 20876, 20869, 20875, -1, 20876, 20877, 20869, -1, 20878, 20879, 20877, -1, 20880, 20879, 20878, -1, 20881, 20879, 20880, -1, 20882, 20879, 20881, -1, 20877, 20879, 20869, -1, 20879, 20867, 20869, -1, 20867, 20865, 20866, -1, 20867, 20864, 20865, -1, 20867, 20863, 20864, -1, 20867, 20862, 20863, -1, 20879, 20883, 20867, -1, 20867, 20883, 20862, -1, 20883, 20884, 20862, -1, 20885, 20886, 20883, -1, 20883, 20887, 20884, -1, 20886, 20888, 20883, -1, 20883, 20889, 20887, -1, 20888, 20890, 20883, -1, 20883, 20891, 20889, -1, 20890, 20892, 20883, -1, 20883, 20892, 20891, -1, 20867, 19145, 20869, -1, 19146, 19145, 20867, -1, 20884, 19112, 20862, -1, 19411, 19112, 20884, -1, 20869, 19474, 20870, -1, 19145, 19474, 20869, -1, 20870, 19480, 20868, -1, 19474, 19480, 20870, -1, 20868, 19486, 20871, -1, 19480, 19486, 20868, -1, 20871, 19488, 20872, -1, 19486, 19488, 20871, -1, 20872, 19510, 20873, -1, 19488, 19510, 20872, -1, 20873, 19527, 20874, -1, 19510, 19527, 20873, -1, 20874, 19532, 20875, -1, 19527, 19532, 20874, -1, 20875, 19054, 20876, -1, 19532, 19054, 20875, -1, 20883, 19142, 20885, -1, 20885, 19407, 20886, -1, 19142, 19407, 20885, -1, 20886, 19406, 20888, -1, 19407, 19406, 20886, -1, 20888, 19404, 20890, -1, 19406, 19404, 20888, -1, 20890, 19398, 20892, -1, 19404, 19398, 20890, -1, 20892, 19393, 20891, -1, 19398, 19393, 20892, -1, 20891, 19395, 20889, -1, 19393, 19395, 20891, -1, 20889, 19403, 20887, -1, 19395, 19403, 20889, -1, 20887, 19409, 20884, -1, 19403, 19409, 20887, -1, 19409, 19411, 20884, -1, 20876, 19055, 20877, -1, 19054, 19055, 20876, -1, 19143, 19142, 20883, -1, 19143, 20883, 20879, -1, 20877, 19598, 20878, -1, 19055, 19598, 20877, -1, 20878, 19595, 20880, -1, 19598, 19595, 20878, -1, 20880, 19591, 20881, -1, 19595, 19591, 20880, -1, 20881, 19589, 20882, -1, 19591, 19589, 20881, -1, 20882, 19143, 20879, -1, 19589, 19143, 20882, -1, 20893, 19197, 20894, -1, 19110, 19197, 20893, -1, 20894, 19162, 20895, -1, 20895, 19162, 20896, -1, 19197, 19162, 20894, -1, 20896, 19122, 20897, -1, 19162, 19122, 20896, -1, 19122, 19134, 20897, -1, 20897, 19159, 20898, -1, 19134, 19159, 20897, -1, 20899, 20900, 20901, -1, 20902, 20900, 20899, -1, 20903, 20900, 20902, -1, 20904, 20900, 20903, -1, 20905, 20900, 20904, -1, 20906, 20900, 20905, -1, 20907, 20900, 20906, -1, 20907, 20908, 20900, -1, 20909, 20910, 20908, -1, 20910, 20911, 20908, -1, 20911, 20912, 20908, -1, 20908, 20913, 20900, -1, 20912, 20913, 20908, -1, 20913, 20898, 20900, -1, 20897, 20895, 20896, -1, 20897, 20894, 20895, -1, 20898, 20893, 20897, -1, 20897, 20893, 20894, -1, 20913, 20914, 20898, -1, 20898, 20914, 20893, -1, 20915, 20916, 20914, -1, 20914, 20916, 20893, -1, 20915, 20917, 20916, -1, 20918, 20919, 20915, -1, 20920, 20919, 20918, -1, 20917, 20919, 20921, -1, 20915, 20919, 20917, -1, 20919, 20922, 20921, -1, 20898, 19156, 20900, -1, 19159, 19156, 20898, -1, 19111, 19110, 20893, -1, 19111, 20893, 20916, -1, 20900, 19366, 20901, -1, 19156, 19366, 20900, -1, 20901, 19369, 20899, -1, 19366, 19369, 20901, -1, 20899, 19373, 20902, -1, 19369, 19373, 20899, -1, 20902, 19376, 20903, -1, 19373, 19376, 20902, -1, 20903, 19379, 20904, -1, 19376, 19379, 20903, -1, 20904, 19386, 20905, -1, 19379, 19386, 20904, -1, 20905, 19390, 20906, -1, 19386, 19390, 20905, -1, 20906, 19095, 20907, -1, 19390, 19095, 20906, -1, 19147, 19309, 20914, -1, 20914, 19309, 20915, -1, 20915, 19309, 20918, -1, 20918, 19308, 20920, -1, 19309, 19308, 20918, -1, 20920, 19306, 20919, -1, 19308, 19306, 20920, -1, 20919, 19298, 20922, -1, 19306, 19298, 20919, -1, 20922, 19290, 20921, -1, 19298, 19290, 20922, -1, 20921, 19292, 20917, -1, 19290, 19292, 20921, -1, 20917, 19302, 20916, -1, 19292, 19302, 20917, -1, 19302, 19111, 20916, -1, 19095, 19096, 20908, -1, 19095, 20908, 20907, -1, 19158, 19147, 20914, -1, 19158, 20914, 20913, -1, 20908, 19096, 20909, -1, 20909, 19533, 20910, -1, 19096, 19533, 20909, -1, 20910, 19526, 20911, -1, 19533, 19526, 20910, -1, 20911, 19509, 20912, -1, 19526, 19509, 20911, -1, 19509, 19490, 20912, -1, 20912, 19158, 20913, -1, 19490, 19158, 20912, -1, 20923, 18981, 20924, -1, 18988, 18981, 20923, -1, 20924, 18968, 20925, -1, 18981, 18968, 20924, -1, 20925, 18959, 20926, -1, 18968, 18959, 20925, -1, 20926, 18951, 20927, -1, 18959, 18951, 20926, -1, 20927, 18962, 20928, -1, 18951, 18962, 20927, -1, 20928, 18972, 20929, -1, 18962, 18972, 20928, -1, 20930, 20931, 20932, -1, 20933, 20934, 20930, -1, 20935, 20934, 20933, -1, 20936, 20934, 20935, -1, 20930, 20934, 20931, -1, 20934, 20937, 20931, -1, 20934, 20938, 20937, -1, 20934, 20939, 20938, -1, 20940, 20941, 20939, -1, 20941, 20942, 20939, -1, 20942, 20943, 20939, -1, 20939, 20944, 20938, -1, 20943, 20944, 20939, -1, 20944, 20929, 20938, -1, 20928, 20926, 20927, -1, 20928, 20925, 20926, -1, 20925, 20923, 20924, -1, 20929, 20923, 20928, -1, 20928, 20923, 20925, -1, 20944, 20945, 20929, -1, 20929, 20945, 20923, -1, 20946, 20947, 20945, -1, 20945, 20947, 20923, -1, 20946, 20948, 20947, -1, 20949, 20950, 20946, -1, 20946, 20950, 20948, -1, 20950, 20951, 20948, -1, 20950, 20952, 20951, -1, 20952, 20953, 20951, -1, 20929, 19157, 20938, -1, 18972, 19157, 20929, -1, 19109, 18988, 20923, -1, 19109, 20923, 20947, -1, 20938, 19278, 20937, -1, 20937, 19278, 20931, -1, 19157, 19278, 20938, -1, 20931, 19281, 20932, -1, 19278, 19281, 20931, -1, 20932, 19284, 20930, -1, 19281, 19284, 20932, -1, 20930, 19314, 20933, -1, 19284, 19314, 20930, -1, 20933, 19322, 20935, -1, 19314, 19322, 20933, -1, 20935, 19326, 20936, -1, 19322, 19326, 20935, -1, 19326, 19331, 20936, -1, 20936, 19093, 20934, -1, 19331, 19093, 20936, -1, 19154, 19174, 20945, -1, 20945, 19174, 20946, -1, 20946, 19173, 20949, -1, 19174, 19173, 20946, -1, 20949, 19133, 20950, -1, 19173, 19133, 20949, -1, 20950, 19121, 20952, -1, 19133, 19121, 20950, -1, 20952, 19123, 20953, -1, 19121, 19123, 20952, -1, 20953, 19163, 20951, -1, 19123, 19163, 20953, -1, 20951, 19198, 20948, -1, 19163, 19198, 20951, -1, 20948, 19109, 20947, -1, 19198, 19109, 20948, -1, 19093, 19094, 20939, -1, 19093, 20939, 20934, -1, 20944, 19154, 20945, -1, 19155, 19154, 20944, -1, 20939, 19387, 20940, -1, 19094, 19387, 20939, -1, 20940, 19382, 20941, -1, 19387, 19382, 20940, -1, 20941, 19378, 20942, -1, 19382, 19378, 20941, -1, 20942, 19374, 20943, -1, 19378, 19374, 20942, -1, 20943, 19155, 20944, -1, 19374, 19155, 20943, -1, 20954, 19627, 20955, -1, 19107, 19627, 20954, -1, 20955, 19620, 20956, -1, 19627, 19620, 20955, -1, 20956, 19612, 20957, -1, 19620, 19612, 20956, -1, 20957, 19608, 20958, -1, 19612, 19608, 20957, -1, 20958, 19617, 20959, -1, 19608, 19617, 20958, -1, 20959, 19168, 20960, -1, 19617, 19168, 20959, -1, 20956, 20957, 20958, -1, 20954, 20955, 20956, -1, 20954, 20958, 20959, -1, 20954, 20959, 20960, -1, 20954, 20956, 20958, -1, 20961, 20962, 20963, -1, 20964, 20961, 20963, -1, 20965, 20966, 20964, -1, 20967, 20965, 20964, -1, 20967, 20964, 20963, -1, 20968, 20967, 20963, -1, 20969, 20963, 20954, -1, 20969, 20954, 20960, -1, 20969, 20968, 20963, -1, 20970, 20971, 20972, -1, 20973, 20971, 20970, -1, 20974, 20971, 20973, -1, 20975, 20971, 20974, -1, 20976, 20971, 20975, -1, 20977, 20971, 20976, -1, 20978, 20971, 20977, -1, 20979, 20971, 20978, -1, 20980, 20960, 20971, -1, 20980, 20969, 20960, -1, 20980, 20971, 20979, -1, 20981, 20979, 20982, -1, 20983, 20980, 20979, -1, 20984, 20979, 20981, -1, 20984, 20983, 20979, -1, 20985, 20983, 20984, -1, 19168, 19166, 20960, -1, 20960, 19166, 20971, -1, 20963, 19107, 20954, -1, 18982, 19107, 20963, -1, 20971, 19166, 20972, -1, 20972, 19217, 20970, -1, 19166, 19217, 20972, -1, 20970, 19222, 20973, -1, 19217, 19222, 20970, -1, 20973, 19229, 20974, -1, 19222, 19229, 20973, -1, 20974, 19235, 20975, -1, 19229, 19235, 20974, -1, 20975, 19241, 20976, -1, 19235, 19241, 20975, -1, 20976, 19246, 20977, -1, 19241, 19246, 20976, -1, 19246, 19251, 20977, -1, 20977, 19091, 20978, -1, 19251, 19091, 20977, -1, 18975, 18974, 20969, -1, 20969, 18974, 20968, -1, 20968, 18973, 20967, -1, 18974, 18973, 20968, -1, 20967, 18965, 20965, -1, 18973, 18965, 20967, -1, 20965, 18950, 20966, -1, 18965, 18950, 20965, -1, 20966, 18952, 20964, -1, 18950, 18952, 20966, -1, 20964, 18960, 20961, -1, 18952, 18960, 20964, -1, 20961, 18969, 20962, -1, 18960, 18969, 20961, -1, 20962, 18982, 20963, -1, 18969, 18982, 20962, -1, 19091, 19092, 20978, -1, 20978, 19092, 20979, -1, 19170, 20969, 20980, -1, 19170, 18975, 20969, -1, 20979, 19330, 20982, -1, 19092, 19330, 20979, -1, 20982, 19329, 20981, -1, 19330, 19329, 20982, -1, 20981, 19323, 20984, -1, 19329, 19323, 20981, -1, 20984, 19315, 20985, -1, 19323, 19315, 20984, -1, 20985, 19285, 20983, -1, 19315, 19285, 20985, -1, 20983, 19170, 20980, -1, 19285, 19170, 20983, -1, 20986, 18993, 20987, -1, 18994, 18993, 20986, -1, 20987, 18995, 20988, -1, 18993, 18995, 20987, -1, 20988, 18999, 20989, -1, 18995, 18999, 20988, -1, 20989, 19007, 20990, -1, 18999, 19007, 20989, -1, 20990, 19012, 20991, -1, 19007, 19012, 20990, -1, 20991, 19021, 20992, -1, 19012, 19021, 20991, -1, 20992, 19030, 20993, -1, 19021, 19030, 20992, -1, 20993, 19036, 20994, -1, 19030, 19036, 20993, -1, 20990, 20988, 20989, -1, 20988, 20994, 20987, -1, 20991, 20994, 20990, -1, 20992, 20994, 20991, -1, 20993, 20994, 20992, -1, 20990, 20994, 20988, -1, 20994, 20986, 20987, -1, 20994, 20995, 20986, -1, 20996, 20997, 20995, -1, 20997, 20998, 20995, -1, 20999, 21000, 20998, -1, 20998, 21000, 20995, -1, 20995, 21001, 20986, -1, 21000, 21001, 20995, -1, 21001, 21002, 20986, -1, 21003, 21004, 21005, -1, 21003, 21006, 21004, -1, 21003, 21007, 21006, -1, 21002, 21008, 21003, -1, 21003, 21008, 21007, -1, 21001, 21009, 21002, -1, 21002, 21009, 21008, -1, 21010, 21011, 21009, -1, 21009, 21011, 21008, -1, 21010, 21012, 21011, -1, 21013, 21014, 21010, -1, 21015, 21014, 21013, -1, 21010, 21014, 21012, -1, 21012, 21016, 21017, -1, 21014, 21016, 21012, -1, 19036, 19090, 20995, -1, 19036, 20995, 20994, -1, 19160, 18994, 20986, -1, 19160, 20986, 21002, -1, 20995, 19250, 20996, -1, 19090, 19250, 20995, -1, 20996, 19248, 20997, -1, 19250, 19248, 20996, -1, 20997, 19242, 20998, -1, 19248, 19242, 20997, -1, 20998, 19236, 20999, -1, 19242, 19236, 20998, -1, 20999, 19228, 21000, -1, 19236, 19228, 20999, -1, 21000, 19165, 21001, -1, 19228, 19165, 21000, -1, 19105, 19551, 21008, -1, 21008, 19551, 21007, -1, 21007, 19542, 21006, -1, 19551, 19542, 21007, -1, 21006, 19529, 21004, -1, 19542, 19529, 21006, -1, 21004, 19539, 21005, -1, 19529, 19539, 21004, -1, 21005, 19545, 21003, -1, 19539, 19545, 21005, -1, 21003, 19160, 21002, -1, 19545, 19160, 21003, -1, 19165, 19164, 21009, -1, 19165, 21009, 21001, -1, 19106, 19105, 21008, -1, 19106, 21008, 21011, -1, 21009, 19626, 21010, -1, 19164, 19626, 21009, -1, 21010, 19625, 21013, -1, 19626, 19625, 21010, -1, 21013, 19616, 21015, -1, 19625, 19616, 21013, -1, 21015, 19607, 21014, -1, 19616, 19607, 21015, -1, 21014, 19609, 21016, -1, 19607, 19609, 21014, -1, 21016, 19613, 21017, -1, 19609, 19613, 21016, -1, 21017, 19621, 21012, -1, 19613, 19621, 21017, -1, 21012, 19106, 21011, -1, 19621, 19106, 21012, -1, 21018, 19449, 21019, -1, 19103, 19449, 21018, -1, 21019, 19443, 21020, -1, 19449, 19443, 21019, -1, 21020, 19437, 21021, -1, 19443, 19437, 21020, -1, 21021, 19441, 21022, -1, 19437, 19441, 21021, -1, 21022, 19448, 21023, -1, 19441, 19448, 21022, -1, 21023, 19453, 21024, -1, 19448, 19453, 21023, -1, 21025, 21026, 21027, -1, 21028, 21029, 21030, -1, 21027, 21029, 21028, -1, 21026, 21031, 21027, -1, 21027, 21031, 21029, -1, 21031, 21032, 21029, -1, 21031, 21033, 21032, -1, 21034, 21035, 21036, -1, 21035, 21037, 21036, -1, 21036, 21038, 21033, -1, 21037, 21038, 21036, -1, 21033, 21039, 21032, -1, 21038, 21039, 21033, -1, 21039, 21024, 21032, -1, 21020, 21018, 21019, -1, 21021, 21018, 21020, -1, 21022, 21018, 21021, -1, 21023, 21018, 21022, -1, 21024, 21018, 21023, -1, 21039, 21040, 21024, -1, 21024, 21040, 21018, -1, 21040, 21041, 21018, -1, 21040, 21042, 21041, -1, 21042, 21043, 21041, -1, 21044, 21045, 21043, -1, 21046, 21045, 21047, -1, 21041, 21045, 21046, -1, 21043, 21045, 21041, -1, 21044, 21048, 21045, -1, 19453, 19637, 21032, -1, 19453, 21032, 21024, -1, 19104, 19103, 21018, -1, 19104, 21018, 21041, -1, 21032, 19638, 21029, -1, 19637, 19638, 21032, -1, 21029, 19640, 21030, -1, 19638, 19640, 21029, -1, 21030, 19641, 21028, -1, 19640, 19641, 21030, -1, 21028, 19651, 21027, -1, 19641, 19651, 21028, -1, 21027, 19653, 21025, -1, 19651, 19653, 21027, -1, 21025, 19658, 21026, -1, 19653, 19658, 21025, -1, 21026, 19089, 21031, -1, 19658, 19089, 21026, -1, 19161, 19554, 21040, -1, 21040, 19554, 21042, -1, 21042, 19544, 21043, -1, 21043, 19544, 21044, -1, 19554, 19544, 21042, -1, 21044, 19538, 21048, -1, 19544, 19538, 21044, -1, 21048, 19528, 21045, -1, 19538, 19528, 21048, -1, 21045, 19530, 21047, -1, 19528, 19530, 21045, -1, 21047, 19543, 21046, -1, 19530, 19543, 21047, -1, 21046, 19553, 21041, -1, 19543, 19553, 21046, -1, 19553, 19104, 21041, -1, 19089, 19033, 21033, -1, 19089, 21033, 21031, -1, 18992, 19161, 21040, -1, 18992, 21040, 21039, -1, 21033, 19025, 21036, -1, 21036, 19025, 21034, -1, 19033, 19025, 21033, -1, 21034, 19013, 21035, -1, 19025, 19013, 21034, -1, 21035, 19006, 21037, -1, 19013, 19006, 21035, -1, 21037, 19001, 21038, -1, 19006, 19001, 21037, -1, 19001, 18997, 21038, -1, 21038, 18992, 21039, -1, 18997, 18992, 21038, -1, 21049, 19359, 21050, -1, 19114, 19359, 21049, -1, 21050, 19353, 21051, -1, 19359, 19353, 21050, -1, 21051, 19347, 21052, -1, 19353, 19347, 21051, -1, 21052, 19352, 21053, -1, 19347, 19352, 21052, -1, 21053, 19357, 21054, -1, 19352, 19357, 21053, -1, 21054, 19364, 21055, -1, 19357, 19364, 21054, -1, 21056, 21057, 21058, -1, 21056, 21059, 21057, -1, 21060, 21061, 21056, -1, 21062, 21061, 21060, -1, 21056, 21061, 21059, -1, 21061, 21063, 21059, -1, 21061, 21064, 21063, -1, 21065, 21066, 21064, -1, 21067, 21068, 21066, -1, 21066, 21068, 21064, -1, 21068, 21069, 21064, -1, 21064, 21070, 21063, -1, 21069, 21070, 21064, -1, 21070, 21055, 21063, -1, 21053, 21051, 21052, -1, 21054, 21051, 21053, -1, 21055, 21051, 21054, -1, 21055, 21050, 21051, -1, 21055, 21049, 21050, -1, 21070, 21071, 21055, -1, 21055, 21071, 21049, -1, 21071, 21072, 21049, -1, 21071, 21073, 21072, -1, 21074, 21075, 21073, -1, 21076, 21075, 21074, -1, 21077, 21075, 21078, -1, 21072, 21075, 21077, -1, 21073, 21075, 21072, -1, 21055, 19574, 21063, -1, 19364, 19574, 21055, -1, 19102, 19114, 21049, -1, 19102, 21049, 21072, -1, 21063, 19579, 21059, -1, 19574, 19579, 21063, -1, 21059, 19581, 21057, -1, 19579, 19581, 21059, -1, 21057, 19585, 21058, -1, 19581, 19585, 21057, -1, 21058, 19588, 21056, -1, 19585, 19588, 21058, -1, 21056, 19594, 21060, -1, 19588, 19594, 21056, -1, 21060, 19597, 21062, -1, 19594, 19597, 21060, -1, 21062, 19087, 21061, -1, 19597, 19087, 21062, -1, 19454, 19452, 21071, -1, 21071, 19452, 21073, -1, 21073, 19452, 21074, -1, 21074, 19447, 21076, -1, 19452, 19447, 21074, -1, 21076, 19442, 21075, -1, 19447, 19442, 21076, -1, 19442, 19436, 21075, -1, 21075, 19438, 21078, -1, 19436, 19438, 21075, -1, 21078, 19445, 21077, -1, 19438, 19445, 21078, -1, 21077, 19102, 21072, -1, 19445, 19102, 21077, -1, 21061, 19088, 21064, -1, 19087, 19088, 21061, -1, 19636, 19454, 21071, -1, 19636, 21071, 21070, -1, 21064, 19088, 21065, -1, 21065, 19657, 21066, -1, 19088, 19657, 21065, -1, 21066, 19654, 21067, -1, 19657, 19654, 21066, -1, 21067, 19652, 21068, -1, 19654, 19652, 21067, -1, 21068, 19642, 21069, -1, 19652, 19642, 21068, -1, 19642, 19639, 21069, -1, 21069, 19636, 21070, -1, 19639, 19636, 21069, -1, 21079, 19116, 21080, -1, 19116, 19280, 21080, -1, 21080, 19275, 21081, -1, 19280, 19275, 21080, -1, 21081, 19271, 21082, -1, 19275, 19271, 21081, -1, 21082, 19269, 21083, -1, 19271, 19269, 21082, -1, 21083, 19273, 21084, -1, 19269, 19273, 21083, -1, 21084, 19277, 21085, -1, 19273, 19277, 21084, -1, 21085, 19282, 21086, -1, 19277, 19282, 21085, -1, 21087, 21088, 21089, -1, 21090, 21088, 21087, -1, 21091, 21088, 21090, -1, 21088, 21092, 21089, -1, 21088, 21093, 21092, -1, 21093, 21094, 21092, -1, 21093, 21095, 21094, -1, 21096, 21097, 21098, -1, 21098, 21099, 21100, -1, 21097, 21099, 21098, -1, 21100, 21101, 21095, -1, 21095, 21101, 21094, -1, 21099, 21101, 21100, -1, 21101, 21086, 21094, -1, 21084, 21082, 21083, -1, 21081, 21079, 21080, -1, 21082, 21079, 21081, -1, 21085, 21079, 21084, -1, 21086, 21079, 21085, -1, 21084, 21079, 21082, -1, 21101, 21102, 21086, -1, 21086, 21102, 21079, -1, 21102, 21103, 21079, -1, 21104, 21105, 21102, -1, 21103, 21106, 21107, -1, 21102, 21108, 21103, -1, 21105, 21108, 21102, -1, 21103, 21108, 21106, -1, 21108, 21109, 21106, -1, 21086, 19502, 21094, -1, 19282, 19502, 21086, -1, 21103, 19116, 21079, -1, 19115, 19116, 21103, -1, 21094, 19506, 21092, -1, 19502, 19506, 21094, -1, 21092, 19511, 21089, -1, 19506, 19511, 21092, -1, 21089, 19514, 21087, -1, 19511, 19514, 21089, -1, 21087, 19517, 21090, -1, 19514, 19517, 21087, -1, 21090, 19520, 21091, -1, 21091, 19520, 21088, -1, 19517, 19520, 21090, -1, 19520, 19523, 21088, -1, 21088, 19085, 21093, -1, 19523, 19085, 21088, -1, 19365, 19356, 21102, -1, 21102, 19356, 21104, -1, 21104, 19351, 21105, -1, 19356, 19351, 21104, -1, 21105, 19346, 21108, -1, 19351, 19346, 21105, -1, 21108, 19348, 21109, -1, 19346, 19348, 21108, -1, 21109, 19354, 21106, -1, 19348, 19354, 21109, -1, 21106, 19360, 21107, -1, 19354, 19360, 21106, -1, 21107, 19115, 21103, -1, 19360, 19115, 21107, -1, 19085, 19086, 21095, -1, 19085, 21095, 21093, -1, 21101, 19365, 21102, -1, 19573, 19365, 21101, -1, 21095, 19086, 21100, -1, 21100, 19593, 21098, -1, 19086, 19593, 21100, -1, 21098, 19587, 21096, -1, 19593, 19587, 21098, -1, 21096, 19584, 21097, -1, 19587, 19584, 21096, -1, 21097, 19580, 21099, -1, 19584, 19580, 21097, -1, 19580, 19578, 21099, -1, 21099, 19573, 21101, -1, 19578, 19573, 21099, -1, 21110, 19119, 21111, -1, 19117, 19119, 21110, -1, 21112, 21113, 21114, -1, 21111, 21112, 21114, -1, 21115, 21116, 21117, -1, 21115, 21118, 21116, -1, 21115, 21114, 21118, -1, 21115, 21111, 21114, -1, 21119, 21120, 21121, -1, 21119, 21121, 21110, -1, 21122, 21110, 21111, -1, 21122, 21123, 21124, -1, 21122, 21124, 21125, -1, 21122, 21125, 21119, -1, 21122, 21111, 21115, -1, 21122, 21119, 21110, -1, 21126, 21122, 21115, -1, 21127, 21126, 21128, -1, 21129, 21126, 21127, -1, 21130, 21126, 21129, -1, 21131, 21130, 21132, -1, 21131, 21126, 21130, -1, 21133, 21126, 21131, -1, 21134, 21133, 21135, -1, 21134, 21122, 21126, -1, 21134, 21126, 21133, -1, 21136, 21134, 21135, -1, 21137, 21138, 21134, -1, 21139, 21136, 21140, -1, 21139, 21134, 21136, -1, 21141, 21137, 21134, -1, 21141, 21134, 21139, -1, 21122, 19283, 21123, -1, 19283, 19279, 21123, -1, 21123, 19274, 21124, -1, 19279, 19274, 21123, -1, 21124, 19268, 21125, -1, 19274, 19268, 21124, -1, 21125, 19270, 21119, -1, 19268, 19270, 21125, -1, 21119, 19272, 21120, -1, 19270, 19272, 21119, -1, 21120, 19276, 21121, -1, 19272, 19276, 21120, -1, 21121, 19117, 21110, -1, 19276, 19117, 21121, -1, 19503, 21122, 21134, -1, 19503, 19283, 21122, -1, 19084, 19525, 21135, -1, 21135, 19525, 21136, -1, 21136, 19525, 21140, -1, 21140, 19521, 21139, -1, 19525, 19521, 21140, -1, 21139, 19518, 21141, -1, 19521, 19518, 21139, -1, 21141, 19513, 21137, -1, 19518, 19513, 21141, -1, 21137, 19512, 21138, -1, 19513, 19512, 21137, -1, 21138, 19507, 21134, -1, 19512, 19507, 21138, -1, 19507, 19503, 21134, -1, 21133, 19084, 21135, -1, 19083, 19084, 21133, -1, 21142, 19882, 21143, -1, 19885, 19882, 21142, -1, 21144, 21145, 21146, -1, 21147, 21148, 21145, -1, 21146, 21149, 21150, -1, 21150, 21149, 21151, -1, 21145, 21149, 21146, -1, 21148, 21149, 21145, -1, 21152, 21153, 21154, -1, 21155, 21156, 21153, -1, 21153, 21156, 21154, -1, 21154, 21157, 21148, -1, 21158, 21157, 21156, -1, 21159, 21157, 21158, -1, 21148, 21157, 21149, -1, 21156, 21157, 21154, -1, 21160, 21161, 21162, -1, 21160, 21163, 21161, -1, 21163, 21143, 21164, -1, 21164, 21143, 21165, -1, 21165, 21143, 21166, -1, 21160, 21143, 21163, -1, 21143, 21167, 21142, -1, 21149, 21167, 21160, -1, 21157, 21167, 21149, -1, 21160, 21167, 21143, -1, 21167, 21168, 21142, -1, 21142, 21169, 21170, -1, 21142, 21171, 21169, -1, 21172, 21173, 21168, -1, 21168, 21173, 21142, -1, 21142, 21173, 21171, -1, 20172, 20187, 21167, -1, 21167, 20187, 21168, -1, 21168, 20192, 21172, -1, 20187, 20192, 21168, -1, 21172, 20196, 21173, -1, 20192, 20196, 21172, -1, 21173, 20198, 21171, -1, 20196, 20198, 21173, -1, 21171, 20200, 21169, -1, 20198, 20200, 21171, -1, 21169, 20202, 21170, -1, 20200, 20202, 21169, -1, 21170, 19885, 21142, -1, 20202, 19885, 21170, -1, 19956, 20172, 21167, -1, 19956, 21167, 21157, -1, 19841, 19897, 21154, -1, 21154, 19897, 21152, -1, 21152, 19872, 21153, -1, 19897, 19872, 21152, -1, 21153, 19852, 21155, -1, 19872, 19852, 21153, -1, 21155, 19865, 21156, -1, 19852, 19865, 21155, -1, 21156, 19889, 21158, -1, 19865, 19889, 21156, -1, 21158, 19914, 21159, -1, 19889, 19914, 21158, -1, 21159, 19956, 21157, -1, 19914, 19956, 21159, -1, 19840, 21154, 21148, -1, 19840, 19841, 21154, -1, 20045, 18907, 21174, -1, 21174, 21175, 21176, -1, 18907, 21175, 21174, -1, 21176, 21177, 21178, -1, 21175, 21177, 21176, -1, 21178, 21179, 21180, -1, 21177, 21179, 21178, -1, 21181, 21182, 21183, -1, 21183, 21184, 21181, -1, 21181, 21185, 21182, -1, 21184, 21186, 21181, -1, 21181, 21187, 21185, -1, 21186, 21188, 21181, -1, 21181, 21189, 21187, -1, 21181, 21190, 21189, -1, 21181, 21191, 21190, -1, 21181, 21192, 21191, -1, 21188, 21193, 21181, -1, 21193, 21194, 21181, -1, 21195, 21196, 21197, -1, 21195, 21198, 21196, -1, 21197, 21199, 21200, -1, 21196, 21199, 21197, -1, 21195, 21201, 21198, -1, 21202, 21203, 21204, -1, 21200, 21203, 21202, -1, 21199, 21203, 21200, -1, 21195, 21205, 21201, -1, 21204, 21206, 21194, -1, 21194, 21206, 21181, -1, 21203, 21206, 21204, -1, 21195, 21207, 21205, -1, 21195, 21208, 21207, -1, 21195, 21209, 21208, -1, 21195, 21210, 21209, -1, 21206, 21211, 21181, -1, 21212, 21213, 21214, -1, 21212, 21215, 21213, -1, 21214, 21216, 21217, -1, 21213, 21216, 21214, -1, 21212, 21218, 21215, -1, 21219, 21220, 21221, -1, 21217, 21220, 21219, -1, 21216, 21220, 21217, -1, 21212, 21222, 21218, -1, 21220, 21223, 21221, -1, 21221, 21223, 21224, -1, 21212, 21225, 21222, -1, 21212, 21226, 21225, -1, 21227, 21228, 21229, -1, 21227, 21230, 21228, -1, 21231, 21230, 21227, -1, 21228, 21232, 21229, -1, 21229, 21232, 21233, -1, 21231, 21234, 21230, -1, 21232, 21235, 21233, -1, 21233, 21235, 21236, -1, 21231, 21237, 21234, -1, 21238, 21237, 21231, -1, 21238, 21239, 21237, -1, 21238, 21240, 21239, -1, 21241, 21242, 21235, -1, 21224, 21242, 21211, -1, 21223, 21242, 21224, -1, 21235, 21242, 21236, -1, 21243, 21242, 21223, -1, 21236, 21242, 21244, -1, 21244, 21242, 21245, -1, 21245, 21242, 21243, -1, 21211, 21242, 21181, -1, 21241, 21246, 21242, -1, 21246, 21247, 21242, -1, 21247, 21248, 21242, -1, 21248, 21249, 21242, -1, 21249, 21250, 21242, -1, 21250, 21251, 21242, -1, 21242, 21252, 21253, -1, 21251, 21252, 21242, -1, 21212, 21254, 21226, -1, 21253, 21255, 21179, -1, 21252, 21255, 21253, -1, 21256, 21257, 21254, -1, 21254, 21258, 21226, -1, 21257, 21259, 21254, -1, 21254, 21260, 21258, -1, 21259, 21260, 21254, -1, 21259, 21261, 21260, -1, 21262, 21263, 21259, -1, 21255, 21264, 21179, -1, 21259, 21265, 21261, -1, 21263, 21266, 21259, -1, 21259, 21267, 21265, -1, 21266, 21268, 21259, -1, 21259, 21268, 21267, -1, 21269, 21270, 21271, -1, 21271, 21270, 21272, -1, 21272, 21270, 21273, -1, 21273, 21270, 21274, -1, 21274, 21270, 21275, -1, 21276, 21277, 21278, -1, 21278, 21277, 21279, -1, 21279, 21277, 21280, -1, 21280, 21277, 21281, -1, 21282, 21277, 21270, -1, 21270, 21277, 21275, -1, 21275, 21277, 21283, -1, 21283, 21277, 21276, -1, 21284, 21285, 21286, -1, 21277, 21287, 21288, -1, 21286, 21289, 21282, -1, 21285, 21289, 21286, -1, 21277, 21290, 21287, -1, 21290, 21291, 21292, -1, 21293, 21291, 21289, -1, 21282, 21291, 21277, -1, 21289, 21291, 21282, -1, 21277, 21291, 21290, -1, 21294, 21295, 21296, -1, 21296, 21295, 21297, -1, 21297, 21295, 21298, -1, 21298, 21295, 21299, -1, 21299, 21295, 21300, -1, 21300, 21295, 21301, -1, 21301, 21295, 21302, -1, 21302, 21303, 21304, -1, 21295, 21303, 21302, -1, 21304, 21180, 21305, -1, 21305, 21180, 21306, -1, 21306, 21180, 21307, -1, 21303, 21180, 21304, -1, 21195, 21270, 21269, -1, 21195, 21269, 21210, -1, 21277, 21240, 21238, -1, 21277, 21238, 21281, -1, 21264, 21307, 21179, -1, 21180, 21179, 21307, -1, 21181, 21295, 21294, -1, 21181, 21294, 21192, -1, 21308, 21277, 21288, -1, 21309, 21288, 21287, -1, 21309, 21308, 21288, -1, 21310, 21287, 21290, -1, 21310, 21309, 21287, -1, 21311, 21290, 21292, -1, 21311, 21310, 21290, -1, 21312, 21292, 21291, -1, 21312, 21311, 21292, -1, 21313, 21291, 21293, -1, 21313, 21312, 21291, -1, 21314, 21293, 21289, -1, 21314, 21313, 21293, -1, 21315, 21289, 21285, -1, 21315, 21314, 21289, -1, 21316, 21285, 21284, -1, 21316, 21315, 21285, -1, 21317, 21316, 21284, -1, 21318, 21202, 21319, -1, 21319, 21204, 21320, -1, 21202, 21204, 21319, -1, 21204, 21194, 21320, -1, 21320, 21193, 21321, -1, 21194, 21193, 21320, -1, 21322, 21249, 21323, -1, 21323, 21248, 21324, -1, 21249, 21248, 21323, -1, 21248, 21247, 21324, -1, 21324, 21246, 21325, -1, 21247, 21246, 21324, -1, 21326, 21258, 21260, -1, 21327, 21260, 21261, -1, 21327, 21326, 21260, -1, 21328, 21327, 21261, -1, 21329, 21261, 21265, -1, 21329, 21328, 21261, -1, 21330, 21265, 21267, -1, 21330, 21329, 21265, -1, 21331, 21267, 21268, -1, 21331, 21330, 21267, -1, 21332, 21268, 21266, -1, 21332, 21331, 21268, -1, 21333, 21266, 21263, -1, 21333, 21332, 21266, -1, 21334, 21263, 21262, -1, 21334, 21333, 21263, -1, 21335, 21262, 21259, -1, 21335, 21334, 21262, -1, 21219, 21221, 21336, -1, 21336, 21221, 21337, -1, 21337, 21224, 21338, -1, 21338, 21224, 21339, -1, 21221, 21224, 21337, -1, 21224, 21211, 21339, -1, 21236, 21244, 21340, -1, 21340, 21244, 21341, -1, 21341, 21245, 21342, -1, 21342, 21245, 21343, -1, 21244, 21245, 21341, -1, 21245, 21243, 21343, -1, 21331, 21332, 21344, -1, 21333, 21344, 21332, -1, 21330, 21331, 21344, -1, 21334, 21344, 21333, -1, 21329, 21330, 21344, -1, 21335, 21344, 21334, -1, 21328, 21329, 21344, -1, 21345, 21344, 21335, -1, 21327, 21328, 21344, -1, 21346, 21344, 21345, -1, 21347, 21344, 21346, -1, 21348, 21326, 21327, -1, 21348, 21327, 21344, -1, 21349, 21350, 21351, -1, 21341, 21352, 21350, -1, 21341, 21349, 21340, -1, 21341, 21350, 21349, -1, 21342, 21348, 21352, -1, 21342, 21352, 21341, -1, 21343, 21348, 21342, -1, 21353, 21326, 21348, -1, 21353, 21348, 21343, -1, 21337, 21354, 21336, -1, 21339, 21355, 21356, -1, 21339, 21356, 21354, -1, 21339, 21337, 21338, -1, 21339, 21354, 21337, -1, 21357, 21347, 21355, -1, 21357, 21355, 21339, -1, 21357, 21344, 21347, -1, 21313, 21314, 21358, -1, 21315, 21358, 21314, -1, 21312, 21313, 21358, -1, 21316, 21358, 21315, -1, 21311, 21312, 21358, -1, 21317, 21358, 21316, -1, 21310, 21311, 21358, -1, 21359, 21358, 21317, -1, 21309, 21310, 21358, -1, 21360, 21358, 21359, -1, 21308, 21309, 21358, -1, 21361, 21358, 21360, -1, 21362, 21363, 21364, -1, 21365, 21363, 21362, -1, 21322, 21365, 21366, -1, 21322, 21363, 21365, -1, 21324, 21322, 21323, -1, 21325, 21322, 21324, -1, 21325, 21363, 21322, -1, 21367, 21363, 21325, -1, 21368, 21369, 21370, -1, 21318, 21369, 21368, -1, 21321, 21318, 21319, -1, 21321, 21319, 21320, -1, 21321, 21369, 21318, -1, 21371, 21361, 21369, -1, 21371, 21369, 21321, -1, 21367, 21308, 21363, -1, 21371, 21358, 21361, -1, 21358, 21363, 21308, -1, 21210, 21344, 21357, -1, 21210, 21269, 21344, -1, 21372, 21373, 21344, -1, 21373, 21374, 21344, -1, 21271, 21375, 21269, -1, 21272, 21375, 21271, -1, 21273, 21375, 21272, -1, 21269, 21375, 21344, -1, 21344, 21375, 21372, -1, 21374, 21376, 21344, -1, 21274, 21377, 21273, -1, 21275, 21377, 21274, -1, 21375, 21377, 21372, -1, 21372, 21377, 21373, -1, 21273, 21377, 21375, -1, 21344, 21378, 21281, -1, 21376, 21378, 21344, -1, 21283, 21379, 21275, -1, 21275, 21379, 21377, -1, 21377, 21379, 21373, -1, 21373, 21379, 21374, -1, 21276, 21380, 21283, -1, 21278, 21380, 21276, -1, 21283, 21380, 21379, -1, 21374, 21380, 21376, -1, 21379, 21380, 21374, -1, 21279, 21381, 21278, -1, 21280, 21381, 21279, -1, 21281, 21381, 21280, -1, 21278, 21381, 21380, -1, 21378, 21381, 21281, -1, 21376, 21381, 21378, -1, 21380, 21381, 21376, -1, 21382, 21383, 21357, -1, 21383, 21384, 21357, -1, 21206, 21385, 21357, -1, 21203, 21385, 21206, -1, 21199, 21385, 21203, -1, 21196, 21385, 21199, -1, 21357, 21385, 21382, -1, 21384, 21386, 21357, -1, 21198, 21387, 21196, -1, 21201, 21387, 21198, -1, 21382, 21387, 21383, -1, 21196, 21387, 21385, -1, 21385, 21387, 21382, -1, 21205, 21388, 21201, -1, 21207, 21388, 21205, -1, 21387, 21388, 21383, -1, 21383, 21388, 21384, -1, 21201, 21388, 21387, -1, 21357, 21389, 21210, -1, 21208, 21389, 21207, -1, 21209, 21389, 21208, -1, 21210, 21389, 21209, -1, 21384, 21389, 21386, -1, 21386, 21389, 21357, -1, 21207, 21389, 21388, -1, 21388, 21389, 21384, -1, 21281, 21238, 21344, -1, 21344, 21238, 21348, -1, 21339, 21206, 21357, -1, 21211, 21206, 21339, -1, 21238, 21231, 21348, -1, 21348, 21231, 21352, -1, 21352, 21231, 21350, -1, 21350, 21227, 21351, -1, 21231, 21227, 21350, -1, 21227, 21229, 21351, -1, 21351, 21233, 21349, -1, 21229, 21233, 21351, -1, 21349, 21236, 21340, -1, 21233, 21236, 21349, -1, 21212, 21214, 21355, -1, 21355, 21214, 21356, -1, 21356, 21214, 21354, -1, 21354, 21217, 21336, -1, 21214, 21217, 21354, -1, 21217, 21219, 21336, -1, 21243, 21223, 21343, -1, 21343, 21223, 21353, -1, 21347, 21212, 21355, -1, 21254, 21212, 21347, -1, 21223, 21390, 21353, -1, 21390, 21391, 21353, -1, 21220, 21392, 21223, -1, 21216, 21392, 21220, -1, 21213, 21392, 21216, -1, 21223, 21392, 21390, -1, 21391, 21393, 21353, -1, 21215, 21394, 21213, -1, 21218, 21394, 21215, -1, 21392, 21394, 21390, -1, 21213, 21394, 21392, -1, 21390, 21394, 21391, -1, 21353, 21395, 21226, -1, 21222, 21395, 21218, -1, 21225, 21395, 21222, -1, 21226, 21395, 21225, -1, 21394, 21395, 21391, -1, 21393, 21395, 21353, -1, 21218, 21395, 21394, -1, 21391, 21395, 21393, -1, 21335, 21259, 21257, -1, 21345, 21257, 21256, -1, 21345, 21335, 21257, -1, 21346, 21256, 21254, -1, 21346, 21345, 21256, -1, 21347, 21346, 21254, -1, 21226, 21326, 21353, -1, 21226, 21258, 21326, -1, 21192, 21358, 21371, -1, 21192, 21294, 21358, -1, 21396, 21397, 21358, -1, 21397, 21398, 21358, -1, 21296, 21399, 21294, -1, 21297, 21399, 21296, -1, 21298, 21399, 21297, -1, 21294, 21399, 21358, -1, 21358, 21399, 21396, -1, 21398, 21400, 21358, -1, 21299, 21401, 21298, -1, 21300, 21401, 21299, -1, 21399, 21401, 21396, -1, 21396, 21401, 21397, -1, 21298, 21401, 21399, -1, 21400, 21402, 21358, -1, 21301, 21403, 21300, -1, 21401, 21403, 21397, -1, 21397, 21403, 21398, -1, 21300, 21403, 21401, -1, 21302, 21404, 21301, -1, 21304, 21404, 21302, -1, 21301, 21404, 21403, -1, 21398, 21404, 21400, -1, 21403, 21404, 21398, -1, 21358, 21405, 21307, -1, 21305, 21405, 21304, -1, 21306, 21405, 21305, -1, 21307, 21405, 21306, -1, 21402, 21405, 21358, -1, 21304, 21405, 21404, -1, 21400, 21405, 21402, -1, 21404, 21405, 21400, -1, 21188, 21406, 21371, -1, 21406, 21407, 21371, -1, 21407, 21408, 21371, -1, 21186, 21409, 21188, -1, 21184, 21409, 21186, -1, 21183, 21409, 21184, -1, 21188, 21409, 21406, -1, 21371, 21410, 21192, -1, 21408, 21410, 21371, -1, 21182, 21411, 21183, -1, 21185, 21411, 21182, -1, 21406, 21411, 21407, -1, 21183, 21411, 21409, -1, 21409, 21411, 21406, -1, 21187, 21412, 21185, -1, 21189, 21412, 21187, -1, 21411, 21412, 21407, -1, 21407, 21412, 21408, -1, 21185, 21412, 21411, -1, 21190, 21413, 21189, -1, 21191, 21413, 21190, -1, 21192, 21413, 21191, -1, 21408, 21413, 21410, -1, 21189, 21413, 21412, -1, 21410, 21413, 21192, -1, 21412, 21413, 21408, -1, 21307, 21264, 21358, -1, 21358, 21264, 21363, -1, 21321, 21188, 21371, -1, 21193, 21188, 21321, -1, 21363, 21264, 21364, -1, 21264, 21255, 21364, -1, 21364, 21252, 21362, -1, 21255, 21252, 21364, -1, 21362, 21251, 21365, -1, 21252, 21251, 21362, -1, 21365, 21250, 21366, -1, 21251, 21250, 21365, -1, 21366, 21249, 21322, -1, 21250, 21249, 21366, -1, 21369, 21195, 21370, -1, 21195, 21197, 21370, -1, 21370, 21200, 21368, -1, 21368, 21200, 21318, -1, 21197, 21200, 21370, -1, 21200, 21202, 21318, -1, 21246, 21241, 21325, -1, 21325, 21241, 21367, -1, 21361, 21195, 21369, -1, 21270, 21195, 21361, -1, 21414, 21415, 21367, -1, 21235, 21416, 21241, -1, 21232, 21416, 21235, -1, 21228, 21416, 21232, -1, 21241, 21416, 21367, -1, 21367, 21416, 21414, -1, 21415, 21417, 21367, -1, 21230, 21418, 21228, -1, 21234, 21418, 21230, -1, 21416, 21418, 21414, -1, 21228, 21418, 21416, -1, 21414, 21418, 21415, -1, 21367, 21419, 21240, -1, 21237, 21419, 21234, -1, 21239, 21419, 21237, -1, 21240, 21419, 21239, -1, 21418, 21419, 21415, -1, 21234, 21419, 21418, -1, 21417, 21419, 21367, -1, 21415, 21419, 21417, -1, 21359, 21317, 21284, -1, 21359, 21284, 21286, -1, 21359, 21286, 21282, -1, 21360, 21282, 21270, -1, 21360, 21359, 21282, -1, 21361, 21360, 21270, -1, 21240, 21277, 21367, -1, 21367, 21277, 21308, -1, 21295, 21181, 21420, -1, 21421, 21422, 21423, -1, 21420, 21422, 21421, -1, 21181, 21422, 21420, -1, 21423, 21424, 21425, -1, 21422, 21424, 21423, -1, 21425, 21426, 21427, -1, 21424, 21426, 21425, -1, 21426, 21428, 21427, -1, 21427, 21429, 21430, -1, 21428, 21429, 21427, -1, 21429, 18899, 21430, -1, 18899, 18898, 21430, -1, 21431, 21432, 21433, -1, 21433, 21432, 21434, -1, 21434, 21432, 21435, -1, 21435, 21432, 21436, -1, 21436, 21432, 21437, -1, 21438, 21439, 21440, -1, 21441, 21432, 21431, -1, 21442, 21432, 21441, -1, 21440, 21443, 21438, -1, 21437, 21430, 21444, -1, 21444, 21430, 21445, -1, 21439, 21446, 21440, -1, 21432, 21430, 21437, -1, 21430, 18898, 21447, -1, 21430, 21447, 21445, -1, 21440, 21448, 21449, -1, 21440, 21449, 21450, -1, 21440, 21451, 21443, -1, 21446, 21452, 21440, -1, 21440, 21450, 21451, -1, 21452, 21453, 21440, -1, 21453, 21454, 21440, -1, 21455, 18898, 21454, -1, 21454, 18898, 21440, -1, 21455, 21456, 18898, -1, 21456, 21457, 18898, -1, 21457, 21458, 18898, -1, 21458, 21459, 18898, -1, 21459, 21460, 18898, -1, 21460, 21447, 18898, -1, 21449, 21448, 21461, -1, 21461, 21448, 21462, -1, 21462, 21442, 21463, -1, 21463, 21442, 21464, -1, 21464, 21442, 21465, -1, 21448, 21442, 21462, -1, 21442, 21466, 21465, -1, 21442, 21441, 21466, -1, 21450, 21449, 21467, -1, 21450, 21467, 21468, -1, 21469, 21470, 21471, -1, 21472, 21470, 21469, -1, 21473, 21470, 21472, -1, 21474, 21475, 21476, -1, 21471, 21475, 21474, -1, 21470, 21475, 21471, -1, 21470, 21477, 21475, -1, 21478, 21479, 21477, -1, 21479, 21480, 21477, -1, 21480, 21481, 21477, -1, 21481, 21482, 21477, -1, 21482, 21483, 21477, -1, 21477, 21468, 21475, -1, 21483, 21468, 21477, -1, 21468, 21484, 21475, -1, 21484, 21485, 21486, -1, 21484, 21487, 21485, -1, 21487, 21488, 21489, -1, 21484, 21488, 21487, -1, 21488, 21490, 21491, -1, 21484, 21490, 21488, -1, 21468, 21467, 21484, -1, 21484, 21467, 21490, -1, 21467, 21492, 21490, -1, 21467, 21493, 21492, -1, 21493, 21494, 21492, -1, 21495, 21496, 21493, -1, 21497, 21496, 21495, -1, 21494, 21496, 21498, -1, 21493, 21496, 21494, -1, 21467, 21461, 21493, -1, 21493, 21461, 21495, -1, 21449, 21461, 21467, -1, 21495, 21462, 21497, -1, 21461, 21462, 21495, -1, 21497, 21463, 21496, -1, 21462, 21463, 21497, -1, 21496, 21464, 21498, -1, 21463, 21464, 21496, -1, 21498, 21465, 21494, -1, 21464, 21465, 21498, -1, 21494, 21466, 21492, -1, 21465, 21466, 21494, -1, 21466, 21441, 21492, -1, 21453, 21452, 21477, -1, 21477, 21452, 21478, -1, 21478, 21452, 21479, -1, 21479, 21446, 21480, -1, 21452, 21446, 21479, -1, 21480, 21439, 21481, -1, 21446, 21439, 21480, -1, 21481, 21438, 21482, -1, 21439, 21438, 21481, -1, 21482, 21443, 21483, -1, 21438, 21443, 21482, -1, 21483, 21451, 21468, -1, 21443, 21451, 21483, -1, 21451, 21450, 21468, -1, 21441, 21431, 21490, -1, 21441, 21490, 21492, -1, 21454, 21453, 21477, -1, 21454, 21477, 21470, -1, 21490, 21433, 21491, -1, 21431, 21433, 21490, -1, 21491, 21434, 21488, -1, 21433, 21434, 21491, -1, 21488, 21435, 21489, -1, 21434, 21435, 21488, -1, 21489, 21436, 21487, -1, 21487, 21436, 21485, -1, 21435, 21436, 21489, -1, 21485, 21437, 21486, -1, 21436, 21437, 21485, -1, 21437, 21444, 21486, -1, 21486, 21445, 21484, -1, 21444, 21445, 21486, -1, 21475, 21447, 21476, -1, 21447, 21460, 21476, -1, 21476, 21459, 21474, -1, 21460, 21459, 21476, -1, 21474, 21458, 21471, -1, 21459, 21458, 21474, -1, 21471, 21457, 21469, -1, 21458, 21457, 21471, -1, 21469, 21456, 21472, -1, 21457, 21456, 21469, -1, 21472, 21455, 21473, -1, 21456, 21455, 21472, -1, 21473, 21454, 21470, -1, 21455, 21454, 21473, -1, 21445, 21447, 21475, -1, 21445, 21475, 21484, -1, 21499, 21500, 21501, -1, 21501, 21502, 21503, -1, 21500, 21502, 21501, -1, 21503, 21504, 21505, -1, 21502, 21504, 21503, -1, 21505, 18918, 21506, -1, 21506, 18918, 19049, -1, 21504, 18918, 21505, -1, 21507, 21508, 21509, -1, 21510, 21508, 21511, -1, 21511, 21508, 21512, -1, 21512, 21508, 21513, -1, 21514, 21515, 21516, -1, 21509, 21508, 21517, -1, 21517, 21508, 21518, -1, 21518, 21508, 21519, -1, 21519, 21508, 21520, -1, 21520, 21508, 21521, -1, 21500, 21522, 21514, -1, 21521, 21508, 21510, -1, 21523, 21524, 21525, -1, 21526, 21524, 21523, -1, 21514, 21522, 21515, -1, 21527, 21524, 21528, -1, 21528, 21524, 21529, -1, 21515, 21530, 21516, -1, 21529, 21524, 21531, -1, 21531, 21524, 21532, -1, 21532, 21524, 21533, -1, 21533, 21524, 21534, -1, 21500, 21535, 21522, -1, 21534, 21524, 21536, -1, 21536, 21524, 21537, -1, 21537, 21524, 21538, -1, 21538, 21524, 21526, -1, 21525, 21524, 21516, -1, 21539, 21540, 21541, -1, 21530, 21542, 21516, -1, 21543, 21544, 21545, -1, 21543, 21545, 21546, -1, 21542, 21547, 21516, -1, 21548, 21535, 21500, -1, 21541, 21549, 21539, -1, 21500, 21499, 21548, -1, 21508, 21524, 21527, -1, 21508, 21527, 21513, -1, 21547, 21550, 21516, -1, 21550, 21551, 21516, -1, 21552, 21553, 21554, -1, 21555, 21556, 21552, -1, 21552, 21556, 21553, -1, 21554, 21557, 21558, -1, 21558, 21557, 21551, -1, 21553, 21557, 21554, -1, 21555, 21549, 21556, -1, 21539, 21549, 21559, -1, 21559, 21549, 21560, -1, 21560, 21549, 21555, -1, 21551, 21561, 21516, -1, 21557, 21561, 21551, -1, 21561, 21562, 21516, -1, 21562, 21563, 21516, -1, 21564, 21565, 21566, -1, 21565, 21567, 21566, -1, 21568, 21567, 21569, -1, 21570, 21567, 21571, -1, 21571, 21567, 21572, -1, 21572, 21567, 21573, -1, 21573, 21567, 21574, -1, 21574, 21567, 21565, -1, 21566, 21567, 21575, -1, 21575, 21567, 21576, -1, 21576, 21567, 21568, -1, 21567, 21577, 21569, -1, 21569, 21577, 21578, -1, 21578, 21577, 21579, -1, 21579, 21577, 21580, -1, 21580, 21577, 21581, -1, 21581, 21577, 21582, -1, 21577, 21583, 21582, -1, 21582, 21583, 21584, -1, 21583, 21585, 21584, -1, 21584, 21585, 21586, -1, 21585, 21587, 21586, -1, 21586, 21587, 21563, -1, 21587, 21588, 21563, -1, 21563, 21588, 21516, -1, 21588, 21525, 21516, -1, 21541, 21540, 21589, -1, 21589, 21540, 21590, -1, 21590, 21540, 21591, -1, 21591, 21540, 21592, -1, 21592, 21540, 21593, -1, 21593, 21540, 21594, -1, 21595, 21596, 21540, -1, 21596, 21597, 21540, -1, 21598, 21599, 21597, -1, 21597, 21600, 21540, -1, 21599, 21600, 21597, -1, 21601, 21602, 21600, -1, 21603, 21543, 21604, -1, 21604, 21543, 21602, -1, 21605, 21543, 21606, -1, 21606, 21543, 21607, -1, 21607, 21543, 21546, -1, 21594, 21543, 21608, -1, 21608, 21543, 21609, -1, 21609, 21543, 21605, -1, 21540, 21543, 21594, -1, 21602, 21543, 21600, -1, 21600, 21543, 21540, -1, 21545, 21544, 21610, -1, 21610, 21544, 21611, -1, 21611, 21544, 21612, -1, 21612, 21544, 21613, -1, 21613, 21544, 21614, -1, 21614, 21544, 21615, -1, 21615, 21544, 21616, -1, 21616, 21617, 21618, -1, 21544, 21617, 21616, -1, 21617, 21619, 21618, -1, 21618, 21619, 21620, -1, 21620, 21621, 21525, -1, 21619, 21621, 21620, -1, 21621, 21523, 21525, -1, 21548, 21499, 21622, -1, 21622, 21499, 21623, -1, 21623, 21499, 21509, -1, 21499, 21507, 21509, -1, 21510, 21511, 21624, -1, 21511, 21512, 21624, -1, 21512, 21513, 21624, -1, 21605, 21606, 21625, -1, 21606, 21607, 21625, -1, 21607, 21546, 21625, -1, 21577, 21626, 21627, -1, 21577, 21567, 21626, -1, 21628, 21629, 21630, -1, 21631, 21632, 21633, -1, 21631, 21633, 21628, -1, 21631, 21628, 21630, -1, 21634, 21631, 21630, -1, 21635, 21634, 21630, -1, 21636, 21635, 21630, -1, 21625, 21637, 21638, -1, 21625, 21638, 21636, -1, 21625, 21636, 21630, -1, 21639, 21637, 21625, -1, 21640, 21639, 21625, -1, 21641, 21640, 21625, -1, 21642, 21641, 21625, -1, 21643, 21642, 21625, -1, 21644, 21643, 21625, -1, 21645, 21644, 21625, -1, 21626, 21645, 21625, -1, 21646, 21647, 21648, -1, 21646, 21648, 21649, -1, 21646, 21649, 21627, -1, 21650, 21627, 21626, -1, 21650, 21646, 21627, -1, 21625, 21650, 21626, -1, 21626, 21567, 21570, -1, 21645, 21570, 21571, -1, 21645, 21626, 21570, -1, 21644, 21571, 21572, -1, 21644, 21645, 21571, -1, 21643, 21572, 21573, -1, 21643, 21644, 21572, -1, 21642, 21573, 21574, -1, 21642, 21643, 21573, -1, 21641, 21574, 21565, -1, 21641, 21642, 21574, -1, 21640, 21565, 21564, -1, 21640, 21641, 21565, -1, 21639, 21564, 21566, -1, 21639, 21640, 21564, -1, 21637, 21566, 21575, -1, 21637, 21639, 21566, -1, 21638, 21575, 21576, -1, 21638, 21637, 21575, -1, 21636, 21576, 21568, -1, 21636, 21638, 21576, -1, 21635, 21636, 21568, -1, 21646, 21588, 21647, -1, 21647, 21587, 21648, -1, 21588, 21587, 21647, -1, 21648, 21585, 21649, -1, 21587, 21585, 21648, -1, 21585, 21583, 21649, -1, 21649, 21577, 21627, -1, 21583, 21577, 21649, -1, 21568, 21569, 21635, -1, 21635, 21569, 21634, -1, 21525, 21646, 21650, -1, 21525, 21588, 21646, -1, 21569, 21651, 21634, -1, 21651, 21652, 21634, -1, 21578, 21653, 21569, -1, 21579, 21653, 21578, -1, 21580, 21653, 21579, -1, 21569, 21653, 21651, -1, 21634, 21654, 21563, -1, 21652, 21654, 21634, -1, 21581, 21655, 21580, -1, 21582, 21655, 21581, -1, 21580, 21655, 21653, -1, 21651, 21655, 21652, -1, 21653, 21655, 21651, -1, 21584, 21656, 21582, -1, 21586, 21656, 21584, -1, 21563, 21656, 21586, -1, 21582, 21656, 21655, -1, 21652, 21656, 21654, -1, 21655, 21656, 21652, -1, 21654, 21656, 21563, -1, 21545, 21657, 21650, -1, 21657, 21658, 21650, -1, 21610, 21659, 21545, -1, 21611, 21659, 21610, -1, 21612, 21659, 21611, -1, 21545, 21659, 21657, -1, 21658, 21660, 21650, -1, 21613, 21661, 21612, -1, 21614, 21661, 21613, -1, 21612, 21661, 21659, -1, 21657, 21661, 21658, -1, 21659, 21661, 21657, -1, 21650, 21662, 21525, -1, 21660, 21662, 21650, -1, 21615, 21663, 21614, -1, 21616, 21663, 21615, -1, 21614, 21663, 21661, -1, 21658, 21663, 21660, -1, 21661, 21663, 21658, -1, 21618, 21664, 21616, -1, 21620, 21664, 21618, -1, 21525, 21664, 21620, -1, 21616, 21664, 21663, -1, 21660, 21664, 21662, -1, 21662, 21664, 21525, -1, 21663, 21664, 21660, -1, 21563, 21631, 21634, -1, 21563, 21562, 21631, -1, 21546, 21650, 21625, -1, 21546, 21545, 21650, -1, 21631, 21561, 21632, -1, 21562, 21561, 21631, -1, 21632, 21557, 21633, -1, 21561, 21557, 21632, -1, 21633, 21553, 21628, -1, 21557, 21553, 21633, -1, 21628, 21556, 21629, -1, 21553, 21556, 21628, -1, 21629, 21549, 21630, -1, 21556, 21549, 21629, -1, 21665, 21666, 21625, -1, 21666, 21667, 21625, -1, 21589, 21668, 21541, -1, 21590, 21668, 21589, -1, 21591, 21668, 21590, -1, 21541, 21668, 21625, -1, 21625, 21668, 21665, -1, 21625, 21669, 21605, -1, 21667, 21669, 21625, -1, 21592, 21670, 21591, -1, 21668, 21670, 21665, -1, 21665, 21670, 21666, -1, 21591, 21670, 21668, -1, 21593, 21671, 21592, -1, 21594, 21671, 21593, -1, 21592, 21671, 21670, -1, 21670, 21671, 21666, -1, 21666, 21671, 21667, -1, 21608, 21672, 21594, -1, 21609, 21672, 21608, -1, 21605, 21672, 21609, -1, 21594, 21672, 21671, -1, 21667, 21672, 21669, -1, 21669, 21672, 21605, -1, 21671, 21672, 21667, -1, 21549, 21625, 21630, -1, 21549, 21541, 21625, -1, 21535, 21624, 21673, -1, 21535, 21548, 21624, -1, 21674, 21675, 21676, -1, 21674, 21676, 21677, -1, 21674, 21677, 21678, -1, 21674, 21678, 21673, -1, 21679, 21674, 21673, -1, 21624, 21680, 21681, -1, 21624, 21681, 21682, -1, 21683, 21680, 21624, -1, 21684, 21683, 21624, -1, 21685, 21684, 21624, -1, 21686, 21685, 21624, -1, 21687, 21686, 21624, -1, 21688, 21687, 21624, -1, 21689, 21688, 21624, -1, 21690, 21689, 21624, -1, 21691, 21690, 21624, -1, 21692, 21693, 21694, -1, 21692, 21694, 21695, -1, 21696, 21692, 21695, -1, 21697, 21695, 21691, -1, 21697, 21696, 21695, -1, 21682, 21679, 21673, -1, 21673, 21624, 21682, -1, 21624, 21697, 21691, -1, 21698, 21699, 21624, -1, 21699, 21700, 21624, -1, 21622, 21701, 21548, -1, 21623, 21701, 21622, -1, 21509, 21701, 21623, -1, 21548, 21701, 21624, -1, 21624, 21701, 21698, -1, 21624, 21702, 21510, -1, 21700, 21702, 21624, -1, 21517, 21703, 21509, -1, 21701, 21703, 21698, -1, 21698, 21703, 21699, -1, 21509, 21703, 21701, -1, 21518, 21704, 21517, -1, 21519, 21704, 21518, -1, 21517, 21704, 21703, -1, 21703, 21704, 21699, -1, 21699, 21704, 21700, -1, 21520, 21705, 21519, -1, 21521, 21705, 21520, -1, 21510, 21705, 21521, -1, 21519, 21705, 21704, -1, 21700, 21705, 21702, -1, 21702, 21705, 21510, -1, 21704, 21705, 21700, -1, 21674, 21547, 21675, -1, 21675, 21542, 21676, -1, 21547, 21542, 21675, -1, 21676, 21530, 21677, -1, 21542, 21530, 21676, -1, 21677, 21515, 21678, -1, 21530, 21515, 21677, -1, 21678, 21522, 21673, -1, 21515, 21522, 21678, -1, 21522, 21535, 21673, -1, 21513, 21527, 21624, -1, 21624, 21527, 21697, -1, 21679, 21547, 21674, -1, 21550, 21547, 21679, -1, 21527, 21706, 21697, -1, 21706, 21707, 21697, -1, 21528, 21708, 21527, -1, 21529, 21708, 21528, -1, 21531, 21708, 21529, -1, 21527, 21708, 21706, -1, 21707, 21709, 21697, -1, 21532, 21710, 21531, -1, 21533, 21710, 21532, -1, 21531, 21710, 21708, -1, 21706, 21710, 21707, -1, 21708, 21710, 21706, -1, 21697, 21711, 21526, -1, 21709, 21711, 21697, -1, 21534, 21712, 21533, -1, 21536, 21712, 21534, -1, 21710, 21712, 21707, -1, 21707, 21712, 21709, -1, 21533, 21712, 21710, -1, 21537, 21713, 21536, -1, 21538, 21713, 21537, -1, 21526, 21713, 21538, -1, 21536, 21713, 21712, -1, 21709, 21713, 21711, -1, 21711, 21713, 21526, -1, 21712, 21713, 21709, -1, 21714, 21715, 21679, -1, 21539, 21716, 21679, -1, 21559, 21716, 21539, -1, 21560, 21716, 21559, -1, 21555, 21716, 21560, -1, 21679, 21716, 21714, -1, 21679, 21717, 21550, -1, 21715, 21717, 21679, -1, 21552, 21718, 21555, -1, 21554, 21718, 21552, -1, 21555, 21718, 21716, -1, 21714, 21718, 21715, -1, 21716, 21718, 21714, -1, 21558, 21719, 21554, -1, 21551, 21719, 21558, -1, 21550, 21719, 21551, -1, 21554, 21719, 21718, -1, 21715, 21719, 21717, -1, 21717, 21719, 21550, -1, 21718, 21719, 21715, -1, 21526, 21696, 21697, -1, 21526, 21523, 21696, -1, 21682, 21539, 21679, -1, 21540, 21539, 21682, -1, 21696, 21621, 21692, -1, 21523, 21621, 21696, -1, 21692, 21619, 21693, -1, 21621, 21619, 21692, -1, 21693, 21617, 21694, -1, 21619, 21617, 21693, -1, 21694, 21544, 21695, -1, 21617, 21544, 21694, -1, 21690, 21691, 21543, -1, 21690, 21543, 21603, -1, 21689, 21603, 21604, -1, 21689, 21690, 21603, -1, 21688, 21604, 21602, -1, 21688, 21689, 21604, -1, 21687, 21602, 21601, -1, 21687, 21688, 21602, -1, 21686, 21601, 21600, -1, 21686, 21687, 21601, -1, 21685, 21600, 21599, -1, 21685, 21686, 21600, -1, 21684, 21599, 21598, -1, 21684, 21685, 21599, -1, 21683, 21598, 21597, -1, 21683, 21684, 21598, -1, 21680, 21597, 21596, -1, 21680, 21683, 21597, -1, 21681, 21596, 21595, -1, 21681, 21595, 21540, -1, 21681, 21680, 21596, -1, 21682, 21681, 21540, -1, 21544, 21543, 21695, -1, 21695, 21543, 21691, -1, 21440, 21720, 21448, -1, 21448, 21720, 21721, -1, 21721, 21722, 21723, -1, 21720, 21722, 21721, -1, 21722, 21724, 21723, -1, 21723, 21725, 21726, -1, 21724, 21725, 21723, -1, 21726, 21727, 21728, -1, 21725, 21727, 21726, -1, 21728, 21729, 21508, -1, 21727, 21729, 21728, -1, 21729, 21524, 21508, -1, 18919, 18918, 21504, -1, 21730, 21502, 21500, -1, 21731, 18919, 21502, -1, 21731, 21502, 21730, -1, 18920, 18919, 21731, -1, 21732, 21504, 21502, -1, 21732, 21502, 18919, -1, 21732, 18919, 21504, -1, 18920, 21733, 18877, -1, 21731, 21734, 21733, -1, 21731, 21733, 18920, -1, 21514, 21735, 21736, -1, 21514, 21516, 21735, -1, 21730, 21736, 21734, -1, 21730, 21514, 21736, -1, 21730, 21734, 21731, -1, 21500, 21514, 21730, -1, 21735, 21516, 21524, -1, 21735, 21524, 21737, -1, 21736, 21737, 21738, -1, 21736, 21735, 21737, -1, 21734, 21738, 21739, -1, 21734, 21736, 21738, -1, 21733, 21739, 21740, -1, 21733, 21734, 21739, -1, 18877, 21740, 18874, -1, 18877, 21733, 21740, -1, 21729, 21738, 21737, -1, 21729, 21737, 21524, -1, 21739, 21738, 21729, -1, 18896, 18874, 21740, -1, 21741, 21720, 21440, -1, 18892, 18893, 21742, -1, 21743, 21729, 21727, -1, 21744, 21729, 21743, -1, 21744, 21739, 21729, -1, 21744, 21743, 21727, -1, 21745, 21740, 21739, -1, 21745, 21739, 21744, -1, 21745, 18896, 21740, -1, 21746, 21725, 21724, -1, 21746, 21727, 21725, -1, 21747, 21744, 21727, -1, 21747, 21727, 21746, -1, 21748, 21724, 21722, -1, 21748, 21746, 21724, -1, 21749, 18895, 18896, -1, 21749, 18896, 21745, -1, 21749, 21745, 21744, -1, 21749, 21744, 21747, -1, 21750, 21746, 21748, -1, 21750, 21747, 21746, -1, 21751, 21722, 21720, -1, 21751, 21748, 21722, -1, 21752, 18894, 18895, -1, 21752, 18895, 21749, -1, 21752, 21749, 21747, -1, 21752, 21747, 21750, -1, 21753, 21741, 21742, -1, 21753, 21750, 21748, -1, 21753, 21720, 21741, -1, 21753, 21751, 21720, -1, 21753, 21748, 21751, -1, 21754, 18893, 18894, -1, 21754, 18894, 21752, -1, 21754, 21750, 21753, -1, 21754, 21742, 18893, -1, 21754, 21752, 21750, -1, 21754, 21753, 21742, -1, 21440, 18898, 18900, -1, 21741, 21440, 18900, -1, 21742, 18900, 18902, -1, 21742, 21741, 18900, -1, 18892, 18902, 18889, -1, 18892, 21742, 18902, -1, 18897, 18899, 21429, -1, 21755, 21422, 21181, -1, 21756, 18885, 21757, -1, 21758, 18885, 21756, -1, 18878, 18885, 21758, -1, 21759, 21429, 21428, -1, 21759, 18897, 21429, -1, 21760, 18901, 18897, -1, 21760, 18897, 21759, -1, 21761, 18888, 18901, -1, 21761, 18887, 18888, -1, 21761, 18901, 21760, -1, 21762, 21428, 21426, -1, 21762, 21759, 21428, -1, 21763, 21760, 21759, -1, 21763, 21759, 21762, -1, 21764, 18886, 18887, -1, 21764, 21761, 21760, -1, 21764, 21760, 21763, -1, 21764, 18887, 21761, -1, 21765, 21424, 21422, -1, 21765, 21426, 21424, -1, 21765, 21762, 21426, -1, 21766, 21763, 21762, -1, 21766, 21762, 21765, -1, 21767, 18883, 18886, -1, 21767, 21763, 21766, -1, 21767, 21764, 21763, -1, 21767, 18886, 21764, -1, 21768, 21765, 21422, -1, 21768, 21422, 21755, -1, 21769, 21755, 21757, -1, 21769, 21766, 21765, -1, 21769, 21768, 21755, -1, 21769, 21765, 21768, -1, 21769, 21757, 18885, -1, 21770, 18884, 18883, -1, 21770, 18885, 18884, -1, 21770, 18883, 21767, -1, 21770, 21767, 21766, -1, 21770, 21769, 18885, -1, 21770, 21766, 21769, -1, 21181, 21242, 21771, -1, 21755, 21771, 21772, -1, 21755, 21181, 21771, -1, 21757, 21772, 21773, -1, 21757, 21755, 21772, -1, 21756, 21773, 21774, -1, 21756, 21757, 21773, -1, 21758, 21774, 18879, -1, 21758, 21756, 21774, -1, 18878, 21758, 18879, -1, 21775, 18879, 21774, -1, 21775, 21774, 21773, -1, 21775, 21776, 18904, -1, 21775, 18904, 18879, -1, 21777, 21773, 21772, -1, 21777, 21778, 21776, -1, 21777, 21775, 21773, -1, 21777, 21776, 21775, -1, 21779, 21772, 21771, -1, 21779, 21771, 21242, -1, 21779, 21253, 21179, -1, 21779, 21242, 21253, -1, 21779, 21179, 21778, -1, 21779, 21777, 21772, -1, 21779, 21778, 21777, -1, 21175, 18907, 18906, -1, 21177, 21175, 18906, -1, 21776, 18906, 18904, -1, 21776, 21177, 18906, -1, 21778, 21177, 21776, -1, 21179, 21177, 21778, -1, 18865, 21780, 18868, -1, 18808, 21780, 18865, -1, 18882, 18857, 18856, -1, 18825, 18857, 18882, -1, 21781, 21782, 18876, -1, 21781, 18876, 18881, -1, 21781, 18881, 21783, -1, 21783, 18891, 21784, -1, 18881, 18891, 21783, -1, 21784, 18890, 18903, -1, 18891, 18890, 21784, -1, 18890, 18880, 18903, -1, 18868, 21785, 18866, -1, 21780, 21785, 18868, -1, 18866, 21786, 18867, -1, 21785, 21786, 18866, -1, 18867, 18921, 18869, -1, 21786, 18921, 18867, -1, 18876, 21782, 18872, -1, 21782, 21787, 18872, -1, 18872, 21788, 18870, -1, 21787, 21788, 18872, -1, 18870, 18821, 18873, -1, 21788, 18821, 18870, -1, 18873, 18820, 18871, -1, 18821, 18820, 18873, -1, 18871, 18824, 18875, -1, 18820, 18824, 18871, -1, 18875, 18825, 18882, -1, 18824, 18825, 18875, -1, 21789, 21790, 21791, -1, 21792, 18725, 18727, -1, 21792, 21793, 18725, -1, 21792, 21794, 21795, -1, 21792, 21795, 21793, -1, 17889, 21796, 17885, -1, 21797, 21798, 21789, -1, 21797, 21799, 21798, -1, 21800, 18727, 18729, -1, 21800, 21794, 21792, -1, 21800, 21792, 18727, -1, 21800, 21791, 21794, -1, 21801, 18743, 18745, -1, 21801, 18745, 21802, -1, 21801, 21802, 21799, -1, 21801, 21799, 21797, -1, 21803, 18729, 18731, -1, 21803, 21800, 18729, -1, 21803, 21789, 21791, -1, 21803, 21791, 21800, -1, 21804, 18731, 18733, -1, 21804, 21803, 18731, -1, 21804, 21797, 21789, -1, 21804, 21789, 21803, -1, 21805, 18733, 18735, -1, 21805, 18741, 18743, -1, 18745, 18747, 21806, -1, 21805, 18735, 18741, -1, 21805, 21804, 18733, -1, 21805, 18743, 21801, -1, 21805, 21801, 21797, -1, 21805, 21797, 21804, -1, 18737, 18741, 18735, -1, 21807, 21796, 17889, -1, 21808, 21809, 21796, -1, 21808, 21796, 21807, -1, 21790, 21810, 21809, -1, 21790, 21809, 21808, -1, 21795, 17889, 17888, -1, 21795, 21807, 17889, -1, 21798, 21811, 21810, -1, 21798, 21810, 21790, -1, 21794, 21808, 21807, -1, 21794, 21807, 21795, -1, 21799, 21812, 21811, -1, 21799, 21811, 21798, -1, 21791, 21808, 21794, -1, 21791, 21790, 21808, -1, 21793, 17904, 18725, -1, 21793, 17914, 17904, -1, 21793, 17888, 17914, -1, 21793, 21795, 17888, -1, 21802, 21806, 21812, -1, 21802, 18745, 21806, -1, 21802, 21812, 21799, -1, 21789, 21798, 21790, -1, 17886, 17885, 21796, -1, 21813, 21796, 21809, -1, 21813, 17886, 21796, -1, 21814, 21809, 21810, -1, 21814, 21813, 21809, -1, 21815, 21810, 21811, -1, 21815, 21814, 21810, -1, 21816, 21811, 21812, -1, 21816, 21815, 21811, -1, 21817, 21812, 21806, -1, 21817, 21816, 21812, -1, 21818, 21806, 18747, -1, 21818, 21817, 21806, -1, 18749, 21818, 18747, -1, 21819, 21820, 21821, -1, 21819, 21821, 21822, -1, 21823, 21813, 21814, -1, 21823, 17928, 17929, -1, 21823, 21814, 21824, -1, 21823, 17929, 21813, -1, 21825, 21826, 21827, -1, 21825, 21822, 21828, -1, 21825, 21829, 21826, -1, 21825, 21828, 21829, -1, 21830, 21820, 21819, -1, 21830, 21824, 21820, -1, 21831, 21827, 21832, -1, 21831, 21822, 21825, -1, 21831, 21825, 21827, -1, 21831, 21819, 21822, -1, 21833, 17928, 21823, -1, 21833, 21823, 21824, -1, 21833, 21824, 21830, -1, 21834, 21832, 21835, -1, 21834, 21830, 21819, -1, 21834, 21819, 21831, -1, 21834, 21831, 21832, -1, 21836, 21835, 21837, -1, 21836, 17931, 17928, -1, 21836, 21837, 17931, -1, 21836, 17928, 21833, -1, 21836, 21830, 21834, -1, 21836, 21833, 21830, -1, 21836, 21834, 21835, -1, 17929, 17886, 21813, -1, 17900, 17931, 21837, -1, 21838, 21818, 18749, -1, 21838, 18749, 18758, -1, 21839, 21817, 21818, -1, 21839, 21818, 21838, -1, 21840, 18758, 18756, -1, 21840, 21838, 18758, -1, 21821, 21816, 21817, -1, 21821, 21817, 21839, -1, 21828, 21839, 21838, -1, 21828, 21838, 21840, -1, 21820, 21815, 21816, -1, 21820, 21816, 21821, -1, 21841, 18754, 18753, -1, 21841, 18756, 18754, -1, 21841, 18753, 21842, -1, 21841, 21840, 18756, -1, 21822, 21821, 21839, -1, 21822, 21839, 21828, -1, 21824, 21814, 21815, -1, 21824, 21815, 21820, -1, 21829, 21842, 21826, -1, 21829, 21828, 21840, -1, 21829, 21840, 21841, -1, 21829, 21841, 21842, -1, 21843, 17900, 21837, -1, 21843, 17907, 17900, -1, 21844, 21837, 21835, -1, 21844, 21843, 21837, -1, 21845, 21835, 21832, -1, 21845, 21844, 21835, -1, 21846, 21832, 21827, -1, 21846, 21845, 21832, -1, 21847, 21827, 21826, -1, 21847, 21846, 21827, -1, 21848, 21826, 21842, -1, 21848, 21847, 21826, -1, 18767, 21842, 18753, -1, 18767, 21848, 21842, -1, 21849, 16708, 16707, -1, 21849, 16707, 21850, -1, 21851, 21850, 21852, -1, 21851, 21849, 21850, -1, 18854, 21852, 18845, -1, 18854, 21851, 21852, -1, 21853, 21854, 21855, -1, 21853, 18628, 18630, -1, 21853, 18630, 21856, -1, 21853, 21857, 21858, -1, 21853, 21855, 18628, -1, 21853, 21856, 21857, -1, 21853, 21858, 21854, -1, 18625, 18628, 21855, -1, 21859, 21848, 18767, -1, 21859, 18767, 18765, -1, 21860, 21847, 21848, -1, 21860, 21848, 21859, -1, 21861, 18763, 18761, -1, 21861, 18765, 18763, -1, 21861, 18761, 21862, -1, 21861, 21859, 18765, -1, 21863, 21846, 21847, -1, 21863, 21847, 21860, -1, 21864, 21862, 21865, -1, 21864, 21860, 21859, -1, 21864, 21861, 21862, -1, 21864, 21859, 21861, -1, 21866, 21845, 21846, -1, 21866, 21846, 21863, -1, 21867, 21865, 21868, -1, 21867, 21863, 21860, -1, 21867, 21860, 21864, -1, 21867, 21864, 21865, -1, 21857, 21844, 21845, -1, 21857, 21845, 21866, -1, 21869, 21868, 21870, -1, 21869, 21867, 21868, -1, 21869, 21866, 21863, -1, 21869, 21863, 21867, -1, 21856, 17907, 21843, -1, 21856, 21843, 21844, -1, 21856, 18630, 17907, -1, 21856, 21844, 21857, -1, 21858, 21870, 21854, -1, 21858, 21869, 21870, -1, 21858, 21857, 21866, -1, 21858, 21866, 21869, -1, 18849, 21871, 18850, -1, 18849, 21872, 21871, -1, 16721, 16747, 21872, -1, 16721, 18849, 18846, -1, 16721, 21872, 18849, -1, 16719, 16721, 18846, -1, 21852, 18846, 18845, -1, 21852, 16719, 18846, -1, 21850, 16719, 21852, -1, 16707, 16719, 21850, -1, 21873, 18625, 21855, -1, 21873, 18645, 18625, -1, 21874, 21855, 21854, -1, 21874, 21873, 21855, -1, 21875, 21854, 21870, -1, 21875, 21874, 21854, -1, 21876, 21870, 21868, -1, 21876, 21875, 21870, -1, 21877, 21868, 21865, -1, 21877, 21876, 21868, -1, 21878, 21865, 21862, -1, 21878, 21862, 18761, -1, 21878, 21877, 21865, -1, 18760, 21878, 18761, -1, 21879, 16882, 21880, -1, 21881, 21882, 16892, -1, 21881, 21879, 21880, -1, 21881, 16892, 21879, -1, 21883, 21880, 21884, -1, 21883, 21885, 21882, -1, 21883, 21882, 21881, -1, 21883, 21881, 21880, -1, 21886, 21885, 21883, -1, 21886, 21887, 21885, -1, 21886, 21883, 21884, -1, 21888, 21884, 21889, -1, 21888, 18853, 18852, -1, 21888, 18852, 21890, -1, 21888, 21889, 18853, -1, 21888, 21890, 21887, -1, 21888, 21886, 21884, -1, 21888, 21887, 21886, -1, 18843, 18853, 21889, -1, 21891, 16748, 16752, -1, 21891, 16740, 16748, -1, 21892, 16743, 16740, -1, 21892, 16744, 16743, -1, 21892, 16747, 16744, -1, 21892, 16740, 21891, -1, 21893, 16752, 21894, -1, 21893, 21894, 16894, -1, 21893, 21891, 16752, -1, 21895, 21892, 21891, -1, 21895, 21891, 21893, -1, 21896, 21872, 16747, -1, 21896, 16747, 21892, -1, 21897, 21892, 21895, -1, 21897, 21896, 21892, -1, 21898, 18850, 21871, -1, 21898, 21871, 21872, -1, 21898, 21872, 21896, -1, 21899, 16894, 16892, -1, 21900, 18852, 18850, -1, 21900, 21898, 21896, -1, 21900, 21896, 21897, -1, 21900, 18850, 21898, -1, 21882, 21893, 16894, -1, 21882, 16894, 21899, -1, 21882, 21899, 16892, -1, 21885, 21893, 21882, -1, 21885, 21895, 21893, -1, 21887, 21897, 21895, -1, 21887, 21895, 21885, -1, 21890, 21897, 21887, -1, 21890, 18852, 21900, -1, 21890, 21900, 21897, -1, 21879, 16890, 16882, -1, 21879, 16892, 16890, -1, 21901, 21902, 21903, -1, 21901, 21904, 21902, -1, 21905, 21906, 21907, -1, 21905, 21907, 21908, -1, 18790, 21878, 18760, -1, 21909, 18668, 18676, -1, 21909, 18662, 18668, -1, 21909, 21910, 21904, -1, 21909, 18676, 21910, -1, 21909, 21904, 21901, -1, 21911, 21912, 21906, -1, 21911, 21906, 21905, -1, 21913, 18785, 18783, -1, 21913, 18783, 21914, -1, 21913, 21908, 18785, -1, 21915, 21903, 21912, -1, 21915, 21912, 21911, -1, 21916, 21914, 21917, -1, 21916, 21913, 21914, -1, 21916, 21905, 21908, -1, 21916, 21908, 21913, -1, 21918, 21901, 21903, -1, 21918, 21903, 21915, -1, 21919, 21917, 21920, -1, 21919, 21911, 21905, -1, 21919, 21916, 21917, -1, 21919, 21905, 21916, -1, 21921, 18662, 21909, -1, 21921, 21909, 21901, -1, 21921, 21901, 21918, -1, 21922, 21920, 21923, -1, 21922, 21915, 21911, -1, 21922, 21911, 21919, -1, 21922, 21919, 21920, -1, 21924, 21923, 21925, -1, 21924, 21922, 21923, -1, 21924, 21915, 21922, -1, 21924, 21918, 21915, -1, 21926, 21924, 21925, -1, 21926, 21921, 21918, -1, 21926, 21925, 18650, -1, 21926, 18649, 18662, -1, 21926, 18650, 18649, -1, 21926, 21918, 21924, -1, 21926, 18662, 21921, -1, 21927, 18790, 18788, -1, 21927, 21878, 18790, -1, 21928, 21877, 21878, -1, 21928, 21878, 21927, -1, 21929, 21876, 21877, -1, 21929, 21877, 21928, -1, 21902, 21875, 21876, -1, 21902, 21876, 21929, -1, 21907, 18788, 18786, -1, 21907, 21927, 18788, -1, 21904, 21873, 21874, -1, 21904, 21874, 21875, -1, 21904, 21875, 21902, -1, 21906, 21927, 21907, -1, 21906, 21928, 21927, -1, 21910, 18645, 21873, -1, 21910, 18676, 18645, -1, 21910, 21873, 21904, -1, 21912, 21929, 21928, -1, 21912, 21928, 21906, -1, 21903, 21902, 21929, -1, 21903, 21929, 21912, -1, 21908, 18786, 18785, -1, 21908, 21907, 18786, -1, 16882, 16879, 21930, -1, 21880, 21930, 21931, -1, 21880, 16882, 21930, -1, 21884, 21931, 21932, -1, 21884, 21880, 21931, -1, 21889, 21932, 18841, -1, 21889, 21884, 21932, -1, 18843, 21889, 18841, -1, 21933, 18650, 21925, -1, 21933, 18679, 18650, -1, 21934, 21925, 21923, -1, 21934, 21933, 21925, -1, 21935, 21923, 21920, -1, 21935, 21934, 21923, -1, 21936, 21920, 21917, -1, 21936, 21935, 21920, -1, 21937, 21917, 21914, -1, 21937, 21936, 21917, -1, 18770, 21914, 18783, -1, 18770, 21937, 21914, -1, 16877, 16876, 21938, -1, 21930, 16878, 21931, -1, 16879, 16878, 21930, -1, 21939, 21940, 18799, -1, 21939, 18837, 18839, -1, 21939, 18799, 18837, -1, 21941, 21942, 21940, -1, 21941, 21938, 21942, -1, 21941, 21940, 21939, -1, 21943, 16875, 16877, -1, 21943, 21938, 21941, -1, 21943, 21941, 16875, -1, 21943, 16877, 21938, -1, 21944, 18841, 21932, -1, 21944, 18839, 18841, -1, 21944, 21939, 18839, -1, 21945, 21932, 21931, -1, 21945, 21941, 21939, -1, 21945, 16875, 21941, -1, 21945, 21939, 21944, -1, 21945, 21931, 16878, -1, 21945, 21944, 21932, -1, 21946, 16878, 16875, -1, 21946, 16875, 21945, -1, 21946, 21945, 16878, -1, 21947, 21948, 21949, -1, 21947, 21950, 21948, -1, 18775, 21937, 18770, -1, 21951, 21952, 21953, -1, 21951, 21953, 21954, -1, 21955, 21956, 21950, -1, 21955, 21950, 21947, -1, 21957, 18723, 18724, -1, 21957, 21958, 21952, -1, 21957, 18724, 21958, -1, 21957, 21952, 21951, -1, 21959, 18772, 18769, -1, 21959, 21949, 18772, -1, 21960, 21954, 21956, -1, 21960, 21956, 21955, -1, 21961, 21947, 21949, -1, 21961, 21949, 21959, -1, 21962, 21954, 21960, -1, 21962, 21951, 21954, -1, 21963, 18769, 18771, -1, 21963, 18771, 21964, -1, 21963, 21959, 18769, -1, 21965, 21947, 21961, -1, 21965, 21955, 21947, -1, 21966, 21951, 21962, -1, 21966, 18722, 18723, -1, 21966, 18723, 21957, -1, 21966, 21957, 21951, -1, 21967, 21963, 21964, -1, 21967, 21959, 21963, -1, 21967, 21968, 21969, -1, 21967, 21964, 21968, -1, 21967, 21961, 21959, -1, 21970, 21955, 21965, -1, 21970, 21960, 21955, -1, 21971, 21961, 21967, -1, 21971, 21967, 21969, -1, 21971, 21965, 21961, -1, 21972, 21962, 21960, -1, 21972, 21960, 21970, -1, 21973, 18775, 18774, -1, 21973, 21937, 18775, -1, 21974, 21975, 21976, -1, 21977, 21936, 21937, -1, 21974, 21969, 21975, -1, 21974, 21971, 21969, -1, 21974, 21965, 21971, -1, 21977, 21937, 21973, -1, 21974, 21970, 21965, -1, 21978, 21935, 21936, -1, 21979, 21962, 21972, -1, 21979, 18721, 18722, -1, 21979, 18720, 18721, -1, 21978, 21936, 21977, -1, 21979, 18722, 21966, -1, 21979, 21966, 21962, -1, 21948, 18774, 18773, -1, 21980, 21974, 21976, -1, 21948, 21973, 18774, -1, 21980, 21970, 21974, -1, 21980, 21972, 21970, -1, 21981, 21979, 21972, -1, 21953, 21934, 21935, -1, 21981, 21982, 16952, -1, 21981, 21976, 21982, -1, 21981, 16952, 18720, -1, 21981, 21980, 21976, -1, 21981, 21972, 21980, -1, 21953, 21935, 21978, -1, 21981, 18720, 21979, -1, 21950, 21977, 21973, -1, 21950, 21973, 21948, -1, 21952, 21933, 21934, -1, 21952, 21934, 21953, -1, 21956, 21978, 21977, -1, 21956, 21977, 21950, -1, 21958, 18679, 21933, -1, 21958, 18724, 18679, -1, 21958, 21933, 21952, -1, 21949, 18773, 18772, -1, 21949, 21948, 18773, -1, 21954, 21978, 21956, -1, 21954, 21953, 21978, -1, 16876, 16881, 21983, -1, 21938, 16876, 21983, -1, 21942, 21983, 21984, -1, 21942, 21938, 21983, -1, 21940, 21984, 21985, -1, 21940, 21942, 21984, -1, 18799, 21985, 18792, -1, 18799, 21940, 21985, -1, 21986, 16952, 21982, -1, 21986, 16950, 16952, -1, 21987, 21982, 21976, -1, 21987, 21986, 21982, -1, 21988, 21976, 21975, -1, 21988, 21987, 21976, -1, 21989, 21975, 21969, -1, 21989, 21988, 21975, -1, 21990, 21969, 21968, -1, 21990, 21989, 21969, -1, 21991, 21968, 21964, -1, 21991, 21964, 18771, -1, 21991, 21990, 21968, -1, 18792, 21991, 18771, -1, 16939, 16938, 16959, -1, 16959, 16936, 21992, -1, 16938, 16936, 16959, -1, 16936, 16935, 21992, -1, 21992, 16934, 21993, -1, 16935, 16934, 21992, -1, 16934, 16933, 21993, -1, 21993, 16932, 21994, -1, 16933, 16932, 21993, -1, 21994, 16931, 21995, -1, 16932, 16931, 21994, -1, 21995, 16949, 16955, -1, 16931, 16949, 21995, -1, 21996, 16925, 16912, -1, 21996, 16912, 21997, -1, 21998, 21996, 21997, -1, 21999, 21997, 22000, -1, 21999, 21998, 21997, -1, 22001, 21999, 22000, -1, 22002, 22000, 22003, -1, 22002, 22001, 22000, -1, 22004, 22003, 16960, -1, 22004, 22002, 22003, -1, 16959, 22004, 16960, -1, 21988, 16881, 22005, -1, 22006, 21987, 22007, -1, 21989, 21983, 16881, -1, 21989, 16881, 21988, -1, 21986, 21987, 22006, -1, 21990, 21984, 21983, -1, 21990, 21983, 21989, -1, 21991, 21985, 21984, -1, 21991, 21984, 21990, -1, 18792, 21985, 21991, -1, 16950, 21986, 22006, -1, 22008, 21987, 21988, -1, 22008, 22005, 22007, -1, 22008, 21988, 22005, -1, 22008, 22007, 21987, -1, 22009, 22010, 22011, -1, 22012, 22010, 22009, -1, 22013, 22010, 22014, -1, 22014, 22010, 22012, -1, 22011, 22015, 22016, -1, 21992, 22004, 16959, -1, 22017, 22015, 22013, -1, 22010, 22015, 22011, -1, 22013, 22015, 22010, -1, 22016, 22018, 16957, -1, 16957, 22018, 16956, -1, 16956, 22018, 22019, -1, 22019, 22018, 22017, -1, 22015, 22018, 22016, -1, 22017, 22018, 22015, -1, 22004, 22020, 22002, -1, 21992, 22020, 22004, -1, 21993, 22021, 21992, -1, 21992, 22021, 22020, -1, 22001, 22022, 21999, -1, 22002, 22022, 22001, -1, 22020, 22022, 22002, -1, 21994, 22023, 21993, -1, 21995, 22023, 21994, -1, 21993, 22023, 22021, -1, 22021, 22024, 22020, -1, 22020, 22024, 22022, -1, 21999, 22014, 21998, -1, 22022, 22014, 21999, -1, 16953, 22025, 16955, -1, 16955, 22025, 21995, -1, 21995, 22025, 22023, -1, 22023, 22026, 22021, -1, 22021, 22026, 22024, -1, 22024, 22013, 22022, -1, 22022, 22013, 22014, -1, 16954, 22027, 16953, -1, 22025, 22027, 22023, -1, 16953, 22027, 22025, -1, 22023, 22027, 22026, -1, 22024, 22017, 22013, -1, 22026, 22017, 22024, -1, 21996, 22012, 16925, -1, 21998, 22012, 21996, -1, 16925, 22012, 22009, -1, 22014, 22012, 21998, -1, 16956, 22019, 16954, -1, 16954, 22019, 22027, -1, 22027, 22019, 22026, -1, 22026, 22019, 22017, -1, 22028, 16950, 22006, -1, 22028, 16958, 16950, -1, 22029, 22006, 22007, -1, 22029, 22028, 22006, -1, 22030, 22007, 22005, -1, 22030, 22029, 22007, -1, 16880, 22005, 16881, -1, 16880, 22030, 22005, -1, 16918, 16925, 22031, -1, 22031, 16925, 22032, -1, 22032, 22009, 22033, -1, 22033, 22009, 22034, -1, 22034, 22009, 22035, -1, 16925, 22009, 22032, -1, 22035, 22011, 22036, -1, 22036, 22011, 22037, -1, 22009, 22011, 22035, -1, 22037, 22016, 16958, -1, 22011, 22016, 22037, -1, 22016, 16957, 16958, -1, 22038, 22039, 22040, -1, 22041, 22032, 22033, -1, 22041, 22033, 22034, -1, 22041, 22034, 22042, -1, 22041, 22043, 22039, -1, 22041, 22042, 22043, -1, 22044, 22045, 22046, -1, 22044, 22047, 22045, -1, 22044, 22048, 22047, -1, 22044, 22038, 22048, -1, 22049, 22032, 22041, -1, 22049, 22039, 22038, -1, 22049, 22041, 22039, -1, 22050, 22046, 16918, -1, 22050, 16918, 22031, -1, 22050, 22031, 22032, -1, 22050, 22032, 22049, -1, 22050, 22044, 22046, -1, 22050, 22038, 22044, -1, 22050, 22049, 22038, -1, 22037, 16958, 22028, -1, 22051, 22030, 16880, -1, 22051, 16880, 16883, -1, 22051, 16883, 16884, -1, 22052, 22029, 22030, -1, 22052, 22030, 22051, -1, 22053, 22028, 22029, -1, 22053, 22036, 22037, -1, 22053, 22037, 22028, -1, 22053, 22029, 22052, -1, 22054, 22051, 16884, -1, 22055, 22051, 22054, -1, 22055, 22052, 22051, -1, 22056, 22035, 22036, -1, 22056, 22053, 22052, -1, 22056, 22052, 22055, -1, 22056, 22036, 22053, -1, 22057, 16884, 16885, -1, 22057, 22054, 16884, -1, 22043, 22055, 22054, -1, 22043, 22054, 22057, -1, 22040, 16885, 16886, -1, 22040, 22057, 16885, -1, 22042, 22034, 22035, -1, 22042, 22055, 22043, -1, 22042, 22035, 22056, -1, 22042, 22056, 22055, -1, 22048, 16886, 16887, -1, 22048, 22040, 16886, -1, 22039, 22043, 22057, -1, 22039, 22057, 22040, -1, 22047, 16887, 16888, -1, 22047, 16888, 22045, -1, 22047, 22048, 16887, -1, 22038, 22040, 22048, -1, 22058, 16905, 16918, -1, 22058, 16918, 22046, -1, 22059, 22046, 22045, -1, 22059, 22058, 22046, -1, 16898, 22045, 16888, -1, 16898, 22059, 22045, -1, 16951, 16930, 16937, -1, 16983, 16937, 16940, -1, 16983, 16951, 16937, -1, 16987, 16941, 16942, -1, 16987, 16940, 16941, -1, 16987, 16983, 16940, -1, 16980, 16943, 16948, -1, 16980, 16942, 16943, -1, 16980, 16987, 16942, -1, 16981, 16946, 16945, -1, 16981, 16947, 16946, -1, 16981, 16948, 16947, -1, 16981, 16980, 16948, -1, 16963, 16945, 15017, -1, 16963, 16981, 16945, -1, 22060, 16999, 16966, -1, 22060, 16966, 16965, -1, 22061, 16978, 16999, -1, 22061, 16999, 22060, -1, 18691, 16978, 22061, -1, 16984, 16978, 18691, -1, 18689, 16984, 18691, -1, 18687, 16984, 18689, -1, 18680, 16984, 18687, -1, 18690, 18691, 22061, -1, 22062, 22061, 22060, -1, 22062, 18690, 22061, -1, 22063, 22060, 16965, -1, 22063, 22062, 22060, -1, 16972, 22063, 16965, -1, 18685, 18683, 22064, -1, 22065, 18685, 22064, -1, 22066, 22064, 22067, -1, 22066, 22067, 16781, -1, 22066, 22065, 22064, -1, 16780, 22066, 16781, -1, 22068, 22069, 22070, -1, 22071, 16791, 22072, -1, 22073, 22074, 22075, -1, 22073, 22075, 22076, -1, 22077, 22078, 22079, -1, 22080, 22081, 22082, -1, 22077, 22079, 22083, -1, 22080, 22082, 22084, -1, 22085, 22086, 22078, -1, 22087, 22088, 22069, -1, 22085, 22072, 22086, -1, 22087, 22069, 22068, -1, 22089, 22083, 22090, -1, 22089, 22077, 22083, -1, 22091, 22092, 22093, -1, 22094, 22095, 22074, -1, 22094, 22074, 22073, -1, 22096, 22065, 22066, -1, 22096, 16791, 22071, -1, 22097, 22098, 22081, -1, 22097, 22081, 22080, -1, 22096, 22066, 16791, -1, 22097, 22080, 22084, -1, 22099, 22072, 22085, -1, 22099, 22071, 22072, -1, 22100, 22095, 22094, -1, 22066, 16780, 16791, -1, 22100, 22101, 22095, -1, 22102, 22085, 22078, -1, 22102, 22078, 22077, -1, 22103, 22104, 22088, -1, 22103, 22088, 22087, -1, 22070, 22092, 22091, -1, 22070, 22091, 22093, -1, 22070, 22105, 22092, -1, 22106, 22084, 22107, -1, 22106, 22068, 22098, -1, 22106, 22097, 22084, -1, 22108, 22071, 22099, -1, 22106, 22098, 22097, -1, 22108, 22096, 22071, -1, 22109, 18660, 18653, -1, 22109, 18653, 22101, -1, 22109, 22101, 22100, -1, 22110, 22099, 22085, -1, 22111, 22104, 22103, -1, 22110, 22085, 22102, -1, 22111, 22076, 22104, -1, 22112, 22102, 22077, -1, 22112, 22077, 22089, -1, 22113, 18651, 18682, -1, 22113, 18682, 18684, -1, 22113, 18684, 18685, -1, 22114, 22073, 22076, -1, 22113, 18685, 22065, -1, 22114, 22076, 22111, -1, 22113, 22065, 22096, -1, 22115, 22107, 22116, -1, 22075, 22102, 22112, -1, 22115, 22068, 22106, -1, 22115, 22087, 22068, -1, 22115, 22106, 22107, -1, 22075, 22110, 22102, -1, 22117, 22099, 22110, -1, 22118, 22094, 22073, -1, 22117, 22108, 22099, -1, 22069, 22105, 22070, -1, 22118, 22073, 22114, -1, 22119, 22116, 22120, -1, 22119, 22115, 22116, -1, 22119, 22103, 22087, -1, 22069, 22090, 22105, -1, 22119, 22087, 22115, -1, 22121, 22096, 22108, -1, 22121, 22113, 22096, -1, 22122, 22103, 22119, -1, 22074, 22117, 22110, -1, 22122, 22120, 22123, -1, 22074, 22110, 22075, -1, 22122, 22111, 22103, -1, 22122, 22119, 22120, -1, 22124, 22121, 22108, -1, 22125, 22100, 22094, -1, 22124, 22108, 22117, -1, 22125, 22094, 22118, -1, 22126, 22100, 22125, -1, 22126, 18660, 22109, -1, 22126, 22109, 22100, -1, 22088, 22090, 22069, -1, 22127, 22111, 22122, -1, 22127, 22123, 22128, -1, 22127, 22114, 22111, -1, 22088, 22089, 22090, -1, 22127, 22122, 22123, -1, 22129, 22118, 22114, -1, 22130, 22093, 22081, -1, 22129, 22127, 22128, -1, 22129, 22114, 22127, -1, 22131, 22132, 22133, -1, 22131, 22133, 22092, -1, 22134, 22125, 22118, -1, 22095, 22117, 22074, -1, 22134, 22118, 22129, -1, 22134, 22129, 22128, -1, 22095, 22124, 22117, -1, 22135, 22136, 22132, -1, 22134, 22128, 18647, -1, 22137, 18651, 22113, -1, 22137, 22113, 22121, -1, 22138, 18660, 22126, -1, 22137, 18652, 18651, -1, 22138, 22125, 22134, -1, 22137, 22121, 22124, -1, 22138, 22134, 18647, -1, 22079, 22139, 22140, -1, 22138, 18667, 18660, -1, 22138, 18647, 18667, -1, 22098, 22070, 22093, -1, 22138, 22126, 22125, -1, 22105, 22135, 22132, -1, 22098, 22130, 22081, -1, 22105, 22132, 22131, -1, 22105, 22131, 22092, -1, 22098, 22093, 22130, -1, 22104, 22112, 22089, -1, 22083, 22140, 22136, -1, 22083, 22136, 22135, -1, 22104, 22089, 22088, -1, 22083, 22079, 22140, -1, 22101, 18653, 18652, -1, 22078, 22086, 22139, -1, 22101, 22124, 22095, -1, 22101, 18652, 22137, -1, 22101, 22137, 22124, -1, 22076, 22075, 22112, -1, 22078, 22139, 22079, -1, 22076, 22112, 22104, -1, 22090, 22135, 22105, -1, 22090, 22083, 22135, -1, 22072, 16791, 22086, -1, 22068, 22070, 22098, -1, 22141, 22142, 22143, -1, 22144, 22142, 22141, -1, 22142, 22145, 22143, -1, 22145, 22146, 22143, -1, 22146, 22147, 22143, -1, 22143, 22082, 22133, -1, 22147, 22082, 22143, -1, 22133, 22093, 22092, -1, 22082, 22081, 22133, -1, 22133, 22081, 22093, -1, 22144, 22141, 22148, -1, 22141, 22149, 22148, -1, 22150, 22151, 22152, -1, 22148, 22151, 22150, -1, 22149, 22151, 22148, -1, 22152, 22153, 22154, -1, 22151, 22153, 22152, -1, 22153, 22155, 22154, -1, 22156, 22154, 22155, -1, 22157, 22154, 22156, -1, 22158, 22159, 22160, -1, 22158, 22160, 22161, -1, 22162, 22161, 22163, -1, 22162, 22158, 22161, -1, 22164, 22163, 22165, -1, 22164, 22162, 22163, -1, 22156, 22165, 22157, -1, 22156, 22164, 22165, -1, 22166, 22160, 22159, -1, 22166, 22159, 22167, -1, 22168, 18647, 22128, -1, 22168, 18626, 18647, -1, 22169, 22128, 22123, -1, 22169, 22168, 22128, -1, 22170, 22123, 22120, -1, 22170, 22169, 22123, -1, 22171, 22120, 22116, -1, 22171, 22170, 22120, -1, 22172, 22116, 22107, -1, 22172, 22171, 22116, -1, 22173, 22107, 22084, -1, 22173, 22172, 22107, -1, 22147, 22084, 22082, -1, 22147, 22173, 22084, -1, 22174, 22175, 17908, -1, 22174, 22176, 22175, -1, 22174, 18629, 18627, -1, 22174, 17908, 18629, -1, 22174, 22177, 22178, -1, 22174, 18627, 22179, -1, 22174, 22179, 22177, -1, 22174, 22178, 22176, -1, 22180, 22145, 22142, -1, 18627, 18626, 22168, -1, 22181, 22173, 22147, -1, 22181, 22147, 22146, -1, 22182, 22172, 22173, -1, 22182, 22173, 22181, -1, 22183, 22146, 22145, -1, 22183, 22181, 22146, -1, 22183, 22145, 22180, -1, 22184, 22171, 22172, -1, 22184, 22172, 22182, -1, 22185, 22180, 22186, -1, 22185, 22182, 22181, -1, 22185, 22181, 22183, -1, 22185, 22183, 22180, -1, 22187, 22170, 22171, -1, 22187, 22171, 22184, -1, 22188, 22186, 22189, -1, 22188, 22185, 22186, -1, 22188, 22182, 22185, -1, 22188, 22184, 22182, -1, 22177, 22169, 22170, -1, 22177, 22170, 22187, -1, 22190, 22189, 22191, -1, 22190, 22187, 22184, -1, 22190, 22184, 22188, -1, 22190, 22188, 22189, -1, 22179, 22168, 22169, -1, 22179, 18627, 22168, -1, 22179, 22169, 22177, -1, 22178, 22191, 22176, -1, 22178, 22177, 22187, -1, 22178, 22190, 22191, -1, 22178, 22187, 22190, -1, 22192, 17908, 22175, -1, 22192, 17905, 17908, -1, 22193, 22175, 22176, -1, 22193, 22192, 22175, -1, 22194, 22176, 22191, -1, 22194, 22193, 22176, -1, 22195, 22191, 22189, -1, 22195, 22194, 22191, -1, 22196, 22189, 22186, -1, 22196, 22195, 22189, -1, 22197, 22186, 22180, -1, 22197, 22196, 22186, -1, 22144, 22180, 22142, -1, 22144, 22197, 22180, -1, 22198, 22199, 22200, -1, 22198, 22201, 22199, -1, 22202, 22192, 22193, -1, 22202, 22203, 22204, -1, 22202, 22205, 22203, -1, 22202, 22204, 22192, -1, 17895, 22206, 17884, -1, 22207, 22208, 22201, -1, 22207, 22201, 22198, -1, 22209, 22193, 22194, -1, 22209, 22202, 22193, -1, 22209, 22200, 22205, -1, 22209, 22205, 22202, -1, 22210, 22148, 22150, -1, 22210, 22150, 22211, -1, 22210, 22211, 22208, -1, 22210, 22208, 22207, -1, 22212, 22194, 22195, -1, 22212, 22198, 22200, -1, 22212, 22209, 22194, -1, 22212, 22200, 22209, -1, 22213, 22195, 22196, -1, 22213, 22212, 22195, -1, 22213, 22207, 22198, -1, 22213, 22198, 22212, -1, 22214, 22196, 22197, -1, 22214, 22207, 22213, -1, 22214, 22197, 22148, -1, 22214, 22148, 22210, -1, 22214, 22210, 22207, -1, 22214, 22213, 22196, -1, 22144, 22148, 22197, -1, 22215, 17895, 17899, -1, 22215, 22206, 17895, -1, 22216, 22217, 22206, -1, 22216, 22206, 22215, -1, 22199, 22218, 22217, -1, 22199, 22217, 22216, -1, 22203, 17899, 17902, -1, 22203, 22215, 17899, -1, 22201, 22219, 22218, -1, 22201, 22218, 22199, -1, 22205, 22216, 22215, -1, 22205, 22215, 22203, -1, 22208, 22220, 22219, -1, 22208, 22219, 22201, -1, 22200, 22216, 22205, -1, 22200, 22199, 22216, -1, 22204, 17905, 22192, -1, 22204, 17902, 17905, -1, 22204, 22203, 17902, -1, 22211, 22152, 22154, -1, 22211, 22150, 22152, -1, 22211, 22221, 22220, -1, 22211, 22154, 22221, -1, 22211, 22220, 22208, -1, 22222, 17884, 22206, -1, 22222, 17887, 17884, -1, 22223, 22206, 22217, -1, 22223, 22222, 22206, -1, 22224, 22217, 22218, -1, 22224, 22223, 22217, -1, 22225, 22218, 22219, -1, 22225, 22224, 22218, -1, 22226, 22219, 22220, -1, 22226, 22225, 22219, -1, 22227, 22220, 22221, -1, 22227, 22226, 22220, -1, 22157, 22221, 22154, -1, 22157, 22227, 22221, -1, 22228, 22229, 22230, -1, 22228, 22230, 22231, -1, 22232, 17887, 22222, -1, 22232, 22222, 22223, -1, 22232, 17880, 17887, -1, 22232, 22223, 22233, -1, 22234, 22235, 22236, -1, 22234, 22231, 22237, -1, 22234, 22238, 22235, -1, 22234, 22237, 22238, -1, 22239, 22229, 22228, -1, 22239, 22233, 22229, -1, 22240, 22236, 22241, -1, 22240, 22231, 22234, -1, 22240, 22234, 22236, -1, 22240, 22228, 22231, -1, 22242, 17881, 17880, -1, 22242, 17880, 22232, -1, 22242, 22232, 22233, -1, 22242, 22233, 22239, -1, 22243, 22241, 22244, -1, 22243, 22239, 22228, -1, 22243, 22240, 22241, -1, 22243, 22228, 22240, -1, 22245, 22244, 22246, -1, 22245, 17882, 17881, -1, 22245, 22246, 17882, -1, 22245, 22239, 22243, -1, 22245, 17881, 22242, -1, 22245, 22242, 22239, -1, 22245, 22243, 22244, -1, 17883, 17882, 22246, -1, 22247, 22227, 22157, -1, 22247, 22157, 22165, -1, 22248, 22226, 22227, -1, 22248, 22227, 22247, -1, 22249, 22165, 22163, -1, 22249, 22247, 22165, -1, 22230, 22225, 22226, -1, 22230, 22226, 22248, -1, 22237, 22248, 22247, -1, 22237, 22247, 22249, -1, 22229, 22224, 22225, -1, 22229, 22225, 22230, -1, 22250, 22161, 22160, -1, 22250, 22163, 22161, -1, 22250, 22160, 22251, -1, 22250, 22249, 22163, -1, 22231, 22248, 22237, -1, 22231, 22230, 22248, -1, 22233, 22223, 22224, -1, 22233, 22224, 22229, -1, 22238, 22251, 22235, -1, 22238, 22250, 22251, -1, 22238, 22249, 22250, -1, 22238, 22237, 22249, -1, 22252, 17883, 22246, -1, 22252, 17876, 17883, -1, 22253, 22246, 22244, -1, 22253, 22252, 22246, -1, 22254, 22244, 22241, -1, 22254, 22253, 22244, -1, 22255, 22241, 22236, -1, 22255, 22254, 22241, -1, 22256, 22236, 22235, -1, 22256, 22255, 22236, -1, 22257, 22235, 22251, -1, 22257, 22251, 22160, -1, 22257, 22256, 22235, -1, 22166, 22257, 22160, -1, 18855, 18847, 22258, -1, 22259, 22258, 22260, -1, 22259, 18855, 22258, -1, 22261, 22260, 22262, -1, 22261, 22259, 22260, -1, 22263, 22262, 22264, -1, 22263, 22261, 22262, -1, 22265, 22264, 19822, -1, 22265, 22263, 22264, -1, 19821, 22265, 19822, -1, 22266, 18851, 18844, -1, 22267, 22258, 18847, -1, 22267, 18847, 18848, -1, 22268, 22260, 22258, -1, 22268, 22258, 22267, -1, 22269, 22262, 22260, -1, 22269, 22260, 22268, -1, 22270, 22264, 22262, -1, 22270, 22262, 22269, -1, 22271, 19822, 22264, -1, 22271, 19977, 19822, -1, 22271, 22264, 22270, -1, 22272, 18848, 18851, -1, 22272, 22267, 18848, -1, 22272, 18851, 22266, -1, 22273, 22266, 22274, -1, 22273, 22272, 22266, -1, 22273, 22267, 22272, -1, 22273, 22268, 22267, -1, 22275, 22274, 22276, -1, 22275, 22269, 22268, -1, 22275, 22273, 22274, -1, 22275, 22268, 22273, -1, 22277, 22278, 22279, -1, 22277, 22276, 22278, -1, 22277, 22269, 22275, -1, 22277, 22270, 22269, -1, 22277, 22275, 22276, -1, 22280, 22279, 19967, -1, 22280, 19971, 19977, -1, 22280, 19967, 19971, -1, 22280, 22271, 22270, -1, 22280, 22277, 22279, -1, 22280, 19977, 22271, -1, 22280, 22270, 22277, -1, 18844, 18842, 22281, -1, 22266, 22281, 22282, -1, 22266, 18844, 22281, -1, 22274, 22282, 22283, -1, 22274, 22266, 22282, -1, 22276, 22274, 22283, -1, 22278, 22283, 22284, -1, 22278, 22276, 22283, -1, 22279, 22284, 22285, -1, 22279, 22278, 22284, -1, 19967, 22285, 19786, -1, 19967, 22279, 22285, -1, 22281, 18842, 18840, -1, 22281, 18840, 22286, -1, 22282, 22286, 22287, -1, 22282, 22281, 22286, -1, 22283, 22287, 22288, -1, 22283, 22282, 22287, -1, 22284, 22288, 22289, -1, 22284, 22283, 22288, -1, 22285, 22289, 22290, -1, 22285, 22284, 22289, -1, 19786, 22290, 22291, -1, 19786, 22285, 22290, -1, 19781, 19786, 22291, -1, 19779, 19781, 22291, -1, 19782, 19779, 22291, -1, 19778, 22291, 18909, -1, 19778, 19782, 22291, -1, 19776, 19778, 18909, -1, 18911, 19776, 18909, -1, 22292, 18836, 22293, -1, 22292, 22294, 22286, -1, 22292, 22293, 22295, -1, 22292, 22295, 22294, -1, 22291, 18910, 18909, -1, 18836, 18800, 22296, -1, 22297, 22298, 18905, -1, 22297, 18905, 18908, -1, 22299, 22300, 22298, -1, 22299, 22298, 22297, -1, 22301, 22291, 22290, -1, 22301, 18908, 18910, -1, 22301, 22297, 18908, -1, 22301, 18910, 22291, -1, 22302, 22303, 22300, -1, 22302, 22300, 22299, -1, 22304, 22290, 22289, -1, 22304, 22299, 22297, -1, 22304, 22301, 22290, -1, 22304, 22297, 22301, -1, 22305, 22306, 22303, -1, 22305, 22303, 22302, -1, 22307, 22289, 22288, -1, 22307, 22299, 22304, -1, 22307, 22302, 22299, -1, 22307, 22304, 22289, -1, 22295, 22308, 22306, -1, 22295, 22306, 22305, -1, 22309, 22288, 22287, -1, 22309, 22302, 22307, -1, 22309, 22305, 22302, -1, 22309, 22307, 22288, -1, 22293, 22296, 22308, -1, 22293, 22308, 22295, -1, 22293, 18836, 22296, -1, 22294, 22287, 22286, -1, 22294, 22295, 22305, -1, 22294, 22309, 22287, -1, 22294, 22305, 22309, -1, 22292, 22286, 18840, -1, 22292, 18838, 18836, -1, 22292, 18840, 18838, -1, 22310, 18905, 22298, -1, 22310, 18903, 18905, -1, 22311, 22298, 22300, -1, 22311, 22310, 22298, -1, 22312, 22300, 22303, -1, 22312, 22311, 22300, -1, 22313, 22303, 22306, -1, 22313, 22312, 22303, -1, 22314, 22306, 22308, -1, 22314, 22313, 22306, -1, 22315, 22308, 22296, -1, 22315, 22314, 22308, -1, 18798, 22296, 18800, -1, 18798, 22315, 22296, -1, 21783, 22316, 21781, -1, 21783, 22317, 22316, -1, 18798, 18797, 22315, -1, 22318, 21783, 21784, -1, 22319, 22317, 21783, -1, 22319, 21783, 22318, -1, 22319, 22318, 21784, -1, 22320, 22321, 22317, -1, 22320, 22317, 22319, -1, 22320, 22319, 21784, -1, 22322, 22321, 22320, -1, 22323, 18796, 18795, -1, 22323, 18797, 18796, -1, 22323, 22324, 22321, -1, 22323, 18795, 22324, -1, 22323, 22321, 22322, -1, 22325, 18903, 22310, -1, 22325, 21784, 18903, -1, 22326, 22310, 22311, -1, 22326, 21784, 22325, -1, 22326, 22325, 22310, -1, 22327, 22311, 22312, -1, 22327, 22312, 22313, -1, 22327, 22320, 21784, -1, 22327, 22326, 22311, -1, 22327, 21784, 22326, -1, 22328, 22313, 22314, -1, 22328, 22322, 22320, -1, 22328, 22320, 22327, -1, 22328, 22327, 22313, -1, 22329, 22314, 22315, -1, 22329, 22328, 22314, -1, 22329, 22323, 22322, -1, 22329, 18797, 22323, -1, 22329, 22322, 22328, -1, 22329, 22315, 18797, -1, 18795, 18779, 22330, -1, 22324, 18795, 22330, -1, 22321, 22331, 22332, -1, 22321, 22330, 22331, -1, 22321, 22324, 22330, -1, 22317, 22332, 22333, -1, 22317, 22321, 22332, -1, 22316, 22333, 21782, -1, 22316, 22317, 22333, -1, 21781, 22316, 21782, -1, 21788, 18819, 18821, -1, 18776, 18778, 18822, -1, 22333, 21787, 21782, -1, 18779, 18777, 22330, -1, 22334, 21788, 21787, -1, 22334, 18819, 21788, -1, 22335, 18834, 18819, -1, 22335, 18819, 22334, -1, 22336, 18835, 18834, -1, 22336, 18834, 22335, -1, 22337, 18822, 18835, -1, 22337, 18777, 18776, -1, 22337, 18835, 22336, -1, 22337, 18776, 18822, -1, 22338, 22333, 22332, -1, 22338, 22332, 22331, -1, 22338, 22331, 22330, -1, 22338, 22335, 22334, -1, 22338, 22334, 21787, -1, 22338, 18777, 22337, -1, 22338, 22337, 22336, -1, 22338, 21787, 22333, -1, 22338, 22336, 22335, -1, 22338, 22330, 18777, -1, 18782, 18784, 22339, -1, 18832, 18782, 22339, -1, 18830, 22339, 22340, -1, 18830, 18832, 22339, -1, 18828, 22340, 22341, -1, 18828, 18830, 22340, -1, 18826, 22341, 22342, -1, 18826, 18828, 22341, -1, 18825, 22342, 18857, -1, 18825, 18826, 22342, -1, 18860, 18802, 18804, -1, 18789, 18791, 18805, -1, 22342, 18859, 18857, -1, 18784, 18787, 22339, -1, 22343, 18860, 18859, -1, 22343, 18802, 18860, -1, 22344, 18817, 18802, -1, 22344, 18802, 22343, -1, 22345, 18818, 18817, -1, 22345, 18817, 22344, -1, 22346, 18805, 18818, -1, 22346, 18787, 18789, -1, 22346, 18818, 22345, -1, 22346, 18789, 18805, -1, 22347, 22342, 22341, -1, 22347, 22341, 22340, -1, 22347, 22340, 22339, -1, 22347, 22344, 22343, -1, 22347, 22343, 18859, -1, 22347, 18787, 22346, -1, 22347, 22346, 22345, -1, 22347, 18859, 22342, -1, 22347, 22345, 22344, -1, 22347, 22339, 18787, -1, 18815, 18762, 18801, -1, 18815, 18801, 22348, -1, 18813, 22348, 22349, -1, 18813, 18815, 22348, -1, 18811, 22350, 22351, -1, 18811, 22349, 22350, -1, 18811, 18813, 22349, -1, 18809, 22351, 21780, -1, 18809, 18811, 22351, -1, 18808, 18809, 21780, -1, 21786, 22352, 18921, -1, 18766, 18768, 22353, -1, 22351, 21785, 21780, -1, 22354, 21786, 21785, -1, 22354, 22352, 21786, -1, 22355, 22356, 22352, -1, 22355, 22352, 22354, -1, 22357, 22358, 22356, -1, 22357, 22359, 22358, -1, 22357, 22356, 22355, -1, 22360, 22361, 22359, -1, 22360, 22359, 22357, -1, 22362, 18764, 18766, -1, 22362, 22353, 22361, -1, 22362, 22361, 22360, -1, 22362, 18766, 22353, -1, 22363, 22355, 22354, -1, 22363, 22354, 21785, -1, 22363, 22362, 22360, -1, 22363, 18764, 22362, -1, 22363, 22360, 22357, -1, 22363, 22357, 22355, -1, 22364, 22363, 21785, -1, 22364, 18764, 22363, -1, 22365, 22351, 22350, -1, 22365, 22350, 22349, -1, 22365, 22349, 22348, -1, 22365, 22348, 18801, -1, 22365, 18801, 18764, -1, 22365, 18764, 22364, -1, 22365, 21785, 22351, -1, 22365, 22364, 21785, -1, 18913, 18921, 22352, -1, 22366, 22352, 22356, -1, 22366, 18913, 22352, -1, 22367, 22356, 22358, -1, 22367, 22366, 22356, -1, 22368, 22358, 22359, -1, 22368, 22367, 22358, -1, 22369, 22359, 22361, -1, 22369, 22368, 22359, -1, 22370, 22361, 22353, -1, 22370, 22369, 22361, -1, 22371, 22353, 18768, -1, 22371, 22370, 22353, -1, 18752, 22371, 18768, -1, 22372, 18759, 22373, -1, 22372, 22373, 22374, -1, 22375, 22367, 22368, -1, 22375, 22376, 22377, -1, 22375, 22378, 22376, -1, 18915, 22379, 18916, -1, 22375, 22377, 22367, -1, 22380, 22374, 22381, -1, 22380, 22381, 22382, -1, 22383, 22368, 22369, -1, 22383, 22375, 22368, -1, 22383, 22382, 22378, -1, 22383, 22378, 22375, -1, 22384, 18757, 18759, -1, 22384, 22374, 22380, -1, 22384, 18759, 22372, -1, 22384, 22372, 22374, -1, 22385, 22369, 22370, -1, 22385, 22380, 22382, -1, 22385, 22382, 22383, -1, 22385, 22383, 22369, -1, 22386, 22370, 22371, -1, 22386, 18755, 18757, -1, 22386, 22371, 18755, -1, 22386, 22380, 22385, -1, 22386, 18757, 22384, -1, 22386, 22385, 22370, -1, 22386, 22384, 22380, -1, 18759, 18751, 22373, -1, 18752, 18755, 22371, -1, 22387, 22388, 22379, -1, 22387, 18915, 18912, -1, 22387, 22379, 18915, -1, 22389, 22390, 22388, -1, 22389, 22388, 22387, -1, 22391, 18912, 18914, -1, 22391, 22387, 18912, -1, 22392, 22393, 22390, -1, 22392, 22390, 22389, -1, 22376, 22389, 22387, -1, 22376, 22387, 22391, -1, 22381, 22394, 22393, -1, 22381, 22393, 22392, -1, 22395, 18913, 22366, -1, 22395, 18914, 18913, -1, 22395, 22391, 18914, -1, 22378, 22392, 22389, -1, 22378, 22389, 22376, -1, 22374, 22373, 22394, -1, 22374, 22394, 22381, -1, 22377, 22366, 22367, -1, 22377, 22376, 22391, -1, 22377, 22395, 22366, -1, 22377, 22391, 22395, -1, 22382, 22381, 22392, -1, 22382, 22392, 22378, -1, 18751, 18750, 22396, -1, 22373, 18751, 22396, -1, 22394, 22396, 22397, -1, 22394, 22373, 22396, -1, 22393, 22397, 22398, -1, 22393, 22394, 22397, -1, 22390, 22398, 22399, -1, 22390, 22393, 22398, -1, 22388, 22399, 22400, -1, 22388, 22390, 22399, -1, 22379, 22400, 19493, -1, 22379, 19495, 19498, -1, 22379, 19493, 19495, -1, 22379, 22388, 22400, -1, 18916, 19500, 18917, -1, 18916, 19498, 19500, -1, 18916, 22379, 19498, -1, 22396, 18750, 18748, -1, 22396, 18748, 22401, -1, 22397, 22401, 22402, -1, 22397, 22396, 22401, -1, 22398, 22403, 22404, -1, 22398, 22402, 22403, -1, 22398, 22397, 22402, -1, 22399, 22404, 22405, -1, 22399, 22398, 22404, -1, 22400, 22405, 19504, -1, 22400, 22399, 22405, -1, 19493, 22400, 19504, -1, 18746, 22403, 22402, -1, 18746, 22402, 22401, -1, 18746, 22401, 18748, -1, 22406, 18746, 18744, -1, 22407, 22406, 18744, -1, 22407, 18746, 22406, -1, 22408, 22404, 22403, -1, 22408, 22403, 18746, -1, 22408, 22407, 18744, -1, 22408, 18746, 22407, -1, 22409, 22405, 22404, -1, 22409, 22404, 22408, -1, 22410, 19504, 22405, -1, 22410, 19468, 19504, -1, 22410, 22405, 22409, -1, 22411, 18744, 18742, -1, 22412, 22408, 18744, -1, 22412, 18744, 22411, -1, 22413, 22408, 22412, -1, 22413, 22409, 22408, -1, 22414, 18742, 18740, -1, 22414, 18740, 22415, -1, 22416, 19461, 19468, -1, 22416, 22410, 22409, -1, 22416, 22409, 22413, -1, 22416, 19468, 22410, -1, 22417, 22415, 22418, -1, 22417, 22411, 18742, -1, 22417, 18742, 22414, -1, 22417, 22414, 22415, -1, 22419, 22418, 22420, -1, 22419, 22412, 22411, -1, 22419, 22411, 22417, -1, 22419, 22417, 22418, -1, 22421, 22422, 22423, -1, 22421, 22420, 22422, -1, 22421, 22413, 22412, -1, 22421, 22412, 22419, -1, 22421, 22419, 22420, -1, 22424, 22423, 19100, -1, 22424, 19451, 19461, -1, 22424, 19100, 19451, -1, 22424, 22421, 22423, -1, 22424, 19461, 22416, -1, 22424, 22416, 22413, -1, 22424, 22413, 22421, -1, 18740, 18739, 22425, -1, 22415, 22425, 22426, -1, 22415, 18740, 22425, -1, 22418, 22426, 22427, -1, 22418, 22415, 22426, -1, 22420, 22427, 22428, -1, 22420, 22418, 22427, -1, 22422, 22428, 22429, -1, 22422, 22420, 22428, -1, 22423, 22429, 19101, -1, 22423, 22422, 22429, -1, 19100, 22423, 19101, -1, 22430, 16872, 16870, -1, 22430, 16870, 22431, -1, 22432, 22431, 16799, -1, 22432, 22430, 22431, -1, 16798, 22432, 16799, -1, 22433, 17066, 17026, -1, 22433, 17026, 17024, -1, 22434, 17016, 16908, -1, 22434, 17024, 17016, -1, 22434, 22433, 17024, -1, 16913, 22434, 16908, -1, 17082, 22435, 17081, -1, 17082, 22436, 22435, -1, 17082, 22437, 22436, -1, 17082, 22438, 22437, -1, 17082, 22439, 22438, -1, 17082, 16907, 22439, -1, 16909, 16907, 17082, -1, 16917, 16909, 17067, -1, 17079, 16929, 17078, -1, 16914, 16915, 17080, -1, 22440, 17082, 17067, -1, 22441, 17082, 22440, -1, 22441, 22440, 17067, -1, 22442, 17082, 22441, -1, 22442, 22441, 17067, -1, 22443, 17082, 22442, -1, 22443, 16909, 17082, -1, 22443, 17067, 16909, -1, 22443, 22442, 17067, -1, 22444, 17067, 17068, -1, 22445, 22444, 17068, -1, 22445, 17067, 22444, -1, 22446, 22445, 17068, -1, 22446, 17067, 22445, -1, 22447, 22446, 17068, -1, 22447, 17067, 22446, -1, 22448, 17067, 22447, -1, 22448, 22447, 17068, -1, 22448, 16917, 17067, -1, 22448, 17068, 16917, -1, 22449, 17069, 17070, -1, 22449, 17068, 17069, -1, 22450, 17068, 22449, -1, 22451, 17068, 22450, -1, 22452, 17068, 22451, -1, 22453, 17068, 22452, -1, 22453, 22452, 16919, -1, 22454, 22453, 16919, -1, 22454, 17068, 22453, -1, 22455, 16919, 16917, -1, 22455, 17068, 22454, -1, 22455, 22454, 16919, -1, 22455, 16917, 17068, -1, 22456, 22449, 17070, -1, 22456, 17070, 17071, -1, 22457, 22449, 22456, -1, 22457, 22450, 22449, -1, 22458, 22451, 22450, -1, 22458, 22457, 16920, -1, 22458, 22450, 22457, -1, 22459, 22451, 22458, -1, 22459, 22452, 22451, -1, 22459, 16919, 22452, -1, 22459, 22458, 16920, -1, 22460, 16919, 22459, -1, 22460, 22459, 16920, -1, 22461, 22460, 16920, -1, 22461, 16919, 22460, -1, 22462, 16920, 16919, -1, 22462, 22461, 16920, -1, 22462, 16919, 22461, -1, 22463, 22456, 17071, -1, 22464, 22457, 22456, -1, 22464, 22456, 22463, -1, 22464, 16920, 22457, -1, 22465, 16920, 22464, -1, 22466, 16920, 22465, -1, 22467, 22466, 16921, -1, 22467, 16920, 22466, -1, 22468, 22467, 16921, -1, 22468, 16920, 22467, -1, 22469, 16921, 16920, -1, 22469, 22468, 16921, -1, 22469, 16920, 22468, -1, 22470, 17072, 17073, -1, 22470, 17071, 17072, -1, 22470, 22463, 17071, -1, 22471, 22464, 22463, -1, 22471, 22470, 17073, -1, 22471, 22463, 22470, -1, 22472, 22465, 22464, -1, 22472, 22464, 22471, -1, 22472, 22471, 17073, -1, 22473, 16921, 22466, -1, 22473, 22466, 22465, -1, 22473, 22465, 22472, -1, 22473, 22472, 17073, -1, 22474, 16921, 22473, -1, 22475, 16921, 22474, -1, 22476, 16922, 16921, -1, 22476, 16921, 22475, -1, 22477, 17073, 17074, -1, 22478, 17073, 22477, -1, 22478, 22477, 17074, -1, 22479, 17073, 22478, -1, 22479, 22478, 17074, -1, 22479, 22473, 17073, -1, 22480, 22479, 17074, -1, 22480, 22474, 22473, -1, 22480, 22473, 22479, -1, 22481, 22474, 22480, -1, 22481, 22480, 17074, -1, 22481, 22475, 22474, -1, 22482, 22476, 22475, -1, 22482, 22475, 22481, -1, 22482, 22481, 17074, -1, 22482, 16923, 16922, -1, 22482, 16922, 22476, -1, 22483, 17074, 17075, -1, 22484, 17074, 22483, -1, 22484, 22483, 17075, -1, 22485, 17074, 22484, -1, 22485, 22484, 17075, -1, 22486, 17074, 22485, -1, 22486, 22485, 17075, -1, 22487, 22482, 17074, -1, 22487, 16924, 16923, -1, 22487, 16923, 22482, -1, 22487, 22486, 17075, -1, 22487, 17074, 22486, -1, 22488, 17075, 17076, -1, 22489, 17075, 22488, -1, 22489, 22488, 17076, -1, 22490, 17075, 22489, -1, 22490, 22489, 17076, -1, 22491, 17075, 22490, -1, 22491, 22490, 17076, -1, 22492, 16924, 22487, -1, 22492, 22487, 17075, -1, 22492, 22491, 17076, -1, 22492, 17075, 22491, -1, 22493, 17076, 17077, -1, 22494, 17076, 22493, -1, 22494, 22493, 17077, -1, 22495, 17076, 22494, -1, 22495, 22494, 17077, -1, 22496, 17076, 22495, -1, 22497, 16924, 22492, -1, 22497, 16926, 16924, -1, 22497, 16927, 16926, -1, 22497, 22492, 17076, -1, 22497, 17076, 22496, -1, 22498, 17078, 16928, -1, 22498, 17077, 17078, -1, 22499, 17077, 22498, -1, 22499, 22498, 16928, -1, 22500, 17077, 22499, -1, 22500, 22499, 16928, -1, 22501, 22500, 16928, -1, 22501, 17077, 22500, -1, 22502, 22501, 16928, -1, 22502, 22495, 17077, -1, 22502, 17077, 22501, -1, 22503, 22496, 22495, -1, 22503, 22502, 16928, -1, 22503, 22495, 22502, -1, 22504, 16928, 16927, -1, 22504, 22496, 22503, -1, 22504, 16927, 22497, -1, 22504, 22497, 22496, -1, 22504, 22503, 16928, -1, 22505, 16928, 17078, -1, 22505, 17078, 16929, -1, 22506, 16928, 22505, -1, 22506, 22505, 16929, -1, 22507, 22506, 16929, -1, 22507, 16928, 22506, -1, 22508, 22507, 16929, -1, 22508, 16928, 22507, -1, 22509, 22508, 16929, -1, 22509, 16928, 22508, -1, 22510, 22509, 16929, -1, 22510, 16928, 22509, -1, 22511, 16928, 22510, -1, 22511, 16929, 16928, -1, 22511, 22510, 16929, -1, 22512, 16929, 17079, -1, 22513, 16929, 22512, -1, 22514, 16929, 22513, -1, 22515, 16929, 22514, -1, 22516, 16929, 22515, -1, 22516, 22515, 16916, -1, 22517, 16929, 22516, -1, 22517, 22516, 16916, -1, 22518, 16929, 22517, -1, 22518, 16916, 16929, -1, 22518, 22517, 16916, -1, 22519, 22512, 17079, -1, 22519, 22513, 22512, -1, 22519, 22514, 22513, -1, 22519, 22515, 22514, -1, 22519, 16916, 22515, -1, 22519, 17079, 17080, -1, 22520, 16916, 22519, -1, 22520, 22519, 17080, -1, 22521, 22520, 17080, -1, 22521, 16916, 22520, -1, 22522, 17080, 16915, -1, 22522, 16915, 16916, -1, 22522, 22521, 17080, -1, 22522, 16916, 22521, -1, 22523, 17060, 17061, -1, 22523, 17061, 17062, -1, 22523, 17062, 17063, -1, 22523, 17063, 17064, -1, 22523, 17064, 17065, -1, 22523, 17080, 17060, -1, 22524, 17065, 17066, -1, 22524, 22523, 17065, -1, 22524, 17080, 22523, -1, 22525, 17066, 22433, -1, 22525, 22524, 17066, -1, 22525, 17080, 22524, -1, 22526, 22433, 22434, -1, 22526, 22434, 16913, -1, 22526, 16914, 17080, -1, 22526, 16913, 16914, -1, 22526, 22525, 22433, -1, 22526, 17080, 22525, -1, 17012, 17081, 22435, -1, 17047, 22435, 22436, -1, 17047, 17012, 22435, -1, 17042, 22436, 22437, -1, 17042, 17047, 22436, -1, 17030, 22437, 22438, -1, 17030, 17042, 22437, -1, 17025, 22438, 22439, -1, 17025, 17030, 22438, -1, 17017, 22439, 16907, -1, 17017, 17025, 22439, -1, 16906, 17017, 16907, -1, 22527, 22528, 22529, -1, 22530, 22531, 22532, -1, 22533, 17014, 17003, -1, 22527, 17019, 22534, -1, 22527, 22534, 22535, -1, 22533, 22536, 22537, -1, 22527, 22535, 22528, -1, 22533, 22537, 22538, -1, 22533, 17003, 22536, -1, 22530, 22539, 22531, -1, 22540, 22541, 22542, -1, 22543, 22544, 22545, -1, 22543, 22538, 22544, -1, 22540, 22532, 22541, -1, 22546, 22542, 22547, -1, 22548, 22549, 22550, -1, 22548, 22545, 22549, -1, 17001, 17015, 22551, -1, 22552, 22553, 22554, -1, 22546, 22547, 22555, -1, 22556, 22550, 22557, -1, 22552, 22554, 22558, -1, 22559, 22555, 22560, -1, 22556, 22557, 22561, -1, 22562, 22553, 22552, -1, 22559, 22560, 22563, -1, 22562, 22564, 22553, -1, 22565, 22561, 22566, -1, 22565, 22566, 22567, -1, 22568, 22563, 22569, -1, 22568, 22569, 22570, -1, 22571, 22572, 22539, -1, 22571, 17036, 17053, -1, 22573, 22574, 22575, -1, 22576, 22558, 22577, -1, 22573, 22567, 22574, -1, 22576, 22552, 22558, -1, 22571, 22539, 22530, -1, 22571, 17053, 22572, -1, 22578, 17008, 17014, -1, 22579, 22530, 22532, -1, 22578, 17014, 22533, -1, 22580, 22564, 22562, -1, 22578, 22533, 22538, -1, 22578, 22538, 22543, -1, 22580, 22581, 22564, -1, 22579, 22532, 22540, -1, 22582, 22545, 22548, -1, 22582, 22543, 22545, -1, 22583, 22540, 22542, -1, 22584, 22548, 22550, -1, 22583, 22542, 22546, -1, 22584, 22550, 22556, -1, 22585, 22562, 22552, -1, 22585, 22552, 22576, -1, 22586, 22555, 22559, -1, 22586, 22546, 22555, -1, 22587, 22561, 22565, -1, 22588, 22577, 22589, -1, 22587, 22556, 22561, -1, 22588, 22576, 22577, -1, 22590, 22563, 22568, -1, 22591, 22592, 22581, -1, 22591, 22581, 22580, -1, 22590, 22559, 22563, -1, 22593, 22565, 22567, -1, 22594, 22595, 22596, -1, 22593, 22567, 22573, -1, 22594, 22568, 22570, -1, 22597, 22580, 22562, -1, 22594, 22598, 22595, -1, 22594, 22570, 22598, -1, 22597, 22562, 22585, -1, 22599, 17028, 17036, -1, 22600, 22575, 22601, -1, 22602, 22576, 22588, -1, 22599, 22530, 22579, -1, 22600, 22573, 22575, -1, 22599, 17036, 22571, -1, 22599, 22571, 22530, -1, 22603, 17006, 17008, -1, 22603, 17008, 22578, -1, 22603, 22578, 22543, -1, 22604, 22579, 22540, -1, 22603, 22543, 22582, -1, 22604, 22540, 22583, -1, 22602, 22585, 22576, -1, 22605, 22589, 22606, -1, 22607, 22546, 22586, -1, 22608, 22582, 22548, -1, 22605, 22588, 22589, -1, 22608, 22548, 22584, -1, 22607, 22583, 22546, -1, 22531, 22584, 22556, -1, 22537, 22609, 22592, -1, 22531, 22556, 22587, -1, 22537, 22592, 22591, -1, 22610, 22586, 22559, -1, 22544, 22591, 22580, -1, 22544, 22580, 22597, -1, 22610, 22559, 22590, -1, 22541, 22587, 22565, -1, 22611, 22596, 22612, -1, 22541, 22565, 22593, -1, 22611, 22590, 22568, -1, 22611, 22568, 22594, -1, 22611, 22594, 22596, -1, 22613, 17023, 17028, -1, 22549, 22585, 22602, -1, 22547, 22593, 22573, -1, 22549, 22597, 22585, -1, 22613, 22579, 22604, -1, 22547, 22573, 22600, -1, 22613, 17028, 22599, -1, 22613, 22599, 22579, -1, 22614, 22604, 22583, -1, 22614, 22583, 22607, -1, 22557, 22602, 22588, -1, 22560, 22601, 22615, -1, 22560, 22600, 22601, -1, 22557, 22588, 22605, -1, 22616, 17058, 17006, -1, 22616, 17006, 22603, -1, 22617, 22607, 22586, -1, 22566, 22606, 22618, -1, 22617, 22586, 22610, -1, 22616, 22603, 22582, -1, 22616, 22582, 22608, -1, 22566, 22605, 22606, -1, 22536, 17003, 17034, -1, 22619, 22612, 22620, -1, 22619, 22611, 22612, -1, 22539, 22584, 22531, -1, 22536, 22621, 22609, -1, 22619, 22610, 22590, -1, 22539, 22608, 22584, -1, 22536, 17034, 22621, -1, 22536, 22609, 22537, -1, 22619, 22590, 22611, -1, 22622, 22604, 22614, -1, 22622, 17021, 17023, -1, 22532, 22587, 22541, -1, 22622, 17023, 22613, -1, 22622, 22613, 22604, -1, 22532, 22531, 22587, -1, 22538, 22591, 22544, -1, 22538, 22537, 22591, -1, 22545, 22597, 22549, -1, 22535, 22614, 22607, -1, 22535, 22607, 22617, -1, 22542, 22541, 22593, -1, 22542, 22593, 22547, -1, 22545, 22544, 22597, -1, 22623, 22620, 22624, -1, 22623, 22619, 22620, -1, 22623, 22617, 22610, -1, 22550, 22549, 22602, -1, 22623, 22610, 22619, -1, 22550, 22602, 22557, -1, 22534, 17019, 17021, -1, 22555, 22547, 22600, -1, 22555, 22600, 22560, -1, 22534, 17021, 22622, -1, 22534, 22622, 22614, -1, 22534, 22614, 22535, -1, 22561, 22557, 22605, -1, 22561, 22605, 22566, -1, 22528, 22624, 22529, -1, 22563, 22615, 22569, -1, 22528, 22623, 22624, -1, 22563, 22560, 22615, -1, 22528, 22535, 22617, -1, 22572, 17053, 17058, -1, 22528, 22617, 22623, -1, 22572, 17058, 22616, -1, 22567, 22618, 22574, -1, 22527, 22529, 22551, -1, 22527, 17015, 17019, -1, 22572, 22616, 22608, -1, 22567, 22566, 22618, -1, 22527, 22551, 17015, -1, 22572, 22608, 22539, -1, 22625, 22598, 22626, -1, 22595, 22598, 22625, -1, 22626, 22570, 22627, -1, 22598, 22570, 22626, -1, 22627, 22569, 22628, -1, 22570, 22569, 22627, -1, 22628, 22615, 22629, -1, 22569, 22615, 22628, -1, 22629, 22601, 22630, -1, 22615, 22601, 22629, -1, 22630, 22575, 22631, -1, 22601, 22575, 22630, -1, 22631, 22574, 22632, -1, 22575, 22574, 22631, -1, 22632, 22618, 22633, -1, 22574, 22618, 22632, -1, 22633, 22606, 22634, -1, 22618, 22606, 22633, -1, 22634, 22589, 22635, -1, 22606, 22589, 22634, -1, 22635, 22577, 22636, -1, 22589, 22577, 22635, -1, 22636, 22558, 22637, -1, 22577, 22558, 22636, -1, 22637, 22554, 22638, -1, 22558, 22554, 22637, -1, 22639, 22625, 22640, -1, 22595, 22625, 22639, -1, 22641, 22642, 22643, -1, 22642, 22644, 22643, -1, 22643, 22645, 22646, -1, 22644, 22645, 22643, -1, 22646, 22647, 22648, -1, 22645, 22647, 22646, -1, 22648, 22649, 22650, -1, 22647, 22649, 22648, -1, 22651, 22652, 22653, -1, 22650, 22652, 22651, -1, 22649, 22652, 22650, -1, 22653, 22654, 22655, -1, 22652, 22654, 22653, -1, 22655, 22656, 22657, -1, 22654, 22656, 22655, -1, 22657, 22658, 22659, -1, 22656, 22658, 22657, -1, 22659, 22660, 22661, -1, 22658, 22660, 22659, -1, 22661, 22662, 22663, -1, 22660, 22662, 22661, -1, 22663, 22664, 22665, -1, 22662, 22664, 22663, -1, 22665, 22666, 22640, -1, 22664, 22666, 22665, -1, 22666, 22639, 22640, -1, 22641, 22638, 22642, -1, 22638, 22554, 22642, -1, 22667, 22554, 22553, -1, 22667, 22642, 22554, -1, 22668, 22553, 22564, -1, 22668, 22667, 22553, -1, 22669, 22564, 22581, -1, 22669, 22668, 22564, -1, 22670, 22581, 22592, -1, 22670, 22669, 22581, -1, 22671, 22592, 22609, -1, 22671, 22670, 22592, -1, 22672, 22609, 22621, -1, 22672, 22671, 22609, -1, 17033, 22621, 17034, -1, 17033, 22672, 22621, -1, 22596, 22595, 22639, -1, 22596, 22639, 22673, -1, 22612, 22673, 22674, -1, 22612, 22596, 22673, -1, 22620, 22674, 22675, -1, 22620, 22612, 22674, -1, 22624, 22675, 22676, -1, 22624, 22620, 22675, -1, 22529, 22676, 22677, -1, 22529, 22624, 22676, -1, 22551, 22677, 22678, -1, 22551, 22529, 22677, -1, 17001, 22678, 17054, -1, 17001, 22551, 22678, -1, 22679, 17049, 22680, -1, 22679, 22681, 22682, -1, 22683, 22684, 22685, -1, 22683, 22685, 22686, -1, 22687, 22686, 22688, -1, 22689, 22682, 22690, -1, 22689, 22690, 22691, -1, 22687, 22688, 22692, -1, 22693, 22692, 22694, -1, 22695, 22691, 22696, -1, 22695, 22696, 22697, -1, 17033, 17031, 22672, -1, 22693, 22694, 22698, -1, 22699, 22700, 22701, -1, 22702, 22673, 22639, -1, 22703, 22698, 22704, -1, 22702, 22639, 22666, -1, 22699, 22697, 22700, -1, 22703, 22704, 22705, -1, 22706, 22673, 22702, -1, 22707, 22701, 22708, -1, 22707, 22708, 22709, -1, 22706, 22674, 22673, -1, 22710, 22705, 22647, -1, 22710, 22647, 22645, -1, 22711, 22712, 22684, -1, 22711, 17056, 17051, -1, 22713, 22656, 22654, -1, 22713, 22709, 22656, -1, 22711, 17051, 22712, -1, 22714, 22666, 22664, -1, 22711, 22684, 22683, -1, 22714, 22702, 22666, -1, 22715, 22683, 22686, -1, 22716, 17038, 17044, -1, 22715, 22686, 22687, -1, 22716, 22682, 22689, -1, 22716, 22679, 22682, -1, 22716, 17044, 22679, -1, 22717, 22674, 22706, -1, 22717, 22675, 22674, -1, 22718, 22691, 22695, -1, 22718, 22689, 22691, -1, 22719, 22706, 22702, -1, 22720, 22692, 22693, -1, 22719, 22702, 22714, -1, 22720, 22687, 22692, -1, 22721, 22695, 22697, -1, 22721, 22697, 22699, -1, 22722, 22698, 22703, -1, 17049, 17054, 22678, -1, 22723, 22701, 22707, -1, 22724, 22664, 22662, -1, 22722, 22693, 22698, -1, 22723, 22699, 22701, -1, 22724, 22714, 22664, -1, 22725, 22705, 22710, -1, 22725, 22703, 22705, -1, 22726, 22676, 22675, -1, 22726, 22675, 22717, -1, 22727, 22642, 22667, -1, 22728, 22707, 22709, -1, 22727, 22710, 22645, -1, 22728, 22709, 22713, -1, 22727, 22644, 22642, -1, 22729, 22706, 22719, -1, 22727, 22645, 22644, -1, 22729, 22717, 22706, -1, 22730, 17059, 17056, -1, 22730, 22711, 22683, -1, 22730, 17056, 22711, -1, 22731, 22654, 22652, -1, 22732, 22714, 22724, -1, 22730, 22683, 22715, -1, 22731, 22713, 22654, -1, 22733, 22687, 22720, -1, 22734, 17041, 17038, -1, 22734, 17038, 22716, -1, 22733, 22715, 22687, -1, 22734, 22716, 22689, -1, 22732, 22719, 22714, -1, 22734, 22689, 22718, -1, 22735, 22718, 22695, -1, 22735, 22695, 22721, -1, 22736, 22662, 22660, -1, 22736, 22724, 22662, -1, 22737, 22720, 22693, -1, 22737, 22693, 22722, -1, 22685, 22721, 22699, -1, 22685, 22699, 22723, -1, 22681, 22677, 22676, -1, 22681, 22676, 22726, -1, 22738, 22722, 22703, -1, 22738, 22703, 22725, -1, 22739, 22667, 22668, -1, 22690, 22717, 22729, -1, 22688, 22723, 22707, -1, 22739, 22725, 22710, -1, 22739, 22727, 22667, -1, 22688, 22707, 22728, -1, 22690, 22726, 22717, -1, 22739, 22710, 22727, -1, 22694, 22728, 22713, -1, 22740, 17010, 17059, -1, 22696, 22719, 22732, -1, 22740, 17059, 22730, -1, 22740, 22730, 22715, -1, 22740, 22715, 22733, -1, 22696, 22729, 22719, -1, 22694, 22713, 22731, -1, 22741, 22733, 22720, -1, 22741, 22720, 22737, -1, 22704, 22652, 22649, -1, 22700, 22732, 22724, -1, 22704, 22731, 22652, -1, 22700, 22724, 22736, -1, 22742, 17048, 17041, -1, 22742, 22718, 22735, -1, 22743, 22737, 22722, -1, 22742, 17041, 22734, -1, 22708, 22660, 22658, -1, 22743, 22722, 22738, -1, 22742, 22734, 22718, -1, 22708, 22736, 22660, -1, 22744, 22668, 22669, -1, 22680, 22677, 22681, -1, 22744, 22725, 22739, -1, 22684, 22721, 22685, -1, 22680, 22678, 22677, -1, 22744, 22739, 22668, -1, 22684, 22735, 22721, -1, 22744, 22738, 22725, -1, 22680, 17049, 22678, -1, 22745, 17011, 17010, -1, 22745, 22733, 22741, -1, 22745, 17010, 22740, -1, 22686, 22685, 22723, -1, 22682, 22726, 22690, -1, 22745, 22740, 22733, -1, 22686, 22723, 22688, -1, 22682, 22681, 22726, -1, 22691, 22729, 22696, -1, 22746, 22741, 22737, -1, 22692, 22728, 22694, -1, 22746, 22737, 22743, -1, 22691, 22690, 22729, -1, 22692, 22688, 22728, -1, 22747, 22669, 22670, -1, 22697, 22732, 22700, -1, 22747, 22744, 22669, -1, 22747, 22743, 22738, -1, 22747, 22738, 22744, -1, 22697, 22696, 22732, -1, 22748, 17018, 17011, -1, 22698, 22694, 22731, -1, 22698, 22731, 22704, -1, 22748, 17011, 22745, -1, 22701, 22736, 22708, -1, 22748, 22745, 22741, -1, 22748, 22741, 22746, -1, 22749, 22670, 22671, -1, 22701, 22700, 22736, -1, 22749, 22746, 22743, -1, 22705, 22649, 22647, -1, 22749, 22747, 22670, -1, 22705, 22704, 22649, -1, 22712, 17051, 17048, -1, 22749, 22743, 22747, -1, 22750, 22671, 22672, -1, 22712, 17048, 22742, -1, 22709, 22658, 22656, -1, 22750, 17031, 17018, -1, 22712, 22742, 22735, -1, 22709, 22708, 22658, -1, 22750, 22672, 17031, -1, 22712, 22735, 22684, -1, 22750, 22746, 22749, -1, 22679, 17044, 17049, -1, 22750, 22748, 22746, -1, 22750, 22749, 22671, -1, 22679, 22680, 22681, -1, 22750, 17018, 22748, -1, 22751, 16856, 16828, -1, 22752, 16856, 22751, -1, 22752, 22751, 16828, -1, 22753, 16856, 22752, -1, 22753, 22754, 16856, -1, 22755, 16828, 16834, -1, 22756, 16828, 22755, -1, 22757, 22754, 22753, -1, 22757, 22758, 22754, -1, 22757, 16828, 22756, -1, 22757, 22756, 22758, -1, 22757, 22752, 16828, -1, 22757, 22753, 22752, -1, 22759, 16834, 16847, -1, 16856, 22760, 16853, -1, 16856, 22761, 22760, -1, 22759, 22755, 16834, -1, 16856, 22762, 22761, -1, 16856, 22763, 22762, -1, 22764, 22755, 22759, -1, 16856, 22765, 22763, -1, 22764, 22756, 22755, -1, 16856, 22766, 22765, -1, 16856, 22767, 22766, -1, 22764, 22758, 22756, -1, 22764, 22759, 22768, -1, 22769, 22764, 22768, -1, 22769, 22758, 22764, -1, 22769, 22768, 22758, -1, 22770, 16847, 16845, -1, 22770, 22759, 16847, -1, 22770, 22768, 22759, -1, 22754, 22767, 16856, -1, 22771, 22768, 22770, -1, 22772, 22768, 22771, -1, 22772, 22773, 22768, -1, 22772, 22771, 22773, -1, 22774, 16845, 16844, -1, 22774, 22770, 16845, -1, 22775, 22770, 22774, -1, 22775, 22773, 22771, -1, 22775, 22774, 22776, -1, 22775, 22771, 22770, -1, 22777, 22775, 22776, -1, 22777, 22776, 22773, -1, 22777, 22773, 22775, -1, 22778, 16843, 16842, -1, 22778, 16844, 16843, -1, 22778, 22776, 22774, -1, 22778, 22774, 16844, -1, 22779, 22776, 22778, -1, 22779, 22778, 22780, -1, 22781, 22780, 22776, -1, 22781, 22779, 22780, -1, 22781, 22776, 22779, -1, 22782, 16842, 16841, -1, 22782, 22778, 16842, -1, 22782, 22780, 22778, -1, 22783, 22782, 22784, -1, 22783, 22780, 22782, -1, 22785, 22784, 22780, -1, 22785, 22783, 22784, -1, 22785, 22780, 22783, -1, 22786, 22784, 22782, -1, 22786, 22782, 16841, -1, 22786, 16841, 22787, -1, 22788, 22784, 22786, -1, 22788, 22786, 22787, -1, 22789, 22787, 22784, -1, 22789, 22788, 22787, -1, 22789, 22784, 22788, -1, 22790, 16839, 22791, -1, 22790, 22787, 16839, -1, 22792, 22790, 22791, -1, 22792, 22787, 22790, -1, 22793, 22791, 22787, -1, 22793, 22792, 22791, -1, 22793, 22787, 22792, -1, 22794, 22791, 16835, -1, 22795, 22791, 22794, -1, 22787, 16841, 16839, -1, 22796, 22797, 22791, -1, 22796, 22791, 22795, -1, 22796, 22795, 22797, -1, 22798, 22794, 16835, -1, 22798, 16835, 16837, -1, 16835, 22791, 16839, -1, 22799, 22794, 22798, -1, 22799, 22798, 16837, -1, 22799, 22795, 22794, -1, 22799, 22797, 22795, -1, 22800, 22797, 22799, -1, 22800, 22799, 16837, -1, 22801, 22802, 22797, -1, 22801, 22803, 22802, -1, 22801, 22797, 22800, -1, 22804, 16837, 16838, -1, 22805, 16837, 22804, -1, 22805, 22800, 16837, -1, 22805, 22804, 16838, -1, 22806, 22803, 22801, -1, 22806, 22801, 22800, -1, 22806, 22800, 22805, -1, 22807, 16838, 16840, -1, 22808, 16838, 22807, -1, 22808, 22805, 16838, -1, 16849, 22809, 16840, -1, 22808, 22807, 22810, -1, 22811, 22805, 22808, -1, 22811, 22808, 22810, -1, 22812, 22809, 16849, -1, 22811, 22813, 22803, -1, 22811, 22810, 22813, -1, 22811, 22806, 22805, -1, 22814, 22809, 22812, -1, 22811, 22803, 22806, -1, 22815, 16840, 22809, -1, 22816, 22809, 22814, -1, 22815, 22807, 16840, -1, 22817, 22815, 22809, -1, 22817, 22807, 22815, -1, 22818, 22809, 22816, -1, 22817, 22810, 22807, -1, 22819, 22817, 22809, -1, 22819, 22810, 22817, -1, 22820, 22809, 22818, -1, 22819, 22809, 22810, -1, 22821, 22809, 22820, -1, 22822, 22809, 22821, -1, 22822, 22823, 22809, -1, 22809, 22824, 22810, -1, 22823, 22824, 22809, -1, 22813, 22825, 22803, -1, 22810, 22825, 22813, -1, 22824, 22825, 22810, -1, 22803, 22826, 22802, -1, 22825, 22826, 22803, -1, 22802, 22827, 22797, -1, 22826, 22827, 22802, -1, 22791, 22828, 22787, -1, 22797, 22828, 22791, -1, 22827, 22828, 22797, -1, 22787, 22829, 22784, -1, 22828, 22829, 22787, -1, 22784, 22830, 22780, -1, 22829, 22830, 22784, -1, 22776, 22831, 22773, -1, 22780, 22831, 22776, -1, 22830, 22831, 22780, -1, 22773, 22832, 22768, -1, 22831, 22832, 22773, -1, 22768, 22833, 22758, -1, 22832, 22833, 22768, -1, 22758, 22834, 22754, -1, 22833, 22834, 22758, -1, 22754, 22835, 22767, -1, 22834, 22835, 22754, -1, 22835, 22836, 22767, -1, 22823, 22822, 22837, -1, 22767, 22836, 22838, -1, 22835, 22839, 22840, -1, 22834, 22839, 22835, -1, 22834, 22841, 22839, -1, 22833, 22841, 22834, -1, 22833, 22832, 22841, -1, 22841, 22832, 22842, -1, 22843, 22844, 22838, -1, 22838, 22845, 22843, -1, 22842, 22831, 22846, -1, 22844, 22847, 22838, -1, 22832, 22831, 22842, -1, 22838, 22848, 22845, -1, 22838, 22849, 22850, -1, 22847, 22849, 22838, -1, 22838, 22851, 22848, -1, 22852, 22853, 22854, -1, 22855, 22853, 22852, -1, 22856, 22857, 22855, -1, 22855, 22857, 22853, -1, 22846, 22830, 22858, -1, 22859, 22860, 22849, -1, 22850, 22860, 22856, -1, 22831, 22830, 22846, -1, 22861, 22823, 22862, -1, 22849, 22860, 22850, -1, 22863, 22823, 22861, -1, 22856, 22860, 22857, -1, 22862, 22823, 22837, -1, 22864, 22829, 22865, -1, 22866, 22837, 22859, -1, 22858, 22829, 22864, -1, 22830, 22829, 22858, -1, 22859, 22837, 22860, -1, 22863, 22824, 22823, -1, 22866, 22867, 22837, -1, 22838, 22836, 22851, -1, 22829, 22828, 22865, -1, 22868, 22825, 22863, -1, 22863, 22825, 22824, -1, 22869, 22827, 22870, -1, 22867, 22871, 22837, -1, 22865, 22827, 22869, -1, 22828, 22827, 22865, -1, 22870, 22826, 22868, -1, 22827, 22826, 22870, -1, 22871, 22872, 22837, -1, 22868, 22826, 22825, -1, 22836, 22873, 22851, -1, 22872, 22874, 22837, -1, 22836, 22840, 22873, -1, 22835, 22840, 22836, -1, 22874, 22862, 22837, -1, 22875, 22864, 22865, -1, 22876, 22877, 22878, -1, 22879, 22868, 22863, -1, 22875, 22880, 22881, -1, 22876, 22882, 22877, -1, 22875, 22865, 22883, -1, 22879, 22884, 22885, -1, 22875, 22883, 22880, -1, 22879, 22885, 22886, -1, 22887, 22888, 22873, -1, 22887, 22889, 22888, -1, 22879, 22863, 22884, -1, 22887, 22840, 22839, -1, 22887, 22873, 22840, -1, 22887, 22890, 22876, -1, 22887, 22839, 22891, -1, 22887, 22876, 22889, -1, 22892, 22881, 22893, -1, 22887, 22891, 22890, -1, 22892, 22893, 22894, -1, 22895, 22896, 22897, -1, 22898, 22899, 22900, -1, 22895, 22886, 22896, -1, 22898, 22894, 22899, -1, 22901, 22902, 22903, -1, 22901, 22897, 22902, -1, 22904, 22900, 22905, -1, 22906, 22907, 22908, -1, 22909, 22903, 22910, -1, 22906, 22908, 22911, -1, 22904, 22905, 22912, -1, 22909, 22910, 22913, -1, 22914, 22912, 22915, -1, 22916, 22907, 22906, -1, 22916, 22917, 22907, -1, 22914, 22915, 22918, -1, 22919, 22913, 22920, -1, 22919, 22920, 22921, -1, 22922, 22918, 22923, -1, 22922, 22923, 22924, -1, 22925, 22911, 22926, -1, 22927, 22928, 22929, -1, 22925, 22906, 22911, -1, 22930, 22858, 22864, -1, 22927, 22921, 22928, -1, 22930, 22881, 22892, -1, 22931, 22870, 22868, -1, 22930, 22875, 22881, -1, 22932, 22917, 22916, -1, 22931, 22868, 22879, -1, 22930, 22864, 22875, -1, 22931, 22879, 22886, -1, 22932, 22933, 22917, -1, 22931, 22886, 22895, -1, 22934, 22894, 22898, -1, 22935, 22897, 22901, -1, 22934, 22892, 22894, -1, 22935, 22895, 22897, -1, 22936, 22916, 22906, -1, 22936, 22906, 22925, -1, 22863, 22861, 22937, -1, 22938, 22900, 22904, -1, 22939, 22901, 22903, -1, 22939, 22903, 22909, -1, 22938, 22898, 22900, -1, 22940, 22913, 22919, -1, 22941, 22926, 22942, -1, 22943, 22904, 22912, -1, 22943, 22912, 22914, -1, 22940, 22909, 22913, -1, 22941, 22925, 22926, -1, 22944, 22945, 22933, -1, 22944, 22933, 22932, -1, 22946, 22914, 22918, -1, 22947, 22919, 22921, -1, 22946, 22918, 22922, -1, 22948, 22932, 22916, -1, 22947, 22921, 22927, -1, 22948, 22916, 22936, -1, 22949, 22922, 22924, -1, 22949, 22924, 22950, -1, 22951, 22925, 22941, -1, 22949, 22950, 22952, -1, 22953, 22858, 22930, -1, 22954, 22929, 22955, -1, 22953, 22892, 22934, -1, 22953, 22930, 22892, -1, 22954, 22927, 22929, -1, 22953, 22846, 22858, -1, 22956, 22869, 22870, -1, 22956, 22870, 22931, -1, 22951, 22936, 22925, -1, 22956, 22931, 22895, -1, 22956, 22895, 22935, -1, 22957, 22934, 22898, -1, 22957, 22898, 22938, -1, 22958, 22942, 22959, -1, 22880, 22935, 22901, -1, 22958, 22941, 22942, -1, 22960, 22904, 22943, -1, 22880, 22901, 22939, -1, 22885, 22961, 22945, -1, 22960, 22938, 22904, -1, 22885, 22945, 22944, -1, 22893, 22939, 22909, -1, 22893, 22909, 22940, -1, 22896, 22944, 22932, -1, 22896, 22932, 22948, -1, 22962, 22914, 22946, -1, 22962, 22943, 22914, -1, 22899, 22940, 22919, -1, 22963, 22952, 22964, -1, 22899, 22919, 22947, -1, 22963, 22946, 22922, -1, 22902, 22936, 22951, -1, 22963, 22922, 22949, -1, 22902, 22948, 22936, -1, 22963, 22949, 22952, -1, 22965, 22842, 22846, -1, 22905, 22947, 22927, -1, 22905, 22927, 22954, -1, 22965, 22934, 22957, -1, 22965, 22953, 22934, -1, 22965, 22846, 22953, -1, 22910, 22951, 22941, -1, 22915, 22955, 22966, -1, 22910, 22941, 22958, -1, 22915, 22954, 22955, -1, 22967, 22957, 22938, -1, 22967, 22938, 22960, -1, 22883, 22865, 22869, -1, 22920, 22959, 22968, -1, 22883, 22935, 22880, -1, 22920, 22958, 22959, -1, 22883, 22869, 22956, -1, 22883, 22956, 22935, -1, 22884, 22937, 22961, -1, 22882, 22960, 22943, -1, 22884, 22961, 22885, -1, 22884, 22863, 22937, -1, 22882, 22943, 22962, -1, 22881, 22880, 22939, -1, 22969, 22964, 22970, -1, 22881, 22939, 22893, -1, 22969, 22946, 22963, -1, 22969, 22963, 22964, -1, 22894, 22893, 22940, -1, 22969, 22962, 22946, -1, 22886, 22944, 22896, -1, 22971, 22841, 22842, -1, 22886, 22885, 22944, -1, 22971, 22842, 22965, -1, 22894, 22940, 22899, -1, 22897, 22948, 22902, -1, 22952, 22950, 22972, -1, 22971, 22965, 22957, -1, 22971, 22957, 22967, -1, 22897, 22896, 22948, -1, 22890, 22967, 22960, -1, 22900, 22899, 22947, -1, 22900, 22947, 22905, -1, 22890, 22960, 22882, -1, 22903, 22902, 22951, -1, 22903, 22951, 22910, -1, 22877, 22970, 22878, -1, 22877, 22969, 22970, -1, 22877, 22882, 22962, -1, 22877, 22962, 22969, -1, 22912, 22905, 22954, -1, 22912, 22954, 22915, -1, 22913, 22910, 22958, -1, 22891, 22839, 22841, -1, 22913, 22958, 22920, -1, 22891, 22967, 22890, -1, 22891, 22841, 22971, -1, 22891, 22971, 22967, -1, 22918, 22966, 22923, -1, 22918, 22915, 22966, -1, 22921, 22968, 22928, -1, 22876, 22878, 22889, -1, 22876, 22890, 22882, -1, 22921, 22920, 22968, -1, 22973, 22950, 22974, -1, 22972, 22950, 22973, -1, 22974, 22924, 22975, -1, 22950, 22924, 22974, -1, 22975, 22923, 22976, -1, 22924, 22923, 22975, -1, 22976, 22966, 22977, -1, 22923, 22966, 22976, -1, 22977, 22955, 22978, -1, 22966, 22955, 22977, -1, 22978, 22929, 22979, -1, 22955, 22929, 22978, -1, 22979, 22928, 22980, -1, 22929, 22928, 22979, -1, 22980, 22968, 22981, -1, 22928, 22968, 22980, -1, 22981, 22959, 22982, -1, 22968, 22959, 22981, -1, 22982, 22942, 22983, -1, 22959, 22942, 22982, -1, 22983, 22926, 22984, -1, 22942, 22926, 22983, -1, 22984, 22911, 22985, -1, 22926, 22911, 22984, -1, 22985, 22908, 22986, -1, 22911, 22908, 22985, -1, 22987, 22973, 22988, -1, 22972, 22973, 22987, -1, 22989, 22990, 22991, -1, 22991, 22992, 22993, -1, 22990, 22992, 22991, -1, 22993, 22994, 22995, -1, 22992, 22994, 22993, -1, 22995, 22996, 22997, -1, 22994, 22996, 22995, -1, 22997, 22998, 22999, -1, 22996, 22998, 22997, -1, 22999, 23000, 23001, -1, 22998, 23000, 22999, -1, 23001, 23002, 23003, -1, 23000, 23002, 23001, -1, 23003, 23004, 23005, -1, 23002, 23004, 23003, -1, 23005, 23006, 23007, -1, 23004, 23006, 23005, -1, 23007, 23008, 23009, -1, 23006, 23008, 23007, -1, 23009, 23010, 23011, -1, 23008, 23010, 23009, -1, 23011, 23012, 23013, -1, 23010, 23012, 23011, -1, 23013, 23014, 22988, -1, 23012, 23014, 23013, -1, 23014, 22987, 22988, -1, 22989, 22986, 22990, -1, 22986, 22908, 22990, -1, 23015, 22908, 22907, -1, 23015, 22990, 22908, -1, 23016, 22907, 22917, -1, 23016, 23015, 22907, -1, 23017, 22917, 22933, -1, 23017, 23016, 22917, -1, 23018, 22933, 22945, -1, 23018, 23017, 22933, -1, 23019, 22945, 22961, -1, 23019, 23018, 22945, -1, 23020, 22961, 22937, -1, 23020, 23019, 22961, -1, 22862, 22937, 22861, -1, 22862, 23020, 22937, -1, 22952, 22972, 22987, -1, 22952, 22987, 23021, -1, 22964, 23021, 23022, -1, 22964, 22952, 23021, -1, 22970, 23022, 23023, -1, 22970, 22964, 23022, -1, 22878, 23023, 23024, -1, 22878, 22970, 23023, -1, 22889, 23024, 23025, -1, 22889, 22878, 23024, -1, 22888, 23025, 23026, -1, 22888, 22889, 23025, -1, 22873, 23026, 22851, -1, 22873, 22888, 23026, -1, 23027, 23028, 23029, -1, 23030, 23031, 23032, -1, 23033, 23019, 23020, -1, 23027, 22848, 23028, -1, 23033, 23034, 23019, -1, 23027, 23029, 23035, -1, 23033, 22874, 22872, -1, 23033, 23020, 22874, -1, 23033, 22872, 23036, -1, 23037, 23035, 23038, -1, 23033, 23036, 23039, -1, 23037, 23038, 23040, -1, 23033, 23039, 23034, -1, 23030, 23041, 23031, -1, 23042, 23043, 23044, -1, 23014, 23021, 22987, -1, 23042, 23032, 23043, -1, 23045, 23040, 23046, -1, 23045, 23046, 23047, -1, 23048, 23044, 23049, -1, 22862, 22874, 23020, -1, 23050, 23051, 23052, -1, 23048, 23049, 23053, -1, 23050, 23047, 23051, -1, 23054, 23021, 23014, -1, 23055, 23053, 23056, -1, 23057, 23021, 23054, -1, 23055, 23056, 23058, -1, 23057, 23022, 23021, -1, 23059, 23052, 23060, -1, 23059, 23060, 23061, -1, 23062, 23058, 22996, -1, 23062, 22996, 22994, -1, 23063, 23004, 23002, -1, 23064, 23014, 23012, -1, 23063, 23061, 23004, -1, 23065, 23066, 23041, -1, 23064, 23054, 23014, -1, 23065, 22859, 22849, -1, 23065, 23041, 23030, -1, 23067, 22843, 22845, -1, 23067, 23027, 23035, -1, 23068, 23022, 23057, -1, 23065, 22849, 23066, -1, 23067, 22845, 23027, -1, 23067, 23035, 23037, -1, 23068, 23023, 23022, -1, 23069, 23032, 23042, -1, 23070, 23040, 23045, -1, 23070, 23037, 23040, -1, 23069, 23030, 23032, -1, 23071, 23057, 23054, -1, 23072, 23045, 23047, -1, 23072, 23047, 23050, -1, 23071, 23054, 23064, -1, 23073, 23042, 23044, -1, 23073, 23044, 23048, -1, 23074, 23012, 23010, -1, 23075, 23053, 23055, -1, 23074, 23064, 23012, -1, 23076, 23052, 23059, -1, 23076, 23050, 23052, -1, 23075, 23048, 23053, -1, 23077, 23024, 23023, -1, 23078, 23058, 23062, -1, 23077, 23023, 23068, -1, 23079, 23061, 23063, -1, 23078, 23055, 23058, -1, 23079, 23059, 23061, -1, 23080, 23068, 23057, -1, 23081, 22990, 23015, -1, 23080, 23057, 23071, -1, 23081, 23062, 22994, -1, 23082, 23063, 23002, -1, 23081, 22992, 22990, -1, 23083, 23064, 23074, -1, 23081, 22994, 22992, -1, 23082, 23002, 23000, -1, 23084, 22866, 22859, -1, 23085, 22844, 22843, -1, 23084, 23065, 23030, -1, 23084, 23030, 23069, -1, 23085, 22843, 23067, -1, 23085, 23067, 23037, -1, 23083, 23071, 23064, -1, 23084, 22859, 23065, -1, 23085, 23037, 23070, -1, 23086, 23069, 23042, -1, 23087, 23045, 23072, -1, 23086, 23042, 23073, -1, 23088, 23010, 23008, -1, 23088, 23074, 23010, -1, 23087, 23070, 23045, -1, 23029, 23024, 23077, -1, 23089, 23073, 23048, -1, 23089, 23048, 23075, -1, 23029, 23025, 23024, -1, 23031, 23072, 23050, -1, 23031, 23050, 23076, -1, 23090, 23075, 23055, -1, 23038, 23068, 23080, -1, 23090, 23055, 23078, -1, 23043, 23076, 23059, -1, 23038, 23077, 23068, -1, 23043, 23059, 23079, -1, 23046, 23080, 23071, -1, 23091, 23015, 23016, -1, 23091, 23078, 23062, -1, 23091, 23081, 23015, -1, 23046, 23071, 23083, -1, 23091, 23062, 23081, -1, 23049, 23079, 23063, -1, 23092, 22867, 22866, -1, 23049, 23063, 23082, -1, 23092, 23084, 23069, -1, 23092, 22866, 23084, -1, 23092, 23069, 23086, -1, 23051, 23083, 23074, -1, 23056, 23000, 22998, -1, 23051, 23074, 23088, -1, 23093, 23086, 23073, -1, 23056, 23082, 23000, -1, 23094, 22847, 22844, -1, 23060, 23008, 23006, -1, 23093, 23073, 23089, -1, 23094, 22844, 23085, -1, 23094, 23085, 23070, -1, 23060, 23088, 23008, -1, 23094, 23070, 23087, -1, 23028, 22848, 22851, -1, 23095, 23075, 23090, -1, 23028, 23025, 23029, -1, 23028, 22851, 23026, -1, 23095, 23089, 23075, -1, 23028, 23026, 23025, -1, 23096, 23016, 23017, -1, 23041, 23087, 23072, -1, 23041, 23072, 23031, -1, 23096, 23078, 23091, -1, 23035, 23077, 23038, -1, 23096, 23091, 23016, -1, 23096, 23090, 23078, -1, 23032, 23076, 23043, -1, 23035, 23029, 23077, -1, 23097, 22871, 22867, -1, 23032, 23031, 23076, -1, 23097, 23086, 23093, -1, 23097, 22867, 23092, -1, 23097, 23092, 23086, -1, 23040, 23080, 23046, -1, 23040, 23038, 23080, -1, 23044, 23043, 23079, -1, 23044, 23079, 23049, -1, 23047, 23046, 23083, -1, 23039, 23093, 23089, -1, 23039, 23089, 23095, -1, 23047, 23083, 23051, -1, 23098, 23017, 23018, -1, 23098, 23096, 23017, -1, 23098, 23095, 23090, -1, 23098, 23090, 23096, -1, 23053, 23049, 23082, -1, 23053, 23082, 23056, -1, 23036, 22871, 23097, -1, 23052, 23088, 23060, -1, 23036, 22872, 22871, -1, 23052, 23051, 23088, -1, 23058, 22998, 22996, -1, 23036, 23097, 23093, -1, 23058, 23056, 22998, -1, 23036, 23093, 23039, -1, 23034, 23018, 23019, -1, 23066, 22849, 22847, -1, 23061, 23006, 23004, -1, 23066, 22847, 23094, -1, 23061, 23060, 23006, -1, 23034, 23098, 23018, -1, 23034, 23039, 23095, -1, 23066, 23094, 23087, -1, 23027, 22845, 22848, -1, 23034, 23095, 23098, -1, 23066, 23087, 23041, -1, 16849, 16831, 23099, -1, 22812, 23099, 23100, -1, 22812, 16849, 23099, -1, 22814, 23100, 22854, -1, 22814, 22854, 22853, -1, 22814, 22812, 23100, -1, 22816, 22853, 22857, -1, 22816, 22814, 22853, -1, 22818, 22857, 22860, -1, 22818, 22816, 22857, -1, 22820, 22818, 22860, -1, 22821, 22860, 22837, -1, 22821, 22820, 22860, -1, 22822, 22821, 22837, -1, 23101, 16830, 16853, -1, 23101, 16853, 22760, -1, 23102, 22760, 22761, -1, 23102, 23101, 22760, -1, 22852, 22761, 22762, -1, 22852, 23102, 22761, -1, 22855, 22762, 22763, -1, 22855, 22852, 22762, -1, 22856, 22763, 22765, -1, 22856, 22855, 22763, -1, 22850, 22765, 22766, -1, 22850, 22856, 22765, -1, 22838, 22766, 22767, -1, 22838, 22850, 22766, -1, 23099, 16831, 16830, -1, 23099, 16830, 23101, -1, 23100, 23101, 23102, -1, 23100, 23099, 23101, -1, 22854, 23102, 22852, -1, 22854, 23100, 23102, -1, 23103, 15821, 15840, -1, 23104, 15578, 15576, -1, 23105, 23106, 23107, -1, 23103, 23108, 15821, -1, 23104, 15576, 23109, -1, 23105, 15575, 15577, -1, 23103, 23110, 23108, -1, 23104, 23109, 23111, -1, 23104, 23111, 23112, -1, 23105, 15577, 23106, -1, 23113, 15840, 15851, -1, 23113, 15851, 15593, -1, 23105, 23107, 23114, -1, 23113, 15592, 15591, -1, 23113, 15593, 15592, -1, 23113, 23115, 23103, -1, 23113, 15591, 23116, -1, 23113, 23116, 23115, -1, 23117, 23112, 23118, -1, 23113, 23103, 15840, -1, 23117, 23118, 23119, -1, 23120, 23119, 23121, -1, 23122, 23123, 23124, -1, 23122, 23114, 23123, -1, 23125, 23126, 23127, -1, 23125, 23124, 23126, -1, 23120, 23121, 23128, -1, 23129, 23128, 23130, -1, 23131, 15827, 15826, -1, 23129, 23130, 23132, -1, 23133, 23127, 23134, -1, 23131, 15826, 17750, -1, 23135, 23136, 23137, -1, 23133, 23134, 23138, -1, 23139, 15843, 15827, -1, 23135, 23132, 23136, -1, 23140, 23138, 23141, -1, 23139, 15827, 23131, -1, 23140, 23141, 23142, -1, 23143, 17741, 17740, -1, 23144, 17750, 17749, -1, 23143, 23137, 17741, -1, 23145, 17745, 17744, -1, 23146, 23104, 23112, -1, 23145, 23142, 17745, -1, 23144, 23131, 17750, -1, 23146, 15540, 15578, -1, 23147, 15573, 15575, -1, 23148, 15853, 15843, -1, 23146, 23112, 23117, -1, 23147, 23105, 23114, -1, 23146, 15578, 23104, -1, 23147, 23114, 23122, -1, 23149, 23119, 23120, -1, 23149, 23117, 23119, -1, 23147, 15575, 23105, -1, 23150, 23124, 23125, -1, 23148, 15843, 23139, -1, 23151, 23139, 23131, -1, 23150, 23122, 23124, -1, 23152, 23125, 23127, -1, 23151, 23131, 23144, -1, 15577, 15579, 15777, -1, 23152, 23127, 23133, -1, 23153, 23120, 23128, -1, 23154, 17749, 17748, -1, 23153, 23128, 23129, -1, 23154, 23144, 17749, -1, 23155, 23132, 23135, -1, 23156, 23133, 23138, -1, 23156, 23138, 23140, -1, 23157, 15857, 15853, -1, 23155, 23129, 23132, -1, 23158, 23135, 23137, -1, 23157, 15853, 23148, -1, 23159, 23139, 23151, -1, 23160, 23140, 23142, -1, 23158, 23137, 23143, -1, 23160, 23142, 23145, -1, 23161, 23143, 17740, -1, 23161, 17740, 17739, -1, 23159, 23148, 23139, -1, 23162, 17744, 17743, -1, 23161, 17739, 15784, -1, 23162, 23145, 17744, -1, 23163, 23117, 23149, -1, 23164, 23151, 23144, -1, 23163, 23146, 23117, -1, 23165, 15574, 15573, -1, 23164, 23144, 23154, -1, 23163, 15540, 23146, -1, 23163, 15588, 15540, -1, 23165, 23147, 23122, -1, 23166, 23149, 23120, -1, 23165, 23122, 23150, -1, 23166, 23120, 23153, -1, 23165, 15573, 23147, -1, 23167, 17748, 17747, -1, 23111, 23150, 23125, -1, 23167, 23154, 17748, -1, 23111, 23125, 23152, -1, 23107, 15766, 15857, -1, 23168, 23153, 23129, -1, 23118, 23133, 23156, -1, 23168, 23129, 23155, -1, 23107, 15857, 23157, -1, 23169, 23155, 23135, -1, 23118, 23152, 23133, -1, 23123, 23157, 23148, -1, 23169, 23135, 23158, -1, 23121, 23156, 23140, -1, 23123, 23148, 23159, -1, 23170, 15784, 15793, -1, 23121, 23140, 23160, -1, 23170, 23143, 23161, -1, 23126, 23159, 23151, -1, 23170, 23158, 23143, -1, 23170, 23161, 15784, -1, 23130, 23160, 23145, -1, 23126, 23151, 23164, -1, 23171, 23149, 23166, -1, 23130, 23145, 23162, -1, 23171, 15589, 15588, -1, 23171, 15588, 23163, -1, 23171, 23163, 23149, -1, 23134, 23164, 23154, -1, 23134, 23154, 23167, -1, 23172, 23166, 23153, -1, 23136, 17743, 17742, -1, 23172, 23153, 23168, -1, 23136, 23162, 17743, -1, 23141, 17747, 17746, -1, 23109, 15576, 15574, -1, 23109, 23150, 23111, -1, 23110, 23155, 23169, -1, 23109, 15574, 23165, -1, 23141, 23167, 17747, -1, 23106, 15777, 15766, -1, 23109, 23165, 23150, -1, 23106, 15766, 23107, -1, 23106, 15577, 15777, -1, 23110, 23168, 23155, -1, 23114, 23157, 23123, -1, 23173, 15793, 15809, -1, 23112, 23111, 23152, -1, 23173, 23170, 15793, -1, 23112, 23152, 23118, -1, 23173, 23169, 23158, -1, 23114, 23107, 23157, -1, 23173, 23158, 23170, -1, 23174, 15589, 23171, -1, 23174, 15590, 15589, -1, 23119, 23118, 23156, -1, 23119, 23156, 23121, -1, 15784, 17739, 15781, -1, 23174, 23166, 23172, -1, 23124, 23123, 23159, -1, 23174, 23171, 23166, -1, 23124, 23159, 23126, -1, 23128, 23121, 23160, -1, 23128, 23160, 23130, -1, 23115, 23172, 23168, -1, 23115, 23168, 23110, -1, 23127, 23126, 23164, -1, 23127, 23164, 23134, -1, 23132, 23130, 23162, -1, 23108, 15809, 15821, -1, 23108, 23173, 15809, -1, 23108, 23110, 23169, -1, 23108, 23169, 23173, -1, 23132, 23162, 23136, -1, 23138, 23167, 23141, -1, 23138, 23134, 23167, -1, 23116, 15591, 15590, -1, 23116, 15590, 23174, -1, 23137, 17742, 17741, -1, 23116, 23174, 23172, -1, 23142, 17746, 17745, -1, 23116, 23172, 23115, -1, 23137, 23136, 17742, -1, 23103, 23115, 23110, -1, 23142, 23141, 17746, -1, 23175, 23176, 23177, -1, 23178, 16592, 16578, -1, 23179, 23180, 17824, -1, 23175, 16678, 16695, -1, 23178, 23181, 23182, -1, 23183, 16580, 23184, -1, 23183, 23184, 23185, -1, 23183, 16574, 16580, -1, 23175, 23177, 23186, -1, 23178, 16578, 23187, -1, 23178, 23187, 23181, -1, 23175, 23186, 16678, -1, 23188, 23176, 23175, -1, 23183, 23185, 23189, -1, 23188, 16674, 16606, -1, 23190, 23189, 23191, -1, 23188, 16695, 16674, -1, 23188, 16606, 16597, -1, 23188, 16597, 23192, -1, 23193, 23194, 23195, -1, 23188, 23192, 23176, -1, 23188, 23175, 16695, -1, 23193, 23182, 23194, -1, 23196, 23195, 23197, -1, 23190, 23191, 23198, -1, 23199, 23198, 23200, -1, 16607, 16606, 16674, -1, 23201, 16685, 16684, -1, 23196, 23197, 23202, -1, 23199, 23200, 23203, -1, 23204, 23202, 23205, -1, 23206, 23203, 23207, -1, 23206, 23207, 23208, -1, 23201, 16684, 17828, -1, 23204, 23205, 23209, -1, 23210, 16698, 16685, -1, 23211, 23208, 23180, -1, 23212, 23213, 23214, -1, 23212, 23209, 23213, -1, 23210, 16685, 23201, -1, 23211, 23180, 23179, -1, 23215, 17819, 17818, -1, 23216, 17828, 17827, -1, 23217, 17823, 17822, -1, 23215, 23214, 17819, -1, 23216, 23201, 17828, -1, 23218, 23178, 23182, -1, 23217, 23179, 17823, -1, 23219, 16704, 16698, -1, 23220, 16572, 16574, -1, 23218, 16593, 16592, -1, 23220, 23189, 23190, -1, 23220, 23183, 23189, -1, 23218, 16592, 23178, -1, 23218, 23182, 23193, -1, 23220, 16574, 23183, -1, 23219, 16698, 23210, -1, 23221, 23193, 23195, -1, 23222, 23198, 23199, -1, 23223, 23210, 23201, -1, 23221, 23195, 23196, -1, 23222, 23190, 23198, -1, 23223, 23201, 23216, -1, 23224, 23199, 23203, -1, 23225, 17827, 17826, -1, 23225, 23216, 17827, -1, 23226, 23202, 23204, -1, 23224, 23203, 23206, -1, 23226, 23196, 23202, -1, 23227, 23206, 23208, -1, 23228, 16613, 16704, -1, 23229, 23204, 23209, -1, 23227, 23208, 23211, -1, 23229, 23209, 23212, -1, 23228, 16704, 23219, -1, 23230, 23210, 23223, -1, 23231, 23214, 23215, -1, 23232, 23211, 23179, -1, 23232, 23179, 23217, -1, 23231, 23212, 23214, -1, 23230, 23219, 23210, -1, 23233, 17817, 16640, -1, 23233, 17818, 17817, -1, 23233, 16640, 16642, -1, 23233, 23215, 17818, -1, 23234, 17822, 17821, -1, 23235, 23223, 23216, -1, 23234, 23217, 17822, -1, 23236, 23193, 23221, -1, 23237, 16573, 16572, -1, 23235, 23216, 23225, -1, 23236, 16593, 23218, -1, 23237, 16572, 23220, -1, 23236, 16594, 16593, -1, 23237, 23220, 23190, -1, 23236, 23218, 23193, -1, 23237, 23190, 23222, -1, 23238, 17826, 17825, -1, 23181, 23199, 23224, -1, 23238, 23225, 17826, -1, 23239, 23196, 23226, -1, 23181, 23222, 23199, -1, 23185, 16625, 16613, -1, 23239, 23221, 23196, -1, 23240, 23226, 23204, -1, 23185, 16613, 23228, -1, 23194, 23206, 23227, -1, 23191, 23219, 23230, -1, 23194, 23224, 23206, -1, 23240, 23204, 23229, -1, 23191, 23228, 23219, -1, 23197, 23227, 23211, -1, 23241, 23229, 23212, -1, 23197, 23211, 23232, -1, 23241, 23212, 23231, -1, 23200, 23230, 23223, -1, 23205, 23232, 23217, -1, 23200, 23223, 23235, -1, 23242, 16642, 16651, -1, 23205, 23217, 23234, -1, 23242, 23231, 23215, -1, 23242, 23215, 23233, -1, 23242, 23233, 16642, -1, 23243, 23236, 23221, -1, 23243, 16595, 16594, -1, 23207, 23235, 23225, -1, 23243, 16594, 23236, -1, 23243, 23221, 23239, -1, 23207, 23225, 23238, -1, 23213, 17821, 17820, -1, 23180, 23238, 17825, -1, 23244, 23239, 23226, -1, 23213, 23234, 17821, -1, 23244, 23226, 23240, -1, 23180, 17825, 17824, -1, 23187, 16578, 16573, -1, 23187, 16573, 23237, -1, 23184, 16626, 16625, -1, 23184, 16575, 16626, -1, 23187, 23237, 23222, -1, 23187, 23222, 23181, -1, 23184, 16580, 16575, -1, 23184, 16625, 23185, -1, 23177, 23240, 23229, -1, 23177, 23229, 23241, -1, 23182, 23181, 23224, -1, 23245, 16651, 16666, -1, 23182, 23224, 23194, -1, 23189, 23228, 23191, -1, 23245, 23241, 23231, -1, 23245, 23242, 16651, -1, 23189, 23185, 23228, -1, 23245, 23231, 23242, -1, 23195, 23194, 23227, -1, 23246, 23239, 23244, -1, 23195, 23227, 23197, -1, 23246, 16595, 23243, -1, 23246, 16596, 16595, -1, 23198, 23230, 23200, -1, 23246, 23243, 23239, -1, 23198, 23191, 23230, -1, 23202, 23232, 23205, -1, 23202, 23197, 23232, -1, 23203, 23200, 23235, -1, 23176, 23244, 23240, -1, 23203, 23235, 23207, -1, 23176, 23240, 23177, -1, 23209, 23205, 23234, -1, 23186, 16666, 16678, -1, 23208, 23238, 23180, -1, 23186, 23241, 23245, -1, 23209, 23234, 23213, -1, 23186, 23245, 16666, -1, 23186, 23177, 23241, -1, 23208, 23207, 23238, -1, 23192, 16597, 16596, -1, 23214, 17820, 17819, -1, 23192, 23246, 23244, -1, 23214, 23213, 17820, -1, 23179, 17824, 17823, -1, 23192, 16596, 23246, -1, 23192, 23244, 23176, -1, 23247, 23248, 23249, -1, 23250, 23251, 23252, -1, 23247, 15060, 23253, -1, 23250, 15051, 15050, -1, 23247, 23249, 15405, -1, 23254, 23255, 23256, -1, 23250, 23252, 23257, -1, 23254, 23258, 23255, -1, 23259, 23256, 23260, -1, 23261, 23262, 23263, -1, 23261, 23257, 23262, -1, 23264, 23265, 23266, -1, 23259, 23260, 23267, -1, 23264, 23263, 23265, -1, 23268, 23267, 23269, -1, 23268, 23269, 23270, -1, 15062, 15061, 15384, -1, 23271, 23266, 23272, -1, 23273, 15393, 15390, -1, 23274, 23270, 23275, -1, 23273, 15390, 17768, -1, 23271, 23272, 23276, -1, 23274, 23275, 23277, -1, 23278, 15407, 15393, -1, 23279, 17756, 17755, -1, 23280, 23276, 23281, -1, 23280, 23281, 23282, -1, 23278, 15393, 23273, -1, 23279, 23277, 17756, -1, 23283, 23284, 23258, -1, 23285, 17770, 17772, -1, 23283, 15056, 15055, -1, 23286, 17768, 17764, -1, 23283, 23258, 23254, -1, 23285, 23282, 17770, -1, 23283, 15055, 23284, -1, 23287, 15052, 15051, -1, 23286, 23273, 17768, -1, 23288, 23254, 23256, -1, 23287, 15051, 23250, -1, 23287, 23250, 23257, -1, 23289, 15415, 15407, -1, 23287, 23257, 23261, -1, 23290, 23263, 23264, -1, 23288, 23256, 23259, -1, 23291, 23267, 23268, -1, 23289, 15407, 23278, -1, 23292, 23278, 23273, -1, 23290, 23261, 23263, -1, 23293, 23264, 23266, -1, 23291, 23259, 23267, -1, 23294, 23270, 23274, -1, 23293, 23266, 23271, -1, 23292, 23273, 23286, -1, 23294, 23268, 23270, -1, 15050, 15049, 15345, -1, 23295, 23271, 23276, -1, 23295, 23276, 23280, -1, 23296, 17764, 17759, -1, 23296, 23286, 17764, -1, 23297, 23277, 23279, -1, 23298, 15418, 15415, -1, 23297, 23274, 23277, -1, 23299, 17754, 15351, -1, 23300, 23280, 23282, -1, 23298, 15415, 23289, -1, 23299, 17755, 17754, -1, 23300, 23282, 23285, -1, 23301, 23278, 23292, -1, 23299, 15351, 15353, -1, 23299, 23279, 17755, -1, 23302, 23283, 23254, -1, 23302, 15056, 23283, -1, 23303, 17772, 17774, -1, 23301, 23289, 23278, -1, 23302, 15057, 15056, -1, 23303, 23285, 17772, -1, 23302, 23254, 23288, -1, 23304, 15053, 15052, -1, 23305, 23292, 23286, -1, 23306, 23288, 23259, -1, 23306, 23259, 23291, -1, 23304, 15052, 23287, -1, 23305, 23286, 23296, -1, 23304, 23287, 23261, -1, 23304, 23261, 23290, -1, 23307, 23291, 23268, -1, 23308, 23264, 23293, -1, 23309, 17759, 17762, -1, 23307, 23268, 23294, -1, 23308, 23290, 23264, -1, 23309, 23296, 17759, -1, 23252, 15326, 15418, -1, 23310, 23294, 23274, -1, 23255, 23293, 23271, -1, 23255, 23271, 23295, -1, 23252, 15418, 23298, -1, 23310, 23274, 23297, -1, 23260, 23295, 23280, -1, 23311, 23297, 23279, -1, 23260, 23280, 23300, -1, 23262, 23298, 23289, -1, 23311, 15353, 15363, -1, 23262, 23289, 23301, -1, 23311, 23279, 23299, -1, 23311, 23299, 15353, -1, 23312, 15058, 15057, -1, 23312, 23288, 23306, -1, 23265, 23301, 23292, -1, 23269, 23300, 23285, -1, 23312, 23302, 23288, -1, 23269, 23285, 23303, -1, 23312, 15057, 23302, -1, 23265, 23292, 23305, -1, 23313, 23306, 23291, -1, 23313, 23291, 23307, -1, 23275, 17774, 17776, -1, 23272, 23305, 23296, -1, 23272, 23296, 23309, -1, 23275, 23303, 17774, -1, 23314, 15054, 15053, -1, 23314, 23304, 23290, -1, 23281, 17762, 17766, -1, 23315, 23307, 23294, -1, 23314, 23290, 23308, -1, 23315, 23294, 23310, -1, 23314, 15053, 23304, -1, 23316, 15363, 15375, -1, 23281, 23309, 17762, -1, 23251, 15345, 15326, -1, 23316, 23297, 23311, -1, 23316, 23311, 15363, -1, 23258, 23308, 23293, -1, 23251, 15326, 23252, -1, 23258, 23293, 23255, -1, 23251, 15050, 15345, -1, 23316, 23310, 23297, -1, 23257, 23298, 23262, -1, 23317, 15059, 15058, -1, 23317, 23306, 23313, -1, 23256, 23255, 23295, -1, 23257, 23252, 23298, -1, 23317, 15058, 23312, -1, 23317, 23312, 23306, -1, 23256, 23295, 23260, -1, 23263, 23262, 23301, -1, 23248, 23313, 23307, -1, 23248, 23307, 23315, -1, 23267, 23260, 23300, -1, 23263, 23301, 23265, -1, 23318, 15375, 15387, -1, 23267, 23300, 23269, -1, 23318, 23316, 15375, -1, 23318, 23315, 23310, -1, 23318, 23310, 23316, -1, 23266, 23265, 23305, -1, 23266, 23305, 23272, -1, 23270, 23269, 23303, -1, 23253, 15060, 15059, -1, 23270, 23303, 23275, -1, 23253, 15059, 23317, -1, 23253, 23317, 23313, -1, 23253, 23313, 23248, -1, 23276, 23309, 23281, -1, 23276, 23272, 23309, -1, 23277, 17776, 17756, -1, 23249, 15387, 15405, -1, 23277, 23275, 17776, -1, 23249, 23318, 15387, -1, 23284, 23314, 23308, -1, 23249, 23248, 23315, -1, 23284, 15055, 15054, -1, 23282, 17766, 17770, -1, 23249, 23315, 23318, -1, 23247, 23253, 23248, -1, 23284, 23308, 23258, -1, 23247, 15384, 15061, -1, 23284, 15054, 23314, -1, 23282, 23281, 17766, -1, 23247, 15405, 15384, -1, 23247, 15061, 15060, -1, 23250, 15050, 23251, -1, 23319, 15105, 23320, -1, 23321, 15099, 23322, -1, 23323, 23324, 17487, -1, 23319, 23320, 23325, -1, 23321, 23322, 23326, -1, 23319, 23327, 15513, -1, 23328, 23329, 23330, -1, 23319, 23325, 23327, -1, 23328, 15096, 15095, -1, 23328, 15095, 23329, -1, 23331, 23332, 23333, -1, 23328, 23330, 23334, -1, 23331, 23335, 23332, -1, 23336, 23334, 23337, -1, 23338, 23333, 23339, -1, 23336, 23337, 23340, -1, 23338, 23339, 23341, -1, 23342, 23340, 23343, -1, 23344, 23341, 23345, -1, 23346, 15501, 15500, -1, 23342, 23343, 23347, -1, 23348, 23347, 23349, -1, 23344, 23345, 23350, -1, 23348, 23349, 23351, -1, 23346, 15500, 17490, -1, 23352, 23353, 23354, -1, 23352, 23350, 23353, -1, 23355, 15516, 15501, -1, 23356, 23351, 23324, -1, 23357, 17521, 17524, -1, 23355, 15501, 23346, -1, 23356, 23324, 23323, -1, 23357, 23354, 17521, -1, 23358, 23321, 23335, -1, 23359, 17490, 17482, -1, 23360, 17498, 17504, -1, 23358, 15101, 15100, -1, 23358, 23335, 23331, -1, 23359, 23346, 17490, -1, 23358, 15100, 23321, -1, 23360, 23323, 17498, -1, 23361, 15097, 15096, -1, 23362, 15525, 15516, -1, 23363, 23333, 23338, -1, 23361, 23334, 23336, -1, 23361, 23328, 23334, -1, 23361, 15096, 23328, -1, 23363, 23331, 23333, -1, 23364, 23340, 23342, -1, 23362, 15516, 23355, -1, 23364, 23336, 23340, -1, 23365, 23355, 23346, -1, 23366, 23341, 23344, -1, 23367, 23342, 23347, -1, 23366, 23338, 23341, -1, 23365, 23346, 23359, -1, 23368, 23350, 23352, -1, 23369, 17482, 17474, -1, 23367, 23347, 23348, -1, 23369, 23359, 17482, -1, 23368, 23344, 23350, -1, 23370, 23348, 23351, -1, 23370, 23351, 23356, -1, 23371, 15528, 15525, -1, 23372, 23354, 23357, -1, 23372, 23352, 23354, -1, 23371, 15525, 23362, -1, 23373, 17524, 17528, -1, 23374, 23355, 23365, -1, 23375, 23356, 23323, -1, 23373, 23357, 17524, -1, 23375, 23323, 23360, -1, 23373, 17528, 15458, -1, 23374, 23362, 23355, -1, 23376, 15101, 23358, -1, 23376, 23358, 23331, -1, 23377, 17504, 17512, -1, 23376, 23331, 23363, -1, 23376, 15102, 15101, -1, 23377, 23360, 17504, -1, 23378, 23365, 23359, -1, 23379, 15098, 15097, -1, 23379, 15097, 23361, -1, 23378, 23359, 23369, -1, 23380, 23338, 23366, -1, 23379, 23361, 23336, -1, 23379, 23336, 23364, -1, 23380, 23363, 23338, -1, 23326, 23342, 23367, -1, 23381, 23366, 23344, -1, 23382, 17474, 17480, -1, 23326, 23364, 23342, -1, 23382, 23369, 17474, -1, 23330, 15433, 15528, -1, 23381, 23344, 23368, -1, 23383, 23352, 23372, -1, 23330, 15528, 23371, -1, 23332, 23348, 23370, -1, 23383, 23368, 23352, -1, 23332, 23367, 23348, -1, 23337, 23362, 23374, -1, 23384, 15458, 15467, -1, 23339, 23370, 23356, -1, 23384, 23372, 23357, -1, 23339, 23356, 23375, -1, 23384, 23357, 23373, -1, 23337, 23371, 23362, -1, 23384, 23373, 15458, -1, 23345, 23375, 23360, -1, 23385, 15102, 23376, -1, 23385, 23376, 23363, -1, 23343, 23374, 23365, -1, 23385, 15103, 15102, -1, 23345, 23360, 23377, -1, 23343, 23365, 23378, -1, 23385, 23363, 23380, -1, 23386, 23366, 23381, -1, 23386, 23380, 23366, -1, 23349, 23378, 23369, -1, 23353, 17512, 17516, -1, 23349, 23369, 23382, -1, 23353, 23377, 17512, -1, 23324, 23382, 17480, -1, 23322, 15099, 15098, -1, 23324, 17480, 17487, -1, 23387, 23381, 23368, -1, 23322, 15098, 23379, -1, 23387, 23368, 23383, -1, 23322, 23379, 23364, -1, 23322, 23364, 23326, -1, 23388, 23383, 23372, -1, 23329, 15437, 15433, -1, 23388, 15467, 15482, -1, 23329, 15093, 15437, -1, 23335, 23326, 23367, -1, 23329, 15094, 15093, -1, 23388, 23372, 23384, -1, 23329, 15095, 15094, -1, 23388, 23384, 15467, -1, 23329, 15433, 23330, -1, 23335, 23367, 23332, -1, 23389, 23380, 23386, -1, 23389, 15104, 15103, -1, 23389, 15103, 23385, -1, 23334, 23371, 23337, -1, 23389, 23385, 23380, -1, 23333, 23332, 23370, -1, 23333, 23370, 23339, -1, 23334, 23330, 23371, -1, 23325, 23386, 23381, -1, 15458, 17528, 15455, -1, 23325, 23381, 23387, -1, 23340, 23374, 23343, -1, 23341, 23375, 23345, -1, 23390, 15482, 15494, -1, 23341, 23339, 23375, -1, 23340, 23337, 23374, -1, 23390, 23388, 15482, -1, 23390, 23383, 23388, -1, 23390, 23387, 23383, -1, 23350, 23345, 23377, -1, 23347, 23343, 23378, -1, 23320, 23386, 23325, -1, 23347, 23378, 23349, -1, 23320, 15105, 15104, -1, 23350, 23377, 23353, -1, 23320, 15104, 23389, -1, 23351, 23382, 23324, -1, 23320, 23389, 23386, -1, 23327, 15494, 15513, -1, 23327, 23390, 15494, -1, 23354, 17516, 17521, -1, 23351, 23349, 23382, -1, 23354, 23353, 17516, -1, 23327, 23325, 23387, -1, 23327, 23387, 23390, -1, 23321, 15100, 15099, -1, 23319, 15513, 15522, -1, 23323, 17487, 17498, -1, 23319, 15522, 15106, -1, 23321, 23326, 23335, -1, 23319, 15106, 15105, -1, 17913, 17861, 17863, -1, 23391, 17863, 17865, -1, 23391, 17913, 17863, -1, 23392, 17865, 17869, -1, 23392, 23391, 17865, -1, 23393, 17869, 17830, -1, 23393, 23392, 17869, -1, 17664, 23393, 17830, -1, 23394, 23395, 23396, -1, 23394, 23396, 23397, -1, 23398, 17933, 17911, -1, 23398, 17934, 17933, -1, 23398, 17911, 23399, -1, 23398, 23397, 17934, -1, 23400, 17702, 17701, -1, 23400, 17701, 23401, -1, 23400, 23401, 23395, -1, 23400, 23395, 23394, -1, 23402, 23399, 23403, -1, 23402, 23394, 23397, -1, 23402, 23398, 23399, -1, 23402, 23397, 23398, -1, 23404, 23403, 23405, -1, 23404, 17703, 17702, -1, 23404, 23405, 17703, -1, 23404, 17702, 23400, -1, 23404, 23402, 23403, -1, 23404, 23400, 23394, -1, 23404, 23394, 23402, -1, 17698, 17697, 17859, -1, 17704, 17703, 23405, -1, 23406, 17854, 17852, -1, 23406, 17852, 17939, -1, 23407, 17857, 17854, -1, 23407, 17854, 23406, -1, 23408, 17939, 17938, -1, 23408, 23406, 17939, -1, 23409, 17859, 17857, -1, 23409, 17857, 23407, -1, 23409, 17698, 17859, -1, 23410, 23406, 23408, -1, 23410, 23407, 23406, -1, 23411, 17938, 17937, -1, 23411, 23408, 17938, -1, 23412, 17699, 17698, -1, 23412, 23407, 23410, -1, 23412, 17698, 23409, -1, 23412, 23409, 23407, -1, 23413, 23410, 23408, -1, 23413, 23408, 23411, -1, 23396, 17937, 17936, -1, 23396, 23411, 17937, -1, 23414, 17700, 17699, -1, 23414, 23410, 23413, -1, 23414, 17699, 23412, -1, 23414, 23412, 23410, -1, 23395, 23413, 23411, -1, 23395, 23411, 23396, -1, 23397, 17936, 17934, -1, 23397, 23396, 17936, -1, 23401, 17701, 17700, -1, 23401, 17700, 23414, -1, 23401, 23414, 23413, -1, 23401, 23413, 23395, -1, 17911, 17879, 17951, -1, 23399, 17951, 17960, -1, 23399, 17911, 17951, -1, 23403, 17960, 17957, -1, 23403, 23399, 17960, -1, 23405, 17957, 17956, -1, 23405, 23403, 17957, -1, 17704, 23405, 17956, -1, 17829, 23415, 17545, -1, 17545, 23415, 17543, -1, 17543, 23416, 17541, -1, 23415, 23416, 17543, -1, 17541, 23417, 17534, -1, 23416, 23417, 17541, -1, 17534, 17479, 17481, -1, 23417, 17479, 17534, -1, 23418, 23419, 23420, -1, 23420, 23419, 23421, -1, 23421, 23422, 23423, -1, 23423, 23422, 23424, -1, 17527, 23425, 17470, -1, 17470, 23425, 17683, -1, 23424, 23425, 17527, -1, 17840, 23426, 17838, -1, 23421, 23426, 23422, -1, 17838, 23426, 23419, -1, 23419, 23426, 23421, -1, 17683, 23427, 17685, -1, 23425, 23427, 17683, -1, 23422, 23427, 23424, -1, 23424, 23427, 23425, -1, 17680, 23428, 17842, -1, 17842, 23428, 17840, -1, 17685, 23428, 17682, -1, 17682, 23428, 17680, -1, 17840, 23428, 23426, -1, 23427, 23428, 17685, -1, 23426, 23428, 23422, -1, 17829, 17832, 23415, -1, 23422, 23428, 23427, -1, 17470, 17683, 17469, -1, 23417, 23429, 17479, -1, 17479, 23429, 17505, -1, 23416, 23430, 23417, -1, 23417, 23430, 23429, -1, 17505, 23431, 17513, -1, 23429, 23431, 17505, -1, 23415, 23432, 23416, -1, 23416, 23432, 23430, -1, 17832, 23432, 23415, -1, 23429, 23433, 23431, -1, 23430, 23433, 23429, -1, 17513, 23434, 17518, -1, 23431, 23434, 17513, -1, 17834, 23435, 17832, -1, 17832, 23435, 23432, -1, 23432, 23435, 23430, -1, 23430, 23435, 23433, -1, 23431, 23420, 23434, -1, 23433, 23420, 23431, -1, 17518, 23423, 17522, -1, 23434, 23423, 17518, -1, 17836, 23418, 17834, -1, 17834, 23418, 23435, -1, 23433, 23418, 23420, -1, 23435, 23418, 23433, -1, 23420, 23421, 23434, -1, 23434, 23421, 23423, -1, 17522, 23424, 17527, -1, 23423, 23424, 17522, -1, 17838, 23419, 17836, -1, 17836, 23419, 23418, -1, 17972, 23436, 17678, -1, 17678, 23436, 17677, -1, 17677, 23437, 17675, -1, 23436, 23437, 17677, -1, 17675, 23438, 17666, -1, 23437, 23438, 17675, -1, 17666, 17461, 17466, -1, 23438, 17461, 17666, -1, 18671, 18674, 18719, -1, 18719, 18674, 23439, -1, 23439, 18673, 23440, -1, 18674, 18673, 23439, -1, 18673, 18672, 23440, -1, 23440, 18664, 23441, -1, 18672, 18664, 23440, -1, 23441, 18663, 17757, -1, 18664, 18663, 23441, -1, 18663, 17753, 17757, -1, 18715, 23442, 18713, -1, 17778, 23443, 17777, -1, 18713, 23442, 23444, -1, 23445, 23442, 23446, -1, 23447, 23443, 17778, -1, 23444, 23442, 23445, -1, 23440, 23448, 23439, -1, 18697, 23449, 18695, -1, 23446, 23448, 23450, -1, 23450, 23448, 23451, -1, 18695, 23449, 23452, -1, 23451, 23448, 23440, -1, 23452, 23449, 23453, -1, 23454, 17752, 17751, -1, 23453, 23449, 23455, -1, 18717, 23456, 18715, -1, 23448, 23456, 23439, -1, 23442, 23456, 23446, -1, 23446, 23456, 23448, -1, 23447, 23457, 23443, -1, 18715, 23456, 23442, -1, 23439, 23456, 18717, -1, 23455, 23457, 23447, -1, 17777, 23458, 17775, -1, 23443, 23458, 17777, -1, 18699, 23459, 18697, -1, 18697, 23459, 23449, -1, 23455, 23459, 23457, -1, 23449, 23459, 23455, -1, 23443, 23460, 23458, -1, 23457, 23460, 23443, -1, 18692, 18695, 23461, -1, 17775, 23462, 17773, -1, 23458, 23462, 17775, -1, 18699, 23463, 23459, -1, 18701, 23463, 18699, -1, 23457, 23463, 23460, -1, 23459, 23463, 23457, -1, 23460, 23464, 23458, -1, 23458, 23464, 23462, -1, 17773, 23465, 17771, -1, 23462, 23465, 17773, -1, 18703, 23466, 18701, -1, 23460, 23466, 23464, -1, 23463, 23466, 23460, -1, 18701, 23466, 23463, -1, 23462, 23467, 23465, -1, 23464, 23467, 23462, -1, 17771, 23468, 17769, -1, 23465, 23468, 17771, -1, 18705, 23469, 18703, -1, 23464, 23469, 23467, -1, 18703, 23469, 23466, -1, 23466, 23469, 23464, -1, 23465, 23470, 23468, -1, 23467, 23470, 23465, -1, 23468, 23471, 17769, -1, 17769, 23471, 17765, -1, 18707, 23472, 18705, -1, 18705, 23472, 23469, -1, 23469, 23472, 23467, -1, 23467, 23472, 23470, -1, 23470, 23473, 23468, -1, 23468, 23473, 23471, -1, 17765, 23474, 17760, -1, 23471, 23474, 17765, -1, 18709, 23475, 18707, -1, 23470, 23475, 23473, -1, 23472, 23475, 23470, -1, 18707, 23475, 23472, -1, 23473, 23476, 23471, -1, 23471, 23476, 23474, -1, 17760, 23477, 17761, -1, 23474, 23477, 17760, -1, 18711, 23478, 18709, -1, 23473, 23478, 23476, -1, 23475, 23478, 23473, -1, 18709, 23478, 23475, -1, 23476, 23445, 23474, -1, 23474, 23445, 23477, -1, 18717, 18719, 23439, -1, 17761, 23450, 17763, -1, 23454, 23479, 17752, -1, 23477, 23450, 17761, -1, 23480, 23453, 23454, -1, 18713, 23444, 18711, -1, 18711, 23444, 23478, -1, 23476, 23444, 23445, -1, 23454, 23453, 23479, -1, 23478, 23444, 23476, -1, 17752, 23447, 17778, -1, 23445, 23446, 23477, -1, 23479, 23447, 17752, -1, 23477, 23446, 23450, -1, 23461, 23452, 23480, -1, 23450, 23451, 17763, -1, 18695, 23452, 23461, -1, 17763, 23451, 17767, -1, 23480, 23452, 23453, -1, 17767, 23451, 17757, -1, 23441, 23451, 23440, -1, 23453, 23455, 23479, -1, 17757, 23451, 23441, -1, 23479, 23455, 23447, -1, 18692, 23461, 18659, -1, 18659, 23461, 18658, -1, 18658, 23461, 18657, -1, 18657, 23480, 18656, -1, 23461, 23480, 18657, -1, 18656, 23454, 18655, -1, 18655, 23454, 18654, -1, 23480, 23454, 18656, -1, 18654, 17751, 17758, -1, 23454, 17751, 18654, -1, 18648, 18644, 23481, -1, 18675, 23482, 23483, -1, 18675, 23481, 23482, -1, 18675, 18648, 23481, -1, 18666, 23483, 18693, -1, 18666, 18675, 23483, -1, 23484, 23482, 23485, -1, 23486, 18633, 18635, -1, 23487, 23485, 23488, -1, 23486, 23489, 18633, -1, 23487, 23488, 23490, -1, 23486, 18635, 23491, -1, 23492, 18714, 18712, -1, 23492, 18712, 23493, -1, 23494, 23490, 18642, -1, 23492, 23495, 23496, -1, 23492, 23493, 23495, -1, 23494, 18642, 18641, -1, 23497, 23491, 23498, -1, 23499, 23485, 23487, -1, 23499, 18696, 18694, -1, 23497, 23496, 23489, -1, 23497, 23486, 23491, -1, 23497, 23489, 23486, -1, 23499, 18694, 23484, -1, 23500, 23501, 18718, -1, 23499, 23484, 23485, -1, 23500, 23498, 23501, -1, 23500, 18716, 18714, -1, 23502, 23487, 23490, -1, 23500, 18718, 18716, -1, 23500, 23497, 23498, -1, 23502, 23490, 23494, -1, 23500, 23492, 23496, -1, 23500, 23496, 23497, -1, 23500, 18714, 23492, -1, 23503, 18641, 18640, -1, 23503, 23494, 18641, -1, 23504, 18698, 18696, -1, 23504, 23499, 23487, -1, 23504, 23487, 23502, -1, 23504, 18696, 23499, -1, 23505, 23494, 23503, -1, 23505, 23502, 23494, -1, 23506, 18640, 18639, -1, 23506, 23503, 18640, -1, 23507, 18700, 18698, -1, 23507, 23504, 23502, -1, 23507, 18698, 23504, -1, 23507, 23502, 23505, -1, 23508, 23505, 23503, -1, 23508, 23503, 23506, -1, 23509, 18639, 18638, -1, 23509, 23506, 18639, -1, 23510, 18702, 18700, -1, 23510, 18700, 23507, -1, 23510, 23507, 23505, -1, 23510, 23505, 23508, -1, 23511, 23508, 23506, -1, 23511, 23506, 23509, -1, 23512, 18638, 18636, -1, 23512, 23509, 18638, -1, 23513, 23508, 23511, -1, 23513, 23510, 23508, -1, 23513, 18704, 18702, -1, 23513, 18702, 23510, -1, 23514, 23511, 23509, -1, 23514, 23509, 23512, -1, 23515, 18636, 18634, -1, 23515, 23512, 18636, -1, 23516, 23513, 23511, -1, 23516, 18704, 23513, -1, 23516, 18706, 18704, -1, 23516, 23511, 23514, -1, 23517, 23514, 23512, -1, 23517, 23512, 23515, -1, 23518, 18634, 18631, -1, 23518, 23515, 18634, -1, 23519, 23516, 23514, -1, 23519, 23514, 23517, -1, 23519, 18708, 18706, -1, 23519, 18706, 23516, -1, 23491, 18635, 18637, -1, 23520, 23517, 23515, -1, 23520, 23515, 23518, -1, 23521, 18631, 18632, -1, 23521, 23518, 18631, -1, 23522, 23519, 23517, -1, 23522, 18708, 23519, -1, 23522, 18710, 18708, -1, 23522, 23517, 23520, -1, 23495, 23520, 23518, -1, 23495, 23518, 23521, -1, 23488, 23481, 18644, -1, 23488, 18644, 18643, -1, 23489, 18632, 18633, -1, 23489, 23521, 18632, -1, 23485, 23482, 23481, -1, 23485, 23481, 23488, -1, 23493, 18712, 18710, -1, 23493, 18710, 23522, -1, 23493, 23520, 23495, -1, 23493, 23522, 23520, -1, 23490, 18643, 18642, -1, 23490, 23488, 18643, -1, 23496, 23495, 23521, -1, 23484, 18693, 23483, -1, 23496, 23521, 23489, -1, 23484, 23483, 23482, -1, 23484, 18694, 18693, -1, 23491, 18637, 18646, -1, 23498, 18646, 18677, -1, 23498, 23491, 18646, -1, 23501, 23498, 18677, -1, 18718, 23501, 18677, -1, 23523, 16864, 16865, -1, 23523, 16865, 23524, -1, 23525, 23524, 23526, -1, 23525, 23523, 23524, -1, 23527, 23526, 23528, -1, 23527, 23528, 23529, -1, 23527, 23525, 23526, -1, 18016, 23529, 18036, -1, 18016, 23527, 23529, -1, 23530, 16824, 16823, -1, 23530, 16823, 23531, -1, 23530, 23531, 23532, -1, 23533, 23532, 23534, -1, 23533, 23530, 23532, -1, 23535, 23534, 23536, -1, 23535, 23533, 23534, -1, 23537, 23536, 18015, -1, 23537, 23535, 23536, -1, 18041, 23537, 18015, -1, 17977, 17987, 17976, -1, 17976, 23538, 17975, -1, 17987, 23538, 17976, -1, 17975, 23539, 17974, -1, 23538, 23539, 17975, -1, 17974, 23540, 17973, -1, 23539, 23540, 17974, -1, 17973, 16810, 16813, -1, 23540, 16810, 17973, -1, 17995, 23541, 17994, -1, 17994, 23541, 23542, -1, 23542, 23541, 23543, -1, 23543, 23541, 23544, -1, 18013, 23545, 17995, -1, 23544, 23545, 23532, -1, 23532, 23545, 18013, -1, 17995, 23545, 23541, -1, 23541, 23545, 23544, -1, 16810, 23540, 16815, -1, 18013, 23534, 23532, -1, 18013, 23536, 23534, -1, 18013, 18015, 23536, -1, 23539, 23546, 23540, -1, 16815, 23546, 16817, -1, 23540, 23546, 16815, -1, 23539, 23547, 23546, -1, 16817, 23548, 16819, -1, 23546, 23548, 16817, -1, 16819, 23549, 16822, -1, 16822, 23549, 16823, -1, 23548, 23549, 16819, -1, 23538, 23550, 23539, -1, 17987, 23550, 23538, -1, 17986, 23550, 17987, -1, 23539, 23550, 23547, -1, 23547, 23551, 23546, -1, 23546, 23551, 23548, -1, 16823, 23543, 23531, -1, 23549, 23543, 16823, -1, 23548, 23552, 23549, -1, 23551, 23552, 23548, -1, 17983, 23553, 17986, -1, 17986, 23553, 23550, -1, 23550, 23553, 23547, -1, 23547, 23553, 23551, -1, 23552, 23542, 23549, -1, 23549, 23542, 23543, -1, 17985, 23554, 17983, -1, 23551, 23554, 23552, -1, 17983, 23554, 23553, -1, 23553, 23554, 23551, -1, 23531, 23544, 23532, -1, 23543, 23544, 23531, -1, 17994, 23555, 17985, -1, 23542, 23555, 17994, -1, 23552, 23555, 23542, -1, 17985, 23555, 23554, -1, 23554, 23555, 23552, -1, 18064, 18622, 18060, -1, 18060, 18622, 23556, -1, 23556, 18623, 23557, -1, 18622, 18623, 23556, -1, 23557, 18624, 23558, -1, 18623, 18624, 23557, -1, 23558, 16850, 16836, -1, 18624, 16850, 23558, -1, 16836, 16857, 23558, -1, 23525, 23527, 18014, -1, 23527, 18016, 18014, -1, 23556, 23559, 18060, -1, 18060, 23559, 18059, -1, 18059, 23560, 18058, -1, 23559, 23560, 18059, -1, 23557, 23561, 23556, -1, 23558, 23561, 23557, -1, 23556, 23561, 23559, -1, 23559, 23562, 23560, -1, 23561, 23562, 23559, -1, 18058, 23563, 18007, -1, 18007, 23563, 18012, -1, 23560, 23563, 18058, -1, 16859, 23564, 16857, -1, 16857, 23564, 23558, -1, 23558, 23564, 23561, -1, 23562, 23565, 23560, -1, 23560, 23565, 23563, -1, 16861, 23566, 16859, -1, 23561, 23566, 23562, -1, 23564, 23566, 23561, -1, 16859, 23566, 23564, -1, 23523, 23567, 16864, -1, 16864, 23567, 16861, -1, 23566, 23567, 23562, -1, 23562, 23567, 23565, -1, 16861, 23567, 23566, -1, 23563, 23568, 18012, -1, 23565, 23568, 23563, -1, 23523, 23569, 23567, -1, 23567, 23569, 23565, -1, 23565, 23569, 23568, -1, 23525, 23570, 23523, -1, 18012, 23570, 18014, -1, 23523, 23570, 23569, -1, 18014, 23570, 23525, -1, 23568, 23570, 18012, -1, 23569, 23570, 23568, -1, 18069, 18070, 18621, -1, 18621, 23571, 18620, -1, 18070, 23571, 18621, -1, 18620, 23572, 18619, -1, 23571, 23572, 18620, -1, 18619, 23573, 18618, -1, 23572, 23573, 18619, -1, 18618, 16833, 16832, -1, 23573, 16833, 18618, -1, 23524, 23574, 23575, -1, 23576, 23574, 16865, -1, 23577, 23574, 23576, -1, 23575, 23574, 23577, -1, 23571, 23578, 23572, -1, 23579, 23578, 23571, -1, 23580, 23578, 23581, -1, 23581, 23578, 23579, -1, 23528, 18038, 23529, -1, 23582, 23583, 23580, -1, 23529, 18038, 18036, -1, 23584, 23583, 23582, -1, 16862, 23585, 16863, -1, 16863, 23585, 16865, -1, 16865, 23585, 23584, -1, 16860, 23586, 16862, -1, 16862, 23586, 23585, -1, 23584, 23586, 23583, -1, 23583, 23586, 16860, -1, 23585, 23586, 23584, -1, 23572, 23587, 23573, -1, 16858, 23587, 16860, -1, 23573, 23587, 16858, -1, 23578, 23587, 23572, -1, 23580, 23587, 23578, -1, 16860, 23587, 23583, -1, 23583, 23587, 23580, -1, 16858, 16833, 23573, -1, 18027, 23588, 18025, -1, 23526, 23589, 23528, -1, 23528, 23589, 18038, -1, 18029, 23590, 18027, -1, 18027, 23590, 23588, -1, 18038, 23577, 18029, -1, 18029, 23577, 23590, -1, 23589, 23577, 18038, -1, 18025, 23591, 18071, -1, 23588, 23591, 18025, -1, 18071, 23581, 18072, -1, 23591, 23581, 18071, -1, 23588, 23582, 23591, -1, 23590, 23582, 23588, -1, 23524, 23575, 23526, -1, 23526, 23575, 23589, -1, 23589, 23575, 23577, -1, 23577, 23576, 23590, -1, 23591, 23580, 23581, -1, 23582, 23580, 23591, -1, 18070, 23579, 23571, -1, 18072, 23579, 18070, -1, 23581, 23579, 18072, -1, 23590, 23584, 23582, -1, 23576, 23584, 23590, -1, 16865, 23584, 23576, -1, 16865, 23574, 23524, -1, 23592, 16757, 16755, -1, 23592, 16755, 23593, -1, 23594, 23593, 23595, -1, 23594, 23592, 23593, -1, 23596, 23595, 23597, -1, 23596, 23594, 23595, -1, 18068, 23597, 18074, -1, 18068, 23596, 23597, -1, 23598, 17982, 17990, -1, 23598, 17990, 23599, -1, 23600, 23599, 23601, -1, 23600, 23598, 23599, -1, 23602, 23601, 23603, -1, 23602, 23600, 23601, -1, 16553, 23603, 16548, -1, 16553, 23602, 23603, -1, 23604, 18062, 18057, -1, 23604, 18057, 23605, -1, 23606, 23605, 23607, -1, 23606, 23604, 23605, -1, 23608, 23607, 23609, -1, 23608, 23606, 23607, -1, 16552, 23609, 16560, -1, 16552, 23608, 23609, -1, 16870, 23610, 23611, -1, 16869, 23610, 16870, -1, 23611, 23612, 23613, -1, 23610, 23612, 23611, -1, 23613, 23614, 23615, -1, 23612, 23614, 23613, -1, 23615, 23616, 16896, -1, 23614, 23616, 23615, -1, 23616, 16901, 16896, -1, 23611, 22431, 16870, -1, 23613, 16895, 23611, -1, 23615, 16895, 23613, -1, 16896, 16895, 23615, -1, 16893, 23617, 23618, -1, 16893, 16889, 23617, -1, 22431, 23619, 16799, -1, 16799, 23619, 23618, -1, 23611, 23619, 22431, -1, 16895, 23619, 23611, -1, 23618, 23619, 16893, -1, 16895, 23620, 23619, -1, 23619, 23620, 16893, -1, 16893, 23621, 16895, -1, 23620, 23621, 16893, -1, 16895, 23621, 23620, -1, 16889, 23622, 23617, -1, 16891, 23622, 16889, -1, 23622, 23623, 23617, -1, 23623, 23624, 23617, -1, 23624, 23625, 23617, -1, 23617, 23626, 23618, -1, 23625, 23626, 23617, -1, 23626, 23627, 23618, -1, 23627, 23628, 23618, -1, 23628, 23629, 23618, -1, 23618, 23630, 16799, -1, 23629, 23630, 23618, -1, 23630, 23631, 16799, -1, 23631, 16800, 16799, -1, 23632, 23627, 23633, -1, 23628, 23627, 23632, -1, 23627, 23634, 23633, -1, 23627, 23635, 23634, -1, 23627, 23636, 23635, -1, 23626, 23637, 23627, -1, 23627, 23637, 23636, -1, 23626, 23638, 23637, -1, 23626, 23639, 23638, -1, 23626, 23640, 23639, -1, 23626, 23641, 23640, -1, 23626, 23642, 23641, -1, 23626, 23643, 23642, -1, 23626, 23644, 23643, -1, 23626, 23645, 23644, -1, 23626, 23625, 23645, -1, 17422, 17196, 17421, -1, 17197, 17196, 17422, -1, 17127, 16215, 17128, -1, 16212, 16215, 17127, -1, 17195, 17205, 17196, -1, 17196, 17205, 17421, -1, 17205, 17399, 17421, -1, 16217, 17128, 16215, -1, 16224, 16223, 16217, -1, 16217, 16223, 17128, -1, 23646, 23647, 23648, -1, 23646, 23648, 23649, -1, 23650, 23649, 23651, -1, 23650, 23646, 23649, -1, 19066, 23651, 19049, -1, 19066, 23650, 23651, -1, 23652, 23653, 23647, -1, 23653, 23648, 23647, -1, 23648, 23654, 23655, -1, 23653, 23654, 23648, -1, 23655, 23654, 23656, -1, 23657, 23658, 23659, -1, 23656, 23658, 23657, -1, 23654, 23658, 23656, -1, 23659, 23660, 23661, -1, 23658, 23660, 23659, -1, 23660, 23662, 23661, -1, 23661, 23662, 23663, -1, 23663, 23664, 23665, -1, 23662, 23664, 23663, -1, 23665, 23664, 23666, -1, 23666, 23664, 23667, -1, 23667, 23668, 23669, -1, 23664, 23668, 23667, -1, 23669, 23670, 23671, -1, 23668, 23670, 23669, -1, 23672, 23673, 23674, -1, 23671, 23673, 23672, -1, 23670, 23673, 23671, -1, 23674, 23675, 23676, -1, 23673, 23675, 23674, -1, 23676, 23677, 23678, -1, 23675, 23677, 23676, -1, 23679, 23677, 23680, -1, 23678, 23677, 23679, -1, 23679, 23680, 23681, -1, 23682, 23683, 23684, -1, 23681, 23683, 23682, -1, 23680, 23683, 23681, -1, 23684, 23685, 23686, -1, 23683, 23685, 23684, -1, 23686, 23687, 23688, -1, 23685, 23687, 23686, -1, 23688, 23689, 23690, -1, 23687, 23689, 23688, -1, 23690, 23691, 23692, -1, 23689, 23691, 23690, -1, 23692, 23691, 23693, -1, 23693, 23694, 23695, -1, 23691, 23694, 23693, -1, 23695, 23696, 23697, -1, 23694, 23696, 23695, -1, 23697, 23698, 23699, -1, 23696, 23698, 23697, -1, 23699, 23700, 23701, -1, 23701, 23700, 23702, -1, 23698, 23700, 23699, -1, 23700, 23703, 23702, -1, 23700, 23704, 23703, -1, 23651, 23705, 21506, -1, 23651, 21506, 19049, -1, 23706, 23705, 23651, -1, 23649, 23706, 23651, -1, 23655, 23706, 23649, -1, 23648, 23655, 23649, -1, 21503, 23707, 21501, -1, 23659, 23708, 23707, -1, 23659, 23661, 23708, -1, 23659, 23707, 21503, -1, 23657, 21503, 21505, -1, 23657, 23659, 21503, -1, 23705, 21505, 21506, -1, 23656, 23657, 21505, -1, 23656, 21505, 23705, -1, 23706, 23656, 23705, -1, 23655, 23656, 23706, -1, 23707, 23709, 21499, -1, 23707, 21499, 21501, -1, 23708, 23710, 23709, -1, 23708, 23663, 23710, -1, 23708, 23709, 23707, -1, 23661, 23663, 23708, -1, 21507, 21499, 23709, -1, 23711, 23709, 23710, -1, 23711, 21507, 23709, -1, 23712, 23710, 23663, -1, 23712, 23711, 23710, -1, 23665, 23712, 23663, -1, 23712, 23665, 23666, -1, 23713, 23712, 23666, -1, 23711, 23712, 23713, -1, 23714, 23711, 23713, -1, 21508, 21507, 23711, -1, 21508, 23711, 23714, -1, 21721, 23715, 21448, -1, 23666, 23667, 23713, -1, 23716, 21721, 21723, -1, 23716, 23715, 21721, -1, 23717, 23718, 23715, -1, 23717, 23715, 23716, -1, 23719, 23674, 23676, -1, 23719, 23672, 23674, -1, 23719, 23720, 23718, -1, 23719, 23676, 23720, -1, 23719, 23718, 23717, -1, 23721, 21723, 21726, -1, 23721, 23716, 21723, -1, 23722, 23717, 23716, -1, 23722, 23716, 23721, -1, 23723, 23671, 23672, -1, 23723, 23672, 23719, -1, 23723, 23719, 23717, -1, 23723, 23717, 23722, -1, 23724, 21726, 21728, -1, 23724, 23721, 21726, -1, 23725, 23722, 23721, -1, 23725, 23721, 23724, -1, 23726, 23669, 23671, -1, 23726, 23723, 23722, -1, 23726, 23671, 23723, -1, 23726, 23722, 23725, -1, 23726, 23725, 23669, -1, 23727, 21508, 23714, -1, 23727, 21728, 21508, -1, 23727, 23724, 21728, -1, 23728, 23714, 23713, -1, 23728, 23725, 23724, -1, 23728, 23727, 23714, -1, 23728, 23669, 23725, -1, 23728, 23724, 23727, -1, 23729, 23667, 23669, -1, 23729, 23728, 23713, -1, 23729, 23669, 23728, -1, 23729, 23713, 23667, -1, 23730, 23720, 23676, -1, 23730, 23676, 23678, -1, 23731, 23718, 23720, -1, 23731, 23720, 23730, -1, 23715, 23718, 23731, -1, 23732, 23715, 23731, -1, 21448, 23715, 23732, -1, 21442, 21448, 23732, -1, 23730, 23678, 23679, -1, 23730, 23679, 23733, -1, 23731, 23733, 23734, -1, 23731, 23730, 23733, -1, 23732, 23734, 23735, -1, 23732, 23731, 23734, -1, 21442, 23735, 21432, -1, 21442, 23732, 23735, -1, 23681, 23733, 23679, -1, 23736, 23734, 23733, -1, 23736, 23733, 23681, -1, 23737, 23734, 23736, -1, 23738, 23735, 23734, -1, 23738, 23734, 23737, -1, 21430, 21432, 23735, -1, 21430, 23735, 23738, -1, 21420, 23739, 21295, -1, 23681, 23682, 23736, -1, 23740, 21420, 21421, -1, 23740, 23739, 21420, -1, 23741, 23742, 23739, -1, 23741, 23739, 23740, -1, 23743, 23688, 23690, -1, 23743, 23690, 23742, -1, 23743, 23742, 23741, -1, 23744, 21421, 21423, -1, 23744, 23740, 21421, -1, 23745, 23741, 23740, -1, 23745, 23740, 23744, -1, 23746, 21425, 21427, -1, 23746, 21423, 21425, -1, 23746, 23744, 21423, -1, 23747, 23686, 23688, -1, 23747, 23743, 23741, -1, 23747, 23688, 23743, -1, 23747, 23741, 23745, -1, 23748, 23745, 23744, -1, 23748, 23744, 23746, -1, 23749, 21430, 23738, -1, 23749, 21427, 21430, -1, 23749, 23746, 21427, -1, 23750, 23684, 23686, -1, 23750, 23745, 23748, -1, 23750, 23686, 23747, -1, 23750, 23747, 23745, -1, 23751, 23738, 23737, -1, 23751, 23749, 23738, -1, 23751, 23748, 23746, -1, 23751, 23746, 23749, -1, 23752, 23737, 23736, -1, 23752, 23682, 23684, -1, 23752, 23684, 23750, -1, 23752, 23751, 23737, -1, 23752, 23736, 23682, -1, 23752, 23750, 23748, -1, 23752, 23748, 23751, -1, 23753, 23742, 23690, -1, 23753, 23690, 23692, -1, 23754, 23739, 23742, -1, 23754, 23742, 23753, -1, 21295, 23739, 23754, -1, 21303, 21295, 23754, -1, 23692, 23693, 23755, -1, 23753, 23692, 23755, -1, 23754, 23755, 23756, -1, 23754, 23753, 23755, -1, 21303, 23756, 21180, -1, 21303, 23754, 23756, -1, 23757, 21178, 21180, -1, 23756, 23757, 21180, -1, 23758, 23757, 23756, -1, 23755, 23758, 23756, -1, 23693, 23695, 23758, -1, 23693, 23758, 23755, -1, 21174, 23759, 20045, -1, 23760, 23759, 21174, -1, 23699, 23701, 23760, -1, 23699, 21174, 21176, -1, 23699, 23760, 21174, -1, 23697, 23699, 21176, -1, 23757, 21176, 21178, -1, 23757, 23697, 21176, -1, 23758, 23697, 23757, -1, 23695, 23697, 23758, -1, 23761, 23760, 23701, -1, 23761, 23701, 23702, -1, 23762, 23759, 23760, -1, 23762, 23760, 23761, -1, 20045, 23759, 23762, -1, 19861, 20045, 23762, -1, 23702, 23703, 23763, -1, 23761, 23763, 23764, -1, 23761, 23702, 23763, -1, 23762, 23764, 19793, -1, 23762, 23761, 23764, -1, 19861, 23762, 19793, -1, 16515, 16569, 23765, -1, 16515, 16513, 16569, -1, 16516, 23765, 23766, -1, 16516, 16515, 23765, -1, 15021, 23766, 23767, -1, 15021, 16516, 23766, -1, 15019, 23767, 23768, -1, 15019, 15021, 23767, -1, 15020, 23768, 16972, -1, 15020, 15019, 23768, -1, 15018, 15020, 16972, -1, 23765, 16569, 23769, -1, 18686, 23770, 18681, -1, 18688, 23770, 18686, -1, 18690, 23770, 18688, -1, 16972, 23768, 22063, -1, 23771, 23767, 23766, -1, 23771, 23766, 23765, -1, 23771, 23769, 23772, -1, 23771, 23765, 23769, -1, 23773, 23768, 23767, -1, 23773, 23774, 23770, -1, 23773, 23772, 23774, -1, 23773, 23771, 23772, -1, 23773, 23767, 23771, -1, 23775, 22062, 22063, -1, 23775, 18690, 22062, -1, 23775, 23768, 23773, -1, 23775, 23773, 23770, -1, 23775, 23770, 18690, -1, 23775, 22063, 23768, -1, 18683, 18678, 18681, -1, 18683, 18681, 23770, -1, 22064, 23770, 23774, -1, 22064, 18683, 23770, -1, 22067, 22064, 23774, -1, 16781, 23774, 23772, -1, 16781, 22067, 23774, -1, 16782, 23772, 23769, -1, 16782, 16781, 23772, -1, 16783, 23769, 16569, -1, 16783, 16782, 23769, -1, 16570, 16783, 16569, -1, 16540, 16800, 23776, -1, 16541, 23776, 23777, -1, 16541, 16540, 23776, -1, 16542, 23777, 16720, -1, 16542, 16541, 23777, -1, 16539, 16542, 16720, -1, 23776, 16800, 23631, -1, 23630, 23776, 23631, -1, 23777, 23776, 23630, -1, 16729, 16720, 23777, -1, 16729, 23777, 23630, -1, 23778, 23629, 23628, -1, 23778, 23630, 23629, -1, 16730, 16729, 23630, -1, 23779, 23630, 23778, -1, 23779, 16730, 23630, -1, 16734, 16730, 23779, -1, 23780, 23625, 23624, -1, 16894, 23781, 23780, -1, 16894, 23623, 23622, -1, 16894, 23624, 23623, -1, 16894, 23780, 23624, -1, 21894, 23781, 16894, -1, 16891, 16894, 23622, -1, 16739, 21894, 16752, -1, 23779, 23781, 21894, -1, 23779, 16739, 16734, -1, 23779, 21894, 16739, -1, 23645, 23625, 23780, -1, 23644, 23645, 23780, -1, 23643, 23644, 23780, -1, 23642, 23643, 23780, -1, 23641, 23642, 23780, -1, 23640, 23641, 23780, -1, 23639, 23640, 23780, -1, 23638, 23780, 23781, -1, 23638, 23639, 23780, -1, 23637, 23638, 23781, -1, 23778, 23781, 23779, -1, 23778, 23637, 23781, -1, 23636, 23637, 23778, -1, 23635, 23636, 23778, -1, 23634, 23635, 23778, -1, 23633, 23634, 23778, -1, 23632, 23633, 23778, -1, 23628, 23632, 23778, -1, 17978, 14991, 14988, -1, 17989, 17978, 14988, -1, 17988, 14988, 14990, -1, 17988, 17989, 14988, -1, 17990, 17988, 14990, -1, 23599, 17990, 14990, -1, 23601, 23599, 14990, -1, 23603, 23601, 14990, -1, 16548, 14990, 14989, -1, 16548, 23603, 14990, -1, 16547, 16548, 14989, -1, 16549, 14989, 14992, -1, 16549, 16547, 14989, -1, 16546, 16549, 14992, -1, 14985, 14984, 18061, -1, 14985, 18063, 18062, -1, 14985, 18061, 18063, -1, 14986, 23608, 16552, -1, 14986, 23606, 23608, -1, 14986, 23604, 23606, -1, 14986, 18062, 23604, -1, 14986, 14985, 18062, -1, 14987, 16551, 16550, -1, 14987, 16552, 16551, -1, 14987, 14986, 16552, -1, 14983, 16550, 16545, -1, 14983, 14987, 16550, -1, 18067, 14978, 14982, -1, 18065, 18067, 14982, -1, 18066, 14982, 14981, -1, 18066, 18065, 14982, -1, 18068, 18066, 14981, -1, 23596, 18068, 14981, -1, 23594, 23596, 14981, -1, 23592, 23594, 14981, -1, 16757, 14981, 14980, -1, 16757, 23592, 14981, -1, 16763, 16757, 14980, -1, 16765, 14980, 14979, -1, 16765, 16763, 14980, -1, 16544, 16765, 14979, -1, 16910, 15015, 15014, -1, 16910, 16902, 15015, -1, 16911, 16910, 15014, -1, 16912, 15014, 15013, -1, 16912, 16911, 15014, -1, 21997, 16912, 15013, -1, 22000, 15013, 15012, -1, 22000, 21997, 15013, -1, 22003, 22000, 15012, -1, 16960, 22003, 15012, -1, 16961, 15012, 15016, -1, 16961, 16960, 15012, -1, 16962, 16961, 15016, -1, 16944, 16962, 15016, -1, 16897, 3134, 3132, -1, 16897, 16873, 3134, -1, 16898, 16897, 3132, -1, 22059, 16898, 3132, -1, 22058, 3132, 3131, -1, 22058, 22059, 3132, -1, 16905, 22058, 3131, -1, 16904, 3131, 3130, -1, 16904, 16905, 3131, -1, 16903, 16904, 3130, -1, 16866, 3137, 16871, -1, 16871, 3139, 16868, -1, 16868, 3139, 16869, -1, 16869, 3139, 23610, -1, 3137, 3139, 16871, -1, 23610, 3141, 23612, -1, 3139, 3141, 23610, -1, 23612, 3140, 23614, -1, 23614, 3140, 23616, -1, 23616, 3140, 16901, -1, 3141, 3140, 23612, -1, 16901, 3138, 16900, -1, 16900, 3138, 16899, -1, 3140, 3138, 16901, -1, 16899, 3136, 16874, -1, 3138, 3136, 16899, -1, 3247, 3245, 16846, -1, 16846, 3245, 16848, -1, 16848, 3246, 16851, -1, 3245, 3246, 16848, -1, 16851, 3244, 16852, -1, 3246, 3244, 16851, -1, 16852, 3243, 16826, -1, 3244, 3243, 16852, -1, 3250, 16814, 3248, -1, 3248, 16812, 3249, -1, 16814, 16812, 3248, -1, 3249, 16811, 3251, -1, 16812, 16811, 3249, -1, 3251, 16809, 3252, -1, 16811, 16809, 3251, -1, 16809, 16801, 3252, -1, 3240, 16827, 3238, -1, 3238, 16829, 3239, -1, 16827, 16829, 3238, -1, 3239, 16855, 3241, -1, 16829, 16855, 3239, -1, 3241, 16854, 3242, -1, 16855, 16854, 3241, -1, 16854, 16825, 3242, -1, 16794, 14977, 14974, -1, 16794, 16543, 14977, -1, 16795, 14974, 14976, -1, 16795, 16794, 14974, -1, 16796, 14976, 14975, -1, 16796, 16795, 14976, -1, 16798, 3125, 3124, -1, 16798, 16797, 3125, -1, 22432, 3124, 3127, -1, 22432, 16798, 3124, -1, 22430, 22432, 3127, -1, 16872, 3127, 3128, -1, 16872, 22430, 3127, -1, 16867, 16872, 3128, -1, 18550, 18537, 18542, -1, 23782, 18542, 18541, -1, 23782, 18550, 18542, -1, 23783, 18541, 18540, -1, 23783, 23782, 18541, -1, 23784, 23783, 18540, -1, 23785, 23786, 23787, -1, 23785, 23787, 23784, -1, 23785, 23784, 18540, -1, 23788, 18540, 18539, -1, 23788, 23785, 18540, -1, 23789, 23788, 18539, -1, 18553, 18539, 18536, -1, 18553, 23789, 18539, -1, 18543, 18551, 23790, -1, 18544, 23790, 23791, -1, 18544, 18543, 23790, -1, 23792, 23793, 23794, -1, 23792, 23794, 23795, -1, 18545, 23791, 23793, -1, 18545, 18544, 23791, -1, 18545, 23793, 23792, -1, 18546, 23792, 23796, -1, 18546, 18545, 23792, -1, 18547, 23796, 23797, -1, 18547, 23797, 18552, -1, 18547, 18546, 23796, -1, 18548, 18547, 18552, -1, 23798, 18534, 18517, -1, 23798, 18517, 18519, -1, 23799, 23798, 18519, -1, 23800, 18519, 18516, -1, 23800, 23799, 18519, -1, 23801, 23800, 18516, -1, 23802, 23801, 18516, -1, 23803, 23802, 18516, -1, 18554, 18516, 18518, -1, 18554, 23803, 18516, -1, 18521, 18535, 18520, -1, 18520, 23804, 18522, -1, 18535, 23804, 18520, -1, 18522, 23805, 18523, -1, 23804, 23805, 18522, -1, 18523, 23806, 18524, -1, 23805, 23806, 18523, -1, 18524, 23807, 18533, -1, 23806, 23807, 18524, -1, 23807, 18509, 18533, -1, 23807, 18510, 18509, -1, 18511, 18183, 18526, -1, 18183, 18188, 18526, -1, 18526, 18190, 18530, -1, 18188, 18190, 18526, -1, 18530, 18192, 18532, -1, 18190, 18192, 18530, -1, 18532, 18191, 18531, -1, 18192, 18191, 18532, -1, 18531, 18189, 18529, -1, 18191, 18189, 18531, -1, 18529, 18187, 18527, -1, 18527, 18187, 18528, -1, 18189, 18187, 18529, -1, 18528, 18037, 18040, -1, 18187, 18037, 18528, -1, 18515, 18156, 23808, -1, 18156, 18160, 23808, -1, 23808, 18161, 23809, -1, 18160, 18161, 23808, -1, 23809, 18162, 18508, -1, 18161, 18162, 23809, -1, 18141, 18147, 18512, -1, 18512, 18147, 23810, -1, 23810, 18146, 23811, -1, 18147, 18146, 23810, -1, 23811, 18151, 23812, -1, 18146, 18151, 23811, -1, 23812, 18150, 18514, -1, 18151, 18150, 23812, -1, 18617, 18590, 23813, -1, 18590, 18594, 23813, -1, 23814, 18595, 23815, -1, 23813, 18595, 23814, -1, 18594, 18595, 23813, -1, 23815, 18599, 23816, -1, 18595, 18599, 23815, -1, 23816, 18601, 23817, -1, 18599, 18601, 23816, -1, 23817, 18598, 23818, -1, 18601, 18598, 23817, -1, 23818, 18592, 23819, -1, 18598, 18592, 23818, -1, 23819, 18588, 23820, -1, 18592, 18588, 23819, -1, 23820, 18584, 23821, -1, 18588, 18584, 23820, -1, 23821, 18579, 23822, -1, 18584, 18579, 23821, -1, 23822, 18578, 23823, -1, 18579, 18578, 23822, -1, 18578, 18602, 23823, -1, 23823, 18597, 23824, -1, 18602, 18597, 23823, -1, 23824, 18593, 18604, -1, 18597, 18593, 23824, -1, 16507, 16506, 23815, -1, 16497, 23825, 23826, -1, 16497, 18608, 23825, -1, 16497, 18607, 18608, -1, 23816, 16507, 23815, -1, 18606, 18607, 16497, -1, 16443, 16445, 16490, -1, 16444, 16443, 16490, -1, 16508, 16507, 23816, -1, 16508, 23816, 23817, -1, 16496, 18606, 16497, -1, 16496, 18605, 18606, -1, 16505, 23827, 23828, -1, 16505, 23828, 23829, -1, 18614, 16489, 16488, -1, 18613, 16488, 16487, -1, 16509, 16508, 23817, -1, 18613, 18614, 16488, -1, 16509, 23817, 23818, -1, 16495, 18604, 18605, -1, 18615, 16490, 16489, -1, 16495, 18605, 16496, -1, 18615, 16489, 18614, -1, 18612, 16487, 16486, -1, 16510, 23818, 23819, -1, 16510, 16509, 23818, -1, 18612, 18613, 16487, -1, 23830, 16484, 23831, -1, 16494, 18604, 16495, -1, 18616, 16444, 16490, -1, 18616, 16490, 18615, -1, 16511, 23819, 23820, -1, 16511, 16510, 23819, -1, 18611, 16486, 16485, -1, 16493, 23824, 18604, -1, 18611, 18612, 16486, -1, 16493, 18604, 16494, -1, 18617, 23829, 16447, -1, 18617, 16447, 16444, -1, 16492, 23823, 23824, -1, 18617, 16444, 18616, -1, 16492, 23824, 16493, -1, 18610, 18611, 16485, -1, 18610, 16485, 16484, -1, 23832, 23833, 16511, -1, 23832, 16511, 23820, -1, 23832, 23820, 23821, -1, 23813, 23829, 18617, -1, 23813, 16505, 23829, -1, 16491, 23822, 23823, -1, 16491, 23821, 23822, -1, 16491, 23823, 16492, -1, 23834, 23821, 16491, -1, 23834, 23832, 23821, -1, 18609, 18610, 16484, -1, 18609, 16484, 23830, -1, 23835, 23834, 16491, -1, 23814, 16505, 23813, -1, 23814, 16506, 16505, -1, 18608, 18609, 23830, -1, 18608, 23830, 23825, -1, 23815, 16506, 23814, -1, 16408, 23836, 16501, -1, 23836, 23837, 16501, -1, 23837, 23827, 16501, -1, 23827, 16505, 16501, -1, 16490, 16445, 16471, -1, 16445, 16442, 16471, -1, 16442, 16448, 16471, -1, 16448, 16438, 16471, -1, 23838, 16483, 16420, -1, 23839, 16483, 23838, -1, 23839, 23835, 16483, -1, 23835, 16491, 16483, -1, 16511, 23833, 16498, -1, 23833, 23840, 16498, -1, 23840, 23841, 16498, -1, 23841, 16417, 16498, -1, 23842, 16462, 16461, -1, 23843, 16462, 23842, -1, 23843, 23831, 16462, -1, 23831, 16484, 16462, -1, 16497, 23826, 16473, -1, 23826, 23844, 16473, -1, 23844, 23845, 16473, -1, 23845, 16475, 16473, -1, 23844, 23826, 23825, -1, 23843, 23830, 23831, -1, 23846, 23842, 16461, -1, 23846, 17373, 16475, -1, 23846, 17374, 17373, -1, 23846, 16461, 17374, -1, 23846, 16475, 23845, -1, 23847, 23825, 23830, -1, 23847, 23830, 23843, -1, 23848, 23843, 23842, -1, 23848, 23845, 23844, -1, 23848, 23825, 23847, -1, 23848, 23847, 23843, -1, 23848, 23844, 23825, -1, 23848, 23846, 23845, -1, 23848, 23842, 23846, -1, 23837, 23828, 23827, -1, 23837, 23829, 23828, -1, 23849, 16447, 23829, -1, 23849, 23837, 23836, -1, 23849, 23829, 23837, -1, 23850, 16405, 16447, -1, 23850, 23836, 16408, -1, 23850, 16406, 16405, -1, 23850, 16407, 16406, -1, 23850, 16408, 16407, -1, 23850, 16447, 23849, -1, 23850, 23849, 23836, -1, 23840, 23833, 23832, -1, 23839, 23834, 23835, -1, 23851, 23838, 16420, -1, 23851, 16418, 16417, -1, 23851, 16419, 16418, -1, 23851, 16420, 16419, -1, 23851, 16417, 23841, -1, 23852, 23832, 23834, -1, 23852, 23834, 23839, -1, 23853, 23839, 23838, -1, 23853, 23841, 23840, -1, 23853, 23832, 23852, -1, 23853, 23852, 23839, -1, 23853, 23840, 23832, -1, 23853, 23851, 23841, -1, 23853, 23838, 23851, -1, 23854, 23855, 23856, -1, 23854, 23856, 23857, -1, 23854, 23857, 23858, -1, 23859, 23858, 23860, -1, 23859, 23854, 23858, -1, 23861, 23859, 23860, -1, 23862, 23860, 23863, -1, 23862, 23861, 23860, -1, 23864, 23863, 23865, -1, 23864, 23862, 23863, -1, 23866, 23865, 23867, -1, 23866, 23864, 23865, -1, 23868, 23867, 23869, -1, 23868, 23866, 23867, -1, 23870, 23869, 23871, -1, 23870, 23871, 18133, -1, 23870, 23868, 23869, -1, 18177, 23870, 18133, -1, 23872, 23856, 23855, -1, 23872, 23873, 23856, -1, 23874, 23875, 23876, -1, 23876, 23877, 23878, -1, 23875, 23877, 23876, -1, 23878, 23879, 23880, -1, 23877, 23879, 23878, -1, 23880, 23881, 23882, -1, 23879, 23881, 23880, -1, 23882, 23883, 23884, -1, 23881, 23883, 23882, -1, 23884, 23885, 23886, -1, 23883, 23885, 23884, -1, 23886, 23887, 23855, -1, 23885, 23887, 23886, -1, 23887, 23872, 23855, -1, 23874, 23888, 23875, -1, 23889, 23888, 23874, -1, 23890, 23891, 23892, -1, 23892, 23891, 23893, -1, 23893, 23894, 23895, -1, 23891, 23894, 23893, -1, 23895, 23896, 23889, -1, 23894, 23896, 23895, -1, 23896, 23888, 23889, -1, 23897, 23892, 23898, -1, 23890, 23892, 23897, -1, 23897, 23898, 23899, -1, 23899, 23900, 23901, -1, 23898, 23900, 23899, -1, 23901, 23902, 23903, -1, 23900, 23902, 23901, -1, 23903, 23904, 23905, -1, 23902, 23904, 23903, -1, 23904, 23906, 23905, -1, 23907, 23906, 23908, -1, 23907, 23905, 23906, -1, 23909, 18186, 23910, -1, 23909, 23911, 18185, -1, 23912, 23859, 23861, -1, 23912, 23861, 23913, -1, 23914, 23915, 23916, -1, 23914, 23880, 23915, -1, 18182, 23868, 23870, -1, 23914, 23916, 23917, -1, 18182, 23870, 18177, -1, 23918, 23919, 23920, -1, 23921, 23910, 23922, -1, 23918, 23923, 23919, -1, 23924, 23855, 23854, -1, 23924, 23854, 23859, -1, 23924, 23886, 23855, -1, 23924, 23912, 23886, -1, 23924, 23859, 23912, -1, 23921, 23925, 23911, -1, 23921, 23911, 23909, -1, 23921, 23909, 23910, -1, 23926, 23923, 23918, -1, 23927, 23878, 23880, -1, 23927, 23880, 23914, -1, 23927, 23914, 23878, -1, 23926, 23928, 23923, -1, 23929, 23922, 23930, -1, 23929, 23925, 23921, -1, 23931, 23928, 23926, -1, 23929, 23932, 23925, -1, 23931, 23933, 23928, -1, 23929, 23921, 23922, -1, 23934, 23913, 23933, -1, 23935, 23930, 23936, -1, 23934, 23933, 23931, -1, 23935, 23929, 23930, -1, 23935, 23937, 23932, -1, 23938, 23913, 23934, -1, 23938, 23912, 23913, -1, 23935, 23932, 23929, -1, 23938, 23886, 23912, -1, 23939, 18180, 18179, -1, 23940, 23917, 23937, -1, 23939, 23920, 18180, -1, 23940, 23937, 23935, -1, 23940, 23935, 23936, -1, 23941, 23936, 23942, -1, 23941, 23878, 23914, -1, 23941, 23914, 23917, -1, 23941, 23940, 23936, -1, 23941, 23917, 23940, -1, 23943, 23918, 23920, -1, 23941, 23942, 23876, -1, 23944, 23876, 23878, -1, 23944, 23941, 23876, -1, 23944, 23878, 23941, -1, 23943, 23920, 23939, -1, 23945, 23884, 23886, -1, 23945, 23938, 23884, -1, 23945, 23886, 23938, -1, 23946, 23918, 23943, -1, 23946, 23926, 23918, -1, 23947, 23926, 23946, -1, 23947, 23931, 23926, -1, 23948, 23931, 23947, -1, 23948, 23934, 23931, -1, 23949, 23934, 23948, -1, 23949, 23884, 23938, -1, 23949, 23938, 23934, -1, 23950, 18178, 18185, -1, 23950, 18179, 18178, -1, 23950, 23939, 18179, -1, 23951, 23943, 23939, -1, 23951, 23939, 23950, -1, 23952, 23949, 23882, -1, 23952, 23884, 23949, -1, 23952, 23882, 23884, -1, 23953, 23943, 23951, -1, 23953, 23946, 23943, -1, 23954, 23947, 23946, -1, 23954, 23946, 23953, -1, 23916, 23947, 23954, -1, 23916, 23948, 23947, -1, 23955, 23876, 23942, -1, 23915, 23948, 23916, -1, 23915, 23949, 23948, -1, 23915, 23882, 23949, -1, 23874, 23876, 23955, -1, 23911, 23950, 18185, -1, 23919, 18181, 18180, -1, 23919, 18182, 18181, -1, 23925, 23951, 23950, -1, 23923, 23868, 18182, -1, 23923, 18182, 23919, -1, 23925, 23950, 23911, -1, 23956, 23880, 23882, -1, 23956, 23882, 23915, -1, 23956, 23915, 23880, -1, 23932, 23953, 23951, -1, 23928, 23866, 23868, -1, 23928, 23868, 23923, -1, 23932, 23951, 23925, -1, 23933, 23862, 23864, -1, 23937, 23954, 23953, -1, 23933, 23864, 23866, -1, 23937, 23953, 23932, -1, 23933, 23866, 23928, -1, 23913, 23861, 23862, -1, 23917, 23916, 23954, -1, 23913, 23862, 23933, -1, 23917, 23954, 23937, -1, 23909, 18184, 18186, -1, 23920, 23919, 18180, -1, 23909, 18185, 18184, -1, 23957, 23874, 23955, -1, 23957, 23889, 23874, -1, 23958, 23955, 23942, -1, 23958, 23957, 23955, -1, 23959, 23942, 23936, -1, 23959, 23958, 23942, -1, 23960, 23936, 23930, -1, 23960, 23959, 23936, -1, 23961, 23930, 23922, -1, 23961, 23960, 23930, -1, 23962, 23922, 23910, -1, 23962, 23961, 23922, -1, 18176, 23910, 18186, -1, 18176, 23962, 23910, -1, 18175, 23960, 23961, -1, 18175, 23961, 23962, -1, 18175, 23962, 18176, -1, 23895, 23889, 23957, -1, 23963, 18173, 18165, -1, 23964, 18173, 23963, -1, 23965, 18175, 18174, -1, 23966, 23965, 18174, -1, 23966, 18175, 23965, -1, 23967, 23959, 23960, -1, 23967, 23960, 18175, -1, 23967, 23966, 18174, -1, 23967, 18175, 23966, -1, 23968, 23959, 23967, -1, 23969, 23958, 23959, -1, 23969, 23959, 23968, -1, 23970, 23957, 23958, -1, 23970, 23893, 23895, -1, 23970, 23958, 23969, -1, 23970, 23895, 23957, -1, 23971, 18174, 18173, -1, 23972, 18174, 23971, -1, 23972, 23971, 18173, -1, 23972, 18173, 23964, -1, 23973, 23964, 23974, -1, 23973, 23972, 23964, -1, 23973, 18174, 23972, -1, 23973, 23967, 18174, -1, 23975, 23974, 23976, -1, 23975, 23968, 23967, -1, 23975, 23967, 23973, -1, 23975, 23973, 23974, -1, 23977, 23976, 23978, -1, 23977, 23975, 23976, -1, 23977, 23968, 23975, -1, 23977, 23969, 23968, -1, 23979, 23978, 23892, -1, 23979, 23892, 23893, -1, 23979, 23893, 23970, -1, 23979, 23970, 23969, -1, 23979, 23977, 23978, -1, 23979, 23969, 23977, -1, 23963, 18165, 18144, -1, 23963, 23980, 23981, -1, 23963, 18144, 23980, -1, 23964, 23981, 23982, -1, 23964, 23963, 23981, -1, 23974, 23982, 23983, -1, 23974, 23964, 23982, -1, 23976, 23983, 23984, -1, 23976, 23974, 23983, -1, 23978, 23984, 23898, -1, 23978, 23976, 23984, -1, 23892, 23978, 23898, -1, 18140, 23981, 23980, -1, 18140, 23980, 18144, -1, 23900, 23898, 23984, -1, 23985, 23904, 23986, -1, 23987, 23904, 23985, -1, 23906, 23904, 23987, -1, 23988, 18140, 18137, -1, 23989, 23988, 18137, -1, 23989, 18140, 23988, -1, 23989, 23981, 18140, -1, 23990, 23982, 23981, -1, 23990, 23989, 18137, -1, 23990, 23981, 23989, -1, 23991, 23984, 23983, -1, 23991, 23983, 23982, -1, 23991, 23982, 23990, -1, 23992, 23900, 23984, -1, 23992, 23984, 23991, -1, 23993, 18137, 18134, -1, 23993, 18134, 23994, -1, 23995, 23994, 23986, -1, 23995, 23993, 23994, -1, 23995, 18137, 23993, -1, 23995, 23986, 23904, -1, 23996, 18137, 23995, -1, 23996, 23990, 18137, -1, 23996, 23995, 23904, -1, 23997, 23991, 23990, -1, 23997, 23996, 23904, -1, 23997, 23990, 23996, -1, 23998, 23902, 23900, -1, 23998, 23904, 23902, -1, 23998, 23997, 23904, -1, 23998, 23992, 23991, -1, 23998, 23900, 23992, -1, 23998, 23991, 23997, -1, 23999, 23908, 23906, -1, 23999, 23906, 23987, -1, 23999, 23987, 23985, -1, 24000, 23999, 23985, -1, 24001, 23985, 23986, -1, 24001, 23986, 23994, -1, 24001, 24000, 23985, -1, 24002, 23994, 18134, -1, 24002, 24001, 23994, -1, 18104, 24002, 18134, -1, 24003, 24004, 24005, -1, 24006, 24007, 24008, -1, 24003, 24009, 24004, -1, 24010, 18492, 18490, -1, 24011, 18159, 18158, -1, 24011, 24012, 18159, -1, 24010, 18490, 24013, -1, 24014, 18561, 24015, -1, 24014, 18563, 18561, -1, 24016, 24007, 24006, -1, 24014, 24015, 24017, -1, 24014, 24017, 24018, -1, 24016, 24019, 24007, -1, 24020, 24021, 24009, -1, 24022, 18167, 18166, -1, 24020, 24009, 24003, -1, 24022, 24023, 18167, -1, 24024, 18422, 18492, -1, 24024, 18555, 18422, -1, 24024, 18492, 24010, -1, 24025, 24012, 24011, -1, 24026, 24019, 24016, -1, 24025, 24005, 24012, -1, 24026, 24013, 24019, -1, 24027, 24018, 24021, -1, 24028, 24006, 24023, -1, 24027, 24021, 24020, -1, 24028, 24023, 24022, -1, 24029, 24003, 24005, -1, 24030, 24013, 24026, -1, 24029, 24005, 24025, -1, 24030, 24010, 24013, -1, 18555, 18420, 18422, -1, 24031, 18158, 18157, -1, 24031, 18157, 24032, -1, 24033, 24006, 24028, -1, 24031, 24011, 18158, -1, 24034, 18565, 18563, -1, 24033, 24016, 24006, -1, 24034, 18563, 24014, -1, 24034, 24014, 24018, -1, 24035, 18166, 18164, -1, 24034, 24018, 24027, -1, 24035, 24022, 18166, -1, 24036, 18557, 18555, -1, 24037, 24003, 24029, -1, 24036, 18555, 24024, -1, 24037, 24020, 24003, -1, 24036, 24024, 24010, -1, 24036, 24010, 24030, -1, 24038, 24016, 24033, -1, 24039, 24032, 24040, -1, 24039, 24025, 24011, -1, 24038, 24026, 24016, -1, 24039, 24011, 24031, -1, 24039, 24031, 24032, -1, 24041, 24022, 24035, -1, 24041, 24028, 24022, -1, 24042, 24020, 24037, -1, 24042, 24027, 24020, -1, 24043, 24026, 24038, -1, 24044, 24040, 24045, -1, 24043, 24030, 24026, -1, 24044, 24029, 24025, -1, 24046, 24033, 24028, -1, 24044, 24039, 24040, -1, 24046, 24028, 24041, -1, 24044, 24025, 24039, -1, 24047, 18567, 18565, -1, 24047, 18565, 24034, -1, 24047, 24034, 24027, -1, 24047, 24027, 24042, -1, 24048, 18164, 18163, -1, 24049, 24050, 24051, -1, 24049, 24045, 24050, -1, 24049, 24037, 24029, -1, 24048, 24035, 18164, -1, 24049, 24029, 24044, -1, 24049, 24044, 24045, -1, 24052, 24036, 24030, -1, 24052, 18559, 18557, -1, 24052, 18557, 24036, -1, 24053, 24049, 24051, -1, 24052, 24030, 24043, -1, 24053, 24037, 24049, -1, 24054, 24033, 24046, -1, 24053, 24042, 24037, -1, 24055, 24042, 24053, -1, 24055, 24056, 18571, -1, 24054, 24038, 24033, -1, 24055, 24051, 24056, -1, 24055, 18569, 18567, -1, 24055, 18571, 18569, -1, 24055, 18567, 24047, -1, 24004, 24035, 24048, -1, 24055, 24047, 24042, -1, 24055, 24053, 24051, -1, 24004, 24041, 24035, -1, 24017, 24043, 24038, -1, 24017, 24038, 24054, -1, 24009, 24046, 24041, -1, 24009, 24041, 24004, -1, 24008, 18465, 18170, -1, 24012, 18163, 18159, -1, 24012, 24048, 18163, -1, 24008, 18169, 18168, -1, 24008, 18170, 18169, -1, 24007, 18478, 18465, -1, 24015, 18559, 24052, -1, 24015, 18561, 18559, -1, 24015, 24043, 24017, -1, 24007, 18465, 24008, -1, 24015, 24052, 24043, -1, 24019, 18484, 18478, -1, 24021, 24046, 24009, -1, 24021, 24054, 24046, -1, 24005, 24004, 24048, -1, 24019, 18478, 24007, -1, 24023, 18168, 18167, -1, 24005, 24048, 24012, -1, 24023, 24008, 18168, -1, 24018, 24017, 24054, -1, 24018, 24054, 24021, -1, 24013, 18490, 18484, -1, 24013, 18484, 24019, -1, 24006, 24008, 24023, -1, 24057, 18157, 18155, -1, 24057, 18155, 18387, -1, 24057, 18387, 18389, -1, 24057, 18389, 18391, -1, 24058, 18391, 18395, -1, 24058, 18395, 18398, -1, 24058, 24057, 18391, -1, 24058, 18573, 24057, -1, 24059, 18398, 18384, -1, 24059, 18384, 18383, -1, 24059, 18575, 18573, -1, 24059, 18383, 18575, -1, 24059, 18573, 24058, -1, 24059, 24058, 18398, -1, 24060, 18571, 24056, -1, 24060, 24056, 24051, -1, 24060, 24051, 24050, -1, 24060, 24050, 24045, -1, 24060, 24045, 24040, -1, 24060, 24040, 24032, -1, 24060, 24032, 18157, -1, 24060, 18573, 18571, -1, 24060, 18157, 24057, -1, 24060, 24057, 18573, -1, 18056, 18010, 18009, -1, 24061, 18009, 18006, -1, 24061, 18056, 18009, -1, 24062, 18006, 18008, -1, 24062, 24061, 18006, -1, 24063, 18008, 18549, -1, 24063, 24062, 18008, -1, 18552, 24063, 18549, -1, 18055, 24064, 18057, -1, 18055, 24065, 24064, -1, 18055, 24066, 24065, -1, 24067, 18055, 18054, -1, 24068, 24067, 18054, -1, 24068, 18055, 24067, -1, 24069, 24066, 18055, -1, 24069, 18055, 24068, -1, 24070, 23796, 23792, -1, 24070, 24071, 24066, -1, 24070, 23792, 24071, -1, 24070, 24066, 24069, -1, 24072, 18056, 24061, -1, 24072, 18054, 18056, -1, 24073, 24061, 24062, -1, 24073, 24068, 18054, -1, 24073, 18054, 24072, -1, 24073, 24072, 24061, -1, 24074, 24062, 24063, -1, 24074, 24069, 24068, -1, 24074, 24073, 24062, -1, 24074, 24068, 24073, -1, 24075, 24063, 18552, -1, 24075, 23797, 23796, -1, 24075, 18552, 23797, -1, 24075, 24074, 24063, -1, 24075, 23796, 24070, -1, 24075, 24070, 24069, -1, 24075, 24069, 24074, -1, 24076, 23794, 23793, -1, 23605, 18057, 24064, -1, 16560, 23609, 24077, -1, 24078, 24071, 23792, -1, 24078, 23792, 23795, -1, 24079, 24066, 24071, -1, 24079, 24071, 24078, -1, 24080, 23795, 23794, -1, 24080, 24078, 23795, -1, 24080, 23794, 24076, -1, 24081, 24065, 24066, -1, 24081, 24066, 24079, -1, 24082, 24076, 24083, -1, 24082, 24080, 24076, -1, 24082, 24079, 24078, -1, 24082, 24078, 24080, -1, 24084, 24065, 24081, -1, 24085, 24086, 24087, -1, 24085, 24083, 24086, -1, 24085, 24082, 24083, -1, 24085, 24079, 24082, -1, 24085, 24081, 24079, -1, 24088, 24064, 24065, -1, 24088, 23607, 23605, -1, 24088, 23605, 24064, -1, 24088, 24065, 24084, -1, 24089, 24087, 24090, -1, 24089, 24084, 24081, -1, 24089, 24085, 24087, -1, 24089, 24081, 24085, -1, 24091, 24090, 24077, -1, 24091, 23609, 23607, -1, 24091, 24089, 24090, -1, 24091, 24088, 24084, -1, 24091, 23607, 24088, -1, 24091, 24084, 24089, -1, 24091, 24077, 23609, -1, 24092, 24093, 24083, -1, 24092, 24076, 23791, -1, 24092, 24094, 24095, -1, 24092, 24095, 24093, -1, 16559, 24096, 16557, -1, 23793, 23791, 24076, -1, 24097, 24096, 16559, -1, 24098, 24099, 24096, -1, 24098, 24096, 24097, -1, 24100, 16560, 24077, -1, 24100, 16558, 16560, -1, 24100, 16559, 16558, -1, 24100, 24097, 16559, -1, 24101, 24102, 24099, -1, 24101, 24099, 24098, -1, 24103, 24077, 24090, -1, 24103, 24098, 24097, -1, 24103, 24100, 24077, -1, 24103, 24097, 24100, -1, 24104, 24105, 24102, -1, 24104, 24102, 24101, -1, 24106, 24090, 24087, -1, 24106, 24103, 24090, -1, 24106, 24101, 24098, -1, 24106, 24098, 24103, -1, 24095, 24107, 24105, -1, 24095, 24105, 24104, -1, 24108, 24087, 24086, -1, 24108, 24106, 24087, -1, 24108, 24101, 24106, -1, 24108, 24104, 24101, -1, 24094, 23790, 18551, -1, 24094, 24109, 24107, -1, 24094, 18551, 24109, -1, 24094, 24107, 24095, -1, 24093, 24086, 24083, -1, 24093, 24108, 24086, -1, 24093, 24095, 24104, -1, 24093, 24104, 24108, -1, 24092, 24083, 24076, -1, 24092, 23791, 23790, -1, 24092, 23790, 24094, -1, 24109, 18551, 18550, -1, 24109, 18550, 24110, -1, 24107, 24110, 24111, -1, 24107, 24109, 24110, -1, 24105, 24112, 24113, -1, 24105, 24111, 24112, -1, 24105, 24107, 24111, -1, 24102, 24113, 24114, -1, 24102, 24105, 24113, -1, 24099, 24114, 24115, -1, 24099, 24102, 24114, -1, 24096, 24115, 16556, -1, 24096, 24099, 24115, -1, 16557, 24096, 16556, -1, 24116, 24111, 24110, -1, 24116, 23782, 23783, -1, 24116, 23783, 24117, -1, 24116, 24118, 24119, -1, 24116, 24110, 23782, -1, 24116, 24119, 24111, -1, 24116, 24117, 24118, -1, 16555, 24120, 16553, -1, 24115, 16554, 16556, -1, 18550, 23782, 24110, -1, 24121, 24120, 16555, -1, 24122, 24123, 24120, -1, 24122, 24120, 24121, -1, 24124, 16555, 16554, -1, 24124, 16554, 24115, -1, 24124, 24121, 16555, -1, 24125, 24126, 24123, -1, 24125, 24123, 24122, -1, 24127, 24115, 24114, -1, 24127, 24122, 24121, -1, 24127, 24124, 24115, -1, 24127, 24121, 24124, -1, 24128, 24129, 24126, -1, 24128, 24126, 24125, -1, 24130, 24114, 24113, -1, 24130, 24122, 24127, -1, 24130, 24127, 24114, -1, 24130, 24125, 24122, -1, 24118, 24131, 24129, -1, 24118, 24129, 24128, -1, 24132, 24113, 24112, -1, 24132, 24130, 24113, -1, 24132, 24125, 24130, -1, 24132, 24128, 24125, -1, 24117, 23783, 23784, -1, 24117, 24133, 24131, -1, 24117, 23784, 24133, -1, 24117, 24131, 24118, -1, 24119, 24112, 24111, -1, 24119, 24118, 24128, -1, 24119, 24132, 24112, -1, 24119, 24128, 24132, -1, 23787, 24133, 23784, -1, 23602, 16553, 24120, -1, 17982, 23598, 24134, -1, 24135, 23787, 23786, -1, 24135, 24133, 23787, -1, 24136, 24131, 24133, -1, 24136, 24133, 24135, -1, 24137, 23786, 23785, -1, 24137, 23785, 24138, -1, 24137, 24135, 23786, -1, 24139, 24126, 24129, -1, 24139, 24129, 24131, -1, 24139, 24131, 24136, -1, 24140, 24138, 24141, -1, 24140, 24136, 24135, -1, 24140, 24135, 24137, -1, 24140, 24137, 24138, -1, 24142, 24123, 24126, -1, 24142, 24126, 24139, -1, 24143, 24141, 24144, -1, 24143, 24136, 24140, -1, 24143, 24140, 24141, -1, 24143, 24139, 24136, -1, 24145, 24120, 24123, -1, 24145, 23600, 23602, -1, 24145, 23602, 24120, -1, 24145, 24123, 24142, -1, 24146, 24142, 24139, -1, 24146, 24139, 24143, -1, 24146, 24143, 24144, -1, 24147, 24144, 24134, -1, 24147, 23598, 23600, -1, 24147, 24142, 24146, -1, 24147, 23600, 24145, -1, 24147, 24145, 24142, -1, 24147, 24146, 24144, -1, 24147, 24134, 23598, -1, 23788, 24144, 24141, -1, 23788, 24141, 24138, -1, 23788, 24138, 23785, -1, 17979, 17982, 24134, -1, 24148, 23788, 23789, -1, 24149, 24148, 23789, -1, 24149, 23788, 24148, -1, 24150, 24144, 23788, -1, 24150, 23788, 24149, -1, 24151, 24134, 24144, -1, 24151, 24144, 24150, -1, 24151, 17979, 24134, -1, 24152, 23789, 18553, -1, 24152, 18553, 24153, -1, 24154, 24153, 24155, -1, 24154, 23789, 24152, -1, 24154, 24152, 24153, -1, 24154, 24149, 23789, -1, 24156, 24155, 24157, -1, 24156, 24154, 24155, -1, 24156, 24150, 24149, -1, 24156, 24149, 24154, -1, 24158, 24157, 17981, -1, 24158, 17980, 17979, -1, 24158, 17981, 17980, -1, 24158, 24156, 24157, -1, 24158, 24150, 24156, -1, 24158, 24151, 24150, -1, 24158, 17979, 24151, -1, 24153, 18553, 18538, -1, 24153, 18538, 17993, -1, 24155, 17993, 17992, -1, 24155, 24153, 17993, -1, 24157, 17992, 17991, -1, 24157, 24155, 17992, -1, 17981, 17991, 17984, -1, 17981, 24157, 17991, -1, 18513, 18512, 24159, -1, 24160, 24159, 24161, -1, 24160, 18513, 24159, -1, 24162, 24161, 24163, -1, 24162, 24160, 24161, -1, 24164, 24163, 24165, -1, 24164, 24162, 24163, -1, 24166, 24165, 24167, -1, 24166, 24164, 24165, -1, 24168, 24167, 24169, -1, 24168, 24166, 24167, -1, 24170, 24169, 16775, -1, 24170, 24168, 24169, -1, 16706, 24170, 16775, -1, 24171, 24172, 24173, -1, 24174, 24175, 24176, -1, 24174, 24177, 24175, -1, 24174, 24173, 24178, -1, 24174, 24178, 24177, -1, 24179, 24169, 24167, -1, 24179, 24167, 24180, -1, 24179, 16776, 24169, -1, 24181, 24182, 24171, -1, 24181, 24180, 24182, -1, 24183, 24176, 24184, -1, 24183, 24174, 24176, -1, 24183, 24171, 24173, -1, 24183, 24173, 24174, -1, 24185, 16777, 16776, -1, 24185, 16776, 24179, -1, 24185, 24179, 24180, -1, 24185, 24180, 24181, -1, 24186, 24184, 24187, -1, 24186, 24183, 24184, -1, 24186, 24181, 24171, -1, 24186, 24171, 24183, -1, 24188, 24187, 24189, -1, 24188, 16778, 16777, -1, 24188, 16777, 24185, -1, 24188, 24181, 24186, -1, 24188, 24186, 24187, -1, 24190, 23812, 18514, -1, 24188, 24189, 16778, -1, 24188, 24185, 24181, -1, 16776, 16775, 24169, -1, 16779, 16778, 24189, -1, 24191, 24159, 18512, -1, 24191, 18512, 23810, -1, 24192, 24161, 24159, -1, 24192, 24159, 24191, -1, 24193, 23810, 23811, -1, 24193, 24191, 23810, -1, 24172, 24163, 24161, -1, 24172, 24161, 24192, -1, 24178, 24191, 24193, -1, 24178, 24192, 24191, -1, 24194, 23811, 23812, -1, 24194, 23812, 24190, -1, 24194, 24193, 23811, -1, 24182, 24165, 24163, -1, 24182, 24163, 24172, -1, 24173, 24172, 24192, -1, 24173, 24192, 24178, -1, 24177, 24190, 24175, -1, 24177, 24178, 24193, -1, 24177, 24194, 24190, -1, 24177, 24193, 24194, -1, 24180, 24167, 24165, -1, 24180, 24165, 24182, -1, 24171, 24182, 24172, -1, 18514, 18515, 24195, -1, 24190, 18514, 24195, -1, 24175, 24195, 24196, -1, 24175, 24190, 24195, -1, 24176, 24196, 24197, -1, 24176, 24175, 24196, -1, 24184, 24197, 24198, -1, 24184, 24176, 24197, -1, 24187, 24198, 24199, -1, 24187, 24184, 24198, -1, 24189, 24199, 24200, -1, 24189, 24187, 24199, -1, 16779, 24200, 16723, -1, 16779, 24189, 24200, -1, 24201, 24202, 24203, -1, 24201, 24203, 24204, -1, 16722, 16723, 24200, -1, 24205, 24195, 18515, -1, 24205, 23808, 23809, -1, 24205, 18515, 23808, -1, 24206, 24196, 24195, -1, 24206, 24195, 24205, -1, 24207, 23809, 18508, -1, 24207, 24208, 24209, -1, 24207, 18508, 24208, -1, 24207, 24205, 23809, -1, 24210, 24197, 24196, -1, 24210, 24196, 24206, -1, 24211, 24206, 24205, -1, 24211, 24205, 24207, -1, 24211, 24207, 24209, -1, 24212, 24198, 24197, -1, 24212, 24197, 24210, -1, 24213, 24214, 24215, -1, 24213, 24209, 24214, -1, 24213, 24211, 24209, -1, 24213, 24210, 24206, -1, 24213, 24206, 24211, -1, 24203, 24199, 24198, -1, 24203, 24198, 24212, -1, 24216, 24215, 24217, -1, 24216, 24213, 24215, -1, 24216, 24212, 24210, -1, 24216, 24210, 24213, -1, 24202, 24200, 24199, -1, 24202, 16724, 16722, -1, 24202, 24199, 24203, -1, 24202, 16722, 24200, -1, 24204, 24217, 24218, -1, 24204, 24216, 24217, -1, 24204, 24212, 24216, -1, 24204, 24203, 24212, -1, 24201, 24218, 16725, -1, 24201, 16725, 16724, -1, 24201, 16724, 24202, -1, 24201, 24204, 24218, -1, 18508, 18510, 24219, -1, 24208, 24219, 24220, -1, 24208, 18508, 24219, -1, 24209, 24220, 24221, -1, 24209, 24208, 24220, -1, 24214, 24221, 24222, -1, 24214, 24209, 24221, -1, 24215, 24222, 24223, -1, 24215, 24214, 24222, -1, 24217, 24223, 24224, -1, 24217, 24215, 24223, -1, 24218, 24224, 16754, -1, 24218, 24217, 24224, -1, 16725, 24218, 16754, -1, 24225, 24226, 24227, -1, 24225, 24227, 24228, -1, 24229, 24223, 24222, -1, 24229, 24222, 24230, -1, 24231, 23805, 23804, -1, 23807, 24219, 18510, -1, 24231, 24228, 23805, -1, 24231, 23804, 24232, -1, 24233, 24230, 24234, -1, 24233, 24234, 24235, -1, 24236, 24226, 24225, -1, 24236, 24235, 24226, -1, 24237, 24224, 24223, -1, 24237, 16756, 24224, -1, 24237, 24223, 24229, -1, 24238, 24232, 24239, -1, 24238, 24231, 24232, -1, 24238, 24225, 24228, -1, 24238, 24228, 24231, -1, 24240, 24229, 24230, -1, 24240, 24230, 24233, -1, 24241, 24233, 24235, -1, 24241, 24235, 24236, -1, 24232, 23804, 18535, -1, 24242, 24239, 24243, -1, 24242, 24238, 24239, -1, 16756, 16754, 24224, -1, 24242, 24236, 24225, -1, 24242, 24225, 24238, -1, 24244, 16766, 16756, -1, 24244, 16756, 24237, -1, 24244, 24237, 24229, -1, 24244, 24229, 24240, -1, 24245, 24240, 24233, -1, 24245, 24233, 24241, -1, 24246, 24243, 24247, -1, 24246, 24242, 24243, -1, 24246, 24241, 24236, -1, 24246, 24236, 24242, -1, 24248, 24244, 24240, -1, 24248, 16764, 16766, -1, 24248, 16766, 24244, -1, 24248, 24240, 24245, -1, 24249, 24245, 24241, -1, 24249, 24247, 24250, -1, 24249, 24241, 24246, -1, 24249, 24246, 24247, -1, 24251, 24248, 24245, -1, 24251, 24252, 16761, -1, 24251, 24250, 24252, -1, 24251, 16762, 16764, -1, 24251, 16761, 16762, -1, 24251, 24249, 24250, -1, 24251, 24245, 24249, -1, 24251, 16764, 24248, -1, 24253, 24220, 24219, -1, 24253, 24219, 23807, -1, 24254, 24220, 24253, -1, 24227, 23807, 23806, -1, 24227, 24253, 23807, -1, 24234, 24221, 24220, -1, 24234, 24220, 24254, -1, 24226, 24253, 24227, -1, 24226, 24254, 24253, -1, 24228, 23806, 23805, -1, 24228, 24227, 23806, -1, 24230, 24222, 24221, -1, 24230, 24221, 24234, -1, 24235, 24234, 24254, -1, 24235, 24254, 24226, -1, 24232, 18535, 18534, -1, 24232, 24255, 24256, -1, 24232, 18534, 24255, -1, 24239, 24256, 24257, -1, 24239, 24232, 24256, -1, 24243, 24257, 24258, -1, 24243, 24239, 24257, -1, 24247, 24243, 24258, -1, 24250, 24258, 24259, -1, 24250, 24247, 24258, -1, 24252, 24259, 24260, -1, 24252, 24250, 24259, -1, 16761, 24260, 16759, -1, 16761, 24252, 24260, -1, 24261, 24256, 24255, -1, 24261, 23798, 23799, -1, 24261, 23799, 24262, -1, 24261, 24263, 24256, -1, 24261, 24255, 23798, -1, 24261, 24262, 24264, -1, 24261, 24264, 24263, -1, 24260, 16760, 16759, -1, 18534, 23798, 24255, -1, 24265, 24266, 16755, -1, 24265, 16755, 16758, -1, 24267, 24268, 24266, -1, 24267, 24266, 24265, -1, 24269, 16758, 16760, -1, 24269, 24265, 16758, -1, 24269, 16760, 24260, -1, 24270, 24271, 24268, -1, 24270, 24268, 24267, -1, 24272, 24260, 24259, -1, 24272, 24267, 24265, -1, 24272, 24269, 24260, -1, 24272, 24265, 24269, -1, 24273, 24274, 24271, -1, 24273, 24271, 24270, -1, 24275, 24259, 24258, -1, 24275, 24267, 24272, -1, 24275, 24270, 24267, -1, 24275, 24272, 24259, -1, 24264, 24276, 24274, -1, 24264, 24274, 24273, -1, 24277, 24258, 24257, -1, 24277, 24275, 24258, -1, 24277, 24270, 24275, -1, 24277, 24273, 24270, -1, 24262, 23799, 23800, -1, 24262, 24278, 24276, -1, 24262, 23800, 24278, -1, 24262, 24276, 24264, -1, 24263, 24257, 24256, -1, 24263, 24264, 24273, -1, 24263, 24277, 24257, -1, 24263, 24273, 24277, -1, 23801, 24278, 23800, -1, 24276, 24278, 23801, -1, 23593, 16755, 24266, -1, 23593, 24266, 24268, -1, 24279, 23801, 23802, -1, 24280, 23801, 24279, -1, 24280, 24276, 23801, -1, 24281, 23802, 23803, -1, 24281, 23803, 24282, -1, 24281, 24279, 23802, -1, 24283, 24271, 24274, -1, 24283, 24274, 24276, -1, 24283, 24276, 24280, -1, 24284, 24282, 24285, -1, 24284, 24280, 24279, -1, 24284, 24281, 24282, -1, 24284, 24279, 24281, -1, 24286, 24285, 24287, -1, 24286, 24283, 24280, -1, 24286, 24284, 24285, -1, 24286, 24280, 24284, -1, 24288, 24268, 24271, -1, 24288, 24271, 24283, -1, 24289, 24286, 24287, -1, 24289, 24288, 24283, -1, 24289, 24283, 24286, -1, 24290, 23595, 23593, -1, 24290, 23593, 24268, -1, 24290, 24268, 24288, -1, 24291, 24287, 24292, -1, 24291, 24289, 24287, -1, 24291, 24288, 24289, -1, 24291, 23595, 24290, -1, 24291, 24290, 24288, -1, 24293, 24292, 18074, -1, 24293, 23597, 23595, -1, 24293, 18074, 23597, -1, 24293, 23595, 24291, -1, 24293, 24291, 24292, -1, 24292, 24294, 18073, -1, 24292, 18073, 18074, -1, 24287, 24295, 24294, -1, 24287, 24294, 24292, -1, 24285, 24296, 24295, -1, 24285, 24295, 24287, -1, 24282, 18554, 24296, -1, 24282, 24296, 24285, -1, 23803, 18554, 24282, -1, 18024, 18073, 24294, -1, 18024, 18023, 18073, -1, 18026, 24294, 24295, -1, 18026, 18024, 24294, -1, 18028, 24295, 24296, -1, 18028, 18026, 24295, -1, 18525, 24296, 18554, -1, 18525, 18028, 24296, -1, 24297, 17123, 24298, -1, 24299, 17123, 24297, -1, 17125, 24300, 24301, -1, 17125, 17123, 24299, -1, 17125, 24299, 24300, -1, 15237, 24302, 15212, -1, 15216, 24302, 15218, -1, 15212, 24302, 15216, -1, 15218, 24303, 15220, -1, 24302, 24303, 15218, -1, 15220, 24304, 15222, -1, 24303, 24304, 15220, -1, 15222, 24305, 15199, -1, 24304, 24305, 15222, -1, 15199, 24306, 15198, -1, 24305, 24306, 15199, -1, 15198, 24307, 15202, -1, 24306, 24307, 15198, -1, 15202, 24308, 15208, -1, 24307, 24308, 15202, -1, 15208, 24309, 15211, -1, 24308, 24309, 15208, -1, 15211, 24310, 15215, -1, 24309, 24310, 15211, -1, 15215, 24311, 15213, -1, 24310, 24311, 15215, -1, 15213, 24312, 15209, -1, 24311, 24312, 15213, -1, 15209, 24313, 15201, -1, 24312, 24313, 15209, -1, 24313, 15224, 15201, -1, 24314, 24315, 24316, -1, 24317, 24318, 24319, -1, 24314, 24320, 24315, -1, 24321, 24322, 24323, -1, 24324, 24316, 24325, -1, 24321, 24323, 24326, -1, 15224, 24313, 24327, -1, 24328, 24329, 24330, -1, 24331, 24328, 24332, -1, 24324, 24325, 24333, -1, 24331, 24329, 24328, -1, 24334, 24326, 24335, -1, 24334, 24335, 24336, -1, 24337, 24333, 24338, -1, 24337, 24338, 24339, -1, 24340, 24341, 24342, -1, 24343, 24344, 24329, -1, 24340, 24309, 24308, -1, 24345, 24346, 24347, -1, 24343, 24329, 24331, -1, 24340, 24348, 24341, -1, 24340, 24308, 24348, -1, 24349, 24342, 24350, -1, 24345, 24339, 24346, -1, 24349, 24350, 24351, -1, 24352, 24332, 24353, -1, 24354, 24304, 24355, -1, 24354, 24305, 24304, -1, 24354, 24355, 24356, -1, 24352, 24331, 24332, -1, 24354, 24356, 24357, -1, 24358, 24344, 24343, -1, 24359, 24318, 24317, -1, 24360, 24357, 24320, -1, 24360, 24320, 24314, -1, 24358, 24361, 24344, -1, 24359, 24351, 24318, -1, 24362, 24317, 24322, -1, 24363, 24316, 24324, -1, 24364, 24343, 24331, -1, 24363, 24314, 24316, -1, 24362, 24322, 24321, -1, 24364, 24331, 24352, -1, 24365, 24352, 24353, -1, 24365, 24353, 24366, -1, 24367, 24324, 24333, -1, 24367, 24333, 24337, -1, 24368, 24321, 24326, -1, 24368, 24326, 24334, -1, 24369, 24334, 24336, -1, 24369, 24336, 24370, -1, 24371, 24372, 24361, -1, 24369, 24370, 24373, -1, 24374, 24337, 24339, -1, 24371, 24361, 24358, -1, 24374, 24339, 24345, -1, 24375, 24340, 24342, -1, 24302, 15237, 24376, -1, 24375, 24310, 24309, -1, 24375, 24309, 24340, -1, 24377, 24347, 24378, -1, 24379, 24343, 24364, -1, 24375, 24342, 24349, -1, 24377, 24345, 24347, -1, 24380, 24357, 24360, -1, 24379, 24358, 24343, -1, 24380, 24306, 24305, -1, 24381, 24351, 24359, -1, 24380, 24354, 24357, -1, 24381, 24349, 24351, -1, 24380, 24305, 24354, -1, 24382, 24359, 24317, -1, 24383, 24364, 24352, -1, 24382, 24317, 24362, -1, 24383, 24352, 24365, -1, 24384, 24360, 24314, -1, 24384, 24314, 24363, -1, 24385, 24366, 24386, -1, 24385, 24365, 24366, -1, 24387, 24363, 24324, -1, 24387, 24324, 24367, -1, 24388, 24362, 24321, -1, 24388, 24321, 24368, -1, 24389, 24373, 24390, -1, 24391, 24392, 24372, -1, 24389, 24334, 24369, -1, 24391, 24372, 24371, -1, 24393, 24367, 24337, -1, 24389, 24368, 24334, -1, 24393, 24337, 24374, -1, 24389, 24369, 24373, -1, 24394, 24311, 24310, -1, 24394, 24310, 24375, -1, 24395, 24358, 24379, -1, 24395, 24371, 24358, -1, 24394, 24375, 24349, -1, 24394, 24349, 24381, -1, 24315, 24364, 24383, -1, 24396, 24359, 24382, -1, 24319, 24374, 24345, -1, 24396, 24381, 24359, -1, 24319, 24345, 24377, -1, 24315, 24379, 24364, -1, 24323, 24378, 24397, -1, 24323, 24377, 24378, -1, 24325, 24365, 24385, -1, 24398, 24307, 24306, -1, 24398, 24380, 24360, -1, 24325, 24383, 24365, -1, 24399, 24382, 24362, -1, 24398, 24306, 24380, -1, 24399, 24362, 24388, -1, 24398, 24360, 24384, -1, 24400, 24390, 24401, -1, 24338, 24386, 24402, -1, 24400, 24389, 24390, -1, 24400, 24388, 24368, -1, 24338, 24385, 24386, -1, 24400, 24368, 24389, -1, 24341, 24363, 24387, -1, 24341, 24384, 24363, -1, 24403, 24392, 24391, -1, 24404, 24312, 24311, -1, 24403, 24303, 24302, -1, 24403, 24376, 24392, -1, 24404, 24311, 24394, -1, 24403, 24302, 24376, -1, 24404, 24394, 24381, -1, 24404, 24381, 24396, -1, 24350, 24367, 24393, -1, 24356, 24371, 24395, -1, 24350, 24387, 24367, -1, 24405, 24396, 24382, -1, 24356, 24391, 24371, -1, 24405, 24382, 24399, -1, 24406, 24401, 24407, -1, 24318, 24393, 24374, -1, 24318, 24374, 24319, -1, 24320, 24379, 24315, -1, 24406, 24400, 24401, -1, 24320, 24395, 24379, -1, 24406, 24399, 24388, -1, 24406, 24388, 24400, -1, 24322, 24319, 24377, -1, 24316, 24383, 24325, -1, 24408, 24312, 24404, -1, 24408, 24313, 24312, -1, 24316, 24315, 24383, -1, 24408, 24404, 24396, -1, 24408, 24396, 24405, -1, 24409, 24406, 24407, -1, 24322, 24377, 24323, -1, 24409, 24407, 24410, -1, 24326, 24397, 24335, -1, 24409, 24405, 24399, -1, 24333, 24325, 24385, -1, 24409, 24399, 24406, -1, 24326, 24323, 24397, -1, 24411, 24408, 24405, -1, 24411, 24410, 24327, -1, 24333, 24385, 24338, -1, 24411, 24327, 24313, -1, 24348, 24308, 24307, -1, 24411, 24313, 24408, -1, 24348, 24307, 24398, -1, 24339, 24402, 24346, -1, 24411, 24409, 24410, -1, 24348, 24398, 24384, -1, 24411, 24405, 24409, -1, 24348, 24384, 24341, -1, 24342, 24387, 24350, -1, 24339, 24338, 24402, -1, 24342, 24341, 24387, -1, 24355, 24391, 24356, -1, 24355, 24304, 24303, -1, 24355, 24303, 24403, -1, 24351, 24393, 24318, -1, 24355, 24403, 24391, -1, 24357, 24395, 24320, -1, 24351, 24350, 24393, -1, 24317, 24319, 24322, -1, 24357, 24356, 24395, -1, 15181, 17573, 15150, -1, 15150, 17573, 15143, -1, 15143, 17614, 15142, -1, 17573, 17614, 15143, -1, 15142, 17613, 15166, -1, 17614, 17613, 15142, -1, 15166, 17637, 15164, -1, 17613, 17637, 15166, -1, 15164, 17651, 15162, -1, 17637, 17651, 15164, -1, 15162, 17612, 15159, -1, 17651, 17612, 15162, -1, 15159, 17611, 15153, -1, 17612, 17611, 15159, -1, 15153, 17638, 15151, -1, 17611, 17638, 15153, -1, 15151, 17648, 15146, -1, 17638, 17648, 15151, -1, 15146, 17655, 15144, -1, 17648, 17655, 15146, -1, 15144, 17578, 15148, -1, 17655, 17578, 15144, -1, 15148, 17575, 15152, -1, 17578, 17575, 15148, -1, 15152, 15168, 15155, -1, 17575, 15168, 15152, -1, 15141, 8283, 11734, -1, 15141, 15258, 8283, -1, 15258, 8280, 8283, -1, 8280, 15861, 11733, -1, 8280, 15640, 15861, -1, 15258, 15640, 8280, -1, 16203, 16205, 24300, -1, 16203, 24300, 24299, -1, 15302, 15296, 15308, -1, 15297, 24412, 24413, -1, 15297, 15303, 24412, -1, 15303, 24414, 24412, -1, 24415, 24416, 24414, -1, 24412, 24416, 24417, -1, 24414, 24416, 24412, -1, 24418, 24415, 24419, -1, 24416, 24415, 24418, -1, 24420, 24421, 24418, -1, 24420, 24418, 24419, -1, 24422, 24420, 24419, -1, 24420, 24423, 24424, -1, 24425, 24424, 24426, -1, 24421, 24424, 24425, -1, 24421, 24420, 24424, -1, 24420, 24422, 24423, -1, 15260, 15264, 15305, -1, 15264, 24427, 15305, -1, 24428, 24429, 24430, -1, 24431, 24432, 24429, -1, 24429, 24432, 24430, -1, 24430, 24433, 24427, -1, 24427, 24433, 15305, -1, 24432, 24433, 24430, -1, 24432, 24434, 24433, -1, 24429, 24435, 24436, -1, 24429, 24428, 24435, -1, 24437, 15265, 24438, -1, 24439, 15265, 24437, -1, 24440, 24436, 24435, -1, 24440, 24435, 24441, -1, 24442, 24436, 24440, -1, 24443, 24436, 24442, -1, 24444, 24443, 24442, -1, 24445, 24442, 24446, -1, 24445, 24444, 24442, -1, 24447, 24437, 24448, -1, 24449, 24445, 24446, -1, 24450, 24448, 24451, -1, 24450, 24447, 24448, -1, 24450, 24449, 24447, -1, 24446, 24447, 24449, -1, 15265, 15263, 24438, -1, 24438, 24448, 24437, -1, 24452, 24453, 24454, -1, 24452, 24455, 24456, -1, 24452, 24457, 24455, -1, 24452, 24458, 24457, -1, 24452, 24454, 24458, -1, 24459, 24460, 24461, -1, 24459, 24462, 24460, -1, 16063, 24459, 24463, -1, 16063, 24463, 24464, -1, 16063, 24462, 24459, -1, 24465, 24466, 24453, -1, 24465, 24453, 24452, -1, 16062, 24452, 16063, -1, 16063, 24452, 24462, -1, 24462, 24452, 24456, -1, 24467, 24468, 24469, -1, 24467, 24470, 24468, -1, 24471, 24469, 24472, -1, 24471, 24467, 24469, -1, 24473, 24472, 24474, -1, 24473, 24471, 24472, -1, 24475, 24474, 24476, -1, 24475, 24473, 24474, -1, 24458, 24475, 24476, -1, 24454, 24475, 24458, -1, 24457, 24476, 24477, -1, 24457, 24458, 24476, -1, 24455, 24477, 24478, -1, 24455, 24457, 24477, -1, 24456, 24478, 24479, -1, 24456, 24455, 24478, -1, 24462, 24479, 24480, -1, 24462, 24456, 24479, -1, 24460, 24480, 24481, -1, 24460, 24462, 24480, -1, 24482, 24481, 24483, -1, 24482, 24461, 24460, -1, 24482, 24460, 24481, -1, 24484, 24483, 24485, -1, 24484, 24482, 24483, -1, 24486, 24485, 24487, -1, 24486, 24484, 24485, -1, 24488, 24487, 24489, -1, 24488, 24486, 24487, -1, 24490, 24488, 24489, -1, 24491, 24492, 24493, -1, 24494, 24495, 24496, -1, 24494, 24496, 24497, -1, 24498, 24491, 24493, -1, 24499, 24500, 24495, -1, 24499, 24495, 24494, -1, 24501, 24498, 24493, -1, 24502, 24500, 24499, -1, 24503, 24500, 24502, -1, 24504, 24500, 24503, -1, 24505, 24500, 24504, -1, 24506, 24500, 24505, -1, 24507, 24500, 24506, -1, 24453, 24507, 24508, -1, 24453, 24500, 24507, -1, 24509, 24453, 24508, -1, 24459, 24488, 24490, -1, 24459, 24486, 24488, -1, 24459, 24484, 24486, -1, 24459, 24482, 24484, -1, 24459, 24461, 24482, -1, 24459, 24490, 24501, -1, 24459, 24501, 24493, -1, 24454, 24453, 24475, -1, 24475, 24453, 24473, -1, 24510, 24500, 24453, -1, 24473, 24453, 24471, -1, 24511, 24510, 24453, -1, 24512, 24513, 24514, -1, 24515, 24516, 24517, -1, 24515, 24517, 24514, -1, 24515, 24514, 24513, -1, 24518, 24512, 24514, -1, 24519, 24509, 24516, -1, 24519, 24516, 24515, -1, 24520, 24514, 24493, -1, 24520, 24518, 24514, -1, 24470, 24453, 24509, -1, 24470, 24509, 24519, -1, 24521, 24520, 24493, -1, 24467, 24453, 24470, -1, 24522, 24521, 24493, -1, 24471, 24453, 24467, -1, 24492, 24522, 24493, -1, 24504, 24503, 24523, -1, 24523, 24503, 24524, -1, 24524, 24502, 24525, -1, 24503, 24502, 24524, -1, 24525, 24499, 24526, -1, 24502, 24499, 24525, -1, 24500, 24527, 24495, -1, 24528, 24527, 24500, -1, 24529, 24530, 24531, -1, 24529, 24532, 24530, -1, 24527, 24533, 24534, -1, 24528, 24533, 24527, -1, 24528, 24535, 24533, -1, 24528, 24536, 24535, -1, 24536, 24466, 24535, -1, 24535, 24465, 24537, -1, 24466, 24465, 24535, -1, 24465, 24538, 24537, -1, 24530, 24538, 24539, -1, 24539, 24540, 24541, -1, 24538, 24540, 24539, -1, 24465, 24540, 24538, -1, 24539, 24531, 24530, -1, 24542, 24529, 24531, -1, 24452, 24543, 24540, -1, 24465, 24452, 24540, -1, 24544, 24545, 24546, -1, 24542, 24544, 24547, -1, 24542, 24545, 24544, -1, 24529, 24547, 24548, -1, 24529, 24542, 24547, -1, 24543, 24549, 24550, -1, 24541, 24551, 24552, -1, 24541, 24552, 24553, -1, 24541, 24553, 24554, -1, 24541, 24554, 24555, -1, 24541, 24555, 24556, -1, 24541, 24556, 24557, -1, 24541, 24540, 24551, -1, 24558, 24559, 24543, -1, 24560, 24543, 24559, -1, 24561, 24557, 24562, -1, 24561, 24562, 24563, -1, 24561, 24451, 24541, -1, 24561, 24541, 24557, -1, 24561, 24563, 24564, -1, 24565, 24558, 24543, -1, 24561, 24566, 24450, -1, 24561, 24450, 24451, -1, 24567, 24543, 24560, -1, 24568, 24565, 24543, -1, 24569, 24543, 24567, -1, 24570, 24540, 24543, -1, 24570, 24543, 24569, -1, 24571, 24540, 24570, -1, 24564, 24572, 24573, -1, 24564, 24573, 24568, -1, 24564, 24543, 24550, -1, 24564, 24568, 24543, -1, 24450, 24566, 24574, -1, 24575, 24572, 24564, -1, 24576, 24540, 24571, -1, 24577, 24575, 24564, -1, 24551, 24540, 24576, -1, 24578, 24577, 24564, -1, 24579, 24578, 24564, -1, 24580, 24579, 24564, -1, 24563, 24580, 24564, -1, 24581, 24569, 24582, -1, 24569, 24567, 24582, -1, 24582, 24560, 24583, -1, 24567, 24560, 24582, -1, 24583, 24559, 24584, -1, 24560, 24559, 24583, -1, 24584, 24558, 24585, -1, 24559, 24558, 24584, -1, 24585, 24565, 24586, -1, 24558, 24565, 24585, -1, 24586, 24568, 24587, -1, 24565, 24568, 24586, -1, 24587, 24573, 24588, -1, 24568, 24573, 24587, -1, 24588, 24572, 24589, -1, 24573, 24572, 24588, -1, 24589, 24575, 24590, -1, 24572, 24575, 24589, -1, 24590, 24577, 24591, -1, 24575, 24577, 24590, -1, 24591, 24578, 24592, -1, 24577, 24578, 24591, -1, 24592, 24579, 24593, -1, 24578, 24579, 24592, -1, 24593, 24580, 24594, -1, 24579, 24580, 24593, -1, 24595, 24564, 24596, -1, 24595, 24561, 24564, -1, 16373, 16371, 24597, -1, 24597, 16371, 24598, -1, 16365, 16364, 16371, -1, 16371, 16364, 24598, -1, 24599, 24597, 24598, -1, 24599, 24600, 24597, -1, 24599, 24601, 24602, -1, 24603, 24601, 24599, -1, 24604, 24599, 24602, -1, 24600, 24599, 24604, -1, 24602, 24605, 24604, -1, 24606, 24605, 24602, -1, 24605, 24607, 24608, -1, 24605, 24606, 24607, -1, 24603, 24599, 24598, -1, 24609, 24603, 24598, -1, 16364, 16366, 24609, -1, 24598, 16364, 24609, -1, 2825, 2828, 16309, -1, 2825, 16309, 16310, -1, 16353, 16360, 16302, -1, 2897, 16298, 16296, -1, 2897, 2898, 16298, -1, 2670, 16296, 16294, -1, 2670, 2897, 16296, -1, 2685, 16294, 16293, -1, 2685, 2670, 16294, -1, 16359, 16292, 16295, -1, 2684, 16293, 16292, -1, 2684, 2685, 16293, -1, 16297, 16359, 16295, -1, 16357, 16359, 16297, -1, 2681, 2684, 16292, -1, 2681, 16292, 16359, -1, 16301, 16357, 16297, -1, 16370, 2681, 16359, -1, 16360, 16357, 16301, -1, 16302, 16360, 16301, -1, 2680, 16370, 24610, -1, 2680, 2681, 16370, -1, 16303, 16353, 16302, -1, 2679, 24610, 24611, -1, 2679, 2680, 24610, -1, 16356, 2679, 24611, -1, 2677, 16356, 16353, -1, 2677, 16353, 16303, -1, 2677, 2679, 16356, -1, 2676, 16303, 16304, -1, 2676, 16304, 16305, -1, 2676, 2677, 16303, -1, 2852, 2676, 16305, -1, 2852, 16305, 16306, -1, 2832, 2852, 16306, -1, 2832, 16306, 16307, -1, 2832, 16307, 16308, -1, 2828, 2832, 16308, -1, 2828, 16308, 16309, -1, 24612, 24613, 24614, -1, 24614, 24615, 24426, -1, 24613, 24615, 24614, -1, 24615, 24616, 24426, -1, 24616, 24617, 24426, -1, 24618, 24619, 24620, -1, 24620, 24619, 24621, -1, 24621, 24619, 24622, -1, 24622, 24619, 24623, -1, 24623, 24619, 24624, -1, 24624, 24619, 24617, -1, 24625, 24619, 24626, -1, 24626, 24619, 24627, -1, 24627, 24619, 24618, -1, 24617, 24619, 24426, -1, 24619, 24425, 24426, -1, 24619, 24628, 24425, -1, 24629, 24630, 24631, -1, 24629, 24631, 24632, -1, 24633, 24632, 24634, -1, 24633, 24629, 24632, -1, 24635, 24634, 24636, -1, 24635, 24633, 24634, -1, 24637, 24636, 24638, -1, 24637, 24635, 24636, -1, 24639, 24638, 24640, -1, 24639, 24637, 24638, -1, 24641, 24639, 24640, -1, 24612, 24642, 24643, -1, 24612, 24640, 24642, -1, 24612, 24641, 24640, -1, 24613, 24643, 24644, -1, 24613, 24644, 24645, -1, 24613, 24612, 24643, -1, 24615, 24645, 24646, -1, 24615, 24613, 24645, -1, 24616, 24646, 24647, -1, 24616, 24615, 24646, -1, 24617, 24647, 24648, -1, 24617, 24616, 24647, -1, 24624, 24648, 24649, -1, 24624, 24617, 24648, -1, 24623, 24649, 24650, -1, 24623, 24624, 24649, -1, 24622, 24650, 24651, -1, 24622, 24623, 24650, -1, 24621, 24651, 24652, -1, 24621, 24622, 24651, -1, 24620, 24621, 24652, -1, 24620, 24652, 24653, -1, 24618, 24620, 24653, -1, 24618, 24654, 24655, -1, 24618, 24656, 24654, -1, 24618, 24653, 24656, -1, 24657, 24658, 24659, -1, 24657, 24659, 24660, -1, 24661, 24660, 24662, -1, 24661, 24663, 24657, -1, 24661, 24657, 24660, -1, 24664, 24662, 24655, -1, 24664, 24655, 24654, -1, 24664, 24654, 24656, -1, 24664, 24656, 24653, -1, 24664, 24653, 24663, -1, 24664, 24661, 24662, -1, 24664, 24663, 24661, -1, 24665, 24666, 24667, -1, 24668, 24666, 24665, -1, 24669, 24665, 24670, -1, 24669, 24668, 24665, -1, 24671, 24670, 24672, -1, 24671, 24669, 24670, -1, 24673, 24671, 24672, -1, 24674, 24672, 24675, -1, 24674, 24675, 24676, -1, 24674, 24673, 24672, -1, 24677, 24678, 24679, -1, 24677, 24676, 24678, -1, 24677, 24674, 24676, -1, 24680, 24679, 24681, -1, 24680, 24677, 24679, -1, 24682, 24681, 24683, -1, 24682, 24680, 24681, -1, 24684, 24683, 24685, -1, 24684, 24682, 24683, -1, 24686, 24685, 24687, -1, 24686, 24684, 24685, -1, 24630, 24687, 24631, -1, 24630, 24686, 24687, -1, 24628, 24619, 24688, -1, 24689, 24628, 24688, -1, 24666, 24690, 24667, -1, 24691, 24690, 24688, -1, 24691, 24667, 24690, -1, 24692, 24668, 24669, -1, 24692, 24666, 24668, -1, 24692, 24690, 24666, -1, 24671, 24692, 24669, -1, 24619, 24693, 24691, -1, 24619, 24694, 24693, -1, 24619, 24695, 24694, -1, 24619, 24625, 24695, -1, 24619, 24691, 24688, -1, 24692, 24696, 24697, -1, 24692, 24697, 24690, -1, 24675, 24672, 24698, -1, 24698, 24672, 24699, -1, 24672, 24670, 24699, -1, 24699, 24665, 24700, -1, 24670, 24665, 24699, -1, 24701, 24702, 24703, -1, 24704, 24705, 24701, -1, 24701, 24705, 24702, -1, 24706, 24667, 24707, -1, 24700, 24667, 24706, -1, 24665, 24667, 24700, -1, 24707, 24691, 24704, -1, 24667, 24691, 24707, -1, 24704, 24691, 24705, -1, 24638, 24708, 24640, -1, 24636, 24708, 24638, -1, 24634, 24709, 24636, -1, 24636, 24709, 24708, -1, 24632, 24710, 24634, -1, 24634, 24710, 24709, -1, 24631, 24711, 24632, -1, 24687, 24711, 24631, -1, 24632, 24711, 24710, -1, 24685, 24712, 24687, -1, 24687, 24712, 24711, -1, 24683, 24713, 24685, -1, 24685, 24713, 24712, -1, 24681, 24714, 24683, -1, 24683, 24714, 24713, -1, 24681, 24679, 24714, -1, 24701, 24715, 24716, -1, 24704, 24716, 24717, -1, 24704, 24701, 24716, -1, 24707, 24717, 24718, -1, 24707, 24704, 24717, -1, 24706, 24718, 24719, -1, 24706, 24707, 24718, -1, 24700, 24719, 24720, -1, 24700, 24706, 24719, -1, 24699, 24700, 24720, -1, 24698, 24720, 24721, -1, 24698, 24699, 24720, -1, 24714, 24722, 24723, -1, 24713, 24714, 24723, -1, 24712, 24723, 24724, -1, 24712, 24713, 24723, -1, 24711, 24724, 24725, -1, 24711, 24712, 24724, -1, 24710, 24725, 24726, -1, 24710, 24711, 24725, -1, 24709, 24726, 24727, -1, 24709, 24710, 24726, -1, 24708, 24727, 24728, -1, 24708, 24709, 24727, -1, 24645, 24729, 24646, -1, 24644, 24729, 24645, -1, 24646, 24730, 24647, -1, 24729, 24730, 24646, -1, 24647, 24731, 24648, -1, 24730, 24731, 24647, -1, 24648, 24732, 24649, -1, 24731, 24732, 24648, -1, 24732, 24733, 24649, -1, 24733, 24650, 24649, -1, 24733, 24734, 24650, -1, 24735, 24651, 24734, -1, 24734, 24651, 24650, -1, 24735, 24652, 24651, -1, 24735, 24653, 24652, -1, 24730, 24729, 24736, -1, 24730, 24736, 24737, -1, 24731, 24737, 24738, -1, 24731, 24730, 24737, -1, 24732, 24738, 24739, -1, 24732, 24731, 24738, -1, 24733, 24739, 24740, -1, 24733, 24732, 24739, -1, 24734, 24740, 24741, -1, 24734, 24733, 24740, -1, 24735, 24741, 24742, -1, 24735, 24734, 24741, -1, 16538, 24545, 16534, -1, 24743, 24546, 24744, -1, 24744, 24546, 24745, -1, 24745, 24546, 16538, -1, 16538, 24546, 24545, -1, 24743, 24746, 24546, -1, 24743, 24747, 24746, -1, 24748, 24497, 24547, -1, 24748, 24547, 24544, -1, 24494, 24497, 24748, -1, 24749, 15305, 24433, -1, 24749, 15307, 15305, -1, 15295, 2759, 2758, -1, 15295, 15294, 2759, -1, 24750, 24635, 24637, -1, 24750, 24633, 24635, -1, 24750, 24629, 24633, -1, 24750, 24630, 24629, -1, 24750, 24686, 24630, -1, 24686, 24751, 24684, -1, 24684, 24751, 24682, -1, 24682, 24751, 24680, -1, 24680, 24751, 24677, -1, 24750, 24751, 24686, -1, 24677, 24692, 24674, -1, 24674, 24692, 24673, -1, 24751, 24692, 24677, -1, 24692, 24671, 24673, -1, 24751, 24696, 24692, -1, 24612, 24637, 24641, -1, 24641, 24637, 24639, -1, 24752, 24753, 17175, -1, 24754, 24752, 17175, -1, 17154, 24755, 24754, -1, 17154, 24754, 17175, -1, 17419, 24755, 17154, -1, 24755, 24756, 24754, -1, 24757, 24756, 24755, -1, 24758, 24756, 24757, -1, 24758, 24759, 24756, -1, 24760, 24758, 24757, -1, 24761, 24759, 24758, -1, 24762, 24761, 24758, -1, 24761, 24762, 24763, -1, 24762, 24764, 24763, -1, 18086, 24765, 18118, -1, 24766, 24765, 18086, -1, 24766, 24767, 24765, -1, 24765, 24768, 18118, -1, 24769, 24770, 15009, -1, 16731, 24771, 24769, -1, 16731, 24772, 24771, -1, 16731, 24769, 15009, -1, 15006, 16731, 15009, -1, 16718, 16731, 15006, -1, 24773, 24774, 15001, -1, 24773, 15001, 14996, -1, 24775, 24774, 24776, -1, 24776, 24774, 24777, -1, 24778, 24779, 24773, -1, 24779, 24780, 24773, -1, 24774, 24781, 24777, -1, 24781, 24782, 24783, -1, 24774, 24784, 24781, -1, 24781, 24784, 24782, -1, 24773, 24785, 24774, -1, 24774, 24785, 24784, -1, 24785, 24786, 24787, -1, 24780, 24788, 24773, -1, 24773, 24788, 24785, -1, 24785, 24788, 24786, -1, 24789, 24790, 24791, -1, 24792, 24793, 19819, -1, 24794, 24793, 24792, -1, 24790, 24793, 24794, -1, 24795, 24796, 24797, -1, 24797, 24796, 24793, -1, 24793, 24796, 19819, -1, 24796, 20264, 19819, -1, 24789, 24793, 24790, -1, 15238, 15255, 12949, -1, 12949, 24798, 13752, -1, 15255, 24798, 12949, -1, 24799, 24800, 24801, -1, 24802, 24800, 24799, -1, 24803, 24800, 24802, -1, 13752, 24803, 12360, -1, 13752, 24800, 24803, -1, 24804, 24798, 24805, -1, 24743, 24526, 24747, -1, 24805, 24526, 24743, -1, 24805, 24525, 24526, -1, 24798, 24525, 24805, -1, 24798, 24524, 24525, -1, 24798, 24523, 24524, -1, 24798, 24806, 24523, -1, 24807, 15254, 24808, -1, 15255, 15254, 24809, -1, 24798, 24810, 24806, -1, 24809, 15254, 24811, -1, 24808, 15254, 24812, -1, 24811, 15254, 24813, -1, 24813, 15254, 24814, -1, 24814, 15254, 24815, -1, 24798, 24816, 24810, -1, 24815, 15254, 24817, -1, 24817, 15254, 24818, -1, 24818, 15254, 24819, -1, 24819, 15254, 24807, -1, 24798, 24820, 24816, -1, 24820, 15255, 24821, -1, 24798, 15255, 24820, -1, 24822, 24823, 24824, -1, 24825, 24826, 24824, -1, 24824, 24826, 24822, -1, 24823, 24827, 24824, -1, 24825, 24828, 24826, -1, 24824, 24829, 24812, -1, 24827, 24829, 24824, -1, 24821, 24830, 24825, -1, 15255, 24830, 24821, -1, 24825, 24830, 24828, -1, 24829, 24831, 24812, -1, 15255, 24832, 24830, -1, 24831, 24833, 24812, -1, 15255, 24834, 24832, -1, 24833, 24835, 24812, -1, 15255, 24836, 24834, -1, 24835, 24837, 24812, -1, 15255, 24838, 24836, -1, 24837, 24839, 24812, -1, 15255, 24809, 24838, -1, 24839, 24808, 24812, -1, 24840, 24841, 24842, -1, 24843, 24844, 24845, -1, 24846, 24845, 24847, -1, 24848, 24842, 24849, -1, 24846, 24847, 24850, -1, 24851, 24852, 24853, -1, 24848, 24849, 24854, -1, 24855, 24854, 24856, -1, 24830, 24832, 24857, -1, 24858, 24850, 24859, -1, 24855, 24856, 24860, -1, 24858, 24859, 24861, -1, 24862, 24851, 24863, -1, 24862, 24852, 24851, -1, 24864, 24860, 24865, -1, 24864, 24865, 24866, -1, 24867, 24861, 24868, -1, 24867, 24868, 24869, -1, 24870, 24871, 24872, -1, 24873, 24874, 24852, -1, 24870, 24872, 24875, -1, 24870, 24809, 24811, -1, 24876, 24877, 24878, -1, 24873, 24852, 24862, -1, 24870, 24811, 24871, -1, 24876, 24869, 24877, -1, 24879, 24863, 24880, -1, 24881, 24815, 24817, -1, 24881, 24817, 24882, -1, 24883, 24884, 24840, -1, 24883, 24875, 24884, -1, 24879, 24862, 24863, -1, 24881, 24885, 24843, -1, 24881, 24882, 24885, -1, 24886, 24874, 24873, -1, 24887, 24840, 24842, -1, 24888, 24845, 24846, -1, 24886, 24889, 24874, -1, 24887, 24842, 24848, -1, 24888, 24843, 24845, -1, 24890, 24848, 24854, -1, 24890, 24854, 24855, -1, 24891, 24873, 24862, -1, 24892, 24846, 24850, -1, 24892, 24850, 24858, -1, 24891, 24862, 24879, -1, 24893, 24858, 24861, -1, 24894, 24880, 24895, -1, 24896, 24855, 24860, -1, 24893, 24861, 24867, -1, 24894, 24879, 24880, -1, 24896, 24860, 24864, -1, 24819, 24807, 24897, -1, 24898, 24866, 24899, -1, 24898, 24899, 24900, -1, 24901, 24902, 24889, -1, 24898, 24864, 24866, -1, 24903, 24869, 24876, -1, 24901, 24889, 24886, -1, 24904, 24870, 24875, -1, 24903, 24867, 24869, -1, 24904, 24875, 24883, -1, 24905, 24878, 24906, -1, 24907, 24873, 24891, -1, 24904, 24838, 24809, -1, 24904, 24809, 24870, -1, 24905, 24876, 24878, -1, 24907, 24886, 24873, -1, 24908, 24814, 24815, -1, 24908, 24815, 24881, -1, 24909, 24883, 24840, -1, 24908, 24881, 24843, -1, 24908, 24843, 24888, -1, 24909, 24840, 24887, -1, 24910, 24891, 24879, -1, 24910, 24879, 24894, -1, 24911, 24888, 24846, -1, 24912, 24887, 24848, -1, 24912, 24848, 24890, -1, 24911, 24846, 24892, -1, 24913, 24895, 24914, -1, 24915, 24890, 24855, -1, 24913, 24894, 24895, -1, 24916, 24892, 24858, -1, 24915, 24855, 24896, -1, 24916, 24858, 24893, -1, 24917, 24918, 24902, -1, 24919, 24898, 24900, -1, 24919, 24900, 24920, -1, 24917, 24902, 24901, -1, 24919, 24896, 24864, -1, 24841, 24893, 24867, -1, 24841, 24867, 24903, -1, 24919, 24864, 24898, -1, 24921, 24836, 24838, -1, 24921, 24904, 24883, -1, 24844, 24886, 24907, -1, 24921, 24838, 24904, -1, 24921, 24883, 24909, -1, 24844, 24901, 24886, -1, 24922, 24909, 24887, -1, 24922, 24887, 24912, -1, 24849, 24903, 24876, -1, 24847, 24891, 24910, -1, 24849, 24876, 24905, -1, 24856, 24906, 24923, -1, 24847, 24907, 24891, -1, 24859, 24910, 24894, -1, 24856, 24905, 24906, -1, 24859, 24894, 24913, -1, 24924, 24813, 24814, -1, 24925, 24912, 24890, -1, 24924, 24888, 24911, -1, 24925, 24890, 24915, -1, 24924, 24814, 24908, -1, 24926, 24920, 24927, -1, 24924, 24908, 24888, -1, 24868, 24914, 24928, -1, 24926, 24919, 24920, -1, 24868, 24913, 24914, -1, 24926, 24915, 24896, -1, 24926, 24896, 24919, -1, 24872, 24892, 24916, -1, 24872, 24911, 24892, -1, 24929, 24918, 24917, -1, 24930, 24834, 24836, -1, 24929, 24818, 24819, -1, 24930, 24836, 24921, -1, 24929, 24897, 24918, -1, 24930, 24921, 24909, -1, 24929, 24819, 24897, -1, 24930, 24909, 24922, -1, 24884, 24893, 24841, -1, 24884, 24916, 24893, -1, 24931, 24922, 24912, -1, 24885, 24901, 24844, -1, 24931, 24912, 24925, -1, 24885, 24917, 24901, -1, 24845, 24907, 24847, -1, 24932, 24927, 24933, -1, 24932, 24926, 24927, -1, 24842, 24841, 24903, -1, 24932, 24925, 24915, -1, 24842, 24903, 24849, -1, 24932, 24915, 24926, -1, 24845, 24844, 24907, -1, 24934, 24832, 24834, -1, 24854, 24849, 24905, -1, 24934, 24834, 24930, -1, 24934, 24930, 24922, -1, 24850, 24847, 24910, -1, 24934, 24922, 24931, -1, 24935, 24925, 24932, -1, 24935, 24931, 24925, -1, 24850, 24910, 24859, -1, 24935, 24933, 24936, -1, 24854, 24905, 24856, -1, 24935, 24932, 24933, -1, 24860, 24923, 24865, -1, 24937, 24936, 24857, -1, 24860, 24856, 24923, -1, 24937, 24857, 24832, -1, 24871, 24811, 24813, -1, 24861, 24859, 24913, -1, 24937, 24931, 24935, -1, 24871, 24813, 24924, -1, 24861, 24913, 24868, -1, 24937, 24935, 24936, -1, 24937, 24832, 24934, -1, 24869, 24928, 24877, -1, 24937, 24934, 24931, -1, 24871, 24924, 24911, -1, 24871, 24911, 24872, -1, 24875, 24916, 24884, -1, 24869, 24868, 24928, -1, 24882, 24917, 24885, -1, 24875, 24872, 24916, -1, 24882, 24817, 24818, -1, 24882, 24818, 24929, -1, 24840, 24884, 24841, -1, 24882, 24929, 24917, -1, 24843, 24885, 24844, -1, 24938, 24939, 24940, -1, 24940, 24939, 24941, -1, 24941, 24942, 18977, -1, 24939, 24942, 24941, -1, 24942, 18932, 18977, -1, 24942, 24943, 18932, -1, 24944, 24945, 24946, -1, 24942, 24945, 24944, -1, 24942, 24944, 24947, -1, 24942, 24947, 24943, -1, 24948, 24949, 24950, -1, 24949, 24791, 24950, -1, 24790, 24951, 24791, -1, 24791, 24951, 24950, -1, 24952, 24944, 24946, -1, 24952, 24946, 24953, -1, 24954, 24955, 24956, -1, 24957, 24950, 24951, -1, 24956, 24955, 24958, -1, 24958, 24955, 24959, -1, 24959, 24960, 24961, -1, 24955, 24960, 24959, -1, 24962, 24963, 24964, -1, 24964, 24965, 24966, -1, 24963, 24965, 24964, -1, 24966, 24957, 24967, -1, 24965, 24957, 24966, -1, 24961, 24968, 24969, -1, 24961, 24970, 24968, -1, 24969, 24952, 24961, -1, 24961, 24971, 24970, -1, 24961, 24972, 24971, -1, 24952, 24953, 24961, -1, 24953, 24973, 24974, -1, 24953, 24946, 24973, -1, 24967, 24975, 24960, -1, 24960, 24975, 24961, -1, 24957, 24975, 24967, -1, 24961, 24975, 24972, -1, 24957, 24976, 24975, -1, 24957, 24977, 24976, -1, 24957, 24978, 24977, -1, 24957, 24979, 24978, -1, 24957, 24980, 24979, -1, 24957, 24981, 24980, -1, 24957, 24951, 24981, -1, 24982, 24975, 24976, -1, 24982, 24983, 24975, -1, 24984, 24983, 24982, -1, 24985, 24984, 24982, -1, 24986, 24984, 24985, -1, 24987, 24986, 24985, -1, 24988, 24989, 24990, -1, 24988, 24990, 24991, -1, 24992, 24988, 24991, -1, 24993, 24988, 24992, -1, 24994, 24988, 24993, -1, 24995, 24988, 24996, -1, 24997, 24994, 24998, -1, 24997, 24988, 24994, -1, 24997, 24996, 24988, -1, 24804, 24998, 24999, -1, 24804, 24999, 25000, -1, 24804, 25000, 25001, -1, 24804, 25001, 25002, -1, 24804, 25002, 25003, -1, 24804, 24997, 24998, -1, 24798, 24800, 13752, -1, 24798, 25003, 24800, -1, 24798, 24804, 25003, -1, 25004, 25005, 25006, -1, 25004, 24995, 25005, -1, 25004, 24988, 24995, -1, 25007, 25004, 25006, -1, 25008, 25006, 25009, -1, 25008, 25007, 25006, -1, 25010, 24770, 24769, -1, 25010, 25011, 24770, -1, 25010, 25012, 25011, -1, 25013, 25010, 24769, -1, 25014, 25013, 24769, -1, 25015, 24769, 25016, -1, 25015, 25014, 24769, -1, 3262, 25017, 3266, -1, 25018, 25017, 3262, -1, 25019, 25020, 25021, -1, 25022, 25023, 25019, -1, 25024, 25025, 25026, -1, 25017, 25018, 25027, -1, 25027, 25018, 25028, -1, 25029, 25030, 25022, -1, 25031, 25026, 25025, -1, 25022, 25030, 25023, -1, 25023, 25030, 25032, -1, 25033, 25031, 25025, -1, 25034, 25025, 25024, -1, 25035, 25033, 25025, -1, 25036, 25025, 25034, -1, 25037, 25030, 25025, -1, 25037, 25025, 25036, -1, 25038, 25030, 25037, -1, 25039, 25030, 25038, -1, 25040, 25030, 25039, -1, 25041, 25035, 25025, -1, 25042, 25043, 25035, -1, 25042, 25044, 25043, -1, 25042, 25035, 25041, -1, 25045, 25041, 25025, -1, 25046, 25044, 25042, -1, 25047, 25044, 25046, -1, 25032, 25030, 25040, -1, 25017, 25044, 25047, -1, 25027, 25044, 25017, -1, 25018, 25020, 25028, -1, 25048, 25020, 25018, -1, 25021, 25020, 25048, -1, 25019, 25023, 25020, -1, 3079, 25013, 3077, -1, 25010, 3079, 15011, -1, 25010, 25013, 3079, -1, 25049, 3083, 3080, -1, 25049, 25050, 3083, -1, 25051, 25052, 25050, -1, 25051, 25053, 25052, -1, 25051, 25054, 25053, -1, 25049, 25051, 25050, -1, 25055, 25051, 25049, -1, 25056, 3091, 3089, -1, 25056, 25057, 3091, -1, 25057, 25058, 25059, -1, 25056, 25058, 25057, -1, 25060, 25061, 25062, -1, 25060, 25063, 25061, -1, 25060, 25056, 25063, -1, 25060, 25058, 25056, -1, 25064, 25065, 25066, -1, 25064, 25067, 25065, -1, 25064, 25060, 25067, -1, 25068, 25069, 25070, -1, 25071, 25072, 25068, -1, 25073, 25071, 25068, -1, 25074, 25068, 25070, -1, 25074, 25073, 25068, -1, 25075, 25070, 25076, -1, 25075, 25076, 25077, -1, 25075, 25077, 25078, -1, 25075, 25078, 25079, -1, 25075, 25079, 25080, -1, 25075, 25080, 25064, -1, 25075, 25064, 25066, -1, 25075, 25074, 25070, -1, 25081, 25075, 25066, -1, 25082, 25081, 25066, -1, 25083, 25081, 25082, -1, 25084, 25083, 25082, -1, 25064, 25058, 25060, -1, 25085, 16529, 3035, -1, 25086, 3035, 3093, -1, 25086, 25085, 3035, -1, 25087, 25085, 25088, -1, 25088, 25085, 25089, -1, 25085, 25090, 25089, -1, 25091, 25090, 25085, -1, 25090, 25092, 25089, -1, 25091, 25086, 25093, -1, 25085, 25086, 25091, -1, 25092, 25094, 25089, -1, 25095, 25096, 25086, -1, 25086, 25096, 25093, -1, 25094, 25097, 25089, -1, 25096, 25098, 25093, -1, 25096, 25099, 25098, -1, 25100, 25101, 25102, -1, 25102, 25101, 25103, -1, 25103, 25101, 25104, -1, 25104, 25101, 25105, -1, 25105, 25101, 25106, -1, 25106, 25101, 25097, -1, 25097, 25101, 25089, -1, 25107, 25108, 25109, -1, 25109, 25108, 25110, -1, 25110, 25108, 25111, -1, 25111, 25108, 25100, -1, 25100, 25108, 25101, -1, 25096, 25108, 25099, -1, 25099, 25108, 25112, -1, 25112, 25108, 25107, -1, 25113, 25091, 25114, -1, 25113, 25114, 25115, -1, 25113, 25090, 25091, -1, 25116, 25115, 25117, -1, 25116, 25113, 25115, -1, 25118, 25116, 25117, -1, 25119, 25120, 25121, -1, 25122, 25121, 25120, -1, 25123, 25121, 25124, -1, 25123, 25119, 25121, -1, 25125, 25123, 25124, -1, 25126, 25121, 25122, -1, 25127, 25128, 25129, -1, 25127, 25130, 25128, -1, 25127, 25131, 25130, -1, 25127, 25124, 25131, -1, 25127, 25125, 25124, -1, 25132, 25121, 25126, -1, 16531, 25133, 16533, -1, 16531, 25134, 25133, -1, 16531, 25135, 25134, -1, 16531, 25136, 25135, -1, 16531, 25129, 25136, -1, 16531, 25127, 25129, -1, 25137, 25127, 16531, -1, 25138, 25121, 25132, -1, 25139, 25121, 25138, -1, 25140, 25141, 25139, -1, 25142, 25139, 25138, -1, 25142, 25140, 25139, -1, 25143, 25140, 25142, -1, 25144, 25140, 25143, -1, 25145, 25140, 25144, -1, 25146, 25140, 25145, -1, 25147, 25140, 25146, -1, 25137, 25148, 25127, -1, 25149, 25137, 25150, -1, 25151, 25148, 25137, -1, 25151, 25137, 25149, -1, 16533, 25152, 16535, -1, 16535, 25152, 25153, -1, 25152, 25154, 25153, -1, 25152, 25155, 25154, -1, 25154, 25156, 25157, -1, 25155, 25158, 25154, -1, 25154, 25159, 25156, -1, 25158, 25160, 25154, -1, 25154, 25161, 25159, -1, 25160, 25161, 25154, -1, 25162, 25154, 25163, -1, 25162, 25153, 25154, -1, 25164, 25163, 25165, -1, 25164, 25162, 25163, -1, 25166, 25165, 25167, -1, 25166, 25164, 25165, -1, 25168, 25169, 25170, -1, 25168, 25171, 25172, -1, 25173, 25172, 25174, -1, 25173, 25168, 25172, -1, 25173, 25175, 25169, -1, 25173, 25169, 25168, -1, 25176, 25177, 25175, -1, 25176, 25173, 25174, -1, 25176, 25175, 25173, -1, 25178, 25174, 25157, -1, 25178, 25157, 25156, -1, 25178, 25156, 25159, -1, 25178, 25177, 25176, -1, 25178, 25159, 25177, -1, 25178, 25176, 25174, -1, 25155, 25179, 25180, -1, 25155, 25152, 25179, -1, 25172, 25171, 25181, -1, 25182, 25139, 25183, -1, 25182, 25184, 25139, -1, 25185, 25186, 25184, -1, 25185, 25180, 25186, -1, 25185, 25184, 25182, -1, 25187, 25158, 25155, -1, 25187, 25155, 25180, -1, 25187, 25180, 25185, -1, 25188, 25183, 25189, -1, 25188, 25182, 25183, -1, 25190, 25185, 25182, -1, 25190, 25182, 25188, -1, 25191, 25187, 25185, -1, 25191, 25158, 25187, -1, 25191, 25185, 25190, -1, 25192, 25189, 25193, -1, 25192, 25188, 25189, -1, 25194, 25188, 25192, -1, 25194, 25190, 25188, -1, 25195, 25161, 25160, -1, 25195, 25160, 25158, -1, 25195, 25158, 25191, -1, 25196, 25190, 25194, -1, 25196, 25191, 25190, -1, 25169, 25193, 25170, -1, 25169, 25192, 25193, -1, 25175, 25194, 25192, -1, 25175, 25192, 25169, -1, 25197, 25159, 25161, -1, 25197, 25161, 25195, -1, 25197, 25195, 25191, -1, 25197, 25191, 25196, -1, 25177, 25196, 25194, -1, 25177, 25159, 25197, -1, 25177, 25194, 25175, -1, 25177, 25197, 25196, -1, 25168, 25170, 25171, -1, 25198, 25199, 25200, -1, 25200, 25199, 25201, -1, 18019, 25202, 18017, -1, 25202, 25203, 18017, -1, 18017, 25204, 25199, -1, 25199, 25204, 25201, -1, 25203, 25204, 18017, -1, 25204, 25205, 25201, -1, 25205, 25206, 25207, -1, 25204, 25208, 25205, -1, 25205, 25208, 25206, -1, 25209, 25210, 25211, -1, 25211, 25210, 25212, -1, 25210, 25213, 25212, -1, 25213, 25214, 25212, -1, 25215, 17996, 25216, -1, 25216, 17996, 25214, -1, 25215, 17997, 17996, -1, 25214, 25217, 25212, -1, 17996, 25218, 25214, -1, 25214, 25218, 25217, -1, 25219, 25220, 25221, -1, 25219, 25222, 25220, -1, 25223, 18032, 18031, -1, 25224, 25223, 18031, -1, 25225, 18031, 25219, -1, 25225, 25219, 25221, -1, 25225, 25224, 18031, -1, 25226, 25225, 25221, -1, 25227, 25228, 25229, -1, 25227, 25226, 25228, -1, 25230, 25225, 25226, -1, 25230, 25226, 25227, -1, 25231, 25232, 25233, -1, 25234, 25232, 25235, -1, 25235, 25232, 25236, -1, 25236, 25232, 25231, -1, 25237, 25238, 25239, -1, 25239, 25238, 25240, -1, 25234, 25241, 25232, -1, 25242, 25241, 25243, -1, 25243, 25241, 25234, -1, 25244, 25245, 25246, -1, 25242, 25247, 25241, -1, 25248, 25249, 25237, -1, 25237, 25249, 25238, -1, 25246, 25250, 25251, -1, 25245, 25250, 25246, -1, 25248, 25252, 25249, -1, 25253, 25254, 25244, -1, 25244, 25254, 25245, -1, 25248, 25255, 25252, -1, 25251, 25256, 25257, -1, 25250, 25256, 25251, -1, 25248, 25258, 25255, -1, 25259, 25260, 25248, -1, 25261, 25260, 25259, -1, 25248, 25260, 25258, -1, 25261, 25262, 25260, -1, 25263, 25264, 25265, -1, 25253, 25266, 25254, -1, 25265, 25264, 25267, -1, 25267, 25264, 25268, -1, 25268, 25264, 25269, -1, 25269, 25264, 25270, -1, 25270, 25264, 25262, -1, 25257, 25271, 25272, -1, 25256, 25271, 25257, -1, 25262, 25264, 25260, -1, 25273, 25274, 25253, -1, 25263, 25275, 25264, -1, 25247, 25276, 25263, -1, 25253, 25274, 25266, -1, 25263, 25276, 25275, -1, 25272, 25277, 25278, -1, 25271, 25277, 25272, -1, 25242, 25279, 25247, -1, 25117, 25279, 25242, -1, 25277, 25280, 25278, -1, 25278, 25280, 25281, -1, 25247, 25279, 25276, -1, 25117, 25282, 25279, -1, 25280, 25283, 25281, -1, 25281, 25283, 25284, -1, 25115, 25282, 25117, -1, 25273, 25285, 25274, -1, 25283, 25286, 25284, -1, 25286, 25240, 25284, -1, 25091, 25093, 25114, -1, 25114, 25093, 25287, -1, 25114, 25287, 25115, -1, 25115, 25287, 25282, -1, 25231, 25233, 25273, -1, 25273, 25233, 25285, -1, 25286, 25239, 25240, -1, 25288, 25252, 25289, -1, 25252, 25255, 25289, -1, 25289, 25258, 25290, -1, 25255, 25258, 25289, -1, 25258, 25260, 25290, -1, 25253, 25244, 25291, -1, 25291, 25244, 25292, -1, 25292, 25246, 25293, -1, 25244, 25246, 25292, -1, 25246, 25251, 25293, -1, 25293, 25257, 25294, -1, 25251, 25257, 25293, -1, 25294, 25272, 25295, -1, 25257, 25272, 25294, -1, 25295, 25278, 25296, -1, 25296, 25278, 25297, -1, 25272, 25278, 25295, -1, 25297, 25281, 25298, -1, 25278, 25281, 25297, -1, 25298, 25284, 25299, -1, 25299, 25284, 25300, -1, 25281, 25284, 25298, -1, 25300, 25240, 25301, -1, 25284, 25240, 25300, -1, 25301, 25238, 25302, -1, 25302, 25238, 25303, -1, 25240, 25238, 25301, -1, 25303, 25249, 25304, -1, 25238, 25249, 25303, -1, 25304, 25252, 25288, -1, 25249, 25252, 25304, -1, 25264, 25290, 25260, -1, 25291, 25273, 25253, -1, 17089, 17153, 24581, -1, 25305, 17173, 25306, -1, 25306, 17173, 25307, -1, 25307, 17173, 25308, -1, 17153, 17173, 25305, -1, 17089, 24585, 17100, -1, 25308, 25309, 25310, -1, 25310, 25309, 25311, -1, 25311, 25309, 25312, -1, 24584, 24585, 17089, -1, 25312, 25309, 25313, -1, 25313, 25309, 24594, -1, 25314, 25309, 17173, -1, 17089, 24583, 24584, -1, 17173, 25309, 25308, -1, 25309, 25315, 24594, -1, 24585, 24586, 17100, -1, 17089, 24582, 24583, -1, 24586, 24587, 17100, -1, 17100, 25315, 25316, -1, 17089, 24581, 24582, -1, 24587, 24588, 17100, -1, 24588, 24589, 17100, -1, 17100, 24589, 25315, -1, 24589, 24590, 25315, -1, 24590, 24591, 25315, -1, 24591, 24592, 25315, -1, 24592, 24593, 25315, -1, 24593, 24594, 25315, -1, 24581, 17153, 25317, -1, 25317, 17153, 25318, -1, 25318, 17153, 25319, -1, 25319, 17153, 25320, -1, 25320, 17153, 25305, -1, 18076, 25321, 18077, -1, 18079, 25322, 18080, -1, 18077, 25322, 18079, -1, 25321, 25322, 18077, -1, 25323, 24768, 25324, -1, 25324, 24768, 25325, -1, 25325, 24768, 25326, -1, 25326, 24768, 25327, -1, 25327, 24768, 25328, -1, 25328, 24768, 24765, -1, 24768, 18042, 25329, -1, 25329, 18042, 25330, -1, 25330, 18042, 25331, -1, 25331, 18042, 25332, -1, 25332, 18042, 25333, -1, 25333, 18042, 25334, -1, 25334, 18042, 25335, -1, 25323, 18042, 24768, -1, 25323, 25336, 18042, -1, 25337, 25338, 25336, -1, 25338, 25339, 25336, -1, 25336, 25339, 18042, -1, 25339, 25340, 18042, -1, 25340, 18000, 18042, -1, 25341, 25342, 25323, -1, 25342, 25336, 25323, -1, 25343, 25344, 25345, -1, 25346, 25344, 25347, -1, 25347, 25344, 25348, -1, 25348, 25344, 25349, -1, 25349, 25344, 25343, -1, 25344, 18021, 25345, -1, 25344, 25350, 18021, -1, 25351, 25352, 25350, -1, 25352, 25353, 25350, -1, 25353, 25354, 25350, -1, 25354, 25355, 25350, -1, 25355, 25356, 25350, -1, 25350, 18030, 18021, -1, 25356, 18030, 25350, -1, 25357, 25358, 25344, -1, 25358, 25350, 25344, -1, 25345, 25359, 25343, -1, 25355, 25360, 25356, -1, 25339, 25361, 25340, -1, 18253, 18252, 18374, -1, 18374, 18252, 25362, -1, 25362, 18278, 25363, -1, 18252, 18278, 25362, -1, 25363, 18214, 25364, -1, 18278, 18214, 25363, -1, 25364, 18213, 25365, -1, 18214, 18213, 25364, -1, 25365, 18245, 25366, -1, 18213, 18245, 25365, -1, 25366, 18269, 25367, -1, 18245, 18269, 25366, -1, 25367, 18288, 25368, -1, 18269, 18288, 25367, -1, 25368, 18234, 25369, -1, 18288, 18234, 25368, -1, 25369, 18233, 25370, -1, 18234, 18233, 25369, -1, 25370, 18260, 25371, -1, 18233, 18260, 25370, -1, 25371, 18282, 25372, -1, 18260, 18282, 25371, -1, 25372, 18291, 25373, -1, 18282, 18291, 25372, -1, 25373, 18292, 18357, -1, 18291, 18292, 25373, -1, 25370, 25374, 25375, -1, 25370, 25371, 25374, -1, 25376, 18362, 18365, -1, 18372, 25377, 25378, -1, 18372, 25378, 25379, -1, 25380, 18365, 18366, -1, 25380, 25376, 18365, -1, 18372, 25379, 18371, -1, 25381, 18360, 18362, -1, 25369, 25370, 25375, -1, 25369, 25375, 25382, -1, 25381, 18362, 25376, -1, 25383, 18366, 18367, -1, 25383, 25380, 18366, -1, 25384, 18358, 18360, -1, 18373, 25377, 18372, -1, 25368, 25369, 25382, -1, 25368, 25382, 25385, -1, 25384, 18360, 25381, -1, 18374, 25386, 25377, -1, 25387, 18367, 18368, -1, 25387, 25383, 18367, -1, 18374, 25388, 25386, -1, 18374, 25377, 18373, -1, 25389, 18357, 18358, -1, 25389, 25373, 18357, -1, 25389, 18358, 25384, -1, 25367, 25385, 25390, -1, 25367, 25368, 25385, -1, 25391, 18368, 18369, -1, 25391, 25387, 18368, -1, 25362, 25388, 18374, -1, 25362, 25392, 25388, -1, 25366, 25390, 25393, -1, 25394, 25372, 25373, -1, 25366, 25367, 25390, -1, 25394, 25373, 25389, -1, 25395, 18369, 18370, -1, 25395, 25391, 18369, -1, 25363, 25392, 25362, -1, 25363, 25396, 25392, -1, 25365, 25393, 25397, -1, 25365, 25366, 25393, -1, 25398, 25372, 25394, -1, 25364, 25397, 25396, -1, 25364, 25396, 25363, -1, 25364, 25365, 25397, -1, 25371, 25372, 25398, -1, 25399, 25395, 18370, -1, 25374, 25371, 25398, -1, 18371, 25379, 25399, -1, 18371, 25399, 18370, -1, 25400, 25389, 25401, -1, 25401, 25384, 25402, -1, 25389, 25384, 25401, -1, 25402, 25381, 25403, -1, 25384, 25381, 25402, -1, 25403, 25376, 25404, -1, 25381, 25376, 25403, -1, 25404, 25380, 25405, -1, 25376, 25380, 25404, -1, 25405, 25383, 25406, -1, 25380, 25383, 25405, -1, 25406, 25387, 25407, -1, 25383, 25387, 25406, -1, 25407, 25391, 25408, -1, 25387, 25391, 25407, -1, 25408, 25395, 25409, -1, 25391, 25395, 25408, -1, 25409, 25399, 25410, -1, 25395, 25399, 25409, -1, 25410, 25379, 25411, -1, 25399, 25379, 25410, -1, 25411, 25378, 25412, -1, 25379, 25378, 25411, -1, 25378, 25377, 25412, -1, 25412, 25386, 25413, -1, 25377, 25386, 25412, -1, 16192, 16126, 16071, -1, 25414, 24444, 24445, -1, 25414, 25415, 24444, -1, 25416, 25415, 25414, -1, 25414, 25417, 25416, -1, 24549, 25418, 24550, -1, 16311, 16290, 2826, -1, 16290, 2823, 2826, -1, 16290, 16285, 2823, -1, 16285, 16284, 2823, -1, 2675, 15299, 2673, -1, 15299, 15298, 2673, -1, 25419, 24614, 24426, -1, 25420, 25419, 24426, -1, 25421, 25422, 25419, -1, 25421, 25419, 25420, -1, 25423, 25420, 25424, -1, 25423, 25424, 25425, -1, 25423, 25421, 25420, -1, 25426, 25421, 25423, -1, 25427, 25422, 25421, -1, 25428, 25422, 25427, -1, 25429, 25430, 25428, -1, 25429, 25428, 25427, -1, 17262, 25431, 25432, -1, 17262, 25432, 17263, -1, 16318, 16315, 2905, -1, 16315, 2906, 2905, -1, 16315, 16317, 2906, -1, 2824, 16287, 2822, -1, 16288, 16287, 2824, -1, 25433, 24434, 25434, -1, 24432, 25435, 24434, -1, 24434, 25436, 25434, -1, 25435, 25436, 24434, -1, 24764, 24762, 24758, -1, 25427, 24758, 24760, -1, 25427, 24764, 24758, -1, 25429, 25427, 24760, -1, 25437, 25435, 25438, -1, 25436, 25437, 25439, -1, 25436, 25435, 25437, -1, 25438, 25440, 25441, -1, 25437, 25438, 25441, -1, 24497, 24548, 24547, -1, 25442, 24510, 24511, -1, 25442, 24431, 24510, -1, 25440, 24431, 25442, -1, 24432, 24431, 25440, -1, 25438, 24432, 25440, -1, 25435, 24432, 25438, -1, 24510, 24528, 24500, -1, 24431, 24436, 24510, -1, 24510, 24436, 24528, -1, 24431, 24429, 24436, -1, 25416, 25442, 25415, -1, 25440, 25416, 25441, -1, 25440, 25442, 25416, -1, 24466, 24511, 24453, -1, 25442, 24511, 24466, -1, 24444, 25442, 24466, -1, 24443, 24466, 24536, -1, 24443, 24444, 24466, -1, 25415, 25442, 24444, -1, 25417, 25441, 25416, -1, 25439, 25417, 25443, -1, 25439, 25437, 25417, -1, 25437, 25441, 25417, -1, 24566, 24449, 24574, -1, 25417, 25414, 24449, -1, 25417, 24566, 25443, -1, 25417, 24449, 24566, -1, 25414, 24445, 24449, -1, 16060, 16201, 25418, -1, 16060, 25418, 24549, -1, 16060, 24549, 24543, -1, 24452, 16062, 16060, -1, 24452, 16060, 24543, -1, 24433, 25433, 24749, -1, 24434, 25433, 24433, -1, 25421, 24764, 25427, -1, 25421, 24763, 24764, -1, 25421, 25426, 24763, -1, 16317, 16314, 2672, -1, 16317, 2672, 2906, -1, 2823, 16288, 2824, -1, 16284, 16288, 2823, -1, 16366, 25444, 24609, -1, 16350, 25445, 16366, -1, 17260, 25445, 16350, -1, 16366, 25445, 25444, -1, 16287, 16286, 2803, -1, 2822, 16287, 2803, -1, 16314, 16312, 2672, -1, 2672, 16312, 16299, -1, 16299, 2900, 2672, -1, 16299, 16300, 2900, -1, 2688, 16318, 2905, -1, 16319, 16318, 2688, -1, 24413, 25446, 2678, -1, 24412, 24417, 24413, -1, 24413, 24417, 25446, -1, 25446, 25447, 2678, -1, 24608, 25448, 25447, -1, 25448, 25449, 25447, -1, 25447, 25449, 2678, -1, 24608, 24607, 25448, -1, 16322, 16320, 25449, -1, 16320, 2688, 25449, -1, 25449, 2688, 2678, -1, 16320, 16319, 2688, -1, 15298, 15297, 2673, -1, 15297, 2678, 2673, -1, 15297, 24413, 2678, -1, 25445, 17260, 17263, -1, 25445, 17263, 25432, -1, 24603, 25444, 24601, -1, 24609, 25444, 24603, -1, 17262, 17296, 25431, -1, 17261, 17296, 17262, -1, 16311, 2826, 2825, -1, 16311, 2825, 16310, -1, 16300, 16298, 2898, -1, 2900, 16300, 2898, -1, 2709, 2942, 15301, -1, 2702, 2709, 15301, -1, 2686, 15301, 15300, -1, 2686, 2702, 15301, -1, 2674, 2686, 15300, -1, 2674, 15299, 2675, -1, 15300, 15299, 2674, -1, 15294, 2757, 2759, -1, 15294, 2927, 2757, -1, 25450, 25451, 25452, -1, 25453, 25450, 25452, -1, 25454, 25450, 25453, -1, 24596, 25450, 25454, -1, 25455, 25456, 25457, -1, 25458, 25459, 25455, -1, 25316, 25315, 24564, -1, 25458, 25455, 25457, -1, 25460, 25458, 25457, -1, 25461, 25462, 25463, -1, 16202, 25464, 25465, -1, 25461, 25463, 25460, -1, 16202, 25465, 25466, -1, 25461, 25460, 25457, -1, 16202, 24297, 25464, -1, 25467, 25461, 25457, -1, 16201, 16202, 25466, -1, 16201, 25466, 25468, -1, 16201, 25468, 25469, -1, 16201, 25469, 25470, -1, 16201, 25470, 25471, -1, 16201, 25471, 25472, -1, 24550, 16201, 25472, -1, 24550, 25472, 25473, -1, 24550, 25473, 25474, -1, 24550, 25474, 25475, -1, 24550, 25475, 25476, -1, 24550, 25418, 16201, -1, 24564, 24550, 25316, -1, 25316, 24550, 25476, -1, 25315, 25457, 25450, -1, 25315, 24596, 24564, -1, 25315, 25450, 24596, -1, 25315, 25467, 25457, -1, 25477, 24297, 24298, -1, 25477, 24298, 25478, -1, 25477, 25478, 25479, -1, 25477, 25479, 25480, -1, 25477, 25480, 25481, -1, 25477, 25481, 25482, -1, 25477, 25482, 25483, -1, 25484, 24297, 25477, -1, 25485, 24297, 25484, -1, 25464, 24297, 25485, -1, 25486, 25457, 25456, -1, 25486, 25487, 25457, -1, 25488, 25456, 25455, -1, 25488, 25486, 25456, -1, 25489, 25455, 25459, -1, 25489, 25488, 25455, -1, 24752, 25490, 24753, -1, 25491, 24595, 25492, -1, 25491, 25492, 25493, -1, 25491, 25493, 25494, -1, 25491, 25494, 25495, -1, 25309, 24561, 24595, -1, 25496, 25490, 24752, -1, 25309, 24595, 25491, -1, 25487, 25309, 25491, -1, 25497, 25496, 24752, -1, 25498, 25488, 25489, -1, 25499, 25487, 25486, -1, 25499, 25309, 25487, -1, 24566, 25500, 25501, -1, 24566, 25501, 25502, -1, 24566, 25502, 25503, -1, 24566, 25503, 25504, -1, 24566, 25504, 25505, -1, 25506, 25499, 25486, -1, 25507, 25486, 25488, -1, 25507, 25498, 25508, -1, 25443, 24566, 25505, -1, 25443, 25497, 24752, -1, 25507, 25488, 25498, -1, 25443, 25505, 25509, -1, 25507, 25506, 25486, -1, 25443, 25509, 25510, -1, 25443, 25510, 25511, -1, 25443, 25511, 25512, -1, 25443, 25512, 25513, -1, 25514, 25506, 25507, -1, 25443, 25513, 25515, -1, 25443, 25515, 25497, -1, 24566, 24561, 25314, -1, 24566, 25314, 25500, -1, 25490, 25516, 25517, -1, 25490, 25517, 25518, -1, 25490, 25518, 25519, -1, 25490, 25519, 25520, -1, 25490, 25520, 25521, -1, 25490, 25521, 24753, -1, 25314, 24561, 25309, -1, 24751, 24750, 25428, -1, 25430, 24751, 25428, -1, 25428, 24750, 24637, -1, 25419, 24612, 24614, -1, 25422, 24637, 24612, -1, 25422, 25428, 24637, -1, 25422, 24612, 25419, -1, 24627, 24618, 24655, -1, 24627, 24655, 25522, -1, 24626, 25522, 25523, -1, 24626, 24627, 25522, -1, 24695, 25523, 24703, -1, 24695, 24625, 24626, -1, 24695, 24626, 25523, -1, 24694, 24703, 24702, -1, 24694, 24695, 24703, -1, 24693, 24702, 24705, -1, 24693, 24694, 24702, -1, 24691, 24693, 24705, -1, 16058, 15536, 15532, -1, 15536, 16061, 25524, -1, 16058, 16061, 15536, -1, 25524, 25525, 25526, -1, 16061, 25525, 25524, -1, 25526, 25527, 24812, -1, 25525, 25527, 25526, -1, 25527, 24493, 24812, -1, 24493, 24824, 24812, -1, 24493, 24514, 24824, -1, 24526, 24494, 24747, -1, 24499, 24494, 24526, -1, 24747, 24748, 24746, -1, 24494, 24748, 24747, -1, 15650, 16151, 15654, -1, 16145, 16151, 15650, -1, 24748, 24544, 24746, -1, 24746, 24544, 24546, -1, 24755, 17418, 25528, -1, 17419, 17418, 24755, -1, 17414, 17416, 25529, -1, 17414, 25529, 17426, -1, 25530, 17410, 17425, -1, 17409, 17410, 25530, -1, 17406, 17409, 25530, -1, 17406, 25530, 25531, -1, 17406, 25531, 25532, -1, 17406, 25532, 17402, -1, 25529, 17402, 25532, -1, 17416, 17402, 25529, -1, 24757, 25532, 24760, -1, 25429, 24760, 25532, -1, 24755, 25529, 24757, -1, 25531, 25429, 25532, -1, 24751, 25430, 25429, -1, 24751, 25531, 25530, -1, 24751, 25429, 25531, -1, 17425, 24751, 25530, -1, 24696, 24751, 17425, -1, 17426, 25529, 24755, -1, 17426, 24696, 17425, -1, 25528, 17426, 24755, -1, 25528, 25533, 17426, -1, 24697, 24696, 17426, -1, 24697, 17426, 25533, -1, 25529, 25532, 24757, -1, 16213, 24301, 24300, -1, 16214, 24301, 16213, -1, 16065, 16213, 24300, -1, 16119, 16213, 16065, -1, 16129, 16198, 16082, -1, 16204, 16198, 16129, -1, 16065, 16204, 16129, -1, 16205, 16204, 16065, -1, 24300, 16205, 16065, -1, 16198, 16119, 16082, -1, 16198, 16207, 16119, -1, 16207, 16213, 16119, -1, 16361, 24610, 16370, -1, 16347, 24610, 16361, -1, 16347, 24611, 24610, -1, 16347, 16356, 24611, -1, 16351, 16350, 16366, -1, 16351, 16366, 16368, -1, 25534, 25447, 25446, -1, 25535, 25447, 25534, -1, 2809, 25536, 2810, -1, 16374, 25537, 25536, -1, 16373, 25537, 16374, -1, 16373, 24597, 25537, -1, 24600, 25538, 24597, -1, 25537, 25538, 25539, -1, 24597, 25538, 25537, -1, 24600, 24604, 25538, -1, 25535, 24608, 25447, -1, 25540, 24605, 25535, -1, 25538, 24605, 25540, -1, 24604, 24605, 25538, -1, 25535, 24605, 24608, -1, 25537, 2810, 25536, -1, 2908, 25537, 25541, -1, 2810, 25537, 2908, -1, 25541, 25539, 25542, -1, 25537, 25539, 25541, -1, 25539, 25543, 25542, -1, 25539, 25538, 25543, -1, 25538, 25544, 25543, -1, 25538, 25540, 25544, -1, 25540, 25534, 25544, -1, 25540, 25535, 25534, -1, 2908, 25545, 2907, -1, 25541, 24689, 25545, -1, 24628, 24689, 25541, -1, 24425, 24628, 25541, -1, 25543, 25541, 25542, -1, 25543, 24425, 25541, -1, 24418, 24421, 24425, -1, 24418, 24425, 25543, -1, 24417, 25534, 25446, -1, 24416, 25543, 25544, -1, 24416, 25544, 25534, -1, 24416, 24418, 25543, -1, 24416, 25534, 24417, -1, 2908, 25541, 25545, -1, 24541, 24448, 24539, -1, 24451, 24448, 24541, -1, 24448, 24531, 24539, -1, 24448, 24438, 24531, -1, 24436, 24536, 24528, -1, 24436, 24443, 24536, -1, 24449, 24450, 24574, -1, 24537, 24442, 24535, -1, 24446, 24442, 24537, -1, 24447, 24537, 24538, -1, 24447, 24446, 24537, -1, 24530, 24447, 24538, -1, 24437, 24447, 24530, -1, 24532, 24437, 24530, -1, 24532, 25546, 25547, -1, 24534, 24532, 25547, -1, 24439, 24437, 24532, -1, 24439, 24532, 24534, -1, 24441, 24439, 24534, -1, 24430, 24427, 24439, -1, 24430, 24439, 24441, -1, 24533, 24441, 24534, -1, 24440, 24441, 24533, -1, 24535, 24440, 24533, -1, 24442, 24440, 24535, -1, 25548, 25549, 25546, -1, 25549, 25547, 25546, -1, 24495, 25547, 24496, -1, 25547, 25549, 24496, -1, 24495, 24527, 25547, -1, 24527, 24534, 25547, -1, 25546, 24548, 24497, -1, 25548, 25546, 24497, -1, 24529, 24548, 25546, -1, 24532, 24529, 25546, -1, 24496, 25548, 24497, -1, 25549, 25548, 24496, -1, 24435, 24428, 24441, -1, 24428, 24430, 24441, -1, 15264, 15265, 24439, -1, 24427, 15264, 24439, -1, 24424, 24419, 25550, -1, 24423, 24419, 24424, -1, 24422, 24419, 24423, -1, 25551, 15308, 15306, -1, 25550, 24415, 25552, -1, 24419, 24415, 25550, -1, 25552, 24415, 24414, -1, 24414, 25553, 25552, -1, 24414, 15303, 25553, -1, 25551, 25554, 15308, -1, 15303, 25554, 25553, -1, 25554, 15302, 15308, -1, 15303, 15302, 25554, -1, 25555, 15306, 15304, -1, 25551, 15306, 25555, -1, 24424, 25420, 24426, -1, 24424, 25550, 25420, -1, 25420, 25552, 25424, -1, 25550, 25552, 25420, -1, 25556, 25553, 25557, -1, 25552, 25556, 25425, -1, 25552, 25425, 25424, -1, 25552, 25553, 25556, -1, 25557, 25554, 25558, -1, 25553, 25554, 25557, -1, 25554, 25555, 25558, -1, 25554, 25551, 25555, -1, 15307, 25555, 15304, -1, 25557, 25434, 25556, -1, 25433, 25434, 25557, -1, 25558, 25555, 15307, -1, 25558, 25433, 25557, -1, 24749, 25558, 15307, -1, 24749, 25433, 25558, -1, 17176, 25496, 17155, -1, 25490, 25496, 17176, -1, 25477, 17124, 25484, -1, 17118, 17124, 25477, -1, 16196, 16199, 16116, -1, 16196, 16116, 16125, -1, 16140, 24299, 24297, -1, 16133, 24299, 16140, -1, 16199, 16133, 16116, -1, 16199, 16203, 16133, -1, 16203, 24299, 16133, -1, 16140, 16196, 16125, -1, 16202, 16196, 16140, -1, 24297, 16202, 16140, -1, 25423, 24763, 25426, -1, 24754, 25559, 24752, -1, 24754, 25560, 25559, -1, 25560, 25561, 25559, -1, 25560, 25562, 25561, -1, 25561, 25425, 25556, -1, 25562, 25425, 25561, -1, 24759, 24761, 25560, -1, 24761, 25562, 25560, -1, 25560, 24756, 24759, -1, 24761, 24763, 25562, -1, 25423, 25425, 24763, -1, 24763, 25425, 25562, -1, 25560, 24754, 24756, -1, 25436, 25439, 25559, -1, 25561, 25436, 25559, -1, 25443, 25559, 25439, -1, 25434, 25436, 25561, -1, 25556, 25434, 25561, -1, 24752, 25559, 25443, -1, 15248, 15604, 15185, -1, 15185, 15604, 15193, -1, 15620, 15184, 15187, -1, 15623, 15187, 15189, -1, 15623, 15620, 15187, -1, 15625, 15189, 15192, -1, 15625, 15623, 15189, -1, 15627, 15192, 15190, -1, 15627, 15625, 15192, -1, 15629, 15190, 15188, -1, 15629, 15627, 15190, -1, 15648, 15188, 15186, -1, 15648, 15629, 15188, -1, 15547, 15186, 15183, -1, 15547, 15648, 15186, -1, 15543, 15183, 15182, -1, 15543, 15547, 15183, -1, 15544, 15182, 15197, -1, 15544, 15543, 15182, -1, 15613, 15197, 15196, -1, 15613, 15544, 15197, -1, 15610, 15196, 15195, -1, 15610, 15613, 15196, -1, 15609, 15195, 15194, -1, 15609, 15610, 15195, -1, 15606, 15194, 15193, -1, 15606, 15609, 15194, -1, 15604, 15606, 15193, -1, 15184, 15257, 15191, -1, 15620, 15257, 15184, -1, 15861, 15639, 15868, -1, 15640, 15639, 15861, -1, 15534, 15249, 15860, -1, 15534, 15250, 15249, -1, 15533, 15534, 15860, -1, 15533, 15860, 15863, -1, 15535, 15863, 15866, -1, 15535, 15533, 15863, -1, 15531, 15866, 15865, -1, 15531, 15535, 15866, -1, 15529, 15865, 15867, -1, 15529, 15531, 15865, -1, 15661, 15867, 15864, -1, 15661, 15529, 15867, -1, 15659, 15864, 15862, -1, 15659, 15661, 15864, -1, 15655, 15862, 15859, -1, 15655, 15659, 15862, -1, 15653, 15859, 15858, -1, 15653, 15655, 15859, -1, 15656, 15858, 15872, -1, 15656, 15653, 15858, -1, 15657, 15872, 15871, -1, 15657, 15656, 15872, -1, 15642, 15871, 15870, -1, 15642, 15657, 15871, -1, 15641, 15870, 15869, -1, 15641, 15642, 15870, -1, 15639, 15869, 15868, -1, 15639, 15641, 15869, -1, 25563, 25564, 25565, -1, 16161, 16160, 25566, -1, 16161, 25567, 25568, -1, 16161, 25566, 25567, -1, 25569, 16161, 25568, -1, 25570, 25571, 25564, -1, 25570, 25572, 25571, -1, 25570, 25564, 25563, -1, 16171, 25572, 25570, -1, 16170, 25573, 25572, -1, 16170, 25572, 16171, -1, 25574, 25575, 25576, -1, 25574, 25577, 25575, -1, 16169, 25578, 25573, -1, 25574, 25579, 25577, -1, 25580, 25581, 25577, -1, 16169, 25573, 16170, -1, 25580, 25577, 25579, -1, 16166, 25582, 25583, -1, 16166, 25569, 25582, -1, 16166, 16161, 25569, -1, 16168, 25584, 25578, -1, 25585, 25574, 25576, -1, 16168, 25578, 16169, -1, 25586, 25587, 25581, -1, 16167, 25583, 25584, -1, 25586, 16156, 25587, -1, 16167, 16166, 25583, -1, 25586, 25581, 25580, -1, 16167, 25584, 16168, -1, 25588, 25576, 25589, -1, 25588, 25585, 25576, -1, 25590, 16157, 16156, -1, 25590, 16156, 25586, -1, 25591, 25589, 25592, -1, 25591, 25588, 25589, -1, 25593, 16158, 16157, -1, 25593, 16157, 25590, -1, 25594, 25592, 25595, -1, 25594, 25591, 25592, -1, 25596, 16158, 25593, -1, 16159, 16158, 25596, -1, 25597, 25595, 25598, -1, 25597, 25594, 25595, -1, 25599, 16159, 25596, -1, 25600, 25597, 25598, -1, 25565, 25600, 25598, -1, 16160, 25599, 25566, -1, 16160, 16159, 25599, -1, 25564, 25600, 25565, -1, 25572, 15688, 25571, -1, 25571, 25601, 25564, -1, 15688, 25601, 25571, -1, 25564, 25602, 25600, -1, 25601, 25602, 25564, -1, 25600, 25603, 25597, -1, 25602, 25603, 25600, -1, 25597, 25604, 25594, -1, 25603, 25604, 25597, -1, 25594, 25605, 25591, -1, 25604, 25605, 25594, -1, 25591, 25606, 25588, -1, 25605, 25606, 25591, -1, 25588, 25607, 25585, -1, 25606, 25607, 25588, -1, 25585, 25608, 25574, -1, 25607, 25608, 25585, -1, 25574, 25609, 25579, -1, 25608, 25609, 25574, -1, 25579, 25610, 25580, -1, 25609, 25610, 25579, -1, 25610, 25611, 25580, -1, 25580, 25612, 25586, -1, 25611, 25612, 25580, -1, 25586, 15737, 25590, -1, 25612, 15737, 25586, -1, 15737, 15734, 25590, -1, 25590, 15734, 25593, -1, 25593, 15714, 25596, -1, 15734, 15714, 25593, -1, 25596, 15713, 25599, -1, 15714, 15713, 25596, -1, 25599, 15751, 25566, -1, 15713, 15751, 25599, -1, 25566, 15736, 25567, -1, 15751, 15736, 25566, -1, 25567, 15711, 25568, -1, 15736, 15711, 25567, -1, 25568, 15710, 25569, -1, 15711, 15710, 25568, -1, 25569, 15753, 25582, -1, 15710, 15753, 25569, -1, 25582, 15743, 25583, -1, 15753, 15743, 25582, -1, 25583, 15725, 25584, -1, 15743, 15725, 25583, -1, 25584, 15708, 25578, -1, 15725, 15708, 25584, -1, 25578, 15689, 25573, -1, 15708, 15689, 25578, -1, 25573, 15688, 25572, -1, 15689, 15688, 25573, -1, 25613, 25614, 24347, -1, 25613, 24347, 24346, -1, 25615, 25616, 25617, -1, 25618, 25617, 25619, -1, 25618, 25615, 25617, -1, 25620, 24402, 24386, -1, 25620, 24346, 24402, -1, 25620, 25613, 24346, -1, 25621, 25622, 25616, -1, 25621, 25616, 25615, -1, 24366, 25620, 24386, -1, 25623, 25619, 25624, -1, 25623, 25618, 25619, -1, 25625, 25626, 25622, -1, 25627, 25628, 25629, -1, 25627, 25630, 25628, -1, 25625, 25622, 25621, -1, 25627, 24330, 25630, -1, 25627, 25629, 25631, -1, 25632, 24328, 24330, -1, 25632, 24332, 24328, -1, 25632, 24353, 24332, -1, 25632, 24330, 25627, -1, 25633, 25624, 25631, -1, 25633, 25623, 25624, -1, 25632, 25620, 24366, -1, 25632, 24366, 24353, -1, 24370, 25634, 25626, -1, 24370, 25626, 25625, -1, 25635, 25633, 25631, -1, 24336, 25636, 25634, -1, 24336, 25634, 24370, -1, 25637, 25635, 25631, -1, 24335, 25636, 24336, -1, 25638, 25636, 24335, -1, 25639, 25637, 25631, -1, 24397, 25638, 24335, -1, 25629, 25639, 25631, -1, 25640, 25638, 24397, -1, 24378, 25640, 24397, -1, 25614, 24378, 24347, -1, 25614, 25640, 24378, -1, 25641, 24476, 25642, -1, 25643, 25644, 25645, -1, 25643, 25646, 25644, -1, 24477, 25641, 25647, -1, 24477, 24476, 25641, -1, 25648, 25649, 25650, -1, 25651, 25650, 25652, -1, 25651, 25648, 25650, -1, 25653, 25654, 25649, -1, 25653, 25649, 25648, -1, 25655, 25656, 25646, -1, 25655, 25646, 25643, -1, 25657, 25652, 25658, -1, 25657, 25651, 25652, -1, 25659, 25654, 25653, -1, 24478, 25647, 25660, -1, 24478, 24477, 25647, -1, 25661, 25658, 25662, -1, 24489, 25663, 25664, -1, 25661, 25657, 25658, -1, 24489, 25664, 25656, -1, 24489, 25656, 25655, -1, 25665, 24469, 24468, -1, 25665, 24468, 25654, -1, 24479, 24478, 25660, -1, 25665, 25654, 25659, -1, 24487, 25666, 25663, -1, 24487, 25663, 24489, -1, 25667, 25668, 25669, -1, 25667, 25662, 25668, -1, 24480, 25660, 25670, -1, 25667, 25661, 25662, -1, 24480, 24479, 25660, -1, 24485, 25671, 25666, -1, 24485, 25666, 24487, -1, 25672, 24469, 25665, -1, 24481, 25670, 25673, -1, 24481, 24480, 25670, -1, 24483, 25673, 25671, -1, 25674, 25667, 25669, -1, 24483, 25671, 24485, -1, 24483, 24481, 25673, -1, 25675, 25674, 25669, -1, 25676, 24472, 24469, -1, 25676, 24469, 25672, -1, 25677, 25674, 25675, -1, 25678, 24474, 24472, -1, 25678, 24472, 25676, -1, 25645, 25644, 25677, -1, 25645, 25677, 25675, -1, 25642, 24474, 25678, -1, 24476, 24474, 25642, -1, 25664, 24853, 25656, -1, 25656, 25679, 25646, -1, 24853, 25679, 25656, -1, 25646, 25680, 25644, -1, 25679, 25680, 25646, -1, 25644, 25681, 25677, -1, 25680, 25681, 25644, -1, 25677, 25682, 25674, -1, 25681, 25682, 25677, -1, 25674, 25683, 25667, -1, 25682, 25683, 25674, -1, 25667, 25684, 25661, -1, 25683, 25684, 25667, -1, 25661, 25685, 25657, -1, 25684, 25685, 25661, -1, 25657, 25686, 25651, -1, 25685, 25686, 25657, -1, 25651, 25687, 25648, -1, 25686, 25687, 25651, -1, 25648, 25688, 25653, -1, 25687, 25688, 25648, -1, 25653, 25689, 25659, -1, 25688, 25689, 25653, -1, 25659, 25690, 25665, -1, 25689, 25690, 25659, -1, 25690, 24899, 25665, -1, 16141, 16171, 25570, -1, 16144, 25570, 25563, -1, 16144, 16141, 25570, -1, 16150, 25563, 25565, -1, 16150, 16144, 25563, -1, 16154, 25565, 25598, -1, 16154, 16150, 25565, -1, 16066, 25598, 25595, -1, 16066, 16154, 25598, -1, 16064, 25595, 25592, -1, 16064, 16066, 25595, -1, 16080, 25592, 25589, -1, 16080, 16064, 25592, -1, 16136, 25589, 25576, -1, 16136, 16080, 25589, -1, 16135, 25576, 25575, -1, 16135, 16136, 25576, -1, 16134, 16135, 25575, -1, 16121, 25575, 25577, -1, 16121, 16134, 25575, -1, 16120, 25577, 25581, -1, 16120, 16121, 25577, -1, 16117, 25581, 25587, -1, 16117, 16120, 25581, -1, 16118, 25587, 16156, -1, 16118, 16117, 25587, -1, 24490, 24489, 25655, -1, 24501, 25655, 25643, -1, 24501, 24490, 25655, -1, 24498, 25643, 25645, -1, 24498, 24501, 25643, -1, 24491, 25645, 25675, -1, 24491, 24498, 25645, -1, 24492, 25675, 25669, -1, 24492, 24491, 25675, -1, 24522, 25669, 25668, -1, 24522, 24492, 25669, -1, 24521, 25668, 25662, -1, 24521, 24522, 25668, -1, 24520, 25662, 25658, -1, 24520, 24521, 25662, -1, 24518, 25658, 25652, -1, 24518, 24520, 25658, -1, 24512, 25652, 25650, -1, 24512, 24518, 25652, -1, 24513, 25650, 25649, -1, 24513, 24512, 25650, -1, 24515, 25649, 25654, -1, 24515, 24513, 25649, -1, 24519, 24515, 25654, -1, 24470, 25654, 24468, -1, 24470, 24519, 25654, -1, 17956, 25691, 17972, -1, 17956, 17955, 25691, -1, 25691, 17963, 25692, -1, 17955, 17963, 25691, -1, 25692, 17967, 25693, -1, 17963, 17967, 25692, -1, 25693, 17971, 25694, -1, 17967, 17971, 25693, -1, 25694, 17942, 25695, -1, 17971, 17942, 25694, -1, 25695, 17954, 25696, -1, 17942, 17954, 25695, -1, 25696, 17657, 17552, -1, 17954, 17657, 25696, -1, 24899, 24866, 25665, -1, 25665, 24866, 25672, -1, 25672, 24865, 25676, -1, 24866, 24865, 25672, -1, 25676, 24923, 25678, -1, 24865, 24923, 25676, -1, 25678, 24906, 25642, -1, 24923, 24906, 25678, -1, 25642, 24878, 25641, -1, 24906, 24878, 25642, -1, 25641, 24877, 25647, -1, 24878, 24877, 25641, -1, 25647, 24928, 25660, -1, 24877, 24928, 25647, -1, 25660, 24914, 25670, -1, 24928, 24914, 25660, -1, 25670, 24895, 25673, -1, 24914, 24895, 25670, -1, 25673, 24880, 25671, -1, 24895, 24880, 25673, -1, 25671, 24863, 25666, -1, 24880, 24863, 25671, -1, 25666, 24851, 25663, -1, 24863, 24851, 25666, -1, 25663, 24853, 25664, -1, 24851, 24853, 25663, -1, 25499, 25467, 25315, -1, 25309, 25499, 25315, -1, 25489, 25459, 25458, -1, 25498, 25458, 25460, -1, 25498, 25489, 25458, -1, 25508, 25460, 25463, -1, 25508, 25498, 25460, -1, 25507, 25463, 25462, -1, 25507, 25508, 25463, -1, 25514, 25462, 25461, -1, 25514, 25507, 25462, -1, 25506, 25461, 25467, -1, 25506, 25514, 25461, -1, 25499, 25506, 25467, -1, 25487, 25491, 25450, -1, 25487, 25450, 25457, -1, 24580, 24563, 24594, -1, 24594, 24563, 25313, -1, 25313, 24562, 25312, -1, 24563, 24562, 25313, -1, 25312, 24557, 25311, -1, 24562, 24557, 25312, -1, 25311, 24556, 25310, -1, 24557, 24556, 25311, -1, 25310, 24555, 25308, -1, 24556, 24555, 25310, -1, 25308, 24554, 25307, -1, 24555, 24554, 25308, -1, 25307, 24553, 25306, -1, 24554, 24553, 25307, -1, 25306, 24552, 25305, -1, 24553, 24552, 25306, -1, 25305, 24551, 25320, -1, 24552, 24551, 25305, -1, 25320, 24576, 25319, -1, 24551, 24576, 25320, -1, 25319, 24571, 25318, -1, 24576, 24571, 25319, -1, 25318, 24570, 25317, -1, 24571, 24570, 25318, -1, 25317, 24569, 24581, -1, 24570, 24569, 25317, -1, 25697, 25698, 25699, -1, 25700, 25701, 25697, -1, 25697, 25701, 25698, -1, 25698, 25702, 25703, -1, 25701, 25702, 25698, -1, 20416, 20417, 25701, -1, 25701, 25704, 25702, -1, 20417, 20418, 25701, -1, 25701, 20418, 25704, -1, 20418, 25705, 25704, -1, 20418, 20419, 25705, -1, 20419, 25706, 25705, -1, 25707, 25708, 25706, -1, 25708, 25709, 25706, -1, 25706, 25709, 25705, -1, 25709, 25710, 25705, -1, 25710, 25711, 25712, -1, 25710, 25713, 25711, -1, 25710, 25714, 25713, -1, 25710, 25715, 25714, -1, 25709, 25716, 25710, -1, 25710, 25716, 25715, -1, 25717, 25718, 25716, -1, 25716, 25718, 25715, -1, 25718, 25719, 25720, -1, 25721, 25719, 25717, -1, 25717, 25719, 25718, -1, 25722, 25723, 25724, -1, 25724, 25723, 25721, -1, 25721, 25723, 25719, -1, 3196, 25230, 14997, -1, 14997, 25230, 25227, -1, 3196, 25725, 25230, -1, 3196, 25726, 25725, -1, 3257, 25727, 3196, -1, 3196, 25727, 25726, -1, 3257, 25728, 25727, -1, 3257, 16805, 25728, -1, 3257, 16804, 16805, -1, 3194, 25213, 15004, -1, 15004, 25213, 25210, -1, 3194, 25729, 25213, -1, 3194, 25730, 25729, -1, 3267, 25731, 3194, -1, 3194, 25731, 25730, -1, 3267, 25732, 25731, -1, 3267, 25045, 25732, -1, 3267, 25041, 25045, -1, 3260, 25029, 25022, -1, 3195, 25733, 3260, -1, 3260, 25733, 25029, -1, 3195, 25734, 25733, -1, 3195, 25735, 25734, -1, 3195, 25208, 25735, -1, 3195, 15002, 25208, -1, 15002, 25206, 25208, -1, 25736, 20237, 25737, -1, 20237, 20241, 25737, -1, 25737, 20249, 25738, -1, 20241, 20249, 25737, -1, 25738, 20253, 25739, -1, 20249, 20253, 25738, -1, 25739, 20256, 25740, -1, 20253, 20256, 25739, -1, 25740, 20274, 25741, -1, 20256, 20274, 25740, -1, 25741, 20279, 25742, -1, 20274, 20279, 25741, -1, 25742, 19881, 25743, -1, 20279, 19881, 25742, -1, 25744, 25745, 25746, -1, 25744, 25747, 25745, -1, 25744, 25748, 25747, -1, 25749, 25750, 25748, -1, 25749, 25748, 25744, -1, 25741, 25742, 25743, -1, 25739, 25740, 25741, -1, 25739, 25741, 25743, -1, 25737, 25738, 25739, -1, 25737, 25739, 25743, -1, 25736, 25743, 25749, -1, 25736, 25749, 25744, -1, 25736, 25737, 25743, -1, 25751, 25752, 25753, -1, 25754, 25752, 25751, -1, 25755, 25752, 25754, -1, 25756, 25755, 25757, -1, 25756, 25752, 25755, -1, 25758, 25752, 25756, -1, 25759, 25752, 25758, -1, 25760, 25744, 25752, -1, 25760, 25736, 25744, -1, 25760, 25752, 25759, -1, 25761, 25760, 25759, -1, 25762, 25763, 25760, -1, 25764, 25761, 25765, -1, 25764, 25760, 25761, -1, 25766, 25762, 25760, -1, 25766, 25760, 25764, -1, 25736, 20036, 20237, -1, 25736, 25760, 20036, -1, 19880, 25743, 19881, -1, 25749, 25743, 19880, -1, 25759, 19838, 25761, -1, 25761, 20034, 25765, -1, 19838, 20034, 25761, -1, 25765, 20030, 25764, -1, 20034, 20030, 25765, -1, 25764, 20024, 25766, -1, 20030, 20024, 25764, -1, 25766, 20020, 25762, -1, 20024, 20020, 25766, -1, 25762, 20026, 25763, -1, 20020, 20026, 25762, -1, 25763, 20032, 25760, -1, 20026, 20032, 25763, -1, 20032, 20036, 25760, -1, 25749, 19880, 25750, -1, 25750, 20334, 25748, -1, 19880, 20334, 25750, -1, 25748, 20332, 25747, -1, 20334, 20332, 25748, -1, 25747, 20330, 25745, -1, 20332, 20330, 25747, -1, 25745, 20326, 25746, -1, 20330, 20326, 25745, -1, 20326, 20322, 25746, -1, 25746, 20315, 25744, -1, 20322, 20315, 25746, -1, 25759, 25758, 19838, -1, 19838, 25758, 19836, -1, 20112, 25744, 20315, -1, 25752, 25744, 20112, -1, 25752, 20112, 25753, -1, 25753, 20106, 25751, -1, 20112, 20106, 25753, -1, 25751, 20096, 25754, -1, 20106, 20096, 25751, -1, 25754, 20092, 25755, -1, 20096, 20092, 25754, -1, 25755, 20094, 25757, -1, 20092, 20094, 25755, -1, 25757, 20099, 25756, -1, 20094, 20099, 25757, -1, 25756, 20108, 25758, -1, 20099, 20108, 25756, -1, 20108, 19836, 25758, -1, 20184, 20185, 25767, -1, 25767, 20185, 25768, -1, 25768, 20176, 25769, -1, 20185, 20176, 25768, -1, 25770, 20165, 25771, -1, 25769, 20165, 25770, -1, 20176, 20165, 25769, -1, 25771, 20156, 25772, -1, 20165, 20156, 25771, -1, 25772, 20158, 25773, -1, 20156, 20158, 25772, -1, 25773, 20170, 25774, -1, 20158, 20170, 25773, -1, 20170, 19833, 25774, -1, 25775, 25776, 25777, -1, 25778, 25775, 25777, -1, 25779, 25775, 25778, -1, 25780, 25778, 25781, -1, 25780, 25779, 25778, -1, 25782, 25783, 25784, -1, 25785, 25784, 25786, -1, 25785, 25782, 25784, -1, 25787, 25788, 25785, -1, 25787, 25785, 25786, -1, 25789, 25786, 25780, -1, 25789, 25780, 25781, -1, 25789, 25787, 25786, -1, 25769, 25767, 25768, -1, 25770, 25767, 25769, -1, 25772, 25770, 25771, -1, 25772, 25767, 25770, -1, 25773, 25767, 25772, -1, 25774, 25767, 25773, -1, 25790, 25767, 25774, -1, 25791, 25781, 25767, -1, 25791, 25789, 25781, -1, 25791, 25767, 25790, -1, 25792, 25790, 25793, -1, 25792, 25791, 25790, -1, 25794, 25792, 25793, -1, 25795, 25793, 25796, -1, 25795, 25794, 25793, -1, 25767, 25781, 20184, -1, 20184, 25781, 20379, -1, 19834, 25774, 19833, -1, 25790, 25774, 19834, -1, 25780, 19877, 25779, -1, 19877, 20403, 25779, -1, 25779, 20401, 25775, -1, 20403, 20401, 25779, -1, 25775, 20399, 25776, -1, 20401, 20399, 25775, -1, 25776, 20397, 25777, -1, 20399, 20397, 25776, -1, 25777, 20388, 25778, -1, 20397, 20388, 25777, -1, 25778, 20379, 25781, -1, 20388, 20379, 25778, -1, 25790, 19834, 25793, -1, 25793, 20107, 25796, -1, 19834, 20107, 25793, -1, 25796, 20097, 25795, -1, 20107, 20097, 25796, -1, 25795, 20093, 25794, -1, 20097, 20093, 25795, -1, 25794, 20095, 25792, -1, 20093, 20095, 25794, -1, 20095, 20104, 25792, -1, 25792, 20111, 25791, -1, 20104, 20111, 25792, -1, 25780, 19878, 19877, -1, 25780, 25786, 19878, -1, 20314, 25791, 20111, -1, 25789, 25791, 20314, -1, 20314, 20323, 25789, -1, 25787, 20323, 25788, -1, 25789, 20323, 25787, -1, 25788, 20327, 25785, -1, 20323, 20327, 25788, -1, 25785, 20329, 25782, -1, 20327, 20329, 25785, -1, 25782, 20333, 25783, -1, 20329, 20333, 25782, -1, 25783, 20335, 25784, -1, 20333, 20335, 25783, -1, 25784, 20336, 25786, -1, 20335, 20336, 25784, -1, 20336, 19878, 25786, -1, 25797, 20380, 25798, -1, 25798, 20386, 25799, -1, 20380, 20386, 25798, -1, 25799, 20387, 25800, -1, 20386, 20387, 25799, -1, 25800, 20398, 25801, -1, 20387, 20398, 25800, -1, 25801, 20400, 25802, -1, 20398, 20400, 25801, -1, 20400, 20402, 25802, -1, 25802, 20404, 25803, -1, 20402, 20404, 25802, -1, 25803, 19876, 25804, -1, 20404, 19876, 25803, -1, 25805, 25806, 25807, -1, 25808, 25809, 25805, -1, 25805, 25810, 25806, -1, 25809, 25810, 25805, -1, 25809, 25811, 25810, -1, 25811, 25812, 25810, -1, 25811, 25813, 25812, -1, 25814, 25815, 25813, -1, 25816, 25817, 25818, -1, 25818, 25817, 25819, -1, 25819, 25817, 25815, -1, 25815, 25817, 25813, -1, 25813, 25817, 25812, -1, 25817, 25820, 25812, -1, 25821, 25822, 25823, -1, 25820, 25824, 25821, -1, 25822, 25824, 25825, -1, 25825, 25824, 25826, -1, 25821, 25824, 25822, -1, 25817, 25797, 25820, -1, 25820, 25797, 25824, -1, 25797, 25804, 25824, -1, 25797, 25798, 25804, -1, 25804, 25800, 25803, -1, 25799, 25800, 25798, -1, 25798, 25800, 25804, -1, 25803, 25801, 25802, -1, 25800, 25801, 25803, -1, 20380, 25817, 20183, -1, 25797, 25817, 20380, -1, 19766, 25804, 19876, -1, 25824, 25804, 19766, -1, 25813, 19831, 25814, -1, 25814, 20180, 25815, -1, 19831, 20180, 25814, -1, 25815, 20166, 25819, -1, 20180, 20166, 25815, -1, 25819, 20157, 25818, -1, 20166, 20157, 25819, -1, 25818, 20164, 25816, -1, 20157, 20164, 25818, -1, 25816, 20177, 25817, -1, 20164, 20177, 25816, -1, 20177, 20183, 25817, -1, 25824, 19760, 25826, -1, 19766, 19760, 25824, -1, 25826, 19751, 25825, -1, 19760, 19751, 25826, -1, 25825, 19745, 25822, -1, 19751, 19745, 25825, -1, 25822, 19739, 25823, -1, 19745, 19739, 25822, -1, 25823, 19732, 25821, -1, 19739, 19732, 25823, -1, 25821, 19727, 25820, -1, 19732, 19727, 25821, -1, 25813, 25811, 19830, -1, 25813, 19830, 19831, -1, 25812, 25820, 19727, -1, 25812, 19727, 19957, -1, 19957, 20278, 25812, -1, 25812, 20278, 25810, -1, 25810, 20270, 25806, -1, 20278, 20270, 25810, -1, 25807, 20266, 25805, -1, 25806, 20266, 25807, -1, 20270, 20266, 25806, -1, 25805, 20261, 25808, -1, 20266, 20261, 25805, -1, 25808, 20263, 25809, -1, 20261, 20263, 25808, -1, 25809, 20268, 25811, -1, 20263, 20268, 25809, -1, 20268, 19830, 25811, -1, 19959, 20355, 25827, -1, 25827, 20355, 25828, -1, 25828, 20349, 25829, -1, 20355, 20349, 25828, -1, 25830, 20341, 25831, -1, 25829, 20341, 25830, -1, 20349, 20341, 25829, -1, 25831, 20337, 25832, -1, 20341, 20337, 25831, -1, 25832, 20339, 25833, -1, 20337, 20339, 25832, -1, 25833, 20344, 25834, -1, 20339, 20344, 25833, -1, 25834, 20352, 25835, -1, 20344, 20352, 25834, -1, 20352, 19828, 25835, -1, 25832, 25833, 25831, -1, 25834, 25835, 25833, -1, 25831, 25835, 25830, -1, 25830, 25835, 25829, -1, 25829, 25835, 25828, -1, 25833, 25835, 25831, -1, 25835, 25827, 25828, -1, 25835, 25836, 25827, -1, 25837, 25838, 25839, -1, 25839, 25838, 25836, -1, 25840, 25841, 25838, -1, 25838, 25841, 25836, -1, 25836, 25842, 25827, -1, 25841, 25842, 25836, -1, 25842, 25843, 25827, -1, 25844, 25845, 25846, -1, 25845, 25847, 25848, -1, 25844, 25847, 25845, -1, 25843, 25849, 25844, -1, 25844, 25849, 25847, -1, 25842, 25850, 25843, -1, 25843, 25850, 25849, -1, 25850, 25851, 25849, -1, 25850, 25852, 25851, -1, 25852, 25853, 25851, -1, 25852, 25854, 25853, -1, 25853, 25855, 25856, -1, 25854, 25855, 25853, -1, 25855, 25857, 25856, -1, 19959, 25843, 19926, -1, 25827, 25843, 19959, -1, 25836, 25835, 19828, -1, 25836, 19828, 19829, -1, 25849, 19873, 25847, -1, 25847, 19973, 25848, -1, 19873, 19973, 25847, -1, 19973, 19965, 25848, -1, 25848, 19963, 25845, -1, 19965, 19963, 25848, -1, 25845, 19953, 25846, -1, 19963, 19953, 25845, -1, 25846, 19939, 25844, -1, 19953, 19939, 25846, -1, 25844, 19926, 25843, -1, 19939, 19926, 25844, -1, 25836, 20276, 25839, -1, 19829, 20276, 25836, -1, 25839, 20267, 25837, -1, 20276, 20267, 25839, -1, 25837, 20262, 25838, -1, 20267, 20262, 25837, -1, 25838, 20265, 25840, -1, 20262, 20265, 25838, -1, 25840, 20271, 25841, -1, 20265, 20271, 25840, -1, 25841, 19961, 25842, -1, 20271, 19961, 25841, -1, 19873, 25851, 19765, -1, 25849, 25851, 19873, -1, 25850, 25842, 19961, -1, 25850, 19961, 19729, -1, 19729, 19728, 25850, -1, 25852, 19728, 25854, -1, 25850, 19728, 25852, -1, 25854, 19733, 25855, -1, 19728, 19733, 25854, -1, 25855, 19740, 25857, -1, 19733, 19740, 25855, -1, 25857, 19746, 25856, -1, 19740, 19746, 25857, -1, 25856, 19752, 25853, -1, 19746, 19752, 25856, -1, 25853, 19759, 25851, -1, 19752, 19759, 25853, -1, 19759, 19765, 25851, -1, 19668, 19670, 25858, -1, 25859, 19670, 25860, -1, 25858, 19670, 25859, -1, 25860, 19674, 25861, -1, 19670, 19674, 25860, -1, 25861, 19675, 25862, -1, 19674, 19675, 25861, -1, 25862, 20406, 25863, -1, 19675, 20406, 25862, -1, 25863, 20408, 25864, -1, 20406, 20408, 25863, -1, 25864, 20411, 25865, -1, 20408, 20411, 25864, -1, 25865, 19685, 25866, -1, 20411, 19685, 25865, -1, 19685, 19686, 25866, -1, 25863, 25861, 25862, -1, 25865, 25866, 25864, -1, 25864, 25866, 25863, -1, 25863, 25866, 25861, -1, 25861, 25859, 25860, -1, 25866, 25859, 25861, -1, 25866, 25858, 25859, -1, 25866, 25867, 25858, -1, 25868, 25869, 25870, -1, 25869, 25871, 25870, -1, 25870, 25872, 25867, -1, 25871, 25872, 25870, -1, 25867, 25873, 25858, -1, 25872, 25873, 25867, -1, 25873, 25874, 25858, -1, 25875, 25876, 25877, -1, 25875, 25878, 25876, -1, 25875, 25879, 25878, -1, 25874, 25880, 25875, -1, 25875, 25880, 25879, -1, 25873, 25881, 25874, -1, 25874, 25881, 25880, -1, 25881, 25882, 25880, -1, 25881, 25883, 25882, -1, 25883, 25884, 25882, -1, 25882, 25885, 25886, -1, 25884, 25887, 25882, -1, 25885, 25888, 25889, -1, 25882, 25888, 25885, -1, 25887, 25888, 25882, -1, 19668, 25874, 19960, -1, 25858, 25874, 19668, -1, 25867, 25866, 19686, -1, 25867, 19686, 19827, -1, 19870, 20080, 25880, -1, 25879, 20080, 25878, -1, 25880, 20080, 25879, -1, 25878, 20074, 25876, -1, 20080, 20074, 25878, -1, 25876, 20068, 25877, -1, 20074, 20068, 25876, -1, 25877, 20062, 25875, -1, 20068, 20062, 25877, -1, 25875, 20055, 25874, -1, 20062, 20055, 25875, -1, 20055, 19960, 25874, -1, 25867, 20351, 25870, -1, 19827, 20351, 25867, -1, 25870, 20342, 25868, -1, 20351, 20342, 25870, -1, 25868, 20338, 25869, -1, 20342, 20338, 25868, -1, 25869, 20340, 25871, -1, 20338, 20340, 25869, -1, 25871, 20345, 25872, -1, 20340, 20345, 25871, -1, 25872, 19958, 25873, -1, 20345, 19958, 25872, -1, 25880, 25882, 19871, -1, 25880, 19871, 19870, -1, 19928, 25873, 19958, -1, 25881, 25873, 19928, -1, 19928, 19927, 25881, -1, 25883, 19927, 25884, -1, 25881, 19927, 25883, -1, 25884, 19940, 25887, -1, 19927, 19940, 25884, -1, 25887, 19954, 25888, -1, 19940, 19954, 25887, -1, 25888, 19964, 25889, -1, 19954, 19964, 25888, -1, 25889, 19966, 25885, -1, 19964, 19966, 25889, -1, 25885, 19972, 25886, -1, 19966, 19972, 25885, -1, 25886, 19979, 25882, -1, 19972, 19979, 25886, -1, 19979, 19871, 25882, -1, 19948, 20035, 25890, -1, 25891, 20035, 25892, -1, 25890, 20035, 25891, -1, 25892, 20038, 25893, -1, 20035, 20038, 25892, -1, 25893, 20051, 25894, -1, 20038, 20051, 25893, -1, 25894, 20057, 25895, -1, 20051, 20057, 25894, -1, 25895, 20066, 25896, -1, 20057, 20066, 25895, -1, 25896, 20073, 25897, -1, 20066, 20073, 25896, -1, 25897, 20079, 25898, -1, 20073, 20079, 25897, -1, 20079, 19869, 25898, -1, 25899, 25900, 25901, -1, 25902, 25903, 25899, -1, 25899, 25903, 25900, -1, 25904, 25905, 25903, -1, 25900, 25905, 25906, -1, 25903, 25905, 25900, -1, 25904, 25907, 25905, -1, 25904, 25908, 25907, -1, 25909, 25910, 25911, -1, 25911, 25910, 25912, -1, 25912, 25910, 25913, -1, 25913, 25910, 25914, -1, 25914, 25910, 25908, -1, 25908, 25910, 25907, -1, 25910, 25915, 25907, -1, 25916, 25917, 25918, -1, 25917, 25919, 25920, -1, 25915, 25921, 25916, -1, 25916, 25921, 25917, -1, 25917, 25921, 25919, -1, 25910, 25890, 25915, -1, 25915, 25890, 25921, -1, 25891, 25898, 25890, -1, 25890, 25898, 25921, -1, 25891, 25892, 25898, -1, 25898, 25896, 25897, -1, 25893, 25894, 25892, -1, 25892, 25894, 25898, -1, 25898, 25895, 25896, -1, 25894, 25895, 25898, -1, 25890, 25910, 19669, -1, 25890, 19669, 19948, -1, 25921, 25898, 19869, -1, 25921, 19869, 19866, -1, 19697, 19684, 25908, -1, 25908, 19684, 25914, -1, 25914, 19683, 25913, -1, 19684, 19683, 25914, -1, 25913, 20409, 25912, -1, 19683, 20409, 25913, -1, 25912, 20407, 25911, -1, 20409, 20407, 25912, -1, 25911, 20412, 25909, -1, 20407, 20412, 25911, -1, 25909, 19669, 25910, -1, 20412, 19669, 25909, -1, 25921, 19866, 25919, -1, 25919, 20203, 25920, -1, 19866, 20203, 25919, -1, 25920, 20193, 25917, -1, 20203, 20193, 25920, -1, 25917, 20171, 25918, -1, 20193, 20171, 25917, -1, 25918, 20159, 25916, -1, 20171, 20159, 25918, -1, 20159, 20152, 25916, -1, 25916, 19949, 25915, -1, 20152, 19949, 25916, -1, 25908, 25904, 19823, -1, 25908, 19823, 19697, -1, 25907, 25915, 19949, -1, 25907, 19949, 19859, -1, 19859, 19860, 25907, -1, 25905, 19860, 25906, -1, 25907, 19860, 25905, -1, 25906, 19862, 25900, -1, 19860, 19862, 25906, -1, 25900, 19832, 25901, -1, 19862, 19832, 25900, -1, 25901, 19804, 25899, -1, 19832, 19804, 25901, -1, 25899, 19806, 25902, -1, 19804, 19806, 25899, -1, 25902, 19818, 25903, -1, 19806, 19818, 25902, -1, 25903, 19844, 25904, -1, 19818, 19844, 25903, -1, 19844, 19823, 25904, -1, 25922, 19938, 25923, -1, 19938, 20022, 25923, -1, 25923, 20023, 25924, -1, 20022, 20023, 25923, -1, 25924, 20014, 25925, -1, 20023, 20014, 25924, -1, 25925, 20009, 25926, -1, 20014, 20009, 25925, -1, 25926, 20011, 25927, -1, 20009, 20011, 25926, -1, 25927, 20018, 25928, -1, 20011, 20018, 25927, -1, 25928, 20028, 25929, -1, 20018, 20028, 25928, -1, 25929, 20039, 25930, -1, 20028, 20039, 25929, -1, 25927, 25928, 25926, -1, 25926, 25924, 25925, -1, 25930, 25922, 25929, -1, 25929, 25922, 25928, -1, 25924, 25922, 25923, -1, 25928, 25922, 25926, -1, 25926, 25922, 25924, -1, 25930, 25931, 25922, -1, 25932, 25933, 25934, -1, 25934, 25933, 25935, -1, 25935, 25936, 25931, -1, 25933, 25936, 25935, -1, 25931, 25937, 25922, -1, 25936, 25937, 25931, -1, 25937, 25938, 25922, -1, 25938, 25939, 25940, -1, 25938, 25941, 25939, -1, 25938, 25942, 25941, -1, 25938, 25943, 25942, -1, 25937, 25944, 25938, -1, 25938, 25944, 25943, -1, 25945, 25946, 25944, -1, 25944, 25946, 25943, -1, 25947, 25948, 25945, -1, 25945, 25948, 25946, -1, 25946, 25949, 25950, -1, 25946, 25951, 25949, -1, 25948, 25951, 25946, -1, 25951, 25952, 25949, -1, 19938, 25938, 19951, -1, 25922, 25938, 19938, -1, 25931, 25930, 20039, -1, 25931, 20039, 19888, -1, 19863, 20308, 25943, -1, 25943, 20308, 25942, -1, 25942, 20304, 25941, -1, 20308, 20304, 25942, -1, 25941, 20300, 25939, -1, 20304, 20300, 25941, -1, 25939, 20294, 25940, -1, 20300, 20294, 25939, -1, 25940, 19951, 25938, -1, 20294, 19951, 25940, -1, 25935, 19874, 25934, -1, 25931, 19874, 25935, -1, 19888, 19874, 25931, -1, 25934, 19842, 25932, -1, 19874, 19842, 25934, -1, 25932, 19813, 25933, -1, 19842, 19813, 25932, -1, 25933, 19805, 25936, -1, 19813, 19805, 25933, -1, 19805, 19824, 25936, -1, 25936, 19857, 25937, -1, 19824, 19857, 25936, -1, 19863, 25946, 19864, -1, 25943, 25946, 19863, -1, 25944, 25937, 19857, -1, 25944, 19857, 19950, -1, 19950, 20137, 25944, -1, 25945, 20137, 25947, -1, 25944, 20137, 25945, -1, 25947, 20141, 25948, -1, 20137, 20141, 25947, -1, 25948, 20153, 25951, -1, 20141, 20153, 25948, -1, 25951, 20155, 25952, -1, 20153, 20155, 25951, -1, 20155, 20169, 25952, -1, 25952, 20190, 25949, -1, 20169, 20190, 25952, -1, 25949, 20201, 25950, -1, 20190, 20201, 25949, -1, 25950, 19864, 25946, -1, 20201, 19864, 25950, -1, 19796, 20383, 25953, -1, 25953, 20383, 25954, -1, 25954, 20377, 25955, -1, 20383, 20377, 25954, -1, 25955, 20372, 25956, -1, 20377, 20372, 25955, -1, 25956, 20366, 25957, -1, 20372, 20366, 25956, -1, 25957, 19942, 25958, -1, 20366, 19942, 25957, -1, 25959, 25960, 25961, -1, 25959, 25962, 25960, -1, 25963, 25964, 25965, -1, 25965, 25964, 25959, -1, 25964, 25966, 25959, -1, 25959, 25966, 25962, -1, 25964, 25967, 25966, -1, 25964, 25968, 25967, -1, 25969, 25970, 25971, -1, 25971, 25970, 25972, -1, 25972, 25970, 25973, -1, 25973, 25970, 25968, -1, 25968, 25970, 25967, -1, 25970, 25958, 25967, -1, 25957, 25955, 25956, -1, 25957, 25954, 25955, -1, 25958, 25953, 25957, -1, 25957, 25953, 25954, -1, 25970, 25974, 25958, -1, 25958, 25974, 25953, -1, 25974, 25975, 25953, -1, 25976, 25977, 25974, -1, 25974, 25978, 25975, -1, 25977, 25979, 25974, -1, 25979, 25980, 25974, -1, 25978, 25981, 25982, -1, 25974, 25981, 25978, -1, 25980, 25981, 25974, -1, 19796, 25975, 19795, -1, 25953, 25975, 19796, -1, 25967, 25958, 19942, -1, 25967, 19942, 19941, -1, 25974, 19936, 25976, -1, 25976, 20289, 25977, -1, 19936, 20289, 25976, -1, 25977, 20293, 25979, -1, 20289, 20293, 25977, -1, 25979, 20295, 25980, -1, 20293, 20295, 25979, -1, 25980, 20299, 25981, -1, 20295, 20299, 25980, -1, 25981, 20303, 25982, -1, 20299, 20303, 25981, -1, 20303, 20307, 25982, -1, 25982, 20311, 25978, -1, 20307, 20311, 25982, -1, 25978, 19795, 25975, -1, 20311, 19795, 25978, -1, 25967, 20133, 25966, -1, 19941, 20133, 25967, -1, 25966, 20134, 25962, -1, 20133, 20134, 25966, -1, 25962, 20098, 25960, -1, 20134, 20098, 25962, -1, 25960, 20090, 25961, -1, 20098, 20090, 25960, -1, 25961, 20089, 25959, -1, 20090, 20089, 25961, -1, 25959, 20088, 25965, -1, 20089, 20088, 25959, -1, 25965, 20086, 25963, -1, 20088, 20086, 25965, -1, 25963, 20085, 25964, -1, 20086, 20085, 25963, -1, 25974, 25970, 19937, -1, 25974, 19937, 19936, -1, 25968, 25964, 20085, -1, 25968, 20085, 20040, -1, 25968, 20040, 25973, -1, 25973, 20027, 25972, -1, 20040, 20027, 25973, -1, 25972, 20017, 25971, -1, 20027, 20017, 25972, -1, 25971, 20010, 25969, -1, 20017, 20010, 25971, -1, 25969, 20015, 25970, -1, 20010, 20015, 25969, -1, 20015, 19937, 25970, -1, 19704, 19701, 25715, -1, 25715, 19701, 25714, -1, 25714, 19691, 25713, -1, 19701, 19691, 25714, -1, 25713, 19680, 25711, -1, 19691, 19680, 25713, -1, 25711, 19682, 25712, -1, 19680, 19682, 25711, -1, 25712, 19671, 25710, -1, 19682, 19671, 25712, -1, 19704, 25718, 19807, -1, 25715, 25718, 19704, -1, 25705, 25710, 19671, -1, 25705, 19671, 19945, -1, 25716, 19943, 25717, -1, 25717, 20346, 25721, -1, 19943, 20346, 25717, -1, 25721, 20356, 25724, -1, 20346, 20356, 25721, -1, 25724, 20359, 25722, -1, 20356, 20359, 25724, -1, 25722, 20367, 25723, -1, 20359, 20367, 25722, -1, 25723, 20373, 25719, -1, 20367, 20373, 25723, -1, 25719, 20378, 25720, -1, 20373, 20378, 25719, -1, 25720, 20384, 25718, -1, 20378, 20384, 25720, -1, 20384, 19807, 25718, -1, 19945, 20221, 25705, -1, 25704, 20221, 25702, -1, 25705, 20221, 25704, -1, 25702, 20222, 25703, -1, 20221, 20222, 25702, -1, 20222, 20224, 25703, -1, 25703, 20225, 25698, -1, 20224, 20225, 25703, -1, 25698, 20226, 25699, -1, 20225, 20226, 25698, -1, 25699, 20227, 25697, -1, 20226, 20227, 25699, -1, 25697, 20228, 25700, -1, 20227, 20228, 25697, -1, 25700, 20229, 25701, -1, 20228, 20229, 25700, -1, 25701, 20220, 20416, -1, 20229, 20220, 25701, -1, 19943, 25709, 19944, -1, 25716, 25709, 19943, -1, 20127, 20419, 20146, -1, 25706, 20419, 20127, -1, 20127, 20126, 25706, -1, 25706, 20126, 25707, -1, 25707, 20131, 25708, -1, 20126, 20131, 25707, -1, 25708, 19944, 25709, -1, 20131, 19944, 25708, -1, 25983, 25984, 19952, -1, 19952, 25984, 19736, -1, 25985, 25986, 25984, -1, 25985, 25987, 25986, -1, 25985, 25988, 25987, -1, 25985, 25989, 25988, -1, 25990, 25991, 25992, -1, 25993, 25990, 25992, -1, 25994, 25995, 25993, -1, 25994, 25993, 25992, -1, 25996, 25997, 25994, -1, 25996, 25994, 25992, -1, 25998, 25999, 25996, -1, 25998, 25992, 25985, -1, 25998, 25985, 25984, -1, 25998, 25996, 25992, -1, 26000, 25983, 26001, -1, 26002, 26000, 26003, -1, 26002, 25983, 26000, -1, 26004, 26002, 26005, -1, 26006, 26004, 26007, -1, 26006, 25983, 26002, -1, 26006, 26002, 26004, -1, 26008, 25983, 26006, -1, 26009, 25983, 26008, -1, 26010, 25983, 26009, -1, 26011, 25983, 26010, -1, 26012, 25983, 26011, -1, 26013, 25984, 25983, -1, 26013, 25998, 25984, -1, 26014, 26015, 26013, -1, 26014, 25983, 26012, -1, 26014, 26013, 25983, -1, 26016, 26015, 26014, -1, 25985, 19812, 25989, -1, 25989, 19770, 25988, -1, 19812, 19770, 25989, -1, 25988, 19764, 25987, -1, 19770, 19764, 25988, -1, 25987, 19761, 25986, -1, 19764, 19761, 25987, -1, 19761, 19755, 25986, -1, 25986, 19736, 25984, -1, 19755, 19736, 25986, -1, 25983, 20319, 26001, -1, 19952, 20319, 25983, -1, 26001, 20320, 26000, -1, 20319, 20320, 26001, -1, 26000, 20321, 26003, -1, 20320, 20321, 26000, -1, 26003, 20324, 26002, -1, 20321, 20324, 26003, -1, 26002, 20316, 26005, -1, 20324, 20316, 26002, -1, 26005, 20277, 26004, -1, 20316, 20277, 26005, -1, 26007, 20273, 26006, -1, 26004, 20273, 26007, -1, 20277, 20273, 26004, -1, 20273, 20272, 26006, -1, 26006, 20269, 26008, -1, 20272, 20269, 26006, -1, 25985, 19709, 19812, -1, 25985, 25992, 19709, -1, 20259, 26008, 20269, -1, 26009, 26008, 20259, -1, 25998, 19946, 25999, -1, 25999, 20405, 25996, -1, 19946, 20405, 25999, -1, 25996, 20410, 25997, -1, 20405, 20410, 25996, -1, 25997, 19673, 25994, -1, 20410, 19673, 25997, -1, 25994, 19672, 25995, -1, 19673, 19672, 25994, -1, 25995, 19681, 25993, -1, 19672, 19681, 25995, -1, 25993, 19692, 25990, -1, 19681, 19692, 25993, -1, 25990, 19696, 25991, -1, 19692, 19696, 25990, -1, 25991, 19705, 25992, -1, 19696, 19705, 25991, -1, 19705, 19709, 25992, -1, 26009, 20243, 26010, -1, 20259, 20243, 26009, -1, 26010, 20231, 26011, -1, 20243, 20231, 26010, -1, 26011, 20230, 26012, -1, 20231, 20230, 26011, -1, 25998, 19955, 19946, -1, 25998, 26013, 19955, -1, 20215, 26012, 20230, -1, 26014, 26012, 20215, -1, 26014, 20215, 26016, -1, 26016, 20212, 26015, -1, 20215, 20212, 26016, -1, 26015, 20217, 26013, -1, 20212, 20217, 26015, -1, 20217, 19955, 26013, -1, 19816, 20389, 26017, -1, 26017, 20389, 26018, -1, 26018, 20390, 26019, -1, 20389, 20390, 26018, -1, 26019, 20391, 26020, -1, 20390, 20391, 26019, -1, 26020, 20392, 26021, -1, 20391, 20392, 26020, -1, 26022, 20393, 26023, -1, 26021, 20393, 26022, -1, 20392, 20393, 26021, -1, 26023, 20394, 26024, -1, 20393, 20394, 26023, -1, 26024, 20395, 26025, -1, 20394, 20395, 26024, -1, 26025, 20396, 26026, -1, 20395, 20396, 26025, -1, 20396, 20343, 26026, -1, 26023, 26024, 26022, -1, 26024, 26025, 26022, -1, 26022, 26020, 26021, -1, 26022, 26019, 26020, -1, 26026, 26017, 26025, -1, 26019, 26017, 26018, -1, 26025, 26017, 26022, -1, 26022, 26017, 26019, -1, 26026, 26027, 26017, -1, 26028, 26029, 26030, -1, 26030, 26029, 26031, -1, 26031, 26029, 26032, -1, 26032, 26029, 26027, -1, 26027, 26029, 26017, -1, 26029, 26033, 26017, -1, 26033, 26034, 26035, -1, 26035, 26034, 26036, -1, 26036, 26034, 26037, -1, 26037, 26034, 26038, -1, 26029, 26039, 26033, -1, 26033, 26039, 26034, -1, 26040, 26041, 26039, -1, 26039, 26042, 26034, -1, 26041, 26043, 26039, -1, 26039, 26044, 26042, -1, 26043, 26045, 26039, -1, 26039, 26046, 26044, -1, 26045, 26047, 26039, -1, 26047, 26048, 26039, -1, 26039, 26048, 26046, -1, 26017, 26033, 19815, -1, 26017, 19815, 19816, -1, 26027, 26026, 20343, -1, 26027, 20343, 20331, -1, 26034, 19797, 26038, -1, 19797, 19798, 26038, -1, 26038, 19799, 26037, -1, 19798, 19799, 26038, -1, 26037, 19800, 26036, -1, 19799, 19800, 26037, -1, 26036, 19801, 26035, -1, 19800, 19801, 26036, -1, 26035, 19815, 26033, -1, 19801, 19815, 26035, -1, 26027, 20331, 26032, -1, 26032, 20328, 26031, -1, 20331, 20328, 26032, -1, 26031, 20325, 26030, -1, 20328, 20325, 26031, -1, 26030, 20318, 26028, -1, 20325, 20318, 26030, -1, 20318, 20317, 26028, -1, 26028, 19962, 26029, -1, 20317, 19962, 26028, -1, 19797, 26042, 19802, -1, 26034, 26042, 19797, -1, 19738, 26029, 19962, -1, 26039, 26029, 19738, -1, 26039, 19738, 26040, -1, 26040, 19737, 26041, -1, 19738, 19737, 26040, -1, 26041, 19741, 26043, -1, 19737, 19741, 26041, -1, 26043, 19742, 26045, -1, 19741, 19742, 26043, -1, 26045, 19749, 26047, -1, 19742, 19749, 26045, -1, 26047, 19753, 26048, -1, 19749, 19753, 26047, -1, 26048, 19757, 26046, -1, 19753, 19757, 26048, -1, 26046, 19763, 26044, -1, 19757, 19763, 26046, -1, 26044, 19768, 26042, -1, 19763, 19768, 26044, -1, 19768, 19802, 26042, -1, 26049, 19004, 26050, -1, 19004, 18978, 26050, -1, 26050, 18979, 26051, -1, 18978, 18979, 26050, -1, 26051, 18980, 26052, -1, 18979, 18980, 26051, -1, 26052, 18983, 26053, -1, 18980, 18983, 26052, -1, 26053, 18976, 26054, -1, 18983, 18976, 26053, -1, 26055, 26056, 26057, -1, 26055, 26058, 26056, -1, 26055, 26059, 26058, -1, 26055, 26060, 26059, -1, 26055, 26061, 26060, -1, 26055, 26062, 26061, -1, 26055, 26063, 26062, -1, 26055, 26064, 26063, -1, 26054, 26064, 26055, -1, 26052, 26053, 26054, -1, 26051, 26052, 26054, -1, 26049, 26050, 26051, -1, 26049, 26054, 26055, -1, 26049, 26051, 26054, -1, 26065, 26049, 26055, -1, 26066, 26065, 26067, -1, 26068, 26065, 26066, -1, 26069, 26065, 26068, -1, 26070, 26065, 26069, -1, 26071, 26049, 26065, -1, 26071, 26065, 26070, -1, 26072, 26073, 26071, -1, 26074, 26071, 26070, -1, 26075, 26072, 26071, -1, 26076, 26071, 26074, -1, 26077, 26075, 26071, -1, 26078, 26071, 26076, -1, 26079, 26077, 26071, -1, 26080, 26079, 26071, -1, 26080, 26071, 26078, -1, 26049, 19209, 19004, -1, 26049, 26071, 19209, -1, 26064, 18976, 18949, -1, 26064, 26054, 18976, -1, 19304, 19311, 26074, -1, 26074, 19311, 26076, -1, 26076, 19349, 26078, -1, 19311, 19349, 26076, -1, 26080, 19342, 26079, -1, 26078, 19342, 26080, -1, 19349, 19342, 26078, -1, 26079, 19337, 26077, -1, 19342, 19337, 26079, -1, 26077, 19338, 26075, -1, 19337, 19338, 26077, -1, 26075, 19339, 26072, -1, 19338, 19339, 26075, -1, 26072, 19340, 26073, -1, 19339, 19340, 26072, -1, 26073, 19341, 26071, -1, 19340, 19341, 26073, -1, 19341, 19209, 26071, -1, 26064, 18942, 26063, -1, 18949, 18942, 26064, -1, 26063, 18935, 26062, -1, 18942, 18935, 26063, -1, 26062, 18934, 26061, -1, 18935, 18934, 26062, -1, 26061, 18933, 26060, -1, 18934, 18933, 26061, -1, 26060, 18939, 26059, -1, 18933, 18939, 26060, -1, 26059, 18944, 26058, -1, 18939, 18944, 26059, -1, 26058, 18953, 26056, -1, 18944, 18953, 26058, -1, 26056, 18956, 26057, -1, 18953, 18956, 26056, -1, 26057, 18961, 26055, -1, 18956, 18961, 26057, -1, 26074, 26070, 19304, -1, 19304, 26070, 19294, -1, 19286, 26055, 18961, -1, 26065, 26055, 19286, -1, 26065, 19286, 26067, -1, 26067, 19287, 26066, -1, 19286, 19287, 26067, -1, 26066, 19288, 26068, -1, 19287, 19288, 26066, -1, 26068, 19289, 26069, -1, 19288, 19289, 26068, -1, 26069, 19293, 26070, -1, 19289, 19293, 26069, -1, 19293, 19294, 26070, -1, 19069, 26081, 19188, -1, 26082, 26081, 19069, -1, 26083, 26084, 26085, -1, 26086, 26083, 26087, -1, 26088, 26084, 26083, -1, 26088, 26083, 26086, -1, 26089, 26084, 26088, -1, 26090, 26084, 26089, -1, 26091, 26092, 26090, -1, 26082, 26090, 26089, -1, 26082, 26091, 26090, -1, 26093, 26082, 26089, -1, 26094, 26095, 26096, -1, 26094, 26097, 26095, -1, 26098, 26093, 26097, -1, 26098, 26097, 26094, -1, 26081, 26082, 26093, -1, 26081, 26093, 26098, -1, 26099, 26100, 26081, -1, 26099, 26081, 26098, -1, 26101, 26102, 26100, -1, 26103, 26099, 26104, -1, 26105, 26106, 26101, -1, 26105, 26101, 26100, -1, 26105, 26100, 26099, -1, 26107, 26105, 26099, -1, 26107, 26099, 26103, -1, 26082, 19069, 26091, -1, 26091, 19070, 26092, -1, 19069, 19070, 26091, -1, 19070, 19073, 26092, -1, 26092, 19048, 26090, -1, 19073, 19048, 26092, -1, 26099, 19370, 26104, -1, 26104, 19423, 26103, -1, 19370, 19423, 26104, -1, 26103, 19421, 26107, -1, 19423, 19421, 26103, -1, 26107, 19419, 26105, -1, 19421, 19419, 26107, -1, 26105, 19412, 26106, -1, 19419, 19412, 26105, -1, 26106, 19413, 26101, -1, 19412, 19413, 26106, -1, 26101, 19414, 26102, -1, 19413, 19414, 26101, -1, 26102, 19415, 26100, -1, 19414, 19415, 26102, -1, 26100, 19416, 26081, -1, 19415, 19416, 26100, -1, 19416, 19188, 26081, -1, 26084, 19048, 19043, -1, 26084, 26090, 19048, -1, 26099, 26098, 19370, -1, 19370, 26098, 19361, -1, 19043, 26108, 26084, -1, 26108, 26109, 26084, -1, 26109, 26110, 26084, -1, 19039, 26111, 19043, -1, 19031, 26111, 19039, -1, 19023, 26111, 19031, -1, 19043, 26111, 26108, -1, 19022, 26112, 19023, -1, 19023, 26112, 26111, -1, 26111, 26112, 26108, -1, 26108, 26112, 26109, -1, 26084, 26113, 18998, -1, 19010, 26113, 19022, -1, 19000, 26113, 19010, -1, 18998, 26113, 19000, -1, 26112, 26113, 26109, -1, 19022, 26113, 26112, -1, 26109, 26113, 26110, -1, 26110, 26113, 26084, -1, 26093, 19208, 26097, -1, 19208, 19343, 26097, -1, 26097, 19350, 26095, -1, 19343, 19350, 26097, -1, 26095, 19355, 26096, -1, 19350, 19355, 26095, -1, 26094, 19358, 26098, -1, 26096, 19358, 26094, -1, 19355, 19358, 26096, -1, 19358, 19361, 26098, -1, 26084, 19005, 26085, -1, 18998, 19005, 26084, -1, 26085, 19011, 26083, -1, 19005, 19011, 26085, -1, 26087, 19029, 26086, -1, 26083, 19029, 26087, -1, 19011, 19029, 26083, -1, 26086, 19037, 26088, -1, 19029, 19037, 26086, -1, 19037, 19046, 26088, -1, 26088, 19047, 26089, -1, 19046, 19047, 26088, -1, 26093, 19047, 19208, -1, 26093, 26089, 19047, -1, 26114, 19189, 26115, -1, 19189, 19219, 26115, -1, 26115, 19221, 26116, -1, 19219, 19221, 26115, -1, 26116, 19226, 26117, -1, 19221, 19226, 26116, -1, 26118, 19214, 26119, -1, 26117, 19214, 26118, -1, 19226, 19214, 26117, -1, 19214, 19210, 26119, -1, 26120, 26121, 26122, -1, 26120, 26123, 26121, -1, 26124, 26125, 26123, -1, 26123, 26125, 26121, -1, 26126, 26127, 26128, -1, 26127, 26129, 26128, -1, 26130, 26131, 26129, -1, 26131, 26132, 26129, -1, 26129, 26132, 26128, -1, 26133, 26134, 26132, -1, 26132, 26134, 26128, -1, 26128, 26135, 26125, -1, 26134, 26135, 26128, -1, 26125, 26135, 26121, -1, 26136, 26137, 26138, -1, 26136, 26139, 26137, -1, 26136, 26140, 26139, -1, 26136, 26141, 26140, -1, 26136, 26142, 26141, -1, 26136, 26143, 26142, -1, 26143, 26144, 26145, -1, 26136, 26144, 26143, -1, 26136, 26119, 26144, -1, 26119, 26114, 26118, -1, 26121, 26114, 26136, -1, 26135, 26114, 26121, -1, 26136, 26114, 26119, -1, 26114, 26117, 26118, -1, 26115, 26116, 26114, -1, 26114, 26116, 26117, -1, 19189, 26135, 19181, -1, 26114, 26135, 19189, -1, 19167, 26119, 19210, -1, 26144, 26119, 19167, -1, 26128, 19444, 26126, -1, 26126, 19492, 26127, -1, 19444, 19492, 26126, -1, 26127, 19489, 26129, -1, 19492, 19489, 26127, -1, 26129, 19484, 26130, -1, 19489, 19484, 26129, -1, 26130, 19482, 26131, -1, 19484, 19482, 26130, -1, 19482, 19477, 26131, -1, 26131, 19478, 26132, -1, 19477, 19478, 26131, -1, 26132, 19479, 26133, -1, 19478, 19479, 26132, -1, 26133, 19481, 26134, -1, 19479, 19481, 26133, -1, 26134, 19181, 26135, -1, 19481, 19181, 26134, -1, 26144, 19128, 26145, -1, 19167, 19128, 26144, -1, 26145, 19113, 26143, -1, 19128, 19113, 26145, -1, 26143, 19098, 26142, -1, 19113, 19098, 26143, -1, 26142, 19108, 26141, -1, 19098, 19108, 26142, -1, 26141, 19118, 26140, -1, 19108, 19118, 26141, -1, 26140, 19151, 26139, -1, 19118, 19151, 26140, -1, 26139, 19172, 26137, -1, 19151, 19172, 26139, -1, 26137, 19185, 26138, -1, 19172, 19185, 26137, -1, 26138, 19187, 26136, -1, 19185, 19187, 26138, -1, 26128, 26125, 19429, -1, 26128, 19429, 19444, -1, 26121, 26136, 19187, -1, 26121, 19187, 19186, -1, 26121, 19186, 26122, -1, 26122, 19417, 26120, -1, 19186, 19417, 26122, -1, 26120, 19420, 26123, -1, 19417, 19420, 26120, -1, 26123, 19422, 26124, -1, 19420, 19422, 26123, -1, 26124, 19426, 26125, -1, 19422, 19426, 26124, -1, 19426, 19429, 26125, -1, 19182, 19254, 26146, -1, 26147, 19254, 26148, -1, 26146, 19254, 26147, -1, 26148, 19256, 26149, -1, 19254, 19256, 26148, -1, 26149, 19259, 26150, -1, 19256, 19259, 26149, -1, 26150, 19265, 26151, -1, 19259, 19265, 26150, -1, 19265, 19141, 26151, -1, 26152, 26153, 26154, -1, 26154, 26153, 26155, -1, 26152, 26156, 26153, -1, 26156, 26157, 26153, -1, 26158, 26159, 26160, -1, 26160, 26161, 26157, -1, 26162, 26161, 26163, -1, 26163, 26161, 26164, -1, 26164, 26161, 26165, -1, 26165, 26161, 26166, -1, 26166, 26161, 26159, -1, 26159, 26161, 26160, -1, 26157, 26161, 26153, -1, 26167, 26168, 26169, -1, 26167, 26170, 26168, -1, 26167, 26171, 26170, -1, 26167, 26172, 26171, -1, 26167, 26173, 26172, -1, 26167, 26174, 26173, -1, 26167, 26175, 26174, -1, 26167, 26176, 26175, -1, 26167, 26151, 26176, -1, 26153, 26146, 26167, -1, 26161, 26146, 26153, -1, 26167, 26146, 26151, -1, 26151, 26149, 26150, -1, 26151, 26147, 26149, -1, 26146, 26147, 26151, -1, 26147, 26148, 26149, -1, 26146, 26161, 19183, -1, 26146, 19183, 19182, -1, 19247, 26151, 19141, -1, 26176, 26151, 19247, -1, 26160, 19067, 26158, -1, 26158, 19563, 26159, -1, 19067, 19563, 26158, -1, 26159, 19560, 26166, -1, 19563, 19560, 26159, -1, 26166, 19540, 26165, -1, 19560, 19540, 26166, -1, 26165, 19534, 26164, -1, 19540, 19534, 26165, -1, 26164, 19535, 26163, -1, 19534, 19535, 26164, -1, 26163, 19536, 26162, -1, 19535, 19536, 26163, -1, 26162, 19537, 26161, -1, 19536, 19537, 26162, -1, 19537, 19183, 26161, -1, 26176, 19238, 26175, -1, 19247, 19238, 26176, -1, 26175, 19232, 26174, -1, 19238, 19232, 26175, -1, 26174, 19225, 26173, -1, 19232, 19225, 26174, -1, 26173, 19220, 26172, -1, 19225, 19220, 26173, -1, 26172, 19227, 26171, -1, 19220, 19227, 26172, -1, 26171, 19237, 26170, -1, 19227, 19237, 26171, -1, 26170, 19243, 26168, -1, 19237, 19243, 26170, -1, 26168, 19249, 26169, -1, 19243, 19249, 26168, -1, 26169, 19180, 26167, -1, 19249, 19180, 26169, -1, 19067, 26157, 19496, -1, 26160, 26157, 19067, -1, 19179, 26167, 19180, -1, 26153, 26167, 19179, -1, 26153, 19179, 26155, -1, 19179, 19483, 26155, -1, 26155, 19485, 26154, -1, 19483, 19485, 26155, -1, 26154, 19487, 26152, -1, 19485, 19487, 26154, -1, 26152, 19491, 26156, -1, 19487, 19491, 26152, -1, 26156, 19496, 26157, -1, 19491, 19496, 26156, -1, 19199, 19324, 26177, -1, 26177, 19324, 26178, -1, 26178, 19319, 26179, -1, 19324, 19319, 26178, -1, 26179, 19321, 26180, -1, 19319, 19321, 26179, -1, 26181, 19328, 26182, -1, 26180, 19328, 26181, -1, 19321, 19328, 26180, -1, 19328, 19136, 26182, -1, 26183, 26184, 26185, -1, 26185, 26184, 26186, -1, 26186, 26184, 26187, -1, 26187, 26184, 26188, -1, 26189, 26190, 26184, -1, 26191, 26190, 26192, -1, 26192, 26190, 26193, -1, 26193, 26190, 26194, -1, 26194, 26190, 26195, -1, 26195, 26190, 26196, -1, 26196, 26190, 26197, -1, 26197, 26190, 26189, -1, 26184, 26190, 26188, -1, 26198, 26199, 26200, -1, 26199, 26201, 26202, -1, 26198, 26201, 26199, -1, 26198, 26203, 26201, -1, 26198, 26204, 26203, -1, 26205, 26206, 26198, -1, 26198, 26206, 26204, -1, 26205, 26182, 26206, -1, 26188, 26177, 26205, -1, 26190, 26177, 26188, -1, 26205, 26177, 26182, -1, 26182, 26178, 26181, -1, 26181, 26178, 26180, -1, 26177, 26178, 26182, -1, 26178, 26179, 26180, -1, 26177, 26190, 19192, -1, 26177, 19192, 19199, -1, 19137, 26182, 19136, -1, 26206, 26182, 19137, -1, 19072, 19618, 26189, -1, 26189, 19618, 26197, -1, 26197, 19615, 26196, -1, 19618, 19615, 26197, -1, 26196, 19610, 26195, -1, 19615, 19610, 26196, -1, 26195, 19604, 26194, -1, 19610, 19604, 26195, -1, 26194, 19600, 26193, -1, 19604, 19600, 26194, -1, 26193, 19601, 26192, -1, 19600, 19601, 26193, -1, 26192, 19602, 26191, -1, 19601, 19602, 26192, -1, 26191, 19192, 26190, -1, 19602, 19192, 26191, -1, 26206, 19137, 26204, -1, 26204, 19264, 26203, -1, 19137, 19264, 26204, -1, 26203, 19258, 26201, -1, 19264, 19258, 26203, -1, 26201, 19255, 26202, -1, 19258, 19255, 26201, -1, 26202, 19257, 26199, -1, 19255, 19257, 26202, -1, 26199, 19260, 26200, -1, 19257, 19260, 26199, -1, 26200, 19266, 26198, -1, 19260, 19266, 26200, -1, 19266, 19267, 26198, -1, 26198, 19184, 26205, -1, 19267, 19184, 26198, -1, 26189, 26184, 19068, -1, 26189, 19068, 19072, -1, 19196, 26205, 19184, -1, 26188, 26205, 19196, -1, 19196, 19541, 26188, -1, 26188, 19541, 26187, -1, 26187, 19561, 26186, -1, 19541, 19561, 26187, -1, 26186, 19564, 26185, -1, 19561, 19564, 26186, -1, 26185, 19568, 26183, -1, 19564, 19568, 26185, -1, 26183, 19068, 26184, -1, 19568, 19068, 26183, -1, 26207, 19193, 26208, -1, 26208, 19388, 26209, -1, 19193, 19388, 26208, -1, 26209, 19383, 26210, -1, 19388, 19383, 26209, -1, 26210, 19385, 26211, -1, 19383, 19385, 26210, -1, 26211, 19392, 26212, -1, 19385, 19392, 26211, -1, 26212, 19401, 26213, -1, 19392, 19401, 26212, -1, 19401, 19132, 26213, -1, 26214, 26215, 26216, -1, 26217, 26218, 26215, -1, 26216, 26218, 26219, -1, 26215, 26218, 26216, -1, 26220, 26221, 26222, -1, 26221, 26223, 26222, -1, 26224, 26225, 26223, -1, 26226, 26227, 26225, -1, 26225, 26227, 26223, -1, 26223, 26227, 26222, -1, 26222, 26228, 26218, -1, 26218, 26228, 26219, -1, 26227, 26228, 26222, -1, 26229, 26230, 26231, -1, 26230, 26232, 26233, -1, 26229, 26232, 26230, -1, 26229, 26234, 26232, -1, 26229, 26235, 26234, -1, 26236, 26237, 26229, -1, 26229, 26237, 26235, -1, 26236, 26213, 26237, -1, 26219, 26207, 26236, -1, 26228, 26207, 26219, -1, 26236, 26207, 26213, -1, 26213, 26211, 26212, -1, 26213, 26208, 26211, -1, 26207, 26208, 26213, -1, 26208, 26210, 26211, -1, 26208, 26209, 26210, -1, 19193, 26228, 19194, -1, 26207, 26228, 19193, -1, 26237, 26213, 19132, -1, 26237, 19132, 19135, -1, 26222, 18937, 26220, -1, 26220, 18930, 26221, -1, 18937, 18930, 26220, -1, 26221, 18922, 26223, -1, 18930, 18922, 26221, -1, 26223, 18924, 26224, -1, 18922, 18924, 26223, -1, 26224, 19666, 26225, -1, 18924, 19666, 26224, -1, 26225, 19660, 26226, -1, 19666, 19660, 26225, -1, 26226, 19661, 26227, -1, 19660, 19661, 26226, -1, 26227, 19662, 26228, -1, 19661, 19662, 26227, -1, 19662, 19194, 26228, -1, 26237, 19333, 26235, -1, 19135, 19333, 26237, -1, 26235, 19327, 26234, -1, 19333, 19327, 26235, -1, 26234, 19320, 26232, -1, 19327, 19320, 26234, -1, 26232, 19325, 26233, -1, 19320, 19325, 26232, -1, 26233, 19332, 26230, -1, 19325, 19332, 26233, -1, 26231, 19335, 26229, -1, 26230, 19335, 26231, -1, 19332, 19335, 26230, -1, 19335, 19336, 26229, -1, 26229, 19191, 26236, -1, 19336, 19191, 26229, -1, 26222, 26218, 19074, -1, 26222, 19074, 18937, -1, 26219, 26236, 19191, -1, 26219, 19191, 19190, -1, 19190, 19605, 26219, -1, 26219, 19605, 26216, -1, 26216, 19606, 26214, -1, 19605, 19606, 26216, -1, 26214, 19611, 26215, -1, 19606, 19611, 26214, -1, 26215, 19619, 26217, -1, 19611, 19619, 26215, -1, 26217, 19074, 26218, -1, 19619, 19074, 26217, -1, 26238, 19205, 26239, -1, 26239, 19463, 26240, -1, 19205, 19463, 26239, -1, 26240, 19458, 26241, -1, 19463, 19458, 26240, -1, 26241, 19460, 26242, -1, 19458, 19460, 26241, -1, 26242, 19466, 26243, -1, 19460, 19466, 26242, -1, 26243, 19471, 26244, -1, 19466, 19471, 26243, -1, 19471, 19130, 26244, -1, 26245, 26246, 26247, -1, 26248, 26249, 26246, -1, 26248, 26246, 26245, -1, 26250, 26251, 26249, -1, 26250, 26252, 26251, -1, 26250, 26249, 26248, -1, 26253, 26252, 26250, -1, 26244, 26252, 26253, -1, 26242, 26243, 26244, -1, 26240, 26241, 26242, -1, 26238, 26239, 26240, -1, 26238, 26242, 26244, -1, 26238, 26244, 26253, -1, 26238, 26240, 26242, -1, 26254, 26238, 26253, -1, 26255, 26256, 26257, -1, 26258, 26259, 26260, -1, 26258, 26255, 26259, -1, 26258, 26254, 26256, -1, 26258, 26256, 26255, -1, 26261, 26238, 26254, -1, 26261, 26254, 26258, -1, 26262, 26261, 26258, -1, 26263, 26264, 26261, -1, 26265, 26261, 26262, -1, 26266, 26263, 26261, -1, 26267, 26261, 26265, -1, 26268, 26266, 26261, -1, 26269, 26261, 26267, -1, 26269, 26268, 26261, -1, 26238, 19020, 19205, -1, 26238, 26261, 19020, -1, 26252, 19130, 19131, -1, 26252, 26244, 19130, -1, 19052, 19045, 26262, -1, 26262, 19045, 26265, -1, 26265, 19042, 26267, -1, 19045, 19042, 26265, -1, 26267, 19038, 26269, -1, 19042, 19038, 26267, -1, 26269, 19028, 26268, -1, 19038, 19028, 26269, -1, 26268, 19014, 26266, -1, 19028, 19014, 26268, -1, 26266, 19016, 26263, -1, 19014, 19016, 26266, -1, 26263, 19017, 26264, -1, 19016, 19017, 26263, -1, 26264, 19020, 26261, -1, 19017, 19020, 26264, -1, 26252, 19131, 26251, -1, 26251, 19400, 26249, -1, 19131, 19400, 26251, -1, 19400, 19391, 26249, -1, 26249, 19384, 26246, -1, 19391, 19384, 26249, -1, 26246, 19389, 26247, -1, 19384, 19389, 26246, -1, 26247, 19397, 26245, -1, 19389, 19397, 26247, -1, 26245, 19405, 26248, -1, 19397, 19405, 26245, -1, 26248, 19410, 26250, -1, 19405, 19410, 26248, -1, 26250, 19195, 26253, -1, 19410, 19195, 26250, -1, 26262, 18941, 19052, -1, 26262, 26258, 18941, -1, 19206, 26253, 19195, -1, 26254, 26253, 19206, -1, 19206, 19667, 26254, -1, 26256, 19667, 26257, -1, 26254, 19667, 26256, -1, 26257, 18925, 26255, -1, 19667, 18925, 26257, -1, 26255, 18923, 26259, -1, 18925, 18923, 26255, -1, 26259, 18931, 26260, -1, 18923, 18931, 26259, -1, 26260, 18938, 26258, -1, 18931, 18938, 26260, -1, 18938, 18941, 26258, -1, 26270, 19076, 26271, -1, 26271, 19253, 26272, -1, 19076, 19253, 26271, -1, 26272, 19244, 26273, -1, 19253, 19244, 26272, -1, 26273, 19239, 26274, -1, 19244, 19239, 26273, -1, 26274, 19234, 26275, -1, 19239, 19234, 26274, -1, 26275, 19230, 26276, -1, 19234, 19230, 26275, -1, 26276, 19223, 26277, -1, 19230, 19223, 26276, -1, 26277, 19224, 26278, -1, 19223, 19224, 26277, -1, 19224, 19201, 26278, -1, 26279, 26280, 26281, -1, 26282, 26283, 26284, -1, 26284, 26283, 26285, -1, 26285, 26283, 26279, -1, 26279, 26283, 26280, -1, 26271, 26272, 26270, -1, 26272, 26273, 26270, -1, 26273, 26274, 26270, -1, 26274, 26275, 26270, -1, 26275, 26276, 26270, -1, 26276, 26277, 26270, -1, 26270, 26278, 26283, -1, 26283, 26278, 26280, -1, 26277, 26278, 26270, -1, 26286, 26287, 26288, -1, 26288, 26287, 26289, -1, 26287, 26290, 26291, -1, 26291, 26290, 26292, -1, 26286, 26290, 26287, -1, 26293, 26294, 26286, -1, 26286, 26294, 26290, -1, 26293, 26295, 26294, -1, 26280, 26296, 26293, -1, 26278, 26296, 26280, -1, 26293, 26296, 26295, -1, 26296, 26297, 26295, -1, 26296, 26298, 26297, -1, 26299, 26300, 26296, -1, 26296, 26301, 26298, -1, 26300, 26301, 26296, -1, 19076, 26283, 19071, -1, 26270, 26283, 19076, -1, 26296, 26278, 19201, -1, 26296, 19201, 19200, -1, 19015, 19027, 26280, -1, 26280, 19027, 26281, -1, 26281, 19035, 26279, -1, 19027, 19035, 26281, -1, 26279, 19041, 26285, -1, 19035, 19041, 26279, -1, 26285, 19044, 26284, -1, 19041, 19044, 26285, -1, 26284, 19053, 26282, -1, 19044, 19053, 26284, -1, 26282, 19071, 26283, -1, 19053, 19071, 26282, -1, 26296, 19200, 26299, -1, 26299, 19555, 26300, -1, 19200, 19555, 26299, -1, 26300, 19546, 26301, -1, 19555, 19546, 26300, -1, 26301, 19548, 26298, -1, 19546, 19548, 26301, -1, 26298, 19550, 26297, -1, 19548, 19550, 26298, -1, 19550, 19557, 26297, -1, 26297, 19127, 26295, -1, 19557, 19127, 26297, -1, 19015, 26293, 19203, -1, 26280, 26293, 19015, -1, 26294, 26295, 19127, -1, 26294, 19127, 19129, -1, 26294, 19129, 26290, -1, 26290, 19470, 26292, -1, 19129, 19470, 26290, -1, 26292, 19465, 26291, -1, 19470, 19465, 26292, -1, 26291, 19459, 26287, -1, 19465, 19459, 26291, -1, 26287, 19462, 26289, -1, 19459, 19462, 26287, -1, 26289, 19469, 26288, -1, 19462, 19469, 26289, -1, 26288, 19472, 26286, -1, 19469, 19472, 26288, -1, 26286, 19475, 26293, -1, 19472, 19475, 26286, -1, 19475, 19203, 26293, -1, 26302, 19261, 26303, -1, 26303, 19628, 26304, -1, 19261, 19628, 26303, -1, 26304, 19622, 26305, -1, 19628, 19622, 26304, -1, 26305, 19624, 26306, -1, 19622, 19624, 26305, -1, 26306, 19631, 26307, -1, 19624, 19631, 26306, -1, 26307, 19634, 26308, -1, 19631, 19634, 26307, -1, 19634, 19125, 26308, -1, 26309, 26310, 26311, -1, 26311, 26310, 26312, -1, 26312, 26313, 26314, -1, 26314, 26313, 26315, -1, 26310, 26313, 26312, -1, 26316, 26317, 26318, -1, 26318, 26317, 26319, -1, 26320, 26321, 26322, -1, 26322, 26321, 26317, -1, 26317, 26321, 26319, -1, 26319, 26323, 26313, -1, 26313, 26323, 26315, -1, 26321, 26323, 26319, -1, 26324, 26325, 26326, -1, 26325, 26327, 26328, -1, 26328, 26327, 26329, -1, 26324, 26330, 26325, -1, 26325, 26330, 26327, -1, 26331, 26332, 26324, -1, 26324, 26332, 26330, -1, 26331, 26308, 26332, -1, 26315, 26302, 26331, -1, 26323, 26302, 26315, -1, 26331, 26302, 26308, -1, 26302, 26307, 26308, -1, 26303, 26304, 26302, -1, 26307, 26305, 26306, -1, 26302, 26305, 26307, -1, 26304, 26305, 26302, -1, 19261, 26323, 19262, -1, 26302, 26323, 19261, -1, 26332, 26308, 19125, -1, 26332, 19125, 19126, -1, 26319, 19078, 26318, -1, 26318, 19316, 26316, -1, 19078, 19316, 26318, -1, 26316, 19313, 26317, -1, 19316, 19313, 26316, -1, 26317, 19307, 26322, -1, 19313, 19307, 26317, -1, 26322, 19303, 26320, -1, 19307, 19303, 26322, -1, 26320, 19295, 26321, -1, 19303, 19295, 26320, -1, 26321, 19297, 26323, -1, 19295, 19297, 26321, -1, 19297, 19262, 26323, -1, 26332, 19559, 26330, -1, 19126, 19559, 26332, -1, 26330, 19556, 26327, -1, 19559, 19556, 26330, -1, 26327, 19549, 26329, -1, 19556, 19549, 26327, -1, 26329, 19547, 26328, -1, 19549, 19547, 26329, -1, 26328, 19552, 26325, -1, 19547, 19552, 26328, -1, 26325, 19558, 26326, -1, 19552, 19558, 26325, -1, 26326, 19562, 26324, -1, 19558, 19562, 26326, -1, 26324, 19202, 26331, -1, 19562, 19202, 26324, -1, 26319, 26313, 19077, -1, 26319, 19077, 19078, -1, 19211, 26331, 19202, -1, 26315, 26331, 19211, -1, 19211, 19231, 26315, -1, 26315, 19231, 26314, -1, 26314, 19233, 26312, -1, 19231, 19233, 26314, -1, 26312, 19240, 26311, -1, 19233, 19240, 26312, -1, 26311, 19245, 26309, -1, 19240, 19245, 26311, -1, 26309, 19252, 26310, -1, 19245, 19252, 26309, -1, 26310, 19077, 26313, -1, 19252, 19077, 26310, -1, 26333, 18970, 26334, -1, 18970, 18963, 26334, -1, 26334, 18954, 26335, -1, 18963, 18954, 26334, -1, 26335, 18945, 26336, -1, 18954, 18945, 26335, -1, 26336, 18947, 26337, -1, 18945, 18947, 26336, -1, 26337, 18958, 26338, -1, 18947, 18958, 26337, -1, 26338, 18967, 26339, -1, 18958, 18967, 26338, -1, 26340, 26341, 26342, -1, 26342, 26341, 26343, -1, 26340, 26344, 26341, -1, 26341, 26345, 26346, -1, 26344, 26345, 26341, -1, 26347, 26348, 26349, -1, 26348, 26350, 26349, -1, 26351, 26352, 26350, -1, 26349, 26352, 26353, -1, 26350, 26352, 26349, -1, 26353, 26354, 26345, -1, 26345, 26354, 26346, -1, 26352, 26354, 26353, -1, 26355, 26356, 26357, -1, 26356, 26358, 26359, -1, 26355, 26360, 26356, -1, 26356, 26360, 26358, -1, 26361, 26362, 26355, -1, 26355, 26362, 26360, -1, 26361, 26339, 26362, -1, 26346, 26333, 26361, -1, 26354, 26333, 26346, -1, 26361, 26333, 26339, -1, 26339, 26337, 26338, -1, 26333, 26337, 26339, -1, 26334, 26335, 26333, -1, 26333, 26336, 26337, -1, 26335, 26336, 26333, -1, 26333, 26354, 19334, -1, 26333, 19334, 18970, -1, 26362, 26339, 18967, -1, 26362, 18967, 19124, -1, 19080, 19381, 26353, -1, 26349, 19381, 26347, -1, 26353, 19381, 26349, -1, 26347, 19377, 26348, -1, 19381, 19377, 26347, -1, 26348, 19372, 26350, -1, 19377, 19372, 26348, -1, 26350, 19368, 26351, -1, 19372, 19368, 26350, -1, 26351, 19362, 26352, -1, 19368, 19362, 26351, -1, 26352, 19344, 26354, -1, 19362, 19344, 26352, -1, 19344, 19334, 26354, -1, 26362, 19633, 26360, -1, 19124, 19633, 26362, -1, 26360, 19630, 26358, -1, 19633, 19630, 26360, -1, 26358, 19623, 26359, -1, 19630, 19623, 26358, -1, 26359, 19629, 26356, -1, 19623, 19629, 26359, -1, 26356, 19632, 26357, -1, 19629, 19632, 26356, -1, 26357, 19635, 26355, -1, 19632, 19635, 26357, -1, 26355, 19263, 26361, -1, 19635, 19263, 26355, -1, 26353, 26345, 19079, -1, 26353, 19079, 19080, -1, 19296, 26361, 19263, -1, 26346, 26361, 19296, -1, 19296, 19300, 26346, -1, 26346, 19300, 26341, -1, 26341, 19305, 26343, -1, 19300, 19305, 26341, -1, 26343, 19312, 26342, -1, 19305, 19312, 26343, -1, 26342, 19317, 26340, -1, 19312, 19317, 26342, -1, 26340, 19318, 26344, -1, 19317, 19318, 26340, -1, 26344, 19079, 26345, -1, 19318, 19079, 26344, -1, 26363, 19215, 26364, -1, 26364, 19207, 26365, -1, 19215, 19207, 26364, -1, 26365, 19169, 26366, -1, 19207, 19169, 26365, -1, 26366, 19138, 26367, -1, 19169, 19138, 26366, -1, 26367, 19140, 26368, -1, 19138, 19140, 26367, -1, 26368, 19178, 26369, -1, 19140, 19178, 26368, -1, 19178, 19213, 26369, -1, 26369, 19120, 26370, -1, 19213, 19120, 26369, -1, 26371, 26372, 26373, -1, 26373, 26372, 26374, -1, 26374, 26372, 26375, -1, 26375, 26372, 26376, -1, 26371, 26377, 26372, -1, 26378, 26379, 26380, -1, 26379, 26381, 26380, -1, 26381, 26382, 26380, -1, 26380, 26383, 26384, -1, 26382, 26383, 26380, -1, 26384, 26385, 26377, -1, 26377, 26385, 26372, -1, 26383, 26385, 26384, -1, 26386, 26387, 26388, -1, 26389, 26390, 26386, -1, 26387, 26390, 26391, -1, 26391, 26390, 26392, -1, 26392, 26390, 26393, -1, 26386, 26390, 26387, -1, 26389, 26370, 26390, -1, 26372, 26363, 26389, -1, 26385, 26363, 26372, -1, 26389, 26363, 26370, -1, 26370, 26368, 26369, -1, 26364, 26365, 26363, -1, 26363, 26367, 26370, -1, 26370, 26367, 26368, -1, 26365, 26367, 26363, -1, 26365, 26366, 26367, -1, 26363, 26385, 19396, -1, 26363, 19396, 19215, -1, 18984, 26370, 19120, -1, 26390, 26370, 18984, -1, 19082, 19440, 26384, -1, 26384, 19440, 26380, -1, 26378, 19435, 26379, -1, 26380, 19435, 26378, -1, 19440, 19435, 26380, -1, 26379, 19433, 26381, -1, 19435, 19433, 26379, -1, 26381, 19430, 26382, -1, 19433, 19430, 26381, -1, 26382, 19427, 26383, -1, 19430, 19427, 26382, -1, 26383, 19424, 26385, -1, 19427, 19424, 26383, -1, 19424, 19396, 26385, -1, 26390, 18984, 26393, -1, 26393, 18966, 26392, -1, 18984, 18966, 26393, -1, 26392, 18957, 26391, -1, 18966, 18957, 26392, -1, 26391, 18946, 26387, -1, 18957, 18946, 26391, -1, 26387, 18955, 26388, -1, 18946, 18955, 26387, -1, 26388, 18964, 26386, -1, 18955, 18964, 26388, -1, 18964, 18971, 26386, -1, 26386, 18989, 26389, -1, 18971, 18989, 26386, -1, 26384, 26377, 19081, -1, 26384, 19081, 19082, -1, 19345, 26389, 18989, -1, 26372, 26389, 19345, -1, 26372, 19345, 26376, -1, 19345, 19363, 26376, -1, 26376, 19367, 26375, -1, 19363, 19367, 26376, -1, 26375, 19371, 26374, -1, 19367, 19371, 26375, -1, 26374, 19375, 26373, -1, 19371, 19375, 26374, -1, 26373, 19380, 26371, -1, 19375, 19380, 26373, -1, 26371, 19081, 26377, -1, 19380, 19081, 26371, -1, 21111, 19119, 21112, -1, 21112, 19212, 21113, -1, 19119, 19212, 21112, -1, 21113, 19176, 21114, -1, 19212, 19176, 21113, -1, 21114, 19139, 21118, -1, 19176, 19139, 21114, -1, 21118, 19152, 21116, -1, 19139, 19152, 21118, -1, 21116, 19204, 21117, -1, 19152, 19204, 21116, -1, 19204, 19216, 21117, -1, 21117, 19218, 21115, -1, 19216, 19218, 21117, -1, 19425, 21115, 19218, -1, 21126, 21115, 19425, -1, 21126, 19428, 21128, -1, 19425, 19428, 21126, -1, 21128, 19431, 21127, -1, 19428, 19431, 21128, -1, 21127, 19432, 21129, -1, 19431, 19432, 21127, -1, 21129, 19434, 21130, -1, 19432, 19434, 21129, -1, 21130, 19439, 21132, -1, 19434, 19439, 21130, -1, 21132, 19456, 21131, -1, 19439, 19456, 21132, -1, 21131, 19083, 21133, -1, 19456, 19083, 21131, -1, 21143, 19882, 21166, -1, 21166, 20280, 21165, -1, 19882, 20280, 21166, -1, 21165, 20275, 21164, -1, 20280, 20275, 21165, -1, 21164, 20258, 21163, -1, 20275, 20258, 21164, -1, 21163, 20255, 21161, -1, 20258, 20255, 21163, -1, 21161, 20252, 21162, -1, 20255, 20252, 21161, -1, 20252, 20248, 21162, -1, 21162, 20238, 21160, -1, 20248, 20238, 21162, -1, 21149, 21160, 20238, -1, 21149, 20238, 20037, -1, 21149, 20037, 21151, -1, 21151, 20033, 21150, -1, 20037, 20033, 21151, -1, 21150, 20029, 21146, -1, 20033, 20029, 21150, -1, 21146, 20019, 21144, -1, 20029, 20019, 21146, -1, 21144, 20021, 21145, -1, 20019, 20021, 21144, -1, 21145, 20025, 21147, -1, 20021, 20025, 21145, -1, 20025, 20031, 21147, -1, 21147, 19840, 21148, -1, 20031, 19840, 21147, -1, 26394, 26395, 26396, -1, 26396, 26397, 26398, -1, 26395, 26397, 26396, -1, 26398, 26399, 26400, -1, 26397, 26399, 26398, -1, 26400, 19819, 19814, -1, 26399, 19819, 26400, -1, 26401, 26402, 26403, -1, 26402, 26404, 26403, -1, 26404, 26405, 26403, -1, 26405, 26406, 26403, -1, 26406, 26407, 26403, -1, 26407, 26408, 26403, -1, 26403, 26409, 26410, -1, 26408, 26409, 26403, -1, 26410, 26411, 26394, -1, 26409, 26411, 26410, -1, 26411, 26412, 26394, -1, 26412, 26413, 26394, -1, 26413, 26414, 26394, -1, 26415, 26416, 26417, -1, 26415, 26418, 26416, -1, 26415, 26419, 26418, -1, 26415, 26420, 26419, -1, 26415, 26421, 26420, -1, 26415, 26422, 26421, -1, 26415, 26423, 26422, -1, 26415, 26424, 26423, -1, 26415, 26425, 26424, -1, 26415, 26426, 26425, -1, 26427, 26428, 26429, -1, 26430, 26428, 26427, -1, 26430, 26431, 26428, -1, 26432, 26433, 26434, -1, 26415, 26435, 26426, -1, 26432, 26436, 26433, -1, 26431, 26436, 26432, -1, 26430, 26436, 26431, -1, 26415, 26437, 26435, -1, 26430, 26438, 26436, -1, 26436, 26438, 26439, -1, 26430, 26440, 26438, -1, 26441, 26440, 26430, -1, 26442, 26443, 26441, -1, 26443, 26444, 26441, -1, 26444, 26445, 26441, -1, 26445, 26446, 26441, -1, 26441, 26447, 26440, -1, 26446, 26447, 26441, -1, 26447, 26448, 26440, -1, 26448, 26449, 26440, -1, 26450, 26451, 26452, -1, 26449, 26453, 26440, -1, 26450, 26454, 26451, -1, 26450, 26455, 26454, -1, 26453, 26456, 26440, -1, 26450, 26457, 26455, -1, 26456, 26458, 26440, -1, 26458, 26459, 26440, -1, 26450, 26460, 26457, -1, 26450, 26461, 26460, -1, 26462, 26463, 26450, -1, 26450, 26463, 26461, -1, 26464, 26465, 26462, -1, 26462, 26465, 26463, -1, 26466, 26467, 26464, -1, 26468, 26467, 26466, -1, 26464, 26467, 26465, -1, 26437, 26469, 26468, -1, 26468, 26469, 26467, -1, 26415, 26469, 26437, -1, 26470, 26471, 26472, -1, 26471, 26473, 26474, -1, 26470, 26473, 26471, -1, 26475, 26476, 26477, -1, 26478, 26476, 26475, -1, 26479, 26476, 26478, -1, 26480, 26476, 26479, -1, 26473, 26476, 26480, -1, 26470, 26476, 26473, -1, 26470, 26481, 26476, -1, 26482, 26481, 26470, -1, 26482, 26483, 26481, -1, 26482, 26484, 26483, -1, 26482, 26485, 26484, -1, 26482, 26486, 26485, -1, 26482, 26487, 26486, -1, 26488, 26487, 26482, -1, 26488, 26489, 26487, -1, 26490, 26489, 26488, -1, 26490, 26491, 26489, -1, 26492, 26491, 26490, -1, 26493, 26491, 26492, -1, 26493, 26494, 26491, -1, 26495, 26494, 26493, -1, 26496, 26497, 26498, -1, 26496, 26499, 26497, -1, 26500, 26499, 26496, -1, 26500, 26501, 26499, -1, 26500, 26502, 26501, -1, 26503, 26502, 26500, -1, 26503, 26504, 26502, -1, 26505, 26504, 26503, -1, 26505, 26506, 26504, -1, 26507, 26506, 26505, -1, 26507, 26508, 26506, -1, 26509, 26508, 26507, -1, 26494, 26510, 26511, -1, 26512, 26510, 26513, -1, 26514, 26510, 26512, -1, 26515, 26510, 26514, -1, 26516, 26510, 26515, -1, 26517, 26510, 26516, -1, 26518, 26510, 26517, -1, 26519, 26510, 26518, -1, 26508, 26510, 26519, -1, 26509, 26510, 26508, -1, 26520, 26510, 26509, -1, 26521, 26510, 26520, -1, 26511, 26510, 26521, -1, 26513, 26522, 26523, -1, 26510, 26522, 26513, -1, 26523, 26395, 26524, -1, 26414, 26395, 26394, -1, 26522, 26395, 26523, -1, 26441, 26450, 26452, -1, 26441, 26452, 26442, -1, 26414, 26524, 26395, -1, 26498, 26440, 26459, -1, 26459, 26496, 26498, -1, 26525, 26477, 26476, -1, 26525, 26476, 26526, -1, 26403, 26415, 26401, -1, 26401, 26415, 26417, -1, 26415, 26510, 26527, -1, 26415, 26527, 26469, -1, 26527, 26510, 26495, -1, 26495, 26510, 26494, -1, 26528, 26441, 26430, -1, 26528, 26529, 26441, -1, 26530, 26430, 26427, -1, 26530, 26528, 26430, -1, 26531, 26427, 26429, -1, 26531, 26530, 26427, -1, 26532, 26466, 26533, -1, 26466, 26464, 26533, -1, 26533, 26462, 26534, -1, 26464, 26462, 26533, -1, 26534, 26450, 26535, -1, 26462, 26450, 26534, -1, 26536, 26515, 26537, -1, 26537, 26514, 26538, -1, 26515, 26514, 26537, -1, 26538, 26512, 26539, -1, 26514, 26512, 26538, -1, 26539, 26513, 26540, -1, 26512, 26513, 26539, -1, 26513, 26523, 26540, -1, 26540, 26524, 26541, -1, 26523, 26524, 26540, -1, 26542, 26472, 26471, -1, 26542, 26470, 26472, -1, 26542, 26543, 26470, -1, 26544, 26542, 26471, -1, 26545, 26471, 26474, -1, 26545, 26544, 26471, -1, 26492, 26490, 26546, -1, 26546, 26490, 26547, -1, 26548, 26488, 26549, -1, 26547, 26488, 26548, -1, 26490, 26488, 26547, -1, 26488, 26482, 26549, -1, 26509, 26507, 26550, -1, 26551, 26507, 26552, -1, 26550, 26507, 26551, -1, 26552, 26505, 26553, -1, 26507, 26505, 26552, -1, 26553, 26503, 26554, -1, 26505, 26503, 26553, -1, 26503, 26500, 26554, -1, 26554, 26496, 26555, -1, 26500, 26496, 26554, -1, 26556, 26557, 26543, -1, 26547, 26558, 26546, -1, 26549, 26557, 26559, -1, 26549, 26560, 26558, -1, 26549, 26559, 26560, -1, 26549, 26547, 26548, -1, 26549, 26558, 26547, -1, 26543, 26557, 26549, -1, 26556, 26544, 26545, -1, 26556, 26542, 26544, -1, 26556, 26543, 26542, -1, 26556, 26561, 26562, -1, 26556, 26545, 26561, -1, 26563, 26556, 26562, -1, 26564, 26556, 26563, -1, 26565, 26556, 26564, -1, 26566, 26556, 26565, -1, 26567, 26556, 26566, -1, 26568, 26556, 26567, -1, 26551, 26569, 26550, -1, 26551, 26570, 26569, -1, 26552, 26570, 26551, -1, 26555, 26571, 26572, -1, 26555, 26572, 26570, -1, 26555, 26568, 26573, -1, 26555, 26573, 26571, -1, 26553, 26570, 26552, -1, 26554, 26555, 26570, -1, 26554, 26570, 26553, -1, 26555, 26556, 26568, -1, 26541, 26574, 26575, -1, 26574, 26576, 26529, -1, 26575, 26577, 26541, -1, 26532, 26578, 26579, -1, 26535, 26576, 26580, -1, 26535, 26580, 26578, -1, 26535, 26533, 26534, -1, 26535, 26532, 26533, -1, 26535, 26578, 26532, -1, 26529, 26576, 26535, -1, 26574, 26530, 26531, -1, 26574, 26528, 26530, -1, 26574, 26529, 26528, -1, 26574, 26581, 26582, -1, 26574, 26531, 26581, -1, 26583, 26574, 26582, -1, 26584, 26574, 26583, -1, 26585, 26574, 26584, -1, 26586, 26574, 26585, -1, 26587, 26574, 26586, -1, 26588, 26574, 26587, -1, 26575, 26574, 26588, -1, 26589, 26590, 26591, -1, 26536, 26590, 26589, -1, 26538, 26536, 26537, -1, 26541, 26577, 26590, -1, 26541, 26590, 26536, -1, 26541, 26536, 26538, -1, 26539, 26541, 26538, -1, 26540, 26541, 26539, -1, 26557, 26556, 26452, -1, 26452, 26556, 26442, -1, 26459, 26592, 26556, -1, 26592, 26593, 26556, -1, 26593, 26594, 26556, -1, 26453, 26595, 26456, -1, 26456, 26595, 26458, -1, 26458, 26595, 26459, -1, 26459, 26595, 26592, -1, 26594, 26596, 26556, -1, 26448, 26597, 26449, -1, 26449, 26597, 26453, -1, 26595, 26597, 26592, -1, 26592, 26597, 26593, -1, 26453, 26597, 26595, -1, 26556, 26598, 26442, -1, 26596, 26598, 26556, -1, 26447, 26599, 26448, -1, 26448, 26599, 26597, -1, 26597, 26599, 26593, -1, 26593, 26599, 26594, -1, 26445, 26600, 26446, -1, 26446, 26600, 26447, -1, 26447, 26600, 26599, -1, 26594, 26600, 26596, -1, 26599, 26600, 26594, -1, 26442, 26601, 26443, -1, 26443, 26601, 26444, -1, 26444, 26601, 26445, -1, 26445, 26601, 26600, -1, 26598, 26601, 26442, -1, 26596, 26601, 26598, -1, 26600, 26601, 26596, -1, 26452, 26602, 26557, -1, 26602, 26603, 26557, -1, 26603, 26604, 26557, -1, 26455, 26605, 26454, -1, 26454, 26605, 26451, -1, 26451, 26605, 26452, -1, 26452, 26605, 26602, -1, 26557, 26606, 26469, -1, 26604, 26606, 26557, -1, 26460, 26607, 26457, -1, 26457, 26607, 26455, -1, 26605, 26607, 26602, -1, 26602, 26607, 26603, -1, 26455, 26607, 26605, -1, 26463, 26608, 26461, -1, 26461, 26608, 26460, -1, 26460, 26608, 26607, -1, 26603, 26608, 26604, -1, 26607, 26608, 26603, -1, 26469, 26609, 26467, -1, 26467, 26609, 26465, -1, 26465, 26609, 26463, -1, 26463, 26609, 26608, -1, 26608, 26609, 26604, -1, 26604, 26609, 26606, -1, 26606, 26609, 26469, -1, 26556, 26555, 26459, -1, 26459, 26555, 26496, -1, 26559, 26469, 26527, -1, 26559, 26557, 26469, -1, 26511, 26521, 26572, -1, 26572, 26521, 26570, -1, 26570, 26520, 26569, -1, 26521, 26520, 26570, -1, 26569, 26509, 26550, -1, 26520, 26509, 26569, -1, 26527, 26495, 26559, -1, 26560, 26495, 26558, -1, 26559, 26495, 26560, -1, 26558, 26493, 26546, -1, 26495, 26493, 26558, -1, 26493, 26492, 26546, -1, 26572, 26494, 26511, -1, 26572, 26571, 26494, -1, 26470, 26549, 26482, -1, 26543, 26549, 26470, -1, 26481, 26610, 26571, -1, 26610, 26611, 26571, -1, 26485, 26612, 26484, -1, 26484, 26612, 26483, -1, 26483, 26612, 26481, -1, 26481, 26612, 26610, -1, 26571, 26613, 26494, -1, 26611, 26613, 26571, -1, 26487, 26614, 26486, -1, 26486, 26614, 26485, -1, 26485, 26614, 26612, -1, 26612, 26614, 26610, -1, 26610, 26614, 26611, -1, 26494, 26615, 26491, -1, 26491, 26615, 26489, -1, 26489, 26615, 26487, -1, 26487, 26615, 26614, -1, 26611, 26615, 26613, -1, 26614, 26615, 26611, -1, 26613, 26615, 26494, -1, 26545, 26474, 26473, -1, 26561, 26545, 26473, -1, 26562, 26473, 26480, -1, 26562, 26561, 26473, -1, 26563, 26480, 26479, -1, 26563, 26562, 26480, -1, 26564, 26479, 26478, -1, 26564, 26563, 26479, -1, 26565, 26478, 26475, -1, 26565, 26564, 26478, -1, 26566, 26475, 26477, -1, 26566, 26565, 26475, -1, 26567, 26477, 26525, -1, 26567, 26566, 26477, -1, 26568, 26525, 26526, -1, 26568, 26567, 26525, -1, 26573, 26526, 26476, -1, 26573, 26568, 26526, -1, 26571, 26476, 26481, -1, 26571, 26573, 26476, -1, 26576, 26401, 26417, -1, 26576, 26574, 26401, -1, 26616, 26617, 26574, -1, 26617, 26618, 26574, -1, 26411, 26619, 26412, -1, 26412, 26619, 26413, -1, 26413, 26619, 26414, -1, 26414, 26619, 26574, -1, 26574, 26619, 26616, -1, 26618, 26620, 26574, -1, 26408, 26621, 26409, -1, 26409, 26621, 26411, -1, 26616, 26621, 26617, -1, 26411, 26621, 26619, -1, 26619, 26621, 26616, -1, 26574, 26622, 26401, -1, 26620, 26622, 26574, -1, 26407, 26623, 26408, -1, 26408, 26623, 26621, -1, 26617, 26623, 26618, -1, 26621, 26623, 26617, -1, 26405, 26624, 26406, -1, 26406, 26624, 26407, -1, 26618, 26624, 26620, -1, 26407, 26624, 26623, -1, 26623, 26624, 26618, -1, 26401, 26625, 26402, -1, 26402, 26625, 26404, -1, 26404, 26625, 26405, -1, 26405, 26625, 26624, -1, 26622, 26625, 26401, -1, 26620, 26625, 26622, -1, 26624, 26625, 26620, -1, 26417, 26626, 26576, -1, 26626, 26627, 26576, -1, 26627, 26628, 26576, -1, 26419, 26629, 26418, -1, 26418, 26629, 26416, -1, 26416, 26629, 26417, -1, 26417, 26629, 26626, -1, 26576, 26630, 26426, -1, 26628, 26630, 26576, -1, 26421, 26631, 26420, -1, 26420, 26631, 26419, -1, 26629, 26631, 26626, -1, 26626, 26631, 26627, -1, 26419, 26631, 26629, -1, 26423, 26632, 26422, -1, 26422, 26632, 26421, -1, 26631, 26632, 26627, -1, 26421, 26632, 26631, -1, 26627, 26632, 26628, -1, 26426, 26633, 26425, -1, 26425, 26633, 26424, -1, 26424, 26633, 26423, -1, 26423, 26633, 26632, -1, 26628, 26633, 26630, -1, 26630, 26633, 26426, -1, 26632, 26633, 26628, -1, 26574, 26524, 26414, -1, 26574, 26541, 26524, -1, 26435, 26576, 26426, -1, 26580, 26576, 26435, -1, 26518, 26517, 26590, -1, 26590, 26517, 26591, -1, 26591, 26516, 26589, -1, 26517, 26516, 26591, -1, 26589, 26515, 26536, -1, 26516, 26515, 26589, -1, 26435, 26437, 26580, -1, 26578, 26437, 26579, -1, 26580, 26437, 26578, -1, 26579, 26468, 26532, -1, 26437, 26468, 26579, -1, 26468, 26466, 26532, -1, 26590, 26577, 26518, -1, 26518, 26577, 26519, -1, 26441, 26535, 26450, -1, 26529, 26535, 26441, -1, 26634, 26635, 26577, -1, 26501, 26636, 26499, -1, 26499, 26636, 26497, -1, 26497, 26636, 26498, -1, 26498, 26636, 26577, -1, 26577, 26636, 26634, -1, 26635, 26637, 26577, -1, 26504, 26638, 26502, -1, 26502, 26638, 26501, -1, 26501, 26638, 26636, -1, 26636, 26638, 26634, -1, 26634, 26638, 26635, -1, 26519, 26639, 26508, -1, 26508, 26639, 26506, -1, 26506, 26639, 26504, -1, 26577, 26639, 26519, -1, 26504, 26639, 26638, -1, 26637, 26639, 26577, -1, 26638, 26639, 26635, -1, 26635, 26639, 26637, -1, 26531, 26429, 26428, -1, 26581, 26531, 26428, -1, 26582, 26428, 26431, -1, 26582, 26581, 26428, -1, 26583, 26431, 26432, -1, 26583, 26582, 26431, -1, 26584, 26432, 26434, -1, 26584, 26583, 26432, -1, 26585, 26433, 26436, -1, 26585, 26434, 26433, -1, 26585, 26584, 26434, -1, 26586, 26436, 26439, -1, 26586, 26585, 26436, -1, 26587, 26439, 26438, -1, 26587, 26586, 26439, -1, 26588, 26587, 26438, -1, 26575, 26438, 26440, -1, 26575, 26588, 26438, -1, 26577, 26440, 26498, -1, 26577, 26575, 26440, -1, 23703, 23704, 26640, -1, 26640, 23704, 26641, -1, 26641, 26642, 26643, -1, 23704, 26642, 26641, -1, 26643, 26644, 26645, -1, 26642, 26644, 26643, -1, 26644, 26646, 26645, -1, 26647, 26648, 26646, -1, 26649, 26648, 26647, -1, 26648, 26645, 26646, -1, 24986, 24987, 26650, -1, 26650, 26651, 26652, -1, 24987, 26651, 26650, -1, 26651, 26653, 26652, -1, 26652, 26654, 26655, -1, 26653, 26654, 26652, -1, 26655, 26656, 26657, -1, 26654, 26656, 26655, -1, 26657, 26658, 26659, -1, 26659, 26658, 26660, -1, 26656, 26658, 26657, -1, 26660, 26415, 26403, -1, 26658, 26415, 26660, -1, 26661, 24986, 26662, -1, 26663, 24986, 26661, -1, 26664, 24986, 26663, -1, 26665, 26666, 26667, -1, 26668, 24986, 26664, -1, 26669, 24986, 26668, -1, 26670, 24986, 26669, -1, 26671, 24986, 26670, -1, 26667, 26672, 26665, -1, 26673, 24986, 26671, -1, 26674, 26673, 26675, -1, 26675, 26673, 26676, -1, 26674, 26677, 26665, -1, 24986, 26650, 26662, -1, 26662, 26650, 26678, -1, 26665, 26677, 26666, -1, 26672, 26679, 26665, -1, 26674, 26680, 26677, -1, 26679, 26681, 26665, -1, 26674, 26675, 26680, -1, 26682, 26683, 26681, -1, 26681, 26683, 26665, -1, 26682, 26684, 26683, -1, 26684, 26685, 26683, -1, 26685, 26686, 26683, -1, 26686, 26687, 26683, -1, 26683, 26688, 26650, -1, 26687, 26688, 26683, -1, 26688, 26689, 26650, -1, 26689, 26678, 26650, -1, 26690, 26673, 26691, -1, 26692, 26673, 26690, -1, 26693, 26673, 26692, -1, 26694, 26673, 26693, -1, 26695, 26673, 26694, -1, 26676, 26673, 26695, -1, 26673, 26696, 26691, -1, 26673, 26671, 26696, -1, 26697, 26698, 26675, -1, 26697, 26675, 26676, -1, 26699, 26700, 26701, -1, 26702, 26703, 26704, -1, 26704, 26703, 26699, -1, 26699, 26703, 26700, -1, 26700, 26705, 26697, -1, 26703, 26705, 26700, -1, 26706, 26707, 26708, -1, 26708, 26707, 26709, -1, 26710, 26711, 26707, -1, 26709, 26711, 26712, -1, 26707, 26711, 26709, -1, 26712, 26713, 26705, -1, 26705, 26713, 26697, -1, 26711, 26713, 26712, -1, 26714, 26715, 26716, -1, 26714, 26717, 26715, -1, 26698, 26718, 26714, -1, 26717, 26718, 26719, -1, 26714, 26718, 26717, -1, 26698, 26720, 26718, -1, 26698, 26721, 26720, -1, 26697, 26722, 26698, -1, 26713, 26722, 26697, -1, 26698, 26722, 26721, -1, 26722, 26723, 26721, -1, 26722, 26724, 26723, -1, 26723, 26725, 26726, -1, 26727, 26725, 26724, -1, 26724, 26725, 26723, -1, 26727, 26728, 26725, -1, 26681, 26679, 26720, -1, 26720, 26679, 26718, -1, 26718, 26672, 26719, -1, 26679, 26672, 26718, -1, 26719, 26667, 26717, -1, 26672, 26667, 26719, -1, 26717, 26666, 26715, -1, 26667, 26666, 26717, -1, 26715, 26677, 26716, -1, 26666, 26677, 26715, -1, 26716, 26680, 26714, -1, 26677, 26680, 26716, -1, 26714, 26675, 26698, -1, 26680, 26675, 26714, -1, 26697, 26695, 26700, -1, 26676, 26695, 26697, -1, 26700, 26694, 26701, -1, 26695, 26694, 26700, -1, 26701, 26693, 26699, -1, 26694, 26693, 26701, -1, 26699, 26692, 26704, -1, 26693, 26692, 26699, -1, 26702, 26690, 26703, -1, 26704, 26690, 26702, -1, 26692, 26690, 26704, -1, 26690, 26691, 26703, -1, 26703, 26696, 26705, -1, 26691, 26696, 26703, -1, 26720, 26721, 26682, -1, 26720, 26682, 26681, -1, 26671, 26705, 26696, -1, 26712, 26705, 26671, -1, 26678, 26689, 26722, -1, 26724, 26689, 26727, -1, 26722, 26689, 26724, -1, 26727, 26688, 26728, -1, 26689, 26688, 26727, -1, 26728, 26687, 26725, -1, 26688, 26687, 26728, -1, 26725, 26686, 26726, -1, 26687, 26686, 26725, -1, 26726, 26685, 26723, -1, 26686, 26685, 26726, -1, 26723, 26684, 26721, -1, 26685, 26684, 26723, -1, 26684, 26682, 26721, -1, 26712, 26671, 26709, -1, 26709, 26670, 26708, -1, 26671, 26670, 26709, -1, 26708, 26669, 26706, -1, 26670, 26669, 26708, -1, 26706, 26668, 26707, -1, 26669, 26668, 26706, -1, 26707, 26664, 26710, -1, 26668, 26664, 26707, -1, 26710, 26663, 26711, -1, 26664, 26663, 26710, -1, 26711, 26661, 26713, -1, 26663, 26661, 26711, -1, 26661, 26662, 26713, -1, 26722, 26713, 26662, -1, 26722, 26662, 26678, -1, 26649, 26647, 26729, -1, 26729, 26730, 26731, -1, 26647, 26730, 26729, -1, 26731, 26732, 26733, -1, 26730, 26732, 26731, -1, 26733, 26734, 26735, -1, 26732, 26734, 26733, -1, 26735, 26736, 26737, -1, 26737, 26736, 26738, -1, 26734, 26736, 26735, -1, 26738, 26739, 26740, -1, 26736, 26739, 26738, -1, 26741, 26739, 26742, -1, 26740, 26739, 26741, -1, 19066, 18932, 26743, -1, 26743, 18932, 26744, -1, 26744, 26745, 26746, -1, 18932, 26745, 26744, -1, 26746, 26747, 26748, -1, 26745, 26747, 26746, -1, 26748, 26749, 26750, -1, 26747, 26749, 26748, -1, 26751, 26752, 26753, -1, 26753, 26754, 26751, -1, 26755, 26756, 26751, -1, 26750, 26756, 26755, -1, 26751, 26756, 26752, -1, 26754, 26757, 26751, -1, 26750, 26758, 26756, -1, 26757, 26759, 26751, -1, 26750, 26760, 26758, -1, 26759, 26761, 26751, -1, 26761, 26762, 26751, -1, 26750, 26763, 26760, -1, 26762, 26764, 26751, -1, 26764, 26765, 26751, -1, 26766, 26767, 26768, -1, 26769, 26767, 26766, -1, 26770, 26767, 26769, -1, 26771, 26767, 26770, -1, 26772, 26767, 26771, -1, 26773, 26767, 26772, -1, 26774, 26767, 26773, -1, 26775, 26776, 26777, -1, 26768, 26776, 26775, -1, 26767, 26776, 26768, -1, 26767, 26778, 26779, -1, 26767, 26780, 26776, -1, 26779, 26780, 26767, -1, 26767, 26781, 26778, -1, 26780, 26782, 26776, -1, 26767, 26783, 26781, -1, 26782, 26784, 26776, -1, 26767, 26785, 26783, -1, 26784, 26786, 26776, -1, 26786, 26787, 26776, -1, 26767, 26788, 26785, -1, 26787, 26789, 26776, -1, 26789, 26790, 26776, -1, 26791, 26749, 26792, -1, 26750, 26749, 26763, -1, 26792, 26793, 26794, -1, 26749, 26793, 26792, -1, 26793, 26795, 26794, -1, 26796, 26795, 26797, -1, 26798, 26795, 26796, -1, 26794, 26795, 26798, -1, 26799, 26800, 26801, -1, 26802, 26800, 26799, -1, 26803, 26800, 26802, -1, 26804, 26800, 26803, -1, 26805, 26800, 26804, -1, 26806, 26800, 26805, -1, 26807, 26800, 26806, -1, 26808, 26800, 26807, -1, 26809, 26800, 26808, -1, 26810, 26800, 26809, -1, 26795, 26811, 26797, -1, 26795, 26812, 26811, -1, 26813, 26814, 26815, -1, 26816, 26814, 26813, -1, 26817, 26814, 26816, -1, 26818, 26819, 26817, -1, 26817, 26819, 26814, -1, 26820, 26821, 26818, -1, 26818, 26821, 26819, -1, 26822, 26823, 26820, -1, 26812, 26823, 26822, -1, 26820, 26823, 26821, -1, 26795, 26824, 26812, -1, 26812, 26824, 26823, -1, 26795, 26825, 26824, -1, 26810, 26826, 26800, -1, 26795, 26827, 26825, -1, 26826, 26828, 26800, -1, 26829, 26828, 26826, -1, 26830, 26828, 26829, -1, 26831, 26828, 26830, -1, 26832, 26828, 26831, -1, 26833, 26828, 26832, -1, 26834, 26835, 26833, -1, 26833, 26835, 26828, -1, 26834, 26836, 26835, -1, 26837, 26836, 26834, -1, 26837, 26838, 26836, -1, 26827, 26838, 26837, -1, 26795, 26839, 26827, -1, 26827, 26839, 26838, -1, 26840, 26841, 26842, -1, 26843, 26841, 26840, -1, 26844, 26841, 26843, -1, 26845, 26841, 26844, -1, 26846, 26841, 26845, -1, 26847, 26841, 26846, -1, 26848, 26841, 26847, -1, 26848, 26849, 26841, -1, 26850, 26849, 26848, -1, 26850, 26851, 26849, -1, 26852, 26851, 26850, -1, 26852, 26853, 26851, -1, 26854, 26853, 26852, -1, 26854, 26855, 26853, -1, 26856, 26857, 26858, -1, 26859, 26857, 26856, -1, 26860, 26857, 26859, -1, 26861, 26857, 26860, -1, 26862, 26857, 26861, -1, 26863, 26857, 26862, -1, 26864, 26857, 26863, -1, 26865, 26857, 26864, -1, 26866, 26857, 26865, -1, 26867, 26857, 26866, -1, 26855, 26857, 26867, -1, 26767, 26815, 26814, -1, 26767, 26814, 26788, -1, 26791, 26763, 26749, -1, 26841, 26776, 26842, -1, 26842, 26776, 26790, -1, 26795, 26857, 26854, -1, 26795, 26854, 26839, -1, 26854, 26857, 26855, -1, 26857, 26751, 26765, -1, 26857, 26765, 26858, -1, 26761, 26868, 26869, -1, 26868, 26870, 26869, -1, 26870, 26871, 26869, -1, 26754, 26872, 26757, -1, 26757, 26872, 26759, -1, 26759, 26872, 26761, -1, 26761, 26872, 26868, -1, 26871, 26873, 26869, -1, 26752, 26874, 26753, -1, 26753, 26874, 26754, -1, 26872, 26874, 26868, -1, 26868, 26874, 26870, -1, 26754, 26874, 26872, -1, 26756, 26875, 26752, -1, 26752, 26875, 26874, -1, 26870, 26875, 26871, -1, 26874, 26875, 26870, -1, 26763, 26876, 26760, -1, 26760, 26876, 26758, -1, 26758, 26876, 26756, -1, 26869, 26876, 26763, -1, 26871, 26876, 26873, -1, 26873, 26876, 26869, -1, 26756, 26876, 26875, -1, 26875, 26876, 26871, -1, 26786, 26877, 26878, -1, 26877, 26879, 26878, -1, 26879, 26880, 26878, -1, 26780, 26881, 26782, -1, 26782, 26881, 26784, -1, 26784, 26881, 26786, -1, 26786, 26881, 26877, -1, 26878, 26882, 26788, -1, 26880, 26882, 26878, -1, 26778, 26883, 26779, -1, 26779, 26883, 26780, -1, 26881, 26883, 26877, -1, 26877, 26883, 26879, -1, 26780, 26883, 26881, -1, 26781, 26884, 26778, -1, 26778, 26884, 26883, -1, 26883, 26884, 26879, -1, 26879, 26884, 26880, -1, 26788, 26885, 26785, -1, 26785, 26885, 26783, -1, 26783, 26885, 26781, -1, 26880, 26885, 26882, -1, 26781, 26885, 26884, -1, 26882, 26885, 26788, -1, 26884, 26885, 26880, -1, 26886, 26887, 26828, -1, 26828, 26887, 26800, -1, 26886, 26888, 26889, -1, 26886, 26890, 26888, -1, 26886, 26891, 26890, -1, 26886, 26889, 26892, -1, 26893, 26894, 26895, -1, 26896, 26893, 26895, -1, 26897, 26896, 26895, -1, 26898, 26895, 26899, -1, 26898, 26897, 26895, -1, 26900, 26898, 26899, -1, 26887, 26886, 26892, -1, 26901, 26898, 26900, -1, 26878, 26902, 26903, -1, 26878, 26904, 26902, -1, 26878, 26905, 26904, -1, 26878, 26906, 26905, -1, 26878, 26907, 26906, -1, 26878, 26908, 26907, -1, 26878, 26909, 26908, -1, 26878, 26910, 26909, -1, 26878, 26901, 26910, -1, 26892, 26878, 26887, -1, 26887, 26878, 26903, -1, 26878, 26898, 26901, -1, 26900, 26810, 26809, -1, 26901, 26900, 26809, -1, 26910, 26809, 26808, -1, 26910, 26901, 26809, -1, 26909, 26808, 26807, -1, 26909, 26910, 26808, -1, 26908, 26807, 26806, -1, 26908, 26909, 26807, -1, 26907, 26806, 26805, -1, 26907, 26908, 26806, -1, 26906, 26805, 26804, -1, 26906, 26907, 26805, -1, 26905, 26804, 26803, -1, 26905, 26906, 26804, -1, 26904, 26803, 26802, -1, 26904, 26905, 26803, -1, 26902, 26802, 26799, -1, 26902, 26904, 26802, -1, 26903, 26799, 26801, -1, 26903, 26902, 26799, -1, 26887, 26801, 26800, -1, 26887, 26903, 26801, -1, 26886, 26835, 26891, -1, 26828, 26835, 26886, -1, 26891, 26836, 26890, -1, 26835, 26836, 26891, -1, 26890, 26838, 26888, -1, 26836, 26838, 26890, -1, 26888, 26839, 26889, -1, 26838, 26839, 26888, -1, 26900, 26826, 26810, -1, 26900, 26899, 26826, -1, 26892, 26839, 26854, -1, 26892, 26889, 26839, -1, 26827, 26911, 26899, -1, 26911, 26912, 26899, -1, 26833, 26913, 26834, -1, 26834, 26913, 26837, -1, 26837, 26913, 26827, -1, 26827, 26913, 26911, -1, 26912, 26914, 26899, -1, 26831, 26915, 26832, -1, 26832, 26915, 26833, -1, 26833, 26915, 26913, -1, 26913, 26915, 26911, -1, 26911, 26915, 26912, -1, 26826, 26916, 26829, -1, 26829, 26916, 26830, -1, 26830, 26916, 26831, -1, 26899, 26916, 26826, -1, 26831, 26916, 26915, -1, 26912, 26916, 26914, -1, 26915, 26916, 26912, -1, 26914, 26916, 26899, -1, 26854, 26917, 26892, -1, 26917, 26918, 26892, -1, 26848, 26919, 26850, -1, 26850, 26919, 26852, -1, 26852, 26919, 26854, -1, 26854, 26919, 26917, -1, 26918, 26920, 26892, -1, 26846, 26921, 26847, -1, 26847, 26921, 26848, -1, 26848, 26921, 26919, -1, 26919, 26921, 26917, -1, 26917, 26921, 26918, -1, 26920, 26922, 26892, -1, 26844, 26923, 26845, -1, 26845, 26923, 26846, -1, 26846, 26923, 26921, -1, 26921, 26923, 26918, -1, 26918, 26923, 26920, -1, 26892, 26924, 26842, -1, 26842, 26924, 26840, -1, 26840, 26924, 26843, -1, 26843, 26924, 26844, -1, 26844, 26924, 26923, -1, 26922, 26924, 26892, -1, 26920, 26924, 26922, -1, 26923, 26924, 26920, -1, 26899, 26895, 26827, -1, 26827, 26895, 26825, -1, 26790, 26892, 26842, -1, 26878, 26892, 26790, -1, 26814, 26819, 26898, -1, 26898, 26819, 26897, -1, 26897, 26821, 26896, -1, 26819, 26821, 26897, -1, 26896, 26823, 26893, -1, 26821, 26823, 26896, -1, 26893, 26824, 26894, -1, 26823, 26824, 26893, -1, 26894, 26825, 26895, -1, 26824, 26825, 26894, -1, 26790, 26789, 26878, -1, 26789, 26787, 26878, -1, 26787, 26786, 26878, -1, 26898, 26788, 26814, -1, 26898, 26878, 26788, -1, 26925, 26869, 26791, -1, 26791, 26869, 26763, -1, 26926, 26927, 26928, -1, 26926, 26929, 26927, -1, 26926, 26930, 26929, -1, 26926, 26928, 26931, -1, 26925, 26932, 26933, -1, 26925, 26934, 26932, -1, 26925, 26935, 26934, -1, 26925, 26936, 26935, -1, 26925, 26933, 26937, -1, 26938, 26926, 26931, -1, 26869, 26939, 26938, -1, 26869, 26940, 26939, -1, 26869, 26941, 26940, -1, 26869, 26942, 26941, -1, 26869, 26943, 26942, -1, 26869, 26944, 26943, -1, 26869, 26945, 26944, -1, 26869, 26946, 26945, -1, 26869, 26947, 26946, -1, 26869, 26948, 26947, -1, 26869, 26949, 26948, -1, 26931, 26869, 26938, -1, 26869, 26925, 26949, -1, 26937, 26949, 26925, -1, 26765, 26764, 26869, -1, 26764, 26762, 26869, -1, 26762, 26761, 26869, -1, 26925, 26792, 26936, -1, 26791, 26792, 26925, -1, 26936, 26794, 26935, -1, 26792, 26794, 26936, -1, 26935, 26798, 26934, -1, 26794, 26798, 26935, -1, 26934, 26796, 26932, -1, 26798, 26796, 26934, -1, 26932, 26797, 26933, -1, 26796, 26797, 26932, -1, 26869, 26858, 26765, -1, 26869, 26931, 26858, -1, 26811, 26933, 26797, -1, 26937, 26933, 26811, -1, 26867, 26950, 26931, -1, 26950, 26951, 26931, -1, 26864, 26952, 26865, -1, 26865, 26952, 26866, -1, 26866, 26952, 26867, -1, 26867, 26952, 26950, -1, 26951, 26953, 26931, -1, 26862, 26954, 26863, -1, 26863, 26954, 26864, -1, 26864, 26954, 26952, -1, 26952, 26954, 26950, -1, 26950, 26954, 26951, -1, 26953, 26955, 26931, -1, 26860, 26956, 26861, -1, 26861, 26956, 26862, -1, 26862, 26956, 26954, -1, 26954, 26956, 26951, -1, 26951, 26956, 26953, -1, 26858, 26957, 26856, -1, 26856, 26957, 26859, -1, 26859, 26957, 26860, -1, 26931, 26957, 26858, -1, 26955, 26957, 26931, -1, 26860, 26957, 26956, -1, 26953, 26957, 26955, -1, 26956, 26957, 26953, -1, 26811, 26958, 26937, -1, 26958, 26959, 26937, -1, 26820, 26960, 26822, -1, 26822, 26960, 26812, -1, 26812, 26960, 26811, -1, 26811, 26960, 26958, -1, 26959, 26961, 26937, -1, 26817, 26962, 26818, -1, 26818, 26962, 26820, -1, 26820, 26962, 26960, -1, 26960, 26962, 26958, -1, 26958, 26962, 26959, -1, 26937, 26963, 26815, -1, 26815, 26963, 26813, -1, 26813, 26963, 26816, -1, 26816, 26963, 26817, -1, 26817, 26963, 26962, -1, 26962, 26963, 26959, -1, 26961, 26963, 26937, -1, 26959, 26963, 26961, -1, 26931, 26855, 26867, -1, 26931, 26928, 26855, -1, 26767, 26937, 26815, -1, 26949, 26937, 26767, -1, 26841, 26849, 26926, -1, 26926, 26849, 26930, -1, 26930, 26851, 26929, -1, 26849, 26851, 26930, -1, 26929, 26853, 26927, -1, 26851, 26853, 26929, -1, 26927, 26855, 26928, -1, 26853, 26855, 26927, -1, 26948, 26949, 26767, -1, 26948, 26774, 26773, -1, 26948, 26767, 26774, -1, 26947, 26773, 26772, -1, 26947, 26948, 26773, -1, 26946, 26772, 26771, -1, 26946, 26947, 26772, -1, 26945, 26946, 26771, -1, 26944, 26771, 26770, -1, 26944, 26945, 26771, -1, 26943, 26770, 26769, -1, 26943, 26944, 26770, -1, 26942, 26769, 26766, -1, 26942, 26943, 26769, -1, 26941, 26766, 26768, -1, 26941, 26942, 26766, -1, 26940, 26768, 26775, -1, 26940, 26941, 26768, -1, 26939, 26775, 26777, -1, 26939, 26940, 26775, -1, 26938, 26777, 26776, -1, 26938, 26939, 26777, -1, 26926, 26938, 26841, -1, 26841, 26938, 26776, -1, 26964, 26965, 26966, -1, 26967, 26965, 26964, -1, 26966, 26968, 26969, -1, 26969, 26968, 26970, -1, 26965, 26968, 26966, -1, 26970, 23653, 23652, -1, 26968, 23653, 26970, -1, 26967, 26971, 26972, -1, 26964, 26971, 26967, -1, 26971, 26973, 26972, -1, 26751, 26974, 26975, -1, 26857, 26974, 26751, -1, 26975, 26976, 26977, -1, 26974, 26976, 26975, -1, 26977, 26978, 26979, -1, 26976, 26978, 26977, -1, 26978, 26980, 26979, -1, 26979, 26981, 26982, -1, 26980, 26981, 26979, -1, 26982, 26983, 26674, -1, 26981, 26983, 26982, -1, 26983, 26673, 26674, -1, 26741, 26742, 26984, -1, 26984, 26985, 26986, -1, 26742, 26985, 26984, -1, 26986, 26987, 26988, -1, 26988, 26987, 26989, -1, 26985, 26987, 26986, -1, 26989, 26990, 26991, -1, 26987, 26990, 26989, -1, 26991, 26992, 26993, -1, 26990, 26992, 26991, -1, 26993, 26972, 26994, -1, 26994, 26972, 26973, -1, 26992, 26972, 26993, -1, 26745, 18932, 24943, -1, 26995, 24943, 24947, -1, 26995, 26747, 24943, -1, 26996, 26747, 26995, -1, 26749, 26747, 26996, -1, 26997, 26747, 26745, -1, 26997, 26745, 24943, -1, 26997, 24943, 26747, -1, 26793, 26998, 26999, -1, 26793, 26999, 26795, -1, 26996, 27000, 26998, -1, 26996, 26793, 26749, -1, 26996, 26998, 26793, -1, 26995, 27001, 27000, -1, 26995, 27000, 26996, -1, 24947, 24944, 27001, -1, 24947, 27001, 26995, -1, 27001, 24944, 24952, -1, 27001, 24952, 27002, -1, 27000, 27002, 27003, -1, 27000, 27001, 27002, -1, 26998, 27003, 27004, -1, 26998, 27004, 27005, -1, 26998, 27000, 27003, -1, 26999, 27005, 26857, -1, 26999, 26998, 27005, -1, 26795, 26999, 26857, -1, 26974, 27004, 27003, -1, 26974, 27005, 27004, -1, 26974, 26857, 27005, -1, 27006, 24971, 24972, -1, 26673, 26983, 27007, -1, 27008, 27002, 24952, -1, 27008, 24952, 24969, -1, 27009, 27003, 27002, -1, 27009, 27002, 27008, -1, 27009, 26974, 27003, -1, 27010, 26976, 26974, -1, 27010, 26974, 27009, -1, 27011, 24969, 24968, -1, 27011, 27008, 24969, -1, 27012, 27008, 27011, -1, 27012, 27009, 27008, -1, 27013, 24968, 24970, -1, 27013, 27011, 24968, -1, 27014, 27010, 27009, -1, 27014, 26976, 27010, -1, 27014, 27009, 27012, -1, 27015, 27012, 27011, -1, 27015, 27011, 27013, -1, 27016, 26980, 26978, -1, 27016, 26978, 26976, -1, 27016, 26976, 27014, -1, 27017, 24970, 24971, -1, 27017, 27013, 24970, -1, 27018, 27014, 27012, -1, 27018, 27012, 27015, -1, 27019, 27006, 27007, -1, 27019, 27015, 27013, -1, 27019, 27017, 24971, -1, 27019, 24971, 27006, -1, 27019, 27013, 27017, -1, 27020, 26981, 26980, -1, 27020, 26980, 27016, -1, 27020, 27014, 27018, -1, 27020, 27016, 27014, -1, 27021, 26983, 26981, -1, 27021, 26981, 27020, -1, 27021, 27015, 27019, -1, 27021, 27007, 26983, -1, 27021, 27019, 27007, -1, 27021, 27018, 27015, -1, 27021, 27020, 27018, -1, 27006, 24972, 24975, -1, 27006, 24975, 24983, -1, 27007, 24983, 24984, -1, 27007, 24984, 24986, -1, 27007, 27006, 24983, -1, 26673, 27007, 24986, -1, 26651, 24987, 24985, -1, 27022, 24981, 24951, -1, 27023, 24981, 27022, -1, 27024, 24981, 27023, -1, 27025, 24982, 24976, -1, 27025, 24976, 24977, -1, 27026, 24985, 24982, -1, 27026, 24982, 27025, -1, 27027, 26653, 26651, -1, 27027, 26651, 24985, -1, 27027, 24985, 27026, -1, 27028, 24977, 24978, -1, 27028, 27025, 24977, -1, 27029, 27025, 27028, -1, 27029, 27026, 27025, -1, 27030, 26654, 26653, -1, 27030, 27027, 27026, -1, 27030, 26653, 27027, -1, 27030, 27026, 27029, -1, 27031, 24978, 24979, -1, 27031, 27028, 24978, -1, 27032, 27029, 27028, -1, 27032, 27028, 27031, -1, 27033, 27029, 27032, -1, 27033, 27030, 27029, -1, 27034, 24979, 24980, -1, 27034, 24980, 24981, -1, 27034, 27031, 24979, -1, 27035, 27034, 24981, -1, 27035, 27032, 27031, -1, 27035, 24981, 27024, -1, 27035, 27031, 27034, -1, 27036, 26658, 26656, -1, 27036, 26656, 26654, -1, 27036, 26654, 27030, -1, 27036, 27030, 27033, -1, 27037, 27024, 27038, -1, 27037, 27033, 27032, -1, 27037, 27035, 27024, -1, 27037, 27032, 27035, -1, 27039, 27038, 26415, -1, 27039, 26415, 26658, -1, 27039, 27037, 27038, -1, 27039, 26658, 27036, -1, 27039, 27036, 27033, -1, 27039, 27033, 27037, -1, 27022, 24951, 24790, -1, 27022, 24790, 27040, -1, 27023, 27040, 27041, -1, 27023, 27022, 27040, -1, 27024, 27041, 27042, -1, 27024, 27023, 27041, -1, 27038, 27042, 27043, -1, 27038, 27024, 27042, -1, 26415, 27043, 26510, -1, 26415, 27038, 27043, -1, 27044, 26510, 27043, -1, 27044, 27045, 26395, -1, 27044, 26395, 26522, -1, 27044, 26522, 26510, -1, 27046, 27042, 27041, -1, 27046, 27043, 27042, -1, 27046, 27047, 27045, -1, 27046, 27045, 27044, -1, 27046, 27044, 27043, -1, 27048, 27040, 24790, -1, 27048, 27041, 27040, -1, 27048, 24790, 24794, -1, 27048, 24794, 27047, -1, 27048, 27046, 27041, -1, 27048, 27047, 27046, -1, 24792, 26399, 26397, -1, 24792, 19819, 26399, -1, 27045, 26397, 26395, -1, 27047, 24792, 26397, -1, 27047, 26397, 27045, -1, 24794, 24792, 27047, -1, 27049, 27050, 27051, -1, 27052, 27050, 27049, -1, 27050, 27053, 27051, -1, 27051, 27054, 27055, -1, 27053, 27054, 27051, -1, 27054, 27056, 27055, -1, 27055, 27057, 18855, -1, 27056, 27057, 27055, -1, 27057, 18854, 18855, -1, 27058, 27059, 27060, -1, 27059, 27052, 27049, -1, 27058, 27052, 27059, -1, 27061, 27058, 27060, -1, 27061, 27060, 27062, -1, 27063, 27062, 27064, -1, 27063, 27061, 27062, -1, 27065, 27064, 27066, -1, 27065, 27063, 27064, -1, 27067, 27068, 27069, -1, 27067, 27070, 27068, -1, 27071, 27072, 27073, -1, 27073, 27072, 27074, -1, 27074, 27072, 27075, -1, 27075, 27072, 27076, -1, 27077, 27078, 27079, -1, 27079, 27078, 27080, -1, 27080, 27078, 27081, -1, 27082, 27078, 27077, -1, 27083, 27078, 27082, -1, 27084, 27085, 27076, -1, 27072, 27086, 27076, -1, 27076, 27086, 27084, -1, 27081, 27065, 27066, -1, 27078, 27065, 27081, -1, 27085, 27087, 27076, -1, 27072, 27088, 27086, -1, 27072, 27089, 27088, -1, 27072, 27090, 27089, -1, 27091, 27092, 27072, -1, 27072, 27092, 27090, -1, 27093, 27094, 27091, -1, 27094, 27095, 27091, -1, 27091, 27096, 27092, -1, 27087, 27097, 27076, -1, 27095, 27098, 27091, -1, 27091, 27099, 27096, -1, 27098, 27100, 27091, -1, 27091, 27101, 27099, -1, 27100, 27083, 27091, -1, 27091, 27083, 27101, -1, 27083, 27102, 27101, -1, 27083, 27103, 27102, -1, 27087, 27104, 27097, -1, 27083, 27082, 27103, -1, 27097, 27105, 27106, -1, 27106, 27105, 27107, -1, 27107, 27105, 27069, -1, 27104, 27105, 27097, -1, 27105, 27108, 27069, -1, 27108, 27067, 27069, -1, 27109, 27110, 27111, -1, 27112, 27084, 27086, -1, 27113, 27114, 27115, -1, 27116, 27087, 27085, -1, 27116, 27085, 27084, -1, 27116, 27117, 27087, -1, 27118, 27119, 27117, -1, 27118, 27117, 27116, -1, 27120, 27121, 27119, -1, 27120, 27119, 27118, -1, 27122, 27114, 27109, -1, 27122, 27111, 27121, -1, 27122, 27109, 27111, -1, 27122, 27121, 27120, -1, 27123, 27112, 27124, -1, 27123, 27124, 27125, -1, 27123, 27125, 27115, -1, 27123, 27118, 27116, -1, 27123, 27114, 27122, -1, 27123, 27084, 27112, -1, 27123, 27116, 27084, -1, 27123, 27122, 27120, -1, 27123, 27115, 27114, -1, 27123, 27120, 27118, -1, 27126, 27127, 27128, -1, 27129, 27099, 27101, -1, 27130, 27131, 27132, -1, 27133, 27092, 27096, -1, 27133, 27096, 27099, -1, 27133, 27134, 27092, -1, 27135, 27136, 27134, -1, 27135, 27134, 27133, -1, 27137, 27138, 27136, -1, 27137, 27136, 27135, -1, 27139, 27131, 27126, -1, 27139, 27128, 27138, -1, 27139, 27126, 27128, -1, 27139, 27138, 27137, -1, 27140, 27129, 27141, -1, 27140, 27141, 27142, -1, 27140, 27142, 27132, -1, 27140, 27135, 27133, -1, 27140, 27131, 27139, -1, 27140, 27099, 27129, -1, 27140, 27133, 27099, -1, 27140, 27139, 27137, -1, 27140, 27132, 27131, -1, 27140, 27137, 27135, -1, 27143, 27144, 27145, -1, 27143, 27145, 27146, -1, 27147, 27146, 27148, -1, 27147, 27143, 27146, -1, 27149, 27150, 27068, -1, 27149, 27148, 27150, -1, 27149, 27147, 27148, -1, 27070, 27149, 27068, -1, 27144, 27151, 27145, -1, 27151, 27152, 27145, -1, 27151, 27153, 27152, -1, 27153, 27154, 27152, -1, 27152, 27154, 27155, -1, 27155, 27156, 27157, -1, 27154, 27156, 27155, -1, 27157, 27158, 27159, -1, 27156, 27158, 27157, -1, 27159, 18739, 18738, -1, 27158, 18739, 27159, -1, 24961, 24953, 27160, -1, 24961, 27160, 27110, -1, 24967, 24960, 27161, -1, 24967, 27161, 27127, -1, 27162, 24957, 27163, -1, 24950, 24957, 27162, -1, 24789, 24949, 27164, -1, 24791, 24949, 24789, -1, 27164, 24948, 27165, -1, 24949, 24948, 27164, -1, 27165, 24950, 27162, -1, 24948, 24950, 27165, -1, 24946, 24945, 24973, -1, 24973, 27166, 24974, -1, 24945, 27166, 24973, -1, 24974, 27167, 24953, -1, 27166, 27167, 24974, -1, 27167, 27160, 24953, -1, 27168, 17898, 17897, -1, 27168, 17897, 27169, -1, 27170, 27169, 27171, -1, 27170, 27168, 27169, -1, 27172, 27171, 27173, -1, 27172, 27170, 27171, -1, 27174, 27173, 27175, -1, 27176, 27175, 27173, -1, 27177, 27173, 27174, -1, 27178, 27176, 27173, -1, 27179, 27173, 27177, -1, 27180, 27178, 27173, -1, 27181, 27173, 27179, -1, 27172, 27181, 27182, -1, 27172, 27173, 27181, -1, 27183, 27172, 27182, -1, 27184, 27172, 27183, -1, 27185, 27172, 27184, -1, 27186, 27172, 27185, -1, 27187, 27172, 27186, -1, 27188, 27180, 27173, -1, 27189, 27180, 27188, -1, 27190, 27187, 27191, -1, 27190, 27172, 27187, -1, 27192, 25632, 27193, -1, 27192, 27194, 25632, -1, 27195, 27192, 27196, -1, 27197, 27189, 27188, -1, 27197, 27188, 27198, -1, 27199, 27198, 27200, -1, 27199, 27197, 27198, -1, 27201, 27199, 27200, -1, 27202, 27201, 27200, -1, 27203, 27200, 27204, -1, 27203, 27202, 27200, -1, 27205, 27203, 27204, -1, 27206, 27205, 27204, -1, 27207, 27208, 27209, -1, 27207, 27190, 27191, -1, 27207, 27191, 27208, -1, 27210, 27206, 27204, -1, 27211, 27210, 27204, -1, 27212, 27211, 27204, -1, 25627, 27212, 27204, -1, 27193, 25627, 27204, -1, 25632, 25627, 27193, -1, 27213, 27209, 27214, -1, 27213, 27214, 27215, -1, 27213, 27216, 27217, -1, 27213, 27218, 27216, -1, 27213, 27219, 27218, -1, 27213, 27215, 27219, -1, 27213, 27207, 27209, -1, 27194, 27220, 25632, -1, 27194, 27217, 27220, -1, 27194, 27213, 27217, -1, 27192, 27193, 27196, -1, 27221, 27222, 27195, -1, 27221, 27195, 27196, -1, 27223, 27221, 27224, -1, 27223, 27222, 27221, -1, 27203, 27199, 27202, -1, 27202, 27199, 27201, -1, 27199, 27225, 27226, -1, 27203, 27225, 27199, -1, 27227, 27228, 27229, -1, 27227, 27230, 27228, -1, 27230, 27231, 27228, -1, 27230, 27232, 27231, -1, 27232, 27233, 27231, -1, 27232, 27234, 27233, -1, 27234, 27235, 27233, -1, 27234, 27236, 27235, -1, 27236, 27237, 27235, -1, 27236, 27238, 27237, -1, 27238, 27239, 27237, -1, 27238, 27240, 27239, -1, 27240, 27241, 27239, -1, 27240, 27242, 27241, -1, 27242, 27243, 27241, -1, 27242, 27244, 27243, -1, 27244, 27245, 27243, -1, 27244, 27246, 27245, -1, 27246, 27247, 27245, -1, 27246, 27248, 27247, -1, 27248, 27249, 27247, -1, 27248, 27250, 27249, -1, 27250, 27251, 27249, -1, 27250, 27252, 27251, -1, 27252, 27225, 27251, -1, 27252, 27226, 27225, -1, 27229, 27208, 27227, -1, 27208, 27214, 27209, -1, 27208, 27215, 27214, -1, 27229, 27215, 27208, -1, 27222, 27223, 25181, -1, 27222, 25181, 25171, -1, 27253, 25170, 25193, -1, 27253, 25171, 25170, -1, 27253, 27222, 25171, -1, 27254, 25193, 25189, -1, 27254, 27253, 25193, -1, 27255, 25189, 25183, -1, 27255, 27254, 25189, -1, 27256, 27255, 25183, -1, 27257, 25183, 25139, -1, 27257, 27256, 25183, -1, 25141, 27257, 25139, -1, 24961, 27110, 24959, -1, 24959, 27109, 24958, -1, 27110, 27109, 24959, -1, 24958, 27114, 24956, -1, 27109, 27114, 24958, -1, 24956, 27113, 24954, -1, 27114, 27113, 24956, -1, 24954, 27258, 24955, -1, 27113, 27258, 24954, -1, 27258, 27259, 24955, -1, 24955, 27161, 24960, -1, 27259, 27161, 24955, -1, 24967, 27127, 24966, -1, 24966, 27126, 24964, -1, 27127, 27126, 24966, -1, 24964, 27131, 24962, -1, 27126, 27131, 24964, -1, 24962, 27130, 24963, -1, 27131, 27130, 24962, -1, 24963, 27260, 24965, -1, 27130, 27260, 24963, -1, 27260, 27261, 24965, -1, 24965, 27163, 24957, -1, 27261, 27163, 24965, -1, 15652, 16139, 16146, -1, 15652, 15542, 16139, -1, 15651, 16146, 16147, -1, 15651, 15652, 16146, -1, 15649, 16147, 16148, -1, 15649, 16148, 16145, -1, 15649, 15651, 16147, -1, 15650, 15649, 16145, -1, 16151, 16152, 15654, -1, 15654, 16152, 15658, -1, 15658, 16155, 15660, -1, 16152, 16155, 15658, -1, 15660, 16059, 15530, -1, 16155, 16059, 15660, -1, 15530, 16058, 15532, -1, 16059, 16058, 15530, -1, 27262, 27263, 27264, -1, 27262, 27264, 27265, -1, 27266, 27265, 27267, -1, 27266, 27262, 27265, -1, 27268, 27267, 27269, -1, 27268, 27266, 27267, -1, 22167, 27269, 22166, -1, 22167, 27268, 27269, -1, 27263, 27270, 27264, -1, 27264, 27270, 27271, -1, 27271, 27272, 27273, -1, 27273, 27272, 27274, -1, 27270, 27272, 27271, -1, 27272, 27275, 27274, -1, 27274, 27276, 27277, -1, 27277, 27276, 27278, -1, 27275, 27276, 27274, -1, 27276, 27279, 27278, -1, 27279, 27280, 27278, -1, 27280, 27281, 27282, -1, 27282, 27281, 27283, -1, 27279, 27281, 27280, -1, 27281, 27284, 27283, -1, 27281, 27285, 27284, -1, 27285, 27286, 27287, -1, 27287, 27286, 27288, -1, 27288, 27286, 27289, -1, 27281, 27286, 27285, -1, 27290, 27291, 27292, -1, 27293, 27294, 27295, -1, 27293, 27296, 27294, -1, 27293, 27295, 27297, -1, 27298, 27299, 27300, -1, 27298, 27300, 27290, -1, 27301, 27297, 27302, -1, 27301, 27302, 27303, -1, 27301, 27293, 27297, -1, 27301, 27292, 27296, -1, 27301, 27296, 27293, -1, 27304, 27157, 27159, -1, 27304, 27159, 27305, -1, 27304, 27305, 27299, -1, 27304, 27299, 27298, -1, 27306, 27301, 27303, -1, 27306, 27290, 27292, -1, 27306, 27292, 27301, -1, 27307, 27303, 27308, -1, 27307, 27308, 27309, -1, 27307, 27298, 27290, -1, 27307, 27290, 27306, -1, 27307, 27306, 27303, -1, 27310, 27309, 27152, -1, 27310, 27152, 27155, -1, 27310, 27155, 27157, -1, 27310, 27307, 27309, -1, 27310, 27298, 27307, -1, 27159, 18738, 18736, -1, 27310, 27157, 27304, -1, 27310, 27304, 27298, -1, 27311, 17916, 17910, -1, 27312, 18726, 17912, -1, 27312, 17912, 17921, -1, 27313, 18728, 18726, -1, 27313, 18726, 27312, -1, 27291, 18730, 18728, -1, 27291, 18728, 27313, -1, 27294, 17921, 17917, -1, 27294, 27312, 17921, -1, 27300, 18732, 18730, -1, 27300, 18730, 27291, -1, 27296, 27313, 27312, -1, 27296, 27312, 27294, -1, 27299, 18734, 18732, -1, 27299, 18732, 27300, -1, 27292, 27291, 27313, -1, 27292, 27313, 27296, -1, 27295, 17917, 17916, -1, 27295, 27311, 27297, -1, 27295, 27294, 17917, -1, 27295, 17916, 27311, -1, 27305, 18736, 18734, -1, 27305, 18734, 27299, -1, 27305, 27159, 18736, -1, 27290, 27300, 27291, -1, 27314, 27152, 27309, -1, 27314, 27145, 27152, -1, 27315, 27309, 27308, -1, 27315, 27314, 27309, -1, 27316, 27308, 27303, -1, 27316, 27315, 27308, -1, 27317, 27303, 27302, -1, 27317, 27316, 27303, -1, 27318, 27302, 27297, -1, 27318, 27317, 27302, -1, 27319, 27311, 17910, -1, 27319, 27297, 27311, -1, 27319, 27318, 27297, -1, 17890, 27319, 17910, -1, 27320, 27321, 27322, -1, 27320, 27322, 27323, -1, 27324, 27325, 27326, -1, 27324, 17893, 27325, -1, 27324, 27326, 27327, -1, 27328, 27315, 27316, -1, 27328, 27323, 27329, -1, 27328, 27330, 27315, -1, 27328, 27329, 27330, -1, 27331, 27327, 27321, -1, 27331, 27321, 27320, -1, 27332, 27316, 27317, -1, 27332, 27328, 27316, -1, 27332, 27320, 27323, -1, 27332, 27323, 27328, -1, 27333, 17891, 17893, -1, 27333, 17893, 27324, -1, 27333, 27324, 27327, -1, 27333, 27327, 27331, -1, 27334, 27317, 27318, -1, 27334, 27331, 27320, -1, 27334, 27332, 27317, -1, 27334, 27320, 27332, -1, 27335, 27318, 27319, -1, 27335, 17892, 17891, -1, 27335, 17891, 27333, -1, 27335, 27333, 27331, -1, 27335, 27331, 27334, -1, 27335, 27319, 17892, -1, 27335, 27334, 27318, -1, 17893, 17894, 27325, -1, 17890, 17892, 27319, -1, 27336, 27337, 27068, -1, 27336, 27068, 27150, -1, 27338, 27339, 27337, -1, 27338, 27337, 27336, -1, 27340, 27150, 27148, -1, 27340, 27336, 27150, -1, 27322, 27341, 27339, -1, 27322, 27339, 27338, -1, 27329, 27338, 27336, -1, 27329, 27336, 27340, -1, 27321, 27342, 27341, -1, 27321, 27341, 27322, -1, 27343, 27145, 27314, -1, 27343, 27148, 27146, -1, 27343, 27146, 27145, -1, 27343, 27340, 27148, -1, 27323, 27338, 27329, -1, 27323, 27322, 27338, -1, 27327, 27326, 27342, -1, 27327, 27342, 27321, -1, 27330, 27314, 27315, -1, 27330, 27343, 27314, -1, 27330, 27329, 27340, -1, 27330, 27340, 27343, -1, 27069, 27068, 27337, -1, 27344, 27337, 27339, -1, 27344, 27069, 27337, -1, 27345, 27339, 27341, -1, 27345, 27344, 27339, -1, 27346, 27341, 27342, -1, 27346, 27345, 27341, -1, 27347, 27342, 27326, -1, 27347, 27346, 27342, -1, 27348, 27326, 27325, -1, 27348, 27347, 27326, -1, 27349, 27325, 17894, -1, 27349, 27348, 27325, -1, 17898, 27349, 17894, -1, 27350, 27170, 27351, -1, 27350, 27349, 27168, -1, 27350, 27351, 27352, -1, 27350, 27353, 27348, -1, 27350, 27352, 27353, -1, 27344, 27107, 27069, -1, 27170, 27172, 27354, -1, 17898, 27168, 27349, -1, 27355, 27356, 27097, -1, 27355, 27097, 27106, -1, 27357, 27358, 27356, -1, 27357, 27356, 27355, -1, 27359, 27106, 27107, -1, 27359, 27107, 27344, -1, 27359, 27355, 27106, -1, 27360, 27361, 27358, -1, 27360, 27358, 27357, -1, 27362, 27344, 27345, -1, 27362, 27357, 27355, -1, 27362, 27359, 27344, -1, 27362, 27355, 27359, -1, 27363, 27364, 27361, -1, 27363, 27361, 27360, -1, 27365, 27345, 27346, -1, 27365, 27362, 27345, -1, 27365, 27357, 27362, -1, 27365, 27360, 27357, -1, 27352, 27366, 27364, -1, 27352, 27364, 27363, -1, 27367, 27346, 27347, -1, 27367, 27363, 27360, -1, 27367, 27360, 27365, -1, 27367, 27365, 27346, -1, 27351, 27354, 27366, -1, 27351, 27170, 27354, -1, 27351, 27366, 27352, -1, 27353, 27347, 27348, -1, 27353, 27367, 27347, -1, 27353, 27363, 27367, -1, 27353, 27352, 27363, -1, 27350, 27348, 27349, -1, 27350, 27168, 27170, -1, 16710, 27368, 16711, -1, 27056, 27054, 27369, -1, 27056, 27369, 27368, -1, 27056, 27368, 16710, -1, 27057, 16710, 16726, -1, 27057, 27056, 16710, -1, 21849, 16726, 16708, -1, 21851, 27057, 16726, -1, 21851, 16726, 21849, -1, 18854, 27057, 21851, -1, 27076, 27097, 27356, -1, 27370, 27356, 27358, -1, 27370, 27076, 27356, -1, 27371, 27358, 27361, -1, 27371, 27370, 27358, -1, 27372, 27361, 27364, -1, 27372, 27371, 27361, -1, 27373, 27364, 27366, -1, 27373, 27372, 27364, -1, 27374, 27366, 27354, -1, 27374, 27373, 27366, -1, 27375, 27354, 27172, -1, 27375, 27374, 27354, -1, 27190, 27375, 27172, -1, 27376, 27053, 27050, -1, 27376, 27377, 27053, -1, 27376, 27050, 27378, -1, 27379, 27378, 27380, -1, 27379, 27376, 27378, -1, 27379, 27381, 27377, -1, 27379, 27377, 27376, -1, 27382, 27380, 27383, -1, 27382, 27384, 27381, -1, 27382, 27379, 27380, -1, 27382, 27381, 27379, -1, 27385, 27382, 27383, -1, 27385, 27386, 27384, -1, 27385, 25083, 27386, -1, 27385, 27384, 27382, -1, 27387, 27383, 25075, -1, 27387, 25075, 25081, -1, 27387, 25081, 25083, -1, 27387, 25083, 27385, -1, 27387, 27385, 27383, -1, 27378, 27050, 27052, -1, 27388, 27369, 27054, -1, 27388, 27368, 27369, -1, 27389, 27054, 27053, -1, 27389, 27388, 27054, -1, 27390, 16711, 27368, -1, 27390, 27368, 27388, -1, 27391, 27390, 27388, -1, 27391, 27388, 27389, -1, 27392, 16774, 16709, -1, 27392, 16709, 16711, -1, 27392, 16711, 27390, -1, 27393, 16771, 16773, -1, 27393, 16773, 16774, -1, 27393, 16774, 27392, -1, 27394, 27390, 27391, -1, 27394, 27392, 27390, -1, 27395, 16772, 16771, -1, 27395, 16771, 27393, -1, 27395, 27392, 27394, -1, 27395, 27393, 27392, -1, 27377, 27389, 27053, -1, 27396, 27397, 16772, -1, 27396, 25084, 27397, -1, 27396, 16772, 27395, -1, 27381, 27391, 27389, -1, 27381, 27389, 27377, -1, 27384, 27394, 27391, -1, 27384, 27391, 27381, -1, 27386, 27395, 27394, -1, 27386, 27394, 27384, -1, 27398, 25083, 25084, -1, 27398, 25084, 27396, -1, 27398, 27396, 27395, -1, 27398, 27386, 25083, -1, 27398, 27395, 27386, -1, 27399, 27400, 27401, -1, 27399, 27402, 27400, -1, 27403, 27404, 27405, -1, 27403, 27405, 27406, -1, 27407, 27073, 27074, -1, 27407, 27074, 27408, -1, 27407, 27408, 27402, -1, 27407, 27402, 27399, -1, 27409, 27410, 27404, -1, 27409, 27404, 27403, -1, 27411, 27194, 27192, -1, 27411, 27192, 27195, -1, 27411, 27195, 27412, -1, 27411, 27406, 27194, -1, 27413, 27410, 27409, -1, 27413, 27401, 27410, -1, 27075, 27076, 27370, -1, 27414, 27412, 27415, -1, 27414, 27411, 27412, -1, 27414, 27403, 27406, -1, 27414, 27406, 27411, -1, 27416, 27399, 27401, -1, 27416, 27401, 27413, -1, 27417, 27415, 27418, -1, 27417, 27414, 27415, -1, 27417, 27409, 27403, -1, 27417, 27403, 27414, -1, 27419, 27071, 27073, -1, 27419, 27073, 27407, -1, 27419, 27407, 27399, -1, 27419, 27399, 27416, -1, 27420, 27409, 27417, -1, 27420, 27418, 27421, -1, 27420, 27417, 27418, -1, 27420, 27413, 27409, -1, 27422, 27413, 27420, -1, 27422, 27421, 27423, -1, 27422, 27420, 27421, -1, 27422, 27416, 27413, -1, 27424, 27419, 27416, -1, 27424, 27416, 27422, -1, 27424, 27422, 27423, -1, 27424, 27423, 27072, -1, 27424, 27072, 27071, -1, 27424, 27071, 27419, -1, 27425, 27375, 27190, -1, 27425, 27190, 27207, -1, 27426, 27374, 27375, -1, 27426, 27375, 27425, -1, 27427, 27373, 27374, -1, 27427, 27372, 27373, -1, 27427, 27374, 27426, -1, 27400, 27371, 27372, -1, 27400, 27372, 27427, -1, 27405, 27207, 27213, -1, 27405, 27213, 27194, -1, 27405, 27425, 27207, -1, 27402, 27371, 27400, -1, 27404, 27426, 27425, -1, 27404, 27425, 27405, -1, 27408, 27370, 27371, -1, 27408, 27074, 27075, -1, 27408, 27075, 27370, -1, 27408, 27371, 27402, -1, 27410, 27427, 27426, -1, 27410, 27426, 27404, -1, 27401, 27400, 27427, -1, 27401, 27427, 27410, -1, 27406, 27405, 27194, -1, 27378, 27052, 27058, -1, 27378, 27058, 27428, -1, 27380, 27428, 27429, -1, 27380, 27378, 27428, -1, 27383, 27429, 27430, -1, 27383, 27380, 27429, -1, 25075, 27430, 25074, -1, 25075, 27383, 27430, -1, 27431, 27072, 27423, -1, 27431, 27091, 27072, -1, 27432, 27423, 27421, -1, 27432, 27431, 27423, -1, 27433, 27421, 27418, -1, 27433, 27432, 27421, -1, 27434, 27418, 27415, -1, 27434, 27433, 27418, -1, 27435, 27415, 27412, -1, 27435, 27434, 27415, -1, 27222, 27412, 27195, -1, 27222, 27435, 27412, -1, 25072, 27436, 25068, -1, 27430, 25073, 25074, -1, 27429, 25073, 27430, -1, 27437, 25072, 25071, -1, 27437, 27436, 25072, -1, 27438, 27439, 27436, -1, 27438, 27437, 25071, -1, 27438, 27436, 27437, -1, 27440, 27061, 27063, -1, 27440, 27063, 27065, -1, 27440, 27065, 27441, -1, 27440, 27441, 27439, -1, 27440, 27439, 27438, -1, 27442, 25071, 25073, -1, 27443, 27429, 27428, -1, 27443, 27438, 25071, -1, 27443, 25071, 27442, -1, 27443, 27442, 25073, -1, 27443, 25073, 27429, -1, 27444, 27428, 27058, -1, 27444, 27058, 27061, -1, 27444, 27061, 27440, -1, 27444, 27438, 27443, -1, 27444, 27443, 27428, -1, 27444, 27440, 27438, -1, 27445, 27446, 27447, -1, 27445, 27447, 27448, -1, 27449, 27450, 27451, -1, 27449, 27451, 27452, -1, 27453, 27446, 27445, -1, 27453, 27454, 27446, -1, 27455, 27450, 27449, -1, 27455, 27448, 27450, -1, 27456, 27095, 27094, -1, 27456, 27094, 27457, -1, 27456, 27457, 27454, -1, 27456, 27454, 27453, -1, 27458, 27255, 27256, -1, 27458, 27256, 27257, -1, 27458, 27452, 27255, -1, 27093, 27091, 27431, -1, 27459, 27445, 27448, -1, 27459, 27448, 27455, -1, 27460, 27449, 27452, -1, 27460, 27452, 27458, -1, 27461, 27445, 27459, -1, 27461, 27453, 27445, -1, 27462, 27257, 25141, -1, 27462, 25141, 27463, -1, 27462, 27458, 27257, -1, 27464, 27455, 27449, -1, 27464, 27449, 27460, -1, 27465, 27453, 27461, -1, 27465, 27098, 27095, -1, 27465, 27095, 27456, -1, 27465, 27456, 27453, -1, 27466, 27460, 27458, -1, 27466, 27462, 27463, -1, 27466, 27463, 27467, -1, 27466, 27458, 27462, -1, 27468, 27455, 27464, -1, 27468, 27459, 27455, -1, 27469, 27464, 27460, -1, 27469, 27466, 27467, -1, 27469, 27467, 27470, -1, 27471, 27435, 27222, -1, 27469, 27460, 27466, -1, 27472, 27461, 27459, -1, 27471, 27222, 27253, -1, 27472, 27459, 27468, -1, 27473, 27434, 27435, -1, 27474, 27470, 27475, -1, 27473, 27435, 27471, -1, 27474, 27464, 27469, -1, 27447, 27433, 27434, -1, 27474, 27468, 27464, -1, 27474, 27469, 27470, -1, 27476, 27098, 27465, -1, 27476, 27461, 27472, -1, 27447, 27434, 27473, -1, 27476, 27100, 27098, -1, 27451, 27253, 27254, -1, 27476, 27465, 27461, -1, 27477, 27474, 27475, -1, 27477, 27475, 27478, -1, 27451, 27471, 27253, -1, 27477, 27472, 27468, -1, 27477, 27468, 27474, -1, 27446, 27432, 27433, -1, 27479, 27478, 27480, -1, 27479, 27477, 27478, -1, 27479, 27480, 27083, -1, 27479, 27083, 27100, -1, 27446, 27433, 27447, -1, 27479, 27100, 27476, -1, 27479, 27472, 27477, -1, 27479, 27476, 27472, -1, 27450, 27471, 27451, -1, 27450, 27473, 27471, -1, 27454, 27431, 27432, -1, 27454, 27432, 27446, -1, 27448, 27447, 27473, -1, 27448, 27473, 27450, -1, 27457, 27094, 27093, -1, 27457, 27431, 27454, -1, 27457, 27093, 27431, -1, 27452, 27254, 27255, -1, 27452, 27451, 27254, -1, 27441, 27065, 27078, -1, 27441, 27078, 27481, -1, 27439, 27481, 27482, -1, 27439, 27441, 27481, -1, 27436, 27482, 27483, -1, 27436, 27439, 27482, -1, 25068, 27483, 25069, -1, 25068, 27436, 27483, -1, 27484, 27083, 27480, -1, 27484, 27078, 27083, -1, 27485, 27480, 27478, -1, 27485, 27484, 27480, -1, 27486, 27478, 27475, -1, 27486, 27485, 27478, -1, 27487, 27475, 27470, -1, 27487, 27486, 27475, -1, 27488, 27470, 27467, -1, 27488, 27487, 27470, -1, 27489, 27467, 27463, -1, 27489, 27488, 27467, -1, 25140, 27463, 25141, -1, 25140, 27489, 27463, -1, 25142, 25138, 27490, -1, 27490, 25132, 27491, -1, 25138, 25132, 27490, -1, 27491, 25126, 27492, -1, 25132, 25126, 27491, -1, 25126, 25122, 27492, -1, 27492, 25120, 27493, -1, 25122, 25120, 27492, -1, 25120, 25119, 27493, -1, 27493, 25123, 25148, -1, 25119, 25123, 27493, -1, 25123, 25125, 25148, -1, 25125, 25127, 25148, -1, 27494, 25148, 25151, -1, 27494, 25151, 27495, -1, 27496, 27495, 27497, -1, 27496, 27494, 27495, -1, 27498, 27496, 27497, -1, 27499, 27497, 27500, -1, 27499, 27498, 27497, -1, 27501, 27499, 27500, -1, 27502, 27500, 25089, -1, 27502, 27501, 27500, -1, 25101, 27502, 25089, -1, 27484, 27481, 27078, -1, 27482, 27481, 27484, -1, 27485, 27482, 27484, -1, 27483, 27482, 27485, -1, 27486, 25069, 27483, -1, 27486, 27483, 27485, -1, 27487, 27503, 25069, -1, 27487, 25069, 27486, -1, 27504, 27488, 27489, -1, 27504, 27505, 27488, -1, 25140, 27504, 27489, -1, 27506, 27487, 27488, -1, 27506, 27505, 27503, -1, 27506, 27503, 27487, -1, 27506, 27488, 27505, -1, 27507, 27508, 27509, -1, 27510, 27511, 27512, -1, 27513, 27511, 27510, -1, 27514, 27511, 27515, -1, 27515, 27511, 27513, -1, 27512, 27516, 27517, -1, 27509, 27516, 27514, -1, 27511, 27516, 27512, -1, 27514, 27516, 27511, -1, 27517, 27518, 25101, -1, 25101, 27518, 27502, -1, 27502, 27518, 27501, -1, 27501, 27518, 27508, -1, 27516, 27518, 27517, -1, 27508, 27518, 27509, -1, 27509, 27518, 27516, -1, 25148, 27494, 27493, -1, 25142, 27519, 25143, -1, 27490, 27519, 25142, -1, 27491, 27520, 27490, -1, 27490, 27520, 27519, -1, 25143, 27521, 25144, -1, 27519, 27521, 25143, -1, 27492, 27522, 27491, -1, 27491, 27522, 27520, -1, 27520, 27523, 27519, -1, 27519, 27523, 27521, -1, 25144, 27515, 25145, -1, 27521, 27515, 25144, -1, 27496, 27524, 27494, -1, 27493, 27524, 27492, -1, 27494, 27524, 27493, -1, 27492, 27524, 27522, -1, 27522, 27507, 27520, -1, 27520, 27507, 27523, -1, 27523, 27514, 27521, -1, 27521, 27514, 27515, -1, 27499, 27525, 27498, -1, 27498, 27525, 27496, -1, 27522, 27525, 27507, -1, 27496, 27525, 27524, -1, 27524, 27525, 27522, -1, 27523, 27509, 27514, -1, 27507, 27509, 27523, -1, 25145, 27513, 25146, -1, 25146, 27513, 27510, -1, 27515, 27513, 25145, -1, 27501, 27508, 27499, -1, 27499, 27508, 27525, -1, 27525, 27508, 27507, -1, 27526, 25069, 27503, -1, 27526, 25070, 25069, -1, 27527, 27503, 27505, -1, 27527, 27526, 27503, -1, 27528, 27505, 27504, -1, 27528, 27527, 27505, -1, 25147, 27504, 25140, -1, 25147, 27528, 27504, -1, 25146, 27510, 25147, -1, 25147, 27510, 27529, -1, 27530, 27512, 27531, -1, 27529, 27512, 27530, -1, 27510, 27512, 27529, -1, 27532, 27517, 27533, -1, 27534, 27517, 27532, -1, 27531, 27517, 27534, -1, 27512, 27517, 27531, -1, 27535, 25101, 25108, -1, 27533, 25101, 27535, -1, 27517, 25101, 27533, -1, 27536, 27537, 27538, -1, 27536, 27539, 27537, -1, 27540, 25079, 25078, -1, 27540, 25078, 27541, -1, 27540, 27542, 27539, -1, 27540, 27541, 27542, -1, 27543, 27544, 27545, -1, 27543, 27546, 27544, -1, 27543, 27538, 27546, -1, 27543, 27536, 27538, -1, 27547, 25080, 25079, -1, 27547, 25079, 27540, -1, 27547, 27539, 27536, -1, 27547, 27540, 27539, -1, 27529, 27528, 25147, -1, 27548, 27545, 25064, -1, 27548, 25064, 25080, -1, 27548, 25080, 27547, -1, 27548, 27543, 27545, -1, 27548, 27536, 27543, -1, 27548, 27547, 27536, -1, 27549, 27529, 27530, -1, 27549, 27528, 27529, -1, 27550, 27527, 27528, -1, 27550, 27526, 27527, -1, 27550, 27528, 27549, -1, 27551, 25070, 27526, -1, 27551, 25076, 25070, -1, 27551, 25077, 25076, -1, 27551, 27526, 27550, -1, 27552, 27530, 27531, -1, 27552, 27549, 27530, -1, 27553, 27550, 27549, -1, 27553, 27549, 27552, -1, 27554, 27551, 27550, -1, 27554, 27550, 27553, -1, 27554, 25077, 27551, -1, 27555, 27531, 27534, -1, 27555, 27552, 27531, -1, 27542, 27553, 27552, -1, 27542, 27552, 27555, -1, 27537, 27532, 27533, -1, 27537, 27534, 27532, -1, 27537, 27555, 27534, -1, 27541, 25078, 25077, -1, 27541, 25077, 27554, -1, 27541, 27554, 27553, -1, 27541, 27553, 27542, -1, 27538, 27537, 27533, -1, 27539, 27542, 27555, -1, 27539, 27555, 27537, -1, 27546, 27535, 25108, -1, 27546, 27533, 27535, -1, 27546, 25108, 27544, -1, 27546, 27538, 27533, -1, 25058, 25064, 27545, -1, 27556, 27545, 27544, -1, 27556, 25058, 27545, -1, 27557, 27544, 25108, -1, 27557, 27556, 27544, -1, 25096, 27557, 25108, -1, 25152, 16533, 25133, -1, 25179, 25133, 25134, -1, 25179, 25134, 25135, -1, 25179, 25135, 25136, -1, 25179, 25152, 25133, -1, 25180, 25136, 25129, -1, 25180, 25129, 25128, -1, 25180, 25179, 25136, -1, 25186, 25128, 25130, -1, 25186, 25130, 25131, -1, 25186, 25180, 25128, -1, 25184, 25131, 25124, -1, 25184, 25186, 25131, -1, 25139, 25124, 25121, -1, 25139, 25184, 25124, -1, 27558, 25181, 27223, -1, 27559, 25181, 27558, -1, 25167, 25172, 25181, -1, 25167, 25181, 27559, -1, 25165, 25172, 25167, -1, 25174, 25172, 25165, -1, 25163, 25174, 25165, -1, 25157, 25174, 25163, -1, 25154, 25157, 25163, -1, 25166, 25167, 27559, -1, 27560, 27559, 27558, -1, 27560, 25166, 27559, -1, 27561, 27558, 27223, -1, 27561, 27560, 27558, -1, 27224, 27561, 27223, -1, 27562, 25008, 25009, -1, 27563, 25009, 27221, -1, 27563, 27562, 25009, -1, 27196, 27563, 27221, -1, 27564, 24989, 27565, -1, 27566, 27200, 27567, -1, 27568, 27569, 27570, -1, 27568, 27570, 27571, -1, 27572, 27573, 27574, -1, 27572, 27574, 27575, -1, 27576, 27289, 27286, -1, 27577, 27565, 27578, -1, 27576, 27286, 27579, -1, 27576, 27579, 27580, -1, 27577, 27564, 27565, -1, 27576, 27580, 27581, -1, 27582, 27583, 27200, -1, 27582, 27584, 27585, -1, 27586, 27587, 27588, -1, 27586, 27588, 27564, -1, 27586, 27564, 27577, -1, 27582, 27200, 27566, -1, 27582, 27566, 27198, -1, 27589, 27578, 27569, -1, 27589, 27569, 27568, -1, 27582, 27198, 27584, -1, 27590, 27591, 27573, -1, 27590, 27573, 27572, -1, 27592, 27193, 27204, -1, 24989, 24988, 25004, -1, 27592, 27593, 27193, -1, 27594, 27583, 27582, -1, 27594, 27595, 27583, -1, 27596, 27578, 27589, -1, 27594, 27582, 27585, -1, 27596, 27577, 27578, -1, 27597, 27581, 27591, -1, 27598, 27599, 27587, -1, 27597, 27591, 27590, -1, 27598, 27587, 27586, -1, 27600, 27585, 27601, -1, 27600, 27575, 27595, -1, 27602, 27592, 27204, -1, 27602, 27571, 27593, -1, 27600, 27594, 27585, -1, 27600, 27595, 27594, -1, 27602, 27593, 27592, -1, 27603, 27577, 27596, -1, 27604, 27600, 27601, -1, 27604, 27601, 27605, -1, 27604, 27572, 27575, -1, 27603, 27586, 27577, -1, 27604, 27575, 27600, -1, 27606, 27602, 27204, -1, 27607, 27287, 27288, -1, 27607, 27288, 27289, -1, 27606, 27568, 27571, -1, 27607, 27576, 27581, -1, 27607, 27581, 27597, -1, 27607, 27289, 27576, -1, 27606, 27571, 27602, -1, 27608, 27590, 27572, -1, 27609, 27599, 27598, -1, 27608, 27604, 27605, -1, 27609, 27586, 27603, -1, 27608, 27572, 27604, -1, 27609, 27598, 27586, -1, 27584, 27198, 27188, -1, 27610, 27605, 27611, -1, 27612, 27568, 27606, -1, 27610, 27608, 27605, -1, 27610, 27597, 27590, -1, 27610, 27590, 27608, -1, 27612, 27589, 27568, -1, 27613, 27611, 27614, -1, 27613, 27287, 27607, -1, 27613, 27610, 27611, -1, 27580, 27599, 27609, -1, 27613, 27607, 27597, -1, 27613, 27614, 27287, -1, 27580, 27615, 27599, -1, 27613, 27597, 27610, -1, 27574, 27589, 27612, -1, 27574, 27596, 27589, -1, 27616, 27204, 27200, -1, 27573, 27596, 27574, -1, 27573, 27603, 27596, -1, 27285, 27287, 27614, -1, 27583, 27606, 27204, -1, 27617, 27563, 27196, -1, 27617, 27562, 27563, -1, 27583, 27204, 27616, -1, 27583, 27616, 27200, -1, 27618, 25008, 27562, -1, 27579, 27286, 27615, -1, 27618, 27562, 27617, -1, 27579, 27615, 27580, -1, 27619, 27196, 27193, -1, 27591, 27609, 27603, -1, 27619, 27617, 27196, -1, 27570, 27618, 27617, -1, 27591, 27603, 27573, -1, 27570, 27617, 27619, -1, 27620, 25007, 25008, -1, 27620, 25004, 25007, -1, 27620, 25008, 27618, -1, 27595, 27606, 27583, -1, 27595, 27612, 27606, -1, 27569, 27620, 27618, -1, 27569, 27618, 27570, -1, 27581, 27609, 27591, -1, 27581, 27580, 27609, -1, 27593, 27619, 27193, -1, 27565, 25004, 27620, -1, 27565, 24989, 25004, -1, 27575, 27612, 27595, -1, 27575, 27574, 27612, -1, 27571, 27619, 27593, -1, 27567, 27200, 27198, -1, 27571, 27570, 27619, -1, 27578, 27620, 27569, -1, 27578, 27565, 27620, -1, 27566, 27567, 27198, -1, 27564, 27588, 24989, -1, 27284, 27285, 27614, -1, 27621, 27614, 27611, -1, 27621, 27284, 27614, -1, 27622, 27611, 27605, -1, 27622, 27621, 27611, -1, 27623, 27605, 27601, -1, 27623, 27622, 27605, -1, 27624, 27601, 27585, -1, 27624, 27623, 27601, -1, 27625, 27585, 27584, -1, 27625, 27624, 27585, -1, 27626, 27584, 27188, -1, 27626, 27625, 27584, -1, 27173, 27626, 27188, -1, 27627, 27625, 27626, -1, 27627, 27171, 27169, -1, 27627, 27169, 27628, -1, 27627, 27626, 27171, -1, 27627, 27628, 27629, -1, 27627, 27630, 27625, -1, 27627, 27629, 27630, -1, 27173, 27171, 27626, -1, 27631, 27632, 27280, -1, 27631, 27280, 27282, -1, 27633, 27634, 27632, -1, 27633, 27632, 27631, -1, 27635, 27284, 27621, -1, 27635, 27282, 27283, -1, 27635, 27283, 27284, -1, 27635, 27631, 27282, -1, 27636, 27637, 27634, -1, 27636, 27634, 27633, -1, 27638, 27621, 27622, -1, 27638, 27633, 27631, -1, 27638, 27631, 27635, -1, 27638, 27635, 27621, -1, 27639, 27640, 27637, -1, 27639, 27637, 27636, -1, 27641, 27622, 27623, -1, 27641, 27638, 27622, -1, 27641, 27633, 27638, -1, 27641, 27636, 27633, -1, 27629, 27642, 27640, -1, 27629, 27640, 27639, -1, 27643, 27623, 27624, -1, 27643, 27641, 27623, -1, 27643, 27636, 27641, -1, 27643, 27639, 27636, -1, 27628, 27169, 17897, -1, 27628, 17897, 27644, -1, 27628, 27644, 27642, -1, 27628, 27642, 27629, -1, 27630, 27624, 27625, -1, 27630, 27643, 27624, -1, 27630, 27629, 27639, -1, 27630, 27639, 27643, -1, 27278, 27280, 27632, -1, 27645, 27632, 27634, -1, 27645, 27278, 27632, -1, 27646, 27634, 27637, -1, 27646, 27645, 27634, -1, 27647, 27637, 27640, -1, 27647, 27646, 27637, -1, 27648, 27640, 27642, -1, 27648, 27647, 27640, -1, 27649, 27642, 27644, -1, 27649, 27648, 27642, -1, 27650, 27644, 17897, -1, 27650, 27649, 27644, -1, 17896, 27650, 17897, -1, 27651, 27652, 27653, -1, 27654, 27655, 27656, -1, 27654, 27657, 27655, -1, 27654, 27658, 27657, -1, 27654, 27659, 27658, -1, 27660, 27661, 27662, -1, 17901, 27650, 17896, -1, 27660, 27662, 27651, -1, 27663, 27656, 27664, -1, 27663, 27654, 27656, -1, 27663, 27653, 27659, -1, 27663, 27659, 27654, -1, 27665, 27274, 27277, -1, 27665, 27661, 27660, -1, 27665, 27277, 27666, -1, 27665, 27666, 27661, -1, 27667, 27664, 27668, -1, 27667, 27653, 27663, -1, 27667, 27651, 27653, -1, 27667, 27663, 27664, -1, 27669, 27668, 27670, -1, 27669, 27651, 27667, -1, 27669, 27660, 27651, -1, 27669, 27667, 27668, -1, 27671, 27670, 27672, -1, 27671, 27273, 27274, -1, 27671, 27274, 27665, -1, 27671, 27672, 27273, -1, 27671, 27665, 27660, -1, 27671, 27669, 27670, -1, 27671, 27660, 27669, -1, 27271, 27273, 27672, -1, 27673, 17901, 17903, -1, 27673, 27650, 17901, -1, 27674, 27649, 27650, -1, 27674, 27650, 27673, -1, 27652, 27648, 27649, -1, 27652, 27649, 27674, -1, 27658, 17903, 17906, -1, 27658, 27673, 17903, -1, 27662, 27647, 27648, -1, 27662, 27648, 27652, -1, 27659, 27673, 27658, -1, 27659, 27674, 27673, -1, 27661, 27646, 27647, -1, 27661, 27647, 27662, -1, 27653, 27652, 27674, -1, 27653, 27674, 27659, -1, 27657, 17906, 17909, -1, 27657, 17909, 27655, -1, 27657, 27658, 17906, -1, 27666, 27645, 27646, -1, 27666, 27278, 27645, -1, 27666, 27277, 27278, -1, 27666, 27646, 27661, -1, 27651, 27662, 27652, -1, 27264, 27271, 27672, -1, 27675, 27672, 27670, -1, 27675, 27264, 27672, -1, 27676, 27670, 27668, -1, 27676, 27675, 27670, -1, 27677, 27668, 27664, -1, 27677, 27676, 27668, -1, 27678, 27664, 27656, -1, 27678, 27677, 27664, -1, 27679, 27656, 27655, -1, 27679, 27678, 27656, -1, 27680, 27655, 17909, -1, 27680, 27679, 27655, -1, 17915, 27680, 17909, -1, 27681, 27682, 27683, -1, 27681, 27683, 27684, -1, 27685, 17920, 17876, -1, 27685, 17876, 22252, -1, 27685, 22252, 22253, -1, 27685, 22253, 27686, -1, 27687, 27676, 27677, -1, 27687, 27684, 27688, -1, 27687, 27689, 27676, -1, 27687, 27688, 27689, -1, 27690, 27686, 27682, -1, 27690, 27682, 27681, -1, 27691, 27677, 27678, -1, 27691, 27687, 27677, -1, 27691, 27681, 27684, -1, 27691, 27684, 27687, -1, 27692, 17918, 17920, -1, 27692, 17920, 27685, -1, 27692, 27685, 27686, -1, 27692, 27686, 27690, -1, 27693, 27678, 27679, -1, 27693, 27690, 27681, -1, 27693, 27691, 27678, -1, 27693, 27681, 27691, -1, 27694, 27679, 27680, -1, 27694, 17919, 17918, -1, 27694, 27692, 27690, -1, 27694, 27690, 27693, -1, 27694, 27680, 17919, -1, 27694, 17918, 27692, -1, 27694, 27693, 27679, -1, 17915, 17919, 27680, -1, 27695, 22257, 22166, -1, 27695, 22166, 27269, -1, 27696, 22256, 22257, -1, 27696, 22257, 27695, -1, 27697, 27269, 27267, -1, 27697, 27695, 27269, -1, 27683, 22255, 22256, -1, 27683, 22256, 27696, -1, 27688, 27696, 27695, -1, 27688, 27695, 27697, -1, 27682, 22254, 22255, -1, 27682, 22255, 27683, -1, 27698, 27264, 27675, -1, 27698, 27267, 27265, -1, 27698, 27265, 27264, -1, 27698, 27697, 27267, -1, 27684, 27696, 27688, -1, 27684, 27683, 27696, -1, 27686, 22253, 22254, -1, 27686, 22254, 27682, -1, 27689, 27675, 27676, -1, 27689, 27698, 27675, -1, 27689, 27688, 27697, -1, 27689, 27697, 27698, -1, 27049, 27051, 27699, -1, 27700, 22265, 19821, -1, 27700, 19821, 20087, -1, 27701, 22263, 22265, -1, 27701, 22265, 27700, -1, 27702, 22261, 22263, -1, 27702, 22263, 27701, -1, 27703, 22259, 22261, -1, 27703, 22261, 27702, -1, 27704, 18855, 22259, -1, 27704, 27055, 18855, -1, 27704, 22259, 27703, -1, 27705, 20087, 20091, -1, 27705, 20091, 20128, -1, 27705, 20128, 27706, -1, 27705, 27700, 20087, -1, 27707, 27706, 27708, -1, 27707, 27700, 27705, -1, 27707, 27705, 27706, -1, 27707, 27701, 27700, -1, 27709, 27708, 27710, -1, 27709, 27710, 27711, -1, 27709, 27701, 27707, -1, 27709, 27702, 27701, -1, 27709, 27707, 27708, -1, 27712, 27711, 27699, -1, 27712, 27703, 27702, -1, 27712, 27709, 27711, -1, 27712, 27702, 27709, -1, 27713, 27051, 27055, -1, 27713, 27704, 27703, -1, 27713, 27055, 27704, -1, 27713, 27703, 27712, -1, 27713, 27712, 27699, -1, 27713, 27699, 27051, -1, 20128, 20178, 27714, -1, 27706, 27714, 27715, -1, 27706, 20128, 27714, -1, 27708, 27715, 27716, -1, 27708, 27706, 27715, -1, 27710, 27708, 27716, -1, 27711, 27716, 27717, -1, 27711, 27710, 27716, -1, 27699, 27717, 27718, -1, 27699, 27711, 27717, -1, 27049, 27718, 27059, -1, 27049, 27699, 27718, -1, 20260, 20264, 24796, -1, 20247, 24796, 27719, -1, 20247, 20260, 24796, -1, 20246, 20247, 27719, -1, 20244, 20246, 27719, -1, 20232, 20244, 27719, -1, 20178, 27719, 27720, -1, 20178, 20232, 27719, -1, 27714, 27720, 27721, -1, 27714, 20178, 27720, -1, 27715, 27721, 27722, -1, 27715, 27714, 27721, -1, 27716, 27722, 27723, -1, 27716, 27715, 27722, -1, 27717, 27723, 27724, -1, 27717, 27716, 27723, -1, 27718, 27724, 27060, -1, 27718, 27717, 27724, -1, 27059, 27718, 27060, -1, 24795, 27719, 24796, -1, 27066, 27064, 27725, -1, 27726, 27720, 27719, -1, 27726, 24795, 24797, -1, 27726, 27719, 24795, -1, 27727, 27721, 27720, -1, 27727, 27720, 27726, -1, 27728, 24797, 24793, -1, 27728, 24793, 27729, -1, 27728, 27726, 24797, -1, 27730, 27722, 27721, -1, 27730, 27721, 27727, -1, 27731, 27729, 27732, -1, 27731, 27727, 27726, -1, 27731, 27728, 27729, -1, 27731, 27726, 27728, -1, 27733, 27723, 27722, -1, 27733, 27722, 27730, -1, 27734, 27732, 27735, -1, 27734, 27730, 27727, -1, 27734, 27727, 27731, -1, 27734, 27731, 27732, -1, 27736, 27724, 27723, -1, 27736, 27723, 27733, -1, 27737, 27735, 27738, -1, 27737, 27730, 27734, -1, 27737, 27733, 27730, -1, 27737, 27734, 27735, -1, 27739, 27060, 27724, -1, 27739, 27062, 27060, -1, 27739, 27724, 27736, -1, 27740, 27738, 27741, -1, 27740, 27737, 27738, -1, 27740, 27736, 27733, -1, 27740, 27733, 27737, -1, 27742, 27741, 27725, -1, 27742, 27064, 27062, -1, 27742, 27740, 27741, -1, 27742, 27725, 27064, -1, 27742, 27062, 27739, -1, 27742, 27739, 27736, -1, 27742, 27736, 27740, -1, 27081, 27066, 27725, -1, 27743, 27725, 27741, -1, 27743, 27081, 27725, -1, 27744, 27741, 27738, -1, 27744, 27743, 27741, -1, 27745, 27738, 27735, -1, 27745, 27744, 27738, -1, 27746, 27735, 27732, -1, 27746, 27745, 27735, -1, 27747, 27732, 27729, -1, 27747, 27746, 27732, -1, 27748, 27729, 24793, -1, 27748, 27747, 27729, -1, 24789, 27748, 24793, -1, 27165, 27162, 27749, -1, 27165, 27749, 27750, -1, 27751, 27752, 27077, -1, 27751, 27077, 27079, -1, 27751, 27079, 27080, -1, 27753, 27754, 27752, -1, 27753, 27752, 27751, -1, 27755, 27750, 27754, -1, 27755, 27754, 27753, -1, 27756, 27750, 27755, -1, 27756, 27165, 27750, -1, 27757, 27164, 27165, -1, 27757, 27756, 27164, -1, 27757, 27165, 27756, -1, 27758, 27081, 27743, -1, 27758, 27080, 27081, -1, 27758, 27751, 27080, -1, 27759, 27744, 27745, -1, 27759, 27743, 27744, -1, 27759, 27751, 27758, -1, 27759, 27753, 27751, -1, 27759, 27758, 27743, -1, 27760, 27745, 27746, -1, 27760, 27753, 27759, -1, 27760, 27755, 27753, -1, 27760, 27759, 27745, -1, 27761, 27746, 27747, -1, 27761, 27164, 27756, -1, 27761, 27755, 27760, -1, 27761, 27760, 27746, -1, 27761, 27756, 27755, -1, 27762, 27748, 24789, -1, 27762, 27747, 27748, -1, 27762, 24789, 27164, -1, 27762, 27761, 27747, -1, 27762, 27164, 27761, -1, 27162, 27163, 27763, -1, 27749, 27763, 27764, -1, 27749, 27162, 27763, -1, 27750, 27764, 27765, -1, 27750, 27749, 27764, -1, 27754, 27765, 27766, -1, 27754, 27750, 27765, -1, 27752, 27766, 27082, -1, 27752, 27754, 27766, -1, 27077, 27752, 27082, -1, 27260, 27130, 27132, -1, 27766, 27103, 27082, -1, 27163, 27261, 27763, -1, 27767, 27129, 27101, -1, 27767, 27101, 27102, -1, 27767, 27102, 27103, -1, 27768, 27141, 27129, -1, 27768, 27129, 27767, -1, 27769, 27142, 27141, -1, 27769, 27141, 27768, -1, 27770, 27132, 27142, -1, 27770, 27261, 27260, -1, 27770, 27142, 27769, -1, 27770, 27260, 27132, -1, 27771, 27764, 27763, -1, 27771, 27765, 27764, -1, 27771, 27766, 27765, -1, 27771, 27768, 27767, -1, 27771, 27767, 27103, -1, 27771, 27261, 27770, -1, 27771, 27103, 27766, -1, 27771, 27770, 27769, -1, 27771, 27763, 27261, -1, 27771, 27769, 27768, -1, 27128, 27127, 27161, -1, 27128, 27161, 27772, -1, 27138, 27772, 27773, -1, 27138, 27773, 27774, -1, 27138, 27128, 27772, -1, 27136, 27774, 27775, -1, 27136, 27138, 27774, -1, 27134, 27136, 27775, -1, 27092, 27775, 27090, -1, 27092, 27134, 27775, -1, 27258, 27113, 27115, -1, 27775, 27089, 27090, -1, 27161, 27259, 27772, -1, 27776, 27112, 27086, -1, 27776, 27086, 27088, -1, 27776, 27088, 27089, -1, 27777, 27124, 27112, -1, 27777, 27112, 27776, -1, 27778, 27125, 27124, -1, 27778, 27124, 27777, -1, 27779, 27115, 27125, -1, 27779, 27259, 27258, -1, 27779, 27125, 27778, -1, 27779, 27258, 27115, -1, 27780, 27773, 27772, -1, 27780, 27774, 27773, -1, 27780, 27775, 27774, -1, 27780, 27777, 27776, -1, 27780, 27776, 27089, -1, 27780, 27259, 27779, -1, 27780, 27089, 27775, -1, 27780, 27779, 27778, -1, 27780, 27772, 27259, -1, 27780, 27778, 27777, -1, 27111, 27110, 27160, -1, 27111, 27160, 27781, -1, 27111, 27781, 27782, -1, 27121, 27782, 27783, -1, 27121, 27111, 27782, -1, 27119, 27783, 27784, -1, 27119, 27121, 27783, -1, 27117, 27784, 27104, -1, 27117, 27119, 27784, -1, 27087, 27117, 27104, -1, 27108, 27785, 27067, -1, 27166, 24945, 27786, -1, 27160, 27167, 27781, -1, 27787, 27788, 27785, -1, 27787, 27108, 27105, -1, 27787, 27785, 27108, -1, 27789, 27788, 27787, -1, 27790, 27791, 27792, -1, 27790, 27792, 27788, -1, 27790, 27788, 27789, -1, 27793, 27794, 27791, -1, 27793, 27791, 27790, -1, 27795, 27167, 27166, -1, 27795, 27786, 27794, -1, 27795, 27794, 27793, -1, 27795, 27166, 27786, -1, 27796, 27795, 27793, -1, 27796, 27787, 27105, -1, 27796, 27789, 27787, -1, 27796, 27167, 27795, -1, 27796, 27793, 27790, -1, 27796, 27790, 27789, -1, 27797, 27796, 27105, -1, 27797, 27167, 27796, -1, 27798, 27782, 27781, -1, 27798, 27783, 27782, -1, 27798, 27784, 27783, -1, 27798, 27104, 27784, -1, 27798, 27105, 27104, -1, 27798, 27167, 27797, -1, 27798, 27797, 27105, -1, 27798, 27781, 27167, -1, 27799, 27067, 27785, -1, 27799, 27070, 27067, -1, 27800, 27785, 27788, -1, 27800, 27799, 27785, -1, 27801, 27788, 27792, -1, 27801, 27800, 27788, -1, 27802, 27792, 27791, -1, 27802, 27801, 27792, -1, 27803, 27791, 27794, -1, 27803, 27802, 27791, -1, 27804, 27794, 27786, -1, 27804, 27803, 27794, -1, 24942, 27786, 24945, -1, 24942, 27804, 27786, -1, 27805, 27806, 27807, -1, 27808, 27799, 27800, -1, 27808, 27800, 27809, -1, 27808, 27149, 27799, -1, 27810, 27811, 27812, -1, 27810, 27813, 27811, -1, 27810, 27814, 27815, -1, 27810, 27815, 27813, -1, 27816, 27809, 27806, -1, 27816, 27806, 27805, -1, 27817, 27812, 27818, -1, 27817, 27810, 27812, -1, 27817, 27805, 27814, -1, 27817, 27814, 27810, -1, 27819, 27147, 27149, -1, 27819, 27149, 27808, -1, 27819, 27808, 27809, -1, 27819, 27809, 27816, -1, 27820, 27818, 27821, -1, 27820, 27817, 27818, -1, 27820, 27805, 27817, -1, 27820, 27816, 27805, -1, 27822, 27821, 27823, -1, 27822, 27823, 27144, -1, 27822, 27144, 27143, -1, 27822, 27143, 27147, -1, 27822, 27147, 27819, -1, 27822, 27820, 27821, -1, 27822, 27819, 27816, -1, 27824, 24940, 24941, -1, 27822, 27816, 27820, -1, 27149, 27070, 27799, -1, 27825, 27804, 24942, -1, 27825, 24942, 24939, -1, 27826, 27803, 27804, -1, 27826, 27804, 27825, -1, 27827, 24939, 24938, -1, 27827, 27825, 24939, -1, 27807, 27802, 27803, -1, 27807, 27803, 27826, -1, 27815, 27826, 27825, -1, 27815, 27825, 27827, -1, 27806, 27801, 27802, -1, 27806, 27802, 27807, -1, 27828, 24938, 24940, -1, 27828, 27827, 24938, -1, 27828, 24940, 27824, -1, 27814, 27826, 27815, -1, 27814, 27807, 27826, -1, 27809, 27800, 27801, -1, 27809, 27801, 27806, -1, 27813, 27824, 27811, -1, 27813, 27815, 27827, -1, 27813, 27827, 27828, -1, 27813, 27828, 27824, -1, 27805, 27807, 27814, -1, 24941, 18977, 19024, -1, 24941, 19024, 19032, -1, 27824, 19032, 19034, -1, 27824, 19034, 19040, -1, 27824, 19040, 27829, -1, 27824, 24941, 19032, -1, 27811, 27829, 27830, -1, 27811, 27824, 27829, -1, 27812, 27830, 27831, -1, 27812, 27811, 27830, -1, 27818, 27831, 27832, -1, 27818, 27812, 27831, -1, 27821, 27832, 27833, -1, 27821, 27818, 27832, -1, 27823, 27821, 27833, -1, 27144, 27833, 27151, -1, 27144, 27823, 27833, -1, 27829, 19040, 19065, -1, 27829, 19065, 27834, -1, 27830, 27834, 27835, -1, 27830, 27829, 27834, -1, 27831, 27835, 27836, -1, 27831, 27836, 27837, -1, 27831, 27830, 27835, -1, 27832, 27837, 27838, -1, 27832, 27831, 27837, -1, 27833, 27838, 27153, -1, 27833, 27832, 27838, -1, 27151, 27833, 27153, -1, 27154, 27837, 27836, -1, 27154, 27838, 27837, -1, 27154, 27153, 27838, -1, 27839, 27834, 19065, -1, 27839, 19065, 19075, -1, 27840, 27835, 27834, -1, 27840, 27834, 27839, -1, 27841, 27836, 27835, -1, 27841, 27154, 27836, -1, 27841, 27835, 27840, -1, 27842, 27841, 27156, -1, 27842, 27154, 27841, -1, 27843, 27156, 27154, -1, 27843, 27842, 27156, -1, 27843, 27154, 27842, -1, 27844, 19075, 19097, -1, 27844, 27839, 19075, -1, 27845, 27839, 27844, -1, 27845, 27840, 27839, -1, 27846, 27156, 27841, -1, 27846, 27841, 27840, -1, 27846, 27840, 27845, -1, 27847, 27156, 27846, -1, 27848, 19097, 19099, -1, 27848, 19099, 19101, -1, 27848, 19101, 22429, -1, 27848, 27844, 19097, -1, 27849, 27158, 27156, -1, 27849, 27156, 27847, -1, 27849, 27847, 27158, -1, 27850, 22429, 22428, -1, 27850, 27845, 27844, -1, 27850, 27848, 22429, -1, 27850, 27844, 27848, -1, 27851, 22428, 22427, -1, 27851, 27846, 27845, -1, 27851, 27845, 27850, -1, 27851, 27850, 22428, -1, 27852, 22427, 22426, -1, 27852, 22426, 22425, -1, 27852, 27158, 27847, -1, 27852, 27846, 27851, -1, 27852, 27847, 27846, -1, 27852, 27851, 22427, -1, 27853, 22425, 18739, -1, 27853, 18739, 27158, -1, 27853, 27852, 22425, -1, 27853, 27158, 27852, -1, 27854, 25014, 25015, -1, 27854, 25015, 27855, -1, 27856, 27855, 25051, -1, 27856, 27854, 27855, -1, 25055, 27856, 25051, -1, 25118, 25117, 25242, -1, 27857, 25242, 25243, -1, 27857, 25118, 25242, -1, 27858, 25243, 25234, -1, 27858, 27857, 25243, -1, 27859, 25234, 25235, -1, 27859, 27858, 25234, -1, 27860, 25235, 25236, -1, 27860, 27859, 25235, -1, 27861, 25236, 25231, -1, 27861, 27860, 25236, -1, 25291, 25231, 25273, -1, 25291, 27861, 25231, -1, 25289, 25290, 27862, -1, 25289, 27862, 27863, -1, 25289, 27863, 27864, -1, 25289, 27864, 27865, -1, 25289, 27865, 27866, -1, 25289, 27866, 25098, -1, 25099, 25289, 25098, -1, 25112, 25288, 25099, -1, 25293, 25294, 25106, -1, 25092, 25292, 25094, -1, 27867, 25289, 25099, -1, 27867, 25099, 25288, -1, 27868, 25289, 27867, -1, 27868, 27867, 25288, -1, 27869, 25289, 27868, -1, 27869, 27868, 25288, -1, 27870, 25289, 27869, -1, 27870, 27869, 25288, -1, 27871, 25289, 27870, -1, 27871, 27870, 25288, -1, 27872, 27871, 25288, -1, 27872, 25289, 27871, -1, 27873, 25288, 25289, -1, 27873, 25289, 27872, -1, 27873, 27872, 25288, -1, 27874, 25288, 25112, -1, 27874, 25112, 25304, -1, 27875, 25288, 27874, -1, 27875, 27874, 25304, -1, 27876, 25288, 27875, -1, 27876, 27875, 25304, -1, 27877, 27876, 25304, -1, 27877, 25288, 27876, -1, 27878, 27877, 25304, -1, 27878, 25288, 27877, -1, 27879, 27878, 25304, -1, 27879, 25288, 27878, -1, 27880, 27879, 25304, -1, 27880, 25288, 27879, -1, 27880, 25304, 25288, -1, 27881, 25112, 25107, -1, 27881, 25304, 25112, -1, 27882, 25304, 27881, -1, 27882, 27881, 25107, -1, 27883, 25304, 27882, -1, 27883, 27882, 25107, -1, 27884, 27883, 25107, -1, 27884, 25304, 27883, -1, 27885, 25304, 27884, -1, 27886, 25304, 27885, -1, 27887, 25302, 25303, -1, 27887, 25303, 25304, -1, 27887, 25304, 27886, -1, 27888, 25107, 25109, -1, 27888, 27884, 25107, -1, 27889, 27885, 27884, -1, 27889, 27888, 25109, -1, 27889, 27884, 27888, -1, 27890, 27886, 27885, -1, 27890, 27885, 27889, -1, 27890, 27889, 25109, -1, 27891, 25301, 25302, -1, 27891, 25302, 27887, -1, 27891, 27887, 27886, -1, 27891, 27886, 27890, -1, 27892, 25109, 25110, -1, 27893, 25109, 27892, -1, 27894, 27890, 25109, -1, 27894, 25109, 27893, -1, 27895, 25301, 27891, -1, 27895, 27891, 27890, -1, 27895, 27890, 27894, -1, 27896, 25110, 25111, -1, 27897, 25110, 27896, -1, 27898, 25110, 27897, -1, 27899, 27892, 25110, -1, 27899, 25110, 27898, -1, 27900, 27893, 27892, -1, 27900, 27892, 27899, -1, 27900, 27899, 25299, -1, 27901, 27894, 27893, -1, 27901, 27900, 25299, -1, 27901, 27893, 27900, -1, 27902, 25299, 25300, -1, 27902, 25300, 25301, -1, 27902, 27895, 27894, -1, 27902, 25301, 27895, -1, 27902, 27894, 27901, -1, 27902, 27901, 25299, -1, 27903, 25111, 25100, -1, 27903, 27896, 25111, -1, 27904, 27897, 27896, -1, 27904, 27903, 25298, -1, 27904, 27896, 27903, -1, 27905, 27898, 27897, -1, 27905, 27904, 25298, -1, 27905, 27897, 27904, -1, 27906, 27905, 25298, -1, 27906, 27898, 27905, -1, 27906, 25299, 27899, -1, 27906, 27899, 27898, -1, 27907, 25299, 27906, -1, 27907, 27906, 25298, -1, 27908, 25299, 27907, -1, 27908, 27907, 25298, -1, 27909, 25299, 27908, -1, 27909, 25298, 25299, -1, 27909, 27908, 25298, -1, 27910, 25100, 25102, -1, 27910, 25298, 27903, -1, 27910, 27903, 25100, -1, 27911, 27910, 25297, -1, 27911, 25298, 27910, -1, 27912, 27911, 25297, -1, 27912, 25298, 27911, -1, 27913, 27912, 25297, -1, 27913, 25298, 27912, -1, 27914, 27913, 25297, -1, 27914, 25298, 27913, -1, 27915, 27914, 25297, -1, 27915, 25298, 27914, -1, 27916, 25297, 25298, -1, 27916, 27915, 25297, -1, 27916, 25298, 27915, -1, 27917, 27910, 25102, -1, 27917, 25297, 27910, -1, 27918, 25297, 27917, -1, 27918, 27917, 25296, -1, 27919, 25297, 27918, -1, 27919, 27918, 25296, -1, 27920, 27919, 25296, -1, 27920, 25297, 27919, -1, 27921, 27920, 25296, -1, 27921, 25297, 27920, -1, 27922, 27921, 25296, -1, 27922, 25297, 27921, -1, 27923, 25296, 25297, -1, 27923, 27922, 25296, -1, 27923, 25297, 27922, -1, 27924, 25102, 25103, -1, 27924, 25103, 25104, -1, 27924, 27917, 25102, -1, 27924, 25296, 27917, -1, 27925, 25296, 27924, -1, 27926, 25296, 27925, -1, 27927, 27926, 25295, -1, 27927, 25296, 27926, -1, 27928, 27927, 25295, -1, 27928, 25296, 27927, -1, 27929, 27928, 25295, -1, 27929, 25296, 27928, -1, 27930, 25295, 25296, -1, 27930, 27929, 25295, -1, 27930, 25296, 27929, -1, 27931, 25104, 25105, -1, 27931, 27924, 25104, -1, 27932, 27931, 25105, -1, 27932, 27925, 27924, -1, 27932, 27924, 27931, -1, 27933, 25295, 27926, -1, 27933, 27926, 27925, -1, 27933, 27932, 25105, -1, 27933, 27925, 27932, -1, 27934, 27933, 25105, -1, 27934, 25295, 27933, -1, 27935, 25295, 27934, -1, 27935, 27934, 25105, -1, 27936, 25295, 27935, -1, 27936, 27935, 25105, -1, 27937, 25294, 25295, -1, 27937, 25105, 25294, -1, 27937, 25295, 27936, -1, 27937, 27936, 25105, -1, 27938, 25105, 25106, -1, 27939, 25105, 27938, -1, 27939, 27938, 25106, -1, 27940, 25105, 27939, -1, 27940, 27939, 25106, -1, 27941, 25105, 27940, -1, 27941, 27940, 25106, -1, 27941, 25294, 25105, -1, 27941, 25106, 25294, -1, 27942, 25106, 25097, -1, 27943, 25106, 27942, -1, 27943, 27942, 25097, -1, 27944, 25106, 27943, -1, 27944, 27943, 25097, -1, 27945, 25106, 27944, -1, 27946, 25106, 27945, -1, 27947, 25293, 25106, -1, 27947, 25106, 27946, -1, 27948, 25094, 25292, -1, 27948, 25097, 25094, -1, 27949, 27948, 25292, -1, 27949, 25097, 27948, -1, 27950, 27949, 25292, -1, 27950, 25097, 27949, -1, 27951, 27944, 25097, -1, 27951, 25097, 27950, -1, 27951, 27950, 25292, -1, 27952, 27945, 27944, -1, 27952, 27951, 25292, -1, 27952, 27944, 27951, -1, 27953, 27946, 27945, -1, 27953, 27952, 25292, -1, 27953, 27945, 27952, -1, 27954, 25292, 25293, -1, 27954, 25293, 27947, -1, 27954, 27947, 27946, -1, 27954, 27953, 25292, -1, 27954, 27946, 27953, -1, 27955, 25292, 25092, -1, 27955, 25092, 25090, -1, 27955, 25090, 25113, -1, 27956, 25292, 27955, -1, 27956, 25116, 25118, -1, 27956, 25113, 25116, -1, 27956, 27955, 25113, -1, 27957, 25118, 27857, -1, 27957, 27956, 25118, -1, 27957, 25292, 27956, -1, 27958, 27858, 27859, -1, 27958, 27857, 27858, -1, 27958, 27957, 27857, -1, 27958, 25292, 27957, -1, 27959, 27958, 27859, -1, 27959, 25292, 27958, -1, 27960, 27859, 27860, -1, 27960, 27959, 27859, -1, 27960, 25292, 27959, -1, 27961, 27861, 25291, -1, 27961, 27860, 27861, -1, 27961, 25291, 25292, -1, 27961, 27960, 27860, -1, 27961, 25292, 27960, -1, 25287, 25098, 27866, -1, 25287, 25093, 25098, -1, 25282, 27866, 27865, -1, 25282, 25287, 27866, -1, 25279, 27865, 27864, -1, 25279, 25282, 27865, -1, 25276, 27864, 27863, -1, 25276, 25279, 27864, -1, 25275, 27863, 27862, -1, 25275, 25276, 27863, -1, 25264, 27862, 25290, -1, 25264, 25275, 27862, -1, 27962, 27963, 27964, -1, 27965, 25256, 27966, -1, 27962, 27967, 27968, -1, 27965, 27969, 27970, -1, 27971, 25254, 25266, -1, 27962, 27964, 27967, -1, 27965, 27966, 27969, -1, 27971, 25266, 27972, -1, 27973, 27974, 27975, -1, 27976, 27977, 25237, -1, 27971, 27978, 27979, -1, 27976, 27980, 27977, -1, 27981, 27979, 27982, -1, 27976, 25237, 25239, -1, 27981, 27982, 27983, -1, 27976, 27963, 27962, -1, 27976, 27962, 27980, -1, 27976, 25239, 27984, -1, 27973, 27970, 27974, -1, 27976, 27984, 27963, -1, 27985, 27986, 27987, -1, 27988, 27975, 27989, -1, 27990, 27983, 27991, -1, 25248, 25237, 27977, -1, 27988, 27989, 27992, -1, 27993, 27992, 27994, -1, 27990, 27991, 27995, -1, 27996, 27995, 27997, -1, 27998, 27986, 27985, -1, 27993, 27994, 27999, -1, 28000, 27999, 28001, -1, 27996, 27997, 28002, -1, 28000, 28001, 28003, -1, 28004, 28005, 27986, -1, 28006, 28002, 28007, -1, 28004, 27986, 27998, -1, 28006, 28007, 28008, -1, 28009, 27985, 28010, -1, 28011, 28003, 28012, -1, 28011, 28012, 28013, -1, 28014, 28015, 28016, -1, 28009, 27998, 27985, -1, 28014, 28008, 28015, -1, 28017, 27965, 27970, -1, 28018, 27979, 27981, -1, 28019, 28020, 28021, -1, 28019, 28021, 28005, -1, 28018, 25245, 25254, -1, 28017, 25277, 25271, -1, 28018, 25254, 27971, -1, 28017, 25271, 27965, -1, 28018, 27971, 27979, -1, 28017, 27970, 27973, -1, 28022, 27975, 27988, -1, 28019, 28005, 28004, -1, 28023, 27983, 27990, -1, 28024, 27998, 28009, -1, 28022, 27973, 27975, -1, 28023, 27981, 27983, -1, 28024, 28004, 27998, -1, 28025, 28010, 28026, -1, 28027, 27990, 27995, -1, 28027, 27995, 27996, -1, 28028, 27992, 27993, -1, 28028, 27988, 27992, -1, 28029, 28002, 28006, -1, 28030, 27999, 28000, -1, 28025, 28009, 28010, -1, 28031, 28020, 28019, -1, 28029, 27996, 28002, -1, 28030, 27993, 27999, -1, 28032, 28003, 28011, -1, 28033, 28006, 28008, -1, 28032, 28000, 28003, -1, 28033, 28008, 28014, -1, 28034, 28004, 28024, -1, 28035, 28013, 28036, -1, 28034, 28019, 28004, -1, 28035, 28036, 28037, -1, 28038, 28016, 28039, -1, 28035, 28037, 28040, -1, 28038, 28014, 28016, -1, 28035, 28011, 28013, -1, 28041, 28009, 28025, -1, 28042, 28017, 27973, -1, 28041, 28024, 28009, -1, 28042, 25277, 28017, -1, 28042, 27973, 28022, -1, 28043, 25250, 25245, -1, 28043, 28018, 27981, -1, 28044, 28026, 28045, -1, 28042, 25280, 25277, -1, 28043, 27981, 28023, -1, 28046, 27988, 28028, -1, 28043, 25245, 28018, -1, 28046, 28022, 27988, -1, 27969, 27990, 28027, -1, 28044, 28025, 28026, -1, 27969, 28023, 27990, -1, 27978, 28047, 28020, -1, 28048, 28028, 27993, -1, 28048, 27993, 28030, -1, 27978, 28020, 28031, -1, 27974, 28027, 27996, -1, 27974, 27996, 28029, -1, 28049, 28030, 28000, -1, 27982, 28019, 28034, -1, 27982, 28031, 28019, -1, 27989, 28029, 28006, -1, 27989, 28006, 28033, -1, 28049, 28000, 28032, -1, 27991, 28024, 28041, -1, 28050, 28035, 28040, -1, 28050, 28040, 28051, -1, 27991, 28034, 28024, -1, 28050, 28032, 28011, -1, 28050, 28011, 28035, -1, 27994, 28033, 28014, -1, 27997, 28041, 28025, -1, 28052, 25283, 25280, -1, 27994, 28014, 28038, -1, 28052, 28042, 28022, -1, 28052, 28022, 28046, -1, 28052, 25280, 28042, -1, 27997, 28025, 28044, -1, 28001, 28039, 28053, -1, 28007, 28044, 28045, -1, 28054, 28028, 28048, -1, 28007, 28045, 28055, -1, 28054, 28046, 28028, -1, 28001, 28038, 28039, -1, 27966, 25256, 25250, -1, 27966, 25250, 28043, -1, 27972, 25274, 28056, -1, 27966, 28043, 28023, -1, 27972, 28056, 28047, -1, 27966, 28023, 27969, -1, 27972, 25266, 25274, -1, 27972, 28047, 27978, -1, 27964, 28048, 28030, -1, 27970, 27969, 28027, -1, 27964, 28030, 28049, -1, 27970, 28027, 27974, -1, 28057, 28051, 28058, -1, 27979, 27978, 28031, -1, 28057, 28050, 28051, -1, 28057, 28049, 28032, -1, 28057, 28032, 28050, -1, 27979, 28031, 27982, -1, 27983, 27982, 28034, -1, 27975, 28029, 27989, -1, 28059, 25286, 25283, -1, 27975, 27974, 28029, -1, 28059, 25283, 28052, -1, 28059, 28052, 28046, -1, 28059, 28046, 28054, -1, 27983, 28034, 27991, -1, 27963, 28054, 28048, -1, 27992, 27989, 28033, -1, 27992, 28033, 27994, -1, 27995, 27991, 28041, -1, 27963, 28048, 27964, -1, 27995, 28041, 27997, -1, 27967, 28058, 27968, -1, 27967, 28057, 28058, -1, 27967, 27964, 28049, -1, 27967, 28049, 28057, -1, 27999, 28038, 28001, -1, 28002, 27997, 28044, -1, 27999, 27994, 28038, -1, 28002, 28044, 28007, -1, 27984, 25286, 28059, -1, 28008, 28055, 28015, -1, 27984, 25239, 25286, -1, 28003, 28001, 28053, -1, 27984, 28059, 28054, -1, 28003, 28053, 28012, -1, 27984, 28054, 27963, -1, 28008, 28007, 28055, -1, 27962, 27968, 27980, -1, 27965, 25271, 25256, -1, 27971, 27972, 27978, -1, 28060, 28037, 28061, -1, 28061, 28036, 28062, -1, 28037, 28036, 28061, -1, 28062, 28013, 28063, -1, 28036, 28013, 28062, -1, 28063, 28012, 28064, -1, 28013, 28012, 28063, -1, 28064, 28053, 28065, -1, 28012, 28053, 28064, -1, 28065, 28039, 28066, -1, 28053, 28039, 28065, -1, 28066, 28016, 28067, -1, 28039, 28016, 28066, -1, 28067, 28015, 28068, -1, 28016, 28015, 28067, -1, 28068, 28055, 28069, -1, 28015, 28055, 28068, -1, 28069, 28045, 28070, -1, 28055, 28045, 28069, -1, 28070, 28026, 28071, -1, 28045, 28026, 28070, -1, 28071, 28010, 28072, -1, 28026, 28010, 28071, -1, 28072, 27985, 28073, -1, 28010, 27985, 28072, -1, 27985, 27987, 28073, -1, 27987, 28074, 28073, -1, 28075, 28074, 27987, -1, 28074, 28075, 28076, -1, 28076, 28077, 28078, -1, 28075, 28077, 28076, -1, 28078, 28079, 28080, -1, 28077, 28079, 28078, -1, 28080, 28081, 28082, -1, 28079, 28081, 28080, -1, 28082, 28083, 28084, -1, 28081, 28083, 28082, -1, 28084, 28085, 28086, -1, 28083, 28085, 28084, -1, 28086, 28087, 28088, -1, 28085, 28087, 28086, -1, 28088, 28089, 28090, -1, 28087, 28089, 28088, -1, 28090, 28091, 28092, -1, 28089, 28091, 28090, -1, 28092, 28093, 28094, -1, 28091, 28093, 28092, -1, 28094, 28095, 28096, -1, 28093, 28095, 28094, -1, 28096, 28097, 28098, -1, 28095, 28097, 28096, -1, 28098, 28099, 28100, -1, 28097, 28099, 28098, -1, 28099, 28101, 28100, -1, 28060, 28100, 28037, -1, 28100, 28101, 28037, -1, 28102, 25248, 27977, -1, 28102, 25259, 25248, -1, 28103, 27977, 27980, -1, 28103, 28102, 27977, -1, 28104, 27980, 27968, -1, 28104, 28103, 27980, -1, 28105, 27968, 28058, -1, 28105, 28104, 27968, -1, 28106, 28058, 28051, -1, 28106, 28105, 28058, -1, 28107, 28051, 28040, -1, 28107, 28106, 28051, -1, 28101, 28040, 28037, -1, 28101, 28107, 28040, -1, 28056, 25274, 25285, -1, 28056, 25285, 28108, -1, 28047, 28108, 28109, -1, 28047, 28056, 28108, -1, 28020, 28109, 28110, -1, 28020, 28047, 28109, -1, 28021, 28110, 28111, -1, 28021, 28020, 28110, -1, 28005, 28111, 28112, -1, 28005, 28021, 28111, -1, 27986, 28112, 28113, -1, 27986, 28005, 28112, -1, 27987, 28113, 28075, -1, 27987, 27986, 28113, -1, 28114, 28115, 28109, -1, 28116, 28117, 28118, -1, 28114, 25285, 25233, -1, 28114, 25233, 25232, -1, 28114, 28119, 28120, -1, 28114, 25232, 28119, -1, 28121, 28122, 28123, -1, 28114, 28120, 28115, -1, 28124, 28118, 28125, -1, 28121, 28123, 28126, -1, 28124, 28125, 28127, -1, 28128, 28129, 28130, -1, 28131, 28127, 28132, -1, 28128, 28126, 28129, -1, 28131, 28132, 28133, -1, 28134, 28130, 28135, -1, 28136, 28107, 28101, -1, 28137, 28138, 28139, -1, 28136, 28101, 28099, -1, 28134, 28135, 28140, -1, 28137, 28133, 28138, -1, 28141, 28106, 28107, -1, 28142, 28140, 28143, -1, 28142, 28143, 28144, -1, 28145, 28139, 28146, -1, 28141, 28107, 28136, -1, 28145, 28146, 28147, -1, 28148, 28144, 28081, -1, 28148, 28081, 28079, -1, 28149, 28099, 28097, -1, 28150, 28089, 28087, -1, 28150, 28147, 28089, -1, 28149, 28136, 28099, -1, 28151, 28122, 28121, -1, 28151, 25267, 28152, -1, 28153, 28105, 28106, -1, 28151, 25265, 25267, -1, 28151, 28152, 28122, -1, 28154, 25270, 25262, -1, 28154, 25262, 28116, -1, 28154, 28116, 28118, -1, 28155, 28126, 28128, -1, 28154, 28118, 28124, -1, 28153, 28106, 28141, -1, 28155, 28121, 28126, -1, 28156, 28124, 28127, -1, 28157, 28136, 28149, -1, 28158, 28130, 28134, -1, 28156, 28127, 28131, -1, 28159, 28131, 28133, -1, 28159, 28133, 28137, -1, 28157, 28141, 28136, -1, 28160, 28149, 28097, -1, 28160, 28097, 28095, -1, 28158, 28128, 28130, -1, 28161, 28134, 28140, -1, 28162, 28137, 28139, -1, 25261, 25259, 28102, -1, 28161, 28140, 28142, -1, 28162, 28139, 28145, -1, 28163, 28105, 28153, -1, 28163, 28104, 28105, -1, 28164, 28144, 28148, -1, 28165, 28147, 28150, -1, 28166, 28141, 28157, -1, 28164, 28142, 28144, -1, 28167, 28077, 28113, -1, 28165, 28145, 28147, -1, 28167, 28079, 28077, -1, 28166, 28153, 28141, -1, 28168, 28087, 28085, -1, 28167, 28148, 28079, -1, 28169, 25265, 28151, -1, 28170, 28157, 28149, -1, 28169, 25263, 25265, -1, 28168, 28150, 28087, -1, 28169, 28121, 28155, -1, 28171, 25269, 25270, -1, 28170, 28149, 28160, -1, 28169, 28151, 28121, -1, 28171, 28124, 28156, -1, 28172, 28095, 28093, -1, 28171, 28154, 28124, -1, 28171, 25270, 28154, -1, 28173, 28131, 28159, -1, 28174, 28128, 28158, -1, 28172, 28160, 28095, -1, 28174, 28155, 28128, -1, 28173, 28156, 28131, -1, 28117, 28103, 28104, -1, 28175, 28158, 28134, -1, 28175, 28134, 28161, -1, 28123, 28159, 28137, -1, 28117, 28104, 28163, -1, 28176, 28161, 28142, -1, 28123, 28137, 28162, -1, 28125, 28163, 28153, -1, 28125, 28153, 28166, -1, 28176, 28142, 28164, -1, 28129, 28162, 28145, -1, 28177, 28167, 28113, -1, 28129, 28145, 28165, -1, 28177, 28113, 28112, -1, 28132, 28157, 28170, -1, 28177, 28164, 28148, -1, 28132, 28166, 28157, -1, 28177, 28148, 28167, -1, 28178, 25263, 28169, -1, 28178, 25247, 25263, -1, 28135, 28150, 28168, -1, 28135, 28165, 28150, -1, 28138, 28170, 28160, -1, 28178, 28169, 28155, -1, 28178, 28155, 28174, -1, 28138, 28160, 28172, -1, 28143, 28085, 28083, -1, 28179, 28158, 28175, -1, 28146, 28093, 28091, -1, 28143, 28168, 28085, -1, 28179, 28174, 28158, -1, 28180, 25269, 28171, -1, 28146, 28172, 28093, -1, 28180, 25268, 25269, -1, 28180, 28171, 28156, -1, 28181, 28102, 28103, -1, 28180, 28156, 28173, -1, 28182, 28175, 28161, -1, 28182, 28161, 28176, -1, 28181, 25261, 28102, -1, 28181, 28103, 28117, -1, 28122, 28159, 28123, -1, 28118, 28163, 28125, -1, 28183, 28112, 28111, -1, 28122, 28173, 28159, -1, 28183, 28177, 28112, -1, 28183, 28176, 28164, -1, 28118, 28117, 28163, -1, 28183, 28164, 28177, -1, 28126, 28123, 28162, -1, 28126, 28162, 28129, -1, 28184, 25241, 25247, -1, 28184, 25247, 28178, -1, 28127, 28125, 28166, -1, 28184, 28178, 28174, -1, 28184, 28174, 28179, -1, 28130, 28129, 28165, -1, 28127, 28166, 28132, -1, 28113, 28077, 28075, -1, 28130, 28165, 28135, -1, 28120, 28179, 28175, -1, 28120, 28175, 28182, -1, 28133, 28170, 28138, -1, 28133, 28132, 28170, -1, 28185, 28111, 28110, -1, 28185, 28183, 28111, -1, 28185, 28182, 28176, -1, 28185, 28176, 28183, -1, 28139, 28138, 28172, -1, 28119, 25241, 28184, -1, 28140, 28135, 28168, -1, 28139, 28172, 28146, -1, 28140, 28168, 28143, -1, 28147, 28091, 28089, -1, 28119, 25232, 25241, -1, 28119, 28184, 28179, -1, 28144, 28083, 28081, -1, 28119, 28179, 28120, -1, 28144, 28143, 28083, -1, 28115, 28110, 28109, -1, 28147, 28146, 28091, -1, 28115, 28185, 28110, -1, 28152, 25267, 25268, -1, 28116, 28181, 28117, -1, 28115, 28120, 28182, -1, 28152, 25268, 28180, -1, 28115, 28182, 28185, -1, 28152, 28180, 28173, -1, 28116, 25262, 25261, -1, 28114, 28108, 25285, -1, 28152, 28173, 28122, -1, 28116, 25261, 28181, -1, 28114, 28109, 28108, -1, 28186, 28187, 28188, -1, 25020, 25023, 28187, -1, 25020, 28187, 28186, -1, 28189, 25043, 28190, -1, 28191, 25043, 28189, -1, 28191, 28189, 25035, -1, 28192, 25035, 25043, -1, 28192, 25043, 28191, -1, 28192, 28191, 25035, -1, 28193, 28190, 28194, -1, 28193, 25035, 28189, -1, 28193, 28189, 28190, -1, 28195, 28193, 28194, -1, 28195, 25035, 28193, -1, 28196, 25035, 28195, -1, 28196, 28195, 28194, -1, 28196, 25033, 25035, -1, 28197, 28194, 28198, -1, 28199, 28196, 28194, -1, 28199, 25033, 28196, -1, 28199, 28194, 28197, -1, 28199, 28197, 28198, -1, 28199, 25031, 25033, -1, 25043, 25044, 28200, -1, 25043, 28200, 28201, -1, 28202, 28198, 28203, -1, 25043, 28201, 28204, -1, 25043, 28204, 28205, -1, 25043, 28205, 28206, -1, 25043, 28206, 28207, -1, 28208, 25026, 25031, -1, 25043, 28207, 28209, -1, 28208, 28202, 28203, -1, 25043, 28209, 28190, -1, 28208, 28198, 28202, -1, 28208, 25031, 28199, -1, 28208, 28199, 28198, -1, 28210, 28203, 28211, -1, 28212, 28208, 28203, -1, 28212, 25024, 25026, -1, 28212, 28203, 28210, -1, 28212, 28210, 28211, -1, 28212, 25026, 28208, -1, 28213, 28211, 28214, -1, 28215, 28213, 28214, -1, 28215, 28211, 28213, -1, 28215, 25036, 25034, -1, 28215, 25034, 25024, -1, 28215, 25024, 28212, -1, 28215, 28212, 28211, -1, 28216, 28214, 28217, -1, 28218, 28215, 28214, -1, 28218, 25037, 25036, -1, 28218, 28216, 28217, -1, 28218, 25036, 28215, -1, 28218, 28214, 28216, -1, 28219, 28217, 28220, -1, 28221, 25037, 28218, -1, 28221, 28217, 28219, -1, 28221, 28218, 28217, -1, 28221, 28219, 28220, -1, 28221, 28220, 25037, -1, 28222, 28220, 28223, -1, 28224, 25038, 28220, -1, 28224, 28220, 28222, -1, 28224, 28222, 28223, -1, 28224, 28223, 25038, -1, 28225, 28223, 28226, -1, 28227, 28225, 28226, -1, 28227, 28223, 28225, -1, 28228, 28223, 28227, -1, 28228, 25039, 28223, -1, 28229, 28226, 28230, -1, 28229, 28230, 28231, -1, 28232, 28226, 28229, -1, 28232, 28227, 28226, -1, 28233, 25040, 25039, -1, 28233, 28228, 28227, -1, 25038, 25037, 28220, -1, 28233, 25039, 28228, -1, 28233, 28232, 25040, -1, 28233, 28227, 28232, -1, 28234, 28229, 28231, -1, 25039, 25038, 28223, -1, 28235, 28229, 28234, -1, 28235, 28232, 28229, -1, 28235, 25040, 28232, -1, 28236, 25032, 25040, -1, 28236, 28235, 25032, -1, 28236, 25040, 28235, -1, 28237, 28231, 28238, -1, 28237, 28238, 28239, -1, 28237, 28234, 28231, -1, 28240, 28237, 28239, -1, 28240, 28235, 28234, -1, 28240, 25032, 28235, -1, 28240, 28234, 28237, -1, 28241, 25023, 25032, -1, 28241, 25032, 28240, -1, 28242, 28239, 28187, -1, 28243, 28240, 28239, -1, 28243, 28239, 28242, -1, 28243, 28242, 28187, -1, 28244, 28187, 25023, -1, 28244, 28240, 28243, -1, 28244, 25023, 28241, -1, 28244, 28241, 28240, -1, 28244, 28243, 28187, -1, 28245, 28187, 28246, -1, 28247, 28187, 28245, -1, 28248, 28187, 28247, -1, 28249, 28187, 28248, -1, 28188, 28187, 28249, -1, 28209, 28250, 28190, -1, 28251, 28250, 28209, -1, 28190, 28252, 28194, -1, 28250, 28252, 28190, -1, 28194, 28253, 28198, -1, 28252, 28253, 28194, -1, 28198, 28254, 28203, -1, 28253, 28254, 28198, -1, 28203, 28255, 28211, -1, 28211, 28255, 28214, -1, 28254, 28255, 28203, -1, 28214, 28256, 28217, -1, 28255, 28256, 28214, -1, 28217, 28257, 28220, -1, 28256, 28257, 28217, -1, 28220, 28258, 28223, -1, 28223, 28258, 28226, -1, 28257, 28258, 28220, -1, 28226, 28259, 28230, -1, 28258, 28259, 28226, -1, 28230, 28260, 28231, -1, 28259, 28260, 28230, -1, 28231, 28261, 28238, -1, 28238, 28261, 28239, -1, 28260, 28261, 28231, -1, 28239, 28262, 28187, -1, 28261, 28262, 28239, -1, 28187, 28263, 28246, -1, 28262, 28263, 28187, -1, 28263, 28264, 28246, -1, 28209, 28265, 28251, -1, 28265, 28266, 28267, -1, 28265, 28268, 28266, -1, 28269, 28268, 28265, -1, 28270, 28271, 28263, -1, 28253, 28272, 28254, -1, 28273, 28272, 28253, -1, 28252, 28274, 28253, -1, 28253, 28274, 28273, -1, 28254, 28275, 28255, -1, 28272, 28275, 28254, -1, 28271, 28264, 28263, -1, 28276, 28264, 28277, -1, 28250, 28278, 28252, -1, 28277, 28264, 28279, -1, 28251, 28278, 28250, -1, 28279, 28264, 28280, -1, 28280, 28264, 28281, -1, 28252, 28278, 28274, -1, 28281, 28264, 28282, -1, 28282, 28264, 28271, -1, 28255, 28283, 28256, -1, 28275, 28283, 28255, -1, 28276, 28284, 28264, -1, 28268, 28284, 28276, -1, 28269, 28284, 28268, -1, 28285, 28284, 28269, -1, 28251, 28286, 28278, -1, 28287, 28288, 28285, -1, 28285, 28288, 28284, -1, 28256, 28289, 28257, -1, 28283, 28289, 28256, -1, 28290, 28291, 28287, -1, 28257, 28292, 28258, -1, 28287, 28291, 28288, -1, 28289, 28292, 28257, -1, 28290, 28293, 28291, -1, 28258, 28294, 28259, -1, 28292, 28294, 28258, -1, 28295, 28260, 28294, -1, 28294, 28260, 28259, -1, 28251, 28296, 28286, -1, 28297, 28261, 28295, -1, 28295, 28261, 28260, -1, 28297, 28262, 28261, -1, 28270, 28262, 28298, -1, 28298, 28262, 28297, -1, 28270, 28263, 28262, -1, 28251, 28265, 28296, -1, 28296, 28265, 28299, -1, 28299, 28265, 28300, -1, 28300, 28265, 28301, -1, 28301, 28265, 28267, -1, 28302, 28303, 28304, -1, 28305, 28306, 28307, -1, 28308, 28309, 28298, -1, 28310, 28311, 28312, -1, 28308, 28313, 28309, -1, 28308, 28298, 28297, -1, 28308, 28314, 28315, -1, 28316, 28312, 28317, -1, 28308, 28302, 28313, -1, 28308, 28297, 28314, -1, 28308, 28315, 28302, -1, 28305, 28318, 28306, -1, 28319, 28320, 28321, -1, 28316, 28317, 28322, -1, 28323, 28322, 28324, -1, 28325, 28326, 28327, -1, 28270, 28298, 28309, -1, 28319, 28307, 28320, -1, 28323, 28324, 28328, -1, 28329, 28321, 28330, -1, 28329, 28330, 28331, -1, 28332, 28326, 28325, -1, 28333, 28334, 28335, -1, 28333, 28328, 28334, -1, 28336, 28337, 28326, -1, 28338, 28331, 28339, -1, 28338, 28339, 28340, -1, 28341, 28342, 28343, -1, 28336, 28326, 28332, -1, 28341, 28335, 28342, -1, 28344, 28325, 28345, -1, 28346, 28340, 28347, -1, 28348, 28349, 28350, -1, 28346, 28347, 28351, -1, 28344, 28332, 28325, -1, 28348, 28343, 28349, -1, 28352, 28318, 28305, -1, 28352, 28353, 28318, -1, 28354, 28312, 28316, -1, 28355, 28356, 28337, -1, 28352, 28283, 28353, -1, 28352, 28289, 28283, -1, 28354, 28273, 28274, -1, 28354, 28274, 28310, -1, 28355, 28337, 28336, -1, 28354, 28310, 28312, -1, 28357, 28307, 28319, -1, 28358, 28322, 28323, -1, 28359, 28332, 28344, -1, 28357, 28305, 28307, -1, 28358, 28316, 28322, -1, 28359, 28336, 28332, -1, 28360, 28321, 28329, -1, 28361, 28345, 28362, -1, 28363, 28323, 28328, -1, 28363, 28328, 28333, -1, 28360, 28319, 28321, -1, 28361, 28344, 28345, -1, 28364, 28329, 28331, -1, 28365, 28356, 28355, -1, 28366, 28333, 28335, -1, 28366, 28335, 28341, -1, 28365, 28367, 28356, -1, 28364, 28331, 28338, -1, 28368, 28338, 28340, -1, 28369, 28343, 28348, -1, 28368, 28340, 28346, -1, 28369, 28341, 28343, -1, 28370, 28336, 28359, -1, 28371, 28351, 28372, -1, 28370, 28355, 28336, -1, 28371, 28372, 28373, -1, 28374, 28350, 28375, -1, 28371, 28373, 28376, -1, 28371, 28346, 28351, -1, 28377, 28352, 28305, -1, 28374, 28348, 28350, -1, 28378, 28344, 28361, -1, 28378, 28359, 28344, -1, 28377, 28289, 28352, -1, 28379, 28272, 28273, -1, 28377, 28292, 28289, -1, 28379, 28354, 28316, -1, 28380, 28362, 28381, -1, 28379, 28273, 28354, -1, 28377, 28305, 28357, -1, 28379, 28316, 28358, -1, 28382, 28357, 28319, -1, 28380, 28361, 28362, -1, 28383, 28358, 28323, -1, 28382, 28319, 28360, -1, 28311, 28384, 28367, -1, 28383, 28323, 28363, -1, 28385, 28360, 28329, -1, 28311, 28367, 28365, -1, 28385, 28329, 28364, -1, 28306, 28333, 28366, -1, 28306, 28363, 28333, -1, 28386, 28364, 28338, -1, 28317, 28365, 28355, -1, 28317, 28355, 28370, -1, 28320, 28366, 28341, -1, 28324, 28370, 28359, -1, 28386, 28338, 28368, -1, 28320, 28341, 28369, -1, 28387, 28371, 28376, -1, 28324, 28359, 28378, -1, 28387, 28376, 28388, -1, 28387, 28368, 28346, -1, 28387, 28346, 28371, -1, 28330, 28369, 28348, -1, 28389, 28357, 28382, -1, 28330, 28348, 28374, -1, 28334, 28378, 28361, -1, 28389, 28377, 28357, -1, 28389, 28294, 28292, -1, 28389, 28292, 28377, -1, 28339, 28375, 28390, -1, 28334, 28361, 28380, -1, 28391, 28360, 28385, -1, 28342, 28381, 28392, -1, 28339, 28374, 28375, -1, 28391, 28382, 28360, -1, 28393, 28275, 28272, -1, 28342, 28380, 28381, -1, 28393, 28272, 28379, -1, 28394, 28286, 28395, -1, 28394, 28395, 28384, -1, 28393, 28379, 28358, -1, 28393, 28358, 28383, -1, 28394, 28278, 28286, -1, 28394, 28384, 28311, -1, 28303, 28364, 28386, -1, 28303, 28385, 28364, -1, 28396, 28388, 28397, -1, 28318, 28383, 28363, -1, 28318, 28363, 28306, -1, 28396, 28387, 28388, -1, 28312, 28311, 28365, -1, 28312, 28365, 28317, -1, 28396, 28386, 28368, -1, 28396, 28368, 28387, -1, 28398, 28389, 28382, -1, 28307, 28306, 28366, -1, 28307, 28366, 28320, -1, 28398, 28295, 28294, -1, 28322, 28317, 28370, -1, 28398, 28294, 28389, -1, 28322, 28370, 28324, -1, 28398, 28382, 28391, -1, 28328, 28378, 28334, -1, 28321, 28320, 28369, -1, 28315, 28391, 28385, -1, 28321, 28369, 28330, -1, 28328, 28324, 28378, -1, 28315, 28385, 28303, -1, 28304, 28397, 28399, -1, 28304, 28396, 28397, -1, 28304, 28303, 28386, -1, 28304, 28386, 28396, -1, 28335, 28380, 28342, -1, 28331, 28330, 28374, -1, 28335, 28334, 28380, -1, 28314, 28391, 28315, -1, 28331, 28374, 28339, -1, 28343, 28342, 28392, -1, 28343, 28392, 28349, -1, 28314, 28297, 28295, -1, 28340, 28339, 28390, -1, 28314, 28398, 28391, -1, 28340, 28390, 28347, -1, 28314, 28295, 28398, -1, 28353, 28275, 28393, -1, 28302, 28399, 28313, -1, 28353, 28283, 28275, -1, 28310, 28278, 28394, -1, 28310, 28394, 28311, -1, 28302, 28304, 28399, -1, 28353, 28393, 28383, -1, 28353, 28383, 28318, -1, 28302, 28315, 28303, -1, 28310, 28274, 28278, -1, 28400, 28373, 28401, -1, 28401, 28372, 28402, -1, 28373, 28372, 28401, -1, 28402, 28351, 28403, -1, 28372, 28351, 28402, -1, 28403, 28347, 28404, -1, 28351, 28347, 28403, -1, 28404, 28390, 28405, -1, 28347, 28390, 28404, -1, 28405, 28375, 28406, -1, 28390, 28375, 28405, -1, 28406, 28350, 28407, -1, 28375, 28350, 28406, -1, 28407, 28349, 28408, -1, 28350, 28349, 28407, -1, 28408, 28392, 28409, -1, 28349, 28392, 28408, -1, 28409, 28381, 28410, -1, 28392, 28381, 28409, -1, 28410, 28362, 28411, -1, 28381, 28362, 28410, -1, 28411, 28345, 28412, -1, 28362, 28345, 28411, -1, 28412, 28325, 28413, -1, 28345, 28325, 28412, -1, 28325, 28327, 28413, -1, 28327, 28414, 28413, -1, 28415, 28414, 28327, -1, 28414, 28415, 28416, -1, 28416, 28417, 28418, -1, 28415, 28417, 28416, -1, 28418, 28419, 28420, -1, 28417, 28419, 28418, -1, 28420, 28421, 28422, -1, 28419, 28421, 28420, -1, 28422, 28423, 28424, -1, 28421, 28423, 28422, -1, 28424, 28425, 28426, -1, 28423, 28425, 28424, -1, 28426, 28427, 28428, -1, 28425, 28427, 28426, -1, 28428, 28429, 28430, -1, 28427, 28429, 28428, -1, 28430, 28431, 28432, -1, 28429, 28431, 28430, -1, 28432, 28433, 28434, -1, 28431, 28433, 28432, -1, 28434, 28435, 28436, -1, 28433, 28435, 28434, -1, 28436, 28437, 28438, -1, 28435, 28437, 28436, -1, 28438, 28439, 28440, -1, 28437, 28439, 28438, -1, 28439, 28441, 28440, -1, 28400, 28440, 28373, -1, 28440, 28441, 28373, -1, 28442, 28270, 28309, -1, 28442, 28271, 28270, -1, 28443, 28309, 28313, -1, 28443, 28442, 28309, -1, 28444, 28313, 28399, -1, 28444, 28443, 28313, -1, 28445, 28399, 28397, -1, 28445, 28444, 28399, -1, 28446, 28397, 28388, -1, 28446, 28445, 28397, -1, 28447, 28388, 28376, -1, 28447, 28446, 28388, -1, 28441, 28376, 28373, -1, 28441, 28447, 28376, -1, 28395, 28286, 28296, -1, 28395, 28296, 28448, -1, 28384, 28448, 28449, -1, 28384, 28395, 28448, -1, 28367, 28449, 28450, -1, 28367, 28384, 28449, -1, 28356, 28450, 28451, -1, 28356, 28367, 28450, -1, 28337, 28451, 28452, -1, 28337, 28356, 28451, -1, 28326, 28452, 28453, -1, 28326, 28337, 28452, -1, 28327, 28453, 28415, -1, 28327, 28326, 28453, -1, 28454, 28455, 28449, -1, 28456, 28457, 28458, -1, 28454, 28448, 28296, -1, 28454, 28449, 28448, -1, 28454, 28459, 28460, -1, 28454, 28296, 28299, -1, 28461, 28462, 28463, -1, 28454, 28299, 28300, -1, 28464, 28458, 28465, -1, 28454, 28300, 28459, -1, 28461, 28463, 28466, -1, 28464, 28465, 28467, -1, 28454, 28460, 28455, -1, 28468, 28469, 28470, -1, 28471, 28467, 28472, -1, 28468, 28466, 28469, -1, 28471, 28472, 28473, -1, 28474, 28470, 28475, -1, 28476, 28447, 28441, -1, 28477, 28478, 28479, -1, 28476, 28441, 28439, -1, 28474, 28475, 28480, -1, 28477, 28473, 28478, -1, 28481, 28446, 28447, -1, 28482, 28480, 28483, -1, 28482, 28483, 28484, -1, 28485, 28479, 28486, -1, 28481, 28447, 28476, -1, 28485, 28486, 28487, -1, 28488, 28484, 28421, -1, 28489, 28439, 28437, -1, 28490, 28429, 28427, -1, 28488, 28421, 28419, -1, 28490, 28487, 28429, -1, 28489, 28476, 28439, -1, 28491, 28462, 28461, -1, 28492, 28445, 28446, -1, 28491, 28276, 28493, -1, 28491, 28268, 28276, -1, 28494, 28280, 28281, -1, 28491, 28493, 28462, -1, 28494, 28281, 28456, -1, 28494, 28456, 28458, -1, 28494, 28458, 28464, -1, 28495, 28466, 28468, -1, 28492, 28446, 28481, -1, 28496, 28464, 28467, -1, 28497, 28476, 28489, -1, 28495, 28461, 28466, -1, 28498, 28470, 28474, -1, 28496, 28467, 28471, -1, 28499, 28471, 28473, -1, 28499, 28473, 28477, -1, 28497, 28481, 28476, -1, 28500, 28489, 28437, -1, 28500, 28437, 28435, -1, 28498, 28468, 28470, -1, 28501, 28474, 28480, -1, 28502, 28477, 28479, -1, 28282, 28271, 28442, -1, 28501, 28480, 28482, -1, 28502, 28479, 28485, -1, 28503, 28445, 28492, -1, 28503, 28444, 28445, -1, 28504, 28482, 28484, -1, 28504, 28484, 28488, -1, 28505, 28487, 28490, -1, 28506, 28481, 28497, -1, 28505, 28485, 28487, -1, 28507, 28419, 28417, -1, 28507, 28417, 28415, -1, 28506, 28492, 28481, -1, 28507, 28488, 28419, -1, 28508, 28427, 28425, -1, 28507, 28415, 28453, -1, 28509, 28497, 28489, -1, 28510, 28268, 28491, -1, 28508, 28490, 28427, -1, 28510, 28266, 28268, -1, 28511, 28279, 28280, -1, 28509, 28489, 28500, -1, 28510, 28461, 28495, -1, 28511, 28464, 28496, -1, 28512, 28435, 28433, -1, 28510, 28491, 28461, -1, 28511, 28494, 28464, -1, 28511, 28280, 28494, -1, 28513, 28471, 28499, -1, 28512, 28500, 28435, -1, 28514, 28468, 28498, -1, 28513, 28496, 28471, -1, 28457, 28443, 28444, -1, 28514, 28495, 28468, -1, 28515, 28474, 28501, -1, 28515, 28498, 28474, -1, 28463, 28499, 28477, -1, 28457, 28444, 28503, -1, 28463, 28477, 28502, -1, 28516, 28501, 28482, -1, 28465, 28503, 28492, -1, 28465, 28492, 28506, -1, 28469, 28502, 28485, -1, 28516, 28482, 28504, -1, 28469, 28485, 28505, -1, 28517, 28488, 28507, -1, 28472, 28497, 28509, -1, 28472, 28506, 28497, -1, 28517, 28453, 28452, -1, 28517, 28504, 28488, -1, 28517, 28507, 28453, -1, 28475, 28490, 28508, -1, 28518, 28266, 28510, -1, 28475, 28505, 28490, -1, 28478, 28509, 28500, -1, 28518, 28267, 28266, -1, 28518, 28510, 28495, -1, 28478, 28500, 28512, -1, 28518, 28495, 28514, -1, 28483, 28425, 28423, -1, 28486, 28433, 28431, -1, 28519, 28514, 28498, -1, 28483, 28508, 28425, -1, 28520, 28279, 28511, -1, 28486, 28512, 28433, -1, 28519, 28498, 28515, -1, 28520, 28277, 28279, -1, 28520, 28511, 28496, -1, 28521, 28442, 28443, -1, 28520, 28496, 28513, -1, 28521, 28282, 28442, -1, 28522, 28515, 28501, -1, 28521, 28443, 28457, -1, 28522, 28501, 28516, -1, 28462, 28499, 28463, -1, 28458, 28503, 28465, -1, 28462, 28513, 28499, -1, 28523, 28452, 28451, -1, 28458, 28457, 28503, -1, 28523, 28517, 28452, -1, 28523, 28516, 28504, -1, 28523, 28504, 28517, -1, 28466, 28463, 28502, -1, 28466, 28502, 28469, -1, 28524, 28514, 28519, -1, 28467, 28465, 28506, -1, 28524, 28301, 28267, -1, 28470, 28469, 28505, -1, 28467, 28506, 28472, -1, 28524, 28518, 28514, -1, 28524, 28267, 28518, -1, 28470, 28505, 28475, -1, 28473, 28509, 28478, -1, 28460, 28519, 28515, -1, 28473, 28472, 28509, -1, 28460, 28515, 28522, -1, 28525, 28451, 28450, -1, 28525, 28523, 28451, -1, 28525, 28522, 28516, -1, 28479, 28478, 28512, -1, 28525, 28516, 28523, -1, 28480, 28475, 28508, -1, 28479, 28512, 28486, -1, 28459, 28524, 28519, -1, 28480, 28508, 28483, -1, 28459, 28519, 28460, -1, 28487, 28431, 28429, -1, 28484, 28423, 28421, -1, 28459, 28300, 28301, -1, 28459, 28301, 28524, -1, 28484, 28483, 28423, -1, 28487, 28486, 28431, -1, 28455, 28450, 28449, -1, 28493, 28276, 28277, -1, 28456, 28521, 28457, -1, 28493, 28277, 28520, -1, 28455, 28525, 28450, -1, 28455, 28460, 28522, -1, 28493, 28520, 28513, -1, 28456, 28281, 28282, -1, 28455, 28522, 28525, -1, 28493, 28513, 28462, -1, 28456, 28282, 28521, -1, 28245, 28246, 28264, -1, 28245, 28264, 28284, -1, 28247, 28245, 28284, -1, 28248, 28284, 28288, -1, 28248, 28247, 28284, -1, 28249, 28288, 28291, -1, 28249, 28248, 28288, -1, 28188, 28291, 28293, -1, 28188, 28293, 28526, -1, 28188, 28249, 28291, -1, 28186, 28526, 28527, -1, 28186, 28188, 28526, -1, 25020, 28527, 25028, -1, 25020, 28186, 28527, -1, 28265, 28209, 28207, -1, 28269, 28207, 28206, -1, 28269, 28265, 28207, -1, 28285, 28206, 28205, -1, 28285, 28269, 28206, -1, 28287, 28205, 28204, -1, 28287, 28285, 28205, -1, 28290, 28204, 28201, -1, 28290, 28287, 28204, -1, 28528, 28201, 28200, -1, 28528, 28290, 28201, -1, 28529, 28200, 25044, -1, 28529, 28528, 28200, -1, 25027, 28529, 25044, -1, 28293, 28290, 28528, -1, 28526, 28528, 28529, -1, 28526, 28293, 28528, -1, 28527, 28529, 25027, -1, 28527, 28526, 28529, -1, 25028, 28527, 25027, -1, 28530, 28531, 28532, -1, 28533, 15755, 15621, -1, 28533, 15745, 15755, -1, 28534, 28535, 28536, -1, 28533, 15621, 15622, -1, 28537, 28538, 28539, -1, 28533, 15622, 28540, -1, 28533, 28540, 28541, -1, 28533, 28542, 15745, -1, 28533, 28541, 28542, -1, 28537, 28543, 28538, -1, 28544, 28545, 28546, -1, 28534, 28532, 28535, -1, 28547, 28536, 28548, -1, 15619, 15621, 15755, -1, 28549, 15738, 15737, -1, 28544, 28539, 28545, -1, 28547, 28548, 28550, -1, 28551, 28546, 28552, -1, 28549, 15737, 25612, -1, 28553, 28554, 28555, -1, 28551, 28552, 28556, -1, 28557, 15749, 15738, -1, 28553, 28550, 28554, -1, 28558, 28556, 28559, -1, 28558, 28559, 28560, -1, 28557, 15738, 28549, -1, 28561, 28555, 28562, -1, 28561, 28562, 28563, -1, 28564, 25612, 25611, -1, 28565, 28560, 25603, -1, 28566, 25607, 25606, -1, 28565, 25603, 25602, -1, 28564, 28549, 25612, -1, 28566, 28563, 25607, -1, 28567, 15757, 15749, -1, 28568, 28543, 28537, -1, 28569, 15647, 15630, -1, 28569, 15630, 28530, -1, 28568, 15643, 15644, -1, 28569, 28530, 28532, -1, 28568, 15644, 28570, -1, 28569, 28532, 28534, -1, 28567, 15749, 28557, -1, 28568, 28570, 28543, -1, 28571, 28539, 28544, -1, 28572, 28536, 28547, -1, 28573, 28557, 28549, -1, 28573, 28549, 28564, -1, 28571, 28537, 28539, -1, 28572, 28534, 28536, -1, 28574, 28544, 28546, -1, 28574, 28546, 28551, -1, 28575, 25611, 25610, -1, 28576, 28547, 28550, -1, 28576, 28550, 28553, -1, 28577, 28556, 28558, -1, 28575, 28564, 25611, -1, 28578, 15757, 28567, -1, 28579, 28553, 28555, -1, 28578, 15759, 15757, -1, 28579, 28555, 28561, -1, 28577, 28551, 28556, -1, 28580, 28558, 28560, -1, 28581, 28557, 28573, -1, 28582, 28563, 28566, -1, 28580, 28560, 28565, -1, 28582, 28561, 28563, -1, 28581, 28567, 28557, -1, 28583, 25602, 25601, -1, 28583, 25601, 15688, -1, 28583, 15688, 15694, -1, 28584, 25606, 25605, -1, 28583, 28565, 25602, -1, 28585, 28573, 28564, -1, 28586, 15643, 28568, -1, 28584, 28566, 25606, -1, 28585, 28564, 28575, -1, 28586, 15628, 15643, -1, 28587, 15646, 15647, -1, 28586, 28537, 28571, -1, 28587, 15647, 28569, -1, 28588, 25610, 25609, -1, 28587, 28569, 28534, -1, 28586, 28568, 28537, -1, 28587, 28534, 28572, -1, 28589, 28572, 28547, -1, 28588, 28575, 25610, -1, 28590, 28544, 28574, -1, 28531, 15674, 15759, -1, 28590, 28571, 28544, -1, 28589, 28547, 28576, -1, 28591, 28574, 28551, -1, 28591, 28551, 28577, -1, 28538, 28553, 28579, -1, 28531, 15759, 28578, -1, 28538, 28576, 28553, -1, 28592, 28577, 28558, -1, 28535, 28578, 28567, -1, 28535, 28567, 28581, -1, 28545, 28579, 28561, -1, 28545, 28561, 28582, -1, 28592, 28558, 28580, -1, 28548, 28573, 28585, -1, 28593, 28583, 15694, -1, 28593, 15694, 15703, -1, 28548, 28581, 28573, -1, 28593, 28580, 28565, -1, 28593, 28565, 28583, -1, 28552, 28582, 28566, -1, 28594, 15626, 15628, -1, 28554, 28585, 28575, -1, 28594, 28586, 28571, -1, 28552, 28566, 28584, -1, 28594, 28571, 28590, -1, 28554, 28575, 28588, -1, 28594, 15628, 28586, -1, 28559, 25605, 25604, -1, 28562, 25609, 25608, -1, 28595, 28574, 28591, -1, 28595, 28590, 28574, -1, 28559, 28584, 25605, -1, 28562, 28588, 25609, -1, 28596, 15646, 28587, -1, 28596, 15645, 15646, -1, 28597, 28591, 28577, -1, 28596, 28572, 28589, -1, 28598, 15675, 15674, -1, 28598, 15632, 15675, -1, 28596, 28587, 28572, -1, 28598, 15631, 15632, -1, 28598, 15674, 28531, -1, 28597, 28577, 28592, -1, 28532, 28578, 28535, -1, 28543, 28589, 28576, -1, 28543, 28576, 28538, -1, 28599, 15703, 15718, -1, 28532, 28531, 28578, -1, 28599, 28593, 15703, -1, 28599, 28592, 28580, -1, 28599, 28580, 28593, -1, 28539, 28538, 28579, -1, 28539, 28579, 28545, -1, 28600, 15626, 28594, -1, 28600, 15624, 15626, -1, 28600, 28594, 28590, -1, 28536, 28535, 28581, -1, 28600, 28590, 28595, -1, 28546, 28545, 28582, -1, 28536, 28581, 28548, -1, 28546, 28582, 28552, -1, 28550, 28548, 28585, -1, 28541, 28595, 28591, -1, 28550, 28585, 28554, -1, 28541, 28591, 28597, -1, 28601, 15718, 15729, -1, 28601, 28599, 15718, -1, 28601, 28597, 28592, -1, 28601, 28592, 28599, -1, 28556, 28552, 28584, -1, 28555, 28588, 28562, -1, 28556, 28584, 28559, -1, 28555, 28554, 28588, -1, 28563, 25608, 25607, -1, 28540, 15622, 15624, -1, 28540, 15624, 28600, -1, 28560, 25604, 25603, -1, 28540, 28600, 28595, -1, 28540, 28595, 28541, -1, 28560, 28559, 25604, -1, 28542, 28601, 15729, -1, 28563, 28562, 25608, -1, 28570, 15644, 15645, -1, 28530, 28598, 28531, -1, 28542, 15729, 15745, -1, 28570, 15645, 28596, -1, 28542, 28541, 28597, -1, 28570, 28596, 28589, -1, 28530, 15630, 15631, -1, 28542, 28597, 28601, -1, 28570, 28589, 28543, -1, 28530, 15631, 28598, -1, 28602, 28603, 28604, -1, 28602, 28604, 28605, -1, 28602, 28605, 24918, -1, 28606, 28607, 28608, -1, 28609, 28610, 28611, -1, 28612, 28613, 28614, -1, 28615, 28611, 28616, -1, 28612, 28617, 28613, -1, 28618, 28614, 28619, -1, 28615, 28616, 28620, -1, 28618, 28619, 28621, -1, 28622, 28620, 28623, -1, 28624, 24900, 24899, -1, 28624, 24899, 25690, -1, 28622, 28623, 28625, -1, 28626, 28621, 28627, -1, 28628, 24920, 24900, -1, 28626, 28627, 28629, -1, 28630, 28625, 28631, -1, 28630, 28631, 28632, -1, 28633, 28629, 25681, -1, 28628, 24900, 28624, -1, 28633, 25681, 25680, -1, 28634, 25685, 25684, -1, 28635, 25690, 25689, -1, 28634, 28632, 25685, -1, 28635, 28624, 25690, -1, 28636, 28607, 28606, -1, 28637, 28638, 28609, -1, 28636, 24831, 24829, -1, 28639, 24927, 24920, -1, 28636, 24829, 28640, -1, 28636, 28640, 28607, -1, 28637, 24822, 24826, -1, 28641, 28606, 28617, -1, 28637, 28642, 28638, -1, 28637, 24826, 28642, -1, 28639, 24920, 28628, -1, 28643, 28628, 28624, -1, 28641, 28617, 28612, -1, 28644, 28609, 28611, -1, 28643, 28624, 28635, -1, 28645, 28614, 28618, -1, 28644, 28611, 28615, -1, 28646, 28620, 28622, -1, 28645, 28612, 28614, -1, 28646, 28615, 28620, -1, 28647, 25689, 25688, -1, 28648, 28618, 28621, -1, 28649, 28622, 28625, -1, 24828, 24830, 24857, -1, 28647, 28635, 25689, -1, 28650, 24927, 28639, -1, 28649, 28625, 28630, -1, 28650, 24933, 24927, -1, 28648, 28621, 28626, -1, 28651, 28629, 28633, -1, 28651, 28626, 28629, -1, 28652, 28630, 28632, -1, 28653, 28628, 28643, -1, 28652, 28632, 28634, -1, 28654, 25679, 24852, -1, 28654, 25680, 25679, -1, 28655, 25684, 25683, -1, 28654, 28633, 25680, -1, 28653, 28639, 28628, -1, 28656, 28636, 28606, -1, 28655, 28634, 25684, -1, 28656, 28606, 28641, -1, 28656, 24831, 28636, -1, 28657, 28643, 28635, -1, 28656, 24833, 24831, -1, 28657, 28635, 28647, -1, 28658, 24823, 24822, -1, 28658, 28637, 28609, -1, 28658, 24822, 28637, -1, 28658, 28609, 28644, -1, 28659, 25688, 25687, -1, 28660, 28641, 28612, -1, 28660, 28612, 28645, -1, 28661, 28644, 28615, -1, 28659, 28647, 25688, -1, 28661, 28615, 28646, -1, 28662, 28645, 28618, -1, 28663, 24936, 24933, -1, 28608, 28646, 28622, -1, 28662, 28618, 28648, -1, 28608, 28622, 28649, -1, 28663, 24933, 28650, -1, 28664, 28626, 28651, -1, 28610, 28650, 28639, -1, 28613, 28649, 28630, -1, 28664, 28648, 28626, -1, 28613, 28630, 28652, -1, 28610, 28639, 28653, -1, 28665, 28654, 24852, -1, 28665, 24852, 24874, -1, 28616, 28653, 28643, -1, 28665, 28633, 28654, -1, 28665, 28651, 28633, -1, 28616, 28643, 28657, -1, 28666, 28641, 28660, -1, 28666, 28656, 28641, -1, 28619, 28652, 28634, -1, 28619, 28634, 28655, -1, 28666, 24835, 24833, -1, 28666, 24833, 28656, -1, 28623, 28657, 28647, -1, 28667, 28645, 28662, -1, 28627, 25683, 25682, -1, 28667, 28660, 28645, -1, 28623, 28647, 28659, -1, 28627, 28655, 25683, -1, 28631, 25687, 25686, -1, 28668, 28644, 28661, -1, 28631, 28659, 25687, -1, 28668, 28658, 28644, -1, 28668, 24827, 24823, -1, 28668, 24823, 28658, -1, 28669, 24857, 24936, -1, 28670, 28662, 28648, -1, 28669, 24936, 28663, -1, 28670, 28648, 28664, -1, 28669, 24828, 24857, -1, 28671, 24874, 24889, -1, 28607, 28661, 28646, -1, 28638, 28650, 28610, -1, 28607, 28646, 28608, -1, 28671, 28665, 24874, -1, 28671, 28664, 28651, -1, 28638, 28663, 28650, -1, 28671, 28651, 28665, -1, 28672, 24837, 24835, -1, 28672, 28660, 28667, -1, 28617, 28649, 28613, -1, 28672, 28666, 28660, -1, 28617, 28608, 28649, -1, 28672, 24835, 28666, -1, 28611, 28653, 28616, -1, 24852, 25679, 24853, -1, 28611, 28610, 28653, -1, 28614, 28613, 28652, -1, 28604, 28667, 28662, -1, 28614, 28652, 28619, -1, 28604, 28662, 28670, -1, 28673, 28670, 28664, -1, 28620, 28616, 28657, -1, 28620, 28657, 28623, -1, 28673, 24889, 24902, -1, 28673, 28664, 28671, -1, 28673, 28671, 24889, -1, 28621, 28619, 28655, -1, 28625, 28659, 28631, -1, 28621, 28655, 28627, -1, 28625, 28623, 28659, -1, 28603, 24839, 24837, -1, 28603, 24837, 28672, -1, 28632, 25686, 25685, -1, 28603, 28672, 28667, -1, 28629, 28627, 25682, -1, 28603, 28667, 28604, -1, 28629, 25682, 25681, -1, 28605, 28604, 28670, -1, 28605, 24902, 24918, -1, 28632, 28631, 25686, -1, 28605, 28670, 28673, -1, 28640, 24829, 24827, -1, 28640, 28668, 28661, -1, 28642, 24828, 28669, -1, 28642, 28669, 28663, -1, 28605, 28673, 24902, -1, 28640, 24827, 28668, -1, 28602, 24918, 24897, -1, 28640, 28661, 28607, -1, 28602, 24897, 24807, -1, 28606, 28608, 28617, -1, 28642, 24826, 24828, -1, 28602, 24807, 24808, -1, 28642, 28663, 28638, -1, 28602, 24808, 24839, -1, 28609, 28638, 28610, -1, 28602, 24839, 28603, -1, 28674, 28675, 24372, -1, 28676, 15230, 15229, -1, 28677, 15225, 28678, -1, 28674, 28679, 28680, -1, 28676, 15229, 28681, -1, 28677, 28682, 28683, -1, 28674, 28680, 28675, -1, 28676, 28684, 28685, -1, 28686, 24392, 24376, -1, 28676, 28681, 28684, -1, 28677, 15226, 15225, -1, 28686, 24376, 15237, -1, 28687, 28688, 28689, -1, 28686, 15237, 15236, -1, 28677, 28678, 28682, -1, 28686, 15236, 15235, -1, 28690, 28683, 28691, -1, 28686, 28674, 24392, -1, 28686, 28692, 28679, -1, 28686, 15235, 28692, -1, 28686, 28679, 28674, -1, 28687, 28685, 28688, -1, 28693, 28689, 28694, -1, 28690, 28691, 28695, -1, 28696, 28695, 28697, -1, 28693, 28694, 28698, -1, 28699, 28698, 28700, -1, 28701, 24373, 24370, -1, 28696, 28697, 28702, -1, 28703, 28702, 28704, -1, 28701, 24370, 25625, -1, 28699, 28700, 28705, -1, 28703, 28704, 28706, -1, 28707, 24390, 24373, -1, 28708, 28705, 28709, -1, 28708, 28709, 28710, -1, 28711, 28706, 28712, -1, 28711, 28712, 28713, -1, 28707, 24373, 28701, -1, 28714, 28710, 25629, -1, 28714, 25629, 25628, -1, 28715, 25633, 25635, -1, 28716, 25625, 25621, -1, 28716, 28701, 25625, -1, 28717, 28676, 28685, -1, 28715, 28713, 25633, -1, 28718, 28677, 28683, -1, 28719, 24401, 24390, -1, 28717, 15231, 15230, -1, 28718, 15227, 15226, -1, 28717, 15230, 28676, -1, 28718, 28683, 28690, -1, 28717, 28685, 28687, -1, 28718, 15226, 28677, -1, 28720, 28689, 28693, -1, 28719, 24390, 28707, -1, 28721, 28695, 28696, -1, 28722, 28707, 28701, -1, 28722, 28701, 28716, -1, 28720, 28687, 28689, -1, 28721, 28690, 28695, -1, 28723, 28696, 28702, -1, 15225, 15224, 24327, -1, 28724, 25621, 25615, -1, 28725, 28698, 28699, -1, 28725, 28693, 28698, -1, 28723, 28702, 28703, -1, 28724, 28716, 25621, -1, 28726, 28706, 28711, -1, 28726, 28703, 28706, -1, 28727, 24401, 28719, -1, 28727, 24407, 24401, -1, 28728, 28699, 28705, -1, 28728, 28705, 28708, -1, 28729, 28708, 28710, -1, 28730, 28707, 28722, -1, 28731, 28711, 28713, -1, 28729, 28710, 28714, -1, 28731, 28713, 28715, -1, 28732, 25630, 24329, -1, 28732, 25628, 25630, -1, 28730, 28719, 28707, -1, 28733, 25635, 25637, -1, 28732, 28714, 25628, -1, 28734, 28717, 28687, -1, 28735, 28722, 28716, -1, 28734, 15231, 28717, -1, 28733, 28715, 25635, -1, 28734, 28687, 28720, -1, 28735, 28716, 28724, -1, 28736, 15228, 15227, -1, 28734, 15232, 15231, -1, 28736, 15227, 28718, -1, 28737, 28720, 28693, -1, 28736, 28718, 28690, -1, 28738, 25615, 25618, -1, 28736, 28690, 28721, -1, 28737, 28693, 28725, -1, 28684, 28696, 28723, -1, 28738, 28724, 25615, -1, 28682, 24410, 24407, -1, 28739, 28725, 28699, -1, 28739, 28699, 28728, -1, 28684, 28721, 28696, -1, 28688, 28723, 28703, -1, 28682, 24407, 28727, -1, 28688, 28703, 28726, -1, 28691, 28727, 28719, -1, 28740, 28708, 28729, -1, 28694, 28726, 28711, -1, 28691, 28719, 28730, -1, 28740, 28728, 28708, -1, 28694, 28711, 28731, -1, 28741, 28732, 24329, -1, 28741, 24329, 24344, -1, 28697, 28730, 28722, -1, 28741, 28729, 28714, -1, 28697, 28722, 28735, -1, 28741, 28714, 28732, -1, 28742, 15233, 15232, -1, 28700, 28731, 28715, -1, 28742, 28720, 28737, -1, 28742, 28734, 28720, -1, 28700, 28715, 28733, -1, 28742, 15232, 28734, -1, 28704, 28735, 28724, -1, 28709, 25637, 25639, -1, 28743, 28725, 28739, -1, 28704, 28724, 28738, -1, 28743, 28737, 28725, -1, 28712, 25618, 25623, -1, 28709, 28733, 25637, -1, 28712, 28738, 25618, -1, 28680, 28739, 28728, -1, 28681, 15229, 15228, -1, 28681, 15228, 28736, -1, 28681, 28736, 28721, -1, 28678, 24327, 24410, -1, 28680, 28728, 28740, -1, 28681, 28721, 28684, -1, 28678, 24410, 28682, -1, 28678, 15225, 24327, -1, 28744, 24344, 24361, -1, 28685, 28684, 28723, -1, 28683, 28727, 28691, -1, 28744, 28741, 24344, -1, 28685, 28723, 28688, -1, 28744, 28740, 28729, -1, 28744, 28729, 28741, -1, 28683, 28682, 28727, -1, 28745, 15234, 15233, -1, 28745, 15233, 28742, -1, 28689, 28726, 28694, -1, 28689, 28688, 28726, -1, 28745, 28742, 28737, -1, 24329, 25630, 24330, -1, 28745, 28737, 28743, -1, 28695, 28730, 28697, -1, 28679, 28743, 28739, -1, 28695, 28691, 28730, -1, 28698, 28694, 28731, -1, 28698, 28731, 28700, -1, 28679, 28739, 28680, -1, 28702, 28697, 28735, -1, 28702, 28735, 28704, -1, 28675, 24361, 24372, -1, 28675, 28744, 24361, -1, 28675, 28680, 28740, -1, 28675, 28740, 28744, -1, 28706, 28738, 28712, -1, 28705, 28733, 28709, -1, 28692, 15234, 28745, -1, 28705, 28700, 28733, -1, 28706, 28704, 28738, -1, 28713, 25623, 25633, -1, 28692, 15235, 15234, -1, 28692, 28745, 28743, -1, 28710, 28709, 25639, -1, 28692, 28743, 28679, -1, 28710, 25639, 25629, -1, 28674, 24372, 24392, -1, 28713, 28712, 25623, -1, 28746, 17625, 15180, -1, 28747, 28748, 28749, -1, 28746, 17643, 17625, -1, 28750, 28749, 28751, -1, 28746, 15180, 15179, -1, 28746, 15179, 28752, -1, 28753, 28754, 28755, -1, 28746, 28756, 17643, -1, 28746, 28752, 28757, -1, 28746, 28757, 28756, -1, 28753, 28758, 28754, -1, 28759, 28760, 28761, -1, 28750, 28751, 28762, -1, 28763, 28762, 28764, -1, 15181, 15180, 17625, -1, 28759, 28755, 28760, -1, 28765, 17633, 17492, -1, 28763, 28764, 28766, -1, 28767, 28761, 28768, -1, 28769, 28766, 28770, -1, 28765, 17492, 17507, -1, 28767, 28768, 28771, -1, 28772, 17646, 17633, -1, 28769, 28770, 28773, -1, 28774, 28771, 28775, -1, 28774, 28775, 28776, -1, 28772, 17633, 28765, -1, 28777, 28773, 28778, -1, 28777, 28778, 28779, -1, 28780, 17507, 17509, -1, 28781, 28776, 17519, -1, 28782, 17464, 17463, -1, 28781, 17519, 17514, -1, 28780, 28765, 17507, -1, 28782, 28779, 17464, -1, 28783, 17653, 17646, -1, 28784, 28758, 28753, -1, 28785, 28749, 28750, -1, 28785, 15171, 15170, -1, 28784, 15175, 15174, -1, 28785, 15170, 28747, -1, 28784, 28786, 28758, -1, 28783, 17646, 28772, -1, 28784, 15174, 28786, -1, 28785, 28747, 28749, -1, 28787, 28755, 28759, -1, 28788, 28772, 28765, -1, 28788, 28765, 28780, -1, 28789, 28750, 28762, -1, 28787, 28753, 28755, -1, 28790, 28759, 28761, -1, 28789, 28762, 28763, -1, 28790, 28761, 28767, -1, 28791, 17509, 17468, -1, 28792, 28763, 28766, -1, 28792, 28766, 28769, -1, 28793, 28771, 28774, -1, 28791, 28780, 17509, -1, 28794, 17653, 28783, -1, 28794, 17656, 17653, -1, 28795, 28769, 28773, -1, 28795, 28773, 28777, -1, 28793, 28767, 28771, -1, 28796, 28774, 28776, -1, 28797, 28772, 28788, -1, 28798, 28779, 28782, -1, 28796, 28776, 28781, -1, 28798, 28777, 28779, -1, 28797, 28783, 28772, -1, 28799, 17514, 17508, -1, 28799, 17508, 17501, -1, 28799, 17501, 17593, -1, 28800, 17463, 17526, -1, 28799, 28781, 17514, -1, 28801, 28788, 28780, -1, 28802, 15175, 28784, -1, 28800, 28782, 17463, -1, 28801, 28780, 28791, -1, 28802, 15176, 15175, -1, 28803, 15172, 15171, -1, 28802, 28753, 28787, -1, 28803, 28785, 28750, -1, 28804, 17468, 17467, -1, 28802, 28784, 28753, -1, 28803, 28750, 28789, -1, 28803, 15171, 28785, -1, 28805, 28789, 28763, -1, 28804, 28791, 17468, -1, 28805, 28763, 28792, -1, 28806, 28759, 28790, -1, 28748, 17571, 17656, -1, 28806, 28787, 28759, -1, 28807, 28790, 28767, -1, 28807, 28767, 28793, -1, 28748, 17656, 28794, -1, 28754, 28792, 28769, -1, 28754, 28769, 28795, -1, 28808, 28793, 28774, -1, 28751, 28794, 28783, -1, 28751, 28783, 28797, -1, 28760, 28795, 28777, -1, 28760, 28777, 28798, -1, 28808, 28774, 28796, -1, 28764, 28788, 28801, -1, 28809, 28799, 17593, -1, 28809, 17593, 17601, -1, 28764, 28797, 28788, -1, 28809, 28796, 28781, -1, 28809, 28781, 28799, -1, 28768, 28798, 28782, -1, 28810, 15177, 15176, -1, 28770, 28801, 28791, -1, 28810, 28802, 28787, -1, 28768, 28782, 28800, -1, 28810, 28787, 28806, -1, 28770, 28791, 28804, -1, 28810, 15176, 28802, -1, 28775, 17526, 17523, -1, 28778, 17467, 17465, -1, 28811, 28790, 28807, -1, 28811, 28806, 28790, -1, 28775, 28800, 17526, -1, 28778, 28804, 17467, -1, 28812, 15172, 28803, -1, 28812, 15173, 15172, -1, 28812, 28789, 28805, -1, 28813, 17572, 17571, -1, 28812, 28803, 28789, -1, 28813, 15168, 17572, -1, 28813, 15169, 15168, -1, 28814, 28807, 28793, -1, 28813, 17571, 28748, -1, 28814, 28793, 28808, -1, 28758, 28805, 28792, -1, 28815, 17601, 17616, -1, 28758, 28792, 28754, -1, 28749, 28748, 28794, -1, 28815, 28808, 28796, -1, 28815, 28809, 17601, -1, 28749, 28794, 28751, -1, 28815, 28796, 28809, -1, 28755, 28754, 28795, -1, 28755, 28795, 28760, -1, 28816, 15177, 28810, -1, 28816, 15178, 15177, -1, 28816, 28810, 28806, -1, 28761, 28760, 28798, -1, 28762, 28797, 28764, -1, 28816, 28806, 28811, -1, 28762, 28751, 28797, -1, 28757, 28807, 28814, -1, 28761, 28798, 28768, -1, 28757, 28811, 28807, -1, 28766, 28801, 28770, -1, 28766, 28764, 28801, -1, 28817, 17616, 17627, -1, 28817, 28808, 28815, -1, 28817, 28815, 17616, -1, 28817, 28814, 28808, -1, 28771, 28768, 28800, -1, 28773, 28804, 28778, -1, 28771, 28800, 28775, -1, 28773, 28770, 28804, -1, 28779, 17465, 17464, -1, 28752, 15179, 15178, -1, 28776, 17523, 17519, -1, 28752, 15178, 28816, -1, 28752, 28816, 28811, -1, 28752, 28811, 28757, -1, 28776, 28775, 17523, -1, 28779, 28778, 17465, -1, 28756, 17627, 17643, -1, 28786, 15174, 15173, -1, 28747, 28813, 28748, -1, 28786, 15173, 28812, -1, 28756, 28817, 17627, -1, 28756, 28757, 28814, -1, 28786, 28812, 28805, -1, 28747, 15170, 15169, -1, 28786, 28805, 28758, -1, 28747, 15169, 28813, -1, 28756, 28814, 28817, -1, 28818, 28819, 28820, -1, 28818, 28820, 28821, -1, 28822, 17924, 17927, -1, 28822, 28821, 17924, -1, 28822, 17927, 23391, -1, 28823, 17662, 17661, -1, 28823, 17661, 28824, -1, 28823, 28824, 28819, -1, 28823, 28819, 28818, -1, 28825, 23391, 23392, -1, 28825, 28818, 28821, -1, 28825, 28822, 23391, -1, 28825, 28821, 28822, -1, 28826, 23393, 17664, -1, 28826, 23392, 23393, -1, 28826, 17664, 17663, -1, 28826, 17663, 17662, -1, 28826, 28818, 28825, -1, 28826, 17662, 28823, -1, 28826, 28823, 28818, -1, 28826, 28825, 23392, -1, 17658, 17657, 17953, -1, 23391, 17927, 17913, -1, 28827, 17947, 17930, -1, 28827, 17930, 17926, -1, 28828, 17948, 17947, -1, 28828, 17947, 28827, -1, 28829, 17926, 17925, -1, 28829, 28827, 17926, -1, 28830, 17953, 17948, -1, 28830, 17658, 17953, -1, 28830, 17948, 28828, -1, 28831, 28827, 28829, -1, 28831, 28828, 28827, -1, 28832, 17925, 17922, -1, 28832, 28829, 17925, -1, 28833, 17659, 17658, -1, 28833, 28828, 28831, -1, 28833, 17658, 28830, -1, 28833, 28830, 28828, -1, 28834, 28831, 28829, -1, 28834, 28829, 28832, -1, 28820, 17922, 17923, -1, 28820, 28832, 17922, -1, 28835, 17660, 17659, -1, 28835, 17659, 28833, -1, 28835, 28833, 28831, -1, 28835, 28831, 28834, -1, 28819, 28834, 28832, -1, 28819, 28832, 28820, -1, 28821, 17923, 17924, -1, 28821, 28820, 17923, -1, 28824, 17661, 17660, -1, 28824, 17660, 28835, -1, 28824, 28834, 28819, -1, 28824, 28835, 28834, -1, 28836, 28837, 28838, -1, 17502, 28839, 17503, -1, 17503, 28839, 17535, -1, 28838, 28839, 17502, -1, 25696, 28840, 25695, -1, 25695, 28840, 28841, -1, 28841, 28840, 28842, -1, 28842, 28840, 28837, -1, 17535, 28843, 17547, -1, 28837, 28843, 28838, -1, 28839, 28843, 17535, -1, 28838, 28843, 28839, -1, 17552, 28844, 25696, -1, 17547, 28844, 17553, -1, 17553, 28844, 17552, -1, 28837, 28844, 28843, -1, 25696, 28844, 28840, -1, 28843, 28844, 17547, -1, 28840, 28844, 28837, -1, 17972, 25691, 23436, -1, 23438, 28845, 17461, -1, 17462, 28845, 17525, -1, 17461, 28845, 17462, -1, 23437, 28846, 23438, -1, 23438, 28846, 28845, -1, 17525, 28847, 17520, -1, 28845, 28847, 17525, -1, 25692, 28848, 25691, -1, 23436, 28848, 23437, -1, 25691, 28848, 23436, -1, 23437, 28848, 28846, -1, 28846, 28849, 28845, -1, 28845, 28849, 28847, -1, 17520, 28850, 17517, -1, 28847, 28850, 17520, -1, 25693, 28851, 25692, -1, 25692, 28851, 28848, -1, 28848, 28851, 28846, -1, 28846, 28851, 28849, -1, 28847, 28852, 28850, -1, 28849, 28852, 28847, -1, 17517, 28836, 17510, -1, 28850, 28836, 17517, -1, 25694, 28853, 25693, -1, 28851, 28853, 28849, -1, 25693, 28853, 28851, -1, 28849, 28853, 28852, -1, 28852, 28842, 28850, -1, 28850, 28842, 28836, -1, 17510, 28838, 17502, -1, 28836, 28838, 17510, -1, 25695, 28841, 25694, -1, 28852, 28841, 28842, -1, 25694, 28841, 28853, -1, 28853, 28841, 28852, -1, 28842, 28837, 28836, -1, 25632, 27220, 25620, -1, 25620, 27220, 28854, -1, 28854, 27217, 28855, -1, 27220, 27217, 28854, -1, 27217, 27216, 28855, -1, 28855, 27218, 28856, -1, 27216, 27218, 28855, -1, 28856, 27219, 27229, -1, 27218, 27219, 28856, -1, 27219, 27215, 27229, -1, 27228, 28857, 28856, -1, 28858, 28859, 28860, -1, 28860, 28859, 28861, -1, 27247, 28859, 28858, -1, 28862, 28863, 28864, -1, 28865, 28866, 28867, -1, 28868, 28863, 28862, -1, 28861, 28866, 28869, -1, 28870, 28866, 28865, -1, 28869, 28866, 28870, -1, 25614, 28871, 25640, -1, 28872, 28873, 27251, -1, 28867, 28873, 28872, -1, 27251, 28873, 27249, -1, 28866, 28873, 28867, -1, 28864, 28871, 25614, -1, 27249, 28873, 28859, -1, 28859, 28873, 28861, -1, 27231, 28874, 27228, -1, 28861, 28873, 28866, -1, 28868, 28874, 28863, -1, 27228, 28874, 28857, -1, 28857, 28874, 28868, -1, 28863, 28875, 28864, -1, 28864, 28875, 28871, -1, 25640, 28876, 25638, -1, 28871, 28876, 25640, -1, 27233, 28877, 27231, -1, 28874, 28877, 28863, -1, 27231, 28877, 28874, -1, 27229, 27228, 28856, -1, 28863, 28877, 28875, -1, 28871, 28878, 28876, -1, 28875, 28878, 28871, -1, 25638, 28879, 25636, -1, 28876, 28879, 25638, -1, 27235, 28880, 27233, -1, 27233, 28880, 28877, -1, 28877, 28880, 28875, -1, 28875, 28880, 28878, -1, 28878, 28881, 28876, -1, 28876, 28881, 28879, -1, 25636, 28882, 25634, -1, 28879, 28882, 25636, -1, 27237, 28883, 27235, -1, 27235, 28883, 28880, -1, 28878, 28883, 28881, -1, 28880, 28883, 28878, -1, 28879, 28884, 28882, -1, 28881, 28884, 28879, -1, 25634, 28885, 25626, -1, 28882, 28885, 25634, -1, 28881, 28886, 28884, -1, 28883, 28886, 28881, -1, 27239, 28886, 27237, -1, 27237, 28886, 28883, -1, 28882, 28887, 28885, -1, 28884, 28887, 28882, -1, 25626, 28888, 25622, -1, 28885, 28888, 25626, -1, 28886, 28889, 28884, -1, 27239, 28889, 28886, -1, 27241, 28889, 27239, -1, 28884, 28889, 28887, -1, 28887, 28890, 28885, -1, 28885, 28890, 28888, -1, 25622, 28891, 25616, -1, 28888, 28891, 25622, -1, 27243, 28892, 27241, -1, 28887, 28892, 28890, -1, 28889, 28892, 28887, -1, 27241, 28892, 28889, -1, 28890, 28893, 28888, -1, 28888, 28893, 28891, -1, 25616, 28894, 25617, -1, 28891, 28894, 25616, -1, 25624, 28865, 25631, -1, 27245, 28895, 27243, -1, 27243, 28895, 28892, -1, 28892, 28895, 28890, -1, 28890, 28895, 28893, -1, 28893, 28860, 28891, -1, 28891, 28860, 28894, -1, 25617, 28869, 25619, -1, 28894, 28869, 25617, -1, 27251, 27225, 28872, -1, 27245, 28858, 28895, -1, 25620, 28862, 25613, -1, 27247, 28858, 27245, -1, 28895, 28858, 28893, -1, 28854, 28862, 25620, -1, 28893, 28858, 28860, -1, 28860, 28861, 28894, -1, 28855, 28868, 28854, -1, 28894, 28861, 28869, -1, 28854, 28868, 28862, -1, 25613, 28864, 25614, -1, 25619, 28870, 25624, -1, 28862, 28864, 25613, -1, 28869, 28870, 25619, -1, 25624, 28870, 28865, -1, 27249, 28859, 27247, -1, 28856, 28857, 28855, -1, 28855, 28857, 28868, -1, 25627, 25631, 27212, -1, 27211, 28865, 27210, -1, 27212, 28865, 27211, -1, 25631, 28865, 27212, -1, 27210, 28867, 27206, -1, 28865, 28867, 27210, -1, 27205, 28872, 27203, -1, 27206, 28872, 27205, -1, 28867, 28872, 27206, -1, 28872, 27225, 27203, -1, 27199, 27226, 28896, -1, 27197, 28896, 28897, -1, 27197, 28897, 28898, -1, 27197, 27199, 28896, -1, 27189, 28898, 27180, -1, 27189, 27197, 28898, -1, 28899, 28900, 27176, -1, 28901, 28902, 28903, -1, 28904, 27250, 27248, -1, 28904, 27248, 28905, -1, 28904, 28906, 28907, -1, 28904, 28905, 28906, -1, 28901, 28908, 28902, -1, 28909, 27185, 27184, -1, 28910, 28898, 28897, -1, 28909, 28903, 27185, -1, 27186, 28911, 27187, -1, 28910, 28899, 28898, -1, 28910, 28907, 28900, -1, 28910, 28900, 28899, -1, 28912, 27232, 27230, -1, 28913, 28897, 28896, -1, 28912, 28908, 28901, -1, 28913, 28896, 27252, -1, 28912, 27230, 28914, -1, 28913, 27252, 27250, -1, 28912, 28914, 28908, -1, 28913, 28904, 28907, -1, 28913, 28910, 28897, -1, 28913, 28907, 28910, -1, 28913, 27250, 28904, -1, 28915, 28903, 28909, -1, 28915, 28901, 28903, -1, 28916, 27184, 27183, -1, 28916, 28909, 27184, -1, 28917, 27234, 27232, -1, 28917, 27232, 28912, -1, 28917, 28901, 28915, -1, 28917, 28912, 28901, -1, 28918, 28909, 28916, -1, 28918, 28915, 28909, -1, 28919, 27183, 27182, -1, 28919, 28916, 27183, -1, 28920, 27236, 27234, -1, 28920, 28915, 28918, -1, 28920, 27234, 28917, -1, 28920, 28917, 28915, -1, 28921, 28916, 28919, -1, 28921, 28918, 28916, -1, 28922, 27182, 27181, -1, 28922, 28919, 27182, -1, 28923, 28918, 28921, -1, 28923, 27238, 27236, -1, 28923, 27236, 28920, -1, 28923, 28920, 28918, -1, 28924, 28919, 28922, -1, 28924, 28921, 28919, -1, 28925, 27181, 27179, -1, 28925, 28922, 27181, -1, 28926, 27238, 28923, -1, 28926, 27240, 27238, -1, 28926, 28921, 28924, -1, 28926, 28923, 28921, -1, 28927, 28922, 28925, -1, 28927, 28924, 28922, -1, 28928, 27179, 27177, -1, 28928, 28925, 27179, -1, 28929, 27242, 27240, -1, 28929, 27240, 28926, -1, 28929, 28926, 28924, -1, 28929, 28924, 28927, -1, 28930, 28927, 28925, -1, 28930, 28925, 28928, -1, 28931, 28928, 27177, -1, 28931, 27177, 27174, -1, 28932, 27244, 27242, -1, 28932, 27242, 28929, -1, 28932, 28927, 28930, -1, 28932, 28929, 28927, -1, 28933, 28930, 28928, -1, 28933, 28928, 28931, -1, 28898, 27178, 27180, -1, 28934, 27174, 27175, -1, 28934, 28931, 27174, -1, 28935, 27246, 27244, -1, 28935, 27244, 28932, -1, 28935, 28930, 28933, -1, 28935, 28932, 28930, -1, 28906, 28933, 28931, -1, 28906, 28931, 28934, -1, 27226, 27252, 28896, -1, 28900, 27175, 27176, -1, 28900, 28934, 27175, -1, 28902, 28911, 27186, -1, 28905, 27248, 27246, -1, 28908, 28911, 28902, -1, 28905, 28933, 28906, -1, 28905, 28935, 28933, -1, 28908, 28936, 28911, -1, 28905, 27246, 28935, -1, 28903, 27186, 27185, -1, 28907, 28906, 28934, -1, 28907, 28934, 28900, -1, 28903, 28902, 27186, -1, 28914, 27230, 27227, -1, 28899, 27176, 27178, -1, 28914, 27227, 28937, -1, 28914, 28937, 28936, -1, 28914, 28936, 28908, -1, 28899, 27178, 28898, -1, 28937, 27227, 27208, -1, 28936, 27208, 27191, -1, 28936, 28937, 27208, -1, 28911, 28936, 27191, -1, 27187, 28911, 27191, -1, 18053, 18052, 28938, -1, 28939, 28940, 28941, -1, 28939, 28938, 28940, -1, 28939, 18053, 28938, -1, 28942, 28941, 28943, -1, 28942, 28939, 28941, -1, 28944, 28943, 25025, -1, 28944, 28942, 28943, -1, 25030, 28944, 25025, -1, 16805, 16803, 25728, -1, 25728, 28945, 25727, -1, 16803, 28945, 25728, -1, 25727, 28946, 25726, -1, 28945, 28946, 25727, -1, 25726, 28947, 25725, -1, 28946, 28947, 25726, -1, 25725, 25225, 25230, -1, 28947, 25225, 25725, -1, 28948, 28949, 28950, -1, 16821, 28951, 16820, -1, 16824, 28951, 16821, -1, 28952, 28951, 28948, -1, 28948, 28951, 16824, -1, 16820, 28951, 28953, -1, 28953, 28951, 28952, -1, 28954, 28955, 18039, -1, 28956, 28955, 28954, -1, 28949, 28955, 28956, -1, 23530, 28957, 16824, -1, 23533, 28957, 23530, -1, 16824, 28957, 28949, -1, 28949, 28957, 28955, -1, 18039, 28958, 18043, -1, 28955, 28958, 18039, -1, 23535, 28959, 23533, -1, 18043, 28959, 23535, -1, 28958, 28959, 18043, -1, 23533, 28959, 28957, -1, 28957, 28959, 28955, -1, 28955, 28959, 28958, -1, 16803, 16816, 28945, -1, 23535, 23537, 18043, -1, 23537, 18041, 18043, -1, 28947, 28960, 25225, -1, 25225, 28960, 25224, -1, 28946, 28961, 28947, -1, 28947, 28961, 28960, -1, 25224, 28962, 25223, -1, 28960, 28962, 25224, -1, 25223, 28963, 18032, -1, 28962, 28963, 25223, -1, 28961, 28964, 28960, -1, 28960, 28964, 28962, -1, 16818, 28965, 16816, -1, 28945, 28965, 28946, -1, 28946, 28965, 28961, -1, 16816, 28965, 28945, -1, 28964, 28950, 28962, -1, 28962, 28950, 28963, -1, 18032, 28966, 18035, -1, 28963, 28966, 18032, -1, 28961, 28952, 28964, -1, 28965, 28952, 28961, -1, 16818, 28952, 28965, -1, 28966, 28956, 18035, -1, 28950, 28956, 28963, -1, 28963, 28956, 28966, -1, 28964, 28948, 28950, -1, 28952, 28948, 28964, -1, 16820, 28953, 16818, -1, 16818, 28953, 28952, -1, 18035, 28954, 18039, -1, 28956, 28954, 18035, -1, 16824, 28949, 28948, -1, 28950, 28949, 28956, -1, 25030, 25029, 28967, -1, 28967, 25733, 28968, -1, 25029, 25733, 28967, -1, 28968, 25734, 28969, -1, 25733, 25734, 28968, -1, 28969, 25735, 25204, -1, 25734, 25735, 28969, -1, 25735, 25208, 25204, -1, 25030, 28967, 28944, -1, 18049, 18044, 18046, -1, 18044, 18011, 18046, -1, 28944, 28970, 28942, -1, 28967, 28970, 28944, -1, 28942, 28971, 28939, -1, 28970, 28971, 28942, -1, 28968, 28972, 28967, -1, 28967, 28972, 28970, -1, 28939, 28973, 18053, -1, 18053, 28973, 18051, -1, 28971, 28973, 28939, -1, 28970, 28974, 28971, -1, 28972, 28974, 28970, -1, 25203, 28975, 25204, -1, 25204, 28975, 28969, -1, 28969, 28975, 28968, -1, 28968, 28975, 28972, -1, 25202, 28976, 25203, -1, 28972, 28976, 28974, -1, 28975, 28976, 28972, -1, 25203, 28976, 28975, -1, 28971, 28977, 28973, -1, 28974, 28977, 28971, -1, 28973, 28978, 18051, -1, 18019, 28979, 25202, -1, 18022, 28979, 18019, -1, 28974, 28979, 28977, -1, 28976, 28979, 28974, -1, 25202, 28979, 28976, -1, 18022, 28980, 28979, -1, 28977, 28980, 28973, -1, 28973, 28980, 28978, -1, 28979, 28980, 28977, -1, 18051, 28981, 18049, -1, 18044, 28981, 18022, -1, 28978, 28981, 18051, -1, 18022, 28981, 28980, -1, 18049, 28981, 18044, -1, 28980, 28981, 28978, -1, 25045, 25025, 25732, -1, 25732, 28982, 25731, -1, 25025, 28982, 25732, -1, 25731, 28983, 25730, -1, 28982, 28983, 25731, -1, 25730, 28984, 25729, -1, 28983, 28984, 25730, -1, 25729, 25214, 25213, -1, 28984, 25214, 25729, -1, 28985, 28986, 28987, -1, 28983, 28988, 28984, -1, 28984, 28988, 25214, -1, 25214, 28988, 25216, -1, 28986, 28988, 28983, -1, 25216, 28988, 28989, -1, 28989, 28988, 28990, -1, 28990, 28988, 28986, -1, 18047, 18004, 18048, -1, 18045, 18004, 18047, -1, 18005, 18004, 18045, -1, 28943, 28982, 25025, -1, 18048, 28991, 18050, -1, 18004, 28991, 18048, -1, 18002, 28992, 18004, -1, 18001, 28992, 18002, -1, 18004, 28992, 28991, -1, 18050, 28993, 18052, -1, 28991, 28993, 18050, -1, 28938, 28994, 28940, -1, 18052, 28994, 28938, -1, 28993, 28994, 18052, -1, 28991, 28995, 28993, -1, 18001, 28995, 28992, -1, 28992, 28995, 28991, -1, 28940, 28985, 28941, -1, 28994, 28985, 28940, -1, 28993, 28996, 28994, -1, 28995, 28996, 28993, -1, 17997, 28997, 18001, -1, 18001, 28997, 28995, -1, 28996, 28990, 28994, -1, 28994, 28990, 28985, -1, 28941, 28987, 28943, -1, 28985, 28987, 28941, -1, 28943, 28987, 28982, -1, 25215, 28998, 17997, -1, 28995, 28998, 28996, -1, 28997, 28998, 28995, -1, 17997, 28998, 28997, -1, 25216, 28989, 25215, -1, 25215, 28989, 28998, -1, 28996, 28989, 28990, -1, 28998, 28989, 28996, -1, 28982, 28986, 28983, -1, 28987, 28986, 28982, -1, 28990, 28986, 28985, -1, 25212, 25217, 28999, -1, 29000, 28999, 29001, -1, 29000, 25212, 28999, -1, 29002, 29001, 29003, -1, 29002, 29000, 29001, -1, 29004, 29003, 16753, -1, 29004, 29002, 29003, -1, 16728, 29004, 16753, -1, 24788, 24780, 29005, -1, 29006, 29005, 29007, -1, 29006, 24788, 29005, -1, 29008, 29007, 29009, -1, 29008, 29006, 29007, -1, 29010, 29009, 25226, -1, 29010, 29008, 29009, -1, 25221, 29010, 25226, -1, 24777, 24781, 29011, -1, 29012, 29011, 29013, -1, 29012, 24777, 29011, -1, 29014, 29013, 29015, -1, 29014, 29012, 29013, -1, 29016, 29015, 25201, -1, 29016, 29014, 29015, -1, 25205, 29016, 25201, -1, 25062, 29017, 25060, -1, 25060, 29017, 29018, -1, 29018, 29019, 29020, -1, 29017, 29019, 29018, -1, 29020, 29021, 29022, -1, 29019, 29021, 29020, -1, 29022, 29023, 25051, -1, 29021, 29023, 29022, -1, 29023, 25054, 25051, -1, 29022, 25067, 29020, -1, 29020, 25067, 29018, -1, 29018, 25067, 25060, -1, 25051, 27855, 29022, -1, 25065, 29024, 25066, -1, 25065, 29025, 29024, -1, 25067, 29026, 25065, -1, 25067, 29027, 29026, -1, 29026, 29027, 25065, -1, 29025, 29028, 25015, -1, 25015, 29028, 27855, -1, 29027, 29028, 25065, -1, 29022, 29028, 25067, -1, 27855, 29028, 29022, -1, 25067, 29028, 29027, -1, 25065, 29028, 29025, -1, 25016, 29029, 25015, -1, 25015, 29030, 29025, -1, 29029, 29030, 25015, -1, 29030, 29031, 29025, -1, 29031, 29032, 29025, -1, 29032, 29033, 29025, -1, 29025, 29034, 29024, -1, 29033, 29034, 29025, -1, 29034, 29035, 29024, -1, 29035, 29036, 29024, -1, 29036, 29037, 29024, -1, 29024, 29038, 25066, -1, 29037, 29038, 29024, -1, 29038, 25082, 25066, -1, 29035, 29034, 29039, -1, 29039, 29034, 29040, -1, 29040, 29034, 29041, -1, 29034, 29042, 29041, -1, 29034, 29043, 29042, -1, 29034, 29044, 29043, -1, 29034, 29045, 29044, -1, 29034, 29046, 29045, -1, 29033, 29047, 29034, -1, 29034, 29047, 29046, -1, 29033, 29048, 29047, -1, 29033, 29049, 29048, -1, 29033, 29050, 29049, -1, 29033, 29051, 29050, -1, 29033, 29052, 29051, -1, 29033, 29032, 29052, -1, 17154, 17197, 17419, -1, 17419, 17422, 17417, -1, 17197, 17422, 17419, -1, 24301, 16214, 17125, -1, 16212, 17127, 16214, -1, 16214, 17127, 17125, -1, 23646, 29053, 23652, -1, 23646, 23652, 23647, -1, 23650, 29054, 29053, -1, 23650, 29053, 23646, -1, 26743, 29054, 23650, -1, 19066, 26743, 23650, -1, 26966, 29055, 29056, -1, 26966, 29056, 26964, -1, 26746, 26748, 29055, -1, 26746, 26966, 26969, -1, 26746, 29055, 26966, -1, 26744, 26969, 26970, -1, 26744, 26746, 26969, -1, 29053, 26970, 23652, -1, 29054, 26744, 26970, -1, 29054, 26970, 29053, -1, 26743, 26744, 29054, -1, 29056, 29057, 29058, -1, 29056, 29058, 26971, -1, 29056, 26971, 26964, -1, 29055, 26750, 29057, -1, 29055, 29057, 29056, -1, 26748, 26750, 29055, -1, 29059, 26971, 29058, -1, 29059, 26973, 26971, -1, 29060, 29058, 29057, -1, 29060, 29059, 29058, -1, 26755, 29057, 26750, -1, 26755, 29060, 29057, -1, 29060, 26755, 26751, -1, 29061, 29060, 26751, -1, 29059, 29060, 29061, -1, 29062, 29059, 29061, -1, 26994, 26973, 29059, -1, 26994, 29059, 29062, -1, 26982, 26674, 29063, -1, 29062, 26993, 26994, -1, 29064, 29065, 26984, -1, 29064, 26984, 26986, -1, 29064, 26986, 26988, -1, 29066, 29067, 29065, -1, 29066, 29065, 29064, -1, 29068, 26979, 26982, -1, 29068, 29063, 29067, -1, 29068, 29067, 29066, -1, 29068, 26982, 29063, -1, 29069, 26988, 26989, -1, 29069, 29064, 26988, -1, 29070, 29066, 29064, -1, 29070, 29064, 29069, -1, 29071, 26977, 26979, -1, 29071, 29068, 29066, -1, 29071, 26979, 29068, -1, 29071, 29066, 29070, -1, 29072, 26989, 26991, -1, 29072, 29069, 26989, -1, 29073, 29072, 26991, -1, 29073, 29069, 29072, -1, 29073, 29070, 29069, -1, 29074, 26975, 26977, -1, 29074, 26977, 29071, -1, 29074, 29070, 29073, -1, 29074, 29071, 29070, -1, 29075, 26991, 26993, -1, 29075, 26993, 29062, -1, 29076, 29062, 29061, -1, 29076, 29073, 26991, -1, 29076, 26991, 29075, -1, 29076, 29075, 29062, -1, 29077, 29061, 26751, -1, 29077, 26751, 26975, -1, 29077, 26975, 29074, -1, 29077, 29074, 29073, -1, 29077, 29073, 29076, -1, 29077, 29076, 29061, -1, 29078, 29063, 26674, -1, 29078, 26674, 26665, -1, 29079, 29067, 29063, -1, 29079, 29063, 29078, -1, 29065, 29067, 29079, -1, 29080, 29065, 29079, -1, 26984, 29065, 29080, -1, 26741, 26984, 29080, -1, 26665, 26683, 29081, -1, 29078, 26665, 29081, -1, 29079, 29081, 29082, -1, 29079, 29078, 29081, -1, 29080, 29082, 29083, -1, 29080, 29079, 29082, -1, 26741, 29083, 26740, -1, 26741, 29080, 29083, -1, 26650, 29081, 26683, -1, 29084, 29082, 29081, -1, 29084, 29081, 26650, -1, 29085, 29082, 29084, -1, 29086, 29083, 29082, -1, 29086, 29082, 29085, -1, 26738, 26740, 29083, -1, 26738, 29083, 29086, -1, 26660, 26403, 29087, -1, 29086, 26737, 26738, -1, 29088, 29089, 26729, -1, 29088, 26729, 26731, -1, 29090, 29087, 29089, -1, 29090, 29089, 29088, -1, 29091, 26659, 26660, -1, 29091, 29087, 29090, -1, 29091, 26660, 29087, -1, 29092, 26731, 26733, -1, 29092, 29088, 26731, -1, 29093, 29088, 29092, -1, 29093, 29090, 29088, -1, 29094, 26733, 26735, -1, 29094, 29092, 26733, -1, 29095, 26657, 26659, -1, 29095, 26659, 29091, -1, 29095, 29091, 29090, -1, 29095, 29090, 29093, -1, 29096, 29093, 29092, -1, 29096, 29092, 29094, -1, 29097, 26735, 26737, -1, 29097, 26737, 29086, -1, 29097, 29094, 26735, -1, 29098, 26652, 26655, -1, 29098, 26655, 26657, -1, 29098, 26657, 29095, -1, 29098, 29095, 29093, -1, 29098, 29093, 29096, -1, 29099, 29086, 29085, -1, 29099, 29096, 29094, -1, 29099, 29097, 29086, -1, 29099, 29094, 29097, -1, 29100, 29084, 26650, -1, 29100, 29085, 29084, -1, 29100, 26650, 26652, -1, 29100, 26652, 29098, -1, 29100, 29098, 29096, -1, 29100, 29099, 29085, -1, 29100, 29096, 29099, -1, 29101, 29087, 26403, -1, 29101, 26403, 26410, -1, 29089, 29087, 29101, -1, 29102, 29089, 29101, -1, 26729, 29089, 29102, -1, 26649, 26729, 29102, -1, 26410, 26394, 29103, -1, 29101, 29103, 29104, -1, 29101, 26410, 29103, -1, 29102, 29104, 26648, -1, 29102, 29101, 29104, -1, 26649, 29102, 26648, -1, 29105, 26645, 26648, -1, 29104, 29105, 26648, -1, 29103, 29106, 29105, -1, 29103, 29105, 29104, -1, 26394, 26396, 29106, -1, 26394, 29106, 29103, -1, 26641, 29107, 26640, -1, 26400, 19814, 29108, -1, 26400, 29108, 29107, -1, 26400, 29107, 26641, -1, 26398, 26641, 26643, -1, 26398, 26400, 26641, -1, 29105, 26643, 26645, -1, 29106, 26398, 26643, -1, 29106, 26643, 29105, -1, 26396, 26398, 29106, -1, 23764, 29108, 19814, -1, 23764, 19814, 19793, -1, 29107, 29108, 23764, -1, 23763, 29107, 23764, -1, 26640, 29107, 23763, -1, 23703, 26640, 23763, -1, 16537, 25153, 29109, -1, 16537, 16535, 25153, -1, 16536, 29109, 29110, -1, 16536, 16537, 29109, -1, 16538, 29110, 29111, -1, 16538, 16536, 29110, -1, 24745, 29111, 29112, -1, 24745, 16538, 29111, -1, 24744, 29112, 24805, -1, 24744, 24745, 29112, -1, 24743, 24744, 24805, -1, 29113, 24805, 29112, -1, 25162, 29109, 25153, -1, 27560, 29114, 25166, -1, 27561, 29114, 27560, -1, 27224, 29114, 27561, -1, 29115, 29116, 29113, -1, 29115, 29111, 29110, -1, 29115, 29112, 29111, -1, 29115, 29113, 29112, -1, 29117, 29114, 29118, -1, 29117, 29118, 29116, -1, 29117, 29110, 29109, -1, 29117, 29116, 29115, -1, 29117, 29115, 29110, -1, 29119, 25162, 25164, -1, 29119, 25164, 25166, -1, 29119, 29117, 29109, -1, 29119, 29109, 25162, -1, 29119, 29114, 29117, -1, 29119, 25166, 29114, -1, 24997, 24804, 24805, -1, 24997, 24805, 29113, -1, 24996, 29113, 29116, -1, 24996, 24997, 29113, -1, 24995, 24996, 29116, -1, 29118, 24995, 29116, -1, 25005, 24995, 29118, -1, 25006, 29118, 29114, -1, 25006, 25005, 29118, -1, 25009, 29114, 27224, -1, 25009, 25006, 29114, -1, 27221, 25009, 27224, -1, 24772, 16731, 16712, -1, 24772, 16712, 29120, -1, 24771, 29120, 29121, -1, 24771, 24772, 29120, -1, 24769, 29121, 25016, -1, 24769, 24771, 29121, -1, 16713, 29120, 16712, -1, 29029, 25016, 29121, -1, 29122, 16714, 16715, -1, 29030, 29121, 29120, -1, 29030, 16713, 16714, -1, 29030, 29120, 16713, -1, 29030, 16714, 29122, -1, 29030, 29029, 29121, -1, 29123, 29030, 29122, -1, 29031, 29030, 29123, -1, 29032, 29031, 29123, -1, 25084, 29124, 29125, -1, 25084, 29125, 27397, -1, 29036, 29035, 29124, -1, 29036, 29124, 25084, -1, 29037, 29036, 25084, -1, 29038, 29037, 25084, -1, 25082, 29038, 25084, -1, 29124, 29035, 29039, -1, 29124, 29039, 29040, -1, 29124, 29040, 29041, -1, 29124, 29041, 29042, -1, 29124, 29042, 29043, -1, 29044, 29124, 29043, -1, 29045, 29124, 29044, -1, 29046, 29124, 29045, -1, 29125, 29046, 29047, -1, 29125, 29124, 29046, -1, 29123, 29047, 29048, -1, 29123, 29048, 29049, -1, 29123, 29049, 29050, -1, 29123, 29050, 29051, -1, 29123, 29051, 29052, -1, 29123, 29052, 29032, -1, 29123, 29125, 29047, -1, 29122, 27397, 29125, -1, 29122, 29125, 29123, -1, 16770, 16772, 27397, -1, 16770, 27397, 29122, -1, 16715, 16770, 29122, -1, 24778, 24773, 14996, -1, 24778, 14996, 14993, -1, 24779, 24778, 14993, -1, 24780, 14993, 14995, -1, 24780, 24779, 14993, -1, 29005, 24780, 14995, -1, 29007, 29005, 14995, -1, 29009, 29007, 14995, -1, 25226, 29009, 14995, -1, 25228, 14995, 14994, -1, 25228, 25226, 14995, -1, 25229, 25228, 14994, -1, 25227, 14994, 14997, -1, 25227, 25229, 14994, -1, 15001, 24774, 24775, -1, 14999, 24775, 24776, -1, 14999, 24776, 24777, -1, 14999, 15001, 24775, -1, 15000, 24777, 29012, -1, 15000, 29012, 29014, -1, 15000, 29014, 29016, -1, 15000, 29016, 25205, -1, 15000, 14999, 24777, -1, 14998, 25205, 25207, -1, 14998, 25207, 25206, -1, 14998, 15000, 25205, -1, 15002, 14998, 25206, -1, 16716, 16718, 15006, -1, 16716, 15006, 15007, -1, 16717, 16716, 15007, -1, 16728, 15007, 15003, -1, 16728, 16717, 15007, -1, 29004, 16728, 15003, -1, 29002, 29004, 15003, -1, 29000, 29002, 15003, -1, 25212, 29000, 15003, -1, 25211, 15003, 15005, -1, 25211, 25212, 15003, -1, 25209, 25211, 15005, -1, 25210, 15005, 15004, -1, 25210, 25209, 15005, -1, 25150, 25137, 16531, -1, 25149, 16531, 16532, -1, 25149, 25150, 16531, -1, 25151, 25149, 16532, -1, 27495, 25151, 16532, -1, 27497, 16532, 16528, -1, 27497, 27495, 16532, -1, 27500, 27497, 16528, -1, 25089, 16528, 16530, -1, 25089, 27500, 16528, -1, 25088, 25089, 16530, -1, 25087, 16530, 16529, -1, 25087, 25088, 16530, -1, 25085, 25087, 16529, -1, 25095, 3093, 3094, -1, 25095, 25086, 3093, -1, 25096, 25095, 3094, -1, 27557, 3094, 3092, -1, 27557, 25096, 3094, -1, 27556, 27557, 3092, -1, 25058, 27556, 3092, -1, 25059, 3092, 3091, -1, 25059, 25058, 3092, -1, 25057, 25059, 3091, -1, 25056, 3089, 25063, -1, 25061, 3088, 25062, -1, 25063, 3088, 25061, -1, 3089, 3088, 25063, -1, 29019, 3086, 29021, -1, 29017, 3086, 29019, -1, 25062, 3086, 29017, -1, 3088, 3086, 25062, -1, 29021, 3085, 29023, -1, 3086, 3085, 29021, -1, 29023, 3087, 25054, -1, 25053, 3087, 25052, -1, 25054, 3087, 25053, -1, 3085, 3087, 29023, -1, 25052, 3083, 25050, -1, 3087, 3083, 25052, -1, 25018, 3262, 25048, -1, 25048, 3261, 25021, -1, 3262, 3261, 25048, -1, 25021, 3259, 25019, -1, 3261, 3259, 25021, -1, 25019, 3258, 25022, -1, 3259, 3258, 25019, -1, 3258, 3260, 25022, -1, 16802, 16806, 3256, -1, 3256, 16806, 3255, -1, 3255, 16807, 3253, -1, 16806, 16807, 3255, -1, 3253, 16808, 3254, -1, 16807, 16808, 3253, -1, 3254, 16804, 3257, -1, 16808, 16804, 3254, -1, 25017, 25047, 3266, -1, 3266, 25047, 3265, -1, 3265, 25046, 3263, -1, 25047, 25046, 3265, -1, 3263, 25042, 3264, -1, 25046, 25042, 3263, -1, 3264, 25041, 3267, -1, 25042, 25041, 3264, -1, 25010, 15011, 15008, -1, 25012, 15008, 15010, -1, 25012, 25010, 15008, -1, 25011, 15010, 15009, -1, 25011, 25012, 15010, -1, 24770, 25011, 15009, -1, 25055, 3080, 3081, -1, 25055, 25049, 3080, -1, 27856, 25055, 3081, -1, 27854, 3081, 3082, -1, 27854, 27856, 3081, -1, 25014, 3082, 3077, -1, 25014, 27854, 3082, -1, 25013, 25014, 3077, -1, 25360, 25355, 25354, -1, 29126, 25360, 25354, -1, 29127, 25354, 25353, -1, 29127, 29126, 25354, -1, 29128, 29127, 25353, -1, 29129, 29130, 29128, -1, 29131, 29128, 25353, -1, 29131, 29129, 29128, -1, 29132, 25353, 25352, -1, 29132, 29131, 25353, -1, 29133, 25352, 25351, -1, 29133, 29132, 25352, -1, 25358, 25351, 25350, -1, 25358, 29133, 25351, -1, 29134, 29135, 29136, -1, 29137, 29135, 29134, -1, 25349, 25343, 25359, -1, 25349, 29138, 29139, -1, 25349, 25359, 29138, -1, 25348, 29139, 29135, -1, 25348, 25349, 29139, -1, 25347, 29137, 29140, -1, 25347, 29135, 29137, -1, 25347, 25348, 29135, -1, 25346, 29140, 29141, -1, 25346, 25347, 29140, -1, 25344, 29141, 25357, -1, 25344, 25346, 29141, -1, 25361, 25339, 25338, -1, 29142, 25361, 25338, -1, 29143, 29142, 25338, -1, 29144, 29143, 25338, -1, 29145, 25338, 25337, -1, 29145, 29144, 25338, -1, 29146, 29145, 25337, -1, 29147, 25337, 25336, -1, 29147, 29146, 25337, -1, 25342, 29147, 25336, -1, 24767, 29148, 24765, -1, 25328, 29148, 25327, -1, 24765, 29148, 25328, -1, 25327, 29149, 25326, -1, 29148, 29149, 25327, -1, 25326, 29150, 25325, -1, 29149, 29150, 25326, -1, 25325, 29151, 25324, -1, 29150, 29151, 25325, -1, 25324, 25341, 25323, -1, 29151, 25341, 25324, -1, 18042, 18003, 25335, -1, 25334, 18128, 25333, -1, 25335, 18128, 25334, -1, 18003, 18128, 25335, -1, 25333, 18127, 25332, -1, 18128, 18127, 25333, -1, 25332, 18126, 25331, -1, 18127, 18126, 25332, -1, 25331, 18124, 25330, -1, 18126, 18124, 25331, -1, 25330, 18123, 25329, -1, 18124, 18123, 25330, -1, 18123, 18125, 25329, -1, 25329, 18118, 24768, -1, 18125, 18118, 25329, -1, 24766, 18086, 29152, -1, 29152, 18085, 29153, -1, 18086, 18085, 29152, -1, 18085, 18087, 29153, -1, 29153, 18080, 25322, -1, 18087, 18080, 29153, -1, 25321, 18082, 29154, -1, 18076, 18082, 25321, -1, 29154, 18083, 29155, -1, 18082, 18083, 29154, -1, 29155, 18089, 29156, -1, 18083, 18089, 29155, -1, 29156, 18090, 18513, -1, 18089, 18090, 29156, -1, 23908, 29157, 23907, -1, 23907, 29157, 29158, -1, 29158, 29159, 29160, -1, 29157, 29159, 29158, -1, 29160, 29161, 29162, -1, 29159, 29161, 29160, -1, 29162, 29163, 29164, -1, 29161, 29163, 29162, -1, 29164, 29163, 29165, -1, 29164, 29165, 29166, -1, 29167, 29168, 29169, -1, 29170, 29168, 29167, -1, 29169, 29171, 29172, -1, 29168, 29171, 29169, -1, 29172, 29173, 29165, -1, 29171, 29173, 29172, -1, 29173, 29166, 29165, -1, 29167, 29174, 29170, -1, 29174, 29175, 29170, -1, 23856, 29176, 29177, -1, 23873, 29176, 23856, -1, 29177, 29178, 29179, -1, 29176, 29178, 29177, -1, 29179, 29180, 29181, -1, 29178, 29180, 29179, -1, 29181, 29182, 29183, -1, 29180, 29182, 29181, -1, 29183, 29184, 29185, -1, 29182, 29184, 29183, -1, 29185, 29186, 29187, -1, 29184, 29186, 29185, -1, 29187, 29175, 29174, -1, 29186, 29175, 29187, -1, 25413, 25386, 29188, -1, 29188, 25388, 29189, -1, 25386, 25388, 29188, -1, 29189, 25392, 29190, -1, 25388, 25392, 29189, -1, 29190, 25396, 29191, -1, 25392, 25396, 29190, -1, 29191, 25397, 29192, -1, 25396, 25397, 29191, -1, 29192, 25393, 29193, -1, 25397, 25393, 29192, -1, 29193, 25390, 29194, -1, 25393, 25390, 29193, -1, 29194, 25385, 29195, -1, 25390, 25385, 29194, -1, 29195, 25382, 29196, -1, 25385, 25382, 29195, -1, 29196, 25375, 29197, -1, 25382, 25375, 29196, -1, 29197, 25374, 29198, -1, 25375, 25374, 29197, -1, 29198, 25398, 29199, -1, 25374, 25398, 29198, -1, 29199, 25394, 25400, -1, 25398, 25394, 29199, -1, 25394, 25389, 25400, -1, 24728, 29200, 29201, -1, 24728, 25404, 29200, -1, 24728, 25403, 25404, -1, 29191, 24717, 29190, -1, 25402, 25403, 24728, -1, 24659, 24658, 24742, -1, 24660, 24659, 24742, -1, 24718, 24717, 29191, -1, 24718, 29191, 29192, -1, 24727, 25402, 24728, -1, 24727, 25401, 25402, -1, 24715, 29202, 29203, -1, 24715, 29204, 29202, -1, 24719, 29192, 29193, -1, 24719, 24718, 29192, -1, 25410, 24741, 24740, -1, 24726, 25401, 24727, -1, 24726, 25400, 25401, -1, 25409, 24740, 24739, -1, 24720, 29193, 29194, -1, 25409, 25410, 24740, -1, 24720, 24719, 29193, -1, 25411, 24742, 24741, -1, 25411, 24741, 25410, -1, 24725, 25400, 24726, -1, 25408, 24739, 24738, -1, 24721, 29194, 29195, -1, 24721, 24720, 29194, -1, 25408, 25409, 24739, -1, 29205, 24736, 29206, -1, 24724, 29199, 25400, -1, 24724, 25400, 24725, -1, 25412, 24660, 24742, -1, 25412, 24742, 25411, -1, 25407, 24738, 24737, -1, 24723, 29198, 29199, -1, 25407, 25408, 24738, -1, 24723, 29199, 24724, -1, 25413, 29203, 24662, -1, 25413, 24662, 24660, -1, 29207, 29208, 24721, -1, 29207, 29195, 29196, -1, 29207, 24721, 29195, -1, 25413, 24660, 25412, -1, 24722, 29196, 29197, -1, 24722, 29197, 29198, -1, 24722, 29198, 24723, -1, 25406, 24737, 24736, -1, 25406, 25407, 24737, -1, 29209, 29207, 29196, -1, 29209, 29196, 24722, -1, 29188, 29203, 25413, -1, 29188, 24715, 29203, -1, 29210, 29209, 24722, -1, 25405, 24736, 29205, -1, 25405, 25406, 24736, -1, 29189, 24716, 24715, -1, 29189, 24715, 29188, -1, 25404, 25405, 29205, -1, 25404, 29205, 29200, -1, 29190, 24716, 29189, -1, 24717, 24716, 29190, -1, 24658, 24735, 24742, -1, 24653, 24735, 24663, -1, 24663, 24735, 24657, -1, 24657, 24735, 24658, -1, 24715, 24701, 29204, -1, 29204, 24701, 29211, -1, 29211, 24701, 29212, -1, 24701, 24703, 29212, -1, 29201, 24708, 24728, -1, 24640, 24708, 29213, -1, 29213, 24708, 29214, -1, 29214, 24708, 29201, -1, 24736, 24729, 29206, -1, 24729, 29215, 29206, -1, 24729, 29216, 29215, -1, 24729, 24644, 29216, -1, 29208, 24698, 24721, -1, 24675, 24698, 29217, -1, 29217, 24698, 29218, -1, 29218, 24698, 29208, -1, 24722, 24714, 29210, -1, 24714, 29219, 29210, -1, 24714, 29220, 29219, -1, 24714, 24679, 29220, -1, 29218, 29208, 29207, -1, 29219, 29209, 29210, -1, 29221, 24675, 29217, -1, 29221, 29220, 24679, -1, 29221, 24679, 24678, -1, 29221, 24678, 24676, -1, 29221, 24676, 24675, -1, 29222, 29207, 29209, -1, 29222, 29218, 29207, -1, 29223, 29217, 29218, -1, 29223, 29219, 29220, -1, 29223, 29222, 29209, -1, 29223, 29218, 29222, -1, 29223, 29221, 29217, -1, 29223, 29220, 29221, -1, 29223, 29209, 29219, -1, 29211, 29203, 29202, -1, 29211, 29202, 29204, -1, 29224, 24662, 29203, -1, 29224, 29211, 29212, -1, 29224, 29203, 29211, -1, 29225, 24655, 24662, -1, 29225, 29212, 24703, -1, 29225, 24703, 25523, -1, 29225, 25523, 25522, -1, 29225, 25522, 24655, -1, 29225, 24662, 29224, -1, 29225, 29224, 29212, -1, 29214, 29201, 29200, -1, 29215, 29205, 29206, -1, 29226, 24640, 29213, -1, 29226, 29216, 24644, -1, 29226, 24644, 24643, -1, 29226, 24643, 24642, -1, 29226, 24642, 24640, -1, 29227, 29200, 29205, -1, 29227, 29214, 29200, -1, 29228, 29213, 29214, -1, 29228, 29215, 29216, -1, 29228, 29227, 29205, -1, 29228, 29214, 29227, -1, 29228, 29226, 29213, -1, 29228, 29216, 29226, -1, 29228, 29205, 29215, -1, 29229, 29230, 29231, -1, 29229, 29231, 29232, -1, 29233, 29185, 29187, -1, 29234, 23869, 23867, -1, 29234, 18132, 23869, -1, 29234, 23867, 29235, -1, 29236, 29237, 29230, -1, 29238, 29239, 29179, -1, 29236, 29230, 29229, -1, 29238, 29177, 29239, -1, 29238, 29240, 29177, -1, 29241, 18130, 18131, -1, 29242, 29233, 29187, -1, 29241, 18131, 18132, -1, 29242, 29243, 29185, -1, 29241, 18132, 29234, -1, 29242, 29185, 29233, -1, 29244, 29245, 29240, -1, 29242, 29187, 29246, -1, 29247, 18121, 29248, -1, 29247, 29237, 29236, -1, 29244, 29240, 29238, -1, 29247, 29248, 29237, -1, 29249, 29246, 29250, -1, 29251, 29252, 29245, -1, 29251, 29245, 29244, -1, 29249, 29253, 29243, -1, 29249, 29242, 29246, -1, 29254, 29235, 29252, -1, 29249, 29243, 29242, -1, 29255, 29250, 29256, -1, 29254, 29252, 29251, -1, 29255, 29232, 29253, -1, 29257, 29235, 29254, -1, 29255, 29253, 29249, -1, 29257, 29234, 29235, -1, 29255, 29249, 29250, -1, 29258, 29179, 29181, -1, 29259, 29256, 29260, -1, 18132, 23871, 23869, -1, 29259, 29232, 29255, -1, 18132, 18133, 23871, -1, 29259, 29229, 29232, -1, 29259, 29255, 29256, -1, 29261, 29238, 29179, -1, 29262, 29236, 29229, -1, 29261, 29258, 29181, -1, 29261, 29179, 29258, -1, 29262, 29259, 29260, -1, 29262, 29229, 29259, -1, 29263, 29260, 29264, -1, 29265, 18130, 29241, -1, 29263, 29264, 18119, -1, 29265, 29241, 29234, -1, 29263, 18119, 18120, -1, 29263, 18120, 18121, -1, 29265, 29234, 29257, -1, 29263, 18121, 29247, -1, 29263, 29247, 29236, -1, 29263, 29236, 29262, -1, 29266, 29244, 29238, -1, 29263, 29262, 29260, -1, 29266, 29238, 29261, -1, 29267, 29251, 29244, -1, 29267, 29244, 29266, -1, 29268, 29251, 29267, -1, 29268, 29254, 29251, -1, 29269, 29254, 29268, -1, 29269, 29257, 29254, -1, 29270, 29181, 29183, -1, 29271, 29261, 29181, -1, 29272, 29187, 29174, -1, 29271, 29270, 29183, -1, 29271, 29181, 29270, -1, 29273, 29265, 29257, -1, 29246, 29187, 29272, -1, 29273, 18129, 18130, -1, 29273, 18130, 29265, -1, 29273, 29257, 29269, -1, 29274, 29271, 29183, -1, 29274, 29266, 29261, -1, 29274, 29261, 29271, -1, 29231, 29267, 29266, -1, 29231, 29266, 29274, -1, 29230, 29268, 29267, -1, 29230, 29267, 29231, -1, 29237, 29269, 29268, -1, 29237, 29268, 29230, -1, 29275, 23857, 23856, -1, 29276, 29183, 29185, -1, 29275, 23856, 29177, -1, 29240, 23858, 23857, -1, 29243, 29276, 29185, -1, 29240, 23857, 29275, -1, 29240, 29275, 29177, -1, 29243, 29183, 29276, -1, 29248, 18129, 29273, -1, 29245, 23860, 23858, -1, 29248, 18121, 18122, -1, 29248, 18122, 18129, -1, 29248, 29269, 29237, -1, 29248, 29273, 29269, -1, 29245, 23858, 29240, -1, 29253, 29274, 29183, -1, 29252, 23863, 23860, -1, 29252, 23865, 23863, -1, 29253, 29183, 29243, -1, 29252, 23860, 29245, -1, 29235, 23867, 23865, -1, 29232, 29231, 29274, -1, 29235, 23865, 29252, -1, 29232, 29274, 29253, -1, 29239, 29177, 29179, -1, 18117, 18119, 29264, -1, 29277, 29264, 29260, -1, 29277, 18117, 29264, -1, 29278, 29260, 29256, -1, 29278, 29277, 29260, -1, 29279, 29256, 29250, -1, 29279, 29278, 29256, -1, 29280, 29250, 29246, -1, 29280, 29279, 29250, -1, 29281, 29246, 29272, -1, 29281, 29280, 29246, -1, 29282, 29272, 29174, -1, 29282, 29281, 29272, -1, 29167, 29282, 29174, -1, 29169, 29282, 29167, -1, 18116, 29278, 29279, -1, 18116, 29277, 29278, -1, 18116, 18117, 29277, -1, 29283, 18114, 29284, -1, 18106, 18114, 29283, -1, 29285, 29169, 29172, -1, 29285, 29282, 29169, -1, 29286, 29281, 29282, -1, 29286, 29282, 29285, -1, 29287, 29280, 29281, -1, 29287, 29281, 29286, -1, 29288, 29279, 29280, -1, 29288, 18116, 29279, -1, 29288, 29280, 29287, -1, 29289, 18116, 29288, -1, 29289, 29288, 18115, -1, 29290, 18115, 18116, -1, 29290, 18116, 29289, -1, 29290, 29289, 18115, -1, 29291, 29172, 29165, -1, 29291, 29165, 29292, -1, 29291, 29285, 29172, -1, 29293, 29292, 29294, -1, 29293, 29285, 29291, -1, 29293, 29291, 29292, -1, 29293, 29286, 29285, -1, 29295, 29294, 29296, -1, 29295, 29287, 29286, -1, 29295, 29293, 29294, -1, 29295, 29286, 29293, -1, 29297, 29296, 29284, -1, 29297, 29287, 29295, -1, 29297, 29288, 29287, -1, 29297, 18115, 29288, -1, 29297, 29295, 29296, -1, 29298, 29297, 29284, -1, 29298, 18115, 29297, -1, 29298, 29284, 18114, -1, 29299, 18114, 18115, -1, 29299, 29298, 18114, -1, 29299, 18115, 29298, -1, 29292, 29165, 29163, -1, 29292, 29163, 29300, -1, 29294, 29300, 29301, -1, 29294, 29292, 29300, -1, 29296, 29301, 29302, -1, 29296, 29294, 29301, -1, 29284, 29302, 29303, -1, 29284, 29296, 29302, -1, 29283, 29303, 29304, -1, 29283, 29284, 29303, -1, 18106, 29304, 18095, -1, 18106, 29283, 29304, -1, 29161, 29300, 29163, -1, 18099, 29304, 29303, -1, 18099, 18095, 29304, -1, 23999, 29157, 23908, -1, 24000, 29157, 23999, -1, 24001, 29157, 24000, -1, 29305, 29301, 29300, -1, 29305, 29300, 29161, -1, 29306, 29302, 29301, -1, 29306, 29301, 29305, -1, 29307, 29302, 29306, -1, 29308, 29303, 29302, -1, 29308, 29307, 18102, -1, 29308, 18099, 29303, -1, 29308, 29302, 29307, -1, 29309, 18102, 18099, -1, 29309, 29308, 18102, -1, 29309, 18099, 29308, -1, 29310, 29161, 29159, -1, 29310, 29159, 29157, -1, 29310, 29305, 29161, -1, 29311, 29310, 29157, -1, 29311, 29305, 29310, -1, 29311, 29306, 29305, -1, 29312, 18102, 29307, -1, 29312, 29311, 29157, -1, 29312, 29307, 29306, -1, 29312, 29306, 29311, -1, 29313, 24001, 24002, -1, 29313, 18102, 29312, -1, 29313, 29312, 29157, -1, 29313, 29157, 24001, -1, 29314, 24002, 18104, -1, 29314, 18104, 18102, -1, 29314, 29313, 24002, -1, 29314, 18102, 29313, -1, 29315, 29316, 29317, -1, 29315, 29318, 18359, -1, 29315, 29319, 29320, -1, 29315, 29320, 29316, -1, 18081, 18257, 18088, -1, 18361, 18359, 29318, -1, 29321, 18081, 18075, -1, 29321, 18257, 18081, -1, 29322, 18267, 18257, -1, 29322, 18257, 29321, -1, 29323, 18276, 18267, -1, 29323, 18267, 29322, -1, 29324, 18075, 18077, -1, 29324, 18077, 29325, -1, 29324, 29321, 18075, -1, 29326, 18284, 18276, -1, 29326, 18276, 29323, -1, 29327, 29325, 29328, -1, 29327, 29322, 29321, -1, 29327, 29321, 29324, -1, 29327, 29324, 29325, -1, 29320, 18286, 18284, -1, 29320, 18284, 29326, -1, 29329, 29328, 29330, -1, 29329, 29322, 29327, -1, 29329, 29323, 29322, -1, 29329, 29327, 29328, -1, 29319, 18290, 18286, -1, 29319, 18292, 18290, -1, 29319, 18356, 18292, -1, 29319, 18286, 29320, -1, 29331, 29330, 29332, -1, 29331, 29326, 29323, -1, 29331, 29329, 29330, -1, 29331, 29323, 29329, -1, 29316, 29332, 29317, -1, 29316, 29320, 29326, -1, 29316, 29331, 29332, -1, 29316, 29326, 29331, -1, 29315, 29317, 29318, -1, 29315, 18359, 18356, -1, 29315, 18356, 29319, -1, 29333, 18364, 18363, -1, 29333, 18363, 18361, -1, 29333, 29318, 29317, -1, 29333, 18361, 29318, -1, 29334, 29332, 29330, -1, 29334, 29317, 29332, -1, 29334, 18364, 29333, -1, 29334, 29333, 29317, -1, 29335, 29325, 18077, -1, 29335, 29328, 29325, -1, 29335, 29330, 29328, -1, 29335, 18077, 18079, -1, 29335, 18364, 29334, -1, 29335, 29334, 29330, -1, 29336, 18321, 18326, -1, 29336, 18308, 18321, -1, 29336, 18309, 18308, -1, 29336, 18297, 18309, -1, 29336, 18355, 18297, -1, 29336, 18354, 18355, -1, 29336, 18079, 18354, -1, 29336, 18326, 18364, -1, 29336, 18364, 29335, -1, 29336, 29335, 18079, -1, 29337, 25345, 18021, -1, 29337, 25359, 25345, -1, 29338, 18021, 18020, -1, 29338, 29337, 18021, -1, 29339, 18020, 18018, -1, 29339, 29338, 18020, -1, 25199, 18018, 18017, -1, 25199, 29339, 18018, -1, 25200, 25201, 29340, -1, 25200, 29340, 29341, -1, 25200, 29341, 29342, -1, 29343, 29342, 29344, -1, 29343, 29344, 29135, -1, 29343, 29135, 29139, -1, 29345, 25200, 29342, -1, 29345, 29342, 29343, -1, 29346, 25200, 29345, -1, 29347, 25198, 25200, -1, 29347, 29346, 25198, -1, 29347, 25200, 29346, -1, 29348, 25359, 29337, -1, 29348, 29139, 29138, -1, 29348, 29138, 25359, -1, 29348, 29343, 29139, -1, 29349, 29337, 29338, -1, 29349, 29345, 29343, -1, 29349, 29343, 29348, -1, 29349, 29348, 29337, -1, 29350, 29338, 29339, -1, 29350, 25198, 29346, -1, 29350, 29346, 29345, -1, 29350, 29349, 29338, -1, 29350, 29345, 29349, -1, 29351, 29339, 25199, -1, 29351, 25199, 25198, -1, 29351, 25198, 29350, -1, 29351, 29350, 29339, -1, 29015, 29340, 25201, -1, 29352, 29011, 24781, -1, 29136, 29135, 29344, -1, 29353, 29015, 29013, -1, 29353, 29340, 29015, -1, 29354, 29341, 29340, -1, 29354, 29340, 29353, -1, 29355, 29013, 29011, -1, 29355, 29353, 29013, -1, 29355, 29011, 29352, -1, 29356, 29342, 29341, -1, 29356, 29341, 29354, -1, 29357, 29352, 29358, -1, 29357, 29354, 29353, -1, 29357, 29355, 29352, -1, 29357, 29353, 29355, -1, 29359, 29342, 29356, -1, 29360, 29358, 29361, -1, 29360, 29361, 29362, -1, 29360, 29356, 29354, -1, 29360, 29354, 29357, -1, 29360, 29357, 29358, -1, 29363, 29344, 29342, -1, 29363, 29136, 29344, -1, 29363, 29342, 29359, -1, 29364, 29362, 29365, -1, 29364, 29359, 29356, -1, 29364, 29356, 29360, -1, 29364, 29360, 29362, -1, 29366, 29365, 29367, -1, 29366, 29364, 29365, -1, 29366, 29363, 29359, -1, 29366, 29359, 29364, -1, 29368, 29367, 29137, -1, 29368, 29137, 29134, -1, 29368, 29134, 29136, -1, 29368, 29136, 29363, -1, 29368, 29366, 29367, -1, 29368, 29363, 29366, -1, 29369, 29370, 29371, -1, 29369, 29141, 29140, -1, 29369, 29371, 29141, -1, 29369, 29372, 29370, -1, 29369, 29140, 29373, -1, 29369, 29373, 29374, -1, 29369, 29374, 29372, -1, 29375, 24782, 24784, -1, 25357, 29141, 29371, -1, 29376, 29352, 24781, -1, 29376, 24781, 24783, -1, 29377, 29358, 29352, -1, 29377, 29352, 29376, -1, 29378, 24783, 24782, -1, 29378, 24782, 29375, -1, 29378, 29376, 24783, -1, 29379, 29361, 29358, -1, 29379, 29358, 29377, -1, 29380, 29375, 29381, -1, 29380, 29377, 29376, -1, 29380, 29378, 29375, -1, 29380, 29376, 29378, -1, 29382, 29362, 29361, -1, 29382, 29361, 29379, -1, 29383, 29381, 29384, -1, 29383, 29377, 29380, -1, 29383, 29379, 29377, -1, 29383, 29380, 29381, -1, 29374, 29365, 29362, -1, 29374, 29362, 29382, -1, 29385, 29384, 29386, -1, 29385, 29379, 29383, -1, 29385, 29383, 29384, -1, 29385, 29382, 29379, -1, 29373, 29367, 29365, -1, 29373, 29137, 29367, -1, 29373, 29140, 29137, -1, 29373, 29365, 29374, -1, 29372, 29386, 29370, -1, 29372, 29382, 29385, -1, 29372, 29374, 29382, -1, 29372, 29385, 29386, -1, 29375, 24784, 24785, -1, 29375, 24785, 29387, -1, 29381, 29387, 29388, -1, 29381, 29375, 29387, -1, 29384, 29388, 29389, -1, 29384, 29381, 29388, -1, 29386, 29389, 29390, -1, 29386, 29390, 29391, -1, 29386, 29384, 29389, -1, 29370, 29391, 29392, -1, 29370, 29386, 29391, -1, 29371, 29392, 25358, -1, 29371, 29370, 29392, -1, 25357, 29371, 25358, -1, 29393, 29394, 29395, -1, 29393, 29395, 29131, -1, 29393, 29131, 29132, -1, 29393, 29132, 29133, -1, 29393, 29396, 29394, -1, 29393, 29133, 29397, -1, 29393, 29397, 29398, -1, 29393, 29398, 29396, -1, 29133, 25358, 29392, -1, 29399, 29387, 24785, -1, 29399, 24785, 24787, -1, 29400, 29388, 29387, -1, 29400, 29387, 29399, -1, 29401, 24787, 24786, -1, 29401, 24786, 24788, -1, 29401, 24788, 29402, -1, 29401, 29399, 24787, -1, 29403, 29389, 29388, -1, 29403, 29388, 29400, -1, 29404, 29402, 29405, -1, 29404, 29400, 29399, -1, 29404, 29399, 29401, -1, 29404, 29401, 29402, -1, 29406, 29390, 29389, -1, 29406, 29389, 29403, -1, 29407, 29405, 29408, -1, 29407, 29404, 29405, -1, 29407, 29400, 29404, -1, 29407, 29403, 29400, -1, 29398, 29391, 29390, -1, 29398, 29390, 29406, -1, 29409, 29408, 29410, -1, 29409, 29403, 29407, -1, 29409, 29406, 29403, -1, 29409, 29407, 29408, -1, 29397, 29392, 29391, -1, 29397, 29133, 29392, -1, 29397, 29391, 29398, -1, 29396, 29410, 29394, -1, 29396, 29409, 29410, -1, 29396, 29398, 29406, -1, 29396, 29406, 29409, -1, 29006, 29402, 24788, -1, 29411, 29010, 25221, -1, 29128, 29130, 29412, -1, 29413, 29006, 29008, -1, 29413, 29402, 29006, -1, 29414, 29405, 29402, -1, 29414, 29402, 29413, -1, 29415, 29008, 29010, -1, 29415, 29010, 29411, -1, 29415, 29413, 29008, -1, 29416, 29408, 29405, -1, 29416, 29410, 29408, -1, 29416, 29405, 29414, -1, 29417, 29411, 29418, -1, 29417, 29414, 29413, -1, 29417, 29413, 29415, -1, 29417, 29415, 29411, -1, 29419, 29394, 29410, -1, 29419, 29410, 29416, -1, 29420, 29418, 29421, -1, 29420, 29416, 29414, -1, 29420, 29417, 29418, -1, 29420, 29414, 29417, -1, 29422, 29395, 29394, -1, 29422, 29394, 29419, -1, 29423, 29416, 29420, -1, 29423, 29419, 29416, -1, 29423, 29420, 29421, -1, 29424, 29131, 29395, -1, 29424, 29130, 29129, -1, 29424, 29129, 29131, -1, 29424, 29395, 29422, -1, 29425, 29421, 29412, -1, 29425, 29422, 29419, -1, 29425, 29423, 29421, -1, 29425, 29412, 29130, -1, 29425, 29419, 29423, -1, 29425, 29130, 29424, -1, 29425, 29424, 29422, -1, 25220, 29411, 25221, -1, 29127, 29421, 29418, -1, 29127, 29412, 29421, -1, 29127, 29128, 29412, -1, 29426, 29411, 25220, -1, 29427, 29418, 29411, -1, 29427, 29411, 29426, -1, 29427, 29127, 29418, -1, 29428, 29127, 29427, -1, 29429, 29126, 29127, -1, 29429, 29428, 29126, -1, 29429, 29127, 29428, -1, 29430, 25220, 25222, -1, 29430, 25222, 25219, -1, 29430, 25219, 29431, -1, 29430, 29426, 25220, -1, 29432, 29431, 29433, -1, 29432, 29430, 29431, -1, 29432, 29426, 29430, -1, 29432, 29427, 29426, -1, 29434, 29433, 29435, -1, 29434, 29126, 29428, -1, 29434, 29428, 29427, -1, 29434, 29427, 29432, -1, 29434, 29432, 29433, -1, 29436, 29435, 25360, -1, 29436, 25360, 29126, -1, 29436, 29434, 29435, -1, 29436, 29126, 29434, -1, 25219, 18031, 18033, -1, 29431, 18033, 18034, -1, 29431, 25219, 18033, -1, 29433, 18034, 18030, -1, 29433, 29431, 18034, -1, 29435, 18030, 25356, -1, 29435, 29433, 18030, -1, 25360, 29435, 25356, -1, 29437, 29438, 29439, -1, 29440, 24162, 24164, -1, 29440, 29439, 29441, -1, 29440, 29441, 29442, -1, 29440, 29442, 24162, -1, 29443, 16742, 16737, -1, 29443, 29444, 29445, -1, 29154, 29446, 25321, -1, 29443, 16737, 29444, -1, 29443, 29445, 29447, -1, 29448, 29447, 29449, -1, 29448, 29449, 29437, -1, 29450, 24164, 24166, -1, 29450, 29439, 29440, -1, 29450, 29440, 24164, -1, 29450, 29437, 29439, -1, 29451, 16746, 16742, -1, 29451, 16742, 29443, -1, 29451, 29447, 29448, -1, 29451, 29443, 29447, -1, 29452, 24166, 24168, -1, 29452, 29450, 24166, -1, 29452, 29448, 29437, -1, 29452, 29437, 29450, -1, 29453, 24168, 24170, -1, 29453, 16746, 29451, -1, 29453, 24170, 16746, -1, 29453, 29452, 24168, -1, 29453, 29451, 29448, -1, 29453, 29448, 29452, -1, 24160, 29156, 18513, -1, 16737, 16735, 29444, -1, 16706, 16746, 24170, -1, 29454, 29446, 29154, -1, 29455, 29456, 29446, -1, 29455, 29446, 29454, -1, 29457, 29154, 29155, -1, 29457, 29454, 29154, -1, 29438, 29458, 29456, -1, 29438, 29456, 29455, -1, 29441, 29455, 29454, -1, 29441, 29454, 29457, -1, 29459, 29155, 29156, -1, 29459, 29457, 29155, -1, 29459, 29156, 24160, -1, 29449, 29460, 29458, -1, 29449, 29458, 29438, -1, 29439, 29455, 29441, -1, 29439, 29438, 29455, -1, 29442, 24160, 24162, -1, 29442, 29459, 24160, -1, 29442, 29457, 29459, -1, 29442, 29441, 29457, -1, 29447, 29445, 29460, -1, 29447, 29460, 29449, -1, 29437, 29449, 29438, -1, 16735, 16727, 29461, -1, 29444, 29461, 29462, -1, 29444, 16735, 29461, -1, 29445, 29462, 29463, -1, 29445, 29444, 29462, -1, 29460, 29463, 29464, -1, 29460, 29445, 29463, -1, 29458, 29464, 29465, -1, 29458, 29460, 29464, -1, 29456, 29465, 29466, -1, 29456, 29458, 29465, -1, 29446, 29466, 25322, -1, 29446, 29456, 29466, -1, 25321, 29446, 25322, -1, 29467, 16768, 16769, -1, 29467, 16769, 29468, -1, 29467, 29461, 16768, -1, 29467, 29468, 29469, -1, 29467, 29470, 29462, -1, 29467, 29469, 29470, -1, 29152, 29471, 24766, -1, 16727, 16768, 29461, -1, 29472, 29471, 29152, -1, 29473, 29474, 29471, -1, 29473, 29471, 29472, -1, 29475, 25322, 29466, -1, 29475, 29152, 29153, -1, 29475, 29153, 25322, -1, 29475, 29472, 29152, -1, 29476, 29477, 29474, -1, 29476, 29474, 29473, -1, 29478, 29466, 29465, -1, 29478, 29473, 29472, -1, 29478, 29472, 29475, -1, 29478, 29475, 29466, -1, 29479, 29480, 29477, -1, 29479, 29477, 29476, -1, 29481, 29465, 29464, -1, 29481, 29478, 29465, -1, 29481, 29473, 29478, -1, 29481, 29476, 29473, -1, 29469, 29482, 29480, -1, 29469, 29480, 29479, -1, 29483, 29464, 29463, -1, 29483, 29476, 29481, -1, 29483, 29479, 29476, -1, 29483, 29481, 29464, -1, 29468, 16769, 16767, -1, 29468, 16767, 29484, -1, 29468, 29484, 29482, -1, 29468, 29482, 29469, -1, 29470, 29463, 29462, -1, 29470, 29483, 29463, -1, 29470, 29469, 29479, -1, 29470, 29479, 29483, -1, 29467, 29462, 29461, -1, 29484, 16767, 16745, -1, 29484, 16745, 29485, -1, 29482, 29485, 29486, -1, 29482, 29484, 29485, -1, 29480, 29486, 29487, -1, 29480, 29482, 29486, -1, 29477, 29487, 29488, -1, 29477, 29480, 29487, -1, 29474, 29488, 29489, -1, 29474, 29477, 29488, -1, 29471, 29489, 29490, -1, 29471, 29474, 29489, -1, 24766, 29490, 24767, -1, 24766, 29471, 29490, -1, 29491, 29492, 29493, -1, 29491, 29494, 29492, -1, 29495, 29496, 29497, -1, 29495, 29497, 29498, -1, 29151, 29499, 25341, -1, 29500, 29149, 29148, -1, 29500, 29493, 29149, -1, 29500, 29148, 29490, -1, 29501, 29502, 29503, -1, 29501, 29498, 29502, -1, 29504, 29503, 29494, -1, 29504, 29494, 29491, -1, 29505, 29506, 29496, -1, 29505, 29496, 29495, -1, 29505, 16732, 29506, -1, 29507, 29490, 29489, -1, 29507, 29500, 29490, -1, 29507, 29491, 29493, -1, 29507, 29493, 29500, -1, 29508, 29495, 29498, -1, 29508, 29498, 29501, -1, 29509, 29501, 29503, -1, 29490, 29148, 24767, -1, 29509, 29503, 29504, -1, 29510, 29489, 29488, -1, 16732, 16738, 29506, -1, 29510, 29504, 29491, -1, 29510, 29507, 29489, -1, 29510, 29491, 29507, -1, 29511, 16733, 16732, -1, 29511, 16732, 29505, -1, 29511, 29495, 29508, -1, 29511, 29505, 29495, -1, 29512, 29508, 29501, -1, 29512, 29501, 29509, -1, 29513, 29488, 29487, -1, 29513, 29504, 29510, -1, 29513, 29509, 29504, -1, 29513, 29510, 29488, -1, 29514, 29511, 29508, -1, 29514, 16736, 16733, -1, 29514, 16733, 29511, -1, 29514, 29508, 29512, -1, 29515, 29487, 29486, -1, 29515, 29512, 29509, -1, 29515, 29509, 29513, -1, 29515, 29513, 29487, -1, 29516, 29486, 29485, -1, 29516, 16736, 29514, -1, 29516, 16741, 16736, -1, 29516, 29514, 29512, -1, 29516, 29515, 29486, -1, 29516, 29485, 16741, -1, 29516, 29512, 29515, -1, 16745, 16741, 29485, -1, 29517, 29499, 29151, -1, 29518, 29519, 29499, -1, 29518, 29499, 29517, -1, 29492, 29151, 29150, -1, 29492, 29517, 29151, -1, 29502, 29520, 29519, -1, 29502, 29519, 29518, -1, 29494, 29518, 29517, -1, 29494, 29517, 29492, -1, 29493, 29150, 29149, -1, 29493, 29492, 29150, -1, 29498, 29497, 29520, -1, 29498, 29520, 29502, -1, 29503, 29518, 29494, -1, 29503, 29502, 29518, -1, 29506, 16738, 16749, -1, 29506, 16749, 29521, -1, 29496, 29521, 29522, -1, 29496, 29506, 29521, -1, 29497, 29522, 29523, -1, 29497, 29496, 29522, -1, 29520, 29523, 29524, -1, 29520, 29497, 29523, -1, 29519, 29524, 29525, -1, 29519, 29520, 29524, -1, 29499, 29525, 29526, -1, 29499, 29519, 29525, -1, 25341, 29526, 25342, -1, 25341, 29499, 29526, -1, 29527, 29528, 29529, -1, 29527, 29529, 29145, -1, 29527, 29145, 29146, -1, 29527, 29146, 29147, -1, 29527, 29530, 29528, -1, 29527, 29147, 29531, -1, 29527, 29531, 29532, -1, 29527, 29532, 29530, -1, 29147, 25342, 29526, -1, 29533, 29521, 16749, -1, 29533, 16749, 16751, -1, 29533, 16751, 16750, -1, 29534, 29522, 29521, -1, 29534, 29521, 29533, -1, 29535, 16750, 16753, -1, 29535, 16753, 29536, -1, 29535, 29533, 16750, -1, 29537, 29523, 29522, -1, 29537, 29522, 29534, -1, 29538, 29536, 29539, -1, 29538, 29534, 29533, -1, 29538, 29533, 29535, -1, 29538, 29535, 29536, -1, 29540, 29524, 29523, -1, 29540, 29523, 29537, -1, 29541, 29539, 29542, -1, 29541, 29537, 29534, -1, 29541, 29534, 29538, -1, 29541, 29538, 29539, -1, 29532, 29525, 29524, -1, 29532, 29524, 29540, -1, 29543, 29542, 29544, -1, 29543, 29540, 29537, -1, 29543, 29537, 29541, -1, 29543, 29541, 29542, -1, 29531, 29526, 29525, -1, 29531, 29147, 29526, -1, 29531, 29525, 29532, -1, 29530, 29544, 29528, -1, 29530, 29540, 29543, -1, 29530, 29543, 29544, -1, 29530, 29532, 29540, -1, 29003, 29536, 16753, -1, 29003, 29539, 29536, -1, 29144, 29529, 29528, -1, 29144, 29145, 29529, -1, 29545, 29003, 29001, -1, 29546, 29539, 29003, -1, 29546, 29003, 29545, -1, 29547, 29001, 28999, -1, 29547, 28999, 25217, -1, 29547, 25217, 29548, -1, 29547, 29545, 29001, -1, 29549, 29542, 29539, -1, 29549, 29544, 29542, -1, 29549, 29539, 29546, -1, 29550, 29548, 29551, -1, 29550, 29546, 29545, -1, 29550, 29545, 29547, -1, 29550, 29547, 29548, -1, 29552, 29551, 29553, -1, 29552, 29546, 29550, -1, 29552, 29549, 29546, -1, 29552, 29550, 29551, -1, 29554, 29528, 29544, -1, 29554, 29544, 29549, -1, 29555, 29552, 29553, -1, 29555, 29554, 29549, -1, 29555, 29549, 29552, -1, 29556, 29143, 29144, -1, 29556, 29144, 29528, -1, 29556, 29528, 29554, -1, 29557, 29553, 29558, -1, 29557, 29558, 29142, -1, 29557, 29142, 29143, -1, 29557, 29555, 29553, -1, 29557, 29554, 29555, -1, 29557, 29143, 29556, -1, 29557, 29556, 29554, -1, 29558, 29559, 25361, -1, 29558, 25361, 29142, -1, 29553, 29560, 29559, -1, 29553, 29559, 29558, -1, 29551, 29561, 29560, -1, 29551, 29560, 29553, -1, 29548, 25218, 29561, -1, 29548, 29561, 29551, -1, 25217, 25218, 29548, -1, 25340, 25361, 29559, -1, 18000, 29559, 29560, -1, 18000, 25340, 29559, -1, 17999, 29560, 29561, -1, 17999, 18000, 29560, -1, 17998, 29561, 25218, -1, 17998, 17999, 29561, -1, 17996, 17998, 25218, -1, 29562, 29563, 17229, -1, 29562, 17229, 29564, -1, 29562, 29564, 29565, -1, 29562, 29565, 29566, -1, 29567, 26642, 23704, -1, 17221, 17219, 29568, -1, 17236, 17229, 29563, -1, 29569, 29570, 26646, -1, 29569, 26646, 26644, -1, 29571, 29572, 29570, -1, 29571, 29570, 29569, -1, 29573, 26644, 26642, -1, 29573, 26642, 29567, -1, 29573, 29569, 26644, -1, 29574, 29575, 29572, -1, 29574, 29572, 29571, -1, 29576, 29567, 29577, -1, 29576, 29571, 29569, -1, 29576, 29569, 29573, -1, 29576, 29573, 29567, -1, 29578, 29579, 29575, -1, 29578, 29575, 29574, -1, 29580, 29577, 29581, -1, 29580, 29576, 29577, -1, 29580, 29571, 29576, -1, 29580, 29574, 29571, -1, 29565, 29582, 29579, -1, 29565, 29579, 29578, -1, 29583, 29581, 29584, -1, 29583, 29578, 29574, -1, 29583, 29574, 29580, -1, 29583, 29580, 29581, -1, 29564, 29568, 29582, -1, 29564, 17229, 17221, -1, 29564, 17221, 29568, -1, 29564, 29582, 29565, -1, 29566, 29584, 29585, -1, 29566, 29578, 29583, -1, 29566, 29583, 29584, -1, 29566, 29565, 29578, -1, 29562, 29585, 29563, -1, 29562, 29566, 29585, -1, 29586, 17236, 29563, -1, 29586, 17246, 17236, -1, 29587, 29563, 29585, -1, 29587, 29586, 29563, -1, 29588, 29585, 29584, -1, 29588, 29587, 29585, -1, 29589, 29584, 29581, -1, 29589, 29588, 29584, -1, 29590, 29581, 29577, -1, 29590, 29589, 29581, -1, 29591, 29577, 29567, -1, 29591, 29590, 29577, -1, 23700, 29567, 23704, -1, 23700, 29591, 29567, -1, 26647, 26646, 29570, -1, 29592, 29570, 29572, -1, 29592, 26647, 29570, -1, 29593, 29572, 29575, -1, 29593, 29592, 29572, -1, 29594, 29575, 29579, -1, 29594, 29593, 29575, -1, 29595, 29579, 29582, -1, 29595, 29594, 29579, -1, 29596, 29582, 29568, -1, 29596, 29595, 29582, -1, 29597, 29596, 29568, -1, 17218, 29568, 17219, -1, 17218, 29597, 29568, -1, 29598, 29599, 29600, -1, 29598, 17247, 29601, -1, 29598, 29601, 29602, -1, 29603, 23696, 23694, -1, 17247, 17246, 29586, -1, 17249, 17248, 29604, -1, 29605, 29591, 23700, -1, 29605, 23700, 23698, -1, 29606, 29590, 29591, -1, 29606, 29591, 29605, -1, 29607, 23698, 23696, -1, 29607, 29605, 23698, -1, 29607, 23696, 29603, -1, 29608, 29589, 29590, -1, 29608, 29590, 29606, -1, 29609, 29603, 29610, -1, 29609, 29606, 29605, -1, 29609, 29605, 29607, -1, 29609, 29607, 29603, -1, 29611, 29588, 29589, -1, 29611, 29589, 29608, -1, 29612, 29610, 29613, -1, 29612, 29609, 29610, -1, 29612, 29606, 29609, -1, 29612, 29608, 29606, -1, 29602, 29587, 29588, -1, 29602, 29588, 29611, -1, 29614, 29613, 29615, -1, 29614, 29611, 29608, -1, 29614, 29608, 29612, -1, 29614, 29612, 29613, -1, 29601, 29586, 29587, -1, 29601, 17247, 29586, -1, 29601, 29587, 29602, -1, 29599, 29615, 29600, -1, 29599, 29602, 29611, -1, 29599, 29611, 29614, -1, 29599, 29614, 29615, -1, 29598, 29600, 29604, -1, 29598, 17248, 17247, -1, 29598, 29602, 29599, -1, 29598, 29604, 17248, -1, 29616, 29617, 29618, -1, 29619, 29592, 29593, -1, 29619, 26732, 26730, -1, 29619, 29620, 26732, -1, 29619, 26730, 29592, -1, 29621, 29618, 29622, -1, 29621, 29622, 29623, -1, 29624, 29625, 29626, -1, 29624, 29623, 29625, -1, 29627, 17220, 17235, -1, 29627, 29628, 29617, -1, 29627, 17235, 29628, -1, 29627, 29617, 29616, -1, 29629, 29593, 29594, -1, 29629, 29619, 29593, -1, 29629, 29626, 29620, -1, 29629, 29620, 29619, -1, 29630, 29616, 29618, -1, 29630, 29618, 29621, -1, 29631, 29621, 29623, -1, 29631, 29623, 29624, -1, 29632, 29594, 29595, -1, 29632, 29629, 29594, -1, 29592, 26730, 26647, -1, 29632, 29624, 29626, -1, 29632, 29626, 29629, -1, 29633, 17217, 17220, -1, 29633, 29616, 29630, -1, 29633, 17220, 29627, -1, 29633, 29627, 29616, -1, 29634, 29630, 29621, -1, 29634, 29621, 29631, -1, 29635, 29595, 29596, -1, 29635, 29632, 29595, -1, 29635, 29631, 29624, -1, 29635, 29624, 29632, -1, 29636, 29630, 29634, -1, 29636, 17215, 17217, -1, 29636, 17217, 29633, -1, 29636, 29633, 29630, -1, 29637, 29634, 29631, -1, 29637, 29635, 29596, -1, 29637, 29596, 29597, -1, 29637, 29631, 29635, -1, 29638, 17216, 17215, -1, 29638, 29637, 29597, -1, 29638, 17215, 29636, -1, 29638, 29597, 17216, -1, 29638, 29636, 29634, -1, 29638, 29634, 29637, -1, 17218, 17216, 29597, -1, 29639, 29640, 26739, -1, 29639, 26739, 26736, -1, 29641, 29642, 29640, -1, 29641, 29643, 29642, -1, 29641, 29640, 29639, -1, 29644, 26736, 26734, -1, 29644, 29639, 26736, -1, 29622, 29643, 29641, -1, 29625, 29641, 29639, -1, 29625, 29639, 29644, -1, 29620, 26734, 26732, -1, 29620, 29644, 26734, -1, 29618, 29645, 29643, -1, 29618, 29617, 29645, -1, 29618, 29643, 29622, -1, 29623, 29641, 29625, -1, 29623, 29622, 29641, -1, 29626, 29625, 29644, -1, 29626, 29644, 29620, -1, 17250, 17249, 29604, -1, 29646, 29604, 29600, -1, 29646, 17250, 29604, -1, 29647, 29600, 29615, -1, 29647, 29646, 29600, -1, 29648, 29615, 29613, -1, 29648, 29647, 29615, -1, 29649, 29613, 29610, -1, 29649, 29648, 29613, -1, 29650, 29610, 29603, -1, 29650, 29649, 29610, -1, 29651, 29603, 23694, -1, 29651, 29650, 29603, -1, 23691, 29651, 23694, -1, 29652, 26739, 29640, -1, 29652, 26742, 26739, -1, 29653, 29640, 29642, -1, 29653, 29652, 29640, -1, 29654, 29642, 29643, -1, 29654, 29653, 29642, -1, 29655, 29643, 29645, -1, 29655, 29645, 29617, -1, 29655, 29654, 29643, -1, 29656, 29655, 29617, -1, 29657, 29617, 29628, -1, 29657, 29628, 17235, -1, 29657, 29656, 29617, -1, 17237, 29657, 17235, -1, 29658, 29646, 29647, -1, 29658, 29647, 29659, -1, 29660, 23683, 23680, -1, 29660, 23685, 23683, -1, 23689, 29651, 23691, -1, 29660, 23680, 29661, -1, 29660, 29662, 23685, -1, 29663, 29659, 29664, -1, 29663, 29664, 29665, -1, 29666, 29667, 29668, -1, 29666, 29665, 29667, -1, 29669, 17250, 29646, -1, 29669, 17251, 17250, -1, 29669, 17252, 17251, -1, 29669, 29646, 29658, -1, 29670, 29661, 29671, -1, 29670, 29660, 29661, -1, 29670, 29668, 29662, -1, 29670, 29662, 29660, -1, 29672, 29659, 29663, -1, 29672, 29658, 29659, -1, 29673, 29663, 29665, -1, 29673, 29665, 29666, -1, 29674, 29671, 29675, -1, 29674, 29666, 29668, -1, 29674, 29670, 29671, -1, 29674, 29668, 29670, -1, 29676, 17253, 17252, -1, 29676, 17252, 29669, -1, 29676, 29669, 29658, -1, 29676, 29658, 29672, -1, 29677, 29672, 29663, -1, 29677, 29663, 29673, -1, 29678, 29675, 29679, -1, 29678, 29674, 29675, -1, 29678, 29666, 29674, -1, 29678, 29673, 29666, -1, 29680, 29676, 29672, -1, 29680, 17254, 17253, -1, 29680, 17253, 29676, -1, 29680, 29672, 29677, -1, 29681, 29677, 29673, -1, 29681, 29679, 29682, -1, 29681, 29673, 29678, -1, 29681, 29678, 29679, -1, 29683, 17254, 29680, -1, 29683, 29680, 29677, -1, 29683, 29682, 29684, -1, 29683, 29677, 29681, -1, 29683, 29681, 29682, -1, 29683, 29684, 17254, -1, 17228, 17254, 29684, -1, 29685, 29650, 29651, -1, 29685, 29651, 23689, -1, 29686, 29649, 29650, -1, 29686, 29650, 29685, -1, 29687, 23689, 23687, -1, 29687, 29685, 23689, -1, 29664, 29648, 29649, -1, 29664, 29649, 29686, -1, 29667, 29685, 29687, -1, 29667, 29686, 29685, -1, 29662, 23687, 23685, -1, 29662, 29687, 23687, -1, 29659, 29647, 29648, -1, 29659, 29648, 29664, -1, 29665, 29686, 29667, -1, 29665, 29664, 29686, -1, 29668, 29667, 29687, -1, 29668, 29687, 29662, -1, 29688, 29689, 29690, -1, 29688, 29690, 29691, -1, 29692, 26742, 29652, -1, 29692, 26985, 26742, -1, 29692, 26987, 26985, -1, 26992, 29693, 26972, -1, 29692, 29694, 26987, -1, 29695, 29691, 29696, -1, 29695, 29696, 29697, -1, 29698, 29697, 29699, -1, 29698, 29699, 29700, -1, 29701, 17241, 17242, -1, 29701, 17242, 29689, -1, 29701, 29689, 29688, -1, 29702, 29652, 29653, -1, 29702, 29700, 29694, -1, 29702, 29692, 29652, -1, 29702, 29694, 29692, -1, 29703, 29691, 29695, -1, 29703, 29688, 29691, -1, 29704, 29697, 29698, -1, 29704, 29695, 29697, -1, 29705, 29653, 29654, -1, 29705, 29700, 29702, -1, 29705, 29698, 29700, -1, 29705, 29702, 29653, -1, 29706, 17240, 17241, -1, 29706, 17241, 29701, -1, 29706, 29688, 29703, -1, 29706, 29701, 29688, -1, 29707, 29703, 29695, -1, 29707, 29695, 29704, -1, 29708, 29654, 29655, -1, 29708, 29705, 29654, -1, 29708, 29704, 29698, -1, 29708, 29698, 29705, -1, 29709, 17239, 17240, -1, 29709, 29703, 29707, -1, 29709, 17240, 29706, -1, 29709, 29706, 29703, -1, 29710, 29707, 29704, -1, 29710, 29655, 29656, -1, 29710, 29708, 29655, -1, 29710, 29704, 29708, -1, 29711, 29710, 29656, -1, 29711, 29656, 29657, -1, 29711, 29709, 29707, -1, 29711, 17238, 17239, -1, 29711, 17239, 29709, -1, 29711, 29707, 29710, -1, 29711, 29657, 17238, -1, 17237, 17238, 29657, -1, 29712, 29713, 29693, -1, 29712, 29693, 26992, -1, 29714, 29715, 29713, -1, 29714, 29713, 29712, -1, 29716, 26992, 26990, -1, 29716, 29712, 26992, -1, 29696, 29717, 29715, -1, 29696, 29715, 29714, -1, 29699, 29714, 29712, -1, 29699, 29712, 29716, -1, 29694, 26990, 26987, -1, 29694, 29716, 26990, -1, 29691, 29690, 29717, -1, 29691, 29717, 29696, -1, 29697, 29714, 29699, -1, 29697, 29696, 29714, -1, 29700, 29699, 29716, -1, 29700, 29716, 29694, -1, 29718, 17228, 29684, -1, 29718, 17227, 17228, -1, 29719, 29684, 29682, -1, 29719, 29718, 29684, -1, 29720, 29682, 29679, -1, 29720, 29719, 29682, -1, 29721, 29679, 29675, -1, 29721, 29720, 29679, -1, 29722, 29675, 29671, -1, 29722, 29721, 29675, -1, 29723, 29671, 29661, -1, 29723, 29661, 23680, -1, 29723, 29722, 29671, -1, 23677, 29723, 23680, -1, 29724, 26972, 29693, -1, 29724, 26967, 26972, -1, 29725, 29693, 29713, -1, 29725, 29724, 29693, -1, 29726, 29713, 29715, -1, 29726, 29725, 29713, -1, 29727, 29715, 29717, -1, 29727, 29726, 29715, -1, 29728, 29717, 29690, -1, 29728, 29727, 29717, -1, 29729, 29690, 29689, -1, 29729, 29728, 29690, -1, 17243, 29689, 17242, -1, 17243, 29729, 29689, -1, 29730, 29731, 29732, -1, 29730, 29732, 29733, -1, 29734, 29719, 29720, -1, 29734, 29720, 29735, -1, 23675, 29723, 23677, -1, 29736, 23670, 23668, -1, 29736, 29733, 23670, -1, 29736, 23668, 29737, -1, 29738, 29739, 29740, -1, 29738, 29735, 29739, -1, 29741, 29740, 29731, -1, 29741, 29731, 29730, -1, 29742, 17227, 29718, -1, 29742, 29718, 29719, -1, 29742, 17230, 17227, -1, 29742, 29719, 29734, -1, 29743, 29737, 29744, -1, 29743, 29736, 29737, -1, 29743, 29730, 29733, -1, 29743, 29733, 29736, -1, 29745, 29734, 29735, -1, 29745, 29735, 29738, -1, 29746, 29740, 29741, -1, 29737, 23668, 23664, -1, 29746, 29738, 29740, -1, 29747, 29744, 29748, -1, 29747, 29743, 29744, -1, 29747, 29741, 29730, -1, 29747, 29730, 29743, -1, 29749, 17231, 17230, -1, 29749, 17230, 29742, -1, 29749, 29734, 29745, -1, 29749, 29742, 29734, -1, 29750, 29745, 29738, -1, 29750, 29738, 29746, -1, 29751, 29748, 29752, -1, 29751, 29747, 29748, -1, 29751, 29746, 29741, -1, 29751, 29741, 29747, -1, 29753, 29749, 29745, -1, 29753, 17232, 17231, -1, 29753, 17231, 29749, -1, 29753, 29745, 29750, -1, 29754, 29750, 29746, -1, 29754, 29752, 29755, -1, 29754, 29751, 29752, -1, 29754, 29746, 29751, -1, 29756, 29753, 29750, -1, 29756, 29755, 29757, -1, 29756, 17233, 17232, -1, 29756, 29754, 29755, -1, 29756, 29757, 17233, -1, 29756, 29750, 29754, -1, 17223, 17233, 29757, -1, 29756, 17232, 29753, -1, 29758, 29723, 23675, -1, 29759, 29722, 29723, -1, 29759, 29723, 29758, -1, 29732, 23675, 23673, -1, 29732, 29758, 23675, -1, 29739, 29721, 29722, -1, 29739, 29722, 29759, -1, 29731, 29759, 29758, -1, 29731, 29758, 29732, -1, 29733, 23673, 23670, -1, 29733, 29732, 23673, -1, 29735, 29720, 29721, -1, 29735, 29721, 29739, -1, 29740, 29739, 29759, -1, 29740, 29759, 29731, -1, 29760, 17245, 29761, -1, 29760, 29762, 29728, -1, 29760, 29729, 17244, -1, 29760, 29761, 29763, -1, 29760, 29763, 29762, -1, 17243, 17244, 29729, -1, 29764, 29765, 23653, -1, 29764, 23653, 26968, -1, 29766, 29767, 29765, -1, 29766, 29765, 29764, -1, 29768, 26967, 29724, -1, 29768, 26965, 26967, -1, 29768, 26968, 26965, -1, 29768, 29764, 26968, -1, 29769, 29770, 29767, -1, 29769, 29767, 29766, -1, 29771, 29724, 29725, -1, 29771, 29766, 29764, -1, 29771, 29768, 29724, -1, 29771, 29764, 29768, -1, 29772, 29773, 29770, -1, 29772, 29770, 29769, -1, 29774, 29725, 29726, -1, 29774, 29771, 29725, -1, 29774, 29769, 29766, -1, 29774, 29766, 29771, -1, 29763, 29775, 29773, -1, 29763, 29773, 29772, -1, 29776, 29726, 29727, -1, 29776, 29769, 29774, -1, 29776, 29774, 29726, -1, 29776, 29772, 29769, -1, 29761, 17245, 17234, -1, 29761, 29777, 29775, -1, 29761, 17234, 29777, -1, 29761, 29775, 29763, -1, 29762, 29727, 29728, -1, 29762, 29776, 29727, -1, 29762, 29772, 29776, -1, 29762, 29763, 29772, -1, 29760, 29728, 29729, -1, 29760, 17244, 17245, -1, 17222, 17223, 29757, -1, 29778, 29757, 29755, -1, 29778, 17222, 29757, -1, 29779, 29755, 29752, -1, 29779, 29778, 29755, -1, 29780, 29752, 29748, -1, 29780, 29779, 29752, -1, 29781, 29748, 29744, -1, 29781, 29780, 29748, -1, 29782, 29744, 29737, -1, 29782, 29781, 29744, -1, 29783, 29737, 23664, -1, 29783, 29782, 29737, -1, 23662, 29783, 23664, -1, 29777, 17234, 17226, -1, 29777, 17226, 29784, -1, 29775, 29784, 29785, -1, 29775, 29777, 29784, -1, 29773, 29785, 29786, -1, 29773, 29775, 29785, -1, 29770, 29786, 29787, -1, 29770, 29773, 29786, -1, 29767, 29787, 29788, -1, 29767, 29770, 29787, -1, 29765, 29788, 29789, -1, 29765, 29767, 29788, -1, 23653, 29789, 23654, -1, 23653, 29765, 29789, -1, 23660, 29783, 23662, -1, 17226, 17225, 29784, -1, 29790, 29782, 29783, -1, 29790, 29783, 23660, -1, 29791, 29781, 29782, -1, 29791, 29782, 29790, -1, 29792, 23658, 23654, -1, 29792, 23660, 23658, -1, 29792, 23654, 29789, -1, 29792, 29790, 23660, -1, 29793, 29780, 29781, -1, 29793, 29781, 29791, -1, 29794, 29789, 29788, -1, 29794, 29791, 29790, -1, 29794, 29792, 29789, -1, 29794, 29790, 29792, -1, 29795, 29779, 29780, -1, 29795, 29780, 29793, -1, 29796, 29788, 29787, -1, 29796, 29791, 29794, -1, 29796, 29793, 29791, -1, 29796, 29794, 29788, -1, 29797, 29778, 29779, -1, 29797, 29779, 29795, -1, 29798, 29787, 29786, -1, 29798, 29795, 29793, -1, 29798, 29793, 29796, -1, 29798, 29796, 29787, -1, 29799, 17222, 29778, -1, 29799, 17224, 17222, -1, 29799, 29778, 29797, -1, 29800, 29786, 29785, -1, 29800, 29795, 29798, -1, 29800, 29798, 29786, -1, 29800, 29797, 29795, -1, 29801, 29785, 29784, -1, 29801, 17225, 17224, -1, 29801, 29784, 17225, -1, 29801, 29800, 29785, -1, 29801, 17224, 29799, -1, 29801, 29799, 29797, -1, 29801, 29797, 29800, -1, 29802, 2861, 29803, -1, 2836, 2861, 29802, -1, 2645, 29804, 29805, -1, 2645, 2667, 29804, -1, 17396, 17400, 17395, -1, 17396, 17420, 17400, -1, 24689, 29806, 25545, -1, 24688, 29806, 24689, -1, 24697, 29807, 24690, -1, 25533, 29807, 24697, -1, 29807, 29808, 24690, -1, 24688, 29809, 29806, -1, 29808, 29810, 24690, -1, 24688, 29811, 29809, -1, 29810, 29812, 24690, -1, 24688, 29813, 29811, -1, 24690, 29804, 24688, -1, 24688, 29804, 29813, -1, 29812, 29805, 24690, -1, 24690, 29805, 29804, -1, 2722, 25545, 29806, -1, 2722, 2907, 25545, -1, 25528, 2798, 29807, -1, 25528, 29807, 25533, -1, 17418, 2798, 25528, -1, 17380, 17418, 17420, -1, 17380, 17420, 17396, -1, 29814, 17379, 17431, -1, 2716, 17380, 17379, -1, 2716, 17379, 29814, -1, 2716, 2798, 17418, -1, 2716, 17418, 17380, -1, 17443, 29815, 16451, -1, 29816, 16450, 29815, -1, 29817, 16450, 29816, -1, 29818, 16450, 29817, -1, 29815, 16450, 16451, -1, 29818, 29802, 16450, -1, 29803, 16457, 29802, -1, 29802, 16457, 16450, -1, 29803, 29819, 16457, -1, 29819, 29820, 16457, -1, 29820, 29821, 16457, -1, 16457, 29814, 16459, -1, 29821, 29814, 16457, -1, 29814, 17431, 16459, -1, 2814, 2812, 29815, -1, 2814, 29815, 17443, -1, 29822, 2783, 17438, -1, 2755, 2783, 29822, -1, 25536, 2811, 29823, -1, 2809, 2811, 25536, -1, 29824, 16332, 29825, -1, 29826, 16332, 29824, -1, 29827, 16332, 29826, -1, 29828, 16332, 29827, -1, 29829, 16332, 29828, -1, 29830, 16332, 29829, -1, 29822, 16332, 29830, -1, 17438, 16334, 29822, -1, 29822, 16334, 16332, -1, 16332, 16327, 29825, -1, 29825, 16327, 16328, -1, 16328, 16337, 29825, -1, 16341, 16345, 16337, -1, 16337, 16345, 16348, -1, 16362, 29831, 16348, -1, 16363, 29831, 16362, -1, 16348, 29831, 16337, -1, 16337, 29831, 29825, -1, 29832, 16372, 29833, -1, 29834, 16372, 29832, -1, 29831, 16372, 29834, -1, 16363, 16372, 29831, -1, 16372, 29835, 29833, -1, 16372, 29836, 29835, -1, 16372, 29837, 29836, -1, 16372, 29823, 29837, -1, 16372, 16374, 29823, -1, 16374, 25536, 29823, -1, 2671, 29825, 29831, -1, 2671, 2747, 29825, -1, 16061, 16063, 25525, -1, 25525, 24464, 25527, -1, 16063, 24464, 25525, -1, 25527, 24463, 24493, -1, 24464, 24463, 25527, -1, 24463, 24459, 24493, -1, 25526, 15254, 15253, -1, 25526, 24812, 15254, -1, 25524, 15253, 15252, -1, 25524, 25526, 15253, -1, 15536, 15252, 15251, -1, 15536, 25524, 15252, -1, 16007, 16009, 17378, -1, 16009, 16056, 17378, -1, 17378, 16055, 17376, -1, 16056, 16055, 17378, -1, 17376, 16054, 16074, -1, 16055, 16054, 17376, -1, 15550, 15242, 15243, -1, 17375, 15243, 15244, -1, 17375, 15550, 15243, -1, 17377, 15244, 15245, -1, 17377, 17375, 15244, -1, 16600, 17377, 15245, -1, 29838, 16323, 16324, -1, 29839, 29838, 16324, -1, 16369, 29840, 29841, -1, 16367, 16369, 29841, -1, 17300, 29842, 29843, -1, 17299, 17300, 29843, -1, 29844, 25449, 25448, -1, 29844, 29845, 25449, -1, 16379, 29846, 16380, -1, 16379, 29843, 29846, -1, 24606, 25448, 24607, -1, 16384, 29843, 16379, -1, 29844, 25448, 24606, -1, 16384, 16385, 17299, -1, 16384, 17299, 29843, -1, 25444, 25445, 16351, -1, 24602, 29844, 24606, -1, 25444, 16351, 16368, -1, 17293, 17294, 16340, -1, 16340, 17294, 16326, -1, 29847, 29844, 24602, -1, 25444, 29841, 29847, -1, 24601, 29847, 24602, -1, 24601, 25444, 29847, -1, 16367, 29841, 25444, -1, 16368, 16367, 25444, -1, 25445, 29848, 16352, -1, 25445, 16352, 16351, -1, 29849, 29848, 25445, -1, 25432, 29849, 25445, -1, 17296, 29850, 29851, -1, 25431, 29851, 29849, -1, 25431, 29849, 25432, -1, 25431, 17296, 29851, -1, 17295, 29852, 29850, -1, 17295, 29850, 17296, -1, 29853, 29852, 17295, -1, 17281, 29853, 17295, -1, 17293, 29854, 29855, -1, 17280, 29855, 29853, -1, 17280, 29853, 17281, -1, 17280, 17293, 29855, -1, 16339, 29854, 17293, -1, 16340, 16339, 17293, -1, 17294, 16324, 16326, -1, 17294, 29839, 16324, -1, 29846, 29839, 17294, -1, 16380, 29846, 17294, -1, 29856, 16269, 16265, -1, 29842, 16269, 29856, -1, 25449, 16321, 16322, -1, 17300, 16271, 29842, -1, 16274, 16271, 17300, -1, 25449, 29845, 16321, -1, 29842, 16271, 16269, -1, 16253, 16250, 16280, -1, 29845, 16316, 16321, -1, 16280, 16250, 16279, -1, 16289, 16291, 16358, -1, 16289, 16358, 16355, -1, 29845, 29857, 16316, -1, 29840, 16291, 29857, -1, 29857, 16313, 16316, -1, 16291, 16313, 29857, -1, 29840, 16369, 16291, -1, 16369, 16358, 16291, -1, 16354, 16289, 16355, -1, 29858, 16289, 16354, -1, 29858, 29859, 16289, -1, 29859, 16283, 16289, -1, 29859, 29860, 16283, -1, 29861, 16278, 29860, -1, 16278, 16282, 29860, -1, 29860, 16282, 16283, -1, 29862, 16275, 29861, -1, 29861, 16275, 16278, -1, 29862, 29863, 16275, -1, 29863, 16258, 16275, -1, 29864, 16250, 29865, -1, 29865, 16257, 29863, -1, 16250, 16257, 29865, -1, 29863, 16257, 16258, -1, 29864, 16338, 16250, -1, 16338, 16279, 16250, -1, 16323, 16253, 16280, -1, 29838, 16253, 16323, -1, 29838, 29856, 16253, -1, 29856, 16265, 16253, -1, 29842, 29856, 29846, -1, 29843, 29842, 29846, -1, 29839, 29856, 29838, -1, 29839, 29846, 29856, -1, 16338, 29864, 29854, -1, 16339, 16338, 29854, -1, 29854, 29864, 29865, -1, 29855, 29854, 29865, -1, 29855, 29865, 29863, -1, 29855, 29863, 29853, -1, 29862, 29853, 29863, -1, 29852, 29853, 29862, -1, 29852, 29862, 29861, -1, 29852, 29861, 29850, -1, 29851, 29861, 29860, -1, 29851, 29850, 29861, -1, 29851, 29860, 29859, -1, 29851, 29859, 29849, -1, 29848, 29859, 29858, -1, 29848, 29849, 29859, -1, 29848, 29858, 16354, -1, 29848, 16354, 16352, -1, 29841, 29840, 29857, -1, 29847, 29841, 29857, -1, 29847, 29857, 29845, -1, 29847, 29845, 29844, -1, 17401, 17392, 17394, -1, 17415, 17392, 17401, -1, 17389, 17413, 17412, -1, 17389, 17412, 17388, -1, 2770, 15263, 15259, -1, 24438, 24542, 24531, -1, 15263, 24542, 24438, -1, 2795, 16534, 24545, -1, 2770, 2795, 15263, -1, 15263, 2795, 24542, -1, 24545, 24542, 2795, -1, 15261, 15915, 2796, -1, 15915, 15982, 2796, -1, 15910, 15980, 15915, -1, 15915, 15980, 15982, -1, 15982, 2797, 2796, -1, 2797, 15983, 15022, -1, 15982, 15983, 2797, -1, 2889, 29814, 29821, -1, 2889, 2716, 29814, -1, 2877, 29821, 29820, -1, 2877, 2889, 29821, -1, 2869, 29820, 29819, -1, 2869, 2877, 29820, -1, 2861, 29819, 29803, -1, 2861, 2869, 29819, -1, 2645, 29805, 29812, -1, 2634, 29812, 29810, -1, 2634, 2645, 29812, -1, 2633, 29810, 29808, -1, 2633, 2634, 29810, -1, 2925, 29808, 29807, -1, 2925, 2633, 29808, -1, 2798, 2925, 29807, -1, 2722, 29806, 29809, -1, 2730, 29809, 29811, -1, 2730, 2722, 29809, -1, 2736, 29811, 29813, -1, 2736, 2730, 29811, -1, 2774, 29813, 29804, -1, 2774, 2736, 29813, -1, 2667, 2774, 29804, -1, 2671, 29831, 29834, -1, 2687, 29834, 29832, -1, 2687, 2671, 29834, -1, 2720, 29832, 29833, -1, 2720, 2687, 29832, -1, 2732, 29833, 29835, -1, 2732, 2720, 29833, -1, 2741, 29835, 29836, -1, 2741, 2732, 29835, -1, 2754, 29836, 29837, -1, 2754, 2741, 29836, -1, 2773, 29837, 29823, -1, 2773, 2754, 29837, -1, 2811, 2773, 29823, -1, 2740, 29822, 29830, -1, 2740, 2755, 29822, -1, 2733, 29830, 29829, -1, 2733, 2740, 29830, -1, 2727, 29829, 29828, -1, 2727, 2733, 29829, -1, 2728, 29828, 29827, -1, 2728, 2727, 29828, -1, 2731, 29827, 29826, -1, 2731, 2728, 29827, -1, 2742, 29826, 29824, -1, 2742, 2731, 29826, -1, 2747, 29824, 29825, -1, 2747, 2742, 29824, -1, 2836, 29802, 29818, -1, 2834, 2836, 29818, -1, 2816, 29818, 29817, -1, 2816, 2834, 29818, -1, 2815, 29816, 29815, -1, 2815, 29817, 29816, -1, 2815, 2816, 29817, -1, 2812, 2815, 29815, -1, 17372, 17202, 17192, -1, 17372, 17192, 17190, -1, 17370, 17190, 17186, -1, 17370, 17372, 17190, -1, 17371, 17186, 17188, -1, 17371, 17370, 17186, -1, 17367, 17188, 17185, -1, 17367, 17371, 17188, -1, 17368, 17185, 17187, -1, 17368, 17367, 17185, -1, 17369, 17187, 17189, -1, 17369, 17368, 17187, -1, 17361, 17189, 17191, -1, 17361, 17369, 17189, -1, 17107, 16222, 16221, -1, 17107, 16221, 17329, -1, 17111, 17329, 17332, -1, 17111, 17107, 17329, -1, 17114, 17332, 17334, -1, 17114, 17111, 17332, -1, 17112, 17334, 17333, -1, 17112, 17114, 17334, -1, 17115, 17333, 17331, -1, 17115, 17112, 17333, -1, 17108, 17331, 17330, -1, 17108, 17115, 17331, -1, 17105, 17330, 17328, -1, 17105, 17108, 17330, -1, 25516, 25490, 17176, -1, 25516, 17176, 17181, -1, 25517, 17181, 17180, -1, 25517, 25516, 17181, -1, 25518, 17180, 17183, -1, 25518, 25517, 17180, -1, 25519, 17183, 17184, -1, 25519, 25518, 17183, -1, 25520, 17184, 17182, -1, 25520, 25519, 17184, -1, 25521, 17182, 17178, -1, 25521, 25520, 17182, -1, 24753, 17178, 17175, -1, 24753, 25521, 17178, -1, 17116, 17118, 25477, -1, 17116, 25477, 25483, -1, 17117, 25483, 25482, -1, 17117, 17116, 25483, -1, 17119, 25482, 25481, -1, 17119, 17117, 25482, -1, 17120, 25481, 25480, -1, 17120, 17119, 25481, -1, 17121, 25480, 25479, -1, 17121, 17120, 25480, -1, 17122, 25479, 25478, -1, 17122, 17121, 25479, -1, 17123, 25478, 24298, -1, 17123, 17122, 25478, -1, 17159, 25505, 17161, -1, 25509, 25505, 17159, -1, 17161, 25504, 17164, -1, 25505, 25504, 17161, -1, 17164, 25503, 17166, -1, 25504, 25503, 17164, -1, 17166, 25502, 17167, -1, 25503, 25502, 17166, -1, 17167, 25501, 17169, -1, 25502, 25501, 17167, -1, 17169, 25500, 17171, -1, 25501, 25500, 17169, -1, 17171, 25314, 17173, -1, 25500, 25314, 17171, -1, 25509, 17159, 25510, -1, 25510, 17152, 25511, -1, 17159, 17152, 25510, -1, 25511, 17151, 25512, -1, 17152, 17151, 25511, -1, 25512, 17199, 25513, -1, 17151, 17199, 25512, -1, 25513, 17198, 25515, -1, 17199, 17198, 25513, -1, 25515, 17200, 25497, -1, 17198, 17200, 25515, -1, 25497, 17156, 25496, -1, 17200, 17156, 25497, -1, 17156, 17155, 25496, -1, 25484, 17124, 25485, -1, 25485, 17126, 25464, -1, 17124, 17126, 25485, -1, 25464, 17113, 25465, -1, 17126, 17113, 25464, -1, 25465, 17110, 25466, -1, 17113, 17110, 25465, -1, 25466, 17109, 25468, -1, 17110, 17109, 25466, -1, 25468, 17106, 25469, -1, 17109, 17106, 25468, -1, 25469, 17104, 25470, -1, 17106, 17104, 25469, -1, 17104, 17103, 25470, -1, 25316, 25476, 17100, -1, 17100, 25476, 17096, -1, 17096, 25475, 17094, -1, 25476, 25475, 17096, -1, 17094, 25474, 17090, -1, 25475, 25474, 17094, -1, 17090, 25473, 17091, -1, 25474, 25473, 17090, -1, 17091, 25472, 17093, -1, 25473, 25472, 17091, -1, 17093, 25471, 17098, -1, 25472, 25471, 17093, -1, 17098, 25470, 17103, -1, 25471, 25470, 17098, -1, 24595, 24596, 25454, -1, 25492, 25454, 25453, -1, 25492, 24595, 25454, -1, 25493, 25453, 25452, -1, 25493, 25492, 25453, -1, 25494, 25452, 25451, -1, 25494, 25493, 25452, -1, 25495, 25451, 25450, -1, 25495, 25494, 25451, -1, 25491, 25495, 25450, -1, 17354, 17312, 17317, -1, 17358, 17354, 17317, -1, 17359, 17317, 17316, -1, 17359, 17358, 17317, -1, 17360, 17316, 17315, -1, 17360, 17359, 17316, -1, 17356, 17315, 17318, -1, 17356, 17360, 17315, -1, 15966, 17318, 15965, -1, 15966, 17356, 17318, -1, 17141, 17348, 17163, -1, 17142, 17348, 17141, -1, 17163, 17346, 17160, -1, 17348, 17346, 17163, -1, 17160, 17344, 17157, -1, 17346, 17344, 17160, -1, 17157, 17345, 17158, -1, 17344, 17345, 17157, -1, 17158, 17347, 17162, -1, 17345, 17347, 17158, -1, 17162, 17349, 17165, -1, 17347, 17349, 17162, -1, 17165, 17353, 17168, -1, 17349, 17353, 17165, -1, 17362, 17193, 17364, -1, 17364, 17194, 17366, -1, 17193, 17194, 17364, -1, 17366, 17179, 17365, -1, 17194, 17179, 17366, -1, 17365, 17177, 17363, -1, 17179, 17177, 17365, -1, 17363, 17174, 17357, -1, 17177, 17174, 17363, -1, 17357, 17172, 17355, -1, 17174, 17172, 17357, -1, 17355, 17170, 17353, -1, 17172, 17170, 17355, -1, 17170, 17168, 17353, -1, 17319, 17086, 17314, -1, 17314, 17085, 17313, -1, 17086, 17085, 17314, -1, 17313, 17131, 17307, -1, 17085, 17131, 17313, -1, 17307, 17130, 17310, -1, 17131, 17130, 17307, -1, 17310, 17129, 17311, -1, 17130, 17129, 17310, -1, 17311, 17132, 17324, -1, 17129, 17132, 17311, -1, 17324, 17084, 17325, -1, 17132, 17084, 17324, -1, 17084, 17083, 17325, -1, 17319, 17320, 17086, -1, 17086, 17320, 17088, -1, 17088, 17322, 17092, -1, 17320, 17322, 17088, -1, 17092, 17323, 17095, -1, 17322, 17323, 17092, -1, 17095, 17326, 17097, -1, 17323, 17326, 17095, -1, 17097, 17327, 17099, -1, 17326, 17327, 17097, -1, 17099, 17321, 17101, -1, 17327, 17321, 17099, -1, 17101, 17139, 17102, -1, 17321, 17139, 17101, -1, 16006, 16004, 16598, -1, 16598, 16004, 16591, -1, 16591, 16000, 16585, -1, 16004, 16000, 16591, -1, 16585, 16001, 16582, -1, 16000, 16001, 16585, -1, 16582, 16031, 16579, -1, 16001, 16031, 16582, -1, 16579, 16025, 16571, -1, 16031, 16025, 16579, -1, 16571, 16022, 16567, -1, 16025, 16022, 16571, -1, 16567, 16021, 16568, -1, 16022, 16021, 16567, -1, 16568, 16023, 16576, -1, 16021, 16023, 16568, -1, 16576, 15996, 16581, -1, 16581, 15996, 16583, -1, 16023, 15996, 16576, -1, 16583, 15990, 16587, -1, 15996, 15990, 16583, -1, 24514, 24517, 24824, -1, 24517, 24825, 24824, -1, 24517, 24516, 24825, -1, 24516, 24821, 24825, -1, 24516, 24509, 24821, -1, 24821, 24508, 24820, -1, 24509, 24508, 24821, -1, 24820, 24507, 24816, -1, 24508, 24507, 24820, -1, 24816, 24506, 24810, -1, 24507, 24506, 24816, -1, 24810, 24505, 24806, -1, 24506, 24505, 24810, -1, 24806, 24504, 24523, -1, 24505, 24504, 24806, -1, 29866, 29867, 29868, -1, 29866, 29869, 29867, -1, 29870, 29871, 29872, -1, 29873, 29874, 29875, -1, 29876, 16791, 16790, -1, 29873, 29875, 29877, -1, 29876, 29878, 16791, -1, 22132, 29879, 22133, -1, 29880, 16563, 16562, -1, 29881, 29882, 22139, -1, 29880, 16562, 29883, -1, 29880, 29884, 29885, -1, 29880, 29883, 29884, -1, 29886, 29879, 22132, -1, 29887, 29888, 29889, -1, 29890, 29891, 29892, -1, 29887, 29889, 29870, -1, 29890, 29893, 29891, -1, 29894, 29868, 29878, -1, 29894, 16788, 16786, -1, 29895, 29872, 29882, -1, 29894, 16790, 16788, -1, 29894, 29878, 29876, -1, 29894, 29876, 16790, -1, 29895, 29882, 29881, -1, 29896, 29897, 29888, -1, 29898, 29892, 29869, -1, 29896, 29888, 29887, -1, 29898, 29869, 29866, -1, 29899, 16565, 16566, -1, 29899, 16566, 29874, -1, 29899, 29874, 29873, -1, 29900, 29893, 29890, -1, 29900, 29901, 29893, -1, 29902, 29877, 29897, -1, 29903, 16786, 16785, -1, 29902, 29897, 29896, -1, 29903, 29866, 29868, -1, 29903, 29868, 29894, -1, 29903, 29894, 16786, -1, 29904, 29870, 29872, -1, 29904, 29872, 29895, -1, 29905, 29890, 29892, -1, 29905, 29892, 29898, -1, 29884, 29877, 29902, -1, 29884, 29873, 29877, -1, 29906, 29901, 29900, -1, 29906, 29885, 29901, -1, 29907, 16789, 16792, -1, 29907, 29900, 29890, -1, 29907, 29890, 29905, -1, 29891, 29870, 29904, -1, 29908, 16784, 16787, -1, 29891, 29887, 29870, -1, 29908, 16785, 16784, -1, 29908, 29903, 16785, -1, 29908, 29898, 29866, -1, 29908, 29866, 29903, -1, 29909, 16793, 16564, -1, 29909, 16564, 16563, -1, 29909, 16563, 29880, -1, 29909, 29880, 29885, -1, 29909, 29885, 29906, -1, 29910, 16792, 16793, -1, 29911, 22139, 22086, -1, 29910, 29907, 16792, -1, 29911, 29881, 22139, -1, 29910, 16793, 29909, -1, 29910, 29906, 29900, -1, 29910, 29900, 29907, -1, 29910, 29909, 29906, -1, 29912, 16787, 16789, -1, 29912, 29908, 16787, -1, 29912, 29907, 29905, -1, 29912, 16789, 29907, -1, 29912, 29905, 29898, -1, 29893, 29887, 29891, -1, 29912, 29898, 29908, -1, 29893, 29896, 29887, -1, 29883, 29873, 29884, -1, 29883, 16562, 16565, -1, 29883, 16565, 29899, -1, 29883, 29899, 29873, -1, 29867, 29881, 29911, -1, 29867, 29895, 29881, -1, 29901, 29896, 29893, -1, 29913, 22136, 22140, -1, 29913, 22132, 22136, -1, 29901, 29902, 29896, -1, 29871, 29886, 22132, -1, 29871, 22132, 29913, -1, 29878, 22086, 16791, -1, 29878, 29911, 22086, -1, 29869, 29895, 29867, -1, 29889, 29886, 29871, -1, 29882, 22140, 22139, -1, 29869, 29904, 29895, -1, 29882, 29913, 22140, -1, 29888, 29914, 29886, -1, 29868, 29911, 29878, -1, 29868, 29867, 29911, -1, 29888, 29886, 29889, -1, 29885, 29884, 29902, -1, 29885, 29902, 29901, -1, 29872, 29871, 29913, -1, 29872, 29913, 29882, -1, 29897, 29915, 29914, -1, 29897, 29914, 29888, -1, 29892, 29904, 29869, -1, 29877, 29875, 29915, -1, 29892, 29891, 29904, -1, 29877, 29915, 29897, -1, 29870, 29889, 29871, -1, 22143, 22133, 29879, -1, 29916, 29879, 29886, -1, 29916, 22143, 29879, -1, 29917, 29886, 29914, -1, 29917, 29916, 29886, -1, 29918, 29914, 29915, -1, 29918, 29917, 29914, -1, 29919, 29915, 29875, -1, 29919, 29918, 29915, -1, 10412, 29874, 16566, -1, 29920, 29875, 29874, -1, 29920, 29919, 29875, -1, 29921, 29920, 29874, -1, 29922, 29874, 10412, -1, 29922, 29921, 29874, -1, 10379, 29922, 10412, -1, 15064, 29922, 10379, -1, 29923, 22143, 29916, -1, 29923, 22141, 22143, -1, 29924, 29916, 29917, -1, 29924, 29923, 29916, -1, 29925, 29917, 29918, -1, 29925, 29924, 29917, -1, 29926, 29918, 29919, -1, 29926, 29925, 29918, -1, 8819, 29922, 15064, -1, 29927, 29919, 29920, -1, 29927, 29926, 29919, -1, 29928, 29920, 29921, -1, 29928, 29921, 29922, -1, 29928, 29927, 29920, -1, 8818, 29928, 29922, -1, 8818, 29922, 8819, -1, 29929, 29930, 29931, -1, 29929, 29932, 29933, -1, 29929, 29934, 29930, -1, 29929, 29933, 29934, -1, 29935, 29936, 29937, -1, 29935, 29937, 29938, -1, 8811, 29928, 8818, -1, 29939, 29931, 29940, -1, 29939, 29941, 29932, -1, 29939, 29929, 29931, -1, 29939, 29932, 29929, -1, 29942, 22153, 22151, -1, 29942, 29943, 29936, -1, 29942, 22151, 29943, -1, 29942, 29936, 29935, -1, 29944, 29940, 29945, -1, 29944, 29939, 29940, -1, 29944, 29941, 29939, -1, 29944, 29938, 29941, -1, 29946, 29945, 29947, -1, 29946, 29935, 29938, -1, 29946, 29944, 29945, -1, 29946, 29938, 29944, -1, 29948, 29949, 22155, -1, 29948, 29947, 29949, -1, 29948, 22155, 22153, -1, 29948, 22153, 29942, -1, 22149, 22141, 29923, -1, 29948, 29942, 29935, -1, 29948, 29946, 29947, -1, 29948, 29935, 29946, -1, 29930, 8810, 8812, -1, 29950, 29928, 8811, -1, 29951, 29927, 29928, -1, 29951, 29928, 29950, -1, 29952, 29926, 29927, -1, 29952, 29927, 29951, -1, 29933, 8811, 8813, -1, 29933, 29950, 8811, -1, 29937, 29925, 29926, -1, 29937, 29926, 29952, -1, 29932, 29950, 29933, -1, 29932, 29951, 29950, -1, 29936, 29924, 29925, -1, 29936, 29925, 29937, -1, 29941, 29952, 29951, -1, 29941, 29951, 29932, -1, 29943, 29923, 29924, -1, 29943, 22151, 22149, -1, 29943, 22149, 29923, -1, 29943, 29924, 29936, -1, 29934, 8813, 8810, -1, 29934, 29933, 8813, -1, 29934, 8810, 29930, -1, 29938, 29952, 29941, -1, 29938, 29937, 29952, -1, 22156, 22155, 29949, -1, 29953, 29949, 29947, -1, 29953, 22156, 29949, -1, 29954, 29947, 29945, -1, 29954, 29953, 29947, -1, 29955, 29945, 29940, -1, 29955, 29954, 29945, -1, 29956, 29940, 29931, -1, 29956, 29955, 29940, -1, 29957, 29931, 29930, -1, 29957, 29956, 29931, -1, 29958, 29957, 29930, -1, 8802, 29930, 8812, -1, 8802, 29958, 29930, -1, 29959, 29960, 29961, -1, 29962, 29953, 29954, -1, 29962, 29963, 29964, -1, 29962, 29964, 29965, -1, 29962, 29965, 29953, -1, 29966, 29967, 29960, -1, 29966, 29960, 29959, -1, 29968, 29954, 29955, -1, 29968, 29962, 29954, -1, 29968, 29969, 29963, -1, 29968, 29963, 29962, -1, 29970, 8797, 8795, -1, 29970, 8795, 29971, -1, 29970, 29971, 29967, -1, 29970, 29967, 29966, -1, 29972, 29955, 29956, -1, 29972, 29959, 29969, -1, 29972, 29968, 29955, -1, 29972, 29969, 29968, -1, 29973, 29956, 29957, -1, 29973, 29966, 29959, -1, 29973, 29972, 29956, -1, 29973, 29959, 29972, -1, 29974, 29957, 29958, -1, 29974, 8799, 8797, -1, 29974, 8797, 29970, -1, 29974, 29958, 8799, -1, 29974, 29973, 29957, -1, 29974, 29970, 29966, -1, 29974, 29966, 29973, -1, 8802, 8799, 29958, -1, 29975, 29976, 22159, -1, 29975, 22159, 22158, -1, 29977, 29978, 29976, -1, 29977, 29976, 29975, -1, 29961, 29979, 29978, -1, 29961, 29978, 29977, -1, 29964, 22158, 22162, -1, 29964, 29975, 22158, -1, 29960, 29980, 29979, -1, 29960, 29979, 29961, -1, 29963, 29977, 29975, -1, 29963, 29975, 29964, -1, 29967, 29981, 29980, -1, 29967, 29980, 29960, -1, 29969, 29977, 29963, -1, 29969, 29961, 29977, -1, 29965, 22156, 29953, -1, 29965, 22164, 22156, -1, 29965, 22162, 22164, -1, 29965, 29964, 22162, -1, 29971, 8795, 8791, -1, 29971, 29982, 29981, -1, 29971, 8791, 29982, -1, 29971, 29981, 29967, -1, 29959, 29961, 29969, -1, 29983, 22159, 29976, -1, 29983, 22167, 22159, -1, 29984, 29976, 29978, -1, 29984, 29983, 29976, -1, 29985, 29978, 29979, -1, 29985, 29979, 29980, -1, 29985, 29984, 29978, -1, 29986, 29980, 29981, -1, 29986, 29985, 29980, -1, 29987, 29981, 29982, -1, 29987, 29986, 29981, -1, 29988, 29982, 8791, -1, 29988, 29987, 29982, -1, 8569, 29988, 8791, -1, 29989, 29983, 29984, -1, 29989, 29990, 29983, -1, 29989, 29991, 29992, -1, 29989, 29992, 29990, -1, 29993, 29994, 29995, -1, 27262, 29996, 27263, -1, 29993, 29995, 29997, -1, 29998, 29984, 29985, -1, 29998, 29989, 29984, -1, 29998, 29999, 29991, -1, 29998, 29991, 29989, -1, 30000, 8563, 8558, -1, 30000, 29994, 29993, -1, 30000, 8558, 30001, -1, 30000, 30001, 29994, -1, 30002, 29985, 29986, -1, 30002, 29999, 29998, -1, 30002, 29997, 29999, -1, 30002, 29998, 29985, -1, 30003, 29986, 29987, -1, 30003, 29993, 29997, -1, 30003, 30002, 29986, -1, 30003, 29997, 30002, -1, 30004, 29987, 29988, -1, 30004, 8565, 8563, -1, 30004, 29988, 8565, -1, 30004, 8563, 30000, -1, 30004, 30000, 29993, -1, 30004, 30003, 29987, -1, 30004, 29993, 30003, -1, 8569, 8565, 29988, -1, 30005, 30006, 29996, -1, 30005, 29996, 27262, -1, 30007, 30008, 30006, -1, 30007, 30006, 30005, -1, 30009, 30010, 30008, -1, 30009, 30008, 30007, -1, 29992, 27262, 27266, -1, 29992, 30005, 27262, -1, 29995, 30011, 30010, -1, 29995, 30010, 30009, -1, 29991, 30007, 30005, -1, 29991, 30005, 29992, -1, 29994, 30012, 30011, -1, 29994, 30011, 29995, -1, 29999, 30009, 30007, -1, 29999, 30007, 29991, -1, 29990, 22167, 29983, -1, 29990, 27268, 22167, -1, 29990, 27266, 27268, -1, 29990, 29992, 27266, -1, 30001, 8558, 8549, -1, 30001, 8549, 30012, -1, 30001, 30012, 29994, -1, 29997, 29995, 30009, -1, 29997, 30009, 29999, -1, 8549, 8554, 30013, -1, 30012, 30013, 30014, -1, 30012, 8549, 30013, -1, 30011, 30014, 30015, -1, 30011, 30012, 30014, -1, 30010, 30015, 30016, -1, 30010, 30011, 30015, -1, 30008, 30016, 30017, -1, 30008, 30010, 30016, -1, 30006, 30017, 30018, -1, 30006, 30008, 30017, -1, 29996, 30018, 27270, -1, 29996, 30006, 30018, -1, 27263, 29996, 27270, -1, 30019, 30020, 30021, -1, 30019, 30022, 30023, -1, 30019, 30024, 30020, -1, 30019, 30023, 30024, -1, 30025, 30026, 30027, -1, 30025, 30027, 30028, -1, 30029, 30021, 30030, -1, 30029, 30031, 30022, -1, 30029, 30022, 30019, -1, 30029, 30019, 30021, -1, 30032, 27275, 27272, -1, 30032, 27276, 27275, -1, 30032, 30033, 30026, -1, 30032, 30026, 30025, -1, 30032, 27272, 30033, -1, 30034, 30030, 30035, -1, 30034, 30031, 30029, -1, 30034, 30028, 30031, -1, 30034, 30029, 30030, -1, 30036, 30035, 30037, -1, 30036, 30025, 30028, -1, 30036, 30034, 30035, -1, 30036, 30028, 30034, -1, 30038, 30039, 27279, -1, 27272, 27270, 30018, -1, 30038, 30037, 30039, -1, 30038, 27279, 27276, -1, 30038, 27276, 30032, -1, 30038, 30036, 30037, -1, 30038, 30032, 30025, -1, 30038, 30025, 30036, -1, 30020, 8543, 8545, -1, 30040, 30013, 8554, -1, 30040, 8554, 8544, -1, 30041, 30014, 30013, -1, 30041, 30013, 30040, -1, 30042, 30015, 30014, -1, 30042, 30014, 30041, -1, 30023, 8544, 8546, -1, 30023, 30040, 8544, -1, 30027, 30016, 30015, -1, 30027, 30015, 30042, -1, 30022, 30040, 30023, -1, 30022, 30041, 30040, -1, 30026, 30017, 30016, -1, 30026, 30016, 30027, -1, 30031, 30042, 30041, -1, 30031, 30041, 30022, -1, 30033, 30018, 30017, -1, 30033, 27272, 30018, -1, 30033, 30017, 30026, -1, 30024, 8546, 8543, -1, 30024, 30023, 8546, -1, 30024, 8543, 30020, -1, 30028, 30027, 30042, -1, 30028, 30042, 30031, -1, 30043, 8528, 15140, -1, 8545, 8528, 30043, -1, 30020, 30044, 30045, -1, 30020, 30043, 30044, -1, 30020, 8545, 30043, -1, 30021, 30045, 30046, -1, 30021, 30020, 30045, -1, 30030, 30046, 30047, -1, 30030, 30021, 30046, -1, 30035, 30047, 30048, -1, 30035, 30030, 30047, -1, 30037, 30048, 30049, -1, 30037, 30035, 30048, -1, 30039, 30049, 27281, -1, 30039, 30037, 30049, -1, 27279, 30039, 27281, -1, 30050, 12360, 24803, -1, 30043, 15140, 12355, -1, 30043, 12355, 12360, -1, 30043, 12360, 30050, -1, 30044, 30043, 30050, -1, 30045, 30050, 30051, -1, 30045, 30044, 30050, -1, 30046, 30051, 30052, -1, 30046, 30045, 30051, -1, 30047, 30052, 30053, -1, 30047, 30046, 30052, -1, 30048, 30053, 30054, -1, 30048, 30047, 30053, -1, 30049, 30054, 30055, -1, 30049, 30048, 30054, -1, 27281, 30055, 27286, -1, 27281, 30049, 30055, -1, 30056, 30057, 30058, -1, 30059, 24799, 30060, -1, 30056, 30058, 25000, -1, 30056, 30061, 30057, -1, 30059, 30062, 24799, -1, 30063, 30064, 30065, -1, 30066, 30054, 30053, -1, 24802, 30050, 24803, -1, 30066, 30053, 30067, -1, 30063, 30065, 30068, -1, 30051, 30050, 24802, -1, 30069, 30070, 30062, -1, 30071, 30068, 30061, -1, 30071, 30061, 30056, -1, 30069, 30062, 30059, -1, 30072, 30073, 30074, -1, 30075, 30055, 30054, -1, 30072, 30074, 30064, -1, 30075, 30054, 30066, -1, 30076, 30056, 25000, -1, 30076, 25000, 24999, -1, 30077, 30078, 30073, -1, 30079, 30070, 30069, -1, 30079, 30080, 30070, -1, 30077, 30073, 30072, -1, 30081, 27286, 30055, -1, 30081, 27615, 27286, -1, 30081, 27599, 27615, -1, 30082, 24999, 24998, -1, 30081, 30055, 30075, -1, 30082, 30071, 30056, -1, 30082, 30076, 24999, -1, 30082, 30056, 30076, -1, 30083, 30084, 30080, -1, 30085, 30063, 30068, -1, 30085, 30068, 30071, -1, 30083, 30080, 30079, -1, 30086, 24801, 24800, -1, 30086, 24800, 25003, -1, 30086, 30060, 24801, -1, 30087, 30064, 30063, -1, 30087, 30072, 30064, -1, 30088, 27587, 30089, -1, 30088, 30089, 30078, -1, 30090, 30059, 30060, -1, 30088, 30078, 30077, -1, 30091, 30072, 30087, -1, 30090, 30060, 30086, -1, 30091, 30077, 30072, -1, 30074, 30067, 30084, -1, 30074, 30084, 30083, -1, 30092, 30085, 30071, -1, 30092, 30071, 30082, -1, 30093, 25003, 25002, -1, 30093, 30086, 25003, -1, 30093, 30090, 30086, -1, 30094, 30063, 30085, -1, 30073, 30066, 30067, -1, 30094, 30087, 30063, -1, 30073, 30067, 30074, -1, 30095, 27588, 27587, -1, 30095, 27587, 30088, -1, 30095, 30088, 30077, -1, 30095, 30077, 30091, -1, 30096, 30082, 24998, -1, 30097, 30069, 30059, -1, 30096, 24994, 24993, -1, 30097, 30059, 30090, -1, 30096, 24998, 24994, -1, 30096, 30092, 30082, -1, 30098, 30091, 30087, -1, 30099, 30069, 30097, -1, 30098, 30087, 30094, -1, 30100, 30094, 30085, -1, 30100, 30085, 30092, -1, 30099, 30079, 30069, -1, 30078, 30066, 30073, -1, 30078, 30075, 30066, -1, 30101, 27588, 30095, -1, 30101, 30091, 30098, -1, 30101, 30095, 30091, -1, 30057, 30090, 30093, -1, 30102, 24802, 24799, -1, 30103, 30098, 30094, -1, 30103, 30094, 30100, -1, 30057, 30097, 30090, -1, 30104, 24993, 24992, -1, 30104, 30096, 24993, -1, 30065, 30079, 30099, -1, 30062, 24802, 30102, -1, 30104, 30092, 30096, -1, 30104, 30100, 30092, -1, 30062, 30102, 24799, -1, 30105, 24991, 24990, -1, 30105, 24992, 24991, -1, 30105, 30104, 24992, -1, 30065, 30083, 30079, -1, 30105, 30103, 30100, -1, 30105, 30100, 30104, -1, 30089, 30075, 30078, -1, 30070, 30051, 24802, -1, 30089, 27587, 27599, -1, 30106, 24989, 27588, -1, 30089, 27599, 30081, -1, 30089, 30081, 30075, -1, 30070, 24802, 30062, -1, 30106, 30098, 30103, -1, 30106, 27588, 30101, -1, 30106, 30101, 30098, -1, 30080, 30052, 30051, -1, 30107, 30106, 30103, -1, 30107, 24990, 24989, -1, 30061, 30097, 30057, -1, 30080, 30051, 30070, -1, 30107, 30105, 24990, -1, 30107, 24989, 30106, -1, 30107, 30103, 30105, -1, 30061, 30099, 30097, -1, 30058, 30057, 30093, -1, 30084, 30053, 30052, -1, 30058, 25001, 25000, -1, 30084, 30052, 30080, -1, 30058, 25002, 25001, -1, 30058, 30093, 25002, -1, 30060, 24799, 24801, -1, 30068, 30099, 30061, -1, 30068, 30065, 30099, -1, 30064, 30074, 30083, -1, 30064, 30083, 30065, -1, 30067, 30053, 30084, -1, 23887, 23875, 23872, -1, 23885, 23875, 23887, -1, 23883, 23875, 23885, -1, 23881, 23875, 23883, -1, 23879, 23875, 23881, -1, 23877, 23875, 23879, -1, 23875, 23888, 23872, -1, 23896, 23894, 23888, -1, 23891, 23890, 23894, -1, 23894, 23890, 23888, -1, 23890, 23897, 23888, -1, 23899, 23901, 23897, -1, 23901, 23903, 23897, -1, 23888, 23905, 23872, -1, 23897, 23905, 23888, -1, 23903, 23905, 23897, -1, 23873, 29178, 29176, -1, 29178, 29182, 29180, -1, 23873, 29182, 29178, -1, 29182, 29186, 29184, -1, 29182, 29175, 29186, -1, 23873, 29175, 29182, -1, 23872, 23907, 23873, -1, 23905, 23907, 23872, -1, 23907, 29170, 23873, -1, 23873, 29170, 29175, -1, 29162, 29164, 29160, -1, 29160, 29164, 29158, -1, 29158, 29164, 23907, -1, 29164, 29166, 23907, -1, 29170, 29166, 29168, -1, 29168, 29166, 29171, -1, 29171, 29166, 29173, -1, 23907, 29166, 29170, -1, 28434, 28430, 28432, -1, 28426, 28422, 28424, -1, 28418, 28414, 28416, -1, 28420, 28414, 28418, -1, 28422, 28414, 28420, -1, 28428, 28414, 28426, -1, 28430, 28414, 28428, -1, 28436, 28414, 28434, -1, 28438, 28414, 28436, -1, 28440, 28414, 28438, -1, 28434, 28414, 28430, -1, 28426, 28414, 28422, -1, 28405, 28406, 28404, -1, 28401, 28413, 28400, -1, 28402, 28413, 28401, -1, 28403, 28413, 28402, -1, 28404, 28413, 28403, -1, 28400, 28413, 28440, -1, 28440, 28413, 28414, -1, 28406, 28413, 28404, -1, 28406, 28407, 28413, -1, 28407, 28408, 28413, -1, 28413, 28411, 28412, -1, 28408, 28409, 28413, -1, 28413, 28410, 28411, -1, 28409, 28410, 28413, -1, 28078, 28074, 28076, -1, 28080, 28074, 28078, -1, 28082, 28074, 28080, -1, 28084, 28074, 28082, -1, 28086, 28074, 28084, -1, 28088, 28074, 28086, -1, 28090, 28074, 28088, -1, 28092, 28074, 28090, -1, 28094, 28074, 28092, -1, 28096, 28074, 28094, -1, 28098, 28074, 28096, -1, 28100, 28074, 28098, -1, 28061, 28073, 28060, -1, 28062, 28073, 28061, -1, 28063, 28073, 28062, -1, 28064, 28073, 28063, -1, 28065, 28073, 28064, -1, 28066, 28073, 28065, -1, 28060, 28073, 28100, -1, 28100, 28073, 28074, -1, 28066, 28067, 28073, -1, 28067, 28068, 28073, -1, 28073, 28071, 28072, -1, 28068, 28069, 28073, -1, 28073, 28070, 28071, -1, 28069, 28070, 28073, -1, 23013, 22988, 23011, -1, 23011, 22988, 23009, -1, 23009, 22988, 23007, -1, 23007, 22988, 23005, -1, 23005, 23001, 23003, -1, 22988, 23001, 23005, -1, 22988, 22999, 23001, -1, 22988, 22997, 22999, -1, 22997, 22993, 22995, -1, 22988, 22993, 22997, -1, 22988, 22991, 22993, -1, 22973, 22989, 22988, -1, 22988, 22989, 22991, -1, 22974, 22975, 22973, -1, 22975, 22976, 22973, -1, 22976, 22977, 22973, -1, 22977, 22978, 22973, -1, 22978, 22979, 22973, -1, 22973, 22986, 22989, -1, 22979, 22980, 22973, -1, 22973, 22985, 22986, -1, 22980, 22981, 22973, -1, 22973, 22984, 22985, -1, 22981, 22982, 22973, -1, 22973, 22982, 22984, -1, 22982, 22983, 22984, -1, 22661, 22663, 22659, -1, 22665, 22640, 22663, -1, 22657, 22651, 22655, -1, 22655, 22651, 22653, -1, 22659, 22650, 22657, -1, 22657, 22650, 22651, -1, 22650, 22646, 22648, -1, 22663, 22646, 22659, -1, 22640, 22646, 22663, -1, 22659, 22646, 22650, -1, 22640, 22643, 22646, -1, 22626, 22627, 22625, -1, 22640, 22641, 22643, -1, 22625, 22638, 22640, -1, 22640, 22638, 22641, -1, 22631, 22632, 22630, -1, 22627, 22637, 22625, -1, 22625, 22637, 22638, -1, 22632, 22633, 22630, -1, 22627, 22636, 22637, -1, 22630, 22634, 22629, -1, 22629, 22634, 22628, -1, 22628, 22634, 22627, -1, 22627, 22634, 22636, -1, 22633, 22634, 22630, -1, 22634, 22635, 22636, -1, 30108, 30109, 30110, -1, 30108, 30110, 30111, -1, 30112, 30108, 30111, -1, 2349, 30111, 3050, -1, 2349, 30112, 30111, -1, 2349, 30113, 30112, -1, 30114, 30112, 30113, -1, 30115, 30116, 30117, -1, 30118, 30119, 30115, -1, 30118, 30117, 30114, -1, 30118, 30115, 30117, -1, 30113, 30118, 30114, -1, 30120, 30121, 30122, -1, 30123, 30121, 30120, -1, 2481, 3108, 30121, -1, 30124, 30125, 2481, -1, 30124, 30121, 30123, -1, 30124, 2481, 30121, -1, 30126, 30125, 30124, -1, 30127, 30128, 30126, -1, 30129, 30127, 30130, -1, 30129, 30128, 30127, -1, 30131, 30128, 30129, -1, 30128, 30125, 30126, -1, 30132, 3064, 30133, -1, 30132, 30133, 30134, -1, 30132, 30134, 30135, -1, 30136, 30137, 30138, -1, 30136, 30138, 30139, -1, 3205, 30137, 30136, -1, 3205, 3064, 30137, -1, 30137, 3064, 30132, -1, 30140, 30141, 30142, -1, 30143, 3204, 30141, -1, 30143, 30141, 30140, -1, 30144, 30145, 30146, -1, 30147, 30145, 30144, -1, 3203, 30145, 30147, -1, 3203, 3204, 30143, -1, 3203, 30143, 30145, -1, 30148, 3202, 30149, -1, 30148, 30150, 30151, -1, 30148, 30149, 30150, -1, 30152, 30153, 30154, -1, 30152, 30155, 30153, -1, 3201, 30155, 30152, -1, 3201, 3202, 30148, -1, 3201, 30148, 30155, -1, 30156, 30157, 30158, -1, 30159, 3200, 30157, -1, 30159, 30157, 30156, -1, 30160, 30161, 30162, -1, 30163, 30161, 30160, -1, 3144, 30161, 30163, -1, 3144, 3200, 30159, -1, 3144, 30159, 30161, -1, 10529, 10530, 30164, -1, 10529, 30164, 30165, -1, 30166, 10124, 10125, -1, 10135, 30167, 10134, -1, 30168, 10125, 10126, -1, 30168, 30166, 10125, -1, 30169, 10123, 10124, -1, 10528, 10529, 30165, -1, 30169, 10124, 30166, -1, 30170, 10126, 10127, -1, 10528, 30165, 30171, -1, 10523, 30167, 10135, -1, 30170, 30168, 10126, -1, 10523, 30172, 30167, -1, 30173, 10122, 10123, -1, 10527, 30171, 30174, -1, 10527, 10528, 30171, -1, 30173, 10123, 30169, -1, 10524, 30172, 10523, -1, 10524, 30175, 30172, -1, 30176, 10127, 10128, -1, 30176, 30170, 10127, -1, 10526, 10527, 30174, -1, 10526, 30174, 30177, -1, 10525, 30177, 30175, -1, 10525, 30175, 10524, -1, 10525, 10526, 30177, -1, 30178, 10122, 30173, -1, 30179, 10128, 10129, -1, 30179, 30176, 10128, -1, 30180, 10534, 10122, -1, 30180, 10122, 30178, -1, 30181, 10129, 10130, -1, 30181, 30179, 10129, -1, 30182, 10533, 10534, -1, 30182, 10534, 30180, -1, 30183, 10130, 10131, -1, 30183, 30181, 10130, -1, 30184, 10533, 30182, -1, 10532, 10533, 30184, -1, 30185, 30183, 10131, -1, 10132, 30185, 10131, -1, 30186, 10532, 30184, -1, 10531, 10532, 30186, -1, 30187, 30185, 10132, -1, 30188, 10531, 30186, -1, 10133, 30187, 10132, -1, 30189, 30187, 10133, -1, 10530, 10531, 30188, -1, 30164, 10530, 30188, -1, 10134, 30189, 10133, -1, 10134, 30167, 30189, -1, 30190, 30191, 30167, -1, 30167, 30191, 30189, -1, 30189, 30192, 30187, -1, 30191, 30192, 30189, -1, 30187, 30193, 30185, -1, 30192, 30193, 30187, -1, 30185, 30194, 30183, -1, 30193, 30194, 30185, -1, 30183, 30195, 30181, -1, 30194, 30195, 30183, -1, 30181, 30196, 30179, -1, 30195, 30196, 30181, -1, 30179, 30197, 30176, -1, 30196, 30197, 30179, -1, 30176, 30198, 30170, -1, 30197, 30198, 30176, -1, 30170, 30199, 30168, -1, 30198, 30199, 30170, -1, 30168, 30200, 30166, -1, 30199, 30200, 30168, -1, 30166, 30201, 30169, -1, 30200, 30201, 30166, -1, 30173, 30202, 30178, -1, 30169, 30202, 30173, -1, 30201, 30202, 30169, -1, 30202, 30203, 30178, -1, 9579, 10367, 30204, -1, 30205, 9587, 9579, -1, 30204, 30205, 9579, -1, 30206, 10553, 10552, -1, 30206, 10554, 10553, -1, 10551, 30206, 10552, -1, 10550, 30206, 10551, -1, 10549, 30206, 10550, -1, 30206, 10555, 10554, -1, 10547, 30206, 10548, -1, 10548, 30206, 10549, -1, 12213, 30207, 12212, -1, 12213, 30208, 30207, -1, 30209, 12203, 12204, -1, 12914, 12915, 30210, -1, 12914, 30210, 30211, -1, 30212, 12204, 12205, -1, 30212, 30209, 12204, -1, 30213, 12202, 12203, -1, 12214, 30208, 12213, -1, 30213, 12203, 30209, -1, 30214, 12205, 12206, -1, 30214, 30212, 12205, -1, 30215, 12201, 12202, -1, 12913, 30211, 30216, -1, 30215, 12202, 30213, -1, 30217, 12206, 12207, -1, 12913, 12914, 30211, -1, 12908, 30208, 12214, -1, 30217, 30214, 12206, -1, 12908, 30218, 30208, -1, 12912, 12913, 30216, -1, 30219, 12201, 30215, -1, 12912, 30216, 30220, -1, 12909, 30218, 12908, -1, 30221, 12207, 12208, -1, 12909, 30222, 30218, -1, 30221, 30217, 12207, -1, 12911, 30220, 30223, -1, 12911, 12912, 30220, -1, 30224, 12919, 12201, -1, 12910, 30223, 30222, -1, 12910, 12911, 30223, -1, 12910, 30222, 12909, -1, 30224, 12201, 30219, -1, 30225, 12208, 12209, -1, 30225, 30221, 12208, -1, 30226, 12918, 12919, -1, 30226, 12919, 30224, -1, 30227, 12209, 12210, -1, 30227, 30225, 12209, -1, 30228, 12918, 30226, -1, 12917, 12918, 30228, -1, 30229, 30227, 12210, -1, 12211, 30229, 12210, -1, 30230, 12917, 30228, -1, 12916, 12917, 30230, -1, 30231, 30229, 12211, -1, 30232, 12916, 30230, -1, 12212, 30231, 12211, -1, 30207, 30231, 12212, -1, 12915, 12916, 30232, -1, 30210, 12915, 30232, -1, 30208, 30233, 30207, -1, 30233, 30234, 30207, -1, 30207, 30235, 30231, -1, 30234, 30235, 30207, -1, 30231, 30236, 30229, -1, 30235, 30236, 30231, -1, 30229, 30237, 30227, -1, 30236, 30237, 30229, -1, 30227, 30238, 30225, -1, 30237, 30238, 30227, -1, 30225, 30239, 30221, -1, 30238, 30239, 30225, -1, 30221, 30240, 30217, -1, 30239, 30240, 30221, -1, 30217, 30241, 30214, -1, 30240, 30241, 30217, -1, 30214, 30242, 30212, -1, 30241, 30242, 30214, -1, 30212, 30243, 30209, -1, 30242, 30243, 30212, -1, 30209, 30244, 30213, -1, 30243, 30244, 30209, -1, 30213, 30245, 30215, -1, 30244, 30245, 30213, -1, 30215, 30246, 30219, -1, 30245, 30246, 30215, -1, 11663, 11670, 30247, -1, 30248, 12427, 11663, -1, 30247, 30248, 11663, -1, 12935, 12936, 30249, -1, 12937, 30249, 12936, -1, 12934, 12935, 30249, -1, 12938, 30249, 12937, -1, 12933, 12934, 30249, -1, 12939, 30249, 12938, -1, 12932, 12933, 30249, -1, 12940, 30249, 12939, -1, 9578, 9577, 30205, -1, 30204, 8393, 9578, -1, 30205, 30204, 9578, -1, 9591, 9592, 30250, -1, 9590, 9591, 30250, -1, 9589, 9590, 30250, -1, 30250, 9588, 9589, -1, 9593, 30250, 9592, -1, 11338, 30251, 11337, -1, 11338, 30252, 30251, -1, 8365, 8366, 30253, -1, 8365, 30253, 30254, -1, 30255, 11329, 11330, -1, 8358, 30256, 30257, -1, 8358, 30257, 30252, -1, 30258, 11330, 11331, -1, 8358, 30252, 11338, -1, 30258, 30255, 11330, -1, 30259, 11328, 11329, -1, 30259, 11329, 30255, -1, 30260, 11331, 11332, -1, 30260, 30258, 11331, -1, 8364, 30254, 30261, -1, 8364, 8365, 30254, -1, 30262, 11327, 11328, -1, 30262, 11328, 30259, -1, 30263, 30260, 11332, -1, 8359, 30264, 30256, -1, 8359, 30256, 8358, -1, 11333, 30263, 11332, -1, 30265, 8371, 11327, -1, 30265, 11327, 30262, -1, 8363, 30261, 30266, -1, 8363, 8364, 30261, -1, 8360, 30267, 30264, -1, 8370, 8371, 30265, -1, 8360, 30264, 8359, -1, 8362, 30266, 30268, -1, 30269, 30263, 11333, -1, 8362, 8363, 30266, -1, 8361, 30268, 30267, -1, 30270, 8370, 30265, -1, 8361, 30267, 8360, -1, 8361, 8362, 30268, -1, 11334, 30269, 11333, -1, 30271, 30269, 11334, -1, 8369, 8370, 30270, -1, 30272, 8369, 30270, -1, 11335, 30271, 11334, -1, 30273, 30271, 11335, -1, 8368, 8369, 30272, -1, 30274, 8368, 30272, -1, 11336, 30275, 30273, -1, 11336, 30273, 11335, -1, 8367, 8368, 30274, -1, 8367, 30274, 30276, -1, 11337, 30275, 11336, -1, 11337, 30251, 30275, -1, 8366, 8367, 30276, -1, 8366, 30276, 30253, -1, 30277, 30278, 30265, -1, 30265, 30278, 30270, -1, 30270, 30279, 30272, -1, 30278, 30279, 30270, -1, 30272, 30280, 30274, -1, 30279, 30280, 30272, -1, 30274, 30281, 30276, -1, 30280, 30281, 30274, -1, 30276, 30282, 30253, -1, 30281, 30282, 30276, -1, 30253, 30283, 30254, -1, 30282, 30283, 30253, -1, 30254, 30284, 30261, -1, 30283, 30284, 30254, -1, 30261, 30285, 30266, -1, 30284, 30285, 30261, -1, 30266, 30286, 30268, -1, 30285, 30286, 30266, -1, 30268, 30287, 30267, -1, 30286, 30287, 30268, -1, 30267, 30288, 30264, -1, 30287, 30288, 30267, -1, 30264, 30289, 30256, -1, 30288, 30289, 30264, -1, 30256, 30290, 30257, -1, 30289, 30290, 30256, -1, 11376, 11377, 30291, -1, 11376, 30291, 30292, -1, 11369, 30293, 9611, -1, 11369, 30294, 30293, -1, 30295, 9595, 9594, -1, 30295, 9596, 9595, -1, 30295, 9597, 9596, -1, 30295, 9598, 9597, -1, 9599, 9598, 30295, -1, 9600, 9599, 30295, -1, 11375, 30292, 30296, -1, 11375, 11376, 30292, -1, 11370, 30294, 11369, -1, 11370, 30297, 30294, -1, 9608, 30298, 9607, -1, 11374, 30296, 30299, -1, 9606, 9607, 30298, -1, 11374, 11375, 30296, -1, 11371, 30300, 30297, -1, 11371, 30297, 11370, -1, 9609, 30298, 9608, -1, 11373, 30299, 30301, -1, 11373, 11374, 30299, -1, 9605, 9606, 30298, -1, 11372, 30301, 30300, -1, 11372, 30300, 11371, -1, 11372, 11373, 30301, -1, 30295, 30302, 9602, -1, 30295, 9602, 9601, -1, 9610, 30298, 9609, -1, 30295, 9601, 9600, -1, 30293, 30298, 9611, -1, 9611, 30298, 9610, -1, 9604, 9605, 30298, -1, 9603, 9604, 30298, -1, 30302, 11382, 9602, -1, 11381, 11382, 30302, -1, 30303, 11381, 30302, -1, 11380, 11381, 30303, -1, 30304, 11380, 30303, -1, 11379, 11380, 30304, -1, 30305, 11379, 30304, -1, 11378, 11379, 30305, -1, 11378, 30305, 30306, -1, 11377, 11378, 30306, -1, 11377, 30306, 30291, -1, 11390, 11391, 30307, -1, 11390, 30307, 30308, -1, 11383, 30309, 9620, -1, 11383, 30310, 30309, -1, 30311, 9628, 9629, -1, 30311, 9627, 9628, -1, 30311, 9626, 9627, -1, 30311, 9625, 9626, -1, 9624, 9625, 30311, -1, 9623, 9624, 30311, -1, 11389, 11390, 30308, -1, 11389, 30308, 30312, -1, 11384, 30310, 11383, -1, 11384, 30313, 30310, -1, 11388, 11389, 30312, -1, 11388, 30312, 30314, -1, 9617, 30315, 9616, -1, 11385, 30313, 11384, -1, 9615, 9616, 30315, -1, 11385, 30316, 30313, -1, 11387, 11388, 30314, -1, 11387, 30314, 30317, -1, 9618, 30315, 9617, -1, 11386, 30317, 30316, -1, 9614, 9615, 30315, -1, 11386, 30316, 11385, -1, 11386, 11387, 30317, -1, 30311, 30318, 9621, -1, 30311, 9621, 9622, -1, 30311, 9622, 9623, -1, 30309, 30315, 9620, -1, 9620, 30315, 9619, -1, 9619, 30315, 9618, -1, 9613, 9614, 30315, -1, 9612, 9613, 30315, -1, 30318, 11396, 9621, -1, 11395, 11396, 30318, -1, 30319, 11395, 30318, -1, 11394, 11395, 30319, -1, 30320, 11394, 30319, -1, 11393, 11394, 30320, -1, 30321, 11393, 30320, -1, 11392, 11393, 30321, -1, 11392, 30321, 30322, -1, 11391, 11392, 30322, -1, 11391, 30322, 30307, -1, 11660, 30247, 11661, -1, 8401, 30248, 11660, -1, 30248, 30247, 11660, -1, 30323, 11673, 11672, -1, 11674, 11673, 30323, -1, 11675, 11674, 30323, -1, 30323, 11676, 11675, -1, 11671, 30323, 11672, -1, 13718, 13719, 30324, -1, 13718, 30324, 30325, -1, 8343, 30326, 8342, -1, 8343, 30327, 30326, -1, 30328, 8333, 8334, -1, 30329, 8334, 8335, -1, 13717, 30325, 30330, -1, 13717, 13718, 30325, -1, 30329, 30328, 8334, -1, 30331, 8332, 8333, -1, 30331, 8333, 30328, -1, 30332, 8335, 8336, -1, 13712, 30333, 30327, -1, 13712, 30327, 8343, -1, 30332, 30329, 8335, -1, 13716, 30330, 30334, -1, 13716, 13717, 30330, -1, 30335, 8331, 8332, -1, 13713, 30336, 30333, -1, 30335, 8332, 30331, -1, 13713, 30333, 13712, -1, 13715, 30334, 30337, -1, 13715, 13716, 30334, -1, 30338, 30332, 8336, -1, 13714, 30337, 30336, -1, 13714, 30336, 13713, -1, 13714, 13715, 30337, -1, 8337, 30338, 8336, -1, 30339, 8330, 8331, -1, 30339, 8331, 30335, -1, 30340, 30338, 8337, -1, 30341, 13723, 8330, -1, 30341, 8330, 30339, -1, 8338, 30340, 8337, -1, 30342, 30340, 8338, -1, 13722, 13723, 30341, -1, 30343, 13722, 30341, -1, 8339, 30342, 8338, -1, 30344, 30342, 8339, -1, 13721, 13722, 30343, -1, 30345, 13721, 30343, -1, 8340, 30344, 8339, -1, 8340, 30346, 30344, -1, 13720, 13721, 30345, -1, 13720, 30345, 30347, -1, 8341, 30346, 8340, -1, 8341, 30348, 30346, -1, 13719, 13720, 30347, -1, 13719, 30347, 30324, -1, 8342, 30348, 8341, -1, 8342, 30349, 30348, -1, 30326, 30349, 8342, -1, 30350, 30351, 30326, -1, 30326, 30351, 30349, -1, 30349, 30352, 30348, -1, 30351, 30352, 30349, -1, 30348, 30353, 30346, -1, 30352, 30353, 30348, -1, 30346, 30354, 30344, -1, 30353, 30354, 30346, -1, 30344, 30355, 30342, -1, 30354, 30355, 30344, -1, 30342, 30356, 30340, -1, 30355, 30356, 30342, -1, 30340, 30357, 30338, -1, 30356, 30357, 30340, -1, 30338, 30358, 30332, -1, 30357, 30358, 30338, -1, 30332, 30359, 30329, -1, 30358, 30359, 30332, -1, 30329, 30360, 30328, -1, 30359, 30360, 30329, -1, 30328, 30361, 30331, -1, 30360, 30361, 30328, -1, 30331, 30362, 30335, -1, 30361, 30362, 30331, -1, 30335, 30363, 30339, -1, 30362, 30363, 30335, -1, 13762, 13763, 30364, -1, 13762, 30364, 30365, -1, 13755, 30366, 11685, -1, 13755, 30367, 30366, -1, 30368, 11691, 11690, -1, 30368, 11690, 11689, -1, 30368, 11689, 11688, -1, 30368, 11688, 11687, -1, 30368, 11687, 11686, -1, 13761, 13762, 30365, -1, 11692, 11691, 30368, -1, 13761, 30365, 30369, -1, 11693, 11692, 30368, -1, 13756, 30367, 13755, -1, 13756, 30370, 30367, -1, 11694, 11693, 30368, -1, 13760, 30369, 30371, -1, 13760, 13761, 30369, -1, 13757, 30372, 30370, -1, 13757, 30370, 13756, -1, 13759, 30371, 30373, -1, 13759, 13760, 30371, -1, 11680, 11681, 30374, -1, 13758, 13759, 30373, -1, 13758, 30373, 30372, -1, 11682, 30374, 11681, -1, 13758, 30372, 13757, -1, 30368, 30375, 11695, -1, 30368, 11695, 11694, -1, 30366, 30374, 11685, -1, 11685, 30374, 11684, -1, 11679, 11680, 30374, -1, 11683, 30374, 11682, -1, 11678, 11679, 30374, -1, 11684, 30374, 11683, -1, 11677, 11678, 30374, -1, 30375, 13754, 11695, -1, 13767, 13754, 30375, -1, 30376, 13767, 30375, -1, 13766, 13767, 30376, -1, 30377, 13766, 30376, -1, 13765, 13766, 30377, -1, 30378, 13765, 30377, -1, 13764, 13765, 30378, -1, 13764, 30378, 30379, -1, 13763, 13764, 30379, -1, 13763, 30379, 30364, -1, 30380, 30323, 7915, -1, 7915, 7914, 30380, -1, 30323, 11671, 7915, -1, 7914, 30381, 30380, -1, 11677, 30374, 7914, -1, 7914, 30374, 30381, -1, 30368, 7877, 30382, -1, 30368, 11686, 7877, -1, 7877, 30383, 30382, -1, 7877, 7879, 30383, -1, 7879, 11669, 30383, -1, 11661, 30247, 7879, -1, 7879, 11670, 11669, -1, 30247, 11670, 7879, -1, 30383, 11795, 30384, -1, 11669, 11795, 30383, -1, 12932, 30249, 11795, -1, 11795, 30249, 30384, -1, 30323, 30380, 7930, -1, 11676, 30323, 7930, -1, 30385, 7930, 30380, -1, 7946, 7930, 30385, -1, 30298, 8286, 9603, -1, 30386, 8286, 30298, -1, 9577, 8317, 30205, -1, 8317, 9587, 30205, -1, 8286, 30387, 8317, -1, 30386, 30387, 8286, -1, 30387, 9586, 8317, -1, 8317, 9586, 9587, -1, 30387, 9722, 9586, -1, 9722, 30206, 10547, -1, 9722, 30388, 30206, -1, 30387, 30388, 9722, -1, 8139, 30389, 7887, -1, 30315, 8139, 9612, -1, 30390, 8139, 30315, -1, 30390, 30389, 8139, -1, 2369, 2375, 30391, -1, 2369, 30391, 2566, -1, 30391, 2375, 30392, -1, 30392, 2368, 30393, -1, 2375, 2368, 30392, -1, 30219, 30246, 30224, -1, 30224, 30394, 30226, -1, 30246, 30394, 30224, -1, 30226, 30395, 30228, -1, 30394, 30395, 30226, -1, 30228, 30396, 30230, -1, 30395, 30396, 30228, -1, 30230, 30397, 30232, -1, 30396, 30397, 30230, -1, 30232, 30398, 30210, -1, 30397, 30398, 30232, -1, 30210, 30399, 30211, -1, 30398, 30399, 30210, -1, 30211, 30400, 30216, -1, 30399, 30400, 30211, -1, 30216, 30401, 30220, -1, 30400, 30401, 30216, -1, 30220, 30402, 30223, -1, 30401, 30402, 30220, -1, 30223, 30403, 30222, -1, 30402, 30403, 30223, -1, 30222, 30404, 30218, -1, 30403, 30404, 30222, -1, 30218, 30405, 30208, -1, 30404, 30405, 30218, -1, 30405, 30233, 30208, -1, 30406, 30407, 30408, -1, 30409, 30410, 30411, -1, 30409, 30411, 30412, -1, 30406, 30413, 30407, -1, 30414, 30415, 30416, -1, 30417, 30412, 30418, -1, 30419, 30420, 30421, -1, 30417, 30418, 30422, -1, 30423, 30419, 30424, -1, 30414, 30408, 30415, -1, 30425, 30426, 30427, -1, 30423, 30420, 30419, -1, 30425, 30416, 30426, -1, 30428, 30429, 30430, -1, 30431, 30432, 30433, -1, 30434, 30435, 30420, -1, 30428, 30422, 30429, -1, 30431, 30401, 30400, -1, 30436, 30437, 30438, -1, 30434, 30420, 30423, -1, 30431, 30433, 30439, -1, 30431, 30400, 30432, -1, 30440, 30441, 30442, -1, 30436, 30430, 30437, -1, 30443, 30424, 30444, -1, 30445, 30397, 30396, -1, 30445, 30446, 30447, -1, 30445, 30447, 30448, -1, 30443, 30423, 30424, -1, 30440, 30439, 30441, -1, 30445, 30396, 30446, -1, 30449, 30435, 30434, -1, 30450, 30442, 30413, -1, 30450, 30413, 30406, -1, 30451, 30448, 30410, -1, 30449, 30452, 30435, -1, 30451, 30410, 30409, -1, 30453, 30423, 30443, -1, 30454, 30406, 30408, -1, 30454, 30408, 30414, -1, 30455, 30412, 30417, -1, 30455, 30409, 30412, -1, 30453, 30434, 30423, -1, 30456, 30414, 30416, -1, 30457, 30444, 30458, -1, 30459, 30417, 30422, -1, 30459, 30422, 30428, -1, 30457, 30443, 30444, -1, 30456, 30416, 30425, -1, 30460, 30427, 30461, -1, 30460, 30461, 30462, -1, 30463, 30464, 30452, -1, 30460, 30425, 30427, -1, 30465, 30428, 30430, -1, 30465, 30430, 30436, -1, 30466, 30402, 30401, -1, 30463, 30452, 30449, -1, 30394, 30246, 30467, -1, 30466, 30401, 30431, -1, 30466, 30431, 30439, -1, 30468, 30449, 30434, -1, 30466, 30439, 30440, -1, 30469, 30438, 30470, -1, 30468, 30434, 30453, -1, 30469, 30436, 30438, -1, 30471, 30398, 30397, -1, 30471, 30448, 30451, -1, 30472, 30442, 30450, -1, 30471, 30397, 30445, -1, 30472, 30440, 30442, -1, 30471, 30445, 30448, -1, 30473, 30443, 30457, -1, 30474, 30450, 30406, -1, 30473, 30453, 30443, -1, 30474, 30406, 30454, -1, 30475, 30451, 30409, -1, 30475, 30409, 30455, -1, 30476, 30458, 30477, -1, 30478, 30454, 30414, -1, 30479, 30417, 30459, -1, 30476, 30457, 30458, -1, 30479, 30455, 30417, -1, 30478, 30414, 30456, -1, 30480, 30481, 30464, -1, 30482, 30462, 30483, -1, 30480, 30464, 30463, -1, 30482, 30456, 30425, -1, 30482, 30425, 30460, -1, 30484, 30459, 30428, -1, 30484, 30428, 30465, -1, 30482, 30460, 30462, -1, 30485, 30463, 30449, -1, 30486, 30403, 30402, -1, 30485, 30449, 30468, -1, 30486, 30402, 30466, -1, 30407, 30465, 30436, -1, 30486, 30466, 30440, -1, 30486, 30440, 30472, -1, 30487, 30450, 30474, -1, 30411, 30453, 30473, -1, 30487, 30472, 30450, -1, 30407, 30436, 30469, -1, 30415, 30470, 30488, -1, 30411, 30468, 30453, -1, 30418, 30457, 30476, -1, 30415, 30469, 30470, -1, 30418, 30473, 30457, -1, 30489, 30474, 30454, -1, 30490, 30399, 30398, -1, 30490, 30398, 30471, -1, 30489, 30454, 30478, -1, 30490, 30471, 30451, -1, 30491, 30483, 30492, -1, 30490, 30451, 30475, -1, 30429, 30477, 30493, -1, 30491, 30482, 30483, -1, 30491, 30478, 30456, -1, 30433, 30475, 30455, -1, 30429, 30476, 30477, -1, 30491, 30456, 30482, -1, 30494, 30404, 30403, -1, 30433, 30455, 30479, -1, 30495, 30395, 30394, -1, 30495, 30467, 30481, -1, 30494, 30403, 30486, -1, 30495, 30481, 30480, -1, 30494, 30486, 30472, -1, 30494, 30472, 30487, -1, 30441, 30479, 30459, -1, 30495, 30394, 30467, -1, 30441, 30459, 30484, -1, 30496, 30487, 30474, -1, 30447, 30480, 30463, -1, 30496, 30474, 30489, -1, 30447, 30463, 30485, -1, 30497, 30492, 30498, -1, 30413, 30484, 30465, -1, 30497, 30491, 30492, -1, 30413, 30465, 30407, -1, 30497, 30489, 30478, -1, 30497, 30478, 30491, -1, 30410, 30485, 30468, -1, 30499, 30487, 30496, -1, 30410, 30468, 30411, -1, 30499, 30405, 30404, -1, 30499, 30404, 30494, -1, 30412, 30411, 30473, -1, 30499, 30494, 30487, -1, 30500, 30498, 30501, -1, 30408, 30407, 30469, -1, 30412, 30473, 30418, -1, 30408, 30469, 30415, -1, 30500, 30497, 30498, -1, 30416, 30488, 30426, -1, 30500, 30496, 30489, -1, 30422, 30476, 30429, -1, 30500, 30489, 30497, -1, 30416, 30415, 30488, -1, 30502, 30501, 30503, -1, 30502, 30503, 30233, -1, 30502, 30233, 30405, -1, 30432, 30400, 30399, -1, 30502, 30500, 30501, -1, 30432, 30399, 30490, -1, 30422, 30418, 30476, -1, 30502, 30499, 30496, -1, 30432, 30475, 30433, -1, 30502, 30405, 30499, -1, 30432, 30490, 30475, -1, 30502, 30496, 30500, -1, 30430, 30493, 30437, -1, 30430, 30429, 30493, -1, 30446, 30396, 30395, -1, 30439, 30479, 30441, -1, 30446, 30495, 30480, -1, 30439, 30433, 30479, -1, 30446, 30480, 30447, -1, 30442, 30441, 30484, -1, 30446, 30395, 30495, -1, 30448, 30447, 30485, -1, 30442, 30484, 30413, -1, 30448, 30485, 30410, -1, 30363, 30504, 30339, -1, 30339, 30504, 30341, -1, 30341, 30505, 30343, -1, 30504, 30505, 30341, -1, 30343, 30506, 30345, -1, 30505, 30506, 30343, -1, 30345, 30507, 30347, -1, 30506, 30507, 30345, -1, 30347, 30508, 30324, -1, 30507, 30508, 30347, -1, 30324, 30509, 30325, -1, 30508, 30509, 30324, -1, 30325, 30510, 30330, -1, 30509, 30510, 30325, -1, 30330, 30511, 30334, -1, 30510, 30511, 30330, -1, 30334, 30512, 30337, -1, 30511, 30512, 30334, -1, 30337, 30513, 30336, -1, 30512, 30513, 30337, -1, 30336, 30514, 30333, -1, 30513, 30514, 30336, -1, 30333, 30515, 30327, -1, 30514, 30515, 30333, -1, 30327, 30350, 30326, -1, 30515, 30350, 30327, -1, 30516, 30517, 30518, -1, 30519, 30509, 30508, -1, 30520, 30505, 30504, -1, 30519, 30508, 30521, -1, 30516, 30522, 30517, -1, 30519, 30521, 30523, -1, 30516, 30524, 30525, -1, 30519, 30523, 30526, -1, 30520, 30527, 30528, -1, 30516, 30525, 30522, -1, 30520, 30528, 30529, -1, 30530, 30531, 30532, -1, 30520, 30504, 30527, -1, 30533, 30518, 30534, -1, 30533, 30534, 30350, -1, 30533, 30515, 30514, -1, 30533, 30350, 30515, -1, 30533, 30514, 30535, -1, 30530, 30526, 30531, -1, 30536, 30529, 30537, -1, 30533, 30516, 30518, -1, 30533, 30535, 30524, -1, 30533, 30524, 30516, -1, 30536, 30537, 30538, -1, 30539, 30540, 30541, -1, 30542, 30538, 30543, -1, 30539, 30532, 30540, -1, 30542, 30543, 30544, -1, 30545, 30541, 30546, -1, 30547, 30548, 30549, -1, 30547, 30550, 30548, -1, 30551, 30552, 30553, -1, 30545, 30546, 30554, -1, 30551, 30544, 30552, -1, 30555, 30554, 30556, -1, 30555, 30556, 30557, -1, 30558, 30559, 30550, -1, 30560, 30553, 30561, -1, 30560, 30561, 30562, -1, 30558, 30550, 30547, -1, 30563, 30564, 30565, -1, 30566, 30567, 30568, -1, 30566, 30562, 30567, -1, 30569, 30549, 30570, -1, 30563, 30557, 30564, -1, 30571, 30519, 30526, -1, 30569, 30547, 30549, -1, 30572, 30506, 30505, -1, 30573, 30559, 30558, -1, 30571, 30510, 30509, -1, 30572, 30520, 30529, -1, 30571, 30509, 30519, -1, 30573, 30574, 30559, -1, 30571, 30526, 30530, -1, 30572, 30505, 30520, -1, 30572, 30529, 30536, -1, 30575, 30532, 30539, -1, 30576, 30536, 30538, -1, 30576, 30538, 30542, -1, 30577, 30547, 30569, -1, 30575, 30530, 30532, -1, 30578, 30541, 30545, -1, 30578, 30539, 30541, -1, 30577, 30558, 30547, -1, 30579, 30542, 30544, -1, 30579, 30544, 30551, -1, 30580, 30570, 30581, -1, 30504, 30363, 30582, -1, 30583, 30553, 30560, -1, 30584, 30545, 30554, -1, 30584, 30554, 30555, -1, 30583, 30551, 30553, -1, 30580, 30569, 30570, -1, 30585, 30586, 30574, -1, 30587, 30555, 30557, -1, 30585, 30574, 30573, -1, 30588, 30573, 30558, -1, 30589, 30560, 30562, -1, 30587, 30557, 30563, -1, 30590, 30591, 30592, -1, 30589, 30562, 30566, -1, 30590, 30565, 30591, -1, 30590, 30563, 30565, -1, 30588, 30558, 30577, -1, 30590, 30592, 30593, -1, 30594, 30568, 30595, -1, 30596, 30530, 30575, -1, 30597, 30577, 30569, -1, 30596, 30571, 30530, -1, 30594, 30566, 30568, -1, 30597, 30569, 30580, -1, 30596, 30511, 30510, -1, 30598, 30507, 30506, -1, 30596, 30510, 30571, -1, 30598, 30506, 30572, -1, 30598, 30536, 30576, -1, 30599, 30575, 30539, -1, 30598, 30572, 30536, -1, 30600, 30581, 30601, -1, 30523, 30576, 30542, -1, 30600, 30580, 30581, -1, 30599, 30539, 30578, -1, 30523, 30542, 30579, -1, 30602, 30578, 30545, -1, 30528, 30603, 30586, -1, 30602, 30545, 30584, -1, 30531, 30579, 30551, -1, 30528, 30586, 30585, -1, 30531, 30551, 30583, -1, 30537, 30573, 30588, -1, 30537, 30585, 30573, -1, 30604, 30555, 30587, -1, 30604, 30584, 30555, -1, 30540, 30583, 30560, -1, 30540, 30560, 30589, -1, 30605, 30593, 30606, -1, 30605, 30587, 30563, -1, 30605, 30590, 30593, -1, 30543, 30588, 30577, -1, 30543, 30577, 30597, -1, 30605, 30563, 30590, -1, 30607, 30511, 30596, -1, 30607, 30512, 30511, -1, 30546, 30589, 30566, -1, 30552, 30597, 30580, -1, 30546, 30566, 30594, -1, 30607, 30596, 30575, -1, 30607, 30575, 30599, -1, 30552, 30580, 30600, -1, 30556, 30595, 30608, -1, 30556, 30594, 30595, -1, 30609, 30578, 30602, -1, 30561, 30601, 30610, -1, 30609, 30599, 30578, -1, 30521, 30508, 30507, -1, 30561, 30600, 30601, -1, 30521, 30576, 30523, -1, 30521, 30507, 30598, -1, 30527, 30603, 30528, -1, 30521, 30598, 30576, -1, 30527, 30582, 30603, -1, 30527, 30504, 30582, -1, 30525, 30584, 30604, -1, 30525, 30602, 30584, -1, 30611, 30606, 30612, -1, 30526, 30523, 30579, -1, 30526, 30579, 30531, -1, 30611, 30605, 30606, -1, 30529, 30528, 30585, -1, 30611, 30604, 30587, -1, 30529, 30585, 30537, -1, 30611, 30587, 30605, -1, 30613, 30513, 30512, -1, 30532, 30531, 30583, -1, 30613, 30512, 30607, -1, 30532, 30583, 30540, -1, 30613, 30607, 30599, -1, 30613, 30599, 30609, -1, 30538, 30588, 30543, -1, 30538, 30537, 30588, -1, 30524, 30609, 30602, -1, 30544, 30597, 30552, -1, 30541, 30540, 30589, -1, 30541, 30589, 30546, -1, 30524, 30602, 30525, -1, 30544, 30543, 30597, -1, 30522, 30612, 30517, -1, 30522, 30611, 30612, -1, 30522, 30525, 30604, -1, 30522, 30604, 30611, -1, 30554, 30546, 30594, -1, 30553, 30552, 30600, -1, 30554, 30594, 30556, -1, 30553, 30600, 30561, -1, 30535, 30514, 30513, -1, 30557, 30608, 30564, -1, 30562, 30610, 30567, -1, 30535, 30513, 30613, -1, 30535, 30613, 30609, -1, 30535, 30609, 30524, -1, 30557, 30556, 30608, -1, 30562, 30561, 30610, -1, 30614, 30615, 30389, -1, 30616, 30617, 30618, -1, 30618, 30617, 30619, -1, 30617, 30620, 30619, -1, 30621, 30620, 30622, -1, 30619, 30620, 30621, -1, 30620, 30623, 30622, -1, 30383, 30624, 30382, -1, 30622, 30623, 30625, -1, 30623, 30626, 30625, -1, 30627, 30626, 30628, -1, 30629, 30626, 30627, -1, 30625, 30626, 30629, -1, 30626, 30387, 30628, -1, 30628, 30387, 30386, -1, 30626, 30630, 30387, -1, 30631, 30614, 30632, -1, 30631, 30632, 30633, -1, 30631, 30633, 30634, -1, 30631, 30634, 30635, -1, 30632, 30614, 30636, -1, 30634, 30633, 30637, -1, 30389, 30390, 30638, -1, 30639, 30385, 30640, -1, 30381, 30641, 30380, -1, 30642, 30643, 30383, -1, 30383, 30643, 30624, -1, 30624, 30643, 30644, -1, 30644, 30643, 30645, -1, 30645, 30643, 30646, -1, 30646, 30647, 30648, -1, 30643, 30647, 30646, -1, 30648, 30649, 30650, -1, 30650, 30649, 30651, -1, 30647, 30649, 30648, -1, 30651, 30652, 30653, -1, 30649, 30652, 30651, -1, 30653, 30654, 30655, -1, 30655, 30654, 30656, -1, 30656, 30654, 30657, -1, 30657, 30654, 30658, -1, 30652, 30654, 30653, -1, 30658, 30385, 30659, -1, 30659, 30385, 30641, -1, 30641, 30385, 30380, -1, 30654, 30385, 30658, -1, 30654, 30660, 30385, -1, 30661, 30662, 30660, -1, 30662, 30631, 30660, -1, 30663, 30631, 30662, -1, 30660, 30631, 30385, -1, 30664, 30665, 30385, -1, 30385, 30666, 30664, -1, 30665, 30667, 30385, -1, 30385, 30668, 30666, -1, 30667, 30669, 30385, -1, 30385, 30670, 30668, -1, 30669, 30640, 30385, -1, 30385, 30671, 30670, -1, 30631, 30672, 30385, -1, 30385, 30672, 30671, -1, 30631, 30673, 30672, -1, 30631, 30674, 30673, -1, 30631, 30675, 30674, -1, 30631, 30676, 30675, -1, 30631, 30677, 30676, -1, 30631, 30678, 30677, -1, 30679, 30639, 30640, -1, 30680, 30639, 30679, -1, 30681, 30639, 30680, -1, 30682, 30639, 30681, -1, 30683, 30639, 30682, -1, 30684, 30639, 30683, -1, 30685, 30686, 30684, -1, 30687, 30686, 30685, -1, 30684, 30686, 30639, -1, 30688, 30689, 30687, -1, 30687, 30689, 30686, -1, 30690, 30691, 30688, -1, 30688, 30691, 30689, -1, 30678, 30692, 30690, -1, 30690, 30692, 30691, -1, 30631, 30693, 30678, -1, 30678, 30693, 30692, -1, 30631, 30694, 30693, -1, 30631, 30635, 30694, -1, 30695, 30696, 30697, -1, 30698, 30696, 30695, -1, 30698, 30699, 30696, -1, 30700, 30699, 30698, -1, 30701, 30702, 30703, -1, 30703, 30702, 30700, -1, 30700, 30702, 30699, -1, 30701, 30704, 30702, -1, 30705, 30704, 30701, -1, 30705, 30706, 30704, -1, 30637, 30633, 30705, -1, 30705, 30633, 30706, -1, 30707, 30708, 30390, -1, 30390, 30709, 30707, -1, 30708, 30710, 30390, -1, 30390, 30711, 30709, -1, 30710, 30638, 30390, -1, 30390, 30712, 30711, -1, 30713, 30712, 30390, -1, 30713, 30714, 30712, -1, 30713, 30715, 30714, -1, 30716, 30715, 30713, -1, 30717, 30718, 30716, -1, 30716, 30718, 30715, -1, 30717, 30719, 30718, -1, 30720, 30719, 30717, -1, 30720, 30721, 30719, -1, 30722, 30721, 30720, -1, 30723, 30389, 30724, -1, 30724, 30389, 30725, -1, 30725, 30389, 30726, -1, 30726, 30389, 30727, -1, 30727, 30389, 30728, -1, 30728, 30389, 30729, -1, 30729, 30389, 30730, -1, 30730, 30389, 30731, -1, 30731, 30389, 30638, -1, 30732, 30733, 30734, -1, 30389, 30733, 30732, -1, 30389, 30735, 30733, -1, 30389, 30736, 30735, -1, 30721, 30614, 30737, -1, 30737, 30614, 30738, -1, 30738, 30614, 30739, -1, 30739, 30614, 30740, -1, 30740, 30614, 30741, -1, 30741, 30614, 30723, -1, 30723, 30614, 30389, -1, 30722, 30614, 30721, -1, 30742, 30614, 30722, -1, 30636, 30614, 30742, -1, 30743, 30744, 30614, -1, 30745, 30616, 30618, -1, 30746, 30616, 30745, -1, 30747, 30616, 30746, -1, 30736, 30616, 30747, -1, 30389, 30616, 30736, -1, 30389, 30615, 30616, -1, 30748, 30615, 30744, -1, 30744, 30615, 30614, -1, 30749, 30750, 30751, -1, 30752, 30753, 30754, -1, 30755, 30756, 30757, -1, 30755, 30711, 30758, -1, 30759, 30727, 30760, -1, 30759, 30761, 30762, -1, 30759, 30762, 30725, -1, 30759, 30725, 30726, -1, 30763, 30754, 30764, -1, 30765, 30757, 30766, -1, 30759, 30726, 30727, -1, 30759, 30749, 30761, -1, 30759, 30760, 30767, -1, 30763, 30764, 30768, -1, 30759, 30767, 30749, -1, 30769, 30768, 30770, -1, 30765, 30766, 30771, -1, 30772, 30771, 30773, -1, 30774, 30775, 30776, -1, 30769, 30770, 30777, -1, 30772, 30773, 30778, -1, 30779, 30777, 30780, -1, 30774, 30781, 30775, -1, 30782, 30778, 30783, -1, 30782, 30783, 30784, -1, 30779, 30780, 30785, -1, 30786, 30785, 30787, -1, 30786, 30787, 30788, -1, 30789, 30790, 30781, -1, 30789, 30781, 30774, -1, 30791, 30792, 30793, -1, 30791, 30784, 30792, -1, 30794, 30776, 30795, -1, 30796, 30797, 30798, -1, 30799, 30788, 30800, -1, 30799, 30800, 30801, -1, 30794, 30774, 30776, -1, 30796, 30793, 30797, -1, 30802, 30790, 30789, -1, 30803, 30752, 30754, -1, 30804, 30755, 30757, -1, 30802, 30805, 30790, -1, 30803, 30731, 30638, -1, 30804, 30707, 30709, -1, 30803, 30754, 30763, -1, 30804, 30709, 30755, -1, 30803, 30638, 30752, -1, 30804, 30757, 30765, -1, 30806, 30763, 30768, -1, 30807, 30789, 30774, -1, 30808, 30765, 30771, -1, 30806, 30768, 30769, -1, 30808, 30771, 30772, -1, 30809, 30769, 30777, -1, 30809, 30777, 30779, -1, 30807, 30774, 30794, -1, 30810, 30778, 30782, -1, 30811, 30794, 30795, -1, 30811, 30795, 30812, -1, 30810, 30772, 30778, -1, 30813, 30779, 30785, -1, 30814, 30782, 30784, -1, 30814, 30784, 30791, -1, 30815, 30816, 30805, -1, 30813, 30785, 30786, -1, 30815, 30805, 30802, -1, 30817, 30786, 30788, -1, 30818, 30789, 30807, -1, 30819, 30791, 30793, -1, 30818, 30802, 30789, -1, 30819, 30793, 30796, -1, 30817, 30788, 30799, -1, 30820, 30801, 30821, -1, 30822, 30798, 30823, -1, 30820, 30821, 30824, -1, 30820, 30824, 30825, -1, 30820, 30799, 30801, -1, 30822, 30796, 30798, -1, 30826, 30807, 30794, -1, 30827, 30803, 30763, -1, 30826, 30794, 30811, -1, 30827, 30730, 30731, -1, 30828, 30708, 30707, -1, 30827, 30731, 30803, -1, 30828, 30707, 30804, -1, 30829, 30812, 30830, -1, 30828, 30804, 30765, -1, 30827, 30763, 30806, -1, 30828, 30765, 30808, -1, 30829, 30811, 30812, -1, 30831, 30769, 30809, -1, 30753, 30808, 30772, -1, 30753, 30772, 30810, -1, 30831, 30806, 30769, -1, 30756, 30832, 30816, -1, 30833, 30809, 30779, -1, 30756, 30816, 30815, -1, 30833, 30779, 30813, -1, 30764, 30782, 30814, -1, 30764, 30810, 30782, -1, 30766, 30802, 30818, -1, 30766, 30815, 30802, -1, 30770, 30814, 30791, -1, 30834, 30813, 30786, -1, 30770, 30791, 30819, -1, 30834, 30786, 30817, -1, 30835, 30820, 30825, -1, 30773, 30818, 30807, -1, 30835, 30825, 30836, -1, 30773, 30807, 30826, -1, 30835, 30817, 30799, -1, 30835, 30799, 30820, -1, 30783, 30826, 30811, -1, 30780, 30796, 30822, -1, 30837, 30729, 30730, -1, 30837, 30730, 30827, -1, 30780, 30819, 30796, -1, 30837, 30827, 30806, -1, 30787, 30823, 30838, -1, 30783, 30811, 30829, -1, 30837, 30806, 30831, -1, 30839, 30809, 30833, -1, 30792, 30830, 30840, -1, 30839, 30831, 30809, -1, 30787, 30822, 30823, -1, 30841, 30708, 30828, -1, 30792, 30829, 30830, -1, 30841, 30710, 30708, -1, 30841, 30808, 30753, -1, 30841, 30828, 30808, -1, 30758, 30711, 30712, -1, 30758, 30842, 30832, -1, 30758, 30712, 30842, -1, 30750, 30833, 30813, -1, 30758, 30832, 30756, -1, 30750, 30813, 30834, -1, 30843, 30836, 30844, -1, 30754, 30753, 30810, -1, 30754, 30810, 30764, -1, 30757, 30815, 30766, -1, 30843, 30834, 30817, -1, 30843, 30835, 30836, -1, 30843, 30817, 30835, -1, 30757, 30756, 30815, -1, 30768, 30764, 30814, -1, 30768, 30814, 30770, -1, 30845, 30728, 30729, -1, 30845, 30729, 30837, -1, 30771, 30818, 30773, -1, 30845, 30837, 30831, -1, 30845, 30831, 30839, -1, 30771, 30766, 30818, -1, 30777, 30770, 30819, -1, 30777, 30819, 30780, -1, 30767, 30839, 30833, -1, 30778, 30773, 30826, -1, 30767, 30833, 30750, -1, 30778, 30826, 30783, -1, 30751, 30843, 30844, -1, 30785, 30780, 30822, -1, 30751, 30844, 30846, -1, 30751, 30834, 30843, -1, 30751, 30750, 30834, -1, 30784, 30783, 30829, -1, 30784, 30829, 30792, -1, 30785, 30822, 30787, -1, 30793, 30840, 30797, -1, 30760, 30727, 30728, -1, 30760, 30728, 30845, -1, 30788, 30838, 30800, -1, 30760, 30845, 30839, -1, 30760, 30839, 30767, -1, 30788, 30787, 30838, -1, 30749, 30846, 30761, -1, 30793, 30792, 30840, -1, 30752, 30638, 30710, -1, 30755, 30758, 30756, -1, 30749, 30751, 30846, -1, 30752, 30710, 30841, -1, 30749, 30767, 30750, -1, 30752, 30841, 30753, -1, 30755, 30709, 30711, -1, 30847, 30848, 30849, -1, 30850, 30677, 30678, -1, 30851, 30687, 30685, -1, 30847, 30852, 30848, -1, 30850, 30678, 30853, -1, 30851, 30854, 30855, -1, 30847, 30856, 30857, -1, 30850, 30853, 30858, -1, 30847, 30857, 30852, -1, 30850, 30858, 30859, -1, 30851, 30685, 30854, -1, 30860, 30849, 30861, -1, 30851, 30855, 30862, -1, 30860, 30861, 30670, -1, 30860, 30671, 30672, -1, 30860, 30670, 30671, -1, 30863, 30859, 30864, -1, 30860, 30847, 30849, -1, 30863, 30864, 30865, -1, 30866, 30862, 30867, -1, 30860, 30672, 30868, -1, 30860, 30868, 30856, -1, 30860, 30856, 30847, -1, 30869, 30865, 30870, -1, 30866, 30867, 30871, -1, 30872, 30871, 30873, -1, 30869, 30870, 30874, -1, 30875, 30874, 30876, -1, 30877, 30878, 30879, -1, 30872, 30873, 30880, -1, 30877, 30881, 30878, -1, 30882, 30880, 30883, -1, 30875, 30876, 30884, -1, 30882, 30883, 30885, -1, 30886, 30887, 30888, -1, 30889, 30890, 30881, -1, 30886, 30884, 30887, -1, 30891, 30885, 30892, -1, 30891, 30892, 30893, -1, 30889, 30881, 30877, -1, 30894, 30895, 30896, -1, 30897, 30879, 30898, -1, 30899, 30900, 30901, -1, 30894, 30888, 30895, -1, 30897, 30877, 30879, -1, 30902, 30859, 30863, -1, 30899, 30893, 30900, -1, 30903, 30890, 30889, -1, 30904, 30688, 30687, -1, 30902, 30676, 30677, -1, 30903, 30905, 30890, -1, 30902, 30677, 30850, -1, 30904, 30851, 30862, -1, 30902, 30850, 30859, -1, 30904, 30687, 30851, -1, 30906, 30865, 30869, -1, 30904, 30862, 30866, -1, 30907, 30877, 30897, -1, 30906, 30863, 30865, -1, 30908, 30866, 30871, -1, 30908, 30871, 30872, -1, 30907, 30889, 30877, -1, 30909, 30869, 30874, -1, 30910, 30872, 30880, -1, 30911, 30898, 30912, -1, 30909, 30874, 30875, -1, 30910, 30880, 30882, -1, 30913, 30885, 30891, -1, 30914, 30875, 30884, -1, 30911, 30897, 30898, -1, 30914, 30884, 30886, -1, 30913, 30882, 30885, -1, 30915, 30916, 30905, -1, 30915, 30905, 30903, -1, 30917, 30886, 30888, -1, 30918, 30903, 30889, -1, 30919, 30891, 30893, -1, 30919, 30893, 30899, -1, 30917, 30888, 30894, -1, 30920, 30921, 30922, -1, 30920, 30896, 30921, -1, 30923, 30899, 30901, -1, 30918, 30889, 30907, -1, 30920, 30922, 30924, -1, 30923, 30901, 30925, -1, 30920, 30894, 30896, -1, 30926, 30675, 30676, -1, 30927, 30907, 30897, -1, 30926, 30676, 30902, -1, 30927, 30897, 30911, -1, 30928, 30904, 30866, -1, 30928, 30690, 30688, -1, 30926, 30863, 30906, -1, 30928, 30688, 30904, -1, 30926, 30902, 30863, -1, 30928, 30866, 30908, -1, 30929, 30906, 30869, -1, 30930, 30912, 30931, -1, 30930, 30911, 30912, -1, 30858, 30908, 30872, -1, 30858, 30872, 30910, -1, 30929, 30869, 30909, -1, 30855, 30932, 30916, -1, 30933, 30875, 30914, -1, 30933, 30909, 30875, -1, 30855, 30916, 30915, -1, 30864, 30910, 30882, -1, 30864, 30882, 30913, -1, 30867, 30915, 30903, -1, 30934, 30914, 30886, -1, 30867, 30903, 30918, -1, 30934, 30886, 30917, -1, 30870, 30913, 30891, -1, 30873, 30907, 30927, -1, 30870, 30891, 30919, -1, 30935, 30924, 30936, -1, 30935, 30917, 30894, -1, 30873, 30918, 30907, -1, 30935, 30894, 30920, -1, 30883, 30911, 30930, -1, 30935, 30920, 30924, -1, 30937, 30674, 30675, -1, 30876, 30899, 30923, -1, 30937, 30675, 30926, -1, 30876, 30919, 30899, -1, 30937, 30926, 30906, -1, 30883, 30927, 30911, -1, 30937, 30906, 30929, -1, 30887, 30925, 30938, -1, 30939, 30909, 30933, -1, 30887, 30923, 30925, -1, 30892, 30931, 30940, -1, 30939, 30929, 30909, -1, 30853, 30678, 30690, -1, 30892, 30930, 30931, -1, 30853, 30908, 30858, -1, 30854, 30685, 30684, -1, 30853, 30690, 30928, -1, 30853, 30928, 30908, -1, 30854, 30941, 30932, -1, 30854, 30684, 30941, -1, 30857, 30933, 30914, -1, 30854, 30932, 30855, -1, 30857, 30914, 30934, -1, 30942, 30936, 30943, -1, 30859, 30858, 30910, -1, 30859, 30910, 30864, -1, 30942, 30935, 30936, -1, 30862, 30855, 30915, -1, 30942, 30934, 30917, -1, 30942, 30917, 30935, -1, 30862, 30915, 30867, -1, 30944, 30673, 30674, -1, 30865, 30864, 30913, -1, 30865, 30913, 30870, -1, 30944, 30674, 30937, -1, 30871, 30867, 30918, -1, 30944, 30937, 30929, -1, 30944, 30929, 30939, -1, 30871, 30918, 30873, -1, 30874, 30870, 30919, -1, 30856, 30933, 30857, -1, 30874, 30919, 30876, -1, 30880, 30927, 30883, -1, 30856, 30939, 30933, -1, 30880, 30873, 30927, -1, 30852, 30943, 30848, -1, 30884, 30923, 30887, -1, 30884, 30876, 30923, -1, 30885, 30883, 30930, -1, 30852, 30942, 30943, -1, 30852, 30857, 30934, -1, 30852, 30934, 30942, -1, 30885, 30930, 30892, -1, 30868, 30672, 30673, -1, 30888, 30938, 30895, -1, 30893, 30940, 30900, -1, 30868, 30673, 30944, -1, 30868, 30944, 30939, -1, 30868, 30939, 30856, -1, 30888, 30887, 30938, -1, 30893, 30892, 30940, -1, 13776, 13777, 30945, -1, 13776, 30945, 30946, -1, 13769, 30947, 30948, -1, 13769, 30948, 11705, -1, 30949, 11700, 11699, -1, 30949, 11699, 11698, -1, 30949, 11698, 11697, -1, 30949, 11697, 11696, -1, 11701, 11700, 30949, -1, 11702, 11701, 30949, -1, 13775, 13776, 30946, -1, 13775, 30946, 30950, -1, 11703, 11702, 30949, -1, 13770, 30951, 30947, -1, 13770, 30947, 13769, -1, 11709, 30952, 11710, -1, 13774, 30950, 30953, -1, 13774, 13775, 30950, -1, 11711, 11710, 30952, -1, 13771, 30954, 30951, -1, 13771, 30951, 13770, -1, 13773, 13774, 30953, -1, 11708, 30952, 11709, -1, 13773, 30953, 30955, -1, 11712, 11711, 30952, -1, 13772, 30955, 30954, -1, 13772, 30954, 13771, -1, 13772, 13773, 30955, -1, 30949, 30956, 11704, -1, 11707, 30952, 11708, -1, 30949, 11704, 11703, -1, 30948, 30952, 11705, -1, 11705, 30952, 11706, -1, 11706, 30952, 11707, -1, 11713, 11712, 30952, -1, 11714, 11713, 30952, -1, 30956, 13768, 11704, -1, 13781, 13768, 30956, -1, 30957, 13781, 30956, -1, 13780, 13781, 30957, -1, 30958, 13780, 30957, -1, 13779, 13780, 30958, -1, 30959, 13779, 30958, -1, 13778, 13779, 30959, -1, 13778, 30959, 30960, -1, 13777, 13778, 30960, -1, 13777, 30960, 30945, -1, 8032, 30952, 30695, -1, 11714, 30952, 8032, -1, 8093, 8032, 30695, -1, 30697, 8093, 30695, -1, 30311, 9629, 8093, -1, 30311, 8093, 30697, -1, 7991, 7946, 30385, -1, 30639, 7991, 30385, -1, 30949, 11696, 7991, -1, 30949, 7991, 30639, -1, 30961, 30962, 30963, -1, 30392, 30962, 30961, -1, 30392, 30393, 30962, -1, 30964, 30965, 30966, -1, 30965, 30967, 30968, -1, 30964, 30969, 30965, -1, 30965, 30969, 30967, -1, 30967, 30970, 30968, -1, 30967, 30971, 30970, -1, 30971, 30972, 30970, -1, 30972, 30973, 30963, -1, 30971, 30973, 30972, -1, 30963, 30974, 30961, -1, 30973, 30974, 30963, -1, 30974, 30975, 30961, -1, 30975, 30976, 30961, -1, 30975, 30977, 30976, -1, 30978, 30979, 30977, -1, 30977, 30979, 30976, -1, 30978, 30980, 30979, -1, 30981, 30979, 30982, -1, 30976, 30979, 30981, -1, 30983, 30984, 30985, -1, 30986, 30987, 30983, -1, 30986, 30983, 30985, -1, 30988, 30989, 30987, -1, 30988, 30990, 30989, -1, 30991, 30987, 30986, -1, 30991, 30988, 30987, -1, 30964, 30966, 30992, -1, 30964, 30992, 30991, -1, 30993, 30994, 30995, -1, 30993, 30995, 30996, -1, 30997, 30998, 30994, -1, 30997, 30994, 30993, -1, 30999, 30998, 30997, -1, 30986, 30993, 30996, -1, 30986, 30996, 30991, -1, 30991, 30996, 30964, -1, 30997, 31000, 30999, -1, 30984, 31001, 30985, -1, 30984, 31002, 31001, -1, 31003, 31004, 31005, -1, 31006, 31004, 31003, -1, 31007, 31004, 31006, -1, 31002, 31004, 31007, -1, 30984, 31004, 31002, -1, 31005, 31008, 31009, -1, 31004, 31008, 31005, -1, 31004, 31010, 31008, -1, 31011, 31010, 31004, -1, 31012, 31013, 31014, -1, 31011, 31014, 31010, -1, 31015, 31012, 31014, -1, 31015, 31014, 31011, -1, 31016, 31015, 31017, -1, 31018, 31015, 31016, -1, 31019, 31015, 31018, -1, 31012, 31015, 31019, -1, 31020, 31016, 31017, -1, 31021, 31022, 31023, -1, 30999, 31023, 30998, -1, 30999, 31021, 31023, -1, 31023, 31022, 31024, -1, 31023, 31024, 31025, -1, 31026, 31027, 31024, -1, 31025, 31027, 31028, -1, 31024, 31027, 31025, -1, 31000, 31029, 31021, -1, 31000, 31021, 30999, -1, 31030, 30996, 30995, -1, 31031, 31030, 31032, -1, 31033, 30996, 31030, -1, 31033, 31030, 31031, -1, 31034, 31031, 31032, -1, 31035, 31031, 31034, -1, 31027, 31035, 31034, -1, 31036, 31035, 31027, -1, 31037, 31027, 31026, -1, 31037, 31036, 31027, -1, 30968, 31038, 31039, -1, 30970, 31038, 30968, -1, 30963, 31040, 30972, -1, 30963, 30962, 31040, -1, 30962, 31041, 31040, -1, 2566, 30391, 30392, -1, 2567, 2566, 30392, -1, 30981, 31042, 31043, -1, 31044, 30981, 31043, -1, 31045, 30981, 31044, -1, 31046, 30981, 31045, -1, 30961, 31047, 31048, -1, 30961, 31048, 31049, -1, 30961, 31049, 31050, -1, 30961, 31050, 31051, -1, 30961, 31051, 31052, -1, 30961, 31052, 2568, -1, 30961, 2568, 2567, -1, 30961, 2567, 30392, -1, 30976, 31046, 31053, -1, 30976, 31053, 31054, -1, 30976, 31054, 31055, -1, 30976, 31055, 31056, -1, 30976, 31056, 31057, -1, 30976, 31057, 31047, -1, 30976, 31047, 30961, -1, 30976, 30981, 31046, -1, 31038, 30972, 31040, -1, 31038, 30970, 30972, -1, 30965, 30992, 30966, -1, 30965, 31058, 30992, -1, 30965, 31039, 31058, -1, 30968, 31039, 30965, -1, 30990, 31059, 30989, -1, 31060, 31059, 30990, -1, 31060, 31061, 31059, -1, 31062, 31061, 31060, -1, 31063, 31064, 31061, -1, 31063, 31061, 31062, -1, 31064, 31065, 31066, -1, 31064, 31063, 31065, -1, 31065, 31067, 31066, -1, 31068, 31067, 31065, -1, 30982, 31069, 30981, -1, 2349, 31069, 30113, -1, 31069, 31042, 30981, -1, 2349, 2351, 31069, -1, 31069, 2351, 31042, -1, 31070, 31071, 31072, -1, 31029, 31071, 31070, -1, 31073, 31000, 31074, -1, 31073, 31071, 31029, -1, 31073, 31029, 31000, -1, 31075, 31076, 31077, -1, 31075, 31077, 31078, -1, 30132, 31079, 31076, -1, 30132, 31076, 31075, -1, 30137, 31075, 31080, -1, 30137, 31080, 31081, -1, 30137, 30132, 31075, -1, 30143, 31082, 31083, -1, 31084, 30143, 31083, -1, 30145, 31084, 31085, -1, 30145, 30143, 31084, -1, 31086, 31087, 31088, -1, 31089, 31090, 31091, -1, 31091, 31090, 31092, -1, 31092, 31090, 31087, -1, 31087, 31090, 31088, -1, 31090, 31093, 31094, -1, 31094, 31093, 31095, -1, 31089, 31096, 31090, -1, 31096, 31097, 31090, -1, 31090, 31098, 31093, -1, 31097, 31098, 31090, -1, 31098, 31099, 31093, -1, 31083, 31100, 31084, -1, 31101, 31102, 31103, -1, 31104, 31102, 31101, -1, 31105, 31102, 31104, -1, 31106, 31102, 31105, -1, 31107, 31102, 31106, -1, 31100, 31102, 31107, -1, 31108, 31109, 31102, -1, 31110, 31109, 31108, -1, 31111, 31109, 31099, -1, 31103, 31109, 31111, -1, 31099, 31109, 31093, -1, 31102, 31109, 31103, -1, 31083, 31102, 31100, -1, 31075, 31112, 31080, -1, 31113, 31114, 31115, -1, 31112, 31114, 31113, -1, 31112, 31116, 31114, -1, 31117, 31118, 31119, -1, 31116, 31118, 31117, -1, 31075, 31118, 31112, -1, 31112, 31118, 31116, -1, 31118, 31120, 31119, -1, 31120, 31121, 31119, -1, 31121, 31122, 31119, -1, 31122, 31123, 31119, -1, 31124, 31125, 31121, -1, 31126, 31125, 31124, -1, 31121, 31125, 31122, -1, 31123, 31127, 31119, -1, 31126, 31128, 31125, -1, 31126, 31129, 31128, -1, 31129, 31130, 31128, -1, 30249, 12940, 30384, -1, 12940, 31131, 30384, -1, 12940, 13753, 31131, -1, 31132, 31133, 31134, -1, 31135, 31136, 31133, -1, 31137, 31136, 31135, -1, 31133, 31136, 31134, -1, 31136, 30118, 31138, -1, 30119, 30118, 31137, -1, 31137, 30118, 31136, -1, 31139, 31140, 31141, -1, 31142, 31139, 31141, -1, 31143, 31142, 31141, -1, 13753, 31143, 31141, -1, 12574, 31143, 13753, -1, 31131, 31144, 30384, -1, 31131, 31145, 31146, -1, 31144, 31147, 30384, -1, 31148, 31147, 31149, -1, 31150, 31151, 30384, -1, 30384, 31147, 31148, -1, 31152, 30383, 31153, -1, 30384, 31154, 31150, -1, 31155, 30383, 31156, -1, 31157, 30383, 31155, -1, 31158, 30383, 31157, -1, 31159, 30383, 31158, -1, 31160, 30383, 31159, -1, 31151, 31156, 30384, -1, 31161, 30383, 31160, -1, 31162, 30383, 31161, -1, 31153, 30383, 31162, -1, 31156, 30383, 30384, -1, 30384, 31163, 31154, -1, 31147, 31164, 31149, -1, 30384, 31148, 31163, -1, 31131, 31165, 31145, -1, 31149, 31166, 31167, -1, 31164, 31166, 31149, -1, 31131, 31168, 31165, -1, 31169, 31170, 31171, -1, 31172, 31170, 31169, -1, 31173, 31170, 31172, -1, 31174, 31170, 31173, -1, 31167, 31170, 31174, -1, 31166, 31170, 31167, -1, 31131, 31175, 31168, -1, 31176, 31177, 31131, -1, 31131, 31177, 31175, -1, 31178, 30642, 31152, -1, 31179, 30642, 31178, -1, 31170, 30642, 31171, -1, 31180, 30642, 31179, -1, 31181, 30642, 31180, -1, 31171, 30642, 31181, -1, 31152, 30642, 30383, -1, 31177, 31133, 31132, -1, 31176, 31133, 31177, -1, 31131, 31146, 31182, -1, 31182, 31144, 31131, -1, 31183, 31184, 31185, -1, 31186, 31179, 31178, -1, 31183, 31187, 31188, -1, 31186, 31189, 31190, -1, 31186, 31178, 31189, -1, 31191, 31192, 31193, -1, 31186, 31190, 31194, -1, 31191, 31195, 31192, -1, 31196, 31193, 31197, -1, 31198, 31194, 31199, -1, 31198, 31199, 31200, -1, 31196, 31197, 31201, -1, 31202, 31200, 31203, -1, 31204, 31205, 31206, -1, 31148, 31149, 31207, -1, 31202, 31203, 31208, -1, 31209, 31210, 31211, -1, 31209, 31212, 31210, -1, 31204, 31201, 31205, -1, 31213, 31208, 31214, -1, 31215, 31216, 31217, -1, 31213, 31214, 31218, -1, 31215, 31206, 31216, -1, 31219, 31220, 31212, -1, 31221, 31218, 31222, -1, 31223, 31224, 31225, -1, 31221, 31222, 31226, -1, 31219, 31212, 31209, -1, 31223, 31217, 31224, -1, 31227, 31228, 31229, -1, 31230, 31231, 31195, -1, 31232, 31211, 31233, -1, 31227, 31226, 31228, -1, 31230, 31172, 31169, -1, 31230, 31169, 31231, -1, 31232, 31209, 31211, -1, 31230, 31195, 31191, -1, 31234, 31180, 31179, -1, 31235, 31220, 31219, -1, 31236, 31193, 31196, -1, 31234, 31186, 31194, -1, 31235, 31237, 31220, -1, 31234, 31179, 31186, -1, 31234, 31194, 31198, -1, 31236, 31191, 31193, -1, 31238, 31200, 31202, -1, 31239, 31196, 31201, -1, 31239, 31201, 31204, -1, 31240, 31209, 31232, -1, 31238, 31198, 31200, -1, 31241, 31208, 31213, -1, 31240, 31219, 31209, -1, 31241, 31202, 31208, -1, 31242, 31204, 31206, -1, 31242, 31206, 31215, -1, 31243, 31233, 31244, -1, 31152, 31153, 31245, -1, 31246, 31213, 31218, -1, 31246, 31218, 31221, -1, 31243, 31232, 31233, -1, 31247, 31215, 31217, -1, 31248, 31249, 31237, -1, 31248, 31237, 31235, -1, 31247, 31217, 31223, -1, 31250, 31251, 31252, -1, 31253, 31221, 31226, -1, 31254, 31235, 31219, -1, 31250, 31225, 31251, -1, 31253, 31226, 31227, -1, 31250, 31252, 31255, -1, 31250, 31223, 31225, -1, 31256, 31229, 31257, -1, 31258, 31173, 31172, -1, 31254, 31219, 31240, -1, 31258, 31172, 31230, -1, 31258, 31230, 31191, -1, 31256, 31227, 31229, -1, 31258, 31191, 31236, -1, 31259, 31181, 31180, -1, 31260, 31236, 31196, -1, 31261, 31240, 31232, -1, 31259, 31180, 31234, -1, 31261, 31232, 31243, -1, 31259, 31234, 31198, -1, 31259, 31198, 31238, -1, 31262, 31238, 31202, -1, 31260, 31196, 31239, -1, 31263, 31244, 31264, -1, 31262, 31202, 31241, -1, 31265, 31239, 31204, -1, 31263, 31243, 31244, -1, 31265, 31204, 31242, -1, 31192, 31213, 31246, -1, 31190, 31266, 31249, -1, 31267, 31215, 31247, -1, 31192, 31241, 31213, -1, 31267, 31242, 31215, -1, 31190, 31249, 31248, -1, 31199, 31248, 31235, -1, 31268, 31255, 31269, -1, 31197, 31246, 31221, -1, 31197, 31221, 31253, -1, 31199, 31235, 31254, -1, 31268, 31247, 31223, -1, 31268, 31250, 31255, -1, 31203, 31240, 31261, -1, 31268, 31223, 31250, -1, 31205, 31253, 31227, -1, 31270, 31174, 31173, -1, 31270, 31173, 31258, -1, 31270, 31258, 31236, -1, 31203, 31254, 31240, -1, 31270, 31236, 31260, -1, 31205, 31227, 31256, -1, 31214, 31243, 31263, -1, 31271, 31239, 31265, -1, 31216, 31257, 31272, -1, 31271, 31260, 31239, -1, 31214, 31261, 31243, -1, 31216, 31256, 31257, -1, 31273, 31171, 31181, -1, 31222, 31264, 31274, -1, 31273, 31238, 31262, -1, 31273, 31259, 31238, -1, 31275, 31242, 31267, -1, 31273, 31181, 31259, -1, 31222, 31263, 31264, -1, 31275, 31265, 31242, -1, 31276, 31269, 31277, -1, 31189, 31178, 31152, -1, 31189, 31245, 31266, -1, 31276, 31268, 31269, -1, 31195, 31262, 31241, -1, 31189, 31152, 31245, -1, 31276, 31247, 31268, -1, 31195, 31241, 31192, -1, 31189, 31266, 31190, -1, 31276, 31267, 31247, -1, 31278, 31167, 31174, -1, 31278, 31174, 31270, -1, 31278, 31270, 31260, -1, 31193, 31192, 31246, -1, 31194, 31190, 31248, -1, 31278, 31260, 31271, -1, 31193, 31246, 31197, -1, 31188, 31271, 31265, -1, 31194, 31248, 31199, -1, 31200, 31199, 31254, -1, 31188, 31265, 31275, -1, 31201, 31253, 31205, -1, 31201, 31197, 31253, -1, 31200, 31254, 31203, -1, 31279, 31277, 31280, -1, 31279, 31276, 31277, -1, 31208, 31261, 31214, -1, 31279, 31275, 31267, -1, 31279, 31267, 31276, -1, 31208, 31203, 31261, -1, 31187, 31149, 31167, -1, 31187, 31167, 31278, -1, 31206, 31205, 31256, -1, 31218, 31214, 31263, -1, 31187, 31278, 31271, -1, 31206, 31256, 31216, -1, 31187, 31271, 31188, -1, 31184, 31280, 31185, -1, 31217, 31272, 31224, -1, 31218, 31263, 31222, -1, 31184, 31188, 31275, -1, 31184, 31279, 31280, -1, 31217, 31216, 31272, -1, 31184, 31275, 31279, -1, 31226, 31274, 31228, -1, 31231, 31169, 31171, -1, 31183, 31185, 31207, -1, 31231, 31171, 31273, -1, 31183, 31207, 31149, -1, 31231, 31273, 31262, -1, 31226, 31222, 31274, -1, 31183, 31188, 31184, -1, 31231, 31262, 31195, -1, 31183, 31149, 31187, -1, 31281, 31282, 31176, -1, 31283, 31284, 31285, -1, 31286, 31285, 31284, -1, 31287, 31283, 31285, -1, 31288, 31285, 31286, -1, 31289, 31285, 31288, -1, 31290, 31285, 31289, -1, 31131, 31281, 31176, -1, 13753, 31141, 31131, -1, 31141, 31291, 31281, -1, 31281, 31291, 31292, -1, 31141, 31281, 31131, -1, 31281, 31292, 31293, -1, 31293, 31287, 31281, -1, 31281, 31287, 31285, -1, 31294, 31295, 31296, -1, 31079, 31294, 31296, -1, 31076, 31296, 31297, -1, 31076, 31079, 31296, -1, 31298, 31076, 31297, -1, 31299, 31076, 31298, -1, 3225, 3219, 31300, -1, 3225, 31300, 31301, -1, 31302, 31303, 31304, -1, 31305, 31303, 31302, -1, 31306, 31307, 31305, -1, 31305, 31307, 31303, -1, 31303, 31308, 31304, -1, 31309, 31310, 31306, -1, 31306, 31310, 31307, -1, 31309, 31311, 31310, -1, 31308, 31312, 31304, -1, 31301, 31313, 31309, -1, 31309, 31313, 31311, -1, 31312, 31314, 31304, -1, 31300, 31315, 31301, -1, 31316, 31315, 31300, -1, 31301, 31315, 31313, -1, 31316, 31317, 31315, -1, 31318, 31319, 31316, -1, 31316, 31319, 31317, -1, 31320, 31321, 31318, -1, 31318, 31321, 31319, -1, 31322, 31323, 31320, -1, 31320, 31323, 31321, -1, 31324, 31325, 31326, -1, 31324, 31326, 31327, -1, 31324, 31327, 31328, -1, 31324, 31328, 31323, -1, 31324, 31323, 31322, -1, 31329, 31304, 31314, -1, 3215, 3209, 31330, -1, 3215, 31330, 31331, -1, 31332, 31333, 31334, -1, 31335, 31336, 31337, -1, 31335, 31337, 31332, -1, 31338, 31339, 31336, -1, 31338, 31336, 31335, -1, 31340, 31341, 31342, -1, 31343, 31342, 31341, -1, 31344, 31345, 31338, -1, 31338, 31345, 31339, -1, 31346, 31341, 31340, -1, 31339, 31345, 31347, -1, 31331, 31330, 31348, -1, 31331, 31348, 31349, -1, 31350, 31345, 31341, -1, 31350, 31341, 31346, -1, 31351, 31345, 31350, -1, 31352, 31345, 31351, -1, 31353, 31354, 31343, -1, 31353, 31343, 31355, -1, 31356, 31343, 31341, -1, 31356, 31355, 31343, -1, 31357, 31358, 31354, -1, 31357, 31354, 31353, -1, 31359, 31358, 31357, -1, 31331, 31358, 31359, -1, 31360, 31345, 31352, -1, 31347, 31345, 31360, -1, 31349, 31358, 31331, -1, 31330, 31361, 31348, -1, 31334, 31333, 31361, -1, 31334, 31361, 31330, -1, 31332, 31337, 31333, -1, 3060, 31362, 31297, -1, 3064, 3060, 31297, -1, 31296, 3064, 31297, -1, 30133, 3064, 31296, -1, 31363, 3072, 31364, -1, 3063, 31363, 31365, -1, 3063, 3072, 31363, -1, 31364, 31366, 31367, -1, 31363, 31364, 31367, -1, 3070, 31368, 31369, -1, 3070, 3071, 31368, -1, 31370, 31371, 31372, -1, 31373, 31371, 31370, -1, 31374, 31371, 31373, -1, 31375, 31376, 31371, -1, 31375, 31371, 31374, -1, 31377, 31378, 31379, -1, 31377, 31379, 31380, -1, 31377, 31380, 31381, -1, 31377, 31381, 31382, -1, 31377, 31382, 31383, -1, 31377, 31383, 31384, -1, 31377, 31384, 31375, -1, 31377, 31375, 31374, -1, 31385, 31386, 31387, -1, 31388, 31385, 31387, -1, 31389, 31377, 31386, -1, 31389, 31378, 31377, -1, 31389, 31386, 31385, -1, 31390, 31388, 31387, -1, 31391, 31378, 31389, -1, 31392, 31378, 31391, -1, 31393, 31378, 31392, -1, 31368, 31394, 31393, -1, 31369, 31368, 31393, -1, 31395, 31369, 31393, -1, 31396, 31395, 31393, -1, 31394, 31378, 31393, -1, 3050, 30111, 31397, -1, 31398, 3050, 31397, -1, 3065, 3050, 31398, -1, 31398, 31399, 31400, -1, 31399, 31401, 31400, -1, 31398, 31402, 31399, -1, 31401, 31403, 31400, -1, 31398, 31397, 31402, -1, 31404, 31405, 31397, -1, 31397, 31405, 31402, -1, 31404, 31406, 31405, -1, 31404, 31407, 31406, -1, 31404, 31408, 31407, -1, 31409, 31410, 31403, -1, 31411, 31410, 31409, -1, 31412, 31410, 31411, -1, 31413, 31410, 31412, -1, 31403, 31410, 31400, -1, 31414, 31415, 31413, -1, 31416, 31415, 31414, -1, 31417, 31415, 31416, -1, 31418, 31415, 31417, -1, 31413, 31415, 31410, -1, 31404, 31415, 31408, -1, 31408, 31415, 31419, -1, 31419, 31415, 31418, -1, 31420, 31421, 31422, -1, 31420, 31422, 31423, -1, 31424, 31420, 31423, -1, 31425, 31420, 31424, -1, 31426, 31427, 31420, -1, 31426, 31420, 31425, -1, 31428, 31427, 31426, -1, 31429, 31430, 31427, -1, 31429, 31427, 31428, -1, 31431, 31430, 31429, -1, 31432, 31431, 31429, -1, 31433, 31432, 31429, -1, 30112, 31434, 31435, -1, 30112, 31429, 31434, -1, 30112, 31433, 31429, -1, 30112, 30114, 31436, -1, 30112, 31436, 31437, -1, 30112, 31437, 31438, -1, 30112, 31438, 31439, -1, 30112, 31439, 31433, -1, 31420, 31440, 31421, -1, 31441, 31442, 31443, -1, 31444, 31441, 31445, -1, 31446, 31442, 31441, -1, 31446, 31441, 31444, -1, 31447, 31445, 31441, -1, 31448, 31447, 31441, -1, 31449, 31448, 31441, -1, 31440, 31442, 31446, -1, 31420, 31442, 31440, -1, 31429, 31450, 31434, -1, 30117, 31451, 30114, -1, 31452, 31453, 31454, -1, 31455, 31453, 31452, -1, 31456, 31453, 31455, -1, 31457, 31453, 31456, -1, 31458, 31453, 31457, -1, 31459, 31453, 31458, -1, 31451, 31453, 31459, -1, 30117, 31460, 31451, -1, 31451, 31460, 31453, -1, 31461, 31462, 31463, -1, 31464, 31465, 31466, -1, 31464, 31466, 31467, -1, 31464, 31461, 31468, -1, 31464, 31468, 31465, -1, 31464, 31467, 31469, -1, 31464, 31469, 31461, -1, 31459, 31470, 31471, -1, 31459, 31471, 31451, -1, 31472, 31442, 31473, -1, 31474, 31465, 31468, -1, 31475, 31459, 31458, -1, 31476, 31477, 31470, -1, 31476, 31470, 31459, -1, 31476, 31475, 31458, -1, 31476, 31459, 31475, -1, 31478, 31473, 31477, -1, 31478, 31472, 31473, -1, 31478, 31477, 31476, -1, 31479, 31457, 31456, -1, 31479, 31458, 31457, -1, 31480, 31458, 31479, -1, 31480, 31476, 31458, -1, 31481, 31482, 31472, -1, 31481, 31478, 31476, -1, 31481, 31472, 31478, -1, 31481, 31476, 31480, -1, 31483, 31456, 31455, -1, 31483, 31479, 31456, -1, 31484, 31480, 31479, -1, 31484, 31479, 31483, -1, 31485, 31486, 31482, -1, 31485, 31480, 31484, -1, 31485, 31482, 31481, -1, 31485, 31481, 31480, -1, 31462, 31483, 31455, -1, 31469, 31484, 31483, -1, 31469, 31483, 31462, -1, 31467, 31466, 31486, -1, 31467, 31486, 31485, -1, 31467, 31485, 31484, -1, 31467, 31484, 31469, -1, 31463, 31452, 31454, -1, 31463, 31455, 31452, -1, 31463, 31454, 31487, -1, 31463, 31462, 31455, -1, 31461, 31487, 31468, -1, 31461, 31463, 31487, -1, 31461, 31469, 31462, -1, 31325, 31488, 31489, -1, 31490, 31325, 31324, -1, 31490, 31488, 31325, -1, 31489, 31491, 31492, -1, 31488, 31491, 31489, -1, 31492, 31493, 31494, -1, 31491, 31493, 31492, -1, 31494, 31495, 31496, -1, 31493, 31495, 31494, -1, 31496, 31497, 31498, -1, 31495, 31497, 31496, -1, 31498, 31499, 31500, -1, 31497, 31499, 31498, -1, 31500, 31501, 31502, -1, 31502, 31501, 31503, -1, 31499, 31501, 31500, -1, 31501, 31504, 31503, -1, 31504, 31505, 31506, -1, 31504, 31506, 31503, -1, 31507, 31508, 31509, -1, 31510, 31508, 31507, -1, 31511, 31512, 31513, -1, 31514, 31515, 31516, -1, 31516, 31515, 31517, -1, 31518, 31519, 31520, -1, 31509, 31521, 31522, -1, 31520, 31519, 31523, -1, 31508, 31521, 31509, -1, 31524, 31525, 31514, -1, 31514, 31525, 31515, -1, 31512, 31526, 31513, -1, 31522, 31527, 31528, -1, 31521, 31527, 31522, -1, 31518, 31529, 31519, -1, 31528, 31530, 31524, -1, 31527, 31530, 31528, -1, 31524, 31530, 31525, -1, 31399, 31402, 31531, -1, 31399, 31531, 31532, -1, 31526, 31533, 31513, -1, 31518, 31534, 31529, -1, 31535, 31534, 31518, -1, 31536, 31537, 31531, -1, 31538, 31537, 31536, -1, 31535, 31539, 31534, -1, 31531, 31537, 31532, -1, 31535, 31540, 31539, -1, 31538, 31541, 31537, -1, 31540, 31542, 31539, -1, 31542, 31543, 31544, -1, 31540, 31543, 31542, -1, 31545, 31546, 31547, -1, 31547, 31548, 31538, -1, 31541, 31548, 31549, -1, 31538, 31548, 31541, -1, 31546, 31548, 31547, -1, 31550, 31551, 31533, -1, 31552, 31553, 31545, -1, 31554, 31551, 31550, -1, 31555, 31553, 31552, -1, 31516, 31551, 31554, -1, 31556, 31553, 31555, -1, 31533, 31551, 31513, -1, 31545, 31553, 31546, -1, 31548, 31557, 31549, -1, 31549, 31557, 31558, -1, 31559, 31560, 31556, -1, 31520, 31560, 31559, -1, 31556, 31560, 31553, -1, 31544, 31561, 31562, -1, 31543, 31561, 31544, -1, 31557, 31563, 31558, -1, 31558, 31563, 31513, -1, 31516, 31564, 31551, -1, 31520, 31523, 31560, -1, 31516, 31565, 31564, -1, 31562, 31510, 31507, -1, 31563, 31566, 31513, -1, 31561, 31510, 31562, -1, 31566, 31511, 31513, -1, 31516, 31517, 31565, -1, 31567, 31520, 31559, -1, 31568, 31559, 31556, -1, 31568, 31567, 31559, -1, 31569, 31556, 31555, -1, 31569, 31568, 31556, -1, 31570, 31555, 31552, -1, 31570, 31569, 31555, -1, 31571, 31552, 31545, -1, 31571, 31570, 31552, -1, 31572, 31545, 31547, -1, 31572, 31571, 31545, -1, 31573, 31547, 31538, -1, 31573, 31572, 31547, -1, 31574, 31517, 31575, -1, 31575, 31515, 31576, -1, 31517, 31515, 31575, -1, 31577, 31525, 31578, -1, 31576, 31525, 31577, -1, 31515, 31525, 31576, -1, 31578, 31530, 31579, -1, 31525, 31530, 31578, -1, 31580, 31527, 31581, -1, 31579, 31527, 31580, -1, 31530, 31527, 31579, -1, 31581, 31521, 31582, -1, 31527, 31521, 31581, -1, 31583, 31508, 31584, -1, 31582, 31508, 31583, -1, 31521, 31508, 31582, -1, 31584, 31510, 31585, -1, 31508, 31510, 31584, -1, 31510, 31561, 31585, -1, 31585, 31543, 31586, -1, 31561, 31543, 31585, -1, 31586, 31540, 31587, -1, 31543, 31540, 31586, -1, 31540, 31535, 31587, -1, 31535, 31567, 31587, -1, 31535, 31518, 31567, -1, 31588, 31574, 31589, -1, 31590, 31574, 31588, -1, 31591, 31574, 31590, -1, 31592, 31574, 31591, -1, 31593, 31574, 31592, -1, 31594, 31574, 31593, -1, 31595, 31574, 31594, -1, 31596, 31574, 31595, -1, 31597, 31574, 31596, -1, 31551, 31564, 31597, -1, 31597, 31565, 31574, -1, 31564, 31565, 31597, -1, 31565, 31517, 31574, -1, 31513, 31551, 31597, -1, 31518, 31520, 31567, -1, 31598, 31599, 31489, -1, 31600, 31601, 31602, -1, 31600, 31603, 31604, -1, 31602, 31603, 31600, -1, 31600, 31605, 31601, -1, 31600, 31606, 31605, -1, 31604, 31607, 31608, -1, 31603, 31607, 31604, -1, 31609, 31610, 31600, -1, 31600, 31610, 31606, -1, 31608, 31611, 31612, -1, 31607, 31611, 31608, -1, 31612, 31325, 31613, -1, 31613, 31325, 31614, -1, 31611, 31325, 31612, -1, 31609, 31615, 31610, -1, 31325, 31489, 31599, -1, 31325, 31599, 31614, -1, 31506, 31616, 31503, -1, 31617, 31616, 31506, -1, 31618, 31619, 31620, -1, 31496, 31619, 31621, -1, 31621, 31619, 31618, -1, 31498, 31622, 31619, -1, 31619, 31622, 31620, -1, 31620, 31622, 31623, -1, 31624, 31625, 31626, -1, 31623, 31625, 31624, -1, 31500, 31627, 31498, -1, 31623, 31627, 31625, -1, 31498, 31627, 31622, -1, 31622, 31627, 31623, -1, 31628, 31629, 31616, -1, 31626, 31629, 31628, -1, 31625, 31629, 31626, -1, 31502, 31630, 31500, -1, 31503, 31630, 31502, -1, 31616, 31630, 31503, -1, 31500, 31630, 31627, -1, 31627, 31630, 31625, -1, 31629, 31630, 31616, -1, 31625, 31630, 31629, -1, 31489, 31492, 31598, -1, 31492, 31494, 31598, -1, 31494, 31496, 31598, -1, 31631, 31632, 31633, -1, 31634, 31632, 31631, -1, 31598, 31632, 31634, -1, 31635, 31620, 31636, -1, 31618, 31620, 31635, -1, 31633, 31621, 31618, -1, 31598, 31621, 31632, -1, 31496, 31621, 31598, -1, 31632, 31621, 31633, -1, 31636, 31623, 31624, -1, 31620, 31623, 31636, -1, 31498, 31619, 31496, -1, 31637, 31638, 31315, -1, 31638, 31639, 31315, -1, 31639, 31640, 31315, -1, 31640, 31641, 31315, -1, 31315, 31642, 31313, -1, 31641, 31642, 31315, -1, 31642, 31643, 31313, -1, 31643, 31644, 31313, -1, 31644, 31645, 31313, -1, 31645, 31646, 31313, -1, 31647, 31648, 31649, -1, 31647, 31650, 31648, -1, 31649, 31651, 31647, -1, 31651, 31652, 31647, -1, 31647, 31653, 31650, -1, 31654, 31655, 31656, -1, 31652, 31657, 31647, -1, 31647, 31658, 31653, -1, 31656, 31659, 31660, -1, 31661, 31659, 31655, -1, 31655, 31659, 31656, -1, 31657, 31662, 31647, -1, 31663, 31664, 31647, -1, 31659, 31664, 31660, -1, 31665, 31664, 31663, -1, 31666, 31664, 31665, -1, 31662, 31667, 31647, -1, 31668, 31664, 31666, -1, 31669, 31664, 31668, -1, 31660, 31664, 31669, -1, 31667, 31670, 31647, -1, 31671, 31672, 31664, -1, 31670, 31673, 31647, -1, 31659, 31674, 31664, -1, 31664, 31674, 31671, -1, 31673, 31675, 31647, -1, 31672, 31676, 31664, -1, 31659, 31677, 31674, -1, 31676, 31678, 31664, -1, 31678, 31679, 31664, -1, 31659, 31680, 31677, -1, 31681, 31682, 31683, -1, 31679, 31684, 31664, -1, 31684, 31685, 31664, -1, 31685, 31686, 31664, -1, 31686, 31687, 31664, -1, 31688, 31689, 31682, -1, 31690, 31689, 31688, -1, 31687, 31691, 31664, -1, 31682, 31071, 31683, -1, 31691, 31692, 31664, -1, 31689, 31071, 31682, -1, 31683, 31071, 31693, -1, 31694, 31071, 31689, -1, 31071, 31073, 31693, -1, 31692, 31695, 31664, -1, 31696, 31073, 31675, -1, 31693, 31073, 31696, -1, 31675, 31073, 31647, -1, 31680, 31697, 31698, -1, 31659, 31697, 31680, -1, 31699, 31700, 31073, -1, 31701, 31700, 31699, -1, 31702, 31700, 31701, -1, 31698, 31703, 31704, -1, 31697, 31703, 31698, -1, 31073, 31705, 31647, -1, 31700, 31705, 31073, -1, 31706, 31707, 31697, -1, 31708, 31707, 31706, -1, 31705, 31709, 31647, -1, 31707, 31710, 31697, -1, 31709, 31711, 31647, -1, 31697, 31710, 31703, -1, 31711, 31712, 31647, -1, 31712, 31663, 31647, -1, 31658, 31713, 31714, -1, 31715, 31716, 31647, -1, 31647, 31717, 31715, -1, 31647, 31718, 31658, -1, 31716, 31718, 31647, -1, 31647, 31719, 31717, -1, 31718, 31720, 31658, -1, 31647, 31721, 31719, -1, 31720, 31722, 31658, -1, 31658, 31723, 31713, -1, 31722, 31723, 31658, -1, 31723, 31724, 31713, -1, 31724, 31725, 31713, -1, 31725, 31726, 31713, -1, 31727, 31728, 31729, -1, 31730, 31728, 31727, -1, 31731, 31728, 31730, -1, 31721, 31728, 31731, -1, 31647, 31728, 31721, -1, 31726, 31732, 31713, -1, 31732, 31733, 31713, -1, 31734, 31735, 31736, -1, 31737, 31735, 31734, -1, 31738, 31735, 31737, -1, 31729, 31735, 31738, -1, 31728, 31735, 31729, -1, 31739, 31740, 31733, -1, 31741, 31740, 31739, -1, 31742, 31740, 31741, -1, 31743, 31740, 31742, -1, 31736, 31740, 31743, -1, 31744, 31740, 31735, -1, 31735, 31740, 31736, -1, 31740, 31713, 31733, -1, 31745, 31746, 31721, -1, 31721, 31746, 31719, -1, 31719, 31747, 31717, -1, 31746, 31747, 31719, -1, 31717, 31748, 31715, -1, 31747, 31748, 31717, -1, 31715, 31749, 31716, -1, 31748, 31749, 31715, -1, 31716, 31750, 31718, -1, 31749, 31750, 31716, -1, 31718, 31751, 31720, -1, 31750, 31751, 31718, -1, 31720, 31752, 31722, -1, 31751, 31752, 31720, -1, 31722, 31753, 31723, -1, 31752, 31753, 31722, -1, 31723, 31754, 31724, -1, 31753, 31754, 31723, -1, 31724, 31755, 31725, -1, 31754, 31755, 31724, -1, 31725, 31756, 31726, -1, 31755, 31756, 31725, -1, 31726, 31757, 31732, -1, 31756, 31757, 31726, -1, 31732, 31758, 31733, -1, 31757, 31758, 31732, -1, 31759, 31760, 31761, -1, 31762, 31759, 31761, -1, 31762, 31763, 31759, -1, 31764, 31762, 31761, -1, 31765, 31766, 31767, -1, 31768, 31764, 31761, -1, 31769, 31770, 31766, -1, 31740, 31768, 31761, -1, 31771, 31770, 31769, -1, 31772, 31768, 31740, -1, 31773, 31770, 31771, -1, 31774, 31769, 31766, -1, 31775, 31774, 31766, -1, 31776, 31777, 31778, -1, 31776, 31778, 31779, -1, 31776, 31779, 31780, -1, 31781, 31775, 31766, -1, 31776, 31780, 31772, -1, 31776, 31772, 31740, -1, 31782, 31740, 31744, -1, 31782, 31776, 31740, -1, 31765, 31782, 31744, -1, 31783, 31781, 31766, -1, 31765, 31744, 31784, -1, 31785, 31766, 31765, -1, 31785, 31783, 31766, -1, 31786, 31785, 31765, -1, 31787, 31773, 31788, -1, 31787, 31788, 31789, -1, 31787, 31770, 31773, -1, 31790, 31786, 31765, -1, 31791, 31790, 31765, -1, 31784, 31791, 31765, -1, 31792, 31787, 31789, -1, 31793, 31787, 31792, -1, 31794, 31793, 31792, -1, 31795, 31796, 31793, -1, 31797, 31794, 31798, -1, 31797, 31793, 31794, -1, 31797, 31795, 31793, -1, 31799, 31795, 31797, -1, 31761, 31800, 31801, -1, 31761, 31760, 31800, -1, 31802, 31761, 31801, -1, 31802, 31803, 31761, -1, 31804, 31801, 31800, -1, 31804, 31802, 31801, -1, 31805, 31800, 31760, -1, 31805, 31804, 31800, -1, 31806, 31760, 31759, -1, 31806, 31805, 31760, -1, 31807, 31759, 31763, -1, 31807, 31806, 31759, -1, 31787, 31793, 31808, -1, 31809, 31787, 31808, -1, 31810, 31811, 31809, -1, 31810, 31809, 31808, -1, 31812, 31811, 31810, -1, 31813, 31814, 31815, -1, 31813, 31815, 31816, -1, 31817, 31813, 31816, -1, 31818, 31814, 31813, -1, 31819, 31818, 31813, -1, 31820, 31817, 31816, -1, 31821, 31822, 31817, -1, 31821, 31817, 31820, -1, 31823, 31824, 31825, -1, 31823, 31825, 31826, -1, 31827, 31828, 31829, -1, 31827, 31829, 31830, -1, 31831, 31830, 31832, -1, 31831, 31827, 31830, -1, 31833, 31831, 31832, -1, 31834, 31828, 31827, -1, 31766, 31770, 31831, -1, 31766, 31831, 31833, -1, 31816, 31830, 31829, -1, 31816, 31829, 31826, -1, 31816, 31826, 31825, -1, 31816, 31825, 31820, -1, 31835, 31836, 31824, -1, 31837, 31836, 31835, -1, 31838, 31835, 31824, -1, 31839, 31838, 31824, -1, 31840, 31839, 31824, -1, 31841, 31840, 31824, -1, 31842, 31824, 31823, -1, 31842, 31841, 31824, -1, 31843, 31842, 31823, -1, 31844, 31843, 31823, -1, 31845, 31844, 31823, -1, 31846, 31845, 31823, -1, 31847, 31848, 31846, -1, 31847, 31846, 31823, -1, 31849, 31850, 31814, -1, 31851, 31852, 31853, -1, 31854, 31855, 31856, -1, 31857, 31849, 31814, -1, 31858, 31852, 31851, -1, 31859, 31860, 31861, -1, 31862, 31857, 31814, -1, 31863, 31814, 31864, -1, 31865, 31855, 31854, -1, 31866, 31859, 31861, -1, 31866, 31861, 31833, -1, 31863, 31862, 31814, -1, 31867, 31852, 31858, -1, 31868, 31866, 31833, -1, 31869, 31864, 31870, -1, 31869, 31863, 31864, -1, 31871, 31868, 31833, -1, 31872, 31873, 31874, -1, 31874, 31873, 31875, -1, 31875, 31873, 31876, -1, 31876, 31873, 31877, -1, 31872, 31874, 31878, -1, 31875, 31876, 31879, -1, 31880, 31871, 31833, -1, 31875, 31879, 31881, -1, 31875, 31881, 31882, -1, 31883, 31880, 31833, -1, 31873, 31884, 31877, -1, 31873, 31885, 31884, -1, 31873, 31886, 31885, -1, 31887, 31888, 31889, -1, 31832, 31883, 31833, -1, 31873, 31890, 31886, -1, 31887, 31889, 31891, -1, 31873, 31892, 31890, -1, 31887, 31891, 31893, -1, 31887, 31893, 31894, -1, 31887, 31894, 31895, -1, 31887, 31895, 31896, -1, 31897, 31832, 31872, -1, 31897, 31883, 31832, -1, 31882, 31896, 31875, -1, 31898, 31897, 31872, -1, 31882, 31887, 31896, -1, 31899, 31883, 31897, -1, 31900, 31865, 31901, -1, 31900, 31901, 31902, -1, 31900, 31902, 31903, -1, 31900, 31903, 31888, -1, 31900, 31888, 31887, -1, 31900, 31855, 31865, -1, 31904, 31905, 31899, -1, 31906, 31907, 31904, -1, 31906, 31899, 31897, -1, 31906, 31904, 31899, -1, 31908, 31882, 31881, -1, 31908, 31909, 31882, -1, 31910, 31911, 31872, -1, 31912, 31872, 31911, -1, 31913, 31910, 31872, -1, 31914, 31915, 31916, -1, 31917, 31892, 31873, -1, 31917, 31918, 31919, -1, 31914, 31916, 31881, -1, 31920, 31906, 31897, -1, 31917, 31921, 31918, -1, 31922, 31916, 31915, -1, 31923, 31898, 31872, -1, 31917, 31919, 31892, -1, 31923, 31872, 31912, -1, 31924, 31873, 31815, -1, 31924, 31917, 31873, -1, 31879, 31914, 31881, -1, 31878, 31913, 31872, -1, 31925, 31916, 31922, -1, 31926, 31898, 31923, -1, 31927, 31852, 31867, -1, 31927, 31921, 31917, -1, 31927, 31928, 31921, -1, 31927, 31929, 31928, -1, 31927, 31930, 31929, -1, 31927, 31931, 31930, -1, 31932, 31916, 31925, -1, 31927, 31867, 31931, -1, 31933, 31898, 31926, -1, 31934, 31935, 31924, -1, 31936, 31855, 31898, -1, 31937, 31916, 31932, -1, 31936, 31898, 31933, -1, 31938, 31939, 31934, -1, 31940, 31855, 31936, -1, 31941, 31916, 31937, -1, 31941, 31852, 31916, -1, 31942, 31855, 31940, -1, 31850, 31815, 31814, -1, 31853, 31852, 31941, -1, 31850, 31924, 31815, -1, 31943, 31944, 31938, -1, 31943, 31934, 31924, -1, 31856, 31855, 31942, -1, 31943, 31938, 31934, -1, 31943, 31924, 31850, -1, 31945, 31919, 31946, -1, 31945, 31946, 31947, -1, 31945, 31947, 31948, -1, 31945, 31948, 31890, -1, 31949, 31950, 31951, -1, 31949, 31951, 31952, -1, 31949, 31952, 31932, -1, 31949, 31953, 31950, -1, 31954, 31932, 31925, -1, 31954, 31925, 31922, -1, 31954, 31949, 31932, -1, 31954, 31922, 31953, -1, 31954, 31953, 31949, -1, 31955, 31956, 31957, -1, 31955, 31957, 31958, -1, 31955, 31885, 31886, -1, 31955, 31886, 31890, -1, 31955, 31948, 31956, -1, 31955, 31890, 31948, -1, 31959, 31958, 31960, -1, 31959, 31960, 31961, -1, 31959, 31877, 31884, -1, 31959, 31884, 31885, -1, 31959, 31955, 31958, -1, 31959, 31885, 31955, -1, 31962, 31961, 31963, -1, 31962, 31876, 31877, -1, 31962, 31877, 31959, -1, 31962, 31959, 31961, -1, 31964, 31963, 31965, -1, 31964, 31965, 31966, -1, 31964, 31914, 31879, -1, 31964, 31879, 31876, -1, 31964, 31962, 31963, -1, 31964, 31876, 31962, -1, 31967, 31966, 31968, -1, 31967, 31968, 31950, -1, 31967, 31922, 31915, -1, 31967, 31915, 31914, -1, 31967, 31914, 31964, -1, 31967, 31964, 31966, -1, 31953, 31967, 31950, -1, 31953, 31922, 31967, -1, 31947, 31946, 31969, -1, 31947, 31969, 31956, -1, 31947, 31956, 31948, -1, 31945, 31890, 31892, -1, 31945, 31892, 31919, -1, 31970, 31888, 31971, -1, 31970, 31971, 31972, -1, 31973, 31974, 31975, -1, 31973, 31976, 31974, -1, 31973, 31975, 31977, -1, 31978, 31933, 31926, -1, 31978, 31936, 31933, -1, 31978, 31926, 31976, -1, 31978, 31973, 31977, -1, 31978, 31977, 31936, -1, 31978, 31976, 31973, -1, 31979, 31980, 31981, -1, 31979, 31972, 31980, -1, 31979, 31981, 31891, -1, 31979, 31970, 31972, -1, 31982, 31889, 31888, -1, 31982, 31891, 31889, -1, 31982, 31888, 31970, -1, 31982, 31979, 31891, -1, 31982, 31970, 31979, -1, 31983, 31984, 31985, -1, 31983, 31975, 31984, -1, 31983, 31940, 31936, -1, 31983, 31942, 31940, -1, 31983, 31936, 31977, -1, 31983, 31977, 31975, -1, 31986, 31987, 31988, -1, 31986, 31985, 31987, -1, 31986, 31856, 31942, -1, 31986, 31854, 31856, -1, 31986, 31983, 31985, -1, 31986, 31942, 31983, -1, 31989, 31988, 31990, -1, 31989, 31865, 31854, -1, 31989, 31986, 31988, -1, 31989, 31854, 31986, -1, 31991, 31992, 31993, -1, 31991, 31990, 31992, -1, 31991, 31901, 31865, -1, 31991, 31902, 31901, -1, 31991, 31865, 31989, -1, 31991, 31989, 31990, -1, 31971, 31994, 31972, -1, 31971, 31993, 31994, -1, 31971, 31903, 31902, -1, 31971, 31888, 31903, -1, 31971, 31902, 31991, -1, 31971, 31991, 31993, -1, 31995, 31996, 31997, -1, 31998, 31996, 31995, -1, 31999, 31996, 31998, -1, 32000, 31999, 31998, -1, 32001, 32000, 31998, -1, 32002, 32001, 31998, -1, 31860, 32003, 32004, -1, 31860, 32004, 32005, -1, 31860, 32005, 32006, -1, 31860, 32006, 32007, -1, 31861, 31860, 32007, -1, 31998, 31861, 32007, -1, 31998, 32007, 32002, -1, 32001, 32002, 32008, -1, 32000, 32008, 32009, -1, 32000, 32001, 32008, -1, 32010, 31999, 32000, -1, 32010, 32000, 32009, -1, 32011, 32012, 32013, -1, 32011, 32009, 32012, -1, 32011, 32013, 32014, -1, 32011, 32015, 31999, -1, 32011, 32016, 32015, -1, 32011, 32014, 32016, -1, 32011, 32010, 32009, -1, 32011, 31999, 32010, -1, 32017, 32018, 32019, -1, 32017, 32019, 32020, -1, 32021, 32022, 32023, -1, 32021, 32013, 32022, -1, 32021, 32023, 32024, -1, 32025, 32026, 32014, -1, 32025, 32027, 32026, -1, 32025, 32014, 32013, -1, 32025, 32021, 32024, -1, 32025, 32024, 32027, -1, 32025, 32013, 32021, -1, 32028, 32029, 32030, -1, 32028, 32020, 32029, -1, 32028, 32030, 32031, -1, 32028, 32017, 32020, -1, 32032, 32033, 32018, -1, 32032, 32031, 32033, -1, 32032, 32028, 32031, -1, 32032, 32018, 32017, -1, 32032, 32017, 32028, -1, 32034, 32035, 32036, -1, 32034, 32023, 32035, -1, 32034, 32037, 32027, -1, 32034, 32038, 32037, -1, 32034, 32027, 32024, -1, 32034, 32024, 32023, -1, 32039, 32040, 32041, -1, 32039, 32036, 32040, -1, 32039, 32042, 32038, -1, 32039, 32043, 32042, -1, 32039, 32034, 32036, -1, 32039, 32038, 32034, -1, 32044, 32041, 32045, -1, 32044, 32046, 32043, -1, 32044, 32039, 32041, -1, 32044, 32043, 32039, -1, 32047, 32048, 32049, -1, 32047, 32045, 32048, -1, 32047, 32050, 32046, -1, 32047, 32051, 32050, -1, 32047, 32046, 32044, -1, 32047, 32044, 32045, -1, 32019, 32052, 32020, -1, 32019, 32049, 32052, -1, 32019, 32053, 32051, -1, 32019, 32018, 32053, -1, 32019, 32051, 32047, -1, 32019, 32047, 32049, -1, 31834, 31811, 31828, -1, 31809, 31811, 31834, -1, 31776, 32054, 32055, -1, 31776, 31782, 32054, -1, 32018, 32033, 31860, -1, 31996, 32056, 32057, -1, 32058, 32056, 31996, -1, 31859, 32059, 32046, -1, 31859, 32046, 32050, -1, 31859, 32050, 32051, -1, 31859, 32018, 31860, -1, 31859, 32051, 32053, -1, 31859, 32053, 32018, -1, 32016, 31996, 32015, -1, 32060, 32058, 32061, -1, 32062, 32060, 32061, -1, 32014, 31996, 32016, -1, 32063, 32060, 32062, -1, 31996, 31999, 32015, -1, 32026, 31996, 32014, -1, 32064, 32058, 31996, -1, 32065, 32058, 32064, -1, 32066, 31996, 32026, -1, 32066, 32064, 31996, -1, 32067, 32058, 32065, -1, 32068, 32058, 32067, -1, 32069, 32026, 32027, -1, 32069, 32066, 32026, -1, 32070, 32058, 32068, -1, 32059, 32027, 32037, -1, 32059, 32037, 32038, -1, 32059, 32038, 32042, -1, 32059, 32069, 32027, -1, 32071, 32058, 32070, -1, 32043, 32059, 32042, -1, 32072, 32058, 32071, -1, 32046, 32059, 32043, -1, 32061, 32058, 32072, -1, 31860, 32033, 32031, -1, 31860, 32031, 32073, -1, 31860, 32073, 32074, -1, 31860, 32074, 32003, -1, 32058, 32060, 32075, -1, 32058, 32075, 32076, -1, 32077, 32063, 32062, -1, 32062, 32078, 32077, -1, 32076, 32079, 31997, -1, 32076, 32080, 32079, -1, 32079, 31995, 31997, -1, 32079, 32081, 31995, -1, 32076, 32075, 32080, -1, 32075, 32082, 32080, -1, 32083, 32084, 32085, -1, 32081, 32086, 31995, -1, 32083, 32087, 32084, -1, 32086, 32088, 31995, -1, 32089, 32088, 32086, -1, 32089, 32090, 32088, -1, 32086, 32084, 32089, -1, 32089, 32084, 32087, -1, 32088, 31998, 31995, -1, 32088, 32091, 31998, -1, 32092, 32093, 32094, -1, 32093, 32095, 32094, -1, 32094, 32096, 32097, -1, 32097, 32098, 32094, -1, 32094, 32099, 32096, -1, 32098, 32100, 32094, -1, 32094, 32101, 32099, -1, 32100, 32102, 32094, -1, 32103, 32104, 32105, -1, 32094, 32106, 32101, -1, 32104, 32107, 32105, -1, 32105, 31810, 32108, -1, 32102, 32109, 32094, -1, 32107, 31810, 32105, -1, 32110, 31728, 32095, -1, 32111, 31728, 32110, -1, 32112, 31728, 32111, -1, 32108, 31728, 32112, -1, 32109, 32113, 32094, -1, 32095, 31728, 32094, -1, 31810, 31728, 32108, -1, 32113, 32114, 32094, -1, 32115, 32116, 31728, -1, 32114, 32117, 32094, -1, 31810, 32118, 31728, -1, 31728, 32118, 32115, -1, 32117, 32119, 32094, -1, 32116, 32120, 31728, -1, 31810, 32121, 32118, -1, 32120, 32122, 31728, -1, 31810, 32123, 32121, -1, 32122, 32124, 31728, -1, 32125, 32126, 32127, -1, 32124, 32128, 31728, -1, 32128, 32129, 31728, -1, 32129, 32130, 31728, -1, 32130, 32131, 31728, -1, 32132, 32133, 32134, -1, 32131, 32135, 31728, -1, 32126, 32136, 32127, -1, 32135, 32137, 31728, -1, 32133, 32136, 32134, -1, 32127, 32136, 32138, -1, 32134, 32136, 32126, -1, 32139, 32136, 32133, -1, 32137, 31735, 31728, -1, 32136, 32140, 32138, -1, 32141, 32140, 32119, -1, 31810, 31808, 32123, -1, 32138, 32140, 32141, -1, 32119, 32140, 32094, -1, 31808, 32142, 32123, -1, 32143, 32144, 32140, -1, 32145, 32144, 32143, -1, 32146, 32144, 32145, -1, 32142, 32147, 32148, -1, 31808, 32147, 32142, -1, 32140, 32149, 32094, -1, 32144, 32149, 32140, -1, 32150, 32151, 31808, -1, 32152, 32151, 32150, -1, 32149, 32153, 32094, -1, 32151, 32154, 31808, -1, 31808, 32154, 32147, -1, 32153, 32155, 32094, -1, 32155, 32092, 32094, -1, 32156, 32157, 31664, -1, 31664, 32158, 32156, -1, 32157, 32159, 31664, -1, 32159, 32160, 31664, -1, 31664, 32161, 32158, -1, 32160, 32162, 31664, -1, 32163, 31728, 32164, -1, 32165, 31728, 32163, -1, 32166, 31728, 32165, -1, 32167, 31728, 32166, -1, 32162, 32168, 31664, -1, 32169, 31728, 32170, -1, 32171, 31728, 32169, -1, 32172, 31728, 32171, -1, 31664, 32173, 32161, -1, 32174, 31728, 32172, -1, 32175, 31728, 32174, -1, 32164, 31728, 32175, -1, 32170, 31728, 31647, -1, 32094, 31728, 32167, -1, 32168, 32176, 31664, -1, 32094, 32167, 32177, -1, 31664, 32094, 32173, -1, 32094, 32178, 32173, -1, 32094, 32179, 32178, -1, 32094, 32180, 32179, -1, 32094, 32181, 32180, -1, 32094, 32182, 32181, -1, 32094, 32183, 32182, -1, 32094, 32184, 32183, -1, 32094, 32185, 32184, -1, 32094, 32186, 32185, -1, 32094, 32177, 32186, -1, 32187, 31647, 32176, -1, 32188, 31647, 32187, -1, 32189, 31647, 32188, -1, 32190, 31647, 32189, -1, 32191, 31647, 32190, -1, 32192, 31647, 32191, -1, 32193, 31647, 32192, -1, 32194, 31647, 32193, -1, 32195, 31647, 32194, -1, 32170, 31647, 32195, -1, 32176, 31647, 31664, -1, 31816, 31872, 31830, -1, 31873, 31872, 31816, -1, 31872, 31832, 31830, -1, 31765, 31767, 32196, -1, 2404, 32197, 32198, -1, 32199, 2403, 32200, -1, 32197, 2403, 32199, -1, 2404, 2403, 32197, -1, 32201, 32202, 32203, -1, 32202, 32204, 32203, -1, 32201, 32205, 32202, -1, 32204, 32206, 32203, -1, 32201, 32207, 32205, -1, 32206, 32208, 32203, -1, 32208, 32209, 32203, -1, 32203, 32210, 32197, -1, 32209, 32210, 32203, -1, 32210, 32198, 32197, -1, 32211, 32212, 32213, -1, 32214, 32215, 32212, -1, 32200, 32214, 32212, -1, 32200, 32212, 32211, -1, 32216, 32199, 32200, -1, 32216, 32200, 32211, -1, 32199, 32216, 32203, -1, 32199, 32203, 32197, -1, 32217, 32213, 32218, -1, 32211, 32213, 32217, -1, 32217, 32219, 32220, -1, 32217, 32218, 32219, -1, 32220, 32221, 32222, -1, 32220, 32219, 32221, -1, 32223, 32224, 32225, -1, 32226, 32227, 32228, -1, 32226, 32228, 32224, -1, 32222, 32221, 32226, -1, 32222, 32226, 32224, -1, 32222, 32224, 32223, -1, 32225, 32229, 32223, -1, 32230, 32229, 32225, -1, 32231, 32232, 32233, -1, 32231, 32234, 32232, -1, 32234, 32229, 32235, -1, 32235, 32229, 32236, -1, 32236, 32229, 32237, -1, 32237, 32229, 32238, -1, 32238, 32229, 32239, -1, 32231, 32229, 32234, -1, 32239, 32230, 32240, -1, 32229, 32230, 32239, -1, 32201, 32241, 32207, -1, 32242, 32243, 32241, -1, 32241, 32243, 32207, -1, 32244, 32245, 32242, -1, 32246, 32245, 32244, -1, 32242, 32247, 32243, -1, 32245, 32247, 32242, -1, 32248, 32249, 32247, -1, 32250, 32249, 32248, -1, 32251, 32252, 32250, -1, 32250, 32252, 32249, -1, 32251, 32253, 32252, -1, 32254, 32252, 32253, -1, 32249, 32243, 32247, -1, 32255, 32256, 32257, -1, 32258, 32255, 32257, -1, 32259, 32255, 32258, -1, 32260, 32259, 32258, -1, 32261, 32259, 32260, -1, 32262, 32256, 32255, -1, 32263, 32256, 32262, -1, 32264, 32263, 32262, -1, 32247, 32260, 32248, -1, 32247, 32261, 32260, -1, 32265, 32266, 32267, -1, 32256, 32265, 32267, -1, 32263, 32268, 32265, -1, 32263, 32265, 32256, -1, 32269, 32265, 32268, -1, 32269, 32270, 32265, -1, 32269, 32271, 32272, -1, 32269, 32272, 32270, -1, 32273, 32274, 32275, -1, 32274, 32276, 32275, -1, 32274, 32277, 32276, -1, 32277, 32278, 32276, -1, 32277, 32279, 32278, -1, 32273, 32280, 32274, -1, 32273, 32281, 32280, -1, 32281, 32282, 32280, -1, 32278, 32245, 32246, -1, 32279, 32245, 32278, -1, 32283, 32281, 32273, -1, 32284, 32281, 32283, -1, 32285, 32283, 32273, -1, 32284, 32286, 32287, -1, 32284, 32283, 32286, -1, 32288, 32287, 32286, -1, 32289, 32287, 32288, -1, 32264, 32262, 32282, -1, 32282, 32262, 32280, -1, 32289, 32290, 32291, -1, 32289, 32288, 32290, -1, 32290, 32292, 32291, -1, 32293, 32292, 32290, -1, 32294, 32293, 32290, -1, 32271, 32295, 32272, -1, 32296, 32295, 32271, -1, 32295, 32296, 32297, -1, 32295, 32298, 32299, -1, 32300, 32295, 32297, -1, 32300, 32298, 32295, -1, 32301, 32297, 32302, -1, 32300, 32297, 32301, -1, 32303, 32300, 32301, -1, 32304, 32300, 32303, -1, 32305, 32306, 32307, -1, 32308, 32303, 32306, -1, 32308, 32304, 32303, -1, 32308, 32306, 32305, -1, 32309, 32305, 32307, -1, 32310, 32305, 32309, -1, 32292, 32311, 32312, -1, 32292, 32293, 32311, -1, 32313, 32314, 32293, -1, 32293, 32314, 32311, -1, 32315, 32316, 32317, -1, 32314, 32318, 32315, -1, 32313, 32318, 32314, -1, 32315, 32318, 32316, -1, 32316, 32319, 32317, -1, 32316, 32320, 32319, -1, 32312, 32311, 32302, -1, 32302, 32311, 32301, -1, 32321, 32322, 32254, -1, 32321, 32254, 32253, -1, 32323, 32321, 32253, -1, 32324, 32323, 32253, -1, 32325, 32324, 32253, -1, 32326, 32325, 32253, -1, 32327, 32326, 32253, -1, 32328, 32326, 32327, -1, 32329, 32328, 32327, -1, 32330, 32329, 32327, -1, 32331, 32330, 32327, -1, 32332, 32331, 32327, -1, 32333, 32334, 32332, -1, 32333, 32332, 32327, -1, 32246, 32335, 32278, -1, 32246, 32244, 32335, -1, 32276, 32336, 32337, -1, 32276, 32337, 32275, -1, 32336, 32276, 32278, -1, 32336, 32278, 32335, -1, 32285, 32338, 32339, -1, 32285, 32337, 32338, -1, 32285, 32273, 32275, -1, 32275, 32337, 32285, -1, 32251, 32250, 32340, -1, 32341, 32342, 32343, -1, 32341, 32340, 32342, -1, 32344, 32341, 32345, -1, 32344, 32251, 32340, -1, 32344, 32340, 32341, -1, 32327, 32251, 32344, -1, 32327, 32253, 32251, -1, 32340, 32248, 32260, -1, 32250, 32248, 32340, -1, 32339, 32338, 32346, -1, 32339, 32346, 32347, -1, 31019, 2343, 31012, -1, 31012, 2345, 31013, -1, 2343, 2345, 31012, -1, 32214, 2410, 32215, -1, 2408, 2410, 32214, -1, 32348, 32304, 32308, -1, 32343, 32349, 32350, -1, 32343, 32350, 32351, -1, 32343, 32351, 32348, -1, 32343, 32348, 32308, -1, 32352, 32349, 32343, -1, 32353, 32352, 32343, -1, 32354, 32353, 32343, -1, 32355, 32354, 32343, -1, 32356, 32258, 32257, -1, 32357, 32355, 32343, -1, 32342, 32358, 32357, -1, 32342, 32359, 32358, -1, 32342, 32360, 32359, -1, 32342, 32361, 32360, -1, 32342, 32362, 32361, -1, 32342, 32363, 32362, -1, 32342, 32356, 32363, -1, 32342, 32258, 32356, -1, 32342, 32357, 32343, -1, 32364, 31034, 31032, -1, 32364, 31032, 32365, -1, 32366, 31028, 32364, -1, 32366, 32364, 32365, -1, 31023, 31025, 31028, -1, 31023, 31028, 32366, -1, 30998, 32366, 30994, -1, 30998, 31023, 32366, -1, 32056, 32367, 32368, -1, 32057, 32056, 32368, -1, 32369, 32367, 32370, -1, 32369, 32368, 32367, -1, 32371, 32370, 32372, -1, 32371, 32369, 32370, -1, 32373, 32370, 32367, -1, 32374, 32375, 32370, -1, 32376, 32377, 32373, -1, 32373, 32377, 32370, -1, 32370, 32377, 32374, -1, 32377, 32378, 32374, -1, 32379, 32380, 32378, -1, 32380, 32374, 32378, -1, 32373, 32381, 32376, -1, 32382, 32381, 32373, -1, 32383, 32382, 32384, -1, 32385, 32382, 32383, -1, 32386, 32383, 32384, -1, 32387, 32383, 32386, -1, 32381, 32382, 32385, -1, 32388, 32381, 32385, -1, 32389, 32390, 32391, -1, 32392, 32387, 32386, -1, 32393, 32390, 32389, -1, 32394, 32392, 32386, -1, 32394, 32395, 32392, -1, 32396, 32395, 32394, -1, 32395, 32393, 32392, -1, 32392, 32393, 32389, -1, 32397, 32380, 32398, -1, 32374, 32380, 32397, -1, 32399, 32384, 32400, -1, 32399, 32400, 32401, -1, 32386, 32384, 32399, -1, 32402, 32399, 32401, -1, 32371, 32403, 32369, -1, 32404, 32403, 32371, -1, 32372, 32375, 32405, -1, 32370, 32375, 32372, -1, 32406, 32407, 32375, -1, 32375, 32407, 32405, -1, 32404, 32371, 32372, -1, 32404, 32372, 32405, -1, 32408, 32404, 32405, -1, 32367, 32382, 32373, -1, 32056, 32382, 32367, -1, 32056, 32076, 32382, -1, 32056, 32058, 32076, -1, 32401, 32369, 32403, -1, 32401, 32400, 32368, -1, 32401, 32368, 32369, -1, 32384, 32368, 32400, -1, 31997, 32057, 32368, -1, 31997, 32368, 32384, -1, 31996, 32057, 31997, -1, 32402, 32401, 32403, -1, 32404, 32402, 32403, -1, 32408, 32402, 32404, -1, 32409, 32402, 32408, -1, 32410, 32399, 32402, -1, 32411, 32399, 32410, -1, 32409, 32410, 32402, -1, 32411, 32394, 32386, -1, 32411, 32386, 32399, -1, 32196, 31767, 31833, -1, 31766, 31833, 31767, -1, 31998, 32091, 32196, -1, 31998, 31833, 31861, -1, 31998, 32196, 31833, -1, 32374, 32397, 32406, -1, 32374, 32406, 32375, -1, 31034, 31028, 31027, -1, 31034, 32364, 31028, -1, 32366, 30995, 30994, -1, 32366, 31030, 30995, -1, 31013, 2344, 31014, -1, 2345, 2344, 31013, -1, 2403, 2408, 32214, -1, 2403, 32214, 32200, -1, 2409, 32212, 32215, -1, 2409, 32215, 2410, -1, 32212, 2409, 32213, -1, 2409, 32218, 32213, -1, 32221, 2415, 32226, -1, 32219, 2415, 32221, -1, 2409, 2415, 32218, -1, 32218, 2415, 32219, -1, 31014, 2344, 31010, -1, 2344, 31008, 31010, -1, 31008, 2377, 31009, -1, 2344, 2377, 31008, -1, 2346, 31019, 31018, -1, 2346, 2343, 31019, -1, 30393, 31041, 30962, -1, 2368, 32412, 30393, -1, 30393, 32412, 31041, -1, 2368, 32413, 32412, -1, 31068, 32414, 31067, -1, 32413, 32414, 31068, -1, 32415, 31016, 31020, -1, 31016, 2346, 31018, -1, 32415, 2346, 31016, -1, 2368, 2346, 32415, -1, 2368, 32415, 32414, -1, 2368, 32414, 32413, -1, 30980, 31069, 30982, -1, 30979, 30980, 30982, -1, 32380, 32416, 32398, -1, 32393, 32380, 32379, -1, 32390, 32393, 32379, -1, 31138, 32087, 32417, -1, 31136, 31138, 32417, -1, 32418, 32417, 32087, -1, 32419, 32087, 32083, -1, 32419, 32418, 32087, -1, 31138, 31069, 32393, -1, 32393, 31069, 32416, -1, 32416, 31069, 30980, -1, 31138, 32393, 32087, -1, 32393, 32416, 32380, -1, 32418, 32420, 32421, -1, 32417, 32418, 32421, -1, 32418, 32419, 32420, -1, 32260, 32342, 32340, -1, 32258, 32342, 32260, -1, 32365, 31032, 31030, -1, 32366, 32365, 31030, -1, 32422, 32356, 32267, -1, 32267, 32257, 32256, -1, 32356, 32257, 32267, -1, 32363, 32356, 32422, -1, 32363, 32422, 32423, -1, 32363, 32423, 32424, -1, 32362, 32424, 32425, -1, 32362, 32363, 32424, -1, 32361, 32425, 32426, -1, 32361, 32362, 32425, -1, 32360, 32426, 32427, -1, 32360, 32361, 32426, -1, 32359, 32427, 32428, -1, 32359, 32360, 32427, -1, 32358, 32428, 32429, -1, 32358, 32359, 32428, -1, 32357, 32429, 32430, -1, 32357, 32358, 32429, -1, 32431, 32357, 32430, -1, 32355, 32357, 32431, -1, 2402, 32210, 32209, -1, 2405, 32209, 32208, -1, 2405, 2402, 32209, -1, 2406, 32208, 32206, -1, 2406, 2405, 32208, -1, 2407, 32204, 32202, -1, 2407, 32206, 32204, -1, 2407, 2406, 32206, -1, 2419, 32202, 32205, -1, 2419, 2407, 32202, -1, 2420, 2419, 32205, -1, 32243, 32205, 32207, -1, 32243, 2420, 32205, -1, 2421, 32243, 32432, -1, 2421, 2420, 32243, -1, 2424, 32432, 32433, -1, 2424, 2421, 32432, -1, 30986, 30985, 31001, -1, 30986, 2424, 32433, -1, 2390, 31001, 31002, -1, 2390, 30986, 31001, -1, 2390, 2424, 30986, -1, 2388, 31002, 31007, -1, 2388, 2390, 31002, -1, 2385, 31007, 31006, -1, 2385, 2388, 31007, -1, 2382, 31006, 31003, -1, 2382, 2385, 31006, -1, 2378, 31003, 31005, -1, 2378, 2382, 31003, -1, 2376, 2378, 31005, -1, 2402, 2404, 32198, -1, 32210, 2402, 32198, -1, 2376, 31005, 31009, -1, 2376, 31009, 2377, -1, 2371, 2568, 31052, -1, 2372, 31051, 31050, -1, 2372, 31052, 31051, -1, 2372, 2371, 31052, -1, 2373, 31050, 31049, -1, 2373, 2372, 31050, -1, 2374, 31048, 31047, -1, 2374, 31049, 31048, -1, 2374, 2373, 31049, -1, 2490, 31057, 31056, -1, 2490, 31047, 31057, -1, 2490, 2374, 31047, -1, 2499, 31056, 31055, -1, 2499, 2490, 31056, -1, 2433, 31055, 31054, -1, 2433, 2499, 31055, -1, 2431, 31054, 31053, -1, 2431, 2433, 31054, -1, 2434, 31053, 31046, -1, 2434, 2431, 31053, -1, 2358, 31046, 31045, -1, 2358, 2434, 31046, -1, 2355, 2358, 31045, -1, 31044, 2355, 31045, -1, 2353, 2355, 31044, -1, 31043, 2353, 31044, -1, 2350, 2353, 31043, -1, 2350, 31043, 31042, -1, 2351, 2350, 31042, -1, 32430, 32434, 32431, -1, 32435, 32434, 32430, -1, 32436, 32437, 32438, -1, 32439, 32440, 32437, -1, 32439, 32437, 32436, -1, 32441, 32427, 32426, -1, 32441, 32426, 32440, -1, 32441, 32440, 32439, -1, 32442, 32438, 32443, -1, 32442, 32436, 32438, -1, 32444, 32439, 32436, -1, 32444, 32436, 32442, -1, 32445, 32428, 32427, -1, 32445, 32427, 32441, -1, 32445, 32441, 32439, -1, 32445, 32439, 32444, -1, 32446, 32443, 32435, -1, 32446, 32435, 32430, -1, 32446, 32442, 32443, -1, 32447, 32444, 32442, -1, 32447, 32446, 32430, -1, 32447, 32442, 32446, -1, 32448, 32429, 32428, -1, 32448, 32430, 32429, -1, 32448, 32444, 32447, -1, 32448, 32428, 32445, -1, 32448, 32445, 32444, -1, 32448, 32447, 32430, -1, 32449, 32266, 32450, -1, 32451, 32267, 32266, -1, 32451, 32266, 32449, -1, 32452, 32450, 32453, -1, 32452, 32449, 32450, -1, 32454, 32451, 32449, -1, 32454, 32452, 32453, -1, 32454, 32449, 32452, -1, 32455, 32453, 32456, -1, 32455, 32454, 32453, -1, 32457, 32456, 32458, -1, 32457, 32455, 32456, -1, 32459, 32423, 32422, -1, 32459, 32422, 32267, -1, 32459, 32267, 32451, -1, 32460, 32451, 32454, -1, 32460, 32423, 32459, -1, 32460, 32459, 32451, -1, 32461, 32424, 32423, -1, 32461, 32423, 32460, -1, 32462, 32454, 32455, -1, 32462, 32460, 32454, -1, 32463, 32425, 32424, -1, 32463, 32424, 32461, -1, 32463, 32461, 32460, -1, 32463, 32460, 32462, -1, 32437, 32458, 32438, -1, 32437, 32457, 32458, -1, 32437, 32455, 32457, -1, 32437, 32462, 32455, -1, 32440, 32426, 32425, -1, 32440, 32425, 32463, -1, 32440, 32463, 32462, -1, 32440, 32462, 32437, -1, 32464, 32434, 32465, -1, 32466, 32434, 32464, -1, 32467, 32434, 32466, -1, 32468, 32434, 32467, -1, 32469, 32434, 32468, -1, 32434, 32299, 32465, -1, 32434, 32435, 32299, -1, 32443, 32438, 32435, -1, 32438, 32458, 32435, -1, 32458, 32456, 32435, -1, 32456, 32453, 32435, -1, 32453, 32450, 32435, -1, 32435, 32266, 32299, -1, 32450, 32266, 32435, -1, 32272, 32295, 32299, -1, 32266, 32270, 32299, -1, 32299, 32270, 32272, -1, 32266, 32265, 32270, -1, 32283, 32285, 32339, -1, 32286, 32283, 32339, -1, 32288, 32339, 32347, -1, 32288, 32286, 32339, -1, 32290, 32347, 32294, -1, 32290, 32288, 32347, -1, 31782, 31757, 32054, -1, 31782, 32091, 32470, -1, 31782, 31765, 32091, -1, 32396, 32394, 32411, -1, 32396, 32411, 32410, -1, 32091, 31765, 32196, -1, 32054, 32090, 32396, -1, 32054, 32396, 32410, -1, 31749, 32088, 32090, -1, 31749, 31748, 32088, -1, 31747, 32088, 31748, -1, 31750, 31749, 32090, -1, 31746, 32091, 32088, -1, 31746, 32088, 31747, -1, 31751, 31750, 32090, -1, 31745, 32091, 31746, -1, 31752, 31751, 32090, -1, 32471, 32091, 31745, -1, 31753, 31752, 32090, -1, 32472, 32091, 32471, -1, 31754, 31753, 32090, -1, 32473, 32091, 32472, -1, 31755, 32090, 32054, -1, 31755, 31754, 32090, -1, 32474, 32091, 32473, -1, 31756, 31755, 32054, -1, 32475, 32091, 32474, -1, 31757, 31756, 32054, -1, 32470, 32091, 32475, -1, 31782, 32476, 31758, -1, 31782, 32477, 32476, -1, 31782, 32478, 32477, -1, 31782, 32479, 32478, -1, 31782, 32480, 32479, -1, 31782, 32481, 32480, -1, 31782, 32470, 32481, -1, 31782, 31758, 31757, -1, 32482, 31803, 31806, -1, 32482, 31806, 31807, -1, 32483, 31803, 32482, -1, 32484, 32410, 32485, -1, 32486, 31803, 32483, -1, 32487, 32410, 32484, -1, 32486, 31713, 31803, -1, 32488, 32485, 32410, -1, 32055, 32054, 31713, -1, 32489, 32410, 32409, -1, 32489, 32488, 32410, -1, 32490, 31713, 32486, -1, 32490, 32055, 31713, -1, 32491, 32410, 32487, -1, 32492, 32493, 32055, -1, 32494, 32055, 32490, -1, 32495, 32492, 32055, -1, 32495, 32055, 32494, -1, 31070, 31072, 32496, -1, 32497, 32489, 32409, -1, 31070, 32496, 32498, -1, 31070, 32498, 32499, -1, 32500, 32497, 32409, -1, 31070, 32499, 32409, -1, 32501, 32500, 32409, -1, 32054, 32410, 31714, -1, 31714, 32410, 32491, -1, 32502, 32501, 32409, -1, 32503, 32502, 32409, -1, 32504, 32503, 32409, -1, 32499, 32504, 32409, -1, 32505, 32506, 32496, -1, 32507, 32505, 32496, -1, 32508, 32509, 32507, -1, 32508, 32507, 32496, -1, 32054, 31714, 31713, -1, 31072, 32510, 32508, -1, 31072, 32508, 32496, -1, 31804, 31803, 31802, -1, 31805, 31803, 31804, -1, 31806, 31803, 31805, -1, 30643, 31859, 31866, -1, 30643, 30642, 31859, -1, 31859, 31170, 32059, -1, 30642, 31170, 31859, -1, 32061, 31132, 32062, -1, 31177, 31132, 32061, -1, 32062, 31134, 32078, -1, 31132, 31134, 32062, -1, 32078, 32417, 32421, -1, 31134, 31136, 32078, -1, 32078, 31136, 32417, -1, 31899, 30654, 31883, -1, 30660, 30654, 31899, -1, 31934, 30614, 31935, -1, 30614, 31927, 31935, -1, 30614, 31852, 31927, -1, 31920, 30631, 31906, -1, 31855, 30631, 31920, -1, 31900, 30631, 31855, -1, 30614, 30631, 31852, -1, 31852, 30631, 31908, -1, 31908, 30631, 31909, -1, 31909, 30631, 31900, -1, 31900, 31847, 31909, -1, 31847, 32511, 31848, -1, 32512, 31812, 32513, -1, 32514, 31812, 32512, -1, 32511, 31812, 32514, -1, 31847, 31812, 32511, -1, 31847, 31811, 31812, -1, 31900, 31811, 31847, -1, 31826, 31887, 31882, -1, 31829, 31887, 31826, -1, 31811, 31900, 31828, -1, 31900, 31829, 31828, -1, 31900, 31887, 31829, -1, 31909, 31847, 31823, -1, 31826, 31909, 31823, -1, 31882, 31909, 31826, -1, 32252, 30997, 32249, -1, 32249, 30997, 30993, -1, 32515, 31074, 32516, -1, 32517, 31074, 32515, -1, 32518, 31074, 32517, -1, 32516, 32254, 32322, -1, 31000, 32254, 31074, -1, 31074, 32254, 32516, -1, 32254, 30997, 32252, -1, 31000, 30997, 32254, -1, 32249, 32432, 32243, -1, 30993, 32432, 32249, -1, 30993, 32433, 32432, -1, 30993, 30986, 32433, -1, 32262, 32255, 32274, -1, 32262, 32274, 32280, -1, 32255, 32259, 32277, -1, 32255, 32277, 32274, -1, 32259, 32261, 32279, -1, 32259, 32279, 32277, -1, 32261, 32247, 32245, -1, 32261, 32245, 32279, -1, 32519, 32413, 32520, -1, 32519, 32412, 32413, -1, 30988, 31060, 30990, -1, 31060, 32521, 31062, -1, 30988, 32522, 31060, -1, 31060, 32522, 32521, -1, 32521, 31063, 31062, -1, 32521, 32523, 31063, -1, 31063, 32524, 31065, -1, 32523, 32524, 31063, -1, 32524, 31068, 31065, -1, 32524, 32520, 31068, -1, 32520, 32413, 31068, -1, 30991, 32522, 30988, -1, 30991, 32525, 32522, -1, 32525, 32526, 32521, -1, 32525, 32521, 32522, -1, 32526, 32527, 32523, -1, 32526, 32523, 32521, -1, 32527, 32528, 32524, -1, 32527, 32524, 32523, -1, 31058, 30991, 30992, -1, 32526, 31058, 31039, -1, 32525, 30991, 31058, -1, 32525, 31058, 32526, -1, 31038, 32526, 31039, -1, 32527, 32526, 31038, -1, 32528, 31038, 31040, -1, 32528, 32527, 31038, -1, 31041, 32519, 32528, -1, 31041, 32528, 31040, -1, 32412, 32519, 31041, -1, 32396, 32089, 32395, -1, 32090, 32089, 32396, -1, 32089, 32393, 32395, -1, 32089, 32087, 32393, -1, 32382, 31997, 32384, -1, 32076, 31997, 32382, -1, 32081, 32079, 32383, -1, 32081, 32383, 32387, -1, 32086, 32081, 32387, -1, 32086, 32387, 32392, -1, 32389, 32086, 32392, -1, 32084, 32086, 32389, -1, 32388, 32391, 32377, -1, 32085, 32389, 32391, -1, 32085, 32084, 32389, -1, 32082, 32085, 32391, -1, 32082, 32391, 32388, -1, 32529, 32530, 32085, -1, 32529, 32085, 32082, -1, 32080, 32388, 32385, -1, 32080, 32082, 32388, -1, 32391, 32378, 32377, -1, 32079, 32080, 32385, -1, 32079, 32385, 32383, -1, 32531, 32530, 32529, -1, 32532, 32530, 32531, -1, 32075, 32529, 32082, -1, 32060, 32529, 32075, -1, 32529, 32063, 32531, -1, 32060, 32063, 32529, -1, 32063, 32077, 32531, -1, 32530, 32419, 32083, -1, 32530, 32083, 32085, -1, 32420, 32530, 32532, -1, 32420, 32419, 32530, -1, 32421, 32420, 32532, -1, 32531, 32421, 32532, -1, 32077, 32421, 32531, -1, 32077, 32078, 32421, -1, 32376, 32388, 32377, -1, 32381, 32388, 32376, -1, 32391, 32379, 32378, -1, 32391, 32390, 32379, -1, 32533, 30980, 30978, -1, 32533, 32416, 30980, -1, 30996, 31033, 30969, -1, 30996, 30969, 30964, -1, 31033, 31031, 30967, -1, 31033, 30967, 30969, -1, 31031, 31035, 30971, -1, 31031, 30971, 30967, -1, 31035, 31036, 30973, -1, 31035, 30973, 30971, -1, 32534, 32535, 30974, -1, 30973, 32534, 30974, -1, 31037, 32534, 30973, -1, 31036, 31037, 30973, -1, 32535, 32536, 30975, -1, 32535, 30975, 30974, -1, 32536, 32537, 30977, -1, 32536, 30977, 30975, -1, 32535, 32534, 32407, -1, 32535, 32407, 32406, -1, 32536, 32535, 32406, -1, 32397, 32536, 32406, -1, 32537, 32536, 32397, -1, 32398, 32533, 32537, -1, 32398, 32537, 32397, -1, 32416, 32533, 32398, -1, 32496, 31693, 32498, -1, 31683, 31693, 32496, -1, 32142, 31789, 32123, -1, 31792, 31789, 32142, -1, 31897, 31898, 31827, -1, 31897, 31827, 31831, -1, 31855, 31787, 31809, -1, 31920, 31787, 31855, -1, 31898, 31855, 31827, -1, 31827, 31855, 31834, -1, 31855, 31809, 31834, -1, 31920, 31897, 31831, -1, 31920, 31831, 31770, -1, 31787, 31920, 31770, -1, 31070, 32538, 32539, -1, 31070, 32539, 31029, -1, 32539, 32538, 32540, -1, 32539, 32540, 32541, -1, 32540, 32534, 31037, -1, 32540, 31037, 32541, -1, 31026, 32541, 31037, -1, 31024, 32541, 31026, -1, 31024, 32539, 32541, -1, 31024, 31022, 32539, -1, 31022, 31021, 32539, -1, 31029, 32539, 31021, -1, 32540, 32405, 32407, -1, 32540, 32407, 32534, -1, 32538, 32408, 32405, -1, 32538, 32405, 32540, -1, 32409, 32408, 32538, -1, 32538, 31070, 32409, -1, 30952, 30948, 30695, -1, 30695, 30948, 30698, -1, 30698, 30948, 30947, -1, 30700, 30947, 30951, -1, 30700, 30698, 30947, -1, 30703, 30951, 30954, -1, 30703, 30700, 30951, -1, 30701, 30954, 30955, -1, 30701, 30703, 30954, -1, 30705, 30701, 30955, -1, 30637, 30955, 30953, -1, 30637, 30705, 30955, -1, 30634, 30953, 30950, -1, 30634, 30637, 30953, -1, 30635, 30950, 30946, -1, 30635, 30946, 30945, -1, 30635, 30634, 30950, -1, 30694, 30635, 30945, -1, 30693, 30945, 30960, -1, 30693, 30960, 30959, -1, 30693, 30694, 30945, -1, 30692, 30959, 30958, -1, 30692, 30693, 30959, -1, 30691, 30958, 30957, -1, 30691, 30692, 30958, -1, 30689, 30957, 30956, -1, 30689, 30691, 30957, -1, 30686, 30689, 30956, -1, 30686, 30949, 30639, -1, 30956, 30949, 30686, -1, 30381, 30366, 30641, -1, 30374, 30366, 30381, -1, 30624, 30368, 30382, -1, 30375, 30368, 30624, -1, 30641, 30366, 30367, -1, 30659, 30367, 30370, -1, 30659, 30641, 30367, -1, 30658, 30370, 30372, -1, 30658, 30659, 30370, -1, 30657, 30372, 30373, -1, 30657, 30658, 30372, -1, 30656, 30657, 30373, -1, 30655, 30373, 30371, -1, 30655, 30656, 30373, -1, 30653, 30371, 30369, -1, 30653, 30655, 30371, -1, 30651, 30369, 30365, -1, 30651, 30365, 30364, -1, 30651, 30653, 30369, -1, 30650, 30651, 30364, -1, 30648, 30364, 30379, -1, 30648, 30379, 30378, -1, 30648, 30650, 30364, -1, 30646, 30378, 30377, -1, 30646, 30648, 30378, -1, 30645, 30377, 30376, -1, 30645, 30646, 30377, -1, 30644, 30376, 30375, -1, 30644, 30645, 30376, -1, 30624, 30644, 30375, -1, 32542, 30548, 32543, -1, 32542, 32543, 32544, -1, 32545, 32546, 32547, -1, 32545, 32548, 32549, -1, 32545, 32547, 32548, -1, 32550, 32545, 32549, -1, 32551, 32552, 32553, -1, 32554, 32553, 32555, -1, 32556, 32545, 32550, -1, 32554, 32551, 32553, -1, 32557, 32558, 32559, -1, 32560, 30548, 32542, -1, 32561, 30564, 30608, -1, 32561, 30608, 30595, -1, 32561, 30595, 30568, -1, 32561, 30568, 30567, -1, 32562, 32563, 32552, -1, 32564, 32565, 32557, -1, 32562, 32552, 32551, -1, 32564, 32557, 32559, -1, 32566, 32558, 32557, -1, 32567, 32555, 32568, -1, 32566, 32569, 32558, -1, 32566, 32570, 32569, -1, 32567, 32554, 32555, -1, 32571, 32572, 32563, -1, 32571, 32563, 32562, -1, 32573, 30549, 30548, -1, 32574, 32567, 32568, -1, 32573, 30548, 32560, -1, 32575, 32565, 32564, -1, 32574, 32568, 32559, -1, 32576, 32561, 30567, -1, 32576, 30567, 30610, -1, 32577, 32570, 32566, -1, 32577, 32578, 32570, -1, 32579, 32572, 32571, -1, 32580, 30549, 32573, -1, 32579, 32581, 32582, -1, 32580, 30570, 30549, -1, 32579, 32582, 32572, -1, 32583, 30610, 30601, -1, 32584, 32575, 32564, -1, 32583, 32576, 30610, -1, 32585, 32574, 32559, -1, 32586, 32581, 32579, -1, 30592, 32578, 32577, -1, 32587, 30581, 30570, -1, 32588, 32581, 32586, -1, 32587, 30570, 32580, -1, 32589, 30601, 30581, -1, 32589, 32583, 30601, -1, 32590, 32585, 32559, -1, 32589, 30581, 32587, -1, 32591, 32564, 32592, -1, 32591, 32584, 32564, -1, 32561, 32545, 30564, -1, 30564, 32545, 32556, -1, 30591, 32593, 32578, -1, 32594, 32588, 32586, -1, 30591, 32578, 30592, -1, 32595, 32590, 32559, -1, 32596, 32588, 32594, -1, 32597, 32592, 32598, -1, 32597, 32591, 32592, -1, 32599, 32596, 32594, -1, 30565, 32593, 30591, -1, 30565, 32600, 32593, -1, 30565, 32556, 32600, -1, 32558, 32595, 32559, -1, 32601, 32597, 32598, -1, 32602, 32596, 32599, -1, 32603, 32601, 32598, -1, 32604, 32602, 32599, -1, 30564, 32556, 30565, -1, 32605, 32601, 32603, -1, 32606, 32605, 32603, -1, 32607, 32602, 32604, -1, 32607, 32604, 32608, -1, 32609, 32605, 32606, -1, 32544, 32609, 32606, -1, 32546, 32607, 32608, -1, 32546, 32608, 32547, -1, 32543, 32609, 32544, -1, 32610, 32611, 32612, -1, 32613, 32611, 32614, -1, 32614, 32611, 32610, -1, 32612, 32615, 32616, -1, 32616, 32615, 32617, -1, 32559, 32618, 32619, -1, 32568, 32618, 32559, -1, 32555, 32618, 32568, -1, 32617, 32618, 32555, -1, 32620, 32621, 32622, -1, 32622, 32621, 32611, -1, 32611, 32621, 32612, -1, 32612, 32621, 32615, -1, 32619, 32623, 32624, -1, 32615, 32623, 32617, -1, 32618, 32623, 32619, -1, 32617, 32623, 32618, -1, 32624, 32625, 32626, -1, 32626, 32625, 32627, -1, 32628, 32625, 32620, -1, 32627, 32625, 32628, -1, 32620, 32625, 32621, -1, 32615, 32625, 32623, -1, 32623, 32625, 32624, -1, 32621, 32625, 32615, -1, 32629, 32630, 32582, -1, 32582, 32630, 32572, -1, 32631, 32632, 32629, -1, 32629, 32632, 32630, -1, 32572, 32633, 32563, -1, 32630, 32633, 32572, -1, 32634, 32635, 32636, -1, 32637, 32635, 32631, -1, 32636, 32635, 32637, -1, 32631, 32635, 32632, -1, 32630, 32638, 32633, -1, 32632, 32638, 32630, -1, 32563, 32639, 32552, -1, 32633, 32639, 32563, -1, 32640, 32641, 32634, -1, 32634, 32641, 32635, -1, 32632, 32641, 32638, -1, 32635, 32641, 32632, -1, 32638, 32610, 32633, -1, 32633, 32610, 32639, -1, 32552, 32616, 32553, -1, 32639, 32616, 32552, -1, 32613, 32614, 32640, -1, 32641, 32614, 32638, -1, 32638, 32614, 32610, -1, 32640, 32614, 32641, -1, 32610, 32612, 32639, -1, 32639, 32612, 32616, -1, 32553, 32617, 32555, -1, 32616, 32617, 32553, -1, 32622, 32611, 32613, -1, 32642, 32643, 32644, -1, 32645, 32646, 32647, -1, 32642, 32644, 30277, -1, 32642, 30277, 32648, -1, 32649, 32650, 32651, -1, 32642, 32648, 32652, -1, 32642, 32653, 32643, -1, 32642, 32654, 32655, -1, 32656, 32657, 32658, -1, 32642, 32652, 32654, -1, 32642, 32655, 32653, -1, 32659, 32660, 32661, -1, 32649, 32651, 32662, -1, 32663, 32662, 32664, -1, 32659, 32665, 32660, -1, 32663, 32664, 32666, -1, 32667, 32661, 32668, -1, 32669, 32579, 32571, -1, 32667, 32668, 32670, -1, 32669, 32671, 32579, -1, 32672, 32666, 32673, -1, 32672, 32673, 32674, -1, 32675, 32670, 32676, -1, 32675, 32676, 32677, -1, 32678, 32679, 32671, -1, 32680, 32674, 32681, -1, 32680, 32681, 32682, -1, 32678, 32671, 32669, -1, 32683, 32677, 32558, -1, 32684, 32574, 32585, -1, 32685, 32571, 32562, -1, 32683, 32558, 32569, -1, 32684, 32682, 32574, -1, 32685, 32669, 32571, -1, 32686, 32657, 32656, -1, 32687, 32645, 32650, -1, 32688, 32679, 32678, -1, 32686, 32689, 32690, -1, 32687, 32691, 32692, -1, 32686, 32693, 32657, -1, 32687, 32692, 32645, -1, 32688, 32694, 32679, -1, 32686, 32690, 32693, -1, 32695, 32656, 32665, -1, 32687, 32650, 32649, -1, 32695, 32665, 32659, -1, 32696, 32649, 32662, -1, 32697, 32678, 32669, -1, 32696, 32662, 32663, -1, 32698, 32666, 32672, -1, 32698, 32663, 32666, -1, 32697, 32669, 32685, -1, 32699, 32685, 32562, -1, 32699, 32562, 32551, -1, 32700, 32659, 32661, -1, 32700, 32661, 32667, -1, 32701, 32667, 32670, -1, 32702, 32672, 32674, -1, 32646, 30290, 32703, -1, 32704, 32705, 32694, -1, 32702, 32674, 32680, -1, 32701, 32670, 32675, -1, 32704, 32694, 32688, -1, 32706, 32677, 32683, -1, 32707, 32680, 32682, -1, 32708, 32678, 32697, -1, 32707, 32682, 32684, -1, 32708, 32688, 32678, -1, 32706, 32675, 32677, -1, 32709, 32569, 32570, -1, 32710, 32585, 32590, -1, 32709, 32570, 32578, -1, 32709, 32578, 32711, -1, 32710, 32684, 32585, -1, 32712, 32697, 32685, -1, 32709, 32683, 32569, -1, 32713, 32686, 32656, -1, 32714, 32715, 32691, -1, 32713, 32716, 32689, -1, 32714, 32691, 32687, -1, 32712, 32685, 32699, -1, 32713, 32689, 32686, -1, 32714, 32649, 32696, -1, 32714, 32687, 32649, -1, 32717, 32551, 32554, -1, 32713, 32656, 32695, -1, 32718, 32659, 32700, -1, 32718, 32695, 32659, -1, 32719, 32696, 32663, -1, 32717, 32699, 32551, -1, 32719, 32663, 32698, -1, 32720, 32700, 32667, -1, 32720, 32667, 32701, -1, 32721, 32722, 32705, -1, 32658, 32672, 32702, -1, 32658, 32698, 32672, -1, 32721, 32705, 32704, -1, 32651, 32688, 32708, -1, 32660, 32702, 32680, -1, 32651, 32704, 32688, -1, 32660, 32680, 32707, -1, 32664, 32708, 32697, -1, 32723, 32701, 32675, -1, 32723, 32675, 32706, -1, 32724, 32709, 32711, -1, 32724, 32711, 32725, -1, 32724, 32706, 32683, -1, 32664, 32697, 32712, -1, 32724, 32683, 32709, -1, 32726, 32713, 32695, -1, 32668, 32684, 32710, -1, 32726, 32727, 32716, -1, 32668, 32707, 32684, -1, 32726, 32716, 32713, -1, 32676, 32590, 32595, -1, 32673, 32712, 32699, -1, 32726, 32695, 32718, -1, 32673, 32699, 32717, -1, 32681, 32717, 32554, -1, 32681, 32554, 32567, -1, 32676, 32710, 32590, -1, 32728, 32718, 32700, -1, 32728, 32700, 32720, -1, 32729, 32730, 32715, -1, 32729, 32715, 32714, -1, 32729, 32714, 32696, -1, 32729, 32696, 32719, -1, 32647, 32703, 32722, -1, 32647, 32646, 32703, -1, 32647, 32722, 32721, -1, 32731, 32720, 32701, -1, 32731, 32701, 32723, -1, 32657, 32719, 32698, -1, 32732, 32725, 32733, -1, 32657, 32698, 32658, -1, 32650, 32704, 32651, -1, 32732, 32724, 32725, -1, 32732, 32723, 32706, -1, 32732, 32706, 32724, -1, 32650, 32721, 32704, -1, 32665, 32702, 32660, -1, 32665, 32658, 32702, -1, 32734, 32735, 32727, -1, 32734, 32727, 32726, -1, 32662, 32651, 32708, -1, 32734, 32726, 32718, -1, 32662, 32708, 32664, -1, 32734, 32718, 32728, -1, 32661, 32660, 32707, -1, 32661, 32707, 32668, -1, 32655, 32728, 32720, -1, 32666, 32712, 32673, -1, 32666, 32664, 32712, -1, 32655, 32720, 32731, -1, 32736, 32733, 32737, -1, 32670, 32668, 32710, -1, 32736, 32732, 32733, -1, 32736, 32731, 32723, -1, 32674, 32717, 32681, -1, 32736, 32723, 32732, -1, 32674, 32673, 32717, -1, 32670, 32710, 32676, -1, 32654, 32728, 32655, -1, 32682, 32567, 32574, -1, 32677, 32595, 32558, -1, 32654, 32652, 32735, -1, 32654, 32735, 32734, -1, 32654, 32734, 32728, -1, 32677, 32676, 32595, -1, 32653, 32737, 32643, -1, 32682, 32681, 32567, -1, 32645, 32647, 32721, -1, 32693, 32690, 32730, -1, 32653, 32736, 32737, -1, 32693, 32730, 32729, -1, 32693, 32729, 32719, -1, 32645, 32692, 32646, -1, 32653, 32655, 32731, -1, 32693, 32719, 32657, -1, 32645, 32721, 32650, -1, 32653, 32731, 32736, -1, 32656, 32658, 32665, -1, 32738, 32634, 32636, -1, 32738, 32739, 32634, -1, 32634, 32740, 32640, -1, 32739, 32740, 32634, -1, 32640, 32741, 32613, -1, 32740, 32741, 32640, -1, 32613, 32742, 32622, -1, 32741, 32742, 32613, -1, 32622, 32743, 32620, -1, 32742, 32743, 32622, -1, 32620, 32744, 32628, -1, 32743, 32744, 32620, -1, 32628, 32745, 32627, -1, 32744, 32745, 32628, -1, 32746, 32747, 32748, -1, 32748, 32747, 32749, -1, 32749, 32747, 32750, -1, 32750, 32751, 32752, -1, 32752, 32751, 32753, -1, 32754, 32573, 32560, -1, 32561, 32755, 32756, -1, 32583, 32755, 32576, -1, 32576, 32755, 32561, -1, 32753, 32755, 32583, -1, 32757, 32758, 32759, -1, 32750, 32758, 32751, -1, 32759, 32758, 32747, -1, 32747, 32758, 32750, -1, 32756, 32760, 32761, -1, 32751, 32760, 32753, -1, 32755, 32760, 32756, -1, 32753, 32760, 32755, -1, 32761, 32762, 32763, -1, 32764, 32762, 32757, -1, 32751, 32762, 32760, -1, 32763, 32762, 32764, -1, 32757, 32762, 32758, -1, 32760, 32762, 32761, -1, 32758, 32762, 32751, -1, 32764, 32765, 32763, -1, 32754, 32766, 32573, -1, 32767, 32768, 32754, -1, 32754, 32768, 32766, -1, 32573, 32769, 32580, -1, 32766, 32769, 32573, -1, 32770, 32771, 32772, -1, 32773, 32771, 32767, -1, 32772, 32771, 32773, -1, 32767, 32771, 32768, -1, 32766, 32774, 32769, -1, 32768, 32774, 32766, -1, 32580, 32775, 32587, -1, 32769, 32775, 32580, -1, 32776, 32777, 32770, -1, 32770, 32777, 32771, -1, 32768, 32777, 32774, -1, 32771, 32777, 32768, -1, 32774, 32749, 32769, -1, 32769, 32749, 32775, -1, 32587, 32752, 32589, -1, 32775, 32752, 32587, -1, 32746, 32748, 32776, -1, 32777, 32748, 32774, -1, 32776, 32748, 32777, -1, 32774, 32748, 32749, -1, 32749, 32750, 32775, -1, 32775, 32750, 32752, -1, 32589, 32753, 32583, -1, 32752, 32753, 32589, -1, 32759, 32747, 32746, -1, 32778, 32779, 32772, -1, 32772, 32779, 32770, -1, 32770, 32780, 32776, -1, 32779, 32780, 32770, -1, 32776, 32781, 32746, -1, 32780, 32781, 32776, -1, 32746, 32782, 32759, -1, 32781, 32782, 32746, -1, 32759, 32783, 32757, -1, 32782, 32783, 32759, -1, 32757, 32784, 32764, -1, 32783, 32784, 32757, -1, 32764, 32785, 32765, -1, 32784, 32785, 32764, -1, 31985, 31984, 32786, -1, 31985, 32786, 32787, -1, 32788, 32789, 32790, -1, 32788, 32790, 32791, -1, 32792, 32793, 32794, -1, 32795, 32794, 32796, -1, 32795, 32792, 32794, -1, 32797, 32798, 32793, -1, 32797, 32793, 32792, -1, 32799, 32796, 32800, -1, 32799, 32795, 32796, -1, 32801, 31976, 32798, -1, 32801, 32798, 32797, -1, 31987, 31985, 32787, -1, 31987, 32787, 32802, -1, 32803, 32800, 32804, -1, 32803, 32799, 32800, -1, 32805, 32806, 32789, -1, 32805, 32789, 32788, -1, 32807, 31976, 32801, -1, 31988, 31987, 32802, -1, 31981, 32808, 32806, -1, 32809, 32804, 32810, -1, 31981, 32811, 32808, -1, 32809, 32810, 32812, -1, 32809, 32803, 32804, -1, 31981, 32806, 32805, -1, 32813, 31974, 31976, -1, 32813, 31976, 32807, -1, 31990, 32802, 32814, -1, 31990, 31988, 32802, -1, 31980, 32815, 32811, -1, 31980, 32811, 31981, -1, 32816, 32812, 32817, -1, 32816, 32809, 32812, -1, 31992, 31990, 32814, -1, 31992, 32814, 32818, -1, 32819, 31975, 31974, -1, 32819, 31974, 32813, -1, 31972, 32820, 32815, -1, 31972, 32815, 31980, -1, 31993, 32818, 32821, -1, 31993, 31992, 32818, -1, 32822, 32816, 32817, -1, 31994, 32821, 32820, -1, 31994, 32820, 31972, -1, 32823, 31975, 32819, -1, 31994, 31993, 32821, -1, 32823, 31984, 31975, -1, 32791, 32822, 32817, -1, 32791, 32790, 32822, -1, 32786, 31984, 32823, -1, 30878, 32824, 32808, -1, 32808, 32824, 32806, -1, 32806, 32825, 32789, -1, 32824, 32825, 32806, -1, 32789, 32826, 32790, -1, 32825, 32826, 32789, -1, 32790, 32827, 32822, -1, 32826, 32827, 32790, -1, 32822, 32828, 32816, -1, 32827, 32828, 32822, -1, 32816, 32829, 32809, -1, 32828, 32829, 32816, -1, 32809, 32830, 32803, -1, 32829, 32830, 32809, -1, 32803, 32831, 32799, -1, 32830, 32831, 32803, -1, 32799, 32832, 32795, -1, 32831, 32832, 32799, -1, 32795, 32833, 32792, -1, 32832, 32833, 32795, -1, 32792, 32834, 32797, -1, 32833, 32834, 32792, -1, 32797, 32835, 32801, -1, 32834, 32835, 32797, -1, 32801, 30922, 32807, -1, 32835, 30922, 32801, -1, 30922, 30921, 32807, -1, 32807, 30921, 32813, -1, 32813, 30896, 32819, -1, 30921, 30896, 32813, -1, 32819, 30895, 32823, -1, 30896, 30895, 32819, -1, 32823, 30938, 32786, -1, 30895, 30938, 32823, -1, 32786, 30925, 32787, -1, 30938, 30925, 32786, -1, 32787, 30901, 32802, -1, 30925, 30901, 32787, -1, 32802, 30900, 32814, -1, 30901, 30900, 32802, -1, 32814, 30940, 32818, -1, 30900, 30940, 32814, -1, 32818, 30931, 32821, -1, 30940, 30931, 32818, -1, 32821, 30912, 32820, -1, 30931, 30912, 32821, -1, 32820, 30898, 32815, -1, 30912, 30898, 32820, -1, 32815, 30879, 32811, -1, 30898, 30879, 32815, -1, 32811, 30878, 32808, -1, 30879, 30878, 32811, -1, 32836, 32837, 30438, -1, 32836, 30438, 30437, -1, 32838, 32839, 32840, -1, 32841, 32840, 32842, -1, 32841, 32838, 32840, -1, 32843, 32844, 32839, -1, 32843, 32839, 32838, -1, 32845, 32836, 30437, -1, 32845, 30437, 30493, -1, 32846, 32842, 32847, -1, 32845, 30493, 30477, -1, 32846, 32841, 32842, -1, 30458, 32845, 30477, -1, 32848, 32849, 32844, -1, 32848, 32844, 32843, -1, 32850, 32847, 32851, -1, 32850, 32846, 32847, -1, 32852, 30421, 32853, -1, 32852, 32853, 32854, -1, 32852, 32854, 32855, -1, 30461, 32856, 32849, -1, 30461, 32849, 32848, -1, 32852, 32855, 32851, -1, 32857, 30421, 32852, -1, 32857, 30444, 30424, -1, 32857, 30424, 30419, -1, 32858, 32850, 32851, -1, 32857, 30419, 30421, -1, 32857, 32845, 30458, -1, 32857, 30458, 30444, -1, 30427, 32859, 32856, -1, 30427, 32856, 30461, -1, 32860, 32858, 32851, -1, 30426, 32859, 30427, -1, 32861, 32859, 30426, -1, 32862, 32860, 32851, -1, 30488, 32861, 30426, -1, 32855, 32862, 32851, -1, 32863, 32861, 30488, -1, 30470, 32863, 30488, -1, 32837, 30470, 30438, -1, 32837, 32863, 30470, -1, 32864, 32009, 32008, -1, 32865, 32008, 32002, -1, 32865, 32864, 32008, -1, 32040, 32036, 32866, -1, 32867, 32012, 32009, -1, 32867, 32009, 32864, -1, 32040, 32866, 32868, -1, 32869, 32865, 32002, -1, 32870, 32871, 32872, -1, 32873, 32013, 32012, -1, 32873, 32012, 32867, -1, 32870, 32872, 32874, -1, 32875, 32869, 32002, -1, 32041, 32868, 32876, -1, 32041, 32040, 32868, -1, 32877, 32022, 32013, -1, 32030, 32871, 32870, -1, 32030, 32878, 32871, -1, 32877, 32013, 32873, -1, 32879, 32875, 32002, -1, 32045, 32041, 32876, -1, 32045, 32876, 32880, -1, 32029, 32881, 32878, -1, 32882, 32023, 32022, -1, 32882, 32022, 32877, -1, 32029, 32878, 32030, -1, 32048, 32045, 32880, -1, 32007, 32879, 32002, -1, 32048, 32883, 32884, -1, 32048, 32880, 32883, -1, 32885, 32879, 32007, -1, 32020, 32886, 32881, -1, 32020, 32881, 32029, -1, 32049, 32884, 32887, -1, 32888, 32023, 32882, -1, 32049, 32048, 32884, -1, 32052, 32887, 32886, -1, 32052, 32049, 32887, -1, 32889, 32885, 32007, -1, 32052, 32886, 32020, -1, 32035, 32023, 32888, -1, 32890, 32035, 32888, -1, 32891, 32892, 32889, -1, 32891, 32889, 32007, -1, 32036, 32890, 32866, -1, 32036, 32035, 32890, -1, 32874, 32872, 32892, -1, 32874, 32892, 32891, -1, 32878, 31210, 32871, -1, 32871, 32893, 32872, -1, 31210, 32893, 32871, -1, 32872, 32894, 32892, -1, 32893, 32894, 32872, -1, 32892, 32895, 32889, -1, 32894, 32895, 32892, -1, 32889, 32896, 32885, -1, 32895, 32896, 32889, -1, 32885, 32897, 32879, -1, 32896, 32897, 32885, -1, 32879, 32898, 32875, -1, 32897, 32898, 32879, -1, 32875, 32899, 32869, -1, 32898, 32899, 32875, -1, 32869, 32900, 32865, -1, 32899, 32900, 32869, -1, 32865, 32901, 32864, -1, 32900, 32901, 32865, -1, 32864, 32902, 32867, -1, 32901, 32902, 32864, -1, 32867, 32903, 32873, -1, 32902, 32903, 32867, -1, 32873, 32904, 32877, -1, 32903, 32904, 32873, -1, 32904, 31252, 32877, -1, 32007, 32006, 32891, -1, 32005, 32874, 32891, -1, 32005, 32891, 32006, -1, 32003, 32074, 32004, -1, 32905, 32031, 32030, -1, 32905, 32870, 32874, -1, 32905, 32030, 32870, -1, 32905, 32005, 32004, -1, 32905, 32073, 32031, -1, 32905, 32074, 32073, -1, 32905, 32874, 32005, -1, 32905, 32004, 32074, -1, 32906, 31912, 32907, -1, 32906, 32907, 32793, -1, 32908, 31891, 31981, -1, 32908, 32805, 32788, -1, 32908, 31981, 32805, -1, 32908, 32788, 32909, -1, 32910, 31893, 31891, -1, 32910, 31894, 31893, -1, 32910, 32908, 32909, -1, 32910, 31891, 32908, -1, 32910, 32909, 31894, -1, 32911, 32798, 31976, -1, 32911, 32793, 32798, -1, 32911, 31976, 31926, -1, 32911, 32906, 32793, -1, 32912, 31923, 31912, -1, 32912, 31926, 31923, -1, 32912, 31912, 32906, -1, 32912, 32911, 31926, -1, 32912, 32906, 32911, -1, 32913, 32791, 32817, -1, 32913, 32788, 32791, -1, 32913, 31895, 31894, -1, 32913, 31896, 31895, -1, 32913, 31894, 32909, -1, 32913, 32909, 32788, -1, 32914, 32812, 32810, -1, 32914, 32817, 32812, -1, 32914, 31875, 31896, -1, 32914, 31874, 31875, -1, 32914, 32913, 32817, -1, 32914, 31896, 32913, -1, 32915, 32810, 32804, -1, 32915, 31878, 31874, -1, 32915, 32914, 32810, -1, 32915, 31874, 32914, -1, 32916, 32800, 32796, -1, 32916, 32804, 32800, -1, 32916, 31913, 31878, -1, 32916, 31910, 31913, -1, 32916, 31878, 32915, -1, 32916, 32915, 32804, -1, 32907, 32794, 32793, -1, 32907, 32796, 32794, -1, 32907, 31911, 31910, -1, 32907, 31912, 31911, -1, 32907, 31910, 32916, -1, 32907, 32916, 32796, -1, 32627, 32917, 32918, -1, 32745, 32917, 32627, -1, 32917, 32919, 32918, -1, 32917, 32920, 32919, -1, 32919, 32921, 32922, -1, 32920, 32921, 32919, -1, 32922, 32923, 32924, -1, 32921, 32923, 32922, -1, 32924, 32925, 32926, -1, 32923, 32925, 32924, -1, 32926, 32927, 32928, -1, 32925, 32927, 32926, -1, 32928, 32929, 32930, -1, 32927, 32929, 32928, -1, 32930, 32778, 32772, -1, 32929, 32778, 32930, -1, 32931, 32927, 32932, -1, 32931, 32932, 32933, -1, 32931, 32933, 32934, -1, 32935, 32936, 32937, -1, 32935, 32938, 32936, -1, 32935, 32934, 32939, -1, 32935, 32939, 32938, -1, 32940, 32941, 32942, -1, 32943, 32937, 32944, -1, 32943, 32935, 32937, -1, 32943, 32934, 32935, -1, 32943, 32944, 32929, -1, 32943, 32929, 32931, -1, 32943, 32931, 32934, -1, 32920, 32917, 32945, -1, 32778, 32929, 32944, -1, 32946, 32940, 32947, -1, 32946, 32941, 32940, -1, 32948, 32949, 32941, -1, 32948, 32941, 32946, -1, 32950, 32947, 32951, -1, 32950, 32946, 32947, -1, 32952, 32921, 32920, -1, 32952, 32945, 32949, -1, 32952, 32920, 32945, -1, 32952, 32949, 32948, -1, 32953, 32946, 32950, -1, 32953, 32948, 32946, -1, 32954, 32951, 32955, -1, 32954, 32950, 32951, -1, 32956, 32923, 32921, -1, 32956, 32921, 32952, -1, 32956, 32952, 32948, -1, 32956, 32948, 32953, -1, 32957, 32953, 32950, -1, 32957, 32950, 32954, -1, 32958, 32955, 32959, -1, 32958, 32954, 32955, -1, 32960, 32925, 32923, -1, 32960, 32956, 32953, -1, 32960, 32923, 32956, -1, 32960, 32953, 32957, -1, 32933, 32957, 32954, -1, 32933, 32954, 32958, -1, 32939, 32959, 32961, -1, 32939, 32958, 32959, -1, 32932, 32927, 32925, -1, 32932, 32957, 32933, -1, 32932, 32925, 32960, -1, 32932, 32960, 32957, -1, 32934, 32933, 32958, -1, 32934, 32958, 32939, -1, 32938, 32961, 32962, -1, 32938, 32962, 32936, -1, 32938, 32939, 32961, -1, 32931, 32929, 32927, -1, 32963, 32964, 32965, -1, 32963, 32965, 32966, -1, 32963, 32966, 32967, -1, 32963, 32962, 32968, -1, 32963, 32967, 32969, -1, 32963, 32969, 32970, -1, 32963, 32970, 32971, -1, 32972, 32973, 32974, -1, 32963, 32971, 32962, -1, 32975, 32973, 32972, -1, 32976, 32977, 32978, -1, 32979, 32977, 32976, -1, 32980, 32977, 32979, -1, 32981, 32982, 32983, -1, 32981, 32983, 32977, -1, 32984, 32985, 32986, -1, 32987, 32981, 32977, -1, 32988, 32985, 32984, -1, 32988, 32989, 32990, -1, 32988, 32990, 32985, -1, 32988, 32991, 32992, -1, 32988, 32992, 32993, -1, 32988, 32993, 32963, -1, 32994, 32977, 32980, -1, 32994, 32987, 32977, -1, 32988, 32963, 32989, -1, 32995, 32984, 32986, -1, 32996, 32994, 32980, -1, 32997, 32961, 32959, -1, 32998, 32995, 32986, -1, 32997, 32959, 32955, -1, 32997, 32955, 32951, -1, 32999, 32996, 32980, -1, 32997, 32951, 32947, -1, 32998, 32986, 33000, -1, 32997, 32947, 32940, -1, 33001, 32999, 32980, -1, 32997, 32940, 32942, -1, 33002, 32998, 33000, -1, 32962, 32961, 32997, -1, 33003, 33002, 33000, -1, 33004, 33003, 33000, -1, 33005, 33003, 33004, -1, 32963, 32973, 32975, -1, 32968, 32962, 32997, -1, 32963, 32975, 32964, -1, 33006, 32997, 32942, -1, 33006, 32942, 33007, -1, 33008, 32999, 33001, -1, 33008, 33009, 33010, -1, 33008, 33001, 33009, -1, 33011, 33012, 33008, -1, 33013, 33011, 33008, -1, 32973, 33008, 33010, -1, 32973, 33013, 33008, -1, 32973, 33010, 33014, -1, 33015, 33016, 33006, -1, 33017, 33006, 33016, -1, 33018, 33015, 33006, -1, 33019, 33006, 33017, -1, 33020, 33018, 33006, -1, 33007, 33020, 33006, -1, 33021, 33006, 33019, -1, 33021, 33014, 33006, -1, 33021, 32973, 33014, -1, 33022, 32986, 33023, -1, 33024, 32973, 33021, -1, 33025, 32973, 33024, -1, 33026, 32973, 33025, -1, 33027, 32986, 33022, -1, 33000, 32986, 33027, -1, 33028, 32973, 33026, -1, 32963, 32968, 32989, -1, 32974, 32973, 33028, -1, 33029, 33030, 33031, -1, 33029, 33031, 33032, -1, 33033, 33034, 33035, -1, 33033, 33035, 33036, -1, 33037, 33025, 33024, -1, 33037, 33024, 33021, -1, 33037, 33021, 33038, -1, 33037, 33036, 33025, -1, 33039, 33040, 33041, -1, 33039, 33041, 33029, -1, 33039, 33029, 33034, -1, 33039, 33034, 33033, -1, 33042, 33038, 33043, -1, 33042, 33033, 33036, -1, 33042, 33037, 33038, -1, 33042, 33036, 33037, -1, 33044, 33043, 33045, -1, 33044, 33046, 33040, -1, 33044, 33033, 33042, -1, 33044, 33045, 33046, -1, 33044, 33040, 33039, -1, 33044, 33042, 33043, -1, 33044, 33039, 33033, -1, 32738, 33046, 33045, -1, 33047, 32975, 32972, -1, 33047, 33048, 32975, -1, 33049, 33050, 33048, -1, 33049, 33048, 33047, -1, 33051, 32972, 32974, -1, 33051, 33047, 32972, -1, 33052, 33053, 33054, -1, 33052, 33054, 33055, -1, 33052, 33055, 33050, -1, 33052, 33050, 33049, -1, 33056, 33047, 33051, -1, 33056, 33049, 33047, -1, 33057, 32974, 33028, -1, 33057, 33051, 32974, -1, 33058, 33059, 33053, -1, 33058, 33053, 33052, -1, 33058, 33052, 33049, -1, 33058, 33049, 33056, -1, 33032, 33056, 33051, -1, 33032, 33051, 33057, -1, 33035, 33028, 33026, -1, 33035, 33057, 33028, -1, 33031, 33030, 33059, -1, 33031, 33058, 33056, -1, 33031, 33059, 33058, -1, 33031, 33056, 33032, -1, 33034, 33032, 33057, -1, 33034, 33057, 33035, -1, 33036, 33026, 33025, -1, 33036, 33035, 33026, -1, 33029, 33041, 33030, -1, 33029, 33032, 33034, -1, 32785, 33060, 32765, -1, 32785, 33054, 33060, -1, 31252, 31251, 32877, -1, 32877, 31251, 32882, -1, 32882, 31225, 32888, -1, 31251, 31225, 32882, -1, 32888, 31224, 32890, -1, 31225, 31224, 32888, -1, 32890, 31272, 32866, -1, 31224, 31272, 32890, -1, 32866, 31257, 32868, -1, 31272, 31257, 32866, -1, 32868, 31229, 32876, -1, 31257, 31229, 32868, -1, 32876, 31228, 32880, -1, 31229, 31228, 32876, -1, 32880, 31274, 32883, -1, 31228, 31274, 32880, -1, 32883, 31264, 32884, -1, 31274, 31264, 32883, -1, 32884, 31244, 32887, -1, 31264, 31244, 32884, -1, 32887, 31233, 32886, -1, 31244, 31233, 32887, -1, 32886, 31211, 32881, -1, 31233, 31211, 32886, -1, 32881, 31210, 32878, -1, 31211, 31210, 32881, -1, 31740, 31761, 31803, -1, 31740, 31803, 31713, -1, 32482, 31807, 31763, -1, 32482, 31763, 31762, -1, 32483, 31762, 31764, -1, 32483, 32482, 31762, -1, 32486, 31764, 31768, -1, 32486, 32483, 31764, -1, 31772, 32490, 32486, -1, 31768, 31772, 32486, -1, 31758, 32476, 31733, -1, 31733, 32476, 31739, -1, 31739, 32477, 31741, -1, 32476, 32477, 31739, -1, 31741, 32478, 31742, -1, 32477, 32478, 31741, -1, 31742, 32479, 31743, -1, 32478, 32479, 31742, -1, 31743, 32480, 31736, -1, 32479, 32480, 31743, -1, 31736, 32481, 31734, -1, 32480, 32481, 31736, -1, 31734, 32470, 31737, -1, 32481, 32470, 31734, -1, 31737, 32475, 31738, -1, 32470, 32475, 31737, -1, 31738, 32474, 31729, -1, 32475, 32474, 31738, -1, 31729, 32473, 31727, -1, 32474, 32473, 31729, -1, 31727, 32472, 31730, -1, 32473, 32472, 31727, -1, 31730, 32471, 31731, -1, 32472, 32471, 31730, -1, 31731, 31745, 31721, -1, 32471, 31745, 31731, -1, 3218, 31324, 31322, -1, 3203, 31324, 3218, -1, 30147, 31490, 3203, -1, 3203, 31490, 31324, -1, 31490, 33061, 33062, -1, 30147, 33063, 31490, -1, 31490, 33063, 33061, -1, 3208, 31344, 31338, -1, 3205, 33064, 3208, -1, 3208, 33064, 31344, -1, 3205, 33065, 33064, -1, 3205, 33066, 33065, -1, 3205, 33067, 33066, -1, 3205, 33068, 33067, -1, 3205, 30136, 33068, -1, 30136, 33069, 33068, -1, 33069, 33070, 33071, -1, 30136, 33072, 33069, -1, 33069, 33072, 33070, -1, 33069, 33073, 33068, -1, 33073, 33074, 33068, -1, 33075, 33076, 33077, -1, 33078, 33076, 33075, -1, 30141, 33076, 33078, -1, 3204, 33079, 30141, -1, 30141, 33079, 33076, -1, 3204, 33080, 33079, -1, 3204, 33081, 33080, -1, 3204, 33082, 33081, -1, 3204, 31356, 33082, -1, 3204, 3217, 31356, -1, 3217, 31355, 31356, -1, 33083, 33079, 33084, -1, 33083, 33076, 33079, -1, 33085, 33086, 33087, -1, 33088, 33087, 33089, -1, 33088, 33085, 33087, -1, 33090, 33089, 33005, -1, 33090, 33088, 33089, -1, 33004, 33090, 33005, -1, 33091, 33085, 33092, -1, 33093, 33092, 33085, -1, 33094, 33085, 33091, -1, 33095, 33093, 33085, -1, 33096, 33085, 33094, -1, 33097, 33095, 33085, -1, 33098, 33085, 33096, -1, 33086, 33098, 33099, -1, 33086, 33085, 33098, -1, 33100, 33086, 33099, -1, 33101, 33086, 33100, -1, 33102, 33086, 33101, -1, 33103, 33086, 33102, -1, 33104, 33086, 33103, -1, 33105, 33097, 33085, -1, 33106, 33097, 33105, -1, 33107, 33104, 33108, -1, 33107, 33086, 33104, -1, 33109, 33110, 33111, -1, 33109, 33111, 33112, -1, 32857, 33112, 33113, -1, 32857, 33113, 33114, -1, 33115, 33114, 33113, -1, 33116, 33115, 33113, -1, 33117, 33116, 33113, -1, 33118, 33117, 33113, -1, 33119, 33113, 33120, -1, 33119, 33118, 33113, -1, 32852, 33109, 33112, -1, 32852, 33112, 32857, -1, 33121, 33119, 33120, -1, 33122, 32852, 33123, -1, 33122, 33123, 33124, -1, 33122, 33109, 32852, -1, 33125, 33121, 33120, -1, 33126, 33120, 33127, -1, 33126, 33125, 33120, -1, 33128, 33129, 33130, -1, 33128, 33131, 33129, -1, 33128, 33124, 33132, -1, 33128, 33132, 33133, -1, 33128, 33133, 33134, -1, 33128, 33134, 33131, -1, 33128, 33122, 33124, -1, 33135, 33127, 33107, -1, 33135, 33126, 33127, -1, 33108, 33135, 33107, -1, 33136, 33130, 33137, -1, 33136, 33128, 33130, -1, 33106, 33136, 33137, -1, 33105, 33136, 33106, -1, 33138, 33139, 33140, -1, 33138, 33110, 33139, -1, 33141, 33142, 33143, -1, 33141, 33143, 33144, -1, 33141, 33144, 33138, -1, 33141, 33138, 33140, -1, 33111, 33110, 33138, -1, 33141, 33140, 33145, -1, 33146, 33145, 33147, -1, 33146, 33147, 33148, -1, 33146, 33141, 33145, -1, 33149, 33111, 33138, -1, 33150, 33138, 33151, -1, 33150, 33149, 33138, -1, 33152, 33151, 33153, -1, 33152, 33150, 33151, -1, 33144, 33151, 33138, -1, 33121, 33126, 33119, -1, 33125, 33126, 33121, -1, 33126, 33154, 33119, -1, 33126, 33155, 33154, -1, 33155, 33156, 33154, -1, 33155, 33157, 33156, -1, 33157, 33158, 33156, -1, 33157, 33159, 33158, -1, 33159, 33160, 33158, -1, 33159, 33161, 33160, -1, 33161, 33162, 33160, -1, 33161, 33163, 33162, -1, 33163, 33164, 33162, -1, 33163, 33165, 33164, -1, 33165, 33166, 33164, -1, 33165, 33167, 33166, -1, 33167, 33168, 33166, -1, 33167, 33169, 33168, -1, 33169, 33170, 33168, -1, 33169, 33171, 33170, -1, 33171, 33172, 33170, -1, 33171, 33173, 33172, -1, 33173, 33174, 33172, -1, 33173, 33175, 33174, -1, 33175, 33176, 33174, -1, 33175, 33177, 33176, -1, 33177, 33178, 33176, -1, 33177, 33179, 33178, -1, 33179, 33180, 33178, -1, 33179, 33181, 33180, -1, 33181, 33137, 33180, -1, 33130, 33129, 33137, -1, 33137, 33131, 33180, -1, 33129, 33131, 33137, -1, 33182, 31443, 31442, -1, 33182, 31442, 31472, -1, 33183, 33182, 31472, -1, 33184, 31472, 31482, -1, 33184, 33183, 31472, -1, 33185, 31482, 31486, -1, 33185, 33184, 31482, -1, 33186, 31486, 31466, -1, 33186, 31466, 31465, -1, 33186, 33185, 31486, -1, 33139, 31465, 31474, -1, 33139, 31474, 33140, -1, 33139, 33186, 31465, -1, 30643, 31866, 30647, -1, 30647, 31868, 30649, -1, 31866, 31868, 30647, -1, 30649, 31871, 30652, -1, 31868, 31871, 30649, -1, 30652, 31880, 30654, -1, 31871, 31880, 30652, -1, 31880, 31883, 30654, -1, 30661, 31899, 31905, -1, 30661, 30660, 31899, -1, 30662, 31905, 31904, -1, 30662, 30661, 31905, -1, 30663, 31904, 31907, -1, 30663, 30662, 31904, -1, 30631, 31907, 31906, -1, 30631, 30663, 31907, -1, 33152, 33153, 33187, -1, 33188, 33187, 33189, -1, 33188, 33152, 33187, -1, 33190, 33189, 31282, -1, 33190, 33188, 33189, -1, 31281, 33190, 31282, -1, 33191, 33192, 33193, -1, 33191, 33193, 33194, -1, 33191, 33113, 33192, -1, 33195, 33196, 33197, -1, 33198, 33199, 33200, -1, 33195, 33197, 33201, -1, 33202, 33203, 33204, -1, 33202, 33204, 33205, -1, 33206, 33207, 33208, -1, 31285, 33188, 33190, -1, 33206, 33208, 33209, -1, 31285, 33190, 31281, -1, 33206, 33210, 33207, -1, 33211, 33152, 33188, -1, 33211, 33188, 31285, -1, 33212, 33213, 33214, -1, 33212, 33215, 33213, -1, 33211, 31285, 33216, -1, 33217, 33218, 33219, -1, 33217, 33219, 33220, -1, 33221, 33194, 33196, -1, 33221, 33196, 33195, -1, 33222, 33199, 33198, -1, 33222, 33216, 33199, -1, 33223, 33201, 33215, -1, 33224, 33225, 33203, -1, 33223, 33215, 33212, -1, 33224, 33200, 33225, -1, 33226, 33209, 33227, -1, 33226, 33214, 33210, -1, 33226, 33206, 33209, -1, 33228, 33200, 33224, -1, 33226, 33210, 33206, -1, 33228, 33198, 33200, -1, 33229, 33120, 33113, -1, 33229, 33221, 33120, -1, 33229, 33113, 33191, -1, 33230, 33149, 33150, -1, 33229, 33191, 33194, -1, 33230, 33150, 33152, -1, 33229, 33194, 33221, -1, 33230, 33112, 33149, -1, 33231, 33201, 33223, -1, 33230, 33152, 33211, -1, 33231, 33195, 33201, -1, 33232, 33227, 33233, -1, 33234, 33218, 33217, -1, 33232, 33214, 33226, -1, 33234, 33205, 33218, -1, 33232, 33212, 33214, -1, 33232, 33226, 33227, -1, 33235, 33224, 33203, -1, 33236, 33120, 33221, -1, 33235, 33203, 33202, -1, 33236, 33127, 33120, -1, 33236, 33221, 33195, -1, 33236, 33195, 33231, -1, 33237, 33233, 33238, -1, 33239, 33220, 33240, -1, 33237, 33223, 33212, -1, 33237, 33232, 33233, -1, 33241, 33112, 33230, -1, 33241, 33216, 33222, -1, 33237, 33212, 33232, -1, 33241, 33211, 33216, -1, 33242, 33238, 33243, -1, 33241, 33230, 33211, -1, 33242, 33223, 33237, -1, 33112, 33111, 33149, -1, 33242, 33231, 33223, -1, 33242, 33237, 33238, -1, 33244, 33222, 33198, -1, 33244, 33198, 33228, -1, 33245, 33127, 33236, -1, 33245, 33236, 33231, -1, 33197, 33224, 33235, -1, 33245, 33242, 33243, -1, 33197, 33228, 33224, -1, 33245, 33231, 33242, -1, 33246, 33243, 33107, -1, 33246, 33107, 33127, -1, 33207, 33220, 33239, -1, 33246, 33245, 33243, -1, 33246, 33127, 33245, -1, 33207, 33217, 33220, -1, 33213, 33202, 33205, -1, 33213, 33205, 33234, -1, 33196, 33228, 33197, -1, 33196, 33244, 33228, -1, 33193, 33241, 33222, -1, 33193, 33222, 33244, -1, 33210, 33217, 33207, -1, 33210, 33234, 33217, -1, 33215, 33235, 33202, -1, 33215, 33202, 33213, -1, 33247, 33248, 33249, -1, 33247, 33240, 33248, -1, 33247, 33249, 33250, -1, 33247, 33239, 33240, -1, 33192, 33113, 33112, -1, 33192, 33241, 33193, -1, 33192, 33112, 33241, -1, 33194, 33193, 33244, -1, 33204, 33251, 33252, -1, 33194, 33244, 33196, -1, 33201, 33197, 33235, -1, 33205, 33252, 33218, -1, 33205, 33204, 33252, -1, 33201, 33235, 33215, -1, 33216, 31285, 33199, -1, 33208, 33207, 33239, -1, 33208, 33239, 33247, -1, 33200, 33199, 33225, -1, 33208, 33250, 33209, -1, 33208, 33247, 33250, -1, 33203, 33225, 33251, -1, 33214, 33234, 33210, -1, 33214, 33213, 33234, -1, 33203, 33251, 33204, -1, 33220, 33219, 33253, -1, 33220, 33253, 33240, -1, 33254, 33255, 33256, -1, 33255, 33257, 33256, -1, 33255, 33258, 33257, -1, 33258, 33259, 33257, -1, 33259, 33260, 33257, -1, 33260, 33249, 33257, -1, 33248, 33253, 33249, -1, 33248, 33240, 33253, -1, 33253, 33257, 33249, -1, 33254, 33261, 33262, -1, 33256, 33261, 33254, -1, 33262, 33263, 33264, -1, 33261, 33263, 33262, -1, 33264, 33265, 33266, -1, 33263, 33265, 33264, -1, 33266, 33267, 33268, -1, 33265, 33267, 33266, -1, 33269, 33268, 33267, -1, 33270, 33268, 33269, -1, 33271, 33272, 33273, -1, 33271, 33273, 33274, -1, 33275, 33274, 33276, -1, 33275, 33271, 33274, -1, 33277, 33276, 33278, -1, 33277, 33275, 33276, -1, 33269, 33278, 33270, -1, 33269, 33277, 33278, -1, 33279, 33273, 33272, -1, 33279, 33272, 33280, -1, 33281, 33107, 33243, -1, 33281, 33086, 33107, -1, 33282, 33243, 33238, -1, 33282, 33281, 33243, -1, 33283, 33238, 33233, -1, 33283, 33282, 33238, -1, 33284, 33233, 33227, -1, 33284, 33283, 33233, -1, 33285, 33227, 33209, -1, 33285, 33284, 33227, -1, 33286, 33209, 33250, -1, 33286, 33285, 33209, -1, 33260, 33250, 33249, -1, 33260, 33286, 33250, -1, 33287, 33089, 33087, -1, 33287, 33005, 33089, -1, 33287, 33288, 33289, -1, 33287, 33087, 33290, -1, 33287, 33290, 33288, -1, 33287, 33289, 33291, -1, 33292, 33258, 33255, -1, 33293, 33285, 33286, -1, 33293, 33286, 33260, -1, 33293, 33260, 33259, -1, 33294, 33284, 33285, -1, 33294, 33285, 33293, -1, 33295, 33259, 33258, -1, 33295, 33293, 33259, -1, 33295, 33258, 33292, -1, 33296, 33283, 33284, -1, 33296, 33284, 33294, -1, 33297, 33292, 33298, -1, 33297, 33294, 33293, -1, 33297, 33293, 33295, -1, 33297, 33295, 33292, -1, 33299, 33282, 33283, -1, 33299, 33283, 33296, -1, 33300, 33298, 33301, -1, 33300, 33296, 33294, -1, 33300, 33297, 33298, -1, 33300, 33294, 33297, -1, 33288, 33281, 33282, -1, 33288, 33282, 33299, -1, 33302, 33301, 33303, -1, 33302, 33296, 33300, -1, 33302, 33300, 33301, -1, 33302, 33299, 33296, -1, 33290, 33086, 33281, -1, 33290, 33087, 33086, -1, 33290, 33281, 33288, -1, 33289, 33303, 33291, -1, 33289, 33288, 33299, -1, 33289, 33302, 33303, -1, 33289, 33299, 33302, -1, 33287, 33304, 33005, -1, 33287, 33291, 33304, -1, 33305, 33005, 33304, -1, 33305, 33003, 33005, -1, 33306, 33304, 33291, -1, 33306, 33305, 33304, -1, 33307, 33291, 33303, -1, 33307, 33306, 33291, -1, 33308, 33303, 33301, -1, 33308, 33307, 33303, -1, 33309, 33301, 33298, -1, 33309, 33308, 33301, -1, 33310, 33298, 33292, -1, 33310, 33309, 33298, -1, 33254, 33292, 33255, -1, 33254, 33310, 33292, -1, 33311, 33312, 33313, -1, 33314, 33305, 33306, -1, 33314, 33315, 33305, -1, 33314, 33316, 33317, -1, 33314, 33317, 33315, -1, 33318, 33319, 33312, -1, 33318, 33312, 33311, -1, 33320, 33306, 33307, -1, 33320, 33321, 33316, -1, 33320, 33314, 33306, -1, 33320, 33316, 33314, -1, 33322, 33264, 33266, -1, 33322, 33319, 33318, -1, 33322, 33266, 33323, -1, 33322, 33323, 33319, -1, 33324, 33307, 33308, -1, 33324, 33321, 33320, -1, 33324, 33311, 33321, -1, 33324, 33320, 33307, -1, 33325, 33308, 33309, -1, 33325, 33324, 33308, -1, 33325, 33318, 33311, -1, 33325, 33311, 33324, -1, 33326, 33309, 33310, -1, 33326, 33310, 33254, -1, 33326, 33262, 33264, -1, 33326, 33254, 33262, -1, 33326, 33264, 33322, -1, 33266, 33268, 33327, -1, 33326, 33322, 33318, -1, 33326, 33325, 33309, -1, 33326, 33318, 33325, -1, 33305, 33002, 33003, -1, 33328, 33329, 32984, -1, 33328, 32984, 32995, -1, 33330, 33331, 33329, -1, 33330, 33329, 33328, -1, 33313, 33332, 33331, -1, 33313, 33331, 33330, -1, 33317, 32995, 32998, -1, 33317, 33328, 32995, -1, 33312, 33333, 33332, -1, 33312, 33332, 33313, -1, 33316, 33330, 33328, -1, 33316, 33328, 33317, -1, 33319, 33334, 33333, -1, 33319, 33333, 33312, -1, 33321, 33330, 33316, -1, 33321, 33313, 33330, -1, 33315, 32998, 33002, -1, 33315, 33002, 33305, -1, 33315, 33317, 32998, -1, 33323, 33327, 33334, -1, 33323, 33266, 33327, -1, 33323, 33334, 33319, -1, 33311, 33313, 33321, -1, 33335, 32984, 33329, -1, 33335, 32988, 32984, -1, 33336, 33329, 33331, -1, 33336, 33335, 33329, -1, 33337, 33331, 33332, -1, 33337, 33336, 33331, -1, 33338, 33332, 33333, -1, 33338, 33337, 33332, -1, 33339, 33333, 33334, -1, 33339, 33338, 33333, -1, 33340, 33334, 33327, -1, 33340, 33339, 33334, -1, 33270, 33327, 33268, -1, 33270, 33340, 33327, -1, 33341, 33342, 33343, -1, 33344, 33335, 33336, -1, 33344, 32992, 32991, -1, 33344, 33336, 33345, -1, 33344, 32991, 33335, -1, 33346, 33347, 33348, -1, 33346, 33349, 33350, -1, 33346, 33350, 33347, -1, 33346, 33351, 33349, -1, 33352, 33345, 33342, -1, 33352, 33342, 33341, -1, 33353, 33348, 33354, -1, 33353, 33341, 33351, -1, 33353, 33346, 33348, -1, 33353, 33351, 33346, -1, 33355, 32993, 32992, -1, 33355, 32992, 33344, -1, 33355, 33344, 33345, -1, 33355, 33345, 33352, -1, 33356, 33354, 33357, -1, 33356, 33341, 33353, -1, 33356, 33353, 33354, -1, 33356, 33352, 33341, -1, 33358, 33359, 32963, -1, 33358, 33357, 33359, -1, 33358, 32963, 32993, -1, 33358, 32993, 33355, -1, 33358, 33355, 33352, -1, 33358, 33356, 33357, -1, 33358, 33352, 33356, -1, 33360, 33274, 33273, -1, 32991, 32988, 33335, -1, 33361, 33340, 33270, -1, 33361, 33270, 33278, -1, 33362, 33339, 33340, -1, 33362, 33340, 33361, -1, 33363, 33278, 33276, -1, 33363, 33361, 33278, -1, 33343, 33338, 33339, -1, 33343, 33339, 33362, -1, 33349, 33362, 33361, -1, 33349, 33361, 33363, -1, 33342, 33337, 33338, -1, 33342, 33338, 33343, -1, 33364, 33276, 33274, -1, 33364, 33363, 33276, -1, 33364, 33274, 33360, -1, 33351, 33343, 33362, -1, 33351, 33362, 33349, -1, 33345, 33336, 33337, -1, 33345, 33337, 33342, -1, 33350, 33360, 33347, -1, 33350, 33349, 33363, -1, 33350, 33363, 33364, -1, 33350, 33364, 33360, -1, 33341, 33343, 33351, -1, 33365, 32963, 33359, -1, 33365, 32973, 32963, -1, 33366, 33359, 33357, -1, 33366, 33365, 33359, -1, 33367, 33357, 33354, -1, 33367, 33366, 33357, -1, 33368, 33354, 33348, -1, 33368, 33367, 33354, -1, 33369, 33348, 33347, -1, 33369, 33368, 33348, -1, 33370, 33347, 33360, -1, 33370, 33369, 33347, -1, 33279, 33360, 33273, -1, 33279, 33370, 33360, -1, 33371, 32997, 33006, -1, 33371, 33006, 33372, -1, 33373, 33372, 33374, -1, 33373, 33371, 33372, -1, 33375, 33374, 33376, -1, 33375, 33373, 33374, -1, 33377, 33376, 33378, -1, 33377, 33375, 33376, -1, 33379, 33378, 33380, -1, 33379, 33377, 33378, -1, 33381, 33380, 33382, -1, 33381, 33379, 33380, -1, 33383, 33382, 33384, -1, 33383, 33381, 33382, -1, 33383, 33385, 33386, -1, 33383, 33384, 33385, -1, 33383, 33386, 33387, -1, 33387, 33388, 33389, -1, 33386, 33388, 33387, -1, 33389, 33390, 33391, -1, 33388, 33390, 33389, -1, 33391, 33392, 33393, -1, 33390, 33392, 33391, -1, 33392, 33394, 33393, -1, 33395, 33396, 33397, -1, 33396, 33393, 33394, -1, 33395, 33393, 33396, -1, 33398, 33399, 33400, -1, 33401, 33400, 33402, -1, 33401, 33398, 33400, -1, 33403, 33402, 33404, -1, 33403, 33401, 33402, -1, 33405, 33404, 33395, -1, 33405, 33403, 33404, -1, 33397, 33405, 33395, -1, 33406, 33407, 33408, -1, 33409, 33407, 33406, -1, 33407, 33410, 33411, -1, 33410, 33412, 33411, -1, 33413, 33414, 33415, -1, 33411, 33414, 33413, -1, 33412, 33414, 33411, -1, 33415, 33399, 33398, -1, 33414, 33399, 33415, -1, 33416, 33417, 33418, -1, 33419, 33417, 33416, -1, 33420, 33417, 33419, -1, 33421, 33417, 33420, -1, 33422, 33417, 33421, -1, 33423, 33424, 33418, -1, 33417, 33425, 33418, -1, 33418, 33425, 33423, -1, 33424, 33426, 33418, -1, 33417, 33427, 33425, -1, 33417, 33428, 33427, -1, 33417, 33429, 33428, -1, 33417, 33430, 33429, -1, 33430, 33431, 33429, -1, 33432, 33433, 33430, -1, 33430, 33434, 33431, -1, 33433, 33435, 33430, -1, 33430, 33436, 33434, -1, 33435, 33437, 33430, -1, 33430, 33438, 33436, -1, 33437, 33409, 33430, -1, 33430, 33409, 33438, -1, 33426, 33439, 33418, -1, 33409, 33440, 33438, -1, 33409, 33441, 33440, -1, 33409, 33406, 33441, -1, 33426, 33442, 33439, -1, 33442, 33443, 33439, -1, 33443, 33444, 33439, -1, 33444, 33445, 33439, -1, 33445, 33446, 33439, -1, 33445, 33447, 33446, -1, 33408, 33407, 33411, -1, 33448, 33449, 33450, -1, 33438, 33440, 33451, -1, 33452, 33453, 33449, -1, 33452, 33454, 33453, -1, 33452, 33455, 33454, -1, 33456, 33457, 33455, -1, 33456, 33455, 33452, -1, 33458, 33459, 33457, -1, 33458, 33457, 33456, -1, 33460, 33441, 33406, -1, 33460, 33440, 33441, -1, 33460, 33461, 33459, -1, 33460, 33406, 33461, -1, 33460, 33459, 33458, -1, 33462, 33448, 33463, -1, 33462, 33463, 33464, -1, 33462, 33464, 33451, -1, 33462, 33456, 33452, -1, 33462, 33440, 33460, -1, 33462, 33452, 33449, -1, 33462, 33460, 33458, -1, 33462, 33449, 33448, -1, 33462, 33451, 33440, -1, 33462, 33458, 33456, -1, 33465, 33466, 33467, -1, 33425, 33427, 33468, -1, 33469, 33470, 33466, -1, 33469, 33471, 33470, -1, 33469, 33472, 33471, -1, 33473, 33474, 33472, -1, 33473, 33472, 33469, -1, 33475, 33476, 33474, -1, 33475, 33474, 33473, -1, 33477, 33428, 33429, -1, 33477, 33427, 33428, -1, 33477, 33478, 33476, -1, 33477, 33429, 33478, -1, 33477, 33476, 33475, -1, 33479, 33465, 33480, -1, 33479, 33480, 33481, -1, 33479, 33481, 33468, -1, 33479, 33473, 33469, -1, 33479, 33427, 33477, -1, 33479, 33469, 33466, -1, 33479, 33477, 33475, -1, 33479, 33466, 33465, -1, 33479, 33468, 33427, -1, 33479, 33475, 33473, -1, 33446, 33447, 33482, -1, 33483, 33482, 33484, -1, 33483, 33446, 33482, -1, 33485, 33484, 33486, -1, 33485, 33483, 33484, -1, 33487, 33485, 33486, -1, 33486, 33488, 33487, -1, 33488, 33489, 33487, -1, 33488, 33490, 33489, -1, 33491, 33492, 33493, -1, 33493, 33492, 33494, -1, 33492, 33495, 33494, -1, 33494, 33496, 33497, -1, 33495, 33496, 33494, -1, 33496, 33498, 33497, -1, 33497, 33499, 33490, -1, 33498, 33499, 33497, -1, 33499, 33489, 33490, -1, 33500, 33501, 33502, -1, 33502, 33501, 33503, -1, 33503, 33501, 33504, -1, 33500, 33505, 33501, -1, 33506, 33505, 33507, -1, 33507, 33505, 33508, -1, 33508, 33505, 33509, -1, 33509, 33505, 33500, -1, 33491, 33510, 33511, -1, 33512, 33505, 33506, -1, 33513, 33505, 33512, -1, 33493, 33505, 33514, -1, 33514, 33505, 33515, -1, 33515, 33505, 33513, -1, 33515, 33513, 33516, -1, 33491, 33517, 33510, -1, 33491, 33518, 33517, -1, 33491, 33519, 33518, -1, 33520, 33493, 33521, -1, 33522, 33493, 33520, -1, 33523, 33493, 33522, -1, 33519, 33493, 33523, -1, 33491, 33493, 33519, -1, 33493, 33524, 33521, -1, 33493, 33514, 33524, -1, 33525, 33526, 33527, -1, 33528, 33526, 33525, -1, 33529, 33526, 33528, -1, 33530, 33531, 33529, -1, 33529, 33531, 33526, -1, 33530, 33532, 33531, -1, 33515, 33516, 33530, -1, 33530, 33516, 33532, -1, 33504, 33501, 33533, -1, 33534, 33535, 33536, -1, 33535, 33537, 33536, -1, 33536, 33538, 33539, -1, 33537, 33538, 33536, -1, 33539, 33450, 33540, -1, 33538, 33450, 33539, -1, 33540, 33449, 33541, -1, 33450, 33449, 33540, -1, 33541, 33453, 33542, -1, 33449, 33453, 33541, -1, 33542, 33454, 33543, -1, 33453, 33454, 33542, -1, 33544, 33545, 33546, -1, 33545, 33547, 33546, -1, 33548, 33549, 33550, -1, 33551, 33549, 33548, -1, 33543, 33546, 33552, -1, 33553, 33552, 33547, -1, 33547, 33552, 33546, -1, 33550, 33554, 33555, -1, 33556, 33557, 33558, -1, 33556, 33558, 33559, -1, 33549, 33554, 33550, -1, 33554, 33560, 33555, -1, 33560, 33534, 33555, -1, 33539, 33540, 33536, -1, 33540, 33541, 33536, -1, 33536, 33542, 33534, -1, 33541, 33542, 33536, -1, 33542, 33543, 33534, -1, 33555, 33561, 33562, -1, 33562, 33563, 33555, -1, 33555, 33564, 33561, -1, 33563, 33556, 33555, -1, 33555, 33565, 33564, -1, 33555, 33566, 33565, -1, 33534, 33567, 33555, -1, 33555, 33567, 33566, -1, 33543, 33567, 33534, -1, 33556, 33559, 33555, -1, 33559, 33568, 33569, -1, 33559, 33558, 33568, -1, 33543, 33570, 33567, -1, 33543, 33571, 33570, -1, 33543, 33572, 33571, -1, 33543, 33573, 33572, -1, 33543, 33574, 33573, -1, 33543, 33552, 33574, -1, 33575, 33576, 33577, -1, 33575, 33578, 33576, -1, 33579, 33580, 33578, -1, 33579, 33578, 33575, -1, 33567, 33580, 33579, -1, 33566, 33567, 33579, -1, 33558, 33557, 33581, -1, 33582, 33583, 33557, -1, 33584, 33583, 33582, -1, 33585, 33583, 33584, -1, 33557, 33583, 33581, -1, 33583, 33586, 33587, -1, 33585, 33588, 33583, -1, 33583, 33588, 33586, -1, 33585, 33589, 33588, -1, 33590, 33591, 33592, -1, 33590, 33593, 33591, -1, 33594, 33595, 33590, -1, 33590, 33595, 33593, -1, 33594, 33596, 33595, -1, 33596, 33597, 33595, -1, 33597, 33598, 33595, -1, 33598, 33553, 33595, -1, 33547, 33599, 33553, -1, 33553, 33599, 33595, -1, 33600, 33601, 33602, -1, 33603, 33604, 33605, -1, 33606, 33601, 33600, -1, 33607, 33608, 33609, -1, 33601, 33610, 33602, -1, 33611, 33612, 33613, -1, 33614, 33615, 33604, -1, 33616, 33617, 33618, -1, 33618, 33619, 33616, -1, 33616, 33620, 33617, -1, 33621, 33622, 33611, -1, 33611, 33622, 33612, -1, 33613, 33623, 33624, -1, 33612, 33623, 33613, -1, 33625, 33626, 33627, -1, 33619, 33628, 33616, -1, 33616, 33629, 33620, -1, 33621, 33630, 33622, -1, 33631, 33630, 33621, -1, 33625, 33632, 33626, -1, 33633, 33632, 33625, -1, 33623, 33634, 33624, -1, 33628, 33635, 33616, -1, 33624, 33634, 33636, -1, 33616, 33637, 33629, -1, 33616, 33638, 33637, -1, 33633, 33639, 33632, -1, 33640, 33639, 33633, -1, 33616, 33641, 33638, -1, 33631, 33642, 33630, -1, 33643, 33642, 33631, -1, 33640, 33644, 33639, -1, 33645, 33644, 33640, -1, 33634, 33646, 33636, -1, 33647, 33648, 33649, -1, 33650, 33648, 33614, -1, 33651, 33648, 33650, -1, 33645, 33652, 33644, -1, 33649, 33648, 33651, -1, 33653, 33648, 33654, -1, 33655, 33652, 33645, -1, 33643, 33656, 33642, -1, 33657, 33648, 33653, -1, 33614, 33648, 33615, -1, 33658, 33648, 33596, -1, 33659, 33648, 33658, -1, 33660, 33648, 33659, -1, 33661, 33648, 33660, -1, 33662, 33648, 33661, -1, 33663, 33648, 33662, -1, 33655, 33664, 33652, -1, 33665, 33648, 33663, -1, 33666, 33664, 33655, -1, 33667, 33648, 33665, -1, 33615, 33648, 33667, -1, 33668, 33669, 33635, -1, 33654, 33648, 33647, -1, 33670, 33669, 33671, -1, 33672, 33648, 33673, -1, 33671, 33669, 33674, -1, 33673, 33648, 33675, -1, 33674, 33669, 33676, -1, 33675, 33648, 33677, -1, 33676, 33669, 33668, -1, 33677, 33648, 33678, -1, 33678, 33648, 33607, -1, 33607, 33648, 33608, -1, 33608, 33648, 33679, -1, 33635, 33669, 33616, -1, 33679, 33648, 33680, -1, 33680, 33648, 33681, -1, 33666, 33682, 33664, -1, 33681, 33648, 33683, -1, 33683, 33648, 33684, -1, 33684, 33648, 33685, -1, 33685, 33648, 33686, -1, 33686, 33648, 33687, -1, 33687, 33648, 33688, -1, 33689, 33682, 33666, -1, 33688, 33648, 33690, -1, 33690, 33648, 33691, -1, 33691, 33648, 33692, -1, 33692, 33648, 33693, -1, 33693, 33648, 33694, -1, 33694, 33648, 33695, -1, 33695, 33648, 33696, -1, 33696, 33648, 33689, -1, 33689, 33648, 33697, -1, 33697, 33648, 33698, -1, 33689, 33697, 33682, -1, 33698, 33648, 33699, -1, 33699, 33648, 33700, -1, 33700, 33648, 33701, -1, 33701, 33648, 33702, -1, 33702, 33648, 33703, -1, 33703, 33648, 33704, -1, 33704, 33648, 33657, -1, 33705, 33706, 33707, -1, 33707, 33706, 33708, -1, 33708, 33706, 33709, -1, 33709, 33706, 33710, -1, 33710, 33706, 33610, -1, 33610, 33706, 33602, -1, 33602, 33706, 33711, -1, 33711, 33706, 33712, -1, 33712, 33706, 33713, -1, 33713, 33706, 33714, -1, 33714, 33706, 33715, -1, 33715, 33706, 33716, -1, 33716, 33706, 33717, -1, 33670, 33718, 33669, -1, 33717, 33706, 33719, -1, 33719, 33706, 33720, -1, 33720, 33706, 33721, -1, 33722, 33723, 33670, -1, 33721, 33706, 33724, -1, 33724, 33706, 33725, -1, 33670, 33723, 33718, -1, 33725, 33706, 33646, -1, 33646, 33706, 33636, -1, 33636, 33706, 33726, -1, 33726, 33706, 33727, -1, 33727, 33706, 33728, -1, 33728, 33706, 33729, -1, 33730, 33731, 33732, -1, 33729, 33706, 33733, -1, 33732, 33731, 33734, -1, 33733, 33706, 33735, -1, 33718, 33736, 33669, -1, 33734, 33731, 33737, -1, 33735, 33706, 33738, -1, 33738, 33706, 33739, -1, 33739, 33706, 33740, -1, 33740, 33706, 33741, -1, 33741, 33706, 33742, -1, 33742, 33706, 33743, -1, 33744, 33745, 33746, -1, 33747, 33748, 33749, -1, 33750, 33751, 33752, -1, 33730, 33753, 33731, -1, 33736, 33754, 33669, -1, 33746, 33755, 33744, -1, 33756, 33757, 33758, -1, 33759, 33760, 33761, -1, 33749, 33762, 33747, -1, 33758, 33763, 33756, -1, 33627, 33764, 33765, -1, 33766, 33767, 33768, -1, 33722, 33769, 33723, -1, 33768, 33770, 33766, -1, 33771, 33753, 33730, -1, 33761, 33772, 33759, -1, 33773, 33774, 33775, -1, 33752, 33776, 33750, -1, 33765, 33625, 33627, -1, 33775, 33777, 33773, -1, 33778, 33779, 33780, -1, 33754, 33781, 33669, -1, 33782, 33783, 33784, -1, 33785, 33786, 33787, -1, 33785, 33787, 33788, -1, 33771, 33789, 33753, -1, 33790, 33780, 33779, -1, 33791, 33792, 33793, -1, 33794, 33795, 33796, -1, 33797, 33784, 33783, -1, 33798, 33793, 33792, -1, 33799, 33800, 33801, -1, 33722, 33802, 33769, -1, 33803, 33789, 33771, -1, 33731, 33804, 33737, -1, 33805, 33737, 33804, -1, 33669, 33806, 33807, -1, 33808, 33796, 33795, -1, 33807, 33806, 33809, -1, 33810, 33811, 33722, -1, 33810, 33722, 33812, -1, 33813, 33801, 33800, -1, 33781, 33806, 33669, -1, 33803, 33814, 33789, -1, 33809, 33815, 33816, -1, 33817, 33814, 33803, -1, 33806, 33815, 33809, -1, 33722, 33818, 33802, -1, 33817, 33819, 33814, -1, 33815, 33820, 33816, -1, 33816, 33820, 33821, -1, 33822, 33819, 33817, -1, 33823, 33824, 33825, -1, 33679, 33826, 33822, -1, 33820, 33827, 33821, -1, 33822, 33826, 33819, -1, 33828, 33829, 33823, -1, 33722, 33830, 33818, -1, 33823, 33829, 33824, -1, 33679, 33680, 33826, -1, 33722, 33811, 33830, -1, 33827, 33831, 33821, -1, 33825, 33832, 33833, -1, 33824, 33832, 33825, -1, 33834, 33763, 33828, -1, 33835, 33763, 33834, -1, 33756, 33763, 33835, -1, 33828, 33763, 33829, -1, 33833, 33836, 33837, -1, 33832, 33836, 33833, -1, 33787, 33838, 33839, -1, 33839, 33838, 33840, -1, 33840, 33838, 33831, -1, 33831, 33838, 33821, -1, 33837, 33709, 33710, -1, 33836, 33709, 33837, -1, 33787, 33841, 33838, -1, 33767, 33842, 33768, -1, 33843, 33844, 33845, -1, 33846, 33847, 33848, -1, 33846, 33849, 33847, -1, 33843, 33850, 33844, -1, 33844, 33851, 33845, -1, 33852, 33849, 33846, -1, 33767, 33853, 33842, -1, 33841, 33854, 33843, -1, 33847, 33855, 33848, -1, 33843, 33854, 33850, -1, 33848, 33855, 33856, -1, 33845, 33857, 33706, -1, 33767, 33858, 33853, -1, 33851, 33857, 33845, -1, 33859, 33858, 33767, -1, 33787, 33860, 33841, -1, 33852, 33861, 33849, -1, 33841, 33860, 33854, -1, 33862, 33861, 33852, -1, 33855, 33863, 33856, -1, 33856, 33863, 33864, -1, 33859, 33865, 33858, -1, 33866, 33865, 33859, -1, 33857, 33867, 33706, -1, 33787, 33868, 33860, -1, 33869, 33870, 33862, -1, 33862, 33870, 33861, -1, 33787, 33871, 33868, -1, 33866, 33872, 33865, -1, 33873, 33872, 33866, -1, 33787, 33786, 33871, -1, 33863, 33724, 33864, -1, 33864, 33724, 33725, -1, 33867, 33874, 33706, -1, 33875, 33876, 33873, -1, 33869, 33877, 33870, -1, 33873, 33876, 33872, -1, 33874, 33878, 33706, -1, 33879, 33880, 33875, -1, 33881, 33813, 33882, -1, 33875, 33880, 33876, -1, 33882, 33813, 33800, -1, 33698, 33699, 33879, -1, 33879, 33699, 33880, -1, 33883, 33884, 33881, -1, 33881, 33884, 33813, -1, 33885, 33886, 33887, -1, 33888, 33889, 33883, -1, 33883, 33889, 33884, -1, 33887, 33890, 33891, -1, 33888, 33892, 33889, -1, 33886, 33890, 33887, -1, 33893, 33892, 33888, -1, 33790, 33894, 33885, -1, 33885, 33894, 33886, -1, 33891, 33895, 33878, -1, 33890, 33895, 33891, -1, 33896, 33897, 33893, -1, 33790, 33898, 33894, -1, 33878, 33899, 33706, -1, 33893, 33897, 33892, -1, 33895, 33899, 33878, -1, 33790, 33900, 33898, -1, 33901, 33902, 33896, -1, 33896, 33902, 33897, -1, 33899, 33903, 33706, -1, 33790, 33904, 33900, -1, 33901, 33683, 33902, -1, 33681, 33683, 33901, -1, 33790, 33779, 33904, -1, 33903, 33743, 33706, -1, 33905, 33906, 33907, -1, 33908, 33909, 33910, -1, 33782, 33911, 33905, -1, 33905, 33911, 33906, -1, 33907, 33912, 33913, -1, 33772, 33914, 33759, -1, 33906, 33912, 33907, -1, 33772, 33915, 33914, -1, 33782, 33916, 33911, -1, 33913, 33917, 33918, -1, 33772, 33919, 33915, -1, 33912, 33917, 33913, -1, 33920, 33919, 33772, -1, 33782, 33921, 33916, -1, 33918, 33742, 33743, -1, 33922, 33923, 33924, -1, 33925, 33926, 33927, -1, 33917, 33742, 33918, -1, 33923, 33928, 33924, -1, 33782, 33929, 33921, -1, 33924, 33928, 33930, -1, 33931, 33932, 33925, -1, 33782, 33784, 33929, -1, 33922, 33933, 33923, -1, 33925, 33932, 33926, -1, 33934, 33933, 33922, -1, 33927, 33935, 33936, -1, 33926, 33935, 33927, -1, 33928, 33937, 33930, -1, 33931, 33748, 33932, -1, 33930, 33937, 33938, -1, 33939, 33748, 33931, -1, 33940, 33748, 33939, -1, 33934, 33941, 33933, -1, 33942, 33748, 33940, -1, 33749, 33748, 33942, -1, 33943, 33941, 33934, -1, 33935, 33944, 33936, -1, 33936, 33944, 33708, -1, 33937, 33945, 33938, -1, 33938, 33945, 33721, -1, 33920, 33946, 33919, -1, 33943, 33947, 33941, -1, 33948, 33946, 33920, -1, 33949, 33947, 33943, -1, 33944, 33707, 33708, -1, 33945, 33720, 33721, -1, 33948, 33950, 33946, -1, 33951, 33950, 33948, -1, 33952, 33953, 33954, -1, 33954, 33953, 33909, -1, 33909, 33953, 33910, -1, 33952, 33955, 33953, -1, 33951, 33956, 33950, -1, 33957, 33956, 33951, -1, 33958, 33959, 33957, -1, 33960, 33955, 33952, -1, 33961, 33672, 33962, -1, 33962, 33672, 33963, -1, 33963, 33672, 33964, -1, 33964, 33672, 33965, -1, 33965, 33672, 33966, -1, 33960, 33967, 33955, -1, 33957, 33959, 33956, -1, 33641, 33672, 33961, -1, 33700, 33701, 33958, -1, 33968, 33967, 33960, -1, 33616, 33672, 33641, -1, 33958, 33701, 33959, -1, 33968, 33969, 33967, -1, 33970, 33969, 33968, -1, 33971, 33972, 33970, -1, 33970, 33972, 33969, -1, 33672, 33973, 33966, -1, 33684, 33974, 33971, -1, 33971, 33974, 33972, -1, 33672, 33975, 33973, -1, 33684, 33685, 33974, -1, 33976, 33977, 33978, -1, 33643, 33979, 33656, -1, 33980, 33981, 33976, -1, 33976, 33981, 33977, -1, 33978, 33982, 33983, -1, 33977, 33982, 33978, -1, 33798, 33984, 33980, -1, 33980, 33984, 33981, -1, 33983, 33985, 33741, -1, 33982, 33985, 33983, -1, 33798, 33986, 33984, -1, 33985, 33740, 33741, -1, 33798, 33987, 33986, -1, 33988, 33989, 33990, -1, 33798, 33792, 33987, -1, 33991, 33992, 33988, -1, 33993, 33810, 33994, -1, 33994, 33810, 33995, -1, 33988, 33992, 33989, -1, 33995, 33810, 33996, -1, 33996, 33810, 33997, -1, 33997, 33810, 33812, -1, 33757, 33998, 33758, -1, 33999, 34000, 33979, -1, 33757, 34001, 33998, -1, 33979, 34000, 33656, -1, 34002, 34003, 33993, -1, 33990, 34004, 34005, -1, 33757, 34006, 34001, -1, 33993, 34003, 33810, -1, 33989, 34004, 33990, -1, 34007, 34006, 33757, -1, 34008, 34009, 33991, -1, 34007, 34010, 34006, -1, 34011, 34012, 34002, -1, 33991, 34009, 33992, -1, 34004, 34013, 34005, -1, 34014, 34010, 34007, -1, 34005, 34013, 34015, -1, 34002, 34012, 34003, -1, 34014, 34016, 34010, -1, 34017, 34016, 34014, -1, 34008, 34018, 34009, -1, 33975, 34019, 34011, -1, 34020, 34018, 34008, -1, 34017, 34021, 34016, -1, 33672, 34019, 33975, -1, 34022, 34021, 34017, -1, 34011, 34019, 34012, -1, 34023, 34024, 33999, -1, 33999, 34024, 34000, -1, 34013, 33717, 34015, -1, 34015, 33717, 33719, -1, 34022, 34025, 34021, -1, 33702, 34025, 34022, -1, 33672, 34026, 34019, -1, 34027, 34028, 34029, -1, 34027, 34030, 34028, -1, 34031, 34032, 34023, -1, 34033, 34030, 34027, -1, 34023, 34032, 34024, -1, 33672, 34034, 34026, -1, 34031, 34035, 34032, -1, 34029, 34036, 34037, -1, 34038, 34035, 34031, -1, 34028, 34036, 34029, -1, 34033, 33755, 34030, -1, 34039, 33755, 34033, -1, 34038, 34040, 34035, -1, 34041, 33755, 34039, -1, 34042, 33755, 34041, -1, 33744, 33755, 34042, -1, 34043, 34040, 34038, -1, 34043, 34044, 34040, -1, 34045, 34044, 34043, -1, 33702, 33703, 34025, -1, 34036, 34046, 34037, -1, 33672, 34047, 34034, -1, 34045, 33687, 34044, -1, 34037, 34046, 34048, -1, 33686, 33687, 34045, -1, 34046, 33705, 34048, -1, 34049, 33705, 33707, -1, 34048, 33705, 34049, -1, 33869, 34050, 33877, -1, 34051, 33705, 34046, -1, 34052, 34053, 34054, -1, 34055, 34056, 34052, -1, 34052, 34056, 34053, -1, 34053, 34057, 34054, -1, 34054, 34057, 34058, -1, 34055, 34059, 34056, -1, 33794, 34059, 34055, -1, 34057, 34060, 34058, -1, 34058, 34060, 34061, -1, 33794, 34062, 34059, -1, 34060, 33738, 34061, -1, 34061, 33738, 33739, -1, 33794, 34063, 34062, -1, 34064, 34065, 34050, -1, 34050, 34065, 33877, -1, 33794, 33796, 34063, -1, 34066, 33785, 34067, -1, 34067, 33785, 34068, -1, 34069, 34070, 34064, -1, 34068, 33785, 34071, -1, 34071, 33785, 34072, -1, 34064, 34070, 34065, -1, 34072, 33785, 33788, -1, 34051, 34073, 33705, -1, 34074, 34075, 34069, -1, 34069, 34075, 34070, -1, 34076, 34077, 34066, -1, 34066, 34077, 33785, -1, 34074, 34078, 34075, -1, 34079, 34080, 34076, -1, 34076, 34080, 34077, -1, 34081, 34078, 34074, -1, 34082, 34083, 34079, -1, 34081, 34084, 34078, -1, 34079, 34083, 34080, -1, 33705, 34085, 34086, -1, 34087, 34084, 34081, -1, 34073, 34085, 33705, -1, 34047, 34088, 34082, -1, 34089, 34090, 34091, -1, 34085, 34092, 34086, -1, 34082, 34088, 34083, -1, 34089, 34093, 34090, -1, 33672, 34094, 34047, -1, 34095, 34093, 34089, -1, 34086, 34096, 34097, -1, 34092, 34096, 34086, -1, 34047, 34094, 34088, -1, 34090, 34098, 34091, -1, 34091, 34098, 34099, -1, 34096, 34100, 34097, -1, 34087, 34101, 34084, -1, 34102, 34101, 34087, -1, 34095, 34103, 34093, -1, 34097, 34104, 34105, -1, 34106, 34103, 34095, -1, 34098, 34107, 34099, -1, 34099, 34107, 33716, -1, 34100, 34104, 34097, -1, 34108, 34109, 34106, -1, 34110, 34109, 34108, -1, 34106, 34109, 34103, -1, 34104, 34111, 34105, -1, 34102, 34112, 34101, -1, 33688, 34112, 34102, -1, 34107, 33715, 33716, -1, 33672, 34113, 34094, -1, 33762, 34114, 33747, -1, 33688, 33690, 34112, -1, 33762, 34115, 34114, -1, 34116, 34117, 34118, -1, 34116, 34119, 34117, -1, 34120, 34119, 34116, -1, 33762, 34121, 34115, -1, 34122, 34123, 33762, -1, 34118, 34124, 34125, -1, 34117, 34124, 34118, -1, 34120, 34126, 34119, -1, 33762, 34123, 34121, -1, 33805, 34126, 34120, -1, 34124, 34127, 34125, -1, 34125, 34127, 34128, -1, 34129, 34130, 34131, -1, 34132, 34130, 34129, -1, 33805, 34133, 34126, -1, 34131, 34134, 34135, -1, 34130, 34134, 34131, -1, 34136, 34137, 33594, -1, 34127, 33733, 34128, -1, 34135, 34137, 34136, -1, 34134, 34137, 34135, -1, 34138, 34139, 34129, -1, 34128, 33733, 33735, -1, 34129, 34139, 34132, -1, 33805, 34140, 34133, -1, 34137, 34141, 33594, -1, 34142, 34143, 34122, -1, 33805, 33804, 34140, -1, 34122, 34143, 34123, -1, 34144, 33778, 34145, -1, 34138, 34146, 34139, -1, 34145, 33778, 34147, -1, 34147, 33778, 34148, -1, 34148, 33778, 33780, -1, 34144, 34149, 33778, -1, 34141, 34150, 33594, -1, 33949, 34151, 33947, -1, 34152, 34149, 34144, -1, 34138, 34153, 34146, -1, 34154, 34151, 33949, -1, 34152, 34155, 34149, -1, 34156, 34155, 34152, -1, 34154, 34157, 34151, -1, 34150, 34158, 33594, -1, 34159, 34157, 34154, -1, 34156, 34160, 34155, -1, 34161, 34162, 34142, -1, 34163, 34160, 34156, -1, 34142, 34162, 34143, -1, 34164, 34165, 34159, -1, 34163, 34166, 34160, -1, 34159, 34165, 34157, -1, 34158, 34167, 33594, -1, 34168, 34166, 34163, -1, 34164, 34169, 34165, -1, 34170, 34169, 34164, -1, 34105, 33776, 34138, -1, 34168, 34171, 34166, -1, 34111, 33776, 34105, -1, 34113, 34171, 34168, -1, 34172, 33776, 34111, -1, 33672, 34171, 34113, -1, 34170, 34173, 34169, -1, 34138, 33776, 34153, -1, 34174, 33776, 34172, -1, 33750, 33776, 34174, -1, 34175, 34173, 34170, -1, 34176, 34177, 34161, -1, 34175, 34178, 34173, -1, 34179, 34178, 34175, -1, 34161, 34177, 34162, -1, 34179, 34180, 34178, -1, 34181, 34180, 34179, -1, 33704, 33657, 34176, -1, 34176, 33657, 34177, -1, 34181, 33692, 34180, -1, 33691, 33692, 34181, -1, 33672, 33673, 34171, -1, 34182, 34183, 34184, -1, 34185, 34186, 34182, -1, 34182, 34186, 34183, -1, 34183, 34187, 34184, -1, 34184, 34187, 34188, -1, 34189, 34190, 34185, -1, 34185, 34190, 34186, -1, 34187, 34191, 34188, -1, 34188, 34191, 34192, -1, 34193, 33764, 34189, -1, 33765, 33764, 34193, -1, 34189, 33764, 34190, -1, 34191, 33713, 34192, -1, 34194, 34195, 34167, -1, 34192, 33713, 33714, -1, 34167, 34195, 33594, -1, 34195, 34196, 33594, -1, 34197, 33797, 34198, -1, 34198, 33797, 34199, -1, 34194, 33777, 34195, -1, 34199, 33797, 34200, -1, 34200, 33797, 33783, -1, 34201, 33777, 34194, -1, 34202, 33777, 34201, -1, 34203, 33777, 34202, -1, 34204, 33777, 34203, -1, 33773, 33777, 34204, -1, 34205, 34206, 34197, -1, 34196, 34207, 33594, -1, 34197, 34206, 33797, -1, 34207, 34208, 33594, -1, 34209, 34210, 34211, -1, 34208, 34212, 33594, -1, 34210, 34213, 34211, -1, 34211, 34213, 34214, -1, 34209, 34215, 34210, -1, 34216, 34215, 34209, -1, 34213, 34217, 34214, -1, 34214, 34217, 34218, -1, 33745, 34219, 33746, -1, 34220, 34221, 34205, -1, 34205, 34221, 34206, -1, 33745, 34222, 34219, -1, 33799, 34223, 34216, -1, 34216, 34223, 34215, -1, 34224, 34225, 34020, -1, 34218, 34226, 33729, -1, 34217, 34226, 34218, -1, 33745, 34227, 34222, -1, 33799, 34228, 34223, -1, 34020, 34225, 34018, -1, 34229, 34230, 34224, -1, 34231, 34232, 33745, -1, 34224, 34230, 34225, -1, 34226, 33728, 33729, -1, 33745, 34232, 34227, -1, 34233, 34234, 34231, -1, 34235, 34236, 34220, -1, 34237, 34238, 34229, -1, 34231, 34234, 34232, -1, 34220, 34236, 34221, -1, 34229, 34238, 34230, -1, 34239, 34240, 34233, -1, 33799, 33801, 34228, -1, 33673, 34241, 34235, -1, 34242, 34243, 34237, -1, 34233, 34240, 34234, -1, 34235, 34241, 34236, -1, 34244, 34245, 34239, -1, 34237, 34243, 34238, -1, 34239, 34245, 34240, -1, 33673, 33675, 34241, -1, 33653, 34246, 34244, -1, 34244, 34246, 34245, -1, 34247, 34248, 34242, -1, 33653, 33654, 34246, -1, 34242, 34248, 34243, -1, 34212, 34249, 33594, -1, 34250, 34251, 34247, -1, 34247, 34251, 34248, -1, 33693, 34252, 34250, -1, 34250, 34252, 34251, -1, 33693, 33694, 34252, -1, 34253, 34254, 34255, -1, 34255, 34256, 34257, -1, 34254, 34256, 34255, -1, 34253, 34258, 34254, -1, 34259, 34258, 34253, -1, 34256, 34260, 34257, -1, 34257, 34260, 34261, -1, 34259, 33770, 34258, -1, 34262, 33770, 34259, -1, 34263, 33770, 34262, -1, 33766, 33770, 34263, -1, 34260, 34264, 34261, -1, 34261, 34264, 33712, -1, 34265, 33791, 34266, -1, 34266, 33791, 34267, -1, 34267, 33791, 33793, -1, 34268, 34269, 34265, -1, 34265, 34269, 33791, -1, 34268, 34270, 34269, -1, 34271, 34270, 34268, -1, 34264, 33711, 33712, -1, 34271, 34272, 34270, -1, 34273, 34272, 34271, -1, 34249, 33596, 33594, -1, 34274, 33596, 34249, -1, 34275, 33596, 34274, -1, 34276, 33596, 34275, -1, 34277, 33596, 34276, -1, 34278, 33596, 34277, -1, 34273, 34279, 34272, -1, 34280, 33596, 34278, -1, 34281, 33596, 34280, -1, 34282, 34279, 34273, -1, 34283, 33596, 34281, -1, 33658, 33596, 34283, -1, 34284, 34285, 34110, -1, 33677, 33678, 34282, -1, 34282, 33678, 34279, -1, 34110, 34285, 34109, -1, 34286, 34287, 34288, -1, 34284, 34289, 34285, -1, 33751, 34290, 33752, -1, 34291, 34292, 34286, -1, 34286, 34292, 34287, -1, 34284, 34293, 34289, -1, 34287, 34294, 34288, -1, 34288, 34294, 34295, -1, 34296, 34293, 34284, -1, 33751, 34297, 34290, -1, 34291, 34298, 34292, -1, 33908, 34298, 34291, -1, 33751, 34299, 34297, -1, 34294, 34300, 34295, -1, 34296, 34301, 34293, -1, 34295, 34300, 34302, -1, 34303, 34301, 34296, -1, 33908, 34304, 34298, -1, 33751, 34305, 34299, -1, 34306, 34307, 33751, -1, 34300, 33726, 34302, -1, 34303, 34308, 34301, -1, 33751, 34307, 34305, -1, 34302, 33726, 33727, -1, 34309, 34308, 34303, -1, 33908, 33910, 34304, -1, 34310, 34311, 34306, -1, 34306, 34311, 34307, -1, 34309, 34312, 34308, -1, 34313, 34312, 34309, -1, 34314, 34315, 34310, -1, 34310, 34315, 34311, -1, 34314, 34316, 34315, -1, 34317, 34316, 34314, -1, 34318, 34319, 34313, -1, 34313, 34319, 34312, -1, 34317, 33649, 34316, -1, 33647, 33649, 34317, -1, 33695, 33696, 34318, -1, 34318, 33696, 34319, -1, 33774, 34320, 33775, -1, 34321, 33808, 34322, -1, 34322, 33808, 34323, -1, 34323, 33808, 33795, -1, 33774, 34324, 34320, -1, 34325, 34326, 34321, -1, 34327, 34328, 34329, -1, 34321, 34326, 33808, -1, 33774, 34330, 34324, -1, 34328, 34331, 34329, -1, 34332, 34333, 34325, -1, 34329, 34331, 34334, -1, 34325, 34333, 34326, -1, 34327, 34335, 34328, -1, 33774, 34336, 34330, -1, 34337, 34338, 33774, -1, 34339, 34335, 34327, -1, 34340, 34341, 34332, -1, 34332, 34341, 34333, -1, 33774, 34338, 34336, -1, 34331, 33606, 34334, -1, 34334, 33606, 33600, -1, 33603, 33605, 34337, -1, 34342, 34343, 34340, -1, 34340, 34343, 34341, -1, 34337, 33605, 34338, -1, 34339, 33760, 34335, -1, 34344, 33760, 34339, -1, 34345, 33760, 34344, -1, 33761, 33760, 34345, -1, 33607, 33609, 34342, -1, 33614, 33604, 33603, -1, 34342, 33609, 34343, -1, 34346, 34347, 34348, -1, 34349, 34347, 34346, -1, 34350, 34351, 34352, -1, 34353, 34354, 34355, -1, 34356, 34357, 34354, -1, 34349, 34358, 34347, -1, 34359, 34357, 34356, -1, 34360, 34358, 34349, -1, 33585, 34361, 34362, -1, 34363, 34364, 34359, -1, 34362, 34365, 33585, -1, 34366, 34367, 34368, -1, 34368, 34367, 34369, -1, 34359, 34364, 34357, -1, 34369, 34367, 34370, -1, 34370, 34367, 34371, -1, 34371, 34367, 34372, -1, 33585, 34373, 34361, -1, 34360, 34374, 34358, -1, 34372, 34367, 34375, -1, 34375, 34367, 34376, -1, 34377, 34374, 34360, -1, 34376, 34367, 34378, -1, 34378, 34367, 34379, -1, 34379, 34367, 34380, -1, 34365, 34381, 33585, -1, 34377, 34382, 34374, -1, 33585, 34383, 34373, -1, 34384, 34385, 34386, -1, 34387, 34382, 34377, -1, 34381, 34388, 33585, -1, 34385, 34389, 34386, -1, 34386, 34389, 34390, -1, 33585, 34391, 34383, -1, 34392, 34393, 34387, -1, 34387, 34393, 34382, -1, 34384, 34394, 34385, -1, 34392, 34395, 34393, -1, 34396, 34394, 34384, -1, 33585, 34397, 34391, -1, 34398, 34395, 34392, -1, 33585, 34399, 34397, -1, 34390, 34400, 34401, -1, 34389, 34400, 34390, -1, 34402, 34403, 34404, -1, 34398, 34405, 34395, -1, 34404, 34403, 34406, -1, 34406, 34403, 34396, -1, 34407, 34408, 34409, -1, 34396, 34403, 34394, -1, 34401, 34410, 34411, -1, 34400, 34410, 34401, -1, 34407, 34412, 34408, -1, 34413, 34412, 34407, -1, 34408, 34414, 34409, -1, 34409, 34414, 34415, -1, 34416, 34417, 34418, -1, 34410, 34419, 34411, -1, 34413, 34420, 34412, -1, 34421, 33589, 34388, -1, 34422, 33589, 34421, -1, 34423, 33589, 34422, -1, 34424, 34420, 34413, -1, 34425, 33589, 34423, -1, 34416, 34426, 34417, -1, 34415, 34427, 34428, -1, 34388, 33589, 33585, -1, 34414, 34427, 34415, -1, 34424, 34429, 34420, -1, 34430, 34429, 34424, -1, 34416, 34431, 34426, -1, 34427, 34432, 34428, -1, 34433, 34434, 34416, -1, 34430, 34435, 34429, -1, 34416, 34434, 34431, -1, 34433, 34436, 34434, -1, 34437, 34436, 34433, -1, 34437, 34438, 34436, -1, 34439, 34438, 34437, -1, 34439, 34440, 34438, -1, 34441, 34440, 34439, -1, 34442, 34443, 34425, -1, 34425, 34443, 33589, -1, 34444, 34445, 34446, -1, 34447, 34448, 34442, -1, 34441, 34449, 34440, -1, 34450, 34449, 34441, -1, 34442, 34448, 34443, -1, 34450, 34451, 34449, -1, 34452, 34453, 34444, -1, 34443, 34454, 33589, -1, 34444, 34453, 34445, -1, 34447, 34455, 34448, -1, 34454, 34456, 33589, -1, 34447, 34457, 34455, -1, 34458, 34459, 34452, -1, 34456, 34460, 33589, -1, 34452, 34459, 34453, -1, 34447, 34461, 34457, -1, 34458, 34462, 34459, -1, 34463, 34462, 34458, -1, 34447, 34464, 34461, -1, 34447, 34465, 34464, -1, 34466, 34467, 34468, -1, 34463, 34469, 34462, -1, 34470, 34467, 34466, -1, 34471, 34472, 34473, -1, 34474, 34469, 34463, -1, 33589, 34472, 34471, -1, 34460, 34472, 33589, -1, 34475, 34476, 34477, -1, 34478, 34476, 34475, -1, 34479, 34480, 34481, -1, 34473, 34476, 34478, -1, 34474, 34482, 34469, -1, 34472, 34476, 34473, -1, 34477, 34483, 34484, -1, 34470, 34485, 34467, -1, 34476, 34483, 34477, -1, 34486, 34485, 34470, -1, 34479, 34487, 34480, -1, 34488, 34482, 34474, -1, 34483, 34489, 34484, -1, 34489, 34490, 34484, -1, 34490, 34491, 34484, -1, 34486, 34492, 34485, -1, 34493, 34492, 34486, -1, 34479, 34494, 34487, -1, 34488, 34495, 34482, -1, 34496, 34495, 34488, -1, 34479, 34497, 34494, -1, 34493, 34498, 34492, -1, 34499, 34498, 34493, -1, 34500, 34501, 34479, -1, 34499, 34502, 34498, -1, 34479, 34501, 34497, -1, 34503, 34502, 34499, -1, 34504, 34505, 34506, -1, 34507, 34508, 34500, -1, 34506, 34509, 34504, -1, 34500, 34508, 34501, -1, 34503, 34510, 34502, -1, 34511, 34510, 34503, -1, 34505, 34512, 34506, -1, 34506, 34513, 34509, -1, 34511, 34514, 34510, -1, 34507, 34515, 34508, -1, 34516, 34514, 34511, -1, 34517, 34515, 34507, -1, 34512, 34518, 34506, -1, 34517, 34519, 34515, -1, 34520, 34521, 34522, -1, 34506, 34523, 34513, -1, 34524, 34519, 34517, -1, 34520, 34525, 34521, -1, 34526, 34525, 34520, -1, 34518, 34527, 34506, -1, 34521, 34528, 34522, -1, 34506, 34529, 34530, -1, 34522, 34528, 34531, -1, 34527, 34529, 34506, -1, 34532, 34533, 34534, -1, 34526, 34535, 34525, -1, 34536, 34535, 34526, -1, 34533, 34537, 34534, -1, 34506, 34538, 34523, -1, 34534, 34537, 34539, -1, 34528, 34540, 34531, -1, 34530, 34541, 34491, -1, 34531, 34540, 34542, -1, 34491, 34541, 34484, -1, 34532, 34543, 34533, -1, 34529, 34541, 34530, -1, 34544, 34543, 34532, -1, 34536, 34545, 34535, -1, 34506, 34546, 34538, -1, 34547, 34545, 34536, -1, 34537, 34548, 34539, -1, 34539, 34548, 34549, -1, 34540, 34550, 34542, -1, 34541, 34551, 34484, -1, 34542, 34550, 34552, -1, 34544, 34553, 34543, -1, 34554, 34553, 34555, -1, 34555, 34553, 34556, -1, 34556, 34553, 34544, -1, 34451, 34557, 34558, -1, 34450, 34557, 34451, -1, 34559, 34557, 34560, -1, 34547, 34561, 34545, -1, 34562, 34557, 34563, -1, 34548, 34564, 34549, -1, 34563, 34557, 34565, -1, 34549, 34564, 34566, -1, 34565, 34557, 34567, -1, 34567, 34557, 34568, -1, 34569, 34557, 34562, -1, 34519, 34557, 34569, -1, 34524, 34557, 34519, -1, 34351, 34557, 34450, -1, 34564, 34570, 34566, -1, 34551, 34571, 34484, -1, 34560, 34557, 34351, -1, 34572, 34571, 34551, -1, 34558, 34557, 34524, -1, 34573, 34571, 34572, -1, 34557, 34574, 34568, -1, 34575, 34571, 34573, -1, 34576, 34574, 34366, -1, 34577, 34571, 34575, -1, 34568, 34574, 34576, -1, 34366, 34574, 34367, -1, 34578, 34579, 34566, -1, 34577, 34580, 34571, -1, 34566, 34579, 34419, -1, 34419, 34579, 34411, -1, 34411, 34579, 34581, -1, 34581, 34579, 34582, -1, 34582, 34579, 34583, -1, 34583, 34579, 34584, -1, 34584, 34579, 34585, -1, 34585, 34579, 34586, -1, 34586, 34579, 34587, -1, 34588, 34589, 34590, -1, 34587, 34579, 34591, -1, 34591, 34579, 34592, -1, 34592, 34579, 34593, -1, 34593, 34579, 34550, -1, 34550, 34579, 34552, -1, 34552, 34579, 34432, -1, 34432, 34579, 34428, -1, 34428, 34579, 34594, -1, 34594, 34579, 34595, -1, 34596, 34597, 34588, -1, 34595, 34579, 34598, -1, 34598, 34579, 34599, -1, 34599, 34579, 34600, -1, 34588, 34597, 34589, -1, 34580, 34601, 34602, -1, 34603, 34604, 34605, -1, 34600, 34579, 34606, -1, 34607, 34604, 34603, -1, 34606, 34579, 34608, -1, 34608, 34579, 34609, -1, 34602, 34601, 34610, -1, 34609, 34579, 34611, -1, 34612, 34557, 34613, -1, 34613, 34557, 34614, -1, 34614, 34557, 34615, -1, 34615, 34557, 34616, -1, 34617, 34618, 34596, -1, 34616, 34557, 34398, -1, 34610, 34619, 34602, -1, 34398, 34557, 34405, -1, 34596, 34618, 34597, -1, 34405, 34557, 34516, -1, 34516, 34557, 34514, -1, 34514, 34557, 34620, -1, 34620, 34557, 34621, -1, 34621, 34557, 34622, -1, 34577, 34623, 34580, -1, 34622, 34557, 34624, -1, 34580, 34623, 34601, -1, 34624, 34557, 34625, -1, 34625, 34557, 34626, -1, 34602, 34627, 34579, -1, 34626, 34557, 34628, -1, 34629, 34630, 34617, -1, 34628, 34557, 34631, -1, 34631, 34557, 34632, -1, 34619, 34627, 34602, -1, 34633, 34634, 34607, -1, 34632, 34557, 34635, -1, 34617, 34630, 34618, -1, 34635, 34557, 34636, -1, 34636, 34557, 34637, -1, 34637, 34557, 34363, -1, 34363, 34557, 34364, -1, 34364, 34557, 34496, -1, 34607, 34634, 34604, -1, 34496, 34557, 34495, -1, 34577, 34638, 34623, -1, 34495, 34557, 34639, -1, 34639, 34557, 34640, -1, 34641, 34642, 34629, -1, 34640, 34557, 34643, -1, 34643, 34557, 34644, -1, 34644, 34557, 34645, -1, 34645, 34557, 34646, -1, 34627, 34647, 34579, -1, 34646, 34557, 34648, -1, 34648, 34557, 34559, -1, 34629, 34642, 34630, -1, 34649, 34650, 34651, -1, 34652, 34653, 34633, -1, 34654, 34655, 34656, -1, 34577, 34656, 34655, -1, 34657, 34546, 34658, -1, 34658, 34546, 34506, -1, 34659, 34660, 34661, -1, 34577, 34662, 34638, -1, 34663, 34664, 34665, -1, 34633, 34653, 34634, -1, 34666, 34665, 34664, -1, 34667, 34651, 34650, -1, 34668, 34465, 34447, -1, 34668, 34447, 34669, -1, 34604, 34670, 34605, -1, 34671, 34468, 34672, -1, 34641, 34673, 34642, -1, 34347, 34661, 34660, -1, 34674, 34605, 34670, -1, 34467, 34672, 34468, -1, 34675, 34676, 34677, -1, 34678, 34679, 34652, -1, 34680, 34681, 34682, -1, 34683, 34416, 34418, -1, 34577, 34655, 34662, -1, 34684, 34673, 34641, -1, 34682, 34685, 34680, -1, 34686, 34403, 34402, -1, 34647, 34687, 34579, -1, 34652, 34679, 34653, -1, 34554, 34688, 34689, -1, 34689, 34553, 34554, -1, 34677, 34690, 34675, -1, 34691, 34479, 34481, -1, 34687, 34692, 34579, -1, 34418, 34693, 34683, -1, 34694, 34444, 34446, -1, 34590, 34695, 34696, -1, 34402, 34697, 34686, -1, 34446, 34698, 34694, -1, 34696, 34588, 34590, -1, 34684, 34699, 34673, -1, 34481, 34700, 34691, -1, 34678, 34701, 34679, -1, 34639, 34699, 34684, -1, 34702, 34701, 34678, -1, 34639, 34640, 34699, -1, 34620, 34703, 34702, -1, 34704, 34705, 34706, -1, 34702, 34703, 34701, -1, 34707, 34708, 34704, -1, 34704, 34708, 34705, -1, 34706, 34709, 34692, -1, 34705, 34709, 34706, -1, 34707, 34710, 34708, -1, 34649, 34710, 34707, -1, 34620, 34621, 34703, -1, 34692, 34711, 34579, -1, 34709, 34711, 34692, -1, 34649, 34712, 34710, -1, 34711, 34713, 34579, -1, 34714, 34715, 34716, -1, 34649, 34717, 34712, -1, 34649, 34651, 34717, -1, 34713, 34718, 34579, -1, 34719, 34720, 34721, -1, 34720, 34722, 34721, -1, 34721, 34722, 34723, -1, 34719, 34724, 34720, -1, 34725, 34726, 34727, -1, 34728, 34724, 34719, -1, 34722, 34729, 34723, -1, 34723, 34729, 34730, -1, 34731, 34732, 34725, -1, 34725, 34732, 34726, -1, 34727, 34733, 34734, -1, 34728, 34735, 34724, -1, 34736, 34735, 34728, -1, 34726, 34733, 34727, -1, 34677, 34676, 34737, -1, 34737, 34676, 34738, -1, 34729, 34739, 34730, -1, 34738, 34676, 34731, -1, 34730, 34739, 34593, -1, 34731, 34676, 34732, -1, 34734, 34740, 34741, -1, 34733, 34740, 34734, -1, 34736, 34742, 34735, -1, 33585, 34743, 34399, -1, 34744, 34742, 34736, -1, 34739, 34592, 34593, -1, 34745, 34743, 34746, -1, 34399, 34743, 34745, -1, 34743, 34612, 34746, -1, 34747, 34612, 34748, -1, 34749, 34612, 34747, -1, 34750, 34612, 34749, -1, 34751, 34752, 34715, -1, 34746, 34612, 34750, -1, 34753, 34752, 34751, -1, 34715, 34752, 34716, -1, 34753, 34754, 34752, -1, 34755, 34754, 34753, -1, 34756, 34757, 34758, -1, 34697, 34759, 34686, -1, 34755, 34760, 34754, -1, 34761, 34762, 34756, -1, 34763, 34760, 34755, -1, 34756, 34762, 34757, -1, 34697, 34764, 34759, -1, 34757, 34765, 34758, -1, 34763, 34766, 34760, -1, 34758, 34765, 34767, -1, 34768, 34766, 34763, -1, 34769, 34578, 34570, -1, 34770, 34578, 34740, -1, 34666, 34771, 34761, -1, 34741, 34578, 34769, -1, 34761, 34771, 34762, -1, 34570, 34578, 34566, -1, 34767, 34772, 34773, -1, 34765, 34772, 34767, -1, 34740, 34578, 34741, -1, 34768, 34774, 34766, -1, 34775, 34774, 34768, -1, 34666, 34776, 34771, -1, 34777, 34778, 34697, -1, 34718, 34611, 34579, -1, 34622, 34779, 34775, -1, 34697, 34778, 34764, -1, 34772, 34611, 34773, -1, 34775, 34779, 34774, -1, 34773, 34611, 34718, -1, 34777, 34780, 34778, -1, 34781, 34780, 34777, -1, 34666, 34782, 34776, -1, 34622, 34624, 34779, -1, 34781, 34783, 34780, -1, 34612, 34784, 34748, -1, 34785, 34783, 34781, -1, 34612, 34786, 34784, -1, 34785, 34787, 34783, -1, 34666, 34664, 34782, -1, 34788, 34787, 34785, -1, 34788, 34789, 34787, -1, 34790, 34789, 34788, -1, 34790, 34644, 34789, -1, 34643, 34644, 34790, -1, 34430, 34791, 34435, -1, 34770, 34792, 34578, -1, 34793, 34668, 34669, -1, 34794, 34668, 34793, -1, 34578, 34795, 34796, -1, 34797, 34668, 34794, -1, 34798, 34668, 34797, -1, 34799, 34668, 34798, -1, 34792, 34795, 34578, -1, 34800, 34801, 34802, -1, 34795, 34803, 34796, -1, 34800, 34804, 34801, -1, 34805, 34806, 34799, -1, 34807, 34804, 34800, -1, 34801, 34808, 34802, -1, 34799, 34806, 34668, -1, 34802, 34808, 34809, -1, 34803, 34810, 34796, -1, 34796, 34811, 34812, -1, 34807, 34813, 34804, -1, 34805, 34814, 34806, -1, 34810, 34811, 34796, -1, 34815, 34813, 34807, -1, 34816, 34814, 34805, -1, 34808, 34817, 34809, -1, 34809, 34817, 34818, -1, 34815, 34819, 34813, -1, 34816, 34820, 34814, -1, 34821, 34819, 34815, -1, 34811, 34822, 34812, -1, 34786, 34820, 34816, -1, 34817, 34587, 34818, -1, 34818, 34587, 34591, -1, 34786, 34823, 34820, -1, 34612, 34823, 34786, -1, 34824, 34825, 34791, -1, 34612, 34826, 34823, -1, 34791, 34825, 34435, -1, 34827, 34828, 34824, -1, 34824, 34828, 34825, -1, 34827, 34829, 34828, -1, 34612, 34830, 34826, -1, 34831, 34829, 34827, -1, 34831, 34832, 34829, -1, 34833, 34832, 34831, -1, 34833, 34834, 34832, -1, 34835, 34834, 34833, -1, 34835, 34836, 34834, -1, 34837, 34836, 34835, -1, 34838, 34839, 34840, -1, 34837, 34626, 34836, -1, 34625, 34626, 34837, -1, 34838, 34841, 34839, -1, 34842, 34843, 34844, -1, 34845, 34841, 34838, -1, 34844, 34846, 34842, -1, 34840, 34847, 34848, -1, 34839, 34847, 34840, -1, 34812, 34685, 34844, -1, 34680, 34685, 34849, -1, 34849, 34685, 34850, -1, 34850, 34685, 34822, -1, 34659, 34851, 34845, -1, 34822, 34685, 34812, -1, 34844, 34685, 34846, -1, 34845, 34851, 34841, -1, 34848, 34852, 34853, -1, 34847, 34852, 34848, -1, 34659, 34854, 34851, -1, 34688, 34855, 34689, -1, 34547, 34856, 34561, -1, 34853, 34608, 34609, -1, 34852, 34608, 34853, -1, 34688, 34857, 34855, -1, 34659, 34858, 34854, -1, 34659, 34661, 34858, -1, 34843, 34859, 34844, -1, 34860, 34657, 34658, -1, 34861, 34657, 34860, -1, 34862, 34657, 34861, -1, 34863, 34657, 34862, -1, 34864, 34865, 34863, -1, 34863, 34865, 34657, -1, 34866, 34867, 34868, -1, 34869, 34870, 34688, -1, 34688, 34870, 34857, -1, 34871, 34872, 34864, -1, 34873, 34874, 34866, -1, 34866, 34874, 34867, -1, 34864, 34872, 34865, -1, 34868, 34875, 34876, -1, 34867, 34875, 34868, -1, 34877, 34878, 34871, -1, 34869, 34879, 34870, -1, 34856, 34880, 34561, -1, 34871, 34878, 34872, -1, 34881, 34879, 34869, -1, 34882, 34880, 34856, -1, 34877, 34883, 34878, -1, 34884, 34885, 34873, -1, 34886, 34883, 34877, -1, 34873, 34885, 34874, -1, 34876, 34887, 34586, -1, 34875, 34887, 34876, -1, 34888, 34889, 34890, -1, 34890, 34889, 34884, -1, 34881, 34891, 34879, -1, 34612, 34892, 34830, -1, 34884, 34889, 34885, -1, 34893, 34894, 34882, -1, 34830, 34892, 34886, -1, 34886, 34892, 34883, -1, 34895, 34891, 34881, -1, 34882, 34894, 34880, -1, 34887, 34585, 34586, -1, 34859, 34896, 34844, -1, 34897, 34898, 34893, -1, 34893, 34898, 34894, -1, 34899, 34896, 34859, -1, 34900, 34901, 34897, -1, 34897, 34901, 34898, -1, 34902, 34903, 34900, -1, 34900, 34903, 34901, -1, 34902, 34904, 34903, -1, 34905, 34904, 34902, -1, 34612, 34906, 34892, -1, 34895, 34907, 34891, -1, 34628, 34908, 34905, -1, 34909, 34907, 34895, -1, 34905, 34908, 34904, -1, 34628, 34631, 34908, -1, 34910, 34911, 34912, -1, 34912, 34913, 34914, -1, 34909, 34915, 34907, -1, 34911, 34913, 34912, -1, 34916, 34917, 34910, -1, 34918, 34915, 34909, -1, 34910, 34917, 34911, -1, 34914, 34919, 34920, -1, 34913, 34919, 34914, -1, 34671, 34921, 34916, -1, 34916, 34921, 34917, -1, 34918, 34646, 34915, -1, 34920, 34922, 34606, -1, 34919, 34922, 34920, -1, 34645, 34646, 34918, -1, 34671, 34923, 34921, -1, 34922, 34600, 34606, -1, 34671, 34672, 34923, -1, 34924, 34654, 34656, -1, 34925, 34654, 34924, -1, 34926, 34654, 34925, -1, 34927, 34654, 34926, -1, 34927, 34928, 34654, -1, 34929, 34928, 34927, -1, 34899, 34930, 34896, -1, 34929, 34931, 34928, -1, 34930, 34932, 34896, -1, 34933, 34931, 34929, -1, 34744, 34934, 34742, -1, 34933, 34935, 34931, -1, 34936, 34934, 34744, -1, 34937, 34935, 34933, -1, 34899, 34938, 34930, -1, 34939, 34938, 34899, -1, 34936, 34940, 34934, -1, 34937, 34941, 34935, -1, 34906, 34941, 34937, -1, 34939, 34693, 34938, -1, 34942, 34940, 34936, -1, 34943, 34693, 34939, -1, 34683, 34693, 34944, -1, 34942, 34945, 34940, -1, 34944, 34693, 34946, -1, 34946, 34693, 34947, -1, 34906, 34948, 34941, -1, 34947, 34693, 34949, -1, 34612, 34948, 34906, -1, 34949, 34693, 34950, -1, 34950, 34693, 34951, -1, 34952, 34945, 34942, -1, 34951, 34693, 34953, -1, 34953, 34693, 34954, -1, 34954, 34693, 34943, -1, 34952, 34955, 34945, -1, 34956, 34955, 34952, -1, 34932, 34957, 34896, -1, 34956, 34958, 34955, -1, 34957, 34959, 34896, -1, 34896, 34959, 34960, -1, 34961, 34958, 34956, -1, 34962, 34963, 34964, -1, 34965, 34966, 34962, -1, 34960, 34967, 34968, -1, 34968, 34967, 34969, -1, 34962, 34966, 34963, -1, 34969, 34967, 34970, -1, 34964, 34971, 34972, -1, 34963, 34971, 34964, -1, 34959, 34967, 34960, -1, 34965, 34973, 34966, -1, 34974, 34973, 34965, -1, 34612, 34613, 34948, -1, 34961, 34975, 34958, -1, 34976, 34975, 34961, -1, 34971, 34977, 34972, -1, 34972, 34977, 34584, -1, 34974, 34698, 34973, -1, 34694, 34698, 34978, -1, 34970, 34979, 34980, -1, 34978, 34698, 34974, -1, 34980, 34979, 34380, -1, 34967, 34979, 34970, -1, 34977, 34583, 34584, -1, 34976, 34981, 34975, -1, 34982, 34983, 34984, -1, 34979, 34985, 34380, -1, 34986, 34981, 34976, -1, 34982, 34987, 34983, -1, 34988, 34987, 34982, -1, 34986, 34635, 34981, -1, 34985, 34989, 34380, -1, 34989, 34990, 34380, -1, 34984, 34991, 34992, -1, 34632, 34635, 34986, -1, 34983, 34991, 34984, -1, 34988, 34993, 34987, -1, 34674, 34993, 34988, -1, 34992, 34994, 34995, -1, 34990, 34996, 34380, -1, 34991, 34994, 34992, -1, 34674, 34997, 34993, -1, 34995, 34598, 34599, -1, 34994, 34598, 34995, -1, 34674, 34670, 34997, -1, 34998, 34667, 34650, -1, 34999, 34667, 34998, -1, 35000, 34667, 34999, -1, 35001, 35002, 35000, -1, 35000, 35002, 34667, -1, 35003, 35004, 35001, -1, 35001, 35004, 35002, -1, 35005, 35006, 35003, -1, 35003, 35006, 35004, -1, 35005, 35007, 35006, -1, 35008, 35007, 35005, -1, 34613, 34614, 35008, -1, 34690, 35009, 34675, -1, 35008, 34614, 35007, -1, 34690, 35010, 35009, -1, 34821, 35011, 34819, -1, 35012, 35013, 34690, -1, 35014, 35011, 34821, -1, 34690, 35013, 35010, -1, 35012, 35015, 35013, -1, 35016, 35015, 35012, -1, 35017, 35018, 35014, -1, 35014, 35018, 35011, -1, 35019, 35020, 35017, -1, 35016, 35021, 35015, -1, 35017, 35020, 35018, -1, 35022, 35021, 35016, -1, 35019, 35023, 35020, -1, 35024, 35023, 35019, -1, 35022, 35025, 35021, -1, 35026, 35025, 35022, -1, 35027, 35028, 35024, -1, 34648, 35029, 35026, -1, 35026, 35029, 35025, -1, 35024, 35028, 35023, -1, 35030, 35031, 35027, -1, 35027, 35031, 35028, -1, 34648, 34559, 35029, -1, 34636, 35032, 35030, -1, 35030, 35032, 35031, -1, 35033, 35034, 34996, -1, 34996, 35035, 34380, -1, 35034, 35035, 34996, -1, 34636, 34637, 35032, -1, 35033, 34700, 35034, -1, 35036, 34663, 34665, -1, 34691, 34700, 35037, -1, 35038, 34663, 35036, -1, 35037, 34700, 35039, -1, 35040, 34663, 35038, -1, 35039, 34700, 35041, -1, 35041, 34700, 35042, -1, 35042, 34700, 35033, -1, 35043, 35044, 35045, -1, 35035, 35046, 34380, -1, 35043, 35047, 35044, -1, 35046, 35048, 34380, -1, 35049, 35050, 35040, -1, 35051, 35047, 35043, -1, 35044, 35052, 35045, -1, 35040, 35050, 34663, -1, 35048, 35053, 34380, -1, 35054, 35055, 35049, -1, 35045, 35052, 35056, -1, 35049, 35055, 35050, -1, 35051, 35057, 35047, -1, 35058, 35057, 35051, -1, 35052, 35059, 35056, -1, 35060, 35061, 35062, -1, 35060, 35063, 35061, -1, 35056, 35059, 35064, -1, 35065, 35063, 35060, -1, 35061, 35066, 35062, -1, 35058, 34695, 35057, -1, 34696, 34695, 35067, -1, 35062, 35066, 35068, -1, 35067, 34695, 35058, -1, 35059, 34581, 35064, -1, 35065, 35069, 35063, -1, 35064, 34581, 34582, -1, 34714, 35069, 35065, -1, 35066, 35070, 35068, -1, 35068, 35070, 35071, -1, 35072, 35073, 35054, -1, 35054, 35073, 35055, -1, 34714, 35074, 35069, -1, 35053, 34379, 34380, -1, 35070, 34594, 35071, -1, 34681, 35075, 34682, -1, 35071, 34594, 34595, -1, 35076, 35077, 35072, -1, 35072, 35077, 35073, -1, 34714, 34716, 35074, -1, 34681, 35078, 35075, -1, 35076, 35079, 35077, -1, 34615, 35079, 35076, -1, 34681, 35080, 35078, -1, 34615, 34616, 35079, -1, 35081, 35082, 34888, -1, 35083, 35084, 34681, -1, 34888, 35082, 34889, -1, 34681, 35084, 35080, -1, 35081, 35085, 35082, -1, 35086, 35087, 35083, -1, 35083, 35087, 35084, -1, 35088, 35089, 35081, -1, 35081, 35089, 35085, -1, 35090, 35091, 35086, -1, 35086, 35091, 35087, -1, 35092, 35093, 35088, -1, 35088, 35093, 35089, -1, 34350, 34352, 35090, -1, 35090, 34352, 35091, -1, 34353, 34355, 35092, -1, 35092, 34355, 35093, -1, 34356, 34354, 34353, -1, 34560, 34351, 34350, -1, 34348, 34347, 34660, -1, 35094, 34943, 35095, -1, 34943, 34939, 35095, -1, 35095, 34899, 35096, -1, 34939, 34899, 35095, -1, 35096, 34859, 35097, -1, 34899, 34859, 35096, -1, 35098, 34527, 35099, -1, 34527, 34518, 35099, -1, 35099, 34512, 35100, -1, 34518, 34512, 35099, -1, 35100, 34505, 35101, -1, 34512, 34505, 35100, -1, 35101, 34504, 35102, -1, 34505, 34504, 35101, -1, 35102, 34509, 35103, -1, 34504, 34509, 35102, -1, 35103, 34513, 35104, -1, 34509, 34513, 35103, -1, 35104, 34523, 35105, -1, 34513, 34523, 35104, -1, 35105, 34538, 35106, -1, 34523, 34538, 35105, -1, 35106, 34546, 35107, -1, 34538, 34546, 35106, -1, 35108, 35109, 35110, -1, 35111, 35112, 35108, -1, 35113, 35110, 35114, -1, 35113, 35114, 35115, -1, 35113, 35115, 35116, -1, 35113, 35108, 35110, -1, 35113, 35111, 35108, -1, 35117, 35111, 35113, -1, 35118, 35119, 35120, -1, 35121, 35120, 35117, -1, 35121, 35118, 35120, -1, 35122, 35117, 35113, -1, 35122, 35121, 35117, -1, 35123, 35122, 35113, -1, 35124, 35123, 35125, -1, 35126, 35123, 35124, -1, 35107, 35126, 35127, -1, 35107, 35123, 35126, -1, 35098, 35127, 35128, -1, 35098, 35128, 35129, -1, 35098, 35107, 35127, -1, 35105, 35106, 35107, -1, 35104, 35107, 35098, -1, 35104, 35105, 35107, -1, 35100, 35098, 35099, -1, 35101, 35098, 35100, -1, 35102, 35103, 35104, -1, 35102, 35104, 35098, -1, 35102, 35098, 35101, -1, 35107, 35122, 35123, -1, 35130, 34905, 35131, -1, 34628, 34905, 35130, -1, 35131, 34902, 35132, -1, 34905, 34902, 35131, -1, 35132, 34900, 35133, -1, 34902, 34900, 35132, -1, 35133, 34897, 35134, -1, 34900, 34897, 35133, -1, 35134, 34893, 35135, -1, 34897, 34893, 35134, -1, 35135, 34882, 35136, -1, 34893, 34882, 35135, -1, 35136, 34856, 35137, -1, 34882, 34856, 35136, -1, 35131, 35132, 35133, -1, 35131, 35133, 35134, -1, 35136, 35134, 35135, -1, 35136, 35131, 35134, -1, 35137, 35130, 35131, -1, 35137, 35131, 35136, -1, 35138, 35130, 35137, -1, 35139, 35140, 35141, -1, 35142, 35143, 35139, -1, 35142, 35141, 35144, -1, 35142, 35144, 35138, -1, 35142, 35138, 35137, -1, 35142, 35139, 35141, -1, 35145, 35142, 35137, -1, 35146, 35147, 35148, -1, 35149, 35145, 35150, -1, 35149, 35150, 35147, -1, 35149, 35146, 35151, -1, 35149, 35151, 35152, -1, 35149, 35147, 35146, -1, 35153, 35142, 35145, -1, 35153, 35145, 35149, -1, 35154, 35153, 35149, -1, 35155, 35153, 35154, -1, 35156, 35155, 35154, -1, 35157, 35154, 35158, -1, 35157, 35158, 35159, -1, 35157, 35160, 35156, -1, 35157, 35156, 35154, -1, 34856, 34547, 35137, -1, 35137, 34547, 35145, -1, 34626, 35130, 35138, -1, 34626, 34628, 35130, -1, 35145, 34536, 35150, -1, 34547, 34536, 35145, -1, 35150, 34526, 35147, -1, 34536, 34526, 35150, -1, 35147, 34520, 35148, -1, 34526, 34520, 35147, -1, 35148, 34522, 35146, -1, 34520, 34522, 35148, -1, 35146, 34531, 35151, -1, 34522, 34531, 35146, -1, 35151, 34542, 35152, -1, 34531, 34542, 35151, -1, 35152, 34552, 35149, -1, 34542, 34552, 35152, -1, 34825, 34828, 35142, -1, 35142, 34828, 35143, -1, 35143, 34829, 35139, -1, 34828, 34829, 35143, -1, 35139, 34832, 35140, -1, 34829, 34832, 35139, -1, 35140, 34834, 35141, -1, 34832, 34834, 35140, -1, 35141, 34836, 35144, -1, 35144, 34836, 35138, -1, 34834, 34836, 35141, -1, 34836, 34626, 35138, -1, 34552, 35154, 35149, -1, 34552, 34432, 35154, -1, 35153, 34825, 35142, -1, 34435, 34825, 35153, -1, 35154, 34427, 35158, -1, 34432, 34427, 35154, -1, 35158, 34414, 35159, -1, 34427, 34414, 35158, -1, 35159, 34408, 35157, -1, 34414, 34408, 35159, -1, 35157, 34412, 35160, -1, 34408, 34412, 35157, -1, 35160, 34420, 35156, -1, 34412, 34420, 35160, -1, 35156, 34429, 35155, -1, 34420, 34429, 35156, -1, 35155, 34435, 35153, -1, 34429, 34435, 35155, -1, 35161, 34594, 35162, -1, 35162, 35070, 35163, -1, 34594, 35070, 35162, -1, 35163, 35066, 35164, -1, 35070, 35066, 35163, -1, 35164, 35061, 35165, -1, 35066, 35061, 35164, -1, 35165, 35063, 35166, -1, 35061, 35063, 35165, -1, 35166, 35069, 35167, -1, 35063, 35069, 35166, -1, 35069, 35074, 35167, -1, 35167, 34716, 35168, -1, 35074, 34716, 35167, -1, 35169, 35170, 35171, -1, 35172, 35173, 35170, -1, 35174, 35170, 35169, -1, 35174, 35172, 35170, -1, 35175, 35176, 35172, -1, 35175, 35172, 35174, -1, 35177, 35176, 35175, -1, 35178, 35179, 35180, -1, 35181, 35180, 35182, -1, 35181, 35182, 35177, -1, 35181, 35178, 35180, -1, 35183, 35177, 35175, -1, 35183, 35181, 35177, -1, 35184, 35183, 35175, -1, 35185, 35186, 35187, -1, 35188, 35184, 35189, -1, 35188, 35189, 35186, -1, 35188, 35185, 35190, -1, 35188, 35186, 35185, -1, 35168, 35183, 35184, -1, 35168, 35184, 35188, -1, 35161, 35168, 35188, -1, 35167, 35168, 35161, -1, 35166, 35167, 35161, -1, 35163, 35161, 35162, -1, 35165, 35166, 35161, -1, 35164, 35161, 35163, -1, 35164, 35165, 35161, -1, 34716, 35183, 35168, -1, 34716, 34752, 35183, -1, 35188, 34594, 35161, -1, 34428, 34594, 35188, -1, 35183, 34754, 35181, -1, 34752, 34754, 35183, -1, 35181, 34760, 35178, -1, 34754, 34760, 35181, -1, 35178, 34766, 35179, -1, 34760, 34766, 35178, -1, 35179, 34774, 35180, -1, 34766, 34774, 35179, -1, 35180, 34779, 35182, -1, 34774, 34779, 35180, -1, 35182, 34624, 35177, -1, 34779, 34624, 35182, -1, 35184, 34430, 35189, -1, 35189, 34424, 35186, -1, 34430, 34424, 35189, -1, 35186, 34413, 35187, -1, 34424, 34413, 35186, -1, 35187, 34407, 35185, -1, 34413, 34407, 35187, -1, 35185, 34409, 35190, -1, 34407, 34409, 35185, -1, 34409, 34415, 35190, -1, 35190, 34428, 35188, -1, 34415, 34428, 35190, -1, 34624, 34625, 35177, -1, 35177, 34625, 35176, -1, 34791, 35184, 35175, -1, 34791, 34430, 35184, -1, 35176, 34837, 35172, -1, 34625, 34837, 35176, -1, 35172, 34835, 35173, -1, 34837, 34835, 35172, -1, 35173, 34833, 35170, -1, 34835, 34833, 35173, -1, 35170, 34831, 35171, -1, 35171, 34831, 35169, -1, 34833, 34831, 35170, -1, 35169, 34827, 35174, -1, 34831, 34827, 35169, -1, 34827, 34824, 35174, -1, 35174, 34791, 35175, -1, 34824, 34791, 35174, -1, 35191, 34775, 35192, -1, 34622, 34775, 35191, -1, 35192, 34768, 35193, -1, 34775, 34768, 35192, -1, 35193, 34763, 35194, -1, 34768, 34763, 35193, -1, 35194, 34755, 35195, -1, 35195, 34755, 35196, -1, 34763, 34755, 35194, -1, 35196, 34753, 35197, -1, 34755, 34753, 35196, -1, 34753, 34751, 35197, -1, 35197, 34715, 35198, -1, 34751, 34715, 35197, -1, 35199, 35200, 35201, -1, 35200, 35202, 35203, -1, 35204, 35202, 35199, -1, 35205, 35202, 35204, -1, 35199, 35202, 35200, -1, 35206, 35207, 35208, -1, 35209, 35210, 35207, -1, 35211, 35210, 35209, -1, 35207, 35212, 35208, -1, 35210, 35212, 35207, -1, 35208, 35213, 35202, -1, 35202, 35213, 35203, -1, 35212, 35213, 35208, -1, 35198, 35196, 35197, -1, 35198, 35195, 35196, -1, 35195, 35193, 35194, -1, 35198, 35193, 35195, -1, 35198, 35192, 35193, -1, 35198, 35191, 35192, -1, 35198, 35214, 35191, -1, 35203, 35215, 35198, -1, 35213, 35215, 35203, -1, 35198, 35215, 35214, -1, 35214, 35216, 35217, -1, 35215, 35216, 35214, -1, 35216, 35218, 35217, -1, 35217, 35219, 35220, -1, 35218, 35219, 35217, -1, 34715, 34714, 35203, -1, 34715, 35203, 35198, -1, 34621, 34622, 35191, -1, 34621, 35191, 35214, -1, 35203, 34714, 35200, -1, 35200, 35065, 35201, -1, 34714, 35065, 35200, -1, 35201, 35060, 35199, -1, 35065, 35060, 35201, -1, 35199, 35062, 35204, -1, 35060, 35062, 35199, -1, 35204, 35068, 35205, -1, 35062, 35068, 35204, -1, 35068, 35071, 35205, -1, 35205, 34595, 35202, -1, 35071, 34595, 35205, -1, 34604, 34634, 35215, -1, 35215, 34634, 35216, -1, 35216, 34653, 35218, -1, 34634, 34653, 35216, -1, 35218, 34679, 35219, -1, 34653, 34679, 35218, -1, 35219, 34701, 35220, -1, 34679, 34701, 35219, -1, 35220, 34703, 35217, -1, 34701, 34703, 35220, -1, 35217, 34621, 35214, -1, 34703, 34621, 35217, -1, 34595, 34598, 35208, -1, 34595, 35208, 35202, -1, 35213, 34604, 35215, -1, 34670, 34604, 35213, -1, 35208, 34598, 35206, -1, 35206, 34994, 35207, -1, 34598, 34994, 35206, -1, 35207, 34991, 35209, -1, 34994, 34991, 35207, -1, 35209, 34983, 35211, -1, 34991, 34983, 35209, -1, 35211, 34987, 35210, -1, 34983, 34987, 35211, -1, 35210, 34993, 35212, -1, 34987, 34993, 35210, -1, 34993, 34997, 35212, -1, 35212, 34670, 35213, -1, 34997, 34670, 35212, -1, 35221, 34600, 35222, -1, 35222, 34922, 35223, -1, 34600, 34922, 35222, -1, 35223, 34919, 35224, -1, 34922, 34919, 35223, -1, 35224, 34913, 35225, -1, 34919, 34913, 35224, -1, 34913, 34911, 35225, -1, 35225, 34917, 35226, -1, 34911, 34917, 35225, -1, 35226, 34921, 35227, -1, 34917, 34921, 35226, -1, 35227, 34923, 35228, -1, 34921, 34923, 35227, -1, 35228, 34672, 35229, -1, 34923, 34672, 35228, -1, 35230, 35231, 35232, -1, 35231, 35233, 35234, -1, 35235, 35233, 35230, -1, 35236, 35233, 35235, -1, 35230, 35233, 35231, -1, 35222, 35223, 35221, -1, 35224, 35225, 35223, -1, 35225, 35226, 35223, -1, 35226, 35227, 35223, -1, 35221, 35229, 35233, -1, 35228, 35229, 35227, -1, 35233, 35229, 35234, -1, 35223, 35229, 35221, -1, 35227, 35229, 35223, -1, 35237, 35238, 35239, -1, 35240, 35238, 35237, -1, 35238, 35241, 35242, -1, 35240, 35241, 35238, -1, 35243, 35244, 35240, -1, 35240, 35244, 35241, -1, 35243, 35245, 35244, -1, 35234, 35246, 35243, -1, 35229, 35246, 35234, -1, 35243, 35246, 35245, -1, 35246, 35247, 35245, -1, 35246, 35248, 35247, -1, 35249, 35250, 35246, -1, 35250, 35251, 35246, -1, 35246, 35251, 35248, -1, 34672, 34467, 35246, -1, 34672, 35246, 35229, -1, 34599, 34600, 35221, -1, 34599, 35221, 35233, -1, 35246, 34485, 35249, -1, 34467, 34485, 35246, -1, 35249, 34492, 35250, -1, 34485, 34492, 35249, -1, 35250, 34498, 35251, -1, 34492, 34498, 35250, -1, 35251, 34502, 35248, -1, 34498, 34502, 35251, -1, 35248, 34510, 35247, -1, 34502, 34510, 35248, -1, 35247, 34514, 35245, -1, 34510, 34514, 35247, -1, 34674, 34988, 35234, -1, 35234, 34988, 35231, -1, 35231, 34982, 35232, -1, 34988, 34982, 35231, -1, 35232, 34984, 35230, -1, 34982, 34984, 35232, -1, 35230, 34992, 35235, -1, 34984, 34992, 35230, -1, 35235, 34995, 35236, -1, 34992, 34995, 35235, -1, 35236, 34599, 35233, -1, 34995, 34599, 35236, -1, 34514, 34620, 35244, -1, 34514, 35244, 35245, -1, 35243, 34674, 35234, -1, 34605, 34674, 35243, -1, 35244, 34702, 35241, -1, 34620, 34702, 35244, -1, 35241, 34678, 35242, -1, 35242, 34678, 35238, -1, 34702, 34678, 35241, -1, 35238, 34652, 35239, -1, 34678, 34652, 35238, -1, 35239, 34633, 35237, -1, 34652, 34633, 35239, -1, 35237, 34607, 35240, -1, 34633, 34607, 35237, -1, 34607, 34603, 35240, -1, 35240, 34605, 35243, -1, 34603, 34605, 35240, -1, 35252, 34608, 35253, -1, 35253, 34852, 35254, -1, 34608, 34852, 35253, -1, 35254, 34847, 35255, -1, 34852, 34847, 35254, -1, 35255, 34839, 35256, -1, 34847, 34839, 35255, -1, 35256, 34841, 35257, -1, 34839, 34841, 35256, -1, 35257, 34851, 35258, -1, 34841, 34851, 35257, -1, 35258, 34854, 35259, -1, 34851, 34854, 35258, -1, 34854, 34858, 35259, -1, 35259, 34661, 35260, -1, 34858, 34661, 35259, -1, 35261, 35262, 35263, -1, 35264, 35262, 35261, -1, 35265, 35262, 35264, -1, 35266, 35262, 35265, -1, 35266, 35267, 35262, -1, 35253, 35254, 35252, -1, 35254, 35255, 35252, -1, 35256, 35257, 35255, -1, 35258, 35259, 35257, -1, 35255, 35259, 35252, -1, 35257, 35259, 35255, -1, 35252, 35260, 35267, -1, 35267, 35260, 35262, -1, 35259, 35260, 35252, -1, 35268, 35269, 35270, -1, 35268, 35271, 35269, -1, 35268, 35272, 35271, -1, 35268, 35273, 35272, -1, 35268, 35274, 35273, -1, 35268, 35275, 35274, -1, 35268, 35276, 35275, -1, 35268, 35277, 35276, -1, 35262, 35278, 35268, -1, 35260, 35278, 35262, -1, 35268, 35278, 35277, -1, 35277, 35279, 35280, -1, 35278, 35279, 35277, -1, 35280, 35281, 35282, -1, 35279, 35281, 35280, -1, 35279, 35283, 35281, -1, 34661, 34347, 35278, -1, 34661, 35278, 35260, -1, 34606, 34608, 35252, -1, 34606, 35252, 35267, -1, 35278, 34358, 35279, -1, 34347, 34358, 35278, -1, 35279, 34374, 35283, -1, 34358, 34374, 35279, -1, 35283, 34382, 35281, -1, 34374, 34382, 35283, -1, 35281, 34393, 35282, -1, 34382, 34393, 35281, -1, 35282, 34395, 35280, -1, 34393, 34395, 35282, -1, 35280, 34405, 35277, -1, 34395, 34405, 35280, -1, 35262, 34671, 35263, -1, 35263, 34916, 35261, -1, 34671, 34916, 35263, -1, 35261, 34910, 35264, -1, 34916, 34910, 35261, -1, 34910, 34912, 35264, -1, 35264, 34914, 35265, -1, 34912, 34914, 35264, -1, 35265, 34920, 35266, -1, 34914, 34920, 35265, -1, 35266, 34606, 35267, -1, 34920, 34606, 35266, -1, 35277, 34516, 35276, -1, 34405, 34516, 35277, -1, 34468, 34671, 35262, -1, 34468, 35262, 35268, -1, 35276, 34511, 35275, -1, 34516, 34511, 35276, -1, 35275, 34503, 35274, -1, 34511, 34503, 35275, -1, 35274, 34499, 35273, -1, 34503, 34499, 35274, -1, 35273, 34493, 35272, -1, 34499, 34493, 35273, -1, 35272, 34486, 35271, -1, 34493, 34486, 35272, -1, 35271, 34470, 35269, -1, 35269, 34470, 35270, -1, 34486, 34470, 35271, -1, 34470, 34466, 35270, -1, 35270, 34468, 35268, -1, 34466, 34468, 35270, -1, 35284, 34398, 35285, -1, 35285, 34392, 35286, -1, 34398, 34392, 35285, -1, 35286, 34387, 35287, -1, 34392, 34387, 35286, -1, 35287, 34377, 35288, -1, 34387, 34377, 35287, -1, 35288, 34360, 35289, -1, 34377, 34360, 35288, -1, 35289, 34349, 35290, -1, 34360, 34349, 35289, -1, 35290, 34346, 35291, -1, 34349, 34346, 35290, -1, 34346, 34348, 35291, -1, 35291, 34660, 35292, -1, 34348, 34660, 35291, -1, 35293, 35294, 35295, -1, 35296, 35294, 35293, -1, 35297, 35294, 35296, -1, 35298, 35294, 35297, -1, 35299, 35294, 35298, -1, 35300, 35301, 35302, -1, 35301, 35303, 35302, -1, 35304, 35305, 35303, -1, 35303, 35305, 35302, -1, 35305, 35306, 35302, -1, 35306, 35307, 35302, -1, 35302, 35308, 35294, -1, 35294, 35308, 35295, -1, 35307, 35308, 35302, -1, 35292, 35290, 35291, -1, 35292, 35289, 35290, -1, 35288, 35286, 35287, -1, 35289, 35286, 35288, -1, 35292, 35286, 35289, -1, 35286, 35284, 35285, -1, 35292, 35284, 35286, -1, 35292, 35309, 35284, -1, 35295, 35310, 35292, -1, 35308, 35310, 35295, -1, 35292, 35310, 35309, -1, 35309, 35311, 35312, -1, 35310, 35313, 35309, -1, 35311, 35314, 35315, -1, 35309, 35314, 35311, -1, 35313, 35314, 35309, -1, 34660, 34659, 35295, -1, 34660, 35295, 35292, -1, 35309, 34398, 35284, -1, 34616, 34398, 35309, -1, 35295, 34659, 35293, -1, 35293, 34845, 35296, -1, 34659, 34845, 35293, -1, 35296, 34838, 35297, -1, 34845, 34838, 35296, -1, 35297, 34840, 35298, -1, 34838, 34840, 35297, -1, 35298, 34848, 35299, -1, 34840, 34848, 35298, -1, 35299, 34853, 35294, -1, 34848, 34853, 35299, -1, 34853, 34609, 35294, -1, 34663, 35050, 35310, -1, 35310, 35050, 35313, -1, 35313, 35050, 35314, -1, 35314, 35055, 35315, -1, 35050, 35055, 35314, -1, 35315, 35073, 35311, -1, 35055, 35073, 35315, -1, 35311, 35077, 35312, -1, 35073, 35077, 35311, -1, 35312, 35079, 35309, -1, 35077, 35079, 35312, -1, 35079, 34616, 35309, -1, 34609, 34611, 35302, -1, 34609, 35302, 35294, -1, 34664, 34663, 35310, -1, 34664, 35310, 35308, -1, 35302, 34611, 35300, -1, 35300, 34772, 35301, -1, 34611, 34772, 35300, -1, 35301, 34765, 35303, -1, 34772, 34765, 35301, -1, 35303, 34757, 35304, -1, 34765, 34757, 35303, -1, 34757, 34762, 35304, -1, 35304, 34771, 35305, -1, 34762, 34771, 35304, -1, 35305, 34776, 35306, -1, 34771, 34776, 35305, -1, 35306, 34782, 35307, -1, 34776, 34782, 35306, -1, 35307, 34664, 35308, -1, 34782, 34664, 35307, -1, 35316, 34713, 35317, -1, 34713, 34711, 35317, -1, 35317, 34709, 35318, -1, 34711, 34709, 35317, -1, 35318, 34705, 35319, -1, 34709, 34705, 35318, -1, 35319, 34708, 35320, -1, 34705, 34708, 35319, -1, 35320, 34710, 35321, -1, 34708, 34710, 35320, -1, 35321, 34712, 35322, -1, 34710, 34712, 35321, -1, 35322, 34717, 35323, -1, 34712, 34717, 35322, -1, 35323, 34651, 35324, -1, 34717, 34651, 35323, -1, 35325, 35326, 35327, -1, 35328, 35326, 35325, -1, 35327, 35329, 35330, -1, 35331, 35329, 35326, -1, 35326, 35329, 35327, -1, 35319, 35320, 35318, -1, 35316, 35324, 35329, -1, 35317, 35324, 35316, -1, 35318, 35324, 35317, -1, 35321, 35324, 35320, -1, 35322, 35324, 35321, -1, 35323, 35324, 35322, -1, 35329, 35324, 35330, -1, 35320, 35324, 35318, -1, 35332, 35333, 35334, -1, 35335, 35336, 35337, -1, 35338, 35336, 35335, -1, 35333, 35336, 35338, -1, 35339, 35336, 35332, -1, 35340, 35336, 35339, -1, 35332, 35336, 35333, -1, 35340, 35341, 35336, -1, 35330, 35342, 35340, -1, 35341, 35342, 35343, -1, 35324, 35342, 35330, -1, 35340, 35342, 35341, -1, 35342, 35344, 35343, -1, 35345, 35346, 35342, -1, 35342, 35346, 35344, -1, 35324, 34667, 35342, -1, 34651, 34667, 35324, -1, 34718, 34713, 35316, -1, 34718, 35316, 35329, -1, 35342, 35002, 35345, -1, 34667, 35002, 35342, -1, 35345, 35004, 35346, -1, 35002, 35004, 35345, -1, 35346, 35006, 35344, -1, 35004, 35006, 35346, -1, 35344, 35007, 35343, -1, 35006, 35007, 35344, -1, 35343, 34614, 35341, -1, 35007, 34614, 35343, -1, 34666, 34761, 35330, -1, 35330, 34761, 35327, -1, 35327, 34761, 35325, -1, 34761, 34756, 35325, -1, 35325, 34758, 35328, -1, 34756, 34758, 35325, -1, 35328, 34767, 35326, -1, 34758, 34767, 35328, -1, 35326, 34773, 35331, -1, 34767, 34773, 35326, -1, 35331, 34718, 35329, -1, 34773, 34718, 35331, -1, 35341, 34615, 35336, -1, 34614, 34615, 35341, -1, 35340, 34666, 35330, -1, 34665, 34666, 35340, -1, 35336, 35076, 35337, -1, 34615, 35076, 35336, -1, 35337, 35072, 35335, -1, 35076, 35072, 35337, -1, 35335, 35054, 35338, -1, 35072, 35054, 35335, -1, 35338, 35049, 35333, -1, 35054, 35049, 35338, -1, 35333, 35040, 35334, -1, 35049, 35040, 35333, -1, 35334, 35038, 35332, -1, 35040, 35038, 35334, -1, 35332, 35036, 35339, -1, 35038, 35036, 35332, -1, 35339, 34665, 35340, -1, 35036, 34665, 35339, -1, 35347, 34928, 35348, -1, 34654, 34928, 35347, -1, 35348, 34931, 35349, -1, 34928, 34931, 35348, -1, 35349, 34935, 35350, -1, 34931, 34935, 35349, -1, 35350, 34941, 35351, -1, 34935, 34941, 35350, -1, 35351, 34948, 35352, -1, 34941, 34948, 35351, -1, 35353, 35354, 35355, -1, 35354, 35356, 35355, -1, 35355, 35357, 35358, -1, 35356, 35357, 35355, -1, 35359, 35360, 35361, -1, 35360, 35362, 35361, -1, 35361, 35363, 35357, -1, 35364, 35363, 35362, -1, 35365, 35363, 35364, -1, 35366, 35363, 35365, -1, 35367, 35363, 35366, -1, 35357, 35363, 35358, -1, 35362, 35363, 35361, -1, 35368, 35369, 35370, -1, 35368, 35371, 35369, -1, 35371, 35372, 35373, -1, 35368, 35372, 35371, -1, 35374, 35375, 35376, -1, 35372, 35375, 35374, -1, 35368, 35375, 35372, -1, 35368, 35352, 35375, -1, 35358, 35347, 35368, -1, 35352, 35347, 35351, -1, 35363, 35347, 35358, -1, 35368, 35347, 35352, -1, 35347, 35350, 35351, -1, 35348, 35349, 35347, -1, 35347, 35349, 35350, -1, 34948, 34613, 35375, -1, 34948, 35375, 35352, -1, 35363, 34654, 35347, -1, 34655, 34654, 35363, -1, 35375, 35008, 35376, -1, 34613, 35008, 35375, -1, 35376, 35005, 35374, -1, 35008, 35005, 35376, -1, 35374, 35003, 35372, -1, 35005, 35003, 35374, -1, 35372, 35001, 35373, -1, 35003, 35001, 35372, -1, 35373, 35000, 35371, -1, 35001, 35000, 35373, -1, 35371, 34999, 35369, -1, 35000, 34999, 35371, -1, 35369, 34998, 35370, -1, 34999, 34998, 35369, -1, 35370, 34650, 35368, -1, 34998, 34650, 35370, -1, 35361, 34647, 35359, -1, 35359, 34627, 35360, -1, 34647, 34627, 35359, -1, 35360, 34619, 35362, -1, 34627, 34619, 35360, -1, 35362, 34610, 35364, -1, 34619, 34610, 35362, -1, 35364, 34601, 35365, -1, 34610, 34601, 35364, -1, 35365, 34623, 35366, -1, 34601, 34623, 35365, -1, 35366, 34638, 35367, -1, 34623, 34638, 35366, -1, 35367, 34662, 35363, -1, 34638, 34662, 35367, -1, 34662, 34655, 35363, -1, 35368, 34649, 35358, -1, 34650, 34649, 35368, -1, 34687, 34647, 35361, -1, 34687, 35361, 35357, -1, 35358, 34707, 35355, -1, 34649, 34707, 35358, -1, 35355, 34704, 35353, -1, 34707, 34704, 35355, -1, 35353, 34706, 35354, -1, 34704, 34706, 35353, -1, 35354, 34692, 35356, -1, 34706, 34692, 35354, -1, 35356, 34687, 35357, -1, 34692, 34687, 35356, -1, 35122, 34865, 35121, -1, 34657, 34865, 35122, -1, 35121, 34872, 35118, -1, 34865, 34872, 35121, -1, 35118, 34878, 35119, -1, 34872, 34878, 35118, -1, 35119, 34883, 35120, -1, 34878, 34883, 35119, -1, 35120, 34892, 35117, -1, 34883, 34892, 35120, -1, 34892, 34906, 35117, -1, 35117, 34906, 35111, -1, 34546, 35122, 35107, -1, 34546, 34657, 35122, -1, 35111, 34937, 35112, -1, 35112, 34937, 35108, -1, 34906, 34937, 35111, -1, 35108, 34933, 35109, -1, 34937, 34933, 35108, -1, 35109, 34929, 35110, -1, 34933, 34929, 35109, -1, 35110, 34927, 35114, -1, 34929, 34927, 35110, -1, 35114, 34926, 35115, -1, 34927, 34926, 35114, -1, 35115, 34925, 35116, -1, 34926, 34925, 35115, -1, 34925, 34924, 35116, -1, 35116, 34656, 35113, -1, 34924, 34656, 35116, -1, 35127, 34551, 35128, -1, 35128, 34541, 35129, -1, 34551, 34541, 35128, -1, 35129, 34529, 35098, -1, 34541, 34529, 35129, -1, 34529, 34527, 35098, -1, 34656, 35123, 35113, -1, 34656, 34577, 35123, -1, 35126, 34551, 35127, -1, 34572, 34551, 35126, -1, 35123, 34575, 35125, -1, 34577, 34575, 35123, -1, 35125, 34573, 35124, -1, 34575, 34573, 35125, -1, 35124, 34572, 35126, -1, 34573, 34572, 35124, -1, 34465, 34668, 35377, -1, 34465, 35377, 35378, -1, 35377, 35379, 35380, -1, 35377, 35381, 35379, -1, 35382, 35383, 35384, -1, 35382, 35385, 35383, -1, 35386, 35387, 35388, -1, 35389, 35387, 35386, -1, 35390, 35391, 35387, -1, 35392, 35391, 35390, -1, 35393, 35394, 35391, -1, 35387, 35394, 35388, -1, 35391, 35394, 35387, -1, 35395, 35378, 35382, -1, 35396, 35378, 35395, -1, 35397, 35378, 35396, -1, 35398, 35378, 35397, -1, 35388, 35378, 35398, -1, 35382, 35378, 35385, -1, 35394, 35378, 35388, -1, 35399, 35400, 35401, -1, 35400, 35402, 35403, -1, 35404, 35405, 35406, -1, 35402, 35405, 35404, -1, 35407, 35405, 35399, -1, 35408, 35405, 35407, -1, 35399, 35405, 35400, -1, 35400, 35405, 35402, -1, 35408, 35409, 35405, -1, 35385, 35377, 35408, -1, 35410, 35377, 35380, -1, 35409, 35377, 35410, -1, 35378, 35377, 35385, -1, 35408, 35377, 35409, -1, 35377, 34806, 35381, -1, 34668, 34806, 35377, -1, 35381, 34814, 35379, -1, 34806, 34814, 35381, -1, 35379, 34820, 35380, -1, 35380, 34820, 35410, -1, 34814, 34820, 35379, -1, 34820, 34823, 35410, -1, 35410, 34826, 35409, -1, 34823, 34826, 35410, -1, 35388, 34460, 35386, -1, 35386, 34456, 35389, -1, 34460, 34456, 35386, -1, 35389, 34454, 35387, -1, 34456, 34454, 35389, -1, 35387, 34443, 35390, -1, 34454, 34443, 35387, -1, 35390, 34448, 35392, -1, 34443, 34448, 35390, -1, 35392, 34455, 35391, -1, 34448, 34455, 35392, -1, 35391, 34457, 35393, -1, 34455, 34457, 35391, -1, 35393, 34461, 35394, -1, 34457, 34461, 35393, -1, 35394, 34464, 35378, -1, 34461, 34464, 35394, -1, 34464, 34465, 35378, -1, 34826, 34830, 35405, -1, 34826, 35405, 35409, -1, 34472, 34460, 35388, -1, 34472, 35388, 35398, -1, 35405, 34886, 35406, -1, 34830, 34886, 35405, -1, 35406, 34877, 35404, -1, 34886, 34877, 35406, -1, 35404, 34871, 35402, -1, 34877, 34871, 35404, -1, 35402, 34864, 35403, -1, 34871, 34864, 35402, -1, 35403, 34863, 35400, -1, 34864, 34863, 35403, -1, 35400, 34862, 35401, -1, 34863, 34862, 35400, -1, 35401, 34861, 35399, -1, 34862, 34861, 35401, -1, 35399, 34860, 35407, -1, 34861, 34860, 35399, -1, 35407, 34658, 35408, -1, 34860, 34658, 35407, -1, 35395, 34489, 35396, -1, 35396, 34483, 35397, -1, 34489, 34483, 35396, -1, 35397, 34476, 35398, -1, 34483, 34476, 35397, -1, 34476, 34472, 35398, -1, 35408, 34506, 35385, -1, 34658, 34506, 35408, -1, 34490, 34489, 35395, -1, 34490, 35395, 35382, -1, 35385, 34530, 35383, -1, 34506, 34530, 35385, -1, 35383, 34491, 35384, -1, 34530, 34491, 35383, -1, 35384, 34490, 35382, -1, 34491, 34490, 35384, -1, 35411, 34388, 35412, -1, 35412, 34381, 35413, -1, 34388, 34381, 35412, -1, 35413, 34365, 35414, -1, 34381, 34365, 35413, -1, 35414, 34362, 35415, -1, 34365, 34362, 35414, -1, 35415, 34361, 35416, -1, 34362, 34361, 35415, -1, 35416, 34373, 35417, -1, 34361, 34373, 35416, -1, 35417, 34383, 35418, -1, 34373, 34383, 35417, -1, 35418, 34391, 35419, -1, 34383, 34391, 35418, -1, 34391, 34397, 35419, -1, 35419, 34399, 35420, -1, 34397, 34399, 35419, -1, 35421, 35422, 35423, -1, 35421, 35424, 35422, -1, 35424, 35425, 35422, -1, 35425, 35426, 35422, -1, 35412, 35414, 35411, -1, 35413, 35414, 35412, -1, 35415, 35417, 35414, -1, 35416, 35417, 35415, -1, 35411, 35420, 35426, -1, 35418, 35420, 35417, -1, 35419, 35420, 35418, -1, 35426, 35420, 35422, -1, 35417, 35420, 35414, -1, 35414, 35420, 35411, -1, 35427, 35428, 35429, -1, 35427, 35430, 35428, -1, 35427, 35431, 35430, -1, 35427, 35432, 35431, -1, 35427, 35433, 35432, -1, 35427, 35434, 35433, -1, 35427, 35435, 35434, -1, 35427, 35436, 35435, -1, 35427, 35437, 35436, -1, 35437, 35438, 35439, -1, 35422, 35440, 35427, -1, 35420, 35440, 35422, -1, 35427, 35440, 35437, -1, 35438, 35441, 35442, -1, 35437, 35441, 35438, -1, 35440, 35441, 35437, -1, 34399, 34745, 35440, -1, 34399, 35440, 35420, -1, 34421, 34388, 35411, -1, 34421, 35411, 35426, -1, 35440, 34746, 35441, -1, 35441, 34746, 35442, -1, 34745, 34746, 35440, -1, 35442, 34750, 35438, -1, 34746, 34750, 35442, -1, 35438, 34749, 35439, -1, 34750, 34749, 35438, -1, 35439, 34747, 35437, -1, 34749, 34747, 35439, -1, 34747, 34748, 35437, -1, 35422, 34447, 35423, -1, 35423, 34442, 35421, -1, 34447, 34442, 35423, -1, 35421, 34425, 35424, -1, 34442, 34425, 35421, -1, 35424, 34423, 35425, -1, 34425, 34423, 35424, -1, 35425, 34422, 35426, -1, 34423, 34422, 35425, -1, 34422, 34421, 35426, -1, 34748, 34784, 35436, -1, 34748, 35436, 35437, -1, 34669, 34447, 35422, -1, 34669, 35422, 35427, -1, 35436, 34786, 35435, -1, 34784, 34786, 35436, -1, 35435, 34816, 35434, -1, 35434, 34816, 35433, -1, 34786, 34816, 35435, -1, 35433, 34805, 35432, -1, 34816, 34805, 35433, -1, 35432, 34799, 35431, -1, 34805, 34799, 35432, -1, 35431, 34798, 35430, -1, 34799, 34798, 35431, -1, 35430, 34797, 35428, -1, 34798, 34797, 35430, -1, 35428, 34794, 35429, -1, 34797, 34794, 35428, -1, 34794, 34793, 35429, -1, 35429, 34669, 35427, -1, 34793, 34669, 35429, -1, 35443, 34212, 35444, -1, 35444, 34208, 35445, -1, 34212, 34208, 35444, -1, 35445, 34207, 35446, -1, 34208, 34207, 35445, -1, 34207, 34196, 35446, -1, 35446, 34195, 35447, -1, 35447, 34195, 35448, -1, 34196, 34195, 35446, -1, 34195, 33777, 35448, -1, 35449, 35450, 35451, -1, 35452, 35450, 35449, -1, 35453, 35450, 35452, -1, 35454, 35450, 35453, -1, 35455, 35450, 35454, -1, 35456, 35450, 35455, -1, 35457, 35450, 35456, -1, 35458, 35450, 35457, -1, 35458, 35459, 35450, -1, 35460, 35461, 35462, -1, 35462, 35463, 35459, -1, 35461, 35463, 35462, -1, 35459, 35464, 35450, -1, 35463, 35464, 35459, -1, 35464, 35448, 35450, -1, 35448, 35446, 35447, -1, 35446, 35444, 35445, -1, 35448, 35444, 35446, -1, 35448, 35443, 35444, -1, 35464, 35465, 35448, -1, 35448, 35465, 35443, -1, 35466, 35467, 35465, -1, 35465, 35467, 35443, -1, 35468, 35469, 35466, -1, 35467, 35470, 35471, -1, 35472, 35473, 35469, -1, 35469, 35473, 35466, -1, 35466, 35473, 35467, -1, 35467, 35473, 35470, -1, 35473, 35474, 35470, -1, 35448, 33775, 35450, -1, 33777, 33775, 35448, -1, 34249, 34212, 35443, -1, 34249, 35443, 35467, -1, 35450, 33775, 35451, -1, 35451, 34320, 35449, -1, 33775, 34320, 35451, -1, 35449, 34324, 35452, -1, 34320, 34324, 35449, -1, 35452, 34330, 35453, -1, 34324, 34330, 35452, -1, 35453, 34336, 35454, -1, 34330, 34336, 35453, -1, 35454, 34338, 35455, -1, 34336, 34338, 35454, -1, 35455, 33605, 35456, -1, 34338, 33605, 35455, -1, 35456, 33604, 35457, -1, 33605, 33604, 35456, -1, 35457, 33615, 35458, -1, 33604, 33615, 35457, -1, 33615, 33667, 35458, -1, 33658, 34283, 35465, -1, 35465, 34283, 35466, -1, 35466, 34283, 35468, -1, 35468, 34281, 35469, -1, 34283, 34281, 35468, -1, 35469, 34280, 35472, -1, 34281, 34280, 35469, -1, 35472, 34278, 35473, -1, 34280, 34278, 35472, -1, 35473, 34277, 35474, -1, 34278, 34277, 35473, -1, 35474, 34276, 35470, -1, 34277, 34276, 35474, -1, 35470, 34275, 35471, -1, 34276, 34275, 35470, -1, 35471, 34274, 35467, -1, 34275, 34274, 35471, -1, 34274, 34249, 35467, -1, 33667, 33665, 35459, -1, 33667, 35459, 35458, -1, 33659, 33658, 35465, -1, 33659, 35465, 35464, -1, 35459, 33663, 35462, -1, 35462, 33663, 35460, -1, 33665, 33663, 35459, -1, 35460, 33662, 35461, -1, 33663, 33662, 35460, -1, 35461, 33661, 35463, -1, 33662, 33661, 35461, -1, 35463, 33660, 35464, -1, 33661, 33660, 35463, -1, 33660, 33659, 35464, -1, 35475, 33752, 35476, -1, 33776, 33752, 35475, -1, 35477, 35476, 35478, -1, 35479, 35476, 35477, -1, 35480, 35476, 35479, -1, 35481, 35476, 35480, -1, 35482, 35476, 35481, -1, 35483, 35476, 35482, -1, 35484, 35476, 35483, -1, 35485, 35476, 35484, -1, 35485, 35486, 35476, -1, 35487, 35488, 35486, -1, 35488, 35489, 35486, -1, 35490, 35491, 35489, -1, 35486, 35491, 35476, -1, 35489, 35491, 35486, -1, 35491, 35475, 35476, -1, 35492, 35493, 35494, -1, 35475, 35493, 35492, -1, 35495, 35496, 35497, -1, 35498, 35499, 35496, -1, 35500, 35499, 35498, -1, 35496, 35499, 35497, -1, 35497, 35499, 35493, -1, 35491, 35497, 35493, -1, 35491, 35493, 35475, -1, 34139, 35494, 35493, -1, 34139, 34146, 35494, -1, 35494, 34153, 35492, -1, 34146, 34153, 35494, -1, 34153, 35475, 35492, -1, 34153, 33776, 35475, -1, 35476, 33752, 35478, -1, 35478, 34290, 35477, -1, 33752, 34290, 35478, -1, 35477, 34297, 35479, -1, 34290, 34297, 35477, -1, 35479, 34299, 35480, -1, 34297, 34299, 35479, -1, 35480, 34305, 35481, -1, 34299, 34305, 35480, -1, 35481, 34307, 35482, -1, 34305, 34307, 35481, -1, 35482, 34311, 35483, -1, 34307, 34311, 35482, -1, 35483, 34315, 35484, -1, 34311, 34315, 35483, -1, 35484, 34316, 35485, -1, 34315, 34316, 35484, -1, 34316, 33649, 35485, -1, 35499, 34139, 35493, -1, 34132, 34139, 35499, -1, 35485, 33651, 35486, -1, 33649, 33651, 35485, -1, 35501, 35502, 35499, -1, 35499, 35503, 34132, -1, 35502, 35503, 35499, -1, 34194, 35504, 35499, -1, 34150, 35504, 34158, -1, 34158, 35504, 34167, -1, 34167, 35504, 34194, -1, 35499, 35504, 35501, -1, 34137, 35505, 34141, -1, 34141, 35505, 34150, -1, 35504, 35505, 35501, -1, 34150, 35505, 35504, -1, 35501, 35505, 35502, -1, 34132, 35506, 34130, -1, 34130, 35506, 34134, -1, 34134, 35506, 34137, -1, 34137, 35506, 35505, -1, 35503, 35506, 34132, -1, 35502, 35506, 35503, -1, 35505, 35506, 35502, -1, 35486, 33650, 35487, -1, 33651, 33650, 35486, -1, 35487, 33614, 35488, -1, 33650, 33614, 35487, -1, 35488, 33603, 35489, -1, 33614, 33603, 35488, -1, 35489, 34337, 35490, -1, 35490, 34337, 35491, -1, 33603, 34337, 35489, -1, 34337, 33774, 35491, -1, 33773, 34204, 35497, -1, 35497, 34204, 35495, -1, 35495, 34203, 35496, -1, 34204, 34203, 35495, -1, 35496, 34202, 35498, -1, 34203, 34202, 35496, -1, 35498, 34201, 35500, -1, 34202, 34201, 35498, -1, 35500, 34194, 35499, -1, 34201, 34194, 35500, -1, 35491, 33773, 35497, -1, 33774, 33773, 35491, -1, 35507, 34046, 35508, -1, 34051, 34046, 35507, -1, 35508, 34036, 35509, -1, 34046, 34036, 35508, -1, 35509, 34028, 35510, -1, 34036, 34028, 35509, -1, 35510, 34030, 35511, -1, 35511, 34030, 35512, -1, 34028, 34030, 35510, -1, 34030, 33755, 35512, -1, 35513, 35514, 35515, -1, 35516, 35514, 35513, -1, 35517, 35514, 35516, -1, 35518, 35514, 35517, -1, 35519, 35514, 35518, -1, 35520, 35514, 35519, -1, 35521, 35514, 35520, -1, 35522, 35514, 35521, -1, 35522, 35523, 35514, -1, 35524, 35525, 35523, -1, 35526, 35525, 35524, -1, 35527, 35525, 35526, -1, 35523, 35528, 35514, -1, 35525, 35528, 35523, -1, 35528, 35512, 35514, -1, 35509, 35507, 35508, -1, 35510, 35507, 35509, -1, 35511, 35507, 35510, -1, 35512, 35507, 35511, -1, 35528, 35529, 35512, -1, 35512, 35529, 35507, -1, 35530, 35531, 35529, -1, 35532, 35531, 35530, -1, 35529, 35531, 35507, -1, 35533, 35534, 35532, -1, 35532, 35534, 35531, -1, 35531, 35535, 35536, -1, 35534, 35537, 35531, -1, 35531, 35538, 35535, -1, 35537, 35538, 35531, -1, 35512, 33746, 35514, -1, 33755, 33746, 35512, -1, 35531, 34051, 35507, -1, 34073, 34051, 35531, -1, 35514, 34219, 35515, -1, 33746, 34219, 35514, -1, 35515, 34222, 35513, -1, 34219, 34222, 35515, -1, 35513, 34227, 35516, -1, 34222, 34227, 35513, -1, 35516, 34232, 35517, -1, 34227, 34232, 35516, -1, 35517, 34234, 35518, -1, 34232, 34234, 35517, -1, 35518, 34240, 35519, -1, 34234, 34240, 35518, -1, 35519, 34245, 35520, -1, 34240, 34245, 35519, -1, 35520, 34246, 35521, -1, 35521, 34246, 35522, -1, 34245, 34246, 35520, -1, 34246, 33654, 35522, -1, 33750, 34174, 35529, -1, 35529, 34174, 35530, -1, 35530, 34172, 35532, -1, 34174, 34172, 35530, -1, 35532, 34111, 35533, -1, 34172, 34111, 35532, -1, 35533, 34104, 35534, -1, 34111, 34104, 35533, -1, 35534, 34100, 35537, -1, 34104, 34100, 35534, -1, 35537, 34096, 35538, -1, 34100, 34096, 35537, -1, 35538, 34092, 35535, -1, 35535, 34092, 35536, -1, 34096, 34092, 35538, -1, 35536, 34085, 35531, -1, 34092, 34085, 35536, -1, 34085, 34073, 35531, -1, 33654, 33647, 35523, -1, 33654, 35523, 35522, -1, 35528, 33750, 35529, -1, 33751, 33750, 35528, -1, 35523, 33647, 35524, -1, 35524, 34317, 35526, -1, 33647, 34317, 35524, -1, 35526, 34314, 35527, -1, 34317, 34314, 35526, -1, 35527, 34310, 35525, -1, 34314, 34310, 35527, -1, 35525, 34306, 35528, -1, 34310, 34306, 35525, -1, 34306, 33751, 35528, -1, 35539, 34114, 35540, -1, 33747, 34114, 35539, -1, 35540, 34115, 35541, -1, 34114, 34115, 35540, -1, 35541, 34121, 35542, -1, 34115, 34121, 35541, -1, 35542, 34123, 35543, -1, 34121, 34123, 35542, -1, 35543, 34143, 35544, -1, 34123, 34143, 35543, -1, 35544, 34162, 35545, -1, 34143, 34162, 35544, -1, 35545, 34177, 35546, -1, 35546, 34177, 35547, -1, 34162, 34177, 35545, -1, 34177, 33657, 35547, -1, 35544, 35545, 35543, -1, 35545, 35542, 35543, -1, 35545, 35541, 35542, -1, 35546, 35547, 35545, -1, 35545, 35547, 35541, -1, 35547, 35540, 35541, -1, 35547, 35539, 35540, -1, 35547, 35548, 35539, -1, 35549, 35550, 35548, -1, 35551, 35550, 35549, -1, 35552, 35550, 35551, -1, 35553, 35550, 35552, -1, 35548, 35550, 35539, -1, 35550, 35554, 35539, -1, 35555, 35556, 35557, -1, 35556, 35558, 35559, -1, 35554, 35558, 35555, -1, 35555, 35558, 35556, -1, 35550, 35560, 35554, -1, 35554, 35560, 35558, -1, 35561, 35562, 35560, -1, 35560, 35562, 35558, -1, 35561, 35563, 35562, -1, 35563, 35564, 35562, -1, 35562, 35565, 35566, -1, 35564, 35567, 35562, -1, 35565, 35568, 35569, -1, 35562, 35568, 35565, -1, 35567, 35568, 35562, -1, 33657, 33653, 35548, -1, 33657, 35548, 35547, -1, 35554, 33747, 35539, -1, 33748, 33747, 35554, -1, 35548, 33653, 35549, -1, 35549, 34244, 35551, -1, 33653, 34244, 35549, -1, 35551, 34239, 35552, -1, 34244, 34239, 35551, -1, 35552, 34233, 35553, -1, 34239, 34233, 35552, -1, 35553, 34231, 35550, -1, 34233, 34231, 35553, -1, 34231, 33745, 35550, -1, 33707, 33944, 35558, -1, 35558, 33944, 35559, -1, 35559, 33935, 35556, -1, 33944, 33935, 35559, -1, 35556, 33926, 35557, -1, 33935, 33926, 35556, -1, 35557, 33932, 35555, -1, 33926, 33932, 35557, -1, 35555, 33748, 35554, -1, 33932, 33748, 35555, -1, 33745, 33744, 35560, -1, 33745, 35560, 35550, -1, 34049, 33707, 35558, -1, 34049, 35558, 35562, -1, 35560, 34042, 35561, -1, 33744, 34042, 35560, -1, 35561, 34041, 35563, -1, 34042, 34041, 35561, -1, 35563, 34039, 35564, -1, 34041, 34039, 35563, -1, 35564, 34033, 35567, -1, 34039, 34033, 35564, -1, 35567, 34027, 35568, -1, 34033, 34027, 35567, -1, 35568, 34029, 35569, -1, 34027, 34029, 35568, -1, 35569, 34037, 35565, -1, 34029, 34037, 35569, -1, 35565, 34048, 35566, -1, 35566, 34048, 35562, -1, 34037, 34048, 35565, -1, 34048, 34049, 35562, -1, 35570, 33709, 35571, -1, 35571, 33836, 35572, -1, 33709, 33836, 35571, -1, 35572, 33832, 35573, -1, 33836, 33832, 35572, -1, 35573, 33824, 35574, -1, 33832, 33824, 35573, -1, 35574, 33829, 35575, -1, 33824, 33829, 35574, -1, 33829, 33763, 35575, -1, 35576, 35577, 35578, -1, 35579, 35577, 35576, -1, 35580, 35577, 35579, -1, 35581, 35577, 35580, -1, 35582, 35577, 35581, -1, 35583, 35577, 35582, -1, 35584, 35577, 35583, -1, 35584, 35585, 35577, -1, 35586, 35587, 35585, -1, 35588, 35589, 35587, -1, 35587, 35589, 35585, -1, 35585, 35590, 35577, -1, 35589, 35590, 35585, -1, 35590, 35575, 35577, -1, 35574, 35572, 35573, -1, 35575, 35572, 35574, -1, 35572, 35570, 35571, -1, 35575, 35570, 35572, -1, 35590, 35591, 35575, -1, 35575, 35591, 35570, -1, 35592, 35593, 35591, -1, 35591, 35593, 35570, -1, 35592, 35594, 35593, -1, 35595, 35596, 35592, -1, 35597, 35598, 35596, -1, 35594, 35598, 35599, -1, 35596, 35598, 35592, -1, 35592, 35598, 35594, -1, 35575, 33758, 35577, -1, 33763, 33758, 35575, -1, 33708, 33709, 35570, -1, 33708, 35570, 35593, -1, 35577, 33998, 35578, -1, 33758, 33998, 35577, -1, 35578, 34001, 35576, -1, 33998, 34001, 35578, -1, 35576, 34006, 35579, -1, 34001, 34006, 35576, -1, 35579, 34010, 35580, -1, 34006, 34010, 35579, -1, 35580, 34016, 35581, -1, 34010, 34016, 35580, -1, 35581, 34021, 35582, -1, 34016, 34021, 35581, -1, 35582, 34025, 35583, -1, 35583, 34025, 35584, -1, 34021, 34025, 35582, -1, 34025, 33703, 35584, -1, 33749, 33942, 35591, -1, 35591, 33942, 35592, -1, 35592, 33940, 35595, -1, 33942, 33940, 35592, -1, 35595, 33939, 35596, -1, 33940, 33939, 35595, -1, 35596, 33931, 35597, -1, 33939, 33931, 35596, -1, 35597, 33925, 35598, -1, 33931, 33925, 35597, -1, 35598, 33927, 35599, -1, 33925, 33927, 35598, -1, 35599, 33936, 35594, -1, 33927, 33936, 35599, -1, 35594, 33708, 35593, -1, 33936, 33708, 35594, -1, 33703, 33704, 35585, -1, 33703, 35585, 35584, -1, 33762, 33749, 35591, -1, 33762, 35591, 35590, -1, 35585, 34176, 35586, -1, 33704, 34176, 35585, -1, 35586, 34161, 35587, -1, 35587, 34161, 35588, -1, 34176, 34161, 35586, -1, 35588, 34142, 35589, -1, 34161, 34142, 35588, -1, 35589, 34122, 35590, -1, 34142, 34122, 35589, -1, 34122, 33762, 35590, -1, 35600, 33601, 35601, -1, 33610, 33601, 35600, -1, 35601, 33606, 35602, -1, 33601, 33606, 35601, -1, 35602, 34331, 35603, -1, 33606, 34331, 35602, -1, 35603, 34328, 35604, -1, 34331, 34328, 35603, -1, 35604, 34335, 35605, -1, 35605, 34335, 35606, -1, 34328, 34335, 35604, -1, 34335, 33760, 35606, -1, 35607, 35608, 35609, -1, 35610, 35608, 35607, -1, 35611, 35608, 35610, -1, 35612, 35608, 35611, -1, 35613, 35608, 35612, -1, 35614, 35608, 35613, -1, 35615, 35608, 35614, -1, 35615, 35616, 35608, -1, 35617, 35618, 35619, -1, 35619, 35620, 35616, -1, 35618, 35620, 35619, -1, 35616, 35621, 35608, -1, 35620, 35621, 35616, -1, 35621, 35606, 35608, -1, 35606, 35604, 35605, -1, 35602, 35600, 35601, -1, 35603, 35600, 35602, -1, 35604, 35600, 35603, -1, 35606, 35600, 35604, -1, 35621, 35622, 35606, -1, 35606, 35622, 35600, -1, 35623, 35624, 35622, -1, 35622, 35624, 35600, -1, 35625, 35626, 35623, -1, 35623, 35626, 35624, -1, 35624, 35627, 35628, -1, 35629, 35630, 35626, -1, 35626, 35630, 35624, -1, 35624, 35630, 35627, -1, 35606, 33759, 35608, -1, 33760, 33759, 35606, -1, 33710, 33610, 35600, -1, 33710, 35600, 35624, -1, 35608, 33914, 35609, -1, 33759, 33914, 35608, -1, 35609, 33915, 35607, -1, 33914, 33915, 35609, -1, 35607, 33919, 35610, -1, 33915, 33919, 35607, -1, 35610, 33946, 35611, -1, 33919, 33946, 35610, -1, 35611, 33950, 35612, -1, 33946, 33950, 35611, -1, 35612, 33956, 35613, -1, 35613, 33956, 35614, -1, 33950, 33956, 35612, -1, 35614, 33959, 35615, -1, 33956, 33959, 35614, -1, 33959, 33701, 35615, -1, 33756, 33835, 35622, -1, 35622, 33835, 35623, -1, 35623, 33835, 35625, -1, 35625, 33834, 35626, -1, 33835, 33834, 35625, -1, 35626, 33828, 35629, -1, 33834, 33828, 35626, -1, 35629, 33823, 35630, -1, 33828, 33823, 35629, -1, 35630, 33825, 35627, -1, 33823, 33825, 35630, -1, 35627, 33833, 35628, -1, 33825, 33833, 35627, -1, 35628, 33837, 35624, -1, 33833, 33837, 35628, -1, 33837, 33710, 35624, -1, 33701, 33702, 35616, -1, 33701, 35616, 35615, -1, 33757, 33756, 35622, -1, 33757, 35622, 35621, -1, 35616, 34022, 35619, -1, 33702, 34022, 35616, -1, 35619, 34017, 35617, -1, 34022, 34017, 35619, -1, 35617, 34014, 35618, -1, 34017, 34014, 35617, -1, 35618, 34007, 35620, -1, 35620, 34007, 35621, -1, 34014, 34007, 35618, -1, 34007, 33757, 35621, -1, 35631, 33711, 35632, -1, 33711, 34264, 35632, -1, 35632, 34260, 35633, -1, 34264, 34260, 35632, -1, 35633, 34256, 35634, -1, 34260, 34256, 35633, -1, 35634, 34254, 35635, -1, 34256, 34254, 35634, -1, 35635, 34258, 35636, -1, 35636, 34258, 35637, -1, 34254, 34258, 35635, -1, 34258, 33770, 35637, -1, 35631, 35632, 35633, -1, 35631, 35633, 35634, -1, 35631, 35634, 35635, -1, 35631, 35635, 35636, -1, 35631, 35636, 35637, -1, 35638, 35639, 35640, -1, 35641, 35642, 35638, -1, 35641, 35638, 35640, -1, 35643, 35644, 35641, -1, 35645, 35643, 35641, -1, 35645, 35641, 35640, -1, 35646, 35640, 35631, -1, 35646, 35631, 35637, -1, 35646, 35645, 35640, -1, 35647, 35648, 35649, -1, 35647, 35649, 35650, -1, 35647, 35650, 35651, -1, 35652, 35647, 35653, -1, 35652, 35648, 35647, -1, 35654, 35655, 35648, -1, 35654, 35648, 35652, -1, 35656, 35655, 35654, -1, 35657, 35637, 35655, -1, 35657, 35646, 35637, -1, 35657, 35655, 35656, -1, 35658, 35656, 35659, -1, 35658, 35657, 35656, -1, 35660, 35659, 35661, -1, 35662, 35658, 35659, -1, 35662, 35659, 35660, -1, 33770, 33768, 35637, -1, 35637, 33768, 35655, -1, 35640, 33711, 35631, -1, 33602, 33711, 35640, -1, 35655, 33842, 35648, -1, 33768, 33842, 35655, -1, 35648, 33853, 35649, -1, 33842, 33853, 35648, -1, 35649, 33858, 35650, -1, 33853, 33858, 35649, -1, 35650, 33865, 35651, -1, 33858, 33865, 35650, -1, 35651, 33872, 35647, -1, 35647, 33872, 35653, -1, 33865, 33872, 35651, -1, 35653, 33876, 35652, -1, 33872, 33876, 35653, -1, 35652, 33880, 35654, -1, 33876, 33880, 35652, -1, 33880, 33699, 35654, -1, 33761, 34345, 35646, -1, 35646, 34345, 35645, -1, 35645, 34344, 35643, -1, 34345, 34344, 35645, -1, 35643, 34339, 35644, -1, 34344, 34339, 35643, -1, 35644, 34327, 35641, -1, 34339, 34327, 35644, -1, 35641, 34329, 35642, -1, 34327, 34329, 35641, -1, 35642, 34334, 35638, -1, 34329, 34334, 35642, -1, 35638, 33600, 35639, -1, 34334, 33600, 35638, -1, 35639, 33602, 35640, -1, 33600, 33602, 35639, -1, 33699, 33700, 35654, -1, 35654, 33700, 35656, -1, 33772, 35646, 35657, -1, 33772, 33761, 35646, -1, 35656, 33958, 35659, -1, 33700, 33958, 35656, -1, 35659, 33957, 35661, -1, 33958, 33957, 35659, -1, 35661, 33951, 35660, -1, 33957, 33951, 35661, -1, 35660, 33948, 35662, -1, 33951, 33948, 35660, -1, 35662, 33920, 35658, -1, 35658, 33920, 35657, -1, 33948, 33920, 35662, -1, 33920, 33772, 35657, -1, 35663, 33627, 35664, -1, 35664, 33626, 35665, -1, 33627, 33626, 35664, -1, 35665, 33632, 35666, -1, 33626, 33632, 35665, -1, 35666, 33639, 35667, -1, 33632, 33639, 35666, -1, 35667, 33644, 35668, -1, 33639, 33644, 35667, -1, 35668, 33652, 35669, -1, 33644, 33652, 35668, -1, 35669, 33664, 35670, -1, 33652, 33664, 35669, -1, 35670, 33682, 35671, -1, 33664, 33682, 35670, -1, 33682, 33697, 35671, -1, 35668, 35669, 35667, -1, 35665, 35663, 35664, -1, 35666, 35663, 35665, -1, 35667, 35663, 35666, -1, 35670, 35663, 35669, -1, 35671, 35663, 35670, -1, 35669, 35663, 35667, -1, 35671, 35672, 35663, -1, 35673, 35674, 35675, -1, 35676, 35677, 35672, -1, 35675, 35677, 35676, -1, 35678, 35677, 35674, -1, 35672, 35677, 35663, -1, 35674, 35677, 35675, -1, 35677, 35679, 35663, -1, 35680, 35681, 35682, -1, 35681, 35683, 35684, -1, 35679, 35683, 35680, -1, 35680, 35683, 35681, -1, 35679, 35685, 35683, -1, 35677, 35686, 35679, -1, 35679, 35686, 35685, -1, 35686, 35687, 35685, -1, 35688, 35689, 35686, -1, 35686, 35690, 35687, -1, 35689, 35691, 35686, -1, 35686, 35692, 35690, -1, 35691, 35693, 35686, -1, 35686, 35694, 35692, -1, 35693, 35694, 35686, -1, 33697, 33698, 35672, -1, 33697, 35672, 35671, -1, 35679, 33627, 35663, -1, 33764, 33627, 35679, -1, 35672, 33879, 35676, -1, 33698, 33879, 35672, -1, 35676, 33875, 35675, -1, 35675, 33875, 35673, -1, 33879, 33875, 35676, -1, 35673, 33873, 35674, -1, 33875, 33873, 35673, -1, 35674, 33866, 35678, -1, 33873, 33866, 35674, -1, 35678, 33859, 35677, -1, 33866, 33859, 35678, -1, 33859, 33767, 35677, -1, 33713, 34191, 35685, -1, 35685, 34191, 35683, -1, 35683, 34191, 35684, -1, 34191, 34187, 35684, -1, 35684, 34183, 35681, -1, 34187, 34183, 35684, -1, 35681, 34186, 35682, -1, 34183, 34186, 35681, -1, 35682, 34190, 35680, -1, 34186, 34190, 35682, -1, 35680, 33764, 35679, -1, 34190, 33764, 35680, -1, 33767, 33766, 35686, -1, 33767, 35686, 35677, -1, 33712, 33713, 35685, -1, 33712, 35685, 35687, -1, 35686, 33766, 35688, -1, 35688, 34263, 35689, -1, 33766, 34263, 35688, -1, 35689, 34262, 35691, -1, 34263, 34262, 35689, -1, 35691, 34259, 35693, -1, 34262, 34259, 35691, -1, 34259, 34253, 35693, -1, 35693, 34255, 35694, -1, 34253, 34255, 35693, -1, 35694, 34257, 35692, -1, 34255, 34257, 35694, -1, 35692, 34261, 35690, -1, 35690, 34261, 35687, -1, 34257, 34261, 35692, -1, 34261, 33712, 35687, -1, 35695, 34107, 35696, -1, 33715, 34107, 35695, -1, 35696, 34098, 35697, -1, 34107, 34098, 35696, -1, 35697, 34090, 35698, -1, 34098, 34090, 35697, -1, 35698, 34093, 35699, -1, 34090, 34093, 35698, -1, 35699, 34103, 35700, -1, 35700, 34103, 35701, -1, 34093, 34103, 35699, -1, 34103, 34109, 35701, -1, 35702, 35703, 35704, -1, 35705, 35706, 35702, -1, 35707, 35706, 35705, -1, 35702, 35706, 35703, -1, 35707, 35708, 35706, -1, 35708, 35709, 35706, -1, 35708, 35710, 35709, -1, 35711, 35712, 35713, -1, 35713, 35714, 35710, -1, 35715, 35714, 35712, -1, 35712, 35714, 35713, -1, 35710, 35716, 35709, -1, 35714, 35716, 35710, -1, 35716, 35701, 35709, -1, 35701, 35699, 35700, -1, 35701, 35698, 35699, -1, 35701, 35697, 35698, -1, 35697, 35695, 35696, -1, 35701, 35695, 35697, -1, 35716, 35717, 35701, -1, 35701, 35717, 35695, -1, 35717, 35718, 35695, -1, 35717, 35719, 35718, -1, 35718, 35720, 35721, -1, 35722, 35723, 35719, -1, 35719, 35724, 35718, -1, 35723, 35724, 35719, -1, 35718, 35724, 35720, -1, 35723, 35725, 35724, -1, 34109, 34285, 35709, -1, 34109, 35709, 35701, -1, 33714, 33715, 35695, -1, 33714, 35695, 35718, -1, 35709, 34289, 35706, -1, 34285, 34289, 35709, -1, 35706, 34293, 35703, -1, 34289, 34293, 35706, -1, 35703, 34301, 35704, -1, 34293, 34301, 35703, -1, 35704, 34308, 35702, -1, 34301, 34308, 35704, -1, 35702, 34312, 35705, -1, 34308, 34312, 35702, -1, 35705, 34319, 35707, -1, 35707, 34319, 35708, -1, 34312, 34319, 35705, -1, 34319, 33696, 35708, -1, 33765, 34193, 35717, -1, 35717, 34193, 35719, -1, 35719, 34193, 35722, -1, 35722, 34189, 35723, -1, 34193, 34189, 35722, -1, 35723, 34185, 35725, -1, 34189, 34185, 35723, -1, 35725, 34182, 35724, -1, 34185, 34182, 35725, -1, 35724, 34184, 35720, -1, 34182, 34184, 35724, -1, 35720, 34188, 35721, -1, 34184, 34188, 35720, -1, 35721, 34192, 35718, -1, 34188, 34192, 35721, -1, 34192, 33714, 35718, -1, 33696, 33689, 35710, -1, 33696, 35710, 35708, -1, 33625, 33765, 35717, -1, 33625, 35717, 35716, -1, 35710, 33689, 35713, -1, 35713, 33666, 35711, -1, 33689, 33666, 35713, -1, 35711, 33655, 35712, -1, 33666, 33655, 35711, -1, 35712, 33645, 35715, -1, 33655, 33645, 35712, -1, 35715, 33640, 35714, -1, 33645, 33640, 35715, -1, 35714, 33633, 35716, -1, 33640, 33633, 35714, -1, 33633, 33625, 35716, -1, 35726, 33717, 35727, -1, 35727, 34013, 35728, -1, 33717, 34013, 35727, -1, 35728, 34004, 35729, -1, 34013, 34004, 35728, -1, 35729, 33989, 35730, -1, 34004, 33989, 35729, -1, 33989, 33992, 35730, -1, 35730, 34009, 35731, -1, 35731, 34009, 35732, -1, 33992, 34009, 35730, -1, 34009, 34018, 35732, -1, 35733, 35734, 35735, -1, 35736, 35734, 35733, -1, 35737, 35734, 35736, -1, 35738, 35734, 35737, -1, 35739, 35734, 35738, -1, 35740, 35734, 35739, -1, 35740, 35741, 35734, -1, 35742, 35743, 35741, -1, 35744, 35743, 35742, -1, 35745, 35746, 35743, -1, 35743, 35746, 35741, -1, 35741, 35747, 35734, -1, 35746, 35747, 35741, -1, 35747, 35732, 35734, -1, 35731, 35729, 35730, -1, 35731, 35728, 35729, -1, 35732, 35727, 35731, -1, 35731, 35727, 35728, -1, 35732, 35726, 35727, -1, 35747, 35748, 35732, -1, 35732, 35748, 35726, -1, 35748, 35749, 35726, -1, 35748, 35750, 35749, -1, 35750, 35751, 35749, -1, 35750, 35752, 35751, -1, 35751, 35753, 35754, -1, 35752, 35753, 35751, -1, 35753, 35755, 35754, -1, 35732, 34225, 35734, -1, 34018, 34225, 35732, -1, 33716, 33717, 35726, -1, 33716, 35726, 35749, -1, 35734, 34230, 35735, -1, 34225, 34230, 35734, -1, 35735, 34238, 35733, -1, 34230, 34238, 35735, -1, 35733, 34243, 35736, -1, 34238, 34243, 35733, -1, 35736, 34248, 35737, -1, 34243, 34248, 35736, -1, 35737, 34251, 35738, -1, 34248, 34251, 35737, -1, 35738, 34252, 35739, -1, 35739, 34252, 35740, -1, 34251, 34252, 35738, -1, 34252, 33694, 35740, -1, 34110, 34108, 35748, -1, 35748, 34108, 35750, -1, 35750, 34106, 35752, -1, 35752, 34106, 35753, -1, 34108, 34106, 35750, -1, 35753, 34095, 35755, -1, 34106, 34095, 35753, -1, 35755, 34089, 35754, -1, 34095, 34089, 35755, -1, 35754, 34091, 35751, -1, 34089, 34091, 35754, -1, 35751, 34099, 35749, -1, 34091, 34099, 35751, -1, 34099, 33716, 35749, -1, 35740, 33695, 35741, -1, 33694, 33695, 35740, -1, 34284, 34110, 35748, -1, 34284, 35748, 35747, -1, 35741, 34318, 35742, -1, 33695, 34318, 35741, -1, 35742, 34313, 35744, -1, 34318, 34313, 35742, -1, 35744, 34309, 35743, -1, 34313, 34309, 35744, -1, 35743, 34303, 35745, -1, 34309, 34303, 35743, -1, 35745, 34296, 35746, -1, 35746, 34296, 35747, -1, 34303, 34296, 35745, -1, 34296, 34284, 35747, -1, 35756, 33720, 35757, -1, 35757, 33945, 35758, -1, 33720, 33945, 35757, -1, 35758, 33937, 35759, -1, 33945, 33937, 35758, -1, 35759, 33928, 35760, -1, 33937, 33928, 35759, -1, 35760, 33923, 35761, -1, 33928, 33923, 35760, -1, 35761, 33933, 35762, -1, 33923, 33933, 35761, -1, 35762, 33941, 35763, -1, 33933, 33941, 35762, -1, 33941, 33947, 35763, -1, 35764, 35765, 35766, -1, 35767, 35768, 35765, -1, 35765, 35768, 35766, -1, 35769, 35770, 35771, -1, 35766, 35770, 35769, -1, 35768, 35770, 35766, -1, 35768, 35772, 35770, -1, 35773, 35774, 35772, -1, 35775, 35774, 35773, -1, 35776, 35774, 35775, -1, 35777, 35774, 35776, -1, 35772, 35778, 35770, -1, 35774, 35778, 35772, -1, 35778, 35763, 35770, -1, 35763, 35761, 35762, -1, 35760, 35758, 35759, -1, 35761, 35758, 35760, -1, 35758, 35756, 35757, -1, 35763, 35756, 35761, -1, 35761, 35756, 35758, -1, 35778, 35779, 35763, -1, 35763, 35779, 35756, -1, 35779, 35780, 35756, -1, 35779, 35781, 35780, -1, 35782, 35783, 35781, -1, 35784, 35783, 35785, -1, 35780, 35783, 35784, -1, 35781, 35783, 35780, -1, 35783, 35786, 35785, -1, 33947, 34151, 35770, -1, 33947, 35770, 35763, -1, 33719, 33720, 35756, -1, 33719, 35756, 35780, -1, 35770, 34157, 35771, -1, 34151, 34157, 35770, -1, 35771, 34165, 35769, -1, 34157, 34165, 35771, -1, 35769, 34169, 35766, -1, 34165, 34169, 35769, -1, 35766, 34173, 35764, -1, 34169, 34173, 35766, -1, 35764, 34178, 35765, -1, 34173, 34178, 35764, -1, 35765, 34180, 35767, -1, 35767, 34180, 35768, -1, 34178, 34180, 35765, -1, 34180, 33692, 35768, -1, 34020, 34008, 35779, -1, 35779, 34008, 35781, -1, 35781, 34008, 35782, -1, 35782, 33991, 35783, -1, 34008, 33991, 35782, -1, 33991, 33988, 35783, -1, 35783, 33990, 35786, -1, 33988, 33990, 35783, -1, 35786, 34005, 35785, -1, 33990, 34005, 35786, -1, 35785, 34015, 35784, -1, 34005, 34015, 35785, -1, 35784, 33719, 35780, -1, 34015, 33719, 35784, -1, 33692, 33693, 35772, -1, 33692, 35772, 35768, -1, 34224, 34020, 35779, -1, 34224, 35779, 35778, -1, 35772, 34250, 35773, -1, 33693, 34250, 35772, -1, 35773, 34247, 35775, -1, 34250, 34247, 35773, -1, 35775, 34242, 35776, -1, 34247, 34242, 35775, -1, 35776, 34237, 35777, -1, 34242, 34237, 35776, -1, 35777, 34229, 35774, -1, 35774, 34229, 35778, -1, 34237, 34229, 35777, -1, 34229, 34224, 35778, -1, 35787, 33724, 35788, -1, 33721, 33724, 35787, -1, 35788, 35789, 35790, -1, 35788, 35791, 35789, -1, 35792, 35793, 35794, -1, 35792, 35795, 35793, -1, 35792, 35790, 35795, -1, 35792, 35788, 35790, -1, 35787, 35788, 35792, -1, 35796, 35797, 35787, -1, 35798, 35796, 35787, -1, 35799, 35800, 35801, -1, 35799, 35801, 35802, -1, 35799, 35802, 35798, -1, 35799, 35787, 35792, -1, 35799, 35798, 35787, -1, 35803, 35804, 35805, -1, 35806, 35804, 35803, -1, 35807, 35804, 35806, -1, 35808, 35807, 35809, -1, 35808, 35804, 35807, -1, 35810, 35804, 35808, -1, 35811, 35792, 35804, -1, 35811, 35810, 35812, -1, 35811, 35799, 35792, -1, 35811, 35804, 35810, -1, 35813, 35811, 35812, -1, 35814, 35815, 35811, -1, 35816, 35813, 35817, -1, 35816, 35811, 35813, -1, 35818, 35814, 35811, -1, 35818, 35811, 35816, -1, 35799, 33949, 35800, -1, 35800, 33943, 35801, -1, 33949, 33943, 35800, -1, 35801, 33934, 35802, -1, 33943, 33934, 35801, -1, 35802, 33922, 35798, -1, 33934, 33922, 35802, -1, 35798, 33924, 35796, -1, 33922, 33924, 35798, -1, 35796, 33930, 35797, -1, 33924, 33930, 35796, -1, 35797, 33938, 35787, -1, 33930, 33938, 35797, -1, 33938, 33721, 35787, -1, 34154, 35799, 35811, -1, 34154, 33949, 35799, -1, 33691, 34181, 35812, -1, 35812, 34181, 35813, -1, 35813, 34181, 35817, -1, 35817, 34179, 35816, -1, 34181, 34179, 35817, -1, 35816, 34175, 35818, -1, 34179, 34175, 35816, -1, 35818, 34170, 35814, -1, 34175, 34170, 35818, -1, 35814, 34164, 35815, -1, 34170, 34164, 35814, -1, 35815, 34159, 35811, -1, 34164, 34159, 35815, -1, 34159, 34154, 35811, -1, 33690, 35812, 35810, -1, 33690, 33691, 35812, -1, 34631, 34632, 35819, -1, 34631, 35819, 35820, -1, 35821, 35822, 35823, -1, 35823, 35824, 35825, -1, 35825, 35824, 35826, -1, 35826, 35824, 35827, -1, 35827, 35824, 35828, -1, 35822, 35824, 35823, -1, 35829, 35830, 35831, -1, 35831, 35832, 35822, -1, 35833, 35832, 35830, -1, 35834, 35832, 35833, -1, 35835, 35832, 35834, -1, 35836, 35832, 35835, -1, 35830, 35832, 35831, -1, 35822, 35832, 35824, -1, 35837, 35838, 35839, -1, 35840, 35819, 35837, -1, 35838, 35819, 35841, -1, 35841, 35819, 35842, -1, 35842, 35819, 35843, -1, 35837, 35819, 35838, -1, 35819, 35844, 35820, -1, 35824, 35844, 35840, -1, 35832, 35844, 35824, -1, 35840, 35844, 35819, -1, 35844, 35845, 35820, -1, 35820, 35846, 35847, -1, 35820, 35848, 35846, -1, 35849, 35850, 35845, -1, 35845, 35850, 35820, -1, 35820, 35850, 35848, -1, 34880, 34894, 35844, -1, 35844, 34894, 35845, -1, 35845, 34898, 35849, -1, 34894, 34898, 35845, -1, 35849, 34901, 35850, -1, 34898, 34901, 35849, -1, 35850, 34903, 35848, -1, 34901, 34903, 35850, -1, 35848, 34904, 35846, -1, 34903, 34904, 35848, -1, 35846, 34908, 35847, -1, 34904, 34908, 35846, -1, 35847, 34631, 35820, -1, 34908, 34631, 35847, -1, 34561, 34880, 35844, -1, 34561, 35844, 35832, -1, 34550, 34540, 35831, -1, 35831, 34540, 35829, -1, 35829, 34528, 35830, -1, 34540, 34528, 35829, -1, 35830, 34521, 35833, -1, 34528, 34521, 35830, -1, 35833, 34525, 35834, -1, 34521, 34525, 35833, -1, 35834, 34535, 35835, -1, 34525, 34535, 35834, -1, 35835, 34545, 35836, -1, 34535, 34545, 35835, -1, 35836, 34561, 35832, -1, 34545, 34561, 35836, -1, 34593, 35831, 35822, -1, 34593, 34550, 35831, -1, 34743, 33585, 35851, -1, 35851, 35852, 35853, -1, 33585, 35852, 35851, -1, 35853, 35854, 35855, -1, 35852, 35854, 35853, -1, 35855, 35856, 35857, -1, 35854, 35856, 35855, -1, 35858, 35859, 35860, -1, 35860, 35861, 35858, -1, 35858, 35862, 35859, -1, 35861, 35863, 35858, -1, 35858, 35864, 35862, -1, 35863, 35865, 35858, -1, 35858, 35866, 35864, -1, 35858, 35867, 35866, -1, 35858, 35868, 35867, -1, 35858, 35869, 35868, -1, 35865, 35870, 35858, -1, 35870, 35871, 35858, -1, 35872, 35873, 35874, -1, 35872, 35875, 35873, -1, 35874, 35876, 35877, -1, 35873, 35876, 35874, -1, 35872, 35878, 35875, -1, 35879, 35880, 35881, -1, 35877, 35880, 35879, -1, 35876, 35880, 35877, -1, 35872, 35882, 35878, -1, 35881, 35883, 35871, -1, 35871, 35883, 35858, -1, 35880, 35883, 35881, -1, 35872, 35884, 35882, -1, 35872, 35885, 35884, -1, 35872, 35886, 35885, -1, 35872, 35887, 35886, -1, 35883, 35888, 35858, -1, 35889, 35890, 35891, -1, 35889, 35892, 35890, -1, 35891, 35893, 35894, -1, 35890, 35893, 35891, -1, 35889, 35895, 35892, -1, 35896, 35897, 35898, -1, 35894, 35897, 35896, -1, 35893, 35897, 35894, -1, 35889, 35899, 35895, -1, 35897, 35900, 35898, -1, 35898, 35900, 35901, -1, 35889, 35902, 35899, -1, 35889, 35903, 35902, -1, 35904, 35905, 35906, -1, 35904, 35907, 35905, -1, 35908, 35907, 35904, -1, 35905, 35909, 35906, -1, 35906, 35909, 35910, -1, 35908, 35911, 35907, -1, 35909, 35912, 35910, -1, 35910, 35912, 35913, -1, 35908, 35914, 35911, -1, 35915, 35914, 35908, -1, 35915, 35916, 35914, -1, 35915, 35917, 35916, -1, 35918, 35919, 35912, -1, 35900, 35919, 35901, -1, 35901, 35919, 35888, -1, 35912, 35919, 35913, -1, 35920, 35919, 35900, -1, 35913, 35919, 35921, -1, 35921, 35919, 35922, -1, 35922, 35919, 35920, -1, 35888, 35919, 35858, -1, 35918, 35923, 35919, -1, 35923, 35924, 35919, -1, 35924, 35925, 35919, -1, 35925, 35926, 35919, -1, 35926, 35927, 35919, -1, 35927, 35928, 35919, -1, 35919, 35929, 35930, -1, 35928, 35929, 35919, -1, 35889, 35931, 35903, -1, 35930, 35932, 35856, -1, 35929, 35932, 35930, -1, 35931, 35933, 35903, -1, 35934, 35933, 35931, -1, 35934, 35935, 35933, -1, 35936, 35937, 35938, -1, 35934, 35939, 35935, -1, 35932, 35940, 35856, -1, 35938, 35941, 35934, -1, 35937, 35941, 35938, -1, 35934, 35941, 35939, -1, 35937, 35942, 35941, -1, 35941, 35942, 35943, -1, 35944, 35942, 35945, -1, 35945, 35942, 35937, -1, 35946, 35947, 35948, -1, 35948, 35947, 35949, -1, 35949, 35947, 35950, -1, 35950, 35947, 35951, -1, 35951, 35947, 35952, -1, 35952, 35947, 35953, -1, 35954, 35955, 35947, -1, 35956, 35957, 35958, -1, 35958, 35957, 35959, -1, 35959, 35957, 35960, -1, 35960, 35957, 35961, -1, 35947, 35957, 35953, -1, 35953, 35957, 35956, -1, 35947, 35962, 35957, -1, 35963, 35964, 35955, -1, 35955, 35965, 35947, -1, 35964, 35965, 35955, -1, 35962, 35966, 35967, -1, 35966, 35968, 35969, -1, 35970, 35968, 35965, -1, 35947, 35968, 35962, -1, 35962, 35968, 35966, -1, 35965, 35968, 35947, -1, 35971, 35972, 35973, -1, 35973, 35972, 35974, -1, 35974, 35972, 35975, -1, 35975, 35972, 35976, -1, 35976, 35972, 35977, -1, 35977, 35972, 35978, -1, 35978, 35972, 35979, -1, 35979, 35980, 35981, -1, 35972, 35980, 35979, -1, 35981, 35857, 35982, -1, 35982, 35857, 35983, -1, 35983, 35857, 35984, -1, 35980, 35857, 35981, -1, 35872, 35947, 35946, -1, 35872, 35946, 35887, -1, 35957, 35917, 35961, -1, 35961, 35917, 35915, -1, 35940, 35984, 35856, -1, 35857, 35856, 35984, -1, 35858, 35972, 35869, -1, 35869, 35972, 35971, -1, 35985, 35957, 35962, -1, 35986, 35962, 35967, -1, 35986, 35985, 35962, -1, 35987, 35967, 35966, -1, 35987, 35986, 35967, -1, 35988, 35966, 35969, -1, 35988, 35987, 35966, -1, 35989, 35969, 35968, -1, 35989, 35988, 35969, -1, 35990, 35968, 35970, -1, 35990, 35989, 35968, -1, 35991, 35970, 35965, -1, 35991, 35990, 35970, -1, 35992, 35965, 35964, -1, 35992, 35991, 35965, -1, 35993, 35964, 35963, -1, 35993, 35992, 35964, -1, 35994, 35993, 35963, -1, 35995, 35879, 35996, -1, 35996, 35881, 35997, -1, 35879, 35881, 35996, -1, 35997, 35871, 35998, -1, 35881, 35871, 35997, -1, 35871, 35870, 35998, -1, 35926, 35925, 35999, -1, 35999, 35925, 36000, -1, 36000, 35924, 36001, -1, 36001, 35924, 36002, -1, 35925, 35924, 36000, -1, 35924, 35923, 36002, -1, 36003, 35933, 35935, -1, 36003, 36004, 35933, -1, 36005, 35935, 35939, -1, 36005, 36003, 35935, -1, 36006, 35939, 35941, -1, 36006, 36005, 35939, -1, 36007, 35941, 35943, -1, 36007, 36006, 35941, -1, 36008, 35943, 35942, -1, 36008, 36007, 35943, -1, 36009, 35942, 35944, -1, 36009, 36008, 35942, -1, 36010, 35944, 35945, -1, 36010, 36009, 35944, -1, 36011, 35945, 35937, -1, 36011, 36010, 35945, -1, 36012, 35937, 35936, -1, 36012, 36011, 35937, -1, 35896, 35898, 36013, -1, 36013, 35898, 36014, -1, 36014, 35901, 36015, -1, 36015, 35901, 36016, -1, 35898, 35901, 36014, -1, 35901, 35888, 36016, -1, 36017, 35913, 36018, -1, 36018, 35921, 36019, -1, 35913, 35921, 36018, -1, 36019, 35922, 36020, -1, 35921, 35922, 36019, -1, 35922, 35920, 36020, -1, 36008, 36009, 36021, -1, 36010, 36021, 36009, -1, 36007, 36008, 36021, -1, 36011, 36021, 36010, -1, 36006, 36007, 36021, -1, 36012, 36021, 36011, -1, 36005, 36006, 36021, -1, 36022, 36021, 36012, -1, 36003, 36005, 36021, -1, 36023, 36021, 36022, -1, 36024, 36021, 36023, -1, 36025, 36004, 36003, -1, 36025, 36003, 36021, -1, 36018, 36026, 36017, -1, 36020, 36025, 36027, -1, 36020, 36027, 36028, -1, 36020, 36028, 36029, -1, 36020, 36029, 36026, -1, 36020, 36018, 36019, -1, 36020, 36026, 36018, -1, 36030, 36004, 36025, -1, 36030, 36025, 36020, -1, 36031, 36032, 36033, -1, 36014, 36031, 36013, -1, 36014, 36032, 36031, -1, 36015, 36032, 36014, -1, 36016, 36032, 36015, -1, 36034, 36024, 36032, -1, 36034, 36032, 36016, -1, 36034, 36021, 36024, -1, 35990, 35991, 36035, -1, 35992, 36035, 35991, -1, 35989, 35990, 36035, -1, 35993, 36035, 35992, -1, 35988, 35989, 36035, -1, 35994, 36035, 35993, -1, 35987, 35988, 36035, -1, 36036, 36035, 35994, -1, 35986, 35987, 36035, -1, 36037, 36035, 36036, -1, 35985, 35986, 36035, -1, 36038, 36035, 36037, -1, 36039, 36040, 36041, -1, 36042, 36040, 36039, -1, 36043, 36040, 36042, -1, 36000, 36043, 35999, -1, 36000, 36040, 36043, -1, 36001, 36040, 36000, -1, 36002, 36040, 36001, -1, 36044, 36040, 36002, -1, 36045, 36046, 36047, -1, 35996, 36045, 35995, -1, 35998, 35996, 35997, -1, 35998, 36045, 35996, -1, 35998, 36046, 36045, -1, 36048, 36038, 36046, -1, 36048, 36046, 35998, -1, 36044, 35985, 36040, -1, 36048, 36035, 36038, -1, 36035, 36040, 35985, -1, 35887, 35946, 36034, -1, 36034, 35946, 36021, -1, 36049, 36050, 36021, -1, 36050, 36051, 36021, -1, 35948, 36052, 35946, -1, 35949, 36052, 35948, -1, 35950, 36052, 35949, -1, 35946, 36052, 36021, -1, 36021, 36052, 36049, -1, 36051, 36053, 36021, -1, 35951, 36054, 35950, -1, 35952, 36054, 35951, -1, 36052, 36054, 36049, -1, 36049, 36054, 36050, -1, 35950, 36054, 36052, -1, 36021, 36055, 35961, -1, 36053, 36055, 36021, -1, 35953, 36056, 35952, -1, 35952, 36056, 36054, -1, 36054, 36056, 36050, -1, 36050, 36056, 36051, -1, 35956, 36057, 35953, -1, 35958, 36057, 35956, -1, 35953, 36057, 36056, -1, 36051, 36057, 36053, -1, 36056, 36057, 36051, -1, 35959, 36058, 35958, -1, 35960, 36058, 35959, -1, 35961, 36058, 35960, -1, 35958, 36058, 36057, -1, 36055, 36058, 35961, -1, 36053, 36058, 36055, -1, 36057, 36058, 36053, -1, 36059, 36060, 36034, -1, 36060, 36061, 36034, -1, 35883, 36062, 36034, -1, 35880, 36062, 35883, -1, 35876, 36062, 35880, -1, 35873, 36062, 35876, -1, 36034, 36062, 36059, -1, 36034, 36063, 35887, -1, 36061, 36063, 36034, -1, 35875, 36064, 35873, -1, 35878, 36064, 35875, -1, 36059, 36064, 36060, -1, 35873, 36064, 36062, -1, 36062, 36064, 36059, -1, 35882, 36065, 35878, -1, 35884, 36065, 35882, -1, 36064, 36065, 36060, -1, 36060, 36065, 36061, -1, 35878, 36065, 36064, -1, 35885, 36066, 35884, -1, 35886, 36066, 35885, -1, 35887, 36066, 35886, -1, 36063, 36066, 35887, -1, 36061, 36066, 36063, -1, 35884, 36066, 36065, -1, 36065, 36066, 36061, -1, 35961, 35915, 36021, -1, 36021, 35915, 36025, -1, 35888, 36034, 36016, -1, 35888, 35883, 36034, -1, 35915, 35908, 36025, -1, 36025, 35908, 36027, -1, 36027, 35904, 36028, -1, 35908, 35904, 36027, -1, 36028, 35906, 36029, -1, 35904, 35906, 36028, -1, 36029, 35910, 36026, -1, 35906, 35910, 36029, -1, 36026, 35913, 36017, -1, 35910, 35913, 36026, -1, 36032, 35889, 36033, -1, 35889, 35891, 36033, -1, 36033, 35894, 36031, -1, 35891, 35894, 36033, -1, 36031, 35896, 36013, -1, 35894, 35896, 36031, -1, 35920, 36030, 36020, -1, 35920, 35900, 36030, -1, 36024, 35889, 36032, -1, 35931, 35889, 36024, -1, 35900, 36067, 36030, -1, 36067, 36068, 36030, -1, 35897, 36069, 35900, -1, 35893, 36069, 35897, -1, 35890, 36069, 35893, -1, 35900, 36069, 36067, -1, 36030, 36070, 35903, -1, 36068, 36070, 36030, -1, 35892, 36071, 35890, -1, 35895, 36071, 35892, -1, 36069, 36071, 36067, -1, 35890, 36071, 36069, -1, 36067, 36071, 36068, -1, 35899, 36072, 35895, -1, 35902, 36072, 35899, -1, 35903, 36072, 35902, -1, 36071, 36072, 36068, -1, 35895, 36072, 36071, -1, 36068, 36072, 36070, -1, 36070, 36072, 35903, -1, 36022, 36012, 35936, -1, 36022, 35936, 35938, -1, 36022, 35938, 35934, -1, 36023, 35934, 35931, -1, 36023, 36022, 35934, -1, 36024, 36023, 35931, -1, 35903, 36004, 36030, -1, 35903, 35933, 36004, -1, 35869, 36035, 36048, -1, 35869, 35971, 36035, -1, 35971, 36073, 36035, -1, 36073, 36074, 36035, -1, 36074, 36075, 36035, -1, 35973, 36076, 35971, -1, 35974, 36076, 35973, -1, 35975, 36076, 35974, -1, 35971, 36076, 36073, -1, 36075, 36077, 36035, -1, 35976, 36078, 35975, -1, 35977, 36078, 35976, -1, 36076, 36078, 36073, -1, 36073, 36078, 36074, -1, 35975, 36078, 36076, -1, 36035, 36079, 35984, -1, 36077, 36079, 36035, -1, 35978, 36080, 35977, -1, 35977, 36080, 36078, -1, 36078, 36080, 36074, -1, 36074, 36080, 36075, -1, 35979, 36081, 35978, -1, 35981, 36081, 35979, -1, 35978, 36081, 36080, -1, 36075, 36081, 36077, -1, 36080, 36081, 36075, -1, 35982, 36082, 35981, -1, 35983, 36082, 35982, -1, 35984, 36082, 35983, -1, 35981, 36082, 36081, -1, 36079, 36082, 35984, -1, 36077, 36082, 36079, -1, 36081, 36082, 36077, -1, 36083, 36084, 36048, -1, 36084, 36085, 36048, -1, 35865, 36086, 36048, -1, 35863, 36086, 35865, -1, 35861, 36086, 35863, -1, 35860, 36086, 35861, -1, 36048, 36086, 36083, -1, 36048, 36087, 35869, -1, 36085, 36087, 36048, -1, 35859, 36088, 35860, -1, 35862, 36088, 35859, -1, 36083, 36088, 36084, -1, 35860, 36088, 36086, -1, 36086, 36088, 36083, -1, 35864, 36089, 35862, -1, 35866, 36089, 35864, -1, 36088, 36089, 36084, -1, 36084, 36089, 36085, -1, 35862, 36089, 36088, -1, 35867, 36090, 35866, -1, 35868, 36090, 35867, -1, 35869, 36090, 35868, -1, 36087, 36090, 35869, -1, 36085, 36090, 36087, -1, 35866, 36090, 36089, -1, 36089, 36090, 36085, -1, 35984, 36040, 36035, -1, 35984, 35940, 36040, -1, 35870, 36048, 35998, -1, 35870, 35865, 36048, -1, 35940, 35932, 36040, -1, 36040, 35932, 36041, -1, 36041, 35932, 36039, -1, 36039, 35929, 36042, -1, 35932, 35929, 36039, -1, 36042, 35928, 36043, -1, 35929, 35928, 36042, -1, 36043, 35927, 35999, -1, 35928, 35927, 36043, -1, 35927, 35926, 35999, -1, 36046, 35872, 36047, -1, 35872, 35874, 36047, -1, 36047, 35877, 36045, -1, 35874, 35877, 36047, -1, 36045, 35879, 35995, -1, 35877, 35879, 36045, -1, 35923, 36044, 36002, -1, 35923, 35918, 36044, -1, 36038, 35872, 36046, -1, 35947, 35872, 36038, -1, 35918, 36091, 36044, -1, 36091, 36092, 36044, -1, 35912, 36093, 35918, -1, 35909, 36093, 35912, -1, 35905, 36093, 35909, -1, 35918, 36093, 36091, -1, 36044, 36094, 35917, -1, 36092, 36094, 36044, -1, 35907, 36095, 35905, -1, 35911, 36095, 35907, -1, 36093, 36095, 36091, -1, 35905, 36095, 36093, -1, 36091, 36095, 36092, -1, 35914, 36096, 35911, -1, 35916, 36096, 35914, -1, 35917, 36096, 35916, -1, 36095, 36096, 36092, -1, 35911, 36096, 36095, -1, 36094, 36096, 35917, -1, 36092, 36096, 36094, -1, 36036, 35994, 35963, -1, 36036, 35963, 35955, -1, 36036, 35955, 35954, -1, 36037, 35954, 35947, -1, 36037, 36036, 35954, -1, 36038, 36037, 35947, -1, 35917, 35985, 36044, -1, 35917, 35957, 35985, -1, 35972, 35858, 36097, -1, 36098, 36099, 36100, -1, 36097, 36099, 36098, -1, 35858, 36099, 36097, -1, 36100, 36101, 36102, -1, 36099, 36101, 36100, -1, 36102, 36103, 36104, -1, 36101, 36103, 36102, -1, 36103, 36105, 36104, -1, 36104, 36106, 36107, -1, 36105, 36106, 36104, -1, 36106, 33577, 36107, -1, 33577, 33576, 36107, -1, 36108, 36109, 36110, -1, 36110, 36109, 36111, -1, 36111, 36109, 36112, -1, 36112, 36109, 36113, -1, 36113, 36109, 36114, -1, 36115, 36116, 36117, -1, 36118, 36109, 36108, -1, 36117, 36119, 36115, -1, 36120, 36109, 36118, -1, 36114, 36107, 36121, -1, 36121, 36107, 36122, -1, 36116, 36123, 36117, -1, 36109, 36107, 36114, -1, 36107, 33576, 36124, -1, 36107, 36124, 36122, -1, 36117, 36125, 36126, -1, 36126, 36125, 36127, -1, 36117, 36128, 36119, -1, 36123, 36129, 36117, -1, 36117, 36126, 36128, -1, 36129, 36130, 36117, -1, 36130, 36131, 36117, -1, 36132, 33576, 36131, -1, 36131, 33576, 36117, -1, 36132, 36133, 33576, -1, 36133, 36134, 33576, -1, 36134, 36135, 33576, -1, 36135, 36136, 33576, -1, 36136, 36137, 33576, -1, 36137, 36124, 33576, -1, 36127, 36125, 36138, -1, 36138, 36125, 36139, -1, 36139, 36120, 36140, -1, 36140, 36120, 36141, -1, 36141, 36120, 36142, -1, 36125, 36120, 36139, -1, 36120, 36143, 36142, -1, 36120, 36118, 36143, -1, 36144, 36127, 36145, -1, 36126, 36127, 36144, -1, 36146, 36147, 36148, -1, 36149, 36147, 36146, -1, 36150, 36147, 36149, -1, 36151, 36147, 36150, -1, 36151, 36152, 36147, -1, 36152, 36153, 36147, -1, 36152, 36154, 36153, -1, 36155, 36156, 36157, -1, 36158, 36159, 36156, -1, 36160, 36159, 36158, -1, 36156, 36159, 36157, -1, 36157, 36144, 36154, -1, 36154, 36144, 36153, -1, 36159, 36144, 36157, -1, 36144, 36161, 36153, -1, 36161, 36162, 36163, -1, 36161, 36164, 36162, -1, 36165, 36166, 36167, -1, 36168, 36166, 36165, -1, 36164, 36166, 36168, -1, 36161, 36166, 36164, -1, 36144, 36145, 36161, -1, 36161, 36145, 36166, -1, 36145, 36169, 36166, -1, 36145, 36170, 36169, -1, 36170, 36171, 36169, -1, 36170, 36172, 36171, -1, 36173, 36174, 36170, -1, 36175, 36174, 36173, -1, 36170, 36174, 36172, -1, 36145, 36138, 36170, -1, 36170, 36138, 36173, -1, 36127, 36138, 36145, -1, 36173, 36139, 36175, -1, 36138, 36139, 36173, -1, 36175, 36140, 36174, -1, 36139, 36140, 36175, -1, 36174, 36141, 36172, -1, 36140, 36141, 36174, -1, 36172, 36142, 36171, -1, 36141, 36142, 36172, -1, 36171, 36143, 36169, -1, 36142, 36143, 36171, -1, 36143, 36118, 36169, -1, 36154, 36130, 36157, -1, 36157, 36129, 36155, -1, 36130, 36129, 36157, -1, 36155, 36123, 36156, -1, 36129, 36123, 36155, -1, 36156, 36116, 36158, -1, 36123, 36116, 36156, -1, 36158, 36115, 36160, -1, 36116, 36115, 36158, -1, 36160, 36119, 36159, -1, 36115, 36119, 36160, -1, 36159, 36128, 36144, -1, 36119, 36128, 36159, -1, 36128, 36126, 36144, -1, 36169, 36108, 36166, -1, 36118, 36108, 36169, -1, 36152, 36130, 36154, -1, 36131, 36130, 36152, -1, 36166, 36110, 36167, -1, 36108, 36110, 36166, -1, 36167, 36111, 36165, -1, 36110, 36111, 36167, -1, 36165, 36112, 36168, -1, 36111, 36112, 36165, -1, 36168, 36113, 36164, -1, 36112, 36113, 36168, -1, 36164, 36114, 36162, -1, 36113, 36114, 36164, -1, 36162, 36121, 36163, -1, 36114, 36121, 36162, -1, 36163, 36122, 36161, -1, 36121, 36122, 36163, -1, 36153, 36124, 36147, -1, 36147, 36137, 36148, -1, 36124, 36137, 36147, -1, 36148, 36136, 36146, -1, 36137, 36136, 36148, -1, 36146, 36135, 36149, -1, 36136, 36135, 36146, -1, 36149, 36134, 36150, -1, 36135, 36134, 36149, -1, 36150, 36133, 36151, -1, 36134, 36133, 36150, -1, 36151, 36132, 36152, -1, 36133, 36132, 36151, -1, 36132, 36131, 36152, -1, 36122, 36124, 36153, -1, 36122, 36153, 36161, -1, 36176, 36177, 36178, -1, 36178, 36179, 36180, -1, 36177, 36179, 36178, -1, 36180, 36181, 36182, -1, 36179, 36181, 36180, -1, 36182, 33596, 36183, -1, 36183, 33596, 33648, -1, 36181, 33596, 36182, -1, 36184, 36185, 36186, -1, 36186, 36185, 36187, -1, 36187, 36185, 36188, -1, 36188, 36185, 36189, -1, 36190, 36191, 36192, -1, 36193, 36194, 36195, -1, 36195, 36194, 36196, -1, 36197, 36198, 36177, -1, 36192, 36199, 36190, -1, 36177, 36176, 36197, -1, 36200, 36185, 36201, -1, 36200, 36201, 36202, -1, 36177, 36203, 36204, -1, 36204, 36203, 36205, -1, 36204, 36206, 36207, -1, 36205, 36206, 36204, -1, 36177, 36198, 36203, -1, 36206, 36208, 36207, -1, 36208, 36209, 36207, -1, 36209, 36210, 36207, -1, 36210, 36211, 36207, -1, 36212, 36213, 36214, -1, 36215, 36216, 36212, -1, 36212, 36216, 36213, -1, 36214, 36217, 36218, -1, 36218, 36217, 36211, -1, 36213, 36217, 36214, -1, 36190, 36199, 36219, -1, 36219, 36199, 36220, -1, 36220, 36199, 36215, -1, 36215, 36199, 36216, -1, 36211, 36221, 36207, -1, 36217, 36221, 36211, -1, 36221, 36222, 36207, -1, 36222, 36223, 36207, -1, 36224, 36225, 36226, -1, 36227, 36228, 36225, -1, 36225, 36228, 36226, -1, 36228, 36229, 36226, -1, 36230, 36229, 36231, -1, 36231, 36229, 36228, -1, 36229, 36232, 36226, -1, 36226, 36232, 36233, -1, 36232, 36234, 36233, -1, 36235, 36234, 36236, -1, 36233, 36234, 36235, -1, 36234, 36237, 36236, -1, 36236, 36237, 36238, -1, 36238, 36237, 36239, -1, 36239, 36237, 36240, -1, 36240, 36237, 36241, -1, 36241, 36237, 36242, -1, 36237, 36243, 36242, -1, 36242, 36243, 36244, -1, 36243, 36245, 36244, -1, 36244, 36245, 36246, -1, 36245, 36247, 36246, -1, 36246, 36247, 36223, -1, 36247, 36248, 36223, -1, 36223, 36248, 36207, -1, 36192, 36191, 36249, -1, 36249, 36191, 36250, -1, 36250, 36191, 36251, -1, 36251, 36191, 36252, -1, 36252, 36191, 36253, -1, 36253, 36191, 36254, -1, 36255, 36193, 36256, -1, 36256, 36193, 36257, -1, 36257, 36193, 36258, -1, 36258, 36193, 36259, -1, 36259, 36193, 36260, -1, 36260, 36193, 36261, -1, 36261, 36193, 36262, -1, 36262, 36193, 36263, -1, 36263, 36193, 36264, -1, 36264, 36193, 36191, -1, 36265, 36193, 36266, -1, 36266, 36193, 36267, -1, 36267, 36193, 36195, -1, 36254, 36193, 36268, -1, 36268, 36193, 36269, -1, 36269, 36193, 36265, -1, 36191, 36193, 36254, -1, 36196, 36194, 36270, -1, 36270, 36194, 36271, -1, 36271, 36194, 36272, -1, 36272, 36194, 36273, -1, 36273, 36194, 36274, -1, 36274, 36194, 36275, -1, 36275, 36194, 36276, -1, 36276, 36277, 36278, -1, 36194, 36277, 36276, -1, 36278, 36279, 36280, -1, 36277, 36279, 36278, -1, 36279, 36281, 36280, -1, 36280, 36281, 36282, -1, 36281, 36283, 36282, -1, 36197, 36176, 36284, -1, 36284, 36176, 36285, -1, 36285, 36176, 36286, -1, 36176, 36287, 36286, -1, 36287, 36200, 36286, -1, 36288, 36200, 36289, -1, 36289, 36200, 36290, -1, 36290, 36200, 36202, -1, 36286, 36200, 36291, -1, 36291, 36200, 36292, -1, 36292, 36200, 36293, -1, 36293, 36200, 36294, -1, 36294, 36200, 36295, -1, 36295, 36200, 36288, -1, 36282, 36185, 36248, -1, 36283, 36185, 36282, -1, 36189, 36185, 36283, -1, 36201, 36185, 36296, -1, 36296, 36185, 36297, -1, 36297, 36185, 36298, -1, 36298, 36185, 36299, -1, 36248, 36185, 36207, -1, 36299, 36185, 36300, -1, 36300, 36185, 36184, -1, 36288, 36289, 36301, -1, 36289, 36290, 36301, -1, 36290, 36202, 36301, -1, 36265, 36266, 36302, -1, 36266, 36267, 36302, -1, 36267, 36195, 36302, -1, 36237, 36234, 36303, -1, 36303, 36234, 36304, -1, 36305, 36306, 36307, -1, 36305, 36307, 36308, -1, 36305, 36308, 36309, -1, 36305, 36309, 36310, -1, 36311, 36305, 36310, -1, 36312, 36311, 36310, -1, 36302, 36313, 36314, -1, 36302, 36314, 36315, -1, 36302, 36315, 36312, -1, 36302, 36312, 36310, -1, 36316, 36313, 36302, -1, 36317, 36316, 36302, -1, 36318, 36317, 36302, -1, 36319, 36318, 36302, -1, 36320, 36319, 36302, -1, 36321, 36320, 36302, -1, 36322, 36321, 36302, -1, 36304, 36322, 36302, -1, 36323, 36324, 36303, -1, 36325, 36326, 36323, -1, 36325, 36323, 36303, -1, 36327, 36303, 36304, -1, 36327, 36325, 36303, -1, 36302, 36327, 36304, -1, 36304, 36234, 36232, -1, 36322, 36232, 36229, -1, 36322, 36304, 36232, -1, 36321, 36229, 36230, -1, 36321, 36322, 36229, -1, 36320, 36230, 36231, -1, 36320, 36321, 36230, -1, 36319, 36231, 36228, -1, 36319, 36320, 36231, -1, 36318, 36228, 36227, -1, 36318, 36319, 36228, -1, 36317, 36227, 36225, -1, 36317, 36318, 36227, -1, 36316, 36225, 36224, -1, 36316, 36317, 36225, -1, 36313, 36224, 36226, -1, 36313, 36316, 36224, -1, 36314, 36226, 36233, -1, 36314, 36313, 36226, -1, 36315, 36233, 36235, -1, 36315, 36314, 36233, -1, 36312, 36315, 36235, -1, 36248, 36247, 36325, -1, 36325, 36247, 36326, -1, 36326, 36247, 36323, -1, 36247, 36245, 36323, -1, 36323, 36243, 36324, -1, 36245, 36243, 36323, -1, 36324, 36237, 36303, -1, 36243, 36237, 36324, -1, 36235, 36236, 36312, -1, 36312, 36236, 36311, -1, 36327, 36248, 36325, -1, 36282, 36248, 36327, -1, 36236, 36328, 36311, -1, 36328, 36329, 36311, -1, 36238, 36330, 36236, -1, 36239, 36330, 36238, -1, 36240, 36330, 36239, -1, 36236, 36330, 36328, -1, 36311, 36331, 36223, -1, 36329, 36331, 36311, -1, 36241, 36332, 36240, -1, 36242, 36332, 36241, -1, 36240, 36332, 36330, -1, 36328, 36332, 36329, -1, 36330, 36332, 36328, -1, 36244, 36333, 36242, -1, 36246, 36333, 36244, -1, 36223, 36333, 36246, -1, 36242, 36333, 36332, -1, 36329, 36333, 36331, -1, 36332, 36333, 36329, -1, 36331, 36333, 36223, -1, 36334, 36335, 36327, -1, 36196, 36336, 36327, -1, 36270, 36336, 36196, -1, 36271, 36336, 36270, -1, 36272, 36336, 36271, -1, 36327, 36336, 36334, -1, 36335, 36337, 36327, -1, 36273, 36338, 36272, -1, 36274, 36338, 36273, -1, 36272, 36338, 36336, -1, 36336, 36338, 36334, -1, 36334, 36338, 36335, -1, 36337, 36339, 36327, -1, 36275, 36340, 36274, -1, 36276, 36340, 36275, -1, 36335, 36340, 36337, -1, 36338, 36340, 36335, -1, 36274, 36340, 36338, -1, 36327, 36341, 36282, -1, 36278, 36341, 36276, -1, 36280, 36341, 36278, -1, 36282, 36341, 36280, -1, 36276, 36341, 36340, -1, 36337, 36341, 36339, -1, 36339, 36341, 36327, -1, 36340, 36341, 36337, -1, 36223, 36305, 36311, -1, 36223, 36222, 36305, -1, 36302, 36196, 36327, -1, 36195, 36196, 36302, -1, 36305, 36222, 36306, -1, 36306, 36221, 36307, -1, 36222, 36221, 36306, -1, 36307, 36217, 36308, -1, 36221, 36217, 36307, -1, 36308, 36213, 36309, -1, 36217, 36213, 36308, -1, 36213, 36216, 36309, -1, 36309, 36199, 36310, -1, 36216, 36199, 36309, -1, 36342, 36343, 36302, -1, 36343, 36344, 36302, -1, 36249, 36345, 36192, -1, 36250, 36345, 36249, -1, 36251, 36345, 36250, -1, 36192, 36345, 36302, -1, 36302, 36345, 36342, -1, 36344, 36346, 36302, -1, 36252, 36347, 36251, -1, 36345, 36347, 36342, -1, 36342, 36347, 36343, -1, 36251, 36347, 36345, -1, 36253, 36348, 36252, -1, 36254, 36348, 36253, -1, 36252, 36348, 36347, -1, 36347, 36348, 36343, -1, 36343, 36348, 36344, -1, 36268, 36349, 36254, -1, 36269, 36349, 36268, -1, 36265, 36349, 36269, -1, 36302, 36349, 36265, -1, 36254, 36349, 36348, -1, 36346, 36349, 36302, -1, 36344, 36349, 36346, -1, 36348, 36349, 36344, -1, 36199, 36302, 36310, -1, 36199, 36192, 36302, -1, 36198, 36197, 36350, -1, 36350, 36197, 36301, -1, 36351, 36352, 36353, -1, 36354, 36351, 36353, -1, 36355, 36353, 36350, -1, 36355, 36354, 36353, -1, 36356, 36355, 36350, -1, 36301, 36357, 36358, -1, 36301, 36358, 36359, -1, 36360, 36357, 36301, -1, 36361, 36360, 36301, -1, 36362, 36361, 36301, -1, 36363, 36362, 36301, -1, 36364, 36363, 36301, -1, 36365, 36364, 36301, -1, 36366, 36365, 36301, -1, 36367, 36366, 36301, -1, 36368, 36367, 36301, -1, 36369, 36370, 36371, -1, 36372, 36373, 36369, -1, 36372, 36369, 36371, -1, 36374, 36371, 36368, -1, 36374, 36372, 36371, -1, 36359, 36356, 36350, -1, 36350, 36301, 36359, -1, 36301, 36374, 36368, -1, 36375, 36376, 36301, -1, 36376, 36377, 36301, -1, 36284, 36378, 36197, -1, 36285, 36378, 36284, -1, 36286, 36378, 36285, -1, 36197, 36378, 36301, -1, 36301, 36378, 36375, -1, 36301, 36379, 36288, -1, 36377, 36379, 36301, -1, 36291, 36380, 36286, -1, 36378, 36380, 36375, -1, 36375, 36380, 36376, -1, 36286, 36380, 36378, -1, 36292, 36381, 36291, -1, 36293, 36381, 36292, -1, 36291, 36381, 36380, -1, 36380, 36381, 36376, -1, 36376, 36381, 36377, -1, 36294, 36382, 36293, -1, 36295, 36382, 36294, -1, 36288, 36382, 36295, -1, 36293, 36382, 36381, -1, 36377, 36382, 36379, -1, 36379, 36382, 36288, -1, 36381, 36382, 36377, -1, 36355, 36209, 36354, -1, 36209, 36208, 36354, -1, 36354, 36206, 36351, -1, 36208, 36206, 36354, -1, 36351, 36205, 36352, -1, 36206, 36205, 36351, -1, 36352, 36203, 36353, -1, 36205, 36203, 36352, -1, 36353, 36198, 36350, -1, 36203, 36198, 36353, -1, 36202, 36201, 36301, -1, 36301, 36201, 36374, -1, 36210, 36355, 36356, -1, 36210, 36209, 36355, -1, 36201, 36383, 36374, -1, 36383, 36384, 36374, -1, 36296, 36385, 36201, -1, 36297, 36385, 36296, -1, 36298, 36385, 36297, -1, 36201, 36385, 36383, -1, 36384, 36386, 36374, -1, 36299, 36387, 36298, -1, 36300, 36387, 36299, -1, 36298, 36387, 36385, -1, 36383, 36387, 36384, -1, 36385, 36387, 36383, -1, 36386, 36388, 36374, -1, 36184, 36389, 36300, -1, 36186, 36389, 36184, -1, 36384, 36389, 36386, -1, 36387, 36389, 36384, -1, 36300, 36389, 36387, -1, 36374, 36390, 36189, -1, 36187, 36390, 36186, -1, 36188, 36390, 36187, -1, 36189, 36390, 36188, -1, 36386, 36390, 36388, -1, 36186, 36390, 36389, -1, 36388, 36390, 36374, -1, 36389, 36390, 36386, -1, 36190, 36391, 36356, -1, 36391, 36392, 36356, -1, 36219, 36393, 36190, -1, 36220, 36393, 36219, -1, 36215, 36393, 36220, -1, 36190, 36393, 36391, -1, 36356, 36394, 36210, -1, 36392, 36394, 36356, -1, 36212, 36395, 36215, -1, 36214, 36395, 36212, -1, 36215, 36395, 36393, -1, 36391, 36395, 36392, -1, 36393, 36395, 36391, -1, 36218, 36396, 36214, -1, 36211, 36396, 36218, -1, 36210, 36396, 36211, -1, 36214, 36396, 36395, -1, 36392, 36396, 36394, -1, 36395, 36396, 36392, -1, 36394, 36396, 36210, -1, 36189, 36283, 36374, -1, 36374, 36283, 36372, -1, 36359, 36190, 36356, -1, 36191, 36190, 36359, -1, 36372, 36281, 36373, -1, 36283, 36281, 36372, -1, 36373, 36279, 36369, -1, 36281, 36279, 36373, -1, 36369, 36277, 36370, -1, 36370, 36277, 36371, -1, 36279, 36277, 36369, -1, 36277, 36194, 36371, -1, 36368, 36193, 36255, -1, 36367, 36255, 36256, -1, 36367, 36368, 36255, -1, 36366, 36367, 36256, -1, 36365, 36256, 36257, -1, 36365, 36366, 36256, -1, 36364, 36257, 36258, -1, 36364, 36365, 36257, -1, 36363, 36258, 36259, -1, 36363, 36364, 36258, -1, 36362, 36259, 36260, -1, 36362, 36363, 36259, -1, 36361, 36260, 36261, -1, 36361, 36362, 36260, -1, 36360, 36261, 36262, -1, 36360, 36361, 36261, -1, 36357, 36262, 36263, -1, 36357, 36360, 36262, -1, 36358, 36263, 36264, -1, 36358, 36357, 36263, -1, 36359, 36264, 36191, -1, 36359, 36358, 36264, -1, 36194, 36368, 36371, -1, 36194, 36193, 36368, -1, 36117, 36397, 36125, -1, 36125, 36397, 36398, -1, 36398, 36399, 36400, -1, 36397, 36399, 36398, -1, 36399, 36401, 36400, -1, 36400, 36402, 36403, -1, 36401, 36402, 36400, -1, 36403, 36404, 36405, -1, 36402, 36404, 36403, -1, 36404, 36406, 36405, -1, 36405, 36185, 36200, -1, 36406, 36185, 36405, -1, 33597, 33596, 36181, -1, 36407, 36179, 36177, -1, 36408, 33597, 36179, -1, 36408, 36179, 36407, -1, 33598, 33597, 36408, -1, 36409, 36181, 36179, -1, 36409, 36179, 33597, -1, 36409, 33597, 36181, -1, 33598, 36410, 33553, -1, 36408, 36411, 36410, -1, 36408, 36410, 33598, -1, 36204, 36412, 36413, -1, 36204, 36207, 36412, -1, 36407, 36413, 36411, -1, 36407, 36204, 36413, -1, 36407, 36411, 36408, -1, 36177, 36204, 36407, -1, 36207, 36185, 36414, -1, 36412, 36414, 36415, -1, 36412, 36207, 36414, -1, 36413, 36415, 36416, -1, 36413, 36412, 36415, -1, 36411, 36416, 36417, -1, 36411, 36413, 36416, -1, 36410, 36417, 33552, -1, 36410, 36411, 36417, -1, 33553, 36410, 33552, -1, 36406, 36415, 36414, -1, 36406, 36414, 36185, -1, 36416, 36415, 36406, -1, 33574, 33552, 36417, -1, 36418, 36397, 36117, -1, 33570, 33571, 36419, -1, 36420, 36406, 36404, -1, 36421, 36406, 36420, -1, 36421, 36416, 36406, -1, 36421, 36420, 36404, -1, 36422, 36417, 36416, -1, 36422, 36416, 36421, -1, 36422, 33574, 36417, -1, 36423, 36402, 36401, -1, 36423, 36404, 36402, -1, 36424, 36421, 36404, -1, 36424, 36404, 36423, -1, 36425, 36401, 36399, -1, 36425, 36423, 36401, -1, 36426, 33573, 33574, -1, 36426, 33574, 36422, -1, 36426, 36422, 36421, -1, 36426, 36421, 36424, -1, 36427, 36423, 36425, -1, 36427, 36424, 36423, -1, 36428, 36399, 36397, -1, 36428, 36425, 36399, -1, 36429, 33572, 33573, -1, 36429, 33573, 36426, -1, 36429, 36426, 36424, -1, 36429, 36424, 36427, -1, 36430, 36418, 36419, -1, 36430, 36427, 36425, -1, 36430, 36397, 36418, -1, 36430, 36428, 36397, -1, 36430, 36425, 36428, -1, 36431, 33571, 33572, -1, 36431, 33572, 36429, -1, 36431, 36427, 36430, -1, 36431, 36419, 33571, -1, 36431, 36429, 36427, -1, 36431, 36430, 36419, -1, 36418, 36117, 33576, -1, 36418, 33576, 33578, -1, 36419, 33578, 33580, -1, 36419, 36418, 33578, -1, 33570, 33580, 33567, -1, 33570, 36419, 33580, -1, 33575, 33577, 36106, -1, 36432, 36099, 35858, -1, 36433, 33563, 36434, -1, 36435, 33563, 36433, -1, 33556, 33563, 36435, -1, 36436, 36106, 36105, -1, 36436, 33575, 36106, -1, 36437, 33579, 33575, -1, 36437, 33575, 36436, -1, 36438, 33566, 33579, -1, 36438, 33565, 33566, -1, 36438, 33579, 36437, -1, 36439, 36105, 36103, -1, 36439, 36436, 36105, -1, 36440, 36437, 36436, -1, 36440, 36436, 36439, -1, 36441, 33564, 33565, -1, 36441, 36438, 36437, -1, 36441, 36437, 36440, -1, 36441, 33565, 36438, -1, 36442, 36101, 36099, -1, 36442, 36103, 36101, -1, 36442, 36439, 36103, -1, 36443, 36440, 36439, -1, 36443, 36439, 36442, -1, 36444, 33561, 33564, -1, 36444, 36440, 36443, -1, 36444, 36441, 36440, -1, 36444, 33564, 36441, -1, 36445, 36432, 36434, -1, 36445, 36442, 36099, -1, 36445, 36099, 36432, -1, 36446, 36445, 36434, -1, 36446, 36443, 36442, -1, 36446, 36442, 36445, -1, 36446, 36434, 33563, -1, 36447, 33562, 33561, -1, 36447, 33563, 33562, -1, 36447, 33561, 36444, -1, 36447, 36444, 36443, -1, 36447, 36446, 33563, -1, 36447, 36443, 36446, -1, 36432, 35858, 35919, -1, 36432, 35919, 36448, -1, 36434, 36448, 36449, -1, 36434, 36432, 36448, -1, 36433, 36449, 36450, -1, 36433, 36434, 36449, -1, 36435, 36450, 36451, -1, 36435, 36433, 36450, -1, 33556, 36451, 33557, -1, 33556, 36435, 36451, -1, 36452, 33557, 36451, -1, 36452, 36451, 36450, -1, 36452, 36453, 33582, -1, 36452, 33582, 33557, -1, 36454, 36450, 36449, -1, 36454, 36455, 36453, -1, 36454, 36452, 36450, -1, 36454, 36453, 36452, -1, 36456, 36449, 36448, -1, 36456, 36448, 35919, -1, 36456, 35930, 35856, -1, 36456, 35919, 35930, -1, 36456, 35856, 36455, -1, 36456, 36454, 36449, -1, 36456, 36455, 36454, -1, 35852, 33585, 33584, -1, 35854, 35852, 33584, -1, 36453, 33584, 33582, -1, 36453, 35854, 33584, -1, 36455, 35854, 36453, -1, 35856, 35854, 36455, -1, 33543, 36457, 33546, -1, 33454, 36457, 33543, -1, 33560, 33535, 33534, -1, 33471, 33535, 33560, -1, 36458, 36459, 33555, -1, 36458, 33555, 33559, -1, 36458, 33559, 36460, -1, 36460, 33569, 36461, -1, 33559, 33569, 36460, -1, 36461, 33568, 33581, -1, 33569, 33568, 36461, -1, 33568, 33558, 33581, -1, 33546, 36462, 33544, -1, 36457, 36462, 33546, -1, 33544, 36463, 33545, -1, 36462, 36463, 33544, -1, 33545, 33599, 33547, -1, 36463, 33599, 33545, -1, 33555, 36459, 33550, -1, 36459, 36464, 33550, -1, 33550, 36465, 33548, -1, 36464, 36465, 33550, -1, 33548, 33467, 33551, -1, 36465, 33467, 33548, -1, 33551, 33466, 33549, -1, 33467, 33466, 33551, -1, 33549, 33470, 33554, -1, 33466, 33470, 33549, -1, 33554, 33471, 33560, -1, 33470, 33471, 33554, -1, 33505, 33493, 36466, -1, 36467, 33505, 36466, -1, 36468, 36466, 36469, -1, 36468, 36467, 36466, -1, 36470, 36469, 36471, -1, 36470, 36468, 36469, -1, 36472, 36471, 36473, -1, 36472, 36470, 36471, -1, 34578, 36473, 34579, -1, 34578, 36472, 36473, -1, 36474, 33497, 33490, -1, 36475, 36466, 33493, -1, 36475, 33493, 33494, -1, 36476, 36469, 36466, -1, 36476, 36466, 36475, -1, 36477, 36471, 36469, -1, 36477, 36469, 36476, -1, 36478, 36473, 36471, -1, 36478, 36471, 36477, -1, 36479, 34579, 36473, -1, 36479, 34602, 34579, -1, 36479, 36473, 36478, -1, 36480, 33494, 33497, -1, 36480, 36474, 36481, -1, 36480, 36475, 33494, -1, 36480, 33497, 36474, -1, 36482, 36475, 36480, -1, 36482, 36480, 36481, -1, 36482, 36476, 36475, -1, 36483, 36481, 36484, -1, 36483, 36476, 36482, -1, 36483, 36477, 36476, -1, 36483, 36482, 36481, -1, 36485, 36486, 36487, -1, 36485, 36484, 36486, -1, 36485, 36477, 36483, -1, 36485, 36478, 36477, -1, 36485, 36483, 36484, -1, 36488, 36487, 34571, -1, 36488, 34580, 34602, -1, 36488, 34571, 34580, -1, 36488, 36479, 36478, -1, 36488, 36485, 36487, -1, 36488, 34602, 36479, -1, 36488, 36478, 36485, -1, 33490, 33488, 36489, -1, 36474, 36489, 36490, -1, 36474, 33490, 36489, -1, 36481, 36490, 36491, -1, 36481, 36474, 36490, -1, 36484, 36481, 36491, -1, 36486, 36491, 36492, -1, 36486, 36484, 36491, -1, 36487, 36492, 36493, -1, 36487, 36486, 36492, -1, 34571, 36493, 34484, -1, 34571, 36487, 36493, -1, 36489, 33488, 33486, -1, 36489, 33486, 36494, -1, 36490, 36494, 36495, -1, 36490, 36489, 36494, -1, 36491, 36495, 36496, -1, 36491, 36490, 36495, -1, 36492, 36496, 36497, -1, 36492, 36491, 36496, -1, 36493, 36497, 36498, -1, 36493, 36492, 36497, -1, 34484, 36498, 36499, -1, 34484, 36493, 36498, -1, 34477, 34484, 36499, -1, 34475, 34477, 36499, -1, 34478, 34475, 36499, -1, 34473, 36499, 33588, -1, 34473, 34478, 36499, -1, 34471, 34473, 33588, -1, 33589, 34471, 33588, -1, 36500, 36495, 36494, -1, 36500, 33484, 33482, -1, 36500, 33482, 36501, -1, 36500, 36502, 36503, -1, 36500, 36494, 33484, -1, 36500, 36503, 36495, -1, 36500, 36501, 36502, -1, 33486, 33484, 36494, -1, 36504, 36505, 33583, -1, 36504, 33583, 33587, -1, 36506, 36507, 36505, -1, 36506, 36505, 36504, -1, 36508, 33588, 36499, -1, 36508, 33586, 33588, -1, 36508, 33587, 33586, -1, 36508, 36504, 33587, -1, 36509, 36510, 36507, -1, 36509, 36507, 36506, -1, 36511, 36499, 36498, -1, 36511, 36506, 36504, -1, 36511, 36508, 36499, -1, 36511, 36504, 36508, -1, 36512, 36513, 36510, -1, 36512, 36510, 36509, -1, 36514, 36498, 36497, -1, 36514, 36511, 36498, -1, 36514, 36506, 36511, -1, 36514, 36509, 36506, -1, 36502, 36515, 36513, -1, 36502, 36513, 36512, -1, 36516, 36497, 36496, -1, 36516, 36509, 36514, -1, 36516, 36512, 36509, -1, 36516, 36514, 36497, -1, 36501, 33482, 33447, -1, 36501, 36517, 36515, -1, 36501, 33447, 36517, -1, 36501, 36515, 36502, -1, 36503, 36496, 36495, -1, 36503, 36502, 36512, -1, 36503, 36516, 36496, -1, 36503, 36512, 36516, -1, 33581, 33583, 36505, -1, 36518, 36505, 36507, -1, 36518, 33581, 36505, -1, 36519, 36507, 36510, -1, 36519, 36518, 36507, -1, 36520, 36510, 36513, -1, 36520, 36519, 36510, -1, 36521, 36513, 36515, -1, 36521, 36520, 36513, -1, 36522, 36515, 36517, -1, 36522, 36521, 36515, -1, 36523, 36522, 36517, -1, 33445, 36517, 33447, -1, 33445, 36523, 36517, -1, 36460, 36524, 36458, -1, 36460, 36525, 36524, -1, 33445, 33444, 36523, -1, 36526, 36460, 36461, -1, 36527, 36525, 36460, -1, 36527, 36460, 36526, -1, 36527, 36526, 36461, -1, 36528, 36529, 36525, -1, 36528, 36525, 36527, -1, 36528, 36527, 36461, -1, 36530, 36531, 36529, -1, 36530, 36529, 36528, -1, 36532, 33443, 33442, -1, 36532, 33444, 33443, -1, 36532, 33442, 36531, -1, 36532, 36531, 36530, -1, 36533, 33581, 36518, -1, 36533, 36461, 33581, -1, 36534, 36518, 36519, -1, 36534, 36461, 36533, -1, 36534, 36533, 36518, -1, 36535, 36519, 36520, -1, 36535, 36520, 36521, -1, 36535, 36528, 36461, -1, 36535, 36534, 36519, -1, 36535, 36461, 36534, -1, 36536, 36521, 36522, -1, 36536, 36528, 36535, -1, 36536, 36530, 36528, -1, 36536, 36535, 36521, -1, 36537, 36522, 36523, -1, 36537, 36532, 36530, -1, 36537, 33444, 36532, -1, 36537, 36536, 36522, -1, 36537, 36523, 33444, -1, 36537, 36530, 36536, -1, 36531, 33442, 33426, -1, 36531, 33426, 36538, -1, 36529, 36538, 36539, -1, 36529, 36531, 36538, -1, 36525, 36540, 36541, -1, 36525, 36539, 36540, -1, 36525, 36529, 36539, -1, 36524, 36541, 36459, -1, 36524, 36525, 36541, -1, 36458, 36524, 36459, -1, 36465, 33465, 33467, -1, 33423, 33425, 33468, -1, 36541, 36464, 36459, -1, 33426, 33424, 36538, -1, 36542, 36465, 36464, -1, 36542, 33465, 36465, -1, 36543, 33480, 33465, -1, 36543, 33465, 36542, -1, 36544, 33481, 33480, -1, 36544, 33480, 36543, -1, 36545, 33468, 33481, -1, 36545, 33424, 33423, -1, 36545, 33481, 36544, -1, 36545, 33423, 33468, -1, 36546, 36541, 36540, -1, 36546, 36540, 36539, -1, 36546, 36539, 36538, -1, 36546, 36543, 36542, -1, 36546, 36542, 36464, -1, 36546, 33424, 36545, -1, 36546, 36545, 36544, -1, 36546, 36464, 36541, -1, 36546, 36544, 36543, -1, 36546, 36538, 33424, -1, 33429, 33431, 36547, -1, 33478, 36547, 36548, -1, 33478, 33429, 36547, -1, 33476, 33478, 36548, -1, 33474, 36548, 36549, -1, 33474, 33476, 36548, -1, 33472, 36549, 36550, -1, 33472, 33474, 36549, -1, 33471, 36550, 33535, -1, 33471, 33472, 36550, -1, 33538, 33448, 33450, -1, 33436, 33438, 33451, -1, 36550, 33537, 33535, -1, 33431, 33434, 36547, -1, 36551, 33538, 33537, -1, 36551, 33448, 33538, -1, 36552, 33463, 33448, -1, 36552, 33448, 36551, -1, 36553, 33464, 33463, -1, 36553, 33463, 36552, -1, 36554, 33451, 33464, -1, 36554, 33434, 33436, -1, 36554, 33464, 36553, -1, 36554, 33436, 33451, -1, 36555, 36550, 36549, -1, 36555, 36549, 36548, -1, 36555, 36548, 36547, -1, 36555, 36552, 36551, -1, 36555, 36551, 33537, -1, 36555, 33434, 36554, -1, 36555, 36554, 36553, -1, 36555, 33537, 36550, -1, 36555, 36553, 36552, -1, 36555, 36547, 33434, -1, 33406, 33408, 36556, -1, 33461, 36556, 36557, -1, 33461, 33406, 36556, -1, 33459, 36557, 36558, -1, 33459, 33461, 36557, -1, 33457, 36558, 36559, -1, 33457, 33459, 36558, -1, 33455, 36559, 36457, -1, 33455, 33457, 36559, -1, 33454, 33455, 36457, -1, 36463, 36560, 33599, -1, 33413, 33415, 36561, -1, 36559, 36462, 36457, -1, 36562, 36463, 36462, -1, 36562, 36560, 36463, -1, 36563, 36564, 36560, -1, 36563, 36560, 36562, -1, 36565, 36566, 36564, -1, 36565, 36567, 36566, -1, 36565, 36564, 36563, -1, 36568, 36569, 36567, -1, 36568, 36567, 36565, -1, 36570, 33411, 33413, -1, 36570, 36561, 36569, -1, 36570, 36569, 36568, -1, 36570, 33413, 36561, -1, 36571, 36563, 36562, -1, 36571, 36562, 36462, -1, 36571, 36570, 36568, -1, 36571, 33411, 36570, -1, 36571, 36568, 36565, -1, 36571, 36565, 36563, -1, 36572, 36571, 36462, -1, 36572, 33411, 36571, -1, 36573, 36559, 36558, -1, 36573, 36558, 36557, -1, 36573, 36557, 36556, -1, 36573, 36556, 33408, -1, 36573, 33408, 33411, -1, 36573, 33411, 36572, -1, 36573, 36462, 36559, -1, 36573, 36572, 36462, -1, 36574, 33599, 36560, -1, 36574, 33595, 33599, -1, 36575, 36560, 36564, -1, 36575, 36574, 36560, -1, 36576, 36564, 36566, -1, 36576, 36575, 36564, -1, 36577, 36566, 36567, -1, 36577, 36576, 36566, -1, 36578, 36567, 36569, -1, 36578, 36577, 36567, -1, 36579, 36569, 36561, -1, 36579, 36578, 36569, -1, 33398, 36561, 33415, -1, 33398, 36579, 36561, -1, 36580, 36581, 36582, -1, 36580, 36582, 36583, -1, 36584, 36585, 36586, -1, 36584, 33405, 36585, -1, 36584, 36586, 36587, -1, 36588, 36575, 36576, -1, 36588, 36589, 36575, -1, 36588, 36583, 36590, -1, 36588, 36590, 36589, -1, 36591, 36587, 36581, -1, 36591, 36581, 36580, -1, 36592, 36576, 36577, -1, 36592, 36588, 36576, -1, 36592, 36580, 36583, -1, 36592, 36583, 36588, -1, 36593, 33403, 33405, -1, 36593, 33405, 36584, -1, 36593, 36584, 36587, -1, 36593, 36587, 36591, -1, 36594, 36577, 36578, -1, 36594, 36592, 36577, -1, 36594, 36591, 36580, -1, 36594, 36580, 36592, -1, 36595, 36578, 36579, -1, 36595, 33401, 33403, -1, 36595, 33403, 36593, -1, 36595, 36579, 33401, -1, 36595, 36594, 36578, -1, 36595, 36593, 36591, -1, 36595, 36591, 36594, -1, 36574, 33593, 33595, -1, 33405, 33397, 36585, -1, 33398, 33401, 36579, -1, 36596, 36597, 33590, -1, 36596, 33590, 33592, -1, 36598, 36599, 36597, -1, 36598, 36597, 36596, -1, 36600, 33592, 33591, -1, 36600, 36596, 33592, -1, 36582, 36601, 36599, -1, 36582, 36599, 36598, -1, 36590, 36598, 36596, -1, 36590, 36596, 36600, -1, 36581, 36602, 36601, -1, 36581, 36601, 36582, -1, 36603, 33591, 33593, -1, 36603, 36600, 33591, -1, 36603, 33593, 36574, -1, 36583, 36598, 36590, -1, 36583, 36582, 36598, -1, 36587, 36586, 36602, -1, 36587, 36602, 36581, -1, 36589, 36574, 36575, -1, 36589, 36600, 36603, -1, 36589, 36590, 36600, -1, 36589, 36603, 36574, -1, 33397, 33396, 36604, -1, 36585, 33397, 36604, -1, 36586, 36604, 36605, -1, 36586, 36585, 36604, -1, 36602, 36605, 36606, -1, 36602, 36586, 36605, -1, 36601, 36606, 36607, -1, 36601, 36602, 36606, -1, 36599, 36607, 36608, -1, 36599, 36601, 36607, -1, 36597, 36608, 34129, -1, 36597, 34131, 34135, -1, 36597, 34129, 34131, -1, 36597, 36599, 36608, -1, 33590, 34136, 33594, -1, 33590, 34135, 34136, -1, 33590, 36597, 34135, -1, 36604, 33396, 33394, -1, 36604, 33394, 36609, -1, 36605, 36609, 36610, -1, 36605, 36604, 36609, -1, 36606, 36611, 36612, -1, 36606, 36610, 36611, -1, 36606, 36605, 36610, -1, 36607, 36612, 36613, -1, 36607, 36606, 36612, -1, 36608, 36613, 34138, -1, 36608, 36607, 36613, -1, 34129, 36608, 34138, -1, 33392, 36611, 36610, -1, 33392, 36610, 36609, -1, 33392, 36609, 33394, -1, 36614, 33392, 33390, -1, 36615, 36614, 33390, -1, 36615, 33392, 36614, -1, 36616, 36612, 36611, -1, 36616, 36611, 33392, -1, 36616, 36615, 33390, -1, 36616, 33392, 36615, -1, 36617, 36613, 36612, -1, 36617, 36612, 36616, -1, 36618, 34138, 36613, -1, 36618, 34105, 34138, -1, 36618, 36613, 36617, -1, 36619, 33390, 33388, -1, 36620, 36616, 33390, -1, 36620, 33390, 36619, -1, 36621, 36616, 36620, -1, 36621, 36617, 36616, -1, 36622, 33388, 33386, -1, 36622, 33386, 36623, -1, 36624, 34097, 34105, -1, 36624, 36618, 36617, -1, 36624, 36617, 36621, -1, 36624, 34105, 36618, -1, 36625, 36623, 36626, -1, 36625, 36619, 33388, -1, 36625, 33388, 36622, -1, 36625, 36622, 36623, -1, 36627, 36626, 36628, -1, 36627, 36620, 36619, -1, 36627, 36619, 36625, -1, 36627, 36625, 36626, -1, 36629, 36630, 36631, -1, 36629, 36628, 36630, -1, 36629, 36621, 36620, -1, 36629, 36620, 36627, -1, 36629, 36627, 36628, -1, 36632, 36631, 33705, -1, 36632, 34086, 34097, -1, 36632, 33705, 34086, -1, 36632, 36629, 36631, -1, 36632, 34097, 36624, -1, 36632, 36624, 36621, -1, 36632, 36621, 36629, -1, 36623, 33386, 33385, -1, 36623, 33385, 36633, -1, 36626, 36633, 36634, -1, 36626, 36623, 36633, -1, 36628, 36634, 36635, -1, 36628, 36626, 36634, -1, 36630, 36635, 36636, -1, 36630, 36628, 36635, -1, 36631, 36637, 33706, -1, 36631, 36636, 36637, -1, 36631, 36630, 36636, -1, 33705, 36631, 33706, -1, 36638, 33371, 33373, -1, 36638, 36639, 36640, -1, 36638, 36641, 33371, -1, 36638, 36640, 36641, -1, 36642, 36643, 36644, -1, 32990, 36645, 32985, -1, 36642, 36644, 36646, -1, 36647, 33373, 33375, -1, 36647, 36638, 33373, -1, 36647, 36648, 36639, -1, 36647, 36639, 36638, -1, 36649, 33389, 33391, -1, 36649, 36643, 36642, -1, 36649, 33391, 36650, -1, 36649, 36650, 36643, -1, 36651, 33375, 33377, -1, 36651, 36646, 36648, -1, 36651, 36647, 33375, -1, 36651, 36648, 36647, -1, 36652, 33377, 33379, -1, 36652, 36651, 33377, -1, 36652, 36642, 36646, -1, 36652, 36646, 36651, -1, 36653, 33379, 33381, -1, 36653, 33387, 33389, -1, 36653, 33381, 33387, -1, 36653, 33389, 36649, -1, 36653, 36649, 36642, -1, 36653, 36652, 33379, -1, 36653, 36642, 36652, -1, 33371, 32968, 32997, -1, 33383, 33387, 33381, -1, 36654, 36655, 36645, -1, 36654, 36645, 32990, -1, 36656, 36657, 36655, -1, 36656, 36655, 36654, -1, 36658, 36659, 36657, -1, 36658, 36657, 36656, -1, 36640, 32990, 32989, -1, 36640, 36654, 32990, -1, 36644, 36660, 36659, -1, 36644, 36659, 36658, -1, 36639, 36656, 36654, -1, 36639, 36654, 36640, -1, 36643, 36661, 36660, -1, 36643, 36660, 36644, -1, 36648, 36656, 36639, -1, 36648, 36658, 36656, -1, 36641, 32989, 32968, -1, 36641, 32968, 33371, -1, 36641, 36640, 32989, -1, 36650, 33391, 33393, -1, 36650, 33393, 36661, -1, 36650, 36661, 36643, -1, 36646, 36658, 36648, -1, 36646, 36644, 36658, -1, 36662, 32985, 36645, -1, 36662, 32986, 32985, -1, 36663, 36645, 36655, -1, 36663, 36662, 36645, -1, 36664, 36655, 36657, -1, 36664, 36663, 36655, -1, 36665, 36657, 36659, -1, 36665, 36664, 36657, -1, 36666, 36659, 36660, -1, 36666, 36665, 36659, -1, 36667, 36660, 36661, -1, 36667, 36666, 36660, -1, 33395, 36661, 33393, -1, 33395, 36667, 36661, -1, 36668, 36669, 36670, -1, 36668, 36670, 36671, -1, 36672, 32986, 36662, -1, 36672, 36662, 36663, -1, 36672, 33023, 32986, -1, 36672, 36663, 36673, -1, 36674, 36675, 36676, -1, 36674, 36671, 36677, -1, 36674, 36678, 36675, -1, 36674, 36677, 36678, -1, 36679, 36669, 36668, -1, 36679, 36673, 36669, -1, 36680, 36676, 36681, -1, 36680, 36671, 36674, -1, 36680, 36674, 36676, -1, 36680, 36668, 36671, -1, 36682, 33022, 33023, -1, 36682, 33023, 36672, -1, 36682, 36672, 36673, -1, 36682, 36673, 36679, -1, 36683, 36681, 36684, -1, 36683, 36679, 36668, -1, 36683, 36668, 36680, -1, 36683, 36680, 36681, -1, 36685, 36684, 36686, -1, 36685, 33027, 33022, -1, 36685, 36686, 33027, -1, 36685, 36682, 36679, -1, 36685, 36679, 36683, -1, 36685, 33022, 36682, -1, 36685, 36683, 36684, -1, 33000, 33027, 36686, -1, 36687, 36667, 33395, -1, 36687, 33395, 33404, -1, 36688, 36666, 36667, -1, 36688, 36667, 36687, -1, 36689, 33404, 33402, -1, 36689, 36687, 33404, -1, 36670, 36665, 36666, -1, 36670, 36666, 36688, -1, 36677, 36688, 36687, -1, 36677, 36687, 36689, -1, 36669, 36664, 36665, -1, 36669, 36665, 36670, -1, 36690, 33400, 33399, -1, 36690, 33402, 33400, -1, 36690, 33399, 36691, -1, 36690, 36689, 33402, -1, 36671, 36670, 36688, -1, 36671, 36688, 36677, -1, 36673, 36663, 36664, -1, 36673, 36664, 36669, -1, 36678, 36691, 36675, -1, 36678, 36677, 36689, -1, 36678, 36689, 36690, -1, 36678, 36690, 36691, -1, 36692, 33000, 36686, -1, 36692, 33004, 33000, -1, 36693, 36686, 36684, -1, 36693, 36692, 36686, -1, 36694, 36684, 36681, -1, 36694, 36693, 36684, -1, 36695, 36681, 36676, -1, 36695, 36694, 36681, -1, 36696, 36676, 36675, -1, 36696, 36695, 36676, -1, 36697, 36675, 36691, -1, 36697, 36696, 36675, -1, 33414, 36691, 33399, -1, 33414, 36697, 36691, -1, 36698, 33090, 36699, -1, 36698, 36699, 36700, -1, 36698, 36700, 36701, -1, 36702, 33410, 33407, -1, 33090, 33004, 36692, -1, 36703, 36697, 33414, -1, 36703, 33414, 33412, -1, 36704, 36696, 36697, -1, 36704, 36697, 36703, -1, 36705, 33412, 33410, -1, 36705, 36702, 36706, -1, 36705, 36703, 33412, -1, 36705, 33410, 36702, -1, 36707, 36695, 36696, -1, 36707, 36696, 36704, -1, 36708, 36706, 36709, -1, 36708, 36704, 36703, -1, 36708, 36705, 36706, -1, 36708, 36703, 36705, -1, 36710, 36694, 36695, -1, 36710, 36695, 36707, -1, 36711, 36709, 36712, -1, 36711, 36707, 36704, -1, 36711, 36708, 36709, -1, 36711, 36704, 36708, -1, 36700, 36693, 36694, -1, 36700, 36694, 36710, -1, 36713, 36712, 36714, -1, 36713, 36710, 36707, -1, 36713, 36711, 36712, -1, 36713, 36707, 36711, -1, 36699, 36692, 36693, -1, 36699, 36693, 36700, -1, 36699, 33090, 36692, -1, 36701, 36714, 36715, -1, 36701, 36713, 36714, -1, 36701, 36700, 36710, -1, 36701, 36710, 36713, -1, 36698, 36715, 33085, -1, 36698, 33088, 33090, -1, 36698, 33085, 33088, -1, 36698, 36701, 36715, -1, 36716, 33085, 36715, -1, 36716, 33105, 33085, -1, 36717, 36715, 36714, -1, 36717, 36716, 36715, -1, 36718, 36714, 36712, -1, 36718, 36717, 36714, -1, 36719, 36712, 36709, -1, 36719, 36718, 36712, -1, 36720, 36709, 36706, -1, 36720, 36719, 36709, -1, 36721, 36706, 36702, -1, 36721, 36720, 36706, -1, 33409, 36702, 33407, -1, 33409, 36721, 36702, -1, 36722, 36723, 36724, -1, 36725, 36726, 36727, -1, 36725, 36727, 36728, -1, 36729, 33128, 33136, -1, 33437, 36721, 33409, -1, 36729, 33122, 33128, -1, 36729, 36730, 36731, -1, 36729, 36731, 36722, -1, 36729, 33136, 36730, -1, 36732, 36733, 36726, -1, 36732, 36726, 36725, -1, 36734, 33432, 33430, -1, 36734, 33430, 36735, -1, 36734, 36728, 33432, -1, 36736, 36724, 36733, -1, 36736, 36733, 36732, -1, 36737, 36735, 36738, -1, 36737, 36734, 36735, -1, 36737, 36725, 36728, -1, 36737, 36728, 36734, -1, 36739, 36724, 36736, -1, 36739, 36722, 36724, -1, 36740, 36738, 36741, -1, 36740, 36732, 36725, -1, 36740, 36737, 36738, -1, 36740, 36725, 36737, -1, 36742, 33122, 36729, -1, 36742, 36729, 36722, -1, 36742, 36722, 36739, -1, 36743, 36732, 36740, -1, 36743, 36741, 36744, -1, 36743, 36740, 36741, -1, 36743, 36736, 36732, -1, 36745, 36736, 36743, -1, 36745, 36744, 36746, -1, 36745, 36739, 36736, -1, 36745, 36743, 36744, -1, 36747, 36742, 36739, -1, 36747, 36745, 36746, -1, 36747, 36746, 33110, -1, 36747, 33109, 33122, -1, 36747, 33110, 33109, -1, 36747, 36739, 36745, -1, 36747, 33122, 36742, -1, 36748, 33437, 33435, -1, 36748, 36721, 33437, -1, 36749, 36720, 36721, -1, 36749, 36721, 36748, -1, 36750, 36718, 36719, -1, 36750, 36719, 36720, -1, 36750, 36720, 36749, -1, 36723, 36717, 36718, -1, 36723, 36718, 36750, -1, 36727, 33435, 33433, -1, 36727, 36748, 33435, -1, 36731, 36717, 36723, -1, 36726, 36748, 36727, -1, 36726, 36749, 36748, -1, 36730, 33105, 36716, -1, 36730, 36716, 36717, -1, 36730, 33136, 33105, -1, 36730, 36717, 36731, -1, 36733, 36749, 36726, -1, 36733, 36750, 36749, -1, 36724, 36750, 36733, -1, 36724, 36723, 36750, -1, 36728, 33433, 33432, -1, 36728, 36727, 33433, -1, 36722, 36731, 36723, -1, 36751, 33110, 36746, -1, 36751, 33139, 33110, -1, 36752, 36746, 36744, -1, 36752, 36751, 36746, -1, 36753, 36744, 36741, -1, 36753, 36752, 36744, -1, 36754, 36741, 36738, -1, 36754, 36753, 36741, -1, 36755, 36738, 36735, -1, 36755, 36754, 36738, -1, 33417, 36735, 33430, -1, 33417, 36755, 36735, -1, 36756, 36757, 36758, -1, 36756, 36759, 36757, -1, 33422, 36755, 33417, -1, 36760, 36761, 36762, -1, 36760, 36762, 36763, -1, 36764, 36765, 36759, -1, 36764, 36759, 36756, -1, 36766, 33185, 33186, -1, 36766, 36767, 36761, -1, 36766, 33186, 36767, -1, 36766, 36761, 36760, -1, 36768, 33419, 33416, -1, 36768, 36758, 33419, -1, 36769, 36763, 36765, -1, 36769, 36765, 36764, -1, 36770, 36756, 36758, -1, 36770, 36758, 36768, -1, 36771, 36763, 36769, -1, 36771, 36760, 36763, -1, 36772, 33416, 33418, -1, 36772, 33418, 36773, -1, 36772, 36768, 33416, -1, 36774, 36756, 36770, -1, 36774, 36764, 36756, -1, 36775, 36760, 36771, -1, 36775, 33184, 33185, -1, 36775, 33185, 36766, -1, 36775, 36766, 36760, -1, 36776, 36772, 36773, -1, 36776, 36768, 36772, -1, 36776, 36773, 36777, -1, 36776, 36770, 36768, -1, 36778, 36764, 36774, -1, 36778, 36769, 36764, -1, 36779, 36776, 36777, -1, 36779, 36770, 36776, -1, 36779, 36777, 36780, -1, 36779, 36774, 36770, -1, 36781, 36771, 36769, -1, 36781, 36769, 36778, -1, 36782, 33422, 33421, -1, 36782, 36755, 33422, -1, 36783, 36754, 36755, -1, 36784, 36780, 36785, -1, 36784, 36779, 36780, -1, 36783, 36755, 36782, -1, 36784, 36774, 36779, -1, 36784, 36778, 36774, -1, 36786, 36753, 36754, -1, 36787, 36771, 36781, -1, 36787, 33183, 33184, -1, 36787, 33182, 33183, -1, 36786, 36754, 36783, -1, 36787, 33184, 36775, -1, 36757, 33421, 33420, -1, 36787, 36775, 36771, -1, 36788, 36789, 36790, -1, 36757, 36782, 33421, -1, 36788, 36785, 36789, -1, 36788, 36784, 36785, -1, 36788, 36778, 36784, -1, 36762, 36752, 36753, -1, 36788, 36781, 36778, -1, 36791, 36787, 36781, -1, 36791, 36790, 31443, -1, 36791, 36788, 36790, -1, 36791, 31443, 33182, -1, 36762, 36753, 36786, -1, 36791, 36781, 36788, -1, 36791, 33182, 36787, -1, 36759, 36783, 36782, -1, 36759, 36782, 36757, -1, 36761, 36751, 36752, -1, 36761, 36752, 36762, -1, 36765, 36786, 36783, -1, 36765, 36783, 36759, -1, 36767, 33139, 36751, -1, 36767, 33186, 33139, -1, 36767, 36751, 36761, -1, 36758, 33420, 33419, -1, 36758, 36757, 33420, -1, 36763, 36786, 36765, -1, 36763, 36762, 36786, -1, 36792, 31443, 36790, -1, 36792, 31441, 31443, -1, 36793, 36790, 36789, -1, 36793, 36792, 36790, -1, 36794, 36789, 36785, -1, 36794, 36793, 36789, -1, 36795, 36785, 36780, -1, 36795, 36794, 36785, -1, 36796, 36780, 36777, -1, 36796, 36795, 36780, -1, 36797, 36777, 36773, -1, 36797, 36796, 36777, -1, 33439, 36773, 33418, -1, 33439, 36797, 36773, -1, 36798, 31449, 31441, -1, 36798, 31441, 36799, -1, 36800, 36799, 36801, -1, 36800, 36798, 36799, -1, 36802, 36803, 31376, -1, 36802, 36801, 36803, -1, 36802, 36800, 36801, -1, 31375, 36802, 31376, -1, 36794, 31376, 36803, -1, 36799, 36793, 36801, -1, 36795, 36804, 31376, -1, 36795, 31376, 36794, -1, 36792, 36793, 36799, -1, 36796, 36805, 36804, -1, 36796, 36804, 36795, -1, 36797, 36806, 36805, -1, 36797, 36805, 36796, -1, 33439, 36806, 36797, -1, 31441, 36792, 36799, -1, 36807, 36803, 36801, -1, 36807, 36793, 36794, -1, 36807, 36794, 36803, -1, 36807, 36801, 36793, -1, 36808, 31376, 36804, -1, 36808, 31371, 31376, -1, 36809, 36804, 36805, -1, 36809, 36808, 36804, -1, 36810, 36805, 36806, -1, 36810, 36809, 36805, -1, 33446, 36806, 33439, -1, 33446, 36810, 36806, -1, 31372, 31371, 36808, -1, 36811, 31373, 36812, -1, 31374, 31373, 36811, -1, 36813, 36810, 33446, -1, 36813, 33483, 33485, -1, 36813, 33446, 33483, -1, 36814, 36809, 36810, -1, 36814, 36810, 36813, -1, 36815, 36808, 36809, -1, 36815, 31370, 31372, -1, 36815, 31372, 36808, -1, 36815, 36814, 31370, -1, 36815, 36809, 36814, -1, 36816, 33485, 33487, -1, 36816, 33487, 36817, -1, 36816, 36813, 33485, -1, 36818, 36817, 36812, -1, 36818, 36814, 36813, -1, 36818, 36816, 36817, -1, 36818, 31370, 36814, -1, 36818, 36813, 36816, -1, 36818, 36812, 31373, -1, 36819, 31373, 31370, -1, 36819, 31370, 36818, -1, 36819, 36818, 31373, -1, 36820, 31374, 36811, -1, 36820, 31377, 31374, -1, 36821, 36811, 36812, -1, 36821, 36820, 36811, -1, 36822, 36812, 36817, -1, 36822, 36821, 36812, -1, 33489, 36817, 33487, -1, 33489, 36822, 36817, -1, 36823, 36824, 36825, -1, 36826, 36827, 36828, -1, 36826, 36828, 36823, -1, 36829, 31386, 31377, -1, 36829, 31377, 36820, -1, 36830, 33499, 33498, -1, 36830, 36827, 36826, -1, 36830, 33498, 36831, -1, 36830, 36831, 36827, -1, 36832, 31386, 36829, -1, 36832, 36825, 31386, -1, 36832, 36829, 36820, -1, 36833, 36820, 36821, -1, 36833, 36832, 36820, -1, 36833, 36823, 36825, -1, 36833, 36825, 36832, -1, 36834, 36821, 36822, -1, 36834, 36833, 36821, -1, 36834, 36826, 36823, -1, 36834, 36823, 36833, -1, 36835, 36822, 33489, -1, 36835, 33489, 33499, -1, 36835, 33499, 36830, -1, 36835, 36834, 36822, -1, 36835, 36830, 36826, -1, 36835, 36826, 36834, -1, 36836, 31122, 31125, -1, 36836, 31123, 31122, -1, 36836, 31127, 31123, -1, 36837, 31128, 31130, -1, 36837, 31125, 31128, -1, 36838, 31130, 36839, -1, 36838, 36839, 31390, -1, 36838, 31390, 31387, -1, 36840, 31125, 36837, -1, 36840, 36836, 31125, -1, 36824, 31130, 36838, -1, 36824, 36837, 31130, -1, 36841, 36842, 31127, -1, 36841, 31127, 36836, -1, 36828, 36837, 36824, -1, 36828, 36840, 36837, -1, 36843, 36836, 36840, -1, 36843, 36841, 36836, -1, 36844, 36845, 36842, -1, 36844, 33496, 36845, -1, 36844, 36842, 36841, -1, 36827, 36843, 36840, -1, 36827, 36840, 36828, -1, 36846, 36844, 36841, -1, 36846, 33496, 36844, -1, 36846, 36841, 36843, -1, 36847, 31387, 31386, -1, 36847, 36838, 31387, -1, 36831, 33498, 33496, -1, 36831, 36843, 36827, -1, 36831, 33496, 36846, -1, 36831, 36846, 36843, -1, 36825, 36824, 36838, -1, 36825, 36847, 31386, -1, 36825, 36838, 36847, -1, 36823, 36828, 36824, -1, 36848, 31114, 31116, -1, 36848, 31116, 36849, -1, 36850, 36849, 36851, -1, 36850, 36848, 36849, -1, 33511, 36851, 33491, -1, 33511, 36850, 36851, -1, 33495, 36842, 36845, -1, 33495, 36845, 33496, -1, 31119, 31127, 36842, -1, 31119, 33495, 33492, -1, 31119, 36842, 33495, -1, 31117, 31119, 33492, -1, 36851, 33492, 33491, -1, 36851, 31117, 33492, -1, 36849, 31117, 36851, -1, 31116, 31117, 36849, -1, 31616, 31617, 36852, -1, 36852, 36853, 36854, -1, 31617, 36853, 36852, -1, 36853, 36855, 36854, -1, 36854, 36856, 36857, -1, 36855, 36856, 36854, -1, 36857, 36858, 36859, -1, 36856, 36858, 36857, -1, 36859, 36860, 36861, -1, 36858, 36860, 36859, -1, 36862, 36863, 36864, -1, 36865, 36863, 36862, -1, 36866, 36865, 36862, -1, 36867, 36866, 36862, -1, 36860, 36867, 36862, -1, 36868, 36869, 36870, -1, 36868, 36870, 36871, -1, 36868, 36871, 36872, -1, 36868, 36872, 36873, -1, 36868, 36873, 36861, -1, 36874, 36862, 36875, -1, 36876, 36862, 36874, -1, 36877, 36862, 36876, -1, 36878, 36861, 36860, -1, 36878, 36860, 36862, -1, 36878, 36862, 36877, -1, 36879, 36868, 36861, -1, 36879, 36861, 36878, -1, 36880, 36868, 36879, -1, 36881, 36868, 36880, -1, 36882, 36868, 36881, -1, 36883, 36868, 36882, -1, 36884, 36885, 36886, -1, 36887, 36886, 36888, -1, 36887, 36884, 36886, -1, 36889, 36888, 36890, -1, 36889, 36887, 36888, -1, 36891, 36890, 36892, -1, 36891, 36889, 36890, -1, 36893, 36891, 36892, -1, 36878, 36892, 36879, -1, 36878, 36893, 36892, -1, 36884, 36894, 36885, -1, 36894, 36895, 36885, -1, 36896, 36897, 36898, -1, 36898, 36897, 36899, -1, 36899, 36900, 36901, -1, 36897, 36900, 36899, -1, 36901, 36902, 36903, -1, 36900, 36902, 36901, -1, 36903, 36904, 36895, -1, 36902, 36904, 36903, -1, 36904, 36885, 36895, -1, 36905, 36898, 36906, -1, 36896, 36898, 36905, -1, 36907, 36908, 36909, -1, 36910, 36908, 36907, -1, 36872, 36911, 36873, -1, 36873, 36911, 36859, -1, 36859, 36911, 36910, -1, 36912, 36913, 36914, -1, 36915, 36913, 36912, -1, 36916, 36913, 36915, -1, 36917, 36913, 36916, -1, 36909, 36918, 36917, -1, 36908, 36918, 36909, -1, 36871, 36919, 36872, -1, 36872, 36919, 36911, -1, 36910, 36919, 36908, -1, 36911, 36919, 36910, -1, 36914, 36920, 36921, -1, 36913, 36920, 36914, -1, 36917, 36920, 36913, -1, 36918, 36920, 36917, -1, 36870, 36922, 36871, -1, 36871, 36922, 36919, -1, 36908, 36922, 36918, -1, 36919, 36922, 36908, -1, 31635, 36923, 31618, -1, 36921, 36924, 36925, -1, 36869, 36924, 36870, -1, 36920, 36924, 36921, -1, 36925, 36924, 36869, -1, 36870, 36924, 36922, -1, 36918, 36924, 36920, -1, 36922, 36924, 36918, -1, 36861, 36873, 36859, -1, 36869, 36868, 36925, -1, 31616, 36926, 31628, -1, 36852, 36926, 31616, -1, 31628, 36927, 31626, -1, 36926, 36927, 31628, -1, 36854, 36928, 36852, -1, 36852, 36928, 36926, -1, 31626, 36929, 31624, -1, 36927, 36929, 31626, -1, 36926, 36930, 36927, -1, 36928, 36930, 36926, -1, 36857, 36907, 36854, -1, 36854, 36907, 36928, -1, 31624, 36931, 31636, -1, 31636, 36931, 31635, -1, 31635, 36931, 36923, -1, 36929, 36931, 31624, -1, 36930, 36916, 36927, -1, 36927, 36916, 36929, -1, 36928, 36909, 36930, -1, 36907, 36909, 36928, -1, 36859, 36910, 36857, -1, 36857, 36910, 36907, -1, 36923, 36915, 36912, -1, 36929, 36915, 36931, -1, 36931, 36915, 36923, -1, 36916, 36915, 36929, -1, 36909, 36917, 36930, -1, 36930, 36917, 36916, -1, 36932, 36933, 36934, -1, 36935, 36888, 36886, -1, 36935, 36936, 36888, -1, 36935, 36934, 36937, -1, 36935, 36937, 36936, -1, 36938, 36886, 36885, -1, 36938, 36885, 36904, -1, 36938, 36904, 36932, -1, 36938, 36932, 36934, -1, 36938, 36935, 36886, -1, 36938, 36934, 36935, -1, 36897, 36896, 36939, -1, 36940, 36941, 36883, -1, 36940, 36942, 36941, -1, 36940, 36883, 36882, -1, 36943, 36944, 36942, -1, 36943, 36942, 36940, -1, 36945, 36882, 36881, -1, 36945, 36940, 36882, -1, 36946, 36944, 36943, -1, 36947, 36943, 36940, -1, 36947, 36940, 36945, -1, 36933, 36948, 36944, -1, 36933, 36944, 36946, -1, 36949, 36879, 36892, -1, 36949, 36881, 36880, -1, 36949, 36880, 36879, -1, 36949, 36945, 36881, -1, 36937, 36943, 36947, -1, 36937, 36946, 36943, -1, 36950, 36900, 36897, -1, 36950, 36939, 36948, -1, 36950, 36948, 36933, -1, 36950, 36897, 36939, -1, 36951, 36892, 36890, -1, 36951, 36949, 36892, -1, 36951, 36947, 36945, -1, 36951, 36945, 36949, -1, 36934, 36946, 36937, -1, 36934, 36933, 36946, -1, 36936, 36890, 36888, -1, 36936, 36937, 36947, -1, 36936, 36951, 36890, -1, 36936, 36947, 36951, -1, 36932, 36904, 36902, -1, 36932, 36902, 36900, -1, 36932, 36950, 36933, -1, 36932, 36900, 36950, -1, 36952, 31633, 31618, -1, 36952, 31631, 31633, -1, 36952, 31618, 36923, -1, 36953, 31634, 31631, -1, 36953, 31598, 31634, -1, 36953, 36954, 31598, -1, 36953, 31631, 36952, -1, 36955, 36923, 36912, -1, 36955, 36952, 36923, -1, 36956, 36957, 36954, -1, 36956, 36952, 36955, -1, 36956, 36954, 36953, -1, 36956, 36953, 36952, -1, 36958, 36912, 36914, -1, 36958, 36955, 36912, -1, 36959, 36960, 36957, -1, 36959, 36957, 36956, -1, 36959, 36955, 36958, -1, 36959, 36956, 36955, -1, 36961, 36914, 36921, -1, 36961, 36958, 36914, -1, 36962, 36921, 36925, -1, 36962, 36961, 36921, -1, 36963, 36964, 36960, -1, 36963, 36958, 36961, -1, 36963, 36960, 36959, -1, 36963, 36959, 36958, -1, 36965, 36966, 36964, -1, 36965, 36967, 36966, -1, 36965, 36963, 36961, -1, 36965, 36961, 36962, -1, 36965, 36964, 36963, -1, 36968, 36962, 36925, -1, 36969, 36925, 36868, -1, 36969, 36968, 36925, -1, 36970, 36971, 36967, -1, 36970, 36967, 36965, -1, 36970, 36965, 36962, -1, 36970, 36962, 36968, -1, 36972, 36973, 36971, -1, 36972, 36868, 36973, -1, 36972, 36969, 36868, -1, 36972, 36971, 36970, -1, 36972, 36968, 36969, -1, 36972, 36970, 36968, -1, 36974, 36883, 36941, -1, 36974, 36941, 36942, -1, 36944, 36974, 36942, -1, 36975, 36944, 36948, -1, 36975, 36948, 36939, -1, 36975, 36974, 36944, -1, 36976, 36939, 36896, -1, 36976, 36975, 36939, -1, 36977, 36976, 36896, -1, 36905, 36977, 36896, -1, 31598, 36954, 31599, -1, 31599, 36954, 36978, -1, 36978, 36957, 36979, -1, 36954, 36957, 36978, -1, 36979, 36960, 36980, -1, 36980, 36960, 36981, -1, 36957, 36960, 36979, -1, 36960, 36964, 36981, -1, 36981, 36966, 36982, -1, 36964, 36966, 36981, -1, 36982, 36967, 36983, -1, 36966, 36967, 36982, -1, 36967, 36971, 36983, -1, 36983, 36973, 36883, -1, 36971, 36973, 36983, -1, 36973, 36868, 36883, -1, 31604, 36984, 31600, -1, 31608, 36984, 31604, -1, 31600, 36984, 36985, -1, 36986, 36984, 31608, -1, 36985, 36987, 36988, -1, 36984, 36987, 36985, -1, 36989, 36987, 36986, -1, 36978, 31614, 31599, -1, 36986, 36987, 36984, -1, 36979, 31614, 36978, -1, 36990, 36991, 36992, -1, 36993, 36991, 36990, -1, 36979, 36980, 31614, -1, 36976, 36994, 36975, -1, 36975, 36994, 36995, -1, 36995, 36994, 36993, -1, 36993, 36994, 36991, -1, 36989, 36996, 36987, -1, 36992, 36996, 36989, -1, 36987, 36996, 36988, -1, 36988, 36997, 36998, -1, 36996, 36997, 36988, -1, 36991, 36997, 36992, -1, 36992, 36997, 36996, -1, 36977, 36999, 36976, -1, 36997, 36999, 36998, -1, 36998, 36999, 36977, -1, 36976, 36999, 36994, -1, 36994, 36999, 36991, -1, 36991, 36999, 36997, -1, 36883, 36974, 36983, -1, 36977, 36905, 36998, -1, 31614, 37000, 31613, -1, 31614, 37001, 37000, -1, 36981, 37002, 36980, -1, 36980, 37002, 31614, -1, 31614, 37002, 37001, -1, 31613, 37003, 31612, -1, 37000, 37003, 31613, -1, 36982, 37004, 36981, -1, 36981, 37004, 37002, -1, 37001, 37005, 37000, -1, 37000, 37005, 37003, -1, 36983, 37006, 36982, -1, 36974, 37006, 36983, -1, 36982, 37006, 37004, -1, 37002, 36990, 37001, -1, 37001, 36990, 37005, -1, 31612, 36986, 31608, -1, 37003, 36986, 31612, -1, 37003, 36989, 36986, -1, 37005, 36989, 37003, -1, 37002, 36993, 36990, -1, 37004, 36993, 37002, -1, 36975, 36995, 36974, -1, 37006, 36995, 37004, -1, 37004, 36995, 36993, -1, 36974, 36995, 37006, -1, 36990, 36992, 37005, -1, 37005, 36992, 36989, -1, 36905, 36906, 36998, -1, 36906, 37007, 36998, -1, 36998, 37008, 36988, -1, 37007, 37008, 36998, -1, 36988, 37009, 36985, -1, 37008, 37009, 36988, -1, 36985, 31609, 31600, -1, 37009, 31609, 36985, -1, 31404, 30111, 30110, -1, 31404, 31397, 30111, -1, 37010, 30110, 30109, -1, 37010, 31404, 30110, -1, 37011, 37010, 30109, -1, 37012, 30109, 30108, -1, 37012, 37011, 30109, -1, 37013, 30108, 30112, -1, 37013, 37012, 30108, -1, 31435, 37013, 30112, -1, 37014, 31415, 31404, -1, 37014, 31404, 37010, -1, 37015, 37014, 37010, -1, 37016, 37010, 37011, -1, 37016, 37015, 37010, -1, 37017, 37011, 37012, -1, 37017, 37016, 37011, -1, 37018, 37012, 37013, -1, 37018, 37017, 37012, -1, 37019, 37013, 31435, -1, 37019, 37018, 37013, -1, 31450, 31435, 31434, -1, 31450, 37019, 31435, -1, 37020, 31415, 37021, -1, 37022, 31415, 37020, -1, 31410, 31415, 37022, -1, 37023, 37024, 37025, -1, 37026, 37024, 37023, -1, 37021, 37024, 37026, -1, 31415, 37024, 37021, -1, 37025, 37027, 37028, -1, 37024, 37027, 37025, -1, 37028, 37029, 31449, -1, 37027, 37029, 37028, -1, 37029, 31448, 31449, -1, 37024, 37030, 37027, -1, 37031, 37030, 37024, -1, 37032, 37030, 37033, -1, 37033, 37030, 37031, -1, 37027, 37034, 37029, -1, 37035, 37019, 31450, -1, 37036, 37034, 37032, -1, 37030, 37034, 37027, -1, 37032, 37034, 37030, -1, 31448, 37037, 31447, -1, 37029, 37037, 31448, -1, 31447, 37037, 37038, -1, 37038, 37037, 37036, -1, 37034, 37037, 37029, -1, 37036, 37037, 37034, -1, 37019, 37039, 37018, -1, 37035, 37039, 37019, -1, 37040, 37041, 37035, -1, 37035, 37041, 37039, -1, 37017, 37042, 37016, -1, 37018, 37042, 37017, -1, 37039, 37042, 37018, -1, 37043, 37044, 37045, -1, 37045, 37044, 37040, -1, 37040, 37044, 37041, -1, 37041, 37046, 37039, -1, 37039, 37046, 37042, -1, 37016, 37033, 37015, -1, 37042, 37033, 37016, -1, 31444, 37047, 31446, -1, 31446, 37047, 37043, -1, 37043, 37047, 37044, -1, 37044, 37048, 37041, -1, 37041, 37048, 37046, -1, 37046, 37032, 37042, -1, 37042, 37032, 37033, -1, 31445, 37049, 31444, -1, 37047, 37049, 37044, -1, 31444, 37049, 37047, -1, 37044, 37049, 37048, -1, 37048, 37036, 37046, -1, 37046, 37036, 37032, -1, 37014, 37031, 31415, -1, 37015, 37031, 37014, -1, 31415, 37031, 37024, -1, 37033, 37031, 37015, -1, 31447, 37038, 31445, -1, 37048, 37038, 37036, -1, 31445, 37038, 37049, -1, 37049, 37038, 37048, -1, 31429, 31428, 31450, -1, 31450, 31426, 37035, -1, 31428, 31426, 31450, -1, 31426, 31425, 37035, -1, 37035, 31424, 37040, -1, 31425, 31424, 37035, -1, 31424, 31423, 37040, -1, 37040, 31422, 37045, -1, 31423, 31422, 37040, -1, 37045, 31421, 37043, -1, 31422, 31421, 37045, -1, 37043, 31440, 31446, -1, 31421, 31440, 37043, -1, 31615, 37050, 31610, -1, 31610, 37050, 37051, -1, 37051, 37052, 37053, -1, 37050, 37052, 37051, -1, 37053, 37054, 37055, -1, 37052, 37054, 37053, -1, 37055, 37056, 37057, -1, 37054, 37056, 37055, -1, 37057, 37056, 37058, -1, 37058, 37056, 37059, -1, 31611, 37060, 31325, -1, 31325, 37060, 31326, -1, 37060, 37061, 31326, -1, 31326, 37062, 31327, -1, 37061, 37062, 31326, -1, 31327, 37063, 31328, -1, 37062, 37063, 31327, -1, 31328, 37064, 31323, -1, 31323, 37064, 31321, -1, 37063, 37064, 31328, -1, 31321, 37065, 31319, -1, 37064, 37065, 31321, -1, 31319, 31637, 31317, -1, 31317, 31637, 31315, -1, 37065, 31637, 31319, -1, 31642, 31641, 37066, -1, 37067, 37066, 37068, -1, 37067, 31642, 37066, -1, 37069, 37068, 37070, -1, 37069, 37067, 37068, -1, 37071, 37070, 37072, -1, 37071, 37069, 37070, -1, 37073, 37071, 37072, -1, 37074, 37072, 37075, -1, 37074, 37073, 37072, -1, 37076, 37075, 37077, -1, 37076, 37074, 37075, -1, 37078, 37077, 37079, -1, 37078, 37076, 37077, -1, 37079, 37080, 37078, -1, 37081, 37080, 37079, -1, 37059, 37082, 37058, -1, 37058, 37082, 37083, -1, 37083, 37084, 37085, -1, 37082, 37084, 37083, -1, 37085, 37086, 37087, -1, 37084, 37086, 37085, -1, 37087, 37081, 37079, -1, 37086, 37081, 37087, -1, 37088, 37089, 37090, -1, 37090, 37089, 37091, -1, 31601, 37092, 31602, -1, 37093, 37092, 31601, -1, 37091, 37094, 37095, -1, 37095, 37094, 37096, -1, 37097, 37098, 37099, -1, 37099, 37098, 37100, -1, 37088, 37098, 37089, -1, 37100, 37098, 37088, -1, 37096, 37101, 37093, -1, 37093, 37101, 37092, -1, 37089, 37102, 37091, -1, 37057, 37103, 37055, -1, 37091, 37102, 37094, -1, 37094, 37104, 37096, -1, 37096, 37104, 37101, -1, 31602, 37105, 31603, -1, 37092, 37105, 31602, -1, 37106, 37107, 37108, -1, 37108, 37107, 37097, -1, 37089, 37107, 37102, -1, 37097, 37107, 37098, -1, 37098, 37107, 37089, -1, 37092, 37109, 37105, -1, 37105, 37109, 31603, -1, 37101, 37109, 37092, -1, 37102, 37110, 37094, -1, 37094, 37110, 37104, -1, 37107, 37111, 37102, -1, 37106, 37111, 37107, -1, 37102, 37111, 37110, -1, 37101, 37112, 37109, -1, 37104, 37112, 37101, -1, 31603, 37113, 31607, -1, 31607, 37060, 31611, -1, 37104, 37114, 37112, -1, 37110, 37114, 37104, -1, 31607, 37061, 37060, -1, 37109, 37115, 31603, -1, 31603, 37115, 37113, -1, 37113, 37115, 31607, -1, 31607, 37062, 37061, -1, 37116, 37117, 37118, -1, 37118, 37117, 37106, -1, 37111, 37117, 37110, -1, 37106, 37117, 37111, -1, 37110, 37117, 37114, -1, 37062, 37119, 37063, -1, 37109, 37119, 37115, -1, 37115, 37119, 31607, -1, 31607, 37119, 37062, -1, 37112, 37119, 37109, -1, 37116, 31637, 37065, -1, 37064, 37120, 37065, -1, 37063, 37120, 37064, -1, 37051, 37121, 31610, -1, 37114, 37120, 37112, -1, 31610, 37121, 31606, -1, 37112, 37120, 37119, -1, 37119, 37120, 37063, -1, 37116, 37122, 37117, -1, 37053, 37123, 37051, -1, 37120, 37122, 37065, -1, 37117, 37122, 37114, -1, 37114, 37122, 37120, -1, 37065, 37122, 37116, -1, 37051, 37123, 37121, -1, 31606, 37124, 31605, -1, 37121, 37124, 31606, -1, 37053, 37090, 37123, -1, 37121, 37095, 37124, -1, 37123, 37095, 37121, -1, 31605, 37093, 31601, -1, 37124, 37093, 31605, -1, 37055, 37088, 37053, -1, 37053, 37088, 37090, -1, 37123, 37091, 37095, -1, 37090, 37091, 37123, -1, 37095, 37096, 37124, -1, 37124, 37096, 37093, -1, 37099, 37100, 37103, -1, 37055, 37100, 37088, -1, 37103, 37100, 37055, -1, 37125, 37075, 37072, -1, 37125, 37126, 37127, -1, 37125, 37127, 37075, -1, 37125, 37128, 37126, -1, 37129, 31639, 31638, -1, 37129, 31638, 31637, -1, 37129, 31637, 37130, -1, 37129, 37130, 37131, -1, 37132, 37133, 37134, -1, 37132, 37131, 37133, -1, 37135, 37072, 37070, -1, 37135, 37125, 37072, -1, 37135, 37134, 37128, -1, 37135, 37128, 37125, -1, 37136, 31639, 37129, -1, 37136, 37129, 37131, -1, 37136, 37131, 37132, -1, 37137, 37070, 37068, -1, 37137, 37135, 37070, -1, 37137, 37132, 37134, -1, 37137, 37134, 37135, -1, 37138, 37068, 37066, -1, 37138, 37066, 31641, -1, 37138, 31641, 31640, -1, 37138, 31640, 31639, -1, 37138, 37137, 37068, -1, 37138, 31639, 37136, -1, 37138, 37136, 37132, -1, 37138, 37132, 37137, -1, 37077, 37087, 37079, -1, 37139, 37140, 37058, -1, 37139, 37141, 37140, -1, 37139, 37058, 37083, -1, 37142, 37143, 37141, -1, 37142, 37141, 37139, -1, 37144, 37083, 37085, -1, 37144, 37139, 37083, -1, 37145, 37146, 37143, -1, 37145, 37143, 37142, -1, 37126, 37142, 37139, -1, 37126, 37139, 37144, -1, 37147, 37085, 37087, -1, 37147, 37144, 37085, -1, 37147, 37087, 37077, -1, 37133, 37148, 37146, -1, 37133, 37146, 37145, -1, 37128, 37145, 37142, -1, 37128, 37142, 37126, -1, 37127, 37077, 37075, -1, 37127, 37144, 37147, -1, 37127, 37147, 37077, -1, 37127, 37126, 37144, -1, 37131, 37130, 37148, -1, 37131, 37148, 37133, -1, 37134, 37133, 37145, -1, 37134, 37145, 37128, -1, 37116, 37130, 31637, -1, 37148, 37130, 37116, -1, 37146, 37116, 37118, -1, 37146, 37148, 37116, -1, 37143, 37118, 37106, -1, 37143, 37146, 37118, -1, 37141, 37106, 37108, -1, 37141, 37143, 37106, -1, 37140, 37108, 37097, -1, 37140, 37097, 37099, -1, 37140, 37141, 37108, -1, 37058, 37099, 37103, -1, 37058, 37103, 37057, -1, 37058, 37140, 37099, -1, 31442, 31420, 31427, -1, 31473, 31427, 31430, -1, 31473, 31442, 31427, -1, 31477, 31431, 31432, -1, 31477, 31430, 31431, -1, 31477, 31473, 31430, -1, 31470, 31433, 31439, -1, 31470, 31432, 31433, -1, 31470, 31477, 31432, -1, 31471, 31437, 31436, -1, 31471, 31438, 31437, -1, 31471, 31439, 31438, -1, 31471, 31470, 31439, -1, 31451, 31436, 30114, -1, 31451, 31471, 31436, -1, 33153, 33151, 33144, -1, 33187, 33153, 33144, -1, 33143, 33189, 33187, -1, 33143, 31282, 33189, -1, 31135, 33143, 33142, -1, 31135, 31282, 33143, -1, 31137, 33142, 33141, -1, 31137, 31135, 33142, -1, 30119, 33141, 33146, -1, 30119, 33146, 37149, -1, 30119, 31137, 33141, -1, 30115, 37149, 37150, -1, 30115, 30119, 37149, -1, 30116, 37150, 31460, -1, 30116, 30115, 37150, -1, 30117, 30116, 31460, -1, 33144, 33143, 33187, -1, 31176, 31282, 31133, -1, 31133, 31282, 31135, -1, 37151, 31487, 31454, -1, 37151, 31454, 31453, -1, 37152, 31468, 31487, -1, 37152, 31487, 37151, -1, 33148, 31468, 37152, -1, 31474, 31468, 33148, -1, 33147, 31474, 33148, -1, 33145, 31474, 33147, -1, 33140, 31474, 33145, -1, 37149, 33146, 33148, -1, 37149, 33148, 37152, -1, 37150, 37152, 37151, -1, 37150, 37149, 37152, -1, 31460, 37151, 31453, -1, 31460, 37150, 37151, -1, 31364, 3072, 31366, -1, 31366, 3073, 37153, -1, 3072, 3073, 31366, -1, 37153, 3075, 37154, -1, 3073, 3075, 37153, -1, 37154, 3076, 37155, -1, 3075, 3076, 37154, -1, 37155, 3074, 37156, -1, 37156, 3074, 31396, -1, 31396, 3074, 31395, -1, 3076, 3074, 37155, -1, 31395, 3070, 31369, -1, 3074, 3070, 31395, -1, 37157, 3060, 3059, -1, 37157, 31362, 3060, -1, 37158, 3062, 3063, -1, 37158, 3059, 3062, -1, 37158, 37157, 3059, -1, 31365, 37158, 3063, -1, 31367, 31366, 37159, -1, 37159, 37153, 37160, -1, 31366, 37153, 37159, -1, 37153, 37154, 37160, -1, 37160, 37155, 37161, -1, 37154, 37155, 37160, -1, 37161, 37156, 31393, -1, 37155, 37156, 37161, -1, 37156, 31396, 31393, -1, 31365, 31363, 31367, -1, 31365, 31367, 37162, -1, 37158, 31365, 37162, -1, 37157, 37162, 31298, -1, 37157, 37158, 37162, -1, 31362, 37157, 31298, -1, 31297, 31362, 31298, -1, 37163, 31391, 37164, -1, 37164, 31391, 31389, -1, 31392, 37161, 31393, -1, 31392, 37160, 37161, -1, 37162, 31367, 37159, -1, 31391, 37165, 31392, -1, 37165, 37166, 31392, -1, 31391, 37166, 37165, -1, 31392, 37166, 37160, -1, 37162, 37167, 31298, -1, 31298, 37167, 37163, -1, 37160, 37167, 37159, -1, 31391, 37167, 37166, -1, 37163, 37167, 31391, -1, 37166, 37167, 37160, -1, 37159, 37167, 37162, -1, 31389, 37168, 37164, -1, 31385, 37168, 31389, -1, 37164, 37169, 37163, -1, 37168, 37169, 37164, -1, 37169, 37170, 37163, -1, 37163, 37171, 31298, -1, 37170, 37171, 37163, -1, 37171, 31299, 31298, -1, 37171, 37170, 37172, -1, 37170, 37173, 37172, -1, 37170, 37174, 37173, -1, 37169, 37175, 37170, -1, 37170, 37175, 37174, -1, 37169, 37176, 37175, -1, 37169, 37177, 37176, -1, 37169, 37178, 37177, -1, 37169, 37179, 37178, -1, 37168, 37180, 37169, -1, 37169, 37180, 37179, -1, 3218, 31322, 3220, -1, 31322, 31320, 3220, -1, 3220, 31318, 3221, -1, 31320, 31318, 3220, -1, 3221, 31316, 3222, -1, 31318, 31316, 3221, -1, 3222, 31300, 3219, -1, 31316, 31300, 3222, -1, 3208, 31338, 3210, -1, 31338, 31335, 3210, -1, 3210, 31332, 3211, -1, 31335, 31332, 3210, -1, 3211, 31334, 3212, -1, 31332, 31334, 3211, -1, 3212, 31330, 3209, -1, 31334, 31330, 3212, -1, 30142, 30141, 33078, -1, 30142, 33078, 37181, -1, 30140, 37181, 37182, -1, 30140, 30142, 37181, -1, 30143, 37182, 31082, -1, 30143, 30140, 37182, -1, 3217, 3214, 31355, -1, 31355, 3214, 31353, -1, 31353, 3216, 31357, -1, 3214, 3216, 31353, -1, 31357, 3213, 31359, -1, 3216, 3213, 31357, -1, 31359, 3215, 31331, -1, 3213, 3215, 31359, -1, 33063, 30147, 30144, -1, 37183, 30144, 30146, -1, 37183, 33063, 30144, -1, 37184, 30146, 30145, -1, 37184, 37183, 30146, -1, 31085, 37184, 30145, -1, 33072, 30136, 30139, -1, 37185, 30139, 30138, -1, 37185, 33072, 30139, -1, 37186, 30138, 30137, -1, 37186, 37185, 30138, -1, 31081, 37186, 30137, -1, 31294, 30132, 30135, -1, 31294, 31079, 30132, -1, 31295, 30135, 30134, -1, 31295, 31294, 30135, -1, 31296, 30134, 30133, -1, 31296, 31295, 30134, -1, 31394, 31368, 3071, -1, 31394, 3071, 3067, -1, 37187, 31394, 3067, -1, 37188, 3067, 3066, -1, 37188, 37187, 3067, -1, 31400, 3066, 3065, -1, 31400, 37188, 3066, -1, 31398, 31400, 3065, -1, 37189, 31573, 31538, -1, 37189, 31538, 31536, -1, 37190, 31531, 31402, -1, 37190, 31536, 31531, -1, 37190, 37189, 31536, -1, 31405, 37190, 31402, -1, 31403, 31401, 37191, -1, 31409, 31575, 31576, -1, 31416, 31414, 31583, -1, 31586, 31419, 31585, -1, 31406, 31407, 31587, -1, 37192, 37193, 31589, -1, 37192, 37194, 37193, -1, 37192, 31589, 31574, -1, 37195, 37194, 37192, -1, 37195, 37192, 31574, -1, 37196, 37197, 37194, -1, 37196, 37194, 37195, -1, 37196, 37195, 31574, -1, 37198, 37196, 31574, -1, 37198, 37199, 37197, -1, 37198, 37197, 37196, -1, 37200, 37198, 31574, -1, 37200, 37191, 37199, -1, 37200, 37199, 37198, -1, 37201, 37191, 37200, -1, 37201, 31403, 37191, -1, 37202, 31574, 31575, -1, 37202, 31575, 31409, -1, 37203, 31574, 37202, -1, 37203, 37202, 31409, -1, 37204, 37203, 31409, -1, 37204, 31574, 37203, -1, 37205, 31574, 37204, -1, 37205, 37204, 31409, -1, 37206, 31574, 37205, -1, 37206, 37205, 31409, -1, 37207, 37200, 31574, -1, 37207, 37206, 31409, -1, 37207, 31574, 37206, -1, 37208, 31409, 31403, -1, 37208, 37207, 31409, -1, 37208, 37200, 37207, -1, 37208, 31403, 37201, -1, 37208, 37201, 37200, -1, 37209, 31409, 31576, -1, 37210, 31409, 37209, -1, 37211, 31409, 37210, -1, 37212, 31409, 37211, -1, 37212, 37211, 31411, -1, 37213, 37212, 31411, -1, 37213, 31409, 37212, -1, 37214, 37213, 31411, -1, 37214, 31409, 37213, -1, 37215, 31411, 31409, -1, 37215, 37214, 31411, -1, 37215, 31409, 37214, -1, 37216, 31577, 31578, -1, 37216, 31576, 31577, -1, 37216, 37209, 31576, -1, 37217, 37209, 37216, -1, 37217, 37216, 31578, -1, 37217, 37210, 37209, -1, 37218, 37210, 37217, -1, 37218, 37217, 31578, -1, 37218, 31411, 37211, -1, 37218, 37211, 37210, -1, 37219, 37218, 31578, -1, 37219, 31411, 37218, -1, 37220, 37219, 31578, -1, 37220, 31411, 37219, -1, 37221, 37220, 31578, -1, 37221, 31411, 37220, -1, 37222, 31411, 37221, -1, 37222, 37221, 31578, -1, 37223, 31578, 31579, -1, 37224, 31578, 37223, -1, 37224, 37223, 31412, -1, 37225, 31578, 37224, -1, 37225, 37224, 31412, -1, 37226, 31578, 37225, -1, 37226, 37225, 31412, -1, 37227, 31578, 37226, -1, 37227, 37226, 31412, -1, 37228, 31578, 37227, -1, 37228, 37227, 31412, -1, 37229, 31412, 31411, -1, 37229, 31411, 37222, -1, 37229, 37222, 31578, -1, 37229, 37228, 31412, -1, 37229, 31578, 37228, -1, 37230, 31580, 31581, -1, 37230, 31579, 31580, -1, 37230, 31412, 37223, -1, 37230, 37223, 31579, -1, 37231, 37230, 31581, -1, 37231, 31412, 37230, -1, 37232, 37231, 31581, -1, 37232, 31412, 37231, -1, 37233, 31412, 37232, -1, 37233, 37232, 31581, -1, 37234, 31412, 37233, -1, 37234, 37233, 31581, -1, 37235, 31412, 37234, -1, 37235, 37234, 31581, -1, 37236, 31412, 37235, -1, 37236, 37235, 31581, -1, 37236, 31413, 31412, -1, 37236, 31581, 31413, -1, 37237, 31581, 31582, -1, 37238, 31581, 37237, -1, 37238, 37237, 31582, -1, 37239, 31581, 37238, -1, 37239, 37238, 31582, -1, 37240, 31581, 37239, -1, 37240, 37239, 31582, -1, 37241, 31581, 37240, -1, 37241, 37240, 31582, -1, 37241, 31413, 31581, -1, 37242, 31582, 31583, -1, 37243, 31582, 37242, -1, 37243, 37242, 31583, -1, 37244, 31582, 37243, -1, 37244, 37243, 31583, -1, 37245, 31414, 31413, -1, 37245, 37241, 31582, -1, 37245, 31582, 37244, -1, 37245, 37244, 31583, -1, 37245, 31413, 37241, -1, 37245, 31583, 31414, -1, 37246, 31583, 31584, -1, 37247, 31583, 37246, -1, 37247, 37246, 31584, -1, 37248, 31583, 37247, -1, 37249, 31417, 31416, -1, 37249, 31583, 37248, -1, 37249, 31416, 31583, -1, 37250, 31585, 31418, -1, 37250, 31584, 31585, -1, 37251, 37250, 31418, -1, 37251, 31584, 37250, -1, 37252, 37251, 31418, -1, 37252, 31584, 37251, -1, 37253, 37252, 31418, -1, 37253, 31584, 37252, -1, 37254, 37247, 31584, -1, 37254, 37253, 31418, -1, 37254, 31584, 37253, -1, 37255, 37248, 37247, -1, 37255, 37254, 31418, -1, 37255, 37247, 37254, -1, 37256, 31418, 31417, -1, 37256, 31417, 37249, -1, 37256, 37249, 37248, -1, 37256, 37255, 31418, -1, 37256, 37248, 37255, -1, 37257, 31418, 31585, -1, 37257, 31585, 31419, -1, 37258, 31418, 37257, -1, 37258, 37257, 31419, -1, 37259, 37258, 31419, -1, 37259, 31418, 37258, -1, 37260, 37259, 31419, -1, 37260, 31418, 37259, -1, 37261, 37260, 31419, -1, 37261, 31418, 37260, -1, 37262, 37261, 31419, -1, 37262, 31418, 37261, -1, 37263, 31419, 31418, -1, 37263, 37262, 31419, -1, 37263, 31418, 37262, -1, 37264, 31419, 31586, -1, 37265, 31419, 37264, -1, 37266, 31419, 37265, -1, 37267, 37266, 31408, -1, 37267, 31419, 37266, -1, 37268, 37267, 31408, -1, 37268, 31419, 37267, -1, 37269, 31419, 37268, -1, 37269, 37268, 31408, -1, 37270, 31419, 37269, -1, 37270, 37269, 31408, -1, 37270, 31408, 31419, -1, 37271, 31586, 31587, -1, 37271, 37264, 31586, -1, 37271, 37265, 37264, -1, 37271, 31408, 37266, -1, 37271, 37266, 37265, -1, 37272, 37271, 31587, -1, 37272, 31408, 37271, -1, 37273, 31408, 37272, -1, 37273, 37272, 31587, -1, 37274, 37273, 31587, -1, 37274, 31408, 37273, -1, 37275, 31587, 31407, -1, 37275, 37274, 31587, -1, 37275, 31408, 37274, -1, 37275, 31407, 31408, -1, 37276, 31567, 31568, -1, 37276, 31568, 31569, -1, 37276, 31569, 31570, -1, 37276, 31570, 31571, -1, 37276, 31571, 31572, -1, 37276, 31587, 31567, -1, 37277, 31572, 31573, -1, 37277, 31587, 37276, -1, 37277, 37276, 31572, -1, 37278, 31573, 37189, -1, 37278, 37277, 31573, -1, 37278, 31587, 37277, -1, 37279, 37189, 37190, -1, 37279, 37190, 31405, -1, 37279, 31406, 31587, -1, 37279, 31405, 31406, -1, 37279, 37278, 37189, -1, 37279, 31587, 37278, -1, 31513, 31588, 31589, -1, 31513, 31590, 31588, -1, 31513, 31591, 31590, -1, 31513, 31592, 31591, -1, 31513, 31593, 31592, -1, 31513, 31594, 31593, -1, 31513, 31595, 31594, -1, 31513, 31596, 31595, -1, 31513, 31597, 31596, -1, 31558, 31589, 37193, -1, 31558, 37193, 37194, -1, 31558, 31513, 31589, -1, 31549, 37194, 37197, -1, 31549, 31558, 37194, -1, 31541, 37197, 37199, -1, 31541, 31549, 37197, -1, 31537, 37199, 37191, -1, 31537, 31541, 37199, -1, 31532, 37191, 31401, -1, 31532, 31537, 37191, -1, 31399, 31532, 31401, -1, 37280, 37281, 37282, -1, 37283, 31509, 37284, -1, 37285, 31524, 31514, -1, 37280, 37286, 37281, -1, 37283, 37284, 37287, -1, 37285, 37288, 37289, -1, 37280, 37290, 37291, -1, 37280, 37291, 37286, -1, 37283, 37287, 37292, -1, 37285, 31514, 37288, -1, 37293, 37292, 37294, -1, 37295, 37282, 37296, -1, 37285, 37289, 37297, -1, 37295, 31529, 31534, -1, 37295, 37296, 31529, -1, 37295, 31534, 37298, -1, 37295, 37280, 37282, -1, 37295, 37298, 37290, -1, 37293, 37294, 37299, -1, 37300, 37297, 37301, -1, 37295, 37290, 37280, -1, 37300, 37301, 37302, -1, 37303, 37299, 37304, -1, 37305, 37302, 37306, -1, 31519, 31529, 37296, -1, 37305, 37306, 37307, -1, 37308, 37309, 37310, -1, 37303, 37304, 37311, -1, 37312, 37311, 37313, -1, 37308, 37310, 37314, -1, 37315, 37316, 37317, -1, 37312, 37313, 37318, -1, 37315, 37307, 37316, -1, 37319, 37309, 37308, -1, 37319, 37320, 37309, -1, 37321, 37318, 37322, -1, 37323, 37317, 37324, -1, 37323, 37324, 37325, -1, 37321, 37322, 37326, -1, 37327, 37326, 37328, -1, 37329, 37314, 37330, -1, 37327, 37328, 37331, -1, 37329, 37308, 37314, -1, 37332, 37333, 37334, -1, 37332, 37325, 37333, -1, 37335, 37320, 37319, -1, 37336, 31528, 31524, -1, 37337, 37292, 37293, -1, 37335, 37338, 37320, -1, 37337, 37283, 37292, -1, 37337, 31562, 31507, -1, 37336, 37285, 37297, -1, 37336, 37297, 37300, -1, 37337, 31507, 37283, -1, 37336, 31524, 37285, -1, 37339, 37293, 37299, -1, 37340, 37300, 37302, -1, 37339, 37299, 37303, -1, 37340, 37302, 37305, -1, 37341, 37319, 37308, -1, 37341, 37308, 37329, -1, 37342, 37311, 37312, -1, 37343, 37305, 37307, -1, 37343, 37307, 37315, -1, 37342, 37303, 37311, -1, 37344, 37330, 37345, -1, 37346, 37317, 37323, -1, 37344, 37329, 37330, -1, 37347, 37318, 37321, -1, 37346, 37315, 37317, -1, 37348, 37349, 37338, -1, 37348, 37338, 37335, -1, 37347, 37312, 37318, -1, 37350, 37326, 37327, -1, 37351, 37323, 37325, -1, 37352, 37335, 37319, -1, 37351, 37325, 37332, -1, 37352, 37319, 37341, -1, 37350, 37321, 37326, -1, 37353, 37354, 37355, -1, 37356, 37329, 37344, -1, 37353, 37327, 37331, -1, 37353, 37357, 37354, -1, 37358, 37334, 37359, -1, 37353, 37331, 37357, -1, 37358, 37332, 37334, -1, 37360, 31544, 31562, -1, 37360, 31562, 37337, -1, 37361, 31522, 31528, -1, 37356, 37341, 37329, -1, 37360, 37337, 37293, -1, 37361, 31528, 37336, -1, 37360, 37293, 37339, -1, 37361, 37336, 37300, -1, 37361, 37300, 37340, -1, 37362, 37345, 37363, -1, 37287, 37340, 37305, -1, 37364, 37339, 37303, -1, 37362, 37344, 37345, -1, 37364, 37303, 37342, -1, 37287, 37305, 37343, -1, 37289, 37365, 37349, -1, 37366, 37342, 37312, -1, 37294, 37343, 37315, -1, 37289, 37349, 37348, -1, 37294, 37315, 37346, -1, 37366, 37312, 37347, -1, 37304, 37323, 37351, -1, 37301, 37348, 37335, -1, 37367, 37347, 37321, -1, 37301, 37335, 37352, -1, 37304, 37346, 37323, -1, 37367, 37321, 37350, -1, 37306, 37341, 37356, -1, 37306, 37352, 37341, -1, 37368, 37355, 37369, -1, 37368, 37353, 37355, -1, 37368, 37350, 37327, -1, 37368, 37327, 37353, -1, 37313, 37351, 37332, -1, 37370, 31544, 37360, -1, 37313, 37332, 37358, -1, 37370, 31542, 31544, -1, 37370, 37339, 37364, -1, 37370, 37360, 37339, -1, 37316, 37356, 37344, -1, 37316, 37344, 37362, -1, 37322, 37359, 37371, -1, 37322, 37358, 37359, -1, 37372, 37342, 37366, -1, 37324, 37363, 37373, -1, 37372, 37364, 37342, -1, 37284, 31509, 31522, -1, 37324, 37362, 37363, -1, 37284, 31522, 37361, -1, 37288, 31514, 31516, -1, 37284, 37340, 37287, -1, 37288, 37374, 37365, -1, 37284, 37361, 37340, -1, 37288, 31516, 37374, -1, 37291, 37347, 37367, -1, 37288, 37365, 37289, -1, 37291, 37366, 37347, -1, 37292, 37343, 37294, -1, 37292, 37287, 37343, -1, 37375, 37369, 37376, -1, 37375, 37368, 37369, -1, 37297, 37348, 37301, -1, 37375, 37367, 37350, -1, 37375, 37350, 37368, -1, 37297, 37289, 37348, -1, 37377, 31539, 31542, -1, 37299, 37294, 37346, -1, 37299, 37346, 37304, -1, 37377, 31542, 37370, -1, 37302, 37352, 37306, -1, 37377, 37370, 37364, -1, 37377, 37364, 37372, -1, 37302, 37301, 37352, -1, 37311, 37304, 37351, -1, 37307, 37356, 37316, -1, 37311, 37351, 37313, -1, 37290, 37372, 37366, -1, 37290, 37366, 37291, -1, 37307, 37306, 37356, -1, 37286, 37376, 37281, -1, 37286, 37375, 37376, -1, 37286, 37291, 37367, -1, 37317, 37316, 37362, -1, 37286, 37367, 37375, -1, 37318, 37313, 37358, -1, 37317, 37362, 37324, -1, 37318, 37358, 37322, -1, 37298, 31534, 31539, -1, 37298, 37377, 37372, -1, 37326, 37371, 37328, -1, 37298, 31539, 37377, -1, 37326, 37322, 37371, -1, 37325, 37373, 37333, -1, 37298, 37372, 37290, -1, 37283, 31507, 31509, -1, 37325, 37324, 37373, -1, 37378, 37357, 37379, -1, 37354, 37357, 37378, -1, 37379, 37331, 37380, -1, 37357, 37331, 37379, -1, 37380, 37328, 37381, -1, 37331, 37328, 37380, -1, 37381, 37371, 37382, -1, 37328, 37371, 37381, -1, 37382, 37359, 37383, -1, 37371, 37359, 37382, -1, 37383, 37334, 37384, -1, 37359, 37334, 37383, -1, 37384, 37333, 37385, -1, 37334, 37333, 37384, -1, 37385, 37373, 37386, -1, 37333, 37373, 37385, -1, 37386, 37363, 37387, -1, 37373, 37363, 37386, -1, 37387, 37345, 37388, -1, 37363, 37345, 37387, -1, 37388, 37330, 37389, -1, 37345, 37330, 37388, -1, 37389, 37314, 37390, -1, 37330, 37314, 37389, -1, 37390, 37310, 37391, -1, 37314, 37310, 37390, -1, 37392, 37378, 37393, -1, 37354, 37378, 37392, -1, 37394, 37395, 37396, -1, 37397, 37395, 37394, -1, 37396, 37398, 37399, -1, 37395, 37398, 37396, -1, 37399, 37400, 37401, -1, 37398, 37400, 37399, -1, 37401, 37402, 37403, -1, 37400, 37402, 37401, -1, 37403, 37404, 37405, -1, 37402, 37404, 37403, -1, 37405, 37406, 37407, -1, 37404, 37406, 37405, -1, 37407, 37408, 37409, -1, 37406, 37408, 37407, -1, 37409, 37410, 37411, -1, 37408, 37410, 37409, -1, 37411, 37412, 37413, -1, 37410, 37412, 37411, -1, 37413, 37414, 37415, -1, 37412, 37414, 37413, -1, 37415, 37416, 37417, -1, 37414, 37416, 37415, -1, 37417, 37418, 37419, -1, 37416, 37418, 37417, -1, 37419, 37392, 37393, -1, 37418, 37392, 37419, -1, 37394, 37310, 37397, -1, 37391, 37310, 37394, -1, 37420, 37310, 37309, -1, 37420, 37397, 37310, -1, 37421, 37309, 37320, -1, 37421, 37420, 37309, -1, 37422, 37320, 37338, -1, 37422, 37421, 37320, -1, 37423, 37338, 37349, -1, 37423, 37422, 37338, -1, 37424, 37349, 37365, -1, 37424, 37423, 37349, -1, 37425, 37365, 37374, -1, 37425, 37424, 37365, -1, 31554, 37374, 31516, -1, 31554, 37425, 37374, -1, 37355, 37354, 37392, -1, 37355, 37392, 37426, -1, 37369, 37426, 37427, -1, 37369, 37355, 37426, -1, 37376, 37427, 37428, -1, 37376, 37369, 37427, -1, 37281, 37428, 37429, -1, 37281, 37376, 37428, -1, 37282, 37429, 37430, -1, 37282, 37281, 37429, -1, 37296, 37430, 37431, -1, 37296, 37282, 37430, -1, 31519, 37431, 31523, -1, 31519, 37296, 37431, -1, 37432, 37433, 37423, -1, 37434, 31553, 31560, -1, 37432, 37435, 37436, -1, 37437, 31557, 37438, -1, 37434, 37439, 37440, -1, 37432, 37436, 37433, -1, 37437, 37438, 37441, -1, 37434, 37442, 37439, -1, 37437, 37441, 37443, -1, 37444, 37424, 37425, -1, 37434, 31560, 37442, -1, 37444, 37425, 31554, -1, 37444, 31550, 31533, -1, 37444, 31554, 31550, -1, 37444, 37445, 37435, -1, 37444, 37435, 37432, -1, 37446, 37447, 37448, -1, 37444, 37432, 37424, -1, 37446, 37443, 37447, -1, 37444, 31533, 37445, -1, 37449, 37448, 37450, -1, 37451, 37440, 37452, -1, 37451, 37452, 37453, -1, 37454, 37453, 37455, -1, 37454, 37455, 37456, -1, 37449, 37450, 37457, -1, 37458, 37457, 37459, -1, 37460, 37426, 37392, -1, 37461, 37462, 37463, -1, 37460, 37392, 37418, -1, 37458, 37459, 37464, -1, 37461, 37456, 37462, -1, 37465, 37464, 37466, -1, 37467, 37426, 37460, -1, 37468, 37463, 37469, -1, 37467, 37427, 37426, -1, 37465, 37466, 37470, -1, 37468, 37469, 37471, -1, 37472, 37470, 37400, -1, 37472, 37400, 37398, -1, 37473, 37408, 37406, -1, 37474, 37418, 37416, -1, 37473, 37471, 37408, -1, 37475, 31566, 31563, -1, 37474, 37460, 37418, -1, 37475, 37443, 37446, -1, 37476, 31546, 31553, -1, 37476, 31553, 37434, -1, 37477, 37427, 37467, -1, 37475, 31563, 37437, -1, 37476, 37434, 37440, -1, 37475, 37437, 37443, -1, 37476, 37440, 37451, -1, 37477, 37428, 37427, -1, 37478, 37446, 37448, -1, 37479, 37453, 37454, -1, 37480, 37467, 37460, -1, 37478, 37448, 37449, -1, 37479, 37451, 37453, -1, 37481, 37449, 37457, -1, 37480, 37460, 37474, -1, 31560, 31523, 37431, -1, 37482, 37454, 37456, -1, 37482, 37456, 37461, -1, 37481, 37457, 37458, -1, 37483, 37416, 37414, -1, 37484, 37463, 37468, -1, 37485, 37464, 37465, -1, 37483, 37474, 37416, -1, 37484, 37461, 37463, -1, 37485, 37458, 37464, -1, 37486, 37429, 37428, -1, 37486, 37428, 37477, -1, 37487, 37470, 37472, -1, 37487, 37465, 37470, -1, 37488, 37467, 37480, -1, 37489, 37468, 37471, -1, 37488, 37477, 37467, -1, 37489, 37471, 37473, -1, 37490, 37472, 37398, -1, 37490, 37398, 37395, -1, 37491, 37474, 37483, -1, 37490, 37395, 37420, -1, 37492, 37406, 37404, -1, 37493, 31511, 31566, -1, 37492, 37473, 37406, -1, 37493, 37446, 37478, -1, 37494, 31548, 31546, -1, 37493, 37475, 37446, -1, 37491, 37480, 37474, -1, 37493, 31566, 37475, -1, 37494, 31546, 37476, -1, 37494, 37476, 37451, -1, 37494, 37451, 37479, -1, 37495, 37449, 37481, -1, 37496, 37414, 37412, -1, 37495, 37478, 37449, -1, 37496, 37483, 37414, -1, 37441, 37479, 37454, -1, 37441, 37454, 37482, -1, 37497, 37481, 37458, -1, 37439, 37430, 37429, -1, 37497, 37458, 37485, -1, 37447, 37482, 37461, -1, 37447, 37461, 37484, -1, 37439, 37429, 37486, -1, 37452, 37477, 37488, -1, 37498, 37485, 37465, -1, 37452, 37486, 37477, -1, 37498, 37465, 37487, -1, 37450, 37484, 37468, -1, 37499, 37420, 37421, -1, 37450, 37468, 37489, -1, 37499, 37490, 37420, -1, 37455, 37480, 37491, -1, 37499, 37487, 37472, -1, 37459, 37489, 37473, -1, 37499, 37472, 37490, -1, 37455, 37488, 37480, -1, 37500, 31512, 31511, -1, 37459, 37473, 37492, -1, 37500, 31511, 37493, -1, 37500, 37493, 37478, -1, 37500, 37478, 37495, -1, 37462, 37491, 37483, -1, 37462, 37483, 37496, -1, 37501, 37495, 37481, -1, 37466, 37404, 37402, -1, 37501, 37481, 37497, -1, 37466, 37492, 37404, -1, 37438, 31557, 31548, -1, 37469, 37412, 37410, -1, 37438, 37494, 37479, -1, 37469, 37496, 37412, -1, 37438, 37479, 37441, -1, 37438, 31548, 37494, -1, 37442, 37430, 37439, -1, 37442, 37431, 37430, -1, 37442, 31560, 37431, -1, 37436, 37497, 37485, -1, 37436, 37485, 37498, -1, 37443, 37482, 37447, -1, 37502, 37421, 37422, -1, 37443, 37441, 37482, -1, 37502, 37499, 37421, -1, 37502, 37498, 37487, -1, 37502, 37487, 37499, -1, 37440, 37486, 37452, -1, 37440, 37439, 37486, -1, 37503, 37495, 37501, -1, 37448, 37447, 37484, -1, 37503, 31526, 31512, -1, 37448, 37484, 37450, -1, 37420, 37395, 37397, -1, 37453, 37452, 37488, -1, 37503, 31512, 37500, -1, 37453, 37488, 37455, -1, 37503, 37500, 37495, -1, 37457, 37489, 37459, -1, 37456, 37491, 37462, -1, 37457, 37450, 37489, -1, 37435, 37501, 37497, -1, 37435, 37497, 37436, -1, 37456, 37455, 37491, -1, 37433, 37422, 37423, -1, 37433, 37502, 37422, -1, 37433, 37436, 37498, -1, 37463, 37496, 37469, -1, 37433, 37498, 37502, -1, 37464, 37459, 37492, -1, 37464, 37492, 37466, -1, 37445, 31533, 31526, -1, 37463, 37462, 37496, -1, 37445, 31526, 37503, -1, 37445, 37503, 37501, -1, 37470, 37402, 37400, -1, 37445, 37501, 37435, -1, 37470, 37466, 37402, -1, 37432, 37423, 37424, -1, 37471, 37410, 37408, -1, 37471, 37469, 37410, -1, 37437, 31563, 31557, -1, 37504, 31333, 31337, -1, 37505, 31333, 37504, -1, 37505, 37504, 31337, -1, 37506, 31333, 37505, -1, 37506, 37507, 31333, -1, 37508, 31337, 31336, -1, 37509, 31337, 37508, -1, 37510, 37507, 37506, -1, 37510, 37511, 37507, -1, 37510, 31337, 37509, -1, 37510, 37509, 37511, -1, 37510, 37505, 31337, -1, 37510, 37506, 37505, -1, 37512, 31336, 31339, -1, 31333, 37513, 31361, -1, 31333, 37514, 37513, -1, 37512, 37508, 31336, -1, 31333, 37515, 37514, -1, 31333, 37516, 37515, -1, 37517, 37508, 37512, -1, 31333, 37518, 37516, -1, 37517, 37509, 37508, -1, 31333, 37519, 37518, -1, 31333, 37520, 37519, -1, 37517, 37511, 37509, -1, 37517, 37512, 37521, -1, 37522, 37517, 37521, -1, 37522, 37511, 37517, -1, 37522, 37521, 37511, -1, 37523, 31339, 31347, -1, 37523, 37512, 31339, -1, 37523, 37521, 37512, -1, 37507, 37520, 31333, -1, 37524, 37521, 37523, -1, 37525, 37521, 37524, -1, 37525, 37526, 37521, -1, 37525, 37524, 37526, -1, 37527, 31347, 31360, -1, 37527, 37523, 31347, -1, 37528, 37523, 37527, -1, 37528, 37526, 37524, -1, 37528, 37527, 37529, -1, 37528, 37524, 37523, -1, 37530, 37528, 37529, -1, 37530, 37529, 37526, -1, 37530, 37526, 37528, -1, 37531, 31352, 31351, -1, 37531, 31360, 31352, -1, 37531, 37529, 37527, -1, 37531, 37527, 31360, -1, 37532, 37529, 37531, -1, 37532, 37531, 37533, -1, 37534, 37533, 37529, -1, 37534, 37532, 37533, -1, 37534, 37529, 37532, -1, 37535, 31351, 31350, -1, 37535, 37531, 31351, -1, 37535, 37533, 37531, -1, 37536, 37535, 37537, -1, 37536, 37533, 37535, -1, 37538, 37537, 37533, -1, 37538, 37536, 37537, -1, 37538, 37533, 37536, -1, 37539, 37537, 37535, -1, 37539, 37535, 31350, -1, 37539, 31350, 37540, -1, 37541, 37537, 37539, -1, 37541, 37539, 37540, -1, 37542, 37540, 37537, -1, 37542, 37541, 37540, -1, 37542, 37537, 37541, -1, 37543, 31346, 37544, -1, 37543, 37540, 31346, -1, 37545, 37543, 37544, -1, 37545, 37540, 37543, -1, 37546, 37544, 37540, -1, 37546, 37545, 37544, -1, 37546, 37540, 37545, -1, 37547, 37544, 31340, -1, 37548, 37544, 37547, -1, 37540, 31350, 31346, -1, 37549, 37550, 37544, -1, 37549, 37544, 37548, -1, 37549, 37548, 37550, -1, 37551, 37547, 31340, -1, 37551, 31340, 31342, -1, 31340, 37544, 31346, -1, 37552, 37547, 37551, -1, 37552, 37551, 31342, -1, 37552, 37548, 37547, -1, 37552, 37550, 37548, -1, 37553, 37550, 37552, -1, 37553, 37552, 31342, -1, 37554, 37555, 37550, -1, 37554, 37556, 37555, -1, 37554, 37550, 37553, -1, 37557, 31342, 31343, -1, 37558, 31342, 37557, -1, 37558, 37553, 31342, -1, 37558, 37557, 31343, -1, 37559, 37556, 37554, -1, 37559, 37554, 37553, -1, 37559, 37553, 37558, -1, 37560, 31343, 31354, -1, 37561, 31343, 37560, -1, 37561, 37558, 31343, -1, 31358, 37562, 31354, -1, 37561, 37560, 37563, -1, 37564, 37558, 37561, -1, 37564, 37561, 37563, -1, 37565, 37562, 31358, -1, 37564, 37566, 37556, -1, 37564, 37563, 37566, -1, 37564, 37559, 37558, -1, 37567, 37562, 37565, -1, 37564, 37556, 37559, -1, 37568, 31354, 37562, -1, 37569, 37562, 37567, -1, 37568, 37560, 31354, -1, 37570, 37568, 37562, -1, 37570, 37560, 37568, -1, 37571, 37562, 37569, -1, 37570, 37563, 37560, -1, 37572, 37570, 37562, -1, 37572, 37563, 37570, -1, 37573, 37562, 37571, -1, 37572, 37562, 37563, -1, 37574, 37562, 37573, -1, 37575, 37562, 37574, -1, 37575, 37576, 37562, -1, 37562, 37577, 37563, -1, 37576, 37577, 37562, -1, 37566, 37578, 37556, -1, 37563, 37578, 37566, -1, 37577, 37578, 37563, -1, 37556, 37579, 37555, -1, 37578, 37579, 37556, -1, 37555, 37580, 37550, -1, 37579, 37580, 37555, -1, 37544, 37581, 37540, -1, 37550, 37581, 37544, -1, 37580, 37581, 37550, -1, 37540, 37582, 37537, -1, 37581, 37582, 37540, -1, 37537, 37583, 37533, -1, 37582, 37583, 37537, -1, 37529, 37584, 37526, -1, 37533, 37584, 37529, -1, 37583, 37584, 37533, -1, 37526, 37585, 37521, -1, 37584, 37585, 37526, -1, 37521, 37586, 37511, -1, 37585, 37586, 37521, -1, 37511, 37587, 37507, -1, 37586, 37587, 37511, -1, 37507, 37588, 37520, -1, 37587, 37588, 37507, -1, 37588, 37589, 37520, -1, 37576, 37575, 37590, -1, 37520, 37589, 37591, -1, 37592, 37585, 37593, -1, 37594, 37584, 37595, -1, 37593, 37584, 37594, -1, 37585, 37584, 37593, -1, 37596, 37597, 37591, -1, 37591, 37598, 37596, -1, 37597, 37599, 37591, -1, 37595, 37583, 37600, -1, 37584, 37583, 37595, -1, 37591, 37601, 37598, -1, 37602, 37576, 37590, -1, 37603, 37576, 37602, -1, 37604, 37576, 37603, -1, 37591, 37605, 37606, -1, 37599, 37605, 37591, -1, 37583, 37582, 37600, -1, 37591, 37607, 37601, -1, 37604, 37577, 37576, -1, 37608, 37581, 37609, -1, 37600, 37581, 37608, -1, 37582, 37581, 37600, -1, 37610, 37578, 37604, -1, 37611, 37578, 37610, -1, 37604, 37578, 37577, -1, 37612, 37613, 37614, -1, 37615, 37613, 37612, -1, 37609, 37580, 37611, -1, 37581, 37580, 37609, -1, 37580, 37579, 37611, -1, 37616, 37617, 37615, -1, 37611, 37579, 37578, -1, 37615, 37617, 37613, -1, 37618, 37619, 37605, -1, 37606, 37619, 37616, -1, 37605, 37619, 37606, -1, 37616, 37619, 37617, -1, 37620, 37590, 37618, -1, 37618, 37590, 37619, -1, 37620, 37621, 37590, -1, 37591, 37589, 37607, -1, 37621, 37622, 37590, -1, 37622, 37623, 37590, -1, 37589, 37624, 37607, -1, 37623, 37625, 37590, -1, 37589, 37626, 37624, -1, 37588, 37626, 37589, -1, 37625, 37602, 37590, -1, 37587, 37627, 37588, -1, 37588, 37627, 37626, -1, 37587, 37592, 37627, -1, 37586, 37592, 37587, -1, 37586, 37585, 37592, -1, 37628, 37629, 37630, -1, 37631, 37610, 37604, -1, 37628, 37632, 37633, -1, 37634, 37608, 37635, -1, 37628, 37633, 37629, -1, 37634, 37635, 37636, -1, 37631, 37637, 37638, -1, 37634, 37636, 37639, -1, 37631, 37638, 37640, -1, 37641, 37642, 37624, -1, 37643, 37644, 37645, -1, 37631, 37604, 37637, -1, 37641, 37646, 37642, -1, 37641, 37626, 37627, -1, 37641, 37624, 37626, -1, 37641, 37627, 37647, -1, 37641, 37628, 37646, -1, 37641, 37647, 37632, -1, 37643, 37639, 37644, -1, 37648, 37649, 37650, -1, 37641, 37632, 37628, -1, 37651, 37652, 37653, -1, 37648, 37640, 37649, -1, 37651, 37645, 37652, -1, 37654, 37655, 37656, -1, 37654, 37650, 37655, -1, 37657, 37658, 37659, -1, 37660, 37653, 37661, -1, 37662, 37656, 37663, -1, 37657, 37659, 37664, -1, 37660, 37661, 37665, -1, 37662, 37663, 37666, -1, 37667, 37665, 37668, -1, 37669, 37658, 37657, -1, 37669, 37670, 37658, -1, 37671, 37666, 37672, -1, 37667, 37668, 37673, -1, 37671, 37672, 37674, -1, 37675, 37673, 37676, -1, 37675, 37676, 37677, -1, 37678, 37664, 37679, -1, 37680, 37681, 37682, -1, 37678, 37657, 37664, -1, 37683, 37634, 37639, -1, 37680, 37674, 37681, -1, 37683, 37595, 37600, -1, 37684, 37611, 37610, -1, 37683, 37639, 37643, -1, 37685, 37670, 37669, -1, 37684, 37610, 37631, -1, 37684, 37631, 37640, -1, 37685, 37686, 37670, -1, 37683, 37600, 37634, -1, 37684, 37640, 37648, -1, 37687, 37645, 37651, -1, 37688, 37650, 37654, -1, 37688, 37648, 37650, -1, 37687, 37643, 37645, -1, 37689, 37669, 37657, -1, 37689, 37657, 37678, -1, 37690, 37654, 37656, -1, 37604, 37603, 37691, -1, 37690, 37656, 37662, -1, 37692, 37651, 37653, -1, 37692, 37653, 37660, -1, 37693, 37666, 37671, -1, 37694, 37679, 37695, -1, 37696, 37660, 37665, -1, 37696, 37665, 37667, -1, 37693, 37662, 37666, -1, 37694, 37678, 37679, -1, 37697, 37698, 37686, -1, 37697, 37686, 37685, -1, 37699, 37667, 37673, -1, 37700, 37671, 37674, -1, 37699, 37673, 37675, -1, 37701, 37685, 37669, -1, 37700, 37674, 37680, -1, 37701, 37669, 37689, -1, 37702, 37675, 37677, -1, 37703, 37678, 37694, -1, 37702, 37677, 37704, -1, 37702, 37704, 37705, -1, 37706, 37682, 37707, -1, 37708, 37594, 37595, -1, 37706, 37680, 37682, -1, 37708, 37683, 37643, -1, 37709, 37609, 37611, -1, 37708, 37643, 37687, -1, 37708, 37595, 37683, -1, 37709, 37611, 37684, -1, 37703, 37689, 37678, -1, 37709, 37684, 37648, -1, 37709, 37648, 37688, -1, 37710, 37687, 37651, -1, 37710, 37651, 37692, -1, 37711, 37695, 37712, -1, 37636, 37688, 37654, -1, 37711, 37694, 37695, -1, 37636, 37654, 37690, -1, 37713, 37660, 37696, -1, 37638, 37714, 37698, -1, 37713, 37692, 37660, -1, 37644, 37690, 37662, -1, 37638, 37698, 37697, -1, 37644, 37662, 37693, -1, 37649, 37697, 37685, -1, 37649, 37685, 37701, -1, 37652, 37693, 37671, -1, 37715, 37667, 37699, -1, 37715, 37696, 37667, -1, 37652, 37671, 37700, -1, 37716, 37705, 37717, -1, 37716, 37699, 37675, -1, 37655, 37689, 37703, -1, 37716, 37675, 37702, -1, 37655, 37701, 37689, -1, 37716, 37702, 37705, -1, 37661, 37700, 37680, -1, 37718, 37593, 37594, -1, 37661, 37680, 37706, -1, 37718, 37687, 37710, -1, 37718, 37594, 37708, -1, 37718, 37708, 37687, -1, 37663, 37703, 37694, -1, 37668, 37707, 37719, -1, 37663, 37694, 37711, -1, 37668, 37706, 37707, -1, 37720, 37710, 37692, -1, 37720, 37692, 37713, -1, 37635, 37608, 37609, -1, 37672, 37712, 37721, -1, 37672, 37711, 37712, -1, 37635, 37688, 37636, -1, 37635, 37609, 37709, -1, 37637, 37691, 37714, -1, 37635, 37709, 37688, -1, 37639, 37690, 37644, -1, 37637, 37714, 37638, -1, 37633, 37713, 37696, -1, 37637, 37604, 37691, -1, 37633, 37696, 37715, -1, 37639, 37636, 37690, -1, 37722, 37717, 37723, -1, 37722, 37699, 37716, -1, 37722, 37715, 37699, -1, 37640, 37697, 37649, -1, 37722, 37716, 37717, -1, 37640, 37638, 37697, -1, 37724, 37592, 37593, -1, 37650, 37701, 37655, -1, 37705, 37704, 37725, -1, 37724, 37593, 37718, -1, 37645, 37693, 37652, -1, 37724, 37718, 37710, -1, 37645, 37644, 37693, -1, 37724, 37710, 37720, -1, 37650, 37649, 37701, -1, 37632, 37720, 37713, -1, 37653, 37652, 37700, -1, 37653, 37700, 37661, -1, 37656, 37655, 37703, -1, 37632, 37713, 37633, -1, 37656, 37703, 37663, -1, 37629, 37723, 37630, -1, 37629, 37722, 37723, -1, 37629, 37633, 37715, -1, 37629, 37715, 37722, -1, 37665, 37661, 37706, -1, 37666, 37663, 37711, -1, 37665, 37706, 37668, -1, 37666, 37711, 37672, -1, 37647, 37592, 37724, -1, 37647, 37627, 37592, -1, 37647, 37724, 37720, -1, 37647, 37720, 37632, -1, 37673, 37719, 37676, -1, 37674, 37721, 37681, -1, 37673, 37668, 37719, -1, 37628, 37630, 37646, -1, 37634, 37600, 37608, -1, 37674, 37672, 37721, -1, 37726, 37704, 37727, -1, 37725, 37704, 37726, -1, 37727, 37677, 37728, -1, 37704, 37677, 37727, -1, 37728, 37676, 37729, -1, 37677, 37676, 37728, -1, 37729, 37719, 37730, -1, 37676, 37719, 37729, -1, 37730, 37707, 37731, -1, 37719, 37707, 37730, -1, 37731, 37682, 37732, -1, 37707, 37682, 37731, -1, 37732, 37681, 37733, -1, 37682, 37681, 37732, -1, 37733, 37721, 37734, -1, 37681, 37721, 37733, -1, 37734, 37712, 37735, -1, 37721, 37712, 37734, -1, 37735, 37695, 37736, -1, 37712, 37695, 37735, -1, 37736, 37679, 37737, -1, 37695, 37679, 37736, -1, 37737, 37664, 37738, -1, 37679, 37664, 37737, -1, 37738, 37659, 37739, -1, 37664, 37659, 37738, -1, 37740, 37726, 37741, -1, 37725, 37726, 37740, -1, 37742, 37743, 37744, -1, 37745, 37743, 37742, -1, 37744, 37746, 37747, -1, 37743, 37746, 37744, -1, 37747, 37748, 37749, -1, 37746, 37748, 37747, -1, 37749, 37750, 37751, -1, 37748, 37750, 37749, -1, 37751, 37752, 37753, -1, 37750, 37752, 37751, -1, 37753, 37754, 37755, -1, 37752, 37754, 37753, -1, 37755, 37756, 37757, -1, 37754, 37756, 37755, -1, 37757, 37758, 37759, -1, 37756, 37758, 37757, -1, 37759, 37760, 37761, -1, 37758, 37760, 37759, -1, 37761, 37762, 37763, -1, 37760, 37762, 37761, -1, 37763, 37764, 37765, -1, 37762, 37764, 37763, -1, 37765, 37766, 37767, -1, 37764, 37766, 37765, -1, 37767, 37740, 37741, -1, 37766, 37740, 37767, -1, 37742, 37659, 37745, -1, 37739, 37659, 37742, -1, 37768, 37659, 37658, -1, 37768, 37745, 37659, -1, 37769, 37658, 37670, -1, 37769, 37768, 37658, -1, 37770, 37670, 37686, -1, 37770, 37769, 37670, -1, 37771, 37686, 37698, -1, 37771, 37770, 37686, -1, 37772, 37698, 37714, -1, 37772, 37771, 37698, -1, 37773, 37714, 37691, -1, 37773, 37772, 37714, -1, 37602, 37691, 37603, -1, 37602, 37773, 37691, -1, 37705, 37725, 37740, -1, 37705, 37740, 37774, -1, 37717, 37774, 37775, -1, 37717, 37705, 37774, -1, 37723, 37775, 37776, -1, 37723, 37717, 37775, -1, 37630, 37776, 37777, -1, 37630, 37723, 37776, -1, 37646, 37777, 37778, -1, 37646, 37630, 37777, -1, 37642, 37778, 37779, -1, 37642, 37646, 37778, -1, 37624, 37779, 37607, -1, 37624, 37642, 37779, -1, 37780, 37605, 37599, -1, 37781, 37598, 37601, -1, 37782, 37783, 37784, -1, 37780, 37785, 37786, -1, 37782, 37787, 37771, -1, 37780, 37599, 37788, -1, 37780, 37788, 37785, -1, 37781, 37789, 37790, -1, 37782, 37784, 37787, -1, 37781, 37790, 37791, -1, 37781, 37601, 37789, -1, 37792, 37772, 37773, -1, 37792, 37625, 37623, -1, 37792, 37773, 37625, -1, 37792, 37623, 37793, -1, 37792, 37782, 37772, -1, 37794, 37795, 37796, -1, 37797, 37798, 37799, -1, 37766, 37774, 37740, -1, 37792, 37793, 37783, -1, 37794, 37786, 37795, -1, 37792, 37783, 37782, -1, 37797, 37791, 37798, -1, 37800, 37796, 37801, -1, 37602, 37625, 37773, -1, 37802, 37799, 37803, -1, 37800, 37801, 37804, -1, 37802, 37803, 37805, -1, 37806, 37774, 37766, -1, 37807, 37808, 37809, -1, 37810, 37805, 37811, -1, 37807, 37804, 37808, -1, 37810, 37811, 37812, -1, 37813, 37774, 37806, -1, 37814, 37809, 37815, -1, 37813, 37775, 37774, -1, 37816, 37812, 37817, -1, 37816, 37817, 37818, -1, 37814, 37815, 37819, -1, 37820, 37766, 37764, -1, 37821, 37819, 37748, -1, 37820, 37806, 37766, -1, 37821, 37748, 37746, -1, 37822, 37756, 37754, -1, 37822, 37818, 37756, -1, 37823, 37780, 37786, -1, 37823, 37786, 37794, -1, 37824, 37596, 37598, -1, 37825, 37775, 37813, -1, 37823, 37618, 37605, -1, 37824, 37598, 37781, -1, 37824, 37781, 37791, -1, 37825, 37776, 37775, -1, 37824, 37791, 37797, -1, 37823, 37605, 37780, -1, 37826, 37794, 37796, -1, 37827, 37797, 37799, -1, 37827, 37799, 37802, -1, 37826, 37796, 37800, -1, 37828, 37813, 37806, -1, 37828, 37806, 37820, -1, 37829, 37802, 37805, -1, 37830, 37804, 37807, -1, 37829, 37805, 37810, -1, 37831, 37764, 37762, -1, 37831, 37820, 37764, -1, 37830, 37800, 37804, -1, 37832, 37809, 37814, -1, 37833, 37810, 37812, -1, 37833, 37812, 37816, -1, 37834, 37777, 37776, -1, 37832, 37807, 37809, -1, 37834, 37776, 37825, -1, 37835, 37819, 37821, -1, 37836, 37816, 37818, -1, 37837, 37825, 37813, -1, 37836, 37818, 37822, -1, 37837, 37813, 37828, -1, 37835, 37814, 37819, -1, 37838, 37745, 37768, -1, 37839, 37820, 37831, -1, 37838, 37821, 37746, -1, 37838, 37743, 37745, -1, 37840, 37754, 37752, -1, 37838, 37746, 37743, -1, 37840, 37822, 37754, -1, 37841, 37618, 37823, -1, 37842, 37597, 37596, -1, 37839, 37828, 37820, -1, 37841, 37620, 37618, -1, 37842, 37596, 37824, -1, 37841, 37794, 37826, -1, 37842, 37824, 37797, -1, 37841, 37823, 37794, -1, 37842, 37797, 37827, -1, 37843, 37762, 37760, -1, 37844, 37800, 37830, -1, 37843, 37831, 37762, -1, 37844, 37826, 37800, -1, 37785, 37827, 37802, -1, 37785, 37802, 37829, -1, 37790, 37778, 37777, -1, 37790, 37777, 37834, -1, 37845, 37830, 37807, -1, 37795, 37829, 37810, -1, 37845, 37807, 37832, -1, 37795, 37810, 37833, -1, 37798, 37825, 37837, -1, 37798, 37834, 37825, -1, 37846, 37832, 37814, -1, 37801, 37833, 37816, -1, 37846, 37814, 37835, -1, 37801, 37816, 37836, -1, 37803, 37828, 37839, -1, 37847, 37768, 37769, -1, 37847, 37835, 37821, -1, 37803, 37837, 37828, -1, 37847, 37838, 37768, -1, 37847, 37821, 37838, -1, 37808, 37836, 37822, -1, 37808, 37822, 37840, -1, 37848, 37826, 37844, -1, 37848, 37621, 37620, -1, 37811, 37831, 37843, -1, 37848, 37841, 37826, -1, 37848, 37620, 37841, -1, 37811, 37839, 37831, -1, 37849, 37830, 37845, -1, 37849, 37844, 37830, -1, 37815, 37752, 37750, -1, 37815, 37840, 37752, -1, 37817, 37760, 37758, -1, 37788, 37599, 37597, -1, 37788, 37597, 37842, -1, 37817, 37843, 37760, -1, 37788, 37842, 37827, -1, 37789, 37601, 37607, -1, 37788, 37827, 37785, -1, 37789, 37607, 37779, -1, 37789, 37779, 37778, -1, 37784, 37845, 37832, -1, 37789, 37778, 37790, -1, 37784, 37832, 37846, -1, 37786, 37785, 37829, -1, 37786, 37829, 37795, -1, 37850, 37769, 37770, -1, 37850, 37847, 37769, -1, 37796, 37795, 37833, -1, 37791, 37790, 37834, -1, 37850, 37846, 37835, -1, 37791, 37834, 37798, -1, 37850, 37835, 37847, -1, 37796, 37833, 37801, -1, 37851, 37622, 37621, -1, 37851, 37621, 37848, -1, 37799, 37798, 37837, -1, 37851, 37848, 37844, -1, 37799, 37837, 37803, -1, 37851, 37844, 37849, -1, 37804, 37801, 37836, -1, 37783, 37849, 37845, -1, 37804, 37836, 37808, -1, 37805, 37803, 37839, -1, 37783, 37845, 37784, -1, 37805, 37839, 37811, -1, 37787, 37770, 37771, -1, 37809, 37808, 37840, -1, 37787, 37850, 37770, -1, 37787, 37784, 37846, -1, 37809, 37840, 37815, -1, 37812, 37843, 37817, -1, 37812, 37811, 37843, -1, 37787, 37846, 37850, -1, 37793, 37623, 37622, -1, 37793, 37849, 37783, -1, 37793, 37622, 37851, -1, 37819, 37750, 37748, -1, 37793, 37851, 37849, -1, 37819, 37815, 37750, -1, 37818, 37758, 37756, -1, 37782, 37771, 37772, -1, 37818, 37817, 37758, -1, 31358, 31349, 37852, -1, 37565, 37852, 37853, -1, 37565, 31358, 37852, -1, 37567, 37853, 37614, -1, 37567, 37614, 37613, -1, 37567, 37565, 37853, -1, 37569, 37613, 37617, -1, 37569, 37567, 37613, -1, 37571, 37617, 37619, -1, 37571, 37569, 37617, -1, 37573, 37571, 37619, -1, 37574, 37619, 37590, -1, 37574, 37573, 37619, -1, 37575, 37574, 37590, -1, 37854, 31348, 31361, -1, 37854, 31361, 37513, -1, 37855, 37513, 37514, -1, 37855, 37854, 37513, -1, 37612, 37514, 37515, -1, 37612, 37855, 37514, -1, 37615, 37515, 37516, -1, 37615, 37612, 37515, -1, 37616, 37516, 37518, -1, 37616, 37615, 37516, -1, 37606, 37518, 37519, -1, 37606, 37616, 37518, -1, 37591, 37519, 37520, -1, 37591, 37606, 37519, -1, 37852, 31349, 31348, -1, 37852, 31348, 37854, -1, 37853, 37854, 37855, -1, 37853, 37852, 37854, -1, 37614, 37855, 37612, -1, 37614, 37853, 37855, -1, 37856, 30916, 30932, -1, 37857, 30669, 30667, -1, 37858, 37859, 32831, -1, 37856, 37860, 30916, -1, 37857, 37861, 37862, -1, 37863, 30668, 37864, -1, 37863, 37864, 37865, -1, 37856, 37866, 37867, -1, 37863, 30666, 30668, -1, 37857, 30667, 37868, -1, 37856, 37867, 37860, -1, 37857, 37868, 37861, -1, 37869, 30932, 30941, -1, 37869, 30941, 30684, -1, 37863, 37865, 37870, -1, 37869, 30683, 30682, -1, 37871, 37870, 37872, -1, 37869, 30684, 30683, -1, 37869, 37856, 30932, -1, 37869, 30682, 37873, -1, 37874, 37875, 37876, -1, 37869, 37873, 37866, -1, 37869, 37866, 37856, -1, 37874, 37862, 37875, -1, 37877, 37876, 37878, -1, 37871, 37872, 37879, -1, 37880, 37879, 37881, -1, 37882, 30924, 30922, -1, 37877, 37878, 37883, -1, 37880, 37881, 37884, -1, 37885, 37883, 37886, -1, 37887, 37884, 37888, -1, 37887, 37888, 37889, -1, 37882, 30922, 32835, -1, 37885, 37886, 37890, -1, 37891, 30936, 30924, -1, 37892, 37893, 37894, -1, 37895, 37889, 37859, -1, 37892, 37890, 37893, -1, 37891, 30924, 37882, -1, 37895, 37859, 37858, -1, 37896, 32826, 32825, -1, 37897, 32835, 32834, -1, 37896, 37894, 32826, -1, 37898, 32830, 32829, -1, 37897, 37882, 32835, -1, 37899, 37857, 37862, -1, 37898, 37858, 32830, -1, 37900, 30943, 30936, -1, 37901, 30664, 30666, -1, 37899, 30640, 30669, -1, 37901, 37870, 37871, -1, 37899, 30669, 37857, -1, 37901, 37863, 37870, -1, 37899, 37862, 37874, -1, 37901, 30666, 37863, -1, 37902, 37874, 37876, -1, 37900, 30936, 37891, -1, 37902, 37876, 37877, -1, 37903, 37879, 37880, -1, 37904, 37891, 37882, -1, 37903, 37871, 37879, -1, 37904, 37882, 37897, -1, 37905, 37880, 37884, -1, 37906, 32834, 32833, -1, 37906, 37897, 32834, -1, 37907, 37883, 37885, -1, 37907, 37877, 37883, -1, 37905, 37884, 37887, -1, 37908, 37890, 37892, -1, 37909, 37887, 37889, -1, 37910, 30848, 30943, -1, 37908, 37885, 37890, -1, 37909, 37889, 37895, -1, 37910, 30943, 37900, -1, 37911, 37891, 37904, -1, 37912, 37894, 37896, -1, 37913, 37895, 37858, -1, 37912, 37892, 37894, -1, 37913, 37858, 37898, -1, 37914, 32825, 32824, -1, 37911, 37900, 37891, -1, 37914, 37896, 32825, -1, 37914, 32824, 30881, -1, 37915, 32829, 32828, -1, 37916, 37904, 37897, -1, 37917, 37874, 37902, -1, 37915, 37898, 32829, -1, 37917, 30640, 37899, -1, 37918, 30665, 30664, -1, 37916, 37897, 37906, -1, 37917, 30679, 30640, -1, 37918, 30664, 37901, -1, 37917, 37899, 37874, -1, 37918, 37901, 37871, -1, 37918, 37871, 37903, -1, 37919, 32833, 32832, -1, 37861, 37880, 37905, -1, 37920, 37877, 37907, -1, 37919, 37906, 32833, -1, 37861, 37903, 37880, -1, 37920, 37902, 37877, -1, 37865, 30849, 30848, -1, 37921, 37907, 37885, -1, 37865, 30848, 37910, -1, 37875, 37887, 37909, -1, 37872, 37900, 37911, -1, 37921, 37885, 37908, -1, 37922, 37892, 37912, -1, 37875, 37905, 37887, -1, 37922, 37908, 37892, -1, 37872, 37910, 37900, -1, 37878, 37909, 37895, -1, 37878, 37895, 37913, -1, 37923, 30881, 30890, -1, 37881, 37911, 37904, -1, 37886, 37913, 37898, -1, 37881, 37904, 37916, -1, 37923, 37912, 37896, -1, 37923, 37896, 37914, -1, 37886, 37898, 37915, -1, 37923, 37914, 30881, -1, 37924, 37917, 37902, -1, 37924, 30680, 30679, -1, 37924, 30679, 37917, -1, 37888, 37916, 37906, -1, 37924, 37902, 37920, -1, 37888, 37906, 37919, -1, 37925, 37920, 37907, -1, 37893, 32828, 32827, -1, 37925, 37907, 37921, -1, 37859, 37919, 32832, -1, 37893, 37915, 32828, -1, 37859, 32832, 32831, -1, 37868, 30667, 30665, -1, 37868, 30665, 37918, -1, 37864, 30861, 30849, -1, 37864, 30670, 30861, -1, 37868, 37918, 37903, -1, 37868, 37903, 37861, -1, 37864, 30668, 30670, -1, 37867, 37921, 37908, -1, 37864, 30849, 37865, -1, 37867, 37908, 37922, -1, 37862, 37861, 37905, -1, 37926, 37922, 37912, -1, 37926, 30890, 30905, -1, 37862, 37905, 37875, -1, 37870, 37910, 37872, -1, 37926, 37912, 37923, -1, 37926, 37923, 30890, -1, 37870, 37865, 37910, -1, 37927, 30680, 37924, -1, 37876, 37875, 37909, -1, 30881, 32824, 30878, -1, 37927, 30681, 30680, -1, 37876, 37909, 37878, -1, 37927, 37920, 37925, -1, 37927, 37924, 37920, -1, 37879, 37911, 37881, -1, 37879, 37872, 37911, -1, 37866, 37925, 37921, -1, 37883, 37913, 37886, -1, 37866, 37921, 37867, -1, 37883, 37878, 37913, -1, 37884, 37881, 37916, -1, 37884, 37916, 37888, -1, 37890, 37886, 37915, -1, 37860, 30905, 30916, -1, 37860, 37926, 30905, -1, 37889, 37919, 37859, -1, 37860, 37922, 37926, -1, 37860, 37867, 37922, -1, 37890, 37915, 37893, -1, 37889, 37888, 37919, -1, 37873, 30682, 30681, -1, 37873, 37925, 37866, -1, 37894, 32827, 32826, -1, 37873, 30681, 37927, -1, 37894, 37893, 32827, -1, 37858, 32831, 32830, -1, 37873, 37927, 37925, -1, 37928, 31162, 31161, -1, 37928, 31153, 31162, -1, 37928, 31161, 37929, -1, 37928, 37930, 31266, -1, 37928, 37929, 37931, -1, 37928, 37931, 37930, -1, 37932, 37933, 37934, -1, 37935, 37936, 37937, -1, 37938, 37939, 37940, -1, 37935, 37941, 37936, -1, 37942, 37943, 37944, -1, 37942, 37937, 37943, -1, 37938, 37945, 37939, -1, 37946, 31255, 31252, -1, 37947, 37944, 37948, -1, 37949, 37950, 37951, -1, 37946, 31252, 32904, -1, 37949, 37940, 37950, -1, 37952, 37951, 37953, -1, 37947, 37948, 37954, -1, 37955, 31269, 31255, -1, 37952, 37953, 37956, -1, 37957, 37954, 37958, -1, 37955, 31255, 37946, -1, 37959, 37956, 32895, -1, 37957, 37958, 37960, -1, 37959, 32895, 32894, -1, 37961, 32904, 32903, -1, 37962, 32899, 32898, -1, 37963, 37933, 37932, -1, 37962, 37960, 32899, -1, 37961, 37946, 32904, -1, 37963, 31157, 31155, -1, 37964, 31150, 31154, -1, 37965, 31277, 31269, -1, 37963, 37966, 37933, -1, 37964, 37967, 37941, -1, 37963, 31155, 37966, -1, 37964, 37941, 37935, -1, 37968, 37932, 37945, -1, 37964, 31154, 37967, -1, 37969, 37937, 37942, -1, 37968, 37945, 37938, -1, 37965, 31269, 37955, -1, 37970, 37955, 37946, -1, 37969, 37935, 37937, -1, 37971, 37940, 37949, -1, 37972, 37942, 37944, -1, 37970, 37946, 37961, -1, 37972, 37944, 37947, -1, 37971, 37938, 37940, -1, 37973, 32903, 32902, -1, 37973, 37961, 32903, -1, 31163, 31148, 31207, -1, 37974, 37949, 37951, -1, 37975, 31280, 31277, -1, 37976, 37947, 37954, -1, 37976, 37954, 37957, -1, 37974, 37951, 37952, -1, 37977, 37952, 37956, -1, 37978, 37957, 37960, -1, 37975, 31277, 37965, -1, 37978, 37960, 37962, -1, 37979, 37955, 37970, -1, 37977, 37956, 37959, -1, 37980, 32894, 32893, -1, 37979, 37965, 37955, -1, 37980, 37959, 32894, -1, 37981, 32898, 32897, -1, 37980, 32893, 31212, -1, 37981, 37962, 32898, -1, 37982, 31157, 37963, -1, 37983, 37970, 37961, -1, 37982, 31158, 31157, -1, 37984, 31151, 31150, -1, 37983, 37961, 37973, -1, 37982, 37963, 37932, -1, 37982, 37932, 37968, -1, 37984, 37964, 37935, -1, 37985, 37968, 37938, -1, 37984, 37935, 37969, -1, 37984, 31150, 37964, -1, 37986, 32902, 32901, -1, 37985, 37938, 37971, -1, 37987, 37969, 37942, -1, 37986, 37973, 32902, -1, 37988, 37971, 37949, -1, 37987, 37942, 37972, -1, 37989, 31185, 31280, -1, 37988, 37949, 37974, -1, 37934, 37972, 37947, -1, 37989, 31280, 37975, -1, 37934, 37947, 37976, -1, 37990, 37974, 37952, -1, 37936, 37975, 37965, -1, 37936, 37965, 37979, -1, 37939, 37976, 37957, -1, 37990, 37952, 37977, -1, 37939, 37957, 37978, -1, 37991, 31212, 31220, -1, 37991, 37977, 37959, -1, 37943, 37979, 37970, -1, 37991, 37980, 31212, -1, 37991, 37959, 37980, -1, 37943, 37970, 37983, -1, 37992, 37968, 37985, -1, 37992, 37982, 37968, -1, 37950, 37962, 37981, -1, 37992, 31159, 31158, -1, 37950, 37978, 37962, -1, 37992, 31158, 37982, -1, 37953, 37981, 32897, -1, 37948, 37983, 37973, -1, 37948, 37973, 37986, -1, 37993, 37985, 37971, -1, 37993, 37971, 37988, -1, 37953, 32897, 32896, -1, 37958, 32901, 32900, -1, 37994, 31156, 31151, -1, 37994, 37969, 37987, -1, 37958, 37986, 32901, -1, 37994, 31151, 37984, -1, 37995, 31207, 31185, -1, 37996, 37988, 37974, -1, 37994, 37984, 37969, -1, 37995, 31185, 37989, -1, 37996, 37974, 37990, -1, 37995, 31163, 31207, -1, 37997, 37991, 31220, -1, 37941, 37975, 37936, -1, 37997, 31220, 31237, -1, 37933, 37987, 37972, -1, 37997, 37990, 37977, -1, 37933, 37972, 37934, -1, 37941, 37989, 37975, -1, 37997, 37977, 37991, -1, 37998, 31160, 31159, -1, 37945, 37976, 37939, -1, 37998, 37985, 37993, -1, 37945, 37934, 37976, -1, 37998, 31159, 37992, -1, 37998, 37992, 37985, -1, 37937, 37936, 37979, -1, 31212, 32893, 31210, -1, 37937, 37979, 37943, -1, 37931, 37988, 37996, -1, 37940, 37939, 37978, -1, 37940, 37978, 37950, -1, 37931, 37993, 37988, -1, 37944, 37943, 37983, -1, 37951, 37981, 37953, -1, 37944, 37983, 37948, -1, 37999, 31237, 31249, -1, 37951, 37950, 37981, -1, 37999, 37997, 31237, -1, 37999, 37996, 37990, -1, 37999, 37990, 37997, -1, 37954, 37986, 37958, -1, 37954, 37948, 37986, -1, 37929, 31161, 31160, -1, 37929, 31160, 37998, -1, 37929, 37998, 37993, -1, 37956, 32896, 32895, -1, 37929, 37993, 37931, -1, 37960, 32900, 32899, -1, 37956, 37953, 32896, -1, 37930, 31249, 31266, -1, 37930, 37999, 31249, -1, 37966, 31155, 31156, -1, 37960, 37958, 32900, -1, 37967, 37995, 37989, -1, 37930, 37931, 37996, -1, 37966, 31156, 37994, -1, 37967, 31154, 31163, -1, 37930, 37996, 37999, -1, 37966, 37994, 37987, -1, 37928, 31266, 31245, -1, 37966, 37987, 37933, -1, 37967, 37989, 37941, -1, 37928, 31245, 31153, -1, 37932, 37934, 37945, -1, 37967, 31163, 37995, -1, 38000, 38001, 30464, -1, 38002, 38003, 38004, -1, 38000, 38005, 38001, -1, 38006, 30238, 38007, -1, 38006, 38008, 38009, -1, 38002, 30235, 30234, -1, 38010, 30481, 30467, -1, 38006, 38007, 38008, -1, 38010, 30467, 30246, -1, 38011, 38012, 38013, -1, 38002, 30234, 38003, -1, 38010, 30245, 30244, -1, 38002, 38004, 38014, -1, 38010, 30246, 30245, -1, 38010, 38015, 38000, -1, 38010, 30244, 38016, -1, 38010, 38000, 30481, -1, 38017, 38018, 38019, -1, 38010, 38016, 38015, -1, 38011, 38009, 38012, -1, 38020, 38021, 38022, -1, 38017, 38014, 38018, -1, 38023, 38024, 38025, -1, 38023, 38019, 38024, -1, 38020, 38013, 38021, -1, 38026, 38022, 38027, -1, 38028, 30462, 30461, -1, 38026, 38027, 38029, -1, 38030, 38025, 38031, -1, 38028, 30461, 32848, -1, 38032, 38029, 38033, -1, 38030, 38031, 38034, -1, 38035, 30483, 30462, -1, 38032, 38033, 38036, -1, 38037, 38034, 38038, -1, 38037, 38038, 38039, -1, 38035, 30462, 38028, -1, 38040, 32855, 32854, -1, 38040, 38036, 32855, -1, 38041, 32850, 32858, -1, 38042, 32848, 32843, -1, 38043, 38009, 38011, -1, 38041, 38039, 32850, -1, 38042, 38028, 32848, -1, 38043, 30240, 30239, -1, 38044, 38002, 38014, -1, 38044, 30236, 30235, -1, 38045, 30492, 30483, -1, 38043, 38006, 38009, -1, 38043, 30239, 38006, -1, 38044, 30235, 38002, -1, 38046, 38011, 38013, -1, 38044, 38014, 38017, -1, 38046, 38013, 38020, -1, 38047, 38019, 38023, -1, 38045, 30483, 38035, -1, 38048, 38035, 38028, -1, 38047, 38017, 38019, -1, 38049, 38023, 38025, -1, 38048, 38028, 38042, -1, 38050, 38022, 38026, -1, 38050, 38020, 38022, -1, 38049, 38025, 38030, -1, 38051, 32843, 32838, -1, 38052, 38026, 38029, -1, 38053, 38030, 38034, -1, 38051, 38042, 32843, -1, 38053, 38034, 38037, -1, 38052, 38029, 38032, -1, 38054, 30498, 30492, -1, 38054, 30492, 38045, -1, 38055, 38036, 38040, -1, 38056, 38035, 38048, -1, 38057, 38037, 38039, -1, 38055, 38032, 38036, -1, 38057, 38039, 38041, -1, 38058, 32854, 32853, -1, 38058, 38040, 32854, -1, 38056, 38045, 38035, -1, 38058, 32853, 30420, -1, 38059, 32858, 32860, -1, 38060, 30240, 38043, -1, 38059, 38041, 32858, -1, 38060, 30241, 30240, -1, 38061, 38048, 38042, -1, 38062, 30237, 30236, -1, 38061, 38042, 38051, -1, 38060, 38043, 38011, -1, 38060, 38011, 38046, -1, 38062, 30236, 38044, -1, 38062, 38044, 38017, -1, 38063, 38020, 38050, -1, 38063, 38046, 38020, -1, 38062, 38017, 38047, -1, 38064, 32838, 32841, -1, 38008, 38047, 38023, -1, 38064, 38051, 32838, -1, 38008, 38023, 38049, -1, 38004, 30501, 30498, -1, 38065, 38026, 38052, -1, 38065, 38050, 38026, -1, 38012, 38049, 38030, -1, 38004, 30498, 38054, -1, 38012, 38030, 38053, -1, 38021, 38053, 38037, -1, 38018, 38054, 38045, -1, 38066, 38052, 38032, -1, 38018, 38045, 38056, -1, 38021, 38037, 38057, -1, 38066, 38032, 38055, -1, 38067, 30420, 30435, -1, 38067, 38055, 38040, -1, 38024, 38056, 38048, -1, 38067, 38058, 30420, -1, 38067, 38040, 38058, -1, 38068, 38046, 38063, -1, 38027, 38057, 38041, -1, 38024, 38048, 38061, -1, 38068, 38060, 38046, -1, 38027, 38041, 38059, -1, 38068, 30242, 30241, -1, 38068, 30241, 38060, -1, 38031, 38061, 38051, -1, 38033, 32860, 32862, -1, 38031, 38051, 38064, -1, 38069, 38050, 38065, -1, 38033, 38059, 32860, -1, 38069, 38063, 38050, -1, 38007, 30238, 30237, -1, 38038, 32841, 32846, -1, 38007, 38062, 38047, -1, 38005, 38065, 38052, -1, 38007, 30237, 38062, -1, 38038, 38064, 32841, -1, 38007, 38047, 38008, -1, 38003, 30503, 30501, -1, 38005, 38052, 38066, -1, 38003, 30233, 30503, -1, 38003, 30234, 30233, -1, 38003, 30501, 38004, -1, 38070, 38067, 30435, -1, 38009, 38008, 38049, -1, 38070, 30435, 30452, -1, 38009, 38049, 38012, -1, 38014, 38054, 38018, -1, 38070, 38066, 38055, -1, 38070, 38055, 38067, -1, 38014, 38004, 38054, -1, 38071, 30243, 30242, -1, 38071, 30242, 38068, -1, 38013, 38053, 38021, -1, 38071, 38068, 38063, -1, 38013, 38012, 38053, -1, 30420, 32853, 30421, -1, 38071, 38063, 38069, -1, 38019, 38018, 38056, -1, 38015, 38065, 38005, -1, 38019, 38056, 38024, -1, 38022, 38021, 38057, -1, 38022, 38057, 38027, -1, 38015, 38069, 38065, -1, 38001, 38070, 30452, -1, 38025, 38024, 38061, -1, 38001, 30452, 30464, -1, 38025, 38061, 38031, -1, 38001, 38005, 38066, -1, 38001, 38066, 38070, -1, 38029, 38027, 38059, -1, 38029, 38059, 38033, -1, 38034, 38064, 38038, -1, 38016, 30244, 30243, -1, 38034, 38031, 38064, -1, 38016, 30243, 38071, -1, 38016, 38071, 38069, -1, 38036, 32862, 32855, -1, 38016, 38069, 38015, -1, 38036, 38033, 32862, -1, 38039, 32846, 32850, -1, 38000, 30464, 30481, -1, 38000, 38015, 38005, -1, 38006, 30239, 30238, -1, 38039, 38038, 32846, -1, 38072, 30586, 30603, -1, 38073, 38074, 38075, -1, 38076, 30351, 38077, -1, 38072, 38078, 30586, -1, 38076, 38077, 38079, -1, 38076, 30352, 30351, -1, 38072, 38080, 38081, -1, 38073, 30355, 38082, -1, 38073, 38082, 38074, -1, 38072, 38081, 38078, -1, 38083, 38072, 30603, -1, 38076, 38079, 38084, -1, 38083, 30582, 30362, -1, 38085, 38084, 38086, -1, 38083, 30603, 30582, -1, 38083, 30362, 30361, -1, 38083, 30361, 38087, -1, 38088, 38089, 38090, -1, 38083, 38087, 38080, -1, 38083, 38080, 38072, -1, 38088, 38075, 38089, -1, 38091, 38090, 38092, -1, 38085, 38086, 38093, -1, 38094, 38093, 38095, -1, 30363, 30362, 30582, -1, 38096, 30593, 30592, -1, 38091, 38092, 38097, -1, 38098, 38097, 38099, -1, 38094, 38095, 38100, -1, 38101, 38100, 38102, -1, 38101, 38102, 38103, -1, 38096, 30592, 32577, -1, 38104, 30606, 30593, -1, 38098, 38099, 38105, -1, 38106, 38107, 38108, -1, 38109, 38103, 38110, -1, 38106, 38105, 38107, -1, 38104, 30593, 38096, -1, 38109, 38110, 38111, -1, 38112, 32605, 32609, -1, 38113, 32577, 32566, -1, 38114, 32584, 32591, -1, 38112, 38108, 32605, -1, 38113, 38096, 32577, -1, 38114, 38111, 32584, -1, 38115, 30612, 30606, -1, 38116, 38073, 38075, -1, 38117, 30353, 30352, -1, 38116, 30357, 30356, -1, 38117, 38084, 38085, -1, 38117, 38076, 38084, -1, 38116, 30356, 38073, -1, 38116, 38075, 38088, -1, 38117, 30352, 38076, -1, 38115, 30606, 38104, -1, 38118, 38093, 38094, -1, 38119, 38104, 38096, -1, 38120, 38088, 38090, -1, 38118, 38085, 38093, -1, 38120, 38090, 38091, -1, 38121, 38097, 38098, -1, 38119, 38096, 38113, -1, 38122, 38094, 38100, -1, 38123, 32566, 32557, -1, 38123, 38113, 32566, -1, 38121, 38091, 38097, -1, 38122, 38100, 38101, -1, 38124, 38101, 38103, -1, 38125, 38105, 38106, -1, 38126, 30517, 30612, -1, 38124, 38103, 38109, -1, 38125, 38098, 38105, -1, 38126, 30612, 38115, -1, 38127, 38104, 38119, -1, 38128, 38108, 38112, -1, 38129, 38109, 38111, -1, 38129, 38111, 38114, -1, 38128, 38106, 38108, -1, 38127, 38115, 38104, -1, 38130, 32543, 30548, -1, 38130, 32609, 32543, -1, 38130, 30548, 30550, -1, 38131, 32591, 32597, -1, 38132, 38119, 38113, -1, 38130, 38112, 32609, -1, 38131, 38114, 32591, -1, 38133, 38116, 38088, -1, 38134, 30354, 30353, -1, 38132, 38113, 38123, -1, 38133, 38088, 38120, -1, 38133, 30357, 38116, -1, 38134, 30353, 38117, -1, 38133, 30358, 30357, -1, 38134, 38117, 38085, -1, 38134, 38085, 38118, -1, 38135, 32557, 32565, -1, 38074, 38094, 38122, -1, 38136, 38091, 38121, -1, 38135, 38123, 32557, -1, 38074, 38118, 38094, -1, 38079, 30518, 30517, -1, 38136, 38120, 38091, -1, 38079, 30517, 38126, -1, 38137, 38121, 38098, -1, 38137, 38098, 38125, -1, 38089, 38101, 38124, -1, 38086, 38115, 38127, -1, 38089, 38122, 38101, -1, 38086, 38126, 38115, -1, 38092, 38124, 38109, -1, 38138, 38106, 38128, -1, 38092, 38109, 38129, -1, 38138, 38125, 38106, -1, 38095, 38127, 38119, -1, 38139, 30550, 30559, -1, 38099, 38129, 38114, -1, 38095, 38119, 38132, -1, 38139, 38128, 38112, -1, 38139, 38112, 38130, -1, 38099, 38114, 38131, -1, 38139, 38130, 30550, -1, 38140, 30359, 30358, -1, 38102, 38132, 38123, -1, 38140, 38133, 38120, -1, 38140, 30358, 38133, -1, 38102, 38123, 38135, -1, 38140, 38120, 38136, -1, 38107, 32597, 32601, -1, 38110, 38135, 32565, -1, 38107, 38131, 32597, -1, 38110, 32565, 32575, -1, 38141, 38136, 38121, -1, 38082, 30355, 30354, -1, 38141, 38121, 38137, -1, 38082, 30354, 38134, -1, 38077, 30534, 30518, -1, 38077, 30350, 30534, -1, 38082, 38134, 38118, -1, 38082, 38118, 38074, -1, 38077, 30351, 30350, -1, 38077, 30518, 38079, -1, 38081, 38137, 38125, -1, 38081, 38125, 38138, -1, 38075, 38074, 38122, -1, 38142, 30559, 30574, -1, 38075, 38122, 38089, -1, 38084, 38126, 38086, -1, 38142, 38139, 30559, -1, 38142, 38138, 38128, -1, 38084, 38079, 38126, -1, 38142, 38128, 38139, -1, 38090, 38089, 38124, -1, 38143, 38140, 38136, -1, 38090, 38124, 38092, -1, 38143, 30359, 38140, -1, 38143, 30360, 30359, -1, 38093, 38127, 38095, -1, 38143, 38136, 38141, -1, 38093, 38086, 38127, -1, 38097, 38129, 38099, -1, 38100, 38095, 38132, -1, 38080, 38141, 38137, -1, 38097, 38092, 38129, -1, 38100, 38132, 38102, -1, 38080, 38137, 38081, -1, 38078, 30574, 30586, -1, 38103, 38135, 38110, -1, 38078, 38142, 30574, -1, 38105, 38099, 38131, -1, 38078, 38081, 38138, -1, 38078, 38138, 38142, -1, 38105, 38131, 38107, -1, 38103, 38102, 38135, -1, 38087, 30361, 30360, -1, 38108, 32601, 32605, -1, 38087, 38143, 38141, -1, 38111, 32575, 32584, -1, 38087, 30360, 38143, -1, 38108, 38107, 32601, -1, 38087, 38141, 38080, -1, 38073, 30356, 30355, -1, 38111, 38110, 32575, -1, 38144, 33007, 32942, -1, 38144, 32941, 32949, -1, 38144, 32942, 32941, -1, 38145, 32949, 32945, -1, 38145, 38144, 32949, -1, 38146, 38145, 32945, -1, 32745, 32945, 32917, -1, 32745, 38146, 32945, -1, 38147, 38148, 38149, -1, 38147, 38149, 38150, -1, 38151, 32966, 32965, -1, 38151, 38150, 32966, -1, 38151, 32965, 38152, -1, 38153, 32783, 32782, -1, 38153, 32782, 38154, -1, 38153, 38154, 38148, -1, 38153, 38148, 38147, -1, 38155, 38152, 38156, -1, 38155, 38151, 38152, -1, 38155, 38147, 38150, -1, 38155, 38150, 38151, -1, 38157, 38156, 38158, -1, 38157, 32784, 32783, -1, 38157, 38158, 32784, -1, 38157, 32783, 38153, -1, 38157, 38155, 38156, -1, 38157, 38153, 38147, -1, 38157, 38147, 38155, -1, 32779, 32778, 32944, -1, 38152, 32965, 32964, -1, 32785, 32784, 38158, -1, 38159, 32936, 32962, -1, 38159, 32962, 32971, -1, 38160, 32937, 32936, -1, 38160, 32936, 38159, -1, 38161, 32971, 32970, -1, 38161, 38159, 32971, -1, 38162, 32944, 32937, -1, 38162, 32937, 38160, -1, 38162, 32779, 32944, -1, 38163, 38159, 38161, -1, 38163, 38160, 38159, -1, 38164, 32970, 32969, -1, 38164, 38161, 32970, -1, 38165, 32780, 32779, -1, 38165, 38160, 38163, -1, 38165, 32779, 38162, -1, 38165, 38162, 38160, -1, 38166, 38163, 38161, -1, 38166, 38161, 38164, -1, 38149, 32969, 32967, -1, 38149, 38164, 32969, -1, 38167, 32781, 32780, -1, 38167, 38163, 38166, -1, 38167, 32780, 38165, -1, 38167, 38165, 38163, -1, 38148, 38166, 38164, -1, 38148, 38164, 38149, -1, 38150, 32967, 32966, -1, 38150, 38149, 32967, -1, 38154, 32782, 32781, -1, 38154, 32781, 38167, -1, 38154, 38167, 38166, -1, 38154, 38166, 38148, -1, 32964, 32975, 33048, -1, 38152, 32964, 33048, -1, 38156, 33048, 33050, -1, 38156, 38152, 33048, -1, 38158, 33050, 33055, -1, 38158, 38156, 33050, -1, 32785, 33055, 33054, -1, 32785, 38158, 33055, -1, 32918, 38168, 32627, -1, 32626, 38168, 32624, -1, 32627, 38168, 32626, -1, 38168, 38169, 32624, -1, 32624, 38170, 32619, -1, 38169, 38170, 32624, -1, 32619, 32564, 32559, -1, 38170, 32564, 32619, -1, 38171, 38172, 32542, -1, 32930, 38173, 32928, -1, 32928, 38173, 38174, -1, 38174, 38173, 38175, -1, 38175, 38173, 38176, -1, 32754, 38177, 32767, -1, 38172, 38177, 32754, -1, 38176, 38177, 38171, -1, 38171, 38177, 38172, -1, 32772, 38178, 32930, -1, 32767, 38178, 32773, -1, 32773, 38178, 32772, -1, 32930, 38178, 38173, -1, 38177, 38178, 32767, -1, 38173, 38178, 38176, -1, 38176, 38178, 38177, -1, 32918, 32919, 38168, -1, 38170, 38179, 32564, -1, 32564, 38179, 32592, -1, 32592, 38179, 32598, -1, 38169, 38180, 38170, -1, 38170, 38180, 38179, -1, 32598, 38181, 32603, -1, 38179, 38181, 32598, -1, 32922, 38182, 32919, -1, 38168, 38182, 38169, -1, 38169, 38182, 38180, -1, 32919, 38182, 38168, -1, 38180, 38183, 38179, -1, 38179, 38183, 38181, -1, 32603, 38184, 32606, -1, 38181, 38184, 32603, -1, 32924, 38185, 32922, -1, 32922, 38185, 38182, -1, 38180, 38185, 38183, -1, 38182, 38185, 38180, -1, 38181, 38186, 38184, -1, 38183, 38186, 38181, -1, 32606, 38187, 32544, -1, 38184, 38187, 32606, -1, 32926, 38188, 32924, -1, 38185, 38188, 38183, -1, 32924, 38188, 38185, -1, 38183, 38188, 38186, -1, 38184, 38175, 38187, -1, 38186, 38175, 38184, -1, 32544, 38171, 32542, -1, 38187, 38171, 32544, -1, 32928, 38174, 32926, -1, 32926, 38174, 38188, -1, 38188, 38174, 38186, -1, 38186, 38174, 38175, -1, 38175, 38176, 38187, -1, 38187, 38176, 38171, -1, 32542, 38172, 32560, -1, 32560, 38172, 32754, -1, 33060, 38189, 32765, -1, 32765, 38189, 32763, -1, 32763, 38190, 32761, -1, 38189, 38190, 32763, -1, 32761, 38191, 32756, -1, 38190, 38191, 32761, -1, 32756, 32545, 32561, -1, 38191, 32545, 32756, -1, 33131, 33134, 33180, -1, 33180, 33134, 38192, -1, 38192, 33133, 38193, -1, 33134, 33133, 38192, -1, 33133, 33132, 38193, -1, 38193, 33124, 38194, -1, 33132, 33124, 38193, -1, 38194, 33123, 32851, -1, 33124, 33123, 38194, -1, 33123, 32852, 32851, -1, 33176, 38195, 33174, -1, 33156, 38196, 38197, -1, 33174, 38195, 38198, -1, 38199, 38196, 38200, -1, 38201, 38195, 38202, -1, 38198, 38195, 38201, -1, 38200, 38203, 38204, -1, 38204, 38203, 38205, -1, 38194, 38206, 38193, -1, 38202, 38206, 38207, -1, 38208, 38206, 38194, -1, 38207, 38206, 38208, -1, 32837, 38209, 32863, -1, 33180, 38210, 33178, -1, 38205, 38209, 32837, -1, 33178, 38210, 33176, -1, 38192, 38210, 33180, -1, 38193, 38210, 38192, -1, 38195, 38210, 38202, -1, 38202, 38210, 38206, -1, 33158, 38211, 33156, -1, 38206, 38210, 38193, -1, 33156, 38211, 38196, -1, 33176, 38210, 38195, -1, 38196, 38211, 38200, -1, 38200, 38211, 38203, -1, 38205, 38212, 38209, -1, 38203, 38212, 38205, -1, 32863, 38213, 32861, -1, 38209, 38213, 32863, -1, 33160, 38214, 33158, -1, 33154, 33156, 38197, -1, 33158, 38214, 38211, -1, 38203, 38214, 38212, -1, 38211, 38214, 38203, -1, 38209, 38215, 38213, -1, 38212, 38215, 38209, -1, 32861, 38216, 32859, -1, 38213, 38216, 32861, -1, 33162, 38217, 33160, -1, 33160, 38217, 38214, -1, 38214, 38217, 38212, -1, 38212, 38217, 38215, -1, 38215, 38218, 38213, -1, 38213, 38218, 38216, -1, 32859, 38219, 32856, -1, 38216, 38219, 32859, -1, 33162, 38220, 38217, -1, 33164, 38220, 33162, -1, 38215, 38220, 38218, -1, 38217, 38220, 38215, -1, 38218, 38221, 38216, -1, 38216, 38221, 38219, -1, 38219, 38222, 32856, -1, 32856, 38222, 32849, -1, 33166, 38223, 33164, -1, 33164, 38223, 38220, -1, 38220, 38223, 38218, -1, 38218, 38223, 38221, -1, 38221, 38224, 38219, -1, 38219, 38224, 38222, -1, 38222, 38225, 32849, -1, 32849, 38225, 32844, -1, 33166, 38226, 38223, -1, 33168, 38226, 33166, -1, 38221, 38226, 38224, -1, 38223, 38226, 38221, -1, 38224, 38227, 38222, -1, 38222, 38227, 38225, -1, 32844, 38228, 32839, -1, 38225, 38228, 32844, -1, 33170, 38229, 33168, -1, 38224, 38229, 38227, -1, 33168, 38229, 38226, -1, 38226, 38229, 38224, -1, 38227, 38230, 38225, -1, 38225, 38230, 38228, -1, 32839, 38231, 32840, -1, 32847, 38194, 32851, -1, 38228, 38231, 32839, -1, 33172, 38232, 33170, -1, 33170, 38232, 38229, -1, 38227, 38232, 38230, -1, 38229, 38232, 38227, -1, 38230, 38201, 38228, -1, 38228, 38201, 38231, -1, 32840, 38207, 32842, -1, 38231, 38207, 32840, -1, 33174, 38198, 33172, -1, 38233, 38204, 32845, -1, 33172, 38198, 38232, -1, 32845, 38204, 32836, -1, 38230, 38198, 38201, -1, 38232, 38198, 38230, -1, 38199, 38200, 38233, -1, 38201, 38202, 38231, -1, 38231, 38202, 38207, -1, 38233, 38200, 38204, -1, 32836, 38205, 32837, -1, 32842, 38208, 32847, -1, 32847, 38208, 38194, -1, 38204, 38205, 32836, -1, 38207, 38208, 32842, -1, 38197, 38196, 38199, -1, 33154, 38197, 33119, -1, 33119, 38197, 33118, -1, 33118, 38197, 33117, -1, 33117, 38199, 33116, -1, 38197, 38199, 33117, -1, 33116, 38233, 33115, -1, 33115, 38233, 33114, -1, 38199, 38233, 33116, -1, 33114, 32845, 32857, -1, 38233, 32845, 33114, -1, 33108, 33104, 38234, -1, 33135, 38235, 38236, -1, 33135, 38234, 38235, -1, 33135, 33108, 38234, -1, 33126, 38236, 33155, -1, 33126, 33135, 38236, -1, 38237, 38238, 38239, -1, 38240, 38241, 38242, -1, 38237, 38243, 38244, -1, 38237, 38245, 38238, -1, 38246, 33102, 33101, -1, 38237, 38244, 38245, -1, 38246, 38242, 33102, -1, 38247, 38248, 33179, -1, 38247, 38239, 38248, -1, 38247, 33179, 33177, -1, 38247, 38237, 38239, -1, 38249, 33159, 33157, -1, 33103, 38234, 33104, -1, 38247, 38250, 38243, -1, 38247, 38243, 38237, -1, 38249, 33157, 38251, -1, 38247, 33177, 38250, -1, 38249, 38251, 38252, -1, 38249, 38252, 38240, -1, 38253, 38242, 38246, -1, 38253, 38240, 38242, -1, 38254, 38246, 33101, -1, 38254, 33101, 33100, -1, 38255, 33161, 33159, -1, 38255, 38249, 38240, -1, 38255, 33159, 38249, -1, 38255, 38240, 38253, -1, 38256, 38246, 38254, -1, 33157, 33155, 38236, -1, 38256, 38253, 38246, -1, 38257, 33100, 33099, -1, 38257, 38254, 33100, -1, 38258, 33163, 33161, -1, 38258, 33161, 38255, -1, 38258, 38253, 38256, -1, 38258, 38255, 38253, -1, 38259, 38254, 38257, -1, 38259, 38256, 38254, -1, 38260, 33099, 33098, -1, 38260, 38257, 33099, -1, 38261, 33163, 38258, -1, 38261, 38256, 38259, -1, 38261, 33165, 33163, -1, 38261, 38258, 38256, -1, 38262, 38257, 38260, -1, 38262, 38259, 38257, -1, 38263, 33098, 33096, -1, 38263, 38260, 33098, -1, 38264, 38261, 38259, -1, 38264, 33165, 38261, -1, 38264, 33167, 33165, -1, 38264, 38259, 38262, -1, 38265, 38262, 38260, -1, 38265, 38260, 38263, -1, 38266, 33096, 33094, -1, 38266, 38263, 33096, -1, 38267, 38262, 38265, -1, 38267, 38264, 38262, -1, 38267, 33167, 38264, -1, 38267, 33169, 33167, -1, 38268, 38265, 38263, -1, 38268, 38263, 38266, -1, 38269, 33094, 33091, -1, 38269, 38266, 33094, -1, 38270, 38267, 38265, -1, 38270, 33171, 33169, -1, 38270, 33169, 38267, -1, 38270, 38265, 38268, -1, 38271, 38268, 38266, -1, 38271, 38266, 38269, -1, 38272, 33091, 33092, -1, 38272, 38269, 33091, -1, 38273, 33171, 38270, -1, 38273, 33173, 33171, -1, 38273, 38268, 38271, -1, 38273, 38270, 38268, -1, 38274, 38271, 38269, -1, 38274, 38269, 38272, -1, 38244, 33092, 33093, -1, 38244, 38272, 33092, -1, 33181, 33179, 38248, -1, 38275, 33175, 33173, -1, 38241, 38235, 38234, -1, 38275, 33173, 38273, -1, 38275, 38271, 38274, -1, 38275, 38273, 38271, -1, 38241, 38234, 33103, -1, 38252, 38236, 38235, -1, 38243, 38274, 38272, -1, 38243, 38272, 38244, -1, 38252, 38235, 38241, -1, 38245, 33095, 33097, -1, 38242, 33103, 33102, -1, 38245, 33093, 33095, -1, 38242, 38241, 33103, -1, 38245, 33097, 38238, -1, 38245, 38244, 33093, -1, 38250, 33177, 33175, -1, 38251, 33157, 38236, -1, 38250, 33175, 38275, -1, 38251, 38236, 38252, -1, 38250, 38274, 38243, -1, 38250, 38275, 38274, -1, 38240, 38252, 38241, -1, 38238, 33097, 33106, -1, 38239, 33106, 33137, -1, 38239, 38238, 33106, -1, 38248, 38239, 33137, -1, 33181, 38248, 33137, -1, 31390, 38276, 37168, -1, 31390, 38277, 38276, -1, 31390, 36839, 38277, -1, 31388, 31390, 37168, -1, 31385, 31388, 37168, -1, 37172, 38278, 37171, -1, 38279, 38278, 37172, -1, 31121, 31120, 38279, -1, 31121, 37173, 37174, -1, 31121, 37172, 37173, -1, 31121, 38279, 37172, -1, 31124, 37174, 37175, -1, 31124, 31121, 37174, -1, 31126, 37175, 37176, -1, 31126, 31124, 37175, -1, 31129, 37177, 37178, -1, 31129, 37176, 37177, -1, 31129, 31126, 37176, -1, 31130, 37179, 37180, -1, 31130, 37178, 37179, -1, 31130, 31129, 37178, -1, 38276, 37180, 37168, -1, 38277, 37180, 38276, -1, 36839, 31130, 37180, -1, 36839, 37180, 38277, -1, 38278, 38280, 31299, -1, 38278, 31299, 37171, -1, 38279, 38281, 38280, -1, 38279, 31118, 38281, -1, 38279, 38280, 38278, -1, 31120, 31118, 38279, -1, 31076, 31299, 38280, -1, 31077, 38280, 38281, -1, 31077, 31076, 38280, -1, 31078, 38281, 31118, -1, 31078, 31077, 38281, -1, 31075, 31078, 31118, -1, 33079, 33080, 33084, -1, 33084, 33080, 38282, -1, 38282, 33081, 38283, -1, 33080, 33081, 38282, -1, 38284, 33082, 38285, -1, 38286, 33082, 38284, -1, 38283, 33082, 38286, -1, 33081, 33082, 38283, -1, 38287, 31356, 31341, -1, 38288, 31356, 38287, -1, 38289, 31356, 38288, -1, 38285, 31356, 38289, -1, 33082, 31356, 38285, -1, 33068, 33074, 33067, -1, 33067, 38290, 33066, -1, 33074, 38290, 33067, -1, 33066, 38291, 33065, -1, 38290, 38291, 33066, -1, 33065, 38292, 33064, -1, 38291, 38292, 33065, -1, 38292, 38293, 33064, -1, 33064, 38294, 31344, -1, 38293, 38294, 33064, -1, 38294, 38295, 31344, -1, 38295, 31345, 31344, -1, 31081, 31080, 31112, -1, 37186, 31112, 38296, -1, 37186, 31081, 31112, -1, 37185, 38296, 38297, -1, 37185, 37186, 38296, -1, 33072, 38297, 38298, -1, 33072, 37185, 38297, -1, 33070, 33072, 38298, -1, 33071, 38298, 33073, -1, 33071, 33070, 38298, -1, 33069, 33071, 33073, -1, 31488, 31490, 33062, -1, 38299, 33061, 33063, -1, 38299, 33062, 33061, -1, 38299, 31488, 33062, -1, 38300, 33063, 37183, -1, 38300, 38299, 33063, -1, 38301, 37183, 37184, -1, 38301, 38300, 37183, -1, 31100, 31085, 31084, -1, 31100, 37184, 31085, -1, 31100, 38301, 37184, -1, 38302, 38303, 38304, -1, 38305, 31495, 31493, -1, 38305, 38304, 31495, -1, 38306, 31105, 31104, -1, 38306, 38307, 38308, -1, 38306, 31104, 38307, -1, 38306, 38308, 38302, -1, 38309, 38302, 38304, -1, 38309, 38304, 38305, -1, 38310, 31488, 38299, -1, 38310, 31491, 31488, -1, 38310, 31493, 31491, -1, 38310, 38305, 31493, -1, 38311, 31106, 31105, -1, 38311, 31105, 38306, -1, 38311, 38306, 38302, -1, 38311, 38302, 38309, -1, 38312, 38299, 38300, -1, 38312, 38310, 38299, -1, 38312, 38309, 38305, -1, 38312, 38305, 38310, -1, 38313, 38300, 38301, -1, 38313, 31107, 31106, -1, 38313, 31106, 38311, -1, 38313, 38312, 38300, -1, 38313, 38301, 31107, -1, 38313, 38311, 38309, -1, 38313, 38309, 38312, -1, 31100, 31107, 38301, -1, 38314, 38315, 31504, -1, 38314, 31504, 31501, -1, 38316, 38317, 38315, -1, 38316, 38315, 38314, -1, 38318, 31501, 31499, -1, 38318, 38314, 31501, -1, 38319, 31103, 31111, -1, 38319, 38320, 38317, -1, 38319, 31111, 38320, -1, 38319, 38317, 38316, -1, 38321, 38316, 38314, -1, 38321, 38314, 38318, -1, 38303, 31499, 31497, -1, 38303, 38318, 31499, -1, 38322, 31101, 31103, -1, 38322, 38316, 38321, -1, 38322, 38319, 38316, -1, 38322, 31103, 38319, -1, 38308, 38318, 38303, -1, 38308, 38321, 38318, -1, 38304, 31497, 31495, -1, 38304, 38303, 31497, -1, 38307, 31104, 31101, -1, 38307, 31101, 38322, -1, 38307, 38322, 38321, -1, 38307, 38321, 38308, -1, 38302, 38308, 38303, -1, 31111, 31099, 38323, -1, 38320, 31111, 38323, -1, 38317, 38323, 38324, -1, 38317, 38320, 38323, -1, 38315, 38324, 38325, -1, 38315, 38317, 38324, -1, 31504, 38325, 31505, -1, 31504, 38315, 38325, -1, 31102, 31083, 31082, -1, 31102, 31082, 37182, -1, 38326, 37182, 37181, -1, 38326, 31102, 37182, -1, 38327, 37181, 33078, -1, 38327, 33078, 33075, -1, 38327, 38326, 37181, -1, 38328, 33075, 33077, -1, 38328, 38327, 33075, -1, 33083, 33077, 33076, -1, 33083, 38328, 33077, -1, 31400, 31410, 38329, -1, 37188, 38329, 38330, -1, 37188, 31400, 38329, -1, 37187, 38330, 31378, -1, 37187, 37188, 38330, -1, 31394, 37187, 31378, -1, 38331, 38332, 31379, -1, 38333, 37026, 37023, -1, 38333, 38334, 38335, -1, 38333, 37023, 38334, -1, 38333, 38335, 38336, -1, 38337, 38336, 38338, -1, 38337, 38338, 38332, -1, 31384, 36802, 31375, -1, 31384, 36800, 36802, -1, 38339, 38330, 38329, -1, 38339, 38331, 38330, -1, 38339, 38332, 38331, -1, 38339, 38337, 38332, -1, 38340, 37021, 37026, -1, 38340, 37026, 38333, -1, 38340, 38336, 38337, -1, 38340, 38333, 38336, -1, 38341, 37020, 37021, -1, 38341, 37022, 37020, -1, 38341, 38329, 37022, -1, 38341, 37021, 38340, -1, 38341, 38339, 38329, -1, 38341, 38337, 38339, -1, 38341, 38340, 38337, -1, 37028, 31449, 36798, -1, 31410, 37022, 38329, -1, 38342, 31384, 31383, -1, 38343, 36800, 31384, -1, 38343, 31384, 38342, -1, 38344, 36798, 36800, -1, 38344, 37028, 36798, -1, 38344, 36800, 38343, -1, 38345, 31383, 31382, -1, 38345, 38342, 31383, -1, 38346, 38343, 38342, -1, 38346, 38342, 38345, -1, 38347, 31381, 31380, -1, 38347, 31382, 31381, -1, 38347, 38345, 31382, -1, 38348, 37025, 37028, -1, 38348, 37028, 38344, -1, 38348, 38344, 38343, -1, 38348, 38343, 38346, -1, 38335, 38345, 38347, -1, 38335, 38346, 38345, -1, 38338, 38347, 31380, -1, 38334, 37023, 37025, -1, 38334, 38346, 38335, -1, 38334, 37025, 38348, -1, 38334, 38348, 38346, -1, 38336, 38335, 38347, -1, 38336, 38347, 38338, -1, 38332, 31380, 31379, -1, 38332, 38338, 31380, -1, 38331, 31379, 31378, -1, 38331, 31378, 38330, -1, 31093, 31109, 38349, -1, 38350, 38349, 38351, -1, 38350, 31093, 38349, -1, 38352, 38351, 33525, -1, 38352, 38350, 38351, -1, 33527, 38352, 33525, -1, 31110, 38353, 31109, -1, 38354, 31110, 31108, -1, 38354, 38353, 31110, -1, 38355, 38356, 38353, -1, 38355, 38353, 38354, -1, 38357, 31108, 31102, -1, 38357, 31102, 38326, -1, 38357, 38354, 31108, -1, 38358, 38359, 38356, -1, 38358, 38360, 38359, -1, 38358, 38361, 38360, -1, 38358, 38356, 38355, -1, 38362, 38326, 38327, -1, 38362, 38355, 38354, -1, 38362, 38354, 38357, -1, 38362, 38357, 38326, -1, 38363, 38328, 33083, -1, 38363, 38327, 38328, -1, 38363, 33083, 38361, -1, 38363, 38362, 38327, -1, 38363, 38358, 38355, -1, 38363, 38361, 38358, -1, 38363, 38355, 38362, -1, 38364, 33525, 38351, -1, 38365, 38351, 38349, -1, 38365, 38364, 38351, -1, 38353, 38349, 31109, -1, 38356, 38365, 38349, -1, 38356, 38349, 38353, -1, 38359, 38365, 38356, -1, 33528, 33525, 38364, -1, 38366, 38364, 38365, -1, 38366, 33528, 38364, -1, 38367, 38359, 38360, -1, 38367, 38365, 38359, -1, 38367, 38366, 38365, -1, 38368, 38360, 38361, -1, 38368, 38367, 38360, -1, 33084, 38361, 33083, -1, 33084, 38368, 38361, -1, 38369, 38370, 38371, -1, 38369, 38372, 38370, -1, 38373, 33514, 33515, -1, 38373, 33515, 38374, -1, 38373, 38375, 38372, -1, 38373, 38374, 38375, -1, 38376, 38377, 33524, -1, 38376, 33524, 33514, -1, 38376, 38369, 38377, -1, 38376, 33514, 38373, -1, 38376, 38372, 38369, -1, 38282, 38368, 33084, -1, 38376, 38373, 38372, -1, 33529, 33528, 38366, -1, 38378, 38367, 38368, -1, 38378, 38282, 38283, -1, 38378, 38368, 38282, -1, 38379, 38367, 38378, -1, 38380, 38283, 38286, -1, 38380, 38378, 38283, -1, 38381, 38366, 38367, -1, 38381, 33530, 33529, -1, 38381, 38367, 38379, -1, 38381, 33529, 38366, -1, 38382, 38378, 38380, -1, 38382, 38379, 38378, -1, 38383, 38286, 38284, -1, 38383, 38380, 38286, -1, 38384, 38379, 38382, -1, 38384, 38381, 38379, -1, 38384, 33530, 38381, -1, 38370, 38285, 38289, -1, 38370, 38284, 38285, -1, 38370, 38383, 38284, -1, 38375, 38380, 38383, -1, 38375, 38382, 38380, -1, 38371, 38287, 31341, -1, 38371, 38288, 38287, -1, 38371, 38289, 38288, -1, 38371, 31341, 38385, -1, 38371, 38370, 38289, -1, 38372, 38375, 38383, -1, 38372, 38383, 38370, -1, 38374, 33515, 33530, -1, 38374, 33530, 38384, -1, 38374, 38384, 38382, -1, 38374, 38382, 38375, -1, 38369, 38385, 38377, -1, 38369, 38371, 38385, -1, 33521, 33524, 38377, -1, 38386, 38377, 38385, -1, 38386, 33521, 38377, -1, 38387, 38385, 31341, -1, 38387, 38386, 38385, -1, 31345, 38387, 31341, -1, 38388, 33518, 33519, -1, 38388, 33519, 38389, -1, 38388, 38389, 38390, -1, 38388, 38390, 38391, -1, 38392, 38290, 33074, -1, 38392, 33074, 38393, -1, 38392, 38394, 38290, -1, 38395, 38393, 38396, -1, 38395, 38392, 38393, -1, 38395, 38391, 38394, -1, 38395, 38394, 38392, -1, 38397, 38398, 33510, -1, 38397, 38396, 38398, -1, 38397, 33517, 33518, -1, 38397, 33510, 33517, -1, 38397, 38395, 38396, -1, 38397, 33518, 38388, -1, 38397, 38388, 38391, -1, 38397, 38391, 38395, -1, 38399, 38387, 31345, -1, 38399, 38294, 38293, -1, 38399, 38295, 38294, -1, 38399, 31345, 38295, -1, 38400, 38293, 38292, -1, 38400, 38399, 38293, -1, 38401, 38386, 38387, -1, 38401, 38387, 38399, -1, 38402, 38401, 38399, -1, 38402, 38399, 38400, -1, 38403, 38292, 38291, -1, 38403, 38400, 38292, -1, 38404, 33521, 38386, -1, 38404, 33520, 33521, -1, 38404, 38386, 38401, -1, 38405, 33522, 33520, -1, 38405, 33520, 38404, -1, 38405, 38404, 38401, -1, 38405, 38401, 38402, -1, 38406, 38402, 38400, -1, 38406, 38400, 38403, -1, 38407, 38291, 38290, -1, 38407, 38403, 38291, -1, 38408, 33523, 33522, -1, 38408, 38405, 38402, -1, 38408, 38402, 38406, -1, 38408, 33522, 38405, -1, 38390, 38406, 38403, -1, 38390, 38403, 38407, -1, 38394, 38407, 38290, -1, 38389, 33519, 33523, -1, 38389, 38406, 38390, -1, 38389, 33523, 38408, -1, 38389, 38408, 38406, -1, 38391, 38390, 38407, -1, 38391, 38407, 38394, -1, 31113, 38296, 31112, -1, 38409, 31115, 31114, -1, 38410, 38411, 38412, -1, 38413, 31113, 31115, -1, 38413, 38296, 31113, -1, 38414, 38297, 38296, -1, 38414, 38409, 38412, -1, 38414, 38413, 31115, -1, 38414, 38296, 38413, -1, 38414, 31115, 38409, -1, 38414, 38412, 38411, -1, 38415, 38416, 33073, -1, 38415, 38411, 38416, -1, 38415, 38298, 38297, -1, 38415, 33073, 38298, -1, 38415, 38297, 38414, -1, 38415, 38414, 38411, -1, 38417, 33511, 33510, -1, 38417, 33510, 38398, -1, 38418, 38398, 38396, -1, 38418, 38417, 38398, -1, 38410, 38418, 38396, -1, 38411, 38396, 38393, -1, 38411, 38410, 38396, -1, 38416, 38393, 33074, -1, 38416, 38411, 38393, -1, 33073, 38416, 33074, -1, 36848, 38412, 38409, -1, 36848, 38409, 31114, -1, 38418, 38410, 38412, -1, 38418, 38412, 36848, -1, 36850, 38418, 36848, -1, 38417, 38418, 36850, -1, 33511, 38417, 36850, -1, 31665, 32326, 32328, -1, 31665, 31663, 32326, -1, 31841, 32095, 32093, -1, 31841, 31842, 32095, -1, 31705, 32322, 32321, -1, 31705, 31700, 32322, -1, 31700, 32516, 32322, -1, 31848, 32108, 31846, -1, 32105, 32108, 31848, -1, 32511, 32105, 31848, -1, 38419, 38420, 38421, -1, 38422, 38421, 38423, -1, 38422, 38419, 38421, -1, 38424, 38423, 33648, -1, 38424, 38422, 38423, -1, 33672, 38424, 33648, -1, 38425, 38426, 38419, -1, 38426, 38420, 38419, -1, 38420, 38427, 38428, -1, 38426, 38427, 38420, -1, 38428, 38427, 38429, -1, 38430, 38431, 38432, -1, 38429, 38431, 38430, -1, 38427, 38431, 38429, -1, 38432, 38433, 38434, -1, 38431, 38433, 38432, -1, 38433, 38435, 38434, -1, 38434, 38435, 38436, -1, 38436, 38437, 38438, -1, 38435, 38437, 38436, -1, 38438, 38437, 38439, -1, 38439, 38437, 38440, -1, 38440, 38441, 38442, -1, 38437, 38441, 38440, -1, 38442, 38443, 38444, -1, 38441, 38443, 38442, -1, 38445, 38446, 38447, -1, 38444, 38446, 38445, -1, 38443, 38446, 38444, -1, 38447, 38448, 38449, -1, 38446, 38448, 38447, -1, 38449, 38450, 38451, -1, 38448, 38450, 38449, -1, 38450, 38452, 38451, -1, 38450, 38453, 38452, -1, 38452, 38453, 38454, -1, 38455, 38456, 38457, -1, 38454, 38456, 38455, -1, 38453, 38456, 38454, -1, 38457, 38458, 38459, -1, 38456, 38458, 38457, -1, 38459, 38460, 38461, -1, 38458, 38460, 38459, -1, 38461, 38462, 38463, -1, 38460, 38462, 38461, -1, 38463, 38464, 38465, -1, 38462, 38464, 38463, -1, 38465, 38464, 38466, -1, 38466, 38467, 38468, -1, 38464, 38467, 38466, -1, 38468, 38469, 38470, -1, 38467, 38469, 38468, -1, 38470, 38471, 38472, -1, 38469, 38471, 38470, -1, 38472, 38473, 38474, -1, 38474, 38473, 38475, -1, 38471, 38473, 38472, -1, 38473, 38476, 38475, -1, 38475, 38476, 38477, -1, 38423, 38478, 36183, -1, 38423, 36183, 33648, -1, 38421, 38479, 38478, -1, 38421, 38478, 38423, -1, 38428, 38479, 38421, -1, 38420, 38428, 38421, -1, 36180, 38480, 36178, -1, 38432, 38481, 38480, -1, 38432, 38434, 38481, -1, 38432, 38480, 36180, -1, 38430, 36180, 36182, -1, 38430, 38432, 36180, -1, 38478, 36182, 36183, -1, 38429, 38430, 36182, -1, 38429, 36182, 38478, -1, 38479, 38429, 38478, -1, 38428, 38429, 38479, -1, 38480, 38482, 36176, -1, 38480, 36176, 36178, -1, 38481, 38483, 38482, -1, 38481, 38436, 38483, -1, 38481, 38482, 38480, -1, 38434, 38436, 38481, -1, 38484, 36176, 38482, -1, 38484, 36287, 36176, -1, 38485, 38482, 38483, -1, 38485, 38484, 38482, -1, 38438, 38483, 38436, -1, 38438, 38485, 38483, -1, 38485, 38438, 38439, -1, 38486, 38485, 38439, -1, 38484, 38485, 38486, -1, 38487, 38484, 38486, -1, 36200, 36287, 38484, -1, 36200, 38484, 38487, -1, 36398, 38488, 36125, -1, 38439, 38440, 38486, -1, 38489, 36398, 36400, -1, 38489, 38488, 36398, -1, 38490, 38491, 38488, -1, 38490, 38488, 38489, -1, 38492, 38447, 38449, -1, 38492, 38445, 38447, -1, 38492, 38493, 38491, -1, 38492, 38449, 38493, -1, 38492, 38491, 38490, -1, 38494, 36400, 36403, -1, 38494, 38489, 36400, -1, 38495, 38490, 38489, -1, 38495, 38489, 38494, -1, 38496, 38444, 38445, -1, 38496, 38445, 38492, -1, 38496, 38492, 38490, -1, 38496, 38490, 38495, -1, 38497, 36403, 36405, -1, 38497, 38494, 36403, -1, 38498, 38495, 38494, -1, 38498, 38494, 38497, -1, 38499, 38442, 38444, -1, 38499, 38496, 38495, -1, 38499, 38444, 38496, -1, 38499, 38495, 38498, -1, 38499, 38498, 38442, -1, 38500, 36200, 38487, -1, 38500, 36405, 36200, -1, 38500, 38497, 36405, -1, 38501, 38487, 38486, -1, 38501, 38498, 38497, -1, 38501, 38500, 38487, -1, 38501, 38442, 38498, -1, 38501, 38497, 38500, -1, 38502, 38440, 38442, -1, 38502, 38501, 38486, -1, 38502, 38442, 38501, -1, 38502, 38486, 38440, -1, 38503, 38493, 38449, -1, 38503, 38449, 38451, -1, 38504, 38491, 38493, -1, 38504, 38493, 38503, -1, 38488, 38491, 38504, -1, 38505, 38488, 38504, -1, 36125, 38488, 38505, -1, 36120, 36125, 38505, -1, 38503, 38451, 38452, -1, 38503, 38452, 38506, -1, 38504, 38506, 38507, -1, 38504, 38503, 38506, -1, 38505, 38507, 38508, -1, 38505, 38504, 38507, -1, 36120, 38508, 36109, -1, 36120, 38505, 38508, -1, 38454, 38506, 38452, -1, 38509, 38507, 38506, -1, 38509, 38506, 38454, -1, 38510, 38507, 38509, -1, 38511, 38508, 38507, -1, 38511, 38507, 38510, -1, 36107, 36109, 38508, -1, 36107, 38508, 38511, -1, 36097, 38512, 35972, -1, 38454, 38455, 38509, -1, 38513, 36097, 36098, -1, 38513, 38512, 36097, -1, 38514, 38515, 38512, -1, 38514, 38512, 38513, -1, 38516, 38461, 38463, -1, 38516, 38463, 38515, -1, 38516, 38515, 38514, -1, 38517, 36098, 36100, -1, 38517, 38513, 36098, -1, 38518, 38514, 38513, -1, 38518, 38513, 38517, -1, 38519, 36102, 36104, -1, 38519, 36100, 36102, -1, 38519, 38517, 36100, -1, 38520, 38459, 38461, -1, 38520, 38516, 38514, -1, 38520, 38461, 38516, -1, 38520, 38514, 38518, -1, 38521, 38518, 38517, -1, 38521, 38517, 38519, -1, 38522, 36107, 38511, -1, 38522, 36104, 36107, -1, 38522, 38519, 36104, -1, 38523, 38457, 38459, -1, 38523, 38518, 38521, -1, 38523, 38459, 38520, -1, 38523, 38520, 38518, -1, 38524, 38511, 38510, -1, 38524, 38522, 38511, -1, 38524, 38521, 38519, -1, 38524, 38519, 38522, -1, 38525, 38510, 38509, -1, 38525, 38455, 38457, -1, 38525, 38457, 38523, -1, 38525, 38524, 38510, -1, 38525, 38509, 38455, -1, 38525, 38523, 38521, -1, 38525, 38521, 38524, -1, 38526, 38515, 38463, -1, 38526, 38463, 38465, -1, 38512, 38515, 38526, -1, 38527, 38512, 38526, -1, 35972, 38512, 38527, -1, 35980, 35972, 38527, -1, 38465, 38466, 38528, -1, 38526, 38465, 38528, -1, 38527, 38528, 38529, -1, 38527, 38526, 38528, -1, 35980, 38529, 35857, -1, 35980, 38527, 38529, -1, 38530, 35855, 35857, -1, 38529, 38530, 35857, -1, 38531, 38530, 38529, -1, 38528, 38531, 38529, -1, 38466, 38468, 38531, -1, 38466, 38531, 38528, -1, 35851, 38532, 34743, -1, 38533, 38532, 35851, -1, 38472, 38474, 38533, -1, 38472, 35851, 35853, -1, 38472, 38533, 35851, -1, 38470, 38472, 35853, -1, 38530, 35853, 35855, -1, 38530, 38470, 35853, -1, 38531, 38470, 38530, -1, 38468, 38470, 38531, -1, 38534, 38533, 38474, -1, 38534, 38474, 38475, -1, 38535, 38532, 38533, -1, 38535, 38533, 38534, -1, 34743, 38532, 38535, -1, 34612, 34743, 38535, -1, 38475, 38477, 38536, -1, 38534, 38536, 38537, -1, 38534, 38475, 38536, -1, 38535, 38537, 34557, -1, 38535, 38534, 38537, -1, 34612, 38535, 34557, -1, 38538, 32136, 38539, -1, 38540, 32136, 38538, -1, 32140, 38541, 38542, -1, 32140, 32136, 38540, -1, 32140, 38540, 38541, -1, 38543, 38544, 38545, -1, 38543, 38546, 38547, -1, 38543, 38548, 38546, -1, 38543, 38545, 38548, -1, 31870, 38549, 38550, -1, 31870, 38551, 38549, -1, 31870, 38552, 38551, -1, 31870, 38553, 38552, -1, 38554, 38555, 38544, -1, 38554, 38544, 38543, -1, 31864, 38553, 31870, -1, 31864, 38543, 38547, -1, 31864, 38547, 38553, -1, 38552, 38553, 38556, -1, 38551, 38556, 38557, -1, 38551, 38552, 38556, -1, 38558, 38550, 38549, -1, 38559, 38557, 38560, -1, 38559, 38560, 38561, -1, 38559, 38561, 38562, -1, 38559, 38562, 38563, -1, 38559, 38563, 38558, -1, 38559, 38549, 38551, -1, 38559, 38551, 38557, -1, 38559, 38558, 38549, -1, 38564, 38565, 38566, -1, 38567, 38568, 38569, -1, 38567, 38569, 38570, -1, 38567, 38571, 38568, -1, 38572, 38570, 38573, -1, 38572, 38573, 38574, -1, 38572, 38574, 38575, -1, 38572, 38567, 38570, -1, 38572, 38575, 38571, -1, 38572, 38571, 38567, -1, 38576, 38577, 38578, -1, 38576, 38578, 38579, -1, 38576, 38580, 38581, -1, 38576, 38581, 38566, -1, 38576, 38565, 38577, -1, 38576, 38566, 38565, -1, 38582, 38579, 38583, -1, 38582, 38583, 38584, -1, 38582, 38585, 38586, -1, 38582, 38586, 38580, -1, 38582, 38576, 38579, -1, 38582, 38580, 38576, -1, 38587, 38584, 38588, -1, 38587, 38589, 38585, -1, 38587, 38585, 38582, -1, 38587, 38582, 38584, -1, 38590, 38588, 38591, -1, 38590, 38591, 38592, -1, 38590, 38593, 38594, -1, 38590, 38594, 38589, -1, 38590, 38587, 38588, -1, 38590, 38589, 38587, -1, 38595, 38592, 38596, -1, 38595, 38596, 38568, -1, 38595, 38575, 38597, -1, 38595, 38597, 38593, -1, 38595, 38593, 38590, -1, 38595, 38590, 38592, -1, 38571, 38595, 38568, -1, 38571, 38575, 38595, -1, 38598, 38562, 38561, -1, 38598, 38561, 38599, -1, 38598, 38599, 38577, -1, 38598, 38577, 38565, -1, 38564, 38566, 38600, -1, 38564, 38600, 38562, -1, 38564, 38562, 38598, -1, 38564, 38598, 38565, -1, 30178, 30203, 30180, -1, 30180, 38601, 30182, -1, 30203, 38601, 30180, -1, 30182, 38602, 30184, -1, 38601, 38602, 30182, -1, 30184, 38603, 30186, -1, 38602, 38603, 30184, -1, 30186, 38604, 30188, -1, 38603, 38604, 30186, -1, 30188, 38605, 30164, -1, 38604, 38605, 30188, -1, 30164, 38606, 30165, -1, 38605, 38606, 30164, -1, 30165, 38607, 30171, -1, 38606, 38607, 30165, -1, 30171, 38608, 30174, -1, 38607, 38608, 30171, -1, 30174, 38609, 30177, -1, 38608, 38609, 30174, -1, 30177, 38610, 30175, -1, 38609, 38610, 30177, -1, 38610, 38611, 30175, -1, 30175, 38612, 30172, -1, 38611, 38612, 30175, -1, 30172, 30190, 30167, -1, 38612, 30190, 30172, -1, 38613, 38614, 38615, -1, 38616, 38617, 38618, -1, 38619, 38620, 38621, -1, 38613, 38615, 38622, -1, 38619, 38603, 38602, -1, 38619, 38602, 38620, -1, 38619, 38621, 38623, -1, 38616, 38624, 38617, -1, 38625, 38623, 38626, -1, 38627, 38618, 38628, -1, 38627, 38628, 38629, -1, 38625, 38626, 38630, -1, 38631, 38629, 38632, -1, 38633, 38630, 38634, -1, 38633, 38634, 38635, -1, 30190, 38612, 38636, -1, 38631, 38632, 38637, -1, 38638, 38639, 38640, -1, 38638, 38641, 38639, -1, 38642, 38643, 38644, -1, 38642, 38635, 38643, -1, 38645, 38646, 38647, -1, 38645, 38637, 38646, -1, 38648, 38649, 38641, -1, 38650, 38644, 38651, -1, 38648, 38641, 38638, -1, 38652, 38647, 38653, -1, 38652, 38653, 38654, -1, 38650, 38651, 38655, -1, 38656, 38657, 38658, -1, 38659, 38640, 38660, -1, 38661, 38624, 38616, -1, 38661, 38608, 38607, -1, 38659, 38638, 38640, -1, 38661, 38662, 38624, -1, 38656, 38655, 38657, -1, 38661, 38607, 38662, -1, 38663, 38616, 38618, -1, 38664, 38619, 38623, -1, 38664, 38604, 38603, -1, 38665, 38666, 38649, -1, 38664, 38603, 38619, -1, 38664, 38623, 38625, -1, 38663, 38618, 38627, -1, 38665, 38649, 38648, -1, 38667, 38629, 38631, -1, 38668, 38625, 38630, -1, 38669, 38648, 38638, -1, 38667, 38627, 38629, -1, 38668, 38630, 38633, -1, 38670, 38633, 38635, -1, 38669, 38638, 38659, -1, 38671, 38631, 38637, -1, 38670, 38635, 38642, -1, 38672, 38659, 38660, -1, 38671, 38637, 38645, -1, 38672, 38660, 38673, -1, 38601, 30203, 38674, -1, 38675, 38642, 38644, -1, 38675, 38644, 38650, -1, 38676, 38645, 38647, -1, 38676, 38647, 38652, -1, 38677, 38678, 38666, -1, 38677, 38666, 38665, -1, 38679, 38650, 38655, -1, 38680, 38654, 38681, -1, 38679, 38655, 38656, -1, 38680, 38681, 38682, -1, 38683, 38648, 38669, -1, 38680, 38682, 38684, -1, 38683, 38665, 38648, -1, 38685, 38658, 38686, -1, 38680, 38652, 38654, -1, 38687, 38661, 38616, -1, 38687, 38609, 38608, -1, 38687, 38608, 38661, -1, 38685, 38656, 38658, -1, 38688, 38669, 38659, -1, 38687, 38616, 38663, -1, 38689, 38605, 38604, -1, 38690, 38627, 38667, -1, 38689, 38625, 38668, -1, 38689, 38604, 38664, -1, 38688, 38659, 38672, -1, 38689, 38664, 38625, -1, 38691, 38673, 38692, -1, 38690, 38663, 38627, -1, 38693, 38668, 38633, -1, 38693, 38633, 38670, -1, 38694, 38631, 38671, -1, 38691, 38672, 38673, -1, 38694, 38667, 38631, -1, 38621, 38695, 38678, -1, 38617, 38642, 38675, -1, 38617, 38670, 38642, -1, 38621, 38678, 38677, -1, 38696, 38671, 38645, -1, 38628, 38675, 38650, -1, 38696, 38645, 38676, -1, 38628, 38650, 38679, -1, 38697, 38684, 38698, -1, 38626, 38665, 38683, -1, 38697, 38676, 38652, -1, 38626, 38677, 38665, -1, 38697, 38680, 38684, -1, 38697, 38652, 38680, -1, 38699, 38609, 38687, -1, 38699, 38610, 38609, -1, 38634, 38683, 38669, -1, 38699, 38687, 38663, -1, 38699, 38663, 38690, -1, 38632, 38679, 38656, -1, 38634, 38669, 38688, -1, 38632, 38656, 38685, -1, 38643, 38688, 38672, -1, 38700, 38690, 38667, -1, 38646, 38685, 38686, -1, 38646, 38686, 38701, -1, 38700, 38667, 38694, -1, 38643, 38672, 38691, -1, 38702, 38606, 38605, -1, 38651, 38692, 38703, -1, 38702, 38668, 38693, -1, 38704, 38694, 38671, -1, 38702, 38605, 38689, -1, 38702, 38689, 38668, -1, 38651, 38691, 38692, -1, 38704, 38671, 38696, -1, 38705, 38698, 38706, -1, 38620, 38602, 38601, -1, 38620, 38674, 38695, -1, 38705, 38676, 38697, -1, 38620, 38695, 38621, -1, 38705, 38697, 38698, -1, 38624, 38693, 38670, -1, 38620, 38601, 38674, -1, 38624, 38670, 38617, -1, 38705, 38696, 38676, -1, 38707, 38611, 38610, -1, 38707, 38690, 38700, -1, 38623, 38677, 38626, -1, 38707, 38610, 38699, -1, 38707, 38699, 38690, -1, 38618, 38675, 38628, -1, 38615, 38694, 38704, -1, 38618, 38617, 38675, -1, 38623, 38621, 38677, -1, 38630, 38626, 38683, -1, 38629, 38628, 38679, -1, 38615, 38700, 38694, -1, 38630, 38683, 38634, -1, 38629, 38679, 38632, -1, 38708, 38706, 38709, -1, 38708, 38705, 38706, -1, 38708, 38704, 38696, -1, 38708, 38696, 38705, -1, 38635, 38688, 38643, -1, 38635, 38634, 38688, -1, 38644, 38643, 38691, -1, 38614, 38612, 38611, -1, 38614, 38611, 38707, -1, 38637, 38685, 38646, -1, 38614, 38707, 38700, -1, 38637, 38632, 38685, -1, 38614, 38700, 38615, -1, 38644, 38691, 38651, -1, 38622, 38709, 38710, -1, 38647, 38701, 38653, -1, 38622, 38708, 38709, -1, 38647, 38646, 38701, -1, 38655, 38703, 38657, -1, 38622, 38615, 38704, -1, 38622, 38704, 38708, -1, 38662, 38607, 38606, -1, 38613, 38612, 38614, -1, 38662, 38606, 38702, -1, 38613, 38710, 38636, -1, 38655, 38651, 38703, -1, 38613, 38636, 38612, -1, 38662, 38702, 38693, -1, 38613, 38622, 38710, -1, 38662, 38693, 38624, -1, 30290, 32646, 30257, -1, 30257, 32646, 30252, -1, 30252, 32692, 30251, -1, 32646, 32692, 30252, -1, 30251, 32691, 30275, -1, 32692, 32691, 30251, -1, 30275, 32715, 30273, -1, 32691, 32715, 30275, -1, 30273, 32730, 30271, -1, 32715, 32730, 30273, -1, 30271, 32690, 30269, -1, 32730, 32690, 30271, -1, 30269, 32689, 30263, -1, 32690, 32689, 30269, -1, 30263, 32716, 30260, -1, 32689, 32716, 30263, -1, 30260, 32727, 30258, -1, 32716, 32727, 30260, -1, 30258, 32735, 30255, -1, 32727, 32735, 30258, -1, 30255, 32652, 30259, -1, 32735, 32652, 30255, -1, 30259, 32648, 30262, -1, 32652, 32648, 30259, -1, 30262, 30277, 30265, -1, 32648, 30277, 30262, -1, 30250, 8258, 9588, -1, 30250, 30732, 8258, -1, 30732, 8268, 8258, -1, 8268, 30295, 9594, -1, 8268, 30734, 30295, -1, 30732, 30734, 8268, -1, 31822, 31821, 38541, -1, 31822, 38541, 38540, -1, 2550, 38711, 38712, -1, 2551, 2550, 38712, -1, 2552, 2551, 38712, -1, 2553, 2552, 38712, -1, 38713, 38714, 38715, -1, 38716, 38713, 38715, -1, 38717, 38713, 38716, -1, 38718, 2554, 2553, -1, 38718, 2555, 2554, -1, 38718, 2556, 2555, -1, 38718, 2557, 2556, -1, 38718, 2558, 2557, -1, 38718, 2559, 2558, -1, 38718, 2553, 38712, -1, 38719, 2560, 2559, -1, 38719, 2561, 2560, -1, 38719, 2559, 38718, -1, 38719, 38713, 38717, -1, 38719, 38717, 2565, -1, 38719, 2565, 2564, -1, 38719, 2564, 2563, -1, 38719, 2563, 2562, -1, 38719, 2562, 2561, -1, 38720, 38721, 38722, -1, 38723, 38721, 38720, -1, 38721, 38724, 38722, -1, 38721, 38725, 38724, -1, 38724, 38726, 38727, -1, 38725, 38726, 38724, -1, 38728, 38729, 38730, -1, 38727, 38731, 38732, -1, 38726, 38731, 38727, -1, 38732, 38731, 38733, -1, 38728, 38734, 38729, -1, 38733, 38735, 38732, -1, 38733, 38719, 38735, -1, 38719, 38736, 38735, -1, 38736, 38718, 38734, -1, 38734, 38718, 38729, -1, 38719, 38718, 38736, -1, 38718, 38712, 38729, -1, 38712, 38737, 38729, -1, 38738, 38739, 38740, -1, 38741, 38740, 38739, -1, 38742, 38741, 38739, -1, 38743, 38741, 38742, -1, 38744, 38743, 38742, -1, 38745, 38723, 38720, -1, 38746, 38745, 38720, -1, 38747, 38748, 38749, -1, 38750, 38749, 38746, -1, 38750, 38747, 38749, -1, 38751, 38752, 38753, -1, 38754, 38751, 38750, -1, 38754, 38750, 38746, -1, 38754, 38752, 38751, -1, 38755, 38739, 38738, -1, 38742, 38754, 38744, -1, 38744, 38754, 38746, -1, 38744, 38746, 38720, -1, 38753, 38756, 38757, -1, 38757, 38756, 38758, -1, 38758, 38759, 38757, -1, 38753, 38760, 38756, -1, 38753, 38752, 38760, -1, 38759, 38761, 38757, -1, 38757, 38762, 38763, -1, 38761, 38762, 38757, -1, 38762, 38764, 38763, -1, 38757, 38765, 38766, -1, 38757, 38763, 38765, -1, 38767, 38768, 38769, -1, 38770, 38767, 38769, -1, 38766, 38765, 38767, -1, 38766, 38767, 38770, -1, 38771, 38770, 38769, -1, 38771, 38772, 38770, -1, 38772, 38773, 38770, -1, 38773, 38774, 38770, -1, 38774, 38773, 38775, -1, 38776, 38777, 38738, -1, 38776, 38778, 38777, -1, 38740, 38776, 38738, -1, 38779, 38778, 38776, -1, 38780, 38779, 38776, -1, 38781, 38779, 38782, -1, 38779, 38780, 38782, -1, 38780, 38783, 38782, -1, 38738, 38784, 38755, -1, 38738, 38777, 38784, -1, 38785, 38743, 38744, -1, 38785, 38744, 38786, -1, 38787, 38785, 38786, -1, 38788, 38785, 38787, -1, 38789, 38787, 38790, -1, 38789, 38788, 38787, -1, 38782, 38790, 38791, -1, 38782, 38791, 38792, -1, 38782, 38789, 38790, -1, 38781, 38782, 38792, -1, 38725, 38793, 38794, -1, 38725, 38794, 38726, -1, 38713, 38795, 38796, -1, 38713, 38719, 38795, -1, 38719, 38733, 38795, -1, 38731, 38797, 38733, -1, 38795, 38797, 38798, -1, 38733, 38797, 38795, -1, 38794, 38731, 38726, -1, 38797, 38731, 38794, -1, 38723, 38799, 38721, -1, 38723, 38745, 38799, -1, 38721, 38799, 38793, -1, 38721, 38793, 38725, -1, 38566, 38581, 31869, -1, 38800, 38801, 38802, -1, 38803, 38804, 38801, -1, 38803, 38801, 38800, -1, 38805, 38804, 38803, -1, 38806, 38804, 38805, -1, 38807, 38804, 38806, -1, 38808, 38804, 38807, -1, 31870, 38566, 31869, -1, 31870, 38563, 38562, -1, 31870, 38558, 38563, -1, 31870, 38550, 38558, -1, 31870, 38600, 38566, -1, 31870, 38562, 38600, -1, 38809, 38804, 38808, -1, 38545, 38544, 38810, -1, 38811, 38804, 38809, -1, 38544, 38811, 38812, -1, 38544, 38804, 38811, -1, 38813, 38544, 38812, -1, 38814, 38804, 38544, -1, 38815, 38814, 38544, -1, 38597, 38816, 38817, -1, 38593, 38597, 38817, -1, 38575, 38818, 38816, -1, 38575, 38816, 38597, -1, 38594, 38593, 38817, -1, 38574, 38813, 38818, -1, 38574, 38544, 38813, -1, 38574, 38818, 38575, -1, 38589, 38594, 38817, -1, 38573, 38544, 38574, -1, 38585, 38589, 38817, -1, 38819, 38544, 38573, -1, 31869, 38585, 38817, -1, 38810, 38544, 38819, -1, 38586, 38585, 31869, -1, 38580, 38586, 31869, -1, 38581, 38580, 31869, -1, 38807, 38806, 38820, -1, 38820, 38806, 38821, -1, 38821, 38805, 38822, -1, 38806, 38805, 38821, -1, 38822, 38803, 38823, -1, 38805, 38803, 38822, -1, 38804, 38824, 38801, -1, 38825, 38824, 38804, -1, 38800, 38802, 38826, -1, 38827, 38800, 38826, -1, 38828, 38829, 38830, -1, 38828, 38831, 38829, -1, 38824, 38832, 38833, -1, 38825, 38832, 38824, -1, 38825, 38834, 38832, -1, 38825, 38555, 38834, -1, 38834, 38554, 38835, -1, 38555, 38554, 38834, -1, 38554, 38836, 38835, -1, 38837, 38838, 38839, -1, 38836, 38838, 38837, -1, 38554, 38838, 38836, -1, 38837, 38830, 38829, -1, 38829, 38836, 38837, -1, 38543, 38840, 38838, -1, 38554, 38543, 38838, -1, 38841, 38842, 38843, -1, 38830, 38841, 38844, -1, 38830, 38844, 38845, -1, 38830, 38842, 38841, -1, 38828, 38830, 38845, -1, 38846, 38847, 38848, -1, 38846, 38849, 38847, -1, 38850, 38851, 38849, -1, 38737, 38730, 38729, -1, 38737, 38852, 38730, -1, 38852, 38842, 38847, -1, 38847, 38842, 38830, -1, 38852, 38847, 38851, -1, 38851, 38847, 38849, -1, 38852, 38851, 38730, -1, 38846, 38853, 38849, -1, 38854, 38855, 38856, -1, 38857, 38858, 38855, -1, 38855, 38858, 38856, -1, 38856, 38859, 38853, -1, 38858, 38859, 38856, -1, 38858, 38860, 38859, -1, 38859, 38849, 38853, -1, 38855, 38861, 38862, -1, 38855, 38854, 38861, -1, 38863, 38848, 38847, -1, 38864, 38848, 38863, -1, 38865, 38862, 38861, -1, 38865, 38861, 38866, -1, 38867, 38862, 38865, -1, 38868, 38862, 38867, -1, 38869, 38867, 38870, -1, 38869, 38868, 38867, -1, 38871, 38869, 38870, -1, 38872, 38873, 38874, -1, 38872, 38871, 38873, -1, 38872, 38869, 38871, -1, 38871, 38863, 38873, -1, 38847, 38873, 38863, -1, 32320, 38875, 38876, -1, 32316, 38875, 32320, -1, 32318, 38877, 38878, -1, 32313, 38877, 32318, -1, 38748, 38879, 38880, -1, 38748, 38747, 38879, -1, 38878, 32316, 32318, -1, 38875, 32316, 38878, -1, 38880, 38879, 38881, -1, 38880, 38881, 38882, -1, 38883, 38881, 38884, -1, 38882, 38881, 38883, -1, 38884, 38885, 38883, -1, 38886, 38885, 38884, -1, 38885, 38887, 38888, -1, 38885, 38886, 38887, -1, 32294, 38877, 32313, -1, 32347, 32346, 32294, -1, 32294, 32346, 38877, -1, 32293, 32294, 32313, -1, 38889, 32327, 32344, -1, 32344, 32345, 38889, -1, 32345, 38890, 38889, -1, 32345, 32310, 38890, -1, 32310, 32309, 38890, -1, 32320, 38876, 32319, -1, 32319, 38891, 32309, -1, 38876, 38891, 32319, -1, 32233, 38892, 32231, -1, 38892, 38893, 38891, -1, 38891, 38893, 32309, -1, 32233, 38893, 38892, -1, 38893, 38890, 32309, -1, 38889, 32333, 32327, -1, 32345, 32305, 32310, -1, 32341, 32305, 32345, -1, 38894, 38895, 38896, -1, 38894, 38896, 38897, -1, 38894, 38897, 38898, -1, 38894, 38898, 38899, -1, 38900, 38901, 38902, -1, 38903, 38904, 38905, -1, 38903, 38905, 38906, -1, 31819, 38538, 38907, -1, 31819, 38907, 38908, -1, 31819, 38908, 38909, -1, 38910, 38903, 38906, -1, 38911, 38906, 38912, -1, 31818, 38909, 38913, -1, 31818, 38913, 38914, -1, 31818, 38914, 38915, -1, 38911, 38910, 38906, -1, 31818, 38915, 38916, -1, 31818, 38916, 38917, -1, 38918, 38912, 38919, -1, 38918, 38911, 38912, -1, 31818, 31819, 38909, -1, 38920, 31818, 38917, -1, 38920, 38917, 38921, -1, 38920, 38921, 38922, -1, 38920, 38922, 38923, -1, 38920, 38923, 38924, -1, 38920, 38925, 31818, -1, 38902, 38920, 38900, -1, 38900, 38920, 38924, -1, 38926, 38539, 38927, -1, 38901, 38919, 38895, -1, 38901, 38894, 38902, -1, 38901, 38895, 38894, -1, 38901, 38918, 38919, -1, 38928, 38926, 38929, -1, 38930, 38926, 38928, -1, 38931, 38926, 38930, -1, 38932, 38538, 38539, -1, 38932, 38539, 38926, -1, 38932, 38926, 38931, -1, 38933, 38538, 38932, -1, 38934, 38538, 38933, -1, 38907, 38538, 38934, -1, 38935, 38919, 38912, -1, 38935, 38936, 38919, -1, 38937, 38912, 38906, -1, 38937, 38935, 38912, -1, 38938, 38906, 38905, -1, 38938, 38937, 38906, -1, 38939, 38902, 38894, -1, 38939, 38940, 38902, -1, 38941, 38849, 38859, -1, 38941, 38850, 38849, -1, 30125, 38852, 2481, -1, 38737, 38712, 38852, -1, 38852, 2482, 2481, -1, 38712, 38711, 38852, -1, 38852, 38711, 2482, -1, 38942, 38943, 31697, -1, 38784, 38942, 31697, -1, 31659, 38755, 38784, -1, 31659, 38784, 31697, -1, 38944, 38755, 31659, -1, 38945, 38946, 30161, -1, 38947, 38948, 38945, -1, 38947, 38949, 38948, -1, 38947, 38945, 30161, -1, 30159, 38947, 30161, -1, 38950, 38947, 30159, -1, 38951, 38950, 30159, -1, 31088, 38952, 30155, -1, 31086, 30155, 30148, -1, 31086, 31088, 30155, -1, 38953, 31086, 30148, -1, 38954, 38955, 38956, -1, 38956, 38955, 38957, -1, 38958, 38959, 38960, -1, 38960, 38959, 38954, -1, 38954, 38959, 38955, -1, 38958, 38961, 38959, -1, 38961, 38962, 38963, -1, 38963, 38962, 38964, -1, 38965, 38962, 38958, -1, 38966, 38962, 38965, -1, 38958, 38962, 38961, -1, 38966, 38967, 38962, -1, 38966, 38968, 38967, -1, 38947, 38969, 38966, -1, 38950, 38969, 38947, -1, 38966, 38969, 38968, -1, 38970, 38971, 38972, -1, 38972, 38971, 38969, -1, 38969, 38971, 38968, -1, 38973, 38974, 38975, -1, 38976, 38977, 34367, -1, 38978, 38977, 38976, -1, 38974, 38977, 38978, -1, 38979, 38980, 38977, -1, 38977, 38981, 34367, -1, 38980, 38981, 38977, -1, 38981, 34380, 34367, -1, 38973, 38977, 38974, -1, 30206, 30388, 10555, -1, 10555, 38982, 11368, -1, 30388, 38982, 10555, -1, 8259, 30250, 9593, -1, 30732, 30250, 8259, -1, 30389, 8259, 7887, -1, 30389, 30732, 8259, -1, 38983, 30128, 30131, -1, 30128, 38843, 38842, -1, 38984, 38843, 38985, -1, 38985, 38843, 38983, -1, 38983, 38843, 30128, -1, 38984, 38986, 38843, -1, 38984, 38987, 38986, -1, 11368, 38988, 10366, -1, 11368, 38989, 38990, -1, 11368, 38990, 38991, -1, 11368, 38991, 38992, -1, 11368, 38992, 38988, -1, 38982, 38823, 38993, -1, 38984, 38823, 38987, -1, 38993, 38823, 38984, -1, 38982, 38822, 38823, -1, 38982, 38821, 38822, -1, 38982, 38820, 38821, -1, 38994, 30387, 38995, -1, 30388, 30387, 38996, -1, 38995, 30387, 30630, -1, 38996, 30387, 38997, -1, 38997, 30387, 38998, -1, 38998, 30387, 38999, -1, 38999, 30387, 39000, -1, 38982, 39001, 38820, -1, 39000, 30387, 39002, -1, 39002, 30387, 39003, -1, 39003, 30387, 39004, -1, 39004, 30387, 38994, -1, 38982, 39005, 39001, -1, 38982, 39006, 39005, -1, 38982, 39007, 39006, -1, 38982, 39008, 39007, -1, 38982, 30388, 39008, -1, 39009, 39010, 39011, -1, 39012, 39013, 39011, -1, 39011, 39013, 39009, -1, 39010, 39014, 39011, -1, 39012, 39015, 39013, -1, 39014, 39016, 39011, -1, 39008, 39017, 39012, -1, 30388, 39017, 39008, -1, 39012, 39017, 39015, -1, 39011, 39018, 30630, -1, 39016, 39018, 39011, -1, 30388, 39019, 39017, -1, 39018, 39020, 30630, -1, 30388, 39021, 39019, -1, 39020, 39022, 30630, -1, 30388, 39023, 39021, -1, 39022, 39024, 30630, -1, 30388, 39025, 39023, -1, 39024, 39026, 30630, -1, 30388, 38996, 39025, -1, 39026, 38995, 30630, -1, 39027, 39028, 39029, -1, 39030, 39031, 39032, -1, 39033, 39034, 39035, -1, 39036, 39004, 39037, -1, 39033, 39035, 39017, -1, 39033, 39017, 39019, -1, 39038, 39039, 39040, -1, 39033, 39019, 39021, -1, 39033, 39027, 39034, -1, 39033, 39041, 39042, -1, 39030, 39043, 39031, -1, 39033, 39021, 39041, -1, 39033, 39042, 39027, -1, 39044, 39045, 39046, -1, 39038, 39040, 39047, -1, 39048, 39047, 39049, -1, 39044, 39032, 39045, -1, 39048, 39049, 39050, -1, 39051, 39046, 39052, -1, 39053, 39054, 39055, -1, 39051, 39052, 39056, -1, 39053, 39057, 39054, -1, 39058, 39050, 39059, -1, 39058, 39059, 39060, -1, 39061, 39056, 39062, -1, 39061, 39062, 39063, -1, 39064, 39065, 39057, -1, 39066, 39060, 39067, -1, 39066, 39067, 39068, -1, 39064, 39057, 39053, -1, 39069, 39063, 39070, -1, 39071, 39072, 39073, -1, 39074, 39055, 39075, -1, 39069, 39070, 39076, -1, 39071, 39068, 39072, -1, 39074, 39053, 39055, -1, 39077, 39043, 39030, -1, 39078, 39036, 39039, -1, 39079, 39065, 39064, -1, 39077, 38997, 38998, -1, 39078, 39002, 39003, -1, 39077, 39080, 39043, -1, 39078, 39003, 39036, -1, 39079, 39081, 39065, -1, 39077, 38998, 39080, -1, 39082, 39030, 39032, -1, 39078, 39039, 39038, -1, 39082, 39032, 39044, -1, 39083, 39038, 39047, -1, 39084, 39064, 39053, -1, 39083, 39047, 39048, -1, 39085, 39050, 39058, -1, 39085, 39048, 39050, -1, 39084, 39053, 39074, -1, 39086, 39074, 39075, -1, 39086, 39075, 39087, -1, 39088, 39044, 39046, -1, 39088, 39046, 39051, -1, 39089, 39051, 39056, -1, 39090, 39058, 39060, -1, 39004, 38994, 39091, -1, 39092, 39093, 39081, -1, 39090, 39060, 39066, -1, 39089, 39056, 39061, -1, 39092, 39081, 39079, -1, 39094, 39063, 39069, -1, 39095, 39066, 39068, -1, 39096, 39064, 39084, -1, 39095, 39068, 39071, -1, 39096, 39079, 39064, -1, 39094, 39061, 39063, -1, 39097, 39076, 39098, -1, 39099, 39073, 39100, -1, 39097, 39098, 39101, -1, 39097, 39101, 39102, -1, 39099, 39071, 39073, -1, 39103, 39084, 39074, -1, 39097, 39069, 39076, -1, 39104, 39077, 39030, -1, 39105, 39000, 39002, -1, 39104, 38996, 38997, -1, 39105, 39002, 39078, -1, 39103, 39074, 39086, -1, 39104, 38997, 39077, -1, 39105, 39038, 39083, -1, 39105, 39078, 39038, -1, 39106, 39087, 39107, -1, 39104, 39030, 39082, -1, 39108, 39044, 39088, -1, 39108, 39082, 39044, -1, 39109, 39083, 39048, -1, 39106, 39086, 39087, -1, 39109, 39048, 39085, -1, 39110, 39088, 39051, -1, 39110, 39051, 39089, -1, 39111, 39112, 39093, -1, 39031, 39058, 39090, -1, 39031, 39085, 39058, -1, 39111, 39093, 39092, -1, 39040, 39079, 39096, -1, 39045, 39090, 39066, -1, 39040, 39092, 39079, -1, 39045, 39066, 39095, -1, 39049, 39096, 39084, -1, 39113, 39089, 39061, -1, 39113, 39061, 39094, -1, 39114, 39097, 39102, -1, 39114, 39102, 39115, -1, 39114, 39094, 39069, -1, 39049, 39084, 39103, -1, 39114, 39069, 39097, -1, 39116, 39104, 39082, -1, 39052, 39071, 39099, -1, 39116, 39025, 38996, -1, 39052, 39095, 39071, -1, 39116, 38996, 39104, -1, 39062, 39100, 39117, -1, 39059, 39103, 39086, -1, 39116, 39082, 39108, -1, 39059, 39086, 39106, -1, 39067, 39106, 39107, -1, 39067, 39107, 39118, -1, 39062, 39099, 39100, -1, 39119, 39108, 39088, -1, 39119, 39088, 39110, -1, 39120, 38999, 39000, -1, 39120, 39000, 39105, -1, 39120, 39105, 39083, -1, 39120, 39083, 39109, -1, 39037, 39091, 39112, -1, 39037, 39004, 39091, -1, 39037, 39112, 39111, -1, 39028, 39110, 39089, -1, 39028, 39089, 39113, -1, 39043, 39109, 39085, -1, 39121, 39115, 39122, -1, 39043, 39085, 39031, -1, 39039, 39092, 39040, -1, 39121, 39114, 39115, -1, 39121, 39113, 39094, -1, 39121, 39094, 39114, -1, 39039, 39111, 39092, -1, 39032, 39090, 39045, -1, 39032, 39031, 39090, -1, 39123, 39023, 39025, -1, 39123, 39025, 39116, -1, 39047, 39040, 39096, -1, 39123, 39116, 39108, -1, 39047, 39096, 39049, -1, 39123, 39108, 39119, -1, 39046, 39045, 39095, -1, 39046, 39095, 39052, -1, 39042, 39119, 39110, -1, 39050, 39103, 39059, -1, 39050, 39049, 39103, -1, 39042, 39110, 39028, -1, 39029, 39122, 39124, -1, 39056, 39052, 39099, -1, 39029, 39121, 39122, -1, 39029, 39028, 39113, -1, 39060, 39106, 39067, -1, 39029, 39113, 39121, -1, 39060, 39059, 39106, -1, 39056, 39099, 39062, -1, 39041, 39119, 39042, -1, 39068, 39118, 39072, -1, 39063, 39117, 39070, -1, 39041, 39021, 39023, -1, 39041, 39023, 39123, -1, 39041, 39123, 39119, -1, 39063, 39062, 39117, -1, 39027, 39124, 39034, -1, 39068, 39067, 39118, -1, 39036, 39037, 39111, -1, 39080, 38998, 38999, -1, 39027, 39029, 39124, -1, 39080, 38999, 39120, -1, 39080, 39120, 39109, -1, 39036, 39003, 39004, -1, 39027, 39042, 39028, -1, 39080, 39109, 39043, -1, 39036, 39111, 39039, -1, 39125, 39126, 39127, -1, 39127, 39126, 39128, -1, 39128, 39126, 39129, -1, 39129, 39126, 33669, -1, 39126, 33616, 33669, -1, 39126, 39130, 33616, -1, 39131, 39132, 39133, -1, 39126, 39132, 39130, -1, 39130, 39132, 39134, -1, 39134, 39132, 39131, -1, 39135, 39136, 39137, -1, 39136, 38975, 39137, -1, 38974, 39138, 38975, -1, 38975, 39138, 39137, -1, 39139, 39131, 39133, -1, 39139, 39133, 39140, -1, 39141, 39142, 39143, -1, 39144, 39137, 39138, -1, 39143, 39142, 39145, -1, 39145, 39142, 39146, -1, 39146, 39147, 39148, -1, 39142, 39147, 39146, -1, 39149, 39150, 39151, -1, 39151, 39152, 39153, -1, 39150, 39152, 39151, -1, 39154, 39144, 39147, -1, 39153, 39144, 39154, -1, 39152, 39144, 39153, -1, 39148, 39155, 39156, -1, 39148, 39157, 39155, -1, 39156, 39139, 39148, -1, 39148, 39158, 39157, -1, 39148, 39159, 39158, -1, 39139, 39140, 39148, -1, 39140, 39160, 39161, -1, 39140, 39133, 39160, -1, 39147, 39162, 39148, -1, 39144, 39162, 39147, -1, 39148, 39162, 39159, -1, 39144, 39163, 39162, -1, 39144, 39164, 39163, -1, 39144, 39165, 39164, -1, 39144, 39166, 39165, -1, 39144, 39167, 39166, -1, 39144, 39168, 39167, -1, 39144, 39138, 39168, -1, 39169, 39162, 39163, -1, 39169, 39170, 39162, -1, 39171, 39170, 39169, -1, 39172, 39171, 39169, -1, 39173, 39171, 39172, -1, 39174, 39173, 39172, -1, 39175, 39176, 39177, -1, 39175, 39177, 39178, -1, 39175, 39178, 39179, -1, 39180, 39175, 39179, -1, 39181, 39175, 39180, -1, 39182, 39175, 39181, -1, 39183, 39175, 39182, -1, 39184, 39183, 39185, -1, 39184, 39185, 39186, -1, 39184, 39175, 39183, -1, 39187, 39184, 39186, -1, 39188, 39184, 39187, -1, 38993, 39189, 39184, -1, 38982, 38989, 11368, -1, 38982, 39188, 38989, -1, 38982, 39184, 39188, -1, 38982, 38993, 39184, -1, 39175, 39190, 39176, -1, 39191, 39189, 39192, -1, 39191, 39184, 39189, -1, 39193, 39192, 39194, -1, 39193, 39191, 39192, -1, 39195, 39194, 39196, -1, 39195, 39193, 39194, -1, 39197, 39198, 38946, -1, 39197, 39199, 39198, -1, 39197, 38946, 38945, -1, 39200, 39197, 38945, -1, 39201, 38945, 39202, -1, 39201, 39200, 38945, -1, 39203, 3235, 3232, -1, 39203, 39204, 3235, -1, 39205, 39206, 39203, -1, 39207, 39208, 39206, -1, 39207, 39206, 39205, -1, 39209, 39210, 39208, -1, 39209, 39208, 39207, -1, 39211, 39212, 39213, -1, 39214, 39213, 39212, -1, 39215, 39210, 39209, -1, 39204, 39203, 39216, -1, 39204, 39216, 39217, -1, 39218, 39219, 39215, -1, 39220, 39212, 39211, -1, 39215, 39219, 39210, -1, 39210, 39219, 39221, -1, 39222, 39212, 39220, -1, 39223, 39219, 39212, -1, 39223, 39212, 39222, -1, 39224, 39219, 39223, -1, 39225, 39226, 39214, -1, 39227, 39228, 39226, -1, 39227, 39226, 39225, -1, 39229, 39230, 39228, -1, 39229, 39228, 39227, -1, 39231, 39214, 39212, -1, 39231, 39225, 39214, -1, 39232, 39233, 39230, -1, 39232, 39230, 39229, -1, 39204, 39233, 39232, -1, 39234, 39219, 39224, -1, 39221, 39219, 39234, -1, 39217, 39233, 39204, -1, 39203, 39206, 39216, -1, 39200, 39235, 3142, -1, 3144, 39200, 3142, -1, 39197, 3144, 30163, -1, 39197, 39200, 3144, -1, 39236, 3150, 3145, -1, 39236, 39237, 3150, -1, 39238, 39236, 3145, -1, 39239, 39240, 39237, -1, 39236, 39239, 39237, -1, 39241, 39242, 3156, -1, 39241, 3156, 3153, -1, 39243, 39244, 39242, -1, 39243, 39242, 39241, -1, 39243, 39245, 39246, -1, 39243, 39241, 39245, -1, 39247, 39243, 39248, -1, 39247, 39248, 39249, -1, 39247, 39249, 39250, -1, 39251, 39252, 39253, -1, 39254, 39255, 39251, -1, 39256, 39254, 39251, -1, 39257, 39251, 39253, -1, 39257, 39256, 39251, -1, 39258, 39259, 39247, -1, 39258, 39260, 39259, -1, 39258, 39261, 39260, -1, 39258, 39262, 39261, -1, 39258, 39263, 39262, -1, 39258, 39264, 39263, -1, 39258, 39253, 39264, -1, 39258, 39247, 39250, -1, 39258, 39257, 39253, -1, 39265, 39258, 39250, -1, 39266, 39267, 39265, -1, 39266, 39265, 39250, -1, 39268, 39267, 39266, -1, 39269, 39267, 39268, -1, 39247, 39244, 39243, -1, 3108, 39270, 30121, -1, 39271, 3108, 3157, -1, 39271, 39270, 3108, -1, 39270, 39272, 39273, -1, 39274, 39272, 39270, -1, 39272, 39275, 39273, -1, 39275, 39276, 39273, -1, 39274, 39271, 39277, -1, 39270, 39271, 39274, -1, 39271, 39278, 39277, -1, 39276, 39279, 39273, -1, 39278, 39280, 39277, -1, 39281, 39282, 39283, -1, 39283, 39282, 39284, -1, 39284, 39282, 39285, -1, 39285, 39282, 39286, -1, 39286, 39282, 39287, -1, 39287, 39282, 39279, -1, 39279, 39282, 39273, -1, 39288, 39289, 39290, -1, 39290, 39289, 39281, -1, 39281, 39289, 39282, -1, 39278, 39289, 39280, -1, 39280, 39289, 39291, -1, 39291, 39289, 39292, -1, 39292, 39289, 39288, -1, 39293, 39274, 39294, -1, 39293, 39294, 39295, -1, 39293, 39272, 39274, -1, 39296, 39295, 39297, -1, 39296, 39293, 39295, -1, 39298, 39296, 39297, -1, 39299, 39300, 39301, -1, 39302, 39301, 39300, -1, 39303, 39301, 39304, -1, 39303, 39299, 39301, -1, 39305, 39303, 39304, -1, 39306, 39301, 39302, -1, 39307, 39308, 39309, -1, 39307, 39310, 39308, -1, 39307, 39311, 39310, -1, 39307, 39304, 39311, -1, 39307, 39305, 39304, -1, 39312, 39301, 39306, -1, 30124, 39313, 30126, -1, 30124, 39314, 39313, -1, 30124, 39315, 39314, -1, 30124, 39316, 39315, -1, 30124, 39309, 39316, -1, 30124, 39307, 39309, -1, 39317, 39307, 30124, -1, 39318, 39317, 30124, -1, 39319, 39301, 39312, -1, 39320, 39301, 39319, -1, 39321, 39322, 39320, -1, 39323, 39320, 39319, -1, 39323, 39321, 39320, -1, 39324, 39321, 39323, -1, 39325, 39321, 39324, -1, 39326, 39321, 39325, -1, 39327, 39321, 39326, -1, 39328, 39321, 39327, -1, 39317, 39329, 39307, -1, 30126, 39330, 30127, -1, 30127, 39330, 39331, -1, 39330, 39332, 39331, -1, 39330, 39333, 39332, -1, 39332, 39334, 39335, -1, 39333, 39336, 39332, -1, 39332, 39337, 39334, -1, 39336, 39338, 39332, -1, 39332, 39339, 39337, -1, 39338, 39339, 39332, -1, 39331, 39332, 39340, -1, 39341, 39340, 39342, -1, 39341, 39331, 39340, -1, 39343, 39342, 39344, -1, 39343, 39341, 39342, -1, 39345, 39343, 39344, -1, 39346, 39347, 39348, -1, 39346, 39349, 39350, -1, 39351, 39350, 39352, -1, 39351, 39346, 39350, -1, 39351, 39353, 39347, -1, 39351, 39347, 39346, -1, 39354, 39355, 39353, -1, 39354, 39351, 39352, -1, 39354, 39353, 39351, -1, 39356, 39352, 39335, -1, 39356, 39335, 39334, -1, 39356, 39334, 39337, -1, 39356, 39355, 39354, -1, 39356, 39337, 39355, -1, 39356, 39354, 39352, -1, 39333, 39357, 39358, -1, 39333, 39330, 39357, -1, 39350, 39349, 39359, -1, 39360, 39320, 39361, -1, 39360, 39362, 39320, -1, 39363, 39364, 39362, -1, 39363, 39358, 39364, -1, 39363, 39362, 39360, -1, 39365, 39336, 39333, -1, 39365, 39333, 39358, -1, 39365, 39358, 39363, -1, 39366, 39361, 39367, -1, 39366, 39360, 39361, -1, 39368, 39363, 39360, -1, 39368, 39360, 39366, -1, 39369, 39365, 39363, -1, 39369, 39336, 39365, -1, 39369, 39363, 39368, -1, 39370, 39367, 39371, -1, 39370, 39366, 39367, -1, 39372, 39366, 39370, -1, 39372, 39368, 39366, -1, 39373, 39339, 39338, -1, 39373, 39338, 39336, -1, 39373, 39336, 39369, -1, 39374, 39368, 39372, -1, 39374, 39369, 39368, -1, 39347, 39371, 39348, -1, 39347, 39370, 39371, -1, 39353, 39372, 39370, -1, 39353, 39370, 39347, -1, 39375, 39337, 39339, -1, 39375, 39339, 39373, -1, 39375, 39373, 39369, -1, 39375, 39369, 39374, -1, 39355, 39374, 39372, -1, 39355, 39337, 39375, -1, 39355, 39372, 39353, -1, 39355, 39375, 39374, -1, 39346, 39348, 39349, -1, 31329, 39376, 39377, -1, 39378, 31329, 39377, -1, 31304, 31329, 39378, -1, 31505, 39379, 31506, -1, 39380, 39379, 39381, -1, 31506, 39379, 39380, -1, 39381, 39382, 39383, -1, 39379, 39382, 39381, -1, 39383, 39384, 39385, -1, 39382, 39384, 39383, -1, 39385, 39386, 39387, -1, 39384, 39386, 39385, -1, 39387, 39388, 39389, -1, 39386, 39388, 39387, -1, 39389, 39390, 39376, -1, 39388, 39390, 39389, -1, 39390, 39377, 39376, -1, 39391, 39392, 39393, -1, 39393, 39392, 39394, -1, 39274, 39277, 39294, -1, 39294, 39277, 39395, -1, 39294, 39395, 39295, -1, 39396, 39397, 39398, -1, 39295, 39395, 39399, -1, 39391, 39400, 39392, -1, 39401, 39400, 39402, -1, 39402, 39400, 39403, -1, 39403, 39400, 39391, -1, 39404, 39405, 39397, -1, 39397, 39405, 39398, -1, 39406, 39407, 39401, -1, 39401, 39407, 39400, -1, 39406, 39408, 39407, -1, 39297, 39408, 39406, -1, 39409, 39410, 39404, -1, 39404, 39410, 39405, -1, 39409, 39411, 39410, -1, 39412, 39413, 39414, -1, 39409, 39415, 39411, -1, 39414, 39416, 39417, -1, 39413, 39416, 39414, -1, 39418, 39419, 39412, -1, 39412, 39419, 39413, -1, 39416, 39420, 39417, -1, 39417, 39420, 39421, -1, 39418, 39422, 39419, -1, 39420, 39423, 39421, -1, 39409, 39424, 39415, -1, 39421, 39423, 39425, -1, 39426, 39427, 39409, -1, 39428, 39427, 39429, -1, 39429, 39427, 39426, -1, 39409, 39427, 39424, -1, 39430, 39431, 39432, -1, 39394, 39433, 39418, -1, 39432, 39431, 39434, -1, 39434, 39431, 39435, -1, 39435, 39431, 39436, -1, 39436, 39431, 39428, -1, 39418, 39433, 39422, -1, 39428, 39431, 39427, -1, 39437, 39438, 39430, -1, 39425, 39439, 39440, -1, 39423, 39439, 39425, -1, 39439, 39441, 39440, -1, 39430, 39438, 39431, -1, 39440, 39441, 39442, -1, 39408, 39443, 39437, -1, 39441, 39444, 39442, -1, 39437, 39443, 39438, -1, 39442, 39444, 39445, -1, 39297, 39446, 39408, -1, 39408, 39446, 39443, -1, 39394, 39447, 39433, -1, 39295, 39399, 39297, -1, 39444, 39396, 39445, -1, 39297, 39399, 39446, -1, 39396, 39398, 39445, -1, 39394, 39392, 39447, -1, 39448, 39449, 39450, -1, 39450, 39451, 39448, -1, 39448, 39452, 39449, -1, 39451, 39453, 39448, -1, 39448, 39454, 39452, -1, 39453, 39455, 39448, -1, 39455, 39456, 39448, -1, 39448, 39457, 39454, -1, 39456, 39458, 39448, -1, 39411, 39415, 39448, -1, 39448, 39415, 39457, -1, 39415, 39424, 39457, -1, 39424, 39427, 39457, -1, 39418, 39412, 39459, -1, 39459, 39412, 39460, -1, 39460, 39414, 39461, -1, 39412, 39414, 39460, -1, 39461, 39417, 39462, -1, 39414, 39417, 39461, -1, 39417, 39421, 39462, -1, 39462, 39425, 39463, -1, 39421, 39425, 39462, -1, 39463, 39440, 39464, -1, 39464, 39440, 39465, -1, 39425, 39440, 39463, -1, 39465, 39442, 39466, -1, 39440, 39442, 39465, -1, 39466, 39445, 39467, -1, 39467, 39445, 39468, -1, 39442, 39445, 39466, -1, 39468, 39398, 39469, -1, 39445, 39398, 39468, -1, 39469, 39405, 39470, -1, 39470, 39405, 39471, -1, 39398, 39405, 39469, -1, 39471, 39410, 39472, -1, 39405, 39410, 39471, -1, 39472, 39411, 39448, -1, 39410, 39411, 39472, -1, 39431, 39457, 39427, -1, 39459, 39394, 39418, -1, 39376, 39473, 39474, -1, 39475, 39476, 39477, -1, 39478, 39476, 39475, -1, 39478, 39479, 39476, -1, 39478, 39480, 39479, -1, 39478, 39481, 39480, -1, 39478, 39482, 39481, -1, 39483, 39484, 39478, -1, 39478, 39484, 39482, -1, 39485, 39486, 39483, -1, 39483, 39486, 39484, -1, 39487, 39488, 39485, -1, 39485, 39488, 39486, -1, 39489, 31329, 39487, -1, 39487, 31329, 39488, -1, 39376, 31329, 39473, -1, 39473, 31329, 39490, -1, 39490, 31329, 39489, -1, 39387, 39389, 39474, -1, 39389, 39376, 39474, -1, 31617, 39491, 39492, -1, 39492, 39491, 39493, -1, 39381, 39494, 39380, -1, 39380, 39494, 31506, -1, 31506, 39494, 31617, -1, 31617, 39494, 39491, -1, 39493, 39495, 39496, -1, 39491, 39495, 39493, -1, 39494, 39497, 39491, -1, 39381, 39497, 39494, -1, 39491, 39497, 39495, -1, 39496, 39498, 39499, -1, 39495, 39498, 39496, -1, 39499, 39500, 39501, -1, 39501, 39500, 39502, -1, 39498, 39500, 39499, -1, 39383, 39503, 39381, -1, 39495, 39503, 39498, -1, 39381, 39503, 39497, -1, 39497, 39503, 39495, -1, 39385, 39504, 39383, -1, 39503, 39504, 39498, -1, 39498, 39504, 39500, -1, 39383, 39504, 39503, -1, 39502, 39505, 39506, -1, 39387, 39505, 39385, -1, 39385, 39505, 39504, -1, 39500, 39505, 39502, -1, 39504, 39505, 39500, -1, 39474, 39505, 39387, -1, 39506, 39507, 39508, -1, 39508, 39507, 39474, -1, 39505, 39507, 39506, -1, 39474, 39507, 39505, -1, 32094, 39509, 32106, -1, 39510, 39509, 32094, -1, 32094, 39511, 39510, -1, 39509, 39512, 32106, -1, 32094, 39513, 39511, -1, 39512, 39514, 32106, -1, 32106, 38901, 38900, -1, 32094, 39515, 39513, -1, 39514, 39516, 32106, -1, 39516, 39517, 32106, -1, 32106, 39517, 38901, -1, 39517, 39518, 38901, -1, 39518, 39519, 38901, -1, 39519, 39520, 38901, -1, 39520, 39521, 38901, -1, 39521, 39522, 38901, -1, 39515, 31664, 39523, -1, 39523, 31664, 39524, -1, 39524, 31664, 39525, -1, 39525, 31664, 39526, -1, 39526, 31664, 39527, -1, 32094, 31664, 39515, -1, 39527, 31695, 39528, -1, 39528, 31695, 39529, -1, 39529, 31695, 39530, -1, 31664, 31695, 39527, -1, 39530, 39531, 39532, -1, 39532, 39531, 39533, -1, 39533, 39531, 39534, -1, 39534, 39531, 39535, -1, 39535, 39531, 39522, -1, 39536, 39531, 31695, -1, 31695, 39531, 39530, -1, 39531, 38901, 39522, -1, 39537, 39538, 39515, -1, 39515, 39538, 39513, -1, 39513, 39539, 39511, -1, 39538, 39539, 39513, -1, 39511, 39540, 39510, -1, 39539, 39540, 39511, -1, 39510, 39541, 39509, -1, 39540, 39541, 39510, -1, 39509, 39542, 39512, -1, 39541, 39542, 39509, -1, 39512, 39543, 39514, -1, 39542, 39543, 39512, -1, 39514, 39544, 39516, -1, 39543, 39544, 39514, -1, 39516, 39545, 39517, -1, 39544, 39545, 39516, -1, 39517, 39546, 39518, -1, 39545, 39546, 39517, -1, 39518, 39547, 39519, -1, 39546, 39547, 39518, -1, 39519, 39548, 39520, -1, 39547, 39548, 39519, -1, 39520, 39549, 39521, -1, 39548, 39549, 39520, -1, 39521, 39550, 39522, -1, 39549, 39550, 39521, -1, 31816, 31815, 31873, -1, 39551, 38868, 38869, -1, 39551, 39552, 38868, -1, 39553, 39552, 39551, -1, 39551, 39554, 39553, -1, 39555, 38925, 38920, -1, 2450, 38715, 2448, -1, 38715, 38714, 2448, -1, 32240, 32230, 2430, -1, 32230, 2427, 2430, -1, 32230, 32225, 2427, -1, 32225, 32224, 2427, -1, 38771, 38769, 2516, -1, 38769, 2517, 2516, -1, 38769, 38768, 2517, -1, 2425, 32227, 2426, -1, 32228, 32227, 2425, -1, 39556, 38788, 38789, -1, 39556, 38789, 39557, -1, 39558, 38860, 39559, -1, 38858, 39560, 38860, -1, 38860, 39561, 39559, -1, 39560, 39561, 38860, -1, 38783, 38780, 38776, -1, 39562, 39557, 38783, -1, 39562, 38776, 38740, -1, 39562, 38783, 38776, -1, 39556, 39557, 39562, -1, 38741, 39562, 38740, -1, 39563, 39560, 39564, -1, 39561, 39563, 39565, -1, 39561, 39560, 39563, -1, 39564, 39566, 39567, -1, 39563, 39564, 39567, -1, 39568, 39569, 38844, -1, 39568, 38844, 38841, -1, 39569, 38845, 38844, -1, 39570, 38814, 38815, -1, 39570, 38857, 38814, -1, 39566, 38857, 39570, -1, 38858, 38857, 39566, -1, 39564, 38858, 39566, -1, 39560, 38858, 39564, -1, 38814, 38825, 38804, -1, 38857, 38862, 38814, -1, 38814, 38862, 38825, -1, 38857, 38855, 38862, -1, 39553, 39570, 39552, -1, 39566, 39553, 39567, -1, 39566, 39570, 39553, -1, 38555, 38815, 38544, -1, 39570, 38815, 38555, -1, 38868, 39570, 38555, -1, 39552, 39570, 38868, -1, 39554, 39567, 39553, -1, 39565, 39554, 39571, -1, 39565, 39563, 39554, -1, 39563, 39567, 39554, -1, 39572, 39551, 39573, -1, 39554, 39572, 39571, -1, 39554, 39551, 39572, -1, 38869, 38872, 39573, -1, 39551, 38869, 39573, -1, 31814, 31818, 38925, -1, 31814, 38925, 39555, -1, 38543, 31864, 31814, -1, 38543, 39555, 38840, -1, 38543, 31814, 39555, -1, 38859, 39558, 38941, -1, 38860, 39558, 38859, -1, 38789, 38783, 39557, -1, 38789, 38782, 38783, -1, 39562, 38743, 38785, -1, 38741, 38743, 39562, -1, 38768, 38767, 2473, -1, 38768, 2473, 2517, -1, 2427, 32228, 2425, -1, 32224, 32228, 2427, -1, 32227, 32226, 2415, -1, 2426, 32227, 2415, -1, 38767, 38765, 2473, -1, 2473, 38765, 38763, -1, 38763, 2474, 2473, -1, 38763, 38764, 2474, -1, 2438, 38771, 2516, -1, 38772, 38771, 2438, -1, 38796, 39574, 2435, -1, 38795, 38798, 38796, -1, 38796, 38798, 39574, -1, 39574, 39575, 2435, -1, 38888, 39576, 39575, -1, 39576, 39577, 39575, -1, 39575, 39577, 2435, -1, 38888, 38887, 39576, -1, 38775, 38773, 39577, -1, 38773, 2438, 39577, -1, 39577, 2438, 2435, -1, 38773, 38772, 2438, -1, 38714, 38713, 2448, -1, 38713, 2435, 2448, -1, 38713, 38796, 2435, -1, 32305, 32343, 32308, -1, 32305, 32341, 32343, -1, 39556, 38785, 38788, -1, 39562, 38785, 39556, -1, 39578, 32298, 32348, -1, 32298, 32304, 32348, -1, 32298, 32300, 32304, -1, 32355, 32431, 39579, -1, 32354, 39579, 39580, -1, 32354, 32355, 39579, -1, 32353, 39580, 39581, -1, 32353, 32354, 39580, -1, 32352, 39581, 39582, -1, 32352, 32353, 39581, -1, 32349, 39582, 39583, -1, 32349, 32352, 39582, -1, 32350, 39583, 39584, -1, 32350, 32349, 39583, -1, 32351, 39585, 39578, -1, 32351, 39584, 39585, -1, 32351, 32350, 39584, -1, 32348, 32351, 39578, -1, 2477, 2472, 38762, -1, 2477, 38762, 38761, -1, 2476, 38761, 38759, -1, 2476, 2477, 38761, -1, 2475, 38759, 38758, -1, 2475, 2476, 38759, -1, 2437, 38758, 38756, -1, 2437, 2475, 38758, -1, 2436, 38756, 38760, -1, 2436, 2437, 38756, -1, 38754, 38760, 38752, -1, 38754, 2436, 38760, -1, 2467, 38754, 39586, -1, 2467, 2436, 38754, -1, 39587, 2467, 39586, -1, 2464, 2467, 39587, -1, 38893, 32233, 32232, -1, 38893, 2464, 39587, -1, 2462, 38893, 32232, -1, 2462, 2464, 38893, -1, 2459, 32232, 32234, -1, 2459, 2462, 32232, -1, 2454, 32234, 32235, -1, 2454, 32235, 32236, -1, 2454, 2459, 32234, -1, 2443, 32236, 32237, -1, 2443, 2454, 32236, -1, 2439, 32237, 32238, -1, 2439, 2443, 32237, -1, 2429, 32238, 32239, -1, 2429, 2439, 32238, -1, 32240, 2430, 2429, -1, 32240, 2429, 32239, -1, 38764, 38762, 2472, -1, 2474, 38764, 2472, -1, 2456, 2565, 38717, -1, 2453, 2456, 38717, -1, 2452, 38717, 38716, -1, 2452, 2453, 38717, -1, 2449, 2452, 38716, -1, 2449, 38715, 2450, -1, 38716, 38715, 2449, -1, 38711, 2480, 2482, -1, 38711, 2550, 2480, -1, 39588, 32468, 32467, -1, 39588, 39589, 32468, -1, 39590, 39582, 39581, -1, 39590, 39581, 39591, -1, 39590, 39591, 39589, -1, 39590, 39589, 39588, -1, 39592, 32467, 39593, -1, 39592, 39588, 32467, -1, 39594, 39583, 39582, -1, 39594, 39582, 39590, -1, 39594, 39592, 39583, -1, 39594, 39590, 39588, -1, 39594, 39588, 39592, -1, 39595, 39592, 39593, -1, 39595, 39593, 39596, -1, 39595, 39583, 39592, -1, 39597, 39585, 39584, -1, 39597, 39584, 39583, -1, 39597, 39583, 39595, -1, 39598, 39578, 39585, -1, 39598, 39585, 39597, -1, 39598, 39596, 39599, -1, 39598, 39595, 39596, -1, 39598, 39597, 39595, -1, 39600, 32298, 39578, -1, 39600, 39599, 39601, -1, 39600, 39598, 39599, -1, 39600, 39601, 32298, -1, 39600, 39578, 39598, -1, 39593, 32467, 32466, -1, 39596, 32466, 32464, -1, 39596, 39593, 32466, -1, 39602, 32464, 32465, -1, 39599, 39596, 32464, -1, 39599, 32464, 39602, -1, 39603, 32465, 32299, -1, 39603, 39602, 32465, -1, 39601, 32299, 32298, -1, 39601, 39602, 39603, -1, 39601, 39599, 39602, -1, 39601, 39603, 32299, -1, 39604, 32431, 32434, -1, 39604, 32434, 32469, -1, 39605, 39580, 39579, -1, 39605, 39579, 32431, -1, 39605, 32431, 39604, -1, 39589, 32469, 32468, -1, 39589, 39604, 32469, -1, 39591, 39581, 39580, -1, 39591, 39580, 39605, -1, 39591, 39605, 39604, -1, 39591, 39604, 39589, -1, 38839, 38838, 39606, -1, 38874, 39573, 38872, -1, 38940, 39607, 38902, -1, 38840, 39555, 38920, -1, 38940, 39608, 39609, -1, 38940, 39609, 39607, -1, 38940, 38874, 38839, -1, 38940, 38839, 39608, -1, 38940, 39572, 39573, -1, 38940, 39573, 38874, -1, 39541, 39540, 38840, -1, 39539, 38840, 39540, -1, 39542, 39541, 38840, -1, 39538, 38840, 39539, -1, 39543, 39542, 38840, -1, 39537, 38840, 39538, -1, 39610, 38838, 38840, -1, 39610, 38840, 39537, -1, 39611, 38838, 39610, -1, 38902, 39545, 39544, -1, 38902, 39544, 39543, -1, 38902, 38840, 38920, -1, 38902, 39543, 38840, -1, 39546, 39545, 38902, -1, 39612, 38838, 39611, -1, 39547, 39546, 38902, -1, 39606, 38838, 39612, -1, 39548, 39547, 38902, -1, 39549, 39548, 38902, -1, 39550, 39549, 38902, -1, 39607, 39550, 38902, -1, 38839, 39606, 39613, -1, 38839, 39613, 39614, -1, 38839, 39614, 39615, -1, 38839, 39615, 39616, -1, 38839, 39616, 39617, -1, 38839, 39617, 39608, -1, 39618, 39619, 38942, -1, 39620, 38939, 39621, -1, 39622, 39618, 38942, -1, 39623, 38939, 39620, -1, 39624, 38939, 39623, -1, 39625, 38939, 39624, -1, 39531, 38940, 38939, -1, 39531, 38939, 39625, -1, 38936, 39531, 39625, -1, 38937, 38936, 38935, -1, 39572, 39626, 39627, -1, 39572, 39627, 39628, -1, 39572, 39628, 39629, -1, 39572, 39629, 39630, -1, 39572, 39630, 39631, -1, 38938, 38936, 38937, -1, 39632, 38936, 38938, -1, 39633, 39531, 38936, -1, 39571, 39622, 38942, -1, 39571, 39572, 39631, -1, 39571, 39631, 39634, -1, 39571, 39634, 39635, -1, 39571, 39635, 39636, -1, 39637, 38936, 39632, -1, 39571, 39636, 39638, -1, 39571, 39638, 39639, -1, 39571, 39639, 39640, -1, 39571, 39640, 39622, -1, 39641, 39633, 38936, -1, 39572, 38940, 39536, -1, 39572, 39536, 39626, -1, 39642, 38936, 39637, -1, 39642, 39641, 38936, -1, 39643, 39644, 39645, -1, 39646, 39644, 39643, -1, 38943, 39643, 39647, -1, 38943, 39646, 39643, -1, 39619, 39648, 39646, -1, 39619, 39646, 38943, -1, 39536, 38940, 39531, -1, 38942, 39619, 38943, -1, 30626, 31869, 30630, -1, 31863, 31869, 30626, -1, 31869, 39011, 30630, -1, 31869, 38817, 39011, -1, 38803, 38987, 38823, -1, 38803, 38800, 38987, -1, 38800, 38986, 38987, -1, 38800, 38827, 38986, -1, 38827, 38843, 38986, -1, 39568, 38841, 38827, -1, 38827, 38841, 38843, -1, 30615, 31850, 30616, -1, 31943, 31850, 30615, -1, 31908, 31836, 31852, -1, 31836, 38541, 31852, -1, 31836, 38542, 38541, -1, 38542, 39649, 39650, -1, 38542, 39651, 39649, -1, 31837, 39652, 31836, -1, 31836, 39652, 38542, -1, 38542, 39652, 39651, -1, 31820, 31881, 31916, -1, 31825, 31881, 31820, -1, 38541, 31821, 31852, -1, 31852, 31820, 31916, -1, 31821, 31820, 31852, -1, 31824, 31836, 31908, -1, 31825, 31908, 31881, -1, 31825, 31824, 31908, -1, 38890, 38742, 38889, -1, 38889, 38742, 38739, -1, 39653, 39654, 38944, -1, 39654, 39655, 38944, -1, 39655, 39656, 38944, -1, 38944, 32333, 38755, -1, 39656, 32333, 38944, -1, 39656, 32334, 32333, -1, 32333, 38739, 38755, -1, 32333, 38889, 38739, -1, 38742, 39586, 38754, -1, 38890, 39587, 38742, -1, 38742, 39587, 39586, -1, 38890, 38893, 39587, -1, 32311, 32303, 32301, -1, 32311, 32314, 32303, -1, 32303, 32315, 32306, -1, 32314, 32315, 32303, -1, 32315, 32307, 32306, -1, 32315, 32317, 32307, -1, 32317, 32319, 32309, -1, 32317, 32309, 32307, -1, 39575, 39574, 39657, -1, 39658, 39575, 39657, -1, 38749, 38880, 39659, -1, 38748, 38880, 38749, -1, 38880, 39660, 39659, -1, 38880, 38882, 39660, -1, 39660, 38883, 39661, -1, 38882, 38883, 39660, -1, 38883, 39662, 39661, -1, 39662, 38888, 39658, -1, 39658, 38888, 39575, -1, 38883, 38885, 39662, -1, 39662, 38885, 38888, -1, 38749, 39659, 39663, -1, 38749, 39663, 38746, -1, 39659, 39664, 39663, -1, 39659, 39660, 39664, -1, 39664, 39661, 39665, -1, 39660, 39661, 39664, -1, 39661, 39666, 39665, -1, 39661, 39662, 39666, -1, 38799, 38745, 38746, -1, 38799, 38746, 39663, -1, 39664, 38799, 39663, -1, 38793, 38799, 39664, -1, 38794, 39664, 39665, -1, 38794, 38793, 39664, -1, 39666, 38794, 39665, -1, 38798, 39666, 39657, -1, 38798, 39657, 39574, -1, 38797, 38794, 39666, -1, 38797, 39666, 38798, -1, 38839, 38873, 38837, -1, 38874, 38873, 38839, -1, 38837, 38847, 38830, -1, 38873, 38847, 38837, -1, 38862, 38555, 38825, -1, 38862, 38868, 38555, -1, 38835, 38867, 38834, -1, 38870, 38867, 38835, -1, 38871, 38835, 38836, -1, 38871, 38870, 38835, -1, 38863, 38836, 38829, -1, 38863, 38871, 38836, -1, 38831, 39667, 39668, -1, 38833, 38831, 39668, -1, 38863, 38829, 38831, -1, 38864, 38863, 38831, -1, 38864, 38831, 38833, -1, 38866, 38864, 38833, -1, 38856, 38864, 38866, -1, 38865, 38833, 38832, -1, 38865, 38866, 38833, -1, 38853, 38864, 38856, -1, 38867, 38832, 38834, -1, 38867, 38865, 38832, -1, 39669, 39668, 39667, -1, 39670, 39668, 39669, -1, 38801, 39668, 38802, -1, 38802, 39670, 38826, -1, 39668, 39670, 38802, -1, 38801, 38824, 39668, -1, 38824, 38833, 39668, -1, 39667, 38845, 39569, -1, 39669, 39569, 39568, -1, 39669, 39667, 39569, -1, 38828, 38845, 39667, -1, 38831, 38828, 39667, -1, 38826, 39568, 38827, -1, 38826, 39670, 39568, -1, 39670, 39669, 39568, -1, 38861, 38854, 38866, -1, 38854, 38856, 38866, -1, 38846, 38848, 38864, -1, 38853, 38846, 38864, -1, 38728, 38851, 39671, -1, 38728, 38730, 38851, -1, 38720, 38786, 38744, -1, 38720, 38722, 38786, -1, 38722, 38787, 38786, -1, 38722, 38724, 38787, -1, 38724, 38790, 38787, -1, 38724, 38727, 38790, -1, 38727, 38791, 38790, -1, 38727, 38732, 38791, -1, 39672, 38735, 39673, -1, 38732, 39672, 38792, -1, 38732, 38792, 38791, -1, 38732, 38735, 39672, -1, 38735, 39674, 39673, -1, 38735, 38736, 39674, -1, 38736, 38734, 39675, -1, 38736, 39675, 39674, -1, 38850, 39671, 38851, -1, 39675, 39671, 38850, -1, 39673, 39559, 39672, -1, 39558, 39559, 39673, -1, 39674, 39558, 39673, -1, 38941, 39674, 39675, -1, 38941, 39675, 38850, -1, 38941, 39558, 39674, -1, 31698, 39618, 31680, -1, 39619, 39618, 31698, -1, 38932, 32138, 38933, -1, 32127, 32138, 38932, -1, 31813, 31817, 31917, -1, 31813, 31917, 31924, -1, 31935, 38540, 38538, -1, 31927, 38540, 31935, -1, 31817, 31927, 31917, -1, 31817, 31822, 31927, -1, 31822, 38540, 31927, -1, 31935, 31813, 31924, -1, 31819, 31813, 31935, -1, 38538, 31819, 31935, -1, 38942, 39676, 39677, -1, 38784, 39676, 38942, -1, 39678, 39679, 39677, -1, 39678, 39677, 39676, -1, 39678, 39672, 39679, -1, 39678, 38792, 39672, -1, 38778, 38779, 39676, -1, 38779, 39678, 39676, -1, 39676, 38777, 38778, -1, 38779, 38781, 39678, -1, 38781, 38792, 39678, -1, 39676, 38784, 38777, -1, 39561, 39565, 39677, -1, 39679, 39561, 39677, -1, 39571, 39677, 39565, -1, 39559, 39561, 39679, -1, 39672, 39559, 39679, -1, 38942, 39677, 39571, -1, 30697, 30696, 30311, -1, 30311, 30696, 30318, -1, 30716, 30713, 30309, -1, 30716, 30309, 30310, -1, 30717, 30310, 30313, -1, 30717, 30716, 30310, -1, 30720, 30313, 30316, -1, 30720, 30717, 30313, -1, 30722, 30316, 30317, -1, 30722, 30720, 30316, -1, 30742, 30317, 30314, -1, 30742, 30722, 30317, -1, 30636, 30314, 30312, -1, 30636, 30742, 30314, -1, 30632, 30312, 30308, -1, 30632, 30636, 30312, -1, 30633, 30308, 30307, -1, 30633, 30632, 30308, -1, 30706, 30307, 30322, -1, 30706, 30633, 30307, -1, 30704, 30322, 30321, -1, 30704, 30706, 30322, -1, 30702, 30321, 30320, -1, 30702, 30704, 30321, -1, 30699, 30320, 30319, -1, 30699, 30702, 30320, -1, 30696, 30319, 30318, -1, 30696, 30699, 30319, -1, 30309, 30390, 30315, -1, 30713, 30390, 30309, -1, 30295, 30733, 30302, -1, 30734, 30733, 30295, -1, 30293, 30386, 30298, -1, 30628, 30386, 30293, -1, 30627, 30628, 30293, -1, 30627, 30293, 30294, -1, 30629, 30294, 30297, -1, 30629, 30627, 30294, -1, 30625, 30297, 30300, -1, 30625, 30629, 30297, -1, 30622, 30300, 30301, -1, 30622, 30625, 30300, -1, 30621, 30301, 30299, -1, 30621, 30622, 30301, -1, 30619, 30299, 30296, -1, 30619, 30621, 30299, -1, 30618, 30296, 30292, -1, 30618, 30619, 30296, -1, 30745, 30292, 30291, -1, 30745, 30618, 30292, -1, 30746, 30291, 30306, -1, 30746, 30745, 30291, -1, 30747, 30306, 30305, -1, 30747, 30746, 30306, -1, 30736, 30305, 30304, -1, 30736, 30747, 30305, -1, 30735, 30304, 30303, -1, 30735, 30736, 30304, -1, 30733, 30303, 30302, -1, 30733, 30735, 30303, -1, 39680, 39681, 39682, -1, 39680, 39682, 39683, -1, 31960, 39684, 39685, -1, 31960, 31958, 39684, -1, 39686, 39687, 39681, -1, 39686, 39681, 39680, -1, 39688, 39689, 39690, -1, 31961, 31960, 39685, -1, 31952, 39687, 39686, -1, 31952, 39691, 39692, -1, 39693, 39690, 39694, -1, 31952, 39692, 39687, -1, 39693, 39688, 39690, -1, 31963, 31961, 39685, -1, 39695, 39696, 39689, -1, 31963, 39685, 39697, -1, 39695, 39689, 39688, -1, 31951, 39691, 31952, -1, 39698, 39694, 39699, -1, 39698, 39693, 39694, -1, 31951, 39700, 39691, -1, 39701, 31946, 39696, -1, 31965, 39697, 39702, -1, 39701, 39696, 39695, -1, 31965, 31963, 39697, -1, 31950, 39703, 39700, -1, 31950, 39700, 31951, -1, 39704, 39699, 39705, -1, 39704, 39698, 39699, -1, 31966, 39702, 39706, -1, 31966, 31965, 39702, -1, 31968, 39706, 39703, -1, 31968, 31966, 39706, -1, 31968, 39703, 31950, -1, 39707, 31946, 39701, -1, 39708, 39709, 39710, -1, 39708, 39705, 39709, -1, 39708, 39704, 39705, -1, 39711, 31969, 31946, -1, 39711, 31946, 39707, -1, 39712, 39710, 39713, -1, 39712, 39708, 39710, -1, 39714, 31956, 31969, -1, 39714, 31969, 39711, -1, 39715, 39712, 39713, -1, 39716, 31956, 39714, -1, 39716, 31957, 31956, -1, 39683, 39715, 39713, -1, 39683, 39682, 39715, -1, 39717, 31957, 39716, -1, 31958, 39717, 39684, -1, 31958, 31957, 39717, -1, 39692, 30775, 39687, -1, 39687, 39718, 39681, -1, 30775, 39718, 39687, -1, 39681, 39719, 39682, -1, 39718, 39719, 39681, -1, 39682, 39720, 39715, -1, 39719, 39720, 39682, -1, 39715, 39721, 39712, -1, 39720, 39721, 39715, -1, 39712, 39722, 39708, -1, 39721, 39722, 39712, -1, 39708, 39723, 39704, -1, 39722, 39723, 39708, -1, 39704, 39724, 39698, -1, 39723, 39724, 39704, -1, 39698, 39725, 39693, -1, 39724, 39725, 39698, -1, 39693, 39726, 39688, -1, 39725, 39726, 39693, -1, 39688, 39727, 39695, -1, 39726, 39727, 39688, -1, 39695, 39728, 39701, -1, 39727, 39728, 39695, -1, 39701, 39729, 39707, -1, 39728, 39729, 39701, -1, 39729, 30824, 39707, -1, 39707, 30824, 39711, -1, 39711, 30821, 39714, -1, 30824, 30821, 39711, -1, 39714, 30801, 39716, -1, 30821, 30801, 39714, -1, 39716, 30800, 39717, -1, 30801, 30800, 39716, -1, 39717, 30838, 39684, -1, 30800, 30838, 39717, -1, 39684, 30823, 39685, -1, 30838, 30823, 39684, -1, 39685, 30798, 39697, -1, 30823, 30798, 39685, -1, 39697, 30797, 39702, -1, 30798, 30797, 39697, -1, 39702, 30840, 39706, -1, 30797, 30840, 39702, -1, 39706, 30830, 39703, -1, 30840, 30830, 39706, -1, 39703, 30812, 39700, -1, 30830, 30812, 39703, -1, 39700, 30795, 39691, -1, 30812, 30795, 39700, -1, 39691, 30776, 39692, -1, 30795, 30776, 39691, -1, 30776, 30775, 39692, -1, 39730, 39731, 38686, -1, 39730, 38686, 38658, -1, 39732, 39733, 39734, -1, 39735, 38657, 38703, -1, 39735, 38658, 38657, -1, 39736, 39734, 39737, -1, 39736, 39732, 39734, -1, 39735, 39730, 38658, -1, 38692, 39735, 38703, -1, 39738, 39739, 39733, -1, 39738, 39733, 39732, -1, 39740, 39737, 39741, -1, 39740, 39736, 39737, -1, 39742, 39743, 39744, -1, 39742, 39745, 39743, -1, 39742, 38639, 39745, -1, 39746, 39747, 39739, -1, 39742, 39744, 39748, -1, 39749, 38640, 38639, -1, 39746, 39739, 39738, -1, 39749, 38660, 38640, -1, 39749, 38673, 38660, -1, 39749, 38639, 39742, -1, 39749, 39735, 38692, -1, 39750, 39741, 39748, -1, 39749, 38692, 38673, -1, 39750, 39740, 39741, -1, 38682, 39751, 39747, -1, 38682, 39747, 39746, -1, 39752, 39750, 39748, -1, 38681, 39753, 39751, -1, 38681, 39751, 38682, -1, 39754, 39752, 39748, -1, 38654, 39753, 38681, -1, 39755, 39753, 38654, -1, 39756, 39754, 39748, -1, 38653, 39755, 38654, -1, 39744, 39756, 39748, -1, 39757, 39755, 38653, -1, 38701, 39757, 38653, -1, 39731, 38701, 38686, -1, 39731, 39757, 38701, -1, 38547, 39758, 39759, -1, 38547, 39760, 39758, -1, 39761, 38547, 39759, -1, 38577, 39762, 38578, -1, 38577, 39763, 39762, -1, 39764, 38547, 39761, -1, 39765, 38568, 38596, -1, 39766, 38596, 38592, -1, 39766, 39765, 38596, -1, 39767, 38569, 38568, -1, 39767, 38568, 39765, -1, 39768, 38592, 38591, -1, 39768, 39766, 38592, -1, 38599, 39769, 39770, -1, 38599, 39770, 39763, -1, 38599, 39763, 38577, -1, 39771, 38569, 39767, -1, 38561, 39769, 38599, -1, 38561, 39772, 39769, -1, 39773, 38591, 38588, -1, 39773, 39768, 38591, -1, 38560, 39774, 39772, -1, 39775, 38570, 38569, -1, 39775, 38569, 39771, -1, 38560, 39772, 38561, -1, 38557, 39776, 39774, -1, 38557, 39774, 38560, -1, 38553, 39764, 39777, -1, 38553, 39777, 39778, -1, 39779, 38584, 38583, -1, 39779, 38588, 38584, -1, 38553, 38547, 39764, -1, 39779, 39773, 38588, -1, 38556, 39778, 39776, -1, 39780, 39781, 38570, -1, 38556, 39776, 38557, -1, 38556, 38553, 39778, -1, 39780, 38570, 39775, -1, 39782, 38583, 38579, -1, 39782, 39779, 38583, -1, 39783, 39784, 39781, -1, 39783, 39781, 39780, -1, 39785, 39782, 38579, -1, 39786, 39760, 39784, -1, 39786, 39784, 39783, -1, 38578, 39762, 39785, -1, 38578, 39785, 38579, -1, 39758, 39760, 39786, -1, 39769, 39054, 39770, -1, 39770, 39787, 39763, -1, 39054, 39787, 39770, -1, 39763, 39788, 39762, -1, 39787, 39788, 39763, -1, 39762, 39789, 39785, -1, 39788, 39789, 39762, -1, 39785, 39790, 39782, -1, 39789, 39790, 39785, -1, 39782, 39791, 39779, -1, 39790, 39791, 39782, -1, 39779, 39792, 39773, -1, 39791, 39792, 39779, -1, 39773, 39793, 39768, -1, 39792, 39793, 39773, -1, 39768, 39794, 39766, -1, 39793, 39794, 39768, -1, 39766, 39795, 39765, -1, 39794, 39795, 39766, -1, 39765, 39796, 39767, -1, 39795, 39796, 39765, -1, 39767, 39797, 39771, -1, 39796, 39797, 39767, -1, 39797, 39798, 39771, -1, 39771, 39101, 39775, -1, 39798, 39101, 39771, -1, 38547, 38546, 39760, -1, 38548, 39784, 39760, -1, 38548, 39760, 38546, -1, 39799, 38573, 38570, -1, 39799, 38570, 39781, -1, 39799, 39781, 39784, -1, 39799, 38548, 38545, -1, 39799, 38545, 38810, -1, 39799, 38810, 38819, -1, 39799, 38819, 38573, -1, 39799, 39784, 38548, -1, 39800, 39801, 39802, -1, 39800, 39802, 31941, -1, 39803, 39689, 39696, -1, 39803, 39696, 31946, -1, 39803, 39804, 39689, -1, 39805, 31946, 31919, -1, 39805, 31919, 31918, -1, 39805, 31918, 31921, -1, 39805, 39803, 31946, -1, 39805, 31921, 39804, -1, 39805, 39804, 39803, -1, 39806, 39680, 39683, -1, 39806, 39683, 39713, -1, 39806, 31851, 31853, -1, 39806, 31853, 31941, -1, 39806, 39802, 39680, -1, 39806, 31941, 39802, -1, 39807, 39713, 39710, -1, 39807, 39710, 39709, -1, 39807, 31867, 31858, -1, 39807, 31858, 31851, -1, 39807, 39806, 39713, -1, 39807, 31851, 39806, -1, 39808, 39709, 39705, -1, 39808, 31931, 31867, -1, 39808, 31867, 39807, -1, 39808, 39807, 39709, -1, 39809, 39705, 39699, -1, 39809, 39699, 39694, -1, 39809, 31929, 31930, -1, 39809, 31930, 31931, -1, 39809, 39808, 39705, -1, 39809, 31931, 39808, -1, 39810, 39694, 39690, -1, 39810, 39690, 39689, -1, 39810, 31921, 31928, -1, 39810, 31928, 31929, -1, 39810, 31929, 39809, -1, 39810, 39809, 39694, -1, 39804, 39810, 39689, -1, 39804, 31921, 39810, -1, 39801, 31932, 31952, -1, 39801, 31952, 39686, -1, 39801, 39686, 39680, -1, 39801, 39680, 39802, -1, 39800, 31941, 31937, -1, 39800, 31937, 31932, -1, 39800, 31932, 39801, -1, 33054, 39811, 33060, -1, 33054, 33053, 39811, -1, 39811, 33059, 39812, -1, 33053, 33059, 39811, -1, 39812, 33030, 39813, -1, 33059, 33030, 39812, -1, 39813, 33041, 39814, -1, 33030, 33041, 39813, -1, 39814, 33040, 39815, -1, 33041, 33040, 39814, -1, 39815, 33046, 39816, -1, 33040, 33046, 39815, -1, 39816, 32738, 32636, -1, 33046, 32738, 39816, -1, 39775, 39101, 39780, -1, 39780, 39098, 39783, -1, 39101, 39098, 39780, -1, 39783, 39076, 39786, -1, 39098, 39076, 39783, -1, 39786, 39070, 39758, -1, 39076, 39070, 39786, -1, 39758, 39117, 39759, -1, 39070, 39117, 39758, -1, 39759, 39100, 39761, -1, 39117, 39100, 39759, -1, 39761, 39073, 39764, -1, 39100, 39073, 39761, -1, 39764, 39072, 39777, -1, 39073, 39072, 39764, -1, 39777, 39118, 39778, -1, 39072, 39118, 39777, -1, 39778, 39107, 39776, -1, 39118, 39107, 39778, -1, 39776, 39087, 39774, -1, 39107, 39087, 39776, -1, 39774, 39075, 39772, -1, 39087, 39075, 39774, -1, 39772, 39055, 39769, -1, 39075, 39055, 39772, -1, 39055, 39054, 39769, -1, 39531, 39633, 38918, -1, 39531, 38918, 38901, -1, 38938, 38905, 38904, -1, 39632, 38904, 38903, -1, 39632, 38938, 38904, -1, 39637, 39632, 38903, -1, 39642, 38910, 38911, -1, 39642, 38903, 38910, -1, 39642, 39637, 38903, -1, 39641, 38911, 38918, -1, 39641, 39642, 38911, -1, 39633, 39641, 38918, -1, 38936, 39625, 38895, -1, 38936, 38895, 38919, -1, 39550, 39607, 39522, -1, 39522, 39607, 39535, -1, 39535, 39609, 39534, -1, 39607, 39609, 39535, -1, 39534, 39608, 39533, -1, 39609, 39608, 39534, -1, 39533, 39617, 39532, -1, 39608, 39617, 39533, -1, 39532, 39616, 39530, -1, 39617, 39616, 39532, -1, 39530, 39615, 39529, -1, 39616, 39615, 39530, -1, 39529, 39614, 39528, -1, 39615, 39614, 39529, -1, 39528, 39613, 39527, -1, 39614, 39613, 39528, -1, 39527, 39606, 39526, -1, 39613, 39606, 39527, -1, 39526, 39612, 39525, -1, 39606, 39612, 39526, -1, 39525, 39611, 39524, -1, 39612, 39611, 39525, -1, 39524, 39610, 39523, -1, 39611, 39610, 39524, -1, 39523, 39537, 39515, -1, 39610, 39537, 39523, -1, 39817, 39818, 39819, -1, 39820, 39817, 39819, -1, 39821, 39819, 39822, -1, 39821, 39820, 39819, -1, 39823, 39824, 39825, -1, 39826, 39827, 39823, -1, 39828, 39829, 39826, -1, 39828, 39830, 39829, -1, 39828, 39831, 39830, -1, 39828, 39825, 39821, -1, 39828, 39821, 39822, -1, 39828, 39823, 39825, -1, 39828, 39826, 39823, -1, 39832, 39833, 39834, -1, 39835, 39833, 39832, -1, 39836, 39833, 39835, -1, 39837, 39836, 39838, -1, 35094, 39839, 39840, -1, 35094, 39837, 39839, -1, 35094, 39833, 39836, -1, 35094, 39836, 39837, -1, 35096, 35094, 35095, -1, 35097, 39833, 35094, -1, 35097, 35094, 35096, -1, 39841, 39822, 39833, -1, 39841, 39828, 39822, -1, 39842, 39841, 39833, -1, 39842, 39833, 35097, -1, 39843, 39844, 39841, -1, 39843, 39841, 39842, -1, 30149, 39378, 39845, -1, 3202, 39378, 30149, -1, 39845, 39378, 39846, -1, 39846, 39378, 39847, -1, 3202, 31304, 39378, -1, 3202, 3227, 31304, -1, 3227, 31302, 31304, -1, 30157, 39848, 39849, -1, 39849, 39848, 39850, -1, 39850, 39848, 39851, -1, 3200, 39852, 30157, -1, 30157, 39852, 39848, -1, 3200, 39853, 39852, -1, 3200, 39854, 39853, -1, 3200, 39855, 39854, -1, 3200, 39856, 39855, -1, 39856, 3237, 39231, -1, 3200, 3237, 39856, -1, 3237, 39225, 39231, -1, 39852, 39857, 39848, -1, 39852, 39858, 39857, -1, 3230, 39218, 39215, -1, 3201, 39218, 3230, -1, 3201, 39859, 39218, -1, 3201, 39860, 39859, -1, 3201, 39861, 39860, -1, 3201, 39862, 39861, -1, 3201, 30152, 39862, -1, 30152, 39863, 39862, -1, 39863, 39864, 39865, -1, 30152, 39866, 39863, -1, 39863, 39866, 39864, -1, 39867, 39862, 39863, -1, 39868, 39862, 39867, -1, 34934, 34940, 39869, -1, 39870, 34940, 39871, -1, 39869, 34940, 39870, -1, 39871, 34945, 39872, -1, 34940, 34945, 39871, -1, 39872, 34955, 39873, -1, 34945, 34955, 39872, -1, 39873, 34958, 39874, -1, 34955, 34958, 39873, -1, 39874, 34975, 39875, -1, 34958, 34975, 39874, -1, 39875, 34981, 39876, -1, 34975, 34981, 39875, -1, 34981, 34635, 39876, -1, 39877, 39878, 39879, -1, 39880, 39879, 39881, -1, 39880, 39882, 39877, -1, 39880, 39877, 39879, -1, 39883, 39882, 39880, -1, 39873, 39874, 39875, -1, 39872, 39873, 39875, -1, 39870, 39871, 39872, -1, 39870, 39872, 39875, -1, 39869, 39875, 39876, -1, 39869, 39876, 39883, -1, 39869, 39870, 39875, -1, 39869, 39883, 39880, -1, 39884, 39885, 39886, -1, 39887, 39884, 39888, -1, 39889, 39890, 39885, -1, 39889, 39891, 39890, -1, 39889, 39885, 39884, -1, 39889, 39884, 39887, -1, 39892, 39891, 39889, -1, 39893, 39880, 39891, -1, 39893, 39869, 39880, -1, 39893, 39891, 39892, -1, 39894, 39893, 39892, -1, 39895, 39892, 39896, -1, 39897, 39894, 39892, -1, 39898, 39892, 39895, -1, 39898, 39897, 39892, -1, 39899, 39897, 39898, -1, 39869, 34742, 34934, -1, 39869, 39893, 34742, -1, 34636, 39876, 34635, -1, 39883, 39876, 34636, -1, 39892, 34592, 39896, -1, 39896, 34739, 39895, -1, 34592, 34739, 39896, -1, 39895, 34729, 39898, -1, 34739, 34729, 39895, -1, 39898, 34722, 39899, -1, 34729, 34722, 39898, -1, 39899, 34720, 39897, -1, 34722, 34720, 39899, -1, 39897, 34724, 39894, -1, 34720, 34724, 39897, -1, 39894, 34735, 39893, -1, 34724, 34735, 39894, -1, 34735, 34742, 39893, -1, 39882, 35030, 39877, -1, 39883, 35030, 39882, -1, 34636, 35030, 39883, -1, 39877, 35027, 39878, -1, 35030, 35027, 39877, -1, 39878, 35024, 39879, -1, 35027, 35024, 39878, -1, 39879, 35019, 39881, -1, 35024, 35019, 39879, -1, 39881, 35017, 39880, -1, 35019, 35017, 39881, -1, 35017, 35014, 39880, -1, 39892, 39889, 34592, -1, 34592, 39889, 34591, -1, 39891, 35014, 34821, -1, 39891, 39880, 35014, -1, 34821, 34815, 39891, -1, 39890, 34815, 39885, -1, 39891, 34815, 39890, -1, 39885, 34807, 39886, -1, 34815, 34807, 39885, -1, 39886, 34800, 39884, -1, 34807, 34800, 39886, -1, 39884, 34802, 39888, -1, 34800, 34802, 39884, -1, 39888, 34809, 39887, -1, 34802, 34809, 39888, -1, 39887, 34818, 39889, -1, 34809, 34818, 39887, -1, 34818, 34591, 39889, -1, 34888, 34890, 39900, -1, 39900, 34890, 39901, -1, 39901, 34884, 39902, -1, 34890, 34884, 39901, -1, 39902, 34873, 39903, -1, 34884, 34873, 39902, -1, 39903, 34866, 39904, -1, 34873, 34866, 39903, -1, 39904, 34868, 39905, -1, 34866, 34868, 39904, -1, 39905, 34876, 39906, -1, 34868, 34876, 39905, -1, 39906, 34586, 39907, -1, 34876, 34586, 39906, -1, 39908, 39909, 39910, -1, 39911, 39908, 39910, -1, 39912, 39908, 39911, -1, 39913, 39911, 39914, -1, 39913, 39912, 39911, -1, 39915, 39916, 39917, -1, 39918, 39919, 39915, -1, 39920, 39918, 39915, -1, 39920, 39915, 39917, -1, 39921, 39922, 39913, -1, 39921, 39917, 39922, -1, 39921, 39913, 39914, -1, 39921, 39920, 39917, -1, 39907, 39905, 39906, -1, 39907, 39904, 39905, -1, 39907, 39903, 39904, -1, 39907, 39902, 39903, -1, 39907, 39901, 39902, -1, 39907, 39900, 39901, -1, 39923, 39900, 39907, -1, 39924, 39914, 39900, -1, 39924, 39921, 39914, -1, 39924, 39900, 39923, -1, 39925, 39924, 39923, -1, 39926, 39923, 39927, -1, 39928, 39925, 39923, -1, 39928, 39923, 39926, -1, 39929, 39928, 39926, -1, 39900, 39914, 34888, -1, 34888, 39914, 35081, -1, 34587, 39907, 34586, -1, 39923, 39907, 34587, -1, 39913, 34363, 39912, -1, 39912, 34359, 39908, -1, 34363, 34359, 39912, -1, 39908, 34356, 39909, -1, 34359, 34356, 39908, -1, 39909, 34353, 39910, -1, 34356, 34353, 39909, -1, 39910, 35092, 39911, -1, 34353, 35092, 39910, -1, 39911, 35088, 39914, -1, 35092, 35088, 39911, -1, 35088, 35081, 39914, -1, 39923, 34587, 39927, -1, 34587, 34817, 39927, -1, 39927, 34808, 39926, -1, 34817, 34808, 39927, -1, 39926, 34801, 39929, -1, 34808, 34801, 39926, -1, 39929, 34804, 39928, -1, 34801, 34804, 39929, -1, 39928, 34813, 39925, -1, 34804, 34813, 39928, -1, 39925, 34819, 39924, -1, 34813, 34819, 39925, -1, 39913, 34637, 34363, -1, 39913, 39922, 34637, -1, 35011, 39924, 34819, -1, 39921, 39924, 35011, -1, 35011, 35018, 39921, -1, 39921, 35018, 39920, -1, 39920, 35020, 39918, -1, 35018, 35020, 39920, -1, 39919, 35023, 39915, -1, 39918, 35023, 39919, -1, 35020, 35023, 39918, -1, 39915, 35028, 39916, -1, 35023, 35028, 39915, -1, 39916, 35031, 39917, -1, 35028, 35031, 39916, -1, 39917, 35032, 39922, -1, 35031, 35032, 39917, -1, 35032, 34637, 39922, -1, 35082, 35085, 39930, -1, 39930, 35085, 39931, -1, 39931, 35089, 39932, -1, 35085, 35089, 39931, -1, 39933, 35093, 39934, -1, 39932, 35093, 39933, -1, 35089, 35093, 39932, -1, 39934, 34355, 39935, -1, 35093, 34355, 39934, -1, 39935, 34354, 39936, -1, 34355, 34354, 39935, -1, 39936, 34357, 39937, -1, 34354, 34357, 39936, -1, 34357, 34364, 39937, -1, 39938, 39939, 39940, -1, 39940, 39941, 39942, -1, 39939, 39941, 39940, -1, 39941, 39943, 39942, -1, 39941, 39944, 39943, -1, 39944, 39945, 39943, -1, 39944, 39946, 39945, -1, 39947, 39948, 39946, -1, 39948, 39949, 39946, -1, 39949, 39950, 39946, -1, 39950, 39951, 39946, -1, 39946, 39952, 39945, -1, 39951, 39952, 39946, -1, 39952, 39953, 39945, -1, 39954, 39955, 39956, -1, 39957, 39958, 39954, -1, 39954, 39958, 39955, -1, 39953, 39959, 39957, -1, 39957, 39959, 39958, -1, 39952, 39930, 39953, -1, 39953, 39930, 39959, -1, 39930, 39937, 39959, -1, 39930, 39936, 39937, -1, 39932, 39933, 39931, -1, 39931, 39933, 39930, -1, 39930, 39933, 39936, -1, 39936, 39934, 39935, -1, 39933, 39934, 39936, -1, 35082, 39952, 34889, -1, 39930, 39952, 35082, -1, 34496, 39937, 34364, -1, 39959, 39937, 34496, -1, 39946, 34585, 39947, -1, 34585, 34887, 39947, -1, 39947, 34875, 39948, -1, 34887, 34875, 39947, -1, 39948, 34867, 39949, -1, 34875, 34867, 39948, -1, 39949, 34874, 39950, -1, 34867, 34874, 39949, -1, 39950, 34885, 39951, -1, 34874, 34885, 39950, -1, 39951, 34889, 39952, -1, 34885, 34889, 39951, -1, 39959, 34496, 39958, -1, 39958, 34488, 39955, -1, 34496, 34488, 39958, -1, 39955, 34474, 39956, -1, 34488, 34474, 39955, -1, 39956, 34463, 39954, -1, 34474, 34463, 39956, -1, 39954, 34458, 39957, -1, 34463, 34458, 39954, -1, 34458, 34452, 39957, -1, 39957, 34444, 39953, -1, 34452, 34444, 39957, -1, 34585, 39944, 34584, -1, 39946, 39944, 34585, -1, 39945, 39953, 34444, -1, 39945, 34444, 34694, -1, 34694, 34978, 39945, -1, 39943, 34978, 39942, -1, 39945, 34978, 39943, -1, 39942, 34974, 39940, -1, 34978, 34974, 39942, -1, 39940, 34965, 39938, -1, 34974, 34965, 39940, -1, 34965, 34962, 39938, -1, 39938, 34964, 39939, -1, 34962, 34964, 39938, -1, 39939, 34972, 39941, -1, 34964, 34972, 39939, -1, 39941, 34584, 39944, -1, 34972, 34584, 39941, -1, 34696, 35067, 39960, -1, 39961, 35067, 39962, -1, 39960, 35067, 39961, -1, 39962, 35058, 39963, -1, 35067, 35058, 39962, -1, 35058, 35051, 39963, -1, 39963, 35043, 39964, -1, 35051, 35043, 39963, -1, 39964, 35045, 39965, -1, 35043, 35045, 39964, -1, 39965, 35056, 39966, -1, 35045, 35056, 39965, -1, 39966, 35064, 39967, -1, 35056, 35064, 39966, -1, 39967, 34582, 39968, -1, 35064, 34582, 39967, -1, 39965, 39966, 39964, -1, 39964, 39966, 39963, -1, 39963, 39961, 39962, -1, 39967, 39968, 39966, -1, 39966, 39968, 39963, -1, 39963, 39968, 39961, -1, 39968, 39960, 39961, -1, 39968, 39969, 39960, -1, 39970, 39971, 39969, -1, 39971, 39972, 39969, -1, 39972, 39973, 39969, -1, 39973, 39974, 39969, -1, 39969, 39975, 39960, -1, 39974, 39975, 39969, -1, 39975, 39976, 39960, -1, 39976, 39977, 39978, -1, 39976, 39979, 39977, -1, 39976, 39980, 39979, -1, 39976, 39981, 39980, -1, 39976, 39982, 39981, -1, 39975, 39983, 39976, -1, 39976, 39983, 39982, -1, 39983, 39984, 39982, -1, 39983, 39985, 39984, -1, 39985, 39986, 39984, -1, 39986, 39987, 39988, -1, 39989, 39987, 39985, -1, 39985, 39987, 39986, -1, 39987, 39990, 39988, -1, 39960, 39976, 34588, -1, 39960, 34588, 34696, -1, 39969, 39968, 34582, -1, 39969, 34582, 34583, -1, 39982, 34639, 39981, -1, 39981, 34684, 39980, -1, 34639, 34684, 39981, -1, 39980, 34641, 39979, -1, 34684, 34641, 39980, -1, 39979, 34629, 39977, -1, 34641, 34629, 39979, -1, 39977, 34617, 39978, -1, 34629, 34617, 39977, -1, 39978, 34596, 39976, -1, 34617, 34596, 39978, -1, 34596, 34588, 39976, -1, 39969, 34583, 39970, -1, 39970, 34977, 39971, -1, 34583, 34977, 39970, -1, 39971, 34971, 39972, -1, 34977, 34971, 39971, -1, 39972, 34963, 39973, -1, 34971, 34963, 39972, -1, 39973, 34966, 39974, -1, 34963, 34966, 39973, -1, 34966, 34973, 39974, -1, 39974, 34698, 39975, -1, 34973, 34698, 39974, -1, 39982, 39984, 34495, -1, 39982, 34495, 34639, -1, 39983, 39975, 34698, -1, 39983, 34698, 34446, -1, 34446, 34445, 39983, -1, 39983, 34445, 39985, -1, 39985, 34453, 39989, -1, 34445, 34453, 39985, -1, 39989, 34459, 39987, -1, 34453, 34459, 39989, -1, 39990, 34462, 39988, -1, 39987, 34462, 39990, -1, 34459, 34462, 39987, -1, 39988, 34469, 39986, -1, 34462, 34469, 39988, -1, 39986, 34482, 39984, -1, 34469, 34482, 39986, -1, 34482, 34495, 39984, -1, 39991, 34402, 39992, -1, 34402, 34404, 39992, -1, 39992, 34406, 39993, -1, 34404, 34406, 39992, -1, 39993, 34396, 39994, -1, 34406, 34396, 39993, -1, 39994, 34384, 39995, -1, 34396, 34384, 39994, -1, 39995, 34386, 39996, -1, 34384, 34386, 39995, -1, 39996, 34390, 39997, -1, 34386, 34390, 39996, -1, 39997, 34401, 39998, -1, 34390, 34401, 39997, -1, 39998, 34411, 39999, -1, 34401, 34411, 39998, -1, 39996, 39994, 39995, -1, 39998, 39999, 39997, -1, 39997, 39999, 39996, -1, 39994, 39991, 39993, -1, 39993, 39991, 39992, -1, 39996, 39991, 39994, -1, 39999, 39991, 39996, -1, 39999, 40000, 39991, -1, 40001, 40002, 40003, -1, 40003, 40002, 40004, -1, 40004, 40002, 40005, -1, 40005, 40002, 40006, -1, 40006, 40002, 40000, -1, 40000, 40002, 39991, -1, 40002, 40007, 39991, -1, 40008, 40009, 40010, -1, 40009, 40011, 40012, -1, 40008, 40011, 40009, -1, 40007, 40013, 40008, -1, 40008, 40013, 40011, -1, 40002, 40014, 40007, -1, 40007, 40014, 40013, -1, 40014, 40015, 40013, -1, 40014, 40016, 40015, -1, 40017, 40018, 40014, -1, 40014, 40019, 40016, -1, 40018, 40020, 40014, -1, 40014, 40021, 40019, -1, 40020, 40022, 40014, -1, 40014, 40022, 40021, -1, 34402, 40007, 34697, -1, 39991, 40007, 34402, -1, 40000, 39999, 34411, -1, 40000, 34411, 34581, -1, 34643, 34790, 40013, -1, 40013, 34790, 40011, -1, 40011, 34788, 40012, -1, 34790, 34788, 40011, -1, 40012, 34785, 40009, -1, 34788, 34785, 40012, -1, 40010, 34781, 40008, -1, 40009, 34781, 40010, -1, 34785, 34781, 40009, -1, 40008, 34777, 40007, -1, 34781, 34777, 40008, -1, 34777, 34697, 40007, -1, 40000, 35059, 40006, -1, 34581, 35059, 40000, -1, 40006, 35052, 40005, -1, 35059, 35052, 40006, -1, 40005, 35044, 40004, -1, 35052, 35044, 40005, -1, 40004, 35047, 40003, -1, 35044, 35047, 40004, -1, 40003, 35057, 40001, -1, 35047, 35057, 40003, -1, 40001, 34695, 40002, -1, 35057, 34695, 40001, -1, 40013, 40015, 34640, -1, 40013, 34640, 34643, -1, 34590, 40002, 34695, -1, 40014, 40002, 34590, -1, 40014, 34590, 40017, -1, 34590, 34589, 40017, -1, 40018, 34597, 40020, -1, 40017, 34597, 40018, -1, 34589, 34597, 40017, -1, 40020, 34618, 40022, -1, 34597, 34618, 40020, -1, 40022, 34630, 40021, -1, 34618, 34630, 40022, -1, 40021, 34642, 40019, -1, 34630, 34642, 40021, -1, 40019, 34673, 40016, -1, 34642, 34673, 40019, -1, 40016, 34699, 40015, -1, 34673, 34699, 40016, -1, 34699, 34640, 40015, -1, 40023, 34686, 40024, -1, 34686, 34759, 40024, -1, 40024, 34764, 40025, -1, 34759, 34764, 40024, -1, 40025, 34778, 40026, -1, 34764, 34778, 40025, -1, 40026, 34780, 40027, -1, 34778, 34780, 40026, -1, 40027, 34783, 40028, -1, 34780, 34783, 40027, -1, 40028, 34787, 40029, -1, 34783, 34787, 40028, -1, 40029, 34789, 40030, -1, 34787, 34789, 40029, -1, 40030, 34644, 40031, -1, 34789, 34644, 40030, -1, 40032, 40033, 40034, -1, 40035, 40036, 40037, -1, 40037, 40036, 40032, -1, 40033, 40036, 40038, -1, 40032, 40036, 40033, -1, 40036, 40039, 40038, -1, 40036, 40040, 40039, -1, 40036, 40041, 40040, -1, 40042, 40043, 40041, -1, 40044, 40045, 40043, -1, 40043, 40045, 40041, -1, 40045, 40046, 40041, -1, 40041, 40047, 40040, -1, 40046, 40047, 40041, -1, 40047, 40048, 40040, -1, 40049, 40050, 40051, -1, 40048, 40052, 40053, -1, 40053, 40052, 40049, -1, 40050, 40052, 40054, -1, 40049, 40052, 40050, -1, 40047, 40023, 40048, -1, 40048, 40023, 40052, -1, 40023, 40031, 40052, -1, 40024, 40025, 40023, -1, 40025, 40026, 40023, -1, 40031, 40029, 40030, -1, 40023, 40027, 40031, -1, 40031, 40027, 40029, -1, 40026, 40027, 40023, -1, 40027, 40028, 40029, -1, 34686, 40047, 34403, -1, 40023, 40047, 34686, -1, 40052, 40031, 34644, -1, 40052, 34644, 34645, -1, 40041, 34419, 40042, -1, 34419, 34410, 40042, -1, 40042, 34400, 40043, -1, 34410, 34400, 40042, -1, 40043, 34389, 40044, -1, 34400, 34389, 40043, -1, 40045, 34385, 40046, -1, 40044, 34385, 40045, -1, 34389, 34385, 40044, -1, 40046, 34394, 40047, -1, 34385, 34394, 40046, -1, 34394, 34403, 40047, -1, 40052, 34918, 40054, -1, 34645, 34918, 40052, -1, 40054, 34909, 40050, -1, 34918, 34909, 40054, -1, 40050, 34895, 40051, -1, 34909, 34895, 40050, -1, 40051, 34881, 40049, -1, 34895, 34881, 40051, -1, 40049, 34869, 40053, -1, 34881, 34869, 40049, -1, 40053, 34688, 40048, -1, 34869, 34688, 40053, -1, 40041, 40036, 34566, -1, 40041, 34566, 34419, -1, 34554, 40048, 34688, -1, 40040, 40048, 34554, -1, 34554, 34555, 40040, -1, 40039, 34555, 40038, -1, 40040, 34555, 40039, -1, 40038, 34556, 40033, -1, 34555, 34556, 40038, -1, 40033, 34544, 40034, -1, 34556, 34544, 40033, -1, 34544, 34532, 40034, -1, 40034, 34534, 40032, -1, 34532, 34534, 40034, -1, 40032, 34539, 40037, -1, 34534, 34539, 40032, -1, 40037, 34549, 40035, -1, 34539, 34549, 40037, -1, 40035, 34566, 40036, -1, 34549, 34566, 40035, -1, 34677, 34737, 40055, -1, 40056, 34737, 40057, -1, 40055, 34737, 40056, -1, 34737, 34738, 40057, -1, 40057, 34731, 40058, -1, 34738, 34731, 40057, -1, 40058, 34725, 40059, -1, 34731, 34725, 40058, -1, 40059, 34727, 40060, -1, 34725, 34727, 40059, -1, 40060, 34734, 40061, -1, 34727, 34734, 40060, -1, 40061, 34741, 40062, -1, 34734, 34741, 40061, -1, 40062, 34769, 40063, -1, 34741, 34769, 40062, -1, 40060, 40061, 40059, -1, 40061, 40062, 40059, -1, 40059, 40056, 40058, -1, 40058, 40056, 40057, -1, 40062, 40056, 40059, -1, 40063, 40055, 40062, -1, 40062, 40055, 40056, -1, 40063, 40064, 40055, -1, 40065, 40066, 40067, -1, 40067, 40068, 40069, -1, 40069, 40068, 40064, -1, 40066, 40068, 40067, -1, 40064, 40070, 40055, -1, 40068, 40070, 40064, -1, 40070, 40071, 40055, -1, 40071, 40072, 40073, -1, 40071, 40074, 40072, -1, 40071, 40075, 40074, -1, 40071, 40076, 40075, -1, 40070, 40077, 40071, -1, 40071, 40077, 40076, -1, 40078, 40079, 40077, -1, 40077, 40079, 40076, -1, 40078, 40080, 40079, -1, 40080, 40081, 40079, -1, 40079, 40082, 40083, -1, 40081, 40084, 40079, -1, 40079, 40085, 40082, -1, 40084, 40085, 40079, -1, 40055, 40071, 34690, -1, 40055, 34690, 34677, -1, 40064, 40063, 34769, -1, 40064, 34769, 34570, -1, 40076, 34648, 40075, -1, 40075, 35026, 40074, -1, 34648, 35026, 40075, -1, 40074, 35022, 40072, -1, 35026, 35022, 40074, -1, 40072, 35016, 40073, -1, 35022, 35016, 40072, -1, 35016, 35012, 40073, -1, 40073, 34690, 40071, -1, 35012, 34690, 40073, -1, 40064, 34564, 40069, -1, 34570, 34564, 40064, -1, 40069, 34548, 40067, -1, 34564, 34548, 40069, -1, 40067, 34537, 40065, -1, 34548, 34537, 40067, -1, 40065, 34533, 40066, -1, 34537, 34533, 40065, -1, 40066, 34543, 40068, -1, 34533, 34543, 40066, -1, 40068, 34553, 40070, -1, 34543, 34553, 40068, -1, 40076, 40079, 34646, -1, 40076, 34646, 34648, -1, 40077, 40070, 34553, -1, 40077, 34553, 34689, -1, 34689, 34855, 40077, -1, 40078, 34855, 40080, -1, 40077, 34855, 40078, -1, 40080, 34857, 40081, -1, 34855, 34857, 40080, -1, 40081, 34870, 40084, -1, 34857, 34870, 40081, -1, 40084, 34879, 40085, -1, 34870, 34879, 40084, -1, 40085, 34891, 40082, -1, 34879, 34891, 40085, -1, 40082, 34907, 40083, -1, 34891, 34907, 40082, -1, 40083, 34915, 40079, -1, 34907, 34915, 40083, -1, 34915, 34646, 40079, -1, 40086, 34560, 40087, -1, 40087, 34350, 40088, -1, 34560, 34350, 40087, -1, 40088, 35090, 40089, -1, 34350, 35090, 40088, -1, 35090, 35086, 40089, -1, 40089, 35083, 40090, -1, 35086, 35083, 40089, -1, 40090, 34681, 40091, -1, 35083, 34681, 40090, -1, 40092, 40093, 40094, -1, 40094, 40093, 40095, -1, 40095, 40096, 40097, -1, 40097, 40096, 40098, -1, 40098, 40096, 40099, -1, 40099, 40096, 40100, -1, 40093, 40096, 40095, -1, 40093, 40101, 40096, -1, 40102, 40103, 40101, -1, 40104, 40105, 40103, -1, 40103, 40105, 40101, -1, 40101, 40106, 40096, -1, 40105, 40106, 40101, -1, 40106, 40091, 40096, -1, 40091, 40089, 40090, -1, 40091, 40088, 40089, -1, 40091, 40087, 40088, -1, 40091, 40086, 40087, -1, 40106, 40107, 40091, -1, 40091, 40107, 40086, -1, 40108, 40109, 40107, -1, 40107, 40109, 40086, -1, 40108, 40110, 40109, -1, 40110, 40111, 40109, -1, 40109, 40112, 40113, -1, 40109, 40114, 40112, -1, 40111, 40114, 40109, -1, 40114, 40115, 40112, -1, 34560, 40109, 34559, -1, 40086, 40109, 34560, -1, 40096, 40091, 34681, -1, 40096, 34681, 34680, -1, 34675, 35009, 40107, -1, 40108, 35009, 40110, -1, 40107, 35009, 40108, -1, 40110, 35010, 40111, -1, 35009, 35010, 40110, -1, 40111, 35013, 40114, -1, 35010, 35013, 40111, -1, 40114, 35015, 40115, -1, 35013, 35015, 40114, -1, 40115, 35021, 40112, -1, 35015, 35021, 40115, -1, 40112, 35025, 40113, -1, 35021, 35025, 40112, -1, 40113, 35029, 40109, -1, 35025, 35029, 40113, -1, 35029, 34559, 40109, -1, 40096, 34849, 40100, -1, 34680, 34849, 40096, -1, 40100, 34850, 40099, -1, 34849, 34850, 40100, -1, 40099, 34822, 40098, -1, 34850, 34822, 40099, -1, 40098, 34811, 40097, -1, 34822, 34811, 40098, -1, 40097, 34810, 40095, -1, 34811, 34810, 40097, -1, 40095, 34803, 40094, -1, 34810, 34803, 40095, -1, 40094, 34795, 40092, -1, 34803, 34795, 40094, -1, 40092, 34792, 40093, -1, 34795, 34792, 40092, -1, 40107, 40106, 34676, -1, 40107, 34676, 34675, -1, 40101, 40093, 34792, -1, 40101, 34792, 34770, -1, 34770, 34740, 40101, -1, 40102, 34740, 40103, -1, 40101, 34740, 40102, -1, 40103, 34733, 40104, -1, 34740, 34733, 40103, -1, 40104, 34726, 40105, -1, 34733, 34726, 40104, -1, 40105, 34732, 40106, -1, 34726, 34732, 40105, -1, 34732, 34676, 40106, -1, 34450, 34441, 39821, -1, 39820, 34441, 39817, -1, 39821, 34441, 39820, -1, 39817, 34439, 39818, -1, 34441, 34439, 39817, -1, 39818, 34437, 39819, -1, 34439, 34437, 39818, -1, 39819, 34433, 39822, -1, 34437, 34433, 39819, -1, 34433, 34416, 39822, -1, 39821, 39825, 34450, -1, 34450, 39825, 34351, -1, 34683, 39822, 34416, -1, 39833, 39822, 34683, -1, 39828, 34682, 39831, -1, 34682, 35075, 39831, -1, 39831, 35078, 39830, -1, 35075, 35078, 39831, -1, 39830, 35080, 39829, -1, 35078, 35080, 39830, -1, 39829, 35084, 39826, -1, 35080, 35084, 39829, -1, 39826, 35087, 39827, -1, 35084, 35087, 39826, -1, 39827, 35091, 39823, -1, 35087, 35091, 39827, -1, 39823, 34352, 39824, -1, 35091, 34352, 39823, -1, 39824, 34351, 39825, -1, 34352, 34351, 39824, -1, 39833, 34683, 39834, -1, 39834, 34944, 39832, -1, 34683, 34944, 39834, -1, 39832, 34946, 39835, -1, 34944, 34946, 39832, -1, 39835, 34947, 39836, -1, 34946, 34947, 39835, -1, 39836, 34949, 39838, -1, 34947, 34949, 39836, -1, 39838, 34950, 39837, -1, 34949, 34950, 39838, -1, 39837, 34951, 39839, -1, 34950, 34951, 39837, -1, 39839, 34953, 39840, -1, 34951, 34953, 39839, -1, 39840, 34954, 35094, -1, 34953, 34954, 39840, -1, 34954, 34943, 35094, -1, 39828, 39841, 34682, -1, 34682, 39841, 34685, -1, 39842, 34859, 34843, -1, 39842, 35097, 34859, -1, 34843, 34842, 39842, -1, 39843, 34842, 39844, -1, 39842, 34842, 39843, -1, 39844, 34846, 39841, -1, 34842, 34846, 39844, -1, 34846, 34685, 39841, -1, 34691, 40116, 34479, -1, 40117, 40116, 34691, -1, 40118, 40119, 40120, -1, 40120, 40119, 40121, -1, 40122, 40123, 40118, -1, 40119, 40124, 40125, -1, 40118, 40124, 40119, -1, 40123, 40126, 40118, -1, 40118, 40126, 40124, -1, 40123, 40117, 40126, -1, 40123, 40127, 40117, -1, 40127, 40128, 40117, -1, 40128, 40129, 40117, -1, 40129, 40130, 40117, -1, 40130, 40131, 40117, -1, 40132, 40133, 40131, -1, 40133, 40134, 40131, -1, 40131, 40134, 40117, -1, 40134, 40116, 40117, -1, 40116, 40135, 40136, -1, 40116, 40137, 40135, -1, 40137, 40138, 40139, -1, 40116, 40138, 40137, -1, 40134, 40140, 40116, -1, 40116, 40140, 40138, -1, 40140, 40141, 40138, -1, 40142, 40143, 40140, -1, 40143, 40144, 40140, -1, 40141, 40145, 40146, -1, 40144, 40147, 40140, -1, 40145, 40148, 40149, -1, 40140, 40148, 40141, -1, 40141, 40148, 40145, -1, 40147, 40148, 40140, -1, 34558, 34524, 40138, -1, 40138, 34524, 40139, -1, 40139, 34517, 40137, -1, 34524, 34517, 40139, -1, 40137, 34507, 40135, -1, 34517, 34507, 40137, -1, 40135, 34500, 40136, -1, 34507, 34500, 40135, -1, 40136, 34479, 40116, -1, 34500, 34479, 40136, -1, 40117, 35037, 40126, -1, 34691, 35037, 40117, -1, 40126, 35039, 40124, -1, 35037, 35039, 40126, -1, 40124, 35041, 40125, -1, 35039, 35041, 40124, -1, 40125, 35042, 40119, -1, 35041, 35042, 40125, -1, 40119, 35033, 40121, -1, 35042, 35033, 40119, -1, 40121, 34996, 40120, -1, 35033, 34996, 40121, -1, 40120, 34990, 40118, -1, 34996, 34990, 40120, -1, 40118, 34989, 40122, -1, 34990, 34989, 40118, -1, 40122, 34985, 40123, -1, 34989, 34985, 40122, -1, 40138, 40141, 34451, -1, 40138, 34451, 34558, -1, 40127, 40123, 34985, -1, 40127, 34985, 34979, -1, 40140, 34418, 40142, -1, 40142, 34417, 40143, -1, 34418, 34417, 40142, -1, 40143, 34426, 40144, -1, 34417, 34426, 40143, -1, 40144, 34431, 40147, -1, 34426, 34431, 40144, -1, 40147, 34434, 40148, -1, 34431, 34434, 40147, -1, 40148, 34436, 40149, -1, 34434, 34436, 40148, -1, 40149, 34438, 40145, -1, 34436, 34438, 40149, -1, 40145, 34440, 40146, -1, 34438, 34440, 40145, -1, 40146, 34449, 40141, -1, 34440, 34449, 40146, -1, 34449, 34451, 40141, -1, 40127, 34979, 40128, -1, 40128, 34967, 40129, -1, 34979, 34967, 40128, -1, 40129, 34959, 40130, -1, 34967, 34959, 40129, -1, 34959, 34957, 40130, -1, 40140, 40134, 34693, -1, 40140, 34693, 34418, -1, 34932, 40130, 34957, -1, 40131, 40130, 34932, -1, 40131, 34932, 40132, -1, 34932, 34930, 40132, -1, 40132, 34938, 40133, -1, 34930, 34938, 40132, -1, 40133, 34693, 40134, -1, 34938, 34693, 40133, -1, 34366, 34368, 40150, -1, 40150, 34368, 40151, -1, 40151, 34369, 40152, -1, 34368, 34369, 40151, -1, 40152, 34370, 40153, -1, 34369, 34370, 40152, -1, 40153, 34371, 40154, -1, 34370, 34371, 40153, -1, 40154, 34372, 40155, -1, 34371, 34372, 40154, -1, 40155, 34375, 40156, -1, 34372, 34375, 40155, -1, 40156, 34376, 40157, -1, 34375, 34376, 40156, -1, 40157, 34378, 40158, -1, 34376, 34378, 40157, -1, 40158, 34379, 40159, -1, 34378, 34379, 40158, -1, 40156, 40157, 40155, -1, 40155, 40153, 40154, -1, 40158, 40159, 40157, -1, 40157, 40159, 40155, -1, 40153, 40151, 40152, -1, 40155, 40151, 40153, -1, 40159, 40151, 40155, -1, 40159, 40150, 40151, -1, 40159, 40160, 40150, -1, 40161, 40162, 40163, -1, 40163, 40162, 40164, -1, 40164, 40162, 40165, -1, 40165, 40162, 40160, -1, 40160, 40162, 40150, -1, 40162, 40166, 40150, -1, 40166, 40167, 40168, -1, 40168, 40167, 40169, -1, 40169, 40167, 40170, -1, 40170, 40167, 40171, -1, 40162, 40172, 40166, -1, 40166, 40172, 40167, -1, 40173, 40174, 40172, -1, 40172, 40175, 40167, -1, 40174, 40176, 40172, -1, 40172, 40177, 40175, -1, 40176, 40178, 40172, -1, 40172, 40179, 40177, -1, 40178, 40180, 40172, -1, 40180, 40181, 40172, -1, 40172, 40181, 40179, -1, 34366, 40166, 34576, -1, 40150, 40166, 34366, -1, 40160, 40159, 34379, -1, 40160, 34379, 35053, -1, 40167, 34562, 40171, -1, 40171, 34563, 40170, -1, 34562, 34563, 40171, -1, 40170, 34565, 40169, -1, 34563, 34565, 40170, -1, 40169, 34567, 40168, -1, 34565, 34567, 40169, -1, 34567, 34568, 40168, -1, 40168, 34576, 40166, -1, 34568, 34576, 40168, -1, 40160, 35048, 40165, -1, 35053, 35048, 40160, -1, 40165, 35046, 40164, -1, 35048, 35046, 40165, -1, 40164, 35035, 40163, -1, 35046, 35035, 40164, -1, 40163, 35034, 40161, -1, 35035, 35034, 40163, -1, 40161, 34700, 40162, -1, 35034, 34700, 40161, -1, 34562, 40175, 34569, -1, 40167, 40175, 34562, -1, 34481, 40162, 34700, -1, 40172, 40162, 34481, -1, 40172, 34481, 40173, -1, 34481, 34480, 40173, -1, 40173, 34487, 40174, -1, 34480, 34487, 40173, -1, 40174, 34494, 40176, -1, 34487, 34494, 40174, -1, 40176, 34497, 40178, -1, 34494, 34497, 40176, -1, 40178, 34501, 40180, -1, 34497, 34501, 40178, -1, 40180, 34508, 40181, -1, 34501, 34508, 40180, -1, 40179, 34515, 40177, -1, 40181, 34515, 40179, -1, 34508, 34515, 40181, -1, 40177, 34519, 40175, -1, 34515, 34519, 40177, -1, 34519, 34569, 40175, -1, 40182, 33722, 40183, -1, 33722, 33670, 40183, -1, 40183, 33671, 40184, -1, 33670, 33671, 40183, -1, 40184, 33674, 40185, -1, 33671, 33674, 40184, -1, 40185, 33676, 40186, -1, 33674, 33676, 40185, -1, 40186, 33668, 40187, -1, 33676, 33668, 40186, -1, 40188, 40189, 40190, -1, 40189, 40191, 40190, -1, 40190, 40192, 40193, -1, 40191, 40192, 40190, -1, 40194, 40195, 40192, -1, 40196, 40195, 40197, -1, 40197, 40195, 40198, -1, 40198, 40195, 40199, -1, 40199, 40195, 40200, -1, 40200, 40195, 40201, -1, 40201, 40195, 40202, -1, 40202, 40195, 40203, -1, 40203, 40195, 40194, -1, 40192, 40195, 40193, -1, 40204, 40205, 40206, -1, 40206, 40205, 40207, -1, 40208, 40209, 40210, -1, 40208, 40211, 40209, -1, 40212, 40213, 40204, -1, 40205, 40213, 40208, -1, 40204, 40213, 40205, -1, 40208, 40213, 40211, -1, 40212, 40187, 40213, -1, 40187, 40182, 40186, -1, 40193, 40182, 40212, -1, 40195, 40182, 40193, -1, 40212, 40182, 40187, -1, 40186, 40184, 40185, -1, 40182, 40184, 40186, -1, 40182, 40183, 40184, -1, 40182, 40195, 33812, -1, 40182, 33812, 33722, -1, 40213, 40187, 33668, -1, 40213, 33668, 33635, -1, 33973, 33975, 40194, -1, 40194, 33975, 40203, -1, 40203, 34011, 40202, -1, 33975, 34011, 40203, -1, 40202, 34002, 40201, -1, 34011, 34002, 40202, -1, 40201, 33993, 40200, -1, 34002, 33993, 40201, -1, 40200, 33994, 40199, -1, 33993, 33994, 40200, -1, 40199, 33995, 40198, -1, 33994, 33995, 40199, -1, 40198, 33996, 40197, -1, 33995, 33996, 40198, -1, 40197, 33997, 40196, -1, 33996, 33997, 40197, -1, 40196, 33812, 40195, -1, 33997, 33812, 40196, -1, 40213, 33635, 40211, -1, 40211, 33628, 40209, -1, 33635, 33628, 40211, -1, 40209, 33619, 40210, -1, 33628, 33619, 40209, -1, 40210, 33618, 40208, -1, 33619, 33618, 40210, -1, 40208, 33617, 40205, -1, 33618, 33617, 40208, -1, 40205, 33620, 40207, -1, 33617, 33620, 40205, -1, 40207, 33629, 40206, -1, 33620, 33629, 40207, -1, 40206, 33637, 40204, -1, 33629, 33637, 40206, -1, 40204, 33638, 40212, -1, 33637, 33638, 40204, -1, 33638, 33641, 40212, -1, 40194, 40192, 33966, -1, 40194, 33966, 33973, -1, 40193, 40212, 33641, -1, 40193, 33641, 33961, -1, 33961, 33962, 40193, -1, 40193, 33962, 40190, -1, 40190, 33963, 40188, -1, 33962, 33963, 40190, -1, 40188, 33964, 40189, -1, 33963, 33964, 40188, -1, 40191, 33965, 40192, -1, 40189, 33965, 40191, -1, 33964, 33965, 40189, -1, 33965, 33966, 40192, -1, 33787, 40214, 33788, -1, 40215, 40214, 33787, -1, 40216, 40217, 40218, -1, 40216, 40219, 40217, -1, 40220, 40221, 40219, -1, 40219, 40221, 40217, -1, 40222, 40214, 40221, -1, 40223, 40214, 40224, -1, 40224, 40214, 40225, -1, 40225, 40214, 40226, -1, 40226, 40214, 40227, -1, 40227, 40214, 40228, -1, 40228, 40214, 40229, -1, 40229, 40214, 40230, -1, 40230, 40214, 40222, -1, 40221, 40214, 40217, -1, 40214, 40215, 40217, -1, 40231, 40232, 40233, -1, 40231, 40234, 40232, -1, 40235, 40236, 40237, -1, 40237, 40236, 40215, -1, 40215, 40236, 40231, -1, 40234, 40238, 40239, -1, 40236, 40238, 40231, -1, 40231, 40238, 40234, -1, 40231, 40217, 40215, -1, 40215, 33839, 40237, -1, 33787, 33839, 40215, -1, 40237, 33840, 40235, -1, 33839, 33840, 40237, -1, 33840, 40236, 40235, -1, 33840, 33831, 40236, -1, 34047, 34082, 40222, -1, 40230, 34082, 40229, -1, 40222, 34082, 40230, -1, 40229, 34079, 40228, -1, 34082, 34079, 40229, -1, 40228, 34076, 40227, -1, 34079, 34076, 40228, -1, 40227, 34066, 40226, -1, 34076, 34066, 40227, -1, 40226, 34067, 40225, -1, 34066, 34067, 40226, -1, 40225, 34068, 40224, -1, 34067, 34068, 40225, -1, 40224, 34071, 40223, -1, 34068, 34071, 40224, -1, 40223, 34072, 40214, -1, 34071, 34072, 40223, -1, 34072, 33788, 40214, -1, 40238, 40236, 33831, -1, 40238, 33831, 33827, -1, 40222, 40221, 34034, -1, 40222, 34034, 34047, -1, 40240, 40241, 40238, -1, 40241, 40242, 40238, -1, 33827, 40243, 40238, -1, 33820, 40243, 33827, -1, 33815, 40243, 33820, -1, 33806, 40243, 33815, -1, 40238, 40243, 40240, -1, 33781, 40244, 33806, -1, 33754, 40244, 33781, -1, 33806, 40244, 40243, -1, 40243, 40244, 40240, -1, 40240, 40244, 40241, -1, 40238, 40245, 33723, -1, 33736, 40245, 33754, -1, 33718, 40245, 33736, -1, 33723, 40245, 33718, -1, 40241, 40245, 40242, -1, 33754, 40245, 40244, -1, 40244, 40245, 40241, -1, 40242, 40245, 40238, -1, 40217, 33810, 40218, -1, 40218, 34003, 40216, -1, 33810, 34003, 40218, -1, 40216, 34012, 40219, -1, 34003, 34012, 40216, -1, 40219, 34019, 40220, -1, 34012, 34019, 40219, -1, 40220, 34026, 40221, -1, 34019, 34026, 40220, -1, 34026, 34034, 40221, -1, 40238, 33723, 40239, -1, 40239, 33769, 40234, -1, 33723, 33769, 40239, -1, 40234, 33802, 40232, -1, 33769, 33802, 40234, -1, 40232, 33818, 40233, -1, 33802, 33818, 40232, -1, 40233, 33830, 40231, -1, 33818, 33830, 40233, -1, 33830, 33811, 40231, -1, 33810, 40231, 33811, -1, 40217, 40231, 33810, -1, 40246, 33790, 40247, -1, 40247, 33885, 40248, -1, 33790, 33885, 40247, -1, 40248, 33887, 40249, -1, 33885, 33887, 40248, -1, 40249, 33891, 40250, -1, 33887, 33891, 40249, -1, 40250, 33878, 40251, -1, 33891, 33878, 40250, -1, 33878, 33874, 40251, -1, 40252, 40253, 40254, -1, 40254, 40253, 40255, -1, 40255, 40256, 40257, -1, 40253, 40256, 40255, -1, 40258, 40259, 40256, -1, 40260, 40259, 40261, -1, 40261, 40259, 40262, -1, 40262, 40259, 40263, -1, 40263, 40259, 40264, -1, 40264, 40259, 40265, -1, 40265, 40259, 40266, -1, 40266, 40259, 40267, -1, 40267, 40259, 40258, -1, 40256, 40259, 40257, -1, 40268, 40269, 40270, -1, 40271, 40272, 40273, -1, 40274, 40275, 40276, -1, 40276, 40275, 40268, -1, 40269, 40275, 40271, -1, 40272, 40275, 40277, -1, 40268, 40275, 40269, -1, 40271, 40275, 40272, -1, 40274, 40251, 40275, -1, 40257, 40246, 40274, -1, 40259, 40246, 40257, -1, 40274, 40246, 40251, -1, 40251, 40249, 40250, -1, 40246, 40247, 40251, -1, 40251, 40248, 40249, -1, 40247, 40248, 40251, -1, 40246, 40259, 33780, -1, 40246, 33780, 33790, -1, 40275, 40251, 33874, -1, 40275, 33874, 33867, -1, 34113, 34168, 40258, -1, 40258, 34168, 40267, -1, 40266, 34163, 40265, -1, 40267, 34163, 40266, -1, 34168, 34163, 40267, -1, 40265, 34156, 40264, -1, 34163, 34156, 40265, -1, 40264, 34152, 40263, -1, 34156, 34152, 40264, -1, 40263, 34144, 40262, -1, 34152, 34144, 40263, -1, 40262, 34145, 40261, -1, 34144, 34145, 40262, -1, 40261, 34147, 40260, -1, 34145, 34147, 40261, -1, 40260, 34148, 40259, -1, 34147, 34148, 40260, -1, 34148, 33780, 40259, -1, 40275, 33857, 40277, -1, 33867, 33857, 40275, -1, 40277, 33851, 40272, -1, 33857, 33851, 40277, -1, 40272, 33844, 40273, -1, 33851, 33844, 40272, -1, 40273, 33850, 40271, -1, 33844, 33850, 40273, -1, 40271, 33854, 40269, -1, 33850, 33854, 40271, -1, 40269, 33860, 40270, -1, 33854, 33860, 40269, -1, 40270, 33868, 40268, -1, 33860, 33868, 40270, -1, 40276, 33871, 40274, -1, 40268, 33871, 40276, -1, 33868, 33871, 40268, -1, 33871, 33786, 40274, -1, 40258, 40256, 34094, -1, 40258, 34094, 34113, -1, 33785, 40274, 33786, -1, 40257, 40274, 33785, -1, 33785, 34077, 40257, -1, 40255, 34077, 40254, -1, 40257, 34077, 40255, -1, 40254, 34080, 40252, -1, 34077, 34080, 40254, -1, 40252, 34083, 40253, -1, 34080, 34083, 40252, -1, 40253, 34088, 40256, -1, 34083, 34088, 40253, -1, 34088, 34094, 40256, -1, 40278, 33673, 40279, -1, 40279, 34235, 40280, -1, 33673, 34235, 40279, -1, 40280, 34220, 40281, -1, 34235, 34220, 40280, -1, 40281, 34205, 40282, -1, 34220, 34205, 40281, -1, 40282, 34197, 40283, -1, 34205, 34197, 40282, -1, 40283, 34198, 40284, -1, 34197, 34198, 40283, -1, 40284, 34199, 40285, -1, 34198, 34199, 40284, -1, 40285, 34200, 40286, -1, 34199, 34200, 40285, -1, 34200, 33783, 40286, -1, 40287, 40288, 40289, -1, 40290, 40291, 40287, -1, 40287, 40291, 40288, -1, 40291, 40292, 40288, -1, 40280, 40281, 40279, -1, 40281, 40282, 40279, -1, 40279, 40283, 40278, -1, 40282, 40283, 40279, -1, 40284, 40285, 40283, -1, 40283, 40285, 40278, -1, 40278, 40286, 40292, -1, 40285, 40286, 40278, -1, 40292, 40286, 40288, -1, 40293, 40294, 40295, -1, 40295, 40294, 40296, -1, 40294, 40297, 40298, -1, 40298, 40297, 40299, -1, 40300, 40301, 40293, -1, 40297, 40301, 40302, -1, 40293, 40301, 40294, -1, 40294, 40301, 40297, -1, 40300, 40303, 40301, -1, 40288, 40304, 40300, -1, 40286, 40304, 40288, -1, 40300, 40304, 40303, -1, 40303, 40305, 40306, -1, 40304, 40307, 40303, -1, 40303, 40308, 40305, -1, 40307, 40308, 40303, -1, 33673, 40292, 34171, -1, 40278, 40292, 33673, -1, 40304, 40286, 33783, -1, 40304, 33783, 33782, -1, 33778, 34149, 40288, -1, 40288, 34149, 40289, -1, 40289, 34155, 40287, -1, 34149, 34155, 40289, -1, 40287, 34160, 40290, -1, 34155, 34160, 40287, -1, 40290, 34166, 40291, -1, 34160, 34166, 40290, -1, 40291, 34171, 40292, -1, 34166, 34171, 40291, -1, 40304, 33782, 40307, -1, 40307, 33905, 40308, -1, 33782, 33905, 40307, -1, 40308, 33907, 40305, -1, 33905, 33907, 40308, -1, 33907, 33913, 40305, -1, 40306, 33918, 40303, -1, 40305, 33918, 40306, -1, 33913, 33918, 40305, -1, 33918, 33743, 40303, -1, 33778, 40300, 33779, -1, 40288, 40300, 33778, -1, 40301, 40303, 33743, -1, 40301, 33743, 33903, -1, 40301, 33903, 40302, -1, 40302, 33899, 40297, -1, 33903, 33899, 40302, -1, 40297, 33895, 40299, -1, 33899, 33895, 40297, -1, 40299, 33890, 40298, -1, 33895, 33890, 40299, -1, 40298, 33886, 40294, -1, 33890, 33886, 40298, -1, 40294, 33894, 40296, -1, 33886, 33894, 40294, -1, 40296, 33898, 40295, -1, 33894, 33898, 40296, -1, 40295, 33900, 40293, -1, 33898, 33900, 40295, -1, 40293, 33904, 40300, -1, 33900, 33904, 40293, -1, 33904, 33779, 40300, -1, 40309, 33798, 40310, -1, 33798, 33980, 40310, -1, 40310, 33976, 40311, -1, 33980, 33976, 40310, -1, 40311, 33978, 40312, -1, 33976, 33978, 40311, -1, 40312, 33983, 40313, -1, 33978, 33983, 40312, -1, 40313, 33741, 40314, -1, 33983, 33741, 40313, -1, 40315, 40316, 40317, -1, 40318, 40319, 40316, -1, 40317, 40319, 40320, -1, 40316, 40319, 40317, -1, 40321, 40322, 40319, -1, 40323, 40322, 40324, -1, 40324, 40322, 40325, -1, 40325, 40322, 40326, -1, 40326, 40322, 40327, -1, 40327, 40322, 40328, -1, 40328, 40322, 40329, -1, 40329, 40322, 40321, -1, 40319, 40322, 40320, -1, 40330, 40331, 40332, -1, 40331, 40333, 40334, -1, 40333, 40335, 40336, -1, 40330, 40335, 40331, -1, 40331, 40335, 40333, -1, 40337, 40338, 40330, -1, 40330, 40338, 40335, -1, 40337, 40314, 40338, -1, 40320, 40309, 40337, -1, 40322, 40309, 40320, -1, 40337, 40309, 40314, -1, 40314, 40312, 40313, -1, 40309, 40312, 40314, -1, 40309, 40310, 40312, -1, 40310, 40311, 40312, -1, 40309, 40322, 33793, -1, 40309, 33793, 33798, -1, 40338, 40314, 33741, -1, 40338, 33741, 33742, -1, 40321, 33677, 40329, -1, 40329, 34282, 40328, -1, 33677, 34282, 40329, -1, 40328, 34273, 40327, -1, 34282, 34273, 40328, -1, 40327, 34271, 40326, -1, 34273, 34271, 40327, -1, 40326, 34268, 40325, -1, 34271, 34268, 40326, -1, 40325, 34265, 40324, -1, 34268, 34265, 40325, -1, 40324, 34266, 40323, -1, 34265, 34266, 40324, -1, 40323, 34267, 40322, -1, 34266, 34267, 40323, -1, 34267, 33793, 40322, -1, 40338, 33742, 40335, -1, 40335, 33917, 40336, -1, 33742, 33917, 40335, -1, 40336, 33912, 40333, -1, 33917, 33912, 40336, -1, 40333, 33906, 40334, -1, 33912, 33906, 40333, -1, 40334, 33911, 40331, -1, 33906, 33911, 40334, -1, 40331, 33916, 40332, -1, 33911, 33916, 40331, -1, 40332, 33921, 40330, -1, 33916, 33921, 40332, -1, 40330, 33929, 40337, -1, 33921, 33929, 40330, -1, 33929, 33784, 40337, -1, 40321, 40319, 33675, -1, 40321, 33675, 33677, -1, 33797, 40337, 33784, -1, 40320, 40337, 33797, -1, 33797, 34206, 40320, -1, 40317, 34206, 40315, -1, 40320, 34206, 40317, -1, 40315, 34221, 40316, -1, 34206, 34221, 40315, -1, 40316, 34236, 40318, -1, 34221, 34236, 40316, -1, 40318, 34241, 40319, -1, 34236, 34241, 40318, -1, 34241, 33675, 40319, -1, 33794, 34055, 40339, -1, 40340, 34055, 40341, -1, 40339, 34055, 40340, -1, 34055, 34052, 40341, -1, 40341, 34054, 40342, -1, 34052, 34054, 40341, -1, 40342, 34058, 40343, -1, 34054, 34058, 40342, -1, 40343, 34061, 40344, -1, 34058, 34061, 40343, -1, 40344, 33739, 40345, -1, 34061, 33739, 40344, -1, 40346, 40347, 40348, -1, 40349, 40350, 40347, -1, 40348, 40350, 40351, -1, 40347, 40350, 40348, -1, 40352, 40353, 40350, -1, 40354, 40353, 40355, -1, 40355, 40353, 40356, -1, 40356, 40353, 40357, -1, 40357, 40353, 40358, -1, 40358, 40353, 40359, -1, 40359, 40353, 40360, -1, 40360, 40353, 40352, -1, 40350, 40353, 40351, -1, 40361, 40362, 40363, -1, 40364, 40365, 40361, -1, 40361, 40365, 40362, -1, 40365, 40366, 40367, -1, 40364, 40366, 40365, -1, 40368, 40369, 40364, -1, 40364, 40369, 40366, -1, 40368, 40345, 40369, -1, 40351, 40339, 40368, -1, 40353, 40339, 40351, -1, 40368, 40339, 40345, -1, 40345, 40343, 40344, -1, 40343, 40341, 40342, -1, 40340, 40341, 40339, -1, 40345, 40341, 40343, -1, 40339, 40341, 40345, -1, 40339, 40353, 33795, -1, 40339, 33795, 33794, -1, 40369, 40345, 33739, -1, 40369, 33739, 33740, -1, 33607, 34342, 40352, -1, 40360, 34342, 40359, -1, 40352, 34342, 40360, -1, 40359, 34340, 40358, -1, 34342, 34340, 40359, -1, 40358, 34332, 40357, -1, 34340, 34332, 40358, -1, 40357, 34325, 40356, -1, 34332, 34325, 40357, -1, 40356, 34321, 40355, -1, 34325, 34321, 40356, -1, 40355, 34322, 40354, -1, 34321, 34322, 40355, -1, 40354, 34323, 40353, -1, 34322, 34323, 40354, -1, 34323, 33795, 40353, -1, 40369, 33985, 40366, -1, 33740, 33985, 40369, -1, 40366, 33982, 40367, -1, 33985, 33982, 40366, -1, 40367, 33977, 40365, -1, 33982, 33977, 40367, -1, 40365, 33981, 40362, -1, 33977, 33981, 40365, -1, 40362, 33984, 40363, -1, 33981, 33984, 40362, -1, 40363, 33986, 40361, -1, 33984, 33986, 40363, -1, 40364, 33987, 40368, -1, 40361, 33987, 40364, -1, 33986, 33987, 40361, -1, 33987, 33792, 40368, -1, 33607, 40350, 33678, -1, 40352, 40350, 33607, -1, 40351, 40368, 33792, -1, 40351, 33792, 33791, -1, 33791, 34269, 40351, -1, 40351, 34269, 40348, -1, 40348, 34270, 40346, -1, 34269, 34270, 40348, -1, 40347, 34272, 40349, -1, 40346, 34272, 40347, -1, 34270, 34272, 40346, -1, 40349, 34279, 40350, -1, 34272, 34279, 40349, -1, 34279, 33678, 40350, -1, 40370, 33805, 40371, -1, 40371, 34120, 40372, -1, 33805, 34120, 40371, -1, 40372, 34116, 40373, -1, 34120, 34116, 40372, -1, 40373, 34118, 40374, -1, 34116, 34118, 40373, -1, 40374, 34125, 40375, -1, 34118, 34125, 40374, -1, 34125, 34128, 40375, -1, 40375, 33735, 40376, -1, 34128, 33735, 40375, -1, 40377, 40378, 40379, -1, 40380, 40379, 40381, -1, 40380, 40382, 40377, -1, 40380, 40377, 40379, -1, 40383, 40381, 40384, -1, 40383, 40380, 40381, -1, 40385, 40380, 40383, -1, 40376, 40380, 40385, -1, 40374, 40375, 40376, -1, 40373, 40374, 40376, -1, 40372, 40373, 40376, -1, 40370, 40371, 40372, -1, 40370, 40376, 40385, -1, 40370, 40372, 40376, -1, 40386, 40370, 40385, -1, 40387, 40388, 40389, -1, 40387, 40390, 40388, -1, 40387, 40391, 40390, -1, 40392, 40386, 40391, -1, 40392, 40391, 40387, -1, 40393, 40370, 40386, -1, 40393, 40386, 40392, -1, 40394, 40395, 40393, -1, 40394, 40393, 40392, -1, 40396, 40397, 40395, -1, 40396, 40398, 40397, -1, 40396, 40394, 40399, -1, 40396, 40395, 40394, -1, 40400, 40399, 40401, -1, 40400, 40396, 40399, -1, 40370, 40393, 33805, -1, 33805, 40393, 33737, -1, 40380, 33735, 33738, -1, 40380, 40376, 33735, -1, 40394, 33679, 40399, -1, 40399, 33822, 40401, -1, 33679, 33822, 40399, -1, 40401, 33817, 40400, -1, 33822, 33817, 40401, -1, 40400, 33803, 40396, -1, 33817, 33803, 40400, -1, 40396, 33771, 40398, -1, 33803, 33771, 40396, -1, 40398, 33730, 40397, -1, 33771, 33730, 40398, -1, 40397, 33732, 40395, -1, 33730, 33732, 40397, -1, 40395, 33734, 40393, -1, 33732, 33734, 40395, -1, 33734, 33737, 40393, -1, 40380, 33738, 40382, -1, 40382, 34060, 40377, -1, 33738, 34060, 40382, -1, 40377, 34057, 40378, -1, 34060, 34057, 40377, -1, 40378, 34053, 40379, -1, 34057, 34053, 40378, -1, 40379, 34056, 40381, -1, 34053, 34056, 40379, -1, 40381, 34059, 40384, -1, 34056, 34059, 40381, -1, 40384, 34062, 40383, -1, 34059, 34062, 40384, -1, 40383, 34063, 40385, -1, 34062, 34063, 40383, -1, 34063, 33796, 40385, -1, 40394, 33608, 33679, -1, 40394, 40392, 33608, -1, 33808, 40385, 33796, -1, 40386, 40385, 33808, -1, 33808, 34326, 40386, -1, 40391, 34326, 40390, -1, 40386, 34326, 40391, -1, 40390, 34333, 40388, -1, 34326, 34333, 40390, -1, 40388, 34341, 40389, -1, 34333, 34341, 40388, -1, 40389, 34343, 40387, -1, 34341, 34343, 40389, -1, 40387, 33609, 40392, -1, 34343, 33609, 40387, -1, 33609, 33608, 40392, -1, 33681, 33901, 40402, -1, 40402, 33901, 40403, -1, 40403, 33896, 40404, -1, 33901, 33896, 40403, -1, 40404, 33893, 40405, -1, 33896, 33893, 40404, -1, 40405, 33888, 40406, -1, 33893, 33888, 40405, -1, 40406, 33883, 40407, -1, 33888, 33883, 40406, -1, 40407, 33881, 40408, -1, 33883, 33881, 40407, -1, 40408, 33882, 40409, -1, 33881, 33882, 40408, -1, 40409, 33800, 40410, -1, 33882, 33800, 40409, -1, 40411, 40412, 40413, -1, 40413, 40414, 40415, -1, 40412, 40414, 40413, -1, 40412, 40416, 40414, -1, 40416, 40417, 40414, -1, 40404, 40405, 40403, -1, 40405, 40406, 40403, -1, 40407, 40408, 40406, -1, 40402, 40410, 40417, -1, 40409, 40410, 40408, -1, 40403, 40410, 40402, -1, 40408, 40410, 40406, -1, 40417, 40410, 40414, -1, 40406, 40410, 40403, -1, 40418, 40419, 40420, -1, 40418, 40421, 40419, -1, 40418, 40422, 40421, -1, 40418, 40423, 40422, -1, 40418, 40424, 40423, -1, 40418, 40425, 40424, -1, 40418, 40426, 40425, -1, 40418, 40427, 40426, -1, 40414, 40428, 40418, -1, 40410, 40428, 40414, -1, 40418, 40428, 40427, -1, 40428, 40429, 40427, -1, 40428, 40430, 40429, -1, 40429, 40431, 40432, -1, 40433, 40431, 40430, -1, 40430, 40431, 40429, -1, 33681, 40417, 33680, -1, 40402, 40417, 33681, -1, 40428, 40410, 33800, -1, 40428, 33800, 33799, -1, 33731, 33753, 40414, -1, 40414, 33753, 40415, -1, 40415, 33789, 40413, -1, 33753, 33789, 40415, -1, 40413, 33814, 40411, -1, 33789, 33814, 40413, -1, 40411, 33819, 40412, -1, 33814, 33819, 40411, -1, 40416, 33826, 40417, -1, 40412, 33826, 40416, -1, 33819, 33826, 40412, -1, 33826, 33680, 40417, -1, 40428, 33799, 40430, -1, 40430, 34216, 40433, -1, 33799, 34216, 40430, -1, 40433, 34209, 40431, -1, 34216, 34209, 40433, -1, 34209, 34211, 40431, -1, 40431, 34214, 40432, -1, 34211, 34214, 40431, -1, 40429, 34218, 40427, -1, 40432, 34218, 40429, -1, 34214, 34218, 40432, -1, 34218, 33729, 40427, -1, 33731, 40418, 33804, -1, 40414, 40418, 33731, -1, 40426, 40427, 33729, -1, 40426, 33729, 33733, -1, 40426, 33733, 40425, -1, 40425, 34127, 40424, -1, 33733, 34127, 40425, -1, 40424, 34124, 40423, -1, 34127, 34124, 40424, -1, 40423, 34117, 40422, -1, 34124, 34117, 40423, -1, 40422, 34119, 40421, -1, 34117, 34119, 40422, -1, 34119, 34126, 40421, -1, 40421, 34133, 40419, -1, 34126, 34133, 40421, -1, 40419, 34140, 40420, -1, 34133, 34140, 40419, -1, 40420, 33804, 40418, -1, 34140, 33804, 40420, -1, 40434, 33908, 40435, -1, 40435, 34291, 40436, -1, 33908, 34291, 40435, -1, 40436, 34286, 40437, -1, 34291, 34286, 40436, -1, 40437, 34288, 40438, -1, 34286, 34288, 40437, -1, 40438, 34295, 40439, -1, 34288, 34295, 40438, -1, 40439, 34302, 40440, -1, 34295, 34302, 40439, -1, 34302, 33727, 40440, -1, 40441, 40442, 40443, -1, 40444, 40445, 40441, -1, 40441, 40445, 40442, -1, 40442, 40446, 40447, -1, 40445, 40446, 40442, -1, 40448, 40449, 40450, -1, 40449, 40451, 40450, -1, 40451, 40452, 40450, -1, 40450, 40453, 40454, -1, 40452, 40453, 40450, -1, 40454, 40455, 40446, -1, 40446, 40455, 40447, -1, 40453, 40455, 40454, -1, 40456, 40457, 40458, -1, 40456, 40459, 40457, -1, 40460, 40461, 40462, -1, 40463, 40464, 40456, -1, 40459, 40464, 40460, -1, 40456, 40464, 40459, -1, 40460, 40464, 40461, -1, 40463, 40440, 40464, -1, 40447, 40434, 40463, -1, 40455, 40434, 40447, -1, 40463, 40434, 40440, -1, 40434, 40435, 40440, -1, 40440, 40438, 40439, -1, 40435, 40438, 40440, -1, 40436, 40437, 40435, -1, 40435, 40437, 40438, -1, 33908, 40455, 33909, -1, 40434, 40455, 33908, -1, 40464, 40440, 33727, -1, 40464, 33727, 33728, -1, 33684, 33971, 40454, -1, 40450, 33971, 40448, -1, 40454, 33971, 40450, -1, 40448, 33970, 40449, -1, 33971, 33970, 40448, -1, 40449, 33968, 40451, -1, 33970, 33968, 40449, -1, 40451, 33960, 40452, -1, 33968, 33960, 40451, -1, 40452, 33952, 40453, -1, 33960, 33952, 40452, -1, 40453, 33954, 40455, -1, 33952, 33954, 40453, -1, 33954, 33909, 40455, -1, 40464, 33728, 40461, -1, 40461, 34226, 40462, -1, 33728, 34226, 40461, -1, 40462, 34217, 40460, -1, 34226, 34217, 40462, -1, 40460, 34213, 40459, -1, 34217, 34213, 40460, -1, 34213, 34210, 40459, -1, 40459, 34215, 40457, -1, 34210, 34215, 40459, -1, 40457, 34223, 40458, -1, 34215, 34223, 40457, -1, 40456, 34228, 40463, -1, 40458, 34228, 40456, -1, 34223, 34228, 40458, -1, 34228, 33801, 40463, -1, 40454, 40446, 33683, -1, 40454, 33683, 33684, -1, 33813, 40463, 33801, -1, 40447, 40463, 33813, -1, 33813, 33884, 40447, -1, 40447, 33884, 40442, -1, 40442, 33889, 40443, -1, 33884, 33889, 40442, -1, 40443, 33892, 40441, -1, 33889, 33892, 40443, -1, 40441, 33897, 40444, -1, 33892, 33897, 40441, -1, 40444, 33902, 40445, -1, 33897, 33902, 40444, -1, 40445, 33683, 40446, -1, 33902, 33683, 40445, -1, 33643, 33631, 40465, -1, 40465, 33631, 40466, -1, 40466, 33621, 40467, -1, 33631, 33621, 40466, -1, 40467, 33611, 40468, -1, 33621, 33611, 40467, -1, 40468, 33613, 40469, -1, 33611, 33613, 40468, -1, 40469, 33624, 40470, -1, 33613, 33624, 40469, -1, 40470, 33636, 40471, -1, 33624, 33636, 40470, -1, 40472, 40473, 40474, -1, 40475, 40476, 40472, -1, 40473, 40477, 40478, -1, 40472, 40477, 40473, -1, 40476, 40477, 40472, -1, 40479, 40480, 40477, -1, 40481, 40480, 40482, -1, 40482, 40480, 40483, -1, 40483, 40480, 40484, -1, 40484, 40480, 40485, -1, 40485, 40480, 40486, -1, 40486, 40480, 40479, -1, 40477, 40480, 40478, -1, 40487, 40488, 40489, -1, 40488, 40490, 40491, -1, 40487, 40492, 40488, -1, 40488, 40492, 40490, -1, 40493, 40494, 40487, -1, 40487, 40494, 40492, -1, 40493, 40471, 40494, -1, 40478, 40465, 40493, -1, 40480, 40465, 40478, -1, 40493, 40465, 40471, -1, 40465, 40470, 40471, -1, 40465, 40466, 40470, -1, 40466, 40469, 40470, -1, 40467, 40468, 40466, -1, 40466, 40468, 40469, -1, 40465, 40480, 33979, -1, 40465, 33979, 33643, -1, 33726, 40471, 33636, -1, 40494, 40471, 33726, -1, 33686, 34045, 40479, -1, 40486, 34045, 40485, -1, 40479, 34045, 40486, -1, 40485, 34043, 40484, -1, 34045, 34043, 40485, -1, 40484, 34038, 40483, -1, 34043, 34038, 40484, -1, 40483, 34031, 40482, -1, 34038, 34031, 40483, -1, 40482, 34023, 40481, -1, 34031, 34023, 40482, -1, 40481, 33999, 40480, -1, 34023, 33999, 40481, -1, 33999, 33979, 40480, -1, 40494, 34300, 40492, -1, 33726, 34300, 40494, -1, 40492, 34294, 40490, -1, 34300, 34294, 40492, -1, 40490, 34287, 40491, -1, 34294, 34287, 40490, -1, 40491, 34292, 40488, -1, 34287, 34292, 40491, -1, 40489, 34298, 40487, -1, 40488, 34298, 40489, -1, 34292, 34298, 40488, -1, 40487, 34304, 40493, -1, 34298, 34304, 40487, -1, 34304, 33910, 40493, -1, 40479, 40477, 33685, -1, 40479, 33685, 33686, -1, 33953, 40493, 33910, -1, 40478, 40493, 33953, -1, 33953, 33955, 40478, -1, 40473, 33955, 40474, -1, 40478, 33955, 40473, -1, 40474, 33967, 40472, -1, 33955, 33967, 40474, -1, 40472, 33969, 40475, -1, 33967, 33969, 40472, -1, 40475, 33972, 40476, -1, 33969, 33972, 40475, -1, 40476, 33974, 40477, -1, 33972, 33974, 40476, -1, 33974, 33685, 40477, -1, 33869, 33862, 40495, -1, 40495, 33862, 40496, -1, 40496, 33852, 40497, -1, 33862, 33852, 40496, -1, 40497, 33846, 40498, -1, 33852, 33846, 40497, -1, 40498, 33848, 40499, -1, 33846, 33848, 40498, -1, 40499, 33856, 40500, -1, 33848, 33856, 40499, -1, 40500, 33864, 40501, -1, 33856, 33864, 40500, -1, 40501, 33725, 40502, -1, 33864, 33725, 40501, -1, 40503, 40504, 40505, -1, 40505, 40504, 40506, -1, 40503, 40507, 40504, -1, 40504, 40508, 40509, -1, 40507, 40508, 40504, -1, 40510, 40511, 40512, -1, 40513, 40514, 40511, -1, 40511, 40514, 40512, -1, 40512, 40515, 40508, -1, 40516, 40515, 40517, -1, 40517, 40515, 40514, -1, 40508, 40515, 40509, -1, 40514, 40515, 40512, -1, 40518, 40519, 40520, -1, 40518, 40521, 40519, -1, 40522, 40523, 40524, -1, 40524, 40523, 40525, -1, 40525, 40523, 40518, -1, 40518, 40523, 40521, -1, 40522, 40502, 40523, -1, 40509, 40495, 40522, -1, 40515, 40495, 40509, -1, 40522, 40495, 40502, -1, 40502, 40500, 40501, -1, 40496, 40497, 40495, -1, 40495, 40497, 40502, -1, 40502, 40497, 40500, -1, 40500, 40498, 40499, -1, 40497, 40498, 40500, -1, 33869, 40515, 34050, -1, 40495, 40515, 33869, -1, 40523, 40502, 33725, -1, 40523, 33725, 33646, -1, 40512, 33688, 40510, -1, 40510, 34102, 40511, -1, 33688, 34102, 40510, -1, 40511, 34087, 40513, -1, 34102, 34087, 40511, -1, 40513, 34081, 40514, -1, 34087, 34081, 40513, -1, 40514, 34074, 40517, -1, 34081, 34074, 40514, -1, 40517, 34069, 40516, -1, 34074, 34069, 40517, -1, 40516, 34064, 40515, -1, 34069, 34064, 40516, -1, 34064, 34050, 40515, -1, 40523, 33646, 40521, -1, 40521, 33634, 40519, -1, 33646, 33634, 40521, -1, 40519, 33623, 40520, -1, 33634, 33623, 40519, -1, 40520, 33612, 40518, -1, 33623, 33612, 40520, -1, 33612, 33622, 40518, -1, 40518, 33630, 40525, -1, 33622, 33630, 40518, -1, 40524, 33642, 40522, -1, 40525, 33642, 40524, -1, 33630, 33642, 40525, -1, 33642, 33656, 40522, -1, 40512, 40508, 33687, -1, 40512, 33687, 33688, -1, 34000, 40522, 33656, -1, 40509, 40522, 34000, -1, 34000, 34024, 40509, -1, 40504, 34024, 40506, -1, 40509, 34024, 40504, -1, 40506, 34032, 40505, -1, 34024, 34032, 40506, -1, 40505, 34035, 40503, -1, 34032, 34035, 40505, -1, 40503, 34040, 40507, -1, 34035, 34040, 40503, -1, 40507, 34044, 40508, -1, 34040, 34044, 40507, -1, 34044, 33687, 40508, -1, 35788, 33863, 35791, -1, 33724, 33863, 35788, -1, 35791, 33855, 35789, -1, 33863, 33855, 35791, -1, 35789, 33847, 35790, -1, 33855, 33847, 35789, -1, 35790, 33849, 35795, -1, 33847, 33849, 35790, -1, 35795, 33861, 35793, -1, 33849, 33861, 35795, -1, 35794, 33870, 35792, -1, 35793, 33870, 35794, -1, 33861, 33870, 35793, -1, 33870, 33877, 35792, -1, 34065, 35792, 33877, -1, 35804, 35792, 34065, -1, 35804, 34070, 35805, -1, 34065, 34070, 35804, -1, 35805, 34075, 35803, -1, 34070, 34075, 35805, -1, 35803, 34078, 35806, -1, 34075, 34078, 35803, -1, 35806, 34084, 35807, -1, 34078, 34084, 35806, -1, 35807, 34101, 35809, -1, 34084, 34101, 35807, -1, 35808, 34112, 35810, -1, 35809, 34112, 35808, -1, 34101, 34112, 35809, -1, 34112, 33690, 35810, -1, 35819, 34632, 35843, -1, 35843, 34986, 35842, -1, 34632, 34986, 35843, -1, 35842, 34976, 35841, -1, 34986, 34976, 35842, -1, 35841, 34961, 35838, -1, 34976, 34961, 35841, -1, 35838, 34956, 35839, -1, 34961, 34956, 35838, -1, 35839, 34952, 35837, -1, 34956, 34952, 35839, -1, 34952, 34942, 35837, -1, 35837, 34936, 35840, -1, 34942, 34936, 35837, -1, 35824, 35840, 34936, -1, 35824, 34936, 34744, -1, 35824, 34744, 35828, -1, 35828, 34736, 35827, -1, 34744, 34736, 35828, -1, 35827, 34728, 35826, -1, 34736, 34728, 35827, -1, 35826, 34719, 35825, -1, 34728, 34719, 35826, -1, 35825, 34721, 35823, -1, 34719, 34721, 35825, -1, 35823, 34723, 35821, -1, 34721, 34723, 35823, -1, 34723, 34730, 35821, -1, 35821, 34593, 35822, -1, 34730, 34593, 35821, -1, 40526, 40527, 40528, -1, 40528, 40529, 40530, -1, 40527, 40529, 40528, -1, 40530, 40531, 40532, -1, 40529, 40531, 40530, -1, 40532, 34367, 34574, -1, 40531, 34367, 40532, -1, 40533, 40534, 40535, -1, 40534, 40536, 40535, -1, 40536, 40537, 40535, -1, 40537, 40538, 40535, -1, 40538, 40539, 40535, -1, 40539, 40540, 40535, -1, 40535, 40541, 40542, -1, 40540, 40541, 40535, -1, 40542, 40543, 40526, -1, 40541, 40543, 40542, -1, 40543, 40544, 40526, -1, 40544, 40545, 40526, -1, 40545, 40546, 40526, -1, 40547, 40548, 40549, -1, 40547, 40550, 40548, -1, 40547, 40551, 40550, -1, 40547, 40552, 40551, -1, 40547, 40553, 40552, -1, 40547, 40554, 40553, -1, 40547, 40555, 40554, -1, 40547, 40556, 40555, -1, 40547, 40557, 40556, -1, 40547, 40558, 40557, -1, 40559, 40560, 40561, -1, 40562, 40560, 40559, -1, 40562, 40563, 40560, -1, 40562, 40564, 40563, -1, 40562, 40565, 40564, -1, 40562, 40566, 40565, -1, 40562, 40567, 40566, -1, 40568, 40567, 40569, -1, 40566, 40567, 40568, -1, 40570, 40567, 40562, -1, 40570, 40571, 40567, -1, 40547, 40572, 40558, -1, 40547, 40573, 40572, -1, 40574, 40575, 40570, -1, 40575, 40576, 40570, -1, 40576, 40577, 40570, -1, 40577, 40578, 40570, -1, 40578, 40579, 40570, -1, 40570, 40580, 40571, -1, 40579, 40580, 40570, -1, 40580, 40581, 40571, -1, 40582, 40583, 40584, -1, 40581, 40585, 40571, -1, 40582, 40586, 40583, -1, 40582, 40587, 40586, -1, 40585, 40588, 40571, -1, 40582, 40589, 40587, -1, 40588, 40590, 40571, -1, 40590, 40591, 40571, -1, 40582, 40592, 40589, -1, 40582, 40593, 40592, -1, 40594, 40595, 40582, -1, 40582, 40595, 40593, -1, 40596, 40597, 40594, -1, 40594, 40597, 40595, -1, 40598, 40599, 40596, -1, 40600, 40599, 40598, -1, 40596, 40599, 40597, -1, 40573, 40601, 40600, -1, 40547, 40601, 40573, -1, 40600, 40601, 40599, -1, 40602, 40603, 40604, -1, 40605, 40603, 40602, -1, 40605, 40606, 40603, -1, 40606, 40607, 40608, -1, 40605, 40607, 40606, -1, 40609, 40610, 40611, -1, 40607, 40610, 40609, -1, 40607, 40612, 40610, -1, 40605, 40612, 40607, -1, 40605, 40613, 40612, -1, 40614, 40613, 40605, -1, 40614, 40615, 40613, -1, 40616, 40615, 40614, -1, 40616, 40617, 40615, -1, 40616, 40618, 40617, -1, 40616, 40619, 40618, -1, 40616, 40620, 40619, -1, 40616, 40621, 40620, -1, 40622, 40621, 40616, -1, 40622, 40623, 40621, -1, 40624, 40623, 40622, -1, 40624, 40625, 40623, -1, 40626, 40625, 40624, -1, 40627, 40625, 40626, -1, 40627, 40628, 40625, -1, 40629, 40628, 40627, -1, 40630, 40631, 40632, -1, 40630, 40633, 40631, -1, 40634, 40633, 40630, -1, 40634, 40635, 40633, -1, 40634, 40636, 40635, -1, 40637, 40636, 40634, -1, 40637, 40638, 40636, -1, 40639, 40638, 40637, -1, 40639, 40640, 40638, -1, 40641, 40640, 40639, -1, 40641, 40642, 40640, -1, 40643, 40642, 40641, -1, 40628, 40644, 40645, -1, 40646, 40644, 40647, -1, 40648, 40644, 40646, -1, 40649, 40644, 40648, -1, 40650, 40644, 40649, -1, 40651, 40644, 40650, -1, 40652, 40644, 40651, -1, 40653, 40644, 40652, -1, 40642, 40644, 40653, -1, 40643, 40644, 40642, -1, 40654, 40644, 40643, -1, 40655, 40644, 40654, -1, 40645, 40644, 40655, -1, 40647, 40656, 40657, -1, 40644, 40656, 40647, -1, 40657, 40527, 40658, -1, 40546, 40527, 40526, -1, 40656, 40527, 40657, -1, 40570, 40582, 40574, -1, 40574, 40582, 40584, -1, 40546, 40658, 40527, -1, 40632, 40571, 40591, -1, 40591, 40630, 40632, -1, 40535, 40547, 40549, -1, 40535, 40549, 40533, -1, 40547, 40644, 40628, -1, 40547, 40628, 40629, -1, 40547, 40629, 40659, -1, 40547, 40659, 40601, -1, 40660, 40570, 40562, -1, 40660, 40661, 40570, -1, 40662, 40562, 40559, -1, 40662, 40660, 40562, -1, 40663, 40559, 40561, -1, 40663, 40662, 40559, -1, 40664, 40598, 40665, -1, 40665, 40596, 40666, -1, 40598, 40596, 40665, -1, 40666, 40594, 40667, -1, 40596, 40594, 40666, -1, 40594, 40582, 40667, -1, 40668, 40649, 40669, -1, 40649, 40648, 40669, -1, 40669, 40646, 40670, -1, 40648, 40646, 40669, -1, 40671, 40647, 40672, -1, 40670, 40647, 40671, -1, 40646, 40647, 40670, -1, 40647, 40657, 40672, -1, 40672, 40658, 40673, -1, 40657, 40658, 40672, -1, 40674, 40614, 40605, -1, 40675, 40605, 40602, -1, 40675, 40674, 40605, -1, 40676, 40675, 40602, -1, 40677, 40602, 40604, -1, 40677, 40676, 40602, -1, 40626, 40624, 40678, -1, 40679, 40624, 40680, -1, 40678, 40624, 40679, -1, 40624, 40622, 40680, -1, 40680, 40616, 40681, -1, 40622, 40616, 40680, -1, 40682, 40643, 40683, -1, 40643, 40641, 40683, -1, 40683, 40639, 40684, -1, 40641, 40639, 40683, -1, 40684, 40637, 40685, -1, 40639, 40637, 40684, -1, 40685, 40634, 40686, -1, 40637, 40634, 40685, -1, 40686, 40630, 40687, -1, 40634, 40630, 40686, -1, 40679, 40688, 40678, -1, 40679, 40689, 40688, -1, 40681, 40690, 40691, -1, 40681, 40691, 40689, -1, 40681, 40679, 40680, -1, 40681, 40689, 40679, -1, 40674, 40690, 40681, -1, 40692, 40676, 40677, -1, 40692, 40675, 40676, -1, 40692, 40674, 40675, -1, 40692, 40693, 40694, -1, 40692, 40677, 40693, -1, 40695, 40692, 40694, -1, 40696, 40692, 40695, -1, 40697, 40692, 40696, -1, 40698, 40692, 40697, -1, 40699, 40692, 40698, -1, 40700, 40692, 40699, -1, 40701, 40702, 40703, -1, 40683, 40701, 40682, -1, 40687, 40704, 40702, -1, 40687, 40683, 40684, -1, 40687, 40700, 40705, -1, 40687, 40705, 40704, -1, 40687, 40702, 40701, -1, 40687, 40701, 40683, -1, 40685, 40687, 40684, -1, 40686, 40687, 40685, -1, 40687, 40692, 40700, -1, 40692, 40690, 40674, -1, 40706, 40707, 40708, -1, 40665, 40706, 40664, -1, 40665, 40707, 40706, -1, 40666, 40707, 40665, -1, 40667, 40709, 40707, -1, 40667, 40707, 40666, -1, 40661, 40709, 40667, -1, 40710, 40662, 40663, -1, 40710, 40660, 40662, -1, 40710, 40661, 40660, -1, 40710, 40711, 40712, -1, 40710, 40663, 40711, -1, 40713, 40710, 40712, -1, 40714, 40710, 40713, -1, 40715, 40710, 40714, -1, 40716, 40710, 40715, -1, 40717, 40710, 40716, -1, 40718, 40710, 40717, -1, 40719, 40710, 40718, -1, 40669, 40720, 40668, -1, 40673, 40721, 40722, -1, 40673, 40723, 40720, -1, 40673, 40722, 40723, -1, 40673, 40669, 40670, -1, 40673, 40720, 40669, -1, 40671, 40673, 40670, -1, 40672, 40673, 40671, -1, 40673, 40710, 40719, -1, 40710, 40709, 40661, -1, 40719, 40721, 40673, -1, 40690, 40574, 40584, -1, 40690, 40692, 40574, -1, 40724, 40725, 40692, -1, 40725, 40726, 40692, -1, 40585, 40727, 40588, -1, 40588, 40727, 40590, -1, 40590, 40727, 40591, -1, 40591, 40727, 40692, -1, 40692, 40727, 40724, -1, 40726, 40728, 40692, -1, 40580, 40729, 40581, -1, 40581, 40729, 40585, -1, 40724, 40729, 40725, -1, 40585, 40729, 40727, -1, 40727, 40729, 40724, -1, 40728, 40730, 40692, -1, 40579, 40731, 40580, -1, 40580, 40731, 40729, -1, 40725, 40731, 40726, -1, 40729, 40731, 40725, -1, 40577, 40732, 40578, -1, 40578, 40732, 40579, -1, 40726, 40732, 40728, -1, 40579, 40732, 40731, -1, 40731, 40732, 40726, -1, 40574, 40733, 40575, -1, 40575, 40733, 40576, -1, 40576, 40733, 40577, -1, 40692, 40733, 40574, -1, 40577, 40733, 40732, -1, 40730, 40733, 40692, -1, 40728, 40733, 40730, -1, 40732, 40733, 40728, -1, 40584, 40734, 40690, -1, 40734, 40735, 40690, -1, 40735, 40736, 40690, -1, 40587, 40737, 40586, -1, 40586, 40737, 40583, -1, 40583, 40737, 40584, -1, 40584, 40737, 40734, -1, 40736, 40738, 40690, -1, 40592, 40739, 40589, -1, 40589, 40739, 40587, -1, 40737, 40739, 40734, -1, 40734, 40739, 40735, -1, 40587, 40739, 40737, -1, 40595, 40740, 40593, -1, 40593, 40740, 40592, -1, 40592, 40740, 40739, -1, 40735, 40740, 40736, -1, 40739, 40740, 40735, -1, 40690, 40741, 40601, -1, 40601, 40741, 40599, -1, 40599, 40741, 40597, -1, 40597, 40741, 40595, -1, 40738, 40741, 40690, -1, 40595, 40741, 40740, -1, 40736, 40741, 40738, -1, 40740, 40741, 40736, -1, 40692, 40630, 40591, -1, 40692, 40687, 40630, -1, 40659, 40690, 40601, -1, 40691, 40690, 40659, -1, 40702, 40645, 40703, -1, 40645, 40655, 40703, -1, 40703, 40654, 40701, -1, 40655, 40654, 40703, -1, 40701, 40643, 40682, -1, 40654, 40643, 40701, -1, 40659, 40629, 40691, -1, 40691, 40629, 40689, -1, 40689, 40627, 40688, -1, 40629, 40627, 40689, -1, 40688, 40626, 40678, -1, 40627, 40626, 40688, -1, 40702, 40704, 40645, -1, 40645, 40704, 40628, -1, 40674, 40616, 40614, -1, 40674, 40681, 40616, -1, 40742, 40743, 40704, -1, 40619, 40744, 40618, -1, 40618, 40744, 40617, -1, 40617, 40744, 40615, -1, 40615, 40744, 40704, -1, 40704, 40744, 40742, -1, 40743, 40745, 40704, -1, 40621, 40746, 40620, -1, 40620, 40746, 40619, -1, 40619, 40746, 40744, -1, 40744, 40746, 40742, -1, 40742, 40746, 40743, -1, 40628, 40747, 40625, -1, 40625, 40747, 40623, -1, 40623, 40747, 40621, -1, 40704, 40747, 40628, -1, 40621, 40747, 40746, -1, 40743, 40747, 40745, -1, 40746, 40747, 40743, -1, 40745, 40747, 40704, -1, 40677, 40604, 40603, -1, 40693, 40603, 40606, -1, 40693, 40677, 40603, -1, 40694, 40606, 40608, -1, 40694, 40693, 40606, -1, 40695, 40608, 40607, -1, 40695, 40694, 40608, -1, 40696, 40607, 40609, -1, 40696, 40695, 40607, -1, 40697, 40609, 40611, -1, 40697, 40696, 40609, -1, 40698, 40611, 40610, -1, 40698, 40697, 40611, -1, 40699, 40610, 40612, -1, 40699, 40698, 40610, -1, 40700, 40699, 40612, -1, 40705, 40612, 40613, -1, 40705, 40700, 40612, -1, 40704, 40613, 40615, -1, 40704, 40705, 40613, -1, 40709, 40533, 40549, -1, 40709, 40710, 40533, -1, 40748, 40749, 40710, -1, 40749, 40750, 40710, -1, 40543, 40751, 40544, -1, 40544, 40751, 40545, -1, 40545, 40751, 40546, -1, 40546, 40751, 40710, -1, 40710, 40751, 40748, -1, 40750, 40752, 40710, -1, 40540, 40753, 40541, -1, 40541, 40753, 40543, -1, 40748, 40753, 40749, -1, 40543, 40753, 40751, -1, 40751, 40753, 40748, -1, 40752, 40754, 40710, -1, 40539, 40755, 40540, -1, 40540, 40755, 40753, -1, 40749, 40755, 40750, -1, 40753, 40755, 40749, -1, 40537, 40756, 40538, -1, 40538, 40756, 40539, -1, 40750, 40756, 40752, -1, 40539, 40756, 40755, -1, 40755, 40756, 40750, -1, 40533, 40757, 40534, -1, 40534, 40757, 40536, -1, 40536, 40757, 40537, -1, 40710, 40757, 40533, -1, 40537, 40757, 40756, -1, 40754, 40757, 40710, -1, 40752, 40757, 40754, -1, 40756, 40757, 40752, -1, 40758, 40759, 40709, -1, 40759, 40760, 40709, -1, 40549, 40761, 40709, -1, 40551, 40761, 40550, -1, 40550, 40761, 40548, -1, 40548, 40761, 40549, -1, 40709, 40761, 40758, -1, 40760, 40762, 40709, -1, 40553, 40763, 40552, -1, 40552, 40763, 40551, -1, 40761, 40763, 40758, -1, 40551, 40763, 40761, -1, 40758, 40763, 40759, -1, 40555, 40764, 40554, -1, 40554, 40764, 40553, -1, 40553, 40764, 40763, -1, 40759, 40764, 40760, -1, 40763, 40764, 40759, -1, 40709, 40765, 40558, -1, 40558, 40765, 40557, -1, 40557, 40765, 40556, -1, 40556, 40765, 40555, -1, 40555, 40765, 40764, -1, 40762, 40765, 40709, -1, 40760, 40765, 40762, -1, 40764, 40765, 40760, -1, 40710, 40658, 40546, -1, 40710, 40673, 40658, -1, 40707, 40558, 40572, -1, 40707, 40709, 40558, -1, 40652, 40651, 40722, -1, 40723, 40651, 40720, -1, 40722, 40651, 40723, -1, 40720, 40650, 40668, -1, 40651, 40650, 40720, -1, 40650, 40649, 40668, -1, 40572, 40573, 40707, -1, 40707, 40573, 40708, -1, 40708, 40600, 40706, -1, 40573, 40600, 40708, -1, 40706, 40598, 40664, -1, 40600, 40598, 40706, -1, 40722, 40653, 40652, -1, 40722, 40721, 40653, -1, 40661, 40582, 40570, -1, 40661, 40667, 40582, -1, 40632, 40766, 40721, -1, 40766, 40767, 40721, -1, 40635, 40768, 40633, -1, 40633, 40768, 40631, -1, 40631, 40768, 40632, -1, 40632, 40768, 40766, -1, 40721, 40769, 40653, -1, 40767, 40769, 40721, -1, 40638, 40770, 40636, -1, 40636, 40770, 40635, -1, 40635, 40770, 40768, -1, 40768, 40770, 40766, -1, 40766, 40770, 40767, -1, 40653, 40771, 40642, -1, 40642, 40771, 40640, -1, 40640, 40771, 40638, -1, 40638, 40771, 40770, -1, 40769, 40771, 40653, -1, 40770, 40771, 40767, -1, 40767, 40771, 40769, -1, 40711, 40663, 40561, -1, 40711, 40561, 40560, -1, 40712, 40560, 40563, -1, 40712, 40711, 40560, -1, 40713, 40563, 40564, -1, 40713, 40712, 40563, -1, 40714, 40564, 40565, -1, 40714, 40713, 40564, -1, 40715, 40565, 40566, -1, 40715, 40714, 40565, -1, 40716, 40566, 40568, -1, 40716, 40715, 40566, -1, 40717, 40568, 40569, -1, 40717, 40716, 40568, -1, 40718, 40569, 40567, -1, 40718, 40717, 40569, -1, 40719, 40567, 40571, -1, 40719, 40718, 40567, -1, 40721, 40571, 40632, -1, 40721, 40719, 40571, -1, 38477, 38476, 40772, -1, 40772, 38476, 40773, -1, 40773, 40774, 40775, -1, 38476, 40774, 40773, -1, 40775, 40776, 40777, -1, 40774, 40776, 40775, -1, 40776, 40778, 40777, -1, 40779, 40780, 40778, -1, 40781, 40780, 40779, -1, 40780, 40777, 40778, -1, 39173, 39174, 40782, -1, 40782, 40783, 40784, -1, 39174, 40783, 40782, -1, 40783, 40785, 40784, -1, 40784, 40786, 40787, -1, 40785, 40786, 40784, -1, 40787, 40788, 40789, -1, 40786, 40788, 40787, -1, 40789, 40790, 40791, -1, 40791, 40790, 40792, -1, 40788, 40790, 40789, -1, 40792, 40547, 40535, -1, 40790, 40547, 40792, -1, 40793, 39173, 40794, -1, 40795, 39173, 40793, -1, 40796, 39173, 40795, -1, 40797, 39173, 40796, -1, 40798, 39173, 40797, -1, 40799, 39173, 40798, -1, 40800, 39173, 40799, -1, 40801, 40802, 40803, -1, 40804, 39173, 40800, -1, 40805, 40804, 40806, -1, 40803, 40807, 40801, -1, 40805, 40806, 40808, -1, 39173, 40782, 40794, -1, 40794, 40782, 40809, -1, 40805, 40810, 40801, -1, 40801, 40810, 40802, -1, 40807, 40811, 40801, -1, 40805, 40812, 40810, -1, 40811, 40813, 40801, -1, 40805, 40808, 40812, -1, 40814, 40815, 40813, -1, 40813, 40815, 40801, -1, 40814, 40816, 40815, -1, 40816, 40817, 40815, -1, 40817, 40818, 40815, -1, 40818, 40819, 40815, -1, 40815, 40820, 40782, -1, 40819, 40820, 40815, -1, 40820, 40821, 40782, -1, 40821, 40809, 40782, -1, 40822, 40804, 40823, -1, 40824, 40804, 40822, -1, 40825, 40804, 40824, -1, 40826, 40804, 40825, -1, 40827, 40804, 40826, -1, 40806, 40804, 40827, -1, 40804, 40828, 40823, -1, 40804, 40800, 40828, -1, 40829, 40830, 40808, -1, 40829, 40808, 40806, -1, 40831, 40832, 40833, -1, 40834, 40835, 40836, -1, 40836, 40835, 40831, -1, 40831, 40835, 40832, -1, 40832, 40837, 40829, -1, 40835, 40837, 40832, -1, 40838, 40839, 40840, -1, 40840, 40839, 40841, -1, 40841, 40839, 40842, -1, 40842, 40839, 40843, -1, 40843, 40839, 40844, -1, 40844, 40845, 40837, -1, 40837, 40845, 40829, -1, 40839, 40845, 40844, -1, 40846, 40847, 40848, -1, 40847, 40849, 40850, -1, 40850, 40849, 40851, -1, 40846, 40849, 40847, -1, 40830, 40852, 40846, -1, 40846, 40852, 40849, -1, 40830, 40853, 40852, -1, 40829, 40854, 40830, -1, 40845, 40854, 40829, -1, 40830, 40854, 40853, -1, 40853, 40855, 40856, -1, 40857, 40858, 40854, -1, 40854, 40858, 40853, -1, 40853, 40859, 40855, -1, 40858, 40860, 40853, -1, 40853, 40860, 40859, -1, 40813, 40811, 40852, -1, 40852, 40811, 40849, -1, 40849, 40807, 40851, -1, 40811, 40807, 40849, -1, 40851, 40803, 40850, -1, 40807, 40803, 40851, -1, 40850, 40802, 40847, -1, 40803, 40802, 40850, -1, 40847, 40810, 40848, -1, 40802, 40810, 40847, -1, 40848, 40812, 40846, -1, 40810, 40812, 40848, -1, 40846, 40808, 40830, -1, 40812, 40808, 40846, -1, 40829, 40827, 40832, -1, 40806, 40827, 40829, -1, 40832, 40826, 40833, -1, 40827, 40826, 40832, -1, 40833, 40825, 40831, -1, 40826, 40825, 40833, -1, 40831, 40824, 40836, -1, 40825, 40824, 40831, -1, 40836, 40822, 40834, -1, 40824, 40822, 40836, -1, 40834, 40823, 40835, -1, 40822, 40823, 40834, -1, 40835, 40828, 40837, -1, 40823, 40828, 40835, -1, 40852, 40853, 40814, -1, 40852, 40814, 40813, -1, 40844, 40837, 40828, -1, 40844, 40828, 40800, -1, 40854, 40809, 40857, -1, 40857, 40821, 40858, -1, 40809, 40821, 40857, -1, 40858, 40820, 40860, -1, 40821, 40820, 40858, -1, 40860, 40819, 40859, -1, 40820, 40819, 40860, -1, 40859, 40818, 40855, -1, 40819, 40818, 40859, -1, 40855, 40817, 40856, -1, 40818, 40817, 40855, -1, 40856, 40816, 40853, -1, 40817, 40816, 40856, -1, 40816, 40814, 40853, -1, 40844, 40799, 40843, -1, 40800, 40799, 40844, -1, 40843, 40798, 40842, -1, 40799, 40798, 40843, -1, 40842, 40797, 40841, -1, 40798, 40797, 40842, -1, 40841, 40796, 40840, -1, 40797, 40796, 40841, -1, 40838, 40795, 40839, -1, 40840, 40795, 40838, -1, 40796, 40795, 40840, -1, 40839, 40793, 40845, -1, 40795, 40793, 40839, -1, 40793, 40794, 40845, -1, 40854, 40845, 40794, -1, 40854, 40794, 40809, -1, 40781, 40779, 40861, -1, 40861, 40862, 40863, -1, 40779, 40862, 40861, -1, 40863, 40864, 40865, -1, 40862, 40864, 40863, -1, 40865, 40866, 40867, -1, 40864, 40866, 40865, -1, 40867, 40868, 40869, -1, 40869, 40868, 40870, -1, 40866, 40868, 40867, -1, 40870, 40871, 40872, -1, 40868, 40871, 40870, -1, 40873, 40872, 40871, -1, 40874, 40872, 40873, -1, 33672, 33616, 40875, -1, 40875, 33616, 40876, -1, 40876, 40877, 40878, -1, 33616, 40877, 40876, -1, 40878, 40879, 40880, -1, 40877, 40879, 40878, -1, 40880, 40881, 40882, -1, 40879, 40881, 40880, -1, 40883, 40884, 40885, -1, 40885, 40886, 40883, -1, 40887, 40888, 40883, -1, 40882, 40888, 40887, -1, 40883, 40888, 40884, -1, 40886, 40889, 40883, -1, 40882, 40890, 40888, -1, 40889, 40891, 40883, -1, 40882, 40892, 40890, -1, 40891, 40893, 40883, -1, 40893, 40894, 40883, -1, 40882, 40895, 40892, -1, 40894, 40896, 40883, -1, 40896, 40897, 40883, -1, 40898, 40899, 40900, -1, 40901, 40899, 40898, -1, 40902, 40899, 40901, -1, 40903, 40899, 40902, -1, 40904, 40899, 40903, -1, 40905, 40899, 40904, -1, 40906, 40899, 40905, -1, 40907, 40899, 40906, -1, 40908, 40899, 40907, -1, 40909, 40899, 40908, -1, 40909, 40910, 40911, -1, 40909, 40912, 40899, -1, 40911, 40912, 40909, -1, 40909, 40913, 40910, -1, 40912, 40914, 40899, -1, 40909, 40915, 40913, -1, 40914, 40916, 40899, -1, 40909, 40917, 40915, -1, 40916, 40918, 40899, -1, 40918, 40919, 40899, -1, 40909, 40920, 40917, -1, 40919, 40921, 40899, -1, 40921, 40922, 40899, -1, 40923, 40924, 40925, -1, 40926, 40927, 40923, -1, 40924, 40928, 40929, -1, 40923, 40930, 40924, -1, 40927, 40930, 40923, -1, 40924, 40931, 40928, -1, 40930, 40931, 40924, -1, 40928, 40931, 40932, -1, 40933, 40931, 40930, -1, 40933, 40934, 40931, -1, 40935, 40881, 40936, -1, 40881, 40937, 40936, -1, 40938, 40937, 40939, -1, 40936, 40937, 40938, -1, 40940, 40941, 40942, -1, 40939, 40941, 40940, -1, 40937, 40941, 40939, -1, 40941, 40943, 40942, -1, 40941, 40944, 40943, -1, 40945, 40946, 40947, -1, 40948, 40946, 40945, -1, 40949, 40946, 40948, -1, 40950, 40951, 40949, -1, 40949, 40951, 40946, -1, 40952, 40953, 40950, -1, 40950, 40953, 40951, -1, 40954, 40955, 40952, -1, 40944, 40955, 40954, -1, 40952, 40955, 40953, -1, 40944, 40956, 40955, -1, 40941, 40956, 40944, -1, 40941, 40957, 40956, -1, 40933, 40958, 40934, -1, 40941, 40959, 40957, -1, 40958, 40960, 40934, -1, 40961, 40960, 40958, -1, 40962, 40960, 40961, -1, 40963, 40960, 40962, -1, 40964, 40960, 40963, -1, 40965, 40960, 40964, -1, 40965, 40966, 40960, -1, 40967, 40966, 40965, -1, 40967, 40968, 40966, -1, 40969, 40968, 40967, -1, 40969, 40970, 40968, -1, 40971, 40972, 40973, -1, 40974, 40972, 40971, -1, 40975, 40972, 40974, -1, 40976, 40972, 40975, -1, 40977, 40972, 40976, -1, 40978, 40972, 40977, -1, 40979, 40972, 40978, -1, 40979, 40980, 40972, -1, 40981, 40980, 40979, -1, 40981, 40982, 40980, -1, 40983, 40982, 40981, -1, 40983, 40984, 40982, -1, 40985, 40984, 40983, -1, 40985, 40986, 40984, -1, 40987, 40988, 40989, -1, 40990, 40988, 40987, -1, 40991, 40988, 40990, -1, 40992, 40988, 40991, -1, 40993, 40988, 40992, -1, 40994, 40988, 40993, -1, 40995, 40988, 40994, -1, 40996, 40988, 40995, -1, 40997, 40988, 40996, -1, 40998, 40988, 40997, -1, 40986, 40988, 40998, -1, 40909, 40947, 40946, -1, 40909, 40946, 40920, -1, 40935, 40895, 40881, -1, 40972, 40899, 40922, -1, 40972, 40922, 40973, -1, 40882, 40881, 40895, -1, 40941, 40988, 40986, -1, 40941, 40986, 40985, -1, 40941, 40985, 40999, -1, 40941, 40999, 40970, -1, 40941, 40970, 40959, -1, 40959, 40970, 40969, -1, 40988, 40883, 40989, -1, 40989, 40883, 40897, -1, 40893, 41000, 41001, -1, 41000, 41002, 41001, -1, 41002, 41003, 41001, -1, 40886, 41004, 40889, -1, 40889, 41004, 40891, -1, 40891, 41004, 40893, -1, 40893, 41004, 41000, -1, 41003, 41005, 41001, -1, 40884, 41006, 40885, -1, 40885, 41006, 40886, -1, 41004, 41006, 41000, -1, 41000, 41006, 41002, -1, 40886, 41006, 41004, -1, 40888, 41007, 40884, -1, 40884, 41007, 41006, -1, 41002, 41007, 41003, -1, 41006, 41007, 41002, -1, 40895, 41008, 40892, -1, 40892, 41008, 40890, -1, 40890, 41008, 40888, -1, 41001, 41008, 40895, -1, 41003, 41008, 41005, -1, 41005, 41008, 41001, -1, 40888, 41008, 41007, -1, 41007, 41008, 41003, -1, 40918, 41009, 41010, -1, 41009, 41011, 41010, -1, 41011, 41012, 41010, -1, 40912, 41013, 40914, -1, 40914, 41013, 40916, -1, 40916, 41013, 40918, -1, 40918, 41013, 41009, -1, 41012, 41014, 41010, -1, 40910, 41015, 40911, -1, 40911, 41015, 40912, -1, 41013, 41015, 41009, -1, 41009, 41015, 41011, -1, 40912, 41015, 41013, -1, 40913, 41016, 40910, -1, 40910, 41016, 41015, -1, 41011, 41016, 41012, -1, 41015, 41016, 41011, -1, 40920, 41017, 40917, -1, 40917, 41017, 40915, -1, 40915, 41017, 40913, -1, 41010, 41017, 40920, -1, 41012, 41017, 41014, -1, 41014, 41017, 41010, -1, 40913, 41017, 41016, -1, 41016, 41017, 41012, -1, 41018, 40934, 40960, -1, 41018, 41019, 40934, -1, 41020, 41021, 41022, -1, 41018, 41023, 41020, -1, 41018, 41022, 41024, -1, 41018, 41020, 41022, -1, 41025, 41026, 41027, -1, 41028, 41029, 41025, -1, 41028, 41030, 41029, -1, 41028, 41027, 41031, -1, 41028, 41025, 41027, -1, 41032, 41028, 41031, -1, 41019, 41018, 41024, -1, 41010, 41033, 41019, -1, 41010, 41034, 41033, -1, 41010, 41035, 41034, -1, 41010, 41036, 41035, -1, 41010, 41037, 41036, -1, 41010, 41038, 41037, -1, 41010, 41039, 41038, -1, 41010, 41040, 41039, -1, 41010, 41041, 41040, -1, 41010, 41042, 41041, -1, 41024, 41010, 41019, -1, 41010, 41028, 41032, -1, 41010, 41032, 41042, -1, 41042, 41032, 40933, -1, 41042, 40933, 40930, -1, 41041, 40930, 40927, -1, 41041, 41042, 40930, -1, 41040, 40927, 40926, -1, 41040, 41041, 40927, -1, 41039, 40926, 40923, -1, 41039, 41040, 40926, -1, 41038, 40923, 40925, -1, 41038, 41039, 40923, -1, 41037, 40925, 40924, -1, 41037, 41038, 40925, -1, 41036, 40924, 40929, -1, 41036, 41037, 40924, -1, 41035, 40929, 40928, -1, 41035, 41036, 40929, -1, 41034, 40928, 40932, -1, 41034, 41035, 40928, -1, 41033, 40932, 40931, -1, 41033, 41034, 40932, -1, 41019, 40931, 40934, -1, 41019, 41033, 40931, -1, 41018, 40960, 41023, -1, 41023, 40966, 41020, -1, 40960, 40966, 41023, -1, 41020, 40968, 41021, -1, 40966, 40968, 41020, -1, 41021, 40970, 41022, -1, 40968, 40970, 41021, -1, 40970, 40999, 41022, -1, 41032, 41031, 40933, -1, 40933, 41031, 40958, -1, 41024, 40999, 40985, -1, 41024, 41022, 40999, -1, 40959, 41043, 41031, -1, 41043, 41044, 41031, -1, 40965, 41045, 40967, -1, 40967, 41045, 40969, -1, 40969, 41045, 40959, -1, 40959, 41045, 41043, -1, 41044, 41046, 41031, -1, 40963, 41047, 40964, -1, 40964, 41047, 40965, -1, 40965, 41047, 41045, -1, 41043, 41047, 41044, -1, 41045, 41047, 41043, -1, 40958, 41048, 40961, -1, 40961, 41048, 40962, -1, 40962, 41048, 40963, -1, 41031, 41048, 40958, -1, 40963, 41048, 41047, -1, 41044, 41048, 41046, -1, 41047, 41048, 41044, -1, 41046, 41048, 41031, -1, 40985, 41049, 41024, -1, 41049, 41050, 41024, -1, 40979, 41051, 40981, -1, 40981, 41051, 40983, -1, 40983, 41051, 40985, -1, 40985, 41051, 41049, -1, 41050, 41052, 41024, -1, 40977, 41053, 40978, -1, 40978, 41053, 40979, -1, 40979, 41053, 41051, -1, 41051, 41053, 41049, -1, 41049, 41053, 41050, -1, 41024, 41054, 40973, -1, 41052, 41054, 41024, -1, 40975, 41055, 40976, -1, 40976, 41055, 40977, -1, 40977, 41055, 41053, -1, 41050, 41055, 41052, -1, 41053, 41055, 41050, -1, 40973, 41056, 40971, -1, 40971, 41056, 40974, -1, 40974, 41056, 40975, -1, 40975, 41056, 41055, -1, 41054, 41056, 40973, -1, 41052, 41056, 41054, -1, 41055, 41056, 41052, -1, 41031, 40957, 40959, -1, 41031, 41027, 40957, -1, 40922, 41024, 40973, -1, 41010, 41024, 40922, -1, 40946, 40951, 41028, -1, 41028, 40951, 41030, -1, 41029, 40953, 41025, -1, 41030, 40953, 41029, -1, 40951, 40953, 41030, -1, 41025, 40955, 41026, -1, 40953, 40955, 41025, -1, 41026, 40956, 41027, -1, 40955, 40956, 41026, -1, 40956, 40957, 41027, -1, 40922, 40921, 41010, -1, 40921, 40919, 41010, -1, 40919, 40918, 41010, -1, 41028, 41010, 40946, -1, 40946, 41010, 40920, -1, 41057, 41001, 40935, -1, 40935, 41001, 40895, -1, 41058, 41059, 41060, -1, 41061, 41058, 41060, -1, 41062, 41060, 41063, -1, 41062, 41061, 41060, -1, 41064, 41065, 41066, -1, 41067, 41064, 41066, -1, 41057, 41068, 41067, -1, 41057, 41066, 41069, -1, 41057, 41067, 41066, -1, 41070, 41062, 41063, -1, 41001, 41071, 41070, -1, 41001, 41072, 41071, -1, 41001, 41073, 41072, -1, 41001, 41074, 41073, -1, 41001, 41075, 41074, -1, 41001, 41076, 41075, -1, 41001, 41077, 41076, -1, 41001, 41078, 41077, -1, 41001, 41079, 41078, -1, 41001, 41080, 41079, -1, 41001, 41081, 41080, -1, 41063, 41001, 41070, -1, 41001, 41057, 41081, -1, 41069, 41081, 41057, -1, 40897, 40896, 41001, -1, 40896, 40894, 41001, -1, 40894, 40893, 41001, -1, 41057, 40936, 41068, -1, 40935, 40936, 41057, -1, 41068, 40938, 41067, -1, 40936, 40938, 41068, -1, 41067, 40939, 41064, -1, 40938, 40939, 41067, -1, 41064, 40940, 41065, -1, 40939, 40940, 41064, -1, 41065, 40942, 41066, -1, 40940, 40942, 41065, -1, 41001, 41063, 40897, -1, 40897, 41063, 40989, -1, 41069, 40942, 40943, -1, 41069, 41066, 40942, -1, 41082, 41083, 41063, -1, 40995, 41084, 40996, -1, 40996, 41084, 40997, -1, 40997, 41084, 40998, -1, 40998, 41084, 41063, -1, 41063, 41084, 41082, -1, 41083, 41085, 41063, -1, 40993, 41086, 40994, -1, 40994, 41086, 40995, -1, 40995, 41086, 41084, -1, 41084, 41086, 41082, -1, 41082, 41086, 41083, -1, 41085, 41087, 41063, -1, 40991, 41088, 40992, -1, 40992, 41088, 40993, -1, 40993, 41088, 41086, -1, 41086, 41088, 41083, -1, 41083, 41088, 41085, -1, 40989, 41089, 40987, -1, 40987, 41089, 40990, -1, 40990, 41089, 40991, -1, 41063, 41089, 40989, -1, 41087, 41089, 41063, -1, 40991, 41089, 41088, -1, 41085, 41089, 41087, -1, 41088, 41089, 41085, -1, 40943, 41090, 41069, -1, 41090, 41091, 41069, -1, 40952, 41092, 40954, -1, 40954, 41092, 40944, -1, 40944, 41092, 40943, -1, 40943, 41092, 41090, -1, 41069, 41093, 40947, -1, 41091, 41093, 41069, -1, 40949, 41094, 40950, -1, 40950, 41094, 40952, -1, 40952, 41094, 41092, -1, 41092, 41094, 41090, -1, 41090, 41094, 41091, -1, 40947, 41095, 40945, -1, 40945, 41095, 40948, -1, 40948, 41095, 40949, -1, 40949, 41095, 41094, -1, 41094, 41095, 41091, -1, 41093, 41095, 40947, -1, 41091, 41095, 41093, -1, 41063, 40986, 40998, -1, 41063, 41060, 40986, -1, 40909, 41069, 40947, -1, 41081, 41069, 40909, -1, 40972, 40980, 41062, -1, 41061, 40980, 41058, -1, 41062, 40980, 41061, -1, 41058, 40982, 41059, -1, 40980, 40982, 41058, -1, 41059, 40984, 41060, -1, 40982, 40984, 41059, -1, 40984, 40986, 41060, -1, 41081, 40909, 40908, -1, 41080, 40908, 40907, -1, 41080, 41081, 40908, -1, 41079, 40907, 40906, -1, 41079, 41080, 40907, -1, 41078, 40906, 40905, -1, 41078, 41079, 40906, -1, 41077, 40905, 40904, -1, 41077, 41078, 40905, -1, 41076, 40904, 40903, -1, 41076, 41077, 40904, -1, 41075, 40903, 40902, -1, 41075, 41076, 40903, -1, 41074, 41075, 40902, -1, 41073, 40902, 40901, -1, 41073, 41074, 40902, -1, 41072, 40901, 40898, -1, 41072, 41073, 40901, -1, 41071, 40900, 40899, -1, 41071, 40898, 40900, -1, 41071, 41072, 40898, -1, 41070, 41071, 40899, -1, 41062, 40899, 40972, -1, 41062, 41070, 40899, -1, 41096, 41097, 41098, -1, 41099, 41097, 41096, -1, 41098, 41100, 41101, -1, 41101, 41100, 41102, -1, 41097, 41100, 41098, -1, 41102, 38426, 38425, -1, 41100, 38426, 41102, -1, 41099, 41103, 41104, -1, 41096, 41103, 41099, -1, 41103, 41105, 41104, -1, 40883, 40988, 41106, -1, 40988, 41107, 41106, -1, 41106, 41108, 41109, -1, 41107, 41108, 41106, -1, 41109, 41110, 41111, -1, 41108, 41110, 41109, -1, 41110, 41112, 41111, -1, 41111, 41113, 41114, -1, 41112, 41113, 41111, -1, 41114, 41115, 40805, -1, 41113, 41115, 41114, -1, 41115, 40804, 40805, -1, 40874, 40873, 41116, -1, 41116, 41117, 41118, -1, 40873, 41117, 41116, -1, 41118, 41119, 41120, -1, 41120, 41119, 41121, -1, 41117, 41119, 41118, -1, 41121, 41122, 41123, -1, 41119, 41122, 41121, -1, 41123, 41124, 41125, -1, 41122, 41124, 41123, -1, 41125, 41104, 41126, -1, 41126, 41104, 41105, -1, 41124, 41104, 41125, -1, 40877, 33616, 39130, -1, 41127, 39130, 39134, -1, 41127, 40879, 39130, -1, 41128, 40879, 41127, -1, 40881, 40879, 41128, -1, 41129, 40879, 40877, -1, 41129, 40877, 39130, -1, 41129, 39130, 40879, -1, 40937, 41130, 41131, -1, 40937, 41131, 40941, -1, 41128, 41132, 41130, -1, 41128, 40937, 40881, -1, 41128, 41130, 40937, -1, 41127, 41133, 41132, -1, 41127, 41132, 41128, -1, 39134, 39131, 41133, -1, 39134, 41133, 41127, -1, 39131, 39139, 41134, -1, 41133, 41134, 41135, -1, 41133, 39131, 41134, -1, 41132, 41135, 41136, -1, 41132, 41133, 41135, -1, 41130, 41136, 41137, -1, 41130, 41132, 41136, -1, 41131, 41137, 40988, -1, 41131, 41130, 41137, -1, 40941, 41131, 40988, -1, 41107, 41136, 41135, -1, 41107, 41137, 41136, -1, 41107, 40988, 41137, -1, 41138, 39158, 39159, -1, 40804, 41115, 41139, -1, 41140, 41134, 39139, -1, 41140, 39139, 39156, -1, 41141, 41135, 41134, -1, 41141, 41134, 41140, -1, 41141, 41107, 41135, -1, 41142, 41108, 41107, -1, 41142, 41107, 41141, -1, 41143, 39156, 39155, -1, 41143, 41140, 39156, -1, 41144, 41140, 41143, -1, 41144, 41141, 41140, -1, 41145, 39155, 39157, -1, 41145, 41143, 39155, -1, 41146, 41142, 41141, -1, 41146, 41108, 41142, -1, 41146, 41141, 41144, -1, 41147, 41144, 41143, -1, 41147, 41143, 41145, -1, 41148, 41112, 41110, -1, 41148, 41110, 41108, -1, 41148, 41108, 41146, -1, 41149, 39157, 39158, -1, 41149, 41145, 39157, -1, 41150, 41146, 41144, -1, 41150, 41144, 41147, -1, 41151, 41138, 41139, -1, 41151, 41147, 41145, -1, 41151, 41149, 39158, -1, 41151, 39158, 41138, -1, 41151, 41145, 41149, -1, 41152, 41113, 41112, -1, 41152, 41112, 41148, -1, 41152, 41146, 41150, -1, 41152, 41148, 41146, -1, 41153, 41115, 41113, -1, 41153, 41113, 41152, -1, 41153, 41147, 41151, -1, 41153, 41139, 41115, -1, 41153, 41151, 41139, -1, 41153, 41150, 41147, -1, 41153, 41152, 41150, -1, 41138, 39159, 39162, -1, 41138, 39162, 39170, -1, 41139, 39170, 39171, -1, 41139, 39171, 39173, -1, 41139, 41138, 39170, -1, 40804, 41139, 39173, -1, 40783, 39174, 39172, -1, 41154, 39168, 39138, -1, 41155, 39168, 41154, -1, 41156, 39168, 41155, -1, 41157, 39169, 39163, -1, 41157, 39163, 39164, -1, 41158, 39172, 39169, -1, 41158, 39169, 41157, -1, 41159, 40785, 40783, -1, 41159, 40783, 39172, -1, 41159, 39172, 41158, -1, 41160, 39164, 39165, -1, 41160, 41157, 39164, -1, 41161, 41157, 41160, -1, 41161, 41158, 41157, -1, 41162, 40786, 40785, -1, 41162, 41159, 41158, -1, 41162, 40785, 41159, -1, 41162, 41158, 41161, -1, 41163, 39165, 39166, -1, 41163, 41160, 39165, -1, 41164, 41161, 41160, -1, 41164, 41160, 41163, -1, 41165, 41161, 41164, -1, 41165, 41162, 41161, -1, 41166, 39166, 39167, -1, 41166, 39167, 39168, -1, 41166, 41163, 39166, -1, 41167, 41166, 39168, -1, 41167, 41164, 41163, -1, 41167, 39168, 41156, -1, 41167, 41163, 41166, -1, 41168, 40790, 40788, -1, 41168, 40788, 40786, -1, 41168, 40786, 41162, -1, 41168, 41162, 41165, -1, 41169, 41156, 41170, -1, 41169, 41165, 41164, -1, 41169, 41167, 41156, -1, 41169, 41164, 41167, -1, 41171, 41170, 40547, -1, 41171, 40547, 40790, -1, 41171, 41169, 41170, -1, 41171, 40790, 41168, -1, 41171, 41168, 41165, -1, 41171, 41165, 41169, -1, 41154, 39138, 38974, -1, 41154, 38974, 41172, -1, 41155, 41172, 41173, -1, 41155, 41154, 41172, -1, 41156, 41173, 41174, -1, 41156, 41155, 41173, -1, 41170, 41174, 41175, -1, 41170, 41156, 41174, -1, 40547, 41175, 40644, -1, 40547, 41170, 41175, -1, 41176, 41175, 41174, -1, 41176, 40644, 41175, -1, 41176, 41177, 40527, -1, 41176, 40527, 40656, -1, 41176, 40656, 40644, -1, 41178, 41174, 41173, -1, 41178, 41179, 41177, -1, 41178, 41177, 41176, -1, 41178, 41176, 41174, -1, 41180, 41172, 38974, -1, 41180, 41173, 41172, -1, 41180, 38974, 38978, -1, 41180, 38978, 41179, -1, 41180, 41178, 41173, -1, 41180, 41179, 41178, -1, 38976, 40531, 40529, -1, 38976, 34367, 40531, -1, 41177, 40529, 40527, -1, 41179, 38976, 40529, -1, 41179, 40529, 41177, -1, 38978, 38976, 41179, -1, 41181, 41182, 41183, -1, 41184, 41182, 41181, -1, 41182, 41185, 41183, -1, 41183, 41186, 41187, -1, 41185, 41186, 41183, -1, 41186, 41188, 41187, -1, 41187, 41189, 33505, -1, 41188, 41189, 41187, -1, 41189, 33501, 33505, -1, 41190, 41191, 41192, -1, 41191, 41184, 41181, -1, 41190, 41184, 41191, -1, 41193, 41190, 41192, -1, 41193, 41192, 41194, -1, 41195, 41194, 41196, -1, 41195, 41193, 41194, -1, 41197, 41196, 41198, -1, 41197, 41195, 41196, -1, 41199, 41200, 41201, -1, 41199, 41202, 41200, -1, 41203, 41204, 41205, -1, 41205, 41204, 41206, -1, 41206, 41204, 41207, -1, 41207, 41204, 41208, -1, 41209, 41210, 41211, -1, 41212, 41210, 41213, -1, 41213, 41210, 41214, -1, 41214, 41210, 41215, -1, 41211, 41210, 41212, -1, 41216, 41217, 41208, -1, 41204, 41218, 41208, -1, 41208, 41218, 41216, -1, 41215, 41197, 41198, -1, 41210, 41197, 41215, -1, 41217, 41219, 41208, -1, 41204, 41220, 41218, -1, 41204, 41221, 41220, -1, 41204, 41222, 41221, -1, 41223, 41224, 41204, -1, 41204, 41224, 41222, -1, 41225, 41226, 41223, -1, 41226, 41227, 41223, -1, 41223, 41228, 41224, -1, 41219, 41229, 41208, -1, 41227, 41230, 41223, -1, 41223, 41231, 41228, -1, 41230, 41232, 41223, -1, 41223, 41233, 41231, -1, 41223, 41209, 41233, -1, 41232, 41209, 41223, -1, 41209, 41234, 41233, -1, 41209, 41235, 41234, -1, 41219, 41236, 41229, -1, 41209, 41211, 41235, -1, 41229, 41237, 41238, -1, 41238, 41237, 41239, -1, 41239, 41237, 41201, -1, 41236, 41237, 41229, -1, 41237, 41240, 41201, -1, 41240, 41199, 41201, -1, 41241, 41242, 41243, -1, 41244, 41216, 41218, -1, 41245, 41246, 41247, -1, 41248, 41219, 41217, -1, 41248, 41217, 41216, -1, 41248, 41249, 41219, -1, 41250, 41251, 41249, -1, 41250, 41249, 41248, -1, 41252, 41243, 41253, -1, 41252, 41253, 41251, -1, 41252, 41251, 41250, -1, 41254, 41246, 41241, -1, 41254, 41243, 41252, -1, 41254, 41241, 41243, -1, 41255, 41244, 41256, -1, 41255, 41256, 41257, -1, 41255, 41257, 41247, -1, 41255, 41250, 41248, -1, 41255, 41254, 41252, -1, 41255, 41246, 41254, -1, 41255, 41216, 41244, -1, 41255, 41248, 41216, -1, 41255, 41247, 41246, -1, 41255, 41252, 41250, -1, 41258, 41259, 41260, -1, 41261, 41231, 41233, -1, 41262, 41263, 41264, -1, 41265, 41224, 41228, -1, 41265, 41228, 41231, -1, 41265, 41266, 41224, -1, 41267, 41268, 41266, -1, 41267, 41266, 41265, -1, 41269, 41270, 41268, -1, 41269, 41268, 41267, -1, 41271, 41263, 41258, -1, 41271, 41260, 41270, -1, 41271, 41258, 41260, -1, 41271, 41270, 41269, -1, 41272, 41261, 41273, -1, 41272, 41273, 41274, -1, 41272, 41274, 41264, -1, 41272, 41267, 41265, -1, 41272, 41263, 41271, -1, 41272, 41231, 41261, -1, 41272, 41265, 41231, -1, 41272, 41271, 41269, -1, 41272, 41264, 41263, -1, 41272, 41269, 41267, -1, 41275, 41276, 41277, -1, 41275, 41277, 41278, -1, 41279, 41278, 41280, -1, 41279, 41275, 41278, -1, 41281, 41280, 41282, -1, 41281, 41279, 41280, -1, 41202, 41282, 41200, -1, 41202, 41281, 41282, -1, 41276, 41283, 41277, -1, 41283, 41284, 41277, -1, 41283, 41285, 41284, -1, 41285, 41286, 41284, -1, 41284, 41286, 41287, -1, 41287, 41288, 41289, -1, 41286, 41288, 41287, -1, 41289, 41290, 41291, -1, 41288, 41290, 41289, -1, 41291, 33385, 33384, -1, 41290, 33385, 41291, -1, 39148, 39140, 41292, -1, 39148, 41292, 41242, -1, 39154, 39147, 41293, -1, 39154, 41293, 41259, -1, 41294, 39144, 41295, -1, 39137, 39144, 41294, -1, 38973, 39136, 41296, -1, 38975, 39136, 38973, -1, 41296, 39135, 41297, -1, 39136, 39135, 41296, -1, 41297, 39137, 41294, -1, 39135, 39137, 41297, -1, 39133, 39132, 39160, -1, 39160, 41298, 39161, -1, 39132, 41298, 39160, -1, 39161, 41299, 39140, -1, 41298, 41299, 39161, -1, 41299, 41292, 39140, -1, 32983, 32982, 41300, -1, 41301, 41300, 41302, -1, 41301, 32983, 41300, -1, 41303, 41302, 41304, -1, 41303, 41301, 41302, -1, 41305, 41303, 41304, -1, 41306, 41304, 41307, -1, 41308, 41307, 41304, -1, 41309, 41304, 41306, -1, 41310, 41308, 41304, -1, 41311, 41304, 41309, -1, 41312, 41310, 41304, -1, 41305, 41313, 41314, -1, 41305, 41311, 41313, -1, 41305, 41304, 41311, -1, 41315, 41305, 41314, -1, 41316, 41305, 41315, -1, 41317, 41305, 41316, -1, 41318, 41305, 41317, -1, 41319, 41305, 41318, -1, 41320, 41312, 41304, -1, 41321, 41312, 41320, -1, 41322, 41319, 41323, -1, 41322, 41305, 41319, -1, 41324, 39749, 41325, -1, 41324, 41326, 39749, -1, 41327, 41324, 41328, -1, 41329, 41321, 41320, -1, 41329, 41320, 41330, -1, 41331, 41330, 41332, -1, 41331, 41329, 41330, -1, 41333, 41331, 41332, -1, 41334, 41333, 41332, -1, 41335, 41332, 41336, -1, 41335, 41334, 41332, -1, 41337, 41335, 41336, -1, 41338, 41337, 41336, -1, 41339, 41340, 41341, -1, 41339, 41322, 41323, -1, 41339, 41323, 41340, -1, 41342, 41338, 41336, -1, 41343, 41342, 41336, -1, 41344, 41343, 41336, -1, 39742, 41344, 41336, -1, 41325, 39742, 41336, -1, 39749, 39742, 41325, -1, 41345, 41341, 41346, -1, 41345, 41346, 41347, -1, 41345, 41348, 41349, -1, 41345, 41350, 41348, -1, 41345, 41351, 41350, -1, 41345, 41347, 41351, -1, 41345, 41339, 41341, -1, 41326, 41352, 39749, -1, 41326, 41349, 41352, -1, 41326, 41345, 41349, -1, 41324, 41325, 41328, -1, 41353, 41354, 41327, -1, 41353, 41327, 41328, -1, 41355, 41353, 41356, -1, 41355, 41357, 41358, -1, 41355, 41356, 41357, -1, 41359, 41354, 41353, -1, 41359, 41353, 41355, -1, 41356, 41353, 41360, -1, 41335, 41331, 41334, -1, 41334, 41331, 41333, -1, 41331, 41361, 41362, -1, 41335, 41361, 41331, -1, 41363, 41364, 41365, -1, 41363, 41366, 41364, -1, 41366, 41367, 41364, -1, 41366, 41368, 41367, -1, 41368, 41369, 41367, -1, 41368, 41370, 41369, -1, 41370, 41371, 41369, -1, 41370, 41372, 41371, -1, 41372, 41373, 41371, -1, 41372, 41374, 41373, -1, 41374, 41375, 41373, -1, 41374, 41376, 41375, -1, 41376, 41377, 41375, -1, 41376, 41378, 41377, -1, 41378, 41379, 41377, -1, 41378, 41380, 41379, -1, 41380, 41381, 41379, -1, 41380, 41382, 41381, -1, 41382, 41383, 41381, -1, 41382, 41384, 41383, -1, 41384, 41385, 41383, -1, 41384, 41386, 41385, -1, 41386, 41387, 41385, -1, 41386, 41388, 41387, -1, 41388, 41361, 41387, -1, 41388, 41362, 41361, -1, 41365, 41340, 41363, -1, 41340, 41346, 41341, -1, 41340, 41347, 41346, -1, 41365, 41347, 41340, -1, 41354, 41359, 39359, -1, 41354, 39359, 39349, -1, 41389, 39348, 39371, -1, 41389, 39349, 39348, -1, 41389, 41354, 39349, -1, 41390, 39371, 39367, -1, 41390, 41389, 39371, -1, 41391, 39367, 39361, -1, 41391, 41390, 39367, -1, 41392, 41391, 39361, -1, 41393, 39361, 39320, -1, 41393, 41392, 39361, -1, 39322, 41393, 39320, -1, 39148, 41242, 39146, -1, 39146, 41241, 39145, -1, 41242, 41241, 39146, -1, 39145, 41246, 39143, -1, 41241, 41246, 39145, -1, 39143, 41245, 39141, -1, 41246, 41245, 39143, -1, 39141, 41394, 39142, -1, 41245, 41394, 39141, -1, 41394, 41395, 39142, -1, 39142, 41293, 39147, -1, 41395, 41293, 39142, -1, 39154, 41259, 39153, -1, 39153, 41258, 39151, -1, 41259, 41258, 39153, -1, 39151, 41263, 39149, -1, 41258, 41263, 39151, -1, 39149, 41262, 39150, -1, 41263, 41262, 39149, -1, 39150, 41396, 39152, -1, 41262, 41396, 39150, -1, 41396, 41397, 39152, -1, 39152, 41295, 39144, -1, 41397, 41295, 39152, -1, 31850, 31849, 30616, -1, 30616, 31849, 30617, -1, 30617, 31857, 30620, -1, 31849, 31857, 30617, -1, 30620, 31862, 30623, -1, 31857, 31862, 30620, -1, 30623, 31863, 30626, -1, 31862, 31863, 30623, -1, 30614, 31934, 31939, -1, 30743, 31939, 31938, -1, 30743, 30614, 31939, -1, 30744, 31938, 31944, -1, 30744, 30743, 31938, -1, 30748, 30744, 31944, -1, 30615, 31944, 31943, -1, 30615, 30748, 31944, -1, 41398, 41399, 41400, -1, 41398, 41400, 41401, -1, 41402, 41401, 41403, -1, 41402, 41398, 41401, -1, 41404, 41403, 41405, -1, 41404, 41402, 41403, -1, 33280, 41405, 33279, -1, 33280, 41404, 41405, -1, 41399, 41406, 41400, -1, 41400, 41406, 41407, -1, 41407, 41408, 41409, -1, 41406, 41408, 41407, -1, 41409, 41410, 41411, -1, 41408, 41410, 41409, -1, 41411, 41412, 41413, -1, 41410, 41412, 41411, -1, 41413, 41414, 41415, -1, 41412, 41414, 41413, -1, 41414, 41416, 41415, -1, 41416, 41417, 41418, -1, 41414, 41417, 41416, -1, 41417, 41419, 41418, -1, 41417, 41420, 41419, -1, 41421, 41422, 41423, -1, 41423, 41422, 41424, -1, 41417, 41422, 41420, -1, 41420, 41422, 41421, -1, 39195, 39196, 41360, -1, 41425, 41360, 41353, -1, 41425, 39195, 41360, -1, 41426, 41425, 41353, -1, 41328, 41426, 41353, -1, 41427, 41428, 41336, -1, 41429, 41430, 41431, -1, 41427, 41432, 41428, -1, 41433, 41434, 41435, -1, 41433, 41436, 41437, -1, 41438, 41439, 41440, -1, 41438, 41440, 41432, -1, 41433, 41441, 41436, -1, 41433, 41435, 41441, -1, 41442, 41443, 39190, -1, 41442, 39190, 41444, -1, 41445, 41446, 41429, -1, 41445, 41447, 41446, -1, 41448, 41432, 41427, -1, 41445, 41449, 41447, -1, 41448, 41438, 41432, -1, 41450, 41437, 41451, -1, 41450, 41431, 41434, -1, 41450, 41433, 41437, -1, 41325, 41426, 41328, -1, 41450, 41434, 41433, -1, 41452, 41439, 41438, -1, 41452, 41444, 41439, -1, 41453, 41424, 41422, -1, 41453, 41422, 41449, -1, 41453, 41449, 41445, -1, 41454, 41451, 41455, -1, 39175, 39191, 39193, -1, 41454, 41429, 41431, -1, 41456, 41442, 41444, -1, 39175, 39184, 39191, -1, 41456, 41444, 41452, -1, 41454, 41431, 41450, -1, 41454, 41450, 41451, -1, 41457, 41452, 41438, -1, 41458, 41429, 41454, -1, 41458, 41455, 41459, -1, 41457, 41438, 41448, -1, 41458, 41454, 41455, -1, 41460, 41456, 41452, -1, 41458, 41445, 41429, -1, 41461, 41423, 41424, -1, 41461, 41424, 41453, -1, 41461, 41453, 41445, -1, 41461, 41458, 41459, -1, 41461, 41445, 41458, -1, 41461, 41459, 41423, -1, 41460, 41452, 41457, -1, 41462, 41463, 41443, -1, 41462, 41443, 41442, -1, 41462, 41442, 41456, -1, 41464, 41427, 41332, -1, 41465, 41427, 41464, -1, 41430, 41456, 41460, -1, 41430, 41462, 41456, -1, 41466, 41467, 41463, -1, 41466, 41463, 41462, -1, 41468, 41427, 41465, -1, 41468, 41448, 41427, -1, 41446, 41462, 41430, -1, 41446, 41466, 41462, -1, 41435, 41457, 41448, -1, 41435, 41448, 41468, -1, 41421, 41423, 41459, -1, 41469, 41425, 41426, -1, 41470, 41332, 41330, -1, 41470, 41330, 41320, -1, 41469, 41426, 41325, -1, 41470, 41464, 41332, -1, 41471, 39195, 41425, -1, 41447, 41449, 41467, -1, 41447, 41466, 41446, -1, 41447, 41467, 41466, -1, 41471, 41425, 41469, -1, 41472, 41465, 41464, -1, 41473, 41325, 41336, -1, 41472, 41320, 41474, -1, 41473, 41469, 41325, -1, 41472, 41470, 41320, -1, 41475, 39193, 39195, -1, 41472, 41464, 41470, -1, 41475, 39195, 41471, -1, 41475, 39175, 39193, -1, 41434, 41460, 41457, -1, 41440, 41471, 41469, -1, 41440, 41469, 41473, -1, 41434, 41457, 41435, -1, 41476, 39190, 39175, -1, 41476, 39175, 41475, -1, 41428, 41473, 41336, -1, 41477, 41474, 41436, -1, 41477, 41465, 41472, -1, 41477, 41472, 41474, -1, 41439, 41475, 41471, -1, 41477, 41468, 41465, -1, 41439, 41471, 41440, -1, 41431, 41460, 41434, -1, 41432, 41473, 41428, -1, 41431, 41430, 41460, -1, 41432, 41440, 41473, -1, 41441, 41435, 41468, -1, 41441, 41468, 41477, -1, 41444, 41476, 41475, -1, 41444, 41475, 41439, -1, 41441, 41477, 41436, -1, 41444, 39190, 41476, -1, 41427, 41336, 41332, -1, 41429, 41446, 41430, -1, 41420, 41421, 41459, -1, 41478, 41459, 41455, -1, 41478, 41420, 41459, -1, 41479, 41455, 41451, -1, 41479, 41478, 41455, -1, 41480, 41451, 41437, -1, 41480, 41479, 41451, -1, 41481, 41437, 41436, -1, 41481, 41480, 41437, -1, 41482, 41436, 41474, -1, 41482, 41481, 41436, -1, 41483, 41474, 41320, -1, 41483, 41482, 41474, -1, 41304, 41483, 41320, -1, 41484, 41300, 41485, -1, 41484, 41483, 41302, -1, 41484, 41485, 41486, -1, 41484, 41487, 41482, -1, 41484, 41486, 41487, -1, 41478, 41419, 41420, -1, 41300, 32982, 41488, -1, 41304, 41302, 41483, -1, 41489, 41490, 41416, -1, 41489, 41416, 41418, -1, 41491, 41492, 41490, -1, 41491, 41490, 41489, -1, 41493, 41418, 41419, -1, 41493, 41419, 41478, -1, 41493, 41489, 41418, -1, 41494, 41495, 41492, -1, 41494, 41492, 41491, -1, 41496, 41478, 41479, -1, 41496, 41491, 41489, -1, 41496, 41493, 41478, -1, 41496, 41489, 41493, -1, 41497, 41498, 41495, -1, 41497, 41495, 41494, -1, 41499, 41479, 41480, -1, 41499, 41496, 41479, -1, 41499, 41491, 41496, -1, 41499, 41494, 41491, -1, 41486, 41500, 41498, -1, 41486, 41498, 41497, -1, 41501, 41480, 41481, -1, 41501, 41497, 41494, -1, 41501, 41499, 41480, -1, 41501, 41494, 41499, -1, 41485, 41488, 41500, -1, 41485, 41300, 41488, -1, 41485, 41500, 41486, -1, 41487, 41481, 41482, -1, 41487, 41501, 41481, -1, 41487, 41497, 41501, -1, 41487, 41486, 41497, -1, 41484, 41482, 41483, -1, 41484, 41302, 41300, -1, 41502, 41416, 41490, -1, 41502, 41415, 41416, -1, 41503, 41490, 41492, -1, 41503, 41502, 41490, -1, 41504, 41492, 41495, -1, 41504, 41503, 41492, -1, 41505, 41498, 41500, -1, 41505, 41495, 41498, -1, 41505, 41504, 41495, -1, 41506, 41505, 41500, -1, 41507, 41488, 32982, -1, 41507, 41500, 41488, -1, 41507, 41506, 41500, -1, 32981, 41507, 32982, -1, 41508, 41509, 41510, -1, 41508, 41511, 41509, -1, 41512, 41513, 41514, -1, 41512, 41515, 41516, -1, 41512, 41516, 41513, -1, 41512, 41517, 41515, -1, 32987, 41507, 32981, -1, 41518, 41519, 41511, -1, 41518, 41511, 41508, -1, 41520, 41514, 41521, -1, 41520, 41512, 41514, -1, 41520, 41510, 41517, -1, 41520, 41517, 41512, -1, 41522, 41411, 41413, -1, 41522, 41519, 41518, -1, 41522, 41413, 41523, -1, 41522, 41523, 41519, -1, 41524, 41521, 41525, -1, 41524, 41510, 41520, -1, 41524, 41508, 41510, -1, 41524, 41520, 41521, -1, 41526, 41525, 41527, -1, 41526, 41508, 41524, -1, 41526, 41518, 41508, -1, 41526, 41524, 41525, -1, 41528, 41527, 41529, -1, 41528, 41409, 41411, -1, 41528, 41411, 41522, -1, 41528, 41529, 41409, -1, 41528, 41522, 41518, -1, 41528, 41526, 41527, -1, 41528, 41518, 41526, -1, 41407, 41409, 41529, -1, 41530, 32987, 32994, -1, 41530, 41507, 32987, -1, 41531, 41506, 41507, -1, 41531, 41507, 41530, -1, 41509, 41505, 41506, -1, 41509, 41506, 41531, -1, 41515, 32994, 32996, -1, 41515, 41530, 32994, -1, 41511, 41504, 41505, -1, 41511, 41505, 41509, -1, 41517, 41531, 41530, -1, 41517, 41530, 41515, -1, 41519, 41503, 41504, -1, 41519, 41504, 41511, -1, 41510, 41509, 41531, -1, 41510, 41531, 41517, -1, 41516, 32996, 32999, -1, 41516, 32999, 41513, -1, 41516, 41515, 32996, -1, 41523, 41502, 41503, -1, 41523, 41415, 41502, -1, 41523, 41413, 41415, -1, 41523, 41503, 41519, -1, 41400, 41407, 41529, -1, 41532, 41529, 41527, -1, 41532, 41400, 41529, -1, 41533, 41527, 41525, -1, 41533, 41532, 41527, -1, 41534, 41525, 41521, -1, 41534, 41533, 41525, -1, 41535, 41521, 41514, -1, 41535, 41534, 41521, -1, 41536, 41514, 41513, -1, 41536, 41535, 41514, -1, 41537, 41513, 32999, -1, 41537, 41536, 41513, -1, 33008, 41537, 32999, -1, 41538, 41539, 41540, -1, 41538, 41540, 41541, -1, 41542, 33013, 32973, -1, 41542, 32973, 33365, -1, 41542, 33365, 33366, -1, 41542, 33366, 41543, -1, 41544, 41533, 41534, -1, 41544, 41541, 41545, -1, 41544, 41546, 41533, -1, 41544, 41545, 41546, -1, 41547, 41543, 41539, -1, 41547, 41539, 41538, -1, 41548, 41534, 41535, -1, 41548, 41544, 41534, -1, 41548, 41538, 41541, -1, 41548, 41541, 41544, -1, 41549, 33011, 33013, -1, 41549, 33013, 41542, -1, 41549, 41542, 41543, -1, 41549, 41543, 41547, -1, 41550, 41535, 41536, -1, 41550, 41547, 41538, -1, 41550, 41548, 41535, -1, 41550, 41538, 41548, -1, 41551, 41536, 41537, -1, 41551, 33012, 33011, -1, 41551, 33011, 41549, -1, 41551, 41549, 41547, -1, 41551, 41547, 41550, -1, 41551, 41537, 33012, -1, 41551, 41550, 41536, -1, 33008, 33012, 41537, -1, 41552, 33370, 33279, -1, 41552, 33279, 41405, -1, 41553, 33369, 33370, -1, 41553, 33370, 41552, -1, 41554, 41405, 41403, -1, 41554, 41552, 41405, -1, 41540, 33368, 33369, -1, 41540, 33369, 41553, -1, 41545, 41553, 41552, -1, 41545, 41552, 41554, -1, 41539, 33367, 33368, -1, 41539, 33368, 41540, -1, 41555, 41400, 41532, -1, 41555, 41403, 41401, -1, 41555, 41401, 41400, -1, 41555, 41554, 41403, -1, 41541, 41553, 41545, -1, 41541, 41540, 41553, -1, 41543, 33366, 33367, -1, 41543, 33367, 41539, -1, 41546, 41532, 41533, -1, 41546, 41555, 41532, -1, 41546, 41545, 41554, -1, 41546, 41554, 41555, -1, 41181, 41183, 41556, -1, 41557, 36472, 34578, -1, 41557, 34578, 34796, -1, 41558, 36470, 36472, -1, 41558, 36472, 41557, -1, 41559, 36468, 36470, -1, 41559, 36470, 41558, -1, 41560, 36467, 36468, -1, 41560, 36468, 41559, -1, 41561, 33505, 36467, -1, 41561, 41187, 33505, -1, 41561, 36467, 41560, -1, 41562, 34796, 34812, -1, 41562, 34812, 34844, -1, 41562, 34844, 41563, -1, 41562, 41557, 34796, -1, 41564, 41563, 41565, -1, 41564, 41565, 41566, -1, 41564, 41557, 41562, -1, 41564, 41562, 41563, -1, 41564, 41558, 41557, -1, 41567, 41558, 41564, -1, 41567, 41559, 41558, -1, 41567, 41564, 41566, -1, 41568, 41566, 41569, -1, 41568, 41569, 41556, -1, 41568, 41567, 41566, -1, 41568, 41560, 41559, -1, 41568, 41559, 41567, -1, 41570, 41183, 41187, -1, 41570, 41561, 41560, -1, 41570, 41187, 41561, -1, 41570, 41560, 41568, -1, 41570, 41568, 41556, -1, 41570, 41556, 41183, -1, 34844, 34896, 41571, -1, 41563, 41571, 41572, -1, 41563, 34844, 41571, -1, 41565, 41572, 41573, -1, 41565, 41563, 41572, -1, 41566, 41565, 41573, -1, 41569, 41573, 41574, -1, 41569, 41566, 41573, -1, 41556, 41574, 41575, -1, 41556, 41569, 41574, -1, 41181, 41575, 41191, -1, 41181, 41556, 41575, -1, 34980, 34380, 38981, -1, 34970, 38981, 41576, -1, 34970, 34980, 38981, -1, 34969, 34970, 41576, -1, 34968, 34969, 41576, -1, 34960, 34968, 41576, -1, 34896, 41576, 41577, -1, 34896, 34960, 41576, -1, 41571, 41577, 41578, -1, 41571, 34896, 41577, -1, 41572, 41578, 41579, -1, 41572, 41571, 41578, -1, 41573, 41579, 41580, -1, 41573, 41572, 41579, -1, 41574, 41580, 41581, -1, 41574, 41573, 41580, -1, 41575, 41581, 41192, -1, 41575, 41574, 41581, -1, 41191, 41575, 41192, -1, 41582, 41583, 41584, -1, 41582, 41584, 41198, -1, 41582, 41198, 41196, -1, 41582, 41196, 41194, -1, 41582, 41585, 41583, -1, 41582, 41194, 41586, -1, 41582, 41586, 41587, -1, 41582, 41587, 41585, -1, 41588, 38979, 38977, -1, 41194, 41192, 41581, -1, 41589, 41576, 38981, -1, 41589, 38981, 38980, -1, 41590, 41577, 41576, -1, 41590, 41576, 41589, -1, 41591, 38980, 38979, -1, 41591, 38979, 41588, -1, 41591, 41589, 38980, -1, 41592, 41578, 41577, -1, 41592, 41577, 41590, -1, 41593, 41588, 41594, -1, 41593, 41590, 41589, -1, 41593, 41591, 41588, -1, 41593, 41589, 41591, -1, 41595, 41579, 41578, -1, 41595, 41578, 41592, -1, 41596, 41594, 41597, -1, 41596, 41590, 41593, -1, 41596, 41592, 41590, -1, 41596, 41593, 41594, -1, 41587, 41580, 41579, -1, 41587, 41579, 41595, -1, 41598, 41597, 41599, -1, 41598, 41595, 41592, -1, 41598, 41592, 41596, -1, 41598, 41596, 41597, -1, 41586, 41581, 41580, -1, 41586, 41194, 41581, -1, 41586, 41580, 41587, -1, 41585, 41599, 41583, -1, 41585, 41595, 41598, -1, 41585, 41598, 41599, -1, 41585, 41587, 41595, -1, 41215, 41198, 41584, -1, 41600, 41584, 41583, -1, 41600, 41215, 41584, -1, 41601, 41583, 41599, -1, 41601, 41600, 41583, -1, 41602, 41599, 41597, -1, 41602, 41601, 41599, -1, 41603, 41597, 41594, -1, 41603, 41602, 41597, -1, 41604, 41594, 41588, -1, 41604, 41603, 41594, -1, 41605, 41604, 41588, -1, 38973, 41588, 38977, -1, 38973, 41605, 41588, -1, 41297, 41294, 41606, -1, 41297, 41606, 41607, -1, 41608, 41609, 41212, -1, 41608, 41212, 41213, -1, 41608, 41213, 41214, -1, 41610, 41611, 41609, -1, 41610, 41609, 41608, -1, 41612, 41607, 41611, -1, 41612, 41611, 41610, -1, 41613, 41607, 41612, -1, 41613, 41297, 41607, -1, 41614, 41296, 41297, -1, 41614, 41613, 41296, -1, 41614, 41297, 41613, -1, 41615, 41215, 41600, -1, 41615, 41214, 41215, -1, 41615, 41608, 41214, -1, 41616, 41601, 41602, -1, 41616, 41600, 41601, -1, 41616, 41608, 41615, -1, 41616, 41610, 41608, -1, 41616, 41615, 41600, -1, 41617, 41602, 41603, -1, 41617, 41610, 41616, -1, 41617, 41612, 41610, -1, 41617, 41616, 41602, -1, 41618, 41603, 41604, -1, 41618, 41296, 41613, -1, 41618, 41612, 41617, -1, 41618, 41617, 41603, -1, 41618, 41613, 41612, -1, 41619, 41605, 38973, -1, 41619, 41604, 41605, -1, 41619, 38973, 41296, -1, 41619, 41618, 41604, -1, 41619, 41296, 41618, -1, 41606, 41294, 41295, -1, 41606, 41295, 41620, -1, 41606, 41620, 41621, -1, 41607, 41621, 41622, -1, 41607, 41606, 41621, -1, 41611, 41622, 41623, -1, 41611, 41607, 41622, -1, 41609, 41623, 41211, -1, 41609, 41611, 41623, -1, 41212, 41609, 41211, -1, 41396, 41262, 41264, -1, 41623, 41235, 41211, -1, 41295, 41397, 41620, -1, 41624, 41261, 41233, -1, 41624, 41233, 41234, -1, 41624, 41234, 41235, -1, 41625, 41273, 41261, -1, 41625, 41261, 41624, -1, 41626, 41274, 41273, -1, 41626, 41273, 41625, -1, 41627, 41264, 41274, -1, 41627, 41397, 41396, -1, 41627, 41274, 41626, -1, 41627, 41396, 41264, -1, 41628, 41621, 41620, -1, 41628, 41622, 41621, -1, 41628, 41623, 41622, -1, 41628, 41625, 41624, -1, 41628, 41624, 41235, -1, 41628, 41397, 41627, -1, 41628, 41235, 41623, -1, 41628, 41627, 41626, -1, 41628, 41620, 41397, -1, 41628, 41626, 41625, -1, 41259, 41293, 41629, -1, 41260, 41629, 41630, -1, 41260, 41259, 41629, -1, 41270, 41630, 41631, -1, 41270, 41260, 41630, -1, 41268, 41631, 41632, -1, 41268, 41270, 41631, -1, 41266, 41632, 41222, -1, 41266, 41268, 41632, -1, 41224, 41266, 41222, -1, 41394, 41245, 41247, -1, 41632, 41221, 41222, -1, 41293, 41395, 41629, -1, 41633, 41244, 41218, -1, 41633, 41218, 41220, -1, 41633, 41220, 41221, -1, 41634, 41256, 41244, -1, 41634, 41244, 41633, -1, 41635, 41257, 41256, -1, 41635, 41256, 41634, -1, 41636, 41247, 41257, -1, 41636, 41395, 41394, -1, 41636, 41257, 41635, -1, 41636, 41394, 41247, -1, 41637, 41630, 41629, -1, 41637, 41631, 41630, -1, 41637, 41632, 41631, -1, 41637, 41634, 41633, -1, 41637, 41633, 41221, -1, 41637, 41395, 41636, -1, 41637, 41221, 41632, -1, 41637, 41636, 41635, -1, 41637, 41629, 41395, -1, 41637, 41635, 41634, -1, 41242, 41292, 41638, -1, 41243, 41638, 41639, -1, 41243, 41242, 41638, -1, 41253, 41639, 41640, -1, 41253, 41243, 41639, -1, 41251, 41640, 41641, -1, 41251, 41253, 41640, -1, 41249, 41641, 41236, -1, 41249, 41251, 41641, -1, 41219, 41249, 41236, -1, 41240, 41642, 41199, -1, 41298, 39132, 41643, -1, 41292, 41299, 41638, -1, 41644, 41240, 41237, -1, 41644, 41642, 41240, -1, 41645, 41646, 41647, -1, 41645, 41647, 41642, -1, 41645, 41642, 41644, -1, 41648, 41649, 41646, -1, 41648, 41646, 41645, -1, 41650, 41651, 41649, -1, 41650, 41649, 41648, -1, 41652, 41299, 41298, -1, 41652, 41643, 41651, -1, 41652, 41651, 41650, -1, 41652, 41298, 41643, -1, 41653, 41645, 41644, -1, 41653, 41644, 41237, -1, 41653, 41652, 41650, -1, 41653, 41299, 41652, -1, 41653, 41650, 41648, -1, 41653, 41648, 41645, -1, 41654, 41653, 41237, -1, 41654, 41299, 41653, -1, 41655, 41639, 41638, -1, 41655, 41640, 41639, -1, 41655, 41641, 41640, -1, 41655, 41236, 41641, -1, 41655, 41237, 41236, -1, 41655, 41299, 41654, -1, 41655, 41654, 41237, -1, 41655, 41638, 41299, -1, 41656, 41199, 41642, -1, 41656, 41202, 41199, -1, 41657, 41642, 41647, -1, 41657, 41656, 41642, -1, 41658, 41647, 41646, -1, 41658, 41657, 41647, -1, 41659, 41646, 41649, -1, 41659, 41658, 41646, -1, 41660, 41649, 41651, -1, 41660, 41659, 41649, -1, 41661, 41651, 41643, -1, 41661, 41660, 41651, -1, 39126, 41643, 39132, -1, 39126, 41661, 41643, -1, 41662, 41663, 41664, -1, 41662, 41664, 41665, -1, 41666, 41656, 41657, -1, 41666, 41202, 41656, -1, 41666, 41281, 41202, -1, 41666, 41657, 41667, -1, 41668, 41669, 41670, -1, 41668, 41665, 41671, -1, 41668, 41671, 41672, -1, 41668, 41672, 41669, -1, 41673, 41667, 41663, -1, 41673, 41663, 41662, -1, 41674, 41670, 41675, -1, 41674, 41668, 41670, -1, 41674, 41665, 41668, -1, 41674, 41662, 41665, -1, 41676, 41279, 41281, -1, 41676, 41281, 41666, -1, 41676, 41666, 41667, -1, 41676, 41667, 41673, -1, 41677, 41675, 41678, -1, 41677, 41674, 41675, -1, 41677, 41673, 41662, -1, 41677, 41662, 41674, -1, 41679, 41678, 41680, -1, 41679, 41275, 41279, -1, 41679, 41680, 41275, -1, 41679, 41279, 41676, -1, 41679, 41677, 41678, -1, 41679, 41676, 41673, -1, 41679, 41673, 41677, -1, 41276, 41275, 41680, -1, 41681, 41661, 39126, -1, 41681, 39126, 39125, -1, 41682, 41660, 41661, -1, 41682, 41661, 41681, -1, 41683, 39125, 39127, -1, 41683, 41681, 39125, -1, 41664, 41659, 41660, -1, 41664, 41660, 41682, -1, 41671, 41682, 41681, -1, 41671, 41681, 41683, -1, 41663, 41658, 41659, -1, 41663, 41659, 41664, -1, 41684, 39127, 39128, -1, 41684, 39128, 39129, -1, 41684, 39129, 41685, -1, 41684, 41683, 39127, -1, 41665, 41682, 41671, -1, 41665, 41664, 41682, -1, 41667, 41657, 41658, -1, 41667, 41658, 41663, -1, 41672, 41685, 41669, -1, 41672, 41671, 41683, -1, 41672, 41684, 41685, -1, 41672, 41683, 41684, -1, 39129, 33669, 33807, -1, 39129, 33807, 33809, -1, 41685, 33809, 33816, -1, 41685, 33816, 33821, -1, 41685, 33821, 41686, -1, 41685, 39129, 33809, -1, 41669, 41686, 41687, -1, 41669, 41685, 41686, -1, 41670, 41687, 41688, -1, 41670, 41669, 41687, -1, 41675, 41688, 41689, -1, 41675, 41670, 41688, -1, 41678, 41689, 41690, -1, 41678, 41675, 41689, -1, 41680, 41678, 41690, -1, 41276, 41690, 41283, -1, 41276, 41680, 41690, -1, 41686, 33821, 33838, -1, 41686, 33838, 41691, -1, 41687, 41691, 41692, -1, 41687, 41686, 41691, -1, 41688, 41692, 41693, -1, 41688, 41693, 41694, -1, 41688, 41687, 41692, -1, 41689, 41694, 41695, -1, 41689, 41688, 41694, -1, 41690, 41695, 41285, -1, 41690, 41689, 41695, -1, 41283, 41690, 41285, -1, 41286, 41694, 41693, -1, 41286, 41695, 41694, -1, 41286, 41285, 41695, -1, 41696, 41691, 33838, -1, 41696, 33838, 33841, -1, 41697, 41692, 41691, -1, 41697, 41691, 41696, -1, 41698, 41693, 41692, -1, 41698, 41286, 41693, -1, 41698, 41692, 41697, -1, 41699, 41698, 41288, -1, 41699, 41286, 41698, -1, 41700, 41288, 41286, -1, 41700, 41699, 41288, -1, 41700, 41286, 41699, -1, 41701, 33841, 33843, -1, 41701, 41696, 33841, -1, 41702, 41696, 41701, -1, 41702, 41697, 41696, -1, 41703, 41288, 41698, -1, 41703, 41698, 41697, -1, 41703, 41697, 41702, -1, 41704, 41288, 41703, -1, 41705, 33843, 33845, -1, 41705, 33845, 33706, -1, 41705, 33706, 36637, -1, 41705, 41701, 33843, -1, 41706, 41290, 41288, -1, 41706, 41288, 41704, -1, 41706, 41704, 41290, -1, 41707, 36637, 36636, -1, 41707, 41702, 41701, -1, 41707, 41705, 36637, -1, 41707, 41701, 41705, -1, 41708, 36636, 36635, -1, 41708, 41703, 41702, -1, 41708, 41702, 41707, -1, 41708, 41707, 36636, -1, 41709, 36635, 36634, -1, 41709, 41290, 41704, -1, 41709, 41703, 41708, -1, 41709, 41704, 41703, -1, 41709, 41708, 36635, -1, 41710, 36634, 36633, -1, 41710, 36633, 33385, -1, 41710, 33385, 41290, -1, 41710, 41290, 41709, -1, 41710, 41709, 36634, -1, 41711, 41712, 41713, -1, 41711, 41713, 41714, -1, 41715, 41716, 41717, -1, 41715, 41718, 41719, -1, 41715, 41720, 41718, -1, 41715, 41719, 41716, -1, 41721, 41712, 41711, -1, 41721, 41722, 41712, -1, 41723, 41717, 41724, -1, 41723, 41715, 41717, -1, 41723, 41714, 41720, -1, 41723, 41720, 41715, -1, 41725, 41289, 41291, -1, 41725, 41291, 41726, -1, 41725, 41726, 41722, -1, 41725, 41722, 41721, -1, 41727, 41724, 41728, -1, 41727, 41711, 41714, -1, 41727, 41723, 41724, -1, 41727, 41714, 41723, -1, 41729, 41728, 41730, -1, 41729, 41711, 41727, -1, 41729, 41727, 41728, -1, 41729, 41721, 41711, -1, 41731, 41730, 41732, -1, 41291, 33384, 33382, -1, 41731, 41732, 41284, -1, 41731, 41284, 41287, -1, 41731, 41287, 41289, -1, 41731, 41289, 41725, -1, 41731, 41725, 41721, -1, 41731, 41729, 41730, -1, 41731, 41721, 41729, -1, 41733, 33372, 33006, -1, 41733, 33006, 33014, -1, 41734, 33374, 33372, -1, 41734, 33372, 41733, -1, 41713, 33376, 33374, -1, 41713, 33374, 41734, -1, 41718, 33014, 33010, -1, 41718, 41733, 33014, -1, 41712, 33378, 33376, -1, 41712, 33376, 41713, -1, 41720, 41734, 41733, -1, 41720, 41733, 41718, -1, 41722, 33380, 33378, -1, 41722, 33378, 41712, -1, 41714, 41713, 41734, -1, 41714, 41734, 41720, -1, 41719, 33010, 33009, -1, 41719, 33009, 33001, -1, 41719, 33001, 41716, -1, 41719, 41718, 33010, -1, 41726, 33382, 33380, -1, 41726, 33380, 41722, -1, 41726, 41291, 33382, -1, 41735, 41284, 41732, -1, 41735, 41277, 41284, -1, 41736, 41732, 41730, -1, 41736, 41735, 41732, -1, 41737, 41730, 41728, -1, 41737, 41736, 41730, -1, 41738, 41728, 41724, -1, 41738, 41737, 41728, -1, 41739, 41724, 41717, -1, 41739, 41738, 41724, -1, 41740, 41717, 41716, -1, 41740, 41739, 41717, -1, 32980, 41716, 33001, -1, 32980, 41740, 41716, -1, 41741, 41742, 41743, -1, 41744, 41745, 41746, -1, 41744, 32978, 41745, -1, 41744, 41746, 41747, -1, 41748, 41737, 41738, -1, 41748, 41749, 41737, -1, 41748, 41743, 41750, -1, 41748, 41750, 41749, -1, 41751, 41747, 41752, -1, 41751, 41752, 41741, -1, 41753, 41738, 41739, -1, 41753, 41741, 41743, -1, 41753, 41748, 41738, -1, 41753, 41743, 41748, -1, 41754, 32976, 32978, -1, 41754, 32978, 41744, -1, 41754, 41747, 41751, -1, 41754, 41744, 41747, -1, 41755, 41739, 41740, -1, 41755, 41753, 41739, -1, 41755, 41741, 41753, -1, 41755, 41751, 41741, -1, 41756, 41740, 32980, -1, 41756, 32980, 32979, -1, 41756, 32979, 32976, -1, 41756, 32976, 41754, -1, 41756, 41755, 41740, -1, 41756, 41754, 41751, -1, 41756, 41751, 41755, -1, 41735, 41278, 41277, -1, 32978, 32977, 41745, -1, 41757, 41758, 41200, -1, 41757, 41200, 41282, -1, 41759, 41760, 41758, -1, 41759, 41758, 41757, -1, 41761, 41282, 41280, -1, 41761, 41757, 41282, -1, 41742, 41762, 41760, -1, 41742, 41760, 41759, -1, 41750, 41759, 41757, -1, 41750, 41757, 41761, -1, 41752, 41763, 41762, -1, 41752, 41762, 41742, -1, 41764, 41735, 41736, -1, 41764, 41280, 41278, -1, 41764, 41761, 41280, -1, 41764, 41278, 41735, -1, 41743, 41759, 41750, -1, 41743, 41742, 41759, -1, 41747, 41746, 41763, -1, 41747, 41763, 41752, -1, 41749, 41736, 41737, -1, 41749, 41750, 41761, -1, 41749, 41764, 41736, -1, 41749, 41761, 41764, -1, 41741, 41752, 41742, -1, 41765, 41200, 41758, -1, 41765, 41201, 41200, -1, 41766, 41758, 41760, -1, 41766, 41765, 41758, -1, 41767, 41760, 41762, -1, 41767, 41766, 41760, -1, 41768, 41762, 41763, -1, 41768, 41767, 41762, -1, 41769, 41763, 41746, -1, 41769, 41768, 41763, -1, 41770, 41746, 41745, -1, 41770, 41769, 41746, -1, 32983, 41745, 32977, -1, 32983, 41770, 41745, -1, 41771, 41303, 41772, -1, 41771, 41770, 41301, -1, 41771, 41772, 41773, -1, 41771, 41774, 41769, -1, 41771, 41773, 41774, -1, 41238, 41775, 41229, -1, 32983, 41301, 41770, -1, 41776, 41775, 41238, -1, 41777, 41778, 41775, -1, 41777, 41775, 41776, -1, 41779, 41201, 41765, -1, 41779, 41238, 41239, -1, 41779, 41239, 41201, -1, 41779, 41776, 41238, -1, 41780, 41781, 41778, -1, 41780, 41778, 41777, -1, 41782, 41765, 41766, -1, 41782, 41777, 41776, -1, 41782, 41779, 41765, -1, 41782, 41776, 41779, -1, 41783, 41784, 41781, -1, 41783, 41781, 41780, -1, 41785, 41766, 41767, -1, 41785, 41782, 41766, -1, 41785, 41777, 41782, -1, 41785, 41780, 41777, -1, 41773, 41786, 41784, -1, 41773, 41784, 41783, -1, 41787, 41767, 41768, -1, 41787, 41783, 41780, -1, 41787, 41785, 41767, -1, 41787, 41780, 41785, -1, 41772, 41303, 41305, -1, 41772, 41305, 41788, -1, 41772, 41788, 41786, -1, 41772, 41786, 41773, -1, 41774, 41768, 41769, -1, 41774, 41783, 41787, -1, 41774, 41787, 41768, -1, 41774, 41773, 41783, -1, 41771, 41769, 41770, -1, 41771, 41301, 41303, -1, 41789, 41229, 41775, -1, 41789, 41208, 41229, -1, 41790, 41775, 41778, -1, 41790, 41789, 41775, -1, 41791, 41778, 41781, -1, 41791, 41790, 41778, -1, 41792, 41781, 41784, -1, 41792, 41791, 41781, -1, 41793, 41784, 41786, -1, 41793, 41792, 41784, -1, 41794, 41786, 41788, -1, 41794, 41793, 41786, -1, 41322, 41788, 41305, -1, 41322, 41794, 41788, -1, 41795, 41796, 41797, -1, 41795, 41797, 41798, -1, 41799, 41800, 41801, -1, 41799, 41801, 41802, -1, 41803, 41205, 41206, -1, 41803, 41206, 41804, -1, 41803, 41804, 41796, -1, 41803, 41796, 41795, -1, 41805, 41806, 41800, -1, 41805, 41800, 41799, -1, 41807, 41326, 41324, -1, 41807, 41324, 41327, -1, 41807, 41327, 41808, -1, 41807, 41802, 41326, -1, 41809, 41806, 41805, -1, 41809, 41798, 41806, -1, 41207, 41208, 41789, -1, 41810, 41808, 41811, -1, 41810, 41807, 41808, -1, 41810, 41799, 41802, -1, 41810, 41802, 41807, -1, 41812, 41795, 41798, -1, 41812, 41798, 41809, -1, 41813, 41811, 41814, -1, 41813, 41810, 41811, -1, 41813, 41805, 41799, -1, 41813, 41799, 41810, -1, 41815, 41203, 41205, -1, 41815, 41205, 41803, -1, 41815, 41803, 41795, -1, 41815, 41795, 41812, -1, 41816, 41805, 41813, -1, 41816, 41814, 41817, -1, 41816, 41809, 41805, -1, 41816, 41813, 41814, -1, 41818, 41809, 41816, -1, 41818, 41817, 41819, -1, 41818, 41812, 41809, -1, 41818, 41816, 41817, -1, 41820, 41815, 41812, -1, 41820, 41812, 41818, -1, 41820, 41818, 41819, -1, 41820, 41819, 41204, -1, 41820, 41204, 41203, -1, 41820, 41203, 41815, -1, 41821, 41794, 41322, -1, 41821, 41793, 41794, -1, 41821, 41322, 41339, -1, 41822, 41793, 41821, -1, 41823, 41792, 41793, -1, 41823, 41793, 41822, -1, 41797, 41791, 41792, -1, 41797, 41790, 41791, -1, 41797, 41792, 41823, -1, 41801, 41339, 41345, -1, 41801, 41345, 41326, -1, 41801, 41821, 41339, -1, 41796, 41790, 41797, -1, 41800, 41821, 41801, -1, 41800, 41822, 41821, -1, 41804, 41789, 41790, -1, 41804, 41206, 41207, -1, 41804, 41207, 41789, -1, 41804, 41790, 41796, -1, 41806, 41823, 41822, -1, 41806, 41822, 41800, -1, 41798, 41797, 41823, -1, 41798, 41823, 41806, -1, 41802, 41801, 41326, -1, 41824, 41204, 41819, -1, 41824, 41223, 41204, -1, 41825, 41819, 41817, -1, 41825, 41824, 41819, -1, 41826, 41817, 41814, -1, 41826, 41825, 41817, -1, 41827, 41814, 41811, -1, 41827, 41826, 41814, -1, 41828, 41811, 41808, -1, 41828, 41827, 41811, -1, 41354, 41808, 41327, -1, 41354, 41828, 41808, -1, 41829, 41830, 41831, -1, 41829, 41831, 41832, -1, 41833, 41834, 41835, -1, 41833, 41835, 41836, -1, 41837, 41830, 41829, -1, 41837, 41838, 41830, -1, 41839, 41834, 41833, -1, 41839, 41832, 41834, -1, 41840, 41227, 41226, -1, 41840, 41226, 41841, -1, 41840, 41841, 41838, -1, 41840, 41838, 41837, -1, 41842, 41391, 41392, -1, 41842, 41392, 41393, -1, 41842, 41836, 41391, -1, 41225, 41223, 41824, -1, 41843, 41829, 41832, -1, 41843, 41832, 41839, -1, 41844, 41833, 41836, -1, 41844, 41836, 41842, -1, 41845, 41829, 41843, -1, 41845, 41837, 41829, -1, 41846, 41393, 39322, -1, 41846, 39322, 41847, -1, 41846, 41842, 41393, -1, 41848, 41839, 41833, -1, 41848, 41833, 41844, -1, 41849, 41837, 41845, -1, 41849, 41230, 41227, -1, 41849, 41227, 41840, -1, 41849, 41840, 41837, -1, 41850, 41844, 41842, -1, 41850, 41846, 41847, -1, 41850, 41847, 41851, -1, 41850, 41842, 41846, -1, 41852, 41839, 41848, -1, 41852, 41843, 41839, -1, 41853, 41848, 41844, -1, 41853, 41850, 41851, -1, 41853, 41851, 41854, -1, 41855, 41828, 41354, -1, 41853, 41844, 41850, -1, 41856, 41845, 41843, -1, 41855, 41354, 41389, -1, 41856, 41843, 41852, -1, 41857, 41827, 41828, -1, 41858, 41854, 41859, -1, 41857, 41828, 41855, -1, 41858, 41848, 41853, -1, 41831, 41826, 41827, -1, 41858, 41852, 41848, -1, 41858, 41853, 41854, -1, 41860, 41230, 41849, -1, 41860, 41845, 41856, -1, 41831, 41827, 41857, -1, 41860, 41232, 41230, -1, 41835, 41389, 41390, -1, 41860, 41849, 41845, -1, 41861, 41858, 41859, -1, 41861, 41859, 41862, -1, 41835, 41855, 41389, -1, 41861, 41856, 41852, -1, 41861, 41852, 41858, -1, 41830, 41825, 41826, -1, 41863, 41862, 41864, -1, 41863, 41861, 41862, -1, 41863, 41864, 41209, -1, 41863, 41209, 41232, -1, 41830, 41826, 41831, -1, 41863, 41232, 41860, -1, 41863, 41856, 41861, -1, 41863, 41860, 41856, -1, 41834, 41855, 41835, -1, 41834, 41857, 41855, -1, 41838, 41824, 41825, -1, 41838, 41825, 41830, -1, 41832, 41831, 41857, -1, 41832, 41857, 41834, -1, 41841, 41226, 41225, -1, 41841, 41824, 41838, -1, 41841, 41225, 41824, -1, 41836, 41390, 41391, -1, 41836, 41835, 41390, -1, 41210, 41209, 41864, -1, 41865, 41864, 41862, -1, 41865, 41210, 41864, -1, 41866, 41862, 41859, -1, 41866, 41865, 41862, -1, 41867, 41859, 41854, -1, 41867, 41866, 41859, -1, 41868, 41854, 41851, -1, 41868, 41867, 41854, -1, 41869, 41851, 41847, -1, 41869, 41868, 41851, -1, 41870, 41869, 41847, -1, 39321, 41847, 39322, -1, 39321, 41870, 41847, -1, 39253, 39252, 41871, -1, 41872, 41871, 41873, -1, 41872, 39253, 41871, -1, 41874, 41873, 41875, -1, 41874, 41872, 41873, -1, 41876, 41875, 39321, -1, 41876, 41874, 41875, -1, 39328, 41876, 39321, -1, 41865, 41877, 41210, -1, 41878, 41877, 41865, -1, 41866, 41878, 41865, -1, 41879, 41878, 41866, -1, 41867, 39252, 41879, -1, 41867, 41879, 41866, -1, 41868, 41871, 39252, -1, 41868, 39252, 41867, -1, 41875, 41869, 41870, -1, 41875, 41873, 41869, -1, 39321, 41875, 41870, -1, 41880, 41873, 41871, -1, 41880, 41868, 41869, -1, 41880, 41871, 41868, -1, 41880, 41869, 41873, -1, 41881, 41210, 41877, -1, 41881, 41197, 41210, -1, 41882, 41877, 41878, -1, 41882, 41881, 41877, -1, 41883, 41878, 41879, -1, 41883, 41882, 41878, -1, 39251, 41879, 39252, -1, 39251, 41883, 41879, -1, 39255, 41883, 39251, -1, 41884, 39256, 39257, -1, 41885, 39256, 41884, -1, 41886, 39255, 39254, -1, 41886, 41883, 39255, -1, 41887, 41882, 41883, -1, 41887, 41886, 39254, -1, 41887, 41883, 41886, -1, 41888, 41881, 41882, -1, 41888, 41197, 41881, -1, 41888, 41193, 41195, -1, 41888, 41195, 41197, -1, 41888, 41882, 41887, -1, 41889, 39254, 39256, -1, 41890, 41885, 41891, -1, 41890, 41887, 39254, -1, 41890, 41889, 39256, -1, 41890, 39256, 41885, -1, 41890, 39254, 41889, -1, 41892, 41891, 41190, -1, 41892, 41190, 41193, -1, 41892, 41890, 41891, -1, 41892, 41193, 41888, -1, 41892, 41887, 41890, -1, 41892, 41888, 41887, -1, 41184, 41190, 41891, -1, 41893, 41891, 41885, -1, 41893, 41184, 41891, -1, 41894, 41885, 41884, -1, 41894, 41893, 41885, -1, 41895, 41884, 39257, -1, 41895, 41894, 41884, -1, 39258, 41895, 39257, -1, 41896, 41897, 41898, -1, 41899, 41900, 41896, -1, 41899, 41901, 41900, -1, 41902, 41903, 41901, -1, 41902, 41901, 41899, -1, 41904, 41182, 41184, -1, 41904, 41184, 41893, -1, 41904, 41898, 41182, -1, 41905, 39265, 39267, -1, 41905, 39267, 41906, -1, 41905, 41902, 39265, -1, 41905, 41906, 41903, -1, 41905, 41903, 41902, -1, 41907, 41893, 41894, -1, 41907, 41904, 41893, -1, 41907, 41896, 41898, -1, 41907, 41898, 41904, -1, 41908, 41894, 41895, -1, 41908, 41907, 41894, -1, 41908, 41899, 41896, -1, 41908, 41896, 41907, -1, 41909, 39265, 41902, -1, 41909, 41908, 41895, -1, 41909, 41902, 41899, -1, 41909, 41899, 41908, -1, 41910, 41895, 39258, -1, 41910, 39258, 39265, -1, 41910, 39265, 41909, -1, 41910, 41909, 41895, -1, 41911, 41912, 41913, -1, 41911, 41913, 41186, -1, 41914, 41911, 41186, -1, 41915, 38964, 41912, -1, 41915, 41912, 41911, -1, 41897, 41186, 41185, -1, 41897, 41914, 41186, -1, 41916, 41915, 41911, -1, 41916, 41911, 41914, -1, 41917, 38959, 38961, -1, 41917, 38961, 38963, -1, 41917, 38963, 38964, -1, 41917, 38964, 41915, -1, 41900, 41916, 41914, -1, 41900, 41914, 41897, -1, 41918, 41917, 41915, -1, 41918, 41915, 41916, -1, 41919, 38957, 38955, -1, 41919, 38955, 38959, -1, 41919, 38959, 41917, -1, 41919, 41917, 41918, -1, 41901, 41916, 41900, -1, 41901, 41918, 41916, -1, 41903, 41919, 41918, -1, 41903, 41918, 41901, -1, 41898, 41185, 41182, -1, 41898, 41897, 41185, -1, 41906, 41920, 38957, -1, 41906, 39267, 39269, -1, 41906, 39269, 41920, -1, 41906, 38957, 41919, -1, 41906, 41919, 41903, -1, 41896, 41900, 41897, -1, 33533, 33501, 41921, -1, 41922, 41921, 41923, -1, 41922, 33533, 41921, -1, 41924, 41923, 38968, -1, 41924, 41922, 41923, -1, 38971, 41924, 38968, -1, 38962, 41912, 38964, -1, 41188, 41913, 41912, -1, 41188, 41186, 41913, -1, 41188, 41912, 38962, -1, 41189, 38962, 38967, -1, 41189, 41188, 38962, -1, 41923, 38967, 38968, -1, 41921, 41189, 38967, -1, 41921, 38967, 41923, -1, 33501, 41189, 41921, -1, 36884, 41925, 36894, -1, 36894, 41925, 41926, -1, 41926, 41927, 41928, -1, 41925, 41927, 41926, -1, 41928, 41929, 41930, -1, 41927, 41929, 41928, -1, 41930, 41931, 41932, -1, 41929, 41931, 41930, -1, 41931, 41933, 41932, -1, 41934, 41935, 41932, -1, 41934, 41932, 41933, -1, 41936, 41937, 41938, -1, 41938, 41937, 41939, -1, 41940, 41941, 41942, -1, 41943, 41941, 41940, -1, 41939, 41941, 41943, -1, 41937, 41941, 41939, -1, 36860, 36858, 36867, -1, 41944, 41945, 41936, -1, 41946, 41945, 41944, -1, 39492, 41947, 31617, -1, 31617, 41947, 36853, -1, 36853, 41947, 41946, -1, 41936, 41948, 41937, -1, 41945, 41948, 41936, -1, 41942, 41949, 41950, -1, 41948, 41949, 41937, -1, 41941, 41949, 41942, -1, 41937, 41949, 41941, -1, 39492, 41951, 41947, -1, 41946, 41951, 41945, -1, 36864, 41952, 36862, -1, 41947, 41951, 41946, -1, 41945, 41953, 41948, -1, 41951, 41953, 41945, -1, 41953, 41954, 41948, -1, 41950, 41954, 41955, -1, 41949, 41954, 41950, -1, 41948, 41954, 41949, -1, 39493, 41956, 39492, -1, 39492, 41956, 41951, -1, 41956, 41957, 41951, -1, 39496, 41957, 39493, -1, 41951, 41957, 41953, -1, 39493, 41957, 41956, -1, 39496, 41958, 41957, -1, 41957, 41958, 41953, -1, 39499, 41958, 39496, -1, 39501, 41958, 39499, -1, 41955, 41958, 39501, -1, 41954, 41958, 41955, -1, 41953, 41958, 41954, -1, 39501, 39502, 41955, -1, 36867, 41959, 36866, -1, 36858, 41959, 36867, -1, 36856, 41960, 36858, -1, 36858, 41960, 41959, -1, 36866, 41961, 36865, -1, 41959, 41961, 36866, -1, 36865, 41962, 36863, -1, 41961, 41962, 36865, -1, 41959, 41938, 41961, -1, 41960, 41938, 41959, -1, 36856, 41944, 41960, -1, 36863, 41963, 36864, -1, 41952, 41963, 41964, -1, 41962, 41963, 36863, -1, 36864, 41963, 41952, -1, 41938, 41939, 41961, -1, 41961, 41939, 41962, -1, 41944, 41936, 41960, -1, 41960, 41936, 41938, -1, 41964, 41943, 41940, -1, 41962, 41943, 41963, -1, 41963, 41943, 41964, -1, 41939, 41943, 41962, -1, 36853, 41946, 36855, -1, 36855, 41946, 36856, -1, 36856, 41946, 41944, -1, 41965, 41966, 41967, -1, 41968, 36891, 36893, -1, 41968, 41969, 36891, -1, 41968, 41967, 41970, -1, 41968, 41970, 41969, -1, 41971, 36893, 36878, -1, 41971, 36877, 36876, -1, 41971, 36878, 36877, -1, 41971, 41965, 41967, -1, 41931, 41972, 41933, -1, 41971, 36876, 41965, -1, 41971, 41967, 41968, -1, 41971, 41968, 36893, -1, 41973, 41931, 41929, -1, 41973, 41972, 41931, -1, 41974, 41975, 41976, -1, 41974, 41976, 41972, -1, 41974, 41972, 41973, -1, 41977, 41927, 41925, -1, 41977, 41929, 41927, -1, 41977, 41973, 41929, -1, 41978, 41975, 41974, -1, 41979, 41974, 41973, -1, 41979, 41973, 41977, -1, 41966, 41980, 41975, -1, 41966, 41975, 41978, -1, 41981, 36884, 36887, -1, 41981, 41925, 36884, -1, 41981, 41977, 41925, -1, 41970, 41978, 41974, -1, 41970, 41974, 41979, -1, 41982, 36874, 36875, -1, 41982, 36875, 41983, -1, 41982, 41983, 41980, -1, 41982, 41980, 41966, -1, 41984, 36887, 36889, -1, 41984, 41977, 41981, -1, 41984, 41979, 41977, -1, 41984, 41981, 36887, -1, 41967, 41966, 41978, -1, 41967, 41978, 41970, -1, 41969, 36889, 36891, -1, 41969, 41984, 36889, -1, 41969, 41970, 41979, -1, 41969, 41979, 41984, -1, 41965, 36876, 36874, -1, 41965, 41982, 41966, -1, 41965, 36874, 41982, -1, 39506, 41955, 39502, -1, 39474, 41985, 39508, -1, 41955, 41986, 41950, -1, 41987, 41986, 41985, -1, 39508, 41986, 39506, -1, 39506, 41986, 41955, -1, 41985, 41986, 39508, -1, 41988, 41989, 41987, -1, 41986, 41989, 41950, -1, 41987, 41989, 41986, -1, 41950, 41990, 41942, -1, 41942, 41990, 41940, -1, 41991, 41990, 41988, -1, 41989, 41990, 41950, -1, 41988, 41990, 41989, -1, 41940, 41992, 41964, -1, 41993, 41992, 41991, -1, 41990, 41992, 41940, -1, 41991, 41992, 41990, -1, 41964, 41994, 41952, -1, 41952, 41994, 36862, -1, 41995, 41994, 41993, -1, 36862, 41994, 41995, -1, 41992, 41994, 41964, -1, 41993, 41994, 41992, -1, 41996, 41934, 41933, -1, 41997, 41933, 41972, -1, 41997, 41996, 41933, -1, 41998, 41976, 41975, -1, 41998, 41972, 41976, -1, 41998, 41997, 41972, -1, 41999, 41980, 41983, -1, 41999, 41975, 41980, -1, 41999, 41998, 41975, -1, 36875, 41999, 41983, -1, 36862, 41995, 36875, -1, 36875, 41995, 42000, -1, 42000, 41993, 42001, -1, 41995, 41993, 42000, -1, 42001, 41991, 42002, -1, 41993, 41991, 42001, -1, 42002, 41988, 42003, -1, 41991, 41988, 42002, -1, 42003, 41987, 42004, -1, 41988, 41987, 42003, -1, 42004, 41985, 42005, -1, 41987, 41985, 42004, -1, 42005, 39474, 39473, -1, 41985, 39474, 42005, -1, 42006, 42007, 42008, -1, 41997, 42009, 41996, -1, 42010, 42009, 41997, -1, 41996, 42009, 42011, -1, 42011, 42012, 42013, -1, 42014, 42012, 42010, -1, 42009, 42012, 42011, -1, 42010, 42012, 42009, -1, 42015, 42016, 42006, -1, 42006, 42016, 42007, -1, 39485, 42017, 39487, -1, 39487, 42017, 42018, -1, 42015, 42017, 42016, -1, 42018, 42017, 42015, -1, 42000, 41999, 36875, -1, 42007, 42019, 42014, -1, 42014, 42019, 42012, -1, 42012, 42019, 42013, -1, 42013, 42020, 42021, -1, 42016, 42020, 42007, -1, 42019, 42020, 42013, -1, 42007, 42020, 42019, -1, 42021, 42022, 39478, -1, 39473, 39490, 42005, -1, 39478, 42022, 39483, -1, 42005, 39490, 42004, -1, 39483, 42022, 39485, -1, 42004, 39490, 42003, -1, 39485, 42022, 42017, -1, 42020, 42022, 42021, -1, 42017, 42022, 42016, -1, 42016, 42022, 42020, -1, 41996, 42011, 41934, -1, 42000, 42023, 41999, -1, 42002, 42024, 42001, -1, 42001, 42024, 42000, -1, 42000, 42024, 42023, -1, 42003, 42025, 42002, -1, 39490, 42025, 42003, -1, 42002, 42025, 42024, -1, 41999, 42026, 41998, -1, 42023, 42026, 41999, -1, 39490, 42027, 42025, -1, 42024, 42008, 42023, -1, 42023, 42008, 42026, -1, 39489, 42028, 39490, -1, 39490, 42028, 42027, -1, 42025, 42006, 42024, -1, 42024, 42006, 42008, -1, 41998, 42010, 41997, -1, 42026, 42010, 41998, -1, 42008, 42014, 42026, -1, 42026, 42014, 42010, -1, 42025, 42015, 42006, -1, 42027, 42015, 42025, -1, 39487, 42018, 39489, -1, 39489, 42018, 42028, -1, 42028, 42018, 42027, -1, 42027, 42018, 42015, -1, 42008, 42007, 42014, -1, 39478, 39475, 42021, -1, 42021, 42029, 42013, -1, 39475, 42029, 42021, -1, 42013, 42030, 42011, -1, 42029, 42030, 42013, -1, 42011, 42031, 41934, -1, 42030, 42031, 42011, -1, 42031, 41935, 41934, -1, 42032, 30124, 30123, -1, 42032, 39318, 30124, -1, 42033, 30123, 30120, -1, 42033, 42032, 30123, -1, 42034, 42033, 30120, -1, 42035, 30120, 30122, -1, 42035, 42034, 30120, -1, 39273, 30122, 30121, -1, 39273, 42035, 30122, -1, 39270, 39273, 30121, -1, 39329, 39317, 39318, -1, 42036, 39318, 42032, -1, 42036, 39329, 39318, -1, 42037, 42032, 42033, -1, 42037, 42036, 42032, -1, 42038, 42033, 42034, -1, 42038, 42037, 42033, -1, 42039, 42034, 42035, -1, 42039, 42038, 42034, -1, 42040, 42039, 42035, -1, 42041, 42035, 39273, -1, 42041, 42040, 42035, -1, 39282, 42041, 39273, -1, 39328, 42042, 42043, -1, 39327, 42042, 39328, -1, 42043, 42044, 42045, -1, 42042, 42044, 42043, -1, 42045, 42046, 42047, -1, 42047, 42046, 42048, -1, 42048, 42046, 42049, -1, 42044, 42046, 42045, -1, 42049, 39282, 42050, -1, 42050, 39282, 42051, -1, 42051, 39282, 39289, -1, 42046, 39282, 42049, -1, 42042, 42052, 42044, -1, 42053, 42052, 42054, -1, 42055, 42052, 42042, -1, 42054, 42052, 42055, -1, 42044, 42056, 42046, -1, 42052, 42056, 42044, -1, 42053, 42056, 42052, -1, 42057, 42056, 42053, -1, 39282, 42058, 42041, -1, 42041, 42058, 42040, -1, 42046, 42058, 39282, -1, 42040, 42058, 42059, -1, 42059, 42058, 42057, -1, 42056, 42058, 42046, -1, 42057, 42058, 42056, -1, 39329, 42036, 42060, -1, 42061, 42062, 39323, -1, 39323, 42062, 39324, -1, 42063, 42064, 42061, -1, 42065, 42064, 42063, -1, 42061, 42064, 42062, -1, 39324, 42066, 39325, -1, 42062, 42066, 39324, -1, 42065, 42067, 42064, -1, 42064, 42068, 42062, -1, 42062, 42068, 42066, -1, 39325, 42054, 39326, -1, 42066, 42054, 39325, -1, 42037, 42069, 42036, -1, 42060, 42069, 42065, -1, 42065, 42069, 42067, -1, 42036, 42069, 42060, -1, 42064, 42070, 42068, -1, 42067, 42070, 42064, -1, 42066, 42053, 42054, -1, 42068, 42053, 42066, -1, 42039, 42071, 42038, -1, 42038, 42071, 42037, -1, 42069, 42071, 42067, -1, 42067, 42071, 42070, -1, 42037, 42071, 42069, -1, 42070, 42057, 42068, -1, 42068, 42057, 42053, -1, 39326, 42055, 39327, -1, 39327, 42055, 42042, -1, 42054, 42055, 39326, -1, 42040, 42059, 42039, -1, 42039, 42059, 42071, -1, 42071, 42059, 42070, -1, 42070, 42059, 42057, -1, 39323, 39319, 42061, -1, 42061, 39312, 42063, -1, 39319, 39312, 42061, -1, 42063, 39306, 42065, -1, 39312, 39306, 42063, -1, 39306, 39302, 42065, -1, 42065, 39300, 42060, -1, 39302, 39300, 42065, -1, 39300, 39299, 42060, -1, 42060, 39303, 39329, -1, 39299, 39303, 42060, -1, 39303, 39305, 39329, -1, 39305, 39307, 39329, -1, 42072, 42073, 42074, -1, 42074, 42075, 42076, -1, 42073, 42075, 42074, -1, 42076, 42077, 42078, -1, 42075, 42077, 42076, -1, 42078, 42079, 39476, -1, 42077, 42079, 42078, -1, 42079, 39477, 39476, -1, 42080, 42081, 42072, -1, 42072, 42081, 42073, -1, 31311, 31646, 31310, -1, 31313, 31646, 31311, -1, 31310, 42082, 31307, -1, 31646, 42082, 31310, -1, 31303, 42083, 31308, -1, 31307, 42083, 31303, -1, 42082, 42083, 31307, -1, 31308, 42084, 31312, -1, 42083, 42084, 31308, -1, 31312, 42085, 31314, -1, 42084, 42085, 31312, -1, 42085, 42086, 31314, -1, 31314, 42087, 31329, -1, 42086, 42087, 31314, -1, 42087, 39488, 31329, -1, 37078, 37080, 42088, -1, 42088, 42089, 42090, -1, 37080, 42089, 42088, -1, 42090, 42091, 42092, -1, 42089, 42091, 42090, -1, 42092, 42093, 42080, -1, 42091, 42093, 42092, -1, 42093, 42081, 42080, -1, 42094, 42095, 42096, -1, 42097, 42098, 42099, -1, 42100, 42101, 42102, -1, 42096, 42101, 42100, -1, 42072, 42074, 42103, -1, 39480, 42104, 39479, -1, 39479, 42104, 42105, -1, 42105, 42104, 42106, -1, 42106, 42104, 42095, -1, 42102, 42107, 42097, -1, 42097, 42107, 42098, -1, 42095, 42108, 42096, -1, 42096, 42108, 42101, -1, 42102, 42109, 42107, -1, 42101, 42109, 42102, -1, 42110, 42111, 42112, -1, 42099, 42111, 42110, -1, 42098, 42111, 42099, -1, 39481, 42113, 39480, -1, 42095, 42113, 42108, -1, 39480, 42113, 42104, -1, 42104, 42113, 42095, -1, 42098, 42114, 42111, -1, 42107, 42114, 42098, -1, 42108, 42115, 42101, -1, 42101, 42115, 42109, -1, 42113, 42116, 42108, -1, 39482, 42116, 39481, -1, 39481, 42116, 42113, -1, 42108, 42116, 42115, -1, 42107, 42117, 42114, -1, 42109, 42117, 42107, -1, 42112, 42118, 42082, -1, 42111, 42118, 42112, -1, 42112, 42082, 31646, -1, 42109, 42119, 42117, -1, 42115, 42119, 42109, -1, 42118, 42120, 42082, -1, 42082, 42120, 42083, -1, 42083, 42120, 42084, -1, 42111, 42120, 42118, -1, 42114, 42120, 42111, -1, 42116, 42121, 42115, -1, 39482, 42121, 42116, -1, 39484, 42121, 39482, -1, 42119, 42121, 39484, -1, 42115, 42121, 42119, -1, 42117, 42122, 42114, -1, 42120, 42122, 42084, -1, 42084, 42122, 42085, -1, 39486, 42086, 42085, -1, 42114, 42122, 42120, -1, 39486, 42087, 42086, -1, 42085, 42122, 39486, -1, 42119, 42123, 42117, -1, 39484, 42123, 42119, -1, 39486, 39488, 42087, -1, 42117, 42123, 42122, -1, 42122, 42123, 39486, -1, 39486, 42124, 39484, -1, 42123, 42124, 39486, -1, 42103, 42125, 42126, -1, 39484, 42124, 42123, -1, 42074, 42125, 42103, -1, 42076, 42127, 42074, -1, 42074, 42127, 42125, -1, 42126, 42128, 42129, -1, 42125, 42128, 42126, -1, 42076, 42094, 42127, -1, 42125, 42100, 42128, -1, 42127, 42100, 42125, -1, 42130, 42097, 42099, -1, 42129, 42097, 42130, -1, 42128, 42097, 42129, -1, 42078, 42106, 42076, -1, 42076, 42106, 42094, -1, 42127, 42096, 42100, -1, 42094, 42096, 42127, -1, 42100, 42102, 42128, -1, 42128, 42102, 42097, -1, 39476, 42105, 42078, -1, 39479, 42105, 39476, -1, 42078, 42105, 42106, -1, 42106, 42095, 42094, -1, 42131, 42132, 42133, -1, 42131, 42134, 42132, -1, 42131, 42135, 42136, -1, 42131, 42136, 42134, -1, 42137, 37067, 37069, -1, 42137, 31642, 37067, -1, 42137, 31643, 31642, -1, 42137, 37069, 42138, -1, 42139, 42140, 42141, -1, 42139, 42138, 42140, -1, 42142, 42133, 42143, -1, 42142, 42131, 42133, -1, 42142, 42141, 42135, -1, 42142, 42135, 42131, -1, 42144, 31644, 31643, -1, 42144, 31643, 42137, -1, 42144, 42137, 42138, -1, 42144, 42138, 42139, -1, 42145, 42143, 42146, -1, 42145, 42139, 42141, -1, 42145, 42142, 42143, -1, 42145, 42141, 42142, -1, 42147, 31645, 31644, -1, 42147, 42146, 31645, -1, 42147, 42145, 42146, -1, 42147, 31644, 42144, -1, 42147, 42144, 42139, -1, 42147, 42139, 42145, -1, 31646, 31645, 42146, -1, 42148, 37076, 37078, -1, 42148, 37078, 42088, -1, 42149, 37074, 37076, -1, 42149, 37076, 42148, -1, 42150, 42088, 42090, -1, 42150, 42148, 42088, -1, 42151, 37073, 37074, -1, 42151, 37074, 42149, -1, 42136, 42148, 42150, -1, 42136, 42149, 42148, -1, 42152, 42092, 42080, -1, 42152, 42090, 42092, -1, 42152, 42080, 42153, -1, 42152, 42153, 42154, -1, 42152, 42150, 42090, -1, 42140, 37071, 37073, -1, 42140, 37073, 42151, -1, 42135, 42151, 42149, -1, 42135, 42149, 42136, -1, 42134, 42154, 42132, -1, 42134, 42152, 42154, -1, 42134, 42136, 42150, -1, 42134, 42150, 42152, -1, 42138, 37069, 37071, -1, 42138, 37071, 42140, -1, 42141, 42140, 42151, -1, 42141, 42151, 42135, -1, 42080, 42103, 42126, -1, 42080, 42072, 42103, -1, 42153, 42129, 42130, -1, 42153, 42126, 42129, -1, 42153, 42080, 42126, -1, 42154, 42130, 42099, -1, 42154, 42153, 42130, -1, 42132, 42099, 42110, -1, 42132, 42154, 42099, -1, 42133, 42110, 42112, -1, 42133, 42132, 42110, -1, 42143, 42133, 42112, -1, 42146, 42143, 42112, -1, 31646, 42146, 42112, -1, 39330, 30126, 39313, -1, 39357, 39313, 39314, -1, 39357, 39314, 39315, -1, 39357, 39315, 39316, -1, 39357, 39330, 39313, -1, 39358, 39316, 39309, -1, 39358, 39309, 39308, -1, 39358, 39357, 39316, -1, 39364, 39308, 39310, -1, 39364, 39310, 39311, -1, 39364, 39358, 39308, -1, 39362, 39311, 39304, -1, 39362, 39364, 39311, -1, 39320, 39304, 39301, -1, 39320, 39362, 39304, -1, 30130, 30127, 39331, -1, 30130, 39331, 39341, -1, 30129, 39341, 39343, -1, 30129, 30130, 39341, -1, 30131, 39343, 39345, -1, 30131, 39345, 41355, -1, 30131, 30129, 39343, -1, 39192, 39189, 41357, -1, 39194, 39192, 41357, -1, 41356, 39196, 39194, -1, 41360, 39196, 41356, -1, 38983, 41355, 41358, -1, 38983, 30131, 41355, -1, 38985, 41358, 41357, -1, 38985, 38983, 41358, -1, 38985, 41357, 39189, -1, 39189, 38993, 38984, -1, 39189, 38984, 38985, -1, 41357, 41356, 39194, -1, 42155, 39359, 41359, -1, 42156, 39359, 42155, -1, 39344, 39350, 39359, -1, 39344, 39359, 42156, -1, 39342, 39350, 39344, -1, 39352, 39350, 39342, -1, 39340, 39352, 39342, -1, 39335, 39352, 39340, -1, 39332, 39335, 39340, -1, 39345, 42156, 42155, -1, 39345, 39344, 42156, -1, 41355, 42155, 41359, -1, 41355, 39345, 42155, -1, 39241, 3153, 39245, -1, 39245, 3152, 39246, -1, 42157, 3152, 42158, -1, 39246, 3152, 42157, -1, 3153, 3152, 39245, -1, 42158, 3151, 42159, -1, 3152, 3151, 42158, -1, 42159, 3149, 42160, -1, 3151, 3149, 42159, -1, 42160, 3148, 39240, -1, 3149, 3148, 42160, -1, 39240, 3150, 39237, -1, 3148, 3150, 39240, -1, 42161, 3145, 3146, -1, 42161, 3146, 3147, -1, 42161, 39238, 3145, -1, 42162, 3147, 3142, -1, 42162, 42161, 3147, -1, 39235, 42162, 3142, -1, 39246, 42157, 39243, -1, 39243, 42157, 42163, -1, 42163, 42158, 42164, -1, 42157, 42158, 42163, -1, 42158, 42159, 42164, -1, 42164, 42160, 42165, -1, 42159, 42160, 42164, -1, 42165, 39240, 39239, -1, 42160, 39240, 42165, -1, 39235, 39200, 39201, -1, 42162, 39201, 42166, -1, 42162, 39235, 39201, -1, 42161, 42162, 42166, -1, 39238, 42166, 39239, -1, 39238, 42161, 42166, -1, 39236, 39238, 39239, -1, 42167, 39249, 42168, -1, 39250, 39249, 42167, -1, 42166, 42165, 39239, -1, 39248, 42163, 42164, -1, 39248, 39243, 42163, -1, 42168, 42169, 39201, -1, 39201, 42169, 42166, -1, 39249, 42169, 42168, -1, 42166, 42169, 42165, -1, 42165, 42170, 42164, -1, 42169, 42170, 42165, -1, 39249, 42170, 42169, -1, 42164, 42170, 39248, -1, 39248, 42171, 39249, -1, 42170, 42171, 39248, -1, 39249, 42171, 42170, -1, 39202, 42172, 39201, -1, 39201, 42172, 42168, -1, 42172, 42173, 42168, -1, 42168, 42174, 42167, -1, 42173, 42174, 42168, -1, 42167, 42175, 39250, -1, 42174, 42175, 42167, -1, 42175, 39266, 39250, -1, 42175, 42174, 42176, -1, 42174, 42177, 42176, -1, 42174, 42178, 42177, -1, 42174, 42179, 42178, -1, 42174, 42180, 42179, -1, 42173, 42181, 42174, -1, 42174, 42181, 42180, -1, 42173, 42182, 42181, -1, 42173, 42183, 42182, -1, 42173, 42184, 42183, -1, 42173, 42172, 42184, -1, 3225, 31301, 3223, -1, 3223, 31309, 3224, -1, 31301, 31309, 3223, -1, 3224, 31306, 3226, -1, 31309, 31306, 3224, -1, 31306, 31305, 3226, -1, 3226, 31302, 3227, -1, 31305, 31302, 3226, -1, 3235, 39204, 3233, -1, 3233, 39232, 3234, -1, 39204, 39232, 3233, -1, 3234, 39229, 3236, -1, 39232, 39229, 3234, -1, 39229, 39227, 3236, -1, 3236, 39225, 3237, -1, 39227, 39225, 3236, -1, 30155, 38952, 42185, -1, 30153, 42185, 42186, -1, 30153, 30155, 42185, -1, 30154, 42186, 39866, -1, 30154, 30153, 42186, -1, 30152, 30154, 39866, -1, 39203, 3232, 39205, -1, 39205, 3231, 39207, -1, 3232, 3231, 39205, -1, 39207, 3229, 39209, -1, 3231, 3229, 39207, -1, 39209, 3228, 39215, -1, 3229, 3228, 39209, -1, 3228, 3230, 39215, -1, 42187, 38953, 30148, -1, 42187, 30148, 30151, -1, 42188, 30151, 30150, -1, 42188, 42187, 30151, -1, 39845, 30150, 30149, -1, 39845, 42188, 30150, -1, 42189, 38951, 30159, -1, 42189, 30159, 30156, -1, 42190, 30156, 30158, -1, 42190, 42189, 30156, -1, 39849, 30158, 30157, -1, 39849, 42190, 30158, -1, 39197, 30163, 30160, -1, 39199, 30160, 30162, -1, 39199, 39197, 30160, -1, 39198, 30162, 30161, -1, 39198, 39199, 30162, -1, 38946, 39198, 30161, -1, 39278, 39271, 3157, -1, 39278, 3157, 3158, -1, 42191, 3158, 3159, -1, 42191, 39278, 3158, -1, 42192, 42191, 3159, -1, 39244, 3159, 3156, -1, 39244, 42192, 3159, -1, 39242, 39244, 3156, -1, 39298, 39297, 39406, -1, 42193, 39406, 39401, -1, 42193, 39298, 39406, -1, 42194, 39401, 39402, -1, 42194, 42193, 39401, -1, 42195, 39402, 39403, -1, 42195, 42194, 39402, -1, 42196, 39403, 39391, -1, 42196, 42195, 39403, -1, 42197, 39391, 39393, -1, 42197, 42196, 39391, -1, 39459, 39393, 39394, -1, 39459, 42197, 39393, -1, 39291, 42198, 39280, -1, 39471, 39472, 39292, -1, 39284, 39464, 39283, -1, 39461, 39462, 39287, -1, 39275, 39460, 39276, -1, 42199, 42198, 39291, -1, 42200, 42198, 42199, -1, 42200, 42201, 42198, -1, 42202, 42203, 42201, -1, 42202, 42201, 42200, -1, 42202, 42200, 39448, -1, 42204, 42205, 42203, -1, 42204, 42203, 42202, -1, 42204, 42202, 39448, -1, 42206, 42204, 39448, -1, 42206, 42205, 42204, -1, 42207, 42205, 42206, -1, 42207, 42208, 42205, -1, 42207, 42206, 39448, -1, 42209, 42208, 42207, -1, 42209, 39448, 39458, -1, 42209, 42207, 39448, -1, 42209, 39458, 42208, -1, 42210, 39291, 39292, -1, 42210, 39448, 42200, -1, 42210, 42200, 42199, -1, 42210, 42199, 39291, -1, 42211, 39448, 42210, -1, 42211, 42210, 39292, -1, 42212, 39448, 42211, -1, 42212, 42211, 39292, -1, 42213, 39472, 39448, -1, 42213, 42212, 39292, -1, 42213, 39448, 42212, -1, 42213, 39292, 39472, -1, 42214, 39292, 39288, -1, 42215, 42214, 39288, -1, 42215, 39292, 42214, -1, 42216, 39292, 42215, -1, 42217, 39471, 39292, -1, 42217, 39292, 42216, -1, 42218, 39288, 42219, -1, 42218, 42219, 39469, -1, 42220, 42218, 39469, -1, 42220, 39288, 42218, -1, 42221, 39288, 42220, -1, 42221, 42220, 39469, -1, 42222, 42221, 39469, -1, 42222, 39288, 42221, -1, 42222, 42215, 39288, -1, 42223, 42222, 39469, -1, 42223, 42215, 42222, -1, 42223, 42216, 42215, -1, 42224, 39469, 39470, -1, 42224, 39470, 39471, -1, 42224, 42223, 39469, -1, 42224, 42216, 42223, -1, 42224, 42217, 42216, -1, 42224, 39471, 42217, -1, 42225, 39288, 39290, -1, 42225, 42219, 39288, -1, 42225, 39469, 42219, -1, 42226, 42225, 39290, -1, 42226, 39469, 42225, -1, 42227, 39469, 42226, -1, 42227, 42226, 39290, -1, 42228, 39469, 42227, -1, 42228, 42227, 39290, -1, 42229, 39469, 42228, -1, 42229, 42228, 39290, -1, 42230, 39469, 42229, -1, 42230, 42229, 39290, -1, 42231, 39468, 39469, -1, 42231, 39469, 42230, -1, 42231, 42230, 39290, -1, 42232, 39290, 39281, -1, 42232, 39281, 39466, -1, 42233, 39290, 42232, -1, 42233, 42232, 39466, -1, 42234, 42233, 39466, -1, 42234, 39290, 42233, -1, 42235, 42234, 39466, -1, 42235, 39290, 42234, -1, 42236, 42235, 39466, -1, 42236, 39290, 42235, -1, 42237, 39466, 39467, -1, 42237, 39467, 39468, -1, 42237, 42231, 39290, -1, 42237, 39468, 42231, -1, 42237, 42236, 39466, -1, 42237, 39290, 42236, -1, 42238, 39466, 39281, -1, 42239, 39466, 42238, -1, 42239, 42238, 39465, -1, 42240, 42239, 39465, -1, 42240, 39466, 42239, -1, 42241, 42240, 39465, -1, 42241, 39466, 42240, -1, 42242, 42241, 39465, -1, 42242, 39466, 42241, -1, 42243, 42242, 39465, -1, 42243, 39466, 42242, -1, 42244, 42243, 39465, -1, 42244, 39466, 42243, -1, 42244, 39465, 39466, -1, 42245, 39281, 39283, -1, 42245, 39465, 42238, -1, 42245, 42238, 39281, -1, 42245, 39283, 39464, -1, 42246, 39465, 42245, -1, 42246, 42245, 39464, -1, 42247, 42246, 39464, -1, 42247, 39465, 42246, -1, 42248, 42247, 39464, -1, 42248, 39465, 42247, -1, 42249, 42248, 39464, -1, 42249, 39465, 42248, -1, 42250, 42249, 39464, -1, 42250, 39465, 42249, -1, 42251, 39464, 39465, -1, 42251, 42250, 39464, -1, 42251, 39465, 42250, -1, 42252, 39284, 39285, -1, 42252, 39464, 39284, -1, 42253, 39464, 42252, -1, 42254, 39464, 42253, -1, 42255, 39464, 42254, -1, 42255, 42254, 39463, -1, 42256, 42255, 39463, -1, 42256, 39464, 42255, -1, 42257, 42256, 39463, -1, 42257, 39464, 42256, -1, 42258, 39463, 39464, -1, 42258, 42257, 39463, -1, 42258, 39464, 42257, -1, 42259, 42252, 39285, -1, 42259, 39285, 39286, -1, 42260, 42253, 42252, -1, 42260, 42252, 42259, -1, 42260, 42259, 39286, -1, 42261, 42254, 42253, -1, 42261, 42260, 39286, -1, 42261, 42253, 42260, -1, 42261, 39463, 42254, -1, 42262, 42261, 39286, -1, 42262, 39463, 42261, -1, 42263, 42262, 39286, -1, 42263, 39463, 42262, -1, 42264, 42263, 39286, -1, 42264, 39463, 42263, -1, 42265, 39286, 39462, -1, 42265, 39462, 39463, -1, 42265, 42264, 39286, -1, 42265, 39463, 42264, -1, 42266, 39286, 39287, -1, 42267, 39286, 42266, -1, 42267, 42266, 39287, -1, 42268, 39286, 42267, -1, 42268, 42267, 39287, -1, 42269, 39462, 39286, -1, 42269, 39287, 39462, -1, 42269, 39286, 42268, -1, 42269, 42268, 39287, -1, 42270, 39287, 39279, -1, 42271, 39287, 42270, -1, 42271, 42270, 39279, -1, 42272, 39287, 42271, -1, 42272, 42271, 39279, -1, 42273, 39287, 42272, -1, 42273, 42272, 39279, -1, 42274, 39287, 42273, -1, 42275, 39461, 39287, -1, 42275, 39287, 42274, -1, 42276, 39276, 39460, -1, 42276, 39279, 39276, -1, 42277, 39279, 42276, -1, 42277, 42276, 39460, -1, 42278, 39279, 42277, -1, 42278, 42277, 39460, -1, 42279, 39279, 42278, -1, 42279, 42278, 39460, -1, 42280, 39279, 42279, -1, 42280, 42279, 39460, -1, 42280, 42273, 39279, -1, 42281, 42280, 39460, -1, 42281, 42273, 42280, -1, 42281, 42274, 42273, -1, 42282, 42275, 42274, -1, 42282, 39460, 39461, -1, 42282, 42281, 39460, -1, 42282, 42274, 42281, -1, 42282, 39461, 42275, -1, 42283, 39460, 39275, -1, 42283, 39275, 39272, -1, 42283, 39272, 39293, -1, 42284, 39460, 42283, -1, 42284, 42283, 39293, -1, 42284, 39296, 39298, -1, 42284, 39293, 39296, -1, 42285, 39298, 42193, -1, 42285, 42284, 39298, -1, 42285, 39460, 42284, -1, 42286, 42193, 42194, -1, 42286, 42285, 42193, -1, 42286, 39460, 42285, -1, 42287, 42195, 42196, -1, 42287, 42194, 42195, -1, 42287, 42286, 42194, -1, 42287, 39460, 42286, -1, 42288, 42287, 42196, -1, 42288, 39460, 42287, -1, 42289, 42197, 39459, -1, 42289, 42196, 42197, -1, 42289, 39459, 39460, -1, 42289, 42288, 42196, -1, 42289, 39460, 42288, -1, 39395, 39280, 42198, -1, 39395, 39277, 39280, -1, 39399, 42198, 42201, -1, 39399, 39395, 42198, -1, 39446, 42201, 42203, -1, 39446, 39399, 42201, -1, 39443, 42203, 42205, -1, 39443, 39446, 42203, -1, 39438, 42208, 39458, -1, 39438, 42205, 42208, -1, 39438, 39443, 42205, -1, 39431, 39458, 39456, -1, 39431, 39456, 39455, -1, 39431, 39455, 39453, -1, 39431, 39453, 39451, -1, 39431, 39451, 39450, -1, 39431, 39450, 39449, -1, 39431, 39449, 39452, -1, 39431, 39452, 39454, -1, 39431, 39454, 39457, -1, 39431, 39438, 39458, -1, 42290, 42291, 42292, -1, 42293, 42294, 42295, -1, 42296, 42297, 42298, -1, 42299, 42298, 42300, -1, 42299, 42300, 42301, -1, 39409, 39404, 42302, -1, 42293, 42303, 42294, -1, 42304, 42305, 42306, -1, 42307, 42295, 42308, -1, 42309, 42301, 42310, -1, 42311, 42305, 42304, -1, 42309, 42310, 42312, -1, 42307, 42308, 42313, -1, 42314, 42315, 42305, -1, 42316, 42317, 42318, -1, 42319, 42312, 42320, -1, 42316, 42313, 42317, -1, 42314, 42305, 42311, -1, 42319, 42320, 42321, -1, 42322, 42318, 42323, -1, 42324, 42304, 42325, -1, 42322, 42323, 42326, -1, 42327, 42328, 42329, -1, 42327, 42330, 42328, -1, 42324, 42311, 42304, -1, 42327, 39439, 39423, -1, 42327, 39423, 42330, -1, 42331, 39413, 39419, -1, 42332, 42333, 42296, -1, 42331, 42334, 42291, -1, 42332, 42329, 42333, -1, 42331, 39419, 42334, -1, 42335, 42336, 42315, -1, 42331, 42291, 42290, -1, 42337, 42290, 42303, -1, 42335, 42315, 42314, -1, 42337, 42303, 42293, -1, 42338, 42311, 42324, -1, 42339, 42295, 42307, -1, 42340, 42298, 42299, -1, 42340, 42296, 42298, -1, 42339, 42293, 42295, -1, 42338, 42314, 42311, -1, 42341, 42301, 42309, -1, 42342, 42325, 42343, -1, 42341, 42299, 42301, -1, 42342, 42324, 42325, -1, 42344, 42307, 42313, -1, 42344, 42313, 42316, -1, 42345, 42336, 42335, -1, 42346, 42309, 42312, -1, 42345, 42347, 42336, -1, 42346, 42312, 42319, -1, 42348, 42318, 42322, -1, 42348, 42316, 42318, -1, 42349, 42321, 42350, -1, 42349, 42350, 42351, -1, 42349, 42351, 42352, -1, 42353, 42326, 42354, -1, 42355, 42314, 42338, -1, 42349, 42319, 42321, -1, 42355, 42335, 42314, -1, 42356, 42329, 42332, -1, 42356, 39439, 42327, -1, 42356, 39441, 39439, -1, 42353, 42322, 42326, -1, 42357, 39413, 42331, -1, 42356, 42327, 42329, -1, 42358, 42332, 42296, -1, 42357, 39416, 39413, -1, 42359, 42324, 42342, -1, 42359, 42338, 42324, -1, 42357, 42290, 42337, -1, 42357, 42331, 42290, -1, 42360, 42343, 42361, -1, 42358, 42296, 42340, -1, 42362, 42337, 42293, -1, 42362, 42293, 42339, -1, 42363, 42299, 42341, -1, 42360, 42342, 42343, -1, 42363, 42340, 42299, -1, 42364, 42365, 42347, -1, 42366, 42339, 42307, -1, 42366, 42307, 42344, -1, 42364, 42347, 42345, -1, 42367, 42309, 42346, -1, 42367, 42341, 42309, -1, 42297, 42344, 42316, -1, 42292, 42335, 42355, -1, 42368, 42349, 42352, -1, 42297, 42316, 42348, -1, 42292, 42345, 42335, -1, 42368, 42352, 42369, -1, 42368, 42346, 42319, -1, 42368, 42319, 42349, -1, 42294, 42338, 42359, -1, 42370, 39444, 39441, -1, 42300, 42348, 42322, -1, 42294, 42355, 42338, -1, 42370, 42356, 42332, -1, 42370, 42332, 42358, -1, 42300, 42322, 42353, -1, 42370, 39441, 42356, -1, 42308, 42359, 42342, -1, 42310, 42354, 42371, -1, 42372, 42358, 42340, -1, 42308, 42342, 42360, -1, 42372, 42340, 42363, -1, 42310, 42353, 42354, -1, 42317, 42360, 42361, -1, 42317, 42361, 42373, -1, 42374, 39420, 39416, -1, 42374, 39416, 42357, -1, 42374, 42357, 42337, -1, 42375, 42363, 42341, -1, 42374, 42337, 42362, -1, 42375, 42341, 42367, -1, 42376, 39433, 42377, -1, 42378, 42369, 42379, -1, 42376, 42377, 42365, -1, 42378, 42368, 42369, -1, 42328, 42362, 42339, -1, 42376, 39422, 39433, -1, 42378, 42367, 42346, -1, 42376, 42365, 42364, -1, 42378, 42346, 42368, -1, 42328, 42339, 42366, -1, 42380, 42358, 42372, -1, 42291, 42364, 42345, -1, 42380, 39396, 39444, -1, 42333, 42366, 42344, -1, 42380, 39444, 42370, -1, 42333, 42344, 42297, -1, 42380, 42370, 42358, -1, 42291, 42345, 42292, -1, 42303, 42355, 42294, -1, 42381, 42372, 42363, -1, 42303, 42292, 42355, -1, 42381, 42363, 42375, -1, 42298, 42297, 42348, -1, 42298, 42348, 42300, -1, 42382, 42379, 42383, -1, 42382, 42378, 42379, -1, 42382, 42375, 42367, -1, 42301, 42300, 42353, -1, 42295, 42359, 42308, -1, 42382, 42367, 42378, -1, 42295, 42294, 42359, -1, 42313, 42360, 42317, -1, 42384, 39397, 39396, -1, 42301, 42353, 42310, -1, 42384, 42380, 42372, -1, 42384, 39396, 42380, -1, 42384, 42372, 42381, -1, 42313, 42308, 42360, -1, 42312, 42371, 42320, -1, 42385, 42383, 42386, -1, 42318, 42373, 42323, -1, 42312, 42310, 42371, -1, 42385, 42382, 42383, -1, 42385, 42381, 42375, -1, 42330, 39423, 39420, -1, 42385, 42375, 42382, -1, 42330, 39420, 42374, -1, 42387, 42384, 42381, -1, 42330, 42362, 42328, -1, 42318, 42317, 42373, -1, 42387, 42302, 39404, -1, 42330, 42374, 42362, -1, 42387, 42386, 42302, -1, 42334, 39422, 42376, -1, 42387, 39404, 39397, -1, 42334, 42364, 42291, -1, 42387, 39397, 42384, -1, 42387, 42381, 42385, -1, 42334, 39419, 39422, -1, 42387, 42385, 42386, -1, 42334, 42376, 42364, -1, 42329, 42366, 42333, -1, 42290, 42292, 42303, -1, 42329, 42328, 42366, -1, 42296, 42333, 42297, -1, 42388, 42351, 42389, -1, 42389, 42350, 42390, -1, 42351, 42350, 42389, -1, 42390, 42321, 42391, -1, 42350, 42321, 42390, -1, 42391, 42320, 42392, -1, 42321, 42320, 42391, -1, 42392, 42371, 42393, -1, 42320, 42371, 42392, -1, 42393, 42354, 42394, -1, 42371, 42354, 42393, -1, 42394, 42326, 42395, -1, 42354, 42326, 42394, -1, 42395, 42323, 42396, -1, 42326, 42323, 42395, -1, 42396, 42373, 42397, -1, 42323, 42373, 42396, -1, 42397, 42361, 42398, -1, 42373, 42361, 42397, -1, 42398, 42343, 42399, -1, 42361, 42343, 42398, -1, 42399, 42325, 42400, -1, 42343, 42325, 42399, -1, 42400, 42304, 42401, -1, 42325, 42304, 42400, -1, 42304, 42306, 42401, -1, 42306, 42402, 42401, -1, 42403, 42402, 42306, -1, 42402, 42403, 42404, -1, 42404, 42405, 42406, -1, 42403, 42405, 42404, -1, 42406, 42407, 42408, -1, 42405, 42407, 42406, -1, 42408, 42409, 42410, -1, 42407, 42409, 42408, -1, 42410, 42411, 42412, -1, 42409, 42411, 42410, -1, 42412, 42413, 42414, -1, 42411, 42413, 42412, -1, 42414, 42415, 42416, -1, 42413, 42415, 42414, -1, 42416, 42417, 42418, -1, 42415, 42417, 42416, -1, 42418, 42419, 42420, -1, 42417, 42419, 42418, -1, 42420, 42421, 42422, -1, 42419, 42421, 42420, -1, 42422, 42423, 42424, -1, 42421, 42423, 42422, -1, 42424, 42425, 42426, -1, 42423, 42425, 42424, -1, 42426, 42427, 42428, -1, 42425, 42427, 42426, -1, 42427, 42429, 42428, -1, 42388, 42429, 42351, -1, 42428, 42429, 42388, -1, 42430, 39409, 42302, -1, 42430, 39426, 39409, -1, 42431, 42302, 42386, -1, 42431, 42430, 42302, -1, 42432, 42386, 42383, -1, 42432, 42431, 42386, -1, 42433, 42383, 42379, -1, 42433, 42432, 42383, -1, 42434, 42379, 42369, -1, 42434, 42433, 42379, -1, 42435, 42369, 42352, -1, 42435, 42434, 42369, -1, 42429, 42352, 42351, -1, 42429, 42435, 42352, -1, 42377, 39433, 39447, -1, 42377, 39447, 42436, -1, 42365, 42436, 42437, -1, 42365, 42377, 42436, -1, 42347, 42437, 42438, -1, 42347, 42365, 42437, -1, 42336, 42438, 42439, -1, 42336, 42347, 42438, -1, 42315, 42439, 42440, -1, 42315, 42336, 42439, -1, 42305, 42440, 42441, -1, 42305, 42315, 42440, -1, 42306, 42441, 42403, -1, 42306, 42305, 42441, -1, 42442, 42443, 42444, -1, 42445, 42446, 42447, -1, 42445, 42447, 42448, -1, 42449, 42450, 42451, -1, 42449, 42452, 42450, -1, 42453, 42451, 42454, -1, 42455, 42448, 42456, -1, 42455, 42456, 42457, -1, 42458, 42435, 42429, -1, 42453, 42454, 42459, -1, 42460, 42461, 42462, -1, 42463, 42459, 42464, -1, 42458, 42429, 42427, -1, 42463, 42464, 42465, -1, 42460, 42457, 42461, -1, 42466, 42434, 42435, -1, 42467, 42465, 42409, -1, 42468, 42462, 42469, -1, 42467, 42409, 42407, -1, 42468, 42469, 42470, -1, 42466, 42435, 42458, -1, 42471, 42417, 42415, -1, 42472, 42427, 42425, -1, 42473, 39432, 42474, -1, 42473, 42443, 42442, -1, 42471, 42470, 42417, -1, 42473, 42474, 42443, -1, 42472, 42458, 42427, -1, 42473, 39430, 39432, -1, 42475, 39436, 39428, -1, 42476, 42433, 42434, -1, 42475, 42477, 42446, -1, 42478, 42452, 42449, -1, 42475, 39428, 42477, -1, 42475, 42446, 42445, -1, 42478, 42442, 42452, -1, 42479, 42445, 42448, -1, 42476, 42434, 42466, -1, 42480, 42449, 42451, -1, 42479, 42448, 42455, -1, 42481, 42458, 42472, -1, 42482, 42455, 42457, -1, 42482, 42457, 42460, -1, 42480, 42451, 42453, -1, 42483, 42453, 42459, -1, 42481, 42466, 42458, -1, 42484, 42472, 42425, -1, 42484, 42425, 42423, -1, 42483, 42459, 42463, -1, 42485, 42460, 42462, -1, 39429, 39426, 42430, -1, 42485, 42462, 42468, -1, 42486, 42463, 42465, -1, 42487, 42433, 42476, -1, 42487, 42432, 42433, -1, 42486, 42465, 42467, -1, 42488, 42407, 42405, -1, 42489, 42470, 42471, -1, 42488, 42405, 42403, -1, 42488, 42467, 42407, -1, 42489, 42468, 42470, -1, 42490, 42466, 42481, -1, 42488, 42403, 42441, -1, 42491, 42415, 42413, -1, 42492, 42473, 42442, -1, 42490, 42476, 42466, -1, 42492, 39430, 42473, -1, 42491, 42471, 42415, -1, 42492, 39437, 39430, -1, 42492, 42442, 42478, -1, 42493, 42481, 42472, -1, 42494, 42449, 42480, -1, 42495, 39435, 39436, -1, 42495, 39436, 42475, -1, 42495, 42475, 42445, -1, 42493, 42472, 42484, -1, 42495, 42445, 42479, -1, 42494, 42478, 42449, -1, 42496, 42423, 42421, -1, 42497, 42479, 42455, -1, 42498, 42480, 42453, -1, 42498, 42453, 42483, -1, 42497, 42455, 42482, -1, 42496, 42484, 42423, -1, 42499, 42431, 42432, -1, 42444, 42482, 42460, -1, 42500, 42483, 42463, -1, 42444, 42460, 42485, -1, 42499, 42432, 42487, -1, 42500, 42463, 42486, -1, 42447, 42487, 42476, -1, 42501, 42467, 42488, -1, 42450, 42485, 42468, -1, 42450, 42468, 42489, -1, 42447, 42476, 42490, -1, 42501, 42441, 42440, -1, 42501, 42486, 42467, -1, 42501, 42488, 42441, -1, 42456, 42490, 42481, -1, 42502, 39408, 39437, -1, 42456, 42481, 42493, -1, 42502, 39437, 42492, -1, 42502, 42492, 42478, -1, 42454, 42471, 42491, -1, 42502, 42478, 42494, -1, 42454, 42489, 42471, -1, 42503, 42480, 42498, -1, 42503, 42494, 42480, -1, 42464, 42413, 42411, -1, 42461, 42493, 42484, -1, 42461, 42484, 42496, -1, 42464, 42491, 42413, -1, 42469, 42421, 42419, -1, 42504, 39434, 39435, -1, 42505, 42498, 42483, -1, 42504, 42479, 42497, -1, 42504, 42495, 42479, -1, 42469, 42496, 42421, -1, 42505, 42483, 42500, -1, 42504, 39435, 42495, -1, 42506, 42430, 42431, -1, 42507, 42440, 42439, -1, 42443, 42482, 42444, -1, 42506, 39429, 42430, -1, 42507, 42501, 42440, -1, 42443, 42497, 42482, -1, 42506, 42431, 42499, -1, 42507, 42500, 42486, -1, 42507, 42486, 42501, -1, 42446, 42487, 42447, -1, 42508, 39407, 39408, -1, 42508, 39408, 42502, -1, 42446, 42499, 42487, -1, 42452, 42444, 42485, -1, 42508, 42502, 42494, -1, 42452, 42485, 42450, -1, 42508, 42494, 42503, -1, 42509, 42503, 42498, -1, 42451, 42450, 42489, -1, 42448, 42447, 42490, -1, 42448, 42490, 42456, -1, 42509, 42498, 42505, -1, 42451, 42489, 42454, -1, 42510, 42507, 42439, -1, 42510, 42439, 42438, -1, 42510, 42505, 42500, -1, 42510, 42500, 42507, -1, 42457, 42493, 42461, -1, 42457, 42456, 42493, -1, 42459, 42454, 42491, -1, 42511, 39400, 39407, -1, 42511, 39407, 42508, -1, 42459, 42491, 42464, -1, 42511, 42503, 42509, -1, 42462, 42461, 42496, -1, 42462, 42496, 42469, -1, 42511, 42508, 42503, -1, 42465, 42411, 42409, -1, 42512, 42438, 42437, -1, 42470, 42419, 42417, -1, 42512, 42510, 42438, -1, 42465, 42464, 42411, -1, 42512, 42509, 42505, -1, 42474, 42504, 42497, -1, 42474, 42497, 42443, -1, 42512, 42505, 42510, -1, 42474, 39432, 39434, -1, 42513, 42436, 39447, -1, 42474, 39434, 42504, -1, 42470, 42469, 42419, -1, 42513, 42437, 42436, -1, 42513, 39447, 39392, -1, 42442, 42444, 42452, -1, 42477, 39429, 42506, -1, 42513, 39392, 39400, -1, 42477, 42506, 42499, -1, 42513, 39400, 42511, -1, 42513, 42512, 42437, -1, 42513, 42511, 42509, -1, 42477, 39428, 39429, -1, 42513, 42509, 42512, -1, 42477, 42499, 42446, -1, 42514, 42515, 42516, -1, 39206, 39208, 42515, -1, 39206, 42515, 42514, -1, 42517, 39230, 42518, -1, 42519, 39230, 42517, -1, 42519, 42517, 39228, -1, 42520, 39228, 39230, -1, 42520, 39230, 42519, -1, 42520, 42519, 39228, -1, 42521, 42518, 42522, -1, 42521, 39228, 42517, -1, 42521, 42517, 42518, -1, 42523, 42521, 42522, -1, 42523, 39228, 42521, -1, 42524, 39228, 42523, -1, 42524, 42523, 42522, -1, 42524, 39226, 39228, -1, 42525, 42522, 42526, -1, 42527, 42524, 42522, -1, 42527, 39226, 42524, -1, 42527, 42522, 42525, -1, 42527, 42525, 42526, -1, 42527, 39214, 39226, -1, 39230, 39233, 42528, -1, 39230, 42528, 42529, -1, 42530, 42526, 42531, -1, 39230, 42529, 42532, -1, 39230, 42532, 42533, -1, 39230, 42533, 42534, -1, 39230, 42534, 42535, -1, 42536, 39213, 39214, -1, 39230, 42535, 42537, -1, 42536, 42530, 42531, -1, 39230, 42537, 42518, -1, 42536, 42526, 42530, -1, 42536, 39214, 42527, -1, 42536, 42527, 42526, -1, 42538, 42531, 42539, -1, 42540, 42536, 42531, -1, 42540, 39211, 39213, -1, 42540, 42531, 42538, -1, 42540, 42538, 42539, -1, 42540, 39213, 42536, -1, 42541, 42539, 42542, -1, 42543, 42541, 42542, -1, 42543, 42539, 42541, -1, 42543, 39222, 39220, -1, 42543, 39220, 39211, -1, 42543, 39211, 42540, -1, 42543, 42540, 42539, -1, 42544, 42542, 42545, -1, 42546, 42543, 42542, -1, 42546, 39223, 39222, -1, 42546, 42544, 42545, -1, 42546, 39222, 42543, -1, 42546, 42542, 42544, -1, 42547, 42545, 42548, -1, 42549, 39223, 42546, -1, 42549, 42545, 42547, -1, 42549, 42546, 42545, -1, 42549, 42547, 42548, -1, 42549, 42548, 39223, -1, 42550, 42548, 42551, -1, 42552, 39224, 42548, -1, 42552, 42548, 42550, -1, 42552, 42550, 42551, -1, 42552, 42551, 39224, -1, 42553, 42551, 42554, -1, 42555, 42553, 42554, -1, 42555, 42551, 42553, -1, 42556, 42551, 42555, -1, 42556, 39234, 42551, -1, 42557, 42554, 42558, -1, 42557, 42558, 42559, -1, 42560, 42554, 42557, -1, 42560, 42555, 42554, -1, 42561, 39221, 39234, -1, 42561, 42556, 42555, -1, 39224, 39223, 42548, -1, 42561, 39234, 42556, -1, 42561, 42560, 39221, -1, 42561, 42555, 42560, -1, 42562, 42557, 42559, -1, 39234, 39224, 42551, -1, 42563, 42557, 42562, -1, 42563, 42560, 42557, -1, 42563, 39221, 42560, -1, 42564, 39210, 39221, -1, 42564, 42563, 39210, -1, 42564, 39221, 42563, -1, 42565, 42559, 42566, -1, 42565, 42566, 42567, -1, 42565, 42562, 42559, -1, 42568, 42565, 42567, -1, 42568, 42563, 42562, -1, 42568, 39210, 42563, -1, 42568, 42562, 42565, -1, 42569, 39208, 39210, -1, 42569, 39210, 42568, -1, 42570, 42567, 42515, -1, 42571, 42568, 42567, -1, 42571, 42567, 42570, -1, 42571, 42570, 42515, -1, 42572, 42515, 39208, -1, 42572, 42568, 42571, -1, 42572, 39208, 42569, -1, 42572, 42569, 42568, -1, 42572, 42571, 42515, -1, 42573, 42515, 42574, -1, 42575, 42515, 42573, -1, 42576, 42515, 42575, -1, 42577, 42515, 42576, -1, 42516, 42515, 42577, -1, 42537, 42578, 42518, -1, 42579, 42578, 42537, -1, 42518, 42580, 42522, -1, 42578, 42580, 42518, -1, 42522, 42581, 42526, -1, 42580, 42581, 42522, -1, 42526, 42582, 42531, -1, 42581, 42582, 42526, -1, 42531, 42583, 42539, -1, 42539, 42583, 42542, -1, 42582, 42583, 42531, -1, 42542, 42584, 42545, -1, 42583, 42584, 42542, -1, 42545, 42585, 42548, -1, 42584, 42585, 42545, -1, 42548, 42586, 42551, -1, 42551, 42586, 42554, -1, 42585, 42586, 42548, -1, 42554, 42587, 42558, -1, 42586, 42587, 42554, -1, 42558, 42588, 42559, -1, 42587, 42588, 42558, -1, 42559, 42589, 42566, -1, 42566, 42589, 42567, -1, 42588, 42589, 42559, -1, 42567, 42590, 42515, -1, 42589, 42590, 42567, -1, 42515, 42591, 42574, -1, 42590, 42591, 42515, -1, 42591, 42592, 42574, -1, 42537, 42593, 42579, -1, 42594, 42590, 42589, -1, 42595, 42590, 42594, -1, 42596, 42591, 42595, -1, 42595, 42591, 42590, -1, 42579, 42593, 42597, -1, 42597, 42593, 42598, -1, 42598, 42593, 42599, -1, 42599, 42593, 42600, -1, 42600, 42593, 42601, -1, 42593, 42602, 42601, -1, 42582, 42603, 42583, -1, 42581, 42603, 42582, -1, 42604, 42603, 42581, -1, 42580, 42605, 42581, -1, 42581, 42605, 42604, -1, 42593, 42606, 42602, -1, 42583, 42607, 42584, -1, 42603, 42607, 42583, -1, 42608, 42606, 42593, -1, 42578, 42609, 42580, -1, 42580, 42609, 42605, -1, 42596, 42610, 42591, -1, 42607, 42611, 42584, -1, 42579, 42612, 42578, -1, 42578, 42612, 42609, -1, 42584, 42613, 42585, -1, 42611, 42613, 42584, -1, 42585, 42614, 42586, -1, 42613, 42614, 42585, -1, 42610, 42592, 42591, -1, 42615, 42592, 42616, -1, 42616, 42592, 42617, -1, 42586, 42618, 42587, -1, 42617, 42592, 42619, -1, 42619, 42592, 42620, -1, 42620, 42592, 42621, -1, 42621, 42592, 42610, -1, 42614, 42618, 42586, -1, 42606, 42622, 42615, -1, 42608, 42622, 42606, -1, 42618, 42623, 42587, -1, 42615, 42622, 42592, -1, 42624, 42622, 42608, -1, 42623, 42588, 42587, -1, 42625, 42626, 42624, -1, 42624, 42626, 42622, -1, 42627, 42628, 42625, -1, 42625, 42628, 42626, -1, 42579, 42597, 42612, -1, 42623, 42589, 42588, -1, 42627, 42629, 42628, -1, 42594, 42589, 42623, -1, 42630, 42631, 42632, -1, 42633, 42634, 42635, -1, 42636, 42632, 42637, -1, 42638, 42635, 42639, -1, 42638, 42639, 42640, -1, 42636, 42637, 42641, -1, 42596, 42595, 42642, -1, 42643, 42644, 42645, -1, 42646, 42647, 42648, -1, 42649, 42640, 42650, -1, 42646, 42648, 42651, -1, 42649, 42650, 42652, -1, 42643, 42641, 42644, -1, 42653, 42654, 42647, -1, 42655, 42645, 42656, -1, 42657, 42652, 42658, -1, 42655, 42656, 42659, -1, 42657, 42658, 42660, -1, 42653, 42647, 42646, -1, 42661, 42662, 42663, -1, 42664, 42665, 42666, -1, 42667, 42651, 42668, -1, 42664, 42613, 42611, -1, 42661, 42659, 42662, -1, 42664, 42611, 42665, -1, 42667, 42646, 42651, -1, 42664, 42666, 42669, -1, 42670, 42671, 42630, -1, 42672, 42669, 42673, -1, 42672, 42673, 42633, -1, 42670, 42604, 42605, -1, 42670, 42674, 42671, -1, 42675, 42676, 42654, -1, 42670, 42605, 42674, -1, 42677, 42632, 42636, -1, 42675, 42654, 42653, -1, 42678, 42653, 42646, -1, 42677, 42630, 42632, -1, 42678, 42646, 42667, -1, 42679, 42635, 42638, -1, 42679, 42633, 42635, -1, 42680, 42636, 42641, -1, 42680, 42641, 42643, -1, 42681, 42640, 42649, -1, 42681, 42638, 42640, -1, 42682, 42668, 42683, -1, 42684, 42643, 42645, -1, 42684, 42645, 42655, -1, 42609, 42612, 42685, -1, 42686, 42649, 42652, -1, 42682, 42667, 42668, -1, 42687, 42688, 42676, -1, 42686, 42652, 42657, -1, 42689, 42655, 42659, -1, 42690, 42660, 42691, -1, 42689, 42659, 42661, -1, 42687, 42676, 42675, -1, 42690, 42691, 42692, -1, 42693, 42653, 42678, -1, 42690, 42692, 42694, -1, 42690, 42657, 42660, -1, 42695, 42663, 42696, -1, 42697, 42613, 42664, -1, 42693, 42675, 42653, -1, 42697, 42664, 42669, -1, 42695, 42661, 42663, -1, 42697, 42614, 42613, -1, 42697, 42669, 42672, -1, 42698, 42672, 42633, -1, 42699, 42603, 42604, -1, 42700, 42678, 42667, -1, 42699, 42670, 42630, -1, 42700, 42667, 42682, -1, 42699, 42604, 42670, -1, 42699, 42630, 42677, -1, 42701, 42683, 42702, -1, 42698, 42633, 42679, -1, 42703, 42677, 42636, -1, 42704, 42638, 42681, -1, 42703, 42636, 42680, -1, 42701, 42682, 42683, -1, 42704, 42679, 42638, -1, 42705, 42706, 42688, -1, 42707, 42680, 42643, -1, 42707, 42643, 42684, -1, 42705, 42688, 42687, -1, 42708, 42681, 42649, -1, 42708, 42649, 42686, -1, 42709, 42690, 42694, -1, 42634, 42655, 42689, -1, 42709, 42694, 42710, -1, 42634, 42684, 42655, -1, 42631, 42675, 42693, -1, 42709, 42686, 42657, -1, 42631, 42687, 42675, -1, 42709, 42657, 42690, -1, 42637, 42693, 42678, -1, 42711, 42618, 42614, -1, 42711, 42672, 42698, -1, 42639, 42689, 42661, -1, 42711, 42614, 42697, -1, 42637, 42678, 42700, -1, 42711, 42697, 42672, -1, 42639, 42661, 42695, -1, 42712, 42698, 42679, -1, 42650, 42696, 42713, -1, 42644, 42700, 42682, -1, 42712, 42679, 42704, -1, 42644, 42682, 42701, -1, 42650, 42695, 42696, -1, 42714, 42607, 42603, -1, 42656, 42702, 42715, -1, 42716, 42704, 42681, -1, 42714, 42677, 42703, -1, 42714, 42603, 42699, -1, 42656, 42701, 42702, -1, 42716, 42681, 42708, -1, 42714, 42699, 42677, -1, 42717, 42710, 42718, -1, 42719, 42685, 42706, -1, 42717, 42709, 42710, -1, 42719, 42706, 42705, -1, 42717, 42708, 42686, -1, 42666, 42703, 42680, -1, 42719, 42609, 42685, -1, 42717, 42686, 42709, -1, 42666, 42680, 42707, -1, 42671, 42687, 42631, -1, 42720, 42698, 42712, -1, 42720, 42623, 42618, -1, 42671, 42705, 42687, -1, 42720, 42618, 42711, -1, 42673, 42707, 42684, -1, 42720, 42711, 42698, -1, 42673, 42684, 42634, -1, 42721, 42712, 42704, -1, 42721, 42704, 42716, -1, 42632, 42693, 42637, -1, 42635, 42634, 42689, -1, 42632, 42631, 42693, -1, 42635, 42689, 42639, -1, 42641, 42700, 42644, -1, 42722, 42718, 42723, -1, 42722, 42717, 42718, -1, 42722, 42716, 42708, -1, 42640, 42639, 42695, -1, 42641, 42637, 42700, -1, 42722, 42708, 42717, -1, 42645, 42644, 42701, -1, 42724, 42594, 42623, -1, 42640, 42695, 42650, -1, 42724, 42623, 42720, -1, 42724, 42712, 42721, -1, 42724, 42720, 42712, -1, 42645, 42701, 42656, -1, 42652, 42713, 42658, -1, 42725, 42723, 42726, -1, 42659, 42715, 42662, -1, 42652, 42650, 42713, -1, 42725, 42722, 42723, -1, 42725, 42721, 42716, -1, 42665, 42611, 42607, -1, 42725, 42716, 42722, -1, 42665, 42607, 42714, -1, 42727, 42721, 42725, -1, 42665, 42714, 42703, -1, 42727, 42724, 42721, -1, 42665, 42703, 42666, -1, 42659, 42656, 42715, -1, 42727, 42642, 42595, -1, 42727, 42726, 42642, -1, 42674, 42609, 42719, -1, 42727, 42595, 42594, -1, 42674, 42719, 42705, -1, 42727, 42594, 42724, -1, 42727, 42725, 42726, -1, 42669, 42666, 42707, -1, 42674, 42605, 42609, -1, 42674, 42705, 42671, -1, 42630, 42671, 42631, -1, 42669, 42707, 42673, -1, 42633, 42673, 42634, -1, 42728, 42692, 42729, -1, 42729, 42691, 42730, -1, 42692, 42691, 42729, -1, 42730, 42660, 42731, -1, 42691, 42660, 42730, -1, 42731, 42658, 42732, -1, 42660, 42658, 42731, -1, 42732, 42713, 42733, -1, 42658, 42713, 42732, -1, 42733, 42696, 42734, -1, 42713, 42696, 42733, -1, 42734, 42663, 42735, -1, 42696, 42663, 42734, -1, 42735, 42662, 42736, -1, 42663, 42662, 42735, -1, 42736, 42715, 42737, -1, 42662, 42715, 42736, -1, 42737, 42702, 42738, -1, 42715, 42702, 42737, -1, 42738, 42683, 42739, -1, 42702, 42683, 42738, -1, 42739, 42668, 42740, -1, 42683, 42668, 42739, -1, 42740, 42651, 42741, -1, 42668, 42651, 42740, -1, 42651, 42648, 42741, -1, 42648, 42742, 42741, -1, 42742, 42743, 42741, -1, 42743, 42742, 42744, -1, 42744, 42745, 42746, -1, 42742, 42745, 42744, -1, 42746, 42747, 42748, -1, 42745, 42747, 42746, -1, 42748, 42749, 42750, -1, 42747, 42749, 42748, -1, 42750, 42751, 42752, -1, 42749, 42751, 42750, -1, 42752, 42753, 42754, -1, 42751, 42753, 42752, -1, 42754, 42755, 42756, -1, 42753, 42755, 42754, -1, 42756, 42757, 42758, -1, 42755, 42757, 42756, -1, 42758, 42759, 42760, -1, 42757, 42759, 42758, -1, 42760, 42761, 42762, -1, 42759, 42761, 42760, -1, 42762, 42763, 42764, -1, 42761, 42763, 42762, -1, 42764, 42765, 42766, -1, 42763, 42765, 42764, -1, 42766, 42767, 42768, -1, 42765, 42767, 42766, -1, 42767, 42769, 42768, -1, 42728, 42769, 42692, -1, 42768, 42769, 42728, -1, 42770, 42596, 42642, -1, 42770, 42610, 42596, -1, 42771, 42642, 42726, -1, 42771, 42770, 42642, -1, 42772, 42726, 42723, -1, 42772, 42771, 42726, -1, 42773, 42723, 42718, -1, 42773, 42772, 42723, -1, 42774, 42718, 42710, -1, 42774, 42773, 42718, -1, 42775, 42710, 42694, -1, 42775, 42774, 42710, -1, 42769, 42694, 42692, -1, 42769, 42775, 42694, -1, 42685, 42612, 42597, -1, 42685, 42597, 42776, -1, 42706, 42776, 42777, -1, 42706, 42685, 42776, -1, 42688, 42777, 42778, -1, 42688, 42706, 42777, -1, 42676, 42778, 42779, -1, 42676, 42688, 42778, -1, 42654, 42779, 42780, -1, 42654, 42676, 42779, -1, 42647, 42780, 42781, -1, 42647, 42654, 42780, -1, 42648, 42781, 42742, -1, 42648, 42647, 42781, -1, 42782, 42783, 42784, -1, 42785, 42784, 42786, -1, 42787, 42788, 42789, -1, 42785, 42786, 42790, -1, 42791, 42789, 42792, -1, 42793, 42794, 42795, -1, 42597, 42598, 42776, -1, 42791, 42792, 42796, -1, 42797, 42796, 42798, -1, 42799, 42775, 42769, -1, 42793, 42790, 42794, -1, 42800, 42795, 42801, -1, 42799, 42769, 42767, -1, 42797, 42798, 42802, -1, 42803, 42774, 42775, -1, 42800, 42801, 42804, -1, 42805, 42804, 42749, -1, 42806, 42802, 42807, -1, 42805, 42749, 42747, -1, 42806, 42807, 42808, -1, 42803, 42775, 42799, -1, 42809, 42757, 42755, -1, 42810, 42767, 42765, -1, 42811, 42812, 42813, -1, 42811, 42606, 42615, -1, 42809, 42808, 42757, -1, 42810, 42799, 42767, -1, 42811, 42813, 42782, -1, 42811, 42615, 42812, -1, 42814, 42815, 42787, -1, 42816, 42773, 42774, -1, 42814, 42619, 42620, -1, 42814, 42620, 42817, -1, 42818, 42782, 42784, -1, 42814, 42817, 42815, -1, 42818, 42784, 42785, -1, 42819, 42785, 42790, -1, 42816, 42774, 42803, -1, 42819, 42790, 42793, -1, 42820, 42787, 42789, -1, 42820, 42789, 42791, -1, 42821, 42799, 42810, -1, 42822, 42796, 42797, -1, 42822, 42791, 42796, -1, 42821, 42803, 42799, -1, 42823, 42795, 42800, -1, 42824, 42810, 42765, -1, 42824, 42765, 42763, -1, 42825, 42797, 42802, -1, 42825, 42802, 42806, -1, 42823, 42793, 42795, -1, 42621, 42610, 42770, -1, 42826, 42773, 42816, -1, 42826, 42772, 42773, -1, 42827, 42800, 42804, -1, 42827, 42804, 42805, -1, 42828, 42806, 42808, -1, 42829, 42747, 42745, -1, 42828, 42808, 42809, -1, 42829, 42745, 42742, -1, 42829, 42742, 42781, -1, 42830, 42755, 42753, -1, 42831, 42803, 42821, -1, 42829, 42805, 42747, -1, 42832, 42606, 42811, -1, 42831, 42816, 42803, -1, 42830, 42809, 42755, -1, 42832, 42782, 42818, -1, 42832, 42602, 42606, -1, 42832, 42811, 42782, -1, 42833, 42785, 42819, -1, 42834, 42617, 42619, -1, 42835, 42821, 42810, -1, 42834, 42814, 42787, -1, 42834, 42619, 42814, -1, 42835, 42810, 42824, -1, 42834, 42787, 42820, -1, 42833, 42818, 42785, -1, 42836, 42820, 42791, -1, 42837, 42763, 42761, -1, 42838, 42819, 42793, -1, 42836, 42791, 42822, -1, 42837, 42824, 42763, -1, 42838, 42793, 42823, -1, 42839, 42771, 42772, -1, 42783, 42797, 42825, -1, 42783, 42822, 42797, -1, 42839, 42772, 42826, -1, 42840, 42823, 42800, -1, 42840, 42800, 42827, -1, 42841, 42829, 42781, -1, 42786, 42825, 42806, -1, 42841, 42781, 42780, -1, 42788, 42826, 42816, -1, 42786, 42806, 42828, -1, 42788, 42816, 42831, -1, 42841, 42827, 42805, -1, 42841, 42805, 42829, -1, 42842, 42818, 42833, -1, 42842, 42832, 42818, -1, 42792, 42831, 42821, -1, 42794, 42828, 42809, -1, 42842, 42601, 42602, -1, 42792, 42821, 42835, -1, 42842, 42602, 42832, -1, 42794, 42809, 42830, -1, 42843, 42833, 42819, -1, 42801, 42753, 42751, -1, 42798, 42835, 42824, -1, 42843, 42819, 42838, -1, 42801, 42830, 42753, -1, 42798, 42824, 42837, -1, 42807, 42761, 42759, -1, 42844, 42616, 42617, -1, 42844, 42617, 42834, -1, 42845, 42838, 42823, -1, 42844, 42820, 42836, -1, 42807, 42837, 42761, -1, 42845, 42823, 42840, -1, 42844, 42834, 42820, -1, 42846, 42780, 42779, -1, 42847, 42770, 42771, -1, 42846, 42840, 42827, -1, 42846, 42841, 42780, -1, 42813, 42836, 42822, -1, 42847, 42621, 42770, -1, 42846, 42827, 42841, -1, 42847, 42771, 42839, -1, 42813, 42822, 42783, -1, 42848, 42600, 42601, -1, 42815, 42839, 42826, -1, 42848, 42842, 42833, -1, 42848, 42833, 42843, -1, 42784, 42783, 42825, -1, 42848, 42601, 42842, -1, 42784, 42825, 42786, -1, 42815, 42826, 42788, -1, 42790, 42828, 42794, -1, 42789, 42788, 42831, -1, 42849, 42843, 42838, -1, 42789, 42831, 42792, -1, 42849, 42838, 42845, -1, 42790, 42786, 42828, -1, 42850, 42779, 42778, -1, 42850, 42846, 42779, -1, 42850, 42840, 42846, -1, 42850, 42845, 42840, -1, 42796, 42835, 42798, -1, 42796, 42792, 42835, -1, 42795, 42794, 42830, -1, 42851, 42599, 42600, -1, 42851, 42600, 42848, -1, 42795, 42830, 42801, -1, 42851, 42848, 42843, -1, 42851, 42843, 42849, -1, 42802, 42837, 42807, -1, 42852, 42849, 42845, -1, 42804, 42801, 42751, -1, 42802, 42798, 42837, -1, 42804, 42751, 42749, -1, 42852, 42778, 42777, -1, 42808, 42759, 42757, -1, 42852, 42845, 42850, -1, 42852, 42850, 42778, -1, 42812, 42615, 42616, -1, 42812, 42616, 42844, -1, 42853, 42776, 42598, -1, 42812, 42844, 42836, -1, 42853, 42777, 42776, -1, 42812, 42836, 42813, -1, 42808, 42807, 42759, -1, 42853, 42598, 42599, -1, 42853, 42599, 42851, -1, 42853, 42849, 42852, -1, 42817, 42621, 42847, -1, 42853, 42852, 42777, -1, 42817, 42847, 42839, -1, 42853, 42851, 42849, -1, 42817, 42620, 42621, -1, 42782, 42813, 42783, -1, 42817, 42839, 42815, -1, 42787, 42815, 42788, -1, 42573, 42574, 42592, -1, 42573, 42592, 42622, -1, 42575, 42573, 42622, -1, 42576, 42622, 42626, -1, 42576, 42575, 42622, -1, 42577, 42626, 42628, -1, 42577, 42576, 42626, -1, 42516, 42628, 42629, -1, 42516, 42629, 42854, -1, 42516, 42577, 42628, -1, 42514, 42854, 42855, -1, 42514, 42516, 42854, -1, 39206, 42855, 39216, -1, 39206, 42514, 42855, -1, 42593, 42537, 42535, -1, 42608, 42535, 42534, -1, 42608, 42593, 42535, -1, 42624, 42534, 42533, -1, 42624, 42608, 42534, -1, 42625, 42533, 42532, -1, 42625, 42624, 42533, -1, 42627, 42532, 42529, -1, 42627, 42625, 42532, -1, 42856, 42529, 42528, -1, 42856, 42627, 42529, -1, 42857, 42528, 39233, -1, 42857, 42856, 42528, -1, 39217, 42857, 39233, -1, 42629, 42627, 42856, -1, 42854, 42856, 42857, -1, 42854, 42629, 42856, -1, 42855, 42857, 39217, -1, 42855, 42854, 42857, -1, 39216, 42855, 39217, -1, 42858, 42859, 42860, -1, 42861, 30842, 30714, -1, 42861, 30832, 30842, -1, 42862, 42863, 42864, -1, 42861, 30714, 30715, -1, 42865, 42866, 42867, -1, 42861, 30715, 42868, -1, 42861, 42868, 42869, -1, 42861, 42870, 30832, -1, 42861, 42869, 42870, -1, 42865, 42871, 42866, -1, 42872, 42873, 42874, -1, 42862, 42860, 42863, -1, 42875, 42864, 42876, -1, 30712, 30714, 30842, -1, 42877, 30825, 30824, -1, 42872, 42867, 42873, -1, 42875, 42876, 42878, -1, 42879, 42874, 42880, -1, 42877, 30824, 39729, -1, 42881, 42882, 42883, -1, 42879, 42880, 42884, -1, 42885, 30836, 30825, -1, 42881, 42878, 42882, -1, 42886, 42884, 42887, -1, 42886, 42887, 42888, -1, 42885, 30825, 42877, -1, 42889, 42883, 42890, -1, 42889, 42890, 42891, -1, 42892, 39729, 39728, -1, 42893, 42888, 39720, -1, 42894, 39724, 39723, -1, 42893, 39720, 39719, -1, 42892, 42877, 39729, -1, 42894, 42891, 39724, -1, 42895, 30844, 30836, -1, 42896, 42871, 42865, -1, 42897, 30741, 30723, -1, 42897, 30723, 42858, -1, 42896, 30737, 30738, -1, 42897, 42858, 42860, -1, 42896, 30738, 42898, -1, 42897, 42860, 42862, -1, 42895, 30836, 42885, -1, 42896, 42898, 42871, -1, 42899, 42867, 42872, -1, 42900, 42864, 42875, -1, 42901, 42885, 42877, -1, 42901, 42877, 42892, -1, 42899, 42865, 42867, -1, 42900, 42862, 42864, -1, 42902, 42872, 42874, -1, 42902, 42874, 42879, -1, 42903, 39728, 39727, -1, 42904, 42875, 42878, -1, 42904, 42878, 42881, -1, 42905, 42884, 42886, -1, 42903, 42892, 39728, -1, 42906, 30844, 42895, -1, 42907, 42881, 42883, -1, 42906, 30846, 30844, -1, 42907, 42883, 42889, -1, 42905, 42879, 42884, -1, 42908, 42886, 42888, -1, 42909, 42885, 42901, -1, 42910, 42891, 42894, -1, 42908, 42888, 42893, -1, 42910, 42889, 42891, -1, 42909, 42895, 42885, -1, 42911, 39719, 39718, -1, 42911, 39718, 30775, -1, 42911, 30775, 30781, -1, 42912, 39723, 39722, -1, 42911, 42893, 39719, -1, 42913, 42901, 42892, -1, 42914, 30737, 42896, -1, 42912, 42894, 39723, -1, 42913, 42892, 42903, -1, 42914, 30721, 30737, -1, 42915, 30740, 30741, -1, 42914, 42865, 42899, -1, 42915, 30741, 42897, -1, 42916, 39727, 39726, -1, 42915, 42897, 42862, -1, 42914, 42896, 42865, -1, 42915, 42862, 42900, -1, 42917, 42900, 42875, -1, 42916, 42903, 39727, -1, 42918, 42872, 42902, -1, 42859, 30761, 30846, -1, 42918, 42899, 42872, -1, 42917, 42875, 42904, -1, 42919, 42902, 42879, -1, 42919, 42879, 42905, -1, 42866, 42881, 42907, -1, 42859, 30846, 42906, -1, 42866, 42904, 42881, -1, 42920, 42905, 42886, -1, 42863, 42906, 42895, -1, 42863, 42895, 42909, -1, 42873, 42907, 42889, -1, 42873, 42889, 42910, -1, 42920, 42886, 42908, -1, 42876, 42901, 42913, -1, 42921, 42911, 30781, -1, 42921, 30781, 30790, -1, 42876, 42909, 42901, -1, 42921, 42908, 42893, -1, 42921, 42893, 42911, -1, 42880, 42910, 42894, -1, 42922, 30719, 30721, -1, 42882, 42913, 42903, -1, 42922, 42914, 42899, -1, 42880, 42894, 42912, -1, 42922, 42899, 42918, -1, 42882, 42903, 42916, -1, 42922, 30721, 42914, -1, 42887, 39722, 39721, -1, 42890, 39726, 39725, -1, 42923, 42902, 42919, -1, 42923, 42918, 42902, -1, 42887, 42912, 39722, -1, 42890, 42916, 39726, -1, 42924, 30740, 42915, -1, 42924, 30739, 30740, -1, 42925, 42919, 42905, -1, 42924, 42900, 42917, -1, 42926, 30762, 30761, -1, 42926, 30725, 30762, -1, 42924, 42915, 42900, -1, 42926, 30724, 30725, -1, 42926, 30761, 42859, -1, 42925, 42905, 42920, -1, 42860, 42906, 42863, -1, 42871, 42917, 42904, -1, 42871, 42904, 42866, -1, 42927, 30790, 30805, -1, 42860, 42859, 42906, -1, 42927, 42921, 30790, -1, 42927, 42920, 42908, -1, 42927, 42908, 42921, -1, 42867, 42866, 42907, -1, 42867, 42907, 42873, -1, 42928, 30719, 42922, -1, 42928, 30718, 30719, -1, 42928, 42922, 42918, -1, 42864, 42863, 42909, -1, 42928, 42918, 42923, -1, 42874, 42873, 42910, -1, 42864, 42909, 42876, -1, 42874, 42910, 42880, -1, 42878, 42876, 42913, -1, 42869, 42923, 42919, -1, 42878, 42913, 42882, -1, 42869, 42919, 42925, -1, 42929, 30805, 30816, -1, 42929, 42927, 30805, -1, 42929, 42925, 42920, -1, 42929, 42920, 42927, -1, 42884, 42880, 42912, -1, 42883, 42916, 42890, -1, 42884, 42912, 42887, -1, 42883, 42882, 42916, -1, 42891, 39725, 39724, -1, 42868, 30715, 30718, -1, 42868, 30718, 42928, -1, 42888, 39721, 39720, -1, 42868, 42928, 42923, -1, 42868, 42923, 42869, -1, 42888, 42887, 39721, -1, 42870, 42929, 30816, -1, 42891, 42890, 39725, -1, 42898, 30738, 30739, -1, 42858, 42926, 42859, -1, 42870, 30816, 30832, -1, 42898, 30739, 42924, -1, 42870, 42869, 42925, -1, 42898, 42924, 42917, -1, 42858, 30723, 30724, -1, 42870, 42925, 42929, -1, 42898, 42917, 42871, -1, 42858, 30724, 42926, -1, 42930, 42931, 42932, -1, 42933, 39091, 38995, -1, 42933, 39112, 39091, -1, 42934, 42935, 42936, -1, 42933, 38995, 39026, -1, 42937, 42938, 42939, -1, 42933, 42940, 39112, -1, 42933, 39026, 42941, -1, 42933, 42941, 42942, -1, 42933, 42942, 42940, -1, 42937, 42943, 42938, -1, 42944, 42945, 42946, -1, 42934, 42932, 42935, -1, 42947, 42936, 42948, -1, 38994, 38995, 39091, -1, 42949, 39102, 39101, -1, 42944, 42939, 42945, -1, 42947, 42948, 42950, -1, 42951, 42946, 42952, -1, 42949, 39101, 39798, -1, 42953, 42954, 42955, -1, 42951, 42952, 42956, -1, 42957, 39115, 39102, -1, 42953, 42950, 42954, -1, 42958, 42956, 42959, -1, 42958, 42959, 42960, -1, 42957, 39102, 42949, -1, 42961, 42955, 42962, -1, 42961, 42962, 42963, -1, 42964, 39798, 39797, -1, 42965, 42960, 39789, -1, 42966, 39793, 39792, -1, 42965, 39789, 39788, -1, 42964, 42949, 39798, -1, 42966, 42963, 39793, -1, 42967, 39122, 39115, -1, 42968, 42943, 42937, -1, 42969, 39009, 39013, -1, 42969, 39013, 42930, -1, 42968, 39018, 39016, -1, 42969, 42930, 42932, -1, 42968, 39016, 42970, -1, 42969, 42932, 42934, -1, 42967, 39115, 42957, -1, 42968, 42970, 42943, -1, 42971, 42939, 42944, -1, 42972, 42936, 42947, -1, 42973, 42957, 42949, -1, 42973, 42949, 42964, -1, 42971, 42937, 42939, -1, 42972, 42934, 42936, -1, 42974, 42944, 42946, -1, 42974, 42946, 42951, -1, 42975, 39797, 39796, -1, 42976, 42947, 42950, -1, 42976, 42950, 42953, -1, 42977, 42956, 42958, -1, 42975, 42964, 39797, -1, 42978, 39122, 42967, -1, 42979, 42953, 42955, -1, 42978, 39124, 39122, -1, 42979, 42955, 42961, -1, 42977, 42951, 42956, -1, 42980, 42958, 42960, -1, 42981, 42957, 42973, -1, 42982, 42963, 42966, -1, 42980, 42960, 42965, -1, 42982, 42961, 42963, -1, 42981, 42967, 42957, -1, 42983, 39788, 39787, -1, 42983, 39787, 39054, -1, 42983, 39054, 39057, -1, 42984, 39792, 39791, -1, 42983, 42965, 39788, -1, 42985, 42973, 42964, -1, 42986, 39018, 42968, -1, 42984, 42966, 39792, -1, 42985, 42964, 42975, -1, 42986, 39020, 39018, -1, 42987, 39010, 39009, -1, 42986, 42937, 42971, -1, 42987, 39009, 42969, -1, 42988, 39796, 39795, -1, 42987, 42969, 42934, -1, 42986, 42968, 42937, -1, 42987, 42934, 42972, -1, 42989, 42972, 42947, -1, 42988, 42975, 39796, -1, 42990, 42944, 42974, -1, 42931, 39034, 39124, -1, 42990, 42971, 42944, -1, 42989, 42947, 42976, -1, 42991, 42974, 42951, -1, 42991, 42951, 42977, -1, 42938, 42953, 42979, -1, 42931, 39124, 42978, -1, 42938, 42976, 42953, -1, 42992, 42977, 42958, -1, 42935, 42978, 42967, -1, 42935, 42967, 42981, -1, 42945, 42979, 42961, -1, 42945, 42961, 42982, -1, 42992, 42958, 42980, -1, 42948, 42973, 42985, -1, 42993, 42983, 39057, -1, 42993, 39057, 39065, -1, 42948, 42981, 42973, -1, 42993, 42980, 42965, -1, 42993, 42965, 42983, -1, 42952, 42982, 42966, -1, 42994, 39022, 39020, -1, 42954, 42985, 42975, -1, 42994, 42986, 42971, -1, 42952, 42966, 42984, -1, 42994, 42971, 42990, -1, 42954, 42975, 42988, -1, 42994, 39020, 42986, -1, 42959, 39791, 39790, -1, 42962, 39795, 39794, -1, 42995, 42974, 42991, -1, 42995, 42990, 42974, -1, 42959, 42984, 39791, -1, 42962, 42988, 39795, -1, 42996, 39010, 42987, -1, 42996, 39014, 39010, -1, 42997, 42991, 42977, -1, 42996, 42972, 42989, -1, 42998, 39035, 39034, -1, 42998, 39017, 39035, -1, 42996, 42987, 42972, -1, 42998, 39015, 39017, -1, 42998, 39034, 42931, -1, 42997, 42977, 42992, -1, 42932, 42978, 42935, -1, 42943, 42989, 42976, -1, 42943, 42976, 42938, -1, 42999, 39065, 39081, -1, 42932, 42931, 42978, -1, 42999, 42993, 39065, -1, 42999, 42992, 42980, -1, 42999, 42980, 42993, -1, 42939, 42938, 42979, -1, 42939, 42979, 42945, -1, 43000, 39022, 42994, -1, 43000, 39024, 39022, -1, 43000, 42994, 42990, -1, 42936, 42935, 42981, -1, 43000, 42990, 42995, -1, 42946, 42945, 42982, -1, 42936, 42981, 42948, -1, 42946, 42982, 42952, -1, 42950, 42948, 42985, -1, 42942, 42995, 42991, -1, 42950, 42985, 42954, -1, 42942, 42991, 42997, -1, 43001, 39081, 39093, -1, 43001, 42999, 39081, -1, 43001, 42997, 42992, -1, 43001, 42992, 42999, -1, 42956, 42952, 42984, -1, 42955, 42988, 42962, -1, 42956, 42984, 42959, -1, 42955, 42954, 42988, -1, 42963, 39794, 39793, -1, 42941, 39026, 39024, -1, 42941, 39024, 43000, -1, 42960, 39790, 39789, -1, 42941, 43000, 42995, -1, 42941, 42995, 42942, -1, 42960, 42959, 39790, -1, 42963, 42962, 39794, -1, 42940, 39093, 39112, -1, 42970, 39016, 39014, -1, 42930, 42998, 42931, -1, 42970, 39014, 42996, -1, 42940, 43001, 39093, -1, 42940, 42942, 42997, -1, 42970, 42996, 42989, -1, 42930, 39013, 39015, -1, 42940, 42997, 43001, -1, 42970, 42989, 42943, -1, 42930, 39015, 42998, -1, 43002, 30201, 43003, -1, 43004, 43005, 43006, -1, 43002, 38695, 38674, -1, 43007, 43008, 43009, -1, 43010, 43011, 43012, -1, 43002, 38674, 30203, -1, 43002, 30203, 30202, -1, 43002, 30202, 30201, -1, 43007, 43013, 43008, -1, 43002, 43003, 43014, -1, 43002, 43015, 38695, -1, 43002, 43014, 43015, -1, 43016, 43009, 43017, -1, 43010, 43012, 43018, -1, 43019, 43018, 43020, -1, 43016, 43017, 43021, -1, 43022, 43021, 43023, -1, 43019, 43020, 43024, -1, 43025, 38684, 38682, -1, 43026, 43024, 43027, -1, 43025, 38682, 39746, -1, 43022, 43023, 43028, -1, 43026, 43027, 43029, -1, 43030, 38698, 38684, -1, 43031, 43032, 43033, -1, 43034, 43035, 43036, -1, 43030, 38684, 43025, -1, 43031, 43028, 43032, -1, 43034, 43029, 43035, -1, 43037, 43033, 39744, -1, 43037, 39744, 39743, -1, 43038, 39750, 39752, -1, 43039, 39746, 39738, -1, 43038, 43036, 39750, -1, 43039, 43025, 39746, -1, 43040, 43013, 43007, -1, 43041, 43004, 43011, -1, 43042, 38706, 38698, -1, 43040, 30197, 30196, -1, 43041, 30193, 30192, -1, 43041, 43011, 43010, -1, 43040, 30196, 43043, -1, 43041, 30192, 43004, -1, 43040, 43043, 43013, -1, 43042, 38698, 43030, -1, 43044, 43018, 43019, -1, 43045, 43030, 43025, -1, 43046, 43009, 43016, -1, 43045, 43025, 43039, -1, 43044, 43010, 43018, -1, 43046, 43007, 43009, -1, 43047, 43024, 43026, -1, 43048, 43021, 43022, -1, 43047, 43019, 43024, -1, 43049, 39738, 39732, -1, 43048, 43016, 43021, -1, 43050, 43026, 43029, -1, 30191, 30190, 38636, -1, 43051, 43022, 43028, -1, 43049, 43039, 39738, -1, 43051, 43028, 43031, -1, 43050, 43029, 43034, -1, 43052, 38706, 43042, -1, 43052, 38709, 38706, -1, 43053, 43033, 43037, -1, 43053, 43031, 43033, -1, 43054, 43030, 43045, -1, 43055, 43034, 43036, -1, 43055, 43036, 43038, -1, 43056, 39743, 39745, -1, 43056, 39745, 38639, -1, 43057, 39752, 39754, -1, 43054, 43042, 43030, -1, 43056, 38639, 38641, -1, 43057, 43038, 39752, -1, 43056, 43037, 39743, -1, 43058, 43045, 43039, -1, 43059, 43040, 43007, -1, 43059, 43007, 43046, -1, 43058, 43039, 43049, -1, 43060, 30194, 30193, -1, 43059, 30198, 30197, -1, 43060, 30193, 43041, -1, 43060, 43041, 43010, -1, 43061, 39732, 39736, -1, 43059, 30197, 43040, -1, 43060, 43010, 43044, -1, 43061, 43049, 39732, -1, 43062, 43019, 43047, -1, 43063, 43016, 43048, -1, 43062, 43044, 43019, -1, 43006, 38710, 38709, -1, 43063, 43046, 43016, -1, 43064, 43022, 43051, -1, 43008, 43047, 43026, -1, 43006, 38709, 43052, -1, 43064, 43048, 43022, -1, 43008, 43026, 43050, -1, 43012, 43052, 43042, -1, 43012, 43042, 43054, -1, 43017, 43034, 43055, -1, 43017, 43050, 43034, -1, 43065, 43031, 43053, -1, 43065, 43051, 43031, -1, 43020, 43054, 43045, -1, 43066, 43056, 38641, -1, 43066, 38641, 38649, -1, 43020, 43045, 43058, -1, 43066, 43053, 43037, -1, 43066, 43037, 43056, -1, 43023, 43055, 43038, -1, 43023, 43038, 43057, -1, 43067, 30199, 30198, -1, 43027, 43058, 43049, -1, 43067, 30198, 43059, -1, 43067, 43046, 43063, -1, 43067, 43059, 43046, -1, 43032, 39754, 39756, -1, 43027, 43049, 43061, -1, 43068, 43063, 43048, -1, 43035, 39736, 39740, -1, 43068, 43048, 43064, -1, 43032, 43057, 39754, -1, 43035, 43061, 39736, -1, 43069, 30195, 30194, -1, 43069, 30194, 43060, -1, 43069, 43060, 43044, -1, 43069, 43044, 43062, -1, 43005, 38636, 38710, -1, 43070, 43064, 43051, -1, 43005, 38710, 43006, -1, 43005, 30191, 38636, -1, 43070, 43051, 43065, -1, 43013, 43062, 43047, -1, 43011, 43052, 43012, -1, 43071, 38649, 38666, -1, 43071, 43066, 38649, -1, 43013, 43047, 43008, -1, 43011, 43006, 43052, -1, 43071, 43065, 43053, -1, 43071, 43053, 43066, -1, 43009, 43008, 43050, -1, 43072, 30199, 43067, -1, 43009, 43050, 43017, -1, 43072, 30200, 30199, -1, 43072, 43067, 43063, -1, 43018, 43054, 43020, -1, 43072, 43063, 43068, -1, 43018, 43012, 43054, -1, 43021, 43017, 43055, -1, 43014, 43064, 43070, -1, 43021, 43055, 43023, -1, 43024, 43020, 43058, -1, 43014, 43068, 43064, -1, 43024, 43058, 43027, -1, 43028, 43057, 43032, -1, 43029, 43061, 43035, -1, 43028, 43023, 43057, -1, 43073, 38666, 38678, -1, 43073, 43071, 38666, -1, 43073, 43070, 43065, -1, 43073, 43065, 43071, -1, 43029, 43027, 43061, -1, 43036, 39740, 39750, -1, 43033, 39756, 39744, -1, 43003, 30201, 30200, -1, 43003, 30200, 43072, -1, 43003, 43072, 43068, -1, 43033, 43032, 39756, -1, 43003, 43068, 43014, -1, 43036, 43035, 39740, -1, 43015, 38678, 38695, -1, 43004, 30191, 43005, -1, 43043, 30196, 30195, -1, 43004, 43006, 43011, -1, 43015, 43073, 38678, -1, 43043, 30195, 43069, -1, 43043, 43062, 43013, -1, 43015, 43014, 43070, -1, 43043, 43069, 43062, -1, 43004, 30192, 30191, -1, 43015, 43070, 43073, -1, 43074, 32703, 30289, -1, 43075, 43076, 43077, -1, 43074, 32722, 32703, -1, 43074, 30289, 30288, -1, 43074, 30288, 43078, -1, 43079, 43077, 43080, -1, 43074, 43081, 32722, -1, 43074, 43078, 43082, -1, 43074, 43082, 43081, -1, 43083, 43084, 43085, -1, 43079, 43080, 43086, -1, 43087, 43086, 43088, -1, 43089, 43090, 43091, -1, 30290, 30289, 32703, -1, 32593, 32711, 32578, -1, 43089, 43091, 43092, -1, 43087, 43088, 43093, -1, 43094, 43092, 43095, -1, 43094, 43095, 43096, -1, 43097, 32711, 32593, -1, 43098, 43099, 43100, -1, 43101, 32725, 32711, -1, 43098, 43093, 43099, -1, 43102, 43096, 43103, -1, 43102, 43103, 43104, -1, 43101, 32711, 43097, -1, 43105, 43100, 43106, -1, 43105, 43106, 43107, -1, 43108, 32593, 32600, -1, 43109, 43104, 32599, -1, 43110, 32548, 32547, -1, 43109, 32599, 32594, -1, 43108, 43097, 32593, -1, 43110, 43107, 32548, -1, 43111, 32733, 32725, -1, 43112, 43084, 43083, -1, 43112, 43113, 43084, -1, 43114, 43077, 43079, -1, 43112, 30283, 43113, -1, 43112, 30284, 30283, -1, 43114, 30280, 30279, -1, 43114, 30279, 43075, -1, 43111, 32725, 43101, -1, 43114, 43075, 43077, -1, 43115, 43086, 43087, -1, 43116, 43090, 43089, -1, 43117, 43097, 43108, -1, 43116, 43083, 43090, -1, 43115, 43079, 43086, -1, 43118, 43089, 43092, -1, 43117, 43101, 43097, -1, 43119, 32600, 32556, -1, 43120, 43087, 43093, -1, 43120, 43093, 43098, -1, 43118, 43092, 43094, -1, 43119, 43108, 32600, -1, 43121, 43094, 43096, -1, 43122, 32737, 32733, -1, 43123, 43098, 43100, -1, 43122, 32733, 43111, -1, 43123, 43100, 43105, -1, 43121, 43096, 43102, -1, 43124, 43102, 43104, -1, 43125, 43105, 43107, -1, 43125, 43107, 43110, -1, 43126, 43101, 43117, -1, 43124, 43104, 43109, -1, 43127, 32594, 32586, -1, 43126, 43111, 43101, -1, 43127, 32586, 32579, -1, 43128, 32547, 32608, -1, 43127, 32579, 32671, -1, 43127, 43109, 32594, -1, 43128, 43110, 32547, -1, 43129, 43112, 43083, -1, 43130, 43108, 43119, -1, 43129, 43083, 43116, -1, 43130, 43117, 43108, -1, 43129, 30284, 43112, -1, 43131, 30281, 30280, -1, 43129, 30285, 30284, -1, 43131, 43114, 43079, -1, 43132, 32556, 32550, -1, 43131, 30280, 43114, -1, 43131, 43079, 43115, -1, 43133, 43089, 43118, -1, 43132, 43119, 32556, -1, 43133, 43116, 43089, -1, 43134, 43115, 43087, -1, 43076, 32643, 32737, -1, 43134, 43087, 43120, -1, 43135, 43094, 43121, -1, 43076, 32737, 43122, -1, 43085, 43098, 43123, -1, 43085, 43120, 43098, -1, 43135, 43118, 43094, -1, 43136, 43121, 43102, -1, 43080, 43122, 43111, -1, 43080, 43111, 43126, -1, 43091, 43105, 43125, -1, 43088, 43126, 43117, -1, 43091, 43123, 43105, -1, 43136, 43102, 43124, -1, 43137, 43127, 32671, -1, 43137, 32671, 32679, -1, 43088, 43117, 43130, -1, 43137, 43124, 43109, -1, 43137, 43109, 43127, -1, 43095, 43125, 43110, -1, 43095, 43110, 43128, -1, 43099, 43130, 43119, -1, 43138, 30286, 30285, -1, 43138, 30285, 43129, -1, 43138, 43116, 43133, -1, 43103, 32608, 32604, -1, 43099, 43119, 43132, -1, 43138, 43129, 43116, -1, 43106, 32550, 32549, -1, 43139, 43133, 43118, -1, 43103, 43128, 32608, -1, 43139, 43118, 43135, -1, 43140, 30282, 30281, -1, 43106, 43132, 32550, -1, 43140, 30281, 43131, -1, 43141, 32644, 32643, -1, 43140, 43131, 43115, -1, 43141, 30277, 32644, -1, 43140, 43115, 43134, -1, 43142, 43135, 43121, -1, 43141, 30278, 30277, -1, 43141, 32643, 43076, -1, 43142, 43121, 43136, -1, 43143, 32679, 32694, -1, 43084, 43134, 43120, -1, 43084, 43120, 43085, -1, 43143, 43136, 43124, -1, 43077, 43076, 43122, -1, 43143, 43137, 32679, -1, 43077, 43122, 43080, -1, 43143, 43124, 43137, -1, 43144, 30286, 43138, -1, 43090, 43085, 43123, -1, 43144, 30287, 30286, -1, 43090, 43123, 43091, -1, 43086, 43080, 43126, -1, 43144, 43138, 43133, -1, 43086, 43126, 43088, -1, 43144, 43133, 43139, -1, 43082, 43135, 43142, -1, 43093, 43130, 43099, -1, 43092, 43091, 43125, -1, 43092, 43125, 43095, -1, 43093, 43088, 43130, -1, 43082, 43139, 43135, -1, 43145, 32694, 32705, -1, 43145, 43136, 43143, -1, 43145, 43143, 32694, -1, 43100, 43132, 43106, -1, 43096, 43095, 43128, -1, 43145, 43142, 43136, -1, 43100, 43099, 43132, -1, 43096, 43128, 43103, -1, 43107, 32549, 32548, -1, 43078, 30288, 30287, -1, 43104, 43103, 32604, -1, 43078, 30287, 43144, -1, 43104, 32604, 32599, -1, 43078, 43144, 43139, -1, 43078, 43139, 43082, -1, 43113, 30282, 43140, -1, 43107, 43106, 32549, -1, 43081, 32705, 32722, -1, 43113, 30283, 30282, -1, 43075, 30278, 43141, -1, 43075, 43141, 43076, -1, 43081, 43145, 32705, -1, 43113, 43140, 43134, -1, 43081, 43082, 43142, -1, 43113, 43134, 43084, -1, 43075, 30279, 30278, -1, 43081, 43142, 43145, -1, 43083, 43085, 43090, -1, 43146, 43147, 43148, -1, 43146, 43148, 43149, -1, 43150, 33018, 33020, -1, 43150, 33020, 33007, -1, 43150, 33007, 38144, -1, 43150, 43149, 33018, -1, 43151, 32743, 32742, -1, 43151, 32742, 43152, -1, 43151, 43152, 43147, -1, 43151, 43147, 43146, -1, 43153, 38144, 38145, -1, 43153, 43146, 43149, -1, 43153, 43150, 38144, -1, 43153, 43149, 43150, -1, 43154, 38145, 38146, -1, 43154, 32744, 32743, -1, 43154, 43146, 43153, -1, 43154, 38146, 32744, -1, 43154, 32743, 43151, -1, 43154, 43153, 38145, -1, 43154, 43151, 43146, -1, 32739, 32738, 33045, -1, 32745, 32744, 38146, -1, 43155, 33038, 33021, -1, 43155, 33021, 33019, -1, 43156, 33043, 33038, -1, 43156, 33038, 43155, -1, 43157, 33019, 33017, -1, 43157, 43155, 33019, -1, 43158, 33045, 33043, -1, 43158, 32739, 33045, -1, 43158, 33043, 43156, -1, 43159, 43155, 43157, -1, 43159, 43156, 43155, -1, 43160, 33017, 33016, -1, 43160, 43157, 33017, -1, 43161, 32740, 32739, -1, 43161, 43156, 43159, -1, 43161, 32739, 43158, -1, 43161, 43158, 43156, -1, 43162, 43159, 43157, -1, 43162, 43157, 43160, -1, 43148, 33016, 33015, -1, 43148, 43160, 33016, -1, 43163, 32741, 32740, -1, 43163, 32740, 43161, -1, 43163, 43161, 43159, -1, 43163, 43159, 43162, -1, 43147, 43162, 43160, -1, 43147, 43160, 43148, -1, 43149, 33015, 33018, -1, 43149, 43148, 33015, -1, 43152, 32742, 32741, -1, 43152, 32741, 43163, -1, 43152, 43163, 43162, -1, 43152, 43162, 43147, -1, 43164, 43165, 43166, -1, 43166, 43165, 43167, -1, 43167, 43168, 43169, -1, 43169, 43168, 43170, -1, 32581, 43171, 32582, -1, 32588, 43171, 32581, -1, 32582, 43171, 32629, -1, 43170, 43171, 32588, -1, 39815, 43172, 39814, -1, 43167, 43172, 43168, -1, 39814, 43172, 43165, -1, 43165, 43172, 43167, -1, 32629, 43173, 32631, -1, 43171, 43173, 32629, -1, 43168, 43173, 43170, -1, 43170, 43173, 43171, -1, 39816, 43174, 39815, -1, 32636, 43174, 39816, -1, 32631, 43174, 32637, -1, 32637, 43174, 32636, -1, 39815, 43174, 43172, -1, 43173, 43174, 32631, -1, 33060, 39811, 38189, -1, 43172, 43174, 43168, -1, 43168, 43174, 43173, -1, 38191, 43175, 32545, -1, 32545, 43175, 32546, -1, 38190, 43176, 38191, -1, 38191, 43176, 43175, -1, 32546, 43177, 32607, -1, 43175, 43177, 32546, -1, 38189, 43178, 38190, -1, 39811, 43178, 38189, -1, 38190, 43178, 43176, -1, 43175, 43179, 43177, -1, 43176, 43179, 43175, -1, 32607, 43180, 32602, -1, 43177, 43180, 32607, -1, 39812, 43181, 39811, -1, 39811, 43181, 43178, -1, 43178, 43181, 43176, -1, 43176, 43181, 43179, -1, 43179, 43166, 43177, -1, 43177, 43166, 43180, -1, 32602, 43169, 32596, -1, 43180, 43169, 32602, -1, 39813, 43164, 39812, -1, 39812, 43164, 43181, -1, 43179, 43164, 43166, -1, 43181, 43164, 43179, -1, 43180, 43167, 43169, -1, 43166, 43167, 43180, -1, 32596, 43170, 32588, -1, 43169, 43170, 32596, -1, 39814, 43165, 39813, -1, 39813, 43165, 43164, -1, 39749, 41352, 39735, -1, 39735, 41352, 43182, -1, 43182, 41349, 43183, -1, 41352, 41349, 43182, -1, 41349, 41348, 43183, -1, 43183, 41350, 43184, -1, 41348, 41350, 43183, -1, 43184, 41351, 41365, -1, 41350, 41351, 43184, -1, 41351, 41347, 41365, -1, 43185, 43186, 39737, -1, 43184, 43187, 43183, -1, 41385, 43188, 41383, -1, 43183, 43187, 43189, -1, 41383, 43188, 43190, -1, 43191, 43188, 43192, -1, 43190, 43188, 43191, -1, 43193, 43194, 43195, -1, 43196, 43197, 43198, -1, 43189, 43194, 43193, -1, 43192, 43197, 43185, -1, 43186, 43197, 43196, -1, 39731, 43199, 39757, -1, 43185, 43197, 43186, -1, 43200, 43201, 41387, -1, 43198, 43201, 43200, -1, 43195, 43199, 39731, -1, 41387, 43201, 41385, -1, 43187, 43202, 43189, -1, 43188, 43201, 43192, -1, 41367, 43202, 41364, -1, 43192, 43201, 43197, -1, 41385, 43201, 43188, -1, 43197, 43201, 43198, -1, 43189, 43202, 43194, -1, 41364, 43202, 43187, -1, 43194, 43203, 43195, -1, 43195, 43203, 43199, -1, 39757, 43204, 39755, -1, 43199, 43204, 39757, -1, 41369, 43205, 41367, -1, 41367, 43205, 43202, -1, 43194, 43205, 43203, -1, 43202, 43205, 43194, -1, 43199, 43206, 43204, -1, 43203, 43206, 43199, -1, 39755, 43207, 39753, -1, 43204, 43207, 39755, -1, 41371, 43208, 41369, -1, 43205, 43208, 43203, -1, 41369, 43208, 43205, -1, 43203, 43208, 43206, -1, 43206, 43209, 43204, -1, 43204, 43209, 43207, -1, 39753, 43210, 39751, -1, 43207, 43210, 39753, -1, 41373, 43211, 41371, -1, 43206, 43211, 43209, -1, 41371, 43211, 43208, -1, 43208, 43211, 43206, -1, 43207, 43212, 43210, -1, 43209, 43212, 43207, -1, 43210, 43213, 39751, -1, 39751, 43213, 39747, -1, 41373, 43214, 43211, -1, 43211, 43214, 43209, -1, 41375, 43214, 41373, -1, 43209, 43214, 43212, -1, 43212, 43215, 43210, -1, 43210, 43215, 43213, -1, 39747, 43216, 39739, -1, 43213, 43216, 39747, -1, 43212, 43217, 43215, -1, 41375, 43217, 43214, -1, 41377, 43217, 41375, -1, 43214, 43217, 43212, -1, 43215, 43218, 43213, -1, 43213, 43218, 43216, -1, 39739, 43219, 39733, -1, 43216, 43219, 39739, -1, 43217, 43220, 43215, -1, 41379, 43220, 41377, -1, 43215, 43220, 43218, -1, 41377, 43220, 43217, -1, 43218, 43221, 43216, -1, 43216, 43221, 43219, -1, 39733, 43222, 39734, -1, 43219, 43222, 39733, -1, 41381, 43223, 41379, -1, 41379, 43223, 43220, -1, 43218, 43223, 43221, -1, 43220, 43223, 43218, -1, 43221, 43191, 43219, -1, 43219, 43191, 43222, -1, 39734, 43185, 39737, -1, 41387, 41361, 43200, -1, 43222, 43185, 39734, -1, 39735, 43193, 39730, -1, 41383, 43190, 41381, -1, 43182, 43193, 39735, -1, 41381, 43190, 43223, -1, 43223, 43190, 43221, -1, 43221, 43190, 43191, -1, 43183, 43189, 43182, -1, 43191, 43192, 43222, -1, 43182, 43189, 43193, -1, 43222, 43192, 43185, -1, 39730, 43195, 39731, -1, 39741, 43186, 39748, -1, 39737, 43186, 39741, -1, 43193, 43195, 39730, -1, 39748, 43186, 43196, -1, 41364, 43187, 41365, -1, 41365, 43187, 43184, -1, 39742, 39748, 41344, -1, 41343, 43196, 41342, -1, 41344, 43196, 41343, -1, 39748, 43196, 41344, -1, 41342, 43198, 41338, -1, 43196, 43198, 41342, -1, 41337, 43200, 41335, -1, 41338, 43200, 41337, -1, 43198, 43200, 41338, -1, 43200, 41361, 41335, -1, 41331, 41362, 43224, -1, 41329, 43224, 43225, -1, 41329, 43225, 43226, -1, 41329, 41331, 43224, -1, 41321, 43226, 41312, -1, 41321, 41329, 43226, -1, 43227, 41388, 41386, -1, 43227, 43228, 43225, -1, 43227, 43229, 43230, -1, 43227, 43230, 43228, -1, 43231, 43232, 43233, -1, 43227, 41386, 43229, -1, 43227, 43224, 41388, -1, 43231, 41368, 41366, -1, 43231, 41366, 43234, -1, 43231, 43234, 43232, -1, 41318, 43235, 41319, -1, 43236, 43237, 43238, -1, 43236, 43233, 43237, -1, 43239, 41316, 41315, -1, 43239, 43238, 41316, -1, 43240, 41370, 41368, -1, 43240, 43231, 43233, -1, 43240, 43233, 43236, -1, 43240, 41368, 43231, -1, 43241, 43238, 43239, -1, 43241, 43236, 43238, -1, 43242, 41315, 41314, -1, 43242, 43239, 41315, -1, 43243, 41372, 41370, -1, 43243, 41370, 43240, -1, 43243, 43236, 43241, -1, 43243, 43240, 43236, -1, 43244, 43241, 43239, -1, 43244, 43239, 43242, -1, 43245, 41314, 41313, -1, 43245, 43242, 41314, -1, 43246, 41374, 41372, -1, 43246, 43243, 43241, -1, 43246, 41372, 43243, -1, 43246, 43241, 43244, -1, 43247, 43242, 43245, -1, 43247, 43244, 43242, -1, 43248, 41313, 41311, -1, 43248, 43245, 41313, -1, 43249, 41376, 41374, -1, 43249, 43246, 43244, -1, 43249, 43244, 43247, -1, 43249, 41374, 43246, -1, 43250, 43245, 43248, -1, 43250, 43247, 43245, -1, 43251, 43248, 41311, -1, 43251, 41311, 41309, -1, 43252, 41378, 41376, -1, 43252, 43249, 43247, -1, 43252, 43247, 43250, -1, 43252, 41376, 43249, -1, 43253, 43250, 43248, -1, 43253, 43248, 43251, -1, 43254, 43251, 41309, -1, 43254, 41309, 41306, -1, 43255, 43250, 43253, -1, 43255, 41378, 43252, -1, 43255, 41380, 41378, -1, 43255, 43252, 43250, -1, 43256, 43253, 43251, -1, 43256, 43251, 43254, -1, 43257, 41306, 41307, -1, 43257, 43254, 41306, -1, 43226, 41310, 41312, -1, 43258, 41382, 41380, -1, 43258, 43255, 43253, -1, 43258, 43253, 43256, -1, 43258, 41380, 43255, -1, 43259, 43256, 43254, -1, 43259, 43254, 43257, -1, 43260, 41307, 41308, -1, 43260, 43257, 41307, -1, 41362, 41388, 43224, -1, 43261, 41384, 41382, -1, 43261, 41382, 43258, -1, 43262, 43235, 41318, -1, 43261, 43256, 43259, -1, 43261, 43258, 43256, -1, 43232, 43263, 43235, -1, 43230, 43259, 43257, -1, 43230, 43257, 43260, -1, 43232, 43235, 43262, -1, 43237, 41318, 41317, -1, 43264, 43260, 41308, -1, 43264, 41308, 41310, -1, 43237, 43262, 41318, -1, 43264, 41310, 43226, -1, 43234, 41366, 41363, -1, 43234, 41363, 43265, -1, 43229, 41386, 41384, -1, 43234, 43265, 43263, -1, 43229, 41384, 43261, -1, 43234, 43263, 43232, -1, 43229, 43259, 43230, -1, 43229, 43261, 43259, -1, 43233, 43262, 43237, -1, 43228, 43226, 43225, -1, 43228, 43230, 43260, -1, 43233, 43232, 43262, -1, 43228, 43260, 43264, -1, 43228, 43264, 43226, -1, 43238, 41317, 41316, -1, 43227, 43225, 43224, -1, 43238, 43237, 41317, -1, 43265, 41363, 41340, -1, 43263, 41340, 41323, -1, 43263, 43265, 41340, -1, 43235, 43263, 41323, -1, 41319, 43235, 41323, -1, 39269, 43266, 41920, -1, 43267, 43266, 39269, -1, 42175, 43267, 39269, -1, 39268, 42175, 39269, -1, 39266, 42175, 39268, -1, 38958, 43268, 38965, -1, 42184, 42172, 43269, -1, 42184, 43269, 43268, -1, 42184, 43268, 38958, -1, 42183, 42184, 38958, -1, 42182, 38958, 38960, -1, 42182, 42183, 38958, -1, 42181, 38960, 38954, -1, 42181, 42182, 38960, -1, 42180, 38954, 38956, -1, 42180, 42181, 38954, -1, 42179, 42180, 38956, -1, 42178, 38956, 38957, -1, 42178, 42179, 38956, -1, 42177, 42178, 38957, -1, 42176, 42177, 38957, -1, 41920, 42176, 38957, -1, 43266, 42176, 41920, -1, 43267, 42176, 43266, -1, 42175, 42176, 43267, -1, 43268, 43270, 43271, -1, 43268, 43271, 38966, -1, 43268, 38966, 38965, -1, 43269, 39202, 43270, -1, 43269, 43270, 43268, -1, 42172, 39202, 43269, -1, 38949, 38947, 38966, -1, 38949, 38966, 43271, -1, 38948, 43271, 43270, -1, 38948, 38949, 43271, -1, 38945, 43270, 39202, -1, 38945, 38948, 43270, -1, 39219, 39218, 43272, -1, 43272, 39218, 43273, -1, 43273, 39218, 43274, -1, 43274, 39218, 43275, -1, 43275, 39859, 43276, -1, 43276, 39859, 43277, -1, 43277, 39859, 43278, -1, 39218, 39859, 43275, -1, 43278, 39860, 43279, -1, 39859, 39860, 43278, -1, 43279, 39861, 39868, -1, 39860, 39861, 43279, -1, 39861, 39862, 39868, -1, 39212, 43280, 39231, -1, 39231, 43281, 39856, -1, 43280, 43281, 39231, -1, 43281, 43282, 39856, -1, 39856, 43283, 39855, -1, 43282, 43283, 39856, -1, 39855, 43284, 39854, -1, 43283, 43284, 39855, -1, 39854, 43285, 39853, -1, 43284, 43285, 39854, -1, 39853, 39858, 39852, -1, 43285, 39858, 39853, -1, 39851, 39848, 39857, -1, 39851, 39857, 43286, -1, 39850, 39851, 43286, -1, 39849, 43286, 43287, -1, 39849, 39850, 43286, -1, 42190, 43287, 43288, -1, 42190, 39849, 43287, -1, 42189, 43288, 38969, -1, 42189, 42190, 43288, -1, 38951, 42189, 38969, -1, 38950, 38951, 38969, -1, 31087, 31086, 38953, -1, 31087, 38953, 42187, -1, 43289, 42187, 42188, -1, 43289, 31087, 42187, -1, 43290, 42188, 39845, -1, 43290, 43289, 42188, -1, 43291, 39845, 39846, -1, 43291, 39846, 39847, -1, 43291, 43290, 39845, -1, 39377, 39847, 39378, -1, 39377, 43291, 39847, -1, 43292, 43293, 39384, -1, 43294, 31096, 31089, -1, 43294, 31089, 43295, -1, 43294, 43296, 43297, -1, 43294, 43295, 43296, -1, 43298, 43297, 43293, -1, 43298, 43293, 43292, -1, 43299, 39382, 39379, -1, 43299, 43292, 39382, -1, 43299, 39379, 38325, -1, 43300, 31097, 31096, -1, 43300, 31096, 43294, -1, 43300, 43294, 43297, -1, 43300, 43297, 43298, -1, 43301, 38325, 38324, -1, 43301, 43298, 43292, -1, 43301, 43299, 38325, -1, 43301, 43292, 43299, -1, 43302, 38324, 38323, -1, 31092, 31087, 43289, -1, 43302, 38323, 31099, -1, 43302, 31099, 31098, -1, 43302, 31098, 31097, -1, 43302, 43301, 38324, -1, 43302, 31097, 43300, -1, 43302, 43300, 43298, -1, 43302, 43298, 43301, -1, 38325, 39379, 31505, -1, 43303, 43291, 39377, -1, 43303, 39377, 39390, -1, 43303, 39390, 39388, -1, 43304, 43290, 43291, -1, 43304, 43291, 43303, -1, 43305, 39388, 39386, -1, 43305, 43303, 39388, -1, 43306, 43289, 43290, -1, 43306, 31092, 43289, -1, 43306, 43290, 43304, -1, 43307, 43303, 43305, -1, 43307, 43304, 43303, -1, 43308, 39386, 39384, -1, 43308, 43305, 39386, -1, 43309, 31091, 31092, -1, 43309, 43306, 43304, -1, 43309, 31092, 43306, -1, 43309, 43304, 43307, -1, 43296, 43307, 43305, -1, 43296, 43305, 43308, -1, 43293, 43308, 39384, -1, 43295, 31089, 31091, -1, 43295, 31091, 43309, -1, 43295, 43307, 43296, -1, 43295, 43309, 43307, -1, 43297, 43296, 43308, -1, 43297, 43308, 43293, -1, 43292, 39384, 39382, -1, 39867, 39863, 39865, -1, 43310, 39865, 39864, -1, 43310, 39867, 39865, -1, 43311, 39864, 39866, -1, 43311, 39866, 42186, -1, 43311, 43310, 39864, -1, 43312, 42186, 42185, -1, 43312, 43311, 42186, -1, 31090, 42185, 38952, -1, 31090, 38952, 31088, -1, 31090, 43312, 42185, -1, 42192, 39244, 39247, -1, 42192, 39247, 43313, -1, 42191, 43313, 43314, -1, 42191, 42192, 43313, -1, 39278, 43314, 39289, -1, 39278, 42191, 43314, -1, 43315, 42049, 42050, -1, 43315, 42050, 42051, -1, 43315, 43316, 42049, -1, 43315, 42051, 43314, -1, 43317, 39260, 43318, -1, 43317, 43318, 43319, -1, 43317, 43319, 43320, -1, 43321, 43320, 43322, -1, 43321, 43322, 43316, -1, 43323, 43314, 43313, -1, 43323, 43315, 43314, -1, 43323, 43316, 43315, -1, 43323, 43321, 43316, -1, 42043, 41876, 39328, -1, 43324, 39259, 39260, -1, 43324, 43320, 43321, -1, 43324, 39260, 43317, -1, 39264, 39253, 41872, -1, 43324, 43317, 43320, -1, 39264, 41872, 41874, -1, 43325, 39247, 39259, -1, 43325, 43313, 39247, -1, 43325, 39259, 43324, -1, 43325, 43323, 43313, -1, 43325, 43321, 43323, -1, 43325, 43324, 43321, -1, 43314, 42051, 39289, -1, 43326, 41876, 42043, -1, 43327, 41874, 41876, -1, 43327, 39264, 41874, -1, 43327, 41876, 43326, -1, 43328, 39263, 39264, -1, 43328, 39264, 43327, -1, 43329, 42043, 42045, -1, 43329, 43326, 42043, -1, 43330, 43326, 43329, -1, 43330, 43327, 43326, -1, 43331, 42045, 42047, -1, 43331, 43329, 42045, -1, 43332, 39262, 39263, -1, 43332, 43327, 43330, -1, 43332, 39263, 43328, -1, 43332, 43328, 43327, -1, 43319, 43330, 43329, -1, 43319, 43329, 43331, -1, 43322, 42047, 42048, -1, 43322, 43331, 42047, -1, 43318, 39260, 39261, -1, 43318, 39261, 39262, -1, 43318, 43332, 43330, -1, 43318, 39262, 43332, -1, 43318, 43330, 43319, -1, 43320, 43319, 43331, -1, 43320, 43331, 43322, -1, 43316, 42048, 42049, -1, 43316, 43322, 42048, -1, 31095, 31093, 43333, -1, 43334, 43335, 43336, -1, 43334, 43336, 43337, -1, 43334, 43337, 43338, -1, 43339, 43333, 43335, -1, 43339, 43335, 43334, -1, 43340, 43338, 39867, -1, 43340, 39867, 43310, -1, 43340, 43334, 43338, -1, 43341, 31094, 31095, -1, 43341, 31095, 43333, -1, 43341, 43333, 43339, -1, 43342, 43310, 43311, -1, 43342, 43339, 43334, -1, 43342, 43334, 43340, -1, 43342, 43340, 43310, -1, 43343, 43311, 43312, -1, 43343, 43312, 31090, -1, 43343, 31090, 31094, -1, 43343, 43342, 43311, -1, 43343, 31094, 43341, -1, 43343, 43341, 43339, -1, 43343, 43339, 43342, -1, 38352, 33527, 43344, -1, 43345, 38352, 43344, -1, 38350, 38352, 43345, -1, 43335, 43345, 43336, -1, 43335, 38350, 43345, -1, 43333, 38350, 43335, -1, 31093, 38350, 43333, -1, 39868, 39867, 43338, -1, 43346, 43338, 43337, -1, 43346, 39868, 43338, -1, 43347, 43337, 43336, -1, 43347, 43336, 43345, -1, 43347, 43346, 43337, -1, 43348, 43345, 43344, -1, 43348, 43347, 43345, -1, 33526, 43344, 33527, -1, 33526, 43348, 43344, -1, 43349, 43350, 43351, -1, 43349, 43352, 43350, -1, 43353, 43274, 43275, -1, 43353, 43275, 43276, -1, 43353, 43276, 43354, -1, 43353, 43355, 43352, -1, 43353, 43354, 43355, -1, 43356, 43357, 39219, -1, 43356, 39219, 43272, -1, 43356, 43272, 43273, -1, 43356, 43273, 43274, -1, 33531, 43348, 33526, -1, 43356, 43349, 43357, -1, 43356, 43274, 43353, -1, 43356, 43352, 43349, -1, 43356, 43353, 43352, -1, 43279, 39868, 43346, -1, 43358, 33531, 33532, -1, 43358, 43348, 33531, -1, 43359, 43347, 43348, -1, 43359, 43346, 43347, -1, 43359, 43348, 43358, -1, 43360, 43358, 33532, -1, 43361, 43278, 43279, -1, 43361, 43279, 43346, -1, 43361, 43346, 43359, -1, 43362, 43358, 43360, -1, 43362, 43359, 43358, -1, 43363, 33532, 33516, -1, 43363, 43360, 33532, -1, 43364, 43277, 43278, -1, 43364, 43278, 43361, -1, 43364, 43361, 43359, -1, 43364, 43359, 43362, -1, 43350, 33516, 33513, -1, 43350, 43363, 33516, -1, 43355, 43360, 43363, -1, 43355, 43362, 43360, -1, 43351, 33513, 33512, -1, 43351, 33512, 43365, -1, 43351, 43350, 33513, -1, 43352, 43355, 43363, -1, 43352, 43363, 43350, -1, 43354, 43276, 43277, -1, 43354, 43277, 43364, -1, 43354, 43362, 43355, -1, 43354, 43364, 43362, -1, 43349, 43365, 43357, -1, 43349, 43351, 43365, -1, 43366, 39219, 43357, -1, 43366, 39212, 39219, -1, 43367, 43357, 43365, -1, 43367, 43366, 43357, -1, 33506, 43365, 33512, -1, 33506, 43367, 43365, -1, 43368, 43369, 43370, -1, 43368, 43370, 43371, -1, 43372, 43285, 43373, -1, 43372, 43369, 43368, -1, 43372, 43373, 43369, -1, 43374, 33502, 33503, -1, 43374, 33503, 33504, -1, 43374, 33504, 43375, -1, 43374, 43371, 33502, -1, 43376, 43375, 43377, -1, 43376, 43374, 43375, -1, 43376, 43368, 43371, -1, 43376, 43371, 43374, -1, 43378, 43377, 43379, -1, 43378, 43379, 39858, -1, 43378, 39858, 43285, -1, 43378, 43285, 43372, -1, 43378, 43372, 43368, -1, 43378, 43376, 43377, -1, 43378, 43368, 43376, -1, 43380, 43367, 33506, -1, 43380, 33506, 33507, -1, 43381, 33507, 33508, -1, 43381, 43380, 33507, -1, 43382, 43366, 43367, -1, 43382, 43367, 43380, -1, 43383, 43382, 43380, -1, 43383, 43380, 43381, -1, 43384, 33508, 33509, -1, 43384, 43381, 33508, -1, 43385, 39212, 43366, -1, 43385, 43282, 43281, -1, 43385, 43281, 43280, -1, 43385, 43280, 39212, -1, 43385, 43366, 43382, -1, 43386, 43283, 43282, -1, 43386, 43385, 43382, -1, 43386, 43282, 43385, -1, 43386, 43382, 43383, -1, 43387, 43383, 43381, -1, 43387, 43381, 43384, -1, 43370, 33509, 33500, -1, 43370, 43384, 33509, -1, 43388, 43284, 43283, -1, 43388, 43283, 43386, -1, 43388, 43383, 43387, -1, 43388, 43386, 43383, -1, 43369, 43387, 43384, -1, 43369, 43384, 43370, -1, 43371, 33500, 33502, -1, 43371, 43370, 33500, -1, 43373, 43285, 43284, -1, 43373, 43284, 43388, -1, 43373, 43388, 43387, -1, 43373, 43387, 43369, -1, 38972, 38969, 43288, -1, 43389, 43390, 43391, -1, 38971, 38970, 43392, -1, 43393, 39857, 43394, -1, 43393, 43394, 43390, -1, 43393, 43286, 39857, -1, 43395, 43389, 43392, -1, 43395, 43287, 43286, -1, 43395, 43286, 43393, -1, 43395, 43393, 43390, -1, 43395, 43390, 43389, -1, 43395, 43392, 38970, -1, 43396, 38970, 38972, -1, 43396, 43288, 43287, -1, 43396, 43395, 38970, -1, 43396, 38972, 43288, -1, 43396, 43287, 43395, -1, 43394, 39857, 39858, -1, 43394, 39858, 43379, -1, 43390, 43379, 43377, -1, 43390, 43394, 43379, -1, 43391, 43390, 43377, -1, 43397, 43377, 43375, -1, 43397, 43391, 43377, -1, 43398, 43375, 33504, -1, 43398, 43397, 43375, -1, 33533, 43398, 33504, -1, 43397, 43389, 43391, -1, 41924, 43392, 43389, -1, 41924, 38971, 43392, -1, 41924, 43389, 43397, -1, 41922, 43397, 43398, -1, 41922, 41924, 43397, -1, 33533, 41922, 43398, -1, 31656, 32334, 39656, -1, 31656, 31660, 32334, -1, 31660, 32332, 32334, -1, 31837, 32144, 39652, -1, 32149, 32144, 31837, -1, 31835, 32149, 31837, -1, 38422, 43399, 38425, -1, 38422, 38425, 38419, -1, 43400, 43399, 38422, -1, 38424, 43400, 38422, -1, 40875, 43400, 38424, -1, 33672, 40875, 38424, -1, 41098, 43401, 43402, -1, 41098, 43402, 41096, -1, 40878, 40880, 43401, -1, 40878, 41098, 41101, -1, 40878, 43401, 41098, -1, 40876, 41101, 41102, -1, 40876, 40878, 41101, -1, 43399, 41102, 38425, -1, 43400, 40876, 41102, -1, 43400, 41102, 43399, -1, 40875, 40876, 43400, -1, 43402, 43403, 41103, -1, 43402, 41103, 41096, -1, 43401, 40882, 43404, -1, 43401, 43404, 43403, -1, 43401, 43403, 43402, -1, 40880, 40882, 43401, -1, 41105, 41103, 43403, -1, 43405, 43403, 43404, -1, 43405, 41105, 43403, -1, 43406, 43404, 40882, -1, 43406, 43405, 43404, -1, 40887, 43406, 40882, -1, 43406, 40887, 40883, -1, 43407, 43406, 40883, -1, 43408, 43405, 43406, -1, 43408, 43406, 43407, -1, 41126, 41105, 43405, -1, 41126, 43405, 43408, -1, 41114, 40805, 43409, -1, 43408, 41125, 41126, -1, 43410, 43411, 41116, -1, 43410, 41116, 41118, -1, 43410, 41118, 41120, -1, 43412, 43413, 43411, -1, 43412, 43411, 43410, -1, 43414, 41111, 41114, -1, 43414, 43409, 43413, -1, 43414, 43413, 43412, -1, 43414, 41114, 43409, -1, 43415, 41120, 41121, -1, 43415, 43410, 41120, -1, 43416, 43412, 43410, -1, 43416, 43410, 43415, -1, 43417, 41109, 41111, -1, 43417, 43414, 43412, -1, 43417, 41111, 43414, -1, 43417, 43412, 43416, -1, 43418, 41121, 41123, -1, 43418, 43415, 41121, -1, 43419, 43418, 41123, -1, 43419, 43415, 43418, -1, 43419, 43416, 43415, -1, 43420, 41106, 41109, -1, 43420, 41109, 43417, -1, 43420, 43416, 43419, -1, 43420, 43417, 43416, -1, 43421, 41123, 41125, -1, 43421, 41125, 43408, -1, 43422, 43408, 43407, -1, 43422, 43419, 41123, -1, 43422, 41123, 43421, -1, 43422, 43421, 43408, -1, 43423, 43407, 40883, -1, 43423, 40883, 41106, -1, 43423, 41106, 43420, -1, 43423, 43420, 43419, -1, 43423, 43419, 43422, -1, 43423, 43422, 43407, -1, 43424, 43409, 40805, -1, 43424, 40805, 40801, -1, 43425, 43413, 43409, -1, 43425, 43409, 43424, -1, 43411, 43413, 43425, -1, 43426, 43411, 43425, -1, 41116, 43411, 43426, -1, 40874, 41116, 43426, -1, 43424, 40801, 40815, -1, 43424, 40815, 43427, -1, 43425, 43427, 43428, -1, 43425, 43424, 43427, -1, 43426, 43428, 43429, -1, 43426, 43425, 43428, -1, 40874, 43429, 40872, -1, 40874, 43426, 43429, -1, 40782, 43427, 40815, -1, 43430, 43428, 43427, -1, 43430, 43427, 40782, -1, 43431, 43428, 43430, -1, 43432, 43429, 43428, -1, 43432, 43428, 43431, -1, 40870, 40872, 43429, -1, 40870, 43429, 43432, -1, 40792, 40535, 43433, -1, 43432, 40869, 40870, -1, 43434, 43435, 40861, -1, 43434, 40861, 40863, -1, 43436, 43433, 43435, -1, 43436, 43435, 43434, -1, 43437, 40791, 40792, -1, 43437, 43433, 43436, -1, 43437, 40792, 43433, -1, 43438, 40863, 40865, -1, 43438, 43434, 40863, -1, 43439, 43434, 43438, -1, 43439, 43436, 43434, -1, 43440, 40865, 40867, -1, 43440, 43438, 40865, -1, 43441, 40789, 40791, -1, 43441, 40791, 43437, -1, 43441, 43437, 43436, -1, 43441, 43436, 43439, -1, 43442, 43439, 43438, -1, 43442, 43438, 43440, -1, 43443, 40867, 40869, -1, 43443, 40869, 43432, -1, 43443, 43440, 40867, -1, 43444, 40784, 40787, -1, 43444, 40787, 40789, -1, 43444, 40789, 43441, -1, 43444, 43441, 43439, -1, 43444, 43439, 43442, -1, 43445, 43432, 43431, -1, 43445, 43442, 43440, -1, 43445, 43443, 43432, -1, 43445, 43440, 43443, -1, 43446, 43430, 40782, -1, 43446, 43431, 43430, -1, 43446, 40782, 40784, -1, 43446, 40784, 43444, -1, 43446, 43444, 43442, -1, 43446, 43445, 43431, -1, 43446, 43442, 43445, -1, 43447, 43433, 40535, -1, 43447, 40535, 40542, -1, 43435, 43433, 43447, -1, 43448, 43435, 43447, -1, 40861, 43435, 43448, -1, 40781, 40861, 43448, -1, 43447, 40542, 40526, -1, 43447, 40526, 43449, -1, 43448, 43449, 43450, -1, 43448, 43447, 43449, -1, 40781, 43450, 40780, -1, 40781, 43448, 43450, -1, 43451, 40777, 40780, -1, 43450, 43451, 40780, -1, 43449, 43452, 43451, -1, 43449, 43451, 43450, -1, 40526, 40528, 43452, -1, 40526, 43452, 43449, -1, 40773, 43453, 40772, -1, 40532, 34574, 43454, -1, 40532, 43454, 43453, -1, 40532, 43453, 40773, -1, 40530, 40773, 40775, -1, 40530, 40532, 40773, -1, 43451, 40775, 40777, -1, 43452, 40530, 40775, -1, 43452, 40775, 43451, -1, 40528, 40530, 43452, -1, 38537, 43454, 34574, -1, 38537, 34574, 34557, -1, 43453, 43454, 38537, -1, 38536, 43453, 38537, -1, 40772, 43453, 38536, -1, 38477, 40772, 38536, -1, 43455, 43456, 43457, -1, 43455, 43458, 43456, -1, 43455, 43459, 32168, -1, 43455, 32162, 43460, -1, 43455, 43460, 43458, -1, 32162, 32160, 43461, -1, 32176, 32168, 43459, -1, 43462, 43463, 40778, -1, 43462, 40778, 40776, -1, 43464, 43465, 43463, -1, 43464, 43463, 43462, -1, 43466, 40774, 38476, -1, 43466, 40776, 40774, -1, 43466, 38476, 43467, -1, 43466, 43462, 40776, -1, 43468, 43469, 43465, -1, 43468, 43465, 43464, -1, 43470, 43467, 43471, -1, 43470, 43464, 43462, -1, 43470, 43466, 43467, -1, 43470, 43462, 43466, -1, 43472, 43473, 43469, -1, 43472, 43469, 43468, -1, 43474, 43471, 43475, -1, 43474, 43468, 43464, -1, 43474, 43464, 43470, -1, 43474, 43470, 43471, -1, 43458, 43476, 43473, -1, 43458, 43473, 43472, -1, 43477, 43475, 43478, -1, 43477, 43468, 43474, -1, 43477, 43474, 43475, -1, 43477, 43472, 43468, -1, 43460, 43461, 43476, -1, 43460, 32162, 43461, -1, 43460, 43476, 43458, -1, 43456, 43478, 43457, -1, 43456, 43477, 43478, -1, 43456, 43458, 43472, -1, 43456, 43472, 43477, -1, 43455, 43457, 43459, -1, 43455, 32168, 32162, -1, 43479, 32176, 43459, -1, 43479, 32187, 32176, -1, 43480, 43459, 43457, -1, 43480, 43479, 43459, -1, 43481, 43457, 43478, -1, 43481, 43480, 43457, -1, 43482, 43478, 43475, -1, 43482, 43481, 43478, -1, 43483, 43475, 43471, -1, 43483, 43482, 43475, -1, 43484, 43471, 43467, -1, 43484, 43483, 43471, -1, 38473, 43467, 38476, -1, 38473, 43484, 43467, -1, 40779, 40778, 43463, -1, 43485, 43463, 43465, -1, 43485, 40779, 43463, -1, 43486, 43465, 43469, -1, 43486, 43485, 43465, -1, 43487, 43469, 43473, -1, 43487, 43486, 43469, -1, 43488, 43473, 43476, -1, 43488, 43487, 43473, -1, 43489, 43476, 43461, -1, 43489, 43488, 43476, -1, 43490, 43461, 32160, -1, 43490, 43489, 43461, -1, 32159, 43490, 32160, -1, 43491, 43492, 43493, -1, 43491, 32188, 43494, -1, 43491, 43494, 43495, -1, 43491, 43495, 43492, -1, 43496, 38469, 38467, -1, 32188, 32187, 43479, -1, 43497, 43484, 38473, -1, 43497, 38473, 38471, -1, 43498, 43483, 43484, -1, 43498, 43484, 43497, -1, 43499, 38471, 38469, -1, 43499, 43496, 43500, -1, 43499, 43497, 38471, -1, 43499, 38469, 43496, -1, 43501, 43482, 43483, -1, 43501, 43483, 43498, -1, 43502, 43500, 43503, -1, 43502, 43498, 43497, -1, 43502, 43499, 43500, -1, 43502, 43497, 43499, -1, 43504, 43481, 43482, -1, 43504, 43482, 43501, -1, 43505, 43503, 43506, -1, 43505, 43501, 43498, -1, 43505, 43502, 43503, -1, 43505, 43498, 43502, -1, 43495, 43480, 43481, -1, 43495, 43481, 43504, -1, 43507, 43506, 43508, -1, 43507, 43504, 43501, -1, 43507, 43505, 43506, -1, 43507, 43501, 43505, -1, 43494, 43479, 43480, -1, 43494, 43480, 43495, -1, 43494, 32188, 43479, -1, 43492, 43508, 43493, -1, 43492, 43507, 43508, -1, 43492, 43495, 43504, -1, 43492, 43504, 43507, -1, 43491, 43493, 32190, -1, 43491, 32189, 32188, -1, 43491, 32190, 32189, -1, 43509, 43510, 43511, -1, 43512, 43513, 43514, -1, 43512, 43514, 43515, -1, 40868, 43516, 40871, -1, 43517, 43485, 43486, -1, 43517, 40864, 40862, -1, 43517, 43511, 40864, -1, 43517, 40862, 43485, -1, 43518, 43515, 43519, -1, 43518, 43519, 43520, -1, 43521, 43520, 43522, -1, 43521, 43522, 43509, -1, 43523, 43524, 43513, -1, 43523, 43513, 43512, -1, 43523, 32161, 43524, -1, 43525, 43486, 43487, -1, 43525, 43509, 43511, -1, 43525, 43517, 43486, -1, 43525, 43511, 43517, -1, 43526, 43512, 43515, -1, 43526, 43515, 43518, -1, 43527, 43520, 43521, -1, 43527, 43518, 43520, -1, 43528, 43487, 43488, -1, 43528, 43525, 43487, -1, 43485, 40862, 40779, -1, 43528, 43521, 43509, -1, 43528, 43509, 43525, -1, 43529, 32158, 32161, -1, 43529, 32161, 43523, -1, 32161, 32173, 43524, -1, 43529, 43512, 43526, -1, 43529, 43523, 43512, -1, 43530, 43526, 43518, -1, 43530, 43518, 43527, -1, 43531, 43488, 43489, -1, 43531, 43528, 43488, -1, 43531, 43527, 43521, -1, 43531, 43521, 43528, -1, 43532, 43529, 43526, -1, 43532, 32156, 32158, -1, 43532, 32158, 43529, -1, 43532, 43526, 43530, -1, 43533, 43530, 43527, -1, 43533, 43531, 43489, -1, 43533, 43489, 43490, -1, 43533, 43527, 43531, -1, 43534, 43532, 43530, -1, 43534, 32157, 32156, -1, 43534, 43533, 43490, -1, 43534, 32156, 43532, -1, 43534, 43490, 32157, -1, 43534, 43530, 43533, -1, 32159, 32157, 43490, -1, 43535, 43516, 40868, -1, 43536, 43537, 43516, -1, 43536, 43538, 43537, -1, 43536, 43516, 43535, -1, 43510, 40868, 40866, -1, 43510, 43535, 40868, -1, 43519, 43538, 43536, -1, 43522, 43536, 43535, -1, 43522, 43535, 43510, -1, 43511, 40866, 40864, -1, 43511, 43510, 40866, -1, 43515, 43514, 43538, -1, 43515, 43538, 43519, -1, 43520, 43519, 43536, -1, 43520, 43536, 43522, -1, 43509, 43522, 43510, -1, 43539, 32190, 43493, -1, 43539, 32191, 32190, -1, 43540, 43493, 43508, -1, 43540, 43539, 43493, -1, 43541, 43508, 43506, -1, 43541, 43540, 43508, -1, 43542, 43506, 43503, -1, 43542, 43541, 43506, -1, 43543, 43503, 43500, -1, 43543, 43542, 43503, -1, 43544, 43500, 43496, -1, 43544, 43543, 43500, -1, 38464, 43496, 38467, -1, 38464, 43544, 43496, -1, 43545, 40871, 43516, -1, 43545, 40873, 40871, -1, 43546, 43516, 43537, -1, 43546, 43545, 43516, -1, 43547, 43537, 43538, -1, 43547, 43546, 43537, -1, 43548, 43538, 43514, -1, 43548, 43547, 43538, -1, 43549, 43514, 43513, -1, 43549, 43548, 43514, -1, 43550, 43513, 43524, -1, 43550, 43549, 43513, -1, 32178, 43524, 32173, -1, 32178, 43550, 43524, -1, 43551, 43552, 43553, -1, 43551, 43553, 43554, -1, 43555, 43540, 43541, -1, 43555, 43541, 43556, -1, 38462, 43544, 38464, -1, 43557, 38456, 38453, -1, 43557, 38458, 38456, -1, 43557, 38453, 43558, -1, 43557, 43554, 38458, -1, 43559, 43560, 43561, -1, 43559, 43556, 43560, -1, 43562, 43561, 43552, -1, 43562, 43552, 43551, -1, 43563, 32191, 43539, -1, 43563, 43539, 43540, -1, 43563, 32192, 32191, -1, 43563, 43540, 43555, -1, 43564, 43558, 43565, -1, 43564, 43557, 43558, -1, 43564, 43551, 43554, -1, 43564, 43554, 43557, -1, 43566, 43555, 43556, -1, 43566, 43556, 43559, -1, 43567, 43559, 43561, -1, 43567, 43561, 43562, -1, 43568, 43565, 43569, -1, 43568, 43564, 43565, -1, 43568, 43562, 43551, -1, 43568, 43551, 43564, -1, 43570, 32193, 32192, -1, 43570, 32192, 43563, -1, 43570, 43555, 43566, -1, 43570, 43563, 43555, -1, 43571, 43559, 43567, -1, 43571, 43566, 43559, -1, 43572, 43569, 43573, -1, 43572, 43568, 43569, -1, 43572, 43567, 43562, -1, 43572, 43562, 43568, -1, 43574, 43570, 43566, -1, 43574, 32194, 32193, -1, 43574, 32193, 43570, -1, 43574, 43566, 43571, -1, 43575, 43571, 43567, -1, 43575, 43573, 43576, -1, 43575, 43567, 43572, -1, 43575, 43572, 43573, -1, 43577, 43574, 43571, -1, 43577, 43578, 32170, -1, 43577, 43576, 43578, -1, 43577, 32195, 32194, -1, 43577, 32170, 32195, -1, 43577, 43571, 43575, -1, 43577, 43575, 43576, -1, 43577, 32194, 43574, -1, 43579, 43544, 38462, -1, 43580, 43543, 43544, -1, 43580, 43544, 43579, -1, 43553, 38462, 38460, -1, 43553, 43579, 38462, -1, 43560, 43542, 43543, -1, 43560, 43543, 43580, -1, 43552, 43580, 43579, -1, 43552, 43579, 43553, -1, 43554, 38460, 38458, -1, 43554, 43553, 38460, -1, 43556, 43541, 43542, -1, 43556, 43542, 43560, -1, 43561, 43560, 43580, -1, 43561, 43580, 43552, -1, 43581, 43582, 43583, -1, 43581, 43583, 43584, -1, 43585, 43586, 43587, -1, 43585, 43587, 43588, -1, 43589, 41119, 41117, -1, 43589, 41117, 43545, -1, 43589, 43584, 41119, -1, 43590, 43588, 43591, -1, 43590, 43591, 43592, -1, 43593, 43592, 43582, -1, 43593, 43582, 43581, -1, 43594, 32181, 32182, -1, 43594, 43595, 43586, -1, 43594, 43586, 43585, -1, 43594, 32182, 43595, -1, 43596, 43545, 43546, -1, 43596, 43581, 43584, -1, 43596, 43589, 43545, -1, 43596, 43584, 43589, -1, 43597, 43585, 43588, -1, 43597, 43588, 43590, -1, 43545, 41117, 40873, -1, 43598, 43590, 43592, -1, 43598, 43592, 43593, -1, 43599, 43546, 43547, -1, 43599, 43596, 43546, -1, 32182, 32183, 43595, -1, 43599, 43593, 43581, -1, 43599, 43581, 43596, -1, 43600, 32180, 32181, -1, 43600, 32181, 43594, -1, 43600, 43594, 43585, -1, 43600, 43585, 43597, -1, 43601, 43597, 43590, -1, 43601, 43590, 43598, -1, 43602, 43547, 43548, -1, 43602, 43599, 43547, -1, 43602, 43598, 43593, -1, 43602, 43593, 43599, -1, 43603, 43597, 43601, -1, 43603, 32179, 32180, -1, 43603, 32180, 43600, -1, 43603, 43600, 43597, -1, 43604, 43601, 43598, -1, 43604, 43548, 43549, -1, 43604, 43598, 43602, -1, 43604, 43602, 43548, -1, 43605, 43604, 43549, -1, 43605, 43549, 43550, -1, 43605, 32179, 43603, -1, 43605, 43601, 43604, -1, 43605, 43603, 43601, -1, 43605, 43550, 32179, -1, 32178, 32179, 43550, -1, 43606, 43607, 41104, -1, 43606, 41104, 41124, -1, 43608, 43609, 43607, -1, 43608, 43607, 43606, -1, 43583, 41124, 41122, -1, 43583, 43606, 41124, -1, 43591, 43610, 43609, -1, 43591, 43609, 43608, -1, 43582, 43608, 43606, -1, 43582, 43606, 43583, -1, 43584, 41122, 41119, -1, 43584, 43583, 41122, -1, 43588, 43587, 43610, -1, 43588, 43610, 43591, -1, 43592, 43608, 43582, -1, 43592, 43591, 43608, -1, 43611, 32170, 43578, -1, 43611, 32169, 32170, -1, 43612, 43578, 43576, -1, 43612, 43611, 43578, -1, 43613, 43576, 43573, -1, 43613, 43573, 43569, -1, 43613, 43612, 43576, -1, 43614, 43613, 43569, -1, 43615, 43569, 43565, -1, 43615, 43614, 43569, -1, 43616, 43565, 43558, -1, 43616, 43615, 43565, -1, 38450, 43558, 38453, -1, 38450, 43616, 43558, -1, 43617, 41104, 43607, -1, 43617, 41099, 41104, -1, 43618, 43607, 43609, -1, 43618, 43617, 43607, -1, 43619, 43609, 43610, -1, 43619, 43618, 43609, -1, 43620, 43610, 43587, -1, 43620, 43619, 43610, -1, 43621, 43587, 43586, -1, 43621, 43620, 43587, -1, 43622, 43586, 43595, -1, 43622, 43621, 43586, -1, 32184, 43595, 32183, -1, 32184, 43622, 43595, -1, 43623, 43624, 43625, -1, 43623, 43625, 43626, -1, 43627, 43612, 43613, -1, 43627, 43613, 43628, -1, 43629, 38443, 38441, -1, 43629, 43626, 38443, -1, 43629, 38441, 43630, -1, 43631, 43632, 43633, -1, 43631, 43628, 43632, -1, 43634, 43633, 43624, -1, 43634, 43624, 43623, -1, 43635, 32169, 43611, -1, 43635, 43611, 43612, -1, 43635, 32171, 32169, -1, 43635, 43612, 43627, -1, 43636, 43630, 43637, -1, 43636, 43629, 43630, -1, 43636, 43623, 43626, -1, 43636, 43626, 43629, -1, 43638, 43627, 43628, -1, 43638, 43628, 43631, -1, 43630, 38441, 38437, -1, 43639, 43631, 43633, -1, 43639, 43633, 43634, -1, 43640, 43637, 43641, -1, 43640, 43636, 43637, -1, 43640, 43634, 43623, -1, 43640, 43623, 43636, -1, 43642, 32172, 32171, -1, 43642, 43627, 43638, -1, 43642, 32171, 43635, -1, 43642, 43635, 43627, -1, 43643, 43638, 43631, -1, 43643, 43631, 43639, -1, 43644, 43641, 43645, -1, 43644, 43640, 43641, -1, 43644, 43639, 43634, -1, 43644, 43634, 43640, -1, 43646, 43642, 43638, -1, 43646, 32174, 32172, -1, 43646, 32172, 43642, -1, 43646, 43638, 43643, -1, 43647, 43643, 43639, -1, 43647, 43645, 43648, -1, 43647, 43639, 43644, -1, 43647, 43644, 43645, -1, 43649, 43646, 43643, -1, 43649, 43648, 43650, -1, 43649, 32175, 32174, -1, 43649, 43643, 43647, -1, 43649, 43650, 32175, -1, 32164, 32175, 43650, -1, 43649, 43647, 43648, -1, 43649, 32174, 43646, -1, 43651, 43616, 38450, -1, 43651, 38450, 38448, -1, 43652, 43615, 43616, -1, 43652, 43616, 43651, -1, 43625, 38448, 38446, -1, 43625, 43651, 38448, -1, 43632, 43614, 43615, -1, 43632, 43615, 43652, -1, 43624, 43652, 43651, -1, 43624, 43651, 43625, -1, 43626, 38446, 38443, -1, 43626, 43625, 38446, -1, 43628, 43613, 43614, -1, 43628, 43614, 43632, -1, 43633, 43632, 43652, -1, 43633, 43652, 43624, -1, 43617, 41097, 41099, -1, 32184, 32185, 43622, -1, 43653, 43654, 38426, -1, 43653, 38426, 41100, -1, 43655, 43656, 43654, -1, 43655, 43654, 43653, -1, 43657, 43617, 43618, -1, 43657, 41100, 41097, -1, 43657, 43653, 41100, -1, 43657, 41097, 43617, -1, 43658, 43659, 43656, -1, 43658, 43656, 43655, -1, 43660, 43618, 43619, -1, 43660, 43655, 43653, -1, 43660, 43657, 43618, -1, 43660, 43653, 43657, -1, 43661, 43662, 43659, -1, 43661, 43659, 43658, -1, 43663, 43619, 43620, -1, 43663, 43655, 43660, -1, 43663, 43658, 43655, -1, 43663, 43660, 43619, -1, 43664, 43665, 43662, -1, 43664, 43662, 43661, -1, 43666, 43620, 43621, -1, 43666, 43658, 43663, -1, 43666, 43661, 43658, -1, 43666, 43663, 43620, -1, 43667, 32186, 32177, -1, 43667, 43668, 43665, -1, 43667, 32177, 43668, -1, 43667, 43665, 43664, -1, 43669, 43621, 43622, -1, 43669, 43664, 43661, -1, 43669, 43666, 43621, -1, 43669, 43661, 43666, -1, 43670, 32185, 32186, -1, 43670, 32186, 43667, -1, 43670, 43669, 43622, -1, 43670, 43622, 32185, -1, 43670, 43667, 43664, -1, 43670, 43664, 43669, -1, 43671, 32164, 43650, -1, 43671, 32163, 32164, -1, 43672, 43650, 43648, -1, 43672, 43671, 43650, -1, 43673, 43648, 43645, -1, 43673, 43672, 43648, -1, 43674, 43645, 43641, -1, 43674, 43673, 43645, -1, 43675, 43641, 43637, -1, 43675, 43674, 43641, -1, 43676, 43637, 43630, -1, 43676, 43675, 43637, -1, 38435, 43630, 38437, -1, 38435, 43676, 43630, -1, 43668, 32177, 32167, -1, 43668, 32167, 43677, -1, 43665, 43677, 43678, -1, 43665, 43668, 43677, -1, 43662, 43678, 43679, -1, 43662, 43665, 43678, -1, 43659, 43679, 43680, -1, 43659, 43662, 43679, -1, 43656, 43680, 43681, -1, 43656, 43659, 43680, -1, 43654, 43681, 43682, -1, 43654, 43656, 43681, -1, 38426, 43682, 38427, -1, 38426, 43654, 43682, -1, 43683, 43684, 43685, -1, 43683, 43685, 43686, -1, 38433, 43676, 38435, -1, 32167, 32166, 43677, -1, 43687, 43675, 43676, -1, 43687, 43676, 38433, -1, 43688, 43674, 43675, -1, 43688, 43675, 43687, -1, 43689, 38431, 38427, -1, 43689, 38433, 38431, -1, 43689, 38427, 43682, -1, 43689, 43687, 38433, -1, 43690, 43673, 43674, -1, 43690, 43674, 43688, -1, 43691, 43682, 43681, -1, 43691, 43688, 43687, -1, 43691, 43689, 43682, -1, 43691, 43687, 43689, -1, 43692, 43672, 43673, -1, 43692, 43673, 43690, -1, 43693, 43681, 43680, -1, 43693, 43688, 43691, -1, 43693, 43690, 43688, -1, 43693, 43691, 43681, -1, 43685, 43671, 43672, -1, 43685, 43672, 43692, -1, 43694, 43680, 43679, -1, 43694, 43692, 43690, -1, 43694, 43690, 43693, -1, 43694, 43693, 43680, -1, 43684, 32163, 43671, -1, 43684, 32165, 32163, -1, 43684, 43671, 43685, -1, 43686, 43679, 43678, -1, 43686, 43692, 43694, -1, 43686, 43685, 43692, -1, 43686, 43694, 43679, -1, 43683, 43678, 43677, -1, 43683, 32166, 32165, -1, 43683, 43686, 43678, -1, 43683, 32165, 43684, -1, 43683, 43677, 32166, -1, 43695, 2458, 43696, -1, 2384, 2458, 43695, -1, 2458, 2428, 43697, -1, 2458, 43697, 43696, -1, 2428, 2414, 43698, -1, 2428, 43698, 43697, -1, 2414, 2418, 43699, -1, 2414, 43699, 43698, -1, 2418, 2460, 43700, -1, 2418, 43700, 43699, -1, 2460, 2512, 43701, -1, 2460, 43701, 43700, -1, 43701, 2337, 43702, -1, 2512, 2337, 43701, -1, 2337, 2384, 43695, -1, 2337, 43695, 43702, -1, 43699, 32287, 43698, -1, 32284, 32287, 43699, -1, 43699, 32282, 32284, -1, 32282, 32281, 32284, -1, 32287, 43697, 43698, -1, 32287, 32289, 43697, -1, 32291, 43696, 32289, -1, 32289, 43696, 43697, -1, 32264, 32268, 32263, -1, 43700, 32268, 32264, -1, 43700, 32269, 32268, -1, 43700, 43701, 32269, -1, 32292, 32312, 32291, -1, 32291, 32312, 43696, -1, 32297, 32296, 32302, -1, 32271, 43695, 32296, -1, 32296, 43695, 32302, -1, 32269, 43702, 32271, -1, 43701, 43702, 32269, -1, 32271, 43702, 43695, -1, 43695, 43696, 32302, -1, 32302, 43696, 32312, -1, 43699, 43700, 32282, -1, 32282, 43700, 32264, -1, 38734, 38728, 39675, -1, 38728, 39671, 39675, -1, 30977, 32537, 30978, -1, 30978, 32537, 32533, -1, 32524, 32528, 32520, -1, 32520, 32528, 32519, -1, 39658, 39657, 39662, -1, 39662, 39657, 39666, -1, 30125, 38842, 38852, -1, 30125, 30128, 38842, -1, 31069, 31138, 30113, -1, 30113, 31138, 30118, -1, 39577, 38774, 38775, -1, 39577, 43703, 38774, -1, 43703, 38770, 38774, -1, 43703, 43704, 38770, -1, 43705, 38757, 43704, -1, 38757, 38766, 43704, -1, 43704, 38766, 38770, -1, 43705, 38751, 38757, -1, 38751, 38753, 38757, -1, 43706, 43705, 43704, -1, 43707, 43706, 43704, -1, 43707, 43704, 43703, -1, 43707, 43703, 43708, -1, 38886, 39576, 38887, -1, 43708, 39576, 38886, -1, 38884, 43708, 38886, -1, 43707, 43708, 38884, -1, 38879, 43706, 43707, -1, 38881, 38879, 43707, -1, 38881, 43707, 38884, -1, 38750, 43706, 38879, -1, 38747, 38750, 38879, -1, 43708, 39577, 39576, -1, 43708, 43703, 39577, -1, 38751, 43705, 43706, -1, 38750, 38751, 43706, -1, 38892, 32229, 32231, -1, 43709, 32229, 38892, -1, 43709, 43710, 32229, -1, 43710, 32223, 32229, -1, 43711, 32220, 43712, -1, 43712, 32222, 43710, -1, 43710, 32222, 32223, -1, 32220, 32222, 43712, -1, 43713, 32217, 43711, -1, 43711, 32217, 32220, -1, 43713, 43714, 32217, -1, 43714, 32211, 32217, -1, 43714, 43715, 32211, -1, 43716, 32203, 43715, -1, 32203, 32216, 43715, -1, 43715, 32216, 32211, -1, 43716, 32241, 32203, -1, 32241, 32201, 32203, -1, 43717, 43716, 43715, -1, 43717, 43718, 43716, -1, 43717, 43715, 43714, -1, 43717, 43714, 43719, -1, 43713, 43719, 43714, -1, 43720, 43719, 43713, -1, 43713, 43711, 43721, -1, 43720, 43713, 43721, -1, 43722, 43711, 43712, -1, 43722, 43721, 43711, -1, 43722, 43712, 43710, -1, 43722, 43710, 43723, -1, 43724, 43710, 43709, -1, 43724, 43723, 43710, -1, 38875, 43724, 38891, -1, 38875, 38891, 38876, -1, 43723, 43724, 38875, -1, 38878, 43723, 38875, -1, 32346, 43721, 43722, -1, 38877, 43722, 43723, -1, 38877, 43723, 38878, -1, 38877, 32346, 43722, -1, 32338, 43720, 43721, -1, 32338, 43721, 32346, -1, 43719, 43720, 32338, -1, 32337, 43719, 32338, -1, 43717, 43719, 32337, -1, 32335, 43718, 43717, -1, 32336, 32335, 43717, -1, 32336, 43717, 32337, -1, 32242, 43718, 32335, -1, 32244, 32242, 32335, -1, 43709, 38892, 38891, -1, 43724, 43709, 38891, -1, 32241, 43716, 43718, -1, 32242, 32241, 43718, -1, 32415, 43725, 43726, -1, 32414, 32415, 43726, -1, 31059, 43727, 30987, -1, 31059, 30987, 30989, -1, 43728, 43727, 31059, -1, 31061, 43728, 31059, -1, 31064, 43726, 43728, -1, 31064, 43728, 31061, -1, 31066, 31067, 32414, -1, 31066, 32414, 43726, -1, 31066, 43726, 31064, -1, 30983, 31004, 30984, -1, 43729, 31004, 30983, -1, 43729, 43730, 31004, -1, 43730, 31011, 31004, -1, 43725, 31015, 43730, -1, 43730, 31015, 31011, -1, 32415, 31017, 43725, -1, 31020, 31017, 32415, -1, 43725, 31017, 31015, -1, 43726, 43725, 43730, -1, 43726, 43730, 43728, -1, 43729, 43728, 43730, -1, 43727, 43728, 43729, -1, 43727, 43729, 30983, -1, 43727, 30983, 30987, -1, 38817, 38816, 39011, -1, 38816, 39012, 39011, -1, 38816, 38818, 39012, -1, 38818, 39008, 39012, -1, 38818, 38813, 39008, -1, 39008, 38812, 39007, -1, 38813, 38812, 39008, -1, 39007, 38811, 39006, -1, 38812, 38811, 39007, -1, 39006, 38809, 39005, -1, 38811, 38809, 39006, -1, 39005, 38808, 39001, -1, 38809, 38808, 39005, -1, 39001, 38807, 38820, -1, 38808, 38807, 39001, -1, 32061, 32072, 31177, -1, 31177, 32072, 31175, -1, 31175, 32071, 31168, -1, 32072, 32071, 31175, -1, 31168, 32070, 31165, -1, 32071, 32070, 31168, -1, 31165, 32068, 31145, -1, 32070, 32068, 31165, -1, 31145, 32067, 31146, -1, 32068, 32067, 31145, -1, 31146, 32065, 31182, -1, 32067, 32065, 31146, -1, 31182, 32064, 31144, -1, 32065, 32064, 31182, -1, 31144, 32066, 31147, -1, 32064, 32066, 31144, -1, 31147, 32069, 31164, -1, 31164, 32069, 31166, -1, 32066, 32069, 31147, -1, 31166, 32059, 31170, -1, 32069, 32059, 31166, -1, 31835, 31838, 32149, -1, 32149, 31838, 32153, -1, 32153, 31839, 32155, -1, 31838, 31839, 32153, -1, 32155, 31840, 32092, -1, 31839, 31840, 32155, -1, 32092, 31841, 32093, -1, 31840, 31841, 32092, -1, 32140, 38542, 39650, -1, 32143, 39650, 39649, -1, 32143, 32140, 39650, -1, 32145, 39649, 39651, -1, 32145, 32143, 39649, -1, 32146, 39651, 39652, -1, 32146, 32145, 39651, -1, 32144, 32146, 39652, -1, 31656, 39656, 39655, -1, 31654, 39655, 39654, -1, 31654, 31656, 39655, -1, 31655, 39654, 39653, -1, 31655, 31654, 39654, -1, 31661, 39653, 38944, -1, 31661, 31655, 39653, -1, 31659, 31661, 38944, -1, 32328, 32329, 31665, -1, 31665, 32329, 31666, -1, 31666, 32330, 31668, -1, 32329, 32330, 31666, -1, 31668, 32331, 31669, -1, 32330, 32331, 31668, -1, 31669, 32332, 31660, -1, 32331, 32332, 31669, -1, 31842, 31843, 32095, -1, 32095, 31843, 32110, -1, 32110, 31844, 32111, -1, 31843, 31844, 32110, -1, 32111, 31845, 32112, -1, 31844, 31845, 32111, -1, 32112, 31846, 32108, -1, 31845, 31846, 32112, -1, 32105, 32511, 32514, -1, 32103, 32514, 32512, -1, 32103, 32105, 32514, -1, 32104, 32512, 32513, -1, 32104, 32103, 32512, -1, 32107, 32513, 31812, -1, 32107, 32104, 32513, -1, 31810, 32107, 31812, -1, 31073, 31074, 32518, -1, 31699, 32518, 32517, -1, 31699, 31073, 32518, -1, 31701, 32517, 32515, -1, 31701, 31699, 32517, -1, 31702, 32515, 32516, -1, 31702, 31701, 32515, -1, 31700, 31702, 32516, -1, 32321, 32323, 31705, -1, 31705, 32323, 31709, -1, 31709, 32324, 31711, -1, 32323, 32324, 31709, -1, 31711, 32325, 31712, -1, 32324, 32325, 31711, -1, 31712, 32326, 31663, -1, 32325, 32326, 31712, -1, 39648, 39619, 31698, -1, 39648, 31698, 31704, -1, 39646, 31704, 31703, -1, 39646, 39648, 31704, -1, 39644, 31703, 31710, -1, 39644, 39646, 31703, -1, 39645, 31710, 31707, -1, 39645, 39644, 31710, -1, 39643, 31707, 31708, -1, 39643, 39645, 31707, -1, 39647, 31708, 31706, -1, 39647, 39643, 31708, -1, 38943, 31706, 31697, -1, 38943, 39647, 31706, -1, 32125, 32127, 38932, -1, 32125, 38932, 38931, -1, 32126, 38931, 38930, -1, 32126, 32125, 38931, -1, 32134, 38930, 38928, -1, 32134, 32126, 38930, -1, 32132, 38928, 38929, -1, 32132, 32134, 38928, -1, 32133, 38929, 38926, -1, 32133, 32132, 38929, -1, 32139, 38926, 38927, -1, 32139, 32133, 38926, -1, 32136, 38927, 38539, -1, 32136, 32139, 38927, -1, 32510, 31072, 31071, -1, 32510, 31071, 31694, -1, 32508, 31694, 31689, -1, 32508, 32510, 31694, -1, 32509, 31689, 31690, -1, 32509, 32508, 31689, -1, 32507, 31690, 31688, -1, 32507, 32509, 31690, -1, 32505, 31688, 31682, -1, 32505, 32507, 31688, -1, 32506, 31682, 31681, -1, 32506, 32505, 31682, -1, 32496, 31681, 31683, -1, 32496, 32506, 31681, -1, 32150, 31808, 31793, -1, 32150, 31793, 31796, -1, 32152, 31796, 31795, -1, 32152, 32150, 31796, -1, 32151, 31795, 31799, -1, 32151, 32152, 31795, -1, 32154, 31799, 31797, -1, 32154, 32151, 31799, -1, 32147, 31797, 31798, -1, 32147, 32154, 31797, -1, 32148, 31798, 31794, -1, 32148, 32147, 31798, -1, 32142, 31794, 31792, -1, 32142, 32148, 31794, -1, 39621, 38894, 38899, -1, 39621, 38939, 38894, -1, 39620, 38899, 38898, -1, 39620, 39621, 38899, -1, 39623, 38898, 38897, -1, 39623, 39620, 38898, -1, 39624, 38897, 38896, -1, 39624, 39623, 38897, -1, 39625, 38896, 38895, -1, 39625, 39624, 38896, -1, 31679, 39631, 31684, -1, 39634, 39631, 31679, -1, 31684, 39630, 31685, -1, 39631, 39630, 31684, -1, 31685, 39629, 31686, -1, 39630, 39629, 31685, -1, 31686, 39628, 31687, -1, 39629, 39628, 31686, -1, 31687, 39627, 31691, -1, 39628, 39627, 31687, -1, 31691, 39626, 31692, -1, 39627, 39626, 31691, -1, 31692, 39536, 31695, -1, 39626, 39536, 31692, -1, 31679, 31678, 39634, -1, 39634, 31678, 39635, -1, 39635, 31676, 39636, -1, 31678, 31676, 39635, -1, 39636, 31672, 39638, -1, 31676, 31672, 39636, -1, 39638, 31671, 39639, -1, 31672, 31671, 39638, -1, 39639, 31674, 39640, -1, 31671, 31674, 39639, -1, 39640, 31677, 39622, -1, 31674, 31677, 39640, -1, 39622, 31680, 39618, -1, 31677, 31680, 39622, -1, 38900, 38924, 32106, -1, 32106, 38924, 32101, -1, 32101, 38923, 32099, -1, 38924, 38923, 32101, -1, 32099, 38922, 32096, -1, 38923, 38922, 32099, -1, 32096, 38921, 32097, -1, 38922, 38921, 32096, -1, 32097, 38917, 32098, -1, 38921, 38917, 32097, -1, 32098, 38916, 32100, -1, 38917, 38916, 32098, -1, 32100, 38915, 32102, -1, 38916, 38915, 32100, -1, 32138, 32141, 38933, -1, 38933, 32141, 38934, -1, 38934, 32119, 38907, -1, 32141, 32119, 38934, -1, 38907, 32117, 38908, -1, 32119, 32117, 38907, -1, 38908, 32114, 38909, -1, 32117, 32114, 38908, -1, 38909, 32113, 38913, -1, 32114, 32113, 38909, -1, 38913, 32109, 38914, -1, 32113, 32109, 38913, -1, 38914, 32102, 38915, -1, 32109, 32102, 38914, -1, 32494, 31772, 31780, -1, 32494, 32490, 31772, -1, 32495, 31780, 31779, -1, 32495, 32494, 31780, -1, 32492, 31779, 31778, -1, 32492, 32495, 31779, -1, 32493, 31778, 31777, -1, 32493, 32492, 31778, -1, 32055, 31777, 31776, -1, 32055, 32493, 31777, -1, 31658, 32491, 31653, -1, 31714, 32491, 31658, -1, 31653, 32487, 31650, -1, 32491, 32487, 31653, -1, 31650, 32484, 31648, -1, 32487, 32484, 31650, -1, 31648, 32485, 31649, -1, 32484, 32485, 31648, -1, 31649, 32488, 31651, -1, 32485, 32488, 31649, -1, 31651, 32489, 31652, -1, 32488, 32489, 31651, -1, 31652, 32497, 31657, -1, 32489, 32497, 31652, -1, 31693, 31696, 32498, -1, 32498, 31696, 32499, -1, 32499, 31675, 32504, -1, 31696, 31675, 32499, -1, 32504, 31673, 32503, -1, 31675, 31673, 32504, -1, 32503, 31670, 32502, -1, 31673, 31670, 32503, -1, 32502, 31667, 32501, -1, 31670, 31667, 32502, -1, 32501, 31662, 32500, -1, 31667, 31662, 32501, -1, 32500, 31657, 32497, -1, 31662, 31657, 32500, -1, 32124, 32122, 31781, -1, 31781, 32122, 31775, -1, 31775, 32120, 31774, -1, 32122, 32120, 31775, -1, 31774, 32116, 31769, -1, 32120, 32116, 31774, -1, 31769, 32115, 31771, -1, 32116, 32115, 31769, -1, 31771, 32118, 31773, -1, 32115, 32118, 31771, -1, 31773, 32121, 31788, -1, 32118, 32121, 31773, -1, 31788, 32123, 31789, -1, 32121, 32123, 31788, -1, 31781, 31783, 32124, -1, 32124, 31783, 32128, -1, 32128, 31785, 32129, -1, 31783, 31785, 32128, -1, 32129, 31786, 32130, -1, 31785, 31786, 32129, -1, 32130, 31790, 32131, -1, 31786, 31790, 32130, -1, 32131, 31791, 32135, -1, 31790, 31791, 32131, -1, 32135, 31784, 32137, -1, 31791, 31784, 32135, -1, 32137, 31744, 31735, -1, 31784, 31744, 32137, -1, 43731, 43732, 43733, -1, 43734, 43735, 43736, -1, 43731, 43733, 43737, -1, 43734, 43738, 43735, -1, 43739, 43740, 43732, -1, 43739, 43732, 43731, -1, 43741, 43742, 33225, -1, 33219, 43743, 33253, -1, 43741, 33225, 43744, -1, 43745, 43746, 43747, -1, 33219, 43748, 43743, -1, 43745, 43749, 43746, -1, 43750, 43751, 43752, -1, 43750, 43753, 43751, -1, 43733, 43748, 33219, -1, 43754, 43749, 43745, -1, 43754, 43755, 43749, -1, 43756, 43738, 43734, -1, 43757, 43758, 43740, -1, 43756, 43759, 43738, -1, 43757, 43740, 43739, -1, 43760, 33252, 33251, -1, 43760, 43761, 33252, -1, 43762, 43736, 43742, -1, 43763, 43755, 43754, -1, 43762, 43742, 43741, -1, 43764, 43765, 31290, -1, 43763, 43737, 43755, -1, 43764, 33199, 43765, -1, 43764, 43744, 33199, -1, 43766, 31142, 31143, -1, 43767, 43753, 43750, -1, 43766, 31143, 43758, -1, 43767, 43768, 43753, -1, 43766, 43758, 43757, -1, 43769, 43747, 43761, -1, 43769, 43761, 43760, -1, 43770, 43736, 43762, -1, 43770, 43734, 43736, -1, 43751, 43731, 43737, -1, 43751, 43737, 43763, -1, 43771, 43752, 43759, -1, 43771, 43759, 43756, -1, 43735, 43745, 43747, -1, 43772, 31290, 31289, -1, 43735, 43747, 43769, -1, 43772, 43741, 43744, -1, 43772, 43744, 43764, -1, 43772, 43764, 31290, -1, 43753, 43739, 43731, -1, 43773, 31140, 31139, -1, 43753, 43731, 43751, -1, 43773, 43774, 43768, -1, 43773, 43768, 43767, -1, 43773, 31139, 43774, -1, 43775, 43756, 43734, -1, 43776, 33251, 33225, -1, 43775, 43734, 43770, -1, 43776, 43760, 33251, -1, 43777, 43750, 43752, -1, 43777, 43752, 43771, -1, 43738, 43754, 43745, -1, 43778, 31289, 31288, -1, 43738, 43745, 43735, -1, 43778, 43762, 43741, -1, 43778, 43772, 31289, -1, 43778, 43741, 43772, -1, 43768, 43739, 43753, -1, 43768, 43757, 43739, -1, 43779, 43767, 43750, -1, 43742, 43769, 43760, -1, 43779, 43750, 43777, -1, 43780, 31286, 31284, -1, 43780, 31288, 31286, -1, 43780, 43770, 43762, -1, 43742, 43776, 33225, -1, 43780, 43762, 43778, -1, 43742, 43760, 43776, -1, 43780, 43778, 31288, -1, 43781, 33219, 33218, -1, 43782, 43756, 43775, -1, 43782, 43771, 43756, -1, 43759, 43754, 43738, -1, 43746, 33219, 43781, -1, 43783, 31293, 31292, -1, 43759, 43763, 43754, -1, 43783, 43777, 43771, -1, 43783, 43771, 43782, -1, 43749, 33219, 43746, -1, 43784, 31284, 31283, -1, 43784, 43770, 43780, -1, 43744, 33225, 33199, -1, 43784, 43775, 43770, -1, 43755, 33219, 43749, -1, 43784, 43780, 31284, -1, 43785, 31291, 31141, -1, 43785, 31141, 31140, -1, 43785, 31140, 43773, -1, 43785, 43767, 43779, -1, 43785, 43773, 43767, -1, 43786, 31292, 31291, -1, 43737, 33219, 43755, -1, 43786, 43777, 43783, -1, 43736, 43769, 43742, -1, 43737, 43733, 33219, -1, 43786, 43779, 43777, -1, 43786, 31291, 43785, -1, 43736, 43735, 43769, -1, 43786, 43783, 31292, -1, 43774, 31139, 31142, -1, 43786, 43785, 43779, -1, 43774, 43757, 43768, -1, 43787, 31287, 31293, -1, 43774, 31142, 43766, -1, 43761, 33218, 33252, -1, 43787, 31283, 31287, -1, 43787, 43784, 31283, -1, 43774, 43766, 43757, -1, 43787, 31293, 43783, -1, 43787, 43782, 43775, -1, 43787, 43783, 43782, -1, 43787, 43775, 43784, -1, 43761, 43781, 33218, -1, 43752, 43763, 43759, -1, 43752, 43751, 43763, -1, 43747, 43746, 43781, -1, 43747, 43781, 43761, -1, 33257, 33253, 43743, -1, 43788, 43743, 43748, -1, 43788, 33257, 43743, -1, 43789, 43748, 43733, -1, 43789, 43788, 43748, -1, 43790, 43733, 43732, -1, 43790, 43789, 43733, -1, 43791, 43732, 43740, -1, 43791, 43790, 43732, -1, 12574, 43758, 31143, -1, 43792, 43740, 43758, -1, 43792, 43791, 43740, -1, 43793, 43792, 43758, -1, 43794, 43758, 12574, -1, 43794, 43793, 43758, -1, 12427, 43794, 12574, -1, 30248, 43794, 12427, -1, 43795, 33257, 43788, -1, 43795, 33256, 33257, -1, 43796, 43788, 43789, -1, 43796, 43795, 43788, -1, 43797, 43789, 43790, -1, 43797, 43796, 43789, -1, 43798, 43790, 43791, -1, 43798, 43797, 43790, -1, 8401, 43794, 30248, -1, 43799, 43791, 43792, -1, 43799, 43798, 43791, -1, 43800, 43792, 43793, -1, 43800, 43793, 43794, -1, 43800, 43799, 43792, -1, 8397, 43800, 43794, -1, 8397, 43794, 8401, -1, 43801, 43802, 43803, -1, 43804, 43805, 43806, -1, 43804, 43807, 43808, -1, 43804, 43809, 43805, -1, 43804, 43808, 43809, -1, 43810, 43811, 43802, -1, 43810, 43802, 43801, -1, 43812, 43806, 43813, -1, 43812, 43807, 43804, -1, 43812, 43814, 43807, -1, 43812, 43804, 43806, -1, 43815, 33263, 33261, -1, 43815, 43811, 43810, -1, 43815, 33261, 43816, -1, 43815, 43816, 43811, -1, 43817, 43813, 43818, -1, 43817, 43814, 43812, -1, 43817, 43801, 43814, -1, 43817, 43812, 43813, -1, 43819, 43818, 43820, -1, 43819, 43810, 43801, -1, 43819, 43817, 43818, -1, 43819, 43801, 43817, -1, 43821, 33265, 33263, -1, 43821, 43820, 33265, -1, 43821, 33263, 43815, -1, 43821, 43815, 43810, -1, 43821, 43819, 43820, -1, 43821, 43810, 43819, -1, 43822, 8403, 8402, -1, 33267, 33265, 43820, -1, 43823, 43800, 8397, -1, 43823, 8397, 8399, -1, 43824, 43799, 43800, -1, 43824, 43800, 43823, -1, 43803, 43798, 43799, -1, 43803, 43799, 43824, -1, 43808, 8399, 8398, -1, 43808, 43823, 8399, -1, 43802, 43797, 43798, -1, 43802, 43798, 43803, -1, 43807, 43823, 43808, -1, 43807, 43824, 43823, -1, 43811, 43796, 43797, -1, 43811, 43797, 43802, -1, 43814, 43803, 43824, -1, 43814, 43824, 43807, -1, 43816, 33256, 43795, -1, 43816, 43795, 43796, -1, 43816, 33261, 33256, -1, 43816, 43796, 43811, -1, 43809, 8398, 8403, -1, 43809, 43822, 43805, -1, 43809, 8403, 43822, -1, 43809, 43808, 8398, -1, 43801, 43803, 43814, -1, 33269, 33267, 43820, -1, 43825, 43820, 43818, -1, 43825, 33269, 43820, -1, 43826, 43818, 43813, -1, 43826, 43825, 43818, -1, 43827, 43813, 43806, -1, 43827, 43826, 43813, -1, 43828, 43806, 43805, -1, 43828, 43827, 43806, -1, 43829, 43805, 43822, -1, 43829, 43828, 43805, -1, 43830, 43829, 43822, -1, 8404, 43822, 8402, -1, 8404, 43830, 43822, -1, 43831, 43832, 43833, -1, 43834, 43826, 43827, -1, 43834, 43835, 43826, -1, 43834, 43836, 43835, -1, 43834, 43837, 43836, -1, 43838, 43839, 43831, -1, 43838, 43840, 43839, -1, 43841, 43827, 43828, -1, 43841, 43834, 43827, -1, 43841, 43833, 43837, -1, 43841, 43837, 43834, -1, 43842, 8453, 8459, -1, 43842, 8459, 43843, -1, 43842, 43843, 43840, -1, 43842, 43840, 43838, -1, 43844, 43828, 43829, -1, 43844, 43831, 43833, -1, 43844, 43841, 43828, -1, 43844, 43833, 43841, -1, 43845, 43829, 43830, -1, 43845, 43831, 43844, -1, 43845, 43838, 43831, -1, 43845, 43844, 43829, -1, 43846, 43830, 8404, -1, 43846, 8404, 8453, -1, 43846, 43845, 43830, -1, 43846, 8453, 43842, -1, 43846, 43842, 43838, -1, 43846, 43838, 43845, -1, 8461, 8468, 43847, -1, 43825, 33277, 33269, -1, 43848, 43849, 33272, -1, 43848, 33272, 33271, -1, 43850, 43851, 43849, -1, 43850, 43849, 43848, -1, 43832, 43852, 43851, -1, 43832, 43851, 43850, -1, 43836, 33271, 33275, -1, 43836, 43848, 33271, -1, 43839, 43853, 43852, -1, 43839, 43852, 43832, -1, 43837, 43850, 43848, -1, 43837, 43848, 43836, -1, 43840, 43854, 43853, -1, 43840, 43853, 43839, -1, 43833, 43832, 43850, -1, 43833, 43850, 43837, -1, 43835, 43825, 43826, -1, 43835, 33275, 33277, -1, 43835, 33277, 43825, -1, 43835, 43836, 33275, -1, 43843, 8459, 8461, -1, 43843, 43847, 43854, -1, 43843, 8461, 43847, -1, 43843, 43854, 43840, -1, 43831, 43839, 43832, -1, 43855, 33272, 43849, -1, 43855, 33280, 33272, -1, 43856, 43849, 43851, -1, 43856, 43855, 43849, -1, 43857, 43851, 43852, -1, 43857, 43856, 43851, -1, 43858, 43852, 43853, -1, 43858, 43857, 43852, -1, 43859, 43853, 43854, -1, 43859, 43858, 43853, -1, 43860, 43854, 43847, -1, 43860, 43859, 43854, -1, 8719, 43847, 8468, -1, 8719, 43860, 43847, -1, 43861, 43862, 43863, -1, 43861, 43863, 43855, -1, 43861, 43864, 43862, -1, 43865, 43866, 43867, -1, 41398, 43868, 41399, -1, 43865, 43867, 43869, -1, 43870, 43856, 43857, -1, 43870, 43871, 43864, -1, 43870, 43861, 43856, -1, 43870, 43864, 43861, -1, 43872, 8914, 8917, -1, 43872, 8917, 43873, -1, 43872, 43873, 43866, -1, 43872, 43866, 43865, -1, 43874, 43857, 43858, -1, 43874, 43870, 43857, -1, 43874, 43869, 43871, -1, 43874, 43871, 43870, -1, 43875, 43858, 43859, -1, 43875, 43865, 43869, -1, 43875, 43874, 43858, -1, 43875, 43869, 43874, -1, 43876, 43859, 43860, -1, 43876, 8912, 8914, -1, 43876, 8914, 43872, -1, 43876, 43875, 43859, -1, 43876, 43860, 8912, -1, 43876, 43872, 43865, -1, 43876, 43865, 43875, -1, 8719, 8912, 43860, -1, 43877, 43878, 43868, -1, 43877, 43868, 41398, -1, 43879, 43880, 43878, -1, 43879, 43878, 43877, -1, 43881, 43882, 43880, -1, 43881, 43880, 43879, -1, 43862, 41398, 41402, -1, 43862, 43877, 41398, -1, 43867, 43883, 43882, -1, 43867, 43882, 43881, -1, 43864, 43877, 43862, -1, 43864, 43879, 43877, -1, 43866, 43884, 43883, -1, 43866, 43883, 43867, -1, 43871, 43879, 43864, -1, 43871, 43881, 43879, -1, 43863, 33280, 43855, -1, 43863, 41404, 33280, -1, 43863, 41402, 41404, -1, 43863, 43862, 41402, -1, 43873, 8917, 8659, -1, 43873, 8659, 43884, -1, 43873, 43884, 43866, -1, 43869, 43881, 43871, -1, 43869, 43867, 43881, -1, 43861, 43855, 43856, -1, 43884, 8659, 8653, -1, 43884, 8653, 43885, -1, 43883, 43885, 43886, -1, 43883, 43884, 43885, -1, 43882, 43886, 43887, -1, 43882, 43883, 43886, -1, 43880, 43887, 43888, -1, 43880, 43882, 43887, -1, 43878, 43888, 43889, -1, 43878, 43880, 43888, -1, 43868, 43889, 43890, -1, 43868, 43878, 43889, -1, 41399, 43890, 41406, -1, 41399, 43868, 43890, -1, 43891, 43892, 43893, -1, 43891, 43893, 43894, -1, 43895, 43896, 43897, -1, 43895, 43897, 43898, -1, 43899, 43900, 43901, -1, 43899, 43902, 43892, -1, 43899, 43892, 43891, -1, 8655, 43885, 8653, -1, 43899, 43891, 43900, -1, 43903, 41410, 41408, -1, 43903, 41408, 43904, -1, 43903, 43896, 43895, -1, 43903, 43904, 43896, -1, 43905, 43901, 43906, -1, 43905, 43899, 43901, -1, 43905, 43898, 43902, -1, 43905, 43902, 43899, -1, 43907, 43906, 43908, -1, 43907, 43905, 43906, -1, 43907, 43895, 43898, -1, 43907, 43898, 43905, -1, 43909, 43908, 43910, -1, 43909, 41412, 41410, -1, 43909, 43910, 41412, -1, 43909, 43907, 43908, -1, 43909, 41410, 43903, -1, 43909, 43903, 43895, -1, 43909, 43895, 43907, -1, 41414, 41412, 43910, -1, 43911, 43886, 43885, -1, 43911, 8655, 8654, -1, 43911, 43885, 8655, -1, 43912, 43887, 43886, -1, 43912, 43886, 43911, -1, 43913, 43888, 43887, -1, 43913, 43887, 43912, -1, 43893, 8654, 8657, -1, 43893, 43911, 8654, -1, 43897, 43889, 43888, -1, 43897, 43888, 43913, -1, 43892, 43911, 43893, -1, 43892, 43912, 43911, -1, 43896, 43890, 43889, -1, 43896, 43889, 43897, -1, 43902, 43913, 43912, -1, 43902, 43912, 43892, -1, 43904, 41406, 43890, -1, 43904, 41408, 41406, -1, 43904, 43890, 43896, -1, 43894, 8657, 8656, -1, 43894, 8656, 43914, -1, 43894, 43893, 8657, -1, 43898, 43913, 43902, -1, 43898, 43897, 43913, -1, 43891, 43914, 43900, -1, 43891, 43894, 43914, -1, 43915, 8393, 30204, -1, 8656, 8393, 43915, -1, 43914, 43916, 43917, -1, 43914, 43915, 43916, -1, 43914, 8656, 43915, -1, 43900, 43917, 43918, -1, 43900, 43914, 43917, -1, 43901, 43918, 43919, -1, 43901, 43900, 43918, -1, 43906, 43919, 43920, -1, 43906, 43901, 43919, -1, 43908, 43920, 43921, -1, 43908, 43906, 43920, -1, 43910, 43921, 41417, -1, 43910, 43908, 43921, -1, 41414, 43910, 41417, -1, 43922, 10366, 38988, -1, 43915, 30204, 10367, -1, 43915, 10367, 10366, -1, 43915, 10366, 43922, -1, 43916, 43915, 43922, -1, 43917, 43922, 43923, -1, 43917, 43916, 43922, -1, 43918, 43923, 43924, -1, 43918, 43917, 43923, -1, 43919, 43924, 43925, -1, 43919, 43918, 43924, -1, 43920, 43925, 43926, -1, 43920, 43919, 43925, -1, 43921, 43926, 43927, -1, 43921, 43920, 43926, -1, 41417, 43927, 41422, -1, 41417, 43921, 43927, -1, 43928, 43929, 39178, -1, 43930, 43924, 43931, -1, 43928, 43932, 43929, -1, 43928, 43933, 43932, -1, 43934, 43935, 43933, -1, 43934, 39176, 39190, -1, 43936, 43926, 43925, -1, 43934, 39190, 41443, -1, 43934, 41443, 43937, -1, 43936, 43925, 43930, -1, 43934, 43937, 43935, -1, 43938, 43933, 43928, -1, 43938, 39177, 39176, -1, 43939, 43940, 43941, -1, 43938, 39176, 43934, -1, 43938, 43934, 43933, -1, 43938, 43928, 39177, -1, 38992, 43923, 43922, -1, 43942, 39186, 39185, -1, 38992, 43922, 38988, -1, 43942, 39187, 39186, -1, 43942, 43943, 39187, -1, 43944, 43945, 43946, -1, 43942, 43941, 43943, -1, 43944, 43946, 43947, -1, 43924, 43923, 38992, -1, 43948, 43926, 43936, -1, 43949, 43950, 43939, -1, 43951, 43952, 43945, -1, 43951, 43945, 43944, -1, 43949, 43953, 43950, -1, 43954, 43939, 43941, -1, 43954, 43941, 43942, -1, 43954, 43942, 39185, -1, 43955, 43956, 43957, -1, 43958, 43952, 43951, -1, 43958, 43931, 43952, -1, 43955, 43957, 43959, -1, 43960, 43949, 43939, -1, 43961, 38990, 38989, -1, 41449, 41422, 43927, -1, 43960, 43939, 43954, -1, 43962, 43927, 43926, -1, 43962, 41449, 43927, -1, 43962, 43926, 43948, -1, 43963, 43953, 43949, -1, 43964, 43961, 38989, -1, 43964, 38990, 43961, -1, 43964, 43947, 38990, -1, 43963, 43965, 43953, -1, 43966, 43930, 43931, -1, 43967, 43968, 43965, -1, 43967, 43965, 43963, -1, 43966, 43931, 43958, -1, 43969, 39185, 39183, -1, 43970, 43930, 43966, -1, 43969, 43954, 39185, -1, 43970, 43936, 43930, -1, 43971, 43949, 43960, -1, 43971, 43963, 43949, -1, 43972, 43973, 43956, -1, 43940, 43947, 43964, -1, 43972, 41463, 43973, -1, 43940, 43944, 43947, -1, 43972, 43956, 43955, -1, 43974, 39182, 39181, -1, 43957, 43936, 43970, -1, 43974, 39183, 39182, -1, 43974, 43969, 39183, -1, 43957, 43948, 43936, -1, 43974, 43960, 43954, -1, 43974, 43954, 43969, -1, 43975, 43959, 43968, -1, 43975, 43968, 43967, -1, 43950, 43951, 43944, -1, 43950, 43944, 43940, -1, 43976, 43967, 43963, -1, 43953, 43951, 43950, -1, 43976, 43963, 43971, -1, 43953, 43958, 43951, -1, 43935, 43975, 43967, -1, 43956, 43948, 43957, -1, 43935, 43967, 43976, -1, 43977, 38992, 38991, -1, 43956, 43962, 43948, -1, 43978, 43974, 39181, -1, 43978, 43960, 43974, -1, 43943, 39188, 39187, -1, 43943, 38989, 39188, -1, 43978, 43971, 43960, -1, 43946, 38992, 43977, -1, 43943, 43964, 38989, -1, 43979, 43959, 43975, -1, 43979, 43955, 43959, -1, 43965, 43958, 43953, -1, 43945, 38992, 43946, -1, 43965, 43966, 43958, -1, 43932, 43976, 43971, -1, 43932, 43971, 43978, -1, 43980, 39181, 39180, -1, 43952, 38992, 43945, -1, 43980, 43978, 39181, -1, 43968, 43966, 43965, -1, 43968, 43970, 43966, -1, 43931, 38992, 43952, -1, 43937, 41443, 43979, -1, 43973, 43962, 43956, -1, 43931, 43924, 38992, -1, 43937, 43975, 43935, -1, 43973, 41467, 41449, -1, 43973, 41463, 41467, -1, 43937, 43979, 43975, -1, 43973, 41449, 43962, -1, 43981, 38991, 38990, -1, 43941, 43964, 43943, -1, 43941, 43940, 43964, -1, 43981, 43977, 38991, -1, 43933, 43935, 43976, -1, 43933, 43976, 43932, -1, 43929, 39179, 39178, -1, 43929, 39180, 39179, -1, 43929, 43932, 43978, -1, 43929, 43980, 39180, -1, 43947, 43981, 38990, -1, 43947, 43977, 43981, -1, 43929, 43978, 43980, -1, 43959, 43970, 43968, -1, 43982, 41443, 41463, -1, 43959, 43957, 43970, -1, 43982, 43979, 41443, -1, 43982, 41463, 43972, -1, 43947, 43946, 43977, -1, 43982, 43972, 43955, -1, 43982, 43955, 43979, -1, 43939, 43950, 43940, -1, 43930, 43925, 43924, -1, 43928, 39178, 39177, -1, 41932, 41935, 39475, -1, 42030, 41935, 42031, -1, 39475, 41935, 42030, -1, 37084, 37081, 37086, -1, 37082, 37081, 37084, -1, 37059, 37081, 37082, -1, 37056, 31615, 37059, -1, 37054, 31615, 37056, -1, 37052, 31615, 37054, -1, 37050, 31615, 37052, -1, 37059, 31615, 37081, -1, 31615, 37080, 37081, -1, 37080, 42091, 42089, -1, 37080, 42093, 42091, -1, 37080, 42081, 42093, -1, 37080, 42073, 42081, -1, 42073, 42077, 42075, -1, 42073, 42079, 42077, -1, 31615, 39477, 37080, -1, 37080, 39477, 42073, -1, 42073, 39477, 42079, -1, 37009, 37008, 31609, -1, 37008, 37007, 31609, -1, 37007, 36906, 31609, -1, 36906, 36898, 31609, -1, 36899, 36901, 36898, -1, 36901, 36903, 36898, -1, 36903, 36895, 36898, -1, 36898, 36895, 31609, -1, 31609, 39475, 31615, -1, 31615, 39475, 39477, -1, 36895, 36894, 31609, -1, 31609, 36894, 39475, -1, 39475, 42030, 42029, -1, 41930, 41932, 41928, -1, 36894, 41932, 39475, -1, 41928, 41932, 41926, -1, 41926, 41932, 36894, -1, 42758, 42768, 42756, -1, 42760, 42768, 42758, -1, 42762, 42768, 42760, -1, 42764, 42768, 42762, -1, 42766, 42768, 42764, -1, 42756, 42752, 42754, -1, 42768, 42752, 42756, -1, 42768, 42750, 42752, -1, 42750, 42746, 42748, -1, 42768, 42746, 42750, -1, 42768, 42744, 42746, -1, 42768, 42743, 42744, -1, 42729, 42730, 42728, -1, 42730, 42731, 42728, -1, 42731, 42732, 42728, -1, 42732, 42733, 42728, -1, 42733, 42734, 42728, -1, 42728, 42741, 42768, -1, 42768, 42741, 42743, -1, 42734, 42735, 42728, -1, 42728, 42740, 42741, -1, 42735, 42736, 42728, -1, 42728, 42739, 42740, -1, 42736, 42737, 42728, -1, 42728, 42737, 42739, -1, 42737, 42738, 42739, -1, 42420, 42426, 42418, -1, 42422, 42426, 42420, -1, 42424, 42426, 42422, -1, 42426, 42428, 42418, -1, 42416, 42412, 42414, -1, 42418, 42412, 42416, -1, 42408, 42404, 42406, -1, 42410, 42404, 42408, -1, 42412, 42404, 42410, -1, 42428, 42402, 42418, -1, 42418, 42402, 42412, -1, 42412, 42402, 42404, -1, 42390, 42391, 42389, -1, 42391, 42392, 42389, -1, 42389, 42393, 42388, -1, 42392, 42393, 42389, -1, 42394, 42401, 42393, -1, 42388, 42401, 42428, -1, 42393, 42401, 42388, -1, 42428, 42401, 42402, -1, 42394, 42395, 42401, -1, 42395, 42396, 42401, -1, 42401, 42399, 42400, -1, 42396, 42397, 42401, -1, 42401, 42398, 42399, -1, 42397, 42398, 42401, -1, 37767, 37741, 37765, -1, 37765, 37741, 37763, -1, 37763, 37741, 37761, -1, 37761, 37741, 37759, -1, 37759, 37741, 37757, -1, 37741, 37755, 37757, -1, 37741, 37753, 37755, -1, 37753, 37749, 37751, -1, 37741, 37749, 37753, -1, 37749, 37744, 37747, -1, 37741, 37744, 37749, -1, 37726, 37742, 37741, -1, 37741, 37742, 37744, -1, 37727, 37728, 37726, -1, 37728, 37729, 37726, -1, 37729, 37730, 37726, -1, 37730, 37731, 37726, -1, 37731, 37732, 37726, -1, 37726, 37739, 37742, -1, 37732, 37733, 37726, -1, 37726, 37738, 37739, -1, 37734, 37735, 37733, -1, 37733, 37735, 37726, -1, 37726, 37735, 37738, -1, 37738, 37736, 37737, -1, 37735, 37736, 37738, -1, 37415, 37417, 37413, -1, 37413, 37409, 37411, -1, 37417, 37407, 37413, -1, 37413, 37407, 37409, -1, 37407, 37403, 37405, -1, 37419, 37399, 37417, -1, 37403, 37399, 37401, -1, 37417, 37399, 37407, -1, 37407, 37399, 37403, -1, 37379, 37380, 37378, -1, 37393, 37394, 37419, -1, 37399, 37394, 37396, -1, 37419, 37394, 37399, -1, 37381, 37382, 37380, -1, 37383, 37384, 37382, -1, 37382, 37384, 37380, -1, 37378, 37391, 37393, -1, 37393, 37391, 37394, -1, 37378, 37390, 37391, -1, 37385, 37389, 37384, -1, 37380, 37389, 37378, -1, 37384, 37389, 37380, -1, 37378, 37389, 37390, -1, 37386, 37387, 37385, -1, 37385, 37387, 37389, -1, 37387, 37388, 37389, -1, 43983, 2129, 43984, -1, 43984, 2129, 2118, -1, 43985, 43986, 43987, -1, 43987, 43983, 43985, -1, 43983, 43988, 43985, -1, 43989, 43990, 43991, -1, 43983, 43992, 43988, -1, 43992, 43993, 43986, -1, 43986, 43993, 43989, -1, 43994, 43984, 43990, -1, 43993, 43984, 43994, -1, 43990, 43984, 43991, -1, 43983, 43984, 43992, -1, 43992, 43984, 43993, -1, 43991, 43987, 43989, -1, 43989, 43987, 43986, -1, 43995, 43993, 43996, -1, 43989, 43993, 43995, -1, 43997, 43998, 43999, -1, 43998, 43996, 43999, -1, 44000, 44001, 44002, -1, 44002, 43995, 43998, -1, 43998, 43995, 43996, -1, 44001, 43995, 44002, -1, 43999, 44001, 43997, -1, 43997, 44001, 44000, -1, 44003, 43992, 43986, -1, 44004, 43992, 44003, -1, 44004, 44005, 44006, -1, 44005, 44007, 44006, -1, 44003, 44008, 44004, -1, 44004, 44008, 44005, -1, 44008, 44009, 44010, -1, 44003, 44009, 44008, -1, 44009, 44006, 44007, -1, 44009, 44007, 44010, -1, 43999, 43996, 43994, -1, 43996, 43993, 43994, -1, 44004, 43988, 43992, -1, 44006, 43988, 44004, -1, 2139, 43987, 43991, -1, 2137, 43987, 2139, -1, 43986, 43985, 44003, -1, 43985, 44009, 44003, -1, 43990, 43995, 44001, -1, 43989, 43995, 43990, -1, 43991, 2118, 2139, -1, 43984, 2118, 43991, -1, 43999, 43994, 44001, -1, 44001, 43994, 43990, -1, 2137, 43983, 43987, -1, 2129, 43983, 2137, -1, 43985, 44006, 44009, -1, 43988, 44006, 43985, -1, 1460, 44011, 1427, -1, 44011, 44005, 44008, -1, 1463, 44005, 44011, -1, 1460, 1463, 44011, -1, 1463, 1462, 44005, -1, 1462, 44007, 44005, -1, 1428, 44012, 1461, -1, 44010, 44007, 44012, -1, 44007, 1462, 44012, -1, 1462, 1461, 44012, -1, 44008, 44010, 44011, -1, 44010, 44012, 44011, -1, 1427, 44012, 1428, -1, 44011, 44012, 1427, -1, 1460, 44013, 44014, -1, 1460, 1461, 44013, -1, 44015, 1461, 1462, -1, 44015, 44013, 1461, -1, 1463, 1460, 44014, -1, 44016, 1462, 1463, -1, 44016, 1463, 44014, -1, 44016, 44015, 1462, -1, 44013, 44017, 44018, -1, 44015, 44017, 44013, -1, 44019, 44015, 44016, -1, 44017, 44015, 44019, -1, 44020, 44016, 44014, -1, 44019, 44016, 44020, -1, 44014, 44018, 44020, -1, 44013, 44018, 44014, -1, 44019, 44020, 44021, -1, 44021, 44020, 44022, -1, 44023, 44021, 44022, -1, 44024, 44021, 44023, -1, 44020, 44023, 44022, -1, 44020, 44018, 44023, -1, 44024, 44019, 44021, -1, 44017, 44019, 44024, -1, 44018, 44017, 44023, -1, 44023, 44017, 44024, -1, 1427, 1428, 1460, -1, 1428, 1461, 1460, -1, 44025, 2222, 2204, -1, 44025, 2204, 1919, -1, 44025, 1919, 1933, -1, 44026, 1933, 1934, -1, 44026, 44025, 1933, -1, 44027, 1934, 1942, -1, 44027, 44026, 1934, -1, 44028, 1942, 1956, -1, 44028, 44027, 1942, -1, 44029, 1956, 1974, -1, 44029, 44028, 1956, -1, 44030, 1974, 1977, -1, 44030, 44029, 1974, -1, 44031, 1977, 1978, -1, 44031, 44030, 1977, -1, 44032, 1978, 1985, -1, 44032, 44031, 1978, -1, 44033, 1985, 1990, -1, 44033, 44032, 1985, -1, 44034, 1990, 2189, -1, 44034, 44033, 1990, -1, 44035, 2189, 2184, -1, 44035, 44034, 2189, -1, 44036, 2184, 2181, -1, 44036, 44035, 2184, -1, 44037, 2181, 2167, -1, 44037, 44036, 2181, -1, 44038, 2167, 2164, -1, 44038, 44037, 2167, -1, 44039, 2164, 2160, -1, 44039, 44038, 2164, -1, 2207, 44039, 2160, -1, 44037, 44040, 44041, -1, 2207, 44042, 44040, -1, 2208, 44042, 2206, -1, 2206, 44042, 2207, -1, 44043, 44027, 44028, -1, 2208, 2209, 44042, -1, 44043, 44029, 44044, -1, 44028, 44029, 44043, -1, 44043, 44045, 44027, -1, 44046, 44047, 2214, -1, 44045, 44026, 44027, -1, 2214, 44047, 2213, -1, 2213, 44047, 2212, -1, 2212, 44047, 2211, -1, 44029, 44030, 44044, -1, 2209, 44048, 44042, -1, 2211, 44048, 2210, -1, 2210, 44048, 2209, -1, 44047, 44048, 2211, -1, 44045, 44025, 44026, -1, 44030, 44031, 44044, -1, 44049, 2222, 44045, -1, 44045, 2222, 44025, -1, 44031, 44032, 44044, -1, 44049, 2221, 2222, -1, 44049, 2220, 2221, -1, 44034, 44050, 44033, -1, 44033, 44050, 44032, -1, 44032, 44050, 44044, -1, 44049, 2219, 2220, -1, 44050, 44035, 44041, -1, 44034, 44035, 44050, -1, 44035, 44036, 44041, -1, 44036, 44037, 44041, -1, 2219, 44051, 2218, -1, 2218, 44051, 2217, -1, 44049, 44051, 2219, -1, 44051, 44046, 2217, -1, 44046, 2216, 2217, -1, 44046, 2215, 2216, -1, 44046, 2214, 2215, -1, 2207, 44040, 44039, -1, 44039, 44040, 44038, -1, 44038, 44040, 44037, -1, 44052, 44053, 44040, -1, 44053, 44041, 44040, -1, 44053, 44054, 44041, -1, 44055, 44056, 44057, -1, 44055, 44058, 44056, -1, 44059, 44055, 44054, -1, 44059, 44058, 44055, -1, 44060, 44059, 44054, -1, 44061, 44060, 44054, -1, 44054, 44053, 44061, -1, 44062, 44063, 44048, -1, 44063, 44042, 44048, -1, 44063, 44064, 44042, -1, 44065, 44066, 44067, -1, 44065, 44068, 44066, -1, 44062, 44069, 44070, -1, 44062, 44067, 44069, -1, 44062, 44065, 44067, -1, 44065, 44071, 44068, -1, 44063, 44062, 44070, -1, 44072, 44073, 44074, -1, 44072, 44075, 44073, -1, 44076, 44074, 44077, -1, 44076, 44072, 44074, -1, 44078, 44077, 44079, -1, 44078, 44076, 44077, -1, 44080, 44079, 44081, -1, 44080, 44078, 44079, -1, 44082, 44081, 44083, -1, 44082, 44080, 44081, -1, 44084, 44083, 44085, -1, 44084, 44082, 44083, -1, 44086, 44085, 44087, -1, 44086, 44084, 44085, -1, 44088, 44087, 44089, -1, 44088, 44086, 44087, -1, 44071, 44089, 44090, -1, 44071, 44088, 44089, -1, 44068, 44090, 44091, -1, 44068, 44071, 44090, -1, 44066, 44091, 44092, -1, 44066, 44068, 44091, -1, 44067, 44092, 44093, -1, 44067, 44066, 44092, -1, 44069, 44093, 44094, -1, 44069, 44067, 44093, -1, 44070, 44094, 44095, -1, 44070, 44069, 44094, -1, 44063, 44095, 44096, -1, 44063, 44070, 44095, -1, 44097, 44096, 44098, -1, 44097, 44063, 44096, -1, 44099, 44097, 44098, -1, 44099, 44098, 44100, -1, 44101, 44099, 44100, -1, 44102, 44103, 44104, -1, 44102, 44104, 44105, -1, 44106, 44107, 44108, -1, 44109, 44091, 44090, -1, 44106, 44108, 44110, -1, 44109, 44090, 44111, -1, 44109, 44111, 44103, -1, 44112, 44107, 44106, -1, 44109, 44103, 44102, -1, 44113, 44114, 44115, -1, 44112, 44116, 44107, -1, 44113, 44105, 44114, -1, 44117, 44118, 44116, -1, 44117, 44119, 44118, -1, 44117, 44074, 44119, -1, 44117, 44116, 44112, -1, 44120, 44102, 44105, -1, 44121, 44110, 44122, -1, 44121, 44106, 44110, -1, 44120, 44105, 44113, -1, 44123, 44092, 44091, -1, 44123, 44091, 44109, -1, 44123, 44109, 44102, -1, 44123, 44102, 44120, -1, 44110, 44108, 44124, -1, 44125, 44115, 44126, -1, 44127, 44106, 44121, -1, 44127, 44112, 44106, -1, 44125, 44113, 44115, -1, 44128, 44112, 44127, -1, 44128, 44077, 44074, -1, 44128, 44074, 44117, -1, 44128, 44117, 44112, -1, 44074, 44073, 44119, -1, 44129, 44120, 44113, -1, 44130, 44122, 44131, -1, 44129, 44113, 44125, -1, 44132, 44092, 44123, -1, 44132, 44093, 44092, -1, 44130, 44121, 44122, -1, 44132, 44123, 44120, -1, 44133, 44127, 44121, -1, 44132, 44120, 44129, -1, 44134, 44126, 44135, -1, 44133, 44121, 44130, -1, 44134, 44125, 44126, -1, 44136, 44128, 44127, -1, 44136, 44079, 44077, -1, 44136, 44077, 44128, -1, 44136, 44127, 44133, -1, 44137, 44129, 44125, -1, 44138, 44131, 44139, -1, 44137, 44125, 44134, -1, 44138, 44130, 44131, -1, 44140, 44094, 44093, -1, 44140, 44093, 44132, -1, 44140, 44132, 44129, -1, 44140, 44129, 44137, -1, 44141, 44133, 44130, -1, 44142, 44135, 44143, -1, 44141, 44130, 44138, -1, 44144, 44133, 44141, -1, 44142, 44134, 44135, -1, 44144, 44079, 44136, -1, 44144, 44081, 44079, -1, 44145, 44134, 44142, -1, 44144, 44136, 44133, -1, 44145, 44137, 44134, -1, 44146, 44139, 44147, -1, 44148, 44094, 44140, -1, 44146, 44138, 44139, -1, 44148, 44140, 44137, -1, 44148, 44137, 44145, -1, 44148, 44095, 44094, -1, 44149, 44138, 44146, -1, 44150, 44143, 44151, -1, 44149, 44141, 44138, -1, 44152, 44083, 44081, -1, 44150, 44142, 44143, -1, 44152, 44081, 44144, -1, 44152, 44144, 44141, -1, 44152, 44141, 44149, -1, 44153, 44142, 44150, -1, 44153, 44145, 44142, -1, 44154, 44147, 44155, -1, 44156, 44148, 44145, -1, 44154, 44146, 44147, -1, 44156, 44095, 44148, -1, 44156, 44145, 44153, -1, 44156, 44096, 44095, -1, 44157, 44151, 44158, -1, 44159, 44146, 44154, -1, 44157, 44150, 44151, -1, 44159, 44149, 44146, -1, 44157, 44160, 44161, -1, 44162, 44085, 44083, -1, 44162, 44083, 44152, -1, 44157, 44158, 44160, -1, 44162, 44149, 44159, -1, 44162, 44152, 44149, -1, 44163, 44150, 44157, -1, 44163, 44153, 44150, -1, 44163, 44161, 44164, -1, 44165, 44155, 44166, -1, 44163, 44164, 44167, -1, 44163, 44157, 44161, -1, 44165, 44154, 44155, -1, 44168, 44156, 44153, -1, 44169, 44159, 44154, -1, 44168, 44096, 44156, -1, 44168, 44167, 44170, -1, 44168, 44153, 44163, -1, 44168, 44163, 44167, -1, 44168, 44170, 44098, -1, 44169, 44154, 44165, -1, 44168, 44098, 44096, -1, 44171, 44087, 44085, -1, 44171, 44162, 44159, -1, 44171, 44159, 44169, -1, 44171, 44085, 44162, -1, 44172, 44166, 44173, -1, 44172, 44165, 44166, -1, 44174, 44169, 44165, -1, 44174, 44165, 44172, -1, 44175, 44089, 44087, -1, 44175, 44087, 44171, -1, 44175, 44171, 44169, -1, 44175, 44169, 44174, -1, 44104, 44173, 44176, -1, 44104, 44172, 44173, -1, 44160, 44158, 44177, -1, 44103, 44174, 44172, -1, 44103, 44172, 44104, -1, 44111, 44090, 44089, -1, 44111, 44089, 44175, -1, 44111, 44175, 44174, -1, 44111, 44174, 44103, -1, 44105, 44176, 44114, -1, 44105, 44104, 44176, -1, 44100, 44098, 44170, -1, 44115, 44178, 44179, -1, 44126, 44115, 44179, -1, 44126, 44179, 44180, -1, 44110, 44124, 44181, -1, 44110, 44181, 44182, -1, 44183, 44131, 44122, -1, 44183, 44122, 44110, -1, 44183, 44184, 44185, -1, 44183, 44186, 44184, -1, 44183, 44110, 44186, -1, 44183, 44185, 44131, -1, 44187, 44147, 44139, -1, 44187, 44139, 44131, -1, 44187, 44185, 44188, -1, 44187, 44131, 44185, -1, 44186, 44182, 44189, -1, 44187, 44188, 44147, -1, 44190, 44191, 44158, -1, 44186, 44110, 44182, -1, 44190, 44158, 44151, -1, 44190, 44151, 44143, -1, 44190, 44192, 44191, -1, 44190, 44193, 44192, -1, 44190, 44143, 44193, -1, 44194, 44143, 44135, -1, 44194, 44135, 44126, -1, 44194, 44126, 44180, -1, 44194, 44180, 44193, -1, 44194, 44193, 44143, -1, 44195, 44147, 44188, -1, 44155, 44147, 44195, -1, 44196, 44155, 44195, -1, 44166, 44196, 44197, -1, 44166, 44155, 44196, -1, 44191, 44198, 44199, -1, 44173, 44197, 44200, -1, 44173, 44166, 44197, -1, 44176, 44173, 44200, -1, 44158, 44201, 44177, -1, 44158, 44199, 44201, -1, 44158, 44191, 44199, -1, 44114, 44176, 44200, -1, 44114, 44200, 44178, -1, 44115, 44114, 44178, -1, 44202, 44203, 44204, -1, 44199, 44203, 44202, -1, 44199, 44198, 44203, -1, 44201, 44199, 44202, -1, 44177, 44201, 44202, -1, 44205, 44206, 44207, -1, 44205, 44207, 44208, -1, 44205, 44209, 44210, -1, 44205, 44210, 44206, -1, 44205, 44208, 44209, -1, 44211, 44212, 44213, -1, 44211, 44213, 44214, -1, 44211, 44215, 44216, -1, 44211, 44216, 44212, -1, 44211, 44214, 44215, -1, 44217, 44218, 44206, -1, 44217, 44206, 44210, -1, 44219, 44220, 44218, -1, 44219, 44218, 44217, -1, 44221, 44208, 44222, -1, 44221, 44209, 44208, -1, 44181, 44124, 44223, -1, 44224, 44223, 44220, -1, 44224, 44220, 44219, -1, 44182, 44181, 44223, -1, 44182, 44223, 44224, -1, 44225, 44222, 44226, -1, 44225, 44226, 44227, -1, 44225, 44221, 44222, -1, 44189, 44182, 44224, -1, 44228, 44227, 44229, -1, 44228, 44225, 44227, -1, 44230, 44228, 44229, -1, 44212, 44230, 44229, -1, 44216, 44230, 44212, -1, 44231, 44215, 44214, -1, 44232, 44231, 44214, -1, 44233, 44231, 44232, -1, 44204, 44203, 44233, -1, 44204, 44233, 44232, -1, 44234, 44235, 44198, -1, 44198, 44235, 44203, -1, 44203, 44236, 44233, -1, 44235, 44236, 44203, -1, 44233, 44237, 44231, -1, 44236, 44237, 44233, -1, 44231, 44238, 44215, -1, 44237, 44238, 44231, -1, 44215, 44239, 44216, -1, 44238, 44239, 44215, -1, 44216, 44240, 44230, -1, 44239, 44240, 44216, -1, 44230, 44241, 44228, -1, 44240, 44241, 44230, -1, 44228, 44242, 44225, -1, 44241, 44242, 44228, -1, 44225, 44243, 44221, -1, 44242, 44243, 44225, -1, 44209, 44244, 44210, -1, 44221, 44244, 44209, -1, 44243, 44244, 44221, -1, 44210, 44245, 44217, -1, 44244, 44245, 44210, -1, 44245, 44246, 44217, -1, 44219, 44247, 44224, -1, 44217, 44247, 44219, -1, 44246, 44247, 44217, -1, 44224, 44248, 44189, -1, 44247, 44248, 44224, -1, 44248, 44249, 44189, -1, 44250, 44082, 44084, -1, 44250, 44080, 44082, -1, 44251, 44250, 44084, -1, 44086, 44251, 44084, -1, 44088, 44251, 44086, -1, 44250, 44078, 44080, -1, 44071, 44251, 44088, -1, 44252, 44253, 44254, -1, 44075, 44255, 44253, -1, 44075, 44253, 44252, -1, 44072, 44255, 44075, -1, 44076, 44255, 44072, -1, 44253, 44256, 44254, -1, 44078, 44255, 44076, -1, 44251, 44071, 44046, -1, 44071, 44047, 44046, -1, 44071, 44065, 44047, -1, 44255, 44078, 44049, -1, 44078, 44051, 44049, -1, 44078, 44250, 44051, -1, 44257, 44256, 44043, -1, 44256, 44045, 44043, -1, 44256, 44253, 44045, -1, 44258, 44259, 44257, -1, 44260, 44257, 44261, -1, 44260, 44258, 44257, -1, 44262, 44260, 44261, -1, 44263, 44262, 44261, -1, 44057, 44263, 44261, -1, 44256, 44257, 44259, -1, 44044, 44057, 44261, -1, 44044, 44050, 44057, -1, 44050, 44055, 44057, -1, 44052, 44264, 44265, -1, 44052, 44101, 44264, -1, 44064, 44099, 44101, -1, 44064, 44101, 44052, -1, 44097, 44099, 44064, -1, 44064, 44063, 44097, -1, 44053, 44052, 44265, -1, 44264, 44101, 44100, -1, 44264, 44100, 44266, -1, 44265, 44266, 44267, -1, 44265, 44264, 44266, -1, 44053, 44267, 44268, -1, 44053, 44265, 44267, -1, 44061, 44268, 44269, -1, 44061, 44053, 44268, -1, 44060, 44269, 44270, -1, 44060, 44061, 44269, -1, 44059, 44270, 44271, -1, 44059, 44060, 44270, -1, 44058, 44271, 44272, -1, 44058, 44059, 44271, -1, 44056, 44272, 44273, -1, 44056, 44058, 44272, -1, 44057, 44273, 44274, -1, 44057, 44056, 44273, -1, 44263, 44274, 44275, -1, 44263, 44057, 44274, -1, 44262, 44275, 44276, -1, 44262, 44263, 44275, -1, 44260, 44276, 44277, -1, 44260, 44262, 44276, -1, 44258, 44277, 44278, -1, 44258, 44260, 44277, -1, 44259, 44278, 44279, -1, 44259, 44258, 44278, -1, 44256, 44279, 44280, -1, 44256, 44259, 44279, -1, 44254, 44280, 44281, -1, 44254, 44256, 44280, -1, 44252, 44254, 44281, -1, 44252, 44281, 44073, -1, 44075, 44252, 44073, -1, 44189, 44249, 44186, -1, 44186, 44282, 44184, -1, 44249, 44282, 44186, -1, 44184, 44283, 44185, -1, 44282, 44283, 44184, -1, 44185, 44284, 44188, -1, 44283, 44284, 44185, -1, 44188, 44285, 44195, -1, 44284, 44285, 44188, -1, 44195, 44286, 44196, -1, 44285, 44286, 44195, -1, 44196, 44287, 44197, -1, 44286, 44287, 44196, -1, 44197, 44288, 44200, -1, 44287, 44288, 44197, -1, 44200, 44289, 44178, -1, 44288, 44289, 44200, -1, 44178, 44290, 44179, -1, 44289, 44290, 44178, -1, 44179, 44291, 44180, -1, 44290, 44291, 44179, -1, 44180, 44292, 44193, -1, 44291, 44292, 44180, -1, 44193, 44293, 44192, -1, 44292, 44293, 44193, -1, 44192, 44294, 44191, -1, 44293, 44294, 44192, -1, 44191, 44295, 44198, -1, 44294, 44295, 44191, -1, 44295, 44234, 44198, -1, 44296, 44297, 44237, -1, 44236, 44296, 44237, -1, 44298, 44246, 44245, -1, 44287, 44286, 44299, -1, 44300, 44298, 44245, -1, 44301, 44287, 44299, -1, 44244, 44300, 44245, -1, 44302, 44296, 44236, -1, 44303, 44247, 44246, -1, 44303, 44246, 44298, -1, 44235, 44302, 44236, -1, 44288, 44287, 44301, -1, 44304, 44300, 44244, -1, 44243, 44304, 44244, -1, 44305, 44302, 44235, -1, 44306, 44248, 44247, -1, 44307, 44288, 44301, -1, 44306, 44247, 44303, -1, 44234, 44305, 44235, -1, 44289, 44288, 44307, -1, 44308, 44304, 44243, -1, 44309, 44289, 44307, -1, 44242, 44308, 44243, -1, 44295, 44310, 44305, -1, 44295, 44305, 44234, -1, 44290, 44289, 44309, -1, 44311, 44249, 44248, -1, 44311, 44248, 44306, -1, 44312, 44308, 44242, -1, 44313, 44290, 44309, -1, 44241, 44312, 44242, -1, 44294, 44314, 44310, -1, 44282, 44249, 44311, -1, 44294, 44310, 44295, -1, 44291, 44290, 44313, -1, 44315, 44282, 44311, -1, 44316, 44312, 44241, -1, 44240, 44316, 44241, -1, 44317, 44291, 44313, -1, 44293, 44318, 44314, -1, 44293, 44314, 44294, -1, 44292, 44317, 44318, -1, 44283, 44282, 44315, -1, 44292, 44318, 44293, -1, 44292, 44291, 44317, -1, 44319, 44283, 44315, -1, 44320, 44316, 44240, -1, 44239, 44320, 44240, -1, 44284, 44283, 44319, -1, 44321, 44284, 44319, -1, 44322, 44320, 44239, -1, 44238, 44322, 44239, -1, 44285, 44284, 44321, -1, 44323, 44285, 44321, -1, 44297, 44322, 44238, -1, 44237, 44297, 44238, -1, 44286, 44285, 44323, -1, 44299, 44286, 44323, -1, 44315, 44324, 44325, -1, 44315, 44311, 44324, -1, 44319, 44325, 44326, -1, 44319, 44315, 44325, -1, 44321, 44326, 44327, -1, 44321, 44319, 44326, -1, 44323, 44327, 44328, -1, 44323, 44321, 44327, -1, 44299, 44328, 44329, -1, 44299, 44323, 44328, -1, 44301, 44329, 44330, -1, 44301, 44299, 44329, -1, 44307, 44330, 44331, -1, 44307, 44301, 44330, -1, 44309, 44331, 44332, -1, 44309, 44307, 44331, -1, 44313, 44332, 44333, -1, 44313, 44309, 44332, -1, 44317, 44333, 44334, -1, 44317, 44313, 44333, -1, 44318, 44334, 44335, -1, 44318, 44317, 44334, -1, 44314, 44335, 44336, -1, 44314, 44318, 44335, -1, 44310, 44336, 44337, -1, 44310, 44314, 44336, -1, 44305, 44337, 44338, -1, 44305, 44310, 44337, -1, 44339, 44340, 44341, -1, 44342, 44343, 44344, -1, 44345, 44346, 44347, -1, 44348, 44342, 44344, -1, 44345, 44347, 44349, -1, 44348, 44350, 44351, -1, 44348, 44344, 44350, -1, 44325, 44324, 44352, -1, 44353, 44354, 44346, -1, 44353, 44355, 44354, -1, 44356, 44339, 44341, -1, 44357, 44351, 44358, -1, 44357, 44348, 44351, -1, 44359, 44360, 44361, -1, 44353, 44346, 44345, -1, 44362, 44325, 44352, -1, 44363, 44361, 44360, -1, 44362, 44352, 44364, -1, 44362, 44364, 44365, -1, 44366, 44341, 44360, -1, 44367, 44368, 44369, -1, 44370, 44357, 44358, -1, 44367, 44369, 44371, -1, 44366, 44360, 44359, -1, 44372, 44363, 44360, -1, 44370, 44358, 44373, -1, 44374, 44372, 44360, -1, 44330, 44375, 44376, -1, 44377, 44355, 44353, -1, 44378, 44341, 44366, -1, 44379, 44330, 44376, -1, 44380, 44381, 44355, -1, 44382, 44371, 44383, -1, 44380, 44384, 44381, -1, 44382, 44367, 44371, -1, 44385, 44330, 44379, -1, 44386, 44374, 44360, -1, 44387, 44325, 44362, -1, 44388, 44386, 44360, -1, 44326, 44325, 44387, -1, 44380, 44355, 44377, -1, 44389, 44390, 44391, -1, 44392, 44388, 44360, -1, 44393, 44394, 44395, -1, 44337, 44396, 44397, -1, 44337, 44398, 44396, -1, 44337, 44399, 44398, -1, 44400, 44401, 44402, -1, 44337, 44403, 44399, -1, 44404, 44390, 44389, -1, 44400, 44402, 44405, -1, 44337, 44406, 44403, -1, 44407, 44392, 44360, -1, 44337, 44408, 44406, -1, 44337, 44409, 44338, -1, 44410, 44411, 44384, -1, 44337, 44412, 44408, -1, 44337, 44413, 44412, -1, 44414, 44389, 44391, -1, 44415, 44407, 44360, -1, 44337, 44397, 44409, -1, 44414, 44416, 44417, -1, 44410, 44384, 44380, -1, 44414, 44391, 44416, -1, 44418, 44415, 44360, -1, 44419, 44420, 44367, -1, 44419, 44367, 44382, -1, 44421, 44422, 44390, -1, 44421, 44423, 44422, -1, 44332, 44424, 44425, -1, 44421, 44390, 44404, -1, 44426, 44418, 44360, -1, 44332, 44331, 44424, -1, 44427, 44414, 44417, -1, 44336, 44428, 44413, -1, 44336, 44429, 44428, -1, 44430, 44411, 44410, -1, 44336, 44431, 44429, -1, 44336, 44432, 44431, -1, 44433, 44400, 44405, -1, 44336, 44434, 44432, -1, 44336, 44435, 44434, -1, 44336, 44436, 44435, -1, 44437, 44426, 44360, -1, 44433, 44405, 44438, -1, 44336, 44439, 44436, -1, 44440, 44441, 44411, -1, 44440, 44442, 44441, -1, 44336, 44413, 44337, -1, 44443, 44437, 44360, -1, 44444, 44326, 44387, -1, 44333, 44425, 44445, -1, 44440, 44411, 44430, -1, 44333, 44332, 44425, -1, 44446, 44417, 44447, -1, 44446, 44427, 44417, -1, 44448, 44443, 44360, -1, 44449, 44450, 44423, -1, 44451, 44393, 44395, -1, 44449, 44423, 44421, -1, 44334, 44445, 44452, -1, 44453, 44356, 44341, -1, 44334, 44333, 44445, -1, 44449, 44454, 44450, -1, 44334, 44452, 44335, -1, 44455, 44456, 44457, -1, 44455, 44458, 44456, -1, 44455, 44459, 44458, -1, 44460, 44330, 44385, -1, 44461, 44448, 44360, -1, 44455, 44462, 44459, -1, 44455, 44463, 44462, -1, 44455, 44464, 44463, -1, 44455, 44465, 44464, -1, 44455, 44466, 44465, -1, 44455, 44467, 44466, -1, 44455, 44468, 44467, -1, 44469, 44442, 44440, -1, 44455, 44470, 44468, -1, 44455, 44471, 44470, -1, 44469, 44472, 44442, -1, 44455, 44473, 44471, -1, 44474, 44461, 44360, -1, 44455, 44475, 44473, -1, 44476, 44446, 44447, -1, 44455, 44477, 44475, -1, 44476, 44478, 44479, -1, 44455, 44480, 44477, -1, 44476, 44447, 44478, -1, 44455, 44457, 44328, -1, 44455, 44481, 44480, -1, 44455, 44482, 44481, -1, 44483, 44476, 44479, -1, 44455, 44484, 44482, -1, 44455, 44485, 44484, -1, 44455, 44444, 44485, -1, 44455, 44326, 44444, -1, 44455, 44328, 44327, -1, 44486, 44474, 44360, -1, 44455, 44327, 44326, -1, 44487, 44488, 44489, -1, 44487, 44490, 44488, -1, 44487, 44491, 44492, -1, 44487, 44493, 44491, -1, 44487, 44494, 44493, -1, 44487, 44495, 44494, -1, 44496, 44453, 44341, -1, 44487, 44328, 44490, -1, 44487, 44497, 44495, -1, 44496, 44341, 44378, -1, 44487, 44498, 44497, -1, 44487, 44499, 44498, -1, 44487, 44500, 44499, -1, 44487, 44501, 44500, -1, 44487, 44502, 44501, -1, 44503, 44486, 44360, -1, 44487, 44504, 44502, -1, 44505, 44479, 44506, -1, 44507, 44472, 44469, -1, 44487, 44508, 44509, -1, 44487, 44510, 44511, -1, 44487, 44512, 44513, -1, 44487, 44514, 44512, -1, 44487, 44515, 44514, -1, 44505, 44483, 44479, -1, 44487, 44516, 44515, -1, 44487, 44517, 44516, -1, 44487, 44518, 44519, -1, 44487, 44520, 44517, -1, 44521, 44503, 44360, -1, 44487, 44522, 44520, -1, 44523, 44330, 44460, -1, 44487, 44509, 44522, -1, 44487, 44524, 44525, -1, 44487, 44526, 44524, -1, 44487, 44527, 44526, -1, 44487, 44492, 44527, -1, 44528, 44330, 44523, -1, 44487, 44529, 44504, -1, 44530, 44521, 44360, -1, 44531, 44532, 44472, -1, 44487, 44533, 44529, -1, 44487, 44534, 44533, -1, 44487, 44535, 44534, -1, 44487, 44536, 44535, -1, 44487, 44537, 44536, -1, 44487, 44538, 44375, -1, 44539, 44540, 44541, -1, 44487, 44542, 44537, -1, 44539, 44506, 44540, -1, 44487, 44543, 44538, -1, 44544, 44530, 44360, -1, 44487, 44545, 44542, -1, 44487, 44546, 44543, -1, 44487, 44547, 44545, -1, 44539, 44505, 44506, -1, 44487, 44548, 44546, -1, 44487, 44549, 44547, -1, 44531, 44472, 44507, -1, 44487, 44519, 44548, -1, 44487, 44550, 44549, -1, 44551, 44539, 44541, -1, 44552, 44544, 44360, -1, 44487, 44553, 44550, -1, 44487, 44375, 44330, -1, 44554, 44555, 44532, -1, 44487, 44511, 44553, -1, 44554, 44504, 44555, -1, 44487, 44556, 44518, -1, 44487, 44557, 44556, -1, 44551, 44541, 44558, -1, 44487, 44559, 44557, -1, 44560, 44552, 44360, -1, 44487, 44561, 44559, -1, 44487, 44562, 44561, -1, 44487, 44513, 44562, -1, 44487, 44563, 44508, -1, 44487, 44564, 44563, -1, 44487, 44565, 44564, -1, 44487, 44566, 44565, -1, 44567, 44560, 44360, -1, 44554, 44532, 44531, -1, 44487, 44568, 44566, -1, 44487, 44330, 44329, -1, 44487, 44569, 44568, -1, 44487, 44329, 44328, -1, 44487, 44570, 44569, -1, 44571, 44551, 44558, -1, 44487, 44525, 44570, -1, 44572, 44451, 44395, -1, 44487, 44489, 44510, -1, 44573, 44452, 44574, -1, 44572, 44575, 44451, -1, 44573, 44576, 44439, -1, 44577, 44578, 44567, -1, 44572, 44579, 44575, -1, 44573, 44580, 44576, -1, 44577, 44558, 44578, -1, 44572, 44581, 44579, -1, 44573, 44582, 44580, -1, 44573, 44583, 44582, -1, 44577, 44567, 44409, -1, 44584, 44581, 44572, -1, 44573, 44585, 44583, -1, 44573, 44574, 44585, -1, 44573, 44439, 44336, -1, 44573, 44336, 44335, -1, 44573, 44335, 44452, -1, 44577, 44571, 44558, -1, 44586, 44584, 44572, -1, 44587, 44330, 44528, -1, 44588, 44330, 44587, -1, 44589, 44330, 44588, -1, 44502, 44504, 44554, -1, 44590, 44577, 44409, -1, 44591, 44586, 44572, -1, 44592, 44590, 44409, -1, 44593, 44592, 44409, -1, 44594, 44330, 44589, -1, 44595, 44593, 44409, -1, 44596, 44330, 44594, -1, 44597, 44595, 44409, -1, 44598, 44330, 44596, -1, 44599, 44597, 44409, -1, 44600, 44601, 44602, -1, 44600, 44602, 44603, -1, 44604, 44599, 44409, -1, 44605, 44606, 44607, -1, 44608, 44606, 44605, -1, 44608, 44508, 44606, -1, 44609, 44604, 44409, -1, 44509, 44508, 44608, -1, 44395, 44610, 44611, -1, 44612, 44609, 44409, -1, 44613, 44614, 44400, -1, 44613, 44400, 44433, -1, 44615, 44616, 44617, -1, 44615, 44607, 44616, -1, 44618, 44612, 44409, -1, 44619, 44600, 44603, -1, 44615, 44605, 44607, -1, 44619, 44454, 44449, -1, 44394, 44610, 44395, -1, 44619, 44603, 44454, -1, 44620, 44621, 44420, -1, 44328, 44622, 44490, -1, 44328, 44623, 44622, -1, 44620, 44420, 44419, -1, 44328, 44457, 44623, -1, 44624, 44617, 44625, -1, 44624, 44615, 44617, -1, 44626, 44618, 44409, -1, 44627, 44621, 44620, -1, 44627, 44628, 44621, -1, 44629, 44624, 44625, -1, 44630, 44626, 44409, -1, 44629, 44625, 44631, -1, 44632, 44633, 44634, -1, 44635, 44629, 44631, -1, 44636, 44630, 44409, -1, 44637, 44628, 44627, -1, 44635, 44631, 44638, -1, 44639, 44628, 44637, -1, 44640, 44633, 44632, -1, 44640, 44641, 44633, -1, 44639, 44642, 44628, -1, 44639, 44643, 44642, -1, 44644, 44636, 44409, -1, 44645, 44635, 44638, -1, 44646, 44641, 44640, -1, 44645, 44638, 44647, -1, 44648, 44643, 44639, -1, 44646, 44649, 44641, -1, 44648, 44650, 44643, -1, 44651, 44634, 44652, -1, 44651, 44632, 44634, -1, 44653, 44650, 44648, -1, 44654, 44651, 44652, -1, 44655, 44645, 44647, -1, 44654, 44652, 44591, -1, 44655, 44647, 44656, -1, 44657, 44649, 44646, -1, 44658, 44655, 44656, -1, 44659, 44650, 44653, -1, 44657, 44660, 44649, -1, 44658, 44656, 44661, -1, 44659, 44662, 44650, -1, 44663, 44658, 44661, -1, 44659, 44664, 44662, -1, 44665, 44654, 44591, -1, 44665, 44591, 44572, -1, 44663, 44661, 44666, -1, 44667, 44660, 44657, -1, 44668, 44664, 44659, -1, 44667, 44669, 44660, -1, 44668, 44670, 44664, -1, 44671, 44665, 44572, -1, 44672, 44663, 44666, -1, 44673, 44670, 44668, -1, 44674, 44669, 44667, -1, 44675, 44370, 44373, -1, 44674, 44676, 44669, -1, 44677, 44671, 44572, -1, 44678, 44670, 44673, -1, 44678, 44679, 44670, -1, 44680, 44675, 44373, -1, 44678, 44681, 44679, -1, 44680, 44373, 44682, -1, 44683, 44676, 44674, -1, 44683, 44684, 44676, -1, 44685, 44572, 44341, -1, 44331, 44686, 44424, -1, 44331, 44330, 44598, -1, 44331, 44687, 44686, -1, 44331, 44688, 44687, -1, 44331, 44689, 44688, -1, 44685, 44677, 44572, -1, 44331, 44690, 44689, -1, 44331, 44691, 44690, -1, 44527, 44492, 44684, -1, 44331, 44692, 44691, -1, 44693, 44681, 44678, -1, 44331, 44694, 44692, -1, 44331, 44598, 44694, -1, 44693, 44695, 44681, -1, 44696, 44697, 44698, -1, 44527, 44684, 44683, -1, 44699, 44695, 44693, -1, 44700, 44697, 44696, -1, 44701, 44695, 44699, -1, 44702, 44703, 44704, -1, 44702, 44698, 44703, -1, 44705, 44685, 44341, -1, 44701, 44706, 44695, -1, 44702, 44696, 44698, -1, 44707, 44697, 44700, -1, 44707, 44708, 44697, -1, 44707, 44709, 44708, -1, 44710, 44705, 44341, -1, 44711, 44706, 44701, -1, 44711, 44712, 44706, -1, 44711, 44713, 44712, -1, 44714, 44710, 44341, -1, 44715, 44702, 44704, -1, 44716, 44704, 44717, -1, 44716, 44715, 44704, -1, 44718, 44713, 44711, -1, 44719, 44720, 44709, -1, 44719, 44709, 44707, -1, 44719, 44721, 44720, -1, 44340, 44714, 44341, -1, 44722, 44723, 44724, -1, 44722, 44717, 44723, -1, 44511, 44713, 44718, -1, 44511, 44510, 44713, -1, 44722, 44716, 44717, -1, 44725, 44722, 44724, -1, 44726, 44725, 44724, -1, 44726, 44724, 44727, -1, 44728, 44672, 44666, -1, 44729, 44726, 44727, -1, 44728, 44666, 44730, -1, 44729, 44731, 44732, -1, 44729, 44727, 44731, -1, 44733, 44729, 44732, -1, 44734, 44732, 44735, -1, 44409, 44567, 44360, -1, 44734, 44733, 44732, -1, 44736, 44735, 44644, -1, 44736, 44734, 44735, -1, 44736, 44644, 44409, -1, 44601, 44728, 44730, -1, 44601, 44730, 44602, -1, 44737, 44736, 44409, -1, 44738, 44737, 44409, -1, 44739, 44738, 44409, -1, 44740, 44741, 44742, -1, 44743, 44739, 44409, -1, 44744, 44745, 44741, -1, 44746, 44743, 44409, -1, 44744, 44741, 44740, -1, 44397, 44746, 44409, -1, 44747, 44745, 44744, -1, 44748, 44749, 44750, -1, 44748, 44742, 44749, -1, 44748, 44740, 44742, -1, 44751, 44745, 44747, -1, 44751, 44752, 44745, -1, 44751, 44518, 44752, -1, 44753, 44682, 44754, -1, 44753, 44680, 44682, -1, 44755, 44750, 44756, -1, 44755, 44748, 44750, -1, 44519, 44518, 44751, -1, 44757, 44614, 44613, -1, 44757, 44758, 44614, -1, 44759, 44755, 44756, -1, 44760, 44347, 44758, -1, 44759, 44756, 44761, -1, 44762, 44721, 44719, -1, 44762, 44753, 44754, -1, 44762, 44754, 44721, -1, 44760, 44758, 44757, -1, 44763, 44759, 44761, -1, 44763, 44761, 44343, -1, 44342, 44763, 44343, -1, 44349, 44347, 44760, -1, 44365, 44764, 44362, -1, 44362, 44765, 44387, -1, 44764, 44765, 44362, -1, 44387, 44766, 44444, -1, 44765, 44766, 44387, -1, 44766, 44767, 44444, -1, 44768, 44769, 44383, -1, 44383, 44769, 44382, -1, 44382, 44770, 44419, -1, 44769, 44770, 44382, -1, 44419, 44771, 44620, -1, 44770, 44771, 44419, -1, 44513, 44772, 44562, -1, 44561, 44773, 44559, -1, 44562, 44773, 44561, -1, 44772, 44773, 44562, -1, 44556, 44774, 44518, -1, 44557, 44774, 44556, -1, 44559, 44774, 44557, -1, 44773, 44774, 44559, -1, 44745, 44775, 44741, -1, 44752, 44775, 44745, -1, 44518, 44775, 44752, -1, 44774, 44775, 44518, -1, 44749, 44776, 44750, -1, 44742, 44776, 44749, -1, 44741, 44776, 44742, -1, 44775, 44776, 44741, -1, 44761, 44777, 44343, -1, 44756, 44777, 44761, -1, 44750, 44777, 44756, -1, 44776, 44777, 44750, -1, 44350, 44778, 44351, -1, 44344, 44778, 44350, -1, 44343, 44778, 44344, -1, 44777, 44778, 44343, -1, 44351, 44779, 44358, -1, 44778, 44779, 44351, -1, 44376, 44780, 44379, -1, 44385, 44781, 44460, -1, 44379, 44781, 44385, -1, 44780, 44781, 44379, -1, 44528, 44782, 44587, -1, 44523, 44782, 44528, -1, 44460, 44782, 44523, -1, 44781, 44782, 44460, -1, 44589, 44783, 44594, -1, 44588, 44783, 44589, -1, 44587, 44783, 44588, -1, 44782, 44783, 44587, -1, 44598, 44784, 44694, -1, 44596, 44784, 44598, -1, 44594, 44784, 44596, -1, 44783, 44784, 44594, -1, 44691, 44785, 44690, -1, 44692, 44785, 44691, -1, 44694, 44785, 44692, -1, 44784, 44785, 44694, -1, 44688, 44786, 44687, -1, 44689, 44786, 44688, -1, 44690, 44786, 44689, -1, 44785, 44786, 44690, -1, 44687, 44787, 44686, -1, 44786, 44787, 44687, -1, 44525, 44788, 44570, -1, 44569, 44789, 44568, -1, 44570, 44789, 44569, -1, 44788, 44789, 44570, -1, 44565, 44790, 44564, -1, 44566, 44790, 44565, -1, 44568, 44790, 44566, -1, 44789, 44790, 44568, -1, 44508, 44791, 44606, -1, 44563, 44791, 44508, -1, 44564, 44791, 44563, -1, 44790, 44791, 44564, -1, 44616, 44792, 44617, -1, 44607, 44792, 44616, -1, 44606, 44792, 44607, -1, 44791, 44792, 44606, -1, 44631, 44793, 44638, -1, 44625, 44793, 44631, -1, 44617, 44793, 44625, -1, 44792, 44793, 44617, -1, 44656, 44794, 44661, -1, 44647, 44794, 44656, -1, 44638, 44794, 44647, -1, 44793, 44794, 44638, -1, 44661, 44795, 44666, -1, 44794, 44795, 44661, -1, 44438, 44796, 44433, -1, 44433, 44797, 44613, -1, 44796, 44797, 44433, -1, 44613, 44798, 44757, -1, 44797, 44798, 44613, -1, 44798, 44799, 44757, -1, 44800, 44801, 44802, -1, 44800, 44803, 44801, -1, 44804, 44805, 44806, -1, 44804, 44806, 44807, -1, 44800, 44802, 44808, -1, 44809, 44810, 44811, -1, 44809, 44812, 44810, -1, 44813, 44814, 44815, -1, 44816, 44817, 44818, -1, 44819, 44341, 44820, -1, 44816, 44818, 44821, -1, 44822, 44341, 44819, -1, 44823, 44824, 44803, -1, 44825, 44816, 44821, -1, 44823, 44803, 44800, -1, 44825, 44821, 44826, -1, 44827, 44824, 44823, -1, 44828, 44829, 44830, -1, 44831, 44832, 44824, -1, 44828, 44830, 44833, -1, 44831, 44824, 44827, -1, 44834, 44825, 44826, -1, 44835, 44836, 44832, -1, 44835, 44837, 44836, -1, 44834, 44826, 44838, -1, 44835, 44832, 44831, -1, 44839, 44837, 44835, -1, 44840, 44834, 44838, -1, 44840, 44838, 44841, -1, 44842, 44843, 44844, -1, 44845, 44843, 44842, -1, 44846, 44847, 44848, -1, 44849, 44840, 44841, -1, 44850, 44846, 44848, -1, 44851, 44852, 44853, -1, 44849, 44841, 44854, -1, 44851, 44844, 44852, -1, 44855, 44850, 44848, -1, 44851, 44842, 44844, -1, 44856, 44857, 44843, -1, 44856, 44858, 44857, -1, 44856, 44843, 44845, -1, 44859, 44813, 44815, -1, 44369, 44368, 44829, -1, 44860, 44829, 44828, -1, 44861, 44849, 44854, -1, 44371, 44369, 44829, -1, 44371, 44829, 44860, -1, 44862, 44851, 44853, -1, 44861, 44854, 44863, -1, 44864, 44865, 44866, -1, 44864, 44866, 44867, -1, 44360, 44868, 44869, -1, 44870, 44871, 44872, -1, 44360, 44873, 44868, -1, 44360, 44874, 44873, -1, 44360, 44875, 44874, -1, 44360, 44876, 44875, -1, 44360, 44877, 44876, -1, 44360, 44878, 44877, -1, 44879, 44853, 44880, -1, 44360, 44881, 44878, -1, 44360, 44882, 44881, -1, 44360, 44883, 44882, -1, 44360, 44884, 44883, -1, 44360, 44885, 44884, -1, 44360, 44886, 44885, -1, 44360, 44887, 44886, -1, 44360, 44888, 44887, -1, 44360, 44889, 44888, -1, 44360, 44341, 44822, -1, 44360, 44890, 44889, -1, 44360, 44891, 44890, -1, 44360, 44892, 44891, -1, 44360, 44893, 44892, -1, 44879, 44862, 44853, -1, 44360, 44894, 44893, -1, 44360, 44895, 44894, -1, 44896, 44897, 44858, -1, 44360, 44898, 44895, -1, 44896, 44858, 44856, -1, 44360, 44899, 44898, -1, 44360, 44900, 44899, -1, 44896, 44901, 44897, -1, 44360, 44822, 44900, -1, 44902, 44903, 44904, -1, 44902, 44880, 44903, -1, 44905, 44906, 44871, -1, 44907, 44908, 44909, -1, 44902, 44879, 44880, -1, 44907, 44910, 44908, -1, 44907, 44911, 44910, -1, 44907, 44912, 44911, -1, 44913, 44861, 44863, -1, 44907, 44914, 44912, -1, 44907, 44915, 44914, -1, 44907, 44916, 44915, -1, 44907, 44917, 44916, -1, 44907, 44918, 44917, -1, 44913, 44863, 44919, -1, 44920, 44913, 44919, -1, 44905, 44871, 44870, -1, 44921, 44902, 44904, -1, 44409, 44869, 44922, -1, 44409, 44923, 44837, -1, 44409, 44924, 44923, -1, 44920, 44919, 44925, -1, 44409, 44926, 44924, -1, 44927, 44928, 44929, -1, 44409, 44930, 44926, -1, 44409, 44931, 44930, -1, 44409, 44932, 44931, -1, 44933, 44920, 44925, -1, 44409, 44934, 44932, -1, 44927, 44929, 44935, -1, 44409, 44936, 44934, -1, 44409, 44937, 44936, -1, 44409, 44938, 44937, -1, 44409, 44939, 44938, -1, 44409, 44940, 44939, -1, 44409, 44941, 44940, -1, 44933, 44925, 44942, -1, 44409, 44943, 44944, -1, 44409, 44945, 44943, -1, 44409, 44946, 44945, -1, 44409, 44947, 44946, -1, 44409, 44948, 44947, -1, 44949, 44805, 44804, -1, 44409, 44839, 44948, -1, 44949, 44950, 44805, -1, 44409, 44837, 44839, -1, 44409, 44922, 44941, -1, 44409, 44360, 44869, -1, 44352, 44324, 44928, -1, 44951, 44952, 44918, -1, 44951, 44953, 44952, -1, 44954, 44904, 44955, -1, 44956, 44906, 44905, -1, 44951, 44957, 44953, -1, 44951, 44958, 44957, -1, 44951, 44959, 44958, -1, 44960, 44928, 44927, -1, 44951, 44961, 44959, -1, 44951, 44962, 44961, -1, 44954, 44921, 44904, -1, 44960, 44352, 44928, -1, 44951, 44944, 44962, -1, 44963, 44872, 44964, -1, 44951, 44409, 44944, -1, 44951, 44918, 44907, -1, 44963, 44870, 44872, -1, 44338, 44409, 44951, -1, 44965, 44929, 44966, -1, 44965, 44966, 44848, -1, 44967, 44950, 44949, -1, 44364, 44352, 44960, -1, 44965, 44968, 44935, -1, 44969, 44933, 44942, -1, 44965, 44970, 44968, -1, 44965, 44971, 44970, -1, 44965, 44972, 44971, -1, 44967, 44973, 44950, -1, 44965, 44974, 44972, -1, 44965, 44975, 44974, -1, 44963, 44964, 44976, -1, 44965, 44977, 44975, -1, 44965, 44978, 44977, -1, 44965, 44979, 44978, -1, 44965, 44980, 44979, -1, 44981, 44982, 44906, -1, 44965, 44983, 44980, -1, 44984, 44985, 44986, -1, 44965, 44987, 44983, -1, 44969, 44942, 44988, -1, 44984, 44955, 44985, -1, 44981, 44989, 44982, -1, 44965, 44990, 44987, -1, 44965, 44991, 44990, -1, 44965, 44992, 44991, -1, 44965, 44993, 44992, -1, 44965, 44994, 44993, -1, 44965, 44995, 44994, -1, 44965, 44996, 44995, -1, 44965, 44847, 44996, -1, 44965, 44935, 44929, -1, 44997, 44998, 44999, -1, 44965, 44848, 44847, -1, 45000, 45001, 45002, -1, 45000, 45003, 45001, -1, 45000, 45004, 45003, -1, 45005, 44973, 44967, -1, 45000, 45006, 44989, -1, 45000, 45007, 45006, -1, 45000, 45008, 45007, -1, 44984, 44954, 44955, -1, 45000, 44848, 45009, -1, 45000, 45010, 45008, -1, 45011, 44998, 44997, -1, 45000, 45009, 45012, -1, 45000, 45013, 45010, -1, 45000, 45014, 45015, -1, 45000, 45012, 45013, -1, 45016, 44997, 44999, -1, 45000, 44989, 45017, -1, 44981, 44906, 44956, -1, 45000, 45018, 45019, -1, 45000, 45020, 45018, -1, 45000, 45021, 45020, -1, 45000, 45022, 45021, -1, 45000, 45023, 45022, -1, 45000, 45024, 45023, -1, 45000, 45025, 45024, -1, 45000, 45026, 45025, -1, 45027, 44963, 44976, -1, 45000, 45028, 45026, -1, 44438, 44405, 45029, -1, 45000, 45030, 44855, -1, 45000, 45015, 45028, -1, 45031, 44867, 45032, -1, 45000, 45033, 45030, -1, 45031, 44864, 44867, -1, 45000, 45034, 45035, -1, 45036, 44973, 45005, -1, 45000, 45037, 45033, -1, 45000, 45038, 45034, -1, 45016, 45039, 45040, -1, 45000, 45041, 45038, -1, 45042, 44984, 44986, -1, 45016, 44999, 45039, -1, 45000, 45043, 45041, -1, 45027, 44976, 45044, -1, 45000, 45045, 45043, -1, 45000, 45046, 45045, -1, 45036, 45047, 44973, -1, 45000, 45048, 45046, -1, 45036, 45049, 45047, -1, 45000, 45050, 45048, -1, 45000, 45051, 45052, -1, 45000, 45053, 45051, -1, 45000, 45054, 45053, -1, 45055, 44998, 45011, -1, 45000, 45056, 45054, -1, 45055, 45057, 44998, -1, 45000, 45058, 45056, -1, 45055, 45059, 45057, -1, 45000, 45017, 45058, -1, 45000, 45019, 45004, -1, 45000, 45060, 45037, -1, 45000, 44855, 44848, -1, 45000, 45061, 45014, -1, 45000, 45062, 45050, -1, 45000, 45035, 45061, -1, 45000, 45063, 45060, -1, 45064, 44986, 45065, -1, 45000, 45066, 45063, -1, 45000, 45067, 45062, -1, 45064, 45042, 44986, -1, 45000, 45068, 45066, -1, 45069, 45016, 45040, -1, 45000, 45070, 45067, -1, 45000, 45071, 45068, -1, 45072, 45049, 45036, -1, 45000, 45073, 45070, -1, 45017, 44989, 44981, -1, 45000, 45074, 45071, -1, 45000, 45075, 45073, -1, 45000, 45076, 45075, -1, 45072, 45077, 45049, -1, 45000, 45078, 45074, -1, 45000, 45079, 45076, -1, 45000, 45080, 45078, -1, 45000, 45081, 45079, -1, 45000, 45082, 45080, -1, 45000, 45083, 45082, -1, 45000, 45052, 45081, -1, 45000, 45002, 45083, -1, 45084, 44859, 44907, -1, 45085, 45027, 45044, -1, 45084, 45086, 45087, -1, 45084, 45088, 45086, -1, 45084, 45089, 45088, -1, 45084, 44909, 45089, -1, 45084, 45087, 44813, -1, 45084, 44813, 44859, -1, 45084, 44907, 44909, -1, 45090, 45077, 45072, -1, 45019, 45065, 45004, -1, 45085, 45044, 45091, -1, 45019, 45064, 45065, -1, 45092, 45040, 45093, -1, 45092, 45069, 45040, -1, 44833, 44830, 45094, -1, 45095, 45015, 45014, -1, 44833, 45059, 45055, -1, 44833, 45094, 45059, -1, 45095, 45096, 45015, -1, 45095, 45097, 45096, -1, 45098, 45077, 45090, -1, 45099, 45100, 45101, -1, 45098, 45102, 45077, -1, 45099, 45093, 45100, -1, 45098, 45103, 45102, -1, 45099, 45092, 45093, -1, 45104, 45085, 45091, -1, 45105, 45099, 45101, -1, 45104, 45091, 45106, -1, 45107, 45097, 45095, -1, 45108, 45103, 45098, -1, 45108, 45109, 45103, -1, 45110, 45101, 45111, -1, 45110, 45105, 45101, -1, 45112, 45097, 45107, -1, 45112, 45113, 45097, -1, 45114, 45110, 45111, -1, 45115, 45109, 45108, -1, 45114, 45116, 45117, -1, 45118, 45119, 45109, -1, 45114, 45111, 45116, -1, 45118, 45120, 45119, -1, 45121, 45104, 45106, -1, 45122, 45123, 45113, -1, 45122, 45124, 45123, -1, 45118, 45109, 45115, -1, 45121, 45106, 45125, -1, 45126, 45114, 45117, -1, 45122, 45113, 45112, -1, 45127, 45117, 45128, -1, 45127, 45126, 45117, -1, 45129, 45130, 45120, -1, 45131, 45124, 45122, -1, 45132, 45133, 45037, -1, 45132, 45128, 45133, -1, 45132, 45127, 45128, -1, 45060, 45132, 45037, -1, 45129, 45120, 45118, -1, 45134, 45124, 45131, -1, 45134, 45135, 45124, -1, 45136, 45130, 45129, -1, 45137, 45138, 45130, -1, 45139, 45121, 45125, -1, 45140, 45141, 45135, -1, 45140, 45142, 45141, -1, 45139, 45125, 45143, -1, 45144, 45012, 45145, -1, 45146, 45139, 45143, -1, 45137, 45130, 45136, -1, 45147, 45012, 45144, -1, 45148, 45149, 45138, -1, 45140, 45135, 45134, -1, 45150, 45012, 44866, -1, 45148, 44922, 45149, -1, 45146, 45143, 45151, -1, 45152, 45142, 45140, -1, 45150, 45145, 45012, -1, 45152, 45153, 45142, -1, 45154, 45146, 45151, -1, 45148, 45138, 45137, -1, 45154, 45151, 45155, -1, 45156, 45012, 45147, -1, 45157, 45150, 44866, -1, 45158, 45012, 45156, -1, 45159, 45157, 44866, -1, 45160, 45153, 45152, -1, 45161, 44922, 45148, -1, 45162, 45012, 45158, -1, 45163, 45164, 45165, -1, 45166, 45159, 44866, -1, 45167, 45154, 45155, -1, 45168, 45169, 45153, -1, 44941, 44922, 45161, -1, 45168, 45153, 45160, -1, 45170, 45012, 45162, -1, 45171, 45166, 44866, -1, 45172, 45012, 45170, -1, 45173, 45012, 45172, -1, 45174, 45171, 44866, -1, 45175, 45174, 44866, -1, 45176, 44901, 44896, -1, 44383, 44371, 44860, -1, 45176, 45177, 44901, -1, 45178, 45012, 45173, -1, 44865, 45175, 44866, -1, 45179, 45012, 45178, -1, 44402, 44401, 45177, -1, 45013, 45012, 45179, -1, 45180, 44812, 44809, -1, 45180, 45181, 44812, -1, 45182, 45183, 45181, -1, 45182, 45181, 45180, -1, 44365, 44364, 44960, -1, 45184, 44969, 44988, -1, 45185, 45164, 45163, -1, 45029, 45177, 45176, -1, 45186, 45183, 45182, -1, 45187, 45188, 45183, -1, 45187, 45189, 45188, -1, 45190, 45184, 44988, -1, 45164, 45155, 45165, -1, 45164, 45167, 45155, -1, 44395, 44611, 45191, -1, 44395, 45191, 45192, -1, 44405, 45177, 45029, -1, 44395, 45192, 45193, -1, 44405, 44402, 45177, -1, 44395, 45193, 45194, -1, 45187, 45183, 45186, -1, 45195, 45196, 45189, -1, 45197, 45184, 45190, -1, 44814, 45031, 45032, -1, 45195, 45189, 45187, -1, 44811, 45185, 45163, -1, 45198, 45196, 45195, -1, 44815, 44814, 45032, -1, 45199, 45200, 45196, -1, 44810, 45185, 44811, -1, 45199, 45201, 45200, -1, 44807, 45197, 45190, -1, 44572, 45202, 45169, -1, 44572, 45203, 45202, -1, 44572, 45204, 45203, -1, 44817, 45205, 44818, -1, 45199, 45196, 45198, -1, 44572, 45206, 45204, -1, 44572, 45207, 45206, -1, 44572, 45208, 45207, -1, 44572, 45194, 45208, -1, 44572, 45209, 45210, -1, 44572, 45211, 45209, -1, 44572, 45168, 45211, -1, 45212, 45205, 44817, -1, 44572, 45169, 45168, -1, 44572, 44395, 45194, -1, 45213, 44802, 45201, -1, 44806, 45197, 44807, -1, 44341, 45214, 45215, -1, 44341, 45216, 45214, -1, 45213, 45201, 45199, -1, 44341, 45217, 45216, -1, 44341, 45210, 45217, -1, 44341, 44572, 45210, -1, 44341, 45215, 45218, -1, 44341, 45218, 45219, -1, 44341, 45219, 45220, -1, 44808, 44802, 45213, -1, 45212, 45062, 45205, -1, 44820, 44341, 45220, -1, 45050, 45062, 45212, -1, 45035, 45221, 45061, -1, 45014, 45222, 45095, -1, 45061, 45222, 45014, -1, 45221, 45222, 45061, -1, 45112, 45223, 45122, -1, 45107, 45223, 45112, -1, 45095, 45223, 45107, -1, 45222, 45223, 45095, -1, 45134, 45224, 45140, -1, 45131, 45224, 45134, -1, 45122, 45224, 45131, -1, 45223, 45224, 45122, -1, 45160, 45225, 45168, -1, 45152, 45225, 45160, -1, 45140, 45225, 45152, -1, 45224, 45225, 45140, -1, 45209, 45226, 45210, -1, 45211, 45226, 45209, -1, 45168, 45226, 45211, -1, 45225, 45226, 45168, -1, 45216, 45227, 45214, -1, 45217, 45227, 45216, -1, 45210, 45227, 45217, -1, 45226, 45227, 45210, -1, 45214, 45228, 45215, -1, 45227, 45228, 45214, -1, 45179, 45229, 45013, -1, 45010, 45230, 45008, -1, 45013, 45230, 45010, -1, 45229, 45230, 45013, -1, 45006, 45231, 44989, -1, 45007, 45231, 45006, -1, 45008, 45231, 45007, -1, 45230, 45231, 45008, -1, 44906, 45232, 44871, -1, 44982, 45232, 44906, -1, 44989, 45232, 44982, -1, 45231, 45232, 44989, -1, 44964, 45233, 44976, -1, 44872, 45233, 44964, -1, 44871, 45233, 44872, -1, 45232, 45233, 44871, -1, 45091, 45234, 45106, -1, 45044, 45234, 45091, -1, 44976, 45234, 45044, -1, 45233, 45234, 44976, -1, 45143, 45235, 45151, -1, 45125, 45235, 45143, -1, 45106, 45235, 45125, -1, 45234, 45235, 45106, -1, 45151, 45236, 45155, -1, 45235, 45236, 45151, -1, 45052, 45237, 45081, -1, 45079, 45238, 45076, -1, 45081, 45238, 45079, -1, 45237, 45238, 45081, -1, 45073, 45239, 45070, -1, 45075, 45239, 45073, -1, 45076, 45239, 45075, -1, 45238, 45239, 45076, -1, 45062, 45240, 45205, -1, 45067, 45240, 45062, -1, 45070, 45240, 45067, -1, 45239, 45240, 45070, -1, 44821, 45241, 44826, -1, 44818, 45241, 44821, -1, 45205, 45241, 44818, -1, 45240, 45241, 45205, -1, 44841, 45242, 44854, -1, 44838, 45242, 44841, -1, 44826, 45242, 44838, -1, 45241, 45242, 44826, -1, 44919, 45243, 44925, -1, 44863, 45243, 44919, -1, 44854, 45243, 44863, -1, 45242, 45243, 44854, -1, 44925, 45244, 44942, -1, 45243, 45244, 44925, -1, 45245, 45094, 44830, -1, 45246, 44830, 44829, -1, 45246, 45245, 44830, -1, 45247, 44829, 44368, -1, 45247, 45246, 44829, -1, 45248, 45247, 44368, -1, 45249, 44897, 44901, -1, 45249, 45250, 44897, -1, 45251, 44901, 45177, -1, 45251, 45249, 44901, -1, 45252, 45177, 44401, -1, 45252, 45251, 45177, -1, 45253, 45193, 45192, -1, 45253, 45254, 45193, -1, 45255, 45192, 45191, -1, 45255, 45253, 45192, -1, 45256, 45191, 44611, -1, 45256, 45255, 45191, -1, 44302, 44305, 44338, -1, 44302, 44338, 44951, -1, 44296, 44951, 44907, -1, 44296, 44302, 44951, -1, 44297, 44907, 44859, -1, 44297, 44296, 44907, -1, 44322, 44859, 44815, -1, 44322, 44297, 44859, -1, 44320, 44815, 45032, -1, 44320, 44322, 44815, -1, 44316, 45032, 44867, -1, 44316, 44320, 45032, -1, 44312, 44867, 44866, -1, 44312, 44316, 44867, -1, 44308, 44866, 45012, -1, 44308, 44312, 44866, -1, 44304, 45012, 45009, -1, 44304, 44308, 45012, -1, 44300, 45009, 44848, -1, 44300, 44304, 45009, -1, 44298, 44848, 44966, -1, 44298, 44300, 44848, -1, 44303, 44966, 44929, -1, 44303, 44298, 44966, -1, 44306, 44929, 44928, -1, 44306, 44303, 44929, -1, 44311, 44928, 44324, -1, 44311, 44306, 44928, -1, 45257, 45258, 44896, -1, 44896, 45258, 45176, -1, 45176, 45259, 45029, -1, 45258, 45259, 45176, -1, 45029, 44796, 44438, -1, 45259, 44796, 45029, -1, 45023, 45260, 45022, -1, 45024, 45260, 45023, -1, 45025, 45260, 45024, -1, 45261, 45260, 45025, -1, 45260, 45262, 45022, -1, 45020, 45262, 45018, -1, 45021, 45262, 45020, -1, 45022, 45262, 45021, -1, 45193, 45254, 45194, -1, 45262, 45263, 45018, -1, 45042, 45263, 44984, -1, 45064, 45263, 45042, -1, 45206, 45264, 45204, -1, 45019, 45263, 45064, -1, 45207, 45264, 45206, -1, 45018, 45263, 45019, -1, 45208, 45264, 45207, -1, 45194, 45264, 45208, -1, 45254, 45264, 45194, -1, 44921, 45265, 44902, -1, 44954, 45265, 44921, -1, 44984, 45265, 44954, -1, 45263, 45265, 44984, -1, 45169, 45266, 45153, -1, 45202, 45266, 45169, -1, 45203, 45266, 45202, -1, 45204, 45266, 45203, -1, 45264, 45266, 45204, -1, 44862, 45267, 44851, -1, 44879, 45267, 44862, -1, 44902, 45267, 44879, -1, 45265, 45267, 44902, -1, 44845, 45268, 44856, -1, 44842, 45268, 44845, -1, 44851, 45268, 44842, -1, 45267, 45268, 44851, -1, 45141, 45269, 45135, -1, 45142, 45269, 45141, -1, 44856, 45257, 44896, -1, 45153, 45269, 45142, -1, 45266, 45269, 45153, -1, 45268, 45257, 44856, -1, 45123, 45270, 45113, -1, 45124, 45270, 45123, -1, 45135, 45270, 45124, -1, 45269, 45270, 45135, -1, 45096, 45271, 45015, -1, 45097, 45271, 45096, -1, 45113, 45271, 45097, -1, 45270, 45271, 45113, -1, 45026, 45261, 45025, -1, 45028, 45261, 45026, -1, 45015, 45261, 45028, -1, 45271, 45261, 45015, -1, 45272, 45256, 44611, -1, 45272, 44611, 44610, -1, 45273, 44610, 44394, -1, 45273, 45272, 44610, -1, 45274, 44394, 44393, -1, 45274, 45273, 44394, -1, 44491, 45275, 44492, -1, 44493, 45275, 44491, -1, 44494, 45275, 44493, -1, 45276, 45275, 44494, -1, 45275, 45277, 44492, -1, 44676, 45277, 44669, -1, 44684, 45277, 44676, -1, 44492, 45277, 44684, -1, 44757, 44799, 44760, -1, 44353, 45278, 44377, -1, 45277, 45279, 44669, -1, 44345, 45278, 44353, -1, 44349, 45278, 44345, -1, 44760, 45278, 44349, -1, 44799, 45278, 44760, -1, 44641, 45279, 44633, -1, 44649, 45279, 44641, -1, 44660, 45279, 44649, -1, 44669, 45279, 44660, -1, 44652, 45280, 44591, -1, 44634, 45280, 44652, -1, 44633, 45280, 44634, -1, 44430, 45281, 44440, -1, 45279, 45280, 44633, -1, 44410, 45281, 44430, -1, 44380, 45281, 44410, -1, 44377, 45281, 44380, -1, 45278, 45281, 44377, -1, 44584, 45282, 44581, -1, 44586, 45282, 44584, -1, 44591, 45282, 44586, -1, 45280, 45282, 44591, -1, 44575, 45283, 44451, -1, 44579, 45283, 44575, -1, 44507, 45284, 44531, -1, 44581, 45283, 44579, -1, 44469, 45284, 44507, -1, 45282, 45283, 44581, -1, 44440, 45284, 44469, -1, 45281, 45284, 44440, -1, 44451, 45274, 44393, -1, 45283, 45274, 44451, -1, 44502, 45285, 44501, -1, 44554, 45285, 44502, -1, 44531, 45285, 44554, -1, 45284, 45285, 44531, -1, 44499, 45286, 44498, -1, 44500, 45286, 44499, -1, 44501, 45286, 44500, -1, 45285, 45286, 44501, -1, 44495, 45276, 44494, -1, 44497, 45276, 44495, -1, 44498, 45276, 44497, -1, 45286, 45276, 44498, -1, 45282, 45274, 45283, -1, 45286, 45285, 45274, -1, 45280, 45274, 45282, -1, 45276, 45286, 45274, -1, 45279, 45274, 45280, -1, 45275, 45276, 45274, -1, 45277, 45274, 45279, -1, 45277, 45275, 45274, -1, 45254, 45258, 45257, -1, 45254, 45257, 45268, -1, 45254, 45268, 45267, -1, 45254, 45267, 45265, -1, 45254, 45265, 45263, -1, 45254, 45263, 45262, -1, 45254, 45262, 45260, -1, 45254, 45260, 45261, -1, 45254, 45261, 45271, -1, 45254, 45271, 45270, -1, 45254, 45270, 45269, -1, 45254, 45269, 45266, -1, 45254, 45266, 45264, -1, 45253, 45258, 45254, -1, 45255, 45259, 45258, -1, 45255, 45258, 45253, -1, 45256, 44796, 45259, -1, 45256, 45259, 45255, -1, 45272, 44797, 44796, -1, 45272, 44796, 45256, -1, 44798, 44797, 45272, -1, 45273, 44798, 45272, -1, 45274, 44799, 44798, -1, 45274, 45281, 45278, -1, 45274, 45278, 44799, -1, 45274, 44798, 45273, -1, 45284, 45281, 45274, -1, 45285, 45284, 45274, -1, 44666, 44795, 44730, -1, 44730, 45287, 44602, -1, 44795, 45287, 44730, -1, 45287, 45288, 44602, -1, 44602, 45289, 44603, -1, 45288, 45289, 44602, -1, 44603, 45290, 44454, -1, 45289, 45290, 44603, -1, 44454, 45291, 44450, -1, 45290, 45291, 44454, -1, 44340, 45292, 44714, -1, 44705, 45293, 44685, -1, 44710, 45293, 44705, -1, 44714, 45293, 44710, -1, 45292, 45293, 44714, -1, 44671, 45294, 44665, -1, 44677, 45294, 44671, -1, 44685, 45294, 44677, -1, 45293, 45294, 44685, -1, 44651, 45295, 44632, -1, 44654, 45295, 44651, -1, 44665, 45295, 44654, -1, 45294, 45295, 44665, -1, 44646, 45296, 44657, -1, 44640, 45296, 44646, -1, 44632, 45296, 44640, -1, 45295, 45296, 44632, -1, 44674, 45297, 44683, -1, 44667, 45297, 44674, -1, 44657, 45297, 44667, -1, 45296, 45297, 44657, -1, 44526, 45298, 44524, -1, 44527, 45298, 44526, -1, 44683, 45298, 44527, -1, 45297, 45298, 44683, -1, 44524, 44788, 44525, -1, 45298, 44788, 44524, -1, 45299, 45292, 44340, -1, 45299, 44340, 44339, -1, 45300, 44339, 44356, -1, 45300, 45299, 44339, -1, 45301, 44356, 44453, -1, 45301, 45300, 44356, -1, 45302, 44453, 44496, -1, 45302, 45301, 44453, -1, 45303, 44496, 44378, -1, 45303, 45302, 44496, -1, 44474, 45304, 44461, -1, 44486, 45304, 44474, -1, 44503, 45304, 44486, -1, 45305, 45304, 44503, -1, 45304, 45306, 44461, -1, 44443, 45306, 44437, -1, 44448, 45306, 44443, -1, 44461, 45306, 44448, -1, 44450, 45291, 44423, -1, 44391, 45307, 44416, -1, 45306, 45308, 44437, -1, 44390, 45307, 44391, -1, 44422, 45307, 44390, -1, 44423, 45307, 44422, -1, 45291, 45307, 44423, -1, 44415, 45308, 44407, -1, 44418, 45308, 44415, -1, 44426, 45308, 44418, -1, 44437, 45308, 44426, -1, 44388, 45309, 44386, -1, 44392, 45309, 44388, -1, 44407, 45309, 44392, -1, 44478, 45310, 44479, -1, 45308, 45309, 44407, -1, 44447, 45310, 44478, -1, 44417, 45310, 44447, -1, 44416, 45310, 44417, -1, 45307, 45310, 44416, -1, 44372, 45311, 44363, -1, 44374, 45311, 44372, -1, 44386, 45311, 44374, -1, 45309, 45311, 44386, -1, 44359, 45312, 44366, -1, 44361, 45312, 44359, -1, 44540, 45313, 44541, -1, 44363, 45312, 44361, -1, 44506, 45313, 44540, -1, 45311, 45312, 44363, -1, 44479, 45313, 44506, -1, 45310, 45313, 44479, -1, 44366, 45303, 44378, -1, 45312, 45303, 44366, -1, 44578, 45314, 44567, -1, 44558, 45314, 44578, -1, 44541, 45314, 44558, -1, 45313, 45314, 44541, -1, 44552, 45315, 44544, -1, 44560, 45315, 44552, -1, 44567, 45315, 44560, -1, 45314, 45315, 44567, -1, 44521, 45305, 44503, -1, 44530, 45305, 44521, -1, 44544, 45305, 44530, -1, 45315, 45305, 44544, -1, 45291, 45304, 45305, -1, 45291, 45305, 45315, -1, 45291, 45315, 45314, -1, 45291, 45314, 45313, -1, 45291, 45313, 45310, -1, 45291, 45310, 45307, -1, 45289, 45300, 45301, -1, 45289, 45288, 45300, -1, 45290, 45303, 45291, -1, 45290, 45289, 45301, -1, 45290, 45302, 45303, -1, 45290, 45301, 45302, -1, 44788, 45298, 45297, -1, 44788, 45297, 45296, -1, 44788, 45296, 45295, -1, 44788, 45295, 45294, -1, 44788, 45294, 45293, -1, 44788, 45293, 45292, -1, 44790, 44789, 44788, -1, 44791, 44790, 44788, -1, 44792, 44791, 44788, -1, 44793, 44792, 44788, -1, 44794, 44788, 45292, -1, 44794, 44793, 44788, -1, 44795, 44794, 45292, -1, 45299, 44795, 45292, -1, 45287, 44795, 45299, -1, 45300, 45287, 45299, -1, 45288, 45287, 45300, -1, 45291, 45303, 45312, -1, 45291, 45312, 45311, -1, 45291, 45311, 45309, -1, 45291, 45309, 45308, -1, 45291, 45308, 45306, -1, 45291, 45306, 45304, -1, 44787, 45316, 44686, -1, 44686, 45316, 44424, -1, 44425, 45317, 44445, -1, 44424, 45317, 44425, -1, 45316, 45317, 44424, -1, 45317, 45318, 44445, -1, 44445, 45319, 44452, -1, 45318, 45319, 44445, -1, 44452, 45320, 44574, -1, 45319, 45320, 44452, -1, 44370, 45321, 44357, -1, 44348, 45322, 44342, -1, 44357, 45322, 44348, -1, 45321, 45322, 44357, -1, 44759, 45323, 44755, -1, 44763, 45323, 44759, -1, 44342, 45323, 44763, -1, 45322, 45323, 44342, -1, 44748, 45324, 44740, -1, 44755, 45324, 44748, -1, 45323, 45324, 44755, -1, 44747, 45325, 44751, -1, 44744, 45325, 44747, -1, 44740, 45325, 44744, -1, 45324, 45325, 44740, -1, 44548, 45326, 44546, -1, 44519, 45326, 44548, -1, 44751, 45326, 44519, -1, 45325, 45326, 44751, -1, 44538, 45327, 44375, -1, 44543, 45327, 44538, -1, 44546, 45327, 44543, -1, 45326, 45327, 44546, -1, 44375, 44780, 44376, -1, 45327, 44780, 44375, -1, 45328, 45321, 44370, -1, 45328, 44370, 44675, -1, 45329, 44675, 44680, -1, 45329, 45328, 44675, -1, 45330, 44680, 44753, -1, 45330, 45329, 44680, -1, 45331, 44753, 44762, -1, 45331, 45330, 44753, -1, 45332, 44762, 44719, -1, 45332, 45331, 44762, -1, 45333, 45334, 44396, -1, 44746, 45334, 44743, -1, 44397, 45334, 44746, -1, 44396, 45334, 44397, -1, 45334, 45335, 44743, -1, 44738, 45335, 44737, -1, 44739, 45335, 44738, -1, 44743, 45335, 44739, -1, 44574, 45320, 44585, -1, 45335, 45336, 44737, -1, 44580, 45337, 44576, -1, 44582, 45337, 44580, -1, 44583, 45337, 44582, -1, 44585, 45337, 44583, -1, 45320, 45337, 44585, -1, 44733, 45336, 44729, -1, 44734, 45336, 44733, -1, 44736, 45336, 44734, -1, 44737, 45336, 44736, -1, 44435, 45338, 44434, -1, 44436, 45338, 44435, -1, 44439, 45338, 44436, -1, 44725, 45339, 44722, -1, 44576, 45338, 44439, -1, 44726, 45339, 44725, -1, 45337, 45338, 44576, -1, 44729, 45339, 44726, -1, 45336, 45339, 44729, -1, 44715, 45340, 44702, -1, 44716, 45340, 44715, -1, 44722, 45340, 44716, -1, 45339, 45340, 44722, -1, 44431, 45341, 44429, -1, 44432, 45341, 44431, -1, 44434, 45341, 44432, -1, 45338, 45341, 44434, -1, 44700, 45342, 44707, -1, 44696, 45342, 44700, -1, 44702, 45342, 44696, -1, 45340, 45342, 44702, -1, 44707, 45332, 44719, -1, 45342, 45332, 44707, -1, 44413, 45343, 44412, -1, 44428, 45343, 44413, -1, 44429, 45343, 44428, -1, 45341, 45343, 44429, -1, 44406, 45344, 44403, -1, 44408, 45344, 44406, -1, 44412, 45344, 44408, -1, 45343, 45344, 44412, -1, 45344, 45333, 44403, -1, 44398, 45333, 44396, -1, 44399, 45333, 44398, -1, 44403, 45333, 44399, -1, 44780, 45327, 45326, -1, 44780, 45326, 45325, -1, 44780, 45325, 45324, -1, 44780, 45324, 45323, -1, 44780, 45323, 45322, -1, 44782, 44781, 44780, -1, 44783, 44782, 44780, -1, 44784, 44783, 44780, -1, 44787, 44786, 44785, -1, 44787, 44785, 44784, -1, 44787, 45322, 45321, -1, 44787, 44780, 45322, -1, 44787, 44784, 44780, -1, 45316, 45321, 45328, -1, 45316, 44787, 45321, -1, 45332, 45342, 45340, -1, 45339, 45332, 45340, -1, 45336, 45332, 45339, -1, 45335, 45332, 45336, -1, 45334, 45332, 45335, -1, 45317, 45328, 45329, -1, 45317, 45316, 45328, -1, 45333, 45332, 45334, -1, 45344, 45332, 45333, -1, 45341, 45344, 45343, -1, 45341, 45332, 45344, -1, 45338, 45332, 45341, -1, 45337, 45332, 45338, -1, 45320, 45332, 45337, -1, 45320, 45331, 45332, -1, 45318, 45329, 45330, -1, 45318, 45317, 45329, -1, 45319, 45331, 45320, -1, 45319, 45318, 45330, -1, 45319, 45330, 45331, -1, 44779, 45345, 44358, -1, 44358, 45345, 44373, -1, 44373, 45346, 44682, -1, 45345, 45346, 44373, -1, 44682, 45347, 44754, -1, 45346, 45347, 44682, -1, 44754, 45348, 44721, -1, 45347, 45348, 44754, -1, 44721, 45349, 44720, -1, 45348, 45349, 44721, -1, 44672, 45350, 44663, -1, 44655, 45351, 44645, -1, 44658, 45351, 44655, -1, 44663, 45351, 44658, -1, 45350, 45351, 44663, -1, 44629, 45352, 44624, -1, 44635, 45352, 44629, -1, 44645, 45352, 44635, -1, 45351, 45352, 44645, -1, 44615, 45353, 44605, -1, 44624, 45353, 44615, -1, 45352, 45353, 44624, -1, 44509, 45354, 44522, -1, 44608, 45354, 44509, -1, 44605, 45354, 44608, -1, 45353, 45354, 44605, -1, 44517, 45355, 44516, -1, 44520, 45355, 44517, -1, 44522, 45355, 44520, -1, 45354, 45355, 44522, -1, 44514, 45356, 44512, -1, 44515, 45356, 44514, -1, 44516, 45356, 44515, -1, 45355, 45356, 44516, -1, 44512, 44772, 44513, -1, 45356, 44772, 44512, -1, 45357, 45350, 44672, -1, 45357, 44672, 44728, -1, 45358, 44728, 44601, -1, 45358, 45357, 44728, -1, 45359, 44601, 44600, -1, 45359, 45358, 44601, -1, 45360, 44600, 44619, -1, 45360, 45359, 44600, -1, 45361, 44619, 44449, -1, 45361, 45360, 44619, -1, 45362, 45363, 44604, -1, 44597, 45363, 44595, -1, 44599, 45363, 44597, -1, 44604, 45363, 44599, -1, 45363, 45364, 44595, -1, 44592, 45364, 44590, -1, 44593, 45364, 44592, -1, 44595, 45364, 44593, -1, 44720, 45349, 44709, -1, 45364, 45365, 44590, -1, 44698, 45366, 44703, -1, 44697, 45366, 44698, -1, 44708, 45366, 44697, -1, 44709, 45366, 44708, -1, 45349, 45366, 44709, -1, 44551, 45365, 44539, -1, 44571, 45365, 44551, -1, 44577, 45365, 44571, -1, 44590, 45365, 44577, -1, 44483, 45367, 44476, -1, 44505, 45367, 44483, -1, 44539, 45367, 44505, -1, 45365, 45367, 44539, -1, 44723, 45368, 44724, -1, 44717, 45368, 44723, -1, 44704, 45368, 44717, -1, 44703, 45368, 44704, -1, 45366, 45368, 44703, -1, 44427, 45369, 44414, -1, 44446, 45369, 44427, -1, 44476, 45369, 44446, -1, 45367, 45369, 44476, -1, 44731, 45370, 44732, -1, 44727, 45370, 44731, -1, 44724, 45370, 44727, -1, 45368, 45370, 44724, -1, 44404, 45371, 44421, -1, 44389, 45371, 44404, -1, 44414, 45371, 44389, -1, 45369, 45371, 44414, -1, 44421, 45361, 44449, -1, 45371, 45361, 44421, -1, 44644, 45372, 44636, -1, 44735, 45372, 44644, -1, 44732, 45372, 44735, -1, 45370, 45372, 44732, -1, 44626, 45373, 44618, -1, 44630, 45373, 44626, -1, 44636, 45373, 44630, -1, 45372, 45373, 44636, -1, 45373, 45362, 44618, -1, 44609, 45362, 44604, -1, 44612, 45362, 44609, -1, 44618, 45362, 44612, -1, 45368, 45372, 45370, -1, 45366, 45361, 45371, -1, 45366, 45371, 45367, -1, 45366, 45362, 45372, -1, 45366, 45372, 45368, -1, 45366, 45367, 45362, -1, 45349, 45361, 45366, -1, 45347, 45358, 45359, -1, 45347, 45346, 45358, -1, 45348, 45361, 45349, -1, 45348, 45347, 45359, -1, 45348, 45360, 45361, -1, 45348, 45359, 45360, -1, 44773, 44772, 45356, -1, 44779, 44778, 44777, -1, 44779, 44777, 44776, -1, 44779, 44776, 44775, -1, 44779, 44775, 44774, -1, 44779, 44774, 44773, -1, 44779, 45356, 45355, -1, 44779, 45355, 45354, -1, 44779, 45354, 45353, -1, 44779, 45353, 45352, -1, 44779, 45352, 45351, -1, 44779, 45351, 45350, -1, 44779, 44773, 45356, -1, 45345, 45350, 45357, -1, 45345, 44779, 45350, -1, 45367, 45371, 45369, -1, 45364, 45367, 45365, -1, 45362, 45364, 45363, -1, 45362, 45367, 45364, -1, 45346, 45357, 45358, -1, 45346, 45345, 45357, -1, 45372, 45362, 45373, -1, 45374, 45375, 44833, -1, 44833, 45375, 44828, -1, 44828, 45376, 44860, -1, 45375, 45376, 44828, -1, 44860, 44768, 44383, -1, 45376, 44768, 44860, -1, 45377, 45378, 45078, -1, 45071, 45378, 45068, -1, 45074, 45378, 45071, -1, 45078, 45378, 45074, -1, 45378, 45379, 45068, -1, 45063, 45379, 45060, -1, 45066, 45379, 45063, -1, 45068, 45379, 45066, -1, 44897, 45250, 44858, -1, 45379, 45380, 45060, -1, 45126, 45380, 45114, -1, 45127, 45380, 45126, -1, 45132, 45380, 45127, -1, 45060, 45380, 45132, -1, 44844, 45381, 44852, -1, 44843, 45381, 44844, -1, 44857, 45381, 44843, -1, 44858, 45381, 44857, -1, 45250, 45381, 44858, -1, 45380, 45382, 45114, -1, 45105, 45382, 45099, -1, 45110, 45382, 45105, -1, 45114, 45382, 45110, -1, 44903, 45383, 44904, -1, 44880, 45383, 44903, -1, 44853, 45383, 44880, -1, 44852, 45383, 44853, -1, 45381, 45383, 44852, -1, 45069, 45384, 45016, -1, 45092, 45384, 45069, -1, 45099, 45384, 45092, -1, 45382, 45384, 45099, -1, 45011, 45385, 45055, -1, 44997, 45385, 45011, -1, 45016, 45385, 44997, -1, 45384, 45385, 45016, -1, 45055, 45374, 44833, -1, 44985, 45386, 44986, -1, 45385, 45374, 45055, -1, 44955, 45386, 44985, -1, 44904, 45386, 44955, -1, 45383, 45386, 44904, -1, 45004, 45387, 45003, -1, 45065, 45387, 45004, -1, 44986, 45387, 45065, -1, 45386, 45387, 44986, -1, 45002, 45388, 45083, -1, 45001, 45388, 45002, -1, 45003, 45388, 45001, -1, 45387, 45388, 45003, -1, 45080, 45377, 45078, -1, 45082, 45377, 45080, -1, 45083, 45377, 45082, -1, 45388, 45377, 45083, -1, 45252, 44401, 44400, -1, 45389, 44400, 44614, -1, 45389, 45252, 44400, -1, 45390, 45389, 44614, -1, 45391, 44614, 44758, -1, 45391, 45390, 44614, -1, 45392, 45393, 44542, -1, 44536, 45393, 44535, -1, 44537, 45393, 44536, -1, 44542, 45393, 44537, -1, 45393, 45394, 44535, -1, 44533, 45394, 44529, -1, 44534, 45394, 44533, -1, 44535, 45394, 44534, -1, 44620, 44771, 44627, -1, 45394, 45395, 44529, -1, 44648, 45396, 44653, -1, 44639, 45396, 44648, -1, 44637, 45396, 44639, -1, 44627, 45396, 44637, -1, 44771, 45396, 44627, -1, 44532, 45395, 44472, -1, 44555, 45395, 44532, -1, 44504, 45395, 44555, -1, 44529, 45395, 44504, -1, 44441, 45397, 44411, -1, 44442, 45397, 44441, -1, 44472, 45397, 44442, -1, 44673, 45398, 44678, -1, 45395, 45397, 44472, -1, 44668, 45398, 44673, -1, 44659, 45398, 44668, -1, 44653, 45398, 44659, -1, 45396, 45398, 44653, -1, 44381, 45399, 44355, -1, 44384, 45399, 44381, -1, 44411, 45399, 44384, -1, 45397, 45399, 44411, -1, 44346, 45400, 44347, -1, 44354, 45400, 44346, -1, 44699, 45401, 44701, -1, 44355, 45400, 44354, -1, 44693, 45401, 44699, -1, 45399, 45400, 44355, -1, 44678, 45401, 44693, -1, 45398, 45401, 44678, -1, 44347, 45391, 44758, -1, 45400, 45391, 44347, -1, 44718, 45402, 44511, -1, 44711, 45402, 44718, -1, 44701, 45402, 44711, -1, 45401, 45402, 44701, -1, 44550, 45403, 44549, -1, 44553, 45403, 44550, -1, 44511, 45403, 44553, -1, 45402, 45403, 44511, -1, 44545, 45392, 44542, -1, 44547, 45392, 44545, -1, 44549, 45392, 44547, -1, 45403, 45392, 44549, -1, 45395, 45399, 45397, -1, 45393, 45392, 45403, -1, 45394, 45399, 45395, -1, 45394, 45393, 45403, -1, 45394, 45403, 45399, -1, 45250, 45375, 45374, -1, 45250, 45374, 45385, -1, 45250, 45385, 45384, -1, 45250, 45384, 45382, -1, 45250, 45382, 45380, -1, 45250, 45380, 45379, -1, 45250, 45379, 45378, -1, 45250, 45378, 45377, -1, 45250, 45377, 45388, -1, 45250, 45388, 45387, -1, 45250, 45387, 45386, -1, 45250, 45386, 45383, -1, 45250, 45383, 45381, -1, 45249, 45375, 45250, -1, 45376, 45375, 45249, -1, 45251, 45376, 45249, -1, 45252, 44768, 45376, -1, 45252, 45376, 45251, -1, 45389, 44769, 44768, -1, 45389, 44768, 45252, -1, 44770, 44769, 45389, -1, 45390, 44770, 45389, -1, 44771, 44770, 45390, -1, 45391, 45396, 44771, -1, 45391, 44771, 45390, -1, 45401, 45398, 45396, -1, 45400, 45396, 45391, -1, 45403, 45396, 45400, -1, 45403, 45400, 45399, -1, 45403, 45402, 45401, -1, 45403, 45401, 45396, -1, 44935, 45404, 44927, -1, 44927, 45405, 44960, -1, 45404, 45405, 44927, -1, 44960, 45406, 44365, -1, 45405, 45406, 44960, -1, 45406, 44764, 44365, -1, 45407, 45408, 44847, -1, 44995, 45408, 44994, -1, 44996, 45408, 44995, -1, 44847, 45408, 44996, -1, 45408, 45409, 44994, -1, 44992, 45409, 44991, -1, 44993, 45409, 44992, -1, 44994, 45409, 44993, -1, 45094, 45245, 45059, -1, 45409, 45410, 44991, -1, 44983, 45410, 44980, -1, 44987, 45410, 44983, -1, 44990, 45410, 44987, -1, 44991, 45410, 44990, -1, 44999, 45411, 45039, -1, 44998, 45411, 44999, -1, 45057, 45411, 44998, -1, 45059, 45411, 45057, -1, 45245, 45411, 45059, -1, 44978, 45412, 44977, -1, 44979, 45412, 44978, -1, 44980, 45412, 44979, -1, 45410, 45412, 44980, -1, 44974, 45413, 44972, -1, 45100, 45414, 45101, -1, 44975, 45413, 44974, -1, 45093, 45414, 45100, -1, 44977, 45413, 44975, -1, 45040, 45414, 45093, -1, 45412, 45413, 44977, -1, 45039, 45414, 45040, -1, 45411, 45414, 45039, -1, 44970, 45415, 44968, -1, 44971, 45415, 44970, -1, 44972, 45415, 44971, -1, 45413, 45415, 44972, -1, 44968, 45404, 44935, -1, 45415, 45404, 44968, -1, 45116, 45416, 45117, -1, 45111, 45416, 45116, -1, 45101, 45416, 45111, -1, 45414, 45416, 45101, -1, 45133, 45417, 45037, -1, 45128, 45417, 45133, -1, 45117, 45417, 45128, -1, 45416, 45417, 45117, -1, 45030, 45418, 44855, -1, 45033, 45418, 45030, -1, 45037, 45418, 45033, -1, 45417, 45418, 45037, -1, 45418, 45407, 44855, -1, 44846, 45407, 44847, -1, 44850, 45407, 44846, -1, 44855, 45407, 44850, -1, 45248, 44368, 44367, -1, 45419, 44367, 44420, -1, 45419, 45248, 44367, -1, 45420, 44420, 44621, -1, 45420, 45419, 44420, -1, 45421, 45420, 44621, -1, 45422, 45423, 44457, -1, 44622, 45423, 44490, -1, 44623, 45423, 44622, -1, 44457, 45423, 44623, -1, 45423, 45424, 44490, -1, 44489, 45424, 44510, -1, 44488, 45424, 44489, -1, 44490, 45424, 44488, -1, 44444, 44767, 44485, -1, 45424, 45425, 44510, -1, 44481, 45426, 44480, -1, 44482, 45426, 44481, -1, 44484, 45426, 44482, -1, 44485, 45426, 44484, -1, 44767, 45426, 44485, -1, 44706, 45425, 44695, -1, 44712, 45425, 44706, -1, 44713, 45425, 44712, -1, 44510, 45425, 44713, -1, 44473, 45427, 44471, -1, 44475, 45427, 44473, -1, 44477, 45427, 44475, -1, 44679, 45428, 44670, -1, 44480, 45427, 44477, -1, 44681, 45428, 44679, -1, 45426, 45427, 44480, -1, 44695, 45428, 44681, -1, 45425, 45428, 44695, -1, 44662, 45429, 44650, -1, 44664, 45429, 44662, -1, 44670, 45429, 44664, -1, 45428, 45429, 44670, -1, 44468, 45430, 44467, -1, 44470, 45430, 44468, -1, 44471, 45430, 44470, -1, 45427, 45430, 44471, -1, 44642, 45431, 44628, -1, 44643, 45431, 44642, -1, 44650, 45431, 44643, -1, 45429, 45431, 44650, -1, 44628, 45421, 44621, -1, 45431, 45421, 44628, -1, 44465, 45432, 44464, -1, 44466, 45432, 44465, -1, 44467, 45432, 44466, -1, 45430, 45432, 44467, -1, 44462, 45433, 44459, -1, 44463, 45433, 44462, -1, 44464, 45433, 44463, -1, 45432, 45433, 44464, -1, 45433, 45422, 44459, -1, 44456, 45422, 44457, -1, 44458, 45422, 44456, -1, 44459, 45422, 44458, -1, 45425, 45429, 45428, -1, 45424, 45422, 45426, -1, 45424, 45429, 45425, -1, 45424, 45431, 45429, -1, 45424, 45423, 45422, -1, 45424, 45426, 45431, -1, 45245, 45404, 45415, -1, 45245, 45415, 45413, -1, 45245, 45413, 45412, -1, 45245, 45412, 45410, -1, 45245, 45410, 45409, -1, 45245, 45409, 45408, -1, 45245, 45408, 45407, -1, 45245, 45407, 45418, -1, 45245, 45418, 45417, -1, 45245, 45417, 45416, -1, 45245, 45416, 45414, -1, 45245, 45414, 45411, -1, 45405, 45404, 45245, -1, 45246, 45405, 45245, -1, 45406, 45405, 45246, -1, 45247, 45406, 45246, -1, 45248, 44764, 45406, -1, 45248, 45406, 45247, -1, 44765, 44764, 45248, -1, 45419, 44765, 45248, -1, 44766, 44765, 45419, -1, 45420, 44766, 45419, -1, 44767, 44766, 45420, -1, 45421, 44767, 45420, -1, 45430, 45427, 45426, -1, 45431, 45426, 44767, -1, 45431, 44767, 45421, -1, 45432, 45430, 45426, -1, 45422, 45432, 45426, -1, 45422, 45433, 45432, -1, 45434, 45435, 45181, -1, 45181, 45435, 44812, -1, 44812, 45436, 44810, -1, 45435, 45436, 44812, -1, 44810, 45437, 45185, -1, 45436, 45437, 44810, -1, 45185, 45438, 45164, -1, 45437, 45438, 45185, -1, 45164, 45439, 45167, -1, 45438, 45439, 45164, -1, 45440, 45441, 44934, -1, 44931, 45441, 44930, -1, 44932, 45441, 44931, -1, 44934, 45441, 44932, -1, 45441, 45442, 44930, -1, 44924, 45442, 44923, -1, 44926, 45442, 44924, -1, 44930, 45442, 44926, -1, 44949, 45443, 44967, -1, 45442, 45444, 44923, -1, 44832, 45444, 44824, -1, 44836, 45444, 44832, -1, 44837, 45444, 44836, -1, 44923, 45444, 44837, -1, 45072, 45445, 45090, -1, 45036, 45445, 45072, -1, 45005, 45445, 45036, -1, 44967, 45445, 45005, -1, 45443, 45445, 44967, -1, 45444, 45446, 44824, -1, 44801, 45446, 44802, -1, 44803, 45446, 44801, -1, 44824, 45446, 44803, -1, 45115, 45447, 45118, -1, 45108, 45447, 45115, -1, 45098, 45447, 45108, -1, 45090, 45447, 45098, -1, 45445, 45447, 45090, -1, 45200, 45448, 45196, -1, 45201, 45448, 45200, -1, 44802, 45448, 45201, -1, 45446, 45448, 44802, -1, 45188, 45449, 45183, -1, 45189, 45449, 45188, -1, 45196, 45449, 45189, -1, 45448, 45449, 45196, -1, 45183, 45434, 45181, -1, 45136, 45450, 45137, -1, 45449, 45434, 45183, -1, 45129, 45450, 45136, -1, 45118, 45450, 45129, -1, 45447, 45450, 45118, -1, 45161, 45451, 44941, -1, 45148, 45451, 45161, -1, 45137, 45451, 45148, -1, 45450, 45451, 45137, -1, 44939, 45452, 44938, -1, 44940, 45452, 44939, -1, 44941, 45452, 44940, -1, 45451, 45452, 44941, -1, 44936, 45440, 44934, -1, 44937, 45440, 44936, -1, 44938, 45440, 44937, -1, 45452, 45440, 44938, -1, 45453, 45443, 44949, -1, 45453, 44949, 44804, -1, 45454, 44804, 44807, -1, 45454, 45453, 44804, -1, 45455, 44807, 45190, -1, 45455, 45454, 44807, -1, 45456, 45190, 44988, -1, 45456, 45455, 45190, -1, 45244, 44988, 44942, -1, 45244, 45456, 44988, -1, 45167, 45439, 45154, -1, 45139, 45457, 45121, -1, 45146, 45457, 45139, -1, 45154, 45457, 45146, -1, 45439, 45457, 45154, -1, 45085, 45458, 45027, -1, 45104, 45458, 45085, -1, 45121, 45458, 45104, -1, 45457, 45458, 45121, -1, 44963, 45459, 44870, -1, 45027, 45459, 44963, -1, 45458, 45459, 45027, -1, 44956, 45460, 44981, -1, 44905, 45460, 44956, -1, 44870, 45460, 44905, -1, 45459, 45460, 44870, -1, 45058, 45461, 45056, -1, 45017, 45461, 45058, -1, 44981, 45461, 45017, -1, 45460, 45461, 44981, -1, 45053, 45462, 45051, -1, 45054, 45462, 45053, -1, 45056, 45462, 45054, -1, 45461, 45462, 45056, -1, 45051, 45237, 45052, -1, 45462, 45237, 45051, -1, 45441, 45449, 45446, -1, 45441, 45446, 45444, -1, 45441, 45451, 45450, -1, 45441, 45450, 45447, -1, 45441, 45447, 45445, -1, 45441, 45445, 45449, -1, 45442, 45441, 45444, -1, 45462, 45461, 45460, -1, 45457, 45459, 45458, -1, 45238, 45237, 45462, -1, 45244, 45243, 45242, -1, 45244, 45242, 45241, -1, 45244, 45241, 45240, -1, 45244, 45240, 45239, -1, 45244, 45239, 45238, -1, 45244, 45460, 45459, -1, 45244, 45457, 45439, -1, 45244, 45238, 45462, -1, 45244, 45462, 45460, -1, 45244, 45459, 45457, -1, 45456, 45439, 45438, -1, 45456, 45244, 45439, -1, 45455, 45438, 45437, -1, 45455, 45456, 45438, -1, 45454, 45437, 45436, -1, 45454, 45455, 45437, -1, 45453, 45454, 45436, -1, 45435, 45453, 45436, -1, 45443, 45453, 45435, -1, 45434, 45443, 45435, -1, 45449, 45445, 45443, -1, 45449, 45443, 45434, -1, 45446, 45449, 45448, -1, 45440, 45452, 45451, -1, 45441, 45440, 45451, -1, 45087, 45463, 44813, -1, 45463, 45464, 44813, -1, 44813, 45465, 44814, -1, 45464, 45465, 44813, -1, 44814, 45466, 45031, -1, 45465, 45466, 44814, -1, 45031, 45467, 44864, -1, 45466, 45467, 45031, -1, 44864, 45468, 44865, -1, 45467, 45468, 44864, -1, 45469, 45470, 44962, -1, 44959, 45470, 44958, -1, 44961, 45470, 44959, -1, 44962, 45470, 44961, -1, 45470, 45471, 44958, -1, 44953, 45471, 44952, -1, 44957, 45471, 44953, -1, 44958, 45471, 44957, -1, 45180, 45472, 45182, -1, 45471, 45473, 44952, -1, 44916, 45473, 44915, -1, 44917, 45473, 44916, -1, 44918, 45473, 44917, -1, 44952, 45473, 44918, -1, 45195, 45474, 45198, -1, 45187, 45474, 45195, -1, 45186, 45474, 45187, -1, 45182, 45474, 45186, -1, 45472, 45474, 45182, -1, 44912, 45475, 44911, -1, 44914, 45475, 44912, -1, 44915, 45475, 44914, -1, 45473, 45475, 44915, -1, 44908, 45476, 44909, -1, 44808, 45477, 44800, -1, 44910, 45476, 44908, -1, 45213, 45477, 44808, -1, 44911, 45476, 44910, -1, 45199, 45477, 45213, -1, 45475, 45476, 44911, -1, 45198, 45477, 45199, -1, 45474, 45477, 45198, -1, 45088, 45478, 45086, -1, 45089, 45478, 45088, -1, 44909, 45478, 45089, -1, 45476, 45478, 44909, -1, 45086, 45463, 45087, -1, 45478, 45463, 45086, -1, 44827, 45479, 44831, -1, 44823, 45479, 44827, -1, 44800, 45479, 44823, -1, 45477, 45479, 44800, -1, 44839, 45480, 44948, -1, 44835, 45480, 44839, -1, 44831, 45480, 44835, -1, 45479, 45480, 44831, -1, 44946, 45481, 44945, -1, 44947, 45481, 44946, -1, 44948, 45481, 44947, -1, 45480, 45481, 44948, -1, 45481, 45469, 44945, -1, 44944, 45469, 44962, -1, 44943, 45469, 44944, -1, 44945, 45469, 44943, -1, 45472, 45180, 44809, -1, 45482, 45472, 44809, -1, 45483, 44809, 44811, -1, 45483, 45482, 44809, -1, 45484, 44811, 45163, -1, 45484, 45483, 44811, -1, 45485, 45163, 45165, -1, 45485, 45484, 45163, -1, 45236, 45165, 45155, -1, 45236, 45485, 45165, -1, 44865, 45468, 45175, -1, 45174, 45486, 45171, -1, 45175, 45486, 45174, -1, 45468, 45486, 45175, -1, 45159, 45487, 45157, -1, 45166, 45487, 45159, -1, 45171, 45487, 45166, -1, 45486, 45487, 45171, -1, 45150, 45488, 45145, -1, 45157, 45488, 45150, -1, 45487, 45488, 45157, -1, 45147, 45489, 45156, -1, 45144, 45489, 45147, -1, 45145, 45489, 45144, -1, 45488, 45489, 45145, -1, 45162, 45490, 45170, -1, 45158, 45490, 45162, -1, 45156, 45490, 45158, -1, 45489, 45490, 45156, -1, 45173, 45491, 45178, -1, 45172, 45491, 45173, -1, 45170, 45491, 45172, -1, 45490, 45491, 45170, -1, 45178, 45229, 45179, -1, 45491, 45229, 45178, -1, 45468, 45491, 45490, -1, 45468, 45490, 45489, -1, 45468, 45489, 45488, -1, 45468, 45488, 45487, -1, 45468, 45487, 45486, -1, 45230, 45229, 45491, -1, 45230, 45491, 45468, -1, 45231, 45230, 45468, -1, 45232, 45231, 45468, -1, 45233, 45232, 45468, -1, 45234, 45233, 45468, -1, 45235, 45234, 45468, -1, 45236, 45235, 45468, -1, 45485, 45468, 45467, -1, 45485, 45236, 45468, -1, 45484, 45467, 45466, -1, 45484, 45485, 45467, -1, 45483, 45466, 45465, -1, 45483, 45484, 45466, -1, 45482, 45483, 45465, -1, 45464, 45482, 45465, -1, 45472, 45482, 45464, -1, 45463, 45474, 45472, -1, 45463, 45472, 45464, -1, 45479, 45477, 45474, -1, 45480, 45474, 45463, -1, 45480, 45479, 45474, -1, 45476, 45463, 45478, -1, 45475, 45463, 45476, -1, 45470, 45469, 45481, -1, 45470, 45481, 45480, -1, 45470, 45480, 45463, -1, 45471, 45475, 45473, -1, 45471, 45470, 45463, -1, 45471, 45463, 45475, -1, 44950, 45492, 44805, -1, 45492, 45493, 44805, -1, 44805, 45494, 44806, -1, 45493, 45494, 44805, -1, 44806, 45495, 45197, -1, 45494, 45495, 44806, -1, 45197, 45496, 45184, -1, 45495, 45496, 45197, -1, 45184, 45497, 44969, -1, 45496, 45497, 45184, -1, 44875, 45498, 44874, -1, 44876, 45498, 44875, -1, 44877, 45498, 44876, -1, 45499, 45498, 44877, -1, 45498, 45500, 44874, -1, 44868, 45500, 44869, -1, 44873, 45500, 44868, -1, 44874, 45500, 44873, -1, 44819, 45501, 44822, -1, 45500, 45502, 44869, -1, 45138, 45502, 45130, -1, 45149, 45502, 45138, -1, 44898, 45503, 44895, -1, 44922, 45502, 45149, -1, 44899, 45503, 44898, -1, 44869, 45502, 44922, -1, 44900, 45503, 44899, -1, 44822, 45503, 44900, -1, 45501, 45503, 44822, -1, 45119, 45504, 45109, -1, 45120, 45504, 45119, -1, 45130, 45504, 45120, -1, 45502, 45504, 45130, -1, 44892, 45505, 44891, -1, 44893, 45505, 44892, -1, 44894, 45505, 44893, -1, 44895, 45505, 44894, -1, 45503, 45505, 44895, -1, 45102, 45506, 45077, -1, 45103, 45506, 45102, -1, 45109, 45506, 45103, -1, 45504, 45506, 45109, -1, 45047, 45507, 44973, -1, 45049, 45507, 45047, -1, 45077, 45507, 45049, -1, 45506, 45507, 45077, -1, 44889, 45508, 44888, -1, 44890, 45508, 44889, -1, 44973, 45492, 44950, -1, 44891, 45508, 44890, -1, 45505, 45508, 44891, -1, 45507, 45492, 44973, -1, 44886, 45509, 44885, -1, 44887, 45509, 44886, -1, 44888, 45509, 44887, -1, 45508, 45509, 44888, -1, 44883, 45510, 44882, -1, 44884, 45510, 44883, -1, 44885, 45510, 44884, -1, 45509, 45510, 44885, -1, 44878, 45499, 44877, -1, 44881, 45499, 44878, -1, 44882, 45499, 44881, -1, 45510, 45499, 44882, -1, 45511, 45501, 44819, -1, 45511, 44819, 44820, -1, 45512, 44820, 45220, -1, 45512, 45511, 44820, -1, 45513, 45220, 45219, -1, 45513, 45512, 45220, -1, 45514, 45219, 45218, -1, 45514, 45513, 45219, -1, 45228, 45218, 45215, -1, 45228, 45514, 45218, -1, 44969, 45497, 44933, -1, 44913, 45515, 44861, -1, 44920, 45515, 44913, -1, 44933, 45515, 44920, -1, 45497, 45515, 44933, -1, 44840, 45516, 44834, -1, 44849, 45516, 44840, -1, 44861, 45516, 44849, -1, 45515, 45516, 44861, -1, 44816, 45517, 44817, -1, 44825, 45517, 44816, -1, 44834, 45517, 44825, -1, 45516, 45517, 44834, -1, 45050, 45518, 45048, -1, 45212, 45518, 45050, -1, 44817, 45518, 45212, -1, 45517, 45518, 44817, -1, 45045, 45519, 45043, -1, 45046, 45519, 45045, -1, 45048, 45519, 45046, -1, 45518, 45519, 45048, -1, 45038, 45520, 45034, -1, 45041, 45520, 45038, -1, 45043, 45520, 45041, -1, 45519, 45520, 45043, -1, 45034, 45221, 45035, -1, 45520, 45221, 45034, -1, 45499, 45510, 45508, -1, 45500, 45507, 45506, -1, 45500, 45506, 45504, -1, 45500, 45504, 45502, -1, 45500, 45498, 45499, -1, 45500, 45508, 45505, -1, 45500, 45505, 45503, -1, 45500, 45503, 45507, -1, 45500, 45499, 45508, -1, 45222, 45221, 45520, -1, 45228, 45227, 45226, -1, 45228, 45226, 45225, -1, 45228, 45225, 45224, -1, 45228, 45224, 45223, -1, 45228, 45223, 45222, -1, 45228, 45520, 45519, -1, 45228, 45519, 45518, -1, 45228, 45518, 45517, -1, 45228, 45517, 45516, -1, 45228, 45516, 45515, -1, 45228, 45515, 45497, -1, 45228, 45222, 45520, -1, 45514, 45497, 45496, -1, 45514, 45228, 45497, -1, 45513, 45496, 45495, -1, 45513, 45514, 45496, -1, 45512, 45495, 45494, -1, 45512, 45513, 45495, -1, 45511, 45512, 45494, -1, 45493, 45511, 45494, -1, 45501, 45511, 45493, -1, 45492, 45503, 45501, -1, 45492, 45501, 45493, -1, 45507, 45503, 45492, -1, 45510, 45509, 45508, -1, 44040, 44064, 44052, -1, 44042, 44064, 44040, -1, 44041, 44054, 44050, -1, 44054, 44055, 44050, -1, 44044, 44257, 44043, -1, 44261, 44257, 44044, -1, 44255, 44049, 44253, -1, 44253, 44049, 44045, -1, 44051, 44251, 44046, -1, 44250, 44251, 44051, -1, 44047, 44062, 44048, -1, 44065, 44062, 44047, -1, 45521, 45522, 44226, -1, 44073, 44281, 44119, -1, 45523, 44161, 44160, -1, 45524, 45525, 45522, -1, 45524, 45522, 45521, -1, 45526, 44275, 44274, -1, 45523, 44160, 44202, -1, 45526, 44274, 45527, -1, 45526, 45527, 45525, -1, 45528, 44164, 44161, -1, 45526, 45525, 45524, -1, 45528, 44167, 44164, -1, 45529, 44222, 44208, -1, 45528, 44161, 45523, -1, 45529, 45521, 44222, -1, 45530, 44167, 45528, -1, 45530, 44170, 44167, -1, 45530, 44266, 44170, -1, 45531, 45524, 45521, -1, 45532, 44202, 44204, -1, 45531, 45521, 45529, -1, 44202, 44160, 44177, -1, 45533, 44276, 44275, -1, 45532, 45523, 44202, -1, 45533, 44275, 45526, -1, 45533, 45526, 45524, -1, 45533, 45524, 45531, -1, 45534, 44208, 44207, -1, 45535, 45523, 45532, -1, 45535, 45528, 45523, -1, 45534, 45529, 44208, -1, 45536, 44267, 44266, -1, 44266, 44100, 44170, -1, 45536, 44266, 45530, -1, 45536, 45530, 45528, -1, 45536, 45528, 45535, -1, 45537, 45531, 45529, -1, 45537, 45529, 45534, -1, 45538, 44204, 44232, -1, 45539, 44277, 44276, -1, 45538, 45532, 44204, -1, 45539, 44276, 45533, -1, 45539, 45533, 45531, -1, 45539, 45531, 45537, -1, 45540, 44207, 44206, -1, 45541, 45532, 45538, -1, 45541, 45535, 45532, -1, 45540, 45534, 44207, -1, 45542, 44267, 45536, -1, 45542, 45536, 45535, -1, 45542, 44268, 44267, -1, 45542, 45535, 45541, -1, 45543, 45537, 45534, -1, 45544, 44232, 44214, -1, 45543, 45534, 45540, -1, 45544, 45538, 44232, -1, 45545, 45537, 45543, -1, 45545, 44277, 45539, -1, 45545, 44278, 44277, -1, 45545, 45539, 45537, -1, 45546, 45541, 45538, -1, 45546, 45538, 45544, -1, 45547, 44206, 44218, -1, 45548, 44269, 44268, -1, 45547, 45540, 44206, -1, 45548, 44268, 45542, -1, 45549, 45540, 45547, -1, 45548, 45542, 45541, -1, 45548, 45541, 45546, -1, 45550, 44214, 44213, -1, 45549, 45543, 45540, -1, 45551, 44278, 45545, -1, 45551, 45543, 45549, -1, 45551, 45545, 45543, -1, 45550, 45544, 44214, -1, 45551, 44279, 44278, -1, 45552, 45544, 45550, -1, 45553, 44218, 44220, -1, 45552, 45546, 45544, -1, 45554, 44269, 45548, -1, 45554, 44270, 44269, -1, 45553, 45547, 44218, -1, 45555, 45549, 45547, -1, 45554, 45548, 45546, -1, 45555, 45547, 45553, -1, 45554, 45546, 45552, -1, 45556, 44213, 44212, -1, 45557, 45551, 45549, -1, 45556, 45550, 44213, -1, 45557, 44279, 45551, -1, 45557, 45549, 45555, -1, 45557, 44280, 44279, -1, 45558, 45552, 45550, -1, 45559, 44223, 44124, -1, 45558, 45550, 45556, -1, 45559, 44220, 44223, -1, 45559, 45553, 44220, -1, 45560, 44271, 44270, -1, 45559, 44124, 44108, -1, 45559, 44108, 44107, -1, 45560, 45552, 45558, -1, 45560, 44270, 45554, -1, 45561, 45555, 45553, -1, 45560, 45554, 45552, -1, 45562, 44212, 44229, -1, 45561, 45559, 44107, -1, 45561, 44107, 44116, -1, 45562, 45556, 44212, -1, 45561, 45553, 45559, -1, 45563, 45557, 45555, -1, 45563, 44280, 45557, -1, 45563, 45555, 45561, -1, 45563, 44116, 44118, -1, 45564, 45556, 45562, -1, 45563, 45561, 44116, -1, 45563, 44118, 44119, -1, 45564, 45558, 45556, -1, 45563, 44119, 44281, -1, 45563, 44281, 44280, -1, 45565, 44271, 45560, -1, 45565, 44272, 44271, -1, 45565, 45560, 45558, -1, 45565, 45558, 45564, -1, 45566, 44229, 44227, -1, 45566, 45562, 44229, -1, 45567, 45564, 45562, -1, 45567, 45562, 45566, -1, 45568, 44273, 44272, -1, 45568, 45565, 45564, -1, 45568, 44272, 45565, -1, 45568, 45564, 45567, -1, 45522, 44227, 44226, -1, 45522, 45566, 44227, -1, 45525, 45567, 45566, -1, 45525, 45566, 45522, -1, 45527, 44274, 44273, -1, 45527, 44273, 45568, -1, 45527, 45568, 45567, -1, 45527, 45567, 45525, -1, 45521, 44226, 44222, -1, 1844, 1845, 1918, -1, 1844, 1918, 1947, -1, 1840, 1947, 1963, -1, 1840, 1844, 1947, -1, 1836, 1963, 1970, -1, 1836, 1840, 1963, -1, 1830, 1970, 1976, -1, 1830, 1836, 1970, -1, 1834, 1976, 1980, -1, 1834, 1830, 1976, -1, 1839, 1980, 1988, -1, 1839, 1834, 1980, -1, 1843, 1988, 2047, -1, 1843, 1839, 1988, -1, 1846, 2047, 2039, -1, 1846, 1843, 2047, -1, 1847, 2039, 2021, -1, 1847, 1846, 2039, -1, 1850, 2021, 2014, -1, 1850, 1847, 2021, -1, 1852, 2014, 2003, -1, 1852, 1850, 2014, -1, 1864, 2003, 2005, -1, 1864, 1852, 2003, -1, 1877, 2005, 2017, -1, 1877, 1864, 2005, -1, 1886, 2017, 2027, -1, 1886, 1877, 2017, -1, 1895, 2027, 2029, -1, 1895, 1886, 2027, -1, 1818, 1895, 2029, -1, 1818, 2029, 1902, -1, 1812, 1551, 1785, -1, 1785, 1551, 1539, -1, 45569, 1807, 1808, -1, 45570, 1807, 45569, -1, 1554, 1897, 1579, -1, 1579, 1897, 1788, -1, 1669, 1531, 1783, -1, 1669, 1783, 45571, -1, 1662, 45571, 45572, -1, 1662, 1669, 45571, -1, 1656, 45572, 45573, -1, 1656, 1662, 45572, -1, 1642, 45573, 45574, -1, 1642, 1656, 45573, -1, 1626, 45574, 45575, -1, 1626, 1642, 45574, -1, 1616, 45575, 45576, -1, 1616, 1626, 45575, -1, 1608, 45576, 45577, -1, 1608, 1616, 45576, -1, 1609, 45577, 45578, -1, 1609, 1608, 45577, -1, 1604, 45578, 45579, -1, 1604, 1609, 45578, -1, 1599, 45579, 45580, -1, 1599, 1604, 45579, -1, 1593, 45580, 45581, -1, 1593, 1599, 45580, -1, 1587, 45581, 45582, -1, 1587, 1593, 45581, -1, 1583, 45582, 45583, -1, 1583, 1587, 45582, -1, 1590, 45583, 45584, -1, 1590, 1583, 45583, -1, 1596, 45584, 45585, -1, 1596, 1590, 45584, -1, 1602, 45585, 45586, -1, 1602, 1596, 45585, -1, 1606, 45586, 1766, -1, 1606, 1602, 45586, -1, 1781, 1769, 1767, -1, 1781, 1767, 1782, -1, 1780, 1769, 1781, -1, 1778, 1777, 1776, -1, 1778, 1770, 1769, -1, 1778, 1772, 1770, -1, 1778, 1776, 1772, -1, 1779, 1778, 1769, -1, 1779, 1769, 1780, -1, 45579, 45582, 45581, -1, 45579, 45581, 45580, -1, 1769, 1768, 1767, -1, 45575, 45579, 45578, -1, 45575, 45578, 45577, -1, 45575, 45577, 45576, -1, 45575, 45582, 45579, -1, 45574, 45585, 45584, -1, 45574, 45584, 45583, -1, 45574, 45583, 45582, -1, 45574, 45582, 45575, -1, 45573, 45585, 45574, -1, 1772, 1771, 1770, -1, 45572, 45585, 45573, -1, 1774, 1773, 1772, -1, 1783, 1766, 45586, -1, 1783, 45586, 45585, -1, 1783, 45572, 45571, -1, 1783, 1767, 1766, -1, 1783, 45585, 45572, -1, 1782, 1767, 1783, -1, 1776, 1775, 1774, -1, 1776, 1774, 1772, -1, 1751, 45587, 1765, -1, 1765, 45587, 1816, -1, 1816, 45588, 1817, -1, 45587, 45588, 1816, -1, 1817, 45589, 1826, -1, 45588, 45589, 1817, -1, 1826, 45590, 1822, -1, 45589, 45590, 1826, -1, 1822, 45591, 1814, -1, 45590, 45591, 1822, -1, 1814, 45592, 1813, -1, 45591, 45592, 1814, -1, 1813, 45593, 1802, -1, 45592, 45593, 1813, -1, 1802, 45594, 1796, -1, 45593, 45594, 1802, -1, 1796, 45595, 1795, -1, 45594, 45595, 1796, -1, 1795, 45596, 1797, -1, 45595, 45596, 1795, -1, 1797, 45597, 1798, -1, 45596, 45597, 1797, -1, 1798, 45598, 1799, -1, 45597, 45598, 1798, -1, 1799, 1738, 1752, -1, 45598, 1738, 1799, -1, 1564, 1565, 1751, -1, 1751, 1565, 45587, -1, 45587, 1571, 45588, -1, 1565, 1571, 45587, -1, 45588, 1575, 45589, -1, 1571, 1575, 45588, -1, 45589, 1573, 45590, -1, 1575, 1573, 45589, -1, 45590, 1568, 45591, -1, 1573, 1568, 45590, -1, 45591, 1567, 45592, -1, 1568, 1567, 45591, -1, 45592, 1569, 45593, -1, 1567, 1569, 45592, -1, 45593, 1556, 45594, -1, 1569, 1556, 45593, -1, 45594, 1541, 45595, -1, 1556, 1541, 45594, -1, 45595, 1540, 45596, -1, 1541, 1540, 45595, -1, 45596, 1525, 45597, -1, 1540, 1525, 45596, -1, 45597, 1527, 45598, -1, 1525, 1527, 45597, -1, 45598, 1681, 1738, -1, 1527, 1681, 45598, -1, 1723, 45599, 1737, -1, 1737, 45599, 1883, -1, 1883, 45600, 1884, -1, 45599, 45600, 1883, -1, 1884, 45601, 1885, -1, 45600, 45601, 1884, -1, 1885, 45602, 1888, -1, 45601, 45602, 1885, -1, 1888, 45603, 1887, -1, 45602, 45603, 1888, -1, 1887, 45604, 1879, -1, 45603, 45604, 1887, -1, 1879, 45605, 1878, -1, 45604, 45605, 1879, -1, 1878, 45606, 1871, -1, 45605, 45606, 1878, -1, 1871, 45607, 1867, -1, 45606, 45607, 1871, -1, 1867, 45608, 1865, -1, 45607, 45608, 1867, -1, 1865, 45609, 1856, -1, 45608, 45609, 1865, -1, 1856, 45610, 1853, -1, 45609, 45610, 1856, -1, 1853, 1710, 1724, -1, 45610, 1710, 1853, -1, 1655, 1659, 1723, -1, 1723, 1659, 45599, -1, 45599, 1545, 45600, -1, 1659, 1545, 45599, -1, 45600, 1670, 45601, -1, 1545, 1670, 45600, -1, 45601, 1664, 45602, -1, 1670, 1664, 45601, -1, 45602, 1663, 45603, -1, 1664, 1663, 45602, -1, 45603, 1658, 45604, -1, 1663, 1658, 45603, -1, 45604, 1657, 45605, -1, 1658, 1657, 45604, -1, 45605, 1648, 45606, -1, 1657, 1648, 45605, -1, 45606, 1643, 45607, -1, 1648, 1643, 45606, -1, 45607, 1636, 45608, -1, 1643, 1636, 45607, -1, 45608, 1629, 45609, -1, 1636, 1629, 45608, -1, 45609, 1623, 45610, -1, 1629, 1623, 45609, -1, 45610, 1618, 1710, -1, 1623, 1618, 45610, -1, 1695, 45611, 1709, -1, 1709, 45611, 1835, -1, 1835, 45612, 1831, -1, 45611, 45612, 1835, -1, 1831, 45613, 1829, -1, 45612, 45613, 1831, -1, 1829, 45614, 1832, -1, 45613, 45614, 1829, -1, 1832, 45615, 1833, -1, 45614, 45615, 1832, -1, 1833, 45616, 1837, -1, 45615, 45616, 1833, -1, 1837, 45617, 1838, -1, 45616, 45617, 1837, -1, 1838, 45618, 1841, -1, 45617, 45618, 1838, -1, 1841, 45619, 1842, -1, 45618, 45619, 1841, -1, 1842, 45620, 1823, -1, 45619, 45620, 1842, -1, 1823, 45621, 1819, -1, 45620, 45621, 1823, -1, 1819, 45622, 1815, -1, 45621, 45622, 1819, -1, 1815, 1682, 1696, -1, 45622, 1682, 1815, -1, 1695, 1594, 45611, -1, 1594, 1589, 45611, -1, 45611, 1588, 45612, -1, 1589, 1588, 45611, -1, 45612, 1585, 45613, -1, 1588, 1585, 45612, -1, 45613, 1584, 45614, -1, 1585, 1584, 45613, -1, 45614, 1586, 45615, -1, 1584, 1586, 45614, -1, 45615, 1591, 45616, -1, 1586, 1591, 45615, -1, 45616, 1592, 45617, -1, 1591, 1592, 45616, -1, 45617, 1597, 45618, -1, 1592, 1597, 45617, -1, 45618, 1598, 45619, -1, 1597, 1598, 45618, -1, 45619, 1603, 45620, -1, 1598, 1603, 45619, -1, 45620, 1561, 45621, -1, 1603, 1561, 45620, -1, 45621, 1559, 45622, -1, 1561, 1559, 45621, -1, 45622, 1557, 1682, -1, 1559, 1557, 45622, -1, 1507, 45623, 1521, -1, 1521, 45623, 1889, -1, 1889, 45624, 1891, -1, 45623, 45624, 1889, -1, 1891, 45625, 1892, -1, 45624, 45625, 1891, -1, 1892, 45626, 1893, -1, 45625, 45626, 1892, -1, 1893, 45627, 1894, -1, 45626, 45627, 1893, -1, 1894, 45628, 1882, -1, 45627, 45628, 1894, -1, 1882, 45629, 1881, -1, 45628, 45629, 1882, -1, 1881, 45630, 1876, -1, 45629, 45630, 1881, -1, 1876, 45631, 1870, -1, 45630, 45631, 1876, -1, 1870, 45632, 1862, -1, 45631, 45632, 1870, -1, 1862, 45633, 1858, -1, 45632, 45633, 1862, -1, 1858, 45634, 1854, -1, 45633, 45634, 1858, -1, 1854, 1480, 1508, -1, 45634, 1480, 1854, -1, 1507, 1506, 45623, -1, 1506, 1661, 45623, -1, 45623, 1666, 45624, -1, 1661, 1666, 45623, -1, 45624, 1665, 45625, -1, 1666, 1665, 45624, -1, 45625, 1667, 45626, -1, 1665, 1667, 45625, -1, 45626, 1582, 45627, -1, 1667, 1582, 45626, -1, 45627, 1581, 45628, -1, 1582, 1581, 45627, -1, 45628, 1654, 45629, -1, 1581, 1654, 45628, -1, 45629, 1652, 45630, -1, 1654, 1652, 45629, -1, 45630, 1644, 45631, -1, 1652, 1644, 45630, -1, 45631, 1637, 45632, -1, 1644, 1637, 45631, -1, 45632, 1630, 45633, -1, 1637, 1630, 45632, -1, 45633, 1624, 45634, -1, 1630, 1624, 45633, -1, 45634, 1481, 1480, -1, 1624, 1481, 45634, -1, 45570, 1812, 1807, -1, 1551, 1812, 45570, -1, 45570, 45569, 1554, -1, 45570, 1554, 1551, -1, 45569, 1897, 1554, -1, 45569, 1808, 1897, -1, 1810, 1548, 1538, -1, 1810, 1792, 1548, -1, 1809, 1538, 1537, -1, 1809, 1810, 1538, -1, 1804, 1537, 1535, -1, 1804, 1809, 1537, -1, 1803, 1535, 1534, -1, 1803, 1804, 1535, -1, 1805, 1534, 1533, -1, 1805, 1803, 1534, -1, 1811, 1533, 1543, -1, 1811, 1805, 1533, -1, 1790, 1543, 1550, -1, 1790, 1811, 1543, -1, 1857, 1621, 1625, -1, 1857, 1791, 1621, -1, 1859, 1625, 1631, -1, 1859, 1857, 1625, -1, 1863, 1631, 1638, -1, 1863, 1859, 1631, -1, 1869, 1638, 1641, -1, 1869, 1863, 1638, -1, 1873, 1641, 1647, -1, 1873, 1869, 1641, -1, 1875, 1647, 1651, -1, 1875, 1873, 1647, -1, 1789, 1651, 1580, -1, 1789, 1875, 1651, -1, 1874, 1546, 1650, -1, 1874, 1787, 1546, -1, 1872, 1650, 1645, -1, 1872, 1874, 1650, -1, 1868, 1645, 1640, -1, 1868, 1872, 1645, -1, 1861, 1640, 1635, -1, 1861, 1868, 1640, -1, 1860, 1635, 1633, -1, 1860, 1861, 1635, -1, 1855, 1633, 1628, -1, 1855, 1860, 1633, -1, 1793, 1628, 1619, -1, 1793, 1855, 1628, -1, 1821, 1566, 1572, -1, 1821, 1784, 1566, -1, 1824, 1572, 1576, -1, 1824, 1821, 1572, -1, 1827, 1576, 1577, -1, 1827, 1824, 1576, -1, 1828, 1577, 1578, -1, 1828, 1827, 1577, -1, 1825, 1578, 1574, -1, 1825, 1828, 1578, -1, 1820, 1574, 1570, -1, 1820, 1825, 1574, -1, 1786, 1570, 1562, -1, 1786, 1820, 1570, -1, 1478, 45635, 1445, -1, 45635, 44002, 43998, -1, 1476, 44002, 45635, -1, 1478, 1476, 45635, -1, 1476, 1477, 44002, -1, 1477, 44000, 44002, -1, 1446, 45636, 1479, -1, 43997, 44000, 45636, -1, 44000, 1477, 45636, -1, 1477, 1479, 45636, -1, 43998, 45636, 45635, -1, 43997, 45636, 43998, -1, 1445, 45636, 1446, -1, 45635, 45636, 1445, -1, 45637, 1479, 45638, -1, 1478, 1479, 45637, -1, 45639, 1479, 1477, -1, 45639, 45638, 1479, -1, 1476, 1478, 45637, -1, 45640, 1477, 1476, -1, 45640, 1476, 45637, -1, 45640, 45639, 1477, -1, 45638, 45641, 45642, -1, 45639, 45641, 45638, -1, 45643, 45639, 45640, -1, 45641, 45639, 45643, -1, 45644, 45640, 45637, -1, 45643, 45640, 45644, -1, 45637, 45638, 45644, -1, 45638, 45642, 45644, -1, 45643, 45645, 45646, -1, 45643, 45644, 45645, -1, 45647, 45648, 45645, -1, 45648, 45646, 45645, -1, 45644, 45642, 45645, -1, 45645, 45642, 45647, -1, 45648, 45643, 45646, -1, 45641, 45643, 45648, -1, 45642, 45648, 45647, -1, 45642, 45641, 45648, -1, 1445, 1479, 1478, -1, 1446, 1479, 1445, -1, 10274, 10138, 45649, -1, 10274, 45649, 45650, -1, 45651, 10244, 10274, -1, 45651, 10274, 45650, -1, 10283, 10244, 45651, -1, 10283, 45651, 45652, -1, 45653, 10245, 10283, -1, 45653, 10283, 45652, -1, 10200, 10245, 45653, -1, 10200, 45653, 45654, -1, 45655, 10181, 10200, -1, 45655, 10200, 45654, -1, 10386, 10181, 45655, -1, 10386, 45655, 45656, -1, 45656, 45649, 10138, -1, 10386, 45656, 10138, -1, 45656, 45657, 45649, -1, 45649, 45657, 45658, -1, 45658, 45659, 45649, -1, 45659, 45650, 45649, -1, 45652, 45650, 45659, -1, 45656, 45660, 45657, -1, 45652, 45651, 45650, -1, 45660, 45653, 45659, -1, 45659, 45653, 45652, -1, 45653, 45655, 45654, -1, 45656, 45655, 45660, -1, 45660, 45655, 45653, -1, 45661, 45660, 45659, -1, 45661, 45659, 45662, -1, 45660, 45663, 45657, -1, 45661, 45663, 45660, -1, 45657, 45663, 45664, -1, 45657, 45664, 45658, -1, 45664, 45662, 45659, -1, 45664, 45659, 45658, -1, 10219, 45665, 45666, -1, 10219, 45666, 10151, -1, 45667, 10414, 10151, -1, 45667, 10151, 45666, -1, 10442, 10414, 45667, -1, 10442, 45667, 45668, -1, 45669, 10442, 45668, -1, 10433, 10442, 45669, -1, 45670, 10433, 45669, -1, 10416, 10433, 45670, -1, 45671, 10416, 45670, -1, 10415, 10416, 45671, -1, 45672, 10415, 45671, -1, 10417, 10415, 45672, -1, 45673, 10417, 45672, -1, 10349, 10417, 45673, -1, 45674, 10349, 45673, -1, 10341, 10349, 45674, -1, 45675, 10341, 45674, -1, 10322, 10341, 45675, -1, 45676, 10322, 45675, -1, 10311, 10322, 45676, -1, 45677, 10311, 45676, -1, 10303, 10311, 45677, -1, 45678, 10303, 45677, -1, 10296, 10303, 45678, -1, 45679, 10296, 45678, -1, 10292, 10296, 45679, -1, 45680, 10292, 45679, -1, 10293, 10292, 45680, -1, 45681, 10293, 45680, -1, 10300, 10293, 45681, -1, 45682, 10300, 45681, -1, 10316, 10300, 45682, -1, 45683, 10316, 45682, -1, 10330, 10316, 45683, -1, 45684, 10330, 45683, -1, 10373, 10330, 45684, -1, 45685, 10373, 45684, -1, 10374, 10373, 45685, -1, 45686, 10374, 45685, -1, 10375, 10374, 45686, -1, 45687, 10375, 45686, -1, 10376, 10375, 45687, -1, 45688, 10376, 45687, -1, 10377, 10376, 45688, -1, 45689, 10377, 45688, -1, 10480, 10377, 45689, -1, 45690, 10480, 45689, -1, 10136, 10480, 45690, -1, 45691, 10136, 45690, -1, 10137, 10136, 45691, -1, 45692, 10137, 45691, -1, 10144, 10137, 45692, -1, 45693, 10144, 45692, -1, 10161, 10144, 45693, -1, 45694, 10161, 45693, -1, 10170, 10161, 45694, -1, 45695, 10170, 45694, -1, 10185, 10170, 45695, -1, 45696, 10185, 45695, -1, 10207, 10185, 45696, -1, 45697, 10207, 45696, -1, 10235, 10207, 45697, -1, 45698, 10235, 45697, -1, 10238, 10235, 45698, -1, 45699, 10238, 45698, -1, 10256, 10238, 45699, -1, 10418, 10256, 45699, -1, 10418, 45699, 45700, -1, 10419, 45700, 45701, -1, 10419, 10418, 45700, -1, 10420, 45701, 45702, -1, 10420, 10419, 45701, -1, 10421, 45702, 45703, -1, 10421, 10420, 45702, -1, 10422, 45703, 45704, -1, 10422, 10421, 45703, -1, 10423, 45704, 45705, -1, 10423, 10422, 45704, -1, 10424, 45705, 45706, -1, 10424, 10423, 45705, -1, 10425, 45706, 45707, -1, 10425, 10424, 45706, -1, 10426, 45707, 45708, -1, 10426, 10425, 45707, -1, 10427, 45708, 45709, -1, 10427, 10426, 45708, -1, 10220, 45709, 45710, -1, 10220, 10427, 45709, -1, 45711, 10177, 10220, -1, 45711, 10220, 45710, -1, 45712, 10177, 45711, -1, 10193, 10177, 45712, -1, 45713, 10193, 45712, -1, 10210, 10193, 45713, -1, 45714, 10210, 45713, -1, 10218, 10210, 45714, -1, 45715, 10218, 45714, -1, 10223, 10218, 45715, -1, 45716, 10223, 45715, -1, 10226, 10223, 45716, -1, 45717, 10226, 45716, -1, 10236, 10226, 45717, -1, 45718, 10236, 45717, -1, 10237, 10236, 45718, -1, 45719, 10237, 45718, -1, 10231, 10237, 45719, -1, 45720, 10231, 45719, -1, 10230, 10231, 45720, -1, 45721, 10230, 45720, -1, 10205, 10230, 45721, -1, 45722, 10205, 45721, -1, 10197, 10205, 45722, -1, 45723, 10197, 45722, -1, 10198, 10197, 45723, -1, 45724, 10198, 45723, -1, 10196, 10198, 45724, -1, 45725, 10196, 45724, -1, 10199, 10196, 45725, -1, 45726, 10199, 45725, -1, 10212, 10199, 45726, -1, 45727, 10212, 45726, -1, 10211, 10212, 45727, -1, 10194, 45727, 45728, -1, 10194, 10211, 45727, -1, 10178, 45728, 45729, -1, 10178, 10194, 45728, -1, 10487, 45729, 45730, -1, 10487, 10178, 45729, -1, 10486, 45730, 45731, -1, 10486, 10487, 45730, -1, 10470, 45731, 45732, -1, 10470, 10486, 45731, -1, 45733, 10470, 45732, -1, 10469, 10470, 45733, -1, 45734, 10469, 45733, -1, 10471, 10469, 45734, -1, 45735, 10471, 45734, -1, 10472, 10471, 45735, -1, 45736, 10472, 45735, -1, 10473, 10472, 45736, -1, 45737, 10473, 45736, -1, 10474, 10473, 45737, -1, 45738, 10474, 45737, -1, 10475, 10474, 45738, -1, 45739, 10475, 45738, -1, 10398, 10475, 45739, -1, 45740, 10398, 45739, -1, 10396, 10398, 45740, -1, 45741, 10396, 45740, -1, 10399, 10396, 45741, -1, 45742, 10399, 45741, -1, 10397, 10399, 45742, -1, 45743, 10397, 45742, -1, 10438, 10397, 45743, -1, 45744, 10438, 45743, -1, 10436, 10438, 45744, -1, 45745, 10436, 45744, -1, 10437, 10436, 45745, -1, 45746, 10437, 45745, -1, 10446, 10437, 45746, -1, 45747, 10446, 45746, -1, 10456, 10446, 45747, -1, 45748, 10456, 45747, -1, 10458, 10456, 45748, -1, 45749, 10458, 45748, -1, 10466, 10458, 45749, -1, 45750, 10466, 45749, -1, 10481, 10466, 45750, -1, 45751, 10481, 45750, -1, 10483, 10481, 45751, -1, 45752, 10483, 45751, -1, 10488, 10483, 45752, -1, 10490, 10488, 45752, -1, 45753, 10490, 45752, -1, 45754, 10467, 10490, -1, 45754, 10490, 45753, -1, 10176, 10467, 45754, -1, 45755, 10176, 45754, -1, 45755, 45665, 10219, -1, 10176, 45755, 10219, -1, 45737, 45679, 45738, -1, 45680, 45679, 45737, -1, 45702, 45718, 45703, -1, 45736, 45680, 45737, -1, 45668, 45667, 45666, -1, 45687, 45686, 45731, -1, 45687, 45731, 45730, -1, 45681, 45680, 45736, -1, 45701, 45718, 45702, -1, 45701, 45719, 45718, -1, 45682, 45736, 45735, -1, 45682, 45681, 45736, -1, 45745, 45668, 45746, -1, 45711, 45710, 45709, -1, 45745, 45669, 45668, -1, 45747, 45746, 45668, -1, 45755, 45754, 45753, -1, 45744, 45669, 45745, -1, 45744, 45670, 45669, -1, 45744, 45671, 45670, -1, 45712, 45709, 45708, -1, 45712, 45711, 45709, -1, 45748, 45747, 45668, -1, 45683, 45735, 45734, -1, 45683, 45682, 45735, -1, 45688, 45687, 45730, -1, 45749, 45748, 45668, -1, 45749, 45668, 45666, -1, 45688, 45730, 45729, -1, 45743, 45671, 45744, -1, 45713, 45708, 45707, -1, 45713, 45712, 45708, -1, 45700, 45719, 45701, -1, 45700, 45720, 45719, -1, 45684, 45734, 45733, -1, 45743, 45672, 45671, -1, 45684, 45683, 45734, -1, 45699, 45721, 45720, -1, 45699, 45720, 45700, -1, 45714, 45707, 45706, -1, 45742, 45672, 45743, -1, 45714, 45713, 45707, -1, 45689, 45729, 45728, -1, 45742, 45673, 45672, -1, 45689, 45688, 45729, -1, 45742, 45674, 45673, -1, 45750, 45749, 45666, -1, 45698, 45721, 45699, -1, 45698, 45722, 45721, -1, 45715, 45706, 45705, -1, 45715, 45714, 45706, -1, 45741, 45674, 45742, -1, 45741, 45675, 45674, -1, 45685, 45684, 45733, -1, 45751, 45750, 45666, -1, 45697, 45722, 45698, -1, 45690, 45689, 45728, -1, 45690, 45728, 45727, -1, 45716, 45715, 45705, -1, 45696, 45723, 45722, -1, 45740, 45675, 45741, -1, 45704, 45716, 45705, -1, 45740, 45676, 45675, -1, 45696, 45722, 45697, -1, 45740, 45677, 45676, -1, 45717, 45716, 45704, -1, 45691, 45690, 45727, -1, 45691, 45727, 45726, -1, 45695, 45724, 45723, -1, 45695, 45723, 45696, -1, 45739, 45677, 45740, -1, 45692, 45691, 45726, -1, 45678, 45677, 45739, -1, 45686, 45733, 45732, -1, 45665, 45752, 45751, -1, 45686, 45732, 45731, -1, 45694, 45725, 45724, -1, 45665, 45751, 45666, -1, 45686, 45685, 45733, -1, 45694, 45724, 45695, -1, 45703, 45717, 45704, -1, 45693, 45726, 45725, -1, 45753, 45752, 45665, -1, 45693, 45692, 45726, -1, 45693, 45725, 45694, -1, 45718, 45717, 45703, -1, 45665, 45755, 45753, -1, 45738, 45678, 45739, -1, 45679, 45678, 45738, -1, 45756, 45757, 10174, -1, 10380, 45756, 10174, -1, 45758, 10148, 10174, -1, 45758, 10174, 45757, -1, 10372, 10148, 45758, -1, 45759, 10372, 45758, -1, 45759, 45756, 10380, -1, 10372, 45759, 10380, -1, 45756, 45758, 45757, -1, 45759, 45758, 45756, -1, 45760, 45761, 10453, -1, 10370, 45760, 10453, -1, 45762, 10319, 10453, -1, 45762, 10453, 45761, -1, 10381, 10319, 45762, -1, 45763, 10381, 45762, -1, 10381, 45763, 45764, -1, 10381, 45764, 10371, -1, 10371, 45764, 45765, -1, 10371, 45765, 10489, -1, 10489, 45765, 45760, -1, 10489, 45760, 10370, -1, 45760, 45765, 45761, -1, 45763, 45765, 45764, -1, 45763, 45762, 45765, -1, 45765, 45762, 45761, -1, 10143, 45766, 45767, -1, 10143, 45767, 10141, -1, 45768, 10368, 10141, -1, 45768, 10141, 45767, -1, 10369, 10368, 45768, -1, 45769, 10369, 45768, -1, 10369, 45769, 45770, -1, 10369, 45770, 10345, -1, 10345, 45770, 45771, -1, 10345, 45771, 10327, -1, 45772, 10234, 10327, -1, 45772, 10327, 45771, -1, 10234, 45772, 45773, -1, 10234, 45773, 10232, -1, 10232, 45773, 45774, -1, 10232, 45774, 10233, -1, 10233, 45774, 45775, -1, 10233, 45775, 10190, -1, 45776, 10191, 10190, -1, 45776, 10190, 45775, -1, 10191, 45776, 45777, -1, 10191, 45777, 10189, -1, 10189, 45777, 45766, -1, 10189, 45766, 10143, -1, 45770, 45772, 45771, -1, 45770, 45769, 45772, -1, 45769, 45773, 45772, -1, 45774, 45776, 45775, -1, 45773, 45776, 45774, -1, 45766, 45777, 45767, -1, 45776, 45768, 45777, -1, 45777, 45768, 45767, -1, 45769, 45768, 45773, -1, 45773, 45768, 45776, -1, 45778, 10362, 45779, -1, 10291, 10362, 45778, -1, 45780, 10267, 10291, -1, 45780, 10291, 45778, -1, 45781, 10267, 45780, -1, 10312, 10267, 45781, -1, 10168, 10312, 45781, -1, 10168, 45781, 45782, -1, 45783, 10140, 10168, -1, 45783, 10168, 45782, -1, 10329, 10140, 45783, -1, 10329, 45783, 45784, -1, 10344, 10329, 45784, -1, 10344, 45784, 45785, -1, 45785, 45786, 10359, -1, 10344, 45785, 10359, -1, 10357, 10359, 45786, -1, 10357, 45786, 45787, -1, 10358, 10357, 45787, -1, 10358, 45787, 45788, -1, 10358, 45788, 45789, -1, 10358, 45789, 10361, -1, 45779, 10361, 45789, -1, 10362, 10361, 45779, -1, 45788, 45787, 45789, -1, 45785, 45787, 45786, -1, 45787, 45779, 45789, -1, 45785, 45784, 45787, -1, 45787, 45784, 45779, -1, 45784, 45781, 45779, -1, 45781, 45778, 45779, -1, 45781, 45780, 45778, -1, 45781, 45783, 45782, -1, 45784, 45783, 45781, -1, 45662, 45663, 45661, -1, 45662, 45664, 45663, -1, 45790, 12764, 45791, -1, 12830, 12764, 45790, -1, 12831, 12830, 45790, -1, 12831, 45790, 45792, -1, 12438, 45792, 45793, -1, 12438, 12831, 45792, -1, 45794, 12263, 12438, -1, 45794, 12438, 45793, -1, 45795, 12263, 45794, -1, 12217, 12263, 45795, -1, 12860, 45795, 45796, -1, 12860, 12217, 45795, -1, 45797, 12860, 45796, -1, 12215, 12860, 45797, -1, 12826, 12215, 45797, -1, 45798, 12826, 45797, -1, 12413, 12826, 45798, -1, 12413, 45798, 45799, -1, 12414, 12413, 45799, -1, 45800, 12414, 45799, -1, 45801, 12414, 45800, -1, 12415, 12414, 45801, -1, 45802, 12415, 45801, -1, 12416, 12415, 45802, -1, 45803, 12416, 45802, -1, 12417, 12416, 45803, -1, 45804, 12417, 45803, -1, 12774, 12417, 45804, -1, 12423, 12774, 45804, -1, 12423, 45804, 45805, -1, 45806, 12423, 45805, -1, 12422, 12423, 45806, -1, 45807, 12422, 45806, -1, 12421, 12422, 45807, -1, 45808, 12421, 45807, -1, 12419, 12421, 45808, -1, 12420, 12419, 45808, -1, 45809, 12420, 45808, -1, 45810, 12420, 45809, -1, 12691, 12420, 45810, -1, 12691, 45810, 45811, -1, 12691, 45811, 12673, -1, 45812, 12673, 45811, -1, 12424, 12673, 45812, -1, 12424, 45812, 45813, -1, 12424, 45813, 12425, -1, 45814, 12425, 45813, -1, 12426, 12425, 45814, -1, 45815, 12426, 45814, -1, 12706, 12426, 45815, -1, 45816, 12706, 45815, -1, 12689, 12706, 45816, -1, 45817, 12689, 45816, -1, 12694, 12689, 45817, -1, 45818, 12694, 45817, -1, 12695, 12694, 45818, -1, 45819, 12695, 45818, -1, 12687, 12695, 45819, -1, 45820, 12687, 45819, -1, 12748, 12687, 45820, -1, 45821, 12748, 45820, -1, 12750, 12748, 45821, -1, 12751, 45821, 45822, -1, 12751, 12750, 45821, -1, 12757, 45822, 45823, -1, 12757, 12751, 45822, -1, 12772, 45823, 45824, -1, 12772, 12757, 45823, -1, 12782, 45824, 45825, -1, 12782, 12772, 45824, -1, 12749, 12782, 45825, -1, 12749, 45825, 45826, -1, 12749, 45826, 45791, -1, 12749, 45791, 12764, -1, 45808, 45812, 45809, -1, 45800, 45799, 45824, -1, 45800, 45824, 45823, -1, 45817, 45820, 45818, -1, 45818, 45820, 45819, -1, 45810, 45812, 45811, -1, 45816, 45815, 45817, -1, 45817, 45815, 45820, -1, 45810, 45809, 45812, -1, 45815, 45821, 45820, -1, 45815, 45814, 45821, -1, 45814, 45822, 45821, -1, 45814, 45813, 45822, -1, 45813, 45823, 45822, -1, 45813, 45800, 45823, -1, 45808, 45800, 45813, -1, 45805, 45804, 45806, -1, 45807, 45801, 45808, -1, 45808, 45801, 45800, -1, 45826, 45825, 45791, -1, 45806, 45803, 45807, -1, 45804, 45803, 45806, -1, 45807, 45803, 45801, -1, 45803, 45802, 45801, -1, 45825, 45790, 45791, -1, 45824, 45799, 45825, -1, 45825, 45799, 45790, -1, 45799, 45796, 45790, -1, 45799, 45798, 45796, -1, 45798, 45797, 45796, -1, 45796, 45795, 45790, -1, 45790, 45795, 45792, -1, 45795, 45794, 45792, -1, 45792, 45794, 45793, -1, 45813, 45812, 45808, -1, 12555, 45827, 45828, -1, 12555, 45828, 12531, -1, 12531, 45828, 45829, -1, 12531, 45829, 12556, -1, 12556, 45829, 45830, -1, 12556, 45830, 12532, -1, 12521, 12532, 45830, -1, 45831, 12521, 45830, -1, 12521, 45831, 45832, -1, 12521, 45832, 12486, -1, 12518, 12486, 45832, -1, 12518, 45832, 45833, -1, 12527, 45833, 45834, -1, 12527, 12518, 45833, -1, 45835, 12527, 45834, -1, 12536, 12527, 45835, -1, 45836, 12536, 45835, -1, 12441, 12536, 45836, -1, 45837, 12442, 12441, -1, 45837, 12441, 45836, -1, 12584, 12442, 45837, -1, 12584, 45837, 45838, -1, 12583, 45838, 45839, -1, 12583, 12584, 45838, -1, 12403, 12583, 45839, -1, 12403, 45839, 45840, -1, 12555, 45840, 45827, -1, 12555, 12403, 45840, -1, 45832, 45831, 45833, -1, 45831, 45830, 45833, -1, 45833, 45841, 45834, -1, 45830, 45841, 45833, -1, 45830, 45829, 45841, -1, 45834, 45842, 45835, -1, 45835, 45842, 45836, -1, 45841, 45842, 45834, -1, 45829, 45843, 45841, -1, 45827, 45840, 45828, -1, 45828, 45840, 45829, -1, 45829, 45840, 45843, -1, 45840, 45839, 45843, -1, 45839, 45844, 45843, -1, 45839, 45838, 45844, -1, 45844, 45837, 45842, -1, 45842, 45837, 45836, -1, 45838, 45837, 45844, -1, 45845, 45846, 45841, -1, 45843, 45845, 45841, -1, 45846, 45847, 45842, -1, 45841, 45846, 45842, -1, 45848, 45844, 45842, -1, 45848, 45842, 45847, -1, 45843, 45844, 45848, -1, 45845, 45843, 45848, -1, 12616, 45849, 45850, -1, 12616, 45850, 12595, -1, 12595, 45850, 45851, -1, 12595, 45851, 12617, -1, 12617, 45851, 45852, -1, 12617, 45852, 12618, -1, 12576, 12618, 45852, -1, 45853, 12576, 45852, -1, 12576, 45853, 45854, -1, 12576, 45854, 12401, -1, 12402, 12401, 45854, -1, 12402, 45854, 45855, -1, 45856, 12402, 45855, -1, 12405, 12402, 45856, -1, 12406, 12405, 45856, -1, 45857, 12406, 45856, -1, 12684, 12406, 45857, -1, 12684, 45857, 45858, -1, 12682, 45858, 45859, -1, 12682, 12684, 45858, -1, 45860, 12682, 45859, -1, 12685, 12682, 45860, -1, 45849, 12685, 45860, -1, 12616, 12685, 45849, -1, 45853, 45852, 45854, -1, 45852, 45855, 45854, -1, 45852, 45861, 45855, -1, 45855, 45862, 45856, -1, 45861, 45862, 45855, -1, 45852, 45851, 45861, -1, 45851, 45863, 45861, -1, 45849, 45860, 45850, -1, 45850, 45860, 45851, -1, 45851, 45860, 45863, -1, 45860, 45859, 45863, -1, 45862, 45864, 45856, -1, 45859, 45864, 45863, -1, 45859, 45858, 45864, -1, 45864, 45857, 45856, -1, 45858, 45857, 45864, -1, 45865, 45866, 45861, -1, 45863, 45865, 45861, -1, 45866, 45867, 45862, -1, 45861, 45866, 45862, -1, 45864, 45862, 45867, -1, 45868, 45864, 45867, -1, 45865, 45863, 45864, -1, 45865, 45864, 45868, -1, 45869, 12469, 45870, -1, 12541, 12469, 45869, -1, 45871, 12541, 45869, -1, 12542, 12541, 45871, -1, 45872, 12542, 45871, -1, 12549, 12542, 45872, -1, 45873, 12549, 45872, -1, 12569, 12549, 45873, -1, 12578, 45873, 45874, -1, 12578, 12569, 45873, -1, 45875, 12578, 45874, -1, 12586, 12578, 45875, -1, 45876, 12586, 45875, -1, 12588, 12586, 45876, -1, 45877, 12588, 45876, -1, 12602, 12588, 45877, -1, 45878, 12602, 45877, -1, 12450, 12602, 45878, -1, 45879, 12450, 45878, -1, 12449, 12450, 45879, -1, 45880, 12449, 45879, -1, 12447, 12449, 45880, -1, 12447, 45880, 45881, -1, 12447, 45881, 12448, -1, 12570, 12448, 45881, -1, 12570, 45881, 45882, -1, 12570, 45882, 45883, -1, 12570, 45883, 12581, -1, 45884, 12581, 45883, -1, 12391, 12581, 45884, -1, 45885, 12646, 12391, -1, 45885, 12391, 45884, -1, 12647, 12646, 45885, -1, 12647, 45885, 45886, -1, 45887, 12647, 45886, -1, 12655, 12647, 45887, -1, 45888, 12655, 45887, -1, 12451, 12655, 45888, -1, 12452, 12451, 45888, -1, 12452, 45888, 45889, -1, 12715, 12452, 45889, -1, 12715, 45889, 45890, -1, 12716, 45890, 45891, -1, 12716, 12715, 45890, -1, 12456, 45891, 45892, -1, 12456, 12716, 45891, -1, 12454, 45892, 45893, -1, 12454, 12456, 45892, -1, 45894, 12455, 12454, -1, 45894, 12454, 45893, -1, 45895, 12455, 45894, -1, 12457, 12455, 45895, -1, 45896, 12457, 45895, -1, 12458, 12457, 45896, -1, 45897, 12458, 45896, -1, 12471, 12458, 45897, -1, 12787, 12471, 45897, -1, 12787, 45897, 45898, -1, 12755, 45898, 45899, -1, 12755, 12787, 45898, -1, 12745, 12755, 45899, -1, 12745, 45899, 45900, -1, 12743, 45900, 45901, -1, 12743, 12745, 45900, -1, 45902, 12744, 12743, -1, 45902, 12743, 45901, -1, 45903, 12744, 45902, -1, 12258, 12744, 45903, -1, 12760, 12258, 45903, -1, 45904, 12760, 45903, -1, 12459, 12760, 45904, -1, 12459, 45904, 45905, -1, 12459, 45905, 45906, -1, 12459, 45906, 12460, -1, 12461, 12460, 45906, -1, 12461, 45906, 45907, -1, 12465, 45907, 45908, -1, 12465, 12461, 45907, -1, 12726, 45908, 45909, -1, 12726, 12465, 45908, -1, 12728, 45909, 45910, -1, 12728, 12726, 45909, -1, 45911, 12728, 45910, -1, 12732, 12728, 45911, -1, 12761, 45911, 45912, -1, 12761, 12732, 45911, -1, 12756, 45912, 45913, -1, 12756, 12761, 45912, -1, 45914, 12756, 45913, -1, 12752, 12756, 45914, -1, 45915, 12752, 45914, -1, 12747, 12752, 45915, -1, 45916, 12747, 45915, -1, 12468, 12747, 45916, -1, 12407, 12468, 45916, -1, 12407, 45916, 45917, -1, 12408, 45917, 45918, -1, 12408, 12407, 45917, -1, 12412, 45918, 45919, -1, 12412, 12408, 45918, -1, 12643, 45919, 45920, -1, 12643, 12412, 45919, -1, 45921, 12643, 45920, -1, 12638, 12643, 45921, -1, 45922, 12638, 45921, -1, 12633, 12638, 45922, -1, 45923, 12633, 45922, -1, 12634, 12633, 45923, -1, 12630, 12634, 45923, -1, 12630, 45923, 45924, -1, 12613, 45924, 45925, -1, 12613, 12630, 45924, -1, 12594, 45925, 45926, -1, 12594, 12613, 45925, -1, 12446, 45926, 45927, -1, 12446, 12594, 45926, -1, 12445, 45927, 45928, -1, 12445, 12446, 45927, -1, 12443, 45928, 45929, -1, 12443, 12445, 45928, -1, 12469, 45929, 45870, -1, 12469, 12443, 45929, -1, 45893, 45892, 45886, -1, 45919, 45908, 45920, -1, 45920, 45908, 45907, -1, 45892, 45891, 45886, -1, 45886, 45891, 45887, -1, 45918, 45909, 45919, -1, 45870, 45873, 45869, -1, 45919, 45909, 45908, -1, 45869, 45873, 45871, -1, 45871, 45873, 45872, -1, 45929, 45873, 45870, -1, 45891, 45890, 45887, -1, 45887, 45890, 45888, -1, 45929, 45874, 45873, -1, 45929, 45928, 45874, -1, 45890, 45889, 45888, -1, 45917, 45910, 45918, -1, 45918, 45910, 45909, -1, 45927, 45875, 45928, -1, 45928, 45875, 45874, -1, 45927, 45876, 45875, -1, 45927, 45926, 45876, -1, 45882, 45884, 45883, -1, 45881, 45884, 45882, -1, 45926, 45877, 45876, -1, 45926, 45878, 45877, -1, 45926, 45925, 45878, -1, 45916, 45911, 45917, -1, 45917, 45911, 45910, -1, 45925, 45879, 45878, -1, 45916, 45915, 45911, -1, 45894, 45900, 45895, -1, 45901, 45900, 45894, -1, 45925, 45924, 45879, -1, 45879, 45924, 45880, -1, 45924, 45923, 45880, -1, 45915, 45912, 45911, -1, 45915, 45914, 45912, -1, 45923, 45885, 45880, -1, 45905, 45902, 45901, -1, 45895, 45897, 45896, -1, 45899, 45898, 45900, -1, 45895, 45898, 45897, -1, 45900, 45898, 45895, -1, 45914, 45913, 45912, -1, 45905, 45904, 45902, -1, 45904, 45903, 45902, -1, 45906, 45905, 45894, -1, 45894, 45905, 45901, -1, 45922, 45906, 45923, -1, 45894, 45893, 45906, -1, 45881, 45880, 45884, -1, 45884, 45880, 45885, -1, 45923, 45893, 45885, -1, 45906, 45893, 45923, -1, 45885, 45893, 45886, -1, 45920, 45907, 45921, -1, 45921, 45907, 45922, -1, 45922, 45907, 45906, -1, 12234, 12236, 45930, -1, 12234, 45930, 45931, -1, 12321, 12234, 45931, -1, 12321, 45931, 45932, -1, 12397, 12321, 45932, -1, 12397, 45932, 45933, -1, 12395, 12397, 45933, -1, 12395, 45933, 45934, -1, 12394, 45934, 45935, -1, 12394, 12395, 45934, -1, 12392, 45935, 45936, -1, 12392, 12394, 45935, -1, 45937, 12393, 12392, -1, 45937, 12392, 45936, -1, 45938, 12393, 45937, -1, 12668, 12393, 45938, -1, 12668, 45938, 45939, -1, 12668, 45939, 12661, -1, 45940, 12661, 45939, -1, 12398, 12661, 45940, -1, 12398, 45940, 45941, -1, 12398, 45941, 12399, -1, 45942, 12399, 45941, -1, 12400, 12399, 45942, -1, 45943, 12400, 45942, -1, 12725, 12400, 45943, -1, 45944, 12725, 45943, -1, 12705, 12725, 45944, -1, 45945, 12705, 45944, -1, 12674, 12705, 45945, -1, 12680, 12674, 45945, -1, 12680, 45945, 45946, -1, 12669, 45946, 45947, -1, 12669, 12680, 45946, -1, 45948, 12669, 45947, -1, 12693, 12669, 45948, -1, 12733, 45948, 45949, -1, 12733, 12693, 45948, -1, 12759, 45949, 45950, -1, 12759, 12733, 45949, -1, 45951, 12759, 45950, -1, 12781, 12759, 45951, -1, 45952, 12781, 45951, -1, 12794, 12781, 45952, -1, 45953, 12794, 45952, -1, 12851, 12794, 45953, -1, 12851, 45953, 45954, -1, 12851, 45954, 12819, -1, 12793, 12819, 45954, -1, 12793, 45954, 45955, -1, 12777, 45955, 45956, -1, 12777, 12793, 45955, -1, 12777, 45956, 45957, -1, 12777, 45957, 12301, -1, 45958, 12301, 45957, -1, 12299, 12301, 45958, -1, 45959, 12302, 12299, -1, 45959, 12299, 45958, -1, 12302, 45959, 45960, -1, 12302, 45960, 12300, -1, 12433, 12300, 45960, -1, 12433, 45960, 45961, -1, 45962, 12432, 12433, -1, 45962, 12433, 45961, -1, 45963, 12432, 45962, -1, 12479, 12432, 45963, -1, 45964, 12479, 45963, -1, 12410, 12479, 45964, -1, 12411, 12410, 45964, -1, 45965, 12411, 45964, -1, 45966, 12409, 12411, -1, 45966, 12411, 45965, -1, 12370, 12409, 45966, -1, 12370, 45966, 45967, -1, 45968, 12375, 12370, -1, 45968, 12370, 45967, -1, 45969, 12375, 45968, -1, 12235, 12375, 45969, -1, 45930, 12236, 12235, -1, 45930, 12235, 45969, -1, 45932, 45931, 45935, -1, 45932, 45934, 45933, -1, 45932, 45935, 45934, -1, 45963, 45962, 45961, -1, 45963, 45961, 45960, -1, 45955, 45958, 45957, -1, 45938, 45937, 45940, -1, 45955, 45957, 45956, -1, 45938, 45940, 45939, -1, 45941, 45940, 45936, -1, 45936, 45940, 45937, -1, 45964, 45963, 45960, -1, 45954, 45958, 45955, -1, 45953, 45959, 45958, -1, 45953, 45958, 45954, -1, 45965, 45960, 45959, -1, 45965, 45964, 45960, -1, 45969, 45966, 45965, -1, 45969, 45953, 45952, -1, 45969, 45965, 45959, -1, 45969, 45959, 45953, -1, 45941, 45951, 45950, -1, 45968, 45967, 45966, -1, 45968, 45966, 45969, -1, 45930, 45952, 45951, -1, 45930, 45969, 45952, -1, 45930, 45951, 45941, -1, 45936, 45930, 45941, -1, 45931, 45930, 45936, -1, 45946, 45948, 45947, -1, 45942, 45950, 45949, -1, 45942, 45941, 45950, -1, 45943, 45942, 45949, -1, 45943, 45949, 45948, -1, 45944, 45943, 45948, -1, 45944, 45948, 45946, -1, 45935, 45931, 45936, -1, 45945, 45944, 45946, -1, 12338, 12342, 45970, -1, 45971, 12338, 45970, -1, 12314, 12338, 45971, -1, 12314, 45971, 45972, -1, 12470, 12314, 45972, -1, 12470, 45972, 45973, -1, 12470, 45973, 45974, -1, 12470, 45974, 12453, -1, 12739, 12453, 45974, -1, 12739, 45974, 45975, -1, 12342, 12739, 45975, -1, 12342, 45975, 45970, -1, 45974, 45976, 45975, -1, 45975, 45977, 45970, -1, 45976, 45977, 45975, -1, 45974, 45978, 45976, -1, 45974, 45973, 45978, -1, 45977, 45979, 45970, -1, 45978, 45972, 45979, -1, 45973, 45972, 45978, -1, 45979, 45971, 45970, -1, 45972, 45971, 45979, -1, 45978, 45980, 45981, -1, 45978, 45981, 45976, -1, 45976, 45981, 45982, -1, 45976, 45982, 45977, -1, 45979, 45977, 45982, -1, 45983, 45979, 45982, -1, 45978, 45979, 45983, -1, 45980, 45978, 45983, -1, 45984, 12429, 12430, -1, 45984, 12430, 45985, -1, 12696, 12429, 45984, -1, 12696, 45984, 45986, -1, 45987, 12696, 45986, -1, 12389, 12696, 45987, -1, 12389, 45987, 45988, -1, 12389, 45988, 12390, -1, 45989, 12390, 45988, -1, 12622, 12390, 45989, -1, 45985, 12622, 45989, -1, 12430, 12622, 45985, -1, 45988, 45990, 45989, -1, 45989, 45991, 45985, -1, 45990, 45991, 45989, -1, 45990, 45987, 45992, -1, 45988, 45987, 45990, -1, 45992, 45986, 45993, -1, 45987, 45986, 45992, -1, 45993, 45984, 45991, -1, 45991, 45984, 45985, -1, 45986, 45984, 45993, -1, 45994, 45995, 45990, -1, 45992, 45994, 45990, -1, 45990, 45995, 45996, -1, 45990, 45996, 45991, -1, 45997, 45993, 45991, -1, 45997, 45991, 45996, -1, 45994, 45992, 45993, -1, 45994, 45993, 45997, -1, 12688, 12678, 45998, -1, 12688, 45998, 45999, -1, 12683, 45999, 46000, -1, 12683, 12688, 45999, -1, 12713, 12683, 46000, -1, 12713, 46000, 46001, -1, 12746, 46001, 46002, -1, 12746, 12713, 46001, -1, 12766, 46002, 46003, -1, 12766, 12746, 46002, -1, 12788, 46003, 46004, -1, 12788, 12766, 46003, -1, 12806, 46004, 46005, -1, 12806, 12788, 46004, -1, 12813, 46005, 46006, -1, 12813, 12806, 46005, -1, 46007, 12813, 46006, -1, 12845, 12813, 46007, -1, 46008, 12845, 46007, -1, 12256, 12845, 46008, -1, 46009, 12256, 46008, -1, 12257, 12256, 46009, -1, 46010, 12257, 46009, -1, 12291, 12257, 46010, -1, 46011, 12291, 46010, -1, 12313, 12291, 46011, -1, 46012, 12313, 46011, -1, 12337, 12313, 46012, -1, 46013, 12337, 46012, -1, 12341, 12337, 46013, -1, 46014, 12341, 46013, -1, 12346, 12341, 46014, -1, 12347, 12346, 46014, -1, 12347, 46014, 46015, -1, 12339, 46015, 46016, -1, 12339, 12347, 46015, -1, 12322, 12339, 46016, -1, 12322, 46016, 46017, -1, 46018, 12322, 46017, -1, 12307, 12322, 46018, -1, 46019, 12307, 46018, -1, 12308, 12307, 46019, -1, 12306, 46019, 46020, -1, 12306, 12308, 46019, -1, 12309, 46020, 46021, -1, 12309, 12306, 46020, -1, 12269, 46021, 46022, -1, 12269, 12309, 46021, -1, 12250, 46022, 46023, -1, 12250, 12269, 46022, -1, 12251, 46023, 46024, -1, 12251, 12250, 46023, -1, 12249, 46024, 46025, -1, 12249, 12251, 46024, -1, 12252, 46025, 46026, -1, 12252, 12249, 46025, -1, 12255, 46026, 46027, -1, 12255, 12252, 46026, -1, 12261, 46027, 46028, -1, 12261, 12255, 46027, -1, 12265, 46028, 46029, -1, 12265, 12261, 46028, -1, 12232, 12265, 46029, -1, 12232, 46029, 46030, -1, 12233, 46030, 46031, -1, 12233, 12232, 46030, -1, 12231, 46031, 46032, -1, 12231, 12233, 46031, -1, 46033, 12231, 46032, -1, 12871, 12231, 46033, -1, 46034, 12871, 46033, -1, 12865, 12871, 46034, -1, 46035, 12865, 46034, -1, 12858, 12865, 46035, -1, 46036, 12858, 46035, -1, 12861, 12858, 46036, -1, 46037, 12861, 46036, -1, 12868, 12861, 46037, -1, 46038, 12868, 46037, -1, 12225, 12868, 46038, -1, 46039, 12225, 46038, -1, 12226, 12225, 46039, -1, 46040, 12226, 46039, -1, 12247, 12226, 46040, -1, 12229, 12247, 46040, -1, 12229, 46040, 46041, -1, 12227, 46041, 46042, -1, 12227, 12229, 46041, -1, 12869, 46042, 46043, -1, 12869, 12227, 46042, -1, 12862, 46043, 46044, -1, 12862, 12869, 46043, -1, 12859, 46044, 46045, -1, 12859, 12862, 46044, -1, 12857, 46045, 46046, -1, 12857, 12859, 46045, -1, 12866, 46046, 46047, -1, 12866, 12857, 46046, -1, 12678, 46047, 45998, -1, 12678, 12866, 46047, -1, 46040, 46009, 46008, -1, 46033, 46028, 46027, -1, 46030, 46028, 46033, -1, 46023, 46022, 46038, -1, 46038, 46022, 46039, -1, 45999, 46001, 46000, -1, 45998, 46047, 45999, -1, 46030, 46029, 46028, -1, 45999, 46047, 46001, -1, 46022, 46021, 46039, -1, 46039, 46021, 46040, -1, 46047, 46002, 46001, -1, 46047, 46046, 46002, -1, 46040, 46020, 46009, -1, 46046, 46003, 46002, -1, 46021, 46020, 46040, -1, 46046, 46045, 46003, -1, 46020, 46019, 46009, -1, 46045, 46004, 46003, -1, 46019, 46018, 46009, -1, 46045, 46044, 46004, -1, 46009, 46018, 46010, -1, 46044, 46005, 46004, -1, 46018, 46017, 46010, -1, 46044, 46043, 46005, -1, 46010, 46017, 46011, -1, 46043, 46006, 46005, -1, 46017, 46016, 46011, -1, 46043, 46042, 46006, -1, 46011, 46016, 46012, -1, 46042, 46007, 46006, -1, 46016, 46015, 46012, -1, 46012, 46015, 46013, -1, 46015, 46014, 46013, -1, 46042, 46041, 46007, -1, 46041, 46008, 46007, -1, 46032, 46031, 46033, -1, 46031, 46030, 46033, -1, 46035, 46025, 46036, -1, 46025, 46024, 46036, -1, 46036, 46024, 46037, -1, 46035, 46026, 46025, -1, 46034, 46026, 46035, -1, 46041, 46040, 46008, -1, 46024, 46023, 46037, -1, 46037, 46023, 46038, -1, 46034, 46027, 46026, -1, 46033, 46027, 46034, -1, 12435, 12786, 46048, -1, 46049, 12435, 46048, -1, 46050, 12435, 46049, -1, 12796, 12435, 46050, -1, 12778, 12796, 46050, -1, 46051, 12778, 46050, -1, 12376, 12778, 46051, -1, 12376, 46051, 46052, -1, 12376, 46052, 46053, -1, 12376, 46053, 12377, -1, 12502, 12377, 46053, -1, 12502, 46053, 46054, -1, 12502, 46054, 46055, -1, 12502, 46055, 12519, -1, 12385, 12519, 46055, -1, 12385, 46055, 46056, -1, 46057, 12386, 12385, -1, 46057, 12385, 46056, -1, 12386, 46057, 46058, -1, 12386, 46058, 12388, -1, 12388, 46058, 46059, -1, 12388, 46059, 12387, -1, 46060, 12387, 46059, -1, 12560, 12387, 46060, -1, 12560, 46060, 46061, -1, 12560, 46061, 12582, -1, 46062, 12582, 46061, -1, 12645, 12582, 46062, -1, 12762, 12645, 46062, -1, 46063, 12762, 46062, -1, 12762, 46063, 46064, -1, 12762, 46064, 12763, -1, 12763, 46064, 46065, -1, 12763, 46065, 12644, -1, 46066, 12644, 46065, -1, 12603, 12644, 46066, -1, 12603, 46066, 46067, -1, 12603, 46067, 12436, -1, 12786, 12436, 46067, -1, 12786, 46067, 46048, -1, 46054, 46056, 46055, -1, 46053, 46056, 46054, -1, 46060, 46062, 46061, -1, 46059, 46062, 46060, -1, 46066, 46048, 46067, -1, 46065, 46048, 46066, -1, 46053, 46057, 46056, -1, 46053, 46052, 46057, -1, 46057, 46051, 46058, -1, 46052, 46051, 46057, -1, 46058, 46063, 46059, -1, 46059, 46063, 46062, -1, 46051, 46063, 46058, -1, 46065, 46064, 46048, -1, 46063, 46050, 46064, -1, 46051, 46050, 46063, -1, 46064, 46049, 46048, -1, 46050, 46049, 46064, -1, 46068, 12262, 46069, -1, 12473, 12262, 46068, -1, 46070, 12473, 46068, -1, 12474, 12473, 46070, -1, 46071, 12474, 46070, -1, 12384, 12474, 46071, -1, 46072, 12384, 46071, -1, 12344, 12384, 46072, -1, 46073, 12344, 46072, -1, 12305, 12344, 46073, -1, 46074, 12305, 46073, -1, 12268, 12305, 46074, -1, 46075, 12268, 46074, -1, 12844, 12268, 46075, -1, 46076, 12844, 46075, -1, 12821, 12844, 46076, -1, 46077, 12821, 46076, -1, 12798, 12821, 46077, -1, 12795, 12798, 46077, -1, 12795, 46077, 46078, -1, 12418, 46078, 46079, -1, 12418, 12795, 46078, -1, 46080, 12418, 46079, -1, 12810, 12418, 46080, -1, 46081, 12810, 46080, -1, 12829, 12810, 46081, -1, 46082, 12829, 46081, -1, 12218, 12829, 46082, -1, 46083, 12218, 46082, -1, 12216, 12218, 46083, -1, 46084, 12216, 46083, -1, 12238, 12216, 46084, -1, 46069, 12238, 46084, -1, 12262, 12238, 46069, -1, 46078, 46080, 46079, -1, 46077, 46076, 46078, -1, 46078, 46076, 46080, -1, 46076, 46081, 46080, -1, 46076, 46075, 46081, -1, 46075, 46082, 46081, -1, 46075, 46074, 46082, -1, 46074, 46083, 46082, -1, 46074, 46073, 46083, -1, 46073, 46084, 46083, -1, 46073, 46072, 46084, -1, 46084, 46068, 46069, -1, 46072, 46068, 46084, -1, 46072, 46070, 46068, -1, 46072, 46071, 46070, -1, 46085, 12266, 46086, -1, 12241, 12266, 46085, -1, 46087, 12241, 46085, -1, 12872, 12241, 46087, -1, 12850, 46087, 46088, -1, 12850, 12872, 46087, -1, 12834, 46088, 46089, -1, 12834, 12850, 46088, -1, 12374, 46089, 46090, -1, 12374, 12834, 46089, -1, 12371, 46090, 46091, -1, 12371, 12374, 46090, -1, 46092, 12372, 12371, -1, 46092, 12371, 46091, -1, 46093, 12372, 46092, -1, 12373, 12372, 46093, -1, 46094, 12373, 46093, -1, 12833, 12373, 46094, -1, 12849, 12833, 46094, -1, 12849, 46094, 46095, -1, 12239, 46095, 46096, -1, 12239, 12849, 46095, -1, 12248, 12239, 46096, -1, 12248, 46096, 46097, -1, 12292, 46097, 46098, -1, 12292, 12248, 46097, -1, 12853, 46098, 46099, -1, 12853, 12292, 46098, -1, 12789, 12853, 46099, -1, 12789, 46099, 46100, -1, 12807, 12789, 46100, -1, 12807, 46100, 46101, -1, 12792, 12807, 46101, -1, 12792, 46101, 46102, -1, 12741, 46102, 46103, -1, 12741, 12792, 46102, -1, 12734, 46103, 46104, -1, 12734, 12741, 46103, -1, 12735, 46104, 46105, -1, 12735, 12734, 46104, -1, 12720, 46105, 46106, -1, 12720, 12735, 46105, -1, 12724, 12720, 46106, -1, 12724, 46106, 46107, -1, 12727, 46107, 46108, -1, 12727, 12724, 46107, -1, 12731, 12727, 46108, -1, 12731, 46108, 46109, -1, 12738, 46109, 46110, -1, 12738, 12731, 46109, -1, 12753, 46110, 46111, -1, 12753, 12738, 46110, -1, 12754, 46111, 46112, -1, 12754, 12753, 46111, -1, 12768, 46112, 46113, -1, 12768, 12754, 46112, -1, 12797, 46113, 46114, -1, 12797, 12768, 46113, -1, 12820, 46114, 46115, -1, 12820, 12797, 46114, -1, 12843, 46115, 46116, -1, 12843, 12820, 46115, -1, 12266, 46116, 46086, -1, 12266, 12843, 46116, -1, 46106, 46105, 46107, -1, 46107, 46109, 46108, -1, 46105, 46104, 46107, -1, 46107, 46110, 46109, -1, 46110, 46091, 46111, -1, 46103, 46091, 46104, -1, 46104, 46091, 46107, -1, 46107, 46091, 46110, -1, 46091, 46112, 46111, -1, 46103, 46102, 46091, -1, 46112, 46090, 46113, -1, 46091, 46090, 46112, -1, 46090, 46114, 46113, -1, 46101, 46092, 46102, -1, 46090, 46089, 46114, -1, 46100, 46099, 46101, -1, 46089, 46115, 46114, -1, 46101, 46098, 46092, -1, 46099, 46098, 46101, -1, 46093, 46095, 46094, -1, 46115, 46088, 46116, -1, 46089, 46088, 46115, -1, 46092, 46097, 46093, -1, 46098, 46097, 46092, -1, 46093, 46097, 46095, -1, 46097, 46096, 46095, -1, 46116, 46087, 46086, -1, 46088, 46087, 46116, -1, 46087, 46085, 46086, -1, 46092, 46091, 46102, -1, 46117, 12472, 46118, -1, 12437, 12472, 46117, -1, 12635, 12437, 46117, -1, 12635, 46117, 46119, -1, 12605, 46119, 46120, -1, 12605, 12635, 46119, -1, 12604, 46120, 46121, -1, 12604, 12605, 46120, -1, 46122, 12604, 46121, -1, 12606, 12604, 46122, -1, 46123, 12606, 46122, -1, 12607, 12606, 46123, -1, 46124, 12607, 46123, -1, 12523, 12607, 46124, -1, 46125, 12523, 46124, -1, 12522, 12523, 46125, -1, 46126, 12522, 46125, -1, 12359, 12522, 46126, -1, 12317, 12359, 46126, -1, 12317, 46126, 46127, -1, 12288, 46127, 46128, -1, 12288, 12317, 46127, -1, 12289, 46128, 46129, -1, 12289, 12288, 46128, -1, 12246, 46129, 46130, -1, 12246, 12289, 46129, -1, 12240, 12246, 46130, -1, 12240, 46130, 46131, -1, 12253, 46131, 46132, -1, 12253, 12240, 46131, -1, 12260, 46132, 46133, -1, 12260, 12253, 46132, -1, 12267, 46133, 46134, -1, 12267, 12260, 46133, -1, 12303, 46134, 46135, -1, 12303, 12267, 46134, -1, 12343, 46135, 46136, -1, 12343, 12303, 46135, -1, 12383, 46136, 46137, -1, 12383, 12343, 46136, -1, 12472, 46137, 46118, -1, 12472, 12383, 46137, -1, 46130, 46129, 46131, -1, 46129, 46128, 46131, -1, 46131, 46124, 46132, -1, 46132, 46123, 46133, -1, 46124, 46123, 46132, -1, 46127, 46125, 46128, -1, 46128, 46125, 46131, -1, 46131, 46125, 46124, -1, 46133, 46122, 46134, -1, 46123, 46122, 46133, -1, 46127, 46126, 46125, -1, 46134, 46121, 46135, -1, 46122, 46121, 46134, -1, 46135, 46120, 46136, -1, 46136, 46120, 46137, -1, 46121, 46120, 46135, -1, 46137, 46119, 46118, -1, 46120, 46119, 46137, -1, 46119, 46117, 46118, -1, 46138, 12579, 12369, -1, 46138, 12369, 46139, -1, 12361, 12579, 46138, -1, 12361, 46138, 46140, -1, 12316, 12361, 46140, -1, 46141, 12316, 46140, -1, 12230, 12316, 46141, -1, 12230, 46141, 46142, -1, 12228, 46142, 46143, -1, 12228, 12230, 46142, -1, 12224, 46143, 46144, -1, 12224, 12228, 46143, -1, 12874, 46144, 46145, -1, 12874, 12224, 46144, -1, 12875, 46145, 46146, -1, 12875, 12874, 46145, -1, 12222, 46146, 46147, -1, 12222, 12875, 46146, -1, 12223, 46147, 46148, -1, 12223, 12222, 46147, -1, 12287, 46148, 46149, -1, 12287, 12223, 46148, -1, 12273, 46149, 46150, -1, 12273, 12287, 46149, -1, 12271, 46150, 46151, -1, 12271, 12273, 46150, -1, 12277, 46151, 46152, -1, 12277, 12271, 46151, -1, 12272, 46152, 46153, -1, 12272, 12277, 46152, -1, 12286, 46153, 46154, -1, 12286, 12272, 46153, -1, 12298, 46154, 46155, -1, 12298, 12286, 46154, -1, 12310, 12298, 46155, -1, 12310, 46155, 46156, -1, 12315, 12310, 46156, -1, 12315, 46156, 46157, -1, 12340, 12315, 46157, -1, 12340, 46157, 46158, -1, 12362, 12340, 46158, -1, 12362, 46158, 46159, -1, 12537, 12362, 46159, -1, 12537, 46159, 46160, -1, 12520, 46160, 46161, -1, 12520, 12537, 46160, -1, 46162, 12520, 46161, -1, 12488, 12520, 46162, -1, 46163, 12488, 46162, -1, 12487, 12488, 46163, -1, 46164, 12487, 46163, -1, 12489, 46164, 46165, -1, 12489, 12487, 46164, -1, 12490, 12489, 46165, -1, 46166, 12490, 46165, -1, 12491, 12490, 46166, -1, 46167, 12491, 46166, -1, 12492, 12491, 46167, -1, 46168, 12492, 46167, -1, 12220, 12492, 46168, -1, 46168, 46169, 12854, -1, 12220, 46168, 12854, -1, 12818, 12854, 46169, -1, 12818, 46169, 46170, -1, 12816, 46170, 46171, -1, 12816, 12818, 46170, -1, 12811, 46171, 46172, -1, 12811, 12816, 46171, -1, 12808, 46172, 46173, -1, 12808, 12811, 46172, -1, 12812, 46173, 46174, -1, 12812, 12808, 46173, -1, 12817, 46174, 46175, -1, 12817, 12812, 46174, -1, 12840, 46175, 46176, -1, 12840, 12817, 46175, -1, 12243, 46176, 46177, -1, 12243, 12840, 46176, -1, 46177, 46178, 12364, -1, 12243, 46177, 12364, -1, 12364, 46178, 46179, -1, 12364, 46179, 12365, -1, 12366, 12365, 46179, -1, 12366, 46179, 46180, -1, 12244, 46180, 46181, -1, 12244, 12366, 46180, -1, 12245, 46181, 46182, -1, 12245, 12244, 46181, -1, 12864, 46182, 46183, -1, 12864, 12245, 46182, -1, 12842, 46183, 46184, -1, 12842, 12864, 46183, -1, 12814, 46184, 46185, -1, 12814, 12842, 46184, -1, 12809, 46185, 46186, -1, 12809, 12814, 46185, -1, 12723, 46186, 46187, -1, 12723, 12809, 46186, -1, 12717, 12723, 46187, -1, 12717, 46187, 46188, -1, 46189, 12717, 46188, -1, 12718, 12717, 46189, -1, 46190, 12718, 46189, -1, 12742, 12718, 46190, -1, 46191, 12742, 46190, -1, 12758, 12742, 46191, -1, 46192, 12758, 46191, -1, 12769, 12758, 46192, -1, 46193, 12769, 46192, -1, 12785, 12769, 46193, -1, 46194, 12785, 46193, -1, 12799, 12785, 46194, -1, 46195, 12799, 46194, -1, 12319, 12799, 46195, -1, 46196, 12319, 46195, -1, 12320, 12319, 46196, -1, 46197, 12320, 46196, -1, 12368, 12320, 46197, -1, 12369, 12368, 46197, -1, 12369, 46197, 46139, -1, 46169, 46149, 46148, -1, 46168, 46149, 46169, -1, 46168, 46150, 46149, -1, 46188, 46190, 46189, -1, 46168, 46151, 46150, -1, 46187, 46186, 46188, -1, 46188, 46186, 46190, -1, 46186, 46191, 46190, -1, 46168, 46152, 46151, -1, 46186, 46185, 46191, -1, 46185, 46192, 46191, -1, 46165, 46153, 46166, -1, 46166, 46153, 46167, -1, 46167, 46153, 46168, -1, 46185, 46184, 46192, -1, 46168, 46153, 46152, -1, 46192, 46183, 46193, -1, 46184, 46183, 46192, -1, 46165, 46164, 46153, -1, 46153, 46164, 46154, -1, 46164, 46163, 46154, -1, 46154, 46163, 46155, -1, 46155, 46162, 46156, -1, 46163, 46162, 46155, -1, 46156, 46162, 46157, -1, 46157, 46162, 46158, -1, 46195, 46180, 46196, -1, 46181, 46180, 46195, -1, 46193, 46182, 46194, -1, 46183, 46182, 46193, -1, 46158, 46160, 46159, -1, 46162, 46160, 46158, -1, 46180, 46197, 46196, -1, 46170, 46145, 46171, -1, 46171, 46145, 46172, -1, 46162, 46161, 46160, -1, 46169, 46146, 46170, -1, 46197, 46179, 46139, -1, 46170, 46146, 46145, -1, 46145, 46144, 46172, -1, 46172, 46144, 46173, -1, 46173, 46144, 46174, -1, 46174, 46144, 46175, -1, 46169, 46147, 46146, -1, 46179, 46178, 46139, -1, 46175, 46143, 46176, -1, 46144, 46143, 46175, -1, 46178, 46138, 46139, -1, 46140, 46138, 46178, -1, 46180, 46179, 46197, -1, 46178, 46177, 46141, -1, 46178, 46141, 46140, -1, 46169, 46148, 46147, -1, 46176, 46142, 46177, -1, 46143, 46142, 46176, -1, 46182, 46181, 46194, -1, 46194, 46181, 46195, -1, 46142, 46141, 46177, -1, 46198, 12505, 46199, -1, 12548, 12505, 46198, -1, 46200, 12548, 46198, -1, 12515, 12548, 46200, -1, 46201, 12515, 46200, -1, 12484, 12515, 46201, -1, 46202, 12484, 46201, -1, 12467, 12484, 46202, -1, 46203, 12467, 46202, -1, 12327, 12467, 46203, -1, 46204, 12327, 46203, -1, 12311, 12327, 46204, -1, 46205, 12311, 46204, -1, 12293, 12311, 46205, -1, 12358, 12293, 46205, -1, 12358, 46205, 46206, -1, 12440, 46206, 46207, -1, 12440, 12358, 46206, -1, 12501, 46207, 46208, -1, 12501, 12440, 46207, -1, 12505, 46208, 46199, -1, 12505, 12501, 46208, -1, 46204, 46206, 46205, -1, 46206, 46202, 46207, -1, 46203, 46202, 46204, -1, 46204, 46202, 46206, -1, 46207, 46201, 46208, -1, 46202, 46201, 46207, -1, 46201, 46200, 46208, -1, 46200, 46199, 46208, -1, 46200, 46198, 46199, -1, 12379, 12378, 46209, -1, 12379, 46209, 46210, -1, 46211, 12379, 46210, -1, 12380, 12379, 46211, -1, 46212, 12380, 46211, -1, 12381, 12380, 46212, -1, 12641, 12381, 46212, -1, 12641, 46212, 46213, -1, 12626, 46213, 46214, -1, 12626, 12641, 46213, -1, 12624, 46214, 46215, -1, 12624, 12626, 46214, -1, 12628, 46215, 46216, -1, 12628, 12624, 46215, -1, 12591, 46216, 46217, -1, 12591, 12628, 46216, -1, 12589, 46217, 46218, -1, 12589, 12591, 46217, -1, 12592, 46218, 46219, -1, 12592, 12589, 46218, -1, 12593, 46219, 46220, -1, 12593, 12592, 46219, -1, 12608, 46220, 46221, -1, 12608, 12593, 46220, -1, 12611, 46221, 46222, -1, 12611, 12608, 46221, -1, 12612, 46222, 46223, -1, 12612, 12611, 46222, -1, 12640, 46223, 46224, -1, 12640, 12612, 46223, -1, 12662, 46224, 46225, -1, 12662, 12640, 46224, -1, 12619, 12662, 46225, -1, 12619, 46225, 46226, -1, 12597, 46226, 46227, -1, 12597, 12619, 46226, -1, 12598, 46227, 46228, -1, 12598, 12597, 46227, -1, 12580, 46228, 46229, -1, 12580, 12598, 46228, -1, 46230, 12580, 46229, -1, 12565, 12580, 46230, -1, 46231, 12565, 46230, -1, 12551, 12565, 46231, -1, 46232, 12551, 46231, -1, 12540, 12551, 46232, -1, 46233, 12540, 46232, -1, 12533, 12540, 46233, -1, 12528, 46233, 46234, -1, 12528, 12533, 46233, -1, 12525, 46234, 46235, -1, 12525, 12528, 46234, -1, 12530, 46235, 46236, -1, 12530, 12525, 46235, -1, 12538, 46236, 46237, -1, 12538, 12530, 46236, -1, 12526, 12538, 46237, -1, 12526, 46237, 46238, -1, 12524, 46238, 46239, -1, 12524, 12526, 46238, -1, 12529, 46239, 46240, -1, 12529, 12524, 46239, -1, 12534, 46240, 46241, -1, 12534, 12529, 46240, -1, 12539, 46241, 46242, -1, 12539, 12534, 46241, -1, 12553, 46242, 46243, -1, 12553, 12539, 46242, -1, 12554, 46243, 46244, -1, 12554, 12553, 46243, -1, 12852, 46244, 46245, -1, 12852, 12554, 46244, -1, 46246, 12852, 46245, -1, 12863, 12852, 46246, -1, 46247, 12863, 46246, -1, 12867, 12863, 46247, -1, 46248, 12867, 46247, -1, 12295, 12867, 46248, -1, 46249, 12295, 46248, -1, 12294, 12295, 46249, -1, 46250, 12294, 46249, -1, 12312, 12294, 46250, -1, 46251, 12312, 46250, -1, 12326, 12312, 46251, -1, 46252, 12326, 46251, -1, 12345, 12326, 46252, -1, 46253, 12345, 46252, -1, 12477, 12345, 46253, -1, 12483, 46253, 46254, -1, 12483, 12477, 46253, -1, 12498, 46254, 46255, -1, 12498, 12483, 46254, -1, 12514, 46255, 46256, -1, 12514, 12498, 46255, -1, 12547, 46256, 46257, -1, 12547, 12514, 46256, -1, 12568, 46257, 46258, -1, 12568, 12547, 46257, -1, 12378, 46258, 46209, -1, 12378, 12568, 46258, -1, 46218, 46217, 46237, -1, 46233, 46221, 46220, -1, 46245, 46244, 46246, -1, 46232, 46221, 46233, -1, 46246, 46249, 46247, -1, 46247, 46249, 46248, -1, 46237, 46216, 46257, -1, 46244, 46249, 46246, -1, 46217, 46216, 46237, -1, 46257, 46215, 46258, -1, 46216, 46215, 46257, -1, 46243, 46250, 46244, -1, 46244, 46250, 46249, -1, 46232, 46222, 46221, -1, 46231, 46222, 46232, -1, 46242, 46251, 46243, -1, 46215, 46214, 46258, -1, 46243, 46251, 46250, -1, 46242, 46241, 46251, -1, 46241, 46252, 46251, -1, 46241, 46240, 46252, -1, 46229, 46228, 46230, -1, 46230, 46223, 46231, -1, 46231, 46223, 46222, -1, 46240, 46253, 46252, -1, 46228, 46227, 46230, -1, 46240, 46239, 46253, -1, 46214, 46210, 46258, -1, 46258, 46210, 46209, -1, 46239, 46254, 46253, -1, 46214, 46213, 46210, -1, 46254, 46238, 46255, -1, 46213, 46211, 46210, -1, 46239, 46238, 46254, -1, 46230, 46224, 46223, -1, 46227, 46224, 46230, -1, 46226, 46224, 46227, -1, 46213, 46212, 46211, -1, 46226, 46225, 46224, -1, 46255, 46237, 46256, -1, 46238, 46237, 46255, -1, 46237, 46257, 46256, -1, 46234, 46219, 46235, -1, 46219, 46218, 46235, -1, 46235, 46218, 46236, -1, 46236, 46218, 46237, -1, 46233, 46220, 46234, -1, 46234, 46220, 46219, -1, 12692, 12382, 46259, -1, 12692, 46259, 46260, -1, 12671, 46260, 46261, -1, 12671, 12692, 46260, -1, 12670, 12671, 46261, -1, 12670, 46261, 46262, -1, 12672, 46262, 46263, -1, 12672, 12670, 46262, -1, 12639, 46263, 46264, -1, 12639, 12672, 46263, -1, 12609, 46264, 46265, -1, 12609, 12639, 46264, -1, 46266, 12609, 46265, -1, 12590, 12609, 46266, -1, 12625, 12590, 46266, -1, 12625, 46266, 46267, -1, 12642, 46267, 46268, -1, 12642, 12625, 46267, -1, 12382, 46268, 46259, -1, 12382, 12642, 46268, -1, 46265, 46267, 46266, -1, 46265, 46264, 46267, -1, 46264, 46268, 46267, -1, 46264, 46263, 46268, -1, 46268, 46260, 46259, -1, 46262, 46260, 46263, -1, 46263, 46260, 46268, -1, 46262, 46261, 46260, -1, 45845, 45848, 45846, -1, 45846, 45848, 45847, -1, 45866, 45865, 45867, -1, 45865, 45868, 45867, -1, 45981, 45980, 45982, -1, 45980, 45983, 45982, -1, 45994, 45997, 45995, -1, 45995, 45997, 45996, -1 - ] - } - } - ] - } - DEF bumpers Shape { - appearance Appearance { - material Material { - diffuseColor 0 0 0 - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.52930337 -0.012879658 0.16683221, -0.52997237 -0.012325231 0.16981676, -0.52848262 -0.012879957 0.16927445, -0.53274298 -0.011431504 0.16575393, -0.53331167 -0.010244135 0.16806874, -0.53217691 -0.011431638 0.16771874, -0.53389001 -0.010243986 0.16606128, -0.52344424 -0.012325276 0.16868052, -0.52373272 -0.012880091 0.17202821, -0.52229601 -0.012325276 0.17135835, -0.52491993 -0.012879897 0.16925988, -0.53487539 -0.0055680163 0.1685513, -0.53528887 -0.0072367378 0.1664362, -0.53598821 -0.0055677779 0.16439784, -0.53580487 -0.0072366931 0.16435611, -0.53526413 -0.0088218339 0.16423249, -0.53475326 -0.0088218935 0.16629267, -0.52950269 -0.01232535 0.17105854, -0.52802712 -0.012879971 0.17047927, -0.53130859 -0.011431683 0.17030299, -0.53081805 -0.012325097 0.16729963, -0.53416556 -0.0088221766 0.16833231, -0.52647358 -0.013067979 0.16986939, -0.52524513 -0.013068248 0.17273352, -0.53082639 -0.011431802 0.17157808, -0.53242451 -0.010244254 0.17070943, -0.53469557 -0.0072369613 0.16849574, -0.52675778 -0.01288015 0.17343885, -0.53193194 -0.010244403 0.17201206, -0.53326422 -0.0088222362 0.1710149, -0.52819449 -0.012325469 0.17410865, -0.53276366 -0.0088223703 0.17233855, -0.518448 -0.0055679418 0.16956434, -0.51689881 -0.0072370209 0.17294684, -0.51673591 -0.00556821 0.17285281, -0.53378546 -0.0072369017 0.17120469, -0.53345513 -0.0055682398 0.1726101, -0.52948326 -0.011431981 0.17470995, -0.53328001 -0.0072371103 0.17254114, -0.5305596 -0.010244478 0.17521161, -0.53136939 -0.0088223852 0.17558956, -0.53187215 -0.0072371848 0.17582396, -0.53173554 -0.0055684485 0.17655149, -0.53066081 -0.009196315 0.17662051, -0.5305596 -0.0080455877 0.17795911, -0.52991337 -0.0095586516 0.1776225, -0.52830929 -0.010244641 0.17953461, -0.52952123 -0.0091963746 0.1788097, -0.52908307 -0.0088226236 0.17998135, -0.53124583 -0.0068247207 0.17730787, -0.53078055 -0.0064082034 0.17834336, -0.52972639 -0.0055686124 0.18035293, -0.52956343 -0.007237602 0.18025905, -0.53024876 -0.0068248399 0.17920867, -0.52978903 -0.010565985 0.17619064, -0.52261788 -0.0072358884 0.15160283, -0.52249843 -0.0072360374 0.15479314, -0.52242982 -0.005567003 0.15160298, -0.52226818 -0.0055671819 0.15530711, -0.52317256 -0.0088211037 0.15160283, -0.52305174 -0.0088213421 0.15483427, -0.52898437 -0.010871757 0.17713895, -0.52728075 -0.011432204 0.17894065, -0.52866906 -0.010566074 0.17834204, -0.53104359 -0.0080455281 0.1770077, -0.52406603 -0.010243166 0.1516026, -0.52394265 -0.01024342 0.15490112, -0.52997261 -0.0080456771 0.17905739, -0.5221411 -0.0072362311 0.15796509, -0.52178413 -0.0055672564 0.15898302, -0.52866584 -0.011685003 0.17563662, -0.52525359 -0.011430804 0.1516026, -0.52512699 -0.011430923 0.15498966, -0.52781969 -0.011918891 0.17653254, -0.5260492 -0.012325693 0.17822972, -0.52757114 -0.011685181 0.17773953, -0.52734762 -0.012497369 0.17498651, -0.52196944 -0.0072363503 0.15901557, -0.5226897 -0.0088213421 0.1580478, -0.52647752 -0.012647409 0.17583382, -0.52667576 -0.012324277 0.1516026, -0.52654499 -0.012324486 0.15509588, -0.52467638 -0.012880359 0.1774371, -0.52628249 -0.012497533 0.17703247, -0.52590019 -0.012962211 0.17427269, -0.52251559 -0.0088215955 0.1591118, -0.52323109 -0.013068486 0.17660254, -0.52486759 -0.01296239 0.1762563, -0.52357322 -0.01024342 0.15818083, -0.52482241 -0.013065267 0.17313546, -0.52826089 -0.012878928 0.15160277, -0.52812582 -0.012879182 0.15521446, -0.52382368 -0.013035435 0.17404822, -0.52154762 -0.007236395 0.16110194, -0.52098167 -0.0055674799 0.16260278, -0.52384037 -0.013065252 0.17507327, -0.52418679 -0.013063017 0.17546582, -0.5217858 -0.012880255 0.1757682, -0.52331787 -0.013065357 0.17602542, -0.52339566 -0.010243554 0.15926695, -0.52304882 -0.012794051 0.17267197, -0.52474743 -0.011431012 0.15835783, -0.52992982 -0.013067055 0.1516026, -0.52978998 -0.013067294 0.15533885, -0.52208871 -0.012794066 0.17453262, -0.52197284 -0.012247432 0.17167482, -0.52100724 -0.011431593 0.17075726, -0.52208835 -0.00882167 0.16122517, -0.52202076 -0.012460936 0.17261389, -0.52152497 -0.012247492 0.17258728, -0.52073485 -0.012004126 0.17315972, -0.52456516 -0.011431206 0.159473, -0.52615362 -0.012324605 0.15856963, -0.5205701 -0.012247581 0.17438152, -0.52041298 -0.012325499 0.17497554, -0.51918143 -0.011431906 0.17426443, -0.52028567 -0.011214469 0.17165625, -0.53145427 -0.012879137 0.15546378, -0.51937252 -0.011214603 0.17339772, -0.53159863 -0.012879033 0.1516026, -0.51815301 -0.010244194 0.17367092, -0.51960224 -0.010110412 0.17070577, -0.51993072 -0.010244165 0.17025563, -0.51912117 -0.0088220574 0.16987801, -0.52116334 -0.0072364546 0.16265142, -0.52295959 -0.010243643 0.16142404, -0.5188536 -0.0096990056 0.1715565, -0.51737911 -0.0088222511 0.173224, -0.51861835 -0.0072367825 0.16964379, -0.52596551 -0.01232462 0.15971994, -0.51873118 -0.010110546 0.17241824, -0.51892489 -0.010501582 0.17273042, -0.51826781 -0.010110576 0.17325941, -0.52772123 -0.012879226 0.15880594, -0.53303498 -0.012324516 0.15558246, -0.53318399 -0.012324307 0.1516026, -0.52169913 -0.0088217594 0.16279495, -0.52072132 -0.0072366484 0.1641852, -0.51986682 -0.0055676438 0.16613874, -0.52411729 -0.011431206 0.16168791, -0.52752668 -0.012879346 0.15999523, -0.52937144 -0.013067428 0.15905461, -0.53460604 -0.011430729 0.1516026, -0.53445327 -0.011430997 0.15568846, -0.52256221 -0.010243673 0.16302589, -0.5212515 -0.0088217743 0.16434899, -0.52550381 -0.012324754 0.16200462, -0.52917022 -0.013067532 0.16028503, -0.53102165 -0.01287939 0.15930343, -0.53563732 -0.010243449 0.15577742, -0.5357936 -0.010243181 0.15160277, -0.52370924 -0.011431385 0.16333342, -0.52004343 -0.007236708 0.16620314, -0.52210528 -0.010243852 0.16461197, -0.52704912 -0.01287942 0.16235733, -0.53081375 -0.01287945 0.16057491, -0.53258914 -0.012324754 0.1595397, -0.53668708 -0.0088212378 0.15160283, -0.53652841 -0.0088214763 0.15584412, -0.52508277 -0.012324978 0.1637013, -0.51966709 -0.0072366036 0.16719866, -0.52056473 -0.0088218339 0.1663928, -0.52324003 -0.011431459 0.16496217, -0.52867633 -0.013067488 0.1627287, -0.53237492 -0.012324814 0.16085005, -0.53399533 -0.011431221 0.15975159, -0.53726912 -0.0055673607 0.1558997, -0.53708142 -0.0072362907 0.15588588, -0.53742981 -0.0055671223 0.15160298, -0.53724182 -0.0072359778 0.15160283, -0.52661413 -0.012879644 0.16411173, -0.52018338 -0.0088219084 0.16740108, -0.52140433 -0.010243971 0.1666981, -0.5245989 -0.012324963 0.16538122, -0.5303033 -0.012879554 0.16310012, -0.53377539 -0.011431191 0.16109705, -0.53516966 -0.010243718 0.15992892, -0.52822608 -0.013067726 0.16454354, -0.52101517 -0.010244001 0.16772759, -0.52252036 -0.011431504 0.16710436, -0.52611369 -0.012879748 0.1658484, -0.53184885 -0.012324963 0.16345263, -0.53494483 -0.010243777 0.1613034, -0.53605318 -0.0088216998 0.16006199, -0.52983814 -0.012879718 0.16497564, -0.52212054 -0.011431638 0.16816127, -0.52385658 -0.012325142 0.16759062, -0.52770847 -0.01306783 0.16634035, -0.53323513 -0.011431444 0.16376939, -0.53582472 -0.0088216849 0.16145855, -0.53678775 -0.0055675395 0.16017294, -0.53660178 -0.0072363801 0.16014475, -0.53136927 -0.012325037 0.16538572, -0.52534622 -0.012879837 0.16813278, -0.53439301 -0.010243867 0.16403377, -0.53637111 -0.0072365142 0.16155493, -0.52691454 -0.013067935 0.16870353, -0.5258444 0.0042401664 0.16576633, -0.52822632 0.0044323318 0.16454458, -0.52770859 0.0044322275 0.1663413, -0.52023584 -0.0017403848 0.15767831, -0.52149856 -1.1373311e-05 0.15471837, -0.52114964 -1.1492521e-05 0.15781617, -0.52057707 -0.0017402209 0.15464926, -0.52828974 0.0042398982 0.17058322, -0.53051072 0.0036708228 0.17001355, -0.53003591 0.0036707781 0.17126873, -0.52874774 0.0042398684 0.16937181, -0.52178258 0.0015036426 0.16115606, -0.52369899 0.0027471744 0.15932107, -0.52325994 0.0027472489 0.1614933, -0.52220672 0.0015037768 0.15905789, -0.53028053 0.0027464591 0.17508236, -0.53164524 0.0027465187 0.17190012, -0.53305584 0.0015028529 0.17245364, -0.53165394 0.0015028082 0.17572272, -0.52691454 0.0044321083 0.16870448, -0.5295729 0.0042401366 0.16691625, -0.52285975 0.0027471744 0.16310644, -0.52494544 0.0036713295 0.16187811, -0.52452976 0.003671106 0.16355395, -0.52007174 -0.0017404594 0.15868127, -0.52098197 -1.1552125e-05 0.15884185, -0.52405173 0.003671106 0.16521314, -0.52634174 0.0042401515 0.16403964, -0.51967317 -0.0036163218 0.15759346, -0.52000964 -0.0036161132 0.15460661, -0.51932216 -0.0055672415 0.15854883, -0.5197776 -0.0055671372 0.15508926, -0.5264737 0.0044320337 0.16987073, -0.5205701 -1.1730939e-05 0.16087914, -0.52871364 0.0036705844 0.1743516, -0.52508134 0.004239928 0.16803727, -0.5213961 0.0015035532 0.16271412, -0.5195114 -0.0036162771 0.15858227, -0.5223996 0.0027469508 0.16470373, -0.52465755 0.0042399578 0.16915771, -0.51966906 -0.0017406382 0.16067338, -0.52701336 0.0042396449 0.17355892, -0.52331847 0.0036710612 0.16739547, -0.52019495 -1.1701137e-05 0.16239217, -0.52095169 0.0015033446 0.16425681, -0.52291125 0.0036708675 0.16847241, -0.51911426 -0.0036165006 0.16054654, -0.51856691 -0.0055674799 0.1619556, -0.52524537 0.00443184 0.17273435, -0.521694 0.0027470104 0.16680411, -0.51930225 -0.0017406084 0.16215301, -0.51976323 -1.1924654e-05 0.16389027, -0.51457083 -0.0055679567 0.17160311, -0.51618218 -0.005567912 0.16850755, -0.51473725 -0.0036171712 0.17169917, -0.52130193 0.0027467571 0.16784072, -0.53957045 -0.0036164261 0.15607253, -0.53973782 -0.0036161281 0.15160331, -0.53992981 -0.0055671372 0.15160298, -0.53976214 -0.0055673011 0.1560868, -0.53900301 -0.0017404892 0.15603006, -0.53916872 -0.0017402209 0.15160322, -0.52347726 0.0042398237 0.1719099, -0.52026999 0.0015034042 0.16628608, -0.53808153 -1.1567026e-05 0.1559611, -0.53824466 -1.1373311e-05 0.15160322, -0.51875257 -0.0036165155 0.16200554, -0.51888013 -0.001740817 0.16361785, -0.53906971 -0.0036166944 0.16051701, -0.53925979 -0.0055675395 0.1605455, -0.53684157 0.0015037768 0.15586835, -0.53700101 0.0015040599 0.15160349, -0.51989138 0.0015032701 0.16728699, -0.52177709 0.0036708228 0.17111713, -0.51910126 -1.1939555e-05 0.16586065, -0.53882909 -0.0036166795 0.16198841, -0.53842556 -0.0055678822 0.16495422, -0.5183363 -0.003616754 0.16344991, -0.53850704 -0.0017408021 0.16043222, -0.51751757 -0.0055677928 0.16528368, -0.53533036 0.0027474128 0.15575519, -0.53548563 0.0027476512 0.15160355, -0.5187338 -1.1969358e-05 0.1668326, -0.52021009 0.0027467273 0.17038628, -0.51823294 -0.0017408617 0.16554439, -0.53826874 -0.0017408021 0.16188967, -0.51787347 -0.0017408468 0.16649497, -0.53759331 -1.1730939e-05 0.16029465, -0.5188368 0.0015031807 0.16974601, -0.53823829 -0.0036168732 0.16491151, -0.53360635 0.0036715232 0.15562597, -0.53375679 0.0036717914 0.15160349, -0.51769805 -0.0036167689 0.16534957, -0.51734376 -0.0036167391 0.16628692, -0.53735864 -1.1805445e-05 0.16172934, -0.51770961 -1.2163073e-05 0.16922018, -0.51687223 -0.0017410852 0.16882968, -0.51635647 -0.0036168732 0.16858897, -0.51523024 -0.001741264 0.17198387, -0.53636366 0.0015036426 0.16010934, -0.53768349 -0.0017409362 0.16478515, -0.5317356 0.0042407177 0.15548587, -0.5318808 0.0042408369 0.15160355, -0.53210324 -0.00085460022 0.17876294, -0.53276861 -0.0026656277 0.17910922, -0.5312323 -0.0017419197 0.18122247, -0.53361857 -0.0017415769 0.17663875, -0.53347903 -0.0041011758 0.17842677, -0.53413409 -0.0036175437 0.17687887, -0.533988 -0.0055685528 0.17763594, -0.53299242 -0.0045883842 0.17950657, -0.53189129 -0.0055687614 0.18160307, -0.53769982 -0.0036170371 0.1670824, -0.53726423 -0.0055681355 0.16928828, -0.53243864 -0.0041013695 0.1804103, -0.53172493 -0.0036178268 0.18150699, -0.536134 0.0015035234 0.16151369, -0.53197736 0.00038858876 0.17727029, -0.53278106 -1.2669712e-05 0.1762481, -0.53113717 0.0007754527 0.17826009, -0.53486514 0.0027471744 0.15988362, -0.53080815 0.00038851425 0.1795159, -0.5367825 -1.2103468e-05 0.16457942, -0.53043193 -1.3042241e-05 0.18076053, -0.52935499 0.0015025251 0.18013895, -0.53079671 0.0018410794 0.17668802, -0.5297901 0.0044327788 0.15533996, -0.52992994 0.0044329725 0.15160367, -0.52990752 0.0021616332 0.17762008, -0.52965409 0.0018410198 0.17888299, -0.52804255 0.0027462654 0.17938137, -0.52938443 0.0030089132 0.1759918, -0.53715014 -0.0017409511 0.16693532, -0.52846187 0.003250774 0.17686751, -0.53464168 0.0027471893 0.16125071, -0.52827364 0.0030088685 0.17812577, -0.52654535 0.0036703907 0.17851704, -0.52779514 0.0038471781 0.17520797, -0.53708065 -0.003617201 0.16923162, -0.53315562 0.0036713593 0.15962583, -0.52685541 0.0040009879 0.17603135, -0.52671987 0.0038469844 0.17727321, -0.52492076 0.0042394511 0.17757896, -0.53557009 0.0015032552 0.16430283, -0.52608961 0.0043235384 0.17436686, -0.52784473 0.004240673 0.15519437, -0.52797908 0.0042408966 0.15160355, -0.52515 0.0043836348 0.17514363, -0.52505255 0.0043234192 0.17635876, -0.52323121 0.0044316761 0.17660362, -0.52433354 0.0044198148 0.17350096, -0.53625757 -1.2192875e-05 0.16669616, -0.52333599 0.0044197403 0.17541698, -0.52154166 0.0042395554 0.17562822, -0.53293902 0.0036711507 0.1609503, -0.52303666 0.0041888319 0.17227975, -0.53653693 -0.001741115 0.1690644, -0.52315587 0.0042983405 0.17331243, -0.5313006 0.0042403452 0.15934643, -0.52257544 0.0041888617 0.17321536, -0.52168506 0.0040474348 0.1737273, -0.53409272 0.0027469359 0.16396582, -0.52159208 0.0041887872 0.17505494, -0.51991719 0.0036707334 0.17469004, -0.52597409 0.0036716126 0.15505412, -0.52610308 0.0036718212 0.15160355, -0.52093154 0.0035065375 0.1720089, -0.53613091 -0.0036173351 0.17205852, -0.53578222 -0.0055682547 0.17352334, -0.52000231 0.0035063736 0.17377788, -0.5184198 0.0027465187 0.17382556, -0.53505641 0.001503285 0.16637468, -0.51981568 0.002631288 0.17082426, -0.51890713 0.0022817962 0.17159438, -0.51893932 0.002631139 0.17254564, -0.51710755 0.0015030466 0.17306781, -0.53109163 0.0042404197 0.16062474, -0.51824296 0.0012180619 0.1703532, -0.51738864 0.001217898 0.17200643, -0.53565383 -1.2282282e-05 0.16879177, -0.51603049 -1.2371689e-05 0.1724458, -0.52937156 0.0044325702 0.15905586, -0.5356034 -0.0036173351 0.17345315, -0.53240734 0.0036711358 0.16358101, -0.52424997 0.0027474426 0.15492472, -0.52437431 0.0027476661 0.15160355, -0.53559613 -0.0017413534 0.17186403, -0.53359264 0.0027468614 0.16598237, -0.52917033 0.0044325255 0.16028607, -0.53446555 0.0015030466 0.16842553, -0.52744234 0.0042406283 0.15876496, -0.53507382 -0.0017413236 0.17324558, -0.53057832 0.0042403303 0.16316366, -0.52273887 0.0015039556 0.15481153, -0.52285892 0.0015040301 0.15160355, -0.53472781 -1.2326986e-05 0.17154816, -0.53192264 0.0036710165 0.165535, -0.52724904 0.0042404495 0.15994704, -0.53301746 0.0027467124 0.16797876, -0.52558738 0.0036714785 0.15848529, -0.53421354 -1.2446195e-05 0.17290798, -0.52867633 0.0044325106 0.16272974, -0.52161527 -1.1254102e-05 0.15160322, -0.53355926 0.0015030615 0.17112267, -0.53011078 0.0042402111 0.1650494, -0.52540165 0.0036713891 0.15962127, -0.53136533 0.0036708228 0.16746923, -0.5238778 0.0027474277 0.15822744, -0.52677435 0.0042403601 0.16229549, -0.52069104 -0.0017401911 0.15160331, -0.53213525 0.0027466379 0.17060444, -0.52237946 0.0015037619 0.15800148, -0.51992989 -0.0055669583 0.15160298, -0.52012199 -0.003615994 0.15160322, -0.52930337 0.0017628931 -0.16683158, -0.52997249 0.0012083761 -0.16981587, -0.52848285 0.0017630868 -0.16927373, -0.53274304 0.00031461939 -0.16575313, -0.53331178 -0.00087279454 -0.16806814, -0.53217709 0.0003147088 -0.16771778, -0.53389013 -0.00087295845 -0.16606066, -0.52344435 0.0012083761 -0.16868016, -0.52373272 0.0017631762 -0.17202756, -0.52229613 0.0012085102 -0.1713576, -0.52492005 0.001763057 -0.1692591, -0.53487527 -0.0055489875 -0.1685507, -0.53528887 -0.0038802661 -0.16643569, -0.53598821 -0.0055492409 -0.16439709, -0.53580499 -0.0038802959 -0.16435537, -0.53526413 -0.002295021 -0.16423175, -0.5347532 -0.0022949018 -0.16629204, -0.52950281 0.0012084208 -0.17105782, -0.52802724 0.001763206 -0.17047867, -0.53130871 0.00031482801 -0.17030248, -0.5308181 0.0012081824 -0.16729879, -0.53416562 -0.0022948273 -0.1683315, -0.52647358 0.0019511543 -0.16986898, -0.52524519 0.0019513778 -0.17273268, -0.53082663 0.00031490251 -0.17157748, -0.53242475 -0.00087270513 -0.17070845, -0.53469563 -0.0038800426 -0.16849515, -0.52675784 0.0017632805 -0.17343798, -0.53193206 -0.00087263063 -0.17201132, -0.53326422 -0.0022946782 -0.1710141, -0.52819461 0.001208555 -0.17410794, -0.53276378 -0.0022946186 -0.17233795, -0.51844794 -0.0055487789 -0.16956353, -0.51689887 -0.0038796701 -0.17294624, -0.51673603 -0.0055486001 -0.17285231, -0.53378558 -0.003879834 -0.17120388, -0.53345501 -0.0055487044 -0.17260948, -0.52948338 0.00031512603 -0.17470908, -0.53328013 -0.0038798191 -0.17254061, -0.53055972 -0.00087236241 -0.17521101, -0.53136933 -0.0022944398 -0.17558867, -0.53187227 -0.0038795806 -0.17582315, -0.53173554 -0.0055485703 -0.17655066, -0.53066075 -0.0019205995 -0.17661977, -0.53055972 -0.003071297 -0.17795843, -0.52991349 -0.0015581734 -0.17762175, -0.52830923 -0.00087219849 -0.17953387, -0.52952111 -0.001920525 -0.1788089, -0.52908301 -0.0022941865 -0.1799807, -0.53124583 -0.0042921938 -0.17730728, -0.53078055 -0.0047086366 -0.17834249, -0.52972639 -0.0055482723 -0.18035236, -0.52956343 -0.0038794316 -0.18025807, -0.53024876 -0.0042921193 -0.17920807, -0.52978909 -0.00055092946 -0.17619005, -0.52261794 -0.0038809218 -0.15160203, -0.52249861 -0.003880728 -0.15479225, -0.52242982 -0.0055498965 -0.15160233, -0.52226818 -0.005549673 -0.15530652, -0.52317262 -0.0022956617 -0.15160218, -0.52305174 -0.0022955872 -0.15483359, -0.52898455 -0.00024518743 -0.17713824, -0.52728087 0.00031539425 -0.17894012, -0.52866924 -0.00055075064 -0.1783413, -0.53104371 -0.0030713268 -0.17700711, -0.52406615 -0.00087367371 -0.15160194, -0.52394271 -0.0008735545 -0.1549004, -0.52997267 -0.0030713119 -0.17905658, -0.52866608 0.00056816265 -0.17563587, -0.52214122 -0.0038805045 -0.15796453, -0.52178413 -0.0055494346 -0.15898231, -0.52525371 0.00031385943 -0.15160194, -0.52512693 0.00031400844 -0.15498903, -0.52781981 0.00080194697 -0.17653194, -0.52604932 0.0012088977 -0.17822891, -0.52757132 0.00056826696 -0.17773888, -0.52734768 0.0013804995 -0.17498571, -0.52196944 -0.0038805492 -0.15901497, -0.52268958 -0.0022953786 -0.15804699, -0.52647769 0.0015306585 -0.17583302, -0.5246765 0.0017636381 -0.17743629, -0.52628261 0.001380723 -0.17703179, -0.52667588 0.0012074523 -0.15160179, -0.52654511 0.0012075715 -0.15509528, -0.5259003 0.0018454306 -0.174272, -0.52251565 -0.0022953041 -0.15911123, -0.52323121 0.0019515119 -0.17660192, -0.52486783 0.0018456094 -0.17625552, -0.52357334 -0.00087327138 -0.15818018, -0.52482241 0.0019483827 -0.17313486, -0.52826113 0.0017621182 -0.1516017, -0.52812588 0.0017622672 -0.15521371, -0.52486217 0.001946222 -0.17416766, -0.52434206 0.0019484721 -0.17410898, -0.52154768 -0.0038804896 -0.16110107, -0.52098179 -0.0055491813 -0.16260216, -0.52339566 -0.00087321177 -0.15926611, -0.52349269 0.0019187443 -0.17468327, -0.52178591 0.0017634146 -0.1757673, -0.52331799 0.0019485317 -0.17602497, -0.5228945 0.0016774051 -0.17298406, -0.52474755 0.00031424686 -0.15835702, -0.52192098 0.0016774498 -0.17483792, -0.52992994 0.0019500963 -0.15160179, -0.5297901 0.0019503199 -0.15533829, -0.52041292 0.0012086742 -0.17497489, -0.52189988 0.0011306517 -0.17182687, -0.5210073 0.00031499192 -0.17075652, -0.52208841 -0.0022951849 -0.16122445, -0.52099311 0.00088734552 -0.17266285, -0.52097768 0.0011308454 -0.17363843, -0.52128357 0.0013441704 -0.1740292, -0.52456528 0.00031429157 -0.15947232, -0.52615374 0.0012078397 -0.15856904, -0.52048713 0.0011307709 -0.17452851, -0.51918155 0.00031514093 -0.17426375, -0.52040648 9.7837299e-05 -0.17141059, -0.53145438 0.0017622374 -0.15546301, -0.51993084 -0.00087270513 -0.17025474, -0.51950389 9.7882003e-05 -0.17315736, -0.53159875 0.0017620437 -0.15160179, -0.51966 -0.0010063089 -0.17058468, -0.51912117 -0.0022946633 -0.16987714, -0.52116334 -0.0038803555 -0.16265056, -0.52295959 -0.00087315217 -0.1614233, -0.51923633 -0.0010062791 -0.17144692, -0.51960349 -0.00061530247 -0.17142662, -0.52596557 0.0012078844 -0.15971926, -0.5186007 -0.0014176406 -0.17204157, -0.51737916 -0.0022944249 -0.17322356, -0.51861835 -0.0038798936 -0.16964293, -0.51833349 -0.0010060556 -0.17314255, -0.52772123 0.0017624162 -0.15880513, -0.51815295 -0.00087237731 -0.17367008, -0.53303522 0.0012075864 -0.15558165, -0.53318411 0.0012073927 -0.15160179, -0.52169919 -0.0022950359 -0.16279408, -0.5207215 -0.0038801618 -0.16418478, -0.51986682 -0.0055491067 -0.16613817, -0.52411735 0.00031442568 -0.16168737, -0.5275268 0.0017625503 -0.15999451, -0.52937156 0.0019505583 -0.15905389, -0.5346061 0.00031388924 -0.15160179, -0.53445315 0.00031397864 -0.15568787, -0.52256227 -0.00087304786 -0.16302538, -0.52125144 -0.002295021 -0.16434798, -0.52550375 0.0012080036 -0.16200361, -0.52917016 0.0019505434 -0.16028425, -0.53102177 0.0017625205 -0.15930256, -0.53563738 -0.0008735545 -0.1557768, -0.53579372 -0.00087377802 -0.15160194, -0.52370942 0.00031454489 -0.16333255, -0.52004361 -0.003880132 -0.16620231, -0.5221054 -0.00087294355 -0.16461131, -0.52704924 0.0017626844 -0.16235647, -0.53081387 0.0017625652 -0.16057405, -0.5325892 0.0012076907 -0.15953898, -0.53668714 -0.0022958405 -0.15160203, -0.53652859 -0.0022954531 -0.15584356, -0.52508289 0.0012080334 -0.16370064, -0.51966715 -0.003879983 -0.16719773, -0.52056491 -0.0022948273 -0.16639194, -0.52324015 0.00031458959 -0.16496134, -0.52867633 0.0019508116 -0.16272789, -0.53237504 0.0012078248 -0.16084939, -0.53399545 0.00031423196 -0.159751, -0.53726912 -0.0055496581 -0.15589932, -0.5370816 -0.0038807578 -0.15588504, -0.53742981 -0.0055499561 -0.15160218, -0.53724182 -0.0038809963 -0.15160218, -0.52661413 0.0017627589 -0.16411087, -0.52018344 -0.0022947975 -0.16740036, -0.52140439 -0.00087285414 -0.16669747, -0.52459908 0.0012081973 -0.16538033, -0.53030342 0.0017626993 -0.16309926, -0.53377551 0.00031432137 -0.16109642, -0.5351696 -0.00087325647 -0.15992799, -0.52822632 0.0019509159 -0.16454276, -0.52101523 -0.00087272003 -0.16772696, -0.52252048 0.0003146641 -0.16710353, -0.52611381 0.0017627887 -0.16584763, -0.53184897 0.0012079738 -0.163452, -0.53494489 -0.00087331608 -0.16130278, -0.53605318 -0.0022953339 -0.16006142, -0.52983826 0.0017628781 -0.16497478, -0.52212059 0.0003147833 -0.16816044, -0.52385676 0.0012083165 -0.1675899, -0.52770853 0.0019509159 -0.16633964, -0.53323519 0.00031448528 -0.1637685, -0.53582478 -0.0022952743 -0.16145787, -0.53678763 -0.005549524 -0.16017205, -0.53660178 -0.0038805492 -0.16014415, -0.53136939 0.0012080185 -0.16538522, -0.52534634 0.0017630421 -0.16813195, -0.53439313 -0.00087300315 -0.16403279, -0.53637111 -0.0038805492 -0.1615544, -0.52691454 0.0019511245 -0.16870296, -0.52584428 -0.015356962 -0.16576552, -0.52822608 -0.015549246 -0.16454396, -0.52770847 -0.015549127 -0.16634047, -0.52023584 -0.0093763359 -0.15767759, -0.52149862 -0.011105422 -0.15471765, -0.52114958 -0.011105169 -0.15781555, -0.52057707 -0.0093765594 -0.15464857, -0.52828956 -0.015356738 -0.17058256, -0.53051043 -0.014787693 -0.17001268, -0.53003591 -0.014787573 -0.17126793, -0.52874774 -0.015356738 -0.16937101, -0.52178246 -0.012620423 -0.16115516, -0.52369899 -0.013864104 -0.15932038, -0.5232597 -0.013864134 -0.16149253, -0.52220649 -0.012620572 -0.15905717, -0.53028041 -0.01386321 -0.17508164, -0.53164512 -0.013863567 -0.17189947, -0.53305572 -0.012619976 -0.17245305, -0.53165382 -0.012619663 -0.17572194, -0.52691442 -0.015548918 -0.16870388, -0.52957267 -0.015356962 -0.16691554, -0.52285963 -0.013863925 -0.16310558, -0.52494544 -0.014788065 -0.16187724, -0.52452976 -0.01478802 -0.16355309, -0.52007186 -0.0093762465 -0.15868038, -0.52098185 -0.011105198 -0.15884116, -0.52405173 -0.014787856 -0.16521257, -0.51967311 -0.0075003989 -0.15759265, -0.52000958 -0.0075005479 -0.15460587, -0.51932216 -0.0055495687 -0.15854818, -0.51977777 -0.0055496432 -0.15508837, -0.52647358 -0.015548844 -0.16986993, -0.52056998 -0.01110499 -0.16087851, -0.52871352 -0.014787558 -0.17435113, -0.52508134 -0.015356768 -0.16803646, -0.52139586 -0.012620319 -0.16271347, -0.51951146 -0.0075003393 -0.15858158, -0.52239954 -0.013863835 -0.16470289, -0.52465737 -0.015356723 -0.16915706, -0.519669 -0.0093761869 -0.16067272, -0.52701324 -0.015356515 -0.17355832, -0.52331835 -0.014787722 -0.16739497, -0.52019477 -0.011104945 -0.16239151, -0.52095157 -0.012620214 -0.16425619, -0.52291125 -0.014787663 -0.16847178, -0.51911438 -0.0075002797 -0.16054615, -0.51856685 -0.0055492409 -0.16195497, -0.52524513 -0.015548754 -0.17273381, -0.52169389 -0.013863672 -0.16680348, -0.51930219 -0.0093760528 -0.16215223, -0.51457083 -0.0055487491 -0.17160225, -0.51618218 -0.0055488236 -0.16850719, -0.51473737 -0.0074995644 -0.17169845, -0.53957057 -0.0075005628 -0.15607181, -0.53973782 -0.0075008161 -0.15160233, -0.53992987 -0.0055499263 -0.15160218, -0.51976317 -0.011104826 -0.16388953, -0.52130175 -0.013863701 -0.16784012, -0.53976214 -0.0055497028 -0.15608615, -0.53900295 -0.0093765296 -0.15602934, -0.53916866 -0.0093767084 -0.15160254, -0.52347714 -0.015356544 -0.17190915, -0.53808147 -0.011105526 -0.1559605, -0.53824455 -0.01110566 -0.15160254, -0.52026993 -0.012620065 -0.16628528, -0.51875257 -0.007500086 -0.16200504, -0.53906971 -0.0075003542 -0.16051617, -0.53925967 -0.0055494793 -0.16054478, -0.51888007 -0.0093760528 -0.16361699, -0.53684133 -0.012620691 -0.15586761, -0.53700083 -0.012621049 -0.15160254, -0.5198912 -0.01262011 -0.16728628, -0.53882909 -0.0075002648 -0.16198799, -0.53842556 -0.0055491813 -0.16495359, -0.52177697 -0.014787484 -0.17111638, -0.53850704 -0.0093762912 -0.16043153, -0.5191012 -0.011104692 -0.16585979, -0.51833642 -0.007500086 -0.16344914, -0.51751757 -0.0055491813 -0.16528305, -0.53533024 -0.013864372 -0.15575445, -0.53548557 -0.013864566 -0.15160275, -0.51873368 -0.011104692 -0.16683197, -0.52021009 -0.013863567 -0.17038572, -0.53826863 -0.0093762763 -0.16188928, -0.51823288 -0.0093759038 -0.16554376, -0.53759319 -0.011105154 -0.16029397, -0.51787341 -0.0093757249 -0.16649425, -0.53823823 -0.0075001009 -0.16491088, -0.51883656 -0.012619901 -0.1697453, -0.53360623 -0.014788557 -0.15562516, -0.53375667 -0.014788691 -0.15160283, -0.51769817 -0.0074999221 -0.16534898, -0.53735858 -0.011105243 -0.16172892, -0.5173437 -0.0074998029 -0.1662862, -0.51770955 -0.011104528 -0.16921952, -0.51687217 -0.0093757249 -0.16882885, -0.53636342 -0.012620557 -0.16010863, -0.51635629 -0.0074997433 -0.16858837, -0.51523012 -0.0093755014 -0.171983, -0.53768331 -0.0093759932 -0.16478428, -0.53173548 -0.015357543 -0.15548503, -0.53188068 -0.015357796 -0.15160263, -0.53210312 -0.010262404 -0.17876226, -0.53361851 -0.0093753375 -0.1766378, -0.53276843 -0.0084512569 -0.17910847, -0.53123224 -0.0093750097 -0.18122181, -0.53769982 -0.0075000264 -0.16708183, -0.53726423 -0.0055490024 -0.16928753, -0.53347909 -0.0070157684 -0.17842618, -0.53413415 -0.0074994005 -0.17687812, -0.533988 -0.005548466 -0.17763552, -0.53299236 -0.0065285452 -0.17950568, -0.53189147 -0.005548168 -0.18160233, -0.53613383 -0.012620497 -0.16151291, -0.53243852 -0.007015679 -0.18040964, -0.53172499 -0.0074991025 -0.18150628, -0.53197724 -0.011505444 -0.17726949, -0.53278095 -0.01110423 -0.17624727, -0.53486508 -0.013864029 -0.15988281, -0.53113705 -0.011892352 -0.17825952, -0.53678244 -0.011104871 -0.16457886, -0.53080815 -0.011505309 -0.17951527, -0.53043193 -0.011103991 -0.18075988, -0.52935487 -0.01261938 -0.1801382, -0.52978998 -0.015549768 -0.15533927, -0.52992982 -0.015549902 -0.15160263, -0.53079647 -0.012958053 -0.17668727, -0.52990741 -0.013278548 -0.1776194, -0.52965385 -0.012957994 -0.17888209, -0.5371502 -0.009375874 -0.1669347, -0.5280425 -0.013862941 -0.17938057, -0.52938432 -0.014125858 -0.175991, -0.53464156 -0.013864089 -0.16124985, -0.52846175 -0.014367674 -0.17686686, -0.53708065 -0.0074999072 -0.16923103, -0.52827352 -0.014125679 -0.17812493, -0.52654535 -0.014787216 -0.17851624, -0.53315562 -0.014788244 -0.15962523, -0.5277949 -0.014963958 -0.17520726, -0.53556997 -0.012620304 -0.1643022, -0.52685529 -0.015117873 -0.17603055, -0.52671975 -0.014963809 -0.17727271, -0.52492064 -0.015356231 -0.1775783, -0.52784461 -0.015357513 -0.15519342, -0.52608949 -0.015440408 -0.17436627, -0.52797896 -0.015357677 -0.15160283, -0.52514988 -0.01550037 -0.17514288, -0.53625745 -0.011104811 -0.16669545, -0.52505261 -0.015440259 -0.17635792, -0.52323109 -0.015548576 -0.17660293, -0.52433354 -0.015536536 -0.17350036, -0.5329389 -0.014788244 -0.16094968, -0.52333599 -0.01553655 -0.17541629, -0.52154166 -0.01535638 -0.17562732, -0.53653687 -0.0093756951 -0.16906333, -0.52303654 -0.015305806 -0.17227927, -0.53130049 -0.015357364 -0.15934572, -0.52315569 -0.015415061 -0.17331174, -0.52257514 -0.015305597 -0.17321455, -0.53409261 -0.01386397 -0.16396508, -0.52597398 -0.014788512 -0.15505332, -0.52168494 -0.01516426 -0.17372656, -0.52610296 -0.014788661 -0.15160263, -0.52159184 -0.015305582 -0.17505422, -0.51991695 -0.01478738 -0.17468938, -0.53613091 -0.0074997284 -0.17205778, -0.53578234 -0.0055487193 -0.17352286, -0.52093142 -0.014623288 -0.17200819, -0.53505629 -0.012620095 -0.16637349, -0.52000231 -0.014623228 -0.17377713, -0.51841968 -0.013863314 -0.17382473, -0.51981562 -0.013748053 -0.17082345, -0.53109139 -0.015357245 -0.16062397, -0.51890701 -0.013398517 -0.17159364, -0.5189392 -0.013747979 -0.17254484, -0.51710743 -0.012619663 -0.17306712, -0.53565377 -0.011104736 -0.16879126, -0.5182429 -0.012334872 -0.17035267, -0.52937144 -0.015549529 -0.15905482, -0.51738852 -0.012334693 -0.17200589, -0.51603049 -0.011104349 -0.17244533, -0.5356034 -0.0074996091 -0.17345265, -0.5324071 -0.014788095 -0.16358039, -0.52424997 -0.013864327 -0.15492395, -0.52437419 -0.013864551 -0.15160263, -0.53559607 -0.0093756653 -0.17186323, -0.5335924 -0.01386394 -0.16598165, -0.52917022 -0.015549365 -0.16028517, -0.53446537 -0.012620006 -0.1684247, -0.52744228 -0.015357364 -0.15876415, -0.5350737 -0.0093754865 -0.17324471, -0.5305782 -0.015357066 -0.16316304, -0.52273875 -0.012620736 -0.1548107, -0.5228588 -0.012620915 -0.15160263, -0.53472775 -0.011104513 -0.1715475, -0.53192264 -0.014787931 -0.16553399, -0.52724904 -0.015357245 -0.15994641, -0.53301734 -0.013863761 -0.16797826, -0.52558738 -0.014788214 -0.1584844, -0.53421348 -0.011104409 -0.17290726, -0.52867621 -0.015549246 -0.16272888, -0.52161521 -0.011105496 -0.15160254, -0.53355914 -0.012619916 -0.17112207, -0.53011066 -0.015357006 -0.16504854, -0.52540153 -0.014788274 -0.1596207, -0.53136533 -0.014787842 -0.16746852, -0.52387768 -0.013864148 -0.15822682, -0.52677423 -0.015357185 -0.16229483, -0.52069098 -0.0093766041 -0.15160239, -0.53213507 -0.013863493 -0.17060384, -0.52237922 -0.012620602 -0.15800089, -0.51992989 -0.005549822 -0.15160218, -0.52012211 -0.0075006522 -0.15160233, -0.52634174 -0.015357081 -0.16403875, -0.52930379 0.071762949 -0.16682765, -0.52997291 0.071208388 -0.16981184, -0.52848327 0.071763068 -0.16926968, -0.53274345 0.070314676 -0.16574916, -0.53331214 0.069127232 -0.16806415, -0.53217757 0.070314795 -0.16771391, -0.53389049 0.069126993 -0.16605675, -0.52344477 0.071208388 -0.16867617, -0.5237332 0.071763158 -0.1720235, -0.52229649 0.071208537 -0.17135355, -0.52492046 0.071763098 -0.16925526, -0.53487581 0.064451039 -0.16854665, -0.53528947 0.06611985 -0.16643164, -0.53598863 0.06445083 -0.16439316, -0.5358054 0.06611973 -0.16435143, -0.53475362 0.067705095 -0.16628802, -0.52950317 0.071208477 -0.17105398, -0.52802765 0.071763158 -0.17047477, -0.53130907 0.070314884 -0.17029837, -0.53081846 0.071208268 -0.16729495, -0.53416604 0.067705154 -0.16832766, -0.52647412 0.07195121 -0.16986489, -0.52524567 0.071951389 -0.17272881, -0.53082705 0.070315003 -0.17157343, -0.53242505 0.069127351 -0.17070457, -0.53469616 0.066119969 -0.16849124, -0.52675825 0.071763277 -0.17343411, -0.53193241 0.06912744 -0.17200747, -0.5332647 0.067705333 -0.17101008, -0.5281949 0.071208626 -0.17410424, -0.5327642 0.067705423 -0.17233405, -0.533786 0.066120148 -0.17120013, -0.51844841 0.064451158 -0.16955969, -0.51689929 0.066120327 -0.17294228, -0.51673645 0.064451456 -0.17284825, -0.53345561 0.064451277 -0.17260551, -0.52948374 0.070315123 -0.17470512, -0.53328055 0.066120207 -0.1725367, -0.53056008 0.069127709 -0.17520705, -0.53136975 0.067705572 -0.17558482, -0.53187257 0.066120356 -0.17581922, -0.53173608 0.064451516 -0.1765466, -0.53066117 0.068079412 -0.17661577, -0.53056026 0.066928774 -0.17795438, -0.52991384 0.068441838 -0.17761782, -0.52830976 0.069127977 -0.17952994, -0.52952164 0.068079561 -0.17880484, -0.52908355 0.06770587 -0.17997679, -0.53124624 0.065707833 -0.1773034, -0.53078097 0.065291375 -0.17833868, -0.5297268 0.064451724 -0.18034843, -0.53024918 0.065707952 -0.17920408, -0.52956396 0.066120684 -0.18025419, -0.52978951 0.069449067 -0.17618594, -0.52261835 0.066119105 -0.1515981, -0.52249902 0.066119283 -0.15478826, -0.52243036 0.064450175 -0.15159833, -0.52226859 0.064450383 -0.15530229, -0.5289849 0.069754809 -0.17713431, -0.52317303 0.06770438 -0.15159795, -0.52305222 0.067704529 -0.15482968, -0.52728134 0.070315421 -0.17893606, -0.52866966 0.069449306 -0.17833734, -0.53104419 0.066928744 -0.17700306, -0.52406657 0.069126368 -0.15159795, -0.52394313 0.069126487 -0.15489641, -0.52997309 0.066928834 -0.17905268, -0.5286665 0.070568174 -0.17563203, -0.52214152 0.066119432 -0.15796041, -0.52178472 0.064450651 -0.15897819, -0.52525419 0.070313931 -0.15159789, -0.52512753 0.070314109 -0.1549851, -0.52782023 0.070801884 -0.17652789, -0.52604991 0.071208924 -0.17822495, -0.5275718 0.070568353 -0.17773488, -0.52734816 0.071380556 -0.17498171, -0.52196985 0.066119552 -0.15901095, -0.52269 0.067704618 -0.15804309, -0.52647805 0.071530551 -0.17582908, -0.52467692 0.071763515 -0.17743233, -0.52628314 0.071380764 -0.17702788, -0.52667624 0.071207523 -0.15159795, -0.52654552 0.071207643 -0.15509123, -0.52590072 0.071845502 -0.17426789, -0.52251613 0.067704707 -0.15910712, -0.52323157 0.071951538 -0.17659804, -0.52486813 0.071845621 -0.17625156, -0.52482277 0.071948349 -0.17313096, -0.5235737 0.069126785 -0.1581763, -0.52826142 0.071762055 -0.15159774, -0.5281263 0.071762234 -0.15520984, -0.52486253 0.071946055 -0.17416361, -0.52434242 0.071948379 -0.17410508, -0.52154797 0.066119522 -0.16109723, -0.52098221 0.06445086 -0.1625981, -0.52349317 0.071918756 -0.17467931, -0.52178633 0.071763486 -0.17576346, -0.52331853 0.071948588 -0.17602086, -0.52339602 0.069126785 -0.15926221, -0.52289498 0.071677417 -0.1729801, -0.52474797 0.070314318 -0.15835315, -0.52192134 0.071677446 -0.17483407, -0.52041352 0.071208775 -0.1749709, -0.52993035 0.071950138 -0.15159774, -0.52979052 0.071950316 -0.15533438, -0.52190018 0.071130663 -0.17182294, -0.52100784 0.070315063 -0.17075267, -0.52099359 0.070887297 -0.17265886, -0.52208894 0.067704916 -0.16122052, -0.52097809 0.071130842 -0.17363441, -0.52128404 0.071344197 -0.17402521, -0.52456564 0.070314348 -0.15946838, -0.52048755 0.071130842 -0.17452458, -0.52615404 0.071207821 -0.15856498, -0.51918209 0.070315212 -0.17425969, -0.52040708 0.070097834 -0.17140654, -0.5314548 0.071762234 -0.15545911, -0.51993138 0.069127321 -0.17025077, -0.51950437 0.070097923 -0.17315319, -0.53159934 0.071762085 -0.15159795, -0.51966053 0.068993807 -0.17058069, -0.51912159 0.067705363 -0.16987315, -0.52116376 0.06611976 -0.16264671, -0.51923692 0.068993807 -0.17144307, -0.52295989 0.069126815 -0.16141936, -0.51960397 0.069384664 -0.17142269, -0.52596611 0.071207941 -0.15971527, -0.51860112 0.068582445 -0.17203763, -0.51737976 0.067705631 -0.1732195, -0.51861876 0.066120088 -0.16963902, -0.51833391 0.068993956 -0.17313853, -0.51815331 0.06912756 -0.17366618, -0.52772164 0.071762413 -0.15880126, -0.53303564 0.071207553 -0.15557757, -0.53318441 0.071207345 -0.15159798, -0.52169961 0.067704946 -0.16279039, -0.52072185 0.06611982 -0.16418073, -0.51986724 0.064450949 -0.16613433, -0.52411777 0.070314467 -0.16168347, -0.52752727 0.071762562 -0.1599904, -0.52937192 0.071950555 -0.15905014, -0.53460652 0.070313871 -0.15159795, -0.53445375 0.07031408 -0.15568388, -0.52256268 0.069127023 -0.16302153, -0.52125198 0.067705035 -0.16434416, -0.52550423 0.071208 -0.16199979, -0.52917063 0.071950674 -0.1602802, -0.53102219 0.071762532 -0.15929866, -0.53579396 0.069126248 -0.15159798, -0.53563786 0.069126546 -0.15577281, -0.52370977 0.070314556 -0.16332862, -0.52004403 0.066119879 -0.16619837, -0.52210575 0.069127172 -0.16460741, -0.52704966 0.071762681 -0.16235265, -0.53081429 0.071762592 -0.16057009, -0.53258967 0.071207881 -0.15953514, -0.53668761 0.06770426 -0.1515981, -0.53652889 0.067704439 -0.1558395, -0.52508324 0.071208 -0.16369677, -0.51966757 0.066119939 -0.16719389, -0.52056521 0.067705184 -0.16638792, -0.52324051 0.070314705 -0.1649574, -0.52867681 0.071950793 -0.16272387, -0.5323754 0.071207941 -0.16084549, -0.53399599 0.070314288 -0.15974721, -0.53726965 0.064450443 -0.15589541, -0.53708202 0.066119283 -0.15588099, -0.53743035 0.064450145 -0.15159827, -0.53724223 0.066118956 -0.15159827, -0.52661467 0.07176286 -0.16410682, -0.52018386 0.067705244 -0.16739649, -0.52140486 0.069127172 -0.16669357, -0.52459943 0.071208239 -0.16537642, -0.53030384 0.071762621 -0.16309541, -0.53377593 0.070314437 -0.16109243, -0.53517002 0.069126725 -0.15992424, -0.52822655 0.071950912 -0.16453907, -0.52101558 0.069127321 -0.16772285, -0.5225209 0.070314854 -0.16709957, -0.52611423 0.0717628 -0.1658437, -0.53184927 0.07120797 -0.16344807, -0.53494537 0.069126785 -0.16129872, -0.5360536 0.067704648 -0.16005751, -0.52983868 0.07176283 -0.16497076, -0.52212107 0.070314854 -0.16815653, -0.52385712 0.071208328 -0.167586, -0.52770901 0.071950942 -0.16633579, -0.53323561 0.070314527 -0.16376454, -0.53582531 0.067704797 -0.1614539, -0.5366022 0.066119522 -0.1601401, -0.53678817 0.064450622 -0.1601682, -0.53136992 0.071208209 -0.16538131, -0.5253467 0.071763009 -0.16812804, -0.53439343 0.069126964 -0.16402888, -0.53637153 0.066119552 -0.16155031, -0.52691489 0.071951091 -0.16869888, -0.53526455 0.067704946 -0.16422769, -0.52584457 0.054642972 -0.16576168, -0.52634203 0.054642912 -0.16403502, -0.52822649 0.054450806 -0.16453993, -0.52023619 0.060623672 -0.15767366, -0.52149904 0.058894571 -0.15471375, -0.52115005 0.058894809 -0.15781149, -0.52057749 0.060623433 -0.15464464, -0.52829003 0.054643389 -0.1705786, -0.5305109 0.055212345 -0.17000875, -0.53003621 0.055212405 -0.17126402, -0.52874815 0.05464324 -0.16936696, -0.52178282 0.057379629 -0.16115138, -0.5236994 0.056135949 -0.15931645, -0.52326024 0.056136008 -0.16148847, -0.52220708 0.0573796 -0.15905327, -0.53028083 0.056136813 -0.17507771, -0.53305614 0.057380136 -0.1724492, -0.5316543 0.057380345 -0.17571798, -0.53164572 0.056136545 -0.1718955, -0.52691489 0.054451134 -0.16869986, -0.5295732 0.05464315 -0.16691157, -0.52770889 0.054450955 -0.16633663, -0.52286005 0.056136068 -0.16310179, -0.52494591 0.055211987 -0.1618734, -0.52453017 0.055211987 -0.16354927, -0.52007216 0.060623731 -0.15867659, -0.52098244 0.058894869 -0.15883726, -0.52405196 0.055212047 -0.16520879, -0.51967353 0.062499579 -0.15758866, -0.52001017 0.06249949 -0.15460199, -0.51932257 0.064450562 -0.15854424, -0.51977819 0.064450473 -0.1550844, -0.526474 0.054451164 -0.16986597, -0.52057046 0.058895018 -0.16087458, -0.528714 0.055212613 -0.1743471, -0.52508175 0.05464315 -0.16803262, -0.52139634 0.057379689 -0.16270956, -0.51951176 0.062499639 -0.15857765, -0.52239996 0.056136247 -0.16469896, -0.52465785 0.05464327 -0.1691533, -0.51966947 0.06062388 -0.16066879, -0.52701378 0.054643538 -0.17355421, -0.52331877 0.055212256 -0.16739115, -0.52019531 0.058895107 -0.16238755, -0.52095199 0.057379778 -0.16425216, -0.52291167 0.055212375 -0.16846767, -0.51911479 0.062499817 -0.16054204, -0.51856738 0.064450741 -0.16195115, -0.52524555 0.054451343 -0.17272967, -0.5216943 0.056136366 -0.16679963, -0.51930267 0.060624 -0.16214833, -0.51457137 0.064451337 -0.17159835, -0.51618272 0.064451277 -0.16850305, -0.51473767 0.062500358 -0.17169461, -0.53957099 0.06249946 -0.15606803, -0.53973824 0.062499251 -0.15159833, -0.5399304 0.064450145 -0.15159827, -0.51976365 0.058895197 -0.16388544, -0.53976256 0.064450294 -0.15608206, -0.52130234 0.056136366 -0.16783616, -0.53900337 0.060623553 -0.15602547, -0.53916913 0.060623255 -0.15159854, -0.52347755 0.054643389 -0.17190531, -0.53808194 0.058894631 -0.15595651, -0.53824502 0.058894362 -0.15159857, -0.52027029 0.057379987 -0.16628143, -0.51875299 0.062499937 -0.16200098, -0.53907019 0.062499639 -0.16051239, -0.53926021 0.064450592 -0.16054088, -0.51888055 0.060624029 -0.16361302, -0.53684175 0.057379302 -0.1558637, -0.53700143 0.057379093 -0.15159869, -0.51989174 0.057379987 -0.16728237, -0.52177745 0.055212494 -0.17111224, -0.53882951 0.062499728 -0.16198394, -0.53842598 0.06445083 -0.16494954, -0.51910174 0.058895316 -0.16585588, -0.53850752 0.060623702 -0.16042745, -0.51833683 0.062499937 -0.16344544, -0.51751798 0.064450949 -0.165279, -0.53533065 0.05613571 -0.15575039, -0.53548598 0.056135412 -0.15159869, -0.51873416 0.058895405 -0.16682804, -0.52021044 0.056136515 -0.1703817, -0.5382691 0.060623791 -0.16188532, -0.51823324 0.060624059 -0.16553971, -0.53759378 0.058894839 -0.16028997, -0.51787382 0.060624178 -0.16649029, -0.5382387 0.062499907 -0.16490689, -0.51883709 0.057380136 -0.16974118, -0.53360665 0.055211421 -0.15562135, -0.53375715 0.055211272 -0.15159887, -0.51769859 0.062500089 -0.16534492, -0.53735906 0.058894899 -0.16172487, -0.51734418 0.062500179 -0.16628227, -0.51771015 0.058895495 -0.16921577, -0.5363639 0.05737954 -0.16010472, -0.51687258 0.060624328 -0.16882494, -0.51635689 0.062500298 -0.16858432, -0.5152306 0.060624477 -0.1719791, -0.5376839 0.060624 -0.16478047, -0.5317359 0.054642465 -0.15548113, -0.53188127 0.054642286 -0.15159878, -0.5321036 0.059737679 -0.17875814, -0.53361899 0.060624715 -0.17663392, -0.53276902 0.061548796 -0.17910448, -0.53123266 0.060624983 -0.181218, -0.53770024 0.062499996 -0.1670779, -0.53726476 0.064451158 -0.16928363, -0.53347951 0.062984347 -0.17842227, -0.53413457 0.062500656 -0.17687437, -0.53398848 0.064451575 -0.17763138, -0.53299278 0.063471526 -0.17950168, -0.53189176 0.064451814 -0.18159834, -0.53613436 0.05737954 -0.16150889, -0.53243905 0.062984377 -0.18040565, -0.53172547 0.062500924 -0.18150228, -0.53197759 0.058494475 -0.17726555, -0.53278142 0.058895733 -0.17624336, -0.5348655 0.056135889 -0.15987906, -0.53113753 0.05810776 -0.17825547, -0.53678292 0.058895107 -0.16457486, -0.53080851 0.058494713 -0.17951146, -0.5304324 0.058896031 -0.18075588, -0.52935523 0.057380643 -0.18013421, -0.53079695 0.057042029 -0.17668352, -0.5297904 0.05445027 -0.15533534, -0.52993029 0.05445021 -0.15159878, -0.529908 0.056721535 -0.17761543, -0.52965438 0.057042148 -0.17887828, -0.53715056 0.060624119 -0.16693065, -0.52804291 0.056137081 -0.17937669, -0.52938479 0.055874165 -0.17598715, -0.53464198 0.056136008 -0.161246, -0.52846217 0.055632379 -0.17686296, -0.53708106 0.062500119 -0.16922703, -0.528274 0.055874374 -0.17812088, -0.52654564 0.055212852 -0.17851225, -0.5331561 0.055211809 -0.15962121, -0.52779543 0.055036094 -0.17520329, -0.53557044 0.057379778 -0.16429836, -0.52685559 0.054882046 -0.17602667, -0.52672017 0.055036094 -0.17726865, -0.52492106 0.054643836 -0.17757431, -0.52784503 0.054642495 -0.15518969, -0.52608979 0.054559585 -0.17436221, -0.52797925 0.054642227 -0.15159878, -0.5251503 0.054499682 -0.17513886, -0.53625792 0.058895197 -0.16669154, -0.52505302 0.054559793 -0.17635402, -0.52323151 0.054451492 -0.17659894, -0.52433383 0.054463442 -0.17349645, -0.53293937 0.055211868 -0.16094568, -0.52333635 0.054463562 -0.17541233, -0.52154207 0.054643687 -0.17562333, -0.53653735 0.060624238 -0.16905954, -0.5230369 0.054694232 -0.17227519, -0.53130108 0.054642733 -0.15934166, -0.52315617 0.054584946 -0.17330769, -0.52257574 0.05469447 -0.17321071, -0.53409302 0.056136128 -0.1639609, -0.52597439 0.055211511 -0.15504932, -0.52610344 0.055211332 -0.15159878, -0.52168548 0.054835822 -0.17372257, -0.52159244 0.05469453 -0.17505029, -0.51991737 0.055212703 -0.17468527, -0.53613132 0.062500268 -0.17205402, -0.53578275 0.064451337 -0.17351884, -0.52093178 0.055376735 -0.17200431, -0.53505677 0.057379898 -0.16636977, -0.52000266 0.055376794 -0.17377332, -0.51842016 0.056136724 -0.173821, -0.51981616 0.056251999 -0.17081952, -0.53109205 0.054642823 -0.16062006, -0.51890749 0.056601491 -0.17158982, -0.51893973 0.056252059 -0.17254099, -0.51710784 0.057380315 -0.17306322, -0.53565437 0.058895435 -0.16878721, -0.51824325 0.057665195 -0.17034861, -0.52937186 0.054450508 -0.15905109, -0.51738912 0.057665374 -0.17200193, -0.51603097 0.058895674 -0.17244124, -0.53560382 0.062500387 -0.17344877, -0.53240752 0.055211987 -0.16357636, -0.52425039 0.056135651 -0.15492004, -0.52437454 0.056135442 -0.15159878, -0.53559655 0.060624447 -0.17185947, -0.53359288 0.056136217 -0.16597781, -0.52917051 0.054450627 -0.16028133, -0.53446585 0.057379987 -0.16842067, -0.52744257 0.054642674 -0.15876019, -0.53507406 0.060624417 -0.17324081, -0.53057861 0.054642852 -0.1631591, -0.52273917 0.057379302 -0.15480691, -0.5228591 0.057379123 -0.15159878, -0.53472823 0.058895525 -0.17154339, -0.53192306 0.055212107 -0.16553017, -0.52724934 0.054642793 -0.15994257, -0.53301781 0.056136277 -0.1679742, -0.52558774 0.055211689 -0.15848055, -0.53421402 0.058895644 -0.17290339, -0.52867675 0.054450836 -0.16272482, -0.52161568 0.058894511 -0.15159854, -0.53355962 0.057380136 -0.17111817, -0.53011107 0.054643031 -0.16504464, -0.52540195 0.055211779 -0.15961671, -0.53136575 0.055212226 -0.16746452, -0.5238781 0.056135889 -0.15822282, -0.5267747 0.054642942 -0.16229078, -0.52069145 0.060623314 -0.15159854, -0.53213555 0.056136545 -0.17059997, -0.52237964 0.057379391 -0.15799692, -0.5199303 0.064450264 -0.15159827, -0.52012259 0.062499341 -0.15159833, -0.53030384 0.071744412 0.16310477, -0.53237557 0.071189851 0.16085485, -0.53081423 0.071744502 0.16057971, -0.53274345 0.07029593 0.16575849, -0.53439343 0.069108427 0.16403806, -0.53323579 0.070296109 0.16377413, -0.5338906 0.069108427 0.16606572, -0.52615416 0.07119 0.15857446, -0.5280776 0.07174477 0.15581974, -0.52649826 0.071190059 0.15568155, -0.52772164 0.07174468 0.15881073, -0.53598863 0.064432323 0.16440186, -0.53528947 0.066101134 0.16644049, -0.53487581 0.064432055 0.16855526, -0.53469604 0.066100895 0.1685001, -0.53416604 0.06768623 0.1683366, -0.53475362 0.067686379 0.16629705, -0.53258967 0.071189851 0.15954435, -0.53102219 0.071744502 0.15930822, -0.53377593 0.070296258 0.1611017, -0.53184932 0.071189582 0.16345727, -0.53526455 0.067686439 0.1642369, -0.52937192 0.071932614 0.15905949, -0.5297401 0.071932852 0.15596509, -0.53399587 0.070296288 0.15975642, -0.53494531 0.069108665 0.16130784, -0.5358054 0.066101193 0.16436014, -0.53140271 0.07174477 0.15611064, -0.53517002 0.069108725 0.15993336, -0.53582519 0.067686558 0.1614629, -0.53298175 0.07118997 0.15624851, -0.53605366 0.067686617 0.16006637, -0.53678817 0.064432502 0.16017687, -0.53637153 0.066101432 0.16155922, -0.53439838 0.070296496 0.15637264, -0.5366022 0.066101521 0.16014898, -0.53558129 0.069108844 0.15647614, -0.53647161 0.067686826 0.15655386, -0.53702432 0.06610164 0.1566022, -0.53726953 0.06443274 0.15590379, -0.53637344 0.068060726 0.15530631, -0.53695518 0.066910058 0.15409672, -0.53622717 0.068423152 0.15406528, -0.53579396 0.069109201 0.15160719, -0.53648108 0.068060905 0.152841, -0.53668761 0.067687154 0.15160701, -0.53722376 0.065689087 0.1550037, -0.53743023 0.064432979 0.15160701, -0.53733844 0.065272689 0.15387446, -0.53724223 0.066101879 0.15160701, -0.53731066 0.065689266 0.15285912, -0.51673633 0.064431906 0.17285678, -0.51839083 0.066100955 0.17012864, -0.51844829 0.064432144 0.16956815, -0.53540373 0.069430441 0.15524295, -0.51689929 0.066100806 0.17295089, -0.53518099 0.069736183 0.1540195, -0.53460652 0.070296764 0.15160748, -0.53550947 0.06943059 0.15282002, -0.51737958 0.067686081 0.17322835, -0.51889068 0.06768623 0.17036939, -0.53689867 0.066909969 0.15516293, -0.51969576 0.069108278 0.17075726, -0.53699589 0.066909999 0.15285221, -0.51815325 0.069108009 0.17367527, -0.53415412 0.070549637 0.15516117, -0.51966757 0.066101223 0.16720268, -0.51986742 0.064432353 0.1661427, -0.53386927 0.070783436 0.15396225, -0.53318447 0.071190268 0.15160728, -0.53425747 0.070549667 0.15279263, -0.51918191 0.070295513 0.17426917, -0.52076566 0.070295721 0.17127252, -0.53268731 0.071361959 0.15506509, -0.52004415 0.066101223 0.16620728, -0.52018386 0.067686349 0.16740549, -0.53235757 0.071512103 0.1538966, -0.53278792 0.071362078 0.15276051, -0.53159916 0.071744949 0.15160748, -0.53107691 0.071826816 0.15495953, -0.52041358 0.071189106 0.17498022, -0.52204692 0.071189195 0.17188954, -0.52993041 0.071933061 0.15160748, -0.53117442 0.071827024 0.15272534, -0.52056521 0.067686468 0.16639709, -0.52957487 0.071929812 0.15540528, -0.52101558 0.069108367 0.16773188, -0.52916628 0.071900189 0.154116, -0.52178633 0.071743697 0.17577291, -0.52347517 0.071743846 0.17257738, -0.53018963 0.071927756 0.1530697, -0.52072185 0.066101372 0.16418946, -0.52098221 0.064432591 0.16260684, -0.52969337 0.071930051 0.15323624, -0.52826154 0.071745038 0.15160748, -0.52971697 0.071930051 0.15215036, -0.52780724 0.07165882 0.15492004, -0.52140486 0.069108516 0.16670248, -0.52212107 0.070295811 0.16816565, -0.52790588 0.07165885 0.15282869, -0.52637684 0.071112156 0.15524563, -0.52508181 0.070296645 0.15555751, -0.52323163 0.071931601 0.1766074, -0.52497876 0.071931869 0.17330173, -0.52688777 0.07132569 0.15445647, -0.52644509 0.071112305 0.15423173, -0.52125204 0.067686528 0.16435313, -0.52604699 0.070868969 0.15334088, -0.52651548 0.071112424 0.15220025, -0.5225209 0.070296139 0.16710913, -0.52667624 0.071190298 0.15160748, -0.52525407 0.070296824 0.15160728, -0.5249064 0.070079505 0.1544182, -0.52344483 0.071189374 0.16868541, -0.52116382 0.066101462 0.1626555, -0.52406657 0.069109201 0.15160728, -0.52498621 0.070079476 0.15245381, -0.52389872 0.069109023 0.15545392, -0.52383912 0.068975329 0.1548996, -0.52300847 0.067686945 0.1553759, -0.52467692 0.071743548 0.17744181, -0.5264824 0.071743786 0.17402571, -0.52261835 0.066101998 0.15160719, -0.52361614 0.068564087 0.15378872, -0.52317309 0.067687243 0.15160701, -0.52245587 0.06610176 0.15532756, -0.52394098 0.068975449 0.1529811, -0.52210581 0.069108635 0.16461655, -0.52385712 0.071189344 0.16759551, -0.52426505 0.069366455 0.15280762, -0.52396059 0.068975449 0.15202057, -0.52492046 0.071744055 0.16926453, -0.52169961 0.067686617 0.16279936, -0.52604973 0.071188927 0.17823446, -0.52791071 0.071189135 0.1747134, -0.52154809 0.066101491 0.16110599, -0.5217846 0.06443274 0.15898708, -0.52324057 0.070296109 0.16496649, -0.52534676 0.071744084 0.16813752, -0.52647412 0.071932077 0.16987434, -0.52256268 0.069108784 0.16303051, -0.5272814 0.070295393 0.17894533, -0.52919197 0.070295572 0.17533043, -0.52208894 0.067686707 0.16122949, -0.52459943 0.071189612 0.16538584, -0.52691507 0.071932167 0.16870832, -0.52802747 0.071743906 0.17048407, -0.52370983 0.070296198 0.16333807, -0.52830976 0.069107711 0.17953902, -0.53026193 0.06910789 0.17584553, -0.52196974 0.066101521 0.15901971, -0.52296001 0.069108784 0.16142857, -0.52611417 0.071744263 0.16585314, -0.52848327 0.071743995 0.16927919, -0.52950323 0.071189255 0.17106321, -0.52508342 0.071189702 0.16370597, -0.52908355 0.067685694 0.17998558, -0.53106683 0.067685753 0.17623299, -0.52214152 0.06610164 0.15796933, -0.52226859 0.06443283 0.15531114, -0.52251607 0.067686737 0.15911585, -0.52411777 0.070296347 0.16169274, -0.52770901 0.071932226 0.16634509, -0.52997273 0.071189284 0.16982135, -0.53082693 0.070295691 0.17158267, -0.52661467 0.071744293 0.16411641, -0.53156668 0.066100508 0.17647383, -0.53173608 0.064431578 0.17655534, -0.52972692 0.064431369 0.18035677, -0.52956396 0.066100299 0.18026319, -0.52269018 0.067686945 0.15805209, -0.52339602 0.069108784 0.15927133, -0.52550417 0.071189821 0.16200936, -0.52930385 0.071744263 0.1668371, -0.53130913 0.070295691 0.17030752, -0.53193241 0.069108009 0.17201641, -0.52822661 0.071932375 0.16454828, -0.5235737 0.069109023 0.15818527, -0.52456564 0.070296258 0.15947768, -0.52704966 0.071744442 0.16236198, -0.52243036 0.064433068 0.15160689, -0.5308184 0.071189463 0.16730452, -0.53242499 0.069108218 0.17071381, -0.53276414 0.067686021 0.17234275, -0.52983868 0.071744233 0.16498029, -0.52474797 0.070296496 0.15836248, -0.52596605 0.07118991 0.15972459, -0.52867675 0.071932524 0.16273358, -0.53217757 0.070295811 0.1677233, -0.5332647 0.067686111 0.17101917, -0.53345555 0.064431787 0.17261389, -0.53328049 0.066100687 0.1725454, -0.53136992 0.071189553 0.16539037, -0.52752721 0.071744531 0.15999997, -0.53331214 0.069108307 0.16807327, -0.53378588 0.066100895 0.17120883, -0.52917075 0.071932614 0.16028976, -0.5267747 0.054624643 0.16229832, -0.52822649 0.05443221 0.16454744, -0.52867663 0.054432508 0.1627326, -0.51787382 0.060605492 0.16649842, -0.51748741 0.058876451 0.16969323, -0.51873416 0.05887663 0.16683614, -0.51665491 0.060605343 0.16929245, -0.53130084 0.054624703 0.15934929, -0.53109199 0.054624703 0.16062739, -0.5331561 0.055193748 0.15962899, -0.52095199 0.057361331 0.16426, -0.52169418 0.056117561 0.16680726, -0.52240002 0.05611771 0.16470659, -0.52027029 0.057361212 0.16628921, -0.53527462 0.056118067 0.15644851, -0.5363639 0.05736145 0.16011226, -0.53678417 0.057361718 0.15658063, -0.5348655 0.056117889 0.1598866, -0.52917063 0.054432567 0.16028893, -0.53057861 0.054624584 0.16316631, -0.52286023 0.056117889 0.16310933, -0.52405202 0.05519354 0.16521606, -0.52453017 0.05519357 0.16355696, -0.51823324 0.060605492 0.16554797, -0.51910174 0.0588766 0.16586387, -0.52494574 0.055193748 0.16188097, -0.52634203 0.054624435 0.1640425, -0.51734418 0.062481489 0.16629076, -0.5161826 0.064432144 0.16851175, -0.51614219 0.06248128 0.16904548, -0.51751798 0.064432353 0.16528761, -0.5293718 0.054432567 0.15905857, -0.51976365 0.05887666 0.16389358, -0.53355229 0.055193897 0.15629774, -0.52724928 0.054624703 0.15995005, -0.52139646 0.05736145 0.16271737, -0.51769847 0.06248134 0.16535342, -0.52326012 0.056117859 0.16149628, -0.52744269 0.054624822 0.15876767, -0.51888067 0.060605552 0.16362131, -0.53168362 0.054624971 0.15613425, -0.52540195 0.055193838 0.15962416, -0.52019531 0.058876898 0.1623956, -0.52178282 0.05736151 0.16115895, -0.52558768 0.055193897 0.15848815, -0.51833683 0.062481459 0.16345382, -0.51856738 0.064432561 0.16195977, -0.52973992 0.054432806 0.15596396, -0.52369946 0.056118008 0.15932408, -0.51930267 0.060605761 0.16215646, -0.52057046 0.058876868 0.1608825, -0.53381532 0.062480655 0.1775564, -0.53172547 0.062480476 0.18151084, -0.53189176 0.06443128 0.18160686, -0.53123266 0.060604539 0.18122625, -0.5238781 0.056118067 0.15823054, -0.53398842 0.064431578 0.17763999, -0.53330261 0.060604777 0.17730954, -0.52779651 0.054624911 0.15579411, -0.53247011 0.058875915 0.1769084, -0.5304324 0.058875617 0.18076414, -0.52935523 0.057360407 0.18014207, -0.52220708 0.057361569 0.1590609, -0.51875299 0.062481668 0.16200936, -0.53560382 0.062480893 0.17345706, -0.53578275 0.064431846 0.17352724, -0.51966947 0.060605761 0.16067684, -0.5223797 0.057361659 0.15800464, -0.53134948 0.057360496 0.17636874, -0.52592772 0.055194046 0.15563086, -0.53613132 0.062480923 0.17206219, -0.53726465 0.064431936 0.16929233, -0.52098233 0.058877017 0.1588451, -0.535074 0.060604867 0.17324919, -0.51911479 0.062481698 0.16055048, -0.52998424 0.056117054 0.17571121, -0.52804279 0.056116816 0.17938435, -0.51932269 0.06443283 0.1585528, -0.52654564 0.055192824 0.17851999, -0.52115011 0.058877137 0.15781963, -0.52420551 0.056118157 0.15548006, -0.53559667 0.060605105 0.17186749, -0.52007228 0.06060588 0.15868473, -0.5342139 0.058876093 0.17291138, -0.52023619 0.060605969 0.15768206, -0.53708106 0.062481042 0.16923547, -0.52269578 0.057361718 0.15534797, -0.52842671 0.055193003 0.17496112, -0.51951188 0.062481906 0.15858617, -0.53472823 0.058876302 0.17155141, -0.51967353 0.062481876 0.15759712, -0.51977819 0.064432949 0.15509301, -0.52145702 0.058877107 0.15523955, -0.5330562 0.057360705 0.1724568, -0.52053636 0.060606029 0.15515929, -0.53653735 0.060605224 0.16906759, -0.51996952 0.062481966 0.1551097, -0.52069145 0.060606297 0.15160683, -0.52012259 0.062482294 0.15160683, -0.5199303 0.064433068 0.15160701, -0.52673644 0.054624047 0.17414713, -0.52492112 0.054623809 0.17758182, -0.52323151 0.054431554 0.17660645, -0.53869361 0.059718933 0.15417233, -0.53894359 0.06060588 0.15676975, -0.53944308 0.06153008 0.15420511, -0.53916913 0.060606148 0.15160668, -0.53770036 0.06248131 0.16708636, -0.53842598 0.064432234 0.16495812, -0.53971714 0.062965482 0.1551514, -0.53951055 0.062481876 0.15681949, -0.53976244 0.064432621 0.15609077, -0.53983551 0.06345281 0.15397295, -0.53993028 0.064433008 0.15160689, -0.53355944 0.057360824 0.17112601, -0.53980786 0.062965661 0.1529133, -0.53973836 0.062482145 0.15160689, -0.53164572 0.056117203 0.17190322, -0.53783816 0.058475818 0.15540236, -0.53802305 0.058876958 0.1566889, -0.53760546 0.058088984 0.15412486, -0.53565425 0.058876272 0.16879529, -0.53794855 0.058476027 0.15287244, -0.53824502 0.058877196 0.15160668, -0.53700143 0.057361897 0.15160662, -0.53652447 0.057023223 0.15531591, -0.52497864 0.054431852 0.17330062, -0.53622061 0.056702849 0.15406433, -0.53715056 0.060605373 0.16693902, -0.53663248 0.057023462 0.15284374, -0.53548598 0.056118306 0.15160644, -0.53495312 0.055855449 0.15521303, -0.53213549 0.056117322 0.17060757, -0.5382387 0.06248137 0.16491529, -0.53459215 0.055613752 0.15399331, -0.53505814 0.055855688 0.15280932, -0.53003621 0.055193152 0.17127159, -0.53375715 0.055194166 0.15160644, -0.53318489 0.055017289 0.15509704, -0.53446585 0.057360973 0.16842866, -0.53278285 0.054863509 0.15391397, -0.53328645 0.055017468 0.15277028, -0.52322102 0.054624077 0.17245415, -0.52154195 0.054623958 0.17563099, -0.53188109 0.054625209 0.15160644, -0.53128749 0.054541048 0.15497243, -0.53625792 0.058876481 0.16669953, -0.53086191 0.054481145 0.15383011, -0.5313853 0.054541167 0.15272912, -0.52993035 0.054433044 0.15160662, -0.5305109 0.055193212 0.17001641, -0.52933359 0.054444876 0.15484434, -0.52942777 0.054445025 0.15268642, -0.52797943 0.05462518 0.15160635, -0.5376839 0.060605492 0.1647886, -0.52760005 0.054675814 0.15525356, -0.52829009 0.054624077 0.17058608, -0.53301781 0.056117442 0.16798174, -0.52821946 0.054566439 0.15441898, -0.52766818 0.054675903 0.15421262, -0.52153087 0.055193361 0.17164025, -0.51991737 0.055193033 0.17469299, -0.52715313 0.054817345 0.15332419, -0.52773637 0.054676022 0.15212786, -0.52610344 0.055194225 0.15160662, -0.53882951 0.062481549 0.16199231, -0.53926021 0.064432472 0.1605494, -0.52564138 0.055358376 0.15443575, -0.52572131 0.055358525 0.15243909, -0.52437466 0.056118365 0.15160644, -0.53505677 0.057361182 0.16637763, -0.52408284 0.056233432 0.15490365, -0.52874804 0.054624166 0.16937494, -0.52368098 0.056583222 0.1537824, -0.52418464 0.05623373 0.15297461, -0.52285922 0.057362016 0.15160662, -0.53678292 0.058876511 0.16458285, -0.52248532 0.057646956 0.15452519, -0.526474 0.054432031 0.16987336, -0.5225721 0.057647135 0.15266633, -0.52161562 0.058877435 0.15160668, -0.53907019 0.062481578 0.16052079, -0.53136569 0.055193301 0.16747224, -0.51997316 0.056117352 0.17089018, -0.5184201 0.056117233 0.17382863, -0.5382691 0.060605612 0.16189361, -0.53359282 0.056117531 0.16598532, -0.52691489 0.054432061 0.16870734, -0.53557044 0.057361241 0.16430604, -0.52465785 0.054624256 0.16916078, -0.53850752 0.060605731 0.16043574, -0.5295732 0.054624435 0.16691911, -0.51860791 0.057360973 0.17023262, -0.51710778 0.057360884 0.17307103, -0.53735906 0.058876779 0.16173279, -0.53192306 0.05519348 0.16553795, -0.52508163 0.054624256 0.16804016, -0.53409302 0.056117591 0.16396883, -0.52291155 0.055193331 0.16847536, -0.53759378 0.058876809 0.16029787, -0.52770889 0.054432269 0.1663439, -0.51603097 0.058876242 0.17244941, -0.53613442 0.05736148 0.1615167, -0.53011101 0.054624464 0.16505229, -0.52331877 0.05519354 0.16739842, -0.53240752 0.05519357 0.16358387, -0.52130222 0.056117471 0.16784367, -0.52584469 0.054624435 0.1657691, -0.5152306 0.060605075 0.17198738, -0.53464186 0.056117769 0.16125336, -0.51989168 0.057361152 0.16729018, -0.51473778 0.062481072 0.1717028, -0.51457137 0.064432174 0.17160702, -0.53293937 0.055193748 0.1609534, -0.52260524 0.062838733 -0.12560588, -0.52254754 0.0018308721 -0.12532279, -0.52243036 0.064448655 -0.12399596, -0.52290612 0.001472529 -0.12662908, -0.52243 0.0019486211 -0.12399921, -0.53743035 0.064448535 -0.12399575, -0.53742981 -0.0055515654 -0.12399966, -0.53737146 0.063510656 -0.12493369, -0.53725505 -0.0039415248 -0.12560973, -0.53718525 0.0625467 -0.12589779, -0.53676689 -0.002468247 -0.12708268, -0.53659576 0.061010417 -0.12743419, -0.53598976 -0.0011323579 -0.12841845, -0.53570282 0.05966061 -0.12878427, -0.53499639 -2.1267682e-05 -0.12952948, -0.53472847 0.058684465 -0.12976047, -0.53385425 0.00084012374 -0.13039058, -0.53360194 0.057909157 -0.13053593, -0.53262478 0.001448106 -0.13099837, -0.53238469 0.057361927 -0.13108301, -0.53148204 0.0017865859 -0.1313369, -0.5311417 0.057047423 -0.13139772, -0.53069586 0.001909744 -0.13146007, -0.52993029 0.056948926 -0.13149631, -0.52992994 0.0019489639 -0.13149917, -0.52916431 0.056988206 -0.13145709, -0.52860636 0.0018311851 -0.13138175, -0.52837831 0.057111409 -0.13133383, -0.52730006 0.0014727823 -0.13102317, -0.52723551 0.057449874 -0.13099551, -0.52607602 0.00088294968 -0.1304332, -0.52600592 0.058057662 -0.13038743, -0.52531046 0.00035740063 -0.12990797, -0.5248639 0.058918919 -0.12952602, -0.52462661 -0.00024782494 -0.12930271, -0.52402145 0.00035740063 -0.12861878, -0.52387029 0.06002992 -0.12841484, -0.52349579 0.00088269636 -0.12785336, -0.52309328 0.06136572 -0.12707889, -0.52260524 0.062824786 0.12239423, -0.52254766 0.0018169396 0.12267712, -0.52243036 0.064434677 0.12400439, -0.52290612 0.0014585815 0.12137106, -0.52243 0.0019346736 0.12400088, -0.53743035 0.064434588 0.12400439, -0.53742981 -0.0055654086 0.12400028, -0.53737146 0.063496709 0.12306654, -0.53725517 -0.0039553978 0.12239057, -0.53718513 0.062532723 0.12210241, -0.53676689 -0.0024822392 0.12091762, -0.53659576 0.060996469 0.12056589, -0.53598988 -0.0011462606 0.11958173, -0.53570282 0.059646662 0.11921585, -0.53499633 -3.523007e-05 0.11847058, -0.53472859 0.058670606 0.11823973, -0.53385425 0.00082617626 0.11760929, -0.53360194 0.05789509 0.11746415, -0.53262466 0.0014340393 0.1170018, -0.53238481 0.057347979 0.11691692, -0.53148204 0.0017725788 0.11666319, -0.5311417 0.057033535 0.11660242, -0.53069586 0.0018959157 0.11654004, -0.52993041 0.056935098 0.11650404, -0.52992994 0.0019350909 0.11650085, -0.52916437 0.056974288 0.11654308, -0.52860636 0.0018172227 0.11661842, -0.52837831 0.057097282 0.11666632, -0.52730006 0.0014587156 0.11697695, -0.52723551 0.057435747 0.11700466, -0.52607602 0.00086895749 0.11756673, -0.52600592 0.058043595 0.11761269, -0.52531046 0.00034345314 0.11809239, -0.52486378 0.058904912 0.11847398, -0.52462661 -0.00026177242 0.11869738, -0.52402145 0.00034333393 0.11938131, -0.52387029 0.060016003 0.11958507, -0.52349579 0.00086889789 0.12014678, -0.52309328 0.061351683 0.12092116, -0.51142502 -0.0055703409 0.21205175, -0.51126224 -0.0072391219 0.2119576, -0.51078171 -0.0088244714 0.21168014, -0.51000804 -0.0102464 0.21123353, -0.5089795 -0.011433963 0.2106396, -0.50774795 -0.012327377 0.20992839, -0.50637513 -0.012881983 0.20913574, -0.50492984 -0.013070095 0.20830119, -0.50348455 -0.012881909 0.20746684, -0.50211173 -0.012327213 0.20667434, -0.50088018 -0.01143356 0.20596331, -0.49985167 -0.010245893 0.20536971, -0.49907792 -0.0088238604 0.2049228, -0.49859747 -0.0072386004 0.20464563, -0.49843466 -0.0055697747 0.20455167, -0.49626955 -0.00556973 0.20330167, -0.49643615 -0.0036187954 0.20339775, -0.49692896 -0.0017428584 0.20368257, -0.49772909 -1.4025718e-05 0.20414484, -0.49880627 0.0015014224 0.20476651, -0.50011855 0.0027450137 0.20552427, -0.50161582 0.003668841 0.20638883, -0.50324029 0.0042379461 0.20732677, -0.50492996 0.0044300221 0.20830238, -0.50661939 0.0042378269 0.20927775, -0.5082441 0.0036686622 0.21021575, -0.50974137 0.0027444921 0.2110799, -0.51105374 0.0015008561 0.21183759, -0.51213062 -1.4502555e-05 0.21245924, -0.51293105 -0.0017434098 0.21292117, -0.51342374 -0.0036194511 0.21320575, -0.51359004 -0.0055704005 0.2133016, -0.49843466 -0.0055467673 -0.20455107, -0.49859747 -0.007215593 -0.20464525, -0.51689869 -0.0072175749 -0.17294633, -0.51737922 -0.0088027157 -0.17322373, -0.49907795 -0.0088008232 -0.20492259, -0.51815301 -0.010224659 -0.17367062, -0.49985173 -0.010222856 -0.20536932, -0.51918143 -0.011412252 -0.17426443, -0.50088018 -0.011410404 -0.20596313, -0.52041298 -0.01230577 -0.17497548, -0.50211173 -0.012303833 -0.20667428, -0.5217858 -0.01286051 -0.17576835, -0.50348455 -0.012858529 -0.20746687, -0.52323109 -0.013048518 -0.17660275, -0.50492984 -0.013046611 -0.2083014, -0.52467638 -0.012860361 -0.17743728, -0.50637513 -0.012858424 -0.20913583, -0.5260492 -0.012305725 -0.17822975, -0.50774807 -0.012303744 -0.2099286, -0.52728081 -0.011412103 -0.17894059, -0.5089795 -0.01141024 -0.21063939, -0.52830929 -0.010224406 -0.17953432, -0.51000804 -0.010222573 -0.21123305, -0.52908307 -0.0088024773 -0.17998108, -0.51078182 -0.0088006444 -0.21167988, -0.52956337 -0.0072172321 -0.18025824, -0.51126224 -0.0072153993 -0.2119571, -0.51142514 -0.0055463351 -0.21205109, -0.5135901 -0.0055463202 -0.21330076, -0.53172493 -0.0035973676 -0.18150613, -0.51342368 -0.0035953857 -0.21320489, -0.53123224 -0.0017214157 -0.18122137, -0.51293099 -0.0017194636 -0.21292025, -0.53043193 7.4021518e-06 -0.1807594, -0.51213062 9.3095005e-06 -0.21245807, -0.52935499 0.001522731 -0.18013743, -0.51105368 0.001524698 -0.21183613, -0.52804261 0.0027664416 -0.17937961, -0.50974137 0.0027683936 -0.21107841, -0.52654535 0.0036904328 -0.1785152, -0.5082441 0.0036922954 -0.2102139, -0.52492064 0.0042594783 -0.17757726, -0.50661951 0.0042613707 -0.20927596, -0.52323133 0.0044515096 -0.17660171, -0.50492996 0.0044533722 -0.20830056, -0.52154171 0.0042593889 -0.17562634, -0.50324041 0.0042612664 -0.20732498, -0.51991707 0.0036902241 -0.17468834, -0.50161576 0.0036921315 -0.20638719, -0.5184198 0.0027661137 -0.17382383, -0.50011855 0.0027679466 -0.20552275, -0.51710755 0.0015224926 -0.17306623, -0.49880627 0.0015243553 -0.20476502, -0.51603049 7.0594251e-06 -0.17244461, -0.49772915 8.9518726e-06 -0.20414335, -0.51523006 -0.0017218627 -0.17198274, -0.49692893 -0.0017199256 -0.20368141, -0.51473725 -0.0035977848 -0.1716983, -0.49643597 -0.0035959072 -0.20339701, -0.49626955 -0.0055468269 -0.20330095, -0.53108877 0.0043667071 0.13393387, -0.53864729 -0.00065172091 -0.12741134, -0.53916878 -0.0017231442 -0.15160203, -0.53893811 -0.0012093671 -0.12582323, -0.52992994 0.0044339113 0.13400102, -0.53856927 -0.0005155541 -0.12029585, -0.53864729 -0.000665728 0.12058857, -0.53811163 0.00018454716 0.1190207, -0.53884935 -0.001030419 -0.12155554, -0.52992982 -0.015567053 0.15160239, -0.53188068 -0.015374903 0.1516026, -0.53740674 0.0010746829 0.1302627, -0.53375667 -0.014805827 0.1516026, -0.5318808 0.0042579286 -0.1516017, -0.53375679 0.0036889426 -0.15160179, -0.53319281 0.0039018653 -0.13344783, -0.53815848 0.00013078377 -0.11912706, -0.53770608 0.00072230026 0.11821979, -0.53548557 -0.013881732 0.1516026, -0.53108877 0.0043806545 -0.1140663, -0.53222448 0.0041811578 -0.11426666, -0.53160447 0.0042937361 0.11414239, -0.53824466 5.7332218e-06 -0.15160203, -0.53700083 -0.01263817 0.1516026, -0.52992994 0.0044480078 -0.1139991, -0.52993006 0.0044351928 0.11400095, -0.53824455 -0.011122916 0.1516026, -0.52992994 0.0044500791 -0.15160155, -0.53160459 0.0043078028 -0.13385797, -0.53770602 0.00073617324 -0.12978041, -0.53811163 0.00019849464 -0.12897938, -0.53319281 0.0038877688 0.11455205, -0.53916866 -0.0093939491 0.15160283, -0.53470486 0.0032215677 0.11524132, -0.53371817 0.0037026964 -0.11475271, -0.53606671 0.0023305826 0.11621338, -0.53512865 0.0029904954 -0.11549971, -0.53721875 0.0012813173 0.11747149, -0.53637296 0.0020957254 -0.11649573, -0.53815836 0.00011689588 0.1288732, -0.5374068 0.0010887943 -0.11773747, -0.53637302 0.002081912 0.13150463, -0.53512865 0.0029765181 0.13250047, -0.53371799 0.0036887489 0.13324746, -0.5322246 0.0041671656 0.13373336, -0.53973782 -0.0075179823 0.15160283, -0.52992994 0.0044490211 -0.13399923, -0.53470486 0.0032355152 -0.13275862, -0.53606671 0.0023444854 -0.13178656, -0.53548557 0.0027646534 -0.15160179, -0.53721875 0.0012952797 -0.13052869, -0.53700101 0.001521226 -0.15160179, -0.53900671 -0.0013691075 0.12509406, -0.5390417 -0.0014451481 0.1237092, -0.53973782 -0.0035989918 -0.15160203, -0.53884947 -0.0010444559 0.12644434, -0.53856927 -0.00052954629 0.12770423, -0.5390417 -0.0014312007 -0.12429088, -0.53900683 -0.0013550557 -0.12290612, -0.53893805 -0.0012233891 0.12217692, -0.49843523 0.064453304 -0.20454711, -0.49859792 0.062784389 -0.20464125, -0.51689917 0.062782526 -0.17294234, -0.51737958 0.061197247 -0.17321983, -0.49907842 0.061199199 -0.20491862, -0.51815337 0.059775259 -0.17366663, -0.49985203 0.059777122 -0.20536542, -0.51918203 0.058587816 -0.1742605, -0.50088066 0.058589619 -0.20595929, -0.52041346 0.057694193 -0.17497173, -0.50211215 0.057696175 -0.20667028, -0.52178639 0.057139572 -0.17576423, -0.50348502 0.057141509 -0.20746309, -0.52323157 0.056951519 -0.17659885, -0.50493032 0.056953337 -0.20829737, -0.50637561 0.057141479 -0.20913193, -0.52467692 0.057139691 -0.17743322, -0.52604961 0.057694312 -0.17822579, -0.50774837 0.057696279 -0.20992449, -0.52728122 0.058587965 -0.17893675, -0.5089801 0.058589812 -0.21063542, -0.51000851 0.059777495 -0.21122926, -0.52830976 0.059775587 -0.17953056, -0.52908355 0.061197545 -0.17997709, -0.51078242 0.061199542 -0.21167594, -0.5112626 0.062784731 -0.21195319, -0.52956396 0.062782884 -0.1802544, -0.51142555 0.064453632 -0.2120471, -0.51342422 0.066404641 -0.21320087, -0.53172547 0.066402763 -0.18150213, -0.51359051 0.064453721 -0.21329695, -0.51293147 0.068280578 -0.21291625, -0.53123271 0.0682787 -0.18121737, -0.51213104 0.070009351 -0.21245423, -0.53043228 0.070007384 -0.1807555, -0.51105404 0.071524724 -0.21183223, -0.52935541 0.071522862 -0.18013337, -0.50974166 0.072768331 -0.21107441, -0.52804297 0.072766483 -0.17937568, -0.50824451 0.073692322 -0.21021, -0.52654576 0.073690414 -0.17851117, -0.50661981 0.074261308 -0.20927206, -0.52492112 0.07425949 -0.17757311, -0.50493038 0.074453458 -0.20829651, -0.52323163 0.074451596 -0.17659786, -0.50324082 0.074261248 -0.20732108, -0.52154219 0.074259371 -0.17562243, -0.50161636 0.073692143 -0.2063832, -0.51991743 0.073690236 -0.17468449, -0.50011891 0.072768033 -0.20551875, -0.51842022 0.072766125 -0.17382005, -0.49880677 0.071524456 -0.20476103, -0.5171079 0.071522474 -0.17306238, -0.49772963 0.070008934 -0.20413929, -0.51603091 0.070007026 -0.17244065, -0.49692926 0.068280071 -0.20367745, -0.5152306 0.068278193 -0.17197862, -0.49643657 0.066404164 -0.2033931, -0.51473778 0.066402256 -0.17169425, -0.49627003 0.064453244 -0.20329699, -0.42099985 -0.0035993047 -0.13380745, -0.42099985 -0.0055502839 -0.13399971, -0.51992989 -0.0055508353 -0.13399953, -0.51992989 -0.0035998859 -0.13380754, -0.42099988 -0.0017234124 -0.13323832, -0.51992989 -0.0017240085 -0.13323832, -0.42099988 5.3755939e-06 -0.13231421, -0.51992995 4.7795475e-06 -0.13231397, -0.42099991 0.0015206747 -0.13107038, -0.51992989 0.0015201233 -0.13107038, -0.42099988 0.0027642213 -0.12955511, -0.51993006 0.0027636401 -0.12955511, -0.42099985 0.0036881976 -0.12782604, -0.51992995 0.0036876164 -0.12782592, -0.42100003 0.0042571984 -0.12595004, -0.51992995 0.0042565726 -0.12595004, -0.42099991 0.0044492446 -0.12399921, -0.51993006 0.0044486634 -0.12399906, -0.42099991 0.00425696 -0.12204808, -0.51992995 0.0042563789 -0.12204823, -0.42099991 0.0036878549 -0.12017232, -0.51993006 0.0036872439 -0.12017232, -0.42099988 0.0027636252 -0.11844358, -0.51992995 0.0027629845 -0.11844364, -0.42099988 0.0015199147 -0.11692813, -0.51992995 0.001519274 -0.11692816, -0.42099988 4.5113266e-06 -0.11568472, -0.51992995 3.9003789e-06 -0.11568472, -0.42099988 -0.0017244704 -0.11476076, -0.51992989 -0.0017251261 -0.11476082, -0.42099985 -0.0036004819 -0.11419162, -0.51992989 -0.003601063 -0.11419177, -0.42099985 -0.0055512972 -0.11399969, -0.51992989 -0.0055519231 -0.11399975, -0.53978175 0.062730849 -0.12227818, -0.5399304 0.064448535 -0.12399575, -0.53992993 0.0044485144 -0.12399921, -0.53973788 0.0044483654 -0.12204823, -0.5393061 0.06097063 -0.12051836, -0.53916878 0.0044481866 -0.1201722, -0.5384801 0.059261616 -0.11880937, -0.53824466 0.0044481419 -0.11844343, -0.53736842 0.057764348 -0.11731234, -0.53700101 0.0044481121 -0.11692801, -0.53603119 0.05652478 -0.11607283, -0.53548557 0.0044480227 -0.11568448, -0.53452814 0.055567708 -0.11511594, -0.53375679 0.0044480078 -0.11476043, -0.53307784 0.054956254 -0.11450449, -0.5318808 0.004447978 -0.11419123, -0.53148341 0.054569449 -0.11411756, -0.52993035 0.054448094 -0.11399624, -0.52834725 0.054574158 -0.11412245, -0.52797908 0.0044480227 -0.11419123, -0.52672243 0.05497646 -0.11452472, -0.52610308 0.0044479631 -0.11476043, -0.52512693 0.055677231 -0.1152254, -0.52437431 0.0044480972 -0.11568448, -0.52376831 0.056572195 -0.11612019, -0.52285892 0.0044482462 -0.11692792, -0.52253306 0.057718929 -0.11726704, -0.52161527 0.0044483356 -0.11844334, -0.52147746 0.059105095 -0.11865264, -0.52069104 0.004448276 -0.12017232, -0.52065939 0.060700145 -0.12024775, -0.52012211 0.0044485442 -0.12204808, -0.52010363 0.062595069 -0.12214234, -0.5199303 0.064448714 -0.12399575, -0.49843505 0.064430267 0.20455572, -0.49859801 0.066099212 0.20464984, -0.49907836 0.067684442 0.2049273, -0.49985215 0.069106385 0.20537376, -0.50088072 0.070293888 0.20596799, -0.50211215 0.071187317 0.20667908, -0.50348508 0.071742013 0.20747164, -0.50493038 0.071930066 0.20830584, -0.50637573 0.071741939 0.20914063, -0.50774848 0.071187183 0.20993304, -0.50897998 0.070293546 0.2106441, -0.51000857 0.069106102 0.21123782, -0.51078218 0.067683861 0.2116845, -0.51126271 0.06609872 0.21196175, -0.51142555 0.06442973 0.21205574, -0.52993041 0.074433029 0.15160748, -0.52797955 0.074240893 0.15160748, -0.52797955 0.074258059 -0.15159774, -0.52249205 0.057751175 0.11732009, -0.52010363 0.062581033 0.12585771, -0.5199303 0.064434677 0.12400439, -0.52065939 0.060686257 0.12775254, -0.52147752 0.059091087 0.12934738, -0.52253312 0.057705071 0.13073322, -0.52376831 0.056558248 0.1318799, -0.5213806 0.059262183 -0.1291827, -0.52512693 0.055663344 0.13277471, -0.52672261 0.054962661 0.13347539, -0.52834725 0.054560181 0.13387772, -0.52382934 0.056511756 0.11608055, -0.52533233 0.055554863 0.11512366, -0.5213806 0.059248295 0.11881727, -0.52837718 0.054570433 -0.13387489, -0.52993029 0.054449197 -0.13399637, -0.52055436 0.06095716 0.12052649, -0.52007896 0.06271714 0.12228668, -0.52678269 0.054957416 -0.13348791, -0.52533233 0.055568811 -0.13287652, -0.52382934 0.056525704 -0.13191938, -0.52249205 0.057765123 -0.13068008, -0.52055448 0.060971107 -0.12747359, -0.52007896 0.062731057 -0.12571353, -0.52837712 0.054556426 0.1141251, -0.52993023 0.05443516 0.11400375, -0.52993035 0.054434057 0.13400385, -0.52678269 0.054943439 0.11451235, -0.52012247 0.066401064 -0.15159827, -0.52012259 0.066384017 0.15160719, -0.52069145 0.068259984 0.15160728, -0.52069145 0.068277031 -0.15159827, -0.5216158 0.069988847 0.15160719, -0.52161556 0.070005894 -0.15159795, -0.52285928 0.071504116 0.15160748, -0.52285928 0.071521223 -0.15159789, -0.52437472 0.072747767 0.15160748, -0.52437472 0.072764933 -0.15159774, -0.5261035 0.073671818 0.15160748, -0.52610356 0.073688954 -0.15159774, -0.52993053 0.074450165 -0.15159774, -0.5134241 0.062478807 0.21320954, -0.51359051 0.06442973 0.21330565, -0.51293141 0.060602959 0.2129249, -0.51213104 0.058874127 0.21246269, -0.51105404 0.057358738 0.21184078, -0.50974172 0.056115177 0.21108299, -0.5082444 0.055191036 0.21021855, -0.50661981 0.05462217 0.20928061, -0.50493026 0.054430064 0.208305, -0.5032407 0.054622199 0.20732963, -0.50161612 0.055191334 0.20639169, -0.50011885 0.056115489 0.20552734, -0.49880651 0.05735917 0.20476973, -0.49772954 0.058874588 0.2041482, -0.49692926 0.060603376 0.20368612, -0.49643654 0.062479448 0.20340171, -0.49627006 0.064430386 0.2033056, -0.42099985 -0.0075162239 0.13380811, -0.51992989 -0.0055659153 0.1340006, -0.51993001 -0.0075167902 0.13380826, -0.42099985 -0.0055653639 0.13400039, -0.42099991 -0.0093919374 0.13323909, -0.51992983 -0.0093926527 0.13323909, -0.4209998 -0.011120934 0.13231477, -0.51992983 -0.011121485 0.13231477, -0.42099991 -0.012636203 0.13107118, -0.51992983 -0.012636874 0.13107094, -0.42099991 -0.013879705 0.12955567, -0.51992983 -0.013880391 0.12955552, -0.4209998 -0.014803786 0.12782678, -0.51992995 -0.014804248 0.12782669, -0.4209998 -0.015372682 0.12595093, -0.51992983 -0.015373353 0.12595081, -0.42099991 -0.015564654 0.12399983, -0.51992983 -0.015565339 0.12399983, -0.4209998 -0.015372548 0.12204888, -0.51992983 -0.015373055 0.122049, -0.4209998 -0.014803279 0.12017319, -0.51992983 -0.014803935 0.12017316, -0.4209998 -0.013879154 0.11844423, -0.51992995 -0.013879646 0.11844423, -0.42099977 -0.012635533 0.11692876, -0.51992995 -0.01263598 0.11692896, -0.4209998 -0.011119965 0.11568537, -0.51992983 -0.011120547 0.11568537, -0.4209998 -0.0093910135 0.11476144, -0.51992983 -0.0093916543 0.11476144, -0.4209998 -0.0075151362 0.11419237, -0.51993001 -0.0075157024 0.11419246, -0.42099985 -0.0055641122 0.11400053, -0.51992989 -0.0055648573 0.11400044, -0.53978175 0.062716752 0.12572181, -0.53993028 0.064434588 0.12400439, -0.53992993 0.004434552 0.12400103, -0.53973788 0.0044343881 0.12595201, -0.5393061 0.060956683 0.12748179, -0.53916878 0.0044343136 0.12782788, -0.53847998 0.059247579 0.12919071, -0.53824466 0.004434105 0.1295566, -0.5373686 0.05775037 0.13068792, -0.53700107 0.0044341497 0.13107187, -0.53603119 0.056510713 0.13192731, -0.53548568 0.004434105 0.13231575, -0.5345282 0.05555388 0.1328842, -0.53375679 0.0044340454 0.13323972, -0.53307796 0.054942455 0.13349551, -0.5318808 0.0044340305 0.13380894, -0.53148341 0.054555383 0.13388258, -0.52797908 0.0044340454 0.13380891, -0.52610308 0.0044340752 0.13323972, -0.52437431 0.004434105 0.13231561, -0.52285892 0.0044341497 0.13107201, -0.52161533 0.004434254 0.12955651, -0.5206911 0.004434403 0.12782767, -0.52012211 0.0044344477 0.12595186, -0.51992995 0.0044346564 0.12400103, -0.52242994 -0.005565796 0.13150048, -0.42099985 -0.0055651255 0.13150048, -0.52246898 -0.0063317157 0.13146123, -0.52259231 -0.0071178563 0.13133797, -0.42099985 -0.0072340555 0.13131234, -0.52293074 -0.0082604773 0.13099954, -0.42099985 -0.0088192858 0.13075742, -0.52353859 -0.0094902404 0.13039139, -0.42099985 -0.010241229 0.12986404, -0.52439982 -0.010632325 0.12953004, -0.4209998 -0.011428703 0.12867615, -0.52551085 -0.011625592 0.12841904, -0.4209998 -0.012322176 0.1272541, -0.52684683 -0.012402583 0.12708306, -0.4209998 -0.012876827 0.12566891, -0.5283199 -0.01289073 0.12561002, -0.52992982 -0.013065327 0.12399983, -0.4209998 -0.013064701 0.1240001, -0.528992 -0.013006423 0.12306225, -0.4209998 -0.012876648 0.12233105, -0.52802795 -0.012820173 0.12209815, -0.4209998 -0.012321744 0.12074587, -0.52649146 -0.012230609 0.12056184, -0.52514166 -0.011337701 0.11921188, -0.4209998 -0.011428136 0.11932379, -0.52416557 -0.01036324 0.11823565, -0.4209998 -0.010240529 0.11813644, -0.52339017 -0.0092365034 0.11746028, -0.42099983 -0.0088185109 0.11724278, -0.52284288 -0.0080194362 0.11691305, -0.42099994 -0.007233236 0.1166884, -0.52252835 -0.0067763515 0.11659887, -0.42099985 -0.0055643059 0.1165005, -0.52242982 -0.0055649169 0.1165005, -0.52242994 -0.0055518039 -0.11649975, -0.42099985 -0.005551178 -0.11649975, -0.52246904 -0.006317798 -0.11653891, -0.52259231 -0.0071039088 -0.11666217, -0.42099983 -0.007220123 -0.1166878, -0.52293068 -0.0082465149 -0.1170007, -0.4209998 -0.0088053681 -0.11724257, -0.52353859 -0.0094761737 -0.11760861, -0.4209998 -0.010227297 -0.11813626, -0.52439994 -0.010618243 -0.11847004, -0.4209998 -0.011414874 -0.11932415, -0.52551097 -0.011611629 -0.11958116, -0.4209998 -0.012308214 -0.12074584, -0.52684683 -0.012388635 -0.12091693, -0.4209998 -0.01286282 -0.12233117, -0.5283199 -0.012876634 -0.12239018, -0.52992982 -0.013051379 -0.12400001, -0.4209998 -0.013050813 -0.12400025, -0.52899188 -0.012992594 -0.12493798, -0.4209998 -0.012862671 -0.12566897, -0.52802795 -0.0128063 -0.125902, -0.4209998 -0.012307841 -0.12725419, -0.52649146 -0.012216587 -0.1274384, -0.52514166 -0.011323754 -0.12878811, -0.4209998 -0.011414189 -0.12867618, -0.52416557 -0.010349322 -0.12976432, -0.4209998 -0.010226626 -0.12986371, -0.52339 -0.0092225708 -0.13053966, -0.42099983 -0.0088045038 -0.13075709, -0.52284282 -0.0080055334 -0.13108706, -0.42099985 -0.0072193034 -0.13131177, -0.52252841 -0.0067624338 -0.1314013, -0.42099985 -0.0055503733 -0.13149977, -0.52242982 -0.0055510886 -0.13149977, -0.53262514 0.057448979 -0.11699694, -0.53385478 0.058056947 -0.11760467, -0.5314824 0.057110485 -0.11665851, -0.53069621 0.056987371 -0.11653545, -0.53499669 0.058918115 -0.11846614, -0.5359903 0.060029294 -0.11957696, -0.5367673 0.061365303 -0.12091294, -0.53725559 0.062838525 -0.12238583, -0.53725559 0.062824547 0.12561405, -0.53724223 0.062764049 0.15160683, -0.5367673 0.061351296 0.12708721, -0.5359903 0.060015436 0.12842312, -0.53668755 0.06117883 0.15160689, -0.53499681 0.058904286 0.1295341, -0.53579408 0.059756812 0.15160668, -0.53385472 0.05804294 0.13039535, -0.53460646 0.058569308 0.15160668, -0.53262502 0.057434972 0.13100299, -0.53318447 0.057675805 0.15160662, -0.5314824 0.057096537 0.13134164, -0.53159916 0.057121005 0.15160644, -0.53069609 0.056973305 0.13146481, -0.53318447 0.057692882 -0.15159869, -0.53460646 0.058586415 -0.15159857, -0.53159922 0.057138201 -0.15159869, -0.53724211 0.062781125 -0.15159854, -0.53668767 0.061196055 -0.15159854, -0.52993041 0.056950238 -0.15159857, -0.52993041 0.056948211 -0.11649612, -0.52993029 0.056932982 0.15160662, -0.52993029 0.056934115 0.13150379, -0.53579408 0.059773978 -0.15159857, -0.52992994 0.0019341819 0.13150081, -0.52915663 0.0018941276 0.13146073, -0.52992994 0.0019329898 0.15160349, -0.52826101 0.0017449819 0.15160349, -0.52837998 0.0017723255 0.13133895, -0.52708977 0.0013755225 0.13094205, -0.52667576 0.0011902563 0.15160349, -0.52576464 0.00067121908 0.13023803, -0.52525365 0.0002967529 0.15160331, -0.52462661 -0.00026230887 0.12930405, -0.52406615 -0.00089082494 0.15160322, -0.52402139 -0.00094627216 0.12990916, -0.52349591 -0.0017118342 0.13043481, -0.52317262 -0.0023128428 0.15160298, -0.52290606 -0.0029359944 0.13102436, -0.52261794 -0.0038980134 0.15160298, -0.5225476 -0.0042422302 0.13138279, -0.52992994 0.0019480698 -0.11649922, -0.52915663 0.0019080751 -0.11653942, -0.52837998 0.0017861985 -0.11666113, -0.52708989 0.0013896637 -0.1170578, -0.52576464 0.00068522617 -0.11776233, -0.52462661 -0.00024843588 -0.11869609, -0.52402145 -0.00093225017 -0.11809093, -0.52369303 -0.0013996251 0.11776391, -0.52349591 -0.0016977377 -0.11756554, -0.52298844 -0.0027248897 0.1170592, -0.52290606 -0.0029219873 -0.11697581, -0.52259183 -0.0040150769 0.11666235, -0.5225476 -0.0042282082 -0.11661723, -0.52246988 -0.0047916062 0.11654046, -0.52369297 -0.0013856329 -0.13023636, -0.52298844 -0.0027108826 -0.13094115, -0.52259183 -0.0040009357 -0.13133773, -0.52246988 -0.004777614 -0.13145971, -0.52261788 -0.007218767 -0.15160233, -0.52317262 -0.0088039823 -0.15160233, -0.52406603 -0.010226 -0.15160254, -0.52525359 -0.011413682 -0.15160254, -0.52667564 -0.012307186 -0.15160263, -0.52826089 -0.012861837 -0.15160263, -0.52992982 -0.013049949 -0.15160254, -0.53099984 -0.012988675 0.12507007, -0.53099996 -0.012988571 0.12292981, -0.53114146 0.001835715 0.13140234, -0.53238434 0.0015211068 0.13108778, -0.53159869 0.0017448775 0.15160349, -0.53360146 0.00097411498 0.1305407, -0.53318411 0.001190301 0.15160349, -0.53472811 0.00019844994 0.12976497, -0.53460604 0.0002966933 0.15160331, -0.53570247 -0.00077748671 0.12878892, -0.53579372 -0.00089094415 0.15160331, -0.53659534 -0.0021271743 0.12743902, -0.53668714 -0.0023129024 0.15160322, -0.53718472 -0.003663782 0.12590244, -0.53737104 -0.0046275146 0.12493837, -0.53724182 -0.0038982369 0.15160298, -0.53737104 -0.0046137162 -0.12306187, -0.53718477 -0.0036497451 -0.12209776, -0.53099996 -0.012974743 -0.12293023, -0.53659534 -0.0021132864 -0.12056115, -0.53570253 -0.00076356903 -0.11921126, -0.53472811 0.00021244213 -0.1182352, -0.5336014 0.00098800287 -0.11745936, -0.53238434 0.001535099 -0.11691248, -0.53114146 0.0018496625 -0.11659768, -0.53099984 -0.012974683 -0.12507021, -0.53159875 -0.012861822 -0.15160263, -0.53318399 -0.012307156 -0.15160263, -0.53460604 -0.011413593 -0.15160254, -0.5357936 -0.010226179 -0.15160239, -0.53668708 -0.0088040568 -0.15160233, -0.53724182 -0.0072188713 -0.15160239, -0.52248925 0.063510686 -0.12305781, -0.52267545 0.06254667 -0.12209401, -0.52326494 0.061009999 -0.12055752, -0.52415758 0.059660044 -0.1192078, -0.52513212 0.058683958 -0.11823159, -0.52625877 0.057908352 -0.11745623, -0.52747583 0.057361182 -0.11690921, -0.52871877 0.057046589 -0.11659476, -0.52261835 0.062781334 -0.15159854, -0.52317303 0.061196055 -0.15159854, -0.52406651 0.059774037 -0.15159857, -0.52525401 0.058586475 -0.15159857, -0.52667612 0.057692882 -0.15159857, -0.52826148 0.057138171 -0.15159869, -0.52317303 0.061178919 0.15160689, -0.52261835 0.062764227 0.15160689, -0.52267534 0.062532544 0.12590623, -0.5282613 0.057121005 0.15160662, -0.52871889 0.057032701 0.13140532, -0.52248913 0.063496739 0.12494206, -0.52667606 0.057675775 0.15160668, -0.52747583 0.057347234 0.13109097, -0.52525407 0.058569249 0.15160668, -0.52625877 0.057894375 0.13054377, -0.52513212 0.05867004 0.12976834, -0.5241577 0.059646215 0.12879229, -0.52406651 0.059756871 0.15160668, -0.52326494 0.060996111 0.12744263, -0.42099985 -0.0038814433 -0.13131166, -0.42099985 -0.002296228 -0.13075683, -0.42099985 -0.00087435916 -0.12986311, -0.42099985 0.00031327829 -0.12867558, -0.42099988 0.0012066476 -0.12725341, -0.42099991 0.0017612092 -0.12566814, -0.42099988 0.0019493066 -0.12399921, -0.52246994 0.0019086115 -0.12322611, -0.52259189 0.0017866157 -0.12244934, -0.42099988 0.0017610751 -0.12233049, -0.5229885 0.0013898127 -0.12115923, -0.42099991 0.0012062602 -0.12074524, -0.52369303 0.00068528578 -0.11983398, -0.42099988 0.00031266734 -0.1193234, -0.42099985 -0.0008748807 -0.11813575, -0.42099985 -0.0022970475 -0.11724231, -0.42099985 -0.0038822331 -0.11668774, -0.42099985 -0.0038954355 0.11668864, -0.42099985 -0.0023101903 0.11724329, -0.42099997 -0.00088817254 0.11813697, -0.42099988 0.00029922649 0.11932459, -0.42099988 0.0011928193 0.12074667, -0.42099991 0.001747366 0.12233201, -0.42099988 0.0019353591 0.12400088, -0.52246988 0.0018946938 0.12477419, -0.52259189 0.0017725937 0.12555075, -0.42099985 0.0017470978 0.12566981, -0.5229885 0.0013759248 0.12684095, -0.42099985 0.0011921935 0.12725493, -0.52369303 0.00067139789 0.12816617, -0.42099988 0.00029877946 0.12867683, -0.42099985 -0.000889007 0.12986463, -0.42099985 -0.0023109801 0.13075799, -0.42099985 -0.0038962699 0.13131258, -0.42100003 0.023448687 -0.11399806, -0.41799989 0.0044486783 -0.1139991, -0.41800013 0.023448776 -0.11399812, -0.42099991 0.0044486336 -0.1139991, -0.42100003 0.023435872 0.11400208, -0.41799989 0.0044358335 0.11400095, -0.42099991 0.0044358186 0.11400113, -0.41800013 0.023435976 0.11400208, -0.52160472 0.004246261 0.1184454, -0.5206911 0.0044348203 0.12017402, -0.52068633 0.0043496452 0.12017423, -0.52003223 0.0042720102 0.12205005, -0.52004975 0.0042844526 0.12205005, -0.52067202 0.0042655133 0.1201742, -0.52012092 0.0044132285 0.12205005, -0.52011734 0.0043919794 0.12205005, -0.52200097 0.0023639761 0.11692971, -0.52279884 0.0014456622 0.11589509, -0.52221978 0.0026088767 0.11692989, -0.52124757 0.003384199 0.11844531, -0.52112156 0.0032431893 0.11844507, -0.52098078 0.0031173341 0.11844531, -0.52046829 0.0038966499 0.1201742, -0.52011126 0.0043712966 0.12205005, -0.52040452 0.003839653 0.1201742, -0.52284044 0.0041070096 0.11692971, -0.5228588 0.0044348799 0.11692989, -0.52161533 0.0044349693 0.11844531, -0.5203349 0.003790345 0.1201742, -0.52157301 0.0040599667 0.11844531, -0.52001339 0.0042616837 0.12205011, -0.52064842 0.0041834973 0.1201742, -0.52175611 0.002145078 0.11692971, -0.52244592 0.0010676496 0.11585197, -0.52668899 0.0038953982 0.11453328, -0.52797908 0.0044351481 0.11419305, -0.52610308 0.0044351034 0.11476228, -0.52404732 0.0039712898 0.11589554, -0.52437431 0.0044351332 0.11568627, -0.52082652 0.0030079596 0.11844531, -0.52826411 0.0042954795 0.11414048, -0.52010304 0.0043513887 0.12205005, -0.52026027 0.0037490986 0.12017423, -0.52278548 0.0037832372 0.11692989, -0.52497393 0.003866788 0.11529729, -0.5254212 0.0033609085 0.11502317, -0.51999336 0.0042533688 0.12205005, -0.52152067 0.0038783215 0.11844531, -0.52148837 0.0019550435 0.11692971, -0.52209932 0.00065452978 0.1157437, -0.52061576 0.0041045658 0.1201742, -0.52066106 0.0029165857 0.11844531, -0.52396929 0.0035131089 0.11589536, -0.52480537 0.0030222647 0.11529717, -0.5201813 0.0037164502 0.12017402, -0.52009267 0.0043325536 0.12205005, -0.51997268 0.0042474084 0.12205005, -0.52120072 0.0017961375 0.11692971, -0.52160573 -2.3443252e-05 0.11548164, -0.52269453 0.0034675859 0.11692989, -0.52144831 0.0037037395 0.11844531, -0.52048653 0.0028441213 0.11844507, -0.52057451 0.004029911 0.12017423, -0.52384084 0.0030667298 0.11589536, -0.52420861 0.0026367269 0.11555794, -0.52009934 0.0036927424 0.1201742, -0.5199514 0.0042438023 0.12205005, -0.51992995 0.0042426102 0.12205011, -0.51992995 0.0036737435 0.1201742, -0.52089721 0.0016704313 0.11692965, -0.52008027 0.0043149702 0.12205011, -0.52256876 0.0031641237 0.11692971, -0.52030492 0.0027919225 0.11844531, -0.521357 0.0035383217 0.11844531, -0.52001506 0.0036783777 0.1201742, -0.51992995 0.0027497075 0.11844507, -0.52052504 0.0039603226 0.1201742, -0.52129841 0.00052423403 0.11589497, -0.52118212 -0.00071983412 0.11517152, -0.52058166 0.0015794747 0.11692971, -0.52006584 0.004298877 0.12205011, -0.52240986 0.0028766654 0.11692989, -0.52011859 0.0027602129 0.11844507, -0.51992989 -0.003613878 0.11419258, -0.5200696 -0.0038994439 0.11413994, -0.52047068 -0.0023211576 0.11453393, -0.51992995 0.0015061013 0.11692971, -0.51992989 -0.0017380156 0.11476186, -0.52085203 0.0003956072 0.11589509, -0.52025789 0.0015244596 0.11692971, -0.52343816 0.0022306405 0.11589512, -0.52352446 0.0021142475 0.1157991, -0.52105939 -0.00051354244 0.11529705, -0.52079451 -0.0014974065 0.11483756, -0.52012211 0.004434716 0.12205011, -0.52039373 0.00031785294 0.11589509, -0.51992989 -9.1828406e-06 0.11568597, -0.52049816 -0.00060888007 0.11529705, -0.53612298 0.0028187595 0.11621338, -0.53700107 0.0044349395 0.11692989, -0.53548557 0.0044349395 0.11568627, -0.5318808 0.0044350736 0.11419305, -0.53691655 0.0027393363 0.11692971, -0.53799969 0.0026311688 0.11821979, -0.53824466 0.0044347905 0.11844531, -0.53375679 0.0044350885 0.11476228, -0.53907365 0.0025239848 0.12017402, -0.53916878 0.0044348352 0.12017423, -0.53773129 0.00084536895 0.11821976, -0.53963989 0.0024672411 0.12204996, -0.53973788 0.0044346116 0.12205005, -0.53878921 0.00063193962 0.12017402, -0.53982681 0.0024484508 0.12370926, -0.53934693 0.00051934645 0.12204972, -0.53977138 0.0024539195 0.12509429, -0.53953117 0.00048213825 0.12370926, -0.53952938 0.0024779551 0.12644476, -0.53947651 0.00049294159 0.12509406, -0.53912348 0.0025185011 0.12770447, -0.5392381 0.00054105744 0.1264447, -0.53856999 0.0025736801 0.12887326, -0.53883833 0.00062168762 0.12770447, -0.53763872 0.0026664846 0.13026285, -0.53829306 0.00073152408 0.1288732, -0.53691655 0.0027385913 0.13107201, -0.53540862 0.002889093 0.13231537, -0.52006572 0.0042985789 0.12595177, -0.52008015 0.0043147318 0.12595201, -0.52278548 0.0037824623 0.13107187, -0.52284056 0.0041063689 0.13107213, -0.52427167 0.0039449893 0.13226494, -0.52052504 0.0039598309 0.12782767, -0.52046812 0.0038961582 0.12782767, -0.52405399 0.0029911511 0.13226494, -0.52510816 0.003194835 0.1328406, -0.52440935 0.0027722828 0.13252896, -0.52182561 0.00049770996 0.1322647, -0.52238727 0.0009999387 0.13216338, -0.52188075 0.00036795065 0.13235891, -0.52418959 0.0034618936 0.13226515, -0.52148819 0.0019542687 0.13107187, -0.52068633 0.0043491982 0.12782767, -0.52827758 0.0042966418 0.13386366, -0.52040452 0.0038393252 0.12782767, -0.52112168 0.0032425784 0.12955651, -0.5216046 0.0042455457 0.1295566, -0.52098078 0.0031166039 0.12955651, -0.52157301 0.0040592514 0.1295566, -0.52670878 0.0039010756 0.13347492, -0.52082664 0.0030072294 0.1295566, -0.52175611 0.0021442883 0.13107201, -0.52269465 0.0034669153 0.13107187, -0.52120084 0.0017954223 0.13107187, -0.5201208 0.0044129454 0.12595201, -0.52004975 0.0042842291 0.12595201, -0.52067214 0.0042650811 0.12782767, -0.52137291 0.00031025335 0.13226473, -0.52117467 -0.00073391572 0.13283595, -0.52152056 0.0038776211 0.1295566, -0.5203349 0.0037899278 0.12782767, -0.52256888 0.0031634681 0.13107213, -0.52373236 0.0022821538 0.13226473, -0.52066118 0.0029158555 0.1295566, -0.52011734 0.0043916963 0.12595201, -0.52111477 -0.00075669959 0.13284039, -0.52062142 -0.0019118227 0.13332391, -0.52064842 0.00418308 0.12782767, -0.52089721 0.0016696565 0.13107187, -0.52144831 0.0037030242 0.1295566, -0.52003223 0.0042717569 0.12595201, -0.5209021 0.00017454848 0.1322647, -0.52240998 0.0028758757 0.13107187, -0.52011126 0.0043710582 0.12595186, -0.52026027 0.0037486814 0.12782767, -0.52061576 0.0041041486 0.12782767, -0.52048653 0.00284357 0.12955651, -0.521357 0.003537681 0.12955651, -0.52052611 -0.00085668638 0.13284048, -0.51992989 -0.0017390288 0.13323936, -0.51992989 -1.0106713e-05 0.13231525, -0.52221984 0.0026080869 0.13107201, -0.52300853 0.0016518347 0.13211089, -0.51992989 -0.0036150701 0.13380834, -0.52014053 -0.003524188 0.13379034, -0.51998341 -0.0045327581 0.13394687, -0.52058166 0.0015786998 0.13107187, -0.52010304 0.0043511651 0.12595201, -0.52001339 0.0042613409 0.12595186, -0.52057463 0.0040295236 0.12782767, -0.52041912 9.245798e-05 0.1322647, -0.51992995 0.0015053265 0.13107187, -0.52124757 0.0033834092 0.12955651, -0.52018136 0.0037159584 0.12782767, -0.52200097 0.0023631416 0.13107187, -0.52030498 0.0027912222 0.1295566, -0.52009255 0.004332196 0.12595186, -0.52025783 0.0015237294 0.13107178, -0.51999336 0.0042530559 0.12595186, -0.52522081 0.0038380139 0.13284048, -0.52588648 0.0035802089 0.13317364, -0.52009934 0.0036923103 0.12782767, -0.52011853 0.0027594976 0.1295566, -0.51992995 0.0027489923 0.12955651, -0.51997262 0.0042470954 0.12595201, -0.52001518 0.0036780648 0.12782767, -0.51992995 0.0036732964 0.12782767, -0.5199514 0.0042435937 0.12595201, -0.51992995 0.0042423271 0.12595186, -0.52007091 -0.0072393157 0.13385901, -0.5215798 -0.012096215 0.11649916, -0.52228445 -0.012010697 0.11649898, -0.52138942 -0.010766912 0.11550263, -0.52019793 -0.0078649111 0.11426899, -0.51999736 -0.0067245252 0.11406788, -0.52363259 -0.013928343 0.11912781, -0.52424723 -0.013793547 0.11912781, -0.52329069 -0.013043333 0.11773998, -0.52169758 -0.013275359 0.11774012, -0.5237326 -0.014424313 0.12017316, -0.52489394 -0.014204565 0.12029693, -0.52179033 -0.014205325 0.11912778, -0.52068013 -0.0093653388 0.11475909, -0.5238232 -0.014873687 0.12155691, -0.5254088 -0.014484916 0.12155682, -0.52184063 -0.014708821 0.12017316, -0.52387124 -0.015112061 0.12290823, -0.52573341 -0.014642332 0.12290823, -0.52388304 -0.015170772 0.12399983, -0.5255869 -0.014573265 0.12582648, -0.52580935 -0.014677111 0.12429419, -0.52188617 -0.015164901 0.12155682, -0.52191037 -0.015406955 0.122908, -0.52384973 -0.01500595 0.12582669, -0.52502841 -0.014281947 0.12741601, -0.52191621 -0.015466485 0.12399983, -0.52376419 -0.014581252 0.12741601, -0.52417833 -0.013746072 0.12898278, -0.52189952 -0.01529913 0.12582648, -0.52362019 -0.013867427 0.12898278, -0.52308089 -0.012852166 0.13053292, -0.5236401 -0.013339881 0.12978414, -0.52185649 -0.014868069 0.12741587, -0.52178413 -0.014143456 0.12898263, -0.52167493 -0.013050158 0.13053271, -0.5220322 -0.011699904 0.13178992, -0.52154571 -0.011755783 0.13178977, -0.52114195 -0.010338146 0.13276109, -0.5204767 -0.0088273622 0.13344952, -0.52240998 0.0028906427 -0.13107038, -0.52221996 0.0026228987 -0.13107038, -0.52352446 0.002128195 -0.13220096, -0.5205816 0.0015934967 -0.13107038, -0.52044952 -0.00016293302 -0.13244224, -0.52096272 -7.5761229e-05 -0.13244224, -0.52025789 0.0015384071 -0.13107038, -0.52146286 6.8362802e-05 -0.13244224, -0.52118212 -0.00070587173 -0.13282856, -0.52160579 -9.4212592e-06 -0.13251853, -0.52006578 0.0043127351 -0.12595004, -0.52004975 0.0042983554 -0.12595004, -0.52040464 0.003853675 -0.12782592, -0.52046824 0.0039105825 -0.12782586, -0.5200696 -0.0038854666 -0.13386014, -0.52001506 0.0036923401 -0.12782592, -0.52011859 0.0027741604 -0.12955511, -0.52052516 0.0039741956 -0.12782571, -0.52112168 0.0032572411 -0.12955511, -0.52124757 0.0033981167 -0.12955511, -0.52047062 -0.0023072399 -0.13346627, -0.52030498 0.0028058998 -0.12955484, -0.521357 0.0035522692 -0.12955484, -0.52256888 0.0031781904 -0.13107011, -0.52420861 0.0026506744 -0.13244224, -0.52089721 0.0016843788 -0.13107038, -0.52008015 0.004328873 -0.12595004, -0.5199514 0.0042577498 -0.12595004, -0.52057451 0.0040438585 -0.12782592, -0.52009928 0.003706675 -0.12782592, -0.52144831 0.0037177466 -0.12955484, -0.52269453 0.0034816973 -0.13107038, -0.52480537 0.0030362718 -0.1327028, -0.52048653 0.0028582327 -0.12955511, -0.52120084 0.0018101446 -0.13107038, -0.52209914 0.00066834316 -0.13225624, -0.52445489 0.0034164153 -0.13244215, -0.52542114 0.0033749305 -0.13297671, -0.51997268 0.0042613558 -0.12595004, -0.52009255 0.0043464415 -0.12595004, -0.52061576 0.0041184686 -0.12782592, -0.52018124 0.0037301742 -0.12782604, -0.52066123 0.0029305033 -0.12955484, -0.52548999 0.003822621 -0.13297671, -0.52668887 0.0039092563 -0.13346684, -0.52610308 0.0044489764 -0.13323793, -0.52437431 0.004449036 -0.13231385, -0.52148825 0.001968991 -0.13107038, -0.52244598 0.0010815971 -0.1321483, -0.52152056 0.0038921498 -0.12955511, -0.51999336 0.0042673014 -0.12595004, -0.52278548 0.0037973039 -0.13107011, -0.52026016 0.0037629418 -0.12782592, -0.52454203 0.0039294325 -0.132442, -0.52082664 0.0030218922 -0.12955484, -0.52797908 0.0044490956 -0.133807, -0.52826411 0.004309427 -0.13385963, -0.52010304 0.0043653063 -0.12594995, -0.52175611 0.0021590255 -0.13107038, -0.52279866 0.0014595054 -0.13210499, -0.5206483 0.0041973703 -0.12782592, -0.52001339 0.004275512 -0.12594995, -0.52157295 0.0040738992 -0.12955484, -0.52284044 0.0041210763 -0.13107038, -0.5203349 0.0038042478 -0.12782592, -0.5228588 0.0044489615 -0.13107011, -0.52161521 0.0044487678 -0.12955484, -0.52098078 0.0031313412 -0.12955511, -0.52011126 0.0043851845 -0.12595004, -0.52067214 0.0042793863 -0.12782592, -0.52200097 0.0023779385 -0.13107038, -0.52003223 0.0042859577 -0.12595004, -0.5216046 0.0042601787 -0.12955484, -0.5206911 0.004448723 -0.12782592, -0.52011722 0.004405912 -0.12595004, -0.52068633 0.0043635182 -0.12782592, -0.52055633 -0.0011109151 -0.13297716, -0.52079451 -0.0014834292 -0.13316238, -0.52012211 0.0044486783 -0.12594995, -0.52012092 0.0044272058 -0.12595004, -0.5318808 0.0044490211 -0.133807, -0.53645819 0.0027982555 -0.11649561, -0.53829306 0.00074547157 -0.11912698, -0.53763872 0.0026804917 -0.11773735, -0.53878915 0.00064551458 -0.12017256, -0.53857011 0.0025876723 -0.11912692, -0.5392381 0.00055497512 -0.12155548, -0.53907365 0.0025373958 -0.12017241, -0.53947657 0.00050696358 -0.12290594, -0.53953528 0.00049528107 -0.12399942, -0.53952938 0.0024919622 -0.12155539, -0.5397715 0.0024679266 -0.12290588, -0.53937095 0.00052846596 -0.12582323, -0.53983098 0.0024620555 -0.12399921, -0.53894717 0.00061401352 -0.12741119, -0.53966421 0.0024787746 -0.12582299, -0.53973788 0.0044486336 -0.12595004, -0.53823322 0.00075801834 -0.1289793, -0.53923398 0.0025218539 -0.1274111, -0.53916878 0.0044486634 -0.12782592, -0.53850943 0.002594199 -0.1289793, -0.53824466 0.0044487379 -0.12955484, -0.53741711 0.0027033202 -0.13052857, -0.53700107 0.0044489168 -0.13107038, -0.53612286 0.0028326474 -0.13178656, -0.53548557 0.0044488572 -0.13231385, -0.53375679 0.0044490062 -0.13323787, -0.52200097 0.0023770891 -0.11692816, -0.52300853 0.0016657226 -0.1158891, -0.52175611 0.0021582358 -0.11692816, -0.52098078 0.0031306408 -0.11844343, -0.52112168 0.0032565258 -0.11844358, -0.52009934 0.0037062727 -0.12017241, -0.52001512 0.0036920123 -0.12017241, -0.5199514 0.0042575561 -0.12204823, -0.51999348 0.0042671524 -0.12204823, -0.51997274 0.0042611621 -0.12204823, -0.52124757 0.0033974312 -0.11844343, -0.52046829 0.0039101802 -0.1201722, -0.52052498 0.0039737038 -0.1201722, -0.52025789 0.0015376471 -0.11692816, -0.52011859 0.0027735047 -0.11844343, -0.52057451 0.0040434264 -0.1201722, -0.52008015 0.0043287687 -0.12204823, -0.52009255 0.0043462776 -0.12204823, -0.52030498 0.0028051846 -0.11844358, -0.52010304 0.0043651573 -0.12204808, -0.52018148 0.0037299953 -0.12017232, -0.52221984 0.0026220046 -0.11692816, -0.52373236 0.0022960268 -0.11573538, -0.52039444 0.00032457337 -0.11588925, -0.52135688 0.0035516135 -0.11844358, -0.52014053 -0.0035102107 -0.11420974, -0.52001339 0.0042753778 -0.12204808, -0.52061576 0.0041180514 -0.1201722, -0.52058166 0.0015926473 -0.11692816, -0.5205251 -0.00083446875 -0.11516437, -0.52062142 -0.0018978454 -0.11467639, -0.52048653 0.0028574727 -0.11844358, -0.51998341 -0.004518915 -0.11405307, -0.52011126 0.0043850057 -0.12204823, -0.52240998 0.0028898679 -0.11692813, -0.52026027 0.0037626885 -0.12017232, -0.52144831 0.0037170462 -0.11844343, -0.52085316 0.00040246174 -0.11588925, -0.52064842 0.0041969977 -0.1201722, -0.52003223 0.0042858087 -0.12204823, -0.52011722 0.0044057332 -0.12204823, -0.52089721 0.0016836636 -0.11692831, -0.52256888 0.0031772964 -0.11692813, -0.52440935 0.0027862154 -0.11547121, -0.5211128 -0.00073451176 -0.11516419, -0.52117467 -0.00072007254 -0.11516437, -0.52066118 0.002929803 -0.11844358, -0.52152067 0.003891658 -0.11844358, -0.52067202 0.0042790137 -0.1201722, -0.52033502 0.0038039498 -0.12017241, -0.52012092 0.0044269674 -0.12204823, -0.52004975 0.0042982064 -0.12204823, -0.52120072 0.0018093251 -0.11692813, -0.52269453 0.0034807436 -0.11692813, -0.52082652 0.0030212663 -0.11844358, -0.52157301 0.0040732734 -0.11844334, -0.52040464 0.0038533024 -0.12017241, -0.52068627 0.004363101 -0.12017211, -0.52173042 0.00070947036 -0.11588913, -0.52188069 0.00038182363 -0.11564118, -0.52384681 0.0030776374 -0.1158891, -0.52510804 0.0032086782 -0.11515948, -0.52006584 0.0043126307 -0.12204808, -0.52148819 0.0019682162 -0.11692813, -0.52278548 0.0037964098 -0.11692813, -0.52160472 0.0042595975 -0.11844343, -0.52827746 0.0043105148 -0.11413643, -0.52670878 0.0039149486 -0.11452511, -0.52397561 0.0035247914 -0.1158891, -0.52588648 0.0035941564 -0.11482638, -0.52213752 0.0009345375 -0.11588925, -0.52238727 0.0010138862 -0.11583689, -0.52284044 0.0041202419 -0.11692813, -0.52405351 0.003983628 -0.1158891, -0.52521247 0.0038529001 -0.11516398, -0.5210762 0.00055688247 -0.11595714, -0.52154583 -0.011741836 -0.11621025, -0.51992983 -0.012622882 -0.11692917, -0.51992983 -0.011107612 -0.11568531, -0.52114195 -0.010324243 -0.11523923, -0.52203232 -0.011685912 -0.11621025, -0.52007091 -0.0072253235 -0.11414096, -0.51993001 -0.0075028278 -0.11419183, -0.52162534 -0.012538511 -0.11692917, -0.52308089 -0.012838278 -0.11746743, -0.52173322 -0.013619293 -0.11821586, -0.51992983 -0.013866384 -0.11844444, -0.52047664 -0.0088134743 -0.11455056, -0.51992989 -0.0093787648 -0.11476099, -0.52184063 -0.014695276 -0.12017339, -0.51992995 -0.014790405 -0.12017331, -0.52351874 -0.013350833 -0.11821595, -0.5236401 -0.013325904 -0.11821571, -0.52417833 -0.013732139 -0.11901721, -0.52189726 -0.015261475 -0.12204921, -0.51992995 -0.015359331 -0.12204912, -0.52373248 -0.014410842 -0.12017331, -0.52502835 -0.014267955 -0.12058407, -0.52191585 -0.015448261 -0.12370616, -0.51992983 -0.015551392 -0.12400025, -0.52384514 -0.014968608 -0.12204936, -0.5255869 -0.014559347 -0.12217346, -0.52191037 -0.015392948 -0.125092, -0.51992983 -0.015359137 -0.12595123, -0.52388221 -0.015152562 -0.12370616, -0.52580935 -0.014663208 -0.12370616, -0.52573353 -0.014628325 -0.125092, -0.52188617 -0.015150923 -0.12644312, -0.51992983 -0.014790002 -0.12782711, -0.52387124 -0.015098158 -0.125092, -0.5254088 -0.014470924 -0.12644312, -0.52184564 -0.014744956 -0.12770316, -0.5238232 -0.014859665 -0.12644324, -0.52489394 -0.014190707 -0.1277034, -0.52179044 -0.014191333 -0.12887248, -0.51992983 -0.013865743 -0.12955594, -0.5237425 -0.014459837 -0.12770316, -0.52424723 -0.013779584 -0.12887225, -0.52169758 -0.013261307 -0.13025996, -0.51992983 -0.012622047 -0.13107121, -0.52329069 -0.01302937 -0.13026008, -0.52228445 -0.011996854 -0.1315012, -0.52363247 -0.013914336 -0.12887248, -0.52162534 -0.012537647 -0.13107121, -0.5214749 -0.011029784 -0.1323148, -0.52138954 -0.010752965 -0.13249755, -0.51992995 -0.011106629 -0.1323148, -0.52068013 -0.0093513615 -0.13324118, -0.51992995 -0.0093776472 -0.13323891, -0.52019793 -0.0078509189 -0.13373101, -0.51993001 -0.0075017102 -0.13380754, -0.5199973 -0.0067105182 -0.13393211, -0.53151339 0.054561194 0.11412975, -0.5331381 0.054963496 0.11453223, -0.53473359 0.055664208 0.11523291, -0.53609222 0.056559142 0.11612791, -0.53732747 0.057705667 0.11727491, -0.53838307 0.059091624 0.11866078, -0.53920132 0.060686644 0.12025601, -0.53975707 0.062581152 0.12215078, -0.41799977 -0.015564147 0.11399993, -0.41799977 -0.013563726 0.10800001, -0.41799971 -0.015563894 0.10999987, -0.41799966 -0.034565363 0.13399881, -0.41799971 -0.026577819 0.12683281, -0.41800001 0.02343474 0.13400206, -0.41800001 0.022568952 0.12218401, -0.41800001 0.022057425 0.12160668, -0.41800001 0.02443574 0.11500219, -0.41799968 -0.031064872 0.12719882, -0.41799968 -0.02806494 0.12719914, -0.41799971 -0.02729908 0.12710631, -0.41800001 0.021422531 0.12116864, -0.41799966 -0.031830702 0.12710607, -0.41800013 0.022927519 0.12286749, -0.41799966 -0.035565186 0.13299879, -0.41800001 0.020701181 0.12089482, -0.41799966 -0.034241367 0.12438449, -0.41799966 -0.03405695 0.12513363, -0.4179996 -0.033698414 0.1258167, -0.41799971 -0.02543113 0.12218136, -0.41799983 -0.025942627 0.12160403, -0.4179998 -0.033186812 0.12639415, -0.41799966 -0.032551948 0.12683246, -0.41800007 0.016169664 0.12089455, -0.41799971 -0.026577506 0.12116578, -0.41799966 -0.035564173 0.11499855, -0.41799966 -0.034241367 0.12361303, -0.41799966 -0.034564126 0.11399886, -0.41799971 -0.027298752 0.1208922, -0.41800013 0.023112115 0.12361628, -0.41799971 -0.025072683 0.12286463, -0.41800001 0.019935455 0.12080202, -0.41800001 0.02311201 0.12438777, -0.41799971 -0.024887998 0.1236136, -0.41799998 0.016935539 0.12080184, -0.41799968 -0.028064493 0.1207993, -0.41799971 -0.024888027 0.12438509, -0.41799971 -0.025072757 0.12513411, -0.41799995 0.013943177 0.12513638, -0.41799971 -0.025431354 0.12581694, -0.41799995 0.014301594 0.12581933, -0.41799966 -0.031064499 0.12079909, -0.41799971 -0.025942806 0.12639472, -0.41799995 0.014813077 0.12639689, -0.41800001 0.024434861 0.13300222, -0.41800001 0.020700853 0.12710893, -0.41800001 0.021422189 0.12683538, -0.41800001 0.022057127 0.12639734, -0.41800001 0.022568714 0.12581977, -0.41800001 0.022927206 0.12513682, -0.41799968 -0.031830419 0.12089193, -0.41799995 0.015447985 0.12683523, -0.41799989 0.0024362318 0.10800079, -0.41799989 0.0044360273 0.11000097, -0.41799995 0.015448313 0.12116817, -0.41799995 0.014813375 0.12160626, -0.41799995 0.014301848 0.12218362, -0.41799995 0.013943341 0.12286666, -0.41799966 -0.032551695 0.12116548, -0.41799995 0.013758745 0.12361562, -0.41799995 0.016935091 0.12720156, -0.41800001 0.019935127 0.12720177, -0.41799966 -0.033186648 0.12160364, -0.41800007 0.013758641 0.12438726, -0.41799966 -0.033698235 0.12218097, -0.41799995 0.016169291 0.12710857, -0.4179996 -0.034056757 0.12286425, -0.42099971 -0.031064544 0.12079921, -0.42099971 -0.028064478 0.12079921, -0.42099971 -0.02806494 0.12719914, -0.42099971 -0.027299095 0.12710631, -0.42099971 -0.02657776 0.1268326, -0.42099985 -0.025942881 0.12639463, -0.42099971 -0.025431324 0.12581694, -0.42099974 -0.025072757 0.1251342, -0.42099985 -0.024888027 0.12438509, -0.42099985 -0.024888027 0.1236136, -0.42099974 -0.025072608 0.12286454, -0.42099971 -0.025431145 0.12218136, -0.42099971 -0.025942732 0.12160403, -0.42099974 -0.026577625 0.12116578, -0.42099968 -0.027298812 0.1208922, -0.42099968 -0.031064916 0.12719899, -0.42099968 -0.031830434 0.12089193, -0.42099971 -0.032551739 0.12116548, -0.42099968 -0.033186663 0.12160364, -0.42099962 -0.033698235 0.12218076, -0.42099968 -0.034056786 0.12286392, -0.42099968 -0.034241322 0.12361303, -0.4209998 -0.034241352 0.12438464, -0.42099968 -0.034056891 0.12513363, -0.42099968 -0.033698458 0.12581655, -0.42099968 -0.033186842 0.12639418, -0.42099965 -0.032552037 0.12683246, -0.42099968 -0.031830717 0.12710607, -0.42099968 -0.034565333 0.13399881, -0.42099959 -0.035565186 0.13299865, -0.42099968 -0.035564233 0.11499873, -0.42099968 -0.034564186 0.11399886, -0.421 0.016935106 0.12720171, -0.42100003 0.019935083 0.12720191, -0.421 0.016935404 0.12080184, -0.42099997 0.016169529 0.12089461, -0.42099997 0.015448269 0.12116826, -0.42099997 0.014813375 0.12160626, -0.42099997 0.014301818 0.12218362, -0.42100003 0.013943296 0.12286666, -0.42099994 0.013758626 0.12361589, -0.42099994 0.013758626 0.12438732, -0.42099997 0.013943117 0.12513649, -0.42099997 0.014301669 0.12581933, -0.42099997 0.014813166 0.12639701, -0.42099997 0.01544797 0.12683499, -0.42100009 0.01616941 0.12710878, -0.421 0.01993553 0.12080184, -0.421 0.020700794 0.12710902, -0.42100003 0.021422189 0.12683538, -0.42100003 0.022057127 0.12639734, -0.42100003 0.022568714 0.12581977, -0.42100003 0.022927161 0.12513682, -0.42100003 0.023111936 0.12438777, -0.42100003 0.023111936 0.12361628, -0.42100003 0.022927325 0.12286717, -0.42100003 0.022568744 0.12218416, -0.42100015 0.022057425 0.12160683, -0.42100003 0.021422502 0.12116852, -0.421 0.020701211 0.12089482, -0.42100003 0.023434754 0.13400215, -0.42100003 0.024434801 0.13300201, -0.42100003 0.024435814 0.11500201, -0.42099991 -0.015564162 0.11399993, -0.42099991 0.0044360571 0.11000097, -0.42099988 -8.5420907e-06 0.11568597, -0.42100003 0.001506757 0.11692971, -0.42099988 0.0027502589 0.11844507, -0.42099991 0.0024362169 0.10800079, -0.42099997 -0.0017373748 0.11476186, -0.42099991 0.0036743246 0.12017402, -0.42099974 -0.0036133118 0.11419258, -0.42099991 0.0042432509 0.12205005, -0.42099991 0.004435312 0.12400103, -0.4209998 -0.013563741 0.10800001, -0.42099991 0.004242938 0.12595186, -0.42099991 0.0036739074 0.12782767, -0.4209998 -0.015564073 0.10999987, -0.42099991 0.0027496181 0.12955651, -0.42099991 0.0015059225 0.13107187, -0.42099997 -9.406358e-06 0.13231531, -0.42099985 -0.0017383434 0.13323936, -0.42099985 -0.0036144294 0.13380846, -0.49772975 0.06998606 0.20414865, -0.50774854 0.057672676 0.20993245, -0.49692926 0.068257064 0.20368662, -0.50637561 0.057118084 0.20913979, -0.51213104 0.069985449 0.21246317, -0.5110541 0.071500838 0.21184161, -0.50974178 0.072744533 0.21108416, -0.50493026 0.056930002 0.20830524, -0.51293141 0.068256557 0.21292526, -0.49643651 0.066381216 0.2034018, -0.50824457 0.073668599 0.21021959, -0.51342422 0.06638059 0.2132096, -0.50661993 0.074237883 0.20928159, -0.50493044 0.074429959 0.20830628, -0.50324076 0.074237943 0.20733067, -0.49859795 0.062761426 0.20464951, -0.50348502 0.057118114 0.20747066, -0.49907842 0.061176147 0.20492685, -0.5112626 0.06276083 0.21196166, -0.50211215 0.057672855 0.20667824, -0.50161624 0.073668942 0.20639277, -0.49985209 0.059754115 0.20537359, -0.5107823 0.06117573 0.21168393, -0.50088066 0.058566462 0.20596719, -0.50011897 0.072744921 0.20552826, -0.51000839 0.059753682 0.21123731, -0.49880669 0.071501464 0.20477057, -0.5089801 0.05856609 0.2106435, -0.51473767 0.066382736 0.17170301, -0.5152306 0.068258822 0.17198792, -0.51603097 0.069987655 0.17244971, -0.51710796 0.071503013 0.17307177, -0.51842034 0.072746605 0.17382953, -0.51991761 0.073670745 0.17469388, -0.52154219 0.074239671 0.17563218, -0.52323169 0.074431688 0.17660743, -0.52492124 0.074239463 0.17758301, -0.52654576 0.073670387 0.17852095, -0.52804291 0.072746277 0.17938524, -0.52935541 0.071502596 0.18014285, -0.5304324 0.069987118 0.18076459, -0.53123254 0.068258107 0.18122652, -0.53172535 0.06638217 0.18151098, -0.53472823 0.069987744 0.17155206, -0.53305632 0.071502984 0.17245761, -0.53355968 0.071503043 0.17112657, -0.53421402 0.069987476 0.17291188, -0.53057873 0.074240327 0.16316751, -0.53011107 0.074240148 0.16505337, -0.52822655 0.074432313 0.16454843, -0.52867687 0.074432552 0.16273367, -0.53507423 0.068258703 0.17324942, -0.53247005 0.069987237 0.176909, -0.53330278 0.068258375 0.17730993, -0.52744269 0.074240506 0.15876892, -0.52540207 0.073671341 0.15962529, -0.5255878 0.07367152 0.15848926, -0.52724946 0.074240386 0.15995109, -0.53446591 0.071503162 0.16842934, -0.53213561 0.072746754 0.17060849, -0.53301793 0.072746813 0.1679827, -0.52420551 0.072747558 0.15548098, -0.52237988 0.071503788 0.15800554, -0.5226959 0.071503878 0.15534863, -0.52387822 0.072747499 0.15823141, -0.52917075 0.074432611 0.16028991, -0.52677482 0.074240357 0.16229951, -0.53359306 0.072746962 0.16598618, -0.53136593 0.073670894 0.1674732, -0.53192317 0.073671043 0.16553906, -0.53559655 0.068258703 0.17186797, -0.53240764 0.073671073 0.16358495, -0.53560382 0.066382736 0.17345726, -0.53381521 0.066382408 0.17755657, -0.52937204 0.074432611 0.1590597, -0.53565425 0.069987714 0.16879582, -0.52592784 0.07367155 0.15563178, -0.53109211 0.074240476 0.1606288, -0.53505683 0.071503371 0.16637862, -0.53613132 0.066382676 0.17206237, -0.53409314 0.072746933 0.16396976, -0.53130102 0.074240506 0.1593504, -0.53653735 0.068258882 0.16906819, -0.52779663 0.074240655 0.15579522, -0.53293949 0.073671371 0.16095424, -0.53625792 0.069987804 0.16670012, -0.53557056 0.071503311 0.16430676, -0.53315604 0.073671371 0.15962988, -0.53708106 0.066382915 0.16923568, -0.5297401 0.07443285 0.15596533, -0.5346421 0.072747231 0.16125441, -0.53715056 0.068259001 0.16693926, -0.51614219 0.066383094 0.16904569, -0.53678292 0.069987893 0.16458344, -0.51665485 0.068258941 0.16929266, -0.53486562 0.072747231 0.15988743, -0.53168356 0.074240595 0.15613544, -0.51748753 0.069987833 0.16969389, -0.53613448 0.07150352 0.16151774, -0.53770024 0.066383064 0.16708636, -0.51734418 0.066383272 0.16629088, -0.53768378 0.06825912 0.16478896, -0.51860797 0.071503192 0.17023373, -0.53636402 0.071503609 0.16011325, -0.53355235 0.07367149 0.15629879, -0.51769859 0.066383213 0.16535354, -0.51787382 0.06825915 0.16649875, -0.53735906 0.069988072 0.16173339, -0.5382387 0.066383064 0.16491556, -0.51997328 0.072746813 0.17089117, -0.53759372 0.069988251 0.16029871, -0.53527462 0.072747469 0.15644938, -0.51823336 0.06825918 0.16554844, -0.51873416 0.069988012 0.16683659, -0.5382691 0.068259299 0.16189373, -0.53850752 0.068259299 0.16043627, -0.51833671 0.066383243 0.16345382, -0.53678429 0.071503788 0.15658152, -0.52153099 0.073670864 0.17164114, -0.53882957 0.066383332 0.16199243, -0.53907019 0.066383451 0.16052091, -0.51910174 0.069988072 0.16586459, -0.53802305 0.06998843 0.15668967, -0.5198918 0.071503371 0.16729093, -0.53894365 0.068259567 0.15677026, -0.53951055 0.06638366 0.15681952, -0.51888067 0.068259299 0.1636219, -0.52322114 0.07423979 0.17245519, -0.53944308 0.067335725 0.15420544, -0.53869355 0.069146842 0.15417293, -0.53916901 0.068259805 0.15160719, -0.53783816 0.070389807 0.15540293, -0.51875299 0.066383511 0.16200951, -0.52027029 0.07150346 0.16628981, -0.53760546 0.07077685 0.15412551, -0.53794861 0.070389986 0.15287322, -0.53700149 0.071504056 0.15160728, -0.53824502 0.069988638 0.15160719, -0.52130228 0.072746783 0.16784474, -0.53971714 0.065899998 0.15515172, -0.53983563 0.065413147 0.15397295, -0.53980792 0.065900296 0.15291351, -0.53973824 0.066383868 0.15160701, -0.51976371 0.069988132 0.16389418, -0.53652453 0.071842313 0.15531689, -0.52497876 0.074431837 0.17330173, -0.53622067 0.072162986 0.15406501, -0.51930255 0.068259418 0.16215694, -0.53663254 0.071842492 0.15284452, -0.53548598 0.072747618 0.15160748, -0.53495336 0.073010117 0.15521389, -0.52169442 0.072746962 0.16680837, -0.51911467 0.066383511 0.16055053, -0.53459215 0.073252171 0.15399396, -0.53505826 0.073010206 0.15281036, -0.52291167 0.073670864 0.16847619, -0.53375727 0.073671788 0.15160748, -0.53318501 0.073848188 0.15509787, -0.53278279 0.074002326 0.15391508, -0.52095205 0.07150346 0.16426075, -0.53328657 0.073848426 0.15277144, -0.52673656 0.074239641 0.1741479, -0.53188121 0.074240863 0.15160748, -0.53128743 0.074324548 0.15497363, -0.53086197 0.074384809 0.15383121, -0.52019525 0.069988251 0.16239619, -0.53138542 0.074324787 0.15273023, -0.52331889 0.073671013 0.16739941, -0.52933377 0.07442081 0.15484539, -0.52942789 0.074420929 0.15268767, -0.51966947 0.068259478 0.16067719, -0.52760011 0.074189842 0.15525475, -0.52465791 0.074239939 0.16916168, -0.52240008 0.072747082 0.16470766, -0.52821958 0.074299395 0.15442005, -0.5276683 0.074189991 0.15421379, -0.52842665 0.073670626 0.17496201, -0.52715325 0.074048698 0.15332523, -0.52773649 0.074189991 0.15212896, -0.5256415 0.073507518 0.15443653, -0.51951176 0.06638363 0.15858626, -0.52572131 0.073507637 0.15243998, -0.52139652 0.071503669 0.16271809, -0.5240829 0.072632164 0.15490457, -0.52508175 0.074239969 0.16804123, -0.52368104 0.072282821 0.15378311, -0.52418476 0.072632462 0.15297571, -0.52057052 0.069988281 0.16088295, -0.52248532 0.071219027 0.15452591, -0.52145708 0.069988519 0.15524036, -0.52647406 0.074432045 0.16987455, -0.52257216 0.071219057 0.15266708, -0.52053636 0.068259716 0.15515977, -0.51967353 0.06638366 0.15759742, -0.52405226 0.073671103 0.16521716, -0.52998435 0.072746426 0.17571226, -0.52007234 0.068259627 0.15868533, -0.52286029 0.07274729 0.16311038, -0.52691501 0.074432164 0.16870868, -0.52178293 0.071503639 0.16115999, -0.52829015 0.07423991 0.17058721, -0.52023619 0.068259567 0.1576823, -0.52584481 0.074240148 0.16577002, -0.53134954 0.071502656 0.17636958, -0.52098238 0.069988459 0.1588456, -0.52453017 0.073671103 0.16355801, -0.52874827 0.074239969 0.16937593, -0.5232603 0.072747201 0.16149712, -0.53003633 0.073670775 0.17127264, -0.52115005 0.069988489 0.15782014, -0.52770901 0.074432254 0.16634524, -0.51996946 0.066383749 0.1551097, -0.52220714 0.071503729 0.15906179, -0.52634227 0.074240208 0.16404355, -0.53051096 0.073670805 0.17001733, -0.52494591 0.073671311 0.16188192, -0.53164577 0.072746634 0.17190409, -0.52957338 0.074240059 0.1669203, -0.5236994 0.07274729 0.159325, -0.53732747 0.057719704 -0.13072526, -0.53975713 0.062595099 -0.12584931, -0.5392012 0.060700383 -0.12774417, -0.53838307 0.059105601 -0.12933916, -0.53609222 0.056573 -0.13187218, -0.53473353 0.055678125 -0.1327672, -0.5331381 0.054977562 -0.13346788, -0.53151321 0.054575142 -0.13387004, -0.53188121 0.074258029 -0.15159774, -0.53375727 0.073688835 -0.15159774, -0.53548598 0.072764724 -0.15159774, -0.53700149 0.071521223 -0.15159789, -0.53824508 0.070005745 -0.15159789, -0.53916913 0.068276972 -0.1515981, -0.53973824 0.066400975 -0.15159833, -0.52256256 0.059756275 0.16302994, -0.52296001 0.059756365 0.16142797, -0.52370977 0.058568653 0.16333726, -0.53258961 0.057675328 0.15954357, -0.53140259 0.057120856 0.15610996, -0.53298181 0.057675507 0.15624797, -0.53102213 0.057120617 0.15930739, -0.52116364 0.062763631 0.16265523, -0.52072173 0.062763482 0.16418919, -0.52125198 0.061178174 0.16435289, -0.52169973 0.061178442 0.16279879, -0.52752715 0.057120588 0.15999901, -0.5261541 0.057675447 0.15857363, -0.5277217 0.057120766 0.1588099, -0.52596599 0.057675388 0.159724, -0.52411771 0.058568772 0.16169205, -0.52456558 0.058568891 0.159477, -0.52550411 0.057675298 0.16200867, -0.52208883 0.061178442 0.16122913, -0.5293718 0.056932535 0.15905872, -0.52974004 0.056932773 0.15596423, -0.52474791 0.05856907 0.15836188, -0.52339607 0.059756484 0.15927073, -0.52154809 0.062763631 0.16110587, -0.52807754 0.057120886 0.15581882, -0.5235737 0.059756692 0.15818486, -0.52251607 0.061178472 0.15911579, -0.52649826 0.057675567 0.15568069, -0.52269 0.061178621 0.1580517, -0.52196974 0.06276378 0.15901947, -0.52508169 0.05856913 0.15555683, -0.52214152 0.06276381 0.157969, -0.52389866 0.059756663 0.15545332, -0.52300853 0.061178681 0.15537563, -0.52245587 0.062763929 0.15532723, -0.5370242 0.06276384 0.156602, -0.53722376 0.063176513 0.15500349, -0.53695506 0.061955865 0.15409663, -0.53733844 0.063593149 0.15387425, -0.53558141 0.059756573 0.1564756, -0.53637332 0.060804781 0.15530625, -0.53647155 0.061178651 0.15655357, -0.53731066 0.063176632 0.15285891, -0.53622717 0.060442682 0.15406477, -0.5364812 0.060805228 0.1528405, -0.53689867 0.061955746 0.15516263, -0.53699583 0.061955776 0.15285191, -0.52956396 0.062762558 0.18026295, -0.53156656 0.062762648 0.17647353, -0.53540349 0.059435125 0.15524238, -0.53439838 0.05856907 0.15637195, -0.52908343 0.061177369 0.1799854, -0.53106695 0.061177518 0.17623296, -0.53518093 0.059129652 0.15401915, -0.53550941 0.059435334 0.15281942, -0.53026181 0.05975562 0.17584512, -0.534154 0.058316048 0.1551604, -0.52830976 0.059755441 0.17953849, -0.53328043 0.062763005 0.17254511, -0.53386921 0.058082487 0.15396169, -0.53425735 0.058316227 0.15279186, -0.53268725 0.057503726 0.15506437, -0.52728128 0.058567878 0.17894471, -0.52919191 0.058567997 0.17532983, -0.53378588 0.062763035 0.17120847, -0.53235734 0.057353791 0.15389556, -0.53276414 0.061177697 0.17234239, -0.53278786 0.057503875 0.15275982, -0.53107679 0.05703878 0.15495887, -0.53117436 0.057038959 0.15272468, -0.52604961 0.057674285 0.17823362, -0.52791065 0.057674553 0.17471266, -0.52957481 0.056935783 0.15540439, -0.5332647 0.061177846 0.17101881, -0.53012562 0.056938168 0.15452996, -0.53193241 0.059755739 0.17201602, -0.52964598 0.056935903 0.15432075, -0.52467698 0.057119783 0.17744103, -0.52648234 0.057119902 0.17402497, -0.52919734 0.056965735 0.15339851, -0.53469616 0.062763155 0.1684998, -0.52971703 0.056935903 0.1521495, -0.52782977 0.057207044 0.15457109, -0.53242499 0.059755828 0.17071331, -0.52791357 0.057207074 0.15247902, -0.53082687 0.058568206 0.17158213, -0.52638978 0.0577535 0.15507618, -0.52323151 0.056931552 0.17660651, -0.52497876 0.05693185 0.1733008, -0.52602261 0.057996985 0.15389889, -0.52695733 0.057540264 0.15286088, -0.53416592 0.061177846 0.16833627, -0.52649683 0.057753589 0.15304625, -0.53130901 0.058568235 0.17030689, -0.52651721 0.057753619 0.15202996, -0.52488834 0.058786478 0.15469009, -0.52950311 0.057674821 0.17106262, -0.52498013 0.058786508 0.15272614, -0.53528935 0.062763333 0.16644013, -0.52382904 0.059890386 0.15503219, -0.52178627 0.057119872 0.1757721, -0.52347505 0.057119843 0.17257646, -0.52420086 0.059499558 0.15427476, -0.53331214 0.059755947 0.16807294, -0.5238933 0.059890535 0.15407369, -0.52363998 0.060301926 0.15324089, -0.52997273 0.057674821 0.16982052, -0.52395898 0.059890535 0.15215358, -0.52802753 0.057120021 0.17048323, -0.53475362 0.061178025 0.1662966, -0.51918185 0.058568116 0.17426848, -0.52204692 0.057674672 0.17188868, -0.52041346 0.057674523 0.1749796, -0.53580528 0.062763304 0.16435996, -0.53217751 0.058568384 0.1677227, -0.52848321 0.057120111 0.16927835, -0.52647388 0.056931969 0.16987345, -0.53389055 0.059756067 0.16606522, -0.5207656 0.058568206 0.17127189, -0.53526455 0.061178084 0.1642364, -0.53081846 0.057674941 0.16730341, -0.52691489 0.056932028 0.16870758, -0.5249204 0.057120141 0.16926384, -0.53274339 0.058568444 0.16575789, -0.51815337 0.059755798 0.17367473, -0.5196957 0.059755947 0.17075673, -0.53637153 0.062763542 0.16155899, -0.53439337 0.059756245 0.16403762, -0.52930373 0.05712026 0.16683626, -0.52534664 0.057120141 0.16813657, -0.52344477 0.057674881 0.16868457, -0.53136986 0.057675 0.16538969, -0.51689929 0.062763005 0.17295089, -0.51889056 0.061177935 0.17036906, -0.51737958 0.061177757 0.17322785, -0.5366022 0.062763661 0.1601485, -0.53582531 0.061178353 0.16146255, -0.53323573 0.058568653 0.1637733, -0.52770895 0.056932237 0.1663442, -0.52385718 0.05767497 0.16759455, -0.52212101 0.058568444 0.16816533, -0.52983856 0.05712029 0.1649797, -0.51839095 0.062763244 0.17012843, -0.5360536 0.061178323 0.16006589, -0.53494531 0.059756305 0.16130733, -0.53184921 0.057675 0.16345668, -0.52611411 0.057120319 0.16585231, -0.52252084 0.058568563 0.16710827, -0.52101558 0.059756007 0.16773137, -0.52822655 0.056932267 0.16454744, -0.53517014 0.059756365 0.15993285, -0.53377587 0.058568653 0.16110098, -0.53030384 0.057120558 0.16310406, -0.52459937 0.05767509 0.16538513, -0.5214048 0.059756156 0.16670194, -0.52018386 0.061178174 0.16740498, -0.52661455 0.057120379 0.16411567, -0.53399581 0.058568772 0.15975565, -0.53237534 0.057675239 0.16085401, -0.52867663 0.056932505 0.1627326, -0.52324051 0.058568534 0.16496602, -0.52056533 0.061178204 0.16639659, -0.51966757 0.062763453 0.16720259, -0.5250833 0.057675119 0.16370535, -0.53081423 0.057120558 0.16057888, -0.52704972 0.057120588 0.16236126, -0.52210575 0.059756216 0.16461599, -0.52004391 0.062763363 0.16620693, -0.52917063 0.056932505 0.16028893, -0.41799971 -0.026563454 -0.12683436, -0.41799971 -0.02728479 -0.12710795, -0.41799966 -0.034550238 -0.1340014, -0.41800001 0.022582706 -0.12218037, -0.41800001 0.024448778 -0.11499792, -0.41800013 0.022071119 -0.12160304, -0.41800013 0.022941377 -0.12286347, -0.41799966 -0.033684421 -0.12218347, -0.4179996 -0.033172939 -0.12160605, -0.41799977 -0.035551269 -0.11500138, -0.41800013 0.023125973 -0.12361237, -0.4179996 -0.03253803 -0.12116772, -0.41799966 -0.034042928 -0.12286657, -0.4179996 -0.031816814 -0.12089437, -0.41799966 -0.034551401 -0.1140013, -0.41799989 0.0044484101 -0.10999903, -0.41799989 0.0024483316 -0.10799918, -0.41799977 -0.013551716 -0.10800001, -0.41799977 -0.015551347 -0.11400029, -0.41799966 -0.034227479 -0.1236158, -0.41799966 -0.031050954 -0.12080115, -0.41800007 0.014315661 -0.12218067, -0.41799995 0.014827084 -0.12160328, -0.41800001 0.02344982 -0.1339981, -0.41800001 0.020715173 -0.12710509, -0.41799995 0.019949432 -0.12719828, -0.41799995 0.015461978 -0.12116501, -0.41799995 0.016949426 -0.12719846, -0.41799995 0.016183626 -0.12710541, -0.41799995 0.01546235 -0.12683183, -0.41800007 0.013957199 -0.12286386, -0.41799971 -0.028050948 -0.12080088, -0.41800001 0.024449807 -0.13299799, -0.41800001 0.021436434 -0.12683171, -0.41800001 0.022071373 -0.12639326, -0.41800001 0.02258287 -0.12581593, -0.41800001 0.022941362 -0.12513283, -0.41800001 0.023125928 -0.12438381, -0.41799971 -0.027285133 -0.12089387, -0.41799995 0.016183268 -0.12089151, -0.41800007 0.013772603 -0.12361282, -0.41799995 0.016949009 -0.12079838, -0.41799995 0.013772573 -0.12438446, -0.41799995 0.013957243 -0.12513337, -0.41799971 -0.025058676 -0.12513554, -0.41799966 -0.035550285 -0.13300133, -0.41799977 -0.03422733 -0.12438709, -0.4179998 -0.034042735 -0.12513599, -0.41799966 -0.033684198 -0.12581918, -0.41799966 -0.033172596 -0.12639651, -0.4179998 -0.032537658 -0.1268346, -0.41799995 0.014315795 -0.12581646, -0.41799977 -0.031816352 -0.1271081, -0.41799971 -0.025417108 -0.12581867, -0.4180001 0.019949149 -0.12079817, -0.41799977 -0.015551541 -0.11000016, -0.41799995 0.014827412 -0.1263938, -0.41799983 -0.025928576 -0.12639603, -0.41799971 -0.025417302 -0.12218294, -0.41799971 -0.025058765 -0.12286609, -0.41799971 -0.025928933 -0.12160558, -0.41799971 -0.026563812 -0.12116748, -0.41800013 0.020714935 -0.12089124, -0.41799971 -0.024874199 -0.123615, -0.41800001 0.021436226 -0.12116471, -0.41799968 -0.028050605 -0.12720093, -0.41799983 -0.031050492 -0.12720126, -0.41799971 -0.02487408 -0.12438649, -0.42099971 -0.028050993 -0.12080088, -0.42099968 -0.031050984 -0.12080115, -0.42099968 -0.027285237 -0.12089393, -0.42099974 -0.026563872 -0.12116757, -0.42099974 -0.025928948 -0.12160581, -0.42099971 -0.025417317 -0.12218314, -0.42099974 -0.025058795 -0.12286609, -0.42099974 -0.024874154 -0.12361521, -0.42099974 -0.024874125 -0.12438649, -0.42099974 -0.02505869 -0.12513539, -0.42099974 -0.025417138 -0.12581867, -0.42099974 -0.02592868 -0.126396, -0.42099971 -0.026563514 -0.12683424, -0.42099985 -0.027284775 -0.12710795, -0.42099971 -0.028050605 -0.12720108, -0.42099968 -0.031050626 -0.12720114, -0.42099968 -0.031816471 -0.12710816, -0.42099968 -0.032537717 -0.12683484, -0.42099968 -0.033172611 -0.12639648, -0.42099968 -0.033684243 -0.12581918, -0.42099968 -0.034042794 -0.1251362, -0.42099968 -0.03422742 -0.12438717, -0.42099968 -0.034227524 -0.12361559, -0.42099968 -0.034042899 -0.12286648, -0.42099968 -0.033684436 -0.12218347, -0.42099968 -0.033172894 -0.12160596, -0.42099968 -0.032538015 -0.12116763, -0.42099977 -0.031816695 -0.12089422, -0.42099968 -0.03555033 -0.13300121, -0.42099968 -0.034550298 -0.13400126, -0.42099968 -0.034551341 -0.1140013, -0.42099965 -0.035551358 -0.11500132, -0.42100015 0.019949447 -0.12719828, -0.42099997 0.016949411 -0.12719831, -0.42099997 0.016183596 -0.12710553, -0.42099997 0.01546235 -0.12683198, -0.42099997 0.014827352 -0.1263938, -0.42099994 0.014315721 -0.12581632, -0.42099997 0.013957243 -0.12513342, -0.42100009 0.013772678 -0.12438446, -0.42099997 0.013772469 -0.12361282, -0.42099997 0.013957065 -0.12286371, -0.42099997 0.014315616 -0.12218076, -0.42099997 0.014827054 -0.12160334, -0.42099997 0.015461963 -0.1211651, -0.42099997 0.016183268 -0.12089151, -0.421 0.016949054 -0.12079853, -0.42099997 0.019948941 -0.12079817, -0.421 0.020714816 -0.12089124, -0.42100003 0.021436136 -0.12116477, -0.42100003 0.02207106 -0.12160295, -0.42100003 0.022582661 -0.12218052, -0.42100003 0.022941153 -0.12286326, -0.42100003 0.023125838 -0.12361237, -0.42100003 0.023125928 -0.12438372, -0.42100015 0.022941422 -0.12513283, -0.42100003 0.0225829 -0.12581587, -0.421 0.022071417 -0.12639326, -0.42100003 0.021436524 -0.12683171, -0.42099997 0.020715233 -0.12710536, -0.42100015 0.023449879 -0.1339981, -0.42100003 0.024449702 -0.13299799, -0.42100003 0.024448689 -0.11499792, -0.42099977 -0.015551303 -0.11400029, -0.4209998 -0.012622286 -0.11692917, -0.4209998 -0.013865788 -0.11844444, -0.4209998 -0.015551571 -0.11000022, -0.4209998 -0.011106942 -0.11568516, -0.42099977 -0.014789883 -0.12017331, -0.4209998 -0.013551671 -0.10800025, -0.4209998 -0.0093781687 -0.11476105, -0.42099991 -0.015358645 -0.12204927, -0.42099985 -0.0075022765 -0.11419201, -0.4209998 -0.015550721 -0.12400034, -0.42099991 0.0024483316 -0.10799918, -0.4209998 -0.015358601 -0.12595123, -0.42099991 -0.014789317 -0.12782711, -0.42099991 0.0044484101 -0.10999927, -0.4209998 -0.013865251 -0.12955594, -0.42099974 -0.012621451 -0.13107121, -0.4209998 -0.011106152 -0.1323148, -0.42099983 -0.0093771257 -0.13323861, -0.42099985 -0.0075011738 -0.13380754, -0.51126271 0.066122562 -0.21195298, -0.51078218 0.067707688 -0.21167558, -0.51000857 0.069129869 -0.21122867, -0.50898015 0.070317373 -0.21063474, -0.50774848 0.071210846 -0.2099238, -0.50637567 0.071765453 -0.20913112, -0.50493038 0.071953475 -0.2082966, -0.50348508 0.071765393 -0.20746216, -0.50211221 0.071210757 -0.20666969, -0.50088072 0.070317194 -0.20595869, -0.49985215 0.069129497 -0.20536503, -0.49907848 0.067707509 -0.20491835, -0.49859807 0.066122144 -0.20464113, -0.52256262 0.059774663 -0.16302177, -0.52210575 0.059774812 -0.16460785, -0.52370983 0.05858713 -0.16332924, -0.52324045 0.05858719 -0.16495818, -0.52802753 0.057139214 -0.17047551, -0.52675819 0.057139453 -0.17343509, -0.52950317 0.057693925 -0.1710546, -0.52819496 0.057694133 -0.1741049, -0.52154809 0.062781811 -0.16109732, -0.52116376 0.062781841 -0.16264683, -0.52208883 0.061196562 -0.16122082, -0.52169973 0.061196741 -0.16279054, -0.5253467 0.057139035 -0.16812885, -0.52344483 0.057693955 -0.16867685, -0.52492034 0.057139155 -0.16925606, -0.52385706 0.057693716 -0.16758662, -0.52252078 0.058587309 -0.16710025, -0.52459937 0.057693686 -0.16537714, -0.52125198 0.061196771 -0.16434452, -0.52524567 0.0569514 -0.17272961, -0.52647388 0.056951102 -0.16986594, -0.52212113 0.058587339 -0.16815725, -0.52140468 0.059774842 -0.16669413, -0.52072185 0.062782019 -0.16418096, -0.5237332 0.057139333 -0.17202428, -0.52101558 0.059774872 -0.16772342, -0.52056521 0.06119689 -0.16638848, -0.52229649 0.057693984 -0.17135438, -0.52018386 0.06119686 -0.16739687, -0.52004403 0.062782049 -0.16619852, -0.52100766 0.058587518 -0.17075324, -0.51966757 0.062782228 -0.16719413, -0.51993132 0.059775081 -0.17025149, -0.51912159 0.061197158 -0.16987368, -0.51861876 0.062782347 -0.1696392, -0.53187257 0.062782556 -0.17581946, -0.53124636 0.063195407 -0.17730346, -0.53056008 0.061974462 -0.17795461, -0.53078085 0.063611835 -0.17833877, -0.53056008 0.059775289 -0.17520764, -0.53066117 0.060823675 -0.17661613, -0.53136986 0.061197396 -0.17558515, -0.53024918 0.063195407 -0.17920423, -0.52991384 0.060461339 -0.17761815, -0.52952164 0.060823794 -0.17880526, -0.53104407 0.061974432 -0.17700338, -0.52997309 0.061974552 -0.17905283, -0.52978951 0.059453782 -0.17618638, -0.53708202 0.062781513 -0.15588143, -0.52948374 0.058587726 -0.17470577, -0.53652889 0.061196145 -0.15583992, -0.52898496 0.059148278 -0.17713493, -0.5286696 0.05945402 -0.17833775, -0.5356378 0.059774157 -0.15577334, -0.52866644 0.058334794 -0.17563269, -0.53660208 0.062781692 -0.16014037, -0.52782011 0.058101114 -0.17652863, -0.52757162 0.058334854 -0.17773572, -0.52734804 0.057522412 -0.17498258, -0.53445369 0.058586653 -0.15568447, -0.53637165 0.062781692 -0.16155061, -0.53605372 0.061196502 -0.16005775, -0.52647811 0.057372387 -0.17582983, -0.52628291 0.057522472 -0.17702863, -0.52590066 0.057057377 -0.17426893, -0.52486807 0.057057496 -0.17625231, -0.53303552 0.05769306 -0.1555784, -0.53582531 0.061196472 -0.16145426, -0.52482277 0.056954291 -0.17313173, -0.52486259 0.056956645 -0.17416444, -0.53517014 0.059774484 -0.15992448, -0.52434242 0.056954321 -0.17410594, -0.53145474 0.05713838 -0.15545994, -0.52349311 0.056984272 -0.17468005, -0.52331829 0.056954499 -0.17602178, -0.53580528 0.06278187 -0.16435143, -0.52289492 0.057225432 -0.17298093, -0.53494531 0.059774455 -0.16129926, -0.52192128 0.057225522 -0.17483476, -0.52190012 0.057771947 -0.17182362, -0.53399581 0.058586773 -0.15974775, -0.52979046 0.056950238 -0.15533522, -0.52099353 0.058015313 -0.17265964, -0.52128404 0.057558533 -0.17402604, -0.53526455 0.061196681 -0.16422817, -0.52097785 0.057772037 -0.17363527, -0.52048749 0.057772156 -0.17452535, -0.53377587 0.058586832 -0.16109297, -0.5204069 0.058804836 -0.17140725, -0.53258955 0.057693239 -0.15953574, -0.51950425 0.058804836 -0.17315391, -0.52812618 0.05713826 -0.15521049, -0.51966035 0.059908774 -0.17058137, -0.51960391 0.059518006 -0.17142317, -0.53528935 0.062782049 -0.16643187, -0.53439337 0.059774604 -0.1640293, -0.51923686 0.059908833 -0.17144361, -0.51860112 0.060320254 -0.17203811, -0.53237534 0.057693359 -0.16084608, -0.51833373 0.059908923 -0.17313924, -0.53102213 0.057138588 -0.15929943, -0.52654546 0.05769312 -0.15509203, -0.53475368 0.06119686 -0.16628858, -0.53469604 0.062782168 -0.16849139, -0.53323573 0.058587071 -0.16376525, -0.53081417 0.057138618 -0.16057095, -0.52937192 0.056950536 -0.15905079, -0.52512747 0.058586594 -0.15498573, -0.53389055 0.059774783 -0.1660572, -0.53416598 0.06119686 -0.16832805, -0.53184932 0.057693448 -0.1634489, -0.52917063 0.056950625 -0.16028112, -0.5277217 0.057138618 -0.15880212, -0.52394313 0.059774127 -0.15489703, -0.53274339 0.05858719 -0.16574988, -0.53378588 0.062782288 -0.17120028, -0.53331208 0.059774872 -0.16806471, -0.53030372 0.057138767 -0.16309613, -0.52752715 0.057138618 -0.15999138, -0.5261541 0.057693299 -0.15856585, -0.52305216 0.061196204 -0.15483013, -0.53136969 0.057693567 -0.16538191, -0.53328043 0.062782288 -0.17253688, -0.53326458 0.061197069 -0.17101061, -0.53217751 0.058587339 -0.16771463, -0.52867669 0.056950774 -0.16272482, -0.52596599 0.057693299 -0.15971601, -0.52474791 0.058586832 -0.15835375, -0.52249891 0.062781334 -0.15478852, -0.52983874 0.057138886 -0.16497168, -0.53276414 0.061197098 -0.17233419, -0.53242511 0.059775021 -0.17070517, -0.53081852 0.057693776 -0.1672956, -0.5270496 0.057138767 -0.16235334, -0.52456564 0.058586832 -0.15946895, -0.5235737 0.059774425 -0.15817675, -0.52822655 0.056950804 -0.16453966, -0.53193241 0.05977514 -0.17200801, -0.53130907 0.058587428 -0.17029908, -0.52930373 0.057139095 -0.16682839, -0.52550429 0.057693567 -0.16200048, -0.52339607 0.059774425 -0.15926287, -0.52269 0.061196413 -0.15804356, -0.52661455 0.057138976 -0.16410768, -0.53082699 0.058587428 -0.17157403, -0.52997285 0.057693895 -0.16981271, -0.52770907 0.056950983 -0.16633639, -0.52411789 0.058587041 -0.16168413, -0.52251607 0.061196413 -0.15910751, -0.52214152 0.062781632 -0.15796059, -0.5250833 0.057693537 -0.16369757, -0.52848321 0.057139184 -0.16927049, -0.52611411 0.057138916 -0.16584468, -0.52296001 0.059774484 -0.16141969, -0.52196974 0.062781662 -0.15901098, -0.52691483 0.056951042 -0.16869983, -0.49772954 0.058897521 -0.20413995, -0.49880663 0.057382192 -0.20476207, -0.4969292 0.060626369 -0.20367801, -0.51213104 0.058897968 -0.21245468, -0.51105398 0.05738255 -0.211833, -0.50974172 0.056138929 -0.21107519, -0.51293141 0.060626861 -0.21291655, -0.5082444 0.055214789 -0.21021107, -0.5134241 0.062502831 -0.21320099, -0.49643657 0.062502339 -0.20339331, -0.50661981 0.054645713 -0.2092731, -0.50493032 0.054453429 -0.20829773, -0.5032407 0.054645564 -0.20732212, -0.50161612 0.055214521 -0.20638418, -0.50011885 0.056138646 -0.20551986, -0.53735912 0.070006311 -0.16172442, -0.53636396 0.07152164 -0.16010386, -0.53613448 0.071521789 -0.16150829, -0.53759372 0.070006192 -0.16028935, -0.52957332 0.074258953 -0.1669105, -0.52822679 0.07445094 -0.16453883, -0.52770901 0.074451029 -0.16633558, -0.53011113 0.074258745 -0.16504356, -0.53192317 0.07368964 -0.1655291, -0.53850752 0.068277478 -0.1604273, -0.538082 0.070006073 -0.15595582, -0.53900343 0.06827724 -0.15602508, -0.52465796 0.074258983 -0.16915202, -0.52331901 0.073689908 -0.16739008, -0.52291179 0.073690027 -0.16846669, -0.52508187 0.074258983 -0.16803148, -0.5355705 0.071521878 -0.16429752, -0.53464216 0.072765321 -0.16124496, -0.53409314 0.072765499 -0.1639601, -0.52021056 0.072765797 -0.1703808, -0.52130234 0.072765678 -0.16783521, -0.5198918 0.071522146 -0.16728163, -0.51883715 0.071522266 -0.16974053, -0.52691501 0.074451149 -0.16869888, -0.52584487 0.074258715 -0.16576049, -0.53359294 0.072765589 -0.16597676, -0.5324077 0.07368952 -0.1635755, -0.5382691 0.068277478 -0.16188487, -0.53136593 0.073689789 -0.16746363, -0.53907019 0.066401482 -0.16051194, -0.53957087 0.066401154 -0.15606764, -0.52647412 0.074451149 -0.16986474, -0.53678298 0.07000643 -0.16457427, -0.52177757 0.073690027 -0.17111126, -0.52874827 0.074258983 -0.16936609, -0.53505683 0.071522087 -0.16636893, -0.53882957 0.066401511 -0.16198379, -0.53301787 0.072765678 -0.16797337, -0.52829009 0.074259043 -0.17057762, -0.53768396 0.068277687 -0.16477999, -0.52347773 0.074259132 -0.17190418, -0.53051096 0.073689938 -0.1700075, -0.53625798 0.070006639 -0.16669083, -0.53446591 0.071522176 -0.16841987, -0.53003639 0.073690087 -0.17126283, -0.53823858 0.06640166 -0.16490674, -0.52524579 0.074451387 -0.17272869, -0.53213567 0.072765946 -0.17059895, -0.53715056 0.068277806 -0.16693017, -0.52001005 0.066401213 -0.15460166, -0.53565431 0.070006788 -0.16878653, -0.52057749 0.06827715 -0.15464431, -0.53164566 0.072765917 -0.17189458, -0.52149916 0.070006043 -0.1547133, -0.52701384 0.074259281 -0.17355326, -0.53355968 0.071522295 -0.17111745, -0.51967353 0.066401362 -0.1575886, -0.53770024 0.066401899 -0.16707763, -0.52273917 0.071521342 -0.15480599, -0.53653735 0.068278015 -0.16905904, -0.5330562 0.071522295 -0.1724484, -0.51951188 0.066401511 -0.15857765, -0.52871406 0.073690116 -0.17434597, -0.52023619 0.068277389 -0.15767318, -0.53472829 0.070006907 -0.17154276, -0.52425045 0.072765023 -0.15491906, -0.53708106 0.066402018 -0.16922688, -0.53421396 0.070006967 -0.17290273, -0.53028101 0.072766155 -0.17507675, -0.52007234 0.068277448 -0.15867636, -0.52115005 0.070006192 -0.1578109, -0.53559655 0.068278074 -0.171859, -0.53507417 0.068278164 -0.17324033, -0.51911467 0.066401571 -0.16054186, -0.53165436 0.071522534 -0.17571723, -0.52597451 0.073689163 -0.15504828, -0.53613132 0.066402078 -0.17205364, -0.53560394 0.066402197 -0.17344859, -0.52098238 0.070006162 -0.15883648, -0.53278148 0.070007205 -0.17624292, -0.52237976 0.07152158 -0.15799627, -0.53361899 0.068278193 -0.17663351, -0.53413457 0.066402376 -0.17687398, -0.51966947 0.068277478 -0.1606684, -0.52784514 0.074258149 -0.15518832, -0.53276908 0.06735459 -0.17910424, -0.53210366 0.069165617 -0.1787577, -0.53197777 0.070408612 -0.1772649, -0.51875287 0.06640172 -0.16200063, -0.52220708 0.071521699 -0.1590524, -0.53113759 0.070795566 -0.17825472, -0.53080851 0.070408702 -0.17951062, -0.52387828 0.072765261 -0.15822193, -0.53347951 0.065918922 -0.17842197, -0.53299278 0.065431863 -0.17950168, -0.52057052 0.070006341 -0.16087398, -0.53243905 0.065918982 -0.18040559, -0.530797 0.071861029 -0.1766825, -0.52979052 0.074450314 -0.15533423, -0.52990806 0.072181672 -0.1776146, -0.51930267 0.068277687 -0.16214797, -0.52965438 0.071861118 -0.1788775, -0.52369952 0.072765321 -0.15931556, -0.52938503 0.073028833 -0.17598605, -0.52846229 0.073270768 -0.17686197, -0.51833671 0.06640172 -0.16344509, -0.52827412 0.073028833 -0.17811993, -0.52558786 0.073689312 -0.15847951, -0.52779555 0.073866904 -0.17520228, -0.52178293 0.071521819 -0.16115054, -0.52685571 0.074020922 -0.17602557, -0.53173608 0.074258178 -0.15548006, -0.52672029 0.073867023 -0.17726776, -0.52608991 0.074343145 -0.17436132, -0.52019525 0.07000646 -0.16238707, -0.52515042 0.074403346 -0.17513788, -0.52540207 0.073689342 -0.15961581, -0.52505314 0.074343324 -0.17635289, -0.52433401 0.074439377 -0.17349523, -0.51888055 0.068277687 -0.16361269, -0.52333653 0.074439466 -0.17541111, -0.52744281 0.074258447 -0.15875915, -0.52303708 0.074208289 -0.1722742, -0.52326024 0.07276535 -0.16148776, -0.5231564 0.074317873 -0.17330661, -0.52257574 0.074208409 -0.17320952, -0.53360677 0.073689103 -0.15562028, -0.52168548 0.074067026 -0.17372152, -0.52159256 0.074208528 -0.17504922, -0.51769859 0.066401899 -0.16534492, -0.52093196 0.073525965 -0.17200315, -0.52139652 0.071521848 -0.16270873, -0.5200029 0.073526055 -0.17377225, -0.51981616 0.072650641 -0.17081854, -0.52724946 0.074258506 -0.15994152, -0.51890755 0.07230112 -0.17158878, -0.51976371 0.070006579 -0.16388497, -0.51893973 0.072650701 -0.17254019, -0.52937198 0.074450582 -0.15904993, -0.51824331 0.071237206 -0.17034772, -0.51771009 0.070006877 -0.16921496, -0.517389 0.071237296 -0.17200109, -0.51687264 0.068278015 -0.16882443, -0.51734418 0.066402018 -0.16628191, -0.52494597 0.07368955 -0.16187236, -0.53533071 0.072765082 -0.15574947, -0.51823324 0.068277866 -0.16553932, -0.52286011 0.072765499 -0.16310093, -0.52917075 0.074450672 -0.16028014, -0.52095222 0.071522027 -0.16425154, -0.53130108 0.074258447 -0.15934068, -0.51787388 0.068277925 -0.16648984, -0.52677476 0.074258566 -0.1622898, -0.53684187 0.071521461 -0.15586287, -0.51910168 0.070006669 -0.16585514, -0.52453035 0.07368961 -0.1635482, -0.53109211 0.074258476 -0.16061899, -0.52240002 0.072765589 -0.16469809, -0.5331561 0.073689312 -0.15962008, -0.5187341 0.070006698 -0.16682735, -0.52867669 0.074450731 -0.16272384, -0.51635677 0.066402078 -0.16858423, -0.52027047 0.071522176 -0.16628039, -0.52634221 0.074258655 -0.16403386, -0.53293943 0.073689401 -0.16094479, -0.52405226 0.073689699 -0.16520759, -0.53486562 0.07276535 -0.15987793, -0.53057873 0.074258596 -0.163158, -0.5216943 0.072765738 -0.16679871, -0.51126218 -0.0038775243 -0.21195695, -0.51078176 -0.0022923239 -0.21167949, -0.5100081 -0.00087020174 -0.21123266, -0.50897956 0.0003173314 -0.2106387, -0.50774807 0.0012107156 -0.2099278, -0.50637531 0.0017655455 -0.20913497, -0.50492996 0.0019534193 -0.20830062, -0.50348455 0.0017653666 -0.20746621, -0.50211173 0.0012105815 -0.20667359, -0.5008803 0.00031704828 -0.20596254, -0.49985185 -0.00087048486 -0.20536873, -0.49907807 -0.0022925325 -0.2049222, -0.49859759 -0.0038777329 -0.20464504, -0.5237093 -0.011412967 -0.16333315, -0.52210528 -0.0102253 -0.16461191, -0.52324003 -0.011412922 -0.16496214, -0.52256221 -0.010225419 -0.16302571, -0.52950269 -0.012306083 -0.17105857, -0.52675778 -0.012860615 -0.173439, -0.52819449 -0.012305964 -0.17410874, -0.52802712 -0.012860794 -0.17047951, -0.52116334 -0.0072181113 -0.16265088, -0.52154762 -0.0072182752 -0.1611014, -0.52208847 -0.008803416 -0.16122505, -0.52169919 -0.0088033564 -0.16279453, -0.52534622 -0.012861002 -0.1681329, -0.52344435 -0.012306217 -0.16868076, -0.52491993 -0.012860823 -0.16926003, -0.52385658 -0.012306307 -0.16759062, -0.5245989 -0.012306321 -0.16538116, -0.52252036 -0.011412714 -0.16710424, -0.5212515 -0.0088031925 -0.16434842, -0.52647358 -0.013048891 -0.16986978, -0.52524513 -0.013048742 -0.17273358, -0.52212054 -0.011412669 -0.16816118, -0.52140439 -0.010225151 -0.16669801, -0.52072138 -0.007218007 -0.16418499, -0.52373272 -0.012860704 -0.17202818, -0.52101523 -0.010225061 -0.16772732, -0.52056473 -0.008803118 -0.16639233, -0.52229589 -0.012306083 -0.17135844, -0.52018344 -0.0088030435 -0.16740072, -0.52004343 -0.0072180219 -0.16620252, -0.52100724 -0.01141246 -0.17075709, -0.51966697 -0.0072178878 -0.16719803, -0.5199309 -0.010224957 -0.17025521, -0.51912117 -0.0088029988 -0.16987744, -0.51861829 -0.0072178282 -0.16964313, -0.53187215 -0.0072174557 -0.17582351, -0.53124577 -0.006804768 -0.17730746, -0.53055966 -0.0080255605 -0.17795867, -0.53078038 -0.0063881911 -0.17834264, -0.5305596 -0.010224748 -0.17521167, -0.53066069 -0.0091764219 -0.17662027, -0.53136927 -0.0088027753 -0.17558897, -0.53024888 -0.0068045743 -0.17920834, -0.52991337 -0.0095386542 -0.1776222, -0.52952123 -0.0091762282 -0.17880911, -0.53104365 -0.0080256201 -0.17700726, -0.52997267 -0.0080254264 -0.17905694, -0.52948326 -0.011412326 -0.17470974, -0.52978903 -0.010546152 -0.17619029, -0.53708154 -0.0072185434 -0.15588528, -0.53652841 -0.0088038482 -0.15584388, -0.52898449 -0.010851774 -0.17713884, -0.52866906 -0.010546032 -0.1783419, -0.53563732 -0.010225881 -0.15577725, -0.52866584 -0.011665288 -0.17563665, -0.53660178 -0.0072183795 -0.16014442, -0.52781969 -0.011898998 -0.17653254, -0.52757114 -0.011665139 -0.17773971, -0.53445309 -0.01141334 -0.15568846, -0.52734762 -0.012477685 -0.17498648, -0.53637111 -0.0072182901 -0.16155455, -0.53605318 -0.00880358 -0.16006181, -0.52647752 -0.012627695 -0.17583373, -0.52628249 -0.012477595 -0.17703247, -0.52590019 -0.012942616 -0.17427269, -0.5330351 -0.012306977 -0.15558231, -0.52486759 -0.012942526 -0.1762563, -0.53582489 -0.0088035651 -0.16145822, -0.52482229 -0.013045717 -0.17313564, -0.53516966 -0.010225598 -0.15992853, -0.52486199 -0.013043497 -0.17416838, -0.52434188 -0.013045657 -0.17410979, -0.53145438 -0.012861673 -0.1554637, -0.52349263 -0.01301581 -0.1746842, -0.52331799 -0.013045553 -0.17602575, -0.53580487 -0.007218156 -0.16435549, -0.52289432 -0.012774635 -0.17298499, -0.53494483 -0.010225523 -0.16130316, -0.52192086 -0.012774486 -0.17483875, -0.53399539 -0.011413295 -0.15975159, -0.52189964 -0.01222812 -0.17182758, -0.52978998 -0.013049785 -0.15533912, -0.52099305 -0.011984635 -0.17266366, -0.52128357 -0.012441386 -0.17403004, -0.53526407 -0.0088033415 -0.16423208, -0.52097756 -0.012227852 -0.17363912, -0.52048701 -0.012227882 -0.17452919, -0.53377539 -0.011413191 -0.16109723, -0.52040642 -0.011195291 -0.17141113, -0.53258914 -0.012306813 -0.15953976, -0.51950377 -0.011195142 -0.17315796, -0.52812582 -0.012861673 -0.15521446, -0.51965994 -0.010091204 -0.1705853, -0.53528887 -0.0072179474 -0.16643593, -0.51960343 -0.010482166 -0.17142722, -0.53439301 -0.010225404 -0.16403338, -0.51923627 -0.010091264 -0.17144755, -0.51860064 -0.0096798427 -0.17204201, -0.53237492 -0.012306694 -0.16085002, -0.51833344 -0.010091085 -0.17314315, -0.53102165 -0.012861434 -0.15930349, -0.53475314 -0.0088032074 -0.16629234, -0.52654505 -0.012306947 -0.15509608, -0.53469557 -0.0072177984 -0.16849539, -0.53323513 -0.011412967 -0.16376922, -0.53081387 -0.012861375 -0.16057488, -0.52937144 -0.013049472 -0.15905482, -0.53389013 -0.01022533 -0.1660611, -0.52512699 -0.011413399 -0.15498966, -0.53416556 -0.0088031776 -0.16833195, -0.53184885 -0.012306575 -0.16345263, -0.52917022 -0.013049413 -0.16028509, -0.52772111 -0.012861479 -0.15880615, -0.53274292 -0.011412907 -0.16575381, -0.52394265 -0.010225836 -0.15490094, -0.5337854 -0.0072177537 -0.17120418, -0.53331167 -0.010225181 -0.16806862, -0.5303033 -0.01286136 -0.16310009, -0.52752668 -0.01286139 -0.15999505, -0.52615362 -0.012306798 -0.1585696, -0.53136927 -0.012306456 -0.16538584, -0.52305168 -0.0088038333 -0.15483397, -0.53328001 -0.007217709 -0.17254069, -0.53326422 -0.0088029988 -0.17101452, -0.53217691 -0.011412699 -0.16771868, -0.52867615 -0.013049264 -0.16272873, -0.52596551 -0.012306724 -0.15971991, -0.52474731 -0.011413265 -0.1583578, -0.52983814 -0.012861107 -0.16497567, -0.52249861 -0.0072185881 -0.15479246, -0.53276366 -0.0088029839 -0.17233828, -0.53242463 -0.010225002 -0.17070904, -0.53081805 -0.012306336 -0.16729972, -0.52704912 -0.012861226 -0.16235748, -0.52456504 -0.011413295 -0.159473, -0.5235731 -0.010225687 -0.15818068, -0.52822608 -0.013049159 -0.16454372, -0.53193194 -0.010224912 -0.17201185, -0.53130859 -0.01141255 -0.17030308, -0.52930337 -0.012860898 -0.16683233, -0.5255037 -0.012306515 -0.16200444, -0.52339548 -0.010225628 -0.15926665, -0.52268958 -0.0088035949 -0.15804753, -0.52661413 -0.012861002 -0.1641117, -0.53082639 -0.011412565 -0.17157802, -0.52997237 -0.012306217 -0.1698167, -0.52770847 -0.013049114 -0.16634047, -0.52411729 -0.011412982 -0.16168818, -0.52251559 -0.0088036694 -0.15911147, -0.52214104 -0.0072184391 -0.15796465, -0.52508289 -0.0123065 -0.16370142, -0.52848274 -0.012860928 -0.16927436, -0.52611369 -0.012861107 -0.16584846, -0.52295953 -0.010225464 -0.16142374, -0.52196944 -0.0072183944 -0.15901497, -0.52691442 -0.013048876 -0.16870356, -0.49692887 -0.0093736388 -0.20368192, -0.49772909 -0.011102486 -0.204144, -0.5110535 -0.012617517 -0.21183699, -0.50974125 -0.013861094 -0.2110793, -0.49643621 -0.007497672 -0.20339715, -0.51213056 -0.011102144 -0.21245867, -0.50824398 -0.014785293 -0.21021497, -0.51293099 -0.0093731023 -0.21292061, -0.50661933 -0.015354399 -0.20927703, -0.51342374 -0.0074971952 -0.21320513, -0.50492984 -0.015546668 -0.20830148, -0.50324017 -0.015354458 -0.20732617, -0.50161564 -0.014785487 -0.20638818, -0.50011843 -0.013861362 -0.20552358, -0.49880615 -0.012617756 -0.20476592, -0.5295729 0.0042588376 -0.16691455, -0.53011066 0.0042587779 -0.16504762, -0.52770859 0.0044508986 -0.16633955, -0.53850698 -0.0017226525 -0.16043136, -0.53808147 5.9269369e-06 -0.15595976, -0.53759325 6.2398612e-06 -0.16029325, -0.53900301 -0.001722876 -0.15602916, -0.52465755 0.0042589419 -0.16915607, -0.52508134 0.004258927 -0.1680356, -0.52331847 0.0036898367 -0.16739401, -0.52291137 0.003689941 -0.16847071, -0.53557009 0.0015218519 -0.16430137, -0.536134 0.0015217625 -0.16151208, -0.53464168 0.0027653538 -0.16124889, -0.53409272 0.0027653836 -0.163964, -0.52021021 0.0027658753 -0.17038479, -0.52130193 0.0027656667 -0.16783926, -0.51989144 0.0015220605 -0.16728553, -0.51883674 0.0015222393 -0.16974446, -0.52691454 0.0044510774 -0.16870263, -0.52584428 0.0042587183 -0.16576439, -0.53359252 0.0027655326 -0.16598067, -0.53240722 0.003689494 -0.16357931, -0.53192276 0.003689643 -0.16553319, -0.53826869 -0.001722578 -0.16188869, -0.5373587 6.2696636e-06 -0.16172817, -0.53136545 0.0036897622 -0.16746745, -0.53906965 -0.0035985596 -0.16051596, -0.53957045 -0.0035988428 -0.15607169, -0.5264737 0.0044511668 -0.1698688, -0.53678256 6.3888729e-06 -0.16457817, -0.52177709 0.0036900006 -0.17111543, -0.52874774 0.0042588972 -0.16937003, -0.53505635 0.0015220605 -0.16637287, -0.53882909 -0.0035985 -0.16198775, -0.53301746 0.0027656071 -0.16797712, -0.52828974 0.0042590462 -0.17058137, -0.53768355 -0.0017223693 -0.16478392, -0.52347726 0.0042590462 -0.17190817, -0.5305106 0.0036898367 -0.17001161, -0.53625757 6.6272914e-06 -0.16669497, -0.53446561 0.0015221052 -0.1684238, -0.53003591 0.0036899559 -0.17126688, -0.53823829 -0.0035983212 -0.16491064, -0.52524537 0.0044513457 -0.17273253, -0.53213519 0.0027658455 -0.17060295, -0.53715014 -0.0017222352 -0.16693419, -0.52000976 -0.0035986938 -0.15460566, -0.52012205 -0.0035989471 -0.15160203, -0.53565383 6.7763031e-06 -0.16879046, -0.52057707 -0.0017228611 -0.1546481, -0.52069116 -0.0017229356 -0.15160194, -0.53164524 0.0027658455 -0.17189851, -0.52701336 0.0042591952 -0.1735571, -0.52149868 6.031245e-06 -0.15471715, -0.52161527 5.9120357e-06 -0.15160194, -0.53355914 0.0015222393 -0.17112127, -0.53769982 -0.0035982169 -0.16708168, -0.51967311 -0.0035986342 -0.15759259, -0.53653693 -0.0017221011 -0.169063, -0.52273881 0.0015214197 -0.15480995, -0.52285892 0.0015212409 -0.1516017, -0.53305578 0.0015222393 -0.17245224, -0.52871364 0.0036901496 -0.17434996, -0.51951146 -0.0035985298 -0.15858155, -0.53472781 6.9104135e-06 -0.1715467, -0.52023596 -0.0017226525 -0.15767717, -0.53708065 -0.0035980977 -0.16923082, -0.52424997 0.0027649961 -0.15492296, -0.52437431 0.0027648769 -0.1516017, -0.5342136 7.0296228e-06 -0.17290679, -0.53028041 0.0027660988 -0.17508072, -0.52007192 -0.0017226525 -0.15868011, -0.52114964 6.2100589e-06 -0.15781489, -0.53559613 -0.0017219968 -0.17186293, -0.53507376 -0.0017218627 -0.17324445, -0.53165394 0.0015225373 -0.17572114, -0.51911426 -0.0035984553 -0.1605458, -0.53613091 -0.0035979189 -0.17205778, -0.52597398 0.0036891066 -0.15505233, -0.52610308 0.0036888979 -0.15160179, -0.5356034 -0.0035977848 -0.17345247, -0.53278095 7.1488321e-06 -0.17624676, -0.52098197 6.2696636e-06 -0.15884048, -0.52237946 0.0015215389 -0.15800005, -0.53361845 -0.0017217882 -0.1766375, -0.53413409 -0.0035976507 -0.17687806, -0.51966906 -0.0017225184 -0.16067216, -0.52784473 0.0042581223 -0.15519238, -0.52797908 0.0042580031 -0.1516017, -0.53276861 -0.0026454814 -0.17910829, -0.53210318 -0.00083446875 -0.17876175, -0.53197736 0.00040851161 -0.1772688, -0.51875257 -0.0035983212 -0.16200468, -0.53113717 0.00079550967 -0.17825869, -0.53080815 0.00040866062 -0.17951468, -0.52220672 0.0015216731 -0.15905625, -0.5238778 0.0027652495 -0.15822583, -0.53347903 -0.0040811785 -0.17842594, -0.53299236 -0.0045681484 -0.17950565, -0.53243876 -0.0040809549 -0.18040946, -0.52057004 6.3888729e-06 -0.16087788, -0.53079671 0.0018609874 -0.17668644, -0.5297901 0.0044502579 -0.15533823, -0.51930213 -0.0017223991 -0.16215187, -0.52990752 0.0021816604 -0.17761859, -0.52965409 0.0018611662 -0.17888144, -0.52938443 0.0030287616 -0.17599002, -0.52369899 0.002765175 -0.15931958, -0.52846187 0.0032707416 -0.17686573, -0.51833642 -0.0035982169 -0.1634489, -0.52827364 0.0030288957 -0.17812392, -0.52558738 0.0036892854 -0.15848342, -0.52779514 0.0038669072 -0.17520627, -0.52685541 0.0040208064 -0.1760295, -0.52178246 0.0015217327 -0.16115433, -0.52671987 0.0038669817 -0.1772716, -0.5317356 0.0042580925 -0.1554839, -0.52608961 0.0043430887 -0.17436495, -0.52514982 0.0044032894 -0.17514184, -0.52019477 6.493181e-06 -0.16239089, -0.52505273 0.0043432824 -0.17635694, -0.52540165 0.0036894493 -0.15961978, -0.52433354 0.0044393055 -0.17349914, -0.52333611 0.0044394694 -0.1754151, -0.51888019 -0.0017223842 -0.16361663, -0.52303666 0.0042082928 -0.17227805, -0.52744228 0.0042583458 -0.15876299, -0.52200252 0.0040670149 -0.17311591, -0.52325988 0.0027654283 -0.1614916, -0.52209383 0.0042084418 -0.17413872, -0.52250618 0.0043178163 -0.17455873, -0.52159208 0.0042085312 -0.17505315, -0.53360617 0.0036889873 -0.15562418, -0.52107888 0.0035258643 -0.17170838, -0.52016252 0.0035259686 -0.17348421, -0.51769817 -0.0035980828 -0.16534865, -0.5213961 0.0015218519 -0.16271269, -0.51945966 0.002650585 -0.17154464, -0.52724898 0.0042584948 -0.15994522, -0.51866192 0.0023011081 -0.1720638, -0.51855224 0.0026506893 -0.17324981, -0.51976329 6.5676868e-06 -0.1638889, -0.51812869 0.0012372695 -0.17058349, -0.51770967 6.8210065e-06 -0.16921881, -0.51687217 -0.0017220266 -0.1688284, -0.52937156 0.0044505112 -0.15905383, -0.51726431 0.0012372248 -0.1722315, -0.51734364 -0.003598053 -0.16628602, -0.52494544 0.0036894493 -0.16187605, -0.53533024 0.0027649961 -0.15575346, -0.51823294 -0.0017221905 -0.1655432, -0.52285975 0.002765473 -0.16310474, -0.52917016 0.0044506006 -0.16028401, -0.52095163 0.0015218817 -0.16425559, -0.53130072 0.0042584203 -0.15934461, -0.51787347 -0.0017221309 -0.1664938, -0.52677435 0.0042585991 -0.16229364, -0.53684157 0.001521375 -0.15586662, -0.51910132 6.6272914e-06 -0.16585919, -0.52452976 0.0036895387 -0.16355225, -0.53109163 0.004258465 -0.16062278, -0.52239966 0.0027655922 -0.16470191, -0.53315562 0.0036892258 -0.15962431, -0.51873368 6.7614019e-06 -0.1668314, -0.52867627 0.0044507198 -0.16272768, -0.51635629 -0.003597904 -0.16858813, -0.52026993 0.0015220754 -0.16628429, -0.52634168 0.0042586289 -0.16403767, -0.53293902 0.0036893599 -0.16094881, -0.52405173 0.003689643 -0.16521165, -0.5348652 0.0027652346 -0.15988201, -0.53057832 0.0042586289 -0.16316172, -0.521694 0.002765771 -0.16680261, -0.52822632 0.0044509135 -0.16454268, -0.53636354 0.0015216582 -0.16010782, -0.52012211 -0.0075178184 0.15160283, -0.52069098 -0.0093937702 0.15160283, -0.52161509 -0.011122692 0.15160277, -0.5228588 -0.012638021 0.1516026, -0.52437419 -0.013881672 0.1516026, -0.52610296 -0.014805783 0.1516026, -0.52797896 -0.015374828 0.1516026, -0.49859759 -0.0039008148 0.20464563, -0.51689887 -0.0038991757 0.17294711, -0.51737916 -0.0023139305 0.17322445, -0.49907789 -0.0023155548 0.20492345, -0.51815295 -0.00089192763 0.17367131, -0.4998517 -0.00089367107 0.20537016, -0.51918155 0.0002954714 0.17426515, -0.5008803 0.00029386207 0.20596394, -0.52041292 0.0011890493 0.17497629, -0.50211179 0.0011873059 0.20667508, -0.52178591 0.00174376 0.175769, -0.50348455 0.0017420016 0.20746762, -0.52323121 0.0019317232 0.17660359, -0.50492996 0.0019300692 0.20830223, -0.5246765 0.0017435662 0.17743793, -0.50637525 0.0017419569 0.20913658, -0.50774807 0.0011871122 0.20992923, -0.52604926 0.0011888109 0.1782304, -0.50897956 0.00029351935 0.21064037, -0.52728093 0.00029532239 0.1789414, -0.52830935 -0.00089234486 0.17953515, -0.5100081 -0.00089402869 0.21123379, -0.51078176 -0.0023161806 0.21168053, -0.52908319 -0.0023143776 0.17998189, -0.52956343 -0.0038997419 0.18025914, -0.51126218 -0.0039013512 0.21195787, -0.52256215 -0.00089143589 0.1630266, -0.52210534 -0.00089148059 0.16461253, -0.52370936 0.00029602274 0.16333413, -0.52324009 0.00029594824 0.16496265, -0.52802724 0.001743909 0.17048001, -0.52675772 0.0017437153 0.17343959, -0.52950281 0.001189243 0.17105937, -0.52819449 0.0011890195 0.17410934, -0.52116334 -0.0038985498 0.16265166, -0.52154768 -0.0038986094 0.16110197, -0.52208841 -0.0023133196 0.16122544, -0.52169919 -0.0023133345 0.1627951, -0.52534634 0.0017439835 0.16813362, -0.52344435 0.0011893027 0.16868147, -0.52492005 0.0017440431 0.16926062, -0.5238567 0.0011893176 0.16759145, -0.52252048 0.00029599294 0.16710508, -0.52459896 0.0011896007 0.16538203, -0.52125162 -0.0023135431 0.16434908, -0.5264737 0.0019320063 0.1698705, -0.52524531 0.001931902 0.17273432, -0.52212059 0.00029584393 0.16816187, -0.52140439 -0.00089157 0.16669858, -0.52072144 -0.003898669 0.16418564, -0.52373284 0.0017437302 0.17202899, -0.52101517 -0.00089170411 0.16772792, -0.52056479 -0.0023136176 0.16639313, -0.52229613 0.001189243 0.17135894, -0.52018332 -0.0023136325 0.16740155, -0.52004361 -0.0038986988 0.16620329, -0.52100724 0.00029565021 0.17075801, -0.51966715 -0.0038987435 0.16719866, -0.51993096 -0.00089174882 0.17025614, -0.51912117 -0.0023137368 0.16987848, -0.51861823 -0.0038990863 0.16964385, -0.53187215 -0.0038993396 0.1758242, -0.53124583 -0.0043121912 0.17730811, -0.53055966 -0.0030913837 0.17795932, -0.53078038 -0.0047287382 0.17834336, -0.53055966 -0.00089213625 0.17521226, -0.53066075 -0.0019404925 0.17662087, -0.53136933 -0.002314169 0.17558995, -0.53024876 -0.004312221 0.1792089, -0.52991343 -0.0015782453 0.17762306, -0.52952123 -0.0019405372 0.17881015, -0.53104365 -0.003091339 0.17700803, -0.52997267 -0.0030914582 0.17905754, -0.52978909 -0.00057083741 0.17619124, -0.5370816 -0.0038982965 0.15588608, -0.53652847 -0.0023131855 0.1558446, -0.52948338 0.0002954714 0.17471042, -0.52898455 -0.00026508048 0.17713955, -0.52866918 -0.00057088211 0.17834249, -0.53563756 -0.00089106336 0.15577796, -0.52866602 0.00054835901 0.17563736, -0.53660166 -0.0038986243 0.16014493, -0.52781981 0.00078202412 0.17653337, -0.52757138 0.0005482547 0.17774013, -0.52734768 0.001360815 0.1749872, -0.53445315 0.00029648468 0.1556893, -0.53637111 -0.0038986243 0.16155529, -0.53605318 -0.0023133345 0.16006243, -0.52647775 0.0015109293 0.17583457, -0.52628255 0.0013606511 0.17703333, -0.52590024 0.0018258058 0.17427355, -0.53303522 0.001190003 0.15558314, -0.52486771 0.0018256269 0.17625704, -0.53582484 -0.0023134686 0.16145909, -0.52482253 0.0019289367 0.17313641, -0.53516978 -0.00089136139 0.15992939, -0.5238238 0.001899045 0.17404881, -0.52418679 0.0019265078 0.1754666, -0.52384049 0.0019288473 0.17507401, -0.53145438 0.0017447583 0.15546456, -0.52331799 0.0019286238 0.17602625, -0.52304876 0.0016578548 0.1726729, -0.53580487 -0.0038988478 0.16435611, -0.52208883 0.0016577356 0.17453337, -0.53494489 -0.00089143589 0.161304, -0.53399539 0.00029629096 0.15975249, -0.52197307 0.0011113845 0.17167556, -0.52202076 0.0013245605 0.17261472, -0.52979004 0.0019327961 0.15533966, -0.5215252 0.0011112653 0.17258805, -0.53526425 -0.002313558 0.164233, -0.52073491 0.000867825 0.1731604, -0.52057028 0.0011111908 0.17438245, -0.53377539 0.00029618666 0.16109779, -0.52028579 7.8584999e-05 0.17165673, -0.5325892 0.0011897795 0.15954044, -0.51937258 7.8316778e-05 0.17339811, -0.52812594 0.0017447881 0.15521538, -0.51960224 -0.0010253973 0.17070639, -0.51885372 -0.001436878 0.17155695, -0.53528899 -0.0038988478 0.16643655, -0.53439295 -0.0008915551 0.16403404, -0.51892507 -0.00063473359 0.17273101, -0.51873124 -0.0010255612 0.17241874, -0.51826799 -0.0010256059 0.17326015, -0.5323751 0.0011897795 0.160851, -0.53102177 0.0017445795 0.15930438, -0.52654517 0.0011901669 0.15509677, -0.53475332 -0.0023135729 0.166293, -0.53469563 -0.0038991012 0.16849601, -0.53323537 0.00029611215 0.16377008, -0.53081387 0.0017444007 0.1605756, -0.52937156 0.0019325577 0.15905544, -0.52512693 0.00029654428 0.15499032, -0.53389019 -0.0008915998 0.16606176, -0.53416562 -0.0023138113 0.16833255, -0.53184885 0.0011895262 0.16345325, -0.52917033 0.0019325726 0.1602858, -0.52772123 0.0017445795 0.15880668, -0.52394277 -0.00089100376 0.15490162, -0.53274304 0.00029590353 0.16575444, -0.5337854 -0.0038991161 0.17120484, -0.5333119 -0.00089177862 0.16806921, -0.53030342 0.0017443262 0.16310096, -0.5275268 0.0017444752 0.15999591, -0.52615374 0.0011899583 0.15857047, -0.52305174 -0.0023130216 0.15483457, -0.53136951 0.0011895262 0.16538668, -0.53328001 -0.0038993247 0.1725415, -0.53326416 -0.0023139156 0.17101517, -0.53217715 0.00029581413 0.16771948, -0.52867633 0.0019323938 0.1627295, -0.52596557 0.0011898987 0.15972057, -0.52474755 0.00029654428 0.15835842, -0.52249861 -0.0038982369 0.15479314, -0.52983826 0.0017441772 0.16497633, -0.53276372 -0.0023140945 0.17233875, -0.53242463 -0.00089189783 0.17070982, -0.5308181 0.0011894666 0.16730031, -0.52704924 0.0017443411 0.16235816, -0.5245651 0.00029623136 0.15947381, -0.52357328 -0.00089098886 0.15818137, -0.5282262 0.0019322746 0.16454458, -0.53193206 -0.00089201704 0.17201245, -0.53130871 0.00029565021 0.17030358, -0.52930337 0.0017442517 0.16683316, -0.52550387 0.0011898391 0.16200545, -0.52339566 -0.00089125708 0.15926725, -0.52268958 -0.0023131259 0.15804818, -0.52661419 0.0017442666 0.16411257, -0.53082651 0.00029565021 0.17157882, -0.52997237 0.0011891834 0.16981736, -0.52770859 0.0019322 0.16634119, -0.52411735 0.00029624626 0.1616888, -0.52251565 -0.0023132302 0.15911233, -0.5221411 -0.0038983412 0.15796554, -0.52508301 0.0011895858 0.16370213, -0.52848285 0.0017439984 0.16927505, -0.52611381 0.0017441921 0.16584918, -0.52295959 -0.00089124218 0.16142452, -0.52196932 -0.0038984902 0.15901572, -0.52691454 0.0019321106 0.16870445, -0.50974125 -0.013884831 0.211079, -0.50824398 -0.014809061 0.2102147, -0.50661939 -0.015377853 0.2092765, -0.50492984 -0.015570018 0.20830095, -0.50324017 -0.015377883 0.20732579, -0.51342374 -0.0075212307 0.21320558, -0.49643609 -0.0075205006 0.20339766, -0.5016157 -0.014808778 0.20638788, -0.4969289 -0.0093965121 0.20368227, -0.51293099 -0.0093971081 0.21292084, -0.50011843 -0.013884414 0.20552337, -0.49772912 -0.011125434 0.20414421, -0.51213056 -0.011125971 0.21245873, -0.49880615 -0.012640793 0.20476583, -0.5110535 -0.012641344 0.21183681, -0.53172505 -0.007519532 0.18150693, -0.53123206 -0.0093955286 0.1812222, -0.53043193 -0.011124317 0.18076003, -0.52935475 -0.012639631 0.18013826, -0.5280425 -0.013883177 0.17938036, -0.52654535 -0.014807213 0.17851606, -0.52492052 -0.015376259 0.17757785, -0.52323109 -0.015568469 0.17660254, -0.52154166 -0.015376035 0.17562696, -0.51991695 -0.01480693 0.17468899, -0.51841968 -0.013882745 0.17382479, -0.51710743 -0.012639213 0.17306718, -0.51603037 -0.01112381 0.17244527, -0.51523018 -0.0093949176 0.17198348, -0.51473737 -0.0075189807 0.17169896, -0.53735864 -0.011123274 0.16172898, -0.53636342 -0.012638602 0.16010845, -0.53613394 -0.012638692 0.16151285, -0.53759319 -0.011123288 0.16029397, -0.52957278 -0.015375633 0.16691518, -0.52822608 -0.015567709 0.16454354, -0.52770847 -0.015567828 0.1663402, -0.53011054 -0.015375499 0.16504848, -0.53192264 -0.014806528 0.16553375, -0.53850704 -0.0093943365 0.16043186, -0.53808147 -0.011123005 0.15596044, -0.53900295 -0.0093941726 0.15602955, -0.52465737 -0.015375856 0.16915679, -0.52331835 -0.014806528 0.16739452, -0.52291113 -0.014806751 0.16847131, -0.52508122 -0.015375827 0.16803619, -0.53556997 -0.0126389 0.16430199, -0.53464144 -0.013882224 0.16124952, -0.53409261 -0.013882387 0.16396487, -0.52021009 -0.013882656 0.17038545, -0.52130193 -0.013882492 0.16783985, -0.51989126 -0.012638826 0.16728613, -0.51883668 -0.012639005 0.16974533, -0.52691454 -0.015567932 0.16870353, -0.52584428 -0.015375603 0.16576514, -0.53359252 -0.013882507 0.16598153, -0.5324071 -0.014806498 0.16357994, -0.53826863 -0.0093944259 0.1618894, -0.53136522 -0.014806751 0.16746819, -0.53906971 -0.0075183995 0.16051686, -0.53957057 -0.0075181611 0.1560722, -0.52647358 -0.015567977 0.16986939, -0.53678244 -0.011123542 0.16457894, -0.52177685 -0.014806855 0.17111608, -0.52874768 -0.015375812 0.16937074, -0.53505629 -0.012638811 0.16637373, -0.53882909 -0.0075185485 0.16198841, -0.53301734 -0.013882626 0.16797793, -0.52828962 -0.015375871 0.17058218, -0.53768331 -0.0093946047 0.16478464, -0.52347714 -0.01537602 0.17190892, -0.53051049 -0.014806855 0.17001244, -0.53625751 -0.011123512 0.16669559, -0.53446537 -0.01263902 0.16842461, -0.53003579 -0.014806885 0.17126775, -0.53823811 -0.0075186975 0.16491127, -0.52524519 -0.0155682 0.17273334, -0.53213507 -0.013882715 0.17060375, -0.52000964 -0.0075179078 0.15460649, -0.53715008 -0.009394709 0.16693497, -0.53565377 -0.011123765 0.16879129, -0.52057707 -0.0093938448 0.15464893, -0.53164524 -0.013882864 0.17189917, -0.52149868 -0.011122677 0.15471771, -0.52701324 -0.015376125 0.17355773, -0.53355914 -0.012639198 0.17112193, -0.51967311 -0.0075181015 0.15759319, -0.53769982 -0.0075187422 0.16708231, -0.52273875 -0.0126382 0.15481067, -0.53653693 -0.0093948282 0.16906381, -0.53305572 -0.012639303 0.17245296, -0.5195114 -0.0075180568 0.15858221, -0.52871364 -0.014807034 0.17435062, -0.52023578 -0.0093940683 0.15767801, -0.53472775 -0.01112381 0.1715475, -0.52424985 -0.013881806 0.1549238, -0.53708059 -0.0075189359 0.1692313, -0.53421348 -0.011123959 0.17290729, -0.5200718 -0.0093940385 0.15868077, -0.53028041 -0.013882939 0.1750814, -0.52114958 -0.011122961 0.15781558, -0.53559607 -0.0093950219 0.17186373, -0.51911432 -0.0075183399 0.16054654, -0.5350737 -0.009395007 0.17324519, -0.5316537 -0.012639422 0.17572179, -0.52597398 -0.014805991 0.15505302, -0.53613102 -0.0075190552 0.17205828, -0.5356034 -0.0075191595 0.17345312, -0.52098185 -0.01112299 0.15884125, -0.53278083 -0.011124138 0.17624748, -0.52237922 -0.012638334 0.15800065, -0.53361851 -0.0093953498 0.17663831, -0.53413409 -0.0075194277 0.17687872, -0.519669 -0.0093942322 0.16067314, -0.52784461 -0.015375141 0.15519315, -0.53276861 -0.0084713437 0.17910889, -0.53210312 -0.010282341 0.17876232, -0.51875257 -0.0075183846 0.16200545, -0.53197724 -0.011525426 0.17726961, -0.5222066 -0.012638438 0.15905684, -0.53113705 -0.011912394 0.17825943, -0.52387768 -0.01388197 0.15822655, -0.53080803 -0.01152553 0.17951527, -0.53347903 -0.0070358403 0.17842653, -0.53299236 -0.0065487362 0.17950648, -0.52057004 -0.011123139 0.16087854, -0.53243864 -0.0070360489 0.18041009, -0.52978998 -0.015567292 0.15533879, -0.53079647 -0.012977947 0.17668739, -0.51930219 -0.0093942769 0.16215244, -0.52990741 -0.01329862 0.17761925, -0.52369887 -0.013882209 0.15932012, -0.52965397 -0.012978081 0.17888215, -0.52938443 -0.014145706 0.17599091, -0.51833636 -0.0075184591 0.16344976, -0.52846175 -0.014387596 0.17686668, -0.52558726 -0.014806096 0.15848416, -0.52827352 -0.014145691 0.17812467, -0.52779502 -0.014983658 0.17520693, -0.52178246 -0.012638617 0.16115522, -0.52685529 -0.015137825 0.17603031, -0.53173548 -0.015375096 0.15548477, -0.52671975 -0.014983822 0.17727223, -0.52608931 -0.015460018 0.17436591, -0.52019471 -0.011123169 0.16239169, -0.52540153 -0.014806274 0.15962029, -0.52514988 -0.0155201 0.1751425, -0.52505249 -0.015460122 0.17635778, -0.52433342 -0.015556086 0.17349997, -0.51888007 -0.0093944706 0.16361734, -0.52333599 -0.015556205 0.1754159, -0.52744216 -0.015375156 0.15876389, -0.52303648 -0.015325177 0.17227885, -0.52325982 -0.013882119 0.16149247, -0.52200228 -0.015183751 0.17311653, -0.52209359 -0.015325222 0.17413953, -0.53360623 -0.014806051 0.15562487, -0.522506 -0.015434612 0.17455938, -0.52159184 -0.015325222 0.17505375, -0.51769817 -0.007518623 0.16534948, -0.52107877 -0.014642674 0.17170918, -0.52139598 -0.012638498 0.16271353, -0.5201624 -0.014642823 0.17348492, -0.51945955 -0.013767306 0.17154515, -0.52724892 -0.01537529 0.15994608, -0.51976317 -0.011123363 0.16388956, -0.5186618 -0.013417933 0.17206454, -0.51855201 -0.013767455 0.17325056, -0.52937144 -0.015567411 0.15905461, -0.51812857 -0.012353901 0.1705842, -0.51770955 -0.011123646 0.16921958, -0.51687211 -0.009394709 0.1688292, -0.51734376 -0.007518623 0.16628683, -0.51726419 -0.012354169 0.17223254, -0.52494544 -0.014806259 0.16187707, -0.53533024 -0.013881985 0.15575436, -0.51823288 -0.0093944706 0.16554403, -0.52285975 -0.013882119 0.16310549, -0.52917022 -0.015567426 0.16028488, -0.52095157 -0.012638766 0.16425622, -0.53130049 -0.015375245 0.15934527, -0.51787341 -0.0093945153 0.16649437, -0.52677423 -0.01537535 0.16229442, -0.53684133 -0.012638319 0.15586746, -0.5191012 -0.011123408 0.16586006, -0.52452976 -0.014806498 0.16355288, -0.53109139 -0.015375365 0.16062355, -0.5223996 -0.013882343 0.16470277, -0.5331555 -0.014806319 0.15962493, -0.51873368 -0.011123408 0.16683197, -0.52867621 -0.015567545 0.16272855, -0.51635629 -0.0075187422 0.16858894, -0.52026981 -0.012638796 0.16628516, -0.52634174 -0.015375484 0.16403854, -0.5329389 -0.014806364 0.16094935, -0.52405173 -0.014806498 0.16521215, -0.53486508 -0.013882179 0.15988278, -0.5305782 -0.015375424 0.16316259, -0.52169389 -0.013882447 0.16680348, -0.53099984 -0.013056863 0.12435785, -0.53099984 -0.013056863 0.1236423, -0.53099984 -0.013042901 -0.124358, -0.53099984 -0.013042975 -0.12364236, 0.53389072 -0.010218371 -0.16606113, 0.53331238 -0.010218192 -0.16806856, 0.53274375 -0.011406038 -0.16575387, 0.53217775 -0.011405934 -0.16771853, 0.52344495 -0.012299422 -0.16868076, 0.5237332 -0.01285385 -0.17202833, 0.52229673 -0.012299169 -0.17135823, 0.52492076 -0.012853984 -0.16925997, 0.53487593 -0.0055420138 -0.16855073, 0.53528959 -0.0072109886 -0.16643584, 0.53598887 -0.0055422075 -0.16439721, 0.53580564 -0.0072111674 -0.16435549, 0.53526479 -0.008796338 -0.16423208, 0.53475392 -0.0087962635 -0.16629234, 0.52848345 -0.012854014 -0.16927448, 0.52950352 -0.012299169 -0.17105857, 0.52802783 -0.012853879 -0.17047945, 0.52997315 -0.012299303 -0.16981664, 0.53130943 -0.01140571 -0.17030287, 0.5308187 -0.012299422 -0.16729972, 0.5341661 -0.0087962188 -0.16833189, 0.52647418 -0.013042066 -0.16986969, 0.52524596 -0.013041917 -0.17273358, 0.53082722 -0.011405621 -0.17157796, 0.53242522 -0.010218088 -0.17070901, 0.53469628 -0.0072108395 -0.1684953, 0.52675837 -0.012853701 -0.173439, 0.53193265 -0.010218043 -0.17201185, 0.53326494 -0.0087960251 -0.17101446, 0.52819508 -0.012298975 -0.17410874, 0.53276426 -0.0087959953 -0.17233825, 0.53378624 -0.0072108842 -0.17120412, 0.53345579 -0.0055417158 -0.17260933, 0.51844853 -0.0055421032 -0.1695635, 0.51689953 -0.0072108246 -0.17294648, 0.51673669 -0.0055418499 -0.17285231, 0.52948397 -0.011405353 -0.17470974, 0.53328079 -0.0072107948 -0.17254069, 0.53056031 -0.010217879 -0.17521146, 0.53136998 -0.0087957717 -0.175589, 0.53187281 -0.0072105862 -0.17582336, 0.53173614 -0.0055415668 -0.17655054, 0.5306614 -0.0091694929 -0.17662016, 0.53056031 -0.0080185868 -0.17795855, 0.52991396 -0.0095318295 -0.1776222, 0.52831 -0.010217655 -0.17953432, 0.52952188 -0.0091694184 -0.17880905, 0.52908379 -0.0087954439 -0.17998093, 0.53124648 -0.0067977943 -0.17730752, 0.53078121 -0.0063813366 -0.17834264, 0.52972704 -0.0055414177 -0.18035218, 0.52956408 -0.0072102733 -0.18025824, 0.53024942 -0.0067977794 -0.17920819, 0.52978975 -0.010539223 -0.17619029, 0.52261859 -0.0072119124 -0.1516023, 0.52249926 -0.0072118081 -0.15479231, 0.5224306 -0.005543042 -0.1516023, 0.52226871 -0.0055428483 -0.15530634, 0.5289852 -0.010844875 -0.17713884, 0.52728152 -0.011405159 -0.17894059, 0.52866977 -0.010539103 -0.1783419, 0.52317327 -0.0087972023 -0.15160239, 0.52305228 -0.0087970831 -0.15483397, 0.5310443 -0.0080186166 -0.17700726, 0.52997333 -0.0080185421 -0.17905667, 0.52406675 -0.01021919 -0.15160248, 0.52394348 -0.010219026 -0.15490073, 0.52866656 -0.01165827 -0.17563665, 0.52214193 -0.0072115697 -0.15796462, 0.52178484 -0.0055426396 -0.15898231, 0.52782053 -0.011892129 -0.17653254, 0.52525443 -0.011406738 -0.15160254, 0.52512759 -0.011406589 -0.15498972, 0.52605003 -0.012298871 -0.17822966, 0.52757186 -0.01165827 -0.17773956, 0.52734834 -0.012470786 -0.17498639, 0.52197009 -0.0072115548 -0.15901509, 0.52269036 -0.0087968595 -0.15804747, 0.52647823 -0.012620721 -0.17583373, 0.5246771 -0.012853552 -0.17743722, 0.5262832 -0.012470786 -0.17703247, 0.52667648 -0.012300272 -0.15160254, 0.5265457 -0.012300167 -0.15509593, 0.5259009 -0.012935806 -0.17427278, 0.5232318 -0.013041664 -0.17660275, 0.52486831 -0.012935687 -0.1762563, 0.52251631 -0.0087967403 -0.15911141, 0.52482301 -0.013038848 -0.17313564, 0.52357382 -0.010218833 -0.15818068, 0.5282616 -0.012854982 -0.15160263, 0.52812648 -0.012854774 -0.15521446, 0.52382427 -0.013009015 -0.17404822, 0.52384108 -0.013038758 -0.1750733, 0.52418745 -0.013036478 -0.1754657, 0.52154833 -0.0072114356 -0.1611014, 0.52098244 -0.0055424459 -0.16260213, 0.52178651 -0.012853745 -0.17576829, 0.52331871 -0.013038758 -0.17602575, 0.52339619 -0.010218773 -0.15926665, 0.52304941 -0.012767855 -0.17267203, 0.52208942 -0.012767825 -0.1745328, 0.52474821 -0.011406351 -0.15835777, 0.52993053 -0.013042931 -0.15160263, 0.5297907 -0.013042871 -0.15533912, 0.52197367 -0.012221295 -0.171675, 0.52100796 -0.01140571 -0.1707572, 0.52202147 -0.012434606 -0.17261377, 0.5215258 -0.012221266 -0.17258731, 0.52208906 -0.0087966956 -0.16122481, 0.52073568 -0.011977855 -0.1731596, 0.52456576 -0.011406366 -0.159473, 0.52057081 -0.012221102 -0.17438164, 0.52615434 -0.012299899 -0.15856975, 0.52041376 -0.012298975 -0.17497543, 0.51918203 -0.011405487 -0.17426443, 0.52028626 -0.011188496 -0.17165613, 0.53145504 -0.012854774 -0.15546384, 0.51937324 -0.011188377 -0.1733973, 0.51815361 -0.010218073 -0.17367056, 0.53159946 -0.012854967 -0.15160263, 0.51993161 -0.010218222 -0.17025518, 0.51960284 -0.010084424 -0.17070571, 0.51912171 -0.0087961443 -0.16987753, 0.52116388 -0.0072113015 -0.16265076, 0.51885432 -0.0096730031 -0.17155614, 0.52296025 -0.010218713 -0.16142374, 0.51737994 -0.0087960251 -0.17322364, 0.518619 -0.0072110184 -0.16964304, 0.51873189 -0.010084454 -0.17241779, 0.51892573 -0.010475222 -0.17273021, 0.52596617 -0.012299884 -0.15971991, 0.51826864 -0.01008432 -0.17325941, 0.52772182 -0.012854565 -0.15880591, 0.5330357 -0.012300033 -0.15558222, 0.53318471 -0.012300286 -0.15160254, 0.52169985 -0.0087966062 -0.16279453, 0.52072197 -0.0072113164 -0.16418466, 0.51986748 -0.0055422969 -0.16613814, 0.52411801 -0.011406291 -0.16168806, 0.52752739 -0.01285449 -0.15999523, 0.52937204 -0.013042558 -0.15905473, 0.53460675 -0.011406723 -0.15160254, 0.53445381 -0.011406396 -0.15568852, 0.52256292 -0.010218579 -0.16302571, 0.5212521 -0.0087964423 -0.16434842, 0.52550429 -0.01229969 -0.16200444, 0.52917093 -0.013042513 -0.16028494, 0.53102237 -0.01285452 -0.15930355, 0.53579432 -0.010219146 -0.15160248, 0.53563803 -0.010218892 -0.15577716, 0.52370995 -0.011406187 -0.16333315, 0.52004415 -0.0072111674 -0.16620243, 0.52210599 -0.010218535 -0.16461205, 0.52704984 -0.012854371 -0.1623573, 0.53081447 -0.012854401 -0.16057485, 0.53258985 -0.012299825 -0.15953967, 0.536529 -0.0087967999 -0.15584388, 0.53668791 -0.0087971278 -0.15160239, 0.52508348 -0.012299586 -0.16370136, 0.5196678 -0.0072111525 -0.16719794, 0.52056551 -0.008796338 -0.16639227, 0.52324075 -0.011406008 -0.16496202, 0.52867693 -0.013042424 -0.16272873, 0.53237563 -0.012299735 -0.16085017, 0.53399605 -0.011406306 -0.15975165, 0.53708214 -0.0072115399 -0.15588525, 0.53726977 -0.0055426694 -0.15589929, 0.53743047 -0.0055429377 -0.15160215, 0.53724247 -0.0072118081 -0.1516023, 0.52661473 -0.012854267 -0.16411158, 0.5201841 -0.0087963976 -0.16740084, 0.52140504 -0.010218326 -0.16669798, 0.52459961 -0.012299586 -0.16538104, 0.53030407 -0.012854312 -0.16309997, 0.5337761 -0.011406172 -0.16109702, 0.53517038 -0.010218699 -0.15992853, 0.52822679 -0.013042215 -0.1645436, 0.52101582 -0.010218356 -0.1677272, 0.52252096 -0.011405844 -0.16710424, 0.5261144 -0.012854192 -0.16584843, 0.53184944 -0.012299646 -0.16345263, 0.53494555 -0.010218624 -0.16130298, 0.53605384 -0.008796636 -0.16006172, 0.52983886 -0.012854207 -0.16497567, 0.52212125 -0.011405978 -0.16816115, 0.52385747 -0.012299541 -0.16759062, 0.52770907 -0.013042096 -0.16634038, 0.53323597 -0.011406053 -0.1637691, 0.53582555 -0.0087965764 -0.1614581, 0.53678828 -0.0055424012 -0.16017225, 0.53660232 -0.007211376 -0.1601443, 0.53136998 -0.012299422 -0.16538584, 0.52534693 -0.012854192 -0.16813287, 0.52930391 -0.012854088 -0.16683242, 0.53439361 -0.010218475 -0.16403329, 0.53637177 -0.0072113462 -0.16155452, 0.52691513 -0.013042007 -0.16870368, 0.52584475 0.0042656474 -0.16576433, 0.52634221 0.0042655282 -0.16403767, 0.52770907 0.0044578575 -0.1663394, 0.52023637 -0.0017158724 -0.15767717, 0.52149916 1.2826174e-05 -0.154717, 0.52115023 1.2990087e-05 -0.15781474, 0.52057779 -0.0017160811 -0.1546481, 0.52829027 0.0042659007 -0.17058143, 0.52874839 0.0042659156 -0.16936994, 0.53003645 0.003696885 -0.17126682, 0.52178311 0.0015284531 -0.16115433, 0.52369946 0.002772104 -0.15931949, 0.52326041 0.0027721487 -0.16149148, 0.5222072 0.0015284382 -0.15905643, 0.53028101 0.0027730577 -0.17508072, 0.53164577 0.0027728789 -0.17189851, 0.53305638 0.0015291981 -0.17245221, 0.53165448 0.001529526 -0.17572108, 0.52691513 0.0044579022 -0.16870263, 0.5295732 0.0042657964 -0.16691446, 0.52286035 0.0027723126 -0.16310474, 0.52494591 0.0036962144 -0.16187614, 0.52453023 0.0036964528 -0.16355211, 0.52007234 -0.0017158277 -0.15868011, 0.52098256 1.3079494e-05 -0.15884057, 0.5240522 0.0036965422 -0.16521153, 0.51967371 -0.0035918243 -0.15759245, 0.52001023 -0.0035920329 -0.15460563, 0.51932281 -0.0055426694 -0.15854806, 0.51977825 -0.0055429228 -0.15508837, 0.52647412 0.0044579469 -0.16986874, 0.5205707 1.3168901e-05 -0.16087788, 0.52871418 0.0036970489 -0.17434987, 0.52508181 0.0042657815 -0.16803539, 0.52139664 0.0015286617 -0.16271251, 0.51951206 -0.0035917796 -0.15858141, 0.5224002 0.0027723722 -0.16470191, 0.52465814 0.0042657964 -0.16915596, 0.51966965 -0.0017157234 -0.16067231, 0.5270139 0.004266154 -0.17355695, 0.52331901 0.0036966465 -0.16739392, 0.52019525 1.3243407e-05 -0.16239089, 0.52095217 0.0015287362 -0.16425529, 0.52291173 0.003696721 -0.16847074, 0.51911485 -0.0035916306 -0.16054577, 0.51856762 -0.0055425651 -0.16195497, 0.52524573 0.0044581406 -0.17273247, 0.52169454 0.0027725212 -0.1668025, 0.51930285 -0.0017156191 -0.16215187, 0.51457149 -0.0055419691 -0.17160216, 0.51618284 -0.0055422075 -0.16850689, 0.5147379 -0.0035910644 -0.17169824, 0.53957117 -0.0035917647 -0.15607154, 0.5397383 -0.003592018 -0.15160203, 0.53993046 -0.005542893 -0.15160218, 0.51976389 1.3273209e-05 -0.16388881, 0.53976279 -0.0055426694 -0.15608597, 0.52130252 0.0027724765 -0.16783914, 0.53900373 -0.0017158426 -0.15602899, 0.53916919 -0.0017160214 -0.15160203, 0.52347761 0.004266005 -0.17190817, 0.53808212 1.3049692e-05 -0.15595976, 0.5382452 1.2781471e-05 -0.15160179, 0.52027053 0.0015287809 -0.16628444, 0.51875305 -0.0035915263 -0.16200468, 0.53907043 -0.0035915412 -0.16051584, 0.53926045 -0.0055424459 -0.16054481, 0.53684199 0.001528319 -0.15586674, 0.53700149 0.00152817 -0.15160179, 0.51888078 -0.0017155595 -0.16361666, 0.51989186 0.0015288852 -0.16728553, 0.52177751 0.0036968701 -0.17111528, 0.53882974 -0.0035914518 -0.16198763, 0.53842622 -0.0055422075 -0.16495344, 0.53850758 -0.0017156191 -0.16043109, 0.51910174 1.3422221e-05 -0.1658591, 0.51833707 -0.0035915263 -0.1634489, 0.51751822 -0.0055422224 -0.16528293, 0.53533089 0.0027720146 -0.15575352, 0.5354861 0.0027718209 -0.1516017, 0.51873422 1.3496727e-05 -0.16683125, 0.52021062 0.0027727 -0.17038479, 0.53826928 -0.001715485 -0.16188869, 0.51823342 -0.0017154254 -0.1655432, 0.53759396 1.3243407e-05 -0.16029325, 0.517874 -0.0017154552 -0.16649365, 0.53823894 -0.0035912879 -0.16491064, 0.53360671 0.0036960207 -0.15562415, 0.53375727 0.0036958568 -0.1516017, 0.51883721 0.0015289895 -0.16974437, 0.51769882 -0.0035913922 -0.16534865, 0.53735924 1.3183802e-05 -0.16172817, 0.51734424 -0.0035913177 -0.16628587, 0.51771021 1.3675541e-05 -0.16921902, 0.53636396 0.0015285723 -0.16010776, 0.51687264 -0.0017152466 -0.16882846, 0.51635695 -0.0035912283 -0.16858807, 0.51523077 -0.0017150678 -0.17198253, 0.53768402 -0.0017152913 -0.16478398, 0.53173614 0.0042650811 -0.15548399, 0.53188133 0.0042649172 -0.1516017, 0.53210378 -0.00082758442 -0.17876166, 0.53276926 -0.0026385523 -0.17910808, 0.53123283 -0.0017145015 -0.18122137, 0.53361911 -0.0017147996 -0.17663744, 0.53770047 -0.003591124 -0.16708156, 0.53726488 -0.0055419542 -0.16928753, 0.53347975 -0.0040742047 -0.17842603, 0.53413486 -0.0035906471 -0.17687804, 0.53398865 -0.0055414774 -0.17763534, 0.5329929 -0.0045611747 -0.17950553, 0.53189212 -0.0055412687 -0.18160227, 0.53613442 0.0015286617 -0.16151208, 0.53243917 -0.0040740855 -0.18040934, 0.53172559 -0.0035903342 -0.1815061, 0.53197789 0.00041553006 -0.17726874, 0.53278148 1.4137477e-05 -0.17624676, 0.53486562 0.0027722977 -0.15988201, 0.53678304 1.3511628e-05 -0.16457808, 0.5311377 0.0008024089 -0.17825869, 0.53080881 0.00041554496 -0.17951477, 0.53043246 1.4375895e-05 -0.18075913, 0.52935553 0.0015296452 -0.18013734, 0.53079724 0.0018678866 -0.17668644, 0.52979052 0.0044572018 -0.1553382, 0.52993041 0.0044570528 -0.1516017, 0.52990818 0.0021885745 -0.17761853, 0.5371508 -0.0017152764 -0.16693419, 0.5296545 0.0018680207 -0.17888135, 0.52804297 0.0027732365 -0.17937961, 0.52938497 0.0030355714 -0.17599002, 0.53464222 0.002772253 -0.16124889, 0.52846241 0.0032776408 -0.17686582, 0.53708124 -0.0035910048 -0.16923073, 0.528274 0.0030357651 -0.17812377, 0.53315616 0.0036962442 -0.15962416, 0.52654582 0.0036972575 -0.17851514, 0.52779561 0.0038737468 -0.17520621, 0.53557074 0.0015288554 -0.16430137, 0.52685595 0.0040277354 -0.17602935, 0.52672035 0.0038738959 -0.1772716, 0.5249213 0.0042662285 -0.17757717, 0.5278452 0.0042649768 -0.15519238, 0.52797961 0.0042648576 -0.1516017, 0.52609009 0.004349988 -0.17436516, 0.52515054 0.0044101141 -0.17514163, 0.5362581 1.366064e-05 -0.16669485, 0.5250532 0.0043500625 -0.17635694, 0.52323169 0.0044583194 -0.1766018, 0.52433395 0.0044461749 -0.17349902, 0.53293973 0.003696274 -0.16094849, 0.52333659 0.0044462197 -0.17541504, 0.52154213 0.0042661838 -0.17562619, 0.53653753 -0.0017152317 -0.169063, 0.52303714 0.0042151175 -0.17227805, 0.53130108 0.0042653047 -0.15934452, 0.52315634 0.0043246858 -0.17331064, 0.52257586 0.004215192 -0.17321351, 0.5340932 0.002772402 -0.16396415, 0.52597451 0.0036958568 -0.1550523, 0.52610368 0.0036957078 -0.1516017, 0.52168566 0.0040737949 -0.17372552, 0.52159262 0.004215207 -0.17505315, 0.51991755 0.0036970489 -0.17468825, 0.53613156 -0.003590975 -0.17205763, 0.53578293 -0.0055418052 -0.17352286, 0.52093202 0.0035326891 -0.17200711, 0.53505689 0.0015289746 -0.16637293, 0.5200029 0.0035327636 -0.17377618, 0.51842034 0.0027728342 -0.17382398, 0.51981634 0.0026574098 -0.17082238, 0.53109217 0.0042653792 -0.16062278, 0.51890761 0.0023077689 -0.17159283, 0.51893991 0.0026573949 -0.172544, 0.51710802 0.0015291534 -0.17306629, 0.53565437 1.3839453e-05 -0.16879034, 0.51824355 0.0012439452 -0.17035162, 0.52937192 0.0044574253 -0.15905374, 0.51738918 0.0012439601 -0.17200494, 0.51603103 1.3720244e-05 -0.17244461, 0.535604 -0.003590811 -0.17345226, 0.5324077 0.003696572 -0.1635792, 0.52425051 0.0027718209 -0.15492311, 0.52437484 0.0027715825 -0.1516017, 0.53559679 -0.0017150082 -0.17186287, 0.53359318 0.0027725212 -0.16598055, 0.52917081 0.0044575296 -0.16028401, 0.53446609 0.001529064 -0.16842386, 0.52744287 0.0042651854 -0.1587629, 0.53507435 -0.001714889 -0.17324445, 0.53057879 0.0042655431 -0.16316184, 0.52273929 0.0015282594 -0.15480989, 0.52285945 0.0015279613 -0.15160179, 0.53472841 1.3899058e-05 -0.17154685, 0.53192329 0.0036965422 -0.16553301, 0.52724952 0.0042653196 -0.15994522, 0.53301799 0.0027725957 -0.16797721, 0.52558786 0.0036961697 -0.15848333, 0.53421414 1.3884157e-05 -0.17290667, 0.52867675 0.0044576041 -0.16272768, 0.5216158 1.2721866e-05 -0.15160194, 0.53355968 0.0015291534 -0.17112127, 0.53011119 0.0042655729 -0.1650475, 0.52540225 0.0036961697 -0.15961966, 0.53136599 0.0036966465 -0.16746739, 0.52387846 0.0027720593 -0.15822586, 0.52677488 0.0042653494 -0.16229361, 0.52069163 -0.0017162152 -0.15160194, 0.53213578 0.0027727447 -0.17060295, 0.52822673 0.0044576637 -0.16454253, 0.52237999 0.0015283786 -0.15800002, 0.51993054 -0.005543042 -0.15160215, 0.52012265 -0.0035921521 -0.15160203, 0.53051108 0.0036968403 -0.1700114, 0.53389078 -0.00088461116 0.16606185, 0.53331232 -0.00088480487 0.16806927, 0.53274351 0.00030292198 0.16575465, 0.53217745 0.00030268356 0.16771957, 0.52344501 0.0011961423 0.1686815, 0.52373314 0.0017506741 0.17202905, 0.52229655 0.0011961423 0.17135903, 0.52492064 0.001750838 0.16926077, 0.53487593 -0.0055610277 0.16855136, 0.53528953 -0.003891889 0.16643658, 0.53598887 -0.0055607297 0.16439807, 0.53580552 -0.0038918741 0.16435614, 0.53526479 -0.0023066439 0.16423294, 0.5347538 -0.0023066737 0.16629311, 0.52848339 0.0017508976 0.16927519, 0.52950329 0.0011961423 0.17105925, 0.52802765 0.0017508827 0.17048022, 0.52997297 0.0011961423 0.16981736, 0.53130925 0.00030263886 0.17030367, 0.53081864 0.0011963956 0.16730031, 0.53416628 -0.0023069121 0.16833267, 0.52647406 0.0019389354 0.16987059, 0.52524573 0.0019387566 0.17273441, 0.53082716 0.00030257925 0.17157891, 0.53242522 -0.00088492408 0.17070982, 0.53469616 -0.0038920529 0.1684961, 0.52675825 0.0017506294 0.17343968, 0.53193259 -0.00088501349 0.17201266, 0.53326488 -0.0023069717 0.17101541, 0.52819514 0.0011959635 0.17410955, 0.53276432 -0.0023070611 0.17233875, 0.51844853 -0.0055611767 0.1695644, 0.51689935 -0.0038924403 0.17294714, 0.51673657 -0.0055613406 0.17285293, 0.53345567 -0.0055612363 0.17261022, 0.53378624 -0.0038922466 0.17120489, 0.5294838 0.00030244514 0.17471069, 0.53328079 -0.0038924105 0.17254156, 0.53056026 -0.00088522211 0.1752122, 0.53136992 -0.0023071803 0.17558995, 0.53187281 -0.0038924702 0.17582434, 0.53173608 -0.0055613555 0.1765514, 0.53066123 -0.0019335635 0.17662087, 0.53056026 -0.0030844249 0.17795941, 0.5299139 -0.0015712418 0.17762294, 0.52830982 -0.00088540092 0.17953521, 0.52952176 -0.0019336231 0.17881003, 0.52908379 -0.0023074187 0.17998198, 0.53124642 -0.0043052174 0.17730811, 0.53078091 -0.0047217645 0.17834347, 0.52972692 -0.0055617429 0.18035302, 0.5302493 -0.0043052472 0.17920902, 0.52956408 -0.0038928278 0.18025926, 0.52978969 -0.00056389347 0.17619118, 0.52261859 -0.0038912781 0.15160322, 0.5224992 -0.0038914718 0.1547932, 0.52243048 -0.0055601336 0.15160298, 0.52226871 -0.0055603273 0.15530717, 0.52898514 -0.00025827065 0.17713958, 0.52317321 -0.0023059882 0.15160322, 0.52305216 -0.0023060776 0.15483472, 0.52728134 0.00030220672 0.1789414, 0.52866971 -0.00056392327 0.17834252, 0.53104413 -0.0030843653 0.17700809, 0.52406669 -0.00088394061 0.15160343, 0.52394331 -0.00088410452 0.15490168, 0.52997333 -0.0030844696 0.17905769, 0.52866644 0.00055542216 0.1756373, 0.52214175 -0.0038915612 0.15796533, 0.52178484 -0.0055603869 0.15898302, 0.52525425 0.00030356273 0.15160343, 0.52512753 0.00030339882 0.15499038, 0.52782035 0.00078893825 0.17653337, 0.52604985 0.0011956804 0.17823055, 0.52757192 0.00055518374 0.17774037, 0.52734822 0.0013677888 0.17498726, 0.52196997 -0.00389174 0.1590158, 0.52269018 -0.0023063459 0.15804818, 0.52647817 0.0015177988 0.17583472, 0.52467704 0.0017504655 0.17743793, 0.52628314 0.0013675056 0.17703328, 0.5266763 0.0011971556 0.15160343, 0.52654552 0.0011969917 0.15509677, 0.52590078 0.0018326156 0.17427358, 0.52251631 -0.0023063757 0.15911227, 0.52323174 0.0019384138 0.1766035, 0.52486825 0.0018324666 0.17625719, 0.52357382 -0.00088420883 0.15818146, 0.52482295 0.0019357912 0.1731365, 0.52826142 0.001751896 0.15160352, 0.52812642 0.0017516129 0.15521532, 0.52486271 0.0019334517 0.17416918, 0.5243426 0.0019357316 0.17411083, 0.52154821 -0.0038917996 0.16110224, 0.52098233 -0.0055606402 0.16260281, 0.52349305 0.0019058846 0.17468494, 0.52339619 -0.00088444725 0.15926734, 0.52178633 0.0017505996 0.17576903, 0.52331847 0.0019355975 0.17602649, 0.52289498 0.0016646497 0.1729857, 0.52474821 0.00030322 0.15835848, 0.52041358 0.0011958443 0.17497638, 0.52192134 0.0016646348 0.17483947, 0.52993035 0.0019399635 0.15160352, 0.52979052 0.0019396804 0.15533981, 0.5219003 0.0011180602 0.17182848, 0.52100778 0.00030266866 0.17075807, 0.52099365 0.00087464973 0.17266434, 0.522089 -0.0023065247 0.16122571, 0.52097821 0.0011180155 0.17363995, 0.52128416 0.0013314001 0.17403084, 0.52456564 0.0003032051 0.15947369, 0.52615416 0.0011968724 0.15857056, 0.52048767 0.0011180155 0.17452997, 0.51918209 0.00030237064 0.17426521, 0.52040696 8.5305423e-05 0.17141202, 0.53145486 0.0017517321 0.15546468, 0.51993155 -0.00088496879 0.17025623, 0.51950455 8.5111707e-05 0.17315891, 0.53159946 0.0017518513 0.15160352, 0.51966053 -0.0010186769 0.17058617, 0.51912171 -0.0023069866 0.16987839, 0.52116388 -0.0038917549 0.16265178, 0.52296007 -0.00088438764 0.16142467, 0.5192368 -0.0010187216 0.17144826, 0.51960403 -0.00062783435 0.17142788, 0.52596605 0.0011967681 0.15972072, 0.5186013 -0.0014302619 0.17204288, 0.51737976 -0.0023072399 0.17322451, 0.518619 -0.003892187 0.16964385, 0.51833379 -0.001018811 0.17314392, 0.52772164 0.0017515533 0.15880704, 0.51815361 -0.00088526681 0.17367142, 0.53303552 0.0011969768 0.1555832, 0.53318459 0.0011972003 0.15160343, 0.52169973 -0.0023065098 0.16279531, 0.52072197 -0.0038919039 0.16418573, 0.51986736 -0.0055608936 0.16613886, 0.52411795 0.00030308589 0.16168883, 0.52752733 0.0017513447 0.15999627, 0.52937198 0.0019395016 0.15905574, 0.5346067 0.00030368194 0.15160343, 0.53445369 0.00030338392 0.15568915, 0.52256286 -0.00088447705 0.1630266, 0.5212521 -0.0023067333 0.16434923, 0.52550429 0.0011966936 0.16200545, 0.52917087 0.0019394122 0.16028586, 0.53102231 0.0017514341 0.15930438, 0.53563803 -0.00088419393 0.15577799, 0.53579426 -0.00088392571 0.15160343, 0.52370989 0.00030296668 0.16333413, 0.52004397 -0.0038919933 0.16620329, 0.52210593 -0.00088464096 0.16461265, 0.52704978 0.0017513148 0.16235819, 0.53081453 0.0017513297 0.16057566, 0.53258979 0.0011966936 0.15954056, 0.53668779 -0.0023059137 0.15160322, 0.53652894 -0.0023061074 0.1558446, 0.52508342 0.0011964999 0.16370225, 0.5196678 -0.0038920529 0.16719875, 0.52056527 -0.0023067631 0.16639295, 0.52324063 0.00030287728 0.1649628, 0.52867687 0.0019393675 0.16272974, 0.53237545 0.0011967532 0.16085079, 0.53399593 0.00030327961 0.15975249, 0.52661467 0.001751136 0.1641126, 0.53726959 -0.0055602975 0.15590006, 0.53708214 -0.0038913973 0.15588623, 0.53743058 -0.0055600144 0.15160307, 0.53724247 -0.0038911439 0.15160307, 0.5201841 -0.0023068674 0.16740149, 0.52140492 -0.00088470057 0.16669878, 0.52459955 0.0011964552 0.16538212, 0.5303039 0.001751285 0.16310096, 0.53377599 0.0003031902 0.16109768, 0.53517032 -0.00088434294 0.15992945, 0.52822679 0.0019392036 0.16454458, 0.52101576 -0.00088489428 0.16772825, 0.5225209 0.00030280277 0.16710508, 0.52611423 0.0017510168 0.16584924, 0.53184944 0.0011965148 0.16345337, 0.53494543 -0.00088434294 0.16130403, 0.5360539 -0.0023064204 0.16006246, 0.5298388 0.0017511509 0.16497645, 0.52212125 0.00030269846 0.16816193, 0.52385724 0.0011961721 0.16759145, 0.52770895 0.0019391887 0.1663411, 0.53323579 0.00030304119 0.16377008, 0.53582549 -0.0023065098 0.16145909, 0.53678828 -0.0055604912 0.16017294, 0.53660238 -0.0038916208 0.16014504, 0.53136992 0.0011963956 0.16538668, 0.52534688 0.0017508827 0.16813377, 0.52930391 0.0017511509 0.16683316, 0.53439361 -0.00088458136 0.16403437, 0.53637177 -0.0038916506 0.16155529, 0.52691513 0.0019389503 0.16870448, 0.52584487 -0.015368704 0.1657652, 0.52822667 -0.01556081 0.16454339, 0.52770907 -0.015560929 0.16634032, 0.52023643 -0.0093873031 0.15767807, 0.52149922 -0.011115912 0.15471774, 0.52115023 -0.011116151 0.15781564, 0.52057779 -0.0093871094 0.15464896, 0.52829033 -0.015368942 0.17058238, 0.53051126 -0.014799941 0.17001241, 0.53003657 -0.014799926 0.17126763, 0.52874845 -0.015368853 0.16937083, 0.52178305 -0.012631688 0.16115525, 0.52369958 -0.01387519 0.15932027, 0.52326053 -0.013875354 0.16149226, 0.5222072 -0.012631644 0.15905699, 0.53028101 -0.013876025 0.17508155, 0.53164577 -0.013875935 0.17189923, 0.53305644 -0.012632269 0.17245311, 0.53165454 -0.012632418 0.17572182, 0.52691531 -0.015561078 0.1687035, 0.52957326 -0.015368704 0.16691512, 0.52286041 -0.013875369 0.16310561, 0.52494591 -0.01479945 0.16187707, 0.52453047 -0.014799599 0.16355288, 0.5200724 -0.0093872733 0.15868098, 0.52098256 -0.011116255 0.15884119, 0.52405232 -0.014799569 0.1652123, 0.52634221 -0.015368585 0.16403866, 0.51967376 -0.0075113811 0.15759331, 0.52001029 -0.0075111575 0.1546064, 0.51932281 -0.0055604614 0.15854898, 0.51977825 -0.0055603273 0.15508917, 0.52647424 -0.015561197 0.16986972, 0.5205707 -0.011116344 0.16087866, 0.52871424 -0.01480015 0.1743508, 0.52508181 -0.015368987 0.16803631, 0.52139658 -0.012631763 0.16271344, 0.51951212 -0.0075114109 0.15858227, 0.52240026 -0.013875518 0.16470268, 0.52465814 -0.015368957 0.16915685, 0.51966983 -0.0093875267 0.16067293, 0.52701408 -0.015369195 0.17355806, 0.52331913 -0.014799688 0.16739458, 0.52019531 -0.011116389 0.16239157, 0.52095228 -0.012632001 0.16425622, 0.52291203 -0.014799912 0.16847137, 0.51911503 -0.0075114705 0.16054654, 0.5185675 -0.0055606402 0.16195574, 0.5252459 -0.015561286 0.17273337, 0.52169436 -0.013875607 0.16680348, 0.51930267 -0.0093874671 0.16215271, 0.51976383 -0.011116568 0.16388988, 0.53957099 -0.007511083 0.15607232, 0.53973836 -0.0075109787 0.15160298, 0.53993052 -0.0055599846 0.15160307, 0.52130252 -0.013875727 0.16783991, 0.53976279 -0.0055602677 0.15608686, 0.53900367 -0.0093871094 0.15602961, 0.53916925 -0.0093868263 0.15160277, 0.52347767 -0.015369076 0.17190877, 0.53808218 -0.011115972 0.15596059, 0.53824526 -0.011115763 0.15160277, 0.52027047 -0.012631897 0.16628525, 0.51875317 -0.007511545 0.16200534, 0.53907037 -0.0075113662 0.16051689, 0.53926033 -0.0055604912 0.16054565, 0.51888078 -0.0093877204 0.1636174, 0.53684205 -0.012631346 0.15586752, 0.53700155 -0.012631107 0.15160263, 0.51989198 -0.012632061 0.16728649, 0.52177769 -0.014800016 0.17111614, 0.53882986 -0.0075115599 0.16198838, 0.53842622 -0.0055608042 0.16495442, 0.5191018 -0.011116643 0.16586, 0.53850764 -0.0093873627 0.16043198, 0.51833707 -0.0075117983 0.16344976, 0.51751822 -0.0055608638 0.16528371, 0.53533083 -0.013874982 0.15575439, 0.53548622 -0.013874758 0.15160263, 0.51873416 -0.011116628 0.16683212, 0.52021068 -0.013875876 0.17038551, 0.53826934 -0.0093873776 0.16188967, 0.51823348 -0.0093877204 0.16554394, 0.5375939 -0.01111624 0.16029397, 0.51787394 -0.00938778 0.16649458, 0.51883727 -0.012632225 0.16974539, 0.53823882 -0.0075117238 0.16491139, 0.53360683 -0.014799107 0.15562493, 0.53375733 -0.014798883 0.15160263, 0.51769882 -0.007511843 0.16534939, 0.51734442 -0.0075119026 0.16628692, 0.51618272 -0.0055610873 0.1685079, 0.53735918 -0.01111621 0.16172877, 0.51771015 -0.01111697 0.16921964, 0.5168727 -0.0093879737 0.16882926, 0.516357 -0.0075120069 0.16858879, 0.51523072 -0.0093881078 0.17198363, 0.5147379 -0.0075122155 0.17169905, 0.51457149 -0.0055611618 0.17160302, 0.53636414 -0.012631644 0.16010851, 0.53768402 -0.0093874969 0.1647847, 0.5317362 -0.015368123 0.15548483, 0.53188139 -0.015367988 0.15160263, 0.53210378 -0.010275517 0.17876235, 0.5327692 -0.0084643252 0.17910889, 0.53123283 -0.0093885995 0.1812222, 0.53361899 -0.0093882717 0.17663839, 0.53347951 -0.007028807 0.17842653, 0.53413492 -0.0075124539 0.17687896, 0.53398854 -0.005561579 0.17763618, 0.53770041 -0.0075117387 0.1670824, 0.53726476 -0.0055609979 0.16928843, 0.53299302 -0.0065417625 0.17950657, 0.531892 -0.0055617131 0.18160301, 0.53243905 -0.0070289411 0.18041024, 0.53172559 -0.0075126328 0.18150702, 0.53613454 -0.012631673 0.16151297, 0.53197777 -0.011518452 0.17726949, 0.53278154 -0.011117149 0.17624763, 0.53486568 -0.01387519 0.15988272, 0.53113776 -0.011905421 0.17825928, 0.53080875 -0.011518527 0.17951557, 0.53678316 -0.011116359 0.16457894, 0.53043252 -0.011117388 0.18076009, 0.52935547 -0.012632612 0.18013832, 0.53079718 -0.012971032 0.17668727, 0.5297907 -0.015560392 0.15533891, 0.52993059 -0.015560064 0.15160263, 0.52990812 -0.013291661 0.17761928, 0.52965456 -0.012971092 0.17888218, 0.52804309 -0.013876263 0.17938051, 0.53715074 -0.0093876161 0.16693506, 0.52938491 -0.014138762 0.175991, 0.53464216 -0.013875265 0.16124964, 0.52846223 -0.014380697 0.17686656, 0.52827418 -0.014138866 0.17812487, 0.52654588 -0.014800373 0.178516, 0.53708124 -0.0075119175 0.16923168, 0.52779579 -0.014976803 0.17520693, 0.5331561 -0.014799345 0.15962499, 0.52685589 -0.015130881 0.17603031, 0.52672035 -0.014976982 0.17727226, 0.52492136 -0.015369464 0.17757812, 0.53557062 -0.012631822 0.16430211, 0.5260902 -0.015453193 0.17436603, 0.52784526 -0.015368167 0.15519321, 0.52797973 -0.015367899 0.15160263, 0.52515054 -0.015513245 0.17514259, 0.52505332 -0.015453283 0.17635757, 0.5232318 -0.015561525 0.17660254, 0.53625804 -0.011116434 0.16669559, 0.52433419 -0.015549291 0.17349997, 0.52333665 -0.015549395 0.17541593, 0.52154213 -0.015369225 0.17562702, 0.53293961 -0.014799345 0.16094947, 0.52303725 -0.015318338 0.17227885, 0.53653747 -0.0093878694 0.16906369, 0.52315652 -0.015427802 0.17331141, 0.53130114 -0.015368316 0.15934551, 0.52257597 -0.015318383 0.17321429, 0.5340932 -0.013875414 0.16396478, 0.52168572 -0.015176985 0.17372614, 0.52597463 -0.014799166 0.15505323, 0.52159268 -0.015318397 0.17505401, 0.51991761 -0.01480018 0.17468911, 0.52610362 -0.014798913 0.15160263, 0.52093208 -0.01463588 0.17200786, 0.53613156 -0.0075120963 0.17205843, 0.53578293 -0.0055612363 0.17352337, 0.52000296 -0.014635954 0.17377713, 0.51842028 -0.013876084 0.17382473, 0.53505689 -0.012631897 0.16637382, 0.51981622 -0.013760496 0.17082348, 0.53109217 -0.01536845 0.16062367, 0.51890761 -0.013410989 0.17159364, 0.51893997 -0.013760675 0.17254484, 0.51710814 -0.012632418 0.17306712, 0.51824361 -0.012347106 0.17035243, 0.53565443 -0.011116732 0.16879135, 0.51738924 -0.012347344 0.17200574, 0.51603097 -0.01111709 0.17244536, 0.52937216 -0.015560556 0.15905467, 0.53560406 -0.0075122006 0.17345306, 0.5324077 -0.014799524 0.16357997, 0.52425045 -0.013875041 0.15492395, 0.52437478 -0.013874818 0.15160263, 0.53559679 -0.0093880929 0.17186385, 0.53359324 -0.013875533 0.16598162, 0.52917093 -0.015560526 0.16028491, 0.53446609 -0.012632061 0.16842455, 0.52744299 -0.015368257 0.15876392, 0.53507441 -0.0093881525 0.17324525, 0.53057891 -0.01536848 0.16316259, 0.52273947 -0.012631509 0.15481073, 0.52285951 -0.012631167 0.15160277, 0.53472847 -0.011116821 0.17154756, 0.53192329 -0.014799599 0.16553402, 0.52724963 -0.015368421 0.15994614, 0.53301811 -0.013875727 0.16797802, 0.52558798 -0.014799286 0.15848425, 0.53421408 -0.011116926 0.17290738, 0.52867693 -0.015560765 0.16272858, 0.5216158 -0.011115763 0.15160277, 0.53355974 -0.012632135 0.17112195, 0.53011131 -0.015368689 0.16504848, 0.52540213 -0.014799405 0.15962043, 0.53136581 -0.014799763 0.16746834, 0.5238784 -0.013875175 0.15822655, 0.526775 -0.01536848 0.16229442, 0.52069169 -0.0093870349 0.15160292, 0.53213578 -0.013875786 0.17060381, 0.52237993 -0.01263148 0.15800074, 0.51993054 -0.0055601485 0.15160298, 0.52012271 -0.0075110383 0.15160298, 0.53389019 0.0691154 0.16606572, 0.5333119 0.069115222 0.16807324, 0.53274304 0.070302904 0.16575849, 0.53217703 0.070302755 0.16772342, 0.52344447 0.071196258 0.16868541, 0.52373284 0.071750641 0.17203301, 0.52229625 0.071196139 0.17136288, 0.52492005 0.071750969 0.16926473, 0.53487551 0.064439029 0.16855532, 0.53528923 0.066108108 0.16644055, 0.53598845 0.064439237 0.16440192, 0.53526431 0.067693412 0.1642369, 0.53475326 0.067693353 0.16629711, 0.53580505 0.066108108 0.1643602, 0.52997249 0.071196318 0.16982132, 0.52950281 0.071196318 0.17106321, 0.52848285 0.071750879 0.16927916, 0.5280273 0.07175082 0.17048413, 0.53081828 0.071196496 0.16730422, 0.53130883 0.070302695 0.17030752, 0.53416568 0.067693204 0.1683366, 0.5264737 0.071938902 0.1698744, 0.52524537 0.071938783 0.17273822, 0.53082651 0.070302665 0.17158297, 0.53242475 0.069115162 0.17071363, 0.53469568 0.066107959 0.1685001, 0.52675784 0.071750641 0.17344359, 0.53193218 0.069115043 0.17201647, 0.53326446 0.067693174 0.17101917, 0.52819461 0.07119599 0.17411336, 0.53276378 0.067692965 0.17234275, 0.53345519 0.06443873 0.17261413, 0.53378576 0.06610781 0.17120883, 0.51844805 0.064438939 0.16956824, 0.51689905 0.066107541 0.17295113, 0.51673609 0.064438671 0.17285687, 0.5294835 0.070302397 0.17471448, 0.53328019 0.066107661 0.17254534, 0.53055972 0.069114923 0.17521626, 0.53136951 0.067692816 0.175594, 0.53187239 0.066107631 0.17582825, 0.5317356 0.064438581 0.17655545, 0.53066093 0.068066418 0.1766248, 0.53055984 0.066915572 0.17796317, 0.52991349 0.068428636 0.177627, 0.5283094 0.069114655 0.17953911, 0.52952129 0.068066388 0.17881393, 0.52908319 0.067692548 0.17998579, 0.53124589 0.065694779 0.17731217, 0.53078073 0.065278232 0.17834738, 0.52972656 0.064438313 0.18035701, 0.52956367 0.066107213 0.18026319, 0.53024894 0.06569472 0.17921284, 0.52978927 0.069436193 0.17619517, 0.52261811 0.066108882 0.15160701, 0.52249867 0.066108614 0.15479714, 0.52243 0.064439893 0.15160701, 0.52226835 0.064439654 0.15531102, 0.52898473 0.069741845 0.17714348, 0.5231728 0.067694068 0.15160722, 0.5230518 0.06769383 0.15483865, 0.52728099 0.070302218 0.17894539, 0.5286693 0.069436133 0.17834654, 0.53104371 0.066915542 0.17701191, 0.52406627 0.069116116 0.15160728, 0.52394277 0.069115996 0.15490553, 0.52997279 0.066915631 0.17906156, 0.52866614 0.070555389 0.17564121, 0.52214116 0.066108525 0.1579693, 0.52178437 0.064439505 0.15898696, 0.52525377 0.070303679 0.15160728, 0.52512699 0.07030347 0.15499431, 0.52781981 0.07078898 0.17653719, 0.52604944 0.071195841 0.17823449, 0.52757138 0.07055524 0.17774433, 0.52734768 0.071367741 0.17499119, 0.5219695 0.066108316 0.15901986, 0.52268988 0.06769374 0.15805215, 0.52647775 0.071517706 0.17583862, 0.52628261 0.071367651 0.17703727, 0.52467662 0.071750402 0.17744198, 0.52667588 0.071197122 0.15160748, 0.52654511 0.071197063 0.15510052, 0.52590042 0.071832746 0.1742774, 0.52251571 0.067693651 0.159116, 0.52323121 0.071938545 0.17660743, 0.52486759 0.071832597 0.1762611, 0.52482241 0.071935773 0.17314029, 0.52357334 0.069115847 0.15818542, 0.52826113 0.071751863 0.15160748, 0.52812594 0.071751714 0.15521929, 0.52486211 0.071933508 0.17417315, 0.52434212 0.071935773 0.17411473, 0.52154773 0.066108257 0.16110614, 0.52098185 0.064439356 0.16260663, 0.52349275 0.071905911 0.17468894, 0.52339572 0.069115609 0.1592713, 0.52178586 0.071750581 0.17577294, 0.52331799 0.071935564 0.17603031, 0.52289456 0.071664631 0.17298967, 0.52474767 0.07030347 0.15836245, 0.52192092 0.071664572 0.17484346, 0.5204131 0.07119593 0.17498034, 0.52992988 0.071939945 0.15160748, 0.5297901 0.071939856 0.15534371, 0.52189988 0.071118027 0.17183223, 0.52100736 0.070302635 0.17076212, 0.52099329 0.070874661 0.17266825, 0.52208847 0.067693621 0.16122949, 0.52097768 0.071118057 0.17364386, 0.52128369 0.071331441 0.17403466, 0.52456528 0.070303082 0.15947765, 0.52615374 0.071196914 0.15857452, 0.52048719 0.071117967 0.17453399, 0.51918167 0.070302367 0.17426923, 0.52040666 0.070085406 0.17141581, 0.51993102 0.069115192 0.17026019, 0.51950413 0.070085168 0.17316252, 0.5211634 0.066108286 0.16265562, 0.53145462 0.071751624 0.15546864, 0.51965994 0.068981528 0.17059007, 0.51912111 0.067693114 0.16988239, 0.53159887 0.071751893 0.15160748, 0.52295965 0.069115639 0.16142857, 0.51923651 0.068981349 0.17145231, 0.51960355 0.069372207 0.17143166, 0.52596563 0.071196645 0.15972462, 0.51860088 0.068569779 0.1720466, 0.51737934 0.067692816 0.17322844, 0.51861852 0.06610775 0.16964805, 0.51833349 0.068981141 0.17314798, 0.51815313 0.069114804 0.17367521, 0.52772123 0.071751535 0.15881079, 0.52169925 0.067693442 0.16279915, 0.53303522 0.071197033 0.15558699, 0.53318411 0.071197182 0.15160728, 0.5207215 0.066108078 0.1641897, 0.51986688 0.064439088 0.16614285, 0.52411753 0.070303082 0.16169286, 0.5275268 0.071751446 0.16000012, 0.52937168 0.071939498 0.15905946, 0.52256233 0.069115639 0.16303053, 0.53460622 0.070303738 0.15160728, 0.53445321 0.070303559 0.1556932, 0.52125156 0.067693323 0.16435322, 0.52550393 0.071196586 0.16200936, 0.52917033 0.071939468 0.16028991, 0.53102189 0.071751446 0.15930843, 0.52370936 0.070302963 0.16333798, 0.53563756 0.069116026 0.15578175, 0.53579384 0.069116235 0.15160728, 0.52004361 0.066108048 0.16620731, 0.52210552 0.069115311 0.16461661, 0.52704924 0.071751386 0.16236201, 0.53081399 0.071751475 0.16057962, 0.53258926 0.071196854 0.1595445, 0.52508295 0.071196437 0.16370597, 0.53668731 0.067694128 0.15160728, 0.53652841 0.06769383 0.15584856, 0.51966721 0.066108048 0.1672028, 0.52056485 0.067693293 0.16639695, 0.52324027 0.070302904 0.16496676, 0.52867627 0.071939409 0.16273347, 0.53237504 0.071196705 0.16085476, 0.53399557 0.070303202 0.15975633, 0.52661419 0.071751177 0.16411647, 0.53726912 0.064439744 0.15590391, 0.53708178 0.066108674 0.15589008, 0.53742999 0.064439952 0.15160701, 0.537242 0.066108912 0.15160722, 0.52018356 0.067693323 0.16740555, 0.52140445 0.0691154 0.1667026, 0.52459913 0.071196437 0.16538593, 0.53030354 0.071751267 0.1631048, 0.53377551 0.070303142 0.1611017, 0.5351699 0.069115669 0.15993336, 0.52822626 0.07193926 0.16454837, 0.52101535 0.069115222 0.16773194, 0.52252036 0.070302784 0.16710913, 0.52611381 0.071751177 0.16585323, 0.53184897 0.071196496 0.1634573, 0.53494495 0.069115669 0.16130784, 0.53605324 0.06769371 0.16006643, 0.52983838 0.071751177 0.16498044, 0.52212065 0.070302725 0.16816577, 0.5238567 0.071196318 0.16759551, 0.52770853 0.071939111 0.16634515, 0.53323525 0.070303023 0.16377413, 0.53582507 0.067693681 0.16146293, 0.53678781 0.064439476 0.16017699, 0.53660184 0.066108406 0.16014889, 0.53136951 0.071196496 0.16539052, 0.52534634 0.071750879 0.16813773, 0.52930337 0.071751177 0.16683701, 0.53439313 0.06911546 0.16403821, 0.53637129 0.066108376 0.16155928, 0.52691466 0.071938962 0.16870838, 0.52584445 0.054631289 0.16576919, 0.52822644 0.054439213 0.16454723, 0.52770871 0.054439213 0.16634417, 0.52023596 0.060612794 0.15768206, 0.52149868 0.05888411 0.15472165, 0.52114975 0.058883872 0.15781963, 0.52057725 0.060613032 0.15465286, 0.52828979 0.05463108 0.17058617, 0.53051072 0.055200275 0.17001635, 0.53003597 0.055200245 0.17127165, 0.52874798 0.05463117 0.16937467, 0.52178276 0.057368305 0.16115928, 0.52369916 0.056124773 0.15932408, 0.52326006 0.056124743 0.16149628, 0.5222069 0.057368305 0.15906098, 0.53028077 0.056123968 0.17508546, 0.53164548 0.056124147 0.17190328, 0.53305608 0.057367679 0.17245701, 0.53165388 0.057367619 0.17572585, 0.52691472 0.054438945 0.16870743, 0.52957302 0.054631319 0.16691902, 0.52286005 0.056124594 0.16310945, 0.52494556 0.055200543 0.16188103, 0.52452981 0.055200424 0.16355696, 0.52007204 0.060612675 0.15868503, 0.52098197 0.058883961 0.1588451, 0.52405196 0.055200394 0.16521627, 0.52634197 0.054631319 0.16404271, 0.51967329 0.062488671 0.15759721, 0.5200097 0.062488969 0.1546104, 0.51932245 0.064439535 0.1585528, 0.51977783 0.064439654 0.15509316, 0.52647382 0.054438855 0.16987342, 0.52057028 0.058883693 0.1608825, 0.52871376 0.055199888 0.17435464, 0.52508146 0.05463108 0.1680401, 0.52139622 0.057368275 0.16271737, 0.51951152 0.062488671 0.15858608, 0.52240002 0.056124445 0.16470674, 0.52465779 0.054630991 0.16916081, 0.51966923 0.060612615 0.16067699, 0.52701366 0.054630902 0.17356184, 0.52331865 0.055200305 0.16739863, 0.52019495 0.058883663 0.1623956, 0.52095175 0.057368185 0.16426006, 0.52291161 0.055200215 0.16847536, 0.51911443 0.062488522 0.16055039, 0.51856703 0.064439327 0.16195968, 0.52524549 0.054438736 0.1727373, 0.52169418 0.056124385 0.16680732, 0.51930225 0.060612526 0.1621567, 0.51976335 0.058883425 0.16389361, 0.53957075 0.062488791 0.15607643, 0.53973776 0.062489118 0.15160692, 0.53993005 0.064440012 0.15160692, 0.5213021 0.056124266 0.16784376, 0.53976232 0.064439803 0.15609059, 0.53900331 0.060612883 0.15603361, 0.53916878 0.060613092 0.15160668, 0.52347732 0.054630812 0.17191282, 0.53808165 0.05888411 0.15596443, 0.53824472 0.058884349 0.15160668, 0.52027011 0.057368066 0.16628921, 0.51875269 0.062488403 0.16200936, 0.53906983 0.062488612 0.16052091, 0.53925973 0.064439505 0.16054943, 0.51888019 0.060612347 0.1636211, 0.53684163 0.057368632 0.15587136, 0.53700119 0.05736896 0.15160668, 0.51989138 0.057368036 0.16729039, 0.52177721 0.055200156 0.1711202, 0.53882939 0.062488493 0.16199222, 0.53842562 0.064439237 0.16495812, 0.51910138 0.058883395 0.16586381, 0.53850728 0.060612705 0.16043574, 0.51833647 0.062488254 0.16345382, 0.51751775 0.064439118 0.16528776, 0.5353303 0.056125101 0.15575829, 0.53548574 0.05612528 0.15160644, 0.51873386 0.058883395 0.16683602, 0.52021033 0.056124207 0.17038947, 0.5382688 0.060612585 0.16189352, 0.518233 0.060612258 0.16554785, 0.53759342 0.058883753 0.1602979, 0.5178737 0.060612228 0.16649842, 0.53823835 0.062488344 0.16491535, 0.53360629 0.055200931 0.15562877, 0.53375691 0.055201169 0.15160644, 0.51883698 0.057367828 0.16974935, 0.51769835 0.062488254 0.16535342, 0.51734382 0.062488195 0.16629076, 0.51618236 0.06443882 0.16851181, 0.53735882 0.058883693 0.16173282, 0.51770967 0.058883246 0.16922355, 0.51687235 0.060612019 0.1688332, 0.53636378 0.057368424 0.16011253, 0.51635641 0.062488016 0.16859284, 0.5152303 0.06061193 0.17198747, 0.51473743 0.062487777 0.17170301, 0.51457101 0.06443876 0.17160708, 0.53768355 0.060612436 0.1647886, 0.53173572 0.054631915 0.15548888, 0.53188092 0.054632183 0.15160644, 0.5321033 0.059724595 0.17876616, 0.53276879 0.061535623 0.17911282, 0.53123224 0.060611513 0.18122616, 0.53361863 0.060611751 0.17664209, 0.53347915 0.062971175 0.17843059, 0.53413433 0.062487658 0.17688268, 0.53398824 0.064438581 0.17763999, 0.53769988 0.062488254 0.16708636, 0.53726429 0.064439029 0.16929233, 0.53299242 0.063458353 0.17951027, 0.53189152 0.064438283 0.18160701, 0.53613412 0.057368424 0.16151682, 0.53243881 0.062970996 0.18041408, 0.53172511 0.06248742 0.18151084, 0.53197742 0.0584816 0.17727333, 0.53278095 0.058882888 0.17625141, 0.53486532 0.056124803 0.15988663, 0.53678274 0.058883544 0.16458285, 0.53113735 0.058094587 0.17826334, 0.53080827 0.058481481 0.17951933, 0.53043205 0.05888265 0.18076399, 0.52935517 0.057367321 0.18014207, 0.53079695 0.057029005 0.17669132, 0.52979022 0.05443969 0.15534273, 0.52993006 0.054439928 0.15160644, 0.5299077 0.056708362 0.1776233, 0.52965409 0.057029065 0.17888609, 0.53715032 0.060612436 0.16693902, 0.52804273 0.056123789 0.17938441, 0.52938449 0.055861291 0.1759949, 0.53464192 0.056124713 0.16125348, 0.52846205 0.055619206 0.17687047, 0.52827358 0.055861171 0.17812863, 0.53708071 0.062488075 0.16923547, 0.52654546 0.055199709 0.17851999, 0.52779526 0.055023249 0.17521089, 0.53315574 0.055200752 0.15962905, 0.52685547 0.054869112 0.17603427, 0.53557032 0.057368245 0.16430607, 0.52671993 0.05502307 0.17727616, 0.52492094 0.054630574 0.17758185, 0.52608967 0.054546949 0.17436978, 0.52784485 0.054631855 0.1551972, 0.52797931 0.054632034 0.15160644, 0.52515 0.054486867 0.17514649, 0.52505285 0.05454674 0.17636174, 0.52323145 0.054438438 0.17660645, 0.53625774 0.058883484 0.16669944, 0.52433366 0.054450747 0.17350402, 0.53293914 0.055200722 0.16095331, 0.52333623 0.054450747 0.17541984, 0.52154171 0.054630812 0.17563108, 0.53653705 0.060612228 0.16906771, 0.52303678 0.054681744 0.17228287, 0.52315605 0.05457228 0.17331529, 0.53130072 0.054631647 0.15934956, 0.52257544 0.054681744 0.17321828, 0.5340929 0.056124534 0.16396868, 0.52168518 0.054823067 0.17373002, 0.52597415 0.055200931 0.1550568, 0.52610332 0.05520108 0.15160644, 0.5215922 0.054681595 0.1750578, 0.51991719 0.055199828 0.17469299, 0.52093154 0.055364247 0.17201191, 0.53613108 0.062487956 0.17206237, 0.5357824 0.06443882 0.17352733, 0.52000254 0.055364128 0.17378083, 0.51841998 0.056123909 0.17382878, 0.53505653 0.057368066 0.16637784, 0.51981586 0.056239542 0.17082721, 0.53109169 0.054631647 0.16062751, 0.51890731 0.056589063 0.17159739, 0.51893944 0.056239422 0.1725488, 0.51710767 0.05736753 0.17307118, 0.53565401 0.058883395 0.16879532, 0.51824325 0.057652798 0.17035636, 0.5173887 0.057652649 0.17200956, 0.52937168 0.054439511 0.15905857, 0.51603049 0.058883008 0.17244944, 0.53560346 0.062487867 0.17345721, 0.53240746 0.055200454 0.1635839, 0.52425021 0.056125011 0.15492785, 0.52437443 0.05612525 0.15160668, 0.53559631 0.06061196 0.17186755, 0.53359276 0.056124534 0.16598552, 0.52917045 0.054439481 0.16028872, 0.53446561 0.057368007 0.16842872, 0.52744246 0.054631736 0.15876788, 0.53507382 0.06061196 0.17324921, 0.53057843 0.054631528 0.16316643, 0.52273893 0.057368781 0.15481472, 0.52285892 0.057368811 0.15160668, 0.53472805 0.058883216 0.17155135, 0.53192288 0.055200394 0.16553786, 0.52724928 0.054631557 0.1599502, 0.53301752 0.056124356 0.16798174, 0.52558744 0.055200931 0.15848821, 0.53421378 0.058883037 0.1729112, 0.52867645 0.054439452 0.1627326, 0.52161521 0.0588842 0.15160668, 0.5335595 0.057367828 0.17112595, 0.53011072 0.054631379 0.16505232, 0.52540177 0.055200722 0.15962425, 0.53136539 0.055200215 0.1674723, 0.52387798 0.056124832 0.1582306, 0.52677447 0.054631528 0.16229832, 0.52069116 0.060613122 0.15160683, 0.53213543 0.056124207 0.17060775, 0.52237958 0.057368513 0.1580047, 0.51993018 0.064439893 0.15160701, 0.52012217 0.062488999 0.15160692, 0.53274316 0.07032162 -0.16574913, 0.53439313 0.069133967 -0.16402897, 0.53323531 0.070321441 -0.16376454, 0.53389019 0.069133997 -0.16605669, 0.52615374 0.071214646 -0.15856498, 0.52807724 0.071769238 -0.15581024, 0.52649808 0.071214497 -0.15567207, 0.52772135 0.071769327 -0.15880117, 0.53598839 0.064457744 -0.16439316, 0.53528923 0.066126794 -0.16643152, 0.53487557 0.064458042 -0.16854668, 0.53469568 0.066126883 -0.16849124, 0.53416574 0.067712188 -0.16832748, 0.53475338 0.067712069 -0.16628802, 0.53081387 0.071769506 -0.16056997, 0.53258938 0.071214795 -0.15953505, 0.53102177 0.071769387 -0.15929881, 0.53237516 0.071214885 -0.16084537, 0.53377551 0.070321232 -0.16109243, 0.53184891 0.071215004 -0.16344807, 0.53526431 0.067711949 -0.16422769, 0.52937156 0.071957499 -0.15905014, 0.5297398 0.07195732 -0.15595561, 0.53399557 0.070321172 -0.15974697, 0.53494507 0.069133788 -0.16129866, 0.53580505 0.066126704 -0.16435122, 0.53140217 0.071769327 -0.15610114, 0.53516978 0.069133818 -0.15992415, 0.53582507 0.067711681 -0.16145381, 0.53298146 0.071214616 -0.1562393, 0.53605348 0.067711711 -0.1600574, 0.53637141 0.066126466 -0.16155031, 0.53678781 0.064457536 -0.1601682, 0.53439802 0.070321143 -0.15636328, 0.53660196 0.066126406 -0.16014001, 0.53558129 0.06913355 -0.15646687, 0.53647131 0.067711532 -0.1565448, 0.5370239 0.066126227 -0.15659323, 0.53726941 0.064457268 -0.15589526, 0.53637308 0.068085134 -0.15529755, 0.53695482 0.066934288 -0.15408778, 0.53622681 0.068447471 -0.15405598, 0.53579384 0.069133312 -0.15159789, 0.53648078 0.068085045 -0.15283194, 0.53668737 0.067711204 -0.15159798, 0.53722352 0.065713525 -0.15499488, 0.53743005 0.064457119 -0.15159824, 0.53733808 0.065296948 -0.15386572, 0.53724194 0.066125929 -0.15159824, 0.53731042 0.065713406 -0.15285027, 0.53540331 0.069454879 -0.15523401, 0.51673609 0.064458221 -0.17284822, 0.51839048 0.066126883 -0.17011979, 0.51844805 0.064457953 -0.1695596, 0.51689905 0.066127032 -0.17294219, 0.53518075 0.069760501 -0.15401033, 0.53550905 0.06945473 -0.15281081, 0.53460622 0.070320815 -0.15159786, 0.53689831 0.066934466 -0.15515366, 0.51737946 0.067712247 -0.17321944, 0.51889044 0.067712098 -0.17036042, 0.53699571 0.066934228 -0.15284336, 0.51969534 0.069134295 -0.17074803, 0.53415388 0.070573866 -0.15515187, 0.51815325 0.069134355 -0.17366618, 0.51966721 0.066126734 -0.16719389, 0.51986688 0.064457774 -0.16613412, 0.53386897 0.070807517 -0.15395299, 0.53318423 0.071214318 -0.15159786, 0.53425711 0.070573837 -0.1527833, 0.53268689 0.071386427 -0.15505579, 0.51918167 0.070321947 -0.17425993, 0.52076536 0.070321888 -0.17126322, 0.52004367 0.066126645 -0.16619822, 0.53235728 0.071536303 -0.15388682, 0.52018362 0.067711979 -0.16739643, 0.53159899 0.071768969 -0.15159786, 0.53278762 0.071386188 -0.15275127, 0.53107673 0.071851254 -0.15495014, 0.52041322 0.0712156 -0.1749709, 0.52204663 0.071215481 -0.17188036, 0.52992994 0.071957141 -0.15159786, 0.53117412 0.071851134 -0.15271592, 0.52056497 0.067711949 -0.16638803, 0.52957469 0.071954221 -0.15539601, 0.52101523 0.069134116 -0.16772282, 0.53012532 0.071951956 -0.15452138, 0.52964568 0.071954191 -0.15431216, 0.52178603 0.071770191 -0.1757634, 0.52347475 0.071770072 -0.17256784, 0.52072161 0.066126674 -0.16418058, 0.52098197 0.064457566 -0.1625981, 0.52919728 0.071924388 -0.15339002, 0.52826118 0.071768999 -0.15159774, 0.52971679 0.071954161 -0.15214095, 0.52140445 0.069133937 -0.16669342, 0.52782971 0.071683079 -0.15456259, 0.52667588 0.071214288 -0.15159789, 0.52791327 0.071683019 -0.15247026, 0.52212077 0.07032156 -0.1681565, 0.52638954 0.071136504 -0.15506759, 0.52508134 0.070320964 -0.15554824, 0.52323133 0.071958393 -0.17659798, 0.52497846 0.071958244 -0.17329207, 0.52602237 0.070893049 -0.15389016, 0.52649659 0.071136385 -0.15303755, 0.52125162 0.06771189 -0.16434413, 0.52695709 0.071349829 -0.15285209, 0.52525383 0.070320725 -0.15159789, 0.52651697 0.071136355 -0.15202141, 0.52252048 0.070321649 -0.16709962, 0.5248881 0.070103616 -0.15468156, 0.52344459 0.071215212 -0.16867617, 0.5238983 0.069133282 -0.15544489, 0.52497977 0.070103586 -0.1527175, 0.52116352 0.066126496 -0.16264659, 0.5238288 0.068999648 -0.15502337, 0.52300829 0.067711294 -0.15536693, 0.52467662 0.07177037 -0.17743224, 0.52648205 0.071770281 -0.17401615, 0.523893 0.068999618 -0.15406507, 0.5242005 0.069390476 -0.15426624, 0.52210552 0.069133937 -0.16460735, 0.52261806 0.06612587 -0.15159824, 0.52363974 0.068588138 -0.15323225, 0.5231728 0.067711145 -0.15159798, 0.52385688 0.071215123 -0.16758585, 0.52245575 0.066125989 -0.15531865, 0.52406627 0.069133222 -0.15159798, 0.52395874 0.068999469 -0.15214506, 0.52492023 0.071769893 -0.16925517, 0.52169925 0.067711711 -0.16279015, 0.52604944 0.071215808 -0.17822495, 0.52791017 0.071215689 -0.17470399, 0.52154773 0.066126406 -0.16109711, 0.52178437 0.064457357 -0.15897813, 0.52324027 0.0703215 -0.16495726, 0.52534634 0.071769774 -0.16812798, 0.52647364 0.071958005 -0.16986489, 0.52256238 0.069133908 -0.16302127, 0.52728111 0.070322275 -0.178936, 0.52919167 0.070322126 -0.17532113, 0.52208859 0.067711592 -0.16122052, 0.52459913 0.071214974 -0.16537642, 0.52691466 0.071958035 -0.16869894, 0.52802724 0.071770072 -0.17047465, 0.52370948 0.070321351 -0.1633285, 0.5283094 0.069134831 -0.17952994, 0.53026158 0.069134623 -0.17583647, 0.5219695 0.066126347 -0.15901089, 0.52295965 0.069133729 -0.16141924, 0.52611393 0.071769774 -0.16584373, 0.52848297 0.071769983 -0.16926959, 0.52950287 0.071215391 -0.17105377, 0.52508312 0.071214885 -0.16369659, 0.52908331 0.067712814 -0.1799767, 0.5310666 0.067712486 -0.17622414, 0.52214128 0.066126287 -0.15796036, 0.52226835 0.064457119 -0.15530244, 0.52251583 0.067711562 -0.15910712, 0.52411753 0.070321202 -0.16168347, 0.52770865 0.071957916 -0.1663357, 0.52997261 0.071215391 -0.16981196, 0.53082663 0.070321918 -0.17157343, 0.52661425 0.071769714 -0.1641067, 0.53156632 0.06612727 -0.17646483, 0.53173584 0.0644584 -0.17654648, 0.52972656 0.064458579 -0.18034831, 0.52956372 0.066127419 -0.18025404, 0.52268976 0.067711473 -0.15804309, 0.52339584 0.06913355 -0.15926221, 0.52550387 0.071214855 -0.16199979, 0.52930337 0.071769863 -0.16682753, 0.53130883 0.070321798 -0.17029834, 0.53193206 0.069134474 -0.17200735, 0.52822632 0.071957797 -0.16453895, 0.52357334 0.06913358 -0.15817624, 0.52456528 0.070321083 -0.15946838, 0.52704936 0.071769565 -0.16235241, 0.52243 0.064456999 -0.15159824, 0.53081816 0.071215242 -0.16729486, 0.53242475 0.069134384 -0.17070451, 0.53276378 0.067712307 -0.17233399, 0.52983832 0.071769744 -0.16497076, 0.52474767 0.070321172 -0.15835312, 0.52596569 0.071214616 -0.15971527, 0.52867639 0.071957648 -0.16272387, 0.53217715 0.070321649 -0.16771403, 0.53326446 0.067712337 -0.17101026, 0.53345531 0.064458251 -0.17260543, 0.53328031 0.066127002 -0.17253649, 0.53136963 0.071215034 -0.16538104, 0.52752692 0.071769446 -0.1599904, 0.53030354 0.071769565 -0.16309521, 0.5333119 0.069134235 -0.16806412, 0.53378552 0.066127002 -0.17120007, 0.52917039 0.071957529 -0.1602802, 0.51910144 0.058902021 -0.16585577, 0.51873386 0.058902111 -0.16682801, 0.51989144 0.057386782 -0.16728243, 0.52677447 0.054649767 -0.16229078, 0.52634203 0.054649826 -0.16403481, 0.52822644 0.05445775 -0.16453981, 0.52867651 0.054457661 -0.16272482, 0.51787359 0.060631033 -0.16649005, 0.51748717 0.05890229 -0.16968516, 0.51665467 0.060631063 -0.16928402, 0.53130078 0.054649588 -0.15934166, 0.53109187 0.054649737 -0.16062003, 0.53293926 0.055218842 -0.16094571, 0.5331558 0.055218663 -0.1596213, 0.52095181 0.057386633 -0.16425216, 0.52027017 0.057386693 -0.16628128, 0.52169406 0.056143191 -0.16679952, 0.52239996 0.056142982 -0.16469881, 0.53527445 0.056142565 -0.15644065, 0.53486526 0.056142863 -0.15987897, 0.53636378 0.057386484 -0.1601046, 0.53678393 0.057386275 -0.15657264, 0.52917051 0.054457542 -0.16028133, 0.53057849 0.054649826 -0.16315898, 0.52285999 0.056142982 -0.16310179, 0.52405185 0.055218961 -0.16520867, 0.52452987 0.055218901 -0.16354924, 0.51823312 0.060630914 -0.16553962, 0.5249458 0.055218663 -0.16187319, 0.51734382 0.062506914 -0.16628215, 0.5161823 0.064457953 -0.1685029, 0.51614195 0.062507063 -0.16903698, 0.51751775 0.064457685 -0.165279, 0.52937168 0.054457452 -0.15905097, 0.51976341 0.058901902 -0.16388565, 0.53355217 0.055218574 -0.15629005, 0.52724922 0.054649707 -0.15994242, 0.52139628 0.057386484 -0.16270944, 0.51769835 0.062506765 -0.1653448, 0.52326012 0.056142863 -0.16148847, 0.52744257 0.054649528 -0.15876004, 0.51888049 0.060630765 -0.16361317, 0.53168333 0.054649439 -0.15612665, 0.52540183 0.055218633 -0.15961665, 0.52019501 0.058901932 -0.16238755, 0.52178276 0.057386424 -0.16115123, 0.52558744 0.055218693 -0.15848055, 0.51833659 0.062506706 -0.16344532, 0.51856709 0.064457476 -0.16195112, 0.52973992 0.054457303 -0.15595654, 0.52369922 0.056142684 -0.15931645, 0.51930231 0.060630735 -0.16214833, 0.51993006 0.064456969 -0.15159833, 0.51977783 0.064457119 -0.15508449, 0.52012223 0.06250605 -0.15159824, 0.53381497 0.062507659 -0.17754808, 0.53172511 0.062507868 -0.18150222, 0.53189152 0.064458787 -0.18159848, 0.52057028 0.058901813 -0.16087446, 0.53398818 0.064458579 -0.17763132, 0.52387798 0.056142624 -0.15822285, 0.53330237 0.060631659 -0.17730123, 0.53123248 0.060631897 -0.18121788, 0.52779645 0.054649439 -0.15578654, 0.53246969 0.058902826 -0.17690039, 0.53043211 0.058902945 -0.18075594, 0.52220678 0.057386335 -0.15905312, 0.53560358 0.062507391 -0.17344877, 0.53578252 0.06445834 -0.17351869, 0.51875275 0.062506616 -0.16200086, 0.5313493 0.057387318 -0.17636088, 0.52935517 0.057387497 -0.18013421, 0.51966923 0.060630675 -0.1606687, 0.52237958 0.057386275 -0.1579968, 0.5259276 0.055218484 -0.15562311, 0.53613108 0.062507361 -0.17205396, 0.53726441 0.064458042 -0.16928357, 0.535074 0.060631391 -0.17324081, 0.52098203 0.058901634 -0.15883723, 0.51911443 0.062506616 -0.16054195, 0.52998412 0.056143727 -0.17570341, 0.52804279 0.056143876 -0.17937654, 0.5193224 0.064457387 -0.15854421, 0.52114981 0.058901604 -0.1578114, 0.52420521 0.056142505 -0.15547231, 0.53559643 0.060631391 -0.17185941, 0.5200721 0.060630526 -0.15867659, 0.53421372 0.058902528 -0.17290339, 0.52023607 0.060630437 -0.15767363, 0.53708082 0.062507153 -0.16922703, 0.52842647 0.055219527 -0.17495352, 0.52654552 0.055219766 -0.17851225, 0.52269566 0.057386156 -0.15534022, 0.51951152 0.062506497 -0.15857765, 0.53472805 0.058902439 -0.17154336, 0.51967329 0.062506348 -0.15758869, 0.52145678 0.058901455 -0.15523174, 0.53305608 0.05738705 -0.17244899, 0.52053618 0.060630348 -0.15515101, 0.51996928 0.062506199 -0.15510133, 0.52069128 0.060630169 -0.15159848, 0.53653699 0.060631271 -0.1690594, 0.52673632 0.054650392 -0.17413941, 0.52492094 0.054650601 -0.17757434, 0.53869331 0.059743311 -0.15416422, 0.53894347 0.060630616 -0.15676141, 0.53944272 0.061554398 -0.15419677, 0.53770012 0.062506974 -0.1670779, 0.53842574 0.064457774 -0.16494966, 0.53916895 0.060630288 -0.15159845, 0.5397169 0.06298992 -0.15514281, 0.53951031 0.062506497 -0.156811, 0.53976232 0.064457327 -0.15608218, 0.53355944 0.05738708 -0.17111817, 0.53983516 0.063477069 -0.15396443, 0.53993005 0.064457059 -0.15159824, 0.53980768 0.06298992 -0.15290487, 0.53973788 0.062506169 -0.15159845, 0.53783786 0.058500316 -0.1553942, 0.53802294 0.058901634 -0.15668109, 0.53164542 0.056143459 -0.1718955, 0.53760535 0.058113184 -0.15411678, 0.53565401 0.05890232 -0.16878733, 0.53794837 0.058500107 -0.15286458, 0.53824478 0.058901336 -0.15159857, 0.53700119 0.057385977 -0.15159857, 0.52497858 0.054458138 -0.17329311, 0.52323145 0.054458257 -0.17659873, 0.53652412 0.057047751 -0.15530801, 0.53715044 0.060630973 -0.16693068, 0.53622037 0.056727108 -0.15405643, 0.53663218 0.057047661 -0.15283597, 0.5354858 0.056142356 -0.15159869, 0.53495318 0.055879917 -0.15520501, 0.53213543 0.05614334 -0.17059994, 0.53823847 0.062506944 -0.16490689, 0.53459209 0.055637952 -0.15398547, 0.53505802 0.055879828 -0.15280178, 0.53003597 0.055219408 -0.17126396, 0.53375703 0.055218246 -0.15159869, 0.53318483 0.055041846 -0.15508929, 0.53446573 0.057386991 -0.16842079, 0.53278255 0.054887827 -0.15390646, 0.53328639 0.055041607 -0.15276307, 0.52322084 0.054650243 -0.17244652, 0.52154183 0.054650452 -0.17562333, 0.53188097 0.0546492 -0.15159884, 0.53128725 0.054565426 -0.15496495, 0.5362578 0.05890223 -0.16669154, 0.53086179 0.054505285 -0.15382257, 0.53138524 0.054565307 -0.15272155, 0.52993006 0.054457065 -0.15159869, 0.53051072 0.055219259 -0.17000875, 0.52933365 0.054469224 -0.15483701, 0.52942765 0.054469164 -0.15267888, 0.5279792 0.05464923 -0.15159869, 0.53768355 0.060631033 -0.16478044, 0.52828985 0.054650243 -0.17057857, 0.52759987 0.054700192 -0.1552459, 0.52821928 0.054590698 -0.15441146, 0.53301775 0.05614325 -0.16797411, 0.527668 0.054700162 -0.15420511, 0.52153075 0.055219289 -0.17163268, 0.51991719 0.055219498 -0.17468548, 0.52715307 0.054841366 -0.15331665, 0.52773619 0.054700073 -0.15212035, 0.52610332 0.055218246 -0.15159869, 0.53882939 0.062506676 -0.16198391, 0.53926003 0.064457625 -0.16054088, 0.52564126 0.055382635 -0.15442792, 0.52572125 0.055382397 -0.1524314, 0.52437443 0.056142297 -0.15159869, 0.53505659 0.057386812 -0.16636965, 0.52408266 0.056257751 -0.15489602, 0.52874792 0.054650154 -0.16936707, 0.52368081 0.056607332 -0.15377453, 0.52418429 0.056257691 -0.15296701, 0.52285904 0.057385888 -0.15159857, 0.53678268 0.058902081 -0.1645748, 0.5224849 0.057671156 -0.15451741, 0.52647382 0.054457989 -0.16986588, 0.5225718 0.057670977 -0.15265849, 0.52161545 0.058901247 -0.15159857, 0.53906995 0.062506706 -0.16051218, 0.53136557 0.05521911 -0.16746452, 0.51997304 0.056143399 -0.17088246, 0.51841992 0.056143578 -0.17382091, 0.53826886 0.060630914 -0.1618852, 0.53359288 0.056143131 -0.16597766, 0.52691478 0.054458018 -0.16869983, 0.53557032 0.057386722 -0.16429815, 0.52465779 0.054650065 -0.16915321, 0.53850728 0.060630705 -0.16042754, 0.52957302 0.054650005 -0.16691157, 0.51860785 0.057386871 -0.17022488, 0.51710767 0.05738702 -0.17306316, 0.53735882 0.058901962 -0.1617249, 0.53192288 0.055218991 -0.16553015, 0.52508152 0.054650065 -0.16803253, 0.53409296 0.056143131 -0.16396105, 0.52291155 0.05521914 -0.16846764, 0.53759354 0.058901813 -0.16028994, 0.52770883 0.05445781 -0.16633672, 0.51603067 0.058902379 -0.17244124, 0.53613418 0.057386514 -0.16150904, 0.53011078 0.054649886 -0.16504461, 0.52331871 0.05521908 -0.16739106, 0.53240728 0.055218961 -0.16357636, 0.5213021 0.056143191 -0.16783616, 0.52584445 0.054649945 -0.16576153, 0.51523036 0.060631212 -0.1719791, 0.53464186 0.056142863 -0.16124588, 0.51473743 0.062507182 -0.1716944, 0.51457101 0.064458102 -0.17159832, 0.522605 0.062831283 0.12561432, 0.52254814 0.0018236004 0.12532437, 0.52243 0.064441532 0.12400439, 0.52290672 0.0014650635 0.12663054, 0.52243042 0.0019414686 0.12400094, 0.53743011 0.064441502 0.12400448, 0.53743058 -0.0055584796 0.12400058, 0.53737122 0.063503563 0.12494218, 0.53725564 -0.0039485879 0.1256105, 0.53718489 0.062539488 0.12590614, 0.5367676 -0.002475623 0.12708354, 0.53659552 0.061003085 0.12744263, 0.53599042 -0.0011397786 0.12841958, 0.53570276 0.05965304 0.12879249, 0.53499705 -2.8897077e-05 0.12953079, 0.53472829 0.058676895 0.12976837, 0.53385496 0.00083237514 0.13039213, 0.53360158 0.057901289 0.13054389, 0.53262502 0.0014403276 0.13100013, 0.53238457 0.057354148 0.13109103, 0.53148258 0.0017786734 0.1313386, 0.53114152 0.057039615 0.13140553, 0.53069639 0.0019019358 0.1314618, 0.52993 0.056941058 0.13150388, 0.52993041 0.0019411258 0.13150093, 0.52916414 0.056980368 0.13146487, 0.52860689 0.0018233769 0.13138318, 0.52837807 0.057103481 0.13134164, 0.52730048 0.00146484 0.13102481, 0.52723533 0.057441946 0.1310032, 0.52607644 0.00087514147 0.13043496, 0.52600569 0.058049824 0.13039535, 0.52531081 0.00034968182 0.12990922, 0.52486354 0.05891126 0.12953404, 0.52462709 -0.00025539473 0.12930414, 0.52402198 0.00034978613 0.12862039, 0.52386999 0.06002235 0.12842318, 0.52349633 0.00087535009 0.1278547, 0.52309304 0.06135821 0.12708727, 0.522605 0.06284529 -0.12238583, 0.5225482 0.0018376224 -0.12267584, 0.52243012 0.06445542 -0.12399572, 0.52290666 0.0014791004 -0.12136954, 0.52243054 0.0019554161 -0.12399921, 0.53742999 0.064455569 -0.12399551, 0.53743058 -0.0055445321 -0.1239996, 0.53737122 0.063517481 -0.1230579, 0.53725564 -0.0039346255 -0.12238964, 0.53718501 0.062553525 -0.12209395, 0.5367676 -0.0024616756 -0.12091649, 0.53659552 0.061016973 -0.12055752, 0.53599048 -0.0011258163 -0.11958045, 0.53570282 0.059667047 -0.11920771, 0.53499711 -1.4904886e-05 -0.11846936, 0.53472823 0.058690932 -0.1182318, 0.5338549 0.00084645674 -0.11760795, 0.53360158 0.057915267 -0.11745632, 0.5326252 0.0014542751 -0.1170001, 0.53238457 0.057368126 -0.11690909, 0.5314827 0.0017926805 -0.11666158, 0.53114158 0.057053592 -0.11659455, 0.53069639 0.0019158088 -0.11653852, 0.52993006 0.056955095 -0.11649621, 0.52993047 0.0019550435 -0.11649922, 0.5291642 0.056994196 -0.11653531, 0.52860701 0.0018372796 -0.11661708, 0.52837795 0.057117399 -0.11665845, 0.5273006 0.001478862 -0.11697546, 0.52723533 0.057455834 -0.11699691, 0.52607644 0.00088911876 -0.11756518, 0.5260058 0.058063682 -0.11760467, 0.52531093 0.00036365911 -0.11809081, 0.52486354 0.058925178 -0.11846608, 0.52462721 -0.00024164096 -0.11869603, 0.52402198 0.00036361441 -0.11937976, 0.52387011 0.060036179 -0.11957711, 0.52349657 0.00088920817 -0.12014538, 0.5230931 0.061372276 -0.12091282, 0.51142579 -0.0055397786 -0.21205086, 0.51126295 -0.0072086491 -0.21195701, 0.51078254 -0.008793924 -0.21167985, 0.51000863 -0.010215957 -0.21123317, 0.50898021 -0.011403609 -0.21063939, 0.50774866 -0.012297127 -0.20992848, 0.50637591 -0.012851883 -0.20913583, 0.50493056 -0.013040055 -0.20830134, 0.50348538 -0.012852002 -0.20746684, 0.50211233 -0.012297262 -0.20667422, 0.5008809 -0.011403952 -0.20596313, 0.49985236 -0.010216344 -0.20536935, 0.49907854 -0.0087942965 -0.20492253, 0.49859819 -0.0072091557 -0.20464513, 0.4984352 -0.0055401959 -0.20455107, 0.49627018 -0.0055402704 -0.20330095, 0.49643657 -0.0035893507 -0.20339689, 0.49692944 -0.0017135777 -0.20368141, 0.49772969 1.5493482e-05 -0.20414335, 0.49880677 0.0015308671 -0.20476502, 0.50011909 0.0027745478 -0.20552269, 0.50161636 0.0036986582 -0.20638713, 0.50324088 0.004267808 -0.20732498, 0.50493032 0.0044600479 -0.20830044, 0.50661999 0.0042679124 -0.20927596, 0.50824469 0.0036989264 -0.2102139, 0.50974184 0.0027749203 -0.21107826, 0.51105416 0.001531329 -0.21183592, 0.51213121 1.5925616e-05 -0.21245804, 0.51293164 -0.0017128326 -0.21292022, 0.51342428 -0.00358871 -0.21320477, 0.51359075 -0.0055396594 -0.21330091, 0.49843529 -0.005563233 0.20455173, 0.49859813 -0.0072321035 0.20464563, 0.51689941 -0.007230226 0.17294699, 0.51737994 -0.0088154711 0.173224, 0.49907848 -0.008817289 0.20492288, 0.51815361 -0.010237563 0.17367092, 0.49985227 -0.010239396 0.20536971, 0.51918215 -0.011425126 0.17426461, 0.50088078 -0.011426989 0.20596313, 0.52041364 -0.012318719 0.17497554, 0.50211233 -0.012320567 0.2066744, 0.52178639 -0.01287334 0.17576805, 0.50348526 -0.012875367 0.20746705, 0.52323174 -0.013061587 0.17660266, 0.5049305 -0.013063315 0.20830119, 0.50637579 -0.012875307 0.20913577, 0.52467722 -0.012873624 0.17743704, 0.52604991 -0.012318868 0.17822975, 0.50774854 -0.012320686 0.20992839, 0.52728158 -0.011425395 0.1789408, 0.5089801 -0.011427153 0.21063954, 0.52830988 -0.010237742 0.17953447, 0.51000863 -0.010239664 0.21123353, 0.51078242 -0.0088176616 0.21168038, 0.52908367 -0.0088157691 0.17998153, 0.52956414 -0.0072306283 0.1802589, 0.51126283 -0.007232476 0.21195775, 0.51142567 -0.0055634417 0.2120516, 0.51359087 -0.0055635013 0.21330193, 0.53172553 -0.003610868 0.18150708, 0.5134244 -0.0036127008 0.21320581, 0.53123266 -0.0017348267 0.1812225, 0.51293153 -0.0017366894 0.21292129, 0.53043246 -5.9939921e-06 0.18076062, 0.51213121 -7.8715384e-06 0.21245939, 0.52935541 0.0015094392 0.18013901, 0.5110541 0.0015075319 0.21183771, 0.52804309 0.0027531646 0.17938119, 0.50974184 0.002751153 0.21108013, 0.5265457 0.003677275 0.17851713, 0.50824463 0.0036752932 0.21021575, 0.52492124 0.0042462759 0.17757899, 0.50661987 0.0042445622 0.20927775, 0.52323163 0.0044385009 0.17660359, 0.50493032 0.0044366233 0.20830244, 0.52154213 0.0042464845 0.17562798, 0.50324088 0.0042445026 0.20732683, 0.51991761 0.0036774389 0.1746901, 0.50161618 0.0036755018 0.20638883, 0.51842028 0.0027532987 0.17382577, 0.50011891 0.0027514808 0.20552441, 0.51710808 0.0015097223 0.17306811, 0.49880663 0.0015078597 0.2047666, 0.51603097 -5.6661665e-06 0.17244586, 0.49772963 -7.4543059e-06 0.20414469, 0.51523072 -0.0017344691 0.17198387, 0.49692932 -0.001736287 0.20368266, 0.5147379 -0.0036104657 0.17169935, 0.49643657 -0.0036122985 0.20339799, 0.49627009 -0.0055631138 0.20330176, 0.53108931 0.0043887012 -0.13393191, 0.53864783 -0.00065897778 0.12741253, 0.53916931 -0.0017331876 0.15160322, 0.53893858 -0.0012165643 0.12582451, 0.52993035 0.0044560544 -0.13399914, 0.53856981 -0.00052211061 0.12029722, 0.53864789 -0.0006451048 -0.12058744, 0.53811216 0.00020488724 -0.11901942, 0.53885007 -0.0010370649 0.12155691, 0.52993059 -0.015543032 -0.15160269, 0.53188139 -0.015350867 -0.15160269, 0.53740728 0.0010964535 -0.13026109, 0.53375739 -0.014781762 -0.15160269, 0.53188133 0.0042477958 0.15160376, 0.53375733 0.003678795 0.15160361, 0.53319317 0.0038938485 0.13344973, 0.53815889 0.00012451038 0.11912841, 0.53770661 0.00074268505 -0.11821827, 0.53548616 -0.013857637 -0.15160269, 0.53108931 0.0043747537 0.11406824, 0.53222495 0.0041751824 0.11426848, 0.53160495 0.0043136589 -0.11414051, 0.53824526 -4.3101609e-06 0.15160322, 0.53700155 -0.012613971 -0.15160263, 0.52993035 0.0044420473 0.11400098, 0.52993041 0.004454907 -0.1139991, 0.53824514 -0.011098612 -0.15160248, 0.52993029 0.0044399612 0.15160361, 0.53160501 0.0042996518 0.13385969, 0.53770655 0.00072858855 0.12978193, 0.5381121 0.00019101426 0.12898096, 0.53319317 0.0039076768 -0.11455026, 0.53916937 -0.0093697198 -0.15160239, 0.5347054 0.0032414161 -0.11523962, 0.53371865 0.0036967508 0.11475465, 0.53606725 0.0023505948 -0.11621168, 0.53512931 0.0029844157 0.11550122, 0.53721929 0.0013014339 -0.11746994, 0.53637344 0.00208975 0.11649719, 0.53815889 0.00013851747 -0.12887156, 0.53740722 0.0010824166 0.11773899, 0.5363735 0.002103623 -0.13150287, 0.53512931 0.0029984377 -0.13249886, 0.53371876 0.0037106685 -0.1332455, 0.53222507 0.0041891448 -0.1337316, 0.53973848 -0.0074938722 -0.1516023, 0.52993035 0.0044408701 0.13400108, 0.5347054 0.0032274984 0.13276035, 0.53606719 0.0023366474 0.13178843, 0.53548616 0.0027546398 0.15160352, 0.53721935 0.001287546 0.13053021, 0.53700155 0.0015109889 0.15160352, 0.53900737 -0.0013478883 -0.1250926, 0.53904229 -0.0014242269 -0.12370795, 0.53973818 -0.003609065 0.15160307, 0.53885007 -0.0010231324 -0.12644312, 0.53856987 -0.00050816312 -0.12770295, 0.53904229 -0.0014381595 0.12429225, 0.53900719 -0.001361791 0.12290746, 0.53893864 -0.0012024678 -0.12217572, 0.49843472 0.064436883 0.20455572, 0.49859765 0.062768012 0.2046496, 0.51689905 0.06276989 0.1729508, 0.51737952 0.061184492 0.17322806, 0.49907807 0.061182719 0.20492694, 0.51815319 0.059762474 0.17367497, 0.49985179 0.059760701 0.20537359, 0.51918155 0.05857503 0.17426839, 0.50088036 0.058572929 0.20596719, 0.50211191 0.0576795 0.20667827, 0.5204131 0.057681438 0.17497951, 0.52178597 0.057126578 0.1757721, 0.50348485 0.05712479 0.20747074, 0.52323139 0.056938466 0.17660668, 0.5049302 0.056936588 0.2083053, 0.52467656 0.057126638 0.17744103, 0.50637549 0.057124641 0.20913979, 0.50774831 0.057679232 0.20993245, 0.52604949 0.057681199 0.1782338, 0.52728111 0.058574703 0.17894474, 0.50897968 0.058572855 0.21064344, 0.52830952 0.059762355 0.17953831, 0.51000804 0.059760388 0.21123737, 0.52908331 0.061184224 0.17998543, 0.51078182 0.061182436 0.21168408, 0.52956372 0.062769413 0.18026283, 0.51126236 0.062767684 0.21196169, 0.5114252 0.064436495 0.21205586, 0.51342386 0.066387445 0.21320966, 0.53172523 0.066389203 0.18151107, 0.51359028 0.064436525 0.21330571, 0.51293105 0.068263292 0.2129254, 0.53123242 0.06826511 0.18122664, 0.51213068 0.069992229 0.21246332, 0.53043205 0.069993973 0.18076462, 0.51105374 0.071507618 0.21184164, 0.52935499 0.07150954 0.18014267, 0.50974131 0.072751224 0.21108416, 0.52804255 0.072753191 0.17938522, 0.50824416 0.073675275 0.21021962, 0.52654529 0.073677182 0.17852095, 0.50661945 0.074244499 0.20928159, 0.52492082 0.074246287 0.17758301, 0.5049299 0.074436709 0.20830628, 0.52323127 0.074438512 0.17660755, 0.50324041 0.074244604 0.20733088, 0.52154177 0.074246466 0.17563203, 0.50161582 0.073675513 0.20639282, 0.51991707 0.073677421 0.17469412, 0.50011861 0.072751611 0.20552826, 0.5184198 0.072753429 0.17382962, 0.49880615 0.071507931 0.20477048, 0.51710767 0.071509868 0.17307177, 0.49772915 0.069992542 0.20414874, 0.51603037 0.06999442 0.17244986, 0.4969289 0.06826368 0.20368662, 0.51523024 0.068265527 0.17198783, 0.496436 0.066387862 0.2034018, 0.51473731 0.06638968 0.17170325, 0.49626973 0.064436823 0.2033056, 0.42100039 -0.0036088862 0.13380846, 0.42100039 -0.005559776 0.1340006, 0.51993054 -0.0055591799 0.13400048, 0.51993054 -0.0036083795 0.13380855, 0.51993048 -0.0017321445 0.13323957, 0.42100039 -0.00173283 0.13323936, 0.42100036 -3.863126e-06 0.13231531, 0.51993048 -3.3266842e-06 0.13231552, 0.42100039 0.0015114956 0.13107178, 0.51993048 0.0015120767 0.13107201, 0.42100039 0.0027551763 0.12955651, 0.51993048 0.0027557872 0.12955675, 0.42100033 0.003679391 0.12782767, 0.51993042 0.0036800019 0.12782773, 0.42100033 0.0042485707 0.12595177, 0.51993042 0.0042491518 0.12595192, 0.42100045 0.0044408254 0.12400103, 0.51993042 0.0044413917 0.12400118, 0.42100033 0.0042487942 0.12205005, 0.51993042 0.0042494051 0.12205011, 0.42100039 0.0036797933 0.12017402, 0.51993042 0.0036805235 0.12017432, 0.42100033 0.0027557872 0.11844531, 0.5199303 0.0027565025 0.11844534, 0.42100039 0.001512181 0.11692971, 0.51993048 0.0015128367 0.11692974, 0.42100039 -3.0137599e-06 0.11568597, 0.51993048 -2.3283064e-06 0.115686, 0.42100054 -0.0017318912 0.11476186, 0.51993048 -0.0017312057 0.11476189, 0.42100039 -0.0036076792 0.11419258, 0.51993048 -0.0036070831 0.11419261, 0.42100051 -0.0055587031 0.11400053, 0.51993054 -0.0055580772 0.1140005, 0.53978151 0.062724024 0.12228659, 0.53993016 0.064441621 0.12400448, 0.5399304 0.0044416152 0.12400109, 0.53973824 0.004441645 0.12205011, 0.53930587 0.060964134 0.12052658, 0.53916931 0.0044418834 0.12017432, 0.53847986 0.059255179 0.11881736, 0.5382452 0.0044419281 0.11844546, 0.5373683 0.05775803 0.11732012, 0.53700155 0.0044418536 0.1169301, 0.53603089 0.05651876 0.1160807, 0.5354861 0.0044420622 0.11568645, 0.5345279 0.055561837 0.11512381, 0.53375733 0.0044420622 0.1147624, 0.53307778 0.054950353 0.11451223, 0.53188127 0.0044420324 0.11419317, 0.53148323 0.054563489 0.11412516, 0.52993017 0.054442044 0.11400381, 0.52834702 0.054568108 0.11412996, 0.52797961 0.0044421367 0.1141932, 0.52672219 0.054970559 0.11453223, 0.52610356 0.0044420473 0.11476219, 0.5251267 0.055671152 0.11523297, 0.52437466 0.0044420175 0.11568636, 0.52376813 0.056566115 0.11612791, 0.52285939 0.0044417642 0.11692989, 0.52253294 0.057712581 0.11727479, 0.52161568 0.004441794 0.11844534, 0.52147716 0.059098568 0.11866075, 0.52069151 0.0044417642 0.12017423, 0.52065915 0.060693499 0.12025586, 0.52012259 0.0044416003 0.1220502, 0.52010328 0.062588096 0.12215069, 0.51993006 0.064441442 0.12400439, 0.49843487 0.064459801 -0.20454711, 0.49859762 0.066128731 -0.20464098, 0.49907807 0.067713991 -0.2049183, 0.49985182 0.069136083 -0.20536503, 0.50088042 0.070323572 -0.20595858, 0.50211185 0.071217224 -0.20666963, 0.50348479 0.07177189 -0.20746204, 0.50492996 0.071959987 -0.2082966, 0.50637537 0.071772113 -0.20913103, 0.50774831 0.071217433 -0.2099238, 0.50897956 0.070323944 -0.21063459, 0.51000816 0.069136426 -0.21122867, 0.51078194 0.067714453 -0.21167544, 0.51126248 0.066129178 -0.21195295, 0.5114252 0.064460397 -0.21204701, 0.52992994 0.074457109 -0.15159765, 0.52797908 0.074264884 -0.15159774, 0.52797902 0.074247807 0.15160751, 0.52249193 0.057771143 -0.11731222, 0.52010328 0.062602013 -0.12584922, 0.51993006 0.06445542 -0.12399551, 0.52065921 0.060707297 -0.12774411, 0.52147734 0.059112456 -0.12933928, 0.52253306 0.057726618 -0.13072529, 0.52376825 0.056579914 -0.13187218, 0.52138031 0.059254553 0.12919071, 0.52512681 0.055685159 -0.13276708, 0.52672237 0.054984536 -0.13346782, 0.52834707 0.054582056 -0.13387015, 0.52382928 0.056531664 -0.11607277, 0.52533227 0.055574622 -0.11511603, 0.52138042 0.059268322 -0.11880937, 0.52837694 0.054562267 0.13388246, 0.52993017 0.054440912 0.13400385, 0.5205543 0.060977604 -0.12051827, 0.52007872 0.062737674 -0.12227815, 0.52678245 0.05494931 0.13349563, 0.52533209 0.055560794 0.13288429, 0.52382922 0.056517776 0.13192731, 0.52249193 0.057757314 0.13068801, 0.52055418 0.060963657 0.12748185, 0.52007872 0.062723756 0.12572196, 0.528377 0.054576155 -0.1141175, 0.52993006 0.054454919 -0.11399633, 0.52993006 0.054456022 -0.13399616, 0.52678251 0.054963227 -0.11450455, 0.52012217 0.066390783 0.15160701, 0.52012217 0.066407919 -0.15159824, 0.52069128 0.068283796 -0.15159798, 0.5206911 0.068266809 0.15160728, 0.52161533 0.070012659 -0.15159789, 0.52161521 0.069995642 0.15160728, 0.52285892 0.071528077 -0.15159789, 0.5228588 0.071510971 0.15160748, 0.52437419 0.072771728 -0.15159789, 0.52437431 0.072754622 0.15160751, 0.52610314 0.073695838 -0.15159774, 0.52610308 0.073678762 0.15160766, 0.52992988 0.074439883 0.15160766, 0.51342392 0.062509447 -0.21320108, 0.5135904 0.064460456 -0.21329707, 0.51293129 0.060633507 -0.21291655, 0.5121308 0.058904525 -0.2124548, 0.51105386 0.057389136 -0.21183285, 0.50974154 0.056145545 -0.21107525, 0.50824428 0.055221345 -0.21021107, 0.50661975 0.05465233 -0.20927298, 0.50493008 0.054460045 -0.20829764, 0.50324064 0.054652121 -0.20732212, 0.501616 0.055221017 -0.20638418, 0.50011867 0.056145173 -0.20551962, 0.49880642 0.057388779 -0.20476186, 0.49772924 0.058904033 -0.20414004, 0.49692908 0.060632791 -0.20367795, 0.49643615 0.062508851 -0.20339319, 0.49626973 0.064459756 -0.20329699, 0.42100039 -0.0055446513 -0.13399971, 0.51993036 -0.0055440553 -0.13399971, 0.51993066 -0.0074950494 -0.13380757, 0.42100051 -0.0074956305 -0.13380754, 0.51993054 -0.0093709566 -0.13323867, 0.42100045 -0.0093715377 -0.13323861, 0.51993054 -0.011099864 -0.13231468, 0.42100051 -0.011100534 -0.1323148, 0.42100054 -0.012615923 -0.13107121, 0.51993054 -0.012615327 -0.13107109, 0.42100051 -0.013859618 -0.12955594, 0.51993054 -0.013859037 -0.12955582, 0.42100045 -0.014783908 -0.12782711, 0.5199306 -0.014783133 -0.12782705, 0.42100051 -0.015353072 -0.12595102, 0.51993054 -0.015352387 -0.12595102, 0.42100051 -0.015545238 -0.12400025, 0.5199306 -0.015544582 -0.12400016, 0.4210006 -0.015353207 -0.12204927, 0.5199306 -0.015352536 -0.12204921, 0.42100045 -0.014784206 -0.12017331, 0.51993054 -0.014783625 -0.12017331, 0.42100051 -0.013860304 -0.11844447, 0.51993054 -0.013859633 -0.11844444, 0.42100057 -0.012616742 -0.11692917, 0.5199306 -0.012616072 -0.11692905, 0.42100051 -0.011101458 -0.11568531, 0.51993054 -0.011100817 -0.11568511, 0.42100045 -0.0093725659 -0.11476105, 0.51993042 -0.00937194 -0.11476099, 0.42100051 -0.0074967481 -0.11419183, 0.51993054 -0.0074960925 -0.11419192, 0.42100045 -0.0055457987 -0.11399955, 0.51993054 -0.0055452026 -0.11399961, 0.53978151 0.062738001 -0.12571362, 0.53993005 0.064455599 -0.12399572, 0.5399304 0.0044555031 -0.12399918, 0.53973812 0.0044556223 -0.12594998, 0.53930598 0.060977992 -0.1274735, 0.53916931 0.0044557266 -0.12782586, 0.5384798 0.059269097 -0.1291827, 0.53824514 0.0044558011 -0.12955484, 0.5373683 0.057772066 -0.13067988, 0.53700149 0.0044558756 -0.13107026, 0.53603083 0.056532618 -0.1319195, 0.53548604 0.004455965 -0.13231385, 0.53452808 0.055575695 -0.13287652, 0.53375733 0.0044560097 -0.13323787, 0.53307772 0.0549643 -0.13348806, 0.53188127 0.0044559799 -0.13380685, 0.53148335 0.054577347 -0.13387492, 0.52797943 0.0044560395 -0.13380685, 0.52610356 0.0044560097 -0.13323787, 0.52437466 0.0044558756 -0.13231385, 0.52285945 0.004455816 -0.13107005, 0.52161574 0.0044557117 -0.12955499, 0.52069157 0.0044556223 -0.12782586, 0.52012259 0.0044555031 -0.12594998, 0.51993048 0.0044553988 -0.12399897, 0.52243048 -0.0055441894 -0.13149977, 0.42100045 -0.0055448301 -0.13149977, 0.5224697 -0.0063100792 -0.13146046, 0.52259284 -0.0070962943 -0.1313374, 0.42100042 -0.0072137304 -0.13131166, 0.5229314 -0.0082389601 -0.13099897, 0.42100045 -0.0087989755 -0.13075709, 0.52353925 -0.0094687231 -0.13039115, 0.42100048 -0.010221202 -0.12986362, 0.52440065 -0.010610793 -0.12952995, 0.42100045 -0.01140869 -0.12867618, 0.52551168 -0.011604298 -0.12841904, 0.42100045 -0.012302238 -0.12725419, 0.52684742 -0.012381379 -0.12708324, 0.42100051 -0.012857158 -0.12566897, 0.52832049 -0.01286963 -0.12561008, 0.52993053 -0.01304454 -0.12400016, 0.42100051 -0.013045225 -0.12400001, 0.52899265 -0.012985799 -0.12306216, 0.42100045 -0.012857217 -0.12233117, 0.52802867 -0.012799431 -0.12209836, 0.42100045 -0.012302656 -0.12074593, 0.52649212 -0.012210209 -0.12056154, 0.52514225 -0.011317436 -0.11921176, 0.42100051 -0.011409257 -0.11932394, 0.52416629 -0.010343079 -0.1182355, 0.42100045 -0.010221768 -0.1181362, 0.52339059 -0.0092165507 -0.11745995, 0.42100042 -0.0087997206 -0.11724257, 0.5228436 -0.0079995431 -0.11691275, 0.42100048 -0.0072146095 -0.1166878, 0.52252907 -0.0067565329 -0.11659837, 0.42100045 -0.0055457242 -0.11649975, 0.5224306 -0.0055450685 -0.11649966, 0.52243048 -0.0055580176 0.1165005, 0.42100039 -0.0055586733 0.1165005, 0.5224697 -0.0063238777 0.11653966, 0.52259278 -0.0071102418 0.1166628, 0.42100045 -0.007227812 0.1166884, 0.5229314 -0.0082530268 0.11700124, 0.42100045 -0.0088130273 0.11724296, 0.52353925 -0.0094827302 0.11760899, 0.42100045 -0.01023512 0.11813644, 0.52440047 -0.010624696 0.1184701, 0.42100045 -0.011422653 0.119324, 0.52551162 -0.011618216 0.11958104, 0.42100045 -0.012316246 0.12074587, 0.52684742 -0.012395371 0.12091711, 0.42100045 -0.012871075 0.12233105, 0.52832049 -0.012883548 0.12239006, 0.52993053 -0.013058532 0.1240001, 0.42100045 -0.013059173 0.1240001, 0.52899259 -0.012999583 0.12493792, 0.42100048 -0.012871329 0.12566891, 0.52802867 -0.012813557 0.12590194, 0.42100045 -0.012316633 0.12725425, 0.5264923 -0.012224156 0.12743849, 0.52514231 -0.011331368 0.12878844, 0.42100045 -0.011423055 0.12867615, 0.52416629 -0.010357071 0.1297645, 0.42100045 -0.010235716 0.12986404, 0.52339059 -0.0092303939 0.1305401, 0.42100042 -0.0088136829 0.13075742, 0.52284354 -0.0080133565 0.13108748, 0.42100042 -0.007228557 0.13131234, 0.52252895 -0.0067703761 0.13140178, 0.42100051 -0.0055595972 0.13150048, 0.52243048 -0.0055590309 0.13150051, 0.5326249 0.057442721 0.1170049, 0.53385448 0.058050569 0.11761269, 0.53148228 0.057104167 0.11666641, 0.53069609 0.056981202 0.1165432, 0.53499651 0.058911886 0.11847404, 0.53598994 0.060022917 0.11958531, 0.53676707 0.061358687 0.12092122, 0.53725523 0.06283167 0.12239426, 0.53725517 0.062845588 -0.12560579, 0.537242 0.062788159 -0.15159833, 0.53676707 0.061372634 -0.12707898, 0.53599 0.060036864 -0.12841484, 0.53668731 0.06120294 -0.15159845, 0.53499657 0.058925834 -0.1295259, 0.5357939 0.059780981 -0.15159848, 0.5338546 0.058064606 -0.13038743, 0.53460634 0.058593448 -0.15159857, 0.53262502 0.057456668 -0.1309953, 0.53318423 0.057699796 -0.15159857, 0.53148216 0.057118174 -0.13133383, 0.53159899 0.057145085 -0.15159857, 0.53069603 0.05699512 -0.13145688, 0.53318423 0.057682779 0.15160668, 0.53460616 0.058576282 0.15160668, 0.53159893 0.057127949 0.15160668, 0.53724188 0.062771112 0.15160692, 0.53668731 0.061185863 0.15160683, 0.52993011 0.056939926 0.15160668, 0.52993 0.056942072 0.11650386, 0.52993006 0.056957003 -0.15159857, 0.52993006 0.05695587 -0.13149619, 0.53579384 0.059763905 0.15160683, 0.52993047 0.0019558631 -0.1314992, 0.52915716 0.0019158386 -0.13145936, 0.52993047 0.0019569956 -0.1516017, 0.52826154 0.0017689578 -0.15160179, 0.52838051 0.0017939322 -0.1313374, 0.52709037 0.0013972335 -0.13094071, 0.5266763 0.0012142621 -0.15160179, 0.52576518 0.00069273636 -0.13023615, 0.52525419 0.00032074377 -0.15160179, 0.52462727 -0.0002409555 -0.12930271, 0.52406669 -0.00086681917 -0.15160194, 0.52402198 -0.00092476979 -0.12990797, 0.52349639 -0.0016902126 -0.13043344, 0.52317327 -0.0022889115 -0.15160203, 0.52290678 -0.0029144324 -0.13102326, 0.52261853 -0.003874097 -0.15160203, 0.52254826 -0.0042206384 -0.1313819, 0.52993029 0.0019420348 0.11650091, 0.52915716 0.0019020401 0.11654079, 0.52838051 0.0017799847 0.11666277, 0.52709037 0.0013833158 0.1170595, 0.52576494 0.00067883357 0.11776379, 0.52462721 -0.0002549924 0.11869743, 0.52402192 -0.00093882158 0.11809251, 0.52369344 -0.0013796128 -0.11776233, 0.52349639 -0.0017041601 0.11756662, 0.52298903 -0.0027049519 -0.11705807, 0.5229066 -0.0029283054 0.11697692, 0.52259248 -0.0039951093 -0.11666158, 0.52254826 -0.00423472 0.11661822, 0.52247047 -0.0047717281 -0.1165396, 0.52369356 -0.0013936795 0.13023779, 0.52298909 -0.0027188398 0.13094199, 0.52259231 -0.0040089674 0.1313386, 0.52247041 -0.0047856607 0.13146049, 0.52261853 -0.007229019 0.15160292, 0.52317327 -0.008814279 0.15160292, 0.52406675 -0.010236252 0.15160292, 0.52525431 -0.011423815 0.15160263, 0.52667642 -0.012317348 0.15160263, 0.5282616 -0.012872014 0.15160263, 0.52993053 -0.013060112 0.15160263, 0.53100067 -0.012967829 -0.12507007, 0.53100061 -0.012967933 -0.12293008, 0.53114194 0.0018573962 -0.1314007, 0.53238493 0.0015428774 -0.13108635, 0.5315994 0.0017689429 -0.15160179, 0.533602 0.00099575147 -0.13053909, 0.53318453 0.0012143217 -0.15160179, 0.53472865 0.00022007152 -0.1297636, 0.53460664 0.00032080337 -0.15160179, 0.53570324 -0.00075611845 -0.12878758, 0.53579426 -0.00086681917 -0.15160203, 0.53659594 -0.0021059848 -0.12743777, 0.53668779 -0.0022888072 -0.15160203, 0.53718537 -0.0036425032 -0.12590155, 0.53737164 -0.0046065338 -0.1249375, 0.53724247 -0.0038740076 -0.15160215, 0.53737181 -0.0046205558 0.12306264, 0.53100055 -0.012981702 0.12292987, 0.53718537 -0.0036564805 0.12209883, 0.536596 -0.0021198429 0.12056234, 0.53570318 -0.00077000633 0.11921254, 0.53472865 0.00020615384 0.11823648, 0.533602 0.00098174438 0.117461, 0.53238487 0.0015288554 0.11691386, 0.53114188 0.0018435232 0.11659935, 0.53100055 -0.012981687 0.12507012, 0.53159934 -0.012872029 0.15160277, 0.53318465 -0.012317363 0.15160263, 0.53460675 -0.01142383 0.15160277, 0.53579432 -0.010236252 0.15160277, 0.53668779 -0.0088141598 0.15160292, 0.53724247 -0.0072288848 0.15160298, 0.52267522 0.062539607 0.12210244, 0.52326471 0.061003383 0.12056595, 0.5241574 0.059653547 0.11921591, 0.52513182 0.05867755 0.11823991, 0.52625859 0.057901915 0.11746421, 0.5274756 0.057354864 0.11691704, 0.52871865 0.057040509 0.11660248, 0.52248889 0.063503593 0.1230666, 0.52261811 0.062771022 0.15160692, 0.5231728 0.061185684 0.15160683, 0.52406633 0.059763756 0.15160668, 0.52525383 0.058576223 0.15160668, 0.52667588 0.05768263 0.15160668, 0.52826124 0.057127919 0.15160668, 0.5231728 0.061202761 -0.15159845, 0.52261811 0.062788069 -0.15159845, 0.52267522 0.062553525 -0.12589765, 0.52826113 0.057145115 -0.15159869, 0.52871853 0.057054337 -0.1313976, 0.52248901 0.063517481 -0.12493369, 0.52667594 0.057699766 -0.15159857, 0.52747566 0.057368841 -0.13108304, 0.52525395 0.058593269 -0.15159857, 0.52625865 0.057915892 -0.13053593, 0.525132 0.058691408 -0.1297603, 0.52415752 0.059667524 -0.12878421, 0.52406627 0.059780832 -0.15159857, 0.52326471 0.061017212 -0.12743431, 0.42100051 -0.0038907714 0.13131258, 0.42100051 -0.0023055263 0.13075778, 0.42100039 -0.00088337436 0.12986463, 0.42100039 0.00030432269 0.12867698, 0.42100051 0.0011978708 0.12725493, 0.42100033 0.0017526709 0.12566981, 0.42100036 0.0019408725 0.12400088, 0.52247047 0.0019015186 0.12322763, 0.52259231 0.0017795824 0.12245092, 0.42100039 0.0017528348 0.1223321, 0.52298903 0.0013829879 0.12116081, 0.42100048 0.0011982583 0.12074667, 0.52369344 0.00067866966 0.11983544, 0.42100039 0.00030476972 0.11932459, 0.42100039 -0.00088273361 0.11813697, 0.42100039 -0.0023047365 0.11724329, 0.42100039 -0.0038899221 0.11668849, 0.42100057 -0.0038767792 -0.11668774, 0.42100045 -0.0022915192 -0.11724216, 0.42100042 -0.00086941198 -0.11813572, 0.42100042 0.00031810626 -0.11932331, 0.42100042 0.0012118779 -0.12074509, 0.42100042 0.0017666481 -0.12233028, 0.42100039 0.0019548051 -0.12399942, 0.52247047 0.001915466 -0.12477267, 0.52259243 0.0017935298 -0.12554929, 0.42100042 0.0017667376 -0.12566814, 0.52298903 0.0013969801 -0.12683928, 0.42100042 0.0012121759 -0.12725347, 0.52369344 0.00069260225 -0.12816465, 0.42100057 0.00031870231 -0.12867558, 0.42100039 -0.00086878613 -0.12986323, 0.42100045 -0.0022907145 -0.13075683, 0.42100045 -0.0038759746 -0.13131166, 0.42100033 0.023441326 0.11400208, 0.41800037 0.0044413768 0.11400095, 0.41800013 0.023441475 0.11400196, 0.42100039 0.0044412874 0.11400113, 0.42100027 0.023454126 -0.11399806, 0.41800043 0.0044541173 -0.1139991, 0.42100042 0.0044541918 -0.1139991, 0.41800028 0.023454171 -0.11399806, 0.52160513 0.0042663179 -0.11844334, 0.52069157 0.0044551454 -0.12017232, 0.52068681 0.0043700002 -0.12017241, 0.52003276 0.0042925887 -0.12204823, 0.52005023 0.0043050312 -0.12204823, 0.52067256 0.0042858236 -0.12017232, 0.5201214 0.0044337474 -0.1220482, 0.52011782 0.0044125132 -0.12204823, 0.52200162 0.0023838989 -0.11692825, 0.52279937 0.0014653914 -0.11589363, 0.52222031 0.0026288144 -0.11692813, 0.5212481 0.0034043305 -0.11844334, 0.52112216 0.0032633506 -0.11844334, 0.52098125 0.0031374656 -0.11844352, 0.52046865 0.0039169602 -0.12017241, 0.52011192 0.0043917559 -0.1220482, 0.52040517 0.0038600825 -0.12017241, 0.52284092 0.0041270219 -0.11692801, 0.52285945 0.0044549368 -0.11692801, 0.52161568 0.0044551454 -0.11844334, 0.52033538 0.0038107 -0.12017232, 0.52157348 0.0040800832 -0.11844328, 0.52001381 0.0042821877 -0.12204823, 0.52064896 0.0042038076 -0.12017232, 0.52175659 0.0021650158 -0.11692813, 0.52244639 0.0010874532 -0.11585033, 0.52668947 0.0039150082 -0.11453155, 0.52797943 0.0044549368 -0.11419117, 0.52610362 0.0044549666 -0.11476043, 0.52404767 0.0039910637 -0.11589348, 0.52437466 0.0044548623 -0.11568442, 0.520827 0.0030281059 -0.11844352, 0.52826458 0.0043151639 -0.1141386, 0.52010369 0.0043718629 -0.12204823, 0.52026081 0.0037693493 -0.12017232, 0.52278596 0.0038032345 -0.11692813, 0.52497441 0.0038865916 -0.11529553, 0.52542168 0.0033808909 -0.11502147, 0.51999396 0.0042738281 -0.12204799, 0.52152109 0.0038985275 -0.11844334, 0.52148867 0.0019750409 -0.11692825, 0.52209973 0.00067430362 -0.11574239, 0.52061629 0.004124891 -0.12017232, 0.52066165 0.0029367171 -0.11844352, 0.52396983 0.0035329871 -0.11589348, 0.5248059 0.0030420087 -0.11529553, 0.52018183 0.0037367307 -0.12017241, 0.52009314 0.0043530278 -0.12204799, 0.51997322 0.0042679124 -0.12204799, 0.52120125 0.00181612 -0.11692831, 0.52160633 -3.6396086e-06 -0.1154803, 0.522695 0.0034875982 -0.11692813, 0.52144879 0.0037238561 -0.11844352, 0.52048707 0.002864372 -0.11844352, 0.52057499 0.0040502511 -0.12017232, 0.52384126 0.0030865334 -0.11589348, 0.52420896 0.002656471 -0.11555624, 0.52009982 0.0037131272 -0.12017232, 0.51995206 0.0042643063 -0.12204799, 0.5199306 0.0042630844 -0.12204823, 0.5199306 0.0036940239 -0.12017232, 0.52089787 0.0016904138 -0.11692813, 0.52008069 0.0043354891 -0.1220482, 0.5225693 0.0031841658 -0.11692813, 0.52030545 0.0028120242 -0.11844334, 0.52135736 0.0035584532 -0.11844334, 0.52001566 0.0036988072 -0.12017232, 0.51993048 0.0027697794 -0.11844352, 0.52052552 0.0039805733 -0.12017241, 0.52129894 0.00054405257 -0.11589384, 0.52118254 -0.00070011988 -0.11517015, 0.52006644 0.0043193661 -0.1220482, 0.5205822 0.0015994273 -0.11692825, 0.52241039 0.0028966181 -0.11692813, 0.52011907 0.0027803592 -0.11844352, 0.51993048 0.0015259944 -0.11692825, 0.51993048 -0.0035942234 -0.11419174, 0.52007014 -0.0038797744 -0.11413908, 0.52047127 -0.002301652 -0.11453277, 0.51993066 -0.0017183162 -0.1147607, 0.52085245 0.00041545555 -0.11589384, 0.52025843 0.0015443079 -0.11692813, 0.52343881 0.0022506081 -0.11589363, 0.52352494 0.0021340959 -0.11579755, 0.52105993 -0.0004937686 -0.11529562, 0.52079511 -0.0014777221 -0.11483631, 0.52012259 0.0044552498 -0.1220482, 0.52039433 0.00033759698 -0.11589384, 0.51993048 1.0605901e-05 -0.11568463, 0.52049875 -0.00058912113 -0.11529568, 0.53612334 0.002838742 -0.11621168, 0.53700149 0.0044551007 -0.11692801, 0.53548604 0.004455056 -0.11568442, 0.53188127 0.0044549666 -0.11419117, 0.53691709 0.0027595423 -0.11692813, 0.53800029 0.0026515387 -0.11821821, 0.53824502 0.0044552647 -0.11844328, 0.53375727 0.0044549219 -0.11476028, 0.539074 0.0025444888 -0.12017241, 0.53916925 0.0044552647 -0.12017211, 0.53773195 0.00086570904 -0.11821821, 0.53964043 0.0024880879 -0.12204838, 0.53973824 0.0044553839 -0.12204823, 0.53878975 0.00065241382 -0.12017244, 0.53982735 0.0024694465 -0.12370762, 0.53934741 0.00054014847 -0.12204838, 0.53977191 0.0024750344 -0.12509254, 0.53953159 0.00050301477 -0.12370777, 0.53952992 0.0024992935 -0.12644303, 0.53947711 0.00051416084 -0.1250928, 0.53912395 0.0025398843 -0.12770268, 0.53923869 0.00056226179 -0.12644312, 0.53857064 0.0025950931 -0.12887144, 0.53883886 0.00064290687 -0.12770283, 0.53763938 0.0026882403 -0.13026094, 0.53829342 0.00075302646 -0.12887156, 0.53691709 0.0027603619 -0.13107026, 0.53540921 0.0029109083 -0.13231385, 0.52006632 0.0043195896 -0.12594998, 0.52008063 0.0043356977 -0.12594998, 0.52278584 0.0038040839 -0.13107026, 0.52284092 0.0041278414 -0.13107026, 0.5242722 0.003966596 -0.13226309, 0.52052552 0.0039809756 -0.12782586, 0.52046865 0.0039173774 -0.12782586, 0.52405441 0.0030128919 -0.13226309, 0.5251087 0.0032166056 -0.13283864, 0.52440989 0.0027939789 -0.13252735, 0.52182615 0.00051939115 -0.1322633, 0.52238792 0.0010216199 -0.13216186, 0.52188116 0.00038963184 -0.13235751, 0.52419007 0.0034836195 -0.13226318, 0.52148873 0.0019758306 -0.13107026, 0.52068692 0.004370328 -0.12782586, 0.52827793 0.0043185018 -0.13386181, 0.52040499 0.0038604699 -0.12782586, 0.52112216 0.0032639466 -0.12955484, 0.52160525 0.0042669885 -0.12955475, 0.52098107 0.0031380169 -0.12955484, 0.5215736 0.0040807091 -0.12955499, 0.52670938 0.0039228909 -0.13347316, 0.52082711 0.0030286871 -0.12955499, 0.52175665 0.0021658204 -0.13107026, 0.52269506 0.0034883879 -0.13107026, 0.52120125 0.0018169396 -0.13107038, 0.5201214 0.0044339858 -0.12594998, 0.52005011 0.0043052994 -0.12594998, 0.5206725 0.0042862408 -0.12782586, 0.52137351 0.00033175573 -0.1322633, 0.52117521 -0.00071221963 -0.13283443, 0.52152115 0.0038991086 -0.12955484, 0.52033538 0.0038109981 -0.12782586, 0.52256924 0.0031849854 -0.13107026, 0.52373278 0.0023037903 -0.13226318, 0.52066165 0.0029373132 -0.12955499, 0.5201177 0.004412692 -0.12594998, 0.52111518 -0.0007350333 -0.13283899, 0.52062207 -0.0018899776 -0.13332251, 0.52064896 0.0042041205 -0.12782586, 0.52089787 0.0016912036 -0.13107026, 0.52144885 0.0037245415 -0.12955499, 0.52003264 0.0042927526 -0.12594998, 0.52090275 0.00019617006 -0.1322633, 0.52241045 0.0028974377 -0.13107026, 0.52011186 0.0043919645 -0.12594998, 0.52026075 0.0037697516 -0.12782586, 0.52061635 0.0041252337 -0.12782586, 0.52048713 0.0028649531 -0.12955499, 0.52135742 0.0035590641 -0.12955484, 0.52052665 -0.0008350648 -0.13283885, 0.51993048 -0.0017172582 -0.1332382, 0.51993048 1.1514872e-05 -0.13231409, 0.52222031 0.0026296936 -0.13107026, 0.52300894 0.0016734414 -0.13210931, 0.51993048 -0.0035931356 -0.13380733, 0.52014118 -0.0035023279 -0.13378942, 0.51998407 -0.0045110025 -0.13394618, 0.52058214 0.0016002469 -0.13107026, 0.52010357 0.0043720864 -0.12594998, 0.52001375 0.0042823665 -0.12594998, 0.52057499 0.0040505789 -0.12782586, 0.5204196 0.00011409447 -0.1322633, 0.51993048 0.0015268438 -0.13107026, 0.5212481 0.0034049265 -0.12955484, 0.52018201 0.0037370585 -0.12782586, 0.52200145 0.0023847781 -0.13107026, 0.52030545 0.0028126203 -0.12955499, 0.52009308 0.0043532364 -0.12594998, 0.52025843 0.0015452616 -0.13107038, 0.51999396 0.0042740814 -0.12594998, 0.52522141 0.0038597248 -0.13283864, 0.52588695 0.003602054 -0.1331718, 0.5200997 0.00371347 -0.12782586, 0.52011913 0.0027810298 -0.12955484, 0.51993048 0.0027704202 -0.12955499, 0.51997322 0.0042681657 -0.12594998, 0.52001566 0.0036991797 -0.12782586, 0.51993042 0.0036943965 -0.12782604, 0.51995188 0.0042645298 -0.12594998, 0.51993048 0.004263293 -0.12594998, 0.52007169 -0.0072174706 -0.13385856, 0.52158064 -0.012076307 -0.11649922, 0.52228504 -0.011990789 -0.11649892, 0.52139014 -0.010747124 -0.11550248, 0.52019864 -0.0078452267 -0.11426851, 0.51999801 -0.0067050047 -0.11406729, 0.52363318 -0.013908092 -0.11912802, 0.52424806 -0.013773505 -0.11912787, 0.52329159 -0.013023112 -0.11774004, 0.52169818 -0.013255242 -0.11774018, 0.52373338 -0.014404047 -0.12017325, 0.52489465 -0.014184225 -0.12029698, 0.52179116 -0.01418503 -0.11912772, 0.52068096 -0.0093456991 -0.11475858, 0.5238238 -0.014853109 -0.12155712, 0.52540958 -0.014464516 -0.12155712, 0.52184135 -0.014688481 -0.12017325, 0.5238719 -0.015091408 -0.12290844, 0.52573425 -0.014621649 -0.1229082, 0.5238837 -0.01514994 -0.12400016, 0.52558762 -0.014552299 -0.12582684, 0.52581018 -0.014656205 -0.12429419, 0.52188689 -0.015144352 -0.12155724, 0.52191114 -0.015386272 -0.12290853, 0.5238505 -0.014985029 -0.12582684, 0.525029 -0.014260877 -0.12741622, 0.52191693 -0.015445713 -0.12400016, 0.52376485 -0.014560107 -0.12741637, 0.52417904 -0.013724733 -0.12898299, 0.52190024 -0.015278239 -0.12582684, 0.52362078 -0.013846043 -0.12898299, 0.52308148 -0.012830604 -0.13053274, 0.52364069 -0.013318483 -0.12978435, 0.5218572 -0.014846925 -0.12741619, 0.52178484 -0.014122147 -0.12898299, 0.52167577 -0.01302867 -0.13053274, 0.52203292 -0.011678327 -0.13178983, 0.52154654 -0.011734251 -0.1317898, 0.52114266 -0.010316376 -0.13276076, 0.52047735 -0.008805681 -0.1334492, 0.52241033 0.0028827749 0.13107201, 0.52222031 0.0026149116 0.13107213, 0.523525 0.0021201335 0.13220268, 0.5205822 0.0015855543 0.13107181, 0.52045 -0.00017096475 0.13244385, 0.52096313 -8.3763152e-05 0.13244385, 0.52025843 0.0015305094 0.13107201, 0.52006632 0.0043053888 0.12595192, 0.52005029 0.004291039 0.12595192, 0.52146333 6.0301274e-05 0.13244385, 0.52118254 -0.00071394816 0.13283008, 0.52160633 -1.7542392e-05 0.1325199, 0.52040499 0.0038460605 0.12782773, 0.52046865 0.0039029829 0.12782788, 0.5200702 -0.0038937964 0.13386112, 0.52001554 0.0036849193 0.12782773, 0.52052552 0.0039667152 0.12782773, 0.52112216 0.0032492839 0.12955675, 0.52011913 0.002766367 0.12955654, 0.52124804 0.0033904277 0.12955654, 0.52047116 -0.0023154058 0.13346726, 0.52135748 0.003544461 0.12955675, 0.52030551 0.0027980171 0.12955654, 0.52256918 0.0031702481 0.13107201, 0.52420914 0.0026426427 0.13244408, 0.52089781 0.0016764961 0.13107201, 0.52008069 0.0043214969 0.12595192, 0.519952 0.0042502992 0.12595192, 0.52057499 0.0040363334 0.12782773, 0.52009982 0.0036991201 0.12782773, 0.52144885 0.0037098341 0.12955675, 0.522695 0.0034736805 0.13107213, 0.5248059 0.0030281655 0.13270456, 0.52048707 0.0028503649 0.12955654, 0.52120125 0.0018021725 0.13107201, 0.52209973 0.00066043064 0.13225767, 0.52445525 0.0034082942 0.13244408, 0.52542156 0.0033669285 0.13297877, 0.51997322 0.0042539649 0.12595192, 0.52009302 0.0043390505 0.12595192, 0.52061611 0.0041109882 0.12782773, 0.52018178 0.0037227981 0.12782767, 0.52066171 0.0029227249 0.12955654, 0.52549034 0.0038146488 0.13297877, 0.52668941 0.003901165 0.1334686, 0.52610356 0.004441034 0.13323981, 0.5243746 0.0044410788 0.13231581, 0.52148861 0.0019611083 0.13107201, 0.52244639 0.0010735504 0.1321499, 0.52152121 0.0038844608 0.12955654, 0.51999396 0.0042598955 0.12595192, 0.52278596 0.0037892424 0.13107213, 0.52026069 0.003755521 0.12782773, 0.52454245 0.0039213859 0.13244408, 0.52010345 0.0043579601 0.12595192, 0.52082705 0.0030141138 0.12955654, 0.52797961 0.0044408552 0.13380906, 0.52826458 0.0043011419 0.13386148, 0.52175659 0.0021512024 0.13107201, 0.52279937 0.0014514886 0.13210642, 0.5206489 0.0041898601 0.12782773, 0.52001381 0.0042681806 0.12595192, 0.52157348 0.0040660314 0.12955654, 0.52284098 0.0041130893 0.13107213, 0.52285933 0.0044410489 0.13107213, 0.52161556 0.004441198 0.12955675, 0.52033538 0.0037967227 0.12782773, 0.52011186 0.0043778382 0.12595192, 0.52098119 0.0031234883 0.12955654, 0.52200145 0.0023699366 0.13107201, 0.5206725 0.0042718761 0.12782788, 0.52160513 0.0042524002 0.12955675, 0.52003258 0.0042785816 0.12595201, 0.52069157 0.0044412576 0.12782773, 0.52011782 0.0043984912 0.12595201, 0.52068669 0.0043561123 0.12782767, 0.52012253 0.004441347 0.12595192, 0.52055687 -0.0011191852 0.1329785, 0.52079511 -0.0014916398 0.13316387, 0.52012146 0.0044197552 0.12595201, 0.53188121 0.0044409595 0.13380906, 0.53645873 0.0027922504 0.11649734, 0.53829354 0.00073910877 0.1191285, 0.5376392 0.0026742183 0.11773911, 0.53878963 0.00063895807 0.12017408, 0.53857052 0.0025812052 0.11912873, 0.53923863 0.0005483143 0.12155703, 0.53907412 0.0025309287 0.12017408, 0.53947699 0.00050031766 0.12290746, 0.53953582 0.00048833713 0.12400094, 0.5395298 0.002485346 0.12155703, 0.53977185 0.0024611317 0.12290764, 0.53937149 0.0005213283 0.12582451, 0.53983146 0.0024552308 0.12400094, 0.5389477 0.00060672686 0.12741277, 0.53966463 0.0024716072 0.12582457, 0.53973824 0.0044414364 0.12595201, 0.53823376 0.00075062737 0.12898082, 0.53923446 0.0025144778 0.1274128, 0.53916925 0.004441347 0.12782773, 0.53850996 0.0025867335 0.12898096, 0.53824508 0.0044412725 0.12955675, 0.53741777 0.0026956908 0.1305303, 0.53700149 0.0044411533 0.13107222, 0.53612345 0.0028247796 0.13178843, 0.53548616 0.004441034 0.13231581, 0.53375727 0.0044411086 0.13323992, 0.5220015 0.0023707263 0.11692974, 0.52300888 0.0016595684 0.11589077, 0.52175665 0.0021519177 0.11692974, 0.52098113 0.0031242333 0.1184451, 0.5211221 0.003250014 0.11844534, 0.5200997 0.0036996417 0.12017423, 0.52001566 0.0036852919 0.12017423, 0.51995188 0.0042505674 0.1220502, 0.5199939 0.0042601489 0.1220502, 0.51997316 0.004254248 0.1220502, 0.52124804 0.0033910386 0.11844534, 0.52046859 0.0039034449 0.12017423, 0.52052546 0.003967192 0.12017423, 0.52025843 0.0015312098 0.11692989, 0.52011913 0.0027670674 0.11844534, 0.52057499 0.0040367506 0.12017423, 0.52008057 0.0043217205 0.1220502, 0.52009308 0.0043392889 0.1220502, 0.52030545 0.0027987026 0.11844534, 0.52010339 0.0043581836 0.12205011, 0.52018183 0.0037232004 0.12017423, 0.52222031 0.0026155971 0.11692989, 0.52373278 0.0022898428 0.11573696, 0.5203951 0.00031840429 0.11589068, 0.52135736 0.0035451613 0.11844534, 0.52014118 -0.0035161264 0.11421078, 0.52001375 0.0042684041 0.1220502, 0.52061629 0.0041114204 0.12017432, 0.5205822 0.0015862696 0.11692974, 0.52052563 -0.00084056333 0.11516565, 0.52062201 -0.0019038804 0.11467776, 0.52048707 0.0028510205 0.1184451, 0.51998407 -0.004524935 0.11405391, 0.52011174 0.0043780319 0.1220502, 0.52241045 0.0028835051 0.11692989, 0.52026075 0.0037558638 0.12017423, 0.52144873 0.0037106089 0.11844534, 0.52085388 0.00039632246 0.11589068, 0.52064896 0.0041902773 0.12017423, 0.5200327 0.0042788498 0.1220502, 0.52011776 0.0043987148 0.1220502, 0.52089787 0.0016772263 0.11692989, 0.5225693 0.0031709783 0.11692989, 0.52440989 0.0027801357 0.115473, 0.52111328 -0.00074069574 0.11516565, 0.52117532 -0.00072616711 0.11516592, 0.52066171 0.0029233806 0.1184451, 0.52152115 0.0038851611 0.11844534, 0.52067256 0.0042722933 0.12017423, 0.52033526 0.0037971847 0.12017423, 0.52012146 0.0044199936 0.1220502, 0.52005017 0.0042912476 0.12205011, 0.52120131 0.0018029325 0.11692974, 0.522695 0.0034743659 0.11692989, 0.52082705 0.003014829 0.1184451, 0.52157336 0.0040667467 0.11844534, 0.52040499 0.003846582 0.12017423, 0.52068681 0.00435647 0.12017423, 0.5217309 0.00070328638 0.11589068, 0.52188122 0.00037574396 0.11564255, 0.52384716 0.0030714236 0.11589092, 0.52510864 0.0032026879 0.11516136, 0.52006626 0.0043057017 0.12205011, 0.52148873 0.0019618087 0.11692989, 0.52278584 0.0037900321 0.11692989, 0.52160513 0.0042531155 0.11844534, 0.52827805 0.0043047033 0.11413854, 0.52670926 0.0039090924 0.11452693, 0.52397609 0.0035185479 0.11589092, 0.52588695 0.0035881363 0.11482832, 0.52213818 0.00092835352 0.11589077, 0.52238774 0.0010077171 0.11583823, 0.5228408 0.004113894 0.11692989, 0.52405399 0.0039774142 0.11589092, 0.52521294 0.0038468055 0.11516595, 0.52107668 0.00055072829 0.11595878, 0.5215466 -0.011748169 0.11621025, 0.51993054 -0.012629274 0.11692896, 0.51993054 -0.011113767 0.1156854, 0.5211426 -0.010330293 0.11523932, 0.52203292 -0.011692096 0.11621025, 0.52007157 -0.0072314031 0.11414161, 0.51993054 -0.007508982 0.11419258, 0.52162611 -0.012544904 0.11692896, 0.52308148 -0.012844611 0.11746731, 0.52173394 -0.013625775 0.11821559, 0.51993054 -0.013872985 0.11844426, 0.52047735 -0.0088196285 0.11455095, 0.51993042 -0.0093848146 0.11476156, 0.52184135 -0.014701966 0.12017316, 0.51993054 -0.014797155 0.12017316, 0.52351958 -0.013357285 0.11821574, 0.52364081 -0.01333246 0.11821574, 0.52417916 -0.0137388 0.11901718, 0.52189779 -0.015268359 0.122049, 0.5199306 -0.015366305 0.12204888, 0.5237332 -0.014417578 0.12017316, 0.52502906 -0.014274646 0.12058392, 0.52191651 -0.015455235 0.12370574, 0.5199306 -0.015558589 0.12399995, 0.52384573 -0.014975552 0.12204906, 0.52558762 -0.014566232 0.12217346, 0.52191091 -0.015400279 0.1250917, 0.51993054 -0.015366558 0.12595078, 0.52388293 -0.015159655 0.12370574, 0.52581018 -0.014670197 0.12370574, 0.52573425 -0.014635671 0.12509155, 0.52188689 -0.015158299 0.12644291, 0.5199306 -0.014797602 0.12782675, 0.52387196 -0.015105475 0.1250917, 0.52540958 -0.014478419 0.12644291, 0.52184629 -0.014752481 0.1277031, 0.52382392 -0.014867116 0.12644291, 0.52489465 -0.014198218 0.12770325, 0.52179122 -0.014199052 0.12887233, 0.51993054 -0.013873626 0.12955558, 0.52374309 -0.014467288 0.1277031, 0.52424794 -0.013787258 0.12887219, 0.52169818 -0.013269264 0.13025996, 0.51993054 -0.01262999 0.13107127, 0.52329147 -0.013037134 0.13025996, 0.52228504 -0.012004782 0.13150102, 0.52363324 -0.013921995 0.12887233, 0.52162606 -0.012545694 0.13107127, 0.52147561 -0.011037845 0.13231465, 0.52139014 -0.010761101 0.13249761, 0.51993054 -0.011114705 0.13231486, 0.52068073 -0.0093594827 0.13324159, 0.51993054 -0.009385813 0.13323909, 0.52019864 -0.0078592487 0.13373166, 0.51993054 -0.00751004 0.13380831, 0.51999801 -0.006718982 0.13393292, 0.53151309 0.054581072 -0.11412236, 0.53313798 0.054983404 -0.11452463, 0.5347333 0.055684146 -0.11522532, 0.5360921 0.056579079 -0.1161201, 0.53732729 0.057725873 -0.11726689, 0.53838283 0.059112009 -0.11865285, 0.53920114 0.060707118 -0.1202476, 0.53975695 0.062601924 -0.12214229, 0.41800031 0.015467819 -0.12683198, 0.41800043 0.01618908 -0.12710544, 0.41800031 0.023455273 -0.1339981, 0.41800067 -0.033678893 -0.12218347, 0.41800067 -0.035545785 -0.11500138, 0.41800073 -0.033167455 -0.12160605, 0.41800019 0.022588309 -0.12218037, 0.4180004 0.022076558 -0.12160304, 0.41800022 0.024454217 -0.11499786, 0.41800058 -0.0340374 -0.12286657, 0.41800025 0.02144165 -0.12116477, 0.41800073 -0.03422204 -0.12361556, 0.41800049 -0.013546143 -0.10800001, 0.41800037 0.0024539344 -0.10799918, 0.41800031 0.022946682 -0.12286347, 0.41800043 0.02072027 -0.12089124, 0.41800061 -0.015545849 -0.11400029, 0.41800055 -0.015546028 -0.11000016, 0.41800028 0.023131367 -0.12361237, 0.41800028 0.019954573 -0.12079817, 0.41800061 -0.025411818 -0.12218314, 0.41800058 -0.025923405 -0.1216056, 0.41800061 -0.026558343 -0.12116748, 0.41800064 -0.03454471 -0.1340014, 0.41800064 -0.031045128 -0.12720108, 0.41800061 -0.028045122 -0.12720093, 0.41800061 -0.027279351 -0.12710795, 0.41800061 -0.02655803 -0.12683424, 0.41800031 0.016954582 -0.12079838, 0.41800067 -0.025053237 -0.12286609, 0.41800061 -0.031810883 -0.1271081, 0.41800061 -0.027279664 -0.12089387, 0.41800067 -0.035544742 -0.13300133, 0.41800076 -0.034221936 -0.12438709, 0.41800067 -0.034037311 -0.1251362, 0.41800031 0.016188797 -0.12089151, 0.41800058 -0.033678759 -0.12581918, 0.41800064 -0.033167113 -0.12639648, 0.41800061 -0.032532189 -0.1268346, 0.41800061 -0.024868671 -0.123615, 0.41800061 -0.034545843 -0.1140013, 0.41800055 -0.028045464 -0.12080115, 0.41800061 -0.024868671 -0.12438652, 0.41800067 -0.025053222 -0.12513554, 0.41800046 0.013962682 -0.12513337, 0.41800061 -0.025411624 -0.12581867, 0.41800031 0.014321264 -0.12581632, 0.41800019 0.024455275 -0.13299799, 0.41800031 0.020720731 -0.12710509, 0.41800043 0.021441992 -0.12683159, 0.41800016 0.02207699 -0.12639341, 0.41800028 0.022588398 -0.12581593, 0.41800028 0.02294689 -0.12513289, 0.41800028 0.023131456 -0.12438381, 0.41800061 -0.0310455 -0.12080115, 0.41800073 -0.025923166 -0.12639603, 0.41800046 0.014832836 -0.1263938, 0.41800031 0.0044539683 -0.10999927, 0.41800031 0.015467491 -0.12116501, 0.41800031 0.014832553 -0.12160328, 0.41800034 0.01432116 -0.12218067, 0.41800064 -0.031811286 -0.12089422, 0.41800031 0.013962682 -0.12286386, 0.41800031 0.013778027 -0.12361282, 0.41800061 -0.032532576 -0.12116772, 0.41800034 0.016954865 -0.12719846, 0.41800043 0.019954886 -0.12719828, 0.41800034 0.013778087 -0.12438425, 0.42100063 -0.031045441 -0.12080115, 0.42100069 -0.028045435 -0.12080094, 0.42100063 -0.028045122 -0.12720093, 0.42100069 -0.027279291 -0.12710795, 0.42100063 -0.026558015 -0.12683424, 0.42100054 -0.025923032 -0.12639603, 0.4210006 -0.025411669 -0.12581867, 0.4210006 -0.025053103 -0.12513539, 0.42100057 -0.024868522 -0.12438649, 0.42100051 -0.024868611 -0.12361521, 0.42100054 -0.025053222 -0.12286609, 0.42100057 -0.025411729 -0.12218314, 0.4210006 -0.02592339 -0.12160581, 0.42100063 -0.026558358 -0.12116748, 0.42100057 -0.027279619 -0.12089393, 0.42100063 -0.031045098 -0.12720114, 0.42100057 -0.031811226 -0.12089422, 0.42100057 -0.032532517 -0.12116772, 0.42100063 -0.033167381 -0.12160596, 0.42100069 -0.033678908 -0.12218338, 0.4210006 -0.0340374 -0.12286648, 0.4210006 -0.034221966 -0.12361544, 0.42100063 -0.034221891 -0.12438709, 0.42100063 -0.034037281 -0.12513599, 0.42100075 -0.033678744 -0.12581894, 0.42100072 -0.033167142 -0.12639648, 0.42100069 -0.032532249 -0.1268346, 0.42100063 -0.031810928 -0.12710816, 0.42100069 -0.03454474 -0.13400126, 0.4210006 -0.035544682 -0.13300145, 0.42100063 -0.0355458 -0.11500132, 0.42100063 -0.034545768 -0.1140013, 0.42100039 0.016954925 -0.12719831, 0.42100027 0.019954976 -0.12719828, 0.42100033 0.016954567 -0.12079838, 0.42100045 0.016188677 -0.12089151, 0.42100027 0.015467416 -0.12116501, 0.42100033 0.014832553 -0.12160334, 0.4210003 0.014321025 -0.12218076, 0.42100045 0.013962608 -0.12286386, 0.42100033 0.013777997 -0.12361282, 0.42100033 0.013778087 -0.12438446, 0.42100027 0.013962846 -0.12513337, 0.42100033 0.014321279 -0.12581632, 0.42100033 0.01483294 -0.12639365, 0.42100033 0.015467789 -0.12683183, 0.42100033 0.016189124 -0.12710541, 0.42100033 0.019954514 -0.12079817, 0.42100027 0.020720776 -0.12710536, 0.42100027 0.021442097 -0.12683159, 0.4210003 0.022076901 -0.12639326, 0.4210003 0.022588398 -0.12581587, 0.42100024 0.02294692 -0.12513283, 0.42100027 0.023131501 -0.12438381, 0.42100033 0.023131367 -0.12361237, 0.4210003 0.022946682 -0.12286347, 0.4210003 0.02258819 -0.12218028, 0.42100027 0.022076663 -0.12160295, 0.42100027 0.021441709 -0.12116471, 0.4210003 0.020720374 -0.12089124, 0.42100021 0.023455363 -0.1339981, 0.42100027 0.024455216 -0.13299799, 0.42100024 0.024454247 -0.11499792, 0.42100051 -0.015545834 -0.11400029, 0.42100033 0.004454013 -0.10999903, 0.42100039 9.9949539e-06 -0.11568472, 0.42100039 0.0015254132 -0.11692831, 0.42100042 0.0027691089 -0.11844358, 0.42100039 0.0024538748 -0.10799921, 0.42100057 -0.0017190464 -0.11476076, 0.42100042 0.0036933087 -0.1201722, 0.42100039 -0.0035948195 -0.11419177, 0.42100039 0.0042624883 -0.12204808, 0.42100042 0.0044547431 -0.12399921, 0.42100057 -0.013546158 -0.10800025, 0.42100042 0.0042626821 -0.12595004, 0.42100039 0.0036937706 -0.12782592, 0.42100057 -0.015546102 -0.11000022, 0.42100042 0.0027697943 -0.12955511, 0.42100042 0.001526203 -0.13107038, 0.42100045 1.0903925e-05 -0.13231421, 0.42100039 -0.0017178245 -0.13323832, 0.42100042 -0.0035937615 -0.1338073, 0.49772924 0.070015356 -0.20413935, 0.50774837 0.057702925 -0.20992449, 0.49692896 0.068286568 -0.20367745, 0.50637543 0.057148185 -0.20913199, 0.51213068 0.070016071 -0.21245414, 0.5110538 0.071531415 -0.21183208, 0.50493014 0.056960072 -0.20829728, 0.50974143 0.072774976 -0.21107441, 0.49643609 0.066410646 -0.20339304, 0.51293117 0.068287194 -0.21291625, 0.50824416 0.073698983 -0.21021, 0.51342398 0.066411227 -0.21320084, 0.50661945 0.074267969 -0.20927203, 0.49859762 0.062790975 -0.20464113, 0.50492996 0.074460074 -0.20829645, 0.50324041 0.074267879 -0.20732102, 0.50348485 0.057148095 -0.20746291, 0.49907812 0.061205667 -0.20491859, 0.51126236 0.062791407 -0.21195319, 0.50211191 0.057702761 -0.20667028, 0.49985182 0.059783738 -0.20536536, 0.50161582 0.073698625 -0.20638308, 0.51078206 0.061206158 -0.21167594, 0.5008803 0.05859619 -0.20595929, 0.50011861 0.072774559 -0.20551875, 0.51000816 0.05978417 -0.21122912, 0.49880612 0.071531042 -0.20476112, 0.5089798 0.058596458 -0.21063539, 0.51473743 0.066408992 -0.17169431, 0.51523036 0.068284929 -0.17197862, 0.51603061 0.070013821 -0.17244062, 0.51710755 0.071529269 -0.17306232, 0.5184198 0.07277298 -0.17382005, 0.51991707 0.073697031 -0.17468444, 0.52154166 0.074266225 -0.17562214, 0.52323127 0.07445842 -0.17659774, 0.52492076 0.074266374 -0.17757323, 0.52654541 0.073697269 -0.1785112, 0.52804267 0.072773278 -0.17937583, 0.52935511 0.071529716 -0.18013337, 0.53043205 0.070014387 -0.18075529, 0.53123242 0.068285644 -0.18121731, 0.53172523 0.066409677 -0.18150213, 0.53192276 0.073696554 -0.1655291, 0.52957296 0.074265808 -0.16691059, 0.53011078 0.074265659 -0.16504347, 0.53136557 0.073696703 -0.16746333, 0.53472787 0.070013881 -0.17154276, 0.53305596 0.071529299 -0.17244831, 0.53355938 0.07152918 -0.17111745, 0.53421372 0.070013881 -0.17290273, 0.53057832 0.074265599 -0.163158, 0.52822644 0.074457735 -0.16453868, 0.52867639 0.074457645 -0.16272372, 0.53507394 0.068285108 -0.17324033, 0.53246975 0.070014149 -0.1768997, 0.53330225 0.068285406 -0.17730069, 0.52744246 0.074265242 -0.15875906, 0.52724922 0.074265301 -0.15994141, 0.52540171 0.073696196 -0.15961567, 0.52558738 0.073696136 -0.15847942, 0.53446561 0.07152912 -0.16841984, 0.53213519 0.072772801 -0.1705991, 0.53301758 0.072772652 -0.16797331, 0.52420527 0.072771877 -0.15547135, 0.52237946 0.071528494 -0.15799618, 0.5226956 0.071528316 -0.15533942, 0.52387786 0.072772086 -0.15822193, 0.52917039 0.074457586 -0.16028014, 0.52677447 0.07426554 -0.16228956, 0.53359276 0.072772533 -0.16597661, 0.53559619 0.068285108 -0.171859, 0.53240728 0.073696464 -0.16357541, 0.5356037 0.0664092 -0.17344847, 0.53381497 0.066409498 -0.17754784, 0.5293715 0.074457437 -0.15904981, 0.53565389 0.070013762 -0.16878641, 0.52592736 0.073696017 -0.15562212, 0.53109163 0.07426545 -0.16061887, 0.53505653 0.071529001 -0.16636887, 0.53613096 0.066409171 -0.17205358, 0.53409284 0.072772473 -0.16395995, 0.5313006 0.074265301 -0.15934068, 0.53653687 0.068284959 -0.16905904, 0.52779621 0.074265182 -0.15578547, 0.53293902 0.073696345 -0.16094467, 0.53625768 0.070013642 -0.16669083, 0.5355702 0.071528822 -0.1642974, 0.53315574 0.073696256 -0.15962026, 0.53708071 0.066408992 -0.16922688, 0.5297398 0.074457347 -0.15595555, 0.51614195 0.066408932 -0.16903678, 0.5346418 0.072772235 -0.16124496, 0.53715032 0.06828481 -0.16693026, 0.53678268 0.070013434 -0.16457412, 0.51665455 0.06828481 -0.16928357, 0.53486526 0.072772235 -0.15987793, 0.53168321 0.074265182 -0.15612558, 0.51748711 0.070013613 -0.16968456, 0.51734382 0.066408694 -0.16628191, 0.53613406 0.071528643 -0.16150817, 0.53770012 0.066408873 -0.16707763, 0.51860768 0.071529031 -0.17022407, 0.53768355 0.06828469 -0.16477987, 0.51769829 0.066408634 -0.16534472, 0.53636366 0.071528643 -0.16010386, 0.53355199 0.073696077 -0.15628913, 0.5178737 0.068284571 -0.16648984, 0.5373587 0.070013344 -0.16172406, 0.5199731 0.072772801 -0.17088139, 0.53823841 0.066408724 -0.16490668, 0.53759342 0.070013285 -0.16028923, 0.51823306 0.068284571 -0.16553918, 0.5187338 0.070013493 -0.1668272, 0.53527445 0.072772026 -0.15643978, 0.53826886 0.068284512 -0.16188487, 0.51833653 0.066408575 -0.16344506, 0.5385071 0.068284422 -0.16042721, 0.52153069 0.073696911 -0.1716316, 0.53678399 0.071528345 -0.15657201, 0.53882933 0.066408515 -0.16198379, 0.51910156 0.070013404 -0.16585505, 0.53906983 0.066408515 -0.16051212, 0.51989132 0.071528882 -0.16728163, 0.53802282 0.070013016 -0.15668049, 0.53894341 0.068284184 -0.15676096, 0.51888031 0.068284482 -0.16361269, 0.53951031 0.066408306 -0.15681079, 0.52322072 0.074265897 -0.17244551, 0.51875269 0.066408515 -0.1620006, 0.53944284 0.067360044 -0.15419653, 0.53869325 0.069171339 -0.15416372, 0.53916883 0.068283886 -0.15159789, 0.53783792 0.070414245 -0.15539354, 0.52026993 0.071528912 -0.16628054, 0.52130198 0.072772652 -0.16783512, 0.53760523 0.070801198 -0.15411597, 0.53794819 0.070414215 -0.15286389, 0.53700107 0.071528196 -0.15159789, 0.53824478 0.070012778 -0.15159798, 0.5397169 0.065924525 -0.15514266, 0.53983516 0.065437406 -0.15396428, 0.51976341 0.070013314 -0.16388491, 0.53980762 0.065924436 -0.15290463, 0.53973782 0.066408038 -0.15159798, 0.53652412 0.071866751 -0.15530732, 0.5249784 0.074458301 -0.17329207, 0.51930231 0.068284482 -0.16214782, 0.53622037 0.072187304 -0.15405551, 0.53663218 0.071866632 -0.15283516, 0.52169394 0.072772652 -0.16679865, 0.53548568 0.072771847 -0.15159786, 0.53495288 0.073034525 -0.15520418, 0.51911455 0.066408426 -0.16054186, 0.52291149 0.073696703 -0.1684666, 0.53459197 0.07327646 -0.15398449, 0.5350579 0.073034346 -0.15280059, 0.52095169 0.071528733 -0.16425145, 0.53375679 0.073695779 -0.15159765, 0.53318459 0.073872685 -0.15508834, 0.52673632 0.074266106 -0.17413837, 0.5327825 0.074026674 -0.15390539, 0.53328627 0.073872507 -0.15276209, 0.53188097 0.074264914 -0.15159765, 0.53128713 0.074349016 -0.15496397, 0.52019483 0.070013225 -0.16238683, 0.52331853 0.073696673 -0.16738987, 0.53086168 0.074408948 -0.1538215, 0.531385 0.074348897 -0.15272057, 0.52933341 0.074445277 -0.15483582, 0.51966912 0.068284333 -0.16066822, 0.52942753 0.074445069 -0.15267769, 0.52465761 0.074265957 -0.16915202, 0.52239978 0.072772443 -0.16469809, 0.52759975 0.07421425 -0.15524483, 0.52712291 0.074072808 -0.15400216, 0.52842629 0.07369718 -0.17495242, 0.52828056 0.074323535 -0.15300453, 0.52771336 0.074214071 -0.153162, 0.52773619 0.074214041 -0.15211919, 0.51951164 0.066408277 -0.15857759, 0.5213961 0.071528614 -0.16270861, 0.52561933 0.073531687 -0.15475917, 0.52571368 0.073531628 -0.15276352, 0.52413517 0.072656512 -0.15409198, 0.52508157 0.074265718 -0.16803148, 0.52057022 0.070013195 -0.16087386, 0.52370387 0.072306901 -0.15324333, 0.52420181 0.072656363 -0.15216136, 0.52647364 0.074458122 -0.1698648, 0.52250177 0.071243107 -0.15425864, 0.52145666 0.070012838 -0.15523103, 0.52053612 0.068284005 -0.15515056, 0.51967317 0.066408157 -0.15758851, 0.52257746 0.071243107 -0.15239909, 0.52405179 0.073696554 -0.16520751, 0.52998388 0.072773188 -0.17570257, 0.52007204 0.068284124 -0.15867606, 0.52285999 0.072772294 -0.16310081, 0.52691478 0.074458033 -0.16869879, 0.5217827 0.071528673 -0.1611504, 0.52828974 0.074265957 -0.17057753, 0.52023596 0.068284124 -0.15767318, 0.5258444 0.074265569 -0.16576037, 0.53134936 0.071529508 -0.17636004, 0.52098209 0.070013046 -0.15883654, 0.52452981 0.073696494 -0.1635482, 0.52874792 0.074265897 -0.16936609, 0.52326006 0.072772205 -0.16148764, 0.53003603 0.073696971 -0.17126289, 0.52114969 0.070012987 -0.15781075, 0.52770859 0.074457943 -0.16633549, 0.51996928 0.066408098 -0.15510109, 0.52220684 0.071528465 -0.15905231, 0.5263418 0.074265599 -0.16403377, 0.53051066 0.073696792 -0.17000756, 0.5249455 0.073696375 -0.161872, 0.53164536 0.072772801 -0.17189458, 0.5236991 0.072772056 -0.1593155, 0.53975683 0.062588006 0.1258578, 0.53920114 0.060693052 0.12775248, 0.53838277 0.059097942 0.12934732, 0.5318808 0.074247897 0.15160751, 0.53732717 0.057712045 0.13073328, 0.53609198 0.056565251 0.13187993, 0.53473341 0.055670258 0.13277471, 0.53313786 0.054969605 0.13347548, 0.53151327 0.054567035 0.13387793, 0.53375679 0.073678792 0.15160766, 0.53548568 0.072754711 0.15160748, 0.53700107 0.07151106 0.15160748, 0.53824466 0.069995642 0.15160748, 0.53916889 0.068266869 0.15160722, 0.53973788 0.066390842 0.15160722, 0.52256244 0.059781518 -0.16302198, 0.52295977 0.059781309 -0.16141969, 0.52370948 0.058593865 -0.16332933, 0.53102195 0.057145532 -0.15929943, 0.53140241 0.057145294 -0.15610197, 0.53258944 0.057700243 -0.15953562, 0.53298163 0.057700004 -0.15624002, 0.52116352 0.062788755 -0.16264674, 0.52072173 0.062788785 -0.16418093, 0.52125162 0.061203595 -0.1643444, 0.52169937 0.061203476 -0.16279048, 0.52752697 0.057145473 -0.15999138, 0.52615386 0.057700094 -0.15856579, 0.52772141 0.057145473 -0.15880206, 0.52596575 0.057700213 -0.15971607, 0.52411753 0.058593806 -0.16168401, 0.5245654 0.058593687 -0.15946913, 0.52550387 0.057700362 -0.16200048, 0.52208859 0.061203357 -0.16122097, 0.52937174 0.05695739 -0.15905079, 0.52973992 0.056957331 -0.15595645, 0.52474773 0.058593597 -0.15835375, 0.5233959 0.059781279 -0.15926278, 0.52154785 0.062788606 -0.16109732, 0.5280773 0.057145383 -0.15581113, 0.52357334 0.05978119 -0.15817675, 0.52251583 0.061203267 -0.15910748, 0.52649808 0.057700034 -0.15567282, 0.52268994 0.061203208 -0.15804338, 0.52196962 0.062788516 -0.15901107, 0.52508152 0.058593448 -0.15554893, 0.5221414 0.062788486 -0.15796077, 0.52389842 0.059781041 -0.15544534, 0.52300823 0.061203059 -0.15536729, 0.52245563 0.062788248 -0.15531889, 0.53702396 0.062788457 -0.15659338, 0.53722352 0.06320101 -0.15499511, 0.53695476 0.061980125 -0.15408817, 0.53733808 0.063617557 -0.15386584, 0.53558117 0.05978116 -0.15646747, 0.53637308 0.060829338 -0.15529791, 0.53647137 0.061203178 -0.15654513, 0.53731042 0.063200831 -0.15285042, 0.53622687 0.060466971 -0.15405643, 0.53648072 0.060829308 -0.15283239, 0.53689837 0.061980154 -0.1551539, 0.53699559 0.061980035 -0.15284351, 0.52908331 0.061204489 -0.17997709, 0.53156632 0.062789589 -0.17646533, 0.52956361 0.062789738 -0.18025431, 0.5343982 0.058593627 -0.1563639, 0.53540337 0.059459623 -0.15523434, 0.53518069 0.059153881 -0.15401095, 0.53106672 0.061204251 -0.1762245, 0.53550917 0.059459534 -0.15281132, 0.53026164 0.059782233 -0.17583695, 0.53415376 0.058340605 -0.15515283, 0.52830952 0.059782442 -0.17953041, 0.53328019 0.062789351 -0.17253688, 0.53386897 0.058106747 -0.15395358, 0.53425717 0.058340486 -0.15278399, 0.53268713 0.057528105 -0.15505648, 0.52728105 0.058594819 -0.17893666, 0.52919161 0.05859467 -0.17532188, 0.53378564 0.062789202 -0.17120028, 0.53276396 0.061204042 -0.17233419, 0.53235722 0.05737802 -0.15388766, 0.53278762 0.057528045 -0.15275207, 0.53107667 0.057063159 -0.15495098, 0.52467674 0.057146516 -0.17743319, 0.52791035 0.057701137 -0.1747047, 0.52604944 0.057701316 -0.1782257, 0.5311743 0.05706301 -0.1527169, 0.52957481 0.056960072 -0.15539685, 0.53326458 0.061204012 -0.17101061, 0.52916598 0.056989904 -0.15410724, 0.53193218 0.059781965 -0.17200795, 0.53018928 0.056962308 -0.15306106, 0.52969307 0.056960043 -0.15322787, 0.52648216 0.057146307 -0.17401701, 0.52971679 0.056960043 -0.15214181, 0.5346958 0.062789172 -0.16849139, 0.52780676 0.057231244 -0.15491155, 0.53242475 0.059781935 -0.17070511, 0.5279057 0.057231124 -0.15282005, 0.53082681 0.058594372 -0.17157412, 0.52637672 0.057777878 -0.15523711, 0.52688742 0.057564434 -0.15444791, 0.52497864 0.056958195 -0.17329291, 0.52323133 0.056958344 -0.1765987, 0.52644497 0.057777788 -0.154223, 0.5341658 0.061203834 -0.16832796, 0.52604675 0.058021154 -0.15333214, 0.52651525 0.057777699 -0.15219167, 0.53130901 0.058594283 -0.17029896, 0.52490598 0.058810588 -0.15440965, 0.52950293 0.057700869 -0.1710546, 0.52498579 0.058810588 -0.15244523, 0.53528911 0.062789023 -0.16643178, 0.52383894 0.059914585 -0.15489092, 0.52041316 0.057701077 -0.17497152, 0.52347493 0.057146188 -0.17256883, 0.52178603 0.057146456 -0.17576423, 0.5236159 0.060325976 -0.15378001, 0.53331208 0.059781786 -0.16806471, 0.52426481 0.059523698 -0.15279892, 0.52394074 0.059914645 -0.15297258, 0.52396023 0.059914585 -0.15201211, 0.52997255 0.05770072 -0.16981259, 0.52802724 0.057146218 -0.17047551, 0.53475338 0.061203774 -0.16628838, 0.52204669 0.057700839 -0.17188099, 0.53580511 0.062788934 -0.16435152, 0.53217709 0.058594223 -0.16771463, 0.52848309 0.057146039 -0.16927052, 0.52647382 0.056957956 -0.16986573, 0.53389037 0.059781667 -0.1660572, 0.51918167 0.058594462 -0.17426053, 0.52076536 0.058594283 -0.17126396, 0.53526431 0.061203685 -0.16422814, 0.53081834 0.05770066 -0.1672956, 0.52691489 0.056957927 -0.16869983, 0.52492023 0.057146039 -0.16925597, 0.53274328 0.058594044 -0.16574988, 0.51815325 0.059782024 -0.17366666, 0.51969546 0.059781875 -0.17074847, 0.53637129 0.062788725 -0.16155049, 0.53439325 0.059781518 -0.16402936, 0.52930337 0.057145949 -0.16682839, 0.52534646 0.05714589 -0.16812897, 0.52344465 0.057700749 -0.16867685, 0.53136963 0.057700451 -0.16538191, 0.51689905 0.062789202 -0.17294243, 0.51889044 0.061203834 -0.17036083, 0.51737946 0.061203983 -0.17321983, 0.53660178 0.062788755 -0.16014031, 0.53582507 0.061203416 -0.16145426, 0.53323555 0.058594014 -0.16376525, 0.52770871 0.056957807 -0.16633654, 0.52385688 0.05770063 -0.16758662, 0.52212095 0.058594134 -0.16815725, 0.52983844 0.05714589 -0.16497162, 0.51839072 0.062789083 -0.17012003, 0.53605348 0.061203416 -0.16005769, 0.53494501 0.059781488 -0.16129926, 0.53184897 0.057700392 -0.16344878, 0.52611399 0.05714583 -0.16584456, 0.5225206 0.058594104 -0.16710025, 0.52101535 0.059781726 -0.16772342, 0.52822655 0.056957688 -0.16453955, 0.53516978 0.059781428 -0.15992457, 0.53377569 0.058593865 -0.16109306, 0.53030366 0.057145681 -0.16309613, 0.52459919 0.057700481 -0.16537714, 0.52140462 0.059781697 -0.16669407, 0.52018362 0.061203655 -0.16739678, 0.52661437 0.057145741 -0.16410768, 0.53399557 0.058593776 -0.15974775, 0.53237522 0.057700273 -0.16084608, 0.52867651 0.056957599 -0.1627247, 0.52324039 0.058593985 -0.164958, 0.52056497 0.061203655 -0.16638842, 0.51966721 0.062788963 -0.16719413, 0.52508312 0.057700302 -0.16369745, 0.53081399 0.057145592 -0.16057095, 0.52704948 0.057145741 -0.16235334, 0.52210557 0.059781577 -0.16460794, 0.52004379 0.062788844 -0.16619852, 0.52917051 0.05695748 -0.160281, 0.41800073 -0.027293611 0.12710643, 0.41800061 -0.028059367 0.12719899, 0.41800061 -0.034559775 0.13399896, 0.41800061 -0.025067288 0.12513411, 0.41800049 -0.015558694 0.11399993, 0.41800049 -0.024882514 0.12438524, 0.41800067 -0.026572261 0.12683281, 0.41800025 0.022574481 0.12218416, 0.4180001 0.024441373 0.11500219, 0.41800025 0.022062909 0.12160683, 0.41800058 -0.033692647 0.12218085, 0.41800064 -0.033181179 0.12160364, 0.41800061 -0.035558674 0.11499882, 0.41800025 0.022932854 0.12286735, 0.41800058 -0.032546211 0.12116531, 0.41800019 0.023117553 0.12361628, 0.41800073 -0.034051213 0.12286416, 0.41800064 -0.03182498 0.12089199, 0.41800079 -0.034558687 0.11399886, 0.41800034 0.0044416003 0.11000097, 0.41800049 0.0024417602 0.10800099, 0.41800067 -0.034235869 0.12361303, 0.41800046 -0.013558257 0.10800001, 0.41800061 -0.031058971 0.12079921, 0.41800043 0.014307346 0.12218362, 0.41800028 0.014818888 0.12160626, 0.41800037 0.023440223 0.13400191, 0.41800019 0.020706441 0.12710917, 0.41800025 0.019940685 0.12720177, 0.41800046 0.015453797 0.12116817, 0.41800043 0.016940575 0.12720171, 0.41800061 -0.02805898 0.1207993, 0.41800034 0.01617473 0.12710893, 0.41800034 0.015453499 0.12683508, 0.41800016 0.013948899 0.12286678, 0.41800025 0.024440389 0.13300222, 0.41800025 0.021427747 0.12683547, 0.41800025 0.022062611 0.12639725, 0.41800019 0.022574168 0.12581956, 0.41800025 0.022932734 0.12513661, 0.41800019 0.023117553 0.12438777, 0.41800064 -0.027293358 0.1208922, 0.4180004 0.016175147 0.12089455, 0.41800019 0.013764169 0.12361562, 0.41800037 0.016941052 0.12080184, 0.41800025 0.013764124 0.12438726, 0.41800037 0.013948645 0.12513623, 0.41800043 0.014307108 0.12581918, 0.41800058 -0.025425795 0.12581715, 0.41800055 -0.025937352 0.12639463, 0.41800064 -0.035559658 0.13299865, 0.41800067 -0.034235854 0.12438476, 0.41800061 -0.034051333 0.12513363, 0.41800061 -0.0336929 0.12581655, 0.41800061 -0.033181343 0.12639418, 0.41800061 -0.032546435 0.12683246, 0.41800061 -0.031825174 0.12710607, 0.41800025 0.019941103 0.12080202, 0.41800037 0.01481868 0.12639689, 0.41800025 0.020706754 0.12089482, 0.41800049 -0.015558396 0.10999987, 0.41800055 -0.025425542 0.12218136, 0.41800055 -0.025067065 0.12286454, 0.41800061 -0.025937129 0.12160403, 0.41800073 -0.026571993 0.12116578, 0.41800049 -0.024882514 0.1236136, 0.41800019 0.021428045 0.12116852, 0.41800061 -0.031059418 0.12719899, 0.42100051 -0.02805889 0.1207993, 0.42100072 -0.031059001 0.12079921, 0.42100051 -0.027293209 0.1208922, 0.42100057 -0.026571963 0.1211659, 0.42100057 -0.025937114 0.12160403, 0.42100051 -0.025425557 0.12218153, 0.42100057 -0.025067065 0.12286454, 0.4210006 -0.024882499 0.1236136, 0.42100051 -0.024882499 0.12438509, 0.42100063 -0.025067288 0.1251342, 0.42100054 -0.025425825 0.12581694, 0.42100063 -0.025937457 0.12639463, 0.42100057 -0.026572261 0.1268326, 0.42100054 -0.027293522 0.12710631, 0.42100051 -0.028059307 0.12719914, 0.42100069 -0.031059463 0.12719899, 0.42100063 -0.031825263 0.12710607, 0.42100069 -0.032546524 0.1268326, 0.4210006 -0.033181313 0.12639415, 0.42100066 -0.033692975 0.1258167, 0.42100063 -0.034051392 0.12513363, 0.42100069 -0.034235928 0.12438464, 0.4210006 -0.034235794 0.12361303, 0.4210006 -0.034051169 0.12286416, 0.4210006 -0.033692721 0.12218085, 0.42100057 -0.033181075 0.12160364, 0.42100063 -0.032546166 0.12116548, 0.42100063 -0.031824905 0.12089193, 0.42100063 -0.035559688 0.13299865, 0.42100063 -0.034559909 0.13399881, 0.42100057 -0.034558672 0.11399886, 0.42100069 -0.035558674 0.11499873, 0.42100024 0.019940596 0.12720191, 0.42100027 0.016940694 0.12720171, 0.4210003 0.016174775 0.12710878, 0.42100027 0.015453573 0.12683499, 0.42100039 0.014818635 0.12639701, 0.42100027 0.014307182 0.12581933, 0.42100027 0.013948631 0.12513638, 0.4210003 0.013764139 0.12438732, 0.4210003 0.013764139 0.12361589, 0.4210003 0.01394878 0.12286666, 0.4210003 0.014307361 0.12218356, 0.42100027 0.014818933 0.12160626, 0.42100024 0.015453842 0.12116826, 0.42100027 0.016175102 0.12089461, 0.42100027 0.016941082 0.12080184, 0.42100027 0.019940939 0.12080184, 0.42100033 0.02070668 0.12089482, 0.42100027 0.021428015 0.12116852, 0.42100027 0.022062879 0.12160668, 0.42100021 0.022574466 0.12218416, 0.42100027 0.022932898 0.12286717, 0.42100024 0.023117524 0.12361622, 0.42100024 0.023117524 0.12438765, 0.42100021 0.022932779 0.12513682, 0.42100021 0.022574272 0.12581977, 0.42100021 0.022062715 0.12639725, 0.42100021 0.021427732 0.12683538, 0.42100021 0.020706516 0.12710902, 0.42100024 0.023440283 0.13400206, 0.42100033 0.02444033 0.13300222, 0.42100027 0.024441253 0.11500201, 0.42100051 -0.015558679 0.11399993, 0.42100045 -0.012629945 0.11692896, 0.42100045 -0.013873626 0.11844423, 0.42100057 -0.01555847 0.10999998, 0.42100045 -0.011114437 0.11568555, 0.42100051 -0.014797766 0.12017316, 0.42100048 -0.013558257 0.10800001, 0.42100045 -0.0093854852 0.1147612, 0.42100045 -0.015366916 0.12204888, 0.42100045 -0.0075095482 0.11419246, 0.42100054 -0.01555923 0.12399983, 0.42100039 0.0024417751 0.10800079, 0.42100051 -0.015367169 0.12595066, 0.42100051 -0.014798257 0.12782678, 0.42100033 0.0044416152 0.11000106, 0.4210006 -0.013874266 0.12955567, 0.42100051 -0.012630705 0.13107118, 0.42100045 -0.011115361 0.13231477, 0.42100045 -0.0093864985 0.13323909, 0.42100045 -0.0075107254 0.13380811, 0.51126236 0.066105366 0.21196181, 0.51078194 0.06769067 0.21168464, 0.51000816 0.069112703 0.21123785, 0.50897968 0.070300221 0.21064413, 0.50774819 0.071193799 0.20993313, 0.50637525 0.071748614 0.20914063, 0.50492996 0.071936697 0.20830593, 0.50348479 0.071748585 0.20747164, 0.50211185 0.071193978 0.20667908, 0.50088018 0.070300445 0.20596784, 0.49985173 0.069113106 0.205374, 0.49907798 0.067691028 0.2049273, 0.49859762 0.066105723 0.20464993, 0.52256244 0.059763249 0.16302994, 0.52210552 0.05976307 0.16461602, 0.52370936 0.058575507 0.16333738, 0.52324021 0.058575507 0.16496602, 0.52802718 0.057127025 0.17048329, 0.5267579 0.057126787 0.17344275, 0.52950299 0.057681676 0.17106244, 0.52819455 0.057681467 0.17411262, 0.52116352 0.062770545 0.16265526, 0.52154773 0.062770516 0.16110587, 0.52208859 0.061185237 0.16122913, 0.52169919 0.061185237 0.16279867, 0.5253464 0.057127055 0.16813684, 0.52344459 0.057681736 0.16868457, 0.52492017 0.057126995 0.1692639, 0.52385676 0.057681676 0.16759464, 0.52252048 0.058575328 0.16710824, 0.52459919 0.057681914 0.16538519, 0.52125168 0.061185028 0.16435289, 0.52524537 0.056938704 0.1727373, 0.52647376 0.056938883 0.16987365, 0.52212083 0.058575179 0.16816506, 0.52140456 0.05976307 0.16670224, 0.52072161 0.062770247 0.16418925, 0.5237329 0.057126757 0.17203218, 0.52101523 0.059762891 0.16773137, 0.52056473 0.061184999 0.16639659, 0.52229613 0.057681706 0.17136234, 0.52018362 0.061184939 0.1674051, 0.52004361 0.062770277 0.16620699, 0.52100742 0.058575179 0.17076129, 0.51966709 0.062770218 0.16720268, 0.51993108 0.059762742 0.17025948, 0.51912135 0.06118476 0.16988203, 0.51861846 0.062770009 0.16964766, 0.53187227 0.06276989 0.17582804, 0.53124601 0.063182294 0.17731196, 0.53055972 0.061961409 0.17796293, 0.53078061 0.063598752 0.17834726, 0.53055972 0.059762593 0.17521557, 0.53066081 0.060810681 0.17662457, 0.53136951 0.061184522 0.17559355, 0.53024882 0.063182175 0.17921272, 0.52991354 0.060448196 0.17762655, 0.52952141 0.060810622 0.17881361, 0.53104371 0.061961468 0.17701164, 0.52997279 0.061961379 0.17906138, 0.5294835 0.058574911 0.17471388, 0.52978915 0.059441026 0.17619473, 0.53708178 0.062770903 0.15588978, 0.53652841 0.061185624 0.15584821, 0.52898473 0.059135195 0.17714289, 0.5286693 0.059440847 0.17834595, 0.53563762 0.059763607 0.15578136, 0.52866608 0.058322009 0.17564061, 0.53660196 0.062770635 0.1601488, 0.52781987 0.05808812 0.17653659, 0.5275715 0.0583218 0.17774346, 0.53445333 0.058576014 0.15569255, 0.5273478 0.057509627 0.17499045, 0.53637129 0.062770545 0.16155902, 0.53605324 0.061185356 0.16006604, 0.52647769 0.057359543 0.17583781, 0.52628273 0.057509448 0.17703652, 0.52590048 0.057044651 0.17427665, 0.53303534 0.057682481 0.1555863, 0.52486795 0.057044473 0.17626029, 0.53582507 0.061185237 0.16146269, 0.52482259 0.056941774 0.17313945, 0.5351699 0.059763368 0.15993276, 0.52486235 0.05694392 0.17417231, 0.52434224 0.056941714 0.17411381, 0.53145444 0.05712777 0.1554676, 0.52349287 0.056971338 0.17468825, 0.52331811 0.056941506 0.17602947, 0.53580505 0.062770456 0.16435996, 0.52289456 0.057212707 0.17298871, 0.53494501 0.059763309 0.16130748, 0.52192104 0.057212617 0.17484266, 0.53399551 0.058575805 0.15975574, 0.52189982 0.057759371 0.17183164, 0.52979028 0.056939658 0.15534312, 0.52099329 0.058002766 0.17266741, 0.52128381 0.057545956 0.17403379, 0.53526419 0.061185118 0.1642364, 0.52097762 0.0577594 0.17364317, 0.52048731 0.057759341 0.17453316, 0.53377563 0.058575746 0.16110104, 0.52040672 0.058792349 0.17141515, 0.53258932 0.057682272 0.15954366, 0.51950413 0.05879214 0.17316213, 0.528126 0.0571278 0.15521854, 0.51966012 0.059896436 0.17058942, 0.53528923 0.062770367 0.16644013, 0.51960367 0.059505489 0.17143124, 0.53439319 0.0597631 0.16403762, 0.51923668 0.059896346 0.17145154, 0.51860088 0.060307588 0.17204604, 0.5323751 0.057682212 0.16085401, 0.51833355 0.059896197 0.17314738, 0.53102183 0.057127591 0.15930739, 0.52654529 0.057682451 0.15509978, 0.53475338 0.061185088 0.16629669, 0.5346958 0.062770247 0.1684998, 0.53323537 0.058575597 0.1637733, 0.53081405 0.057127532 0.16057876, 0.5293718 0.056939479 0.15905863, 0.52512717 0.058575895 0.15499371, 0.53389031 0.05976304 0.16606528, 0.5341658 0.06118485 0.16833633, 0.53184903 0.057682004 0.16345668, 0.52917051 0.05693936 0.16028896, 0.52772135 0.057127621 0.15880996, 0.52394277 0.059763547 0.15490514, 0.53274316 0.058575537 0.16575789, 0.53378564 0.062770069 0.17120853, 0.53331196 0.059762921 0.16807267, 0.53030342 0.057127472 0.16310418, 0.52752703 0.057127442 0.15999913, 0.52615386 0.057682361 0.15857369, 0.5230518 0.061185565 0.15483832, 0.53136951 0.057681944 0.16538969, 0.53328019 0.06276986 0.17254516, 0.53326434 0.06118476 0.17101887, 0.53217715 0.058575328 0.16772255, 0.52867645 0.05693939 0.1627326, 0.52596581 0.057682212 0.159724, 0.52474779 0.058575835 0.15836173, 0.52249879 0.062770754 0.15479699, 0.52983832 0.057127293 0.16497949, 0.5327639 0.061184701 0.17234245, 0.53242475 0.059762802 0.17071325, 0.53081834 0.057681944 0.16730347, 0.5270493 0.057127412 0.16236138, 0.52456522 0.058575805 0.15947691, 0.52357334 0.059763517 0.15818468, 0.52822626 0.056939121 0.16454744, 0.53193218 0.059762653 0.17201582, 0.53130883 0.058575209 0.17030698, 0.52930349 0.057127174 0.16683614, 0.52550387 0.057682123 0.16200855, 0.52339572 0.059763279 0.15927079, 0.52268964 0.061185416 0.15805176, 0.52661431 0.057127174 0.16411558, 0.53082657 0.058575209 0.17158213, 0.52997255 0.057681706 0.16982073, 0.52770859 0.05693927 0.16634437, 0.52411759 0.058575597 0.16169205, 0.52251577 0.061185326 0.15911594, 0.52214128 0.062770694 0.15796906, 0.52508307 0.057681914 0.16370535, 0.52848297 0.057127025 0.16927829, 0.52611387 0.057127234 0.16585237, 0.52295965 0.059763309 0.16142803, 0.52196962 0.062770605 0.15901962, 0.52691472 0.056938913 0.16870755, 0.49772924 0.058881219 0.20414796, 0.49692896 0.060610082 0.20368612, 0.51213068 0.058880743 0.21246269, 0.5110538 0.057365384 0.21184093, 0.50974143 0.056121822 0.21108305, 0.51293123 0.060609605 0.2129249, 0.49643615 0.062485959 0.20340171, 0.50824422 0.055197831 0.21021861, 0.51342398 0.062485453 0.21320954, 0.50661957 0.054628845 0.20928061, 0.50493008 0.05443674 0.208305, 0.50324064 0.054628786 0.20732969, 0.50161594 0.05519795 0.20639178, 0.50011867 0.056122195 0.20552742, 0.49880639 0.057365786 0.20476988, 0.53735864 0.069995254 0.16173342, 0.53636366 0.071510553 0.16011339, 0.536134 0.071510613 0.16151765, 0.53759342 0.069995224 0.16029871, 0.52957284 0.074246943 0.1669203, 0.52822632 0.074439287 0.16454864, 0.52770859 0.074439228 0.1663453, 0.5301106 0.074247092 0.16505352, 0.53850728 0.068266392 0.16043627, 0.53808171 0.069995433 0.15596509, 0.53900319 0.0682666 0.15603411, 0.52465761 0.074246824 0.16916198, 0.52331853 0.073677808 0.16739953, 0.52291137 0.073677808 0.16847619, 0.52508128 0.074246883 0.16804129, 0.53557009 0.071510375 0.16430688, 0.5346418 0.072754115 0.16125455, 0.53409284 0.072754055 0.16396967, 0.52021021 0.072753638 0.17039031, 0.52130198 0.072753757 0.16784471, 0.51989144 0.071510106 0.16729099, 0.5188368 0.071510017 0.16974992, 0.52691448 0.074439049 0.16870841, 0.52584434 0.074247062 0.16577014, 0.53359264 0.072753966 0.16598627, 0.53240728 0.073678017 0.16358495, 0.53192264 0.073678046 0.16553891, 0.53826874 0.068266273 0.16189376, 0.53136545 0.073677868 0.16747326, 0.53906989 0.066390455 0.16052094, 0.53957051 0.066390723 0.15607649, 0.5264737 0.0744389 0.16987461, 0.53678268 0.069995016 0.16458347, 0.52177697 0.073677659 0.17112112, 0.5287478 0.074246854 0.16937584, 0.53505653 0.071510255 0.16637847, 0.53882915 0.066390425 0.16199246, 0.53301746 0.072753757 0.1679827, 0.52828974 0.074246794 0.17058721, 0.53768343 0.068266213 0.1647892, 0.52347714 0.074246585 0.17191398, 0.5305106 0.073677868 0.17001733, 0.53625774 0.069994926 0.16670018, 0.53446549 0.071510166 0.16842943, 0.53003591 0.073677748 0.1712727, 0.53823835 0.066390216 0.1649155, 0.52524537 0.074438721 0.17273846, 0.53213519 0.072753727 0.17060849, 0.5200097 0.066390693 0.15461054, 0.5371502 0.068266153 0.16693935, 0.52057725 0.06826669 0.15465331, 0.53565401 0.069994777 0.16879591, 0.5316453 0.072753429 0.17190421, 0.52149874 0.069995522 0.15472239, 0.52701348 0.074246675 0.17356294, 0.53355926 0.071510047 0.17112666, 0.51967329 0.066390455 0.15759742, 0.5377 0.066390157 0.16708651, 0.52273899 0.071510732 0.15481552, 0.53653705 0.068265915 0.16906825, 0.53305584 0.071509898 0.17245767, 0.51951152 0.066390544 0.15858632, 0.52871364 0.07367751 0.17435589, 0.52023596 0.068266511 0.15768236, 0.53472787 0.069994658 0.17155212, 0.52425003 0.072754443 0.15492874, 0.53708076 0.066389948 0.16923565, 0.53421372 0.069994479 0.17291194, 0.52007192 0.068266481 0.15868533, 0.53028053 0.072753429 0.17508629, 0.52114969 0.069995254 0.15782017, 0.53559619 0.068265676 0.17186797, 0.51911443 0.066390336 0.16055077, 0.53507382 0.068265617 0.17324954, 0.53165382 0.071509808 0.17572668, 0.52597398 0.073678523 0.15505812, 0.53613096 0.066389799 0.17206243, 0.53560358 0.06638971 0.17345732, 0.52098197 0.069995254 0.15884596, 0.53278118 0.069994181 0.17625222, 0.52237946 0.071510732 0.15800554, 0.53361863 0.068265438 0.17664248, 0.53413433 0.066389441 0.17688301, 0.51966923 0.068266273 0.16067722, 0.52784467 0.074247628 0.15519825, 0.53276867 0.067341328 0.17911318, 0.53210324 0.069152504 0.17876688, 0.51875263 0.066390276 0.16200972, 0.53197736 0.070395529 0.17727414, 0.5222066 0.071510553 0.15906182, 0.52387792 0.072754413 0.15823144, 0.53113723 0.070782393 0.17826393, 0.53080827 0.07039547 0.17951989, 0.53347909 0.06590575 0.17843083, 0.53299242 0.065418661 0.17951062, 0.5205701 0.069995105 0.1608831, 0.53243876 0.065905601 0.18041423, 0.5297901 0.074439734 0.15534395, 0.53079671 0.071848035 0.17669207, 0.51930231 0.068266153 0.16215706, 0.52990758 0.072168618 0.17762414, 0.5236991 0.072754174 0.15932515, 0.52965397 0.071848065 0.17888692, 0.52938437 0.073015749 0.17599574, 0.51833659 0.066390008 0.16345397, 0.52846187 0.073257744 0.17687157, 0.52558732 0.073678493 0.15848929, 0.52827364 0.07301572 0.1781297, 0.52779514 0.073854148 0.17521206, 0.52178258 0.071510524 0.16116005, 0.52685529 0.074008018 0.17603528, 0.53173566 0.074247599 0.15548971, 0.52671993 0.07385391 0.17727712, 0.52608955 0.074330509 0.17437091, 0.52019483 0.069995105 0.16239643, 0.52514988 0.074390471 0.17514756, 0.52540159 0.073678195 0.15962532, 0.52505261 0.07433033 0.17636293, 0.52433366 0.074426681 0.17350495, 0.51888031 0.068266004 0.16362169, 0.52333611 0.074426591 0.17542103, 0.52744246 0.074247479 0.15876892, 0.52303654 0.074195892 0.17228395, 0.52325988 0.072754145 0.16149715, 0.52200234 0.07405436 0.17312154, 0.53360617 0.073678464 0.1556299, 0.52250624 0.074305058 0.17456433, 0.52209383 0.074195683 0.17414466, 0.52159208 0.074195683 0.17505875, 0.51769823 0.066390097 0.16535363, 0.52107877 0.073513269 0.17171422, 0.52139604 0.071510553 0.16271809, 0.52016258 0.073513299 0.17348996, 0.51945966 0.072638214 0.17154998, 0.52724916 0.074247301 0.15995112, 0.51976341 0.069994837 0.16389418, 0.51866204 0.072288483 0.17206934, 0.51855218 0.072637975 0.17325544, 0.52937156 0.074439555 0.15905976, 0.51812863 0.071224868 0.17058894, 0.51770967 0.069994569 0.1692242, 0.51687223 0.068265766 0.16883367, 0.51734382 0.066389978 0.16629103, 0.51726431 0.071224809 0.17223713, 0.52494556 0.073678166 0.16188195, 0.53533036 0.072754472 0.15575927, 0.518233 0.068265975 0.16554838, 0.52285987 0.072754085 0.16311038, 0.52917039 0.074439585 0.16029012, 0.52095169 0.071510226 0.16426083, 0.53130066 0.07424736 0.1593504, 0.51787359 0.068265945 0.16649902, 0.52677447 0.074247211 0.16229951, 0.53684145 0.071510881 0.15587226, 0.51910132 0.069994718 0.1658645, 0.52452987 0.073678017 0.16355801, 0.53109175 0.07424733 0.16062859, 0.52239972 0.072753906 0.16470757, 0.53315562 0.073678285 0.15962997, 0.51873368 0.069994807 0.16683665, 0.52867633 0.074439436 0.16273358, 0.51635641 0.066389799 0.16859302, 0.52026993 0.071510226 0.1662899, 0.52634186 0.074247122 0.16404355, 0.53293896 0.073678315 0.16095436, 0.52405185 0.073677897 0.16521719, 0.5348652 0.072754204 0.15988758, 0.53057832 0.07424733 0.16316763, 0.52169383 0.072753876 0.16680816, 0.51126283 -0.0038946904 0.21195787, 0.51078242 -0.0023093112 0.21168059, 0.51000863 -0.00088732317 0.21123385, 0.50898004 0.00030023977 0.21064025, 0.50774854 0.0011937432 0.20992923, 0.50637579 0.0017486475 0.20913661, 0.50493044 0.0019367151 0.20830223, 0.50348502 0.0017486773 0.20746773, 0.50211227 0.0011938922 0.20667502, 0.50088072 0.00030040368 0.20596394, 0.49985227 -0.00088702515 0.20537016, 0.49907848 -0.0023090579 0.20492327, 0.49859813 -0.0038943328 0.20464572, 0.52950341 -0.012318332 0.17105862, 0.52675837 -0.012873236 0.17343894, 0.52819508 -0.0123186 0.17410865, 0.52802771 -0.012873042 0.17047957, 0.52116388 -0.007229615 0.16265133, 0.52154833 -0.0072295554 0.16110197, 0.52208906 -0.0088147558 0.16122523, 0.52169985 -0.0088149048 0.16279507, 0.52534699 -0.012873057 0.16813272, 0.52344507 -0.012318376 0.16868088, 0.52492076 -0.012873057 0.16925988, 0.5238573 -0.012318347 0.16759074, 0.52324075 -0.011424605 0.16496196, 0.5225209 -0.01142462 0.16710436, 0.52459961 -0.012318183 0.16538122, 0.5225628 -0.010236833 0.16302606, 0.52125198 -0.0088149793 0.16434893, 0.52210587 -0.010236952 0.16461217, 0.52647418 -0.01306117 0.16986972, 0.52524596 -0.013061289 0.17273358, 0.52212125 -0.011424813 0.16816121, 0.52140492 -0.010237101 0.16669819, 0.52072203 -0.0072297491 0.16418529, 0.52373332 -0.012873266 0.17202821, 0.52101582 -0.010237265 0.16772744, 0.52056527 -0.0088150091 0.1663928, 0.52229661 -0.012318481 0.17135823, 0.5201841 -0.0088151135 0.16740128, 0.52004403 -0.0072298385 0.16620314, 0.52100772 -0.011424858 0.17075732, 0.5196678 -0.0072298534 0.16719869, 0.51993155 -0.01023731 0.17025563, 0.51912183 -0.008815337 0.16987807, 0.51861912 -0.0072301365 0.16964385, 0.53187281 -0.0072303452 0.17582399, 0.53124636 -0.0068178065 0.17730787, 0.53056031 -0.0080385841 0.17795911, 0.53078121 -0.0064012893 0.17834333, 0.53056031 -0.010237474 0.17521173, 0.53066128 -0.009189371 0.17662042, 0.53136998 -0.0088155158 0.17558962, 0.5302493 -0.006817881 0.17920873, 0.52991396 -0.0095517524 0.1776225, 0.52952188 -0.0091894902 0.17880979, 0.53104419 -0.0080386288 0.17700773, 0.52997327 -0.0080386437 0.17905733, 0.52978975 -0.01055913 0.17619079, 0.5370822 -0.0072292425 0.15588593, 0.52948397 -0.011425022 0.17470995, 0.536529 -0.0088143982 0.15584427, 0.5289852 -0.010864798 0.17713898, 0.52866977 -0.010559071 0.17834213, 0.53563809 -0.010236491 0.15577748, 0.52866656 -0.011678103 0.17563671, 0.52782041 -0.011911977 0.17653257, 0.53660226 -0.0072293319 0.16014484, 0.52757186 -0.011678252 0.17773953, 0.52734834 -0.01249053 0.17498654, 0.53445381 -0.011423949 0.15568855, 0.53637171 -0.0072293319 0.16155496, 0.52647823 -0.01264051 0.17583388, 0.53605384 -0.0088146217 0.16006213, 0.5262832 -0.012490708 0.17703253, 0.5259009 -0.012955416 0.17427269, 0.52486819 -0.012955595 0.17625645, 0.53303581 -0.012317527 0.15558231, 0.53582555 -0.0088146664 0.16145864, 0.52482301 -0.013058398 0.17313558, 0.52486271 -0.013056073 0.17416826, 0.53517038 -0.010236669 0.15992892, 0.5243426 -0.013058458 0.17411008, 0.53145498 -0.012872253 0.1554639, 0.52349311 -0.013028551 0.17468423, 0.52331859 -0.013058607 0.17602566, 0.53580552 -0.0072297193 0.1643559, 0.52289504 -0.012787331 0.17298478, 0.53494555 -0.010236714 0.16130343, 0.52192158 -0.012787346 0.17483881, 0.52190024 -0.012240637 0.17182767, 0.53399605 -0.011424232 0.1597518, 0.52979058 -0.01306032 0.15533906, 0.52099371 -0.011997242 0.17266363, 0.52128428 -0.012454096 0.17402986, 0.53526479 -0.0088149644 0.16423261, 0.52097827 -0.012240816 0.17363912, 0.52048784 -0.012240816 0.17452925, 0.53377604 -0.011424232 0.16109708, 0.52040714 -0.011207674 0.17141125, 0.53258991 -0.01231781 0.15953985, 0.51950461 -0.011207882 0.17315808, 0.52812642 -0.012872282 0.15521449, 0.51966065 -0.010103647 0.17058551, 0.51960409 -0.010494519 0.17142719, 0.53528965 -0.0072297491 0.16643634, 0.53439361 -0.010236997 0.16403377, 0.51923698 -0.010103632 0.17144772, 0.51860136 -0.0096923895 0.17204243, 0.53237551 -0.01231784 0.16085017, 0.51833397 -0.010103811 0.17314342, 0.53102237 -0.012872446 0.15930349, 0.52654564 -0.012317527 0.15509593, 0.53475386 -0.0088149346 0.1662927, 0.53469628 -0.0072298981 0.1684958, 0.53323597 -0.01142453 0.16376927, 0.53081423 -0.012872461 0.16057482, 0.52937216 -0.013060499 0.15905467, 0.52512771 -0.011424113 0.15498972, 0.53389066 -0.010236997 0.16606152, 0.53416616 -0.0088151135 0.16833237, 0.53184938 -0.012318004 0.16345271, 0.52917093 -0.013060514 0.16028503, 0.52772182 -0.012872431 0.15880591, 0.52394336 -0.010236431 0.15490118, 0.53274363 -0.011424515 0.16575399, 0.53378612 -0.0072299279 0.17120478, 0.53331226 -0.010237176 0.16806898, 0.53030407 -0.01287267 0.16309991, 0.52752739 -0.012872551 0.15999511, 0.52615428 -0.012317676 0.15856993, 0.52305228 -0.0088145025 0.15483442, 0.5313701 -0.012318123 0.16538584, 0.53328055 -0.0072300918 0.1725412, 0.53326494 -0.0088152327 0.1710149, 0.53217763 -0.011424679 0.16771886, 0.52867693 -0.013060678 0.1627287, 0.52596611 -0.012317751 0.15971974, 0.52474809 -0.011424113 0.1583578, 0.52249926 -0.0072291978 0.1547932, 0.52983886 -0.012872744 0.16497561, 0.53276432 -0.0088153966 0.17233866, 0.53242522 -0.010237206 0.17070952, 0.53081876 -0.012318123 0.16729969, 0.52704984 -0.01287261 0.16235733, 0.52456576 -0.011424307 0.15947309, 0.5235737 -0.010236565 0.15818086, 0.52822667 -0.013060812 0.16454354, 0.53193265 -0.010237429 0.17201212, 0.53130931 -0.011424828 0.17030305, 0.52930373 -0.012872864 0.1668323, 0.52550429 -0.012317855 0.1620045, 0.52339619 -0.010236774 0.15926695, 0.52269036 -0.0088146068 0.15804771, 0.52661467 -0.012872685 0.16411152, 0.53082711 -0.011424828 0.17157808, 0.52997309 -0.012318376 0.16981682, 0.52770913 -0.013060916 0.16634044, 0.52411801 -0.011424292 0.16168821, 0.52251631 -0.008814726 0.15911186, 0.52214164 -0.0072293915 0.15796524, 0.52508348 -0.012318019 0.16370133, 0.52848351 -0.012873042 0.16927427, 0.52611434 -0.012872804 0.16584834, 0.52296013 -0.010236759 0.16142407, 0.52196985 -0.0072294064 0.15901572, 0.52370995 -0.011424575 0.16333333, 0.52691513 -0.01306111 0.16870359, 0.49692944 -0.0093900301 0.20368227, 0.49772969 -0.011118848 0.20414424, 0.49643663 -0.0075140782 0.20339766, 0.51105422 -0.012634505 0.21183702, 0.50974184 -0.013878245 0.21107906, 0.51213115 -0.011119235 0.21245894, 0.50824463 -0.01480234 0.21021473, 0.51293164 -0.0093904324 0.2129209, 0.50662011 -0.015371177 0.20927665, 0.51342434 -0.0075144805 0.21320552, 0.5049305 -0.015563313 0.20830119, 0.50324088 -0.015371162 0.20732558, 0.5016163 -0.014802117 0.20638794, 0.50011915 -0.013877872 0.20552358, 0.49880672 -0.012634192 0.20476592, 0.53192312 0.003678035 0.16553521, 0.53240758 0.0036781393 0.16358104, 0.53057885 0.0042471401 0.16316378, 0.53735912 -4.8913062e-06 0.16172948, 0.53636408 0.0015105568 0.16010934, 0.53613448 0.0015104972 0.16151381, 0.5375939 -4.8317015e-06 0.16029471, 0.52957332 0.0042469613 0.16691634, 0.52822667 0.0044392459 0.16454461, 0.52770901 0.0044391863 0.16634125, 0.53011113 0.0042470805 0.16504946, 0.53850758 -0.0017337389 0.16043228, 0.538082 -4.503876e-06 0.15596122, 0.53900361 -0.0017334111 0.15603012, 0.52465802 0.0042467229 0.16915795, 0.52331901 0.0036779307 0.16739568, 0.52291191 0.003677737 0.16847259, 0.52508169 0.0042467974 0.16803753, 0.53557062 0.0015102737 0.16430286, 0.53464216 0.0027541332 0.16125071, 0.53409326 0.0027539246 0.16396585, 0.52021062 0.0027535222 0.1703864, 0.52130258 0.0027536266 0.1678409, 0.51989174 0.0015101545 0.16728705, 0.51883733 0.0015099607 0.1697461, 0.52691513 0.0044389032 0.16870457, 0.52584475 0.004247006 0.16576633, 0.53359318 0.0027539842 0.16598246, 0.53826916 -0.001733724 0.16188994, 0.53136587 0.0036778115 0.16746935, 0.53907031 -0.0036096014 0.16051701, 0.53957111 -0.0036093779 0.15607253, 0.52647406 0.0044388287 0.16987064, 0.53678316 -5.0403178e-06 0.16457972, 0.52177745 0.003677588 0.17111707, 0.52874833 0.0042468272 0.16937187, 0.53505695 0.0015101992 0.16637462, 0.53882974 -0.0036096312 0.16198865, 0.53301799 0.002753716 0.16797885, 0.52829015 0.0042467974 0.17058331, 0.53768402 -0.0017339028 0.16478515, 0.52347761 0.0042465739 0.17190993, 0.53051096 0.0036777221 0.17001355, 0.53625822 -5.1148236e-06 0.16669622, 0.53446603 0.0015100054 0.16842553, 0.53003645 0.0036776923 0.17126873, 0.53823876 -0.0036098398 0.16491154, 0.52524573 0.0044387542 0.1727345, 0.53213573 0.002753567 0.17060456, 0.52001011 -0.0036093183 0.1546067, 0.52012259 -0.0036092587 0.15160322, 0.53715068 -0.0017339177 0.16693541, 0.52057755 -0.0017333515 0.15464926, 0.52069163 -0.0017332472 0.15160322, 0.53565454 -5.2936375e-06 0.16879207, 0.53164577 0.0027534477 0.17190042, 0.52149916 -4.5336783e-06 0.15471843, 0.5216158 -4.4740736e-06 0.15160352, 0.52701396 0.0042465292 0.17355898, 0.51967365 -0.0036095567 0.15759343, 0.53355968 0.001509916 0.17112282, 0.53770059 -0.0036098845 0.16708267, 0.52273935 0.0015107356 0.15481156, 0.52285933 0.001510974 0.15160352, 0.53653729 -0.0017341264 0.16906419, 0.53305632 0.0015098266 0.17245394, 0.51951212 -0.0036095418 0.15858236, 0.52871418 0.0036774985 0.17435184, 0.52023631 -0.0017334856 0.1576784, 0.53472841 -5.4128468e-06 0.17154822, 0.52425039 0.0027543418 0.15492478, 0.52437478 0.0027545802 0.15160352, 0.53708118 -0.0036101229 0.16923174, 0.5200724 -0.0017336048 0.15868142, 0.53421402 -5.5767596e-06 0.17290798, 0.52115011 -4.6975911e-06 0.15781635, 0.53028101 0.0027534328 0.17508236, 0.53559661 -0.0017343052 0.17186412, 0.51911485 -0.0036097206 0.16054669, 0.53507423 -0.0017343797 0.17324558, 0.53165436 0.001509767 0.17572278, 0.52597451 0.0036784522 0.15505415, 0.52610356 0.0036786906 0.15160361, 0.53613144 -0.0036102422 0.17205867, 0.53560394 -0.0036103465 0.17345336, 0.52098238 -4.7571957e-06 0.15884191, 0.52237976 0.0015106462 0.15800157, 0.53278142 -5.6512654e-06 0.17624825, 0.53361899 -0.0017345436 0.17663863, 0.53413475 -0.00361057 0.17687902, 0.51966977 -0.0017337836 0.16067344, 0.5278452 0.0042475276 0.15519443, 0.52797961 0.0042477511 0.15160361, 0.51875317 -0.0036098249 0.16200566, 0.53276914 -0.0026586838 0.17910928, 0.53210378 -0.00084762648 0.17876294, 0.53197777 0.0003955327 0.17727023, 0.5222072 0.0015104674 0.15905789, 0.52387828 0.0027542673 0.15822759, 0.5311377 0.00078238174 0.17826012, 0.53080881 0.00039542839 0.17951605, 0.53347957 -0.0040941872 0.17842677, 0.52057058 -4.9211085e-06 0.16087919, 0.5329929 -0.0045814998 0.17950657, 0.53243911 -0.004094366 0.1804103, 0.52979058 0.0044396631 0.15534002, 0.51930273 -0.001733873 0.16215304, 0.530797 0.0018480532 0.17668802, 0.52369952 0.0027541779 0.15932122, 0.52990806 0.0021686517 0.17762023, 0.52965462 0.0018479191 0.17888287, 0.52938485 0.0030157678 0.17599195, 0.51833689 -0.0036099739 0.16345012, 0.52558786 0.003678333 0.15848535, 0.52846229 0.0032576881 0.17686754, 0.528274 0.0030156933 0.17812577, 0.52779555 0.0038541071 0.17520806, 0.52178299 0.0015104078 0.16115609, 0.53173602 0.0042476319 0.15548593, 0.52685577 0.0040078722 0.17603138, 0.5267204 0.0038539283 0.1772733, 0.52609015 0.0043304078 0.1743671, 0.52019536 -4.9956143e-06 0.16239238, 0.52515042 0.0043905042 0.17514363, 0.52540213 0.0036782734 0.15962142, 0.52505296 0.0043303333 0.17635897, 0.52433389 0.0044266693 0.17350107, 0.51888078 -0.0017340071 0.16361785, 0.52744287 0.0042474829 0.15876502, 0.52333647 0.0044266693 0.17541698, 0.52326047 0.0027540885 0.1614933, 0.52303714 0.0041957013 0.17227998, 0.522003 0.0040542446 0.17311779, 0.53360671 0.0036785565 0.15562585, 0.52250677 0.0043049566 0.17456058, 0.52209413 0.0041956566 0.1741406, 0.5215925 0.0041955821 0.17505494, 0.51769882 -0.0036100037 0.16534963, 0.52107918 0.0035133027 0.17171016, 0.52139652 0.0015103482 0.16271424, 0.52016318 0.0035131238 0.17348614, 0.52724952 0.0042473041 0.15994719, 0.5194602 0.0026381724 0.17154604, 0.51976383 -5.1148236e-06 0.16389027, 0.51866245 0.0022885464 0.17206538, 0.52937204 0.0044394545 0.15905586, 0.51855266 0.0026379339 0.17325139, 0.51812911 0.0012247972 0.1705851, 0.51771009 -5.3979456e-06 0.16922027, 0.5168727 -0.0017342605 0.16882962, 0.51734436 -0.0036100037 0.16628698, 0.51726472 0.0012246929 0.17223337, 0.52494597 0.0036781095 0.16187802, 0.53533077 0.002754461 0.15575522, 0.51823342 -0.0017340817 0.16554442, 0.52286035 0.0027540438 0.16310647, 0.52917081 0.0044394545 0.1602861, 0.52095211 0.0015101545 0.16425684, 0.53130102 0.0042474233 0.15934649, 0.51787394 -0.0017341115 0.16649503, 0.52677488 0.0042472892 0.16229549, 0.53684199 0.0015106909 0.1558682, 0.51910174 -5.1744282e-06 0.1658605, 0.52453035 0.0036780201 0.16355398, 0.53109205 0.0042473488 0.16062474, 0.5224002 0.0027538501 0.16470373, 0.53315598 0.0036783628 0.15962604, 0.51873422 -5.2936375e-06 0.16683289, 0.52867681 0.0044393651 0.16272977, 0.51635689 -0.0036101975 0.16858912, 0.52027035 0.0015101545 0.16628608, 0.52634227 0.0042471401 0.16403964, 0.53293955 0.0036781691 0.16095045, 0.5240522 0.0036779456 0.16521332, 0.53486568 0.0027541481 0.15988377, 0.52169442 0.0027537905 0.16680425, 0.52012271 -0.0074939318 -0.15160248, 0.52069175 -0.0093698688 -0.15160248, 0.5216158 -0.011098657 -0.15160248, 0.52285939 -0.01261406 -0.15160263, 0.52437478 -0.013857711 -0.15160263, 0.52610379 -0.014781807 -0.15160269, 0.52797973 -0.015350882 -0.15160263, 0.49859816 -0.0038713552 -0.20464498, 0.51689935 -0.0038729496 -0.17294613, 0.49907845 -0.0022860356 -0.2049222, 0.51737988 -0.0022877492 -0.1732235, 0.4998523 -0.00086398795 -0.20536888, 0.51815361 -0.00086571649 -0.1736702, 0.50088072 0.00032363459 -0.20596263, 0.51918209 0.00032187626 -0.17426383, 0.50211233 0.0012171827 -0.20667347, 0.5204137 0.0012154542 -0.17497483, 0.5034852 0.0017719381 -0.2074661, 0.52178633 0.0017702691 -0.17576745, 0.5049305 0.0019600056 -0.2083005, 0.52323174 0.0019583963 -0.1766018, 0.50637585 0.0017720722 -0.20913494, 0.52467716 0.0017703883 -0.17743623, 0.5077486 0.001217436 -0.20992765, 0.52604997 0.0012157522 -0.1782288, 0.50898015 0.00032388791 -0.21063864, 0.52728146 0.00032233819 -0.17893997, 0.51000869 -0.00086367503 -0.21123257, 0.52830982 -0.00086526945 -0.17953387, 0.51078248 -0.0022855885 -0.21167949, 0.52908373 -0.0022872128 -0.17998061, 0.51126277 -0.0038708933 -0.2119568, 0.52956414 -0.0038725175 -0.18025821, 0.52256286 -0.00086628273 -0.16302532, 0.52210593 -0.00086617842 -0.16461131, 0.52370995 0.00032126531 -0.16333255, 0.52324063 0.00032150373 -0.16496119, 0.52802765 0.0017700903 -0.17047846, 0.52675825 0.001770135 -0.1734381, 0.52950335 0.0012153946 -0.17105782, 0.52819514 0.0012154691 -0.17410791, 0.521164 -0.003873501 -0.16265056, 0.52154833 -0.00387365 -0.16110095, 0.522089 -0.0022883452 -0.16122442, 0.52169967 -0.0022882856 -0.16279408, 0.52534682 0.0017698817 -0.16813195, 0.52344501 0.0012151711 -0.16868007, 0.52492064 0.0017699711 -0.16925907, 0.52385724 0.0012150519 -0.1675899, 0.52252108 0.00032153353 -0.16710353, 0.52459955 0.0012149923 -0.16538033, 0.52125204 -0.0022881962 -0.16434807, 0.52647418 0.001957994 -0.16986883, 0.52524573 0.0019581728 -0.17273286, 0.52212131 0.00032148883 -0.16816044, 0.52140498 -0.00086599961 -0.16669744, 0.52072197 -0.0038734563 -0.16418466, 0.52373332 0.0017700307 -0.17202726, 0.52101576 -0.00086605921 -0.16772687, 0.52056527 -0.0022880472 -0.16639197, 0.52229667 0.0012153499 -0.17135739, 0.52018392 -0.002288077 -0.16740036, 0.52004409 -0.0038733669 -0.16620213, 0.52100784 0.00032181665 -0.17075646, 0.51966769 -0.0038732924 -0.16719779, 0.51993155 -0.00086594 -0.17025474, 0.51912177 -0.0022878982 -0.16987717, 0.51861912 -0.0038732029 -0.16964293, 0.53187281 -0.003872741 -0.17582324, 0.53124648 -0.0042852201 -0.17730728, 0.53056031 -0.0030643232 -0.17795843, 0.53078109 -0.0047017224 -0.17834237, 0.53056014 -0.00086540356 -0.1752111, 0.53066134 -0.0019137599 -0.17661971, 0.53137004 -0.002287481 -0.17558855, 0.53024936 -0.0042851157 -0.17920792, 0.5299139 -0.0015512146 -0.17762175, 0.52952182 -0.0019136406 -0.17880887, 0.5310443 -0.0030643828 -0.17700699, 0.52997333 -0.0030642487 -0.1790565, 0.52978969 -0.00054401532 -0.17618978, 0.53708231 -0.0038738735 -0.1558851, 0.5294838 0.00032212958 -0.17470908, 0.53652912 -0.0022885539 -0.15584353, 0.52898514 -0.00023828819 -0.17713824, 0.52866971 -0.00054389611 -0.1783413, 0.53563797 -0.00086655095 -0.15577656, 0.52866662 0.00057503209 -0.17563587, 0.53660232 -0.003873501 -0.16014412, 0.52782047 0.0008087866 -0.17653182, 0.5275718 0.00057515129 -0.17773885, 0.52734816 0.0013873838 -0.17498571, 0.53445375 0.00032101199 -0.15568784, 0.53637171 -0.0038735755 -0.1615544, 0.52647817 0.0015374832 -0.17583302, 0.5360539 -0.0022883601 -0.16006127, 0.52628309 0.0013874881 -0.17703179, 0.52590084 0.0018523 -0.17427194, 0.53303576 0.0012145005 -0.15558162, 0.52486825 0.0018524043 -0.17625552, 0.53582549 -0.00228839 -0.16145784, 0.52482295 0.0019552819 -0.1731348, 0.53517038 -0.00086632743 -0.15992802, 0.52382421 0.0019254945 -0.17404726, 0.52418745 0.001953017 -0.17546493, 0.52384102 0.0019554012 -0.17507255, 0.53145492 0.0017692409 -0.15546301, 0.52331847 0.0019553266 -0.17602482, 0.53580564 -0.0038733222 -0.16435513, 0.52304935 0.0016841553 -0.17267111, 0.53494549 -0.00086619332 -0.16130254, 0.52208936 0.0016842149 -0.17453188, 0.52197355 0.0011374913 -0.17167422, 0.53399587 0.00032126531 -0.15975091, 0.52202135 0.001351025 -0.17261302, 0.52979064 0.0019571893 -0.15533829, 0.52152574 0.0011374466 -0.17258656, 0.53526461 -0.002288077 -0.16423175, 0.52073538 0.00089418516 -0.17315876, 0.52057076 0.0011375509 -0.17438093, 0.53377604 0.00032122061 -0.16109633, 0.52028632 0.00010461733 -0.17165551, 0.53258979 0.0012146346 -0.15953889, 0.51937318 0.00010461733 -0.17339668, 0.5281263 0.0017691515 -0.15521365, 0.51960284 -0.00099946931 -0.17070496, 0.51885426 -0.0014108457 -0.17155555, 0.53528953 -0.0038732179 -0.16643554, 0.53439367 -0.00086622313 -0.16403276, 0.51892567 -0.00060850754 -0.17272961, 0.51873177 -0.00099942461 -0.17241743, 0.51826859 -0.0009993799 -0.1732589, 0.53237551 0.0012148134 -0.16084939, 0.53102231 0.0017693304 -0.15930256, 0.52654564 0.0012144111 -0.15509525, 0.5347538 -0.0022880323 -0.16629195, 0.53469634 -0.0038731582 -0.16849518, 0.53323579 0.00032144412 -0.1637685, 0.53081453 0.0017694794 -0.16057399, 0.5293721 0.0019573085 -0.15905389, 0.52512759 0.00032086298 -0.15498903, 0.53389072 -0.00086602941 -0.16606054, 0.53416616 -0.0022879727 -0.1683315, 0.5318495 0.0012147985 -0.16345197, 0.52917087 0.001957532 -0.16028419, 0.52772176 0.0017693155 -0.15880519, 0.52394336 -0.00086662546 -0.15490025, 0.53274357 0.00032151863 -0.16575307, 0.53378612 -0.0038729198 -0.17120403, 0.53331232 -0.00086594 -0.16806814, 0.53030396 0.0017696731 -0.16309914, 0.52752739 0.0017694347 -0.15999439, 0.52615428 0.0012146495 -0.15856901, 0.52305239 -0.0022887327 -0.1548335, 0.53136992 0.0012150966 -0.16538501, 0.53328067 -0.0038729049 -0.17254055, 0.53326488 -0.0022877045 -0.17101407, 0.53217757 0.00032162294 -0.16771793, 0.52867669 0.0019576363 -0.16272777, 0.52596611 0.001214575 -0.15971926, 0.52474815 0.0003210865 -0.15835696, 0.52249926 -0.0038739927 -0.15479222, 0.52983874 0.0017697625 -0.16497469, 0.53276443 -0.0022877194 -0.17233765, 0.53242528 -0.00086573139 -0.17070842, 0.5308187 0.0012151562 -0.16729891, 0.52704978 0.001769539 -0.16235647, 0.5245657 0.0003211014 -0.15947229, 0.52357376 -0.00086646155 -0.15818015, 0.52822685 0.0019577108 -0.16454276, 0.53193265 -0.00086573139 -0.17201126, 0.53130925 0.00032171234 -0.17030227, 0.52930391 0.0017698072 -0.16683146, 0.52550435 0.0012148581 -0.16200379, 0.52339613 -0.00086641684 -0.15926611, 0.52269018 -0.0022884645 -0.15804699, 0.52661479 0.0017696284 -0.16411075, 0.53082705 0.00032186136 -0.17157736, 0.52997303 0.0012153201 -0.1698159, 0.52770913 0.0019577853 -0.16633955, 0.52411795 0.0003211461 -0.16168737, 0.52251625 -0.0022884496 -0.15911117, 0.52214175 -0.0038737692 -0.15796441, 0.52508354 0.0012148581 -0.16370064, 0.52848339 0.0017699562 -0.1692735, 0.52611423 0.001769688 -0.16584769, 0.52296019 -0.00086635724 -0.16142306, 0.52197003 -0.0038737692 -0.15901485, 0.52691507 0.0019579791 -0.16870284, 0.50974196 -0.013854448 -0.2110793, 0.50824469 -0.014778782 -0.21021488, 0.50662011 -0.015347738 -0.20927691, 0.50493062 -0.015540022 -0.20830148, 0.503241 -0.015347857 -0.20732602, 0.49643674 -0.0074912347 -0.20339715, 0.49692944 -0.0093671419 -0.20368171, 0.51342434 -0.007490579 -0.21320489, 0.50161642 -0.014779005 -0.20638812, 0.49772969 -0.011095989 -0.20414394, 0.51293164 -0.0093665011 -0.21292061, 0.50011915 -0.013854925 -0.20552361, 0.4988068 -0.012611229 -0.20476592, 0.51213127 -0.011095513 -0.21245864, 0.51105422 -0.012610842 -0.21183676, 0.53172559 -0.0074921884 -0.18150625, 0.53123289 -0.009368185 -0.18122187, 0.53043252 -0.011097122 -0.18075979, 0.52935559 -0.01261251 -0.18013817, 0.52804327 -0.013856102 -0.17938057, 0.526546 -0.014780346 -0.17851609, 0.52492142 -0.015349481 -0.17757824, 0.5232318 -0.015541676 -0.1766029, 0.52154225 -0.015349571 -0.17562726, 0.51991773 -0.014780629 -0.17468932, 0.51842028 -0.013856459 -0.17382482, 0.51710808 -0.012612898 -0.173067, 0.51603109 -0.011097658 -0.17244509, 0.51523083 -0.0093687661 -0.171983, 0.5147379 -0.0074929334 -0.17169845, 0.5373593 -0.011098165 -0.16172871, 0.53636414 -0.012613509 -0.16010851, 0.5361346 -0.012613524 -0.16151282, 0.5375939 -0.01109824 -0.16029388, 0.5295735 -0.015349988 -0.16691548, 0.52822679 -0.015542272 -0.16454375, 0.52770907 -0.015542168 -0.16634059, 0.53011125 -0.015350047 -0.16504854, 0.53850764 -0.0093692578 -0.16043153, 0.53808218 -0.011098374 -0.1559605, 0.53900367 -0.0093694367 -0.15602937, 0.52465802 -0.015349913 -0.16915706, 0.52331913 -0.014780913 -0.16739497, 0.52291191 -0.014780913 -0.16847169, 0.52508199 -0.015349928 -0.16803658, 0.53557056 -0.0126133 -0.16430208, 0.53464216 -0.013857145 -0.16124985, 0.53409338 -0.013857041 -0.16396481, 0.52021086 -0.013856757 -0.17038563, 0.51989192 -0.01261327 -0.16728628, 0.51883739 -0.012613092 -0.16974521, 0.52130252 -0.013856892 -0.16784, 0.52691513 -0.015542138 -0.16870368, 0.52584499 -0.015350137 -0.16576552, 0.53359324 -0.013856936 -0.16598153, 0.53240788 -0.014781091 -0.16358024, 0.53192323 -0.014781062 -0.16553399, 0.53826934 -0.0093692131 -0.16188914, 0.53136593 -0.014780898 -0.16746864, 0.53907031 -0.0074933805 -0.16051629, 0.53957117 -0.0074934848 -0.15607181, 0.52647424 -0.015542138 -0.16986978, 0.53678316 -0.011097897 -0.16457886, 0.52177775 -0.014780749 -0.17111623, 0.52874839 -0.015349824 -0.16937098, 0.53505689 -0.012613226 -0.16637367, 0.53882986 -0.0074933656 -0.16198784, 0.53301811 -0.013856743 -0.16797805, 0.52829021 -0.015349779 -0.17058241, 0.53768414 -0.0093690641 -0.16478428, 0.52347773 -0.015349705 -0.17190909, 0.5305112 -0.014780734 -0.17001259, 0.53625816 -0.011097763 -0.16669542, 0.53446609 -0.012613047 -0.1684247, 0.53003657 -0.014780674 -0.17126787, 0.53823882 -0.0074930824 -0.16491079, 0.52524596 -0.01554184 -0.17273369, 0.53213567 -0.013856519 -0.17060387, 0.52001029 -0.0074938275 -0.15460578, 0.5371508 -0.0093689151 -0.16693461, 0.53565449 -0.011097718 -0.16879106, 0.52057773 -0.0093696155 -0.15464854, 0.53164583 -0.013856534 -0.17189932, 0.52701408 -0.015349705 -0.17355815, 0.52149922 -0.011098582 -0.15471771, 0.53355974 -0.012612987 -0.17112201, 0.51967388 -0.0074936785 -0.15759259, 0.53770047 -0.0074929632 -0.16708168, 0.53653747 -0.009368781 -0.16906345, 0.52273947 -0.012613971 -0.1548107, 0.53305644 -0.012612943 -0.17245305, 0.51951212 -0.0074936189 -0.15858158, 0.52871424 -0.01478057 -0.17435101, 0.52023643 -0.009369541 -0.15767759, 0.53472835 -0.011097539 -0.17154744, 0.52425045 -0.013857532 -0.15492395, 0.5370813 -0.0074927695 -0.16923097, 0.5342142 -0.011097465 -0.17290723, 0.53028113 -0.013856415 -0.17508164, 0.52007252 -0.0093695261 -0.15868038, 0.52115023 -0.011098418 -0.15781546, 0.53559667 -0.0093686469 -0.17186338, 0.53507441 -0.009368632 -0.17324486, 0.51911491 -0.0074934103 -0.16054592, 0.53165442 -0.012612719 -0.17572194, 0.52597463 -0.014781643 -0.15505329, 0.53613156 -0.0074927397 -0.17205787, 0.53560406 -0.0074926801 -0.17345265, 0.53278154 -0.011097346 -0.17624742, 0.52098256 -0.011098359 -0.15884107, 0.52237993 -0.012613703 -0.15800089, 0.53361917 -0.0093683787 -0.1766378, 0.53413486 -0.0074924864 -0.17687815, 0.51966983 -0.009369377 -0.16067261, 0.52784526 -0.015350629 -0.15519348, 0.53276926 -0.0084443279 -0.17910844, 0.53210384 -0.010255504 -0.17876226, 0.53197783 -0.011498485 -0.17726949, 0.51875305 -0.0074933656 -0.16200477, 0.52220732 -0.012613822 -0.15905717, 0.53113776 -0.011885393 -0.17825943, 0.53080887 -0.011498395 -0.17951542, 0.52387846 -0.013857339 -0.15822676, 0.53347963 -0.00700875 -0.17842618, 0.53299302 -0.006521631 -0.17950574, 0.5205707 -0.011098269 -0.16087836, 0.53243929 -0.0070087202 -0.18040961, 0.53079718 -0.01295108 -0.17668727, 0.52979064 -0.015542794 -0.15533927, 0.51930279 -0.0093692876 -0.16215226, 0.52990812 -0.013271589 -0.1776194, 0.52965468 -0.01295102 -0.17888209, 0.52369982 -0.013857353 -0.15932038, 0.52938503 -0.014118943 -0.17599088, 0.51833707 -0.0074933656 -0.16344935, 0.52846253 -0.014360819 -0.1768668, 0.52827412 -0.014118839 -0.17812482, 0.52558798 -0.014781449 -0.15848431, 0.52779567 -0.014957149 -0.17520726, 0.52178317 -0.012613583 -0.16115516, 0.52685601 -0.015111078 -0.17603046, 0.52672035 -0.014957 -0.17727259, 0.5317362 -0.015350703 -0.15548503, 0.5260902 -0.015433613 -0.17436615, 0.52515066 -0.015493546 -0.17514268, 0.52019542 -0.01109818 -0.16239139, 0.5250532 -0.015433434 -0.17635787, 0.52540225 -0.014781464 -0.1596207, 0.52433413 -0.01552977 -0.17350012, 0.52333665 -0.015529621 -0.17541629, 0.51888078 -0.009369228 -0.16361699, 0.5230372 -0.015298951 -0.17227924, 0.52744299 -0.01535048 -0.15876403, 0.52326065 -0.013857309 -0.16149253, 0.52200311 -0.01515745 -0.17311695, 0.52209437 -0.015298877 -0.17413977, 0.52250689 -0.015408281 -0.17455971, 0.53360683 -0.014781598 -0.15562537, 0.52159274 -0.015298802 -0.17505413, 0.52107936 -0.014616523 -0.17170942, 0.51769882 -0.007493306 -0.16534883, 0.52016324 -0.014616374 -0.17348519, 0.52139658 -0.012613568 -0.16271335, 0.51946044 -0.013741273 -0.17154539, 0.52724963 -0.01535045 -0.15994629, 0.51866251 -0.013391782 -0.17206469, 0.5185529 -0.013741169 -0.17325071, 0.51976377 -0.011098135 -0.16388953, 0.51812929 -0.012328077 -0.17058423, 0.51771027 -0.011097837 -0.16921958, 0.5168727 -0.0093689151 -0.16882885, 0.52937222 -0.015542615 -0.15905502, 0.5172649 -0.012327958 -0.17223233, 0.5173443 -0.0074930973 -0.16628608, 0.52494609 -0.01478133 -0.16187724, 0.53533083 -0.013857428 -0.15575445, 0.5182336 -0.0093691535 -0.16554368, 0.52286047 -0.013857115 -0.16310567, 0.52917111 -0.015542541 -0.16028532, 0.52095228 -0.012613479 -0.16425607, 0.5313012 -0.015350405 -0.15934566, 0.51787418 -0.009369079 -0.16649413, 0.526775 -0.015350271 -0.16229472, 0.53684205 -0.012613822 -0.15586752, 0.51910192 -0.011098001 -0.16585967, 0.52453047 -0.014781225 -0.16355324, 0.53109223 -0.015350346 -0.16062397, 0.52240032 -0.013857011 -0.16470289, 0.53315628 -0.014781404 -0.15962514, 0.5187344 -0.011098001 -0.16683185, 0.52867693 -0.015542392 -0.16272873, 0.516357 -0.007492993 -0.16858828, 0.52027041 -0.0126133 -0.16628528, 0.52634251 -0.015350197 -0.16403875, 0.53293967 -0.01478127 -0.16094968, 0.52405232 -0.014781106 -0.16521257, 0.5348658 -0.01385719 -0.15988281, 0.53057885 -0.015350137 -0.16316289, 0.52169448 -0.013856892 -0.16680348, 0.53100055 -0.013036016 -0.12364236, 0.53100067 -0.013035957 -0.12435791, 0.53100061 -0.013049949 0.12364221, 0.53100067 -0.013049949 0.12435785, 0.11158257 -0.034058694 -0.28770545, 0.11175451 -0.034612481 -0.28977057, 0.11270262 -0.034612585 -0.28772396, 0.1155405 -0.034776185 -0.29925618, 0.11433356 -0.034776051 -0.30099997, 0.11573554 -0.033851873 -0.30201173, 0.111048 -0.033737402 -0.28769937, 0.11022817 -0.033387821 -0.28834888, 0.11698119 -0.033851948 -0.30021173, 0.11148382 -0.033737484 -0.28670016, 0.11181444 -0.033852767 -0.28634444, 0.11041216 -0.032609235 -0.2857703, 0.080449089 -0.0310927 -0.31002706, 0.079088479 -0.032607947 -0.31159976, 0.080740452 -0.032607999 -0.31123608, 0.075408801 -0.02553593 -0.32931453, 0.070685245 -0.027486879 -0.32930881, 0.07068529 -0.025535945 -0.32950094, 0.12221504 -0.031093147 -0.29680118, 0.12130208 -0.02936409 -0.30027747, 0.12303165 -0.029364277 -0.29723364, 0.078845046 -0.03109264 -0.31038013, 0.084247798 -0.032322992 -0.30994266, 0.084014207 -0.033736203 -0.3117229, 0.085049897 -0.033736166 -0.31138188, 0.085772678 -0.033386651 -0.31062606, 0.1205125 -0.031092983 -0.29979742, 0.083188109 -0.032607909 -0.31056944, 0.10369543 -0.029363219 -0.31869024, 0.10203028 -0.02748714 -0.32043692, 0.10401246 -0.027487185 -0.31916279, 0.11815512 -0.033852097 -0.29836416, 0.11824404 -0.032608379 -0.30104944, 0.086222529 -0.032322984 -0.30922595, 0.087094501 -0.03373627 -0.31062391, 0.10173211 -0.029363129 -0.31995255, 0.087166578 -0.032608036 -0.30914059, 0.10594299 -0.027487312 -0.31781131, 0.10605624 -0.025536362 -0.3179664, 0.086689129 -0.031092774 -0.30799204, 0.11944991 -0.032608423 -0.29915148, 0.098514229 -0.032323312 -0.30182764, 0.097996779 -0.032608327 -0.30262205, 0.099341258 -0.033736605 -0.3032527, 0.095199175 -0.034775246 -0.31742221, 0.092014186 -0.033850987 -0.3207998, 0.095986545 -0.033850994 -0.3189615, 0.091350503 -0.034775209 -0.31920347, 0.097205542 -0.031093042 -0.30166253, 0.10588385 -0.034776252 -0.29938516, 0.10342197 -0.034776051 -0.30206344, 0.10475199 -0.035345066 -0.30338642, 0.099961922 -0.033387076 -0.30208579, 0.10007206 -0.032323409 -0.30041835, 0.1009682 -0.03373665 -0.30180088, 0.10731389 -0.035345193 -0.3005994, 0.10175443 -0.033736702 -0.30104548, 0.10112178 -0.032608431 -0.29977542, 0.078552686 -0.027487893 -0.30891559, 0.078515127 -0.025537077 -0.30872729, 0.07699395 -0.02748796 -0.30919504, 0.077083327 -0.029363882 -0.30975702, 0.078664191 -0.029363897 -0.30947378, 0.11123033 -0.035537351 -0.29876083, 0.11028828 -0.035345007 -0.30312446, 0.1128124 -0.0353452 -0.29990244, 0.081095397 -0.033851516 -0.31270948, 0.083629437 -0.033851508 -0.31201905, 0.10879232 -0.032324042 -0.2886664, 0.11010303 -0.033737253 -0.28966457, 0.10880107 -0.035537209 -0.30186191, 0.10861954 -0.032609012 -0.28959849, 0.10752052 -0.031093743 -0.28901613, 0.10059602 -0.032607477 -0.31810659, 0.096676715 -0.032607365 -0.32031035, 0.097243056 -0.03109194 -0.32141742, 0.10968969 -0.032324094 -0.28676692, 0.10124771 -0.031091992 -0.31916565, 0.1139773 -0.035345282 -0.29821923, 0.083351009 -0.030927267 -0.30910221, 0.082556792 -0.029363874 -0.30849531, 0.082825929 -0.031092715 -0.30937937, 0.084360853 -0.030422445 -0.30844441, 0.12111619 -0.032608543 -0.29621905, 0.080232628 -0.029363889 -0.30912867, 0.08558508 -0.031413365 -0.30867198, 0.11667783 -0.034776267 -0.29746613, 0.08528544 -0.030927289 -0.30843058, 0.10318051 -0.031092156 -0.31792325, 0.086239554 -0.030927274 -0.30805925, 0.10456595 -0.033852238 -0.29826602, 0.0863344 -0.029363994 -0.30713859, 0.097475402 -0.030927662 -0.30129659, 0.096617684 -0.02936421 -0.30094945, 0.10219619 -0.033852022 -0.30084401, 0.1096483 -0.035345275 -0.29761896, 0.10560752 -0.029363256 -0.31735176, 0.094344832 -0.035344381 -0.31575227, 0.090630308 -0.035344373 -0.31747124, 0.098323122 -0.03141376 -0.30100518, 0.098250218 -0.030927625 -0.30062732, 0.11235156 -0.035537522 -0.2971409, 0.098695278 -0.030422803 -0.2998167, 0.099749252 -0.030927707 -0.29923233, 0.10024004 -0.031093162 -0.29889819, 0.099584833 -0.029364269 -0.29824647, 0.099801801 -0.033851136 -0.31681603, 0.11977716 -0.033852208 -0.29550979, 0.10762922 -0.030928288 -0.28857478, 0.10670397 -0.02936485 -0.28858358, 0.10830013 -0.031414438 -0.28798023, 0.11507492 -0.035345387 -0.29649147, 0.10808772 -0.03092828 -0.28765932, 0.0800993 -0.02748796 -0.30857506, 0.082335107 -0.025537152 -0.30776694, 0.10341071 -0.032608617 -0.29728538, 0.10248745 -0.032607462 -0.31689042, 0.10818751 -0.030423518 -0.28674009, 0.10893638 -0.030928392 -0.28579584, 0.10926123 -0.031093854 -0.28529885, 0.1084061 -0.029365029 -0.28494835, 0.10873513 -0.027487364 -0.31564417, 0.109762 -0.025536526 -0.31503147, 0.083331913 -0.028997753 -0.30810013, 0.082391039 -0.027487967 -0.30795076, 0.10812718 -0.034776349 -0.29652116, 0.10506279 -0.031092238 -0.31660539, 0.085217044 -0.028997857 -0.30743065, 0.093456388 -0.03553671 -0.31401533, 0.089881316 -0.035536546 -0.31566983, 0.11072575 -0.035345394 -0.29606229, 0.097398669 -0.028998133 -0.30009875, 0.11824942 -0.034776416 -0.29470053, 0.098872699 -0.028998245 -0.29874635, 0.098895699 -0.034775343 -0.31534368, 0.099181399 -0.027488437 -0.29784507, 0.10709853 -0.028998766 -0.28749815, 0.11340802 -0.035537545 -0.29547805, 0.10794047 -0.028998937 -0.28568366, 0.10246264 -0.031093318 -0.29648012, 0.10787936 -0.0274891 -0.28473282, 0.082784943 -0.027294848 -0.30779055, 0.10164311 -0.03385118 -0.31563237, 0.10672525 -0.03385229 -0.2955094, 0.083584346 -0.02787127 -0.3076559, 0.10837312 -0.029363301 -0.31520528, 0.083724156 -0.027294878 -0.30748105, 0.10916255 -0.034776468 -0.29502529, 0.084493183 -0.026712324 -0.30711603, 0.10432964 -0.032607574 -0.31560087, 0.086042047 -0.025537167 -0.30643561, 0.085578255 -0.027294856 -0.30679286, 0.086115777 -0.027488012 -0.30661312, 0.11659175 -0.035345498 -0.29382235, 0.096666142 -0.027295191 -0.30011934, 0.096255593 -0.027488273 -0.30051029, 0.092567891 -0.035344649 -0.31227842, 0.089132287 -0.035344575 -0.31386846, 0.096133374 -0.025537435 -0.30036196, 0.11174098 -0.035345513 -0.29446441, 0.097459652 -0.026712719 -0.29931182, 0.099045172 -0.025537554 -0.29770952, 0.097912528 -0.035344508 -0.31374615, 0.10175818 -0.029364441 -0.29588205, 0.098362081 -0.027871605 -0.29876134, 0.098142043 -0.027295176 -0.29880294, 0.10549638 -0.032608699 -0.29462272, 0.098855346 -0.027295295 -0.29811797, 0.10643008 -0.027295802 -0.28779846, 0.10067967 -0.03477541 -0.31419668, 0.10772184 -0.033852402 -0.29406959, 0.10620107 -0.027488958 -0.28831699, 0.10603134 -0.025538061 -0.28822687, 0.10685271 -0.02671333 -0.2867482, 0.10778524 -0.03109229 -0.3144924, 0.10770167 -0.025538292 -0.28465968, 0.11486792 -0.035537783 -0.292909, 0.1074748 -0.02787229 -0.28589347, 0.10343631 -0.033851292 -0.31437701, 0.10728758 -0.027295854 -0.28601635, 0.10768318 -0.027295951 -0.28511003, 0.11013812 -0.034776498 -0.29348978, 0.09171354 -0.034775626 -0.3106083, 0.088412128 -0.034775641 -0.3121362, 0.10132436 -0.027488526 -0.29551369, 0.10168198 -0.02553774 -0.29478353, 0.096890166 -0.035536777 -0.3120845, 0.1044879 -0.031093415 -0.29389483, 0.10645906 -0.032608848 -0.29323179, 0.11314393 -0.03534561 -0.29199556, 0.099634334 -0.03534453 -0.31263903, 0.10866087 -0.033852447 -0.29259154, 0.1069941 -0.032607716 -0.31353289, 0.10373861 -0.029364575 -0.29335406, 0.075393721 -0.027486887 -0.32912341, 0.10542269 -0.031093556 -0.29254434, 0.10241713 -0.03477544 -0.31298059, 0.075348899 -0.029362787 -0.32855621, 0.070685245 -0.029362787 -0.32873982, 0.1114863 -0.034776669 -0.29111737, 0.0909262 -0.033851672 -0.30906901, 0.087748408 -0.033851605 -0.31053987, 0.10736617 -0.032608937 -0.29180422, 0.095867619 -0.035344679 -0.31042308, 0.075276181 -0.031091686 -0.32763517, 0.070685282 -0.031091746 -0.32781604, 0.10327706 -0.027488653 -0.29302093, 0.080072969 -0.027486857 -0.32856765, 0.080103084 -0.02553596 -0.32875735, 0.1040182 -0.025537837 -0.29161233, 0.10465258 -0.029364649 -0.29203337, 0.098547339 -0.035536859 -0.31101921, 0.10995854 -0.033852596 -0.29030791, 0.07517831 -0.032607216 -0.3263953, 0.07068529 -0.032607164 -0.32657245, 0.10603002 -0.033851426 -0.31236389, 0.1063034 -0.031093601 -0.29115805, 0.079983607 -0.029362824 -0.3280057, 0.10417838 -0.027488779 -0.29171878, 0.082392439 -0.027486842 -0.32815185, 0.084738821 -0.0255359 -0.3278318, 0.10131122 -0.035344612 -0.31146529, 0.075058997 -0.03385089 -0.32488465, 0.070685275 -0.033850837 -0.32505718, 0.090236045 -0.032608125 -0.30772001, 0.10551385 -0.029364768 -0.29067782, 0.079838559 -0.031091776 -0.32709303, 0.094884455 -0.034775723 -0.30882517, 0.10502758 -0.027488817 -0.29038188, 0.082281068 -0.029362809 -0.32759383, 0.097460121 -0.035344753 -0.30939928, 0.084693797 -0.027486835 -0.32764521, 0.10493004 -0.034775537 -0.31103018, 0.074922845 -0.034775015 -0.32316115, 0.070685297 -0.034775104 -0.32332826, 0.089863904 -0.028750423 -0.32579306, 0.087938309 -0.029362891 -0.32617199, 0.088104025 -0.027486954 -0.32671618, 0.079643339 -0.032607105 -0.32586515, 0.10016109 -0.035536807 -0.30988935, 0.091768801 -0.028124247 -0.32531074, 0.093646675 -0.027486969 -0.32472566, 0.093428224 -0.029362906 -0.32420042, 0.090565681 -0.030250032 -0.32485881, 0.09307342 -0.031091813 -0.32334712, 0.082100198 -0.031091761 -0.32668784, 0.090819344 -0.0284389 -0.32556474, 0.08966966 -0.031092789 -0.30661252, 0.084560581 -0.029362876 -0.32709208, 0.087669179 -0.031091783 -0.32528797, 0.090197667 -0.031880062 -0.32383397, 0.087306961 -0.032607231 -0.32409826, 0.11627766 -0.027487706 -0.30820921, 0.11322518 -0.025536764 -0.31181362, 0.11642417 -0.025536839 -0.30833331, 0.11308885 -0.027487572 -0.31167832, 0.092596039 -0.032607291 -0.32219878, 0.074775256 -0.03534421 -0.32129121, 0.070685372 -0.035344277 -0.32145238, 0.0897291 -0.033266295 -0.32252946, 0.093978398 -0.033851739 -0.3073529, 0.086865693 -0.033850979 -0.32264861, 0.079405539 -0.033850875 -0.32436848, 0.096414737 -0.034775767 -0.30784145, 0.089178234 -0.034355517 -0.32099551, 0.081856817 -0.032607172 -0.32546845, 0.11000572 -0.028750945 -0.31411609, 0.10373659 -0.035344686 -0.30958286, 0.089287378 -0.025535997 -0.3265444, 0.11157943 -0.028124791 -0.31293944, 0.11268538 -0.029363532 -0.31127697, 0.084344119 -0.031091746 -0.32619372, 0.11029516 -0.030250628 -0.31298414, 0.11203028 -0.031092498 -0.31062558, 0.099011041 -0.035344806 -0.3083134, 0.11080027 -0.028439414 -0.31353873, 0.10956169 -0.031880606 -0.31217912, 0.11114854 -0.032607909 -0.30974844, 0.07462161 -0.035536435 -0.3193464, 0.070685349 -0.035344485 -0.3175506, 0.070685312 -0.035536502 -0.31950161, 0.10862824 -0.033266846 -0.31115428, 0.089248762 -0.029363986 -0.30578995, 0.11007415 -0.03385153 -0.30867985, 0.079134151 -0.034775075 -0.32266116, 0.1075306 -0.034356106 -0.30994955, 0.11584391 -0.02936377 -0.30784085, 0.093184233 -0.032608185 -0.30606225, 0.081560135 -0.03385089 -0.32398239, 0.12429176 -0.028125677 -0.29568478, 0.12353451 -0.02748834 -0.29750007, 0.095451429 -0.033851828 -0.30640599, 0.084052861 -0.032607194 -0.32498479, 0.10249537 -0.035536919 -0.30807772, 0.12494915 -0.028751973 -0.29383296, 0.12603199 -0.027488563 -0.29216662, 0.12550534 -0.029364508 -0.29195091, 0.12395362 -0.030251574 -0.29444486, 0.12463301 -0.028440405 -0.29476294, 0.074468076 -0.03534447 -0.3174015, 0.12465023 -0.031093437 -0.29160076, 0.12296736 -0.03188156 -0.29398307, 0.078839712 -0.035344269 -0.32080844, 0.12349937 -0.032608856 -0.29112956, 0.12171197 -0.033267725 -0.29339537, 0.08122173 -0.03477506 -0.32228717, 0.097905152 -0.03477582 -0.3067981, 0.1220971 -0.033852506 -0.29055554, 0.08898963 -0.027488139 -0.30528322, 0.12023585 -0.034356948 -0.29270419, 0.089600213 -0.025537279 -0.30474624, 0.11513947 -0.031092692 -0.30724302, 0.089619353 -0.027164955 -0.32629457, 0.083697908 -0.033850875 -0.32351163, 0.090093158 -0.027003307 -0.32616103, 0.092532411 -0.031092916 -0.30500302, 0.090565182 -0.026841324 -0.32602125, 0.074320406 -0.034775529 -0.31553131, 0.070685297 -0.034775537 -0.31567472, 0.090027921 -0.02759378 -0.32607165, 0.09460704 -0.032608259 -0.3051475, 0.0916299 -0.026407573 -0.32568601, 0.093720458 -0.025536057 -0.32490292, 0.078533456 -0.035536457 -0.31888193, 0.087481305 -0.03495178 -0.32015863, 0.086362086 -0.03477506 -0.32099494, 0.10125427 -0.035344865 -0.30657247, 0.085815817 -0.035344321 -0.31920022, 0.1191835 -0.027487885 -0.30449975, 0.08085449 -0.035344232 -0.3204475, 0.11933932 -0.02553704 -0.30461207, 0.088566042 -0.035105739 -0.31929091, 0.08995501 -0.034951802 -0.31927022, 0.10997251 -0.027165461 -0.31467292, 0.11035877 -0.027003903 -0.31436807, 0.096885949 -0.033851806 -0.30540171, 0.083292991 -0.034775149 -0.32183087, 0.11074095 -0.026841898 -0.31405765, 0.11419149 -0.032608021 -0.30643812, 0.11026417 -0.027594339 -0.31431049, 0.074184224 -0.033851516 -0.31380776, 0.070685312 -0.033851501 -0.31394583, 0.11159541 -0.026408132 -0.31333929, 0.092048019 -0.029364031 -0.30421588, 0.078227229 -0.035344455 -0.31695497, 0.1056424 -0.034952264 -0.30982831, 0.093913913 -0.031092841 -0.30411473, 0.080472685 -0.035536546 -0.31853434, 0.10631097 -0.035106245 -0.30861071, 0.10758545 -0.034952383 -0.30805841, 0.10884842 -0.03477579 -0.3074607, 0.1075184 -0.035344873 -0.30613795, 0.10006079 -0.034775909 -0.30512497, 0.12454368 -0.027004782 -0.29569823, 0.12424737 -0.025537524 -0.29653996, 0.11872208 -0.029363897 -0.30416682, 0.1251452 -0.026517753 -0.294568, 0.12620981 -0.025537673 -0.29223913, 0.12553397 -0.027004901 -0.29355639, 0.082853608 -0.035344277 -0.32000723, 0.11844572 -0.034953106 -0.29331726, 0.07406494 -0.032607976 -0.31229705, 0.070685327 -0.032607917 -0.31243044, 0.09599258 -0.032608222 -0.30417761, 0.077932835 -0.034775522 -0.31510225, 0.11859564 -0.035107154 -0.29193625, 0.12052458 -0.027487997 -0.302562, 0.12195251 -0.025537249 -0.30067262, 0.11956041 -0.034953255 -0.29093689, 0.12049714 -0.034776662 -0.28990039, 0.11876119 -0.035345774 -0.28918934, 0.086882845 -0.035428297 -0.31835356, 0.080090769 -0.03534447 -0.31662124, 0.085247621 -0.035536561 -0.31733388, 0.1130363 -0.033851732 -0.30545747, 0.087916225 -0.035488393 -0.31748125, 0.09174978 -0.027488176 -0.30373117, 0.092974804 -0.025537316 -0.30271506, 0.089268416 -0.035428334 -0.31749696, 0.10439685 -0.035428677 -0.30839136, 0.093398973 -0.029364105 -0.30334735, 0.082396656 -0.035536531 -0.31811064, 0.098960944 -0.03385197 -0.30379137, 0.10501625 -0.035488892 -0.30718923, 0.10627066 -0.035428789 -0.3066844, 0.073967032 -0.031092677 -0.311057, 0.07068529 -0.031092707 -0.31118661, 0.10613523 -0.03553712 -0.30476227, 0.11674397 -0.035429534 -0.29246864, 0.11797277 -0.031092849 -0.30362615, 0.09792304 -0.027487103 -0.32274663, 0.098010503 -0.025536131 -0.32291758, 0.1168544 -0.035489712 -0.29112092, 0.077661395 -0.033851493 -0.31339484, 0.095259473 -0.031093005 -0.30317283, 0.11781889 -0.035429645 -0.29017299, 0.1169558 -0.035537992 -0.28845006, 0.079723492 -0.034775432 -0.31478137, 0.086266577 -0.035524536 -0.31649524, 0.1200504 -0.029363971 -0.30224761, 0.084679373 -0.035344478 -0.31546754, 0.088561393 -0.035524543 -0.31567103, 0.10311434 -0.035524923 -0.30691186, 0.12178823 -0.027488086 -0.30057299, 0.11171827 -0.034775835 -0.30433857, 0.10491686 -0.035524983 -0.30527005, 0.081939675 -0.035344463 -0.31621403, 0.11499172 -0.035525691 -0.29159477, 0.093081877 -0.027488198 -0.30287474, 0.073894292 -0.029363904 -0.31013599, 0.07068532 -0.029363889 -0.31026235, 0.11602581 -0.03552587 -0.28938678, 0.11515038 -0.035345864 -0.28771082, 0.085171558 -0.035293657 -0.31506294, 0.11696426 -0.032608207 -0.30289844, 0.097663887 -0.02936304 -0.32223997, 0.084133036 -0.034775551 -0.31367287, 0.077423602 -0.032608006 -0.31189817, 0.086291201 -0.035152327 -0.31410426, 0.087779552 -0.035403077 -0.31475142, 0.079385094 -0.033851441 -0.31308594, 0.087397195 -0.035293754 -0.31429452, 0.094714686 -0.029364143 -0.30242631, 0.088495195 -0.035293762 -0.31386945, 0.11928038 -0.031092968 -0.30173677, 0.10155337 -0.035294119 -0.30600998, 0.10266769 -0.035403524 -0.30579054, 0.081500366 -0.034775589 -0.31438997, 0.10244305 -0.035294112 -0.30523887, 0.073849432 -0.027487975 -0.30956843, 0.070685245 -0.02553707 -0.30950084, 0.07068523 -0.027487922 -0.30969316, 0.074619316 -0.025537085 -0.30930692, 0.10279271 -0.035152797 -0.30417237, 0.10416409 -0.035294283 -0.30363187, 0.11320421 -0.035294849 -0.29136139, 0.077228419 -0.031092715 -0.31066993, 0.11414883 -0.035404321 -0.29073077, 0.1137296 -0.035294909 -0.29030767, 0.094379187 -0.027488228 -0.30196655, 0.11364301 -0.035153497 -0.2891888, 0.11470172 -0.035295028 -0.28816313, 0.11341438 -0.03477684 -0.28699982, 0.10213098 -0.02553625 -0.32060066, 0.084920257 -0.0346114 -0.31303158, 0.087046176 -0.034611408 -0.31227809, 0.10082555 -0.034611773 -0.30398443, 0.10248669 -0.034611765 -0.30245885, 0.085006066 -0.034057599 -0.31191462, 0.10145959 -0.034057956 -0.30201173, -0.072031632 -0.034058478 -0.31424692, -0.073877484 -0.034612279 -0.31518859, -0.071624212 -0.03461225 -0.31529027, -0.081220813 -0.034776103 -0.32228696, -0.083292037 -0.034776162 -0.32183087, -0.083696984 -0.033851948 -0.32351163, -0.072228819 -0.033737075 -0.31374997, -0.073140413 -0.033387538 -0.31323734, -0.071138777 -0.033737037 -0.31377465, -0.070684396 -0.033852477 -0.31394571, -0.070684366 -0.032608848 -0.31243044, -0.076419704 -0.03109267 -0.32753307, -0.079837672 -0.031092811 -0.32709303, -0.07998278 -0.029363755 -0.3280057, -0.076510526 -0.029363845 -0.32845262, -0.10448707 -0.031094801 -0.29389483, -0.10542178 -0.031094868 -0.29254434, -0.10645808 -0.032610271 -0.29323202, -0.10315933 -0.032324899 -0.29715675, -0.10298709 -0.031094644 -0.29584903, -0.10395079 -0.032609951 -0.29663512, -0.07940457 -0.033851918 -0.32436848, -0.081855901 -0.032608163 -0.32546845, -0.07964249 -0.032608155 -0.32586503, -0.10549551 -0.032610137 -0.29462272, -0.10458865 -0.033738147 -0.29797623, -0.10342499 -0.033388566 -0.29860324, -0.10369457 -0.029364552 -0.31869024, -0.10594218 -0.027488638 -0.31781107, -0.10401169 -0.027488519 -0.31916273, -0.10175832 -0.032324795 -0.2987223, -0.10314561 -0.033738118 -0.29961106, -0.081559233 -0.03385197 -0.32398239, -0.10239426 -0.033738028 -0.30040121, -0.10112088 -0.032609787 -0.29977542, -0.084999695 -0.034776624 -0.31339937, -0.089131422 -0.035345744 -0.31386846, -0.085581288 -0.035345662 -0.31518289, -0.10560669 -0.029364567 -0.31735164, -0.08841119 -0.034776744 -0.3121362, -0.10202949 -0.027488504 -0.32043692, -0.10213016 -0.025537614 -0.32060066, -0.090053186 -0.032324236 -0.30750513, -0.091058426 -0.03373744 -0.30881053, -0.089743219 -0.033387955 -0.30894282, -0.090396285 -0.031093959 -0.30623153, -0.09098427 -0.032609347 -0.30732742, -0.10574066 -0.034776915 -0.3103475, -0.11007316 -0.033852968 -0.30867991, -0.10686663 -0.03385279 -0.31165937, -0.10884748 -0.034777109 -0.3074607, -0.088158607 -0.032324109 -0.3084127, -0.089098379 -0.033737425 -0.30976596, -0.088101275 -0.033737373 -0.31020716, -0.087165624 -0.032609191 -0.30914059, -0.10417753 -0.027490098 -0.29171878, -0.10401739 -0.025539223 -0.29161233, -0.10502676 -0.027490202 -0.29038197, -0.082395688 -0.035537612 -0.31811064, -0.086186126 -0.035537679 -0.31703776, -0.082852639 -0.035345342 -0.32000723, -0.10551299 -0.02936611 -0.29067782, -0.10465171 -0.029366013 -0.29203352, -0.073978484 -0.032323863 -0.31202891, -0.074784137 -0.031093653 -0.31098452, -0.074906528 -0.032608937 -0.31222227, -0.1051251 -0.033853475 -0.29759306, -0.074405491 -0.033737134 -0.31362039, -0.080853567 -0.035345364 -0.32044753, -0.071880661 -0.032323819 -0.31213942, -0.10432873 -0.032608915 -0.31560087, -0.10866354 -0.031093705 -0.31375283, -0.10506194 -0.031093527 -0.31660539, -0.1026228 -0.030929167 -0.29612082, -0.10227101 -0.029365797 -0.29526478, -0.076297395 -0.032608118 -0.32629573, -0.10785355 -0.032609094 -0.31280917, -0.10233582 -0.031415287 -0.2969701, -0.079133168 -0.034776155 -0.32266116, -0.10373777 -0.029365901 -0.29335406, -0.1019576 -0.030929107 -0.29689914, -0.084463716 -0.033852641 -0.31175584, -0.10114952 -0.030424248 -0.29734844, -0.087747447 -0.033852685 -0.31053975, -0.10317966 -0.031093378 -0.31792301, -0.10057076 -0.030929025 -0.29840562, -0.10023923 -0.031094451 -0.29889813, -0.081938744 -0.035345588 -0.31621403, -0.099584013 -0.02936564 -0.29824647, -0.089955494 -0.030928504 -0.30634263, -0.10173117 -0.02936447 -0.31995255, -0.089959249 -0.029365193 -0.30541709, -0.10451887 -0.035346072 -0.30892387, -0.10751745 -0.035346214 -0.30613795, -0.089364462 -0.031414624 -0.30701664, -0.080471747 -0.035537537 -0.31853434, -0.08904247 -0.030928496 -0.30680606, -0.10343537 -0.033852678 -0.31437701, -0.088123798 -0.030423615 -0.30691043, -0.087183557 -0.030928422 -0.30766466, -0.086688213 -0.031093936 -0.30799204, -0.076148324 -0.033851873 -0.32478777, -0.086333454 -0.029365007 -0.30713859, -0.074334644 -0.030928146 -0.31091788, -0.07883881 -0.03534526 -0.32080844, -0.074693292 -0.029364806 -0.3100647, -0.073530018 -0.031414311 -0.31131342, -0.10327633 -0.027489994 -0.29302093, -0.1016812 -0.025539037 -0.29478353, -0.08399383 -0.032609086 -0.31031504, -0.073313609 -0.030928146 -0.31099513, -0.10248657 -0.032608818 -0.31689042, -0.081499383 -0.034776587 -0.31438997, -0.072425127 -0.030423287 -0.31073919, -0.098965928 -0.027488317 -0.32219967, -0.098009773 -0.025537368 -0.32291758, -0.071267515 -0.030928109 -0.31107429, -0.070684403 -0.031093601 -0.31118658, -0.070684448 -0.029364761 -0.31026235, -0.1014246 -0.028999645 -0.29605028, -0.080089837 -0.03534558 -0.31662124, -0.10124692 -0.03109334 -0.31916544, -0.10008021 -0.028999601 -0.29753169, -0.099180602 -0.027489651 -0.29784518, -0.10324827 -0.035538342 -0.30744341, -0.10613425 -0.035538469 -0.30476227, -0.075978294 -0.034775984 -0.32306734, -0.088876106 -0.028999072 -0.30581746, -0.087066047 -0.02899896 -0.30666912, -0.086115018 -0.027489174 -0.30661312, -0.078532562 -0.035537478 -0.31888193, -0.073539458 -0.028998729 -0.31001857, -0.10241613 -0.034776825 -0.31298059, -0.083608352 -0.031093802 -0.30913249, -0.071541138 -0.028998699 -0.31011012, -0.081094436 -0.033852551 -0.31270948, -0.070684433 -0.027488869 -0.30969316, -0.10144135 -0.027296741 -0.29531771, -0.10183004 -0.027489927 -0.29490501, -0.079722665 -0.034776527 -0.31478161, -0.10164215 -0.033852492 -0.31563237, -0.10063808 -0.02671418 -0.29611549, -0.098696828 -0.029364254 -0.32169834, -0.099044263 -0.02553888 -0.29770955, -0.10009249 -0.027873013 -0.297021, -0.07579378 -0.035345148 -0.32120046, -0.1005951 -0.032608736 -0.31810659, -0.10013296 -0.027296629 -0.29680067, -0.099451788 -0.027296644 -0.29751751, -0.078226343 -0.035345439 -0.31695497, -0.10197777 -0.035346266 -0.30596292, -0.10475115 -0.035346407 -0.30338642, -0.089172877 -0.027296085 -0.30514729, -0.089599326 -0.025538359 -0.30474624, -0.089690201 -0.027489286 -0.3049157, -0.083321802 -0.02936494 -0.30825388, -0.088124864 -0.026713554 -0.3055757, -0.086041212 -0.025538269 -0.30643561, -0.10131027 -0.03534596 -0.31146529, -0.080739528 -0.032608975 -0.31123608, -0.087273464 -0.027872372 -0.30620229, -0.08739534 -0.027296063 -0.30601427, -0.08649125 -0.027295996 -0.30641493, -0.079384267 -0.033852454 -0.31308594, -0.10067876 -0.034776729 -0.31419668, -0.074070692 -0.02729575 -0.30951384, -0.075601898 -0.035537478 -0.31925923, -0.09825974 -0.031093311 -0.32088414, -0.074637368 -0.027488891 -0.30949834, -0.074618496 -0.025538001 -0.30930692, -0.072938636 -0.026713159 -0.30950692, -0.070684463 -0.025538009 -0.30950108, -0.077931926 -0.034776453 -0.31510225, -0.0998009 -0.033852432 -0.31681603, -0.071911901 -0.027872164 -0.30975869, -0.08314541 -0.027489092 -0.30771288, -0.072096579 -0.027295735 -0.30963185, -0.08233425 -0.025538217 -0.30776694, -0.10075599 -0.034777213 -0.30453947, -0.10342104 -0.034777377 -0.30206344, -0.071107924 -0.027295765 -0.3096545, -0.080448255 -0.031093758 -0.31002706, -0.10016017 -0.03553823 -0.30988935, -0.079087511 -0.032609064 -0.31159976, -0.075410008 -0.035345461 -0.31731778, -0.09963347 -0.035345796 -0.31263903, -0.077660546 -0.033852484 -0.31339484, -0.097671658 -0.032608662 -0.31978855, -0.080231801 -0.02936488 -0.30912867, -0.078844197 -0.031093653 -0.31038013, -0.075225569 -0.034776431 -0.31545085, -0.09889479 -0.03477658 -0.31534368, -0.12407506 -0.027489971 -0.29645342, -0.12550455 -0.029366154 -0.29195112, -0.12603121 -0.02749021 -0.2921665, -0.12620898 -0.02553929 -0.29223934, -0.12424661 -0.025539059 -0.29653996, -0.099629939 -0.033853259 -0.30322745, -0.10219528 -0.033853393 -0.30084401, -0.077422693 -0.032608952 -0.31189829, -0.12356698 -0.029365901 -0.29619709, -0.099010117 -0.035346095 -0.3083134, -0.080098554 -0.027488973 -0.30857506, -0.078514375 -0.025538009 -0.3087272, -0.078663327 -0.02936485 -0.30947378, -0.1227421 -0.031094801 -0.29578075, -0.1234986 -0.032610353 -0.29112956, -0.12464939 -0.031095002 -0.29160073, -0.075055435 -0.033852499 -0.3137303, -0.1217875 -0.027489696 -0.30057284, -0.12195174 -0.025538761 -0.30067274, -0.098546311 -0.035538044 -0.31101921, -0.096955128 -0.033852357 -0.31845337, -0.077227511 -0.031093623 -0.31066993, -0.12163183 -0.032610204 -0.29522043, -0.078551963 -0.027488898 -0.30891559, -0.12130125 -0.029365625 -0.30027747, -0.097911641 -0.035345796 -0.31374615, -0.12052376 -0.027489576 -0.302562, -0.11933856 -0.025538508 -0.30461189, -0.077082455 -0.029364858 -0.30975702, -0.098643109 -0.032609556 -0.30207765, -0.12027907 -0.033853855 -0.29453748, -0.12049628 -0.034778152 -0.28990039, -0.12209611 -0.033854101 -0.29055554, -0.097904183 -0.034777101 -0.3067981, -0.076993197 -0.027488921 -0.30919504, -0.12051167 -0.031094525 -0.29979727, -0.12004951 -0.029365573 -0.30224741, -0.097459204 -0.035346042 -0.30939904, -0.096137576 -0.034776468 -0.31693, -0.11918268 -0.027489472 -0.30449975, -0.11873572 -0.034777936 -0.29375845, -0.11550936 -0.028752711 -0.30858222, -0.11658964 -0.029365245 -0.3069438, -0.11703059 -0.027489301 -0.30730346, -0.11944896 -0.032610003 -0.29915148, -0.1143411 -0.02812646 -0.31016222, -0.11308803 -0.02748904 -0.31167832, -0.11268456 -0.029364962 -0.31127709, -0.096889183 -0.035537992 -0.3120845, -0.11437871 -0.030252296 -0.30887753, -0.11202939 -0.031093884 -0.31062534, -0.097833171 -0.031094361 -0.30113378, -0.11493605 -0.02844109 -0.30937973, -0.11587359 -0.031094056 -0.3063598, -0.11356973 -0.03188226 -0.30814853, -0.1149098 -0.032609563 -0.30557382, -0.11927952 -0.031094421 -0.30173677, -0.11114766 -0.032609265 -0.30974856, -0.089227043 -0.027488042 -0.32636192, -0.093645871 -0.02748822 -0.32472566, -0.093719684 -0.025537256 -0.32490292, -0.11872122 -0.029365364 -0.30416682, -0.089286648 -0.025537107 -0.3265444, -0.11253995 -0.033268455 -0.30722076, -0.11373545 -0.033853214 -0.30461612, -0.096885063 -0.033853043 -0.30540171, -0.11132914 -0.034357663 -0.3061296, -0.11706102 -0.035347123 -0.29291305, -0.11876027 -0.035347227 -0.28918934, -0.096413925 -0.034777049 -0.30784169, -0.097070254 -0.028751839 -0.32279655, -0.11815419 -0.033853564 -0.29836416, -0.095250472 -0.035345677 -0.31527704, -0.11824314 -0.032609817 -0.30104944, -0.095385097 -0.028125476 -0.32380688, -0.093427368 -0.029364128 -0.3242003, -0.095912918 -0.030251373 -0.32263538, -0.11642338 -0.025538269 -0.30833331, -0.096234657 -0.028440174 -0.32331285, -0.093072608 -0.031093035 -0.32334712, -0.095866635 -0.035345975 -0.31042308, -0.095445774 -0.031881433 -0.32165167, -0.092595153 -0.032608476 -0.32219899, -0.11797196 -0.031094309 -0.30362615, -0.094851159 -0.033267636 -0.32039946, -0.092013255 -0.033852275 -0.3207998, -0.097231328 -0.029365446 -0.30043241, -0.11531947 -0.035539258 -0.29203394, -0.11514945 -0.035347391 -0.28771061, -0.11695487 -0.035539459 -0.28845006, -0.09415213 -0.034356769 -0.31892711, -0.11667687 -0.034777772 -0.29746613, -0.089050591 -0.029363949 -0.32582095, -0.095991671 -0.032609571 -0.30417761, -0.074599616 -0.028125111 -0.32903165, -0.076566622 -0.027487826 -0.32901898, -0.11698029 -0.03385346 -0.30021173, -0.095450476 -0.033852961 -0.30640599, -0.094328001 -0.035537865 -0.31355813, -0.07263688 -0.028751317 -0.32893839, -0.070684433 -0.027487796 -0.32930881, -0.070684373 -0.029363777 -0.32873982, -0.073580332 -0.030250918 -0.32824913, -0.11696336 -0.032609779 -0.30289856, -0.073617302 -0.028439771 -0.32899827, -0.070684455 -0.031092655 -0.32781604, -0.11357796 -0.035347153 -0.29115489, -0.073526785 -0.031880926 -0.32716143, -0.070684388 -0.032608118 -0.32657245, -0.0734585 -0.033267152 -0.32577696, -0.094883569 -0.03477696 -0.3088254, -0.115074 -0.035346862 -0.29649147, -0.070684336 -0.033851881 -0.32505718, -0.096860752 -0.027489591 -0.30000049, -0.07337828 -0.034356382 -0.32414916, -0.096132562 -0.025538657 -0.30036196, -0.088764064 -0.031092931 -0.32494262, -0.11553963 -0.034777645 -0.29925618, -0.11606604 -0.027167309 -0.30854598, -0.1157631 -0.027005639 -0.30893388, -0.095258601 -0.031094234 -0.30317283, -0.11545482 -0.026843537 -0.3093175, -0.11573458 -0.033853341 -0.30201173, -0.11570501 -0.027596142 -0.30883947, -0.11474117 -0.026409749 -0.31017581, -0.11322427 -0.02553815 -0.31181362, -0.11190328 -0.034778137 -0.29030946, -0.11181355 -0.033854295 -0.28634444, -0.11341351 -0.034778249 -0.28699973, -0.094606072 -0.032609422 -0.30514756, -0.093405433 -0.035345856 -0.31183904, -0.11119768 -0.03495397 -0.30424213, -0.11094204 -0.035346527 -0.30233777, -0.11239577 -0.03477734 -0.30352333, -0.084692985 -0.027487982 -0.32764521, -0.084738031 -0.025536995 -0.3278318, -0.11340707 -0.035539005 -0.29547805, -0.10998369 -0.035107862 -0.30491734, -0.10943805 -0.034953844 -0.30619475, -0.11397636 -0.035346705 -0.29821923, -0.097598284 -0.027166378 -0.32297659, -0.097169571 -0.0270047 -0.32321849, -0.093977474 -0.033852946 -0.30735281, -0.096737586 -0.026842613 -0.32345441, -0.097152159 -0.027595151 -0.32310927, -0.11433265 -0.034777511 -0.30099997, -0.088378474 -0.032608304 -0.3237603, -0.095749006 -0.026408907 -0.32397309, -0.094755381 -0.034953114 -0.31713367, -0.094713785 -0.029365424 -0.30242631, -0.11035992 -0.033854011 -0.2895301, -0.11174007 -0.035347011 -0.29446441, -0.093375221 -0.035107125 -0.31729096, -0.093913086 -0.031094123 -0.30411473, -0.09238109 -0.034953076 -0.31826103, -0.11235058 -0.035538998 -0.2971409, -0.091349557 -0.034776349 -0.31920347, -0.090629376 -0.035345521 -0.31747124, -0.092518359 -0.034776922 -0.31018621, -0.074516788 -0.027004246 -0.32927012, -0.084559701 -0.029363934 -0.32709199, -0.075408019 -0.025536936 -0.32931477, -0.073242821 -0.026517045 -0.3293983, -0.070684455 -0.025536831 -0.32950094, -0.072159313 -0.027004134 -0.3293747, -0.074623778 -0.034952778 -0.32272491, -0.11281139 -0.035346638 -0.29990244, -0.093183249 -0.032609377 -0.30606225, -0.073289044 -0.035106685 -0.3223401, -0.10900715 -0.032610472 -0.28884736, -0.10926037 -0.031095292 -0.28529885, -0.11041118 -0.032610711 -0.2857703, -0.071998611 -0.034952674 -0.32285431, -0.070684373 -0.034776013 -0.32332826, -0.07068444 -0.035345118 -0.32145238, -0.082391612 -0.027487893 -0.32815185, -0.080102272 -0.02553698 -0.32875732, -0.10975417 -0.035430346 -0.30300424, -0.10943022 -0.035538722 -0.30110475, -0.11013724 -0.034777869 -0.29348978, -0.087908596 -0.033852082 -0.32231987, -0.11072481 -0.035346877 -0.29606229, -0.10855544 -0.035490435 -0.3036302, -0.094378375 -0.02748948 -0.30196655, -0.092974007 -0.025538493 -0.30271506, -0.10805734 -0.035430204 -0.30488726, -0.093398161 -0.029365327 -0.30334732, -0.093897708 -0.035429601 -0.31543645, -0.092550598 -0.035489675 -0.31555423, -0.091700889 -0.033852819 -0.30866265, -0.11122944 -0.035538878 -0.29876083, -0.091608047 -0.035429504 -0.31652373, -0.089880347 -0.035537791 -0.31567007, -0.074483491 -0.035429146 -0.32082844, -0.084343269 -0.031092849 -0.32619372, -0.10789699 -0.031095136 -0.28828672, -0.073194392 -0.03548925 -0.32041979, -0.10963602 -0.027488831 -0.3148858, -0.10976117 -0.02553786 -0.31503147, -0.071951784 -0.035429109 -0.32095337, -0.070684381 -0.035537411 -0.31950161, -0.092531569 -0.031094078 -0.30500302, -0.10866006 -0.033853877 -0.29259154, -0.10826782 -0.035526689 -0.30172968, -0.082280256 -0.029363859 -0.3275941, -0.10791849 -0.035346571 -0.29987165, -0.10916161 -0.034777839 -0.29502529, -0.1066355 -0.035526488 -0.30354121, -0.09301459 -0.035525884 -0.31368917, -0.08007212 -0.027487818 -0.32856765, -0.087372579 -0.034776326 -0.32067606, -0.09081202 -0.035525721 -0.31473479, -0.074338913 -0.03552543 -0.31887585, -0.093081005 -0.027489413 -0.30287474, -0.10964741 -0.035346825 -0.29761916, -0.071903549 -0.035525393 -0.31899589, -0.10707203 -0.029366281 -0.28787032, -0.1078786 -0.027490575 -0.28473282, -0.10840527 -0.029366378 -0.28494835, -0.070684433 -0.035345349 -0.3175506, -0.084051937 -0.032608274 -0.32498479, -0.1073575 -0.035295758 -0.30017367, -0.10646479 -0.034777608 -0.29868585, -0.10714408 -0.035405081 -0.30128917, -0.10926541 -0.029364791 -0.3144539, -0.10736523 -0.032610241 -0.29180399, -0.10659111 -0.035295669 -0.30106747, -0.10552663 -0.035154287 -0.3014228, -0.092047177 -0.029365245 -0.30421588, -0.1077209 -0.033853751 -0.29406959, -0.10499336 -0.035295624 -0.30279705, -0.082099326 -0.031092782 -0.32668784, -0.092771441 -0.035294998 -0.31190279, -0.092146143 -0.035404298 -0.31285077, -0.10812624 -0.034777757 -0.29652116, -0.0917207 -0.035294939 -0.31243378, -0.086791016 -0.035345409 -0.31889272, -0.10656404 -0.027490374 -0.28761363, -0.10770079 -0.025539678 -0.28465989, -0.090601355 -0.035153586 -0.31235319, -0.10603055 -0.025539372 -0.28822687, -0.089581423 -0.035294879 -0.31341746, -0.074800208 -0.035294604 -0.31713301, -0.10630258 -0.031094972 -0.29115805, -0.073858798 -0.035403986 -0.31776819, -0.091748931 -0.02748936 -0.30373117, -0.073626138 -0.035294529 -0.31721991, -0.072623439 -0.035153214 -0.31671569, -0.10605544 -0.025537755 -0.3179664, -0.071273029 -0.035294596 -0.31730705, -0.070684373 -0.034776453 -0.31567472, -0.10532825 -0.03461339 -0.29945669, -0.10381138 -0.034613241 -0.30112606, -0.10672436 -0.033853639 -0.2955094, -0.091172978 -0.034612652 -0.31046155, -0.089131504 -0.0346126 -0.3114205, -0.10335891 -0.034059379 -0.30010128, -0.089107074 -0.034058686 -0.31030062, -0.20049968 -0.025548283 -0.14350086, -0.20041202 -0.02476931 -0.14350089, -0.20049979 -0.025548328 -0.14050063, -0.20041202 -0.024769533 -0.14050087, -0.20015308 -0.024029594 -0.14350086, -0.20015314 -0.02402978 -0.14050063, -0.19973616 -0.023365971 -0.14350066, -0.19973616 -0.023366135 -0.14050063, -0.19918197 -0.022811767 -0.14350051, -0.19918197 -0.022811953 -0.14050063, -0.19851826 -0.02239481 -0.14350051, -0.19851832 -0.022394929 -0.14050063, -0.19777854 -0.022135857 -0.14350051, -0.19777854 -0.022136096 -0.14050063, -0.1969997 -0.02204809 -0.14350051, -0.19699982 -0.022048276 -0.14050063, 0.1905005 -0.025545638 -0.14350089, 0.1905883 -0.024766807 -0.14350086, 0.19050051 -0.025545824 -0.14050087, 0.19058827 -0.024766993 -0.14050063, 0.19084716 -0.024027023 -0.14350066, 0.19084714 -0.024027292 -0.14050063, 0.19126412 -0.023363415 -0.14350066, 0.19126411 -0.023363594 -0.14050063, 0.19181833 -0.022809241 -0.14350051, 0.19181831 -0.022809472 -0.14050063, 0.19248191 -0.022392239 -0.14350051, 0.19248199 -0.022392441 -0.14050063, 0.19322172 -0.022133339 -0.14350051, 0.19322173 -0.022133555 -0.14050063, 0.1940005 -0.022045579 -0.14350051, 0.19400056 -0.022045795 -0.14050063, 0.18692845 -0.023666847 -0.14350066, 0.12603205 -0.023586813 -0.2921662, 0.18712097 -0.02554572 -0.14350089, 0.18639955 -0.021953139 -0.14350051, 0.1255053 -0.021710817 -0.29195049, 0.18551545 -0.020300958 -0.14350051, 0.12465018 -0.019982036 -0.29160029, 0.18432604 -0.018834684 -0.14350033, 0.1234993 -0.01846673 -0.29112878, 0.1828725 -0.017597537 -0.14350033, 0.12209699 -0.017223146 -0.29055455, 0.18120429 -0.016627911 -0.14350033, 0.12049704 -0.01629905 -0.28989941, 0.17937878 -0.015956085 -0.14350033, 0.1187611 -0.015730042 -0.28918821, 0.1774596 -0.015601967 -0.14350033, 0.11695562 -0.015537951 -0.28844902, 0.17551415 -0.015573207 -0.14350027, 0.1151503 -0.015730139 -0.28770947, 0.17340408 -0.015915308 -0.14350033, 0.11341426 -0.016299222 -0.28699869, 0.17143169 -0.016624991 -0.14350033, 0.11181439 -0.017223451 -0.28634357, 0.16967079 -0.01765937 -0.14350033, 0.11041204 -0.01846708 -0.28576952, 0.16817953 -0.018963862 -0.14350033, 0.10926122 -0.019982513 -0.28529805, 0.16699946 -0.020477537 -0.14350051, 0.10840604 -0.021711368 -0.28494802, 0.1661559 -0.022137273 -0.14350051, 0.10787944 -0.023587313 -0.28473249, 0.16564879 -0.023941245 -0.14350086, 0.16550884 -0.025545824 -0.14350089, -0.070684396 -0.023586016 -0.32930881, 0.070685275 -0.023585077 -0.32930866, -0.07068444 -0.021710094 -0.32873955, 0.070685267 -0.021709178 -0.32873955, -0.070684455 -0.019981224 -0.32781532, 0.07068526 -0.019980308 -0.32781544, 0.0706852 -0.018465083 -0.3265717, -0.070684455 -0.018465977 -0.3265717, 0.070685245 -0.017221559 -0.32505623, -0.070684485 -0.017222438 -0.32505623, 0.070685185 -0.016297463 -0.32332742, -0.07068447 -0.016298365 -0.32332742, 0.070685193 -0.015728492 -0.32145137, -0.070684478 -0.015729453 -0.32145137, 0.07068523 -0.015536521 -0.31950039, -0.070684575 -0.015537355 -0.31950039, 0.070685185 -0.015728738 -0.31754959, -0.0706845 -0.015729655 -0.31754941, 0.070685171 -0.016297895 -0.31567353, -0.070684455 -0.016298842 -0.31567371, 0.07068523 -0.01722214 -0.31394473, -0.070684478 -0.017223056 -0.31394473, 0.070685245 -0.018465851 -0.31242949, -0.070684545 -0.018466685 -0.31242949, 0.070685215 -0.019981269 -0.31118599, -0.07068447 -0.019982185 -0.31118599, 0.07068523 -0.021710206 -0.31026191, -0.070684463 -0.021711137 -0.31026191, 0.070685245 -0.023586143 -0.30969295, -0.07068444 -0.023587067 -0.30969295, -0.18712008 -0.025548022 -0.14350086, -0.18692772 -0.023669202 -0.14350051, -0.12603119 -0.023588363 -0.2921662, -0.18639871 -0.021955613 -0.14350066, -0.12550466 -0.021712426 -0.29195061, -0.18551469 -0.020303447 -0.14350051, -0.12464944 -0.019983571 -0.29160029, -0.18432537 -0.018837001 -0.14350051, -0.12349866 -0.018468287 -0.29112878, -0.18287188 -0.01759984 -0.14350033, -0.12209629 -0.017224718 -0.29055455, -0.18120365 -0.016630251 -0.14350033, -0.12049633 -0.016300593 -0.28989926, -0.179378 -0.015958402 -0.14350033, -0.11876035 -0.015731569 -0.28918821, -0.17745897 -0.015604246 -0.14350027, -0.11695502 -0.015539426 -0.28844902, -0.17551339 -0.015575532 -0.14350027, -0.11514957 -0.015731659 -0.28770947, -0.1734035 -0.015917424 -0.14350027, -0.11341354 -0.016300734 -0.28699869, -0.17143102 -0.016627129 -0.14350033, -0.11181372 -0.017224852 -0.28634357, -0.16966999 -0.017661501 -0.14350033, -0.1104114 -0.018468458 -0.28576952, -0.16817886 -0.018965978 -0.14350033, -0.10926044 -0.019983876 -0.28529826, -0.16699871 -0.020479705 -0.14350051, -0.10840528 -0.021712717 -0.28494814, -0.1661552 -0.022139382 -0.14350051, -0.10787864 -0.023588721 -0.28473249, -0.16564801 -0.023943428 -0.14350051, -0.16550796 -0.025547948 -0.14350089, -0.16570042 -0.027426686 -0.14350089, -0.16622937 -0.029140431 -0.1435011, -0.16711344 -0.030792553 -0.1435011, -0.16830277 -0.032258909 -0.1435011, -0.16975629 -0.033496011 -0.1435011, -0.17142455 -0.034465749 -0.14350137, -0.17325008 -0.035137545 -0.14350137, -0.17516932 -0.035491604 -0.14350149, -0.17711459 -0.035520602 -0.14350149, -0.17922479 -0.035178322 -0.14350137, -0.18119709 -0.034468789 -0.14350149, -0.18295801 -0.033434588 -0.14350137, -0.18444932 -0.032129992 -0.1435011, -0.18562944 -0.030616235 -0.1435011, -0.18647304 -0.028956506 -0.1435011, -0.1869801 -0.027152594 -0.14350089, -0.11373562 -0.017223816 -0.30461529, -0.11573468 -0.017223995 -0.30201074, -0.11433274 -0.016299952 -0.30099887, -0.11239584 -0.01629981 -0.30352238, -0.088101365 -0.017338689 -0.31020632, -0.089107163 -0.017017338 -0.31029963, -0.089098483 -0.017338712 -0.30976513, -0.086791188 -0.01572964 -0.3188915, -0.089880511 -0.015537757 -0.31566888, -0.08618626 -0.015537698 -0.31703681, -0.089131601 -0.016463432 -0.31141964, -0.087165803 -0.018467013 -0.30913964, -0.087747552 -0.01722331 -0.31053892, -0.074405581 -0.017338458 -0.31361932, -0.075055555 -0.017223131 -0.31372947, -0.07490661 -0.018466812 -0.31222135, -0.090629518 -0.015729774 -0.31747025, -0.075225644 -0.016298909 -0.31544989, -0.095258668 -0.019982774 -0.30317232, -0.097833216 -0.019982923 -0.30113325, -0.097231314 -0.021711838 -0.30043191, -0.073877685 -0.016463082 -0.31518751, -0.094713882 -0.021711674 -0.30242586, -0.098965846 -0.02358656 -0.32219937, -0.10202949 -0.023586687 -0.32043672, -0.10173126 -0.021710727 -0.31995213, -0.098696806 -0.021710645 -0.32169804, -0.081938908 -0.015729863 -0.31621295, -0.085581437 -0.015729871 -0.31518191, -0.0849998 -0.016299043 -0.31339851, -0.073140495 -0.017687935 -0.31323642, -0.072228983 -0.017338384 -0.31374902, -0.08149945 -0.01629902 -0.31438917, -0.072031774 -0.01701707 -0.314246, -0.071624346 -0.016463067 -0.31528932, -0.11797195 -0.019982908 -0.30362549, -0.11824319 -0.018467735 -0.30104876, -0.11696352 -0.018467579 -0.30289775, -0.11927952 -0.019983049 -0.30173615, -0.071138866 -0.017338421 -0.31377357, -0.10315946 -0.018752825 -0.29715592, -0.1034251 -0.017689023 -0.2986024, -0.10458878 -0.017339502 -0.29797539, -0.093398154 -0.021711681 -0.30334696, -0.094378337 -0.023587663 -0.30196616, -0.1039509 -0.018467825 -0.29663438, -0.093081027 -0.023587633 -0.30287457, -0.10298719 -0.019983206 -0.29584843, -0.079722784 -0.016298916 -0.31478029, -0.081094541 -0.017223138 -0.31270844, -0.09174902 -0.023587544 -0.30373088, -0.10175837 -0.018752802 -0.29872131, -0.10239439 -0.017339345 -0.30040035, -0.10314568 -0.017339457 -0.29961002, -0.10112108 -0.018467564 -0.29977459, -0.079384334 -0.017223146 -0.31308511, -0.074784234 -0.019982222 -0.31098393, -0.077082448 -0.021711197 -0.30975679, -0.074693345 -0.021711159 -0.31006435, -0.077227533 -0.019982237 -0.31066921, -0.090053231 -0.018752236 -0.3075045, -0.089743353 -0.017688308 -0.30894187, -0.091058545 -0.017338764 -0.30880967, -0.10075606 -0.016299699 -0.3045384, -0.10219538 -0.01722401 -0.30084309, -0.09963014 -0.017223839 -0.30322662, -0.077660576 -0.017223146 -0.31339389, -0.079087697 -0.018466856 -0.31159917, -0.090984404 -0.018467177 -0.30732664, -0.090396278 -0.019982565 -0.30623099, -0.10342108 -0.016299803 -0.30206224, -0.12052383 -0.02358776 -0.30256185, -0.12178749 -0.023587871 -0.3005726, -0.08815866 -0.018752124 -0.30841187, -0.12130121 -0.021712024 -0.30027705, -0.12004956 -0.021711875 -0.30224702, -0.077422746 -0.018466812 -0.31189731, -0.087372728 -0.01629867 -0.32067487, -0.11490992 -0.018467437 -0.30557302, -0.073978536 -0.018751871 -0.3120282, -0.091349669 -0.016298745 -0.31920248, -0.095991813 -0.01846737 -0.30417666, -0.098643221 -0.01846746 -0.30207682, -0.071880661 -0.018751886 -0.31213883, -0.082395881 -0.015537564 -0.31810945, -0.10262287 -0.020148661 -0.29612026, -0.10227103 -0.021712188 -0.29526433, -0.080089971 -0.015729804 -0.31661999, -0.11872122 -0.021711726 -0.30416644, -0.10233591 -0.019662458 -0.29696938, -0.10195766 -0.020148646 -0.29689845, -0.09391316 -0.019982699 -0.30411413, -0.10114957 -0.02065346 -0.29734784, -0.10057084 -0.020148534 -0.29840523, -0.099584028 -0.021712001 -0.29824609, -0.10023924 -0.019983027 -0.29889774, -0.077931978 -0.016298886 -0.31510124, -0.092047304 -0.021711502 -0.30421546, -0.089955546 -0.020148013 -0.3063421, -0.089959271 -0.021711532 -0.30541673, -0.10197781 -0.015730608 -0.30596194, -0.10475121 -0.015730698 -0.30338538, -0.087908745 -0.017222706 -0.32231879, -0.089364521 -0.019661862 -0.3070159, -0.092013441 -0.017222811 -0.32079875, -0.089042537 -0.020147998 -0.3068054, -0.11587355 -0.019982684 -0.30635932, -0.082852773 -0.015729617 -0.32000634, -0.096885167 -0.01722366 -0.3054007, -0.088123858 -0.020652805 -0.30691007, -0.087183543 -0.020148013 -0.30766395, -0.086333521 -0.021711413 -0.30713835, -0.08668828 -0.019982506 -0.3079915, -0.074334599 -0.020147722 -0.31091717, -0.080471851 -0.015537594 -0.31853312, -0.11918267 -0.023587715 -0.3044996, -0.07353016 -0.019661512 -0.31131282, -0.073313713 -0.020147625 -0.31099454, -0.094606206 -0.018467311 -0.30514672, -0.072425149 -0.020652514 -0.3107385, -0.078226477 -0.015729707 -0.31695396, -0.07126753 -0.020147655 -0.31107369, -0.089690231 -0.023587417 -0.30491552, -0.10142464 -0.02207816 -0.29605013, -0.092531569 -0.01998267 -0.30500236, -0.10008021 -0.02207816 -0.29753146, -0.088378526 -0.01846623 -0.32375953, -0.099180594 -0.023587879 -0.29784486, -0.092595197 -0.018466379 -0.32219803, -0.10324847 -0.015538339 -0.30744246, -0.10613435 -0.015538525 -0.30476105, -0.11658965 -0.021711607 -0.30694345, -0.08887618 -0.022077534 -0.30581725, -0.083292164 -0.016298529 -0.32183009, -0.087066039 -0.022077527 -0.30666876, -0.08611504 -0.023587298 -0.30661297, -0.080853775 -0.015729573 -0.32044625, -0.097904392 -0.016299497 -0.30679712, -0.073539458 -0.022077288 -0.31001833, -0.071541153 -0.022077214 -0.31010979, -0.10144137 -0.023781236 -0.29531747, -0.10183011 -0.023588058 -0.29490477, -0.095450498 -0.017223667 -0.30640498, -0.078532726 -0.015537482 -0.31888077, -0.10063809 -0.024363715 -0.29611522, -0.10013302 -0.023781199 -0.29680043, -0.088764071 -0.019981567 -0.32494202, -0.10009255 -0.023204748 -0.29702061, -0.093072601 -0.019981641 -0.32334653, -0.093183398 -0.018467221 -0.30606142, -0.09945181 -0.023781117 -0.29751736, -0.083697103 -0.017222594 -0.32351086, -0.08917287 -0.02378061 -0.30514729, -0.10451899 -0.015730385 -0.30892271, -0.10751756 -0.015730467 -0.30613694, -0.081220932 -0.016298544 -0.32228598, -0.11703061 -0.023587499 -0.30730319, -0.088124909 -0.024363134 -0.30557549, -0.099010333 -0.015730303 -0.30831236, -0.087395422 -0.023780514 -0.30601421, -0.075410143 -0.015729737 -0.31731659, -0.087273531 -0.023204055 -0.30620208, -0.086491264 -0.023780476 -0.30641451, -0.078838877 -0.015729588 -0.32080731, -0.074070722 -0.02378029 -0.3095136, -0.089050539 -0.021710355 -0.3258206, -0.074637353 -0.023587141 -0.30949822, -0.093427435 -0.021710489 -0.32420003, -0.096413925 -0.016299505 -0.3078405, -0.072938621 -0.024362769 -0.30950668, -0.084052108 -0.018466119 -0.3249841, -0.072096661 -0.023780245 -0.30963174, -0.093977585 -0.017223608 -0.30735186, -0.071911909 -0.023203861 -0.30975834, -0.081559412 -0.017222572 -0.32398152, -0.071107931 -0.023780283 -0.30965427, -0.10574079 -0.016299281 -0.31034639, -0.10884758 -0.016299572 -0.30745986, -0.075602055 -0.01553743 -0.31925806, -0.10016039 -0.015538145 -0.30988827, -0.079133406 -0.016298477 -0.32266012, -0.089227021 -0.023586247 -0.32636166, -0.093645878 -0.023586374 -0.32472551, -0.097459324 -0.015730303 -0.30939808, -0.084343337 -0.019981418 -0.32619324, -0.10656404 -0.023588549 -0.28761333, -0.081855953 -0.018466119 -0.32546762, -0.10707209 -0.021712553 -0.28786972, -0.075793885 -0.01572952 -0.32119942, -0.079404674 -0.017222542 -0.32436755, -0.094883628 -0.016299371 -0.30882421, -0.10789704 -0.019983727 -0.28828624, -0.10686675 -0.017223377 -0.31165844, -0.11007331 -0.01722363 -0.3086789, -0.1050268 -0.023588348 -0.29038188, -0.084559761 -0.021710251 -0.3270916, -0.08209943 -0.019981395 -0.32668725, -0.1013104 -0.015730236 -0.3114641, -0.075978361 -0.016298417 -0.3230662, -0.10900722 -0.018468376 -0.28884652, -0.10551304 -0.021712411 -0.29067746, -0.079642542 -0.018466044 -0.32586432, -0.098546445 -0.015538026 -0.31101814, -0.10417753 -0.023588296 -0.29171851, -0.08469303 -0.023586128 -0.327645, -0.091700993 -0.017223481 -0.30866185, -0.11036003 -0.017224666 -0.28952923, -0.082280286 -0.021710146 -0.32759368, -0.076148473 -0.017222445 -0.32478693, -0.10630264 -0.019983564 -0.29115731, -0.079837762 -0.019981343 -0.32709265, -0.1046517 -0.021712337 -0.29203299, -0.095866814 -0.015730221 -0.31042185, -0.082391627 -0.023586113 -0.32815173, -0.10785367 -0.018466938 -0.31280842, -0.1032763 -0.023588251 -0.29302055, -0.11114778 -0.018467162 -0.30974773, -0.076297514 -0.018465947 -0.32629502, -0.11190335 -0.016300518 -0.2903083, -0.10241634 -0.016299132 -0.31297949, -0.079982802 -0.021710146 -0.32800522, -0.1073653 -0.018468138 -0.29180342, -0.076419763 -0.019981276 -0.32753268, -0.099633537 -0.015730117 -0.31263787, -0.08007215 -0.023585994 -0.32856742, -0.076510631 -0.021710146 -0.32845229, -0.10542185 -0.019983437 -0.29254371, -0.092518516 -0.016299289 -0.31018522, -0.10373772 -0.021712262 -0.2933535, -0.076566614 -0.023586009 -0.32901877, -0.11357805 -0.015731473 -0.29115358, -0.096889213 -0.015538115 -0.31208351, -0.1125401 -0.017808247 -0.30721977, -0.11132925 -0.016719181 -0.30612862, -0.10866361 -0.019982222 -0.3137522, -0.10866007 -0.017224532 -0.29259071, -0.11356981 -0.019194376 -0.30814794, -0.11202944 -0.019982431 -0.31062475, -0.08314538 -0.02358729 -0.3077127, -0.10645825 -0.018468048 -0.29323119, -0.11437885 -0.020824309 -0.30887714, -0.10343554 -0.017223265 -0.31437594, -0.11268464 -0.021711294 -0.31127658, -0.11565252 -0.022950176 -0.30870658, -0.10448714 -0.019983318 -0.29389423, -0.11493608 -0.022635426 -0.30937949, -0.10067893 -0.016299088 -0.31419569, -0.11420222 -0.022323828 -0.3100324, -0.11308806 -0.023587216 -0.31167808, -0.093405612 -0.015730117 -0.31183785, -0.11531961 -0.015539188 -0.29203278, -0.11013737 -0.016300309 -0.2934888, -0.09485127 -0.017807465 -0.32039845, -0.097671837 -0.018466461 -0.31978759, -0.096955232 -0.01722296 -0.31845236, -0.09415219 -0.016718376 -0.3189261, -0.107721 -0.017224405 -0.29406855, -0.095445834 -0.019193504 -0.32165083, -0.098259874 -0.01998182 -0.32088381, -0.097911701 -0.015730117 -0.31374496, -0.095913015 -0.020823415 -0.32263479, -0.10926545 -0.021711085 -0.31445354, -0.097154543 -0.022949297 -0.32296634, -0.1054956 -0.018468026 -0.29462191, -0.096234709 -0.02263451 -0.3233124, -0.083321862 -0.021711301 -0.30825332, -0.11706117 -0.015731353 -0.29291207, -0.095306449 -0.022322964 -0.32363355, -0.10432886 -0.018466767 -0.31560022, -0.11174019 -0.015731264 -0.29446322, -0.10164227 -0.017223168 -0.31563139, -0.073458612 -0.017806944 -0.32577613, -0.073378406 -0.016717877 -0.32414821, -0.10916173 -0.016300242 -0.29502445, -0.094328105 -0.015537877 -0.31355706, -0.073526852 -0.019193087 -0.32716066, -0.073580392 -0.020822968 -0.32824856, -0.1067245 -0.017224301 -0.29550868, -0.074587271 -0.022322465 -0.32884172, -0.098894894 -0.01629905 -0.31534261, -0.11873587 -0.016300332 -0.29375747, -0.073617354 -0.022634078 -0.328998, -0.10963598 -0.023587037 -0.3148855, -0.072643198 -0.022948671 -0.32912794, -0.083608434 -0.019982401 -0.30913189, -0.1134072 -0.015539039 -0.29547685, -0.11119779 -0.01612306 -0.30424115, -0.11094216 -0.015730817 -0.30233678, -0.110725 -0.015731137 -0.29606125, -0.10506192 -0.019982163 -0.31660479, -0.1099838 -0.015969086 -0.30491614, -0.1094382 -0.016122963 -0.30619374, -0.10248669 -0.018466663 -0.3168897, -0.1157631 -0.024071019 -0.30893365, -0.11495569 -0.024558093 -0.30992723, -0.095250659 -0.015729945 -0.31527609, -0.10812639 -0.016300146 -0.29652017, -0.08009854 -0.023587149 -0.30857494, -0.11417472 -0.024070907 -0.31067878, -0.094755478 -0.016122263 -0.31713265, -0.096137658 -0.016298939 -0.31692895, -0.12027923 -0.017224457 -0.29453665, -0.093375415 -0.015968282 -0.31728986, -0.11507417 -0.01573113 -0.29649049, -0.092381194 -0.016122129 -0.31826025, -0.099801026 -0.017223027 -0.31681499, -0.097169541 -0.024070088 -0.32321835, -0.083994016 -0.018466938 -0.31031421, -0.11235075 -0.015538935 -0.2971397, -0.096042596 -0.024557117 -0.32382587, -0.10512517 -0.017224167 -0.29759222, -0.095032938 -0.024069991 -0.32421997, -0.10560668 -0.021710936 -0.3173514, -0.07462389 -0.016121861 -0.32272387, -0.10317969 -0.019982036 -0.31792241, -0.07328923 -0.015967887 -0.32233921, -0.10964759 -0.015731025 -0.29761791, -0.071998693 -0.016121846 -0.32285324, -0.12163198 -0.018468056 -0.2952196, -0.075005464 -0.023908 -0.32921112, -0.080231853 -0.021711174 -0.3091282, -0.074542657 -0.023479167 -0.3291623, -0.11667702 -0.01630019 -0.29746494, -0.074516796 -0.024069626 -0.32926995, -0.11397645 -0.015730981 -0.29821819, -0.074027278 -0.024231669 -0.32932204, -0.10059528 -0.01846661 -0.31810576, -0.07291539 -0.024665292 -0.32942134, -0.10646492 -0.016300049 -0.29868481, -0.10975429 -0.015646841 -0.30300319, -0.10943044 -0.015538704 -0.30110356, -0.078551978 -0.023587156 -0.30891541, -0.10855557 -0.015586723 -0.30362916, -0.084463783 -0.017223295 -0.31175485, -0.10805744 -0.0156467 -0.30488637, -0.1059422 -0.023586858 -0.31781107, -0.1112296 -0.015538838 -0.29875952, -0.093897834 -0.015646029 -0.31543547, -0.12274218 -0.019983362 -0.29578024, -0.10369457 -0.021710921 -0.31868988, -0.092550717 -0.015585911 -0.31555301, -0.096860737 -0.023587722 -0.30000031, -0.091608129 -0.015645932 -0.31652272, -0.080448255 -0.019982379 -0.31002644, -0.074483529 -0.015645657 -0.32082742, -0.1181543 -0.017224271 -0.2983633, -0.1155397 -0.016300056 -0.29925507, -0.073194548 -0.015585553 -0.32041878, -0.071951926 -0.015645515 -0.32095218, -0.10791855 -0.015730891 -0.29987049, -0.10826796 -0.015550692 -0.3017287, -0.10124692 -0.019981939 -0.31916499, -0.078663312 -0.021711197 -0.30947343, -0.10663563 -0.015550595 -0.30354002, -0.093014739 -0.015549976 -0.31368798, -0.11281153 -0.015730914 -0.2999014, -0.07699319 -0.023587149 -0.30919477, -0.12356705 -0.021712262 -0.29619679, -0.090812147 -0.015549812 -0.31473368, -0.089131534 -0.015729997 -0.31386739, -0.074339077 -0.01554947 -0.31887466, -0.088411301 -0.016299177 -0.31213525, -0.10401172 -0.023586731 -0.31916255, -0.071903706 -0.0155495 -0.3189947, -0.11944908 -0.018467832 -0.29915065, -0.10735765 -0.015781675 -0.30017263, -0.08073955 -0.018466871 -0.31123534, -0.11698044 -0.017224107 -0.30021089, -0.10714416 -0.01567224 -0.30128804, -0.10659123 -0.015781675 -0.30106649, -0.10552677 -0.015923042 -0.30142161, -0.10499357 -0.015781511 -0.30279601, -0.09277159 -0.015780989 -0.31190163, -0.078844205 -0.019982252 -0.31037977, -0.12407503 -0.023588214 -0.29645321, -0.092146233 -0.015671406 -0.31284967, -0.091720767 -0.015780944 -0.31243268, -0.0906014 -0.015922371 -0.31235209, -0.12051167 -0.019983087 -0.29979682, -0.089581534 -0.015780833 -0.3134163, -0.074800387 -0.015780542 -0.31713206, -0.073858909 -0.015671086 -0.31776732, -0.073626176 -0.015780535 -0.31721875, -0.072623543 -0.015921969 -0.31671482, -0.071273215 -0.015780475 -0.3173058, -0.10532833 -0.01646423 -0.2994557, -0.1038115 -0.016464088 -0.3011249, -0.09117315 -0.01646344 -0.31046039, -0.10335901 -0.017018024 -0.30010045, 0.11028821 -0.015729379 -0.30312344, 0.10751818 -0.015729126 -0.30613694, 0.10613503 -0.015537102 -0.30476105, 0.086865589 -0.017221611 -0.32264778, 0.083697811 -0.017221477 -0.32351086, 0.083292909 -0.016297486 -0.32183009, 0.1016246 -0.017338011 -0.30117166, 0.10221501 -0.016462687 -0.30271754, 0.10040493 -0.017687578 -0.30168125, 0.086362034 -0.01629753 -0.32099381, 0.10342186 -0.016298439 -0.30206218, 0.10112168 -0.018466357 -0.29977459, 0.1021961 -0.017222706 -0.30084309, 0.10880095 -0.015537214 -0.30186072, 0.11010289 -0.017338555 -0.28966382, 0.10995848 -0.017223205 -0.29030702, 0.10861944 -0.018466879 -0.28959766, 0.092532299 -0.019981448 -0.30500236, 0.089669615 -0.01998141 -0.30661213, 0.089248762 -0.021710347 -0.3057895, 0.11148618 -0.016299043 -0.29111615, 0.1117544 -0.016463336 -0.28976959, 0.10873517 -0.023585599 -0.315644, 0.10594297 -0.02358545 -0.31781107, 0.11022803 -0.017688211 -0.2883479, 0.10560754 -0.02170964 -0.3173514, 0.092047997 -0.02171037 -0.30421546, 0.10837308 -0.021709647 -0.3152048, 0.11104786 -0.017338704 -0.28769857, 0.10964829 -0.015729655 -0.29761791, 0.10731375 -0.015729506 -0.30059817, 0.10588372 -0.016298663 -0.29938397, 0.11158247 -0.017017368 -0.2877045, 0.10812707 -0.01629873 -0.29652017, 0.1127025 -0.016463477 -0.28772298, 0.084344052 -0.019980308 -0.32619312, 0.082100146 -0.019980285 -0.32668725, 0.081856675 -0.018465023 -0.32546747, 0.11148374 -0.017338786 -0.28669912, 0.084052801 -0.018465113 -0.32498395, 0.093399003 -0.021710452 -0.30334696, 0.091749772 -0.023586374 -0.30373088, 0.084247723 -0.018750962 -0.30994204, 0.085049793 -0.017337535 -0.31138101, 0.084014125 -0.017337527 -0.31172207, 0.093081899 -0.023586426 -0.30287457, 0.083188049 -0.018465828 -0.31056839, 0.10916241 -0.016298804 -0.29502425, 0.10672512 -0.017222885 -0.29550856, 0.085772552 -0.017687093 -0.31062499, 0.094379164 -0.023586381 -0.30196616, 0.086222403 -0.018750947 -0.30922511, 0.087094374 -0.017337535 -0.31062296, 0.10772172 -0.017223034 -0.29406855, 0.087166503 -0.01846591 -0.30913964, 0.086689062 -0.019981388 -0.3079915, 0.091713458 -0.016298059 -0.31060722, 0.08841195 -0.016297963 -0.31213525, 0.087748311 -0.017222229 -0.31053892, 0.098734617 -0.018751379 -0.30163571, 0.10002773 -0.017337907 -0.30265668, 0.10752044 -0.019982245 -0.28901553, 0.10630336 -0.019982141 -0.29115728, 0.1055138 -0.021711122 -0.29067746, 0.10670394 -0.021711204 -0.28858295, 0.10866082 -0.017223116 -0.29259056, 0.10645897 -0.018466745 -0.29323119, 0.107366 -0.018466774 -0.29180342, 0.090926073 -0.017222296 -0.30906814, 0.09920235 -0.0173379 -0.30336908, 0.097996756 -0.018466253 -0.30262119, 0.082392432 -0.023585033 -0.32815173, 0.080072865 -0.023585018 -0.3285673, 0.10028276 -0.018751372 -0.30021578, 0.10024001 -0.019981775 -0.29889756, 0.079983555 -0.021709103 -0.32800534, 0.082281008 -0.02170914 -0.32759368, 0.087306887 -0.018465076 -0.32409751, 0.10879224 -0.018752035 -0.28866556, 0.11171828 -0.016298268 -0.30433759, 0.10884825 -0.016298126 -0.30745986, 0.10968961 -0.018752117 -0.28676617, 0.093184024 -0.018466014 -0.30606142, 0.090235978 -0.018466029 -0.30771914, 0.11123031 -0.01553743 -0.29875979, 0.083350979 -0.020146783 -0.30910164, 0.082825877 -0.019981269 -0.30937889, 0.082556747 -0.021710213 -0.30849496, 0.084360778 -0.020651605 -0.30844381, 0.084560499 -0.02170917 -0.3270916, 0.085285291 -0.020146754 -0.30842999, 0.1107257 -0.015729692 -0.29606125, 0.08558505 -0.019660566 -0.30867115, 0.086239532 -0.020146858 -0.30805865, 0.086334296 -0.02171028 -0.30713814, 0.093913868 -0.019981448 -0.30411413, 0.11013798 -0.016298842 -0.2934888, 0.094714619 -0.021710444 -0.30242586, 0.097583957 -0.020147163 -0.30120417, 0.09720552 -0.019981686 -0.30166194, 0.096617617 -0.021710534 -0.30094886, 0.092567779 -0.015728924 -0.31227726, 0.11303616 -0.017222334 -0.30545664, 0.089132205 -0.015728887 -0.31386739, 0.0982638 -0.020651963 -0.30020913, 0.11007412 -0.017222177 -0.3086789, 0.087669075 -0.01998033 -0.32528737, 0.09911222 -0.020147163 -0.29984134, 0.11281227 -0.015729446 -0.2999014, 0.099481694 -0.019661058 -0.29994926, 0.099850729 -0.020147275 -0.2991322, 0.099584892 -0.02171072 -0.29824609, 0.093978308 -0.017222401 -0.30735186, 0.10762916 -0.020147767 -0.28857434, 0.11235136 -0.015537504 -0.2971397, 0.10830003 -0.019661646 -0.28797972, 0.10808761 -0.020147797 -0.28765881, 0.084693864 -0.023585077 -0.327645, 0.10818745 -0.020652708 -0.28673941, 0.094606839 -0.018466104 -0.30514672, 0.10893631 -0.020147908 -0.28579515, 0.11174094 -0.015729804 -0.29446322, 0.083331943 -0.022076335 -0.30809978, 0.096255563 -0.023586493 -0.30051014, 0.082391031 -0.023586225 -0.30795076, 0.085216992 -0.022076327 -0.30743018, 0.095259406 -0.019981515 -0.30317232, 0.11419132 -0.018465851 -0.30643734, 0.11114843 -0.018465761 -0.30974773, 0.0971817 -0.022076692 -0.30028638, 0.11433349 -0.016298454 -0.30099908, 0.093456261 -0.015536677 -0.31401411, 0.089881204 -0.015536655 -0.31566888, 0.087938242 -0.02170917 -0.32617122, 0.098665282 -0.022076812 -0.29894453, 0.1070985 -0.022077288 -0.28749791, 0.11397721 -0.015729632 -0.29821819, 0.094884314 -0.016298134 -0.30882421, 0.10794041 -0.022077408 -0.2856833, 0.082784899 -0.023779381 -0.30779019, 0.09545128 -0.017222401 -0.30640498, 0.11340785 -0.015537526 -0.29547685, 0.083724119 -0.023779389 -0.30748069, 0.083584361 -0.023202967 -0.30765572, 0.08449319 -0.024361935 -0.30711594, 0.11513937 -0.019981224 -0.3072423, 0.11203021 -0.019981023 -0.31062475, 0.085578188 -0.023779381 -0.30679265, 0.086115807 -0.023586225 -0.30661297, 0.095992565 -0.018466163 -0.30417666, 0.11573535 -0.017222453 -0.30201074, 0.096557714 -0.023779664 -0.30021068, 0.094344757 -0.015728731 -0.31575105, 0.09730605 -0.023779724 -0.29956439, 0.090630256 -0.015728649 -0.31747025, 0.11554041 -0.016298573 -0.29925534, 0.088104017 -0.023585107 -0.32671601, 0.097244181 -0.02320325 -0.29977953, 0.097876161 -0.024362277 -0.29893228, 0.095867537 -0.015728962 -0.31042185, 0.098753944 -0.023779746 -0.29821721, 0.1131438 -0.0157299 -0.29199448, 0.099181376 -0.02358662 -0.29784486, 0.10642998 -0.02378029 -0.28779811, 0.11507483 -0.015729647 -0.29649031, 0.10620105 -0.023587119 -0.28831673, 0.10685278 -0.024362955 -0.28674793, 0.11584387 -0.021710012 -0.3078405, 0.096414633 -0.016298208 -0.3078405, 0.11268537 -0.021709818 -0.31127658, 0.10728752 -0.023780432 -0.28601617, 0.11696425 -0.018466104 -0.30289775, 0.10747477 -0.023203995 -0.2858932, 0.10768317 -0.023780469 -0.28510979, 0.11698111 -0.017222602 -0.30021089, 0.096885882 -0.017222498 -0.3054007, 0.11486774 -0.01553772 -0.29290786, 0.095199063 -0.016297627 -0.3174212, 0.091350406 -0.01629756 -0.31920224, 0.096889928 -0.015536737 -0.31208351, 0.11667773 -0.01629867 -0.29746509, 0.11627766 -0.023585889 -0.30820897, 0.11308887 -0.023585763 -0.31167799, 0.11797266 -0.019981373 -0.30362549, 0.097459987 -0.015729066 -0.30939808, 0.073849402 -0.02358612 -0.3095682, 0.11824393 -0.018466201 -0.30104876, 0.073894195 -0.021710183 -0.31013551, 0.11659165 -0.015729804 -0.29382116, 0.11815496 -0.017222706 -0.2983633, 0.07396695 -0.019981209 -0.31105664, 0.097905047 -0.016298231 -0.30679712, 0.076993987 -0.023586173 -0.30919477, 0.095986493 -0.017221723 -0.31896049, 0.092014134 -0.017221671 -0.32079875, 0.11872205 -0.021710206 -0.30416644, 0.11928026 -0.019981492 -0.30173615, 0.097912461 -0.015728798 -0.31374496, 0.11824931 -0.016298819 -0.2946994, 0.074064799 -0.018465843 -0.31229621, 0.077083252 -0.021710198 -0.30975679, 0.11944972 -0.018466238 -0.29915065, 0.098547086 -0.015536752 -0.31101802, 0.078552783 -0.023586188 -0.30891541, 0.11918353 -0.023586143 -0.30449939, 0.098960765 -0.01722255 -0.30379033, 0.074184164 -0.017222125 -0.31380683, 0.12005039 -0.021710318 -0.30224696, 0.11977705 -0.01722284 -0.2955088, 0.0772283 -0.019981232 -0.31066933, 0.12051248 -0.019981626 -0.29979682, 0.078664117 -0.021710161 -0.30947343, 0.099010974 -0.015729118 -0.30831236, 0.12052453 -0.023586188 -0.30256185, 0.096676603 -0.018465269 -0.32030952, 0.080099277 -0.023586143 -0.30857494, 0.092595913 -0.018465187 -0.32219803, 0.12111606 -0.018466387 -0.29621822, 0.074320212 -0.01629791 -0.31553021, 0.098895602 -0.016297746 -0.31534261, 0.12130205 -0.021710429 -0.30027705, 0.077423453 -0.018465858 -0.31189731, 0.12221503 -0.019981746 -0.29680043, 0.099634267 -0.01572888 -0.31263787, 0.12178832 -0.023586337 -0.3005726, 0.078844965 -0.019981172 -0.31037977, 0.10006072 -0.01629835 -0.30512407, 0.080232576 -0.021710198 -0.30912811, 0.1230316 -0.021710563 -0.29723328, 0.12353451 -0.02358656 -0.29749984, 0.07446795 -0.015728753 -0.3174004, 0.10016106 -0.015536945 -0.30988827, 0.077661343 -0.01722211 -0.31339389, 0.089729033 -0.017806094 -0.32252863, 0.089178123 -0.016717073 -0.3209945, 0.097242944 -0.019980524 -0.32141697, 0.09307339 -0.019980419 -0.32334653, 0.090197541 -0.019192178 -0.32383335, 0.07908842 -0.018465843 -0.31159893, 0.10132435 -0.023586731 -0.29551345, 0.090565726 -0.020822141 -0.32485834, 0.093428157 -0.021709289 -0.32419983, 0.099801689 -0.017221753 -0.31681499, 0.080449015 -0.019981284 -0.31002635, 0.089925066 -0.022947807 -0.32597256, 0.10067955 -0.016297836 -0.31419569, 0.090819217 -0.022633176 -0.32556453, 0.074621491 -0.015536483 -0.3193453, 0.10125417 -0.0157292 -0.30657139, 0.091701642 -0.022321682 -0.32513276, 0.093646705 -0.023585197 -0.32472551, 0.077932701 -0.016297888 -0.31510124, 0.10862815 -0.017806638 -0.31115356, 0.10602989 -0.017222065 -0.31236309, 0.10753049 -0.016717616 -0.30994862, 0.079384997 -0.017222088 -0.31308511, 0.10699398 -0.018465582 -0.31353205, 0.10956166 -0.019192774 -0.31217834, 0.10778517 -0.019980866 -0.31449181, 0.1013111 -0.015728895 -0.3114641, 0.11029503 -0.020822648 -0.31298357, 0.097663783 -0.021709297 -0.32223967, 0.080740325 -0.018465873 -0.31123534, 0.11013129 -0.022948395 -0.31425852, 0.10175812 -0.021710794 -0.2958816, 0.074775048 -0.015728462 -0.32129022, 0.11080022 -0.022633735 -0.31353834, 0.11144923 -0.022322174 -0.31280082, 0.07822717 -0.015728753 -0.31695396, 0.10059583 -0.018465322 -0.31810576, 0.079723477 -0.01629791 -0.31478029, 0.12171187 -0.017807487 -0.29339463, 0.12023571 -0.016718488 -0.29270333, 0.10164295 -0.017221849 -0.31563139, 0.10249535 -0.01553702 -0.30807653, 0.12296727 -0.019193705 -0.29398233, 0.12395359 -0.020823579 -0.29444426, 0.081095241 -0.017222125 -0.31270844, 0.124121 -0.02232312 -0.29560119, 0.10241703 -0.016297843 -0.31297949, 0.07492277 -0.016297463 -0.32316017, 0.12463298 -0.022634733 -0.29476255, 0.097923025 -0.023585316 -0.32274649, 0.10246257 -0.019981895 -0.29647967, 0.1251224 -0.022949371 -0.29391044, 0.078533344 -0.015536461 -0.31888077, 0.087481134 -0.016120922 -0.32015771, 0.085815646 -0.015728515 -0.3191992, 0.080090635 -0.015728775 -0.31661999, 0.088565975 -0.015967015 -0.31928998, 0.10124769 -0.019980643 -0.31916499, 0.089954875 -0.016120929 -0.31926918, 0.10248733 -0.018465344 -0.3168897, 0.090093143 -0.024068717 -0.32616085, 0.10373647 -0.015728969 -0.30958167, 0.0913186 -0.024555776 -0.3257902, 0.081500135 -0.016297918 -0.31438917, 0.10327715 -0.023586895 -0.29302055, 0.092310101 -0.024068687 -0.32535231, 0.07505887 -0.017221499 -0.32488382, 0.10564228 -0.016121428 -0.30982724, 0.10492996 -0.016297955 -0.31102911, 0.10631079 -0.015967492 -0.30860952, 0.07883963 -0.015728597 -0.32080728, 0.10758539 -0.016121533 -0.30805722, 0.10343623 -0.017221954 -0.31437594, 0.080472521 -0.015536536 -0.31853312, 0.11035878 -0.024069298 -0.31436807, 0.10341062 -0.018466491 -0.29728454, 0.111348 -0.024556432 -0.31355506, 0.083629481 -0.017222252 -0.31201798, 0.11209542 -0.024069283 -0.31277016, 0.10173205 -0.021709446 -0.31995213, 0.11844563 -0.0161223 -0.29331607, 0.10318044 -0.019980732 -0.31792241, 0.1185955 -0.015968341 -0.29193512, 0.081939615 -0.015728813 -0.31621295, 0.11956029 -0.01612239 -0.2909359, 0.10373854 -0.021710891 -0.2933535, 0.075178154 -0.018465001 -0.32639459, 0.12430418 -0.023908515 -0.296128, 0.079134077 -0.016297508 -0.32266012, 0.12443428 -0.023479711 -0.29568118, 0.080854475 -0.015728611 -0.3204464, 0.1245437 -0.024070147 -0.29569823, 0.12477744 -0.024232287 -0.29526478, 0.10432954 -0.018465441 -0.31560022, 0.084132902 -0.016297963 -0.31367198, 0.12529069 -0.024665985 -0.2942737, 0.086882643 -0.015644614 -0.3183524, 0.085247464 -0.015536536 -0.31733283, 0.10417836 -0.023586977 -0.29171851, 0.10456581 -0.017222788 -0.29826519, 0.087916128 -0.015584681 -0.31748039, 0.08926829 -0.015644711 -0.31749588, 0.10203025 -0.023585286 -0.32043672, 0.082396485 -0.015536491 -0.31810963, 0.10439672 -0.015645143 -0.30839029, 0.075276151 -0.019980308 -0.32763439, 0.1036954 -0.02170958 -0.31868979, 0.088989623 -0.023586329 -0.30528304, 0.10501608 -0.015585143 -0.30718824, 0.10627057 -0.01564524 -0.30668333, 0.079405367 -0.017221447 -0.32436755, 0.11674388 -0.015645977 -0.29246765, 0.10448784 -0.019981977 -0.29389399, 0.081221603 -0.016297471 -0.32228598, 0.11685431 -0.015586022 -0.29111978, 0.11781879 -0.015646134 -0.29017189, 0.084679291 -0.01572879 -0.31546658, 0.10506274 -0.019980807 -0.31660479, 0.086266473 -0.015548658 -0.31649405, 0.10465253 -0.021710981 -0.29203299, 0.088561341 -0.01554868 -0.31566983, 0.082853504 -0.015728597 -0.32000607, 0.10311422 -0.015549038 -0.3069109, 0.10502756 -0.023587 -0.29038188, 0.075348876 -0.021709133 -0.32855564, 0.10491678 -0.015549172 -0.30526879, 0.10475193 -0.015729386 -0.30338523, 0.11499158 -0.015549753 -0.29159382, 0.10401248 -0.02358536 -0.31916255, 0.11602567 -0.015549932 -0.28938553, 0.079643331 -0.018465083 -0.32586432, 0.085171483 -0.015779626 -0.31506196, 0.10549634 -0.018466633 -0.29462188, 0.086291082 -0.01592106 -0.3141031, 0.081560008 -0.017221492 -0.32398152, 0.087779418 -0.015670184 -0.31475025, 0.087397099 -0.015779708 -0.31429353, 0.088495076 -0.015779693 -0.31386825, 0.1015533 -0.015780065 -0.30600896, 0.10542266 -0.019982148 -0.29254371, 0.10221902 -0.015921492 -0.30469355, 0.075393714 -0.023585077 -0.32912317, 0.10384172 -0.015670676 -0.30471992, 0.10331333 -0.01578014 -0.30444479, 0.079838522 -0.01998036 -0.32709265, 0.10416397 -0.015780214 -0.3036308, 0.11320409 -0.015780795 -0.29136035, 0.11414871 -0.015671421 -0.2907297, 0.1137294 -0.01578084 -0.2903066, 0.11364293 -0.015922297 -0.28918782, 0.11470163 -0.015781004 -0.28816214, 0.08492019 -0.016462225 -0.31303066, 0.08704605 -0.01646227 -0.31227699, 0.10054131 -0.016462576 -0.30422971, 0.085005946 -0.017016191 -0.31191376, 0.10019182 -0.017016556 -0.30316541, 0.16570126 -0.027424585 -0.14350089, 0.16623026 -0.029138315 -0.1435011, 0.16711424 -0.030790407 -0.1435011, 0.16830365 -0.032256786 -0.1435011, 0.16975717 -0.03349388 -0.14350137, 0.17142545 -0.034463514 -0.14350137, 0.173251 -0.035135362 -0.14350137, 0.17517012 -0.035489429 -0.14350137, 0.17711557 -0.035518277 -0.14350137, 0.17922559 -0.035176102 -0.14350137, 0.18119803 -0.03446639 -0.1435011, 0.18295906 -0.03343216 -0.1435011, 0.18445027 -0.032127608 -0.1435011, 0.18563034 -0.030613918 -0.1435011, 0.18647385 -0.028954152 -0.1435011, 0.1869809 -0.027150158 -0.14350089, -0.15949981 -0.012547869 -0.14350027, -0.20049989 -0.012548309 -0.14050004, -0.15949981 -0.012548078 -0.14050004, -0.20049986 -0.012548093 -0.14350006, -0.20049973 -0.038548101 -0.14350149, -0.15949968 -0.038548093 -0.14050168, -0.20049967 -0.038548362 -0.14050168, -0.15949968 -0.038547877 -0.14350149, -0.19111933 -0.027536269 -0.14350089, -0.19167881 -0.028167848 -0.14350089, -0.1997361 -0.027730349 -0.1435011, -0.19918194 -0.028284494 -0.14350089, -0.20249972 -0.036548141 -0.14350149, -0.15749966 -0.036547858 -0.14350149, -0.19851828 -0.028701577 -0.14350089, -0.20015313 -0.027066756 -0.14350089, -0.19777849 -0.028960388 -0.14350089, -0.19052523 -0.025969986 -0.14350089, -0.19072711 -0.026789222 -0.14350089, -0.20041206 -0.026326869 -0.14350089, -0.19399969 -0.022048127 -0.14350066, -0.19699964 -0.029048178 -0.1435011, -0.19316213 -0.022149865 -0.14350051, -0.20249984 -0.014548134 -0.14350027, -0.19052526 -0.025126148 -0.14350089, -0.19399974 -0.029048089 -0.1435011, -0.19316216 -0.028946307 -0.14350089, -0.1911193 -0.02355988 -0.14350066, -0.19072714 -0.024306972 -0.14350066, -0.19237322 -0.022448983 -0.14350051, -0.19167881 -0.022928316 -0.14350066, -0.15749979 -0.014547903 -0.14350027, -0.19237325 -0.028647188 -0.14350089, -0.19399977 -0.022048328 -0.14050063, -0.19316214 -0.022149984 -0.14050063, -0.1923732 -0.022449199 -0.14050063, -0.2024999 -0.014548268 -0.14050025, -0.19052517 -0.025970209 -0.14050087, -0.19072713 -0.026789475 -0.14050087, -0.19111927 -0.02753653 -0.14050108, -0.19167873 -0.028168093 -0.14050108, -0.19237323 -0.028647419 -0.14050108, -0.199182 -0.028284702 -0.14050108, -0.19973609 -0.027730558 -0.14050108, -0.20249966 -0.03654838 -0.14050147, -0.19167887 -0.02292848 -0.14050063, -0.19851828 -0.028701726 -0.14050108, -0.19111936 -0.023560029 -0.14050063, -0.19072716 -0.024307232 -0.14050087, -0.19052526 -0.025126461 -0.14050063, -0.20015307 -0.02706698 -0.14050087, -0.19777854 -0.028960619 -0.14050108, -0.15749981 -0.014548037 -0.14050025, -0.15749966 -0.036548052 -0.14050147, -0.20041201 -0.026327137 -0.14050087, -0.19699974 -0.029048342 -0.14050108, -0.19399974 -0.029048342 -0.14050108, -0.19316216 -0.028946552 -0.14050108, 0.20050049 -0.012545627 -0.14350006, 0.15950045 -0.012545828 -0.14350006, 0.15950045 -0.012546066 -0.14050025, 0.20050046 -0.012545716 -0.14050025, 0.15950055 -0.038545821 -0.14350149, 0.20050067 -0.038545851 -0.14050168, 0.15950058 -0.038546059 -0.14050168, 0.20050067 -0.038545597 -0.14350149, 0.15750057 -0.036545862 -0.14350149, 0.19988097 -0.027533744 -0.14350089, 0.2025006 -0.036545519 -0.14350149, 0.19932151 -0.028165359 -0.14350089, 0.1986271 -0.028644662 -0.1435011, 0.20027311 -0.026786681 -0.14350089, 0.19783816 -0.02894387 -0.1435011, 0.19084716 -0.027064253 -0.14350089, 0.20047499 -0.025967408 -0.14350089, 0.19700058 -0.029045615 -0.1435011, 0.19058833 -0.026324462 -0.14350089, 0.19700052 -0.022045586 -0.14350051, 0.20250048 -0.014545593 -0.14350027, 0.19400053 -0.029045645 -0.1435011, 0.19322176 -0.028957862 -0.1435011, 0.15750039 -0.014545817 -0.14350027, 0.19783813 -0.022147287 -0.14350051, 0.19862705 -0.022446517 -0.14350051, 0.19932142 -0.022925813 -0.14350051, 0.19988096 -0.023557309 -0.14350051, 0.20027307 -0.024304423 -0.14350066, 0.20047504 -0.025123712 -0.14350089, 0.19248191 -0.028699014 -0.14350089, 0.1918183 -0.02828205 -0.14350089, 0.19126414 -0.027727816 -0.14350089, 0.19126421 -0.027728099 -0.14050108, 0.19181834 -0.028282274 -0.14050108, 0.19084716 -0.027064417 -0.14050108, 0.1905883 -0.026324693 -0.14050087, 0.15750057 -0.03654607 -0.14050147, 0.20250058 -0.036545787 -0.14050147, 0.19988099 -0.027533967 -0.14050108, 0.19932151 -0.028165568 -0.14050108, 0.19862708 -0.028644871 -0.14050108, 0.20027316 -0.026786927 -0.14050087, 0.15750042 -0.014546018 -0.14050025, 0.19783817 -0.028944049 -0.14050108, 0.20047499 -0.025967617 -0.14050087, 0.19700061 -0.029045876 -0.14050108, 0.1940005 -0.029045794 -0.14050108, 0.19322178 -0.028958131 -0.14050108, 0.19248192 -0.028699171 -0.14050108, 0.19783813 -0.022147495 -0.14050063, 0.20250043 -0.014545735 -0.14050025, 0.19700049 -0.02204578 -0.14050063, 0.19862705 -0.022446673 -0.14050063, 0.19932143 -0.022926066 -0.14050063, 0.19988103 -0.02355757 -0.14050063, 0.20027307 -0.024304602 -0.14050063, 0.20047499 -0.025123876 -0.14050063, 0.058384772 0.014462713 -0.30635646, 0.058432706 0.014067739 -0.30635655, 0.058384787 0.014463034 -0.31235653, 0.058432687 0.014068153 -0.31235665, 0.058573782 0.013695776 -0.3063567, 0.058573756 0.01369625 -0.31235665, 0.058799732 0.013368484 -0.30635661, 0.058799718 0.013368815 -0.31235665, 0.05909748 0.013104737 -0.3063567, 0.05909748 0.013105098 -0.31235665, 0.059449669 0.012919724 -0.3063567, 0.059449695 0.012920205 -0.31235674, 0.059835944 0.012824599 -0.3063567, 0.059835918 0.012825083 -0.31235674, 0.060233694 0.012824632 -0.3063567, 0.060233679 0.012825076 -0.31235674, 0.06061988 0.012919795 -0.3063567, 0.060619887 0.012920212 -0.31235674, 0.060972102 0.013104752 -0.3063567, 0.060972091 0.013105076 -0.31235674, 0.061269827 0.013368506 -0.3063567, 0.061269864 0.01336886 -0.31235653, 0.061495814 0.013695795 -0.3063567, 0.061495829 0.013696212 -0.31235665, 0.06163682 0.014067758 -0.30635655, 0.061636847 0.014068168 -0.31235665, 0.061684791 0.014462702 -0.30635652, 0.061684791 0.014462996 -0.31235665, 0.058384899 -0.0055373497 -0.30635777, 0.058432873 -0.0059323311 -0.30635768, 0.058384944 -0.0055370219 -0.31235763, 0.058432862 -0.0059319511 -0.31235757, 0.058573917 -0.0063041188 -0.30635786, 0.058573943 -0.0063038543 -0.31235781, 0.058799841 -0.0066314675 -0.30635777, 0.058799867 -0.0066310838 -0.31235781, 0.059097659 -0.0068953633 -0.30635795, 0.059097584 -0.0068949275 -0.31235781, 0.059449852 -0.0070801415 -0.30635795, 0.059449837 -0.0070797764 -0.31235781, 0.059835993 -0.0071752332 -0.30635777, 0.059836015 -0.0071749352 -0.31235781, 0.060233761 -0.0071753077 -0.30635777, 0.060233779 -0.007174965 -0.31235781, 0.060619973 -0.007080134 -0.30635786, 0.060620051 -0.0070797838 -0.31235781, 0.060972165 -0.0068952776 -0.30635777, 0.060972225 -0.0068949126 -0.31235781, 0.061269913 -0.0066314451 -0.30635777, 0.061269969 -0.0066311806 -0.31235781, 0.061495919 -0.0063041039 -0.30635777, 0.06149596 -0.0063038357 -0.31235781, 0.061636958 -0.0059323013 -0.30635777, 0.061637018 -0.0059318803 -0.31235763, 0.061684951 -0.0055373758 -0.30635795, 0.061684962 -0.0055370145 -0.31235781, 0.059449788 -0.0039946251 -0.30635759, 0.058573898 -0.0047705062 -0.30635768, 0.058432806 -0.005142428 -0.30635768, 0.050535098 -0.035037447 -0.30635932, 0.059836026 -0.0038993172 -0.30635759, 0.060233798 -0.0038993768 -0.30635759, 0.069535166 -0.03503735 -0.30635929, 0.060619991 -0.0039946027 -0.30635753, 0.06097224 -0.0041793771 -0.30635759, 0.061495971 -0.0047705919 -0.30635768, 0.06127001 -0.0044433214 -0.30635759, 0.061637029 -0.0051425286 -0.30635768, 0.059835881 0.016100653 -0.30635646, 0.050534636 0.043962579 -0.30635503, 0.059449699 0.016005401 -0.30635652, 0.059097458 0.015820503 -0.30635646, 0.058799684 0.015556842 -0.30635646, 0.058573816 0.01522946 -0.30635655, 0.058432762 0.014857527 -0.30635652, 0.06953457 0.043962698 -0.306355, 0.061636832 0.014857549 -0.3063567, 0.061495792 0.015229449 -0.30635646, 0.061269835 0.015556861 -0.30635646, 0.060972106 0.015820544 -0.30635646, 0.06061992 0.016005408 -0.30635646, 0.060233649 0.016100653 -0.30635646, 0.059097622 -0.0041794814 -0.30635753, 0.058799841 -0.0044431984 -0.30635753, 0.069535159 -0.035537001 -0.3118594, 0.069535159 -0.035537329 -0.30685952, 0.050535087 -0.035537068 -0.3118594, 0.050535116 -0.035537478 -0.30685928, 0.050035078 -0.032537106 -0.31235915, 0.07003513 -0.03253689 -0.31235915, 0.0500351 -0.035037074 -0.31235924, 0.070035085 -0.035036977 -0.31235924, 0.050035022 -0.031537253 -0.3093591, 0.070035085 -0.031537104 -0.3113592, 0.050035048 -0.031537239 -0.3113592, 0.070035085 -0.031537157 -0.30935898, 0.050034992 -0.019537125 -0.30935839, 0.070035003 -0.019536991 -0.30935848, 0.050034977 -0.019537147 -0.31135839, 0.070035003 -0.01953705 -0.31135839, 0.059449803 -0.0039941669 -0.31235757, 0.059097655 -0.0041791201 -0.31235757, 0.058432832 -0.0051421821 -0.31235781, 0.058573924 -0.0047701672 -0.31235757, 0.059836037 -0.0038990602 -0.31235757, 0.050034687 0.027462903 -0.31235579, 0.059097495 0.015820984 -0.31235638, 0.058799773 0.015557174 -0.31235638, 0.058573745 0.015229825 -0.31235647, 0.059449699 0.016005758 -0.31235647, 0.060233761 -0.0038990341 -0.31235757, 0.058432709 0.014857884 -0.31235665, 0.059835915 0.016101014 -0.31235647, 0.060619995 -0.0039941594 -0.31235757, 0.07003472 0.027463026 -0.31235579, 0.060233649 0.01610101 -0.31235647, 0.060972225 -0.0041790791 -0.31235757, 0.060619898 0.016005762 -0.31235638, 0.06126995 -0.0044428222 -0.31235757, 0.060972076 0.015820991 -0.31235647, 0.061269846 0.015557181 -0.31235638, 0.061495889 -0.0047701448 -0.31235757, 0.061495803 0.01522984 -0.31235647, 0.061636977 -0.0051421374 -0.31235763, 0.061636876 0.014857817 -0.31235653, 0.050035022 -0.018537093 -0.31235841, 0.058799841 -0.0044428371 -0.31235757, 0.070035018 -0.018536981 -0.31235841, 0.050034668 0.028462898 -0.30935568, 0.070034698 0.028462932 -0.3113558, 0.050034694 0.028462891 -0.31135571, 0.070034683 0.028462898 -0.30935568, 0.050034605 0.04046277 -0.30935505, 0.070034616 0.040462896 -0.30935505, 0.050034638 0.040462893 -0.31135514, 0.070034638 0.040462952 -0.31135514, 0.050034583 0.043962933 -0.31235495, 0.070034638 0.041463152 -0.31235495, 0.050034571 0.041463025 -0.31235495, 0.070034593 0.04396306 -0.31235495, 0.050534565 0.044462688 -0.30685484, 0.069534637 0.044463143 -0.31185487, 0.050534602 0.044463016 -0.31185475, 0.069534622 0.044462718 -0.30685487, 0.0700351 -0.035037342 -0.30685931, 0.070034608 0.043962762 -0.30685487, 0.0500351 -0.035037432 -0.30685928, 0.05003459 0.043962635 -0.30685487, 0.061684757 0.022464145 -0.33264035, 0.061636765 0.022069294 -0.33264044, 0.061684731 0.022463758 -0.32664043, 0.061636768 0.022068873 -0.32664049, 0.061495736 0.021697361 -0.33264035, 0.061495747 0.02169694 -0.32664043, 0.061269786 0.021369975 -0.33264035, 0.061269786 0.021369617 -0.32664049, 0.060972054 0.021106198 -0.33264044, 0.060972031 0.021105807 -0.32664043, 0.060619868 0.020921391 -0.33264044, 0.060619853 0.020920973 -0.32664043, 0.060233645 0.020826168 -0.33264056, 0.060233619 0.020825785 -0.32664061, 0.059835877 0.020826135 -0.33264056, 0.059835833 0.020825777 -0.32664061, 0.059449647 0.020921387 -0.33264056, 0.059449647 0.020921033 -0.32664043, 0.059097447 0.021106187 -0.33264056, 0.059097439 0.0211058 -0.32664043, 0.058799721 0.021369938 -0.33264035, 0.058799684 0.02136961 -0.32664049, 0.058573756 0.021697339 -0.33264056, 0.058573741 0.021696929 -0.32664043, 0.058432657 0.022069361 -0.33264023, 0.05843268 0.022068854 -0.32664043, 0.058384702 0.022464242 -0.33264035, 0.058384713 0.022463735 -0.32664043, 0.061684962 -0.013535868 -0.33264238, 0.061637051 -0.013930637 -0.33264259, 0.061684959 -0.013536271 -0.32664233, 0.061637025 -0.013931204 -0.32664251, 0.061496031 -0.01430263 -0.33264259, 0.061496012 -0.014303077 -0.32664245, 0.061269999 -0.014629956 -0.33264259, 0.06127004 -0.014630396 -0.32664245, 0.060972285 -0.014893819 -0.33264259, 0.060972296 -0.014894243 -0.32664245, 0.060620081 -0.0150786 -0.33264259, 0.060620099 -0.01507907 -0.32664245, 0.060233809 -0.015173744 -0.33264259, 0.060233857 -0.015174259 -0.32664266, 0.059836086 -0.015173789 -0.33264259, 0.059836097 -0.015174281 -0.32664245, 0.059449892 -0.0150786 -0.33264259, 0.059449911 -0.015079048 -0.32664251, 0.059097655 -0.014893848 -0.33264247, 0.059097636 -0.014894258 -0.32664245, 0.058799949 -0.014629994 -0.33264238, 0.058799937 -0.014630403 -0.32664251, 0.058573984 -0.014302615 -0.33264238, 0.058573954 -0.014303062 -0.32664251, 0.058432881 -0.01393066 -0.33264238, 0.058432885 -0.01393107 -0.32664233, 0.058384944 -0.013535928 -0.33264232, 0.058384951 -0.013536278 -0.32664233, 0.064284816 0.014464144 -0.33264086, 0.064161308 0.01344705 -0.33264086, 0.063784845 0.0144642 -0.33214077, 0.063675851 0.013566852 -0.33214077, 0.063355237 0.012721505 -0.33214095, 0.063797988 0.012489174 -0.33264095, 0.062841721 0.011977457 -0.33214095, 0.063216016 0.01164588 -0.33264098, 0.062165026 0.011377979 -0.33214095, 0.062449101 0.010966443 -0.33264095, 0.061364576 0.010957878 -0.33214098, 0.061541904 0.010490377 -0.33264098, 0.060486831 0.010741457 -0.33214113, 0.060547091 0.010245156 -0.33264118, 0.059582826 0.010741446 -0.33214098, 0.059522491 0.010245237 -0.33264098, 0.058705043 0.010957871 -0.33214098, 0.058527719 0.010490444 -0.33264098, 0.05790456 0.011378042 -0.33214098, 0.057620548 0.010966416 -0.33264095, 0.057227891 0.011977423 -0.33214095, 0.056853633 0.011645783 -0.33264086, 0.05671436 0.012721404 -0.33214098, 0.056271624 0.012489062 -0.33264086, 0.056393795 0.013566718 -0.33214095, 0.05590827 0.013447028 -0.33264086, 0.056284808 0.014464095 -0.33214086, 0.055784788 0.014464151 -0.33264083, 0.064284973 -0.0055358671 -0.33264199, 0.064161442 -0.0065529905 -0.33264202, 0.063784964 -0.0055358931 -0.33214194, 0.06367591 -0.0064333118 -0.33214203, 0.063355386 -0.0072785355 -0.33214203, 0.063798144 -0.0075109191 -0.33264205, 0.062841862 -0.0080225207 -0.33214217, 0.063216127 -0.0083540715 -0.33264217, 0.062165197 -0.0086220168 -0.33214206, 0.062449239 -0.0090335719 -0.33264223, 0.061364692 -0.0090421103 -0.33214217, 0.061542012 -0.0095096268 -0.33264223, 0.060486965 -0.0092585273 -0.33214217, 0.060547195 -0.0097549222 -0.33264217, 0.059582945 -0.0092585348 -0.33214217, 0.059522685 -0.0097548924 -0.33264223, 0.058705166 -0.0090421401 -0.33214217, 0.058527846 -0.0095097013 -0.33264223, 0.05790465 -0.0086220615 -0.33214217, 0.057620682 -0.0090335794 -0.33264217, 0.057228044 -0.0080225877 -0.33214217, 0.056853738 -0.0083541386 -0.33264202, 0.056714445 -0.0072785504 -0.33214206, 0.056271721 -0.0075109191 -0.33264205, 0.056393877 -0.0064333528 -0.33214203, 0.055908397 -0.0065529794 -0.33264199, 0.056284927 -0.0055358559 -0.33214194, 0.055784922 -0.0055358298 -0.33264193, 0.063784927 -0.0055360682 -0.32814205, 0.063675947 -0.0064334609 -0.32814208, 0.063355356 -0.0072787814 -0.32814208, 0.062841848 -0.0080228336 -0.32814208, 0.062165167 -0.0086222552 -0.32814208, 0.061364766 -0.0090425052 -0.32814208, 0.060486939 -0.0092587583 -0.32814208, 0.059582938 -0.0092587732 -0.32814208, 0.058705159 -0.0090423562 -0.32814208, 0.057904672 -0.0086222999 -0.32814232, 0.05722798 -0.0080228858 -0.32814208, 0.056714498 -0.0072788782 -0.32814205, 0.056393929 -0.0064335652 -0.32814208, 0.056285001 -0.0055361837 -0.32814208, 0.063784853 0.014463905 -0.32814091, 0.063675739 0.013566617 -0.32814091, 0.063355222 0.0127213 -0.32814091, 0.062841669 0.011977222 -0.32814091, 0.062164996 0.01137777 -0.32814103, 0.061364576 0.010957606 -0.32814103, 0.060486801 0.010741305 -0.32814103, 0.059582833 0.010741297 -0.32814103, 0.058705077 0.010957565 -0.32814103, 0.057904538 0.011377778 -0.32814103, 0.057227887 0.011977214 -0.32814103, 0.056714304 0.012721289 -0.328141, 0.056393761 0.013566423 -0.32814091, 0.056284789 0.014463946 -0.32814085, 0.060034875 0.0028637685 -0.32664147, 0.060417749 0.0029102117 -0.32664147, 0.060034886 0.0028641298 -0.33264145, 0.060417768 0.0029106513 -0.33264145, 0.060778417 0.003046941 -0.32664144, 0.060778376 0.0030475631 -0.33264145, 0.061095841 0.0032661147 -0.32664147, 0.06109589 0.0032664388 -0.33264145, 0.061351635 0.0035548322 -0.32664147, 0.061351638 0.0035552494 -0.33264145, 0.061530866 0.0038963743 -0.32664147, 0.061530832 0.0038968474 -0.33264145, 0.061623219 0.0042708702 -0.32664147, 0.061623175 0.0042713769 -0.33264145, 0.061623164 0.0046566315 -0.32664147, 0.061623193 0.0046571009 -0.33264142, 0.061530858 0.00503112 -0.32664147, 0.061530873 0.0050315149 -0.33264133, 0.061351586 0.0053726807 -0.32664123, 0.061351608 0.0053731352 -0.33264139, 0.061095759 0.0056614168 -0.32664135, 0.06109583 0.0056617968 -0.33264133, 0.060778376 0.0058804564 -0.32664123, 0.060778376 0.0058809072 -0.33264133, 0.060417749 0.0060172193 -0.32664123, 0.060417734 0.0060176365 -0.33264133, 0.060034852 0.0060637072 -0.32664123, 0.060034882 0.0060641244 -0.33264133, 0.060034949 -0.0076362006 -0.32664207, 0.060537498 -0.0075752996 -0.32664204, 0.060034957 -0.0076361559 -0.32814208, 0.060537547 -0.007575091 -0.32814208, 0.061010823 -0.0073957331 -0.32664204, 0.061010804 -0.0073955245 -0.32814208, 0.061427452 -0.0071081705 -0.32664204, 0.06142744 -0.0071079619 -0.32814205, 0.061763134 -0.0067291707 -0.32664204, 0.061763197 -0.0067290813 -0.32814205, 0.061998408 -0.0062809065 -0.32664204, 0.061998423 -0.0062807612 -0.32814205, 0.062119558 -0.0057893842 -0.32664204, 0.062119648 -0.0057892613 -0.32814208, 0.062119585 -0.0052831285 -0.32664204, 0.062119525 -0.0052828304 -0.32814205, 0.061998464 -0.0047916025 -0.32664204, 0.061998449 -0.0047914498 -0.32814208, 0.061763145 -0.004343316 -0.32664183, 0.061763149 -0.0043431483 -0.32814196, 0.061427452 -0.0039643347 -0.32664186, 0.061427437 -0.0039641559 -0.32814187, 0.061010838 -0.0036767945 -0.32664186, 0.061010823 -0.0036765821 -0.32814205, 0.060537472 -0.0034972653 -0.32664186, 0.060537465 -0.0034970827 -0.32814187, 0.060034908 -0.0034362637 -0.32664183, 0.060034849 -0.0034360513 -0.32814187, 0.06003483 0.012363739 -0.3266409, 0.060537379 0.012424655 -0.3266409, 0.060034771 0.012363974 -0.32814085, 0.06053732 0.012424957 -0.32814085, 0.061010707 0.012604311 -0.32664093, 0.061010733 0.01260446 -0.328141, 0.061427336 0.012891904 -0.32664093, 0.061427366 0.012892056 -0.32814091, 0.061763059 0.013270788 -0.32664087, 0.061763015 0.013271052 -0.32814091, 0.061998334 0.013719138 -0.32664087, 0.061998293 0.013719305 -0.32814091, 0.062119503 0.01421063 -0.32664087, 0.06211945 0.014210813 -0.32814091, 0.062119443 0.014716882 -0.32664087, 0.062119514 0.014716946 -0.32814085, 0.061998319 0.015208438 -0.32664087, 0.061998315 0.015208595 -0.32814091, 0.061763044 0.015656639 -0.32664064, 0.061763063 0.015656907 -0.32814085, 0.061427273 0.016035601 -0.32664075, 0.061427254 0.016035873 -0.32814085, 0.061010715 0.016323131 -0.32664075, 0.061010707 0.016323309 -0.32814065, 0.060537346 0.01650266 -0.32664087, 0.060537353 0.016502813 -0.32814077, 0.060034797 0.016563665 -0.32664087, 0.060034804 0.016563874 -0.32814077, 0.059532188 0.016502772 -0.32664087, 0.059532199 0.016502835 -0.32814065, 0.059058875 0.016323242 -0.32814065, 0.059058838 0.016323153 -0.32664078, 0.058642212 0.016035851 -0.32814065, 0.05864222 0.01603562 -0.32664087, 0.058306515 0.015656795 -0.32814085, 0.058306459 0.01565671 -0.32664064, 0.058071226 0.015208568 -0.32814091, 0.058071226 0.015208419 -0.32664087, 0.057950068 0.014717065 -0.32814085, 0.057950068 0.01471686 -0.32664087, 0.057950083 0.014210749 -0.32814091, 0.057950091 0.014210604 -0.32664087, 0.058071233 0.01371929 -0.32814091, 0.05807123 0.013719078 -0.32664093, 0.058306523 0.013270911 -0.32814091, 0.05830653 0.013270762 -0.3266409, 0.058642287 0.012892034 -0.32814103, 0.058642279 0.012891736 -0.32664087, 0.059058864 0.012604441 -0.32814091, 0.059058871 0.012604292 -0.32664087, 0.059532177 0.01242495 -0.32814085, 0.059532214 0.01242486 -0.3266409, 0.069535166 -0.03503583 -0.33264378, 0.050535109 -0.035035964 -0.33264354, 0.06163701 -0.013140995 -0.33264247, 0.06126998 -0.012441684 -0.33264232, 0.061495978 -0.012769062 -0.33264232, 0.06062004 -0.011992965 -0.33264229, 0.060972281 -0.012177933 -0.33264232, 0.059836056 -0.011897799 -0.33264229, 0.060233824 -0.011897851 -0.33264229, 0.059449859 -0.011993114 -0.33264229, 0.058799904 -0.012441639 -0.33264232, 0.059097718 -0.012177978 -0.33264232, 0.058432899 -0.013141084 -0.33264229, 0.058573954 -0.01276907 -0.33264238, 0.061541982 -0.0015619956 -0.33264172, 0.062449187 -0.0020381361 -0.33264172, 0.060547162 -0.0013167933 -0.33264172, 0.063216098 -0.0027176328 -0.33264178, 0.063798107 -0.0035607852 -0.33264178, 0.059522599 -0.0013168156 -0.33264178, 0.059651952 0.0029106475 -0.33264145, 0.059291333 0.0030473545 -0.33264145, 0.058527831 -0.0015620664 -0.33264172, 0.05897389 0.0032665692 -0.33264142, 0.057620652 -0.0020381622 -0.33264172, 0.058718093 0.003555242 -0.33264145, 0.058538839 0.0038967133 -0.33264145, 0.056853753 -0.002717644 -0.33264178, 0.056271669 -0.0035607666 -0.33264181, 0.058446527 0.0042713247 -0.33264142, 0.058446489 0.0046570562 -0.33264145, 0.06416142 -0.0045187101 -0.33264178, 0.059651937 0.0060176291 -0.33264133, 0.059291262 0.0058808625 -0.33264133, 0.058973782 0.0056617893 -0.33264133, 0.058718074 0.0053731464 -0.33264133, 0.058538832 0.0050314926 -0.33264133, 0.055908352 -0.0045186952 -0.33264181, 0.061541829 0.018437941 -0.33264068, 0.062449053 0.017961856 -0.33264068, 0.060547058 0.018683236 -0.33264068, 0.063215971 0.017282452 -0.33264068, 0.059522454 0.018683143 -0.33264056, 0.063797951 0.016439382 -0.33264068, 0.061636746 0.022858996 -0.33264035, 0.058527689 0.018437948 -0.33264068, 0.057620477 0.017961819 -0.33264062, 0.056853596 0.017282356 -0.33264062, 0.056271575 0.016439304 -0.33264068, 0.058432654 0.022859063 -0.33264023, 0.060233586 0.024102163 -0.33264023, 0.0695346 0.043964248 -0.33263916, 0.06061979 0.024006974 -0.33264035, 0.060972013 0.023822054 -0.33264023, 0.061269782 0.023558334 -0.33264035, 0.061495725 0.023230962 -0.33264035, 0.064161293 0.015481237 -0.33264068, 0.05590827 0.015481219 -0.33264068, 0.05053458 0.04396404 -0.33263913, 0.058573727 0.023230936 -0.33264035, 0.05879968 0.023558315 -0.33264035, 0.059097424 0.023822043 -0.33264023, 0.059449654 0.024006907 -0.33264023, 0.059835855 0.024102125 -0.33264023, 0.050535113 -0.035536397 -0.32714358, 0.050535116 -0.035535816 -0.33214355, 0.069535159 -0.035536285 -0.3271437, 0.069535196 -0.035535809 -0.3321436, 0.0700351 -0.032536257 -0.3266435, 0.050035093 -0.035036419 -0.32664371, 0.070035152 -0.035036188 -0.32664371, 0.050035127 -0.032536391 -0.3266435, 0.070035122 -0.031536024 -0.32964331, 0.050035048 -0.031536173 -0.32764328, 0.070035085 -0.031536039 -0.32764331, 0.050035067 -0.031536166 -0.32964331, 0.070035018 -0.019535925 -0.32964268, 0.050034963 -0.019536015 -0.32964268, 0.070034988 -0.019535955 -0.32764274, 0.050034974 -0.019536112 -0.32764274, 0.050034981 -0.018536303 -0.32664266, 0.070035025 -0.018536288 -0.32664266, 0.058071326 -0.0062808357 -0.32664204, 0.058432929 -0.013141479 -0.32664233, 0.050034717 0.027463619 -0.32664001, 0.058446523 0.0046564899 -0.32664147, 0.058446493 0.0042708479 -0.32664147, 0.070034727 0.027463747 -0.32664001, 0.060972013 0.023821633 -0.32664031, 0.061269794 0.023557857 -0.32664031, 0.061495706 0.023230601 -0.32664037, 0.06061982 0.024006501 -0.32664037, 0.061636761 0.022858668 -0.32664037, 0.060233597 0.024101775 -0.32664025, 0.058432657 0.022858646 -0.32664031, 0.058573712 0.023230586 -0.32664037, 0.058799669 0.023557905 -0.32664043, 0.059097465 0.023821596 -0.32664037, 0.059449628 0.02400649 -0.32664037, 0.059835803 0.024101768 -0.32664037, 0.059651941 0.0060171783 -0.32664123, 0.059291307 0.0058804452 -0.32664144, 0.058973867 0.0056612752 -0.3266412, 0.058718089 0.0053726994 -0.32664147, 0.058538832 0.0050311312 -0.32664147, 0.059651922 0.0029102303 -0.32664147, 0.059532344 -0.003497269 -0.32664183, 0.059291296 0.0030469373 -0.32664147, 0.059058998 -0.0036768019 -0.32664186, 0.05897386 0.0032660961 -0.32664144, 0.058642335 -0.0039643683 -0.32664186, 0.0587181 0.0035548173 -0.32664147, 0.058306679 -0.0043433309 -0.32664186, 0.058538858 0.0038963519 -0.32664147, 0.058071375 -0.0047916397 -0.32664186, 0.057950228 -0.0052831843 -0.32664186, 0.061269991 -0.012442175 -0.32664227, 0.060972251 -0.01217832 -0.32664233, 0.061496001 -0.012769479 -0.32664233, 0.060619991 -0.011993479 -0.32664227, 0.061637025 -0.013141435 -0.32664245, 0.060233798 -0.011898275 -0.32664227, 0.05953237 -0.0075752698 -0.32664204, 0.059836071 -0.011898305 -0.32664227, 0.059059009 -0.0073957779 -0.32664204, 0.059449859 -0.011993561 -0.32664227, 0.058642417 -0.0071082227 -0.32664204, 0.059097674 -0.012178335 -0.32664233, 0.058306649 -0.0067292191 -0.32664207, 0.058799844 -0.012442101 -0.32664233, 0.058573984 -0.012769517 -0.32664233, 0.057950184 -0.0057894327 -0.32664204, 0.070034668 0.028464062 -0.32964003, 0.050034709 0.028463844 -0.32764006, 0.07003466 0.028463939 -0.32764006, 0.050034702 0.02846388 -0.32964003, 0.070034653 0.040464088 -0.32963935, 0.050034616 0.040463958 -0.32963926, 0.070034653 0.040463969 -0.32763928, 0.050034612 0.040463813 -0.32763928, 0.070034623 0.043963894 -0.32663918, 0.050034638 0.041463714 -0.32663921, 0.070034608 0.041463837 -0.32663947, 0.05003459 0.043963708 -0.32663918, 0.0695346 0.044464208 -0.33213916, 0.050534591 0.04446362 -0.32713911, 0.069534585 0.044463828 -0.32713911, 0.05053452 0.044464156 -0.3321391, 0.050035112 -0.035035972 -0.33214349, 0.050034583 0.043964125 -0.33213916, 0.07003513 -0.035035845 -0.33214355, 0.070034578 0.043964371 -0.33213916, 0.059532296 -0.0034970641 -0.32814196, 0.059058961 -0.0036766082 -0.32814187, 0.058642346 -0.0039641596 -0.32814205, 0.058306567 -0.0043431707 -0.32814208, 0.058071405 -0.0047914907 -0.32814208, 0.05795018 -0.0052829161 -0.32814187, 0.057950236 -0.0057892986 -0.32814205, 0.058071326 -0.0062807724 -0.32814208, 0.058306657 -0.0067291036 -0.32814208, 0.058642391 -0.0071079768 -0.32814208, 0.059059035 -0.0073955394 -0.32814208, 0.05953237 -0.007575091 -0.32814208, 0.061364569 0.017970223 -0.32814062, 0.062164955 0.01755007 -0.32814062, 0.060486805 0.018186551 -0.32814065, 0.059582777 0.018186513 -0.32814062, 0.056393735 0.015361298 -0.32814091, 0.058705017 0.017970268 -0.32814062, 0.056714315 0.016206611 -0.32814065, 0.057904556 0.017550077 -0.32814062, 0.057227854 0.01695063 -0.32814062, 0.063675776 0.015361335 -0.32814085, 0.063355207 0.016206652 -0.32814085, 0.062841706 0.01695063 -0.32814091, 0.056393772 0.015361566 -0.33214071, 0.056714322 0.016206879 -0.33214071, 0.057227861 0.016950864 -0.33214071, 0.057904501 0.017550427 -0.33214051, 0.058705043 0.017970379 -0.33214062, 0.059582785 0.018186752 -0.33214071, 0.060486782 0.018186823 -0.33214071, 0.061364535 0.017970484 -0.33214071, 0.062165011 0.017550398 -0.33214051, 0.062841639 0.016950931 -0.33214071, 0.06335523 0.01620695 -0.33214071, 0.063675813 0.015361633 -0.33214071, 0.057904653 -0.0024499409 -0.32814175, 0.058705151 -0.0020297952 -0.32814175, 0.059582934 -0.001813516 -0.32814175, 0.060486861 -0.0018134005 -0.32814187, 0.056393869 -0.0046386272 -0.32814196, 0.063675918 -0.0046386309 -0.32814187, 0.061364692 -0.0020297617 -0.32814175, 0.063355334 -0.0037933886 -0.32814187, 0.056714408 -0.0037933849 -0.32814187, 0.06216513 -0.0024498366 -0.32814175, 0.06284178 -0.0030493215 -0.32814175, 0.057228029 -0.0030494705 -0.32814196, 0.056393903 -0.0046385713 -0.33214185, 0.056714483 -0.0037931874 -0.33214185, 0.057227928 -0.0030491613 -0.33214185, 0.057904638 -0.0024497919 -0.33214173, 0.058705136 -0.0020295568 -0.33214161, 0.059582911 -0.0018131994 -0.33214173, 0.060486954 -0.0018132702 -0.33214173, 0.061364718 -0.0020295493 -0.33214173, 0.062165137 -0.0024497025 -0.33214179, 0.06284187 -0.0030491687 -0.33214182, 0.063355364 -0.0037931539 -0.33214182, 0.063675955 -0.0046383478 -0.33214185, -0.05838453 0.022463311 -0.3326405, -0.058432464 0.02206846 -0.33264035, -0.05838456 0.022462949 -0.32664049, -0.058432508 0.022068124 -0.32664037, -0.058573559 0.021696523 -0.3326405, -0.058573578 0.021696161 -0.32664049, -0.058799397 0.021369208 -0.33264056, -0.058799446 0.021368723 -0.32664049, -0.059097245 0.021105479 -0.33264044, -0.059097316 0.021105122 -0.32664049, -0.059449371 0.020920578 -0.33264044, -0.059449449 0.020920224 -0.32664064, -0.059835654 0.020825457 -0.33264056, -0.059835624 0.02082498 -0.32664049, -0.060233325 0.020825386 -0.33264056, -0.060233396 0.020824973 -0.32664049, -0.060619589 0.020920694 -0.33264056, -0.060619619 0.020920072 -0.32664049, -0.06097189 0.021105465 -0.33264056, -0.060971931 0.021104958 -0.32664049, -0.061269522 0.021369155 -0.33264044, -0.061269548 0.021368742 -0.32664049, -0.061495546 0.021696534 -0.33264044, -0.061495557 0.021696176 -0.32664049, -0.061636556 0.022068437 -0.33264044, -0.061636571 0.02206808 -0.32664049, -0.06168456 0.022463344 -0.33264044, -0.061684553 0.022462931 -0.32664037, -0.058384288 -0.013536591 -0.33264247, -0.058432255 -0.01393142 -0.3326425, -0.058384303 -0.013537113 -0.32664251, -0.058432277 -0.013931978 -0.32664251, -0.058573294 -0.014303435 -0.33264247, -0.058573294 -0.014303844 -0.32664251, -0.0587992 -0.014630798 -0.33264247, -0.058799237 -0.014631163 -0.32664251, -0.059096977 -0.014894601 -0.33264247, -0.059097007 -0.014895018 -0.32664251, -0.059449129 -0.01507939 -0.33264238, -0.059449196 -0.015079852 -0.32664251, -0.059835382 -0.015174579 -0.33264247, -0.059835419 -0.015175115 -0.32664251, -0.060233127 -0.015174624 -0.33264261, -0.060233146 -0.015175041 -0.32664251, -0.060619369 -0.01507939 -0.33264247, -0.060619369 -0.015079889 -0.32664251, -0.060971603 -0.014894579 -0.33264247, -0.060971644 -0.014894973 -0.32664251, -0.061269313 -0.014630806 -0.3326425, -0.061269332 -0.014631253 -0.32664251, -0.061495334 -0.014303368 -0.33264261, -0.061495353 -0.014303874 -0.32664251, -0.061636403 -0.013931435 -0.33264261, -0.061636355 -0.013932001 -0.32664251, -0.061684314 -0.013536613 -0.33264238, -0.061684329 -0.01353715 -0.32664251, -0.055784434 0.014463335 -0.33264074, -0.056393482 0.013566017 -0.33214077, -0.056284457 0.014463361 -0.33214077, -0.055907991 0.013446271 -0.33264086, -0.056714002 0.012720697 -0.33214098, -0.056271277 0.012488302 -0.33264086, -0.057227496 0.011976618 -0.33214098, -0.05685325 0.011645127 -0.33264098, -0.057904225 0.011377174 -0.33214098, -0.057620164 0.010965601 -0.33264107, -0.058704693 0.010957137 -0.33214095, -0.058527343 0.010489542 -0.33264118, -0.059582464 0.010740705 -0.33214098, -0.059522185 0.010244314 -0.33264098, -0.060486551 0.010740783 -0.33214098, -0.060546689 0.01024431 -0.33264118, -0.061364241 0.010957122 -0.33214098, -0.061541524 0.010489512 -0.33264118, -0.06216469 0.011377174 -0.33214095, -0.062448747 0.010965638 -0.33264118, -0.062841453 0.011976615 -0.33214098, -0.063215584 0.01164503 -0.33264098, -0.063354924 0.012720626 -0.33214098, -0.06379766 0.012488317 -0.33264095, -0.063675538 0.013565969 -0.33214098, -0.064161032 0.01344613 -0.33264095, -0.063784473 0.014463346 -0.33214098, -0.064284474 0.014463399 -0.33264086, -0.055784304 -0.0055366904 -0.33264199, -0.056393329 -0.006434083 -0.33214203, -0.056284349 -0.0055366792 -0.33214194, -0.055907819 -0.0065536834 -0.33264202, -0.056713898 -0.0072793774 -0.33214203, -0.056271181 -0.007511612 -0.33264205, -0.05722741 -0.0080233328 -0.33214217, -0.056853157 -0.0083548985 -0.33264217, -0.057904098 -0.008622881 -0.33214206, -0.057620037 -0.0090343021 -0.33264223, -0.058704622 -0.0090429671 -0.33214217, -0.058527246 -0.0095104836 -0.33264223, -0.059582341 -0.0092592798 -0.33214217, -0.059522048 -0.0097555779 -0.33264232, -0.06048635 -0.0092592798 -0.33214217, -0.060546566 -0.0097556747 -0.33264223, -0.061364088 -0.0090429895 -0.33214217, -0.061541442 -0.0095104389 -0.33264223, -0.062164642 -0.0086227916 -0.33214217, -0.06244855 -0.0090343319 -0.33264205, -0.062841229 -0.0080232583 -0.33214217, -0.063215464 -0.0083549134 -0.33264217, -0.063354887 -0.0072794072 -0.33214203, -0.063797534 -0.0075116791 -0.33264223, -0.063675441 -0.006434083 -0.33214203, -0.064160891 -0.0065537952 -0.33264199, -0.063784406 -0.0055365786 -0.33214203, -0.064284317 -0.0055366568 -0.33264193, -0.056284346 -0.0055368543 -0.32814205, -0.056393355 -0.0064342618 -0.32814208, -0.05671395 -0.007279519 -0.32814208, -0.057227388 -0.0080235861 -0.32814208, -0.057904147 -0.0086229779 -0.32814208, -0.058704559 -0.0090431608 -0.32814208, -0.059582371 -0.0092594288 -0.32814234, -0.06048638 -0.0092594586 -0.32814208, -0.061364118 -0.0090431832 -0.32814208, -0.062164579 -0.0086231045 -0.32814208, -0.062841311 -0.0080235712 -0.32814208, -0.063354857 -0.0072797276 -0.32814208, -0.063675337 -0.0064343698 -0.32814208, -0.063784331 -0.0055369474 -0.32814208, -0.056284472 0.014463123 -0.32814091, -0.056393422 0.013565715 -0.32814091, -0.056713954 0.012720376 -0.32814091, -0.057227608 0.011976387 -0.32814103, -0.057904206 0.01137697 -0.32814109, -0.058704775 0.010956865 -0.32814091, -0.059582468 0.010740519 -0.328141, -0.060486492 0.010740429 -0.32814103, -0.061364245 0.01095682 -0.32814109, -0.062164724 0.011376936 -0.32814091, -0.06284143 0.01197644 -0.328141, -0.063354954 0.01272051 -0.328141, -0.063675597 0.01356573 -0.32814103, -0.063784502 0.014463104 -0.32814091, -0.060034461 0.0028629899 -0.32664159, -0.059651494 0.0029094629 -0.32664159, -0.060034398 0.0028633513 -0.33264145, -0.059651472 0.0029098988 -0.33264142, -0.05929083 0.0030461624 -0.32664159, -0.05929083 0.0030466691 -0.33264145, -0.058973409 0.0032653026 -0.32664147, -0.058973365 0.0032656565 -0.33264139, -0.058717649 0.0035539083 -0.32664147, -0.058717657 0.0035545081 -0.33264145, -0.058538418 0.0038955919 -0.32664147, -0.058538388 0.0038959496 -0.33264145, -0.058446124 0.004270114 -0.32664147, -0.058446139 0.0042705946 -0.33264139, -0.058446139 0.0046558157 -0.32664135, -0.058446128 0.0046562962 -0.33264139, -0.058538381 0.005030226 -0.32664147, -0.058538381 0.0050307326 -0.33264139, -0.058717672 0.0053718276 -0.32664135, -0.058717702 0.0053722672 -0.33264139, -0.058973446 0.005660519 -0.32664135, -0.058973391 0.0056609921 -0.33264139, -0.05929089 0.0058797114 -0.32664123, -0.059290923 0.0058801286 -0.33264133, -0.059651501 0.006016437 -0.32664147, -0.059651487 0.0060168914 -0.33264133, -0.060034417 0.0060629584 -0.32664123, -0.06003442 0.0060634352 -0.33264133, -0.06003435 -0.0076370277 -0.32664207, -0.059531834 -0.0075759925 -0.32664219, -0.060034331 -0.0076369159 -0.32814208, -0.059531819 -0.0075758509 -0.32814208, -0.059058439 -0.007396508 -0.32664207, -0.059058484 -0.0073962547 -0.32814208, -0.058641825 -0.007108923 -0.32664219, -0.05864181 -0.0071087442 -0.32814208, -0.058306102 -0.0067300238 -0.32664204, -0.058306105 -0.0067297854 -0.32814208, -0.058070771 -0.0062818117 -0.32664204, -0.058070812 -0.0062816031 -0.32814208, -0.057949636 -0.0057902187 -0.32664207, -0.057949644 -0.005789984 -0.32814208, -0.057949696 -0.0052839592 -0.32664204, -0.057949707 -0.0052836686 -0.32814208, -0.058070824 -0.0047924407 -0.32664204, -0.058070805 -0.0047921687 -0.32814196, -0.058306098 -0.0043440759 -0.32664195, -0.058306072 -0.0043439344 -0.32814196, -0.05864184 -0.0039652176 -0.32664183, -0.058641855 -0.0039649494 -0.32814196, -0.059058469 -0.0036775954 -0.32664183, -0.059058487 -0.0036773793 -0.32814187, -0.059531789 -0.003498178 -0.32664183, -0.059531789 -0.0034979247 -0.32814196, -0.060034379 -0.0034371205 -0.32664183, -0.060034327 -0.0034369603 -0.32814196, -0.060034458 0.012362961 -0.3266409, -0.059531946 0.012423936 -0.32664093, -0.060034472 0.01236305 -0.32814091, -0.059531886 0.012424085 -0.32814091, -0.05905864 0.012603622 -0.32664093, -0.059058581 0.012603618 -0.328141, -0.058641937 0.012891032 -0.3266409, -0.058641914 0.012891244 -0.32814091, -0.058306225 0.013270009 -0.3266409, -0.058306195 0.013270129 -0.32814091, -0.058070987 0.013718296 -0.32664093, -0.058070924 0.013718497 -0.328141, -0.05794974 0.014209703 -0.3266409, -0.057949763 0.014209975 -0.32814091, -0.057949755 0.014716018 -0.3266409, -0.057949767 0.014716312 -0.32814091, -0.058070932 0.015207637 -0.3266409, -0.058070857 0.015207779 -0.32814091, -0.05830624 0.015655864 -0.32664078, -0.058306273 0.015656125 -0.32814065, -0.058642011 0.016034823 -0.32664087, -0.058641996 0.016035091 -0.32814091, -0.059058648 0.016322445 -0.32664075, -0.059058633 0.016322475 -0.32814077, -0.059531972 0.016501974 -0.3266409, -0.059531961 0.016502116 -0.32814091, -0.060034454 0.016562913 -0.32664075, -0.060034547 0.016563151 -0.32814091, -0.06053704 0.016501848 -0.32664078, -0.06053707 0.016502116 -0.32814077, -0.061010446 0.01632246 -0.32814077, -0.061010431 0.016322434 -0.32664075, -0.061427094 0.016035076 -0.32814091, -0.061427098 0.016034808 -0.32664075, -0.061762806 0.015656136 -0.32814091, -0.061762806 0.015655808 -0.32664075, -0.061997972 0.015207846 -0.32814091, -0.061997972 0.015207518 -0.32664087, -0.062119238 0.014716227 -0.32814091, -0.06211916 0.014716107 -0.32664087, -0.062119175 0.014209885 -0.32814091, -0.062119156 0.014209826 -0.3266409, -0.061997995 0.013718449 -0.32814091, -0.061998051 0.013718326 -0.3266409, -0.061762758 0.013270255 -0.32814091, -0.061762791 0.013269983 -0.32664093, -0.061427001 0.012891229 -0.328141, -0.061427005 0.012891021 -0.3266409, -0.061010383 0.012603633 -0.32814091, -0.061010424 0.012603465 -0.3266409, -0.060537059 0.012424115 -0.328141, -0.060537044 0.012423903 -0.32664093, -0.050534178 -0.035036627 -0.33264357, -0.069534242 -0.035036657 -0.33264357, -0.058432259 -0.013141755 -0.33264232, -0.058799222 -0.012442496 -0.33264232, -0.058573276 -0.012769964 -0.33264232, -0.059449207 -0.011993874 -0.33264229, -0.059097052 -0.012178656 -0.33264232, -0.060233187 -0.011898618 -0.33264232, -0.059835404 -0.011898641 -0.33264229, -0.060619406 -0.011993889 -0.33264232, -0.061269298 -0.012442511 -0.33264232, -0.060971648 -0.012178663 -0.33264232, -0.061636373 -0.0131418 -0.33264229, -0.061495267 -0.012769785 -0.33264232, -0.058527302 -0.0015627965 -0.33264178, -0.057620052 -0.0020389669 -0.33264178, -0.059522055 -0.0013175644 -0.33264172, -0.056853216 -0.0027183183 -0.33264178, -0.056271147 -0.0035615936 -0.33264181, -0.060546629 -0.0013175905 -0.33264178, -0.060417272 0.0029098094 -0.33264142, -0.060777936 0.0030466579 -0.33264145, -0.061541419 -0.0015628114 -0.33264181, -0.06109539 0.0032657646 -0.33264145, -0.062448595 -0.0020390451 -0.33264181, -0.061351154 0.0035544932 -0.33264145, -0.061530437 0.0038959347 -0.33264139, -0.063215524 -0.0027184077 -0.33264178, -0.063797534 -0.0035616085 -0.33264181, -0.061622784 0.004270453 -0.33264139, -0.061622784 0.0046562813 -0.33264139, -0.055907808 -0.0045195557 -0.33264181, -0.060417321 0.0060168505 -0.33264133, -0.060777985 0.0058801137 -0.33264133, -0.061095428 0.0056610033 -0.33264133, -0.06135121 0.0053722523 -0.33264139, -0.061530478 0.005030714 -0.33264139, -0.064160921 -0.0045195632 -0.33264181, -0.058527377 0.018437099 -0.33264068, -0.057620235 0.017961048 -0.33264068, -0.059522223 0.018682335 -0.33264056, -0.056853268 0.017281551 -0.33264068, -0.060546789 0.018682331 -0.33264068, -0.056271303 0.01643851 -0.33264074, -0.058432546 0.022858243 -0.33264035, -0.061541591 0.018437229 -0.33264068, -0.062448792 0.017961044 -0.33264068, -0.063215621 0.017281603 -0.33264068, -0.063797675 0.016438462 -0.33264068, -0.061636634 0.022858229 -0.33264035, -0.059835706 0.024101321 -0.33264035, -0.050534625 0.04396341 -0.33263913, -0.059449408 0.024006102 -0.33264023, -0.059097275 0.023821335 -0.33264035, -0.058799457 0.023557495 -0.33264035, -0.05857357 0.023230147 -0.33264044, -0.055908047 0.015480462 -0.33264083, -0.064161062 0.015480462 -0.33264083, -0.069534689 0.043963291 -0.33263916, -0.061495543 0.023230132 -0.33264035, -0.061269555 0.023557477 -0.33264035, -0.060971886 0.023821324 -0.33264035, -0.060619656 0.024006125 -0.33264035, -0.060233399 0.024101321 -0.33264035, -0.050534148 -0.03553706 -0.3271437, -0.069534272 -0.035537098 -0.3271437, -0.050534148 -0.035536531 -0.33214363, -0.06953419 -0.03553668 -0.3321436, -0.050034158 -0.032537047 -0.3266435, -0.070034213 -0.035037193 -0.32664371, -0.050034199 -0.035037015 -0.32664382, -0.070034236 -0.032537136 -0.3266435, -0.050034154 -0.031536784 -0.3296434, -0.070034236 -0.031536978 -0.32764331, -0.050034136 -0.031536873 -0.32764331, -0.070034206 -0.031536888 -0.32964349, -0.050034225 -0.01953673 -0.32964271, -0.070034251 -0.019536946 -0.32964268, -0.050034225 -0.019536834 -0.32764283, -0.07003428 -0.019536991 -0.32764286, -0.062119063 -0.0052839331 -0.32664207, -0.07003428 -0.018537257 -0.32664266, -0.062119074 -0.005790215 -0.32664204, -0.061997879 -0.0062818341 -0.32664204, -0.061636366 -0.013142224 -0.32664245, -0.061622795 0.0042699762 -0.32664147, -0.050034545 0.027462907 -0.32664016, -0.059097271 0.023820862 -0.32664031, -0.058799431 0.023557018 -0.32664031, -0.058573544 0.023229763 -0.32664043, -0.050034206 -0.018537086 -0.32664266, -0.070034578 0.02746281 -0.32664004, -0.061622757 0.0046557114 -0.32664135, -0.059449408 0.024005715 -0.32664037, -0.058432546 0.022857737 -0.32664037, -0.059835687 0.024100937 -0.32664031, -0.060233444 0.024100933 -0.32664031, -0.061636683 0.022857778 -0.32664025, -0.061495584 0.023229744 -0.32664031, -0.06126963 0.023557119 -0.32664031, -0.060971882 0.023820817 -0.32664037, -0.060619656 0.024005707 -0.32664037, -0.060417321 0.0060163438 -0.32664123, -0.060778026 0.0058796108 -0.32664135, -0.061095405 0.0056604408 -0.32664123, -0.061351229 0.0053718053 -0.32664147, -0.06153046 0.0050302371 -0.32664147, -0.060417332 0.0029094517 -0.32664147, -0.060536932 -0.0034982003 -0.32664183, -0.060778011 0.0030461513 -0.32664147, -0.061010297 -0.0036776252 -0.32664186, -0.061095364 0.003265284 -0.32664144, -0.061426956 -0.0039652511 -0.32664186, -0.06135115 0.0035539195 -0.32664147, -0.06176265 -0.0043441169 -0.32664195, -0.061530497 0.0038955733 -0.32664147, -0.061997876 -0.0047924146 -0.32664207, -0.058799259 -0.012442905 -0.32664245, -0.059097037 -0.012179162 -0.32664233, -0.058573324 -0.012770284 -0.32664233, -0.059449229 -0.011994239 -0.32664227, -0.058432259 -0.013142262 -0.32664233, -0.059835453 -0.011899125 -0.32664227, -0.060536917 -0.0075759925 -0.32664207, -0.060233209 -0.011899117 -0.32664233, -0.061010297 -0.0073964484 -0.32664207, -0.060619429 -0.011994224 -0.32664233, -0.061426938 -0.0071089529 -0.32664204, -0.060971651 -0.012179162 -0.32664233, -0.061762664 -0.0067300573 -0.32664204, -0.061269313 -0.012442958 -0.32664245, -0.061495334 -0.012770291 -0.32664245, -0.050034508 0.028463226 -0.32964003, -0.070034556 0.028463038 -0.32764006, -0.050034508 0.028463105 -0.32764006, -0.070034578 0.028463159 -0.32964006, -0.050034627 0.040463306 -0.32963949, -0.070034601 0.040463097 -0.32963935, -0.050034627 0.040463071 -0.32763937, -0.070034645 0.040463038 -0.32763928, -0.050034635 0.043962963 -0.32663918, -0.070034653 0.041462816 -0.32663947, -0.050034635 0.041463025 -0.32663947, -0.070034698 0.043962903 -0.32663918, -0.050534662 0.044463493 -0.33213916, -0.069534689 0.044463255 -0.3321391, -0.050534677 0.044462986 -0.32713908, -0.069534793 0.044462956 -0.32713911, -0.070034184 -0.035036746 -0.3321436, -0.070034638 0.043963287 -0.33213916, -0.050034169 -0.035036635 -0.3321436, -0.050034631 0.04396338 -0.33213916, -0.060536917 -0.0034979321 -0.32814196, -0.06101029 -0.0036773868 -0.32814175, -0.06142696 -0.0039649867 -0.32814187, -0.061762668 -0.0043439418 -0.32814196, -0.06199792 -0.0047922246 -0.32814196, -0.062119056 -0.0052838176 -0.32814208, -0.062119078 -0.0057900846 -0.32814208, -0.061997902 -0.0062815994 -0.32814208, -0.061762653 -0.0067297928 -0.32814208, -0.061426938 -0.0071088038 -0.32814208, -0.061010268 -0.0073964037 -0.32814208, -0.060536921 -0.0075758211 -0.32814208, -0.058704745 0.017969407 -0.32814065, -0.057904299 0.017549381 -0.32814065, -0.059582453 0.018185712 -0.32814065, -0.060486536 0.018185709 -0.32814065, -0.056393493 0.01536062 -0.32814091, -0.063675553 0.015360545 -0.32814085, -0.061364349 0.017969452 -0.32814062, -0.063355036 0.016205795 -0.32814091, -0.056714144 0.016205925 -0.32814091, -0.062164728 0.017549302 -0.32814065, -0.062841453 0.016949847 -0.32814077, -0.057227585 0.016949851 -0.32814077, -0.063675568 0.015360903 -0.33214074, -0.063355029 0.016206067 -0.33214071, -0.062841393 0.01695003 -0.33214074, -0.062164761 0.017549533 -0.33214051, -0.061364274 0.017969601 -0.33214071, -0.060486522 0.018186033 -0.33214071, -0.059582494 0.01818607 -0.33214051, -0.058704816 0.017969679 -0.33214071, -0.057904251 0.017549533 -0.33214051, -0.057227641 0.016950268 -0.33214071, -0.056714054 0.016206052 -0.33214074, -0.056393452 0.015360888 -0.33214077, -0.062164646 -0.0024506859 -0.32814175, -0.061364159 -0.0020305552 -0.32814187, -0.060486384 -0.0018142834 -0.32814175, -0.059582405 -0.0018141866 -0.32814175, -0.05639331 -0.0046394505 -0.32814196, -0.063675426 -0.0046394691 -0.32814196, -0.058704562 -0.002030544 -0.32814175, -0.056713887 -0.0037941523 -0.32814187, -0.057904169 -0.0024506487 -0.32814187, -0.057227474 -0.0030501597 -0.32814175, -0.06335485 -0.0037941411 -0.32814187, -0.062841281 -0.0030502789 -0.32814196, -0.063675411 -0.0046392493 -0.33214185, -0.06335482 -0.0037939437 -0.33214179, -0.062841371 -0.0030498728 -0.33214185, -0.062164668 -0.0024504662 -0.33214185, -0.061364129 -0.0020303316 -0.33214179, -0.060486402 -0.0018139668 -0.33214161, -0.059582356 -0.0018140338 -0.33214158, -0.058704559 -0.0020303652 -0.33214179, -0.057904154 -0.0024504252 -0.33214161, -0.057227403 -0.003049925 -0.33214179, -0.056713928 -0.003793858 -0.33214173, -0.056393337 -0.0046391375 -0.33214185, -0.061684478 0.014461931 -0.30635652, -0.061636541 0.014067106 -0.30635661, -0.061684445 0.014462259 -0.31235653, -0.061636508 0.014067378 -0.31235653, -0.061495524 0.013695296 -0.30635652, -0.061495479 0.013695505 -0.31235653, -0.061269548 0.013367798 -0.30635652, -0.061269529 0.013368066 -0.31235665, -0.060971778 0.013103988 -0.30635652, -0.060971834 0.013104435 -0.31235665, -0.060619581 0.012919247 -0.30635661, -0.060619567 0.012919515 -0.31235665, -0.060233332 0.012823999 -0.30635661, -0.060233358 0.01282433 -0.31235665, -0.059835646 0.012824003 -0.30635667, -0.059835576 0.012824245 -0.31235653, -0.059449408 0.012919251 -0.30635661, -0.059449356 0.012919489 -0.31235653, -0.059097152 0.013103999 -0.30635661, -0.059097163 0.01310445 -0.31235653, -0.058799472 0.013367809 -0.30635661, -0.058799416 0.013368048 -0.31235653, -0.058573436 0.013695192 -0.30635667, -0.058573466 0.013695519 -0.31235653, -0.058432456 0.014067214 -0.30635652, -0.058432456 0.014067426 -0.31235653, -0.058384463 0.014461953 -0.30635661, -0.058384482 0.014462274 -0.31235653, -0.061684292 -0.0055380873 -0.30635762, -0.061636399 -0.0059329048 -0.30635768, -0.061684366 -0.0055376962 -0.31235781, -0.061636385 -0.0059326366 -0.31235763, -0.061495405 -0.0063047856 -0.30635768, -0.061495308 -0.006304536 -0.31235757, -0.061269373 -0.0066321529 -0.30635786, -0.061269365 -0.0066318884 -0.31235781, -0.060971651 -0.0068959221 -0.30635777, -0.060971651 -0.0068956949 -0.31235781, -0.060619444 -0.0070809461 -0.30635795, -0.060619418 -0.0070805438 -0.31235781, -0.060233179 -0.0071760006 -0.30635795, -0.060233224 -0.0071757026 -0.31235781, -0.059835404 -0.0071760975 -0.30635768, -0.059835494 -0.0071757175 -0.31235757, -0.059449192 -0.0070809536 -0.30635786, -0.059449226 -0.0070805214 -0.31235781, -0.059097067 -0.0068958774 -0.30635768, -0.059097055 -0.0068956986 -0.31235781, -0.058799241 -0.006632261 -0.30635777, -0.058799297 -0.0066318661 -0.31235781, -0.058573347 -0.0063047931 -0.30635768, -0.058573384 -0.0063045099 -0.31235781, -0.058432296 -0.005932875 -0.30635768, -0.058432318 -0.0059325546 -0.31235763, -0.058384299 -0.005538065 -0.30635777, -0.058384344 -0.0055378005 -0.31235781, -0.060619459 -0.0039952099 -0.3063575, -0.060971685 -0.0041800216 -0.30635753, -0.06149539 -0.0047712699 -0.30635759, -0.061636373 -0.0051431917 -0.30635762, -0.069534205 -0.03503805 -0.30635929, -0.06023322 -0.0039001107 -0.30635753, -0.059835482 -0.003900107 -0.30635759, -0.050534207 -0.035037924 -0.30635929, -0.059449308 -0.0039951913 -0.3063575, -0.059097048 -0.0041799806 -0.30635768, -0.058799297 -0.0044438429 -0.30635759, -0.058432337 -0.005143173 -0.30635759, -0.058573354 -0.004771255 -0.30635759, -0.060233336 0.016099844 -0.30635646, -0.069534659 0.043961979 -0.30635491, -0.060619589 0.016004737 -0.30635643, -0.060971837 0.015819814 -0.30635646, -0.061269563 0.01555609 -0.30635652, -0.061495446 0.015228774 -0.30635643, -0.061636526 0.014856838 -0.30635652, -0.050534677 0.043962099 -0.30635491, -0.058432389 0.01485686 -0.30635652, -0.058573477 0.015228797 -0.30635646, -0.058799438 0.015556108 -0.30635652, -0.061269391 -0.0044438578 -0.30635759, -0.059097227 0.015819829 -0.30635643, -0.059449431 0.016004752 -0.30635643, -0.059835561 0.016099848 -0.30635646, -0.069534183 -0.035537828 -0.31185934, -0.050534129 -0.035537709 -0.31185934, -0.069534197 -0.03553817 -0.3068594, -0.050534159 -0.035537992 -0.3068594, -0.070034169 -0.032537792 -0.31235924, -0.05003415 -0.032537673 -0.31235924, -0.070034191 -0.035037857 -0.31235924, -0.050034165 -0.0350377 -0.31235933, -0.070034221 -0.031538058 -0.30935901, -0.050034087 -0.031537805 -0.31135911, -0.070034176 -0.031537872 -0.31135911, -0.050034132 -0.031537842 -0.30935901, -0.070034258 -0.019537974 -0.30935839, -0.050034225 -0.019537847 -0.30935848, -0.070034273 -0.019537892 -0.31135839, -0.050034236 -0.019537609 -0.31135839, -0.05003456 0.027462253 -0.31235579, -0.050034244 -0.018537726 -0.31235841, -0.058432363 -0.0051427633 -0.31235757, -0.060619514 -0.0039948821 -0.31235757, -0.0609717 -0.0041797534 -0.31235757, -0.061636448 -0.0051427744 -0.31235757, -0.061495379 -0.0047709085 -0.31235763, -0.060233228 -0.0038997382 -0.31235752, -0.070034549 0.02746219 -0.31235582, -0.060971852 0.015820231 -0.31235647, -0.061269488 0.015556481 -0.31235647, -0.061495502 0.015229043 -0.31235653, -0.060619574 0.016005192 -0.31235638, -0.05983549 -0.0038997419 -0.31235757, -0.061636496 0.01485708 -0.31235653, -0.060233351 0.016100232 -0.31235653, -0.059835546 0.016100116 -0.31235638, -0.059449244 -0.0039949827 -0.31235757, -0.059449341 0.016004987 -0.31235647, -0.059097044 -0.004179813 -0.31235757, -0.059097167 0.015820127 -0.31235638, -0.058799285 -0.0044436641 -0.31235757, -0.058799427 0.015556496 -0.31235647, -0.058573354 -0.0047708973 -0.31235757, -0.058573477 0.015229058 -0.31235647, -0.058432419 0.014857132 -0.31235647, -0.061269406 -0.0044436082 -0.31235757, -0.070034266 -0.018537823 -0.31235841, -0.070034541 0.028462084 -0.30935568, -0.050034534 0.028462175 -0.31135571, -0.070034578 0.028462145 -0.31135571, -0.050034508 0.028462032 -0.30935568, -0.070034601 0.040461987 -0.30935505, -0.050034579 0.040462177 -0.30935505, -0.070034653 0.0404622 -0.31135505, -0.050034609 0.040462323 -0.31135514, -0.070034608 0.043962218 -0.31235495, -0.050034616 0.041462339 -0.31235498, -0.070034683 0.04146222 -0.31235498, -0.050034661 0.0439624 -0.31235495, -0.069534674 0.044461973 -0.30685478, -0.050534647 0.044462062 -0.30685487, -0.069534704 0.044462301 -0.31185487, -0.050534707 0.04446245 -0.31185487, -0.050034132 -0.035038035 -0.30685917, -0.050034624 0.043962009 -0.30685487, -0.070034154 -0.035038102 -0.30685931, -0.070034683 0.043961857 -0.30685487, -0.21050063 0.11745176 -0.14049274, -0.21042791 0.11804995 -0.1404928, -0.21050063 0.11745131 -0.13399267, -0.21042797 0.11804965 -0.13399267, -0.21021432 0.11861354 -0.14049274, -0.21021429 0.11861315 -0.13399267, -0.20987187 0.1191095 -0.14049274, -0.20987189 0.11910918 -0.13399267, -0.20942083 0.11950922 -0.14049271, -0.20942082 0.11950882 -0.13399255, -0.20888719 0.1197893 -0.1404925, -0.20888713 0.11978887 -0.13399255, -0.20830196 0.11993349 -0.14049274, -0.20830202 0.11993319 -0.13399255, -0.20769927 0.11993349 -0.14049259, -0.20769928 0.11993307 -0.13399267, -0.20711407 0.1197893 -0.14049271, -0.20711407 0.11978887 -0.13399267, -0.2065804 0.11950919 -0.14049271, -0.20658046 0.11950883 -0.13399282, -0.2061294 0.11910947 -0.14049271, -0.2061294 0.11910918 -0.13399267, -0.20578709 0.1186136 -0.14049274, -0.20578708 0.11861315 -0.13399282, -0.20557329 0.11805004 -0.1404928, -0.20557323 0.11804962 -0.13399282, -0.20550066 0.11745182 -0.1404928, -0.20550063 0.11745131 -0.13399282, -0.18150058 0.11745182 -0.14049289, -0.18142784 0.11805016 -0.14049271, -0.18150067 0.11745158 -0.13399282, -0.18142796 0.11804982 -0.13399267, -0.18121424 0.11861375 -0.1404925, -0.18121421 0.11861341 -0.13399267, -0.18087187 0.11910971 -0.14049274, -0.1808719 0.11910933 -0.13399267, -0.18042074 0.11950937 -0.14049274, -0.18042068 0.11950901 -0.13399267, -0.17988709 0.11978941 -0.1404925, -0.17988703 0.11978905 -0.13399267, -0.17930195 0.11993368 -0.1404925, -0.17930195 0.11993338 -0.13399267, -0.17869928 0.11993366 -0.14049274, -0.1786993 0.11993338 -0.13399267, -0.17811419 0.1197895 -0.1404928, -0.17811415 0.11978912 -0.13399267, -0.17758039 0.1195094 -0.14049259, -0.17758039 0.11950898 -0.13399255, -0.1771294 0.11910979 -0.1404928, -0.17712933 0.11910942 -0.13399267, -0.17678702 0.11861384 -0.14049274, -0.17678694 0.11861339 -0.13399267, -0.17657322 0.11805013 -0.1404928, -0.17657319 0.11804979 -0.13399282, -0.17650062 0.11745194 -0.14049274, -0.1765006 0.11745152 -0.13399291, -0.21050073 0.12945171 -0.14049196, -0.21042798 0.13005003 -0.14049226, -0.2105006 0.12945133 -0.13399208, -0.21042791 0.1300496 -0.13399222, -0.21021435 0.13061361 -0.14049196, -0.21021441 0.13061321 -0.13399208, -0.20987196 0.1311096 -0.1404922, -0.20987201 0.13110916 -0.13399196, -0.20942086 0.13150916 -0.14049211, -0.20942086 0.1315088 -0.13399208, -0.20888732 0.13178934 -0.1404922, -0.20888722 0.13178891 -0.13399208, -0.20830214 0.13193357 -0.1404922, -0.20830211 0.13193317 -0.13399208, -0.20769942 0.13193351 -0.14049196, -0.20769939 0.13193312 -0.13399208, -0.20711426 0.1317893 -0.1404919, -0.20711422 0.13178891 -0.13399196, -0.20658061 0.13150924 -0.1404919, -0.20658058 0.13150881 -0.13399196, -0.2061294 0.13110952 -0.1404922, -0.20612952 0.13110915 -0.13399208, -0.20578694 0.13061354 -0.14049205, -0.20578694 0.13061318 -0.13399178, -0.20557328 0.13004997 -0.14049196, -0.20557328 0.13004968 -0.13399208, -0.20550065 0.12945169 -0.14049211, -0.20550057 0.12945133 -0.13399208, -0.18150067 0.12945187 -0.14049205, -0.18142803 0.13005026 -0.14049196, -0.18150063 0.12945154 -0.13399222, -0.18142815 0.13004994 -0.13399208, -0.18121429 0.13061382 -0.14049196, -0.1812143 0.13061333 -0.13399208, -0.18087195 0.13110976 -0.14049205, -0.18087199 0.13110939 -0.13399208, -0.18042083 0.13150938 -0.14049211, -0.18042091 0.13150901 -0.13399178, -0.17988719 0.13178946 -0.14049196, -0.17988718 0.13178909 -0.13399208, -0.17930204 0.13193366 -0.14049196, -0.17930204 0.13193336 -0.13399208, -0.17869937 0.13193367 -0.1404922, -0.17869939 0.13193329 -0.13399196, -0.17811416 0.13178945 -0.1404919, -0.17811427 0.13178912 -0.13399208, -0.17758051 0.1315093 -0.14049196, -0.17758057 0.13150901 -0.13399208, -0.17712945 0.13110977 -0.14049196, -0.1771294 0.13110939 -0.13399208, -0.17678706 0.13061379 -0.14049211, -0.17678702 0.13061336 -0.13399196, -0.17657329 0.13005015 -0.14049226, -0.17657329 0.13004985 -0.13399222, -0.17650066 0.12945189 -0.1404922, -0.17650066 0.12945148 -0.13399208, -0.21600048 0.11145175 -0.14049312, -0.21600053 0.11145134 -0.13399306, -0.2160009 0.1474517 -0.14049116, -0.21600075 0.14745125 -0.13399112, -0.21400058 0.10945171 -0.1404933, -0.17300057 0.10945195 -0.14049333, -0.21400055 0.10945135 -0.13399321, -0.1730006 0.10945161 -0.1339933, -0.17100082 0.14745164 -0.13399112, -0.1710005 0.11145194 -0.14049312, -0.17100078 0.14745189 -0.14049122, -0.17100053 0.11145164 -0.13399315, -0.21400069 0.14945129 -0.13399088, -0.17300077 0.14945158 -0.13399112, -0.2140009 0.14945172 -0.14049107, -0.17300083 0.14945197 -0.14049107, -0.21021433 0.12828994 -0.14049226, -0.20987196 0.12779388 -0.14049229, -0.20942087 0.12739427 -0.14049226, -0.20888729 0.12711413 -0.14049229, -0.20830207 0.12696992 -0.14049229, -0.20769939 0.12696993 -0.14049229, -0.21042798 0.12885341 -0.14049226, -0.21042791 0.11685339 -0.1404928, -0.20711422 0.12711427 -0.14049226, -0.21021426 0.11628999 -0.1404928, -0.20658043 0.12739426 -0.14049226, -0.20612937 0.12779388 -0.1404922, -0.2098718 0.11579385 -0.14049289, -0.205787 0.12828991 -0.14049226, -0.20942065 0.11539416 -0.14049301, -0.2088871 0.11511421 -0.14049301, -0.20830199 0.11496997 -0.14049301, -0.20769927 0.11496997 -0.14049301, -0.20711407 0.11511415 -0.14049301, -0.2065805 0.11539432 -0.14049301, -0.18142807 0.12885363 -0.14049205, -0.20557332 0.12885341 -0.1404922, -0.18121426 0.12829013 -0.14049229, -0.18087198 0.1277941 -0.14049226, -0.1804208 0.12739436 -0.1404922, -0.17988722 0.12711434 -0.14049241, -0.17930208 0.12697007 -0.14049229, -0.17869936 0.12697016 -0.14049229, -0.18142796 0.11685361 -0.1404928, -0.2055732 0.11685352 -0.1404928, -0.17811424 0.12711439 -0.14049226, -0.18121423 0.11629009 -0.14049289, -0.20612937 0.11579393 -0.14049295, -0.205787 0.11629 -0.1404928, -0.17758051 0.12739445 -0.14049226, -0.17712945 0.12779419 -0.14049226, -0.18087186 0.11579411 -0.1404928, -0.17678697 0.12829016 -0.14049226, -0.18042077 0.11539449 -0.1404928, -0.17657325 0.12885368 -0.14049205, -0.17712928 0.11579405 -0.14049274, -0.17678694 0.11629014 -0.1404928, -0.17657317 0.11685354 -0.1404928, -0.17988697 0.11511434 -0.14049307, -0.17930189 0.11497019 -0.1404928, -0.17869918 0.11497014 -0.14049301, -0.17811407 0.11511435 -0.14049295, -0.17758043 0.11539443 -0.1404928, -0.21021418 0.12828951 -0.13399222, -0.20987193 0.12779354 -0.13399208, -0.20942089 0.12739393 -0.13399231, -0.20888716 0.12711379 -0.13399231, -0.20830193 0.1269695 -0.13399231, -0.20769942 0.12696968 -0.13399208, -0.21042798 0.12885305 -0.13399222, -0.21042794 0.116853 -0.13399282, -0.20711419 0.12711388 -0.13399222, -0.2102142 0.1162895 -0.13399282, -0.20658055 0.1273939 -0.13399246, -0.20612945 0.12779358 -0.13399208, -0.20987187 0.11579354 -0.13399294, -0.205787 0.12828961 -0.13399222, -0.20942076 0.11539388 -0.13399294, -0.20888722 0.11511387 -0.13399294, -0.20830193 0.11496954 -0.13399294, -0.20769921 0.11496957 -0.13399294, -0.20711416 0.11511388 -0.13399294, -0.20658046 0.11539392 -0.133993, -0.18142794 0.12885328 -0.13399222, -0.20557332 0.12885313 -0.13399231, -0.18121421 0.12828967 -0.13399222, -0.18087199 0.12779379 -0.13399231, -0.18042085 0.12739407 -0.13399222, -0.17988709 0.12711398 -0.13399222, -0.17930204 0.12696978 -0.13399222, -0.17869928 0.1269698 -0.13399222, -0.20557326 0.11685315 -0.13399267, -0.18142806 0.11685333 -0.13399282, -0.17811412 0.12711397 -0.13399231, -0.20612934 0.11579353 -0.133993, -0.18121432 0.11628969 -0.13399306, -0.20578685 0.11628956 -0.13399282, -0.17758048 0.12739408 -0.13399222, -0.17712942 0.12779379 -0.13399231, -0.18087184 0.11579372 -0.133993, -0.17678702 0.1282898 -0.13399222, -0.18042077 0.11539406 -0.13399294, -0.17657325 0.12885323 -0.13399231, -0.17712931 0.11579369 -0.1339927, -0.17678697 0.11628965 -0.13399282, -0.17657323 0.11685324 -0.13399282, -0.17988709 0.11511399 -0.13399294, -0.17930186 0.11496972 -0.13399294, -0.17869924 0.11496979 -0.13399294, -0.1781141 0.11511393 -0.133993, -0.1775804 0.11539401 -0.13399291, 0.21049958 0.11745441 -0.14049271, 0.21042699 0.11685611 -0.1404928, 0.21049958 0.11745405 -0.13399282, 0.21042694 0.1168557 -0.13399291, 0.21021332 0.11629255 -0.14049289, 0.21021332 0.11629218 -0.13399282, 0.20987087 0.11579655 -0.1404928, 0.20987082 0.11579615 -0.13399282, 0.20941982 0.11539689 -0.14049307, 0.2094197 0.11539657 -0.13399294, 0.20888612 0.11511682 -0.14049307, 0.20888616 0.11511654 -0.13399294, 0.20830095 0.11497268 -0.14049301, 0.20830099 0.11497226 -0.133993, 0.20769827 0.11497259 -0.14049301, 0.20769823 0.11497228 -0.133993, 0.20711315 0.11511689 -0.14049295, 0.20711309 0.11511652 -0.13399294, 0.2065794 0.11539698 -0.14049289, 0.20657936 0.11539656 -0.13399294, 0.2061283 0.11579654 -0.1404928, 0.2061283 0.11579618 -0.13399294, 0.20578596 0.11629257 -0.1404928, 0.20578595 0.11629222 -0.13399291, 0.20557228 0.11685607 -0.1404928, 0.20557225 0.11685565 -0.13399291, 0.20549965 0.11745438 -0.14049271, 0.20549953 0.11745401 -0.13399291, 0.18149954 0.11745424 -0.1404928, 0.18142688 0.11685598 -0.14049274, 0.1814996 0.11745387 -0.13399291, 0.18142694 0.11685558 -0.13399291, 0.1812132 0.11629239 -0.14049289, 0.18121323 0.11629207 -0.13399291, 0.18087083 0.11579639 -0.1404928, 0.18087083 0.11579606 -0.13399294, 0.18041976 0.11539671 -0.14049289, 0.18041976 0.1153964 -0.13399291, 0.17988607 0.11511677 -0.14049295, 0.1798861 0.1151163 -0.13399291, 0.17930083 0.11497246 -0.14049301, 0.17930093 0.11497208 -0.13399294, 0.17869827 0.11497246 -0.1404928, 0.17869824 0.11497205 -0.133993, 0.17811312 0.11511667 -0.14049289, 0.17811315 0.11511633 -0.13399294, 0.1775794 0.11539678 -0.14049309, 0.1775794 0.11539639 -0.13399294, 0.17712834 0.11579637 -0.1404928, 0.17712827 0.11579596 -0.13399282, 0.1767858 0.1162924 -0.1404928, 0.17678598 0.11629197 -0.13399291, 0.17657217 0.11685589 -0.1404928, 0.17657226 0.11685548 -0.13399291, 0.1764995 0.11745426 -0.1404928, 0.17649955 0.11745384 -0.13399291, 0.21049947 0.12945443 -0.14049196, 0.21042676 0.12885612 -0.14049226, 0.21049953 0.12945402 -0.13399222, 0.21042691 0.12885572 -0.13399222, 0.21021318 0.12829264 -0.1404922, 0.21021317 0.12829228 -0.13399231, 0.2098708 0.12779659 -0.14049226, 0.20987082 0.12779617 -0.13399222, 0.20941971 0.12739694 -0.14049226, 0.20941971 0.12739657 -0.13399231, 0.208886 0.12711692 -0.14049226, 0.20888604 0.12711649 -0.13399222, 0.20830086 0.12697268 -0.14049226, 0.20830077 0.12697226 -0.13399222, 0.2076982 0.12697262 -0.14049226, 0.20769821 0.12697218 -0.13399222, 0.20711294 0.12711687 -0.14049226, 0.207113 0.12711655 -0.13399231, 0.20657933 0.12739688 -0.14049226, 0.2065793 0.12739655 -0.13399231, 0.20612822 0.12779658 -0.14049226, 0.20612821 0.1277962 -0.13399222, 0.20578586 0.12829259 -0.1404922, 0.20578586 0.12829223 -0.13399222, 0.20557213 0.12885615 -0.14049226, 0.20557213 0.12885574 -0.13399222, 0.20549944 0.12945433 -0.14049205, 0.20549953 0.12945393 -0.13399208, 0.18149947 0.12945415 -0.1404922, 0.18142679 0.12885594 -0.14049226, 0.18149951 0.12945379 -0.13399231, 0.18142685 0.12885559 -0.13399222, 0.18121313 0.12829246 -0.1404922, 0.18121317 0.12829204 -0.13399222, 0.18087085 0.12779637 -0.14049226, 0.18087074 0.12779605 -0.13399222, 0.18041967 0.12739678 -0.14049226, 0.18041959 0.12739636 -0.13399222, 0.17988595 0.12711667 -0.14049226, 0.17988595 0.12711635 -0.13399222, 0.17930086 0.12697245 -0.14049226, 0.17930086 0.12697206 -0.13399222, 0.17869814 0.12697248 -0.14049211, 0.1786982 0.12697202 -0.13399222, 0.17811298 0.12711667 -0.14049226, 0.17811303 0.12711625 -0.13399231, 0.17757934 0.12739669 -0.14049226, 0.17757927 0.12739633 -0.13399222, 0.1771283 0.12779631 -0.14049226, 0.17712826 0.12779608 -0.13399231, 0.17678593 0.12829235 -0.1404922, 0.17678592 0.12829205 -0.13399222, 0.1765721 0.12885597 -0.14049211, 0.17657219 0.12885551 -0.13399222, 0.17649943 0.12945418 -0.14049211, 0.17649947 0.12945375 -0.13399208, 0.21599966 0.11145447 -0.14049312, 0.21599942 0.14745401 -0.13399118, 0.2159996 0.11145411 -0.13399321, 0.21599944 0.14745443 -0.1404911, 0.17299956 0.10945417 -0.14049333, 0.21399969 0.10945411 -0.13399321, 0.17299961 0.1094538 -0.13399321, 0.2139997 0.10945442 -0.14049333, 0.17099932 0.14745386 -0.13399112, 0.17099947 0.14745414 -0.1404911, 0.17099969 0.11145383 -0.13399321, 0.17099965 0.11145419 -0.14049312, 0.17299934 0.1494538 -0.13399088, 0.21399938 0.14945444 -0.14049107, 0.17299931 0.14945419 -0.14049098, 0.21399944 0.14945412 -0.13399088, 0.21042699 0.11805266 -0.14049271, 0.21021324 0.11861616 -0.1404928, 0.20941979 0.1195119 -0.14049274, 0.20888607 0.11979198 -0.14049274, 0.20987085 0.11911219 -0.14049274, 0.20830087 0.11993615 -0.1404925, 0.20769823 0.11993609 -0.1404925, 0.20711301 0.11979204 -0.14049271, 0.20657933 0.11951187 -0.1404928, 0.20612836 0.11911218 -0.14049274, 0.20578592 0.11861613 -0.14049274, 0.20888595 0.13179195 -0.1404919, 0.2083008 0.13193619 -0.14049196, 0.20941973 0.13151184 -0.14049196, 0.20987073 0.13111222 -0.14049205, 0.21021323 0.13061623 -0.14049211, 0.21042687 0.13005269 -0.1404922, 0.20711297 0.13179192 -0.14049196, 0.20657933 0.1315119 -0.14049196, 0.20769823 0.13193606 -0.14049196, 0.1814269 0.1180525 -0.14049271, 0.20557222 0.11805269 -0.1404928, 0.1812132 0.11861598 -0.14049274, 0.17657214 0.11805245 -0.14049271, 0.17678589 0.11861597 -0.1404925, 0.18087088 0.11911203 -0.14049274, 0.1804197 0.11951166 -0.14049274, 0.17988612 0.11979178 -0.1404925, 0.17930093 0.11993602 -0.14049274, 0.17869823 0.11993597 -0.14049259, 0.18142682 0.13005251 -0.1404922, 0.20557219 0.13005263 -0.14049211, 0.17811301 0.11979179 -0.1404925, 0.18121324 0.13061604 -0.14049211, 0.20578596 0.13061611 -0.14049196, 0.20612818 0.13111214 -0.14049211, 0.17757946 0.1195116 -0.14049271, 0.17712839 0.11911191 -0.14049274, 0.18087074 0.1311121 -0.1404922, 0.18041967 0.13151161 -0.14049196, 0.17657213 0.13005249 -0.1404922, 0.17678593 0.13061593 -0.14049205, 0.17712818 0.13111202 -0.14049196, 0.17757927 0.1315117 -0.14049196, 0.17811298 0.13179177 -0.14049196, 0.17869815 0.13193595 -0.14049187, 0.17930071 0.13193601 -0.1404922, 0.17988598 0.13179177 -0.14049196, 0.2104269 0.1180523 -0.13399267, 0.2102132 0.1186159 -0.13399267, 0.20987092 0.11911178 -0.13399267, 0.2094197 0.11951149 -0.13399267, 0.208886 0.11979163 -0.13399252, 0.20830095 0.11993586 -0.1339927, 0.20769823 0.11993586 -0.13399267, 0.20711309 0.11979155 -0.13399252, 0.20657942 0.11951151 -0.13399267, 0.20612825 0.11911182 -0.13399267, 0.20578587 0.11861585 -0.13399252, 0.20888601 0.13179158 -0.13399196, 0.20830083 0.13193578 -0.13399208, 0.20941961 0.13151148 -0.13399208, 0.20987074 0.13111186 -0.13399208, 0.21021317 0.13061583 -0.13399222, 0.2104269 0.13005222 -0.13399208, 0.20711297 0.1317915 -0.13399208, 0.20657936 0.13151155 -0.13399208, 0.20769811 0.13193576 -0.13399208, 0.20557214 0.11805233 -0.1339927, 0.1814269 0.1180522 -0.13399267, 0.18121317 0.1186157 -0.13399267, 0.17657222 0.1180521 -0.13399267, 0.17678592 0.1186156 -0.13399267, 0.18041971 0.11951131 -0.13399267, 0.17988607 0.11979136 -0.13399267, 0.18087091 0.11911166 -0.13399267, 0.17930093 0.1199356 -0.13399267, 0.17869823 0.1199356 -0.13399267, 0.20557222 0.1300523 -0.13399208, 0.18142691 0.13005212 -0.13399208, 0.1781131 0.11979137 -0.13399267, 0.1812132 0.13061565 -0.13399208, 0.20578584 0.13061593 -0.13399196, 0.20612825 0.13111185 -0.13399222, 0.17757936 0.11951135 -0.13399267, 0.18087076 0.13111176 -0.13399208, 0.1771283 0.11911157 -0.13399267, 0.18041964 0.13151139 -0.13399208, 0.17930083 0.13193564 -0.13399208, 0.17869817 0.13193558 -0.13399208, 0.17988595 0.13179147 -0.13399208, 0.17657222 0.13005206 -0.13399208, 0.17678586 0.13061556 -0.13399222, 0.17712818 0.13111164 -0.13399208, 0.17757936 0.13151132 -0.13399208, 0.17811307 0.13179132 -0.13399196, -0.11685908 0.057089545 -0.29606265, -0.11817721 0.05674658 -0.29726478, -0.11730927 0.057334971 -0.2956855, -0.081072226 0.043507449 -0.31383142, -0.079463407 0.043379225 -0.31408784, -0.079657629 0.044185195 -0.31586438, -0.087473996 0.045514777 -0.31768489, -0.085834131 0.045237236 -0.3165409, -0.086335085 0.045323636 -0.31843415, -0.11784828 0.049625728 -0.30776411, -0.11514699 0.048097964 -0.31081933, -0.11629795 0.046544686 -0.3111451, -0.11907291 0.048114169 -0.30800632, -0.087368764 0.045164455 -0.31991133, -0.088481314 0.045328598 -0.31958306, -0.099361673 0.047368851 -0.30610892, -0.097420439 0.046699632 -0.30744752, -0.1001496 0.048293948 -0.30764729, -0.089210346 0.045581043 -0.31876191, -0.089584388 0.045856271 -0.31700182, -0.090595394 0.046004258 -0.31707317, -0.089934736 0.045892306 -0.31523091, -0.090677723 0.04569301 -0.31885427, -0.10268509 0.049361002 -0.3099927, -0.10369224 0.049174674 -0.31189135, -0.10435743 0.049633268 -0.31065792, -0.084151879 0.044699349 -0.32095549, -0.086878769 0.045029663 -0.3202945, -0.10220495 0.0491101 -0.31086186, -0.10110967 0.048881844 -0.30925202, -0.083714589 0.045006163 -0.31906947, -0.077652723 0.030072615 -0.32827669, -0.072952874 0.031420603 -0.32902354, -0.072952926 0.029990211 -0.32844165, -0.10435585 0.050031215 -0.30865246, -0.1054491 0.049867887 -0.31050509, -0.103706 0.038335439 -0.32175338, -0.099936329 0.035815768 -0.323594, -0.10400954 0.036833972 -0.32155785, -0.10629852 0.05022864 -0.30978352, -0.10556053 0.050466895 -0.30814826, -0.12035505 0.048934329 -0.30636629, -0.12007782 0.046431147 -0.30798364, -0.10433958 0.050187919 -0.30664, -0.12138802 0.047269091 -0.30630806, -0.099672541 0.037327141 -0.32376984, -0.082958505 0.044478282 -0.31527811, -0.081609651 0.044764902 -0.31748569, -0.083311677 0.044931542 -0.31715229, -0.11390826 0.055773262 -0.29716903, -0.11363573 0.055321064 -0.29844055, -0.11535101 0.055670135 -0.29890114, -0.096543953 0.044016112 -0.30475378, -0.095250487 0.043613762 -0.3055585, -0.096877962 0.045487866 -0.30600491, -0.11587951 0.056137733 -0.29796612, -0.11579718 0.056509867 -0.29690582, -0.098294035 0.04298294 -0.30245784, -0.095143877 0.041940439 -0.3045429, -0.11211242 0.054860186 -0.29729602, -0.081314459 0.044317212 -0.31560013, -0.12262383 0.048129331 -0.30458787, -0.12191066 0.046144135 -0.30613711, -0.12315962 0.047013521 -0.30439827, -0.11486331 0.056681566 -0.29535264, -0.11557747 0.057148479 -0.29478601, -0.11398153 0.056619287 -0.29377851, -0.098136671 0.042113934 -0.32278678, -0.094759449 0.039561212 -0.3251113, -0.098823577 0.040397622 -0.32343861, -0.094180256 0.041299798 -0.32441512, -0.086389378 0.04529031 -0.31617686, -0.10597615 0.03739582 -0.32043397, -0.1041948 0.035354432 -0.32115629, -0.1061731 0.035919562 -0.32002586, -0.085394874 0.044773579 -0.31468755, -0.11092755 0.051221691 -0.30834085, -0.10964072 0.049146444 -0.31206158, -0.11240923 0.050482158 -0.3093901, -0.10826305 0.049936004 -0.31091201, -0.079230204 0.040814646 -0.31115669, -0.076101176 0.040649198 -0.31148726, -0.076145768 0.042073455 -0.31283364, -0.076867193 0.039020851 -0.31038156, -0.087406069 0.045351341 -0.31527323, -0.079319075 0.042241015 -0.31249836, -0.080743939 0.039277613 -0.30986813, -0.12540063 0.046954617 -0.30131775, -0.12395751 0.04417032 -0.30352542, -0.1257133 0.045535371 -0.30079558, -0.088439941 0.04560731 -0.31554288, -0.089355767 0.045406196 -0.31342238, -0.10217471 0.049281642 -0.30819455, -0.12365533 0.045597792 -0.30403134, -0.10337761 0.039543904 -0.32175756, -0.099387348 0.038546469 -0.32375228, -0.11645125 0.050907709 -0.30726644, -0.10810042 0.03651908 -0.318827, -0.10817031 0.035098821 -0.31822485, -0.102552 0.049403206 -0.30716977, -0.08089222 0.042366412 -0.31224746, -0.11383392 0.049427327 -0.31022695, -0.10376906 0.049939748 -0.30687848, -0.1032695 0.049555462 -0.30512431, -0.098776311 0.046142317 -0.3046962, -0.11225899 0.055043142 -0.2966722, -0.11077733 0.054068465 -0.29609877, -0.1123887 0.055316217 -0.29534456, -0.11909643 0.050424073 -0.30616784, -0.11321025 0.05591524 -0.29492813, -0.082668602 0.043663759 -0.3135187, -0.11258265 0.055767488 -0.29270104, -0.12156446 0.049776178 -0.3046827, -0.086173996 0.044756554 -0.31408411, -0.085034385 0.043950532 -0.31294519, -0.10565327 0.038891699 -0.32064071, -0.088144876 0.04506807 -0.31346121, -0.088880479 0.044564884 -0.3117165, -0.12488782 0.048357036 -0.30171132, -0.097352982 0.043629717 -0.32182166, -0.09351974 0.042840969 -0.32339931, -0.1008864 0.048476774 -0.30664423, -0.10944592 0.05161747 -0.30711973, -0.10688531 0.050381918 -0.30959052, -0.10243198 0.049105957 -0.30538562, -0.107892 0.03799177 -0.31924236, -0.10239124 0.04859392 -0.30365893, -0.11095311 0.054228026 -0.29514223, -0.10968155 0.052976161 -0.29489499, -0.11493522 0.051910877 -0.30653277, -0.1027289 0.04137389 -0.3214865, -0.11185674 0.05507113 -0.29345623, -0.11143445 0.054625947 -0.2915954, -0.080781445 0.040938284 -0.3109093, -0.098415762 0.044661321 -0.30346337, -0.086390227 0.044048566 -0.31237903, -0.084766582 0.042799745 -0.31138101, -0.087109178 0.043854132 -0.31163913, -0.11766043 0.051681109 -0.30571988, -0.088301569 0.044364076 -0.31174821, -0.088527456 0.043400448 -0.3101795, -0.10530435 0.040094461 -0.32065666, -0.099739552 0.047424048 -0.30562863, -0.12433358 0.049458671 -0.30192935, -0.12027365 0.051243473 -0.30452877, -0.082453191 0.042519346 -0.31194174, -0.10041851 0.047414742 -0.30451834, -0.10126505 0.0480281 -0.3044208, -0.096502669 0.04488663 -0.32058069, -0.092803016 0.044125274 -0.32210323, -0.10173864 0.047340233 -0.30230057, -0.11025287 0.053430792 -0.29361612, -0.1088673 0.051625431 -0.2937308, -0.10802101 0.051654171 -0.30577379, -0.10755037 0.039481893 -0.31946057, -0.11335865 0.052596692 -0.3055909, -0.11035594 0.05338826 -0.29257199, -0.110889 0.037480336 -0.3169044, -0.11186719 0.036399286 -0.31562403, -0.11110786 0.054257765 -0.29196188, -0.11058146 0.053238567 -0.29050449, -0.085809521 0.042687949 -0.31078592, -0.084601656 0.041365452 -0.3100549, -0.10193831 0.043064255 -0.32088616, -0.087681614 0.042990401 -0.31018117, -0.088310048 0.041957781 -0.30887023, -0.11610243 0.052657355 -0.30504012, -0.099339284 0.046109051 -0.30394423, -0.10082041 0.046703711 -0.30275485, -0.12323774 0.051077101 -0.30208099, -0.10133666 0.045842551 -0.30110133, -0.10461441 0.041912381 -0.32040903, -0.1188011 0.052475188 -0.30413207, -0.10926522 0.051779959 -0.29260281, -0.082320586 0.041089073 -0.3106077, -0.10836582 0.050067849 -0.29265091, -0.10670806 0.051330794 -0.30435458, -0.11011323 0.052585442 -0.29099229, -0.08454594 0.039702781 -0.30901778, -0.11005612 0.051658563 -0.28946987, -0.10718115 0.040678158 -0.31948918, -0.11178206 0.052938893 -0.30447719, -0.085128412 0.041282918 -0.30978814, -0.086166449 0.040957507 -0.3091363, -0.088236652 0.04029236 -0.30783883, -0.095618188 0.045836113 -0.31911135, -0.092057578 0.04510342 -0.32057664, -0.086988285 0.041570175 -0.30921364, -0.099464215 0.044907838 -0.30253872, -0.1106642 0.038947474 -0.31733119, -0.11448205 0.053315099 -0.30415413, -0.10003348 0.044667244 -0.30171704, -0.10103633 0.044550531 -0.31998044, -0.10120103 0.044158477 -0.300107, -0.10090985 0.045504861 -0.30134451, -0.10859637 0.050125364 -0.29210418, -0.10819662 0.048363607 -0.29169732, -0.12190264 0.052509915 -0.30199623, -0.10902239 0.050070681 -0.29091102, -0.1098787 0.049946632 -0.28853133, -0.10945952 0.050916195 -0.29052252, -0.11720323 0.053423718 -0.3035073, -0.10555714 0.050659232 -0.30291677, -0.10377364 0.043588698 -0.31983742, -0.11026611 0.052924033 -0.30323437, -0.10645117 0.042483855 -0.31926647, -0.11029543 0.040428095 -0.31756812, -0.12037935 0.053702138 -0.30167821, -0.1128616 0.053629197 -0.30309662, -0.094733946 0.046442062 -0.31746989, -0.091312088 0.045737859 -0.31887829, -0.10005751 0.045775291 -0.31880343, -0.1155415 0.054052699 -0.30267921, -0.077643394 0.031502794 -0.328859, -0.077615559 0.033005252 -0.32921466, -0.072952941 0.032923624 -0.3293784, -0.10461263 0.049665719 -0.30151525, -0.10886899 0.052552965 -0.30191037, -0.1028146 0.045058586 -0.31896436, -0.077570111 0.034544095 -0.32933554, -0.072952911 0.034463271 -0.32949752, -0.10989686 0.041614376 -0.317617, -0.11872653 0.054607928 -0.30113912, -0.10556176 0.044144802 -0.31872544, -0.077520721 0.035793059 -0.32925871, -0.1113036 0.053587545 -0.30190754, -0.072952881 0.036364242 -0.32931507, -0.0938835 0.046680875 -0.3157199, -0.082305111 0.031749211 -0.32836634, -0.08232373 0.030319497 -0.32778302, -0.11387972 0.054337978 -0.3016791, -0.082249753 0.033250228 -0.32872501, -0.10391073 0.04838831 -0.30020452, -0.099039607 0.046691451 -0.31740075, -0.077423394 0.037703022 -0.32882777, -0.072952919 0.038195983 -0.3287746, -0.10764448 0.05183984 -0.3005558, -0.084616184 0.031933486 -0.32799786, -0.086937144 0.030729162 -0.32696381, -0.10177386 0.046265561 -0.31782269, -0.11700757 0.055192452 -0.30039978, -0.082158834 0.034786634 -0.32885066, -0.10986748 0.053191599 -0.30063319, -0.109109 0.043400105 -0.31743401, -0.11228191 0.05426858 -0.30054533, -0.077304661 0.03949108 -0.32803261, -0.072952926 0.039891616 -0.32789543, -0.10454696 0.045597434 -0.31788656, -0.084547073 0.033433318 -0.32835877, -0.10347853 0.046875995 -0.29903433, -0.10383681 0.045455426 -0.29751295, -0.093099877 0.046543606 -0.31392831, -0.10663946 0.05081211 -0.29922295, -0.082060568 0.036033053 -0.32877892, -0.10860887 0.052456707 -0.2993221, -0.086909398 0.032158155 -0.32754853, -0.084433764 0.034967996 -0.32848769, -0.09802182 0.047263958 -0.31582636, -0.11528866 0.055433232 -0.29948863, -0.10069158 0.04716333 -0.31645697, -0.1108093 0.053847216 -0.29932195, -0.077169314 0.041088387 -0.32690424, -0.072952911 0.041389123 -0.32671025, -0.10589272 0.049509224 -0.29796287, -0.086826622 0.033656582 -0.32791212, -0.10814901 0.045036796 -0.31694144, -0.10344593 0.046785686 -0.3167828, -0.10757596 0.051411074 -0.29802486, -0.081866331 0.037937749 -0.32835808, -0.084311202 0.036212478 -0.32841995, -0.077022389 0.042433795 -0.32548597, -0.10951854 0.053089943 -0.29805559, -0.092412919 0.04603545 -0.31216386, -0.072952874 0.042634055 -0.32526189, -0.10543276 0.047981314 -0.29682386, -0.10617619 0.046861731 -0.29470068, -0.09704306 0.047470637 -0.31414038, -0.086691007 0.035189141 -0.32804552, -0.10680838 0.050094884 -0.29679137, -0.090307772 0.032569967 -0.32672495, -0.091464698 0.031299196 -0.32582355, -0.10705372 0.046461597 -0.31615847, -0.081629694 0.039719544 -0.32757559, -0.099609286 0.047717478 -0.31491929, -0.084068969 0.038113479 -0.32800689, -0.1084593 0.052026007 -0.29679531, -0.1063358 0.04855888 -0.29566893, -0.086544409 0.036431238 -0.32798246, -0.10767215 0.050696198 -0.29558891, -0.11843176 0.040779799 -0.31030589, -0.11532496 0.037825339 -0.31277195, -0.11852235 0.039368071 -0.30968681, -0.076869488 0.043475468 -0.3238326, -0.072952971 0.043580905 -0.32360324, -0.1152408 0.039240133 -0.31338519, -0.10230076 0.047663875 -0.315456, -0.090204954 0.034065988 -0.3270933, -0.10718744 0.04915173 -0.29448324, -0.091849163 0.045175802 -0.31049472, -0.096141115 0.047303755 -0.31240791, -0.081359699 0.0413098 -0.32646155, -0.083773836 0.039890446 -0.32723358, -0.11816229 0.042227365 -0.31077173, -0.11499016 0.040696677 -0.31383279, -0.086254552 0.038327508 -0.32757869, -0.090868652 0.032647219 -0.32657021, -0.10586532 0.047619693 -0.31511471, -0.092510633 0.033386298 -0.32622567, -0.093646273 0.033070508 -0.32572398, -0.095878467 0.032026194 -0.32436979, -0.090036303 0.035594463 -0.32723492, -0.098568559 0.047906555 -0.31326869, -0.094378904 0.033193618 -0.32547784, -0.095832847 0.0334525 -0.3249599, -0.095697239 0.034943517 -0.32533848, -0.092886604 0.035235357 -0.326379, -0.076716721 0.044173442 -0.32200685, -0.072952956 0.04419513 -0.32179502, -0.095474914 0.036463372 -0.32549742, -0.08106669 0.042647511 -0.32505861, -0.10115568 0.048198391 -0.31395718, -0.092371158 0.038183887 -0.32624, -0.08949355 0.038719986 -0.32679346, -0.089854047 0.036832359 -0.32718053, -0.095234424 0.037691884 -0.32546154, -0.091904841 0.040007487 -0.32569233, -0.089054346 0.040480975 -0.32605258, -0.083437145 0.041475516 -0.32613018, -0.091430232 0.043997902 -0.30898479, -0.091356695 0.04166808 -0.32480672, -0.085901469 0.040098906 -0.32681674, -0.11134134 0.037647709 -0.31656998, -0.11772022 0.043675993 -0.31107286, -0.11457919 0.042160414 -0.3141039, -0.095350519 0.046769738 -0.31069556, -0.11261457 0.038645595 -0.31570753, -0.11354654 0.038513422 -0.31483835, -0.076569661 0.044500884 -0.3200798, -0.072952956 0.044454411 -0.3199029, -0.11411834 0.038752314 -0.31436071, -0.10462928 0.048466627 -0.31385058, -0.11269854 0.040535461 -0.31577948, -0.097609401 0.047723334 -0.31156898, -0.080761939 0.043681115 -0.32342103, -0.083071768 0.042807322 -0.32473877, -0.11167078 0.043346956 -0.31591433, -0.11413482 0.04332811 -0.31418961, -0.11325656 0.045077153 -0.31407982, -0.11074108 0.045046616 -0.31561476, -0.11218647 0.046669375 -0.31367651, -0.10005459 0.048368748 -0.31234434, -0.091172263 0.042546861 -0.30769208, -0.10964791 0.046561413 -0.3150205, -0.091780573 0.041040584 -0.30634227, -0.085498527 0.041677352 -0.32572642, -0.11724241 0.044827562 -0.3111909, -0.12598838 0.045767181 -0.30033192, -0.12636447 0.044598915 -0.29922563, -0.12676275 0.046597224 -0.29897925, -0.12834162 0.046507541 -0.29540846, -0.07643427 0.044445179 -0.31812504, -0.12816423 0.048285667 -0.296215, -0.072952956 0.044349179 -0.31799591, -0.12134337 0.042426635 -0.30701268, -0.12143969 0.04101814 -0.30638677, -0.12509485 0.051416419 -0.29977643, -0.12384281 0.052922249 -0.29986441, -0.1256378 0.053335678 -0.29756409, -0.12423889 0.05470866 -0.29759896, -0.094701573 0.045888841 -0.30906883, -0.08045733 0.044371132 -0.32161176, -0.096768729 0.047174919 -0.30988505, -0.082691744 0.043835029 -0.32311341, -0.12237076 0.054209337 -0.29972571, -0.09266147 0.036720343 -0.32641727, -0.089667395 0.042577952 -0.32432023, -0.088553235 0.042047538 -0.32498589, -0.088009618 0.043359559 -0.32363459, -0.085061282 0.043002184 -0.32434914, -0.090747535 0.043101933 -0.32361662, -0.10339335 0.048969898 -0.31241462, -0.09903983 0.048168279 -0.31067902, -0.092130311 0.042971391 -0.32353342, -0.11224971 0.041960686 -0.31593722, -0.12105665 0.043864265 -0.30749777, -0.076315656 0.044008549 -0.31621766, -0.10776512 0.047154058 -0.31516844, -0.072952896 0.043883339 -0.31614357, -0.080164284 0.044690762 -0.31969988, -0.10843335 0.047833357 -0.31415433, -0.10970508 0.047938492 -0.31359968, -0.11096558 0.048043445 -0.31299499, -0.12268877 0.04328699 -0.30529192, -0.12405917 0.042765349 -0.30289271, -0.12592331 0.047480449 -0.30041423, -0.082311749 0.044518992 -0.321316, -0.12577845 0.048832014 -0.30028018, -0.094219476 0.044695083 -0.3075904, -0.12620595 0.049073886 -0.29955408, -0.096078858 0.046282347 -0.30828181, -0.12670143 0.049399029 -0.29866466, -0.10009719 0.034330092 -0.32320476, -0.1001512 0.032905478 -0.32261133, -0.12763898 0.050061319 -0.29685849, -0.12646024 0.050760936 -0.29839754, -0.12678581 0.05176647 -0.29731387, -0.084606573 0.044022564 -0.32273826, -0.12058015 0.054475687 -0.30052599, -0.076218143 0.043207578 -0.31443092, -0.072952949 0.043073997 -0.31441385, -0.12073492 0.05522798 -0.299366, -0.12058632 0.045297012 -0.30783108, -0.079894289 0.044627998 -0.31775922, -0.12170269 0.055532113 -0.29841357, -0.12264292 0.055832356 -0.29741788, -0.12091117 0.056663945 -0.29702729, -0.098150387 0.047604661 -0.30902544, -0.089071929 0.043811634 -0.32291797, -0.087444186 0.044366404 -0.32205048, -0.09010081 0.044253759 -0.32216826, -0.091446951 0.044191055 -0.32215935, -0.122394 0.044719677 -0.30578721, -0.081946366 0.044832967 -0.31941578, -0.10652477 0.048224732 -0.31409243, -0.093922541 0.043234359 -0.3063173, -0.10714383 0.048813201 -0.31304976, -0.10839549 0.048981316 -0.31257933, -0.11888318 0.055285458 -0.299972, -0.072952911 0.041950539 -0.31286949, -0.095566131 0.04507982 -0.30682099, -0.11899838 0.055939041 -0.29879898, -0.11996562 0.056304242 -0.29793438, -0.11911017 0.057171319 -0.29644245, -0.088458717 0.044729393 -0.32129773, -0.090743393 0.045094248 -0.32056803, -0.10524768 0.04897451 -0.31280801, -0.10704725 0.049702242 -0.31135264, -0.11713582 0.055766691 -0.29922459, -0.072952896 0.03893508 -0.31055334, -0.072952859 0.040553853 -0.31156677, -0.088476866 0.045160089 -0.32016465, -0.10425697 0.033931788 -0.32055894, -0.10597575 0.049841572 -0.31080237, -0.11629678 0.05604564 -0.29839486, 0.077184498 0.042493705 -0.32540527, 0.078036621 0.042474899 -0.32540587, 0.077337548 0.041164607 -0.32683146, 0.077845722 0.04351509 -0.32375529, 0.076759033 0.042505324 -0.32540002, 0.076896787 0.041183792 -0.32683149, 0.075577796 0.041239195 -0.32682115, 0.10757577 0.051412538 -0.29802486, 0.10951839 0.053091433 -0.29805565, 0.10860871 0.052458066 -0.29932207, 0.10845912 0.052027423 -0.2967951, 0.08590135 0.040099997 -0.32681677, 0.090561077 0.038870864 -0.32649425, 0.086254597 0.038328584 -0.32757857, 0.075486317 0.042535532 -0.32538256, 0.072952911 0.041390002 -0.32671025, 0.090093479 0.040627915 -0.32576099, 0.10767189 0.050697636 -0.29558879, 0.072952904 0.042634994 -0.32526183, 0.10673197 0.051358048 -0.30404472, 0.10609803 0.050948862 -0.30234039, 0.10726812 0.051630393 -0.303758, 0.10746736 0.051478453 -0.30576098, 0.10556979 0.050769325 -0.3044405, 0.092573762 0.045345727 -0.31015706, 0.095350385 0.046770949 -0.31069532, 0.093159109 0.046210449 -0.31181616, 0.094701469 0.045890052 -0.30906883, 0.10755044 0.039483167 -0.31946069, 0.1115597 0.039283402 -0.31666201, 0.10789211 0.037993088 -0.31924242, 0.084068999 0.038114533 -0.3280068, 0.086544469 0.036432356 -0.3279826, 0.084311247 0.036213499 -0.32842007, 0.11118218 0.040760905 -0.3169055, 0.1052893 0.050633337 -0.3054941, 0.10595107 0.050738458 -0.30724075, 0.10433942 0.050189223 -0.30664003, 0.10764423 0.051841184 -0.3005558, 0.10986729 0.053192906 -0.30063319, 0.10326927 0.049556751 -0.30512428, 0.10886882 0.052554443 -0.30191025, 0.09323246 0.046556871 -0.31364626, 0.093872331 0.046724901 -0.31356829, 0.093346052 0.04660188 -0.31551319, 0.10898475 0.045350391 -0.31631711, 0.11218631 0.046670891 -0.31367642, 0.1132565 0.04507865 -0.31407994, 0.10996751 0.043722361 -0.31679255, 0.08206062 0.036034103 -0.32877892, 0.084433794 0.034969136 -0.32848769, 0.082158871 0.034787647 -0.32885066, 0.093922466 0.043235675 -0.30631709, 0.095143698 0.041941546 -0.30454302, 0.095250301 0.04361495 -0.30555856, 0.091922529 0.046187703 -0.31360289, 0.095566019 0.045080982 -0.30682096, 0.094219387 0.04469626 -0.3075904, 0.091780514 0.041041788 -0.30634239, 0.10597625 0.037397142 -0.32043409, 0.10810035 0.036520496 -0.31882709, 0.091279954 0.046133574 -0.31449264, 0.091312617 0.04617703 -0.31636268, 0.089934692 0.045893356 -0.31523094, 0.10617298 0.035920948 -0.32002586, 0.088379294 0.044498812 -0.32178828, 0.092057511 0.045104507 -0.32057676, 0.092802912 0.044126395 -0.32210335, 0.089355752 0.04540731 -0.31342217, 0.088981315 0.043496884 -0.32336214, 0.077025741 0.043517586 -0.32374969, 0.10718113 0.040679488 -0.31948918, 0.11077411 0.041943554 -0.31696129, 0.077654749 0.044211626 -0.32193276, 0.078777932 0.033052392 -0.32912284, 0.08230523 0.031750232 -0.32836631, 0.078812703 0.031550154 -0.32876647, 0.07661631 0.043520834 -0.32374224, 0.10718734 0.049153015 -0.29448345, 0.10873151 0.050381389 -0.29202691, 0.10923814 0.051943265 -0.29309779, 0.10819657 0.048364956 -0.29169735, 0.10617605 0.046863027 -0.29470083, 0.07539171 0.043528572 -0.32372287, 0.082249738 0.033251226 -0.3287251, 0.072952896 0.043581847 -0.32360339, 0.085498393 0.041678417 -0.3257263, 0.089560024 0.042189885 -0.32470369, 0.10419486 0.035355642 -0.32115641, 0.1042569 0.033933148 -0.32055867, 0.11026599 0.052925371 -0.30323437, 0.10860299 0.051965617 -0.30515388, 0.10530725 0.050463673 -0.30267328, 0.1051379 0.049946871 -0.30095571, 0.10390675 0.049769804 -0.30406097, 0.1068083 0.050096188 -0.2967914, 0.10239105 0.048595108 -0.30365902, 0.092138782 0.044164188 -0.3086547, 0.092231646 0.045877904 -0.31184378, 0.083773851 0.039891608 -0.32723346, 0.10663933 0.05081344 -0.29922277, 0.090344489 0.045475986 -0.31264773, 0.08888045 0.04456608 -0.31171659, 0.076867312 0.044198688 -0.3219268, 0.081866398 0.037938803 -0.3283582, 0.10565327 0.038893163 -0.32064044, 0.077471279 0.044537518 -0.32000837, 0.0764741 0.044194154 -0.32191956, 0.078721054 0.034590729 -0.32924449, 0.10786342 0.046765454 -0.31555328, 0.11096546 0.048044838 -0.31299499, 0.07529752 0.044182528 -0.32190394, 0.072952889 0.044196129 -0.32179487, 0.10400969 0.036835268 -0.32155785, 0.1041086 0.049333826 -0.30181178, 0.087777495 0.045156814 -0.32004264, 0.091312081 0.045739025 -0.3188782, 0.1044244 0.048663244 -0.29965723, 0.085061163 0.04300331 -0.32434919, 0.1033015 0.048684377 -0.30198207, 0.10645117 0.042485211 -0.31926653, 0.10272247 0.048666008 -0.30314761, 0.10173845 0.047341436 -0.30230063, 0.091225073 0.044943959 -0.31059101, 0.091870964 0.042710844 -0.30736652, 0.090310186 0.044447266 -0.31045547, 0.083437093 0.041476466 -0.32613018, 0.10633565 0.048560176 -0.29566905, 0.08937373 0.044563603 -0.31135145, 0.088527396 0.043401551 -0.31017953, 0.10530424 0.040095661 -0.32065651, 0.076715283 0.044511467 -0.32000595, 0.07865949 0.035839178 -0.32916862, 0.077302083 0.044480443 -0.31805634, 0.10589242 0.04951065 -0.29796275, 0.076337576 0.044500351 -0.32000059, 0.081629619 0.039720647 -0.32757542, 0.1066467 0.047913019 -0.31453079, 0.10964065 0.049147747 -0.31206146, 0.07517904 0.04448761 -0.31935617, 0.087198645 0.045445953 -0.31819198, 0.09059526 0.046005517 -0.31707317, 0.074079096 0.04445786 -0.31997296, 0.10370596 0.038336713 -0.32175329, 0.073703349 0.044455715 -0.31995228, 0.072952867 0.044455379 -0.31990272, 0.072952852 0.044350181 -0.31799576, 0.084606469 0.044023592 -0.32273826, 0.10357828 0.047988158 -0.30018878, 0.10398501 0.047147173 -0.29849467, 0.10113822 0.034573887 -0.32271969, 0.10015135 0.03290673 -0.32261124, 0.10223445 0.047331493 -0.30150193, 0.10133655 0.045843784 -0.3011013, 0.10556174 0.044146173 -0.31872544, 0.091059849 0.043659952 -0.30884448, 0.089256965 0.043282796 -0.30959851, 0.088309973 0.041958939 -0.30887023, 0.083071575 0.042808451 -0.3247391, 0.076192938 0.04438024 -0.3177436, 0.077153817 0.044042677 -0.3161512, 0.078537717 0.037748162 -0.32873943, 0.074031696 0.044315644 -0.31773823, 0.08135961 0.041310873 -0.32646158, 0.1046143 0.041913766 -0.32040924, 0.10359628 0.046791598 -0.29877385, 0.086665243 0.045354959 -0.31630784, 0.10337767 0.039545279 -0.32175756, 0.10383673 0.045456748 -0.29751295, 0.10279346 0.045917246 -0.29921994, 0.10120089 0.044159796 -0.30010697, 0.10543267 0.0479826 -0.29682386, 0.10228834 0.046134088 -0.30008864, 0.084151775 0.04470022 -0.3209556, 0.10538135 0.048749026 -0.3132886, 0.091355547 0.042435609 -0.30748522, 0.10826293 0.049937386 -0.31091201, 0.090311646 0.041725207 -0.30760315, 0.10097125 0.036058217 -0.32311186, 0.088236518 0.040293433 -0.30783883, 0.089585111 0.042051569 -0.30825311, 0.082691699 0.043836091 -0.32311347, 0.076617956 0.043955564 -0.31600532, 0.077032059 0.043240871 -0.31436637, 0.10454687 0.045598641 -0.31788644, 0.075772509 0.044097442 -0.31658995, 0.078389384 0.03953496 -0.32794681, 0.075570256 0.04390391 -0.31602642, 0.081066623 0.042648457 -0.32505882, 0.07468152 0.043654568 -0.31548899, 0.072952814 0.041951511 -0.31286949, 0.076941669 0.04210585 -0.31277087, 0.086197659 0.044887185 -0.31446236, 0.072952889 0.043074913 -0.31441396, 0.10377359 0.043589998 -0.31983742, 0.073475994 0.043843336 -0.31602377, 0.072952904 0.043884341 -0.3161436, 0.083714508 0.04500721 -0.31906947, 0.10272887 0.041375104 -0.32148647, 0.08231166 0.044520028 -0.32131591, 0.10069723 0.037567258 -0.32329237, 0.078220263 0.041130908 -0.32682115, 0.1041161 0.049241234 -0.31187457, 0.10688511 0.050383285 -0.30959061, 0.1034457 0.046787009 -0.31678274, 0.072952844 0.038936082 -0.31055334, 0.076867171 0.03902185 -0.3103818, 0.072952859 0.040554851 -0.31156677, 0.080761932 0.043682154 -0.323421, 0.12625822 0.046001919 -0.29986584, 0.12816401 0.048287291 -0.296215, 0.12834142 0.046509288 -0.29540846, 0.12636442 0.044600502 -0.29922563, 0.085814036 0.044060998 -0.31272644, 0.12594235 0.047418419 -0.30039346, 0.12763876 0.050062921 -0.29685837, 0.08331158 0.044932585 -0.3171522, 0.12542421 0.048816383 -0.30079588, 0.12678567 0.051768098 -0.29731387, 0.10281447 0.045059841 -0.31896427, 0.10040112 0.038783938 -0.32328013, 0.081946343 0.044833895 -0.31941578, 0.10193826 0.043065526 -0.32088631, 0.12486412 0.049913045 -0.30102372, 0.12395752 0.044171866 -0.30352542, 0.12405899 0.042766925 -0.30289268, 0.10289946 0.04937087 -0.31034294, 0.10556036 0.050468296 -0.30814818, 0.080457255 0.04437213 -0.32161167, 0.12365511 0.045599457 -0.30403134, 0.085528977 0.042907707 -0.31116727, 0.10230063 0.047665212 -0.315456, 0.123757 0.051521763 -0.30119485, 0.12563756 0.053337317 -0.29756388, 0.082958385 0.044479288 -0.3152779, 0.1226887 0.043288577 -0.30529192, 0.1214397 0.041019715 -0.30638686, 0.081609517 0.04476586 -0.31748569, 0.12315953 0.04701506 -0.30439827, 0.10177384 0.046266891 -0.31782278, 0.099815682 0.040630005 -0.32297623, 0.12240802 0.052942909 -0.30113348, 0.12423863 0.054710265 -0.29759914, 0.080164269 0.044691846 -0.31969988, 0.1010362 0.044551793 -0.31998044, 0.085353374 0.041472003 -0.30984405, 0.12239395 0.044721171 -0.30578735, 0.10177813 0.049132913 -0.30875257, 0.084545955 0.039703861 -0.30901784, 0.082668558 0.04366488 -0.3135187, 0.12262352 0.048130978 -0.30458772, 0.12134328 0.042428143 -0.30701268, 0.10115559 0.048199721 -0.31395718, 0.12191042 0.046145476 -0.3061372, 0.081314385 0.044318285 -0.31560013, 0.12086897 0.054121651 -0.30084226, 0.12264262 0.05583401 -0.29741788, 0.07989414 0.044629112 -0.31775928, 0.10069143 0.047164675 -0.31645697, 0.082453109 0.042520501 -0.31194174, 0.12105662 0.043865837 -0.30749777, 0.099102482 0.042340234 -0.32233664, 0.10005745 0.045776509 -0.31880361, 0.12156421 0.049777724 -0.3046827, 0.12138787 0.047270607 -0.30630803, 0.081072181 0.043508496 -0.31383142, 0.11919905 0.055012818 -0.3003324, 0.12091089 0.056665573 -0.2970272, 0.07965754 0.044186126 -0.31586438, 0.10079525 0.048536509 -0.30716473, 0.082320571 0.041090041 -0.3106077, 0.080743909 0.039278645 -0.30986816, 0.12058614 0.045298543 -0.30783105, 0.10005456 0.048369966 -0.31234434, 0.11918661 0.041183412 -0.30950204, 0.11852233 0.039369598 -0.30968672, 0.099609211 0.047718696 -0.31491929, 0.080892242 0.042367451 -0.31224757, 0.1202735 0.051245037 -0.30452886, 0.079463363 0.04338007 -0.31408805, 0.098288655 0.043849062 -0.32138568, 0.12035491 0.04893586 -0.30636635, 0.1200777 0.04643276 -0.30798367, 0.080781318 0.040939324 -0.31090921, 0.11746234 0.055582177 -0.29962334, 0.11910992 0.057172857 -0.29644245, 0.07931897 0.042242095 -0.31249836, 0.091427982 0.032728132 -0.32641083, 0.095878437 0.032027394 -0.32436994, 0.091464698 0.031300426 -0.32582358, 0.095832922 0.033453733 -0.32495967, 0.099039592 0.046692684 -0.3174009, 0.11891259 0.042628426 -0.30997241, 0.079230167 0.040815603 -0.31115663, 0.099988729 0.047604434 -0.30564025, 0.11880092 0.052476667 -0.30413207, 0.099039689 0.048169538 -0.31067911, 0.076886006 0.040681265 -0.31142512, 0.091318436 0.034223434 -0.32678095, 0.095697209 0.034944735 -0.32533863, 0.11909629 0.050425559 -0.30616772, 0.11881132 0.040981583 -0.30990571, 0.11759052 0.040866841 -0.31126827, 0.1190727 0.048115749 -0.30800632, 0.098568439 0.047907814 -0.31326872, 0.11687003 0.039997406 -0.31187358, 0.11532496 0.037826862 -0.31277204, 0.1184632 0.04407331 -0.31028134, 0.097405732 0.045098256 -0.32015976, 0.11633433 0.039742354 -0.31238392, 0.11524083 0.039241612 -0.31338519, 0.11499016 0.040698159 -0.3138327, 0.11572568 0.055807892 -0.29874238, 0.11680942 0.042370804 -0.31211191, 0.11457907 0.042161819 -0.31410393, 0.11730898 0.057336431 -0.2956855, 0.11720301 0.053425144 -0.30350745, 0.11567527 0.045134809 -0.31234172, 0.11701714 0.046929404 -0.31037873, 0.11797735 0.045220599 -0.31040782, 0.098021701 0.04726515 -0.31582636, 0.11413474 0.043329496 -0.3141897, 0.11464949 0.04679152 -0.31212798, 0.11584716 0.048472408 -0.31007352, 0.11766033 0.051682662 -0.30571982, 0.11344323 0.048255999 -0.31163439, 0.099389404 0.04637273 -0.30423808, 0.091138892 0.035750356 -0.32692555, 0.095474884 0.036464535 -0.32549739, 0.11784811 0.049627263 -0.30776411, 0.10061911 0.034451455 -0.32296464, 0.099005543 0.034588527 -0.32382372, 0.11405574 0.055681162 -0.29772353, 0.098150276 0.047605887 -0.30902559, 0.097984299 0.03387386 -0.32411972, 0.11557721 0.057149947 -0.29478601, 0.097271323 0.03372962 -0.32440805, 0.097609326 0.047724497 -0.31156901, 0.098252311 0.036228787 -0.32439494, 0.096487403 0.046039943 -0.31870615, 0.11554129 0.054054264 -0.30267918, 0.097598083 0.039151616 -0.32430717, 0.095234454 0.037693068 -0.32546154, 0.094759278 0.039562453 -0.32511118, 0.11610216 0.05265877 -0.30504009, 0.097006351 0.04095206 -0.32380596, 0.094180271 0.041301027 -0.32441506, 0.097042963 0.047471914 -0.31414047, 0.096310548 0.042585284 -0.32297471, 0.099020332 0.044888571 -0.30301166, 0.098294005 0.042984203 -0.30245781, 0.116451 0.050909229 -0.30726653, 0.078228369 0.031525705 -0.32881546, 0.090944737 0.036986493 -0.32687464, 0.077652872 0.030073646 -0.32827675, 0.1125167 0.055206884 -0.2966058, 0.076466992 0.03196254 -0.3290751, 0.1125823 0.055768918 -0.29270107, 0.1139813 0.056620713 -0.29377812, 0.075300053 0.031442121 -0.32898241, 0.072952993 0.029991185 -0.32844165, 0.086909473 0.032159209 -0.3275485, 0.086937219 0.030730337 -0.32696369, 0.074517868 0.031430706 -0.32900518, 0.072952896 0.031421572 -0.32902357, 0.072952889 0.032924566 -0.32937843, 0.097420268 0.046700835 -0.30744752, 0.075856015 0.03372385 -0.32940406, 0.11387955 0.054339431 -0.30167881, 0.1163141 0.04377526 -0.31231099, 0.11448173 0.053316709 -0.30415401, 0.095569149 0.046637863 -0.3170808, 0.11331534 0.049631521 -0.31021672, 0.11451232 0.049790259 -0.3095043, 0.09676864 0.047176164 -0.30988505, 0.11306389 0.050832495 -0.30869254, 0.11493509 0.05191236 -0.30653289, 0.11210297 0.049471743 -0.31088057, 0.11155649 0.048765879 -0.31194788, 0.097966686 0.037702508 -0.32445541, 0.096140966 0.047304954 -0.31240791, 0.096911922 0.043918818 -0.32164106, 0.086826786 0.033657786 -0.327912, 0.11116774 0.054403249 -0.29543227, 0.09553729 0.043988876 -0.32184538, 0.1122817 0.05427007 -0.30054536, 0.094546951 0.043419469 -0.32263973, 0.093519673 0.042842157 -0.32339945, 0.11286141 0.053630576 -0.30309662, 0.077711657 0.035780255 -0.32924777, 0.084616289 0.031934626 -0.32799786, 0.082323842 0.030320553 -0.32778311, 0.077237085 0.035753429 -0.32928199, 0.096877873 0.045489199 -0.30600488, 0.075804107 0.035942543 -0.32932952, 0.094686136 0.046869114 -0.31534585, 0.07439056 0.035041586 -0.32946545, 0.072952807 0.036365271 -0.32931507, 0.072952963 0.03446418 -0.32949752, 0.11178987 0.03781832 -0.31623134, 0.11186716 0.036400717 -0.31562403, 0.096078642 0.046283539 -0.30828181, 0.1118772 0.050613828 -0.30931726, 0.11155761 0.051558737 -0.30766955, 0.11335848 0.052598167 -0.3055909, 0.11068004 0.050392121 -0.30989498, 0.11006071 0.053301364 -0.29424754, 0.11018105 0.049779117 -0.31098655, 0.11143429 0.054627452 -0.29159561, 0.096058175 0.045104768 -0.32033432, 0.1108091 0.053848598 -0.29932198, 0.086691096 0.035190217 -0.32804552, 0.094716445 0.04510846 -0.32046133, 0.09377753 0.044623207 -0.32129744, 0.077605397 0.03777343 -0.32879335, 0.11130325 0.053588934 -0.30190754, 0.077139303 0.03778863 -0.32881486, 0.084547162 0.033434432 -0.32835868, 0.07573919 0.037910417 -0.3288348, 0.072952881 0.038196951 -0.32877436, 0.096543908 0.044017311 -0.30475384, 0.11039639 0.051272895 -0.30821455, 0.11005135 0.051941484 -0.30647478, 0.11178195 0.052940287 -0.30447727, 0.10876474 0.050469827 -0.30982032, 0.11058128 0.053239942 -0.29050463, 0.095179215 0.045973234 -0.31881258, 0.092985265 0.045510061 -0.31973907, 0.077479444 0.039576173 -0.32797518, 0.077024922 0.039599176 -0.32798389, 0.07566309 0.039683066 -0.32798606, 0.072952919 0.039892584 -0.32789555, 0.10949091 0.051762957 -0.30671814, 0.10927581 0.051364087 -0.30776036, 0.10872449 0.051366668 -0.30751032, 0.1076619 0.051084835 -0.30775765, 0.10712779 0.050600003 -0.30904347, 0.1098786 0.049948033 -0.28853133, 0.11005598 0.051659934 -0.28947002, 0.094937615 0.046565317 -0.31711251, 0.10817028 0.035100173 -0.31822494, 0.094314456 0.046240762 -0.31800589, 0.09389089 0.046330024 -0.31758267, 0.09277609 0.046241712 -0.31744328, 0.091760218 0.045894355 -0.31845397, 0.20199952 0.12945448 -0.14349216, 0.20208724 0.13023338 -0.14349204, 0.20199953 0.12945437 -0.14049205, 0.20208721 0.13023318 -0.14049196, 0.2023461 0.13097318 -0.14349198, 0.20234619 0.13097295 -0.14049196, 0.20276305 0.13163671 -0.14349192, 0.20276313 0.13163652 -0.1404919, 0.20331725 0.13219094 -0.14349183, 0.20331725 0.13219081 -0.14049187, 0.20398095 0.13260797 -0.14349192, 0.20398092 0.13260774 -0.14049187, 0.20472065 0.13286684 -0.14349183, 0.20472062 0.13286667 -0.14049196, 0.20549944 0.13295457 -0.14349172, 0.20549944 0.1329544 -0.1404919, 0.20199952 0.11745457 -0.14349282, 0.20208731 0.11823338 -0.14349276, 0.20199952 0.11745436 -0.1404928, 0.2020873 0.11823323 -0.14049274, 0.20234615 0.11897315 -0.14349273, 0.20234615 0.11897294 -0.1404925, 0.20276326 0.11963673 -0.14349276, 0.20276323 0.11963649 -0.1404925, 0.2033174 0.12019102 -0.14349255, 0.20331736 0.12019083 -0.1404925, 0.20398095 0.12060799 -0.14349255, 0.20398095 0.12060776 -0.1404925, 0.20472071 0.12086689 -0.14349243, 0.20472078 0.12086663 -0.1404925, 0.20549962 0.1209546 -0.14349252, 0.20549953 0.12095436 -0.14049271, -0.21400061 0.11745194 -0.14349282, -0.21391286 0.11823069 -0.14349276, -0.21400055 0.11745168 -0.14049274, -0.21391287 0.11823048 -0.14049295, -0.21365407 0.1189705 -0.14349282, -0.21365413 0.11897032 -0.14049274, -0.213237 0.11963408 -0.14349276, -0.21323709 0.11963384 -0.14049271, -0.21268286 0.12018836 -0.14349276, -0.21268286 0.12018809 -0.14049271, -0.21201918 0.12060528 -0.14349252, -0.21201926 0.12060508 -0.14049271, -0.21127945 0.12086424 -0.14349255, -0.21127951 0.12086402 -0.1404925, -0.2105006 0.12095186 -0.14349252, -0.21050058 0.12095168 -0.14049274, -0.21400064 0.12945195 -0.14349216, -0.21391296 0.13023072 -0.14349216, -0.2140006 0.12945162 -0.1404922, -0.21391287 0.13023047 -0.1404922, -0.21365407 0.13097058 -0.14349183, -0.2136541 0.13097031 -0.14049196, -0.21323714 0.1316341 -0.14349198, -0.21323708 0.13163382 -0.1404922, -0.2126829 0.13218825 -0.14349192, -0.21268293 0.13218807 -0.14049196, -0.21201932 0.13260537 -0.14349198, -0.21201923 0.1326052 -0.14049187, -0.21127954 0.13286418 -0.14349183, -0.21127959 0.13286397 -0.14049187, -0.21050073 0.13295189 -0.14349183, -0.21050072 0.13295172 -0.14049196, -0.072952859 0.034462083 -0.30949751, 0.072952852 0.034463048 -0.30949754, 0.072952949 0.036002636 -0.30961668, -0.072952949 0.03600179 -0.30961674, 0.072952896 0.037505597 -0.30997136, -0.072952941 0.037504598 -0.30997148, 0.11911006 0.03928452 -0.28749767, 0.18616217 0.11129266 -0.14349306, 0.18486236 0.11137533 -0.14349306, 0.11730909 0.039791834 -0.28691268, 0.18346629 0.11166303 -0.14349303, 0.11557731 0.040623363 -0.28652203, 0.18183304 0.1123119 -0.14349306, 0.11398134 0.041747138 -0.28634092, 0.18038309 0.113267 -0.14349282, 0.11258243 0.043120008 -0.28637603, 0.17915645 0.11451167 -0.14349297, 0.1781936 0.11602636 -0.14349282, 0.11143434 0.044689212 -0.28662628, 0.17753732 0.11778528 -0.14349282, 0.11058135 0.046394434 -0.2870816, 0.17723115 0.11975051 -0.14349255, 0.11005591 0.048170175 -0.28772485, 0.17728834 0.12165003 -0.14349246, 0.17768238 0.12361787 -0.14349246, 0.1784218 0.12558912 -0.14349243, 0.17949837 0.12748994 -0.14349222, 0.18088479 0.12924325 -0.14349216, 0.18253562 0.1307755 -0.14349192, 0.18438928 0.1320228 -0.14349216, 0.18637507 0.13293651 -0.14349183, 0.18829355 0.13346247 -0.14349172, 0.19032755 0.13365431 -0.14349192, -0.19162866 0.13356927 -0.14349183, -0.19032891 0.13365196 -0.14349198, -0.19302464 0.13328144 -0.14349192, -0.19465803 0.13263245 -0.14349192, -0.19610782 0.13167749 -0.14349183, -0.1973346 0.13043275 -0.14349222, -0.19829749 0.12891805 -0.14349216, -0.19895363 0.12715903 -0.14349231, -0.19925959 0.12519388 -0.14349243, -0.1992026 0.12329432 -0.14349243, -0.19880846 0.12132646 -0.14349255, -0.12816416 0.044795811 -0.29447001, -0.19806907 0.11935531 -0.14349276, -0.12763885 0.043215785 -0.29343528, -0.19699249 0.11745453 -0.14349282, -0.12678584 0.041828346 -0.29234442, -0.19560589 0.11570115 -0.14349282, -0.12563772 0.040686857 -0.29123893, -0.19395527 0.11416894 -0.14349297, -0.12423873 0.039835002 -0.2901617, -0.19210154 0.11292168 -0.14349306, -0.12264276 0.039305773 -0.28915393, -0.1901156 0.11200802 -0.14349306, -0.12091103 0.0391194 -0.28825438, -0.18819721 0.11148219 -0.14349306, -0.11911013 0.039282974 -0.28749755, -0.18616319 0.11129029 -0.14349315, -0.18486334 0.11137299 -0.14349306, -0.11730908 0.039790314 -0.28691256, -0.18346721 0.1116606 -0.14349303, -0.11557736 0.040621858 -0.28652203, -0.18183397 0.1123096 -0.14349315, -0.11398131 0.041745607 -0.28634092, -0.18038401 0.11326464 -0.14349297, -0.11258256 0.043118481 -0.28637606, -0.17915742 0.1145093 -0.14349291, -0.17819463 0.11602411 -0.14349282, -0.11143436 0.044687789 -0.28662628, -0.17753813 0.11778301 -0.14349276, -0.11058138 0.046393033 -0.2870816, -0.1772323 0.11974819 -0.14349252, -0.11005609 0.048168745 -0.28772488, -0.17728941 0.12164766 -0.14349255, -0.17768356 0.12361565 -0.14349246, -0.17842291 0.12558678 -0.14349222, -0.17949949 0.12748767 -0.14349222, -0.18088606 0.12924096 -0.14349207, -0.18253666 0.13077316 -0.14349207, -0.18439043 0.13202044 -0.14349198, -0.1863762 0.13293402 -0.14349172, -0.18829474 0.13345996 -0.14349192, 0.19162746 0.13357158 -0.14349172, 0.19302353 0.13328402 -0.14349183, 0.19465667 0.13263495 -0.14349192, 0.19610676 0.13167992 -0.14349192, 0.19733329 0.13043527 -0.14349204, 0.19829614 0.12892053 -0.14349216, 0.1989525 0.12716159 -0.14349216, 0.19925852 0.12519646 -0.14349231, 0.19920141 0.12329692 -0.14349246, 0.1988073 0.12132907 -0.14349273, 0.12816407 0.044797439 -0.29447001, 0.19806784 0.11935776 -0.14349273, 0.12763874 0.043217503 -0.29343536, 0.19699147 0.117457 -0.14349273, 0.12678576 0.041829951 -0.29234427, 0.19560488 0.11570367 -0.14349291, 0.12563762 0.040688455 -0.29123908, 0.1939542 0.11417136 -0.14349291, 0.12423881 0.03983663 -0.2901617, 0.19210057 0.11292417 -0.14349315, 0.12264277 0.03930743 -0.28915387, 0.19011478 0.11201048 -0.14349315, 0.12091103 0.039120913 -0.28825432, 0.18819629 0.11148451 -0.14349306, 0.094937772 0.029111702 -0.30838481, 0.095179304 0.028106499 -0.3098785, 0.095569201 0.029093374 -0.30830768, 0.1234107 0.039522544 -0.30082446, 0.1248641 0.039974872 -0.2960543, 0.12262358 0.038192701 -0.2996183, 0.0946863 0.030342501 -0.30708185, 0.12568672 0.041332785 -0.29720411, 0.093474358 0.029188316 -0.3085475, 0.10385982 0.030800801 -0.31826636, 0.10530432 0.030157439 -0.31568736, 0.10337768 0.029607072 -0.31678826, 0.10581698 0.031359978 -0.31714818, 0.087777577 0.027612334 -0.31126967, 0.091312192 0.028194305 -0.31010538, 0.090595312 0.029478811 -0.30880922, 0.08719869 0.028919311 -0.309928, 0.092831597 0.028652735 -0.30930251, 0.092885435 0.028289683 -0.30978373, 0.092985436 0.027643267 -0.31080499, 0.12138793 0.037332445 -0.30133864, 0.12156433 0.037128784 -0.29835778, 0.091760337 0.028440807 -0.3097263, 0.12035495 0.036286887 -0.30004144, 0.079365157 0.034688331 -0.30904678, 0.080836311 0.036349468 -0.30892327, 0.079274222 0.036224857 -0.30917242, 0.080949724 0.034814738 -0.3087942, 0.11451229 0.033263735 -0.3012403, 0.11645114 0.034382615 -0.29900262, 0.11493513 0.034367856 -0.29775995, 0.076739043 0.024996841 -0.31634015, 0.075552277 0.024608299 -0.31792039, 0.076877542 0.024591919 -0.31824073, 0.07687889 0.037591726 -0.30979931, 0.11306408 0.03328786 -0.29991958, 0.078036718 0.024930334 -0.31663305, 0.077845834 0.025626779 -0.31481043, 0.075459629 0.025085256 -0.31604689, 0.07921882 0.037725814 -0.30953109, 0.097051002 0.037959006 -0.30250645, 0.099580705 0.038848922 -0.30072686, 0.099203229 0.040326342 -0.3009702, 0.096709386 0.039448977 -0.30272469, 0.074220926 0.024881907 -0.31664485, 0.072952993 0.025345355 -0.31539172, 0.072952963 0.024731044 -0.31720006, 0.074266285 0.024516147 -0.31853196, 0.083311677 0.030058987 -0.30971509, 0.086665325 0.030481366 -0.30887049, 0.086197734 0.03223836 -0.30813739, 0.1190729 0.035466816 -0.30168137, 0.11909646 0.035551902 -0.29873043, 0.10771212 0.035372149 -0.29739082, 0.10860309 0.035438966 -0.29688996, 0.10726815 0.036756944 -0.29632038, 0.10949109 0.034309283 -0.29799032, 0.08295846 0.031830408 -0.3089532, 0.11784825 0.034753717 -0.30032679, 0.081314452 0.031669457 -0.3092753, 0.082668617 0.033726729 -0.3085492, 0.10818116 0.034139734 -0.2986457, 0.081072249 0.033570282 -0.30886197, 0.10177825 0.034259319 -0.30131519, 0.10433957 0.035315625 -0.29920274, 0.10326941 0.03690777 -0.29879948, 0.10620959 0.034626603 -0.29888171, 0.10079543 0.035887443 -0.30083975, 0.10556047 0.033941809 -0.29988432, 0.10040118 0.028845724 -0.3183105, 0.1027289 0.028726202 -0.31516135, 0.09981589 0.027981129 -0.3166514, 0.10712785 0.033146389 -0.30031627, 0.10793678 0.033525269 -0.29955822, 0.093680352 0.03044416 -0.30724591, 0.095406815 0.03904384 -0.30353498, 0.096501142 0.040921748 -0.30313995, 0.095209911 0.040520128 -0.30394301, 0.09387242 0.031851247 -0.30613095, 0.09742038 0.036762688 -0.3024779, 0.099988826 0.037666284 -0.30067086, 0.091654778 0.030011889 -0.30811036, 0.079463363 0.033441938 -0.30911851, 0.089934848 0.031019766 -0.30779365, 0.12389542 0.041067 -0.30193019, 0.076596089 0.025763299 -0.31455499, 0.07765495 0.026667004 -0.31315988, 0.12619343 0.042894758 -0.29827493, 0.10415676 0.032261536 -0.31953958, 0.10614067 0.036384966 -0.29732221, 0.10613269 0.032826062 -0.31841055, 0.093884453 0.040141445 -0.3047004, 0.12215545 0.038648646 -0.3025721, 0.10609813 0.038299948 -0.29601532, 0.088379391 0.026610527 -0.31284341, 0.092057616 0.027216189 -0.31163198, 0.10516879 0.036530107 -0.29781362, 0.11584732 0.03359884 -0.30263627, 0.10466513 0.035673641 -0.29874468, 0.076913603 0.036089569 -0.30944303, 0.092424631 0.031708151 -0.30667499, 0.093159184 0.033561531 -0.30549124, 0.083714664 0.028480569 -0.31080544, 0.091383383 0.03203186 -0.30680916, 0.12007783 0.036494583 -0.30301416, 0.090453342 0.031302802 -0.30748564, 0.089355797 0.03275843 -0.30709711, 0.081609577 0.02989235 -0.31004849, 0.077052131 0.026765341 -0.31305376, 0.077471375 0.028010959 -0.31174463, 0.095729664 0.037547942 -0.30332839, 0.10083612 0.030027352 -0.31981301, 0.075664297 0.026991799 -0.31282121, 0.10289957 0.032844197 -0.30207893, 0.10511738 0.038226444 -0.29679945, 0.10513796 0.040008716 -0.29598612, 0.10465217 0.041156046 -0.29611272, 0.10194673 0.039824702 -0.2987752, 0.094069667 0.038661767 -0.30429909, 0.079657607 0.03153722 -0.30953947, 0.10370643 0.037536789 -0.29817888, 0.10239108 0.038656987 -0.29868937, 0.098150283 0.034956969 -0.30270061, 0.076970577 0.034551144 -0.30932122, 0.091972291 0.033680595 -0.30589056, 0.092277572 0.036624469 -0.30517542, 0.088640109 0.035856407 -0.30671123, 0.096078768 0.03634524 -0.30331248, 0.092573851 0.03540761 -0.3051877, 0.090079106 0.033284355 -0.30668288, 0.088880546 0.03462784 -0.30674723, 0.12262802 0.040184781 -0.30369452, 0.088981405 0.025952438 -0.3145892, 0.076510198 0.028209802 -0.31162053, 0.077302217 0.029607 -0.31061891, 0.092803031 0.026581772 -0.31333047, 0.075080693 0.025710357 -0.31465846, 0.074720629 0.026544256 -0.31338125, 0.072953001 0.026292114 -0.31373304, 0.084151872 0.027155677 -0.31218249, 0.074681737 0.029396662 -0.31085503, 0.077153876 0.031393729 -0.3098262, 0.11701731 0.034280512 -0.30405387, 0.081946447 0.028307375 -0.31115189, 0.07379131 0.030923761 -0.31013918, 0.072952896 0.030730188 -0.31022042, 0.072953045 0.029034555 -0.31109965, 0.072952956 0.032561809 -0.30968004, 0.12082458 0.037797485 -0.30427429, 0.077032141 0.033302665 -0.30939701, 0.075157493 0.028113646 -0.31174451, 0.10411625 0.031696692 -0.30310166, 0.10688521 0.032838739 -0.3008177, 0.10110389 0.031480696 -0.32110116, 0.074700311 0.027849087 -0.31198114, 0.094373308 0.037160322 -0.3041034, 0.075016499 0.027550234 -0.31225088, 0.074121282 0.027740575 -0.31208757, 0.072952949 0.027537046 -0.31228465, 0.091836669 0.039617687 -0.30574796, 0.079894304 0.029755548 -0.31032187, 0.099039778 0.033296004 -0.30324176, 0.089560181 0.02566324 -0.31643972, 0.093519747 0.026315551 -0.31513566, 0.096768662 0.034527209 -0.30356005, 0.08460661 0.026135398 -0.31379348, 0.11797749 0.035282392 -0.3054384, 0.082311846 0.026975451 -0.31254309, 0.094701543 0.035951842 -0.30409929, 0.12128443 0.039325334 -0.30541328, 0.10538146 0.030860838 -0.3043437, 0.080164351 0.02816518 -0.31143597, 0.108263 0.032049164 -0.30196714, 0.092003673 0.038133379 -0.3053557, 0.090093575 0.025754349 -0.31832379, 0.09418039 0.026427459 -0.31697759, 0.10005455 0.031843416 -0.30408046, 0.085061297 0.025458798 -0.31557649, 0.097609416 0.032850988 -0.30413151, 0.11869091 0.036566067 -0.30673701, 0.095350407 0.034122046 -0.30437052, 0.082691744 0.025947781 -0.31416863, 0.10866669 0.047274128 -0.29043609, 0.10898259 0.045857746 -0.28990856, 0.080457322 0.026827592 -0.31283897, 0.090561137 0.026221892 -0.3201693, 0.094759345 0.026913572 -0.31878635, 0.10664684 0.030368477 -0.30575788, 0.10950066 0.044459779 -0.28950587, 0.10964069 0.031603269 -0.30328849, 0.08549846 0.025151901 -0.31746253, 0.10115574 0.030655231 -0.30518413, 0.098568544 0.031381138 -0.30500484, 0.11006084 0.043363057 -0.28927797, 0.10712522 0.046048112 -0.2928881, 0.1191304 0.038082141 -0.30789936, 0.083071768 0.025263852 -0.31596598, 0.10742748 0.0446207 -0.29238233, 0.080762058 0.025793901 -0.31447628, 0.096141011 0.032431483 -0.30497065, 0.11116782 0.041754369 -0.28910702, 0.090944812 0.027048312 -0.32190505, 0.095234551 0.027754869 -0.32049209, 0.085901454 0.025226435 -0.31937951, 0.10627504 0.045456376 -0.2940715, 0.10786352 0.030238822 -0.3072893, 0.11096549 0.031518228 -0.30473098, 0.10792327 0.043205094 -0.29201525, 0.088282108 0.03886709 -0.30724877, 0.10230079 0.029776912 -0.30651116, 0.083437175 0.024949856 -0.3178663, 0.11251679 0.040333353 -0.28916851, 0.10656987 0.044023726 -0.29357621, 0.099609181 0.030174244 -0.30614614, 0.081066735 0.025103919 -0.31628582, 0.10845919 0.042089146 -0.29182559, 0.091229923 0.028201513 -0.32346454, 0.095587701 0.028919242 -0.32202917, 0.10537377 0.044879794 -0.2952244, 0.086254649 0.02567967 -0.32125399, 0.10705318 0.042599447 -0.29322627, 0.097043104 0.030945268 -0.30587646, 0.083773941 0.025017982 -0.31979629, 0.10898481 0.030476823 -0.30887961, 0.11218643 0.03179729 -0.3062391, 0.11405587 0.039154522 -0.28945959, 0.088417783 0.03737627 -0.30686989, 0.081359744 0.024784261 -0.31819755, 0.10566053 0.043442156 -0.2947391, 0.10344584 0.029242411 -0.30800977, 0.10951844 0.0404424 -0.2917307, 0.091405511 0.029637244 -0.32478753, 0.095805071 0.030361857 -0.32333848, 0.10757586 0.041474175 -0.2930555, 0.086544462 0.026494201 -0.32301325, 0.084069088 0.025465557 -0.32168174, 0.1157258 0.038263321 -0.28996947, 0.10069156 0.029276397 -0.3075121, 0.10613086 0.042009503 -0.29440615, 0.09802179 0.029720586 -0.30705354, 0.10392873 0.04404588 -0.29689226, 0.081629671 0.024847057 -0.32013819, 0.11080918 0.038975094 -0.29188469, 0.08675994 0.027638551 -0.32459021, 0.10860878 0.039809152 -0.29299718, 0.10996766 0.031073235 -0.31046763, 0.11325663 0.032429796 -0.30775493, 0.1066394 0.0408752 -0.29425332, 0.078220375 0.024604294 -0.31855732, 0.084311306 0.02627538 -0.32345068, 0.10454697 0.029072005 -0.3096227, 0.081866473 0.025289861 -0.32203317, 0.11746253 0.037693929 -0.29067859, 0.086892486 0.029068975 -0.32592398, 0.10420278 0.04260077 -0.29642186, 0.11228184 0.03774349 -0.29228145, 0.078389533 0.024661364 -0.32050946, 0.084491327 0.027416272 -0.32503465, 0.10986747 0.038319375 -0.29319569, 0.082060717 0.026095927 -0.32380942, 0.10177384 0.028722316 -0.30904996, 0.1076443 0.039192304 -0.29423076, 0.078537837 0.025099164 -0.32241443, 0.085330933 0.038381029 -0.30822092, 0.084602132 0.028844548 -0.32637289, 0.099039681 0.028804459 -0.30845585, 0.082205005 0.027234016 -0.32539919, 0.11077417 0.03200531 -0.31199187, 0.11413483 0.033391282 -0.30922014, 0.11919922 0.037468221 -0.29155949, 0.078659624 0.025901057 -0.3241992, 0.1055618 0.029272608 -0.31128791, 0.11387961 0.036794834 -0.29290614, 0.082293846 0.028660417 -0.32674089, 0.085440382 0.03688582 -0.30785063, 0.11130338 0.037062254 -0.2936435, 0.07874994 0.02703608 -0.32579485, 0.078805611 0.028460566 -0.32714063, 0.10886891 0.037680794 -0.29447287, 0.11464958 0.032963749 -0.30521357, 0.11344329 0.032479927 -0.30374578, 0.12086909 0.037595 -0.29257837, 0.11567532 0.033786718 -0.30666712, 0.10281463 0.028533198 -0.31070045, 0.10128509 0.042744845 -0.29949379, 0.11648137 0.034916826 -0.30805141, 0.10005746 0.028231993 -0.31003061, 0.11478743 0.034645077 -0.31057861, 0.11554144 0.036165949 -0.2937344, 0.11137357 0.03323704 -0.31339428, 0.11775255 0.036890518 -0.30885759, 0.11286151 0.036086064 -0.29432353, 0.085619971 0.035358869 -0.30770615, 0.11703649 0.036311105 -0.30931261, 0.11630315 0.035743445 -0.30975133, 0.11518924 0.036142733 -0.31177789, 0.10645123 0.029836234 -0.31294146, 0.11026601 0.036398884 -0.29497045, 0.097006425 0.02712423 -0.31689149, 0.099102572 0.027466755 -0.31489941, 0.096310556 0.026809301 -0.31508607, 0.12240817 0.038069293 -0.29369614, 0.097598225 0.027803339 -0.31863266, 0.10377368 0.028716456 -0.31240013, 0.098063141 0.02882079 -0.3202424, 0.10153577 0.041288286 -0.29904652, 0.096487507 0.028151631 -0.3097614, 0.11720309 0.035880692 -0.29473433, 0.099299625 0.030571595 -0.32149401, 0.10103625 0.02802518 -0.31171641, 0.085814089 0.034122787 -0.30775714, 0.098383427 0.030137286 -0.32165918, 0.097458795 0.029716767 -0.32180336, 0.11448184 0.035428338 -0.29520947, 0.1117426 0.034721293 -0.31462058, 0.075836137 0.026378859 -0.32527593, 0.075784184 0.025405124 -0.32360458, 0.072953001 0.025852146 -0.32458118, 0.11178207 0.035395648 -0.29570422, 0.072952993 0.026975719 -0.32612544, 0.082303569 0.037999779 -0.30898327, 0.076836802 0.027434168 -0.32643977, 0.10718115 0.030741401 -0.31451982, 0.075871862 0.027656335 -0.32672912, 0.12375718 0.038872838 -0.29486984, 0.074902192 0.02788092 -0.32698452, 0.072952963 0.028372407 -0.32742828, 0.11331551 0.032788917 -0.30179486, 0.11880098 0.035950113 -0.2958681, 0.10461444 0.029264886 -0.31408402, 0.11210304 0.03235371 -0.30232087, 0.097405851 0.027553625 -0.31138688, 0.11155663 0.031923272 -0.30352601, 0.10193834 0.028192069 -0.31344897, 0.11786246 0.037791569 -0.30956188, 0.11705511 0.037786465 -0.31066123, 0.082386285 0.036501262 -0.30861965, 0.11610231 0.035114355 -0.29626709, 0.11627477 0.037017949 -0.31110913, 0.096911982 0.027076185 -0.31321922, 0.098973088 0.041791335 -0.30140096, 0.09828876 0.027322453 -0.31312171, 0.11335856 0.034709856 -0.29664618, 0.095537394 0.026870809 -0.31328574, 0.080767088 0.037849329 -0.30928412, 0.094547033 0.026576832 -0.31421784, 0.10772362 0.031953037 -0.31596214, 0.099314496 0.031461552 -0.32222047, 0.098191842 0.031627905 -0.32297683, 0.12027366 0.036371376 -0.29709154, 0.097186312 0.031017963 -0.32310784, 0.077121183 0.024915215 -0.32210207, 0.075717568 0.024769647 -0.32176915, 0.11005138 0.034396909 -0.29770169, 0.074345782 0.024889866 -0.32234558, 0.072952926 0.025042711 -0.32285151, 0.072952986 0.024576966 -0.32099929, 0.082521975 0.034968793 -0.30848619, 0.077252492 0.028676864 -0.32746521, 0.07679221 0.028323645 -0.32723725, 0.11766037 0.035156026 -0.29745588, 0.076766282 0.028802417 -0.32759455, 0.075172804 0.029261453 -0.32799, 0.11187731 0.032919262 -0.30046919, 0.11155777 0.033670545 -0.29872462, 0.11068019 0.032589998 -0.3009932, 0.11018115 0.032084491 -0.30213854, 0.10805754 0.033424862 -0.31721327, 0.096058272 0.02741012 -0.31148618, 0.094716623 0.027306337 -0.31155956, 0.093777642 0.026928559 -0.31244943, 0.077006489 0.024564052 -0.32018539, 0.075639404 0.024501458 -0.31985155, 0.074308425 0.024518382 -0.32045543, 0.072953008 0.02447179 -0.31909221, 0.11039653 0.033406079 -0.29928038, 0.10876489 0.0326031 -0.30088633, 0.1082131 0.033191606 -0.29998094, -0.072952837 0.028371435 -0.32742834, -0.072952896 0.026974751 -0.32612562, -0.072952822 0.025851263 -0.32458118, -0.072952792 0.025041834 -0.32285133, -0.072952785 0.024575967 -0.32099929, -0.072952829 0.024470879 -0.31909224, -0.072952792 0.024730187 -0.31720006, -0.072952822 0.025344325 -0.31539184, -0.072952837 0.026291268 -0.31373319, -0.072952822 0.027536113 -0.31228474, -0.072952814 0.029033644 -0.31109956, -0.072952874 0.030729128 -0.31022063, -0.072952896 0.0325609 -0.30967999, -0.10480344 0.031718217 -0.30292511, -0.1052475 0.03110778 -0.30387378, -0.10369214 0.031721082 -0.30316386, -0.10458004 0.032062855 -0.30248043, -0.10704711 0.031835452 -0.30241871, -0.088553183 0.02552087 -0.31672201, -0.085498333 0.025150649 -0.31746238, -0.085061088 0.025457617 -0.31557614, -0.088009536 0.025814928 -0.31486169, -0.10492993 0.032664176 -0.30159375, -0.08431115 0.026274271 -0.32345071, -0.082060546 0.026094873 -0.32380947, -0.081866294 0.025288871 -0.32203308, -0.10792327 0.043203626 -0.29201511, -0.1070533 0.042597994 -0.29322645, -0.10656989 0.04402237 -0.2935763, -0.10629845 0.03277497 -0.30105615, -0.10556047 0.033940367 -0.29988429, -0.10688518 0.032837346 -0.30081764, -0.10742758 0.044619419 -0.29238203, -0.084068887 0.025464509 -0.32168174, -0.10830155 0.046961281 -0.29105911, -0.1071253 0.046046719 -0.29288808, -0.11535084 0.038216483 -0.2901738, -0.11528853 0.037888702 -0.29071572, -0.1136356 0.03879445 -0.29017657, -0.1171357 0.037899945 -0.29029053, -0.1088689 0.03767946 -0.29447287, -0.10670793 0.036457106 -0.29691738, -0.10555702 0.038010404 -0.29659182, -0.11629666 0.03839634 -0.28956941, -0.11587943 0.038684115 -0.28923857, -0.10764439 0.039190982 -0.29423055, -0.11817706 0.038879868 -0.2883307, -0.094373316 0.037159212 -0.30410349, -0.091300078 0.037968241 -0.30568376, -0.09406969 0.038660649 -0.30429891, -0.091563836 0.036456872 -0.30550784, -0.11579715 0.039309125 -0.2883046, -0.086254448 0.025678625 -0.32125369, -0.083773717 0.025016915 -0.31979629, -0.08590135 0.025225366 -0.31937951, -0.11685894 0.039635845 -0.28733519, -0.10989685 0.031676166 -0.31264743, -0.107181 0.030739855 -0.31451979, -0.10645121 0.029834971 -0.31294146, -0.087473929 0.029282048 -0.30956775, -0.087368682 0.027710835 -0.31118387, -0.086334966 0.028797081 -0.3101702, -0.085833915 0.030363645 -0.3091034, -0.10910899 0.030751165 -0.31110889, -0.093099713 0.031669982 -0.30649096, -0.089355752 0.032757372 -0.3070972, -0.092412844 0.03338651 -0.30583903, -0.088481151 0.027874919 -0.31085569, -0.089210264 0.028380284 -0.31016102, -0.089934625 0.031018607 -0.30779347, -0.089584261 0.029623479 -0.30888477, -0.09059526 0.029477619 -0.30880931, -0.090677612 0.028239399 -0.31012666, -0.09540683 0.039042585 -0.30353507, -0.093884483 0.040140182 -0.30470073, -0.10860878 0.039807703 -0.29299733, -0.10663946 0.0408739 -0.29425332, -0.10296851 0.033237405 -0.30165738, -0.10220481 0.032583553 -0.30259788, -0.10757591 0.041472863 -0.29305547, -0.095209956 0.040518939 -0.3039431, -0.10805756 0.033423521 -0.31721306, -0.10613258 0.03282477 -0.31841061, -0.1058169 0.031358648 -0.31714815, -0.082293697 0.028659392 -0.32674077, -0.10110953 0.034008164 -0.30181479, -0.10772349 0.031951673 -0.31596223, -0.077637672 0.028413488 -0.3272329, -0.077593111 0.026989294 -0.32588661, -0.10845918 0.042087793 -0.29182571, -0.10462706 0.033913549 -0.30030498, -0.082204774 0.027233021 -0.32539919, -0.10433952 0.035314348 -0.29920274, -0.1139082 0.03954047 -0.28905204, -0.094701573 0.035950597 -0.30409929, -0.091849148 0.035237633 -0.30552518, -0.096501216 0.040920489 -0.30313993, -0.11211239 0.039986771 -0.28985873, -0.1148632 0.040448781 -0.28723556, -0.11092748 0.033333346 -0.2993961, -0.10826293 0.032047726 -0.30196717, -0.10944571 0.034072898 -0.29834688, -0.086389348 0.030623158 -0.30884269, -0.085394762 0.032124639 -0.3083626, -0.10861434 0.045542065 -0.29053712, -0.089054257 0.025607504 -0.31861517, -0.087405898 0.031309415 -0.30825153, -0.084491178 0.027415311 -0.32503441, -0.088439859 0.030940093 -0.30820876, -0.110266 0.036397394 -0.29497048, -0.10148937 0.034350734 -0.30138779, -0.10802098 0.035127617 -0.29750988, -0.10014951 0.035644941 -0.30132231, -0.10210955 0.035182517 -0.30050609, -0.086544327 0.026493059 -0.32301325, -0.095729686 0.037546743 -0.30332839, -0.11048223 0.03290271 -0.31406012, -0.10311348 0.034994043 -0.30010104, -0.10326934 0.036906514 -0.29879931, -0.11225883 0.040376056 -0.28933817, -0.11077727 0.041419588 -0.28977379, -0.10986748 0.038317997 -0.29319587, -0.093883447 0.030154195 -0.30745596, -0.10951851 0.04044104 -0.2917307, -0.11238857 0.041274317 -0.2883231, -0.11321008 0.04124812 -0.28759408, -0.096709467 0.039447803 -0.30272481, -0.086173929 0.032617535 -0.30801407, -0.0850344 0.034012288 -0.3079758, -0.084852025 0.035250038 -0.30792144, -0.1091271 0.044139568 -0.29014352, -0.0953504 0.034120854 -0.30437046, -0.088144675 0.032928921 -0.30739123, -0.088640086 0.035855267 -0.30671147, -0.088880479 0.034626726 -0.30674705, -0.11240913 0.03293762 -0.30061698, -0.10066627 0.036253054 -0.30074364, -0.099361666 0.037430678 -0.30113947, -0.10964064 0.031601869 -0.30328849, -0.098963097 0.038616803 -0.30118832, -0.089493528 0.026071161 -0.32046849, -0.10222146 0.036877617 -0.29949448, -0.10194678 0.039823342 -0.29877517, -0.10239109 0.03865568 -0.29868966, -0.11178196 0.035394322 -0.29570419, -0.084601976 0.028843468 -0.32637277, -0.11095303 0.04208912 -0.28907213, -0.10968146 0.043038037 -0.28992537, -0.11185665 0.042932108 -0.28738642, -0.096078694 0.036344074 -0.30331251, -0.1108428 0.034383729 -0.31529313, -0.1111078 0.044615492 -0.28714043, -0.086759731 0.027637469 -0.32459012, -0.094733804 0.028897461 -0.30869693, -0.11130343 0.037060905 -0.29364374, -0.091312014 0.02819325 -0.31010523, -0.097051047 0.037957713 -0.30250648, -0.098369583 0.041564651 -0.30185184, -0.11080921 0.038973644 -0.29188469, -0.096140951 0.032430246 -0.30497065, -0.11383393 0.032900833 -0.30196306, -0.11096548 0.031516805 -0.30473098, -0.11335864 0.034708381 -0.29664618, -0.089853831 0.026894089 -0.32221094, -0.096768633 0.034525976 -0.30356002, -0.11286156 0.036084715 -0.29432353, -0.086892359 0.029067805 -0.32592398, -0.097420394 0.036761504 -0.3024779, -0.095618173 0.027947892 -0.31016639, -0.092057496 0.027215108 -0.31163186, -0.11228181 0.037741996 -0.29228145, -0.098594412 0.040097568 -0.30142513, -0.11514691 0.033224337 -0.30338237, -0.11218633 0.031795859 -0.3062391, -0.097042926 0.030943949 -0.30587646, -0.11493511 0.034366451 -0.29775977, -0.090121761 0.028044965 -0.32377523, -0.11448191 0.035426911 -0.29520935, -0.097609386 0.032849826 -0.30413154, -0.098150328 0.034955718 -0.30270067, -0.11387967 0.036793407 -0.29290614, -0.096502557 0.027342033 -0.3118079, -0.092802912 0.026580613 -0.31333023, -0.076095499 0.037559774 -0.30986112, -0.11629781 0.033895802 -0.30482009, -0.11325659 0.032428388 -0.30775478, -0.076123305 0.036057319 -0.30950546, -0.098021746 0.02971939 -0.30705327, -0.11645107 0.034381106 -0.2990025, -0.11610226 0.035112724 -0.29626709, -0.07616891 0.034518443 -0.3093847, -0.090286732 0.029479198 -0.32510138, -0.098568469 0.031379908 -0.30500478, -0.076218165 0.033269517 -0.30946139, -0.079218812 0.03772483 -0.30953112, -0.11554142 0.036164444 -0.29373449, -0.099039823 0.033294734 -0.30324194, -0.079274222 0.036223833 -0.30917218, -0.11724237 0.034889352 -0.30622137, -0.11413485 0.033389892 -0.30922014, -0.11784825 0.03475219 -0.30032668, -0.097352892 0.027103163 -0.31355771, -0.076315559 0.031359665 -0.30989248, -0.093519568 0.026314232 -0.31513566, -0.10128516 0.042743552 -0.29949388, -0.11766035 0.035154473 -0.29745597, -0.080767177 0.037848204 -0.30928427, -0.079365045 0.034687374 -0.30904686, -0.099039473 0.028803106 -0.30845597, -0.1172031 0.035879113 -0.29473445, -0.076434299 0.029571766 -0.31068757, -0.080836333 0.036348458 -0.30892327, -0.099609144 0.030172914 -0.3061462, -0.0794634 0.033440985 -0.30911857, -0.11794429 0.036166757 -0.30753231, -0.11478741 0.034643557 -0.31057861, -0.11907278 0.035465211 -0.30168149, -0.10005459 0.031842165 -0.30408037, -0.082303569 0.037998818 -0.30898321, -0.11909634 0.035550442 -0.29873034, -0.098136589 0.027240403 -0.31534952, -0.094180293 0.026426315 -0.31697759, -0.11700746 0.037304264 -0.29145512, -0.080949575 0.034813672 -0.30879429, -0.10153577 0.041287053 -0.29904646, -0.118801 0.035948515 -0.29586813, -0.076569632 0.027974155 -0.31181598, -0.08238633 0.036500171 -0.30861965, -0.10005742 0.0282306 -0.31003052, -0.11837642 0.037679084 -0.30870241, -0.11518931 0.036141265 -0.31177798, -0.079657473 0.031536192 -0.30953926, -0.12007782 0.036493029 -0.30301416, -0.11872631 0.037063338 -0.29236621, -0.10069142 0.029275052 -0.30751204, -0.081072144 0.033569239 -0.30886197, -0.12035498 0.036285352 -0.30004138, -0.076716572 0.026628841 -0.31323403, -0.10115556 0.030653939 -0.30518433, -0.12027356 0.036369845 -0.29709154, -0.082521871 0.034967761 -0.30848601, -0.12082462 0.037795953 -0.30427432, -0.084580503 0.038274713 -0.30843121, -0.079894245 0.029754519 -0.31032196, -0.12037922 0.037175585 -0.29341418, -0.098823443 0.027748641 -0.31711376, -0.081314392 0.031668328 -0.30927518, -0.094759271 0.026912238 -0.31878656, -0.12138796 0.037330873 -0.30133864, -0.10103618 0.028023861 -0.31171641, -0.12156428 0.037127208 -0.29835758, -0.082668535 0.033725664 -0.3085492, -0.10177381 0.028721027 -0.30904987, -0.12128451 0.039323937 -0.30541313, -0.076869428 0.025587192 -0.3148877, -0.12190253 0.03763641 -0.29455882, -0.084683284 0.036778539 -0.30806306, -0.12215543 0.038647067 -0.3025721, -0.080164224 0.028164176 -0.31143597, -0.12262356 0.03819114 -0.2996183, -0.081609517 0.02989121 -0.3100484, -0.10342313 0.043775178 -0.29743096, -0.12323767 0.038428165 -0.29575604, -0.12262808 0.040183216 -0.30369452, -0.10230076 0.029775631 -0.30651119, -0.082958445 0.031829432 -0.30895311, -0.12341072 0.039520949 -0.30082446, -0.099387288 0.028608296 -0.31878287, -0.095234424 0.027753647 -0.32049212, -0.12433341 0.039520442 -0.29695982, -0.10193817 0.028190739 -0.31344894, -0.07702221 0.024889218 -0.31671339, -0.12389551 0.041065451 -0.30193031, -0.10369263 0.042327706 -0.29696518, -0.080457255 0.026826587 -0.31283873, -0.12514763 0.040871285 -0.29812416, -0.12564906 0.042428743 -0.29920372, -0.10281447 0.028531913 -0.31070042, -0.081946313 0.028306266 -0.3111518, -0.091904789 0.02617969 -0.31877786, -0.091356568 0.025892068 -0.3169181, -0.1033933 0.031425294 -0.30364156, -0.083311498 0.030057916 -0.30971506, -0.092371106 0.026835572 -0.32056558, -0.092737429 0.027834784 -0.32221192, -0.10344584 0.029241022 -0.30800968, -0.07716918 0.024561778 -0.31864041, -0.095587552 0.028918084 -0.32202917, -0.099806175 0.029786166 -0.32029289, -0.092099547 0.029238977 -0.32415667, -0.088282198 0.038865991 -0.30724877, -0.10413463 0.040879011 -0.29666418, -0.080761969 0.025792895 -0.31447631, -0.092989787 0.029138632 -0.32365379, -0.093868256 0.029051658 -0.32313123, -0.10272878 0.028724916 -0.31516141, -0.095805019 0.030360717 -0.32333854, -0.10377356 0.028715104 -0.31240025, -0.11074105 0.03121879 -0.30870023, -0.10814891 0.030163199 -0.30950421, -0.08231163 0.026974395 -0.31254309, -0.10964786 0.030785404 -0.3071318, -0.11167073 0.031998765 -0.31023982, -0.083714396 0.028479492 -0.31080547, -0.077304587 0.024617422 -0.32059526, -0.11240114 0.033095334 -0.31169137, -0.1046292 0.030578371 -0.30490586, -0.11223635 0.034428246 -0.31377873, -0.10454687 0.029070761 -0.3096227, -0.10006414 0.031237204 -0.32158551, -0.088417679 0.037375074 -0.30686989, -0.11290424 0.034466304 -0.31299919, -0.10461256 0.039727472 -0.29654586, -0.11355241 0.034514815 -0.31220537, -0.081066594 0.025102817 -0.31628582, -0.12384279 0.039094362 -0.29294986, -0.10537389 0.044878483 -0.2952244, -0.12237069 0.038433235 -0.29183701, -0.082691632 0.025946688 -0.31416863, -0.12509485 0.040068224 -0.29410201, -0.1033776 0.02960575 -0.31678802, -0.10586519 0.030075118 -0.3063418, -0.084151715 0.027154628 -0.31218246, -0.12607843 0.041316878 -0.29524919, -0.12641183 0.042664893 -0.29730663, -0.10461423 0.029263522 -0.31408411, -0.12675604 0.042792834 -0.2963472, -0.07742323 0.025054021 -0.3225027, -0.1270754 0.042927239 -0.29538161, -0.089667261 0.02573535 -0.31589833, -0.10556167 0.02927126 -0.31128791, -0.08135955 0.024783095 -0.31819758, -0.090747409 0.025983918 -0.31505707, -0.10566062 0.043440778 -0.29473919, -0.083071671 0.025262754 -0.31596598, -0.092130139 0.02612875 -0.31511146, -0.092266858 0.030157167 -0.32482684, -0.09348692 0.030756779 -0.32471684, -0.094474077 0.03051525 -0.32411066, -0.10627525 0.045454934 -0.29407161, -0.091139257 0.039454002 -0.30607304, -0.10776503 0.030311413 -0.30674648, -0.10705364 0.029934954 -0.30789453, -0.10843325 0.030715346 -0.30559459, -0.10385986 0.030799504 -0.31826639, -0.084606424 0.026134314 -0.31379333, -0.10970494 0.031095769 -0.30517769, -0.077520721 0.02585493 -0.32428935, -0.10530421 0.030156191 -0.31568724, -0.11246303 0.035381384 -0.3143788, -0.081629544 0.024845915 -0.32013819, -0.11345058 0.036177039 -0.31387681, -0.11419693 0.036089476 -0.3129628, -0.12058003 0.037633024 -0.29210433, -0.10613091 0.042008244 -0.294406, -0.083437026 0.024948848 -0.31786609, -0.12073481 0.038109884 -0.29080638, -0.12170255 0.038689494 -0.28999165, -0.086878672 0.027485151 -0.31152159, -0.12666354 0.043660525 -0.29782164, -0.12726854 0.044597603 -0.29703689, -0.12766081 0.044611186 -0.29592067, -0.089071788 0.026116971 -0.31407005, -0.087444082 0.026478188 -0.31310576, -0.090100609 0.026451588 -0.31326643, -0.10415673 0.032260269 -0.31953949, -0.091446839 0.026496371 -0.31331137, -0.10652465 0.030530076 -0.30524442, -0.10714363 0.031011082 -0.30414808, -0.10839544 0.031286534 -0.30373135, -0.11888298 0.037590742 -0.29112378, -0.11899823 0.038136978 -0.2898972, -0.11996558 0.038609464 -0.28908628, -0.088458568 0.026862541 -0.31236386, -0.090743229 0.027227573 -0.31163386, -0.088476822 0.027510798 -0.31133938, 0.21599965 0.11145471 -0.14349306, 0.21599932 0.14745466 -0.14349103, 0.17299958 0.10945441 -0.14349326, 0.2139997 0.1094546 -0.14349326, 0.17299932 0.14945437 -0.14349094, 0.21399939 0.14945465 -0.14349094, 0.21338007 0.11546639 -0.14349282, 0.21282059 0.11483482 -0.14349291, 0.2121262 0.11435544 -0.14349291, 0.21377212 0.11621353 -0.14349282, 0.21133721 0.11405641 -0.14349291, 0.21397407 0.11703269 -0.14349276, 0.21049955 0.11395459 -0.14349291, 0.21397406 0.11787651 -0.14349276, 0.20549956 0.1139545 -0.14349291, 0.20472078 0.11404237 -0.14349306, 0.21282047 0.12683484 -0.14349222, 0.21337998 0.11944285 -0.14349273, 0.2128205 0.12007442 -0.14349255, 0.21337995 0.12746641 -0.14349222, 0.21377209 0.11869572 -0.14349273, 0.21212608 0.1263555 -0.14349222, 0.21212614 0.12055373 -0.14349276, 0.21133718 0.12085295 -0.14349273, 0.2137721 0.12821344 -0.14349216, 0.21133718 0.12605625 -0.14349222, 0.213974 0.12903272 -0.14349216, 0.21049948 0.12595463 -0.14349222, 0.21049953 0.12095454 -0.14349246, 0.20276329 0.11527236 -0.14349291, 0.20331743 0.11471812 -0.14349291, 0.20234619 0.11593594 -0.14349282, 0.20398104 0.11430123 -0.14349291, 0.20549947 0.1259546 -0.14349222, 0.20208734 0.11667572 -0.14349282, 0.20472071 0.12604228 -0.14349222, 0.20398086 0.12630112 -0.14349216, 0.20331737 0.12671807 -0.14349222, 0.20276311 0.12727232 -0.14349231, 0.20234612 0.12793598 -0.14349204, 0.20208727 0.12867579 -0.14349204, 0.21133709 0.13285285 -0.14349183, 0.2104995 0.13295466 -0.14349192, 0.21212605 0.13255379 -0.14349183, 0.21282047 0.13207445 -0.14349183, 0.21337986 0.13144284 -0.14349192, 0.21377198 0.13069576 -0.14349192, 0.21397397 0.12987657 -0.14349207, 0.17099963 0.11145431 -0.14349315, 0.17099936 0.14745438 -0.14349112, 0.20234612 0.12793578 -0.14049229, 0.21397395 0.12903254 -0.14049205, 0.21397403 0.11787628 -0.14049271, 0.21377197 0.12821327 -0.1404922, 0.20472071 0.12604216 -0.14049241, 0.20398092 0.1263009 -0.14049241, 0.20208733 0.12867548 -0.14049211, 0.20276323 0.11527206 -0.14049289, 0.20331743 0.11471792 -0.1404928, 0.20234619 0.11593576 -0.1404928, 0.21397413 0.1170325 -0.1404928, 0.21377221 0.11621335 -0.14049274, 0.20398101 0.11430092 -0.14049295, 0.20208727 0.11667554 -0.14049274, 0.20472077 0.11404221 -0.14049301, 0.2104995 0.13295436 -0.14049196, 0.2054995 0.12595436 -0.14049229, 0.21049958 0.12095447 -0.1404925, 0.2113371 0.13285269 -0.1404919, 0.21212608 0.13255347 -0.1404919, 0.21282046 0.13207422 -0.1404919, 0.21337992 0.13144264 -0.14049196, 0.21377207 0.13069557 -0.14049196, 0.21397401 0.12987629 -0.1404922, 0.20549968 0.11395434 -0.14049289, 0.21049958 0.11395437 -0.14049289, 0.21133718 0.11405618 -0.14049307, 0.21049948 0.12595449 -0.14049241, 0.21133727 0.12085266 -0.1404928, 0.21212611 0.11435528 -0.14049301, 0.21133715 0.12605619 -0.14049229, 0.21282059 0.11483462 -0.14049289, 0.21338001 0.11546616 -0.1404928, 0.21212605 0.12635536 -0.14049229, 0.21212614 0.12055343 -0.14049259, 0.21282053 0.12007424 -0.1404925, 0.21282047 0.12683466 -0.14049226, 0.21337999 0.11944267 -0.14049274, 0.2033173 0.126718 -0.14049226, 0.21337996 0.12746617 -0.1404922, 0.21377218 0.11869553 -0.14049274, 0.20276317 0.12727208 -0.14049226, -0.21400052 0.10945186 -0.14349315, -0.17300057 0.10945215 -0.14349315, -0.21600083 0.14745194 -0.14349103, -0.2160005 0.11145186 -0.14349306, -0.21400075 0.14945182 -0.143491, -0.17300077 0.14945218 -0.14349094, -0.21323691 0.1152696 -0.14349297, -0.21268287 0.11471559 -0.14349291, -0.213654 0.11593333 -0.14349282, -0.21201918 0.11429857 -0.14349291, -0.21391296 0.11667308 -0.14349276, -0.2112795 0.11403966 -0.14349291, -0.21050069 0.11395186 -0.14349303, -0.20550063 0.11395183 -0.14349297, -0.20466298 0.11405367 -0.14349303, -0.21268287 0.1267155 -0.14349222, -0.21323705 0.12726974 -0.14349207, -0.21365413 0.12793334 -0.14349231, -0.21201926 0.12629835 -0.14349243, -0.21391292 0.12867305 -0.14349207, -0.21127948 0.12603959 -0.14349231, -0.21050066 0.12595195 -0.14349216, -0.20222798 0.11621086 -0.14349291, -0.20262019 0.11546379 -0.14349297, -0.20317958 0.11483215 -0.14349303, -0.2038741 0.11435287 -0.14349303, -0.20550072 0.12595192 -0.14349222, -0.20550068 0.12095192 -0.14349255, -0.20466295 0.12085021 -0.14349276, -0.20202613 0.11703005 -0.14349282, -0.20222808 0.11869311 -0.14349276, -0.20202604 0.11787376 -0.14349276, -0.20466307 0.12605363 -0.14349222, -0.20387417 0.12635289 -0.14349222, -0.20387407 0.12055099 -0.14349282, -0.2031797 0.12007174 -0.14349276, -0.20262021 0.11944018 -0.14349276, -0.20262027 0.12746376 -0.14349231, -0.20317966 0.12683213 -0.14349216, -0.20202611 0.12903002 -0.14349222, -0.2022281 0.12821078 -0.14349216, -0.20222814 0.13069305 -0.14349204, -0.20202628 0.1298739 -0.14349198, -0.20262028 0.13144022 -0.14349216, -0.20550069 0.13295192 -0.14349183, -0.20466307 0.13285021 -0.14349183, -0.20317972 0.13207163 -0.14349198, -0.20387414 0.13255106 -0.14349192, -0.17100053 0.11145215 -0.14349303, -0.17100078 0.14745219 -0.14349103, -0.2105007 0.12595177 -0.14049229, -0.21127942 0.12603942 -0.14049229, -0.21268281 0.11471523 -0.14049289, -0.213237 0.1152695 -0.14049289, -0.21365392 0.11593306 -0.14049274, -0.20550075 0.13295171 -0.14049196, -0.2046631 0.13284999 -0.14049196, -0.20387422 0.13255088 -0.1404919, -0.21201912 0.11429819 -0.14049309, -0.20466292 0.11405343 -0.14049289, -0.20222805 0.11869289 -0.14049274, -0.20202604 0.11787358 -0.1404928, -0.20202611 0.11702991 -0.1404928, -0.20222807 0.11621064 -0.1404928, -0.20262003 0.11546345 -0.14049289, -0.20317958 0.114832 -0.1404928, -0.20387408 0.11435264 -0.14049295, -0.2139129 0.1166729 -0.1404928, -0.21127941 0.11403945 -0.14049307, -0.20222816 0.12821069 -0.14049211, -0.20202623 0.1290299 -0.14049205, -0.21050051 0.11395162 -0.14049295, -0.20222813 0.13069274 -0.14049211, -0.20202626 0.12987363 -0.1404922, -0.20317978 0.13207155 -0.1404919, -0.20262021 0.13143989 -0.14049196, -0.2055008 0.12595184 -0.14049226, -0.20550062 0.12095164 -0.14049271, -0.20466299 0.12085007 -0.1404925, -0.20550063 0.11395165 -0.14049301, -0.20466298 0.12605345 -0.14049229, -0.20387425 0.12635276 -0.14049226, -0.20387404 0.12055083 -0.1404925, -0.20317961 0.12007159 -0.14049271, -0.20317978 0.12683201 -0.14049229, -0.20262039 0.12746364 -0.14049226, -0.20262027 0.11944009 -0.1404928, -0.21268289 0.1267153 -0.14049226, -0.21323711 0.12726945 -0.14049226, -0.21365406 0.12793307 -0.14049229, -0.21201929 0.12629825 -0.14049241, -0.21391298 0.12867291 -0.1404922, 0.058384772 0.022426717 0.33264405, 0.058432702 0.022031907 0.33264402, 0.058384713 0.022427198 0.32664412, 0.058432709 0.022032257 0.32664412, 0.058573838 0.021659967 0.33264416, 0.058573786 0.021660324 0.32664412, 0.058799736 0.021332506 0.33264402, 0.058799695 0.021333095 0.32664412, 0.059097547 0.021068785 0.33264405, 0.059097484 0.021069262 0.32664412, 0.059449691 0.020884011 0.33264416, 0.059449699 0.020884376 0.326644, 0.059835881 0.020788819 0.33264402, 0.059835959 0.020789247 0.32664412, 0.060233679 0.02078883 0.33264402, 0.060233679 0.020789247 0.32664412, 0.060619827 0.020884078 0.33264402, 0.060619887 0.020884383 0.326644, 0.060972054 0.021068949 0.33264402, 0.060972113 0.021069277 0.32664412, 0.061269812 0.021332521 0.33264402, 0.061269812 0.021332998 0.326644, 0.061495841 0.021659989 0.33264402, 0.061495718 0.021660432 0.32664436, 0.061636746 0.022032037 0.33264402, 0.061636783 0.02203228 0.32664424, 0.061684776 0.022426803 0.33264405, 0.06168472 0.022427104 0.32664412, 0.058385082 -0.013573263 0.33264211, 0.058432922 -0.013968173 0.33264202, 0.058385 -0.013572875 0.32664222, 0.058432844 -0.013967615 0.32664225, 0.058573987 -0.014340017 0.3326419, 0.058573924 -0.01433963 0.32664222, 0.058799915 -0.014667366 0.33264202, 0.058799945 -0.014667008 0.32664225, 0.059097655 -0.014931146 0.33264202, 0.059097685 -0.014930751 0.32664225, 0.059449844 -0.015115913 0.33264199, 0.059449881 -0.015115704 0.3266421, 0.059836086 -0.015211161 0.33264202, 0.059836157 -0.015210804 0.32664198, 0.060233898 -0.015211169 0.33264199, 0.060233798 -0.015210796 0.32664198, 0.060620137 -0.015115973 0.3326422, 0.060620107 -0.015115704 0.3266421, 0.060972281 -0.014931131 0.33264199, 0.060972326 -0.014930744 0.32664198, 0.061270025 -0.014667351 0.3326422, 0.061270088 -0.014667001 0.32664225, 0.061495982 -0.014339972 0.33264199, 0.061495982 -0.014339615 0.32664198, 0.061636955 -0.013968159 0.33264211, 0.061637096 -0.013967801 0.3266421, 0.061685003 -0.013573233 0.33264223, 0.061684944 -0.013572749 0.3266421, 0.055784825 0.014426809 0.33264366, 0.056393806 0.013529431 0.33214372, 0.056284852 0.014426809 0.33214372, 0.055908304 0.013409719 0.33264366, 0.056714434 0.012683917 0.33214372, 0.05627165 0.012451693 0.33264351, 0.057227992 0.011940051 0.33214346, 0.056853708 0.011608411 0.33264351, 0.057904538 0.011340547 0.33214346, 0.057620574 0.010929037 0.33264345, 0.05870505 0.010920491 0.33214346, 0.05852776 0.01045296 0.33264345, 0.059582762 0.010704134 0.3321436, 0.059522588 0.010207836 0.33264342, 0.060486794 0.01070426 0.3321436, 0.060547106 0.010207757 0.33264351, 0.06136458 0.010920513 0.3321436, 0.061541874 0.010453027 0.33264345, 0.062165018 0.011340581 0.3321436, 0.062449165 0.010929015 0.33264345, 0.063215971 0.01160863 0.33264342, 0.062841736 0.011940144 0.3321436, 0.063355245 0.012684133 0.3321436, 0.063797936 0.012451801 0.33264366, 0.063675873 0.01352933 0.33214372, 0.064161286 0.013409708 0.33264366, 0.064284764 0.014426801 0.33264366, 0.063784815 0.014426801 0.33214384, 0.055784918 -0.0055732615 0.33264253, 0.056394033 -0.0064707734 0.33214253, 0.05628496 -0.0055732504 0.33214265, 0.055908445 -0.0065903589 0.33264253, 0.056714531 -0.0073160119 0.33214241, 0.056271777 -0.0075483732 0.33264238, 0.057228018 -0.0080598406 0.33214247, 0.056853786 -0.0083914809 0.33264229, 0.057904597 -0.0086592548 0.33214241, 0.057620671 -0.0090708844 0.33264238, 0.058705185 -0.0090795495 0.33214232, 0.058527812 -0.0095469244 0.33264229, 0.059582878 -0.0092958175 0.33214238, 0.059522685 -0.0097921453 0.33264238, 0.060486984 -0.0092958324 0.33214241, 0.060547303 -0.0097922646 0.33264238, 0.061364789 -0.0090795942 0.33214247, 0.061542027 -0.0095470734 0.33264238, 0.062165283 -0.0086594336 0.33214247, 0.062449228 -0.0090709291 0.33264229, 0.062841944 -0.008060012 0.33214238, 0.063216157 -0.008391466 0.33264238, 0.063355364 -0.0073159076 0.33214238, 0.063798197 -0.0075482465 0.33264238, 0.063676044 -0.0064707138 0.33214247, 0.064161532 -0.0065903552 0.33264253, 0.06428504 -0.0055733323 0.33264253, 0.063785046 -0.0055733025 0.33214247, 0.056284953 -0.0055729486 0.32814258, 0.056393921 -0.0064703599 0.32814258, 0.056714468 -0.0073157065 0.32814258, 0.057228036 -0.008059714 0.32814234, 0.05790472 -0.0086591877 0.32814234, 0.058705244 -0.009079311 0.32814258, 0.059582967 -0.0092956685 0.32814246, 0.06048701 -0.009295661 0.32814255, 0.061364681 -0.0090791769 0.32814246, 0.062165249 -0.0086591728 0.32814246, 0.0628419 -0.0080597065 0.32814258, 0.063355319 -0.0073156096 0.32814246, 0.063675955 -0.006470345 0.32814258, 0.063785017 -0.0055729449 0.32814258, 0.056284834 0.014426988 0.32814369, 0.056393761 0.01352952 0.3281436, 0.056714375 0.012684297 0.32814366, 0.05722791 0.011940349 0.32814369, 0.057904538 0.011340905 0.32814366, 0.058705088 0.0109207 0.32814354, 0.059582826 0.010704368 0.32814354, 0.060486875 0.010704432 0.32814354, 0.061364587 0.010920718 0.32814369, 0.062165145 0.011340823 0.32814369, 0.06284184 0.011940233 0.3281436, 0.063355267 0.012684349 0.32814378, 0.063675903 0.013529632 0.32814369, 0.063784949 0.014426976 0.32814378, 0.060034961 0.0028271452 0.3266432, 0.059651971 0.0028736666 0.3266432, 0.060034852 0.0028267875 0.33264303, 0.05965193 0.0028734021 0.33264318, 0.059291359 0.0030103922 0.3266432, 0.059291303 0.0030101277 0.33264303, 0.058973897 0.0032294728 0.3266432, 0.058973879 0.0032292046 0.33264318, 0.058718156 0.003518194 0.3266432, 0.058718201 0.0035178363 0.33264294, 0.058538981 0.0038597211 0.3266432, 0.058538925 0.003859248 0.33264318, 0.058446623 0.004234165 0.3266432, 0.058446568 0.0042338036 0.33264321, 0.058446586 0.0046199821 0.32664329, 0.058446586 0.0046195053 0.33264321, 0.058538858 0.0049945153 0.3266432, 0.058538921 0.0049940944 0.33264318, 0.058718137 0.0053360797 0.32664329, 0.058718137 0.0053357184 0.33264321, 0.058973823 0.0056247711 0.32664341, 0.058973931 0.0056243278 0.33264333, 0.059291292 0.0058439113 0.32664329, 0.059291415 0.0058435276 0.33264321, 0.059652027 0.0059806444 0.3266432, 0.059652019 0.0059802271 0.33264321, 0.06003492 0.0060271695 0.32664329, 0.060034934 0.0060267523 0.33264321, 0.060034931 -0.0076728128 0.32664245, 0.059532385 -0.0076116882 0.32664245, 0.060034987 -0.0076729916 0.32814255, 0.059532404 -0.0076119117 0.32814258, 0.059058961 -0.0074322335 0.32664245, 0.059059076 -0.0074324943 0.32814258, 0.058642369 -0.0071447231 0.32664257, 0.058642466 -0.007144969 0.32814255, 0.058306687 -0.0067658499 0.32664257, 0.058306705 -0.0067659356 0.32814258, 0.058071356 -0.006317623 0.32664254, 0.058071382 -0.0063176788 0.3281427, 0.057950269 -0.0058259442 0.32664269, 0.057950269 -0.0058260635 0.3281427, 0.057950243 -0.0053197332 0.32664257, 0.057950199 -0.0053198412 0.32814258, 0.058071475 -0.0048283264 0.3266426, 0.058071326 -0.0048283227 0.32814258, 0.058306694 -0.0043798983 0.32664269, 0.058306634 -0.004380025 0.32814282, 0.058642369 -0.0040009208 0.32664281, 0.058642346 -0.0040011406 0.3281427, 0.059059087 -0.0037133396 0.32664269, 0.05905899 -0.0037135221 0.32814282, 0.05953237 -0.0035338365 0.32664281, 0.059532251 -0.0035339855 0.32814282, 0.060034979 -0.0034727976 0.32664281, 0.060034871 -0.0034729503 0.32814282, 0.060034852 0.012327116 0.32664365, 0.059532281 0.012388233 0.32664371, 0.0600348 0.012327023 0.32814369, 0.059532154 0.012388173 0.32814378, 0.059058849 0.012567699 0.32664344, 0.05905886 0.012567554 0.32814369, 0.058642279 0.012855258 0.32664379, 0.058642287 0.012855228 0.32814369, 0.058306523 0.013234224 0.32664365, 0.05830653 0.013234079 0.32814366, 0.058071237 0.013682418 0.32664365, 0.058071256 0.013682391 0.32814389, 0.057950143 0.014174011 0.32664379, 0.057950087 0.014173921 0.32814378, 0.057950076 0.014680322 0.32664379, 0.057950072 0.014680233 0.32814378, 0.058071326 0.015171818 0.32664379, 0.05807123 0.015171703 0.32814378, 0.058306541 0.015620075 0.32664379, 0.058306478 0.015619993 0.32814378, 0.058642264 0.015999082 0.32664379, 0.058642205 0.015998986 0.32814395, 0.059058879 0.016286675 0.32664379, 0.059058886 0.016286407 0.32814395, 0.059532259 0.016466144 0.32664371, 0.059532236 0.016466025 0.32814389, 0.060034856 0.016527127 0.32664379, 0.060034815 0.016527005 0.32814389, 0.060537402 0.016466152 0.32664379, 0.060537394 0.016466059 0.32814395, 0.061010677 0.016286414 0.32814378, 0.061010778 0.016286507 0.32664388, 0.061427291 0.015999008 0.32814395, 0.061427332 0.015999127 0.32664388, 0.061763011 0.015620012 0.32814378, 0.061763097 0.015620101 0.32664379, 0.061998386 0.015171785 0.32814395, 0.061998386 0.015171845 0.32664379, 0.062119454 0.014680196 0.32814389, 0.062119603 0.014680225 0.32664371, 0.062119603 0.014173884 0.32814366, 0.06211951 0.014174063 0.32664379, 0.061998483 0.013682302 0.32814389, 0.061998431 0.013682563 0.32664379, 0.061763093 0.013234068 0.32814378, 0.061763085 0.013234247 0.32664365, 0.061427407 0.012855131 0.32814389, 0.061427336 0.012855273 0.32664365, 0.061010841 0.012567561 0.32814369, 0.061010752 0.01256771 0.32664379, 0.060537394 0.012388062 0.32814369, 0.06053742 0.012388241 0.32664371, 0.050535131 -0.035073254 0.33264101, 0.069535203 -0.035073217 0.33264092, 0.058433 -0.013178322 0.33264223, 0.058799911 -0.012479041 0.33264223, 0.058573995 -0.012806516 0.33264211, 0.059449926 -0.012030568 0.33264223, 0.059097793 -0.01221535 0.3326422, 0.060233828 -0.011935186 0.33264223, 0.059836131 -0.01193532 0.33264211, 0.060620081 -0.012030471 0.33264223, 0.061269954 -0.012479018 0.33264223, 0.060972251 -0.012215246 0.33264211, 0.061637092 -0.013178308 0.3326422, 0.061495937 -0.012806389 0.33264211, 0.058527812 -0.001599405 0.33264282, 0.057620637 -0.0020755082 0.33264282, 0.059522618 -0.0013541989 0.33264285, 0.056853756 -0.0027549379 0.33264285, 0.056271698 -0.0035981722 0.33264273, 0.060547262 -0.0013543032 0.33264282, 0.060417805 0.0028732829 0.33264318, 0.060778428 0.0030100234 0.33264303, 0.061541997 -0.0015993863 0.33264273, 0.061095845 0.0032292157 0.33264318, 0.062449135 -0.0020754449 0.33264282, 0.061351627 0.0035179369 0.33264318, 0.061530959 0.0038593896 0.33264318, 0.063216098 -0.0027549341 0.33264259, 0.06379807 -0.0035980046 0.33264282, 0.061623283 0.0042339079 0.33264318, 0.055908512 -0.0045562424 0.33264259, 0.060417827 0.0059802048 0.33264321, 0.060778487 0.0058434084 0.33264333, 0.061095927 0.0056243949 0.33264321, 0.061351705 0.0053356141 0.33264321, 0.061530892 0.0049941726 0.33264318, 0.061623182 0.0046196431 0.33264321, 0.064161472 -0.0045560859 0.33264253, 0.058527756 0.018400673 0.33264387, 0.057620477 0.017924506 0.33264381, 0.059522498 0.018645886 0.33264402, 0.056853667 0.017245013 0.33264381, 0.060547035 0.018645804 0.33264378, 0.056271575 0.016401846 0.33264381, 0.058432773 0.022821516 0.33264405, 0.061541911 0.018400569 0.3326439, 0.062449083 0.01792448 0.33264381, 0.063216008 0.017245088 0.33264402, 0.063797981 0.016401861 0.33264378, 0.061636779 0.022821687 0.33264416, 0.059835926 0.024064731 0.33264416, 0.050534632 0.043926701 0.33264524, 0.059449617 0.023969594 0.33264416, 0.059097599 0.023784604 0.33264416, 0.05879974 0.02352095 0.33264416, 0.058573846 0.023193568 0.33264402, 0.055908244 0.015443902 0.33264366, 0.064161345 0.015443835 0.33264378, 0.069534652 0.04392682 0.33264542, 0.061495833 0.023193497 0.33264428, 0.06126982 0.023520906 0.33264428, 0.060972139 0.023784656 0.33264428, 0.060619872 0.023969546 0.33264428, 0.060233697 0.024064731 0.33264428, 0.069535129 -0.035572816 0.32714099, 0.069535218 -0.035573196 0.33214083, 0.050535161 -0.035572935 0.32714075, 0.050535146 -0.035573307 0.33214083, 0.050035127 -0.032572906 0.32664117, 0.070035145 -0.03507277 0.32664102, 0.050035164 -0.035072897 0.32664111, 0.070035145 -0.032572795 0.32664111, 0.0500351 -0.03157324 0.32964113, 0.070035085 -0.031572904 0.32764119, 0.050035108 -0.031573001 0.32764119, 0.07003516 -0.031573158 0.32964116, 0.050034937 -0.019573148 0.32964197, 0.070035048 -0.019573171 0.32964176, 0.050034951 -0.019573022 0.32764167, 0.07003504 -0.019572821 0.32764179, 0.050034646 0.027427144 0.32664451, 0.05909745 0.023784995 0.32664424, 0.058799684 0.023521308 0.32664412, 0.058573715 0.023194075 0.32664427, 0.059449654 0.023969952 0.32664427, 0.058432601 0.022822078 0.32664427, 0.059835847 0.024065115 0.32664427, 0.060233623 0.024065118 0.32664427, 0.061636757 0.022822045 0.32664427, 0.070034698 0.027427267 0.32664448, 0.061495844 0.023193944 0.32664436, 0.061269801 0.023521293 0.32664424, 0.06097205 0.023785066 0.32664436, 0.060619842 0.023969959 0.32664427, 0.060417771 0.0059806518 0.32664329, 0.060778394 0.0058439188 0.32664341, 0.061095797 0.0056248493 0.32664341, 0.061351623 0.0053360909 0.32664329, 0.061530951 0.0049945302 0.32664329, 0.061623219 0.0046201199 0.32664329, 0.06041782 0.002873607 0.32664308, 0.060537476 -0.0035339482 0.32664281, 0.06077851 0.0030103438 0.32664305, 0.06101089 -0.0037133284 0.32664281, 0.061095972 0.0032294504 0.3266432, 0.061427515 -0.0040009953 0.32664281, 0.061351772 0.0035182387 0.32664305, 0.061763275 -0.0043799728 0.32664269, 0.061530896 0.0038598627 0.3266432, 0.061998405 -0.0048281997 0.32664269, 0.061623193 0.0042343065 0.32664329, 0.062119637 -0.0053196959 0.32664257, 0.050035048 -0.018572893 0.32664177, 0.058799841 -0.012478638 0.32664225, 0.059097756 -0.012214866 0.32664236, 0.058573999 -0.012806136 0.32664233, 0.059449885 -0.012030054 0.32664233, 0.058432892 -0.013177965 0.32664225, 0.059836023 -0.011934843 0.32664225, 0.060233794 -0.011934843 0.32664236, 0.060537469 -0.0076117404 0.32664245, 0.06101089 -0.0074323006 0.32664245, 0.060620114 -0.012030061 0.32664233, 0.06142747 -0.007144656 0.32664245, 0.060972359 -0.012214858 0.32664225, 0.061763171 -0.0067657344 0.32664257, 0.061270051 -0.012478638 0.32664236, 0.061998416 -0.0063174777 0.32664254, 0.061496045 -0.012806136 0.32664216, 0.06163713 -0.013178039 0.32664225, 0.070035033 -0.018572863 0.32664198, 0.062119599 -0.0058259666 0.32664257, 0.050034732 0.028426804 0.32964462, 0.070034817 0.028427076 0.32764453, 0.050034709 0.028427009 0.32764444, 0.070034817 0.028426897 0.3296445, 0.050034691 0.040426828 0.3296454, 0.070034645 0.040426955 0.3296454, 0.050034653 0.040426977 0.32764503, 0.070034653 0.040427044 0.32764524, 0.050034512 0.043927208 0.32664555, 0.070034623 0.041427206 0.32664531, 0.050034638 0.041427147 0.32664531, 0.070034623 0.043927208 0.32664543, 0.050534572 0.044426691 0.33214533, 0.069534644 0.044427197 0.3271454, 0.050534751 0.044427019 0.32714552, 0.069534644 0.044426844 0.33214548, 0.070035182 -0.035073202 0.33214095, 0.070034653 0.04392688 0.33214533, 0.050035104 -0.035073254 0.33214098, 0.050034542 0.043926813 0.33214539, 0.060537435 -0.0035339706 0.32814282, 0.061010908 -0.0037135072 0.3281427, 0.061427474 -0.0040010363 0.3281427, 0.061763309 -0.0043801218 0.3281427, 0.061998595 -0.0048283711 0.3281427, 0.062119611 -0.0053198114 0.3281427, 0.062119748 -0.0058260933 0.3281427, 0.061998498 -0.0063176267 0.32814246, 0.061763249 -0.0067659169 0.32814258, 0.061427385 -0.0071447231 0.32814255, 0.061010856 -0.00743239 0.32814246, 0.060537543 -0.0076119564 0.32814255, 0.05870505 0.017933305 0.32814401, 0.057904612 0.017513178 0.32814395, 0.059582803 0.018149655 0.32814395, 0.060486857 0.018149596 0.32814401, 0.063675866 0.015324473 0.32814378, 0.061364569 0.017933387 0.32814395, 0.056393761 0.015324336 0.32814378, 0.063355215 0.016169872 0.32814378, 0.062165063 0.017513324 0.32814401, 0.062841699 0.016913738 0.32814401, 0.056714408 0.016169719 0.32814398, 0.057227958 0.016913731 0.32814389, 0.063675821 0.015324324 0.33214372, 0.063355222 0.016169634 0.33214381, 0.062841743 0.0169135 0.33214393, 0.062165085 0.017512847 0.33214384, 0.06136452 0.017933086 0.33214408, 0.060486805 0.018149417 0.33214393, 0.059582718 0.018149499 0.33214393, 0.058704991 0.017933067 0.33214384, 0.057904489 0.017512973 0.33214384, 0.057227876 0.016913462 0.33214381, 0.056714352 0.016169541 0.33214372, 0.056393713 0.015324254 0.33214384, 0.062165152 -0.0024867766 0.32814282, 0.061364774 -0.0020666905 0.32814294, 0.06048689 -0.0018502101 0.32814282, 0.059582952 -0.0018503927 0.32814282, 0.063675992 -0.0046755448 0.32814258, 0.056393925 -0.0046756119 0.3281427, 0.058705136 -0.0020666458 0.3281427, 0.063355438 -0.003830228 0.3281427, 0.056714457 -0.003830269 0.32814282, 0.057904705 -0.0024868287 0.3281427, 0.057228018 -0.0030863099 0.3281427, 0.062841937 -0.003086362 0.3281427, 0.063675977 -0.0046757497 0.33214265, 0.063355342 -0.0038304925 0.33214265, 0.062841803 -0.0030865148 0.33214265, 0.062165163 -0.0024870373 0.33214283, 0.061364774 -0.0020670146 0.33214283, 0.060487021 -0.0018505938 0.33214283, 0.059582926 -0.0018505491 0.33214283, 0.0587052 -0.0020669103 0.33214274, 0.057904627 -0.0024870709 0.33214274, 0.05722804 -0.0030864887 0.33214283, 0.056714524 -0.0038305074 0.33214265, 0.05639394 -0.0046759099 0.33214265, -0.21050054 0.11743599 0.14050737, -0.21042794 0.11683762 0.14050737, -0.21050064 0.11743627 0.13400719, -0.2104279 0.11683793 0.13400719, -0.2102142 0.11627421 0.14050737, -0.2102142 0.11627443 0.13400739, -0.2098718 0.11577812 0.14050737, -0.20987178 0.11577837 0.13400719, -0.20942074 0.1153785 0.14050728, -0.20942074 0.1153788 0.13400739, -0.20888707 0.11509842 0.14050728, -0.20888713 0.11509871 0.13400719, -0.20830178 0.11495413 0.14050713, -0.2083019 0.11495444 0.13400739, -0.20769927 0.11495429 0.14050737, -0.20769911 0.11495444 0.13400719, -0.20711422 0.11509852 0.14050737, -0.20711401 0.11509873 0.13400719, -0.20658049 0.11537856 0.14050728, -0.20658037 0.1153788 0.13400719, -0.20612933 0.11577815 0.14050713, -0.20612927 0.11577851 0.13400719, -0.20578694 0.11627421 0.14050728, -0.20578694 0.11627439 0.13400739, -0.20557326 0.11683771 0.14050749, -0.20557319 0.11683801 0.13400751, -0.20550054 0.11743596 0.14050737, -0.2055006 0.11743626 0.13400739, -0.1815006 0.11743611 0.14050749, -0.18142787 0.11683783 0.14050728, -0.18150064 0.11743644 0.13400719, -0.1814279 0.11683811 0.13400751, -0.18121415 0.11627433 0.14050737, -0.18121414 0.1162746 0.13400739, -0.18087196 0.11577833 0.14050728, -0.18087181 0.11577851 0.13400739, -0.18042077 0.11537865 0.14050713, -0.18042068 0.11537898 0.13400719, -0.17988703 0.1150986 0.14050728, -0.17988709 0.11509897 0.13400719, -0.17930189 0.11495443 0.14050728, -0.17930189 0.11495478 0.13400695, -0.17869918 0.11495444 0.14050728, -0.17869914 0.11495464 0.13400704, -0.17811407 0.11509866 0.14050713, -0.17811403 0.11509892 0.13400719, -0.17758039 0.11537864 0.14050728, -0.17758039 0.115379 0.13400719, -0.17712927 0.11577838 0.14050728, -0.17712922 0.11577858 0.13400719, -0.17678691 0.1162743 0.14050728, -0.17678688 0.11627463 0.13400739, -0.17657322 0.11683783 0.14050728, -0.17657319 0.11683816 0.13400739, -0.17650062 0.11743622 0.14050737, -0.17650062 0.11743644 0.13400739, -0.21050058 0.12943593 0.14050797, -0.21042797 0.12883765 0.14050773, -0.21050055 0.12943619 0.1340079, -0.21042795 0.12883802 0.1340079, -0.21021418 0.12827407 0.14050788, -0.21021418 0.12827449 0.1340079, -0.20987186 0.12777814 0.14050773, -0.20987201 0.12777853 0.1340079, -0.20942083 0.12737849 0.14050788, -0.2094208 0.12737876 0.1340079, -0.20888725 0.12709841 0.14050773, -0.20888716 0.12709868 0.13400778, -0.20830208 0.12695429 0.14050773, -0.20830202 0.12695451 0.1340079, -0.20769931 0.12695414 0.14050788, -0.20769942 0.12695451 0.1340079, -0.20711404 0.12709841 0.14050773, -0.20711413 0.12709874 0.1340079, -0.20658046 0.12737855 0.14050797, -0.20658045 0.12737879 0.13400778, -0.20612933 0.12777822 0.14050797, -0.20612925 0.1277785 0.13400778, -0.205787 0.12827417 0.14050797, -0.20578694 0.12827453 0.1340079, -0.20557331 0.12883776 0.14050797, -0.20557332 0.12883809 0.1340079, -0.20550066 0.12943602 0.14050812, -0.20550068 0.12943624 0.13400808, -0.18150064 0.12943611 0.14050797, -0.18142805 0.12883791 0.1405082, -0.18150057 0.12943639 0.1340079, -0.18142807 0.12883826 0.13400799, -0.18121427 0.12827441 0.14050797, -0.18121418 0.1282746 0.1340079, -0.1808719 0.12777823 0.14050788, -0.1808719 0.12777859 0.13400799, -0.18042076 0.12737858 0.14050773, -0.1804208 0.12737896 0.13400778, -0.17988706 0.1270985 0.14050773, -0.17988706 0.12709887 0.13400778, -0.17930198 0.12695441 0.14050773, -0.17930199 0.12695473 0.13400778, -0.17869936 0.12695445 0.14050773, -0.17869921 0.1269546 0.1340079, -0.17811418 0.12709865 0.14050788, -0.17811403 0.1270988 0.13400799, -0.17758049 0.1273787 0.14050788, -0.17758045 0.12737896 0.1340079, -0.17712939 0.1277784 0.14050773, -0.17712936 0.12777865 0.1340079, -0.1767869 0.12827437 0.14050797, -0.17678699 0.12827469 0.1340079, -0.17657328 0.12883791 0.14050797, -0.17657328 0.12883821 0.1340079, -0.17650068 0.12943618 0.14050797, -0.1765006 0.12943645 0.13400808, -0.21600075 0.14743599 0.14050895, -0.21600081 0.14743629 0.13400897, -0.21600047 0.11143592 0.14050713, -0.21600047 0.11143622 0.13400704, -0.21400046 0.10943589 0.14050689, -0.21400045 0.10943617 0.13400692, -0.17300051 0.10943614 0.14050689, -0.17300057 0.10943651 0.13400716, -0.1710005 0.11143656 0.13400704, -0.17100084 0.14743657 0.13400897, -0.17100048 0.11143614 0.14050713, -0.17100081 0.14743626 0.14050916, -0.17300077 0.14943653 0.13400906, -0.21400069 0.14943589 0.14050916, -0.17300077 0.14943612 0.1405094, -0.21400088 0.1494363 0.13400906, -0.21042794 0.11803424 0.14050728, -0.21021427 0.11859776 0.14050749, -0.2094207 0.11949342 0.14050761, -0.20888719 0.11977358 0.14050761, -0.20987187 0.11909376 0.14050749, -0.20830202 0.11991775 0.14050761, -0.20769933 0.11991777 0.14050761, -0.20711404 0.11977351 0.14050761, -0.20658042 0.11949345 0.14050737, -0.20612925 0.1190937 0.14050737, -0.20578694 0.11859778 0.14050773, -0.20888716 0.13177353 0.14050812, -0.20830196 0.1319177 0.14050812, -0.20942083 0.1314934 0.14050812, -0.20987189 0.13109377 0.1405082, -0.21021426 0.13059774 0.14050812, -0.21042801 0.13003421 0.1405082, -0.20711419 0.1317735 0.1405082, -0.20658055 0.13149336 0.1405082, -0.20769948 0.13191777 0.1405082, -0.18142788 0.11803432 0.14050737, -0.20557323 0.11803418 0.14050737, -0.18121423 0.11859789 0.14050737, -0.17657322 0.11803447 0.14050728, -0.17678696 0.11859801 0.14050761, -0.18042071 0.11949354 0.14050737, -0.179887 0.1197737 0.14050749, -0.18087178 0.11909397 0.14050737, -0.17930183 0.11991784 0.14050749, -0.17869923 0.11991791 0.14050737, -0.18142797 0.13003448 0.14050797, -0.20557328 0.1300343 0.14050812, -0.17811409 0.11977375 0.14050749, -0.17758039 0.11949366 0.14050761, -0.18121436 0.13059804 0.14050797, -0.20578709 0.1305978 0.14050812, -0.18087195 0.13109408 0.14050797, -0.20612934 0.13109377 0.14050812, -0.1771293 0.11909395 0.14050749, -0.18042079 0.13149358 0.14050812, -0.17657332 0.13003445 0.14050812, -0.17678699 0.13059798 0.14050812, -0.17712946 0.13109401 0.14050812, -0.17758045 0.1314936 0.1405082, -0.17811413 0.13177374 0.1405082, -0.17869931 0.13191795 0.14050832, -0.1793021 0.13191801 0.14050832, -0.17988718 0.13177365 0.1405082, -0.21042804 0.11803453 0.13400739, -0.21021438 0.11859816 0.13400751, -0.20942083 0.1194938 0.13400739, -0.20888713 0.11977389 0.13400751, -0.2098719 0.11909409 0.13400751, -0.20830196 0.11991817 0.13400751, -0.2076993 0.11991812 0.13400739, -0.20711412 0.11977383 0.13400739, -0.20658034 0.11949374 0.13400739, -0.20612925 0.119094 0.13400739, -0.20578688 0.11859807 0.13400739, -0.20888704 0.13177374 0.13400823, -0.2083019 0.13191794 0.13400838, -0.2094209 0.1314937 0.13400835, -0.2098719 0.13109417 0.13400799, -0.2102143 0.13059804 0.13400808, -0.2104279 0.13003451 0.1340079, -0.20711425 0.13177387 0.13400835, -0.20658043 0.1314937 0.13400808, -0.20769933 0.13191809 0.13400823, -0.2055732 0.11803457 0.13400751, -0.18142787 0.11803463 0.13400751, -0.18121427 0.11859824 0.13400739, -0.17657319 0.11803468 0.13400719, -0.17678702 0.11859831 0.13400751, -0.18042071 0.1194938 0.13400763, -0.17988712 0.11977401 0.13400751, -0.1808719 0.11909427 0.13400739, -0.17930195 0.11991827 0.13400751, -0.17869924 0.11991817 0.13400751, -0.20557334 0.13003466 0.1340079, -0.18142807 0.13003486 0.1340079, -0.1781141 0.119774 0.13400751, -0.17758036 0.11949393 0.13400751, -0.20578709 0.13059816 0.13400808, -0.18121429 0.13059832 0.1340079, -0.20612942 0.13109422 0.13400808, -0.18087205 0.13109434 0.13400823, -0.17712939 0.11909428 0.13400751, -0.18042083 0.13149402 0.13400808, -0.17930199 0.13191828 0.13400808, -0.17869931 0.13191825 0.13400808, -0.17988724 0.13177395 0.13400823, -0.17657323 0.13003477 0.13400799, -0.17678705 0.13059834 0.13400808, -0.17712934 0.13109438 0.13400808, -0.17758045 0.1314939 0.13400835, -0.17811416 0.13177395 0.13400823, 0.21049958 0.11743858 0.14050713, 0.210427 0.11803688 0.14050761, 0.21049967 0.11743893 0.13400739, 0.21042714 0.1180371 0.13400751, 0.21021342 0.11860031 0.14050737, 0.21021335 0.11860055 0.13400751, 0.20987087 0.1190964 0.14050761, 0.20987096 0.11909661 0.13400719, 0.20941976 0.11949605 0.14050749, 0.2094198 0.11949641 0.13400739, 0.20888621 0.11977609 0.14050761, 0.20888627 0.11977637 0.13400751, 0.20830104 0.11992027 0.14050737, 0.20830095 0.11992069 0.13400751, 0.20769835 0.1199203 0.14050737, 0.2076982 0.11992066 0.13400751, 0.20711307 0.11977613 0.14050761, 0.20711306 0.11977649 0.13400739, 0.20657942 0.11949605 0.14050737, 0.20657949 0.11949645 0.13400719, 0.20612833 0.11909638 0.14050737, 0.20612836 0.11909662 0.13400739, 0.20578605 0.11860034 0.14050749, 0.20578596 0.11860065 0.13400739, 0.20557219 0.11803685 0.14050737, 0.20557225 0.11803713 0.13400751, 0.20549956 0.11743858 0.14050737, 0.20549962 0.11743894 0.13400739, 0.18149969 0.11743841 0.14050737, 0.18142697 0.11803675 0.14050728, 0.1814997 0.11743871 0.13400719, 0.18142699 0.11803706 0.13400739, 0.18121324 0.11860022 0.14050737, 0.18121326 0.11860049 0.13400751, 0.18087088 0.1190962 0.14050737, 0.18087083 0.11909658 0.13400739, 0.18041983 0.11949591 0.14050761, 0.18041982 0.1194963 0.13400739, 0.17988618 0.11977595 0.14050749, 0.1798861 0.11977617 0.13400751, 0.17930096 0.11992018 0.14050761, 0.17930102 0.11992055 0.13400751, 0.17869827 0.11992007 0.14050761, 0.17869833 0.11992036 0.13400751, 0.17811321 0.11977595 0.14050737, 0.17811318 0.1197762 0.13400751, 0.17757958 0.11949578 0.14050761, 0.17757954 0.11949603 0.13400763, 0.17712839 0.11909619 0.14050749, 0.17712836 0.1190964 0.13400751, 0.17678601 0.1186001 0.14050737, 0.17678595 0.11860046 0.13400751, 0.17657232 0.1180366 0.14050737, 0.17657229 0.11803696 0.13400751, 0.17649963 0.11743847 0.14050728, 0.17649968 0.1174387 0.13400751, 0.21049953 0.12943861 0.14050797, 0.21042691 0.13003685 0.1405082, 0.21049961 0.12943889 0.13400808, 0.2104269 0.1300372 0.13400808, 0.21021318 0.13060042 0.1405082, 0.21021317 0.13060078 0.13400808, 0.20987087 0.13109642 0.14050812, 0.20987085 0.13109678 0.13400778, 0.20941973 0.13149595 0.14050812, 0.20941968 0.13149637 0.1340079, 0.20888603 0.13177609 0.14050812, 0.20888618 0.13177633 0.13400835, 0.2083009 0.13192034 0.1405082, 0.20830095 0.13192055 0.13400823, 0.20769823 0.13192038 0.14050797, 0.20769826 0.13192056 0.13400823, 0.20711309 0.13177608 0.1405082, 0.20711309 0.13177644 0.13400808, 0.20657943 0.13149595 0.14050797, 0.20657937 0.13149635 0.13400808, 0.20612828 0.13109635 0.14050797, 0.20612828 0.13109674 0.13400808, 0.20578596 0.13060033 0.14050797, 0.2057859 0.13060069 0.1340079, 0.20557226 0.13003682 0.14050797, 0.20557217 0.13003717 0.1340079, 0.20549962 0.12943856 0.14050797, 0.20549965 0.12943892 0.13400808, 0.18149959 0.12943842 0.14050797, 0.18142703 0.13003677 0.14050797, 0.18149962 0.12943864 0.1340079, 0.18142681 0.13003704 0.13400808, 0.1812132 0.13060026 0.14050797, 0.18121307 0.13060059 0.13400835, 0.18087092 0.13109615 0.1405082, 0.18087085 0.13109662 0.13400808, 0.18041983 0.13149577 0.14050832, 0.18041977 0.13149613 0.13400823, 0.17988601 0.13177598 0.14050832, 0.17988612 0.13177633 0.13400808, 0.17930086 0.13192014 0.14050812, 0.17930093 0.1319204 0.13400823, 0.1786983 0.13192013 0.14050812, 0.17869826 0.13192038 0.13400823, 0.17811295 0.13177598 0.1405082, 0.17811297 0.13177632 0.13400835, 0.17757928 0.13149588 0.14050812, 0.1775793 0.13149624 0.13400808, 0.17712824 0.13109627 0.14050812, 0.17712829 0.13109659 0.13400808, 0.17678587 0.13060026 0.1405082, 0.17678584 0.1306005 0.13400808, 0.17657225 0.13003671 0.14050797, 0.17657216 0.13003699 0.13400823, 0.17649956 0.12943831 0.14050797, 0.17649956 0.12943864 0.1340079, 0.21599942 0.14743863 0.14050895, 0.2159996 0.11143865 0.14050713, 0.21599947 0.14743893 0.13400906, 0.21599966 0.1114389 0.13400704, 0.2139996 0.1094386 0.14050677, 0.17299967 0.10943834 0.14050698, 0.2139997 0.10943899 0.13400704, 0.17299962 0.10943866 0.13400695, 0.17099948 0.1474387 0.13400894, 0.17099974 0.11143854 0.13400704, 0.17099962 0.1474383 0.14050916, 0.17099971 0.11143836 0.14050698, 0.21399958 0.14943889 0.13400906, 0.17299946 0.14943863 0.13400906, 0.21399942 0.14943866 0.14050931, 0.17299947 0.14943828 0.14050916, 0.2102132 0.12827674 0.14050788, 0.20987082 0.12778071 0.14050773, 0.20941968 0.12738113 0.14050797, 0.20888618 0.12710106 0.14050773, 0.20830104 0.12695676 0.14050812, 0.20769829 0.12695681 0.14050797, 0.21042693 0.1288404 0.14050797, 0.21042706 0.11684024 0.14050737, 0.20711312 0.12710093 0.14050773, 0.21021326 0.11627677 0.14050737, 0.20657939 0.12738118 0.14050773, 0.20612827 0.12778082 0.14050773, 0.20987087 0.11578077 0.14050713, 0.20578596 0.12827674 0.14050788, 0.20941982 0.11538112 0.14050728, 0.20888615 0.11510102 0.14050728, 0.20830105 0.11495686 0.14050713, 0.20769829 0.11495674 0.14050728, 0.20711321 0.11510098 0.14050713, 0.20657948 0.11538105 0.14050713, 0.18142696 0.12884016 0.14050797, 0.2055722 0.1288403 0.14050797, 0.18121317 0.12827665 0.14050812, 0.18087089 0.12778068 0.14050797, 0.18041976 0.12738103 0.14050788, 0.17988607 0.12710088 0.14050773, 0.17930098 0.1269567 0.14050773, 0.17869826 0.12695663 0.14050773, 0.18142697 0.11684011 0.14050737, 0.20557219 0.11684029 0.14050737, 0.17811309 0.12710087 0.14050773, 0.18121333 0.11627662 0.14050737, 0.20578602 0.11627679 0.14050713, 0.1775794 0.12738089 0.14050788, 0.17712831 0.1277805 0.14050773, 0.18087082 0.11578058 0.14050728, 0.20612833 0.11578082 0.14050728, 0.17678601 0.12827654 0.14050788, 0.1804198 0.11538096 0.14050737, 0.17657226 0.12884007 0.14050797, 0.17712839 0.1157806 0.14050728, 0.17678593 0.11627659 0.14050737, 0.17657232 0.11684017 0.14050737, 0.17988615 0.11510094 0.14050737, 0.17930108 0.11495654 0.14050713, 0.17869836 0.11495654 0.14050728, 0.17811312 0.11510085 0.14050728, 0.1775794 0.1153809 0.14050737, 0.20987087 0.12778103 0.13400808, 0.20941964 0.12738135 0.13400778, 0.20888619 0.12710123 0.1340079, 0.21021318 0.12827706 0.1340079, 0.20830092 0.12695704 0.1340079, 0.20769829 0.1269571 0.13400799, 0.21042697 0.12884055 0.1340079, 0.21042709 0.11684057 0.13400719, 0.20711303 0.12710142 0.13400778, 0.21021345 0.11627698 0.13400739, 0.20657939 0.12738155 0.13400799, 0.20987087 0.11578104 0.13400719, 0.2061283 0.12778105 0.1340079, 0.2057859 0.12827709 0.1340079, 0.2094198 0.11538136 0.13400719, 0.20888615 0.11510134 0.13400719, 0.20830107 0.11495705 0.13400719, 0.20769843 0.11495696 0.13400719, 0.20711318 0.11510138 0.13400719, 0.20657952 0.11538133 0.13400719, 0.18142685 0.12884052 0.1340079, 0.20557229 0.1288406 0.1340079, 0.18121313 0.12827694 0.1340079, 0.18087086 0.12778091 0.13400778, 0.18041973 0.12738116 0.1340079, 0.17988607 0.12710118 0.1340079, 0.1793009 0.12695694 0.13400778, 0.17869824 0.12695688 0.1340079, 0.20557225 0.11684063 0.13400739, 0.18142697 0.11684036 0.13400739, 0.17811312 0.12710109 0.13400799, 0.20578596 0.11627701 0.13400719, 0.18121329 0.1162769 0.13400719, 0.17757933 0.12738122 0.1340079, 0.20612839 0.11578098 0.13400719, 0.18087099 0.11578086 0.13400719, 0.17712831 0.1277808 0.1340079, 0.1804198 0.11538123 0.13400739, 0.17678608 0.12827684 0.1340079, 0.17657225 0.12884034 0.1340079, 0.17712833 0.11578086 0.13400719, 0.17678601 0.11627688 0.13400739, 0.17657231 0.11684033 0.13400739, 0.17988612 0.11510116 0.13400719, 0.17930105 0.11495691 0.13400704, 0.17869836 0.1149569 0.13400704, 0.17811307 0.1151012 0.13400719, 0.17757946 0.1153812 0.13400719, 0.11587927 0.056105707 0.29797378, 0.11535074 0.055637959 0.29890862, 0.11629663 0.056013558 0.2984027, 0.12571327 0.045503121 0.30080202, 0.12395756 0.044137776 0.30353171, 0.12405915 0.042732798 0.30289891, 0.081072271 0.043473057 0.31383753, 0.079657659 0.044150602 0.31587031, 0.081314519 0.044282734 0.31560633, 0.11579698 0.056477964 0.29691344, 0.11817705 0.056714609 0.29727247, 0.079463497 0.043344781 0.31409422, 0.11685885 0.0570576 0.29607034, 0.11730903 0.057303075 0.29569328, 0.11557729 0.057116665 0.29479375, 0.087473974 0.045480162 0.31769109, 0.087368757 0.045129597 0.31991783, 0.088481218 0.045293819 0.31958959, 0.11784828 0.04959251 0.30777094, 0.11514704 0.048064318 0.31082645, 0.11629787 0.046511173 0.31115165, 0.085833937 0.045202665 0.31654739, 0.086335108 0.045288917 0.31844077, 0.11907281 0.048081007 0.30801305, 0.089210302 0.045546371 0.31876826, 0.10370593 0.038300507 0.32175881, 0.099672556 0.037291992 0.32377526, 0.099936321 0.035780746 0.32359934, 0.089584395 0.045821719 0.31700829, 0.090595335 0.045969632 0.31707969, 0.089934736 0.045857873 0.31523743, 0.090677664 0.045658309 0.31886065, 0.10296855 0.049436614 0.30978113, 0.10369205 0.049140856 0.31189817, 0.10457997 0.049482848 0.3112148, 0.10492995 0.049831323 0.31020191, 0.099361703 0.047335651 0.30611539, 0.098150358 0.04757107 0.30903244, 0.10014953 0.048260413 0.30765408, 0.10400973 0.036799029 0.32156333, 0.097420394 0.046666212 0.30745399, 0.10220468 0.049076416 0.31086877, 0.12035504 0.048901271 0.3063733, 0.12007779 0.04639807 0.30799037, 0.12138799 0.047236186 0.30631489, 0.082958482 0.044443853 0.31528446, 0.081609629 0.044730034 0.3174921, 0.10110964 0.048848178 0.30925888, 0.10462695 0.050113074 0.30842906, 0.083311602 0.044896908 0.31715894, 0.10629843 0.050195187 0.30979067, 0.09813673 0.042078894 0.32279268, 0.094759323 0.039525799 0.32511705, 0.0988236 0.040362492 0.32344458, 0.10556044 0.050433509 0.30815512, 0.094180346 0.041264404 0.32442099, 0.10433953 0.050154701 0.30664709, 0.11390822 0.055741183 0.29717675, 0.11363558 0.055289023 0.29844809, 0.096543968 0.043982957 0.3047601, 0.095250443 0.043580588 0.3055647, 0.095566139 0.045046479 0.30682749, 0.09829402 0.042950191 0.3024641, 0.095143676 0.04190734 0.30454919, 0.096878022 0.045454681 0.3060115, 0.11211225 0.054828323 0.29730353, 0.11486311 0.056649711 0.29536057, 0.10597625 0.037361082 0.32043958, 0.10419491 0.035319556 0.32116175, 0.11398135 0.056587622 0.29378599, 0.10617302 0.035884853 0.32003146, 0.086389333 0.045255717 0.3161833, 0.07923013 0.040780619 0.31116271, 0.076867186 0.038986884 0.3103874, 0.076101154 0.040615313 0.31149313, 0.12262361 0.048096582 0.30459449, 0.1219105 0.046111085 0.3061437, 0.12315957 0.046980731 0.30440497, 0.076145753 0.042039119 0.31284001, 0.080743968 0.03924378 0.30987397, 0.07931909 0.042206839 0.31250444, 0.085394844 0.044739209 0.31469396, 0.10337771 0.039509039 0.32176331, 0.099387437 0.038511176 0.32375804, 0.087406024 0.045317024 0.31527951, 0.11092746 0.05118838 0.30834779, 0.10826294 0.049902361 0.31091884, 0.10964073 0.049112637 0.31206837, 0.11240913 0.05044876 0.30939716, 0.088439867 0.045573041 0.31554917, 0.12540059 0.046922296 0.30132431, 0.089355737 0.045371965 0.31342867, 0.10810034 0.036484551 0.31883249, 0.10817032 0.035064321 0.31823027, 0.10148937 0.048984379 0.30872887, 0.083714545 0.044971388 0.31907585, 0.12365521 0.045565151 0.30403778, 0.1021096 0.049190972 0.30753428, 0.116451 0.050874714 0.30727381, 0.08089228 0.042332251 0.31225348, 0.10311336 0.049627941 0.30744225, 0.11383401 0.049393941 0.31023386, 0.10326937 0.049522445 0.30513105, 0.11225879 0.055011194 0.29667988, 0.11077708 0.054036498 0.29610601, 0.098776318 0.046109211 0.30470273, 0.082668692 0.043629531 0.31352496, 0.11238857 0.055284332 0.29535216, 0.11321005 0.055883396 0.2949357, 0.11258237 0.055735957 0.29270867, 0.11909637 0.050390989 0.30617493, 0.086173952 0.044722378 0.3140904, 0.085034385 0.04391627 0.31295151, 0.10565339 0.038857047 0.32064638, 0.097352937 0.043594789 0.3218281, 0.088144809 0.04503382 0.31346774, 0.088880509 0.044530936 0.3117229, 0.12156427 0.049743395 0.30468962, 0.093519717 0.042805772 0.32340524, 0.12488775 0.048324768 0.30171797, 0.1006663 0.048358768 0.30682045, 0.10789216 0.037957259 0.31924793, 0.10944568 0.051584266 0.30712694, 0.10222149 0.048983373 0.30557141, 0.10688522 0.050348405 0.30959767, 0.10272887 0.041338895 0.32149237, 0.10239117 0.048560951 0.30366582, 0.11095297 0.054196212 0.29514936, 0.10968144 0.052944269 0.29490224, 0.11493509 0.051877853 0.30653995, 0.11185654 0.055039473 0.293464, 0.11143439 0.054594465 0.29160324, 0.10530435 0.040059593 0.32066268, 0.086390279 0.044014484 0.31238532, 0.1243335 0.049426138 0.30193633, 0.084766611 0.042765785 0.31138709, 0.098415703 0.044628426 0.30346963, 0.080781437 0.040904302 0.31091505, 0.087109119 0.043820143 0.31164521, 0.088301495 0.04433025 0.31175429, 0.088527441 0.043366775 0.31018561, 0.082453191 0.042485241 0.31194764, 0.10040431 0.047646906 0.30512354, 0.11766034 0.051648278 0.30572695, 0.096502602 0.044851661 0.32058728, 0.092802979 0.044090189 0.32210964, 0.10755046 0.039447259 0.31946635, 0.10084912 0.047555897 0.30417681, 0.10190102 0.048265375 0.30388719, 0.10173853 0.047307465 0.30230731, 0.12027362 0.051210731 0.30453604, 0.10802097 0.05162115 0.3057811, 0.11025275 0.053398933 0.29362336, 0.10886722 0.051593617 0.29373792, 0.110889 0.037446138 0.31691, 0.11186728 0.036365185 0.31562942, 0.11035578 0.053356677 0.29257959, 0.11335851 0.052563772 0.30559835, 0.10193814 0.043029517 0.32089236, 0.11110769 0.05422619 0.29196957, 0.11058125 0.053207215 0.29051203, 0.085809454 0.042654119 0.31079233, 0.084601596 0.041331634 0.31006077, 0.12323761 0.051044695 0.30208817, 0.087681532 0.042956598 0.31018725, 0.08831013 0.041924156 0.30887616, 0.09955585 0.046159342 0.30378422, 0.10461429 0.04187768 0.32041499, 0.11610233 0.052624471 0.30504704, 0.10102754 0.04675898 0.30258566, 0.10133663 0.045809899 0.30110797, 0.10926504 0.05174851 0.29261011, 0.10718113 0.040643461 0.31949511, 0.10836582 0.050036263 0.29265791, 0.11880101 0.052442331 0.30413944, 0.11011307 0.052554037 0.29099968, 0.082320616 0.041055024 0.31061369, 0.084545866 0.039669022 0.30902383, 0.11005592 0.051627364 0.28947705, 0.10670789 0.051297847 0.30436158, 0.085128345 0.041249119 0.30979413, 0.095618337 0.045801401 0.31911772, 0.086166367 0.040923886 0.30914226, 0.08823663 0.040258802 0.30784482, 0.092057586 0.045068357 0.32058316, 0.11066423 0.038913097 0.31733695, 0.086988315 0.041536454 0.30921951, 0.11178198 0.052905954 0.30448437, 0.098825425 0.044629168 0.30303648, 0.12190244 0.052477486 0.30200347, 0.099617489 0.044466455 0.30205968, 0.10103625 0.044515755 0.31998673, 0.10120092 0.044125944 0.30011329, 0.10029873 0.045212708 0.30187002, 0.10859625 0.050093818 0.29211134, 0.1081965 0.048332114 0.29170421, 0.11448184 0.053282347 0.30416116, 0.10902232 0.05003931 0.2909179, 0.10987857 0.049915574 0.2885384, 0.10945949 0.050884806 0.29052979, 0.1172031 0.053390995 0.30351481, 0.10377367 0.04355406 0.31984368, 0.10645116 0.042449269 0.31927243, 0.10555697 0.050626639 0.30292389, 0.11026607 0.052891221 0.30324158, 0.11029548 0.040393919 0.31757382, 0.094733812 0.046407484 0.31747672, 0.091312125 0.045703199 0.31888476, 0.11286147 0.053596418 0.30310392, 0.077643529 0.031466901 0.32886392, 0.072953023 0.031384502 0.32902846, 0.072952911 0.029954318 0.32844642, 0.077652976 0.030036626 0.32828155, 0.1000575 0.045740627 0.3188099, 0.077615641 0.032969236 0.32921988, 0.072952934 0.032887407 0.32938337, 0.12037925 0.053669728 0.30168542, 0.10989694 0.041579925 0.31762275, 0.11554129 0.054020163 0.30268654, 0.07757017 0.03450799 0.32934064, 0.072952867 0.034427077 0.32950276, 0.10461253 0.049633134 0.3015224, 0.10886889 0.052520473 0.30191743, 0.10281463 0.045023866 0.31897071, 0.07752087 0.035757035 0.32926431, 0.10556169 0.044110358 0.31873158, 0.11130337 0.05355493 0.3019149, 0.072952971 0.036328048 0.32932049, 0.082305238 0.031713277 0.32837123, 0.082323864 0.030283716 0.32778808, 0.1187263 0.054575499 0.30114648, 0.093883447 0.04664664 0.31572643, 0.082249977 0.0332141 0.32873026, 0.077423386 0.037666976 0.32883328, 0.11387957 0.054305542 0.30168644, 0.099039607 0.046656922 0.31740737, 0.072952896 0.038160034 0.32878011, 0.10391062 0.048355777 0.30021146, 0.084616356 0.031897709 0.32800275, 0.086937293 0.030693531 0.32696834, 0.082158893 0.034750551 0.32885566, 0.1076443 0.051807411 0.30056298, 0.10910907 0.043365676 0.31744027, 0.10986736 0.05315908 0.30064055, 0.10177389 0.046231061 0.31782922, 0.077304706 0.039455086 0.32803839, 0.072953001 0.039855659 0.32790133, 0.11700732 0.055160113 0.30040735, 0.084547259 0.033397481 0.32836393, 0.11228172 0.054236151 0.30055305, 0.10454687 0.045562912 0.31789306, 0.082060635 0.035997063 0.32878423, 0.10347842 0.046843629 0.29904115, 0.093099758 0.046509366 0.3139348, 0.10383675 0.045423441 0.29751936, 0.10663939 0.050779648 0.29922995, 0.086909458 0.032122314 0.32755345, 0.084433883 0.034931995 0.32849306, 0.098021768 0.047229599 0.31583288, 0.11528838 0.055400964 0.29949632, 0.077169225 0.041052483 0.32691032, 0.072952881 0.041353352 0.32671624, 0.10860865 0.052424449 0.29932943, 0.10814899 0.045002352 0.31694803, 0.086826824 0.033620887 0.32791728, 0.11080912 0.053814832 0.29932937, 0.10069158 0.047128942 0.31646374, 0.1058925 0.04947713 0.29796961, 0.081866421 0.037901908 0.32836369, 0.1034458 0.046751242 0.3167893, 0.084311396 0.036176573 0.32842547, 0.077022299 0.042398062 0.32549235, 0.1075758 0.051378977 0.29803225, 0.072952963 0.042598341 0.32526803, 0.086691111 0.035153359 0.3280507, 0.10951845 0.053057812 0.29806301, 0.092412829 0.046001408 0.31217042, 0.10543275 0.047949132 0.29683065, 0.10617605 0.046829883 0.2947073, 0.097043052 0.047436547 0.31414691, 0.090307951 0.032534346 0.32672983, 0.091464818 0.031263676 0.32582837, 0.099609166 0.047683287 0.31492606, 0.081629783 0.039683726 0.32758147, 0.10680836 0.050062787 0.29679859, 0.084069014 0.038077641 0.32801256, 0.086544529 0.036395397 0.32798809, 0.10845916 0.051993925 0.29680249, 0.10705376 0.046427198 0.31616488, 0.076869398 0.04344013 0.32383868, 0.10633571 0.048526883 0.29567599, 0.11843179 0.040746469 0.31031185, 0.11532503 0.037791546 0.31277755, 0.11852245 0.039334729 0.30969268, 0.072952926 0.043545395 0.32360965, 0.10767202 0.050664227 0.295596, 0.11524087 0.039206136 0.313391, 0.10230072 0.047629695 0.31546271, 0.09020514 0.03403037 0.32709846, 0.091849163 0.045141995 0.31050125, 0.10718736 0.049119953 0.29449013, 0.081359699 0.041274004 0.32646757, 0.096141025 0.047269825 0.31241471, 0.083773896 0.039854717 0.32723957, 0.086254552 0.038291812 0.32758433, 0.11816235 0.042193785 0.31077772, 0.1149902 0.040662877 0.3138386, 0.090868764 0.032611694 0.32657522, 0.098568469 0.047872469 0.31327549, 0.0925107 0.033350762 0.3262307, 0.090036467 0.035558868 0.32724029, 0.093646333 0.033034898 0.32572907, 0.095878527 0.031990763 0.32437497, 0.07671655 0.044138134 0.32201335, 0.072952971 0.044159956 0.32180119, 0.094378963 0.033158019 0.32548261, 0.095832944 0.033417072 0.32496518, 0.095697299 0.034907993 0.32534382, 0.092886597 0.035199765 0.3263846, 0.081066713 0.04261177 0.32506484, 0.10586523 0.04758561 0.31512138, 0.095474899 0.036427908 0.32550269, 0.10115562 0.048164342 0.31396437, 0.092371181 0.038148262 0.32624564, 0.089493603 0.038684353 0.32679921, 0.089853987 0.036796737 0.32718593, 0.095234334 0.037656508 0.32546705, 0.091430202 0.043964293 0.30899113, 0.091904871 0.039971892 0.32569835, 0.089054331 0.040445428 0.32605833, 0.083437182 0.041439753 0.32613608, 0.09135665 0.041632716 0.32481283, 0.085901439 0.040063165 0.3268227, 0.11772043 0.043642417 0.31107897, 0.11457916 0.04212641 0.31410977, 0.076569661 0.044465683 0.32008618, 0.11134128 0.037613485 0.31657556, 0.095350377 0.046735935 0.310702, 0.072952837 0.044419475 0.31990919, 0.11261462 0.038611572 0.31571305, 0.097609356 0.047689326 0.31157571, 0.11354652 0.038479462 0.31484446, 0.11411835 0.038718447 0.31436661, 0.11269858 0.040501278 0.31578529, 0.080762096 0.043645702 0.32342714, 0.10462929 0.048432644 0.31385741, 0.083071604 0.04277179 0.32474515, 0.11167072 0.043312769 0.31592038, 0.11413489 0.043294124 0.31419593, 0.11325662 0.045043334 0.31408638, 0.11074102 0.045012616 0.31562108, 0.10005462 0.048334837 0.31235102, 0.11218643 0.046635553 0.31368306, 0.085498497 0.041641705 0.32573241, 0.10964796 0.046527345 0.31502679, 0.076434225 0.0444104 0.31813142, 0.11724238 0.044794034 0.31119728, 0.091172308 0.042513367 0.3076984, 0.091780543 0.041007366 0.30634826, 0.072952926 0.044314325 0.31800213, 0.1259883 0.045734949 0.30033857, 0.12636432 0.04456681 0.29923233, 0.12676269 0.046565067 0.29898596, 0.12834157 0.04647591 0.29541531, 0.12816416 0.048253857 0.29622188, 0.12134333 0.042393658 0.3070187, 0.12143967 0.040985253 0.30639297, 0.080457248 0.044335984 0.32161793, 0.12509476 0.051384237 0.29978368, 0.094701521 0.045855276 0.30907533, 0.12384278 0.052889995 0.29987174, 0.12563753 0.053303868 0.29757109, 0.10339332 0.048936028 0.31242138, 0.12423877 0.054676708 0.29760638, 0.12237057 0.054177091 0.29973319, 0.082691729 0.043799669 0.3231197, 0.092661634 0.036684759 0.32642269, 0.096768744 0.047141168 0.30989164, 0.085061133 0.042966742 0.32435557, 0.089667454 0.042542472 0.32432646, 0.088009641 0.043324295 0.32364082, 0.088553302 0.042012099 0.324992, 0.099039689 0.04813464 0.31068602, 0.090747356 0.043066766 0.32362303, 0.092130288 0.042936116 0.32353958, 0.0763155 0.043973979 0.31622377, 0.12105657 0.043831199 0.30750406, 0.11224966 0.041926395 0.31594315, 0.072952896 0.043848693 0.31614974, 0.080164328 0.044655934 0.31970626, 0.10776517 0.04711993 0.31517518, 0.082311809 0.044483755 0.32132232, 0.10843316 0.047799274 0.31416109, 0.12268872 0.043254182 0.3052983, 0.10970493 0.047904573 0.31360641, 0.11096549 0.048009548 0.31300157, 0.12592329 0.047448225 0.30042085, 0.094219424 0.04466163 0.30759689, 0.1257783 0.048799824 0.3002871, 0.10009725 0.034294982 0.32320994, 0.10015132 0.032870494 0.32261643, 0.1262058 0.049041659 0.29956093, 0.096078709 0.04624882 0.30828837, 0.084606484 0.043987319 0.32274458, 0.12670135 0.049367078 0.29867145, 0.12763883 0.050029472 0.29686546, 0.12646015 0.050729018 0.29840472, 0.12678576 0.051734701 0.29732105, 0.076218203 0.04317325 0.31443727, 0.072952956 0.04303962 0.3144199, 0.12057998 0.054443363 0.30053374, 0.079894245 0.044593237 0.31776574, 0.12058619 0.045263857 0.3078374, 0.12073481 0.055195786 0.29937357, 0.12170252 0.055500135 0.29842123, 0.12264267 0.05580049 0.29742539, 0.12091095 0.056632139 0.29703498, 0.089071795 0.043776464 0.32292435, 0.087444209 0.04433129 0.32205686, 0.081946447 0.044797957 0.31942222, 0.09010075 0.044218618 0.32217464, 0.091446906 0.044155892 0.3221657, 0.12239398 0.044686839 0.30579385, 0.10652477 0.048190687 0.31409922, 0.093922511 0.04320113 0.30632341, 0.084151864 0.044664074 0.32096171, 0.10714373 0.048779286 0.31305653, 0.072952941 0.041916192 0.31287542, 0.10839541 0.048947349 0.31258634, 0.11888289 0.05525317 0.29997948, 0.11899814 0.055907033 0.29880667, 0.11996548 0.056272209 0.29794213, 0.11910994 0.057139475 0.29645011, 0.088458687 0.04469426 0.32130429, 0.086878777 0.044994712 0.32030103, 0.090743333 0.045059349 0.32057443, 0.10524748 0.048940651 0.3128151, 0.10704716 0.049668498 0.31135935, 0.11713566 0.055734377 0.29923233, 0.072952911 0.038901091 0.31055906, 0.07295303 0.040519599 0.3115727, 0.10425697 0.033897094 0.32056388, 0.088476747 0.045125201 0.32017115, 0.10480347 0.049333565 0.31175715, -0.091312811 0.046140365 0.31636894, -0.093346044 0.046565212 0.31551984, -0.092776313 0.046204753 0.31744972, -0.078812547 0.03151197 0.32877141, -0.082305044 0.031712338 0.32837114, -0.0823237 0.030282695 0.32778805, -0.09059535 0.045968536 0.31707951, -0.089934722 0.0458568 0.31523743, -0.091760203 0.045857295 0.31846046, -0.10757589 0.051377483 0.29803213, -0.10845933 0.051992659 0.29680249, -0.10951848 0.053056441 0.29806301, -0.07718458 0.042456202 0.32541129, -0.078036755 0.04243733 0.32541209, -0.077337563 0.041126952 0.32683748, -0.10860893 0.052423004 0.29932943, -0.076896787 0.041146003 0.32683748, -0.077845827 0.043477669 0.32376155, -0.085901372 0.040062189 0.3268227, -0.090561002 0.038832985 0.3265, -0.08625453 0.038290642 0.32758424, -0.07675907 0.042467769 0.32540601, -0.075577959 0.041201442 0.32682723, -0.090093493 0.040590048 0.32576698, -0.075486235 0.04249784 0.32538891, -0.10755032 0.039445881 0.3194662, -0.11118226 0.04072376 0.31691125, -0.11155976 0.039246269 0.31666768, -0.072952919 0.041352436 0.32671624, -0.072952889 0.042597372 0.32526803, -0.10789202 0.037955862 0.31924781, -0.092573754 0.045309678 0.31016356, -0.095350474 0.04673481 0.31070203, -0.093159169 0.04617412 0.3118228, -0.10673228 0.051322445 0.30405185, -0.1072683 0.051594898 0.303765, -0.10746747 0.05144272 0.30576786, -0.10609832 0.050913591 0.30234739, -0.094701603 0.045854088 0.30907518, -0.10764449 0.051806074 0.30056298, -0.10986748 0.053157743 0.30064043, -0.10886907 0.052519109 0.30191755, -0.084068976 0.038076587 0.32801265, -0.086544409 0.03639441 0.32798821, -0.10898483 0.045313422 0.31632331, -0.11218636 0.046634056 0.31368294, -0.11325663 0.045041952 0.31408638, -0.10556994 0.05073373 0.30444726, -0.10996761 0.04368525 0.31679872, -0.10528947 0.05059763 0.30550119, -0.10595132 0.050702654 0.30724782, -0.084311172 0.036175612 0.32842547, -0.10433947 0.050153375 0.30664724, -0.082060546 0.035995916 0.32878432, -0.084433615 0.034930915 0.32849318, -0.10326949 0.049521033 0.30513126, -0.10597625 0.037359703 0.32043973, -0.1081004 0.036483236 0.31883267, -0.093232468 0.046520423 0.31365278, -0.093872353 0.046688296 0.31357485, -0.082158908 0.034749649 0.32885566, -0.10617307 0.035883505 0.32003149, -0.09392257 0.043199897 0.30632338, -0.09514381 0.041906085 0.30454919, -0.095250443 0.043579388 0.3055647, -0.095566072 0.045045223 0.30682737, -0.094219476 0.044660423 0.30759674, -0.091922551 0.046151295 0.31360939, -0.091780499 0.041006073 0.30634826, -0.10718113 0.040642243 0.31949511, -0.11077421 0.041906442 0.31696746, -0.088379428 0.044461381 0.32179472, -0.092803009 0.044088971 0.32210955, -0.088981226 0.043459445 0.32336795, -0.091280192 0.046097178 0.31449896, -0.089355804 0.045371003 0.31342867, -0.10718752 0.049118683 0.29449013, -0.10873166 0.05034706 0.29203397, -0.10923833 0.051908944 0.29310501, -0.077025741 0.043480176 0.32375571, -0.10819654 0.048330668 0.29170421, -0.092057429 0.045067213 0.32058316, -0.10617609 0.046828497 0.29470745, -0.10767217 0.050663002 0.29559603, -0.078777835 0.033014186 0.32912797, -0.077654794 0.044174302 0.32193908, -0.10419474 0.035318222 0.3211616, -0.10425693 0.033895668 0.32056376, -0.076616347 0.043483552 0.32374832, -0.1102661 0.05288985 0.30324158, -0.10860309 0.051929839 0.30516118, -0.07539168 0.043491095 0.32372925, -0.082249723 0.033213153 0.3287302, -0.072952926 0.043544486 0.32360956, -0.085498467 0.041640669 0.32573226, -0.089560077 0.042152196 0.32470959, -0.10680832 0.050061539 0.29679826, -0.10530744 0.050428387 0.30268008, -0.10513798 0.04991173 0.30096278, -0.10390679 0.049734119 0.30406803, -0.10239115 0.048559681 0.30366582, -0.092138827 0.04412825 0.30866092, -0.092231721 0.045841556 0.31185037, -0.10663952 0.050778404 0.29922977, -0.083773851 0.03985367 0.32723957, -0.10565323 0.038855579 0.32064646, -0.090344526 0.045439422 0.3126542, -0.088880599 0.044529889 0.31172299, -0.081866287 0.037900824 0.3283636, -0.076867387 0.044161461 0.32193303, -0.1078635 0.046728592 0.31556004, -0.11096558 0.048008222 0.31300145, -0.077471256 0.044500403 0.32001486, -0.078720868 0.034552611 0.3292498, -0.0764741 0.044156935 0.32192573, -0.10400957 0.036797851 0.32156318, -0.075297609 0.044145405 0.32191026, -0.072952867 0.044158921 0.32180122, -0.087777555 0.045119684 0.32004881, -0.10645122 0.042447969 0.31927258, -0.10410872 0.049298584 0.30181882, -0.10442466 0.0486283 0.29966423, -0.091312014 0.045701999 0.31888476, -0.10330181 0.04864905 0.30198905, -0.085061222 0.04296568 0.32435521, -0.10272263 0.048630483 0.3031542, -0.10173856 0.047306169 0.30230731, -0.091225095 0.044907711 0.31059736, -0.10530429 0.040058248 0.32066271, -0.090310246 0.044411175 0.31046146, -0.078659378 0.035801068 0.32917398, -0.10633567 0.048525441 0.29567578, -0.091870926 0.042674951 0.30737275, -0.089373782 0.044527501 0.3113578, -0.088527329 0.043365628 0.31018582, -0.076715425 0.044474475 0.32001221, -0.10589266 0.049475811 0.29796979, -0.077302098 0.044443779 0.31806263, -0.08343707 0.04143871 0.32613617, -0.10664685 0.047876343 0.31453755, -0.1096407 0.049111187 0.31206852, -0.076337591 0.044463329 0.32000694, -0.081629634 0.039682675 0.32758132, -0.10370603 0.038299263 0.32175887, -0.075179011 0.044450611 0.31936243, -0.074079141 0.044420879 0.31997913, -0.087198704 0.045409009 0.31819835, -0.10113817 0.03453638 0.32272491, -0.10015115 0.032869127 0.32261631, -0.073703423 0.044418886 0.31995854, -0.084606573 0.04398635 0.3227447, -0.072952926 0.044418529 0.31990907, -0.072952896 0.044313416 0.31800213, -0.1055617 0.044109095 0.31873158, -0.10357833 0.047952928 0.30019578, -0.10398517 0.04711229 0.29850116, -0.10223451 0.047296301 0.30150887, -0.10133657 0.045808513 0.30110785, -0.091059908 0.043624032 0.30885047, -0.089256972 0.043246806 0.30960479, -0.088309914 0.041923024 0.30887619, -0.078537717 0.037710018 0.32874495, -0.076192901 0.044343527 0.31774989, -0.077153847 0.044006098 0.31615761, -0.10461426 0.041876342 0.32041499, -0.083071664 0.042770728 0.32474524, -0.074031696 0.044278897 0.31774476, -0.10337767 0.039507635 0.32176352, -0.081359617 0.041273084 0.32646757, -0.10359641 0.046756689 0.29878053, -0.086665288 0.045318175 0.31631437, -0.10543278 0.047947876 0.29683056, -0.10383676 0.045422047 0.29751948, -0.1027935 0.045882083 0.29922679, -0.10120098 0.044124592 0.30011335, -0.10538143 0.048712399 0.31329542, -0.10228834 0.046099048 0.30009517, -0.08415179 0.044663023 0.32096189, -0.10826308 0.049901076 0.31091896, -0.091355667 0.042399723 0.30749142, -0.10097112 0.036020596 0.32311735, -0.090311766 0.041689482 0.30760941, -0.088236652 0.040257677 0.30784461, -0.078389525 0.039497115 0.32795256, -0.089585125 0.042015672 0.30825919, -0.10454688 0.045561515 0.31789327, -0.076618075 0.0439189 0.3160114, -0.077032156 0.043204568 0.31437284, -0.082691684 0.043798644 0.32311988, -0.075772658 0.044060882 0.31659642, -0.075570315 0.04386735 0.31603259, -0.081066675 0.04261085 0.32506484, -0.10377367 0.043552753 0.31984389, -0.074681535 0.04361818 0.31549525, -0.086197712 0.044850729 0.31446877, -0.076941699 0.042069726 0.31277695, -0.072952822 0.04191523 0.31287542, -0.072952844 0.043038622 0.31442001, -0.1027288 0.041337594 0.32149228, -0.073476061 0.043806866 0.31603006, -0.072952867 0.043847784 0.31614974, -0.08371456 0.044970285 0.31907576, -0.10069729 0.037529606 0.32329804, -0.082311764 0.044482905 0.32132241, -0.10411617 0.049204767 0.31188148, -0.10688533 0.050347034 0.30959755, -0.072952785 0.038900036 0.31055906, -0.076867238 0.03898599 0.31038755, -0.072952837 0.040518716 0.31157261, -0.10344587 0.046749953 0.3167893, -0.12625813 0.045966454 0.29987228, -0.12816417 0.048252285 0.29622188, -0.12834151 0.046474367 0.29541528, -0.12636454 0.044565242 0.29923216, -0.078220285 0.041093215 0.32682723, -0.080761924 0.043644726 0.32342741, -0.12594241 0.047383029 0.30040014, -0.12763892 0.050028 0.29686534, -0.10040113 0.038746379 0.32328555, -0.085814118 0.044024702 0.31273296, -0.12542427 0.048780877 0.3008028, -0.12678573 0.051733024 0.29732105, -0.083311692 0.044895872 0.31715867, -0.10281462 0.045022737 0.31897089, -0.10193822 0.043028098 0.32089236, -0.12486418 0.049877487 0.30103073, -0.12395768 0.044136245 0.30353171, -0.12405905 0.042731315 0.30289891, -0.081946351 0.044796992 0.31942227, -0.10289958 0.049334601 0.31034976, -0.12365533 0.045563515 0.3040379, -0.1055605 0.050432228 0.30815527, -0.080457389 0.044334974 0.32161805, -0.12375717 0.05148631 0.30120191, -0.12563777 0.053302281 0.29757142, -0.10230082 0.047628447 0.3154625, -0.085528836 0.04287165 0.31117323, -0.12268871 0.043252647 0.30529827, -0.12143965 0.040983718 0.30639297, -0.082958549 0.044442877 0.31528446, -0.12315965 0.046979159 0.3044048, -0.081609569 0.044729076 0.3174921, -0.12240818 0.052907381 0.30114064, -0.12264295 0.055799007 0.29742551, -0.12423883 0.054675192 0.29760638, -0.099815808 0.040592462 0.32298225, -0.10177384 0.046229824 0.31782922, -0.12239395 0.044685159 0.30579361, -0.080164194 0.04465488 0.31970635, -0.10103626 0.044514555 0.31998673, -0.10177821 0.049096812 0.30875939, -0.085353449 0.041436043 0.3098501, -0.08454591 0.039668057 0.30902356, -0.12262365 0.048095118 0.30459449, -0.12134346 0.042392239 0.30701858, -0.08266858 0.043628592 0.31352478, -0.12191053 0.04610962 0.30614358, -0.10115573 0.048163138 0.31396413, -0.0813144 0.044281743 0.31560636, -0.12086914 0.054086193 0.30084974, -0.099102363 0.042302638 0.32234296, -0.12105657 0.043829635 0.30750424, -0.079894215 0.044592202 0.31776574, -0.10069149 0.047127657 0.31646374, -0.082453214 0.042484269 0.31194764, -0.12156434 0.04974173 0.3046895, -0.12138799 0.047234729 0.30631489, -0.10005753 0.045739353 0.31881014, -0.11919928 0.05497754 0.30033994, -0.12091114 0.056630567 0.29703498, -0.0810721 0.043471992 0.31383759, -0.07965757 0.044149462 0.31587052, -0.10079548 0.048500624 0.3071714, -0.1205862 0.045262322 0.30783731, -0.082320586 0.041054174 0.31061378, -0.080743879 0.039242707 0.30987397, -0.1000545 0.048333466 0.31235117, -0.11918662 0.041147083 0.30950776, -0.11852229 0.039333288 0.30969253, -0.099609181 0.047682043 0.31492594, -0.12027358 0.05120917 0.30453596, -0.080892265 0.042331364 0.31225362, -0.079463437 0.043343876 0.3140941, -0.12035501 0.048899822 0.3063733, -0.12007788 0.046396572 0.30799043, -0.098288864 0.04381175 0.32139179, -0.11746258 0.055546917 0.29963085, -0.11911011 0.05713791 0.29645023, -0.080781356 0.040903263 0.31091523, -0.091427878 0.032690275 0.32641578, -0.09583284 0.033415876 0.32496506, -0.095878415 0.031989627 0.32437477, -0.091464624 0.031262539 0.32582837, -0.079319105 0.04220584 0.31250456, -0.11891273 0.042592168 0.30997872, -0.099039599 0.046655726 0.31740737, -0.11880103 0.052440822 0.30413923, -0.09998896 0.047568828 0.30564699, -0.079230152 0.040779628 0.31116241, -0.099039882 0.048133347 0.31068602, -0.11909646 0.050389685 0.30617481, -0.076885946 0.040645227 0.31143126, -0.11907291 0.048079487 0.30801299, -0.091318443 0.034185547 0.32678625, -0.11881141 0.040945228 0.30991167, -0.1184632 0.04403675 0.31028765, -0.095697224 0.034906738 0.32534406, -0.11759061 0.040830415 0.31127432, -0.098568507 0.047871232 0.31327549, -0.11572596 0.055772897 0.29874989, -0.11687006 0.039960869 0.31187946, -0.11532494 0.037790112 0.31277779, -0.11633436 0.039705735 0.31238943, -0.11524078 0.039204825 0.313391, -0.11499012 0.040661447 0.31383842, -0.11730923 0.057301644 0.29569349, -0.11680938 0.042334151 0.3121182, -0.097405776 0.045061003 0.32016608, -0.11720321 0.053389493 0.30351481, -0.11457924 0.042125128 0.31410959, -0.098021843 0.047228407 0.31583288, -0.11797742 0.045184013 0.31041446, -0.11567527 0.045098141 0.31234828, -0.11701725 0.046892948 0.31038553, -0.11413489 0.043292791 0.31419584, -0.11464953 0.046754982 0.31213444, -0.099389434 0.046337128 0.30424464, -0.11584735 0.048436061 0.31008032, -0.11766044 0.051646709 0.30572695, -0.11784824 0.049591038 0.30777103, -0.11344327 0.04821936 0.3116414, -0.10061905 0.034413926 0.32296985, -0.11405599 0.055646155 0.29773119, -0.091138862 0.035712387 0.32693091, -0.095474824 0.036426567 0.32550281, -0.11557744 0.057115246 0.29479396, -0.099005297 0.034550726 0.323829, -0.098150358 0.047569882 0.30903244, -0.09798415 0.033836164 0.32412466, -0.097609431 0.047688231 0.31157556, -0.097271211 0.033691868 0.32441324, -0.11554135 0.054018606 0.30268666, -0.098252296 0.036190905 0.32440025, -0.096487492 0.04600279 0.3187128, -0.097598195 0.039113831 0.32431275, -0.095234424 0.037655227 0.3254672, -0.094759226 0.039524525 0.32511711, -0.1161024 0.052623082 0.30504721, -0.097006381 0.040914435 0.32381195, -0.094180271 0.041263223 0.32442099, -0.09704309 0.047435299 0.31414703, -0.11645108 0.050873172 0.30727375, -0.090944797 0.03694858 0.32688001, -0.096310534 0.042547785 0.32298082, -0.11251689 0.055172037 0.29661334, -0.078228228 0.031487629 0.32882029, -0.099020399 0.044853155 0.30301794, -0.077652752 0.030035811 0.32828158, -0.098293982 0.042948909 0.30246413, -0.11398145 0.05658621 0.29378608, -0.086909339 0.032121319 0.32755345, -0.086937092 0.030692328 0.3269684, -0.076466888 0.031924363 0.32908025, -0.075299881 0.031404078 0.32898727, -0.072952777 0.029953254 0.32844633, -0.074517779 0.031392641 0.32901007, -0.072952762 0.031383559 0.32902831, -0.072952807 0.03288646 0.32938331, -0.097420409 0.046665002 0.30745393, -0.11387983 0.05430406 0.30168661, -0.075855993 0.033685863 0.32940915, -0.095569119 0.046600901 0.31708726, -0.11448203 0.053280976 0.30416149, -0.1163142 0.043738615 0.31231752, -0.11331543 0.049595032 0.31022376, -0.096768729 0.04714014 0.30989164, -0.11451246 0.049753938 0.30951133, -0.11493516 0.051876359 0.30654004, -0.11306407 0.050796244 0.30869955, -0.11210293 0.049435303 0.31088743, -0.11155662 0.048729379 0.31195456, -0.096141033 0.047268532 0.31241471, -0.11116794 0.05436857 0.29543948, -0.097966641 0.037664782 0.32446083, -0.11258261 0.055734552 0.29270867, -0.11228189 0.054234751 0.30055305, -0.096911937 0.043881372 0.32164747, -0.086826667 0.03361978 0.32791737, -0.095537424 0.043951448 0.32185146, -0.11286154 0.053595036 0.30310383, -0.094547108 0.043381959 0.32264608, -0.093519643 0.042804394 0.32340533, -0.084616244 0.03189671 0.32800275, -0.077711552 0.035742179 0.32925302, -0.077237003 0.035715424 0.32928744, -0.096877977 0.045453448 0.30601126, -0.075804032 0.035904378 0.32933515, -0.09468618 0.046832383 0.31535244, -0.11178986 0.037781272 0.31623709, -0.1118671 0.036363706 0.31562957, -0.074390322 0.035003431 0.32947069, -0.072952904 0.036327191 0.32932049, -0.072952926 0.034426048 0.32950276, -0.096078679 0.046247568 0.30828851, -0.11335863 0.052562326 0.30559832, -0.11187741 0.050577711 0.30932426, -0.1115578 0.051522709 0.30767649, -0.11068015 0.050355811 0.30990201, -0.11006078 0.053266697 0.2942549, -0.11143448 0.05459322 0.29160315, -0.1108093 0.053813443 0.29932937, -0.1101812 0.049742844 0.31099334, -0.086690992 0.035152212 0.3280507, -0.096058346 0.045067456 0.32034084, -0.11130348 0.053553566 0.3019149, -0.094716527 0.045071159 0.32046768, -0.093777575 0.044585805 0.3213037, -0.077605382 0.037735451 0.32879871, -0.084547073 0.033396482 0.32836372, -0.077139311 0.037750769 0.32882068, -0.1117821 0.052904535 0.30448458, -0.075739175 0.037872426 0.32884017, -0.072952852 0.038158912 0.32878023, -0.11039658 0.051236745 0.30822152, -0.096543878 0.04398175 0.3047601, -0.11058155 0.053205833 0.29051179, -0.11005155 0.051905561 0.3064819, -0.10876492 0.050433636 0.30982715, -0.095179237 0.045936137 0.31881899, -0.092985377 0.045472901 0.31974563, -0.077479422 0.039538313 0.3279807, -0.077024922 0.03956135 0.32798973, -0.075663075 0.039645217 0.32799202, -0.072952904 0.03985475 0.3279013, -0.10949106 0.051727086 0.30672508, -0.10927597 0.051327854 0.30776745, -0.10872467 0.051330633 0.30751738, -0.10987873 0.049914233 0.28853855, -0.11005609 0.051625993 0.28947696, -0.10817035 0.035062943 0.31823027, -0.10766195 0.051048853 0.30776483, -0.10712792 0.050563771 0.30905074, -0.094937712 0.046528336 0.31711891, -0.094314441 0.046203703 0.31801239, -0.093890995 0.046293203 0.31758931, -0.2020006 0.12943569 0.14350832, -0.20208834 0.13021466 0.14350814, -0.20200069 0.12943602 0.14050797, -0.20208842 0.13021478 0.14050812, -0.20234728 0.13095436 0.14350823, -0.20234737 0.13095462 0.1405082, -0.20276418 0.13161802 0.14350814, -0.2027643 0.13161832 0.1405082, -0.20331857 0.13217217 0.14350832, -0.20331848 0.13217238 0.1405082, -0.20398213 0.13258927 0.14350814, -0.20398214 0.13258952 0.1405082, -0.20472178 0.13284808 0.14350832, -0.20472187 0.1328482 0.1405082, -0.20550069 0.13293569 0.14350832, -0.20550071 0.13293603 0.14050832, -0.20200065 0.11743584 0.1435073, -0.2020883 0.11821461 0.14350745, -0.20200059 0.11743602 0.14050737, -0.20208836 0.11821483 0.14050737, -0.20234713 0.11895433 0.14350745, -0.20234716 0.11895452 0.14050728, -0.20276418 0.11961803 0.14350763, -0.2027643 0.11961834 0.14050749, -0.20331839 0.12017219 0.14350748, -0.20331839 0.12017243 0.14050737, -0.20398213 0.12058924 0.14350748, -0.20398198 0.12058941 0.14050761, -0.20472184 0.12084803 0.14350748, -0.20472176 0.12084827 0.14050749, -0.20550062 0.12093577 0.14350763, -0.2055006 0.12093592 0.14050773, 0.21399967 0.11743847 0.14350715, 0.21391177 0.11821726 0.14350748, 0.21399961 0.11743866 0.14050737, 0.21391186 0.1182175 0.14050737, 0.21365303 0.11895697 0.14350763, 0.21365298 0.11895722 0.14050737, 0.21323606 0.11962064 0.14350763, 0.21323615 0.11962077 0.14050737, 0.21268183 0.12017484 0.14350748, 0.21268186 0.12017508 0.14050737, 0.21201828 0.12059179 0.14350748, 0.21201839 0.12059198 0.14050761, 0.2112785 0.12085065 0.14350763, 0.21127851 0.12085082 0.14050773, 0.21049964 0.1209383 0.14350745, 0.21049964 0.12093866 0.14050773, 0.21399949 0.1294384 0.14350799, 0.2139118 0.13021722 0.14350814, 0.21399949 0.12943864 0.14050812, 0.2139118 0.13021739 0.1405082, 0.21365292 0.13095698 0.14350799, 0.21365309 0.1309572 0.14050832, 0.21323594 0.1316206 0.14350823, 0.213236 0.13162073 0.1405082, 0.21268177 0.13217482 0.14350823, 0.21268174 0.1321751 0.14050832, 0.21201821 0.13259187 0.14350832, 0.21201816 0.13259204 0.1405082, 0.21127826 0.13285071 0.14350832, 0.21127841 0.13285077 0.14050832, 0.21049953 0.13293836 0.14350832, 0.21049944 0.13293862 0.14050812, 0.07295303 0.034428187 0.30950287, -0.072952896 0.03442727 0.30950287, -0.072952881 0.035966948 0.30962199, 0.072952911 0.035967804 0.30962199, -0.072952881 0.037469789 0.30997697, 0.072953001 0.037470728 0.30997699, -0.11911018 0.039250672 0.28750333, -0.18616304 0.11127403 0.1435073, -0.18486336 0.11135678 0.1435073, -0.11730917 0.03975803 0.28691858, -0.18346712 0.11164443 0.14350688, -0.1155774 0.040589627 0.28652796, -0.18183401 0.1122935 0.14350715, -0.11398138 0.041713387 0.28634697, -0.18038405 0.11324853 0.14350715, -0.11258247 0.043086212 0.28638238, -0.17915732 0.11449318 0.1435073, -0.17819455 0.11600801 0.1435073, -0.11143441 0.044655401 0.28663248, -0.17753825 0.11776686 0.14350745, -0.1105814 0.046360716 0.2870881, -0.17723233 0.11973205 0.14350763, -0.11005612 0.04813635 0.28773159, -0.17728943 0.12163147 0.14350763, -0.17768353 0.12359945 0.14350784, -0.17842291 0.12557067 0.14350775, -0.17949939 0.12747146 0.14350799, -0.18088605 0.12922487 0.14350814, -0.18253662 0.13075697 0.14350799, -0.18439043 0.13200428 0.14350799, -0.18637624 0.13291797 0.14350832, -0.18829477 0.13344382 0.14350832, -0.19032873 0.13363564 0.14350846, 0.19162749 0.13355532 0.14350832, 0.19032769 0.13363814 0.14350846, 0.19302365 0.13326766 0.14350832, 0.19465682 0.1326187 0.14350832, 0.19610676 0.13166383 0.14350823, 0.1973334 0.13041906 0.14350832, 0.19829629 0.12890431 0.14350799, 0.1989526 0.12714541 0.14350784, 0.1992586 0.12518023 0.14350775, 0.19920146 0.1232807 0.14350784, 0.19880754 0.1213128 0.14350763, 0.12816419 0.044764299 0.29447648, 0.19806802 0.1193416 0.14350745, 0.12763879 0.043184411 0.29344183, 0.1969915 0.11744092 0.14350745, 0.12678577 0.041796956 0.29235041, 0.19560505 0.11568743 0.14350715, 0.12563775 0.040655527 0.29124489, 0.19395426 0.11415519 0.14350715, 0.12423874 0.039804153 0.29016763, 0.19210055 0.11290795 0.14350715, 0.1226428 0.039274793 0.2891598, 0.19011486 0.1119943 0.14350715, 0.12091111 0.039088517 0.28826004, 0.1881963 0.11146836 0.14350715, 0.11911012 0.039252121 0.28750318, 0.18616226 0.11127648 0.14350688, 0.18486257 0.11135903 0.14350715, 0.1173092 0.039759446 0.28691837, 0.18346629 0.11164674 0.14350688, 0.11557738 0.040590998 0.2865279, 0.1818331 0.11229576 0.14350715, 0.11398141 0.041714866 0.28634697, 0.18038327 0.11325074 0.1435073, 0.1125825 0.043087706 0.28638244, 0.17915653 0.11449541 0.14350715, 0.17819358 0.1160103 0.14350715, 0.11143448 0.044656791 0.28663248, 0.17753732 0.11776905 0.14350763, 0.11058135 0.046362009 0.28708786, 0.1772314 0.11973421 0.14350748, 0.11005606 0.048137758 0.28773165, 0.17728844 0.12163374 0.14350775, 0.17768249 0.12360172 0.14350799, 0.17842184 0.12557302 0.14350784, 0.17949843 0.1274737 0.14350814, 0.18088493 0.12922706 0.14350814, 0.18253565 0.13075937 0.14350814, 0.18438947 0.13200648 0.14350814, 0.18637507 0.13292031 0.14350832, 0.18829359 0.13344622 0.14350832, -0.19162861 0.13355303 0.14350832, -0.19302475 0.13326535 0.14350832, -0.19465789 0.13261633 0.14350832, -0.19610792 0.1316613 0.14350832, -0.19733456 0.13041666 0.14350814, -0.19829737 0.12890184 0.14350775, -0.19895363 0.12714292 0.14350799, -0.19925958 0.12517774 0.14350799, -0.19920245 0.12327828 0.14350775, -0.19880837 0.12131031 0.14350748, -0.12816419 0.04476276 0.29447651, -0.19806905 0.1193392 0.14350745, -0.12763879 0.043182742 0.29344168, -0.19699243 0.11743832 0.1435073, -0.12678576 0.041795529 0.29235047, -0.19560599 0.11568502 0.14350715, -0.12563764 0.040653996 0.2912448, -0.19395529 0.11415285 0.14350715, -0.1242388 0.039802521 0.29016757, -0.19210154 0.11290559 0.143507, -0.12264279 0.039273322 0.28915972, -0.19011575 0.11199193 0.14350715, -0.12091091 0.039086949 0.28826004, -0.18819714 0.11146592 0.14350715, -0.094314486 0.028555449 0.30918497, -0.095179096 0.028070446 0.30988291, -0.0949376 0.029075742 0.30838951, -0.093890794 0.028840341 0.30885968, -0.092985258 0.027607124 0.31080928, -0.09277609 0.029004999 0.30884698, -0.12341075 0.039487064 0.30083022, -0.12486418 0.039939895 0.2960602, -0.12262356 0.038157374 0.29962394, -0.091760099 0.028404634 0.30973083, -0.090595305 0.029442869 0.30881411, -0.091312081 0.028158449 0.3101097, -0.07936509 0.034652509 0.30905232, -0.080836244 0.03631359 0.30892867, -0.079274282 0.036189023 0.30917808, -0.080949545 0.034778886 0.30879945, -0.076738715 0.024960177 0.31634429, -0.078036666 0.024893651 0.31663698, -0.077845693 0.025590433 0.31481484, -0.076878846 0.037555888 0.30980474, -0.079218835 0.037689902 0.30953676, -0.12138796 0.037297051 0.30134389, -0.12156435 0.037093587 0.29836324, -0.12035485 0.036251564 0.30004677, -0.076877333 0.024555203 0.31824458, -0.075552195 0.024571626 0.31792426, -0.07545945 0.025048584 0.31605104, -0.11451243 0.033228334 0.30124539, -0.11645103 0.034347337 0.29900777, -0.11493504 0.034332864 0.29776511, -0.083311498 0.030023109 0.30971959, -0.086197689 0.032202475 0.30814227, -0.082958385 0.031794563 0.30895799, -0.11306396 0.033252694 0.2999244, -0.097051114 0.037923798 0.30251199, -0.09958075 0.038813826 0.30073255, -0.099203207 0.04029122 0.30097637, -0.074220702 0.024845308 0.31664887, -0.072952822 0.025308954 0.31539595, -0.072952777 0.024694396 0.31720445, -0.074266076 0.024479397 0.31853619, -0.086665176 0.030445438 0.30887514, -0.096709371 0.039413709 0.30273041, -0.10746744 0.035210796 0.29764917, -0.10949112 0.034274396 0.29799581, -0.10860289 0.035404231 0.29689527, -0.10872449 0.033878028 0.29878795, -0.081314303 0.031633489 0.3092801, -0.082668446 0.033690736 0.30855423, -0.10766196 0.033849217 0.29916182, -0.10726813 0.036722284 0.29632589, -0.10595122 0.034470581 0.29912904, -0.081072204 0.033534434 0.30886713, -0.11907272 0.035431322 0.30168673, -0.11909639 0.035516851 0.29873565, -0.10556039 0.033906601 0.29988912, -0.10712779 0.033111222 0.30032107, -0.10040094 0.02880859 0.31831518, -0.10272881 0.028689511 0.315166, -0.099815756 0.027944263 0.31665608, -0.11784817 0.034718424 0.30033192, -0.10433945 0.035280615 0.2992079, -0.093346015 0.030333139 0.30740076, -0.10385977 0.030763686 0.31827128, -0.10337758 0.029570021 0.31679291, -0.10177821 0.034224167 0.30132043, -0.10326932 0.03687289 0.29880488, -0.10079526 0.03585228 0.30084518, -0.094686098 0.03030673 0.30708677, -0.093872353 0.031815652 0.30613607, -0.091312706 0.029908471 0.30825013, -0.095406801 0.039008498 0.30354071, -0.096501119 0.040886365 0.30314595, -0.089934722 0.030984044 0.30779821, -0.079463385 0.033406176 0.30912355, -0.095209949 0.04048463 0.30394897, -0.076596014 0.025726993 0.31455913, -0.077654839 0.026630711 0.31316403, -0.09742029 0.036727469 0.30248326, -0.10673207 0.036656037 0.29671609, -0.10609807 0.03826521 0.2960211, -0.1041567 0.032224268 0.3195447, -0.1061326 0.032788895 0.31841573, -0.10581677 0.031322889 0.31715307, -0.099988788 0.037631121 0.30067679, -0.12389546 0.041031536 0.30193612, -0.12619331 0.042859565 0.29828131, -0.12568676 0.041297659 0.29721013, -0.10556976 0.036692612 0.29742458, -0.093884416 0.040105909 0.30470639, -0.10528925 0.035931222 0.29816544, -0.088379219 0.026574019 0.31284764, -0.087777466 0.027576217 0.31127408, -0.092057317 0.027179975 0.31163627, -0.12215555 0.038613118 0.30257773, -0.093232438 0.031854041 0.30631691, -0.076913528 0.036053762 0.30944821, -0.09315908 0.033525951 0.30549639, -0.091922477 0.032110143 0.30658633, -0.11584723 0.033563357 0.3026416, -0.083714388 0.02844453 0.31081003, -0.0871986 0.028883355 0.30993253, -0.091279998 0.031430829 0.30716339, -0.089355655 0.032722801 0.30710238, -0.077051997 0.026729064 0.31305829, -0.081609458 0.029856285 0.31005314, -0.077471167 0.027974769 0.31174898, -0.12007783 0.036459077 0.30301949, -0.075664088 0.02695548 0.31282559, -0.095729619 0.037512563 0.30333406, -0.10083593 0.029990125 0.31981787, -0.10530734 0.03828999 0.29660904, -0.10513798 0.03997409 0.29599226, -0.10289945 0.032808997 0.30208388, -0.10465217 0.04112142 0.29611889, -0.10390677 0.037595864 0.29799673, -0.102391 0.038622059 0.29869524, -0.10194672 0.039789777 0.29878116, -0.079657525 0.031501383 0.30954427, -0.092231646 0.033703402 0.30577907, -0.094069555 0.03862625 0.30430496, -0.076970473 0.034515306 0.30932644, -0.092573859 0.035372183 0.30519313, -0.092277616 0.036588926 0.30518076, -0.090344526 0.033301264 0.3065829, -0.088640071 0.03582073 0.30671698, -0.088880323 0.034592092 0.30675253, -0.098150335 0.034921769 0.30270588, -0.076510087 0.028173646 0.31162539, -0.077302024 0.029571071 0.31062359, -0.096078768 0.03631001 0.30331767, -0.088981248 0.025915923 0.31459311, -0.092802905 0.026545446 0.31333485, -0.075080484 0.025673991 0.31466272, -0.12262797 0.040148951 0.30370042, -0.072952822 0.026255891 0.31373745, -0.07472048 0.026507951 0.31338552, -0.08415167 0.027119404 0.31218678, -0.074681491 0.029360719 0.31085962, -0.077153735 0.031357903 0.30983108, -0.11701722 0.034244761 0.304059, -0.081946172 0.028271334 0.3111563, -0.073791265 0.030887997 0.31014401, -0.072952792 0.028998686 0.31110412, -0.077032067 0.033266835 0.30940199, -0.072952762 0.030694293 0.3102254, -0.072952822 0.032526061 0.30968505, -0.075157322 0.028077511 0.31174898, -0.12082458 0.037761673 0.30427998, -0.10110398 0.031443343 0.32110584, -0.10411607 0.031661209 0.30310628, -0.074700214 0.02781287 0.31198567, -0.075016394 0.027514158 0.31225532, -0.10688514 0.032803517 0.30082262, -0.074121103 0.027704451 0.31209201, -0.072952762 0.027500851 0.31228915, -0.094373211 0.037124902 0.30410892, -0.07989423 0.029719559 0.31032652, -0.091836661 0.039582092 0.30575377, -0.099039726 0.033260487 0.30324703, -0.089559965 0.025626536 0.31644392, -0.093519665 0.02627892 0.31513974, -0.096768633 0.034491763 0.30356532, -0.084606394 0.02609906 0.31379783, -0.11797741 0.035246462 0.30544382, -0.082311586 0.026939141 0.31254736, -0.094701588 0.035916328 0.30410454, -0.1212844 0.039289486 0.30541906, -0.080164179 0.028129157 0.31144062, -0.10538145 0.030825067 0.30434859, -0.10826297 0.032013718 0.30197203, -0.092003584 0.038097814 0.30536148, -0.090093441 0.025717407 0.31832802, -0.094180249 0.026390612 0.31698206, -0.085061103 0.025422184 0.31558052, -0.10005456 0.031807922 0.30408546, -0.097609356 0.032815523 0.30413672, -0.11869104 0.036530048 0.30674234, -0.08269164 0.025911374 0.31417289, -0.09535034 0.034086522 0.3043755, -0.080457255 0.026791394 0.3128432, -0.090560988 0.026184816 0.32017359, -0.10866674 0.047240112 0.29044271, -0.094759271 0.02687642 0.31879079, -0.10898271 0.045823783 0.28991514, -0.085498214 0.02511492 0.31746641, -0.10664678 0.030332789 0.30576253, -0.10964069 0.031567719 0.3032935, -0.1011556 0.03061961 0.30518919, -0.10950068 0.044425841 0.28951222, -0.098568454 0.031345613 0.30500966, -0.083071589 0.025227115 0.31597006, -0.11006084 0.04332912 0.28928429, -0.10712527 0.046013907 0.29289442, -0.11913028 0.038045969 0.30790502, -0.08076188 0.025757484 0.31448045, -0.10742749 0.044586487 0.2923885, -0.090944618 0.027010914 0.32190928, -0.095234454 0.027717497 0.32049656, -0.096140884 0.032395855 0.30497545, -0.11116787 0.041720379 0.28911334, -0.085901208 0.025189424 0.31938377, -0.10786343 0.030202873 0.30729419, -0.11096546 0.031482503 0.30473584, -0.10627517 0.045421943 0.29407811, -0.10792321 0.043170784 0.29202121, -0.088282153 0.038831484 0.30725461, -0.083437011 0.02491302 0.31787029, -0.10230063 0.029741149 0.30651581, -0.11251688 0.040299296 0.28917447, -0.081066549 0.025067264 0.31628993, -0.099609181 0.030138493 0.30615121, -0.10656986 0.043989316 0.29358247, -0.091229849 0.028164022 0.32346898, -0.095587596 0.028881934 0.3220337, -0.10845916 0.042054866 0.29183164, -0.086254463 0.025642475 0.32125786, -0.10537393 0.044845279 0.29523075, -0.083773732 0.024981026 0.31980035, -0.097043008 0.030909676 0.30588156, -0.10705329 0.042565096 0.29323235, -0.10898472 0.030440625 0.30888453, -0.11218637 0.031761467 0.30624419, -0.11325652 0.032393664 0.30775994, -0.081359535 0.024747362 0.31820166, -0.088417694 0.037340533 0.30687541, -0.11405581 0.039120521 0.28946537, -0.10566063 0.043407615 0.29474548, -0.091405436 0.029599536 0.32479236, -0.095804967 0.030324265 0.32334325, -0.10951842 0.040408067 0.2917369, -0.08654438 0.02645676 0.32301766, -0.10344574 0.029206272 0.30801433, -0.084068887 0.025428388 0.32168624, -0.10757585 0.041439902 0.29306138, -0.11572573 0.038229279 0.28997523, -0.10069145 0.029240482 0.30751663, -0.10613091 0.04197504 0.29441229, -0.081629567 0.024809953 0.32014224, -0.098021775 0.029684938 0.30705804, -0.10392882 0.044011172 0.29689839, -0.086759672 0.027600843 0.32459459, -0.084311076 0.026237933 0.32345489, -0.11080915 0.038940709 0.29189053, -0.078220099 0.024567464 0.31856135, -0.10860884 0.039774839 0.29300287, -0.10996749 0.031037021 0.31047228, -0.10663946 0.040840875 0.29425919, -0.081866309 0.025252661 0.32203731, -0.10454684 0.029035892 0.30962747, -0.086892366 0.029031055 0.32592875, -0.084491149 0.02737874 0.32503885, -0.11746249 0.037659593 0.29068416, -0.10420278 0.042566027 0.29642788, -0.078389362 0.024624268 0.32051355, -0.11228174 0.037709031 0.29228702, -0.082060471 0.026058447 0.32381389, -0.10986747 0.03828501 0.2932016, -0.084601976 0.028806776 0.32637724, -0.10177375 0.028686244 0.30905434, -0.085330844 0.038345184 0.3082265, -0.1076443 0.039157756 0.29423642, -0.078537703 0.025061855 0.32241866, -0.082204819 0.027196301 0.32540351, -0.09903951 0.028768327 0.30846065, -0.078659326 0.025863623 0.32420358, -0.11077406 0.031968758 0.31199688, -0.11478737 0.034608688 0.31058377, -0.11413476 0.033355024 0.30922529, -0.11919911 0.037433885 0.29156485, -0.082293682 0.028622609 0.3267453, -0.1055617 0.029236369 0.31129235, -0.11387964 0.036760505 0.29291144, -0.078749835 0.026998352 0.32579958, -0.078805439 0.028422842 0.32714504, -0.085440308 0.036850035 0.30785626, -0.11130338 0.037027817 0.29364911, -0.095569044 0.029057316 0.30831239, -0.1146495 0.032927956 0.3052187, -0.10886884 0.037646152 0.29447854, -0.11344314 0.032444216 0.30375096, -0.11567523 0.033750605 0.30667242, -0.11648132 0.034880713 0.30805653, -0.12086906 0.037560534 0.29258409, -0.10281444 0.028496929 0.31070498, -0.10005733 0.028195705 0.31003514, -0.10128518 0.042709816 0.2995002, -0.11775252 0.036854263 0.3088631, -0.11137349 0.033200365 0.31339946, -0.11703646 0.036274832 0.30931813, -0.11554138 0.036131453 0.29373962, -0.11630324 0.035707187 0.3097567, -0.085619956 0.035323173 0.3077113, -0.11518936 0.036106132 0.31178334, -0.11286154 0.036051605 0.29432881, -0.097006306 0.027087282 0.31689587, -0.099102356 0.027430084 0.31490389, -0.096310422 0.026772633 0.31509045, -0.1064511 0.029799655 0.31294623, -0.097598098 0.027766328 0.31863675, -0.110266 0.036364101 0.29497579, -0.098062962 0.028783422 0.32024705, -0.10377353 0.028679993 0.31240469, -0.12240811 0.038034733 0.29370192, -0.10153565 0.041253254 0.2990526, -0.099299468 0.030534178 0.32149884, -0.096487388 0.02811553 0.30976599, -0.098383248 0.030099872 0.32166415, -0.1010362 0.027988661 0.31172097, -0.117203 0.03584579 0.29473981, -0.097458661 0.029679302 0.32180819, -0.085814044 0.034087002 0.30776221, -0.075835928 0.026341164 0.32528049, -0.11174259 0.034684464 0.31462589, -0.07295274 0.025814608 0.32458538, -0.072952785 0.02693807 0.32612997, -0.075783998 0.025367828 0.32360882, -0.11448196 0.035393652 0.29521459, -0.076836646 0.02739637 0.32644427, -0.082303621 0.037964061 0.30898872, -0.11178195 0.035360973 0.2957097, -0.075871646 0.02761849 0.32673356, -0.074901976 0.027843175 0.326989, -0.10718113 0.030704629 0.31452459, -0.072952852 0.028334541 0.32743281, -0.11331536 0.032753497 0.30179989, -0.11210295 0.032318272 0.30232605, -0.12375706 0.038838055 0.29487556, -0.11880088 0.035915229 0.2958734, -0.11155654 0.031887665 0.30353078, -0.10461424 0.029228322 0.31408861, -0.097405598 0.027517386 0.31139126, -0.11786242 0.037755132 0.30956748, -0.11705498 0.037750047 0.31066662, -0.10193817 0.028155431 0.31345347, -0.11627473 0.036981326 0.31111473, -0.096911892 0.027039666 0.31322351, -0.098288596 0.027285911 0.31312624, -0.082386211 0.036465388 0.30862504, -0.11610217 0.035079405 0.29627225, -0.095537156 0.026834246 0.31328994, -0.094546951 0.026540309 0.31422213, -0.09897317 0.04175622 0.30140695, -0.08076711 0.037813485 0.30928987, -0.099314436 0.031424135 0.32222551, -0.11335848 0.034675032 0.2966511, -0.098191798 0.031590436 0.3229818, -0.10772339 0.03191603 0.31596699, -0.09718632 0.030980445 0.32311252, -0.077121019 0.024878098 0.32210609, -0.12027352 0.03633653 0.29709664, -0.10530433 0.030120809 0.31569186, -0.075717375 0.024732379 0.32177329, -0.074345455 0.024852639 0.32234973, -0.072952732 0.025005411 0.32285565, -0.072952732 0.024539813 0.32100329, -0.077252351 0.028638974 0.32746994, -0.11005146 0.034362033 0.29770684, -0.082521826 0.034933016 0.30849153, -0.076792046 0.028285939 0.32724148, -0.0767662 0.02876463 0.32759905, -0.075172514 0.029223591 0.32799453, -0.1176603 0.035121053 0.29746148, -0.11187721 0.03288386 0.30047414, -0.11155768 0.033635508 0.29872975, -0.11068011 0.032554761 0.30099809, -0.11018093 0.032049112 0.30214363, -0.09605819 0.027373839 0.3114908, -0.1080575 0.03338775 0.31721827, -0.094716415 0.027269989 0.31156388, -0.093777359 0.026892014 0.31245366, -0.077006251 0.024526915 0.32018933, -0.075639151 0.024464637 0.31985569, -0.074308224 0.02448136 0.32045946, -0.072952807 0.024434969 0.31909645, -0.11039641 0.033370957 0.29928541, -0.10876471 0.032567926 0.30089125, -0.10927579 0.033679482 0.29894015, 0.072953075 0.028335454 0.32743281, 0.072953053 0.026938973 0.32612997, 0.07295309 0.025815487 0.32458538, 0.072952978 0.025006417 0.32285568, 0.072953068 0.02454078 0.32100338, 0.072953068 0.024435846 0.3190963, 0.072953045 0.024695279 0.31720439, 0.07295306 0.025309829 0.31539574, 0.072953053 0.026256885 0.31373745, 0.072952911 0.027501881 0.3122893, 0.072952963 0.028999658 0.31110412, 0.072952896 0.030695288 0.3102254, 0.072953016 0.03252697 0.3096849, 0.082205065 0.027197421 0.32540357, 0.07752084 0.025819449 0.32429355, 0.082060717 0.026059531 0.32381374, 0.089210369 0.028346606 0.31016535, 0.090743273 0.027193625 0.3116383, 0.088481441 0.027841043 0.3108601, 0.10772362 0.031917453 0.31596699, 0.1058169 0.031324323 0.31715307, 0.10530426 0.030122004 0.31569186, 0.090677753 0.028205596 0.31013122, 0.08431147 0.026238987 0.32345495, 0.081866495 0.02525359 0.32203731, 0.090595469 0.029443882 0.30881414, 0.091312215 0.028159492 0.31010979, 0.10718118 0.03070588 0.31452459, 0.10369211 0.031688314 0.30316874, 0.10339342 0.031392418 0.3036463, 0.10220492 0.032550782 0.30260289, 0.10524763 0.031074874 0.30387872, 0.084069133 0.025429292 0.32168609, 0.088553414 0.025486359 0.31672633, 0.085498497 0.025116077 0.31746641, 0.085061289 0.025423279 0.31558052, 0.088009723 0.025780685 0.31486586, 0.10944583 0.034040652 0.29835197, 0.10556053 0.033907887 0.29988942, 0.10802095 0.035095554 0.29751527, 0.10688527 0.03280485 0.30082276, 0.10480355 0.031685434 0.30292982, 0.10704724 0.031802811 0.30242348, 0.10458001 0.032030217 0.30248532, 0.1049301 0.032631565 0.30159912, 0.10792331 0.043172076 0.29202145, 0.10705335 0.042566393 0.29323232, 0.10656982 0.043990709 0.29358259, 0.1074275 0.044587832 0.29238874, 0.10629855 0.032742471 0.3010613, 0.10830151 0.046929847 0.2910659, 0.094373405 0.037126049 0.30410892, 0.091300115 0.037934959 0.30568928, 0.094069779 0.038627461 0.30430469, 0.10712525 0.046015147 0.29289448, 0.091563895 0.036423709 0.30551323, 0.11535087 0.038185325 0.29017916, 0.11528853 0.037857376 0.29072121, 0.11363567 0.03876321 0.29018241, 0.11713579 0.037868749 0.29029614, 0.086254649 0.025643468 0.32125786, 0.083774038 0.024982018 0.31980038, 0.085901424 0.025190497 0.31938377, 0.108869 0.037647743 0.29447857, 0.10670803 0.036424972 0.29692301, 0.10555707 0.037978228 0.29659727, 0.10764438 0.03915925 0.29423642, 0.11629684 0.038365185 0.28957528, 0.10989691 0.031642433 0.31265217, 0.10645123 0.029800948 0.31294626, 0.10910897 0.030717544 0.31111389, 0.11587949 0.038653072 0.28924423, 0.093099862 0.031636722 0.30649585, 0.089355856 0.032723855 0.30710238, 0.092412956 0.033353217 0.30584413, 0.11817706 0.038848922 0.28833634, 0.089934751 0.030985136 0.30779836, 0.11579716 0.039278243 0.2883105, 0.09540686 0.039009541 0.30354071, 0.093884498 0.040107179 0.30470619, 0.095210001 0.040485788 0.30394897, 0.11685893 0.039604969 0.28734106, 0.082293905 0.028623609 0.32674545, 0.077637903 0.028377563 0.32723755, 0.077593274 0.02695361 0.32589084, 0.087473959 0.029248329 0.30957228, 0.10860885 0.039776098 0.2930029, 0.1066394 0.040842149 0.29425934, 0.10757595 0.041441273 0.29306138, 0.086335242 0.028763257 0.31017485, 0.085834078 0.030329842 0.30910832, 0.087368682 0.027677026 0.3111884, 0.089584507 0.029589761 0.30888945, 0.10805759 0.03338908 0.31721833, 0.094701648 0.035917569 0.30410454, 0.091849118 0.035204381 0.30553073, 0.10296867 0.033204656 0.30166253, 0.096501261 0.040887535 0.30314606, 0.10613261 0.03279018 0.31841567, 0.10110962 0.033975571 0.30181995, 0.10845922 0.042056311 0.29183176, 0.10462718 0.033881005 0.30031025, 0.10433965 0.035281915 0.2992079, 0.084491327 0.027379645 0.325039, 0.11390828 0.039509349 0.28905788, 0.11092764 0.033301026 0.29940093, 0.11211237 0.039955564 0.28986424, 0.089054465 0.025572756 0.31861955, 0.11486325 0.040417906 0.28724128, 0.10826308 0.03201516 0.30197203, 0.086389445 0.030589489 0.30884758, 0.085394941 0.032090954 0.30836752, 0.10861434 0.045510579 0.29054362, 0.086544529 0.026457876 0.32301754, 0.11026615 0.036365479 0.29497579, 0.087406144 0.031275783 0.30825669, 0.095729783 0.037513666 0.30333406, 0.088439956 0.030906625 0.30821329, 0.10148942 0.034318034 0.30139279, 0.10014962 0.035612278 0.30132771, 0.11048236 0.032868769 0.31406525, 0.093883567 0.030120824 0.30746096, 0.10210963 0.035149913 0.30051139, 0.10311342 0.034961622 0.30010659, 0.10986757 0.038286321 0.29320151, 0.09670952 0.039414912 0.30273056, 0.10326933 0.036874339 0.29880464, 0.1122588 0.040344872 0.28934398, 0.11077718 0.04138843 0.28977963, 0.095350519 0.034087714 0.3043755, 0.11238854 0.041243266 0.28832921, 0.10951855 0.040409468 0.29173675, 0.084602192 0.028807677 0.32637745, 0.11321013 0.041217044 0.2876001, 0.10912705 0.044108354 0.29014984, 0.086173996 0.032583971 0.30801922, 0.089493707 0.02603619 0.32047275, 0.0850344 0.033978689 0.30798084, 0.08485204 0.035216499 0.30792674, 0.088144913 0.032895513 0.30739635, 0.088640183 0.035821777 0.30671674, 0.11240928 0.032905191 0.30062228, 0.088880658 0.034593232 0.30675238, 0.10964075 0.031569086 0.30329359, 0.096078843 0.03631115 0.30331749, 0.1006663 0.036220398 0.30074909, 0.099361785 0.037398081 0.30114493, 0.11178214 0.035362341 0.29570952, 0.098963082 0.038584188 0.30119383, 0.10222146 0.036845189 0.29950002, 0.10194681 0.039791141 0.29878116, 0.10239114 0.038623434 0.29869524, 0.086759903 0.027601987 0.32459468, 0.1109529 0.04205808 0.28907833, 0.10968146 0.043006834 0.28993174, 0.11084287 0.034349646 0.31529811, 0.094733909 0.028863955 0.30870169, 0.11185662 0.042901132 0.28739256, 0.097051166 0.037924953 0.30251214, 0.11110777 0.044584546 0.28714678, 0.098369576 0.041531846 0.30185792, 0.096141092 0.032397088 0.30497545, 0.11130348 0.037029237 0.29364923, 0.11080918 0.038942128 0.29189056, 0.089854077 0.026859002 0.32221508, 0.11383397 0.032868277 0.30196807, 0.11096552 0.031483918 0.30473584, 0.096768692 0.03449297 0.30356535, 0.11335869 0.034676418 0.29665139, 0.086892515 0.029032258 0.32592869, 0.097420439 0.036728621 0.30248326, 0.11286151 0.036053047 0.29432896, 0.095618367 0.027914248 0.31017083, 0.092057571 0.027181093 0.31163627, 0.098594323 0.040064912 0.301431, 0.11228175 0.037710529 0.29228717, 0.097043142 0.030910939 0.30588138, 0.11514703 0.033191618 0.30338717, 0.11218652 0.03176276 0.30624399, 0.090121925 0.028009672 0.32377988, 0.11493525 0.034334328 0.29776511, 0.097609453 0.032816712 0.30413672, 0.098150395 0.034922905 0.30270573, 0.11448193 0.035394948 0.29521468, 0.076095514 0.037525885 0.30986682, 0.076123364 0.036023431 0.30951089, 0.11387962 0.036761932 0.29291144, 0.096502692 0.027308013 0.31181234, 0.092803076 0.026546452 0.31333473, 0.11629799 0.033862919 0.30482516, 0.098021895 0.029686015 0.30705804, 0.076168954 0.034484647 0.30938977, 0.11325657 0.03239505 0.30776009, 0.11645101 0.034348905 0.29900786, 0.090286903 0.02944364 0.32510597, 0.076218188 0.033235572 0.30946654, 0.079218924 0.037690893 0.30953667, 0.11610244 0.03508091 0.29627219, 0.098568588 0.031346869 0.3050096, 0.079274252 0.036189955 0.30917808, 0.11554143 0.036132988 0.29373962, 0.099039882 0.033261824 0.30324703, 0.076315746 0.031325668 0.30989736, 0.11724247 0.03485639 0.3062267, 0.080767177 0.03781449 0.30928987, 0.11413489 0.033356532 0.30922517, 0.097353056 0.027069069 0.31356218, 0.079365104 0.034653611 0.30905205, 0.11784816 0.034719963 0.30033201, 0.09351977 0.026280113 0.31513959, 0.10128516 0.042711139 0.29950011, 0.11766045 0.035122529 0.29746148, 0.099039793 0.028769594 0.30846041, 0.076434404 0.029537668 0.31069234, 0.080836371 0.036314659 0.30892867, 0.11720315 0.035847433 0.29473987, 0.07946337 0.033407189 0.30912355, 0.099609241 0.03013967 0.306151, 0.11794424 0.036133662 0.30753773, 0.082303539 0.037965029 0.30898872, 0.11478752 0.034610089 0.31058395, 0.1190729 0.035432812 0.30168661, 0.10005453 0.031809166 0.30408543, 0.080949701 0.034779925 0.30879945, 0.11909645 0.0355184 0.2987358, 0.098136768 0.027206223 0.31535369, 0.094180465 0.026391666 0.31698191, 0.07656984 0.027940087 0.31182027, 0.10153578 0.04125464 0.29905245, 0.082386337 0.036466449 0.30862504, 0.11700745 0.037272763 0.29146063, 0.11880104 0.035916761 0.2958734, 0.079657748 0.031502321 0.30954444, 0.11837649 0.03764575 0.30870813, 0.10005754 0.028197099 0.31003514, 0.11518933 0.036107596 0.31178346, 0.12007785 0.036460485 0.3030197, 0.081072308 0.033535473 0.30886707, 0.07671684 0.026594635 0.31323844, 0.10069162 0.029241644 0.30751666, 0.11872637 0.037031971 0.29237166, 0.12035504 0.036253009 0.30004677, 0.082522005 0.034933962 0.30849162, 0.1011557 0.030620784 0.30518922, 0.084580585 0.038240958 0.30843699, 0.12027372 0.036338054 0.29709685, 0.079894356 0.029720709 0.3103267, 0.12082465 0.037763182 0.30427986, 0.081314504 0.031634472 0.30928022, 0.12037936 0.037144046 0.29341972, 0.098823696 0.027714148 0.3171182, 0.094759375 0.026877686 0.31879064, 0.082668692 0.033691913 0.30855435, 0.121388 0.037298534 0.30134386, 0.1010363 0.027989987 0.31172097, 0.12156427 0.03709523 0.29836324, 0.076869547 0.025552714 0.31489193, 0.12128453 0.039291054 0.30541885, 0.10177386 0.028687444 0.30905423, 0.084683381 0.036744941 0.3080686, 0.12215545 0.038614612 0.30257791, 0.080164373 0.028130218 0.31144047, 0.12190267 0.037604731 0.29456419, 0.081609666 0.029857326 0.31005314, 0.12262374 0.038158879 0.29962394, 0.082958542 0.031795539 0.30895799, 0.10342295 0.043743122 0.29743719, 0.12323777 0.038396291 0.29576185, 0.12262818 0.040150501 0.30370057, 0.10230079 0.029742457 0.30651566, 0.099387363 0.028573643 0.31878731, 0.095234662 0.027718682 0.32049659, 0.12341078 0.039488658 0.30083022, 0.077022344 0.024854505 0.3167173, 0.12433349 0.039488554 0.29696563, 0.10193841 0.028156698 0.31345338, 0.080457285 0.026792394 0.3128432, 0.12389551 0.041032933 0.30193615, 0.10369261 0.04229562 0.29697123, 0.12514763 0.040839314 0.29813004, 0.081946418 0.028272295 0.31115621, 0.12564896 0.042396732 0.2992098, 0.10281459 0.028498236 0.3107051, 0.083311766 0.030024176 0.30971971, 0.091905028 0.026144922 0.3187823, 0.091356643 0.025857471 0.31692228, 0.077169329 0.02452692 0.31864443, 0.092371285 0.026800714 0.32056999, 0.088282116 0.038832612 0.30725425, 0.092737593 0.027799606 0.32221636, 0.095587656 0.028883036 0.3220337, 0.10344587 0.029207747 0.30801448, 0.080762014 0.025758555 0.31448057, 0.099806212 0.029751409 0.32029742, 0.092099831 0.02920362 0.32416135, 0.10413474 0.040846989 0.29666999, 0.082311884 0.026940165 0.31254733, 0.092989773 0.029103491 0.32365844, 0.093868405 0.02901651 0.32313582, 0.095805064 0.030325558 0.32334328, 0.10272896 0.028690707 0.31516603, 0.083714724 0.028445641 0.31081003, 0.11074114 0.031185351 0.30870521, 0.10964802 0.03075223 0.30713645, 0.10377378 0.02868126 0.31240469, 0.07730481 0.024582295 0.32059944, 0.10814908 0.030129652 0.30950874, 0.11167081 0.031965222 0.31024483, 0.10462934 0.030545406 0.30491048, 0.11240122 0.033061516 0.31169656, 0.088417724 0.037341721 0.30687553, 0.1122364 0.034394361 0.31378403, 0.081066802 0.025068216 0.31628984, 0.10454701 0.029037286 0.30962712, 0.11290439 0.034432508 0.31300437, 0.10006424 0.031202216 0.32159054, 0.11355241 0.03448116 0.31221071, 0.10461255 0.039695404 0.29655161, 0.082691789 0.025912438 0.3141731, 0.12384292 0.039063003 0.2929557, 0.12237065 0.038402002 0.29184276, 0.084151983 0.027120514 0.31218687, 0.10537376 0.044846628 0.29523078, 0.12509486 0.040036649 0.29410809, 0.12607852 0.041285187 0.29525498, 0.10337773 0.029571366 0.31679291, 0.12624162 0.042110659 0.29695725, 0.077423431 0.025018897 0.3225069, 0.10461442 0.029229566 0.31408861, 0.081359744 0.024748374 0.31820163, 0.10586528 0.030042049 0.3063466, 0.12675612 0.042761065 0.29635322, 0.12724833 0.043420564 0.29573819, 0.083071873 0.025228146 0.31597033, 0.089667559 0.025700761 0.3159025, 0.10556172 0.029237624 0.31129259, 0.090747468 0.025949685 0.31506118, 0.092130348 0.02609447 0.31511572, 0.10566048 0.043408994 0.29474539, 0.092266887 0.030121692 0.32483155, 0.091139235 0.039420694 0.30607861, 0.093486995 0.030721411 0.32472175, 0.094474182 0.030479953 0.32411557, 0.084606618 0.026100025 0.31379783, 0.10776521 0.030278277 0.30675134, 0.10705376 0.029901631 0.30789924, 0.10627511 0.045423333 0.29407811, 0.10843332 0.030682277 0.30559951, 0.10386001 0.030764922 0.31827134, 0.08162982 0.024810877 0.32014242, 0.10970505 0.031062894 0.30518258, 0.11246312 0.035347413 0.31438413, 0.11345062 0.036143113 0.3138825, 0.083437286 0.024914032 0.31787053, 0.11419708 0.03605561 0.31296837, 0.086878829 0.027451217 0.31152618, 0.12058 0.037601802 0.29210991, 0.10613082 0.041976396 0.29441226, 0.12073486 0.038078669 0.29081219, 0.1217026 0.038658421 0.2899974, 0.12642249 0.043293301 0.29813698, 0.12655419 0.043108322 0.29754815, 0.12666346 0.043628644 0.29782799, 0.12689856 0.043965742 0.29751614, 0.12741503 0.044793349 0.29683065, 0.10415691 0.032225594 0.31954455, 0.089071915 0.026082795 0.31407407, 0.087444365 0.026444077 0.31311023, 0.090100855 0.026417453 0.31327072, 0.091447063 0.026462222 0.31331575, 0.10652486 0.030497011 0.30524907, 0.10714375 0.030978143 0.30415303, 0.10839556 0.031253628 0.30373642, 0.11888307 0.037559528 0.29112935, 0.11899836 0.038105868 0.28990275, 0.11996555 0.038578596 0.28909212, 0.088458709 0.026828533 0.31236818, 0.088476993 0.027476883 0.31134385, -0.21600084 0.14743584 0.14350918, -0.21600059 0.1114358 0.14350715, -0.17300053 0.10943592 0.14350688, -0.21400045 0.10943568 0.14350685, -0.17300077 0.14943606 0.14350927, -0.21400076 0.14943577 0.14350918, -0.21338098 0.11544749 0.1435073, -0.21282151 0.11481594 0.1435073, -0.21212721 0.11433665 0.14350715, -0.21377319 0.11619459 0.14350715, -0.21133825 0.11403751 0.1435073, -0.21397498 0.11701383 0.1435073, -0.21050054 0.11393574 0.1435073, -0.21397504 0.11785752 0.14350745, -0.20550056 0.11393577 0.14350739, -0.20472172 0.11402354 0.14350715, -0.21338105 0.12744753 0.14350799, -0.21282148 0.12005551 0.14350748, -0.21282154 0.12681597 0.14350799, -0.21338098 0.11942396 0.14350748, -0.21212724 0.12633666 0.14350775, -0.21212719 0.12053487 0.14350748, -0.21377322 0.1281947 0.14350799, -0.21377313 0.11867689 0.14350763, -0.21133818 0.12603739 0.14350799, -0.21133819 0.12083399 0.14350763, -0.21397515 0.12901387 0.14350799, -0.21050069 0.12593582 0.14350775, -0.21050058 0.12093571 0.14350748, -0.20276415 0.11525364 0.1435073, -0.20331836 0.11469947 0.14350715, -0.2023472 0.11591721 0.14350715, -0.20398211 0.11428249 0.1435073, -0.20550063 0.12593579 0.14350775, -0.20208827 0.11665693 0.1435073, -0.20472175 0.12602353 0.14350799, -0.20398194 0.12628236 0.14350799, -0.20331845 0.12669936 0.14350799, -0.20276418 0.12725362 0.14350799, -0.20234722 0.12791722 0.14350784, -0.20208842 0.12865692 0.14350799, -0.2113384 0.13283405 0.14350823, -0.21050079 0.13293581 0.14350823, -0.21212718 0.13253486 0.14350814, -0.21282154 0.13205548 0.14350814, -0.21338126 0.13142394 0.14350823, -0.21377337 0.13067687 0.14350823, -0.21397509 0.12985764 0.14350799, -0.17100056 0.11143601 0.14350715, -0.17100072 0.14743604 0.14350897, -0.21377319 0.12819473 0.14050788, -0.21338099 0.12744765 0.14050788, -0.21338102 0.11942415 0.14050737, -0.20208848 0.12865724 0.14050812, -0.20234725 0.12791744 0.14050788, -0.21397509 0.12901393 0.14050812, -0.21377321 0.11867712 0.14050761, -0.21397507 0.11785784 0.14050737, -0.20472187 0.12602386 0.14050773, -0.20398214 0.12628257 0.14050788, -0.20331837 0.11469962 0.14050713, -0.20276412 0.11525382 0.14050713, -0.20234713 0.11591735 0.14050737, -0.21397501 0.11701398 0.14050737, -0.21377319 0.11619481 0.14050737, -0.20398201 0.11428264 0.14050728, -0.20208827 0.11665723 0.14050737, -0.20472173 0.11402385 0.14050713, -0.20550071 0.12593606 0.14050788, -0.21050072 0.13293605 0.14050832, -0.21133831 0.13283432 0.14050832, -0.21212727 0.13253507 0.14050832, -0.21282163 0.13205574 0.1405082, -0.21338114 0.13142416 0.14050812, -0.21377328 0.13067697 0.1405082, -0.21397507 0.12985784 0.14050797, -0.20550048 0.11393595 0.14050728, -0.21050046 0.1139359 0.14050713, -0.21133813 0.11403768 0.14050713, -0.21050061 0.125936 0.14050773, -0.21050058 0.12093601 0.14050761, -0.21212706 0.11433677 0.14050737, -0.21133824 0.12603763 0.14050788, -0.21133816 0.12083422 0.14050761, -0.21282157 0.11481614 0.14050728, -0.21338105 0.11544773 0.14050713, -0.21212724 0.1263369 0.14050788, -0.21212718 0.1205349 0.14050761, -0.20276418 0.12725383 0.14050788, -0.20331845 0.12669964 0.14050773, -0.21282154 0.1268162 0.14050773, -0.21282147 0.12005571 0.14050737, 0.21399954 0.10943843 0.14350685, 0.17299967 0.10943814 0.1435068, 0.21599953 0.14743842 0.14350918, 0.21599965 0.1114385 0.14350688, 0.21399947 0.14943843 0.14350918, 0.17299946 0.14943823 0.14350903, 0.21323609 0.11525626 0.14350715, 0.21268189 0.11470197 0.14350715, 0.21365306 0.11591975 0.14350715, 0.21201825 0.11428502 0.14350715, 0.21391189 0.11665966 0.14350715, 0.21127841 0.11402613 0.14350715, 0.21049978 0.11393835 0.14350715, 0.20549969 0.11393832 0.14350715, 0.20466213 0.11404006 0.1435073, 0.21323612 0.12725617 0.14350799, 0.21268183 0.12670194 0.14350799, 0.21201821 0.12628497 0.14350799, 0.21365298 0.1279197 0.14350814, 0.21391195 0.12865946 0.14350823, 0.21127836 0.1260262 0.14350799, 0.21049964 0.1259383 0.14350775, 0.20222715 0.1161973 0.14350745, 0.20261918 0.1154502 0.1435073, 0.20317878 0.11481863 0.14350715, 0.2038731 0.11433925 0.14350715, 0.20549969 0.12593834 0.14350775, 0.20549956 0.12093835 0.14350745, 0.204662 0.12083662 0.14350775, 0.20202515 0.11701645 0.14350745, 0.20222712 0.11867939 0.14350745, 0.20202522 0.11786027 0.14350739, 0.204662 0.12604007 0.14350784, 0.2038731 0.12633924 0.14350784, 0.20387307 0.12053743 0.14350748, 0.20317864 0.12005815 0.14350763, 0.20261919 0.11942656 0.14350745, 0.20261915 0.12745006 0.14350799, 0.20317873 0.12681857 0.14350799, 0.20202506 0.12901641 0.14350799, 0.20222697 0.12819715 0.14350799, 0.20222703 0.13067946 0.14350799, 0.20202507 0.12986025 0.14350799, 0.20261912 0.13142647 0.14350823, 0.20549956 0.13293833 0.14350832, 0.20466202 0.13283655 0.14350814, 0.20317861 0.13205805 0.14350814, 0.20387304 0.13253735 0.14350832, 0.17099968 0.11143816 0.14350715, 0.1709995 0.14743814 0.14350918, 0.21391195 0.12865981 0.14050797, 0.21049953 0.12593861 0.14050773, 0.21127835 0.12602638 0.14050761, 0.21323603 0.11525644 0.14050713, 0.21268186 0.11470218 0.14050713, 0.20549953 0.13293859 0.14050832, 0.20466191 0.13283679 0.14050812, 0.20387311 0.13253769 0.1405082, 0.21365301 0.11592004 0.14050737, 0.2046621 0.11404029 0.14050728, 0.21201824 0.11428523 0.14050713, 0.20222713 0.11867966 0.14050749, 0.20202531 0.11786039 0.14050737, 0.20202512 0.11701673 0.14050728, 0.20222713 0.11619736 0.14050737, 0.20261922 0.11545034 0.14050728, 0.20317876 0.11481865 0.14050728, 0.20387311 0.11433938 0.14050728, 0.21391192 0.11665979 0.14050728, 0.21127844 0.11402635 0.14050713, 0.20202503 0.12901665 0.14050797, 0.20222706 0.12819742 0.1405082, 0.21049953 0.11393856 0.14050713, 0.20222697 0.13067968 0.14050832, 0.20202506 0.12986048 0.1405082, 0.2031787 0.13205838 0.14050832, 0.20261906 0.13142671 0.14050832, 0.2054996 0.12593858 0.14050773, 0.20549957 0.12093852 0.14050761, 0.20549965 0.11393848 0.14050713, 0.20466202 0.12083688 0.14050761, 0.20466204 0.12604031 0.14050773, 0.20387307 0.12633947 0.14050788, 0.20387322 0.12053758 0.14050761, 0.20317882 0.12005833 0.14050761, 0.20317882 0.12681873 0.14050773, 0.20261922 0.1274503 0.14050797, 0.20261922 0.11942674 0.14050761, 0.21323603 0.12725648 0.14050773, 0.21268174 0.12670222 0.14050773, 0.21201821 0.12628521 0.14050773, 0.21365294 0.12792006 0.14050788, -0.11010208 -0.033771213 0.28966218, -0.1114853 -0.034810793 0.29111484, -0.11175348 -0.03464644 0.2897678, -0.1102272 -0.033421654 0.28834611, -0.11553951 -0.034811344 0.29925331, -0.11433261 -0.034811329 0.30099747, -0.1157345 -0.033887271 0.30200911, -0.11158156 -0.034092512 0.28770286, -0.1127016 -0.03464644 0.28772122, -0.1169802 -0.033887256 0.30020937, -0.080448151 -0.031128537 0.31002492, -0.079087518 -0.03264406 0.31159732, -0.080739513 -0.032643888 0.31123367, -0.11104706 -0.033771109 0.2876969, -0.078844175 -0.031128559 0.31037778, -0.12221412 -0.031128105 0.29679909, -0.12051157 -0.031128217 0.29979524, -0.12130111 -0.029399443 0.3002753, -0.11148289 -0.033771124 0.28669757, -0.11181346 -0.033886511 0.28634208, -0.12303077 -0.029399235 0.2972317, -0.11041113 -0.032642711 0.28576773, -0.11815409 -0.033887122 0.29836175, -0.11824308 -0.032643657 0.30104697, -0.083969861 -0.032358918 0.31003198, -0.082825072 -0.031128522 0.30937725, -0.083187245 -0.032643881 0.3105666, -0.10369453 -0.029400308 0.31868836, -0.1017312 -0.0294003 0.31995034, -0.10202951 -0.027524475 0.32043514, -0.084186487 -0.033772383 0.31166509, -0.11944886 -0.03264362 0.29914904, -0.10401164 -0.027524393 0.31916079, -0.085207574 -0.033422749 0.31082585, -0.085949495 -0.032358851 0.30932873, -0.086246148 -0.033772271 0.31094936, -0.10594209 -0.027524408 0.31780949, -0.10605533 -0.025573481 0.31796494, -0.087262072 -0.033772301 0.31055349, -0.10588285 -0.034811277 0.29938236, -0.103421 -0.034811389 0.30206072, -0.10475095 -0.035380628 0.30338359, -0.087165534 -0.032643992 0.30913824, -0.10731286 -0.035380352 0.30059645, -0.095198289 -0.034812164 0.31741974, -0.092013195 -0.033888381 0.32079712, -0.095985591 -0.033888135 0.31895867, -0.09851332 -0.032358486 0.30182537, -0.099340357 -0.033771951 0.30325013, -0.099960998 -0.033422302 0.30208328, -0.091349617 -0.034812134 0.31920072, -0.097204663 -0.031128194 0.30166015, -0.097995855 -0.032643568 0.30261964, -0.078551859 -0.0275237 0.30891377, -0.076993108 -0.027523685 0.30919319, -0.077082358 -0.029399652 0.30975518, -0.078663185 -0.029399689 0.30947179, -0.11122935 -0.035572406 0.29875791, -0.10880007 -0.03557257 0.30185911, -0.11028726 -0.035380621 0.30312166, -0.078514382 -0.025572743 0.30872554, -0.10007112 -0.032358442 0.30041578, -0.10175346 -0.033771824 0.30104309, -0.10112087 -0.032643501 0.29977298, -0.10096736 -0.033771757 0.30179852, -0.11281138 -0.035380375 0.29989967, -0.081094295 -0.03388783 0.31270662, -0.083628677 -0.033887599 0.31201637, -0.10879134 -0.032357868 0.28866404, -0.1086186 -0.03264283 0.2895959, -0.10751968 -0.031127494 0.28901404, -0.11397633 -0.035380173 0.29821643, -0.10968879 -0.032357763 0.28676456, -0.100595 -0.032644499 0.31810394, -0.097242035 -0.031129416 0.32141525, -0.10124677 -0.0311292 0.31916356, -0.096675746 -0.032644589 0.32030794, -0.12111521 -0.032643426 0.29621664, -0.08321467 -0.030962963 0.30914313, -0.08255592 -0.029399555 0.30849329, -0.084109291 -0.031449262 0.30919951, -0.11667679 -0.034811262 0.29746333, -0.080231696 -0.029399689 0.30912644, -0.10317963 -0.03112914 0.31792066, -0.084186919 -0.030963127 0.30882275, -0.10456493 -0.03388698 0.29826352, -0.10219525 -0.033887226 0.30084148, -0.084909149 -0.030458186 0.30824503, -0.1096473 -0.035380248 0.29761627, -0.086106636 -0.030963074 0.30810994, -0.086688183 -0.031128559 0.3079899, -0.10560662 -0.029400293 0.31734976, -0.086333431 -0.02939954 0.3071366, -0.094343878 -0.035381053 0.31574926, -0.090629265 -0.035381246 0.3174684, -0.097474456 -0.030962687 0.30129418, -0.096616834 -0.02939928 0.30094734, -0.098322257 -0.031448785 0.30100283, -0.098249249 -0.030962754 0.30062494, -0.1123505 -0.035572316 0.29713812, -0.09980081 -0.03388809 0.3168135, -0.11977616 -0.033887107 0.29550722, -0.098694347 -0.030457873 0.29981455, -0.09974841 -0.030962598 0.29923031, -0.10023925 -0.031128053 0.29889598, -0.099583983 -0.029399108 0.29824439, -0.11507394 -0.035380203 0.29648888, -0.10762831 -0.030962091 0.28857261, -0.10670305 -0.029398669 0.28858143, -0.10829918 -0.031448197 0.28797799, -0.080098502 -0.027523648 0.30857331, -0.082334213 -0.025572848 0.30776542, -0.10340964 -0.032643374 0.29728281, -0.10808678 -0.030961994 0.28765708, -0.10248655 -0.032644484 0.31688806, -0.10812628 -0.034811083 0.29651868, -0.10818662 -0.03045721 0.28673762, -0.10873424 -0.027524237 0.31564236, -0.10976107 -0.025573302 0.31502965, -0.10893546 -0.030961882 0.2857936, -0.10926028 -0.031127352 0.28529638, -0.10840525 -0.02939843 0.28494662, -0.10506187 -0.031129111 0.31660327, -0.11072481 -0.035380114 0.29605952, -0.083603673 -0.029033538 0.30800778, -0.085483834 -0.029033612 0.30732483, -0.086114928 -0.027523573 0.30661139, -0.093455389 -0.035573188 0.31401259, -0.11824847 -0.034811098 0.29469779, -0.08988034 -0.035573203 0.31566682, -0.097397745 -0.02903318 0.30009666, -0.098894715 -0.034812097 0.315341, -0.09887179 -0.029033039 0.29874453, -0.11340698 -0.035572331 0.29547516, -0.099180579 -0.027523097 0.2978431, -0.1070977 -0.029032517 0.2874963, -0.10246173 -0.031127978 0.29647794, -0.10672431 -0.033886913 0.29550698, -0.10793947 -0.029032376 0.28568166, -0.10164214 -0.033887926 0.31562975, -0.10787857 -0.027522448 0.28473088, -0.082919277 -0.027330507 0.30774587, -0.08239007 -0.027523782 0.30794877, -0.1091616 -0.034811031 0.29502255, -0.10837224 -0.029400129 0.31520322, -0.083961964 -0.026748035 0.30730462, -0.086041182 -0.025572661 0.30643409, -0.10432864 -0.03264441 0.31559864, -0.1165909 -0.035379943 0.29381946, -0.085006632 -0.027906861 0.30714291, -0.084787384 -0.027330447 0.3070969, -0.092567042 -0.035380933 0.3122758, -0.08570905 -0.027330365 0.30673814, -0.089131325 -0.035380986 0.31386572, -0.11174002 -0.035380084 0.29446164, -0.096665226 -0.027330164 0.30011758, -0.096254684 -0.027523357 0.30050817, -0.10175729 -0.029399101 0.29588008, -0.097911581 -0.035381053 0.31374326, -0.096132547 -0.025572453 0.30036041, -0.097458832 -0.026747536 0.29931012, -0.099044248 -0.025572333 0.29770783, -0.10549551 -0.03264324 0.2946201, -0.098361276 -0.027906414 0.29875961, -0.09814126 -0.027329993 0.29880106, -0.10772085 -0.033886749 0.29406685, -0.1006788 -0.034811918 0.31419423, -0.098854437 -0.027329978 0.29811618, -0.1064292 -0.02732956 0.28779668, -0.10778439 -0.031128962 0.31449011, -0.11486687 -0.0355721 0.29290622, -0.1060304 -0.025571767 0.28822523, -0.10620026 -0.027522687 0.28831524, -0.10685188 -0.026747044 0.2867462, -0.10770071 -0.025571626 0.2846581, -0.10343544 -0.033887882 0.31437436, -0.11013717 -0.034810875 0.29348707, -0.10132347 -0.027523082 0.29551175, -0.10168119 -0.025572147 0.29478195, -0.091712631 -0.034811694 0.3106057, -0.088411108 -0.034811888 0.31213358, -0.10747389 -0.027905833 0.28589147, -0.10728672 -0.027329374 0.28601438, -0.10768228 -0.027329367 0.28510818, -0.096889086 -0.035573114 0.31208169, -0.10448702 -0.031127792 0.29389265, -0.10645807 -0.032643173 0.29322937, -0.11314301 -0.035379868 0.29199296, -0.099633448 -0.035380971 0.31263641, -0.10865999 -0.03388669 0.29258901, -0.10699311 -0.03264429 0.31353059, -0.1037377 -0.029398862 0.29335192, -0.075392932 -0.027524833 0.32912159, -0.070684351 -0.027524885 0.32930702, -0.07068444 -0.02557398 0.3294993, -0.075407974 -0.025573988 0.3293131, -0.10542178 -0.031127732 0.29254222, -0.10241612 -0.034811985 0.31297785, -0.07534799 -0.029400792 0.32855406, -0.070684411 -0.029400725 0.3287378, -0.090925284 -0.033887509 0.30906671, -0.087747425 -0.033887599 0.31053737, -0.1073652 -0.032643039 0.29180184, -0.075275257 -0.03112952 0.32763293, -0.070684396 -0.031129505 0.32781386, -0.10327628 -0.02752291 0.29301897, -0.095866576 -0.035380829 0.31042033, -0.080071986 -0.027524952 0.32856563, -0.080102205 -0.025573906 0.32875535, -0.10401746 -0.025571983 0.29161078, -0.10465167 -0.029398862 0.29203144, -0.10995756 -0.03388657 0.29030544, -0.098546289 -0.035572972 0.31101638, -0.075177342 -0.032644819 0.32639283, -0.070684336 -0.032644819 0.32657012, -0.10602903 -0.033887852 0.31236127, -0.10630243 -0.031127784 0.29115561, -0.079982698 -0.029400643 0.32800362, -0.10417748 -0.027522925 0.29171684, -0.082391568 -0.02752478 0.32815006, -0.084737957 -0.025573876 0.32783014, -0.10131025 -0.035380933 0.31146264, -0.090235084 -0.032643925 0.30771738, -0.075057939 -0.03388847 0.32488209, -0.070684381 -0.033888359 0.32505459, -0.10551299 -0.029398773 0.29067582, -0.094883524 -0.034811717 0.30882281, -0.079837583 -0.031129558 0.32709071, -0.1050268 -0.027522828 0.29038018, -0.082280166 -0.02940068 0.32759196, -0.09745916 -0.035380851 0.30939654, -0.084692948 -0.027524721 0.32764339, -0.10492904 -0.034811866 0.31102732, -0.074921921 -0.034812335 0.32315859, -0.070684388 -0.034812313 0.32332563, -0.089863025 -0.028788161 0.32579121, -0.087937385 -0.029400628 0.32616979, -0.088103145 -0.027524736 0.32671422, -0.079642422 -0.03264479 0.32586271, -0.10016011 -0.035572987 0.30988649, -0.091767885 -0.028161976 0.32530883, -0.093645744 -0.027524736 0.32472384, -0.093427248 -0.029400613 0.3241981, -0.082099341 -0.031129483 0.32668552, -0.090564847 -0.030287739 0.32485682, -0.093072578 -0.031129334 0.32334495, -0.087668307 -0.031129476 0.32528552, -0.089668758 -0.031128351 0.30661052, -0.084559731 -0.029400621 0.32709005, -0.090818346 -0.028476704 0.32556301, -0.090196654 -0.031917643 0.32383162, -0.087306045 -0.032644656 0.32409579, -0.11627679 -0.027523968 0.30820736, -0.11322419 -0.025573228 0.3118121, -0.11642335 -0.025573034 0.30833179, -0.092595115 -0.032644678 0.3221966, -0.11308796 -0.027524125 0.31167656, -0.074774303 -0.035381328 0.32128838, -0.070684336 -0.035381343 0.32144961, -0.089728139 -0.033303771 0.32252702, -0.086864673 -0.033888239 0.32264599, -0.093977384 -0.033887539 0.30735028, -0.079404645 -0.033888403 0.32436603, -0.096413873 -0.034811612 0.30783886, -0.089177176 -0.034392845 0.32099277, -0.10373564 -0.035380822 0.30958003, -0.11000475 -0.028787721 0.31411409, -0.081855781 -0.032644864 0.32546601, -0.089286521 -0.025573816 0.32654268, -0.11157855 -0.028161433 0.31293756, -0.11268461 -0.02939989 0.31127506, -0.1102943 -0.030287188 0.31298175, -0.084343269 -0.031129446 0.32619148, -0.11079947 -0.028476004 0.31353658, -0.11202937 -0.031128753 0.31062323, -0.09901011 -0.035380799 0.30831081, -0.10956076 -0.031917151 0.31217676, -0.074620582 -0.035573337 0.31934354, -0.070684373 -0.03538109 0.3175478, -0.070684299 -0.03557333 0.31949899, -0.1111476 -0.03264403 0.30974609, -0.089247987 -0.029399429 0.30578786, -0.10862736 -0.033303101 0.3111521, -0.11007315 -0.033887733 0.30867746, -0.079133138 -0.034812365 0.32265839, -0.11584305 -0.029399801 0.30783886, -0.10752971 -0.034392182 0.30994692, -0.081559166 -0.033888336 0.32397994, -0.093183219 -0.032643739 0.30605966, -0.12429088 -0.028160546 0.29568267, -0.12353367 -0.027523283 0.29749808, -0.095450476 -0.033887427 0.30640313, -0.084051922 -0.032644767 0.32498261, -0.10249445 -0.035572995 0.30807513, -0.12494814 -0.028786663 0.29383099, -0.12603116 -0.027523089 0.29216486, -0.12550448 -0.029398981 0.29194903, -0.12395273 -0.030286212 0.29444277, -0.12463206 -0.028475191 0.29476106, -0.074467055 -0.03538115 0.31739864, -0.12464933 -0.031127814 0.2915985, -0.078838721 -0.03538138 0.32080588, -0.12296639 -0.031916115 0.29398075, -0.12349842 -0.03264318 0.29112712, -0.097904183 -0.034811493 0.3067953, -0.12171105 -0.033302296 0.29339293, -0.12209615 -0.033886734 0.29055291, -0.081220664 -0.034812402 0.32228419, -0.088988766 -0.027523506 0.30528146, -0.089599326 -0.025572632 0.30474457, -0.12023491 -0.034391303 0.29270154, -0.11513854 -0.031128597 0.30724072, -0.089618422 -0.027202819 0.3262926, -0.083696961 -0.033888277 0.32350907, -0.090092197 -0.027041223 0.32615936, -0.09253145 -0.03112838 0.30500084, -0.090564221 -0.026879083 0.3260197, -0.074319333 -0.034811903 0.31552863, -0.070684344 -0.034811851 0.31567207, -0.094606012 -0.032643747 0.30514508, -0.09002693 -0.027631667 0.32606977, -0.091628991 -0.026445393 0.32568449, -0.093719646 -0.025573794 0.32490134, -0.10125321 -0.035380695 0.30656964, -0.078532457 -0.035573352 0.31887886, -0.087480225 -0.034988996 0.32015586, -0.086361192 -0.03481235 0.32099223, -0.085814826 -0.035381194 0.31919757, -0.11918261 -0.02752379 0.30449793, -0.11933845 -0.025572862 0.30461034, -0.080853552 -0.035381403 0.32044467, -0.088564999 -0.035142902 0.31928822, -0.089954063 -0.034988742 0.31926754, -0.10997155 -0.02720229 0.31467107, -0.096885018 -0.03388739 0.30539891, -0.11035787 -0.027040597 0.31436628, -0.083292037 -0.034812283 0.32182834, -0.11073999 -0.026878532 0.31405607, -0.11419051 -0.032643873 0.30643567, -0.11026324 -0.027631115 0.31430843, -0.074183293 -0.033887763 0.31380513, -0.070684299 -0.033887785 0.31394315, -0.11159448 -0.026444849 0.31333771, -0.092047185 -0.029399481 0.30421388, -0.10564142 -0.034988459 0.30982563, -0.078226246 -0.035381105 0.31695235, -0.093913063 -0.031128328 0.30411229, -0.080471672 -0.035573345 0.31853151, -0.10630996 -0.035142403 0.308608, -0.10005983 -0.034811575 0.30512246, -0.10758452 -0.034988407 0.30805555, -0.10884741 -0.034811821 0.30745822, -0.10751743 -0.035380658 0.3061353, -0.12454286 -0.027039748 0.29569665, -0.11872116 -0.029399659 0.30416483, -0.12424664 -0.025572319 0.29653823, -0.1251443 -0.026552271 0.29456627, -0.12620892 -0.02557217 0.29223743, -0.12553304 -0.027039487 0.29355457, -0.082852587 -0.035381351 0.32000455, -0.11844475 -0.034987565 0.29331464, -0.095991619 -0.032643739 0.30417499, -0.074064121 -0.032644022 0.31229466, -0.070684277 -0.032644074 0.3124277, -0.11859468 -0.035141464 0.29193348, -0.12052383 -0.027523484 0.30256006, -0.12195159 -0.025572632 0.30067107, -0.077931881 -0.034811858 0.31509981, -0.11955938 -0.034987513 0.29093412, -0.1204963 -0.034810666 0.28989762, -0.11876027 -0.035379689 0.28918654, -0.080089927 -0.035381075 0.3166182, -0.086881831 -0.03546514 0.31835082, -0.11303529 -0.033887532 0.30545485, -0.085246615 -0.035573322 0.31733105, -0.087915286 -0.035525147 0.31747857, -0.091748923 -0.027523477 0.30372921, -0.092973903 -0.025572542 0.3027133, -0.089267448 -0.035465132 0.31749412, -0.093398154 -0.029399406 0.3033455, -0.10439586 -0.0354647 0.30838865, -0.098960005 -0.033887301 0.3037886, -0.082395718 -0.0355733 0.31810763, -0.10501523 -0.035524596 0.30718666, -0.10626972 -0.035464559 0.30668172, -0.10613412 -0.035572808 0.30475926, -0.073966019 -0.031128597 0.31105483, -0.070684455 -0.031128462 0.31118444, -0.11797189 -0.031128455 0.30362388, -0.11674302 -0.035463911 0.29246593, -0.097922139 -0.027524579 0.3227447, -0.098009668 -0.025573704 0.32291585, -0.11685344 -0.035523932 0.29111809, -0.077660456 -0.03388774 0.31339231, -0.11781795 -0.035463665 0.29017037, -0.11695485 -0.035571802 0.28844729, -0.095258564 -0.031128351 0.30317053, -0.079722673 -0.034811851 0.31477872, -0.12004957 -0.029399421 0.30224535, -0.086265631 -0.035561245 0.31649244, -0.084678352 -0.035381075 0.31546474, -0.088560537 -0.035561118 0.31566802, -0.12178738 -0.027523551 0.30057117, -0.10311334 -0.035560701 0.30690926, -0.1117174 -0.034811508 0.3043358, -0.10491595 -0.035560701 0.30526704, -0.081938773 -0.03538112 0.31621137, -0.09308093 -0.027523417 0.30287284, -0.11499079 -0.035559971 0.29159206, -0.073893324 -0.029399689 0.31013373, -0.070684396 -0.029399622 0.31026036, -0.11602472 -0.035559904 0.2893838, -0.11696331 -0.032643709 0.30289596, -0.11514939 -0.035379726 0.28770798, -0.085170619 -0.035330173 0.31506017, -0.084132023 -0.03481191 0.31367043, -0.097662926 -0.029400539 0.32223794, -0.077422582 -0.032644074 0.31189576, -0.086283788 -0.03543957 0.31528541, -0.07938423 -0.033887718 0.31308332, -0.086288191 -0.035330098 0.31468979, -0.094713911 -0.029399265 0.30242449, -0.087020516 -0.035188679 0.31383935, -0.11927948 -0.031128239 0.30173463, -0.088494152 -0.035330113 0.31386659, -0.10155243 -0.035329778 0.30600733, -0.10266677 -0.03543916 0.30578774, -0.081499308 -0.034811918 0.31438759, -0.073848605 -0.02752376 0.30956659, -0.070684426 -0.025572766 0.30949944, -0.070684366 -0.027523708 0.30969137, -0.074618459 -0.025572766 0.30930528, -0.10244211 -0.035329733 0.30523583, -0.10279181 -0.035188328 0.30416974, -0.10416301 -0.035329733 0.30362904, -0.11320317 -0.03532907 0.29135841, -0.077227421 -0.031128567 0.31066757, -0.11414789 -0.035438377 0.29072815, -0.11372869 -0.035328846 0.29030484, -0.094378322 -0.02752335 0.30196476, -0.10213008 -0.025573704 0.32059893, -0.11364204 -0.035187516 0.28918618, -0.11470076 -0.035328899 0.28816035, -0.11341342 -0.034810629 0.28699714, -0.085276037 -0.034647699 0.31291062, -0.087395817 -0.034647655 0.31213966, -0.10082462 -0.03464723 0.3039819, -0.1024858 -0.034647059 0.3024562, -0.086619005 -0.034093637 0.31133237, -0.10145868 -0.034093153 0.30200896, 0.08122173 -0.034811337 0.32228431, 0.08369796 -0.033887241 0.32350907, 0.08156018 -0.033887248 0.32397994, 0.10506287 -0.031127889 0.31660309, 0.10866439 -0.031127561 0.31375042, 0.10926638 -0.029398818 0.31445208, 0.073141299 -0.033421855 0.31323478, 0.07440646 -0.033771489 0.3136175, 0.073878467 -0.034646709 0.31518593, 0.072032616 -0.034092847 0.3142443, 0.071625151 -0.034646671 0.31528774, 0.083293058 -0.034811351 0.32182834, 0.07222978 -0.033771452 0.31374756, 0.076420635 -0.031128589 0.32753095, 0.079838589 -0.031128492 0.32709071, 0.079983719 -0.029399756 0.32800379, 0.071139723 -0.033771474 0.31377175, 0.070685431 -0.033886854 0.31394315, 0.076511502 -0.029399741 0.32845074, 0.10448798 -0.031126421 0.2938925, 0.10645907 -0.032641757 0.29322946, 0.10549641 -0.032641884 0.29462031, 0.070685349 -0.032643098 0.3124277, 0.10542271 -0.031126421 0.29254216, 0.07940565 -0.033887472 0.32436603, 0.08185678 -0.032643769 0.3254661, 0.10316024 -0.032356989 0.29715443, 0.1029881 -0.031126682 0.2958467, 0.10395174 -0.032642063 0.29663268, 0.10458971 -0.033770408 0.29797378, 0.10342596 -0.033420835 0.29860064, 0.10369542 -0.029399004 0.31868836, 0.1056076 -0.029398959 0.31734964, 0.10594311 -0.027523059 0.31780931, 0.079643391 -0.032643821 0.32586259, 0.10175926 -0.032356981 0.29871976, 0.10314662 -0.033770557 0.29960847, 0.1040125 -0.027523089 0.31916079, 0.1023953 -0.033770535 0.30039847, 0.10112178 -0.032642167 0.29977298, 0.085000634 -0.0348108 0.31339672, 0.088412173 -0.034810822 0.31213358, 0.085582368 -0.035379972 0.31518027, 0.1020303 -0.027523238 0.32043514, 0.10213105 -0.025572401 0.32059893, 0.090054117 -0.032357711 0.30750284, 0.090397224 -0.031127322 0.30622917, 0.090985261 -0.032642763 0.30732483, 0.10574157 -0.034810435 0.31034476, 0.11007428 -0.033886354 0.30867729, 0.10686762 -0.033886518 0.31165674, 0.091059387 -0.033771086 0.30880815, 0.08974424 -0.033421542 0.30894038, 0.082396671 -0.035572302 0.31810784, 0.086792037 -0.035380159 0.31888983, 0.082853667 -0.035380345 0.32000455, 0.10884833 -0.034810301 0.3074581, 0.088159524 -0.032357726 0.30841011, 0.089099348 -0.033771154 0.30976361, 0.086187176 -0.035572287 0.31703502, 0.088102184 -0.033771183 0.31020468, 0.087166652 -0.032642853 0.30913824, 0.10417841 -0.027521562 0.29171699, 0.10502758 -0.02752148 0.29038015, 0.10551385 -0.029397432 0.29067582, 0.10465255 -0.029397476 0.29203144, 0.1040182 -0.025570687 0.29161078, 0.10672533 -0.033885632 0.29550689, 0.10512614 -0.033885781 0.29759046, 0.073979467 -0.032358106 0.31202653, 0.074907497 -0.032643188 0.31221971, 0.074785084 -0.031127583 0.31098214, 0.080854565 -0.035380382 0.32044461, 0.07188157 -0.032358017 0.31213719, 0.10432975 -0.032643076 0.3155984, 0.10262378 -0.030961249 0.2961185, 0.10227194 -0.029397819 0.29526275, 0.076298289 -0.032643873 0.32629317, 0.10785447 -0.032642957 0.31280664, 0.10233676 -0.03144737 0.29696766, 0.079134151 -0.034811344 0.32265854, 0.10373864 -0.029397603 0.29335192, 0.10195855 -0.030961204 0.29689708, 0.084464662 -0.033886667 0.3117533, 0.10115037 -0.030456346 0.29734614, 0.10318056 -0.031127889 0.31792066, 0.087748408 -0.033886496 0.31053716, 0.081939682 -0.035380069 0.31621128, 0.10057162 -0.030961219 0.29840353, 0.10024009 -0.031126898 0.29889616, 0.099584907 -0.029397804 0.29824454, 0.1017321 -0.029399071 0.31995034, 0.089956447 -0.030961838 0.30634028, 0.089960188 -0.029398371 0.30541533, 0.10451985 -0.035379518 0.30892107, 0.089365378 -0.031448033 0.30701444, 0.10751845 -0.035379324 0.30613512, 0.080472693 -0.035572339 0.31853151, 0.089043364 -0.030961838 0.30680364, 0.076149195 -0.033887435 0.32478529, 0.10343637 -0.033886615 0.31437436, 0.08812461 -0.030456934 0.30690867, 0.087184347 -0.030961934 0.30766222, 0.086689152 -0.031127434 0.3079899, 0.086334378 -0.029398423 0.3071366, 0.074335545 -0.030962136 0.31091541, 0.078839846 -0.035380419 0.32080588, 0.074694157 -0.029398706 0.3100628, 0.073530979 -0.031448338 0.31131107, 0.083994895 -0.032642957 0.31031242, 0.10327717 -0.027521629 0.29301897, 0.10168207 -0.025570933 0.2947818, 0.073314503 -0.030962173 0.3109929, 0.081500344 -0.034810882 0.31438759, 0.1024876 -0.032643203 0.31688806, 0.072426043 -0.030457299 0.31073692, 0.098966725 -0.027523305 0.32219779, 0.098010525 -0.025572423 0.32291594, 0.071268454 -0.030962188 0.31107193, 0.07068532 -0.03112765 0.31118444, 0.070685461 -0.029398855 0.31026036, 0.1014255 -0.029031675 0.29604828, 0.080090806 -0.035380114 0.31661835, 0.10124776 -0.031127889 0.31916356, 0.10008103 -0.029031772 0.29752958, 0.099181488 -0.027521942 0.29784313, 0.07597927 -0.034811426 0.32306474, 0.10324938 -0.035571691 0.30744082, 0.10613532 -0.03557146 0.30475944, 0.088876985 -0.029032286 0.30581546, 0.0785335 -0.035572324 0.31887913, 0.087066941 -0.029032324 0.30666706, 0.08611583 -0.027522486 0.30661136, 0.10241716 -0.034810733 0.31297785, 0.073540337 -0.029032622 0.31001657, 0.083609298 -0.031127546 0.30913028, 0.071542002 -0.029032614 0.3101081, 0.081095427 -0.033886742 0.31270662, 0.070685282 -0.027522732 0.30969137, 0.10164309 -0.033886623 0.31562975, 0.10144217 -0.027328681 0.29531574, 0.10183091 -0.0275218 0.29490319, 0.079723597 -0.034810875 0.31477872, 0.098697625 -0.029399205 0.32169625, 0.100639 -0.026746165 0.29611361, 0.09904515 -0.025570992 0.29770783, 0.075794742 -0.03538039 0.32119796, 0.10059606 -0.032643247 0.31810394, 0.1000934 -0.027905118 0.29701912, 0.10013387 -0.027328771 0.29679874, 0.099452689 -0.027328733 0.29751575, 0.10197871 -0.035379309 0.30596039, 0.078227326 -0.035380166 0.31695214, 0.10475206 -0.035379242 0.30338332, 0.089173734 -0.027329262 0.30514556, 0.089691117 -0.027522463 0.3049137, 0.083322845 -0.029398669 0.3082518, 0.089600205 -0.025571529 0.30474445, 0.10131121 -0.03537957 0.31146246, 0.088125765 -0.026746769 0.30557388, 0.086042084 -0.025571596 0.30643409, 0.080740482 -0.032642979 0.31123367, 0.087274328 -0.027905684 0.30620044, 0.087396272 -0.027329285 0.30601248, 0.079385154 -0.033886727 0.31308332, 0.086492151 -0.027329367 0.30641311, 0.10067976 -0.034810733 0.31419423, 0.074071646 -0.027329657 0.30951196, 0.075602889 -0.035572398 0.31925648, 0.098260619 -0.031128045 0.32088196, 0.074619345 -0.025571849 0.30930528, 0.074638255 -0.027522784 0.30949655, 0.0729395 -0.026747141 0.30950516, 0.070685297 -0.025571901 0.30949944, 0.077932872 -0.034810934 0.31509969, 0.07191284 -0.027906079 0.30975685, 0.099801891 -0.033886854 0.3168135, 0.083146334 -0.027522687 0.30771089, 0.082335062 -0.025571737 0.30776519, 0.072097532 -0.027329665 0.30963007, 0.100757 -0.034810256 0.30453679, 0.1034219 -0.034809973 0.30206057, 0.071108833 -0.02732962 0.30965266, 0.080449127 -0.031127561 0.31002492, 0.1001612 -0.035571743 0.30988649, 0.079088554 -0.032643054 0.31159714, 0.075410977 -0.035380173 0.31731477, 0.099634461 -0.035379801 0.31263626, 0.077661544 -0.033886831 0.31339231, 0.097672574 -0.03264324 0.31978607, 0.080232762 -0.029398713 0.30912644, 0.078845032 -0.031127539 0.31037778, 0.1240759 -0.027521741 0.29645148, 0.12603202 -0.027521443 0.29216462, 0.12620987 -0.02557059 0.29223743, 0.12424742 -0.025570858 0.29653811, 0.075226471 -0.034810927 0.31544816, 0.098895669 -0.034810718 0.315341, 0.12356792 -0.029397655 0.29619506, 0.1255054 -0.029397395 0.29194903, 0.099631004 -0.033886094 0.30322489, 0.10219632 -0.033885937 0.30084148, 0.077423722 -0.032643143 0.31189576, 0.080099419 -0.027522739 0.30857331, 0.099011146 -0.035379555 0.30831081, 0.12274299 -0.031126555 0.29577851, 0.12465036 -0.031126324 0.2915985, 0.078515165 -0.025571819 0.30872554, 0.078664176 -0.029398683 0.30947179, 0.1217884 -0.027522001 0.30057117, 0.12195253 -0.025571112 0.30067107, 0.075056434 -0.033886749 0.31372768, 0.098547347 -0.035571765 0.31101638, 0.096956059 -0.033886854 0.31845072, 0.077228509 -0.031127665 0.31066757, 0.1216327 -0.032641802 0.29521787, 0.12349951 -0.032641705 0.29112712, 0.07855273 -0.027522687 0.30891365, 0.12130205 -0.029397842 0.3002755, 0.12052455 -0.027521957 0.30256006, 0.11933937 -0.025571328 0.30461034, 0.097912565 -0.035379801 0.31374326, 0.077083297 -0.029398661 0.30975518, 0.098644085 -0.032642368 0.30207512, 0.12027997 -0.033885311 0.29453492, 0.12209719 -0.033885349 0.29055291, 0.12051241 -0.031126697 0.29979524, 0.097905278 -0.034810338 0.3067953, 0.076994039 -0.027522709 0.3091931, 0.12005048 -0.029397976 0.30224535, 0.097460203 -0.035379585 0.30939654, 0.1191835 -0.027522158 0.30449781, 0.096138597 -0.034811076 0.31692728, 0.11873677 -0.034809496 0.29375583, 0.12049727 -0.034809273 0.28989762, 0.11551026 -0.028785985 0.30858001, 0.11659053 -0.029398236 0.30694181, 0.11703148 -0.027522419 0.30730146, 0.1194499 -0.032642115 0.29914916, 0.096890159 -0.035571937 0.31208169, 0.11434212 -0.028159853 0.31016007, 0.11308894 -0.027522679 0.31167656, 0.11268554 -0.029398549 0.31127506, 0.11437968 -0.030285519 0.3088755, 0.11203038 -0.031127449 0.31062323, 0.11587451 -0.031127188 0.30635756, 0.097834095 -0.03112695 0.30113143, 0.11928045 -0.031126838 0.30173442, 0.11493698 -0.028474469 0.30937791, 0.11357063 -0.031915549 0.30814633, 0.11491077 -0.032642435 0.30557129, 0.11872212 -0.029398132 0.30416483, 0.11114852 -0.032642636 0.30974606, 0.089227863 -0.027523626 0.32636011, 0.093720488 -0.025572654 0.32490134, 0.089287467 -0.025572706 0.32654294, 0.093646824 -0.027523633 0.32472393, 0.11254103 -0.033301648 0.30721816, 0.11373647 -0.033886071 0.30461359, 0.096886039 -0.033886146 0.30539891, 0.11706204 -0.035378482 0.29291028, 0.11876128 -0.035378259 0.28918692, 0.11815514 -0.033885587 0.29836175, 0.11133008 -0.034390632 0.30612701, 0.096414804 -0.034810465 0.30783865, 0.09707126 -0.028786901 0.32279429, 0.095251508 -0.03537992 0.3152743, 0.1182441 -0.032642234 0.30104697, 0.095385872 -0.028160643 0.3238048, 0.093428276 -0.029399391 0.3241981, 0.11642428 -0.025571588 0.30833179, 0.095913798 -0.030286435 0.322633, 0.096235536 -0.028475266 0.32331073, 0.093073517 -0.031128217 0.32334495, 0.11797284 -0.031127069 0.30362377, 0.095867634 -0.035379577 0.31042033, 0.095446691 -0.031916346 0.32164896, 0.092596062 -0.032643538 0.32219645, 0.11532038 -0.035570543 0.29203108, 0.11695584 -0.035570417 0.28844747, 0.094852075 -0.033302423 0.32039678, 0.097232237 -0.029398125 0.3004303, 0.092014298 -0.033887144 0.32079709, 0.08905147 -0.02939954 0.32581896, 0.094153062 -0.034391489 0.31892437, 0.11667792 -0.034809683 0.29746351, 0.11698128 -0.033885743 0.30020928, 0.095992744 -0.032642562 0.3041752, 0.074600518 -0.028161217 0.32902986, 0.076567404 -0.027523827 0.3290174, 0.095451467 -0.033886258 0.30640334, 0.1169644 -0.032642256 0.30289605, 0.072637767 -0.028787445 0.32893655, 0.070685394 -0.027523976 0.32930702, 0.070685402 -0.029399861 0.3287378, 0.073581249 -0.030286793 0.32824701, 0.09432894 -0.035571944 0.3135553, 0.0736183 -0.028475944 0.32899648, 0.070685416 -0.031128619 0.32781368, 0.11357886 -0.035378475 0.29115206, 0.11515041 -0.035378229 0.28770798, 0.073527649 -0.031916801 0.32715899, 0.070685357 -0.032643903 0.32656997, 0.115075 -0.035378765 0.29648876, 0.073459342 -0.033302862 0.32577452, 0.094884574 -0.034810562 0.30882281, 0.070685342 -0.033887509 0.32505459, 0.096861593 -0.027522121 0.29999873, 0.073379189 -0.034391824 0.32414633, 0.11554055 -0.034809809 0.29925331, 0.096133411 -0.025571283 0.30036032, 0.088765003 -0.031128425 0.32494023, 0.11606694 -0.027200524 0.3085441, 0.11576391 -0.027038846 0.30893189, 0.11573553 -0.033885788 0.30200911, 0.095259532 -0.031127203 0.30317068, 0.11545578 -0.026876841 0.30931574, 0.115706 -0.027629416 0.30883747, 0.09460704 -0.032642599 0.30514508, 0.1119042 -0.034809273 0.29030663, 0.11341443 -0.034809191 0.28699714, 0.11474194 -0.026443142 0.31017402, 0.11322512 -0.025571819 0.3118121, 0.093406446 -0.035379764 0.3118363, 0.11119862 -0.03498676 0.30423948, 0.1123966 -0.034810033 0.30352077, 0.11094297 -0.035379048 0.30233514, 0.1134081 -0.035570893 0.29547513, 0.084693842 -0.027523663 0.32764339, 0.084738865 -0.025572766 0.32783037, 0.10998469 -0.035140816 0.30491453, 0.11397732 -0.035378803 0.29821643, 0.10943903 -0.034986857 0.3061921, 0.097599149 -0.027201433 0.32297489, 0.097170487 -0.02703977 0.32321656, 0.093978494 -0.033886414 0.3073501, 0.096738465 -0.026877765 0.32345268, 0.11433358 -0.034809869 0.30099747, 0.097152993 -0.027630273 0.32310733, 0.088379413 -0.03264365 0.32375795, 0.095749997 -0.026444096 0.32397121, 0.11036092 -0.033885192 0.28952771, 0.1118145 -0.03388508 0.28634208, 0.094756424 -0.034987647 0.31713104, 0.094714798 -0.02939814 0.30242449, 0.111741 -0.035378519 0.29446185, 0.093914002 -0.031127211 0.30411255, 0.093376271 -0.035141621 0.31728831, 0.092382044 -0.034987647 0.3182582, 0.1123516 -0.035570923 0.29713812, 0.091350563 -0.03481112 0.31920072, 0.092519335 -0.034810524 0.31018323, 0.09063036 -0.035380077 0.3174682, 0.074517682 -0.027040359 0.32926837, 0.075408861 -0.025573004 0.3293131, 0.0732437 -0.026553165 0.32939672, 0.084560588 -0.02939963 0.32709008, 0.070685297 -0.025573019 0.32949951, 0.072160184 -0.027040388 0.32937312, 0.074624769 -0.034988027 0.32272214, 0.1128124 -0.035378937 0.29989967, 0.093184203 -0.032642607 0.30605969, 0.073290043 -0.035141993 0.32233748, 0.10900812 -0.032641578 0.28884476, 0.11041224 -0.032641303 0.28576773, 0.071999662 -0.034988102 0.32285148, 0.082392529 -0.027523722 0.32815006, 0.080103099 -0.025572944 0.32875553, 0.070685342 -0.034811478 0.32332563, 0.070685439 -0.035380457 0.32144961, 0.11013818 -0.034809474 0.29348707, 0.10975507 -0.035462964 0.30300158, 0.10943127 -0.035571139 0.30110195, 0.087909624 -0.033887219 0.32231709, 0.11072577 -0.035378676 0.29605952, 0.10855639 -0.035523254 0.30362743, 0.094379254 -0.027522195 0.30196461, 0.10805824 -0.035463218 0.3048844, 0.092974909 -0.025571372 0.30271345, 0.093898728 -0.035463836 0.31543377, 0.093398951 -0.029398229 0.30334532, 0.092551686 -0.035524014 0.31555143, 0.091701753 -0.033886392 0.30866021, 0.11123049 -0.03557108 0.29875791, 0.091608934 -0.035463963 0.31652093, 0.089881375 -0.035572018 0.31566706, 0.084344171 -0.031128425 0.32619151, 0.10789785 -0.031126145 0.28828448, 0.10926127 -0.031125922 0.28529662, 0.074484453 -0.035464335 0.32082561, 0.10963693 -0.027522873 0.31488356, 0.10976203 -0.025571946 0.31502965, 0.073195368 -0.035524409 0.32041702, 0.071952753 -0.035464343 0.32095051, 0.10866099 -0.033885438 0.29258886, 0.070685335 -0.035572376 0.31949899, 0.092532381 -0.031127188 0.30500075, 0.1082688 -0.035559129 0.30172706, 0.082281128 -0.029399645 0.32759207, 0.10791942 -0.035378996 0.29986888, 0.10916259 -0.034809705 0.29502264, 0.10663653 -0.03555942 0.30353829, 0.080073006 -0.027523916 0.32856569, 0.093015566 -0.035559904 0.31368628, 0.087373555 -0.034811202 0.32067344, 0.090812922 -0.035559986 0.3147321, 0.089132451 -0.03537995 0.31386572, 0.074339844 -0.035560217 0.31887317, 0.093081921 -0.02752221 0.30287299, 0.10964842 -0.035378773 0.29761639, 0.071904525 -0.035560358 0.31899315, 0.10707293 -0.029397275 0.28786823, 0.1084061 -0.029397067 0.28494662, 0.070685357 -0.035380241 0.31754795, 0.084052898 -0.032643776 0.32498258, 0.10735846 -0.035328146 0.30017111, 0.1064657 -0.034809742 0.29868314, 0.10714508 -0.035437729 0.30128655, 0.1073662 -0.032641802 0.29180184, 0.10659213 -0.03532825 0.3010647, 0.10772192 -0.033885423 0.29406682, 0.092048086 -0.029398266 0.30421373, 0.10552758 -0.035186809 0.30142024, 0.082100242 -0.031128448 0.32668552, 0.10499437 -0.035328265 0.30279431, 0.092772432 -0.035328936 0.31189993, 0.092147119 -0.03543843 0.31284788, 0.10812724 -0.034809727 0.29651859, 0.091721632 -0.035329048 0.31243104, 0.10656496 -0.027521376 0.28761142, 0.10770167 -0.025570232 0.28465825, 0.10787948 -0.027521137 0.28473073, 0.10603137 -0.025570463 0.28822523, 0.090602405 -0.035187643 0.31235045, 0.089582443 -0.035329048 0.3134146, 0.074801207 -0.035329338 0.31713, 0.073859721 -0.03543878 0.3177655, 0.10630345 -0.031126346 0.29115587, 0.091749787 -0.027522352 0.30372921, 0.07362698 -0.035329316 0.31721708, 0.072624341 -0.035187859 0.31671318, 0.10605634 -0.02557217 0.31796479, 0.071274109 -0.03532942 0.31730416, 0.070685349 -0.034810942 0.31567207, 0.10532922 -0.034645747 0.29945421, 0.10381234 -0.034645732 0.30112323, 0.091174066 -0.034646433 0.31045893, 0.089132488 -0.034646463 0.31141785, 0.10335989 -0.034091908 0.30009851, 0.089108057 -0.03409243 0.31029803, 0.20050062 -0.025561828 0.1434994, 0.20041287 -0.024782944 0.1434994, 0.20050058 -0.025561582 0.14049953, 0.20041281 -0.024782691 0.14049953, 0.20015407 -0.024043206 0.1434994, 0.20015395 -0.024042923 0.14049953, 0.19973695 -0.023379486 0.1434994, 0.19973703 -0.023379344 0.14049953, 0.19918278 -0.022825319 0.1434994, 0.19918276 -0.022825088 0.14049953, 0.19851914 -0.02240834 0.1434994, 0.19851911 -0.022408146 0.14049953, 0.19777939 -0.022149507 0.1434994, 0.19777951 -0.022149395 0.14049953, 0.19700055 -0.022061754 0.1434994, 0.19700056 -0.02206159 0.14049953, -0.19049963 -0.02556425 0.1434994, -0.19058743 -0.024785381 0.14349911, -0.19049972 -0.025563974 0.14049953, -0.19058746 -0.02478515 0.14049938, -0.19084641 -0.024045531 0.1434994, -0.19084629 -0.024045397 0.14049953, -0.19126324 -0.023381997 0.1434994, -0.19126336 -0.023381691 0.14049953, -0.19181755 -0.022827778 0.1434994, -0.19181754 -0.022827629 0.14049953, -0.19248106 -0.022410903 0.1434994, -0.19248119 -0.02241059 0.14049953, -0.19322081 -0.022151981 0.1434994, -0.19322078 -0.022151832 0.14049953, -0.19399974 -0.022064257 0.1434994, -0.19399971 -0.022064034 0.14049953, -0.18692769 -0.023685385 0.1434994, -0.1260311 -0.02362131 0.29216486, -0.18712005 -0.025564205 0.1434994, -0.18639877 -0.021971676 0.1434994, -0.12550463 -0.021745224 0.29194933, -0.1855146 -0.020319466 0.1434994, -0.12464946 -0.020016421 0.29159933, -0.18432522 -0.018853147 0.14349988, -0.12349851 -0.018501032 0.29112786, -0.1828718 -0.017615993 0.14349964, -0.12209619 -0.017257418 0.29055381, -0.18120354 -0.016646359 0.14349988, -0.1204963 -0.016333107 0.28989869, -0.17937803 -0.01597451 0.14349988, -0.1187603 -0.015764054 0.28918785, -0.17745885 -0.015620429 0.14349988, -0.11695497 -0.015571866 0.28844875, -0.17551342 -0.015591573 0.14349994, -0.11514957 -0.015763942 0.28770918, -0.17340344 -0.015933637 0.14349988, -0.11341356 -0.016332988 0.28699797, -0.17143087 -0.016643401 0.14349964, -0.11181354 -0.017257113 0.28634304, -0.16966996 -0.017677609 0.14349988, -0.11041134 -0.018500548 0.28576872, -0.16817874 -0.018982124 0.14349964, -0.10926038 -0.020015914 0.28529713, -0.16699857 -0.020495903 0.14349964, -0.10840514 -0.021744836 0.28494686, -0.16615511 -0.022155549 0.1434994, -0.10787851 -0.023620766 0.28473109, -0.1656481 -0.023959409 0.1434994, -0.16550803 -0.025564048 0.14349911, -0.07068444 -0.023622978 0.32930726, 0.070685282 -0.023622129 0.3293075, 0.070685342 -0.021746207 0.32873836, -0.070684515 -0.021747019 0.32873836, 0.070685349 -0.02001721 0.32781416, -0.07068453 -0.020017993 0.32781416, 0.0706852 -0.018501785 0.32657081, -0.070684478 -0.018502612 0.32657069, 0.07068526 -0.017258067 0.32505554, -0.070684515 -0.017258938 0.32505554, -0.070684426 -0.016334739 0.32332662, 0.07068523 -0.016333822 0.3233268, -0.070684433 -0.015765633 0.32145074, 0.07068523 -0.015764687 0.3214508, -0.070684507 -0.015573304 0.3195, 0.070685185 -0.015572358 0.3195, -0.070684478 -0.015765373 0.31754902, 0.070685312 -0.015764553 0.31754878, -0.07068447 -0.016334269 0.3156729, 0.070685305 -0.01633342 0.3156729, -0.070684485 -0.017258305 0.31394398, 0.070685245 -0.017257426 0.31394398, -0.070684455 -0.018501874 0.31242862, 0.070685245 -0.018501032 0.31242862, -0.070684418 -0.020017099 0.31118491, 0.070685312 -0.020016234 0.31118503, -0.07068444 -0.021745924 0.3102608, 0.070685357 -0.021745156 0.3102608, -0.07068444 -0.023621846 0.30969137, 0.070685275 -0.023620967 0.30969149, 0.18712094 -0.025561843 0.1434994, 0.18692861 -0.023683097 0.1434994, 0.1260321 -0.023619752 0.29216486, 0.18639955 -0.021969322 0.1434994, 0.12550537 -0.021743756 0.29194951, 0.18551545 -0.020317186 0.1434994, 0.12465028 -0.020014901 0.29159918, 0.18432616 -0.018850837 0.14349964, 0.1234993 -0.018499482 0.29112786, 0.18287265 -0.017613772 0.14349964, 0.12209702 -0.017255928 0.29055396, 0.18120435 -0.016644109 0.14349988, 0.12049715 -0.016331624 0.28989866, 0.17937872 -0.015972201 0.14349988, 0.11876106 -0.015762527 0.28918785, 0.1774597 -0.015618209 0.14349988, 0.11695565 -0.015570361 0.28844875, 0.17551412 -0.015589323 0.14349988, 0.11515033 -0.015762549 0.28770918, 0.17340408 -0.015931476 0.14349988, 0.11341432 -0.016331542 0.28699797, 0.17143172 -0.016641211 0.14349988, 0.11181441 -0.017255668 0.28634304, 0.16967082 -0.017675493 0.14349988, 0.1104121 -0.018499169 0.28576872, 0.16817957 -0.018980075 0.14349988, 0.10926118 -0.020014528 0.28529713, 0.16699955 -0.020493742 0.14349964, 0.1084061 -0.021743435 0.28494686, 0.16615596 -0.022153456 0.1434994, 0.10787952 -0.023619365 0.28473109, 0.16564882 -0.02395739 0.1434994, 0.16550893 -0.025562022 0.1434994, 0.1657014 -0.027440827 0.14349911, 0.16623029 -0.029154446 0.14349905, 0.16711438 -0.030806642 0.14349905, 0.16830377 -0.032272976 0.14349881, 0.16975726 -0.033510063 0.14349905, 0.17142548 -0.034479667 0.14349905, 0.17325105 -0.035151545 0.14349881, 0.17517018 -0.035505656 0.14349881, 0.17711557 -0.035534393 0.14349881, 0.17922565 -0.035192285 0.14349881, 0.18119805 -0.034482617 0.14349881, 0.18295905 -0.033448312 0.14349881, 0.18445027 -0.032143753 0.14349905, 0.18563035 -0.030630093 0.14349905, 0.18647388 -0.028970335 0.14349905, 0.1869809 -0.027166326 0.1434994, 0.08810205 -0.017372455 0.31020564, 0.089107879 -0.017051067 0.31029907, 0.089099243 -0.017372478 0.30976459, 0.089132361 -0.016497243 0.31141904, 0.09525951 -0.020015772 0.30317134, 0.097834073 -0.020015549 0.30113196, 0.097232141 -0.021744329 0.3004308, 0.08716654 -0.018500779 0.30913907, 0.087748267 -0.017257083 0.31053811, 0.074406348 -0.017372746 0.31361854, 0.075056307 -0.017257381 0.31372884, 0.074907348 -0.018500965 0.31222051, 0.09896677 -0.023621518 0.32219788, 0.075226344 -0.016333263 0.31544927, 0.10203031 -0.023621414 0.32043532, 0.10173217 -0.021745417 0.31995073, 0.073878385 -0.016497586 0.31518713, 0.098697647 -0.021745581 0.32169685, 0.08193969 -0.015764441 0.31621242, 0.085582264 -0.015764277 0.31518155, 0.085000619 -0.016333278 0.31339791, 0.094714746 -0.021744508 0.30242473, 0.073141269 -0.017722312 0.31323555, 0.081500217 -0.016333226 0.31438866, 0.072229601 -0.017372709 0.31374815, 0.072032504 -0.017051402 0.31424534, 0.1179727 -0.020015594 0.30362451, 0.11928031 -0.02001537 0.30173501, 0.11824401 -0.018500078 0.30104783, 0.11696424 -0.018500146 0.3028968, 0.071625166 -0.016497638 0.3152889, 0.071139619 -0.017372798 0.31377286, 0.093399025 -0.021744628 0.30334577, 0.094379358 -0.02362046 0.30196497, 0.093081966 -0.02362049 0.30287319, 0.07972353 -0.01633333 0.31477991, 0.081095286 -0.017257322 0.31270772, 0.07938496 -0.017257284 0.31308419, 0.10316018 -0.018784937 0.29715514, 0.10342587 -0.017721217 0.29860163, 0.10458947 -0.017371636 0.29797459, 0.091749839 -0.023620579 0.30372939, 0.10395172 -0.018499937 0.29663342, 0.10298796 -0.020015243 0.2958473, 0.10175922 -0.018785033 0.29872048, 0.10314645 -0.01737183 0.29960945, 0.10239524 -0.017371912 0.30039942, 0.10112179 -0.01850016 0.29977366, 0.10075689 -0.016332682 0.30453783, 0.1021961 -0.017256547 0.30084246, 0.09963084 -0.01725674 0.30322585, 0.074785069 -0.02001616 0.31098288, 0.077228323 -0.020016145 0.31066814, 0.077083319 -0.021744993 0.3097555, 0.10342193 -0.016332436 0.30206165, 0.074694179 -0.021745067 0.31006318, 0.090054043 -0.018785704 0.30750367, 0.089744113 -0.01772194 0.30894122, 0.091059215 -0.017372344 0.30880898, 0.077661395 -0.017257381 0.31339327, 0.079088457 -0.018500943 0.31159818, 0.077423513 -0.018500958 0.31189662, 0.090985119 -0.018500637 0.30732566, 0.09039709 -0.020015854 0.30623001, 0.12052465 -0.023620244 0.30256021, 0.1217884 -0.023620237 0.30057138, 0.12130205 -0.021744195 0.30027589, 0.12005049 -0.021744322 0.3022458, 0.088159449 -0.018785749 0.30841094, 0.087373488 -0.016333651 0.32067442, 0.091350488 -0.016333532 0.31920168, 0.090630241 -0.015764367 0.3174696, 0.11491062 -0.018500295 0.30557209, 0.11573556 -0.017256584 0.30201012, 0.1137364 -0.017256726 0.30461437, 0.086791873 -0.015764412 0.31889072, 0.073979311 -0.018786076 0.31202719, 0.082396559 -0.015572291 0.31810883, 0.095992573 -0.018500399 0.30417582, 0.098644041 -0.018500257 0.30207586, 0.071881525 -0.018786084 0.3121379, 0.08618705 -0.015572291 0.31703594, 0.10262361 -0.020180698 0.29611912, 0.10227188 -0.021744121 0.29526329, 0.080090746 -0.015764434 0.3166194, 0.11872213 -0.021744471 0.30416521, 0.10233675 -0.019694608 0.29696837, 0.10195847 -0.020180788 0.29689756, 0.09391389 -0.020015735 0.304113, 0.10115042 -0.020685617 0.29734695, 0.10057161 -0.020180803 0.29840422, 0.077932723 -0.016333286 0.31510082, 0.099584922 -0.021744248 0.29824474, 0.10024009 -0.020015489 0.2988967, 0.092048138 -0.021744687 0.30421409, 0.08995638 -0.020181287 0.30634087, 0.089960076 -0.021744657 0.30541572, 0.1019786 -0.015763614 0.30596155, 0.10475194 -0.015763555 0.30338463, 0.087909512 -0.017257813 0.32231793, 0.092014238 -0.017257791 0.32079822, 0.089365274 -0.019695129 0.30701488, 0.08904326 -0.020181295 0.30680448, 0.11587434 -0.020015668 0.30635834, 0.082853608 -0.015764702 0.32000566, 0.09688592 -0.017256837 0.30539972, 0.088124596 -0.020686161 0.30690908, 0.08718434 -0.020181429 0.30766281, 0.086334392 -0.021744799 0.30713719, 0.086689204 -0.020016078 0.30799049, 0.074335396 -0.020181563 0.31091622, 0.080472589 -0.015572328 0.31853256, 0.11918347 -0.023620378 0.30449802, 0.073530994 -0.019695584 0.31131166, 0.073314436 -0.02018163 0.31099334, 0.094606966 -0.018500496 0.30514586, 0.089691028 -0.023620669 0.30491397, 0.072426036 -0.020686518 0.31073752, 0.078227237 -0.015764449 0.31695333, 0.071268387 -0.020181734 0.3110725, 0.092532374 -0.02001578 0.30500144, 0.088379264 -0.018501449 0.32375851, 0.093073517 -0.020016875 0.3233456, 0.092595935 -0.018501382 0.3221972, 0.10142546 -0.022110168 0.29604873, 0.10008095 -0.022110213 0.29752997, 0.10324918 -0.01557165 0.30744189, 0.099181354 -0.023620073 0.29784337, 0.1061352 -0.015571486 0.30476052, 0.083292857 -0.016333703 0.3218295, 0.11659054 -0.021744605 0.30694228, 0.088876948 -0.022110779 0.30581588, 0.087066792 -0.022110794 0.30666751, 0.086115822 -0.023620684 0.30661151, 0.097905166 -0.016332801 0.30679652, 0.073540352 -0.022111181 0.31001669, 0.080854401 -0.015764613 0.32044587, 0.071541943 -0.022111077 0.31010836, 0.095451362 -0.01725683 0.30640417, 0.10144216 -0.023813177 0.29531598, 0.1018309 -0.023620035 0.29490331, 0.078533351 -0.015572283 0.31888011, 0.10063899 -0.024395753 0.29611376, 0.088764876 -0.020016965 0.32494089, 0.10013377 -0.023813199 0.29679909, 0.093184069 -0.018500451 0.30606049, 0.10009348 -0.023236882 0.29701927, 0.083697788 -0.017257836 0.32351014, 0.099452622 -0.023813237 0.29751587, 0.1045198 -0.01576383 0.30892235, 0.10751832 -0.015763547 0.30613619, 0.089173786 -0.023813818 0.30514592, 0.11703148 -0.023620639 0.30730182, 0.081221692 -0.016333755 0.32228529, 0.088125795 -0.024396393 0.30557412, 0.075410821 -0.015764367 0.31731597, 0.087396197 -0.023813743 0.30601275, 0.099011019 -0.015763868 0.30831179, 0.087274358 -0.023237456 0.30620068, 0.086492024 -0.023813825 0.30641335, 0.078839563 -0.015764575 0.32080686, 0.074071608 -0.023814168 0.30951208, 0.074638166 -0.023620915 0.30949682, 0.08905147 -0.021745887 0.32581943, 0.096414752 -0.016332876 0.30783984, 0.093428232 -0.021745708 0.32419866, 0.072939448 -0.024396662 0.30950531, 0.084052801 -0.018501665 0.32498321, 0.072097443 -0.023814086 0.30963033, 0.071912713 -0.023237709 0.30975714, 0.093978293 -0.017257024 0.30735129, 0.081560075 -0.017257843 0.32398078, 0.071108721 -0.023814093 0.30965304, 0.07560274 -0.015572395 0.31925741, 0.10574151 -0.016332906 0.31034583, 0.10884836 -0.016332787 0.30745909, 0.10016107 -0.015571732 0.30988789, 0.079134099 -0.016333755 0.32265946, 0.08922784 -0.023621786 0.3263604, 0.093646683 -0.023621742 0.32472414, 0.097460032 -0.015763823 0.30939752, 0.084344104 -0.020017024 0.3261922, 0.081856698 -0.018501651 0.3254669, 0.10656487 -0.023619469 0.28761211, 0.10707293 -0.021743622 0.28786856, 0.075794622 -0.015764643 0.32119885, 0.079405405 -0.017257977 0.32436702, 0.094884396 -0.016332928 0.30882365, 0.10789792 -0.020014819 0.28828532, 0.084560491 -0.021745849 0.32709062, 0.10502777 -0.023619827 0.29038063, 0.10686754 -0.017257158 0.31165773, 0.11007412 -0.017256986 0.30867833, 0.082100175 -0.020017061 0.32668629, 0.1013112 -0.015763927 0.31146362, 0.075979106 -0.01633377 0.3230657, 0.10900797 -0.018499378 0.28884548, 0.079643369 -0.018501725 0.32586348, 0.10551387 -0.021743823 0.2906763, 0.098547176 -0.01557174 0.31101754, 0.084693886 -0.023621898 0.32764375, 0.10417842 -0.023619857 0.29171705, 0.091701701 -0.017257016 0.30866104, 0.08228109 -0.021745924 0.32759228, 0.11036076 -0.017255764 0.28952876, 0.076149173 -0.017258067 0.32478637, 0.10630338 -0.020014893 0.29115635, 0.079838634 -0.020017128 0.3270914, 0.10465261 -0.021743882 0.29203165, 0.095867574 -0.01576383 0.3104215, 0.082392417 -0.023621861 0.32815033, 0.10327715 -0.023619797 0.29301935, 0.10785438 -0.018500794 0.31280759, 0.076298237 -0.018501747 0.32629412, 0.11114852 -0.018500578 0.30974692, 0.11190417 -0.016331706 0.2903077, 0.10241707 -0.016333085 0.31297889, 0.079983681 -0.021746051 0.32800415, 0.10736599 -0.018499549 0.29180253, 0.076420546 -0.020017106 0.32753181, 0.099634334 -0.015764136 0.31263739, 0.080072902 -0.023621995 0.32856607, 0.092519335 -0.016333032 0.31018457, 0.10542271 -0.020015012 0.29254296, 0.07651154 -0.021746043 0.32845107, 0.10373864 -0.021743957 0.29335251, 0.076567434 -0.023622107 0.32901743, 0.11357883 -0.01576281 0.2911531, 0.096890032 -0.015571903 0.31208268, 0.11254081 -0.017841343 0.30721915, 0.11133005 -0.016752239 0.3061282, 0.10866441 -0.020016212 0.31375101, 0.10866088 -0.01725607 0.29258996, 0.11357048 -0.01922759 0.30814701, 0.11203025 -0.020015981 0.31062394, 0.083146259 -0.023620848 0.3077113, 0.10645904 -0.018499736 0.29323021, 0.11437955 -0.020857621 0.30887607, 0.11268551 -0.021744873 0.31127566, 0.10343627 -0.017257217 0.31437522, 0.1156534 -0.022983443 0.30870539, 0.10448798 -0.020015094 0.29389304, 0.10067959 -0.016333092 0.31419507, 0.11493693 -0.022668768 0.30937797, 0.093406409 -0.015764143 0.31183735, 0.11420304 -0.022357214 0.310031, 0.11308896 -0.02362093 0.31167674, 0.11532027 -0.015570622 0.29203248, 0.11013807 -0.016331907 0.29348806, 0.094852097 -0.017842297 0.3203977, 0.097672664 -0.018501218 0.31978691, 0.096956037 -0.017257545 0.31845176, 0.09415298 -0.016753096 0.31892529, 0.095446616 -0.019228507 0.32164964, 0.10772184 -0.017256137 0.2940678, 0.098260686 -0.020016726 0.32088259, 0.097912505 -0.015764061 0.31374431, 0.095913805 -0.020858508 0.32263359, 0.10926614 -0.021745015 0.31445214, 0.10549635 -0.01849981 0.29462114, 0.097155437 -0.022984292 0.32296503, 0.083322726 -0.021744963 0.30825227, 0.096235543 -0.022669654 0.32331115, 0.11706192 -0.015762802 0.29291144, 0.095307209 -0.022358071 0.32363227, 0.10432974 -0.018501017 0.31559923, 0.11174107 -0.015762929 0.29446283, 0.10164306 -0.017257247 0.31563058, 0.07345932 -0.017842684 0.32577541, 0.073379092 -0.016753409 0.3241474, 0.10916252 -0.016332116 0.29502356, 0.094328746 -0.015571918 0.31355637, 0.073527627 -0.019228932 0.32715949, 0.073581234 -0.020858888 0.32824761, 0.10672513 -0.017256189 0.29550791, 0.074587941 -0.022358503 0.32884073, 0.098895691 -0.016333219 0.31534198, 0.11873664 -0.01633196 0.29375687, 0.10963684 -0.023620974 0.3148841, 0.073618129 -0.022670139 0.32899672, 0.072643928 -0.022984814 0.32912651, 0.083609186 -0.020016048 0.30913073, 0.11340792 -0.015570808 0.29547623, 0.11119856 -0.016155932 0.30424052, 0.11239661 -0.016332496 0.30352172, 0.11094289 -0.015763346 0.30233619, 0.11072571 -0.015763078 0.2960608, 0.10506269 -0.020016361 0.31660369, 0.10998452 -0.016001943 0.30491573, 0.10943897 -0.016155977 0.30619317, 0.10248748 -0.018501107 0.31688884, 0.11576395 -0.024104301 0.30893213, 0.11495657 -0.024591457 0.30992576, 0.095251277 -0.015764106 0.31527552, 0.10812713 -0.016332146 0.29651979, 0.080099382 -0.023620907 0.30857354, 0.11417562 -0.024104338 0.31067735, 0.12027995 -0.017255973 0.29453579, 0.094756246 -0.016156737 0.31713203, 0.096138477 -0.016333427 0.3169283, 0.09337616 -0.0160028 0.31728914, 0.11507488 -0.015763026 0.29648992, 0.092381947 -0.016156796 0.3182596, 0.099801674 -0.017257381 0.31681433, 0.097170465 -0.024105195 0.32321665, 0.11235149 -0.015570942 0.29713917, 0.083994739 -0.018500771 0.31031328, 0.096043393 -0.024592351 0.32382423, 0.10512586 -0.017256204 0.29759133, 0.09503375 -0.024105232 0.32421839, 0.10560761 -0.021745313 0.31735018, 0.074624717 -0.016157087 0.32272303, 0.1031805 -0.020016488 0.31792143, 0.10964835 -0.015763085 0.29761723, 0.073289916 -0.016003195 0.32233831, 0.071999453 -0.016157176 0.32285243, 0.080232643 -0.021744955 0.30912688, 0.12163273 -0.018499773 0.29521871, 0.075006343 -0.023944076 0.32920972, 0.11667778 -0.016332109 0.29746452, 0.074543439 -0.023515221 0.32916087, 0.07451766 -0.024105687 0.32926837, 0.11397728 -0.015763175 0.29821742, 0.074028164 -0.024267796 0.32932049, 0.10059597 -0.018501107 0.31810477, 0.072916314 -0.02470148 0.32941979, 0.078552835 -0.0236209 0.30891401, 0.1064657 -0.016332265 0.29868424, 0.10975506 -0.01567949 0.30300269, 0.10943115 -0.015571225 0.3011032, 0.084464602 -0.017257329 0.31175402, 0.10855633 -0.015619513 0.30362856, 0.10805815 -0.015679616 0.3048856, 0.10594302 -0.02362122 0.31780949, 0.11123025 -0.015570957 0.29875895, 0.093898602 -0.015680242 0.31543487, 0.12274295 -0.020015132 0.29577917, 0.1036955 -0.02174541 0.31868878, 0.092551485 -0.015620206 0.31555262, 0.096861526 -0.023620296 0.29999888, 0.091608755 -0.015680362 0.31652212, 0.089881308 -0.01557209 0.31566823, 0.074484408 -0.015680816 0.3208268, 0.11815502 -0.017256226 0.29836261, 0.080449127 -0.020016219 0.31002551, 0.073195241 -0.015620638 0.32041815, 0.1155405 -0.016332362 0.29925457, 0.071952544 -0.015680727 0.32095158, 0.10791934 -0.015763279 0.29986989, 0.10826863 -0.015583191 0.30172834, 0.10124768 -0.020016473 0.31916383, 0.10663629 -0.0155834 0.30353948, 0.078664146 -0.021744963 0.30947223, 0.076994024 -0.023620974 0.30919319, 0.11281229 -0.015763249 0.29990062, 0.093015492 -0.01558404 0.31368738, 0.089132242 -0.015764166 0.31386667, 0.088411994 -0.01633307 0.31213462, 0.09081275 -0.015584003 0.31473315, 0.12356787 -0.021743942 0.29619554, 0.074339718 -0.015584406 0.31887439, 0.10401261 -0.02362131 0.31916097, 0.071904399 -0.01558445 0.31899408, 0.11944975 -0.018499974 0.29914987, 0.10735844 -0.015814159 0.300172, 0.080740407 -0.018500816 0.31123453, 0.11698118 -0.017256442 0.30021021, 0.10714483 -0.01570474 0.30128771, 0.10659205 -0.015814234 0.30106589, 0.10552746 -0.015955526 0.30142123, 0.10499425 -0.015814174 0.30279541, 0.11433346 -0.01633228 0.30099854, 0.09277238 -0.015814934 0.31190103, 0.078844965 -0.02001607 0.31037861, 0.12407588 -0.023619968 0.29645184, 0.092146941 -0.0157055 0.31284907, 0.09172152 -0.015814971 0.31243208, 0.090602212 -0.015956324 0.3123515, 0.12051253 -0.0200154 0.2997959, 0.089582197 -0.015814949 0.31341562, 0.074801147 -0.015815306 0.31713143, 0.073859692 -0.015705917 0.31776658, 0.073626898 -0.015815292 0.31721815, 0.072624296 -0.015956681 0.31671438, 0.07127396 -0.015815336 0.31730521, 0.10532916 -0.01649664 0.29945502, 0.10381225 -0.016496595 0.30112436, 0.091173954 -0.016497236 0.31045979, 0.10335984 -0.017050553 0.30009952, -0.10736521 -0.018500928 0.29180267, -0.10542183 -0.020016346 0.29254276, -0.10630266 -0.020016272 0.29115632, -0.10645821 -0.018500995 0.29323021, -0.086864807 -0.017258901 0.32264692, -0.083697043 -0.017258953 0.32350987, -0.083292097 -0.016334761 0.3218295, -0.10145865 -0.017051864 0.30201012, -0.10248583 -0.016498033 0.30245706, -0.10082468 -0.016498122 0.30398291, -0.086361267 -0.016334724 0.32099327, -0.10175359 -0.017373089 0.30104378, -0.10096735 -0.017373156 0.30179939, -0.10219525 -0.017257843 0.30084246, -0.11028734 -0.015764918 0.30312285, -0.10751744 -0.015764941 0.30613619, -0.1061344 -0.015572686 0.30476046, -0.10112092 -0.01850142 0.29977381, -0.10880018 -0.015572604 0.30186018, -0.092531428 -0.020017032 0.30500138, -0.089668848 -0.020016927 0.30661124, -0.089247949 -0.021745805 0.30578822, -0.11010219 -0.017372537 0.28966302, -0.10995776 -0.017257195 0.29030648, -0.10861857 -0.018500853 0.28959686, -0.11148547 -0.016333181 0.29111558, -0.11175358 -0.016497333 0.28976884, -0.10873435 -0.023622353 0.31564239, -0.092047133 -0.021745849 0.3042143, -0.11022728 -0.017722044 0.28834718, -0.1059421 -0.023622569 0.31780955, -0.10560665 -0.021746557 0.31735012, -0.10837233 -0.021746423 0.31520367, -0.10964745 -0.015764508 0.29761723, -0.107313 -0.01576471 0.3005974, -0.10812636 -0.016333472 0.29651979, -0.11104707 -0.017372508 0.28769797, -0.08434324 -0.020018104 0.3261922, -0.082099333 -0.020018157 0.32668629, -0.081855901 -0.018502709 0.32546672, -0.11158161 -0.017051224 0.28770393, -0.11270179 -0.016497228 0.28772241, -0.11148294 -0.0173725 0.28669852, -0.084052034 -0.018502671 0.32498321, -0.093398131 -0.021745797 0.30334574, -0.091748901 -0.023621749 0.30372939, -0.083970003 -0.018786881 0.31003287, -0.085207701 -0.017723124 0.31082684, -0.084186688 -0.01737358 0.3116661, -0.1091617 -0.016333427 0.29502356, -0.10672437 -0.017257538 0.29550791, -0.10772098 -0.017257389 0.2940678, -0.093080968 -0.023621622 0.30287319, -0.083187319 -0.018501859 0.31056741, -0.094378293 -0.023621563 0.30196497, -0.082825102 -0.020017128 0.30937797, -0.08594957 -0.018786836 0.30932948, -0.086246252 -0.017373603 0.31095046, -0.087262236 -0.017373595 0.31055444, -0.087165684 -0.018501814 0.30913907, -0.091712706 -0.01633412 0.31060672, -0.088411227 -0.016334329 0.31213462, -0.087747462 -0.017258245 0.31053811, -0.098513432 -0.018786442 0.30182618, -0.099340357 -0.017373357 0.30325109, -0.097995944 -0.018501442 0.30262026, -0.10751973 -0.020016108 0.28901443, -0.10551301 -0.021745089 0.2906763, -0.099961087 -0.017722663 0.30208418, -0.10670312 -0.02174494 0.28858179, -0.090925343 -0.017258186 0.30906767, -0.09720467 -0.020016786 0.30166072, -0.10866008 -0.017257366 0.29258981, -0.08239162 -0.023622919 0.3281503, -0.080072105 -0.023623023 0.32856607, -0.079982772 -0.021746974 0.32800415, -0.10007113 -0.018786509 0.30041668, -0.082280174 -0.021747041 0.32759228, -0.087306246 -0.018502478 0.32409668, -0.10879138 -0.018785883 0.28866476, -0.11171748 -0.016333941 0.30433676, -0.10884746 -0.016334195 0.30745909, -0.093183316 -0.018501621 0.30606049, -0.090235129 -0.018501837 0.30771837, -0.10968889 -0.018785749 0.28676528, -0.11122953 -0.015572358 0.29875913, -0.0832147 -0.020182598 0.30914372, -0.082555957 -0.021745916 0.3084937, -0.11072489 -0.015764412 0.29606071, -0.084559686 -0.021746967 0.32709062, -0.084109358 -0.019696448 0.30920011, -0.08418709 -0.020182561 0.30882326, -0.084909119 -0.020687465 0.30824563, -0.09391319 -0.020016853 0.304113, -0.08610674 -0.020182628 0.30811065, -0.086333476 -0.021745834 0.30713719, -0.086688243 -0.020017106 0.30799049, -0.094713919 -0.021745618 0.30242473, -0.11013728 -0.01633339 0.29348809, -0.09747453 -0.020182211 0.30129489, -0.096616767 -0.021745626 0.30094767, -0.092566974 -0.015765276 0.31227678, -0.08913146 -0.015765246 0.31386688, -0.09832231 -0.019696046 0.30100366, -0.098249353 -0.020182211 0.30062568, -0.087668322 -0.02001809 0.32528624, -0.11303539 -0.017258171 0.30545586, -0.11007325 -0.017258305 0.30867833, -0.11281149 -0.015764672 0.29990077, -0.098694488 -0.020686958 0.29981515, -0.093977533 -0.017258156 0.30735129, -0.09974841 -0.020182181 0.2992309, -0.099584006 -0.021745499 0.29824471, -0.10023918 -0.020016748 0.2988967, -0.1076284 -0.0201816 0.28857309, -0.11235067 -0.015572313 0.29713917, -0.084692918 -0.023623023 0.32764378, -0.10829923 -0.019695412 0.28797859, -0.10808686 -0.020181525 0.28765768, -0.094606146 -0.018501569 0.30514592, -0.10818668 -0.020686362 0.28673831, -0.10893556 -0.020181302 0.2857942, -0.096254729 -0.023621518 0.30050871, -0.083603717 -0.022112016 0.30800802, -0.1117401 -0.015764344 0.29446283, -0.095258564 -0.020016935 0.30317119, -0.11419065 -0.018501762 0.30643651, -0.11114766 -0.018501926 0.30974692, -0.085483961 -0.022112098 0.30732521, -0.086114965 -0.023621786 0.30661139, -0.093455538 -0.015573103 0.31401375, -0.089880429 -0.01557323 0.31566802, -0.097397782 -0.022111733 0.30009699, -0.0879374 -0.021747027 0.32617027, -0.11433271 -0.016333725 0.3009986, -0.098871842 -0.022111524 0.2987448, -0.099180609 -0.023621392 0.29784364, -0.11397636 -0.015764538 0.29821742, -0.094883606 -0.016334135 0.30882365, -0.10709771 -0.02211104 0.28749675, -0.10793953 -0.022110943 0.2856819, -0.082919292 -0.023815122 0.30774599, -0.082390137 -0.023621913 0.30794916, -0.095450543 -0.017258015 0.30640417, -0.11340715 -0.015572276 0.29547632, -0.083962046 -0.024397548 0.30730483, -0.08478751 -0.023814891 0.30709714, -0.11513862 -0.020017121 0.30724138, -0.11202937 -0.020017374 0.31062382, -0.085006796 -0.023238454 0.30714324, -0.095991746 -0.018501643 0.30417603, -0.085709058 -0.023814958 0.30673832, -0.1157346 -0.017257933 0.30201012, -0.096665233 -0.023814697 0.30011773, -0.094343983 -0.015765373 0.31575051, -0.090629466 -0.015765477 0.31746963, -0.08810316 -0.023622941 0.32671458, -0.1155396 -0.01633377 0.29925442, -0.09745881 -0.024397228 0.29931021, -0.11314304 -0.01576427 0.29199392, -0.095866725 -0.015765112 0.31042138, -0.098141208 -0.023814585 0.29880151, -0.098361209 -0.023238171 0.29875994, -0.098854475 -0.023814503 0.29811648, -0.11507409 -0.015764493 0.29648992, -0.10642924 -0.023814011 0.28779691, -0.10620015 -0.023620922 0.28831545, -0.096413918 -0.016334128 0.30783969, -0.10685197 -0.02439649 0.28674641, -0.11584308 -0.021746162 0.3078391, -0.11268461 -0.021746244 0.31127539, -0.11696351 -0.018501516 0.30289683, -0.10728671 -0.023813892 0.28601462, -0.10747395 -0.023237418 0.28589171, -0.09688516 -0.017257955 0.30539972, -0.1076824 -0.02381378 0.28510839, -0.11698037 -0.017257858 0.30021012, -0.095198348 -0.016334567 0.31742075, -0.091349587 -0.016334612 0.31920183, -0.11486708 -0.015572075 0.29290727, -0.096889146 -0.015573177 0.31208295, -0.11667702 -0.016333591 0.29746452, -0.11627673 -0.023622196 0.30820745, -0.11308802 -0.023622293 0.31167656, -0.1179719 -0.020017046 0.30362451, -0.073848538 -0.023621883 0.30956692, -0.097459175 -0.015765097 0.30939752, -0.11824313 -0.018501583 0.30104798, -0.073893391 -0.021745991 0.31013399, -0.1165909 -0.015764285 0.29382053, -0.11815421 -0.017257724 0.29836261, -0.097904243 -0.016333994 0.30679652, -0.073966123 -0.020017188 0.31105536, -0.076993085 -0.02362192 0.30919319, -0.11872109 -0.021746088 0.30416521, -0.095985673 -0.017258737 0.31895986, -0.092013493 -0.017258834 0.32079786, -0.097911619 -0.015765425 0.31374437, -0.11927947 -0.020016883 0.30173501, -0.074064136 -0.018501904 0.31229541, -0.11824856 -0.016333509 0.29469886, -0.077082448 -0.021745984 0.3097555, -0.11944902 -0.018501464 0.29914972, -0.098546356 -0.015573036 0.31101757, -0.078551911 -0.023621943 0.30891401, -0.11918262 -0.023621906 0.30449802, -0.098960042 -0.017257933 0.30378973, -0.074183397 -0.017258298 0.31380618, -0.12004963 -0.021745775 0.30224583, -0.11977626 -0.017257649 0.29550824, -0.077227481 -0.020017158 0.31066814, -0.078663297 -0.021746006 0.30947235, -0.12051164 -0.020016868 0.29979584, -0.099010088 -0.015765104 0.30831179, -0.12052366 -0.023621779 0.30256042, -0.080098413 -0.023621928 0.30857354, -0.096675836 -0.018502552 0.32030869, -0.092595115 -0.018502634 0.3221972, -0.12111532 -0.018501285 0.29621765, -0.074319489 -0.016334292 0.31552961, -0.098894782 -0.016334478 0.31534198, -0.1213011 -0.021745797 0.30027568, -0.077422686 -0.018501978 0.31189674, -0.12221424 -0.020016674 0.29679957, -0.099633455 -0.015765328 0.31263739, -0.12178745 -0.023621645 0.30057138, -0.078844175 -0.020017151 0.31037849, -0.10005993 -0.016333889 0.30512363, -0.080231763 -0.021745961 0.30912688, -0.12303088 -0.021745536 0.29723218, -0.12353364 -0.023621541 0.29749838, -0.074467167 -0.015765402 0.31739971, -0.10016032 -0.015572947 0.30988789, -0.077660576 -0.017258387 0.31339327, -0.089728236 -0.017843548 0.32252774, -0.089177392 -0.016754311 0.32099375, -0.097242117 -0.020018 0.32141563, -0.093072429 -0.020018037 0.32334551, -0.090196759 -0.019229699 0.32383224, -0.079087608 -0.018501934 0.311598, -0.10132346 -0.023621339 0.29551196, -0.090564817 -0.020859901 0.32485706, -0.093427338 -0.021746811 0.32419866, -0.099800944 -0.01725873 0.31681439, -0.080448076 -0.020017248 0.31002545, -0.089924268 -0.022985626 0.32597119, -0.10067884 -0.016334433 0.31419507, -0.074620709 -0.015573326 0.31934485, -0.090818398 -0.022670988 0.32556337, -0.0917008 -0.02235936 0.3251316, -0.093645863 -0.023622867 0.32472393, -0.10125338 -0.015764836 0.30657095, -0.077931918 -0.016334262 0.31510082, -0.10862741 -0.017842915 0.31115276, -0.079384275 -0.01725838 0.31308419, -0.10699318 -0.018502157 0.31353143, -0.10602904 -0.017258573 0.3123621, -0.10752977 -0.016753782 0.30994791, -0.10956082 -0.019229252 0.31217733, -0.10778438 -0.020017538 0.31449062, -0.10131029 -0.015765231 0.31146362, -0.11029418 -0.02085932 0.3129825, -0.097662941 -0.021746825 0.32223836, -0.080739506 -0.018501814 0.31123453, -0.11013044 -0.022985097 0.31425694, -0.10175733 -0.02174538 0.29588065, -0.074774362 -0.015765611 0.32128963, -0.11079947 -0.022670407 0.31353691, -0.11144831 -0.022358928 0.31279945, -0.078226447 -0.01576538 0.31695333, -0.10059524 -0.018502314 0.31810477, -0.10164223 -0.017258544 0.31563058, -0.079722717 -0.016334329 0.31477991, -0.12171096 -0.017842162 0.29339367, -0.12023487 -0.016752962 0.29270259, -0.12296652 -0.019228239 0.29398146, -0.1024947 -0.01557285 0.30807611, -0.12395268 -0.020858284 0.29444328, -0.081094451 -0.017258387 0.31270766, -0.12412016 -0.022357959 0.29559976, -0.10241628 -0.016334403 0.31297913, -0.074922092 -0.016334716 0.32315966, -0.12463211 -0.02266955 0.29476139, -0.097922102 -0.023622829 0.32274494, -0.12512158 -0.022984024 0.2939091, -0.10246178 -0.02001651 0.29647842, -0.078532636 -0.015573304 0.31888011, -0.087480299 -0.016158167 0.32015678, -0.085814878 -0.015765559 0.31919861, -0.080089875 -0.015765432 0.3166194, -0.088565275 -0.01600394 0.31928933, -0.1012468 -0.020017829 0.31916383, -0.089954168 -0.016157944 0.31926844, -0.1024866 -0.018502403 0.31688884, -0.090092294 -0.024106476 0.32615945, -0.091317698 -0.0245937 0.32578865, -0.081499398 -0.016334359 0.31438845, -0.10373575 -0.015765119 0.30958131, -0.092309304 -0.024106536 0.32535073, -0.10327639 -0.023621101 0.29301935, -0.075058155 -0.01725902 0.32488307, -0.10564148 -0.016157534 0.30982667, -0.10492928 -0.01633412 0.31102863, -0.10631008 -0.016003598 0.3086091, -0.078838795 -0.015765678 0.32080686, -0.10758452 -0.016157527 0.30805653, -0.10343546 -0.017258529 0.31437522, -0.080471754 -0.015573371 0.31853256, -0.11035798 -0.02410594 0.31436628, -0.1034098 -0.018501226 0.29728377, -0.11134715 -0.024593081 0.3135536, -0.083628684 -0.017258365 0.31201735, -0.1120946 -0.02410588 0.31276849, -0.10173124 -0.021746632 0.31995079, -0.11844487 -0.016156707 0.29331553, -0.10317964 -0.020017724 0.31792143, -0.081938818 -0.015765388 0.31621221, -0.11859477 -0.016002703 0.29193452, -0.11955951 -0.016156558 0.29093525, -0.075177468 -0.018502649 0.32639369, -0.10373773 -0.021745164 0.29335228, -0.1243034 -0.023943368 0.29612672, -0.079133272 -0.016334791 0.32265946, -0.12443338 -0.023514595 0.29567987, -0.080853701 -0.015765633 0.32044587, -0.12454288 -0.024105076 0.29569674, -0.12477651 -0.024267126 0.29526344, -0.08413209 -0.016334329 0.31367147, -0.12528981 -0.024700645 0.29427198, -0.1043289 -0.018502127 0.31559923, -0.086881898 -0.015681561 0.31835198, -0.085246801 -0.015573252 0.31733224, -0.10417743 -0.023621146 0.2917172, -0.10456508 -0.017257523 0.29826447, -0.087915376 -0.015621509 0.31747964, -0.089267574 -0.015681583 0.31749511, -0.082395867 -0.015573289 0.31810904, -0.1020294 -0.02362277 0.32043532, -0.075275376 -0.020018052 0.32763323, -0.10439599 -0.015681114 0.30838984, -0.10369457 -0.021746669 0.31868863, -0.10501529 -0.015620995 0.30718786, -0.088988826 -0.023621667 0.30528149, -0.10626973 -0.015681077 0.30668277, -0.079404697 -0.017258983 0.32436693, -0.11674316 -0.015680287 0.29246706, -0.10448711 -0.020016368 0.29389301, -0.081220858 -0.016334768 0.32228529, -0.11685359 -0.015620161 0.29111928, -0.11781807 -0.015680093 0.29017156, -0.084678516 -0.015765313 0.31546596, -0.086265795 -0.0155853 0.31649342, -0.10506193 -0.020017657 0.31660369, -0.088560611 -0.015585225 0.31566945, -0.082852736 -0.015765663 0.32000566, -0.10465162 -0.021745224 0.29203179, -0.10311352 -0.01558483 0.30691025, -0.10502675 -0.023621041 0.29038054, -0.075347997 -0.021747176 0.32855463, -0.10491609 -0.015584778 0.30526823, -0.10475118 -0.015764806 0.30338463, -0.10588302 -0.016333651 0.29938352, -0.10342103 -0.016333807 0.30206186, -0.11499089 -0.0155841 0.29159325, -0.10401173 -0.023622509 0.31916097, -0.11602492 -0.015583936 0.28938511, -0.079642564 -0.018502656 0.32586348, -0.085170753 -0.015816104 0.31506142, -0.10549548 -0.018501226 0.29462114, -0.081559323 -0.017258938 0.32398078, -0.086283959 -0.015706729 0.31528664, -0.086288281 -0.015816074 0.31469083, -0.087020561 -0.015957493 0.31384039, -0.088494256 -0.015816096 0.31386775, -0.10155259 -0.015815694 0.30600831, -0.075392835 -0.023623053 0.32912162, -0.10266687 -0.015706334 0.30578873, -0.10244229 -0.015815627 0.30523705, -0.079837725 -0.020018104 0.32709131, -0.1027918 -0.015957121 0.30417091, -0.10416315 -0.015815657 0.30363005, -0.11320329 -0.015815001 0.2913596, -0.11414797 -0.015705589 0.29072934, -0.11372863 -0.015814912 0.29030627, -0.11364214 -0.015956257 0.28918716, -0.11470094 -0.015814837 0.28816134, -0.085276201 -0.016498547 0.31291178, -0.087395899 -0.01649848 0.31214049, -0.086619027 -0.017052311 0.31133342, -0.16570036 -0.027442846 0.1434994, -0.16622931 -0.029156517 0.14349905, -0.16711341 -0.030808646 0.14349905, -0.16830271 -0.032275055 0.14349905, -0.16975625 -0.033512238 0.14349905, -0.17142445 -0.034481909 0.14349881, -0.17324999 -0.035153758 0.14349881, -0.17516917 -0.035507787 0.14349881, -0.17711473 -0.035536561 0.14349881, -0.1792247 -0.03519455 0.14349881, -0.18119705 -0.034484927 0.14349881, -0.1829581 -0.033450548 0.14349881, -0.1844493 -0.03214616 0.14349881, -0.18562937 -0.03063244 0.14349905, -0.18647291 -0.028972719 0.14349905, -0.18698001 -0.027168784 0.14349911, 0.15950051 -0.012561966 0.14349994, 0.20050052 -0.012561616 0.14049998, 0.15950057 -0.012561824 0.14049998, 0.20050043 -0.012561712 0.14349994, 0.20050061 -0.038561705 0.14349854, 0.15950069 -0.03856181 0.14049855, 0.20050071 -0.038561601 0.14049855, 0.15950067 -0.038562071 0.14349854, 0.19112018 -0.02755006 0.14349911, 0.19167973 -0.028181646 0.14349911, 0.19973698 -0.027743977 0.14349911, 0.19918279 -0.028298166 0.14349911, 0.2025007 -0.036561806 0.14349881, 0.15750059 -0.036562014 0.14349881, 0.19851929 -0.028715197 0.14349911, 0.20015402 -0.027080331 0.1434994, 0.19777948 -0.028974045 0.14349905, 0.20041285 -0.026340593 0.14349911, 0.19052604 -0.025983673 0.14349911, 0.19072804 -0.026802938 0.14349911, 0.19400059 -0.022061784 0.1434994, 0.19700068 -0.029061858 0.14349905, 0.19316299 -0.022163544 0.1434994, 0.20250046 -0.014561731 0.14349988, 0.19052611 -0.025139991 0.14349911, 0.19400053 -0.029061768 0.14349911, 0.19316304 -0.028960083 0.14349911, 0.19112015 -0.023573551 0.1434994, 0.19072795 -0.024320673 0.1434994, 0.19237407 -0.0224627 0.1434994, 0.19167961 -0.02294204 0.1434994, 0.15750043 -0.01456194 0.14349988, 0.19237402 -0.028660823 0.14349905, 0.19400056 -0.02206159 0.14049953, 0.19316289 -0.022163305 0.14049953, 0.19237396 -0.022462424 0.14049953, 0.20250049 -0.01456156 0.14049998, 0.19052607 -0.025983471 0.14049938, 0.19072802 -0.026802685 0.14049938, 0.19112016 -0.027549814 0.14049903, 0.1916797 -0.028181385 0.14049903, 0.1923741 -0.028660718 0.14049903, 0.19918279 -0.028297935 0.14049903, 0.19973706 -0.027743805 0.14049903, 0.20250067 -0.036561552 0.14049855, 0.19167957 -0.022941757 0.14049953, 0.19851919 -0.028714966 0.14049903, 0.19112004 -0.023573365 0.14049953, 0.19072804 -0.024320547 0.14049953, 0.19052605 -0.025139708 0.14049938, 0.20015401 -0.027080122 0.14049903, 0.19777949 -0.028973859 0.14049903, 0.15750043 -0.014561731 0.14049998, 0.15750062 -0.036561865 0.14049855, 0.2004129 -0.026340466 0.14049938, 0.19700055 -0.029061545 0.14049903, 0.19400059 -0.029061589 0.14049903, 0.19316302 -0.028959934 0.14049903, -0.20049986 -0.012564201 0.14350024, -0.15949978 -0.012564 0.14349994, -0.15949978 -0.012563746 0.14050022, -0.2004998 -0.012564074 0.14050022, -0.15949959 -0.038564008 0.14349854, -0.20049965 -0.03856406 0.14049855, -0.15949956 -0.038563866 0.14049855, -0.20049958 -0.038564336 0.14349854, -0.15749958 -0.036563959 0.14349854, -0.19988008 -0.027552467 0.14349911, -0.20249972 -0.03656422 0.14349854, -0.19932057 -0.02818409 0.14349911, -0.19862619 -0.028663348 0.1434994, -0.2002722 -0.026805405 0.1434994, -0.19783735 -0.028962467 0.14349911, -0.19084628 -0.027082849 0.14349911, -0.20047417 -0.025986169 0.14349911, -0.19699964 -0.029064301 0.14349905, -0.19058742 -0.026343036 0.1434994, -0.19699977 -0.022064213 0.1434994, -0.20249976 -0.014564302 0.14349988, -0.19399966 -0.029064182 0.1434994, -0.19322081 -0.028976563 0.14349905, -0.15749973 -0.014564019 0.14349988, -0.1978374 -0.022165958 0.1434994, -0.19862621 -0.022465173 0.1434994, -0.19932055 -0.022944529 0.1434994, -0.19988011 -0.023576055 0.1434994, -0.20027229 -0.024323147 0.1434994, -0.20047408 -0.025142398 0.1434994, -0.19248107 -0.028717589 0.14349911, -0.19181757 -0.028300587 0.14349911, -0.1912633 -0.027746398 0.14349911, -0.1912632 -0.027746264 0.14049903, -0.19181743 -0.028300468 0.14049903, -0.19084625 -0.027082626 0.14049938, -0.19058737 -0.026342902 0.14049903, -0.20249964 -0.036564056 0.14049855, -0.19988015 -0.027552258 0.14049938, -0.19932063 -0.028183866 0.14049903, -0.15749961 -0.036563862 0.14049855, -0.19862628 -0.028663088 0.14049903, -0.20027223 -0.026805159 0.14049903, -0.15749976 -0.014563795 0.14049998, -0.19783725 -0.028962348 0.14049903, -0.20047417 -0.02598599 0.14049938, -0.19699973 -0.029063974 0.14049903, -0.19399972 -0.029064003 0.14049903, -0.19322076 -0.02897634 0.14049903, -0.19248104 -0.028717462 0.14049903, -0.19783729 -0.022165801 0.14049953, -0.20249976 -0.014564123 0.14049998, -0.19699968 -0.022064034 0.14049953, -0.19862619 -0.022465017 0.14049953, -0.19932061 -0.022944298 0.14049938, -0.19988017 -0.023575816 0.14049938, -0.20027226 -0.024322931 0.14049938, -0.20047417 -0.025142115 0.14049903, -0.061684467 0.022425856 0.33264402, -0.061636526 0.022031002 0.33264416, -0.061684486 0.02242633 0.326644, -0.061636589 0.022031512 0.32664424, -0.061495502 0.021659158 0.33264402, -0.061495546 0.021659728 0.32664424, -0.061269477 0.021331783 0.33264416, -0.061269432 0.021332201 0.32664412, -0.0609718 0.021067999 0.33264402, -0.060971826 0.02106848 0.32664412, -0.060619581 0.020883169 0.33264402, -0.060619589 0.020883564 0.326644, -0.060233276 0.020787932 0.33264402, -0.060233414 0.020788375 0.32664412, -0.059835501 0.020787902 0.33264402, -0.059835624 0.020788375 0.326644, -0.059449367 0.02088315 0.33264402, -0.059449371 0.020883564 0.326644, -0.059097201 0.021068167 0.33264402, -0.059097294 0.021068551 0.32664412, -0.058799427 0.021331832 0.33264402, -0.058799472 0.021332189 0.32664412, -0.058573544 0.021659177 0.33264402, -0.058573484 0.021659538 0.326644, -0.058432464 0.022031087 0.33264402, -0.058432404 0.02203162 0.326644, -0.058384459 0.022425991 0.33264416, -0.058384471 0.022426415 0.32664424, -0.061684225 -0.01357412 0.33264199, -0.061636288 -0.013969075 0.33264211, -0.061684329 -0.013573658 0.32664222, -0.061636314 -0.013968598 0.32664225, -0.061495259 -0.014340889 0.33264211, -0.061495245 -0.014340486 0.32664198, -0.061269231 -0.01466826 0.33264199, -0.061269253 -0.014667775 0.32664216, -0.060971659 -0.014931988 0.33264199, -0.060971543 -0.01493163 0.3266421, -0.060619399 -0.015116852 0.33264199, -0.060619313 -0.015116442 0.3266421, -0.060233224 -0.015211981 0.3326419, -0.060233131 -0.015211675 0.3266421, -0.059835363 -0.015211981 0.33264202, -0.059835315 -0.015211683 0.3266421, -0.059449181 -0.015116747 0.33264199, -0.05944914 -0.015116509 0.3266421, -0.059096962 -0.014931958 0.33264199, -0.059096895 -0.014931653 0.3266421, -0.058799196 -0.014668126 0.3326419, -0.058799215 -0.014667768 0.3266421, -0.058573321 -0.014340755 0.33264199, -0.058573246 -0.014340471 0.3266421, -0.058432214 -0.013968918 0.33264199, -0.05843218 -0.013968427 0.32664233, -0.058384303 -0.013573978 0.33264211, -0.058384214 -0.013573762 0.3266421, -0.064284436 0.014425915 0.33264366, -0.063675418 0.013528567 0.33214372, -0.063784443 0.014425915 0.33214372, -0.064160913 0.013408843 0.33264366, -0.063354917 0.012683313 0.33214346, -0.063797601 0.012450855 0.33264351, -0.062841386 0.011939306 0.33214357, -0.063215494 0.011607632 0.33264342, -0.06216469 0.011339713 0.33214357, -0.062448662 0.010928292 0.33264351, -0.061364111 0.010919563 0.33214346, -0.06154149 0.010452025 0.33264351, -0.060486503 0.010703478 0.33214331, -0.060546748 0.010207091 0.33264333, -0.059582476 0.010703418 0.33214346, -0.059522159 0.010207094 0.33264333, -0.05870473 0.010919701 0.33214357, -0.058527369 0.010452077 0.33264342, -0.057904299 0.011339922 0.33214346, -0.057620194 0.010928351 0.33264342, -0.057227537 0.011939339 0.33214357, -0.05685319 0.011607733 0.33264345, -0.056713987 0.012683265 0.33214346, -0.056271259 0.012451049 0.33264351, -0.056393456 0.013528701 0.33214372, -0.055907931 0.013408896 0.33264351, -0.055784449 0.014426082 0.33264351, -0.056284457 0.014425989 0.33214357, -0.064284183 -0.0055741929 0.33264253, -0.063675366 -0.0064714924 0.33214238, -0.063784197 -0.0055741593 0.33214247, -0.064160697 -0.006591212 0.33264253, -0.063354738 -0.0073166974 0.33214247, -0.063797452 -0.0075491928 0.33264253, -0.062841281 -0.0080607273 0.33214247, -0.06321542 -0.0083923973 0.33264229, -0.062164519 -0.0086602829 0.33214238, -0.062448595 -0.009071704 0.33264223, -0.061364103 -0.0090803318 0.33214238, -0.061541382 -0.0095479451 0.33264223, -0.06048635 -0.0092966445 0.33214232, -0.060546592 -0.0097930096 0.33264223, -0.059582356 -0.009296637 0.33214238, -0.059521895 -0.0097931586 0.33264223, -0.058704518 -0.0090803765 0.33214232, -0.058527131 -0.0095479079 0.33264223, -0.057904027 -0.0086602457 0.33214238, -0.057619877 -0.0090718307 0.33264223, -0.056853063 -0.0083924122 0.33264223, -0.057227362 -0.0080607049 0.33214247, -0.056713823 -0.0073167495 0.33214247, -0.056271102 -0.007549081 0.33264253, -0.056393329 -0.0064713992 0.33214247, -0.055907726 -0.0065912306 0.33264259, -0.055784263 -0.0055740774 0.33264259, -0.056284335 -0.0055740364 0.33214262, -0.063784316 -0.0055737756 0.3281427, -0.063675292 -0.0064712688 0.32814255, -0.063354723 -0.0073165037 0.32814255, -0.062841207 -0.0080605261 0.32814246, -0.062164508 -0.00865997 0.32814246, -0.061363991 -0.0090802722 0.32814234, -0.060486261 -0.0092964582 0.32814258, -0.059582401 -0.0092963837 0.32814234, -0.058704574 -0.0090801083 0.32814246, -0.057904106 -0.0086599328 0.32814246, -0.05722744 -0.0080604814 0.32814246, -0.056713905 -0.0073164739 0.32814246, -0.056393228 -0.0064712092 0.32814255, -0.056284346 -0.0055737533 0.3281427, -0.063784383 0.014426149 0.32814378, -0.063675508 0.013528805 0.32814378, -0.063354924 0.012683608 0.3281436, -0.062841348 0.011939541 0.32814354, -0.062164709 0.01134013 0.32814354, -0.061364137 0.010919865 0.32814342, -0.060486455 0.010703687 0.3281436, -0.05958239 0.010703541 0.3281436, -0.058704641 0.010919821 0.32814342, -0.057904206 0.0113401 0.32814354, -0.057227496 0.011939604 0.32814378, -0.056713954 0.012683507 0.32814354, -0.056393351 0.01352885 0.3281436, -0.056284472 0.014426287 0.3281436, -0.060034428 0.0028263927 0.32664314, -0.060417268 0.0028728805 0.32664305, -0.060034383 0.0028259493 0.33264282, -0.060417268 0.0028724372 0.33264318, -0.060777936 0.0030094944 0.32664305, -0.06077788 0.0030091964 0.33264318, -0.061095305 0.0032287203 0.32664314, -0.061095338 0.0032282695 0.33264306, -0.061351113 0.0035174452 0.32664314, -0.06135105 0.0035170279 0.33264306, -0.061530478 0.003859099 0.3266432, -0.061530408 0.0038585328 0.33264285, -0.061622761 0.0042335913 0.32664314, -0.061622694 0.0042330809 0.33264306, -0.061622817 0.004619319 0.32664329, -0.061622668 0.0046188161 0.33264318, -0.061530456 0.0049936436 0.32664314, -0.061530385 0.0049932189 0.33264318, -0.061351214 0.0053353272 0.32664329, -0.061351139 0.0053347871 0.33264318, -0.06109539 0.0056239665 0.32664314, -0.061095316 0.0056234896 0.33264318, -0.060777944 0.0058430657 0.3266432, -0.060777929 0.005842682 0.33264318, -0.060417295 0.0059797727 0.32664329, -0.060417287 0.0059794523 0.33264318, -0.060034417 0.0060263313 0.32664329, -0.060034301 0.0060259402 0.33264318, -0.060034208 -0.0076736473 0.32664254, -0.060536813 -0.0076125748 0.32664254, -0.060034256 -0.0076738112 0.32814255, -0.060536817 -0.0076126643 0.32814258, -0.061010212 -0.0074331202 0.32664257, -0.061010182 -0.0074332468 0.32814255, -0.061426833 -0.0071455427 0.3266426, -0.061426893 -0.0071456917 0.32814258, -0.061762609 -0.0067665726 0.32664254, -0.061762579 -0.0067667514 0.3281427, -0.061997745 -0.0063183717 0.32664257, -0.061997872 -0.0063184053 0.32814246, -0.062119044 -0.0058268122 0.32664254, -0.062119018 -0.0058268756 0.32814255, -0.062119067 -0.0053205192 0.32664257, -0.062119007 -0.0053207874 0.3281427, -0.061997939 -0.0048290007 0.32664257, -0.061997831 -0.0048291311 0.3281427, -0.06176262 -0.0043806545 0.32664281, -0.06176265 -0.0043807738 0.32814255, -0.061426904 -0.0040018335 0.32664257, -0.0614269 -0.0040019527 0.3281427, -0.061010294 -0.003714148 0.32664257, -0.061010201 -0.0037143864 0.3281427, -0.060536843 -0.0035346933 0.32664257, -0.060536813 -0.0035348423 0.3281427, -0.060034223 -0.0034736805 0.32664257, -0.060034383 -0.0034736991 0.3281427, -0.060034368 0.01232627 0.32664365, -0.060536969 0.012387309 0.32664365, -0.060034491 0.01232633 0.3281436, -0.060536955 0.012387279 0.32814378, -0.06101032 0.012566891 0.32664365, -0.061010368 0.012566805 0.32814354, -0.0614269 0.012854476 0.32664344, -0.061427049 0.012854364 0.32814366, -0.061762698 0.013233479 0.32664365, -0.061762791 0.013233297 0.32814378, -0.061997909 0.013681639 0.32664365, -0.061997965 0.013681583 0.3281436, -0.062119126 0.014173172 0.32664365, -0.062119141 0.014172964 0.32814378, -0.062119126 0.01467951 0.32664365, -0.06211907 0.014679328 0.32814378, -0.061998006 0.015171014 0.32664365, -0.061997946 0.015170887 0.32814378, -0.061762717 0.015619241 0.32664379, -0.061762683 0.015619095 0.32814389, -0.061427023 0.015998211 0.32664371, -0.061426949 0.015998032 0.32814389, -0.061010394 0.016285833 0.32664379, -0.061010342 0.016285654 0.32814389, -0.060536981 0.01646537 0.32664371, -0.06053694 0.016465068 0.32814389, -0.060034458 0.016526405 0.32664388, -0.060034361 0.016526226 0.32814389, -0.059531823 0.016465377 0.32664379, -0.059531871 0.016465161 0.32814389, -0.05905854 0.016285609 0.32814389, -0.059058603 0.016285848 0.32664371, -0.058641903 0.01599808 0.32814389, -0.058641907 0.015998315 0.32664379, -0.05830618 0.015619233 0.32814389, -0.058306154 0.015619349 0.32664379, -0.058070906 0.015170917 0.32814378, -0.058070891 0.01517104 0.32664365, -0.057949726 0.014679447 0.32814378, -0.057949767 0.01467954 0.32664371, -0.057949815 0.014173165 0.3281436, -0.057949763 0.014173288 0.32664379, -0.058070906 0.01368155 0.3281436, -0.058070909 0.013681781 0.32664371, -0.05830615 0.013233352 0.32814378, -0.05830615 0.013233501 0.32664371, -0.058641877 0.012854345 0.3281436, -0.058641843 0.012854498 0.32664365, -0.059058584 0.012566812 0.3281436, -0.059058495 0.012566902 0.32664341, -0.059531901 0.012387313 0.3281436, -0.059531797 0.012387313 0.32664365, -0.069534168 -0.035074059 0.33264104, -0.05053417 -0.03507394 0.33264083, -0.06163631 -0.013179179 0.33264199, -0.061269298 -0.012479957 0.33264199, -0.061495274 -0.012807291 0.33264211, -0.060619328 -0.01203135 0.33264211, -0.060971618 -0.012216154 0.33264211, -0.059835318 -0.011936124 0.33264223, -0.06023312 -0.011936124 0.33264223, -0.059449166 -0.012031343 0.33264211, -0.058799222 -0.012479912 0.33264211, -0.059096888 -0.012216162 0.33264211, -0.0584323 -0.01317906 0.33264199, -0.058573224 -0.012807224 0.33264199, -0.061541431 -0.0016001649 0.33264267, -0.062448628 -0.0020763427 0.33264273, -0.060546588 -0.0013550222 0.33264285, -0.063215561 -0.0027557462 0.33264259, -0.063797511 -0.0035990551 0.33264273, -0.059521999 -0.0013550632 0.33264285, -0.059651524 0.0028724447 0.33264318, -0.059290774 0.0030092038 0.33264318, -0.058527183 -0.0016001947 0.33264282, -0.058973391 0.0032283776 0.33264285, -0.057620022 -0.0020763166 0.33264285, -0.058717586 0.003517013 0.33264294, -0.058538418 0.0038585775 0.33264294, -0.056853216 -0.0027557537 0.33264273, -0.05627111 -0.0035989471 0.33264259, -0.05844612 0.004233107 0.33264318, -0.064160831 -0.0045569353 0.33264261, -0.059651501 0.005979456 0.33264318, -0.059290878 0.005842749 0.33264318, -0.058973409 0.0056235567 0.33264306, -0.058717616 0.0053348914 0.33264318, -0.058538198 0.0049932413 0.33264318, -0.058446128 0.0046188608 0.33264318, -0.055907816 -0.0045568869 0.33264259, -0.061541524 0.018399708 0.33264366, -0.062448643 0.017923553 0.3326439, -0.060546726 0.018644903 0.33264378, -0.063215621 0.017244179 0.33264366, -0.059522182 0.018645089 0.33264402, -0.063797653 0.016400974 0.3326439, -0.061636545 0.022820886 0.33264416, -0.058527362 0.018399764 0.33264366, -0.057620209 0.017923668 0.33264366, -0.056853265 0.017244186 0.33264366, -0.05627121 0.016401108 0.33264378, -0.058432467 0.022820815 0.33264402, -0.060233474 0.024064008 0.33264425, -0.069534659 0.043925919 0.33264542, -0.060619641 0.023968812 0.33264416, -0.060971815 0.023783855 0.33264425, -0.061269589 0.023520082 0.33264416, -0.061495565 0.02319273 0.33264428, -0.064161018 0.015443157 0.33264378, -0.055908017 0.015443176 0.33264366, -0.05053464 0.043926038 0.33264542, -0.058573466 0.023192775 0.33264416, -0.058799401 0.023520123 0.33264416, -0.059097227 0.023783937 0.33264416, -0.05944939 0.02396873 0.33264416, -0.059835643 0.024063986 0.33264428, -0.050534051 -0.035573717 0.32714078, -0.050534051 -0.035574045 0.33214083, -0.06953425 -0.035573635 0.32714078, -0.069534123 -0.035574157 0.33214083, -0.070034198 -0.032573674 0.32664111, -0.050034132 -0.035073508 0.3266409, -0.070034176 -0.035073753 0.3266409, -0.050034102 -0.032573614 0.32664093, -0.070034146 -0.031573955 0.32964113, -0.050034028 -0.031573851 0.32764098, -0.070034191 -0.031573858 0.32764119, -0.050034147 -0.031573821 0.32964113, -0.070034228 -0.019573901 0.32964188, -0.050034218 -0.019573759 0.32964173, -0.070034191 -0.019573811 0.32764179, -0.050034236 -0.019573685 0.32764167, -0.057949591 -0.0058268011 0.32664254, -0.050034214 -0.018573668 0.32664165, -0.058070723 -0.0063183494 0.32664254, -0.058432266 -0.01317868 0.32664216, -0.05844605 0.0042335205 0.32664314, -0.057949543 -0.0053205453 0.3266426, -0.070034228 -0.018573795 0.32664186, -0.070034519 0.027426243 0.32664448, -0.060971797 0.023784254 0.32664424, -0.061269566 0.023520496 0.32664412, -0.050034486 0.027426371 0.32664448, -0.058446068 0.0046192221 0.32664329, -0.061495524 0.023193207 0.32664424, -0.060619537 0.023969173 0.32664424, -0.06163653 0.022821274 0.32664424, -0.060233358 0.024064336 0.32664424, -0.058432486 0.022821296 0.32664436, -0.058573551 0.023193251 0.32664412, -0.058799386 0.02352054 0.32664424, -0.05909726 0.023784321 0.32664424, -0.059449427 0.023969147 0.32664424, -0.059835572 0.024064336 0.32664412, -0.059651405 0.0059797764 0.3266432, -0.059290793 0.0058429874 0.32664314, -0.058973391 0.0056240074 0.3266432, -0.058717571 0.0053352527 0.32664329, -0.058538351 0.0049937405 0.32664329, -0.059651438 0.0028728284 0.32664314, -0.059531651 -0.0035347901 0.3266426, -0.05929083 0.0030095689 0.32664314, -0.059058402 -0.003714148 0.32664257, -0.058973346 0.003228765 0.32664314, -0.058641758 -0.004001759 0.32664257, -0.058717616 0.0035174601 0.32664329, -0.058306132 -0.0043806136 0.32664269, -0.058538388 0.0038591139 0.3266432, -0.058070783 -0.0048289597 0.32664281, -0.061269261 -0.012479592 0.32664222, -0.060971603 -0.01221573 0.32664222, -0.061495319 -0.012806859 0.32664225, -0.060619403 -0.012030821 0.32664225, -0.061636247 -0.013178851 0.32664198, -0.060233179 -0.011935677 0.32664225, -0.059531689 -0.0076125525 0.32664245, -0.059835318 -0.011935677 0.32664233, -0.059058372 -0.0074330531 0.32664245, -0.059449296 -0.012030873 0.32664225, -0.058641717 -0.0071454681 0.32664245, -0.059097029 -0.012215707 0.32664233, -0.058306016 -0.0067666695 0.32664257, -0.058799211 -0.012479473 0.32664216, -0.058573306 -0.012806889 0.32664233, -0.070034526 0.028426057 0.32964459, -0.050034434 0.028426182 0.32764438, -0.070034459 0.028426087 0.32764453, -0.050034534 0.028426178 0.3296445, -0.070034601 0.040426083 0.32964519, -0.050034594 0.040426236 0.32964519, -0.07003469 0.040426172 0.32764503, -0.050034493 0.040426265 0.32764521, -0.070034645 0.043926336 0.32664531, -0.050034586 0.041426402 0.3266452, -0.070034556 0.041426275 0.3266452, -0.050034571 0.043926403 0.32664531, -0.069534704 0.044426031 0.33214533, -0.050534602 0.044426333 0.3271454, -0.069534667 0.044426329 0.32714552, -0.050534751 0.044426151 0.33214533, -0.050034095 -0.035074066 0.33214095, -0.050034631 0.043926068 0.33214533, -0.070034169 -0.035074051 0.33214095, -0.070034623 0.043925948 0.33214524, -0.059531778 -0.0035347342 0.3281427, -0.059058361 -0.0037142523 0.3281427, -0.058641776 -0.0040017813 0.3281427, -0.058306046 -0.0043808557 0.3281427, -0.058070797 -0.0048291609 0.3281427, -0.057949618 -0.0053207427 0.3281427, -0.057949521 -0.0058270209 0.32814255, -0.058070667 -0.0063184686 0.32814246, -0.058305997 -0.0067667104 0.32814255, -0.058641672 -0.0071456917 0.32814258, -0.059058379 -0.0074332692 0.32814258, -0.05953167 -0.0076128058 0.32814258, -0.061364152 0.017932471 0.32814395, -0.062164735 0.017512493 0.32814389, -0.060486402 0.018148869 0.32814401, -0.05958236 0.018148851 0.32814398, -0.063675456 0.015323561 0.32814389, -0.056393497 0.015323784 0.32814378, -0.058704685 0.017932426 0.32814401, -0.056714039 0.016168978 0.32814389, -0.06335488 0.016168933 0.32814395, -0.057904251 0.017512456 0.32814378, -0.057227496 0.016912926 0.32814389, -0.062841482 0.016913012 0.32814389, -0.056393463 0.01532355 0.33214381, -0.056714028 0.01616874 0.33214381, -0.057227466 0.016912784 0.33214381, -0.057904232 0.017512165 0.33214393, -0.05870476 0.017932333 0.33214381, -0.059582528 0.018148784 0.33214402, -0.060486462 0.018148631 0.33214393, -0.061364226 0.017932326 0.33214393, -0.062164672 0.017512135 0.33214381, -0.062841348 0.016912717 0.33214393, -0.063354999 0.016168758 0.33214372, -0.063675486 0.015323445 0.33214372, -0.057904139 -0.0024875365 0.32814282, -0.058704618 -0.0020674355 0.32814285, -0.059582252 -0.001851093 0.32814282, -0.060486335 -0.0018510632 0.32814282, -0.063675404 -0.0046762861 0.3281427, -0.05639331 -0.0046763793 0.3281427, -0.061363999 -0.0020675734 0.32814285, -0.063354723 -0.0038311034 0.3281427, -0.062164608 -0.0024875812 0.32814282, -0.062841192 -0.0030870475 0.32814282, -0.056713872 -0.0038310997 0.3281427, -0.057227354 -0.0030870102 0.32814282, -0.056393411 -0.0046764798 0.33214265, -0.056713928 -0.0038311854 0.33214265, -0.057227414 -0.0030872785 0.33214265, -0.057904053 -0.0024878681 0.33214262, -0.05870454 -0.0020677261 0.33214265, -0.059582312 -0.001851391 0.33214286, -0.06048632 -0.0018514097 0.33214274, -0.061364088 -0.0020678118 0.33214274, -0.062164668 -0.002487883 0.33214286, -0.062841289 -0.0030872859 0.33214274, -0.063354783 -0.0038312562 0.33214265, -0.063675463 -0.0046765208 0.33214265, -0.058384433 0.014427107 0.31235951, -0.058384378 0.014427554 0.30635938, -0.058432411 0.0140322 0.31235951, -0.058432356 0.014032681 0.30635959, -0.058573421 0.013660353 0.31235951, -0.058573451 0.013660859 0.30635959, -0.058799259 0.013332825 0.31235951, -0.058799338 0.013333388 0.30635959, -0.059097107 0.013069194 0.31235936, -0.0590971 0.013069671 0.30635935, -0.059449319 0.012884326 0.31235951, -0.059449382 0.012884896 0.30635935, -0.059835631 0.012789164 0.31235951, -0.059835527 0.012789641 0.30635947, -0.060233351 0.01278916 0.31235951, -0.060233302 0.012789633 0.30635938, -0.060619604 0.012884315 0.3123593, -0.060619507 0.012884673 0.30635959, -0.060971837 0.013069205 0.31235951, -0.060971774 0.013069656 0.30635938, -0.061269429 0.0133329 0.31235936, -0.061269414 0.013333347 0.30635959, -0.061495431 0.013660338 0.31235951, -0.061495505 0.013660844 0.30635959, -0.061636511 0.014032148 0.31235951, -0.061636504 0.014032658 0.30635971, -0.061684415 0.014426973 0.31235951, -0.061684493 0.014427591 0.30635959, -0.058384277 -0.0055729263 0.31235826, -0.05838437 -0.0055724271 0.3063584, -0.058432214 -0.0059678592 0.31235832, -0.058432344 -0.0059672147 0.30635852, -0.05857328 -0.0063396879 0.31235841, -0.058573343 -0.0063391216 0.3063584, -0.05879923 -0.006667085 0.31235841, -0.058799315 -0.0066665784 0.30635855, -0.05909704 -0.0069309287 0.31235808, -0.059097067 -0.0069302693 0.3063584, -0.059449185 -0.0071157031 0.31235841, -0.059449259 -0.0071152411 0.30635852, -0.059835374 -0.0072109662 0.31235841, -0.059835404 -0.0072104894 0.3063584, -0.060233071 -0.0072109587 0.31235841, -0.060233191 -0.0072104819 0.30635828, -0.060619399 -0.0071157031 0.31235841, -0.060619477 -0.0071152486 0.3063584, -0.060971588 -0.0069309473 0.31235841, -0.060971651 -0.0069304742 0.3063584, -0.061269302 -0.0066670366 0.31235841, -0.06126941 -0.0066666715 0.3063584, -0.061495252 -0.0063397922 0.3123585, -0.061495375 -0.0063391402 0.30635834, -0.061636414 -0.0059677586 0.31235841, -0.06163631 -0.0059673861 0.30635852, -0.061684441 -0.0055728927 0.31235841, -0.061684292 -0.0055724494 0.30635855, -0.058573369 -0.0048054829 0.30635852, -0.0584324 -0.0051775016 0.3063584, -0.059449304 -0.0040295683 0.30635855, -0.050534047 -0.035072457 0.30635679, -0.059835393 -0.0039344989 0.30635852, -0.060233153 -0.0039345138 0.30635855, -0.069534242 -0.035072405 0.30635679, -0.060619388 -0.0040297993 0.30635864, -0.060971621 -0.004214514 0.30635852, -0.061269332 -0.004478287 0.30635852, -0.061495334 -0.0048056729 0.30635855, -0.061636344 -0.0051775686 0.3063584, -0.060233355 0.016065631 0.30635971, -0.050534595 0.043927766 0.30636129, -0.059835669 0.016065631 0.30635971, -0.059449334 0.015970387 0.30635971, -0.059097134 0.015785526 0.30635986, -0.058799319 0.01552169 0.30635959, -0.058573402 0.015194405 0.30635971, -0.058432329 0.014822409 0.30635959, -0.05909707 -0.004214488 0.30635852, -0.058799315 -0.004478205 0.3063584, -0.069534726 0.043927651 0.30636126, -0.061636511 0.01482239 0.30635971, -0.061495531 0.015194442 0.30635971, -0.061269514 0.015521672 0.30635959, -0.060971852 0.015785597 0.30635971, -0.060619589 0.015970346 0.30635959, -0.069534093 -0.035572965 0.31185669, -0.069534227 -0.035572503 0.30685681, -0.050534103 -0.035572853 0.31185681, -0.050534043 -0.035572436 0.30685681, -0.050034087 -0.032572877 0.31235689, -0.070034169 -0.032572981 0.31235671, -0.050034214 -0.035072755 0.31235683, -0.070034184 -0.035072986 0.31235671, -0.050034095 -0.031572755 0.30935687, -0.070034146 -0.031572793 0.31135684, -0.050034128 -0.031572726 0.31135693, -0.070034102 -0.031572845 0.30935696, -0.050034147 -0.019572679 0.3093577, -0.070034266 -0.019572746 0.30935749, -0.050034255 -0.019572604 0.31135768, -0.070034288 -0.019572731 0.31135768, -0.058799166 -0.0044788308 0.31235841, -0.058573261 -0.0048061498 0.31235841, -0.050034501 0.027427088 0.3123602, -0.059097122 0.01578505 0.31235951, -0.058799408 0.015521359 0.31235951, -0.059449218 -0.0040301383 0.3123585, -0.059096977 -0.0042149909 0.31235832, -0.058573402 0.015193898 0.31235951, -0.058432236 -0.0051781051 0.31235841, -0.059449337 0.01596994 0.31235951, -0.059835471 -0.0039348714 0.3123585, -0.058432415 0.014822025 0.31235951, -0.059835546 0.016065069 0.31235951, -0.070034519 0.027426902 0.3123602, -0.060233261 0.016065005 0.31235951, -0.060233243 -0.0039349645 0.3123585, -0.060619421 -0.0040301532 0.31235841, -0.060619511 0.015969906 0.31235951, -0.060971759 0.015784979 0.31235951, -0.060971741 -0.0042149015 0.31235841, -0.061269443 0.015521076 0.31235951, -0.06126938 -0.0044787489 0.31235841, -0.061495505 0.015193876 0.31235951, -0.061495397 -0.0048061572 0.31235841, -0.061636481 0.014822032 0.31235951, -0.061636336 -0.005178038 0.31235841, -0.050034326 -0.018572833 0.31235749, -0.070034243 -0.018572967 0.31235772, -0.050034493 0.028427314 0.30936041, -0.070034549 0.028427253 0.31136036, -0.050034478 0.028427253 0.31136036, -0.070034578 0.02842728 0.30936033, -0.050034586 0.040427279 0.30936092, -0.070034645 0.040427245 0.30936092, -0.050034609 0.040427364 0.31136101, -0.070034586 0.040427245 0.31136113, -0.050034571 0.043927055 0.31236103, -0.070034593 0.04142699 0.31236103, -0.050034557 0.041427203 0.31236094, -0.070034623 0.043926954 0.31236127, -0.050534602 0.044427644 0.30686122, -0.069534659 0.044427045 0.31186119, -0.050534602 0.044427164 0.31186134, -0.069534659 0.044427525 0.30686122, -0.070034221 -0.035072427 0.30685681, -0.070034713 0.043927647 0.30686122, -0.050034057 -0.035072502 0.30685669, -0.050034631 0.043927766 0.30686122, 0.061684981 0.014427859 0.31235951, 0.061684858 0.014428511 0.30635938, 0.061636891 0.014033038 0.31235936, 0.061636921 0.014033545 0.30635959, 0.061495904 0.013661105 0.31235936, 0.061495874 0.013661612 0.30635938, 0.061269868 0.013333723 0.31235936, 0.061269846 0.013334289 0.30635947, 0.060972165 0.013069998 0.31235936, 0.060972113 0.013070539 0.30635959, 0.060619958 0.012885135 0.31235936, 0.060619928 0.012885641 0.30635947, 0.060233708 0.012789972 0.31235936, 0.060233735 0.012790512 0.30635938, 0.059835974 0.012789879 0.31235936, 0.059835929 0.012790445 0.30635938, 0.05944977 0.012885012 0.31235936, 0.059449758 0.012885574 0.30635938, 0.059097532 0.013069987 0.31235936, 0.059097622 0.013070405 0.30635947, 0.05879977 0.013333738 0.31235951, 0.05879977 0.013334181 0.30635938, 0.058573861 0.01366109 0.31235936, 0.058573887 0.013661563 0.30635959, 0.058432762 0.014033016 0.31235951, 0.05843287 0.014033489 0.30635959, 0.058384776 0.014427926 0.31235936, 0.058384929 0.014428284 0.30635959, 0.061684977 -0.005571615 0.30635852, 0.061637003 -0.0059665069 0.3063584, 0.061685022 -0.0055721812 0.31235841, 0.061636999 -0.0059670061 0.31235832, 0.061495993 -0.0063383728 0.3063584, 0.061496127 -0.0063389689 0.31235841, 0.061270006 -0.006665729 0.3063584, 0.061270051 -0.0066662617 0.31235841, 0.060972296 -0.0069296248 0.3063584, 0.060972296 -0.0069299825 0.31235832, 0.060620092 -0.0071144067 0.3063584, 0.060620092 -0.0071149729 0.31235841, 0.060233798 -0.0072095953 0.3063584, 0.060233921 -0.0072101094 0.31235841, 0.059836052 -0.0072095953 0.3063584, 0.059836105 -0.0072101019 0.31235841, 0.059449848 -0.0071143918 0.3063584, 0.059449859 -0.0071148537 0.31235841, 0.059097651 -0.0069295764 0.3063584, 0.059097745 -0.0069301128 0.31235841, 0.058799889 -0.0066657476 0.3063584, 0.058799904 -0.0066661872 0.31235808, 0.058573943 -0.0063383915 0.3063584, 0.058573976 -0.0063388385 0.31235841, 0.058432836 -0.0059664436 0.30635852, 0.058432918 -0.0059670284 0.31235832, 0.058384944 -0.0055716224 0.3063584, 0.058385026 -0.0055721737 0.31235832, 0.061637059 -0.0051767789 0.3063584, 0.060620025 -0.0040288158 0.30635852, 0.069535218 -0.035071637 0.30635679, 0.060233835 -0.0039335713 0.30635852, 0.059449736 -0.004028827 0.30635852, 0.059836082 -0.003933724 0.30635852, 0.050535176 -0.035071764 0.30635661, 0.059097733 -0.0042137504 0.30635852, 0.058799852 -0.0044775046 0.30635852, 0.058573954 -0.0048047975 0.30635852, 0.058432903 -0.0051765852 0.30635852, 0.059835944 0.016066317 0.30635959, 0.06953463 0.043928429 0.30636129, 0.060233686 0.01606632 0.30635959, 0.060619894 0.015971076 0.30635971, 0.060972143 0.015786279 0.30635971, 0.061269961 0.015522435 0.30635971, 0.061495807 0.01519521 0.30635959, 0.061636891 0.014823366 0.30635959, 0.060972307 -0.0042137392 0.3063584, 0.061270006 -0.0044775195 0.30635852, 0.061495949 -0.0048047751 0.30635852, 0.050534725 0.043928251 0.30636105, 0.058432784 0.014823344 0.30635959, 0.058573868 0.015195187 0.30635959, 0.0587998 0.015522625 0.30635971, 0.05909751 0.015786324 0.30635971, 0.059449699 0.015971217 0.30635971, 0.069535159 -0.035572033 0.31185669, 0.050535139 -0.035572123 0.31185678, 0.069535203 -0.035571601 0.30685669, 0.050535236 -0.035571728 0.30685669, 0.070035227 -0.032572109 0.31235683, 0.05003519 -0.035072241 0.31235671, 0.070035174 -0.035072122 0.31235662, 0.050035138 -0.032572214 0.31235689, 0.070035078 -0.031571884 0.30935696, 0.050035056 -0.031571899 0.30935696, 0.070035234 -0.031571981 0.31135708, 0.05003516 -0.031571921 0.31135708, 0.07003504 -0.019571807 0.30935767, 0.050035089 -0.019571926 0.30935767, 0.070035025 -0.019571822 0.31135768, 0.050034951 -0.0195718 0.31135768, 0.060620092 -0.0040292963 0.31235841, 0.060972303 -0.0042140968 0.31235841, 0.061496004 -0.0048053898 0.31235841, 0.061637051 -0.0051771589 0.31235841, 0.070034847 0.027427834 0.3123602, 0.060972113 0.015785854 0.31235951, 0.061269827 0.015522141 0.31235951, 0.060233921 -0.0039341711 0.31235841, 0.061495803 0.015194733 0.31235969, 0.060619861 0.015970714 0.31235951, 0.061636936 0.0148228 0.31235936, 0.060233649 0.016065966 0.31235951, 0.05983603 -0.0039341748 0.31235832, 0.059449855 -0.0040293299 0.31235841, 0.050034821 0.02742774 0.31236008, 0.0598359 0.016065869 0.31235951, 0.059097722 -0.0042141862 0.31235832, 0.059449714 0.015970621 0.31235951, 0.059097543 0.015785847 0.31235951, 0.058799937 -0.0044780001 0.31235841, 0.058799874 0.015521947 0.31235951, 0.058573965 -0.00480536 0.31235841, 0.058573902 0.015194681 0.31235969, 0.058432952 -0.0051772967 0.31235841, 0.058432747 0.014822815 0.31235951, 0.07003507 -0.018572111 0.31235769, 0.050035093 -0.018572193 0.31235749, 0.061269987 -0.0044779666 0.31235841, 0.070034787 0.028428091 0.30936041, 0.050034761 0.028428081 0.30936041, 0.070034802 0.028428178 0.31136042, 0.050034732 0.028428175 0.31136036, 0.07003472 0.040428117 0.30936092, 0.050034653 0.04042802 0.30936101, 0.070034727 0.040428266 0.31136099, 0.05003475 0.04042802 0.31136099, 0.07003472 0.043927863 0.31236127, 0.050034646 0.043927826 0.31236115, 0.070034631 0.041427955 0.31236094, 0.050034687 0.041427705 0.31236094, 0.0695346 0.044428445 0.30686134, 0.050534684 0.0444283 0.30686122, 0.069534734 0.044427857 0.31186119, 0.050534684 0.044427793 0.31186119, 0.050035123 -0.035071764 0.30685681, 0.050034616 0.043928392 0.30686122, 0.07003516 -0.035071637 0.30685681, 0.070034623 0.043928429 0.30686104 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 3, 4, 5, -1, 6, 4, 3, -1, 7, 8, 9, -1, 10, 8, 7, -1, 11, 12, 13, -1, 13, 12, 14, -1, 15, 12, 16, -1, 14, 12, 15, -1, 2, 17, 18, -1, 1, 17, 2, -1, 5, 19, 20, -1, 20, 19, 1, -1, 16, 21, 6, -1, 6, 21, 4, -1, 22, 23, 10, -1, 10, 23, 8, -1, 1, 24, 17, -1, 19, 24, 1, -1, 4, 25, 5, -1, 5, 25, 19, -1, 11, 26, 12, -1, 12, 26, 16, -1, 16, 26, 21, -1, 18, 27, 22, -1, 22, 27, 23, -1, 19, 28, 24, -1, 25, 28, 19, -1, 4, 29, 25, -1, 21, 29, 4, -1, 17, 30, 18, -1, 18, 30, 27, -1, 29, 31, 25, -1, 32, 33, 34, -1, 25, 31, 28, -1, 21, 35, 29, -1, 36, 35, 11, -1, 11, 35, 26, -1, 26, 35, 21, -1, 17, 37, 30, -1, 24, 37, 17, -1, 29, 38, 31, -1, 36, 38, 35, -1, 35, 38, 29, -1, 24, 39, 37, -1, 28, 39, 24, -1, 28, 40, 39, -1, 31, 40, 28, -1, 31, 41, 40, -1, 38, 41, 31, -1, 36, 41, 38, -1, 42, 41, 36, -1, 40, 43, 39, -1, 44, 45, 43, -1, 46, 47, 48, -1, 44, 47, 45, -1, 42, 49, 41, -1, 49, 50, 44, -1, 51, 50, 42, -1, 42, 50, 49, -1, 52, 53, 51, -1, 51, 53, 50, -1, 50, 53, 44, -1, 39, 54, 37, -1, 55, 56, 57, -1, 43, 54, 39, -1, 57, 56, 58, -1, 45, 54, 43, -1, 59, 60, 55, -1, 45, 61, 54, -1, 55, 60, 56, -1, 62, 63, 46, -1, 47, 63, 45, -1, 46, 63, 47, -1, 45, 63, 61, -1, 41, 64, 40, -1, 44, 64, 49, -1, 65, 66, 59, -1, 40, 64, 43, -1, 43, 64, 44, -1, 59, 66, 60, -1, 49, 64, 41, -1, 48, 67, 52, -1, 47, 67, 48, -1, 52, 67, 53, -1, 44, 67, 47, -1, 53, 67, 44, -1, 58, 68, 69, -1, 37, 70, 30, -1, 56, 68, 58, -1, 54, 70, 37, -1, 61, 70, 54, -1, 71, 72, 65, -1, 61, 73, 70, -1, 74, 75, 62, -1, 65, 72, 66, -1, 62, 75, 63, -1, 63, 75, 61, -1, 61, 75, 73, -1, 30, 76, 27, -1, 68, 77, 69, -1, 70, 76, 30, -1, 73, 76, 70, -1, 60, 78, 56, -1, 56, 78, 68, -1, 73, 79, 76, -1, 80, 81, 71, -1, 82, 83, 74, -1, 74, 83, 75, -1, 75, 83, 73, -1, 73, 83, 79, -1, 71, 81, 72, -1, 79, 84, 76, -1, 76, 84, 27, -1, 78, 85, 68, -1, 27, 84, 23, -1, 86, 87, 82, -1, 68, 85, 77, -1, 82, 87, 83, -1, 83, 87, 79, -1, 60, 88, 78, -1, 84, 89, 23, -1, 66, 88, 60, -1, 23, 89, 8, -1, 90, 91, 80, -1, 80, 91, 81, -1, 84, 92, 89, -1, 69, 93, 94, -1, 84, 95, 92, -1, 79, 96, 84, -1, 77, 93, 69, -1, 87, 96, 79, -1, 84, 96, 95, -1, 97, 98, 86, -1, 88, 99, 78, -1, 86, 98, 87, -1, 96, 98, 95, -1, 87, 98, 96, -1, 78, 99, 85, -1, 8, 100, 9, -1, 89, 100, 8, -1, 72, 101, 66, -1, 92, 100, 89, -1, 66, 101, 88, -1, 102, 103, 90, -1, 97, 104, 98, -1, 95, 104, 92, -1, 98, 104, 95, -1, 100, 105, 9, -1, 9, 105, 106, -1, 90, 103, 91, -1, 85, 107, 77, -1, 92, 108, 100, -1, 77, 107, 93, -1, 100, 108, 105, -1, 105, 108, 109, -1, 109, 108, 104, -1, 104, 108, 92, -1, 104, 110, 109, -1, 101, 111, 88, -1, 88, 111, 99, -1, 72, 112, 101, -1, 97, 113, 104, -1, 104, 113, 110, -1, 114, 113, 97, -1, 115, 113, 114, -1, 81, 112, 72, -1, 105, 116, 106, -1, 109, 116, 105, -1, 110, 116, 109, -1, 102, 117, 103, -1, 113, 118, 110, -1, 115, 118, 113, -1, 119, 117, 102, -1, 120, 118, 115, -1, 116, 121, 106, -1, 122, 121, 123, -1, 93, 124, 94, -1, 106, 121, 122, -1, 85, 125, 107, -1, 33, 126, 127, -1, 121, 126, 123, -1, 116, 126, 121, -1, 123, 126, 128, -1, 128, 126, 33, -1, 99, 125, 85, -1, 101, 129, 111, -1, 126, 130, 127, -1, 116, 130, 126, -1, 118, 131, 110, -1, 112, 129, 101, -1, 116, 131, 130, -1, 110, 131, 116, -1, 127, 132, 120, -1, 130, 132, 127, -1, 120, 132, 118, -1, 81, 133, 112, -1, 118, 132, 131, -1, 131, 132, 130, -1, 91, 133, 81, -1, 119, 134, 117, -1, 135, 134, 119, -1, 107, 136, 93, -1, 93, 136, 124, -1, 124, 137, 94, -1, 94, 137, 138, -1, 99, 139, 125, -1, 111, 139, 99, -1, 133, 140, 112, -1, 112, 140, 129, -1, 91, 141, 133, -1, 103, 141, 91, -1, 142, 143, 135, -1, 135, 143, 134, -1, 107, 144, 136, -1, 125, 144, 107, -1, 136, 145, 124, -1, 124, 145, 137, -1, 129, 146, 111, -1, 111, 146, 139, -1, 133, 147, 140, -1, 141, 147, 133, -1, 117, 148, 103, -1, 103, 148, 141, -1, 142, 149, 143, -1, 150, 149, 142, -1, 139, 151, 125, -1, 125, 151, 144, -1, 137, 152, 138, -1, 144, 153, 136, -1, 136, 153, 145, -1, 140, 154, 129, -1, 129, 154, 146, -1, 141, 155, 147, -1, 148, 155, 141, -1, 134, 156, 117, -1, 117, 156, 148, -1, 157, 158, 150, -1, 150, 158, 149, -1, 146, 159, 139, -1, 139, 159, 151, -1, 138, 160, 32, -1, 152, 160, 138, -1, 145, 161, 137, -1, 137, 161, 152, -1, 144, 162, 153, -1, 151, 162, 144, -1, 140, 163, 154, -1, 147, 163, 140, -1, 156, 164, 148, -1, 148, 164, 155, -1, 143, 165, 134, -1, 134, 165, 156, -1, 166, 167, 168, -1, 168, 167, 169, -1, 169, 167, 157, -1, 157, 167, 158, -1, 146, 170, 159, -1, 154, 170, 146, -1, 161, 171, 152, -1, 152, 171, 160, -1, 145, 172, 161, -1, 153, 172, 145, -1, 151, 173, 162, -1, 159, 173, 151, -1, 155, 174, 147, -1, 147, 174, 163, -1, 165, 175, 156, -1, 156, 175, 164, -1, 143, 176, 165, -1, 149, 176, 143, -1, 154, 177, 170, -1, 163, 177, 154, -1, 172, 178, 161, -1, 161, 178, 171, -1, 153, 179, 172, -1, 162, 179, 153, -1, 159, 180, 173, -1, 170, 180, 159, -1, 32, 128, 33, -1, 160, 128, 32, -1, 164, 181, 155, -1, 155, 181, 174, -1, 176, 182, 165, -1, 165, 182, 175, -1, 158, 183, 149, -1, 149, 183, 176, -1, 174, 184, 163, -1, 163, 184, 177, -1, 172, 185, 178, -1, 179, 185, 172, -1, 173, 186, 162, -1, 162, 186, 179, -1, 177, 187, 170, -1, 170, 187, 180, -1, 160, 123, 128, -1, 171, 123, 160, -1, 175, 188, 164, -1, 164, 188, 181, -1, 176, 189, 182, -1, 183, 189, 176, -1, 190, 191, 166, -1, 167, 191, 158, -1, 158, 191, 183, -1, 166, 191, 167, -1, 174, 192, 184, -1, 181, 192, 174, -1, 179, 7, 185, -1, 186, 7, 179, -1, 180, 193, 173, -1, 173, 193, 186, -1, 177, 0, 187, -1, 184, 0, 177, -1, 178, 122, 171, -1, 171, 122, 123, -1, 182, 194, 175, -1, 175, 194, 188, -1, 13, 195, 190, -1, 190, 195, 191, -1, 183, 195, 189, -1, 191, 195, 183, -1, 188, 3, 181, -1, 181, 3, 192, -1, 193, 10, 186, -1, 186, 10, 7, -1, 180, 196, 193, -1, 187, 196, 180, -1, 192, 20, 184, -1, 184, 20, 0, -1, 178, 106, 122, -1, 185, 106, 178, -1, 182, 15, 194, -1, 189, 15, 182, -1, 194, 6, 188, -1, 188, 6, 3, -1, 196, 22, 193, -1, 193, 22, 10, -1, 187, 2, 196, -1, 0, 2, 187, -1, 192, 5, 20, -1, 3, 5, 192, -1, 185, 9, 106, -1, 7, 9, 185, -1, 195, 14, 189, -1, 13, 14, 195, -1, 189, 14, 15, -1, 15, 16, 194, -1, 194, 16, 6, -1, 196, 18, 22, -1, 2, 18, 196, -1, 20, 1, 0, -1, 197, 198, 199, -1, 200, 201, 202, -1, 200, 203, 201, -1, 204, 205, 206, -1, 204, 207, 205, -1, 208, 209, 210, -1, 208, 211, 209, -1, 212, 213, 214, -1, 212, 214, 215, -1, 216, 199, 217, -1, 216, 217, 207, -1, 218, 210, 219, -1, 218, 219, 220, -1, 221, 200, 202, -1, 221, 202, 222, -1, 223, 224, 197, -1, 223, 220, 224, -1, 225, 226, 203, -1, 225, 227, 228, -1, 225, 203, 200, -1, 225, 228, 226, -1, 229, 207, 204, -1, 229, 216, 207, -1, 230, 211, 208, -1, 230, 222, 211, -1, 231, 206, 213, -1, 231, 213, 212, -1, 232, 197, 199, -1, 232, 199, 216, -1, 233, 210, 218, -1, 233, 208, 210, -1, 234, 200, 221, -1, 234, 227, 225, -1, 234, 225, 200, -1, 235, 220, 223, -1, 235, 218, 220, -1, 236, 216, 229, -1, 236, 232, 216, -1, 237, 221, 222, -1, 237, 222, 230, -1, 238, 204, 206, -1, 238, 206, 231, -1, 239, 223, 197, -1, 239, 197, 232, -1, 240, 230, 208, -1, 240, 208, 233, -1, 241, 233, 218, -1, 241, 218, 235, -1, 242, 239, 232, -1, 242, 232, 236, -1, 243, 221, 237, -1, 243, 244, 227, -1, 243, 227, 234, -1, 243, 234, 221, -1, 245, 229, 204, -1, 245, 204, 238, -1, 246, 223, 239, -1, 246, 235, 223, -1, 247, 230, 240, -1, 247, 237, 230, -1, 248, 240, 233, -1, 249, 250, 251, -1, 248, 233, 241, -1, 252, 239, 242, -1, 253, 254, 255, -1, 252, 246, 239, -1, 253, 255, 256, -1, 257, 258, 254, -1, 259, 229, 245, -1, 259, 236, 229, -1, 260, 241, 235, -1, 257, 254, 253, -1, 260, 235, 246, -1, 261, 262, 258, -1, 263, 244, 243, -1, 263, 237, 247, -1, 263, 243, 237, -1, 264, 247, 240, -1, 261, 258, 257, -1, 265, 256, 266, -1, 264, 240, 248, -1, 265, 253, 256, -1, 267, 268, 262, -1, 269, 260, 246, -1, 269, 246, 252, -1, 270, 242, 236, -1, 267, 262, 261, -1, 270, 236, 259, -1, 271, 248, 241, -1, 272, 266, 273, -1, 271, 241, 260, -1, 272, 265, 266, -1, 274, 247, 264, -1, 275, 257, 253, -1, 274, 276, 244, -1, 274, 244, 263, -1, 274, 263, 247, -1, 275, 253, 265, -1, 277, 278, 268, -1, 279, 260, 269, -1, 279, 271, 260, -1, 280, 252, 242, -1, 277, 268, 267, -1, 280, 242, 270, -1, 281, 264, 248, -1, 281, 248, 271, -1, 282, 265, 272, -1, 282, 275, 265, -1, 283, 271, 279, -1, 283, 281, 271, -1, 284, 261, 257, -1, 284, 257, 275, -1, 285, 269, 252, -1, 285, 252, 280, -1, 286, 272, 273, -1, 287, 288, 278, -1, 289, 274, 264, -1, 289, 276, 274, -1, 289, 264, 281, -1, 290, 276, 289, -1, 290, 250, 276, -1, 290, 281, 283, -1, 290, 289, 281, -1, 287, 278, 277, -1, 291, 275, 282, -1, 292, 279, 269, -1, 292, 269, 285, -1, 291, 284, 275, -1, 293, 279, 292, -1, 293, 283, 279, -1, 294, 295, 251, -1, 294, 251, 250, -1, 294, 290, 283, -1, 294, 250, 290, -1, 296, 267, 261, -1, 294, 293, 295, -1, 294, 283, 293, -1, 296, 261, 284, -1, 297, 282, 272, -1, 297, 272, 286, -1, 298, 299, 288, -1, 300, 301, 302, -1, 300, 303, 301, -1, 304, 305, 306, -1, 304, 303, 305, -1, 298, 288, 287, -1, 304, 301, 303, -1, 307, 306, 308, -1, 309, 273, 310, -1, 307, 304, 306, -1, 307, 301, 304, -1, 311, 308, 312, -1, 309, 286, 273, -1, 311, 312, 302, -1, 311, 302, 301, -1, 311, 307, 308, -1, 311, 301, 307, -1, 313, 284, 291, -1, 314, 215, 315, -1, 314, 315, 303, -1, 313, 296, 284, -1, 314, 303, 300, -1, 316, 314, 300, -1, 317, 277, 267, -1, 317, 267, 296, -1, 318, 300, 302, -1, 318, 316, 300, -1, 319, 282, 297, -1, 318, 302, 320, -1, 318, 320, 321, -1, 322, 314, 316, -1, 322, 215, 314, -1, 322, 212, 215, -1, 319, 291, 282, -1, 323, 324, 299, -1, 325, 322, 316, -1, 326, 325, 316, -1, 326, 316, 318, -1, 326, 318, 321, -1, 326, 321, 327, -1, 323, 299, 298, -1, 328, 212, 322, -1, 328, 322, 325, -1, 329, 286, 309, -1, 328, 231, 212, -1, 329, 297, 286, -1, 330, 328, 325, -1, 331, 296, 313, -1, 332, 325, 326, -1, 332, 330, 325, -1, 331, 317, 296, -1, 332, 326, 327, -1, 332, 327, 333, -1, 334, 238, 231, -1, 335, 309, 310, -1, 334, 231, 328, -1, 334, 328, 330, -1, 336, 277, 317, -1, 336, 287, 277, -1, 337, 334, 330, -1, 338, 333, 339, -1, 338, 330, 332, -1, 338, 332, 333, -1, 338, 337, 330, -1, 340, 291, 319, -1, 341, 245, 238, -1, 341, 334, 337, -1, 340, 313, 291, -1, 341, 238, 334, -1, 342, 324, 323, -1, 342, 343, 324, -1, 344, 341, 337, -1, 345, 339, 346, -1, 345, 338, 339, -1, 345, 337, 338, -1, 345, 344, 337, -1, 347, 245, 341, -1, 348, 319, 297, -1, 348, 297, 329, -1, 347, 341, 344, -1, 347, 259, 245, -1, 349, 346, 350, -1, 351, 336, 317, -1, 349, 345, 346, -1, 351, 317, 331, -1, 349, 344, 345, -1, 349, 347, 344, -1, 352, 259, 347, -1, 352, 270, 259, -1, 353, 309, 335, -1, 353, 329, 309, -1, 354, 347, 349, -1, 354, 352, 347, -1, 355, 287, 336, -1, 355, 298, 287, -1, 356, 352, 354, -1, 356, 354, 349, -1, 357, 356, 349, -1, 358, 313, 340, -1, 359, 350, 360, -1, 358, 331, 313, -1, 359, 349, 350, -1, 361, 343, 342, -1, 359, 357, 349, -1, 361, 362, 343, -1, 363, 280, 270, -1, 363, 270, 352, -1, 363, 352, 356, -1, 363, 356, 357, -1, 364, 310, 365, -1, 366, 360, 367, -1, 366, 359, 360, -1, 366, 357, 359, -1, 366, 363, 357, -1, 364, 335, 310, -1, 368, 340, 319, -1, 369, 285, 280, -1, 369, 280, 363, -1, 368, 319, 348, -1, 370, 369, 363, -1, 371, 367, 372, -1, 371, 366, 367, -1, 373, 336, 351, -1, 371, 363, 366, -1, 371, 370, 363, -1, 373, 355, 336, -1, 374, 285, 369, -1, 374, 369, 370, -1, 374, 292, 285, -1, 375, 292, 374, -1, 376, 348, 329, -1, 375, 372, 377, -1, 376, 329, 353, -1, 375, 377, 295, -1, 375, 371, 372, -1, 375, 293, 292, -1, 375, 295, 293, -1, 375, 370, 371, -1, 378, 323, 298, -1, 375, 374, 370, -1, 378, 298, 355, -1, 379, 364, 365, -1, 380, 351, 331, -1, 380, 331, 358, -1, 381, 362, 361, -1, 381, 382, 362, -1, 383, 353, 335, -1, 383, 335, 364, -1, 384, 340, 368, -1, 384, 358, 340, -1, 385, 355, 373, -1, 385, 378, 355, -1, 386, 368, 348, -1, 386, 348, 376, -1, 387, 342, 323, -1, 387, 323, 378, -1, 388, 364, 379, -1, 388, 383, 364, -1, 389, 351, 380, -1, 389, 373, 351, -1, 390, 391, 382, -1, 390, 382, 381, -1, 392, 353, 383, -1, 392, 376, 353, -1, 393, 358, 384, -1, 393, 380, 358, -1, 394, 378, 385, -1, 394, 387, 378, -1, 395, 368, 386, -1, 395, 384, 368, -1, 396, 342, 387, -1, 396, 361, 342, -1, 397, 392, 383, -1, 397, 383, 388, -1, 398, 385, 373, -1, 398, 373, 389, -1, 305, 365, 306, -1, 305, 379, 365, -1, 201, 399, 391, -1, 201, 391, 390, -1, 400, 386, 376, -1, 400, 376, 392, -1, 401, 380, 393, -1, 401, 389, 380, -1, 402, 387, 394, -1, 402, 396, 387, -1, 403, 384, 395, -1, 403, 393, 384, -1, 404, 361, 396, -1, 404, 381, 361, -1, 214, 392, 397, -1, 214, 400, 392, -1, 405, 394, 385, -1, 405, 385, 398, -1, 303, 388, 379, -1, 303, 379, 305, -1, 203, 406, 399, -1, 203, 399, 201, -1, 407, 395, 386, -1, 407, 386, 400, -1, 198, 398, 389, -1, 198, 389, 401, -1, 209, 404, 396, -1, 209, 396, 402, -1, 217, 401, 393, -1, 217, 393, 403, -1, 408, 381, 404, -1, 408, 390, 381, -1, 213, 400, 214, -1, 213, 407, 400, -1, 219, 402, 394, -1, 219, 394, 405, -1, 315, 397, 388, -1, 315, 388, 303, -1, 226, 406, 203, -1, 226, 228, 409, -1, 226, 410, 406, -1, 226, 409, 410, -1, 205, 403, 395, -1, 205, 395, 407, -1, 224, 405, 398, -1, 224, 398, 198, -1, 211, 404, 209, -1, 211, 408, 404, -1, 199, 198, 401, -1, 199, 401, 217, -1, 202, 201, 390, -1, 202, 390, 408, -1, 206, 205, 407, -1, 206, 407, 213, -1, 210, 402, 219, -1, 210, 209, 402, -1, 215, 397, 315, -1, 215, 214, 397, -1, 207, 403, 205, -1, 207, 217, 403, -1, 220, 219, 405, -1, 220, 405, 224, -1, 222, 408, 211, -1, 222, 202, 408, -1, 197, 224, 198, -1, 411, 412, 413, -1, 414, 415, 416, -1, 417, 415, 414, -1, 418, 419, 420, -1, 421, 419, 418, -1, 422, 423, 424, -1, 424, 423, 425, -1, 426, 423, 427, -1, 425, 423, 426, -1, 413, 428, 429, -1, 412, 428, 413, -1, 416, 430, 431, -1, 431, 430, 412, -1, 427, 432, 417, -1, 417, 432, 415, -1, 433, 434, 421, -1, 421, 434, 419, -1, 412, 435, 428, -1, 430, 435, 412, -1, 415, 436, 416, -1, 416, 436, 430, -1, 422, 437, 423, -1, 423, 437, 427, -1, 427, 437, 432, -1, 429, 438, 433, -1, 433, 438, 434, -1, 430, 439, 435, -1, 436, 439, 430, -1, 415, 440, 436, -1, 432, 440, 415, -1, 428, 441, 429, -1, 429, 441, 438, -1, 440, 442, 436, -1, 436, 442, 439, -1, 443, 444, 445, -1, 432, 446, 440, -1, 447, 446, 422, -1, 422, 446, 437, -1, 437, 446, 432, -1, 428, 448, 441, -1, 435, 448, 428, -1, 440, 449, 442, -1, 447, 449, 446, -1, 446, 449, 440, -1, 435, 450, 448, -1, 439, 450, 435, -1, 439, 451, 450, -1, 442, 451, 439, -1, 442, 452, 451, -1, 449, 452, 442, -1, 447, 452, 449, -1, 453, 452, 447, -1, 451, 454, 450, -1, 455, 456, 454, -1, 457, 458, 459, -1, 455, 458, 456, -1, 453, 460, 452, -1, 460, 461, 455, -1, 462, 461, 453, -1, 453, 461, 460, -1, 463, 464, 462, -1, 462, 464, 461, -1, 461, 464, 455, -1, 450, 465, 448, -1, 454, 465, 450, -1, 466, 467, 468, -1, 468, 467, 469, -1, 456, 465, 454, -1, 470, 471, 466, -1, 456, 472, 465, -1, 466, 471, 467, -1, 473, 474, 457, -1, 457, 474, 458, -1, 458, 474, 456, -1, 456, 474, 472, -1, 454, 475, 455, -1, 452, 475, 451, -1, 455, 475, 460, -1, 476, 477, 470, -1, 451, 475, 454, -1, 460, 475, 452, -1, 470, 477, 471, -1, 459, 478, 463, -1, 458, 478, 459, -1, 463, 478, 464, -1, 455, 478, 458, -1, 464, 478, 455, -1, 448, 479, 441, -1, 469, 480, 481, -1, 465, 479, 448, -1, 467, 480, 469, -1, 472, 479, 465, -1, 482, 483, 476, -1, 472, 484, 479, -1, 485, 486, 473, -1, 473, 486, 474, -1, 476, 483, 477, -1, 474, 486, 472, -1, 472, 486, 484, -1, 441, 487, 438, -1, 480, 488, 481, -1, 479, 487, 441, -1, 484, 487, 479, -1, 471, 489, 467, -1, 467, 489, 480, -1, 484, 490, 487, -1, 491, 492, 485, -1, 493, 494, 482, -1, 485, 492, 486, -1, 486, 492, 484, -1, 484, 492, 490, -1, 482, 494, 483, -1, 490, 495, 487, -1, 489, 496, 480, -1, 487, 495, 438, -1, 438, 495, 434, -1, 497, 498, 491, -1, 480, 496, 488, -1, 491, 498, 492, -1, 492, 498, 490, -1, 471, 499, 489, -1, 477, 499, 471, -1, 495, 500, 434, -1, 434, 500, 419, -1, 501, 502, 493, -1, 493, 502, 494, -1, 500, 503, 504, -1, 490, 503, 495, -1, 498, 503, 490, -1, 495, 503, 500, -1, 481, 505, 506, -1, 504, 503, 498, -1, 488, 505, 481, -1, 499, 507, 489, -1, 498, 508, 504, -1, 509, 510, 497, -1, 497, 510, 498, -1, 498, 510, 508, -1, 489, 507, 496, -1, 504, 511, 500, -1, 500, 511, 419, -1, 483, 512, 477, -1, 477, 512, 499, -1, 508, 511, 504, -1, 510, 513, 508, -1, 514, 515, 501, -1, 516, 513, 509, -1, 509, 513, 510, -1, 511, 517, 419, -1, 420, 517, 518, -1, 501, 515, 502, -1, 419, 517, 420, -1, 496, 519, 488, -1, 488, 519, 505, -1, 511, 520, 517, -1, 511, 521, 520, -1, 508, 522, 511, -1, 512, 523, 499, -1, 499, 523, 507, -1, 511, 522, 521, -1, 483, 524, 512, -1, 513, 522, 508, -1, 516, 525, 513, -1, 513, 525, 522, -1, 522, 525, 521, -1, 526, 525, 516, -1, 494, 524, 483, -1, 520, 527, 517, -1, 514, 528, 515, -1, 517, 527, 518, -1, 518, 527, 529, -1, 521, 530, 520, -1, 525, 530, 521, -1, 531, 528, 514, -1, 526, 530, 525, -1, 529, 532, 533, -1, 505, 534, 506, -1, 527, 532, 529, -1, 496, 535, 519, -1, 532, 536, 533, -1, 520, 537, 527, -1, 507, 535, 496, -1, 536, 537, 530, -1, 527, 537, 532, -1, 512, 538, 523, -1, 532, 537, 536, -1, 530, 537, 520, -1, 444, 539, 540, -1, 524, 538, 512, -1, 530, 539, 536, -1, 536, 539, 533, -1, 533, 539, 541, -1, 541, 539, 444, -1, 526, 542, 530, -1, 494, 543, 524, -1, 544, 542, 526, -1, 540, 542, 544, -1, 539, 542, 540, -1, 530, 542, 539, -1, 502, 543, 494, -1, 531, 545, 528, -1, 546, 545, 531, -1, 519, 547, 505, -1, 505, 547, 534, -1, 534, 548, 506, -1, 506, 548, 549, -1, 507, 550, 535, -1, 523, 550, 507, -1, 543, 551, 524, -1, 524, 551, 538, -1, 502, 552, 543, -1, 515, 552, 502, -1, 553, 554, 546, -1, 546, 554, 545, -1, 519, 555, 547, -1, 535, 555, 519, -1, 547, 556, 534, -1, 534, 556, 548, -1, 538, 557, 523, -1, 523, 557, 550, -1, 543, 558, 551, -1, 552, 558, 543, -1, 528, 559, 515, -1, 515, 559, 552, -1, 553, 560, 554, -1, 561, 560, 553, -1, 550, 562, 535, -1, 535, 562, 555, -1, 548, 563, 549, -1, 555, 564, 547, -1, 547, 564, 556, -1, 551, 565, 538, -1, 538, 565, 557, -1, 552, 566, 558, -1, 559, 566, 552, -1, 545, 567, 528, -1, 528, 567, 559, -1, 568, 569, 561, -1, 561, 569, 560, -1, 557, 570, 550, -1, 550, 570, 562, -1, 549, 571, 443, -1, 563, 571, 549, -1, 556, 572, 548, -1, 548, 572, 563, -1, 555, 573, 564, -1, 562, 573, 555, -1, 551, 574, 565, -1, 558, 574, 551, -1, 567, 575, 559, -1, 559, 575, 566, -1, 554, 576, 545, -1, 545, 576, 567, -1, 577, 578, 579, -1, 579, 578, 580, -1, 580, 578, 568, -1, 568, 578, 569, -1, 557, 581, 570, -1, 565, 581, 557, -1, 572, 582, 563, -1, 563, 582, 571, -1, 556, 583, 572, -1, 564, 583, 556, -1, 562, 584, 573, -1, 570, 584, 562, -1, 566, 585, 558, -1, 558, 585, 574, -1, 576, 586, 567, -1, 567, 586, 575, -1, 554, 587, 576, -1, 560, 587, 554, -1, 565, 588, 581, -1, 574, 588, 565, -1, 583, 589, 572, -1, 572, 589, 582, -1, 564, 590, 583, -1, 573, 590, 564, -1, 570, 591, 584, -1, 581, 591, 570, -1, 443, 541, 444, -1, 571, 541, 443, -1, 575, 592, 566, -1, 566, 592, 585, -1, 576, 593, 586, -1, 587, 593, 576, -1, 569, 594, 560, -1, 560, 594, 587, -1, 585, 595, 574, -1, 574, 595, 588, -1, 583, 596, 589, -1, 590, 596, 583, -1, 584, 597, 573, -1, 573, 597, 590, -1, 588, 598, 581, -1, 581, 598, 591, -1, 571, 533, 541, -1, 582, 533, 571, -1, 586, 599, 575, -1, 575, 599, 592, -1, 587, 600, 593, -1, 594, 600, 587, -1, 601, 602, 577, -1, 578, 602, 569, -1, 569, 602, 594, -1, 577, 602, 578, -1, 585, 603, 595, -1, 592, 603, 585, -1, 590, 418, 596, -1, 597, 418, 590, -1, 591, 604, 584, -1, 584, 604, 597, -1, 588, 411, 598, -1, 595, 411, 588, -1, 589, 529, 582, -1, 582, 529, 533, -1, 593, 605, 586, -1, 586, 605, 599, -1, 424, 606, 601, -1, 601, 606, 602, -1, 594, 606, 600, -1, 602, 606, 594, -1, 599, 414, 592, -1, 592, 414, 603, -1, 604, 421, 597, -1, 597, 421, 418, -1, 591, 607, 604, -1, 598, 607, 591, -1, 603, 431, 595, -1, 595, 431, 411, -1, 589, 518, 529, -1, 596, 518, 589, -1, 593, 426, 605, -1, 600, 426, 593, -1, 605, 417, 599, -1, 599, 417, 414, -1, 607, 433, 604, -1, 604, 433, 421, -1, 598, 413, 607, -1, 411, 413, 598, -1, 603, 416, 431, -1, 414, 416, 603, -1, 596, 420, 518, -1, 418, 420, 596, -1, 606, 425, 600, -1, 424, 425, 606, -1, 600, 425, 426, -1, 426, 427, 605, -1, 605, 427, 417, -1, 607, 429, 433, -1, 413, 429, 607, -1, 431, 412, 411, -1, 608, 609, 610, -1, 611, 612, 613, -1, 611, 614, 612, -1, 615, 616, 617, -1, 615, 618, 616, -1, 619, 620, 621, -1, 619, 622, 620, -1, 623, 624, 625, -1, 623, 625, 626, -1, 627, 610, 628, -1, 627, 628, 618, -1, 629, 630, 631, -1, 629, 621, 630, -1, 632, 613, 633, -1, 632, 611, 613, -1, 634, 631, 608, -1, 635, 636, 614, -1, 635, 637, 638, -1, 635, 614, 611, -1, 635, 638, 636, -1, 639, 627, 618, -1, 639, 618, 615, -1, 640, 633, 622, -1, 640, 622, 619, -1, 641, 624, 623, -1, 641, 617, 624, -1, 642, 608, 610, -1, 642, 610, 627, -1, 643, 619, 621, -1, 643, 621, 629, -1, 643, 640, 619, -1, 644, 611, 632, -1, 644, 637, 635, -1, 644, 635, 611, -1, 645, 631, 634, -1, 645, 629, 631, -1, 646, 627, 639, -1, 646, 642, 627, -1, 647, 632, 633, -1, 647, 633, 640, -1, 648, 615, 617, -1, 648, 617, 641, -1, 649, 634, 608, -1, 649, 608, 642, -1, 650, 640, 643, -1, 651, 650, 643, -1, 651, 643, 629, -1, 651, 629, 645, -1, 652, 642, 646, -1, 652, 649, 642, -1, 653, 654, 637, -1, 653, 637, 644, -1, 653, 632, 647, -1, 653, 644, 632, -1, 655, 639, 615, -1, 655, 615, 648, -1, 656, 634, 649, -1, 656, 645, 634, -1, 657, 647, 640, -1, 658, 659, 660, -1, 657, 640, 650, -1, 661, 662, 663, -1, 664, 650, 651, -1, 665, 649, 652, -1, 661, 663, 666, -1, 667, 668, 662, -1, 665, 656, 649, -1, 669, 639, 655, -1, 667, 662, 661, -1, 670, 671, 668, -1, 669, 646, 639, -1, 672, 651, 645, -1, 672, 645, 656, -1, 673, 653, 647, -1, 670, 668, 667, -1, 674, 666, 675, -1, 673, 654, 653, -1, 673, 647, 657, -1, 676, 657, 650, -1, 676, 650, 664, -1, 674, 661, 666, -1, 677, 678, 671, -1, 679, 672, 656, -1, 679, 656, 665, -1, 677, 671, 670, -1, 680, 675, 681, -1, 682, 646, 669, -1, 682, 652, 646, -1, 680, 674, 675, -1, 683, 667, 661, -1, 684, 651, 672, -1, 684, 664, 651, -1, 685, 686, 654, -1, 685, 657, 676, -1, 685, 673, 657, -1, 685, 654, 673, -1, 683, 661, 674, -1, 687, 688, 678, -1, 689, 672, 679, -1, 689, 684, 672, -1, 687, 678, 677, -1, 690, 652, 682, -1, 690, 665, 652, -1, 691, 674, 680, -1, 692, 676, 664, -1, 691, 683, 674, -1, 692, 664, 684, -1, 693, 670, 667, -1, 693, 667, 683, -1, 694, 684, 689, -1, 694, 692, 684, -1, 695, 680, 681, -1, 696, 679, 665, -1, 697, 698, 688, -1, 696, 665, 690, -1, 699, 686, 685, -1, 699, 685, 676, -1, 699, 676, 692, -1, 697, 688, 687, -1, 700, 683, 691, -1, 701, 659, 686, -1, 701, 686, 699, -1, 701, 692, 694, -1, 701, 699, 692, -1, 702, 689, 679, -1, 702, 679, 696, -1, 700, 693, 683, -1, 703, 689, 702, -1, 703, 694, 689, -1, 704, 677, 670, -1, 704, 670, 693, -1, 705, 706, 660, -1, 705, 660, 659, -1, 707, 691, 680, -1, 705, 659, 701, -1, 705, 701, 694, -1, 705, 703, 706, -1, 705, 694, 703, -1, 707, 680, 695, -1, 708, 709, 698, -1, 708, 698, 697, -1, 710, 711, 712, -1, 710, 712, 713, -1, 714, 681, 715, -1, 716, 717, 718, -1, 716, 711, 717, -1, 714, 695, 681, -1, 716, 712, 711, -1, 719, 712, 716, -1, 719, 718, 720, -1, 721, 693, 700, -1, 719, 716, 718, -1, 722, 720, 723, -1, 722, 723, 713, -1, 722, 712, 719, -1, 722, 713, 712, -1, 721, 704, 693, -1, 722, 719, 720, -1, 724, 626, 725, -1, 724, 725, 711, -1, 726, 687, 677, -1, 724, 711, 710, -1, 726, 677, 704, -1, 727, 724, 710, -1, 728, 691, 707, -1, 729, 713, 730, -1, 729, 730, 731, -1, 729, 710, 713, -1, 729, 727, 710, -1, 728, 700, 691, -1, 732, 733, 709, -1, 734, 626, 724, -1, 734, 623, 626, -1, 734, 724, 727, -1, 735, 734, 727, -1, 732, 709, 708, -1, 736, 735, 727, -1, 737, 695, 714, -1, 736, 729, 731, -1, 736, 731, 738, -1, 736, 727, 729, -1, 737, 707, 695, -1, 739, 734, 735, -1, 739, 641, 623, -1, 739, 623, 734, -1, 740, 704, 721, -1, 741, 739, 735, -1, 740, 726, 704, -1, 742, 714, 715, -1, 743, 735, 736, -1, 743, 741, 735, -1, 743, 736, 738, -1, 743, 738, 744, -1, 745, 687, 726, -1, 745, 697, 687, -1, 746, 648, 641, -1, 746, 739, 741, -1, 746, 641, 739, -1, 747, 700, 728, -1, 748, 746, 741, -1, 749, 744, 750, -1, 749, 741, 743, -1, 749, 743, 744, -1, 747, 721, 700, -1, 751, 733, 732, -1, 749, 748, 741, -1, 752, 655, 648, -1, 752, 648, 746, -1, 751, 753, 733, -1, 752, 746, 748, -1, 754, 752, 748, -1, 755, 728, 707, -1, 756, 750, 757, -1, 756, 749, 750, -1, 756, 748, 749, -1, 755, 707, 737, -1, 756, 754, 748, -1, 758, 669, 655, -1, 759, 745, 726, -1, 758, 752, 754, -1, 759, 726, 740, -1, 758, 655, 752, -1, 760, 757, 761, -1, 760, 756, 757, -1, 760, 754, 756, -1, 760, 758, 754, -1, 762, 714, 742, -1, 762, 737, 714, -1, 763, 682, 669, -1, 763, 669, 758, -1, 764, 697, 745, -1, 765, 758, 760, -1, 764, 708, 697, -1, 765, 763, 758, -1, 766, 765, 760, -1, 766, 763, 765, -1, 767, 721, 747, -1, 767, 740, 721, -1, 768, 753, 751, -1, 769, 766, 760, -1, 768, 770, 753, -1, 771, 761, 772, -1, 771, 760, 761, -1, 771, 769, 760, -1, 773, 715, 774, -1, 775, 682, 763, -1, 775, 690, 682, -1, 775, 763, 766, -1, 775, 766, 769, -1, 773, 742, 715, -1, 776, 747, 728, -1, 777, 772, 778, -1, 777, 775, 769, -1, 777, 771, 772, -1, 777, 769, 771, -1, 776, 728, 755, -1, 779, 690, 775, -1, 779, 696, 690, -1, 780, 745, 759, -1, 780, 764, 745, -1, 781, 779, 775, -1, 782, 778, 783, -1, 782, 777, 778, -1, 782, 775, 777, -1, 782, 781, 775, -1, 784, 755, 737, -1, 784, 737, 762, -1, 785, 696, 779, -1, 785, 779, 781, -1, 785, 702, 696, -1, 786, 732, 708, -1, 787, 783, 788, -1, 787, 788, 706, -1, 787, 782, 783, -1, 787, 785, 781, -1, 786, 708, 764, -1, 787, 706, 703, -1, 787, 781, 782, -1, 787, 703, 702, -1, 789, 773, 774, -1, 787, 702, 785, -1, 790, 759, 740, -1, 790, 740, 767, -1, 791, 770, 768, -1, 791, 792, 770, -1, 793, 762, 742, -1, 793, 742, 773, -1, 794, 747, 776, -1, 794, 767, 747, -1, 795, 764, 780, -1, 795, 786, 764, -1, 796, 776, 755, -1, 796, 755, 784, -1, 797, 751, 732, -1, 797, 732, 786, -1, 798, 773, 789, -1, 798, 793, 773, -1, 799, 759, 790, -1, 799, 780, 759, -1, 800, 801, 792, -1, 800, 792, 791, -1, 802, 762, 793, -1, 802, 784, 762, -1, 803, 767, 794, -1, 803, 790, 767, -1, 804, 786, 795, -1, 804, 797, 786, -1, 805, 776, 796, -1, 805, 794, 776, -1, 806, 751, 797, -1, 806, 768, 751, -1, 807, 802, 793, -1, 807, 793, 798, -1, 808, 795, 780, -1, 808, 780, 799, -1, 717, 774, 718, -1, 717, 789, 774, -1, 612, 809, 801, -1, 612, 801, 800, -1, 810, 796, 784, -1, 810, 784, 802, -1, 811, 790, 803, -1, 811, 808, 799, -1, 811, 799, 790, -1, 812, 797, 804, -1, 812, 806, 797, -1, 813, 794, 805, -1, 813, 803, 794, -1, 814, 768, 806, -1, 814, 791, 768, -1, 625, 802, 807, -1, 625, 810, 802, -1, 815, 804, 795, -1, 815, 795, 808, -1, 711, 798, 789, -1, 711, 789, 717, -1, 614, 816, 809, -1, 614, 809, 612, -1, 817, 805, 796, -1, 817, 796, 810, -1, 609, 808, 811, -1, 620, 814, 806, -1, 620, 806, 812, -1, 628, 811, 803, -1, 628, 803, 813, -1, 628, 609, 811, -1, 818, 791, 814, -1, 818, 800, 791, -1, 624, 810, 625, -1, 624, 817, 810, -1, 630, 812, 804, -1, 630, 804, 815, -1, 725, 807, 798, -1, 725, 798, 711, -1, 636, 816, 614, -1, 636, 638, 819, -1, 636, 820, 816, -1, 636, 819, 820, -1, 616, 813, 805, -1, 616, 805, 817, -1, 821, 630, 815, -1, 821, 815, 808, -1, 821, 808, 609, -1, 622, 814, 620, -1, 622, 818, 814, -1, 610, 609, 628, -1, 613, 612, 800, -1, 613, 800, 818, -1, 617, 817, 624, -1, 617, 616, 817, -1, 621, 812, 630, -1, 621, 620, 812, -1, 626, 807, 725, -1, 626, 625, 807, -1, 618, 813, 616, -1, 618, 628, 813, -1, 631, 630, 821, -1, 633, 818, 622, -1, 633, 613, 818, -1, 608, 631, 821, -1, 608, 821, 609, -1, 822, 823, 824, -1, 825, 826, 827, -1, 828, 826, 825, -1, 829, 830, 831, -1, 832, 830, 829, -1, 833, 834, 835, -1, 835, 834, 836, -1, 836, 834, 837, -1, 824, 838, 839, -1, 823, 838, 824, -1, 827, 840, 841, -1, 841, 840, 823, -1, 837, 842, 828, -1, 828, 842, 826, -1, 843, 844, 832, -1, 832, 844, 830, -1, 823, 845, 838, -1, 840, 845, 823, -1, 826, 846, 827, -1, 827, 846, 840, -1, 833, 847, 834, -1, 837, 847, 842, -1, 834, 847, 837, -1, 839, 848, 843, -1, 843, 848, 844, -1, 840, 849, 845, -1, 846, 849, 840, -1, 826, 850, 846, -1, 842, 850, 826, -1, 838, 851, 839, -1, 839, 851, 848, -1, 850, 852, 846, -1, 846, 852, 849, -1, 842, 853, 850, -1, 854, 855, 856, -1, 857, 853, 833, -1, 833, 853, 847, -1, 847, 853, 842, -1, 838, 858, 851, -1, 845, 858, 838, -1, 857, 859, 853, -1, 850, 859, 852, -1, 853, 859, 850, -1, 845, 860, 858, -1, 849, 860, 845, -1, 849, 861, 860, -1, 852, 861, 849, -1, 857, 862, 859, -1, 852, 862, 861, -1, 863, 862, 857, -1, 859, 862, 852, -1, 861, 864, 860, -1, 865, 866, 864, -1, 867, 868, 869, -1, 865, 868, 866, -1, 863, 870, 862, -1, 870, 871, 865, -1, 872, 871, 863, -1, 863, 871, 870, -1, 872, 873, 871, -1, 874, 873, 872, -1, 871, 873, 865, -1, 860, 875, 858, -1, 864, 875, 860, -1, 866, 875, 864, -1, 876, 877, 878, -1, 878, 877, 879, -1, 866, 880, 875, -1, 881, 882, 876, -1, 883, 884, 867, -1, 867, 884, 868, -1, 876, 882, 877, -1, 868, 884, 866, -1, 866, 884, 880, -1, 862, 885, 861, -1, 865, 885, 870, -1, 861, 885, 864, -1, 864, 885, 865, -1, 870, 885, 862, -1, 886, 887, 881, -1, 874, 888, 873, -1, 869, 888, 874, -1, 881, 887, 882, -1, 868, 888, 869, -1, 865, 888, 868, -1, 873, 888, 865, -1, 858, 889, 851, -1, 875, 889, 858, -1, 879, 890, 891, -1, 880, 889, 875, -1, 877, 890, 879, -1, 892, 893, 886, -1, 880, 894, 889, -1, 895, 896, 883, -1, 883, 896, 884, -1, 884, 896, 880, -1, 880, 896, 894, -1, 886, 893, 887, -1, 851, 897, 848, -1, 889, 897, 851, -1, 890, 898, 891, -1, 894, 897, 889, -1, 882, 899, 877, -1, 894, 900, 897, -1, 877, 899, 890, -1, 901, 902, 895, -1, 895, 902, 896, -1, 896, 902, 894, -1, 903, 904, 892, -1, 894, 902, 900, -1, 900, 905, 897, -1, 892, 904, 893, -1, 897, 905, 848, -1, 848, 905, 844, -1, 899, 906, 890, -1, 907, 908, 901, -1, 890, 906, 898, -1, 901, 908, 902, -1, 902, 908, 900, -1, 905, 909, 844, -1, 882, 910, 899, -1, 844, 909, 830, -1, 887, 910, 882, -1, 911, 912, 903, -1, 903, 912, 904, -1, 900, 913, 905, -1, 908, 913, 900, -1, 905, 913, 909, -1, 914, 913, 908, -1, 909, 913, 914, -1, 891, 915, 916, -1, 898, 915, 891, -1, 908, 917, 914, -1, 918, 919, 907, -1, 910, 920, 899, -1, 907, 919, 908, -1, 908, 919, 917, -1, 899, 920, 906, -1, 917, 921, 914, -1, 909, 921, 830, -1, 893, 922, 887, -1, 914, 921, 909, -1, 887, 922, 910, -1, 919, 923, 917, -1, 924, 923, 918, -1, 925, 926, 911, -1, 918, 923, 919, -1, 921, 927, 830, -1, 831, 927, 928, -1, 830, 927, 831, -1, 911, 926, 912, -1, 921, 929, 927, -1, 906, 930, 898, -1, 898, 930, 915, -1, 921, 931, 929, -1, 917, 932, 921, -1, 921, 932, 931, -1, 922, 933, 910, -1, 910, 933, 920, -1, 923, 932, 917, -1, 924, 934, 923, -1, 893, 935, 922, -1, 923, 934, 932, -1, 932, 934, 931, -1, 936, 934, 924, -1, 929, 937, 927, -1, 904, 935, 893, -1, 925, 938, 926, -1, 927, 937, 928, -1, 928, 937, 939, -1, 931, 940, 929, -1, 934, 940, 931, -1, 936, 940, 934, -1, 941, 938, 925, -1, 939, 942, 943, -1, 937, 942, 939, -1, 915, 944, 916, -1, 942, 945, 943, -1, 906, 946, 930, -1, 940, 947, 929, -1, 929, 947, 937, -1, 942, 947, 945, -1, 920, 946, 906, -1, 937, 947, 942, -1, 945, 947, 940, -1, 922, 948, 933, -1, 855, 949, 950, -1, 945, 949, 943, -1, 940, 949, 945, -1, 935, 948, 922, -1, 943, 949, 951, -1, 951, 949, 855, -1, 936, 952, 940, -1, 953, 952, 936, -1, 950, 952, 953, -1, 904, 954, 935, -1, 940, 952, 949, -1, 949, 952, 950, -1, 912, 954, 904, -1, 941, 955, 938, -1, 956, 955, 941, -1, 930, 957, 915, -1, 915, 957, 944, -1, 944, 958, 916, -1, 916, 958, 959, -1, 920, 960, 946, -1, 933, 960, 920, -1, 954, 961, 935, -1, 935, 961, 948, -1, 912, 962, 954, -1, 926, 962, 912, -1, 963, 964, 956, -1, 956, 964, 955, -1, 930, 965, 957, -1, 946, 965, 930, -1, 957, 966, 944, -1, 944, 966, 958, -1, 948, 967, 933, -1, 933, 967, 960, -1, 954, 968, 961, -1, 962, 968, 954, -1, 938, 969, 926, -1, 926, 969, 962, -1, 970, 971, 963, -1, 963, 971, 964, -1, 960, 972, 946, -1, 946, 972, 965, -1, 958, 973, 959, -1, 965, 974, 957, -1, 957, 974, 966, -1, 961, 975, 948, -1, 948, 975, 967, -1, 962, 976, 968, -1, 969, 976, 962, -1, 955, 977, 938, -1, 938, 977, 969, -1, 978, 979, 970, -1, 970, 979, 971, -1, 967, 980, 960, -1, 960, 980, 972, -1, 959, 981, 854, -1, 973, 981, 959, -1, 966, 982, 958, -1, 958, 982, 973, -1, 965, 983, 974, -1, 972, 983, 965, -1, 961, 984, 975, -1, 968, 984, 961, -1, 977, 985, 969, -1, 969, 985, 976, -1, 955, 986, 977, -1, 964, 986, 955, -1, 987, 988, 989, -1, 978, 988, 979, -1, 989, 988, 990, -1, 990, 988, 978, -1, 967, 991, 980, -1, 975, 991, 967, -1, 982, 992, 973, -1, 973, 992, 981, -1, 966, 993, 982, -1, 974, 993, 966, -1, 972, 994, 983, -1, 980, 994, 972, -1, 976, 995, 968, -1, 968, 995, 984, -1, 986, 996, 977, -1, 977, 996, 985, -1, 964, 997, 986, -1, 971, 997, 964, -1, 975, 998, 991, -1, 984, 998, 975, -1, 993, 999, 982, -1, 982, 999, 992, -1, 974, 1000, 993, -1, 983, 1000, 974, -1, 980, 1001, 994, -1, 991, 1001, 980, -1, 854, 951, 855, -1, 981, 951, 854, -1, 985, 1002, 976, -1, 976, 1002, 995, -1, 997, 1003, 986, -1, 986, 1003, 996, -1, 971, 1004, 997, -1, 979, 1004, 971, -1, 995, 1005, 984, -1, 984, 1005, 998, -1, 1002, 1005, 995, -1, 993, 1006, 999, -1, 1000, 1006, 993, -1, 994, 1007, 983, -1, 983, 1007, 1000, -1, 998, 1008, 991, -1, 991, 1008, 1001, -1, 981, 943, 951, -1, 992, 943, 981, -1, 985, 1009, 1002, -1, 996, 1009, 985, -1, 997, 1010, 1003, -1, 1004, 1010, 997, -1, 987, 1011, 988, -1, 1012, 1011, 987, -1, 988, 1011, 979, -1, 979, 1011, 1004, -1, 1002, 1013, 1005, -1, 1000, 829, 1006, -1, 1007, 829, 1000, -1, 1001, 1014, 994, -1, 994, 1014, 1007, -1, 998, 822, 1008, -1, 1005, 822, 998, -1, 999, 939, 992, -1, 992, 939, 943, -1, 1003, 1015, 996, -1, 996, 1015, 1009, -1, 1012, 1016, 1011, -1, 835, 1016, 1012, -1, 1004, 1016, 1010, -1, 1011, 1016, 1004, -1, 1002, 825, 1013, -1, 1009, 825, 1002, -1, 1014, 832, 1007, -1, 1007, 832, 829, -1, 1001, 1017, 1014, -1, 1008, 1017, 1001, -1, 1013, 841, 1005, -1, 1005, 841, 822, -1, 999, 928, 939, -1, 1006, 928, 999, -1, 1003, 1018, 1015, -1, 1010, 1018, 1003, -1, 1015, 828, 1009, -1, 1009, 828, 825, -1, 1018, 828, 1015, -1, 1017, 843, 1014, -1, 1014, 843, 832, -1, 1008, 824, 1017, -1, 822, 824, 1008, -1, 1013, 827, 841, -1, 825, 827, 1013, -1, 1006, 831, 928, -1, 829, 831, 1006, -1, 1016, 836, 1010, -1, 1010, 836, 1018, -1, 835, 836, 1016, -1, 1018, 837, 828, -1, 836, 837, 1018, -1, 1017, 839, 843, -1, 824, 839, 1017, -1, 841, 823, 822, -1, 1019, 1020, 1021, -1, 1022, 1023, 1024, -1, 1022, 1025, 1023, -1, 1026, 1027, 1028, -1, 1026, 1029, 1027, -1, 1030, 1031, 1032, -1, 1030, 1033, 1031, -1, 1034, 1035, 1036, -1, 1034, 1037, 1035, -1, 1038, 1039, 1029, -1, 1038, 1040, 1039, -1, 1041, 1032, 1042, -1, 1041, 1042, 1043, -1, 1044, 1022, 1024, -1, 1044, 1024, 1045, -1, 1046, 1043, 1020, -1, 1046, 1020, 1019, -1, 1047, 1048, 1025, -1, 1047, 1049, 1050, -1, 1047, 1025, 1022, -1, 1047, 1050, 1048, -1, 1051, 1029, 1026, -1, 1051, 1038, 1029, -1, 1052, 1045, 1033, -1, 1052, 1033, 1030, -1, 1053, 1037, 1034, -1, 1053, 1028, 1037, -1, 1054, 1019, 1040, -1, 1054, 1040, 1038, -1, 1055, 1030, 1032, -1, 1055, 1032, 1041, -1, 1056, 1022, 1044, -1, 1056, 1049, 1047, -1, 1056, 1047, 1022, -1, 1057, 1043, 1046, -1, 1057, 1041, 1043, -1, 1058, 1038, 1051, -1, 1058, 1054, 1038, -1, 1059, 1044, 1045, -1, 1059, 1045, 1052, -1, 1060, 1028, 1053, -1, 1060, 1026, 1028, -1, 1061, 1019, 1054, -1, 1061, 1046, 1019, -1, 1062, 1052, 1030, -1, 1062, 1030, 1055, -1, 1063, 1055, 1041, -1, 1063, 1041, 1057, -1, 1064, 1061, 1054, -1, 1064, 1054, 1058, -1, 1065, 1044, 1059, -1, 1065, 1066, 1049, -1, 1065, 1049, 1056, -1, 1065, 1056, 1044, -1, 1067, 1051, 1026, -1, 1067, 1026, 1060, -1, 1068, 1046, 1061, -1, 1068, 1057, 1046, -1, 1069, 1052, 1062, -1, 1070, 1071, 1072, -1, 1069, 1065, 1059, -1, 1069, 1059, 1052, -1, 1073, 1074, 1075, -1, 1076, 1062, 1055, -1, 1076, 1055, 1063, -1, 1073, 1075, 1077, -1, 1078, 1068, 1061, -1, 1078, 1061, 1064, -1, 1079, 1080, 1074, -1, 1079, 1074, 1073, -1, 1081, 1051, 1067, -1, 1082, 1083, 1080, -1, 1081, 1058, 1051, -1, 1084, 1057, 1068, -1, 1084, 1063, 1057, -1, 1082, 1080, 1079, -1, 1085, 1066, 1065, -1, 1086, 1077, 1087, -1, 1085, 1065, 1069, -1, 1088, 1069, 1062, -1, 1086, 1073, 1077, -1, 1089, 1090, 1083, -1, 1088, 1085, 1069, -1, 1088, 1062, 1076, -1, 1091, 1068, 1078, -1, 1089, 1083, 1082, -1, 1091, 1084, 1068, -1, 1092, 1058, 1081, -1, 1092, 1064, 1058, -1, 1093, 1087, 1094, -1, 1093, 1086, 1087, -1, 1095, 1076, 1063, -1, 1096, 1079, 1073, -1, 1095, 1063, 1084, -1, 1097, 1066, 1085, -1, 1097, 1098, 1066, -1, 1096, 1073, 1086, -1, 1097, 1085, 1088, -1, 1099, 1100, 1090, -1, 1101, 1084, 1091, -1, 1101, 1095, 1084, -1, 1099, 1090, 1089, -1, 1102, 1078, 1064, -1, 1102, 1064, 1092, -1, 1103, 1086, 1093, -1, 1103, 1096, 1086, -1, 1104, 1088, 1076, -1, 1104, 1076, 1095, -1, 1105, 1082, 1079, -1, 1105, 1079, 1096, -1, 1106, 1095, 1101, -1, 1106, 1104, 1095, -1, 1107, 1093, 1094, -1, 1108, 1091, 1078, -1, 1109, 1110, 1100, -1, 1108, 1078, 1102, -1, 1111, 1088, 1104, -1, 1111, 1098, 1097, -1, 1111, 1097, 1088, -1, 1109, 1100, 1099, -1, 1112, 1096, 1103, -1, 1113, 1071, 1098, -1, 1113, 1098, 1111, -1, 1113, 1104, 1106, -1, 1113, 1111, 1104, -1, 1114, 1091, 1108, -1, 1112, 1105, 1096, -1, 1114, 1101, 1091, -1, 1115, 1089, 1082, -1, 1116, 1106, 1101, -1, 1115, 1082, 1105, -1, 1116, 1101, 1114, -1, 1117, 1118, 1072, -1, 1117, 1072, 1071, -1, 1119, 1103, 1093, -1, 1117, 1113, 1106, -1, 1117, 1071, 1113, -1, 1117, 1116, 1118, -1, 1117, 1106, 1116, -1, 1119, 1093, 1107, -1, 1120, 1121, 1110, -1, 1122, 1123, 1124, -1, 1120, 1110, 1109, -1, 1122, 1124, 1125, -1, 1126, 1094, 1127, -1, 1128, 1129, 1130, -1, 1128, 1123, 1129, -1, 1126, 1107, 1094, -1, 1128, 1124, 1123, -1, 1131, 1124, 1128, -1, 1131, 1130, 1132, -1, 1133, 1105, 1112, -1, 1131, 1128, 1130, -1, 1134, 1132, 1135, -1, 1134, 1135, 1125, -1, 1134, 1124, 1131, -1, 1134, 1125, 1124, -1, 1133, 1115, 1105, -1, 1134, 1131, 1132, -1, 1136, 1036, 1137, -1, 1136, 1137, 1123, -1, 1138, 1099, 1089, -1, 1136, 1123, 1122, -1, 1138, 1089, 1115, -1, 1139, 1136, 1122, -1, 1140, 1103, 1119, -1, 1141, 1125, 1142, -1, 1141, 1142, 1143, -1, 1141, 1139, 1122, -1, 1141, 1122, 1125, -1, 1140, 1112, 1103, -1, 1144, 1036, 1136, -1, 1145, 1146, 1121, -1, 1144, 1034, 1036, -1, 1144, 1136, 1139, -1, 1147, 1144, 1139, -1, 1145, 1121, 1120, -1, 1148, 1141, 1143, -1, 1149, 1107, 1126, -1, 1148, 1147, 1139, -1, 1148, 1143, 1150, -1, 1148, 1139, 1141, -1, 1149, 1119, 1107, -1, 1151, 1034, 1144, -1, 1151, 1053, 1034, -1, 1152, 1115, 1133, -1, 1151, 1144, 1147, -1, 1152, 1138, 1115, -1, 1153, 1151, 1147, -1, 1154, 1126, 1127, -1, 1155, 1147, 1148, -1, 1155, 1148, 1150, -1, 1155, 1150, 1156, -1, 1157, 1099, 1138, -1, 1155, 1153, 1147, -1, 1157, 1109, 1099, -1, 1158, 1053, 1151, -1, 1158, 1151, 1153, -1, 1158, 1060, 1053, -1, 1159, 1112, 1140, -1, 1160, 1158, 1153, -1, 1161, 1156, 1162, -1, 1161, 1155, 1156, -1, 1161, 1153, 1155, -1, 1159, 1133, 1112, -1, 1163, 1146, 1145, -1, 1161, 1160, 1153, -1, 1164, 1060, 1158, -1, 1164, 1158, 1160, -1, 1163, 1165, 1146, -1, 1164, 1067, 1060, -1, 1166, 1164, 1160, -1, 1167, 1140, 1119, -1, 1168, 1162, 1169, -1, 1168, 1161, 1162, -1, 1167, 1119, 1149, -1, 1168, 1160, 1161, -1, 1168, 1166, 1160, -1, 1170, 1081, 1067, -1, 1171, 1157, 1138, -1, 1171, 1138, 1152, -1, 1170, 1164, 1166, -1, 1170, 1067, 1164, -1, 1172, 1169, 1173, -1, 1172, 1168, 1169, -1, 1172, 1166, 1168, -1, 1172, 1170, 1166, -1, 1174, 1126, 1154, -1, 1175, 1092, 1081, -1, 1174, 1149, 1126, -1, 1175, 1081, 1170, -1, 1176, 1109, 1157, -1, 1176, 1120, 1109, -1, 1177, 1170, 1172, -1, 1177, 1175, 1170, -1, 1178, 1175, 1177, -1, 1179, 1133, 1159, -1, 1179, 1152, 1133, -1, 1180, 1165, 1163, -1, 1180, 1181, 1165, -1, 1182, 1177, 1172, -1, 1182, 1178, 1177, -1, 1183, 1173, 1184, -1, 1183, 1172, 1173, -1, 1183, 1182, 1172, -1, 1185, 1127, 1186, -1, 1187, 1092, 1175, -1, 1187, 1175, 1178, -1, 1187, 1102, 1092, -1, 1185, 1154, 1127, -1, 1187, 1178, 1182, -1, 1188, 1159, 1140, -1, 1189, 1184, 1190, -1, 1189, 1187, 1182, -1, 1189, 1183, 1184, -1, 1189, 1182, 1183, -1, 1188, 1140, 1167, -1, 1191, 1102, 1187, -1, 1191, 1108, 1102, -1, 1192, 1157, 1171, -1, 1192, 1176, 1157, -1, 1193, 1191, 1187, -1, 1194, 1190, 1195, -1, 1194, 1189, 1190, -1, 1194, 1187, 1189, -1, 1196, 1167, 1149, -1, 1194, 1193, 1187, -1, 1196, 1149, 1174, -1, 1197, 1108, 1191, -1, 1197, 1191, 1193, -1, 1198, 1145, 1120, -1, 1197, 1114, 1108, -1, 1199, 1195, 1200, -1, 1199, 1200, 1118, -1, 1199, 1194, 1195, -1, 1198, 1120, 1176, -1, 1199, 1114, 1197, -1, 1199, 1118, 1116, -1, 1199, 1193, 1194, -1, 1201, 1185, 1186, -1, 1199, 1116, 1114, -1, 1199, 1197, 1193, -1, 1202, 1171, 1152, -1, 1202, 1152, 1179, -1, 1203, 1181, 1180, -1, 1203, 1204, 1181, -1, 1205, 1174, 1154, -1, 1205, 1154, 1185, -1, 1206, 1159, 1188, -1, 1206, 1179, 1159, -1, 1207, 1176, 1192, -1, 1207, 1198, 1176, -1, 1208, 1188, 1167, -1, 1208, 1167, 1196, -1, 1209, 1163, 1145, -1, 1209, 1145, 1198, -1, 1210, 1185, 1201, -1, 1210, 1205, 1185, -1, 1211, 1171, 1202, -1, 1211, 1192, 1171, -1, 1212, 1213, 1204, -1, 1212, 1204, 1203, -1, 1214, 1174, 1205, -1, 1214, 1196, 1174, -1, 1215, 1179, 1206, -1, 1215, 1202, 1179, -1, 1215, 1211, 1202, -1, 1216, 1198, 1207, -1, 1216, 1209, 1198, -1, 1217, 1188, 1208, -1, 1217, 1206, 1188, -1, 1218, 1163, 1209, -1, 1218, 1180, 1163, -1, 1219, 1214, 1205, -1, 1219, 1205, 1210, -1, 1220, 1207, 1192, -1, 1220, 1192, 1211, -1, 1129, 1186, 1130, -1, 1129, 1201, 1186, -1, 1023, 1221, 1213, -1, 1023, 1213, 1212, -1, 1222, 1208, 1196, -1, 1222, 1196, 1214, -1, 1223, 1211, 1215, -1, 1224, 1209, 1216, -1, 1224, 1218, 1209, -1, 1225, 1206, 1217, -1, 1225, 1223, 1215, -1, 1225, 1215, 1206, -1, 1226, 1180, 1218, -1, 1226, 1203, 1180, -1, 1035, 1214, 1219, -1, 1035, 1222, 1214, -1, 1227, 1216, 1207, -1, 1227, 1207, 1220, -1, 1123, 1210, 1201, -1, 1123, 1201, 1129, -1, 1025, 1228, 1221, -1, 1025, 1221, 1023, -1, 1229, 1217, 1208, -1, 1229, 1208, 1222, -1, 1021, 1220, 1211, -1, 1021, 1211, 1223, -1, 1031, 1226, 1218, -1, 1031, 1218, 1224, -1, 1039, 1223, 1225, -1, 1230, 1203, 1226, -1, 1230, 1212, 1203, -1, 1037, 1222, 1035, -1, 1037, 1229, 1222, -1, 1042, 1224, 1216, -1, 1042, 1216, 1227, -1, 1137, 1219, 1210, -1, 1137, 1210, 1123, -1, 1048, 1228, 1025, -1, 1048, 1050, 1231, -1, 1048, 1232, 1228, -1, 1048, 1231, 1232, -1, 1027, 1225, 1217, -1, 1027, 1217, 1229, -1, 1020, 1227, 1220, -1, 1020, 1220, 1021, -1, 1033, 1226, 1031, -1, 1033, 1230, 1226, -1, 1040, 1021, 1223, -1, 1040, 1223, 1039, -1, 1024, 1023, 1212, -1, 1024, 1212, 1230, -1, 1028, 1229, 1037, -1, 1028, 1027, 1229, -1, 1032, 1224, 1042, -1, 1032, 1031, 1224, -1, 1036, 1035, 1219, -1, 1036, 1219, 1137, -1, 1029, 1225, 1027, -1, 1029, 1039, 1225, -1, 1043, 1227, 1020, -1, 1043, 1042, 1227, -1, 1045, 1230, 1033, -1, 1045, 1024, 1230, -1, 1019, 1021, 1040, -1, 1233, 1234, 1235, -1, 1236, 1237, 1238, -1, 1239, 1237, 1236, -1, 1240, 1241, 1242, -1, 1243, 1241, 1240, -1, 1244, 1245, 1246, -1, 1247, 1245, 1248, -1, 1246, 1245, 1247, -1, 1248, 1245, 1249, -1, 1235, 1250, 1251, -1, 1234, 1250, 1235, -1, 1238, 1252, 1253, -1, 1253, 1252, 1234, -1, 1249, 1254, 1239, -1, 1239, 1254, 1237, -1, 1255, 1256, 1243, -1, 1243, 1256, 1241, -1, 1234, 1257, 1250, -1, 1252, 1257, 1234, -1, 1237, 1258, 1238, -1, 1238, 1258, 1252, -1, 1244, 1259, 1245, -1, 1245, 1259, 1249, -1, 1249, 1259, 1254, -1, 1255, 1260, 1256, -1, 1251, 1260, 1255, -1, 1258, 1261, 1252, -1, 1252, 1261, 1257, -1, 1254, 1262, 1237, -1, 1237, 1262, 1258, -1, 1250, 1263, 1251, -1, 1251, 1263, 1260, -1, 1258, 1264, 1261, -1, 1262, 1264, 1258, -1, 1265, 1266, 1244, -1, 1244, 1266, 1259, -1, 1254, 1266, 1262, -1, 1259, 1266, 1254, -1, 1250, 1267, 1263, -1, 1257, 1267, 1250, -1, 1265, 1268, 1266, -1, 1266, 1268, 1262, -1, 1262, 1268, 1264, -1, 1257, 1269, 1267, -1, 1261, 1269, 1257, -1, 1264, 1270, 1261, -1, 1261, 1270, 1269, -1, 1265, 1271, 1268, -1, 1268, 1271, 1264, -1, 1264, 1271, 1270, -1, 1272, 1271, 1265, -1, 1270, 1273, 1269, -1, 1274, 1275, 1273, -1, 1276, 1277, 1278, -1, 1274, 1277, 1275, -1, 1272, 1279, 1271, -1, 1280, 1281, 1272, -1, 1279, 1281, 1274, -1, 1272, 1281, 1279, -1, 1282, 1283, 1280, -1, 1280, 1283, 1281, -1, 1281, 1283, 1274, -1, 1284, 1285, 1286, -1, 1273, 1287, 1269, -1, 1275, 1287, 1273, -1, 1269, 1287, 1267, -1, 1288, 1285, 1284, -1, 1275, 1289, 1287, -1, 1290, 1291, 1276, -1, 1276, 1291, 1277, -1, 1292, 1293, 1288, -1, 1277, 1291, 1275, -1, 1275, 1291, 1289, -1, 1288, 1293, 1285, -1, 1270, 1294, 1273, -1, 1271, 1294, 1270, -1, 1274, 1294, 1279, -1, 1273, 1294, 1274, -1, 1292, 1295, 1293, -1, 1279, 1294, 1271, -1, 1278, 1296, 1282, -1, 1277, 1296, 1278, -1, 1282, 1296, 1283, -1, 1274, 1296, 1277, -1, 1283, 1296, 1274, -1, 1297, 1295, 1292, -1, 1267, 1298, 1263, -1, 1287, 1298, 1267, -1, 1286, 1299, 1300, -1, 1289, 1298, 1287, -1, 1285, 1299, 1286, -1, 1289, 1301, 1298, -1, 1302, 1303, 1290, -1, 1290, 1303, 1291, -1, 1291, 1303, 1289, -1, 1304, 1305, 1297, -1, 1289, 1303, 1301, -1, 1263, 1306, 1260, -1, 1297, 1305, 1295, -1, 1298, 1306, 1263, -1, 1301, 1306, 1298, -1, 1299, 1307, 1300, -1, 1285, 1308, 1299, -1, 1301, 1309, 1306, -1, 1302, 1310, 1303, -1, 1293, 1308, 1285, -1, 1311, 1310, 1302, -1, 1303, 1310, 1301, -1, 1301, 1310, 1309, -1, 1306, 1312, 1260, -1, 1313, 1314, 1304, -1, 1260, 1312, 1256, -1, 1304, 1314, 1305, -1, 1309, 1312, 1306, -1, 1315, 1316, 1311, -1, 1311, 1316, 1310, -1, 1308, 1317, 1299, -1, 1310, 1316, 1309, -1, 1299, 1317, 1307, -1, 1312, 1318, 1256, -1, 1295, 1319, 1293, -1, 1256, 1318, 1241, -1, 1293, 1319, 1308, -1, 1312, 1320, 1318, -1, 1321, 1322, 1313, -1, 1313, 1322, 1314, -1, 1309, 1323, 1312, -1, 1300, 1324, 1325, -1, 1316, 1323, 1309, -1, 1312, 1323, 1320, -1, 1320, 1323, 1326, -1, 1327, 1328, 1315, -1, 1315, 1328, 1316, -1, 1307, 1324, 1300, -1, 1323, 1328, 1326, -1, 1316, 1328, 1323, -1, 1318, 1329, 1241, -1, 1319, 1330, 1308, -1, 1241, 1329, 1242, -1, 1308, 1330, 1317, -1, 1320, 1329, 1318, -1, 1295, 1331, 1319, -1, 1305, 1331, 1295, -1, 1327, 1332, 1328, -1, 1326, 1332, 1320, -1, 1328, 1332, 1326, -1, 1329, 1333, 1242, -1, 1242, 1333, 1334, -1, 1335, 1336, 1321, -1, 1321, 1336, 1322, -1, 1320, 1337, 1329, -1, 1333, 1337, 1338, -1, 1317, 1339, 1307, -1, 1338, 1337, 1332, -1, 1307, 1339, 1324, -1, 1332, 1337, 1320, -1, 1329, 1337, 1333, -1, 1332, 1340, 1338, -1, 1332, 1341, 1340, -1, 1331, 1342, 1319, -1, 1343, 1341, 1327, -1, 1319, 1342, 1330, -1, 1344, 1341, 1343, -1, 1327, 1341, 1332, -1, 1338, 1345, 1333, -1, 1305, 1346, 1331, -1, 1333, 1345, 1334, -1, 1314, 1346, 1305, -1, 1340, 1345, 1338, -1, 1324, 1347, 1325, -1, 1348, 1349, 1344, -1, 1344, 1349, 1341, -1, 1341, 1349, 1340, -1, 1350, 1351, 1352, -1, 1334, 1351, 1350, -1, 1353, 1354, 1335, -1, 1345, 1351, 1334, -1, 1355, 1356, 1357, -1, 1335, 1354, 1336, -1, 1351, 1356, 1352, -1, 1345, 1356, 1351, -1, 1358, 1356, 1355, -1, 1352, 1356, 1358, -1, 1356, 1359, 1357, -1, 1330, 1360, 1317, -1, 1345, 1359, 1356, -1, 1317, 1360, 1339, -1, 1346, 1361, 1331, -1, 1349, 1362, 1340, -1, 1345, 1362, 1359, -1, 1331, 1361, 1342, -1, 1340, 1362, 1345, -1, 1357, 1363, 1348, -1, 1348, 1363, 1349, -1, 1349, 1363, 1362, -1, 1362, 1363, 1359, -1, 1359, 1363, 1357, -1, 1314, 1364, 1346, -1, 1322, 1364, 1314, -1, 1324, 1365, 1347, -1, 1339, 1365, 1324, -1, 1366, 1367, 1353, -1, 1353, 1367, 1354, -1, 1325, 1368, 1369, -1, 1347, 1368, 1325, -1, 1342, 1370, 1330, -1, 1330, 1370, 1360, -1, 1346, 1371, 1361, -1, 1364, 1371, 1346, -1, 1322, 1372, 1364, -1, 1336, 1372, 1322, -1, 1339, 1373, 1365, -1, 1360, 1373, 1339, -1, 1374, 1375, 1366, -1, 1366, 1375, 1367, -1, 1365, 1376, 1347, -1, 1347, 1376, 1368, -1, 1342, 1377, 1370, -1, 1361, 1377, 1342, -1, 1364, 1378, 1371, -1, 1372, 1378, 1364, -1, 1336, 1379, 1372, -1, 1354, 1379, 1336, -1, 1372, 1379, 1378, -1, 1360, 1380, 1373, -1, 1370, 1380, 1360, -1, 1381, 1382, 1374, -1, 1374, 1382, 1375, -1, 1368, 1383, 1369, -1, 1373, 1384, 1365, -1, 1365, 1384, 1376, -1, 1371, 1385, 1361, -1, 1361, 1385, 1377, -1, 1379, 1386, 1378, -1, 1354, 1387, 1379, -1, 1367, 1387, 1354, -1, 1377, 1388, 1370, -1, 1370, 1388, 1380, -1, 1389, 1390, 1381, -1, 1381, 1390, 1382, -1, 1369, 1391, 1392, -1, 1383, 1391, 1369, -1, 1376, 1393, 1368, -1, 1368, 1393, 1383, -1, 1373, 1394, 1384, -1, 1380, 1394, 1373, -1, 1378, 1395, 1371, -1, 1371, 1395, 1385, -1, 1379, 1396, 1386, -1, 1387, 1396, 1379, -1, 1367, 1397, 1387, -1, 1387, 1397, 1396, -1, 1375, 1397, 1367, -1, 1377, 1398, 1388, -1, 1385, 1398, 1377, -1, 1389, 1399, 1390, -1, 1400, 1399, 1401, -1, 1401, 1399, 1402, -1, 1402, 1399, 1389, -1, 1383, 1403, 1391, -1, 1393, 1403, 1383, -1, 1376, 1404, 1393, -1, 1384, 1404, 1376, -1, 1388, 1405, 1380, -1, 1380, 1405, 1394, -1, 1378, 1406, 1395, -1, 1386, 1406, 1378, -1, 1397, 1407, 1396, -1, 1375, 1408, 1397, -1, 1382, 1408, 1375, -1, 1395, 1409, 1385, -1, 1385, 1409, 1398, -1, 1393, 1410, 1403, -1, 1404, 1410, 1393, -1, 1394, 1411, 1384, -1, 1384, 1411, 1404, -1, 1388, 1412, 1405, -1, 1398, 1412, 1388, -1, 1392, 1358, 1413, -1, 1413, 1358, 1355, -1, 1391, 1358, 1392, -1, 1386, 1414, 1406, -1, 1396, 1414, 1386, -1, 1408, 1415, 1397, -1, 1397, 1415, 1407, -1, 1408, 1416, 1415, -1, 1382, 1416, 1408, -1, 1390, 1416, 1382, -1, 1395, 1417, 1409, -1, 1406, 1417, 1395, -1, 1411, 1418, 1404, -1, 1404, 1418, 1410, -1, 1405, 1419, 1394, -1, 1394, 1419, 1411, -1, 1409, 1420, 1398, -1, 1398, 1420, 1412, -1, 1403, 1352, 1391, -1, 1391, 1352, 1358, -1, 1396, 1421, 1414, -1, 1407, 1421, 1396, -1, 1416, 1422, 1415, -1, 1423, 1424, 1400, -1, 1390, 1424, 1416, -1, 1399, 1424, 1390, -1, 1400, 1424, 1399, -1, 1414, 1425, 1406, -1, 1406, 1425, 1417, -1, 1411, 1240, 1418, -1, 1419, 1240, 1411, -1, 1412, 1426, 1405, -1, 1405, 1426, 1419, -1, 1409, 1233, 1420, -1, 1417, 1233, 1409, -1, 1410, 1350, 1403, -1, 1403, 1350, 1352, -1, 1415, 1427, 1407, -1, 1407, 1427, 1421, -1, 1246, 1428, 1423, -1, 1424, 1428, 1416, -1, 1423, 1428, 1424, -1, 1416, 1428, 1422, -1, 1421, 1236, 1414, -1, 1414, 1236, 1425, -1, 1419, 1243, 1240, -1, 1426, 1243, 1419, -1, 1412, 1429, 1426, -1, 1420, 1429, 1412, -1, 1417, 1253, 1233, -1, 1425, 1253, 1417, -1, 1418, 1334, 1410, -1, 1410, 1334, 1350, -1, 1415, 1248, 1427, -1, 1422, 1248, 1415, -1, 1421, 1239, 1236, -1, 1427, 1239, 1421, -1, 1429, 1255, 1426, -1, 1426, 1255, 1243, -1, 1420, 1235, 1429, -1, 1233, 1235, 1420, -1, 1425, 1238, 1253, -1, 1236, 1238, 1425, -1, 1418, 1242, 1334, -1, 1240, 1242, 1418, -1, 1422, 1247, 1248, -1, 1246, 1247, 1428, -1, 1428, 1247, 1422, -1, 1427, 1249, 1239, -1, 1248, 1249, 1427, -1, 1429, 1251, 1255, -1, 1235, 1251, 1429, -1, 1253, 1234, 1233, -1, 1430, 1431, 1432, -1, 1433, 1434, 1435, -1, 1433, 1436, 1434, -1, 1437, 1438, 1439, -1, 1440, 1441, 1442, -1, 1440, 1443, 1441, -1, 1444, 1445, 1446, -1, 1444, 1447, 1445, -1, 1448, 1432, 1449, -1, 1448, 1449, 1438, -1, 1450, 1451, 1452, -1, 1450, 1442, 1451, -1, 1453, 1433, 1435, -1, 1453, 1435, 1454, -1, 1455, 1456, 1430, -1, 1455, 1452, 1456, -1, 1457, 1436, 1433, -1, 1457, 1458, 1459, -1, 1457, 1459, 1436, -1, 1457, 1460, 1458, -1, 1461, 1438, 1437, -1, 1461, 1448, 1438, -1, 1462, 1454, 1443, -1, 1462, 1443, 1440, -1, 1463, 1447, 1444, -1, 1463, 1439, 1447, -1, 1464, 1432, 1448, -1, 1464, 1430, 1432, -1, 1465, 1440, 1442, -1, 1465, 1442, 1450, -1, 1466, 1457, 1433, -1, 1466, 1433, 1453, -1, 1466, 1460, 1457, -1, 1467, 1450, 1452, -1, 1467, 1452, 1455, -1, 1468, 1448, 1461, -1, 1468, 1464, 1448, -1, 1469, 1453, 1454, -1, 1469, 1454, 1462, -1, 1469, 1466, 1453, -1, 1470, 1437, 1439, -1, 1470, 1439, 1463, -1, 1471, 1455, 1430, -1, 1471, 1430, 1464, -1, 1472, 1462, 1440, -1, 1472, 1440, 1465, -1, 1473, 1465, 1450, -1, 1473, 1450, 1467, -1, 1474, 1471, 1464, -1, 1474, 1464, 1468, -1, 1475, 1466, 1469, -1, 1475, 1476, 1460, -1, 1475, 1460, 1466, -1, 1477, 1437, 1470, -1, 1477, 1461, 1437, -1, 1478, 1467, 1455, -1, 1478, 1455, 1471, -1, 1479, 1469, 1462, -1, 1479, 1475, 1469, -1, 1479, 1462, 1472, -1, 1480, 1472, 1465, -1, 1481, 1482, 1483, -1, 1481, 1484, 1482, -1, 1480, 1465, 1473, -1, 1485, 1478, 1471, -1, 1481, 1483, 1486, -1, 1485, 1471, 1474, -1, 1487, 1484, 1481, -1, 1488, 1461, 1477, -1, 1489, 1490, 1484, -1, 1489, 1491, 1490, -1, 1488, 1468, 1461, -1, 1492, 1473, 1467, -1, 1492, 1467, 1478, -1, 1489, 1484, 1487, -1, 1493, 1476, 1475, -1, 1493, 1475, 1479, -1, 1494, 1486, 1495, -1, 1494, 1481, 1486, -1, 1496, 1479, 1472, -1, 1496, 1472, 1480, -1, 1497, 1478, 1485, -1, 1497, 1492, 1478, -1, 1498, 1491, 1489, -1, 1499, 1474, 1468, -1, 1500, 1495, 1501, -1, 1500, 1494, 1495, -1, 1499, 1468, 1488, -1, 1502, 1473, 1492, -1, 1502, 1480, 1473, -1, 1503, 1481, 1494, -1, 1503, 1487, 1481, -1, 1504, 1476, 1493, -1, 1504, 1493, 1479, -1, 1505, 1506, 1491, -1, 1504, 1507, 1476, -1, 1505, 1508, 1506, -1, 1504, 1479, 1496, -1, 1509, 1492, 1497, -1, 1505, 1491, 1498, -1, 1509, 1502, 1492, -1, 1510, 1474, 1499, -1, 1511, 1503, 1494, -1, 1511, 1494, 1500, -1, 1510, 1485, 1474, -1, 1512, 1496, 1480, -1, 1513, 1489, 1487, -1, 1512, 1480, 1502, -1, 1513, 1487, 1503, -1, 1514, 1502, 1509, -1, 1514, 1512, 1502, -1, 1515, 1500, 1501, -1, 1516, 1497, 1485, -1, 1516, 1485, 1510, -1, 1517, 1508, 1505, -1, 1518, 1512, 1514, -1, 1518, 1504, 1496, -1, 1518, 1507, 1504, -1, 1518, 1496, 1512, -1, 1519, 1503, 1511, -1, 1520, 1518, 1514, -1, 1520, 1521, 1507, -1, 1520, 1507, 1518, -1, 1522, 1497, 1516, -1, 1519, 1513, 1503, -1, 1522, 1509, 1497, -1, 1523, 1489, 1513, -1, 1524, 1514, 1509, -1, 1523, 1498, 1489, -1, 1524, 1509, 1522, -1, 1525, 1500, 1515, -1, 1526, 1514, 1524, -1, 1526, 1527, 1528, -1, 1526, 1528, 1529, -1, 1526, 1529, 1521, -1, 1526, 1524, 1527, -1, 1526, 1520, 1514, -1, 1526, 1521, 1520, -1, 1525, 1511, 1500, -1, 1530, 1531, 1508, -1, 1530, 1532, 1531, -1, 1533, 1534, 1535, -1, 1530, 1508, 1517, -1, 1533, 1535, 1536, -1, 1537, 1501, 1538, -1, 1539, 1535, 1534, -1, 1539, 1540, 1541, -1, 1537, 1515, 1501, -1, 1539, 1534, 1540, -1, 1542, 1541, 1543, -1, 1544, 1513, 1519, -1, 1542, 1535, 1539, -1, 1542, 1539, 1541, -1, 1545, 1543, 1546, -1, 1544, 1523, 1513, -1, 1545, 1546, 1536, -1, 1545, 1536, 1535, -1, 1545, 1542, 1543, -1, 1547, 1498, 1523, -1, 1545, 1535, 1542, -1, 1548, 1446, 1549, -1, 1548, 1549, 1534, -1, 1547, 1505, 1498, -1, 1548, 1534, 1533, -1, 1550, 1548, 1533, -1, 1551, 1511, 1525, -1, 1552, 1550, 1533, -1, 1552, 1536, 1553, -1, 1552, 1553, 1554, -1, 1551, 1519, 1511, -1, 1552, 1533, 1536, -1, 1555, 1548, 1550, -1, 1556, 1532, 1530, -1, 1555, 1444, 1446, -1, 1555, 1446, 1548, -1, 1557, 1555, 1550, -1, 1558, 1525, 1515, -1, 1559, 1550, 1552, -1, 1559, 1552, 1554, -1, 1559, 1554, 1560, -1, 1558, 1515, 1537, -1, 1559, 1557, 1550, -1, 1561, 1555, 1557, -1, 1562, 1523, 1544, -1, 1561, 1444, 1555, -1, 1561, 1463, 1444, -1, 1562, 1547, 1523, -1, 1563, 1537, 1538, -1, 1564, 1561, 1557, -1, 1565, 1564, 1557, -1, 1566, 1505, 1547, -1, 1565, 1559, 1560, -1, 1565, 1557, 1559, -1, 1565, 1560, 1567, -1, 1566, 1517, 1505, -1, 1568, 1470, 1463, -1, 1568, 1561, 1564, -1, 1568, 1463, 1561, -1, 1569, 1519, 1551, -1, 1569, 1544, 1519, -1, 1570, 1568, 1564, -1, 1571, 1564, 1565, -1, 1572, 1573, 1532, -1, 1571, 1565, 1567, -1, 1571, 1567, 1574, -1, 1571, 1570, 1564, -1, 1575, 1470, 1568, -1, 1575, 1568, 1570, -1, 1572, 1532, 1556, -1, 1575, 1477, 1470, -1, 1576, 1551, 1525, -1, 1577, 1575, 1570, -1, 1576, 1525, 1558, -1, 1578, 1574, 1579, -1, 1578, 1571, 1574, -1, 1578, 1570, 1571, -1, 1580, 1566, 1547, -1, 1578, 1577, 1570, -1, 1580, 1547, 1562, -1, 1581, 1477, 1575, -1, 1581, 1575, 1577, -1, 1581, 1488, 1477, -1, 1582, 1579, 1583, -1, 1584, 1537, 1563, -1, 1582, 1578, 1579, -1, 1582, 1577, 1578, -1, 1584, 1558, 1537, -1, 1582, 1581, 1577, -1, 1585, 1499, 1488, -1, 1586, 1517, 1566, -1, 1585, 1488, 1581, -1, 1586, 1530, 1517, -1, 1587, 1544, 1569, -1, 1588, 1581, 1582, -1, 1588, 1585, 1581, -1, 1589, 1588, 1582, -1, 1589, 1585, 1588, -1, 1587, 1562, 1544, -1, 1590, 1591, 1573, -1, 1592, 1589, 1582, -1, 1590, 1573, 1572, -1, 1593, 1583, 1594, -1, 1593, 1582, 1583, -1, 1595, 1538, 1596, -1, 1593, 1592, 1582, -1, 1595, 1563, 1538, -1, 1597, 1499, 1585, -1, 1597, 1585, 1589, -1, 1597, 1589, 1592, -1, 1597, 1510, 1499, -1, 1598, 1594, 1599, -1, 1600, 1569, 1551, -1, 1598, 1593, 1594, -1, 1600, 1551, 1576, -1, 1598, 1597, 1592, -1, 1598, 1592, 1593, -1, 1601, 1510, 1597, -1, 1601, 1516, 1510, -1, 1602, 1586, 1566, -1, 1602, 1566, 1580, -1, 1603, 1601, 1597, -1, 1604, 1598, 1599, -1, 1604, 1599, 1605, -1, 1606, 1576, 1558, -1, 1606, 1558, 1584, -1, 1604, 1597, 1598, -1, 1604, 1603, 1597, -1, 1607, 1522, 1516, -1, 1607, 1516, 1601, -1, 1608, 1556, 1530, -1, 1607, 1601, 1603, -1, 1608, 1530, 1586, -1, 1609, 1605, 1610, -1, 1609, 1610, 1527, -1, 1609, 1527, 1524, -1, 1609, 1522, 1607, -1, 1611, 1595, 1596, -1, 1609, 1604, 1605, -1, 1609, 1603, 1604, -1, 1609, 1524, 1522, -1, 1609, 1607, 1603, -1, 1612, 1580, 1562, -1, 1612, 1562, 1587, -1, 1613, 1614, 1591, -1, 1613, 1591, 1590, -1, 1615, 1584, 1563, -1, 1615, 1563, 1595, -1, 1616, 1569, 1600, -1, 1616, 1587, 1569, -1, 1617, 1586, 1602, -1, 1617, 1608, 1586, -1, 1618, 1600, 1576, -1, 1618, 1576, 1606, -1, 1619, 1572, 1556, -1, 1619, 1556, 1608, -1, 1620, 1615, 1595, -1, 1620, 1595, 1611, -1, 1621, 1580, 1612, -1, 1621, 1602, 1580, -1, 1622, 1623, 1614, -1, 1622, 1614, 1613, -1, 1624, 1584, 1615, -1, 1624, 1606, 1584, -1, 1625, 1612, 1587, -1, 1625, 1621, 1612, -1, 1625, 1587, 1616, -1, 1626, 1619, 1608, -1, 1626, 1608, 1617, -1, 1627, 1600, 1618, -1, 1627, 1616, 1600, -1, 1628, 1572, 1619, -1, 1628, 1590, 1572, -1, 1629, 1615, 1620, -1, 1629, 1624, 1615, -1, 1630, 1617, 1602, -1, 1630, 1602, 1621, -1, 1540, 1596, 1541, -1, 1540, 1611, 1596, -1, 1434, 1623, 1622, -1, 1434, 1631, 1623, -1, 1632, 1606, 1624, -1, 1632, 1618, 1606, -1, 1633, 1621, 1625, -1, 1634, 1619, 1626, -1, 1634, 1628, 1619, -1, 1635, 1616, 1627, -1, 1635, 1625, 1616, -1, 1636, 1613, 1590, -1, 1636, 1590, 1628, -1, 1445, 1624, 1629, -1, 1445, 1632, 1624, -1, 1637, 1617, 1630, -1, 1637, 1626, 1617, -1, 1534, 1620, 1611, -1, 1534, 1611, 1540, -1, 1436, 1638, 1631, -1, 1436, 1631, 1434, -1, 1639, 1627, 1618, -1, 1639, 1618, 1632, -1, 1431, 1630, 1621, -1, 1431, 1621, 1633, -1, 1441, 1628, 1634, -1, 1441, 1636, 1628, -1, 1449, 1633, 1625, -1, 1449, 1625, 1635, -1, 1640, 1622, 1613, -1, 1640, 1613, 1636, -1, 1447, 1632, 1445, -1, 1447, 1639, 1632, -1, 1451, 1634, 1626, -1, 1451, 1626, 1637, -1, 1549, 1620, 1534, -1, 1549, 1629, 1620, -1, 1459, 1641, 1638, -1, 1459, 1642, 1641, -1, 1459, 1458, 1642, -1, 1459, 1638, 1436, -1, 1643, 1627, 1639, -1, 1643, 1635, 1627, -1, 1456, 1637, 1630, -1, 1456, 1630, 1431, -1, 1443, 1636, 1441, -1, 1443, 1640, 1636, -1, 1432, 1633, 1449, -1, 1432, 1431, 1633, -1, 1435, 1434, 1622, -1, 1435, 1622, 1640, -1, 1439, 1639, 1447, -1, 1439, 1643, 1639, -1, 1442, 1634, 1451, -1, 1442, 1441, 1634, -1, 1446, 1629, 1549, -1, 1446, 1445, 1629, -1, 1438, 1635, 1643, -1, 1438, 1449, 1635, -1, 1438, 1643, 1439, -1, 1452, 1637, 1456, -1, 1452, 1451, 1637, -1, 1454, 1435, 1640, -1, 1454, 1640, 1443, -1, 1430, 1456, 1431, -1, 1644, 1645, 1646, -1, 1647, 1645, 1644, -1, 1645, 1648, 1646, -1, 1649, 1650, 1651, -1, 1651, 1652, 1653, -1, 1650, 1652, 1651, -1, 1653, 1654, 1655, -1, 1652, 1654, 1653, -1, 1655, 1656, 1657, -1, 1654, 1656, 1655, -1, 1657, 1658, 1659, -1, 1656, 1658, 1657, -1, 1659, 1660, 1661, -1, 1658, 1660, 1659, -1, 1661, 1662, 1663, -1, 1660, 1662, 1661, -1, 1663, 1664, 1665, -1, 1662, 1664, 1663, -1, 1665, 1666, 1667, -1, 1664, 1666, 1665, -1, 1667, 1668, 1669, -1, 1666, 1668, 1667, -1, 1669, 1670, 1671, -1, 1668, 1670, 1669, -1, 1671, 1672, 1673, -1, 1670, 1672, 1671, -1, 1673, 1674, 1675, -1, 1672, 1674, 1673, -1, 1675, 1676, 1677, -1, 1674, 1676, 1675, -1, 1676, 1678, 1677, -1, 1677, 1679, 1680, -1, 1678, 1679, 1677, -1, 1680, 1681, 1682, -1, 1679, 1681, 1680, -1, 1682, 1647, 1644, -1, 1681, 1647, 1682, -1, 1683, 1684, 1685, -1, 1686, 1684, 1683, -1, 1684, 1687, 1685, -1, 1688, 1689, 1690, -1, 1690, 1691, 1692, -1, 1689, 1691, 1690, -1, 1692, 1693, 1694, -1, 1691, 1693, 1692, -1, 1694, 1695, 1696, -1, 1693, 1695, 1694, -1, 1696, 1697, 1698, -1, 1695, 1697, 1696, -1, 1698, 1699, 1700, -1, 1697, 1699, 1698, -1, 1700, 1701, 1702, -1, 1699, 1701, 1700, -1, 1702, 1703, 1704, -1, 1701, 1703, 1702, -1, 1704, 1705, 1706, -1, 1703, 1705, 1704, -1, 1706, 1707, 1708, -1, 1705, 1707, 1706, -1, 1708, 1709, 1710, -1, 1707, 1709, 1708, -1, 1710, 1711, 1712, -1, 1709, 1711, 1710, -1, 1712, 1713, 1714, -1, 1711, 1713, 1712, -1, 1714, 1715, 1716, -1, 1713, 1715, 1714, -1, 1715, 1717, 1716, -1, 1716, 1718, 1719, -1, 1717, 1718, 1716, -1, 1719, 1720, 1721, -1, 1718, 1720, 1719, -1, 1721, 1686, 1683, -1, 1720, 1686, 1721, -1, 51, 1722, 52, -1, 1722, 1723, 52, -1, 52, 1724, 48, -1, 1723, 1724, 52, -1, 48, 1725, 46, -1, 1724, 1725, 48, -1, 46, 1726, 62, -1, 1725, 1726, 46, -1, 62, 1727, 74, -1, 1726, 1727, 62, -1, 74, 1728, 82, -1, 1727, 1728, 74, -1, 82, 1729, 86, -1, 1728, 1729, 82, -1, 86, 1730, 97, -1, 1729, 1730, 86, -1, 97, 1731, 114, -1, 1730, 1731, 97, -1, 114, 1732, 115, -1, 1731, 1732, 114, -1, 115, 1733, 120, -1, 1732, 1733, 115, -1, 120, 1734, 127, -1, 1733, 1734, 120, -1, 127, 1735, 33, -1, 33, 1735, 34, -1, 1734, 1735, 127, -1, 1735, 1736, 34, -1, 1737, 249, 251, -1, 1738, 251, 295, -1, 1738, 1737, 251, -1, 1739, 295, 377, -1, 1739, 1738, 295, -1, 1740, 377, 372, -1, 1740, 1739, 377, -1, 1741, 1740, 372, -1, 1742, 372, 367, -1, 1742, 1741, 372, -1, 1743, 360, 350, -1, 1743, 367, 360, -1, 1743, 1742, 367, -1, 1744, 350, 346, -1, 1744, 1743, 350, -1, 1745, 1744, 346, -1, 1746, 339, 333, -1, 1746, 346, 339, -1, 1746, 1745, 346, -1, 1747, 1746, 333, -1, 1748, 327, 321, -1, 1748, 333, 327, -1, 1748, 1747, 333, -1, 1749, 1748, 321, -1, 1750, 320, 302, -1, 1750, 321, 320, -1, 1750, 1749, 321, -1, 1751, 1750, 302, -1, 1752, 302, 312, -1, 1752, 1751, 302, -1, 1753, 312, 308, -1, 1753, 1752, 312, -1, 1754, 1755, 445, -1, 445, 1755, 1756, -1, 1756, 1755, 1757, -1, 1757, 1758, 1759, -1, 1755, 1758, 1757, -1, 1759, 1760, 1761, -1, 1758, 1760, 1759, -1, 1761, 1762, 1763, -1, 1760, 1762, 1761, -1, 1763, 1764, 1765, -1, 1762, 1764, 1763, -1, 1765, 1766, 1767, -1, 1764, 1766, 1765, -1, 1767, 1768, 1769, -1, 1766, 1768, 1767, -1, 1769, 1770, 1771, -1, 1768, 1770, 1769, -1, 1771, 1772, 1773, -1, 1770, 1772, 1771, -1, 1773, 1774, 1775, -1, 1772, 1774, 1773, -1, 1775, 1776, 1777, -1, 1774, 1776, 1775, -1, 1777, 1778, 1779, -1, 1776, 1778, 1777, -1, 1778, 1780, 1779, -1, 1779, 1781, 462, -1, 1780, 1781, 1779, -1, 1782, 720, 1783, -1, 1784, 1783, 1785, -1, 1784, 1782, 1783, -1, 1786, 1785, 1787, -1, 1786, 1784, 1785, -1, 1788, 1787, 1789, -1, 1788, 1786, 1787, -1, 1790, 1789, 1791, -1, 1790, 1788, 1789, -1, 1792, 1791, 1793, -1, 1792, 1790, 1791, -1, 1794, 1793, 1795, -1, 1794, 1792, 1793, -1, 1796, 1795, 1797, -1, 1796, 1794, 1795, -1, 1798, 1797, 1799, -1, 1798, 1796, 1797, -1, 1800, 1799, 1801, -1, 1800, 1798, 1799, -1, 1802, 1801, 1803, -1, 1802, 1800, 1801, -1, 1804, 1803, 1805, -1, 1804, 1802, 1803, -1, 1806, 1805, 1807, -1, 1806, 1804, 1805, -1, 1808, 1807, 1809, -1, 1808, 1806, 1807, -1, 1810, 1809, 1811, -1, 1810, 1808, 1809, -1, 1812, 1811, 658, -1, 1812, 1810, 1811, -1, 1813, 1812, 658, -1, 324, 1814, 299, -1, 1815, 1816, 1817, -1, 1818, 1814, 324, -1, 1819, 1820, 1821, -1, 1819, 1822, 1820, -1, 709, 1823, 1824, -1, 709, 733, 1823, -1, 268, 1825, 262, -1, 698, 1824, 1826, -1, 698, 709, 1824, -1, 1827, 1828, 1829, -1, 1830, 1821, 1831, -1, 688, 1826, 1832, -1, 1830, 1819, 1821, -1, 688, 698, 1826, -1, 1833, 1834, 1835, -1, 1836, 1816, 1815, -1, 678, 1832, 1837, -1, 678, 688, 1832, -1, 1838, 1833, 1839, -1, 671, 678, 1837, -1, 671, 1837, 1840, -1, 1841, 1827, 1842, -1, 1843, 1836, 1844, -1, 668, 671, 1840, -1, 1835, 1839, 1833, -1, 1845, 1835, 1834, -1, 668, 1840, 1846, -1, 1847, 1845, 1848, -1, 1849, 1847, 1850, -1, 1851, 1849, 1852, -1, 1825, 1853, 262, -1, 1854, 1831, 1851, -1, 1855, 1825, 268, -1, 1856, 1855, 278, -1, 1857, 1856, 288, -1, 1858, 1857, 288, -1, 662, 1846, 1859, -1, 1814, 1858, 299, -1, 1842, 1860, 1841, -1, 1829, 1842, 1827, -1, 662, 668, 1846, -1, 1861, 1829, 1828, -1, 278, 1855, 268, -1, 1862, 1861, 1863, -1, 1864, 1862, 1865, -1, 1815, 1844, 1836, -1, 1854, 1830, 1831, -1, 1852, 1854, 1851, -1, 663, 662, 1859, -1, 1850, 1852, 1849, -1, 663, 1859, 255, -1, 1848, 1850, 1847, -1, 1834, 1848, 1845, -1, 1865, 1843, 1864, -1, 1865, 1836, 1843, -1, 1866, 1867, 258, -1, 1868, 255, 254, -1, 1868, 663, 255, -1, 1869, 1866, 258, -1, 288, 1856, 278, -1, 262, 1869, 258, -1, 262, 1870, 1869, -1, 1863, 1865, 1862, -1, 1853, 1870, 262, -1, 1816, 254, 258, -1, 1816, 258, 1867, -1, 1816, 1868, 254, -1, 1871, 1816, 1867, -1, 299, 1858, 288, -1, 1872, 1867, 1873, -1, 1872, 1871, 1867, -1, 1817, 1816, 1871, -1, 1828, 1863, 1861, -1, 1822, 1872, 1873, -1, 1822, 1873, 1820, -1, 1874, 1875, 856, -1, 856, 1875, 1876, -1, 1876, 1875, 1877, -1, 1877, 1878, 1879, -1, 1875, 1878, 1877, -1, 1879, 1880, 1881, -1, 1878, 1880, 1879, -1, 1881, 1882, 1883, -1, 1880, 1882, 1881, -1, 1883, 1884, 1885, -1, 1882, 1884, 1883, -1, 1885, 1886, 1887, -1, 1884, 1886, 1885, -1, 1886, 1888, 1887, -1, 1887, 1889, 1890, -1, 1890, 1889, 1891, -1, 1888, 1889, 1887, -1, 1891, 1892, 1893, -1, 1889, 1892, 1891, -1, 1892, 1894, 1893, -1, 1893, 1895, 1896, -1, 1896, 1895, 1897, -1, 1894, 1895, 1893, -1, 1895, 1898, 1897, -1, 1897, 1899, 1900, -1, 1898, 1899, 1897, -1, 1900, 1901, 872, -1, 1899, 1901, 1900, -1, 1902, 1132, 1903, -1, 1902, 1904, 1132, -1, 1905, 1903, 1906, -1, 1905, 1902, 1903, -1, 1907, 1906, 1908, -1, 1907, 1905, 1906, -1, 1909, 1908, 1910, -1, 1909, 1907, 1908, -1, 1911, 1910, 1912, -1, 1911, 1909, 1910, -1, 1913, 1912, 1914, -1, 1913, 1911, 1912, -1, 1915, 1914, 1916, -1, 1915, 1913, 1914, -1, 1917, 1916, 1918, -1, 1917, 1915, 1916, -1, 1919, 1918, 1920, -1, 1919, 1917, 1918, -1, 1921, 1920, 1922, -1, 1921, 1919, 1920, -1, 1923, 1922, 1924, -1, 1923, 1921, 1922, -1, 1925, 1924, 1926, -1, 1925, 1923, 1924, -1, 1927, 1926, 1928, -1, 1927, 1925, 1926, -1, 1929, 1928, 1930, -1, 1929, 1927, 1928, -1, 1931, 1930, 1932, -1, 1931, 1929, 1930, -1, 1933, 1932, 1070, -1, 1933, 1931, 1932, -1, 1934, 1935, 1936, -1, 1934, 1936, 1937, -1, 1938, 1937, 1939, -1, 1938, 1934, 1937, -1, 1940, 1939, 1941, -1, 1940, 1938, 1939, -1, 1942, 1941, 1943, -1, 1942, 1940, 1941, -1, 1944, 1943, 1945, -1, 1944, 1942, 1943, -1, 1946, 1945, 1947, -1, 1946, 1944, 1945, -1, 1948, 1947, 1949, -1, 1948, 1946, 1947, -1, 1950, 1949, 1951, -1, 1950, 1948, 1949, -1, 1952, 1951, 1953, -1, 1952, 1950, 1951, -1, 1954, 1953, 1955, -1, 1954, 1952, 1953, -1, 1956, 1955, 1957, -1, 1956, 1954, 1955, -1, 1958, 1957, 1959, -1, 1958, 1956, 1957, -1, 1960, 1959, 1961, -1, 1960, 1958, 1959, -1, 1962, 1961, 1963, -1, 1962, 1960, 1961, -1, 1964, 1963, 1965, -1, 1964, 1962, 1963, -1, 1966, 1965, 1967, -1, 1966, 1964, 1965, -1, 1968, 1969, 1970, -1, 1968, 1970, 1971, -1, 1972, 1971, 1973, -1, 1972, 1968, 1971, -1, 1974, 1973, 1975, -1, 1974, 1972, 1973, -1, 1976, 1975, 1977, -1, 1976, 1974, 1975, -1, 1978, 1977, 1979, -1, 1978, 1976, 1977, -1, 1980, 1979, 1981, -1, 1980, 1978, 1979, -1, 1982, 1981, 1983, -1, 1982, 1980, 1981, -1, 1984, 1983, 1838, -1, 1984, 1982, 1983, -1, 1985, 1984, 1838, -1, 1986, 1838, 1987, -1, 1986, 1985, 1838, -1, 1988, 1987, 1989, -1, 1988, 1986, 1987, -1, 1990, 1989, 1991, -1, 1990, 1988, 1989, -1, 1992, 1991, 1993, -1, 1992, 1990, 1991, -1, 1994, 1993, 1995, -1, 1994, 1992, 1993, -1, 1996, 1995, 1997, -1, 1996, 1994, 1995, -1, 1998, 1997, 1999, -1, 1998, 1996, 1997, -1, 2000, 1998, 1999, -1, 2000, 1999, 1951, -1, 2001, 2000, 1951, -1, 2002, 2003, 1284, -1, 1288, 2003, 1292, -1, 1284, 2003, 1288, -1, 1292, 2004, 1297, -1, 2003, 2004, 1292, -1, 1297, 2005, 1304, -1, 2004, 2005, 1297, -1, 2005, 2006, 1304, -1, 1313, 2007, 1321, -1, 1304, 2007, 1313, -1, 2006, 2007, 1304, -1, 1321, 2008, 1335, -1, 2007, 2008, 1321, -1, 1335, 2009, 1353, -1, 2008, 2009, 1335, -1, 2009, 2010, 1353, -1, 1366, 2011, 1374, -1, 1353, 2011, 1366, -1, 2010, 2011, 1353, -1, 1374, 2012, 1381, -1, 2011, 2012, 1374, -1, 1381, 2013, 1389, -1, 2012, 2013, 1381, -1, 1389, 2014, 1402, -1, 2013, 2014, 1389, -1, 2014, 2015, 1402, -1, 1402, 2016, 1401, -1, 2015, 2016, 1402, -1, 2017, 2018, 2019, -1, 2020, 1994, 1996, -1, 2020, 1992, 1994, -1, 2021, 2022, 1528, -1, 1528, 2022, 1529, -1, 2023, 2021, 1527, -1, 1527, 2021, 1528, -1, 2024, 2023, 1527, -1, 2025, 2024, 1610, -1, 2026, 2025, 1605, -1, 1228, 2027, 1221, -1, 2028, 2026, 1599, -1, 2029, 2028, 1594, -1, 2030, 2029, 1583, -1, 2031, 2032, 1990, -1, 2033, 2020, 1996, -1, 2034, 2035, 1146, -1, 2036, 2033, 1998, -1, 2037, 2036, 2000, -1, 2000, 2001, 2037, -1, 1998, 2000, 2036, -1, 1996, 1998, 2033, -1, 2038, 2034, 1165, -1, 2039, 2038, 1181, -1, 2040, 2039, 1204, -1, 2041, 2040, 1213, -1, 2027, 2041, 1221, -1, 2042, 2027, 1228, -1, 2043, 2042, 1232, -1, 1165, 2034, 1146, -1, 1610, 1605, 2025, -1, 1232, 2042, 1228, -1, 1181, 2038, 1165, -1, 2044, 2045, 1985, -1, 2044, 1985, 1986, -1, 1527, 1610, 2024, -1, 2030, 1579, 2046, -1, 1583, 1579, 2030, -1, 1231, 2043, 1232, -1, 2047, 2044, 1986, -1, 2001, 2043, 1231, -1, 2047, 1986, 1988, -1, 1204, 2039, 1181, -1, 2048, 2001, 1231, -1, 2022, 2037, 2001, -1, 1594, 1583, 2029, -1, 2032, 2047, 1988, -1, 2049, 2022, 2001, -1, 2049, 2001, 2048, -1, 2049, 1529, 2022, -1, 2032, 1988, 1990, -1, 1213, 2040, 1204, -1, 2050, 2049, 2048, -1, 2050, 2048, 2051, -1, 2052, 2051, 2053, -1, 2052, 2050, 2051, -1, 1599, 1594, 2028, -1, 2054, 2053, 2055, -1, 2054, 2052, 2053, -1, 2031, 1990, 1992, -1, 2056, 2055, 2057, -1, 1221, 2041, 1213, -1, 2056, 2054, 2055, -1, 2058, 2057, 2059, -1, 2058, 2056, 2057, -1, 1605, 1599, 2026, -1, 2018, 2059, 2019, -1, 2018, 2058, 2059, -1, 2020, 2031, 1992, -1, 2017, 2019, 2060, -1, 2061, 1483, 1482, -1, 2061, 2062, 1483, -1, 2063, 1482, 1484, -1, 2063, 2061, 1482, -1, 2064, 1484, 1490, -1, 2064, 2063, 1484, -1, 2065, 1490, 1491, -1, 2065, 2064, 1490, -1, 2066, 1491, 1506, -1, 2066, 2065, 1491, -1, 2067, 1506, 1508, -1, 2067, 2066, 1506, -1, 2068, 1508, 1531, -1, 2068, 2067, 1508, -1, 2069, 1531, 1532, -1, 2069, 2068, 1531, -1, 2070, 1532, 1573, -1, 2070, 2069, 1532, -1, 2071, 1573, 1591, -1, 2071, 2070, 1573, -1, 2072, 1591, 1614, -1, 2072, 2071, 1591, -1, 2073, 1614, 1623, -1, 2073, 2072, 1614, -1, 2074, 1623, 1631, -1, 2074, 2073, 1623, -1, 2075, 1631, 1638, -1, 2075, 2074, 1631, -1, 2076, 1638, 1641, -1, 2076, 1641, 1642, -1, 2076, 2075, 1638, -1, 2077, 2076, 1642, -1, 2078, 2079, 2080, -1, 2078, 2081, 2079, -1, 2082, 2080, 2083, -1, 2082, 2078, 2080, -1, 2084, 2083, 2085, -1, 2084, 2082, 2083, -1, 2086, 2085, 2087, -1, 2086, 2084, 2085, -1, 2088, 2087, 2089, -1, 2088, 2086, 2087, -1, 2090, 2089, 2091, -1, 2090, 2088, 2089, -1, 2092, 2091, 2093, -1, 2092, 2090, 2091, -1, 2094, 2093, 2095, -1, 2094, 2092, 2093, -1, 2096, 2095, 2097, -1, 2096, 2094, 2095, -1, 2098, 2097, 2099, -1, 2098, 2096, 2097, -1, 2100, 2099, 2101, -1, 2100, 2098, 2099, -1, 2102, 2101, 2103, -1, 2102, 2100, 2101, -1, 2104, 2103, 2105, -1, 2104, 2102, 2103, -1, 2106, 2105, 2107, -1, 2106, 2104, 2105, -1, 2108, 2107, 2109, -1, 2108, 2106, 2107, -1, 2110, 2108, 2109, -1, 2110, 2109, 2111, -1, 2112, 2113, 2114, -1, 2112, 2114, 2115, -1, 2116, 2115, 2117, -1, 2116, 2112, 2115, -1, 2118, 2117, 2119, -1, 2118, 2116, 2117, -1, 2120, 2119, 2121, -1, 2120, 2118, 2119, -1, 2122, 2121, 2123, -1, 2122, 2120, 2121, -1, 2124, 2123, 2125, -1, 2124, 2122, 2123, -1, 2126, 2125, 2127, -1, 2126, 2124, 2125, -1, 2128, 2127, 1818, -1, 2128, 2126, 2127, -1, 2046, 2128, 1818, -1, 2030, 1818, 2129, -1, 2030, 2046, 1818, -1, 2029, 2129, 2130, -1, 2029, 2030, 2129, -1, 2028, 2130, 2131, -1, 2028, 2029, 2130, -1, 2026, 2131, 2132, -1, 2026, 2028, 2131, -1, 2025, 2132, 2133, -1, 2025, 2026, 2132, -1, 2024, 2133, 2134, -1, 2024, 2025, 2133, -1, 2023, 2134, 2135, -1, 2023, 2024, 2134, -1, 2021, 2135, 2136, -1, 2021, 2023, 2135, -1, 2022, 2021, 2136, -1, 2137, 2138, 2139, -1, 2140, 2141, 2142, -1, 2139, 2141, 2140, -1, 2138, 2141, 2139, -1, 2142, 2143, 2144, -1, 2141, 2143, 2142, -1, 2144, 2145, 2146, -1, 2143, 2145, 2144, -1, 2146, 2147, 2148, -1, 2145, 2147, 2146, -1, 2148, 2149, 2150, -1, 2147, 2149, 2148, -1, 2150, 2151, 2152, -1, 2149, 2151, 2150, -1, 2153, 2154, 2155, -1, 2152, 2154, 2153, -1, 2151, 2154, 2152, -1, 2155, 2156, 2157, -1, 2154, 2156, 2155, -1, 2157, 2158, 2159, -1, 2156, 2158, 2157, -1, 2160, 2161, 2162, -1, 2159, 2161, 2160, -1, 2158, 2161, 2159, -1, 2162, 2163, 2164, -1, 2161, 2163, 2162, -1, 2164, 2165, 2166, -1, 2163, 2165, 2164, -1, 2166, 2167, 2168, -1, 2165, 2167, 2166, -1, 2168, 2169, 2170, -1, 2167, 2169, 2168, -1, 2171, 2172, 2173, -1, 2174, 2175, 2176, -1, 2173, 2175, 2174, -1, 2172, 2175, 2173, -1, 2176, 2177, 2178, -1, 2175, 2177, 2176, -1, 2178, 2179, 2180, -1, 2177, 2179, 2178, -1, 2180, 2181, 2182, -1, 2179, 2181, 2180, -1, 2182, 2183, 2184, -1, 2181, 2183, 2182, -1, 2184, 2185, 2186, -1, 2183, 2185, 2184, -1, 2187, 2188, 2189, -1, 2186, 2188, 2187, -1, 2185, 2188, 2186, -1, 2189, 2190, 2191, -1, 2188, 2190, 2189, -1, 2191, 2192, 2193, -1, 2190, 2192, 2191, -1, 2194, 2195, 2196, -1, 2193, 2195, 2194, -1, 2192, 2195, 2193, -1, 2196, 2197, 2198, -1, 2195, 2197, 2196, -1, 2198, 2199, 2200, -1, 2197, 2199, 2198, -1, 2200, 2201, 2202, -1, 2199, 2201, 2200, -1, 2202, 2203, 2204, -1, 2201, 2203, 2202, -1, 2205, 2206, 1700, -1, 2207, 2205, 1702, -1, 1704, 1706, 2208, -1, 1702, 1704, 2207, -1, 1700, 1702, 2205, -1, 1698, 1700, 2206, -1, 1696, 1698, 2209, -1, 1694, 1696, 2210, -1, 1692, 1694, 2211, -1, 1690, 1692, 2212, -1, 2213, 1688, 2214, -1, 2214, 1688, 1280, -1, 925, 1315, 941, -1, 2215, 2213, 2214, -1, 2216, 2215, 2217, -1, 2218, 2216, 2219, -1, 2220, 2218, 2221, -1, 2222, 2220, 2223, -1, 2217, 2219, 2216, -1, 2224, 2222, 2225, -1, 2226, 2224, 2225, -1, 941, 1311, 956, -1, 1315, 1311, 941, -1, 956, 1302, 963, -1, 1311, 1302, 956, -1, 1661, 2227, 2228, -1, 963, 1290, 970, -1, 1302, 1290, 963, -1, 970, 1276, 978, -1, 1290, 1276, 970, -1, 2219, 2221, 2218, -1, 978, 1278, 990, -1, 1276, 1278, 978, -1, 990, 1649, 989, -1, 1278, 1282, 990, -1, 990, 1282, 1649, -1, 1649, 1651, 989, -1, 1663, 2229, 2227, -1, 1651, 2230, 989, -1, 1282, 1688, 1649, -1, 1282, 1280, 1688, -1, 1688, 1690, 1649, -1, 2221, 2223, 2220, -1, 1653, 2231, 2230, -1, 1665, 2232, 2229, -1, 2223, 2225, 2222, -1, 2207, 1704, 2208, -1, 2208, 1706, 2233, -1, 2214, 2217, 2215, -1, 2225, 2234, 2226, -1, 2226, 2234, 2235, -1, 1665, 1667, 2232, -1, 1663, 1665, 2229, -1, 1661, 1663, 2227, -1, 1659, 1661, 2228, -1, 1657, 1659, 2228, -1, 1657, 2228, 2236, -1, 1655, 1657, 2236, -1, 1655, 2236, 2231, -1, 1653, 1655, 2231, -1, 1651, 1653, 2230, -1, 2212, 1649, 1690, -1, 2211, 2212, 1692, -1, 2210, 2211, 1694, -1, 2209, 2210, 1696, -1, 2206, 2209, 1698, -1, 2237, 2238, 2239, -1, 2239, 2238, 2240, -1, 2238, 2241, 2240, -1, 2240, 2242, 2243, -1, 2241, 2242, 2240, -1, 2243, 2244, 2245, -1, 2242, 2244, 2243, -1, 2245, 2246, 2247, -1, 2244, 2246, 2245, -1, 2246, 2248, 2247, -1, 2247, 2249, 2250, -1, 2248, 2249, 2247, -1, 2250, 2251, 2252, -1, 2249, 2251, 2250, -1, 2252, 2253, 57, -1, 2251, 2253, 2252, -1, 2253, 2137, 57, -1, 57, 2139, 55, -1, 2137, 2139, 57, -1, 2139, 2140, 55, -1, 55, 2142, 59, -1, 2140, 2142, 55, -1, 59, 2144, 65, -1, 2142, 2144, 59, -1, 65, 2146, 71, -1, 2144, 2146, 65, -1, 71, 2148, 80, -1, 2146, 2148, 71, -1, 80, 2150, 90, -1, 2148, 2150, 80, -1, 90, 2152, 102, -1, 2150, 2152, 90, -1, 2152, 2153, 102, -1, 2254, 2255, 1707, -1, 1707, 2255, 1709, -1, 1709, 2256, 1711, -1, 2255, 2256, 1709, -1, 1711, 2257, 1713, -1, 2256, 2257, 1711, -1, 1713, 2258, 1715, -1, 2257, 2258, 1713, -1, 1715, 2259, 1717, -1, 2258, 2259, 1715, -1, 1717, 2260, 2261, -1, 2259, 2260, 1717, -1, 2261, 2262, 2263, -1, 2260, 2262, 2261, -1, 2263, 2264, 2265, -1, 2262, 2264, 2263, -1, 2265, 2266, 2267, -1, 2264, 2266, 2265, -1, 2267, 2171, 2170, -1, 2266, 2171, 2267, -1, 2170, 2173, 2168, -1, 2171, 2173, 2170, -1, 2168, 2174, 2166, -1, 2173, 2174, 2168, -1, 2166, 2176, 2164, -1, 2174, 2176, 2166, -1, 2164, 2178, 2162, -1, 2176, 2178, 2164, -1, 2178, 2180, 2162, -1, 2162, 2180, 2160, -1, 2180, 2182, 2160, -1, 2160, 2182, 2159, -1, 2182, 2184, 2159, -1, 2159, 2184, 2157, -1, 2184, 2186, 2157, -1, 2157, 2186, 2155, -1, 2155, 2187, 2153, -1, 2186, 2187, 2155, -1, 1668, 514, 1670, -1, 1670, 501, 1672, -1, 514, 501, 1670, -1, 1672, 493, 1674, -1, 501, 493, 1672, -1, 1674, 482, 1676, -1, 1676, 482, 1678, -1, 493, 482, 1674, -1, 1678, 476, 2268, -1, 482, 476, 1678, -1, 2268, 470, 2269, -1, 476, 470, 2268, -1, 2269, 466, 2270, -1, 2270, 466, 2271, -1, 470, 466, 2269, -1, 2271, 468, 2204, -1, 2204, 468, 2202, -1, 466, 468, 2271, -1, 2202, 2272, 2200, -1, 468, 2272, 2202, -1, 2200, 2273, 2198, -1, 2272, 2273, 2200, -1, 2198, 2274, 2196, -1, 2273, 2274, 2198, -1, 2196, 2275, 2194, -1, 2194, 2275, 2193, -1, 2274, 2275, 2196, -1, 2193, 2276, 2191, -1, 2275, 2276, 2193, -1, 2191, 2277, 2189, -1, 2276, 2277, 2191, -1, 2277, 2278, 2189, -1, 2189, 2278, 2187, -1, 1705, 2254, 1707, -1, 2153, 2279, 102, -1, 580, 568, 1654, -1, 531, 514, 1666, -1, 2280, 119, 2279, -1, 1666, 514, 1668, -1, 2281, 2237, 2239, -1, 2279, 119, 102, -1, 2282, 2281, 2283, -1, 2284, 2282, 2285, -1, 2286, 2284, 2287, -1, 2288, 2286, 2287, -1, 2288, 2287, 2289, -1, 2290, 2288, 2289, -1, 2290, 2289, 2291, -1, 2292, 2290, 2291, -1, 2293, 2292, 2294, -1, 1691, 1689, 2295, -1, 1693, 1691, 2296, -1, 2153, 2297, 2280, -1, 1695, 1693, 2298, -1, 1697, 1695, 2299, -1, 2187, 2297, 2153, -1, 1699, 1697, 2300, -1, 1701, 1699, 2301, -1, 1703, 1701, 2302, -1, 2303, 2254, 1705, -1, 2302, 2303, 1703, -1, 2278, 2304, 2187, -1, 2301, 2302, 1701, -1, 2300, 2301, 1699, -1, 2299, 2300, 1697, -1, 2298, 2299, 1695, -1, 2296, 2298, 1693, -1, 2295, 2296, 1691, -1, 1652, 1650, 580, -1, 580, 1650, 579, -1, 1654, 1652, 580, -1, 1656, 1654, 568, -1, 2304, 2305, 2297, -1, 1658, 1656, 561, -1, 119, 2305, 135, -1, 1660, 1658, 553, -1, 2280, 2305, 119, -1, 1662, 1660, 546, -1, 1664, 1662, 531, -1, 2297, 2305, 2280, -1, 1666, 1664, 531, -1, 568, 561, 1656, -1, 2278, 2305, 2304, -1, 135, 2306, 142, -1, 2305, 2306, 135, -1, 2284, 2285, 2287, -1, 2306, 2307, 142, -1, 2307, 2308, 142, -1, 142, 2308, 150, -1, 2308, 2309, 150, -1, 150, 2309, 157, -1, 561, 553, 1658, -1, 169, 1689, 168, -1, 157, 2310, 169, -1, 2309, 2310, 157, -1, 1689, 2293, 168, -1, 2282, 2283, 2285, -1, 2293, 2294, 168, -1, 2310, 1650, 169, -1, 169, 1650, 1689, -1, 2310, 579, 1650, -1, 553, 546, 1660, -1, 1650, 2295, 1689, -1, 2292, 2291, 2294, -1, 2281, 2239, 2283, -1, 546, 531, 1662, -1, 1703, 2303, 1705, -1, 1683, 1685, 2311, -1, 1721, 1683, 2312, -1, 1719, 1721, 2313, -1, 1716, 1719, 2314, -1, 1714, 1716, 2315, -1, 1712, 1714, 2316, -1, 1710, 1712, 2317, -1, 2318, 2233, 1708, -1, 2317, 2318, 1710, -1, 2316, 2317, 1712, -1, 2315, 2316, 1714, -1, 2314, 2315, 1716, -1, 2313, 2314, 1719, -1, 2312, 2313, 1721, -1, 2311, 2312, 1683, -1, 1644, 1646, 2319, -1, 1667, 1669, 2232, -1, 2319, 1646, 878, -1, 1682, 1644, 2319, -1, 1680, 1682, 2320, -1, 1677, 1680, 2321, -1, 1675, 1677, 2322, -1, 1673, 1675, 2323, -1, 1671, 1673, 2324, -1, 1669, 1671, 2324, -1, 1669, 2324, 2232, -1, 1682, 2319, 2320, -1, 1706, 1708, 2233, -1, 1673, 2323, 2324, -1, 1708, 1710, 2318, -1, 2325, 2326, 2327, -1, 2234, 2328, 2329, -1, 1646, 876, 878, -1, 2311, 1685, 1646, -1, 2330, 1413, 1685, -1, 2326, 1413, 2330, -1, 1675, 2322, 2323, -1, 1685, 1355, 1646, -1, 1413, 1355, 1685, -1, 1646, 1355, 876, -1, 1355, 1357, 876, -1, 876, 1357, 881, -1, 2328, 2331, 2332, -1, 1357, 1348, 881, -1, 881, 1348, 886, -1, 1348, 1344, 886, -1, 1677, 2321, 2322, -1, 886, 1344, 892, -1, 1344, 1343, 892, -1, 892, 1343, 903, -1, 1343, 1327, 903, -1, 903, 1327, 911, -1, 2331, 2333, 2334, -1, 1327, 1315, 911, -1, 911, 1315, 925, -1, 2329, 2235, 2234, -1, 2332, 2329, 2328, -1, 2334, 2332, 2331, -1, 2335, 2334, 2333, -1, 2336, 2335, 2333, -1, 2336, 2333, 2337, -1, 2338, 2336, 2337, -1, 2338, 2337, 2325, -1, 2327, 2338, 2325, -1, 1680, 2320, 2321, -1, 2330, 2327, 2326, -1, 2204, 2203, 2271, -1, 2270, 2339, 2269, -1, 2271, 2339, 2270, -1, 2203, 2339, 2271, -1, 2269, 2340, 2268, -1, 2339, 2340, 2269, -1, 2268, 2341, 1678, -1, 2340, 2341, 2268, -1, 1679, 2342, 1681, -1, 1678, 2342, 1679, -1, 2341, 2342, 1678, -1, 1681, 2343, 1647, -1, 2342, 2343, 1681, -1, 1647, 2344, 1645, -1, 2343, 2344, 1647, -1, 1645, 2345, 1648, -1, 1648, 2345, 2346, -1, 2344, 2345, 1645, -1, 2347, 2348, 2349, -1, 2346, 2348, 2347, -1, 2345, 2348, 2346, -1, 2349, 2350, 2351, -1, 2348, 2350, 2349, -1, 2351, 2352, 2259, -1, 2350, 2352, 2351, -1, 2260, 2353, 2262, -1, 2259, 2353, 2260, -1, 2352, 2353, 2259, -1, 2262, 2354, 2264, -1, 2353, 2354, 2262, -1, 2354, 2355, 2264, -1, 2264, 2355, 2266, -1, 2355, 2172, 2266, -1, 2266, 2172, 2171, -1, 2170, 2169, 2267, -1, 2265, 2356, 2263, -1, 2267, 2356, 2265, -1, 2169, 2356, 2267, -1, 2263, 2357, 2261, -1, 2356, 2357, 2263, -1, 2261, 2358, 1717, -1, 2357, 2358, 2261, -1, 1718, 2359, 1720, -1, 1717, 2359, 1718, -1, 2358, 2359, 1717, -1, 1720, 2360, 1686, -1, 2359, 2360, 1720, -1, 1686, 2361, 1684, -1, 2360, 2361, 1686, -1, 1684, 2362, 1687, -1, 1687, 2362, 2363, -1, 2361, 2362, 1684, -1, 2364, 2365, 2366, -1, 2363, 2365, 2364, -1, 2362, 2365, 2363, -1, 2366, 2367, 2368, -1, 2365, 2367, 2366, -1, 2368, 2369, 2246, -1, 2367, 2369, 2368, -1, 2248, 2370, 2249, -1, 2246, 2370, 2248, -1, 2369, 2370, 2246, -1, 2249, 2371, 2251, -1, 2370, 2371, 2249, -1, 2371, 2372, 2251, -1, 2251, 2372, 2253, -1, 2372, 2138, 2253, -1, 2253, 2138, 2137, -1, 2373, 2374, 2375, -1, 2373, 2376, 2374, -1, 2377, 2378, 2379, -1, 2380, 2378, 2377, -1, 2381, 2382, 2383, -1, 2384, 2385, 2136, -1, 2386, 2387, 2388, -1, 2386, 2383, 2387, -1, 2389, 2390, 2391, -1, 2389, 2391, 2392, -1, 2389, 2392, 2393, -1, 2394, 2393, 2395, -1, 2396, 2388, 2136, -1, 2394, 2395, 2397, -1, 2398, 2399, 2400, -1, 2398, 2400, 2381, -1, 2401, 2397, 2385, -1, 2401, 2385, 2384, -1, 2402, 2381, 2383, -1, 2403, 2384, 2136, -1, 2402, 2383, 2386, -1, 2404, 2386, 2388, -1, 2405, 2406, 2390, -1, 2407, 2408, 2409, -1, 2404, 2388, 2396, -1, 2405, 2390, 2389, -1, 2405, 2393, 2394, -1, 2405, 2389, 2393, -1, 2410, 2411, 2399, -1, 2412, 2394, 2397, -1, 2412, 2397, 2401, -1, 2410, 2399, 2398, -1, 2413, 2408, 2407, -1, 2414, 2396, 2136, -1, 2415, 2401, 2384, -1, 2416, 2381, 2402, -1, 2415, 2384, 2403, -1, 2416, 2398, 2381, -1, 2417, 2418, 2407, -1, 2417, 2409, 2411, -1, 2417, 2407, 2409, -1, 2417, 2410, 2418, -1, 1839, 2408, 2413, -1, 2419, 2403, 2136, -1, 2417, 2411, 2410, -1, 2420, 2402, 2386, -1, 2421, 2422, 2406, -1, 2421, 2394, 2412, -1, 2420, 2386, 2404, -1, 2421, 2406, 2405, -1, 2421, 2405, 2394, -1, 2423, 2404, 2396, -1, 2424, 2412, 2401, -1, 2424, 2401, 2415, -1, 2423, 2396, 2414, -1, 2425, 2426, 2418, -1, 2425, 2418, 2410, -1, 2425, 2410, 2398, -1, 2427, 2415, 2403, -1, 2425, 2398, 2416, -1, 2427, 2403, 2419, -1, 2428, 2414, 2136, -1, 2429, 2419, 2136, -1, 2430, 2431, 2422, -1, 2430, 2422, 2421, -1, 2432, 2416, 2402, -1, 2432, 2402, 2420, -1, 2430, 2421, 2412, -1, 2430, 2412, 2424, -1, 2433, 2420, 2404, -1, 2433, 2404, 2423, -1, 2434, 2415, 2427, -1, 2435, 2423, 2414, -1, 2434, 2424, 2415, -1, 2435, 2414, 2428, -1, 2436, 2425, 2416, -1, 2436, 2432, 2437, -1, 2436, 2437, 2426, -1, 2438, 2427, 2419, -1, 2436, 2426, 2425, -1, 2438, 2419, 2429, -1, 2436, 2416, 2432, -1, 2439, 2440, 2441, -1, 2439, 2136, 2440, -1, 2439, 2429, 2136, -1, 2442, 2430, 2424, -1, 2443, 2428, 2136, -1, 2442, 2424, 2434, -1, 2444, 2437, 2432, -1, 2444, 2432, 2420, -1, 2444, 2420, 2433, -1, 2445, 2427, 2438, -1, 2446, 2433, 2423, -1, 2445, 2434, 2427, -1, 2446, 2423, 2435, -1, 2447, 2441, 2448, -1, 2447, 2438, 2429, -1, 2449, 2435, 2428, -1, 2447, 2439, 2441, -1, 2449, 2428, 2443, -1, 2447, 2429, 2439, -1, 2450, 2430, 2442, -1, 2450, 2451, 2431, -1, 2450, 2431, 2430, -1, 2452, 2442, 2434, -1, 2453, 2443, 2136, -1, 2452, 2434, 2445, -1, 2454, 2444, 2433, -1, 2455, 2438, 2447, -1, 2456, 2457, 2458, -1, 2455, 2448, 2459, -1, 2454, 2433, 2446, -1, 2456, 2458, 2460, -1, 2455, 2447, 2448, -1, 2392, 2435, 2449, -1, 2455, 2445, 2438, -1, 2392, 2446, 2435, -1, 2461, 2450, 2442, -1, 2461, 2451, 2450, -1, 2461, 2442, 2452, -1, 2395, 2449, 2443, -1, 2111, 2457, 2456, -1, 2462, 2452, 2445, -1, 2395, 2443, 2453, -1, 2462, 2455, 2459, -1, 2463, 2454, 2464, -1, 2462, 2445, 2455, -1, 2463, 2464, 2437, -1, 2463, 2444, 2454, -1, 2463, 2437, 2444, -1, 2465, 2466, 2451, -1, 2387, 2467, 2136, -1, 2465, 2451, 2461, -1, 2468, 2459, 2469, -1, 2468, 2452, 2462, -1, 2385, 2453, 2136, -1, 2468, 2461, 2452, -1, 2391, 2464, 2454, -1, 2391, 2390, 2464, -1, 2383, 2382, 2467, -1, 2468, 2462, 2459, -1, 2391, 2454, 2446, -1, 2470, 2469, 2460, -1, 2391, 2446, 2392, -1, 2383, 2467, 2387, -1, 2470, 2458, 2466, -1, 2470, 2468, 2469, -1, 2393, 2392, 2449, -1, 2470, 2466, 2465, -1, 2393, 2449, 2395, -1, 2470, 2465, 2461, -1, 2470, 2461, 2468, -1, 2470, 2460, 2458, -1, 2388, 2387, 2136, -1, 2397, 2395, 2453, -1, 2381, 2400, 2382, -1, 2397, 2453, 2385, -1, 2471, 2472, 2473, -1, 2471, 1847, 1849, -1, 2471, 2473, 1847, -1, 1835, 2474, 1839, -1, 2475, 1849, 1851, -1, 2475, 2471, 1849, -1, 2475, 2472, 2471, -1, 2476, 2477, 2472, -1, 1845, 2478, 2474, -1, 2476, 2475, 1851, -1, 2476, 2472, 2475, -1, 1845, 2474, 1835, -1, 2479, 2480, 2477, -1, 1847, 2473, 2478, -1, 2479, 2477, 2476, -1, 1847, 2478, 1845, -1, 2481, 1851, 1831, -1, 2481, 1831, 1821, -1, 2481, 2476, 1851, -1, 2482, 2483, 2480, -1, 2482, 2480, 2479, -1, 2484, 2479, 2476, -1, 2484, 1821, 1820, -1, 2484, 2481, 1821, -1, 2484, 2476, 2481, -1, 2485, 2114, 2483, -1, 2485, 2483, 2482, -1, 2486, 1820, 1873, -1, 2486, 2482, 2479, -1, 2486, 2479, 2484, -1, 2486, 2484, 1820, -1, 2487, 2115, 2114, -1, 2487, 2114, 2485, -1, 2488, 2486, 1873, -1, 2488, 1873, 1867, -1, 2488, 1867, 1866, -1, 2488, 2485, 2482, -1, 2488, 2482, 2486, -1, 2489, 2117, 2115, -1, 2489, 2115, 2487, -1, 2490, 1866, 1869, -1, 2490, 2487, 2485, -1, 2490, 2488, 1866, -1, 2490, 2485, 2488, -1, 2491, 2117, 2489, -1, 2492, 1869, 1870, -1, 2492, 2490, 1869, -1, 2492, 2489, 2487, -1, 2492, 2487, 2490, -1, 2493, 2119, 2117, -1, 2493, 2117, 2491, -1, 2494, 1870, 1853, -1, 2494, 2492, 1870, -1, 2494, 2491, 2489, -1, 2494, 2489, 2492, -1, 2495, 2121, 2119, -1, 2495, 2493, 1825, -1, 2495, 1825, 1855, -1, 2495, 2119, 2493, -1, 2496, 2491, 2494, -1, 2496, 1825, 2493, -1, 2496, 2493, 2491, -1, 2496, 2494, 1853, -1, 2496, 1853, 1825, -1, 2497, 2123, 2121, -1, 2497, 2495, 1855, -1, 2497, 2121, 2495, -1, 2498, 1856, 2123, -1, 2498, 2123, 2497, -1, 2498, 2497, 1855, -1, 2498, 1855, 1856, -1, 1857, 2123, 1856, -1, 1857, 2125, 2123, -1, 1858, 2127, 2125, -1, 1858, 2125, 1857, -1, 1814, 2127, 1858, -1, 1818, 2127, 1814, -1, 2499, 2136, 2500, -1, 2501, 2502, 2503, -1, 2499, 2500, 2504, -1, 2499, 2504, 2505, -1, 2506, 2507, 2508, -1, 2509, 2510, 2511, -1, 2506, 2512, 2507, -1, 2509, 2513, 2510, -1, 2514, 2135, 2134, -1, 2515, 2129, 1818, -1, 2516, 2505, 2517, -1, 2514, 2134, 2518, -1, 2516, 2517, 2519, -1, 2520, 2502, 2501, -1, 2521, 2130, 2129, -1, 2522, 2523, 2513, -1, 2520, 2518, 2502, -1, 2521, 2129, 2515, -1, 2522, 2519, 2523, -1, 2524, 2512, 2506, -1, 2524, 2501, 2512, -1, 2525, 2513, 2509, -1, 2526, 2136, 2135, -1, 2526, 2135, 2514, -1, 2527, 2505, 2516, -1, 2527, 2136, 2499, -1, 2527, 2499, 2505, -1, 2528, 2518, 2520, -1, 2529, 2511, 2530, -1, 2529, 2509, 2511, -1, 2528, 2514, 2518, -1, 2531, 2520, 2501, -1, 2532, 2516, 2519, -1, 2532, 2519, 2522, -1, 2531, 2501, 2524, -1, 2533, 2508, 2534, -1, 2533, 2506, 2508, -1, 2535, 2522, 2513, -1, 2533, 2524, 2506, -1, 2535, 2513, 2525, -1, 2536, 2526, 2514, -1, 2537, 2530, 2538, -1, 2536, 2514, 2528, -1, 2536, 2136, 2526, -1, 2539, 2520, 2531, -1, 2539, 2528, 2520, -1, 2540, 2525, 2509, -1, 2540, 2509, 2529, -1, 2541, 2524, 2533, -1, 2542, 2527, 2516, -1, 2542, 2516, 2532, -1, 2542, 2136, 2527, -1, 2541, 2531, 2524, -1, 2543, 2529, 2530, -1, 2544, 2533, 2534, -1, 2543, 2530, 2537, -1, 2545, 2536, 2528, -1, 2545, 2528, 2539, -1, 2546, 2522, 2535, -1, 2545, 2136, 2536, -1, 2546, 2532, 2522, -1, 2547, 2539, 2531, -1, 2548, 2535, 2525, -1, 2547, 2531, 2541, -1, 2548, 2525, 2540, -1, 2549, 2533, 2544, -1, 2550, 2551, 2552, -1, 2550, 2538, 2551, -1, 2549, 2541, 2533, -1, 2550, 2537, 2538, -1, 2553, 2544, 2534, -1, 2553, 2534, 2554, -1, 2555, 2556, 2557, -1, 2555, 2557, 2079, -1, 2558, 2529, 2543, -1, 2558, 2540, 2529, -1, 2559, 2136, 2545, -1, 2559, 2539, 2547, -1, 2551, 2538, 2556, -1, 2559, 2545, 2539, -1, 2551, 2556, 2555, -1, 2560, 2542, 2532, -1, 2561, 2547, 2541, -1, 2560, 2136, 2542, -1, 2560, 2532, 2546, -1, 2561, 2541, 2549, -1, 2562, 2537, 2550, -1, 2562, 2552, 2563, -1, 2562, 2550, 2552, -1, 2564, 2549, 2544, -1, 2562, 2543, 2537, -1, 2564, 2544, 2553, -1, 2565, 2535, 2548, -1, 2566, 2553, 2554, -1, 2565, 2546, 2535, -1, 2567, 2548, 2540, -1, 2568, 2559, 2547, -1, 2568, 2136, 2559, -1, 2568, 2547, 2561, -1, 2567, 2540, 2558, -1, 2569, 2543, 2562, -1, 2569, 2562, 2563, -1, 2504, 2561, 2549, -1, 2569, 2558, 2543, -1, 2504, 2549, 2564, -1, 2570, 2136, 2560, -1, 2570, 2560, 2546, -1, 2570, 2546, 2565, -1, 2517, 2564, 2553, -1, 2517, 2553, 2566, -1, 2571, 2131, 2130, -1, 2571, 2521, 2572, -1, 2573, 2570, 2565, -1, 2523, 2554, 2510, -1, 2571, 2130, 2521, -1, 2573, 2565, 2548, -1, 2523, 2566, 2554, -1, 2573, 2548, 2567, -1, 2574, 2567, 2558, -1, 2503, 2132, 2131, -1, 2574, 2569, 2563, -1, 2500, 2136, 2568, -1, 2500, 2568, 2561, -1, 2503, 2131, 2571, -1, 2574, 2563, 2575, -1, 2500, 2561, 2504, -1, 2574, 2558, 2569, -1, 2502, 2133, 2132, -1, 2505, 2564, 2517, -1, 2576, 2570, 2573, -1, 2502, 2132, 2503, -1, 2576, 2136, 2570, -1, 2505, 2504, 2564, -1, 2577, 2567, 2574, -1, 2512, 2572, 2507, -1, 2577, 2575, 2578, -1, 2512, 2571, 2572, -1, 2577, 2573, 2567, -1, 2512, 2503, 2571, -1, 2577, 2574, 2575, -1, 2579, 2576, 2573, -1, 2519, 2566, 2523, -1, 2579, 2573, 2577, -1, 2579, 2580, 2136, -1, 2518, 2134, 2133, -1, 2579, 2578, 2580, -1, 2519, 2517, 2566, -1, 2579, 2136, 2576, -1, 2579, 2577, 2578, -1, 2518, 2133, 2502, -1, 2513, 2523, 2510, -1, 2501, 2503, 2512, -1, 2079, 2581, 2080, -1, 2582, 2105, 2103, -1, 2582, 2583, 2584, -1, 2582, 2584, 2105, -1, 2109, 2585, 2586, -1, 2109, 2586, 2111, -1, 2587, 2588, 2589, -1, 2590, 2582, 2103, -1, 2590, 2103, 2101, -1, 2590, 2589, 2583, -1, 2590, 2583, 2582, -1, 2591, 2592, 2588, -1, 2591, 2588, 2587, -1, 2593, 2589, 2590, -1, 2107, 2594, 2585, -1, 2593, 2590, 2101, -1, 2593, 2101, 2099, -1, 2107, 2585, 2109, -1, 2593, 2587, 2589, -1, 2595, 2596, 2592, -1, 2595, 2592, 2591, -1, 2597, 2593, 2099, -1, 2597, 2587, 2593, -1, 2597, 2591, 2587, -1, 2598, 2599, 2596, -1, 2105, 2584, 2594, -1, 2598, 2596, 2595, -1, 2105, 2594, 2107, -1, 2600, 2601, 2602, -1, 2600, 2602, 2599, -1, 2600, 2599, 2598, -1, 2603, 2099, 2097, -1, 2603, 2595, 2591, -1, 2603, 2591, 2597, -1, 2603, 2597, 2099, -1, 2604, 2097, 2095, -1, 2604, 2603, 2097, -1, 2604, 2598, 2595, -1, 2604, 2595, 2603, -1, 2605, 2606, 2601, -1, 2605, 2601, 2600, -1, 2607, 2604, 2095, -1, 2607, 2600, 2598, -1, 2607, 2598, 2604, -1, 2608, 2609, 2606, -1, 2608, 2606, 2605, -1, 2610, 2095, 2093, -1, 2610, 2607, 2095, -1, 2610, 2600, 2607, -1, 2610, 2605, 2600, -1, 2611, 2612, 2613, -1, 2611, 2613, 2609, -1, 2611, 2609, 2608, -1, 2614, 2093, 2091, -1, 2614, 2605, 2610, -1, 2614, 2608, 2605, -1, 2614, 2610, 2093, -1, 2615, 2091, 2089, -1, 2615, 2612, 2611, -1, 2615, 2608, 2614, -1, 2615, 2611, 2608, -1, 2615, 2614, 2091, -1, 2616, 2089, 2087, -1, 2616, 2617, 2612, -1, 2616, 2615, 2089, -1, 2616, 2612, 2615, -1, 2618, 2085, 2619, -1, 2618, 2087, 2085, -1, 2618, 2617, 2616, -1, 2618, 2619, 2617, -1, 2618, 2616, 2087, -1, 2083, 2619, 2085, -1, 2083, 2620, 2619, -1, 2080, 2620, 2083, -1, 2080, 2581, 2620, -1, 2621, 2622, 2623, -1, 2624, 2625, 2626, -1, 2624, 2627, 2625, -1, 2628, 2629, 2630, -1, 2631, 1951, 2632, -1, 2628, 2626, 2629, -1, 2631, 2632, 2633, -1, 2631, 2633, 2634, -1, 2635, 1937, 1936, -1, 2636, 1947, 1945, -1, 2636, 1945, 2637, -1, 2638, 2634, 2639, -1, 2638, 2639, 2640, -1, 2641, 1939, 1937, -1, 2642, 2627, 2624, -1, 2643, 2640, 2622, -1, 2641, 1937, 2635, -1, 2643, 2622, 2621, -1, 2642, 2637, 2627, -1, 2644, 2623, 2645, -1, 2646, 2626, 2628, -1, 2646, 2624, 2626, -1, 2644, 2621, 2623, -1, 2646, 2628, 2630, -1, 2647, 1951, 2631, -1, 2648, 1951, 1949, -1, 2648, 1949, 1947, -1, 2647, 2631, 2634, -1, 2647, 2634, 2638, -1, 2648, 1947, 2636, -1, 2649, 2638, 2640, -1, 2649, 2640, 2643, -1, 2650, 2637, 2642, -1, 2650, 2636, 2637, -1, 2651, 2643, 2621, -1, 2651, 2621, 2644, -1, 2652, 2645, 2653, -1, 2654, 2624, 2646, -1, 2654, 2642, 2624, -1, 2655, 2630, 2656, -1, 2652, 2644, 2645, -1, 2655, 2646, 2630, -1, 2657, 2653, 2658, -1, 2659, 1951, 2648, -1, 2659, 2648, 2636, -1, 2660, 1951, 2647, -1, 2659, 2636, 2650, -1, 2660, 2638, 2649, -1, 2660, 2647, 2638, -1, 2661, 2643, 2651, -1, 2662, 2642, 2654, -1, 2662, 2650, 2642, -1, 2661, 2649, 2643, -1, 2663, 2646, 2655, -1, 2664, 2658, 2665, -1, 2664, 2666, 2667, -1, 2663, 2654, 2646, -1, 2664, 2665, 2666, -1, 2668, 2656, 2669, -1, 2668, 2655, 2656, -1, 2670, 2651, 2644, -1, 2671, 2650, 2662, -1, 2670, 2644, 2652, -1, 2671, 2659, 2650, -1, 2671, 1951, 2659, -1, 2672, 2653, 2657, -1, 2672, 2652, 2653, -1, 2673, 2654, 2663, -1, 2673, 2662, 2654, -1, 2674, 2657, 2658, -1, 2674, 2664, 2667, -1, 2674, 2658, 2664, -1, 2675, 2655, 2668, -1, 2676, 2665, 2677, -1, 2678, 2660, 2649, -1, 2676, 2677, 1860, -1, 2678, 1951, 2660, -1, 2675, 2663, 2655, -1, 2678, 2649, 2661, -1, 2679, 2668, 2669, -1, 2679, 2669, 2680, -1, 2666, 2665, 2676, -1, 2681, 2651, 2670, -1, 2682, 1951, 2671, -1, 2681, 2661, 2651, -1, 2682, 2662, 2673, -1, 2683, 2652, 2672, -1, 2682, 2671, 2662, -1, 2683, 2670, 2652, -1, 2684, 2674, 2667, -1, 2685, 2663, 2675, -1, 2684, 2686, 2687, -1, 2684, 2667, 2686, -1, 2685, 2673, 2663, -1, 2684, 2672, 2657, -1, 2684, 2657, 2674, -1, 2688, 2675, 2668, -1, 2689, 2678, 2661, -1, 2689, 1951, 2678, -1, 2688, 2668, 2679, -1, 2689, 2661, 2681, -1, 2690, 2681, 2670, -1, 2691, 2679, 2680, -1, 2690, 2670, 2683, -1, 2692, 2682, 2673, -1, 2692, 2673, 2685, -1, 2693, 2672, 2684, -1, 2693, 2683, 2672, -1, 2693, 2684, 2687, -1, 2692, 1951, 2682, -1, 2693, 2687, 2694, -1, 2633, 2675, 2688, -1, 2695, 1951, 2689, -1, 2633, 2685, 2675, -1, 2695, 2689, 2681, -1, 2695, 2681, 2690, -1, 2696, 2683, 2693, -1, 2697, 1941, 1939, -1, 2696, 2690, 2683, -1, 2697, 2641, 2698, -1, 2696, 2694, 2699, -1, 2639, 2688, 2679, -1, 2696, 2693, 2694, -1, 2639, 2679, 2691, -1, 2697, 1939, 2641, -1, 2700, 1951, 2695, -1, 2700, 2690, 2696, -1, 2622, 2680, 2623, -1, 2700, 2699, 1951, -1, 2700, 2695, 2690, -1, 2622, 2691, 2680, -1, 2625, 2697, 2698, -1, 2700, 2696, 2699, -1, 2625, 1941, 2697, -1, 2632, 1951, 2692, -1, 2627, 1943, 1941, -1, 2632, 2692, 2685, -1, 2632, 2685, 2633, -1, 2627, 1941, 2625, -1, 2626, 2698, 2629, -1, 2634, 2633, 2688, -1, 2626, 2625, 2698, -1, 2634, 2688, 2639, -1, 2637, 1945, 1943, -1, 2640, 2639, 2691, -1, 2640, 2691, 2622, -1, 2637, 1943, 2627, -1, 1860, 1842, 2701, -1, 2702, 1852, 1850, -1, 2702, 1979, 1977, -1, 2702, 1850, 1979, -1, 1983, 1834, 1833, -1, 1983, 1833, 1838, -1, 2703, 1830, 1854, -1, 2704, 1852, 2702, -1, 2704, 1854, 1852, -1, 2704, 1977, 1975, -1, 2704, 2702, 1977, -1, 2705, 1830, 2703, -1, 2705, 1819, 1830, -1, 2706, 2703, 1854, -1, 1981, 1848, 1834, -1, 2706, 1975, 1973, -1, 1981, 1834, 1983, -1, 2706, 2704, 1975, -1, 2706, 1854, 2704, -1, 2707, 1822, 1819, -1, 2707, 1819, 2705, -1, 2708, 2706, 1973, -1, 2708, 2705, 2703, -1, 2708, 2703, 2706, -1, 2709, 1872, 1822, -1, 1979, 1850, 1848, -1, 2709, 1822, 2707, -1, 1979, 1848, 1981, -1, 2710, 1872, 2709, -1, 2710, 1817, 1871, -1, 2710, 1871, 1872, -1, 2711, 1973, 1971, -1, 2711, 2705, 2708, -1, 2711, 2707, 2705, -1, 2711, 2708, 1973, -1, 2712, 1971, 1970, -1, 2712, 2711, 1971, -1, 2712, 2709, 2707, -1, 2712, 2707, 2711, -1, 2713, 1815, 1817, -1, 2713, 1817, 2710, -1, 2714, 2709, 2712, -1, 2714, 2712, 1970, -1, 2714, 2710, 2709, -1, 2715, 1844, 1815, -1, 2715, 1815, 2713, -1, 2716, 1970, 2717, -1, 2716, 2713, 2710, -1, 2716, 2710, 2714, -1, 2716, 2714, 1970, -1, 2718, 1864, 1843, -1, 2718, 1843, 1844, -1, 2718, 1844, 2715, -1, 2719, 2717, 2720, -1, 2719, 2715, 2713, -1, 2719, 2713, 2716, -1, 2719, 2716, 2717, -1, 2721, 2720, 2722, -1, 2721, 2718, 2715, -1, 2721, 2719, 2720, -1, 2721, 1864, 2718, -1, 2721, 2715, 2719, -1, 2723, 2722, 2724, -1, 2723, 1862, 1864, -1, 2723, 2721, 2722, -1, 2723, 1864, 2721, -1, 2725, 2726, 1861, -1, 2725, 2724, 2726, -1, 2725, 1861, 1862, -1, 2725, 2723, 2724, -1, 2725, 1862, 2723, -1, 2727, 1861, 2726, -1, 2727, 1829, 1861, -1, 2701, 1829, 2727, -1, 2701, 1842, 1829, -1, 2728, 2729, 2730, -1, 2728, 2731, 2732, -1, 2733, 2734, 2735, -1, 2728, 2730, 2731, -1, 2736, 2737, 1951, -1, 2738, 2732, 2739, -1, 2738, 2739, 2740, -1, 2741, 1959, 2742, -1, 2743, 2740, 2744, -1, 2743, 2744, 2745, -1, 2746, 2742, 2734, -1, 2746, 2734, 2733, -1, 2747, 2745, 1951, -1, 2748, 2733, 2737, -1, 2749, 2750, 2729, -1, 2748, 2737, 2736, -1, 2749, 2729, 2728, -1, 2749, 2732, 2738, -1, 2749, 2728, 2732, -1, 2751, 1961, 1959, -1, 2751, 1959, 2741, -1, 2752, 2738, 2740, -1, 2753, 1965, 1963, -1, 2752, 2740, 2743, -1, 2754, 2736, 1951, -1, 2755, 2743, 2745, -1, 2756, 2742, 2746, -1, 2755, 2745, 2747, -1, 2756, 2741, 2742, -1, 2757, 1963, 1961, -1, 2758, 2753, 1963, -1, 2757, 1961, 2751, -1, 2757, 2758, 1963, -1, 2759, 2746, 2733, -1, 2760, 1965, 2753, -1, 2761, 2747, 1951, -1, 2759, 2733, 2748, -1, 2762, 2750, 2749, -1, 2762, 2738, 2752, -1, 2762, 2749, 2738, -1, 1967, 1965, 2760, -1, 2763, 2736, 2754, -1, 2763, 2748, 2736, -1, 2764, 2752, 2743, -1, 2764, 2743, 2755, -1, 2765, 2741, 2756, -1, 2765, 2751, 2741, -1, 2766, 2755, 2747, -1, 2766, 2747, 2761, -1, 2767, 2754, 1951, -1, 2768, 2761, 1951, -1, 2769, 2756, 2746, -1, 2770, 2771, 2750, -1, 2769, 2746, 2759, -1, 2770, 2750, 2762, -1, 2772, 2751, 2765, -1, 2770, 2762, 2752, -1, 2772, 2773, 2758, -1, 2770, 2752, 2764, -1, 2772, 2758, 2757, -1, 2772, 2765, 2773, -1, 2772, 2757, 2751, -1, 2774, 2748, 2763, -1, 2775, 2764, 2755, -1, 2775, 2755, 2766, -1, 2774, 2759, 2748, -1, 2776, 2761, 2768, -1, 2777, 2763, 2754, -1, 2777, 2754, 2767, -1, 2776, 2766, 2761, -1, 2778, 1951, 1999, -1, 2779, 2767, 1951, -1, 2778, 2768, 1951, -1, 2780, 2759, 2774, -1, 2781, 2764, 2775, -1, 2780, 2769, 2759, -1, 2782, 2774, 2763, -1, 2781, 2770, 2764, -1, 2782, 2763, 2777, -1, 2783, 2766, 2776, -1, 2783, 2775, 2766, -1, 2784, 2777, 2767, -1, 2784, 2767, 2779, -1, 2785, 1999, 1997, -1, 2785, 2768, 2778, -1, 2785, 2778, 1999, -1, 2786, 2769, 2780, -1, 2785, 2776, 2768, -1, 2786, 2787, 2769, -1, 2788, 2789, 2771, -1, 2790, 2779, 1951, -1, 2788, 2770, 2781, -1, 2788, 2771, 2770, -1, 2791, 2780, 2774, -1, 2792, 2775, 2783, -1, 2792, 2781, 2775, -1, 2791, 2774, 2782, -1, 2793, 2783, 2776, -1, 2731, 2782, 2777, -1, 1987, 2794, 2795, -1, 2793, 1997, 1995, -1, 2793, 2776, 2785, -1, 2793, 2785, 1997, -1, 1987, 2795, 1989, -1, 2731, 2777, 2784, -1, 2739, 2779, 2790, -1, 2796, 2797, 2789, -1, 2796, 2789, 2788, -1, 2739, 2784, 2779, -1, 2796, 2788, 2781, -1, 2796, 2781, 2792, -1, 2798, 2799, 2787, -1, 2798, 2780, 2791, -1, 1838, 2794, 1987, -1, 2798, 2787, 2786, -1, 2800, 1995, 1993, -1, 2798, 2786, 2780, -1, 2800, 2783, 2793, -1, 2798, 2791, 2799, -1, 2800, 2792, 2783, -1, 2800, 2793, 1995, -1, 2744, 2790, 1951, -1, 2735, 1955, 1953, -1, 2735, 1953, 1951, -1, 2801, 1993, 1991, -1, 2730, 2729, 2799, -1, 2801, 2796, 2792, -1, 2801, 2792, 2800, -1, 2730, 2799, 2791, -1, 2734, 1957, 1955, -1, 2801, 2800, 1993, -1, 2730, 2791, 2782, -1, 2730, 2782, 2731, -1, 2802, 1991, 1989, -1, 2734, 1955, 2735, -1, 2802, 2795, 2797, -1, 2802, 2797, 2796, -1, 2732, 2731, 2784, -1, 2802, 2801, 1991, -1, 2732, 2784, 2739, -1, 2802, 2796, 2801, -1, 2802, 1989, 2795, -1, 2803, 2756, 2769, -1, 2803, 2787, 2773, -1, 2803, 2769, 2787, -1, 2737, 2735, 1951, -1, 2803, 2773, 2765, -1, 2740, 2739, 2790, -1, 2803, 2765, 2756, -1, 2740, 2790, 2744, -1, 2742, 1959, 1957, -1, 2742, 1957, 2734, -1, 2745, 2744, 1951, -1, 2733, 2735, 2737, -1, 2804, 2805, 2806, -1, 2804, 2807, 2808, -1, 2804, 2806, 2807, -1, 2809, 2810, 1967, -1, 2811, 2808, 2812, -1, 2811, 2804, 2808, -1, 2811, 2805, 2804, -1, 2813, 2814, 2805, -1, 2815, 2816, 2810, -1, 2813, 2811, 2812, -1, 2813, 2805, 2811, -1, 2815, 2810, 2809, -1, 2817, 2818, 2814, -1, 2807, 2806, 2816, -1, 2817, 2814, 2813, -1, 2807, 2816, 2815, -1, 2819, 2812, 2820, -1, 2819, 2820, 2821, -1, 2819, 2813, 2812, -1, 2822, 2823, 2818, -1, 2822, 2818, 2817, -1, 2824, 2817, 2813, -1, 2824, 2821, 2825, -1, 2824, 2819, 2821, -1, 2824, 2813, 2819, -1, 2826, 2827, 2823, -1, 2826, 2823, 2822, -1, 2828, 2825, 2829, -1, 2828, 2822, 2817, -1, 2828, 2817, 2824, -1, 2828, 2824, 2825, -1, 2830, 2831, 2827, -1, 2830, 2827, 2826, -1, 2832, 2828, 2829, -1, 2832, 2829, 2833, -1, 2832, 2833, 2834, -1, 2832, 2826, 2822, -1, 2832, 2822, 2828, -1, 2835, 2836, 2831, -1, 2835, 2831, 2830, -1, 2837, 2834, 2838, -1, 2837, 2830, 2826, -1, 2837, 2832, 2834, -1, 2837, 2826, 2832, -1, 2839, 2836, 2835, -1, 2840, 2838, 2841, -1, 2840, 2837, 2838, -1, 2840, 2835, 2830, -1, 2840, 2830, 2837, -1, 2842, 2843, 2836, -1, 2842, 2836, 2839, -1, 2844, 2841, 2845, -1, 2844, 2840, 2841, -1, 2844, 2839, 2835, -1, 2844, 2835, 2840, -1, 2846, 2847, 2843, -1, 2846, 2842, 2848, -1, 2846, 2848, 2849, -1, 2846, 2843, 2842, -1, 2850, 2839, 2844, -1, 2850, 2848, 2842, -1, 2850, 2842, 2839, -1, 2850, 2844, 2845, -1, 2850, 2845, 2848, -1, 2851, 2846, 2849, -1, 2851, 2847, 2846, -1, 2852, 2853, 2854, -1, 2852, 2854, 2847, -1, 2852, 2847, 2851, -1, 2852, 2851, 2849, -1, 2852, 2849, 2853, -1, 2855, 2854, 2853, -1, 2855, 2856, 2854, -1, 2857, 2858, 2856, -1, 2857, 2856, 2855, -1, 2859, 2858, 2857, -1, 1936, 2858, 2859, -1, 2037, 2022, 2136, -1, 2037, 2136, 2467, -1, 2036, 2467, 2382, -1, 2036, 2037, 2467, -1, 2033, 2382, 2400, -1, 2033, 2036, 2382, -1, 2020, 2400, 2399, -1, 2020, 2033, 2400, -1, 2031, 2399, 2411, -1, 2031, 2020, 2399, -1, 2032, 2411, 2409, -1, 2032, 2031, 2411, -1, 2047, 2409, 2408, -1, 2047, 2032, 2409, -1, 2044, 2408, 1839, -1, 2044, 2047, 2408, -1, 2045, 2044, 1839, -1, 2860, 1839, 2474, -1, 2860, 2045, 1839, -1, 2861, 2474, 2478, -1, 2861, 2860, 2474, -1, 2862, 2478, 2473, -1, 2862, 2861, 2478, -1, 2863, 2473, 2472, -1, 2863, 2862, 2473, -1, 2864, 2472, 2477, -1, 2864, 2863, 2472, -1, 2865, 2477, 2480, -1, 2865, 2864, 2477, -1, 2866, 2480, 2483, -1, 2866, 2865, 2480, -1, 2867, 2866, 2483, -1, 2867, 2483, 2114, -1, 2113, 2867, 2114, -1, 2868, 2869, 2378, -1, 2868, 2870, 2869, -1, 2871, 2872, 2873, -1, 2874, 2875, 2876, -1, 2871, 2877, 2878, -1, 2871, 2878, 2879, -1, 2871, 2879, 2872, -1, 2880, 2876, 2875, -1, 2871, 2881, 2877, -1, 2882, 2874, 2876, -1, 2883, 2881, 2871, -1, 2884, 2380, 2876, -1, 2883, 2885, 2886, -1, 2883, 2886, 2887, -1, 2888, 2889, 2868, -1, 2883, 2887, 2890, -1, 2884, 2876, 2880, -1, 2883, 2890, 2891, -1, 2883, 2891, 2881, -1, 2378, 2380, 2892, -1, 2893, 2868, 2889, -1, 2883, 2894, 2895, -1, 2883, 2895, 2885, -1, 2896, 2868, 2897, -1, 2898, 2882, 2876, -1, 2899, 2888, 2868, -1, 2900, 2380, 2884, -1, 2901, 2898, 2876, -1, 2897, 2868, 2893, -1, 2902, 2899, 2868, -1, 2903, 2380, 2900, -1, 2892, 2380, 2903, -1, 2904, 2896, 2897, -1, 2905, 2902, 2868, -1, 2906, 2378, 2907, -1, 2906, 2868, 2378, -1, 2906, 2905, 2868, -1, 2908, 2907, 2909, -1, 2908, 2906, 2907, -1, 2910, 2896, 2904, -1, 2911, 2909, 2912, -1, 2913, 2914, 2915, -1, 2913, 2915, 2916, -1, 2913, 2916, 2917, -1, 2913, 2917, 2918, -1, 2913, 2918, 2901, -1, 2911, 2908, 2909, -1, 2913, 2901, 2876, -1, 2919, 2894, 2896, -1, 2919, 2896, 2910, -1, 2872, 2912, 2920, -1, 2378, 2921, 2922, -1, 2872, 2920, 2873, -1, 2378, 2892, 2923, -1, 2378, 2923, 2924, -1, 2378, 2924, 2925, -1, 2378, 2925, 2926, -1, 2872, 2911, 2912, -1, 2927, 2894, 2919, -1, 2928, 2378, 2926, -1, 2873, 2914, 2913, -1, 2873, 2929, 2930, -1, 2931, 2894, 2927, -1, 2873, 2930, 2914, -1, 2932, 2378, 2928, -1, 2933, 2894, 2931, -1, 2934, 2929, 2873, -1, 2935, 2894, 2933, -1, 2907, 2378, 2932, -1, 2895, 2894, 2935, -1, 2920, 2934, 2873, -1, 2869, 2921, 2378, -1, 2936, 2910, 2904, -1, 2936, 2904, 2937, -1, 2938, 2939, 2878, -1, 2878, 2939, 2879, -1, 2879, 2940, 2872, -1, 2939, 2940, 2879, -1, 2872, 2941, 2911, -1, 2940, 2941, 2872, -1, 2911, 2942, 2908, -1, 2941, 2942, 2911, -1, 2908, 2943, 2906, -1, 2942, 2943, 2908, -1, 2906, 2944, 2905, -1, 2943, 2944, 2906, -1, 2905, 2945, 2902, -1, 2944, 2945, 2905, -1, 2902, 2946, 2899, -1, 2945, 2946, 2902, -1, 2899, 2947, 2888, -1, 2946, 2947, 2899, -1, 2888, 2948, 2889, -1, 2947, 2948, 2888, -1, 2889, 2949, 2893, -1, 2948, 2949, 2889, -1, 2893, 2950, 2897, -1, 2949, 2950, 2893, -1, 2897, 2937, 2904, -1, 2950, 2937, 2897, -1, 2877, 2951, 2938, -1, 2877, 2938, 2878, -1, 2936, 2952, 2910, -1, 2910, 2952, 2919, -1, 2919, 2953, 2927, -1, 2952, 2953, 2919, -1, 2927, 2954, 2931, -1, 2953, 2954, 2927, -1, 2931, 2955, 2933, -1, 2954, 2955, 2931, -1, 2933, 2956, 2935, -1, 2955, 2956, 2933, -1, 2935, 2957, 2895, -1, 2956, 2957, 2935, -1, 2895, 2958, 2885, -1, 2957, 2958, 2895, -1, 2885, 2959, 2886, -1, 2958, 2959, 2885, -1, 2886, 2960, 2887, -1, 2959, 2960, 2886, -1, 2887, 2961, 2890, -1, 2960, 2961, 2887, -1, 2890, 2962, 2891, -1, 2961, 2962, 2890, -1, 2891, 2963, 2881, -1, 2962, 2963, 2891, -1, 2881, 2951, 2877, -1, 2963, 2951, 2881, -1, 2871, 2964, 2883, -1, 2883, 2964, 2965, -1, 2894, 2966, 2896, -1, 2896, 2966, 2967, -1, 2966, 2883, 2965, -1, 2894, 2883, 2966, -1, 2929, 2968, 2969, -1, 2929, 2969, 2930, -1, 2970, 2971, 2903, -1, 2903, 2971, 2892, -1, 2892, 2972, 2923, -1, 2971, 2972, 2892, -1, 2923, 2973, 2924, -1, 2972, 2973, 2923, -1, 2924, 2974, 2925, -1, 2973, 2974, 2924, -1, 2925, 2975, 2926, -1, 2974, 2975, 2925, -1, 2926, 2976, 2928, -1, 2975, 2976, 2926, -1, 2928, 2977, 2932, -1, 2976, 2977, 2928, -1, 2932, 2978, 2907, -1, 2977, 2978, 2932, -1, 2907, 2979, 2909, -1, 2978, 2979, 2907, -1, 2909, 2980, 2912, -1, 2979, 2980, 2909, -1, 2912, 2981, 2920, -1, 2980, 2981, 2912, -1, 2920, 2982, 2934, -1, 2981, 2982, 2920, -1, 2934, 2968, 2929, -1, 2982, 2968, 2934, -1, 2970, 2903, 2900, -1, 2970, 2900, 2983, -1, 2969, 2984, 2930, -1, 2930, 2984, 2914, -1, 2914, 2985, 2915, -1, 2984, 2985, 2914, -1, 2915, 2986, 2916, -1, 2985, 2986, 2915, -1, 2916, 2987, 2917, -1, 2986, 2987, 2916, -1, 2917, 2988, 2918, -1, 2987, 2988, 2917, -1, 2918, 2989, 2901, -1, 2988, 2989, 2918, -1, 2901, 2990, 2898, -1, 2989, 2990, 2901, -1, 2898, 2991, 2882, -1, 2990, 2991, 2898, -1, 2882, 2992, 2874, -1, 2991, 2992, 2882, -1, 2874, 2993, 2875, -1, 2992, 2993, 2874, -1, 2875, 2994, 2880, -1, 2993, 2994, 2875, -1, 2880, 2995, 2884, -1, 2994, 2995, 2880, -1, 2884, 2983, 2900, -1, 2995, 2983, 2884, -1, 2996, 2081, 2873, -1, 2964, 2871, 2081, -1, 2871, 2873, 2081, -1, 2913, 2997, 2873, -1, 2873, 2997, 2996, -1, 2997, 2913, 2998, -1, 2998, 2913, 2876, -1, 2380, 2377, 2876, -1, 2876, 2377, 2998, -1, 2868, 2967, 2999, -1, 2868, 2896, 2967, -1, 2993, 2992, 2998, -1, 2998, 2994, 2993, -1, 2992, 2991, 2998, -1, 2377, 2995, 2998, -1, 2998, 2995, 2994, -1, 2991, 2990, 2998, -1, 2377, 2983, 2995, -1, 2990, 2989, 2998, -1, 2377, 2970, 2983, -1, 2377, 2971, 2970, -1, 2989, 2997, 2998, -1, 2984, 2997, 2985, -1, 2985, 2997, 2986, -1, 2986, 2997, 2987, -1, 2987, 2997, 2988, -1, 2988, 2997, 2989, -1, 2971, 2379, 2972, -1, 2972, 2379, 2973, -1, 2973, 2379, 2974, -1, 2984, 2996, 2997, -1, 2969, 2996, 2984, -1, 2968, 2996, 2969, -1, 2968, 2982, 2996, -1, 3000, 3001, 2379, -1, 2379, 3001, 3002, -1, 3002, 3003, 2379, -1, 3004, 3005, 3000, -1, 3000, 3005, 3001, -1, 2379, 3006, 2974, -1, 3003, 3006, 2379, -1, 3004, 3007, 3005, -1, 3006, 3008, 2974, -1, 2974, 3008, 2975, -1, 2975, 3008, 2976, -1, 3004, 2110, 3007, -1, 3008, 3009, 2976, -1, 2976, 3009, 2977, -1, 3004, 3010, 2110, -1, 3010, 2108, 2110, -1, 3009, 3011, 2977, -1, 2977, 3011, 2978, -1, 2978, 3011, 2979, -1, 3010, 2106, 2108, -1, 3011, 3012, 2979, -1, 2979, 3012, 2980, -1, 3010, 3013, 2106, -1, 3013, 2104, 2106, -1, 3012, 3014, 2980, -1, 2980, 3014, 2981, -1, 3013, 2999, 2104, -1, 2999, 2102, 2104, -1, 2981, 3015, 2982, -1, 2982, 3015, 2996, -1, 3014, 3015, 2981, -1, 2999, 2100, 2102, -1, 3015, 3016, 2996, -1, 2999, 2098, 2100, -1, 3016, 3017, 2996, -1, 3017, 3018, 2996, -1, 2999, 2947, 2098, -1, 2948, 2947, 2999, -1, 2098, 2947, 2096, -1, 2999, 2949, 2948, -1, 2947, 2946, 2096, -1, 2999, 2950, 2949, -1, 2096, 2945, 2094, -1, 2946, 2945, 2096, -1, 2967, 2937, 2950, -1, 2094, 2944, 2092, -1, 2945, 2944, 2094, -1, 2944, 2943, 2092, -1, 2092, 2942, 2090, -1, 2943, 2942, 2092, -1, 2967, 2936, 2937, -1, 2090, 2941, 2088, -1, 2942, 2941, 2090, -1, 2966, 2952, 2967, -1, 2967, 2952, 2936, -1, 2088, 2940, 2086, -1, 2941, 2940, 2088, -1, 2966, 2953, 2952, -1, 2940, 2939, 2086, -1, 2966, 2954, 2953, -1, 2966, 2955, 2954, -1, 2966, 2956, 2955, -1, 2966, 2957, 2956, -1, 2082, 2964, 2078, -1, 2084, 2964, 2082, -1, 2086, 2964, 2084, -1, 2963, 2964, 2951, -1, 2938, 2964, 2939, -1, 2939, 2964, 2086, -1, 2951, 2964, 2938, -1, 2963, 2965, 2964, -1, 2958, 2965, 2959, -1, 2959, 2965, 2960, -1, 2960, 2965, 2961, -1, 2961, 2965, 2962, -1, 2962, 2965, 2963, -1, 2081, 2996, 3018, -1, 2964, 2081, 2078, -1, 2966, 2965, 2957, -1, 2957, 2965, 2958, -1, 2999, 2967, 2950, -1, 2377, 2379, 2971, -1, 2110, 2111, 2456, -1, 3007, 2456, 2460, -1, 3007, 2110, 2456, -1, 3005, 2460, 2469, -1, 3005, 3007, 2460, -1, 3001, 2469, 2459, -1, 3001, 3005, 2469, -1, 3002, 2459, 2448, -1, 3002, 3001, 2459, -1, 3003, 2448, 2441, -1, 3003, 3002, 2448, -1, 3006, 2441, 2440, -1, 3006, 3003, 2441, -1, 3008, 2440, 2136, -1, 3008, 3006, 2440, -1, 3009, 2136, 2580, -1, 3009, 3008, 2136, -1, 3011, 3009, 2580, -1, 3012, 2580, 2578, -1, 3012, 3011, 2580, -1, 3014, 2578, 2575, -1, 3014, 3012, 2578, -1, 3015, 2575, 2563, -1, 3015, 3014, 2575, -1, 3016, 2563, 2552, -1, 3016, 3015, 2563, -1, 3017, 2552, 2551, -1, 3017, 3016, 2552, -1, 3018, 2551, 2555, -1, 3018, 3017, 2551, -1, 2081, 3018, 2555, -1, 2081, 2555, 2079, -1, 2005, 2004, 3019, -1, 2066, 2067, 3020, -1, 2004, 3021, 3019, -1, 2067, 3022, 3020, -1, 2004, 2003, 3021, -1, 3023, 2013, 3024, -1, 3024, 2012, 3025, -1, 2013, 2012, 3024, -1, 3022, 2068, 3026, -1, 3027, 2014, 3023, -1, 3023, 2014, 2013, -1, 2067, 2068, 3022, -1, 2002, 3028, 2003, -1, 2003, 3028, 3021, -1, 3025, 2011, 3029, -1, 2012, 2011, 3025, -1, 2002, 2077, 3028, -1, 2068, 2069, 3026, -1, 3030, 2015, 3027, -1, 3027, 2015, 2014, -1, 3029, 2010, 3031, -1, 2011, 2010, 3029, -1, 3032, 2009, 3033, -1, 3031, 2009, 3032, -1, 2010, 2009, 3031, -1, 3034, 2076, 2002, -1, 2002, 2076, 2077, -1, 2061, 2016, 2062, -1, 3026, 2070, 3035, -1, 2062, 2016, 3030, -1, 2069, 2070, 3026, -1, 3030, 2016, 2015, -1, 3036, 2075, 3034, -1, 2061, 3037, 2016, -1, 3034, 2075, 2076, -1, 2009, 2008, 3033, -1, 2061, 2063, 3037, -1, 3035, 2071, 3038, -1, 2070, 2071, 3035, -1, 2008, 3039, 3033, -1, 3040, 2074, 3036, -1, 3036, 2074, 2075, -1, 2063, 3041, 3037, -1, 2008, 2007, 3039, -1, 3038, 2072, 3042, -1, 2071, 2072, 3038, -1, 3042, 2073, 3040, -1, 2063, 2064, 3041, -1, 3040, 2073, 2074, -1, 2072, 2073, 3042, -1, 2007, 3043, 3039, -1, 2064, 3044, 3041, -1, 2007, 2006, 3043, -1, 2064, 2065, 3044, -1, 2006, 3045, 3043, -1, 2065, 3046, 3044, -1, 2006, 2005, 3045, -1, 2065, 2066, 3046, -1, 2005, 3019, 3045, -1, 2066, 3020, 3046, -1, 3028, 2077, 1642, -1, 3028, 1642, 3047, -1, 3028, 3047, 3048, -1, 3021, 3048, 3049, -1, 3021, 3028, 3048, -1, 3019, 3049, 3050, -1, 3019, 3021, 3049, -1, 3045, 3050, 3051, -1, 3045, 3019, 3050, -1, 3043, 3045, 3051, -1, 3039, 3051, 3052, -1, 3039, 3052, 3053, -1, 3039, 3043, 3051, -1, 3033, 3053, 3054, -1, 3033, 3039, 3053, -1, 3032, 3033, 3054, -1, 3031, 3054, 3055, -1, 3031, 3055, 3056, -1, 3031, 3032, 3054, -1, 3029, 3056, 3057, -1, 3029, 3031, 3056, -1, 3025, 3057, 3058, -1, 3025, 3029, 3057, -1, 3024, 3058, 3059, -1, 3024, 3025, 3058, -1, 3023, 3059, 3060, -1, 3023, 3024, 3059, -1, 3027, 3023, 3060, -1, 3030, 3060, 3061, -1, 3030, 3027, 3060, -1, 2062, 3030, 3061, -1, 2062, 3061, 1483, -1, 3062, 3063, 3064, -1, 3062, 3065, 3063, -1, 3066, 3067, 3068, -1, 3066, 3068, 3069, -1, 3070, 3071, 3065, -1, 3070, 3072, 3071, -1, 3073, 3074, 3075, -1, 3073, 3076, 3074, -1, 3077, 3078, 3079, -1, 3077, 3064, 3078, -1, 3080, 3081, 3082, -1, 3080, 3083, 3081, -1, 3084, 3085, 3076, -1, 3084, 3076, 3073, -1, 3084, 3069, 3085, -1, 3086, 3087, 3088, -1, 3086, 3079, 3087, -1, 3089, 3070, 3065, -1, 3089, 3065, 3062, -1, 3090, 3067, 3066, -1, 3090, 3088, 3067, -1, 3091, 1495, 1486, -1, 3091, 3092, 3072, -1, 3091, 3072, 3070, -1, 3091, 1486, 3092, -1, 3093, 3084, 3073, -1, 3094, 3062, 3064, -1, 3094, 3064, 3077, -1, 3095, 3083, 3080, -1, 3095, 3075, 3083, -1, 3096, 3066, 3069, -1, 3096, 3069, 3084, -1, 3097, 3077, 3079, -1, 3097, 3079, 3086, -1, 3098, 3070, 3089, -1, 3098, 1501, 1495, -1, 3098, 1495, 3091, -1, 3098, 3091, 3070, -1, 3099, 3086, 3088, -1, 3099, 3088, 3090, -1, 3100, 3084, 3093, -1, 3100, 3096, 3084, -1, 3101, 3089, 3062, -1, 3101, 3062, 3094, -1, 3102, 3075, 3095, -1, 3102, 3073, 3075, -1, 3103, 3066, 3096, -1, 3103, 3090, 3066, -1, 3103, 3096, 3100, -1, 3104, 3077, 3097, -1, 3104, 3094, 3077, -1, 3105, 3086, 3099, -1, 3105, 3097, 3086, -1, 3106, 3103, 3100, -1, 3107, 1501, 3098, -1, 3107, 3089, 3101, -1, 3107, 3098, 3089, -1, 3108, 3073, 3102, -1, 3108, 3093, 3073, -1, 3109, 3090, 3103, -1, 3109, 3099, 3090, -1, 3110, 3101, 3094, -1, 3111, 3047, 1642, -1, 3110, 3094, 3104, -1, 3112, 3104, 3097, -1, 3112, 3097, 3105, -1, 3111, 1642, 1458, -1, 3113, 3048, 3047, -1, 3114, 3103, 3106, -1, 3114, 3109, 3103, -1, 3113, 3047, 3111, -1, 3115, 3093, 3108, -1, 3116, 3049, 3048, -1, 3115, 3100, 3093, -1, 3117, 3099, 3109, -1, 3116, 3048, 3113, -1, 3117, 3105, 3099, -1, 3118, 1538, 1501, -1, 3118, 1501, 3107, -1, 3119, 1458, 1460, -1, 3118, 3101, 3110, -1, 3118, 3107, 3101, -1, 3119, 3111, 1458, -1, 3120, 3110, 3104, -1, 3120, 3104, 3112, -1, 3121, 3050, 3049, -1, 3122, 3109, 3114, -1, 3122, 3117, 3109, -1, 3121, 3049, 3116, -1, 3123, 3100, 3115, -1, 3123, 3106, 3100, -1, 3124, 3119, 1460, -1, 3125, 3111, 3119, -1, 3126, 3112, 3105, -1, 3126, 3105, 3117, -1, 3125, 3113, 3111, -1, 3127, 3110, 3120, -1, 3127, 1538, 3118, -1, 3128, 3051, 3050, -1, 3127, 3118, 3110, -1, 3129, 3117, 3122, -1, 3128, 3050, 3121, -1, 3129, 3126, 3117, -1, 3130, 3106, 3123, -1, 3131, 3119, 3124, -1, 3131, 3125, 3119, -1, 3130, 3114, 3106, -1, 3132, 3116, 3113, -1, 3133, 3120, 3112, -1, 3133, 3112, 3126, -1, 3132, 3113, 3125, -1, 3134, 3126, 3129, -1, 3134, 3133, 3126, -1, 3135, 1460, 1476, -1, 3135, 3124, 1460, -1, 3136, 3122, 3114, -1, 3136, 3114, 3130, -1, 3137, 3051, 3128, -1, 3137, 3052, 3051, -1, 3138, 1596, 1538, -1, 3138, 1538, 3127, -1, 3138, 3120, 3133, -1, 3138, 3127, 3120, -1, 3139, 1596, 3138, -1, 3139, 3133, 3134, -1, 3139, 3138, 3133, -1, 3140, 3132, 3125, -1, 3141, 3122, 3136, -1, 3141, 3129, 3122, -1, 3140, 3125, 3131, -1, 3142, 3116, 3132, -1, 3143, 3134, 3129, -1, 3142, 3121, 3116, -1, 3143, 3129, 3141, -1, 3144, 1541, 1596, -1, 3144, 1596, 3139, -1, 3145, 3124, 3135, -1, 3144, 3139, 3134, -1, 3144, 3134, 3143, -1, 3145, 3131, 3124, -1, 3146, 3053, 3052, -1, 3147, 3148, 3149, -1, 3147, 3143, 3148, -1, 3146, 3052, 3137, -1, 3150, 3141, 3136, -1, 3151, 3135, 1476, -1, 3150, 3143, 3141, -1, 3150, 3148, 3143, -1, 3152, 3132, 3140, -1, 3153, 3148, 3150, -1, 3152, 3142, 3132, -1, 3154, 3155, 3156, -1, 3154, 3156, 3149, -1, 3154, 3149, 3148, -1, 3157, 3121, 3142, -1, 3154, 3148, 3153, -1, 3157, 3128, 3121, -1, 3158, 1541, 3144, -1, 3158, 3144, 3143, -1, 3158, 3143, 3147, -1, 3159, 3158, 3147, -1, 3159, 1543, 1541, -1, 3159, 1541, 3158, -1, 3160, 1543, 3159, -1, 3160, 3147, 3149, -1, 3160, 3149, 3161, -1, 3160, 3161, 1543, -1, 3160, 3159, 3147, -1, 3162, 3140, 3131, -1, 3162, 3131, 3145, -1, 3163, 3150, 3136, -1, 3164, 3054, 3053, -1, 3163, 3136, 3130, -1, 3163, 3153, 3150, -1, 3165, 3153, 3163, -1, 3164, 3053, 3146, -1, 3166, 3145, 3135, -1, 3167, 3154, 3153, -1, 3167, 3168, 3155, -1, 3166, 3135, 3151, -1, 3167, 3155, 3154, -1, 3167, 3153, 3165, -1, 3169, 3163, 3130, -1, 3170, 3142, 3152, -1, 3169, 3130, 3123, -1, 3169, 3165, 3163, -1, 3170, 3157, 3142, -1, 3171, 1476, 1507, -1, 3171, 3151, 1476, -1, 3172, 3165, 3169, -1, 3173, 3167, 3165, -1, 3173, 3168, 3167, -1, 3174, 3137, 3128, -1, 3173, 3165, 3172, -1, 3173, 3175, 3168, -1, 3174, 3128, 3157, -1, 3176, 3172, 3169, -1, 3176, 3169, 3123, -1, 3176, 3123, 3115, -1, 3177, 3172, 3176, -1, 3178, 3140, 3162, -1, 3178, 3152, 3140, -1, 3179, 3173, 3172, -1, 3179, 3175, 3173, -1, 3179, 3172, 3177, -1, 3180, 3055, 3054, -1, 3179, 3181, 3175, -1, 3182, 3177, 3176, -1, 3182, 3176, 3115, -1, 3180, 3054, 3164, -1, 3182, 3115, 3108, -1, 3183, 3177, 3182, -1, 3184, 3162, 3145, -1, 3184, 3145, 3166, -1, 3185, 3177, 3183, -1, 3185, 3179, 3177, -1, 3185, 3181, 3179, -1, 3185, 2017, 3181, -1, 3186, 3157, 3170, -1, 3186, 3174, 3157, -1, 3187, 3183, 3182, -1, 3187, 3182, 3108, -1, 3187, 3108, 3102, -1, 3188, 2018, 2017, -1, 3189, 3166, 3151, -1, 3188, 3185, 3183, -1, 3189, 3151, 3171, -1, 3188, 2017, 3185, -1, 3188, 3183, 3187, -1, 3190, 3102, 3095, -1, 3190, 3187, 3102, -1, 3191, 3137, 3174, -1, 3191, 3146, 3137, -1, 3192, 3170, 3152, -1, 3193, 3190, 3194, -1, 3192, 3152, 3178, -1, 3193, 3188, 3187, -1, 3193, 3187, 3190, -1, 3193, 3194, 3188, -1, 3195, 3056, 3055, -1, 3196, 3188, 3194, -1, 3197, 2058, 2018, -1, 3197, 2018, 3188, -1, 3195, 3055, 3180, -1, 3197, 3188, 3196, -1, 3198, 3095, 3080, -1, 3198, 3190, 3095, -1, 3198, 3194, 3190, -1, 3199, 3171, 1507, -1, 3198, 3196, 3194, -1, 3200, 2056, 2058, -1, 3200, 2058, 3197, -1, 3200, 3197, 3196, -1, 3201, 3162, 3184, -1, 3200, 3196, 3198, -1, 3201, 3178, 3162, -1, 3202, 3198, 3080, -1, 3202, 3080, 3082, -1, 3203, 3174, 3186, -1, 3203, 3191, 3174, -1, 3204, 3198, 3202, -1, 3205, 2054, 2056, -1, 3205, 2056, 3200, -1, 3206, 3184, 3166, -1, 3205, 3200, 3198, -1, 3205, 3198, 3204, -1, 3206, 3166, 3189, -1, 3207, 3082, 3208, -1, 3207, 3202, 3082, -1, 3207, 3204, 3202, -1, 3209, 3164, 3146, -1, 3209, 3146, 3191, -1, 3210, 3208, 3211, -1, 3210, 2054, 3205, -1, 3210, 2050, 2052, -1, 3210, 2052, 2054, -1, 3210, 3207, 3208, -1, 3210, 3205, 3204, -1, 3210, 3211, 2050, -1, 3210, 3204, 3207, -1, 3212, 1507, 1521, -1, 3212, 3199, 1507, -1, 3213, 3170, 3192, -1, 3213, 3186, 3170, -1, 3214, 3057, 3056, -1, 3214, 3056, 3195, -1, 3215, 3189, 3171, -1, 3215, 3171, 3199, -1, 3216, 3192, 3178, -1, 3216, 3178, 3201, -1, 3217, 3209, 3191, -1, 3217, 3191, 3203, -1, 3218, 3201, 3184, -1, 3218, 3184, 3206, -1, 3219, 3180, 3164, -1, 3219, 3164, 3209, -1, 3220, 3199, 3212, -1, 3220, 3215, 3199, -1, 3221, 3186, 3213, -1, 3221, 3217, 3203, -1, 3221, 3203, 3186, -1, 3222, 3058, 3057, -1, 3222, 3057, 3214, -1, 3223, 3189, 3215, -1, 3223, 3206, 3189, -1, 3224, 3213, 3192, -1, 3224, 3192, 3216, -1, 3225, 3209, 3217, -1, 3225, 3219, 3209, -1, 3226, 3201, 3218, -1, 3226, 3216, 3201, -1, 3227, 3180, 3219, -1, 3227, 3195, 3180, -1, 3228, 3215, 3220, -1, 3228, 3223, 3215, -1, 3229, 3217, 3221, -1, 3230, 1521, 1529, -1, 3230, 1529, 2049, -1, 3230, 2049, 2050, -1, 3230, 3212, 1521, -1, 3071, 3059, 3058, -1, 3071, 3058, 3222, -1, 3231, 3206, 3223, -1, 3231, 3218, 3206, -1, 3232, 3221, 3213, -1, 3232, 3213, 3224, -1, 3232, 3229, 3221, -1, 3233, 3219, 3225, -1, 3233, 3227, 3219, -1, 3234, 3216, 3226, -1, 3234, 3224, 3216, -1, 3235, 3214, 3195, -1, 3235, 3195, 3227, -1, 3081, 3223, 3228, -1, 3081, 3231, 3223, -1, 3236, 3217, 3229, -1, 3236, 3225, 3217, -1, 3211, 3220, 3212, -1, 3211, 3212, 3230, -1, 3211, 3230, 2050, -1, 3072, 3060, 3059, -1, 3072, 3059, 3071, -1, 3237, 3218, 3231, -1, 3237, 3226, 3218, -1, 3068, 3229, 3232, -1, 3078, 3227, 3233, -1, 3078, 3235, 3227, -1, 3085, 3232, 3224, -1, 3085, 3224, 3234, -1, 3063, 3222, 3214, -1, 3063, 3214, 3235, -1, 3083, 3231, 3081, -1, 3083, 3237, 3231, -1, 3087, 3233, 3225, -1, 3087, 3225, 3236, -1, 3208, 3228, 3220, -1, 3208, 3220, 3211, -1, 3092, 1486, 1483, -1, 3092, 3061, 3060, -1, 3092, 1483, 3061, -1, 3092, 3060, 3072, -1, 3074, 3234, 3226, -1, 3074, 3226, 3237, -1, 3067, 3087, 3236, -1, 3067, 3236, 3229, -1, 3067, 3229, 3068, -1, 3064, 3235, 3078, -1, 3064, 3063, 3235, -1, 3069, 3232, 3085, -1, 3069, 3068, 3232, -1, 3065, 3071, 3222, -1, 3065, 3222, 3063, -1, 3075, 3237, 3083, -1, 3075, 3074, 3237, -1, 3079, 3233, 3087, -1, 3079, 3078, 3233, -1, 3082, 3228, 3208, -1, 3082, 3081, 3228, -1, 3076, 3234, 3074, -1, 3076, 3085, 3234, -1, 3088, 3087, 3067, -1, 1090, 3238, 1083, -1, 1579, 1574, 2128, -1, 1579, 2128, 2046, -1, 3239, 1969, 1074, -1, 1074, 1969, 1075, -1, 3240, 3239, 1080, -1, 1080, 3239, 1074, -1, 3241, 3240, 1080, -1, 3238, 3241, 1083, -1, 3242, 3238, 1090, -1, 3243, 3242, 1100, -1, 3244, 3243, 1110, -1, 3245, 3244, 1121, -1, 1978, 1980, 2862, -1, 1974, 1976, 2865, -1, 1972, 1974, 2866, -1, 3181, 2017, 2060, -1, 1968, 1972, 2867, -1, 3181, 2060, 3246, -1, 2867, 2113, 1968, -1, 2866, 2867, 1972, -1, 1553, 1536, 2118, -1, 2865, 2866, 1974, -1, 2126, 2128, 1574, -1, 2124, 2126, 1567, -1, 2122, 2124, 1560, -1, 2120, 2122, 1554, -1, 2118, 2120, 1553, -1, 2116, 2118, 1536, -1, 3175, 3246, 3247, -1, 2112, 2116, 1546, -1, 3175, 3181, 3246, -1, 1100, 3242, 1090, -1, 3168, 3247, 3248, -1, 3168, 3175, 3247, -1, 2864, 2865, 1976, -1, 3155, 3248, 3249, -1, 3155, 3168, 3248, -1, 1554, 1553, 2120, -1, 3156, 3249, 3250, -1, 3156, 3155, 3249, -1, 3149, 3250, 3251, -1, 2863, 1976, 1978, -1, 3149, 3156, 3250, -1, 2863, 2864, 1976, -1, 1110, 3243, 1100, -1, 1969, 3252, 1075, -1, 3161, 3252, 1969, -1, 3161, 3149, 3251, -1, 3161, 3251, 3252, -1, 1560, 1554, 2122, -1, 2113, 3161, 1969, -1, 2113, 1969, 1968, -1, 1543, 3161, 2113, -1, 2862, 2863, 1978, -1, 1121, 3244, 1110, -1, 2112, 1543, 2113, -1, 1546, 1543, 2112, -1, 1567, 1560, 2124, -1, 2861, 1980, 1982, -1, 2861, 2862, 1980, -1, 1083, 3241, 1080, -1, 1146, 3245, 1121, -1, 2035, 3245, 1146, -1, 1574, 1567, 2126, -1, 1536, 1546, 2116, -1, 2860, 2861, 1982, -1, 2860, 1982, 1984, -1, 2045, 2860, 1984, -1, 2045, 1984, 1985, -1, 3253, 3254, 3255, -1, 3256, 3257, 3258, -1, 3259, 3257, 3256, -1, 1325, 3260, 3261, -1, 3261, 3260, 3262, -1, 3262, 3260, 3263, -1, 3264, 3265, 3266, -1, 3267, 3265, 3264, -1, 3268, 3269, 3270, -1, 3270, 3269, 3267, -1, 3263, 3271, 3253, -1, 3253, 3271, 3254, -1, 3272, 3273, 3259, -1, 3259, 3273, 3257, -1, 3267, 3274, 3265, -1, 3269, 3274, 3267, -1, 3268, 3275, 3269, -1, 3254, 3275, 3268, -1, 1369, 3276, 1325, -1, 1325, 3276, 3260, -1, 3263, 3276, 3271, -1, 3260, 3276, 3263, -1, 3272, 3277, 3273, -1, 3266, 3277, 3272, -1, 3269, 3278, 3274, -1, 3275, 3278, 3269, -1, 3271, 3279, 3254, -1, 3254, 3279, 3275, -1, 3265, 3280, 3266, -1, 3266, 3280, 3277, -1, 3279, 3281, 3275, -1, 3275, 3281, 3278, -1, 3271, 3282, 3279, -1, 1369, 3282, 3276, -1, 3276, 3282, 3271, -1, 3265, 3283, 3280, -1, 3274, 3283, 3265, -1, 1369, 3284, 3282, -1, 1392, 3284, 1369, -1, 3279, 3284, 3281, -1, 3282, 3284, 3279, -1, 3274, 3285, 3283, -1, 3278, 3285, 3274, -1, 3281, 3286, 3278, -1, 3278, 3286, 3285, -1, 3281, 3287, 3286, -1, 3284, 3287, 3281, -1, 1392, 3287, 3284, -1, 2326, 3287, 1392, -1, 3288, 3289, 1272, -1, 3290, 3291, 3289, -1, 3289, 3291, 1272, -1, 1272, 3291, 1280, -1, 3292, 3293, 3294, -1, 1280, 3295, 2214, -1, 3291, 3295, 1280, -1, 3290, 3295, 3291, -1, 3293, 3296, 3290, -1, 2217, 3297, 2219, -1, 3296, 3297, 3290, -1, 3293, 3298, 3294, -1, 3289, 3298, 3290, -1, 3288, 3298, 3289, -1, 1392, 1413, 2326, -1, 3290, 3298, 3293, -1, 3294, 3298, 3288, -1, 2214, 3299, 2217, -1, 3295, 3299, 2214, -1, 2217, 3299, 3297, -1, 3290, 3299, 3295, -1, 3297, 3299, 3290, -1, 3300, 3301, 1401, -1, 1401, 3301, 1400, -1, 3292, 3302, 3293, -1, 3303, 3302, 3292, -1, 3293, 3302, 3296, -1, 3304, 3305, 3300, -1, 3302, 3306, 3296, -1, 3300, 3305, 3301, -1, 2219, 3307, 2221, -1, 3297, 3307, 2219, -1, 3304, 3308, 3305, -1, 3296, 3307, 3297, -1, 3306, 3307, 3296, -1, 3258, 3309, 3303, -1, 3303, 3309, 3302, -1, 3310, 3308, 3304, -1, 3302, 3309, 3306, -1, 3301, 3311, 1400, -1, 1400, 3311, 1423, -1, 3309, 3312, 3306, -1, 2221, 3313, 2223, -1, 3307, 3313, 2221, -1, 3306, 3313, 3307, -1, 3312, 3313, 3306, -1, 3257, 3314, 3258, -1, 3315, 3316, 3310, -1, 3258, 3314, 3309, -1, 3310, 3316, 3308, -1, 3309, 3314, 3312, -1, 3311, 3317, 1423, -1, 1423, 3317, 1246, -1, 3314, 3318, 3312, -1, 3305, 3319, 3301, -1, 2223, 3320, 2225, -1, 3313, 3320, 2223, -1, 3312, 3320, 3313, -1, 3318, 3320, 3312, -1, 3301, 3319, 3311, -1, 3257, 3321, 3314, -1, 3314, 3321, 3318, -1, 3273, 3321, 3257, -1, 2225, 3322, 2234, -1, 3323, 3324, 3315, -1, 3315, 3324, 3316, -1, 3320, 3322, 2225, -1, 3318, 3322, 3320, -1, 3277, 3325, 3273, -1, 3319, 3326, 3311, -1, 3273, 3325, 3321, -1, 3311, 3326, 3317, -1, 3321, 3327, 3318, -1, 3325, 3327, 3321, -1, 3318, 3327, 3322, -1, 3305, 3328, 3319, -1, 3308, 3328, 3305, -1, 3327, 3329, 3322, -1, 3325, 3329, 3327, -1, 3330, 3331, 3323, -1, 3323, 3331, 3324, -1, 3329, 3332, 3322, -1, 3317, 3333, 1246, -1, 2234, 3334, 2328, -1, 3322, 3334, 2234, -1, 3332, 3334, 3322, -1, 3277, 3335, 3325, -1, 3328, 3336, 3319, -1, 3325, 3335, 3329, -1, 3319, 3336, 3326, -1, 3329, 3335, 3332, -1, 3332, 3337, 3334, -1, 2328, 3337, 2331, -1, 3308, 3338, 3328, -1, 3334, 3337, 2328, -1, 3316, 3338, 3308, -1, 3280, 3339, 3277, -1, 3283, 3339, 3280, -1, 3277, 3339, 3335, -1, 3340, 3341, 3330, -1, 3339, 3342, 3335, -1, 3330, 3341, 3331, -1, 3335, 3343, 3332, -1, 3332, 3343, 3337, -1, 3326, 3344, 3317, -1, 3335, 3345, 3343, -1, 3317, 3344, 3333, -1, 3338, 3346, 3328, -1, 3342, 3345, 3335, -1, 3337, 3347, 2331, -1, 2331, 3347, 2333, -1, 3345, 3347, 3343, -1, 3328, 3346, 3336, -1, 3343, 3347, 3337, -1, 3283, 3348, 3339, -1, 3339, 3348, 3342, -1, 3285, 3348, 3283, -1, 3316, 3349, 3338, -1, 3324, 3349, 3316, -1, 3342, 3350, 3345, -1, 3333, 3351, 1246, -1, 3347, 3350, 2333, -1, 3345, 3350, 3347, -1, 1246, 3351, 1244, -1, 3285, 3352, 3348, -1, 3286, 3352, 3285, -1, 3353, 3354, 3340, -1, 3342, 3355, 3350, -1, 3348, 3355, 3342, -1, 3352, 3355, 3348, -1, 3340, 3354, 3341, -1, 3326, 3356, 3344, -1, 3355, 3357, 3350, -1, 3286, 3357, 3352, -1, 3336, 3356, 3326, -1, 3352, 3357, 3355, -1, 2325, 3358, 2326, -1, 3287, 3358, 3286, -1, 3286, 3358, 3357, -1, 2326, 3358, 3287, -1, 3338, 3359, 3346, -1, 3357, 3358, 3350, -1, 3349, 3359, 3338, -1, 2337, 3360, 2325, -1, 2333, 3360, 2337, -1, 3350, 3360, 2333, -1, 3331, 3361, 3324, -1, 2325, 3360, 3358, -1, 3358, 3360, 3350, -1, 3324, 3361, 3349, -1, 3344, 3362, 3333, -1, 3333, 3362, 3351, -1, 3363, 3364, 3365, -1, 3365, 3364, 3353, -1, 3353, 3364, 3354, -1, 3351, 3366, 1244, -1, 3336, 3367, 3356, -1, 3346, 3367, 3336, -1, 3361, 3368, 3349, -1, 3349, 3368, 3359, -1, 3331, 3369, 3361, -1, 3341, 3369, 3331, -1, 3356, 3370, 3344, -1, 3344, 3370, 3362, -1, 3363, 3371, 3364, -1, 3362, 3372, 3351, -1, 3351, 3372, 3366, -1, 3359, 3373, 3346, -1, 3346, 3373, 3367, -1, 3361, 3374, 3368, -1, 3369, 3374, 3361, -1, 3354, 3375, 3341, -1, 3341, 3375, 3369, -1, 3356, 3376, 3370, -1, 3367, 3376, 3356, -1, 3377, 3378, 3363, -1, 3363, 3378, 3371, -1, 1244, 3379, 1265, -1, 3366, 3379, 1244, -1, 3362, 3380, 3372, -1, 3370, 3380, 3362, -1, 3359, 3381, 3373, -1, 3368, 3381, 3359, -1, 3369, 3382, 3374, -1, 3375, 3382, 3369, -1, 3364, 3383, 3354, -1, 3354, 3383, 3375, -1, 3373, 3384, 3367, -1, 3367, 3384, 3376, -1, 3385, 3386, 3387, -1, 3387, 3386, 3377, -1, 3377, 3386, 3378, -1, 3379, 3388, 1265, -1, 3372, 3389, 3366, -1, 3366, 3389, 3379, -1, 3376, 3390, 3370, -1, 3370, 3390, 3380, -1, 3374, 3391, 3368, -1, 3368, 3391, 3381, -1, 3383, 3392, 3375, -1, 3375, 3392, 3382, -1, 3371, 3393, 3364, -1, 3364, 3393, 3383, -1, 3373, 3394, 3384, -1, 3381, 3394, 3373, -1, 3385, 3395, 3386, -1, 1286, 3395, 1284, -1, 1284, 3395, 3385, -1, 3379, 3396, 3388, -1, 3389, 3396, 3379, -1, 3380, 3397, 3372, -1, 3372, 3397, 3389, -1, 3384, 3398, 3376, -1, 3376, 3398, 3390, -1, 3374, 3399, 3391, -1, 3382, 3399, 3374, -1, 3393, 3400, 3383, -1, 3383, 3400, 3392, -1, 3371, 3401, 3393, -1, 3378, 3401, 3371, -1, 3381, 3402, 3394, -1, 3391, 3402, 3381, -1, 3389, 3403, 3396, -1, 3397, 3403, 3389, -1, 3380, 3404, 3397, -1, 3390, 3404, 3380, -1, 3394, 3405, 3384, -1, 3384, 3405, 3398, -1, 1265, 3288, 1272, -1, 3388, 3288, 1265, -1, 3392, 3406, 3382, -1, 3382, 3406, 3399, -1, 3393, 3407, 3400, -1, 3401, 3407, 3393, -1, 3386, 3408, 3378, -1, 3378, 3408, 3401, -1, 3399, 3409, 3391, -1, 3391, 3409, 3402, -1, 3397, 3410, 3403, -1, 3404, 3410, 3397, -1, 3398, 3411, 3390, -1, 3390, 3411, 3404, -1, 3402, 3412, 3394, -1, 3394, 3412, 3405, -1, 3388, 3294, 3288, -1, 3396, 3294, 3388, -1, 3392, 3413, 3406, -1, 3400, 3413, 3392, -1, 3401, 3414, 3407, -1, 3408, 3414, 3401, -1, 1300, 3415, 1286, -1, 1286, 3415, 3395, -1, 3386, 3415, 3408, -1, 3395, 3415, 3386, -1, 3406, 3416, 3399, -1, 3399, 3416, 3409, -1, 3404, 3256, 3410, -1, 3411, 3256, 3404, -1, 3398, 3417, 3411, -1, 3405, 3417, 3398, -1, 3402, 3418, 3412, -1, 3409, 3418, 3402, -1, 3403, 3292, 3396, -1, 3396, 3292, 3294, -1, 3407, 3419, 3400, -1, 3400, 3419, 3413, -1, 1300, 3420, 3415, -1, 3408, 3420, 3414, -1, 3415, 3420, 3408, -1, 3413, 3255, 3406, -1, 3406, 3255, 3416, -1, 3411, 3259, 3256, -1, 3417, 3259, 3411, -1, 3405, 3421, 3417, -1, 3412, 3421, 3405, -1, 3416, 3270, 3409, -1, 3409, 3270, 3418, -1, 3403, 3303, 3292, -1, 3410, 3303, 3403, -1, 3407, 3262, 3419, -1, 3414, 3262, 3407, -1, 3419, 3253, 3413, -1, 3413, 3253, 3255, -1, 3417, 3272, 3259, -1, 3421, 3272, 3417, -1, 3412, 3264, 3421, -1, 3418, 3264, 3412, -1, 3416, 3268, 3270, -1, 3255, 3268, 3416, -1, 3256, 3258, 3410, -1, 3410, 3258, 3303, -1, 1300, 3261, 3420, -1, 1325, 3261, 1300, -1, 3414, 3261, 3262, -1, 3420, 3261, 3414, -1, 3419, 3263, 3253, -1, 3262, 3263, 3419, -1, 3264, 3266, 3421, -1, 3421, 3266, 3272, -1, 3418, 3267, 3264, -1, 3270, 3267, 3418, -1, 3255, 3254, 3268, -1, 2016, 3037, 1401, -1, 1401, 3037, 3300, -1, 3300, 3041, 3304, -1, 3037, 3041, 3300, -1, 3304, 3044, 3310, -1, 3041, 3044, 3304, -1, 3310, 3046, 3315, -1, 3044, 3046, 3310, -1, 3315, 3020, 3323, -1, 3046, 3020, 3315, -1, 3323, 3022, 3330, -1, 3020, 3022, 3323, -1, 3330, 3026, 3340, -1, 3022, 3026, 3330, -1, 3340, 3035, 3353, -1, 3026, 3035, 3340, -1, 3353, 3038, 3365, -1, 3035, 3038, 3353, -1, 3365, 3042, 3363, -1, 3038, 3042, 3365, -1, 3363, 3040, 3377, -1, 3042, 3040, 3363, -1, 3377, 3036, 3387, -1, 3040, 3036, 3377, -1, 3387, 3034, 3385, -1, 3036, 3034, 3387, -1, 3385, 2002, 1284, -1, 3034, 2002, 3385, -1, 2043, 2001, 1951, -1, 2043, 1951, 2699, -1, 2042, 2699, 2694, -1, 2042, 2043, 2699, -1, 2027, 2694, 2687, -1, 2027, 2042, 2694, -1, 2041, 2687, 2686, -1, 2041, 2027, 2687, -1, 2040, 2686, 2667, -1, 2040, 2041, 2686, -1, 2039, 2667, 2666, -1, 2039, 2040, 2667, -1, 2038, 2666, 2676, -1, 2038, 2039, 2666, -1, 2034, 2676, 1860, -1, 2034, 2038, 2676, -1, 2035, 2034, 1860, -1, 3245, 1860, 2701, -1, 3245, 2035, 1860, -1, 3244, 2701, 2727, -1, 3244, 3245, 2701, -1, 3243, 2727, 2726, -1, 3243, 3244, 2727, -1, 3242, 2726, 2724, -1, 3242, 3243, 2726, -1, 3238, 2724, 2722, -1, 3238, 3242, 2724, -1, 3241, 2722, 2720, -1, 3241, 3238, 2722, -1, 3240, 2720, 2717, -1, 3240, 3241, 2720, -1, 3239, 3240, 2717, -1, 3239, 2717, 1970, -1, 1969, 3239, 1970, -1, 3422, 3423, 3424, -1, 3425, 3426, 3427, -1, 3428, 3426, 3425, -1, 3429, 3430, 3431, -1, 3432, 3426, 3428, -1, 3433, 3431, 3430, -1, 3434, 3429, 3431, -1, 3435, 3436, 3431, -1, 2374, 3437, 3438, -1, 2374, 3438, 3439, -1, 2374, 3439, 3440, -1, 3435, 3431, 3433, -1, 3441, 3434, 3431, -1, 3442, 3436, 3435, -1, 3443, 3444, 2374, -1, 3445, 3446, 3447, -1, 3448, 2374, 3444, -1, 3445, 3447, 3449, -1, 3445, 3422, 3424, -1, 3445, 3450, 3451, -1, 3445, 3449, 3450, -1, 3452, 3443, 2374, -1, 3453, 3436, 3442, -1, 3445, 3451, 3422, -1, 3454, 3446, 3445, -1, 3454, 3455, 3446, -1, 3454, 3456, 3455, -1, 3454, 3457, 3456, -1, 3454, 3458, 3457, -1, 3454, 3459, 3458, -1, 3440, 3436, 3460, -1, 3454, 3426, 3432, -1, 3461, 2374, 3448, -1, 3454, 3432, 3459, -1, 3460, 3436, 3453, -1, 2375, 2374, 3461, -1, 3462, 3452, 2374, -1, 3463, 2375, 3461, -1, 3464, 3462, 2374, -1, 3465, 2374, 3440, -1, 3465, 3440, 3466, -1, 3465, 3464, 2374, -1, 3467, 3468, 3441, -1, 3467, 3469, 3468, -1, 3467, 3470, 3469, -1, 3467, 3471, 3470, -1, 3467, 3472, 3471, -1, 3473, 3465, 3466, -1, 3467, 3474, 3472, -1, 3473, 3466, 3475, -1, 3467, 3441, 3431, -1, 3476, 2375, 3463, -1, 3440, 3439, 3477, -1, 3478, 3475, 3479, -1, 3440, 3480, 3481, -1, 3440, 3482, 3480, -1, 3478, 3473, 3475, -1, 3440, 3483, 3482, -1, 3440, 3460, 3483, -1, 3484, 3426, 2375, -1, 3484, 2375, 3476, -1, 3451, 3478, 3479, -1, 3485, 3440, 3481, -1, 3451, 3479, 3422, -1, 3424, 3474, 3467, -1, 3486, 3426, 3484, -1, 3424, 3487, 3488, -1, 3424, 3488, 3474, -1, 3489, 3440, 3485, -1, 3427, 3426, 3486, -1, 3423, 3487, 3424, -1, 3466, 3440, 3489, -1, 3490, 3453, 3442, -1, 3490, 3442, 3491, -1, 3490, 3492, 3453, -1, 3453, 3492, 3460, -1, 3460, 3493, 3483, -1, 3492, 3493, 3460, -1, 3483, 3494, 3482, -1, 3493, 3494, 3483, -1, 3482, 3495, 3480, -1, 3494, 3495, 3482, -1, 3480, 3496, 3481, -1, 3495, 3496, 3480, -1, 3481, 3497, 3485, -1, 3496, 3497, 3481, -1, 3485, 3498, 3489, -1, 3497, 3498, 3485, -1, 3489, 3499, 3466, -1, 3498, 3499, 3489, -1, 3466, 3500, 3475, -1, 3499, 3500, 3466, -1, 3475, 3501, 3479, -1, 3500, 3501, 3475, -1, 3479, 3502, 3422, -1, 3501, 3502, 3479, -1, 3422, 3503, 3423, -1, 3502, 3503, 3422, -1, 3423, 3504, 3487, -1, 3503, 3504, 3423, -1, 3487, 3504, 3505, -1, 3487, 3505, 3488, -1, 3505, 3506, 3488, -1, 3488, 3506, 3474, -1, 3474, 3507, 3472, -1, 3506, 3507, 3474, -1, 3472, 3508, 3471, -1, 3507, 3508, 3472, -1, 3471, 3509, 3470, -1, 3508, 3509, 3471, -1, 3470, 3510, 3469, -1, 3509, 3510, 3470, -1, 3469, 3511, 3468, -1, 3510, 3511, 3469, -1, 3468, 3512, 3441, -1, 3511, 3512, 3468, -1, 3441, 3513, 3434, -1, 3512, 3513, 3441, -1, 3434, 3514, 3429, -1, 3513, 3514, 3434, -1, 3429, 3515, 3430, -1, 3514, 3515, 3429, -1, 3430, 3516, 3433, -1, 3515, 3516, 3430, -1, 3433, 3517, 3435, -1, 3516, 3517, 3433, -1, 3435, 3491, 3442, -1, 3517, 3491, 3435, -1, 3467, 3518, 3424, -1, 3424, 3518, 3519, -1, 3436, 3520, 3431, -1, 3431, 3520, 3521, -1, 3431, 3518, 3467, -1, 3521, 3518, 3431, -1, 3447, 3522, 3523, -1, 3447, 3523, 3449, -1, 3523, 3524, 3449, -1, 3449, 3524, 3450, -1, 3450, 3525, 3451, -1, 3524, 3525, 3450, -1, 3451, 3526, 3478, -1, 3525, 3526, 3451, -1, 3478, 3527, 3473, -1, 3526, 3527, 3478, -1, 3473, 3528, 3465, -1, 3527, 3528, 3473, -1, 3465, 3529, 3464, -1, 3528, 3529, 3465, -1, 3464, 3530, 3462, -1, 3529, 3530, 3464, -1, 3462, 3531, 3452, -1, 3530, 3531, 3462, -1, 3452, 3532, 3443, -1, 3531, 3532, 3452, -1, 3443, 3533, 3444, -1, 3532, 3533, 3443, -1, 3444, 3534, 3448, -1, 3533, 3534, 3444, -1, 3448, 3535, 3461, -1, 3534, 3535, 3448, -1, 3461, 3536, 3463, -1, 3535, 3536, 3461, -1, 3537, 3476, 3463, -1, 3537, 3463, 3536, -1, 3537, 3538, 3476, -1, 3476, 3538, 3484, -1, 3484, 3539, 3486, -1, 3538, 3539, 3484, -1, 3486, 3540, 3427, -1, 3539, 3540, 3486, -1, 3427, 3541, 3425, -1, 3540, 3541, 3427, -1, 3425, 3542, 3428, -1, 3541, 3542, 3425, -1, 3428, 3543, 3432, -1, 3542, 3543, 3428, -1, 3432, 3544, 3459, -1, 3543, 3544, 3432, -1, 3459, 3545, 3458, -1, 3544, 3545, 3459, -1, 3458, 3546, 3457, -1, 3545, 3546, 3458, -1, 3457, 3547, 3456, -1, 3546, 3547, 3457, -1, 3456, 3548, 3455, -1, 3547, 3548, 3456, -1, 3455, 3549, 3446, -1, 3548, 3549, 3455, -1, 3446, 3522, 3447, -1, 3549, 3522, 3446, -1, 3519, 1935, 3424, -1, 3550, 3445, 1935, -1, 3445, 3424, 1935, -1, 3445, 3550, 3454, -1, 3454, 3550, 3551, -1, 3551, 3552, 3454, -1, 3552, 3426, 3454, -1, 3426, 3552, 2375, -1, 2375, 3552, 2373, -1, 3440, 3520, 3436, -1, 3553, 3520, 3440, -1, 3515, 3514, 3521, -1, 3521, 3516, 3515, -1, 3514, 3513, 3521, -1, 3520, 3517, 3521, -1, 3521, 3517, 3516, -1, 3513, 3512, 3521, -1, 3520, 3491, 3517, -1, 3520, 3490, 3491, -1, 3520, 3492, 3490, -1, 3512, 3518, 3521, -1, 3511, 3518, 3512, -1, 3510, 3518, 3511, -1, 3509, 3518, 3510, -1, 3508, 3518, 3509, -1, 3507, 3518, 3508, -1, 3506, 3518, 3507, -1, 3494, 3553, 3495, -1, 3493, 3553, 3494, -1, 3492, 3553, 3493, -1, 3506, 3519, 3518, -1, 3505, 3519, 3506, -1, 3504, 3519, 3505, -1, 3504, 3503, 3519, -1, 3554, 3555, 3553, -1, 3556, 3557, 3553, -1, 3553, 3557, 3554, -1, 3553, 3558, 3495, -1, 3555, 3558, 3553, -1, 3559, 3560, 3556, -1, 3556, 3560, 3557, -1, 3496, 3561, 3497, -1, 3495, 3561, 3496, -1, 3558, 3561, 3495, -1, 3559, 3562, 3560, -1, 3497, 3563, 3498, -1, 3561, 3563, 3497, -1, 3559, 1966, 3562, -1, 3559, 3564, 1966, -1, 3499, 3565, 3500, -1, 3498, 3565, 3499, -1, 3563, 3565, 3498, -1, 3564, 1964, 1966, -1, 3500, 3566, 3501, -1, 3565, 3566, 3500, -1, 3564, 1962, 1964, -1, 3564, 3567, 1962, -1, 3567, 1960, 1962, -1, 3501, 3568, 3502, -1, 3566, 3568, 3501, -1, 3567, 2376, 1960, -1, 2376, 1958, 1960, -1, 3568, 3569, 3502, -1, 3503, 3569, 3519, -1, 3502, 3569, 3503, -1, 3569, 3570, 3519, -1, 2376, 1956, 1958, -1, 2376, 1954, 1956, -1, 3570, 3571, 3519, -1, 3571, 3572, 3519, -1, 2376, 3532, 1954, -1, 3533, 3532, 2376, -1, 1954, 3532, 1952, -1, 2376, 3534, 3533, -1, 3532, 3531, 1952, -1, 2376, 3535, 3534, -1, 1952, 3530, 1950, -1, 3531, 3530, 1952, -1, 2373, 3536, 3535, -1, 1950, 3529, 1948, -1, 3530, 3529, 1950, -1, 3529, 3528, 1948, -1, 1948, 3527, 1946, -1, 3528, 3527, 1948, -1, 2373, 3537, 3536, -1, 1946, 3526, 1944, -1, 3527, 3526, 1946, -1, 3552, 3538, 2373, -1, 2373, 3538, 3537, -1, 1944, 3525, 1942, -1, 3526, 3525, 1944, -1, 3552, 3539, 3538, -1, 3525, 3524, 1942, -1, 3552, 3540, 3539, -1, 3552, 3541, 3540, -1, 3552, 3542, 3541, -1, 3552, 3543, 3542, -1, 3548, 3551, 3549, -1, 3547, 3551, 3548, -1, 3546, 3551, 3547, -1, 3545, 3551, 3546, -1, 3544, 3551, 3545, -1, 3523, 3550, 3524, -1, 3522, 3550, 3523, -1, 1942, 3550, 1940, -1, 1940, 3550, 1938, -1, 1938, 3550, 1934, -1, 3549, 3550, 3522, -1, 3551, 3550, 3549, -1, 3524, 3550, 1942, -1, 1935, 3519, 3572, -1, 3550, 1935, 1934, -1, 3552, 3551, 3543, -1, 3543, 3551, 3544, -1, 2376, 2373, 3535, -1, 3520, 3553, 3492, -1, 3562, 1966, 1967, -1, 3562, 1967, 2810, -1, 3560, 2810, 2816, -1, 3560, 3562, 2810, -1, 3557, 2816, 2806, -1, 3557, 3560, 2816, -1, 3554, 2806, 2805, -1, 3554, 3557, 2806, -1, 3555, 2805, 2814, -1, 3555, 3554, 2805, -1, 3558, 2814, 2818, -1, 3558, 3555, 2814, -1, 3561, 2818, 2823, -1, 3561, 3558, 2818, -1, 3563, 2823, 2827, -1, 3563, 3561, 2823, -1, 3565, 2827, 2831, -1, 3565, 3563, 2827, -1, 3566, 2831, 2836, -1, 3566, 3565, 2831, -1, 3568, 2836, 2843, -1, 3568, 3566, 2836, -1, 3569, 2843, 2847, -1, 3569, 3568, 2843, -1, 3570, 2847, 2854, -1, 3570, 3569, 2847, -1, 3571, 2854, 2856, -1, 3571, 3570, 2854, -1, 3572, 2856, 2858, -1, 3572, 3571, 2856, -1, 1935, 3572, 2858, -1, 1935, 2858, 1936, -1, 872, 1901, 874, -1, 1901, 3573, 874, -1, 874, 3574, 869, -1, 3573, 3574, 874, -1, 869, 3575, 867, -1, 3574, 3575, 869, -1, 867, 3576, 883, -1, 3575, 3576, 867, -1, 883, 3577, 895, -1, 3576, 3577, 883, -1, 895, 3578, 901, -1, 3577, 3578, 895, -1, 901, 3579, 907, -1, 3578, 3579, 901, -1, 907, 3580, 918, -1, 3579, 3580, 907, -1, 918, 3581, 924, -1, 3580, 3581, 918, -1, 924, 3582, 936, -1, 3581, 3582, 924, -1, 936, 3583, 953, -1, 3582, 3583, 936, -1, 953, 3584, 950, -1, 3583, 3584, 953, -1, 950, 3585, 855, -1, 3584, 3585, 950, -1, 855, 1874, 856, -1, 3585, 1874, 855, -1, 3586, 3587, 3588, -1, 3588, 3587, 3589, -1, 3590, 3591, 3592, -1, 3592, 3591, 3593, -1, 2230, 987, 989, -1, 3594, 3595, 3596, -1, 916, 3595, 3594, -1, 3596, 3595, 3597, -1, 3598, 3599, 3600, -1, 3601, 3599, 3598, -1, 3589, 3602, 3603, -1, 3603, 3602, 3601, -1, 3597, 3604, 3586, -1, 3586, 3604, 3587, -1, 3590, 3605, 3591, -1, 3606, 3605, 3590, -1, 3601, 3607, 3599, -1, 3602, 3607, 3601, -1, 3589, 3608, 3602, -1, 3587, 3608, 3589, -1, 959, 3609, 916, -1, 3595, 3609, 3597, -1, 916, 3609, 3595, -1, 3597, 3609, 3604, -1, 3600, 3610, 3606, -1, 3606, 3610, 3605, -1, 3602, 3611, 3607, -1, 3608, 3611, 3602, -1, 3604, 3612, 3587, -1, 3587, 3612, 3608, -1, 3600, 3613, 3610, -1, 3599, 3613, 3600, -1, 3612, 3614, 3608, -1, 3608, 3614, 3611, -1, 959, 3615, 3609, -1, 3604, 3615, 3612, -1, 3609, 3615, 3604, -1, 3599, 3616, 3613, -1, 3607, 3616, 3599, -1, 3612, 3617, 3614, -1, 959, 3617, 3615, -1, 854, 3617, 959, -1, 3615, 3617, 3612, -1, 3607, 3618, 3616, -1, 3611, 3618, 3607, -1, 3614, 3619, 3611, -1, 3611, 3619, 3618, -1, 3614, 3620, 3619, -1, 854, 3620, 3617, -1, 1876, 3620, 854, -1, 3617, 3620, 3614, -1, 3621, 3622, 863, -1, 3623, 3624, 3622, -1, 3622, 3624, 863, -1, 863, 3624, 872, -1, 3625, 3626, 3627, -1, 872, 3628, 1900, -1, 3624, 3628, 872, -1, 3623, 3628, 3624, -1, 3626, 3629, 3623, -1, 1897, 3630, 1896, -1, 3629, 3630, 3623, -1, 3622, 3631, 3623, -1, 3621, 3631, 3622, -1, 3623, 3631, 3626, -1, 3626, 3631, 3627, -1, 3627, 3631, 3621, -1, 854, 856, 1876, -1, 1900, 3632, 1897, -1, 3628, 3632, 1900, -1, 3623, 3632, 3628, -1, 1897, 3632, 3630, -1, 3630, 3632, 3623, -1, 3625, 3633, 3626, -1, 3626, 3633, 3629, -1, 2230, 3634, 987, -1, 3635, 3633, 3625, -1, 2230, 3636, 3634, -1, 3633, 3637, 3629, -1, 2231, 3636, 2230, -1, 1896, 3638, 1893, -1, 3637, 3638, 3629, -1, 3629, 3638, 3630, -1, 2231, 3639, 3636, -1, 3630, 3638, 1896, -1, 3593, 3640, 3635, -1, 3635, 3640, 3633, -1, 2236, 3639, 2231, -1, 3633, 3640, 3637, -1, 3634, 3641, 987, -1, 987, 3641, 1012, -1, 3640, 3642, 3637, -1, 1893, 3643, 1891, -1, 3638, 3643, 1893, -1, 3637, 3643, 3638, -1, 3642, 3643, 3637, -1, 3593, 3644, 3640, -1, 3640, 3644, 3642, -1, 2228, 3645, 2236, -1, 3591, 3644, 3593, -1, 2236, 3645, 3639, -1, 1012, 3646, 835, -1, 3641, 3646, 1012, -1, 3636, 3647, 3634, -1, 3644, 3648, 3642, -1, 1891, 3649, 1890, -1, 3643, 3649, 1891, -1, 3642, 3649, 3643, -1, 3648, 3649, 3642, -1, 3634, 3647, 3641, -1, 3591, 3650, 3644, -1, 3644, 3650, 3648, -1, 3605, 3650, 3591, -1, 1890, 3651, 1887, -1, 2227, 3652, 2228, -1, 3648, 3651, 3649, -1, 2228, 3652, 3645, -1, 3649, 3651, 1890, -1, 3641, 3653, 3646, -1, 3605, 3654, 3650, -1, 3610, 3654, 3605, -1, 3647, 3653, 3641, -1, 3648, 3655, 3651, -1, 3636, 3656, 3647, -1, 3650, 3655, 3648, -1, 3654, 3655, 3650, -1, 3639, 3656, 3636, -1, 3655, 3657, 3651, -1, 3654, 3657, 3655, -1, 2229, 3658, 2227, -1, 2227, 3658, 3652, -1, 3657, 3659, 3651, -1, 1887, 3660, 1885, -1, 3651, 3660, 1887, -1, 3659, 3660, 3651, -1, 3646, 3661, 835, -1, 3610, 3662, 3654, -1, 3654, 3662, 3657, -1, 3656, 3663, 3647, -1, 3657, 3662, 3659, -1, 3647, 3663, 3653, -1, 3659, 3664, 3660, -1, 1885, 3664, 1883, -1, 3660, 3664, 1885, -1, 3613, 3665, 3610, -1, 3639, 3666, 3656, -1, 3645, 3666, 3639, -1, 3610, 3665, 3662, -1, 3616, 3665, 3613, -1, 2232, 3667, 2229, -1, 3665, 3668, 3662, -1, 2229, 3667, 3658, -1, 3662, 3669, 3659, -1, 3653, 3670, 3646, -1, 3659, 3669, 3664, -1, 3662, 3671, 3669, -1, 3646, 3670, 3661, -1, 3668, 3671, 3662, -1, 3664, 3672, 1883, -1, 1883, 3672, 1881, -1, 3671, 3672, 3669, -1, 3666, 3673, 3656, -1, 3669, 3672, 3664, -1, 3656, 3673, 3663, -1, 3616, 3674, 3665, -1, 3665, 3674, 3668, -1, 3618, 3674, 3616, -1, 3652, 3675, 3645, -1, 3645, 3675, 3666, -1, 3668, 3676, 3671, -1, 3672, 3676, 1881, -1, 3671, 3676, 3672, -1, 2324, 3677, 2232, -1, 3619, 3678, 3618, -1, 3618, 3678, 3674, -1, 2232, 3677, 3667, -1, 3668, 3679, 3676, -1, 3674, 3679, 3668, -1, 835, 3680, 833, -1, 3678, 3679, 3674, -1, 3661, 3680, 835, -1, 3653, 3681, 3670, -1, 3679, 3682, 3676, -1, 3619, 3682, 3678, -1, 3678, 3682, 3679, -1, 1877, 3683, 1876, -1, 3663, 3681, 3653, -1, 3682, 3683, 3676, -1, 1876, 3683, 3620, -1, 3620, 3683, 3619, -1, 3666, 3684, 3673, -1, 3619, 3683, 3682, -1, 3675, 3684, 3666, -1, 1879, 3685, 1877, -1, 1881, 3685, 1879, -1, 3676, 3685, 1881, -1, 1877, 3685, 3683, -1, 3683, 3685, 3676, -1, 3658, 3686, 3652, -1, 3652, 3686, 3675, -1, 2323, 3687, 2324, -1, 2324, 3687, 3677, -1, 3670, 3688, 3661, -1, 3661, 3688, 3680, -1, 3680, 3689, 833, -1, 3663, 3690, 3681, -1, 3673, 3690, 3663, -1, 3675, 3691, 3684, -1, 3686, 3691, 3675, -1, 3658, 3692, 3686, -1, 3667, 3692, 3658, -1, 2322, 3693, 2323, -1, 2323, 3693, 3687, -1, 3670, 3694, 3688, -1, 3681, 3694, 3670, -1, 3688, 3695, 3680, -1, 3680, 3695, 3689, -1, 3673, 3696, 3690, -1, 3684, 3696, 3673, -1, 3686, 3697, 3691, -1, 3692, 3697, 3686, -1, 3677, 3698, 3667, -1, 3667, 3698, 3692, -1, 2321, 3699, 2322, -1, 2322, 3699, 3693, -1, 3681, 3700, 3694, -1, 3690, 3700, 3681, -1, 833, 3701, 857, -1, 3689, 3701, 833, -1, 3694, 3702, 3688, -1, 3688, 3702, 3695, -1, 3691, 3703, 3684, -1, 3684, 3703, 3696, -1, 3692, 3704, 3697, -1, 3698, 3704, 3692, -1, 3687, 3705, 3677, -1, 3677, 3705, 3698, -1, 2320, 3706, 2321, -1, 2321, 3706, 3699, -1, 3696, 3707, 3690, -1, 3690, 3707, 3700, -1, 3701, 3708, 857, -1, 3695, 3709, 3689, -1, 3689, 3709, 3701, -1, 3694, 3710, 3702, -1, 3700, 3710, 3694, -1, 3697, 3711, 3691, -1, 3691, 3711, 3703, -1, 3705, 3712, 3698, -1, 3698, 3712, 3704, -1, 3693, 3713, 3687, -1, 3687, 3713, 3705, -1, 2320, 3714, 3706, -1, 879, 3714, 878, -1, 878, 3714, 2319, -1, 2319, 3714, 2320, -1, 3696, 3715, 3707, -1, 3703, 3715, 3696, -1, 3701, 3716, 3708, -1, 3709, 3716, 3701, -1, 3695, 3717, 3709, -1, 3702, 3717, 3695, -1, 3707, 3718, 3700, -1, 3700, 3718, 3710, -1, 3697, 3719, 3711, -1, 3704, 3719, 3697, -1, 3713, 3720, 3705, -1, 3705, 3720, 3712, -1, 3693, 3721, 3713, -1, 3699, 3721, 3693, -1, 3703, 3722, 3715, -1, 3711, 3722, 3703, -1, 3709, 3723, 3716, -1, 3717, 3723, 3709, -1, 3710, 3724, 3702, -1, 3702, 3724, 3717, -1, 3715, 3725, 3707, -1, 3707, 3725, 3718, -1, 857, 3621, 863, -1, 3708, 3621, 857, -1, 3712, 3726, 3704, -1, 3704, 3726, 3719, -1, 3713, 3727, 3720, -1, 3721, 3727, 3713, -1, 3699, 3728, 3721, -1, 3706, 3728, 3699, -1, 3719, 3729, 3711, -1, 3711, 3729, 3722, -1, 3717, 3730, 3723, -1, 3724, 3730, 3717, -1, 3710, 3731, 3724, -1, 3718, 3731, 3710, -1, 3715, 3732, 3725, -1, 3722, 3732, 3715, -1, 3708, 3627, 3621, -1, 3716, 3627, 3708, -1, 3712, 3733, 3726, -1, 3720, 3733, 3712, -1, 3721, 3734, 3727, -1, 3728, 3734, 3721, -1, 3714, 3735, 3706, -1, 891, 3735, 879, -1, 3706, 3735, 3728, -1, 879, 3735, 3714, -1, 3726, 3736, 3719, -1, 3719, 3736, 3729, -1, 3724, 3592, 3730, -1, 3731, 3592, 3724, -1, 3725, 3737, 3718, -1, 3718, 3737, 3731, -1, 3729, 3738, 3722, -1, 3722, 3738, 3732, -1, 3723, 3625, 3716, -1, 3716, 3625, 3627, -1, 3727, 3739, 3720, -1, 3720, 3739, 3733, -1, 891, 3740, 3735, -1, 3728, 3740, 3734, -1, 3735, 3740, 3728, -1, 3726, 3588, 3736, -1, 3733, 3588, 3726, -1, 3737, 3590, 3731, -1, 3731, 3590, 3592, -1, 3725, 3741, 3737, -1, 3732, 3741, 3725, -1, 3736, 3603, 3729, -1, 3729, 3603, 3738, -1, 3723, 3635, 3625, -1, 3730, 3635, 3723, -1, 3727, 3596, 3739, -1, 3734, 3596, 3727, -1, 3733, 3586, 3588, -1, 3739, 3586, 3733, -1, 3741, 3606, 3737, -1, 3737, 3606, 3590, -1, 3738, 3598, 3732, -1, 3732, 3598, 3741, -1, 3736, 3589, 3603, -1, 3588, 3589, 3736, -1, 3730, 3593, 3635, -1, 3592, 3593, 3730, -1, 891, 3594, 3740, -1, 916, 3594, 891, -1, 3734, 3594, 3596, -1, 3740, 3594, 3734, -1, 3739, 3597, 3586, -1, 3596, 3597, 3739, -1, 3741, 3600, 3606, -1, 3598, 3600, 3741, -1, 3603, 3601, 3738, -1, 3738, 3601, 3598, -1, 1909, 1911, 3576, -1, 1880, 3742, 3743, -1, 1911, 3577, 3576, -1, 1880, 1878, 3742, -1, 1911, 1913, 3577, -1, 1878, 3744, 3742, -1, 3745, 1895, 3746, -1, 1913, 3578, 3577, -1, 3746, 1894, 3747, -1, 1878, 1875, 3744, -1, 1895, 1894, 3746, -1, 3748, 1898, 3745, -1, 3745, 1898, 1895, -1, 3747, 1892, 3749, -1, 1894, 1892, 3747, -1, 3578, 1915, 3579, -1, 3750, 1899, 3748, -1, 1913, 1915, 3578, -1, 3748, 1899, 1898, -1, 1874, 3751, 1875, -1, 3749, 1889, 3752, -1, 1875, 3751, 3744, -1, 1892, 1889, 3749, -1, 1874, 1933, 3751, -1, 1904, 1901, 3750, -1, 1902, 1901, 1904, -1, 3750, 1901, 1899, -1, 1915, 1917, 3579, -1, 3752, 1888, 3753, -1, 3753, 1888, 3754, -1, 1889, 1888, 3752, -1, 1902, 3573, 1901, -1, 1888, 1886, 3754, -1, 3579, 1919, 3580, -1, 1902, 1905, 3573, -1, 1917, 1919, 3579, -1, 1886, 3755, 3754, -1, 3585, 1931, 1874, -1, 1874, 1931, 1933, -1, 3580, 1921, 3581, -1, 1905, 3574, 3573, -1, 1886, 1884, 3755, -1, 1919, 1921, 3580, -1, 3584, 1929, 3585, -1, 1905, 1907, 3574, -1, 3585, 1929, 1931, -1, 1884, 3756, 3755, -1, 3583, 1927, 3584, -1, 3584, 1927, 1929, -1, 3581, 1923, 3582, -1, 1907, 3575, 3574, -1, 1921, 1923, 3581, -1, 1884, 1882, 3756, -1, 3582, 1925, 3583, -1, 3583, 1925, 1927, -1, 1923, 1925, 3582, -1, 1907, 1909, 3575, -1, 1882, 3743, 3756, -1, 1909, 3576, 3575, -1, 1882, 1880, 3743, -1, 1933, 1070, 1072, -1, 3751, 1072, 1118, -1, 3751, 1933, 1072, -1, 3744, 1118, 1200, -1, 3744, 3751, 1118, -1, 3742, 1200, 1195, -1, 3742, 3744, 1200, -1, 3743, 1195, 1190, -1, 3743, 3742, 1195, -1, 3756, 1190, 1184, -1, 3756, 3743, 1190, -1, 3755, 3756, 1184, -1, 3754, 1173, 1169, -1, 3754, 1184, 1173, -1, 3754, 3755, 1184, -1, 3753, 1169, 1162, -1, 3753, 3754, 1169, -1, 3752, 3753, 1162, -1, 3749, 1156, 1150, -1, 3749, 1162, 1156, -1, 3749, 3752, 1162, -1, 3747, 3749, 1150, -1, 3746, 1143, 1142, -1, 3746, 1150, 1143, -1, 3746, 3747, 1150, -1, 3745, 1142, 1125, -1, 3745, 3746, 1142, -1, 3748, 3745, 1125, -1, 3750, 1125, 1135, -1, 3750, 3748, 1125, -1, 1904, 3750, 1135, -1, 1904, 1135, 1132, -1, 3757, 3758, 3759, -1, 3757, 3760, 3758, -1, 3761, 3762, 3763, -1, 3761, 3764, 3762, -1, 3761, 3765, 3764, -1, 3766, 3767, 3760, -1, 3766, 3768, 3767, -1, 3769, 3770, 3771, -1, 3769, 3772, 3770, -1, 3773, 3774, 3775, -1, 3773, 3759, 3774, -1, 3776, 3777, 3778, -1, 3776, 3778, 3779, -1, 3780, 3763, 3781, -1, 3780, 3781, 3772, -1, 3782, 3783, 3765, -1, 3782, 3775, 3783, -1, 3784, 3760, 3757, -1, 3784, 3766, 3760, -1, 3785, 3765, 3761, -1, 3786, 1087, 1077, -1, 3786, 3787, 3768, -1, 3786, 1077, 3787, -1, 3786, 3768, 3766, -1, 3788, 3772, 3769, -1, 3788, 3780, 3772, -1, 3789, 3757, 3759, -1, 3789, 3759, 3773, -1, 3790, 3777, 3776, -1, 3790, 3771, 3777, -1, 3791, 3761, 3763, -1, 3791, 3763, 3780, -1, 1077, 1075, 3252, -1, 3792, 3773, 3775, -1, 3792, 3775, 3782, -1, 3793, 1094, 1087, -1, 3793, 1087, 3786, -1, 3793, 3766, 3784, -1, 3793, 3786, 3766, -1, 3794, 3782, 3765, -1, 3794, 3765, 3785, -1, 3795, 3780, 3788, -1, 3795, 3791, 3780, -1, 3796, 3757, 3789, -1, 3796, 3784, 3757, -1, 3797, 3769, 3771, -1, 3797, 3771, 3790, -1, 3798, 3785, 3761, -1, 3798, 3761, 3791, -1, 3799, 3789, 3773, -1, 3799, 3773, 3792, -1, 3800, 3782, 3794, -1, 3800, 3792, 3782, -1, 3801, 3798, 3791, -1, 3801, 3791, 3795, -1, 3802, 3784, 3796, -1, 3802, 1094, 3793, -1, 3802, 3793, 3784, -1, 3803, 3788, 3769, -1, 3803, 3769, 3797, -1, 3804, 3785, 3798, -1, 3804, 3794, 3785, -1, 3805, 3789, 3799, -1, 3806, 2048, 1231, -1, 3805, 3796, 3789, -1, 3807, 3799, 3792, -1, 3806, 1231, 1050, -1, 3807, 3792, 3800, -1, 3808, 2051, 2048, -1, 3809, 3798, 3801, -1, 3808, 2048, 3806, -1, 3809, 3804, 3798, -1, 3810, 2053, 2051, -1, 3811, 3788, 3803, -1, 3811, 3795, 3788, -1, 3810, 2051, 3808, -1, 3812, 3794, 3804, -1, 3813, 1050, 1049, -1, 3812, 3800, 3794, -1, 3814, 1127, 1094, -1, 3814, 1094, 3802, -1, 3813, 3806, 1050, -1, 3814, 3796, 3805, -1, 3814, 3802, 3796, -1, 3815, 2055, 2053, -1, 3816, 3805, 3799, -1, 3816, 3799, 3807, -1, 3817, 3804, 3809, -1, 3815, 2053, 3810, -1, 3817, 3812, 3804, -1, 3818, 3813, 1049, -1, 3819, 3795, 3811, -1, 3819, 3801, 3795, -1, 3820, 3806, 3813, -1, 3821, 3807, 3800, -1, 3820, 3808, 3806, -1, 3821, 3800, 3812, -1, 3822, 2057, 2055, -1, 3823, 1127, 3814, -1, 3823, 3814, 3805, -1, 3823, 3805, 3816, -1, 3822, 2055, 3815, -1, 3824, 3821, 3812, -1, 3824, 3812, 3817, -1, 3825, 3809, 3801, -1, 3826, 3813, 3818, -1, 3826, 3820, 3813, -1, 3825, 3801, 3819, -1, 3827, 3810, 3808, -1, 3827, 3808, 3820, -1, 3828, 3807, 3821, -1, 3828, 3816, 3807, -1, 3829, 3821, 3824, -1, 3830, 1049, 1066, -1, 3829, 3828, 3821, -1, 3831, 3817, 3809, -1, 3830, 3818, 1049, -1, 3831, 3809, 3825, -1, 3832, 2059, 2057, -1, 3833, 1186, 1127, -1, 3833, 1127, 3823, -1, 3832, 2057, 3822, -1, 3833, 3823, 3816, -1, 3833, 3816, 3828, -1, 3834, 1186, 3833, -1, 3834, 3828, 3829, -1, 3834, 3833, 3828, -1, 3835, 3827, 3820, -1, 3836, 3817, 3831, -1, 3835, 3820, 3826, -1, 3836, 3824, 3817, -1, 3837, 3810, 3827, -1, 3837, 3815, 3810, -1, 3838, 3829, 3824, -1, 3838, 3824, 3836, -1, 3839, 1186, 3834, -1, 3839, 1130, 1186, -1, 3839, 3834, 3829, -1, 3839, 3829, 3838, -1, 3840, 3826, 3818, -1, 3840, 3818, 3830, -1, 3841, 2019, 2059, -1, 3842, 3838, 3843, -1, 3841, 2059, 3832, -1, 3842, 3843, 1906, -1, 3844, 3843, 3838, -1, 3845, 3830, 1066, -1, 3844, 3836, 3831, -1, 3844, 3838, 3836, -1, 3846, 3837, 3827, -1, 3846, 3827, 3835, -1, 3847, 3843, 3844, -1, 3848, 3843, 3847, -1, 3848, 1910, 1908, -1, 3849, 3822, 3815, -1, 3848, 1908, 1906, -1, 3848, 1906, 3843, -1, 3849, 3815, 3837, -1, 3850, 3839, 3838, -1, 3850, 1130, 3839, -1, 3850, 3838, 3842, -1, 3851, 3850, 3842, -1, 3851, 1132, 1130, -1, 3851, 1130, 3850, -1, 3852, 3826, 3840, -1, 3853, 3851, 3842, -1, 3853, 1132, 3851, -1, 3853, 1906, 1903, -1, 3852, 3835, 3826, -1, 3853, 1903, 1132, -1, 3853, 3842, 1906, -1, 3854, 3831, 3825, -1, 3854, 3844, 3831, -1, 3855, 2060, 2019, -1, 3854, 3847, 3844, -1, 3855, 2019, 3841, -1, 3856, 3847, 3854, -1, 3857, 3830, 3845, -1, 3857, 3840, 3830, -1, 3858, 1910, 3848, -1, 3858, 3848, 3847, -1, 3858, 1912, 1910, -1, 3859, 3849, 3837, -1, 3858, 3847, 3856, -1, 3859, 3837, 3846, -1, 3860, 3825, 3819, -1, 3860, 3856, 3854, -1, 3860, 3854, 3825, -1, 3861, 3856, 3860, -1, 3862, 1066, 1098, -1, 3862, 3845, 1066, -1, 3863, 3858, 3856, -1, 3863, 1912, 3858, -1, 3864, 3822, 3849, -1, 3863, 1914, 1912, -1, 3863, 3856, 3861, -1, 3864, 3832, 3822, -1, 3865, 3860, 3819, -1, 3865, 3819, 3811, -1, 3865, 3861, 3860, -1, 3866, 3835, 3852, -1, 3867, 3861, 3865, -1, 3866, 3846, 3835, -1, 3868, 3246, 2060, -1, 3869, 3861, 3867, -1, 3869, 3863, 3861, -1, 3869, 1914, 3863, -1, 3869, 1916, 1914, -1, 3868, 2060, 3855, -1, 3870, 3865, 3811, -1, 3870, 3867, 3865, -1, 3870, 3811, 3803, -1, 3871, 3852, 3840, -1, 3872, 3867, 3870, -1, 3871, 3840, 3857, -1, 3873, 3849, 3859, -1, 3874, 3869, 3867, -1, 3874, 3867, 3872, -1, 3874, 1916, 3869, -1, 3874, 1918, 1916, -1, 3875, 3870, 3803, -1, 3873, 3864, 3849, -1, 3875, 3803, 3797, -1, 3875, 3872, 3870, -1, 3876, 3845, 3862, -1, 3877, 1920, 1918, -1, 3876, 3857, 3845, -1, 3877, 3874, 3872, -1, 3877, 1918, 3874, -1, 3877, 3872, 3875, -1, 3878, 3832, 3864, -1, 3878, 3841, 3832, -1, 3879, 3797, 3790, -1, 3880, 3859, 3846, -1, 3879, 3875, 3797, -1, 3880, 3846, 3866, -1, 3881, 3879, 3882, -1, 3881, 3877, 3875, -1, 3881, 3875, 3879, -1, 3883, 3247, 3246, -1, 3884, 3881, 3882, -1, 3884, 3877, 3881, -1, 3883, 3246, 3868, -1, 3885, 1922, 1920, -1, 3885, 1920, 3877, -1, 3885, 3877, 3884, -1, 3886, 3862, 1098, -1, 3887, 3882, 3879, -1, 3887, 3879, 3790, -1, 3887, 3884, 3882, -1, 3887, 3790, 3776, -1, 3888, 3866, 3852, -1, 3889, 1924, 1922, -1, 3888, 3852, 3871, -1, 3889, 3885, 3884, -1, 3889, 1922, 3885, -1, 3889, 3884, 3887, -1, 3890, 3776, 3779, -1, 3890, 3887, 3776, -1, 3891, 3864, 3873, -1, 3891, 3878, 3864, -1, 3892, 3887, 3890, -1, 3893, 3871, 3857, -1, 3894, 1926, 1924, -1, 3893, 3857, 3876, -1, 3894, 1924, 3889, -1, 3894, 3889, 3887, -1, 3894, 3887, 3892, -1, 3895, 3855, 3841, -1, 3896, 3779, 3897, -1, 3895, 3841, 3878, -1, 3896, 3890, 3779, -1, 3896, 3892, 3890, -1, 3898, 3897, 3899, -1, 3898, 1930, 1928, -1, 3898, 1928, 1926, -1, 3900, 1098, 1071, -1, 3898, 3899, 1930, -1, 3898, 1926, 3894, -1, 3898, 3894, 3892, -1, 3898, 3896, 3897, -1, 3900, 3886, 1098, -1, 3898, 3892, 3896, -1, 3901, 3873, 3859, -1, 3901, 3859, 3880, -1, 3902, 3248, 3247, -1, 3902, 3247, 3883, -1, 3903, 3876, 3862, -1, 3903, 3862, 3886, -1, 3904, 3866, 3888, -1, 3904, 3880, 3866, -1, 3905, 3895, 3878, -1, 3905, 3878, 3891, -1, 3906, 3888, 3871, -1, 3906, 3871, 3893, -1, 3907, 3855, 3895, -1, 3907, 3868, 3855, -1, 3908, 3886, 3900, -1, 3908, 3903, 3886, -1, 3909, 3891, 3873, -1, 3909, 3873, 3901, -1, 3910, 3249, 3248, -1, 3910, 3248, 3902, -1, 3911, 3876, 3903, -1, 3911, 3893, 3876, -1, 3912, 3901, 3880, -1, 3912, 3880, 3904, -1, 3913, 3895, 3905, -1, 3913, 3907, 3895, -1, 3914, 3888, 3906, -1, 3914, 3904, 3888, -1, 3915, 3868, 3907, -1, 3915, 3883, 3868, -1, 3916, 3903, 3908, -1, 3916, 3911, 3903, -1, 3917, 3905, 3891, -1, 3917, 3891, 3909, -1, 3918, 1071, 1070, -1, 3918, 1070, 1932, -1, 3918, 3900, 1071, -1, 3767, 3250, 3249, -1, 3767, 3249, 3910, -1, 3919, 3893, 3911, -1, 3919, 3906, 3893, -1, 3920, 3909, 3901, -1, 3920, 3917, 3909, -1, 3920, 3901, 3912, -1, 3921, 3907, 3913, -1, 3921, 3915, 3907, -1, 3922, 3912, 3904, -1, 3922, 3904, 3914, -1, 3923, 3902, 3883, -1, 3923, 3883, 3915, -1, 3778, 3919, 3911, -1, 3778, 3911, 3916, -1, 3924, 3905, 3917, -1, 3924, 3913, 3905, -1, 3899, 1932, 1930, -1, 3899, 3908, 3900, -1, 3899, 3900, 3918, -1, 3899, 3918, 1932, -1, 3768, 3251, 3250, -1, 3768, 3250, 3767, -1, 3925, 3906, 3919, -1, 3925, 3914, 3906, -1, 3762, 3917, 3920, -1, 3774, 3915, 3921, -1, 3774, 3923, 3915, -1, 3781, 3920, 3912, -1, 3781, 3762, 3920, -1, 3781, 3912, 3922, -1, 3758, 3902, 3923, -1, 3758, 3910, 3902, -1, 3777, 3919, 3778, -1, 3777, 3925, 3919, -1, 3783, 3921, 3913, -1, 3783, 3913, 3924, -1, 3897, 3916, 3908, -1, 3897, 3908, 3899, -1, 3787, 3252, 3251, -1, 3787, 1077, 3252, -1, 3787, 3251, 3768, -1, 3770, 3922, 3914, -1, 3770, 3914, 3925, -1, 3764, 3924, 3917, -1, 3764, 3917, 3762, -1, 3764, 3783, 3924, -1, 3759, 3923, 3774, -1, 3759, 3758, 3923, -1, 3763, 3762, 3781, -1, 3760, 3910, 3758, -1, 3760, 3767, 3910, -1, 3771, 3925, 3777, -1, 3771, 3770, 3925, -1, 3775, 3921, 3783, -1, 3775, 3774, 3921, -1, 3779, 3778, 3916, -1, 3779, 3916, 3897, -1, 3772, 3922, 3770, -1, 3772, 3781, 3922, -1, 3765, 3783, 3764, -1, 462, 1781, 463, -1, 1781, 3926, 463, -1, 463, 3927, 459, -1, 3926, 3927, 463, -1, 459, 3928, 457, -1, 3927, 3928, 459, -1, 457, 3929, 473, -1, 3928, 3929, 457, -1, 473, 3930, 485, -1, 3929, 3930, 473, -1, 485, 3931, 491, -1, 3930, 3931, 485, -1, 491, 3932, 497, -1, 3931, 3932, 491, -1, 497, 3933, 509, -1, 3932, 3933, 497, -1, 509, 3934, 516, -1, 3933, 3934, 509, -1, 516, 3935, 526, -1, 3934, 3935, 516, -1, 526, 3936, 544, -1, 3935, 3936, 526, -1, 544, 3937, 540, -1, 3936, 3937, 544, -1, 540, 3938, 444, -1, 3937, 3938, 540, -1, 444, 1754, 445, -1, 3938, 1754, 444, -1, 3939, 3940, 3941, -1, 3942, 3940, 3939, -1, 3943, 3944, 3945, -1, 3946, 3944, 3943, -1, 506, 3947, 3948, -1, 2310, 577, 579, -1, 3948, 3947, 3949, -1, 3949, 3947, 3950, -1, 3951, 3952, 3953, -1, 3954, 3952, 3951, -1, 3955, 3956, 3954, -1, 3941, 3956, 3955, -1, 3950, 3957, 3942, -1, 3942, 3957, 3940, -1, 3958, 3959, 3946, -1, 3946, 3959, 3944, -1, 3956, 3960, 3954, -1, 3954, 3960, 3952, -1, 3940, 3961, 3941, -1, 3941, 3961, 3956, -1, 549, 3962, 506, -1, 506, 3962, 3947, -1, 3950, 3962, 3957, -1, 3947, 3962, 3950, -1, 3953, 3963, 3958, -1, 3958, 3963, 3959, -1, 3956, 3964, 3960, -1, 3961, 3964, 3956, -1, 3957, 3965, 3940, -1, 3940, 3965, 3961, -1, 3952, 3966, 3953, -1, 3953, 3966, 3963, -1, 3965, 3967, 3961, -1, 3961, 3967, 3964, -1, 3957, 3968, 3965, -1, 549, 3968, 3962, -1, 3962, 3968, 3957, -1, 3952, 3969, 3966, -1, 3960, 3969, 3952, -1, 549, 3970, 3968, -1, 443, 3970, 549, -1, 3965, 3970, 3967, -1, 3968, 3970, 3965, -1, 3960, 3971, 3969, -1, 3964, 3971, 3960, -1, 3967, 3972, 3964, -1, 3964, 3972, 3971, -1, 3967, 3973, 3972, -1, 3970, 3973, 3967, -1, 443, 3973, 3970, -1, 1756, 3973, 443, -1, 3974, 3975, 453, -1, 3976, 3977, 3975, -1, 3975, 3977, 453, -1, 453, 3977, 462, -1, 3978, 3979, 3980, -1, 462, 3981, 1779, -1, 3977, 3981, 462, -1, 3976, 3981, 3977, -1, 3979, 3982, 3976, -1, 1777, 3983, 1775, -1, 3982, 3983, 3976, -1, 3980, 3984, 3974, -1, 3974, 3984, 3975, -1, 3975, 3984, 3976, -1, 443, 445, 1756, -1, 3979, 3984, 3980, -1, 3976, 3984, 3979, -1, 1777, 3985, 3983, -1, 1779, 3985, 1777, -1, 3981, 3985, 1779, -1, 3983, 3985, 3976, -1, 3976, 3985, 3981, -1, 3986, 3987, 3978, -1, 2310, 3988, 577, -1, 3979, 3987, 3982, -1, 2310, 3989, 3988, -1, 3978, 3987, 3979, -1, 2309, 3989, 2310, -1, 3987, 3990, 3982, -1, 1775, 3991, 1773, -1, 2309, 3992, 3989, -1, 3983, 3991, 1775, -1, 3982, 3991, 3983, -1, 3990, 3991, 3982, -1, 3986, 3993, 3987, -1, 3945, 3993, 3986, -1, 2308, 3992, 2309, -1, 3987, 3993, 3990, -1, 3988, 3994, 577, -1, 577, 3994, 601, -1, 3993, 3995, 3990, -1, 1773, 3996, 1771, -1, 3991, 3996, 1773, -1, 3990, 3996, 3991, -1, 3995, 3996, 3990, -1, 2307, 3997, 2308, -1, 3945, 3998, 3993, -1, 2308, 3997, 3992, -1, 3993, 3998, 3995, -1, 3944, 3998, 3945, -1, 601, 3999, 424, -1, 3994, 3999, 601, -1, 3989, 4000, 3988, -1, 3998, 4001, 3995, -1, 1771, 4002, 1769, -1, 3996, 4002, 1771, -1, 3988, 4000, 3994, -1, 3995, 4002, 3996, -1, 4001, 4002, 3995, -1, 3944, 4003, 3998, -1, 3998, 4003, 4001, -1, 3959, 4003, 3944, -1, 2306, 4004, 2307, -1, 2307, 4004, 3997, -1, 1769, 4005, 1767, -1, 4002, 4005, 1769, -1, 4001, 4005, 4002, -1, 3994, 4006, 3999, -1, 3963, 4007, 3959, -1, 4000, 4006, 3994, -1, 3959, 4007, 4003, -1, 3989, 4008, 4000, -1, 4003, 4009, 4001, -1, 4007, 4009, 4003, -1, 4001, 4009, 4005, -1, 3992, 4008, 3989, -1, 4009, 4010, 4005, -1, 4007, 4010, 4009, -1, 2305, 4011, 2306, -1, 2306, 4011, 4004, -1, 4010, 4012, 4005, -1, 1767, 4013, 1765, -1, 4005, 4013, 1767, -1, 3999, 4014, 424, -1, 4012, 4013, 4005, -1, 3963, 4015, 4007, -1, 4008, 4016, 4000, -1, 4000, 4016, 4006, -1, 4007, 4015, 4010, -1, 4010, 4015, 4012, -1, 4012, 4017, 4013, -1, 1765, 4017, 1763, -1, 3992, 4018, 4008, -1, 4013, 4017, 1765, -1, 3997, 4018, 3992, -1, 3966, 4019, 3963, -1, 3969, 4019, 3966, -1, 3963, 4019, 4015, -1, 2278, 4020, 2305, -1, 4019, 4021, 4015, -1, 2305, 4020, 4011, -1, 4015, 4022, 4012, -1, 4006, 4023, 3999, -1, 4012, 4022, 4017, -1, 3999, 4023, 4014, -1, 4015, 4024, 4022, -1, 4021, 4024, 4015, -1, 4017, 4025, 1763, -1, 1763, 4025, 1761, -1, 4018, 4026, 4008, -1, 4008, 4026, 4016, -1, 4024, 4025, 4022, -1, 4022, 4025, 4017, -1, 3969, 4027, 4019, -1, 4019, 4027, 4021, -1, 3971, 4027, 3969, -1, 4004, 4028, 3997, -1, 3997, 4028, 4018, -1, 4021, 4029, 4024, -1, 4025, 4029, 1761, -1, 4024, 4029, 4025, -1, 2277, 4030, 2278, -1, 2278, 4030, 4020, -1, 3972, 4031, 3971, -1, 3971, 4031, 4027, -1, 424, 4032, 422, -1, 4021, 4033, 4029, -1, 4014, 4032, 424, -1, 4027, 4033, 4021, -1, 4006, 4034, 4023, -1, 4031, 4033, 4027, -1, 4033, 4035, 4029, -1, 3972, 4035, 4031, -1, 4031, 4035, 4033, -1, 4016, 4034, 4006, -1, 1757, 4036, 1756, -1, 1756, 4036, 3973, -1, 4018, 4037, 4026, -1, 4035, 4036, 4029, -1, 4028, 4037, 4018, -1, 3973, 4036, 3972, -1, 3972, 4036, 4035, -1, 1759, 4038, 1757, -1, 1761, 4038, 1759, -1, 1757, 4038, 4036, -1, 4011, 4039, 4004, -1, 4036, 4038, 4029, -1, 4029, 4038, 1761, -1, 4004, 4039, 4028, -1, 4023, 4040, 4014, -1, 4014, 4040, 4032, -1, 2276, 4041, 2277, -1, 2277, 4041, 4030, -1, 4032, 4042, 422, -1, 4016, 4043, 4034, -1, 4026, 4043, 4016, -1, 4028, 4044, 4037, -1, 4039, 4044, 4028, -1, 4011, 4045, 4039, -1, 4020, 4045, 4011, -1, 4023, 4046, 4040, -1, 4034, 4046, 4023, -1, 2275, 4047, 2276, -1, 2276, 4047, 4041, -1, 4040, 4048, 4032, -1, 4032, 4048, 4042, -1, 4026, 4049, 4043, -1, 4037, 4049, 4026, -1, 4039, 4050, 4044, -1, 4045, 4050, 4039, -1, 4030, 4051, 4020, -1, 4020, 4051, 4045, -1, 4034, 4052, 4046, -1, 4043, 4052, 4034, -1, 2274, 4053, 2275, -1, 2275, 4053, 4047, -1, 422, 4054, 447, -1, 4042, 4054, 422, -1, 4046, 4055, 4040, -1, 4040, 4055, 4048, -1, 4044, 4056, 4037, -1, 4037, 4056, 4049, -1, 4045, 4057, 4050, -1, 4051, 4057, 4045, -1, 4041, 4058, 4030, -1, 4030, 4058, 4051, -1, 4049, 4059, 4043, -1, 4043, 4059, 4052, -1, 2273, 4060, 2274, -1, 2274, 4060, 4053, -1, 4054, 4061, 447, -1, 4048, 4062, 4042, -1, 4042, 4062, 4054, -1, 4046, 4063, 4055, -1, 4052, 4063, 4046, -1, 4050, 4064, 4044, -1, 4044, 4064, 4056, -1, 4058, 4065, 4051, -1, 4051, 4065, 4057, -1, 4047, 4066, 4041, -1, 4041, 4066, 4058, -1, 4049, 4067, 4059, -1, 4056, 4067, 4049, -1, 2273, 4068, 4060, -1, 469, 4068, 468, -1, 468, 4068, 2272, -1, 2272, 4068, 2273, -1, 4054, 4069, 4061, -1, 4062, 4069, 4054, -1, 4048, 4070, 4062, -1, 4055, 4070, 4048, -1, 4059, 4071, 4052, -1, 4052, 4071, 4063, -1, 4050, 4072, 4064, -1, 4057, 4072, 4050, -1, 4066, 4073, 4058, -1, 4058, 4073, 4065, -1, 4047, 4074, 4066, -1, 4053, 4074, 4047, -1, 4056, 4075, 4067, -1, 4064, 4075, 4056, -1, 4062, 4076, 4069, -1, 4070, 4076, 4062, -1, 4063, 4077, 4055, -1, 4055, 4077, 4070, -1, 4067, 4078, 4059, -1, 4059, 4078, 4071, -1, 447, 3974, 453, -1, 4061, 3974, 447, -1, 4065, 4079, 4057, -1, 4057, 4079, 4072, -1, 4066, 4080, 4073, -1, 4074, 4080, 4066, -1, 4053, 4081, 4074, -1, 4060, 4081, 4053, -1, 4064, 4082, 4075, -1, 4072, 4082, 4064, -1, 4077, 4083, 4070, -1, 4070, 4083, 4076, -1, 4063, 4084, 4077, -1, 4071, 4084, 4063, -1, 4075, 4085, 4067, -1, 4067, 4085, 4078, -1, 4061, 3980, 3974, -1, 4069, 3980, 4061, -1, 4065, 4086, 4079, -1, 4073, 4086, 4065, -1, 4074, 4087, 4080, -1, 4081, 4087, 4074, -1, 4068, 4088, 4060, -1, 481, 4088, 469, -1, 4060, 4088, 4081, -1, 469, 4088, 4068, -1, 4079, 4089, 4072, -1, 4072, 4089, 4082, -1, 4077, 3943, 4083, -1, 4084, 3943, 4077, -1, 4078, 4090, 4071, -1, 4071, 4090, 4084, -1, 4082, 4091, 4075, -1, 4075, 4091, 4085, -1, 4076, 3978, 4069, -1, 4069, 3978, 3980, -1, 4080, 4092, 4073, -1, 4073, 4092, 4086, -1, 481, 4093, 4088, -1, 4081, 4093, 4087, -1, 4088, 4093, 4081, -1, 4079, 3939, 4089, -1, 4086, 3939, 4079, -1, 4084, 3946, 3943, -1, 4090, 3946, 4084, -1, 4085, 4094, 4078, -1, 4078, 4094, 4090, -1, 4082, 3955, 4091, -1, 4089, 3955, 4082, -1, 4076, 3986, 3978, -1, 4083, 3986, 4076, -1, 4080, 3949, 4092, -1, 4087, 3949, 4080, -1, 4086, 3942, 3939, -1, 4092, 3942, 4086, -1, 4090, 3958, 3946, -1, 4094, 3958, 4090, -1, 4091, 3951, 4085, -1, 4085, 3951, 4094, -1, 3939, 3941, 4089, -1, 4089, 3941, 3955, -1, 3943, 3945, 4083, -1, 4083, 3945, 3986, -1, 481, 3948, 4093, -1, 506, 3948, 481, -1, 4087, 3948, 3949, -1, 4093, 3948, 4087, -1, 4092, 3950, 3942, -1, 3949, 3950, 4092, -1, 4094, 3953, 3958, -1, 3951, 3953, 4094, -1, 3955, 3954, 4091, -1, 4091, 3954, 3951, -1, 1758, 4095, 4096, -1, 1792, 1794, 3930, -1, 1758, 1755, 4095, -1, 1794, 3931, 3930, -1, 4097, 1774, 4098, -1, 1754, 4099, 1755, -1, 1755, 4099, 4095, -1, 4100, 1776, 4097, -1, 3931, 1796, 3932, -1, 4097, 1776, 1774, -1, 1794, 1796, 3931, -1, 4098, 1772, 4101, -1, 1774, 1772, 4098, -1, 4102, 1778, 4100, -1, 4100, 1778, 1776, -1, 1796, 1798, 3932, -1, 1754, 1813, 4099, -1, 4101, 1770, 4103, -1, 1772, 1770, 4101, -1, 4104, 1780, 4102, -1, 4102, 1780, 1778, -1, 3938, 1812, 1754, -1, 1754, 1812, 1813, -1, 4105, 1768, 4106, -1, 4103, 1768, 4105, -1, 3932, 1800, 3933, -1, 1770, 1768, 4103, -1, 1798, 1800, 3932, -1, 3937, 1810, 3938, -1, 3938, 1810, 1812, -1, 1784, 1781, 1782, -1, 1782, 1781, 4104, -1, 4104, 1781, 1780, -1, 3933, 1802, 3934, -1, 1768, 1766, 4106, -1, 1800, 1802, 3933, -1, 1784, 3926, 1781, -1, 3936, 1808, 3937, -1, 3937, 1808, 1810, -1, 1784, 1786, 3926, -1, 1766, 4107, 4106, -1, 3934, 1804, 3935, -1, 1802, 1804, 3934, -1, 1766, 1764, 4107, -1, 3935, 1806, 3936, -1, 3936, 1806, 1808, -1, 1804, 1806, 3935, -1, 1786, 3927, 3926, -1, 1786, 1788, 3927, -1, 1764, 4108, 4107, -1, 1764, 1762, 4108, -1, 1788, 3928, 3927, -1, 1788, 1790, 3928, -1, 1762, 4109, 4108, -1, 1762, 1760, 4109, -1, 1790, 3929, 3928, -1, 1790, 1792, 3929, -1, 1760, 4096, 4109, -1, 1760, 1758, 4096, -1, 1792, 3930, 3929, -1, 1813, 658, 660, -1, 4099, 660, 706, -1, 4099, 1813, 660, -1, 4095, 706, 788, -1, 4095, 4099, 706, -1, 4096, 788, 783, -1, 4096, 4095, 788, -1, 4109, 783, 778, -1, 4109, 4096, 783, -1, 4108, 778, 772, -1, 4108, 4109, 778, -1, 4107, 772, 761, -1, 4107, 4108, 772, -1, 4106, 761, 757, -1, 4106, 4107, 761, -1, 4105, 4106, 757, -1, 4103, 750, 744, -1, 4103, 757, 750, -1, 4103, 4105, 757, -1, 4101, 4103, 744, -1, 4098, 744, 738, -1, 4098, 4101, 744, -1, 4097, 738, 731, -1, 4097, 4098, 738, -1, 4100, 731, 730, -1, 4100, 4097, 731, -1, 4102, 730, 713, -1, 4102, 4100, 730, -1, 4104, 713, 723, -1, 4104, 4102, 713, -1, 1782, 4104, 723, -1, 1782, 723, 720, -1, 4110, 4111, 4112, -1, 4113, 4114, 4115, -1, 4113, 4116, 4114, -1, 4117, 4118, 4119, -1, 4117, 4119, 4120, -1, 4121, 4122, 4123, -1, 4121, 4123, 4124, -1, 4125, 4126, 4127, -1, 4125, 4127, 4128, -1, 4129, 4130, 4118, -1, 4129, 4112, 4130, -1, 4131, 4124, 4132, -1, 4131, 4132, 4133, -1, 4134, 4113, 4115, -1, 4134, 4115, 4135, -1, 4136, 4133, 4111, -1, 4136, 4111, 4110, -1, 4137, 675, 666, -1, 4137, 4138, 4116, -1, 4137, 666, 4138, -1, 4137, 4116, 4113, -1, 4139, 4129, 4118, -1, 4139, 4118, 4117, -1, 4140, 4135, 4122, -1, 4140, 4122, 4121, -1, 4141, 4126, 4125, -1, 4141, 4120, 4126, -1, 4142, 4112, 4129, -1, 4142, 4110, 4112, -1, 666, 663, 1868, -1, 4143, 4121, 4124, -1, 4143, 4124, 4131, -1, 4144, 681, 675, -1, 4144, 675, 4137, -1, 4144, 4113, 4134, -1, 4144, 4137, 4113, -1, 4145, 4133, 4136, -1, 4145, 4131, 4133, -1, 4146, 4129, 4139, -1, 4146, 4142, 4129, -1, 4147, 4135, 4140, -1, 4147, 4134, 4135, -1, 4148, 4117, 4120, -1, 4148, 4120, 4141, -1, 4149, 4136, 4110, -1, 4149, 4110, 4142, -1, 4150, 4140, 4121, -1, 4150, 4121, 4143, -1, 4151, 4131, 4145, -1, 4151, 4143, 4131, -1, 4152, 4149, 4142, -1, 4152, 4142, 4146, -1, 4153, 4134, 4147, -1, 4153, 681, 4144, -1, 4153, 4144, 4134, -1, 4154, 4139, 4117, -1, 4154, 4117, 4148, -1, 4155, 4136, 4149, -1, 4155, 4145, 4136, -1, 4156, 4147, 4140, -1, 4156, 4140, 4150, -1, 4157, 4158, 819, -1, 4159, 4150, 4143, -1, 4157, 819, 638, -1, 4159, 4143, 4151, -1, 4160, 4161, 4158, -1, 4162, 4149, 4152, -1, 4162, 4155, 4149, -1, 4160, 4158, 4157, -1, 4163, 4139, 4154, -1, 4164, 4165, 4161, -1, 4163, 4146, 4139, -1, 4166, 4151, 4145, -1, 4164, 4161, 4160, -1, 4166, 4145, 4155, -1, 4167, 715, 681, -1, 4167, 681, 4153, -1, 4167, 4147, 4156, -1, 4168, 638, 637, -1, 4167, 4153, 4147, -1, 4168, 4157, 638, -1, 4169, 4156, 4150, -1, 4169, 4150, 4159, -1, 4170, 4171, 4165, -1, 4172, 4166, 4155, -1, 4170, 4165, 4164, -1, 4172, 4155, 4162, -1, 4173, 4152, 4146, -1, 4173, 4146, 4163, -1, 4174, 4168, 637, -1, 4175, 4159, 4151, -1, 4175, 4151, 4166, -1, 4176, 4157, 4168, -1, 4176, 4160, 4157, -1, 4177, 715, 4167, -1, 4177, 4167, 4156, -1, 4177, 4156, 4169, -1, 4178, 4179, 4171, -1, 4180, 4166, 4172, -1, 4178, 4171, 4170, -1, 4180, 4175, 4166, -1, 4181, 4152, 4173, -1, 4181, 4162, 4152, -1, 4182, 4168, 4174, -1, 4182, 4176, 4168, -1, 4183, 4164, 4160, -1, 4183, 4160, 4176, -1, 4184, 4169, 4159, -1, 4184, 4159, 4175, -1, 4185, 4175, 4180, -1, 4185, 4184, 4175, -1, 4186, 4172, 4162, -1, 4187, 637, 654, -1, 4186, 4162, 4181, -1, 4187, 4174, 637, -1, 4188, 774, 715, -1, 4188, 715, 4177, -1, 4189, 4190, 4179, -1, 4188, 4177, 4169, -1, 4188, 4169, 4184, -1, 4189, 4179, 4178, -1, 4191, 774, 4188, -1, 4191, 4184, 4185, -1, 4191, 4188, 4184, -1, 4192, 4180, 4172, -1, 4192, 4172, 4186, -1, 4193, 4183, 4176, -1, 4193, 4176, 4182, -1, 4194, 4164, 4183, -1, 4195, 4185, 4180, -1, 4194, 4170, 4164, -1, 4195, 4180, 4192, -1, 4196, 718, 774, -1, 4196, 774, 4191, -1, 4196, 4191, 4185, -1, 4196, 4185, 4195, -1, 4197, 4182, 4174, -1, 4197, 4174, 4187, -1, 4198, 4199, 4190, -1, 4200, 4201, 1785, -1, 4200, 4195, 4201, -1, 4198, 4190, 4189, -1, 4202, 4192, 4186, -1, 4202, 4195, 4192, -1, 4203, 4187, 654, -1, 4202, 4201, 4195, -1, 4204, 4201, 4202, -1, 4205, 1789, 1787, -1, 4206, 4194, 4183, -1, 4205, 1787, 1785, -1, 4206, 4183, 4193, -1, 4205, 1785, 4201, -1, 4205, 4201, 4204, -1, 4207, 4178, 4170, -1, 4208, 4196, 4195, -1, 4207, 4170, 4194, -1, 4208, 718, 4196, -1, 4208, 4195, 4200, -1, 4209, 720, 718, -1, 4209, 718, 4208, -1, 4209, 4208, 4200, -1, 4210, 4209, 4200, -1, 4210, 1785, 1783, -1, 4210, 1783, 720, -1, 4211, 4182, 4197, -1, 4210, 4200, 1785, -1, 4210, 720, 4209, -1, 4212, 4204, 4202, -1, 4211, 4193, 4182, -1, 4212, 4186, 4181, -1, 4212, 4202, 4186, -1, 4213, 1841, 4199, -1, 4213, 4199, 4198, -1, 4214, 4187, 4203, -1, 4215, 4204, 4212, -1, 4216, 4205, 4204, -1, 4214, 4197, 4187, -1, 4216, 4204, 4215, -1, 4216, 1791, 1789, -1, 4216, 1789, 4205, -1, 4217, 4215, 4212, -1, 4217, 4212, 4181, -1, 4218, 4207, 4194, -1, 4217, 4181, 4173, -1, 4218, 4194, 4206, -1, 4219, 4215, 4217, -1, 4220, 654, 686, -1, 4220, 4203, 654, -1, 4221, 4216, 4215, -1, 4221, 1791, 4216, -1, 4221, 4215, 4219, -1, 4221, 1793, 1791, -1, 4222, 4178, 4207, -1, 4223, 4219, 4217, -1, 4223, 4217, 4173, -1, 4222, 4189, 4178, -1, 4223, 4173, 4163, -1, 4224, 4219, 4223, -1, 4225, 4193, 4211, -1, 4226, 4219, 4224, -1, 4225, 4206, 4193, -1, 4226, 4221, 4219, -1, 4226, 1793, 4221, -1, 4227, 1827, 1841, -1, 4226, 1795, 1793, -1, 4228, 4223, 4163, -1, 4228, 4224, 4223, -1, 4228, 4163, 4154, -1, 4227, 1841, 4213, -1, 4229, 4224, 4228, -1, 4230, 4211, 4197, -1, 4231, 4226, 4224, -1, 4230, 4197, 4214, -1, 4231, 4224, 4229, -1, 4231, 1795, 4226, -1, 4231, 1797, 1795, -1, 4232, 4207, 4218, -1, 4233, 4228, 4154, -1, 4233, 4154, 4148, -1, 4233, 4229, 4228, -1, 4232, 4222, 4207, -1, 4234, 1799, 1797, -1, 4234, 4231, 4229, -1, 4234, 1797, 4231, -1, 4234, 4229, 4233, -1, 4235, 4203, 4220, -1, 4236, 4148, 4141, -1, 4235, 4214, 4203, -1, 4236, 4233, 4148, -1, 4237, 4189, 4222, -1, 4237, 4198, 4189, -1, 4238, 4233, 4236, -1, 4237, 4222, 4232, -1, 4239, 4218, 4206, -1, 4239, 4206, 4225, -1, 4240, 4233, 4238, -1, 4241, 4234, 4233, -1, 4241, 4233, 4240, -1, 4242, 1801, 1799, -1, 4243, 1828, 1827, -1, 4242, 1799, 4234, -1, 4242, 4234, 4241, -1, 4242, 4241, 4240, -1, 4244, 4238, 4236, -1, 4243, 1827, 4227, -1, 4244, 4236, 4141, -1, 4244, 4141, 4125, -1, 4245, 1803, 1801, -1, 4246, 4220, 686, -1, 4245, 1801, 4242, -1, 4245, 4238, 4244, -1, 4245, 4240, 4238, -1, 4245, 4242, 4240, -1, 4247, 4225, 4211, -1, 4247, 4211, 4230, -1, 4248, 4245, 4244, -1, 4248, 4125, 4128, -1, 4248, 4244, 4125, -1, 4249, 4237, 4232, -1, 4250, 4245, 4248, -1, 4251, 1805, 1803, -1, 4251, 1803, 4245, -1, 4251, 4245, 4250, -1, 4252, 4230, 4214, -1, 4253, 4254, 4255, -1, 4252, 4214, 4235, -1, 4253, 1809, 1807, -1, 4253, 4128, 4254, -1, 4253, 4255, 1809, -1, 4253, 4248, 4128, -1, 4256, 4213, 4198, -1, 4256, 4198, 4237, -1, 4253, 4250, 4248, -1, 4257, 1807, 1805, -1, 4257, 4253, 1807, -1, 4257, 1805, 4251, -1, 4257, 4251, 4250, -1, 4256, 4237, 4249, -1, 4257, 4250, 4253, -1, 4258, 686, 659, -1, 4258, 4246, 686, -1, 4259, 4232, 4218, -1, 4259, 4218, 4239, -1, 4260, 1863, 1828, -1, 4260, 1828, 4243, -1, 4261, 4235, 4220, -1, 4261, 4220, 4246, -1, 4262, 4225, 4247, -1, 4262, 4239, 4225, -1, 4263, 4256, 4249, -1, 4264, 4247, 4230, -1, 4264, 4230, 4252, -1, 4265, 4213, 4256, -1, 4265, 4256, 4263, -1, 4265, 4227, 4213, -1, 4266, 4246, 4258, -1, 4266, 4261, 4246, -1, 4267, 4249, 4232, -1, 4267, 4232, 4259, -1, 4268, 1865, 1863, -1, 4268, 1863, 4260, -1, 4269, 4235, 4261, -1, 4269, 4252, 4235, -1, 4270, 4259, 4239, -1, 4270, 4267, 4259, -1, 4270, 4239, 4262, -1, 4271, 4265, 4263, -1, 4272, 4247, 4264, -1, 4272, 4262, 4247, -1, 4273, 4227, 4265, -1, 4273, 4243, 4227, -1, 4274, 4261, 4266, -1, 4274, 4269, 4261, -1, 4275, 4263, 4249, -1, 4275, 4249, 4267, -1, 4276, 659, 658, -1, 4276, 658, 1811, -1, 4276, 4258, 659, -1, 4114, 1836, 1865, -1, 4114, 1865, 4268, -1, 4277, 4252, 4269, -1, 4277, 4264, 4252, -1, 4278, 4267, 4270, -1, 4278, 4275, 4267, -1, 4279, 4265, 4271, -1, 4279, 4273, 4265, -1, 4280, 4270, 4262, -1, 4280, 4278, 4270, -1, 4280, 4262, 4272, -1, 4281, 4260, 4243, -1, 4281, 4243, 4273, -1, 4127, 4277, 4269, -1, 4127, 4269, 4274, -1, 4282, 4263, 4275, -1, 4282, 4271, 4263, -1, 4255, 1811, 1809, -1, 4255, 4266, 4258, -1, 4255, 4258, 4276, -1, 4255, 4276, 1811, -1, 4116, 1836, 4114, -1, 4116, 1816, 1836, -1, 4283, 4264, 4277, -1, 4283, 4272, 4264, -1, 4284, 4282, 4275, -1, 4284, 4275, 4278, -1, 4123, 4273, 4279, -1, 4123, 4281, 4273, -1, 4130, 4278, 4280, -1, 4130, 4284, 4278, -1, 4285, 4260, 4281, -1, 4285, 4268, 4260, -1, 4126, 4277, 4127, -1, 4126, 4283, 4277, -1, 4132, 4279, 4271, -1, 4132, 4271, 4282, -1, 4254, 4274, 4266, -1, 4254, 4266, 4255, -1, 4138, 1868, 1816, -1, 4138, 666, 1868, -1, 4138, 1816, 4116, -1, 4119, 4280, 4272, -1, 4119, 4272, 4283, -1, 4111, 4282, 4284, -1, 4122, 4281, 4123, -1, 4122, 4285, 4281, -1, 4112, 4111, 4284, -1, 4112, 4284, 4130, -1, 4115, 4114, 4268, -1, 4115, 4268, 4285, -1, 4120, 4283, 4126, -1, 4120, 4119, 4283, -1, 4124, 4279, 4132, -1, 4124, 4123, 4279, -1, 4128, 4127, 4274, -1, 4128, 4274, 4254, -1, 4118, 4280, 4119, -1, 4118, 4130, 4280, -1, 4133, 4132, 4282, -1, 4133, 4282, 4111, -1, 4135, 4115, 4285, -1, 4135, 4285, 4122, -1, 2515, 1818, 324, -1, 343, 2515, 324, -1, 362, 2521, 343, -1, 2794, 1839, 2413, -1, 2794, 1838, 1839, -1, 2677, 1841, 1860, -1, 4199, 1841, 2677, -1, 2507, 2572, 362, -1, 2795, 2794, 2413, -1, 2795, 2413, 2407, -1, 382, 2507, 362, -1, 2797, 2795, 2407, -1, 4190, 4199, 2665, -1, 2789, 2797, 2418, -1, 2789, 2418, 2426, -1, 391, 2554, 2534, -1, 391, 2534, 382, -1, 2771, 2789, 2426, -1, 2771, 2426, 2437, -1, 4179, 4190, 2658, -1, 4179, 2658, 2653, -1, 2750, 2771, 2437, -1, 2750, 2437, 2464, -1, 2623, 4179, 2645, -1, 399, 2510, 391, -1, 399, 2511, 2510, -1, 2729, 2750, 2464, -1, 2729, 2464, 2390, -1, 4171, 4179, 2623, -1, 2799, 2729, 2390, -1, 2799, 2406, 2422, -1, 2799, 2390, 2406, -1, 2669, 4171, 2680, -1, 2656, 4171, 2669, -1, 406, 2530, 399, -1, 2787, 2799, 2422, -1, 2787, 2422, 2431, -1, 4165, 4171, 2656, -1, 2773, 2451, 2466, -1, 2773, 2431, 2451, -1, 2629, 4165, 2630, -1, 2758, 2466, 2458, -1, 4161, 2629, 2698, -1, 4161, 4165, 2629, -1, 409, 2557, 410, -1, 2079, 2557, 409, -1, 4158, 4161, 2641, -1, 2760, 2753, 2457, -1, 4286, 2581, 409, -1, 1967, 2111, 2586, -1, 1967, 2760, 2111, -1, 819, 4158, 2635, -1, 2859, 819, 1936, -1, 4287, 2620, 4286, -1, 2809, 2586, 2585, -1, 820, 819, 2859, -1, 4288, 2619, 4287, -1, 816, 820, 2857, -1, 4289, 2617, 4288, -1, 809, 816, 2853, -1, 2613, 2612, 4289, -1, 4290, 2609, 2613, -1, 4290, 2613, 4289, -1, 801, 809, 2849, -1, 2820, 2812, 2589, -1, 4291, 2601, 2606, -1, 4291, 2602, 2601, -1, 4291, 2606, 4290, -1, 2821, 2588, 2592, -1, 2821, 2820, 2588, -1, 792, 801, 2848, -1, 2841, 792, 2845, -1, 2825, 2821, 2592, -1, 2825, 2592, 2596, -1, 2838, 792, 2841, -1, 2829, 2596, 2599, -1, 2829, 2825, 2596, -1, 2833, 2599, 2602, -1, 2833, 2602, 4291, -1, 2833, 2829, 2599, -1, 770, 4291, 4292, -1, 770, 792, 2838, -1, 770, 2833, 4291, -1, 770, 2834, 2833, -1, 770, 2838, 2834, -1, 753, 4292, 1823, -1, 753, 770, 4292, -1, 733, 753, 1823, -1, 2635, 1936, 819, -1, 2641, 2635, 4158, -1, 2698, 2641, 4161, -1, 2656, 2630, 4165, -1, 2623, 2680, 4171, -1, 2653, 2645, 4179, -1, 2665, 2658, 4190, -1, 2677, 2665, 4199, -1, 2809, 1967, 2586, -1, 2815, 2809, 2585, -1, 2807, 2815, 2594, -1, 2808, 2807, 2584, -1, 2812, 2808, 2583, -1, 2848, 2845, 792, -1, 2849, 2848, 801, -1, 2853, 2849, 809, -1, 2855, 2853, 816, -1, 2857, 2855, 816, -1, 2859, 2857, 820, -1, 2773, 2787, 2431, -1, 2758, 2773, 2466, -1, 2753, 2758, 2458, -1, 2457, 2111, 2760, -1, 2458, 2457, 2753, -1, 2407, 2418, 2797, -1, 2581, 2079, 409, -1, 2620, 2581, 4286, -1, 2619, 2620, 4287, -1, 2617, 2619, 4288, -1, 2612, 2617, 4289, -1, 2606, 2609, 4290, -1, 2589, 2588, 2820, -1, 2583, 2589, 2812, -1, 2584, 2583, 2808, -1, 2594, 2584, 2807, -1, 2585, 2594, 2815, -1, 2521, 2515, 343, -1, 2572, 2521, 362, -1, 2508, 2507, 382, -1, 2534, 2508, 382, -1, 2510, 2554, 391, -1, 2530, 2511, 399, -1, 2538, 2530, 406, -1, 2556, 2538, 410, -1, 410, 2538, 406, -1, 2557, 2556, 410, -1, 1736, 4293, 34, -1, 34, 4293, 4294, -1, 4294, 4293, 4295, -1, 4295, 4296, 4297, -1, 4293, 4296, 4295, -1, 4297, 4298, 4299, -1, 4296, 4298, 4297, -1, 4299, 4300, 4301, -1, 4298, 4300, 4299, -1, 4301, 4302, 4303, -1, 4300, 4302, 4301, -1, 4303, 4304, 4305, -1, 4302, 4304, 4303, -1, 4305, 4306, 4307, -1, 4304, 4306, 4305, -1, 4306, 4308, 4307, -1, 4307, 4309, 4310, -1, 4308, 4309, 4307, -1, 4310, 4311, 4312, -1, 4312, 4311, 4313, -1, 4309, 4311, 4310, -1, 4311, 4314, 4313, -1, 4313, 4315, 4316, -1, 4316, 4315, 4317, -1, 4314, 4315, 4313, -1, 4315, 4318, 4317, -1, 4317, 1722, 51, -1, 4318, 1722, 4317, -1, 4319, 4320, 4321, -1, 4321, 4320, 4322, -1, 4323, 4324, 4325, -1, 4325, 4324, 4326, -1, 94, 4327, 4328, -1, 2294, 166, 168, -1, 4328, 4327, 4329, -1, 4329, 4327, 4330, -1, 4331, 4332, 4333, -1, 4334, 4332, 4331, -1, 4322, 4335, 4336, -1, 4336, 4335, 4334, -1, 4319, 4337, 4320, -1, 4330, 4337, 4319, -1, 4338, 4339, 4323, -1, 4323, 4339, 4324, -1, 4334, 4340, 4332, -1, 4335, 4340, 4334, -1, 4322, 4341, 4335, -1, 4320, 4341, 4322, -1, 138, 4342, 94, -1, 94, 4342, 4327, -1, 4327, 4342, 4330, -1, 4330, 4342, 4337, -1, 4333, 4343, 4338, -1, 4338, 4343, 4339, -1, 4341, 4344, 4335, -1, 4335, 4344, 4340, -1, 4337, 4345, 4320, -1, 4320, 4345, 4341, -1, 4333, 4346, 4343, -1, 4332, 4346, 4333, -1, 4345, 4347, 4341, -1, 4341, 4347, 4344, -1, 4337, 4348, 4345, -1, 138, 4348, 4342, -1, 4342, 4348, 4337, -1, 4332, 4349, 4346, -1, 4340, 4349, 4332, -1, 138, 4350, 4348, -1, 32, 4350, 138, -1, 4345, 4350, 4347, -1, 4348, 4350, 4345, -1, 4340, 4351, 4349, -1, 4344, 4351, 4340, -1, 4347, 4352, 4344, -1, 4344, 4352, 4351, -1, 4294, 4353, 34, -1, 4347, 4353, 4352, -1, 32, 4353, 4350, -1, 4350, 4353, 4347, -1, 34, 4353, 32, -1, 4354, 4355, 42, -1, 4356, 4357, 4355, -1, 4355, 4357, 42, -1, 42, 4357, 51, -1, 4358, 4359, 4360, -1, 51, 4361, 4317, -1, 4357, 4361, 51, -1, 4356, 4361, 4357, -1, 4359, 4362, 4356, -1, 4316, 4363, 4313, -1, 4362, 4363, 4356, -1, 4355, 4364, 4356, -1, 4354, 4364, 4355, -1, 4356, 4364, 4359, -1, 4359, 4364, 4360, -1, 4360, 4364, 4354, -1, 4317, 4365, 4316, -1, 4361, 4365, 4317, -1, 4356, 4365, 4361, -1, 4363, 4365, 4356, -1, 4316, 4365, 4363, -1, 4358, 4366, 4359, -1, 2294, 4367, 166, -1, 4359, 4366, 4362, -1, 2294, 4368, 4367, -1, 4369, 4366, 4358, -1, 2291, 4368, 2294, -1, 4366, 4370, 4362, -1, 4313, 4371, 4312, -1, 4363, 4371, 4313, -1, 2291, 4372, 4368, -1, 4362, 4371, 4363, -1, 4370, 4371, 4362, -1, 4326, 4373, 4369, -1, 4369, 4373, 4366, -1, 2289, 4372, 2291, -1, 4366, 4373, 4370, -1, 4367, 4374, 166, -1, 166, 4374, 190, -1, 4373, 4375, 4370, -1, 4312, 4376, 4310, -1, 4371, 4376, 4312, -1, 4370, 4376, 4371, -1, 4375, 4376, 4370, -1, 4326, 4377, 4373, -1, 2287, 4378, 2289, -1, 4373, 4377, 4375, -1, 2289, 4378, 4372, -1, 4324, 4377, 4326, -1, 190, 4379, 13, -1, 4374, 4379, 190, -1, 4368, 4380, 4367, -1, 4377, 4381, 4375, -1, 4310, 4382, 4307, -1, 4375, 4382, 4376, -1, 4381, 4382, 4375, -1, 4376, 4382, 4310, -1, 4367, 4380, 4374, -1, 4339, 4383, 4324, -1, 4324, 4383, 4377, -1, 4377, 4383, 4381, -1, 2285, 4384, 2287, -1, 4307, 4385, 4305, -1, 2287, 4384, 4378, -1, 4382, 4385, 4307, -1, 4381, 4385, 4382, -1, 4374, 4386, 4379, -1, 4339, 4387, 4383, -1, 4343, 4387, 4339, -1, 4380, 4386, 4374, -1, 4368, 4388, 4380, -1, 4387, 4389, 4383, -1, 4372, 4388, 4368, -1, 4383, 4390, 4381, -1, 4381, 4390, 4385, -1, 4389, 4391, 4383, -1, 2283, 4392, 2285, -1, 4383, 4391, 4390, -1, 4305, 4393, 4303, -1, 2285, 4392, 4384, -1, 4385, 4393, 4305, -1, 4390, 4393, 4385, -1, 4391, 4393, 4390, -1, 4346, 4394, 4343, -1, 4379, 4395, 13, -1, 4343, 4394, 4387, -1, 4387, 4394, 4389, -1, 4391, 4396, 4393, -1, 4388, 4397, 4380, -1, 4380, 4397, 4386, -1, 4393, 4396, 4303, -1, 4389, 4396, 4391, -1, 4372, 4398, 4388, -1, 4349, 4399, 4346, -1, 4378, 4398, 4372, -1, 4346, 4399, 4394, -1, 4394, 4400, 4389, -1, 4399, 4400, 4394, -1, 2239, 4401, 2283, -1, 4389, 4400, 4396, -1, 2283, 4401, 4392, -1, 4400, 4402, 4396, -1, 4399, 4402, 4400, -1, 4386, 4403, 4379, -1, 4379, 4403, 4395, -1, 4402, 4404, 4396, -1, 4301, 4405, 4299, -1, 4303, 4405, 4301, -1, 4396, 4405, 4303, -1, 4398, 4406, 4388, -1, 4404, 4405, 4396, -1, 4388, 4406, 4397, -1, 4399, 4407, 4402, -1, 4402, 4407, 4404, -1, 4349, 4407, 4399, -1, 4384, 4408, 4378, -1, 4378, 4408, 4398, -1, 4299, 4409, 4297, -1, 4404, 4409, 4405, -1, 4405, 4409, 4299, -1, 2240, 4410, 2239, -1, 4351, 4411, 4349, -1, 4349, 4411, 4407, -1, 4352, 4411, 4351, -1, 2239, 4410, 4401, -1, 4295, 4412, 4294, -1, 4352, 4412, 4411, -1, 13, 4413, 11, -1, 4294, 4412, 4353, -1, 4395, 4413, 13, -1, 4353, 4412, 4352, -1, 4386, 4414, 4403, -1, 4411, 4412, 4407, -1, 4407, 4415, 4404, -1, 4404, 4415, 4409, -1, 4295, 4416, 4412, -1, 4407, 4416, 4415, -1, 4397, 4414, 4386, -1, 4412, 4416, 4407, -1, 4297, 4417, 4295, -1, 4398, 4418, 4406, -1, 4295, 4417, 4416, -1, 4408, 4418, 4398, -1, 4409, 4417, 4297, -1, 4415, 4417, 4409, -1, 4416, 4417, 4415, -1, 4392, 4419, 4384, -1, 4384, 4419, 4408, -1, 2243, 4420, 2240, -1, 2240, 4420, 4410, -1, 4403, 4421, 4395, -1, 4395, 4421, 4413, -1, 4413, 4422, 11, -1, 4397, 4423, 4414, -1, 4406, 4423, 4397, -1, 4408, 4424, 4418, -1, 4419, 4424, 4408, -1, 4392, 4425, 4419, -1, 4401, 4425, 4392, -1, 2245, 4426, 2243, -1, 2243, 4426, 4420, -1, 4403, 4427, 4421, -1, 4414, 4427, 4403, -1, 4421, 4428, 4413, -1, 4413, 4428, 4422, -1, 4406, 4429, 4423, -1, 4418, 4429, 4406, -1, 4419, 4430, 4424, -1, 4425, 4430, 4419, -1, 4410, 4431, 4401, -1, 4401, 4431, 4425, -1, 2247, 4432, 2245, -1, 2245, 4432, 4426, -1, 4414, 4433, 4427, -1, 4423, 4433, 4414, -1, 11, 4434, 36, -1, 4422, 4434, 11, -1, 4427, 4435, 4421, -1, 4421, 4435, 4428, -1, 4424, 4436, 4418, -1, 4418, 4436, 4429, -1, 4425, 4437, 4430, -1, 4431, 4437, 4425, -1, 4420, 4438, 4410, -1, 4410, 4438, 4431, -1, 2250, 4439, 2247, -1, 2247, 4439, 4432, -1, 4429, 4440, 4423, -1, 4423, 4440, 4433, -1, 4434, 4441, 36, -1, 4428, 4442, 4422, -1, 4422, 4442, 4434, -1, 4427, 4443, 4435, -1, 4433, 4443, 4427, -1, 4430, 4444, 4424, -1, 4424, 4444, 4436, -1, 4438, 4445, 4431, -1, 4431, 4445, 4437, -1, 4426, 4446, 4420, -1, 4420, 4446, 4438, -1, 2250, 4447, 4439, -1, 58, 4447, 57, -1, 57, 4447, 2252, -1, 2252, 4447, 2250, -1, 4429, 4448, 4440, -1, 4436, 4448, 4429, -1, 4434, 4449, 4441, -1, 4442, 4449, 4434, -1, 4428, 4450, 4442, -1, 4435, 4450, 4428, -1, 4440, 4451, 4433, -1, 4433, 4451, 4443, -1, 4430, 4452, 4444, -1, 4437, 4452, 4430, -1, 4446, 4453, 4438, -1, 4438, 4453, 4445, -1, 4426, 4454, 4446, -1, 4432, 4454, 4426, -1, 4436, 4455, 4448, -1, 4444, 4455, 4436, -1, 4442, 4456, 4449, -1, 4450, 4456, 4442, -1, 4443, 4457, 4435, -1, 4435, 4457, 4450, -1, 4448, 4458, 4440, -1, 4440, 4458, 4451, -1, 36, 4354, 42, -1, 4441, 4354, 36, -1, 4445, 4459, 4437, -1, 4437, 4459, 4452, -1, 4446, 4460, 4453, -1, 4454, 4460, 4446, -1, 4432, 4461, 4454, -1, 4439, 4461, 4432, -1, 4452, 4462, 4444, -1, 4444, 4462, 4455, -1, 4450, 4463, 4456, -1, 4457, 4463, 4450, -1, 4443, 4464, 4457, -1, 4451, 4464, 4443, -1, 4448, 4465, 4458, -1, 4455, 4465, 4448, -1, 4441, 4360, 4354, -1, 4449, 4360, 4441, -1, 4445, 4466, 4459, -1, 4453, 4466, 4445, -1, 4454, 4467, 4460, -1, 4461, 4467, 4454, -1, 4447, 4468, 4439, -1, 69, 4468, 58, -1, 4439, 4468, 4461, -1, 58, 4468, 4447, -1, 4459, 4469, 4452, -1, 4452, 4469, 4462, -1, 4457, 4325, 4463, -1, 4464, 4325, 4457, -1, 4458, 4470, 4451, -1, 4451, 4470, 4464, -1, 4462, 4471, 4455, -1, 4455, 4471, 4465, -1, 4456, 4358, 4449, -1, 4449, 4358, 4360, -1, 4460, 4472, 4453, -1, 4453, 4472, 4466, -1, 69, 4473, 4468, -1, 4461, 4473, 4467, -1, 4468, 4473, 4461, -1, 4459, 4321, 4469, -1, 4466, 4321, 4459, -1, 4470, 4323, 4464, -1, 4464, 4323, 4325, -1, 4458, 4474, 4470, -1, 4465, 4474, 4458, -1, 4469, 4336, 4462, -1, 4462, 4336, 4471, -1, 4456, 4369, 4358, -1, 4463, 4369, 4456, -1, 4460, 4329, 4472, -1, 4467, 4329, 4460, -1, 4466, 4319, 4321, -1, 4472, 4319, 4466, -1, 4474, 4338, 4470, -1, 4470, 4338, 4323, -1, 4471, 4331, 4465, -1, 4465, 4331, 4474, -1, 4469, 4322, 4336, -1, 4321, 4322, 4469, -1, 4463, 4326, 4369, -1, 4325, 4326, 4463, -1, 69, 4328, 4473, -1, 94, 4328, 69, -1, 4467, 4328, 4329, -1, 4473, 4328, 4467, -1, 4472, 4330, 4319, -1, 4329, 4330, 4472, -1, 4474, 4333, 4338, -1, 4331, 4333, 4474, -1, 4336, 4334, 4471, -1, 4471, 4334, 4331, -1, 4475, 1727, 1726, -1, 4475, 4476, 1727, -1, 4296, 1739, 1740, -1, 4296, 4293, 1739, -1, 4476, 1728, 1727, -1, 1749, 4311, 1748, -1, 1750, 4314, 1749, -1, 1749, 4314, 4311, -1, 4476, 4477, 1728, -1, 1728, 4477, 1729, -1, 1751, 4315, 1750, -1, 1750, 4315, 4314, -1, 1736, 1738, 4293, -1, 4293, 1738, 1739, -1, 1748, 4309, 1747, -1, 4311, 4309, 1748, -1, 4477, 4478, 1729, -1, 1736, 1737, 1738, -1, 1752, 4318, 1751, -1, 1751, 4318, 4315, -1, 1747, 4308, 1746, -1, 4309, 4308, 1747, -1, 1729, 4479, 1730, -1, 4480, 1722, 1753, -1, 4478, 4479, 1729, -1, 1753, 1722, 1752, -1, 1752, 1722, 4318, -1, 1735, 4481, 1736, -1, 1746, 4306, 1745, -1, 1736, 4481, 1737, -1, 1745, 4306, 1744, -1, 4308, 4306, 1746, -1, 1730, 4482, 1731, -1, 4306, 4304, 1744, -1, 4479, 4482, 1730, -1, 4480, 1723, 1722, -1, 1734, 4483, 1735, -1, 4480, 4484, 1723, -1, 1735, 4483, 4481, -1, 4304, 1743, 1744, -1, 1731, 4485, 1732, -1, 4482, 4485, 1731, -1, 4304, 4302, 1743, -1, 1733, 4486, 1734, -1, 1734, 4486, 4483, -1, 4484, 1724, 1723, -1, 4484, 4487, 1724, -1, 1732, 4488, 1733, -1, 1733, 4488, 4486, -1, 4485, 4488, 1732, -1, 4302, 1742, 1743, -1, 4302, 4300, 1742, -1, 4487, 1725, 1724, -1, 4487, 4489, 1725, -1, 4300, 1741, 1742, -1, 4300, 4298, 1741, -1, 4489, 1726, 1725, -1, 4489, 4475, 1726, -1, 4298, 1740, 1741, -1, 4298, 4296, 1740, -1, 1753, 308, 4490, -1, 4480, 1753, 4490, -1, 4484, 4490, 4491, -1, 4484, 4480, 4490, -1, 4487, 4491, 4492, -1, 4487, 4484, 4491, -1, 4489, 4492, 4493, -1, 4489, 4487, 4492, -1, 4475, 4493, 4494, -1, 4475, 4489, 4493, -1, 4476, 4494, 4495, -1, 4476, 4475, 4494, -1, 4477, 4495, 4496, -1, 4477, 4476, 4495, -1, 4478, 4496, 4497, -1, 4478, 4477, 4496, -1, 4479, 4497, 4498, -1, 4479, 4478, 4497, -1, 4482, 4498, 4499, -1, 4482, 4479, 4498, -1, 4485, 4499, 4500, -1, 4485, 4482, 4499, -1, 4488, 4500, 4501, -1, 4488, 4485, 4500, -1, 4486, 4501, 4502, -1, 4486, 4488, 4501, -1, 4483, 4502, 4503, -1, 4483, 4486, 4502, -1, 4481, 4503, 4504, -1, 4481, 4483, 4503, -1, 1737, 4481, 4504, -1, 1737, 4504, 249, -1, 4505, 4506, 4507, -1, 4505, 4508, 4506, -1, 4509, 4510, 4511, -1, 4509, 4512, 4510, -1, 4509, 4513, 4512, -1, 4514, 4515, 4508, -1, 4514, 4516, 4515, -1, 4517, 4518, 4519, -1, 4517, 4520, 4518, -1, 4521, 4522, 4523, -1, 4521, 4507, 4522, -1, 4524, 4525, 4526, -1, 4524, 4526, 4527, -1, 4528, 4529, 4520, -1, 4528, 4511, 4529, -1, 4530, 4531, 4513, -1, 4530, 4523, 4531, -1, 4532, 4514, 4508, -1, 4532, 4508, 4505, -1, 4533, 4513, 4509, -1, 4534, 266, 256, -1, 4534, 4535, 4516, -1, 4534, 256, 4535, -1, 4534, 4516, 4514, -1, 4536, 4520, 4517, -1, 4536, 4528, 4520, -1, 4537, 4505, 4507, -1, 4537, 4507, 4521, -1, 4504, 250, 249, -1, 4538, 4525, 4524, -1, 4538, 4519, 4525, -1, 4539, 4511, 4528, -1, 4539, 4509, 4511, -1, 256, 255, 1859, -1, 4540, 4523, 4530, -1, 4540, 4521, 4523, -1, 4541, 273, 266, -1, 4541, 4514, 4532, -1, 4541, 266, 4534, -1, 4541, 4534, 4514, -1, 4542, 4530, 4513, -1, 4542, 4513, 4533, -1, 4543, 4539, 4528, -1, 4543, 4528, 4536, -1, 4544, 4505, 4537, -1, 4544, 4532, 4505, -1, 4545, 4517, 4519, -1, 4545, 4519, 4538, -1, 4546, 4533, 4509, -1, 4546, 4509, 4539, -1, 4547, 4537, 4521, -1, 4547, 4521, 4540, -1, 4548, 4530, 4542, -1, 4548, 4540, 4530, -1, 4549, 4546, 4539, -1, 4549, 4539, 4543, -1, 4550, 4532, 4544, -1, 4550, 273, 4541, -1, 4550, 4541, 4532, -1, 4551, 4536, 4517, -1, 4551, 4517, 4545, -1, 4552, 4533, 4546, -1, 4552, 4542, 4533, -1, 4553, 4286, 409, -1, 4554, 4537, 4547, -1, 4554, 4544, 4537, -1, 4553, 409, 228, -1, 4555, 4547, 4540, -1, 4556, 4287, 4286, -1, 4555, 4540, 4548, -1, 4557, 4552, 4546, -1, 4556, 4286, 4553, -1, 4557, 4546, 4549, -1, 4558, 4288, 4287, -1, 4559, 4536, 4551, -1, 4558, 4287, 4556, -1, 4559, 4543, 4536, -1, 4560, 4548, 4542, -1, 4561, 228, 227, -1, 4560, 4542, 4552, -1, 4562, 310, 273, -1, 4561, 4553, 228, -1, 4562, 273, 4550, -1, 4562, 4544, 4554, -1, 4562, 4550, 4544, -1, 4563, 4289, 4288, -1, 4564, 4547, 4555, -1, 4564, 4554, 4547, -1, 4563, 4288, 4558, -1, 4565, 4560, 4552, -1, 4566, 4561, 227, -1, 4565, 4552, 4557, -1, 4567, 4543, 4559, -1, 4568, 4553, 4561, -1, 4567, 4549, 4543, -1, 4568, 4556, 4553, -1, 4569, 4548, 4560, -1, 4570, 4290, 4289, -1, 4569, 4555, 4548, -1, 4571, 310, 4562, -1, 4571, 4562, 4554, -1, 4570, 4289, 4563, -1, 4571, 4554, 4564, -1, 4572, 4569, 4560, -1, 4572, 4560, 4565, -1, 4573, 4561, 4566, -1, 4573, 4568, 4561, -1, 4574, 4557, 4549, -1, 4575, 4558, 4556, -1, 4575, 4556, 4568, -1, 4574, 4549, 4567, -1, 4576, 4564, 4555, -1, 4576, 4555, 4569, -1, 4577, 227, 244, -1, 4578, 4569, 4572, -1, 4578, 4576, 4569, -1, 4577, 4566, 227, -1, 4579, 4565, 4557, -1, 4580, 4291, 4290, -1, 4579, 4557, 4574, -1, 4580, 4290, 4570, -1, 4581, 365, 310, -1, 4581, 310, 4571, -1, 4581, 4571, 4564, -1, 4581, 4564, 4576, -1, 4582, 365, 4581, -1, 4582, 4576, 4578, -1, 4582, 4581, 4576, -1, 4583, 4575, 4568, -1, 4583, 4568, 4573, -1, 4584, 4565, 4579, -1, 4585, 4558, 4575, -1, 4584, 4572, 4565, -1, 4585, 4563, 4558, -1, 4586, 4578, 4572, -1, 4586, 4572, 4584, -1, 4587, 306, 365, -1, 4588, 4573, 4566, -1, 4587, 365, 4582, -1, 4588, 4566, 4577, -1, 4587, 4582, 4578, -1, 4587, 4578, 4586, -1, 4589, 4292, 4291, -1, 4589, 4291, 4580, -1, 4590, 4586, 4591, -1, 4592, 4577, 244, -1, 4590, 4591, 4491, -1, 4593, 4586, 4584, -1, 4593, 4591, 4586, -1, 4593, 4584, 4579, -1, 4594, 4585, 4575, -1, 4594, 4575, 4583, -1, 4595, 4591, 4593, -1, 4596, 4570, 4563, -1, 4597, 4493, 4492, -1, 4596, 4563, 4585, -1, 4597, 4492, 4491, -1, 4597, 4491, 4591, -1, 4597, 4591, 4595, -1, 4598, 306, 4587, -1, 4598, 4587, 4586, -1, 4598, 4586, 4590, -1, 4599, 308, 306, -1, 4600, 4573, 4588, -1, 4599, 4598, 4590, -1, 4599, 306, 4598, -1, 4600, 4583, 4573, -1, 4601, 308, 4599, -1, 4601, 4599, 4590, -1, 4601, 4491, 4490, -1, 4601, 4490, 308, -1, 4601, 4590, 4491, -1, 4602, 1823, 4292, -1, 4603, 4579, 4574, -1, 4602, 4292, 4589, -1, 4603, 4593, 4579, -1, 4603, 4595, 4593, -1, 4604, 4577, 4592, -1, 4605, 4595, 4603, -1, 4604, 4588, 4577, -1, 4606, 4596, 4585, -1, 4607, 4494, 4493, -1, 4607, 4597, 4595, -1, 4606, 4585, 4594, -1, 4607, 4493, 4597, -1, 4607, 4595, 4605, -1, 4608, 4603, 4574, -1, 4609, 244, 276, -1, 4608, 4574, 4567, -1, 4608, 4605, 4603, -1, 4609, 4592, 244, -1, 4610, 4605, 4608, -1, 4611, 4570, 4596, -1, 4612, 4605, 4610, -1, 4612, 4607, 4605, -1, 4611, 4580, 4570, -1, 4612, 4494, 4607, -1, 4612, 4495, 4494, -1, 4613, 4608, 4567, -1, 4613, 4567, 4559, -1, 4614, 4583, 4600, -1, 4613, 4610, 4608, -1, 4614, 4594, 4583, -1, 4615, 4610, 4613, -1, 4616, 1824, 1823, -1, 4617, 4612, 4610, -1, 4617, 4610, 4615, -1, 4617, 4495, 4612, -1, 4616, 1823, 4602, -1, 4617, 4496, 4495, -1, 4618, 4559, 4551, -1, 4618, 4615, 4613, -1, 4618, 4613, 4559, -1, 4619, 4600, 4588, -1, 4619, 4588, 4604, -1, 4620, 4596, 4606, -1, 4621, 4615, 4618, -1, 4622, 4615, 4621, -1, 4622, 4617, 4615, -1, 4622, 4496, 4617, -1, 4620, 4611, 4596, -1, 4622, 4497, 4496, -1, 4623, 4621, 4618, -1, 4623, 4551, 4545, -1, 4623, 4618, 4551, -1, 4624, 4592, 4609, -1, 4624, 4604, 4592, -1, 4625, 4622, 4621, -1, 4625, 4498, 4497, -1, 4625, 4621, 4623, -1, 4626, 4580, 4611, -1, 4625, 4497, 4622, -1, 4626, 4589, 4580, -1, 4627, 4623, 4545, -1, 4628, 4606, 4594, -1, 4627, 4545, 4538, -1, 4629, 4623, 4627, -1, 4628, 4594, 4614, -1, 4630, 4623, 4629, -1, 4631, 1826, 1824, -1, 4632, 4623, 4630, -1, 4632, 4625, 4623, -1, 4631, 1824, 4616, -1, 4633, 4499, 4498, -1, 4633, 4498, 4625, -1, 4633, 4632, 4630, -1, 4633, 4625, 4632, -1, 4634, 4609, 276, -1, 4635, 4629, 4627, -1, 4635, 4627, 4538, -1, 4635, 4538, 4524, -1, 4636, 4614, 4600, -1, 4637, 4500, 4499, -1, 4636, 4600, 4619, -1, 4637, 4630, 4629, -1, 4637, 4499, 4633, -1, 4637, 4629, 4635, -1, 4637, 4633, 4630, -1, 4638, 4524, 4527, -1, 4639, 4611, 4620, -1, 4638, 4635, 4524, -1, 4639, 4626, 4611, -1, 4638, 4637, 4635, -1, 4640, 4619, 4604, -1, 4641, 4637, 4638, -1, 4640, 4604, 4624, -1, 4642, 4501, 4500, -1, 4642, 4500, 4637, -1, 4642, 4637, 4641, -1, 4643, 4602, 4589, -1, 4644, 4645, 4646, -1, 4643, 4589, 4626, -1, 4644, 4638, 4527, -1, 4644, 4503, 4502, -1, 4644, 4646, 4503, -1, 4644, 4527, 4645, -1, 4644, 4641, 4638, -1, 4647, 276, 250, -1, 4648, 4502, 4501, -1, 4648, 4501, 4642, -1, 4648, 4642, 4641, -1, 4648, 4644, 4502, -1, 4647, 4634, 276, -1, 4648, 4641, 4644, -1, 4649, 4620, 4606, -1, 4649, 4606, 4628, -1, 4650, 1832, 1826, -1, 4650, 1826, 4631, -1, 4651, 4624, 4609, -1, 4651, 4609, 4634, -1, 4652, 4614, 4636, -1, 4652, 4628, 4614, -1, 4653, 4643, 4626, -1, 4653, 4626, 4639, -1, 4654, 4636, 4619, -1, 4654, 4619, 4640, -1, 4655, 4602, 4643, -1, 4655, 4616, 4602, -1, 4656, 4634, 4647, -1, 4656, 4651, 4634, -1, 4657, 4639, 4620, -1, 4657, 4620, 4649, -1, 4658, 1837, 1832, -1, 4658, 1832, 4650, -1, 4659, 4624, 4651, -1, 4659, 4640, 4624, -1, 4660, 4649, 4628, -1, 4660, 4628, 4652, -1, 4661, 4643, 4653, -1, 4661, 4655, 4643, -1, 4662, 4636, 4654, -1, 4662, 4652, 4636, -1, 4663, 4616, 4655, -1, 4663, 4631, 4616, -1, 4664, 4651, 4656, -1, 4664, 4659, 4651, -1, 4665, 4653, 4639, -1, 4665, 4639, 4657, -1, 4666, 4647, 250, -1, 4666, 250, 4504, -1, 4515, 1840, 1837, -1, 4515, 1837, 4658, -1, 4667, 4640, 4659, -1, 4667, 4654, 4640, -1, 4668, 4657, 4649, -1, 4668, 4649, 4660, -1, 4669, 4655, 4661, -1, 4669, 4663, 4655, -1, 4670, 4660, 4652, -1, 4670, 4652, 4662, -1, 4671, 4650, 4631, -1, 4671, 4631, 4663, -1, 4526, 4667, 4659, -1, 4526, 4659, 4664, -1, 4672, 4653, 4665, -1, 4672, 4661, 4653, -1, 4646, 4666, 4504, -1, 4646, 4504, 4503, -1, 4646, 4656, 4647, -1, 4646, 4647, 4666, -1, 4516, 1846, 1840, -1, 4516, 1840, 4515, -1, 4673, 4654, 4667, -1, 4673, 4662, 4654, -1, 4510, 4657, 4668, -1, 4510, 4665, 4657, -1, 4522, 4663, 4669, -1, 4522, 4671, 4663, -1, 4529, 4668, 4660, -1, 4529, 4660, 4670, -1, 4506, 4650, 4671, -1, 4506, 4658, 4650, -1, 4525, 4667, 4526, -1, 4525, 4673, 4667, -1, 4531, 4669, 4661, -1, 4531, 4661, 4672, -1, 4645, 4664, 4656, -1, 4645, 4656, 4646, -1, 4535, 1859, 1846, -1, 4535, 256, 1859, -1, 4535, 1846, 4516, -1, 4518, 4670, 4662, -1, 4518, 4662, 4673, -1, 4512, 4672, 4665, -1, 4512, 4665, 4510, -1, 4512, 4531, 4672, -1, 4507, 4671, 4522, -1, 4507, 4506, 4671, -1, 4511, 4510, 4668, -1, 4511, 4668, 4529, -1, 4508, 4658, 4506, -1, 4508, 4515, 4658, -1, 4519, 4673, 4525, -1, 4519, 4518, 4673, -1, 4523, 4669, 4531, -1, 4523, 4522, 4669, -1, 4527, 4526, 4664, -1, 4527, 4664, 4645, -1, 4520, 4670, 4518, -1, 4520, 4529, 4670, -1, 4513, 4531, 4512, -1, 3000, 2378, 2922, -1, 3000, 2379, 2378, -1, 3004, 2921, 2869, -1, 3004, 2869, 3010, -1, 2868, 2999, 3013, -1, 2868, 3013, 2870, -1, 2376, 3567, 3437, -1, 2376, 3437, 2374, -1, 3477, 3556, 3553, -1, 3477, 3553, 3440, -1, 3564, 3559, 3439, -1, 3438, 3564, 3439, -1, 3000, 2922, 3004, -1, 3004, 2922, 2921, -1, 3010, 2869, 3013, -1, 3013, 2869, 2870, -1, 3564, 3438, 3567, -1, 3567, 3438, 3437, -1, 3556, 3477, 3559, -1, 3559, 3477, 3439, -1, 2280, 2279, 4674, -1, 2280, 4674, 4675, -1, 4675, 2153, 2280, -1, 4674, 2153, 4675, -1, 2279, 2153, 4674, -1, 2304, 2297, 4676, -1, 4676, 2297, 4677, -1, 4676, 2187, 2304, -1, 4677, 2187, 4676, -1, 2297, 2187, 4677, -1, 2179, 2177, 2181, -1, 2181, 2185, 2183, -1, 2353, 2352, 2354, -1, 2350, 2348, 2352, -1, 2199, 2203, 2201, -1, 2197, 2203, 2199, -1, 2195, 2203, 2197, -1, 2192, 2203, 2195, -1, 2190, 2203, 2192, -1, 2188, 2203, 2190, -1, 2185, 2203, 2188, -1, 2175, 2203, 2177, -1, 2172, 2203, 2175, -1, 2355, 2203, 2172, -1, 2354, 2203, 2355, -1, 2177, 2203, 2181, -1, 2181, 2203, 2185, -1, 2352, 2203, 2354, -1, 2348, 2203, 2352, -1, 2348, 2345, 2203, -1, 2345, 2344, 2203, -1, 2203, 2340, 2339, -1, 2344, 2343, 2203, -1, 2203, 2341, 2340, -1, 2343, 2342, 2203, -1, 2203, 2342, 2341, -1, 2357, 2356, 2358, -1, 2360, 2362, 2361, -1, 2359, 2362, 2360, -1, 2169, 2167, 2356, -1, 2362, 2367, 2365, -1, 2359, 2367, 2362, -1, 2165, 2163, 2167, -1, 2167, 2163, 2356, -1, 2356, 2163, 2358, -1, 2367, 2370, 2369, -1, 2358, 2371, 2359, -1, 2359, 2371, 2367, -1, 2163, 2371, 2358, -1, 2367, 2371, 2370, -1, 2161, 2154, 2163, -1, 2158, 2154, 2161, -1, 2156, 2154, 2158, -1, 2371, 2138, 2372, -1, 2138, 2143, 2141, -1, 2163, 2143, 2371, -1, 2371, 2143, 2138, -1, 2151, 2149, 2154, -1, 2154, 2145, 2163, -1, 2149, 2145, 2154, -1, 2163, 2145, 2143, -1, 2149, 2147, 2145, -1, 2290, 2292, 2215, -1, 2215, 2292, 2213, -1, 2292, 2293, 2213, -1, 2213, 2293, 1688, -1, 2293, 1689, 1688, -1, 1687, 2363, 1685, -1, 1685, 2363, 2330, -1, 2330, 2364, 2327, -1, 2363, 2364, 2330, -1, 2327, 2366, 2338, -1, 2364, 2366, 2327, -1, 2338, 2368, 2336, -1, 2366, 2368, 2338, -1, 2336, 2246, 2335, -1, 2368, 2246, 2336, -1, 2335, 2244, 2334, -1, 2246, 2244, 2335, -1, 2334, 2242, 2332, -1, 2244, 2242, 2334, -1, 2332, 2241, 2329, -1, 2242, 2241, 2332, -1, 2329, 2238, 2235, -1, 2241, 2238, 2329, -1, 2235, 2237, 2226, -1, 2238, 2237, 2235, -1, 2226, 2281, 2224, -1, 2237, 2281, 2226, -1, 2224, 2282, 2222, -1, 2281, 2282, 2224, -1, 2222, 2284, 2220, -1, 2282, 2284, 2222, -1, 2220, 2286, 2218, -1, 2284, 2286, 2220, -1, 2286, 2288, 2218, -1, 2218, 2288, 2216, -1, 2288, 2290, 2216, -1, 2216, 2290, 2215, -1, 2298, 2296, 2211, -1, 2211, 2296, 2212, -1, 2296, 2295, 2212, -1, 2212, 2295, 1649, -1, 2295, 1650, 1649, -1, 1648, 2346, 1646, -1, 1646, 2346, 2311, -1, 2311, 2347, 2312, -1, 2346, 2347, 2311, -1, 2312, 2349, 2313, -1, 2347, 2349, 2312, -1, 2313, 2351, 2314, -1, 2349, 2351, 2313, -1, 2314, 2259, 2315, -1, 2351, 2259, 2314, -1, 2315, 2258, 2316, -1, 2259, 2258, 2315, -1, 2316, 2257, 2317, -1, 2258, 2257, 2316, -1, 2317, 2256, 2318, -1, 2257, 2256, 2317, -1, 2318, 2255, 2233, -1, 2256, 2255, 2318, -1, 2233, 2254, 2208, -1, 2255, 2254, 2233, -1, 2208, 2303, 2207, -1, 2254, 2303, 2208, -1, 2207, 2302, 2205, -1, 2303, 2302, 2207, -1, 2205, 2301, 2206, -1, 2302, 2301, 2205, -1, 2206, 2300, 2209, -1, 2301, 2300, 2206, -1, 2300, 2299, 2209, -1, 2209, 2299, 2210, -1, 2299, 2298, 2210, -1, 2210, 2298, 2211, -1, 4678, 4679, 4680, -1, 4680, 4679, 4681, -1, 4682, 4683, 4684, -1, 4685, 4683, 4682, -1, 4686, 4687, 4688, -1, 4689, 4687, 4690, -1, 4688, 4687, 4689, -1, 4690, 4687, 4691, -1, 4692, 4693, 4694, -1, 4695, 4693, 4692, -1, 4681, 4696, 4697, -1, 4697, 4696, 4695, -1, 4691, 4698, 4678, -1, 4678, 4698, 4679, -1, 4699, 4700, 4685, -1, 4685, 4700, 4683, -1, 4695, 4701, 4693, -1, 4696, 4701, 4695, -1, 4679, 4702, 4681, -1, 4681, 4702, 4696, -1, 4686, 4703, 4687, -1, 4687, 4703, 4691, -1, 4691, 4703, 4698, -1, 4694, 4704, 4699, -1, 4699, 4704, 4700, -1, 4696, 4705, 4701, -1, 4702, 4705, 4696, -1, 4679, 4706, 4702, -1, 4698, 4706, 4679, -1, 4693, 4707, 4694, -1, 4694, 4707, 4704, -1, 4706, 4708, 4702, -1, 4702, 4708, 4705, -1, 4698, 4709, 4706, -1, 4710, 4709, 4686, -1, 4711, 4712, 4713, -1, 4686, 4709, 4703, -1, 4703, 4709, 4698, -1, 4693, 4714, 4707, -1, 4701, 4714, 4693, -1, 4709, 4715, 4706, -1, 4710, 4715, 4709, -1, 4706, 4715, 4708, -1, 4701, 4716, 4714, -1, 4705, 4716, 4701, -1, 4705, 4717, 4716, -1, 4708, 4717, 4705, -1, 4708, 4718, 4717, -1, 4715, 4718, 4708, -1, 4710, 4718, 4715, -1, 4719, 4718, 4710, -1, 4717, 4720, 4716, -1, 4721, 4722, 4720, -1, 4723, 4724, 4725, -1, 4721, 4724, 4722, -1, 4719, 4726, 4718, -1, 4726, 4727, 4721, -1, 4728, 4727, 4719, -1, 4719, 4727, 4726, -1, 4729, 4730, 4728, -1, 4727, 4730, 4721, -1, 4728, 4730, 4727, -1, 4716, 4731, 4714, -1, 4720, 4731, 4716, -1, 4722, 4731, 4720, -1, 4732, 4733, 4734, -1, 4734, 4733, 4735, -1, 4722, 4736, 4731, -1, 4737, 4738, 4723, -1, 4739, 4740, 4732, -1, 4723, 4738, 4724, -1, 4724, 4738, 4722, -1, 4732, 4740, 4733, -1, 4722, 4738, 4736, -1, 4718, 4741, 4717, -1, 4721, 4741, 4726, -1, 4717, 4741, 4720, -1, 4720, 4741, 4721, -1, 4726, 4741, 4718, -1, 4725, 4742, 4729, -1, 4743, 4744, 4739, -1, 4729, 4742, 4730, -1, 4721, 4742, 4724, -1, 4739, 4744, 4740, -1, 4724, 4742, 4725, -1, 4730, 4742, 4721, -1, 4714, 4745, 4707, -1, 4731, 4745, 4714, -1, 4735, 4746, 4747, -1, 4736, 4745, 4731, -1, 4733, 4746, 4735, -1, 4736, 4748, 4745, -1, 4749, 4750, 4743, -1, 4751, 4752, 4737, -1, 4737, 4752, 4738, -1, 4738, 4752, 4736, -1, 4736, 4752, 4748, -1, 4707, 4753, 4704, -1, 4743, 4750, 4744, -1, 4745, 4753, 4707, -1, 4748, 4753, 4745, -1, 4746, 4754, 4747, -1, 4740, 4755, 4733, -1, 4748, 4756, 4753, -1, 4733, 4755, 4746, -1, 4757, 4758, 4751, -1, 4751, 4758, 4752, -1, 4752, 4758, 4748, -1, 4748, 4758, 4756, -1, 4759, 4760, 4749, -1, 4749, 4760, 4750, -1, 4756, 4761, 4753, -1, 4753, 4761, 4704, -1, 4704, 4761, 4700, -1, 4762, 4763, 4757, -1, 4755, 4764, 4746, -1, 4757, 4763, 4758, -1, 4746, 4764, 4754, -1, 4758, 4763, 4756, -1, 4761, 4765, 4700, -1, 4700, 4765, 4683, -1, 4740, 4766, 4755, -1, 4744, 4766, 4740, -1, 4767, 4768, 4759, -1, 4759, 4768, 4760, -1, 4761, 4769, 4765, -1, 4761, 4770, 4769, -1, 4756, 4771, 4761, -1, 4747, 4772, 4773, -1, 4763, 4771, 4756, -1, 4761, 4771, 4770, -1, 4754, 4772, 4747, -1, 4774, 4775, 4762, -1, 4762, 4775, 4763, -1, 4763, 4775, 4771, -1, 4771, 4775, 4770, -1, 4766, 4776, 4755, -1, 4769, 4777, 4765, -1, 4765, 4777, 4683, -1, 4683, 4777, 4684, -1, 4755, 4776, 4764, -1, 4775, 4778, 4770, -1, 4750, 4779, 4744, -1, 4744, 4779, 4766, -1, 4774, 4778, 4775, -1, 4770, 4778, 4769, -1, 4780, 4781, 4767, -1, 4777, 4782, 4684, -1, 4684, 4782, 4783, -1, 4767, 4781, 4768, -1, 4782, 4784, 4785, -1, 4777, 4784, 4782, -1, 4785, 4784, 4778, -1, 4764, 4786, 4754, -1, 4769, 4784, 4777, -1, 4754, 4786, 4772, -1, 4778, 4784, 4769, -1, 4778, 4787, 4785, -1, 4779, 4788, 4766, -1, 4766, 4788, 4776, -1, 4774, 4789, 4778, -1, 4778, 4789, 4787, -1, 4750, 4790, 4779, -1, 4791, 4789, 4774, -1, 4792, 4789, 4791, -1, 4785, 4793, 4782, -1, 4760, 4790, 4750, -1, 4787, 4793, 4785, -1, 4780, 4794, 4781, -1, 4782, 4793, 4783, -1, 4789, 4795, 4787, -1, 4792, 4795, 4789, -1, 4796, 4795, 4792, -1, 4797, 4794, 4780, -1, 4798, 4799, 4800, -1, 4793, 4799, 4783, -1, 4783, 4799, 4798, -1, 4772, 4801, 4773, -1, 4793, 4802, 4799, -1, 4764, 4803, 4786, -1, 4712, 4802, 4804, -1, 4799, 4802, 4800, -1, 4800, 4802, 4805, -1, 4805, 4802, 4712, -1, 4802, 4806, 4804, -1, 4776, 4803, 4764, -1, 4793, 4806, 4802, -1, 4795, 4807, 4787, -1, 4787, 4807, 4793, -1, 4779, 4808, 4788, -1, 4793, 4807, 4806, -1, 4804, 4809, 4796, -1, 4790, 4808, 4779, -1, 4796, 4809, 4795, -1, 4795, 4809, 4807, -1, 4806, 4809, 4804, -1, 4807, 4809, 4806, -1, 4760, 4810, 4790, -1, 4768, 4810, 4760, -1, 4797, 4811, 4794, -1, 4812, 4811, 4797, -1, 4786, 4813, 4772, -1, 4772, 4813, 4801, -1, 4801, 4814, 4773, -1, 4773, 4814, 4815, -1, 4776, 4816, 4803, -1, 4788, 4816, 4776, -1, 4810, 4817, 4790, -1, 4790, 4817, 4808, -1, 4768, 4818, 4810, -1, 4781, 4818, 4768, -1, 4819, 4820, 4812, -1, 4812, 4820, 4811, -1, 4786, 4821, 4813, -1, 4803, 4821, 4786, -1, 4813, 4822, 4801, -1, 4801, 4822, 4814, -1, 4808, 4823, 4788, -1, 4788, 4823, 4816, -1, 4810, 4824, 4817, -1, 4818, 4824, 4810, -1, 4794, 4825, 4781, -1, 4781, 4825, 4818, -1, 4826, 4827, 4819, -1, 4819, 4827, 4820, -1, 4816, 4828, 4803, -1, 4803, 4828, 4821, -1, 4814, 4829, 4815, -1, 4821, 4830, 4813, -1, 4813, 4830, 4822, -1, 4817, 4831, 4808, -1, 4808, 4831, 4823, -1, 4818, 4832, 4824, -1, 4825, 4832, 4818, -1, 4811, 4833, 4794, -1, 4794, 4833, 4825, -1, 4826, 4834, 4827, -1, 4835, 4834, 4826, -1, 4823, 4836, 4816, -1, 4816, 4836, 4828, -1, 4815, 4837, 4711, -1, 4829, 4837, 4815, -1, 4822, 4838, 4814, -1, 4814, 4838, 4829, -1, 4821, 4839, 4830, -1, 4828, 4839, 4821, -1, 4824, 4840, 4817, -1, 4817, 4840, 4831, -1, 4833, 4841, 4825, -1, 4825, 4841, 4832, -1, 4820, 4842, 4811, -1, 4811, 4842, 4833, -1, 4835, 4843, 4834, -1, 4844, 4843, 4845, -1, 4845, 4843, 4846, -1, 4846, 4843, 4835, -1, 4823, 4847, 4836, -1, 4831, 4847, 4823, -1, 4838, 4848, 4829, -1, 4829, 4848, 4837, -1, 4822, 4849, 4838, -1, 4830, 4849, 4822, -1, 4828, 4850, 4839, -1, 4836, 4850, 4828, -1, 4824, 4851, 4840, -1, 4832, 4851, 4824, -1, 4842, 4852, 4833, -1, 4833, 4852, 4841, -1, 4820, 4853, 4842, -1, 4827, 4853, 4820, -1, 4831, 4854, 4847, -1, 4840, 4854, 4831, -1, 4849, 4855, 4838, -1, 4838, 4855, 4848, -1, 4830, 4856, 4849, -1, 4839, 4856, 4830, -1, 4836, 4857, 4850, -1, 4847, 4857, 4836, -1, 4711, 4805, 4712, -1, 4837, 4805, 4711, -1, 4832, 4858, 4851, -1, 4841, 4858, 4832, -1, 4853, 4859, 4842, -1, 4842, 4859, 4852, -1, 4834, 4860, 4827, -1, 4827, 4860, 4853, -1, 4851, 4861, 4840, -1, 4840, 4861, 4854, -1, 4849, 4862, 4855, -1, 4856, 4862, 4849, -1, 4850, 4863, 4839, -1, 4839, 4863, 4856, -1, 4854, 4864, 4847, -1, 4847, 4864, 4857, -1, 4837, 4800, 4805, -1, 4848, 4800, 4837, -1, 4852, 4865, 4841, -1, 4841, 4865, 4858, -1, 4853, 4866, 4859, -1, 4860, 4866, 4853, -1, 4867, 4868, 4844, -1, 4834, 4868, 4860, -1, 4843, 4868, 4834, -1, 4844, 4868, 4843, -1, 4858, 4869, 4851, -1, 4851, 4869, 4861, -1, 4856, 4682, 4862, -1, 4863, 4682, 4856, -1, 4857, 4870, 4850, -1, 4850, 4870, 4863, -1, 4854, 4871, 4864, -1, 4861, 4871, 4854, -1, 4855, 4798, 4848, -1, 4848, 4798, 4800, -1, 4859, 4872, 4852, -1, 4852, 4872, 4865, -1, 4688, 4873, 4867, -1, 4867, 4873, 4868, -1, 4860, 4873, 4866, -1, 4868, 4873, 4860, -1, 4865, 4680, 4858, -1, 4858, 4680, 4869, -1, 4870, 4685, 4863, -1, 4863, 4685, 4682, -1, 4857, 4874, 4870, -1, 4864, 4874, 4857, -1, 4869, 4697, 4861, -1, 4861, 4697, 4871, -1, 4855, 4783, 4798, -1, 4862, 4783, 4855, -1, 4859, 4690, 4872, -1, 4866, 4690, 4859, -1, 4865, 4678, 4680, -1, 4872, 4678, 4865, -1, 4874, 4699, 4870, -1, 4870, 4699, 4685, -1, 4864, 4692, 4874, -1, 4871, 4692, 4864, -1, 4869, 4681, 4697, -1, 4680, 4681, 4869, -1, 4862, 4684, 4783, -1, 4682, 4684, 4862, -1, 4873, 4689, 4866, -1, 4866, 4689, 4690, -1, 4688, 4689, 4873, -1, 4872, 4691, 4678, -1, 4690, 4691, 4872, -1, 4874, 4694, 4699, -1, 4692, 4694, 4874, -1, 4697, 4695, 4871, -1, 4871, 4695, 4692, -1, 4875, 4876, 4877, -1, 4878, 4879, 4880, -1, 4878, 4881, 4879, -1, 4882, 4883, 4884, -1, 4885, 4886, 4887, -1, 4885, 4888, 4886, -1, 4889, 4890, 4891, -1, 4889, 4891, 4892, -1, 4893, 4894, 4883, -1, 4893, 4877, 4894, -1, 4895, 4896, 4897, -1, 4895, 4887, 4896, -1, 4898, 4878, 4880, -1, 4898, 4880, 4899, -1, 4900, 4897, 4876, -1, 4900, 4876, 4875, -1, 4901, 4902, 4881, -1, 4901, 4903, 4904, -1, 4901, 4881, 4878, -1, 4901, 4904, 4902, -1, 4905, 4893, 4883, -1, 4905, 4883, 4882, -1, 4906, 4899, 4888, -1, 4906, 4888, 4885, -1, 4907, 4884, 4890, -1, 4907, 4890, 4889, -1, 4908, 4875, 4877, -1, 4908, 4877, 4893, -1, 4908, 4893, 4905, -1, 4909, 4887, 4895, -1, 4909, 4885, 4887, -1, 4910, 4878, 4898, -1, 4910, 4903, 4901, -1, 4910, 4901, 4878, -1, 4911, 4897, 4900, -1, 4911, 4895, 4897, -1, 4912, 4908, 4905, -1, 4913, 4898, 4899, -1, 4913, 4899, 4906, -1, 4914, 4882, 4884, -1, 4914, 4884, 4907, -1, 4915, 4900, 4875, -1, 4915, 4875, 4908, -1, 4916, 4906, 4885, -1, 4916, 4885, 4909, -1, 4917, 4909, 4895, -1, 4917, 4895, 4911, -1, 4918, 4915, 4908, -1, 4918, 4908, 4912, -1, 4919, 4920, 4903, -1, 4919, 4903, 4910, -1, 4919, 4898, 4913, -1, 4919, 4910, 4898, -1, 4921, 4882, 4914, -1, 4921, 4905, 4882, -1, 4922, 4911, 4900, -1, 4922, 4900, 4915, -1, 4923, 4913, 4906, -1, 4924, 4925, 4926, -1, 4927, 4928, 4929, -1, 4923, 4906, 4916, -1, 4930, 4916, 4909, -1, 4930, 4923, 4916, -1, 4927, 4929, 4931, -1, 4930, 4909, 4917, -1, 4932, 4915, 4918, -1, 4933, 4934, 4928, -1, 4932, 4922, 4915, -1, 4933, 4928, 4927, -1, 4935, 4905, 4921, -1, 4936, 4937, 4934, -1, 4935, 4912, 4905, -1, 4938, 4917, 4911, -1, 4938, 4911, 4922, -1, 4936, 4934, 4933, -1, 4939, 4919, 4913, -1, 4940, 4931, 4941, -1, 4939, 4913, 4923, -1, 4939, 4920, 4919, -1, 4940, 4927, 4931, -1, 4942, 4943, 4937, -1, 4944, 4923, 4930, -1, 4942, 4937, 4936, -1, 4945, 4938, 4922, -1, 4945, 4922, 4932, -1, 4946, 4918, 4912, -1, 4947, 4941, 4948, -1, 4946, 4912, 4935, -1, 4947, 4940, 4941, -1, 4949, 4933, 4927, -1, 4950, 4917, 4938, -1, 4950, 4930, 4917, -1, 4951, 4939, 4923, -1, 4951, 4952, 4920, -1, 4949, 4927, 4940, -1, 4953, 4954, 4943, -1, 4951, 4920, 4939, -1, 4951, 4923, 4944, -1, 4955, 4950, 4938, -1, 4953, 4943, 4942, -1, 4955, 4938, 4945, -1, 4956, 4932, 4918, -1, 4957, 4940, 4947, -1, 4956, 4918, 4946, -1, 4957, 4949, 4940, -1, 4958, 4944, 4930, -1, 4958, 4950, 4955, -1, 4958, 4930, 4950, -1, 4959, 4936, 4933, -1, 4959, 4933, 4949, -1, 4960, 4958, 4955, -1, 4961, 4947, 4948, -1, 4962, 4963, 4954, -1, 4964, 4945, 4932, -1, 4964, 4932, 4956, -1, 4965, 4952, 4951, -1, 4965, 4944, 4958, -1, 4962, 4954, 4953, -1, 4965, 4951, 4944, -1, 4966, 4949, 4957, -1, 4967, 4925, 4952, -1, 4967, 4952, 4965, -1, 4967, 4958, 4960, -1, 4967, 4965, 4958, -1, 4968, 4945, 4964, -1, 4966, 4959, 4949, -1, 4968, 4955, 4945, -1, 4969, 4942, 4936, -1, 4970, 4960, 4955, -1, 4969, 4936, 4959, -1, 4970, 4955, 4968, -1, 4971, 4972, 4926, -1, 4973, 4957, 4947, -1, 4971, 4926, 4925, -1, 4971, 4967, 4960, -1, 4971, 4925, 4967, -1, 4971, 4970, 4972, -1, 4971, 4960, 4970, -1, 4973, 4947, 4961, -1, 4974, 4975, 4963, -1, 4974, 4963, 4962, -1, 4976, 4977, 4978, -1, 4976, 4979, 4977, -1, 4980, 4948, 4981, -1, 4982, 4983, 4984, -1, 4982, 4979, 4983, -1, 4980, 4961, 4948, -1, 4982, 4977, 4979, -1, 4985, 4984, 4986, -1, 4987, 4959, 4966, -1, 4985, 4982, 4984, -1, 4985, 4977, 4982, -1, 4988, 4986, 4989, -1, 4988, 4989, 4978, -1, 4988, 4985, 4986, -1, 4987, 4969, 4959, -1, 4988, 4978, 4977, -1, 4988, 4977, 4985, -1, 4990, 4979, 4976, -1, 4990, 4991, 4979, -1, 4992, 4953, 4942, -1, 4990, 4892, 4991, -1, 4992, 4942, 4969, -1, 4993, 4957, 4973, -1, 4994, 4990, 4976, -1, 4995, 4994, 4976, -1, 4995, 4976, 4978, -1, 4995, 4978, 4996, -1, 4995, 4996, 4997, -1, 4993, 4966, 4957, -1, 4998, 4892, 4990, -1, 4999, 5000, 4975, -1, 4998, 4889, 4892, -1, 4998, 4990, 4994, -1, 4999, 4975, 4974, -1, 5001, 4998, 4994, -1, 5002, 4961, 4980, -1, 5003, 4994, 4995, -1, 5003, 4995, 4997, -1, 5003, 5001, 4994, -1, 5002, 4973, 4961, -1, 5003, 4997, 5004, -1, 5005, 4998, 5001, -1, 5005, 4889, 4998, -1, 5005, 4907, 4889, -1, 5006, 4969, 4987, -1, 5007, 5005, 5001, -1, 5006, 4992, 4969, -1, 5008, 4980, 4981, -1, 5009, 5001, 5003, -1, 5009, 5003, 5004, -1, 5010, 4953, 4992, -1, 5009, 5004, 5011, -1, 5010, 4962, 4953, -1, 5009, 5007, 5001, -1, 5012, 5005, 5007, -1, 5012, 4907, 5005, -1, 5012, 4914, 4907, -1, 5013, 4966, 4993, -1, 5014, 5012, 5007, -1, 5015, 5009, 5011, -1, 5013, 4987, 4966, -1, 5015, 5011, 5016, -1, 5017, 5000, 4999, -1, 5015, 5007, 5009, -1, 5015, 5014, 5007, -1, 5017, 5018, 5000, -1, 5019, 4921, 4914, -1, 5019, 4914, 5012, -1, 5019, 5012, 5014, -1, 5020, 5019, 5014, -1, 5021, 4993, 4973, -1, 5022, 5016, 5023, -1, 5021, 4973, 5002, -1, 5022, 5020, 5014, -1, 5022, 5014, 5015, -1, 5022, 5015, 5016, -1, 5024, 4921, 5019, -1, 5025, 5010, 4992, -1, 5024, 5019, 5020, -1, 5025, 4992, 5006, -1, 5024, 4935, 4921, -1, 5026, 5023, 5027, -1, 5026, 5022, 5023, -1, 5026, 5020, 5022, -1, 5028, 4980, 5008, -1, 5026, 5024, 5020, -1, 5028, 5002, 4980, -1, 5029, 4946, 4935, -1, 5029, 4935, 5024, -1, 5030, 4962, 5010, -1, 5030, 4974, 4962, -1, 5031, 5024, 5026, -1, 5031, 5029, 5024, -1, 5032, 5031, 5026, -1, 5033, 4987, 5013, -1, 5032, 5029, 5031, -1, 5033, 5006, 4987, -1, 5034, 5018, 5017, -1, 5034, 5035, 5018, -1, 5036, 5032, 5026, -1, 5037, 5026, 5027, -1, 5037, 5027, 5038, -1, 5037, 5036, 5026, -1, 5039, 4981, 5040, -1, 5041, 4956, 4946, -1, 5041, 4946, 5029, -1, 5039, 5008, 4981, -1, 5041, 5029, 5032, -1, 5041, 5032, 5036, -1, 5042, 5013, 4993, -1, 5043, 5038, 5044, -1, 5043, 5037, 5038, -1, 5043, 5036, 5037, -1, 5043, 5041, 5036, -1, 5042, 4993, 5021, -1, 5045, 4956, 5041, -1, 5045, 4964, 4956, -1, 5046, 5010, 5025, -1, 5046, 5030, 5010, -1, 5047, 5045, 5041, -1, 5048, 5044, 5049, -1, 5048, 5043, 5044, -1, 5048, 5041, 5043, -1, 5050, 5021, 5002, -1, 5048, 5047, 5041, -1, 5050, 5002, 5028, -1, 5051, 4968, 4964, -1, 5051, 4964, 5045, -1, 5052, 4999, 4974, -1, 5051, 5045, 5047, -1, 5053, 5049, 5054, -1, 5053, 5054, 4972, -1, 5053, 5048, 5049, -1, 5052, 4974, 5030, -1, 5053, 4970, 4968, -1, 5053, 4968, 5051, -1, 5053, 4972, 4970, -1, 5055, 5039, 5040, -1, 5053, 5047, 5048, -1, 5053, 5051, 5047, -1, 5056, 5025, 5006, -1, 5056, 5006, 5033, -1, 5057, 5035, 5034, -1, 5057, 5058, 5035, -1, 5059, 5028, 5008, -1, 5059, 5008, 5039, -1, 5060, 5013, 5042, -1, 5060, 5033, 5013, -1, 5061, 5030, 5046, -1, 5061, 5052, 5030, -1, 5062, 5042, 5021, -1, 5062, 5021, 5050, -1, 5063, 5017, 4999, -1, 5063, 4999, 5052, -1, 5064, 5039, 5055, -1, 5064, 5059, 5039, -1, 5065, 5025, 5056, -1, 5065, 5046, 5025, -1, 5066, 5067, 5058, -1, 5066, 5058, 5057, -1, 5068, 5028, 5059, -1, 5068, 5050, 5028, -1, 5069, 5033, 5060, -1, 5069, 5056, 5033, -1, 5070, 5052, 5061, -1, 5070, 5063, 5052, -1, 5071, 5042, 5062, -1, 5071, 5060, 5042, -1, 5072, 5017, 5063, -1, 5072, 5034, 5017, -1, 5073, 5068, 5059, -1, 5073, 5059, 5064, -1, 5074, 5061, 5046, -1, 5074, 5046, 5065, -1, 4983, 5040, 4984, -1, 4983, 5055, 5040, -1, 4879, 5075, 5067, -1, 4879, 5067, 5066, -1, 5076, 5062, 5050, -1, 5076, 5050, 5068, -1, 5077, 5056, 5069, -1, 5077, 5065, 5056, -1, 5078, 5063, 5070, -1, 5078, 5072, 5063, -1, 5079, 5060, 5071, -1, 5079, 5077, 5069, -1, 5079, 5069, 5060, -1, 5080, 5034, 5072, -1, 5080, 5057, 5034, -1, 4891, 5068, 5073, -1, 4891, 5076, 5068, -1, 5081, 5070, 5061, -1, 5081, 5061, 5074, -1, 4979, 5064, 5055, -1, 4979, 5055, 4983, -1, 4881, 5082, 5075, -1, 4881, 5075, 4879, -1, 5083, 5071, 5062, -1, 5083, 5062, 5076, -1, 5084, 5074, 5065, -1, 5084, 5065, 5077, -1, 4886, 5080, 5072, -1, 4886, 5072, 5078, -1, 4894, 5077, 5079, -1, 5085, 5057, 5080, -1, 5085, 5066, 5057, -1, 4890, 5076, 4891, -1, 4890, 5083, 5076, -1, 4896, 5078, 5070, -1, 4896, 5070, 5081, -1, 4991, 5073, 5064, -1, 4991, 5064, 4979, -1, 4902, 5082, 4881, -1, 4902, 4904, 5086, -1, 4902, 5087, 5082, -1, 4902, 5086, 5087, -1, 5088, 5079, 5071, -1, 5088, 5071, 5083, -1, 4876, 5081, 5074, -1, 4876, 5074, 5084, -1, 4888, 5080, 4886, -1, 4888, 5085, 5080, -1, 4877, 4876, 5084, -1, 4877, 5077, 4894, -1, 4877, 5084, 5077, -1, 4880, 4879, 5066, -1, 4880, 5066, 5085, -1, 4884, 5083, 4890, -1, 4884, 5088, 5083, -1, 4887, 5078, 4896, -1, 4887, 4886, 5078, -1, 4892, 4891, 5073, -1, 4892, 5073, 4991, -1, 4883, 5079, 5088, -1, 4883, 5088, 4884, -1, 4883, 4894, 5079, -1, 4897, 4896, 5081, -1, 4897, 5081, 4876, -1, 4899, 5085, 4888, -1, 4899, 4880, 5085, -1, 5089, 5090, 5091, -1, 5091, 5090, 5092, -1, 5093, 5094, 5095, -1, 5096, 5094, 5093, -1, 5097, 5098, 5099, -1, 5099, 5098, 5100, -1, 5101, 5098, 5102, -1, 5100, 5098, 5101, -1, 5103, 5104, 5105, -1, 5106, 5104, 5103, -1, 5092, 5107, 5108, -1, 5108, 5107, 5106, -1, 5089, 5109, 5090, -1, 5102, 5109, 5089, -1, 5110, 5111, 5096, -1, 5096, 5111, 5094, -1, 5106, 5112, 5104, -1, 5107, 5112, 5106, -1, 5092, 5113, 5107, -1, 5090, 5113, 5092, -1, 5097, 5114, 5098, -1, 5098, 5114, 5102, -1, 5102, 5114, 5109, -1, 5110, 5115, 5111, -1, 5105, 5115, 5110, -1, 5113, 5116, 5107, -1, 5107, 5116, 5112, -1, 5109, 5117, 5090, -1, 5090, 5117, 5113, -1, 5104, 5118, 5105, -1, 5105, 5118, 5115, -1, 5117, 5119, 5113, -1, 5113, 5119, 5116, -1, 5120, 5121, 5122, -1, 5123, 5124, 5097, -1, 5097, 5124, 5114, -1, 5109, 5124, 5117, -1, 5114, 5124, 5109, -1, 5104, 5125, 5118, -1, 5112, 5125, 5104, -1, 5123, 5126, 5124, -1, 5124, 5126, 5117, -1, 5117, 5126, 5119, -1, 5112, 5127, 5125, -1, 5116, 5127, 5112, -1, 5116, 5128, 5127, -1, 5119, 5128, 5116, -1, 5119, 5129, 5128, -1, 5126, 5129, 5119, -1, 5130, 5129, 5123, -1, 5123, 5129, 5126, -1, 5128, 5131, 5127, -1, 5132, 5133, 5131, -1, 5134, 5135, 5136, -1, 5132, 5135, 5133, -1, 5130, 5137, 5129, -1, 5137, 5138, 5132, -1, 5139, 5138, 5130, -1, 5130, 5138, 5137, -1, 5139, 5140, 5138, -1, 5141, 5140, 5139, -1, 5138, 5140, 5132, -1, 5127, 5142, 5125, -1, 5131, 5142, 5127, -1, 5143, 5144, 5145, -1, 5133, 5142, 5131, -1, 5145, 5144, 5146, -1, 5133, 5147, 5142, -1, 5148, 5149, 5143, -1, 5150, 5151, 5134, -1, 5143, 5149, 5144, -1, 5134, 5151, 5135, -1, 5135, 5151, 5133, -1, 5133, 5151, 5147, -1, 5128, 5152, 5131, -1, 5129, 5152, 5128, -1, 5132, 5152, 5137, -1, 5131, 5152, 5132, -1, 5153, 5154, 5148, -1, 5137, 5152, 5129, -1, 5136, 5155, 5141, -1, 5148, 5154, 5149, -1, 5141, 5155, 5140, -1, 5135, 5155, 5136, -1, 5132, 5155, 5135, -1, 5140, 5155, 5132, -1, 5125, 5156, 5118, -1, 5146, 5157, 5158, -1, 5142, 5156, 5125, -1, 5147, 5156, 5142, -1, 5144, 5157, 5146, -1, 5159, 5160, 5153, -1, 5147, 5161, 5156, -1, 5162, 5163, 5150, -1, 5150, 5163, 5151, -1, 5151, 5163, 5147, -1, 5153, 5160, 5154, -1, 5147, 5163, 5161, -1, 5118, 5164, 5115, -1, 5157, 5165, 5158, -1, 5161, 5164, 5156, -1, 5156, 5164, 5118, -1, 5149, 5166, 5144, -1, 5144, 5166, 5157, -1, 5161, 5167, 5164, -1, 5168, 5169, 5162, -1, 5162, 5169, 5163, -1, 5170, 5171, 5159, -1, 5163, 5169, 5161, -1, 5161, 5169, 5167, -1, 5159, 5171, 5160, -1, 5164, 5172, 5115, -1, 5167, 5172, 5164, -1, 5115, 5172, 5111, -1, 5166, 5173, 5157, -1, 5174, 5175, 5168, -1, 5168, 5175, 5169, -1, 5157, 5173, 5165, -1, 5169, 5175, 5167, -1, 5149, 5176, 5166, -1, 5172, 5177, 5111, -1, 5111, 5177, 5094, -1, 5154, 5176, 5149, -1, 5178, 5179, 5170, -1, 5170, 5179, 5171, -1, 5167, 5180, 5172, -1, 5175, 5180, 5167, -1, 5172, 5180, 5177, -1, 5177, 5180, 5181, -1, 5158, 5182, 5183, -1, 5165, 5182, 5158, -1, 5175, 5184, 5180, -1, 5176, 5185, 5166, -1, 5180, 5184, 5181, -1, 5186, 5187, 5174, -1, 5174, 5187, 5175, -1, 5175, 5187, 5184, -1, 5166, 5185, 5173, -1, 5177, 5188, 5094, -1, 5160, 5189, 5154, -1, 5154, 5189, 5176, -1, 5181, 5188, 5177, -1, 5184, 5188, 5181, -1, 5190, 5191, 5186, -1, 5192, 5193, 5178, -1, 5186, 5191, 5187, -1, 5187, 5191, 5184, -1, 5188, 5194, 5094, -1, 5094, 5194, 5095, -1, 5178, 5193, 5179, -1, 5095, 5194, 5195, -1, 5188, 5196, 5194, -1, 5173, 5197, 5165, -1, 5165, 5197, 5182, -1, 5188, 5198, 5196, -1, 5184, 5199, 5188, -1, 5189, 5200, 5176, -1, 5188, 5199, 5198, -1, 5176, 5200, 5185, -1, 5160, 5201, 5189, -1, 5191, 5199, 5184, -1, 5199, 5202, 5198, -1, 5191, 5202, 5199, -1, 5203, 5202, 5190, -1, 5190, 5202, 5191, -1, 5171, 5201, 5160, -1, 5194, 5204, 5195, -1, 5192, 5205, 5193, -1, 5195, 5204, 5206, -1, 5196, 5204, 5194, -1, 5198, 5207, 5196, -1, 5202, 5207, 5198, -1, 5203, 5207, 5202, -1, 5208, 5205, 5192, -1, 5206, 5209, 5210, -1, 5182, 5211, 5183, -1, 5204, 5209, 5206, -1, 5173, 5212, 5197, -1, 5209, 5213, 5210, -1, 5207, 5214, 5196, -1, 5185, 5212, 5173, -1, 5196, 5214, 5204, -1, 5213, 5214, 5207, -1, 5189, 5215, 5200, -1, 5204, 5214, 5209, -1, 5209, 5214, 5213, -1, 5121, 5216, 5217, -1, 5201, 5215, 5189, -1, 5207, 5216, 5213, -1, 5213, 5216, 5210, -1, 5210, 5216, 5218, -1, 5218, 5216, 5121, -1, 5203, 5219, 5207, -1, 5171, 5220, 5201, -1, 5221, 5219, 5203, -1, 5217, 5219, 5221, -1, 5216, 5219, 5217, -1, 5207, 5219, 5216, -1, 5179, 5220, 5171, -1, 5208, 5222, 5205, -1, 5223, 5222, 5208, -1, 5197, 5224, 5182, -1, 5182, 5224, 5211, -1, 5211, 5225, 5183, -1, 5183, 5225, 5226, -1, 5185, 5227, 5212, -1, 5200, 5227, 5185, -1, 5220, 5228, 5201, -1, 5201, 5228, 5215, -1, 5179, 5229, 5220, -1, 5193, 5229, 5179, -1, 5230, 5231, 5223, -1, 5223, 5231, 5222, -1, 5197, 5232, 5224, -1, 5212, 5232, 5197, -1, 5224, 5233, 5211, -1, 5211, 5233, 5225, -1, 5215, 5234, 5200, -1, 5200, 5234, 5227, -1, 5220, 5235, 5228, -1, 5229, 5235, 5220, -1, 5205, 5236, 5193, -1, 5193, 5236, 5229, -1, 5230, 5237, 5231, -1, 5238, 5237, 5230, -1, 5227, 5239, 5212, -1, 5212, 5239, 5232, -1, 5225, 5240, 5226, -1, 5232, 5241, 5224, -1, 5224, 5241, 5233, -1, 5228, 5242, 5215, -1, 5215, 5242, 5234, -1, 5229, 5243, 5235, -1, 5236, 5243, 5229, -1, 5222, 5244, 5205, -1, 5205, 5244, 5236, -1, 5245, 5246, 5238, -1, 5238, 5246, 5237, -1, 5234, 5247, 5227, -1, 5227, 5247, 5239, -1, 5226, 5248, 5120, -1, 5240, 5248, 5226, -1, 5233, 5249, 5225, -1, 5225, 5249, 5240, -1, 5232, 5250, 5241, -1, 5239, 5250, 5232, -1, 5228, 5251, 5242, -1, 5235, 5251, 5228, -1, 5244, 5252, 5236, -1, 5236, 5252, 5243, -1, 5231, 5253, 5222, -1, 5222, 5253, 5244, -1, 5234, 5254, 5247, -1, 5242, 5254, 5234, -1, 5255, 5256, 5257, -1, 5257, 5256, 5258, -1, 5258, 5256, 5245, -1, 5245, 5256, 5246, -1, 5249, 5259, 5240, -1, 5240, 5259, 5248, -1, 5233, 5260, 5249, -1, 5241, 5260, 5233, -1, 5239, 5261, 5250, -1, 5247, 5261, 5239, -1, 5243, 5262, 5235, -1, 5235, 5262, 5251, -1, 5253, 5263, 5244, -1, 5244, 5263, 5252, -1, 5231, 5264, 5253, -1, 5237, 5264, 5231, -1, 5242, 5265, 5254, -1, 5251, 5265, 5242, -1, 5260, 5266, 5249, -1, 5249, 5266, 5259, -1, 5241, 5267, 5260, -1, 5250, 5267, 5241, -1, 5247, 5268, 5261, -1, 5254, 5268, 5247, -1, 5120, 5218, 5121, -1, 5248, 5218, 5120, -1, 5252, 5269, 5243, -1, 5243, 5269, 5262, -1, 5253, 5270, 5263, -1, 5264, 5270, 5253, -1, 5246, 5271, 5237, -1, 5237, 5271, 5264, -1, 5251, 5272, 5265, -1, 5262, 5272, 5251, -1, 5260, 5273, 5266, -1, 5267, 5273, 5260, -1, 5261, 5274, 5250, -1, 5250, 5274, 5267, -1, 5254, 5275, 5268, -1, 5265, 5275, 5254, -1, 5248, 5210, 5218, -1, 5259, 5210, 5248, -1, 5263, 5276, 5252, -1, 5252, 5276, 5269, -1, 5264, 5277, 5270, -1, 5271, 5277, 5264, -1, 5278, 5279, 5255, -1, 5256, 5279, 5246, -1, 5246, 5279, 5271, -1, 5255, 5279, 5256, -1, 5269, 5280, 5262, -1, 5262, 5280, 5272, -1, 5267, 5093, 5273, -1, 5274, 5093, 5267, -1, 5268, 5281, 5261, -1, 5261, 5281, 5274, -1, 5272, 5282, 5265, -1, 5265, 5282, 5275, -1, 5266, 5206, 5259, -1, 5259, 5206, 5210, -1, 5270, 5283, 5263, -1, 5263, 5283, 5276, -1, 5099, 5284, 5278, -1, 5278, 5284, 5279, -1, 5271, 5284, 5277, -1, 5279, 5284, 5271, -1, 5269, 5091, 5280, -1, 5276, 5091, 5269, -1, 5274, 5096, 5093, -1, 5281, 5096, 5274, -1, 5268, 5285, 5281, -1, 5275, 5285, 5268, -1, 5272, 5108, 5282, -1, 5280, 5108, 5272, -1, 5266, 5195, 5206, -1, 5273, 5195, 5266, -1, 5270, 5101, 5283, -1, 5277, 5101, 5270, -1, 5276, 5089, 5091, -1, 5283, 5089, 5276, -1, 5281, 5110, 5096, -1, 5285, 5110, 5281, -1, 5275, 5103, 5285, -1, 5282, 5103, 5275, -1, 5280, 5092, 5108, -1, 5091, 5092, 5280, -1, 5093, 5095, 5273, -1, 5273, 5095, 5195, -1, 5284, 5100, 5277, -1, 5277, 5100, 5101, -1, 5099, 5100, 5284, -1, 5101, 5102, 5283, -1, 5283, 5102, 5089, -1, 5285, 5105, 5110, -1, 5103, 5105, 5285, -1, 5108, 5106, 5282, -1, 5282, 5106, 5103, -1, 5286, 5287, 5288, -1, 5289, 5290, 5291, -1, 5289, 5292, 5290, -1, 5293, 5294, 5295, -1, 5293, 5296, 5294, -1, 5297, 5298, 5299, -1, 5297, 5300, 5298, -1, 5301, 5302, 5303, -1, 5301, 5303, 5304, -1, 5305, 5288, 5306, -1, 5305, 5306, 5296, -1, 5307, 5299, 5308, -1, 5307, 5308, 5309, -1, 5310, 5289, 5291, -1, 5310, 5291, 5311, -1, 5312, 5313, 5286, -1, 5312, 5309, 5313, -1, 5314, 5315, 5292, -1, 5314, 5316, 5317, -1, 5314, 5292, 5289, -1, 5314, 5317, 5315, -1, 5318, 5296, 5293, -1, 5318, 5305, 5296, -1, 5319, 5300, 5297, -1, 5319, 5311, 5300, -1, 5320, 5302, 5301, -1, 5320, 5295, 5302, -1, 5321, 5286, 5288, -1, 5321, 5288, 5305, -1, 5322, 5299, 5307, -1, 5322, 5297, 5299, -1, 5323, 5289, 5310, -1, 5323, 5316, 5314, -1, 5323, 5314, 5289, -1, 5324, 5309, 5312, -1, 5324, 5307, 5309, -1, 5325, 5305, 5318, -1, 5325, 5321, 5305, -1, 5326, 5310, 5311, -1, 5326, 5311, 5319, -1, 5327, 5293, 5295, -1, 5327, 5295, 5320, -1, 5328, 5312, 5286, -1, 5328, 5286, 5321, -1, 5329, 5319, 5297, -1, 5329, 5297, 5322, -1, 5330, 5322, 5307, -1, 5330, 5307, 5324, -1, 5331, 5328, 5321, -1, 5331, 5321, 5325, -1, 5332, 5310, 5326, -1, 5332, 5333, 5316, -1, 5332, 5316, 5323, -1, 5332, 5323, 5310, -1, 5334, 5293, 5327, -1, 5334, 5318, 5293, -1, 5335, 5312, 5328, -1, 5335, 5324, 5312, -1, 5336, 5319, 5329, -1, 5336, 5326, 5319, -1, 5337, 5329, 5322, -1, 5338, 5339, 5340, -1, 5337, 5322, 5330, -1, 5341, 5335, 5328, -1, 5338, 5340, 5342, -1, 5343, 5344, 5339, -1, 5341, 5328, 5331, -1, 5345, 5318, 5334, -1, 5343, 5339, 5338, -1, 5346, 5347, 5344, -1, 5345, 5325, 5318, -1, 5348, 5330, 5324, -1, 5348, 5324, 5335, -1, 5349, 5332, 5326, -1, 5346, 5344, 5343, -1, 5349, 5326, 5336, -1, 5349, 5333, 5332, -1, 5350, 5342, 5351, -1, 5352, 5336, 5329, -1, 5350, 5338, 5342, -1, 5353, 5354, 5347, -1, 5352, 5329, 5337, -1, 5355, 5335, 5341, -1, 5353, 5347, 5346, -1, 5355, 5348, 5335, -1, 5356, 5331, 5325, -1, 5356, 5325, 5345, -1, 5357, 5351, 5358, -1, 5357, 5350, 5351, -1, 5359, 5330, 5348, -1, 5360, 5343, 5338, -1, 5359, 5337, 5330, -1, 5361, 5362, 5333, -1, 5361, 5333, 5349, -1, 5361, 5336, 5352, -1, 5360, 5338, 5350, -1, 5361, 5349, 5336, -1, 5363, 5364, 5354, -1, 5365, 5359, 5348, -1, 5365, 5348, 5355, -1, 5363, 5354, 5353, -1, 5366, 5331, 5356, -1, 5366, 5341, 5331, -1, 5367, 5350, 5357, -1, 5367, 5360, 5350, -1, 5368, 5352, 5337, -1, 5368, 5337, 5359, -1, 5369, 5346, 5343, -1, 5369, 5343, 5360, -1, 5370, 5359, 5365, -1, 5370, 5368, 5359, -1, 5371, 5355, 5341, -1, 5372, 5357, 5358, -1, 5371, 5341, 5366, -1, 5373, 5374, 5364, -1, 5375, 5361, 5352, -1, 5375, 5362, 5361, -1, 5375, 5352, 5368, -1, 5376, 5377, 5362, -1, 5373, 5364, 5363, -1, 5376, 5368, 5370, -1, 5378, 5360, 5367, -1, 5376, 5362, 5375, -1, 5376, 5375, 5368, -1, 5379, 5365, 5355, -1, 5379, 5355, 5371, -1, 5378, 5369, 5360, -1, 5380, 5370, 5365, -1, 5380, 5376, 5370, -1, 5380, 5365, 5379, -1, 5381, 5382, 5383, -1, 5381, 5383, 5384, -1, 5385, 5353, 5346, -1, 5381, 5384, 5377, -1, 5381, 5380, 5382, -1, 5385, 5346, 5369, -1, 5381, 5377, 5376, -1, 5381, 5376, 5380, -1, 5386, 5367, 5357, -1, 5386, 5357, 5372, -1, 5387, 5388, 5374, -1, 5389, 5390, 5391, -1, 5389, 5392, 5390, -1, 5393, 5394, 5395, -1, 5387, 5374, 5373, -1, 5393, 5392, 5394, -1, 5393, 5390, 5392, -1, 5396, 5358, 5397, -1, 5398, 5393, 5395, -1, 5398, 5395, 5399, -1, 5396, 5372, 5358, -1, 5398, 5390, 5393, -1, 5400, 5399, 5401, -1, 5400, 5401, 5391, -1, 5400, 5391, 5390, -1, 5402, 5369, 5378, -1, 5400, 5398, 5399, -1, 5400, 5390, 5398, -1, 5403, 5404, 5392, -1, 5402, 5385, 5369, -1, 5403, 5304, 5404, -1, 5403, 5392, 5389, -1, 5405, 5363, 5353, -1, 5405, 5353, 5385, -1, 5406, 5403, 5389, -1, 5407, 5389, 5391, -1, 5408, 5367, 5386, -1, 5407, 5406, 5389, -1, 5407, 5391, 5409, -1, 5407, 5409, 5410, -1, 5411, 5304, 5403, -1, 5411, 5301, 5304, -1, 5411, 5403, 5406, -1, 5408, 5378, 5367, -1, 5412, 5413, 5388, -1, 5414, 5411, 5406, -1, 5415, 5414, 5406, -1, 5415, 5407, 5410, -1, 5415, 5406, 5407, -1, 5412, 5388, 5387, -1, 5415, 5410, 5416, -1, 5417, 5372, 5396, -1, 5418, 5301, 5411, -1, 5418, 5411, 5414, -1, 5417, 5386, 5372, -1, 5418, 5320, 5301, -1, 5419, 5385, 5402, -1, 5420, 5418, 5414, -1, 5419, 5405, 5385, -1, 5421, 5414, 5415, -1, 5421, 5420, 5414, -1, 5421, 5415, 5416, -1, 5421, 5416, 5422, -1, 5423, 5396, 5397, -1, 5424, 5327, 5320, -1, 5424, 5320, 5418, -1, 5424, 5418, 5420, -1, 5425, 5363, 5405, -1, 5425, 5373, 5363, -1, 5426, 5424, 5420, -1, 5427, 5422, 5428, -1, 5427, 5420, 5421, -1, 5429, 5378, 5408, -1, 5427, 5421, 5422, -1, 5427, 5426, 5420, -1, 5430, 5334, 5327, -1, 5430, 5327, 5424, -1, 5429, 5402, 5378, -1, 5430, 5424, 5426, -1, 5431, 5413, 5412, -1, 5431, 5432, 5413, -1, 5433, 5430, 5426, -1, 5434, 5428, 5435, -1, 5434, 5427, 5428, -1, 5434, 5426, 5427, -1, 5434, 5433, 5426, -1, 5436, 5408, 5386, -1, 5437, 5345, 5334, -1, 5436, 5386, 5417, -1, 5437, 5334, 5430, -1, 5437, 5430, 5433, -1, 5438, 5435, 5439, -1, 5440, 5425, 5405, -1, 5440, 5405, 5419, -1, 5438, 5434, 5435, -1, 5438, 5433, 5434, -1, 5438, 5437, 5433, -1, 5441, 5356, 5345, -1, 5441, 5345, 5437, -1, 5442, 5396, 5423, -1, 5442, 5417, 5396, -1, 5443, 5437, 5438, -1, 5443, 5441, 5437, -1, 5444, 5373, 5425, -1, 5444, 5387, 5373, -1, 5445, 5441, 5443, -1, 5446, 5402, 5429, -1, 5446, 5419, 5402, -1, 5447, 5443, 5438, -1, 5447, 5445, 5443, -1, 5448, 5432, 5431, -1, 5449, 5439, 5450, -1, 5449, 5438, 5439, -1, 5448, 5451, 5432, -1, 5449, 5447, 5438, -1, 5452, 5441, 5445, -1, 5452, 5356, 5441, -1, 5452, 5366, 5356, -1, 5453, 5397, 5454, -1, 5452, 5445, 5447, -1, 5455, 5450, 5456, -1, 5453, 5423, 5397, -1, 5455, 5449, 5450, -1, 5455, 5447, 5449, -1, 5457, 5429, 5408, -1, 5455, 5452, 5447, -1, 5458, 5366, 5452, -1, 5457, 5408, 5436, -1, 5458, 5371, 5366, -1, 5459, 5425, 5440, -1, 5460, 5458, 5452, -1, 5461, 5456, 5462, -1, 5461, 5455, 5456, -1, 5459, 5444, 5425, -1, 5461, 5452, 5455, -1, 5461, 5460, 5452, -1, 5463, 5458, 5460, -1, 5463, 5371, 5458, -1, 5464, 5436, 5417, -1, 5464, 5417, 5442, -1, 5463, 5379, 5371, -1, 5465, 5462, 5466, -1, 5465, 5466, 5382, -1, 5465, 5382, 5380, -1, 5465, 5461, 5462, -1, 5467, 5412, 5387, -1, 5465, 5380, 5379, -1, 5465, 5460, 5461, -1, 5465, 5463, 5460, -1, 5465, 5379, 5463, -1, 5467, 5387, 5444, -1, 5468, 5453, 5454, -1, 5469, 5440, 5419, -1, 5469, 5419, 5446, -1, 5470, 5451, 5448, -1, 5470, 5471, 5451, -1, 5472, 5442, 5423, -1, 5472, 5423, 5453, -1, 5473, 5429, 5457, -1, 5473, 5446, 5429, -1, 5474, 5444, 5459, -1, 5474, 5467, 5444, -1, 5475, 5457, 5436, -1, 5475, 5436, 5464, -1, 5476, 5431, 5412, -1, 5476, 5412, 5467, -1, 5477, 5453, 5468, -1, 5477, 5472, 5453, -1, 5478, 5440, 5469, -1, 5478, 5459, 5440, -1, 5479, 5480, 5471, -1, 5479, 5471, 5470, -1, 5481, 5442, 5472, -1, 5481, 5464, 5442, -1, 5482, 5446, 5473, -1, 5482, 5469, 5446, -1, 5483, 5467, 5474, -1, 5483, 5476, 5467, -1, 5484, 5457, 5475, -1, 5484, 5473, 5457, -1, 5485, 5431, 5476, -1, 5485, 5448, 5431, -1, 5486, 5481, 5472, -1, 5486, 5472, 5477, -1, 5487, 5474, 5459, -1, 5487, 5459, 5478, -1, 5394, 5454, 5395, -1, 5394, 5468, 5454, -1, 5290, 5488, 5480, -1, 5290, 5480, 5479, -1, 5489, 5475, 5464, -1, 5489, 5464, 5481, -1, 5490, 5469, 5482, -1, 5490, 5478, 5469, -1, 5491, 5476, 5483, -1, 5491, 5485, 5476, -1, 5492, 5473, 5484, -1, 5492, 5482, 5473, -1, 5493, 5448, 5485, -1, 5493, 5470, 5448, -1, 5303, 5481, 5486, -1, 5303, 5489, 5481, -1, 5494, 5483, 5474, -1, 5494, 5474, 5487, -1, 5392, 5477, 5468, -1, 5392, 5468, 5394, -1, 5292, 5495, 5488, -1, 5292, 5488, 5290, -1, 5496, 5484, 5475, -1, 5496, 5475, 5489, -1, 5287, 5487, 5478, -1, 5287, 5478, 5490, -1, 5298, 5493, 5485, -1, 5298, 5485, 5491, -1, 5306, 5490, 5482, -1, 5306, 5482, 5492, -1, 5497, 5470, 5493, -1, 5497, 5479, 5470, -1, 5302, 5489, 5303, -1, 5302, 5496, 5489, -1, 5308, 5491, 5483, -1, 5308, 5483, 5494, -1, 5404, 5486, 5477, -1, 5404, 5477, 5392, -1, 5315, 5495, 5292, -1, 5315, 5317, 5498, -1, 5315, 5499, 5495, -1, 5315, 5498, 5499, -1, 5294, 5492, 5484, -1, 5294, 5484, 5496, -1, 5313, 5494, 5487, -1, 5313, 5487, 5287, -1, 5300, 5493, 5298, -1, 5300, 5497, 5493, -1, 5288, 5287, 5490, -1, 5288, 5490, 5306, -1, 5291, 5290, 5479, -1, 5291, 5479, 5497, -1, 5295, 5294, 5496, -1, 5295, 5496, 5302, -1, 5299, 5491, 5308, -1, 5299, 5298, 5491, -1, 5304, 5486, 5404, -1, 5304, 5303, 5486, -1, 5296, 5492, 5294, -1, 5296, 5306, 5492, -1, 5309, 5308, 5494, -1, 5309, 5494, 5313, -1, 5311, 5497, 5300, -1, 5311, 5291, 5497, -1, 5286, 5313, 5287, -1, 5500, 5501, 5502, -1, 5502, 5501, 5503, -1, 5504, 5505, 5506, -1, 5507, 5505, 5504, -1, 5508, 5509, 5510, -1, 5511, 5509, 5512, -1, 5510, 5509, 5513, -1, 5513, 5509, 5511, -1, 5514, 5515, 5516, -1, 5516, 5515, 5517, -1, 5518, 5519, 5514, -1, 5503, 5519, 5518, -1, 5500, 5520, 5501, -1, 5512, 5520, 5500, -1, 5521, 5522, 5507, -1, 5507, 5522, 5505, -1, 5519, 5523, 5514, -1, 5514, 5523, 5515, -1, 5503, 5524, 5519, -1, 5501, 5524, 5503, -1, 5512, 5525, 5520, -1, 5508, 5525, 5509, -1, 5509, 5525, 5512, -1, 5517, 5526, 5521, -1, 5521, 5526, 5522, -1, 5519, 5527, 5523, -1, 5524, 5527, 5519, -1, 5520, 5528, 5501, -1, 5501, 5528, 5524, -1, 5515, 5529, 5517, -1, 5517, 5529, 5526, -1, 5528, 5530, 5524, -1, 5524, 5530, 5527, -1, 5531, 5532, 5508, -1, 5533, 5534, 5535, -1, 5508, 5532, 5525, -1, 5520, 5532, 5528, -1, 5525, 5532, 5520, -1, 5515, 5536, 5529, -1, 5523, 5536, 5515, -1, 5531, 5537, 5532, -1, 5532, 5537, 5528, -1, 5528, 5537, 5530, -1, 5523, 5538, 5536, -1, 5527, 5538, 5523, -1, 5527, 5539, 5538, -1, 5530, 5539, 5527, -1, 5530, 5540, 5539, -1, 5537, 5540, 5530, -1, 5541, 5540, 5531, -1, 5531, 5540, 5537, -1, 5539, 5542, 5538, -1, 5543, 5544, 5542, -1, 5545, 5546, 5547, -1, 5543, 5546, 5544, -1, 5541, 5548, 5540, -1, 5548, 5549, 5543, -1, 5550, 5549, 5541, -1, 5541, 5549, 5548, -1, 5551, 5552, 5550, -1, 5550, 5552, 5549, -1, 5549, 5552, 5543, -1, 5538, 5553, 5536, -1, 5542, 5553, 5538, -1, 5544, 5553, 5542, -1, 5554, 5555, 5556, -1, 5556, 5555, 5557, -1, 5544, 5558, 5553, -1, 5559, 5560, 5554, -1, 5561, 5562, 5545, -1, 5545, 5562, 5546, -1, 5554, 5560, 5555, -1, 5546, 5562, 5544, -1, 5544, 5562, 5558, -1, 5540, 5563, 5539, -1, 5543, 5563, 5548, -1, 5539, 5563, 5542, -1, 5542, 5563, 5543, -1, 5548, 5563, 5540, -1, 5564, 5565, 5559, -1, 5547, 5566, 5551, -1, 5551, 5566, 5552, -1, 5559, 5565, 5560, -1, 5546, 5566, 5547, -1, 5543, 5566, 5546, -1, 5552, 5566, 5543, -1, 5536, 5567, 5529, -1, 5557, 5568, 5569, -1, 5553, 5567, 5536, -1, 5558, 5567, 5553, -1, 5555, 5568, 5557, -1, 5570, 5571, 5564, -1, 5558, 5572, 5567, -1, 5573, 5574, 5561, -1, 5561, 5574, 5562, -1, 5562, 5574, 5558, -1, 5558, 5574, 5572, -1, 5564, 5571, 5565, -1, 5529, 5575, 5526, -1, 5568, 5576, 5569, -1, 5572, 5575, 5567, -1, 5567, 5575, 5529, -1, 5560, 5577, 5555, -1, 5555, 5577, 5568, -1, 5572, 5578, 5575, -1, 5573, 5579, 5574, -1, 5580, 5579, 5573, -1, 5581, 5582, 5570, -1, 5574, 5579, 5572, -1, 5572, 5579, 5578, -1, 5526, 5583, 5522, -1, 5570, 5582, 5571, -1, 5575, 5583, 5526, -1, 5578, 5583, 5575, -1, 5577, 5584, 5568, -1, 5585, 5586, 5580, -1, 5580, 5586, 5579, -1, 5579, 5586, 5578, -1, 5568, 5584, 5576, -1, 5522, 5587, 5505, -1, 5560, 5588, 5577, -1, 5583, 5587, 5522, -1, 5565, 5588, 5560, -1, 5589, 5590, 5581, -1, 5581, 5590, 5582, -1, 5578, 5591, 5583, -1, 5586, 5591, 5578, -1, 5583, 5591, 5587, -1, 5587, 5591, 5592, -1, 5569, 5593, 5594, -1, 5576, 5593, 5569, -1, 5586, 5595, 5591, -1, 5591, 5595, 5592, -1, 5588, 5596, 5577, -1, 5597, 5598, 5585, -1, 5585, 5598, 5586, -1, 5586, 5598, 5595, -1, 5577, 5596, 5584, -1, 5587, 5599, 5505, -1, 5571, 5600, 5565, -1, 5592, 5599, 5587, -1, 5565, 5600, 5588, -1, 5595, 5599, 5592, -1, 5598, 5601, 5595, -1, 5602, 5601, 5597, -1, 5603, 5604, 5589, -1, 5597, 5601, 5598, -1, 5599, 5605, 5505, -1, 5505, 5605, 5506, -1, 5506, 5605, 5606, -1, 5589, 5604, 5590, -1, 5599, 5607, 5605, -1, 5584, 5608, 5576, -1, 5576, 5608, 5593, -1, 5599, 5609, 5607, -1, 5595, 5610, 5599, -1, 5600, 5611, 5588, -1, 5599, 5610, 5609, -1, 5588, 5611, 5596, -1, 5601, 5610, 5595, -1, 5571, 5612, 5600, -1, 5602, 5613, 5601, -1, 5601, 5613, 5610, -1, 5610, 5613, 5609, -1, 5614, 5613, 5602, -1, 5607, 5615, 5605, -1, 5582, 5612, 5571, -1, 5606, 5615, 5616, -1, 5605, 5615, 5606, -1, 5609, 5617, 5607, -1, 5593, 5618, 5594, -1, 5613, 5617, 5609, -1, 5603, 5619, 5604, -1, 5614, 5617, 5613, -1, 5616, 5620, 5621, -1, 5622, 5619, 5603, -1, 5615, 5620, 5616, -1, 5584, 5623, 5608, -1, 5620, 5624, 5621, -1, 5617, 5625, 5607, -1, 5607, 5625, 5615, -1, 5596, 5623, 5584, -1, 5620, 5625, 5624, -1, 5615, 5625, 5620, -1, 5600, 5626, 5611, -1, 5624, 5625, 5617, -1, 5534, 5627, 5628, -1, 5617, 5627, 5624, -1, 5612, 5626, 5600, -1, 5624, 5627, 5621, -1, 5621, 5627, 5629, -1, 5629, 5627, 5534, -1, 5614, 5630, 5617, -1, 5631, 5630, 5614, -1, 5582, 5632, 5612, -1, 5628, 5630, 5631, -1, 5627, 5630, 5628, -1, 5617, 5630, 5627, -1, 5590, 5632, 5582, -1, 5608, 5633, 5593, -1, 5593, 5633, 5618, -1, 5622, 5634, 5619, -1, 5635, 5634, 5622, -1, 5618, 5636, 5594, -1, 5594, 5636, 5637, -1, 5596, 5638, 5623, -1, 5611, 5638, 5596, -1, 5632, 5639, 5612, -1, 5612, 5639, 5626, -1, 5590, 5640, 5632, -1, 5604, 5640, 5590, -1, 5608, 5641, 5633, -1, 5623, 5641, 5608, -1, 5642, 5643, 5635, -1, 5635, 5643, 5634, -1, 5633, 5644, 5618, -1, 5618, 5644, 5636, -1, 5626, 5645, 5611, -1, 5611, 5645, 5638, -1, 5632, 5646, 5639, -1, 5640, 5646, 5632, -1, 5619, 5647, 5604, -1, 5604, 5647, 5640, -1, 5638, 5648, 5623, -1, 5623, 5648, 5641, -1, 5642, 5649, 5643, -1, 5650, 5649, 5642, -1, 5636, 5651, 5637, -1, 5641, 5652, 5633, -1, 5633, 5652, 5644, -1, 5639, 5653, 5626, -1, 5626, 5653, 5645, -1, 5640, 5654, 5646, -1, 5647, 5654, 5640, -1, 5619, 5655, 5647, -1, 5634, 5655, 5619, -1, 5645, 5656, 5638, -1, 5638, 5656, 5648, -1, 5657, 5658, 5650, -1, 5650, 5658, 5649, -1, 5637, 5659, 5533, -1, 5651, 5659, 5637, -1, 5644, 5660, 5636, -1, 5636, 5660, 5651, -1, 5641, 5661, 5652, -1, 5648, 5661, 5641, -1, 5646, 5662, 5639, -1, 5639, 5662, 5653, -1, 5655, 5663, 5647, -1, 5647, 5663, 5654, -1, 5634, 5664, 5655, -1, 5643, 5664, 5634, -1, 5645, 5665, 5656, -1, 5653, 5665, 5645, -1, 5666, 5667, 5668, -1, 5668, 5667, 5669, -1, 5669, 5667, 5657, -1, 5657, 5667, 5658, -1, 5660, 5670, 5651, -1, 5651, 5670, 5659, -1, 5644, 5671, 5660, -1, 5652, 5671, 5644, -1, 5648, 5672, 5661, -1, 5656, 5672, 5648, -1, 5646, 5673, 5662, -1, 5654, 5673, 5646, -1, 5655, 5674, 5663, -1, 5664, 5674, 5655, -1, 5643, 5675, 5664, -1, 5649, 5675, 5643, -1, 5653, 5676, 5665, -1, 5662, 5676, 5653, -1, 5671, 5677, 5660, -1, 5660, 5677, 5670, -1, 5652, 5678, 5671, -1, 5661, 5678, 5652, -1, 5656, 5679, 5672, -1, 5665, 5679, 5656, -1, 5533, 5629, 5534, -1, 5659, 5629, 5533, -1, 5654, 5680, 5673, -1, 5663, 5680, 5654, -1, 5664, 5681, 5674, -1, 5675, 5681, 5664, -1, 5658, 5682, 5649, -1, 5649, 5682, 5675, -1, 5673, 5683, 5662, -1, 5662, 5683, 5676, -1, 5671, 5684, 5677, -1, 5678, 5684, 5671, -1, 5672, 5685, 5661, -1, 5661, 5685, 5678, -1, 5676, 5686, 5665, -1, 5665, 5686, 5679, -1, 5659, 5621, 5629, -1, 5670, 5621, 5659, -1, 5674, 5687, 5663, -1, 5663, 5687, 5680, -1, 5682, 5688, 5675, -1, 5675, 5688, 5681, -1, 5689, 5690, 5666, -1, 5667, 5690, 5658, -1, 5658, 5690, 5682, -1, 5666, 5690, 5667, -1, 5673, 5691, 5683, -1, 5680, 5691, 5673, -1, 5678, 5504, 5684, -1, 5685, 5504, 5678, -1, 5679, 5692, 5672, -1, 5672, 5692, 5685, -1, 5676, 5693, 5686, -1, 5683, 5693, 5676, -1, 5677, 5616, 5670, -1, 5670, 5616, 5621, -1, 5674, 5694, 5687, -1, 5681, 5694, 5674, -1, 5510, 5695, 5689, -1, 5682, 5695, 5688, -1, 5689, 5695, 5690, -1, 5690, 5695, 5682, -1, 5680, 5502, 5691, -1, 5687, 5502, 5680, -1, 5692, 5507, 5685, -1, 5685, 5507, 5504, -1, 5679, 5696, 5692, -1, 5686, 5696, 5679, -1, 5683, 5518, 5693, -1, 5691, 5518, 5683, -1, 5677, 5606, 5616, -1, 5684, 5606, 5677, -1, 5681, 5511, 5694, -1, 5688, 5511, 5681, -1, 5687, 5500, 5502, -1, 5694, 5500, 5687, -1, 5696, 5521, 5692, -1, 5692, 5521, 5507, -1, 5686, 5516, 5696, -1, 5693, 5516, 5686, -1, 5691, 5503, 5518, -1, 5502, 5503, 5691, -1, 5684, 5506, 5606, -1, 5504, 5506, 5684, -1, 5695, 5513, 5688, -1, 5688, 5513, 5511, -1, 5510, 5513, 5695, -1, 5511, 5512, 5694, -1, 5694, 5512, 5500, -1, 5696, 5517, 5521, -1, 5516, 5517, 5696, -1, 5518, 5514, 5693, -1, 5693, 5514, 5516, -1, 5697, 5698, 5699, -1, 5700, 5701, 5702, -1, 5700, 5703, 5701, -1, 5704, 5705, 5706, -1, 5704, 5707, 5705, -1, 5708, 5709, 5710, -1, 5708, 5711, 5709, -1, 5712, 5713, 5714, -1, 5712, 5714, 5715, -1, 5716, 5699, 5717, -1, 5716, 5717, 5707, -1, 5718, 5710, 5719, -1, 5718, 5719, 5720, -1, 5721, 5700, 5702, -1, 5721, 5702, 5722, -1, 5723, 5724, 5697, -1, 5723, 5720, 5724, -1, 5725, 5726, 5703, -1, 5725, 5727, 5728, -1, 5725, 5703, 5700, -1, 5725, 5728, 5726, -1, 5729, 5707, 5704, -1, 5729, 5716, 5707, -1, 5730, 5711, 5708, -1, 5730, 5722, 5711, -1, 5731, 5713, 5712, -1, 5731, 5706, 5713, -1, 5732, 5697, 5699, -1, 5732, 5699, 5716, -1, 5733, 5710, 5718, -1, 5733, 5708, 5710, -1, 5734, 5700, 5721, -1, 5734, 5727, 5725, -1, 5734, 5725, 5700, -1, 5735, 5720, 5723, -1, 5735, 5718, 5720, -1, 5736, 5716, 5729, -1, 5736, 5732, 5716, -1, 5737, 5721, 5722, -1, 5737, 5722, 5730, -1, 5738, 5704, 5706, -1, 5738, 5706, 5731, -1, 5739, 5723, 5697, -1, 5739, 5697, 5732, -1, 5740, 5730, 5708, -1, 5740, 5708, 5733, -1, 5741, 5733, 5718, -1, 5741, 5718, 5735, -1, 5742, 5739, 5732, -1, 5742, 5732, 5736, -1, 5743, 5721, 5737, -1, 5743, 5744, 5727, -1, 5743, 5727, 5734, -1, 5743, 5734, 5721, -1, 5745, 5704, 5738, -1, 5745, 5729, 5704, -1, 5746, 5723, 5739, -1, 5746, 5735, 5723, -1, 5747, 5730, 5740, -1, 5747, 5737, 5730, -1, 5748, 5740, 5733, -1, 5749, 5750, 5751, -1, 5748, 5733, 5741, -1, 5752, 5739, 5742, -1, 5749, 5751, 5753, -1, 5752, 5746, 5739, -1, 5754, 5755, 5750, -1, 5756, 5729, 5745, -1, 5754, 5750, 5749, -1, 5757, 5758, 5755, -1, 5756, 5736, 5729, -1, 5759, 5741, 5735, -1, 5759, 5735, 5746, -1, 5757, 5755, 5754, -1, 5760, 5744, 5743, -1, 5760, 5737, 5747, -1, 5761, 5753, 5762, -1, 5760, 5743, 5737, -1, 5763, 5747, 5740, -1, 5761, 5749, 5753, -1, 5763, 5740, 5748, -1, 5764, 5765, 5758, -1, 5766, 5746, 5752, -1, 5764, 5758, 5757, -1, 5766, 5759, 5746, -1, 5767, 5742, 5736, -1, 5767, 5736, 5756, -1, 5768, 5762, 5769, -1, 5768, 5761, 5762, -1, 5770, 5748, 5741, -1, 5770, 5741, 5759, -1, 5771, 5754, 5749, -1, 5772, 5747, 5763, -1, 5772, 5773, 5744, -1, 5772, 5744, 5760, -1, 5771, 5749, 5761, -1, 5772, 5760, 5747, -1, 5774, 5775, 5765, -1, 5776, 5759, 5766, -1, 5776, 5770, 5759, -1, 5777, 5752, 5742, -1, 5774, 5765, 5764, -1, 5777, 5766, 5752, -1, 5777, 5742, 5767, -1, 5778, 5761, 5768, -1, 5778, 5771, 5761, -1, 5779, 5763, 5748, -1, 5779, 5748, 5770, -1, 5780, 5757, 5754, -1, 5780, 5754, 5771, -1, 5781, 5770, 5776, -1, 5781, 5779, 5770, -1, 5782, 5768, 5769, -1, 5783, 5784, 5775, -1, 5785, 5766, 5777, -1, 5786, 5772, 5763, -1, 5786, 5773, 5772, -1, 5786, 5763, 5779, -1, 5787, 5773, 5786, -1, 5783, 5775, 5774, -1, 5787, 5788, 5773, -1, 5789, 5771, 5778, -1, 5787, 5779, 5781, -1, 5787, 5786, 5779, -1, 5790, 5776, 5766, -1, 5790, 5766, 5785, -1, 5789, 5780, 5771, -1, 5791, 5776, 5790, -1, 5791, 5781, 5776, -1, 5792, 5764, 5757, -1, 5793, 5794, 5795, -1, 5793, 5795, 5796, -1, 5792, 5757, 5780, -1, 5793, 5796, 5788, -1, 5793, 5787, 5781, -1, 5793, 5788, 5787, -1, 5797, 5778, 5768, -1, 5793, 5791, 5794, -1, 5793, 5781, 5791, -1, 5797, 5768, 5782, -1, 5798, 5799, 5784, -1, 5800, 5801, 5802, -1, 5800, 5803, 5801, -1, 5798, 5784, 5783, -1, 5804, 5805, 5806, -1, 5807, 5769, 5808, -1, 5804, 5803, 5805, -1, 5804, 5801, 5803, -1, 5809, 5804, 5806, -1, 5807, 5782, 5769, -1, 5809, 5806, 5810, -1, 5809, 5801, 5804, -1, 5811, 5780, 5789, -1, 5812, 5810, 5813, -1, 5812, 5813, 5802, -1, 5812, 5802, 5801, -1, 5812, 5809, 5810, -1, 5812, 5801, 5809, -1, 5811, 5792, 5780, -1, 5814, 5815, 5803, -1, 5814, 5715, 5815, -1, 5814, 5803, 5800, -1, 5816, 5774, 5764, -1, 5816, 5764, 5792, -1, 5817, 5778, 5797, -1, 5818, 5814, 5800, -1, 5819, 5800, 5802, -1, 5819, 5818, 5800, -1, 5819, 5802, 5820, -1, 5819, 5820, 5821, -1, 5822, 5715, 5814, -1, 5817, 5789, 5778, -1, 5822, 5712, 5715, -1, 5823, 5824, 5799, -1, 5822, 5814, 5818, -1, 5825, 5822, 5818, -1, 5823, 5799, 5798, -1, 5826, 5825, 5818, -1, 5826, 5819, 5821, -1, 5826, 5818, 5819, -1, 5827, 5782, 5807, -1, 5826, 5821, 5828, -1, 5827, 5797, 5782, -1, 5829, 5712, 5822, -1, 5829, 5822, 5825, -1, 5829, 5731, 5712, -1, 5830, 5792, 5811, -1, 5830, 5816, 5792, -1, 5831, 5829, 5825, -1, 5832, 5825, 5826, -1, 5832, 5831, 5825, -1, 5833, 5807, 5808, -1, 5832, 5826, 5828, -1, 5832, 5828, 5834, -1, 5835, 5738, 5731, -1, 5836, 5774, 5816, -1, 5836, 5783, 5774, -1, 5835, 5829, 5831, -1, 5835, 5731, 5829, -1, 5837, 5835, 5831, -1, 5838, 5789, 5817, -1, 5839, 5834, 5840, -1, 5839, 5831, 5832, -1, 5839, 5832, 5834, -1, 5839, 5837, 5831, -1, 5838, 5811, 5789, -1, 5841, 5738, 5835, -1, 5842, 5824, 5823, -1, 5841, 5745, 5738, -1, 5841, 5835, 5837, -1, 5842, 5843, 5824, -1, 5844, 5841, 5837, -1, 5845, 5840, 5846, -1, 5845, 5839, 5840, -1, 5847, 5817, 5797, -1, 5845, 5837, 5839, -1, 5845, 5844, 5837, -1, 5847, 5797, 5827, -1, 5848, 5841, 5844, -1, 5848, 5756, 5745, -1, 5848, 5745, 5841, -1, 5849, 5836, 5816, -1, 5849, 5816, 5830, -1, 5850, 5846, 5851, -1, 5850, 5848, 5844, -1, 5850, 5845, 5846, -1, 5850, 5844, 5845, -1, 5852, 5807, 5833, -1, 5853, 5767, 5756, -1, 5852, 5827, 5807, -1, 5853, 5756, 5848, -1, 5854, 5848, 5850, -1, 5854, 5853, 5848, -1, 5855, 5783, 5836, -1, 5855, 5798, 5783, -1, 5856, 5853, 5854, -1, 5857, 5811, 5838, -1, 5857, 5830, 5811, -1, 5858, 5854, 5850, -1, 5859, 5843, 5842, -1, 5858, 5856, 5854, -1, 5859, 5860, 5843, -1, 5861, 5851, 5862, -1, 5861, 5850, 5851, -1, 5861, 5858, 5850, -1, 5863, 5767, 5853, -1, 5864, 5808, 5865, -1, 5863, 5853, 5856, -1, 5863, 5777, 5767, -1, 5863, 5856, 5858, -1, 5864, 5833, 5808, -1, 5866, 5862, 5867, -1, 5868, 5838, 5817, -1, 5866, 5861, 5862, -1, 5866, 5858, 5861, -1, 5866, 5863, 5858, -1, 5868, 5817, 5847, -1, 5869, 5777, 5863, -1, 5869, 5785, 5777, -1, 5870, 5836, 5849, -1, 5871, 5869, 5863, -1, 5870, 5855, 5836, -1, 5872, 5867, 5873, -1, 5872, 5863, 5866, -1, 5872, 5871, 5863, -1, 5872, 5866, 5867, -1, 5874, 5847, 5827, -1, 5874, 5827, 5852, -1, 5875, 5785, 5869, -1, 5875, 5869, 5871, -1, 5875, 5790, 5785, -1, 5876, 5872, 5873, -1, 5877, 5823, 5798, -1, 5876, 5873, 5878, -1, 5876, 5878, 5794, -1, 5876, 5791, 5790, -1, 5876, 5790, 5875, -1, 5877, 5798, 5855, -1, 5876, 5794, 5791, -1, 5876, 5871, 5872, -1, 5876, 5875, 5871, -1, 5879, 5864, 5865, -1, 5880, 5849, 5830, -1, 5880, 5830, 5857, -1, 5881, 5860, 5859, -1, 5881, 5882, 5860, -1, 5883, 5852, 5833, -1, 5883, 5833, 5864, -1, 5884, 5838, 5868, -1, 5884, 5857, 5838, -1, 5885, 5855, 5870, -1, 5885, 5877, 5855, -1, 5886, 5868, 5847, -1, 5886, 5847, 5874, -1, 5887, 5842, 5823, -1, 5887, 5823, 5877, -1, 5888, 5864, 5879, -1, 5888, 5883, 5864, -1, 5889, 5849, 5880, -1, 5889, 5870, 5849, -1, 5890, 5891, 5882, -1, 5890, 5882, 5881, -1, 5892, 5852, 5883, -1, 5892, 5874, 5852, -1, 5893, 5857, 5884, -1, 5893, 5880, 5857, -1, 5894, 5877, 5885, -1, 5894, 5887, 5877, -1, 5895, 5868, 5886, -1, 5895, 5884, 5868, -1, 5896, 5842, 5887, -1, 5896, 5859, 5842, -1, 5897, 5892, 5883, -1, 5897, 5883, 5888, -1, 5898, 5885, 5870, -1, 5898, 5870, 5889, -1, 5805, 5865, 5806, -1, 5805, 5879, 5865, -1, 5701, 5899, 5891, -1, 5701, 5891, 5890, -1, 5900, 5886, 5874, -1, 5900, 5874, 5892, -1, 5901, 5880, 5893, -1, 5901, 5889, 5880, -1, 5902, 5887, 5894, -1, 5902, 5896, 5887, -1, 5903, 5884, 5895, -1, 5903, 5893, 5884, -1, 5904, 5859, 5896, -1, 5904, 5881, 5859, -1, 5714, 5892, 5897, -1, 5714, 5900, 5892, -1, 5905, 5894, 5885, -1, 5905, 5885, 5898, -1, 5803, 5888, 5879, -1, 5803, 5879, 5805, -1, 5703, 5906, 5899, -1, 5703, 5899, 5701, -1, 5907, 5895, 5886, -1, 5907, 5886, 5900, -1, 5698, 5898, 5889, -1, 5698, 5889, 5901, -1, 5709, 5904, 5896, -1, 5709, 5896, 5902, -1, 5717, 5901, 5893, -1, 5717, 5893, 5903, -1, 5908, 5881, 5904, -1, 5908, 5890, 5881, -1, 5713, 5900, 5714, -1, 5713, 5907, 5900, -1, 5719, 5902, 5894, -1, 5719, 5894, 5905, -1, 5815, 5897, 5888, -1, 5815, 5888, 5803, -1, 5726, 5906, 5703, -1, 5726, 5728, 5909, -1, 5726, 5910, 5906, -1, 5726, 5909, 5910, -1, 5705, 5903, 5895, -1, 5705, 5895, 5907, -1, 5724, 5905, 5898, -1, 5724, 5898, 5698, -1, 5711, 5904, 5709, -1, 5711, 5908, 5904, -1, 5699, 5698, 5901, -1, 5699, 5901, 5717, -1, 5702, 5701, 5890, -1, 5702, 5890, 5908, -1, 5706, 5705, 5907, -1, 5706, 5907, 5713, -1, 5710, 5902, 5719, -1, 5710, 5709, 5902, -1, 5715, 5897, 5815, -1, 5715, 5714, 5897, -1, 5707, 5903, 5705, -1, 5707, 5717, 5903, -1, 5720, 5719, 5905, -1, 5720, 5905, 5724, -1, 5722, 5908, 5711, -1, 5722, 5702, 5908, -1, 5697, 5724, 5698, -1, 5911, 5912, 5913, -1, 5914, 5912, 5911, -1, 5915, 5916, 5917, -1, 5918, 5916, 5915, -1, 5919, 5920, 5921, -1, 5921, 5920, 5922, -1, 5922, 5920, 5923, -1, 5923, 5920, 5924, -1, 5925, 5926, 5927, -1, 5928, 5926, 5925, -1, 5913, 5929, 5930, -1, 5930, 5929, 5928, -1, 5928, 5929, 5926, -1, 5914, 5931, 5912, -1, 5924, 5931, 5914, -1, 5932, 5933, 5918, -1, 5918, 5933, 5916, -1, 5929, 5934, 5926, -1, 5912, 5935, 5913, -1, 5913, 5935, 5929, -1, 5919, 5936, 5920, -1, 5920, 5936, 5924, -1, 5924, 5936, 5931, -1, 5927, 5937, 5932, -1, 5932, 5937, 5933, -1, 5935, 5938, 5929, -1, 5929, 5938, 5934, -1, 5931, 5939, 5912, -1, 5912, 5939, 5935, -1, 5935, 5939, 5938, -1, 5927, 5940, 5937, -1, 5926, 5940, 5927, -1, 5939, 5941, 5938, -1, 5939, 5942, 5941, -1, 5943, 5942, 5919, -1, 5919, 5942, 5936, -1, 5931, 5942, 5939, -1, 5936, 5942, 5931, -1, 5926, 5944, 5940, -1, 5934, 5944, 5926, -1, 5943, 5945, 5942, -1, 5942, 5945, 5941, -1, 5934, 5946, 5944, -1, 5938, 5946, 5934, -1, 5938, 5947, 5946, -1, 5941, 5947, 5938, -1, 5943, 5948, 5945, -1, 5945, 5948, 5941, -1, 5941, 5948, 5947, -1, 5949, 5948, 5943, -1, 5947, 5950, 5946, -1, 5951, 5952, 5950, -1, 5953, 5954, 5955, -1, 5951, 5954, 5952, -1, 5949, 5956, 5948, -1, 5957, 5958, 5949, -1, 5949, 5958, 5956, -1, 5956, 5958, 5951, -1, 5959, 5960, 5957, -1, 5958, 5960, 5951, -1, 5957, 5960, 5958, -1, 5946, 5961, 5944, -1, 5950, 5961, 5946, -1, 5952, 5961, 5950, -1, 5962, 5963, 5964, -1, 5965, 5963, 5962, -1, 5952, 5966, 5961, -1, 5952, 5967, 5966, -1, 5954, 5967, 5952, -1, 5968, 5967, 5953, -1, 5953, 5967, 5954, -1, 5948, 5969, 5947, -1, 5970, 5971, 5965, -1, 5956, 5969, 5948, -1, 5950, 5969, 5951, -1, 5965, 5971, 5963, -1, 5947, 5969, 5950, -1, 5951, 5969, 5956, -1, 5955, 5972, 5959, -1, 5954, 5972, 5955, -1, 5970, 5973, 5971, -1, 5951, 5972, 5954, -1, 5959, 5972, 5960, -1, 5960, 5972, 5951, -1, 5944, 5974, 5940, -1, 5961, 5974, 5944, -1, 5966, 5974, 5961, -1, 5975, 5973, 5970, -1, 5964, 5976, 5977, -1, 5963, 5976, 5964, -1, 5966, 5978, 5974, -1, 5979, 5980, 5968, -1, 5967, 5980, 5966, -1, 5968, 5980, 5967, -1, 5966, 5980, 5978, -1, 5974, 5981, 5940, -1, 5982, 5983, 5975, -1, 5975, 5983, 5973, -1, 5978, 5981, 5974, -1, 5940, 5981, 5937, -1, 5976, 5984, 5977, -1, 5978, 5985, 5981, -1, 5963, 5986, 5976, -1, 5987, 5988, 5979, -1, 5979, 5988, 5980, -1, 5980, 5988, 5978, -1, 5971, 5986, 5963, -1, 5978, 5988, 5985, -1, 5981, 5989, 5937, -1, 5985, 5989, 5981, -1, 5937, 5989, 5933, -1, 5990, 5991, 5982, -1, 5982, 5991, 5983, -1, 5992, 5993, 5987, -1, 5987, 5993, 5988, -1, 5988, 5993, 5985, -1, 5986, 5994, 5976, -1, 5989, 5995, 5933, -1, 5976, 5994, 5984, -1, 5933, 5995, 5916, -1, 5973, 5996, 5971, -1, 5971, 5996, 5986, -1, 5989, 5997, 5995, -1, 5985, 5997, 5989, -1, 5993, 5997, 5985, -1, 5998, 5997, 5993, -1, 5995, 5997, 5998, -1, 5999, 6000, 5990, -1, 5990, 6000, 5991, -1, 5977, 6001, 6002, -1, 5993, 6003, 5998, -1, 6004, 6005, 5992, -1, 5992, 6005, 5993, -1, 5993, 6005, 6003, -1, 5984, 6001, 5977, -1, 5996, 6006, 5986, -1, 5995, 6007, 5916, -1, 5998, 6007, 5995, -1, 5986, 6006, 5994, -1, 6003, 6007, 5998, -1, 6008, 6009, 6004, -1, 5973, 6010, 5996, -1, 6004, 6009, 6005, -1, 5983, 6010, 5973, -1, 6005, 6009, 6003, -1, 6007, 6011, 5916, -1, 5917, 6011, 6012, -1, 5916, 6011, 5917, -1, 6013, 6014, 5999, -1, 5999, 6014, 6000, -1, 6007, 6015, 6011, -1, 6007, 6016, 6015, -1, 5994, 6017, 5984, -1, 5984, 6017, 6001, -1, 6009, 6018, 6003, -1, 6007, 6018, 6016, -1, 6003, 6018, 6007, -1, 6019, 6020, 6008, -1, 6009, 6020, 6018, -1, 6010, 6021, 5996, -1, 6018, 6020, 6016, -1, 5996, 6021, 6006, -1, 6008, 6020, 6009, -1, 6011, 6022, 6012, -1, 5983, 6023, 6010, -1, 6012, 6022, 6024, -1, 6015, 6022, 6011, -1, 5991, 6023, 5983, -1, 6016, 6025, 6015, -1, 6001, 6026, 6002, -1, 6019, 6025, 6020, -1, 6020, 6025, 6016, -1, 6024, 6027, 6028, -1, 6022, 6027, 6024, -1, 6029, 6030, 6013, -1, 6013, 6030, 6014, -1, 6027, 6031, 6028, -1, 6025, 6032, 6015, -1, 6015, 6032, 6022, -1, 6022, 6032, 6027, -1, 6027, 6032, 6031, -1, 6031, 6032, 6025, -1, 6006, 6033, 5994, -1, 6034, 6035, 6036, -1, 6031, 6035, 6028, -1, 5994, 6033, 6017, -1, 6025, 6035, 6031, -1, 6023, 6037, 6010, -1, 6038, 6035, 6034, -1, 6010, 6037, 6021, -1, 6028, 6035, 6038, -1, 6039, 6040, 6019, -1, 6036, 6040, 6039, -1, 6035, 6040, 6036, -1, 6025, 6040, 6035, -1, 6019, 6040, 6025, -1, 5991, 6041, 6023, -1, 6000, 6041, 5991, -1, 6001, 6042, 6026, -1, 6017, 6042, 6001, -1, 6043, 6044, 6029, -1, 6029, 6044, 6030, -1, 6002, 6045, 6046, -1, 6026, 6045, 6002, -1, 6021, 6047, 6006, -1, 6006, 6047, 6033, -1, 6023, 6048, 6037, -1, 6041, 6048, 6023, -1, 6014, 6049, 6000, -1, 6000, 6049, 6041, -1, 6017, 6050, 6042, -1, 6033, 6050, 6017, -1, 6051, 6052, 6043, -1, 6043, 6052, 6044, -1, 6042, 6053, 6026, -1, 6026, 6053, 6045, -1, 6021, 6054, 6047, -1, 6037, 6054, 6021, -1, 6041, 6055, 6048, -1, 6049, 6055, 6041, -1, 6014, 6056, 6049, -1, 6030, 6056, 6014, -1, 6033, 6057, 6050, -1, 6047, 6057, 6033, -1, 6058, 6059, 6051, -1, 6051, 6059, 6052, -1, 6045, 6060, 6046, -1, 6050, 6061, 6042, -1, 6042, 6061, 6053, -1, 6048, 6062, 6037, -1, 6037, 6062, 6054, -1, 6056, 6063, 6049, -1, 6049, 6063, 6055, -1, 6030, 6064, 6056, -1, 6044, 6064, 6030, -1, 6054, 6065, 6047, -1, 6047, 6065, 6057, -1, 6066, 6067, 6058, -1, 6058, 6067, 6059, -1, 6046, 6068, 6069, -1, 6060, 6068, 6046, -1, 6053, 6070, 6045, -1, 6045, 6070, 6060, -1, 6050, 6071, 6061, -1, 6057, 6071, 6050, -1, 6055, 6072, 6048, -1, 6048, 6072, 6062, -1, 6064, 6073, 6056, -1, 6056, 6073, 6063, -1, 6044, 6074, 6064, -1, 6052, 6074, 6044, -1, 6054, 6075, 6065, -1, 6062, 6075, 6054, -1, 6066, 6076, 6067, -1, 6077, 6076, 6078, -1, 6078, 6076, 6079, -1, 6079, 6076, 6066, -1, 6060, 6080, 6068, -1, 6070, 6080, 6060, -1, 6053, 6081, 6070, -1, 6061, 6081, 6053, -1, 6065, 6082, 6057, -1, 6057, 6082, 6071, -1, 6055, 6083, 6072, -1, 6063, 6083, 6055, -1, 6064, 6084, 6073, -1, 6074, 6084, 6064, -1, 6052, 6085, 6074, -1, 6059, 6085, 6052, -1, 6072, 6086, 6062, -1, 6062, 6086, 6075, -1, 6070, 6087, 6080, -1, 6081, 6087, 6070, -1, 6071, 6088, 6061, -1, 6061, 6088, 6081, -1, 6065, 6089, 6082, -1, 6075, 6089, 6065, -1, 6069, 6038, 6090, -1, 6090, 6038, 6034, -1, 6068, 6038, 6069, -1, 6063, 6091, 6083, -1, 6073, 6091, 6063, -1, 6074, 6092, 6084, -1, 6085, 6092, 6074, -1, 6059, 6093, 6085, -1, 6067, 6093, 6059, -1, 6083, 6094, 6072, -1, 6072, 6094, 6086, -1, 6088, 6095, 6081, -1, 6081, 6095, 6087, -1, 6082, 6096, 6071, -1, 6071, 6096, 6088, -1, 6086, 6097, 6075, -1, 6075, 6097, 6089, -1, 6080, 6028, 6068, -1, 6068, 6028, 6038, -1, 6084, 6098, 6073, -1, 6073, 6098, 6091, -1, 6085, 6099, 6092, -1, 6093, 6099, 6085, -1, 6100, 6101, 6077, -1, 6067, 6101, 6093, -1, 6076, 6101, 6067, -1, 6077, 6101, 6076, -1, 6083, 6102, 6094, -1, 6091, 6102, 6083, -1, 6088, 5915, 6095, -1, 6096, 5915, 6088, -1, 6089, 6103, 6082, -1, 6082, 6103, 6096, -1, 6086, 6104, 6097, -1, 6094, 6104, 6086, -1, 6087, 6024, 6080, -1, 6080, 6024, 6028, -1, 6092, 6105, 6084, -1, 6084, 6105, 6098, -1, 5921, 6106, 6100, -1, 6100, 6106, 6101, -1, 6093, 6106, 6099, -1, 6101, 6106, 6093, -1, 6098, 5911, 6091, -1, 6091, 5911, 6102, -1, 6096, 5918, 5915, -1, 6103, 5918, 6096, -1, 6089, 6107, 6103, -1, 6103, 6107, 5918, -1, 6097, 6107, 6089, -1, 6094, 5930, 6104, -1, 6102, 5930, 6094, -1, 6095, 6012, 6087, -1, 6087, 6012, 6024, -1, 6092, 5923, 6105, -1, 6099, 5923, 6092, -1, 6098, 5914, 5911, -1, 6105, 5914, 6098, -1, 6107, 5932, 5918, -1, 6097, 5925, 6107, -1, 6104, 5925, 6097, -1, 6102, 5913, 5930, -1, 5911, 5913, 6102, -1, 5915, 5917, 6095, -1, 6095, 5917, 6012, -1, 6106, 5922, 6099, -1, 6099, 5922, 5923, -1, 5921, 5922, 6106, -1, 6105, 5924, 5914, -1, 5923, 5924, 6105, -1, 5925, 5927, 6107, -1, 6107, 5927, 5932, -1, 5930, 5928, 6104, -1, 6104, 5928, 5925, -1, 6108, 6109, 6110, -1, 6111, 6112, 6113, -1, 6111, 6113, 6114, -1, 6115, 6116, 6109, -1, 6115, 6117, 6116, -1, 6118, 6119, 6120, -1, 6118, 6120, 6121, -1, 6122, 6123, 6124, -1, 6122, 6124, 6125, -1, 6126, 6127, 6128, -1, 6126, 6128, 6129, -1, 6130, 6131, 6119, -1, 6130, 6114, 6131, -1, 6130, 6119, 6118, -1, 6132, 6125, 6133, -1, 6132, 6133, 6134, -1, 6135, 6109, 6108, -1, 6135, 6115, 6109, -1, 6136, 6134, 6112, -1, 6136, 6112, 6111, -1, 6137, 6138, 6139, -1, 6137, 6139, 6117, -1, 6137, 6140, 6138, -1, 6137, 6117, 6115, -1, 6141, 6130, 6118, -1, 6142, 6108, 6123, -1, 6142, 6123, 6122, -1, 6143, 6121, 6127, -1, 6143, 6127, 6126, -1, 6144, 6111, 6114, -1, 6144, 6114, 6130, -1, 6145, 6125, 6132, -1, 6145, 6122, 6125, -1, 6146, 6115, 6135, -1, 6146, 6140, 6137, -1, 6146, 6137, 6115, -1, 6147, 6132, 6134, -1, 6147, 6134, 6136, -1, 6148, 6130, 6141, -1, 6148, 6144, 6130, -1, 6149, 6135, 6108, -1, 6149, 6108, 6142, -1, 6150, 6118, 6121, -1, 6150, 6121, 6143, -1, 6151, 6136, 6111, -1, 6151, 6111, 6144, -1, 6152, 6142, 6122, -1, 6152, 6122, 6145, -1, 6153, 6132, 6147, -1, 6153, 6145, 6132, -1, 6154, 6151, 6144, -1, 6154, 6144, 6148, -1, 6155, 6156, 6140, -1, 6155, 6140, 6146, -1, 6155, 6135, 6149, -1, 6155, 6146, 6135, -1, 6157, 6141, 6118, -1, 6157, 6118, 6150, -1, 6158, 6136, 6151, -1, 6158, 6147, 6136, -1, 6159, 6149, 6142, -1, 6160, 6161, 6162, -1, 6163, 6164, 6165, -1, 6159, 6142, 6152, -1, 6166, 6152, 6145, -1, 6163, 6165, 6167, -1, 6166, 6145, 6153, -1, 6168, 6158, 6151, -1, 6169, 6170, 6164, -1, 6169, 6164, 6163, -1, 6168, 6151, 6154, -1, 6171, 6141, 6157, -1, 6172, 6173, 6170, -1, 6171, 6148, 6141, -1, 6174, 6153, 6147, -1, 6172, 6170, 6169, -1, 6174, 6147, 6158, -1, 6175, 6167, 6176, -1, 6177, 6155, 6149, -1, 6177, 6156, 6155, -1, 6175, 6163, 6167, -1, 6177, 6149, 6159, -1, 6178, 6179, 6173, -1, 6180, 6159, 6152, -1, 6180, 6152, 6166, -1, 6181, 6158, 6168, -1, 6178, 6173, 6172, -1, 6181, 6174, 6158, -1, 6182, 6154, 6148, -1, 6183, 6176, 6184, -1, 6183, 6175, 6176, -1, 6182, 6148, 6171, -1, 6185, 6163, 6175, -1, 6186, 6166, 6153, -1, 6186, 6153, 6174, -1, 6185, 6169, 6163, -1, 6187, 6159, 6180, -1, 6188, 6189, 6179, -1, 6187, 6177, 6159, -1, 6187, 6156, 6177, -1, 6187, 6190, 6156, -1, 6188, 6179, 6178, -1, 6191, 6174, 6181, -1, 6191, 6186, 6174, -1, 6192, 6154, 6182, -1, 6192, 6168, 6154, -1, 6193, 6185, 6175, -1, 6193, 6175, 6183, -1, 6194, 6180, 6166, -1, 6194, 6166, 6186, -1, 6195, 6172, 6169, -1, 6195, 6169, 6185, -1, 6196, 6194, 6186, -1, 6196, 6186, 6191, -1, 6197, 6183, 6184, -1, 6198, 6199, 6189, -1, 6200, 6168, 6192, -1, 6200, 6181, 6168, -1, 6198, 6189, 6188, -1, 6201, 6180, 6194, -1, 6201, 6187, 6180, -1, 6202, 6185, 6193, -1, 6201, 6190, 6187, -1, 6203, 6161, 6190, -1, 6203, 6201, 6194, -1, 6203, 6194, 6196, -1, 6203, 6190, 6201, -1, 6202, 6195, 6185, -1, 6204, 6191, 6181, -1, 6204, 6181, 6200, -1, 6205, 6172, 6195, -1, 6205, 6178, 6172, -1, 6206, 6196, 6191, -1, 6206, 6191, 6204, -1, 6207, 6162, 6161, -1, 6207, 6208, 6162, -1, 6207, 6206, 6208, -1, 6207, 6203, 6196, -1, 6209, 6183, 6197, -1, 6207, 6161, 6203, -1, 6207, 6196, 6206, -1, 6209, 6193, 6183, -1, 6210, 6211, 6199, -1, 6212, 6213, 6214, -1, 6210, 6199, 6198, -1, 6215, 6184, 6216, -1, 6212, 6214, 6217, -1, 6218, 6214, 6213, -1, 6218, 6219, 6220, -1, 6215, 6197, 6184, -1, 6221, 6195, 6202, -1, 6218, 6213, 6219, -1, 6222, 6220, 6223, -1, 6222, 6214, 6218, -1, 6222, 6218, 6220, -1, 6224, 6223, 6225, -1, 6224, 6225, 6217, -1, 6221, 6205, 6195, -1, 6224, 6217, 6214, -1, 6224, 6222, 6223, -1, 6224, 6214, 6222, -1, 6226, 6227, 6213, -1, 6228, 6178, 6205, -1, 6226, 6129, 6227, -1, 6228, 6188, 6178, -1, 6226, 6213, 6212, -1, 6229, 6226, 6212, -1, 6230, 6193, 6209, -1, 6231, 6229, 6212, -1, 6231, 6217, 6232, -1, 6231, 6232, 6233, -1, 6230, 6202, 6193, -1, 6231, 6212, 6217, -1, 6234, 6235, 6211, -1, 6236, 6129, 6226, -1, 6236, 6126, 6129, -1, 6234, 6211, 6210, -1, 6236, 6226, 6229, -1, 6237, 6209, 6197, -1, 6238, 6236, 6229, -1, 6237, 6197, 6215, -1, 6239, 6229, 6231, -1, 6239, 6231, 6233, -1, 6239, 6238, 6229, -1, 6239, 6233, 6240, -1, 6241, 6236, 6238, -1, 6241, 6126, 6236, -1, 6241, 6143, 6126, -1, 6242, 6205, 6221, -1, 6242, 6228, 6205, -1, 6243, 6215, 6216, -1, 6244, 6241, 6238, -1, 6245, 6244, 6238, -1, 6245, 6238, 6239, -1, 6246, 6188, 6228, -1, 6245, 6239, 6240, -1, 6245, 6240, 6247, -1, 6248, 6150, 6143, -1, 6248, 6143, 6241, -1, 6248, 6241, 6244, -1, 6246, 6198, 6188, -1, 6249, 6221, 6202, -1, 6249, 6202, 6230, -1, 6250, 6248, 6244, -1, 6251, 6244, 6245, -1, 6251, 6250, 6244, -1, 6251, 6245, 6247, -1, 6252, 6253, 6235, -1, 6251, 6247, 6254, -1, 6255, 6157, 6150, -1, 6252, 6235, 6234, -1, 6255, 6150, 6248, -1, 6255, 6248, 6250, -1, 6256, 6209, 6237, -1, 6257, 6255, 6250, -1, 6258, 6254, 6259, -1, 6256, 6230, 6209, -1, 6258, 6250, 6251, -1, 6260, 6228, 6242, -1, 6258, 6251, 6254, -1, 6258, 6257, 6250, -1, 6261, 6171, 6157, -1, 6261, 6157, 6255, -1, 6261, 6255, 6257, -1, 6260, 6246, 6228, -1, 6262, 6258, 6259, -1, 6262, 6259, 6263, -1, 6264, 6215, 6243, -1, 6262, 6257, 6258, -1, 6262, 6261, 6257, -1, 6264, 6237, 6215, -1, 6265, 6210, 6198, -1, 6265, 6198, 6246, -1, 6266, 6171, 6261, -1, 6266, 6182, 6171, -1, 6267, 6261, 6262, -1, 6267, 6266, 6261, -1, 6268, 6221, 6249, -1, 6269, 6266, 6267, -1, 6268, 6242, 6221, -1, 6270, 6271, 6253, -1, 6272, 6267, 6262, -1, 6270, 6253, 6252, -1, 6272, 6269, 6267, -1, 6273, 6263, 6274, -1, 6273, 6262, 6263, -1, 6275, 6216, 6276, -1, 6273, 6272, 6262, -1, 6275, 6243, 6216, -1, 6277, 6182, 6266, -1, 6277, 6192, 6182, -1, 6277, 6266, 6269, -1, 6277, 6269, 6272, -1, 6278, 6277, 6272, -1, 6278, 6274, 6279, -1, 6280, 6249, 6230, -1, 6278, 6273, 6274, -1, 6280, 6230, 6256, -1, 6278, 6272, 6273, -1, 6281, 6200, 6192, -1, 6281, 6192, 6277, -1, 6282, 6265, 6246, -1, 6282, 6246, 6260, -1, 6283, 6281, 6277, -1, 6284, 6279, 6285, -1, 6286, 6256, 6237, -1, 6284, 6277, 6278, -1, 6286, 6237, 6264, -1, 6284, 6278, 6279, -1, 6284, 6283, 6277, -1, 6287, 6281, 6283, -1, 6288, 6210, 6265, -1, 6287, 6200, 6281, -1, 6288, 6234, 6210, -1, 6287, 6204, 6200, -1, 6289, 6287, 6283, -1, 6289, 6285, 6290, -1, 6289, 6290, 6208, -1, 6289, 6208, 6206, -1, 6291, 6275, 6276, -1, 6289, 6284, 6285, -1, 6289, 6283, 6284, -1, 6289, 6206, 6204, -1, 6289, 6204, 6287, -1, 6292, 6260, 6242, -1, 6292, 6242, 6268, -1, 6293, 6294, 6271, -1, 6293, 6271, 6270, -1, 6295, 6264, 6243, -1, 6295, 6243, 6275, -1, 6296, 6268, 6249, -1, 6296, 6249, 6280, -1, 6297, 6265, 6282, -1, 6297, 6288, 6265, -1, 6298, 6280, 6256, -1, 6298, 6256, 6286, -1, 6299, 6252, 6234, -1, 6299, 6234, 6288, -1, 6300, 6275, 6291, -1, 6300, 6295, 6275, -1, 6301, 6260, 6292, -1, 6301, 6282, 6260, -1, 6302, 6303, 6294, -1, 6302, 6294, 6293, -1, 6304, 6264, 6295, -1, 6304, 6286, 6264, -1, 6305, 6268, 6296, -1, 6305, 6292, 6268, -1, 6306, 6299, 6288, -1, 6306, 6288, 6297, -1, 6307, 6296, 6280, -1, 6307, 6280, 6298, -1, 6308, 6270, 6252, -1, 6308, 6252, 6299, -1, 6309, 6295, 6300, -1, 6309, 6304, 6295, -1, 6310, 6297, 6282, -1, 6310, 6282, 6301, -1, 6219, 6276, 6220, -1, 6219, 6291, 6276, -1, 6116, 6303, 6302, -1, 6116, 6311, 6303, -1, 6312, 6286, 6304, -1, 6312, 6298, 6286, -1, 6313, 6301, 6292, -1, 6313, 6292, 6305, -1, 6314, 6299, 6306, -1, 6314, 6308, 6299, -1, 6315, 6305, 6296, -1, 6315, 6296, 6307, -1, 6316, 6293, 6270, -1, 6316, 6270, 6308, -1, 6128, 6312, 6304, -1, 6128, 6304, 6309, -1, 6317, 6306, 6297, -1, 6317, 6297, 6310, -1, 6213, 6291, 6219, -1, 6213, 6300, 6291, -1, 6117, 6311, 6116, -1, 6117, 6318, 6311, -1, 6319, 6307, 6298, -1, 6319, 6298, 6312, -1, 6113, 6310, 6301, -1, 6113, 6301, 6313, -1, 6124, 6316, 6308, -1, 6124, 6308, 6314, -1, 6131, 6305, 6315, -1, 6131, 6313, 6305, -1, 6131, 6113, 6313, -1, 6110, 6302, 6293, -1, 6110, 6293, 6316, -1, 6127, 6312, 6128, -1, 6127, 6319, 6312, -1, 6133, 6314, 6306, -1, 6133, 6306, 6317, -1, 6227, 6309, 6300, -1, 6227, 6300, 6213, -1, 6139, 6320, 6318, -1, 6139, 6321, 6320, -1, 6139, 6138, 6321, -1, 6139, 6318, 6117, -1, 6120, 6307, 6319, -1, 6120, 6315, 6307, -1, 6112, 6310, 6113, -1, 6112, 6317, 6310, -1, 6123, 6110, 6316, -1, 6123, 6316, 6124, -1, 6114, 6113, 6131, -1, 6109, 6116, 6302, -1, 6109, 6302, 6110, -1, 6121, 6319, 6127, -1, 6121, 6120, 6319, -1, 6125, 6124, 6314, -1, 6125, 6314, 6133, -1, 6129, 6309, 6227, -1, 6129, 6128, 6309, -1, 6119, 6315, 6120, -1, 6119, 6131, 6315, -1, 6134, 6133, 6317, -1, 6134, 6317, 6112, -1, 6108, 6110, 6123, -1, 6322, 6323, 6324, -1, 6325, 6323, 6322, -1, 6323, 6326, 6324, -1, 6327, 6328, 6329, -1, 6329, 6330, 6331, -1, 6328, 6330, 6329, -1, 6331, 6332, 6333, -1, 6330, 6332, 6331, -1, 6333, 6334, 6335, -1, 6332, 6334, 6333, -1, 6335, 6336, 6337, -1, 6334, 6336, 6335, -1, 6337, 6338, 6339, -1, 6336, 6338, 6337, -1, 6339, 6340, 6341, -1, 6338, 6340, 6339, -1, 6341, 6342, 6343, -1, 6340, 6342, 6341, -1, 6343, 6344, 6345, -1, 6342, 6344, 6343, -1, 6345, 6346, 6347, -1, 6344, 6346, 6345, -1, 6347, 6348, 6349, -1, 6346, 6348, 6347, -1, 6349, 6350, 6351, -1, 6348, 6350, 6349, -1, 6351, 6352, 6353, -1, 6350, 6352, 6351, -1, 6353, 6354, 6355, -1, 6352, 6354, 6353, -1, 6354, 6356, 6355, -1, 6355, 6357, 6358, -1, 6356, 6357, 6355, -1, 6358, 6359, 6360, -1, 6357, 6359, 6358, -1, 6360, 6325, 6322, -1, 6359, 6325, 6360, -1, 6361, 6362, 6363, -1, 6364, 6362, 6361, -1, 6362, 6365, 6363, -1, 6366, 6367, 6368, -1, 6368, 6369, 6370, -1, 6367, 6369, 6368, -1, 6370, 6371, 6372, -1, 6369, 6371, 6370, -1, 6372, 6373, 6374, -1, 6371, 6373, 6372, -1, 6374, 6375, 6376, -1, 6373, 6375, 6374, -1, 6376, 6377, 6378, -1, 6375, 6377, 6376, -1, 6378, 6379, 6380, -1, 6377, 6379, 6378, -1, 6380, 6381, 6382, -1, 6379, 6381, 6380, -1, 6382, 6383, 6384, -1, 6381, 6383, 6382, -1, 6384, 6385, 6386, -1, 6383, 6385, 6384, -1, 6386, 6387, 6388, -1, 6385, 6387, 6386, -1, 6388, 6389, 6390, -1, 6387, 6389, 6388, -1, 6390, 6391, 6392, -1, 6389, 6391, 6390, -1, 6392, 6393, 6394, -1, 6391, 6393, 6392, -1, 6393, 6395, 6394, -1, 6394, 6396, 6397, -1, 6395, 6396, 6394, -1, 6397, 6398, 6399, -1, 6396, 6398, 6397, -1, 6399, 6364, 6361, -1, 6398, 6364, 6399, -1, 4728, 6400, 4729, -1, 4729, 6401, 4725, -1, 6400, 6401, 4729, -1, 4725, 6402, 4723, -1, 6401, 6402, 4725, -1, 4723, 6403, 4737, -1, 6402, 6403, 4723, -1, 4737, 6404, 4751, -1, 6403, 6404, 4737, -1, 6404, 6405, 4751, -1, 4751, 6406, 4757, -1, 4757, 6406, 4762, -1, 6405, 6406, 4751, -1, 4762, 6407, 4774, -1, 6406, 6407, 4762, -1, 4774, 6408, 4791, -1, 6407, 6408, 4774, -1, 6408, 6409, 4791, -1, 4791, 6410, 4792, -1, 6409, 6410, 4791, -1, 4792, 6411, 4796, -1, 6410, 6411, 4792, -1, 4796, 6412, 4804, -1, 6411, 6412, 4796, -1, 4804, 6413, 4712, -1, 4712, 6413, 4713, -1, 6412, 6413, 4804, -1, 6413, 6414, 4713, -1, 6415, 4924, 4926, -1, 6416, 4926, 4972, -1, 6416, 6415, 4926, -1, 6417, 4972, 5054, -1, 6417, 6416, 4972, -1, 6418, 5054, 5049, -1, 6418, 6417, 5054, -1, 6419, 5049, 5044, -1, 6419, 6418, 5049, -1, 6420, 5044, 5038, -1, 6420, 6419, 5044, -1, 6421, 5038, 5027, -1, 6421, 6420, 5038, -1, 6422, 5027, 5023, -1, 6422, 6421, 5027, -1, 6423, 5023, 5016, -1, 6423, 6422, 5023, -1, 6424, 5016, 5011, -1, 6424, 6423, 5016, -1, 6425, 5011, 5004, -1, 6425, 6424, 5011, -1, 6426, 5004, 4997, -1, 6426, 6425, 5004, -1, 6427, 4997, 4996, -1, 6427, 6426, 4997, -1, 6428, 4996, 4978, -1, 6428, 6427, 4996, -1, 6429, 4978, 4989, -1, 6429, 6428, 4978, -1, 6430, 4989, 4986, -1, 6430, 6429, 4989, -1, 6431, 6430, 4986, -1, 6432, 6433, 5122, -1, 5122, 6433, 6434, -1, 6434, 6433, 6435, -1, 6435, 6436, 6437, -1, 6433, 6436, 6435, -1, 6437, 6438, 6439, -1, 6436, 6438, 6437, -1, 6439, 6440, 6441, -1, 6438, 6440, 6439, -1, 6441, 6442, 6443, -1, 6440, 6442, 6441, -1, 6443, 6444, 6445, -1, 6442, 6444, 6443, -1, 6444, 6446, 6445, -1, 6445, 6447, 6448, -1, 6448, 6447, 6449, -1, 6446, 6447, 6445, -1, 6449, 6450, 6451, -1, 6447, 6450, 6449, -1, 6451, 6452, 6453, -1, 6450, 6452, 6451, -1, 6452, 6454, 6453, -1, 6453, 6455, 6456, -1, 6456, 6455, 6457, -1, 6454, 6455, 6453, -1, 6455, 6458, 6457, -1, 6457, 6459, 5139, -1, 6458, 6459, 6457, -1, 6460, 5399, 6461, -1, 6462, 6461, 6463, -1, 6462, 6460, 6461, -1, 6464, 6463, 6465, -1, 6464, 6462, 6463, -1, 6466, 6465, 6467, -1, 6466, 6464, 6465, -1, 6468, 6467, 6469, -1, 6468, 6466, 6467, -1, 6470, 6469, 6471, -1, 6470, 6468, 6469, -1, 6472, 6471, 6473, -1, 6472, 6470, 6471, -1, 6474, 6473, 6475, -1, 6474, 6472, 6473, -1, 6476, 6475, 6477, -1, 6476, 6474, 6475, -1, 6478, 6477, 6479, -1, 6478, 6476, 6477, -1, 6480, 6479, 6481, -1, 6480, 6478, 6479, -1, 6482, 6481, 6483, -1, 6482, 6480, 6481, -1, 6484, 6483, 6485, -1, 6484, 6482, 6483, -1, 6486, 6485, 6487, -1, 6486, 6484, 6485, -1, 6488, 6487, 6489, -1, 6488, 6486, 6487, -1, 6490, 6489, 5384, -1, 6490, 6488, 6489, -1, 6491, 6490, 5384, -1, 5000, 6492, 4975, -1, 6493, 6494, 6495, -1, 6496, 6492, 5000, -1, 6497, 6498, 6499, -1, 6497, 6500, 6498, -1, 5388, 6501, 6502, -1, 5388, 5413, 6501, -1, 4943, 6503, 4937, -1, 5374, 6502, 6504, -1, 5374, 5388, 6502, -1, 6505, 6506, 6507, -1, 6508, 6499, 6509, -1, 5364, 6504, 6510, -1, 6508, 6497, 6499, -1, 5364, 5374, 6504, -1, 6511, 6512, 6513, -1, 6514, 6494, 6493, -1, 5354, 6510, 6515, -1, 5354, 5364, 6510, -1, 6516, 6511, 6517, -1, 5347, 5354, 6515, -1, 5347, 6515, 6518, -1, 6519, 6505, 6520, -1, 6521, 6514, 6522, -1, 5344, 5347, 6518, -1, 6513, 6517, 6511, -1, 6523, 6513, 6512, -1, 5344, 6518, 6524, -1, 6525, 6523, 6526, -1, 6527, 6525, 6528, -1, 6529, 6527, 6530, -1, 6503, 6531, 4937, -1, 6532, 6509, 6529, -1, 6533, 6503, 4943, -1, 6534, 6533, 4954, -1, 6535, 6534, 4963, -1, 6536, 6535, 4963, -1, 5339, 6524, 6537, -1, 6492, 6536, 4975, -1, 6520, 6538, 6519, -1, 6507, 6520, 6505, -1, 5339, 5344, 6524, -1, 6539, 6507, 6506, -1, 4954, 6533, 4943, -1, 6540, 6539, 6541, -1, 6542, 6540, 6543, -1, 6493, 6522, 6514, -1, 6532, 6508, 6509, -1, 6530, 6532, 6529, -1, 5340, 5339, 6537, -1, 6528, 6530, 6527, -1, 5340, 6537, 4929, -1, 6526, 6528, 6525, -1, 6512, 6526, 6523, -1, 6543, 6521, 6542, -1, 6543, 6514, 6521, -1, 6544, 6545, 4934, -1, 6546, 4929, 4928, -1, 6546, 5340, 4929, -1, 6547, 6544, 4934, -1, 4963, 6534, 4954, -1, 4937, 6547, 4934, -1, 4937, 6548, 6547, -1, 6541, 6543, 6540, -1, 6531, 6548, 4937, -1, 6494, 4928, 4934, -1, 6494, 4934, 6545, -1, 6494, 6546, 4928, -1, 6549, 6494, 6545, -1, 4975, 6536, 4963, -1, 6550, 6545, 6551, -1, 6550, 6549, 6545, -1, 6495, 6494, 6549, -1, 6506, 6541, 6539, -1, 6500, 6550, 6551, -1, 6500, 6551, 6498, -1, 6552, 6553, 5535, -1, 5535, 6553, 6554, -1, 6554, 6553, 6555, -1, 6555, 6556, 6557, -1, 6553, 6556, 6555, -1, 6557, 6558, 6559, -1, 6556, 6558, 6557, -1, 6558, 6560, 6559, -1, 6559, 6561, 6562, -1, 6562, 6561, 6563, -1, 6560, 6561, 6559, -1, 6563, 6564, 6565, -1, 6561, 6564, 6563, -1, 6565, 6566, 6567, -1, 6564, 6566, 6565, -1, 6566, 6568, 6567, -1, 6567, 6569, 6570, -1, 6570, 6569, 6571, -1, 6568, 6569, 6567, -1, 6571, 6572, 6573, -1, 6569, 6572, 6571, -1, 6573, 6574, 6575, -1, 6572, 6574, 6573, -1, 6575, 6576, 6577, -1, 6574, 6576, 6575, -1, 6577, 6578, 5550, -1, 6576, 6578, 6577, -1, 6578, 6579, 5550, -1, 6580, 5810, 6581, -1, 6580, 6582, 5810, -1, 6583, 6581, 6584, -1, 6583, 6580, 6581, -1, 6585, 6584, 6586, -1, 6585, 6583, 6584, -1, 6587, 6586, 6588, -1, 6587, 6585, 6586, -1, 6589, 6588, 6590, -1, 6589, 6587, 6588, -1, 6591, 6590, 6592, -1, 6591, 6589, 6590, -1, 6593, 6592, 6594, -1, 6593, 6591, 6592, -1, 6595, 6594, 6596, -1, 6595, 6593, 6594, -1, 6597, 6596, 6598, -1, 6597, 6595, 6596, -1, 6599, 6598, 6600, -1, 6599, 6597, 6598, -1, 6601, 6600, 6602, -1, 6601, 6599, 6600, -1, 6603, 6602, 6604, -1, 6603, 6601, 6602, -1, 6605, 6604, 6606, -1, 6605, 6603, 6604, -1, 6607, 6606, 6608, -1, 6607, 6605, 6606, -1, 6609, 6610, 5796, -1, 6609, 6608, 6610, -1, 6609, 6607, 6608, -1, 6611, 6609, 5796, -1, 6612, 6613, 6614, -1, 6612, 6615, 6616, -1, 6612, 6614, 6615, -1, 6617, 6612, 6616, -1, 6618, 6616, 6619, -1, 6618, 6617, 6616, -1, 6620, 6619, 6621, -1, 6620, 6618, 6619, -1, 6622, 6621, 6623, -1, 6622, 6620, 6621, -1, 6624, 6623, 6625, -1, 6624, 6622, 6623, -1, 6626, 6625, 6627, -1, 6626, 6624, 6625, -1, 6628, 6627, 6629, -1, 6628, 6626, 6627, -1, 6630, 6629, 6631, -1, 6630, 6628, 6629, -1, 6632, 6631, 6633, -1, 6632, 6630, 6631, -1, 6634, 6633, 6635, -1, 6634, 6632, 6633, -1, 6636, 6635, 6637, -1, 6636, 6634, 6635, -1, 6638, 6637, 6639, -1, 6638, 6636, 6637, -1, 6640, 6639, 6641, -1, 6640, 6638, 6639, -1, 6642, 6641, 6643, -1, 6642, 6640, 6641, -1, 6644, 6643, 6645, -1, 6644, 6642, 6643, -1, 6646, 6647, 6648, -1, 6646, 6648, 6649, -1, 6650, 6649, 6651, -1, 6650, 6646, 6649, -1, 6652, 6651, 6653, -1, 6652, 6650, 6651, -1, 6654, 6653, 6655, -1, 6654, 6652, 6653, -1, 6656, 6655, 6657, -1, 6656, 6654, 6655, -1, 6658, 6657, 6659, -1, 6658, 6656, 6657, -1, 6660, 6659, 6661, -1, 6660, 6658, 6659, -1, 6662, 6661, 6516, -1, 6662, 6660, 6661, -1, 6663, 6662, 6516, -1, 6664, 6516, 6665, -1, 6664, 6663, 6516, -1, 6666, 6665, 6667, -1, 6666, 6664, 6665, -1, 6668, 6667, 6669, -1, 6668, 6666, 6667, -1, 6670, 6669, 6671, -1, 6670, 6668, 6669, -1, 6672, 6671, 6673, -1, 6672, 6670, 6671, -1, 6674, 6673, 6675, -1, 6674, 6672, 6673, -1, 6676, 6675, 6677, -1, 6676, 6674, 6675, -1, 6678, 6676, 6677, -1, 6678, 6677, 6629, -1, 6679, 6678, 6629, -1, 5962, 6680, 5965, -1, 5965, 6681, 5970, -1, 6680, 6681, 5965, -1, 5970, 6682, 5975, -1, 6681, 6682, 5970, -1, 5975, 6683, 5982, -1, 6682, 6683, 5975, -1, 5982, 6684, 5990, -1, 6683, 6684, 5982, -1, 5990, 6685, 5999, -1, 6684, 6685, 5990, -1, 6685, 6686, 5999, -1, 6013, 6687, 6029, -1, 5999, 6687, 6013, -1, 6686, 6687, 5999, -1, 6029, 6688, 6043, -1, 6687, 6688, 6029, -1, 6043, 6689, 6051, -1, 6688, 6689, 6043, -1, 6051, 6690, 6058, -1, 6689, 6690, 6051, -1, 6058, 6691, 6066, -1, 6690, 6691, 6058, -1, 6066, 6692, 6079, -1, 6691, 6692, 6066, -1, 6692, 6693, 6079, -1, 6079, 6694, 6078, -1, 6693, 6694, 6079, -1, 6695, 6696, 6697, -1, 6698, 6672, 6674, -1, 6698, 6670, 6672, -1, 6699, 6700, 6162, -1, 6162, 6700, 6160, -1, 6701, 6699, 6208, -1, 6208, 6699, 6162, -1, 6702, 6701, 6208, -1, 6703, 6702, 6290, -1, 6704, 6703, 6285, -1, 5906, 6705, 5899, -1, 6706, 6704, 6279, -1, 6707, 6706, 6274, -1, 6708, 6707, 6263, -1, 6709, 6710, 6668, -1, 6711, 6698, 6674, -1, 6712, 6713, 5824, -1, 6714, 6711, 6676, -1, 6715, 6714, 6678, -1, 6678, 6679, 6715, -1, 6676, 6678, 6714, -1, 6674, 6676, 6711, -1, 6716, 6712, 5843, -1, 6717, 6716, 5860, -1, 6718, 6717, 5882, -1, 6719, 6718, 5891, -1, 6705, 6719, 5899, -1, 6720, 6705, 5906, -1, 6721, 6720, 5910, -1, 5843, 6712, 5824, -1, 6290, 6285, 6703, -1, 5910, 6720, 5906, -1, 5860, 6716, 5843, -1, 6722, 6723, 6663, -1, 6722, 6663, 6664, -1, 6208, 6290, 6702, -1, 6708, 6259, 6724, -1, 6263, 6259, 6708, -1, 5909, 6721, 5910, -1, 6725, 6722, 6664, -1, 6679, 6721, 5909, -1, 6725, 6664, 6666, -1, 5882, 6717, 5860, -1, 6726, 6679, 5909, -1, 6700, 6715, 6679, -1, 6274, 6263, 6707, -1, 6710, 6725, 6666, -1, 6727, 6700, 6679, -1, 6727, 6679, 6726, -1, 6727, 6160, 6700, -1, 6710, 6666, 6668, -1, 5891, 6718, 5882, -1, 6728, 6727, 6726, -1, 6728, 6726, 6729, -1, 6730, 6729, 6731, -1, 6730, 6728, 6729, -1, 6279, 6274, 6706, -1, 6732, 6731, 6733, -1, 6732, 6730, 6731, -1, 6709, 6668, 6670, -1, 6734, 6733, 6735, -1, 5899, 6719, 5891, -1, 6734, 6732, 6733, -1, 6736, 6735, 6737, -1, 6736, 6734, 6735, -1, 6285, 6279, 6704, -1, 6696, 6737, 6697, -1, 6696, 6736, 6737, -1, 6698, 6709, 6670, -1, 6695, 6697, 6738, -1, 6739, 6165, 6164, -1, 6739, 6740, 6165, -1, 6741, 6164, 6170, -1, 6741, 6739, 6164, -1, 6742, 6170, 6173, -1, 6742, 6741, 6170, -1, 6743, 6173, 6179, -1, 6743, 6742, 6173, -1, 6744, 6179, 6189, -1, 6744, 6743, 6179, -1, 6745, 6189, 6199, -1, 6745, 6744, 6189, -1, 6746, 6199, 6211, -1, 6746, 6745, 6199, -1, 6747, 6211, 6235, -1, 6747, 6746, 6211, -1, 6748, 6235, 6253, -1, 6748, 6747, 6235, -1, 6749, 6253, 6271, -1, 6749, 6748, 6253, -1, 6750, 6271, 6294, -1, 6750, 6749, 6271, -1, 6751, 6294, 6303, -1, 6751, 6750, 6294, -1, 6752, 6303, 6311, -1, 6752, 6751, 6303, -1, 6753, 6311, 6318, -1, 6753, 6752, 6311, -1, 6754, 6318, 6320, -1, 6754, 6320, 6321, -1, 6754, 6753, 6318, -1, 6755, 6754, 6321, -1, 6756, 6757, 6758, -1, 6759, 6758, 6760, -1, 6759, 6756, 6758, -1, 6761, 6760, 6762, -1, 6761, 6759, 6760, -1, 6763, 6761, 6762, -1, 6764, 6762, 6765, -1, 6764, 6763, 6762, -1, 6766, 6765, 6767, -1, 6766, 6764, 6765, -1, 6768, 6767, 6769, -1, 6768, 6766, 6767, -1, 6770, 6769, 6771, -1, 6770, 6768, 6769, -1, 6772, 6771, 6773, -1, 6772, 6770, 6771, -1, 6774, 6773, 6775, -1, 6774, 6772, 6773, -1, 6776, 6775, 6777, -1, 6776, 6774, 6775, -1, 6778, 6777, 6779, -1, 6778, 6776, 6777, -1, 6780, 6779, 6781, -1, 6780, 6778, 6779, -1, 6782, 6781, 6783, -1, 6782, 6780, 6781, -1, 6784, 6783, 6785, -1, 6784, 6782, 6783, -1, 6786, 6785, 6787, -1, 6786, 6784, 6785, -1, 6788, 6786, 6787, -1, 6788, 6787, 6789, -1, 6790, 6791, 6792, -1, 6790, 6792, 6793, -1, 6794, 6793, 6795, -1, 6794, 6790, 6793, -1, 6796, 6795, 6797, -1, 6796, 6794, 6795, -1, 6798, 6797, 6799, -1, 6798, 6796, 6797, -1, 6800, 6799, 6801, -1, 6800, 6798, 6799, -1, 6802, 6801, 6803, -1, 6802, 6800, 6801, -1, 6804, 6803, 6805, -1, 6804, 6802, 6803, -1, 6806, 6805, 6496, -1, 6806, 6804, 6805, -1, 6724, 6806, 6496, -1, 6708, 6496, 6807, -1, 6708, 6724, 6496, -1, 6707, 6807, 6808, -1, 6707, 6708, 6807, -1, 6706, 6808, 6809, -1, 6706, 6707, 6808, -1, 6704, 6809, 6810, -1, 6704, 6706, 6809, -1, 6703, 6810, 6811, -1, 6703, 6704, 6810, -1, 6702, 6811, 6812, -1, 6702, 6703, 6811, -1, 6701, 6812, 6813, -1, 6701, 6702, 6812, -1, 6699, 6813, 6814, -1, 6699, 6701, 6813, -1, 6700, 6699, 6814, -1, 6815, 6816, 6817, -1, 6818, 6819, 6820, -1, 6817, 6819, 6818, -1, 6816, 6819, 6817, -1, 6820, 6821, 6822, -1, 6819, 6821, 6820, -1, 6822, 6823, 6824, -1, 6821, 6823, 6822, -1, 6824, 6825, 6826, -1, 6823, 6825, 6824, -1, 6826, 6827, 6828, -1, 6825, 6827, 6826, -1, 6828, 6829, 6830, -1, 6827, 6829, 6828, -1, 6831, 6832, 6833, -1, 6830, 6832, 6831, -1, 6829, 6832, 6830, -1, 6833, 6834, 6835, -1, 6832, 6834, 6833, -1, 6835, 6836, 6837, -1, 6834, 6836, 6835, -1, 6838, 6839, 6840, -1, 6837, 6839, 6838, -1, 6836, 6839, 6837, -1, 6840, 6841, 6842, -1, 6839, 6841, 6840, -1, 6842, 6843, 6844, -1, 6841, 6843, 6842, -1, 6844, 6845, 6846, -1, 6843, 6845, 6844, -1, 6846, 6847, 6848, -1, 6845, 6847, 6846, -1, 6849, 6850, 6851, -1, 6852, 6853, 6854, -1, 6851, 6853, 6852, -1, 6850, 6853, 6851, -1, 6854, 6855, 6856, -1, 6853, 6855, 6854, -1, 6856, 6857, 6858, -1, 6855, 6857, 6856, -1, 6858, 6859, 6860, -1, 6857, 6859, 6858, -1, 6860, 6861, 6862, -1, 6859, 6861, 6860, -1, 6862, 6863, 6864, -1, 6861, 6863, 6862, -1, 6865, 6866, 6867, -1, 6864, 6866, 6865, -1, 6863, 6866, 6864, -1, 6867, 6868, 6869, -1, 6866, 6868, 6867, -1, 6869, 6870, 6871, -1, 6868, 6870, 6869, -1, 6872, 6873, 6874, -1, 6871, 6873, 6872, -1, 6870, 6873, 6871, -1, 6874, 6875, 6876, -1, 6873, 6875, 6874, -1, 6876, 6877, 6878, -1, 6875, 6877, 6876, -1, 6878, 6879, 6880, -1, 6877, 6879, 6878, -1, 6880, 6881, 6882, -1, 6879, 6881, 6880, -1, 6883, 6884, 6378, -1, 6885, 6883, 6380, -1, 6382, 6384, 6886, -1, 6380, 6382, 6885, -1, 6378, 6380, 6883, -1, 6376, 6378, 6884, -1, 6374, 6376, 6887, -1, 6372, 6374, 6888, -1, 6370, 6372, 6889, -1, 6368, 6370, 6890, -1, 6891, 6366, 6892, -1, 6892, 6366, 5957, -1, 5603, 5992, 5622, -1, 6893, 6891, 6892, -1, 6894, 6893, 6895, -1, 6896, 6894, 6897, -1, 6898, 6896, 6899, -1, 6900, 6898, 6901, -1, 6895, 6897, 6894, -1, 6902, 6900, 6903, -1, 6904, 6902, 6903, -1, 5622, 5987, 5635, -1, 5992, 5987, 5622, -1, 5635, 5979, 5642, -1, 5987, 5979, 5635, -1, 6339, 6905, 6906, -1, 5642, 5968, 5650, -1, 5979, 5968, 5642, -1, 5650, 5953, 5657, -1, 5968, 5953, 5650, -1, 6897, 6899, 6896, -1, 5657, 5955, 5669, -1, 5953, 5955, 5657, -1, 5669, 6327, 5668, -1, 5955, 5959, 5669, -1, 5669, 5959, 6327, -1, 6327, 6329, 5668, -1, 6341, 6907, 6905, -1, 6329, 6908, 5668, -1, 5959, 6366, 6327, -1, 5959, 5957, 6366, -1, 6366, 6368, 6327, -1, 6899, 6901, 6898, -1, 6331, 6909, 6908, -1, 6343, 6910, 6907, -1, 6901, 6903, 6900, -1, 6885, 6382, 6886, -1, 6886, 6384, 6911, -1, 6892, 6895, 6893, -1, 6903, 6912, 6904, -1, 6904, 6912, 6913, -1, 6343, 6345, 6910, -1, 6341, 6343, 6907, -1, 6339, 6341, 6905, -1, 6337, 6339, 6906, -1, 6335, 6337, 6906, -1, 6335, 6906, 6914, -1, 6333, 6335, 6914, -1, 6333, 6914, 6909, -1, 6331, 6333, 6909, -1, 6329, 6331, 6908, -1, 6890, 6327, 6368, -1, 6889, 6890, 6370, -1, 6888, 6889, 6372, -1, 6887, 6888, 6374, -1, 6884, 6887, 6376, -1, 6915, 6916, 6917, -1, 6917, 6916, 6918, -1, 6916, 6919, 6918, -1, 6918, 6920, 6921, -1, 6919, 6920, 6918, -1, 6921, 6922, 6923, -1, 6920, 6922, 6921, -1, 6923, 6924, 6925, -1, 6922, 6924, 6923, -1, 6924, 6926, 6925, -1, 6925, 6927, 6928, -1, 6926, 6927, 6925, -1, 6928, 6929, 6930, -1, 6927, 6929, 6928, -1, 6930, 6931, 4734, -1, 6929, 6931, 6930, -1, 6931, 6815, 4734, -1, 4734, 6817, 4732, -1, 6815, 6817, 4734, -1, 6817, 6818, 4732, -1, 4732, 6820, 4739, -1, 6818, 6820, 4732, -1, 4739, 6822, 4743, -1, 6820, 6822, 4739, -1, 4743, 6824, 4749, -1, 6822, 6824, 4743, -1, 4749, 6826, 4759, -1, 6824, 6826, 4749, -1, 4759, 6828, 4767, -1, 6826, 6828, 4759, -1, 4767, 6830, 4780, -1, 6828, 6830, 4767, -1, 6830, 6831, 4780, -1, 6932, 6933, 6385, -1, 6385, 6933, 6387, -1, 6387, 6934, 6389, -1, 6933, 6934, 6387, -1, 6389, 6935, 6391, -1, 6934, 6935, 6389, -1, 6391, 6936, 6393, -1, 6935, 6936, 6391, -1, 6393, 6937, 6395, -1, 6936, 6937, 6393, -1, 6395, 6938, 6939, -1, 6937, 6938, 6395, -1, 6939, 6940, 6941, -1, 6938, 6940, 6939, -1, 6941, 6942, 6943, -1, 6940, 6942, 6941, -1, 6943, 6944, 6945, -1, 6942, 6944, 6943, -1, 6945, 6849, 6848, -1, 6944, 6849, 6945, -1, 6848, 6851, 6846, -1, 6849, 6851, 6848, -1, 6846, 6852, 6844, -1, 6851, 6852, 6846, -1, 6844, 6854, 6842, -1, 6852, 6854, 6844, -1, 6842, 6856, 6840, -1, 6854, 6856, 6842, -1, 6856, 6858, 6840, -1, 6840, 6858, 6838, -1, 6858, 6860, 6838, -1, 6838, 6860, 6837, -1, 6860, 6862, 6837, -1, 6837, 6862, 6835, -1, 6862, 6864, 6835, -1, 6835, 6864, 6833, -1, 6833, 6865, 6831, -1, 6864, 6865, 6833, -1, 6346, 5192, 6348, -1, 6348, 5178, 6350, -1, 5192, 5178, 6348, -1, 6350, 5170, 6352, -1, 5178, 5170, 6350, -1, 6352, 5159, 6354, -1, 6354, 5159, 6356, -1, 5170, 5159, 6352, -1, 6356, 5153, 6946, -1, 5159, 5153, 6356, -1, 6946, 5148, 6947, -1, 5153, 5148, 6946, -1, 6947, 5143, 6948, -1, 6948, 5143, 6949, -1, 5148, 5143, 6947, -1, 6949, 5145, 6882, -1, 6882, 5145, 6880, -1, 5143, 5145, 6949, -1, 6880, 6950, 6878, -1, 5145, 6950, 6880, -1, 6878, 6951, 6876, -1, 6950, 6951, 6878, -1, 6876, 6952, 6874, -1, 6951, 6952, 6876, -1, 6874, 6953, 6872, -1, 6872, 6953, 6871, -1, 6952, 6953, 6874, -1, 6871, 6954, 6869, -1, 6953, 6954, 6871, -1, 6869, 6955, 6867, -1, 6954, 6955, 6869, -1, 6955, 6956, 6867, -1, 6867, 6956, 6865, -1, 6383, 6932, 6385, -1, 6831, 6957, 4780, -1, 5258, 5245, 6332, -1, 6958, 4797, 6957, -1, 5208, 5192, 6344, -1, 6344, 5192, 6346, -1, 6957, 4797, 4780, -1, 6959, 6915, 6917, -1, 6960, 6959, 6961, -1, 6962, 6960, 6963, -1, 6964, 6962, 6965, -1, 6966, 6964, 6965, -1, 6966, 6965, 6967, -1, 6968, 6966, 6967, -1, 6968, 6967, 6969, -1, 6970, 6968, 6969, -1, 6971, 6970, 6972, -1, 6369, 6367, 6973, -1, 6831, 6974, 6958, -1, 6371, 6369, 6975, -1, 6373, 6371, 6976, -1, 6865, 6974, 6831, -1, 6375, 6373, 6977, -1, 6958, 6974, 4797, -1, 6377, 6375, 6978, -1, 6379, 6377, 6979, -1, 6381, 6379, 6980, -1, 6981, 6932, 6383, -1, 6956, 6982, 6865, -1, 6980, 6981, 6381, -1, 6979, 6980, 6379, -1, 6978, 6979, 6377, -1, 6977, 6978, 6375, -1, 6976, 6977, 6373, -1, 6975, 6976, 6371, -1, 6973, 6975, 6369, -1, 6330, 6328, 5258, -1, 5258, 6328, 5257, -1, 6332, 6330, 5258, -1, 6982, 6983, 6974, -1, 6334, 6332, 5245, -1, 6336, 6334, 5238, -1, 6338, 6336, 5230, -1, 5245, 5238, 6334, -1, 6974, 6983, 4797, -1, 6340, 6338, 5223, -1, 6956, 6983, 6982, -1, 6342, 6340, 5208, -1, 6344, 6342, 5208, -1, 4797, 6984, 4812, -1, 6983, 6984, 4797, -1, 6984, 6985, 4812, -1, 6962, 6963, 6965, -1, 4812, 6985, 4819, -1, 6985, 6986, 4819, -1, 4819, 6986, 4826, -1, 6986, 6987, 4826, -1, 5238, 5230, 6336, -1, 4826, 6987, 4835, -1, 4846, 6367, 4845, -1, 4835, 6988, 4846, -1, 6987, 6988, 4835, -1, 6367, 6971, 4845, -1, 6960, 6961, 6963, -1, 6971, 6972, 4845, -1, 4846, 6328, 6367, -1, 6988, 6328, 4846, -1, 6988, 5257, 6328, -1, 5230, 5223, 6338, -1, 6328, 6973, 6367, -1, 6970, 6969, 6972, -1, 6959, 6917, 6961, -1, 5223, 5208, 6340, -1, 6381, 6981, 6383, -1, 6399, 6361, 6989, -1, 6397, 6399, 6990, -1, 6394, 6397, 6991, -1, 6392, 6394, 6992, -1, 6390, 6392, 6993, -1, 6388, 6390, 6994, -1, 6995, 6911, 6386, -1, 6994, 6995, 6388, -1, 6993, 6994, 6390, -1, 6992, 6993, 6392, -1, 6991, 6992, 6394, -1, 6990, 6991, 6397, -1, 6989, 6990, 6399, -1, 6996, 6989, 6361, -1, 6322, 6324, 6997, -1, 6345, 6347, 6910, -1, 6997, 6324, 5556, -1, 6360, 6322, 6997, -1, 6358, 6360, 6998, -1, 6355, 6358, 6999, -1, 6353, 6355, 7000, -1, 6351, 6353, 7001, -1, 6349, 6351, 7002, -1, 6347, 6349, 7002, -1, 6347, 7002, 6910, -1, 6360, 6997, 6998, -1, 6384, 6386, 6911, -1, 6351, 7001, 7002, -1, 6386, 6388, 6995, -1, 7003, 7004, 7005, -1, 6912, 7006, 7007, -1, 6324, 5554, 5556, -1, 6996, 6363, 6324, -1, 7008, 6090, 6363, -1, 7004, 6090, 7008, -1, 6353, 7000, 7001, -1, 6363, 6034, 6324, -1, 6090, 6034, 6363, -1, 6324, 6034, 5554, -1, 6034, 6036, 5554, -1, 5554, 6036, 5559, -1, 7006, 7009, 7010, -1, 6036, 6039, 5559, -1, 5559, 6039, 5564, -1, 6039, 6019, 5564, -1, 6355, 6999, 7000, -1, 5564, 6019, 5570, -1, 6019, 6008, 5570, -1, 5570, 6008, 5581, -1, 6008, 6004, 5581, -1, 5581, 6004, 5589, -1, 7009, 7011, 7012, -1, 6004, 5992, 5589, -1, 5589, 5992, 5603, -1, 7007, 6913, 6912, -1, 7010, 7007, 7006, -1, 7012, 7010, 7009, -1, 7013, 7012, 7011, -1, 7014, 7013, 7011, -1, 7014, 7011, 7015, -1, 7016, 7014, 7015, -1, 7016, 7015, 7003, -1, 7005, 7016, 7003, -1, 6358, 6998, 6999, -1, 7008, 7005, 7004, -1, 6361, 6363, 6996, -1, 6882, 6881, 6949, -1, 6948, 7017, 6947, -1, 6949, 7017, 6948, -1, 6881, 7017, 6949, -1, 6947, 7018, 6946, -1, 7017, 7018, 6947, -1, 6946, 7019, 6356, -1, 7018, 7019, 6946, -1, 6357, 7020, 6359, -1, 6356, 7020, 6357, -1, 7019, 7020, 6356, -1, 6359, 7021, 6325, -1, 7020, 7021, 6359, -1, 6325, 7022, 6323, -1, 7021, 7022, 6325, -1, 6323, 7023, 6326, -1, 6326, 7023, 7024, -1, 7022, 7023, 6323, -1, 7025, 7026, 7027, -1, 7024, 7026, 7025, -1, 7023, 7026, 7024, -1, 7027, 7028, 7029, -1, 7026, 7028, 7027, -1, 7029, 7030, 6937, -1, 7028, 7030, 7029, -1, 6938, 7031, 6940, -1, 6937, 7031, 6938, -1, 7030, 7031, 6937, -1, 6940, 7032, 6942, -1, 7031, 7032, 6940, -1, 7032, 7033, 6942, -1, 6942, 7033, 6944, -1, 7033, 6850, 6944, -1, 6944, 6850, 6849, -1, 6848, 6847, 6945, -1, 6943, 7034, 6941, -1, 6945, 7034, 6943, -1, 6847, 7034, 6945, -1, 6941, 7035, 6939, -1, 7034, 7035, 6941, -1, 6939, 7036, 6395, -1, 7035, 7036, 6939, -1, 6396, 7037, 6398, -1, 6395, 7037, 6396, -1, 7036, 7037, 6395, -1, 6398, 7038, 6364, -1, 7037, 7038, 6398, -1, 6364, 7039, 6362, -1, 7038, 7039, 6364, -1, 6362, 7040, 6365, -1, 6365, 7040, 7041, -1, 7039, 7040, 6362, -1, 7042, 7043, 7044, -1, 7041, 7043, 7042, -1, 7040, 7043, 7041, -1, 7044, 7045, 7046, -1, 7043, 7045, 7044, -1, 7046, 7047, 6924, -1, 7045, 7047, 7046, -1, 6926, 7048, 6927, -1, 6924, 7048, 6926, -1, 7047, 7048, 6924, -1, 6927, 7049, 6929, -1, 7048, 7049, 6927, -1, 7049, 7050, 6929, -1, 6929, 7050, 6931, -1, 7050, 6816, 6931, -1, 6931, 6816, 6815, -1, 7051, 7052, 7053, -1, 7051, 7054, 7052, -1, 7055, 7056, 7057, -1, 7058, 7056, 7055, -1, 7059, 7060, 7061, -1, 7062, 7063, 6814, -1, 7064, 7065, 7066, -1, 7064, 7061, 7065, -1, 7067, 7068, 7069, -1, 7067, 7069, 7070, -1, 7067, 7070, 7071, -1, 7072, 7071, 7073, -1, 7074, 7066, 6814, -1, 7072, 7073, 7075, -1, 7076, 7077, 7078, -1, 7076, 7078, 7059, -1, 7079, 7075, 7063, -1, 7079, 7063, 7062, -1, 7080, 7059, 7061, -1, 7081, 7062, 6814, -1, 7080, 7061, 7064, -1, 7082, 7064, 7066, -1, 7083, 7084, 7068, -1, 7085, 7086, 7087, -1, 7082, 7066, 7074, -1, 7083, 7068, 7067, -1, 7083, 7071, 7072, -1, 7083, 7067, 7071, -1, 7088, 7089, 7077, -1, 7090, 7072, 7075, -1, 7090, 7075, 7079, -1, 7088, 7077, 7076, -1, 7091, 7086, 7085, -1, 7092, 7074, 6814, -1, 7093, 7062, 7081, -1, 7094, 7059, 7080, -1, 7093, 7079, 7062, -1, 7094, 7076, 7059, -1, 7095, 7096, 7085, -1, 7095, 7087, 7089, -1, 7095, 7085, 7087, -1, 7095, 7088, 7096, -1, 6517, 7086, 7091, -1, 7097, 7081, 6814, -1, 7095, 7089, 7088, -1, 7098, 7080, 7064, -1, 7099, 7100, 7084, -1, 7099, 7072, 7090, -1, 7098, 7064, 7082, -1, 7099, 7084, 7083, -1, 7099, 7083, 7072, -1, 7101, 7082, 7074, -1, 7102, 7090, 7079, -1, 7102, 7079, 7093, -1, 7101, 7074, 7092, -1, 7103, 7104, 7096, -1, 7103, 7096, 7088, -1, 7103, 7088, 7076, -1, 7103, 7076, 7094, -1, 7105, 7093, 7081, -1, 7105, 7081, 7097, -1, 7106, 7092, 6814, -1, 7107, 7097, 6814, -1, 7108, 7109, 7100, -1, 7110, 7094, 7080, -1, 7108, 7100, 7099, -1, 7110, 7080, 7098, -1, 7108, 7099, 7090, -1, 7108, 7090, 7102, -1, 7111, 7098, 7082, -1, 7111, 7082, 7101, -1, 7112, 7102, 7093, -1, 7113, 7101, 7092, -1, 7112, 7093, 7105, -1, 7113, 7092, 7106, -1, 7114, 7103, 7094, -1, 7114, 7110, 7115, -1, 7114, 7115, 7104, -1, 7116, 7105, 7097, -1, 7114, 7104, 7103, -1, 7116, 7097, 7107, -1, 7114, 7094, 7110, -1, 7117, 7118, 7119, -1, 7117, 6814, 7118, -1, 7117, 7107, 6814, -1, 7120, 7102, 7112, -1, 7121, 7106, 6814, -1, 7120, 7108, 7102, -1, 7122, 7115, 7110, -1, 7122, 7110, 7098, -1, 7122, 7098, 7111, -1, 7123, 7105, 7116, -1, 7124, 7111, 7101, -1, 7123, 7112, 7105, -1, 7124, 7101, 7113, -1, 7125, 7116, 7107, -1, 7125, 7119, 7126, -1, 7127, 7113, 7106, -1, 7125, 7117, 7119, -1, 7127, 7106, 7121, -1, 7125, 7107, 7117, -1, 7128, 7129, 7109, -1, 7128, 7108, 7120, -1, 7128, 7109, 7108, -1, 7130, 7121, 6814, -1, 7131, 7112, 7123, -1, 7132, 7122, 7111, -1, 7131, 7120, 7112, -1, 7133, 7126, 7134, -1, 7135, 7136, 7137, -1, 7132, 7111, 7124, -1, 7133, 7125, 7126, -1, 7133, 7123, 7116, -1, 7135, 7137, 7138, -1, 7133, 7116, 7125, -1, 7070, 7113, 7127, -1, 7070, 7124, 7113, -1, 7139, 7128, 7120, -1, 7139, 7129, 7128, -1, 7139, 7120, 7131, -1, 7073, 7127, 7121, -1, 6789, 7136, 7135, -1, 7073, 7121, 7130, -1, 7140, 7123, 7133, -1, 7141, 7132, 7142, -1, 7140, 7133, 7134, -1, 7141, 7142, 7115, -1, 7140, 7131, 7123, -1, 7141, 7122, 7132, -1, 7141, 7115, 7122, -1, 7143, 7129, 7139, -1, 7143, 7144, 7129, -1, 7065, 7145, 6814, -1, 7146, 7134, 7147, -1, 7146, 7140, 7134, -1, 7063, 7130, 6814, -1, 7146, 7139, 7131, -1, 7146, 7131, 7140, -1, 7069, 7142, 7132, -1, 7069, 7068, 7142, -1, 7061, 7060, 7145, -1, 7069, 7132, 7124, -1, 7148, 7147, 7138, -1, 7069, 7124, 7070, -1, 7061, 7145, 7065, -1, 7148, 7137, 7144, -1, 7148, 7146, 7147, -1, 7071, 7070, 7127, -1, 7148, 7143, 7139, -1, 7071, 7127, 7073, -1, 7148, 7144, 7143, -1, 7148, 7139, 7146, -1, 7148, 7138, 7137, -1, 7066, 7065, 6814, -1, 7075, 7073, 7130, -1, 7059, 7078, 7060, -1, 7075, 7130, 7063, -1, 7149, 7150, 7151, -1, 7149, 6525, 6527, -1, 7149, 7151, 6525, -1, 6513, 7152, 6517, -1, 7153, 6527, 6529, -1, 7153, 7149, 6527, -1, 7153, 7150, 7149, -1, 7154, 7155, 7150, -1, 6523, 7156, 7152, -1, 7154, 7153, 6529, -1, 7154, 7150, 7153, -1, 6523, 7152, 6513, -1, 7157, 7158, 7155, -1, 6525, 7151, 7156, -1, 7157, 7155, 7154, -1, 6525, 7156, 6523, -1, 7159, 6529, 6509, -1, 7159, 6509, 6499, -1, 7159, 7154, 6529, -1, 7160, 7161, 7158, -1, 7160, 7158, 7157, -1, 7162, 7157, 7154, -1, 7162, 6499, 6498, -1, 7162, 7159, 6499, -1, 7162, 7154, 7159, -1, 7163, 6792, 7161, -1, 7163, 7161, 7160, -1, 7164, 6498, 6551, -1, 7164, 7160, 7157, -1, 7164, 7157, 7162, -1, 7164, 7162, 6498, -1, 7165, 6793, 6792, -1, 7165, 6792, 7163, -1, 7166, 7164, 6551, -1, 7166, 6551, 6545, -1, 7166, 6545, 6544, -1, 7166, 7163, 7160, -1, 7166, 7160, 7164, -1, 7167, 6795, 6793, -1, 7167, 6793, 7165, -1, 7168, 6544, 6547, -1, 7168, 7165, 7163, -1, 7168, 7166, 6544, -1, 7168, 7163, 7166, -1, 7169, 6795, 7167, -1, 7170, 6547, 6548, -1, 7170, 7168, 6547, -1, 7170, 7167, 7165, -1, 7170, 7165, 7168, -1, 7171, 6797, 6795, -1, 7171, 6795, 7169, -1, 7172, 6548, 6531, -1, 7172, 7170, 6548, -1, 7172, 7169, 7167, -1, 7172, 7167, 7170, -1, 7173, 6799, 6797, -1, 7173, 7171, 6503, -1, 7173, 6503, 6533, -1, 7173, 6797, 7171, -1, 7174, 7169, 7172, -1, 7174, 6503, 7171, -1, 7174, 7171, 7169, -1, 7174, 7172, 6531, -1, 7174, 6531, 6503, -1, 7175, 7173, 6533, -1, 7175, 6799, 7173, -1, 7176, 6534, 6801, -1, 7176, 6801, 6799, -1, 7176, 6799, 7175, -1, 7176, 7175, 6533, -1, 7176, 6533, 6534, -1, 6535, 6801, 6534, -1, 6535, 6803, 6801, -1, 6536, 6805, 6803, -1, 6536, 6803, 6535, -1, 6492, 6805, 6536, -1, 6496, 6805, 6492, -1, 7177, 6814, 7178, -1, 7179, 7180, 7181, -1, 7177, 7178, 7182, -1, 7177, 7182, 7183, -1, 7184, 7185, 7186, -1, 7187, 7188, 7189, -1, 7184, 7190, 7185, -1, 7187, 7191, 7188, -1, 7192, 6813, 6812, -1, 7193, 6807, 6496, -1, 7194, 7183, 7195, -1, 7192, 6812, 7196, -1, 7194, 7195, 7197, -1, 7198, 7180, 7179, -1, 7199, 6808, 6807, -1, 7200, 7201, 7191, -1, 7198, 7196, 7180, -1, 7199, 6807, 7193, -1, 7200, 7197, 7201, -1, 7202, 7190, 7184, -1, 7202, 7179, 7190, -1, 7203, 7191, 7187, -1, 7204, 6814, 6813, -1, 7204, 6813, 7192, -1, 7205, 7183, 7194, -1, 7205, 6814, 7177, -1, 7205, 7177, 7183, -1, 7206, 7196, 7198, -1, 7207, 7189, 7208, -1, 7207, 7187, 7189, -1, 7206, 7192, 7196, -1, 7209, 7198, 7179, -1, 7210, 7194, 7197, -1, 7210, 7197, 7200, -1, 7209, 7179, 7202, -1, 7211, 7186, 7212, -1, 7211, 7184, 7186, -1, 7213, 7200, 7191, -1, 7211, 7202, 7184, -1, 7213, 7191, 7203, -1, 7214, 7204, 7192, -1, 7215, 7208, 7216, -1, 7214, 7192, 7206, -1, 7214, 6814, 7204, -1, 7217, 7198, 7209, -1, 7217, 7206, 7198, -1, 7218, 7203, 7187, -1, 7218, 7187, 7207, -1, 7219, 7202, 7211, -1, 7220, 7205, 7194, -1, 7220, 7194, 7210, -1, 7220, 6814, 7205, -1, 7219, 7209, 7202, -1, 7221, 7207, 7208, -1, 7222, 7211, 7212, -1, 7221, 7208, 7215, -1, 7223, 7214, 7206, -1, 7223, 7206, 7217, -1, 7224, 7200, 7213, -1, 7223, 6814, 7214, -1, 7224, 7210, 7200, -1, 7225, 7217, 7209, -1, 7226, 7213, 7203, -1, 7225, 7209, 7219, -1, 7226, 7203, 7218, -1, 7227, 7211, 7222, -1, 7228, 7229, 7230, -1, 7228, 7216, 7229, -1, 7227, 7219, 7211, -1, 7228, 7215, 7216, -1, 7231, 7222, 7212, -1, 7231, 7212, 7232, -1, 7233, 7234, 7235, -1, 7233, 7235, 6757, -1, 7236, 7207, 7221, -1, 7236, 7218, 7207, -1, 7237, 6814, 7223, -1, 7237, 7217, 7225, -1, 7229, 7216, 7234, -1, 7237, 7223, 7217, -1, 7229, 7234, 7233, -1, 7238, 7220, 7210, -1, 7239, 7225, 7219, -1, 7238, 6814, 7220, -1, 7238, 7210, 7224, -1, 7239, 7219, 7227, -1, 7240, 7215, 7228, -1, 7240, 7230, 7241, -1, 7240, 7228, 7230, -1, 7242, 7227, 7222, -1, 7240, 7221, 7215, -1, 7242, 7222, 7231, -1, 7243, 7213, 7226, -1, 7244, 7231, 7232, -1, 7243, 7224, 7213, -1, 7245, 7226, 7218, -1, 7246, 7237, 7225, -1, 7246, 6814, 7237, -1, 7246, 7225, 7239, -1, 7245, 7218, 7236, -1, 7247, 7221, 7240, -1, 7247, 7240, 7241, -1, 7182, 7239, 7227, -1, 7247, 7236, 7221, -1, 7182, 7227, 7242, -1, 7248, 6814, 7238, -1, 7248, 7238, 7224, -1, 7248, 7224, 7243, -1, 7195, 7242, 7231, -1, 7195, 7231, 7244, -1, 7249, 6809, 6808, -1, 7249, 7199, 7250, -1, 7201, 7232, 7188, -1, 7249, 6808, 7199, -1, 7251, 7243, 7226, -1, 7201, 7244, 7232, -1, 7251, 7226, 7245, -1, 7252, 7245, 7236, -1, 7181, 6810, 6809, -1, 7252, 7236, 7247, -1, 7252, 7247, 7241, -1, 7178, 6814, 7246, -1, 7178, 7246, 7239, -1, 7181, 6809, 7249, -1, 7178, 7239, 7182, -1, 7252, 7241, 7253, -1, 7180, 6811, 6810, -1, 7183, 7242, 7195, -1, 7254, 7248, 7243, -1, 7180, 6810, 7181, -1, 7254, 7243, 7251, -1, 7183, 7182, 7242, -1, 7254, 6814, 7248, -1, 7190, 7250, 7185, -1, 7255, 7253, 7256, -1, 7190, 7249, 7250, -1, 7255, 7251, 7245, -1, 7190, 7181, 7249, -1, 7255, 7252, 7253, -1, 7255, 7245, 7252, -1, 7197, 7244, 7201, -1, 7257, 7258, 6814, -1, 7257, 7256, 7258, -1, 7196, 6812, 6811, -1, 7257, 7254, 7251, -1, 7197, 7195, 7244, -1, 7257, 7255, 7256, -1, 7257, 6814, 7254, -1, 7257, 7251, 7255, -1, 7196, 6811, 7180, -1, 7191, 7201, 7188, -1, 7179, 7181, 7190, -1, 6757, 7259, 6758, -1, 7260, 6783, 6781, -1, 7260, 7261, 7262, -1, 7260, 7262, 6783, -1, 6787, 7263, 7264, -1, 6787, 7264, 6789, -1, 7265, 7266, 7267, -1, 7268, 7260, 6781, -1, 7268, 6781, 6779, -1, 7268, 7267, 7261, -1, 7268, 7261, 7260, -1, 7269, 7270, 7266, -1, 7269, 7266, 7265, -1, 7271, 7267, 7268, -1, 6785, 7272, 7263, -1, 7271, 7268, 6779, -1, 7271, 6779, 6777, -1, 6785, 7263, 6787, -1, 7271, 7265, 7267, -1, 7273, 7274, 7270, -1, 7273, 7270, 7269, -1, 7275, 7271, 6777, -1, 7275, 7265, 7271, -1, 7275, 7269, 7265, -1, 7276, 7277, 7274, -1, 6783, 7262, 7272, -1, 7276, 7274, 7273, -1, 6783, 7272, 6785, -1, 7278, 7279, 7280, -1, 7278, 7280, 7277, -1, 7278, 7277, 7276, -1, 7281, 6777, 6775, -1, 7281, 7273, 7269, -1, 7281, 7269, 7275, -1, 7281, 7275, 6777, -1, 7282, 6775, 6773, -1, 7282, 7281, 6775, -1, 7282, 7276, 7273, -1, 7282, 7273, 7281, -1, 7283, 7284, 7279, -1, 7283, 7279, 7278, -1, 7285, 7282, 6773, -1, 7285, 7278, 7276, -1, 7285, 7276, 7282, -1, 7286, 7287, 7284, -1, 7286, 7284, 7283, -1, 7288, 6773, 6771, -1, 7288, 7285, 6773, -1, 7288, 7278, 7285, -1, 7288, 7283, 7278, -1, 7289, 7290, 7291, -1, 7289, 7291, 7287, -1, 7289, 7287, 7286, -1, 7292, 6771, 6769, -1, 7292, 7283, 7288, -1, 7292, 7286, 7283, -1, 7292, 7288, 6771, -1, 7293, 6769, 6767, -1, 7293, 7290, 7289, -1, 7293, 7286, 7292, -1, 7293, 7289, 7286, -1, 7293, 7292, 6769, -1, 7294, 6767, 6765, -1, 7294, 7295, 7290, -1, 7294, 7293, 6767, -1, 7294, 7290, 7293, -1, 7296, 6762, 7297, -1, 7296, 6765, 6762, -1, 7296, 7295, 7294, -1, 7296, 7297, 7295, -1, 7296, 7294, 6765, -1, 6760, 7297, 6762, -1, 6760, 7298, 7297, -1, 6758, 7298, 6760, -1, 6758, 7259, 7298, -1, 7299, 7300, 7301, -1, 7302, 7303, 7304, -1, 7302, 7305, 7303, -1, 7306, 6629, 7307, -1, 7308, 7309, 7310, -1, 7306, 7307, 7311, -1, 7306, 7311, 7312, -1, 7308, 7304, 7309, -1, 7313, 6615, 6614, -1, 7314, 6625, 6623, -1, 7315, 7312, 7316, -1, 7314, 6623, 7317, -1, 7315, 7316, 7318, -1, 7319, 6616, 6615, -1, 7320, 7318, 7300, -1, 7321, 7305, 7302, -1, 7320, 7300, 7299, -1, 7319, 6615, 7313, -1, 7321, 7317, 7305, -1, 7322, 7301, 7323, -1, 7324, 7304, 7308, -1, 7322, 7299, 7301, -1, 7324, 7302, 7304, -1, 7324, 7308, 7310, -1, 7325, 6629, 7306, -1, 7325, 7306, 7312, -1, 7326, 6629, 6627, -1, 7325, 7312, 7315, -1, 7326, 6627, 6625, -1, 7327, 7315, 7318, -1, 7326, 6625, 7314, -1, 7327, 7318, 7320, -1, 7328, 7317, 7321, -1, 7329, 7320, 7299, -1, 7328, 7314, 7317, -1, 7329, 7299, 7322, -1, 7330, 7323, 7331, -1, 7332, 7302, 7324, -1, 7332, 7321, 7302, -1, 7330, 7322, 7323, -1, 7333, 7310, 7334, -1, 7333, 7324, 7310, -1, 7335, 7331, 7336, -1, 7337, 6629, 7326, -1, 7338, 6629, 7325, -1, 7337, 7326, 7314, -1, 7338, 7315, 7327, -1, 7337, 7314, 7328, -1, 7338, 7325, 7315, -1, 7339, 7320, 7329, -1, 7339, 7327, 7320, -1, 7340, 7321, 7332, -1, 7340, 7328, 7321, -1, 7341, 7324, 7333, -1, 7342, 7336, 7343, -1, 7342, 7344, 7345, -1, 7342, 7343, 7344, -1, 7341, 7332, 7324, -1, 7346, 7334, 7347, -1, 7348, 7329, 7322, -1, 7346, 7333, 7334, -1, 7348, 7322, 7330, -1, 7349, 7328, 7340, -1, 7349, 7337, 7328, -1, 7350, 7331, 7335, -1, 7350, 7330, 7331, -1, 7349, 6629, 7337, -1, 7351, 7332, 7341, -1, 7352, 7335, 7336, -1, 7351, 7340, 7332, -1, 7352, 7342, 7345, -1, 7352, 7336, 7342, -1, 7353, 7338, 7327, -1, 7354, 7333, 7346, -1, 7353, 6629, 7338, -1, 7355, 7343, 7356, -1, 7355, 7356, 6538, -1, 7353, 7327, 7339, -1, 7354, 7341, 7333, -1, 7357, 7346, 7347, -1, 7357, 7347, 7358, -1, 7359, 7329, 7348, -1, 7344, 7343, 7355, -1, 7359, 7339, 7329, -1, 7360, 6629, 7349, -1, 7361, 7330, 7350, -1, 7360, 7340, 7351, -1, 7361, 7359, 7348, -1, 7360, 7349, 7340, -1, 7361, 7348, 7330, -1, 7362, 7352, 7345, -1, 7362, 7363, 7364, -1, 7365, 7341, 7354, -1, 7362, 7345, 7363, -1, 7362, 7350, 7335, -1, 7365, 7351, 7341, -1, 7362, 7335, 7352, -1, 7366, 7353, 7339, -1, 7367, 7354, 7346, -1, 7366, 6629, 7353, -1, 7367, 7365, 7354, -1, 7366, 7339, 7359, -1, 7367, 7346, 7357, -1, 7368, 7357, 7358, -1, 7369, 7359, 7361, -1, 7370, 7350, 7362, -1, 7370, 7361, 7350, -1, 7371, 7360, 7351, -1, 7370, 7362, 7364, -1, 7371, 7351, 7365, -1, 7370, 7364, 7372, -1, 7370, 7369, 7361, -1, 7373, 6629, 7366, -1, 7371, 6629, 7360, -1, 7373, 7366, 7359, -1, 7373, 7359, 7369, -1, 7311, 7365, 7367, -1, 7374, 7372, 7375, -1, 7374, 7370, 7372, -1, 7374, 7369, 7370, -1, 7376, 6619, 6616, -1, 7316, 7367, 7357, -1, 7376, 7319, 7377, -1, 7378, 6629, 7373, -1, 7316, 7357, 7368, -1, 7378, 7374, 7375, -1, 7376, 6616, 7319, -1, 7378, 7375, 6629, -1, 7316, 7311, 7367, -1, 7378, 7373, 7369, -1, 7378, 7369, 7374, -1, 7300, 7358, 7301, -1, 7300, 7368, 7358, -1, 7303, 7376, 7377, -1, 7303, 6619, 7376, -1, 7307, 6629, 7371, -1, 7307, 7371, 7365, -1, 7305, 6621, 6619, -1, 7307, 7365, 7311, -1, 7305, 6619, 7303, -1, 7304, 7377, 7309, -1, 7312, 7311, 7316, -1, 7304, 7303, 7377, -1, 7318, 7316, 7368, -1, 7317, 6623, 6621, -1, 7318, 7368, 7300, -1, 7317, 6621, 7305, -1, 6538, 6520, 7379, -1, 7380, 6530, 6528, -1, 7380, 6657, 6655, -1, 7380, 6528, 6657, -1, 6661, 6512, 6511, -1, 6661, 6511, 6516, -1, 7381, 6508, 6532, -1, 7382, 6530, 7380, -1, 7382, 6532, 6530, -1, 7382, 6655, 6653, -1, 7382, 7380, 6655, -1, 7383, 6508, 7381, -1, 7383, 6497, 6508, -1, 7384, 7381, 6532, -1, 6659, 6526, 6512, -1, 7384, 6653, 6651, -1, 6659, 6512, 6661, -1, 7384, 7382, 6653, -1, 7384, 6532, 7382, -1, 7385, 6500, 6497, -1, 7385, 6497, 7383, -1, 7386, 7384, 6651, -1, 7386, 7383, 7381, -1, 7386, 7381, 7384, -1, 7387, 6550, 6500, -1, 6657, 6528, 6526, -1, 7387, 6500, 7385, -1, 6657, 6526, 6659, -1, 7388, 6550, 7387, -1, 7388, 6495, 6549, -1, 7388, 6549, 6550, -1, 7389, 6651, 6649, -1, 7389, 7383, 7386, -1, 7389, 7385, 7383, -1, 7389, 7386, 6651, -1, 7390, 6649, 6648, -1, 7390, 7389, 6649, -1, 7390, 7387, 7385, -1, 7390, 7385, 7389, -1, 7391, 6493, 6495, -1, 7391, 6495, 7388, -1, 7392, 7387, 7390, -1, 7392, 7390, 6648, -1, 7392, 7388, 7387, -1, 7393, 6522, 6493, -1, 7393, 6493, 7391, -1, 7394, 6648, 7395, -1, 7394, 7391, 7388, -1, 7394, 7388, 7392, -1, 7394, 7392, 6648, -1, 7396, 6542, 6521, -1, 7396, 6521, 6522, -1, 7396, 6522, 7393, -1, 7397, 7395, 7398, -1, 7397, 7393, 7391, -1, 7397, 7391, 7394, -1, 7397, 7394, 7395, -1, 7399, 7398, 7400, -1, 7399, 7396, 7393, -1, 7399, 7397, 7398, -1, 7399, 6542, 7396, -1, 7399, 7393, 7397, -1, 7401, 7400, 7402, -1, 7401, 6540, 6542, -1, 7401, 7399, 7400, -1, 7401, 6542, 7399, -1, 7403, 7404, 6539, -1, 7403, 7402, 7404, -1, 7403, 6539, 6540, -1, 7403, 7401, 7402, -1, 7403, 6540, 7401, -1, 7405, 6539, 7404, -1, 7405, 6507, 6539, -1, 7379, 6507, 7405, -1, 7379, 6520, 6507, -1, 7406, 7407, 7408, -1, 7406, 7409, 7410, -1, 7411, 7412, 7413, -1, 7406, 7408, 7409, -1, 7414, 7415, 6629, -1, 7416, 7410, 7417, -1, 7416, 7417, 7418, -1, 7419, 6637, 7420, -1, 7421, 7418, 7422, -1, 7421, 7422, 7423, -1, 7424, 7420, 7412, -1, 7424, 7412, 7411, -1, 7425, 7423, 6629, -1, 7426, 7411, 7415, -1, 7427, 7428, 7407, -1, 7426, 7415, 7414, -1, 7427, 7407, 7406, -1, 7427, 7410, 7416, -1, 7427, 7406, 7410, -1, 7429, 6639, 6637, -1, 7429, 6637, 7419, -1, 7430, 7416, 7418, -1, 7431, 6643, 6641, -1, 7430, 7418, 7421, -1, 7432, 7414, 6629, -1, 7433, 7421, 7423, -1, 7434, 7420, 7424, -1, 7433, 7423, 7425, -1, 7434, 7419, 7420, -1, 7435, 6641, 6639, -1, 7436, 7431, 6641, -1, 7435, 6639, 7429, -1, 7435, 7436, 6641, -1, 7437, 7424, 7411, -1, 7438, 6643, 7431, -1, 7439, 7425, 6629, -1, 7437, 7411, 7426, -1, 7440, 7428, 7427, -1, 7440, 7416, 7430, -1, 7440, 7427, 7416, -1, 6645, 6643, 7438, -1, 7441, 7414, 7432, -1, 7441, 7426, 7414, -1, 7442, 7430, 7421, -1, 7442, 7421, 7433, -1, 7443, 7419, 7434, -1, 7443, 7429, 7419, -1, 7444, 7433, 7425, -1, 7444, 7425, 7439, -1, 7445, 7432, 6629, -1, 7446, 7439, 6629, -1, 7447, 7434, 7424, -1, 7448, 7449, 7428, -1, 7447, 7424, 7437, -1, 7448, 7428, 7440, -1, 7450, 7429, 7443, -1, 7448, 7440, 7430, -1, 7450, 7451, 7436, -1, 7448, 7430, 7442, -1, 7450, 7436, 7435, -1, 7450, 7443, 7451, -1, 7450, 7435, 7429, -1, 7452, 7426, 7441, -1, 7453, 7442, 7433, -1, 7453, 7433, 7444, -1, 7452, 7437, 7426, -1, 7454, 7439, 7446, -1, 7455, 7441, 7432, -1, 7455, 7432, 7445, -1, 7454, 7444, 7439, -1, 7456, 6629, 6677, -1, 7457, 7445, 6629, -1, 7456, 7446, 6629, -1, 7458, 7437, 7452, -1, 7459, 7442, 7453, -1, 7458, 7447, 7437, -1, 7460, 7452, 7441, -1, 7459, 7448, 7442, -1, 7460, 7441, 7455, -1, 7461, 7444, 7454, -1, 7461, 7453, 7444, -1, 7462, 7455, 7445, -1, 7462, 7445, 7457, -1, 7463, 6677, 6675, -1, 7463, 7446, 7456, -1, 7463, 7456, 6677, -1, 7464, 7447, 7458, -1, 7463, 7454, 7446, -1, 7464, 7465, 7447, -1, 7466, 7467, 7449, -1, 7468, 7457, 6629, -1, 7466, 7448, 7459, -1, 7466, 7449, 7448, -1, 7469, 7458, 7452, -1, 7470, 7453, 7461, -1, 7470, 7459, 7453, -1, 7469, 7452, 7460, -1, 7471, 7461, 7454, -1, 7409, 7460, 7455, -1, 6665, 7472, 7473, -1, 7471, 6675, 6673, -1, 7471, 7454, 7463, -1, 7471, 7463, 6675, -1, 6665, 7473, 6667, -1, 7409, 7455, 7462, -1, 7417, 7457, 7468, -1, 7474, 7475, 7467, -1, 7474, 7467, 7466, -1, 7417, 7462, 7457, -1, 7474, 7466, 7459, -1, 7474, 7459, 7470, -1, 7476, 7477, 7465, -1, 7476, 7458, 7469, -1, 6516, 7472, 6665, -1, 7476, 7465, 7464, -1, 7478, 6673, 6671, -1, 7476, 7464, 7458, -1, 7478, 7461, 7471, -1, 7476, 7469, 7477, -1, 7478, 7470, 7461, -1, 7478, 7471, 6673, -1, 7422, 7468, 6629, -1, 7413, 6633, 6631, -1, 7413, 6631, 6629, -1, 7479, 6671, 6669, -1, 7408, 7407, 7477, -1, 7479, 7474, 7470, -1, 7479, 7470, 7478, -1, 7408, 7477, 7469, -1, 7412, 6635, 6633, -1, 7479, 7478, 6671, -1, 7408, 7469, 7460, -1, 7408, 7460, 7409, -1, 7480, 6669, 6667, -1, 7412, 6633, 7413, -1, 7480, 7473, 7475, -1, 7480, 7475, 7474, -1, 7410, 7409, 7462, -1, 7480, 7479, 6669, -1, 7410, 7462, 7417, -1, 7480, 7474, 7479, -1, 7480, 6667, 7473, -1, 7481, 7434, 7447, -1, 7481, 7465, 7451, -1, 7481, 7447, 7465, -1, 7415, 7413, 6629, -1, 7481, 7451, 7443, -1, 7418, 7417, 7468, -1, 7481, 7443, 7434, -1, 7418, 7468, 7422, -1, 7420, 6637, 6635, -1, 7420, 6635, 7412, -1, 7423, 7422, 6629, -1, 7411, 7413, 7415, -1, 7482, 7483, 7484, -1, 7482, 7485, 7486, -1, 7482, 7484, 7485, -1, 7487, 7488, 6645, -1, 7489, 7486, 7490, -1, 7489, 7482, 7486, -1, 7489, 7483, 7482, -1, 7491, 7492, 7483, -1, 7493, 7494, 7488, -1, 7491, 7489, 7490, -1, 7491, 7483, 7489, -1, 7493, 7488, 7487, -1, 7495, 7496, 7492, -1, 7485, 7484, 7494, -1, 7495, 7492, 7491, -1, 7485, 7494, 7493, -1, 7497, 7490, 7498, -1, 7497, 7498, 7499, -1, 7497, 7491, 7490, -1, 7500, 7501, 7496, -1, 7500, 7496, 7495, -1, 7502, 7495, 7491, -1, 7502, 7499, 7503, -1, 7502, 7497, 7499, -1, 7502, 7491, 7497, -1, 7504, 7505, 7501, -1, 7504, 7501, 7500, -1, 7506, 7503, 7507, -1, 7506, 7500, 7495, -1, 7506, 7495, 7502, -1, 7506, 7502, 7503, -1, 7508, 7509, 7505, -1, 7508, 7505, 7504, -1, 7510, 7506, 7507, -1, 7510, 7507, 7511, -1, 7510, 7511, 7512, -1, 7510, 7504, 7500, -1, 7510, 7500, 7506, -1, 7513, 7514, 7509, -1, 7513, 7509, 7508, -1, 7515, 7512, 7516, -1, 7515, 7508, 7504, -1, 7515, 7510, 7512, -1, 7515, 7504, 7510, -1, 7517, 7514, 7513, -1, 7518, 7516, 7519, -1, 7518, 7515, 7516, -1, 7518, 7513, 7508, -1, 7518, 7508, 7515, -1, 7520, 7521, 7514, -1, 7520, 7514, 7517, -1, 7522, 7519, 7523, -1, 7522, 7518, 7519, -1, 7522, 7517, 7513, -1, 7522, 7513, 7518, -1, 7524, 7525, 7521, -1, 7524, 7520, 7526, -1, 7524, 7526, 7527, -1, 7524, 7521, 7520, -1, 7528, 7517, 7522, -1, 7528, 7526, 7520, -1, 7528, 7520, 7517, -1, 7528, 7522, 7523, -1, 7528, 7523, 7526, -1, 7529, 7524, 7527, -1, 7529, 7525, 7524, -1, 7530, 7531, 7532, -1, 7530, 7532, 7525, -1, 7530, 7525, 7529, -1, 7530, 7529, 7527, -1, 7530, 7527, 7531, -1, 7533, 7532, 7531, -1, 7533, 7534, 7532, -1, 7535, 7536, 7534, -1, 7535, 7534, 7533, -1, 7537, 7536, 7535, -1, 6614, 7536, 7537, -1, 6715, 6700, 6814, -1, 6715, 6814, 7145, -1, 6714, 7145, 7060, -1, 6714, 6715, 7145, -1, 6711, 7060, 7078, -1, 6711, 6714, 7060, -1, 6698, 7078, 7077, -1, 6698, 6711, 7078, -1, 6709, 7077, 7089, -1, 6709, 6698, 7077, -1, 6710, 7089, 7087, -1, 6710, 6709, 7089, -1, 6725, 7087, 7086, -1, 6725, 6710, 7087, -1, 6722, 7086, 6517, -1, 6722, 6725, 7086, -1, 6723, 6722, 6517, -1, 7538, 6517, 7152, -1, 7538, 6723, 6517, -1, 7539, 7152, 7156, -1, 7539, 7538, 7152, -1, 7540, 7156, 7151, -1, 7540, 7539, 7156, -1, 7541, 7151, 7150, -1, 7541, 7540, 7151, -1, 7542, 7150, 7155, -1, 7542, 7541, 7150, -1, 7543, 7155, 7158, -1, 7543, 7542, 7155, -1, 7544, 7158, 7161, -1, 7544, 7543, 7158, -1, 7545, 7544, 7161, -1, 7545, 7161, 6792, -1, 6791, 7545, 6792, -1, 7546, 7547, 7548, -1, 7549, 7550, 7551, -1, 7552, 7553, 7554, -1, 7555, 7550, 7549, -1, 7556, 7554, 7553, -1, 7557, 7550, 7555, -1, 7558, 7559, 7056, -1, 7560, 7552, 7554, -1, 7561, 7058, 7554, -1, 7561, 7554, 7556, -1, 7562, 7563, 7558, -1, 7562, 7558, 7056, -1, 7564, 7560, 7554, -1, 7565, 7058, 7561, -1, 7566, 7567, 7562, -1, 7568, 7562, 7567, -1, 7569, 7570, 7571, -1, 7569, 7571, 7572, -1, 7569, 7572, 7573, -1, 7574, 7058, 7565, -1, 7575, 7566, 7562, -1, 7569, 7576, 7570, -1, 7569, 7573, 7548, -1, 7577, 7562, 7568, -1, 7578, 7576, 7569, -1, 7578, 7579, 7580, -1, 7581, 7058, 7574, -1, 7578, 7580, 7582, -1, 7578, 7582, 7583, -1, 7578, 7583, 7584, -1, 7578, 7584, 7576, -1, 7056, 7058, 7581, -1, 7578, 7550, 7557, -1, 7585, 7575, 7562, -1, 7578, 7557, 7579, -1, 7586, 7562, 7577, -1, 7587, 7586, 7577, -1, 7588, 7585, 7562, -1, 7589, 7056, 7590, -1, 7589, 7562, 7056, -1, 7589, 7588, 7562, -1, 7591, 7590, 7592, -1, 7593, 7594, 7595, -1, 7593, 7595, 7596, -1, 7593, 7596, 7597, -1, 7593, 7597, 7598, -1, 7593, 7598, 7599, -1, 7591, 7589, 7590, -1, 7593, 7599, 7564, -1, 7593, 7564, 7554, -1, 7600, 7586, 7587, -1, 7601, 7592, 7602, -1, 7056, 7559, 7603, -1, 7601, 7591, 7592, -1, 7056, 7581, 7604, -1, 7056, 7604, 7605, -1, 7056, 7605, 7606, -1, 7607, 7550, 7586, -1, 7056, 7606, 7608, -1, 7607, 7586, 7600, -1, 7573, 7602, 7546, -1, 7609, 7056, 7608, -1, 7573, 7546, 7548, -1, 7573, 7601, 7602, -1, 7548, 7594, 7593, -1, 7610, 7550, 7607, -1, 7548, 7611, 7612, -1, 7548, 7612, 7594, -1, 7613, 7056, 7609, -1, 7547, 7611, 7548, -1, 7590, 7056, 7613, -1, 7551, 7550, 7610, -1, 7614, 7600, 7587, -1, 7614, 7587, 7615, -1, 7616, 7617, 7571, -1, 7571, 7617, 7572, -1, 7572, 7618, 7573, -1, 7617, 7618, 7572, -1, 7573, 7619, 7601, -1, 7618, 7619, 7573, -1, 7601, 7620, 7591, -1, 7619, 7620, 7601, -1, 7591, 7621, 7589, -1, 7620, 7621, 7591, -1, 7589, 7622, 7588, -1, 7621, 7622, 7589, -1, 7588, 7623, 7585, -1, 7622, 7623, 7588, -1, 7585, 7624, 7575, -1, 7623, 7624, 7585, -1, 7575, 7625, 7566, -1, 7624, 7625, 7575, -1, 7566, 7626, 7567, -1, 7625, 7626, 7566, -1, 7567, 7627, 7568, -1, 7626, 7627, 7567, -1, 7568, 7628, 7577, -1, 7627, 7628, 7568, -1, 7577, 7615, 7587, -1, 7628, 7615, 7577, -1, 7570, 7629, 7616, -1, 7570, 7616, 7571, -1, 7614, 7630, 7600, -1, 7600, 7630, 7607, -1, 7607, 7631, 7610, -1, 7630, 7631, 7607, -1, 7610, 7632, 7551, -1, 7631, 7632, 7610, -1, 7551, 7633, 7549, -1, 7632, 7633, 7551, -1, 7549, 7634, 7555, -1, 7633, 7634, 7549, -1, 7555, 7635, 7557, -1, 7634, 7635, 7555, -1, 7557, 7636, 7579, -1, 7635, 7636, 7557, -1, 7579, 7637, 7580, -1, 7636, 7637, 7579, -1, 7580, 7638, 7582, -1, 7637, 7638, 7580, -1, 7582, 7639, 7583, -1, 7638, 7639, 7582, -1, 7583, 7640, 7584, -1, 7639, 7640, 7583, -1, 7584, 7641, 7576, -1, 7640, 7641, 7584, -1, 7576, 7629, 7570, -1, 7641, 7629, 7576, -1, 7569, 7642, 7578, -1, 7578, 7642, 7643, -1, 7550, 7644, 7586, -1, 7586, 7644, 7645, -1, 7644, 7578, 7643, -1, 7550, 7578, 7644, -1, 7611, 7646, 7647, -1, 7611, 7647, 7612, -1, 7648, 7649, 7574, -1, 7574, 7649, 7581, -1, 7581, 7650, 7604, -1, 7649, 7650, 7581, -1, 7604, 7651, 7605, -1, 7650, 7651, 7604, -1, 7605, 7652, 7606, -1, 7651, 7652, 7605, -1, 7606, 7653, 7608, -1, 7652, 7653, 7606, -1, 7608, 7654, 7609, -1, 7653, 7654, 7608, -1, 7609, 7655, 7613, -1, 7654, 7655, 7609, -1, 7613, 7656, 7590, -1, 7655, 7656, 7613, -1, 7590, 7657, 7592, -1, 7656, 7657, 7590, -1, 7592, 7658, 7602, -1, 7657, 7658, 7592, -1, 7602, 7659, 7546, -1, 7658, 7659, 7602, -1, 7546, 7660, 7547, -1, 7659, 7660, 7546, -1, 7547, 7646, 7611, -1, 7660, 7646, 7547, -1, 7648, 7574, 7565, -1, 7648, 7565, 7661, -1, 7647, 7662, 7612, -1, 7612, 7662, 7594, -1, 7594, 7663, 7595, -1, 7662, 7663, 7594, -1, 7595, 7664, 7596, -1, 7663, 7664, 7595, -1, 7596, 7665, 7597, -1, 7664, 7665, 7596, -1, 7597, 7666, 7598, -1, 7665, 7666, 7597, -1, 7598, 7667, 7599, -1, 7666, 7667, 7598, -1, 7599, 7668, 7564, -1, 7667, 7668, 7599, -1, 7564, 7669, 7560, -1, 7668, 7669, 7564, -1, 7560, 7670, 7552, -1, 7669, 7670, 7560, -1, 7552, 7671, 7553, -1, 7670, 7671, 7552, -1, 7553, 7672, 7556, -1, 7671, 7672, 7553, -1, 7556, 7673, 7561, -1, 7672, 7673, 7556, -1, 7561, 7661, 7565, -1, 7673, 7661, 7561, -1, 7674, 6756, 7548, -1, 7642, 7569, 6756, -1, 7569, 7548, 6756, -1, 7593, 7675, 7548, -1, 7548, 7675, 7674, -1, 7675, 7593, 7676, -1, 7676, 7593, 7554, -1, 7058, 7055, 7554, -1, 7554, 7055, 7676, -1, 7562, 7645, 7677, -1, 7562, 7586, 7645, -1, 7671, 7670, 7676, -1, 7676, 7672, 7671, -1, 7670, 7669, 7676, -1, 7055, 7673, 7676, -1, 7676, 7673, 7672, -1, 7669, 7668, 7676, -1, 7055, 7661, 7673, -1, 7055, 7648, 7661, -1, 7055, 7649, 7648, -1, 7668, 7675, 7676, -1, 7662, 7675, 7663, -1, 7663, 7675, 7664, -1, 7664, 7675, 7665, -1, 7665, 7675, 7666, -1, 7666, 7675, 7667, -1, 7667, 7675, 7668, -1, 7649, 7057, 7650, -1, 7650, 7057, 7651, -1, 7651, 7057, 7652, -1, 7662, 7674, 7675, -1, 7647, 7674, 7662, -1, 7646, 7674, 7647, -1, 7646, 7660, 7674, -1, 7678, 7679, 7057, -1, 7057, 7679, 7680, -1, 7680, 7681, 7057, -1, 7682, 7683, 7678, -1, 7678, 7683, 7679, -1, 7057, 7684, 7652, -1, 7681, 7684, 7057, -1, 7682, 7685, 7683, -1, 7684, 7686, 7652, -1, 7652, 7686, 7653, -1, 7653, 7686, 7654, -1, 7682, 6788, 7685, -1, 7686, 7687, 7654, -1, 7654, 7687, 7655, -1, 7682, 7688, 6788, -1, 7688, 6786, 6788, -1, 7687, 7689, 7655, -1, 7655, 7689, 7656, -1, 7656, 7689, 7657, -1, 7688, 6784, 6786, -1, 7689, 7690, 7657, -1, 7657, 7690, 7658, -1, 7688, 7691, 6784, -1, 7691, 6782, 6784, -1, 7690, 7692, 7658, -1, 7658, 7692, 7659, -1, 7691, 7677, 6782, -1, 7677, 6780, 6782, -1, 7659, 7693, 7660, -1, 7692, 7693, 7659, -1, 7660, 7693, 7674, -1, 7677, 6778, 6780, -1, 7693, 7694, 7674, -1, 7677, 6776, 6778, -1, 7694, 7695, 7674, -1, 7695, 7696, 7674, -1, 7677, 7625, 6776, -1, 7626, 7625, 7677, -1, 6776, 7625, 6774, -1, 7677, 7627, 7626, -1, 7625, 7624, 6774, -1, 7677, 7628, 7627, -1, 6774, 7623, 6772, -1, 7624, 7623, 6774, -1, 7645, 7615, 7628, -1, 6772, 7622, 6770, -1, 7623, 7622, 6772, -1, 7622, 7621, 6770, -1, 6770, 7620, 6768, -1, 7621, 7620, 6770, -1, 7645, 7614, 7615, -1, 7620, 7619, 6768, -1, 6768, 7619, 6766, -1, 7644, 7630, 7645, -1, 7645, 7630, 7614, -1, 6766, 7618, 6764, -1, 7619, 7618, 6766, -1, 7644, 7631, 7630, -1, 7618, 7617, 6764, -1, 7644, 7632, 7631, -1, 7644, 7633, 7632, -1, 7644, 7634, 7633, -1, 7644, 7635, 7634, -1, 7636, 7643, 7637, -1, 7637, 7643, 7638, -1, 7638, 7643, 7639, -1, 7639, 7643, 7640, -1, 7640, 7643, 7641, -1, 7643, 7642, 7641, -1, 6761, 7642, 6759, -1, 6763, 7642, 6761, -1, 6764, 7642, 6763, -1, 7641, 7642, 7629, -1, 7616, 7642, 7617, -1, 7629, 7642, 7616, -1, 7617, 7642, 6764, -1, 6756, 7674, 7696, -1, 7642, 6756, 6759, -1, 7644, 7643, 7635, -1, 7635, 7643, 7636, -1, 7677, 7645, 7628, -1, 7055, 7057, 7649, -1, 6788, 6789, 7135, -1, 7685, 6788, 7135, -1, 7683, 7135, 7138, -1, 7683, 7685, 7135, -1, 7679, 7138, 7147, -1, 7679, 7683, 7138, -1, 7680, 7147, 7134, -1, 7680, 7679, 7147, -1, 7681, 7134, 7126, -1, 7681, 7680, 7134, -1, 7684, 7126, 7119, -1, 7684, 7681, 7126, -1, 7686, 7119, 7118, -1, 7686, 7684, 7119, -1, 7687, 7118, 6814, -1, 7687, 7686, 7118, -1, 7689, 6814, 7258, -1, 7689, 7687, 6814, -1, 7690, 7258, 7256, -1, 7690, 7689, 7258, -1, 7692, 7256, 7253, -1, 7692, 7690, 7256, -1, 7693, 7253, 7241, -1, 7693, 7692, 7253, -1, 7694, 7241, 7230, -1, 7694, 7693, 7241, -1, 7695, 7230, 7229, -1, 7695, 7694, 7230, -1, 7696, 7229, 7233, -1, 7696, 7695, 7229, -1, 6756, 7696, 7233, -1, 6756, 7233, 6757, -1, 6683, 6682, 7697, -1, 6744, 6745, 7698, -1, 6682, 7699, 7697, -1, 6745, 7700, 7698, -1, 6682, 6681, 7699, -1, 7701, 6691, 7702, -1, 7700, 6746, 7703, -1, 7702, 6690, 7704, -1, 6691, 6690, 7702, -1, 6745, 6746, 7700, -1, 6680, 7705, 6681, -1, 7706, 6692, 7701, -1, 6681, 7705, 7699, -1, 7701, 6692, 6691, -1, 7704, 6689, 7707, -1, 6690, 6689, 7704, -1, 6746, 6747, 7703, -1, 6680, 6755, 7705, -1, 7708, 6693, 7706, -1, 7706, 6693, 6692, -1, 7707, 6688, 7709, -1, 6689, 6688, 7707, -1, 7710, 6754, 6680, -1, 7711, 6687, 7712, -1, 7709, 6687, 7711, -1, 6688, 6687, 7709, -1, 6680, 6754, 6755, -1, 7703, 6748, 7713, -1, 6747, 6748, 7703, -1, 6739, 6694, 6740, -1, 6740, 6694, 7708, -1, 7714, 6753, 7710, -1, 7708, 6694, 6693, -1, 6739, 7715, 6694, -1, 7710, 6753, 6754, -1, 7713, 6749, 7716, -1, 6687, 6686, 7712, -1, 6748, 6749, 7713, -1, 6739, 6741, 7715, -1, 7717, 6752, 7714, -1, 6686, 7718, 7712, -1, 7714, 6752, 6753, -1, 6741, 7719, 7715, -1, 7716, 6750, 7720, -1, 6749, 6750, 7716, -1, 6686, 6685, 7718, -1, 7720, 6751, 7717, -1, 7717, 6751, 6752, -1, 6750, 6751, 7720, -1, 6741, 6742, 7719, -1, 6685, 7721, 7718, -1, 6742, 7722, 7719, -1, 6685, 6684, 7721, -1, 6742, 6743, 7722, -1, 6684, 7723, 7721, -1, 6743, 7724, 7722, -1, 6684, 6683, 7723, -1, 6743, 6744, 7724, -1, 6683, 7697, 7723, -1, 6744, 7698, 7724, -1, 7705, 6755, 6321, -1, 7705, 6321, 7725, -1, 7699, 7725, 7726, -1, 7699, 7705, 7725, -1, 7697, 7726, 7727, -1, 7697, 7699, 7726, -1, 7723, 7727, 7728, -1, 7723, 7697, 7727, -1, 7721, 7728, 7729, -1, 7721, 7723, 7728, -1, 7718, 7729, 7730, -1, 7718, 7721, 7729, -1, 7712, 7730, 7731, -1, 7712, 7731, 7732, -1, 7712, 7718, 7730, -1, 7711, 7712, 7732, -1, 7709, 7732, 7733, -1, 7709, 7711, 7732, -1, 7707, 7733, 7734, -1, 7707, 7709, 7733, -1, 7704, 7734, 7735, -1, 7704, 7707, 7734, -1, 7702, 7735, 7736, -1, 7702, 7704, 7735, -1, 7701, 7736, 7737, -1, 7701, 7702, 7736, -1, 7706, 7737, 7738, -1, 7706, 7701, 7737, -1, 7708, 7738, 7739, -1, 7708, 7739, 6165, -1, 7708, 7706, 7738, -1, 6740, 7708, 6165, -1, 7740, 7741, 7742, -1, 7740, 7743, 7741, -1, 7744, 7745, 7746, -1, 7744, 7747, 7745, -1, 7748, 7742, 7749, -1, 7748, 7749, 7750, -1, 7751, 7752, 7747, -1, 7751, 7753, 7752, -1, 7754, 7755, 7756, -1, 7754, 7756, 7757, -1, 7758, 7746, 7759, -1, 7758, 7759, 7760, -1, 7761, 7762, 7763, -1, 7761, 7764, 7762, -1, 7765, 7766, 7755, -1, 7765, 7750, 7766, -1, 7765, 7755, 7754, -1, 7767, 7760, 7743, -1, 7767, 7743, 7740, -1, 7768, 7747, 7744, -1, 7768, 7751, 7747, -1, 7769, 7742, 7748, -1, 7769, 7740, 7742, -1, 7770, 7753, 7751, -1, 7770, 6176, 6167, -1, 7770, 7771, 7753, -1, 7770, 6167, 7771, -1, 7772, 7765, 7754, -1, 7773, 7744, 7746, -1, 7773, 7746, 7758, -1, 6727, 6161, 6160, -1, 7774, 7764, 7761, -1, 7774, 7757, 7764, -1, 7775, 7748, 7750, -1, 7775, 7750, 7765, -1, 7776, 7760, 7767, -1, 7776, 7758, 7760, -1, 7777, 6184, 6176, -1, 7777, 7751, 7768, -1, 7777, 6176, 7770, -1, 7777, 7770, 7751, -1, 7778, 7767, 7740, -1, 7778, 7740, 7769, -1, 7779, 7765, 7772, -1, 7779, 7775, 7765, -1, 7780, 7744, 7773, -1, 7780, 7768, 7744, -1, 7781, 7754, 7757, -1, 7781, 7757, 7774, -1, 7782, 7769, 7748, -1, 7782, 7748, 7775, -1, 7783, 7773, 7758, -1, 7783, 7758, 7776, -1, 7784, 7776, 7767, -1, 7784, 7767, 7778, -1, 7785, 7782, 7775, -1, 7785, 7775, 7779, -1, 7786, 7768, 7780, -1, 7786, 6184, 7777, -1, 7786, 7777, 7768, -1, 7787, 7754, 7781, -1, 7787, 7772, 7754, -1, 7788, 7725, 6321, -1, 7789, 7769, 7782, -1, 7789, 7778, 7769, -1, 7790, 7773, 7783, -1, 7788, 6321, 6138, -1, 7790, 7780, 7773, -1, 7791, 7776, 7784, -1, 7792, 7726, 7725, -1, 7792, 7727, 7726, -1, 7791, 7783, 7776, -1, 7793, 7782, 7785, -1, 7792, 7725, 7788, -1, 7793, 7789, 7782, -1, 7794, 7772, 7787, -1, 7795, 7727, 7792, -1, 7794, 7779, 7772, -1, 7796, 6138, 6140, -1, 7797, 7784, 7778, -1, 7797, 7789, 7793, -1, 7796, 7788, 6138, -1, 7797, 7778, 7789, -1, 7798, 6216, 6184, -1, 7799, 7728, 7727, -1, 7798, 6184, 7786, -1, 7798, 7780, 7790, -1, 7798, 7786, 7780, -1, 7800, 7783, 7791, -1, 7799, 7727, 7795, -1, 7800, 7790, 7783, -1, 7801, 7796, 6140, -1, 7802, 7797, 7793, -1, 7803, 7779, 7794, -1, 7804, 7788, 7796, -1, 7803, 7785, 7779, -1, 7804, 7792, 7788, -1, 7805, 7784, 7797, -1, 7806, 7729, 7728, -1, 7805, 7791, 7784, -1, 7806, 7728, 7799, -1, 7807, 6216, 7798, -1, 7807, 7798, 7790, -1, 7807, 7790, 7800, -1, 7808, 7805, 7797, -1, 7808, 7797, 7802, -1, 7809, 7796, 7801, -1, 7809, 7804, 7796, -1, 7810, 7795, 7792, -1, 7810, 7792, 7804, -1, 7811, 7802, 7793, -1, 7811, 7785, 7803, -1, 7811, 7793, 7785, -1, 7812, 7800, 7791, -1, 7813, 6140, 6156, -1, 7812, 7791, 7805, -1, 7813, 7801, 6140, -1, 7814, 7805, 7808, -1, 7814, 7812, 7805, -1, 7815, 7729, 7806, -1, 7816, 7802, 7811, -1, 7815, 7730, 7729, -1, 7817, 6276, 6216, -1, 7817, 6216, 7807, -1, 7817, 7807, 7800, -1, 7818, 7810, 7804, -1, 7817, 7800, 7812, -1, 7819, 6276, 7817, -1, 7819, 7812, 7814, -1, 7819, 7817, 7812, -1, 7818, 7804, 7809, -1, 7820, 7795, 7810, -1, 7821, 7808, 7802, -1, 7821, 7802, 7816, -1, 7820, 7799, 7795, -1, 7822, 7814, 7808, -1, 7823, 7801, 7813, -1, 7822, 7808, 7821, -1, 7824, 6220, 6276, -1, 7824, 6276, 7819, -1, 7823, 7809, 7801, -1, 7824, 7819, 7814, -1, 7824, 7814, 7822, -1, 7825, 7731, 7730, -1, 7825, 7732, 7731, -1, 7825, 7730, 7815, -1, 7826, 7813, 6156, -1, 7827, 7828, 7829, -1, 7827, 7822, 7828, -1, 7830, 7821, 7816, -1, 7830, 7822, 7821, -1, 7831, 7820, 7810, -1, 7830, 7828, 7822, -1, 7831, 7810, 7818, -1, 7832, 7806, 7799, -1, 7833, 7828, 7830, -1, 7834, 7828, 7833, -1, 7832, 7799, 7820, -1, 7834, 7835, 7836, -1, 7834, 7836, 7829, -1, 7834, 7829, 7828, -1, 7837, 7824, 7822, -1, 7837, 6220, 7824, -1, 7837, 7822, 7827, -1, 7838, 6223, 6220, -1, 7839, 7818, 7809, -1, 7838, 6220, 7837, -1, 7838, 7837, 7827, -1, 7839, 7809, 7823, -1, 7840, 7838, 7827, -1, 7840, 7829, 7841, -1, 7840, 7841, 6223, -1, 7840, 7827, 7829, -1, 7840, 6223, 7838, -1, 7842, 7833, 7830, -1, 7842, 7830, 7816, -1, 7843, 7732, 7825, -1, 7844, 7823, 7813, -1, 7842, 7816, 7811, -1, 7844, 7813, 7826, -1, 7845, 7833, 7842, -1, 7846, 7835, 7834, -1, 7847, 7820, 7831, -1, 7846, 7833, 7845, -1, 7846, 7834, 7833, -1, 7847, 7832, 7820, -1, 7846, 7848, 7835, -1, 7849, 7845, 7842, -1, 7850, 6156, 6190, -1, 7849, 7811, 7803, -1, 7849, 7842, 7811, -1, 7850, 7826, 6156, -1, 7851, 7815, 7806, -1, 7851, 7806, 7832, -1, 7852, 7845, 7849, -1, 7853, 7846, 7845, -1, 7854, 7818, 7839, -1, 7853, 7848, 7846, -1, 7853, 7855, 7848, -1, 7853, 7845, 7852, -1, 7856, 7849, 7803, -1, 7854, 7831, 7818, -1, 7856, 7852, 7849, -1, 7856, 7803, 7794, -1, 7857, 7733, 7732, -1, 7858, 7852, 7856, -1, 7859, 7853, 7852, -1, 7857, 7732, 7843, -1, 7859, 7855, 7853, -1, 7859, 7852, 7858, -1, 7859, 7860, 7855, -1, 7861, 7794, 7787, -1, 7861, 7858, 7856, -1, 7861, 7856, 7794, -1, 7862, 7839, 7823, -1, 7862, 7823, 7844, -1, 7863, 7832, 7847, -1, 7863, 7851, 7832, -1, 7864, 7858, 7861, -1, 7865, 7858, 7864, -1, 7865, 7859, 7858, -1, 7865, 6695, 7860, -1, 7865, 7860, 7859, -1, 7866, 7787, 7781, -1, 7867, 7844, 7826, -1, 7866, 7864, 7861, -1, 7867, 7826, 7850, -1, 7866, 7861, 7787, -1, 7868, 7865, 7864, -1, 7868, 6696, 6695, -1, 7868, 6695, 7865, -1, 7869, 7825, 7815, -1, 7868, 7864, 7866, -1, 7869, 7815, 7851, -1, 7870, 7847, 7831, -1, 7871, 7781, 7774, -1, 7871, 7866, 7781, -1, 7872, 7866, 7871, -1, 7870, 7831, 7854, -1, 7873, 7734, 7733, -1, 7873, 7733, 7857, -1, 7874, 7866, 7872, -1, 7874, 7872, 7875, -1, 7874, 7868, 7866, -1, 7876, 6736, 6696, -1, 7876, 6696, 7868, -1, 7876, 7874, 7875, -1, 7877, 7850, 6190, -1, 7876, 7868, 7874, -1, 7878, 7854, 7839, -1, 7879, 7872, 7871, -1, 7879, 7774, 7761, -1, 7879, 7871, 7774, -1, 7878, 7839, 7862, -1, 7880, 6734, 6736, -1, 7880, 6736, 7876, -1, 7880, 7875, 7872, -1, 7880, 7876, 7875, -1, 7880, 7872, 7879, -1, 7881, 7879, 7761, -1, 7882, 7851, 7863, -1, 7882, 7869, 7851, -1, 7881, 7761, 7763, -1, 7881, 7880, 7879, -1, 7883, 7862, 7844, -1, 7883, 7844, 7867, -1, 7884, 7880, 7881, -1, 7885, 6732, 6734, -1, 7886, 7825, 7869, -1, 7885, 6734, 7880, -1, 7886, 7843, 7825, -1, 7885, 7880, 7884, -1, 7887, 7888, 7889, -1, 7887, 6728, 6730, -1, 7887, 7763, 7888, -1, 7887, 7881, 7763, -1, 7887, 7884, 7881, -1, 7890, 6190, 6161, -1, 7887, 7889, 6728, -1, 7891, 6730, 6732, -1, 7891, 6732, 7885, -1, 7890, 7877, 6190, -1, 7891, 7885, 7884, -1, 7891, 7884, 7887, -1, 7892, 7863, 7847, -1, 7891, 7887, 6730, -1, 7892, 7847, 7870, -1, 7893, 7735, 7734, -1, 7893, 7734, 7873, -1, 7894, 7867, 7850, -1, 7894, 7850, 7877, -1, 7895, 7854, 7878, -1, 7895, 7870, 7854, -1, 7896, 7886, 7869, -1, 7896, 7869, 7882, -1, 7897, 7878, 7862, -1, 7897, 7862, 7883, -1, 7898, 7843, 7886, -1, 7898, 7857, 7843, -1, 7899, 7877, 7890, -1, 7899, 7894, 7877, -1, 7900, 7863, 7892, -1, 7900, 7882, 7863, -1, 7901, 7736, 7735, -1, 7901, 7735, 7893, -1, 7902, 7867, 7894, -1, 7902, 7883, 7867, -1, 7903, 7892, 7870, -1, 7903, 7870, 7895, -1, 7904, 7886, 7896, -1, 7904, 7898, 7886, -1, 7905, 7878, 7897, -1, 7905, 7895, 7878, -1, 7906, 7857, 7898, -1, 7906, 7873, 7857, -1, 7907, 7902, 7894, -1, 7907, 7894, 7899, -1, 7908, 7882, 7900, -1, 7908, 7896, 7882, -1, 7909, 7890, 6161, -1, 7909, 6161, 6727, -1, 7752, 7737, 7736, -1, 7752, 7738, 7737, -1, 7752, 7736, 7901, -1, 7910, 7883, 7902, -1, 7910, 7897, 7883, -1, 7911, 7900, 7892, -1, 7911, 7892, 7903, -1, 7912, 7898, 7904, -1, 7912, 7906, 7898, -1, 7913, 7903, 7895, -1, 7913, 7895, 7905, -1, 7914, 7893, 7873, -1, 7914, 7873, 7906, -1, 7762, 7902, 7907, -1, 7762, 7910, 7902, -1, 7741, 7904, 7896, -1, 7741, 7896, 7908, -1, 7889, 7899, 7890, -1, 7889, 7909, 6727, -1, 7889, 6727, 6728, -1, 7889, 7890, 7909, -1, 7753, 7738, 7752, -1, 7915, 7905, 7897, -1, 7915, 7897, 7910, -1, 7749, 7900, 7911, -1, 7749, 7908, 7900, -1, 7759, 7906, 7912, -1, 7759, 7914, 7906, -1, 7766, 7903, 7913, -1, 7766, 7911, 7903, -1, 7745, 7901, 7893, -1, 7745, 7893, 7914, -1, 7764, 7910, 7762, -1, 7764, 7915, 7910, -1, 7743, 7904, 7741, -1, 7743, 7912, 7904, -1, 7888, 7907, 7899, -1, 7888, 7899, 7889, -1, 7771, 6167, 6165, -1, 7771, 7739, 7738, -1, 7771, 6165, 7739, -1, 7771, 7738, 7753, -1, 7756, 7905, 7915, -1, 7756, 7913, 7905, -1, 7742, 7741, 7908, -1, 7742, 7908, 7749, -1, 7746, 7914, 7759, -1, 7746, 7745, 7914, -1, 7750, 7911, 7766, -1, 7750, 7749, 7911, -1, 7747, 7752, 7901, -1, 7747, 7901, 7745, -1, 7757, 7756, 7915, -1, 7757, 7915, 7764, -1, 7760, 7912, 7743, -1, 7760, 7759, 7912, -1, 7763, 7762, 7907, -1, 7763, 7907, 7888, -1, 7755, 7913, 7756, -1, 7755, 7766, 7913, -1, 6259, 6254, 6806, -1, 6259, 6806, 6724, -1, 7916, 6647, 5750, -1, 5750, 6647, 5751, -1, 7917, 7916, 5755, -1, 5755, 7916, 5750, -1, 7918, 7917, 5755, -1, 6695, 6738, 7919, -1, 7920, 7918, 5758, -1, 7921, 7920, 5765, -1, 7922, 7921, 5775, -1, 7923, 7922, 5784, -1, 7924, 7923, 5799, -1, 6656, 6658, 7540, -1, 6652, 6654, 7543, -1, 6650, 6652, 7544, -1, 6646, 6650, 7545, -1, 7545, 6791, 6646, -1, 7860, 6695, 7919, -1, 7544, 7545, 6650, -1, 6232, 6217, 6796, -1, 7543, 7544, 6652, -1, 6804, 6806, 6254, -1, 6802, 6804, 6247, -1, 6800, 6802, 6240, -1, 6798, 6800, 6233, -1, 6796, 6798, 6232, -1, 6794, 6796, 6217, -1, 7855, 7919, 7925, -1, 6790, 6794, 6225, -1, 7855, 7860, 7919, -1, 5775, 7921, 5765, -1, 7848, 7925, 7926, -1, 7848, 7855, 7925, -1, 7542, 7543, 6654, -1, 7835, 7926, 7927, -1, 7835, 7848, 7926, -1, 6233, 6232, 6798, -1, 7836, 7927, 7928, -1, 7836, 7835, 7927, -1, 7829, 7928, 7929, -1, 7541, 6654, 6656, -1, 7829, 7836, 7928, -1, 7541, 7542, 6654, -1, 5784, 7922, 5775, -1, 6647, 7930, 5751, -1, 7841, 7930, 6647, -1, 7841, 7829, 7929, -1, 7841, 7929, 7930, -1, 6240, 6233, 6800, -1, 6791, 7841, 6647, -1, 6791, 6647, 6646, -1, 6223, 7841, 6791, -1, 7540, 7541, 6656, -1, 5799, 7923, 5784, -1, 6790, 6223, 6791, -1, 6225, 6223, 6790, -1, 6247, 6240, 6802, -1, 7539, 6658, 6660, -1, 7539, 7540, 6658, -1, 5758, 7918, 5755, -1, 5824, 7924, 5799, -1, 6713, 7924, 5824, -1, 6254, 6247, 6804, -1, 6217, 6225, 6794, -1, 7538, 7539, 6660, -1, 7538, 6660, 6662, -1, 6723, 7538, 6662, -1, 6723, 6662, 6663, -1, 5765, 7920, 5758, -1, 7931, 7932, 7933, -1, 7934, 7935, 7936, -1, 7936, 7935, 7937, -1, 6002, 7938, 7939, -1, 7939, 7938, 7940, -1, 7940, 7938, 7941, -1, 7942, 7943, 7944, -1, 7945, 7943, 7942, -1, 7946, 7947, 7948, -1, 7948, 7947, 7945, -1, 7941, 7949, 7931, -1, 7931, 7949, 7932, -1, 7950, 7951, 7934, -1, 7934, 7951, 7935, -1, 7945, 7952, 7943, -1, 7947, 7952, 7945, -1, 7946, 7953, 7947, -1, 7932, 7953, 7946, -1, 6046, 7954, 6002, -1, 6002, 7954, 7938, -1, 7938, 7954, 7941, -1, 7941, 7954, 7949, -1, 7950, 7955, 7951, -1, 7944, 7955, 7950, -1, 7947, 7956, 7952, -1, 7953, 7956, 7947, -1, 7953, 7957, 7956, -1, 7949, 7957, 7932, -1, 7932, 7957, 7953, -1, 7943, 7958, 7944, -1, 7944, 7958, 7955, -1, 7957, 7959, 7956, -1, 7949, 7960, 7957, -1, 6046, 7960, 7954, -1, 7957, 7960, 7959, -1, 7954, 7960, 7949, -1, 7943, 7961, 7958, -1, 7952, 7961, 7943, -1, 7960, 7962, 7959, -1, 6046, 7962, 7960, -1, 6069, 7962, 6046, -1, 7952, 7963, 7961, -1, 7956, 7963, 7952, -1, 7959, 7964, 7956, -1, 7956, 7964, 7963, -1, 7004, 7965, 6090, -1, 6069, 7965, 7962, -1, 7959, 7965, 7964, -1, 6090, 7965, 6069, -1, 7962, 7965, 7959, -1, 7966, 7967, 5949, -1, 7968, 7969, 7967, -1, 7967, 7969, 5949, -1, 5949, 7969, 5957, -1, 7970, 7971, 7972, -1, 5957, 7973, 6892, -1, 7969, 7973, 5957, -1, 7968, 7973, 7969, -1, 7971, 7974, 7968, -1, 6895, 7975, 6897, -1, 7974, 7975, 7968, -1, 7967, 7976, 7968, -1, 7966, 7976, 7967, -1, 7972, 7976, 7966, -1, 7968, 7976, 7971, -1, 7971, 7976, 7972, -1, 6892, 7977, 6895, -1, 7973, 7977, 6892, -1, 6895, 7977, 7975, -1, 7968, 7977, 7973, -1, 7975, 7977, 7968, -1, 7978, 7979, 7980, -1, 7980, 7979, 6078, -1, 7981, 7982, 7970, -1, 6078, 7979, 6077, -1, 7971, 7982, 7974, -1, 7970, 7982, 7971, -1, 7982, 7983, 7974, -1, 7978, 7984, 7979, -1, 6897, 7985, 6899, -1, 7983, 7985, 7974, -1, 7978, 7986, 7984, -1, 7974, 7985, 7975, -1, 7975, 7985, 6897, -1, 7937, 7987, 7981, -1, 7982, 7987, 7983, -1, 7988, 7986, 7978, -1, 7981, 7987, 7982, -1, 7979, 7989, 6077, -1, 6077, 7989, 6100, -1, 7987, 7990, 7983, -1, 6899, 7991, 6901, -1, 7985, 7991, 6899, -1, 7983, 7991, 7985, -1, 7990, 7991, 7983, -1, 7935, 7992, 7937, -1, 7993, 7994, 7988, -1, 7937, 7992, 7987, -1, 7988, 7994, 7986, -1, 7987, 7992, 7990, -1, 6100, 7995, 5921, -1, 7989, 7995, 6100, -1, 7984, 7996, 7979, -1, 7992, 7997, 7990, -1, 6901, 7998, 6903, -1, 7991, 7998, 6901, -1, 7979, 7996, 7989, -1, 7990, 7998, 7991, -1, 7997, 7998, 7990, -1, 7935, 7999, 7992, -1, 7951, 7999, 7935, -1, 7992, 7999, 7997, -1, 8000, 8001, 8002, -1, 6903, 8003, 6912, -1, 8002, 8001, 7993, -1, 7993, 8001, 7994, -1, 7998, 8003, 6903, -1, 7997, 8003, 7998, -1, 7951, 8004, 7999, -1, 7989, 8005, 7995, -1, 7955, 8004, 7951, -1, 7996, 8005, 7989, -1, 8004, 8006, 7999, -1, 7986, 8007, 7984, -1, 7984, 8007, 7996, -1, 7999, 8008, 7997, -1, 7997, 8008, 8003, -1, 8006, 8009, 7999, -1, 7999, 8009, 8008, -1, 8000, 8010, 8001, -1, 6912, 8011, 7006, -1, 8003, 8011, 6912, -1, 8008, 8011, 8003, -1, 8009, 8011, 8008, -1, 7995, 8012, 5921, -1, 7958, 8013, 7955, -1, 7955, 8013, 8004, -1, 8004, 8013, 8006, -1, 8007, 8014, 7996, -1, 7996, 8014, 8005, -1, 8011, 8015, 7006, -1, 8006, 8015, 8009, -1, 8009, 8015, 8011, -1, 7994, 8016, 7986, -1, 7986, 8016, 8007, -1, 7958, 8017, 8013, -1, 7961, 8017, 7958, -1, 8013, 8018, 8006, -1, 8000, 8019, 8010, -1, 8017, 8018, 8013, -1, 8020, 8019, 8000, -1, 8006, 8018, 8015, -1, 8018, 8021, 8015, -1, 7995, 8022, 8012, -1, 8017, 8021, 8018, -1, 8021, 8023, 8015, -1, 8005, 8022, 7995, -1, 8015, 8024, 7006, -1, 7009, 8024, 7011, -1, 7006, 8024, 7009, -1, 8023, 8024, 8015, -1, 8016, 8025, 8007, -1, 8007, 8025, 8014, -1, 8021, 8026, 8023, -1, 8017, 8026, 8021, -1, 8001, 8027, 7994, -1, 7961, 8026, 8017, -1, 7994, 8027, 8016, -1, 7011, 8028, 7015, -1, 5921, 8029, 5919, -1, 8024, 8028, 7011, -1, 8023, 8028, 8024, -1, 8012, 8029, 5921, -1, 7963, 8030, 7961, -1, 7964, 8030, 7963, -1, 7961, 8030, 8026, -1, 8031, 8032, 8033, -1, 7004, 8034, 7965, -1, 7003, 8034, 7004, -1, 8033, 8032, 8020, -1, 7964, 8034, 8030, -1, 8020, 8032, 8019, -1, 7965, 8034, 7964, -1, 8030, 8034, 8026, -1, 8005, 8035, 8022, -1, 8023, 8036, 8028, -1, 8026, 8036, 8023, -1, 7003, 8037, 8034, -1, 8014, 8035, 8005, -1, 8034, 8037, 8026, -1, 8026, 8037, 8036, -1, 7003, 8038, 8037, -1, 7015, 8038, 7003, -1, 8016, 8039, 8025, -1, 8028, 8038, 7015, -1, 8027, 8039, 8016, -1, 8036, 8038, 8028, -1, 8037, 8038, 8036, -1, 8010, 8040, 8001, -1, 8001, 8040, 8027, -1, 8012, 8041, 8029, -1, 8022, 8041, 8012, -1, 8031, 8042, 8032, -1, 8029, 8043, 5919, -1, 8014, 8044, 8035, -1, 8025, 8044, 8014, -1, 8027, 8045, 8039, -1, 8040, 8045, 8027, -1, 8019, 8046, 8010, -1, 8010, 8046, 8040, -1, 8022, 8047, 8041, -1, 8035, 8047, 8022, -1, 8048, 8049, 8031, -1, 8031, 8049, 8042, -1, 8041, 8050, 8029, -1, 8029, 8050, 8043, -1, 8025, 8051, 8044, -1, 8039, 8051, 8025, -1, 8046, 8052, 8040, -1, 8040, 8052, 8045, -1, 8032, 8053, 8019, -1, 8019, 8053, 8046, -1, 8044, 8054, 8035, -1, 8035, 8054, 8047, -1, 8055, 8056, 8048, -1, 8048, 8056, 8049, -1, 5919, 8057, 5943, -1, 8043, 8057, 5919, -1, 8041, 8058, 8050, -1, 8047, 8058, 8041, -1, 8045, 8059, 8039, -1, 8039, 8059, 8051, -1, 8046, 8060, 8052, -1, 8053, 8060, 8046, -1, 8042, 8061, 8032, -1, 8032, 8061, 8053, -1, 8051, 8062, 8044, -1, 8044, 8062, 8054, -1, 8063, 8064, 8065, -1, 8065, 8064, 8055, -1, 8055, 8064, 8056, -1, 8057, 8066, 5943, -1, 8050, 8067, 8043, -1, 8043, 8067, 8057, -1, 8054, 8068, 8047, -1, 8047, 8068, 8058, -1, 8045, 8069, 8059, -1, 8052, 8069, 8045, -1, 8061, 8070, 8053, -1, 8053, 8070, 8060, -1, 8042, 8071, 8061, -1, 8049, 8071, 8042, -1, 8051, 8072, 8062, -1, 8059, 8072, 8051, -1, 8063, 8073, 8064, -1, 5964, 8073, 5962, -1, 5962, 8073, 8063, -1, 8057, 8074, 8066, -1, 8067, 8074, 8057, -1, 8050, 8075, 8067, -1, 8058, 8075, 8050, -1, 8054, 8076, 8068, -1, 8062, 8076, 8054, -1, 8052, 8077, 8069, -1, 8060, 8077, 8052, -1, 8071, 8078, 8061, -1, 8061, 8078, 8070, -1, 8049, 8079, 8071, -1, 8056, 8079, 8049, -1, 8069, 8080, 8059, -1, 8059, 8080, 8072, -1, 8075, 8081, 8067, -1, 8067, 8081, 8074, -1, 8068, 8082, 8058, -1, 8058, 8082, 8075, -1, 8062, 8083, 8076, -1, 8072, 8083, 8062, -1, 5943, 7966, 5949, -1, 8066, 7966, 5943, -1, 8070, 8084, 8060, -1, 8060, 8084, 8077, -1, 8079, 8085, 8071, -1, 8071, 8085, 8078, -1, 8056, 8086, 8079, -1, 8064, 8086, 8056, -1, 8069, 8087, 8080, -1, 8077, 8087, 8069, -1, 8075, 8088, 8081, -1, 8082, 8088, 8075, -1, 8076, 8089, 8068, -1, 8068, 8089, 8082, -1, 8080, 8090, 8072, -1, 8072, 8090, 8083, -1, 8074, 7972, 8066, -1, 8066, 7972, 7966, -1, 8070, 8091, 8084, -1, 8078, 8091, 8070, -1, 8079, 8092, 8085, -1, 8086, 8092, 8079, -1, 5977, 8093, 5964, -1, 5964, 8093, 8073, -1, 8064, 8093, 8086, -1, 8073, 8093, 8064, -1, 8084, 8094, 8077, -1, 8077, 8094, 8087, -1, 8089, 7936, 8082, -1, 8082, 7936, 8088, -1, 8076, 8095, 8089, -1, 8083, 8095, 8076, -1, 8087, 8096, 8080, -1, 8080, 8096, 8090, -1, 8081, 7970, 8074, -1, 8074, 7970, 7972, -1, 8085, 8097, 8078, -1, 8078, 8097, 8091, -1, 5977, 8098, 8093, -1, 8086, 8098, 8092, -1, 8093, 8098, 8086, -1, 8091, 7933, 8084, -1, 8084, 7933, 8094, -1, 8089, 7934, 7936, -1, 8095, 7934, 8089, -1, 8083, 8099, 8095, -1, 8090, 8099, 8083, -1, 8087, 7948, 8096, -1, 8094, 7948, 8087, -1, 8081, 7981, 7970, -1, 8088, 7981, 8081, -1, 8085, 7940, 8097, -1, 8092, 7940, 8085, -1, 8091, 7931, 7933, -1, 8097, 7931, 8091, -1, 8099, 7950, 8095, -1, 8095, 7950, 7934, -1, 8090, 7942, 8099, -1, 8096, 7942, 8090, -1, 8099, 7942, 7950, -1, 8094, 7946, 7948, -1, 7933, 7946, 8094, -1, 7936, 7937, 8088, -1, 8088, 7937, 7981, -1, 5977, 7939, 8098, -1, 6002, 7939, 5977, -1, 8092, 7939, 7940, -1, 8098, 7939, 8092, -1, 8097, 7941, 7931, -1, 7940, 7941, 8097, -1, 7942, 7944, 7950, -1, 7948, 7945, 8096, -1, 8096, 7945, 7942, -1, 7933, 7932, 7946, -1, 6694, 7715, 6078, -1, 6078, 7715, 7980, -1, 7980, 7719, 7978, -1, 7715, 7719, 7980, -1, 7978, 7722, 7988, -1, 7719, 7722, 7978, -1, 7988, 7724, 7993, -1, 7722, 7724, 7988, -1, 7993, 7698, 8002, -1, 7724, 7698, 7993, -1, 8002, 7700, 8000, -1, 7698, 7700, 8002, -1, 8000, 7703, 8020, -1, 7700, 7703, 8000, -1, 8020, 7713, 8033, -1, 7703, 7713, 8020, -1, 8033, 7716, 8031, -1, 7713, 7716, 8033, -1, 8031, 7720, 8048, -1, 7716, 7720, 8031, -1, 8048, 7717, 8055, -1, 7720, 7717, 8048, -1, 8055, 7714, 8065, -1, 7717, 7714, 8055, -1, 8065, 7710, 8063, -1, 7714, 7710, 8065, -1, 8063, 6680, 5962, -1, 7710, 6680, 8063, -1, 6721, 6679, 6629, -1, 6721, 6629, 7375, -1, 6720, 7375, 7372, -1, 6720, 6721, 7375, -1, 6705, 7372, 7364, -1, 6705, 6720, 7372, -1, 6719, 7364, 7363, -1, 6719, 6705, 7364, -1, 6718, 7363, 7345, -1, 6718, 6719, 7363, -1, 6717, 7345, 7344, -1, 6717, 6718, 7345, -1, 6716, 7344, 7355, -1, 6716, 6717, 7344, -1, 6712, 7355, 6538, -1, 6712, 6716, 7355, -1, 6713, 6712, 6538, -1, 7924, 6538, 7379, -1, 7924, 6713, 6538, -1, 7923, 7379, 7405, -1, 7923, 7924, 7379, -1, 7922, 7405, 7404, -1, 7922, 7923, 7405, -1, 7921, 7404, 7402, -1, 7921, 7922, 7404, -1, 7920, 7402, 7400, -1, 7920, 7921, 7402, -1, 7918, 7400, 7398, -1, 7918, 7920, 7400, -1, 7917, 7398, 7395, -1, 7917, 7918, 7398, -1, 7916, 7917, 7395, -1, 7916, 7395, 6648, -1, 6647, 7916, 6648, -1, 8100, 8101, 8102, -1, 8103, 8104, 8105, -1, 8106, 8100, 8102, -1, 8107, 8108, 8109, -1, 8110, 8111, 8112, -1, 8113, 8108, 8107, -1, 8114, 8112, 8111, -1, 8115, 8108, 8113, -1, 8116, 8110, 8112, -1, 8117, 8118, 8112, -1, 8117, 8112, 8114, -1, 7052, 8119, 8120, -1, 8121, 8116, 8112, -1, 7052, 8120, 8122, -1, 7052, 8122, 8104, -1, 8123, 8118, 8117, -1, 8124, 8125, 7052, -1, 8126, 8127, 8128, -1, 8129, 7052, 8125, -1, 8126, 8128, 8130, -1, 8126, 8106, 8102, -1, 8131, 8118, 8123, -1, 8126, 8132, 8133, -1, 8126, 8130, 8132, -1, 8134, 8124, 7052, -1, 8126, 8133, 8106, -1, 8135, 8127, 8126, -1, 8135, 8136, 8127, -1, 8135, 8137, 8136, -1, 8135, 8138, 8137, -1, 8135, 8139, 8138, -1, 8135, 8140, 8139, -1, 8104, 8118, 8141, -1, 8135, 8108, 8115, -1, 8142, 7052, 8129, -1, 8135, 8115, 8140, -1, 8141, 8118, 8131, -1, 7053, 7052, 8142, -1, 8143, 8134, 7052, -1, 8144, 7053, 8142, -1, 8145, 8143, 7052, -1, 8146, 8104, 8103, -1, 8146, 7052, 8104, -1, 8146, 8145, 7052, -1, 8147, 8146, 8103, -1, 8147, 8148, 8149, -1, 8147, 8103, 8148, -1, 8150, 8151, 8121, -1, 8150, 8152, 8151, -1, 8150, 8153, 8152, -1, 8150, 8154, 8153, -1, 8150, 8155, 8154, -1, 8150, 8156, 8155, -1, 8157, 7053, 8144, -1, 8150, 8121, 8112, -1, 8158, 8147, 8149, -1, 8159, 8108, 7053, -1, 8104, 8122, 8160, -1, 8159, 7053, 8157, -1, 8104, 8161, 8162, -1, 8104, 8163, 8161, -1, 8104, 8164, 8163, -1, 8104, 8141, 8164, -1, 8165, 8104, 8162, -1, 8133, 8149, 8106, -1, 8133, 8158, 8149, -1, 8166, 8108, 8159, -1, 8102, 8101, 8167, -1, 8102, 8167, 8156, -1, 8109, 8108, 8166, -1, 8102, 8156, 8150, -1, 8105, 8104, 8165, -1, 8168, 8131, 8123, -1, 8168, 8123, 8169, -1, 8168, 8170, 8131, -1, 8131, 8170, 8141, -1, 8141, 8171, 8164, -1, 8170, 8171, 8141, -1, 8164, 8172, 8163, -1, 8171, 8172, 8164, -1, 8163, 8173, 8161, -1, 8172, 8173, 8163, -1, 8161, 8174, 8162, -1, 8173, 8174, 8161, -1, 8162, 8175, 8165, -1, 8174, 8175, 8162, -1, 8165, 8176, 8105, -1, 8175, 8176, 8165, -1, 8105, 8177, 8103, -1, 8176, 8177, 8105, -1, 8103, 8178, 8148, -1, 8177, 8178, 8103, -1, 8148, 8179, 8149, -1, 8178, 8179, 8148, -1, 8149, 8180, 8106, -1, 8179, 8180, 8149, -1, 8106, 8181, 8100, -1, 8180, 8181, 8106, -1, 8100, 8182, 8101, -1, 8181, 8182, 8100, -1, 8101, 8182, 8183, -1, 8101, 8183, 8167, -1, 8183, 8184, 8167, -1, 8167, 8184, 8156, -1, 8156, 8185, 8155, -1, 8184, 8185, 8156, -1, 8155, 8186, 8154, -1, 8185, 8186, 8155, -1, 8154, 8187, 8153, -1, 8186, 8187, 8154, -1, 8153, 8188, 8152, -1, 8187, 8188, 8153, -1, 8152, 8189, 8151, -1, 8188, 8189, 8152, -1, 8151, 8190, 8121, -1, 8189, 8190, 8151, -1, 8121, 8191, 8116, -1, 8190, 8191, 8121, -1, 8116, 8192, 8110, -1, 8191, 8192, 8116, -1, 8110, 8193, 8111, -1, 8192, 8193, 8110, -1, 8111, 8194, 8114, -1, 8193, 8194, 8111, -1, 8114, 8195, 8117, -1, 8194, 8195, 8114, -1, 8117, 8169, 8123, -1, 8195, 8169, 8117, -1, 8150, 8196, 8102, -1, 8102, 8196, 8197, -1, 8118, 8198, 8112, -1, 8112, 8198, 8199, -1, 8112, 8196, 8150, -1, 8199, 8196, 8112, -1, 8128, 8200, 8201, -1, 8128, 8201, 8130, -1, 8201, 8202, 8130, -1, 8130, 8202, 8132, -1, 8132, 8203, 8133, -1, 8202, 8203, 8132, -1, 8133, 8204, 8158, -1, 8203, 8204, 8133, -1, 8158, 8205, 8147, -1, 8204, 8205, 8158, -1, 8147, 8206, 8146, -1, 8205, 8206, 8147, -1, 8146, 8207, 8145, -1, 8206, 8207, 8146, -1, 8145, 8208, 8143, -1, 8207, 8208, 8145, -1, 8143, 8209, 8134, -1, 8208, 8209, 8143, -1, 8134, 8210, 8124, -1, 8209, 8210, 8134, -1, 8124, 8211, 8125, -1, 8210, 8211, 8124, -1, 8125, 8212, 8129, -1, 8211, 8212, 8125, -1, 8129, 8213, 8142, -1, 8212, 8213, 8129, -1, 8142, 8214, 8144, -1, 8213, 8214, 8142, -1, 8215, 8157, 8144, -1, 8215, 8144, 8214, -1, 8215, 8216, 8157, -1, 8157, 8216, 8159, -1, 8159, 8217, 8166, -1, 8216, 8217, 8159, -1, 8166, 8218, 8109, -1, 8217, 8218, 8166, -1, 8109, 8219, 8107, -1, 8218, 8219, 8109, -1, 8107, 8220, 8113, -1, 8219, 8220, 8107, -1, 8113, 8221, 8115, -1, 8220, 8221, 8113, -1, 8115, 8222, 8140, -1, 8221, 8222, 8115, -1, 8140, 8223, 8139, -1, 8222, 8223, 8140, -1, 8139, 8224, 8138, -1, 8223, 8224, 8139, -1, 8138, 8225, 8137, -1, 8224, 8225, 8138, -1, 8137, 8226, 8136, -1, 8225, 8226, 8137, -1, 8136, 8227, 8127, -1, 8226, 8227, 8136, -1, 8127, 8200, 8128, -1, 8227, 8200, 8127, -1, 8197, 6613, 8102, -1, 8228, 8126, 6613, -1, 8126, 8102, 6613, -1, 8126, 8228, 8135, -1, 8135, 8228, 8229, -1, 8230, 8108, 8229, -1, 8229, 8108, 8135, -1, 8108, 8230, 7053, -1, 7053, 8230, 7051, -1, 8231, 8118, 8104, -1, 8231, 8198, 8118, -1, 8193, 8192, 8199, -1, 8199, 8194, 8193, -1, 8192, 8191, 8199, -1, 8198, 8195, 8199, -1, 8199, 8195, 8194, -1, 8191, 8190, 8199, -1, 8198, 8169, 8195, -1, 8198, 8168, 8169, -1, 8198, 8170, 8168, -1, 8190, 8196, 8199, -1, 8189, 8196, 8190, -1, 8188, 8196, 8189, -1, 8187, 8196, 8188, -1, 8186, 8196, 8187, -1, 8185, 8196, 8186, -1, 8184, 8196, 8185, -1, 8172, 8231, 8173, -1, 8171, 8231, 8172, -1, 8170, 8231, 8171, -1, 8184, 8197, 8196, -1, 8183, 8197, 8184, -1, 8182, 8197, 8183, -1, 8182, 8181, 8197, -1, 8232, 8233, 8231, -1, 8234, 8235, 8231, -1, 8231, 8235, 8232, -1, 8231, 8236, 8173, -1, 8233, 8236, 8231, -1, 8237, 8238, 8234, -1, 8234, 8238, 8235, -1, 8174, 8239, 8175, -1, 8173, 8239, 8174, -1, 8236, 8239, 8173, -1, 8237, 8240, 8238, -1, 8175, 8241, 8176, -1, 8239, 8241, 8175, -1, 8237, 6644, 8240, -1, 8237, 8242, 6644, -1, 8241, 8243, 8176, -1, 8177, 8243, 8178, -1, 8176, 8243, 8177, -1, 8242, 6642, 6644, -1, 8178, 8244, 8179, -1, 8243, 8244, 8178, -1, 8242, 6640, 6642, -1, 8242, 8245, 6640, -1, 8245, 6638, 6640, -1, 8244, 8246, 8179, -1, 8179, 8246, 8180, -1, 8245, 7054, 6638, -1, 7054, 6636, 6638, -1, 8180, 8247, 8181, -1, 8181, 8247, 8197, -1, 8246, 8247, 8180, -1, 8247, 8248, 8197, -1, 7054, 6634, 6636, -1, 7054, 6632, 6634, -1, 8248, 8249, 8197, -1, 8249, 8250, 8197, -1, 7054, 8210, 6632, -1, 8211, 8210, 7054, -1, 6632, 8210, 6630, -1, 7054, 8212, 8211, -1, 8210, 8209, 6630, -1, 7054, 8213, 8212, -1, 6630, 8208, 6628, -1, 8209, 8208, 6630, -1, 7051, 8214, 8213, -1, 8208, 8207, 6628, -1, 6628, 8207, 6626, -1, 8207, 8206, 6626, -1, 8206, 8205, 6626, -1, 6626, 8205, 6624, -1, 7051, 8215, 8214, -1, 6624, 8204, 6622, -1, 8205, 8204, 6624, -1, 8230, 8216, 7051, -1, 7051, 8216, 8215, -1, 6622, 8203, 6620, -1, 8204, 8203, 6622, -1, 8230, 8217, 8216, -1, 8203, 8202, 6620, -1, 8230, 8218, 8217, -1, 8230, 8219, 8218, -1, 8230, 8220, 8219, -1, 8230, 8221, 8220, -1, 8226, 8229, 8227, -1, 8225, 8229, 8226, -1, 8224, 8229, 8225, -1, 8223, 8229, 8224, -1, 8222, 8229, 8223, -1, 8201, 8228, 8202, -1, 8200, 8228, 8201, -1, 6620, 8228, 6618, -1, 6618, 8228, 6617, -1, 6617, 8228, 6612, -1, 8202, 8228, 6620, -1, 8227, 8228, 8200, -1, 8229, 8228, 8227, -1, 6613, 8197, 8250, -1, 8228, 6613, 6612, -1, 8230, 8229, 8221, -1, 8221, 8229, 8222, -1, 7054, 7051, 8213, -1, 8198, 8231, 8170, -1, 6644, 6645, 7488, -1, 8240, 6644, 7488, -1, 8238, 7488, 7494, -1, 8238, 8240, 7488, -1, 8235, 7484, 7483, -1, 8235, 7494, 7484, -1, 8235, 8238, 7494, -1, 8232, 8235, 7483, -1, 8233, 7483, 7492, -1, 8233, 8232, 7483, -1, 8236, 7492, 7496, -1, 8236, 8233, 7492, -1, 8239, 7496, 7501, -1, 8239, 8236, 7496, -1, 8241, 7501, 7505, -1, 8241, 8239, 7501, -1, 8243, 7505, 7509, -1, 8243, 8241, 7505, -1, 8244, 7509, 7514, -1, 8244, 8243, 7509, -1, 8246, 7514, 7521, -1, 8246, 8244, 7514, -1, 8247, 7521, 7525, -1, 8247, 8246, 7521, -1, 8248, 7525, 7532, -1, 8248, 8247, 7525, -1, 8249, 7532, 7534, -1, 8249, 8248, 7532, -1, 8250, 7534, 7536, -1, 8250, 8249, 7534, -1, 6613, 8250, 7536, -1, 6613, 7536, 6614, -1, 6579, 8251, 5550, -1, 5550, 8251, 5551, -1, 5551, 8252, 5547, -1, 8251, 8252, 5551, -1, 5547, 8253, 5545, -1, 8252, 8253, 5547, -1, 5545, 8254, 5561, -1, 8253, 8254, 5545, -1, 5561, 8255, 5573, -1, 8254, 8255, 5561, -1, 5573, 8256, 5580, -1, 8255, 8256, 5573, -1, 5580, 8257, 5585, -1, 8256, 8257, 5580, -1, 5585, 8258, 5597, -1, 8257, 8258, 5585, -1, 5597, 8259, 5602, -1, 8258, 8259, 5597, -1, 5602, 8260, 5614, -1, 8259, 8260, 5602, -1, 5614, 8261, 5631, -1, 8260, 8261, 5614, -1, 5631, 8262, 5628, -1, 8261, 8262, 5631, -1, 5628, 8263, 5534, -1, 8262, 8263, 5628, -1, 5534, 6552, 5535, -1, 8263, 6552, 5534, -1, 8264, 8265, 8266, -1, 8266, 8265, 8267, -1, 8268, 8269, 8270, -1, 8270, 8269, 8271, -1, 5594, 8272, 8273, -1, 6908, 5666, 5668, -1, 8273, 8272, 8274, -1, 8274, 8272, 8275, -1, 8276, 8277, 8278, -1, 8279, 8277, 8276, -1, 8267, 8280, 8281, -1, 8281, 8280, 8279, -1, 8264, 8282, 8265, -1, 8275, 8282, 8264, -1, 8268, 8283, 8269, -1, 8284, 8283, 8268, -1, 8279, 8285, 8277, -1, 8280, 8285, 8279, -1, 8267, 8286, 8280, -1, 8265, 8286, 8267, -1, 5637, 8287, 5594, -1, 5594, 8287, 8272, -1, 8272, 8287, 8275, -1, 8275, 8287, 8282, -1, 8278, 8288, 8284, -1, 8284, 8288, 8283, -1, 8286, 8289, 8280, -1, 8280, 8289, 8285, -1, 8282, 8290, 8265, -1, 8265, 8290, 8286, -1, 8278, 8291, 8288, -1, 8277, 8291, 8278, -1, 8286, 8292, 8289, -1, 8290, 8292, 8286, -1, 8282, 8293, 8290, -1, 5637, 8293, 8287, -1, 8287, 8293, 8282, -1, 8277, 8294, 8291, -1, 8285, 8294, 8277, -1, 8293, 8295, 8290, -1, 8290, 8295, 8292, -1, 5637, 8295, 8293, -1, 5533, 8295, 5637, -1, 8285, 8296, 8294, -1, 8289, 8296, 8285, -1, 8292, 8297, 8289, -1, 8289, 8297, 8296, -1, 6554, 8298, 5535, -1, 8292, 8298, 8297, -1, 8295, 8298, 8292, -1, 5533, 8298, 8295, -1, 5535, 8298, 5533, -1, 8299, 8300, 5541, -1, 8301, 8302, 8300, -1, 8300, 8302, 5541, -1, 5541, 8302, 5550, -1, 8303, 8304, 8305, -1, 5550, 8306, 6577, -1, 8302, 8306, 5550, -1, 8301, 8306, 8302, -1, 8304, 8307, 8301, -1, 8307, 8308, 8301, -1, 6575, 8308, 6573, -1, 8300, 8309, 8301, -1, 8299, 8309, 8300, -1, 8301, 8309, 8304, -1, 8305, 8309, 8299, -1, 8304, 8309, 8305, -1, 8308, 8310, 8301, -1, 6577, 8310, 6575, -1, 6575, 8310, 8308, -1, 8306, 8310, 6577, -1, 8301, 8310, 8306, -1, 8311, 8312, 8303, -1, 6908, 8313, 5666, -1, 8304, 8312, 8307, -1, 6908, 8314, 8313, -1, 8303, 8312, 8304, -1, 6909, 8314, 6908, -1, 8312, 8315, 8307, -1, 6573, 8316, 6571, -1, 6909, 8317, 8314, -1, 8308, 8316, 6573, -1, 8315, 8316, 8307, -1, 8307, 8316, 8308, -1, 6914, 8317, 6909, -1, 8271, 8318, 8311, -1, 8312, 8318, 8315, -1, 8311, 8318, 8312, -1, 8313, 8319, 5666, -1, 5666, 8319, 5689, -1, 8318, 8320, 8315, -1, 6571, 8321, 6570, -1, 8316, 8321, 6571, -1, 8315, 8321, 8316, -1, 8320, 8321, 8315, -1, 6906, 8322, 6914, -1, 8271, 8323, 8318, -1, 6914, 8322, 8317, -1, 8318, 8323, 8320, -1, 5689, 8324, 5510, -1, 8269, 8323, 8271, -1, 8319, 8324, 5689, -1, 8314, 8325, 8313, -1, 8323, 8326, 8320, -1, 6570, 8327, 6567, -1, 8321, 8327, 6570, -1, 8313, 8325, 8319, -1, 8320, 8327, 8321, -1, 8326, 8327, 8320, -1, 8269, 8328, 8323, -1, 8283, 8328, 8269, -1, 8323, 8328, 8326, -1, 6905, 8329, 6906, -1, 6906, 8329, 8322, -1, 6567, 8330, 6565, -1, 8327, 8330, 6567, -1, 8326, 8330, 8327, -1, 8319, 8331, 8324, -1, 8283, 8332, 8328, -1, 8325, 8331, 8319, -1, 8288, 8332, 8283, -1, 8314, 8333, 8325, -1, 8328, 8334, 8326, -1, 8326, 8334, 8330, -1, 8332, 8334, 8328, -1, 8317, 8333, 8314, -1, 8334, 8335, 8330, -1, 8332, 8335, 8334, -1, 6907, 8336, 6905, -1, 6905, 8336, 8329, -1, 8335, 8337, 8330, -1, 6565, 8338, 6563, -1, 8330, 8338, 6565, -1, 8324, 8339, 5510, -1, 8337, 8338, 8330, -1, 8288, 8340, 8332, -1, 8333, 8341, 8325, -1, 8325, 8341, 8331, -1, 8332, 8340, 8335, -1, 8335, 8340, 8337, -1, 8337, 8342, 8338, -1, 6563, 8342, 6562, -1, 8317, 8343, 8333, -1, 8338, 8342, 6563, -1, 8322, 8343, 8317, -1, 8291, 8344, 8288, -1, 8288, 8344, 8340, -1, 8294, 8344, 8291, -1, 6910, 8345, 6907, -1, 8344, 8346, 8340, -1, 6907, 8345, 8336, -1, 8340, 8347, 8337, -1, 8331, 8348, 8324, -1, 8337, 8347, 8342, -1, 8324, 8348, 8339, -1, 8340, 8349, 8347, -1, 8346, 8349, 8340, -1, 8342, 8350, 6562, -1, 6562, 8350, 6559, -1, 8343, 8351, 8333, -1, 8333, 8351, 8341, -1, 8349, 8350, 8347, -1, 8347, 8350, 8342, -1, 8294, 8352, 8344, -1, 8344, 8352, 8346, -1, 8296, 8352, 8294, -1, 8329, 8353, 8322, -1, 8322, 8353, 8343, -1, 8346, 8354, 8349, -1, 8350, 8354, 6559, -1, 8349, 8354, 8350, -1, 7002, 8355, 6910, -1, 6910, 8355, 8345, -1, 8297, 8356, 8296, -1, 8296, 8356, 8352, -1, 5510, 8357, 5508, -1, 8346, 8358, 8354, -1, 8339, 8357, 5510, -1, 8352, 8358, 8346, -1, 8331, 8359, 8348, -1, 8356, 8358, 8352, -1, 8358, 8360, 8354, -1, 8297, 8360, 8356, -1, 8356, 8360, 8358, -1, 8341, 8359, 8331, -1, 6555, 8361, 6554, -1, 8343, 8362, 8351, -1, 8360, 8361, 8354, -1, 8353, 8362, 8343, -1, 6554, 8361, 8298, -1, 8298, 8361, 8297, -1, 8297, 8361, 8360, -1, 6557, 8363, 6555, -1, 6559, 8363, 6557, -1, 6555, 8363, 8361, -1, 8336, 8364, 8329, -1, 8361, 8363, 8354, -1, 8354, 8363, 6559, -1, 8329, 8364, 8353, -1, 7001, 8365, 7002, -1, 7002, 8365, 8355, -1, 8348, 8366, 8339, -1, 8339, 8366, 8357, -1, 8357, 8367, 5508, -1, 8341, 8368, 8359, -1, 8351, 8368, 8341, -1, 8353, 8369, 8362, -1, 8364, 8369, 8353, -1, 8336, 8370, 8364, -1, 8345, 8370, 8336, -1, 7000, 8371, 7001, -1, 7001, 8371, 8365, -1, 8348, 8372, 8366, -1, 8359, 8372, 8348, -1, 8366, 8373, 8357, -1, 8357, 8373, 8367, -1, 8351, 8374, 8368, -1, 8362, 8374, 8351, -1, 8364, 8375, 8369, -1, 8370, 8375, 8364, -1, 8355, 8376, 8345, -1, 8345, 8376, 8370, -1, 6999, 8377, 7000, -1, 7000, 8377, 8371, -1, 8359, 8378, 8372, -1, 8368, 8378, 8359, -1, 5508, 8379, 5531, -1, 8367, 8379, 5508, -1, 8372, 8380, 8366, -1, 8366, 8380, 8373, -1, 8369, 8381, 8362, -1, 8362, 8381, 8374, -1, 8370, 8382, 8375, -1, 8376, 8382, 8370, -1, 8365, 8383, 8355, -1, 8355, 8383, 8376, -1, 6998, 8384, 6999, -1, 6999, 8384, 8377, -1, 8374, 8385, 8368, -1, 8368, 8385, 8378, -1, 8379, 8386, 5531, -1, 8373, 8387, 8367, -1, 8367, 8387, 8379, -1, 8372, 8388, 8380, -1, 8378, 8388, 8372, -1, 8375, 8389, 8369, -1, 8369, 8389, 8381, -1, 8383, 8390, 8376, -1, 8376, 8390, 8382, -1, 8371, 8391, 8365, -1, 8365, 8391, 8383, -1, 6998, 8392, 8384, -1, 5557, 8392, 5556, -1, 5556, 8392, 6997, -1, 6997, 8392, 6998, -1, 8374, 8393, 8385, -1, 8381, 8393, 8374, -1, 8379, 8394, 8386, -1, 8387, 8394, 8379, -1, 8373, 8395, 8387, -1, 8380, 8395, 8373, -1, 8385, 8396, 8378, -1, 8378, 8396, 8388, -1, 8375, 8397, 8389, -1, 8382, 8397, 8375, -1, 8391, 8398, 8383, -1, 8383, 8398, 8390, -1, 8371, 8399, 8391, -1, 8377, 8399, 8371, -1, 8381, 8400, 8393, -1, 8389, 8400, 8381, -1, 8387, 8401, 8394, -1, 8395, 8401, 8387, -1, 8388, 8402, 8380, -1, 8380, 8402, 8395, -1, 8393, 8403, 8385, -1, 8385, 8403, 8396, -1, 5531, 8299, 5541, -1, 8386, 8299, 5531, -1, 8390, 8404, 8382, -1, 8382, 8404, 8397, -1, 8391, 8405, 8398, -1, 8399, 8405, 8391, -1, 8377, 8406, 8399, -1, 8384, 8406, 8377, -1, 8397, 8407, 8389, -1, 8389, 8407, 8400, -1, 8395, 8408, 8401, -1, 8402, 8408, 8395, -1, 8388, 8409, 8402, -1, 8396, 8409, 8388, -1, 8393, 8410, 8403, -1, 8400, 8410, 8393, -1, 8386, 8305, 8299, -1, 8394, 8305, 8386, -1, 8390, 8411, 8404, -1, 8398, 8411, 8390, -1, 8399, 8412, 8405, -1, 8406, 8412, 8399, -1, 8392, 8413, 8384, -1, 5569, 8413, 5557, -1, 8384, 8413, 8406, -1, 5557, 8413, 8392, -1, 8404, 8414, 8397, -1, 8397, 8414, 8407, -1, 8402, 8270, 8408, -1, 8409, 8270, 8402, -1, 8403, 8415, 8396, -1, 8396, 8415, 8409, -1, 8407, 8416, 8400, -1, 8400, 8416, 8410, -1, 8401, 8303, 8394, -1, 8394, 8303, 8305, -1, 8405, 8417, 8398, -1, 8398, 8417, 8411, -1, 5569, 8418, 8413, -1, 8406, 8418, 8412, -1, 8413, 8418, 8406, -1, 8404, 8266, 8414, -1, 8411, 8266, 8404, -1, 8415, 8268, 8409, -1, 8409, 8268, 8270, -1, 8403, 8419, 8415, -1, 8410, 8419, 8403, -1, 8414, 8281, 8407, -1, 8407, 8281, 8416, -1, 8401, 8311, 8303, -1, 8408, 8311, 8401, -1, 8405, 8274, 8417, -1, 8412, 8274, 8405, -1, 8411, 8264, 8266, -1, 8417, 8264, 8411, -1, 8419, 8284, 8415, -1, 8415, 8284, 8268, -1, 8416, 8276, 8410, -1, 8410, 8276, 8419, -1, 8414, 8267, 8281, -1, 8266, 8267, 8414, -1, 8408, 8271, 8311, -1, 8270, 8271, 8408, -1, 5569, 8273, 8418, -1, 5594, 8273, 5569, -1, 8412, 8273, 8274, -1, 8418, 8273, 8412, -1, 8417, 8275, 8264, -1, 8274, 8275, 8417, -1, 8419, 8278, 8284, -1, 8276, 8278, 8419, -1, 8281, 8279, 8416, -1, 8416, 8279, 8276, -1, 6558, 6556, 8420, -1, 6589, 6591, 8255, -1, 6556, 8421, 8420, -1, 6591, 8256, 8255, -1, 6556, 6553, 8421, -1, 8422, 6574, 8423, -1, 8423, 6572, 8424, -1, 6574, 6572, 8423, -1, 8425, 6576, 8422, -1, 8422, 6576, 6574, -1, 8256, 6593, 8257, -1, 6591, 6593, 8256, -1, 6552, 8426, 6553, -1, 8424, 6569, 8427, -1, 6553, 8426, 8421, -1, 6572, 6569, 8424, -1, 6593, 6595, 8257, -1, 8428, 6578, 8425, -1, 6552, 6611, 8426, -1, 8425, 6578, 6576, -1, 8427, 6568, 8429, -1, 6569, 6568, 8427, -1, 8429, 6566, 8430, -1, 8430, 6566, 8431, -1, 6568, 6566, 8429, -1, 8257, 6597, 8258, -1, 6595, 6597, 8257, -1, 6582, 6579, 8428, -1, 6580, 6579, 6582, -1, 8263, 6609, 6552, -1, 8428, 6579, 6578, -1, 6552, 6609, 6611, -1, 6580, 8251, 6579, -1, 8258, 6599, 8259, -1, 6597, 6599, 8258, -1, 6566, 6564, 8431, -1, 6580, 6583, 8251, -1, 8262, 6607, 8263, -1, 6564, 8432, 8431, -1, 8263, 6607, 6609, -1, 8261, 6605, 8262, -1, 6583, 8252, 8251, -1, 8262, 6605, 6607, -1, 8259, 6601, 8260, -1, 6564, 6561, 8432, -1, 6599, 6601, 8259, -1, 8260, 6603, 8261, -1, 6583, 6585, 8252, -1, 8261, 6603, 6605, -1, 6601, 6603, 8260, -1, 6561, 8433, 8432, -1, 6585, 8253, 8252, -1, 6561, 6560, 8433, -1, 6585, 6587, 8253, -1, 6560, 8434, 8433, -1, 6587, 8254, 8253, -1, 6560, 6558, 8434, -1, 6587, 6589, 8254, -1, 6558, 8420, 8434, -1, 6589, 8255, 8254, -1, 8426, 6611, 5796, -1, 8426, 5795, 5794, -1, 8426, 5796, 5795, -1, 8421, 5794, 5878, -1, 8421, 8426, 5794, -1, 8420, 5878, 5873, -1, 8420, 8421, 5878, -1, 8434, 8420, 5873, -1, 8433, 5867, 5862, -1, 8433, 5873, 5867, -1, 8433, 8434, 5873, -1, 8432, 8433, 5862, -1, 8431, 5851, 5846, -1, 8431, 5862, 5851, -1, 8431, 8432, 5862, -1, 8430, 5846, 5840, -1, 8430, 8431, 5846, -1, 8429, 8430, 5840, -1, 8427, 5834, 5828, -1, 8427, 5840, 5834, -1, 8427, 8429, 5840, -1, 8424, 5828, 5821, -1, 8424, 8427, 5828, -1, 8423, 5821, 5820, -1, 8423, 8424, 5821, -1, 8422, 5820, 5802, -1, 8422, 8423, 5820, -1, 8425, 5802, 5813, -1, 8425, 8422, 5802, -1, 8428, 8425, 5813, -1, 6582, 8428, 5813, -1, 6582, 5813, 5810, -1, 8435, 8436, 8437, -1, 8435, 8438, 8436, -1, 8439, 8440, 8441, -1, 8439, 8442, 8440, -1, 8443, 8444, 8438, -1, 8443, 8445, 8444, -1, 8446, 8447, 8448, -1, 8446, 8449, 8447, -1, 8450, 8451, 8452, -1, 8450, 8437, 8451, -1, 8453, 8454, 8455, -1, 8453, 8455, 8456, -1, 8457, 8458, 8449, -1, 8457, 8441, 8458, -1, 8459, 8460, 8461, -1, 8459, 8452, 8460, -1, 8462, 8438, 8435, -1, 8462, 8443, 8438, -1, 8463, 8461, 8442, -1, 8463, 8442, 8439, -1, 8464, 5762, 5753, -1, 8464, 8465, 8445, -1, 8464, 5753, 8465, -1, 8464, 8445, 8443, -1, 8466, 8449, 8446, -1, 8466, 8457, 8449, -1, 8467, 8435, 8437, -1, 8467, 8437, 8450, -1, 6610, 5788, 5796, -1, 8468, 8454, 8453, -1, 8468, 8448, 8454, -1, 8469, 8439, 8441, -1, 5753, 5751, 7930, -1, 8469, 8441, 8457, -1, 8470, 8450, 8452, -1, 8470, 8452, 8459, -1, 8471, 5769, 5762, -1, 8471, 5762, 8464, -1, 8471, 8443, 8462, -1, 8471, 8464, 8443, -1, 8472, 8459, 8461, -1, 8472, 8461, 8463, -1, 8473, 8457, 8466, -1, 8473, 8469, 8457, -1, 8474, 8435, 8467, -1, 8474, 8462, 8435, -1, 8475, 8446, 8448, -1, 8475, 8448, 8468, -1, 8476, 8439, 8469, -1, 8476, 8463, 8439, -1, 8477, 8467, 8450, -1, 8477, 8450, 8470, -1, 8478, 8459, 8472, -1, 8478, 8470, 8459, -1, 8479, 8476, 8469, -1, 8479, 8469, 8473, -1, 8480, 8462, 8474, -1, 8480, 5769, 8471, -1, 8480, 8471, 8462, -1, 8481, 8446, 8475, -1, 8481, 8466, 8446, -1, 8482, 8463, 8476, -1, 8482, 8472, 8463, -1, 8483, 6726, 5909, -1, 8484, 8474, 8467, -1, 8484, 8467, 8477, -1, 8483, 5909, 5728, -1, 8485, 6729, 6726, -1, 8486, 8477, 8470, -1, 8486, 8470, 8478, -1, 8487, 8482, 8476, -1, 8485, 6726, 8483, -1, 8487, 8476, 8479, -1, 8488, 6731, 6729, -1, 8489, 8466, 8481, -1, 8488, 6729, 8485, -1, 8489, 8473, 8466, -1, 8490, 8478, 8472, -1, 8491, 5728, 5727, -1, 8490, 8472, 8482, -1, 8491, 8483, 5728, -1, 8492, 5808, 5769, -1, 8492, 5769, 8480, -1, 8492, 8474, 8484, -1, 8492, 8480, 8474, -1, 8493, 6733, 6731, -1, 8494, 8484, 8477, -1, 8494, 8477, 8486, -1, 8493, 6731, 8488, -1, 8495, 8482, 8487, -1, 8495, 8490, 8482, -1, 8496, 8491, 5727, -1, 8497, 8473, 8489, -1, 8497, 8479, 8473, -1, 8498, 8483, 8491, -1, 8498, 8485, 8483, -1, 8499, 8486, 8478, -1, 8500, 6735, 6733, -1, 8499, 8478, 8490, -1, 8501, 5808, 8492, -1, 8501, 8484, 8494, -1, 8500, 6733, 8493, -1, 8501, 8492, 8484, -1, 8502, 8490, 8495, -1, 8502, 8499, 8490, -1, 8503, 8491, 8496, -1, 8504, 8487, 8479, -1, 8503, 8498, 8491, -1, 8505, 8488, 8485, -1, 8504, 8479, 8497, -1, 8505, 8485, 8498, -1, 8506, 8494, 8486, -1, 8506, 8486, 8499, -1, 8507, 5727, 5744, -1, 8508, 8506, 8499, -1, 8508, 8499, 8502, -1, 8507, 8496, 5727, -1, 8509, 8495, 8487, -1, 8509, 8487, 8504, -1, 8510, 6737, 6735, -1, 8510, 6735, 8500, -1, 8511, 5865, 5808, -1, 8511, 5808, 8501, -1, 8511, 8501, 8494, -1, 8511, 8494, 8506, -1, 8512, 5865, 8511, -1, 8512, 8506, 8508, -1, 8512, 8511, 8506, -1, 8513, 8505, 8498, -1, 8513, 8498, 8503, -1, 8514, 8495, 8509, -1, 8514, 8502, 8495, -1, 8515, 8488, 8505, -1, 8515, 8493, 8488, -1, 8516, 8508, 8502, -1, 8516, 8502, 8514, -1, 8517, 5806, 5865, -1, 8518, 8503, 8496, -1, 8517, 8512, 8508, -1, 8518, 8496, 8507, -1, 8517, 8508, 8516, -1, 8517, 5865, 8512, -1, 8519, 6697, 6737, -1, 8519, 6737, 8510, -1, 8520, 8516, 8521, -1, 8522, 8507, 5744, -1, 8520, 8521, 6584, -1, 8523, 8516, 8514, -1, 8523, 8514, 8509, -1, 8523, 8521, 8516, -1, 8524, 8515, 8505, -1, 8524, 8505, 8513, -1, 8525, 8500, 8493, -1, 8526, 8521, 8523, -1, 8527, 6588, 6586, -1, 8525, 8493, 8515, -1, 8527, 6586, 6584, -1, 8527, 6584, 8521, -1, 8527, 8521, 8526, -1, 8528, 5806, 8517, -1, 8528, 8517, 8516, -1, 8528, 8516, 8520, -1, 8529, 5810, 5806, -1, 8530, 8503, 8518, -1, 8529, 5806, 8528, -1, 8529, 8528, 8520, -1, 8530, 8513, 8503, -1, 8531, 5810, 8529, -1, 8531, 8529, 8520, -1, 8531, 6584, 6581, -1, 8531, 6581, 5810, -1, 8531, 8520, 6584, -1, 8532, 6738, 6697, -1, 8533, 8523, 8509, -1, 8532, 6697, 8519, -1, 8533, 8509, 8504, -1, 8533, 8526, 8523, -1, 8534, 8507, 8522, -1, 8535, 8526, 8533, -1, 8534, 8518, 8507, -1, 8536, 8525, 8515, -1, 8537, 8526, 8535, -1, 8537, 6590, 6588, -1, 8536, 8515, 8524, -1, 8537, 6588, 8527, -1, 8537, 8527, 8526, -1, 8538, 8504, 8497, -1, 8539, 5744, 5773, -1, 8538, 8535, 8533, -1, 8538, 8533, 8504, -1, 8539, 8522, 5744, -1, 8540, 8535, 8538, -1, 8541, 8500, 8525, -1, 8542, 6590, 8537, -1, 8542, 8537, 8535, -1, 8541, 8510, 8500, -1, 8542, 6592, 6590, -1, 8542, 8535, 8540, -1, 8543, 8540, 8538, -1, 8543, 8497, 8489, -1, 8544, 8513, 8530, -1, 8543, 8538, 8497, -1, 8544, 8524, 8513, -1, 8545, 8540, 8543, -1, 8546, 7919, 6738, -1, 8547, 8540, 8545, -1, 8547, 8542, 8540, -1, 8547, 6592, 8542, -1, 8546, 6738, 8532, -1, 8547, 6594, 6592, -1, 8548, 8489, 8481, -1, 8548, 8545, 8543, -1, 8548, 8543, 8489, -1, 8549, 8530, 8518, -1, 8550, 8545, 8548, -1, 8549, 8518, 8534, -1, 8551, 8525, 8536, -1, 8552, 8547, 8545, -1, 8552, 6594, 8547, -1, 8551, 8541, 8525, -1, 8552, 6596, 6594, -1, 8552, 8545, 8550, -1, 8553, 8481, 8475, -1, 8554, 8522, 8539, -1, 8553, 8548, 8481, -1, 8553, 8550, 8548, -1, 8554, 8534, 8522, -1, 8555, 8550, 8553, -1, 8555, 6598, 6596, -1, 8555, 8552, 8550, -1, 8556, 8510, 8541, -1, 8555, 6596, 8552, -1, 8556, 8519, 8510, -1, 8557, 8475, 8468, -1, 8558, 8536, 8524, -1, 8557, 8553, 8475, -1, 8558, 8524, 8544, -1, 8559, 8553, 8557, -1, 8560, 7925, 7919, -1, 8561, 8555, 8553, -1, 8561, 8553, 8559, -1, 8560, 7919, 8546, -1, 8561, 8559, 8562, -1, 8563, 6600, 6598, -1, 8563, 6598, 8555, -1, 8563, 8555, 8561, -1, 8563, 8561, 8562, -1, 8564, 8539, 5773, -1, 8565, 8557, 8468, -1, 8565, 8559, 8557, -1, 8565, 8468, 8453, -1, 8566, 8544, 8530, -1, 8566, 8530, 8549, -1, 8567, 6602, 6600, -1, 8567, 6600, 8563, -1, 8567, 8562, 8559, -1, 8567, 8563, 8562, -1, 8567, 8559, 8565, -1, 8568, 8453, 8456, -1, 8569, 8541, 8551, -1, 8569, 8556, 8541, -1, 8568, 8565, 8453, -1, 8568, 8567, 8565, -1, 8570, 8549, 8534, -1, 8570, 8534, 8554, -1, 8571, 8567, 8568, -1, 8572, 6604, 6602, -1, 8572, 6602, 8567, -1, 8573, 8532, 8519, -1, 8572, 8567, 8571, -1, 8573, 8519, 8556, -1, 8574, 8575, 8576, -1, 8574, 8568, 8456, -1, 8574, 6608, 6606, -1, 8574, 8576, 6608, -1, 8574, 8456, 8575, -1, 8574, 8571, 8568, -1, 8577, 5773, 5788, -1, 8578, 6606, 6604, -1, 8578, 6604, 8572, -1, 8578, 8572, 8571, -1, 8577, 8564, 5773, -1, 8578, 8574, 6606, -1, 8578, 8571, 8574, -1, 8579, 8551, 8536, -1, 8579, 8536, 8558, -1, 8580, 7926, 7925, -1, 8580, 7925, 8560, -1, 8581, 8554, 8539, -1, 8581, 8539, 8564, -1, 8582, 8544, 8566, -1, 8582, 8558, 8544, -1, 8583, 8573, 8556, -1, 8583, 8556, 8569, -1, 8584, 8566, 8549, -1, 8584, 8549, 8570, -1, 8585, 8532, 8573, -1, 8585, 8546, 8532, -1, 8586, 8564, 8577, -1, 8586, 8581, 8564, -1, 8587, 8569, 8551, -1, 8587, 8551, 8579, -1, 8588, 7927, 7926, -1, 8588, 7926, 8580, -1, 8589, 8554, 8581, -1, 8589, 8570, 8554, -1, 8590, 8579, 8558, -1, 8590, 8558, 8582, -1, 8591, 8573, 8583, -1, 8591, 8585, 8573, -1, 8592, 8566, 8584, -1, 8592, 8582, 8566, -1, 8593, 8546, 8585, -1, 8593, 8560, 8546, -1, 8594, 8581, 8586, -1, 8594, 8589, 8581, -1, 8595, 8583, 8569, -1, 8595, 8569, 8587, -1, 8596, 8577, 5788, -1, 8596, 5788, 6610, -1, 8444, 7928, 7927, -1, 8444, 7927, 8588, -1, 8597, 8570, 8589, -1, 8597, 8584, 8570, -1, 8598, 8587, 8579, -1, 8598, 8579, 8590, -1, 8599, 8585, 8591, -1, 8599, 8593, 8585, -1, 8600, 8590, 8582, -1, 8600, 8582, 8592, -1, 8601, 8580, 8560, -1, 8601, 8560, 8593, -1, 8455, 8597, 8589, -1, 8455, 8589, 8594, -1, 8602, 8583, 8595, -1, 8602, 8591, 8583, -1, 8576, 8596, 6610, -1, 8576, 6610, 6608, -1, 8576, 8586, 8577, -1, 8576, 8577, 8596, -1, 8445, 7929, 7928, -1, 8445, 7928, 8444, -1, 8603, 8584, 8597, -1, 8603, 8592, 8584, -1, 8440, 8587, 8598, -1, 8440, 8595, 8587, -1, 8451, 8593, 8599, -1, 8451, 8601, 8593, -1, 8458, 8598, 8590, -1, 8458, 8590, 8600, -1, 8436, 8580, 8601, -1, 8436, 8588, 8580, -1, 8454, 8597, 8455, -1, 8454, 8603, 8597, -1, 8460, 8599, 8591, -1, 8460, 8591, 8602, -1, 8575, 8594, 8586, -1, 8575, 8586, 8576, -1, 8465, 7930, 7929, -1, 8465, 5753, 7930, -1, 8465, 7929, 8445, -1, 8447, 8600, 8592, -1, 8447, 8592, 8603, -1, 8442, 8602, 8595, -1, 8442, 8595, 8440, -1, 8437, 8601, 8451, -1, 8437, 8436, 8601, -1, 8441, 8440, 8598, -1, 8441, 8598, 8458, -1, 8438, 8588, 8436, -1, 8438, 8444, 8588, -1, 8448, 8603, 8454, -1, 8448, 8447, 8603, -1, 8452, 8599, 8460, -1, 8452, 8451, 8599, -1, 8456, 8455, 8594, -1, 8456, 8594, 8575, -1, 8449, 8600, 8447, -1, 8449, 8458, 8600, -1, 8461, 8602, 8442, -1, 8461, 8460, 8602, -1, 6459, 8604, 5139, -1, 5139, 8604, 5141, -1, 5141, 8605, 5136, -1, 8604, 8605, 5141, -1, 5136, 8606, 5134, -1, 8605, 8606, 5136, -1, 5134, 8607, 5150, -1, 8606, 8607, 5134, -1, 5150, 8608, 5162, -1, 8607, 8608, 5150, -1, 5162, 8609, 5168, -1, 8608, 8609, 5162, -1, 5168, 8610, 5174, -1, 8609, 8610, 5168, -1, 5174, 8611, 5186, -1, 8610, 8611, 5174, -1, 5186, 8612, 5190, -1, 8611, 8612, 5186, -1, 5190, 8613, 5203, -1, 8612, 8613, 5190, -1, 5203, 8614, 5221, -1, 8613, 8614, 5203, -1, 5221, 8615, 5217, -1, 8614, 8615, 5221, -1, 5217, 8616, 5121, -1, 8615, 8616, 5217, -1, 5121, 6432, 5122, -1, 8616, 6432, 5121, -1, 8617, 8618, 8619, -1, 8620, 8618, 8617, -1, 5183, 8621, 8622, -1, 8622, 8621, 8623, -1, 6988, 5255, 5257, -1, 8623, 8621, 8624, -1, 8625, 8626, 8627, -1, 8628, 8626, 8625, -1, 8629, 8630, 8631, -1, 8631, 8630, 8628, -1, 8632, 8633, 8634, -1, 8624, 8633, 8632, -1, 8635, 8636, 8620, -1, 8620, 8636, 8618, -1, 8628, 8637, 8626, -1, 8630, 8637, 8628, -1, 8629, 8638, 8630, -1, 8634, 8638, 8629, -1, 5226, 8639, 5183, -1, 5183, 8639, 8621, -1, 8621, 8639, 8624, -1, 8624, 8639, 8633, -1, 8627, 8640, 8635, -1, 8635, 8640, 8636, -1, 8638, 8641, 8630, -1, 8630, 8641, 8637, -1, 8633, 8642, 8634, -1, 8634, 8642, 8638, -1, 8626, 8643, 8627, -1, 8627, 8643, 8640, -1, 8638, 8644, 8641, -1, 8642, 8644, 8638, -1, 8633, 8645, 8642, -1, 5226, 8645, 8639, -1, 8639, 8645, 8633, -1, 8626, 8646, 8643, -1, 8637, 8646, 8626, -1, 8645, 8647, 8642, -1, 8642, 8647, 8644, -1, 5226, 8647, 8645, -1, 5120, 8647, 5226, -1, 8637, 8648, 8646, -1, 8641, 8648, 8637, -1, 8644, 8649, 8641, -1, 8641, 8649, 8648, -1, 6434, 8650, 5122, -1, 8644, 8650, 8649, -1, 8647, 8650, 8644, -1, 5120, 8650, 8647, -1, 5122, 8650, 5120, -1, 8651, 8652, 5130, -1, 8653, 8654, 8652, -1, 8652, 8654, 5130, -1, 5130, 8654, 5139, -1, 8655, 8656, 8657, -1, 5139, 8658, 6457, -1, 8654, 8658, 5139, -1, 8653, 8658, 8654, -1, 8656, 8659, 8653, -1, 6456, 8660, 6453, -1, 8659, 8660, 8653, -1, 8652, 8661, 8653, -1, 8651, 8661, 8652, -1, 8653, 8661, 8656, -1, 8656, 8661, 8657, -1, 8657, 8661, 8651, -1, 6457, 8662, 6456, -1, 6456, 8662, 8660, -1, 8658, 8662, 6457, -1, 8660, 8662, 8653, -1, 8653, 8662, 8658, -1, 8655, 8663, 8656, -1, 6988, 8664, 5255, -1, 8656, 8663, 8659, -1, 8665, 8663, 8655, -1, 6988, 8666, 8664, -1, 8663, 8667, 8659, -1, 6987, 8666, 6988, -1, 6453, 8668, 6451, -1, 8660, 8668, 6453, -1, 6987, 8669, 8666, -1, 8659, 8668, 8660, -1, 8667, 8668, 8659, -1, 8619, 8670, 8665, -1, 8665, 8670, 8663, -1, 6986, 8669, 6987, -1, 8663, 8670, 8667, -1, 8670, 8671, 8667, -1, 8664, 8672, 5255, -1, 5255, 8672, 5278, -1, 8668, 8673, 6451, -1, 6451, 8673, 6449, -1, 8667, 8673, 8668, -1, 8671, 8673, 8667, -1, 8670, 8674, 8671, -1, 8619, 8674, 8670, -1, 6985, 8675, 6986, -1, 8618, 8674, 8619, -1, 6986, 8675, 8669, -1, 5278, 8676, 5099, -1, 8672, 8676, 5278, -1, 8674, 8677, 8671, -1, 8666, 8678, 8664, -1, 6449, 8679, 6448, -1, 8673, 8679, 6449, -1, 8671, 8679, 8673, -1, 8677, 8679, 8671, -1, 8664, 8678, 8672, -1, 8618, 8680, 8674, -1, 8674, 8680, 8677, -1, 8636, 8680, 8618, -1, 6448, 8681, 6445, -1, 6984, 8682, 6985, -1, 6985, 8682, 8675, -1, 8679, 8681, 6448, -1, 8677, 8681, 8679, -1, 8672, 8683, 8676, -1, 8636, 8684, 8680, -1, 8640, 8684, 8636, -1, 8678, 8683, 8672, -1, 8680, 8685, 8677, -1, 8666, 8686, 8678, -1, 8677, 8685, 8681, -1, 8684, 8685, 8680, -1, 8669, 8686, 8666, -1, 8684, 8687, 8685, -1, 8685, 8687, 8681, -1, 6983, 8688, 6984, -1, 6984, 8688, 8682, -1, 8687, 8689, 8681, -1, 6445, 8690, 6443, -1, 8681, 8690, 6445, -1, 8689, 8690, 8681, -1, 8676, 8691, 5099, -1, 8640, 8692, 8684, -1, 8684, 8692, 8687, -1, 8686, 8693, 8678, -1, 8687, 8692, 8689, -1, 8678, 8693, 8683, -1, 8689, 8694, 8690, -1, 6443, 8694, 6441, -1, 8690, 8694, 6443, -1, 8643, 8695, 8640, -1, 8669, 8696, 8686, -1, 8675, 8696, 8669, -1, 8646, 8695, 8643, -1, 8640, 8695, 8692, -1, 6956, 8697, 6983, -1, 8695, 8698, 8692, -1, 6983, 8697, 8688, -1, 8692, 8699, 8689, -1, 8683, 8700, 8676, -1, 8689, 8699, 8694, -1, 8698, 8701, 8692, -1, 8676, 8700, 8691, -1, 8692, 8701, 8699, -1, 8694, 8702, 6441, -1, 6441, 8702, 6439, -1, 8701, 8702, 8699, -1, 8696, 8703, 8686, -1, 8699, 8702, 8694, -1, 8686, 8703, 8693, -1, 8646, 8704, 8695, -1, 8695, 8704, 8698, -1, 8648, 8704, 8646, -1, 8682, 8705, 8675, -1, 8675, 8705, 8696, -1, 8698, 8706, 8701, -1, 8702, 8706, 6439, -1, 8701, 8706, 8702, -1, 6955, 8707, 6956, -1, 8649, 8708, 8648, -1, 8648, 8708, 8704, -1, 6956, 8707, 8697, -1, 8698, 8709, 8706, -1, 5099, 8710, 5097, -1, 8704, 8709, 8698, -1, 8691, 8710, 5099, -1, 8708, 8709, 8704, -1, 8683, 8711, 8700, -1, 8709, 8712, 8706, -1, 8649, 8712, 8708, -1, 8708, 8712, 8709, -1, 6435, 8713, 6434, -1, 8693, 8711, 8683, -1, 8712, 8713, 8706, -1, 6434, 8713, 8650, -1, 8650, 8713, 8649, -1, 8696, 8714, 8703, -1, 8649, 8713, 8712, -1, 8705, 8714, 8696, -1, 6437, 8715, 6435, -1, 6439, 8715, 6437, -1, 8706, 8715, 6439, -1, 6435, 8715, 8713, -1, 8713, 8715, 8706, -1, 8688, 8716, 8682, -1, 8682, 8716, 8705, -1, 6954, 8717, 6955, -1, 6955, 8717, 8707, -1, 8700, 8718, 8691, -1, 8691, 8718, 8710, -1, 8710, 8719, 5097, -1, 8693, 8720, 8711, -1, 8703, 8720, 8693, -1, 8705, 8721, 8714, -1, 8716, 8721, 8705, -1, 8688, 8722, 8716, -1, 8697, 8722, 8688, -1, 6953, 8723, 6954, -1, 6954, 8723, 8717, -1, 8700, 8724, 8718, -1, 8711, 8724, 8700, -1, 8718, 8725, 8710, -1, 8710, 8725, 8719, -1, 8703, 8726, 8720, -1, 8714, 8726, 8703, -1, 8716, 8727, 8721, -1, 8722, 8727, 8716, -1, 8707, 8728, 8697, -1, 8697, 8728, 8722, -1, 6952, 8729, 6953, -1, 6953, 8729, 8723, -1, 8711, 8730, 8724, -1, 8720, 8730, 8711, -1, 5097, 8731, 5123, -1, 8719, 8731, 5097, -1, 8724, 8732, 8718, -1, 8718, 8732, 8725, -1, 8721, 8733, 8714, -1, 8714, 8733, 8726, -1, 8722, 8734, 8727, -1, 8728, 8734, 8722, -1, 8717, 8735, 8707, -1, 8707, 8735, 8728, -1, 6951, 8736, 6952, -1, 6952, 8736, 8729, -1, 8726, 8737, 8720, -1, 8720, 8737, 8730, -1, 8731, 8738, 5123, -1, 8725, 8739, 8719, -1, 8719, 8739, 8731, -1, 8724, 8740, 8732, -1, 8730, 8740, 8724, -1, 8727, 8741, 8721, -1, 8721, 8741, 8733, -1, 8735, 8742, 8728, -1, 8728, 8742, 8734, -1, 8723, 8743, 8717, -1, 8717, 8743, 8735, -1, 6951, 8744, 8736, -1, 5146, 8744, 5145, -1, 5145, 8744, 6950, -1, 6950, 8744, 6951, -1, 8726, 8745, 8737, -1, 8733, 8745, 8726, -1, 8731, 8746, 8738, -1, 8739, 8746, 8731, -1, 8725, 8747, 8739, -1, 8732, 8747, 8725, -1, 8737, 8748, 8730, -1, 8730, 8748, 8740, -1, 8727, 8749, 8741, -1, 8734, 8749, 8727, -1, 8743, 8750, 8735, -1, 8735, 8750, 8742, -1, 8723, 8751, 8743, -1, 8729, 8751, 8723, -1, 8733, 8752, 8745, -1, 8741, 8752, 8733, -1, 8739, 8753, 8746, -1, 8747, 8753, 8739, -1, 8740, 8754, 8732, -1, 8732, 8754, 8747, -1, 8745, 8755, 8737, -1, 8737, 8755, 8748, -1, 5123, 8651, 5130, -1, 8738, 8651, 5123, -1, 8742, 8756, 8734, -1, 8734, 8756, 8749, -1, 8743, 8757, 8750, -1, 8751, 8757, 8743, -1, 8729, 8758, 8751, -1, 8736, 8758, 8729, -1, 8749, 8759, 8741, -1, 8741, 8759, 8752, -1, 8747, 8760, 8753, -1, 8754, 8760, 8747, -1, 8740, 8761, 8754, -1, 8748, 8761, 8740, -1, 8745, 8762, 8755, -1, 8752, 8762, 8745, -1, 8738, 8657, 8651, -1, 8746, 8657, 8738, -1, 8742, 8763, 8756, -1, 8750, 8763, 8742, -1, 8751, 8764, 8757, -1, 8758, 8764, 8751, -1, 8744, 8765, 8736, -1, 5158, 8765, 5146, -1, 8736, 8765, 8758, -1, 5146, 8765, 8744, -1, 8756, 8766, 8749, -1, 8749, 8766, 8759, -1, 8754, 8617, 8760, -1, 8761, 8617, 8754, -1, 8755, 8767, 8748, -1, 8748, 8767, 8761, -1, 8759, 8768, 8752, -1, 8752, 8768, 8762, -1, 8753, 8655, 8746, -1, 8746, 8655, 8657, -1, 8757, 8769, 8750, -1, 8750, 8769, 8763, -1, 5158, 8770, 8765, -1, 8758, 8770, 8764, -1, 8765, 8770, 8758, -1, 8756, 8771, 8766, -1, 8763, 8771, 8756, -1, 8761, 8620, 8617, -1, 8767, 8620, 8761, -1, 8755, 8772, 8767, -1, 8762, 8772, 8755, -1, 8766, 8631, 8759, -1, 8759, 8631, 8768, -1, 8753, 8665, 8655, -1, 8760, 8665, 8753, -1, 8757, 8623, 8769, -1, 8764, 8623, 8757, -1, 8763, 8632, 8771, -1, 8769, 8632, 8763, -1, 8772, 8635, 8767, -1, 8767, 8635, 8620, -1, 8768, 8625, 8762, -1, 8762, 8625, 8772, -1, 8766, 8629, 8631, -1, 8771, 8629, 8766, -1, 8617, 8619, 8760, -1, 8760, 8619, 8665, -1, 5158, 8622, 8770, -1, 5183, 8622, 5158, -1, 8764, 8622, 8623, -1, 8770, 8622, 8764, -1, 8769, 8624, 8632, -1, 8623, 8624, 8769, -1, 8772, 8627, 8635, -1, 8625, 8627, 8772, -1, 8631, 8628, 8768, -1, 8768, 8628, 8625, -1, 8632, 8634, 8771, -1, 8771, 8634, 8629, -1, 6436, 8773, 8774, -1, 6470, 6472, 8608, -1, 6436, 6433, 8773, -1, 6472, 8609, 8608, -1, 6432, 8775, 6433, -1, 6433, 8775, 8773, -1, 8609, 6474, 8610, -1, 6472, 6474, 8609, -1, 8776, 6452, 8777, -1, 8778, 6454, 8776, -1, 8776, 6454, 6452, -1, 6474, 6476, 8610, -1, 8777, 6450, 8779, -1, 6432, 6491, 8775, -1, 6452, 6450, 8777, -1, 8780, 6455, 8778, -1, 8778, 6455, 6454, -1, 8779, 6447, 8781, -1, 6450, 6447, 8779, -1, 8782, 6458, 8780, -1, 8616, 6490, 6432, -1, 6432, 6490, 6491, -1, 8780, 6458, 6455, -1, 8610, 6478, 8611, -1, 6476, 6478, 8610, -1, 8615, 6488, 8616, -1, 8783, 6446, 8784, -1, 8616, 6488, 6490, -1, 8781, 6446, 8783, -1, 6447, 6446, 8781, -1, 8611, 6480, 8612, -1, 6478, 6480, 8611, -1, 6462, 6459, 6460, -1, 8614, 6486, 8615, -1, 6460, 6459, 8782, -1, 8615, 6486, 6488, -1, 8782, 6459, 6458, -1, 6446, 6444, 8784, -1, 8612, 6482, 8613, -1, 6480, 6482, 8612, -1, 6462, 8604, 6459, -1, 8613, 6484, 8614, -1, 6444, 8785, 8784, -1, 8614, 6484, 6486, -1, 6482, 6484, 8613, -1, 6462, 6464, 8604, -1, 6444, 6442, 8785, -1, 6464, 8605, 8604, -1, 6442, 8786, 8785, -1, 6464, 6466, 8605, -1, 6442, 6440, 8786, -1, 6466, 8606, 8605, -1, 6440, 8787, 8786, -1, 6466, 6468, 8606, -1, 6440, 6438, 8787, -1, 6468, 8607, 8606, -1, 6438, 8774, 8787, -1, 6468, 6470, 8607, -1, 6438, 6436, 8774, -1, 6470, 8608, 8607, -1, 8775, 6491, 5384, -1, 8775, 5383, 5382, -1, 8775, 5384, 5383, -1, 8773, 5382, 5466, -1, 8773, 8775, 5382, -1, 8774, 5466, 5462, -1, 8774, 8773, 5466, -1, 8787, 5462, 5456, -1, 8787, 8774, 5462, -1, 8786, 5456, 5450, -1, 8786, 8787, 5456, -1, 8785, 5450, 5439, -1, 8785, 8786, 5450, -1, 8784, 5439, 5435, -1, 8784, 8785, 5439, -1, 8783, 8784, 5435, -1, 8781, 5428, 5422, -1, 8781, 5435, 5428, -1, 8781, 8783, 5435, -1, 8779, 8781, 5422, -1, 8777, 5422, 5416, -1, 8777, 8779, 5422, -1, 8776, 5416, 5410, -1, 8776, 8777, 5416, -1, 8778, 5410, 5409, -1, 8778, 8776, 5410, -1, 8780, 5409, 5391, -1, 8780, 8778, 5409, -1, 8782, 5391, 5401, -1, 8782, 8780, 5391, -1, 6460, 8782, 5401, -1, 6460, 5401, 5399, -1, 8788, 8789, 8790, -1, 8791, 8792, 8793, -1, 8791, 8794, 8792, -1, 8795, 8796, 8797, -1, 8795, 8798, 8796, -1, 8799, 8800, 8794, -1, 8799, 8801, 8800, -1, 8802, 8803, 8804, -1, 8802, 8805, 8803, -1, 8806, 8807, 8808, -1, 8806, 8793, 8807, -1, 8809, 8810, 8811, -1, 8809, 8811, 8812, -1, 8813, 8814, 8805, -1, 8813, 8797, 8814, -1, 8815, 8789, 8788, -1, 8815, 8808, 8789, -1, 8816, 8799, 8794, -1, 8816, 8794, 8791, -1, 8817, 8788, 8798, -1, 8817, 8798, 8795, -1, 8818, 5351, 5342, -1, 8818, 8819, 8801, -1, 8818, 5342, 8819, -1, 8818, 8801, 8799, -1, 8820, 8805, 8802, -1, 8820, 8813, 8805, -1, 8821, 8791, 8793, -1, 8821, 8793, 8806, -1, 6489, 5377, 5384, -1, 8822, 8810, 8809, -1, 8822, 8804, 8810, -1, 8823, 8795, 8797, -1, 5342, 5340, 6546, -1, 8823, 8797, 8813, -1, 8824, 8808, 8815, -1, 8824, 8806, 8808, -1, 8825, 5358, 5351, -1, 8825, 8799, 8816, -1, 8825, 5351, 8818, -1, 8825, 8818, 8799, -1, 8826, 8815, 8788, -1, 8826, 8788, 8817, -1, 8827, 8813, 8820, -1, 8827, 8823, 8813, -1, 8828, 8791, 8821, -1, 8828, 8816, 8791, -1, 8829, 8802, 8804, -1, 8829, 8804, 8822, -1, 8830, 8795, 8823, -1, 8830, 8817, 8795, -1, 8831, 8821, 8806, -1, 8831, 8806, 8824, -1, 8832, 8815, 8826, -1, 8832, 8824, 8815, -1, 8833, 8830, 8823, -1, 8833, 8823, 8827, -1, 8834, 8816, 8828, -1, 8834, 5358, 8825, -1, 8834, 8825, 8816, -1, 8835, 8802, 8829, -1, 8835, 8820, 8802, -1, 8836, 8817, 8830, -1, 8837, 8838, 5498, -1, 8836, 8826, 8817, -1, 8839, 8828, 8821, -1, 8837, 5498, 5317, -1, 8839, 8821, 8831, -1, 8840, 8841, 8838, -1, 8842, 8831, 8824, -1, 8842, 8824, 8832, -1, 8843, 8836, 8830, -1, 8840, 8838, 8837, -1, 8844, 8845, 8841, -1, 8843, 8830, 8833, -1, 8846, 8820, 8835, -1, 8844, 8841, 8840, -1, 8846, 8827, 8820, -1, 8847, 5317, 5316, -1, 8848, 8826, 8836, -1, 8847, 8837, 5317, -1, 8848, 8832, 8826, -1, 8849, 5397, 5358, -1, 8849, 5358, 8834, -1, 8849, 8834, 8828, -1, 8850, 8851, 8845, -1, 8849, 8828, 8839, -1, 8852, 8839, 8831, -1, 8850, 8845, 8844, -1, 8852, 8831, 8842, -1, 8853, 8836, 8843, -1, 8854, 8847, 5316, -1, 8853, 8848, 8836, -1, 8855, 8827, 8846, -1, 8856, 8837, 8847, -1, 8855, 8833, 8827, -1, 8856, 8840, 8837, -1, 8857, 8842, 8832, -1, 8858, 8859, 8851, -1, 8857, 8832, 8848, -1, 8858, 8851, 8850, -1, 8860, 5397, 8849, -1, 8860, 8849, 8839, -1, 8860, 8839, 8852, -1, 8861, 8847, 8854, -1, 8862, 8848, 8853, -1, 8861, 8856, 8847, -1, 8862, 8857, 8848, -1, 8863, 8844, 8840, -1, 8863, 8840, 8856, -1, 8864, 8833, 8855, -1, 8864, 8843, 8833, -1, 8865, 8842, 8857, -1, 8866, 5316, 5333, -1, 8865, 8852, 8842, -1, 8867, 8857, 8862, -1, 8866, 8854, 5316, -1, 8867, 8865, 8857, -1, 8868, 8853, 8843, -1, 8869, 8870, 8859, -1, 8869, 8859, 8858, -1, 8868, 8843, 8864, -1, 8871, 5454, 5397, -1, 8871, 5397, 8860, -1, 8871, 8860, 8852, -1, 8871, 8852, 8865, -1, 8872, 5454, 8871, -1, 8873, 8863, 8856, -1, 8872, 8865, 8867, -1, 8872, 8871, 8865, -1, 8873, 8856, 8861, -1, 8874, 8844, 8863, -1, 8875, 8853, 8868, -1, 8874, 8850, 8844, -1, 8875, 8862, 8853, -1, 8876, 8867, 8862, -1, 8876, 8862, 8875, -1, 8877, 5395, 5454, -1, 8878, 8861, 8854, -1, 8877, 5454, 8872, -1, 8878, 8854, 8866, -1, 8877, 8872, 8867, -1, 8877, 8867, 8876, -1, 8879, 8880, 8870, -1, 8879, 8870, 8869, -1, 8881, 8866, 5333, -1, 8882, 8883, 6463, -1, 8882, 8876, 8883, -1, 8884, 8875, 8868, -1, 8884, 8876, 8875, -1, 8885, 8874, 8863, -1, 8885, 8863, 8873, -1, 8884, 8883, 8876, -1, 8886, 8858, 8850, -1, 8886, 8850, 8874, -1, 8887, 8883, 8884, -1, 8888, 6467, 6465, -1, 8888, 6465, 6463, -1, 8888, 6463, 8883, -1, 8888, 8883, 8887, -1, 8889, 5395, 8877, -1, 8889, 8877, 8876, -1, 8890, 8861, 8878, -1, 8889, 8876, 8882, -1, 8891, 8889, 8882, -1, 8891, 5399, 5395, -1, 8890, 8873, 8861, -1, 8891, 5395, 8889, -1, 8892, 5399, 8891, -1, 8892, 8882, 6463, -1, 8892, 6463, 6461, -1, 8892, 6461, 5399, -1, 8892, 8891, 8882, -1, 8893, 6519, 8880, -1, 8893, 8880, 8879, -1, 8894, 8866, 8881, -1, 8895, 8868, 8864, -1, 8895, 8884, 8868, -1, 8895, 8887, 8884, -1, 8894, 8878, 8866, -1, 8896, 8886, 8874, -1, 8897, 8887, 8895, -1, 8896, 8874, 8885, -1, 8898, 8888, 8887, -1, 8898, 8887, 8897, -1, 8898, 6467, 8888, -1, 8898, 6469, 6467, -1, 8899, 8897, 8895, -1, 8900, 5333, 5362, -1, 8899, 8864, 8855, -1, 8900, 8881, 5333, -1, 8899, 8895, 8864, -1, 8901, 8858, 8886, -1, 8902, 8897, 8899, -1, 8901, 8869, 8858, -1, 8903, 8898, 8897, -1, 8903, 6469, 8898, -1, 8903, 8897, 8902, -1, 8903, 6471, 6469, -1, 8904, 8902, 8899, -1, 8905, 8873, 8890, -1, 8904, 8855, 8846, -1, 8904, 8899, 8855, -1, 8905, 8885, 8873, -1, 8906, 6505, 6519, -1, 8907, 8902, 8904, -1, 8908, 8902, 8907, -1, 8906, 6519, 8893, -1, 8908, 8903, 8902, -1, 8908, 6471, 8903, -1, 8908, 6473, 6471, -1, 8909, 8846, 8835, -1, 8909, 8907, 8904, -1, 8910, 8890, 8878, -1, 8909, 8904, 8846, -1, 8910, 8878, 8894, -1, 8911, 8907, 8909, -1, 8912, 8886, 8896, -1, 8912, 8901, 8886, -1, 8913, 8908, 8907, -1, 8913, 6475, 6473, -1, 8913, 6473, 8908, -1, 8913, 8907, 8911, -1, 8914, 8909, 8835, -1, 8915, 8881, 8900, -1, 8915, 8894, 8881, -1, 8914, 8911, 8909, -1, 8914, 8835, 8829, -1, 8916, 8869, 8901, -1, 8917, 6477, 6475, -1, 8917, 6475, 8913, -1, 8916, 8879, 8869, -1, 8917, 8913, 8911, -1, 8917, 8911, 8914, -1, 8918, 8896, 8885, -1, 8919, 8829, 8822, -1, 8919, 8914, 8829, -1, 8918, 8885, 8905, -1, 8920, 8914, 8919, -1, 8921, 6506, 6505, -1, 8921, 6505, 8906, -1, 8922, 8917, 8914, -1, 8922, 8914, 8920, -1, 8922, 8920, 8923, -1, 8924, 6477, 8917, -1, 8924, 6479, 6477, -1, 8925, 8900, 5362, -1, 8924, 8917, 8922, -1, 8924, 8922, 8923, -1, 8926, 8919, 8822, -1, 8926, 8920, 8919, -1, 8927, 8905, 8890, -1, 8926, 8822, 8809, -1, 8927, 8890, 8910, -1, 8928, 6481, 6479, -1, 8928, 8920, 8926, -1, 8928, 8923, 8920, -1, 8928, 6479, 8924, -1, 8928, 8924, 8923, -1, 8929, 8901, 8912, -1, 8929, 8916, 8901, -1, 8930, 8809, 8812, -1, 8930, 8926, 8809, -1, 8930, 8928, 8926, -1, 8931, 8910, 8894, -1, 8931, 8894, 8915, -1, 8932, 8928, 8930, -1, 8933, 8893, 8879, -1, 8934, 6483, 6481, -1, 8933, 8879, 8916, -1, 8934, 6481, 8928, -1, 8934, 8928, 8932, -1, 8935, 8936, 8937, -1, 8935, 8930, 8812, -1, 8935, 6487, 6485, -1, 8938, 5362, 5377, -1, 8935, 8937, 6487, -1, 8935, 8812, 8936, -1, 8935, 8932, 8930, -1, 8938, 8925, 5362, -1, 8939, 6485, 6483, -1, 8939, 6483, 8934, -1, 8939, 8934, 8932, -1, 8940, 8912, 8896, -1, 8939, 8935, 6485, -1, 8939, 8932, 8935, -1, 8940, 8896, 8918, -1, 8941, 6541, 6506, -1, 8941, 6506, 8921, -1, 8942, 8915, 8900, -1, 8942, 8900, 8925, -1, 8943, 8905, 8927, -1, 8943, 8918, 8905, -1, 8944, 8933, 8916, -1, 8944, 8916, 8929, -1, 8945, 8927, 8910, -1, 8945, 8910, 8931, -1, 8946, 8893, 8933, -1, 8946, 8906, 8893, -1, 8947, 8925, 8938, -1, 8947, 8942, 8925, -1, 8948, 8929, 8912, -1, 8948, 8912, 8940, -1, 8949, 6543, 6541, -1, 8949, 6541, 8941, -1, 8950, 8915, 8942, -1, 8950, 8931, 8915, -1, 8951, 8940, 8918, -1, 8951, 8918, 8943, -1, 8952, 8933, 8944, -1, 8952, 8946, 8933, -1, 8953, 8927, 8945, -1, 8953, 8943, 8927, -1, 8954, 8906, 8946, -1, 8954, 8921, 8906, -1, 8955, 8942, 8947, -1, 8955, 8950, 8942, -1, 8956, 8944, 8929, -1, 8956, 8929, 8948, -1, 8957, 8938, 5377, -1, 8957, 5377, 6489, -1, 8800, 6514, 6543, -1, 8800, 6543, 8949, -1, 8958, 8931, 8950, -1, 8958, 8945, 8931, -1, 8959, 8948, 8940, -1, 8959, 8940, 8951, -1, 8960, 8946, 8952, -1, 8960, 8954, 8946, -1, 8961, 8951, 8943, -1, 8961, 8943, 8953, -1, 8962, 8941, 8921, -1, 8962, 8921, 8954, -1, 8811, 8958, 8950, -1, 8811, 8950, 8955, -1, 8790, 8944, 8956, -1, 8790, 8952, 8944, -1, 8937, 8957, 6489, -1, 8937, 6489, 6487, -1, 8937, 8947, 8938, -1, 8937, 8938, 8957, -1, 8801, 6494, 6514, -1, 8801, 6514, 8800, -1, 8963, 8945, 8958, -1, 8963, 8953, 8945, -1, 8796, 8948, 8959, -1, 8796, 8956, 8948, -1, 8807, 8954, 8960, -1, 8807, 8962, 8954, -1, 8814, 8959, 8951, -1, 8814, 8951, 8961, -1, 8792, 8941, 8962, -1, 8792, 8949, 8941, -1, 8810, 8958, 8811, -1, 8810, 8963, 8958, -1, 8789, 8960, 8952, -1, 8789, 8952, 8790, -1, 8936, 8955, 8947, -1, 8936, 8947, 8937, -1, 8819, 6546, 6494, -1, 8819, 5342, 6546, -1, 8819, 6494, 8801, -1, 8803, 8961, 8953, -1, 8803, 8953, 8963, -1, 8798, 8790, 8956, -1, 8798, 8956, 8796, -1, 8793, 8962, 8807, -1, 8793, 8792, 8962, -1, 8797, 8796, 8959, -1, 8797, 8959, 8814, -1, 8794, 8949, 8792, -1, 8794, 8800, 8949, -1, 8804, 8963, 8810, -1, 8804, 8803, 8963, -1, 8808, 8960, 8789, -1, 8808, 8807, 8960, -1, 8812, 8811, 8955, -1, 8812, 8955, 8936, -1, 8805, 8961, 8803, -1, 8805, 8814, 8961, -1, 8788, 8790, 8798, -1, 7193, 6496, 5000, -1, 5018, 7193, 5000, -1, 5035, 7199, 5018, -1, 7472, 6517, 7091, -1, 7472, 6516, 6517, -1, 7356, 6519, 6538, -1, 8880, 6519, 7356, -1, 7185, 7250, 5035, -1, 7473, 7472, 7091, -1, 7473, 7091, 7085, -1, 5058, 7185, 5035, -1, 7475, 7473, 7085, -1, 8870, 8880, 7343, -1, 7467, 7475, 7096, -1, 7467, 7096, 7104, -1, 5067, 7232, 7212, -1, 5067, 7212, 5058, -1, 7449, 7467, 7104, -1, 7449, 7104, 7115, -1, 8859, 8870, 7336, -1, 8859, 7336, 7331, -1, 7428, 7449, 7115, -1, 7428, 7115, 7142, -1, 7301, 8859, 7323, -1, 5075, 7188, 5067, -1, 5075, 7189, 7188, -1, 7407, 7428, 7142, -1, 7407, 7142, 7068, -1, 8851, 8859, 7301, -1, 7477, 7407, 7068, -1, 7477, 7084, 7100, -1, 7477, 7068, 7084, -1, 7347, 8851, 7358, -1, 7334, 8851, 7347, -1, 5082, 7208, 5075, -1, 7465, 7477, 7100, -1, 7465, 7100, 7109, -1, 8845, 8851, 7334, -1, 7451, 7129, 7144, -1, 7451, 7109, 7129, -1, 7309, 8845, 7310, -1, 7436, 7144, 7137, -1, 8841, 7309, 7377, -1, 8841, 8845, 7309, -1, 5086, 7235, 5087, -1, 6757, 7235, 5086, -1, 8838, 8841, 7319, -1, 7438, 7431, 7136, -1, 8964, 7259, 5086, -1, 6645, 6789, 7264, -1, 6645, 7438, 6789, -1, 5498, 8838, 7313, -1, 7537, 5498, 6614, -1, 8965, 7298, 8964, -1, 7487, 7264, 7263, -1, 5499, 5498, 7537, -1, 8966, 7297, 8965, -1, 5495, 5499, 7535, -1, 8967, 7295, 8966, -1, 5488, 5495, 7531, -1, 7291, 7290, 8967, -1, 8968, 7287, 7291, -1, 8968, 7291, 8967, -1, 5480, 5488, 7527, -1, 7498, 7490, 7267, -1, 8969, 7279, 7284, -1, 8969, 7280, 7279, -1, 8969, 7284, 8968, -1, 7499, 7266, 7270, -1, 7499, 7498, 7266, -1, 5471, 5480, 7526, -1, 7519, 5471, 7523, -1, 7503, 7499, 7270, -1, 7503, 7270, 7274, -1, 7516, 5471, 7519, -1, 7507, 7274, 7277, -1, 7507, 7503, 7274, -1, 7511, 7277, 7280, -1, 7511, 7280, 8969, -1, 7511, 7507, 7277, -1, 5451, 8969, 8970, -1, 5451, 5471, 7516, -1, 5451, 7511, 8969, -1, 5451, 7512, 7511, -1, 5451, 7516, 7512, -1, 5432, 8970, 6501, -1, 5432, 5451, 8970, -1, 5413, 5432, 6501, -1, 7313, 6614, 5498, -1, 7319, 7313, 8838, -1, 7377, 7319, 8841, -1, 7334, 7310, 8845, -1, 7301, 7358, 8851, -1, 7331, 7323, 8859, -1, 7343, 7336, 8870, -1, 7356, 7343, 8880, -1, 7487, 6645, 7264, -1, 7493, 7487, 7263, -1, 7485, 7493, 7272, -1, 7486, 7485, 7262, -1, 7490, 7486, 7261, -1, 7526, 7523, 5471, -1, 7527, 7526, 5480, -1, 7531, 7527, 5488, -1, 7533, 7531, 5495, -1, 7535, 7533, 5495, -1, 7537, 7535, 5499, -1, 7451, 7465, 7109, -1, 7436, 7451, 7144, -1, 7431, 7436, 7137, -1, 7136, 6789, 7438, -1, 7137, 7136, 7431, -1, 7085, 7096, 7475, -1, 7259, 6757, 5086, -1, 7298, 7259, 8964, -1, 7297, 7298, 8965, -1, 7295, 7297, 8966, -1, 7290, 7295, 8967, -1, 7284, 7287, 8968, -1, 7267, 7266, 7498, -1, 7261, 7267, 7490, -1, 7262, 7261, 7486, -1, 7272, 7262, 7485, -1, 7263, 7272, 7493, -1, 7199, 7193, 5018, -1, 7250, 7199, 5035, -1, 7186, 7185, 5058, -1, 7212, 7186, 5058, -1, 7188, 7232, 5067, -1, 7208, 7189, 5075, -1, 7216, 7208, 5082, -1, 7234, 7216, 5087, -1, 5087, 7216, 5082, -1, 7235, 7234, 5087, -1, 6414, 8971, 4713, -1, 4713, 8971, 8972, -1, 8972, 8973, 8974, -1, 8971, 8973, 8972, -1, 8974, 8975, 8976, -1, 8973, 8975, 8974, -1, 8976, 8977, 8978, -1, 8975, 8977, 8976, -1, 8978, 8979, 8980, -1, 8977, 8979, 8978, -1, 8980, 8981, 8982, -1, 8979, 8981, 8980, -1, 8982, 8983, 8984, -1, 8981, 8983, 8982, -1, 8984, 8985, 8986, -1, 8983, 8985, 8984, -1, 8986, 8987, 8988, -1, 8985, 8987, 8986, -1, 8988, 8989, 8990, -1, 8987, 8989, 8988, -1, 8990, 8991, 8992, -1, 8989, 8991, 8990, -1, 8992, 8993, 8994, -1, 8991, 8993, 8992, -1, 8994, 8995, 8996, -1, 8993, 8995, 8994, -1, 8996, 6400, 4728, -1, 8995, 6400, 8996, -1, 8997, 8998, 8999, -1, 8999, 8998, 9000, -1, 9001, 9002, 9003, -1, 9003, 9002, 9004, -1, 4773, 9005, 9006, -1, 6972, 4844, 4845, -1, 9006, 9005, 9007, -1, 9007, 9005, 9008, -1, 9009, 9010, 9011, -1, 9012, 9010, 9009, -1, 9000, 9013, 9014, -1, 9014, 9013, 9012, -1, 8997, 9015, 8998, -1, 9008, 9015, 8997, -1, 9016, 9017, 9001, -1, 9001, 9017, 9002, -1, 9012, 9018, 9010, -1, 9013, 9018, 9012, -1, 9000, 9019, 9013, -1, 8998, 9019, 9000, -1, 4815, 9020, 4773, -1, 4773, 9020, 9005, -1, 9005, 9020, 9008, -1, 9008, 9020, 9015, -1, 9011, 9021, 9016, -1, 9016, 9021, 9017, -1, 9019, 9022, 9013, -1, 9013, 9022, 9018, -1, 9015, 9023, 8998, -1, 8998, 9023, 9019, -1, 9020, 9023, 9015, -1, 9011, 9024, 9021, -1, 9010, 9024, 9011, -1, 9023, 9025, 9019, -1, 9019, 9025, 9022, -1, 4815, 9026, 9020, -1, 9020, 9026, 9023, -1, 9010, 9027, 9024, -1, 9018, 9027, 9010, -1, 4815, 9028, 9026, -1, 9026, 9028, 9023, -1, 4711, 9028, 4815, -1, 9023, 9028, 9025, -1, 9018, 9029, 9027, -1, 9022, 9029, 9018, -1, 9025, 9030, 9022, -1, 9022, 9030, 9029, -1, 8972, 9031, 4713, -1, 4711, 9031, 9028, -1, 9028, 9031, 9025, -1, 4713, 9031, 4711, -1, 9025, 9031, 9030, -1, 9032, 9033, 4719, -1, 9034, 9035, 9033, -1, 9033, 9035, 4719, -1, 4719, 9035, 4728, -1, 9036, 9037, 9038, -1, 4728, 9039, 8996, -1, 9035, 9039, 4728, -1, 9034, 9039, 9035, -1, 9037, 9040, 9034, -1, 9040, 9041, 9034, -1, 8994, 9041, 8992, -1, 9033, 9042, 9034, -1, 9032, 9042, 9033, -1, 9034, 9042, 9037, -1, 9037, 9042, 9038, -1, 9038, 9042, 9032, -1, 9041, 9043, 9034, -1, 8996, 9043, 8994, -1, 8994, 9043, 9041, -1, 9039, 9043, 8996, -1, 9034, 9043, 9039, -1, 9037, 9044, 9040, -1, 6972, 9045, 4844, -1, 9046, 9044, 9036, -1, 6972, 9047, 9045, -1, 9036, 9044, 9037, -1, 6969, 9047, 6972, -1, 9044, 9048, 9040, -1, 8992, 9049, 8990, -1, 9040, 9049, 9041, -1, 6969, 9050, 9047, -1, 9041, 9049, 8992, -1, 9048, 9049, 9040, -1, 9004, 9051, 9046, -1, 6967, 9050, 6969, -1, 9046, 9051, 9044, -1, 9044, 9051, 9048, -1, 9045, 9052, 4844, -1, 9051, 9053, 9048, -1, 4844, 9052, 4867, -1, 8990, 9054, 8988, -1, 9048, 9054, 9049, -1, 9053, 9054, 9048, -1, 9049, 9054, 8990, -1, 9051, 9055, 9053, -1, 6965, 9056, 6967, -1, 9004, 9055, 9051, -1, 6967, 9056, 9050, -1, 9002, 9055, 9004, -1, 4867, 9057, 4688, -1, 9055, 9058, 9053, -1, 9052, 9057, 4867, -1, 9047, 9059, 9045, -1, 8988, 9060, 8986, -1, 9054, 9060, 8988, -1, 9058, 9060, 9053, -1, 9045, 9059, 9052, -1, 9053, 9060, 9054, -1, 9055, 9061, 9058, -1, 9017, 9061, 9002, -1, 9002, 9061, 9055, -1, 6963, 9062, 6965, -1, 8986, 9063, 8984, -1, 6965, 9062, 9056, -1, 9060, 9063, 8986, -1, 9058, 9063, 9060, -1, 9052, 9064, 9057, -1, 9017, 9065, 9061, -1, 9021, 9065, 9017, -1, 9059, 9064, 9052, -1, 9047, 9066, 9059, -1, 9065, 9067, 9061, -1, 9050, 9066, 9047, -1, 9061, 9068, 9058, -1, 9058, 9068, 9063, -1, 9067, 9069, 9061, -1, 6961, 9070, 6963, -1, 9061, 9069, 9068, -1, 8984, 9071, 8982, -1, 6963, 9070, 9062, -1, 9063, 9071, 8984, -1, 9068, 9071, 9063, -1, 9069, 9071, 9068, -1, 9057, 9072, 4688, -1, 9024, 9073, 9021, -1, 9021, 9073, 9065, -1, 9065, 9073, 9067, -1, 9066, 9074, 9059, -1, 9059, 9074, 9064, -1, 9071, 9075, 8982, -1, 9067, 9075, 9069, -1, 9069, 9075, 9071, -1, 9024, 9076, 9073, -1, 9050, 9077, 9066, -1, 9027, 9076, 9024, -1, 9056, 9077, 9050, -1, 9073, 9078, 9067, -1, 9076, 9078, 9073, -1, 9067, 9078, 9075, -1, 6917, 9079, 6961, -1, 9076, 9080, 9078, -1, 6961, 9079, 9070, -1, 9078, 9080, 9075, -1, 9064, 9081, 9057, -1, 9080, 9082, 9075, -1, 9057, 9081, 9072, -1, 9075, 9083, 8982, -1, 8980, 9083, 8978, -1, 8982, 9083, 8980, -1, 9082, 9083, 9075, -1, 9077, 9084, 9066, -1, 9066, 9084, 9074, -1, 9076, 9085, 9080, -1, 9080, 9085, 9082, -1, 9027, 9085, 9076, -1, 9062, 9086, 9056, -1, 9056, 9086, 9077, -1, 8978, 9087, 8976, -1, 9083, 9087, 8978, -1, 9082, 9087, 9083, -1, 6918, 9088, 6917, -1, 9029, 9089, 9027, -1, 9027, 9089, 9085, -1, 9030, 9089, 9029, -1, 6917, 9088, 9079, -1, 8974, 9090, 8972, -1, 4688, 9091, 4686, -1, 8972, 9090, 9031, -1, 9072, 9091, 4688, -1, 9031, 9090, 9030, -1, 9030, 9090, 9089, -1, 9064, 9092, 9081, -1, 9089, 9090, 9085, -1, 9082, 9093, 9087, -1, 9085, 9093, 9082, -1, 8974, 9094, 9090, -1, 9074, 9092, 9064, -1, 9090, 9094, 9085, -1, 9085, 9094, 9093, -1, 8976, 9095, 8974, -1, 9077, 9096, 9084, -1, 8974, 9095, 9094, -1, 9086, 9096, 9077, -1, 9087, 9095, 8976, -1, 9093, 9095, 9087, -1, 9094, 9095, 9093, -1, 9070, 9097, 9062, -1, 9062, 9097, 9086, -1, 6921, 9098, 6918, -1, 6918, 9098, 9088, -1, 9081, 9099, 9072, -1, 9072, 9099, 9091, -1, 9091, 9100, 4686, -1, 9074, 9101, 9092, -1, 9084, 9101, 9074, -1, 9086, 9102, 9096, -1, 9097, 9102, 9086, -1, 9070, 9103, 9097, -1, 9079, 9103, 9070, -1, 6923, 9104, 6921, -1, 6921, 9104, 9098, -1, 9081, 9105, 9099, -1, 9092, 9105, 9081, -1, 9099, 9106, 9091, -1, 9091, 9106, 9100, -1, 9084, 9107, 9101, -1, 9096, 9107, 9084, -1, 9097, 9108, 9102, -1, 9103, 9108, 9097, -1, 9088, 9109, 9079, -1, 9079, 9109, 9103, -1, 6925, 9110, 6923, -1, 6923, 9110, 9104, -1, 9092, 9111, 9105, -1, 9101, 9111, 9092, -1, 4686, 9112, 4710, -1, 9100, 9112, 4686, -1, 9105, 9113, 9099, -1, 9099, 9113, 9106, -1, 9102, 9114, 9096, -1, 9096, 9114, 9107, -1, 9103, 9115, 9108, -1, 9109, 9115, 9103, -1, 9098, 9116, 9088, -1, 9088, 9116, 9109, -1, 6928, 9117, 6925, -1, 6925, 9117, 9110, -1, 9107, 9118, 9101, -1, 9101, 9118, 9111, -1, 9112, 9119, 4710, -1, 9106, 9120, 9100, -1, 9100, 9120, 9112, -1, 9105, 9121, 9113, -1, 9111, 9121, 9105, -1, 9108, 9122, 9102, -1, 9102, 9122, 9114, -1, 9116, 9123, 9109, -1, 9109, 9123, 9115, -1, 9104, 9124, 9098, -1, 9098, 9124, 9116, -1, 6928, 9125, 9117, -1, 4735, 9125, 4734, -1, 4734, 9125, 6930, -1, 6930, 9125, 6928, -1, 9107, 9126, 9118, -1, 9114, 9126, 9107, -1, 9112, 9127, 9119, -1, 9120, 9127, 9112, -1, 9106, 9128, 9120, -1, 9113, 9128, 9106, -1, 9118, 9129, 9111, -1, 9111, 9129, 9121, -1, 9108, 9130, 9122, -1, 9115, 9130, 9108, -1, 9124, 9131, 9116, -1, 9116, 9131, 9123, -1, 9104, 9132, 9124, -1, 9110, 9132, 9104, -1, 9114, 9133, 9126, -1, 9122, 9133, 9114, -1, 9120, 9134, 9127, -1, 9128, 9134, 9120, -1, 9121, 9135, 9113, -1, 9113, 9135, 9128, -1, 9126, 9136, 9118, -1, 9118, 9136, 9129, -1, 4710, 9032, 4719, -1, 9119, 9032, 4710, -1, 9123, 9137, 9115, -1, 9115, 9137, 9130, -1, 9124, 9138, 9131, -1, 9132, 9138, 9124, -1, 9110, 9139, 9132, -1, 9117, 9139, 9110, -1, 9130, 9140, 9122, -1, 9122, 9140, 9133, -1, 9128, 9141, 9134, -1, 9135, 9141, 9128, -1, 9121, 9142, 9135, -1, 9129, 9142, 9121, -1, 9126, 9143, 9136, -1, 9133, 9143, 9126, -1, 9119, 9038, 9032, -1, 9127, 9038, 9119, -1, 9123, 9144, 9137, -1, 9131, 9144, 9123, -1, 9132, 9145, 9138, -1, 9139, 9145, 9132, -1, 9125, 9146, 9117, -1, 4747, 9146, 4735, -1, 9117, 9146, 9139, -1, 4735, 9146, 9125, -1, 9137, 9147, 9130, -1, 9130, 9147, 9140, -1, 9135, 9003, 9141, -1, 9142, 9003, 9135, -1, 9136, 9148, 9129, -1, 9129, 9148, 9142, -1, 9140, 9149, 9133, -1, 9133, 9149, 9143, -1, 9134, 9036, 9127, -1, 9127, 9036, 9038, -1, 9138, 9150, 9131, -1, 9131, 9150, 9144, -1, 4747, 9151, 9146, -1, 9139, 9151, 9145, -1, 9146, 9151, 9139, -1, 9137, 8999, 9147, -1, 9144, 8999, 9137, -1, 9148, 9001, 9142, -1, 9142, 9001, 9003, -1, 9136, 9152, 9148, -1, 9143, 9152, 9136, -1, 9147, 9014, 9140, -1, 9140, 9014, 9149, -1, 9134, 9046, 9036, -1, 9141, 9046, 9134, -1, 9138, 9007, 9150, -1, 9145, 9007, 9138, -1, 9144, 8997, 8999, -1, 9150, 8997, 9144, -1, 9152, 9016, 9148, -1, 9148, 9016, 9001, -1, 9149, 9009, 9143, -1, 9143, 9009, 9152, -1, 9147, 9000, 9014, -1, 8999, 9000, 9147, -1, 9141, 9004, 9046, -1, 9003, 9004, 9141, -1, 4747, 9006, 9151, -1, 4773, 9006, 4747, -1, 9145, 9006, 9007, -1, 9151, 9006, 9145, -1, 9150, 9008, 8997, -1, 9007, 9008, 9150, -1, 9152, 9011, 9016, -1, 9009, 9011, 9152, -1, 9014, 9012, 9149, -1, 9149, 9012, 9009, -1, 9153, 9154, 6405, -1, 8973, 6417, 6418, -1, 8973, 8971, 6417, -1, 9154, 6406, 6405, -1, 6427, 8989, 6426, -1, 6406, 9155, 6407, -1, 9154, 9155, 6406, -1, 6414, 6416, 8971, -1, 8971, 6416, 6417, -1, 6428, 8991, 6427, -1, 6427, 8991, 8989, -1, 6426, 8987, 6425, -1, 8989, 8987, 6426, -1, 9155, 9156, 6407, -1, 6429, 8993, 6428, -1, 6428, 8993, 8991, -1, 6414, 6415, 6416, -1, 6425, 8985, 6424, -1, 8987, 8985, 6425, -1, 6430, 8995, 6429, -1, 6429, 8995, 8993, -1, 6407, 9157, 6408, -1, 9156, 9157, 6407, -1, 6424, 8983, 6423, -1, 6423, 8983, 6422, -1, 6413, 9158, 6414, -1, 8985, 8983, 6424, -1, 6414, 9158, 6415, -1, 6412, 9159, 6413, -1, 9160, 6400, 6431, -1, 6431, 6400, 6430, -1, 6430, 6400, 8995, -1, 6413, 9159, 9158, -1, 6408, 9161, 6409, -1, 9157, 9161, 6408, -1, 8983, 8981, 6422, -1, 6411, 9162, 6412, -1, 9160, 6401, 6400, -1, 6412, 9162, 9159, -1, 9160, 9163, 6401, -1, 6409, 9164, 6410, -1, 9161, 9164, 6409, -1, 8981, 6421, 6422, -1, 6410, 9165, 6411, -1, 9164, 9165, 6410, -1, 6411, 9165, 9162, -1, 8981, 8979, 6421, -1, 9163, 6402, 6401, -1, 9163, 9166, 6402, -1, 8979, 6420, 6421, -1, 8979, 8977, 6420, -1, 9166, 6403, 6402, -1, 9166, 9167, 6403, -1, 8977, 6419, 6420, -1, 8977, 8975, 6419, -1, 9167, 6404, 6403, -1, 9167, 9153, 6404, -1, 8975, 6418, 6419, -1, 8975, 8973, 6418, -1, 9153, 6405, 6404, -1, 6431, 4986, 9168, -1, 9160, 6431, 9168, -1, 9163, 9168, 9169, -1, 9163, 9160, 9168, -1, 9166, 9169, 9170, -1, 9166, 9163, 9169, -1, 9167, 9170, 9171, -1, 9167, 9166, 9170, -1, 9153, 9171, 9172, -1, 9153, 9167, 9171, -1, 9154, 9172, 9173, -1, 9154, 9153, 9172, -1, 9155, 9173, 9174, -1, 9155, 9154, 9173, -1, 9156, 9174, 9175, -1, 9156, 9155, 9174, -1, 9157, 9175, 9176, -1, 9157, 9156, 9175, -1, 9161, 9176, 9177, -1, 9161, 9157, 9176, -1, 9164, 9177, 9178, -1, 9164, 9161, 9177, -1, 9165, 9178, 9179, -1, 9165, 9164, 9178, -1, 9162, 9179, 9180, -1, 9162, 9165, 9179, -1, 9159, 9180, 9181, -1, 9159, 9162, 9180, -1, 9158, 9181, 9182, -1, 9158, 9159, 9181, -1, 6415, 9158, 9182, -1, 6415, 9182, 4924, -1, 9183, 9184, 9185, -1, 9183, 9186, 9184, -1, 9187, 9188, 9189, -1, 9187, 9190, 9188, -1, 9191, 9192, 9186, -1, 9191, 9193, 9192, -1, 9194, 9195, 9196, -1, 9194, 9197, 9195, -1, 9198, 9185, 9199, -1, 9198, 9199, 9200, -1, 9201, 9202, 9203, -1, 9201, 9204, 9202, -1, 9205, 9206, 9197, -1, 9205, 9189, 9206, -1, 9207, 9200, 9208, -1, 9207, 9208, 9209, -1, 9210, 9186, 9183, -1, 9210, 9191, 9186, -1, 9211, 9190, 9187, -1, 9211, 9209, 9190, -1, 9212, 4941, 4931, -1, 9212, 9213, 9193, -1, 9212, 9193, 9191, -1, 9212, 4931, 9213, -1, 9214, 9205, 9197, -1, 9214, 9197, 9194, -1, 9215, 9185, 9198, -1, 9215, 9183, 9185, -1, 9216, 9204, 9201, -1, 9216, 9196, 9204, -1, 9217, 9189, 9205, -1, 9217, 9187, 9189, -1, 9218, 9198, 9200, -1, 9218, 9200, 9207, -1, 9219, 4948, 4941, -1, 9219, 4941, 9212, -1, 9219, 9191, 9210, -1, 9219, 9212, 9191, -1, 9220, 9207, 9209, -1, 9220, 9209, 9211, -1, 9221, 9205, 9214, -1, 9221, 9217, 9205, -1, 9222, 9210, 9183, -1, 9222, 9183, 9215, -1, 9223, 9196, 9216, -1, 9223, 9194, 9196, -1, 9224, 9211, 9187, -1, 9224, 9187, 9217, -1, 9225, 9215, 9198, -1, 9225, 9198, 9218, -1, 9226, 9218, 9207, -1, 9226, 9207, 9220, -1, 9227, 9224, 9217, -1, 9227, 9217, 9221, -1, 9228, 4948, 9219, -1, 9228, 9219, 9210, -1, 9228, 9210, 9222, -1, 9229, 9194, 9223, -1, 9229, 9214, 9194, -1, 9230, 9211, 9224, -1, 9230, 9220, 9211, -1, 9231, 8964, 5086, -1, 9232, 9222, 9215, -1, 9232, 9215, 9225, -1, 9231, 5086, 4904, -1, 9233, 9225, 9218, -1, 9233, 9218, 9226, -1, 9234, 8965, 8964, -1, 9235, 9224, 9227, -1, 9234, 8964, 9231, -1, 9235, 9230, 9224, -1, 9236, 9214, 9229, -1, 9237, 8966, 8965, -1, 9236, 9221, 9214, -1, 9237, 8965, 9234, -1, 9238, 9226, 9220, -1, 9239, 4904, 4903, -1, 9238, 9220, 9230, -1, 9240, 4981, 4948, -1, 9239, 9231, 4904, -1, 9240, 9228, 9222, -1, 9240, 9222, 9232, -1, 9240, 4948, 9228, -1, 9241, 9225, 9233, -1, 9242, 8967, 8966, -1, 9241, 9232, 9225, -1, 9242, 8966, 9237, -1, 9243, 9230, 9235, -1, 9243, 9238, 9230, -1, 9244, 9239, 4903, -1, 9245, 9221, 9236, -1, 9246, 9231, 9239, -1, 9245, 9227, 9221, -1, 9247, 9233, 9226, -1, 9246, 9234, 9231, -1, 9247, 9226, 9238, -1, 9248, 8968, 8967, -1, 9249, 4981, 9240, -1, 9249, 9240, 9232, -1, 9249, 9232, 9241, -1, 9248, 8967, 9242, -1, 9250, 9238, 9243, -1, 9250, 9247, 9238, -1, 9251, 9227, 9245, -1, 9252, 9239, 9244, -1, 9251, 9235, 9227, -1, 9252, 9246, 9239, -1, 9253, 9237, 9234, -1, 9253, 9234, 9246, -1, 9254, 9233, 9247, -1, 9254, 9241, 9233, -1, 9255, 9247, 9250, -1, 9256, 4903, 4920, -1, 9255, 9254, 9247, -1, 9256, 9244, 4903, -1, 9257, 9243, 9235, -1, 9257, 9235, 9251, -1, 9258, 8969, 8968, -1, 9259, 5040, 4981, -1, 9258, 8968, 9248, -1, 9259, 4981, 9249, -1, 9259, 9249, 9241, -1, 9259, 9241, 9254, -1, 9260, 5040, 9259, -1, 9260, 9254, 9255, -1, 9260, 9259, 9254, -1, 9261, 9243, 9257, -1, 9262, 9253, 9246, -1, 9261, 9250, 9243, -1, 9262, 9246, 9252, -1, 9263, 9237, 9253, -1, 9263, 9242, 9237, -1, 9264, 9255, 9250, -1, 9264, 9250, 9261, -1, 9265, 4984, 5040, -1, 9265, 5040, 9260, -1, 9265, 9260, 9255, -1, 9265, 9255, 9264, -1, 9266, 9252, 9244, -1, 9266, 9244, 9256, -1, 9267, 8970, 8969, -1, 9268, 9269, 9169, -1, 9267, 8969, 9258, -1, 9268, 9264, 9269, -1, 9270, 9261, 9257, -1, 9271, 9256, 4920, -1, 9270, 9264, 9261, -1, 9270, 9269, 9264, -1, 9272, 9263, 9253, -1, 9272, 9253, 9262, -1, 9273, 9269, 9270, -1, 9274, 9171, 9170, -1, 9274, 9170, 9169, -1, 9275, 9248, 9242, -1, 9274, 9169, 9269, -1, 9274, 9269, 9273, -1, 9275, 9242, 9263, -1, 9276, 4984, 9265, -1, 9276, 9265, 9264, -1, 9276, 9264, 9268, -1, 9277, 9276, 9268, -1, 9277, 4986, 4984, -1, 9277, 4984, 9276, -1, 9278, 9252, 9266, -1, 9279, 9277, 9268, -1, 9279, 4986, 9277, -1, 9279, 9268, 9169, -1, 9279, 9169, 9168, -1, 9278, 9262, 9252, -1, 9279, 9168, 4986, -1, 9280, 9257, 9251, -1, 9280, 9270, 9257, -1, 9280, 9273, 9270, -1, 9281, 6501, 8970, -1, 9281, 8970, 9267, -1, 9282, 9256, 9271, -1, 9283, 9273, 9280, -1, 9282, 9266, 9256, -1, 9284, 9274, 9273, -1, 9284, 9172, 9171, -1, 9284, 9171, 9274, -1, 9284, 9273, 9283, -1, 9285, 9275, 9263, -1, 9286, 9280, 9251, -1, 9285, 9263, 9272, -1, 9286, 9251, 9245, -1, 9286, 9283, 9280, -1, 9287, 4920, 4952, -1, 9288, 9283, 9286, -1, 9287, 9271, 4920, -1, 9289, 9283, 9288, -1, 9289, 9284, 9283, -1, 9289, 9172, 9284, -1, 9290, 9248, 9275, -1, 9289, 9173, 9172, -1, 9290, 9258, 9248, -1, 9291, 9286, 9245, -1, 9291, 9288, 9286, -1, 9291, 9245, 9236, -1, 9292, 9262, 9278, -1, 9293, 9288, 9291, -1, 9292, 9272, 9262, -1, 9294, 9173, 9289, -1, 9295, 6502, 6501, -1, 9294, 9288, 9293, -1, 9294, 9289, 9288, -1, 9294, 9174, 9173, -1, 9296, 9293, 9291, -1, 9296, 9236, 9229, -1, 9295, 6501, 9281, -1, 9296, 9291, 9236, -1, 9297, 9293, 9296, -1, 9298, 9278, 9266, -1, 9298, 9266, 9282, -1, 9299, 9293, 9297, -1, 9300, 9275, 9285, -1, 9299, 9294, 9293, -1, 9299, 9174, 9294, -1, 9299, 9175, 9174, -1, 9301, 9229, 9223, -1, 9301, 9296, 9229, -1, 9300, 9290, 9275, -1, 9301, 9297, 9296, -1, 9302, 9299, 9297, -1, 9303, 9271, 9287, -1, 9302, 9176, 9175, -1, 9302, 9175, 9299, -1, 9303, 9282, 9271, -1, 9302, 9297, 9301, -1, 9304, 9301, 9223, -1, 9305, 9258, 9290, -1, 9305, 9267, 9258, -1, 9304, 9223, 9216, -1, 9305, 9290, 9300, -1, 9306, 9285, 9272, -1, 9307, 9301, 9304, -1, 9306, 9272, 9292, -1, 9308, 9301, 9307, -1, 9309, 9302, 9301, -1, 9310, 6504, 6502, -1, 9309, 9301, 9308, -1, 9311, 9177, 9176, -1, 9311, 9176, 9302, -1, 9311, 9302, 9309, -1, 9310, 6502, 9295, -1, 9311, 9309, 9308, -1, 9312, 9216, 9201, -1, 9312, 9304, 9216, -1, 9313, 9287, 4952, -1, 9312, 9307, 9304, -1, 9314, 9178, 9177, -1, 9314, 9177, 9311, -1, 9314, 9308, 9307, -1, 9315, 9292, 9278, -1, 9314, 9311, 9308, -1, 9315, 9278, 9298, -1, 9314, 9307, 9312, -1, 9316, 9314, 9312, -1, 9316, 9201, 9203, -1, 9316, 9312, 9201, -1, 9317, 9305, 9300, -1, 9318, 9314, 9316, -1, 9319, 9179, 9178, -1, 9320, 9298, 9282, -1, 9319, 9178, 9314, -1, 9320, 9282, 9303, -1, 9319, 9314, 9318, -1, 9321, 9322, 9323, -1, 9321, 9316, 9203, -1, 9321, 9181, 9180, -1, 9324, 9281, 9267, -1, 9324, 9267, 9305, -1, 9321, 9203, 9322, -1, 9321, 9323, 9181, -1, 9321, 9318, 9316, -1, 9325, 9180, 9179, -1, 9325, 9179, 9319, -1, 9325, 9319, 9318, -1, 9326, 4952, 4925, -1, 9325, 9321, 9180, -1, 9325, 9318, 9321, -1, 9326, 9313, 4952, -1, 9327, 9300, 9285, -1, 9327, 9285, 9306, -1, 9328, 6510, 6504, -1, 9328, 6504, 9310, -1, 9329, 9303, 9287, -1, 9329, 9287, 9313, -1, 9330, 9292, 9315, -1, 9330, 9306, 9292, -1, 9331, 9324, 9305, -1, 9331, 9305, 9317, -1, 9332, 9315, 9298, -1, 9332, 9298, 9320, -1, 9333, 9281, 9324, -1, 9333, 9295, 9281, -1, 9334, 9313, 9326, -1, 9334, 9329, 9313, -1, 9335, 9317, 9300, -1, 9335, 9300, 9327, -1, 9336, 6515, 6510, -1, 9336, 6510, 9328, -1, 9337, 9303, 9329, -1, 9337, 9320, 9303, -1, 9338, 9327, 9306, -1, 9338, 9306, 9330, -1, 9339, 9324, 9331, -1, 9339, 9333, 9324, -1, 9340, 9315, 9332, -1, 9340, 9330, 9315, -1, 9341, 9295, 9333, -1, 9341, 9333, 9339, -1, 9341, 9310, 9295, -1, 9342, 9329, 9334, -1, 9342, 9337, 9329, -1, 9343, 9331, 9317, -1, 9343, 9317, 9335, -1, 9344, 4925, 4924, -1, 9344, 4924, 9182, -1, 9344, 9182, 9181, -1, 9344, 9326, 4925, -1, 9192, 6518, 6515, -1, 9192, 6515, 9336, -1, 9345, 9320, 9337, -1, 9345, 9332, 9320, -1, 9346, 9335, 9327, -1, 9346, 9327, 9338, -1, 9347, 9341, 9339, -1, 9348, 9338, 9330, -1, 9348, 9330, 9340, -1, 9349, 9328, 9310, -1, 9349, 9310, 9341, -1, 9202, 9337, 9342, -1, 9202, 9345, 9337, -1, 9350, 9331, 9343, -1, 9350, 9339, 9331, -1, 9323, 9334, 9326, -1, 9323, 9344, 9181, -1, 9323, 9326, 9344, -1, 9193, 6524, 6518, -1, 9193, 6518, 9192, -1, 9351, 9332, 9345, -1, 9351, 9340, 9332, -1, 9188, 9335, 9346, -1, 9188, 9343, 9335, -1, 9199, 9341, 9347, -1, 9199, 9349, 9341, -1, 9206, 9346, 9338, -1, 9206, 9338, 9348, -1, 9184, 9328, 9349, -1, 9184, 9336, 9328, -1, 9204, 9351, 9345, -1, 9204, 9345, 9202, -1, 9208, 9347, 9339, -1, 9208, 9339, 9350, -1, 9322, 9342, 9334, -1, 9322, 9334, 9323, -1, 9213, 4931, 4929, -1, 9213, 6537, 6524, -1, 9213, 4929, 6537, -1, 9213, 6524, 9193, -1, 9195, 9348, 9340, -1, 9195, 9340, 9351, -1, 9190, 9343, 9188, -1, 9190, 9350, 9343, -1, 9185, 9349, 9199, -1, 9185, 9184, 9349, -1, 9189, 9188, 9346, -1, 9189, 9346, 9206, -1, 9186, 9336, 9184, -1, 9186, 9192, 9336, -1, 9196, 9195, 9351, -1, 9196, 9351, 9204, -1, 9200, 9347, 9208, -1, 9200, 9199, 9347, -1, 9203, 9202, 9342, -1, 9203, 9342, 9322, -1, 9197, 9348, 9195, -1, 9197, 9206, 9348, -1, 9209, 9208, 9350, -1, 9209, 9350, 9190, -1, 7678, 7056, 7603, -1, 7678, 7057, 7056, -1, 7682, 7559, 7558, -1, 7682, 7558, 7688, -1, 7562, 7677, 7691, -1, 7562, 7691, 7563, -1, 7054, 8245, 8119, -1, 7054, 8119, 7052, -1, 8160, 8234, 8231, -1, 8160, 8231, 8104, -1, 8242, 8237, 8122, -1, 8120, 8242, 8122, -1, 7678, 7603, 7682, -1, 7682, 7603, 7559, -1, 7688, 7558, 7691, -1, 7691, 7558, 7563, -1, 8242, 8120, 8245, -1, 8245, 8120, 8119, -1, 8234, 8160, 8237, -1, 8237, 8160, 8122, -1, 6958, 6957, 9352, -1, 9352, 6957, 9353, -1, 9352, 6831, 6958, -1, 9353, 6831, 9352, -1, 6957, 6831, 9353, -1, 6982, 6974, 9354, -1, 6982, 9354, 9355, -1, 9355, 6865, 6982, -1, 9354, 6865, 9355, -1, 6974, 6865, 9354, -1, 6855, 6853, 6857, -1, 6861, 6866, 6863, -1, 6859, 6866, 6861, -1, 6850, 7033, 6853, -1, 6853, 7033, 6857, -1, 6866, 6870, 6868, -1, 6859, 6870, 6866, -1, 7032, 7031, 7033, -1, 7033, 7031, 6857, -1, 6870, 6875, 6873, -1, 6857, 6877, 6859, -1, 6859, 6877, 6870, -1, 7031, 6877, 6857, -1, 6870, 6877, 6875, -1, 6877, 6881, 6879, -1, 7030, 7023, 7031, -1, 7028, 7023, 7030, -1, 7026, 7023, 7028, -1, 6881, 7018, 7017, -1, 7031, 7018, 6877, -1, 6877, 7018, 6881, -1, 7022, 7021, 7023, -1, 7023, 7019, 7031, -1, 7021, 7019, 7023, -1, 7031, 7019, 7018, -1, 7021, 7020, 7019, -1, 7036, 7035, 7037, -1, 7037, 7039, 7038, -1, 6841, 6839, 6843, -1, 6836, 6834, 6839, -1, 6845, 6816, 6847, -1, 6843, 6816, 6845, -1, 7049, 6816, 7050, -1, 7048, 6816, 7049, -1, 7047, 6816, 7048, -1, 7045, 6816, 7047, -1, 7043, 6816, 7045, -1, 7040, 6816, 7043, -1, 7039, 6816, 7040, -1, 7034, 6816, 7035, -1, 6847, 6816, 7034, -1, 7035, 6816, 7037, -1, 7037, 6816, 7039, -1, 6834, 6816, 6839, -1, 6839, 6816, 6843, -1, 6834, 6832, 6816, -1, 6832, 6829, 6816, -1, 6816, 6821, 6819, -1, 6829, 6827, 6816, -1, 6816, 6823, 6821, -1, 6827, 6825, 6816, -1, 6816, 6825, 6823, -1, 6968, 6970, 6893, -1, 6893, 6970, 6891, -1, 6970, 6971, 6891, -1, 6891, 6971, 6366, -1, 6971, 6367, 6366, -1, 6365, 7041, 6363, -1, 6363, 7041, 7008, -1, 7008, 7042, 7005, -1, 7041, 7042, 7008, -1, 7005, 7044, 7016, -1, 7042, 7044, 7005, -1, 7016, 7046, 7014, -1, 7044, 7046, 7016, -1, 7014, 6924, 7013, -1, 7046, 6924, 7014, -1, 7013, 6922, 7012, -1, 6924, 6922, 7013, -1, 7012, 6920, 7010, -1, 6922, 6920, 7012, -1, 7010, 6919, 7007, -1, 6920, 6919, 7010, -1, 7007, 6916, 6913, -1, 6919, 6916, 7007, -1, 6913, 6915, 6904, -1, 6916, 6915, 6913, -1, 6904, 6959, 6902, -1, 6915, 6959, 6904, -1, 6902, 6960, 6900, -1, 6959, 6960, 6902, -1, 6900, 6962, 6898, -1, 6960, 6962, 6900, -1, 6898, 6964, 6896, -1, 6962, 6964, 6898, -1, 6964, 6966, 6896, -1, 6896, 6966, 6894, -1, 6966, 6968, 6894, -1, 6894, 6968, 6893, -1, 6976, 6975, 6889, -1, 6889, 6975, 6890, -1, 6975, 6973, 6890, -1, 6890, 6973, 6327, -1, 6973, 6328, 6327, -1, 6326, 7024, 6324, -1, 6324, 7024, 6996, -1, 6996, 7025, 6989, -1, 7024, 7025, 6996, -1, 6989, 7027, 6990, -1, 7025, 7027, 6989, -1, 6990, 7029, 6991, -1, 7027, 7029, 6990, -1, 6991, 6937, 6992, -1, 7029, 6937, 6991, -1, 6992, 6936, 6993, -1, 6937, 6936, 6992, -1, 6993, 6935, 6994, -1, 6936, 6935, 6993, -1, 6994, 6934, 6995, -1, 6935, 6934, 6994, -1, 6995, 6933, 6911, -1, 6934, 6933, 6995, -1, 6911, 6932, 6886, -1, 6933, 6932, 6911, -1, 6886, 6981, 6885, -1, 6932, 6981, 6886, -1, 6885, 6980, 6883, -1, 6981, 6980, 6885, -1, 6883, 6979, 6884, -1, 6980, 6979, 6883, -1, 6884, 6978, 6887, -1, 6979, 6978, 6884, -1, 6978, 6977, 6887, -1, 6887, 6977, 6888, -1, 6977, 6976, 6888, -1, 6888, 6976, 6889, -1, 9356, 9357, 9358, -1, 9359, 9360, 9361, -1, 9362, 9357, 9356, -1, 9362, 9363, 9357, -1, 9359, 9361, 9364, -1, 9365, 9366, 9367, -1, 9368, 9369, 9370, -1, 9371, 9372, 9373, -1, 9365, 9356, 9358, -1, 9374, 9375, 9376, -1, 9368, 9377, 9369, -1, 9365, 9358, 9366, -1, 9365, 9362, 9356, -1, 9378, 9379, 9380, -1, 9378, 9380, 9381, -1, 9374, 9382, 9375, -1, 9378, 9383, 9379, -1, 9384, 9385, 9386, -1, 9387, 9364, 9388, -1, 9389, 9381, 9390, -1, 9384, 9391, 9385, -1, 9389, 9390, 9392, -1, 9389, 9378, 9381, -1, 9393, 9386, 9394, -1, 9389, 9392, 9395, -1, 9387, 9388, 9396, -1, 9397, 9398, 9399, -1, 9400, 9401, 9402, -1, 9400, 9403, 9401, -1, 9397, 9404, 9398, -1, 9405, 9406, 9407, -1, 9397, 9399, 9408, -1, 9409, 9408, 9410, -1, 9405, 9407, 9411, -1, 9409, 9410, 9412, -1, 9409, 9412, 9413, -1, 9414, 9415, 9416, -1, 9414, 9416, 9417, -1, 9414, 9417, 9418, -1, 9409, 9397, 9408, -1, 9419, 9420, 9421, -1, 9383, 9422, 9423, -1, 9424, 9425, 9363, -1, 9419, 9426, 9420, -1, 9383, 9370, 9422, -1, 9424, 9427, 9425, -1, 9424, 9428, 9427, -1, 9429, 9430, 9431, -1, 9432, 9365, 9367, -1, 9432, 9363, 9362, -1, 9432, 9362, 9365, -1, 9429, 9431, 9433, -1, 9432, 9424, 9363, -1, 9434, 9421, 9360, -1, 9435, 9436, 9437, -1, 9435, 9383, 9378, -1, 9435, 9437, 9383, -1, 9434, 9360, 9359, -1, 9438, 9435, 9378, -1, 9439, 9382, 9374, -1, 9440, 9418, 9377, -1, 9441, 9378, 9389, -1, 9439, 9396, 9382, -1, 9440, 9377, 9368, -1, 9442, 9359, 9364, -1, 9443, 9378, 9441, -1, 9444, 9433, 9391, -1, 9443, 9438, 9378, -1, 9442, 9364, 9387, -1, 9445, 9389, 9395, -1, 9445, 9441, 9389, -1, 9446, 9406, 9405, -1, 9445, 9443, 9441, -1, 9444, 9391, 9384, -1, 9445, 9395, 9447, -1, 9448, 9449, 9404, -1, 9448, 9404, 9397, -1, 9446, 9450, 9406, -1, 9451, 9411, 9426, -1, 9452, 9384, 9386, -1, 9452, 9386, 9393, -1, 9453, 9454, 9403, -1, 9455, 9397, 9409, -1, 9453, 9403, 9400, -1, 9455, 9448, 9397, -1, 9451, 9426, 9419, -1, 9456, 9455, 9409, -1, 9456, 9448, 9455, -1, 9437, 9370, 9383, -1, 9457, 9419, 9421, -1, 9437, 9368, 9370, -1, 9458, 9456, 9409, -1, 9459, 9409, 9413, -1, 9459, 9460, 9461, -1, 9459, 9413, 9460, -1, 9457, 9421, 9434, -1, 9462, 9430, 9429, -1, 9459, 9458, 9409, -1, 9462, 9402, 9430, -1, 9463, 9396, 9439, -1, 9464, 9428, 9424, -1, 9463, 9387, 9396, -1, 9464, 9465, 9428, -1, 9466, 9464, 9424, -1, 9467, 9359, 9442, -1, 9466, 9424, 9432, -1, 9468, 9466, 9432, -1, 9469, 9470, 9415, -1, 9467, 9434, 9359, -1, 9469, 9414, 9418, -1, 9469, 9418, 9440, -1, 9469, 9415, 9414, -1, 9468, 9464, 9466, -1, 9471, 9450, 9446, -1, 9472, 9433, 9444, -1, 9473, 9468, 9432, -1, 9472, 9429, 9433, -1, 9471, 9413, 9450, -1, 9474, 9473, 9432, -1, 9474, 9475, 9476, -1, 9474, 9367, 9475, -1, 9477, 9394, 9478, -1, 9474, 9432, 9367, -1, 9477, 9393, 9394, -1, 9479, 9480, 9436, -1, 9481, 9411, 9451, -1, 9481, 9405, 9411, -1, 9479, 9436, 9435, -1, 9479, 9435, 9438, -1, 9482, 9444, 9384, -1, 9483, 9479, 9438, -1, 9482, 9384, 9452, -1, 9483, 9438, 9443, -1, 9484, 9485, 9454, -1, 9483, 9445, 9447, -1, 9483, 9443, 9445, -1, 9486, 9419, 9457, -1, 9486, 9451, 9419, -1, 9484, 9454, 9453, -1, 9487, 9449, 9448, -1, 9487, 9448, 9456, -1, 9488, 9442, 9387, -1, 9436, 9368, 9437, -1, 9487, 9456, 9458, -1, 9489, 9487, 9458, -1, 9488, 9387, 9463, -1, 9436, 9440, 9368, -1, 9490, 9402, 9462, -1, 9489, 9461, 9491, -1, 9489, 9459, 9461, -1, 9489, 9458, 9459, -1, 9492, 9465, 9464, -1, 9492, 9464, 9468, -1, 9492, 9468, 9473, -1, 9493, 9457, 9434, -1, 9490, 9400, 9402, -1, 9493, 9434, 9467, -1, 9494, 9473, 9474, -1, 9494, 9474, 9476, -1, 9495, 9460, 9413, -1, 9495, 9413, 9471, -1, 9494, 9476, 9496, -1, 9494, 9492, 9473, -1, 9497, 9470, 9480, -1, 9498, 9462, 9429, -1, 9497, 9480, 9479, -1, 9498, 9429, 9472, -1, 9499, 9446, 9405, -1, 9499, 9405, 9481, -1, 9500, 9497, 9479, -1, 9501, 9393, 9477, -1, 9500, 9479, 9483, -1, 9502, 9470, 9497, -1, 9502, 9497, 9500, -1, 9502, 9500, 9483, -1, 9503, 9481, 9451, -1, 9501, 9452, 9393, -1, 9503, 9451, 9486, -1, 9504, 9470, 9502, -1, 9505, 9444, 9482, -1, 9504, 9502, 9483, -1, 9504, 9506, 9470, -1, 9505, 9472, 9444, -1, 9507, 9508, 9506, -1, 9507, 9447, 9508, -1, 9507, 9504, 9483, -1, 9507, 9483, 9447, -1, 9509, 9467, 9442, -1, 9507, 9506, 9504, -1, 9509, 9442, 9488, -1, 9510, 9511, 9449, -1, 9512, 9485, 9484, -1, 9510, 9449, 9487, -1, 9512, 9513, 9485, -1, 9510, 9514, 9511, -1, 9480, 9469, 9440, -1, 9480, 9470, 9469, -1, 9515, 9486, 9457, -1, 9480, 9440, 9436, -1, 9516, 9514, 9510, -1, 9515, 9457, 9493, -1, 9516, 9510, 9487, -1, 9516, 9517, 9514, -1, 9518, 9400, 9490, -1, 9519, 9461, 9460, -1, 9519, 9460, 9495, -1, 9520, 9487, 9489, -1, 9518, 9453, 9400, -1, 9521, 9516, 9487, -1, 9522, 9446, 9499, -1, 9521, 9517, 9516, -1, 9522, 9471, 9446, -1, 9521, 9487, 9520, -1, 9523, 9489, 9491, -1, 9523, 9520, 9489, -1, 9523, 9521, 9520, -1, 9523, 9517, 9521, -1, 9523, 9491, 9517, -1, 9524, 9465, 9492, -1, 9525, 9490, 9462, -1, 9526, 9481, 9503, -1, 9526, 9499, 9481, -1, 9524, 9527, 9465, -1, 9525, 9462, 9498, -1, 9524, 9528, 9527, -1, 9529, 9524, 9492, -1, 9530, 9482, 9452, -1, 9529, 9531, 9528, -1, 9529, 9528, 9524, -1, 9532, 9493, 9467, -1, 9533, 9492, 9494, -1, 9532, 9467, 9509, -1, 9530, 9452, 9501, -1, 9534, 9472, 9505, -1, 9535, 9492, 9533, -1, 9535, 9529, 9492, -1, 9534, 9498, 9472, -1, 9535, 9531, 9529, -1, 9536, 9494, 9496, -1, 9537, 9503, 9486, -1, 9536, 9496, 9531, -1, 9536, 9535, 9533, -1, 9537, 9486, 9515, -1, 9538, 9539, 9513, -1, 9536, 9533, 9494, -1, 9540, 9541, 9517, -1, 9536, 9531, 9535, -1, 9540, 9517, 9491, -1, 9538, 9513, 9512, -1, 9540, 9461, 9519, -1, 9540, 9491, 9461, -1, 9542, 9453, 9518, -1, 9542, 9484, 9453, -1, 9543, 9495, 9471, -1, 9543, 9471, 9522, -1, 9544, 9522, 9499, -1, 9544, 9499, 9526, -1, 9545, 9493, 9532, -1, 9546, 9518, 9490, -1, 9546, 9490, 9525, -1, 9545, 9515, 9493, -1, 9547, 9526, 9503, -1, 9548, 9505, 9482, -1, 9548, 9482, 9530, -1, 9547, 9503, 9537, -1, 9549, 9519, 9495, -1, 9550, 9372, 9371, -1, 9549, 9495, 9543, -1, 9551, 9543, 9522, -1, 9551, 9522, 9544, -1, 9552, 9498, 9534, -1, 9553, 9554, 9372, -1, 9555, 9537, 9515, -1, 9552, 9525, 9498, -1, 9556, 9557, 9539, -1, 9553, 9372, 9550, -1, 9556, 9539, 9538, -1, 9555, 9515, 9545, -1, 9558, 9544, 9526, -1, 9559, 9512, 9484, -1, 9560, 9561, 9554, -1, 9559, 9484, 9542, -1, 9558, 9526, 9547, -1, 9562, 9541, 9540, -1, 9560, 9554, 9553, -1, 9562, 9540, 9519, -1, 9562, 9519, 9549, -1, 9563, 9371, 9564, -1, 9562, 9565, 9541, -1, 9566, 9543, 9551, -1, 9566, 9549, 9543, -1, 9563, 9550, 9371, -1, 9567, 9518, 9546, -1, 9567, 9542, 9518, -1, 9568, 9537, 9555, -1, 9568, 9547, 9537, -1, 9569, 9570, 9561, -1, 9571, 9534, 9505, -1, 9571, 9505, 9548, -1, 9569, 9561, 9560, -1, 9572, 9551, 9544, -1, 9573, 9550, 9563, -1, 9572, 9544, 9558, -1, 9573, 9553, 9550, -1, 9574, 9549, 9566, -1, 9574, 9562, 9549, -1, 9575, 9564, 9576, -1, 9574, 9565, 9562, -1, 9575, 9563, 9564, -1, 9427, 9547, 9568, -1, 9577, 9525, 9552, -1, 9427, 9558, 9547, -1, 9577, 9546, 9525, -1, 9578, 9579, 9570, -1, 9580, 9392, 9557, -1, 9578, 9570, 9569, -1, 9580, 9557, 9556, -1, 9581, 9566, 9551, -1, 9581, 9551, 9572, -1, 9582, 9553, 9573, -1, 9583, 9512, 9559, -1, 9582, 9560, 9553, -1, 9583, 9538, 9512, -1, 9428, 9558, 9427, -1, 9428, 9572, 9558, -1, 9584, 9574, 9566, -1, 9585, 9573, 9563, -1, 9584, 9566, 9581, -1, 9584, 9565, 9574, -1, 9584, 9528, 9565, -1, 9585, 9563, 9575, -1, 9586, 9559, 9542, -1, 9465, 9581, 9572, -1, 9586, 9542, 9567, -1, 9587, 9575, 9576, -1, 9465, 9572, 9428, -1, 9527, 9581, 9465, -1, 9588, 9534, 9571, -1, 9589, 9590, 9579, -1, 9527, 9528, 9584, -1, 9588, 9552, 9534, -1, 9527, 9584, 9581, -1, 9589, 9579, 9578, -1, 9591, 9592, 9593, -1, 9594, 9569, 9560, -1, 9594, 9560, 9582, -1, 9595, 9546, 9577, -1, 9595, 9567, 9546, -1, 9596, 9597, 9598, -1, 9599, 9598, 9600, -1, 9601, 9573, 9585, -1, 9599, 9592, 9591, -1, 9601, 9582, 9573, -1, 9599, 9591, 9602, -1, 9603, 9395, 9392, -1, 9599, 9602, 9596, -1, 9599, 9596, 9598, -1, 9604, 9585, 9575, -1, 9599, 9605, 9592, -1, 9603, 9392, 9580, -1, 9606, 9607, 9605, -1, 9608, 9609, 9610, -1, 9604, 9575, 9587, -1, 9606, 9599, 9600, -1, 9608, 9611, 9609, -1, 9606, 9600, 9612, -1, 9606, 9605, 9599, -1, 9613, 9614, 9590, -1, 9615, 9612, 9401, -1, 9616, 9538, 9583, -1, 9613, 9590, 9589, -1, 9615, 9617, 9607, -1, 9615, 9607, 9606, -1, 9615, 9606, 9612, -1, 9616, 9556, 9538, -1, 9618, 9569, 9594, -1, 9619, 9559, 9586, -1, 9620, 9615, 9401, -1, 9620, 9617, 9615, -1, 9618, 9578, 9569, -1, 9619, 9583, 9559, -1, 9621, 9594, 9582, -1, 9622, 9501, 9477, -1, 9623, 9552, 9588, -1, 9623, 9577, 9552, -1, 9621, 9582, 9601, -1, 9593, 9576, 9624, -1, 9593, 9587, 9576, -1, 9625, 9611, 9626, -1, 9627, 9601, 9585, -1, 9628, 9501, 9622, -1, 9628, 9625, 9626, -1, 9628, 9530, 9501, -1, 9628, 9626, 9629, -1, 9627, 9585, 9604, -1, 9630, 9586, 9567, -1, 9628, 9622, 9631, -1, 9630, 9567, 9595, -1, 9628, 9631, 9625, -1, 9632, 9629, 9633, -1, 9634, 9635, 9636, -1, 9632, 9548, 9530, -1, 9634, 9636, 9614, -1, 9632, 9628, 9629, -1, 9634, 9614, 9613, -1, 9632, 9530, 9628, -1, 9637, 9632, 9633, -1, 9638, 9395, 9603, -1, 9637, 9548, 9632, -1, 9637, 9633, 9639, -1, 9640, 9578, 9618, -1, 9638, 9447, 9395, -1, 9640, 9589, 9578, -1, 9637, 9571, 9548, -1, 9641, 9571, 9637, -1, 9642, 9611, 9608, -1, 9641, 9637, 9639, -1, 9642, 9626, 9611, -1, 9643, 9603, 9580, -1, 9644, 9594, 9621, -1, 9643, 9556, 9616, -1, 9644, 9618, 9594, -1, 9592, 9604, 9587, -1, 9643, 9580, 9556, -1, 9645, 9376, 9646, -1, 9592, 9587, 9593, -1, 9647, 9583, 9619, -1, 9648, 9601, 9627, -1, 9647, 9616, 9583, -1, 9648, 9621, 9601, -1, 9649, 9595, 9577, -1, 9649, 9577, 9623, -1, 9650, 9651, 9652, -1, 9653, 9376, 9645, -1, 9653, 9374, 9376, -1, 9653, 9645, 9654, -1, 9653, 9650, 9652, -1, 9653, 9654, 9650, -1, 9655, 9635, 9634, -1, 9653, 9652, 9656, -1, 9657, 9374, 9653, -1, 9657, 9653, 9656, -1, 9658, 9613, 9589, -1, 9658, 9589, 9640, -1, 9657, 9656, 9659, -1, 9657, 9439, 9374, -1, 9660, 9439, 9657, -1, 9660, 9657, 9659, -1, 9661, 9640, 9618, -1, 9661, 9618, 9644, -1, 9660, 9463, 9439, -1, 9662, 9586, 9630, -1, 9660, 9659, 9663, -1, 9662, 9619, 9586, -1, 9664, 9506, 9508, -1, 9665, 9463, 9660, -1, 9664, 9508, 9447, -1, 9664, 9447, 9638, -1, 9664, 9666, 9506, -1, 9665, 9660, 9663, -1, 9667, 9629, 9626, -1, 9605, 9604, 9592, -1, 9667, 9626, 9642, -1, 9668, 9591, 9593, -1, 9605, 9627, 9604, -1, 9668, 9593, 9624, -1, 9669, 9644, 9621, -1, 9669, 9621, 9648, -1, 9670, 9668, 9624, -1, 9671, 9603, 9643, -1, 9672, 9670, 9624, -1, 9673, 9674, 9635, -1, 9672, 9596, 9602, -1, 9673, 9635, 9655, -1, 9675, 9668, 9670, -1, 9675, 9672, 9602, -1, 9676, 9643, 9616, -1, 9675, 9670, 9672, -1, 9675, 9591, 9668, -1, 9676, 9616, 9647, -1, 9675, 9602, 9591, -1, 9677, 9624, 9678, -1, 9677, 9596, 9672, -1, 9679, 9634, 9613, -1, 9677, 9672, 9624, -1, 9677, 9678, 9597, -1, 9679, 9613, 9658, -1, 9677, 9597, 9596, -1, 9680, 9681, 9617, -1, 9682, 9595, 9649, -1, 9680, 9683, 9681, -1, 9682, 9630, 9595, -1, 9680, 9617, 9620, -1, 9684, 9608, 9610, -1, 9685, 9658, 9640, -1, 9684, 9610, 9686, -1, 9685, 9640, 9661, -1, 9607, 9627, 9605, -1, 9687, 9680, 9620, -1, 9688, 9620, 9401, -1, 9688, 9401, 9403, -1, 9688, 9403, 9454, -1, 9607, 9648, 9627, -1, 9688, 9687, 9620, -1, 9689, 9477, 9478, -1, 9689, 9622, 9477, -1, 9690, 9689, 9478, -1, 9691, 9647, 9619, -1, 9691, 9619, 9662, -1, 9692, 9644, 9669, -1, 9693, 9690, 9478, -1, 9694, 9633, 9629, -1, 9692, 9661, 9644, -1, 9693, 9625, 9631, -1, 9695, 9622, 9689, -1, 9695, 9690, 9693, -1, 9694, 9629, 9667, -1, 9695, 9693, 9631, -1, 9695, 9689, 9690, -1, 9696, 9697, 9674, -1, 9695, 9631, 9622, -1, 9698, 9611, 9625, -1, 9696, 9674, 9673, -1, 9698, 9478, 9609, -1, 9698, 9609, 9611, -1, 9698, 9693, 9478, -1, 9698, 9625, 9693, -1, 9699, 9603, 9671, -1, 9700, 9634, 9679, -1, 9701, 9571, 9641, -1, 9700, 9655, 9634, -1, 9701, 9588, 9571, -1, 9699, 9638, 9603, -1, 9701, 9623, 9588, -1, 9702, 9671, 9643, -1, 9703, 9679, 9658, -1, 9702, 9643, 9676, -1, 9703, 9658, 9685, -1, 9704, 9701, 9641, -1, 9705, 9706, 9707, -1, 9617, 9669, 9648, -1, 9705, 9641, 9639, -1, 9705, 9704, 9641, -1, 9708, 9662, 9630, -1, 9705, 9639, 9706, -1, 9708, 9630, 9682, -1, 9709, 9645, 9646, -1, 9709, 9646, 9710, -1, 9617, 9648, 9607, -1, 9709, 9654, 9645, -1, 9711, 9642, 9608, -1, 9712, 9710, 9713, -1, 9711, 9608, 9684, -1, 9712, 9654, 9709, -1, 9712, 9709, 9710, -1, 9714, 9651, 9650, -1, 9714, 9650, 9654, -1, 9714, 9713, 9651, -1, 9714, 9712, 9713, -1, 9715, 9661, 9692, -1, 9714, 9654, 9712, -1, 9716, 9463, 9665, -1, 9715, 9685, 9661, -1, 9716, 9509, 9488, -1, 9716, 9488, 9463, -1, 9717, 9718, 9697, -1, 9719, 9647, 9691, -1, 9717, 9697, 9696, -1, 9719, 9676, 9647, -1, 9720, 9673, 9655, -1, 9721, 9716, 9665, -1, 9722, 9686, 9723, -1, 9724, 9665, 9663, -1, 9724, 9725, 9726, -1, 9724, 9663, 9725, -1, 9724, 9721, 9665, -1, 9720, 9655, 9700, -1, 9722, 9684, 9686, -1, 9727, 9683, 9680, -1, 9728, 9700, 9679, -1, 9728, 9679, 9703, -1, 9727, 9680, 9687, -1, 9727, 9729, 9683, -1, 9730, 9633, 9694, -1, 9731, 9727, 9687, -1, 9681, 9669, 9617, -1, 9681, 9692, 9669, -1, 9730, 9639, 9633, -1, 9732, 9664, 9638, -1, 9732, 9666, 9664, -1, 9732, 9733, 9666, -1, 9734, 9731, 9687, -1, 9732, 9638, 9699, -1, 9734, 9454, 9485, -1, 9734, 9688, 9454, -1, 9734, 9687, 9688, -1, 9735, 9701, 9704, -1, 9735, 9649, 9623, -1, 9736, 9699, 9671, -1, 9736, 9671, 9702, -1, 9735, 9623, 9701, -1, 9737, 9703, 9685, -1, 9737, 9685, 9715, -1, 9738, 9662, 9708, -1, 9738, 9691, 9662, -1, 9739, 9735, 9704, -1, 9740, 9705, 9707, -1, 9740, 9739, 9704, -1, 9741, 9742, 9718, -1, 9740, 9707, 9743, -1, 9741, 9718, 9717, -1, 9740, 9704, 9705, -1, 9744, 9532, 9509, -1, 9745, 9667, 9642, -1, 9745, 9642, 9711, -1, 9746, 9678, 9747, -1, 9744, 9716, 9721, -1, 9744, 9509, 9716, -1, 9748, 9744, 9721, -1, 9746, 9597, 9678, -1, 9749, 9696, 9673, -1, 9749, 9673, 9720, -1, 9750, 9676, 9719, -1, 9751, 9726, 9752, -1, 9751, 9721, 9724, -1, 9753, 9720, 9700, -1, 9751, 9748, 9721, -1, 9753, 9700, 9728, -1, 9751, 9724, 9726, -1, 9750, 9702, 9676, -1, 9754, 9727, 9731, -1, 9755, 9711, 9684, -1, 9754, 9756, 9729, -1, 9754, 9729, 9727, -1, 9683, 9692, 9681, -1, 9757, 9731, 9734, -1, 9757, 9734, 9485, -1, 9755, 9684, 9722, -1, 9757, 9485, 9513, -1, 9683, 9715, 9692, -1, 9758, 9735, 9739, -1, 9759, 9722, 9723, -1, 9758, 9649, 9735, -1, 9758, 9682, 9649, -1, 9760, 9639, 9730, -1, 9761, 9739, 9740, -1, 9761, 9740, 9743, -1, 9761, 9743, 9407, -1, 9762, 9728, 9703, -1, 9760, 9706, 9639, -1, 9762, 9703, 9737, -1, 9763, 9744, 9748, -1, 9764, 9733, 9732, -1, 9763, 9532, 9744, -1, 9764, 9732, 9699, -1, 9764, 9699, 9736, -1, 9763, 9545, 9532, -1, 9765, 9766, 9742, -1, 9398, 9691, 9738, -1, 9767, 9751, 9752, -1, 9765, 9742, 9741, -1, 9767, 9748, 9751, -1, 9398, 9719, 9691, -1, 9767, 9752, 9768, -1, 9769, 9756, 9754, -1, 9770, 9667, 9745, -1, 9771, 9597, 9746, -1, 9769, 9772, 9756, -1, 9771, 9598, 9597, -1, 9773, 9717, 9696, -1, 9774, 9769, 9754, -1, 9770, 9694, 9667, -1, 9773, 9696, 9749, -1, 9775, 9774, 9754, -1, 9776, 9749, 9720, -1, 9775, 9754, 9731, -1, 9776, 9720, 9753, -1, 9775, 9731, 9757, -1, 9777, 9774, 9775, -1, 9778, 9736, 9702, -1, 9778, 9702, 9750, -1, 9779, 9513, 9539, -1, 9729, 9737, 9715, -1, 9779, 9757, 9513, -1, 9779, 9775, 9757, -1, 9779, 9777, 9775, -1, 9780, 9711, 9755, -1, 9729, 9715, 9683, -1, 9781, 9708, 9682, -1, 9780, 9745, 9711, -1, 9781, 9682, 9758, -1, 9782, 9758, 9739, -1, 9782, 9739, 9761, -1, 9782, 9781, 9758, -1, 9375, 9755, 9722, -1, 9375, 9722, 9759, -1, 9783, 9753, 9728, -1, 9783, 9728, 9762, -1, 9784, 9782, 9761, -1, 9784, 9781, 9782, -1, 9420, 9707, 9706, -1, 9785, 9786, 9787, -1, 9785, 9787, 9766, -1, 9420, 9706, 9760, -1, 9785, 9788, 9786, -1, 9785, 9766, 9765, -1, 9789, 9784, 9761, -1, 9431, 9598, 9771, -1, 9790, 9761, 9407, -1, 9404, 9719, 9398, -1, 9431, 9600, 9598, -1, 9790, 9789, 9761, -1, 9790, 9407, 9406, -1, 9791, 9555, 9545, -1, 9404, 9750, 9719, -1, 9361, 9730, 9694, -1, 9791, 9545, 9763, -1, 9792, 9741, 9717, -1, 9792, 9717, 9773, -1, 9793, 9791, 9763, -1, 9793, 9763, 9748, -1, 9793, 9748, 9767, -1, 9361, 9694, 9770, -1, 9369, 9749, 9776, -1, 9369, 9773, 9749, -1, 9794, 9791, 9793, -1, 9794, 9793, 9767, -1, 9756, 9762, 9737, -1, 9756, 9737, 9729, -1, 9795, 9764, 9736, -1, 9795, 9736, 9778, -1, 9795, 9514, 9733, -1, 9796, 9794, 9767, -1, 9797, 9768, 9798, -1, 9385, 9746, 9747, -1, 9797, 9767, 9768, -1, 9795, 9733, 9764, -1, 9385, 9747, 9799, -1, 9388, 9770, 9745, -1, 9797, 9796, 9767, -1, 9800, 9769, 9774, -1, 9800, 9423, 9772, -1, 9800, 9772, 9769, -1, 9388, 9745, 9780, -1, 9646, 9759, 9723, -1, 9646, 9723, 9710, -1, 9801, 9779, 9539, -1, 9801, 9774, 9777, -1, 9801, 9777, 9779, -1, 9801, 9800, 9774, -1, 9422, 9753, 9783, -1, 9422, 9776, 9753, -1, 9802, 9781, 9784, -1, 9382, 9755, 9375, -1, 9430, 9600, 9431, -1, 9802, 9784, 9789, -1, 9382, 9780, 9755, -1, 9802, 9708, 9781, -1, 9803, 9789, 9790, -1, 9803, 9790, 9406, -1, 9426, 9743, 9707, -1, 9803, 9802, 9789, -1, 9430, 9612, 9600, -1, 9803, 9406, 9450, -1, 9426, 9707, 9420, -1, 9357, 9555, 9791, -1, 9417, 9741, 9792, -1, 9357, 9791, 9794, -1, 9449, 9778, 9750, -1, 9417, 9765, 9741, -1, 9449, 9750, 9404, -1, 9377, 9792, 9773, -1, 9357, 9794, 9796, -1, 9358, 9357, 9796, -1, 9358, 9798, 9366, -1, 9377, 9773, 9369, -1, 9358, 9797, 9798, -1, 9358, 9796, 9797, -1, 9379, 9383, 9423, -1, 9379, 9423, 9800, -1, 9360, 9730, 9361, -1, 9772, 9762, 9756, -1, 9804, 9379, 9800, -1, 9360, 9760, 9730, -1, 9772, 9783, 9762, -1, 9391, 9771, 9746, -1, 9804, 9800, 9801, -1, 9380, 9804, 9801, -1, 9391, 9746, 9385, -1, 9380, 9379, 9804, -1, 9364, 9770, 9388, -1, 9381, 9380, 9801, -1, 9364, 9361, 9770, -1, 9390, 9557, 9392, -1, 9370, 9369, 9776, -1, 9390, 9539, 9557, -1, 9376, 9759, 9646, -1, 9390, 9381, 9801, -1, 9390, 9801, 9539, -1, 9370, 9776, 9422, -1, 9386, 9385, 9799, -1, 9399, 9738, 9708, -1, 9386, 9799, 9394, -1, 9399, 9398, 9738, -1, 9376, 9375, 9759, -1, 9399, 9708, 9802, -1, 9402, 9401, 9612, -1, 9408, 9399, 9802, -1, 9396, 9388, 9780, -1, 9402, 9612, 9430, -1, 9396, 9780, 9382, -1, 9416, 9785, 9765, -1, 9411, 9407, 9743, -1, 9416, 9788, 9785, -1, 9416, 9415, 9788, -1, 9805, 9802, 9803, -1, 9416, 9765, 9417, -1, 9411, 9743, 9426, -1, 9418, 9792, 9377, -1, 9410, 9802, 9805, -1, 9410, 9408, 9802, -1, 9511, 9795, 9778, -1, 9418, 9417, 9792, -1, 9412, 9803, 9450, -1, 9511, 9514, 9795, -1, 9412, 9410, 9805, -1, 9511, 9778, 9449, -1, 9412, 9805, 9803, -1, 9423, 9422, 9783, -1, 9412, 9450, 9413, -1, 9425, 9427, 9568, -1, 9421, 9420, 9760, -1, 9425, 9568, 9555, -1, 9421, 9760, 9360, -1, 9423, 9783, 9772, -1, 9425, 9555, 9357, -1, 9433, 9771, 9391, -1, 9433, 9431, 9771, -1, 9363, 9425, 9357, -1, 9806, 9807, 9808, -1, 9809, 9810, 9811, -1, 9812, 9807, 9806, -1, 9812, 9813, 9807, -1, 9814, 9815, 9816, -1, 9814, 9806, 9808, -1, 9817, 9818, 9819, -1, 9814, 9808, 9815, -1, 9817, 9819, 9820, -1, 9821, 9822, 9823, -1, 9814, 9812, 9806, -1, 9824, 9825, 9826, -1, 9827, 9828, 9829, -1, 9821, 9823, 9830, -1, 9824, 9831, 9832, -1, 9833, 9834, 9835, -1, 9824, 9826, 9831, -1, 9836, 9832, 9837, -1, 9827, 9838, 9828, -1, 9836, 9839, 9840, -1, 9836, 9837, 9839, -1, 9841, 9842, 9843, -1, 9833, 9844, 9834, -1, 9836, 9824, 9832, -1, 9841, 9845, 9842, -1, 9846, 9835, 9847, -1, 9848, 9849, 9850, -1, 9848, 9851, 9852, -1, 9853, 9854, 9855, -1, 9848, 9852, 9849, -1, 9853, 9856, 9854, -1, 9857, 9850, 9858, -1, 9857, 9858, 9859, -1, 9857, 9859, 9860, -1, 9861, 9862, 9863, -1, 9857, 9848, 9850, -1, 9864, 9865, 9866, -1, 9861, 9863, 9867, -1, 9861, 9867, 9868, -1, 9869, 9870, 9871, -1, 9826, 9830, 9872, -1, 9869, 9873, 9813, -1, 9869, 9871, 9873, -1, 9874, 9866, 9810, -1, 9875, 9814, 9816, -1, 9875, 9813, 9812, -1, 9875, 9812, 9814, -1, 9874, 9810, 9809, -1, 9876, 9877, 9878, -1, 9875, 9869, 9813, -1, 9879, 9825, 9824, -1, 9879, 9880, 9825, -1, 9881, 9818, 9817, -1, 9876, 9882, 9877, -1, 9883, 9879, 9824, -1, 9883, 9824, 9836, -1, 9881, 9829, 9818, -1, 9884, 9809, 9838, -1, 9884, 9838, 9827, -1, 9885, 9868, 9822, -1, 9886, 9883, 9836, -1, 9885, 9822, 9821, -1, 9886, 9879, 9883, -1, 9887, 9845, 9841, -1, 9888, 9886, 9836, -1, 9887, 9889, 9845, -1, 9890, 9878, 9844, -1, 9891, 9836, 9840, -1, 9890, 9844, 9833, -1, 9891, 9840, 9892, -1, 9893, 9843, 9865, -1, 9891, 9888, 9836, -1, 9891, 9892, 9894, -1, 9895, 9851, 9848, -1, 9896, 9833, 9835, -1, 9893, 9841, 9843, -1, 9896, 9835, 9846, -1, 9895, 9897, 9851, -1, 9893, 9865, 9864, -1, 9898, 9899, 9856, -1, 9900, 9848, 9857, -1, 9900, 9895, 9848, -1, 9898, 9856, 9853, -1, 9901, 9864, 9866, -1, 9901, 9866, 9874, -1, 9902, 9900, 9857, -1, 9902, 9895, 9900, -1, 9825, 9830, 9826, -1, 9825, 9821, 9830, -1, 9903, 9855, 9882, -1, 9904, 9902, 9857, -1, 9903, 9882, 9876, -1, 9905, 9904, 9857, -1, 9905, 9860, 9906, -1, 9907, 9827, 9829, -1, 9905, 9906, 9908, -1, 9907, 9829, 9881, -1, 9905, 9857, 9860, -1, 9909, 9870, 9869, -1, 9910, 9809, 9884, -1, 9909, 9911, 9870, -1, 9910, 9874, 9809, -1, 9912, 9909, 9869, -1, 9912, 9869, 9875, -1, 9913, 9914, 9862, -1, 9915, 9889, 9887, -1, 9913, 9861, 9868, -1, 9916, 9912, 9875, -1, 9913, 9868, 9885, -1, 9913, 9862, 9861, -1, 9915, 9860, 9889, -1, 9916, 9909, 9912, -1, 9917, 9876, 9878, -1, 9918, 9841, 9893, -1, 9917, 9878, 9890, -1, 9919, 9916, 9875, -1, 9920, 9847, 9921, -1, 9922, 9919, 9875, -1, 9922, 9923, 9924, -1, 9922, 9816, 9923, -1, 9922, 9875, 9816, -1, 9920, 9846, 9847, -1, 9925, 9880, 9879, -1, 9926, 9864, 9901, -1, 9925, 9879, 9886, -1, 9926, 9893, 9864, -1, 9927, 9890, 9833, -1, 9925, 9886, 9888, -1, 9927, 9833, 9896, -1, 9928, 9894, 9929, -1, 9928, 9925, 9888, -1, 9930, 9931, 9899, -1, 9928, 9891, 9894, -1, 9928, 9888, 9891, -1, 9932, 9884, 9827, -1, 9930, 9899, 9898, -1, 9933, 9897, 9895, -1, 9932, 9827, 9907, -1, 9933, 9895, 9902, -1, 9880, 9885, 9821, -1, 9933, 9902, 9904, -1, 9880, 9821, 9825, -1, 9934, 9933, 9904, -1, 9934, 9908, 9935, -1, 9936, 9874, 9910, -1, 9934, 9904, 9905, -1, 9936, 9901, 9874, -1, 9934, 9905, 9908, -1, 9937, 9911, 9909, -1, 9938, 9853, 9855, -1, 9939, 9906, 9860, -1, 9937, 9916, 9919, -1, 9939, 9860, 9915, -1, 9938, 9855, 9903, -1, 9937, 9909, 9916, -1, 9940, 9937, 9919, -1, 9941, 9887, 9841, -1, 9940, 9919, 9922, -1, 9941, 9915, 9887, -1, 9940, 9922, 9924, -1, 9940, 9924, 9942, -1, 9943, 9914, 9944, -1, 9941, 9841, 9918, -1, 9943, 9944, 9880, -1, 9945, 9918, 9893, -1, 9943, 9880, 9925, -1, 9946, 9903, 9876, -1, 9946, 9938, 9903, -1, 9945, 9893, 9926, -1, 9946, 9876, 9917, -1, 9947, 9914, 9943, -1, 9948, 9846, 9920, -1, 9947, 9949, 9914, -1, 9947, 9943, 9925, -1, 9948, 9896, 9846, -1, 9950, 9925, 9928, -1, 9951, 9910, 9884, -1, 9952, 9917, 9890, -1, 9953, 9947, 9925, -1, 9951, 9884, 9932, -1, 9953, 9925, 9950, -1, 9953, 9949, 9947, -1, 9952, 9890, 9927, -1, 9954, 9929, 9949, -1, 9954, 9950, 9928, -1, 9954, 9949, 9953, -1, 9954, 9953, 9950, -1, 9954, 9928, 9929, -1, 9955, 9926, 9901, -1, 9956, 9957, 9931, -1, 9958, 9959, 9960, -1, 9955, 9901, 9936, -1, 9958, 9960, 9897, -1, 9956, 9931, 9930, -1, 9944, 9913, 9885, -1, 9958, 9897, 9933, -1, 9961, 9906, 9939, -1, 9944, 9914, 9913, -1, 9944, 9885, 9880, -1, 9961, 9908, 9906, -1, 9962, 9959, 9958, -1, 9962, 9963, 9959, -1, 9964, 9853, 9938, -1, 9965, 9915, 9941, -1, 9962, 9958, 9933, -1, 9966, 9933, 9934, -1, 9964, 9898, 9853, -1, 9967, 9933, 9966, -1, 9967, 9962, 9933, -1, 9967, 9963, 9962, -1, 9968, 9934, 9935, -1, 9969, 9918, 9945, -1, 9968, 9966, 9934, -1, 9969, 9941, 9918, -1, 9968, 9967, 9966, -1, 9968, 9963, 9967, -1, 9968, 9935, 9963, -1, 9970, 9938, 9946, -1, 9971, 9911, 9937, -1, 9972, 9910, 9951, -1, 9972, 9936, 9910, -1, 9973, 9896, 9948, -1, 9971, 9974, 9911, -1, 9973, 9927, 9896, -1, 9971, 9975, 9974, -1, 9976, 9971, 9937, -1, 9976, 9977, 9975, -1, 9976, 9975, 9971, -1, 9978, 9945, 9926, -1, 9979, 9946, 9917, -1, 9978, 9926, 9955, -1, 9980, 9937, 9940, -1, 9981, 9908, 9961, -1, 9982, 9976, 9937, -1, 9981, 9983, 9963, -1, 9981, 9935, 9908, -1, 9979, 9917, 9952, -1, 9982, 9937, 9980, -1, 9981, 9963, 9935, -1, 9984, 9985, 9957, -1, 9982, 9977, 9976, -1, 9986, 9940, 9942, -1, 9986, 9942, 9977, -1, 9987, 9939, 9915, -1, 9986, 9980, 9940, -1, 9986, 9977, 9982, -1, 9986, 9982, 9980, -1, 9984, 9957, 9956, -1, 9987, 9915, 9965, -1, 9988, 9930, 9898, -1, 9988, 9898, 9964, -1, 9989, 9965, 9941, -1, 9989, 9941, 9969, -1, 9990, 9936, 9972, -1, 9991, 9938, 9970, -1, 9990, 9955, 9936, -1, 9991, 9988, 9964, -1, 9992, 9969, 9945, -1, 9991, 9964, 9938, -1, 9992, 9945, 9978, -1, 9993, 9952, 9927, -1, 9993, 9927, 9973, -1, 9994, 9939, 9987, -1, 9994, 9961, 9939, -1, 9995, 9965, 9989, -1, 9995, 9987, 9965, -1, 9996, 9955, 9990, -1, 9997, 9970, 9946, -1, 9998, 9999, 10000, -1, 9997, 9946, 9979, -1, 9998, 10000, 10001, -1, 9998, 10001, 10002, -1, 9996, 9978, 9955, -1, 10003, 10004, 9985, -1, 10005, 9989, 9969, -1, 10003, 9985, 9984, -1, 10005, 9969, 9992, -1, 10006, 9999, 9998, -1, 10007, 9930, 9988, -1, 10008, 9983, 9981, -1, 10007, 9956, 9930, -1, 10008, 9961, 9994, -1, 10008, 10009, 9983, -1, 10008, 9981, 9961, -1, 10010, 9987, 9995, -1, 10011, 10012, 10013, -1, 10010, 9994, 9987, -1, 10011, 10013, 9999, -1, 10011, 9999, 10006, -1, 10014, 9992, 9978, -1, 10014, 9978, 9996, -1, 10015, 10002, 10016, -1, 10014, 10005, 9992, -1, 10017, 9988, 9991, -1, 10018, 9952, 9993, -1, 10015, 9998, 10002, -1, 10019, 9989, 10005, -1, 10018, 9979, 9952, -1, 10019, 9995, 9989, -1, 10020, 10012, 10011, -1, 10021, 10008, 9994, -1, 10021, 9994, 10010, -1, 10021, 10009, 10008, -1, 10022, 9998, 10015, -1, 10022, 10006, 9998, -1, 10023, 9991, 9970, -1, 10023, 9970, 9997, -1, 10024, 10016, 10025, -1, 9871, 10005, 10014, -1, 10026, 10010, 9995, -1, 10024, 10015, 10016, -1, 10026, 9995, 10019, -1, 10027, 10004, 10003, -1, 10027, 9840, 10004, -1, 9870, 10019, 10005, -1, 10028, 10029, 10030, -1, 9870, 10005, 9871, -1, 10028, 10030, 10012, -1, 10031, 9984, 9956, -1, 10028, 10012, 10020, -1, 10031, 9956, 10007, -1, 10032, 10021, 10010, -1, 10032, 10010, 10026, -1, 10033, 10006, 10022, -1, 10032, 10009, 10021, -1, 10032, 9975, 10009, -1, 10033, 10011, 10006, -1, 10034, 10022, 10015, -1, 9911, 10026, 10019, -1, 9911, 10019, 9870, -1, 10035, 10007, 9988, -1, 10035, 10031, 10007, -1, 10034, 10015, 10024, -1, 9974, 10026, 9911, -1, 10035, 9988, 10017, -1, 9974, 10032, 10026, -1, 9974, 9975, 10032, -1, 10036, 9997, 9979, -1, 10037, 10024, 10025, -1, 10036, 9979, 10018, -1, 10038, 10029, 10028, -1, 10039, 10040, 10041, -1, 10042, 10020, 10011, -1, 10043, 10044, 10045, -1, 10046, 9991, 10023, -1, 10042, 10011, 10033, -1, 10047, 10040, 10039, -1, 10046, 10017, 9991, -1, 10047, 10045, 10048, -1, 10049, 9840, 10027, -1, 10047, 10039, 10050, -1, 10047, 10043, 10045, -1, 10047, 10050, 10043, -1, 10047, 10051, 10040, -1, 10052, 10053, 10051, -1, 10049, 9892, 9840, -1, 10054, 10033, 10022, -1, 10052, 10048, 10055, -1, 10056, 10057, 10058, -1, 10054, 10022, 10034, -1, 10052, 10047, 10048, -1, 10059, 10034, 10024, -1, 10056, 10058, 10060, -1, 10052, 10051, 10047, -1, 10061, 10062, 10053, -1, 10059, 10024, 10037, -1, 10061, 10055, 9854, -1, 10061, 10053, 10052, -1, 10061, 10052, 10055, -1, 10063, 9984, 10031, -1, 10064, 10061, 9854, -1, 10065, 10066, 10029, -1, 10064, 10062, 10061, -1, 10063, 10003, 9984, -1, 10067, 10031, 10035, -1, 10065, 10029, 10038, -1, 10068, 9948, 9920, -1, 10069, 10020, 10042, -1, 10070, 10023, 9997, -1, 10069, 10028, 10020, -1, 10070, 9997, 10036, -1, 10071, 10042, 10033, -1, 10072, 10057, 10073, -1, 10071, 10033, 10054, -1, 10074, 9948, 10068, -1, 10074, 10072, 10073, -1, 10041, 10025, 10075, -1, 10074, 10076, 10072, -1, 10074, 9973, 9948, -1, 10074, 10073, 10077, -1, 10041, 10037, 10025, -1, 10074, 10068, 10076, -1, 10078, 10035, 10017, -1, 10079, 10074, 10077, -1, 10078, 10017, 10046, -1, 10079, 9993, 9973, -1, 10079, 10077, 10080, -1, 10081, 10034, 10059, -1, 10081, 10054, 10034, -1, 10079, 9973, 10074, -1, 10082, 10079, 10080, -1, 10082, 9993, 10079, -1, 10082, 10080, 10083, -1, 10084, 9892, 10049, -1, 10085, 10086, 10087, -1, 10085, 10087, 10066, -1, 10082, 10018, 9993, -1, 10085, 10066, 10065, -1, 10084, 9894, 9892, -1, 10088, 10018, 10082, -1, 10088, 10082, 10083, -1, 10089, 10038, 10028, -1, 10090, 10057, 10056, -1, 10090, 10073, 10057, -1, 10091, 10003, 10063, -1, 10089, 10028, 10069, -1, 10092, 9820, 10093, -1, 10091, 10027, 10003, -1, 10094, 10069, 10042, -1, 10095, 10063, 10031, -1, 10094, 10042, 10071, -1, 10095, 10091, 10063, -1, 10095, 10031, 10067, -1, 10096, 10046, 10023, -1, 10040, 10037, 10041, -1, 10096, 10023, 10070, -1, 10040, 10059, 10037, -1, 10097, 10098, 10099, -1, 10100, 9820, 10092, -1, 10100, 9817, 9820, -1, 10101, 10071, 10054, -1, 10100, 10092, 10102, -1, 10100, 10102, 10097, -1, 10101, 10054, 10081, -1, 10100, 10097, 10099, -1, 10100, 10099, 10103, -1, 10104, 10086, 10085, -1, 10105, 10100, 10103, -1, 10105, 9881, 9817, -1, 10105, 9817, 10100, -1, 10105, 10103, 10106, -1, 10107, 10105, 10106, -1, 10108, 10067, 10035, -1, 10108, 10035, 10078, -1, 10107, 9907, 9881, -1, 10109, 10065, 10038, -1, 10107, 9881, 10105, -1, 10107, 10106, 10110, -1, 10109, 10038, 10089, -1, 10111, 9949, 9929, -1, 10112, 9907, 10107, -1, 10111, 9929, 9894, -1, 10111, 9894, 10084, -1, 10111, 10113, 9949, -1, 10112, 10107, 10110, -1, 10114, 10077, 10073, -1, 10115, 10089, 10069, -1, 10116, 10039, 10041, -1, 10115, 10069, 10094, -1, 10116, 10041, 10075, -1, 10051, 10081, 10059, -1, 10117, 10116, 10075, -1, 10051, 10059, 10040, -1, 10114, 10073, 10090, -1, 10118, 10049, 10027, -1, 10119, 10117, 10075, -1, 10118, 10027, 10091, -1, 10119, 10043, 10050, -1, 10120, 10071, 10101, -1, 10121, 10117, 10119, -1, 10120, 10094, 10071, -1, 10121, 10119, 10050, -1, 10121, 10039, 10116, -1, 10121, 10050, 10039, -1, 10121, 10116, 10117, -1, 10122, 10123, 10044, -1, 10122, 10075, 10123, -1, 10124, 10125, 10126, -1, 10122, 10119, 10075, -1, 10124, 10126, 10086, -1, 10122, 10043, 10119, -1, 10127, 10091, 10095, -1, 10122, 10044, 10043, -1, 10124, 10086, 10104, -1, 10128, 10078, 10046, -1, 10129, 10130, 10131, -1, 10129, 10131, 10062, -1, 10129, 10062, 10064, -1, 10128, 10046, 10096, -1, 10132, 10060, 10133, -1, 10134, 10085, 10065, -1, 10134, 10065, 10109, -1, 10135, 10129, 10064, -1, 10136, 9856, 9899, -1, 10137, 10109, 10089, -1, 10132, 10056, 10060, -1, 10136, 10135, 10064, -1, 10136, 10064, 9854, -1, 10137, 10089, 10115, -1, 10136, 9854, 9856, -1, 10138, 9920, 9921, -1, 10138, 10068, 9920, -1, 10053, 10081, 10051, -1, 10053, 10101, 10081, -1, 10139, 10138, 9921, -1, 10140, 10095, 10067, -1, 10140, 10067, 10108, -1, 10141, 10072, 10076, -1, 10141, 10139, 9921, -1, 10142, 10068, 10138, -1, 10142, 10138, 10139, -1, 10142, 10139, 10141, -1, 10143, 10094, 10120, -1, 10142, 10141, 10076, -1, 10144, 10080, 10077, -1, 10142, 10076, 10068, -1, 10144, 10077, 10114, -1, 10145, 10058, 10057, -1, 10145, 9921, 10058, -1, 10145, 10072, 10141, -1, 10145, 10141, 9921, -1, 10143, 10115, 10094, -1, 10145, 10057, 10072, -1, 10146, 10018, 10088, -1, 10147, 10049, 10118, -1, 10148, 10125, 10124, -1, 10146, 10070, 10036, -1, 10146, 10036, 10018, -1, 10147, 10084, 10049, -1, 10149, 10085, 10134, -1, 10150, 10146, 10088, -1, 10151, 10118, 10091, -1, 10151, 10091, 10127, -1, 10149, 10104, 10085, -1, 10152, 10088, 10083, -1, 10152, 10150, 10088, -1, 10153, 10109, 10137, -1, 10152, 10154, 10155, -1, 10156, 10108, 10078, -1, 10152, 10083, 10154, -1, 10157, 10092, 10093, -1, 10156, 10078, 10128, -1, 10153, 10134, 10109, -1, 10157, 10102, 10092, -1, 10158, 10090, 10056, -1, 10062, 10101, 10053, -1, 10157, 10093, 10159, -1, 10160, 10159, 10161, -1, 10160, 10102, 10157, -1, 10062, 10120, 10101, -1, 10160, 10157, 10159, -1, 10162, 10098, 10097, -1, 10158, 10056, 10132, -1, 10162, 10097, 10102, -1, 10162, 10102, 10160, -1, 10162, 10161, 10098, -1, 10162, 10160, 10161, -1, 10163, 9932, 9907, -1, 10164, 10137, 10115, -1, 10163, 9907, 10112, -1, 10163, 9951, 9932, -1, 10164, 10115, 10143, -1, 10165, 10095, 10140, -1, 10166, 10163, 10112, -1, 10165, 10127, 10095, -1, 10167, 10168, 10169, -1, 10167, 10169, 10125, -1, 10170, 10112, 10110, -1, 10170, 10171, 10172, -1, 10173, 10132, 10133, -1, 10170, 10110, 10171, -1, 10170, 10166, 10112, -1, 10173, 10133, 10174, -1, 10167, 10125, 10148, -1, 10175, 10176, 10130, -1, 10177, 10124, 10104, -1, 10175, 10130, 10129, -1, 10177, 10104, 10149, -1, 10175, 10129, 10135, -1, 10178, 10080, 10144, -1, 10178, 10083, 10080, -1, 10179, 10134, 10153, -1, 10180, 10175, 10135, -1, 10181, 10182, 10113, -1, 10179, 10149, 10134, -1, 10181, 10111, 10084, -1, 10131, 10143, 10120, -1, 10183, 9899, 9931, -1, 10181, 10113, 10111, -1, 10183, 10180, 10135, -1, 10183, 10135, 10136, -1, 10131, 10120, 10062, -1, 10183, 10136, 9899, -1, 10181, 10084, 10147, -1, 10184, 10147, 10118, -1, 10185, 10070, 10146, -1, 10185, 10146, 10150, -1, 10184, 10118, 10151, -1, 10185, 10096, 10070, -1, 10186, 10185, 10150, -1, 10187, 10108, 10156, -1, 10187, 10165, 10140, -1, 10187, 10140, 10108, -1, 10188, 10137, 10164, -1, 10189, 10155, 10190, -1, 10189, 10186, 10150, -1, 10189, 10150, 10152, -1, 10189, 10152, 10155, -1, 10188, 10153, 10137, -1, 10191, 9972, 9951, -1, 10191, 9951, 10163, -1, 10192, 10114, 10090, -1, 10193, 10168, 10167, -1, 10192, 10090, 10158, -1, 10191, 10163, 10166, -1, 10194, 10191, 10166, -1, 10195, 10044, 10123, -1, 10195, 10123, 10196, -1, 10197, 10172, 10198, -1, 10199, 10127, 10165, -1, 10200, 10148, 10124, -1, 10197, 10194, 10166, -1, 10197, 10170, 10172, -1, 10197, 10166, 10170, -1, 10200, 10124, 10177, -1, 10199, 10151, 10127, -1, 10201, 10176, 10175, -1, 10202, 10158, 10132, -1, 10201, 10203, 10176, -1, 10202, 10132, 10173, -1, 10204, 10177, 10149, -1, 10201, 10175, 10180, -1, 10204, 10149, 10179, -1, 10205, 10180, 10183, -1, 10205, 10183, 9931, -1, 10130, 10164, 10143, -1, 10205, 9931, 9957, -1, 10130, 10143, 10131, -1, 10206, 10096, 10185, -1, 10207, 10173, 10174, -1, 10206, 10185, 10186, -1, 10206, 10128, 10096, -1, 10208, 10083, 10178, -1, 10209, 10186, 10189, -1, 10209, 10190, 9842, -1, 10209, 10189, 10190, -1, 10210, 9990, 9972, -1, 10208, 10154, 10083, -1, 10211, 10181, 10147, -1, 10210, 9972, 10191, -1, 10210, 10191, 10194, -1, 10212, 10179, 10153, -1, 10211, 10182, 10181, -1, 10211, 10147, 10184, -1, 10213, 10197, 10198, -1, 10213, 10194, 10197, -1, 9852, 10165, 10187, -1, 10212, 10153, 10188, -1, 10214, 10215, 10216, -1, 10214, 10216, 10168, -1, 10213, 10198, 10217, -1, 10214, 10168, 10193, -1, 10218, 10114, 10192, -1, 10219, 10203, 10201, -1, 10219, 10220, 10203, -1, 10221, 10180, 10205, -1, 10222, 10044, 10195, -1, 10221, 10201, 10180, -1, 10218, 10144, 10114, -1, 10222, 10045, 10044, -1, 10221, 10219, 10201, -1, 10223, 10167, 10148, -1, 10223, 10148, 10200, -1, 10224, 10219, 10221, -1, 10225, 10224, 10221, -1, 10226, 10184, 10151, -1, 10227, 10200, 10177, -1, 10225, 10221, 10205, -1, 10226, 10151, 10199, -1, 10227, 10177, 10204, -1, 10228, 9957, 9985, -1, 10176, 10188, 10164, -1, 10228, 10205, 9957, -1, 10229, 10158, 10202, -1, 10228, 10225, 10205, -1, 10176, 10164, 10130, -1, 10230, 10128, 10206, -1, 10229, 10192, 10158, -1, 10230, 10156, 10128, -1, 9819, 10173, 10207, -1, 10231, 10186, 10209, -1, 9819, 10202, 10173, -1, 10231, 10230, 10206, -1, 10231, 10206, 10186, -1, 10232, 10179, 10212, -1, 10233, 10230, 10231, -1, 10232, 10204, 10179, -1, 10234, 10154, 10208, -1, 10234, 10155, 10154, -1, 10235, 10236, 10215, -1, 10235, 10215, 10214, -1, 10237, 10231, 10209, -1, 10235, 10238, 10236, -1, 10237, 10233, 10231, -1, 9851, 10199, 10165, -1, 10239, 9842, 9845, -1, 9851, 10165, 9852, -1, 9877, 10048, 10045, -1, 10239, 10237, 10209, -1, 10239, 10209, 9842, -1, 9877, 10045, 10222, -1, 10240, 9996, 9990, -1, 10240, 9990, 10210, -1, 9811, 10178, 10144, -1, 9811, 10144, 10218, -1, 10241, 10193, 10167, -1, 10242, 10194, 10213, -1, 9811, 10208, 10178, -1, 10241, 10167, 10223, -1, 10242, 10210, 10194, -1, 10242, 10240, 10210, -1, 9823, 10223, 10200, -1, 9823, 10200, 10227, -1, 10203, 10188, 10176, -1, 10243, 10211, 10184, -1, 10244, 10240, 10242, -1, 10243, 10184, 10226, -1, 10243, 10182, 10211, -1, 10203, 10212, 10188, -1, 10243, 9959, 10182, -1, 9828, 10218, 10192, -1, 9828, 10192, 10229, -1, 10245, 10242, 10213, -1, 9834, 10196, 10246, -1, 10245, 10244, 10242, -1, 10247, 10217, 10248, -1, 10247, 10213, 10217, -1, 9834, 10195, 10196, -1, 10247, 10245, 10213, -1, 10249, 10220, 10219, -1, 10093, 10207, 10174, -1, 10249, 10224, 10225, -1, 10093, 10174, 10159, -1, 10249, 10219, 10224, -1, 10250, 9985, 10004, -1, 10250, 10228, 9985, -1, 10250, 10225, 10228, -1, 9818, 10202, 9819, -1, 10250, 10249, 10225, -1, 10251, 10227, 10204, -1, 10252, 10156, 10230, -1, 10251, 10204, 10232, -1, 10252, 10230, 10233, -1, 9818, 10229, 10202, -1, 10252, 10233, 10237, -1, 9865, 10190, 10155, -1, 9882, 10055, 10048, -1, 9882, 10048, 9877, -1, 10253, 9845, 9889, -1, 10253, 10239, 9845, -1, 10253, 10237, 10239, -1, 10253, 10252, 10237, -1, 9865, 10155, 10234, -1, 9897, 10226, 10199, -1, 9807, 9996, 10240, -1, 9867, 10193, 10241, -1, 9897, 10199, 9851, -1, 9807, 10240, 10244, -1, 9867, 10214, 10193, -1, 9822, 10241, 10223, -1, 9807, 10244, 10245, -1, 9808, 9807, 10245, -1, 9808, 10248, 9815, -1, 9822, 10223, 9823, -1, 9808, 10247, 10248, -1, 9808, 10245, 10247, -1, 9831, 9826, 9872, -1, 9810, 10208, 9811, -1, 10220, 10212, 10203, -1, 9831, 10220, 10249, -1, 9831, 9872, 10220, -1, 10220, 10232, 10212, -1, 9844, 10195, 9834, -1, 9844, 10222, 10195, -1, 9832, 9831, 10249, -1, 9838, 10218, 9828, -1, 9838, 9811, 10218, -1, 10254, 10249, 10250, -1, 9837, 9832, 10249, -1, 9820, 10207, 10093, -1, 9820, 9819, 10207, -1, 9837, 10249, 10254, -1, 9839, 10254, 10250, -1, 9830, 9823, 10227, -1, 9839, 9837, 10254, -1, 9839, 10250, 10004, -1, 9839, 10004, 9840, -1, 9849, 9852, 10187, -1, 9829, 9828, 10229, -1, 9830, 10227, 10251, -1, 9835, 10246, 9847, -1, 9849, 10156, 10252, -1, 9849, 10187, 10156, -1, 9835, 9834, 10246, -1, 9855, 10055, 9882, -1, 9829, 10229, 9818, -1, 9855, 9854, 10055, -1, 9850, 9849, 10252, -1, 9843, 9842, 10190, -1, 9863, 10235, 10214, -1, 9863, 10238, 10235, -1, 9843, 10190, 9865, -1, 9960, 10243, 10226, -1, 9863, 9862, 10238, -1, 10255, 10252, 10253, -1, 9863, 10214, 9867, -1, 9960, 10226, 9897, -1, 9960, 9959, 10243, -1, 9868, 10241, 9822, -1, 9858, 10252, 10255, -1, 9858, 9850, 10252, -1, 9866, 9865, 10234, -1, 9868, 9867, 10241, -1, 9859, 10255, 10253, -1, 9859, 9858, 10255, -1, 9872, 10251, 10232, -1, 9859, 10253, 9889, -1, 9859, 9889, 9860, -1, 9873, 10014, 9996, -1, 9872, 9830, 10251, -1, 9873, 9996, 9807, -1, 9866, 10234, 10208, -1, 9866, 10208, 9810, -1, 9872, 10232, 10220, -1, 9873, 9871, 10014, -1, 9878, 9877, 10222, -1, 9813, 9873, 9807, -1, 9809, 9811, 9838, -1, 9878, 10222, 9844, -1, 10256, 10257, 10258, -1, 10258, 10257, 10259, -1, 10259, 10260, 10261, -1, 10257, 10260, 10259, -1, 10261, 10262, 10263, -1, 10260, 10262, 10261, -1, 10263, 10264, 10265, -1, 10262, 10264, 10263, -1, 10265, 10266, 10267, -1, 10264, 10266, 10265, -1, 10267, 10268, 10269, -1, 10266, 10268, 10267, -1, 10269, 10270, 10271, -1, 10268, 10270, 10269, -1, 10272, 10273, 10274, -1, 10274, 10273, 10275, -1, 10275, 10276, 10277, -1, 10273, 10276, 10275, -1, 10277, 10278, 10279, -1, 10276, 10278, 10277, -1, 10279, 10280, 10281, -1, 10278, 10280, 10279, -1, 10281, 10282, 10283, -1, 10280, 10282, 10281, -1, 10283, 10284, 10285, -1, 10282, 10284, 10283, -1, 10285, 10286, 10287, -1, 10284, 10286, 10285, -1, 10288, 9713, 10289, -1, 10288, 10290, 9713, -1, 10291, 10289, 10292, -1, 10291, 10288, 10289, -1, 10293, 10292, 10294, -1, 10293, 10291, 10292, -1, 10295, 10294, 10296, -1, 10295, 10293, 10294, -1, 10297, 10296, 10298, -1, 10297, 10295, 10296, -1, 10299, 10298, 10300, -1, 10299, 10297, 10298, -1, 10301, 10300, 10302, -1, 10301, 10299, 10300, -1, 10303, 10302, 10304, -1, 10303, 10301, 10302, -1, 10305, 10304, 10306, -1, 10305, 10303, 10304, -1, 10307, 10306, 10308, -1, 10307, 10305, 10306, -1, 10309, 10308, 10310, -1, 10309, 10307, 10308, -1, 10311, 10310, 10312, -1, 10311, 10309, 10310, -1, 10313, 10312, 10314, -1, 10313, 10311, 10312, -1, 10315, 10314, 10316, -1, 10315, 10313, 10314, -1, 10317, 10316, 10318, -1, 10317, 10315, 10316, -1, 10319, 10318, 9531, -1, 10319, 10317, 10318, -1, 10320, 10319, 9531, -1, 9373, 10161, 10321, -1, 10322, 10321, 10323, -1, 10322, 9373, 10321, -1, 10324, 10323, 10325, -1, 10324, 10322, 10323, -1, 10326, 10324, 10325, -1, 10327, 10325, 10328, -1, 10327, 10326, 10325, -1, 10329, 10328, 10330, -1, 10329, 10327, 10328, -1, 10331, 10330, 10332, -1, 10331, 10329, 10330, -1, 10333, 10332, 10334, -1, 10333, 10331, 10332, -1, 10335, 10334, 10336, -1, 10335, 10333, 10334, -1, 10337, 10336, 10338, -1, 10337, 10335, 10336, -1, 10339, 10338, 10340, -1, 10339, 10337, 10338, -1, 10341, 10340, 10342, -1, 10341, 10339, 10340, -1, 10343, 10342, 10344, -1, 10343, 10341, 10342, -1, 10345, 10344, 10346, -1, 10345, 10343, 10344, -1, 10347, 10346, 10348, -1, 10347, 10345, 10346, -1, 10349, 10348, 10350, -1, 10349, 10347, 10348, -1, 9786, 10349, 10350, -1, 9786, 10350, 9977, -1, 10001, 10351, 10352, -1, 10353, 10352, 10354, -1, 10353, 10001, 10352, -1, 10355, 10354, 10356, -1, 10355, 10353, 10354, -1, 10357, 10356, 10358, -1, 10357, 10355, 10356, -1, 10359, 10358, 10360, -1, 10359, 10357, 10358, -1, 10361, 10360, 10362, -1, 10361, 10359, 10360, -1, 10363, 10362, 10364, -1, 10363, 10361, 10362, -1, 10365, 10364, 10366, -1, 10365, 10363, 10364, -1, 10367, 10366, 10368, -1, 10367, 10365, 10366, -1, 10369, 10368, 10370, -1, 10369, 10367, 10368, -1, 10371, 10370, 10372, -1, 10371, 10369, 10370, -1, 10373, 10372, 10374, -1, 10373, 10371, 10372, -1, 10375, 10374, 10376, -1, 10375, 10373, 10374, -1, 10377, 10376, 10378, -1, 10377, 10375, 10376, -1, 10379, 10378, 10380, -1, 10379, 10377, 10378, -1, 10381, 10380, 10382, -1, 10381, 10379, 10380, -1, 10236, 10381, 10382, -1, 10236, 10382, 10383, -1, 10236, 10383, 10384, -1, 10215, 10384, 10385, -1, 10215, 10236, 10384, -1, 10216, 10385, 10386, -1, 10216, 10215, 10385, -1, 10168, 10386, 10387, -1, 10168, 10216, 10386, -1, 10169, 10387, 10388, -1, 10169, 10168, 10387, -1, 10125, 10388, 10389, -1, 10125, 10169, 10388, -1, 10126, 10389, 10390, -1, 10126, 10125, 10389, -1, 10086, 10390, 10391, -1, 10086, 10126, 10390, -1, 10087, 10391, 10392, -1, 10087, 10086, 10391, -1, 10066, 10392, 10393, -1, 10066, 10087, 10392, -1, 10029, 10393, 10394, -1, 10029, 10066, 10393, -1, 10030, 10394, 10395, -1, 10030, 10029, 10394, -1, 10012, 10395, 10396, -1, 10012, 10030, 10395, -1, 10013, 10396, 10397, -1, 10013, 10012, 10396, -1, 9999, 10397, 10398, -1, 9999, 10013, 10397, -1, 10000, 10398, 10399, -1, 10000, 9999, 10398, -1, 10001, 10000, 10399, -1, 10001, 10399, 10351, -1, 10400, 10401, 10402, -1, 10400, 10402, 10403, -1, 10404, 10405, 10406, -1, 10407, 10408, 10409, -1, 10404, 10410, 10405, -1, 10404, 10411, 10412, -1, 10404, 10412, 10410, -1, 10413, 10414, 10415, -1, 10407, 10416, 10408, -1, 10413, 10417, 10414, -1, 10418, 10419, 10420, -1, 10413, 10421, 10417, -1, 10418, 10420, 10422, -1, 10423, 9921, 9847, -1, 10423, 9847, 10424, -1, 10423, 10424, 10425, -1, 10423, 10425, 10426, -1, 10427, 10428, 10429, -1, 10430, 10421, 10413, -1, 10431, 10421, 10430, -1, 10427, 10429, 10432, -1, 10427, 10409, 10428, -1, 10433, 10434, 10421, -1, 10433, 10421, 10431, -1, 10435, 10436, 10437, -1, 10435, 10438, 10436, -1, 10439, 10434, 10433, -1, 10439, 10433, 10431, -1, 10439, 10344, 10342, -1, 10439, 10342, 10434, -1, 10440, 10441, 10442, -1, 10443, 10422, 10444, -1, 10440, 10442, 10445, -1, 10443, 10444, 10446, -1, 10440, 10445, 10447, -1, 10448, 10432, 10449, -1, 10450, 10182, 9959, -1, 10451, 10452, 10453, -1, 10451, 10454, 10452, -1, 10448, 10449, 10455, -1, 10450, 10446, 10182, -1, 10456, 10457, 10458, -1, 10451, 10453, 10441, -1, 10451, 10441, 10440, -1, 10456, 10459, 10457, -1, 10460, 10461, 10462, -1, 10463, 10464, 10465, -1, 10466, 10455, 10467, -1, 10460, 10468, 10469, -1, 10463, 10470, 10464, -1, 10471, 10025, 10016, -1, 10460, 10462, 10468, -1, 10471, 10016, 10472, -1, 10473, 10461, 10460, -1, 10471, 10472, 10474, -1, 10471, 10474, 10475, -1, 10473, 10406, 10461, -1, 10473, 10404, 10406, -1, 10466, 10467, 10476, -1, 10473, 10411, 10404, -1, 10477, 10416, 10407, -1, 10478, 10435, 10437, -1, 10478, 10401, 10400, -1, 10478, 10437, 10401, -1, 10479, 10415, 10456, -1, 10479, 10430, 10413, -1, 10477, 10480, 10416, -1, 10481, 10482, 10419, -1, 10479, 10413, 10415, -1, 10481, 10419, 10418, -1, 10483, 10431, 10430, -1, 10484, 10409, 10427, -1, 10483, 10439, 10431, -1, 10483, 10344, 10439, -1, 10483, 10430, 10479, -1, 10485, 10440, 10447, -1, 10485, 10447, 10486, -1, 10487, 10432, 10448, -1, 10488, 10475, 10438, -1, 10489, 10490, 10451, -1, 10488, 10438, 10435, -1, 10489, 10451, 10440, -1, 10489, 10440, 10485, -1, 10489, 10485, 10490, -1, 10487, 10427, 10432, -1, 10491, 10422, 10443, -1, 10415, 10459, 10456, -1, 10491, 10418, 10422, -1, 10492, 10451, 10490, -1, 10493, 10494, 10495, -1, 10493, 10451, 10492, -1, 10415, 10476, 10459, -1, 10493, 10454, 10451, -1, 10496, 10455, 10466, -1, 10493, 10495, 10454, -1, 10497, 10443, 10446, -1, 10497, 10446, 10450, -1, 10498, 10469, 10499, -1, 10498, 10460, 10469, -1, 10496, 10448, 10455, -1, 10500, 10501, 10470, -1, 10500, 10470, 10463, -1, 10502, 10480, 10477, -1, 10503, 10473, 10460, -1, 10503, 10460, 10498, -1, 10502, 10504, 10480, -1, 10503, 10505, 10473, -1, 10503, 10498, 10505, -1, 10506, 10435, 10478, -1, 10507, 10409, 10484, -1, 10508, 10482, 10481, -1, 10508, 10465, 10482, -1, 10509, 10473, 10505, -1, 10510, 10511, 10512, -1, 10507, 10407, 10409, -1, 10510, 10411, 10473, -1, 10507, 10477, 10407, -1, 10510, 10512, 10411, -1, 10510, 10473, 10509, -1, 10513, 10479, 10456, -1, 10513, 10456, 10458, -1, 10514, 10427, 10487, -1, 10515, 10025, 10471, -1, 10515, 10471, 10475, -1, 10516, 10483, 10479, -1, 10515, 10475, 10488, -1, 10516, 10479, 10513, -1, 10514, 10484, 10427, -1, 10516, 10513, 10517, -1, 10414, 10466, 10476, -1, 10516, 10517, 10483, -1, 10518, 10418, 10491, -1, 10518, 10481, 10418, -1, 10414, 10476, 10415, -1, 10519, 10483, 10517, -1, 10520, 10487, 10448, -1, 10521, 10346, 10344, -1, 10520, 10448, 10496, -1, 10522, 10450, 9959, -1, 10521, 10348, 10346, -1, 10521, 10344, 10483, -1, 10521, 10483, 10519, -1, 10523, 10485, 10486, -1, 10524, 10491, 10443, -1, 10523, 10490, 10485, -1, 10523, 10492, 10490, -1, 10524, 10443, 10497, -1, 10525, 10494, 10493, -1, 10526, 10504, 10502, -1, 10525, 10527, 10494, -1, 10525, 10492, 10523, -1, 10526, 10528, 10504, -1, 10529, 10501, 10500, -1, 10525, 10493, 10492, -1, 10529, 10530, 10501, -1, 10531, 10435, 10506, -1, 10532, 10498, 10499, -1, 10533, 10477, 10507, -1, 10532, 10509, 10505, -1, 10532, 10505, 10498, -1, 10531, 10488, 10435, -1, 10534, 10509, 10532, -1, 10534, 10511, 10510, -1, 10534, 10510, 10509, -1, 10534, 10535, 10511, -1, 10536, 10507, 10484, -1, 10537, 10463, 10465, -1, 10538, 10519, 10517, -1, 10536, 10484, 10514, -1, 10537, 10465, 10508, -1, 10538, 10513, 10458, -1, 10538, 10517, 10513, -1, 10539, 10519, 10538, -1, 10417, 10466, 10414, -1, 10539, 10350, 10348, -1, 10539, 10521, 10519, -1, 10539, 10348, 10521, -1, 10540, 10523, 10486, -1, 10540, 10541, 9914, -1, 10417, 10496, 10466, -1, 10542, 10508, 10481, -1, 10543, 10514, 10487, -1, 10542, 10481, 10518, -1, 10540, 10486, 10541, -1, 10544, 10540, 9914, -1, 10543, 10487, 10520, -1, 10544, 9914, 9949, -1, 10499, 10450, 10522, -1, 10544, 10523, 10540, -1, 10545, 10523, 10544, -1, 10499, 10497, 10450, -1, 10545, 10544, 9949, -1, 10546, 10528, 10526, -1, 10547, 10525, 10523, -1, 10546, 10548, 10528, -1, 10547, 10523, 10545, -1, 10549, 10518, 10491, -1, 10550, 10525, 10547, -1, 10550, 10545, 9949, -1, 10551, 10502, 10477, -1, 10549, 10491, 10524, -1, 10550, 10547, 10545, -1, 10550, 9949, 10527, -1, 10550, 10527, 10525, -1, 10552, 10499, 10522, -1, 10551, 10477, 10533, -1, 10552, 10522, 9959, -1, 10553, 10530, 10529, -1, 10553, 10554, 10530, -1, 10552, 10532, 10499, -1, 10555, 10533, 10507, -1, 10556, 10075, 10025, -1, 10555, 10507, 10536, -1, 10556, 10025, 10515, -1, 10557, 10552, 9959, -1, 10557, 9959, 9963, -1, 10556, 10488, 10531, -1, 10557, 10532, 10552, -1, 10556, 10515, 10488, -1, 10558, 10463, 10537, -1, 10559, 10532, 10557, -1, 10559, 10557, 9963, -1, 10560, 10520, 10496, -1, 10560, 10496, 10417, -1, 10561, 10532, 10559, -1, 10558, 10500, 10463, -1, 10561, 10534, 10532, -1, 10562, 9963, 10535, -1, 10562, 10535, 10534, -1, 10562, 10559, 9963, -1, 10563, 10536, 10514, -1, 10562, 10534, 10561, -1, 10563, 10514, 10543, -1, 10562, 10561, 10559, -1, 10564, 10538, 10458, -1, 10565, 10548, 10546, -1, 10564, 10566, 9975, -1, 10564, 10458, 10566, -1, 10565, 10567, 10548, -1, 10568, 10537, 10508, -1, 10569, 10538, 10564, -1, 10568, 10508, 10542, -1, 10569, 9975, 9977, -1, 10569, 10564, 9975, -1, 10469, 10524, 10497, -1, 10570, 10546, 10526, -1, 10469, 10497, 10499, -1, 10571, 10538, 10569, -1, 10570, 10526, 10502, -1, 10571, 10569, 9977, -1, 10570, 10502, 10551, -1, 10572, 10542, 10518, -1, 10573, 10538, 10571, -1, 10574, 10551, 10533, -1, 10572, 10518, 10549, -1, 10573, 10539, 10538, -1, 10575, 10350, 10539, -1, 10575, 9977, 10350, -1, 10574, 10533, 10555, -1, 10575, 10571, 9977, -1, 10575, 10539, 10573, -1, 10575, 10573, 10571, -1, 10576, 10577, 10554, -1, 10578, 10520, 10560, -1, 10578, 10543, 10520, -1, 10576, 10554, 10553, -1, 10579, 10529, 10500, -1, 10580, 10536, 10563, -1, 10580, 10555, 10536, -1, 10579, 10500, 10558, -1, 10581, 10060, 10058, -1, 10581, 10058, 10582, -1, 10581, 10582, 10567, -1, 10581, 10567, 10565, -1, 10583, 10558, 10537, -1, 10583, 10537, 10568, -1, 10584, 10546, 10570, -1, 10585, 10381, 10236, -1, 10585, 10236, 10238, -1, 10586, 10570, 10551, -1, 10583, 10579, 10558, -1, 10586, 10551, 10574, -1, 10587, 10381, 10585, -1, 10468, 10524, 10469, -1, 10468, 10549, 10524, -1, 10588, 10543, 10578, -1, 10587, 10379, 10381, -1, 10588, 10563, 10543, -1, 10589, 10555, 10580, -1, 10589, 10574, 10555, -1, 10590, 10568, 10542, -1, 10591, 10377, 10379, -1, 10590, 10542, 10572, -1, 10591, 10379, 10587, -1, 10592, 10593, 10577, -1, 10594, 10585, 10238, -1, 10595, 10546, 10584, -1, 10592, 10577, 10576, -1, 10594, 10238, 9862, -1, 10595, 10565, 10546, -1, 10596, 10584, 10570, -1, 10596, 10570, 10586, -1, 10597, 10553, 10529, -1, 10598, 10580, 10563, -1, 10597, 10529, 10579, -1, 10598, 10563, 10588, -1, 10599, 10375, 10377, -1, 10599, 10377, 10591, -1, 10600, 10585, 10594, -1, 10601, 10586, 10574, -1, 10600, 10587, 10585, -1, 10601, 10574, 10589, -1, 10602, 10579, 10583, -1, 10603, 10594, 9862, -1, 10604, 10060, 10581, -1, 10604, 10133, 10060, -1, 10604, 10581, 10565, -1, 10604, 10565, 10595, -1, 10605, 10572, 10549, -1, 10605, 10549, 10468, -1, 10606, 10373, 10375, -1, 10607, 10595, 10584, -1, 10607, 10584, 10596, -1, 10606, 10375, 10599, -1, 10608, 10580, 10598, -1, 10609, 10587, 10600, -1, 10608, 10589, 10580, -1, 10610, 10596, 10586, -1, 10609, 10591, 10587, -1, 10610, 10586, 10601, -1, 10611, 10600, 10594, -1, 10612, 10568, 10590, -1, 10612, 10583, 10568, -1, 10611, 10594, 10603, -1, 10613, 10174, 10133, -1, 10613, 10133, 10604, -1, 10614, 10593, 10592, -1, 10613, 10604, 10595, -1, 10615, 9862, 9914, -1, 10613, 10595, 10607, -1, 10614, 10616, 10593, -1, 10615, 10603, 9862, -1, 10617, 10610, 10601, -1, 10618, 10373, 10606, -1, 10617, 10589, 10608, -1, 10617, 10601, 10589, -1, 10619, 10576, 10553, -1, 10618, 10371, 10373, -1, 10620, 10596, 10610, -1, 10619, 10553, 10597, -1, 10620, 10607, 10596, -1, 10621, 10599, 10591, -1, 10622, 10610, 10617, -1, 10623, 10619, 10597, -1, 10621, 10591, 10609, -1, 10624, 10613, 10607, -1, 10623, 10597, 10579, -1, 10623, 10579, 10602, -1, 10624, 10607, 10620, -1, 10624, 10174, 10613, -1, 10625, 10620, 10610, -1, 10625, 10610, 10622, -1, 10626, 10600, 10611, -1, 10627, 10572, 10605, -1, 10626, 10609, 10600, -1, 10627, 10590, 10572, -1, 10628, 10611, 10603, -1, 10629, 10159, 10174, -1, 10628, 10603, 10615, -1, 10629, 10174, 10624, -1, 10629, 10624, 10620, -1, 10629, 10620, 10625, -1, 10630, 10369, 10371, -1, 10630, 10371, 10618, -1, 10631, 10583, 10612, -1, 10632, 10633, 10593, -1, 10632, 10593, 10616, -1, 10631, 10602, 10583, -1, 10634, 10616, 10614, -1, 10635, 10599, 10621, -1, 10632, 10400, 10633, -1, 10632, 10478, 10400, -1, 10635, 10606, 10599, -1, 10636, 10506, 10478, -1, 10636, 10616, 10637, -1, 10634, 10637, 10616, -1, 10636, 10478, 10632, -1, 10636, 10632, 10616, -1, 10638, 10535, 9963, -1, 10639, 10609, 10626, -1, 10640, 10531, 10506, -1, 10638, 9963, 9983, -1, 10639, 10621, 10609, -1, 10640, 10506, 10636, -1, 10640, 10636, 10637, -1, 10541, 10615, 9914, -1, 10641, 10592, 10576, -1, 10640, 10637, 10642, -1, 10641, 10576, 10619, -1, 10643, 10556, 10531, -1, 10643, 10531, 10640, -1, 10644, 10611, 10628, -1, 10644, 10626, 10611, -1, 10645, 10643, 10640, -1, 10646, 10619, 10623, -1, 10647, 10642, 10648, -1, 10649, 10612, 10590, -1, 10647, 10640, 10642, -1, 10650, 10367, 10369, -1, 10647, 10645, 10640, -1, 10650, 10369, 10630, -1, 10649, 10590, 10627, -1, 10651, 10618, 10606, -1, 10652, 10653, 10654, -1, 10651, 10606, 10635, -1, 10652, 10655, 10504, -1, 10652, 10504, 10528, -1, 10656, 10621, 10639, -1, 10652, 10654, 10655, -1, 10657, 10653, 10652, -1, 10656, 10635, 10621, -1, 10657, 10658, 10653, -1, 10657, 10528, 10548, -1, 10486, 10615, 10541, -1, 10657, 10652, 10528, -1, 10659, 10602, 10631, -1, 10660, 10658, 10657, -1, 10660, 10548, 10567, -1, 10486, 10628, 10615, -1, 10659, 10623, 10602, -1, 10660, 10426, 10658, -1, 10660, 10657, 10548, -1, 10661, 10637, 10634, -1, 10662, 10423, 10426, -1, 10661, 10642, 10637, -1, 10663, 10626, 10644, -1, 10663, 10639, 10626, -1, 10662, 10426, 10660, -1, 10664, 10662, 10660, -1, 10665, 10535, 10638, -1, 10666, 10365, 10367, -1, 10665, 10511, 10535, -1, 10667, 10660, 10567, -1, 10668, 10592, 10641, -1, 10666, 10367, 10650, -1, 10667, 10664, 10660, -1, 10669, 10630, 10618, -1, 10667, 10567, 10582, -1, 10668, 10614, 10592, -1, 10670, 10641, 10619, -1, 10669, 10618, 10651, -1, 10670, 10619, 10646, -1, 10671, 10608, 10672, -1, 10673, 10651, 10635, -1, 10671, 10330, 10328, -1, 10673, 10635, 10656, -1, 10671, 10617, 10608, -1, 10674, 10612, 10649, -1, 10671, 10672, 10330, -1, 10675, 10671, 10328, -1, 10675, 10617, 10671, -1, 10674, 10631, 10612, -1, 10447, 10644, 10628, -1, 10675, 10328, 10325, -1, 10447, 10628, 10486, -1, 10675, 10622, 10617, -1, 10676, 10622, 10675, -1, 10676, 10325, 10323, -1, 10676, 10625, 10622, -1, 10677, 10639, 10663, -1, 10676, 10675, 10325, -1, 10677, 10656, 10639, -1, 10678, 10625, 10676, -1, 10679, 10646, 10623, -1, 10678, 10629, 10625, -1, 10680, 10365, 10666, -1, 10679, 10623, 10659, -1, 10681, 10678, 10676, -1, 10680, 10363, 10365, -1, 10682, 10196, 10123, -1, 10682, 10648, 10642, -1, 10682, 10642, 10661, -1, 10683, 10681, 10676, -1, 10682, 10123, 10648, -1, 10684, 10511, 10665, -1, 10683, 10323, 10321, -1, 10684, 10512, 10511, -1, 10683, 10676, 10323, -1, 10685, 10650, 10630, -1, 10685, 10630, 10669, -1, 10686, 10403, 10687, -1, 10686, 10400, 10403, -1, 10686, 10633, 10400, -1, 10688, 10651, 10673, -1, 10689, 10634, 10614, -1, 10688, 10669, 10651, -1, 10690, 10633, 10686, -1, 10689, 10614, 10668, -1, 10691, 10554, 10577, -1, 10691, 10577, 10593, -1, 10691, 10633, 10690, -1, 10692, 10641, 10670, -1, 10691, 10593, 10633, -1, 10445, 10663, 10644, -1, 10445, 10644, 10447, -1, 10693, 10075, 10556, -1, 10693, 10556, 10643, -1, 10692, 10668, 10641, -1, 10692, 10689, 10668, -1, 10693, 10643, 10645, -1, 10694, 10123, 10075, -1, 10695, 10659, 10631, -1, 10694, 10693, 10645, -1, 10695, 10631, 10674, -1, 10696, 10656, 10677, -1, 10694, 10075, 10693, -1, 10697, 9983, 10009, -1, 10698, 10123, 10694, -1, 10698, 10694, 10645, -1, 10696, 10673, 10656, -1, 10698, 10648, 10123, -1, 10698, 10647, 10648, -1, 10698, 10645, 10647, -1, 10699, 10700, 10695, -1, 10701, 10363, 10680, -1, 10697, 10638, 9983, -1, 10699, 10654, 10700, -1, 10701, 10361, 10363, -1, 10699, 10655, 10654, -1, 10702, 10655, 10699, -1, 10703, 10650, 10685, -1, 10704, 10655, 10702, -1, 10703, 10666, 10650, -1, 10704, 10416, 10480, -1, 10704, 10504, 10655, -1, 10705, 10646, 10679, -1, 10704, 10480, 10504, -1, 10705, 10670, 10646, -1, 10706, 10423, 10662, -1, 10707, 10411, 10512, -1, 10708, 10669, 10688, -1, 10706, 10662, 10664, -1, 10708, 10685, 10669, -1, 10706, 9921, 10423, -1, 10709, 10058, 9921, -1, 10707, 10512, 10684, -1, 10710, 10663, 10445, -1, 10709, 10706, 10664, -1, 10709, 9921, 10706, -1, 10711, 10058, 10709, -1, 10711, 10664, 10667, -1, 10711, 10667, 10582, -1, 10712, 10634, 10689, -1, 10710, 10677, 10663, -1, 10711, 10582, 10058, -1, 10712, 10661, 10634, -1, 10711, 10709, 10664, -1, 10713, 10598, 10588, -1, 10713, 10672, 10608, -1, 10713, 10608, 10598, -1, 10714, 10689, 10692, -1, 10715, 10672, 10713, -1, 10716, 10673, 10696, -1, 10700, 10679, 10659, -1, 10717, 10672, 10715, -1, 10716, 10688, 10673, -1, 10717, 10332, 10330, -1, 10700, 10659, 10695, -1, 10717, 10334, 10332, -1, 10717, 10330, 10672, -1, 10718, 10359, 10361, -1, 10718, 10361, 10701, -1, 10719, 10629, 10678, -1, 10720, 10665, 10638, -1, 10719, 10159, 10629, -1, 10721, 10678, 10681, -1, 10720, 10638, 10697, -1, 10722, 10680, 10666, -1, 10721, 10719, 10678, -1, 10722, 10666, 10703, -1, 10723, 10159, 10719, -1, 10724, 10703, 10685, -1, 10723, 10719, 10721, -1, 10724, 10685, 10708, -1, 10725, 10681, 10683, -1, 10725, 10159, 10723, -1, 10725, 10721, 10681, -1, 10726, 10692, 10670, -1, 10725, 10723, 10721, -1, 10727, 10161, 10159, -1, 10728, 10696, 10677, -1, 10727, 10683, 10321, -1, 10727, 10321, 10161, -1, 10726, 10670, 10705, -1, 10727, 10159, 10725, -1, 10727, 10725, 10683, -1, 10729, 10687, 10730, -1, 10729, 10686, 10687, -1, 10728, 10677, 10710, -1, 10729, 10690, 10686, -1, 10731, 10697, 10009, -1, 10732, 10690, 10729, -1, 10733, 10412, 10411, -1, 10734, 10690, 10732, -1, 10733, 10411, 10707, -1, 10734, 10691, 10690, -1, 10735, 10246, 10196, -1, 10736, 10708, 10688, -1, 10734, 10530, 10554, -1, 10736, 10688, 10716, -1, 10734, 10554, 10691, -1, 10735, 10682, 10661, -1, 10735, 10196, 10682, -1, 10737, 10699, 10695, -1, 10735, 10661, 10712, -1, 10737, 10695, 10674, -1, 10738, 10357, 10359, -1, 10738, 10359, 10718, -1, 10737, 10702, 10699, -1, 10739, 10712, 10689, -1, 10740, 10702, 10737, -1, 10739, 10689, 10714, -1, 10741, 9949, 10113, -1, 10741, 10527, 9949, -1, 10742, 10702, 10740, -1, 10654, 10705, 10679, -1, 10742, 10416, 10704, -1, 10654, 10679, 10700, -1, 10742, 10408, 10416, -1, 10742, 10704, 10702, -1, 10743, 10684, 10665, -1, 10744, 10588, 10578, -1, 10745, 10680, 10722, -1, 10744, 10713, 10588, -1, 10745, 10701, 10680, -1, 10744, 10715, 10713, -1, 10746, 10703, 10724, -1, 10747, 10715, 10744, -1, 10743, 10665, 10720, -1, 10746, 10722, 10703, -1, 10748, 10717, 10715, -1, 10749, 10716, 10696, -1, 10748, 10336, 10334, -1, 10748, 10715, 10747, -1, 10748, 10334, 10717, -1, 10749, 10696, 10728, -1, 10750, 10729, 10730, -1, 10750, 10730, 10749, -1, 10751, 10692, 10726, -1, 10751, 10714, 10692, -1, 10750, 10732, 10729, -1, 10752, 10720, 10697, -1, 10752, 10697, 10731, -1, 10753, 10530, 10734, -1, 10753, 10501, 10530, -1, 10753, 10734, 10732, -1, 10754, 10737, 10674, -1, 10755, 10724, 10708, -1, 10754, 10740, 10737, -1, 10756, 10731, 10009, -1, 10755, 10708, 10736, -1, 10754, 10674, 10649, -1, 10756, 10009, 9975, -1, 10757, 10357, 10738, -1, 10758, 10408, 10742, -1, 10758, 10742, 10740, -1, 10757, 10355, 10357, -1, 10429, 10412, 10733, -1, 10758, 10759, 10408, -1, 10420, 10494, 10527, -1, 10760, 10578, 10560, -1, 10760, 10744, 10578, -1, 10429, 10761, 10412, -1, 10420, 10527, 10741, -1, 10760, 10747, 10744, -1, 10762, 9847, 10246, -1, 10762, 10735, 10712, -1, 10763, 10748, 10747, -1, 10762, 10712, 10739, -1, 10763, 10336, 10748, -1, 10762, 10246, 10735, -1, 10763, 10338, 10336, -1, 10653, 10726, 10705, -1, 10764, 10718, 10701, -1, 10764, 10701, 10745, -1, 10653, 10705, 10654, -1, 10765, 10749, 10728, -1, 10653, 10751, 10726, -1, 10765, 10750, 10749, -1, 10766, 10684, 10743, -1, 10767, 10745, 10722, -1, 10767, 10722, 10746, -1, 10766, 10707, 10684, -1, 10768, 10765, 10769, -1, 10768, 10732, 10750, -1, 10730, 10736, 10716, -1, 10768, 10753, 10732, -1, 10730, 10716, 10749, -1, 10768, 10750, 10765, -1, 10770, 10768, 10769, -1, 10770, 10753, 10768, -1, 10771, 10470, 10501, -1, 10425, 10714, 10751, -1, 10771, 10753, 10770, -1, 10402, 10724, 10755, -1, 10771, 10501, 10753, -1, 10402, 10746, 10724, -1, 10425, 10739, 10714, -1, 10772, 10754, 10649, -1, 10773, 10743, 10720, -1, 10772, 10649, 10627, -1, 10773, 10720, 10752, -1, 10774, 10002, 10001, -1, 10774, 10001, 10353, -1, 10774, 10353, 10355, -1, 10774, 10355, 10757, -1, 10457, 10731, 10756, -1, 10457, 10752, 10731, -1, 10419, 10495, 10494, -1, 10775, 10754, 10772, -1, 10419, 10494, 10420, -1, 10775, 10740, 10754, -1, 10775, 10772, 10776, -1, 10775, 10758, 10740, -1, 10428, 10759, 10761, -1, 10777, 10758, 10775, -1, 10777, 10775, 10776, -1, 10778, 10738, 10718, -1, 10778, 10718, 10764, -1, 10779, 10761, 10759, -1, 10428, 10761, 10429, -1, 10779, 10759, 10758, -1, 10779, 10758, 10777, -1, 10780, 10760, 10560, -1, 10658, 10751, 10653, -1, 10436, 10764, 10745, -1, 10436, 10745, 10767, -1, 10780, 10560, 10417, -1, 10449, 10707, 10766, -1, 10687, 10755, 10736, -1, 10687, 10736, 10730, -1, 10781, 10760, 10780, -1, 10781, 10780, 10782, -1, 10449, 10733, 10707, -1, 10781, 10747, 10760, -1, 10781, 10763, 10747, -1, 10444, 10113, 10182, -1, 10444, 10741, 10113, -1, 10783, 10781, 10782, -1, 10783, 10763, 10781, -1, 10784, 10338, 10763, -1, 10784, 10340, 10338, -1, 10424, 9847, 10762, -1, 10784, 10763, 10783, -1, 10424, 10762, 10739, -1, 10785, 10769, 10765, -1, 10424, 10739, 10425, -1, 10785, 10770, 10769, -1, 10467, 10766, 10743, -1, 10467, 10743, 10773, -1, 10401, 10767, 10746, -1, 10785, 10765, 10728, -1, 10401, 10746, 10402, -1, 10786, 10770, 10785, -1, 10786, 10470, 10771, -1, 10786, 10771, 10770, -1, 10786, 10464, 10470, -1, 10566, 10756, 9975, -1, 10482, 10495, 10419, -1, 10787, 10777, 10776, -1, 10787, 10772, 10627, -1, 10482, 10454, 10495, -1, 10787, 10776, 10772, -1, 10459, 10773, 10752, -1, 10459, 10752, 10457, -1, 10410, 10761, 10779, -1, 10474, 10738, 10778, -1, 10410, 10777, 10787, -1, 10410, 10779, 10777, -1, 10474, 10757, 10738, -1, 10410, 10412, 10761, -1, 10438, 10778, 10764, -1, 10421, 10782, 10780, -1, 10438, 10764, 10436, -1, 10409, 10408, 10759, -1, 10421, 10780, 10417, -1, 10409, 10759, 10428, -1, 10421, 10783, 10782, -1, 10403, 10755, 10687, -1, 10434, 10342, 10340, -1, 10434, 10340, 10784, -1, 10403, 10402, 10755, -1, 10434, 10784, 10783, -1, 10434, 10783, 10421, -1, 10426, 10425, 10751, -1, 10442, 10710, 10445, -1, 10426, 10751, 10658, -1, 10422, 10741, 10444, -1, 10442, 10728, 10710, -1, 10432, 10429, 10733, -1, 10442, 10785, 10728, -1, 10432, 10733, 10449, -1, 10422, 10420, 10741, -1, 10441, 10785, 10442, -1, 10453, 10785, 10441, -1, 10437, 10436, 10767, -1, 10788, 10785, 10453, -1, 10788, 10786, 10785, -1, 10437, 10767, 10401, -1, 10446, 10444, 10182, -1, 10452, 10788, 10453, -1, 10455, 10449, 10766, -1, 10452, 10786, 10788, -1, 10452, 10464, 10786, -1, 10452, 10454, 10464, -1, 10462, 10787, 10627, -1, 10455, 10766, 10467, -1, 10462, 10627, 10605, -1, 10465, 10454, 10482, -1, 10462, 10605, 10468, -1, 10458, 10756, 10566, -1, 10465, 10464, 10454, -1, 10472, 10016, 10002, -1, 10472, 10757, 10474, -1, 10461, 10787, 10462, -1, 10472, 10774, 10757, -1, 10458, 10457, 10756, -1, 10472, 10002, 10774, -1, 10475, 10778, 10438, -1, 10406, 10787, 10461, -1, 10475, 10474, 10778, -1, 10405, 10787, 10406, -1, 10476, 10467, 10773, -1, 10405, 10410, 10787, -1, 10476, 10773, 10459, -1, 9787, 9786, 9977, -1, 9787, 9977, 9942, -1, 9766, 9942, 9924, -1, 9766, 9787, 9942, -1, 9742, 9924, 9923, -1, 9742, 9766, 9924, -1, 9718, 9923, 9816, -1, 9718, 9742, 9923, -1, 9697, 9816, 9815, -1, 9697, 9718, 9816, -1, 9674, 9815, 10248, -1, 9674, 9697, 9815, -1, 9635, 10248, 10217, -1, 9635, 9674, 10248, -1, 9636, 10217, 10198, -1, 9636, 9635, 10217, -1, 9614, 10198, 10172, -1, 9614, 9636, 10198, -1, 9590, 10172, 10171, -1, 9590, 9614, 10172, -1, 9579, 10171, 10110, -1, 9579, 9590, 10171, -1, 9570, 10110, 10106, -1, 9570, 9579, 10110, -1, 9561, 10106, 10103, -1, 9561, 9570, 10106, -1, 9554, 10103, 10099, -1, 9554, 9561, 10103, -1, 9372, 10099, 10098, -1, 9372, 10098, 10161, -1, 9372, 9554, 10099, -1, 9373, 9372, 10161, -1, 10789, 10790, 10791, -1, 10792, 10793, 10794, -1, 10795, 10796, 10797, -1, 10792, 10794, 10798, -1, 10795, 10799, 10796, -1, 10795, 10800, 10801, -1, 10789, 10791, 10802, -1, 10795, 10801, 10799, -1, 10803, 10804, 10805, -1, 10806, 10807, 10808, -1, 10803, 10809, 10804, -1, 10803, 10810, 10809, -1, 10811, 9394, 10812, -1, 10811, 9478, 9394, -1, 10813, 10810, 10803, -1, 10811, 10812, 10814, -1, 10806, 10808, 10815, -1, 10811, 10814, 10816, -1, 10817, 10810, 10813, -1, 10818, 10819, 10820, -1, 10821, 10810, 10817, -1, 10818, 10820, 10822, -1, 10821, 10823, 10810, -1, 10824, 10825, 10826, -1, 10827, 10821, 10817, -1, 10827, 10823, 10821, -1, 10824, 10826, 10828, -1, 10827, 10312, 10310, -1, 10827, 10310, 10823, -1, 10829, 10815, 10830, -1, 10831, 10832, 10833, -1, 10829, 10830, 10834, -1, 10831, 10833, 10835, -1, 10836, 10822, 10837, -1, 10831, 10838, 10832, -1, 10836, 10818, 10822, -1, 10839, 9733, 9514, -1, 10840, 10841, 10838, -1, 10836, 10837, 10842, -1, 10839, 10834, 9733, -1, 10840, 10843, 10841, -1, 10840, 10838, 10831, -1, 10840, 10844, 10843, -1, 10845, 10846, 10847, -1, 10848, 10797, 10849, -1, 10850, 10851, 10852, -1, 10850, 10852, 10853, -1, 10854, 10855, 10856, -1, 10845, 10847, 10857, -1, 10848, 10858, 10859, -1, 10854, 10842, 10855, -1, 10848, 10849, 10858, -1, 10860, 9576, 9564, -1, 10860, 9564, 10861, -1, 10862, 10863, 10800, -1, 10860, 10861, 10864, -1, 10862, 10795, 10797, -1, 10860, 10864, 10865, -1, 10862, 10800, 10795, -1, 10862, 10797, 10848, -1, 10866, 10793, 10792, -1, 10866, 10828, 10793, -1, 10867, 10813, 10803, -1, 10868, 10869, 10790, -1, 10867, 10803, 10805, -1, 10867, 10805, 10850, -1, 10868, 10790, 10789, -1, 10870, 10817, 10813, -1, 10871, 10807, 10806, -1, 10870, 10827, 10817, -1, 10871, 10872, 10807, -1, 10870, 10312, 10827, -1, 10873, 10819, 10818, -1, 10870, 10813, 10867, -1, 10874, 10831, 10835, -1, 10873, 10802, 10819, -1, 10874, 10875, 10876, -1, 10874, 10835, 10875, -1, 10877, 10831, 10874, -1, 10878, 10865, 10825, -1, 10878, 10825, 10824, -1, 10879, 10831, 10877, -1, 10880, 10818, 10836, -1, 10805, 10856, 10851, -1, 10881, 10840, 10831, -1, 10881, 10831, 10879, -1, 10882, 10844, 10840, -1, 10882, 10883, 10844, -1, 10884, 10815, 10829, -1, 9371, 9373, 10322, -1, 10882, 10840, 10881, -1, 10884, 10806, 10815, -1, 10882, 10881, 10879, -1, 10805, 10851, 10850, -1, 10885, 10842, 10854, -1, 10886, 10829, 10834, -1, 10887, 10859, 10888, -1, 10885, 10836, 10842, -1, 10886, 10834, 10839, -1, 10887, 10848, 10859, -1, 10887, 10888, 10889, -1, 10890, 10846, 10845, -1, 10891, 10869, 10868, -1, 10890, 10892, 10846, -1, 10893, 10848, 10887, -1, 10891, 10894, 10869, -1, 10895, 10828, 10866, -1, 10896, 10848, 10893, -1, 10895, 10824, 10828, -1, 10897, 10789, 10802, -1, 10898, 10862, 10848, -1, 10898, 10848, 10896, -1, 10899, 10900, 10863, -1, 10899, 10863, 10862, -1, 10901, 10857, 10872, -1, 10897, 10802, 10873, -1, 10899, 10862, 10898, -1, 10901, 10872, 10871, -1, 10899, 10898, 10896, -1, 10902, 10850, 10853, -1, 10902, 10867, 10850, -1, 10903, 10818, 10880, -1, 10904, 10870, 10867, -1, 10904, 10905, 10870, -1, 10906, 9576, 10860, -1, 10904, 10902, 10905, -1, 10906, 10860, 10865, -1, 10904, 10867, 10902, -1, 10907, 10870, 10905, -1, 10903, 10873, 10818, -1, 10906, 10865, 10878, -1, 10804, 10856, 10805, -1, 10908, 10871, 10806, -1, 10908, 10806, 10884, -1, 10909, 10314, 10312, -1, 10909, 10316, 10314, -1, 10804, 10854, 10856, -1, 10909, 10312, 10870, -1, 10910, 10836, 10885, -1, 10909, 10870, 10907, -1, 10910, 10880, 10836, -1, 10911, 10874, 10876, -1, 10912, 10839, 9514, -1, 10911, 10877, 10874, -1, 10911, 10876, 10913, -1, 10914, 10877, 10911, -1, 10915, 10884, 10829, -1, 10915, 10829, 10886, -1, 10916, 10894, 10891, -1, 10914, 10879, 10877, -1, 10914, 10883, 10882, -1, 10914, 10882, 10879, -1, 10916, 10917, 10894, -1, 10918, 10889, 10912, -1, 10918, 10887, 10889, -1, 10919, 10868, 10789, -1, 10920, 10921, 10892, -1, 10920, 10892, 10890, -1, 10918, 10893, 10887, -1, 10922, 10824, 10895, -1, 10919, 10789, 10897, -1, 10923, 10893, 10918, -1, 10923, 10900, 10899, -1, 10922, 10878, 10824, -1, 10923, 10896, 10893, -1, 10923, 10899, 10896, -1, 10924, 10902, 10853, -1, 10925, 10897, 10873, -1, 10925, 10873, 10903, -1, 10926, 10845, 10857, -1, 10926, 10857, 10901, -1, 10924, 10905, 10902, -1, 10924, 10907, 10905, -1, 10925, 10919, 10897, -1, 10927, 10316, 10909, -1, 10927, 10909, 10907, -1, 10927, 10318, 10316, -1, 10927, 10907, 10924, -1, 10928, 10913, 9470, -1, 10809, 10854, 10804, -1, 10928, 10911, 10913, -1, 10809, 10885, 10854, -1, 10929, 10901, 10871, -1, 10930, 10880, 10910, -1, 10931, 10928, 9470, -1, 10930, 10903, 10880, -1, 10929, 10871, 10908, -1, 10932, 10914, 10911, -1, 10932, 10928, 10931, -1, 10889, 10839, 10912, -1, 10932, 10911, 10928, -1, 10932, 10931, 10914, -1, 10933, 10914, 10931, -1, 10933, 10931, 9470, -1, 10934, 10935, 10917, -1, 10889, 10886, 10839, -1, 10933, 9470, 9506, -1, 10934, 10917, 10916, -1, 10936, 10937, 10883, -1, 10938, 10908, 10884, -1, 10936, 10914, 10933, -1, 10936, 10933, 9506, -1, 10938, 10884, 10915, -1, 10936, 9506, 10937, -1, 10936, 10883, 10914, -1, 10939, 10868, 10919, -1, 10940, 10918, 10912, -1, 10940, 10912, 9514, -1, 10941, 10921, 10920, -1, 10939, 10891, 10868, -1, 10942, 10940, 9514, -1, 10941, 10943, 10921, -1, 10944, 10919, 10925, -1, 10945, 9624, 9576, -1, 10946, 10923, 10918, -1, 10946, 10942, 10923, -1, 10945, 9576, 10906, -1, 10946, 10940, 10942, -1, 10945, 10878, 10922, -1, 10946, 10918, 10940, -1, 10945, 10906, 10878, -1, 10947, 9514, 9517, -1, 10947, 10923, 10942, -1, 10947, 10942, 9514, -1, 10948, 10845, 10926, -1, 10949, 10947, 9517, -1, 10949, 10923, 10947, -1, 10948, 10890, 10845, -1, 10949, 10900, 10923, -1, 10950, 10910, 10885, -1, 10949, 10951, 10900, -1, 10950, 10885, 10809, -1, 10949, 9517, 10951, -1, 10952, 10924, 10853, -1, 10953, 10925, 10903, -1, 10952, 10954, 9528, -1, 10953, 10903, 10930, -1, 10952, 10853, 10954, -1, 10955, 10924, 10952, -1, 10955, 9528, 9531, -1, 10956, 10935, 10934, -1, 10955, 10952, 9528, -1, 10957, 10901, 10929, -1, 10956, 10958, 10935, -1, 10957, 10926, 10901, -1, 10959, 10924, 10955, -1, 10888, 10915, 10886, -1, 10959, 10955, 9531, -1, 10960, 10916, 10891, -1, 10961, 10927, 10924, -1, 10961, 10924, 10959, -1, 10960, 10891, 10939, -1, 10962, 10318, 10927, -1, 10888, 10886, 10889, -1, 10962, 10927, 10961, -1, 10962, 9531, 10318, -1, 10962, 10959, 9531, -1, 10963, 10939, 10919, -1, 10964, 10929, 10908, -1, 10962, 10961, 10959, -1, 10963, 10919, 10944, -1, 10964, 10908, 10938, -1, 10965, 10930, 10910, -1, 10966, 10967, 10943, -1, 10965, 10910, 10950, -1, 10966, 10943, 10941, -1, 10968, 10920, 10890, -1, 10969, 10925, 10953, -1, 10968, 10890, 10948, -1, 10969, 10944, 10925, -1, 10970, 10958, 10956, -1, 10970, 9610, 9609, -1, 10970, 9609, 10971, -1, 10970, 10971, 10958, -1, 10972, 10916, 10960, -1, 10973, 10948, 10926, -1, 10974, 10349, 9786, -1, 10972, 10934, 10916, -1, 10974, 9786, 9788, -1, 10973, 10926, 10957, -1, 10975, 10960, 10939, -1, 10976, 10349, 10974, -1, 10859, 10915, 10888, -1, 10859, 10938, 10915, -1, 10976, 10347, 10349, -1, 10975, 10939, 10963, -1, 10977, 10930, 10965, -1, 10977, 10953, 10930, -1, 10978, 10963, 10944, -1, 10979, 10345, 10347, -1, 10980, 10957, 10929, -1, 10978, 10944, 10969, -1, 10980, 10973, 10957, -1, 10979, 10347, 10976, -1, 10980, 10929, 10964, -1, 10981, 10974, 9788, -1, 10981, 9788, 9415, -1, 10982, 10983, 10967, -1, 10982, 10967, 10966, -1, 10984, 10934, 10972, -1, 10984, 10956, 10934, -1, 10985, 10972, 10960, -1, 10985, 10960, 10975, -1, 10986, 10941, 10920, -1, 10985, 10984, 10972, -1, 10987, 10969, 10953, -1, 10988, 10343, 10345, -1, 10987, 10953, 10977, -1, 10988, 10345, 10979, -1, 10986, 10920, 10968, -1, 10989, 10974, 10981, -1, 10990, 10963, 10978, -1, 10989, 10976, 10974, -1, 10991, 10968, 10948, -1, 10992, 10981, 9415, -1, 10991, 10948, 10973, -1, 10990, 10975, 10963, -1, 10993, 9686, 9610, -1, 10993, 10956, 10984, -1, 10993, 10970, 10956, -1, 10994, 10938, 10859, -1, 10995, 10341, 10343, -1, 10993, 9610, 10970, -1, 10994, 10964, 10938, -1, 10995, 10343, 10988, -1, 10996, 10984, 10985, -1, 10997, 10969, 10987, -1, 10997, 10978, 10969, -1, 10998, 10976, 10989, -1, 10998, 10979, 10976, -1, 10999, 10975, 10990, -1, 11000, 10989, 10981, -1, 10999, 10985, 10975, -1, 11001, 10973, 10980, -1, 11000, 10981, 10992, -1, 11002, 9723, 9686, -1, 11002, 9686, 10993, -1, 11003, 10983, 10982, -1, 11004, 9415, 9470, -1, 11002, 10993, 10984, -1, 11003, 11005, 10983, -1, 11002, 10984, 10996, -1, 11004, 10992, 9415, -1, 11006, 10990, 10978, -1, 11007, 10341, 10995, -1, 11006, 10978, 10997, -1, 11008, 10966, 10941, -1, 11007, 10339, 10341, -1, 11008, 10941, 10986, -1, 11009, 10996, 10985, -1, 11009, 10985, 10999, -1, 11010, 10988, 10979, -1, 11011, 10999, 10990, -1, 11011, 10990, 11006, -1, 11010, 10979, 10998, -1, 11012, 10968, 10991, -1, 11013, 10996, 11009, -1, 11012, 10986, 10968, -1, 11013, 9723, 11002, -1, 11013, 11002, 10996, -1, 11014, 10989, 11000, -1, 11014, 10998, 10989, -1, 11015, 10980, 10964, -1, 11016, 11000, 10992, -1, 11015, 10964, 10994, -1, 11017, 11009, 10999, -1, 11017, 10999, 11011, -1, 11016, 10992, 11004, -1, 11018, 9710, 9723, -1, 11018, 11013, 11009, -1, 11018, 9723, 11013, -1, 11018, 11009, 11017, -1, 11019, 10337, 10339, -1, 11019, 10339, 11007, -1, 11020, 10973, 11001, -1, 11020, 10991, 10973, -1, 11021, 10988, 11010, -1, 11022, 10866, 10792, -1, 11022, 10983, 11005, -1, 11021, 10995, 10988, -1, 11022, 11023, 10983, -1, 11024, 11025, 11005, -1, 11022, 10792, 11023, -1, 11024, 11005, 11003, -1, 11026, 10895, 10866, -1, 11026, 10866, 11022, -1, 11026, 11005, 11025, -1, 11027, 10998, 11014, -1, 11026, 11022, 11005, -1, 11027, 11010, 10998, -1, 11028, 9517, 9541, -1, 11029, 10922, 10895, -1, 10913, 11004, 9470, -1, 11028, 10951, 9517, -1, 11029, 11026, 11025, -1, 11029, 11025, 11030, -1, 11031, 10982, 10966, -1, 11029, 10895, 11026, -1, 11031, 10966, 11008, -1, 11032, 11000, 11016, -1, 11033, 10945, 10922, -1, 11032, 11014, 11000, -1, 11033, 10922, 11029, -1, 11034, 11008, 10986, -1, 11034, 10986, 11012, -1, 11035, 11033, 11029, -1, 11036, 10335, 10337, -1, 11037, 11001, 10980, -1, 11038, 11030, 11039, -1, 11036, 10337, 11019, -1, 11038, 11029, 11030, -1, 11038, 11035, 11029, -1, 11037, 10980, 11015, -1, 11040, 11007, 10995, -1, 11040, 10995, 11021, -1, 11041, 11042, 11043, -1, 11044, 11010, 11027, -1, 11041, 11045, 11042, -1, 11041, 11043, 10894, -1, 11044, 11021, 11010, -1, 11041, 10894, 10917, -1, 11046, 10917, 10935, -1, 10876, 11004, 10913, -1, 11046, 11047, 11045, -1, 11048, 11012, 10991, -1, 11046, 11041, 10917, -1, 11048, 10991, 11020, -1, 11046, 11045, 11041, -1, 11048, 11034, 11012, -1, 10876, 11016, 11004, -1, 11049, 10816, 11047, -1, 11049, 11047, 11046, -1, 11049, 11046, 10935, -1, 11050, 11025, 11024, -1, 11049, 10935, 10958, -1, 11051, 11014, 11032, -1, 11051, 11027, 11014, -1, 11050, 11030, 11025, -1, 11052, 10811, 10816, -1, 11052, 10816, 11049, -1, 11053, 10951, 11028, -1, 11054, 10333, 10335, -1, 11053, 10900, 10951, -1, 11055, 11052, 11049, -1, 11054, 10335, 11036, -1, 11056, 11049, 10958, -1, 11057, 11019, 11007, -1, 11056, 11055, 11049, -1, 11056, 10958, 10971, -1, 11058, 11003, 10982, -1, 11058, 10982, 11031, -1, 11057, 11007, 11040, -1, 11059, 11040, 11021, -1, 11060, 10997, 11061, -1, 11062, 11031, 11008, -1, 11060, 11061, 10298, -1, 11062, 11008, 11034, -1, 11059, 11021, 11044, -1, 11060, 11006, 10997, -1, 11060, 10298, 10296, -1, 11063, 11001, 11037, -1, 11064, 11060, 10296, -1, 10875, 11032, 11016, -1, 11064, 11006, 11060, -1, 11063, 11020, 11001, -1, 10875, 11016, 10876, -1, 11064, 10296, 10294, -1, 11064, 11011, 11006, -1, 11065, 11011, 11064, -1, 11066, 11027, 11051, -1, 11065, 10294, 10292, -1, 11066, 11044, 11027, -1, 11065, 11064, 10294, -1, 11065, 11017, 11011, -1, 11067, 11017, 11065, -1, 11068, 11034, 11048, -1, 11067, 11018, 11017, -1, 11069, 10331, 10333, -1, 11070, 11067, 11065, -1, 11071, 9747, 9678, -1, 11069, 10333, 11054, -1, 11071, 11039, 11030, -1, 11071, 9678, 11039, -1, 11071, 11030, 11050, -1, 11072, 10863, 10900, -1, 11073, 11070, 11065, -1, 11073, 10292, 10289, -1, 11074, 11036, 11019, -1, 11073, 11065, 10292, -1, 11072, 10900, 11053, -1, 11074, 11019, 11057, -1, 11075, 10798, 11076, -1, 11075, 10792, 10798, -1, 11075, 11023, 10792, -1, 11077, 11040, 11059, -1, 11077, 11057, 11040, -1, 11078, 11023, 11075, -1, 11079, 11003, 11058, -1, 11079, 11024, 11003, -1, 11080, 10943, 10967, -1, 11080, 10967, 10983, -1, 11080, 11023, 11078, -1, 11081, 11058, 11031, -1, 10835, 11051, 11032, -1, 11080, 10983, 11023, -1, 10835, 11032, 10875, -1, 11081, 11031, 11062, -1, 11082, 9624, 10945, -1, 11082, 10945, 11033, -1, 11082, 11033, 11035, -1, 11083, 11048, 11020, -1, 11084, 9678, 9624, -1, 11083, 11020, 11063, -1, 11085, 11044, 11066, -1, 11084, 9624, 11082, -1, 11084, 11082, 11035, -1, 11086, 9541, 9565, -1, 11085, 11059, 11044, -1, 11087, 11084, 11035, -1, 11087, 11039, 9678, -1, 11087, 9678, 11084, -1, 11087, 11038, 11039, -1, 11088, 10331, 11069, -1, 11087, 11035, 11038, -1, 11086, 11028, 9541, -1, 11089, 11042, 11090, -1, 11088, 10329, 10331, -1, 11089, 11043, 11042, -1, 11089, 11090, 11083, -1, 11091, 11043, 11089, -1, 11092, 11036, 11074, -1, 11093, 10790, 10869, -1, 11094, 11062, 11034, -1, 11092, 11054, 11036, -1, 11094, 11034, 11068, -1, 11093, 11043, 11091, -1, 11093, 10869, 10894, -1, 11095, 11074, 11057, -1, 11093, 10894, 11043, -1, 11096, 10811, 11052, -1, 11097, 10800, 10863, -1, 11095, 11057, 11077, -1, 11097, 10863, 11072, -1, 11096, 11052, 11055, -1, 11096, 9478, 10811, -1, 11098, 9609, 9478, -1, 11099, 11051, 10835, -1, 11098, 9478, 11096, -1, 11098, 11096, 11055, -1, 11100, 11098, 11055, -1, 11099, 11066, 11051, -1, 11100, 11055, 11056, -1, 11100, 11056, 10971, -1, 11101, 11050, 11024, -1, 11100, 10971, 9609, -1, 11100, 9609, 11098, -1, 11101, 11024, 11079, -1, 11102, 10987, 10977, -1, 11102, 11061, 10997, -1, 11103, 11058, 11081, -1, 11103, 11079, 11058, -1, 11102, 10997, 10987, -1, 11104, 11061, 11102, -1, 11105, 11059, 11085, -1, 11090, 11048, 11083, -1, 11090, 11068, 11048, -1, 11105, 11077, 11059, -1, 11106, 10298, 11061, -1, 11106, 10300, 10298, -1, 11106, 10302, 10300, -1, 11107, 11053, 11028, -1, 11108, 10327, 10329, -1, 11106, 11061, 11104, -1, 11108, 10329, 11088, -1, 11107, 11028, 11086, -1, 11109, 11018, 11067, -1, 11109, 9710, 11018, -1, 11110, 11069, 11054, -1, 11111, 11067, 11070, -1, 11111, 11109, 11067, -1, 11110, 11054, 11092, -1, 11112, 11074, 11095, -1, 11113, 9710, 11109, -1, 11112, 11092, 11074, -1, 11113, 11109, 11111, -1, 11114, 11070, 11073, -1, 11114, 11111, 11070, -1, 11114, 9710, 11113, -1, 11115, 11062, 11094, -1, 11116, 11085, 11066, -1, 11114, 11113, 11111, -1, 11117, 9713, 9710, -1, 11115, 11081, 11062, -1, 11117, 11073, 10289, -1, 11117, 10289, 9713, -1, 11117, 9710, 11114, -1, 11117, 11114, 11073, -1, 11118, 11076, 11119, -1, 11116, 11066, 11099, -1, 11120, 11086, 9565, -1, 11118, 11078, 11075, -1, 11118, 11075, 11076, -1, 11121, 10800, 11097, -1, 11121, 10801, 10800, -1, 11122, 11078, 11118, -1, 11123, 10943, 11080, -1, 11123, 11080, 11078, -1, 11124, 11050, 11101, -1, 11125, 11095, 11077, -1, 11123, 11078, 11122, -1, 11124, 11071, 11050, -1, 11125, 11077, 11105, -1, 11123, 10921, 10943, -1, 11124, 9799, 9747, -1, 11126, 11089, 11083, -1, 11124, 9747, 11071, -1, 11127, 10326, 10327, -1, 11126, 11091, 11089, -1, 11127, 10327, 11108, -1, 11126, 11083, 11063, -1, 11128, 11101, 11079, -1, 11128, 11079, 11103, -1, 11042, 11068, 11090, -1, 11129, 9506, 9666, -1, 11129, 10937, 9506, -1, 11130, 11091, 11126, -1, 11042, 11094, 11068, -1, 11131, 10791, 10790, -1, 11132, 11088, 11069, -1, 11131, 11091, 11130, -1, 11131, 11093, 11091, -1, 11131, 10790, 11093, -1, 11133, 10977, 10965, -1, 11134, 11072, 11053, -1, 11133, 11102, 10977, -1, 11132, 11069, 11110, -1, 11133, 11104, 11102, -1, 11134, 11053, 11107, -1, 11135, 11110, 11092, -1, 11136, 11104, 11133, -1, 11135, 11092, 11112, -1, 11137, 11104, 11136, -1, 11138, 11105, 11085, -1, 11137, 10304, 10302, -1, 11137, 10302, 11106, -1, 11137, 11106, 11104, -1, 11139, 11081, 11115, -1, 11138, 11085, 11116, -1, 11139, 11128, 11103, -1, 11140, 11118, 11119, -1, 11140, 11119, 11138, -1, 11139, 11103, 11081, -1, 11140, 11122, 11118, -1, 11141, 11086, 11120, -1, 11142, 11123, 11122, -1, 11142, 10921, 11123, -1, 11142, 10892, 10921, -1, 11141, 11107, 11086, -1, 11143, 11112, 11095, -1, 11144, 11126, 11063, -1, 11145, 9565, 9528, -1, 11143, 11095, 11125, -1, 11144, 11130, 11126, -1, 11145, 11120, 9565, -1, 11144, 11063, 11037, -1, 11146, 10324, 10326, -1, 11147, 11131, 11130, -1, 11147, 10791, 11131, -1, 11146, 10326, 11127, -1, 11147, 11148, 10791, -1, 11149, 10965, 10950, -1, 10808, 10883, 10937, -1, 10820, 10801, 11121, -1, 10820, 10799, 10801, -1, 11149, 11133, 10965, -1, 10808, 10937, 11129, -1, 11149, 11136, 11133, -1, 11150, 9394, 9799, -1, 11151, 11137, 11136, -1, 11150, 11101, 11128, -1, 11151, 10304, 11137, -1, 11150, 11124, 11101, -1, 11150, 9799, 11124, -1, 11151, 10306, 10304, -1, 11045, 11094, 11042, -1, 11152, 11108, 11088, -1, 11153, 11140, 11138, -1, 11152, 11088, 11132, -1, 11045, 11115, 11094, -1, 11153, 11138, 11116, -1, 11154, 11097, 11072, -1, 11155, 11140, 11153, -1, 11154, 11072, 11134, -1, 11156, 11132, 11110, -1, 11156, 11110, 11135, -1, 11119, 11125, 11105, -1, 11119, 11105, 11138, -1, 11157, 11140, 11155, -1, 11157, 11142, 11122, -1, 11157, 11155, 11158, -1, 11157, 11122, 11140, -1, 11159, 10892, 11142, -1, 11159, 11142, 11157, -1, 11159, 11157, 11158, -1, 10814, 11128, 11139, -1, 11159, 10846, 10892, -1, 10794, 11112, 11143, -1, 11160, 11144, 11037, -1, 10794, 11135, 11112, -1, 11160, 11037, 11015, -1, 11161, 11107, 11141, -1, 11162, 11144, 11160, -1, 11163, 10322, 10324, -1, 11163, 10324, 11146, -1, 11161, 11134, 11107, -1, 11163, 9371, 10322, -1, 10852, 11120, 11145, -1, 10807, 10844, 10883, -1, 10807, 10883, 10808, -1, 11164, 11130, 11144, -1, 11164, 11147, 11130, -1, 10852, 11141, 11120, -1, 11164, 11162, 11165, -1, 11164, 11144, 11162, -1, 10819, 11148, 10799, -1, 11166, 11108, 11152, -1, 11167, 10799, 11148, -1, 11166, 11127, 11108, -1, 11167, 11147, 11164, -1, 11167, 11148, 11147, -1, 11167, 11164, 11165, -1, 10819, 10799, 10820, -1, 11168, 11149, 10950, -1, 11168, 10950, 10809, -1, 11047, 11115, 11045, -1, 10826, 11152, 11132, -1, 10826, 11132, 11156, -1, 11047, 11139, 11115, -1, 10837, 11097, 11154, -1, 11076, 11143, 11125, -1, 11169, 11151, 11136, -1, 11076, 11125, 11119, -1, 11169, 11149, 11168, -1, 11169, 11170, 11151, -1, 11169, 11168, 11170, -1, 11169, 11136, 11149, -1, 10837, 11121, 11097, -1, 10830, 9666, 9733, -1, 11171, 11151, 11170, -1, 10830, 11129, 9666, -1, 11172, 10306, 11151, -1, 11172, 10308, 10306, -1, 11172, 11151, 11171, -1, 10812, 9394, 11150, -1, 11173, 11153, 11116, -1, 10812, 11150, 11128, -1, 11173, 11116, 11099, -1, 10812, 11128, 10814, -1, 11173, 11155, 11153, -1, 10793, 11156, 11135, -1, 10793, 11135, 10794, -1, 11174, 11158, 11155, -1, 11174, 11159, 11158, -1, 10855, 11134, 11161, -1, 11174, 10846, 11159, -1, 10855, 11154, 11134, -1, 11174, 11155, 11173, -1, 10954, 11145, 9528, -1, 10872, 10844, 10807, -1, 11175, 11160, 11015, -1, 10872, 10843, 10844, -1, 11175, 11015, 10994, -1, 11175, 11162, 11160, -1, 10851, 11161, 11141, -1, 10864, 11127, 11166, -1, 10851, 11141, 10852, -1, 10796, 10799, 11167, -1, 10864, 11146, 11127, -1, 10796, 11165, 11162, -1, 10796, 11167, 11165, -1, 10796, 11162, 11175, -1, 10810, 11171, 11170, -1, 10825, 11152, 10826, -1, 10825, 11166, 11152, -1, 10810, 11170, 11168, -1, 10810, 11168, 10809, -1, 10802, 11148, 10819, -1, 10823, 10310, 10308, -1, 10798, 11143, 11076, -1, 10798, 10794, 11143, -1, 10823, 11172, 11171, -1, 10802, 10791, 11148, -1, 10823, 11171, 10810, -1, 10823, 10308, 11172, -1, 10833, 11099, 10835, -1, 10816, 10814, 11139, -1, 10816, 11139, 11047, -1, 10815, 11129, 10830, -1, 10833, 11173, 11099, -1, 10822, 10820, 11121, -1, 10815, 10808, 11129, -1, 10822, 11121, 10837, -1, 11176, 10833, 10832, -1, 11176, 11173, 10833, -1, 11176, 11174, 11173, -1, 11176, 10832, 11174, -1, 10828, 10826, 11156, -1, 10838, 11174, 10832, -1, 10828, 11156, 10793, -1, 10841, 11174, 10838, -1, 10834, 10830, 9733, -1, 10841, 10847, 10846, -1, 10842, 10837, 11154, -1, 10841, 10843, 10847, -1, 10841, 10846, 11174, -1, 10858, 10994, 10859, -1, 10857, 10847, 10843, -1, 10858, 11175, 10994, -1, 10842, 11154, 10855, -1, 10857, 10843, 10872, -1, 10853, 11145, 10954, -1, 10853, 10852, 11145, -1, 10861, 9564, 9371, -1, 10861, 11146, 10864, -1, 11177, 11175, 10858, -1, 10861, 11163, 11146, -1, 11177, 10849, 10796, -1, 10861, 9371, 11163, -1, 11177, 10858, 10849, -1, 11177, 10796, 11175, -1, 10856, 10855, 11161, -1, 10865, 11166, 10825, -1, 10797, 10796, 10849, -1, 10865, 10864, 11166, -1, 10856, 11161, 10851, -1, 11178, 10320, 9531, -1, 11178, 9531, 9496, -1, 11179, 9496, 9476, -1, 11179, 11178, 9496, -1, 11180, 9476, 9475, -1, 11180, 11179, 9476, -1, 11181, 9475, 9367, -1, 11181, 11180, 9475, -1, 11182, 9367, 9366, -1, 11182, 11181, 9367, -1, 11183, 9366, 9798, -1, 11183, 11182, 9366, -1, 11184, 9798, 9768, -1, 11184, 11183, 9798, -1, 11185, 9768, 9752, -1, 11185, 11184, 9768, -1, 11186, 9752, 9726, -1, 11186, 11185, 9752, -1, 11187, 9726, 9725, -1, 11187, 11186, 9726, -1, 11188, 9725, 9663, -1, 11188, 11187, 9725, -1, 11189, 9663, 9659, -1, 11189, 11188, 9663, -1, 11190, 9659, 9656, -1, 11190, 11189, 9659, -1, 11191, 9656, 9652, -1, 11191, 11190, 9656, -1, 11192, 9652, 9651, -1, 11192, 11191, 9652, -1, 11193, 11192, 9651, -1, 11193, 9651, 9713, -1, 10290, 11193, 9713, -1, 11194, 11195, 11196, -1, 11194, 11197, 11195, -1, 11198, 11199, 11200, -1, 11198, 11201, 11199, -1, 11202, 10398, 11203, -1, 11197, 10364, 10362, -1, 11204, 11205, 11206, -1, 10385, 11207, 10386, -1, 10386, 11207, 11201, -1, 11205, 11208, 11206, -1, 10385, 10384, 11207, -1, 11206, 11209, 11204, -1, 11206, 11210, 11198, -1, 10394, 10393, 11198, -1, 11208, 11210, 11206, -1, 11202, 10399, 10398, -1, 11211, 10399, 11212, -1, 11206, 11213, 11209, -1, 11212, 10399, 11202, -1, 11206, 10256, 11213, -1, 10270, 11197, 11214, -1, 10268, 11197, 10270, -1, 11210, 11215, 11198, -1, 10384, 10383, 11207, -1, 11214, 11197, 11216, -1, 11217, 11197, 10268, -1, 11211, 10351, 10399, -1, 11218, 10351, 11211, -1, 10393, 10392, 11198, -1, 11215, 11219, 11198, -1, 11219, 11220, 11198, -1, 11218, 10352, 10351, -1, 11221, 10352, 11222, -1, 11222, 10352, 11218, -1, 11223, 10354, 11224, -1, 10368, 11194, 10370, -1, 11224, 10354, 11221, -1, 10370, 11194, 10372, -1, 11221, 10354, 10352, -1, 10372, 11194, 10374, -1, 10374, 11194, 10376, -1, 10376, 11194, 10378, -1, 11194, 11225, 10378, -1, 10378, 11225, 10380, -1, 10380, 11225, 10382, -1, 10382, 11225, 10383, -1, 11216, 10356, 11223, -1, 10383, 11225, 11207, -1, 11197, 11194, 10368, -1, 11223, 10356, 10354, -1, 11197, 10368, 10366, -1, 11197, 10366, 10364, -1, 10256, 11217, 10257, -1, 10257, 11217, 10260, -1, 10260, 11217, 10262, -1, 10262, 11217, 10264, -1, 10264, 11217, 10266, -1, 10266, 11217, 10268, -1, 11216, 10358, 10356, -1, 11206, 11217, 10256, -1, 11197, 10358, 11216, -1, 11220, 10396, 11198, -1, 11197, 10360, 10358, -1, 10396, 10395, 11198, -1, 11220, 10397, 10396, -1, 10392, 11201, 11198, -1, 11203, 10397, 11226, -1, 10387, 11201, 10388, -1, 11226, 10397, 11220, -1, 10388, 11201, 10389, -1, 10389, 11201, 10390, -1, 10390, 11201, 10391, -1, 10391, 11201, 10392, -1, 10387, 10386, 11201, -1, 10395, 10394, 11198, -1, 11203, 10398, 10397, -1, 11197, 10362, 10360, -1, 11195, 10271, 11227, -1, 11195, 11227, 11228, -1, 11195, 11228, 11229, -1, 11195, 11230, 10269, -1, 11199, 11231, 11232, -1, 11199, 11232, 11233, -1, 11199, 11233, 11234, -1, 11199, 11234, 11235, -1, 11199, 11235, 11200, -1, 11236, 11237, 11238, -1, 11196, 11195, 11229, -1, 11196, 11229, 11239, -1, 11240, 11236, 11238, -1, 11196, 11239, 11241, -1, 11196, 11241, 11242, -1, 11196, 11242, 11243, -1, 11196, 11243, 11231, -1, 11244, 11238, 11237, -1, 11196, 11231, 11199, -1, 11245, 11238, 11200, -1, 11246, 11199, 11247, -1, 11246, 11196, 11199, -1, 11245, 11240, 11238, -1, 11248, 11238, 11244, -1, 10258, 11238, 11248, -1, 11249, 11245, 11200, -1, 11250, 11249, 11200, -1, 11251, 11250, 11200, -1, 11235, 11251, 11200, -1, 11230, 10258, 10259, -1, 11230, 10259, 10261, -1, 11230, 10261, 10263, -1, 11230, 10263, 10265, -1, 11230, 10265, 10267, -1, 11230, 10267, 10269, -1, 11230, 11238, 10258, -1, 11195, 10269, 10271, -1, 11230, 11217, 11206, -1, 11230, 11206, 11238, -1, 11225, 11246, 11247, -1, 11225, 11247, 11207, -1, 11252, 11253, 11254, -1, 11252, 11254, 11255, -1, 11256, 11257, 11258, -1, 11256, 11259, 11257, -1, 10301, 11252, 10299, -1, 11260, 11179, 11180, -1, 11261, 11262, 11263, -1, 11260, 11180, 11256, -1, 11264, 11263, 11262, -1, 11178, 11179, 11260, -1, 11265, 11262, 11261, -1, 11187, 11188, 11259, -1, 11266, 11264, 11262, -1, 11193, 11267, 11192, -1, 11268, 11262, 11265, -1, 11269, 11262, 11259, -1, 11193, 11270, 11267, -1, 11269, 11266, 11262, -1, 11252, 11271, 10286, -1, 10320, 11178, 11260, -1, 11252, 10286, 10284, -1, 11252, 11272, 11271, -1, 10290, 11270, 11193, -1, 10290, 10273, 10272, -1, 10290, 10272, 11270, -1, 11273, 11269, 11259, -1, 11186, 11187, 11259, -1, 11274, 11273, 11259, -1, 10288, 10273, 10290, -1, 10288, 10276, 10273, -1, 10288, 10278, 10276, -1, 11253, 10305, 10307, -1, 11253, 10307, 10309, -1, 11253, 10309, 10311, -1, 11253, 10311, 10313, -1, 11253, 10313, 10315, -1, 10291, 10280, 10278, -1, 10291, 10278, 10288, -1, 11275, 11253, 10315, -1, 11275, 10315, 10317, -1, 11275, 10317, 10319, -1, 11275, 10319, 10320, -1, 11275, 10320, 11260, -1, 11253, 11252, 10305, -1, 10305, 11252, 10303, -1, 10303, 11252, 10301, -1, 11272, 11276, 11271, -1, 11272, 11277, 11276, -1, 10293, 10280, 10291, -1, 11272, 11278, 11277, -1, 11272, 11279, 11278, -1, 10293, 10282, 10280, -1, 11272, 11280, 11279, -1, 10293, 10284, 10282, -1, 11272, 11281, 11280, -1, 11272, 11268, 11281, -1, 11272, 11262, 11268, -1, 10295, 11252, 10284, -1, 10295, 10284, 10293, -1, 11190, 11274, 11259, -1, 11189, 11190, 11259, -1, 11191, 11274, 11190, -1, 11191, 11282, 11274, -1, 11191, 11283, 11282, -1, 10297, 11252, 10295, -1, 11256, 11181, 11182, -1, 11256, 11182, 11183, -1, 11256, 11183, 11184, -1, 11256, 11184, 11185, -1, 11256, 11185, 11186, -1, 11256, 11186, 11259, -1, 11180, 11181, 11256, -1, 11188, 11189, 11259, -1, 11192, 11283, 11191, -1, 10299, 11252, 10297, -1, 11192, 11284, 11283, -1, 11192, 11267, 11284, -1, 11285, 11258, 11286, -1, 11287, 11258, 11285, -1, 11288, 11258, 11287, -1, 10274, 11258, 11288, -1, 11286, 11258, 11257, -1, 11258, 11254, 11289, -1, 11290, 11291, 11292, -1, 10275, 11254, 10274, -1, 10277, 11254, 10275, -1, 10279, 11254, 10277, -1, 10281, 11254, 10279, -1, 11292, 11293, 11290, -1, 10274, 11254, 11258, -1, 11255, 11254, 10281, -1, 11290, 11294, 11291, -1, 11254, 11295, 11289, -1, 11293, 11296, 11290, -1, 11290, 11297, 11294, -1, 11290, 11298, 11257, -1, 11296, 11298, 11290, -1, 11298, 11299, 11257, -1, 11299, 11300, 11257, -1, 11300, 11301, 11257, -1, 11301, 11286, 11257, -1, 11302, 11303, 11304, -1, 11305, 11303, 11302, -1, 11306, 11303, 11305, -1, 11307, 11303, 11306, -1, 11308, 11303, 11307, -1, 11309, 11303, 11308, -1, 11297, 11303, 11309, -1, 11290, 11303, 11297, -1, 11304, 11255, 10287, -1, 10283, 11255, 10281, -1, 10285, 11255, 10283, -1, 10287, 11255, 10285, -1, 11303, 11255, 11304, -1, 11295, 11275, 11260, -1, 11295, 11260, 11289, -1, 11272, 11303, 11290, -1, 11272, 11290, 11262, -1, 11271, 11276, 11304, -1, 11304, 11276, 11302, -1, 11302, 11277, 11305, -1, 11276, 11277, 11302, -1, 11305, 11278, 11306, -1, 11277, 11278, 11305, -1, 11306, 11279, 11307, -1, 11278, 11279, 11306, -1, 11307, 11280, 11308, -1, 11279, 11280, 11307, -1, 11308, 11281, 11309, -1, 11280, 11281, 11308, -1, 11309, 11268, 11297, -1, 11281, 11268, 11309, -1, 11297, 11265, 11294, -1, 11268, 11265, 11297, -1, 11294, 11261, 11291, -1, 11265, 11261, 11294, -1, 11291, 11263, 11292, -1, 11261, 11263, 11291, -1, 11292, 11264, 11293, -1, 11263, 11264, 11292, -1, 11293, 11266, 11296, -1, 11264, 11266, 11293, -1, 11296, 11269, 11298, -1, 11266, 11269, 11296, -1, 10287, 11271, 11304, -1, 10286, 11271, 10287, -1, 11273, 11274, 11299, -1, 11299, 11274, 11300, -1, 11300, 11282, 11301, -1, 11274, 11282, 11300, -1, 11301, 11283, 11286, -1, 11282, 11283, 11301, -1, 11286, 11284, 11285, -1, 11283, 11284, 11286, -1, 11285, 11267, 11287, -1, 11284, 11267, 11285, -1, 11287, 11270, 11288, -1, 11267, 11270, 11287, -1, 11288, 10272, 10274, -1, 11270, 10272, 11288, -1, 11298, 11273, 11299, -1, 11269, 11273, 11298, -1, 11215, 11210, 11249, -1, 11249, 11210, 11245, -1, 11245, 11208, 11240, -1, 11210, 11208, 11245, -1, 11240, 11205, 11236, -1, 11208, 11205, 11240, -1, 11236, 11204, 11237, -1, 11205, 11204, 11236, -1, 11237, 11209, 11244, -1, 11204, 11209, 11237, -1, 11244, 11213, 11248, -1, 11209, 11213, 11244, -1, 11248, 10256, 10258, -1, 11213, 10256, 11248, -1, 11250, 11215, 11249, -1, 11219, 11215, 11250, -1, 11214, 11216, 11227, -1, 11227, 11216, 11228, -1, 11228, 11223, 11229, -1, 11216, 11223, 11228, -1, 11229, 11224, 11239, -1, 11223, 11224, 11229, -1, 11239, 11221, 11241, -1, 11224, 11221, 11239, -1, 11241, 11222, 11242, -1, 11221, 11222, 11241, -1, 11242, 11218, 11243, -1, 11222, 11218, 11242, -1, 11243, 11211, 11231, -1, 11218, 11211, 11243, -1, 11231, 11212, 11232, -1, 11211, 11212, 11231, -1, 11232, 11202, 11233, -1, 11212, 11202, 11232, -1, 11233, 11203, 11234, -1, 11202, 11203, 11233, -1, 11234, 11226, 11235, -1, 11203, 11226, 11234, -1, 11235, 11220, 11251, -1, 11226, 11220, 11235, -1, 11251, 11219, 11250, -1, 11220, 11219, 11251, -1, 10271, 11214, 11227, -1, 10270, 11214, 10271, -1, 11194, 11196, 11225, -1, 11225, 11196, 11246, -1, 11217, 11230, 11197, -1, 11197, 11230, 11195, -1, 11198, 11200, 11206, -1, 11206, 11200, 11238, -1, 11207, 11247, 11201, -1, 11201, 11247, 11199, -1, 11275, 11295, 11253, -1, 11253, 11295, 11254, -1, 11256, 11258, 11260, -1, 11260, 11258, 11289, -1, 11262, 11290, 11259, -1, 11259, 11290, 11257, -1, 11252, 11255, 11272, -1, 11272, 11255, 11303, -1, 11310, 11311, 11312, -1, 11312, 11311, 11313, -1, 11313, 11314, 11315, -1, 11311, 11314, 11313, -1, 11315, 11316, 11317, -1, 11314, 11316, 11315, -1, 11317, 11318, 11319, -1, 11316, 11318, 11317, -1, 11319, 11320, 11321, -1, 11318, 11320, 11319, -1, 11321, 11322, 11323, -1, 11320, 11322, 11321, -1, 11323, 11324, 11325, -1, 11322, 11324, 11323, -1, 11325, 11326, 11327, -1, 11324, 11326, 11325, -1, 11327, 11328, 11329, -1, 11326, 11328, 11327, -1, 11329, 11330, 11331, -1, 11328, 11330, 11329, -1, 11331, 11332, 11333, -1, 11330, 11332, 11331, -1, 11333, 11334, 11335, -1, 11332, 11334, 11333, -1, 11335, 11336, 11337, -1, 11334, 11336, 11335, -1, 11338, 11339, 11340, -1, 11340, 11339, 11341, -1, 11341, 11342, 11343, -1, 11339, 11342, 11341, -1, 11343, 11344, 11345, -1, 11342, 11344, 11343, -1, 11345, 11346, 11347, -1, 11344, 11346, 11345, -1, 11347, 11348, 11349, -1, 11346, 11348, 11347, -1, 11349, 11350, 11351, -1, 11348, 11350, 11349, -1, 11351, 11352, 11353, -1, 11350, 11352, 11351, -1, 11353, 11354, 11355, -1, 11352, 11354, 11353, -1, 11355, 11356, 11357, -1, 11354, 11356, 11355, -1, 11357, 11358, 11359, -1, 11356, 11358, 11357, -1, 11359, 11360, 11361, -1, 11358, 11360, 11359, -1, 11361, 11362, 11363, -1, 11360, 11362, 11361, -1, 11363, 11364, 11365, -1, 11362, 11364, 11363, -1, 11366, 11320, 11318, -1, 11314, 11311, 11367, -1, 11367, 11311, 11368, -1, 11368, 11311, 11338, -1, 11366, 11322, 11320, -1, 11369, 11346, 11344, -1, 11344, 11342, 11369, -1, 11370, 11322, 11366, -1, 11369, 11348, 11346, -1, 11338, 11310, 11369, -1, 11311, 11310, 11338, -1, 11342, 11339, 11369, -1, 11370, 11324, 11322, -1, 11369, 11350, 11348, -1, 11371, 11324, 11370, -1, 11339, 11338, 11369, -1, 11372, 11352, 11369, -1, 11369, 11352, 11350, -1, 11371, 11326, 11324, -1, 11373, 11326, 11371, -1, 11372, 11354, 11352, -1, 11374, 11328, 11373, -1, 11373, 11328, 11326, -1, 11372, 11356, 11354, -1, 11375, 11330, 11376, -1, 11376, 11330, 11374, -1, 11374, 11330, 11328, -1, 11372, 11358, 11356, -1, 11372, 11360, 11358, -1, 11375, 11332, 11330, -1, 11377, 11334, 11375, -1, 11372, 11362, 11360, -1, 11375, 11334, 11332, -1, 11372, 11364, 11362, -1, 11378, 11379, 11380, -1, 11380, 11379, 11381, -1, 11381, 11379, 11382, -1, 11382, 11379, 11383, -1, 11383, 11379, 11384, -1, 11384, 11379, 11310, -1, 11310, 11379, 11369, -1, 11336, 11385, 11386, -1, 11386, 11385, 11387, -1, 11387, 11385, 11388, -1, 11388, 11385, 11389, -1, 11389, 11385, 11390, -1, 11390, 11385, 11391, -1, 11391, 11385, 11378, -1, 11378, 11385, 11379, -1, 11372, 11385, 11364, -1, 11364, 11385, 11377, -1, 11366, 11318, 11392, -1, 11377, 11385, 11334, -1, 11392, 11318, 11393, -1, 11334, 11385, 11336, -1, 11393, 11318, 11316, -1, 11393, 11314, 11367, -1, 11316, 11314, 11393, -1, 11394, 11395, 11396, -1, 11396, 11395, 11397, -1, 11398, 11399, 11400, -1, 11399, 11401, 11400, -1, 11402, 11403, 11404, -1, 11405, 11403, 11402, -1, 11406, 11405, 11402, -1, 11407, 11405, 11406, -1, 11408, 11407, 11406, -1, 11409, 11407, 11408, -1, 11319, 11410, 11411, -1, 11315, 11412, 11313, -1, 11413, 11412, 11315, -1, 11321, 11414, 11410, -1, 11323, 11414, 11321, -1, 11415, 11416, 11417, -1, 11417, 11418, 11415, -1, 11415, 11419, 11416, -1, 11325, 11420, 11323, -1, 11418, 11421, 11415, -1, 11323, 11420, 11414, -1, 11415, 11422, 11419, -1, 11327, 11423, 11325, -1, 11421, 11312, 11415, -1, 11325, 11423, 11420, -1, 11424, 11425, 11415, -1, 11415, 11425, 11422, -1, 11312, 11313, 11415, -1, 11329, 11426, 11327, -1, 11331, 11426, 11329, -1, 11424, 11427, 11425, -1, 11327, 11426, 11423, -1, 11331, 11428, 11426, -1, 11333, 11428, 11331, -1, 11424, 11429, 11427, -1, 11424, 11430, 11429, -1, 11335, 11431, 11333, -1, 11333, 11431, 11428, -1, 11424, 11432, 11430, -1, 11335, 11433, 11431, -1, 11424, 11434, 11432, -1, 11424, 11337, 11434, -1, 11424, 11335, 11337, -1, 11412, 11435, 11313, -1, 11340, 11435, 11412, -1, 11341, 11435, 11340, -1, 11343, 11435, 11341, -1, 11345, 11435, 11343, -1, 11347, 11435, 11345, -1, 11349, 11435, 11347, -1, 11351, 11435, 11349, -1, 11353, 11435, 11351, -1, 11317, 11436, 11315, -1, 11313, 11435, 11415, -1, 11433, 11437, 11365, -1, 11355, 11437, 11353, -1, 11357, 11437, 11355, -1, 11359, 11437, 11357, -1, 11317, 11411, 11436, -1, 11361, 11437, 11359, -1, 11363, 11437, 11361, -1, 11365, 11437, 11363, -1, 11319, 11411, 11317, -1, 11353, 11437, 11435, -1, 11424, 11437, 11335, -1, 11335, 11437, 11433, -1, 11436, 11413, 11315, -1, 11321, 11410, 11319, -1, 11438, 11439, 11440, -1, 11441, 11439, 11438, -1, 11442, 11441, 11438, -1, 11443, 11441, 11442, -1, 11444, 11443, 11442, -1, 11445, 11443, 11444, -1, 11446, 11447, 11448, -1, 11449, 11447, 11446, -1, 11450, 11451, 11452, -1, 11453, 11451, 11450, -1, 11401, 11405, 11454, -1, 11399, 11405, 11401, -1, 11403, 11405, 11399, -1, 11437, 11407, 11409, -1, 11405, 11407, 11454, -1, 11424, 11441, 11437, -1, 11439, 11441, 11424, -1, 11437, 11441, 11407, -1, 11447, 11443, 11445, -1, 11447, 11449, 11443, -1, 11443, 11455, 11441, -1, 11449, 11455, 11443, -1, 11455, 11454, 11441, -1, 11441, 11454, 11407, -1, 11402, 11398, 11400, -1, 11402, 11400, 11456, -1, 11402, 11404, 11398, -1, 11406, 11435, 11408, -1, 11406, 11402, 11456, -1, 11438, 11440, 11415, -1, 11438, 11415, 11435, -1, 11438, 11435, 11406, -1, 11442, 11448, 11444, -1, 11446, 11448, 11442, -1, 11457, 11442, 11438, -1, 11457, 11446, 11442, -1, 11456, 11457, 11438, -1, 11456, 11438, 11406, -1, 11399, 11398, 11403, -1, 11403, 11398, 11404, -1, 11409, 11408, 11437, -1, 11437, 11408, 11435, -1, 11445, 11448, 11447, -1, 11445, 11444, 11448, -1, 11424, 11440, 11439, -1, 11424, 11415, 11440, -1, 11452, 11457, 11450, -1, 11446, 11457, 11452, -1, 11451, 11446, 11452, -1, 11449, 11446, 11451, -1, 11379, 11450, 11457, -1, 11453, 11379, 11385, -1, 11453, 11450, 11379, -1, 11451, 11455, 11449, -1, 11451, 11453, 11455, -1, 11457, 11456, 11369, -1, 11457, 11369, 11379, -1, 11385, 11455, 11453, -1, 11369, 11456, 11397, -1, 11395, 11369, 11397, -1, 11372, 11369, 11395, -1, 11385, 11372, 11455, -1, 11455, 11372, 11454, -1, 11456, 11400, 11396, -1, 11456, 11396, 11397, -1, 11454, 11372, 11395, -1, 11394, 11400, 11401, -1, 11394, 11396, 11400, -1, 11395, 11394, 11454, -1, 11454, 11394, 11401, -1, 11364, 11377, 11365, -1, 11365, 11377, 11433, -1, 11433, 11375, 11431, -1, 11377, 11375, 11433, -1, 11431, 11376, 11428, -1, 11375, 11376, 11431, -1, 11428, 11374, 11426, -1, 11376, 11374, 11428, -1, 11426, 11373, 11423, -1, 11374, 11373, 11426, -1, 11423, 11371, 11420, -1, 11373, 11371, 11423, -1, 11420, 11370, 11414, -1, 11371, 11370, 11420, -1, 11414, 11366, 11410, -1, 11370, 11366, 11414, -1, 11410, 11392, 11411, -1, 11366, 11392, 11410, -1, 11411, 11393, 11436, -1, 11392, 11393, 11411, -1, 11436, 11367, 11413, -1, 11393, 11367, 11436, -1, 11413, 11368, 11412, -1, 11367, 11368, 11413, -1, 11412, 11338, 11340, -1, 11368, 11338, 11412, -1, 11336, 11386, 11337, -1, 11337, 11386, 11434, -1, 11434, 11387, 11432, -1, 11386, 11387, 11434, -1, 11432, 11388, 11430, -1, 11387, 11388, 11432, -1, 11430, 11389, 11429, -1, 11388, 11389, 11430, -1, 11429, 11390, 11427, -1, 11389, 11390, 11429, -1, 11427, 11391, 11425, -1, 11390, 11391, 11427, -1, 11425, 11378, 11422, -1, 11391, 11378, 11425, -1, 11422, 11380, 11419, -1, 11378, 11380, 11422, -1, 11419, 11381, 11416, -1, 11380, 11381, 11419, -1, 11416, 11382, 11417, -1, 11381, 11382, 11416, -1, 11417, 11383, 11418, -1, 11382, 11383, 11417, -1, 11418, 11384, 11421, -1, 11383, 11384, 11418, -1, 11421, 11310, 11312, -1, 11384, 11310, 11421, -1, 11458, 11459, 11460, -1, 11460, 11459, 11461, -1, 11461, 11462, 11463, -1, 11459, 11462, 11461, -1, 11463, 11464, 11465, -1, 11462, 11464, 11463, -1, 11465, 11466, 11467, -1, 11464, 11466, 11465, -1, 11467, 11468, 11469, -1, 11466, 11468, 11467, -1, 11469, 11470, 11471, -1, 11468, 11470, 11469, -1, 11471, 11472, 11473, -1, 11470, 11472, 11471, -1, 11473, 11474, 11475, -1, 11472, 11474, 11473, -1, 11475, 11476, 11477, -1, 11474, 11476, 11475, -1, 11477, 11478, 11479, -1, 11476, 11478, 11477, -1, 11479, 11480, 11481, -1, 11478, 11480, 11479, -1, 11481, 11482, 11483, -1, 11480, 11482, 11481, -1, 11483, 11484, 11485, -1, 11482, 11484, 11483, -1, 11486, 11487, 11488, -1, 11488, 11487, 11489, -1, 11489, 11490, 11491, -1, 11487, 11490, 11489, -1, 11491, 11492, 11493, -1, 11490, 11492, 11491, -1, 11493, 11494, 11495, -1, 11492, 11494, 11493, -1, 11495, 11496, 11497, -1, 11494, 11496, 11495, -1, 11497, 11498, 11499, -1, 11496, 11498, 11497, -1, 11499, 11500, 11501, -1, 11498, 11500, 11499, -1, 11501, 11502, 11503, -1, 11500, 11502, 11501, -1, 11503, 11504, 11505, -1, 11502, 11504, 11503, -1, 11505, 11506, 11507, -1, 11504, 11506, 11505, -1, 11507, 11508, 11509, -1, 11506, 11508, 11507, -1, 11509, 11510, 11511, -1, 11508, 11510, 11509, -1, 11511, 11512, 11513, -1, 11510, 11512, 11511, -1, 11514, 11515, 11516, -1, 11516, 11515, 11517, -1, 11515, 11518, 11517, -1, 11515, 11519, 11518, -1, 11519, 11520, 11518, -1, 11519, 11521, 11520, -1, 11521, 11522, 11520, -1, 11521, 11523, 11522, -1, 11523, 11524, 11522, -1, 11523, 11525, 11524, -1, 11525, 11526, 11524, -1, 11525, 11527, 11526, -1, 11527, 11528, 11526, -1, 11527, 11529, 11528, -1, 11529, 11530, 11528, -1, 11529, 11531, 11530, -1, 11531, 11532, 11530, -1, 11531, 11533, 11532, -1, 11533, 11534, 11532, -1, 11533, 11535, 11534, -1, 11535, 11536, 11534, -1, 11535, 11537, 11536, -1, 11537, 11538, 11536, -1, 11537, 11539, 11538, -1, 11539, 11540, 11538, -1, 11539, 11541, 11540, -1, 11542, 11543, 11544, -1, 11544, 11543, 11545, -1, 11543, 11546, 11545, -1, 11543, 11547, 11546, -1, 11547, 11548, 11546, -1, 11547, 11549, 11548, -1, 11549, 11550, 11548, -1, 11549, 11551, 11550, -1, 11551, 11552, 11550, -1, 11551, 11553, 11552, -1, 11553, 11554, 11552, -1, 11553, 11555, 11554, -1, 11555, 11556, 11554, -1, 11555, 11557, 11556, -1, 11557, 11558, 11556, -1, 11557, 11559, 11558, -1, 11559, 11560, 11558, -1, 11559, 11561, 11560, -1, 11561, 11562, 11560, -1, 11561, 11563, 11562, -1, 11563, 11564, 11562, -1, 11563, 11565, 11564, -1, 11565, 11566, 11564, -1, 11565, 11567, 11566, -1, 11567, 11568, 11566, -1, 11567, 11569, 11568, -1, 11544, 11545, 11570, -1, 11570, 11545, 11571, -1, 11571, 11546, 11572, -1, 11545, 11546, 11571, -1, 11572, 11548, 11573, -1, 11546, 11548, 11572, -1, 11573, 11550, 11574, -1, 11548, 11550, 11573, -1, 11574, 11552, 11575, -1, 11550, 11552, 11574, -1, 11575, 11554, 11576, -1, 11552, 11554, 11575, -1, 11576, 11556, 11577, -1, 11554, 11556, 11576, -1, 11577, 11558, 11578, -1, 11556, 11558, 11577, -1, 11578, 11560, 11579, -1, 11558, 11560, 11578, -1, 11579, 11562, 11580, -1, 11560, 11562, 11579, -1, 11580, 11564, 11581, -1, 11562, 11564, 11580, -1, 11581, 11566, 11582, -1, 11564, 11566, 11581, -1, 11582, 11568, 11583, -1, 11566, 11568, 11582, -1, 11516, 11517, 11584, -1, 11584, 11517, 11585, -1, 11585, 11517, 11586, -1, 11586, 11518, 11587, -1, 11517, 11518, 11586, -1, 11587, 11520, 11588, -1, 11518, 11520, 11587, -1, 11588, 11522, 11589, -1, 11520, 11522, 11588, -1, 11589, 11524, 11590, -1, 11522, 11524, 11589, -1, 11590, 11526, 11591, -1, 11524, 11526, 11590, -1, 11591, 11528, 11592, -1, 11526, 11528, 11591, -1, 11592, 11530, 11593, -1, 11528, 11530, 11592, -1, 11593, 11532, 11594, -1, 11530, 11532, 11593, -1, 11594, 11534, 11595, -1, 11532, 11534, 11594, -1, 11595, 11536, 11596, -1, 11534, 11536, 11595, -1, 11596, 11538, 11597, -1, 11536, 11538, 11596, -1, 11538, 11540, 11597, -1, 11598, 11599, 11600, -1, 11600, 11599, 11601, -1, 11601, 11602, 11603, -1, 11599, 11602, 11601, -1, 11603, 11604, 11605, -1, 11602, 11604, 11603, -1, 11605, 11606, 11607, -1, 11604, 11606, 11605, -1, 11607, 11608, 11609, -1, 11606, 11608, 11607, -1, 11609, 11610, 11611, -1, 11608, 11610, 11609, -1, 11611, 11612, 11613, -1, 11610, 11612, 11611, -1, 11613, 11614, 11615, -1, 11612, 11614, 11613, -1, 11615, 11616, 11617, -1, 11614, 11616, 11615, -1, 11617, 11618, 11619, -1, 11616, 11618, 11617, -1, 11619, 11620, 11621, -1, 11618, 11620, 11619, -1, 11621, 11622, 11623, -1, 11620, 11622, 11621, -1, 11623, 11624, 11625, -1, 11622, 11624, 11623, -1, 11626, 11627, 11628, -1, 11628, 11627, 11629, -1, 11629, 11630, 11631, -1, 11627, 11630, 11629, -1, 11631, 11632, 11633, -1, 11630, 11632, 11631, -1, 11633, 11634, 11635, -1, 11632, 11634, 11633, -1, 11635, 11636, 11637, -1, 11634, 11636, 11635, -1, 11637, 11638, 11639, -1, 11636, 11638, 11637, -1, 11639, 11640, 11641, -1, 11638, 11640, 11639, -1, 11641, 11642, 11643, -1, 11640, 11642, 11641, -1, 11643, 11644, 11645, -1, 11642, 11644, 11643, -1, 11645, 11646, 11647, -1, 11644, 11646, 11645, -1, 11647, 11648, 11649, -1, 11646, 11648, 11647, -1, 11649, 11650, 11651, -1, 11648, 11650, 11649, -1, 11651, 11652, 11653, -1, 11650, 11652, 11651, -1, 11654, 11655, 11656, -1, 11656, 11655, 11657, -1, 11657, 11658, 11659, -1, 11655, 11658, 11657, -1, 11659, 11660, 11661, -1, 11658, 11660, 11659, -1, 11661, 11662, 11663, -1, 11660, 11662, 11661, -1, 11663, 11664, 11665, -1, 11662, 11664, 11663, -1, 11665, 11666, 11667, -1, 11664, 11666, 11665, -1, 11667, 11668, 11669, -1, 11666, 11668, 11667, -1, 11669, 11670, 11671, -1, 11668, 11670, 11669, -1, 11671, 11672, 11673, -1, 11670, 11672, 11671, -1, 11673, 11674, 11675, -1, 11672, 11674, 11673, -1, 11675, 11676, 11677, -1, 11674, 11676, 11675, -1, 11677, 11678, 11679, -1, 11676, 11678, 11677, -1, 11679, 11680, 11681, -1, 11678, 11680, 11679, -1, 11680, 11682, 11681, -1, 11681, 11682, 11683, -1, 11683, 11682, 11684, -1, 11684, 11685, 11686, -1, 11682, 11685, 11684, -1, 11686, 11687, 11688, -1, 11685, 11687, 11686, -1, 11688, 11689, 11690, -1, 11687, 11689, 11688, -1, 11690, 11691, 11692, -1, 11689, 11691, 11690, -1, 11692, 11693, 11694, -1, 11691, 11693, 11692, -1, 11694, 11695, 11696, -1, 11693, 11695, 11694, -1, 11696, 11697, 11698, -1, 11695, 11697, 11696, -1, 11698, 11699, 11700, -1, 11697, 11699, 11698, -1, 11700, 11701, 11702, -1, 11699, 11701, 11700, -1, 11702, 11703, 11704, -1, 11701, 11703, 11702, -1, 11704, 11705, 11656, -1, 11703, 11705, 11704, -1, 11705, 11654, 11656, -1, 11706, 11494, 11492, -1, 11492, 11490, 11706, -1, 11706, 11496, 11494, -1, 11490, 11487, 11706, -1, 11706, 11498, 11496, -1, 11707, 11500, 11706, -1, 11706, 11500, 11498, -1, 11707, 11502, 11500, -1, 11707, 11504, 11502, -1, 11707, 11506, 11504, -1, 11707, 11508, 11506, -1, 11707, 11510, 11508, -1, 11708, 11549, 11486, -1, 11709, 11551, 11710, -1, 11710, 11551, 11708, -1, 11708, 11551, 11549, -1, 11486, 11547, 11487, -1, 11487, 11547, 11706, -1, 11549, 11547, 11486, -1, 11711, 11553, 11712, -1, 11712, 11553, 11709, -1, 11709, 11553, 11551, -1, 11547, 11543, 11706, -1, 11713, 11555, 11714, -1, 11714, 11555, 11711, -1, 11711, 11555, 11553, -1, 11543, 11542, 11706, -1, 11715, 11557, 11713, -1, 11713, 11557, 11555, -1, 11715, 11559, 11557, -1, 11716, 11559, 11717, -1, 11717, 11559, 11715, -1, 11718, 11561, 11719, -1, 11719, 11561, 11716, -1, 11716, 11561, 11559, -1, 11512, 11563, 11718, -1, 11718, 11563, 11561, -1, 11510, 11565, 11512, -1, 11707, 11565, 11510, -1, 11512, 11565, 11563, -1, 11707, 11567, 11565, -1, 11720, 11605, 11721, -1, 11605, 11607, 11721, -1, 11720, 11603, 11605, -1, 11722, 11603, 11720, -1, 11607, 11609, 11721, -1, 11721, 11609, 11723, -1, 11722, 11601, 11603, -1, 11609, 11611, 11723, -1, 11723, 11611, 11724, -1, 11722, 11600, 11601, -1, 11725, 11600, 11722, -1, 11611, 11613, 11724, -1, 11725, 11726, 11600, -1, 11725, 11727, 11726, -1, 11728, 11727, 11725, -1, 11728, 11729, 11727, -1, 11730, 11729, 11728, -1, 11730, 11731, 11729, -1, 11730, 11732, 11731, -1, 11733, 11732, 11730, -1, 11734, 11735, 11733, -1, 11733, 11735, 11732, -1, 11734, 11736, 11735, -1, 11615, 11521, 11613, -1, 11617, 11523, 11615, -1, 11619, 11523, 11617, -1, 11615, 11523, 11521, -1, 11613, 11519, 11724, -1, 11521, 11519, 11613, -1, 11621, 11525, 11619, -1, 11619, 11525, 11523, -1, 11519, 11515, 11724, -1, 11724, 11515, 11737, -1, 11623, 11527, 11621, -1, 11625, 11527, 11623, -1, 11621, 11527, 11525, -1, 11515, 11514, 11737, -1, 11737, 11514, 11542, -1, 11738, 11529, 11625, -1, 11739, 11529, 11738, -1, 11625, 11529, 11527, -1, 11740, 11531, 11739, -1, 11739, 11531, 11529, -1, 11741, 11533, 11740, -1, 11742, 11533, 11741, -1, 11740, 11533, 11531, -1, 11736, 11535, 11742, -1, 11742, 11535, 11533, -1, 11736, 11537, 11535, -1, 11734, 11537, 11736, -1, 11734, 11539, 11537, -1, 11743, 11539, 11734, -1, 11744, 11464, 11745, -1, 11744, 11466, 11464, -1, 11464, 11462, 11745, -1, 11744, 11468, 11466, -1, 11746, 11468, 11744, -1, 11462, 11459, 11745, -1, 11745, 11459, 11747, -1, 11746, 11470, 11468, -1, 11748, 11470, 11746, -1, 11459, 11458, 11747, -1, 11747, 11458, 11749, -1, 11748, 11472, 11470, -1, 11458, 11750, 11749, -1, 11748, 11474, 11472, -1, 11751, 11474, 11748, -1, 11751, 11476, 11474, -1, 11751, 11478, 11476, -1, 11752, 11478, 11751, -1, 11752, 11480, 11478, -1, 11753, 11482, 11752, -1, 11752, 11482, 11480, -1, 11754, 11484, 11753, -1, 11753, 11484, 11482, -1, 11754, 11755, 11484, -1, 11756, 11757, 11758, -1, 11514, 11757, 11542, -1, 11758, 11757, 11759, -1, 11759, 11757, 11760, -1, 11760, 11757, 11761, -1, 11761, 11757, 11750, -1, 11542, 11757, 11706, -1, 11750, 11757, 11749, -1, 11762, 11757, 11514, -1, 11749, 11757, 11762, -1, 11763, 11764, 11754, -1, 11755, 11764, 11765, -1, 11765, 11764, 11766, -1, 11766, 11764, 11767, -1, 11767, 11764, 11768, -1, 11768, 11764, 11769, -1, 11769, 11764, 11756, -1, 11756, 11764, 11757, -1, 11754, 11764, 11755, -1, 11707, 11764, 11569, -1, 11707, 11569, 11567, -1, 11569, 11764, 11743, -1, 11743, 11764, 11541, -1, 11743, 11541, 11539, -1, 11541, 11764, 11763, -1, 11770, 11771, 11772, -1, 11772, 11771, 11773, -1, 11774, 11775, 11776, -1, 11777, 11775, 11774, -1, 11778, 11779, 11780, -1, 11781, 11779, 11778, -1, 11782, 11781, 11778, -1, 11783, 11781, 11782, -1, 11784, 11783, 11782, -1, 11785, 11783, 11784, -1, 11501, 11786, 11499, -1, 11503, 11786, 11501, -1, 11505, 11786, 11503, -1, 11507, 11786, 11505, -1, 11509, 11786, 11507, -1, 11511, 11786, 11509, -1, 11513, 11786, 11511, -1, 11499, 11786, 11787, -1, 11788, 11786, 11789, -1, 11790, 11786, 11791, -1, 11791, 11786, 11792, -1, 11793, 11794, 11795, -1, 11795, 11796, 11793, -1, 11793, 11797, 11794, -1, 11796, 11798, 11793, -1, 11793, 11799, 11797, -1, 11798, 11460, 11793, -1, 11460, 11461, 11793, -1, 11800, 11790, 11485, -1, 11801, 11790, 11800, -1, 11802, 11790, 11801, -1, 11803, 11790, 11802, -1, 11804, 11790, 11803, -1, 11805, 11790, 11804, -1, 11799, 11790, 11805, -1, 11485, 11790, 11483, -1, 11793, 11790, 11799, -1, 11467, 11674, 11465, -1, 11465, 11672, 11463, -1, 11674, 11672, 11465, -1, 11469, 11676, 11467, -1, 11467, 11676, 11674, -1, 11463, 11670, 11461, -1, 11461, 11670, 11793, -1, 11672, 11670, 11463, -1, 11471, 11678, 11469, -1, 11469, 11678, 11676, -1, 11670, 11668, 11793, -1, 11473, 11680, 11471, -1, 11471, 11680, 11678, -1, 11668, 11666, 11793, -1, 11473, 11682, 11680, -1, 11475, 11682, 11473, -1, 11477, 11685, 11475, -1, 11475, 11685, 11682, -1, 11479, 11687, 11477, -1, 11477, 11687, 11685, -1, 11479, 11689, 11687, -1, 11481, 11689, 11479, -1, 11483, 11691, 11481, -1, 11481, 11691, 11689, -1, 11790, 11691, 11483, -1, 11790, 11693, 11691, -1, 11790, 11695, 11693, -1, 11658, 11618, 11660, -1, 11618, 11616, 11660, -1, 11660, 11616, 11662, -1, 11658, 11620, 11618, -1, 11655, 11620, 11658, -1, 11616, 11614, 11662, -1, 11662, 11614, 11664, -1, 11655, 11622, 11620, -1, 11654, 11622, 11655, -1, 11614, 11612, 11664, -1, 11664, 11612, 11666, -1, 11666, 11612, 11793, -1, 11654, 11624, 11622, -1, 11654, 11806, 11624, -1, 11705, 11806, 11654, -1, 11705, 11807, 11806, -1, 11703, 11807, 11705, -1, 11701, 11808, 11703, -1, 11703, 11808, 11807, -1, 11699, 11809, 11701, -1, 11701, 11809, 11808, -1, 11699, 11810, 11809, -1, 11697, 11810, 11699, -1, 11790, 11791, 11695, -1, 11695, 11791, 11697, -1, 11697, 11791, 11810, -1, 11604, 11646, 11606, -1, 11606, 11644, 11608, -1, 11646, 11644, 11606, -1, 11602, 11648, 11604, -1, 11604, 11648, 11646, -1, 11644, 11642, 11608, -1, 11608, 11642, 11610, -1, 11602, 11650, 11648, -1, 11599, 11650, 11602, -1, 11642, 11640, 11610, -1, 11599, 11652, 11650, -1, 11811, 11652, 11598, -1, 11598, 11652, 11599, -1, 11811, 11812, 11652, -1, 11813, 11812, 11811, -1, 11813, 11814, 11812, -1, 11815, 11814, 11813, -1, 11815, 11816, 11814, -1, 11817, 11816, 11815, -1, 11817, 11818, 11816, -1, 11819, 11818, 11817, -1, 11819, 11820, 11818, -1, 11792, 11820, 11819, -1, 11792, 11821, 11820, -1, 11636, 11787, 11638, -1, 11638, 11787, 11640, -1, 11612, 11787, 11793, -1, 11640, 11787, 11610, -1, 11610, 11787, 11612, -1, 11632, 11822, 11634, -1, 11630, 11823, 11632, -1, 11632, 11823, 11822, -1, 11634, 11824, 11636, -1, 11822, 11824, 11634, -1, 11627, 11825, 11630, -1, 11630, 11825, 11823, -1, 11636, 11826, 11787, -1, 11824, 11826, 11636, -1, 11626, 11827, 11627, -1, 11627, 11827, 11825, -1, 11826, 11488, 11787, -1, 11828, 11829, 11626, -1, 11626, 11829, 11827, -1, 11488, 11489, 11787, -1, 11830, 11831, 11828, -1, 11828, 11831, 11829, -1, 11489, 11491, 11787, -1, 11832, 11833, 11830, -1, 11830, 11833, 11831, -1, 11491, 11493, 11787, -1, 11834, 11835, 11832, -1, 11832, 11835, 11833, -1, 11493, 11495, 11787, -1, 11788, 11836, 11834, -1, 11834, 11836, 11835, -1, 11495, 11497, 11787, -1, 11788, 11789, 11836, -1, 11497, 11499, 11787, -1, 11821, 11786, 11837, -1, 11837, 11786, 11788, -1, 11789, 11786, 11513, -1, 11792, 11786, 11821, -1, 11838, 11839, 11840, -1, 11841, 11839, 11838, -1, 11842, 11841, 11838, -1, 11843, 11841, 11842, -1, 11844, 11843, 11842, -1, 11845, 11843, 11844, -1, 11846, 11847, 11848, -1, 11849, 11847, 11846, -1, 11850, 11851, 11852, -1, 11853, 11851, 11850, -1, 11775, 11781, 11854, -1, 11777, 11781, 11775, -1, 11779, 11781, 11777, -1, 11786, 11783, 11785, -1, 11781, 11783, 11854, -1, 11786, 11790, 11783, -1, 11839, 11841, 11790, -1, 11790, 11841, 11783, -1, 11847, 11843, 11845, -1, 11847, 11849, 11843, -1, 11843, 11855, 11841, -1, 11849, 11855, 11843, -1, 11855, 11854, 11841, -1, 11841, 11854, 11783, -1, 11778, 11774, 11776, -1, 11778, 11776, 11856, -1, 11778, 11780, 11774, -1, 11782, 11787, 11784, -1, 11782, 11778, 11856, -1, 11793, 11787, 11782, -1, 11838, 11840, 11793, -1, 11838, 11793, 11782, -1, 11842, 11848, 11844, -1, 11846, 11848, 11842, -1, 11857, 11842, 11838, -1, 11857, 11846, 11842, -1, 11856, 11857, 11838, -1, 11856, 11838, 11782, -1, 11777, 11774, 11779, -1, 11779, 11774, 11780, -1, 11785, 11784, 11786, -1, 11786, 11784, 11787, -1, 11845, 11844, 11847, -1, 11847, 11844, 11848, -1, 11790, 11793, 11839, -1, 11839, 11793, 11840, -1, 11852, 11857, 11850, -1, 11846, 11857, 11852, -1, 11851, 11846, 11852, -1, 11849, 11846, 11851, -1, 11757, 11850, 11857, -1, 11853, 11757, 11764, -1, 11853, 11850, 11757, -1, 11851, 11855, 11849, -1, 11851, 11853, 11855, -1, 11757, 11856, 11706, -1, 11857, 11856, 11757, -1, 11764, 11855, 11853, -1, 11706, 11856, 11773, -1, 11771, 11706, 11773, -1, 11707, 11706, 11771, -1, 11764, 11854, 11855, -1, 11764, 11707, 11854, -1, 11856, 11776, 11772, -1, 11856, 11772, 11773, -1, 11854, 11707, 11771, -1, 11770, 11776, 11775, -1, 11770, 11772, 11776, -1, 11771, 11770, 11854, -1, 11854, 11770, 11775, -1, 11652, 11812, 11653, -1, 11653, 11812, 11858, -1, 11858, 11814, 11859, -1, 11812, 11814, 11858, -1, 11859, 11816, 11860, -1, 11814, 11816, 11859, -1, 11860, 11818, 11861, -1, 11816, 11818, 11860, -1, 11861, 11820, 11862, -1, 11818, 11820, 11861, -1, 11862, 11821, 11863, -1, 11820, 11821, 11862, -1, 11863, 11837, 11864, -1, 11821, 11837, 11863, -1, 11864, 11788, 11865, -1, 11837, 11788, 11864, -1, 11865, 11834, 11866, -1, 11788, 11834, 11865, -1, 11866, 11832, 11867, -1, 11834, 11832, 11866, -1, 11867, 11830, 11868, -1, 11832, 11830, 11867, -1, 11868, 11828, 11869, -1, 11830, 11828, 11868, -1, 11869, 11626, 11628, -1, 11828, 11626, 11869, -1, 11624, 11806, 11625, -1, 11625, 11806, 11738, -1, 11738, 11807, 11739, -1, 11806, 11807, 11738, -1, 11739, 11808, 11740, -1, 11807, 11808, 11739, -1, 11740, 11809, 11741, -1, 11808, 11809, 11740, -1, 11741, 11810, 11742, -1, 11809, 11810, 11741, -1, 11742, 11791, 11736, -1, 11810, 11791, 11742, -1, 11736, 11792, 11735, -1, 11791, 11792, 11736, -1, 11735, 11819, 11732, -1, 11792, 11819, 11735, -1, 11732, 11817, 11731, -1, 11819, 11817, 11732, -1, 11731, 11815, 11729, -1, 11817, 11815, 11731, -1, 11729, 11813, 11727, -1, 11815, 11813, 11729, -1, 11727, 11811, 11726, -1, 11813, 11811, 11727, -1, 11726, 11598, 11600, -1, 11811, 11598, 11726, -1, 11870, 11871, 11677, -1, 11870, 11677, 11679, -1, 11596, 11696, 11595, -1, 11596, 11694, 11696, -1, 11661, 11587, 11588, -1, 11663, 11586, 11587, -1, 11663, 11587, 11661, -1, 11872, 11870, 11679, -1, 11659, 11588, 11589, -1, 11872, 11679, 11681, -1, 11597, 11694, 11596, -1, 11659, 11661, 11588, -1, 11597, 11692, 11694, -1, 11873, 11681, 11683, -1, 11665, 11585, 11586, -1, 11873, 11872, 11681, -1, 11665, 11586, 11663, -1, 11657, 11589, 11590, -1, 11874, 11692, 11597, -1, 11874, 11690, 11692, -1, 11657, 11659, 11589, -1, 11875, 11683, 11684, -1, 11667, 11584, 11585, -1, 11875, 11873, 11683, -1, 11667, 11585, 11665, -1, 11876, 11688, 11690, -1, 11876, 11690, 11874, -1, 11656, 11590, 11591, -1, 11877, 11684, 11686, -1, 11877, 11875, 11684, -1, 11656, 11657, 11590, -1, 11878, 11686, 11688, -1, 11878, 11877, 11686, -1, 11878, 11688, 11876, -1, 11669, 11879, 11584, -1, 11669, 11584, 11667, -1, 11704, 11591, 11592, -1, 11704, 11656, 11591, -1, 11671, 11880, 11879, -1, 11671, 11879, 11669, -1, 11702, 11592, 11593, -1, 11702, 11704, 11592, -1, 11673, 11880, 11671, -1, 11881, 11880, 11673, -1, 11700, 11702, 11593, -1, 11675, 11881, 11673, -1, 11594, 11700, 11593, -1, 11698, 11700, 11594, -1, 11871, 11881, 11675, -1, 11871, 11675, 11677, -1, 11595, 11698, 11594, -1, 11595, 11696, 11698, -1, 11540, 11882, 11597, -1, 11597, 11882, 11874, -1, 11874, 11883, 11876, -1, 11882, 11883, 11874, -1, 11876, 11884, 11878, -1, 11883, 11884, 11876, -1, 11878, 11885, 11877, -1, 11884, 11885, 11878, -1, 11877, 11886, 11875, -1, 11885, 11886, 11877, -1, 11875, 11887, 11873, -1, 11886, 11887, 11875, -1, 11873, 11888, 11872, -1, 11887, 11888, 11873, -1, 11872, 11889, 11870, -1, 11888, 11889, 11872, -1, 11870, 11890, 11871, -1, 11889, 11890, 11870, -1, 11871, 11891, 11881, -1, 11890, 11891, 11871, -1, 11881, 11892, 11880, -1, 11891, 11892, 11881, -1, 11880, 11893, 11879, -1, 11892, 11893, 11880, -1, 11879, 11516, 11584, -1, 11893, 11516, 11879, -1, 11637, 11572, 11635, -1, 11635, 11572, 11573, -1, 11894, 11895, 11859, -1, 11859, 11895, 11858, -1, 11580, 11867, 11579, -1, 11581, 11866, 11580, -1, 11580, 11866, 11867, -1, 11579, 11868, 11578, -1, 11867, 11868, 11579, -1, 11639, 11571, 11637, -1, 11637, 11571, 11572, -1, 11582, 11865, 11581, -1, 11581, 11865, 11866, -1, 11578, 11869, 11577, -1, 11868, 11869, 11578, -1, 11583, 11864, 11582, -1, 11895, 11896, 11858, -1, 11858, 11896, 11653, -1, 11582, 11864, 11865, -1, 11639, 11570, 11571, -1, 11641, 11570, 11639, -1, 11577, 11628, 11576, -1, 11653, 11897, 11651, -1, 11869, 11628, 11577, -1, 11896, 11897, 11653, -1, 11898, 11863, 11583, -1, 11583, 11863, 11864, -1, 11643, 11899, 11641, -1, 11641, 11899, 11570, -1, 11651, 11900, 11649, -1, 11576, 11629, 11575, -1, 11897, 11900, 11651, -1, 11628, 11629, 11576, -1, 11645, 11901, 11643, -1, 11902, 11862, 11898, -1, 11643, 11901, 11899, -1, 11900, 11903, 11649, -1, 11649, 11903, 11647, -1, 11898, 11862, 11863, -1, 11903, 11904, 11647, -1, 11647, 11904, 11645, -1, 11645, 11904, 11901, -1, 11575, 11631, 11574, -1, 11629, 11631, 11575, -1, 11902, 11861, 11862, -1, 11902, 11905, 11861, -1, 11631, 11633, 11574, -1, 11905, 11860, 11861, -1, 11633, 11573, 11574, -1, 11633, 11635, 11573, -1, 11905, 11894, 11860, -1, 11860, 11894, 11859, -1, 11568, 11906, 11583, -1, 11583, 11906, 11898, -1, 11898, 11907, 11902, -1, 11906, 11907, 11898, -1, 11902, 11908, 11905, -1, 11907, 11908, 11902, -1, 11905, 11909, 11894, -1, 11908, 11909, 11905, -1, 11894, 11910, 11895, -1, 11909, 11910, 11894, -1, 11895, 11911, 11896, -1, 11910, 11911, 11895, -1, 11896, 11912, 11897, -1, 11911, 11912, 11896, -1, 11897, 11913, 11900, -1, 11912, 11913, 11897, -1, 11900, 11914, 11903, -1, 11913, 11914, 11900, -1, 11903, 11915, 11904, -1, 11914, 11915, 11903, -1, 11904, 11916, 11901, -1, 11915, 11916, 11904, -1, 11901, 11917, 11899, -1, 11916, 11917, 11901, -1, 11899, 11544, 11570, -1, 11917, 11544, 11899, -1, 11569, 11906, 11568, -1, 11569, 11743, 11906, -1, 11743, 11907, 11906, -1, 11743, 11734, 11907, -1, 11734, 11908, 11907, -1, 11734, 11733, 11908, -1, 11733, 11909, 11908, -1, 11733, 11730, 11909, -1, 11730, 11910, 11909, -1, 11730, 11728, 11910, -1, 11728, 11911, 11910, -1, 11728, 11725, 11911, -1, 11725, 11912, 11911, -1, 11725, 11722, 11912, -1, 11722, 11913, 11912, -1, 11722, 11720, 11913, -1, 11720, 11914, 11913, -1, 11720, 11721, 11914, -1, 11721, 11915, 11914, -1, 11721, 11723, 11915, -1, 11723, 11916, 11915, -1, 11723, 11724, 11916, -1, 11724, 11917, 11916, -1, 11724, 11737, 11917, -1, 11737, 11544, 11917, -1, 11737, 11542, 11544, -1, 11541, 11882, 11540, -1, 11541, 11763, 11882, -1, 11763, 11883, 11882, -1, 11763, 11754, 11883, -1, 11754, 11884, 11883, -1, 11754, 11753, 11884, -1, 11753, 11885, 11884, -1, 11753, 11752, 11885, -1, 11752, 11886, 11885, -1, 11752, 11751, 11886, -1, 11751, 11887, 11886, -1, 11751, 11748, 11887, -1, 11748, 11888, 11887, -1, 11748, 11746, 11888, -1, 11746, 11889, 11888, -1, 11746, 11744, 11889, -1, 11744, 11890, 11889, -1, 11744, 11745, 11890, -1, 11745, 11891, 11890, -1, 11745, 11747, 11891, -1, 11747, 11892, 11891, -1, 11747, 11749, 11892, -1, 11749, 11893, 11892, -1, 11749, 11762, 11893, -1, 11762, 11516, 11893, -1, 11762, 11514, 11516, -1, 11512, 11718, 11513, -1, 11513, 11718, 11789, -1, 11789, 11719, 11836, -1, 11718, 11719, 11789, -1, 11836, 11716, 11835, -1, 11719, 11716, 11836, -1, 11835, 11717, 11833, -1, 11716, 11717, 11835, -1, 11833, 11715, 11831, -1, 11717, 11715, 11833, -1, 11831, 11713, 11829, -1, 11715, 11713, 11831, -1, 11829, 11714, 11827, -1, 11713, 11714, 11829, -1, 11827, 11711, 11825, -1, 11714, 11711, 11827, -1, 11825, 11712, 11823, -1, 11711, 11712, 11825, -1, 11823, 11709, 11822, -1, 11712, 11709, 11823, -1, 11822, 11710, 11824, -1, 11709, 11710, 11822, -1, 11824, 11708, 11826, -1, 11710, 11708, 11824, -1, 11826, 11486, 11488, -1, 11708, 11486, 11826, -1, 11484, 11755, 11485, -1, 11485, 11755, 11800, -1, 11800, 11765, 11801, -1, 11755, 11765, 11800, -1, 11801, 11766, 11802, -1, 11765, 11766, 11801, -1, 11802, 11767, 11803, -1, 11766, 11767, 11802, -1, 11803, 11768, 11804, -1, 11767, 11768, 11803, -1, 11804, 11769, 11805, -1, 11768, 11769, 11804, -1, 11805, 11756, 11799, -1, 11769, 11756, 11805, -1, 11799, 11758, 11797, -1, 11756, 11758, 11799, -1, 11797, 11759, 11794, -1, 11758, 11759, 11797, -1, 11794, 11760, 11795, -1, 11759, 11760, 11794, -1, 11795, 11761, 11796, -1, 11760, 11761, 11795, -1, 11796, 11750, 11798, -1, 11761, 11750, 11796, -1, 11798, 11458, 11460, -1, 11750, 11458, 11798, -1, 11918, 11919, 11920, -1, 11920, 11919, 11921, -1, 11921, 11922, 11923, -1, 11919, 11922, 11921, -1, 11923, 11924, 11925, -1, 11922, 11924, 11923, -1, 11925, 11926, 11927, -1, 11924, 11926, 11925, -1, 11927, 11928, 11929, -1, 11926, 11928, 11927, -1, 11929, 11930, 11931, -1, 11928, 11930, 11929, -1, 11931, 11932, 11933, -1, 11930, 11932, 11931, -1, 11933, 11934, 11935, -1, 11932, 11934, 11933, -1, 11935, 11936, 11937, -1, 11934, 11936, 11935, -1, 11937, 11938, 11939, -1, 11936, 11938, 11937, -1, 11939, 11940, 11941, -1, 11938, 11940, 11939, -1, 11941, 11942, 11943, -1, 11940, 11942, 11941, -1, 11943, 11944, 11945, -1, 11942, 11944, 11943, -1, 11946, 11947, 11948, -1, 11948, 11947, 11949, -1, 11949, 11950, 11951, -1, 11947, 11950, 11949, -1, 11951, 11952, 11953, -1, 11950, 11952, 11951, -1, 11953, 11954, 11955, -1, 11952, 11954, 11953, -1, 11955, 11956, 11957, -1, 11954, 11956, 11955, -1, 11957, 11958, 11959, -1, 11956, 11958, 11957, -1, 11959, 11960, 11961, -1, 11958, 11960, 11959, -1, 11961, 11962, 11963, -1, 11960, 11962, 11961, -1, 11963, 11964, 11965, -1, 11962, 11964, 11963, -1, 11965, 11966, 11967, -1, 11964, 11966, 11965, -1, 11967, 11968, 11969, -1, 11966, 11968, 11967, -1, 11969, 11970, 11971, -1, 11968, 11970, 11969, -1, 11971, 11972, 11973, -1, 11970, 11972, 11971, -1, 11974, 11975, 11976, -1, 11974, 11977, 11975, -1, 11977, 11978, 11975, -1, 11977, 11979, 11978, -1, 11979, 11980, 11978, -1, 11979, 11981, 11980, -1, 11981, 11982, 11980, -1, 11981, 11983, 11982, -1, 11983, 11984, 11982, -1, 11983, 11985, 11984, -1, 11985, 11986, 11984, -1, 11985, 11987, 11986, -1, 11987, 11988, 11986, -1, 11987, 11989, 11988, -1, 11989, 11990, 11988, -1, 11989, 11991, 11990, -1, 11991, 11992, 11990, -1, 11991, 11993, 11992, -1, 11993, 11994, 11992, -1, 11993, 11995, 11994, -1, 11995, 11996, 11994, -1, 11995, 11997, 11996, -1, 11997, 11998, 11996, -1, 11997, 11999, 11998, -1, 11999, 12000, 11998, -1, 11999, 12001, 12000, -1, 12002, 12003, 12004, -1, 12002, 12005, 12003, -1, 12005, 12006, 12003, -1, 12005, 12007, 12006, -1, 12007, 12008, 12006, -1, 12007, 12009, 12008, -1, 12009, 12010, 12008, -1, 12009, 12011, 12010, -1, 12011, 12012, 12010, -1, 12011, 12013, 12012, -1, 12013, 12014, 12012, -1, 12013, 12015, 12014, -1, 12015, 12016, 12014, -1, 12015, 12017, 12016, -1, 12017, 12018, 12016, -1, 12017, 12019, 12018, -1, 12019, 12020, 12018, -1, 12019, 12021, 12020, -1, 12021, 12022, 12020, -1, 12021, 12023, 12022, -1, 12023, 12024, 12022, -1, 12023, 12025, 12024, -1, 12025, 12026, 12024, -1, 12025, 12027, 12026, -1, 12027, 12028, 12026, -1, 12027, 12029, 12028, -1, 12004, 12003, 12030, -1, 12030, 12003, 12031, -1, 12031, 12006, 12032, -1, 12003, 12006, 12031, -1, 12032, 12008, 12033, -1, 12006, 12008, 12032, -1, 12033, 12010, 12034, -1, 12008, 12010, 12033, -1, 12034, 12012, 12035, -1, 12010, 12012, 12034, -1, 12035, 12014, 12036, -1, 12012, 12014, 12035, -1, 12036, 12016, 12037, -1, 12014, 12016, 12036, -1, 12037, 12018, 12038, -1, 12016, 12018, 12037, -1, 12038, 12020, 12039, -1, 12018, 12020, 12038, -1, 12039, 12022, 12040, -1, 12020, 12022, 12039, -1, 12040, 12024, 12041, -1, 12022, 12024, 12040, -1, 12041, 12026, 12042, -1, 12024, 12026, 12041, -1, 12042, 12028, 12043, -1, 12026, 12028, 12042, -1, 11976, 11975, 12044, -1, 12044, 11975, 12045, -1, 12045, 11975, 12046, -1, 12046, 11978, 12047, -1, 11975, 11978, 12046, -1, 12047, 11980, 12048, -1, 11978, 11980, 12047, -1, 12048, 11982, 12049, -1, 11980, 11982, 12048, -1, 12049, 11984, 12050, -1, 11982, 11984, 12049, -1, 12050, 11986, 12051, -1, 11984, 11986, 12050, -1, 12051, 11988, 12052, -1, 11986, 11988, 12051, -1, 12052, 11990, 12053, -1, 11988, 11990, 12052, -1, 12053, 11992, 12054, -1, 11990, 11992, 12053, -1, 12054, 11994, 12055, -1, 11992, 11994, 12054, -1, 12055, 11996, 12056, -1, 11994, 11996, 12055, -1, 12056, 11998, 12057, -1, 11996, 11998, 12056, -1, 11998, 12000, 12057, -1, 12058, 12059, 12060, -1, 12060, 12059, 12061, -1, 12061, 12062, 12063, -1, 12059, 12062, 12061, -1, 12063, 12064, 12065, -1, 12062, 12064, 12063, -1, 12065, 12066, 12067, -1, 12064, 12066, 12065, -1, 12067, 12068, 12069, -1, 12066, 12068, 12067, -1, 12069, 12070, 12071, -1, 12068, 12070, 12069, -1, 12071, 12072, 12073, -1, 12070, 12072, 12071, -1, 12073, 12074, 12075, -1, 12072, 12074, 12073, -1, 12075, 12076, 12077, -1, 12074, 12076, 12075, -1, 12077, 12078, 12079, -1, 12076, 12078, 12077, -1, 12079, 12080, 12081, -1, 12078, 12080, 12079, -1, 12081, 12082, 12083, -1, 12080, 12082, 12081, -1, 12083, 12084, 12085, -1, 12082, 12084, 12083, -1, 12086, 12087, 12088, -1, 12088, 12087, 12089, -1, 12089, 12090, 12091, -1, 12087, 12090, 12089, -1, 12091, 12092, 12093, -1, 12090, 12092, 12091, -1, 12093, 12094, 12095, -1, 12092, 12094, 12093, -1, 12095, 12096, 12097, -1, 12094, 12096, 12095, -1, 12097, 12098, 12099, -1, 12096, 12098, 12097, -1, 12099, 12100, 12101, -1, 12098, 12100, 12099, -1, 12101, 12102, 12103, -1, 12100, 12102, 12101, -1, 12103, 12104, 12105, -1, 12102, 12104, 12103, -1, 12105, 12106, 12107, -1, 12104, 12106, 12105, -1, 12107, 12108, 12109, -1, 12106, 12108, 12107, -1, 12109, 12110, 12111, -1, 12108, 12110, 12109, -1, 12111, 12112, 12113, -1, 12110, 12112, 12111, -1, 12114, 12115, 12116, -1, 12116, 12115, 12117, -1, 12117, 12118, 12119, -1, 12115, 12118, 12117, -1, 12119, 12120, 12121, -1, 12118, 12120, 12119, -1, 12121, 12122, 12123, -1, 12120, 12122, 12121, -1, 12123, 12124, 12125, -1, 12122, 12124, 12123, -1, 12125, 12126, 12127, -1, 12124, 12126, 12125, -1, 12127, 12128, 12129, -1, 12126, 12128, 12127, -1, 12129, 12130, 12131, -1, 12128, 12130, 12129, -1, 12131, 12132, 12133, -1, 12130, 12132, 12131, -1, 12133, 12134, 12135, -1, 12132, 12134, 12133, -1, 12135, 12136, 12137, -1, 12134, 12136, 12135, -1, 12137, 12138, 12139, -1, 12136, 12138, 12137, -1, 12139, 12140, 12141, -1, 12138, 12140, 12139, -1, 12140, 12142, 12141, -1, 12141, 12142, 12143, -1, 12143, 12142, 12144, -1, 12144, 12145, 12146, -1, 12142, 12145, 12144, -1, 12146, 12147, 12148, -1, 12145, 12147, 12146, -1, 12148, 12149, 12150, -1, 12147, 12149, 12148, -1, 12150, 12151, 12152, -1, 12149, 12151, 12150, -1, 12152, 12153, 12154, -1, 12151, 12153, 12152, -1, 12154, 12155, 12156, -1, 12153, 12155, 12154, -1, 12156, 12157, 12158, -1, 12155, 12157, 12156, -1, 12158, 12159, 12160, -1, 12157, 12159, 12158, -1, 12160, 12161, 12162, -1, 12159, 12161, 12160, -1, 12162, 12163, 12164, -1, 12161, 12163, 12162, -1, 12164, 12165, 12116, -1, 12163, 12165, 12164, -1, 12165, 12114, 12116, -1, 12166, 11954, 11952, -1, 11952, 11950, 12166, -1, 12166, 11956, 11954, -1, 11950, 11947, 12166, -1, 12166, 11958, 11956, -1, 12167, 11960, 12166, -1, 12166, 11960, 11958, -1, 12167, 11962, 11960, -1, 12167, 11964, 11962, -1, 12167, 11966, 11964, -1, 12167, 11968, 11966, -1, 12167, 11970, 11968, -1, 12168, 12009, 11946, -1, 12169, 12011, 12170, -1, 12170, 12011, 12168, -1, 12168, 12011, 12009, -1, 11946, 12007, 11947, -1, 11947, 12007, 12166, -1, 12009, 12007, 11946, -1, 12171, 12013, 12172, -1, 12172, 12013, 12169, -1, 12169, 12013, 12011, -1, 12007, 12005, 12166, -1, 12173, 12015, 12174, -1, 12174, 12015, 12171, -1, 12171, 12015, 12013, -1, 12005, 12002, 12166, -1, 12175, 12017, 12173, -1, 12173, 12017, 12015, -1, 12175, 12019, 12017, -1, 12176, 12019, 12177, -1, 12177, 12019, 12175, -1, 12178, 12021, 12179, -1, 12179, 12021, 12176, -1, 12176, 12021, 12019, -1, 11972, 12023, 12178, -1, 12178, 12023, 12021, -1, 11970, 12025, 11972, -1, 12167, 12025, 11970, -1, 11972, 12025, 12023, -1, 12167, 12027, 12025, -1, 12180, 12065, 12181, -1, 12065, 12067, 12181, -1, 12180, 12063, 12065, -1, 12182, 12063, 12180, -1, 12067, 12069, 12181, -1, 12181, 12069, 12183, -1, 12182, 12061, 12063, -1, 12069, 12071, 12183, -1, 12183, 12071, 12184, -1, 12182, 12060, 12061, -1, 12185, 12060, 12182, -1, 12071, 12073, 12184, -1, 12185, 12186, 12060, -1, 12185, 12187, 12186, -1, 12188, 12187, 12185, -1, 12188, 12189, 12187, -1, 12190, 12189, 12188, -1, 12190, 12191, 12189, -1, 12190, 12192, 12191, -1, 12193, 12192, 12190, -1, 12194, 12195, 12193, -1, 12193, 12195, 12192, -1, 12194, 12196, 12195, -1, 12075, 11981, 12073, -1, 12077, 11983, 12075, -1, 12079, 11983, 12077, -1, 12075, 11983, 11981, -1, 12073, 11979, 12184, -1, 11981, 11979, 12073, -1, 12081, 11985, 12079, -1, 12079, 11985, 11983, -1, 11979, 11977, 12184, -1, 12184, 11977, 12197, -1, 12083, 11987, 12081, -1, 12085, 11987, 12083, -1, 12081, 11987, 11985, -1, 11977, 11974, 12197, -1, 12197, 11974, 12002, -1, 12198, 11989, 12085, -1, 12199, 11989, 12198, -1, 12085, 11989, 11987, -1, 12200, 11991, 12199, -1, 12199, 11991, 11989, -1, 12201, 11993, 12200, -1, 12202, 11993, 12201, -1, 12200, 11993, 11991, -1, 12196, 11995, 12202, -1, 12202, 11995, 11993, -1, 12196, 11997, 11995, -1, 12194, 11997, 12196, -1, 12194, 11999, 11997, -1, 12203, 11999, 12194, -1, 12204, 11924, 12205, -1, 12204, 11926, 11924, -1, 11924, 11922, 12205, -1, 12204, 11928, 11926, -1, 12206, 11928, 12204, -1, 11922, 11919, 12205, -1, 12205, 11919, 12207, -1, 12206, 11930, 11928, -1, 12208, 11930, 12206, -1, 11919, 11918, 12207, -1, 12207, 11918, 12209, -1, 12208, 11932, 11930, -1, 11918, 12210, 12209, -1, 12208, 11934, 11932, -1, 12211, 11934, 12208, -1, 12211, 11936, 11934, -1, 12211, 11938, 11936, -1, 12212, 11938, 12211, -1, 12212, 11940, 11938, -1, 12213, 11942, 12212, -1, 12212, 11942, 11940, -1, 12214, 11944, 12213, -1, 12213, 11944, 11942, -1, 12214, 12215, 11944, -1, 12216, 12217, 12218, -1, 11974, 12217, 12002, -1, 12218, 12217, 12219, -1, 12219, 12217, 12220, -1, 12220, 12217, 12221, -1, 12221, 12217, 12210, -1, 12002, 12217, 12166, -1, 12210, 12217, 12209, -1, 12222, 12217, 11974, -1, 12209, 12217, 12222, -1, 12223, 12224, 12214, -1, 12215, 12224, 12225, -1, 12225, 12224, 12226, -1, 12226, 12224, 12227, -1, 12227, 12224, 12228, -1, 12228, 12224, 12229, -1, 12229, 12224, 12216, -1, 12216, 12224, 12217, -1, 12214, 12224, 12215, -1, 12167, 12224, 12029, -1, 12167, 12029, 12027, -1, 12029, 12224, 12203, -1, 12203, 12224, 12001, -1, 12203, 12001, 11999, -1, 12001, 12224, 12223, -1, 12230, 12231, 12232, -1, 12231, 12233, 12232, -1, 12234, 12235, 12236, -1, 12237, 12235, 12234, -1, 12238, 12239, 12240, -1, 12241, 12239, 12238, -1, 12242, 12241, 12238, -1, 12243, 12241, 12242, -1, 12244, 12243, 12242, -1, 12245, 12243, 12244, -1, 12246, 12247, 12248, -1, 12248, 12247, 12249, -1, 12250, 12247, 11973, -1, 12251, 12247, 12246, -1, 11963, 12247, 11961, -1, 11965, 12247, 11963, -1, 12252, 12253, 12254, -1, 11967, 12247, 11965, -1, 11969, 12247, 11967, -1, 11971, 12247, 11969, -1, 11973, 12247, 11971, -1, 12249, 12247, 12250, -1, 12254, 12255, 12252, -1, 11961, 12247, 12256, -1, 12257, 12247, 12258, -1, 12258, 12247, 12251, -1, 12252, 12259, 12253, -1, 12255, 12260, 12252, -1, 12252, 12261, 12259, -1, 12260, 11920, 12252, -1, 12252, 12262, 12261, -1, 11920, 11921, 12252, -1, 12263, 12257, 11945, -1, 12264, 12257, 12263, -1, 12265, 12257, 12264, -1, 12266, 12257, 12265, -1, 12267, 12257, 12266, -1, 12262, 12257, 12267, -1, 11945, 12257, 11943, -1, 12252, 12257, 12262, -1, 11927, 12134, 11925, -1, 11925, 12132, 11923, -1, 12134, 12132, 11925, -1, 11929, 12136, 11927, -1, 11927, 12136, 12134, -1, 11923, 12130, 11921, -1, 11921, 12130, 12252, -1, 12132, 12130, 11923, -1, 11931, 12138, 11929, -1, 11929, 12138, 12136, -1, 12130, 12128, 12252, -1, 11933, 12140, 11931, -1, 11931, 12140, 12138, -1, 12128, 12126, 12252, -1, 11933, 12142, 12140, -1, 11935, 12142, 11933, -1, 11937, 12145, 11935, -1, 11935, 12145, 12142, -1, 11939, 12147, 11937, -1, 11937, 12147, 12145, -1, 11939, 12149, 12147, -1, 11941, 12149, 11939, -1, 11943, 12151, 11941, -1, 12257, 12151, 11943, -1, 11941, 12151, 12149, -1, 12257, 12153, 12151, -1, 12257, 12155, 12153, -1, 12118, 12078, 12120, -1, 12078, 12076, 12120, -1, 12120, 12076, 12122, -1, 12118, 12080, 12078, -1, 12115, 12080, 12118, -1, 12076, 12074, 12122, -1, 12122, 12074, 12124, -1, 12115, 12082, 12080, -1, 12114, 12082, 12115, -1, 12074, 12072, 12124, -1, 12124, 12072, 12126, -1, 12126, 12072, 12252, -1, 12114, 12084, 12082, -1, 12114, 12268, 12084, -1, 12165, 12268, 12114, -1, 12165, 12269, 12268, -1, 12163, 12269, 12165, -1, 12161, 12270, 12163, -1, 12163, 12270, 12269, -1, 12159, 12271, 12161, -1, 12161, 12271, 12270, -1, 12159, 12272, 12271, -1, 12157, 12272, 12159, -1, 12257, 12258, 12155, -1, 12155, 12258, 12157, -1, 12157, 12258, 12272, -1, 12064, 12106, 12066, -1, 12066, 12104, 12068, -1, 12106, 12104, 12066, -1, 12062, 12108, 12064, -1, 12064, 12108, 12106, -1, 12104, 12102, 12068, -1, 12068, 12102, 12070, -1, 12062, 12110, 12108, -1, 12059, 12110, 12062, -1, 12102, 12100, 12070, -1, 12059, 12112, 12110, -1, 12273, 12112, 12058, -1, 12058, 12112, 12059, -1, 12273, 12274, 12112, -1, 12275, 12274, 12273, -1, 12275, 12276, 12274, -1, 12277, 12276, 12275, -1, 12277, 12278, 12276, -1, 12279, 12278, 12277, -1, 12279, 12280, 12278, -1, 12281, 12280, 12279, -1, 12281, 12282, 12280, -1, 12251, 12282, 12281, -1, 12251, 12246, 12282, -1, 12096, 12256, 12098, -1, 12098, 12256, 12100, -1, 12072, 12256, 12252, -1, 12100, 12256, 12070, -1, 12070, 12256, 12072, -1, 12092, 12283, 12094, -1, 12090, 12284, 12092, -1, 12092, 12284, 12283, -1, 12094, 12285, 12096, -1, 12283, 12285, 12094, -1, 12087, 12286, 12090, -1, 12090, 12286, 12284, -1, 12096, 12287, 12256, -1, 12285, 12287, 12096, -1, 12086, 12288, 12087, -1, 12087, 12288, 12286, -1, 12287, 11948, 12256, -1, 12289, 12290, 12086, -1, 12086, 12290, 12288, -1, 11948, 11949, 12256, -1, 12291, 12292, 12289, -1, 12289, 12292, 12290, -1, 11949, 11951, 12256, -1, 12293, 12294, 12291, -1, 12291, 12294, 12292, -1, 11951, 11953, 12256, -1, 12295, 12296, 12293, -1, 12293, 12296, 12294, -1, 11953, 11955, 12256, -1, 12249, 12297, 12295, -1, 12295, 12297, 12296, -1, 11955, 11957, 12256, -1, 12249, 12250, 12297, -1, 11957, 11959, 12256, -1, 11959, 11961, 12256, -1, 12298, 12299, 12300, -1, 12301, 12299, 12298, -1, 12302, 12301, 12298, -1, 12303, 12301, 12302, -1, 12304, 12303, 12302, -1, 12305, 12303, 12304, -1, 12306, 12307, 12308, -1, 12309, 12307, 12306, -1, 12310, 12311, 12312, -1, 12311, 12313, 12312, -1, 12235, 12241, 12314, -1, 12237, 12241, 12235, -1, 12239, 12241, 12237, -1, 12247, 12243, 12245, -1, 12241, 12243, 12314, -1, 12247, 12257, 12243, -1, 12299, 12301, 12257, -1, 12257, 12301, 12243, -1, 12307, 12303, 12305, -1, 12307, 12309, 12303, -1, 12303, 12315, 12301, -1, 12309, 12315, 12303, -1, 12315, 12314, 12301, -1, 12301, 12314, 12243, -1, 12238, 12234, 12236, -1, 12238, 12236, 12316, -1, 12238, 12240, 12234, -1, 12242, 12256, 12244, -1, 12242, 12238, 12316, -1, 12252, 12256, 12242, -1, 12298, 12300, 12252, -1, 12298, 12252, 12242, -1, 12302, 12308, 12304, -1, 12306, 12308, 12302, -1, 12317, 12302, 12298, -1, 12317, 12306, 12302, -1, 12316, 12317, 12298, -1, 12316, 12298, 12242, -1, 12237, 12234, 12239, -1, 12239, 12234, 12240, -1, 12245, 12244, 12247, -1, 12247, 12244, 12256, -1, 12305, 12304, 12307, -1, 12307, 12304, 12308, -1, 12257, 12252, 12299, -1, 12299, 12252, 12300, -1, 12312, 12317, 12310, -1, 12306, 12317, 12312, -1, 12313, 12306, 12312, -1, 12309, 12306, 12313, -1, 12217, 12310, 12317, -1, 12224, 12310, 12217, -1, 12311, 12310, 12224, -1, 12313, 12315, 12309, -1, 12313, 12311, 12315, -1, 12217, 12316, 12166, -1, 12317, 12316, 12217, -1, 12224, 12315, 12311, -1, 12166, 12316, 12232, -1, 12233, 12166, 12232, -1, 12167, 12166, 12233, -1, 12224, 12314, 12315, -1, 12224, 12167, 12314, -1, 12316, 12236, 12230, -1, 12316, 12230, 12232, -1, 12314, 12167, 12233, -1, 12235, 12230, 12236, -1, 12231, 12230, 12235, -1, 12233, 12231, 12314, -1, 12314, 12231, 12235, -1, 12112, 12274, 12113, -1, 12113, 12274, 12318, -1, 12318, 12276, 12319, -1, 12274, 12276, 12318, -1, 12319, 12278, 12320, -1, 12276, 12278, 12319, -1, 12320, 12280, 12321, -1, 12278, 12280, 12320, -1, 12321, 12282, 12322, -1, 12280, 12282, 12321, -1, 12322, 12246, 12323, -1, 12282, 12246, 12322, -1, 12323, 12248, 12324, -1, 12246, 12248, 12323, -1, 12324, 12249, 12325, -1, 12248, 12249, 12324, -1, 12325, 12295, 12326, -1, 12249, 12295, 12325, -1, 12326, 12293, 12327, -1, 12295, 12293, 12326, -1, 12327, 12291, 12328, -1, 12293, 12291, 12327, -1, 12328, 12289, 12329, -1, 12291, 12289, 12328, -1, 12329, 12086, 12088, -1, 12289, 12086, 12329, -1, 12084, 12268, 12085, -1, 12085, 12268, 12198, -1, 12198, 12269, 12199, -1, 12268, 12269, 12198, -1, 12199, 12270, 12200, -1, 12269, 12270, 12199, -1, 12200, 12271, 12201, -1, 12270, 12271, 12200, -1, 12201, 12272, 12202, -1, 12271, 12272, 12201, -1, 12202, 12258, 12196, -1, 12272, 12258, 12202, -1, 12196, 12251, 12195, -1, 12258, 12251, 12196, -1, 12195, 12281, 12192, -1, 12251, 12281, 12195, -1, 12192, 12279, 12191, -1, 12281, 12279, 12192, -1, 12191, 12277, 12189, -1, 12279, 12277, 12191, -1, 12189, 12275, 12187, -1, 12277, 12275, 12189, -1, 12187, 12273, 12186, -1, 12275, 12273, 12187, -1, 12186, 12058, 12060, -1, 12273, 12058, 12186, -1, 12055, 12158, 12054, -1, 12055, 12156, 12158, -1, 12330, 12137, 12139, -1, 12330, 12331, 12137, -1, 12121, 12047, 12048, -1, 12056, 12156, 12055, -1, 12123, 12046, 12047, -1, 12123, 12047, 12121, -1, 12056, 12154, 12156, -1, 12119, 12048, 12049, -1, 12119, 12121, 12048, -1, 12125, 12045, 12046, -1, 12125, 12046, 12123, -1, 12117, 12049, 12050, -1, 12117, 12119, 12049, -1, 12127, 12044, 12045, -1, 12332, 12330, 12139, -1, 12332, 12139, 12141, -1, 12127, 12045, 12125, -1, 12057, 12152, 12154, -1, 12057, 12154, 12056, -1, 12116, 12050, 12051, -1, 12333, 12141, 12143, -1, 12116, 12117, 12050, -1, 12129, 12334, 12044, -1, 12333, 12332, 12141, -1, 12129, 12044, 12127, -1, 12335, 12150, 12152, -1, 12335, 12152, 12057, -1, 12336, 12333, 12143, -1, 12164, 12051, 12052, -1, 12336, 12143, 12144, -1, 12164, 12116, 12051, -1, 12337, 12150, 12335, -1, 12131, 12338, 12334, -1, 12337, 12148, 12150, -1, 12131, 12334, 12129, -1, 12339, 12336, 12144, -1, 12339, 12144, 12146, -1, 12162, 12052, 12053, -1, 12340, 12339, 12146, -1, 12340, 12146, 12148, -1, 12340, 12148, 12337, -1, 12162, 12164, 12052, -1, 12133, 12338, 12131, -1, 12341, 12338, 12133, -1, 12160, 12162, 12053, -1, 12135, 12341, 12133, -1, 12054, 12160, 12053, -1, 12158, 12160, 12054, -1, 12331, 12135, 12137, -1, 12331, 12341, 12135, -1, 12000, 12342, 12057, -1, 12057, 12342, 12335, -1, 12335, 12343, 12337, -1, 12342, 12343, 12335, -1, 12337, 12344, 12340, -1, 12343, 12344, 12337, -1, 12340, 12345, 12339, -1, 12344, 12345, 12340, -1, 12339, 12346, 12336, -1, 12345, 12346, 12339, -1, 12336, 12347, 12333, -1, 12346, 12347, 12336, -1, 12333, 12348, 12332, -1, 12347, 12348, 12333, -1, 12332, 12349, 12330, -1, 12348, 12349, 12332, -1, 12330, 12350, 12331, -1, 12349, 12350, 12330, -1, 12331, 12351, 12341, -1, 12350, 12351, 12331, -1, 12341, 12352, 12338, -1, 12351, 12352, 12341, -1, 12338, 12353, 12334, -1, 12352, 12353, 12338, -1, 12334, 11976, 12044, -1, 12353, 11976, 12334, -1, 12095, 12032, 12033, -1, 12097, 12032, 12095, -1, 12354, 12355, 12319, -1, 12319, 12355, 12318, -1, 12099, 12031, 12097, -1, 12097, 12031, 12032, -1, 12040, 12327, 12039, -1, 12041, 12326, 12040, -1, 12040, 12326, 12327, -1, 12039, 12328, 12038, -1, 12327, 12328, 12039, -1, 12042, 12325, 12041, -1, 12041, 12325, 12326, -1, 12038, 12329, 12037, -1, 12355, 12356, 12318, -1, 12318, 12356, 12113, -1, 12328, 12329, 12038, -1, 12101, 12030, 12099, -1, 12043, 12324, 12042, -1, 12099, 12030, 12031, -1, 12113, 12357, 12111, -1, 12042, 12324, 12325, -1, 12356, 12357, 12113, -1, 12037, 12088, 12036, -1, 12103, 12358, 12101, -1, 12329, 12088, 12037, -1, 12101, 12358, 12030, -1, 12359, 12323, 12043, -1, 12111, 12360, 12109, -1, 12357, 12360, 12111, -1, 12043, 12323, 12324, -1, 12103, 12361, 12358, -1, 12105, 12361, 12103, -1, 12036, 12089, 12035, -1, 12109, 12362, 12107, -1, 12360, 12362, 12109, -1, 12107, 12363, 12105, -1, 12088, 12089, 12036, -1, 12105, 12363, 12361, -1, 12364, 12322, 12359, -1, 12362, 12363, 12107, -1, 12359, 12322, 12323, -1, 12035, 12091, 12034, -1, 12089, 12091, 12035, -1, 12364, 12321, 12322, -1, 12364, 12365, 12321, -1, 12091, 12093, 12034, -1, 12365, 12320, 12321, -1, 12093, 12033, 12034, -1, 12093, 12095, 12033, -1, 12365, 12354, 12320, -1, 12320, 12354, 12319, -1, 12028, 12366, 12043, -1, 12043, 12366, 12359, -1, 12359, 12367, 12364, -1, 12366, 12367, 12359, -1, 12364, 12368, 12365, -1, 12367, 12368, 12364, -1, 12365, 12369, 12354, -1, 12368, 12369, 12365, -1, 12354, 12370, 12355, -1, 12369, 12370, 12354, -1, 12355, 12371, 12356, -1, 12370, 12371, 12355, -1, 12356, 12372, 12357, -1, 12371, 12372, 12356, -1, 12357, 12373, 12360, -1, 12372, 12373, 12357, -1, 12360, 12374, 12362, -1, 12373, 12374, 12360, -1, 12362, 12375, 12363, -1, 12374, 12375, 12362, -1, 12363, 12376, 12361, -1, 12375, 12376, 12363, -1, 12361, 12377, 12358, -1, 12376, 12377, 12361, -1, 12358, 12004, 12030, -1, 12377, 12004, 12358, -1, 12029, 12366, 12028, -1, 12029, 12203, 12366, -1, 12203, 12367, 12366, -1, 12203, 12194, 12367, -1, 12194, 12368, 12367, -1, 12194, 12193, 12368, -1, 12193, 12369, 12368, -1, 12193, 12190, 12369, -1, 12190, 12370, 12369, -1, 12190, 12188, 12370, -1, 12188, 12371, 12370, -1, 12188, 12185, 12371, -1, 12185, 12372, 12371, -1, 12185, 12182, 12372, -1, 12182, 12373, 12372, -1, 12182, 12180, 12373, -1, 12180, 12374, 12373, -1, 12180, 12181, 12374, -1, 12181, 12375, 12374, -1, 12181, 12183, 12375, -1, 12183, 12376, 12375, -1, 12183, 12184, 12376, -1, 12184, 12377, 12376, -1, 12184, 12197, 12377, -1, 12197, 12004, 12377, -1, 12197, 12002, 12004, -1, 12001, 12342, 12000, -1, 12001, 12223, 12342, -1, 12223, 12343, 12342, -1, 12223, 12214, 12343, -1, 12214, 12344, 12343, -1, 12214, 12213, 12344, -1, 12213, 12345, 12344, -1, 12213, 12212, 12345, -1, 12212, 12346, 12345, -1, 12212, 12211, 12346, -1, 12211, 12347, 12346, -1, 12211, 12208, 12347, -1, 12208, 12348, 12347, -1, 12208, 12206, 12348, -1, 12206, 12349, 12348, -1, 12206, 12204, 12349, -1, 12204, 12350, 12349, -1, 12204, 12205, 12350, -1, 12205, 12351, 12350, -1, 12205, 12207, 12351, -1, 12207, 12352, 12351, -1, 12207, 12209, 12352, -1, 12209, 12353, 12352, -1, 12209, 12222, 12353, -1, 12222, 11976, 12353, -1, 12222, 11974, 11976, -1, 11972, 12178, 11973, -1, 11973, 12178, 12250, -1, 12250, 12179, 12297, -1, 12178, 12179, 12250, -1, 12297, 12176, 12296, -1, 12179, 12176, 12297, -1, 12296, 12177, 12294, -1, 12176, 12177, 12296, -1, 12294, 12175, 12292, -1, 12177, 12175, 12294, -1, 12292, 12173, 12290, -1, 12175, 12173, 12292, -1, 12290, 12174, 12288, -1, 12173, 12174, 12290, -1, 12288, 12171, 12286, -1, 12174, 12171, 12288, -1, 12286, 12172, 12284, -1, 12171, 12172, 12286, -1, 12284, 12169, 12283, -1, 12172, 12169, 12284, -1, 12283, 12170, 12285, -1, 12169, 12170, 12283, -1, 12285, 12168, 12287, -1, 12170, 12168, 12285, -1, 12287, 11946, 11948, -1, 12168, 11946, 12287, -1, 11944, 12215, 11945, -1, 11945, 12215, 12263, -1, 12263, 12225, 12264, -1, 12215, 12225, 12263, -1, 12264, 12226, 12265, -1, 12225, 12226, 12264, -1, 12265, 12227, 12266, -1, 12226, 12227, 12265, -1, 12266, 12228, 12267, -1, 12227, 12228, 12266, -1, 12267, 12229, 12262, -1, 12228, 12229, 12267, -1, 12262, 12216, 12261, -1, 12229, 12216, 12262, -1, 12261, 12218, 12259, -1, 12216, 12218, 12261, -1, 12259, 12219, 12253, -1, 12218, 12219, 12259, -1, 12253, 12220, 12254, -1, 12219, 12220, 12253, -1, 12254, 12221, 12255, -1, 12220, 12221, 12254, -1, 12255, 12210, 12260, -1, 12221, 12210, 12255, -1, 12260, 11918, 11920, -1, 12210, 11918, 12260, -1, 12378, 12379, 12380, -1, 12380, 12379, 12381, -1, 12381, 12382, 12383, -1, 12379, 12382, 12381, -1, 12383, 12384, 12385, -1, 12382, 12384, 12383, -1, 12385, 12386, 12387, -1, 12384, 12386, 12385, -1, 12387, 12388, 12389, -1, 12386, 12388, 12387, -1, 12389, 12390, 12391, -1, 12388, 12390, 12389, -1, 12391, 12392, 12393, -1, 12390, 12392, 12391, -1, 12393, 12394, 12395, -1, 12392, 12394, 12393, -1, 12395, 12396, 12397, -1, 12394, 12396, 12395, -1, 12397, 12398, 12399, -1, 12396, 12398, 12397, -1, 12399, 12400, 12401, -1, 12398, 12400, 12399, -1, 12401, 12402, 12403, -1, 12400, 12402, 12401, -1, 12403, 12404, 12405, -1, 12402, 12404, 12403, -1, 12406, 12407, 12408, -1, 12408, 12407, 12409, -1, 12409, 12410, 12411, -1, 12407, 12410, 12409, -1, 12411, 12412, 12413, -1, 12410, 12412, 12411, -1, 12413, 12414, 12415, -1, 12412, 12414, 12413, -1, 12415, 12416, 12417, -1, 12414, 12416, 12415, -1, 12417, 12418, 12419, -1, 12416, 12418, 12417, -1, 12419, 12420, 12421, -1, 12418, 12420, 12419, -1, 12421, 12422, 12423, -1, 12420, 12422, 12421, -1, 12423, 12424, 12425, -1, 12422, 12424, 12423, -1, 12425, 12426, 12427, -1, 12424, 12426, 12425, -1, 12427, 12428, 12429, -1, 12426, 12428, 12427, -1, 12429, 12430, 12431, -1, 12428, 12430, 12429, -1, 12431, 12432, 12433, -1, 12430, 12432, 12431, -1, 12434, 12388, 12435, -1, 12382, 12379, 12436, -1, 12436, 12379, 12437, -1, 12438, 12414, 12412, -1, 12434, 12390, 12388, -1, 12412, 12410, 12438, -1, 12439, 12390, 12434, -1, 12438, 12416, 12414, -1, 12437, 12378, 12406, -1, 12379, 12378, 12437, -1, 12406, 12378, 12438, -1, 12410, 12407, 12438, -1, 12439, 12392, 12390, -1, 12438, 12418, 12416, -1, 12407, 12406, 12438, -1, 12440, 12392, 12439, -1, 12441, 12420, 12438, -1, 12438, 12420, 12418, -1, 12440, 12394, 12392, -1, 12442, 12394, 12440, -1, 12441, 12422, 12420, -1, 12443, 12396, 12442, -1, 12442, 12396, 12394, -1, 12441, 12424, 12422, -1, 12441, 12426, 12424, -1, 12444, 12398, 12443, -1, 12443, 12398, 12396, -1, 12441, 12428, 12426, -1, 12445, 12400, 12446, -1, 12446, 12400, 12444, -1, 12444, 12400, 12398, -1, 12441, 12430, 12428, -1, 12445, 12402, 12400, -1, 12441, 12432, 12430, -1, 12447, 12448, 12449, -1, 12449, 12448, 12450, -1, 12450, 12448, 12451, -1, 12451, 12448, 12452, -1, 12452, 12448, 12453, -1, 12453, 12448, 12378, -1, 12378, 12448, 12438, -1, 12404, 12454, 12455, -1, 12455, 12454, 12456, -1, 12456, 12454, 12457, -1, 12435, 12386, 12458, -1, 12457, 12454, 12459, -1, 12458, 12386, 12384, -1, 12459, 12454, 12460, -1, 12460, 12454, 12461, -1, 12458, 12382, 12436, -1, 12461, 12454, 12447, -1, 12447, 12454, 12448, -1, 12384, 12382, 12458, -1, 12441, 12454, 12432, -1, 12432, 12454, 12445, -1, 12445, 12454, 12402, -1, 12402, 12454, 12404, -1, 12435, 12388, 12386, -1, 12462, 12463, 12464, -1, 12463, 12465, 12464, -1, 12466, 12467, 12468, -1, 12467, 12469, 12468, -1, 12470, 12471, 12472, -1, 12473, 12471, 12470, -1, 12474, 12473, 12470, -1, 12475, 12473, 12474, -1, 12476, 12475, 12474, -1, 12477, 12475, 12476, -1, 12478, 12479, 12480, -1, 12478, 12480, 12403, -1, 12387, 12481, 12482, -1, 12383, 12483, 12381, -1, 12484, 12483, 12383, -1, 12389, 12485, 12481, -1, 12486, 12487, 12488, -1, 12391, 12485, 12389, -1, 12488, 12489, 12486, -1, 12486, 12490, 12487, -1, 12393, 12491, 12391, -1, 12489, 12492, 12486, -1, 12486, 12493, 12490, -1, 12391, 12491, 12485, -1, 12492, 12380, 12486, -1, 12478, 12494, 12486, -1, 12395, 12495, 12393, -1, 12486, 12494, 12493, -1, 12393, 12495, 12491, -1, 12380, 12381, 12486, -1, 12478, 12496, 12494, -1, 12395, 12497, 12495, -1, 12397, 12497, 12395, -1, 12478, 12498, 12496, -1, 12399, 12499, 12397, -1, 12401, 12499, 12399, -1, 12397, 12499, 12497, -1, 12478, 12500, 12498, -1, 12401, 12501, 12499, -1, 12478, 12502, 12500, -1, 12403, 12480, 12401, -1, 12401, 12480, 12501, -1, 12478, 12503, 12502, -1, 12478, 12405, 12503, -1, 12478, 12403, 12405, -1, 12385, 12504, 12383, -1, 12483, 12505, 12381, -1, 12408, 12505, 12483, -1, 12409, 12505, 12408, -1, 12411, 12505, 12409, -1, 12413, 12505, 12411, -1, 12385, 12482, 12504, -1, 12415, 12505, 12413, -1, 12417, 12505, 12415, -1, 12419, 12505, 12417, -1, 12387, 12482, 12385, -1, 12421, 12505, 12419, -1, 12381, 12505, 12486, -1, 12480, 12479, 12433, -1, 12504, 12484, 12383, -1, 12423, 12479, 12421, -1, 12425, 12479, 12423, -1, 12427, 12479, 12425, -1, 12429, 12479, 12427, -1, 12431, 12479, 12429, -1, 12433, 12479, 12431, -1, 12421, 12479, 12505, -1, 12389, 12481, 12387, -1, 12506, 12507, 12508, -1, 12509, 12507, 12506, -1, 12510, 12509, 12506, -1, 12511, 12509, 12510, -1, 12512, 12511, 12510, -1, 12513, 12511, 12512, -1, 12514, 12515, 12516, -1, 12517, 12515, 12514, -1, 12518, 12519, 12520, -1, 12519, 12521, 12520, -1, 12469, 12473, 12522, -1, 12467, 12473, 12469, -1, 12471, 12473, 12467, -1, 12479, 12475, 12477, -1, 12473, 12475, 12522, -1, 12478, 12509, 12479, -1, 12507, 12509, 12478, -1, 12479, 12509, 12475, -1, 12515, 12511, 12513, -1, 12515, 12517, 12511, -1, 12511, 12523, 12509, -1, 12517, 12523, 12511, -1, 12523, 12522, 12509, -1, 12509, 12522, 12475, -1, 12470, 12466, 12468, -1, 12470, 12468, 12524, -1, 12470, 12472, 12466, -1, 12474, 12505, 12476, -1, 12474, 12470, 12524, -1, 12506, 12508, 12486, -1, 12506, 12486, 12505, -1, 12506, 12505, 12474, -1, 12510, 12516, 12512, -1, 12514, 12516, 12510, -1, 12525, 12510, 12506, -1, 12525, 12514, 12510, -1, 12524, 12525, 12506, -1, 12524, 12506, 12474, -1, 12467, 12466, 12471, -1, 12471, 12466, 12472, -1, 12477, 12476, 12479, -1, 12479, 12476, 12505, -1, 12513, 12516, 12515, -1, 12513, 12512, 12516, -1, 12478, 12508, 12507, -1, 12478, 12486, 12508, -1, 12520, 12525, 12518, -1, 12514, 12525, 12520, -1, 12521, 12514, 12520, -1, 12517, 12514, 12521, -1, 12448, 12518, 12525, -1, 12519, 12448, 12454, -1, 12519, 12518, 12448, -1, 12521, 12523, 12517, -1, 12521, 12519, 12523, -1, 12525, 12524, 12438, -1, 12525, 12438, 12448, -1, 12454, 12523, 12519, -1, 12438, 12524, 12464, -1, 12441, 12464, 12465, -1, 12441, 12438, 12464, -1, 12454, 12441, 12523, -1, 12523, 12441, 12522, -1, 12524, 12468, 12462, -1, 12524, 12462, 12464, -1, 12522, 12441, 12465, -1, 12469, 12462, 12468, -1, 12463, 12462, 12469, -1, 12465, 12463, 12522, -1, 12522, 12463, 12469, -1, 12432, 12445, 12433, -1, 12433, 12445, 12480, -1, 12480, 12446, 12501, -1, 12445, 12446, 12480, -1, 12501, 12444, 12499, -1, 12446, 12444, 12501, -1, 12499, 12443, 12497, -1, 12444, 12443, 12499, -1, 12497, 12442, 12495, -1, 12443, 12442, 12497, -1, 12495, 12440, 12491, -1, 12442, 12440, 12495, -1, 12491, 12439, 12485, -1, 12440, 12439, 12491, -1, 12485, 12434, 12481, -1, 12439, 12434, 12485, -1, 12481, 12435, 12482, -1, 12434, 12435, 12481, -1, 12482, 12458, 12504, -1, 12435, 12458, 12482, -1, 12504, 12436, 12484, -1, 12458, 12436, 12504, -1, 12484, 12437, 12483, -1, 12436, 12437, 12484, -1, 12483, 12406, 12408, -1, 12437, 12406, 12483, -1, 12404, 12455, 12405, -1, 12405, 12455, 12503, -1, 12503, 12456, 12502, -1, 12455, 12456, 12503, -1, 12502, 12457, 12500, -1, 12456, 12457, 12502, -1, 12500, 12459, 12498, -1, 12457, 12459, 12500, -1, 12498, 12460, 12496, -1, 12459, 12460, 12498, -1, 12496, 12461, 12494, -1, 12460, 12461, 12496, -1, 12494, 12447, 12493, -1, 12461, 12447, 12494, -1, 12493, 12449, 12490, -1, 12447, 12449, 12493, -1, 12490, 12450, 12487, -1, 12449, 12450, 12490, -1, 12487, 12451, 12488, -1, 12450, 12451, 12487, -1, 12488, 12452, 12489, -1, 12451, 12452, 12488, -1, 12489, 12453, 12492, -1, 12452, 12453, 12489, -1, 12492, 12378, 12380, -1, 12453, 12378, 12492, -1, 12526, 12527, 12528, -1, 12528, 12527, 12529, -1, 12529, 12530, 12531, -1, 12527, 12530, 12529, -1, 12531, 12532, 12533, -1, 12530, 12532, 12531, -1, 12533, 12534, 12535, -1, 12532, 12534, 12533, -1, 12535, 12536, 12537, -1, 12534, 12536, 12535, -1, 12537, 12538, 12539, -1, 12536, 12538, 12537, -1, 12539, 12540, 12541, -1, 12538, 12540, 12539, -1, 12541, 12542, 12543, -1, 12540, 12542, 12541, -1, 12543, 12544, 12545, -1, 12542, 12544, 12543, -1, 12545, 12546, 12547, -1, 12544, 12546, 12545, -1, 12547, 12548, 12549, -1, 12546, 12548, 12547, -1, 12549, 12550, 12551, -1, 12548, 12550, 12549, -1, 12551, 12552, 12553, -1, 12550, 12552, 12551, -1, 12554, 12555, 12556, -1, 12556, 12555, 12557, -1, 12557, 12558, 12559, -1, 12555, 12558, 12557, -1, 12559, 12560, 12561, -1, 12558, 12560, 12559, -1, 12561, 12562, 12563, -1, 12560, 12562, 12561, -1, 12563, 12564, 12565, -1, 12562, 12564, 12563, -1, 12565, 12566, 12567, -1, 12564, 12566, 12565, -1, 12567, 12568, 12569, -1, 12566, 12568, 12567, -1, 12569, 12570, 12571, -1, 12568, 12570, 12569, -1, 12571, 12572, 12573, -1, 12570, 12572, 12571, -1, 12573, 12574, 12575, -1, 12572, 12574, 12573, -1, 12575, 12576, 12577, -1, 12574, 12576, 12575, -1, 12577, 12578, 12579, -1, 12576, 12578, 12577, -1, 12579, 12580, 12581, -1, 12578, 12580, 12579, -1, 12582, 12583, 12584, -1, 12584, 12583, 12585, -1, 12585, 12586, 12587, -1, 12583, 12586, 12585, -1, 12587, 12588, 12589, -1, 12586, 12588, 12587, -1, 12589, 12590, 12591, -1, 12588, 12590, 12589, -1, 12591, 12592, 12593, -1, 12590, 12592, 12591, -1, 12593, 12594, 12595, -1, 12592, 12594, 12593, -1, 12595, 12596, 12597, -1, 12594, 12596, 12595, -1, 12597, 12598, 12599, -1, 12596, 12598, 12597, -1, 12599, 12600, 12601, -1, 12598, 12600, 12599, -1, 12601, 12602, 12603, -1, 12600, 12602, 12601, -1, 12603, 12604, 12605, -1, 12602, 12604, 12603, -1, 12605, 12606, 12607, -1, 12604, 12606, 12605, -1, 12607, 12608, 12609, -1, 12606, 12608, 12607, -1, 12610, 12611, 12612, -1, 12612, 12611, 12613, -1, 12613, 12614, 12615, -1, 12611, 12614, 12613, -1, 12615, 12616, 12617, -1, 12614, 12616, 12615, -1, 12617, 12618, 12619, -1, 12616, 12618, 12617, -1, 12619, 12620, 12621, -1, 12618, 12620, 12619, -1, 12621, 12622, 12623, -1, 12620, 12622, 12621, -1, 12623, 12624, 12625, -1, 12622, 12624, 12623, -1, 12625, 12626, 12627, -1, 12624, 12626, 12625, -1, 12627, 12628, 12629, -1, 12626, 12628, 12627, -1, 12629, 12630, 12631, -1, 12628, 12630, 12629, -1, 12631, 12632, 12633, -1, 12630, 12632, 12631, -1, 12633, 12634, 12635, -1, 12632, 12634, 12633, -1, 12635, 12636, 12637, -1, 12634, 12636, 12635, -1, 12638, 12639, 12640, -1, 12640, 12639, 12641, -1, 12642, 12643, 12644, -1, 12643, 12645, 12644, -1, 12646, 12647, 12648, -1, 12649, 12647, 12646, -1, 12650, 12651, 12652, -1, 12651, 12653, 12652, -1, 12590, 12588, 12640, -1, 12586, 12640, 12588, -1, 12592, 12590, 12640, -1, 12583, 12640, 12586, -1, 12594, 12640, 12652, -1, 12594, 12592, 12640, -1, 12582, 12640, 12583, -1, 12596, 12594, 12652, -1, 12598, 12596, 12652, -1, 12600, 12598, 12652, -1, 12532, 12654, 12655, -1, 12534, 12532, 12655, -1, 12534, 12655, 12656, -1, 12534, 12656, 12657, -1, 12530, 12654, 12532, -1, 12536, 12534, 12657, -1, 12536, 12657, 12658, -1, 12538, 12536, 12658, -1, 12540, 12658, 12659, -1, 12540, 12538, 12658, -1, 12638, 12530, 12527, -1, 12638, 12527, 12526, -1, 12638, 12640, 12582, -1, 12638, 12582, 12660, -1, 12638, 12660, 12654, -1, 12638, 12654, 12530, -1, 12661, 12638, 12526, -1, 12542, 12540, 12659, -1, 12542, 12659, 12662, -1, 12663, 12638, 12661, -1, 12544, 12542, 12662, -1, 12544, 12662, 12664, -1, 12544, 12664, 12665, -1, 12666, 12638, 12663, -1, 12546, 12544, 12665, -1, 12546, 12665, 12667, -1, 12548, 12546, 12667, -1, 12642, 12666, 12668, -1, 12642, 12668, 12669, -1, 12642, 12638, 12666, -1, 12670, 12642, 12669, -1, 12671, 12642, 12670, -1, 12672, 12642, 12671, -1, 12673, 12642, 12672, -1, 12618, 12652, 12653, -1, 12618, 12616, 12602, -1, 12618, 12600, 12652, -1, 12618, 12602, 12600, -1, 12614, 12602, 12616, -1, 12614, 12604, 12602, -1, 12620, 12618, 12653, -1, 12611, 12604, 12614, -1, 12611, 12606, 12604, -1, 12622, 12620, 12653, -1, 12610, 12606, 12611, -1, 12610, 12608, 12606, -1, 12624, 12653, 12648, -1, 12624, 12622, 12653, -1, 12674, 12608, 12610, -1, 12674, 12675, 12608, -1, 12626, 12624, 12648, -1, 12676, 12675, 12674, -1, 12676, 12548, 12667, -1, 12676, 12667, 12675, -1, 12628, 12626, 12648, -1, 12630, 12628, 12648, -1, 12632, 12630, 12648, -1, 12634, 12632, 12648, -1, 12636, 12634, 12648, -1, 12560, 12676, 12677, -1, 12562, 12560, 12677, -1, 12562, 12677, 12678, -1, 12562, 12678, 12679, -1, 12558, 12548, 12676, -1, 12558, 12676, 12560, -1, 12564, 12562, 12679, -1, 12564, 12679, 12680, -1, 12555, 12550, 12548, -1, 12555, 12548, 12558, -1, 12566, 12564, 12680, -1, 12554, 12552, 12550, -1, 12554, 12550, 12555, -1, 12568, 12566, 12680, -1, 12568, 12680, 12681, -1, 12682, 12683, 12552, -1, 12682, 12552, 12554, -1, 12570, 12568, 12681, -1, 12570, 12681, 12684, -1, 12685, 12686, 12687, -1, 12685, 12687, 12683, -1, 12685, 12683, 12682, -1, 12572, 12688, 12689, -1, 12572, 12570, 12684, -1, 12572, 12684, 12688, -1, 12690, 12686, 12685, -1, 12574, 12689, 12691, -1, 12574, 12572, 12689, -1, 12692, 12673, 12686, -1, 12692, 12686, 12690, -1, 12576, 12574, 12691, -1, 12647, 12691, 12693, -1, 12647, 12693, 12636, -1, 12647, 12580, 12578, -1, 12647, 12578, 12576, -1, 12647, 12694, 12695, -1, 12647, 12695, 12696, -1, 12647, 12696, 12580, -1, 12647, 12636, 12648, -1, 12647, 12576, 12691, -1, 12643, 12694, 12647, -1, 12643, 12692, 12697, -1, 12643, 12697, 12698, -1, 12643, 12698, 12699, -1, 12643, 12699, 12700, -1, 12643, 12700, 12701, -1, 12643, 12701, 12694, -1, 12643, 12642, 12673, -1, 12643, 12673, 12692, -1, 12589, 12591, 12641, -1, 12641, 12587, 12589, -1, 12591, 12593, 12641, -1, 12641, 12585, 12587, -1, 12641, 12595, 12650, -1, 12593, 12595, 12641, -1, 12641, 12584, 12585, -1, 12595, 12597, 12650, -1, 12597, 12599, 12650, -1, 12599, 12601, 12650, -1, 12702, 12533, 12703, -1, 12533, 12535, 12703, -1, 12703, 12535, 12704, -1, 12704, 12535, 12705, -1, 12702, 12531, 12533, -1, 12535, 12537, 12705, -1, 12705, 12537, 12706, -1, 12537, 12539, 12706, -1, 12706, 12541, 12707, -1, 12539, 12541, 12706, -1, 12531, 12639, 12529, -1, 12529, 12639, 12528, -1, 12641, 12639, 12584, -1, 12584, 12639, 12708, -1, 12708, 12639, 12702, -1, 12702, 12639, 12531, -1, 12639, 12709, 12528, -1, 12541, 12543, 12707, -1, 12707, 12543, 12710, -1, 12639, 12711, 12709, -1, 12543, 12545, 12710, -1, 12710, 12545, 12712, -1, 12712, 12545, 12713, -1, 12639, 12714, 12711, -1, 12545, 12547, 12713, -1, 12713, 12547, 12715, -1, 12547, 12549, 12715, -1, 12714, 12644, 12716, -1, 12716, 12644, 12717, -1, 12639, 12644, 12714, -1, 12644, 12718, 12717, -1, 12644, 12719, 12718, -1, 12644, 12720, 12719, -1, 12644, 12721, 12720, -1, 12650, 12619, 12651, -1, 12617, 12619, 12603, -1, 12601, 12619, 12650, -1, 12603, 12619, 12601, -1, 12603, 12615, 12617, -1, 12605, 12615, 12603, -1, 12619, 12621, 12651, -1, 12605, 12613, 12615, -1, 12607, 12613, 12605, -1, 12621, 12623, 12651, -1, 12607, 12612, 12613, -1, 12609, 12612, 12607, -1, 12651, 12625, 12646, -1, 12623, 12625, 12651, -1, 12609, 12722, 12612, -1, 12723, 12722, 12609, -1, 12625, 12627, 12646, -1, 12723, 12724, 12722, -1, 12549, 12724, 12715, -1, 12715, 12724, 12723, -1, 12627, 12629, 12646, -1, 12629, 12631, 12646, -1, 12631, 12633, 12646, -1, 12633, 12635, 12646, -1, 12635, 12637, 12646, -1, 12724, 12561, 12725, -1, 12561, 12563, 12725, -1, 12725, 12563, 12726, -1, 12726, 12563, 12727, -1, 12549, 12559, 12724, -1, 12724, 12559, 12561, -1, 12563, 12565, 12727, -1, 12727, 12565, 12728, -1, 12551, 12557, 12549, -1, 12549, 12557, 12559, -1, 12565, 12567, 12728, -1, 12553, 12556, 12551, -1, 12551, 12556, 12557, -1, 12567, 12569, 12728, -1, 12728, 12569, 12729, -1, 12730, 12731, 12553, -1, 12553, 12731, 12556, -1, 12569, 12571, 12729, -1, 12729, 12571, 12732, -1, 12733, 12734, 12735, -1, 12735, 12734, 12730, -1, 12730, 12734, 12731, -1, 12736, 12573, 12737, -1, 12571, 12573, 12732, -1, 12732, 12573, 12736, -1, 12733, 12738, 12734, -1, 12737, 12575, 12739, -1, 12573, 12575, 12737, -1, 12721, 12740, 12733, -1, 12733, 12740, 12738, -1, 12575, 12577, 12739, -1, 12739, 12649, 12741, -1, 12741, 12649, 12637, -1, 12581, 12649, 12579, -1, 12579, 12649, 12577, -1, 12742, 12649, 12743, -1, 12743, 12649, 12744, -1, 12744, 12649, 12581, -1, 12637, 12649, 12646, -1, 12577, 12649, 12739, -1, 12742, 12645, 12649, -1, 12740, 12645, 12745, -1, 12745, 12645, 12746, -1, 12746, 12645, 12747, -1, 12747, 12645, 12748, -1, 12748, 12645, 12749, -1, 12749, 12645, 12742, -1, 12644, 12645, 12721, -1, 12721, 12645, 12740, -1, 12636, 12693, 12637, -1, 12637, 12693, 12741, -1, 12741, 12691, 12739, -1, 12693, 12691, 12741, -1, 12739, 12689, 12737, -1, 12691, 12689, 12739, -1, 12737, 12688, 12736, -1, 12689, 12688, 12737, -1, 12736, 12684, 12732, -1, 12688, 12684, 12736, -1, 12732, 12681, 12729, -1, 12684, 12681, 12732, -1, 12729, 12680, 12728, -1, 12681, 12680, 12729, -1, 12728, 12679, 12727, -1, 12680, 12679, 12728, -1, 12727, 12678, 12726, -1, 12679, 12678, 12727, -1, 12726, 12677, 12725, -1, 12678, 12677, 12726, -1, 12725, 12676, 12724, -1, 12677, 12676, 12725, -1, 12724, 12674, 12722, -1, 12676, 12674, 12724, -1, 12722, 12610, 12612, -1, 12674, 12610, 12722, -1, 12608, 12675, 12609, -1, 12609, 12675, 12723, -1, 12723, 12667, 12715, -1, 12675, 12667, 12723, -1, 12715, 12665, 12713, -1, 12667, 12665, 12715, -1, 12713, 12664, 12712, -1, 12665, 12664, 12713, -1, 12712, 12662, 12710, -1, 12664, 12662, 12712, -1, 12710, 12659, 12707, -1, 12662, 12659, 12710, -1, 12707, 12658, 12706, -1, 12659, 12658, 12707, -1, 12706, 12657, 12705, -1, 12658, 12657, 12706, -1, 12705, 12656, 12704, -1, 12657, 12656, 12705, -1, 12704, 12655, 12703, -1, 12656, 12655, 12704, -1, 12703, 12654, 12702, -1, 12655, 12654, 12703, -1, 12702, 12660, 12708, -1, 12654, 12660, 12702, -1, 12708, 12582, 12584, -1, 12660, 12582, 12708, -1, 12580, 12696, 12581, -1, 12581, 12696, 12744, -1, 12744, 12695, 12743, -1, 12696, 12695, 12744, -1, 12743, 12694, 12742, -1, 12695, 12694, 12743, -1, 12742, 12701, 12749, -1, 12694, 12701, 12742, -1, 12749, 12700, 12748, -1, 12701, 12700, 12749, -1, 12748, 12699, 12747, -1, 12700, 12699, 12748, -1, 12747, 12698, 12746, -1, 12699, 12698, 12747, -1, 12746, 12697, 12745, -1, 12698, 12697, 12746, -1, 12745, 12692, 12740, -1, 12697, 12692, 12745, -1, 12740, 12690, 12738, -1, 12692, 12690, 12740, -1, 12738, 12685, 12734, -1, 12690, 12685, 12738, -1, 12734, 12682, 12731, -1, 12685, 12682, 12734, -1, 12731, 12554, 12556, -1, 12682, 12554, 12731, -1, 12552, 12683, 12553, -1, 12553, 12683, 12730, -1, 12730, 12687, 12735, -1, 12683, 12687, 12730, -1, 12735, 12686, 12733, -1, 12687, 12686, 12735, -1, 12733, 12673, 12721, -1, 12686, 12673, 12733, -1, 12721, 12672, 12720, -1, 12673, 12672, 12721, -1, 12720, 12671, 12719, -1, 12672, 12671, 12720, -1, 12719, 12670, 12718, -1, 12671, 12670, 12719, -1, 12718, 12669, 12717, -1, 12670, 12669, 12718, -1, 12717, 12668, 12716, -1, 12669, 12668, 12717, -1, 12716, 12666, 12714, -1, 12668, 12666, 12716, -1, 12714, 12663, 12711, -1, 12666, 12663, 12714, -1, 12711, 12661, 12709, -1, 12663, 12661, 12711, -1, 12709, 12526, 12528, -1, 12661, 12526, 12709, -1, 12653, 12651, 12648, -1, 12648, 12651, 12646, -1, 12647, 12649, 12643, -1, 12643, 12649, 12645, -1, 12642, 12644, 12638, -1, 12638, 12644, 12639, -1, 12640, 12641, 12652, -1, 12652, 12641, 12650, -1, 12750, 12751, 12752, -1, 12752, 12751, 12753, -1, 12753, 12754, 12755, -1, 12751, 12754, 12753, -1, 12755, 12756, 12757, -1, 12754, 12756, 12755, -1, 12757, 12758, 12759, -1, 12756, 12758, 12757, -1, 12759, 12760, 12761, -1, 12758, 12760, 12759, -1, 12761, 12762, 12763, -1, 12760, 12762, 12761, -1, 12763, 12764, 12765, -1, 12762, 12764, 12763, -1, 12765, 12766, 12767, -1, 12764, 12766, 12765, -1, 12767, 12768, 12769, -1, 12766, 12768, 12767, -1, 12769, 12770, 12771, -1, 12768, 12770, 12769, -1, 12771, 12772, 12773, -1, 12770, 12772, 12771, -1, 12773, 12774, 12775, -1, 12772, 12774, 12773, -1, 12775, 12776, 12777, -1, 12774, 12776, 12775, -1, 12778, 12779, 12780, -1, 12780, 12779, 12781, -1, 12781, 12782, 12783, -1, 12779, 12782, 12781, -1, 12783, 12784, 12785, -1, 12782, 12784, 12783, -1, 12785, 12786, 12787, -1, 12784, 12786, 12785, -1, 12787, 12788, 12789, -1, 12786, 12788, 12787, -1, 12789, 12790, 12791, -1, 12788, 12790, 12789, -1, 12791, 12792, 12793, -1, 12790, 12792, 12791, -1, 12793, 12794, 12795, -1, 12792, 12794, 12793, -1, 12795, 12796, 12797, -1, 12794, 12796, 12795, -1, 12797, 12798, 12799, -1, 12796, 12798, 12797, -1, 12799, 12800, 12801, -1, 12798, 12800, 12799, -1, 12801, 12802, 12803, -1, 12800, 12802, 12801, -1, 12803, 12804, 12805, -1, 12802, 12804, 12803, -1, 12806, 12807, 12808, -1, 12808, 12807, 12809, -1, 12809, 12810, 12811, -1, 12807, 12810, 12809, -1, 12811, 12812, 12813, -1, 12810, 12812, 12811, -1, 12813, 12814, 12815, -1, 12812, 12814, 12813, -1, 12815, 12816, 12817, -1, 12814, 12816, 12815, -1, 12817, 12818, 12819, -1, 12816, 12818, 12817, -1, 12819, 12820, 12821, -1, 12818, 12820, 12819, -1, 12821, 12822, 12823, -1, 12820, 12822, 12821, -1, 12823, 12824, 12825, -1, 12822, 12824, 12823, -1, 12825, 12826, 12827, -1, 12824, 12826, 12825, -1, 12827, 12828, 12829, -1, 12826, 12828, 12827, -1, 12829, 12830, 12831, -1, 12828, 12830, 12829, -1, 12831, 12832, 12833, -1, 12830, 12832, 12831, -1, 12834, 12835, 12836, -1, 12836, 12835, 12837, -1, 12837, 12838, 12839, -1, 12835, 12838, 12837, -1, 12839, 12840, 12841, -1, 12838, 12840, 12839, -1, 12841, 12842, 12843, -1, 12840, 12842, 12841, -1, 12843, 12844, 12845, -1, 12842, 12844, 12843, -1, 12845, 12846, 12847, -1, 12844, 12846, 12845, -1, 12847, 12848, 12849, -1, 12846, 12848, 12847, -1, 12849, 12850, 12851, -1, 12848, 12850, 12849, -1, 12851, 12852, 12853, -1, 12850, 12852, 12851, -1, 12853, 12854, 12855, -1, 12852, 12854, 12853, -1, 12855, 12856, 12857, -1, 12854, 12856, 12855, -1, 12857, 12858, 12859, -1, 12856, 12858, 12857, -1, 12859, 12860, 12861, -1, 12858, 12860, 12859, -1, 12862, 12863, 12864, -1, 12865, 12863, 12862, -1, 12866, 12867, 12868, -1, 12869, 12867, 12866, -1, 12870, 12871, 12872, -1, 12872, 12871, 12873, -1, 12874, 12875, 12876, -1, 12877, 12875, 12874, -1, 12756, 12862, 12869, -1, 12758, 12756, 12869, -1, 12754, 12862, 12756, -1, 12760, 12758, 12869, -1, 12751, 12862, 12754, -1, 12762, 12760, 12869, -1, 12750, 12862, 12751, -1, 12764, 12762, 12869, -1, 12878, 12862, 12750, -1, 12766, 12764, 12869, -1, 12879, 12862, 12878, -1, 12768, 12766, 12869, -1, 12814, 12880, 12881, -1, 12814, 12882, 12880, -1, 12814, 12812, 12882, -1, 12810, 12879, 12882, -1, 12810, 12862, 12879, -1, 12810, 12882, 12812, -1, 12816, 12814, 12881, -1, 12807, 12862, 12810, -1, 12818, 12881, 12883, -1, 12818, 12816, 12881, -1, 12806, 12862, 12807, -1, 12820, 12883, 12884, -1, 12820, 12818, 12883, -1, 12822, 12885, 12886, -1, 12822, 12884, 12885, -1, 12822, 12820, 12884, -1, 12824, 12822, 12886, -1, 12826, 12886, 12887, -1, 12826, 12824, 12886, -1, 12828, 12887, 12888, -1, 12828, 12826, 12887, -1, 12865, 12889, 12890, -1, 12865, 12891, 12889, -1, 12865, 12892, 12891, -1, 12865, 12893, 12892, -1, 12865, 12894, 12893, -1, 12865, 12806, 12894, -1, 12865, 12862, 12806, -1, 12786, 12770, 12768, -1, 12786, 12784, 12770, -1, 12782, 12772, 12770, -1, 12782, 12770, 12784, -1, 12779, 12774, 12772, -1, 12779, 12776, 12774, -1, 12779, 12772, 12782, -1, 12875, 12865, 12890, -1, 12875, 12895, 12896, -1, 12875, 12897, 12895, -1, 12875, 12890, 12897, -1, 12778, 12776, 12779, -1, 12866, 12786, 12768, -1, 12866, 12768, 12869, -1, 12866, 12788, 12786, -1, 12866, 12790, 12788, -1, 12866, 12792, 12790, -1, 12898, 12899, 12776, -1, 12898, 12776, 12778, -1, 12794, 12792, 12866, -1, 12900, 12888, 12899, -1, 12900, 12899, 12898, -1, 12796, 12794, 12866, -1, 12798, 12796, 12866, -1, 12873, 12800, 12798, -1, 12873, 12802, 12800, -1, 12873, 12798, 12866, -1, 12804, 12802, 12873, -1, 12901, 12804, 12873, -1, 12902, 12901, 12873, -1, 12840, 12903, 12904, -1, 12840, 12900, 12903, -1, 12842, 12840, 12904, -1, 12838, 12888, 12900, -1, 12838, 12900, 12840, -1, 12838, 12828, 12888, -1, 12844, 12904, 12905, -1, 12844, 12842, 12904, -1, 12835, 12830, 12828, -1, 12835, 12832, 12830, -1, 12835, 12828, 12838, -1, 12846, 12905, 12906, -1, 12846, 12844, 12905, -1, 12834, 12832, 12835, -1, 12848, 12846, 12906, -1, 12848, 12906, 12907, -1, 12908, 12909, 12832, -1, 12908, 12832, 12834, -1, 12850, 12907, 12910, -1, 12850, 12848, 12907, -1, 12911, 12912, 12909, -1, 12911, 12913, 12912, -1, 12911, 12909, 12908, -1, 12852, 12914, 12915, -1, 12852, 12910, 12914, -1, 12852, 12850, 12910, -1, 12916, 12913, 12911, -1, 12916, 12896, 12913, -1, 12854, 12852, 12915, -1, 12854, 12915, 12902, -1, 12917, 12896, 12916, -1, 12856, 12902, 12873, -1, 12856, 12854, 12902, -1, 12858, 12856, 12873, -1, 12860, 12858, 12873, -1, 12871, 12918, 12860, -1, 12871, 12919, 12918, -1, 12871, 12920, 12919, -1, 12871, 12921, 12920, -1, 12871, 12922, 12921, -1, 12871, 12923, 12922, -1, 12871, 12860, 12873, -1, 12876, 12875, 12896, -1, 12876, 12923, 12871, -1, 12876, 12924, 12923, -1, 12876, 12925, 12924, -1, 12876, 12917, 12925, -1, 12876, 12896, 12917, -1, 12864, 12757, 12867, -1, 12757, 12759, 12867, -1, 12864, 12755, 12757, -1, 12759, 12761, 12867, -1, 12864, 12753, 12755, -1, 12761, 12763, 12867, -1, 12864, 12752, 12753, -1, 12763, 12765, 12867, -1, 12864, 12926, 12752, -1, 12765, 12767, 12867, -1, 12864, 12927, 12926, -1, 12767, 12769, 12867, -1, 12928, 12813, 12929, -1, 12813, 12815, 12929, -1, 12927, 12811, 12928, -1, 12864, 12811, 12927, -1, 12928, 12811, 12813, -1, 12929, 12817, 12930, -1, 12815, 12817, 12929, -1, 12864, 12809, 12811, -1, 12930, 12819, 12931, -1, 12817, 12819, 12930, -1, 12864, 12808, 12809, -1, 12931, 12821, 12932, -1, 12819, 12821, 12931, -1, 12932, 12823, 12933, -1, 12821, 12823, 12932, -1, 12933, 12825, 12934, -1, 12823, 12825, 12933, -1, 12934, 12827, 12935, -1, 12825, 12827, 12934, -1, 12935, 12829, 12936, -1, 12827, 12829, 12935, -1, 12937, 12863, 12938, -1, 12939, 12863, 12937, -1, 12940, 12863, 12939, -1, 12941, 12863, 12940, -1, 12942, 12863, 12941, -1, 12808, 12863, 12942, -1, 12864, 12863, 12808, -1, 12771, 12787, 12769, -1, 12785, 12787, 12771, -1, 12773, 12783, 12771, -1, 12775, 12783, 12773, -1, 12771, 12783, 12785, -1, 12775, 12781, 12783, -1, 12863, 12877, 12938, -1, 12943, 12877, 12944, -1, 12945, 12877, 12943, -1, 12938, 12877, 12945, -1, 12777, 12780, 12775, -1, 12775, 12780, 12781, -1, 12787, 12868, 12769, -1, 12769, 12868, 12867, -1, 12789, 12868, 12787, -1, 12791, 12868, 12789, -1, 12793, 12868, 12791, -1, 12946, 12947, 12777, -1, 12777, 12947, 12780, -1, 12793, 12795, 12868, -1, 12936, 12948, 12946, -1, 12829, 12948, 12936, -1, 12946, 12948, 12947, -1, 12795, 12797, 12868, -1, 12797, 12799, 12868, -1, 12801, 12872, 12799, -1, 12803, 12872, 12801, -1, 12799, 12872, 12868, -1, 12803, 12805, 12872, -1, 12805, 12949, 12872, -1, 12949, 12950, 12872, -1, 12951, 12843, 12952, -1, 12953, 12843, 12951, -1, 12841, 12843, 12953, -1, 12953, 12839, 12841, -1, 12948, 12839, 12953, -1, 12829, 12839, 12948, -1, 12831, 12839, 12829, -1, 12843, 12845, 12952, -1, 12831, 12837, 12839, -1, 12952, 12847, 12954, -1, 12845, 12847, 12952, -1, 12831, 12836, 12837, -1, 12833, 12836, 12831, -1, 12954, 12849, 12955, -1, 12847, 12849, 12954, -1, 12956, 12957, 12833, -1, 12833, 12957, 12836, -1, 12955, 12851, 12958, -1, 12849, 12851, 12955, -1, 12956, 12959, 12957, -1, 12960, 12959, 12956, -1, 12961, 12959, 12960, -1, 12958, 12853, 12962, -1, 12851, 12853, 12958, -1, 12961, 12963, 12959, -1, 12962, 12855, 12964, -1, 12853, 12855, 12962, -1, 12877, 12965, 12944, -1, 12944, 12965, 12961, -1, 12961, 12965, 12963, -1, 12855, 12857, 12964, -1, 12964, 12857, 12950, -1, 12950, 12857, 12872, -1, 12857, 12859, 12872, -1, 12859, 12861, 12872, -1, 12877, 12874, 12965, -1, 12966, 12874, 12967, -1, 12968, 12874, 12966, -1, 12965, 12874, 12968, -1, 12874, 12870, 12967, -1, 12861, 12870, 12872, -1, 12969, 12870, 12861, -1, 12970, 12870, 12969, -1, 12971, 12870, 12970, -1, 12972, 12870, 12971, -1, 12973, 12870, 12972, -1, 12967, 12870, 12973, -1, 12860, 12918, 12861, -1, 12861, 12918, 12969, -1, 12969, 12919, 12970, -1, 12918, 12919, 12969, -1, 12970, 12920, 12971, -1, 12919, 12920, 12970, -1, 12971, 12921, 12972, -1, 12920, 12921, 12971, -1, 12972, 12922, 12973, -1, 12921, 12922, 12972, -1, 12973, 12923, 12967, -1, 12922, 12923, 12973, -1, 12967, 12924, 12966, -1, 12923, 12924, 12967, -1, 12966, 12925, 12968, -1, 12924, 12925, 12966, -1, 12968, 12917, 12965, -1, 12925, 12917, 12968, -1, 12965, 12916, 12963, -1, 12917, 12916, 12965, -1, 12963, 12911, 12959, -1, 12916, 12911, 12963, -1, 12959, 12908, 12957, -1, 12911, 12908, 12959, -1, 12957, 12834, 12836, -1, 12908, 12834, 12957, -1, 12832, 12909, 12833, -1, 12833, 12909, 12956, -1, 12956, 12912, 12960, -1, 12909, 12912, 12956, -1, 12960, 12913, 12961, -1, 12912, 12913, 12960, -1, 12961, 12896, 12944, -1, 12913, 12896, 12961, -1, 12944, 12895, 12943, -1, 12896, 12895, 12944, -1, 12943, 12897, 12945, -1, 12895, 12897, 12943, -1, 12945, 12890, 12938, -1, 12897, 12890, 12945, -1, 12938, 12889, 12937, -1, 12890, 12889, 12938, -1, 12937, 12891, 12939, -1, 12889, 12891, 12937, -1, 12939, 12892, 12940, -1, 12891, 12892, 12939, -1, 12940, 12893, 12941, -1, 12892, 12893, 12940, -1, 12941, 12894, 12942, -1, 12893, 12894, 12941, -1, 12942, 12806, 12808, -1, 12894, 12806, 12942, -1, 12804, 12901, 12805, -1, 12805, 12901, 12949, -1, 12949, 12902, 12950, -1, 12901, 12902, 12949, -1, 12950, 12915, 12964, -1, 12902, 12915, 12950, -1, 12964, 12914, 12962, -1, 12915, 12914, 12964, -1, 12962, 12910, 12958, -1, 12914, 12910, 12962, -1, 12958, 12907, 12955, -1, 12910, 12907, 12958, -1, 12955, 12906, 12954, -1, 12907, 12906, 12955, -1, 12954, 12905, 12952, -1, 12906, 12905, 12954, -1, 12952, 12904, 12951, -1, 12905, 12904, 12952, -1, 12951, 12903, 12953, -1, 12904, 12903, 12951, -1, 12953, 12900, 12948, -1, 12903, 12900, 12953, -1, 12948, 12898, 12947, -1, 12900, 12898, 12948, -1, 12947, 12778, 12780, -1, 12898, 12778, 12947, -1, 12776, 12899, 12777, -1, 12777, 12899, 12946, -1, 12946, 12888, 12936, -1, 12899, 12888, 12946, -1, 12936, 12887, 12935, -1, 12888, 12887, 12936, -1, 12935, 12886, 12934, -1, 12887, 12886, 12935, -1, 12934, 12885, 12933, -1, 12886, 12885, 12934, -1, 12933, 12884, 12932, -1, 12885, 12884, 12933, -1, 12932, 12883, 12931, -1, 12884, 12883, 12932, -1, 12931, 12881, 12930, -1, 12883, 12881, 12931, -1, 12930, 12880, 12929, -1, 12881, 12880, 12930, -1, 12929, 12882, 12928, -1, 12880, 12882, 12929, -1, 12928, 12879, 12927, -1, 12882, 12879, 12928, -1, 12927, 12878, 12926, -1, 12879, 12878, 12927, -1, 12926, 12750, 12752, -1, 12878, 12750, 12926, -1, 12871, 12870, 12876, -1, 12876, 12870, 12874, -1, 12866, 12868, 12873, -1, 12873, 12868, 12872, -1, 12862, 12864, 12869, -1, 12869, 12864, 12867, -1, 12875, 12877, 12865, -1, 12865, 12877, 12863, -1, 12974, 12975, 12976, -1, 12977, 12978, 12979, -1, 12980, 12981, 12982, -1, 12983, 12984, 12985, -1, 12983, 12985, 12986, -1, 12980, 12987, 12988, -1, 12989, 12990, 12991, -1, 12980, 12988, 12992, -1, 12980, 12982, 12987, -1, 12993, 12980, 12992, -1, 12993, 12994, 12995, -1, 12993, 12996, 12994, -1, 12993, 12992, 12996, -1, 12997, 12998, 12999, -1, 12982, 13000, 13001, -1, 12997, 13002, 12998, -1, 12997, 13003, 13002, -1, 12982, 13004, 13000, -1, 13005, 13006, 13007, -1, 13008, 12999, 13009, -1, 13010, 13011, 13012, -1, 13008, 13009, 13013, -1, 13008, 13013, 13014, -1, 13008, 12997, 12999, -1, 13015, 12986, 13016, -1, 13008, 13014, 13017, -1, 13015, 13016, 13018, -1, 13010, 13019, 13011, -1, 13020, 13021, 13022, -1, 13023, 13024, 13025, -1, 13026, 13027, 13028, -1, 13023, 13025, 13029, -1, 13023, 13029, 13030, -1, 13026, 13031, 13032, -1, 13023, 13033, 13024, -1, 13026, 13032, 13027, -1, 13020, 13034, 13021, -1, 13035, 13018, 13036, -1, 13035, 13036, 13037, -1, 13038, 13023, 13030, -1, 13038, 12974, 13039, -1, 13038, 13030, 12974, -1, 13038, 13039, 13040, -1, 13041, 13042, 13043, -1, 13041, 13044, 13042, -1, 13045, 12981, 12980, -1, 13046, 13047, 13048, -1, 13045, 13049, 12981, -1, 13046, 13012, 13047, -1, 13050, 13051, 13052, -1, 13050, 13053, 13051, -1, 13054, 13055, 13056, -1, 13054, 13057, 13055, -1, 13058, 13045, 12980, -1, 13054, 13056, 13059, -1, 13054, 13060, 13057, -1, 13061, 13062, 13063, -1, 13064, 12993, 12995, -1, 13064, 13058, 12980, -1, 13064, 12995, 13065, -1, 13064, 12980, 12993, -1, 13066, 12991, 13003, -1, 13061, 13067, 13062, -1, 13068, 13019, 13010, -1, 13066, 12997, 13008, -1, 13068, 13069, 13019, -1, 13066, 13003, 12997, -1, 13070, 12984, 12983, -1, 13071, 13048, 13072, -1, 13073, 13066, 13008, -1, 13074, 13059, 12978, -1, 13070, 13075, 12984, -1, 13074, 12978, 12977, -1, 13076, 13073, 13008, -1, 13076, 13008, 13017, -1, 13076, 13017, 13077, -1, 13078, 13026, 13028, -1, 13078, 13028, 12990, -1, 13078, 12990, 12989, -1, 13079, 13033, 13023, -1, 13079, 13080, 13033, -1, 13081, 13079, 13023, -1, 12981, 13022, 13004, -1, 12981, 13004, 12982, -1, 13082, 12986, 13015, -1, 13083, 13023, 13038, -1, 13084, 12977, 13034, -1, 13083, 13040, 13085, -1, 13083, 13081, 13023, -1, 13082, 12983, 12986, -1, 13084, 13034, 13020, -1, 13083, 13038, 13040, -1, 13086, 13018, 13035, -1, 13087, 13049, 13045, -1, 13087, 13088, 13049, -1, 13087, 13045, 13058, -1, 13086, 13015, 13018, -1, 13089, 13012, 13046, -1, 13090, 13065, 13091, -1, 13089, 13010, 13012, -1, 13092, 13037, 13067, -1, 13093, 13094, 13044, -1, 13090, 13064, 13065, -1, 13090, 13058, 13064, -1, 13090, 13087, 13058, -1, 13092, 13067, 13061, -1, 13095, 12991, 13066, -1, 13093, 13044, 13041, -1, 13096, 13097, 13053, -1, 13095, 13066, 13073, -1, 13095, 12989, 12991, -1, 13098, 13076, 13077, -1, 13098, 13095, 13073, -1, 13099, 13046, 13048, -1, 13098, 13073, 13076, -1, 13096, 13053, 13050, -1, 13099, 13048, 13071, -1, 13098, 13077, 13100, -1, 13101, 13102, 13080, -1, 13103, 13075, 13070, -1, 13104, 13043, 13069, -1, 13103, 13052, 13075, -1, 13101, 13080, 13079, -1, 13104, 13069, 13068, -1, 13101, 13079, 13081, -1, 13105, 13085, 13106, -1, 13107, 13059, 13074, -1, 13107, 13054, 13059, -1, 13105, 13083, 13085, -1, 13107, 13060, 13054, -1, 13105, 13081, 13083, -1, 13108, 13031, 13026, -1, 13105, 13101, 13081, -1, 13108, 13026, 13078, -1, 13109, 13088, 13087, -1, 13109, 13110, 13088, -1, 13049, 13020, 13022, -1, 13109, 13087, 13090, -1, 13049, 13022, 12981, -1, 13049, 13084, 13020, -1, 13111, 13109, 13090, -1, 13112, 12983, 13082, -1, 13113, 13091, 13114, -1, 13113, 13090, 13091, -1, 13115, 13010, 13089, -1, 13113, 13111, 13090, -1, 13112, 13070, 12983, -1, 13116, 12989, 13095, -1, 13116, 13078, 12989, -1, 13117, 13037, 13092, -1, 13117, 13035, 13037, -1, 13115, 13068, 13010, -1, 13118, 13082, 13015, -1, 13119, 12977, 13084, -1, 13119, 13074, 12977, -1, 13120, 13116, 13095, -1, 13118, 13015, 13086, -1, 13121, 13095, 13098, -1, 13121, 13098, 13100, -1, 13122, 13123, 13094, -1, 13121, 13100, 13124, -1, 13121, 13120, 13095, -1, 13125, 13126, 13102, -1, 13122, 13094, 13093, -1, 13127, 13097, 13096, -1, 13128, 13089, 13046, -1, 13125, 13102, 13101, -1, 13127, 13014, 13097, -1, 13125, 13101, 13105, -1, 13129, 13052, 13103, -1, 13130, 13125, 13105, -1, 13129, 13050, 13052, -1, 13128, 13046, 13099, -1, 13131, 13072, 13132, -1, 13133, 13130, 13105, -1, 13131, 13071, 13072, -1, 13133, 13106, 13134, -1, 13133, 13105, 13106, -1, 13135, 13136, 13110, -1, 13135, 13110, 13109, -1, 13137, 13043, 13104, -1, 13135, 13109, 13111, -1, 13138, 13114, 13139, -1, 13137, 13041, 13043, -1, 13138, 13135, 13111, -1, 13088, 13084, 13049, -1, 13138, 13113, 13114, -1, 13140, 13103, 13070, -1, 13138, 13111, 13113, -1, 13140, 13070, 13112, -1, 13141, 13108, 13078, -1, 13141, 13116, 13120, -1, 13141, 13078, 13116, -1, 13142, 13121, 13124, -1, 13143, 13035, 13117, -1, 13142, 13124, 13144, -1, 13142, 13141, 13120, -1, 13143, 13086, 13035, -1, 13145, 13104, 13068, -1, 13142, 13120, 13121, -1, 13146, 13082, 13118, -1, 13145, 13068, 13115, -1, 13147, 13126, 13125, -1, 13146, 13112, 13082, -1, 13147, 13125, 13130, -1, 13148, 13107, 13074, -1, 13147, 13149, 13126, -1, 13150, 13017, 13014, -1, 13148, 13074, 13119, -1, 13151, 13147, 13130, -1, 13151, 13130, 13133, -1, 13150, 13014, 13127, -1, 13148, 13152, 13060, -1, 13151, 13133, 13134, -1, 13148, 13060, 13107, -1, 13151, 13134, 13153, -1, 13154, 13115, 13089, -1, 13154, 13089, 13128, -1, 13155, 13050, 13129, -1, 13156, 13136, 13135, -1, 13156, 13152, 13136, -1, 13155, 13096, 13050, -1, 13157, 13152, 13156, -1, 13157, 13158, 13152, -1, 13159, 13160, 13123, -1, 13157, 13156, 13135, -1, 13161, 13135, 13138, -1, 13161, 13157, 13135, -1, 13159, 13123, 13122, -1, 13161, 13158, 13157, -1, 13161, 13138, 13139, -1, 13161, 13139, 13158, -1, 13162, 13141, 13142, -1, 13163, 13071, 13131, -1, 13163, 13099, 13071, -1, 13164, 13129, 13103, -1, 13162, 13031, 13108, -1, 13162, 13108, 13141, -1, 13165, 13162, 13142, -1, 13164, 13103, 13140, -1, 13165, 13031, 13162, -1, 13166, 13093, 13041, -1, 13165, 13167, 13031, -1, 13168, 13165, 13142, -1, 13166, 13041, 13137, -1, 13168, 13144, 13167, -1, 13168, 13142, 13144, -1, 13168, 13167, 13165, -1, 13169, 13170, 13149, -1, 13169, 13149, 13147, -1, 13171, 13118, 13086, -1, 13171, 13086, 13143, -1, 13110, 13148, 13119, -1, 13172, 13170, 13169, -1, 13172, 13169, 13147, -1, 13110, 13119, 13084, -1, 13110, 13084, 13088, -1, 13172, 13173, 13170, -1, 13174, 13147, 13151, -1, 13175, 13140, 13112, -1, 13174, 13153, 13173, -1, 13175, 13112, 13146, -1, 13174, 13151, 13153, -1, 13174, 13172, 13147, -1, 13174, 13173, 13172, -1, 13176, 13017, 13150, -1, 13177, 13104, 13145, -1, 13176, 13077, 13017, -1, 13177, 13137, 13104, -1, 13178, 13096, 13155, -1, 13179, 13115, 13154, -1, 13178, 13127, 13096, -1, 13179, 13145, 13115, -1, 13180, 13099, 13163, -1, 13181, 13118, 13171, -1, 13180, 13128, 13099, -1, 13181, 13146, 13118, -1, 13182, 13129, 13164, -1, 13183, 13160, 13159, -1, 13183, 13184, 13160, -1, 13182, 13155, 13129, -1, 13185, 13122, 13093, -1, 13186, 13164, 13140, -1, 13185, 13093, 13166, -1, 13187, 13006, 13005, -1, 13136, 13152, 13148, -1, 13188, 13189, 13006, -1, 13186, 13140, 13175, -1, 13136, 13148, 13110, -1, 13190, 13077, 13176, -1, 13188, 13006, 13187, -1, 13190, 13100, 13077, -1, 13191, 13150, 13127, -1, 13192, 13166, 13137, -1, 13193, 13194, 13189, -1, 13191, 13127, 13178, -1, 13193, 13189, 13188, -1, 13192, 13137, 13177, -1, 13195, 13154, 13128, -1, 13196, 13175, 13146, -1, 13195, 13128, 13180, -1, 13196, 13146, 13181, -1, 13197, 13177, 13145, -1, 13198, 13194, 13193, -1, 13197, 13145, 13179, -1, 13199, 13155, 13182, -1, 13198, 13200, 13194, -1, 13201, 12994, 13184, -1, 13202, 13005, 13203, -1, 13199, 13178, 13155, -1, 13201, 13184, 13183, -1, 13202, 13187, 13005, -1, 13204, 13164, 13186, -1, 13204, 13182, 13164, -1, 13205, 13188, 13187, -1, 13206, 13100, 13190, -1, 13205, 13187, 13202, -1, 13207, 13122, 13185, -1, 13206, 13124, 13100, -1, 13207, 13159, 13122, -1, 13208, 13209, 13200, -1, 13208, 13200, 13198, -1, 13210, 13150, 13191, -1, 13210, 13176, 13150, -1, 13211, 13202, 13203, -1, 13211, 13203, 13212, -1, 13213, 13185, 13166, -1, 13214, 13186, 13175, -1, 13215, 13193, 13188, -1, 13214, 13175, 13196, -1, 13213, 13166, 13192, -1, 13216, 13191, 13178, -1, 13215, 13188, 13205, -1, 13216, 13178, 13199, -1, 13217, 13179, 13154, -1, 13218, 13182, 13204, -1, 13217, 13154, 13195, -1, 13219, 13220, 13209, -1, 13221, 13177, 13197, -1, 13219, 13209, 13208, -1, 13218, 13199, 13182, -1, 13222, 13205, 13202, -1, 13221, 13192, 13177, -1, 13223, 13144, 13124, -1, 13223, 13167, 13144, -1, 13223, 13224, 13167, -1, 13225, 12994, 13201, -1, 13222, 13202, 13211, -1, 13223, 13124, 13206, -1, 13225, 12995, 12994, -1, 13226, 13176, 13210, -1, 13227, 13198, 13193, -1, 13227, 13193, 13215, -1, 13226, 13190, 13176, -1, 13228, 13210, 13191, -1, 13229, 13211, 13212, -1, 13228, 13191, 13216, -1, 13230, 13205, 13222, -1, 13231, 13183, 13159, -1, 13231, 13159, 13207, -1, 13230, 13215, 13205, -1, 13232, 13204, 13186, -1, 13232, 13186, 13214, -1, 13233, 13207, 13185, -1, 13234, 13216, 13199, -1, 13235, 13236, 13220, -1, 13235, 13220, 13219, -1, 13234, 13199, 13218, -1, 13233, 13185, 13213, -1, 13237, 13190, 13226, -1, 13238, 13211, 13229, -1, 13237, 13206, 13190, -1, 13239, 13179, 13217, -1, 13238, 13222, 13211, -1, 13239, 13197, 13179, -1, 13240, 13213, 13192, -1, 13241, 13210, 13228, -1, 13240, 13192, 13221, -1, 13241, 13226, 13210, -1, 13242, 13198, 13227, -1, 13242, 13208, 13198, -1, 13024, 13218, 13204, -1, 13243, 13215, 13230, -1, 13243, 13227, 13215, -1, 13024, 13204, 13232, -1, 13244, 13236, 13235, -1, 13245, 13216, 13234, -1, 13245, 13228, 13216, -1, 13246, 12995, 13225, -1, 13244, 13247, 13236, -1, 13248, 13249, 13224, -1, 13248, 13224, 13223, -1, 13248, 13223, 13206, -1, 13246, 13065, 12995, -1, 13250, 13183, 13231, -1, 13248, 13206, 13237, -1, 13251, 13230, 13222, -1, 13252, 13226, 13241, -1, 13252, 13237, 13226, -1, 13251, 13222, 13238, -1, 13250, 13201, 13183, -1, 13253, 13212, 13254, -1, 13253, 13229, 13212, -1, 13033, 13234, 13218, -1, 13255, 13197, 13239, -1, 13033, 13218, 13024, -1, 13256, 13208, 13242, -1, 13255, 13221, 13197, -1, 13257, 13207, 13233, -1, 13256, 13219, 13208, -1, 13258, 13227, 13243, -1, 13259, 13241, 13228, -1, 13259, 13228, 13245, -1, 13257, 13231, 13207, -1, 13258, 13242, 13227, -1, 13260, 13249, 13248, -1, 13260, 13248, 13237, -1, 13260, 13237, 13252, -1, 13261, 13243, 13230, -1, 13080, 13234, 13033, -1, 13261, 13230, 13251, -1, 13080, 13245, 13234, -1, 13262, 13241, 13259, -1, 13263, 13264, 13265, -1, 13266, 13267, 13247, -1, 13262, 13252, 13241, -1, 13266, 13247, 13244, -1, 13102, 13245, 13080, -1, 13263, 13268, 13264, -1, 13269, 13213, 13240, -1, 13269, 13233, 13213, -1, 13102, 13259, 13245, -1, 13270, 13238, 13229, -1, 13270, 13229, 13253, -1, 13271, 13249, 13260, -1, 13272, 13091, 13065, -1, 13271, 13252, 13262, -1, 13271, 13170, 13249, -1, 13271, 13260, 13252, -1, 13126, 13259, 13102, -1, 13272, 13065, 13246, -1, 13273, 13225, 13201, -1, 13273, 13201, 13250, -1, 13274, 13219, 13256, -1, 13126, 13262, 13259, -1, 13274, 13235, 13219, -1, 13149, 13262, 13126, -1, 13275, 13256, 13242, -1, 13149, 13271, 13262, -1, 13149, 13170, 13271, -1, 13275, 13242, 13258, -1, 13276, 13277, 13268, -1, 13278, 13243, 13261, -1, 13279, 13253, 13254, -1, 13279, 13270, 13253, -1, 13276, 13268, 13263, -1, 13278, 13258, 13243, -1, 13280, 13240, 13221, -1, 13281, 13270, 13279, -1, 13280, 13221, 13255, -1, 13281, 13279, 13254, -1, 13282, 13254, 13283, -1, 13284, 13238, 13270, -1, 13282, 13281, 13254, -1, 13285, 13231, 13257, -1, 13285, 13250, 13231, -1, 13284, 13251, 13238, -1, 13286, 13287, 13288, -1, 13286, 13282, 13283, -1, 13286, 13283, 13287, -1, 13289, 13284, 13270, -1, 13289, 13281, 13282, -1, 13290, 13291, 13267, -1, 13289, 13286, 13288, -1, 13289, 13282, 13286, -1, 13289, 13288, 13292, -1, 13290, 13267, 13266, -1, 13289, 13270, 13281, -1, 13293, 13244, 13235, -1, 13294, 13257, 13233, -1, 13294, 13233, 13269, -1, 13295, 13296, 13297, -1, 13293, 13235, 13274, -1, 13295, 13298, 13042, -1, 13299, 13300, 13296, -1, 13299, 13295, 13042, -1, 13301, 13274, 13256, -1, 13302, 13114, 13091, -1, 13299, 13042, 13044, -1, 13301, 13256, 13275, -1, 13299, 13296, 13295, -1, 13302, 13091, 13272, -1, 13297, 13251, 13284, -1, 13303, 13299, 13044, -1, 13297, 13261, 13251, -1, 13303, 13300, 13299, -1, 13304, 13258, 13278, -1, 13305, 13131, 13132, -1, 13305, 13163, 13131, -1, 13306, 13307, 13277, -1, 13306, 13277, 13276, -1, 13308, 13246, 13225, -1, 13304, 13275, 13258, -1, 13309, 13163, 13305, -1, 13309, 13305, 13132, -1, 13308, 13225, 13273, -1, 13310, 13132, 13264, -1, 13311, 13312, 13291, -1, 13310, 13309, 13132, -1, 13311, 13291, 13290, -1, 13313, 13268, 13277, -1, 13313, 13264, 13268, -1, 13313, 13310, 13264, -1, 13314, 13269, 13240, -1, 13314, 13240, 13280, -1, 13315, 13163, 13309, -1, 13315, 13309, 13310, -1, 13315, 13313, 13277, -1, 13316, 13273, 13250, -1, 13315, 13310, 13313, -1, 13316, 13250, 13285, -1, 13315, 13277, 13307, -1, 13315, 13180, 13163, -1, 13317, 13266, 13244, -1, 13317, 13244, 13293, -1, 13318, 13274, 13301, -1, 13319, 13217, 13195, -1, 13318, 13293, 13274, -1, 13319, 13320, 13321, -1, 13322, 13239, 13217, -1, 13322, 13217, 13319, -1, 13296, 13261, 13297, -1, 13322, 13319, 13321, -1, 13322, 13321, 13323, -1, 13324, 13257, 13294, -1, 13324, 13285, 13257, -1, 13325, 13139, 13114, -1, 13326, 13322, 13323, -1, 13325, 13327, 13158, -1, 13325, 13158, 13139, -1, 13296, 13278, 13261, -1, 13325, 13114, 13302, -1, 13328, 13301, 13275, -1, 13326, 13239, 13322, -1, 13329, 13320, 13307, -1, 13328, 13275, 13304, -1, 13330, 13061, 13063, -1, 13330, 13063, 13331, -1, 13332, 13331, 13333, -1, 13334, 13312, 13311, -1, 13332, 13333, 13335, -1, 13329, 13307, 13306, -1, 13334, 13336, 13312, -1, 13332, 13330, 13331, -1, 13337, 13265, 13338, -1, 13337, 13263, 13265, -1, 13339, 13143, 13117, -1, 13340, 13341, 13342, -1, 13343, 13272, 13246, -1, 13344, 13290, 13266, -1, 13340, 13171, 13143, -1, 13344, 13266, 13317, -1, 13340, 13339, 13341, -1, 13340, 13143, 13339, -1, 13343, 13246, 13308, -1, 13345, 13343, 13308, -1, 13346, 13293, 13318, -1, 13347, 13171, 13340, -1, 13345, 13308, 13273, -1, 13346, 13317, 13293, -1, 13347, 13340, 13342, -1, 13345, 13273, 13316, -1, 13348, 13297, 13284, -1, 13348, 13284, 13289, -1, 13348, 13289, 13292, -1, 13348, 13295, 13297, -1, 13348, 13298, 13295, -1, 13300, 13278, 13296, -1, 13348, 13292, 13298, -1, 13349, 13300, 13303, -1, 13300, 13304, 13278, -1, 13349, 13350, 13300, -1, 13349, 13351, 13350, -1, 13352, 13301, 13328, -1, 13352, 13318, 13301, -1, 13353, 13349, 13303, -1, 13354, 13294, 13269, -1, 13354, 13269, 13314, -1, 13355, 13316, 13285, -1, 13356, 13044, 13094, -1, 13356, 13094, 13123, -1, 13356, 13303, 13044, -1, 13355, 13285, 13324, -1, 13356, 13353, 13303, -1, 13357, 13307, 13320, -1, 13357, 13315, 13307, -1, 13357, 13319, 13195, -1, 13358, 13263, 13337, -1, 13357, 13180, 13315, -1, 13357, 13320, 13319, -1, 13357, 13195, 13180, -1, 13359, 13336, 13334, -1, 13360, 13239, 13326, -1, 13360, 13255, 13239, -1, 13359, 13361, 13336, -1, 13360, 13280, 13255, -1, 13358, 13276, 13263, -1, 13362, 13290, 13344, -1, 13363, 13360, 13326, -1, 13362, 13311, 13290, -1, 13364, 13323, 13365, -1, 12985, 13321, 13320, -1, 13350, 13328, 13304, -1, 13350, 13304, 13300, -1, 13364, 13363, 13326, -1, 12985, 13320, 13329, -1, 13364, 13365, 13051, -1, 13364, 13326, 13323, -1, 13366, 13338, 13367, -1, 13366, 13337, 13338, -1, 13368, 13061, 13330, -1, 13369, 13344, 13317, -1, 13368, 13092, 13061, -1, 13369, 13317, 13346, -1, 13368, 13330, 13332, -1, 13370, 13092, 13368, -1, 13371, 13272, 13343, -1, 13370, 13117, 13092, -1, 13370, 13339, 13117, -1, 13372, 13339, 13370, -1, 13371, 13302, 13272, -1, 13372, 13368, 13332, -1, 13372, 13370, 13368, -1, 13373, 13343, 13345, -1, 13374, 13372, 13332, -1, 13375, 13283, 13376, -1, 13374, 13335, 13377, -1, 13374, 13332, 13335, -1, 13378, 13339, 13372, -1, 13378, 13372, 13374, -1, 13375, 13287, 13283, -1, 13378, 13374, 13377, -1, 13378, 13379, 13341, -1, 13378, 13377, 13379, -1, 13380, 13318, 13352, -1, 13378, 13341, 13339, -1, 13002, 13324, 13294, -1, 13381, 13181, 13171, -1, 13380, 13346, 13318, -1, 13381, 13171, 13347, -1, 13002, 13294, 13354, -1, 13381, 13196, 13181, -1, 13382, 13383, 13361, -1, 13382, 13361, 13359, -1, 13384, 13381, 13347, -1, 13385, 13276, 13358, -1, 13386, 13334, 13311, -1, 13387, 13388, 13389, -1, 13387, 13342, 13388, -1, 13385, 13306, 13276, -1, 13387, 13384, 13347, -1, 13386, 13311, 13362, -1, 13390, 13316, 13355, -1, 13387, 13347, 13342, -1, 13390, 13345, 13316, -1, 13390, 13373, 13345, -1, 13011, 13288, 13287, -1, 13391, 13351, 13349, -1, 13391, 13349, 13353, -1, 13391, 13392, 13351, -1, 13011, 13287, 13375, -1, 12984, 13321, 12985, -1, 13351, 13328, 13350, -1, 13351, 13352, 13328, -1, 13393, 13391, 13353, -1, 12984, 13323, 13321, -1, 13394, 13123, 13160, -1, 13395, 13358, 13337, -1, 13394, 13393, 13353, -1, 13396, 13344, 13369, -1, 13394, 13356, 13123, -1, 13394, 13353, 13356, -1, 13396, 13362, 13344, -1, 13395, 13337, 13366, -1, 13397, 13280, 13360, -1, 13397, 13360, 13363, -1, 13398, 13325, 13302, -1, 13397, 13314, 13280, -1, 13398, 13327, 13325, -1, 13398, 13032, 13327, -1, 13398, 13302, 13371, -1, 13016, 13306, 13385, -1, 13399, 13397, 13363, -1, 13016, 13329, 13306, -1, 13000, 13369, 13346, -1, 13400, 13399, 13363, -1, 13000, 13346, 13380, -1, 13400, 13364, 13051, -1, 13400, 13363, 13364, -1, 13400, 13051, 13053, -1, 13401, 13196, 13381, -1, 13401, 13214, 13196, -1, 13401, 13381, 13384, -1, 13062, 13366, 13367, -1, 13056, 13402, 13383, -1, 13056, 13383, 13382, -1, 13403, 13371, 13343, -1, 13403, 13343, 13373, -1, 13019, 13292, 13288, -1, 13403, 13398, 13371, -1, 13404, 13401, 13384, -1, 13019, 13288, 13011, -1, 13405, 13389, 13406, -1, 13405, 13387, 13389, -1, 12979, 13334, 13386, -1, 13405, 13384, 13387, -1, 13405, 13404, 13384, -1, 12979, 13359, 13334, -1, 13003, 13355, 13324, -1, 13407, 13392, 13391, -1, 13407, 13391, 13393, -1, 13003, 13324, 13002, -1, 13407, 13001, 13392, -1, 13408, 13393, 13394, -1, 13392, 13380, 13352, -1, 13408, 13160, 13184, -1, 12990, 13373, 13390, -1, 13392, 13352, 13351, -1, 13408, 13394, 13160, -1, 13408, 13407, 13393, -1, 13409, 13354, 13314, -1, 13409, 13314, 13397, -1, 13021, 13386, 13362, -1, 13409, 13397, 13399, -1, 13021, 13362, 13396, -1, 13036, 13385, 13358, -1, 13410, 13053, 13097, -1, 13036, 13358, 13395, -1, 13410, 13400, 13053, -1, 13410, 13409, 13399, -1, 13075, 13365, 13323, -1, 13410, 13399, 13400, -1, 13411, 13214, 13401, -1, 13411, 13401, 13404, -1, 13411, 13232, 13214, -1, 13004, 13396, 13369, -1, 13004, 13369, 13000, -1, 12975, 13411, 13404, -1, 13075, 13323, 12984, -1, 13055, 13402, 13056, -1, 12975, 13406, 12976, -1, 13055, 13057, 13412, -1, 12975, 13405, 13406, -1, 13055, 13412, 13413, -1, 12975, 13404, 13405, -1, 13055, 13413, 13402, -1, 13067, 13395, 13366, -1, 13067, 13366, 13062, -1, 13069, 13292, 13019, -1, 12987, 13001, 13407, -1, 12987, 12982, 13001, -1, 12986, 12985, 13329, -1, 13069, 13298, 13292, -1, 13414, 13407, 13408, -1, 13414, 12987, 13407, -1, 12986, 13329, 13016, -1, 13047, 13376, 13415, -1, 13047, 13375, 13376, -1, 13027, 13032, 13398, -1, 12988, 12987, 13414, -1, 13027, 13398, 13403, -1, 12978, 13359, 12979, -1, 12991, 13390, 13355, -1, 12991, 13355, 13003, -1, 12991, 12990, 13390, -1, 12978, 13382, 13359, -1, 12992, 13414, 13408, -1, 12992, 12988, 13414, -1, 13034, 13386, 13021, -1, 12996, 13184, 12994, -1, 12996, 13408, 13184, -1, 12996, 12992, 13408, -1, 12998, 13002, 13354, -1, 13034, 12979, 13386, -1, 12998, 13354, 13409, -1, 13018, 13016, 13385, -1, 13001, 13380, 13392, -1, 12999, 12998, 13409, -1, 13018, 13385, 13036, -1, 13416, 13409, 13410, -1, 13028, 13403, 13373, -1, 13028, 13373, 12990, -1, 13001, 13000, 13380, -1, 13009, 13409, 13416, -1, 13022, 13021, 13396, -1, 13028, 13027, 13403, -1, 13009, 12999, 13409, -1, 13013, 13009, 13416, -1, 13022, 13396, 13004, -1, 13013, 13410, 13097, -1, 13013, 13097, 13014, -1, 13012, 13011, 13375, -1, 13013, 13416, 13410, -1, 13052, 13051, 13365, -1, 13012, 13375, 13047, -1, 13025, 13232, 13411, -1, 13052, 13365, 13075, -1, 13025, 13024, 13232, -1, 13417, 13411, 12975, -1, 13043, 13298, 13069, -1, 13417, 13025, 13411, -1, 13029, 13025, 13417, -1, 13037, 13036, 13395, -1, 13029, 13417, 12975, -1, 13037, 13395, 13067, -1, 13043, 13042, 13298, -1, 13048, 13047, 13415, -1, 13063, 13062, 13367, -1, 13048, 13415, 13072, -1, 13063, 13367, 13331, -1, 13059, 13056, 13382, -1, 13030, 13029, 12975, -1, 13059, 13382, 12978, -1, 12974, 13030, 12975, -1, 12977, 12979, 13034, -1, 12974, 12976, 13039, -1, 13418, 13419, 13420, -1, 13418, 13421, 13419, -1, 13422, 13423, 13424, -1, 13422, 13418, 13423, -1, 13425, 13426, 13427, -1, 13425, 13428, 13426, -1, 13429, 13430, 13431, -1, 13432, 13424, 13433, -1, 13429, 13434, 13430, -1, 13425, 13435, 13428, -1, 13432, 13433, 13436, -1, 13432, 13422, 13424, -1, 13437, 13438, 13439, -1, 13437, 13439, 13440, -1, 13441, 13437, 13440, -1, 13442, 13443, 13444, -1, 13442, 13445, 13443, -1, 13446, 13447, 13448, -1, 13449, 13450, 13451, -1, 13446, 13452, 13447, -1, 13453, 13454, 13455, -1, 13453, 13441, 13440, -1, 13456, 13427, 13457, -1, 13453, 13455, 13458, -1, 13449, 13431, 13450, -1, 13453, 13440, 13454, -1, 13456, 13457, 13459, -1, 13460, 13461, 13462, -1, 13460, 13444, 13461, -1, 13463, 13464, 13465, -1, 13463, 13465, 13466, -1, 13467, 13468, 13469, -1, 13467, 13451, 13468, -1, 13470, 13471, 13472, -1, 13473, 13460, 13462, -1, 13470, 13474, 13475, -1, 13470, 13472, 13474, -1, 13470, 13476, 13471, -1, 13477, 13448, 13478, -1, 13479, 13480, 13481, -1, 13479, 13473, 13462, -1, 13477, 13478, 13482, -1, 13479, 13462, 13480, -1, 13483, 13484, 13485, -1, 13479, 13481, 13486, -1, 13483, 13485, 13487, -1, 13488, 13418, 13422, -1, 13489, 13490, 13452, -1, 13488, 13421, 13418, -1, 13488, 13491, 13421, -1, 13492, 13493, 13494, -1, 13495, 13488, 13422, -1, 13489, 13452, 13446, -1, 13496, 13497, 13498, -1, 13495, 13422, 13432, -1, 13496, 13499, 13497, -1, 13496, 13498, 13435, -1, 13496, 13500, 13499, -1, 13501, 13432, 13436, -1, 13492, 13502, 13493, -1, 13501, 13436, 13503, -1, 13504, 13505, 13434, -1, 13506, 13482, 13507, -1, 13501, 13495, 13432, -1, 13439, 13508, 13509, -1, 13510, 13438, 13437, -1, 13439, 13459, 13508, -1, 13510, 13437, 13441, -1, 13504, 13434, 13429, -1, 13510, 13511, 13438, -1, 13512, 13510, 13441, -1, 13512, 13441, 13453, -1, 13513, 13435, 13425, -1, 13512, 13453, 13458, -1, 13512, 13458, 13514, -1, 13515, 13445, 13442, -1, 13515, 13475, 13445, -1, 13516, 13442, 13444, -1, 13516, 13444, 13460, -1, 13516, 13460, 13473, -1, 13517, 13429, 13431, -1, 13517, 13431, 13449, -1, 13518, 13425, 13427, -1, 13519, 13486, 13520, -1, 13519, 13473, 13479, -1, 13519, 13479, 13486, -1, 13519, 13516, 13473, -1, 13518, 13427, 13456, -1, 13521, 13488, 13495, -1, 13522, 13451, 13467, -1, 13521, 13491, 13488, -1, 13523, 13446, 13448, -1, 13523, 13448, 13477, -1, 13521, 13524, 13491, -1, 13522, 13449, 13451, -1, 13525, 13495, 13501, -1, 13526, 13469, 13502, -1, 13527, 13464, 13463, -1, 13527, 13528, 13464, -1, 13525, 13521, 13495, -1, 13529, 13501, 13503, -1, 13526, 13502, 13492, -1, 13529, 13503, 13530, -1, 13529, 13525, 13501, -1, 13531, 13477, 13482, -1, 13532, 13510, 13512, -1, 13533, 13534, 13484, -1, 13531, 13482, 13506, -1, 13532, 13511, 13510, -1, 13533, 13484, 13483, -1, 13532, 13535, 13511, -1, 13536, 13505, 13504, -1, 13537, 13532, 13512, -1, 13536, 13487, 13505, -1, 13538, 13466, 13490, -1, 13538, 13490, 13489, -1, 13539, 13537, 13512, -1, 13539, 13512, 13514, -1, 13539, 13514, 13540, -1, 13541, 13515, 13442, -1, 13541, 13516, 13519, -1, 13438, 13456, 13459, -1, 13542, 13470, 13475, -1, 13438, 13459, 13439, -1, 13541, 13442, 13516, -1, 13542, 13476, 13470, -1, 13542, 13475, 13515, -1, 13543, 13541, 13519, -1, 13544, 13429, 13517, -1, 13545, 13496, 13435, -1, 13545, 13500, 13496, -1, 13545, 13435, 13513, -1, 13546, 13520, 13547, -1, 13546, 13519, 13520, -1, 13544, 13504, 13429, -1, 13546, 13543, 13519, -1, 13548, 13446, 13523, -1, 13549, 13524, 13521, -1, 13550, 13467, 13469, -1, 13548, 13489, 13446, -1, 13549, 13521, 13525, -1, 13549, 13551, 13524, -1, 13550, 13469, 13526, -1, 13552, 13513, 13425, -1, 13553, 13525, 13529, -1, 13552, 13425, 13518, -1, 13553, 13549, 13525, -1, 13554, 13517, 13449, -1, 13555, 13528, 13527, -1, 13554, 13449, 13522, -1, 13555, 13556, 13528, -1, 13557, 13553, 13529, -1, 13558, 13559, 13534, -1, 13560, 13557, 13529, -1, 13561, 13477, 13531, -1, 13558, 13534, 13533, -1, 13560, 13529, 13530, -1, 13562, 13560, 13530, -1, 13562, 13563, 13564, -1, 13562, 13530, 13563, -1, 13561, 13523, 13477, -1, 13565, 13483, 13487, -1, 13565, 13487, 13536, -1, 13566, 13567, 13535, -1, 13568, 13507, 13569, -1, 13566, 13535, 13532, -1, 13566, 13532, 13537, -1, 13568, 13506, 13507, -1, 13570, 13540, 13571, -1, 13570, 13566, 13537, -1, 13572, 13466, 13538, -1, 13570, 13537, 13539, -1, 13570, 13539, 13540, -1, 13572, 13463, 13466, -1, 13573, 13515, 13541, -1, 13573, 13542, 13515, -1, 13573, 13541, 13543, -1, 13574, 13547, 13575, -1, 13576, 13536, 13504, -1, 13574, 13573, 13543, -1, 13574, 13546, 13547, -1, 13576, 13504, 13544, -1, 13574, 13543, 13546, -1, 13577, 13549, 13553, -1, 13577, 13553, 13557, -1, 13577, 13578, 13551, -1, 13579, 13467, 13550, -1, 13577, 13551, 13549, -1, 13579, 13522, 13467, -1, 13511, 13456, 13438, -1, 13580, 13557, 13560, -1, 13581, 13544, 13517, -1, 13511, 13518, 13456, -1, 13580, 13562, 13564, -1, 13580, 13560, 13562, -1, 13582, 13489, 13548, -1, 13581, 13517, 13554, -1, 13580, 13577, 13557, -1, 13582, 13538, 13489, -1, 13583, 13567, 13566, -1, 13584, 13559, 13558, -1, 13585, 13523, 13561, -1, 13583, 13586, 13567, -1, 13587, 13586, 13583, -1, 13584, 13481, 13559, -1, 13587, 13588, 13586, -1, 13585, 13548, 13523, -1, 13589, 13500, 13545, -1, 13587, 13583, 13566, -1, 13590, 13566, 13570, -1, 13589, 13513, 13552, -1, 13590, 13587, 13566, -1, 13591, 13483, 13565, -1, 13589, 13586, 13500, -1, 13590, 13588, 13587, -1, 13589, 13545, 13513, -1, 13590, 13571, 13588, -1, 13592, 13556, 13555, -1, 13590, 13570, 13571, -1, 13593, 13542, 13573, -1, 13591, 13533, 13483, -1, 13593, 13476, 13542, -1, 13592, 13594, 13556, -1, 13595, 13593, 13573, -1, 13595, 13476, 13593, -1, 13596, 13531, 13506, -1, 13595, 13597, 13476, -1, 13598, 13575, 13597, -1, 13598, 13597, 13595, -1, 13598, 13573, 13574, -1, 13599, 13536, 13576, -1, 13598, 13595, 13573, -1, 13598, 13574, 13575, -1, 13596, 13506, 13568, -1, 13600, 13601, 13578, -1, 13599, 13565, 13536, -1, 13602, 13463, 13572, -1, 13600, 13578, 13577, -1, 13603, 13600, 13577, -1, 13604, 13554, 13522, -1, 13603, 13577, 13580, -1, 13604, 13522, 13579, -1, 13602, 13527, 13463, -1, 13605, 13601, 13600, -1, 13606, 13544, 13581, -1, 13606, 13576, 13544, -1, 13605, 13600, 13603, -1, 13605, 13603, 13580, -1, 13535, 13518, 13511, -1, 13607, 13608, 13609, -1, 13610, 13481, 13584, -1, 13607, 13605, 13580, -1, 13607, 13609, 13601, -1, 13535, 13552, 13518, -1, 13607, 13611, 13608, -1, 13612, 13572, 13538, -1, 13612, 13538, 13582, -1, 13607, 13601, 13605, -1, 13610, 13486, 13481, -1, 13613, 13580, 13564, -1, 13612, 13602, 13572, -1, 13613, 13614, 13611, -1, 13615, 13533, 13591, -1, 13613, 13564, 13614, -1, 13613, 13607, 13580, -1, 13613, 13611, 13607, -1, 13615, 13558, 13533, -1, 13616, 13548, 13585, -1, 13617, 13565, 13599, -1, 13616, 13582, 13548, -1, 13618, 13561, 13531, -1, 13618, 13531, 13596, -1, 13617, 13591, 13565, -1, 13619, 13554, 13604, -1, 13620, 13594, 13592, -1, 13620, 13621, 13594, -1, 13622, 13555, 13527, -1, 13623, 13624, 13625, -1, 13622, 13527, 13602, -1, 13619, 13581, 13554, -1, 13626, 13599, 13576, -1, 13627, 13628, 13629, -1, 13627, 13629, 13630, -1, 13626, 13576, 13606, -1, 13631, 13486, 13610, -1, 13631, 13520, 13486, -1, 13632, 13633, 13628, -1, 13632, 13628, 13627, -1, 13567, 13589, 13552, -1, 13634, 13584, 13558, -1, 13567, 13586, 13589, -1, 13634, 13558, 13615, -1, 13567, 13552, 13535, -1, 13635, 13633, 13632, -1, 13635, 13636, 13633, -1, 13637, 13602, 13612, -1, 13638, 13585, 13561, -1, 13639, 13591, 13617, -1, 13638, 13561, 13618, -1, 13639, 13615, 13591, -1, 13419, 13606, 13581, -1, 13640, 13612, 13582, -1, 13640, 13582, 13616, -1, 13641, 13636, 13635, -1, 13642, 13630, 13643, -1, 13644, 13645, 13621, -1, 13419, 13581, 13619, -1, 13644, 13621, 13620, -1, 13642, 13627, 13630, -1, 13646, 13599, 13626, -1, 13646, 13617, 13599, -1, 13647, 13632, 13627, -1, 13647, 13627, 13642, -1, 13648, 13547, 13520, -1, 13648, 13520, 13631, -1, 13649, 13592, 13555, -1, 13650, 13651, 13636, -1, 13652, 13610, 13584, -1, 13652, 13584, 13634, -1, 13649, 13555, 13622, -1, 13650, 13636, 13641, -1, 13653, 13643, 13654, -1, 13655, 13634, 13615, -1, 13653, 13642, 13643, -1, 13656, 13635, 13632, -1, 13655, 13615, 13639, -1, 13657, 13622, 13602, -1, 13657, 13602, 13637, -1, 13656, 13632, 13647, -1, 13658, 13616, 13585, -1, 13421, 13626, 13606, -1, 13659, 13660, 13651, -1, 13421, 13606, 13419, -1, 13661, 13617, 13646, -1, 13658, 13585, 13638, -1, 13659, 13651, 13650, -1, 13661, 13639, 13617, -1, 13662, 13637, 13612, -1, 13663, 13597, 13575, -1, 13662, 13612, 13640, -1, 13664, 13642, 13653, -1, 13663, 13575, 13547, -1, 13663, 13547, 13648, -1, 13665, 13455, 13645, -1, 13664, 13647, 13642, -1, 13663, 13666, 13597, -1, 13665, 13645, 13644, -1, 13667, 13610, 13652, -1, 13668, 13635, 13656, -1, 13668, 13641, 13635, -1, 13667, 13631, 13610, -1, 13491, 13626, 13421, -1, 13491, 13646, 13626, -1, 13669, 13653, 13654, -1, 13670, 13620, 13592, -1, 13671, 13647, 13664, -1, 13672, 13652, 13634, -1, 13671, 13656, 13647, -1, 13672, 13634, 13655, -1, 13670, 13592, 13649, -1, 13673, 13674, 13660, -1, 13675, 13655, 13639, -1, 13673, 13660, 13659, -1, 13675, 13639, 13661, -1, 13676, 13649, 13622, -1, 13676, 13622, 13657, -1, 13676, 13670, 13649, -1, 13677, 13648, 13631, -1, 13678, 13664, 13653, -1, 13677, 13631, 13667, -1, 13678, 13653, 13669, -1, 13679, 13616, 13658, -1, 13679, 13640, 13616, -1, 13680, 13657, 13637, -1, 13681, 13641, 13668, -1, 13524, 13646, 13491, -1, 13524, 13661, 13646, -1, 13681, 13650, 13641, -1, 13680, 13637, 13662, -1, 13682, 13656, 13671, -1, 13683, 13667, 13652, -1, 13683, 13652, 13672, -1, 13682, 13668, 13656, -1, 13684, 13685, 13674, -1, 13686, 13655, 13675, -1, 13686, 13672, 13655, -1, 13684, 13674, 13673, -1, 13687, 13458, 13455, -1, 13688, 13648, 13677, -1, 13687, 13455, 13665, -1, 13688, 13689, 13666, -1, 13688, 13663, 13648, -1, 13690, 13671, 13664, -1, 13688, 13666, 13663, -1, 13690, 13664, 13678, -1, 13691, 13620, 13670, -1, 13551, 13675, 13661, -1, 13692, 13654, 13693, -1, 13691, 13644, 13620, -1, 13551, 13661, 13524, -1, 13694, 13670, 13676, -1, 13692, 13669, 13654, -1, 13695, 13667, 13683, -1, 13694, 13691, 13670, -1, 13695, 13677, 13667, -1, 13696, 13650, 13681, -1, 13696, 13659, 13650, -1, 13697, 13672, 13686, -1, 13698, 13662, 13640, -1, 13697, 13683, 13672, -1, 13698, 13640, 13679, -1, 13699, 13681, 13668, -1, 13699, 13668, 13682, -1, 13578, 13686, 13675, -1, 13578, 13675, 13551, -1, 13700, 13671, 13690, -1, 13701, 13688, 13677, -1, 13701, 13689, 13688, -1, 13700, 13682, 13671, -1, 13701, 13677, 13695, -1, 13702, 13703, 13685, -1, 13704, 13683, 13697, -1, 13702, 13685, 13684, -1, 13705, 13706, 13707, -1, 13704, 13695, 13683, -1, 13705, 13708, 13706, -1, 13601, 13686, 13578, -1, 13601, 13697, 13686, -1, 13709, 13657, 13680, -1, 13710, 13678, 13669, -1, 13711, 13701, 13695, -1, 13709, 13676, 13657, -1, 13710, 13669, 13692, -1, 13711, 13695, 13704, -1, 13711, 13624, 13689, -1, 13711, 13689, 13701, -1, 13712, 13458, 13687, -1, 13713, 13673, 13659, -1, 13712, 13514, 13458, -1, 13714, 13665, 13644, -1, 13609, 13697, 13601, -1, 13609, 13704, 13697, -1, 13715, 13609, 13608, -1, 13713, 13659, 13696, -1, 13715, 13704, 13609, -1, 13715, 13711, 13704, -1, 13715, 13624, 13711, -1, 13714, 13644, 13691, -1, 13715, 13608, 13625, -1, 13716, 13717, 13708, -1, 13715, 13625, 13624, -1, 13718, 13696, 13681, -1, 13718, 13681, 13699, -1, 13719, 13692, 13693, -1, 13718, 13713, 13696, -1, 13719, 13710, 13692, -1, 13716, 13708, 13705, -1, 13720, 13719, 13693, -1, 13721, 13699, 13682, -1, 13721, 13682, 13700, -1, 13722, 13691, 13694, -1, 13720, 13710, 13719, -1, 13723, 13693, 13724, -1, 13723, 13720, 13693, -1, 13725, 13678, 13710, -1, 13726, 13680, 13662, -1, 13726, 13662, 13698, -1, 13727, 13723, 13724, -1, 13725, 13690, 13678, -1, 13727, 13728, 13729, -1, 13727, 13724, 13728, -1, 13730, 13703, 13702, -1, 13731, 13725, 13710, -1, 13731, 13720, 13723, -1, 13731, 13723, 13727, -1, 13731, 13729, 13732, -1, 13731, 13727, 13729, -1, 13731, 13710, 13720, -1, 13730, 13733, 13703, -1, 13734, 13673, 13713, -1, 13735, 13736, 13737, -1, 13738, 13694, 13676, -1, 13738, 13676, 13709, -1, 13734, 13684, 13673, -1, 13735, 13739, 13465, -1, 13740, 13465, 13464, -1, 13740, 13741, 13736, -1, 13742, 13713, 13718, -1, 13740, 13735, 13465, -1, 13740, 13736, 13735, -1, 13743, 13740, 13464, -1, 13744, 13514, 13712, -1, 13737, 13690, 13725, -1, 13743, 13741, 13740, -1, 13744, 13540, 13514, -1, 13745, 13746, 13717, -1, 13737, 13700, 13690, -1, 13747, 13699, 13721, -1, 13748, 13568, 13569, -1, 13748, 13596, 13568, -1, 13745, 13717, 13716, -1, 13747, 13718, 13699, -1, 13749, 13596, 13748, -1, 13750, 13733, 13730, -1, 13749, 13748, 13569, -1, 13751, 13665, 13714, -1, 13751, 13687, 13665, -1, 13752, 13749, 13569, -1, 13750, 13753, 13733, -1, 13752, 13569, 13706, -1, 13754, 13708, 13717, -1, 13755, 13691, 13722, -1, 13754, 13706, 13708, -1, 13755, 13714, 13691, -1, 13754, 13752, 13706, -1, 13756, 13717, 13746, -1, 13756, 13596, 13749, -1, 13756, 13749, 13752, -1, 13757, 13709, 13680, -1, 13756, 13754, 13717, -1, 13756, 13752, 13754, -1, 13757, 13680, 13726, -1, 13758, 13684, 13734, -1, 13756, 13618, 13596, -1, 13758, 13702, 13684, -1, 13759, 13760, 13761, -1, 13759, 13658, 13638, -1, 13762, 13713, 13742, -1, 13763, 13679, 13658, -1, 13762, 13734, 13713, -1, 13763, 13761, 13764, -1, 13736, 13721, 13700, -1, 13763, 13759, 13761, -1, 13763, 13658, 13759, -1, 13765, 13722, 13694, -1, 13765, 13694, 13738, -1, 13766, 13763, 13764, -1, 13767, 13571, 13540, -1, 13766, 13679, 13763, -1, 13767, 13768, 13588, -1, 13736, 13700, 13737, -1, 13767, 13588, 13571, -1, 13769, 13742, 13718, -1, 13770, 13492, 13494, -1, 13767, 13540, 13744, -1, 13771, 13760, 13746, -1, 13771, 13746, 13745, -1, 13770, 13494, 13772, -1, 13769, 13718, 13747, -1, 13773, 13753, 13750, -1, 13774, 13492, 13770, -1, 13774, 13770, 13772, -1, 13773, 13775, 13776, -1, 13777, 13772, 13778, -1, 13773, 13776, 13753, -1, 13779, 13707, 13780, -1, 13777, 13774, 13772, -1, 13781, 13782, 13783, -1, 13781, 13778, 13782, -1, 13779, 13705, 13707, -1, 13781, 13777, 13778, -1, 13784, 13712, 13687, -1, 13785, 13526, 13492, -1, 13785, 13492, 13774, -1, 13784, 13687, 13751, -1, 13785, 13774, 13777, -1, 13786, 13702, 13758, -1, 13785, 13781, 13783, -1, 13785, 13777, 13781, -1, 13786, 13730, 13702, -1, 13787, 13735, 13737, -1, 13787, 13731, 13732, -1, 13788, 13758, 13734, -1, 13787, 13739, 13735, -1, 13788, 13734, 13762, -1, 13787, 13732, 13739, -1, 13789, 13709, 13757, -1, 13788, 13786, 13758, -1, 13787, 13725, 13731, -1, 13789, 13738, 13709, -1, 13787, 13737, 13725, -1, 13790, 13741, 13743, -1, 13741, 13747, 13721, -1, 13790, 13791, 13741, -1, 13741, 13721, 13736, -1, 13792, 13751, 13714, -1, 13790, 13793, 13791, -1, 13792, 13714, 13755, -1, 13794, 13742, 13769, -1, 13795, 13790, 13743, -1, 13796, 13464, 13528, -1, 13796, 13743, 13464, -1, 13796, 13795, 13743, -1, 13794, 13762, 13742, -1, 13796, 13528, 13556, -1, 13797, 13746, 13760, -1, 13798, 13722, 13765, -1, 13797, 13760, 13759, -1, 13797, 13756, 13746, -1, 13797, 13618, 13756, -1, 13797, 13759, 13638, -1, 13797, 13638, 13618, -1, 13799, 13726, 13698, -1, 13798, 13755, 13722, -1, 13800, 13705, 13779, -1, 13801, 13775, 13773, -1, 13799, 13679, 13766, -1, 13799, 13698, 13679, -1, 13802, 13799, 13766, -1, 13800, 13716, 13705, -1, 13803, 13750, 13730, -1, 13803, 13730, 13786, -1, 13804, 13764, 13805, -1, 13804, 13802, 13766, -1, 13804, 13805, 13485, -1, 13806, 13786, 13788, -1, 13804, 13766, 13764, -1, 13430, 13760, 13771, -1, 13806, 13803, 13786, -1, 13430, 13761, 13760, -1, 13807, 13550, 13526, -1, 13807, 13579, 13550, -1, 13808, 13780, 13809, -1, 13791, 13747, 13741, -1, 13810, 13807, 13526, -1, 13808, 13779, 13780, -1, 13811, 13744, 13712, -1, 13810, 13526, 13785, -1, 13791, 13769, 13747, -1, 13812, 13810, 13785, -1, 13811, 13712, 13784, -1, 13813, 13738, 13789, -1, 13814, 13815, 13812, -1, 13814, 13783, 13816, -1, 13814, 13816, 13815, -1, 13814, 13785, 13783, -1, 13813, 13765, 13738, -1, 13814, 13812, 13785, -1, 13817, 13724, 13818, -1, 13819, 13784, 13751, -1, 13820, 13821, 13793, -1, 13819, 13751, 13792, -1, 13820, 13793, 13790, -1, 13819, 13811, 13784, -1, 13817, 13728, 13724, -1, 13820, 13790, 13795, -1, 13822, 13788, 13762, -1, 13823, 13820, 13795, -1, 13822, 13762, 13794, -1, 13824, 13775, 13801, -1, 13825, 13823, 13795, -1, 13825, 13556, 13594, -1, 13825, 13795, 13796, -1, 13824, 13826, 13775, -1, 13825, 13796, 13556, -1, 13827, 13799, 13802, -1, 13828, 13773, 13750, -1, 13827, 13726, 13799, -1, 13829, 13716, 13800, -1, 13828, 13750, 13803, -1, 13827, 13757, 13726, -1, 13829, 13745, 13716, -1, 13443, 13755, 13798, -1, 13830, 13827, 13802, -1, 13443, 13792, 13755, -1, 13447, 13729, 13728, -1, 13831, 13830, 13802, -1, 13831, 13802, 13804, -1, 13447, 13728, 13817, -1, 13831, 13804, 13485, -1, 13831, 13485, 13484, -1, 13832, 13579, 13807, -1, 13832, 13604, 13579, -1, 13434, 13761, 13430, -1, 13833, 13803, 13806, -1, 13434, 13764, 13761, -1, 13832, 13807, 13810, -1, 13793, 13794, 13769, -1, 13793, 13769, 13791, -1, 13834, 13810, 13812, -1, 13835, 13800, 13779, -1, 13834, 13832, 13810, -1, 13835, 13779, 13808, -1, 13836, 13812, 13815, -1, 13836, 13815, 13837, -1, 13838, 13744, 13811, -1, 13838, 13768, 13767, -1, 13836, 13834, 13812, -1, 13839, 13840, 13821, -1, 13838, 13471, 13768, -1, 13838, 13767, 13744, -1, 13839, 13821, 13820, -1, 13450, 13771, 13745, -1, 13841, 13806, 13788, -1, 13839, 13820, 13823, -1, 13841, 13788, 13822, -1, 13842, 13823, 13825, -1, 13842, 13825, 13594, -1, 13842, 13839, 13823, -1, 13450, 13745, 13829, -1, 13842, 13594, 13621, -1, 13498, 13843, 13826, -1, 13844, 13789, 13757, -1, 13493, 13808, 13809, -1, 13498, 13826, 13824, -1, 13844, 13827, 13830, -1, 13452, 13732, 13729, -1, 13844, 13757, 13827, -1, 13845, 13830, 13831, -1, 13461, 13765, 13813, -1, 13845, 13831, 13484, -1, 13452, 13729, 13447, -1, 13845, 13844, 13830, -1, 13845, 13484, 13534, -1, 13461, 13798, 13765, -1, 13474, 13811, 13819, -1, 13426, 13773, 13828, -1, 13846, 13832, 13834, -1, 13846, 13604, 13832, -1, 13426, 13801, 13773, -1, 13846, 13619, 13604, -1, 13457, 13828, 13803, -1, 13457, 13803, 13833, -1, 13847, 13834, 13836, -1, 13847, 13846, 13834, -1, 13821, 13794, 13793, -1, 13848, 13837, 13849, -1, 13848, 13836, 13837, -1, 13445, 13819, 13792, -1, 13821, 13822, 13794, -1, 13848, 13847, 13836, -1, 13850, 13840, 13839, -1, 13850, 13509, 13840, -1, 13445, 13792, 13443, -1, 13468, 13829, 13800, -1, 13851, 13839, 13842, -1, 13468, 13800, 13835, -1, 13851, 13850, 13839, -1, 13505, 13805, 13764, -1, 13505, 13764, 13434, -1, 13508, 13833, 13806, -1, 13508, 13806, 13841, -1, 13852, 13851, 13842, -1, 13852, 13850, 13851, -1, 13490, 13739, 13732, -1, 13490, 13732, 13452, -1, 13853, 13852, 13842, -1, 13502, 13808, 13493, -1, 13854, 13853, 13842, -1, 13497, 13843, 13498, -1, 13854, 13842, 13621, -1, 13497, 13499, 13855, -1, 13854, 13621, 13645, -1, 13502, 13835, 13808, -1, 13497, 13855, 13856, -1, 13497, 13856, 13843, -1, 13857, 13813, 13789, -1, 13857, 13789, 13844, -1, 13478, 13818, 13858, -1, 13431, 13430, 13771, -1, 13478, 13817, 13818, -1, 13859, 13844, 13845, -1, 13431, 13771, 13450, -1, 13859, 13857, 13844, -1, 13428, 13801, 13426, -1, 13428, 13824, 13801, -1, 13860, 13857, 13859, -1, 13840, 13822, 13821, -1, 13861, 13859, 13845, -1, 13444, 13443, 13798, -1, 13444, 13798, 13461, -1, 13861, 13860, 13859, -1, 13840, 13841, 13822, -1, 13862, 13534, 13559, -1, 13862, 13845, 13534, -1, 13472, 13811, 13474, -1, 13427, 13828, 13457, -1, 13862, 13861, 13845, -1, 13427, 13426, 13828, -1, 13420, 13419, 13619, -1, 13472, 13471, 13838, -1, 13420, 13619, 13846, -1, 13472, 13838, 13811, -1, 13420, 13846, 13847, -1, 13451, 13829, 13468, -1, 13423, 13420, 13847, -1, 13451, 13450, 13829, -1, 13459, 13457, 13833, -1, 13459, 13833, 13508, -1, 13423, 13847, 13848, -1, 13424, 13848, 13849, -1, 13424, 13849, 13433, -1, 13475, 13474, 13819, -1, 13475, 13819, 13445, -1, 13424, 13423, 13848, -1, 13440, 13439, 13509, -1, 13448, 13817, 13478, -1, 13440, 13509, 13850, -1, 13448, 13447, 13817, -1, 13440, 13850, 13852, -1, 13487, 13485, 13805, -1, 13440, 13852, 13853, -1, 13454, 13440, 13853, -1, 13487, 13805, 13505, -1, 13466, 13739, 13490, -1, 13454, 13645, 13455, -1, 13454, 13853, 13854, -1, 13454, 13854, 13645, -1, 13466, 13465, 13739, -1, 13462, 13813, 13857, -1, 13482, 13858, 13507, -1, 13462, 13461, 13813, -1, 13469, 13468, 13835, -1, 13462, 13857, 13860, -1, 13469, 13835, 13502, -1, 13482, 13478, 13858, -1, 13462, 13860, 13861, -1, 13435, 13498, 13824, -1, 13480, 13462, 13861, -1, 13494, 13809, 13772, -1, 13480, 13862, 13559, -1, 13494, 13493, 13809, -1, 13480, 13559, 13481, -1, 13480, 13861, 13862, -1, 13435, 13824, 13428, -1, 13418, 13420, 13423, -1, 13509, 13508, 13841, -1, 13509, 13841, 13840, -1, 13863, 13864, 13865, -1, 13865, 13864, 13866, -1, 13866, 13867, 13868, -1, 13864, 13867, 13866, -1, 13868, 13869, 13870, -1, 13867, 13869, 13868, -1, 13870, 13871, 13872, -1, 13869, 13871, 13870, -1, 13872, 13873, 13874, -1, 13871, 13873, 13872, -1, 13874, 13875, 13876, -1, 13873, 13875, 13874, -1, 13876, 13877, 13878, -1, 13875, 13877, 13876, -1, 13879, 13880, 13881, -1, 13881, 13880, 13882, -1, 13882, 13883, 13884, -1, 13880, 13883, 13882, -1, 13884, 13885, 13886, -1, 13883, 13885, 13884, -1, 13886, 13887, 13888, -1, 13885, 13887, 13886, -1, 13888, 13889, 13890, -1, 13887, 13889, 13888, -1, 13890, 13891, 13892, -1, 13889, 13891, 13890, -1, 13892, 13893, 13894, -1, 13891, 13893, 13892, -1, 13895, 13896, 13897, -1, 13897, 13896, 13898, -1, 13898, 13899, 13900, -1, 13896, 13899, 13898, -1, 13900, 13901, 13902, -1, 13899, 13901, 13900, -1, 13902, 13903, 13904, -1, 13901, 13903, 13902, -1, 13904, 13905, 13906, -1, 13903, 13905, 13904, -1, 13906, 13907, 13908, -1, 13905, 13907, 13906, -1, 13908, 13909, 13910, -1, 13907, 13909, 13908, -1, 13911, 13912, 13913, -1, 13913, 13912, 13914, -1, 13914, 13915, 13916, -1, 13912, 13915, 13914, -1, 13916, 13917, 13918, -1, 13915, 13917, 13916, -1, 13918, 13919, 13920, -1, 13917, 13919, 13918, -1, 13920, 13921, 13922, -1, 13919, 13921, 13920, -1, 13922, 13923, 13924, -1, 13921, 13923, 13922, -1, 13924, 13925, 13926, -1, 13923, 13925, 13924, -1, 13927, 13928, 13929, -1, 13930, 13929, 13931, -1, 13930, 13927, 13929, -1, 13932, 13931, 13623, -1, 13932, 13930, 13931, -1, 13412, 13623, 13625, -1, 13412, 13932, 13623, -1, 13413, 13625, 13608, -1, 13413, 13412, 13625, -1, 13402, 13608, 13611, -1, 13402, 13413, 13608, -1, 13383, 13611, 13614, -1, 13383, 13402, 13611, -1, 13361, 13614, 13564, -1, 13361, 13383, 13614, -1, 13336, 13564, 13563, -1, 13336, 13361, 13564, -1, 13312, 13563, 13530, -1, 13312, 13336, 13563, -1, 13291, 13312, 13530, -1, 13267, 13530, 13503, -1, 13267, 13291, 13530, -1, 13247, 13503, 13436, -1, 13247, 13267, 13503, -1, 13236, 13436, 13433, -1, 13236, 13247, 13436, -1, 13220, 13433, 13849, -1, 13220, 13236, 13433, -1, 13209, 13849, 13837, -1, 13209, 13220, 13849, -1, 13200, 13209, 13837, -1, 13200, 13837, 13815, -1, 13194, 13200, 13815, -1, 13194, 13815, 13816, -1, 13933, 13934, 13935, -1, 13936, 13935, 13937, -1, 13936, 13933, 13935, -1, 13938, 13937, 13939, -1, 13938, 13936, 13937, -1, 13940, 13939, 13941, -1, 13940, 13938, 13939, -1, 13942, 13943, 13944, -1, 13942, 13941, 13943, -1, 13942, 13940, 13941, -1, 13945, 13944, 13946, -1, 13945, 13942, 13944, -1, 13947, 13946, 13948, -1, 13947, 13945, 13946, -1, 13949, 13948, 13950, -1, 13949, 13947, 13948, -1, 13855, 13950, 13951, -1, 13855, 13949, 13950, -1, 13856, 13951, 13952, -1, 13856, 13855, 13951, -1, 13843, 13952, 13953, -1, 13843, 13856, 13952, -1, 13826, 13953, 13954, -1, 13826, 13843, 13953, -1, 13775, 13954, 13955, -1, 13775, 13826, 13954, -1, 13776, 13955, 13956, -1, 13776, 13775, 13955, -1, 13753, 13956, 13957, -1, 13753, 13776, 13956, -1, 13733, 13753, 13957, -1, 13733, 13957, 13958, -1, 13703, 13958, 13959, -1, 13703, 13733, 13958, -1, 13960, 13406, 13389, -1, 13960, 13961, 13406, -1, 13962, 13389, 13388, -1, 13962, 13960, 13389, -1, 13963, 13388, 13342, -1, 13963, 13962, 13388, -1, 13964, 13342, 13341, -1, 13964, 13963, 13342, -1, 13965, 13964, 13341, -1, 13966, 13341, 13379, -1, 13966, 13965, 13341, -1, 13967, 13379, 13377, -1, 13967, 13966, 13379, -1, 13968, 13377, 13335, -1, 13968, 13967, 13377, -1, 13969, 13335, 13333, -1, 13969, 13968, 13335, -1, 13970, 13333, 13971, -1, 13970, 13969, 13333, -1, 13972, 13971, 13973, -1, 13972, 13970, 13971, -1, 13974, 13973, 13975, -1, 13974, 13972, 13973, -1, 13976, 13975, 13977, -1, 13976, 13974, 13975, -1, 13978, 13977, 13979, -1, 13978, 13976, 13977, -1, 13980, 13979, 13981, -1, 13980, 13978, 13979, -1, 13982, 13981, 13983, -1, 13982, 13980, 13981, -1, 13984, 13982, 13983, -1, 13984, 13983, 13985, -1, 13986, 13984, 13985, -1, 13987, 13986, 13985, -1, 13987, 13985, 13988, -1, 13989, 13988, 13990, -1, 13989, 13987, 13988, -1, 13991, 13990, 13992, -1, 13991, 13989, 13990, -1, 13993, 13992, 13994, -1, 13993, 13991, 13992, -1, 13995, 13993, 13994, -1, 13996, 13994, 13997, -1, 13996, 13995, 13994, -1, 13998, 13997, 13999, -1, 13998, 13996, 13997, -1, 14000, 13999, 14001, -1, 14000, 13998, 13999, -1, 14002, 14001, 13173, -1, 14002, 14000, 14001, -1, 14003, 13173, 13153, -1, 14003, 14002, 13173, -1, 14004, 13153, 13134, -1, 14004, 14003, 13153, -1, 14005, 13134, 13106, -1, 14005, 14004, 13134, -1, 14006, 13106, 13085, -1, 14006, 14005, 13106, -1, 14007, 13085, 13040, -1, 14007, 14006, 13085, -1, 14008, 13040, 13039, -1, 14008, 14007, 13040, -1, 14009, 13039, 12976, -1, 14009, 14008, 13039, -1, 14010, 14009, 12976, -1, 14010, 12976, 13406, -1, 13961, 14010, 13406, -1, 13703, 13959, 14011, -1, 13685, 14011, 14012, -1, 13685, 13703, 14011, -1, 13674, 14012, 14013, -1, 13674, 13685, 14012, -1, 13660, 14013, 14014, -1, 13660, 13674, 14013, -1, 13651, 14015, 14016, -1, 13651, 14014, 14015, -1, 13651, 13660, 14014, -1, 13636, 14016, 14017, -1, 13636, 13651, 14016, -1, 13633, 14017, 14018, -1, 13633, 13636, 14017, -1, 13628, 14018, 14019, -1, 13628, 13633, 14018, -1, 13629, 14019, 14020, -1, 13629, 13628, 14019, -1, 14021, 14020, 14022, -1, 14021, 13629, 14020, -1, 14023, 14022, 14024, -1, 14023, 14021, 14022, -1, 14025, 14024, 14026, -1, 14025, 14023, 14024, -1, 14027, 14026, 14028, -1, 14027, 14025, 14026, -1, 14029, 14028, 14030, -1, 14029, 14027, 14028, -1, 14031, 14030, 14032, -1, 14031, 14029, 14030, -1, 14033, 14032, 14034, -1, 14033, 14031, 14032, -1, 13933, 14034, 13934, -1, 13933, 14033, 14034, -1, 14035, 14036, 14037, -1, 14038, 14039, 14040, -1, 14035, 14037, 14041, -1, 14038, 14042, 14039, -1, 14043, 14036, 14035, -1, 14044, 14045, 14046, -1, 14044, 14047, 14045, -1, 14048, 14049, 14050, -1, 14048, 14050, 14051, -1, 14052, 14036, 14043, -1, 14053, 14036, 14052, -1, 14053, 14054, 14036, -1, 14055, 14040, 14056, -1, 14057, 14053, 14052, -1, 14055, 14056, 14058, -1, 14057, 14054, 14053, -1, 14057, 14050, 14049, -1, 14057, 14049, 14054, -1, 14059, 14060, 14061, -1, 14059, 14062, 14060, -1, 14063, 14064, 14065, -1, 14066, 14067, 14068, -1, 14069, 13624, 13931, -1, 14063, 14065, 14070, -1, 14066, 14071, 14072, -1, 14066, 14068, 14071, -1, 14073, 14067, 14066, -1, 14069, 14074, 13624, -1, 14075, 14076, 14077, -1, 14075, 14077, 14078, -1, 14079, 14067, 14073, -1, 14079, 14080, 14081, -1, 14079, 14082, 14067, -1, 14079, 14081, 14082, -1, 14083, 14084, 14085, -1, 14086, 14058, 14087, -1, 14088, 14089, 14090, -1, 14088, 14091, 14089, -1, 14083, 14085, 14092, -1, 14086, 14087, 14093, -1, 14094, 14092, 14095, -1, 14088, 14096, 14091, -1, 14094, 14095, 14097, -1, 14098, 14099, 14100, -1, 14101, 14096, 14088, -1, 14098, 14100, 14102, -1, 14101, 14099, 14103, -1, 14104, 14105, 14106, -1, 14101, 14103, 14107, -1, 14101, 14108, 14096, -1, 14104, 14046, 14105, -1, 14101, 14107, 14108, -1, 14109, 14043, 14035, -1, 14110, 14111, 14112, -1, 14109, 14041, 14113, -1, 14109, 14035, 14041, -1, 14110, 14078, 14111, -1, 14114, 14115, 14076, -1, 14116, 14052, 14043, -1, 14116, 14057, 14052, -1, 14116, 14050, 14057, -1, 14117, 14062, 14059, -1, 14114, 14076, 14075, -1, 14116, 14043, 14109, -1, 14116, 14118, 14050, -1, 14119, 14042, 14038, -1, 14120, 14072, 14121, -1, 14119, 13630, 14122, -1, 14119, 13643, 13630, -1, 14120, 14073, 14066, -1, 14117, 14097, 14062, -1, 14119, 14122, 14042, -1, 14120, 14066, 14072, -1, 14123, 14047, 14044, -1, 14124, 14088, 14090, -1, 14123, 13507, 14125, -1, 14126, 13471, 13476, -1, 14123, 14125, 14047, -1, 14126, 14112, 13471, -1, 14124, 14101, 14088, -1, 14127, 14040, 14055, -1, 14124, 14090, 14128, -1, 14129, 14049, 14048, -1, 14129, 14130, 14049, -1, 14127, 14038, 14040, -1, 14131, 14101, 14124, -1, 14132, 14093, 14064, -1, 14133, 14100, 14099, -1, 14134, 14074, 14069, -1, 14133, 14099, 14101, -1, 14133, 14101, 14131, -1, 14134, 13931, 13929, -1, 14135, 14113, 14136, -1, 14134, 14069, 13931, -1, 14132, 14064, 14063, -1, 14135, 14109, 14113, -1, 14135, 14116, 14109, -1, 14134, 14061, 14074, -1, 14137, 14084, 14083, -1, 14138, 14116, 14135, -1, 14139, 14058, 14086, -1, 14139, 14055, 14058, -1, 14140, 14118, 14116, -1, 14140, 14116, 14138, -1, 14137, 14051, 14084, -1, 14140, 14141, 14118, -1, 14142, 14083, 14092, -1, 14143, 14120, 14121, -1, 14143, 14121, 14144, -1, 14145, 14075, 14078, -1, 14142, 14092, 14094, -1, 14145, 14078, 14110, -1, 14146, 14046, 14104, -1, 14147, 14120, 14143, -1, 14148, 14103, 14099, -1, 14148, 14099, 14098, -1, 14146, 14044, 14046, -1, 14149, 14128, 14150, -1, 14149, 14150, 14151, -1, 14149, 14151, 14152, -1, 14153, 14110, 14112, -1, 14149, 14124, 14128, -1, 14149, 14131, 14124, -1, 14154, 14097, 14117, -1, 14153, 14112, 14126, -1, 14155, 14156, 14100, -1, 14155, 14149, 14152, -1, 14155, 14133, 14131, -1, 14155, 14131, 14149, -1, 14155, 14152, 14156, -1, 14154, 14094, 14097, -1, 14157, 14102, 14115, -1, 14155, 14100, 14133, -1, 14158, 14059, 14061, -1, 14157, 14115, 14114, -1, 14159, 14135, 14136, -1, 14158, 13929, 13928, -1, 14159, 14160, 14161, -1, 14159, 14138, 14135, -1, 14162, 14075, 14145, -1, 14159, 14163, 14160, -1, 14159, 14136, 14163, -1, 14164, 14161, 14165, -1, 14158, 14061, 14134, -1, 14164, 14159, 14161, -1, 14158, 14134, 13929, -1, 14164, 14140, 14138, -1, 14162, 14114, 14075, -1, 14164, 14141, 14140, -1, 14164, 14138, 14159, -1, 14166, 13654, 13643, -1, 14164, 14165, 14141, -1, 14166, 14119, 14038, -1, 14167, 14130, 14129, -1, 14168, 14144, 14169, -1, 14166, 13643, 14119, -1, 14166, 14038, 14127, -1, 14168, 14147, 14143, -1, 14168, 14143, 14144, -1, 14167, 14170, 14130, -1, 14171, 14147, 14172, -1, 14171, 14120, 14147, -1, 14171, 14080, 14079, -1, 14171, 14079, 14073, -1, 14171, 14073, 14120, -1, 14171, 14173, 14080, -1, 14174, 14051, 14137, -1, 14171, 14172, 14173, -1, 14175, 14169, 14176, -1, 14175, 14168, 14169, -1, 14174, 14048, 14051, -1, 14177, 14093, 14132, -1, 14177, 14086, 14093, -1, 14178, 14137, 14083, -1, 14178, 14083, 14142, -1, 14179, 14180, 14181, -1, 14179, 14182, 14180, -1, 14183, 14127, 14055, -1, 14179, 14175, 14176, -1, 14183, 14055, 14139, -1, 14179, 14184, 14182, -1, 14179, 14181, 14175, -1, 14179, 14176, 14184, -1, 14184, 14059, 14158, -1, 14185, 14168, 14175, -1, 14184, 14117, 14059, -1, 14186, 14103, 14148, -1, 14186, 14187, 14103, -1, 14185, 14147, 14168, -1, 14184, 13928, 14182, -1, 14184, 14158, 13928, -1, 14188, 13569, 13507, -1, 14189, 14185, 14175, -1, 14188, 14123, 14044, -1, 14188, 14044, 14146, -1, 14190, 14145, 14110, -1, 14191, 14172, 14147, -1, 14188, 13507, 14123, -1, 14191, 14147, 14185, -1, 14190, 14110, 14153, -1, 14191, 14185, 14189, -1, 13931, 13624, 13623, -1, 14192, 14193, 14173, -1, 14192, 14181, 14193, -1, 14192, 14173, 14172, -1, 14192, 14172, 14191, -1, 14192, 14175, 14181, -1, 14194, 14126, 13476, -1, 14192, 14189, 14175, -1, 14192, 14191, 14189, -1, 14195, 14094, 14154, -1, 14195, 14142, 14094, -1, 14196, 14098, 14102, -1, 14196, 14102, 14157, -1, 14197, 14198, 14170, -1, 14199, 14157, 14114, -1, 14199, 14114, 14162, -1, 14197, 14170, 14167, -1, 14200, 14129, 14048, -1, 14201, 14086, 14177, -1, 14200, 14048, 14174, -1, 14201, 14139, 14086, -1, 14202, 14137, 14178, -1, 14203, 14162, 14145, -1, 14202, 14174, 14137, -1, 14203, 14145, 14190, -1, 14176, 14154, 14117, -1, 14176, 14117, 14184, -1, 14204, 14166, 14127, -1, 14204, 14127, 14183, -1, 14204, 13654, 14166, -1, 14205, 14187, 14186, -1, 14206, 14178, 14142, -1, 14205, 14207, 14187, -1, 14208, 14153, 14126, -1, 14206, 14142, 14195, -1, 14208, 14126, 14194, -1, 14209, 14210, 14198, -1, 14209, 14198, 14197, -1, 14211, 14098, 14196, -1, 14212, 14167, 14129, -1, 14211, 14148, 14098, -1, 14212, 14129, 14200, -1, 14213, 14157, 14199, -1, 14169, 14195, 14154, -1, 14213, 14196, 14157, -1, 14169, 14154, 14176, -1, 14214, 14183, 14139, -1, 14214, 14139, 14201, -1, 14215, 14199, 14162, -1, 14216, 14200, 14174, -1, 14215, 14162, 14203, -1, 14216, 14174, 14202, -1, 14160, 14190, 14153, -1, 14217, 13949, 13855, -1, 14217, 13855, 13499, -1, 14160, 14153, 14208, -1, 14218, 13949, 14217, -1, 14219, 14202, 14178, -1, 14219, 14178, 14206, -1, 14220, 14221, 14210, -1, 14218, 13947, 13949, -1, 14220, 14210, 14209, -1, 14222, 14207, 14205, -1, 14223, 13947, 14218, -1, 14222, 14224, 14207, -1, 14223, 13945, 13947, -1, 14225, 14167, 14212, -1, 14225, 14197, 14167, -1, 14226, 14186, 14148, -1, 14226, 14148, 14211, -1, 14144, 14195, 14169, -1, 14227, 14211, 14196, -1, 14144, 14206, 14195, -1, 14227, 14196, 14213, -1, 14228, 13945, 14223, -1, 14229, 14217, 13499, -1, 14163, 14190, 14160, -1, 14229, 13499, 13500, -1, 14163, 14203, 14190, -1, 14230, 13693, 13654, -1, 14230, 14183, 14214, -1, 14231, 14212, 14200, -1, 14230, 14204, 14183, -1, 14230, 13654, 14204, -1, 14231, 14200, 14216, -1, 14232, 14217, 14229, -1, 14233, 14216, 14202, -1, 14232, 14218, 14217, -1, 14233, 14202, 14219, -1, 14234, 14199, 14215, -1, 14235, 13945, 14228, -1, 14236, 14221, 14220, -1, 14234, 14213, 14199, -1, 14235, 13942, 13945, -1, 14236, 14237, 14221, -1, 14238, 14209, 14197, -1, 14239, 14229, 13500, -1, 14240, 14241, 14224, -1, 14242, 14218, 14232, -1, 14238, 14197, 14225, -1, 14240, 14224, 14222, -1, 14243, 14194, 13476, -1, 14243, 13476, 13597, -1, 14121, 14206, 14144, -1, 14242, 14223, 14218, -1, 14121, 14219, 14206, -1, 14244, 14186, 14226, -1, 14245, 14225, 14212, -1, 14244, 14205, 14186, -1, 14246, 13940, 13942, -1, 14245, 14212, 14231, -1, 14246, 13942, 14235, -1, 14247, 14229, 14239, -1, 14248, 14226, 14211, -1, 14248, 14211, 14227, -1, 14247, 14232, 14229, -1, 14249, 14231, 14216, -1, 14249, 14216, 14233, -1, 14250, 14228, 14223, -1, 14251, 14252, 14237, -1, 14136, 14215, 14203, -1, 14250, 14223, 14242, -1, 14136, 14203, 14163, -1, 14253, 13500, 13586, -1, 14251, 14237, 14236, -1, 14253, 14239, 13500, -1, 14254, 14220, 14209, -1, 14254, 14209, 14238, -1, 14255, 14232, 14247, -1, 14255, 14242, 14232, -1, 14256, 14227, 14213, -1, 14257, 14225, 14245, -1, 14256, 14213, 14234, -1, 14257, 14238, 14225, -1, 14258, 14259, 14241, -1, 14258, 14241, 14240, -1, 14072, 14233, 14219, -1, 14260, 13936, 13938, -1, 14260, 13938, 13940, -1, 14072, 14219, 14121, -1, 14261, 14208, 14194, -1, 14260, 13940, 14246, -1, 14262, 14245, 14231, -1, 14263, 14239, 14253, -1, 14262, 14231, 14249, -1, 14261, 14194, 14243, -1, 14263, 14247, 14239, -1, 14264, 14205, 14244, -1, 14265, 14228, 14250, -1, 14266, 13706, 14267, -1, 14266, 13707, 13706, -1, 14265, 14235, 14228, -1, 14264, 14222, 14205, -1, 14266, 14267, 14252, -1, 14266, 14252, 14251, -1, 14113, 14215, 14136, -1, 14268, 14242, 14255, -1, 14269, 14236, 14220, -1, 14269, 14220, 14254, -1, 14268, 14250, 14242, -1, 14113, 14234, 14215, -1, 14270, 14254, 14238, -1, 14270, 14238, 14257, -1, 14271, 13936, 14260, -1, 14272, 14226, 14248, -1, 14071, 14233, 14072, -1, 14272, 14244, 14226, -1, 14273, 14247, 14263, -1, 14273, 14255, 14247, -1, 14274, 14248, 14227, -1, 14071, 14249, 14233, -1, 14275, 14253, 13586, -1, 14274, 14227, 14256, -1, 14276, 14245, 14262, -1, 14276, 14257, 14245, -1, 14161, 14208, 14261, -1, 14277, 14235, 14265, -1, 14277, 14246, 14235, -1, 14278, 14251, 14236, -1, 14161, 14160, 14208, -1, 14278, 14236, 14269, -1, 14279, 14250, 14268, -1, 14279, 14265, 14250, -1, 14280, 14259, 14258, -1, 14280, 14281, 14259, -1, 14282, 14255, 14273, -1, 14283, 14262, 14249, -1, 14282, 14268, 14255, -1, 14283, 14249, 14071, -1, 14284, 14269, 14254, -1, 14285, 14222, 14264, -1, 14284, 14254, 14270, -1, 14286, 14270, 14257, -1, 14285, 14240, 14222, -1, 14286, 14257, 14276, -1, 14287, 13933, 13936, -1, 14287, 13936, 14271, -1, 14041, 14234, 14113, -1, 14288, 13780, 13707, -1, 14041, 14256, 14234, -1, 14288, 13707, 14266, -1, 14288, 14266, 14251, -1, 14289, 14263, 14253, -1, 14288, 14251, 14278, -1, 14289, 14253, 14275, -1, 14290, 14246, 14277, -1, 14290, 14260, 14246, -1, 14291, 14276, 14262, -1, 14291, 14262, 14283, -1, 14292, 14278, 14269, -1, 14292, 14269, 14284, -1, 14293, 14265, 14279, -1, 14293, 14277, 14265, -1, 14294, 14270, 14286, -1, 14294, 14284, 14270, -1, 14295, 14264, 14244, -1, 14296, 14268, 14282, -1, 14295, 14244, 14272, -1, 14296, 14279, 14268, -1, 14297, 14276, 14291, -1, 14297, 14286, 14276, -1, 14298, 13597, 13666, -1, 14151, 14263, 14289, -1, 14298, 14243, 13597, -1, 14151, 14273, 14263, -1, 14299, 13809, 13780, -1, 14300, 14272, 14248, -1, 14299, 13780, 14288, -1, 14300, 14248, 14274, -1, 14299, 14288, 14278, -1, 14299, 14278, 14292, -1, 14301, 14292, 14284, -1, 14302, 14281, 14280, -1, 14302, 14303, 14281, -1, 14304, 14033, 13933, -1, 14304, 13933, 14287, -1, 14301, 14284, 14294, -1, 14305, 14294, 14286, -1, 14305, 14286, 14297, -1, 14306, 14258, 14240, -1, 14306, 14240, 14285, -1, 14307, 14271, 14260, -1, 14307, 14260, 14290, -1, 14308, 14299, 14292, -1, 14309, 14261, 14243, -1, 14308, 14292, 14301, -1, 14308, 13809, 14299, -1, 14310, 14290, 14277, -1, 14309, 14243, 14298, -1, 14310, 14277, 14293, -1, 14311, 14301, 14294, -1, 14311, 14294, 14305, -1, 14312, 13772, 13809, -1, 14150, 14282, 14273, -1, 14312, 14308, 14301, -1, 14312, 13809, 14308, -1, 14150, 14273, 14151, -1, 14037, 14274, 14256, -1, 14037, 14256, 14041, -1, 14313, 14279, 14296, -1, 14312, 14301, 14311, -1, 14313, 14293, 14279, -1, 14314, 14132, 14315, -1, 14314, 14259, 14281, -1, 14316, 14031, 14033, -1, 14316, 14033, 14304, -1, 14314, 14177, 14132, -1, 14314, 14315, 14259, -1, 14317, 14281, 14303, -1, 14318, 14285, 14264, -1, 14317, 14177, 14314, -1, 14319, 13586, 13588, -1, 14317, 14201, 14177, -1, 14318, 14264, 14295, -1, 14317, 14314, 14281, -1, 14319, 14275, 13586, -1, 14320, 14201, 14317, -1, 14321, 14272, 14300, -1, 14321, 14295, 14272, -1, 14320, 14303, 14322, -1, 14323, 14271, 14307, -1, 14320, 14214, 14201, -1, 14320, 14317, 14303, -1, 14324, 14303, 14302, -1, 14323, 14287, 14271, -1, 14325, 14214, 14320, -1, 14324, 14322, 14303, -1, 14326, 14307, 14290, -1, 14326, 14290, 14310, -1, 14325, 14230, 14214, -1, 14327, 14161, 14261, -1, 14128, 14282, 14150, -1, 14328, 14325, 14320, -1, 14327, 14261, 14309, -1, 14329, 14328, 14320, -1, 14128, 14296, 14282, -1, 14329, 14322, 14330, -1, 14329, 14320, 14322, -1, 14331, 14280, 14258, -1, 14331, 14258, 14306, -1, 14332, 14293, 14313, -1, 14333, 14334, 14335, -1, 14332, 14310, 14293, -1, 14333, 14335, 14210, -1, 14336, 14031, 14316, -1, 14333, 14106, 14334, -1, 14333, 14210, 14221, -1, 14336, 14027, 14029, -1, 14337, 14104, 14106, -1, 14336, 14029, 14031, -1, 14337, 14106, 14333, -1, 14337, 14333, 14221, -1, 14338, 14306, 14285, -1, 14337, 14221, 14237, -1, 14338, 14285, 14318, -1, 14339, 14237, 14252, -1, 14340, 14275, 14319, -1, 14339, 14104, 14337, -1, 14339, 14146, 14104, -1, 14341, 14274, 14037, -1, 14340, 14289, 14275, -1, 14339, 14337, 14237, -1, 14341, 14300, 14274, -1, 14342, 14304, 14287, -1, 14343, 14146, 14339, -1, 14344, 14295, 14321, -1, 14343, 14188, 14146, -1, 14344, 14318, 14295, -1, 14342, 14287, 14323, -1, 14090, 14296, 14128, -1, 14345, 14165, 14161, -1, 14090, 14313, 14296, -1, 14346, 14343, 14339, -1, 14347, 14339, 14252, -1, 14347, 14252, 14267, -1, 14345, 14161, 14327, -1, 14347, 14346, 14339, -1, 14348, 14307, 14326, -1, 14349, 13818, 13724, -1, 14349, 13724, 14330, -1, 14349, 14330, 14322, -1, 14348, 14323, 14307, -1, 14350, 14351, 14352, -1, 14349, 14322, 14324, -1, 14350, 14311, 14305, -1, 14353, 14326, 14310, -1, 14353, 14310, 14332, -1, 14350, 14352, 14354, -1, 14355, 13666, 13689, -1, 14350, 14305, 14351, -1, 14355, 14298, 13666, -1, 14356, 14312, 14311, -1, 14356, 14311, 14350, -1, 14357, 14280, 14331, -1, 14152, 14289, 14340, -1, 14357, 14302, 14280, -1, 14152, 14151, 14289, -1, 14358, 14356, 14350, -1, 14359, 14027, 14336, -1, 14360, 14354, 14361, -1, 14360, 14350, 14354, -1, 14360, 14358, 14350, -1, 14362, 14315, 14132, -1, 14363, 14316, 14304, -1, 14362, 14063, 14070, -1, 14362, 14132, 14063, -1, 14363, 14304, 14342, -1, 14364, 14331, 14306, -1, 14364, 14306, 14338, -1, 14365, 14315, 14362, -1, 14366, 14300, 14341, -1, 14089, 14313, 14090, -1, 14089, 14332, 14313, -1, 14367, 14241, 14259, -1, 14367, 14224, 14241, -1, 14366, 14321, 14300, -1, 14367, 14259, 14315, -1, 14367, 14315, 14365, -1, 14368, 14318, 14344, -1, 14369, 14230, 14325, -1, 14369, 14325, 14328, -1, 14368, 14338, 14318, -1, 14369, 13693, 14230, -1, 14370, 13724, 13693, -1, 14371, 14298, 14355, -1, 14370, 13693, 14369, -1, 14371, 14309, 14298, -1, 14370, 14369, 14328, -1, 14372, 14342, 14323, -1, 14373, 14330, 13724, -1, 14373, 13724, 14370, -1, 14372, 14323, 14348, -1, 14373, 14329, 14330, -1, 14373, 14328, 14329, -1, 14373, 14370, 14328, -1, 14374, 14335, 14334, -1, 14375, 14319, 13588, -1, 14374, 14334, 14376, -1, 14085, 14165, 14345, -1, 14374, 14376, 14366, -1, 14375, 13588, 13768, -1, 14085, 14141, 14165, -1, 14377, 14348, 14326, -1, 14377, 14326, 14353, -1, 14378, 14335, 14374, -1, 14379, 14355, 13689, -1, 14380, 14335, 14378, -1, 14380, 14170, 14198, -1, 14380, 14198, 14210, -1, 14380, 14210, 14335, -1, 14039, 14025, 14027, -1, 14381, 14302, 14357, -1, 14039, 14027, 14359, -1, 14382, 13569, 14188, -1, 14382, 14188, 14343, -1, 14381, 14324, 14302, -1, 14382, 14343, 14346, -1, 14383, 14382, 14346, -1, 14384, 14316, 14363, -1, 14383, 13569, 14382, -1, 14383, 13706, 13569, -1, 14385, 14267, 13706, -1, 14384, 14336, 14316, -1, 14385, 14383, 14346, -1, 14385, 13706, 14383, -1, 14385, 14347, 14267, -1, 14385, 14346, 14347, -1, 14077, 14340, 14319, -1, 14386, 14305, 14297, -1, 14045, 14331, 14364, -1, 14077, 14319, 14375, -1, 14386, 14351, 14305, -1, 14045, 14357, 14331, -1, 14386, 14297, 14291, -1, 14387, 14351, 14386, -1, 14388, 14353, 14332, -1, 14376, 14321, 14366, -1, 14388, 14332, 14089, -1, 14376, 14344, 14321, -1, 14389, 14351, 14387, -1, 14389, 14352, 14351, -1, 14389, 14390, 14352, -1, 14389, 14391, 14390, -1, 14392, 14309, 14371, -1, 14393, 13772, 14312, -1, 14393, 14312, 14356, -1, 14392, 14327, 14309, -1, 14394, 14393, 14356, -1, 14395, 14342, 14372, -1, 14395, 14363, 14342, -1, 14394, 14356, 14358, -1, 14105, 14338, 14368, -1, 14105, 14364, 14338, -1, 14396, 13772, 14393, -1, 14396, 14393, 14394, -1, 14065, 14348, 14377, -1, 14065, 14372, 14348, -1, 14397, 13778, 13772, -1, 14084, 14141, 14085, -1, 14397, 14396, 14394, -1, 14397, 13772, 14396, -1, 14397, 14394, 14358, -1, 14397, 14361, 13778, -1, 14397, 14360, 14361, -1, 14084, 14118, 14141, -1, 14397, 14358, 14360, -1, 14042, 14023, 14025, -1, 14398, 14070, 14399, -1, 14060, 14355, 14379, -1, 14398, 14365, 14362, -1, 14398, 14362, 14070, -1, 14042, 14025, 14039, -1, 14076, 14340, 14077, -1, 14400, 14365, 14398, -1, 14060, 14371, 14355, -1, 14095, 14345, 14327, -1, 14095, 14327, 14392, -1, 14076, 14152, 14340, -1, 14401, 14365, 14400, -1, 14056, 14359, 14336, -1, 14401, 14367, 14365, -1, 14401, 14224, 14367, -1, 14401, 14207, 14224, -1, 14402, 13858, 13818, -1, 14056, 14336, 14384, -1, 14403, 14374, 14366, -1, 14402, 14349, 14324, -1, 14403, 14378, 14374, -1, 14402, 13818, 14349, -1, 14402, 14324, 14381, -1, 14403, 14366, 14341, -1, 14074, 14379, 13689, -1, 14074, 13689, 13624, -1, 14404, 14378, 14403, -1, 14087, 14384, 14363, -1, 14087, 14363, 14395, -1, 14047, 14381, 14357, -1, 14047, 14357, 14045, -1, 14405, 14380, 14378, -1, 14405, 14378, 14404, -1, 14405, 14170, 14380, -1, 14405, 14130, 14170, -1, 14406, 14386, 14291, -1, 14334, 14368, 14344, -1, 14399, 14377, 14353, -1, 14399, 14353, 14388, -1, 14406, 14387, 14386, -1, 14334, 14344, 14376, -1, 14406, 14291, 14283, -1, 14064, 14395, 14372, -1, 14064, 14372, 14065, -1, 14407, 14387, 14406, -1, 14115, 14152, 14076, -1, 14408, 14391, 14389, -1, 14408, 14409, 14391, -1, 14408, 14387, 14407, -1, 14046, 14045, 14364, -1, 14408, 14389, 14387, -1, 14046, 14364, 14105, -1, 14115, 14156, 14152, -1, 14410, 14400, 14398, -1, 14122, 13630, 13629, -1, 14410, 14399, 14388, -1, 14062, 14392, 14371, -1, 14122, 14023, 14042, -1, 14410, 14398, 14399, -1, 14122, 13629, 14021, -1, 14122, 14021, 14023, -1, 14411, 14207, 14401, -1, 14411, 14401, 14400, -1, 14062, 14371, 14060, -1, 14111, 13768, 13471, -1, 14411, 14400, 14410, -1, 14411, 14187, 14207, -1, 14111, 14375, 13768, -1, 14036, 14341, 14037, -1, 14036, 14404, 14403, -1, 14036, 14403, 14341, -1, 14040, 14359, 14056, -1, 14051, 14118, 14084, -1, 14040, 14039, 14359, -1, 14054, 14405, 14404, -1, 14054, 14130, 14405, -1, 14054, 14049, 14130, -1, 14051, 14050, 14118, -1, 14054, 14404, 14036, -1, 14061, 14060, 14379, -1, 14068, 14406, 14283, -1, 14068, 14407, 14406, -1, 14061, 14379, 14074, -1, 14068, 14283, 14071, -1, 14058, 14384, 14087, -1, 14067, 14407, 14068, -1, 14092, 14345, 14095, -1, 14058, 14056, 14384, -1, 14082, 14407, 14067, -1, 14070, 14377, 14399, -1, 14082, 14081, 14409, -1, 14082, 14409, 14408, -1, 14092, 14085, 14345, -1, 14082, 14408, 14407, -1, 14097, 14095, 14392, -1, 14070, 14065, 14377, -1, 14091, 14388, 14089, -1, 14093, 14395, 14064, -1, 14091, 14410, 14388, -1, 14097, 14392, 14062, -1, 14093, 14087, 14395, -1, 14125, 13507, 13858, -1, 14125, 14381, 14047, -1, 14125, 14402, 14381, -1, 14125, 13858, 14402, -1, 14096, 14410, 14091, -1, 14106, 14368, 14334, -1, 14078, 14375, 14111, -1, 14106, 14105, 14368, -1, 14108, 14410, 14096, -1, 14078, 14077, 14375, -1, 14412, 14411, 14410, -1, 14412, 14410, 14108, -1, 14102, 14100, 14156, -1, 14107, 14103, 14187, -1, 14102, 14156, 14115, -1, 14107, 14187, 14411, -1, 14107, 14411, 14412, -1, 14107, 14412, 14108, -1, 14112, 14111, 13471, -1, 13189, 13194, 13816, -1, 13189, 13816, 13783, -1, 13006, 13783, 13782, -1, 13006, 13189, 13783, -1, 13007, 13782, 13778, -1, 13007, 13006, 13782, -1, 14413, 13778, 14361, -1, 14413, 13007, 13778, -1, 14414, 14361, 14354, -1, 14414, 14413, 14361, -1, 14415, 14354, 14352, -1, 14415, 14414, 14354, -1, 14416, 14352, 14390, -1, 14416, 14415, 14352, -1, 14417, 14390, 14391, -1, 14417, 14416, 14390, -1, 14418, 14391, 14409, -1, 14418, 14417, 14391, -1, 14419, 14409, 14081, -1, 14419, 14418, 14409, -1, 14420, 14081, 14080, -1, 14420, 14419, 14081, -1, 14421, 14080, 14173, -1, 14421, 14420, 14080, -1, 14422, 14173, 14193, -1, 14422, 14421, 14173, -1, 14423, 14193, 14181, -1, 14423, 14422, 14193, -1, 14424, 14181, 14180, -1, 14424, 14423, 14181, -1, 14425, 14424, 14180, -1, 14425, 14180, 14182, -1, 13927, 14425, 14182, -1, 13927, 14182, 13928, -1, 14426, 14427, 14428, -1, 14426, 14429, 14430, -1, 14426, 14428, 14429, -1, 14426, 14430, 14427, -1, 14431, 14432, 14433, -1, 14431, 14433, 14434, -1, 14435, 14430, 14429, -1, 14436, 14437, 14438, -1, 14439, 14440, 14441, -1, 14442, 14443, 14444, -1, 14439, 14441, 14445, -1, 14436, 14438, 14446, -1, 14442, 14444, 14430, -1, 14442, 14430, 14435, -1, 14447, 14448, 13170, -1, 14449, 14450, 14451, -1, 14447, 13170, 13173, -1, 14449, 14452, 14450, -1, 14447, 13173, 14001, -1, 14453, 14454, 14455, -1, 14456, 14449, 14457, -1, 14456, 14452, 14449, -1, 14453, 14455, 14458, -1, 14456, 14457, 14459, -1, 14460, 14461, 14462, -1, 14456, 14459, 14452, -1, 14460, 14463, 14461, -1, 14464, 14459, 14457, -1, 14465, 14446, 14466, -1, 14465, 14466, 14467, -1, 14468, 13990, 13988, -1, 14468, 14459, 14464, -1, 14468, 13988, 14459, -1, 14469, 14470, 14471, -1, 14472, 14473, 14474, -1, 14472, 14474, 14475, -1, 14469, 14471, 14476, -1, 14477, 14478, 14479, -1, 14472, 14480, 14473, -1, 14472, 14481, 14480, -1, 14477, 14482, 14478, -1, 14483, 14481, 14472, -1, 14483, 14484, 14485, -1, 14486, 14462, 14487, -1, 14483, 14482, 14484, -1, 14483, 14485, 14481, -1, 14488, 14458, 14489, -1, 14490, 14428, 14491, -1, 14488, 14489, 14492, -1, 14486, 14487, 14493, -1, 14490, 14429, 14428, -1, 14494, 14495, 14496, -1, 14497, 13203, 13005, -1, 14494, 13072, 14495, -1, 14490, 14491, 14498, -1, 14494, 14496, 14499, -1, 14497, 13005, 14500, -1, 14490, 14435, 14429, -1, 14497, 14500, 14501, -1, 14502, 14492, 14440, -1, 14503, 14443, 14442, -1, 14497, 14501, 14504, -1, 14503, 14442, 14435, -1, 14503, 14505, 14443, -1, 14503, 14435, 14490, -1, 14506, 14457, 14449, -1, 14502, 14440, 14439, -1, 14507, 14463, 14460, -1, 14506, 14464, 14457, -1, 14507, 14508, 14463, -1, 14506, 14449, 14451, -1, 14509, 13032, 13031, -1, 14506, 14451, 14510, -1, 14511, 14468, 14464, -1, 14511, 13990, 14468, -1, 14509, 14493, 13032, -1, 14512, 14513, 14444, -1, 14511, 13992, 13990, -1, 14511, 14464, 14506, -1, 14512, 14444, 14514, -1, 14515, 14475, 14516, -1, 14517, 14447, 14001, -1, 14518, 14432, 14431, -1, 14515, 14472, 14475, -1, 14517, 14448, 14447, -1, 14518, 14465, 14467, -1, 14518, 14467, 14432, -1, 14517, 14001, 13999, -1, 14519, 14472, 14515, -1, 14517, 14445, 14448, -1, 14520, 14504, 14437, -1, 14520, 14437, 14436, -1, 14521, 14482, 14483, -1, 14522, 14454, 14453, -1, 14521, 14472, 14519, -1, 14521, 14483, 14472, -1, 14521, 14478, 14482, -1, 14523, 14490, 14498, -1, 14522, 14524, 14454, -1, 14523, 14498, 14525, -1, 14526, 14490, 14523, -1, 14527, 14436, 14446, -1, 14527, 14446, 14465, -1, 14528, 14460, 14462, -1, 13005, 13007, 14413, -1, 14529, 14470, 14469, -1, 14530, 14505, 14503, -1, 14528, 14462, 14486, -1, 14530, 14503, 14490, -1, 14530, 14531, 14505, -1, 14530, 14490, 14526, -1, 14529, 14499, 14470, -1, 14532, 14510, 14533, -1, 14534, 14458, 14488, -1, 14534, 14453, 14458, -1, 14532, 14506, 14510, -1, 14535, 14482, 14477, -1, 14536, 14492, 14502, -1, 14535, 14484, 14482, -1, 14537, 14506, 14532, -1, 14538, 14511, 14506, -1, 14539, 14486, 14493, -1, 14538, 13992, 14511, -1, 14538, 13994, 13992, -1, 14536, 14488, 14492, -1, 14539, 14493, 14509, -1, 14538, 14506, 14537, -1, 14540, 14541, 14542, -1, 14543, 14445, 14517, -1, 14540, 14516, 14541, -1, 14543, 14439, 14445, -1, 14540, 14519, 14515, -1, 14540, 14515, 14516, -1, 14544, 14479, 14508, -1, 14544, 14508, 14507, -1, 14545, 14540, 14542, -1, 14545, 14521, 14519, -1, 14545, 14478, 14521, -1, 14545, 14519, 14540, -1, 14545, 14546, 14547, -1, 14545, 14542, 14546, -1, 14545, 14547, 14478, -1, 14548, 14513, 14512, -1, 14549, 14523, 14525, -1, 14549, 14525, 14550, -1, 14549, 14526, 14523, -1, 14548, 14551, 14513, -1, 14549, 14550, 14552, -1, 14553, 14465, 14518, -1, 14554, 14555, 14556, -1, 14554, 14556, 14531, -1, 14554, 14526, 14549, -1, 14557, 14524, 14522, -1, 14554, 14552, 14555, -1, 14558, 13212, 13203, -1, 14554, 14549, 14552, -1, 14558, 13203, 14497, -1, 14554, 14530, 14526, -1, 14554, 14531, 14530, -1, 14558, 14497, 14504, -1, 14559, 14532, 14533, -1, 14557, 14514, 14524, -1, 14558, 14504, 14520, -1, 14559, 14537, 14532, -1, 14559, 14560, 14543, -1, 14559, 14533, 14560, -1, 14561, 13997, 13994, -1, 14562, 14507, 14460, -1, 14562, 14460, 14528, -1, 14561, 13994, 14538, -1, 14561, 14538, 14537, -1, 14563, 13132, 13072, -1, 14561, 14537, 14559, -1, 14564, 14543, 14517, -1, 14564, 14517, 13999, -1, 14563, 13072, 14494, -1, 14565, 14520, 14436, -1, 14564, 13999, 13997, -1, 14563, 14494, 14499, -1, 14565, 14436, 14527, -1, 14564, 14559, 14543, -1, 14563, 14499, 14529, -1, 14566, 14484, 14535, -1, 14564, 13997, 14561, -1, 14567, 14453, 14534, -1, 14564, 14561, 14559, -1, 14567, 14522, 14453, -1, 14566, 14568, 14484, -1, 14569, 14486, 14539, -1, 14560, 14502, 14439, -1, 14569, 14528, 14486, -1, 14560, 14439, 14543, -1, 14570, 14509, 13031, -1, 14571, 14488, 14536, -1, 14571, 14534, 14488, -1, 14572, 14479, 14544, -1, 14572, 14477, 14479, -1, 14573, 14574, 14551, -1, 14573, 14551, 14548, -1, 14575, 14512, 14514, -1, 14575, 14514, 14557, -1, 14576, 14465, 14553, -1, 14576, 14527, 14465, -1, 14577, 14507, 14562, -1, 14577, 14544, 14507, -1, 14578, 14557, 14522, -1, 14579, 14558, 14520, -1, 14579, 14520, 14565, -1, 14579, 13212, 14558, -1, 14580, 14528, 14569, -1, 14580, 14562, 14528, -1, 14578, 14522, 14567, -1, 14533, 14536, 14502, -1, 14533, 14502, 14560, -1, 14581, 14582, 14568, -1, 14581, 14568, 14566, -1, 14583, 14567, 14534, -1, 14583, 14534, 14571, -1, 14584, 14509, 14570, -1, 14585, 14586, 14574, -1, 14584, 14539, 14509, -1, 14585, 14574, 14573, -1, 14587, 14535, 14477, -1, 14587, 14477, 14572, -1, 14588, 14512, 14575, -1, 14588, 14548, 14512, -1, 14589, 14527, 14576, -1, 14589, 14565, 14527, -1, 14590, 14557, 14578, -1, 14591, 14572, 14544, -1, 14591, 14544, 14577, -1, 14590, 14575, 14557, -1, 14592, 14562, 14580, -1, 14592, 14577, 14562, -1, 14510, 14571, 14536, -1, 14510, 14536, 14533, -1, 14552, 14569, 14539, -1, 14593, 14578, 14567, -1, 14552, 14539, 14584, -1, 14593, 14567, 14583, -1, 14594, 14595, 14582, -1, 14596, 13932, 13412, -1, 14596, 13412, 13057, -1, 14597, 14586, 14585, -1, 14597, 14598, 14586, -1, 14594, 14582, 14581, -1, 14599, 13932, 14596, -1, 14599, 13930, 13932, -1, 14600, 14566, 14535, -1, 14601, 14573, 14548, -1, 14601, 14548, 14588, -1, 14600, 14535, 14587, -1, 14602, 14575, 14590, -1, 14603, 13927, 13930, -1, 14602, 14588, 14575, -1, 14603, 13930, 14599, -1, 14604, 13254, 13212, -1, 14604, 14579, 14565, -1, 14604, 13212, 14579, -1, 14604, 14565, 14589, -1, 14451, 14571, 14510, -1, 14605, 14572, 14591, -1, 14606, 14425, 13927, -1, 14605, 14587, 14572, -1, 14606, 13927, 14603, -1, 14451, 14583, 14571, -1, 14607, 14596, 13057, -1, 14607, 13057, 13060, -1, 14550, 14580, 14569, -1, 14608, 14578, 14593, -1, 14550, 14569, 14552, -1, 14608, 14590, 14578, -1, 14609, 14591, 14577, -1, 14610, 14596, 14607, -1, 14611, 14598, 14597, -1, 14609, 14577, 14592, -1, 14610, 14599, 14596, -1, 14611, 14612, 14598, -1, 14613, 14585, 14573, -1, 14614, 14595, 14594, -1, 14613, 14597, 14585, -1, 14615, 14424, 14425, -1, 14615, 14425, 14606, -1, 14613, 14573, 14601, -1, 14614, 14616, 14595, -1, 14617, 14570, 13031, -1, 14618, 14601, 14588, -1, 14617, 13031, 13167, -1, 14619, 14607, 13060, -1, 14618, 14588, 14602, -1, 14620, 14599, 14610, -1, 14621, 14581, 14566, -1, 14621, 14566, 14600, -1, 14450, 14593, 14583, -1, 14620, 14603, 14599, -1, 14450, 14583, 14451, -1, 14622, 14602, 14590, -1, 14622, 14590, 14608, -1, 14623, 14423, 14424, -1, 14623, 14424, 14615, -1, 14624, 14610, 14607, -1, 14625, 14600, 14587, -1, 14624, 14607, 14619, -1, 14625, 14587, 14605, -1, 14626, 14603, 14620, -1, 14627, 14612, 14611, -1, 14627, 14628, 14612, -1, 14525, 14592, 14580, -1, 14629, 14597, 14613, -1, 14626, 14606, 14603, -1, 14525, 14580, 14550, -1, 14630, 14605, 14591, -1, 14631, 14619, 13060, -1, 14630, 14591, 14609, -1, 14632, 14613, 14601, -1, 14631, 13060, 13152, -1, 14632, 14601, 14618, -1, 14633, 14634, 14616, -1, 14635, 14593, 14450, -1, 14636, 14620, 14610, -1, 14635, 14608, 14593, -1, 14633, 14616, 14614, -1, 14636, 14610, 14624, -1, 14637, 14584, 14570, -1, 14638, 14602, 14622, -1, 14638, 14618, 14602, -1, 14637, 14570, 14617, -1, 14639, 14422, 14423, -1, 14639, 14423, 14623, -1, 14640, 14624, 14619, -1, 14641, 14594, 14581, -1, 14642, 14628, 14627, -1, 14642, 14643, 14628, -1, 14642, 13265, 13264, -1, 14641, 14581, 14621, -1, 14640, 14619, 14631, -1, 14642, 13264, 14643, -1, 14644, 14606, 14626, -1, 14645, 14611, 14597, -1, 14645, 14597, 14629, -1, 14644, 14615, 14606, -1, 14646, 14622, 14608, -1, 14646, 14608, 14635, -1, 14647, 14621, 14600, -1, 14647, 14600, 14625, -1, 14648, 14620, 14636, -1, 14648, 14626, 14620, -1, 14649, 14629, 14613, -1, 14498, 14592, 14525, -1, 14649, 14613, 14632, -1, 14650, 14421, 14422, -1, 14498, 14609, 14592, -1, 14651, 14625, 14605, -1, 14650, 14422, 14639, -1, 14652, 14632, 14618, -1, 14652, 14618, 14638, -1, 14653, 14636, 14624, -1, 14651, 14605, 14630, -1, 14653, 14624, 14640, -1, 14654, 14627, 14611, -1, 14555, 14584, 14637, -1, 14655, 14631, 13152, -1, 14654, 14611, 14645, -1, 14555, 14552, 14584, -1, 14656, 14615, 14644, -1, 14657, 14638, 14622, -1, 14658, 14634, 14633, -1, 14657, 14622, 14646, -1, 14656, 14623, 14615, -1, 14659, 14626, 14648, -1, 14658, 14660, 14634, -1, 14659, 14644, 14626, -1, 14661, 14629, 14649, -1, 14661, 14645, 14629, -1, 14662, 14594, 14641, -1, 14662, 14614, 14594, -1, 14663, 14649, 14632, -1, 14663, 14632, 14652, -1, 14664, 14636, 14653, -1, 14665, 14641, 14621, -1, 14664, 14648, 14636, -1, 14665, 14621, 14647, -1, 14666, 13338, 13265, -1, 14666, 14627, 14654, -1, 14666, 14642, 14627, -1, 14666, 13265, 14642, -1, 14667, 14420, 14421, -1, 14667, 14421, 14650, -1, 14668, 14652, 14638, -1, 14668, 14638, 14657, -1, 14669, 14640, 14631, -1, 14669, 14631, 14655, -1, 14670, 14654, 14645, -1, 14670, 14645, 14661, -1, 14671, 14623, 14656, -1, 14671, 14639, 14623, -1, 14491, 14630, 14609, -1, 14491, 14609, 14498, -1, 14672, 14661, 14649, -1, 14672, 14649, 14663, -1, 14673, 14644, 14659, -1, 14674, 13167, 13224, -1, 14673, 14656, 14644, -1, 14675, 14652, 14668, -1, 14674, 14617, 13167, -1, 14675, 14663, 14652, -1, 14676, 13367, 13338, -1, 14677, 14625, 14651, -1, 14678, 14659, 14648, -1, 14676, 13338, 14666, -1, 14676, 14654, 14670, -1, 14678, 14648, 14664, -1, 14676, 14666, 14654, -1, 14677, 14647, 14625, -1, 14679, 14670, 14661, -1, 14680, 14681, 14660, -1, 14680, 14660, 14658, -1, 14542, 14653, 14640, -1, 14679, 14661, 14672, -1, 14682, 14672, 14663, -1, 14542, 14640, 14669, -1, 14683, 14614, 14662, -1, 14682, 14663, 14675, -1, 14683, 14633, 14614, -1, 14684, 14419, 14420, -1, 14685, 14676, 14670, -1, 14685, 14670, 14679, -1, 14686, 14637, 14617, -1, 14684, 14420, 14667, -1, 14685, 13367, 14676, -1, 14686, 14617, 14674, -1, 14687, 14650, 14639, -1, 14687, 14639, 14671, -1, 14688, 14679, 14672, -1, 14688, 14672, 14682, -1, 14689, 14679, 14688, -1, 14690, 14662, 14641, -1, 14689, 14685, 14679, -1, 14541, 14653, 14542, -1, 14689, 13331, 13367, -1, 14689, 13367, 14685, -1, 14690, 14641, 14665, -1, 14541, 14664, 14653, -1, 14691, 14671, 14656, -1, 14691, 14656, 14673, -1, 14692, 14693, 14634, -1, 14692, 14518, 14693, -1, 14692, 14634, 14660, -1, 14694, 14630, 14491, -1, 14692, 14553, 14518, -1, 14694, 14651, 14630, -1, 14695, 14659, 14678, -1, 14696, 14660, 14681, -1, 14695, 14673, 14659, -1, 14696, 14553, 14692, -1, 14696, 14576, 14553, -1, 14696, 14692, 14660, -1, 14697, 14589, 14576, -1, 14698, 14665, 14647, -1, 14697, 14576, 14696, -1, 14698, 14647, 14677, -1, 14699, 14418, 14419, -1, 14699, 14419, 14684, -1, 14697, 14681, 14700, -1, 14701, 14681, 14680, -1, 14697, 14696, 14681, -1, 14701, 14700, 14681, -1, 14702, 14589, 14697, -1, 14703, 13152, 13158, -1, 14704, 14637, 14686, -1, 14704, 14555, 14637, -1, 14703, 14655, 13152, -1, 14702, 14604, 14589, -1, 14705, 14650, 14687, -1, 14706, 14702, 14697, -1, 14707, 14697, 14700, -1, 14705, 14667, 14650, -1, 14707, 14706, 14697, -1, 14708, 14658, 14633, -1, 14516, 14678, 14664, -1, 14707, 14700, 14709, -1, 14708, 14633, 14683, -1, 14710, 14662, 14690, -1, 14516, 14664, 14541, -1, 14710, 14683, 14662, -1, 14711, 14476, 14712, -1, 14713, 14687, 14671, -1, 14711, 14712, 14714, -1, 14711, 14714, 14586, -1, 14713, 14671, 14691, -1, 14711, 14586, 14598, -1, 14715, 14469, 14476, -1, 14716, 14673, 14695, -1, 14715, 14476, 14711, -1, 14715, 14711, 14598, -1, 14716, 14691, 14673, -1, 14715, 14598, 14612, -1, 14717, 14418, 14699, -1, 14718, 14469, 14715, -1, 14718, 14715, 14612, -1, 14719, 14677, 14651, -1, 14717, 14417, 14418, -1, 14718, 14612, 14628, -1, 14719, 14651, 14694, -1, 14718, 14529, 14469, -1, 14720, 14529, 14718, -1, 14721, 14690, 14665, -1, 14720, 14563, 14529, -1, 14721, 14665, 14698, -1, 14722, 13376, 13283, -1, 14723, 14655, 14703, -1, 14722, 13415, 13376, -1, 14722, 13283, 14709, -1, 14722, 14709, 14700, -1, 14724, 14720, 14718, -1, 14723, 14669, 14655, -1, 14722, 14700, 14701, -1, 14725, 14556, 14555, -1, 14726, 14628, 14643, -1, 14726, 14724, 14718, -1, 14727, 14684, 14667, -1, 14726, 14718, 14628, -1, 14725, 14555, 14704, -1, 14727, 14667, 14705, -1, 14475, 14695, 14678, -1, 14728, 14675, 14668, -1, 14475, 14678, 14516, -1, 14729, 13224, 13249, -1, 14728, 14668, 14730, -1, 14728, 13979, 13977, -1, 14729, 14674, 13224, -1, 14728, 14730, 13979, -1, 14731, 14705, 14687, -1, 14732, 14682, 14675, -1, 14731, 14687, 14713, -1, 14733, 14680, 14658, -1, 14732, 13977, 13975, -1, 14732, 14675, 14728, -1, 14733, 14658, 14708, -1, 14732, 14728, 13977, -1, 14734, 14698, 14677, -1, 14735, 14713, 14691, -1, 14736, 13975, 13973, -1, 14735, 14691, 14716, -1, 14736, 14732, 13975, -1, 14734, 14677, 14719, -1, 14736, 14682, 14732, -1, 14546, 14542, 14669, -1, 14736, 14688, 14682, -1, 14737, 14689, 14688, -1, 14546, 14669, 14723, -1, 14737, 14688, 14736, -1, 14738, 14708, 14683, -1, 14738, 14683, 14710, -1, 14739, 14737, 14736, -1, 14740, 14416, 14417, -1, 14740, 14417, 14717, -1, 14741, 14736, 13973, -1, 14741, 13973, 13971, -1, 14741, 14739, 14736, -1, 14742, 14693, 14518, -1, 14743, 14690, 14721, -1, 14744, 14699, 14684, -1, 14742, 14431, 14434, -1, 14742, 14518, 14431, -1, 14743, 14710, 14690, -1, 14744, 14684, 14727, -1, 14745, 14693, 14742, -1, 14746, 14686, 14674, -1, 14747, 14727, 14705, -1, 14746, 14674, 14729, -1, 14748, 14634, 14693, -1, 14747, 14705, 14731, -1, 14748, 14616, 14634, -1, 14748, 14693, 14745, -1, 14748, 14595, 14616, -1, 14455, 14531, 14556, -1, 14749, 14604, 14702, -1, 14749, 14702, 14706, -1, 14749, 13254, 14604, -1, 14750, 13283, 13254, -1, 14750, 13254, 14749, -1, 14474, 14716, 14695, -1, 14750, 14749, 14706, -1, 14751, 14750, 14706, -1, 14455, 14556, 14725, -1, 14751, 14709, 13283, -1, 14752, 14729, 13249, -1, 14751, 14707, 14709, -1, 14474, 14695, 14475, -1, 14751, 14706, 14707, -1, 14753, 14703, 13158, -1, 14751, 13283, 14750, -1, 14753, 13158, 13327, -1, 14754, 14714, 14712, -1, 14754, 14712, 14755, -1, 14754, 14755, 14734, -1, 14756, 14714, 14754, -1, 14757, 14680, 14733, -1, 14758, 14731, 14713, -1, 14757, 14701, 14680, -1, 14758, 14713, 14735, -1, 14759, 14574, 14586, -1, 14755, 14698, 14734, -1, 14760, 14415, 14416, -1, 14759, 14586, 14714, -1, 14755, 14721, 14698, -1, 14759, 14551, 14574, -1, 14759, 14714, 14756, -1, 14760, 14416, 14740, -1, 14761, 14733, 14708, -1, 14762, 13132, 14563, -1, 14761, 14708, 14738, -1, 14762, 14563, 14720, -1, 14762, 14720, 14724, -1, 14763, 14717, 14699, -1, 14764, 13264, 13132, -1, 14764, 14762, 14724, -1, 14764, 13132, 14762, -1, 14763, 14699, 14744, -1, 14765, 14764, 14724, -1, 14765, 13264, 14764, -1, 14765, 14726, 14643, -1, 14461, 14723, 14703, -1, 14765, 14724, 14726, -1, 14461, 14703, 14753, -1, 14765, 14643, 13264, -1, 14766, 14730, 14668, -1, 14767, 14686, 14746, -1, 14768, 14727, 14747, -1, 14766, 14668, 14657, -1, 14768, 14744, 14727, -1, 14766, 14657, 14646, -1, 14767, 14704, 14686, -1, 14769, 14730, 14766, -1, 14471, 14710, 14743, -1, 14770, 14730, 14769, -1, 14770, 13981, 13979, -1, 14471, 14738, 14710, -1, 14770, 13983, 13981, -1, 14771, 14716, 14474, -1, 14770, 13979, 14730, -1, 14454, 14531, 14455, -1, 14772, 14689, 14737, -1, 14771, 14735, 14716, -1, 14772, 13331, 14689, -1, 14772, 14737, 14739, -1, 14454, 14505, 14531, -1, 14773, 13333, 13331, -1, 14773, 14772, 14739, -1, 14773, 13331, 14772, -1, 14441, 14746, 14729, -1, 14433, 14731, 14758, -1, 14433, 14747, 14731, -1, 14441, 14729, 14752, -1, 14774, 14773, 14739, -1, 14774, 13971, 13333, -1, 14774, 13333, 14773, -1, 14774, 14741, 13971, -1, 14774, 14739, 14741, -1, 14501, 14415, 14760, -1, 14489, 14725, 14704, -1, 14501, 14414, 14415, -1, 14489, 14704, 14767, -1, 14775, 14745, 14742, -1, 14775, 14742, 14434, -1, 14463, 14723, 14461, -1, 14775, 14434, 14776, -1, 14463, 14546, 14723, -1, 14777, 14745, 14775, -1, 14778, 13415, 14722, -1, 14778, 14722, 14701, -1, 14779, 14582, 14595, -1, 14779, 14745, 14777, -1, 14778, 14701, 14757, -1, 14438, 14740, 14717, -1, 14448, 14752, 13249, -1, 14438, 14717, 14763, -1, 14779, 14748, 14745, -1, 14448, 13249, 13170, -1, 14779, 14595, 14748, -1, 14780, 14756, 14754, -1, 14780, 14734, 14719, -1, 14780, 14754, 14734, -1, 14712, 14743, 14721, -1, 14466, 14763, 14744, -1, 14712, 14721, 14755, -1, 14466, 14744, 14768, -1, 14496, 14733, 14761, -1, 14496, 14757, 14733, -1, 14781, 14756, 14780, -1, 14782, 14759, 14756, -1, 14782, 14551, 14759, -1, 14782, 14756, 14781, -1, 14782, 14513, 14551, -1, 14776, 14735, 14771, -1, 14783, 14769, 14766, -1, 14776, 14758, 14735, -1, 14783, 14646, 14635, -1, 14783, 14766, 14646, -1, 14470, 14761, 14738, -1, 14470, 14738, 14471, -1, 14432, 14768, 14747, -1, 14432, 14747, 14433, -1, 14500, 14414, 14501, -1, 14784, 14769, 14783, -1, 14500, 13005, 14413, -1, 14440, 14746, 14441, -1, 14500, 14413, 14414, -1, 14785, 13983, 14770, -1, 14785, 14770, 14769, -1, 14785, 13985, 13983, -1, 14785, 14769, 14784, -1, 14508, 14546, 14463, -1, 14786, 14776, 14771, -1, 14440, 14767, 14746, -1, 14508, 14547, 14546, -1, 14786, 14775, 14776, -1, 14786, 14777, 14775, -1, 14524, 14443, 14505, -1, 14787, 14568, 14582, -1, 14487, 13327, 13032, -1, 14787, 14582, 14779, -1, 14787, 14779, 14777, -1, 14487, 14753, 13327, -1, 14787, 14777, 14786, -1, 14524, 14505, 14454, -1, 14427, 14719, 14694, -1, 14445, 14752, 14448, -1, 14427, 14780, 14719, -1, 14437, 14760, 14740, -1, 14427, 14781, 14780, -1, 14437, 14740, 14438, -1, 14445, 14441, 14752, -1, 14434, 14758, 14776, -1, 14430, 14781, 14427, -1, 14430, 14782, 14781, -1, 14458, 14455, 14725, -1, 14430, 14513, 14782, -1, 14430, 14444, 14513, -1, 14434, 14433, 14758, -1, 14446, 14438, 14763, -1, 14452, 14635, 14450, -1, 14446, 14763, 14466, -1, 14452, 14783, 14635, -1, 14452, 14784, 14783, -1, 14458, 14725, 14489, -1, 14459, 13988, 13985, -1, 14459, 14785, 14784, -1, 14459, 13985, 14785, -1, 14459, 14784, 14452, -1, 14473, 14771, 14474, -1, 14473, 14786, 14771, -1, 14476, 14743, 14712, -1, 14467, 14768, 14432, -1, 14476, 14471, 14743, -1, 14467, 14466, 14768, -1, 14495, 13072, 13415, -1, 14495, 14778, 14757, -1, 14495, 14757, 14496, -1, 14788, 14480, 14787, -1, 14495, 13415, 14778, -1, 14462, 14753, 14487, -1, 14788, 14787, 14786, -1, 14788, 14786, 14473, -1, 14492, 14489, 14767, -1, 14788, 14473, 14480, -1, 14462, 14461, 14753, -1, 14481, 14787, 14480, -1, 14492, 14767, 14440, -1, 14479, 14547, 14508, -1, 14485, 14484, 14568, -1, 14485, 14568, 14787, -1, 14499, 14761, 14470, -1, 14485, 14787, 14481, -1, 14479, 14478, 14547, -1, 14499, 14496, 14761, -1, 14428, 14427, 14694, -1, 14514, 14444, 14443, -1, 14493, 14487, 13032, -1, 14428, 14694, 14491, -1, 14504, 14501, 14760, -1, 14514, 14443, 14524, -1, 14504, 14760, 14437, -1, 12865, 12862, 14789, -1, 14790, 12865, 14789, -1, 12866, 14791, 14792, -1, 12866, 14792, 12869, -1, 14793, 12876, 12875, -1, 14793, 12875, 14794, -1, 14795, 14789, 14796, -1, 14797, 14796, 14789, -1, 14797, 14789, 14792, -1, 14798, 14789, 14795, -1, 14799, 14797, 14792, -1, 14800, 14789, 14798, -1, 14801, 14799, 14792, -1, 14802, 14789, 14800, -1, 14803, 14801, 14792, -1, 14804, 14803, 14792, -1, 14805, 14806, 14807, -1, 14808, 14809, 14806, -1, 14808, 14806, 14805, -1, 14810, 14805, 14807, -1, 14810, 14811, 14812, -1, 14810, 14807, 14811, -1, 14813, 14802, 14809, -1, 14813, 14809, 14808, -1, 14814, 14810, 14812, -1, 14815, 14789, 14802, -1, 14815, 14802, 14813, -1, 14816, 14814, 14812, -1, 14816, 14812, 14817, -1, 14026, 14818, 14819, -1, 14026, 14820, 14818, -1, 14028, 14026, 14819, -1, 14028, 14819, 14821, -1, 14822, 14817, 13893, -1, 14822, 14816, 14817, -1, 14024, 14823, 14820, -1, 14024, 13879, 14823, -1, 14024, 14820, 14026, -1, 14030, 14804, 14792, -1, 14030, 14821, 14804, -1, 14030, 14028, 14821, -1, 14022, 13880, 13879, -1, 14022, 13883, 13880, -1, 14022, 13879, 14024, -1, 14824, 14822, 13893, -1, 14824, 13893, 13891, -1, 14032, 14030, 14792, -1, 14825, 14824, 13891, -1, 14825, 13891, 13889, -1, 14020, 13883, 14022, -1, 14020, 13885, 13883, -1, 14020, 13887, 13885, -1, 14034, 14032, 14792, -1, 14019, 14825, 13889, -1, 14019, 14826, 14825, -1, 14019, 13889, 13887, -1, 14019, 13887, 14020, -1, 13934, 14034, 14792, -1, 14018, 14826, 14019, -1, 14018, 14827, 14826, -1, 14017, 14827, 14018, -1, 14017, 14828, 14827, -1, 14017, 14829, 14828, -1, 14016, 13864, 13863, -1, 14016, 13863, 14829, -1, 14016, 14829, 14017, -1, 14790, 14830, 14831, -1, 14790, 14832, 14830, -1, 14790, 14833, 14832, -1, 14790, 14834, 14833, -1, 14790, 14835, 14834, -1, 14790, 14836, 14835, -1, 14015, 13867, 13864, -1, 14015, 13869, 13867, -1, 14015, 13864, 14016, -1, 14794, 14831, 13877, -1, 14794, 13875, 13873, -1, 14794, 13877, 13875, -1, 14794, 14790, 14831, -1, 14014, 13871, 13869, -1, 14014, 13869, 14015, -1, 14791, 13937, 13935, -1, 14791, 13935, 13934, -1, 14791, 13934, 14792, -1, 14791, 13943, 13941, -1, 14791, 13941, 13939, -1, 14791, 13939, 13937, -1, 13944, 13943, 14791, -1, 14013, 13873, 13871, -1, 14013, 14794, 13873, -1, 14013, 13871, 14014, -1, 14012, 14794, 14013, -1, 14837, 13944, 14791, -1, 14837, 13946, 13944, -1, 14011, 14794, 14012, -1, 13948, 13946, 14837, -1, 13950, 13948, 14837, -1, 13951, 13950, 14837, -1, 14793, 14794, 14011, -1, 14793, 14011, 13959, -1, 14793, 13959, 13958, -1, 14793, 13958, 13957, -1, 14793, 13957, 13956, -1, 14838, 14793, 13956, -1, 14838, 13956, 13955, -1, 14838, 13955, 13954, -1, 14838, 13954, 13953, -1, 14838, 13951, 14837, -1, 14838, 13953, 13952, -1, 14838, 13952, 13951, -1, 14790, 14789, 14815, -1, 14790, 14815, 14836, -1, 14839, 13884, 13886, -1, 14840, 14841, 12862, -1, 14840, 14842, 14841, -1, 14843, 14844, 13892, -1, 14843, 13892, 13894, -1, 14845, 13884, 14839, -1, 14846, 12866, 14847, -1, 14845, 13882, 13884, -1, 14845, 12873, 13882, -1, 14848, 12866, 14846, -1, 14849, 14850, 12862, -1, 14851, 14847, 12866, -1, 14852, 12866, 14848, -1, 13865, 12873, 14845, -1, 13865, 12871, 12873, -1, 14853, 14851, 12866, -1, 12875, 13874, 13876, -1, 12875, 13876, 13878, -1, 12875, 13878, 14854, -1, 12875, 12876, 13874, -1, 13881, 12866, 14852, -1, 14855, 13894, 14856, -1, 14855, 14843, 13894, -1, 12865, 14854, 14857, -1, 12865, 14857, 14858, -1, 12865, 14858, 14859, -1, 12865, 14859, 14860, -1, 14841, 14849, 12862, -1, 12865, 14860, 14861, -1, 12865, 14861, 14862, -1, 12865, 12875, 14854, -1, 13882, 12873, 12866, -1, 13882, 12866, 13881, -1, 12862, 12865, 14862, -1, 12862, 14862, 14840, -1, 13866, 12871, 13865, -1, 13866, 12876, 12871, -1, 12869, 14863, 14853, -1, 12869, 14853, 12866, -1, 13868, 12876, 13866, -1, 14864, 14863, 12869, -1, 13870, 12876, 13868, -1, 14865, 14864, 12869, -1, 13872, 12876, 13870, -1, 14866, 14856, 14867, -1, 14866, 14855, 14856, -1, 13874, 12876, 13872, -1, 14868, 14865, 12869, -1, 14869, 14866, 14867, -1, 12862, 14868, 12869, -1, 14870, 14868, 12862, -1, 14871, 14870, 12862, -1, 14872, 14867, 14873, -1, 14872, 14873, 14874, -1, 14872, 14869, 14867, -1, 14850, 14871, 12862, -1, 14875, 14874, 14876, -1, 14877, 13888, 13890, -1, 14875, 14872, 14874, -1, 14878, 14876, 14879, -1, 14880, 13888, 14877, -1, 14880, 13886, 13888, -1, 14878, 14875, 14876, -1, 14844, 14877, 13890, -1, 14842, 14879, 14841, -1, 14842, 14878, 14879, -1, 14844, 13890, 13892, -1, 14839, 13886, 14880, -1, 12642, 14881, 14882, -1, 12642, 14882, 12643, -1, 12640, 14883, 14884, -1, 12640, 14884, 12638, -1, 14885, 12652, 12653, -1, 14885, 12653, 14886, -1, 14887, 14888, 14884, -1, 14884, 14889, 14887, -1, 14888, 14890, 14884, -1, 14884, 14890, 14881, -1, 14884, 14891, 14889, -1, 14890, 14892, 14881, -1, 14884, 13895, 14891, -1, 14892, 14893, 14881, -1, 14884, 13896, 13895, -1, 14893, 14894, 14881, -1, 14894, 14895, 14881, -1, 13901, 14896, 13903, -1, 14897, 14896, 13901, -1, 13896, 14898, 13899, -1, 13899, 14898, 13901, -1, 13901, 14898, 14897, -1, 13903, 14899, 13905, -1, 14896, 14899, 13903, -1, 14884, 14900, 13896, -1, 13896, 14900, 14898, -1, 13905, 14901, 13907, -1, 14899, 14901, 13905, -1, 14884, 13911, 14900, -1, 13907, 14902, 13909, -1, 14901, 14902, 13907, -1, 14903, 13976, 14904, -1, 14904, 13976, 14905, -1, 13976, 13978, 14905, -1, 14905, 13978, 14906, -1, 13909, 14907, 14908, -1, 14908, 14907, 14909, -1, 14902, 14907, 13909, -1, 14903, 13974, 13976, -1, 14910, 13974, 14903, -1, 14906, 13980, 14895, -1, 14895, 13980, 14881, -1, 13978, 13980, 14906, -1, 14911, 13972, 14912, -1, 14912, 13972, 14910, -1, 14910, 13972, 13974, -1, 14907, 14913, 14909, -1, 13980, 13982, 14881, -1, 14909, 14914, 14915, -1, 14913, 14914, 14909, -1, 14916, 13970, 14917, -1, 14917, 13970, 14911, -1, 14911, 13970, 13972, -1, 13982, 13984, 14881, -1, 14916, 13969, 13970, -1, 14914, 13969, 14915, -1, 14915, 13969, 14916, -1, 13984, 13986, 14881, -1, 14914, 13968, 13969, -1, 14918, 13968, 14919, -1, 14919, 13968, 14914, -1, 14918, 13967, 13968, -1, 14920, 13967, 14921, -1, 14921, 13967, 14918, -1, 14922, 13966, 14923, -1, 14923, 13966, 14920, -1, 14920, 13966, 13967, -1, 13911, 14883, 13912, -1, 13912, 14883, 13915, -1, 13915, 14883, 13917, -1, 13917, 14883, 13919, -1, 13919, 14883, 13921, -1, 13921, 14883, 13923, -1, 13923, 14883, 13925, -1, 14924, 13965, 14922, -1, 14922, 13965, 13966, -1, 13925, 14885, 14925, -1, 14925, 14885, 14926, -1, 14883, 14885, 13925, -1, 14927, 13964, 14924, -1, 14924, 13964, 13965, -1, 13986, 14882, 14881, -1, 13995, 14882, 13993, -1, 13993, 14882, 13991, -1, 13991, 14882, 13989, -1, 13989, 14882, 13987, -1, 13987, 14882, 13986, -1, 13995, 13996, 14882, -1, 14885, 13963, 14926, -1, 14926, 13963, 14928, -1, 14928, 13963, 14927, -1, 14927, 13963, 13964, -1, 14885, 13962, 13963, -1, 13996, 14929, 14882, -1, 13998, 14929, 13996, -1, 14885, 13960, 13962, -1, 13998, 14000, 14929, -1, 14000, 14002, 14929, -1, 14002, 14003, 14929, -1, 14003, 14930, 14929, -1, 14008, 14930, 14007, -1, 14007, 14930, 14006, -1, 14006, 14930, 14005, -1, 14005, 14930, 14004, -1, 14004, 14930, 14003, -1, 13961, 14886, 14010, -1, 14010, 14886, 14009, -1, 14009, 14886, 14008, -1, 14885, 14886, 13960, -1, 14008, 14886, 14930, -1, 13960, 14886, 13961, -1, 14884, 14883, 13911, -1, 12640, 13913, 13914, -1, 12640, 13914, 13916, -1, 12640, 13916, 13918, -1, 12640, 13918, 13920, -1, 14931, 13908, 13910, -1, 12640, 13920, 13922, -1, 12640, 13922, 13924, -1, 14931, 14932, 13908, -1, 12640, 13924, 13926, -1, 14933, 14934, 12638, -1, 12652, 12640, 13926, -1, 14935, 12638, 14934, -1, 12652, 13926, 14936, -1, 12652, 14936, 14937, -1, 12652, 14937, 14938, -1, 14939, 12638, 12642, -1, 12643, 14940, 12642, -1, 12643, 14941, 14942, -1, 12643, 14942, 14943, -1, 14939, 14933, 12638, -1, 12643, 14943, 14944, -1, 12643, 14944, 14945, -1, 12643, 14945, 14946, -1, 12643, 14946, 14947, -1, 12643, 14947, 14940, -1, 14948, 12638, 14935, -1, 14949, 14939, 12642, -1, 12647, 14950, 14941, -1, 12647, 14951, 14950, -1, 13897, 12638, 14948, -1, 12647, 14941, 12643, -1, 12648, 14951, 12647, -1, 14952, 14949, 12642, -1, 12648, 14953, 14954, -1, 12648, 14954, 14951, -1, 12653, 14938, 14955, -1, 13898, 12638, 13897, -1, 12653, 14955, 14956, -1, 12653, 14956, 14953, -1, 12653, 12652, 14938, -1, 12653, 14953, 12648, -1, 12640, 12638, 13913, -1, 14957, 13910, 14958, -1, 14957, 14958, 14959, -1, 14960, 14952, 12642, -1, 14957, 14931, 13910, -1, 14940, 14960, 12642, -1, 14961, 14957, 14959, -1, 14962, 14959, 14963, -1, 14962, 14963, 14964, -1, 14962, 14961, 14959, -1, 14965, 14962, 14964, -1, 14966, 14964, 14967, -1, 14966, 14965, 14964, -1, 14968, 14969, 13902, -1, 14950, 14967, 14941, -1, 14968, 13902, 13904, -1, 14950, 14966, 14967, -1, 14970, 13902, 14969, -1, 14970, 13898, 13900, -1, 14970, 13900, 13902, -1, 14971, 13904, 13906, -1, 14971, 14968, 13904, -1, 14972, 13898, 14970, -1, 14972, 12638, 13898, -1, 14932, 13906, 13908, -1, 14932, 14971, 13906, -1, 13913, 12638, 14972, -1, 14929, 14930, 12647, -1, 14930, 12648, 12647, -1, 12873, 12871, 14837, -1, 12871, 14838, 14837, -1, 14902, 14901, 14931, -1, 14931, 14901, 14932, -1, 14932, 14899, 14971, -1, 14901, 14899, 14932, -1, 14971, 14896, 14968, -1, 14899, 14896, 14971, -1, 14968, 14897, 14969, -1, 14896, 14897, 14968, -1, 14969, 14898, 14970, -1, 14897, 14898, 14969, -1, 14970, 14900, 14972, -1, 14898, 14900, 14970, -1, 14972, 13911, 13913, -1, 14900, 13911, 14972, -1, 14902, 14931, 14907, -1, 14907, 14931, 14957, -1, 14925, 14926, 14936, -1, 14936, 14926, 14937, -1, 14937, 14928, 14938, -1, 14926, 14928, 14937, -1, 14938, 14927, 14955, -1, 14928, 14927, 14938, -1, 14955, 14924, 14956, -1, 14927, 14924, 14955, -1, 14956, 14922, 14953, -1, 14924, 14922, 14956, -1, 14953, 14923, 14954, -1, 14922, 14923, 14953, -1, 14954, 14920, 14951, -1, 14923, 14920, 14954, -1, 14951, 14921, 14950, -1, 14920, 14921, 14951, -1, 14950, 14918, 14966, -1, 14921, 14918, 14950, -1, 14966, 14919, 14965, -1, 14918, 14919, 14966, -1, 14965, 14914, 14962, -1, 14919, 14914, 14965, -1, 14962, 14913, 14961, -1, 14914, 14913, 14962, -1, 14961, 14907, 14957, -1, 14913, 14907, 14961, -1, 14936, 13925, 14925, -1, 13926, 13925, 14936, -1, 14893, 14892, 14952, -1, 14952, 14892, 14949, -1, 14949, 14890, 14939, -1, 14892, 14890, 14949, -1, 14939, 14888, 14933, -1, 14890, 14888, 14939, -1, 14933, 14887, 14934, -1, 14888, 14887, 14933, -1, 14934, 14889, 14935, -1, 14887, 14889, 14934, -1, 14935, 14891, 14948, -1, 14889, 14891, 14935, -1, 14948, 13895, 13897, -1, 14891, 13895, 14948, -1, 14893, 14952, 14894, -1, 14894, 14952, 14960, -1, 14908, 14909, 14958, -1, 14958, 14909, 14959, -1, 14959, 14915, 14963, -1, 14909, 14915, 14959, -1, 14963, 14916, 14964, -1, 14915, 14916, 14963, -1, 14964, 14917, 14967, -1, 14916, 14917, 14964, -1, 14967, 14911, 14941, -1, 14917, 14911, 14967, -1, 14941, 14912, 14942, -1, 14911, 14912, 14941, -1, 14942, 14910, 14943, -1, 14912, 14910, 14942, -1, 14943, 14903, 14944, -1, 14910, 14903, 14943, -1, 14944, 14904, 14945, -1, 14903, 14904, 14944, -1, 14945, 14905, 14946, -1, 14904, 14905, 14945, -1, 14946, 14906, 14947, -1, 14905, 14906, 14946, -1, 14947, 14895, 14940, -1, 14906, 14895, 14947, -1, 14940, 14894, 14960, -1, 14895, 14894, 14940, -1, 14958, 13909, 14908, -1, 13910, 13909, 14958, -1, 14817, 14812, 14856, -1, 14856, 14812, 14867, -1, 14867, 14811, 14873, -1, 14812, 14811, 14867, -1, 14873, 14807, 14874, -1, 14811, 14807, 14873, -1, 14874, 14806, 14876, -1, 14807, 14806, 14874, -1, 14876, 14809, 14879, -1, 14806, 14809, 14876, -1, 14879, 14802, 14841, -1, 14809, 14802, 14879, -1, 14841, 14800, 14849, -1, 14802, 14800, 14841, -1, 14849, 14798, 14850, -1, 14800, 14798, 14849, -1, 14850, 14795, 14871, -1, 14798, 14795, 14850, -1, 14871, 14796, 14870, -1, 14795, 14796, 14871, -1, 14870, 14797, 14868, -1, 14796, 14797, 14870, -1, 14868, 14799, 14865, -1, 14797, 14799, 14868, -1, 14865, 14801, 14864, -1, 14799, 14801, 14865, -1, 14856, 13893, 14817, -1, 13894, 13893, 14856, -1, 14803, 14804, 14863, -1, 14863, 14804, 14853, -1, 14853, 14821, 14851, -1, 14804, 14821, 14853, -1, 14851, 14819, 14847, -1, 14821, 14819, 14851, -1, 14847, 14818, 14846, -1, 14819, 14818, 14847, -1, 14846, 14820, 14848, -1, 14818, 14820, 14846, -1, 14848, 14823, 14852, -1, 14820, 14823, 14848, -1, 14852, 13879, 13881, -1, 14823, 13879, 14852, -1, 14803, 14863, 14801, -1, 14801, 14863, 14864, -1, 14831, 14830, 14854, -1, 14854, 14830, 14857, -1, 14857, 14832, 14858, -1, 14830, 14832, 14857, -1, 14858, 14833, 14859, -1, 14832, 14833, 14858, -1, 14859, 14834, 14860, -1, 14833, 14834, 14859, -1, 14860, 14835, 14861, -1, 14834, 14835, 14860, -1, 14861, 14836, 14862, -1, 14835, 14836, 14861, -1, 14862, 14815, 14840, -1, 14836, 14815, 14862, -1, 14840, 14813, 14842, -1, 14815, 14813, 14840, -1, 14842, 14808, 14878, -1, 14813, 14808, 14842, -1, 14878, 14805, 14875, -1, 14808, 14805, 14878, -1, 14875, 14810, 14872, -1, 14805, 14810, 14875, -1, 14872, 14814, 14869, -1, 14810, 14814, 14872, -1, 14869, 14816, 14866, -1, 14814, 14816, 14869, -1, 14854, 13877, 14831, -1, 13878, 13877, 14854, -1, 14822, 14824, 14855, -1, 14855, 14824, 14843, -1, 14843, 14825, 14844, -1, 14824, 14825, 14843, -1, 14844, 14826, 14877, -1, 14825, 14826, 14844, -1, 14877, 14827, 14880, -1, 14826, 14827, 14877, -1, 14880, 14828, 14839, -1, 14827, 14828, 14880, -1, 14839, 14829, 14845, -1, 14828, 14829, 14839, -1, 14845, 13863, 13865, -1, 14829, 13863, 14845, -1, 14822, 14855, 14816, -1, 14816, 14855, 14866, -1, 14929, 12647, 12643, -1, 14929, 12643, 14882, -1, 14881, 12642, 14884, -1, 14884, 12642, 12638, -1, 12652, 14885, 12640, -1, 12640, 14885, 14883, -1, 14886, 12653, 12648, -1, 14886, 12648, 14930, -1, 14789, 12862, 14792, -1, 14792, 12862, 12869, -1, 14838, 12871, 12876, -1, 14838, 12876, 14793, -1, 14791, 12866, 12873, -1, 14791, 12873, 14837, -1, 12865, 14790, 12875, -1, 12875, 14790, 14794, -1, 14973, 14974, 14975, -1, 14975, 14974, 14976, -1, 14976, 14977, 14978, -1, 14974, 14977, 14976, -1, 14978, 14979, 14980, -1, 14977, 14979, 14978, -1, 14980, 14981, 14982, -1, 14979, 14981, 14980, -1, 14982, 14983, 14984, -1, 14981, 14983, 14982, -1, 14984, 14985, 14986, -1, 14983, 14985, 14984, -1, 14986, 14987, 14988, -1, 14985, 14987, 14986, -1, 14988, 14989, 14990, -1, 14987, 14989, 14988, -1, 14990, 14991, 14992, -1, 14989, 14991, 14990, -1, 14992, 14993, 14994, -1, 14991, 14993, 14992, -1, 14994, 14995, 14996, -1, 14993, 14995, 14994, -1, 14996, 14997, 14998, -1, 14995, 14997, 14996, -1, 14998, 14999, 15000, -1, 14997, 14999, 14998, -1, 15001, 15002, 15003, -1, 15003, 15002, 15004, -1, 15004, 15005, 15006, -1, 15002, 15005, 15004, -1, 15006, 15007, 15008, -1, 15005, 15007, 15006, -1, 15008, 15009, 15010, -1, 15007, 15009, 15008, -1, 15010, 15011, 15012, -1, 15009, 15011, 15010, -1, 15012, 15013, 15014, -1, 15011, 15013, 15012, -1, 15014, 15015, 15016, -1, 15013, 15015, 15014, -1, 15016, 15017, 15018, -1, 15015, 15017, 15016, -1, 15018, 15019, 15020, -1, 15017, 15019, 15018, -1, 15020, 15021, 15022, -1, 15019, 15021, 15020, -1, 15022, 15023, 15024, -1, 15021, 15023, 15022, -1, 15024, 15025, 15026, -1, 15023, 15025, 15024, -1, 15026, 15027, 15028, -1, 15025, 15027, 15026, -1, 15029, 15030, 15031, -1, 15029, 15032, 15030, -1, 15032, 15033, 15030, -1, 15032, 15034, 15033, -1, 15034, 15035, 15033, -1, 15034, 15036, 15035, -1, 15036, 15037, 15035, -1, 15036, 15038, 15037, -1, 15038, 15039, 15037, -1, 15038, 15040, 15039, -1, 15040, 15041, 15039, -1, 15040, 15042, 15041, -1, 15042, 15043, 15041, -1, 15042, 15044, 15043, -1, 15044, 15045, 15043, -1, 15044, 15046, 15045, -1, 15046, 15047, 15045, -1, 15046, 15048, 15047, -1, 15047, 15049, 15050, -1, 15048, 15049, 15047, -1, 15049, 15051, 15050, -1, 15049, 15052, 15051, -1, 15052, 15053, 15051, -1, 15052, 15054, 15053, -1, 15053, 15055, 15056, -1, 15054, 15055, 15053, -1, 15057, 15058, 15059, -1, 15057, 15060, 15058, -1, 15060, 15061, 15058, -1, 15060, 15062, 15061, -1, 15062, 15063, 15061, -1, 15062, 15064, 15063, -1, 15064, 15065, 15063, -1, 15064, 15066, 15065, -1, 15066, 15067, 15065, -1, 15066, 15068, 15067, -1, 15068, 15069, 15067, -1, 15068, 15070, 15069, -1, 15070, 15071, 15069, -1, 15070, 15072, 15071, -1, 15072, 15073, 15071, -1, 15072, 15074, 15073, -1, 15074, 15075, 15073, -1, 15074, 15076, 15075, -1, 15076, 15077, 15075, -1, 15076, 15078, 15077, -1, 15078, 15079, 15077, -1, 15078, 15080, 15079, -1, 15080, 15081, 15079, -1, 15080, 15082, 15081, -1, 15081, 15083, 15084, -1, 15082, 15083, 15081, -1, 15059, 15058, 15085, -1, 15085, 15058, 15086, -1, 15086, 15061, 15087, -1, 15058, 15061, 15086, -1, 15087, 15063, 15088, -1, 15061, 15063, 15087, -1, 15088, 15065, 15089, -1, 15063, 15065, 15088, -1, 15089, 15067, 15090, -1, 15065, 15067, 15089, -1, 15090, 15069, 15091, -1, 15067, 15069, 15090, -1, 15091, 15071, 15092, -1, 15069, 15071, 15091, -1, 15092, 15073, 15093, -1, 15071, 15073, 15092, -1, 15093, 15075, 15094, -1, 15073, 15075, 15093, -1, 15094, 15077, 15095, -1, 15075, 15077, 15094, -1, 15095, 15079, 15096, -1, 15077, 15079, 15095, -1, 15096, 15081, 15097, -1, 15079, 15081, 15096, -1, 15097, 15084, 15098, -1, 15081, 15084, 15097, -1, 15031, 15030, 15099, -1, 15099, 15030, 15100, -1, 15100, 15030, 15101, -1, 15101, 15033, 15102, -1, 15030, 15033, 15101, -1, 15102, 15035, 15103, -1, 15033, 15035, 15102, -1, 15103, 15037, 15104, -1, 15035, 15037, 15103, -1, 15104, 15039, 15105, -1, 15037, 15039, 15104, -1, 15105, 15041, 15106, -1, 15039, 15041, 15105, -1, 15106, 15043, 15107, -1, 15041, 15043, 15106, -1, 15107, 15045, 15108, -1, 15043, 15045, 15107, -1, 15108, 15047, 15109, -1, 15045, 15047, 15108, -1, 15109, 15050, 15110, -1, 15047, 15050, 15109, -1, 15110, 15051, 15111, -1, 15050, 15051, 15110, -1, 15111, 15053, 15112, -1, 15051, 15053, 15111, -1, 15053, 15056, 15112, -1, 15113, 15114, 15115, -1, 15115, 15114, 15116, -1, 15116, 15117, 15118, -1, 15114, 15117, 15116, -1, 15118, 15119, 15120, -1, 15117, 15119, 15118, -1, 15120, 15121, 15122, -1, 15119, 15121, 15120, -1, 15122, 15123, 15124, -1, 15121, 15123, 15122, -1, 15124, 15125, 15126, -1, 15123, 15125, 15124, -1, 15126, 15127, 15128, -1, 15125, 15127, 15126, -1, 15128, 15129, 15130, -1, 15127, 15129, 15128, -1, 15130, 15131, 15132, -1, 15129, 15131, 15130, -1, 15132, 15133, 15134, -1, 15131, 15133, 15132, -1, 15134, 15135, 15136, -1, 15133, 15135, 15134, -1, 15136, 15137, 15138, -1, 15135, 15137, 15136, -1, 15138, 15139, 15140, -1, 15137, 15139, 15138, -1, 15141, 15142, 15143, -1, 15143, 15142, 15144, -1, 15144, 15145, 15146, -1, 15142, 15145, 15144, -1, 15146, 15147, 15148, -1, 15145, 15147, 15146, -1, 15148, 15149, 15150, -1, 15147, 15149, 15148, -1, 15150, 15151, 15152, -1, 15149, 15151, 15150, -1, 15152, 15153, 15154, -1, 15151, 15153, 15152, -1, 15154, 15155, 15156, -1, 15153, 15155, 15154, -1, 15156, 15157, 15158, -1, 15155, 15157, 15156, -1, 15158, 15159, 15160, -1, 15157, 15159, 15158, -1, 15160, 15161, 15162, -1, 15159, 15161, 15160, -1, 15162, 15163, 15164, -1, 15161, 15163, 15162, -1, 15164, 15165, 15166, -1, 15163, 15165, 15164, -1, 15166, 15167, 15168, -1, 15165, 15167, 15166, -1, 15169, 15170, 15171, -1, 15171, 15170, 15172, -1, 15172, 15173, 15174, -1, 15170, 15173, 15172, -1, 15174, 15175, 15176, -1, 15173, 15175, 15174, -1, 15176, 15177, 15178, -1, 15175, 15177, 15176, -1, 15178, 15179, 15180, -1, 15177, 15179, 15178, -1, 15180, 15181, 15182, -1, 15179, 15181, 15180, -1, 15182, 15183, 15184, -1, 15181, 15183, 15182, -1, 15184, 15185, 15186, -1, 15183, 15185, 15184, -1, 15186, 15187, 15188, -1, 15185, 15187, 15186, -1, 15188, 15189, 15190, -1, 15187, 15189, 15188, -1, 15190, 15191, 15192, -1, 15189, 15191, 15190, -1, 15192, 15193, 15194, -1, 15191, 15193, 15192, -1, 15194, 15195, 15196, -1, 15193, 15195, 15194, -1, 15195, 15197, 15196, -1, 15196, 15197, 15198, -1, 15198, 15197, 15199, -1, 15199, 15200, 15201, -1, 15197, 15200, 15199, -1, 15201, 15202, 15203, -1, 15200, 15202, 15201, -1, 15203, 15204, 15205, -1, 15202, 15204, 15203, -1, 15205, 15206, 15207, -1, 15204, 15206, 15205, -1, 15207, 15208, 15209, -1, 15206, 15208, 15207, -1, 15209, 15210, 15211, -1, 15208, 15210, 15209, -1, 15211, 15212, 15213, -1, 15210, 15212, 15211, -1, 15213, 15214, 15215, -1, 15212, 15214, 15213, -1, 15215, 15216, 15217, -1, 15214, 15216, 15215, -1, 15217, 15218, 15219, -1, 15216, 15218, 15217, -1, 15219, 15220, 15171, -1, 15218, 15220, 15219, -1, 15220, 15169, 15171, -1, 15221, 15009, 15007, -1, 15007, 15005, 15221, -1, 15221, 15011, 15009, -1, 15005, 15002, 15221, -1, 15221, 15013, 15011, -1, 15222, 15015, 15221, -1, 15221, 15015, 15013, -1, 15222, 15017, 15015, -1, 15222, 15019, 15017, -1, 15222, 15021, 15019, -1, 15222, 15023, 15021, -1, 15222, 15025, 15023, -1, 15223, 15064, 15001, -1, 15224, 15066, 15225, -1, 15225, 15066, 15223, -1, 15223, 15066, 15064, -1, 15001, 15062, 15002, -1, 15002, 15062, 15221, -1, 15064, 15062, 15001, -1, 15226, 15068, 15227, -1, 15227, 15068, 15224, -1, 15224, 15068, 15066, -1, 15062, 15060, 15221, -1, 15228, 15070, 15229, -1, 15229, 15070, 15226, -1, 15226, 15070, 15068, -1, 15060, 15057, 15221, -1, 15230, 15072, 15228, -1, 15228, 15072, 15070, -1, 15230, 15074, 15072, -1, 15231, 15074, 15232, -1, 15232, 15074, 15230, -1, 15233, 15076, 15234, -1, 15234, 15076, 15231, -1, 15231, 15076, 15074, -1, 15027, 15078, 15233, -1, 15233, 15078, 15076, -1, 15025, 15080, 15027, -1, 15222, 15080, 15025, -1, 15027, 15080, 15078, -1, 15222, 15082, 15080, -1, 15235, 15120, 15236, -1, 15120, 15122, 15236, -1, 15235, 15118, 15120, -1, 15237, 15118, 15235, -1, 15122, 15124, 15236, -1, 15236, 15124, 15238, -1, 15237, 15116, 15118, -1, 15124, 15126, 15238, -1, 15238, 15126, 15239, -1, 15237, 15115, 15116, -1, 15240, 15115, 15237, -1, 15240, 15241, 15115, -1, 15240, 15242, 15241, -1, 15243, 15242, 15240, -1, 15243, 15244, 15242, -1, 15245, 15244, 15243, -1, 15245, 15246, 15244, -1, 15245, 15247, 15246, -1, 15248, 15247, 15245, -1, 15249, 15250, 15248, -1, 15248, 15250, 15247, -1, 15130, 15036, 15128, -1, 15132, 15038, 15130, -1, 15134, 15038, 15132, -1, 15130, 15038, 15036, -1, 15128, 15034, 15126, -1, 15126, 15034, 15239, -1, 15036, 15034, 15128, -1, 15136, 15040, 15134, -1, 15134, 15040, 15038, -1, 15034, 15032, 15239, -1, 15239, 15032, 15251, -1, 15136, 15042, 15040, -1, 15138, 15042, 15136, -1, 15140, 15042, 15138, -1, 15032, 15029, 15251, -1, 15251, 15029, 15057, -1, 15252, 15044, 15140, -1, 15253, 15044, 15252, -1, 15140, 15044, 15042, -1, 15254, 15046, 15253, -1, 15253, 15046, 15044, -1, 15255, 15048, 15254, -1, 15256, 15048, 15255, -1, 15254, 15048, 15046, -1, 15257, 15049, 15256, -1, 15256, 15049, 15048, -1, 15250, 15052, 15257, -1, 15257, 15052, 15049, -1, 15249, 15052, 15250, -1, 15258, 15052, 15249, -1, 15258, 15054, 15052, -1, 15259, 14979, 15260, -1, 15259, 14981, 14979, -1, 14979, 14977, 15260, -1, 15259, 14983, 14981, -1, 15261, 14983, 15259, -1, 14977, 14974, 15260, -1, 15260, 14974, 15262, -1, 15261, 14985, 14983, -1, 15263, 14985, 15261, -1, 14974, 14973, 15262, -1, 15262, 14973, 15264, -1, 15263, 14987, 14985, -1, 14973, 15265, 15264, -1, 15263, 14989, 14987, -1, 15266, 14989, 15263, -1, 15266, 14991, 14989, -1, 15266, 14993, 14991, -1, 15267, 14993, 15266, -1, 15267, 14995, 14993, -1, 15268, 14997, 15267, -1, 15267, 14997, 14995, -1, 15269, 14999, 15268, -1, 15268, 14999, 14997, -1, 15269, 15270, 14999, -1, 15271, 15272, 15273, -1, 15273, 15272, 15274, -1, 15274, 15272, 15275, -1, 15275, 15272, 15276, -1, 15276, 15272, 15265, -1, 15057, 15272, 15221, -1, 15265, 15272, 15264, -1, 15277, 15272, 15029, -1, 15264, 15272, 15277, -1, 15029, 15272, 15057, -1, 15278, 15279, 15269, -1, 15270, 15279, 15280, -1, 15280, 15279, 15281, -1, 15281, 15279, 15282, -1, 15282, 15279, 15283, -1, 15283, 15279, 15284, -1, 15284, 15279, 15271, -1, 15271, 15279, 15272, -1, 15269, 15279, 15270, -1, 15222, 15279, 15083, -1, 15222, 15083, 15082, -1, 15083, 15279, 15258, -1, 15258, 15279, 15055, -1, 15258, 15055, 15054, -1, 15055, 15279, 15278, -1, 15285, 15286, 15287, -1, 15287, 15286, 15288, -1, 15289, 15290, 15291, -1, 15292, 15290, 15289, -1, 15293, 15294, 15295, -1, 15296, 15294, 15293, -1, 15297, 15296, 15293, -1, 15298, 15296, 15297, -1, 15299, 15298, 15297, -1, 15300, 15298, 15299, -1, 15301, 15302, 15303, -1, 15303, 15304, 15301, -1, 15301, 15305, 15302, -1, 15304, 15306, 15301, -1, 15301, 15307, 15305, -1, 15306, 14975, 15301, -1, 15301, 15308, 15307, -1, 14975, 14976, 15301, -1, 15309, 15310, 15000, -1, 15311, 15310, 15309, -1, 15312, 15310, 15311, -1, 15313, 15310, 15312, -1, 15314, 15310, 15313, -1, 15308, 15310, 15314, -1, 15000, 15310, 14998, -1, 15301, 15310, 15308, -1, 14982, 15189, 14980, -1, 14980, 15187, 14978, -1, 15189, 15187, 14980, -1, 14984, 15191, 14982, -1, 14982, 15191, 15189, -1, 14978, 15185, 14976, -1, 14976, 15185, 15301, -1, 15187, 15185, 14978, -1, 14986, 15193, 14984, -1, 14984, 15193, 15191, -1, 15185, 15183, 15301, -1, 14988, 15195, 14986, -1, 14986, 15195, 15193, -1, 15183, 15181, 15301, -1, 14990, 15197, 14988, -1, 14988, 15197, 15195, -1, 14990, 15200, 15197, -1, 14992, 15200, 14990, -1, 14992, 15202, 15200, -1, 14994, 15202, 14992, -1, 14996, 15204, 14994, -1, 14994, 15204, 15202, -1, 14996, 15206, 15204, -1, 14998, 15206, 14996, -1, 15310, 15206, 14998, -1, 15310, 15208, 15206, -1, 15310, 15210, 15208, -1, 15173, 15133, 15175, -1, 15133, 15131, 15175, -1, 15175, 15131, 15177, -1, 15173, 15135, 15133, -1, 15170, 15135, 15173, -1, 15177, 15129, 15179, -1, 15131, 15129, 15177, -1, 15170, 15137, 15135, -1, 15169, 15137, 15170, -1, 15129, 15127, 15179, -1, 15179, 15127, 15181, -1, 15181, 15127, 15301, -1, 15169, 15139, 15137, -1, 15169, 15315, 15139, -1, 15220, 15315, 15169, -1, 15220, 15316, 15315, -1, 15218, 15316, 15220, -1, 15216, 15317, 15218, -1, 15218, 15317, 15316, -1, 15214, 15318, 15216, -1, 15216, 15318, 15317, -1, 15212, 15319, 15214, -1, 15214, 15319, 15318, -1, 15310, 15320, 15210, -1, 15212, 15320, 15319, -1, 15210, 15320, 15212, -1, 15119, 15161, 15121, -1, 15121, 15159, 15123, -1, 15161, 15159, 15121, -1, 15117, 15163, 15119, -1, 15119, 15163, 15161, -1, 15159, 15157, 15123, -1, 15123, 15157, 15125, -1, 15117, 15165, 15163, -1, 15114, 15165, 15117, -1, 15157, 15155, 15125, -1, 15114, 15167, 15165, -1, 15321, 15167, 15113, -1, 15113, 15167, 15114, -1, 15321, 15322, 15167, -1, 15323, 15322, 15321, -1, 15323, 15324, 15322, -1, 15325, 15324, 15323, -1, 15325, 15326, 15324, -1, 15327, 15326, 15325, -1, 15327, 15328, 15326, -1, 15329, 15328, 15327, -1, 15329, 15330, 15328, -1, 15331, 15330, 15329, -1, 15331, 15332, 15330, -1, 15151, 15333, 15153, -1, 15153, 15333, 15155, -1, 15127, 15333, 15301, -1, 15155, 15333, 15125, -1, 15125, 15333, 15127, -1, 15147, 15334, 15149, -1, 15145, 15335, 15147, -1, 15147, 15335, 15334, -1, 15149, 15336, 15151, -1, 15334, 15336, 15149, -1, 15142, 15337, 15145, -1, 15145, 15337, 15335, -1, 15151, 15338, 15333, -1, 15336, 15338, 15151, -1, 15141, 15339, 15142, -1, 15142, 15339, 15337, -1, 15338, 15003, 15333, -1, 15141, 15340, 15339, -1, 15341, 15340, 15141, -1, 15003, 15004, 15333, -1, 15342, 15343, 15341, -1, 15341, 15343, 15340, -1, 15004, 15006, 15333, -1, 15344, 15345, 15342, -1, 15342, 15345, 15343, -1, 15006, 15008, 15333, -1, 15346, 15347, 15344, -1, 15344, 15347, 15345, -1, 15008, 15010, 15333, -1, 15348, 15349, 15346, -1, 15346, 15349, 15347, -1, 15010, 15012, 15333, -1, 15348, 15350, 15349, -1, 15012, 15014, 15333, -1, 15014, 15016, 15333, -1, 15332, 15351, 15352, -1, 15352, 15351, 15348, -1, 15350, 15351, 15028, -1, 15331, 15351, 15332, -1, 15018, 15351, 15016, -1, 15020, 15351, 15018, -1, 15022, 15351, 15020, -1, 15024, 15351, 15022, -1, 15026, 15351, 15024, -1, 15028, 15351, 15026, -1, 15016, 15351, 15333, -1, 15348, 15351, 15350, -1, 15310, 15351, 15320, -1, 15320, 15351, 15331, -1, 15353, 15354, 15355, -1, 15356, 15354, 15353, -1, 15357, 15356, 15353, -1, 15358, 15356, 15357, -1, 15359, 15358, 15357, -1, 15360, 15358, 15359, -1, 15361, 15362, 15363, -1, 15364, 15362, 15361, -1, 15365, 15366, 15367, -1, 15368, 15366, 15365, -1, 15290, 15296, 15369, -1, 15292, 15296, 15290, -1, 15294, 15296, 15292, -1, 15351, 15298, 15300, -1, 15296, 15298, 15369, -1, 15310, 15356, 15351, -1, 15354, 15356, 15310, -1, 15351, 15356, 15298, -1, 15362, 15358, 15360, -1, 15362, 15364, 15358, -1, 15358, 15370, 15356, -1, 15364, 15370, 15358, -1, 15370, 15369, 15356, -1, 15356, 15369, 15298, -1, 15293, 15289, 15291, -1, 15293, 15291, 15371, -1, 15293, 15295, 15289, -1, 15297, 15333, 15299, -1, 15297, 15293, 15371, -1, 15353, 15355, 15301, -1, 15353, 15301, 15333, -1, 15353, 15333, 15297, -1, 15357, 15363, 15359, -1, 15361, 15363, 15357, -1, 15372, 15357, 15353, -1, 15372, 15361, 15357, -1, 15371, 15372, 15353, -1, 15371, 15353, 15297, -1, 15292, 15289, 15294, -1, 15294, 15289, 15295, -1, 15300, 15299, 15351, -1, 15351, 15299, 15333, -1, 15360, 15359, 15362, -1, 15362, 15359, 15363, -1, 15310, 15301, 15354, -1, 15354, 15301, 15355, -1, 15367, 15372, 15365, -1, 15361, 15372, 15367, -1, 15366, 15361, 15367, -1, 15364, 15361, 15366, -1, 15272, 15365, 15372, -1, 15368, 15272, 15279, -1, 15368, 15365, 15272, -1, 15366, 15370, 15364, -1, 15366, 15368, 15370, -1, 15372, 15371, 15221, -1, 15372, 15221, 15272, -1, 15279, 15370, 15368, -1, 15221, 15371, 15288, -1, 15286, 15221, 15288, -1, 15222, 15221, 15286, -1, 15279, 15369, 15370, -1, 15279, 15222, 15369, -1, 15371, 15291, 15287, -1, 15371, 15287, 15288, -1, 15369, 15222, 15286, -1, 15285, 15291, 15290, -1, 15285, 15287, 15291, -1, 15286, 15285, 15369, -1, 15369, 15285, 15290, -1, 15167, 15322, 15168, -1, 15168, 15322, 15373, -1, 15373, 15324, 15374, -1, 15322, 15324, 15373, -1, 15374, 15326, 15375, -1, 15324, 15326, 15374, -1, 15375, 15328, 15376, -1, 15326, 15328, 15375, -1, 15376, 15330, 15377, -1, 15328, 15330, 15376, -1, 15377, 15332, 15378, -1, 15330, 15332, 15377, -1, 15378, 15352, 15379, -1, 15332, 15352, 15378, -1, 15379, 15348, 15380, -1, 15352, 15348, 15379, -1, 15380, 15346, 15381, -1, 15348, 15346, 15380, -1, 15381, 15344, 15382, -1, 15346, 15344, 15381, -1, 15382, 15342, 15383, -1, 15344, 15342, 15382, -1, 15383, 15341, 15384, -1, 15342, 15341, 15383, -1, 15384, 15141, 15143, -1, 15341, 15141, 15384, -1, 15139, 15315, 15140, -1, 15140, 15315, 15252, -1, 15252, 15316, 15253, -1, 15315, 15316, 15252, -1, 15253, 15317, 15254, -1, 15316, 15317, 15253, -1, 15254, 15318, 15255, -1, 15317, 15318, 15254, -1, 15255, 15319, 15256, -1, 15318, 15319, 15255, -1, 15256, 15320, 15257, -1, 15319, 15320, 15256, -1, 15257, 15331, 15250, -1, 15320, 15331, 15257, -1, 15250, 15329, 15247, -1, 15331, 15329, 15250, -1, 15247, 15327, 15246, -1, 15329, 15327, 15247, -1, 15246, 15325, 15244, -1, 15327, 15325, 15246, -1, 15244, 15323, 15242, -1, 15325, 15323, 15244, -1, 15242, 15321, 15241, -1, 15323, 15321, 15242, -1, 15241, 15113, 15115, -1, 15321, 15113, 15241, -1, 15110, 15211, 15213, -1, 15110, 15213, 15109, -1, 15385, 15386, 15192, -1, 15385, 15192, 15194, -1, 15176, 15102, 15103, -1, 15111, 15211, 15110, -1, 15111, 15209, 15211, -1, 15178, 15101, 15102, -1, 15178, 15102, 15176, -1, 15174, 15103, 15104, -1, 15174, 15176, 15103, -1, 15180, 15100, 15101, -1, 15387, 15385, 15194, -1, 15387, 15194, 15196, -1, 15180, 15101, 15178, -1, 15172, 15104, 15105, -1, 15112, 15207, 15209, -1, 15112, 15209, 15111, -1, 15172, 15174, 15104, -1, 15388, 15196, 15198, -1, 15182, 15099, 15100, -1, 15388, 15387, 15196, -1, 15182, 15100, 15180, -1, 15389, 15207, 15112, -1, 15389, 15205, 15207, -1, 15171, 15105, 15106, -1, 15390, 15198, 15199, -1, 15171, 15172, 15105, -1, 15390, 15388, 15198, -1, 15184, 15391, 15099, -1, 15392, 15203, 15205, -1, 15392, 15205, 15389, -1, 15184, 15099, 15182, -1, 15393, 15199, 15201, -1, 15393, 15390, 15199, -1, 15219, 15106, 15107, -1, 15394, 15201, 15203, -1, 15394, 15393, 15201, -1, 15219, 15171, 15106, -1, 15394, 15203, 15392, -1, 15186, 15395, 15391, -1, 15186, 15391, 15184, -1, 15217, 15107, 15108, -1, 15217, 15219, 15107, -1, 15188, 15395, 15186, -1, 15396, 15395, 15188, -1, 15215, 15217, 15108, -1, 15190, 15396, 15188, -1, 15109, 15215, 15108, -1, 15213, 15215, 15109, -1, 15386, 15190, 15192, -1, 15386, 15396, 15190, -1, 15056, 15397, 15112, -1, 15112, 15397, 15389, -1, 15389, 15398, 15392, -1, 15397, 15398, 15389, -1, 15392, 15399, 15394, -1, 15398, 15399, 15392, -1, 15394, 15400, 15393, -1, 15399, 15400, 15394, -1, 15393, 15401, 15390, -1, 15400, 15401, 15393, -1, 15390, 15402, 15388, -1, 15401, 15402, 15390, -1, 15388, 15403, 15387, -1, 15402, 15403, 15388, -1, 15387, 15404, 15385, -1, 15403, 15404, 15387, -1, 15385, 15405, 15386, -1, 15404, 15405, 15385, -1, 15386, 15406, 15396, -1, 15405, 15406, 15386, -1, 15396, 15407, 15395, -1, 15406, 15407, 15396, -1, 15395, 15408, 15391, -1, 15407, 15408, 15395, -1, 15391, 15031, 15099, -1, 15408, 15031, 15391, -1, 15152, 15087, 15150, -1, 15150, 15087, 15088, -1, 15409, 15410, 15374, -1, 15374, 15410, 15373, -1, 15095, 15382, 15094, -1, 15096, 15381, 15095, -1, 15095, 15381, 15382, -1, 15094, 15383, 15093, -1, 15382, 15383, 15094, -1, 15154, 15086, 15152, -1, 15152, 15086, 15087, -1, 15097, 15380, 15096, -1, 15096, 15380, 15381, -1, 15093, 15384, 15092, -1, 15383, 15384, 15093, -1, 15098, 15379, 15097, -1, 15097, 15379, 15380, -1, 15410, 15411, 15373, -1, 15373, 15411, 15168, -1, 15092, 15143, 15091, -1, 15156, 15085, 15154, -1, 15154, 15085, 15086, -1, 15384, 15143, 15092, -1, 15168, 15412, 15166, -1, 15413, 15378, 15098, -1, 15411, 15412, 15168, -1, 15098, 15378, 15379, -1, 15158, 15414, 15156, -1, 15091, 15144, 15090, -1, 15156, 15414, 15085, -1, 15166, 15415, 15164, -1, 15412, 15415, 15166, -1, 15143, 15144, 15091, -1, 15416, 15377, 15413, -1, 15160, 15417, 15158, -1, 15158, 15417, 15414, -1, 15413, 15377, 15378, -1, 15415, 15418, 15164, -1, 15164, 15418, 15162, -1, 15090, 15146, 15089, -1, 15418, 15419, 15162, -1, 15162, 15419, 15160, -1, 15160, 15419, 15417, -1, 15144, 15146, 15090, -1, 15416, 15376, 15377, -1, 15416, 15420, 15376, -1, 15146, 15148, 15089, -1, 15420, 15375, 15376, -1, 15148, 15088, 15089, -1, 15148, 15150, 15088, -1, 15420, 15409, 15375, -1, 15375, 15409, 15374, -1, 15084, 15421, 15098, -1, 15098, 15421, 15413, -1, 15413, 15422, 15416, -1, 15421, 15422, 15413, -1, 15416, 15423, 15420, -1, 15422, 15423, 15416, -1, 15420, 15424, 15409, -1, 15423, 15424, 15420, -1, 15409, 15425, 15410, -1, 15424, 15425, 15409, -1, 15410, 15426, 15411, -1, 15425, 15426, 15410, -1, 15411, 15427, 15412, -1, 15426, 15427, 15411, -1, 15412, 15428, 15415, -1, 15427, 15428, 15412, -1, 15415, 15429, 15418, -1, 15428, 15429, 15415, -1, 15418, 15430, 15419, -1, 15429, 15430, 15418, -1, 15419, 15431, 15417, -1, 15430, 15431, 15419, -1, 15417, 15432, 15414, -1, 15431, 15432, 15417, -1, 15414, 15059, 15085, -1, 15432, 15059, 15414, -1, 15083, 15421, 15084, -1, 15083, 15258, 15421, -1, 15258, 15422, 15421, -1, 15258, 15249, 15422, -1, 15249, 15423, 15422, -1, 15249, 15248, 15423, -1, 15248, 15424, 15423, -1, 15248, 15245, 15424, -1, 15245, 15425, 15424, -1, 15245, 15243, 15425, -1, 15243, 15426, 15425, -1, 15243, 15240, 15426, -1, 15240, 15427, 15426, -1, 15240, 15237, 15427, -1, 15237, 15428, 15427, -1, 15237, 15235, 15428, -1, 15235, 15429, 15428, -1, 15235, 15236, 15429, -1, 15236, 15430, 15429, -1, 15236, 15238, 15430, -1, 15238, 15431, 15430, -1, 15238, 15239, 15431, -1, 15239, 15432, 15431, -1, 15239, 15251, 15432, -1, 15251, 15059, 15432, -1, 15251, 15057, 15059, -1, 15055, 15397, 15056, -1, 15055, 15278, 15397, -1, 15278, 15398, 15397, -1, 15278, 15269, 15398, -1, 15269, 15399, 15398, -1, 15269, 15268, 15399, -1, 15268, 15400, 15399, -1, 15268, 15267, 15400, -1, 15267, 15401, 15400, -1, 15267, 15266, 15401, -1, 15266, 15402, 15401, -1, 15266, 15263, 15402, -1, 15263, 15403, 15402, -1, 15263, 15261, 15403, -1, 15261, 15404, 15403, -1, 15261, 15259, 15404, -1, 15259, 15405, 15404, -1, 15259, 15260, 15405, -1, 15260, 15406, 15405, -1, 15260, 15262, 15406, -1, 15262, 15407, 15406, -1, 15262, 15264, 15407, -1, 15264, 15408, 15407, -1, 15264, 15277, 15408, -1, 15277, 15031, 15408, -1, 15277, 15029, 15031, -1, 15027, 15233, 15028, -1, 15028, 15233, 15350, -1, 15350, 15234, 15349, -1, 15233, 15234, 15350, -1, 15349, 15231, 15347, -1, 15234, 15231, 15349, -1, 15347, 15232, 15345, -1, 15231, 15232, 15347, -1, 15345, 15230, 15343, -1, 15232, 15230, 15345, -1, 15343, 15228, 15340, -1, 15230, 15228, 15343, -1, 15340, 15229, 15339, -1, 15228, 15229, 15340, -1, 15339, 15226, 15337, -1, 15229, 15226, 15339, -1, 15337, 15227, 15335, -1, 15226, 15227, 15337, -1, 15335, 15224, 15334, -1, 15227, 15224, 15335, -1, 15334, 15225, 15336, -1, 15224, 15225, 15334, -1, 15336, 15223, 15338, -1, 15225, 15223, 15336, -1, 15338, 15001, 15003, -1, 15223, 15001, 15338, -1, 14999, 15270, 15000, -1, 15000, 15270, 15309, -1, 15309, 15280, 15311, -1, 15270, 15280, 15309, -1, 15311, 15281, 15312, -1, 15280, 15281, 15311, -1, 15312, 15282, 15313, -1, 15281, 15282, 15312, -1, 15313, 15283, 15314, -1, 15282, 15283, 15313, -1, 15314, 15284, 15308, -1, 15283, 15284, 15314, -1, 15308, 15271, 15307, -1, 15284, 15271, 15308, -1, 15307, 15273, 15305, -1, 15271, 15273, 15307, -1, 15305, 15274, 15302, -1, 15273, 15274, 15305, -1, 15302, 15275, 15303, -1, 15274, 15275, 15302, -1, 15303, 15276, 15304, -1, 15275, 15276, 15303, -1, 15304, 15265, 15306, -1, 15276, 15265, 15304, -1, 15306, 14973, 14975, -1, 15265, 14973, 15306, -1, 15433, 15434, 15435, -1, 15435, 15434, 15436, -1, 15436, 15437, 15438, -1, 15434, 15437, 15436, -1, 15438, 15439, 15440, -1, 15437, 15439, 15438, -1, 15440, 15441, 15442, -1, 15439, 15441, 15440, -1, 15442, 15443, 15444, -1, 15441, 15443, 15442, -1, 15444, 15445, 15446, -1, 15443, 15445, 15444, -1, 15446, 15447, 15448, -1, 15445, 15447, 15446, -1, 15448, 15449, 15450, -1, 15447, 15449, 15448, -1, 15450, 15451, 15452, -1, 15449, 15451, 15450, -1, 15452, 15453, 15454, -1, 15451, 15453, 15452, -1, 15454, 15455, 15456, -1, 15453, 15455, 15454, -1, 15456, 15457, 15458, -1, 15455, 15457, 15456, -1, 15458, 15459, 15460, -1, 15457, 15459, 15458, -1, 15461, 15462, 15463, -1, 15463, 15462, 15464, -1, 15464, 15465, 15466, -1, 15462, 15465, 15464, -1, 15466, 15467, 15468, -1, 15465, 15467, 15466, -1, 15468, 15469, 15470, -1, 15467, 15469, 15468, -1, 15470, 15471, 15472, -1, 15469, 15471, 15470, -1, 15472, 15473, 15474, -1, 15471, 15473, 15472, -1, 15474, 15475, 15476, -1, 15473, 15475, 15474, -1, 15476, 15477, 15478, -1, 15475, 15477, 15476, -1, 15478, 15479, 15480, -1, 15477, 15479, 15478, -1, 15480, 15481, 15482, -1, 15479, 15481, 15480, -1, 15482, 15483, 15484, -1, 15481, 15483, 15482, -1, 15484, 15485, 15486, -1, 15483, 15485, 15484, -1, 15486, 15487, 15488, -1, 15485, 15487, 15486, -1, 15489, 15490, 15491, -1, 15491, 15490, 15492, -1, 15492, 15493, 15494, -1, 15490, 15493, 15492, -1, 15494, 15495, 15496, -1, 15493, 15495, 15494, -1, 15496, 15497, 15498, -1, 15495, 15497, 15496, -1, 15498, 15499, 15500, -1, 15497, 15499, 15498, -1, 15500, 15501, 15502, -1, 15499, 15501, 15500, -1, 15502, 15503, 15504, -1, 15501, 15503, 15502, -1, 15504, 15505, 15506, -1, 15503, 15505, 15504, -1, 15506, 15507, 15508, -1, 15505, 15507, 15506, -1, 15508, 15509, 15510, -1, 15507, 15509, 15508, -1, 15510, 15511, 15512, -1, 15509, 15511, 15510, -1, 15512, 15513, 15514, -1, 15511, 15513, 15512, -1, 15514, 15515, 15516, -1, 15513, 15515, 15514, -1, 15517, 15518, 15519, -1, 15519, 15518, 15520, -1, 15520, 15521, 15522, -1, 15518, 15521, 15520, -1, 15522, 15523, 15524, -1, 15521, 15523, 15522, -1, 15524, 15525, 15526, -1, 15523, 15525, 15524, -1, 15526, 15527, 15528, -1, 15525, 15527, 15526, -1, 15528, 15529, 15530, -1, 15527, 15529, 15528, -1, 15530, 15531, 15532, -1, 15529, 15531, 15530, -1, 15532, 15533, 15534, -1, 15531, 15533, 15532, -1, 15534, 15535, 15536, -1, 15533, 15535, 15534, -1, 15536, 15537, 15538, -1, 15535, 15537, 15536, -1, 15538, 15539, 15540, -1, 15537, 15539, 15538, -1, 15540, 15541, 15542, -1, 15539, 15541, 15540, -1, 15542, 15543, 15544, -1, 15541, 15543, 15542, -1, 15545, 15546, 15547, -1, 15547, 15546, 15548, -1, 15549, 15550, 15551, -1, 15551, 15550, 15552, -1, 15553, 15554, 15555, -1, 15554, 15556, 15555, -1, 15557, 15558, 15559, -1, 15560, 15558, 15557, -1, 15439, 15547, 15549, -1, 15441, 15439, 15549, -1, 15437, 15547, 15439, -1, 15443, 15441, 15549, -1, 15434, 15547, 15437, -1, 15445, 15443, 15549, -1, 15433, 15547, 15434, -1, 15447, 15445, 15549, -1, 15561, 15547, 15433, -1, 15449, 15447, 15549, -1, 15562, 15547, 15561, -1, 15451, 15449, 15549, -1, 15497, 15563, 15564, -1, 15497, 15565, 15563, -1, 15497, 15495, 15565, -1, 15493, 15562, 15565, -1, 15493, 15547, 15562, -1, 15493, 15565, 15495, -1, 15499, 15497, 15564, -1, 15490, 15547, 15493, -1, 15501, 15564, 15566, -1, 15501, 15499, 15564, -1, 15489, 15547, 15490, -1, 15503, 15566, 15567, -1, 15503, 15501, 15566, -1, 15505, 15568, 15569, -1, 15505, 15567, 15568, -1, 15505, 15503, 15567, -1, 15507, 15505, 15569, -1, 15509, 15569, 15570, -1, 15509, 15507, 15569, -1, 15511, 15570, 15571, -1, 15511, 15509, 15570, -1, 15545, 15572, 15573, -1, 15545, 15574, 15572, -1, 15545, 15575, 15574, -1, 15545, 15576, 15575, -1, 15545, 15577, 15576, -1, 15545, 15489, 15577, -1, 15545, 15547, 15489, -1, 15469, 15453, 15451, -1, 15469, 15451, 15549, -1, 15469, 15467, 15453, -1, 15465, 15455, 15453, -1, 15465, 15453, 15467, -1, 15462, 15457, 15455, -1, 15462, 15459, 15457, -1, 15462, 15455, 15465, -1, 15558, 15545, 15573, -1, 15558, 15578, 15579, -1, 15558, 15580, 15578, -1, 15558, 15573, 15580, -1, 15461, 15459, 15462, -1, 15551, 15469, 15549, -1, 15551, 15471, 15469, -1, 15551, 15473, 15471, -1, 15551, 15475, 15473, -1, 15581, 15582, 15459, -1, 15581, 15459, 15461, -1, 15477, 15475, 15551, -1, 15583, 15571, 15582, -1, 15583, 15582, 15581, -1, 15479, 15477, 15551, -1, 15481, 15479, 15551, -1, 15555, 15483, 15481, -1, 15555, 15485, 15483, -1, 15555, 15481, 15551, -1, 15487, 15485, 15555, -1, 15584, 15487, 15555, -1, 15585, 15584, 15555, -1, 15525, 15586, 15587, -1, 15525, 15588, 15586, -1, 15525, 15523, 15588, -1, 15521, 15571, 15583, -1, 15521, 15583, 15588, -1, 15521, 15588, 15523, -1, 15521, 15511, 15571, -1, 15527, 15525, 15587, -1, 15518, 15513, 15511, -1, 15518, 15515, 15513, -1, 15518, 15511, 15521, -1, 15529, 15527, 15587, -1, 15529, 15587, 15589, -1, 15517, 15515, 15518, -1, 15531, 15589, 15590, -1, 15531, 15529, 15589, -1, 15591, 15592, 15515, -1, 15591, 15515, 15517, -1, 15533, 15593, 15594, -1, 15533, 15590, 15593, -1, 15533, 15531, 15590, -1, 15595, 15596, 15592, -1, 15595, 15592, 15591, -1, 15535, 15533, 15594, -1, 15597, 15598, 15596, -1, 15597, 15596, 15595, -1, 15537, 15535, 15594, -1, 15537, 15594, 15599, -1, 15600, 15598, 15597, -1, 15600, 15579, 15598, -1, 15539, 15599, 15585, -1, 15539, 15537, 15599, -1, 15539, 15585, 15555, -1, 15541, 15539, 15555, -1, 15543, 15541, 15555, -1, 15556, 15543, 15555, -1, 15556, 15601, 15543, -1, 15556, 15602, 15601, -1, 15556, 15603, 15602, -1, 15556, 15604, 15603, -1, 15556, 15605, 15604, -1, 15556, 15606, 15605, -1, 15559, 15579, 15600, -1, 15559, 15558, 15579, -1, 15559, 15607, 15606, -1, 15559, 15608, 15607, -1, 15559, 15600, 15608, -1, 15559, 15606, 15556, -1, 15548, 15440, 15550, -1, 15440, 15442, 15550, -1, 15548, 15438, 15440, -1, 15442, 15444, 15550, -1, 15548, 15436, 15438, -1, 15444, 15446, 15550, -1, 15548, 15435, 15436, -1, 15446, 15448, 15550, -1, 15548, 15609, 15435, -1, 15448, 15450, 15550, -1, 15548, 15610, 15609, -1, 15450, 15452, 15550, -1, 15611, 15498, 15612, -1, 15613, 15498, 15611, -1, 15496, 15498, 15613, -1, 15610, 15494, 15613, -1, 15548, 15494, 15610, -1, 15613, 15494, 15496, -1, 15498, 15500, 15612, -1, 15548, 15492, 15494, -1, 15612, 15502, 15614, -1, 15500, 15502, 15612, -1, 15548, 15491, 15492, -1, 15614, 15504, 15615, -1, 15502, 15504, 15614, -1, 15616, 15506, 15617, -1, 15615, 15506, 15616, -1, 15504, 15506, 15615, -1, 15506, 15508, 15617, -1, 15617, 15510, 15618, -1, 15508, 15510, 15617, -1, 15618, 15512, 15619, -1, 15510, 15512, 15618, -1, 15620, 15546, 15621, -1, 15622, 15546, 15620, -1, 15623, 15546, 15622, -1, 15624, 15546, 15623, -1, 15625, 15546, 15624, -1, 15491, 15546, 15625, -1, 15548, 15546, 15491, -1, 15454, 15470, 15452, -1, 15452, 15470, 15550, -1, 15468, 15470, 15454, -1, 15456, 15466, 15454, -1, 15454, 15466, 15468, -1, 15458, 15464, 15456, -1, 15460, 15464, 15458, -1, 15456, 15464, 15466, -1, 15546, 15560, 15621, -1, 15626, 15560, 15627, -1, 15628, 15560, 15626, -1, 15621, 15560, 15628, -1, 15460, 15463, 15464, -1, 15470, 15552, 15550, -1, 15472, 15552, 15470, -1, 15474, 15552, 15472, -1, 15476, 15552, 15474, -1, 15629, 15630, 15460, -1, 15460, 15630, 15463, -1, 15476, 15478, 15552, -1, 15619, 15631, 15629, -1, 15629, 15631, 15630, -1, 15478, 15480, 15552, -1, 15480, 15482, 15552, -1, 15484, 15553, 15482, -1, 15486, 15553, 15484, -1, 15482, 15553, 15552, -1, 15486, 15488, 15553, -1, 15488, 15632, 15553, -1, 15632, 15633, 15553, -1, 15634, 15526, 15635, -1, 15636, 15526, 15634, -1, 15524, 15526, 15636, -1, 15619, 15522, 15631, -1, 15631, 15522, 15636, -1, 15636, 15522, 15524, -1, 15512, 15522, 15619, -1, 15526, 15528, 15635, -1, 15514, 15520, 15512, -1, 15516, 15520, 15514, -1, 15512, 15520, 15522, -1, 15528, 15530, 15635, -1, 15635, 15530, 15637, -1, 15516, 15519, 15520, -1, 15637, 15532, 15638, -1, 15530, 15532, 15637, -1, 15639, 15640, 15516, -1, 15516, 15640, 15519, -1, 15641, 15534, 15642, -1, 15638, 15534, 15641, -1, 15532, 15534, 15638, -1, 15643, 15644, 15639, -1, 15639, 15644, 15640, -1, 15534, 15536, 15642, -1, 15645, 15646, 15643, -1, 15643, 15646, 15644, -1, 15536, 15538, 15642, -1, 15642, 15538, 15647, -1, 15645, 15648, 15646, -1, 15627, 15648, 15645, -1, 15647, 15540, 15633, -1, 15538, 15540, 15647, -1, 15633, 15540, 15553, -1, 15540, 15542, 15553, -1, 15542, 15544, 15553, -1, 15627, 15557, 15648, -1, 15560, 15557, 15627, -1, 15649, 15557, 15650, -1, 15651, 15557, 15649, -1, 15648, 15557, 15651, -1, 15557, 15554, 15650, -1, 15544, 15554, 15553, -1, 15652, 15554, 15544, -1, 15653, 15554, 15652, -1, 15654, 15554, 15653, -1, 15655, 15554, 15654, -1, 15656, 15554, 15655, -1, 15650, 15554, 15656, -1, 15543, 15601, 15544, -1, 15544, 15601, 15652, -1, 15652, 15602, 15653, -1, 15601, 15602, 15652, -1, 15653, 15603, 15654, -1, 15602, 15603, 15653, -1, 15654, 15604, 15655, -1, 15603, 15604, 15654, -1, 15655, 15605, 15656, -1, 15604, 15605, 15655, -1, 15656, 15606, 15650, -1, 15605, 15606, 15656, -1, 15650, 15607, 15649, -1, 15606, 15607, 15650, -1, 15649, 15608, 15651, -1, 15607, 15608, 15649, -1, 15651, 15600, 15648, -1, 15608, 15600, 15651, -1, 15648, 15597, 15646, -1, 15600, 15597, 15648, -1, 15646, 15595, 15644, -1, 15597, 15595, 15646, -1, 15644, 15591, 15640, -1, 15595, 15591, 15644, -1, 15640, 15517, 15519, -1, 15591, 15517, 15640, -1, 15515, 15592, 15516, -1, 15516, 15592, 15639, -1, 15639, 15596, 15643, -1, 15592, 15596, 15639, -1, 15643, 15598, 15645, -1, 15596, 15598, 15643, -1, 15645, 15579, 15627, -1, 15598, 15579, 15645, -1, 15627, 15578, 15626, -1, 15579, 15578, 15627, -1, 15626, 15580, 15628, -1, 15578, 15580, 15626, -1, 15628, 15573, 15621, -1, 15580, 15573, 15628, -1, 15621, 15572, 15620, -1, 15573, 15572, 15621, -1, 15620, 15574, 15622, -1, 15572, 15574, 15620, -1, 15622, 15575, 15623, -1, 15574, 15575, 15622, -1, 15623, 15576, 15624, -1, 15575, 15576, 15623, -1, 15624, 15577, 15625, -1, 15576, 15577, 15624, -1, 15625, 15489, 15491, -1, 15577, 15489, 15625, -1, 15487, 15584, 15488, -1, 15488, 15584, 15632, -1, 15632, 15585, 15633, -1, 15584, 15585, 15632, -1, 15633, 15599, 15647, -1, 15585, 15599, 15633, -1, 15647, 15594, 15642, -1, 15599, 15594, 15647, -1, 15642, 15593, 15641, -1, 15594, 15593, 15642, -1, 15641, 15590, 15638, -1, 15593, 15590, 15641, -1, 15638, 15589, 15637, -1, 15590, 15589, 15638, -1, 15637, 15587, 15635, -1, 15589, 15587, 15637, -1, 15635, 15586, 15634, -1, 15587, 15586, 15635, -1, 15634, 15588, 15636, -1, 15586, 15588, 15634, -1, 15636, 15583, 15631, -1, 15588, 15583, 15636, -1, 15631, 15581, 15630, -1, 15583, 15581, 15631, -1, 15630, 15461, 15463, -1, 15581, 15461, 15630, -1, 15459, 15582, 15460, -1, 15460, 15582, 15629, -1, 15629, 15571, 15619, -1, 15582, 15571, 15629, -1, 15619, 15570, 15618, -1, 15571, 15570, 15619, -1, 15618, 15569, 15617, -1, 15570, 15569, 15618, -1, 15617, 15568, 15616, -1, 15569, 15568, 15617, -1, 15616, 15567, 15615, -1, 15568, 15567, 15616, -1, 15615, 15566, 15614, -1, 15567, 15566, 15615, -1, 15614, 15564, 15612, -1, 15566, 15564, 15614, -1, 15612, 15563, 15611, -1, 15564, 15563, 15612, -1, 15611, 15565, 15613, -1, 15563, 15565, 15611, -1, 15613, 15562, 15610, -1, 15565, 15562, 15613, -1, 15610, 15561, 15609, -1, 15562, 15561, 15610, -1, 15609, 15433, 15435, -1, 15561, 15433, 15609, -1, 15556, 15554, 15559, -1, 15559, 15554, 15557, -1, 15558, 15560, 15545, -1, 15545, 15560, 15546, -1, 15547, 15548, 15549, -1, 15549, 15548, 15550, -1, 15551, 15552, 15555, -1, 15555, 15552, 15553, -1, 15657, 15658, 15659, -1, 15659, 15658, 15660, -1, 15660, 15661, 15662, -1, 15658, 15661, 15660, -1, 15662, 15663, 15664, -1, 15661, 15663, 15662, -1, 15664, 15665, 15666, -1, 15663, 15665, 15664, -1, 15666, 15667, 15668, -1, 15665, 15667, 15666, -1, 15668, 15669, 15670, -1, 15667, 15669, 15668, -1, 15670, 15671, 15672, -1, 15669, 15671, 15670, -1, 15672, 15673, 15674, -1, 15671, 15673, 15672, -1, 15674, 15675, 15676, -1, 15673, 15675, 15674, -1, 15676, 15677, 15678, -1, 15675, 15677, 15676, -1, 15678, 15679, 15680, -1, 15677, 15679, 15678, -1, 15680, 15681, 15682, -1, 15679, 15681, 15680, -1, 15682, 15683, 15684, -1, 15681, 15683, 15682, -1, 15685, 15686, 15687, -1, 15687, 15686, 15688, -1, 15688, 15689, 15690, -1, 15686, 15689, 15688, -1, 15690, 15691, 15692, -1, 15689, 15691, 15690, -1, 15692, 15693, 15694, -1, 15691, 15693, 15692, -1, 15694, 15695, 15696, -1, 15693, 15695, 15694, -1, 15696, 15697, 15698, -1, 15695, 15697, 15696, -1, 15698, 15699, 15700, -1, 15697, 15699, 15698, -1, 15700, 15701, 15702, -1, 15699, 15701, 15700, -1, 15702, 15703, 15704, -1, 15701, 15703, 15702, -1, 15704, 15705, 15706, -1, 15703, 15705, 15704, -1, 15706, 15707, 15708, -1, 15705, 15707, 15706, -1, 15708, 15709, 15710, -1, 15707, 15709, 15708, -1, 15710, 15711, 15712, -1, 15709, 15711, 15710, -1, 15713, 15714, 15715, -1, 15715, 15714, 15716, -1, 15716, 15717, 15718, -1, 15714, 15717, 15716, -1, 15718, 15719, 15720, -1, 15717, 15719, 15718, -1, 15720, 15721, 15722, -1, 15719, 15721, 15720, -1, 15722, 15723, 15724, -1, 15721, 15723, 15722, -1, 15724, 15725, 15726, -1, 15723, 15725, 15724, -1, 15726, 15727, 15728, -1, 15725, 15727, 15726, -1, 15728, 15729, 15730, -1, 15727, 15729, 15728, -1, 15730, 15731, 15732, -1, 15729, 15731, 15730, -1, 15732, 15733, 15734, -1, 15731, 15733, 15732, -1, 15734, 15735, 15736, -1, 15733, 15735, 15734, -1, 15736, 15737, 15738, -1, 15735, 15737, 15736, -1, 15738, 15739, 15740, -1, 15737, 15739, 15738, -1, 15741, 15742, 15743, -1, 15743, 15742, 15744, -1, 15744, 15745, 15746, -1, 15742, 15745, 15744, -1, 15746, 15747, 15748, -1, 15745, 15747, 15746, -1, 15748, 15749, 15750, -1, 15747, 15749, 15748, -1, 15750, 15751, 15752, -1, 15749, 15751, 15750, -1, 15752, 15753, 15754, -1, 15751, 15753, 15752, -1, 15754, 15755, 15756, -1, 15753, 15755, 15754, -1, 15756, 15757, 15758, -1, 15755, 15757, 15756, -1, 15758, 15759, 15760, -1, 15757, 15759, 15758, -1, 15760, 15761, 15762, -1, 15759, 15761, 15760, -1, 15762, 15763, 15764, -1, 15761, 15763, 15762, -1, 15764, 15765, 15766, -1, 15763, 15765, 15764, -1, 15766, 15767, 15768, -1, 15765, 15767, 15766, -1, 15769, 15770, 15771, -1, 15770, 15772, 15771, -1, 15773, 15774, 15775, -1, 15774, 15776, 15775, -1, 15777, 15778, 15779, -1, 15778, 15780, 15779, -1, 15781, 15782, 15783, -1, 15782, 15784, 15783, -1, 15721, 15719, 15769, -1, 15717, 15769, 15719, -1, 15723, 15721, 15769, -1, 15714, 15769, 15717, -1, 15725, 15769, 15783, -1, 15725, 15723, 15769, -1, 15713, 15769, 15714, -1, 15727, 15725, 15783, -1, 15729, 15727, 15783, -1, 15731, 15729, 15783, -1, 15663, 15785, 15786, -1, 15665, 15663, 15786, -1, 15665, 15786, 15787, -1, 15665, 15787, 15788, -1, 15661, 15785, 15663, -1, 15667, 15665, 15788, -1, 15667, 15788, 15789, -1, 15669, 15667, 15789, -1, 15671, 15789, 15790, -1, 15671, 15669, 15789, -1, 15770, 15661, 15658, -1, 15770, 15658, 15657, -1, 15770, 15769, 15713, -1, 15770, 15713, 15791, -1, 15770, 15791, 15785, -1, 15770, 15785, 15661, -1, 15792, 15770, 15657, -1, 15673, 15671, 15790, -1, 15673, 15790, 15793, -1, 15794, 15770, 15792, -1, 15675, 15673, 15793, -1, 15675, 15793, 15795, -1, 15675, 15795, 15796, -1, 15797, 15770, 15794, -1, 15677, 15675, 15796, -1, 15677, 15796, 15798, -1, 15679, 15677, 15798, -1, 15773, 15797, 15799, -1, 15773, 15799, 15800, -1, 15773, 15770, 15797, -1, 15801, 15773, 15800, -1, 15802, 15773, 15801, -1, 15784, 15731, 15783, -1, 15803, 15773, 15802, -1, 15804, 15773, 15803, -1, 15747, 15733, 15731, -1, 15749, 15747, 15731, -1, 15749, 15731, 15784, -1, 15745, 15733, 15747, -1, 15745, 15737, 15735, -1, 15745, 15735, 15733, -1, 15751, 15749, 15784, -1, 15742, 15737, 15745, -1, 15753, 15751, 15784, -1, 15741, 15737, 15742, -1, 15741, 15739, 15737, -1, 15755, 15784, 15779, -1, 15755, 15753, 15784, -1, 15805, 15739, 15741, -1, 15805, 15806, 15739, -1, 15757, 15755, 15779, -1, 15807, 15806, 15805, -1, 15807, 15798, 15806, -1, 15759, 15757, 15779, -1, 15761, 15759, 15779, -1, 15763, 15761, 15779, -1, 15765, 15763, 15779, -1, 15767, 15765, 15779, -1, 15691, 15807, 15808, -1, 15691, 15808, 15809, -1, 15693, 15691, 15809, -1, 15693, 15809, 15810, -1, 15689, 15681, 15679, -1, 15689, 15798, 15807, -1, 15689, 15807, 15691, -1, 15689, 15679, 15798, -1, 15695, 15693, 15810, -1, 15695, 15810, 15811, -1, 15686, 15681, 15689, -1, 15697, 15695, 15811, -1, 15685, 15683, 15681, -1, 15685, 15681, 15686, -1, 15699, 15697, 15811, -1, 15699, 15811, 15812, -1, 15813, 15814, 15683, -1, 15813, 15683, 15685, -1, 15701, 15699, 15812, -1, 15701, 15812, 15815, -1, 15816, 15814, 15813, -1, 15816, 15817, 15814, -1, 15703, 15818, 15819, -1, 15703, 15701, 15815, -1, 15703, 15815, 15818, -1, 15820, 15821, 15817, -1, 15820, 15817, 15816, -1, 15705, 15819, 15822, -1, 15705, 15703, 15819, -1, 15823, 15821, 15820, -1, 15823, 15804, 15821, -1, 15707, 15705, 15822, -1, 15780, 15822, 15824, -1, 15780, 15824, 15767, -1, 15780, 15707, 15822, -1, 15780, 15711, 15709, -1, 15780, 15709, 15707, -1, 15780, 15767, 15779, -1, 15780, 15825, 15826, -1, 15780, 15826, 15827, -1, 15780, 15827, 15711, -1, 15774, 15823, 15828, -1, 15774, 15828, 15829, -1, 15774, 15829, 15830, -1, 15774, 15830, 15831, -1, 15774, 15831, 15832, -1, 15774, 15832, 15825, -1, 15774, 15825, 15780, -1, 15774, 15773, 15804, -1, 15774, 15804, 15823, -1, 15720, 15722, 15771, -1, 15771, 15718, 15720, -1, 15722, 15724, 15771, -1, 15771, 15716, 15718, -1, 15771, 15726, 15781, -1, 15724, 15726, 15771, -1, 15771, 15715, 15716, -1, 15726, 15728, 15781, -1, 15728, 15730, 15781, -1, 15730, 15732, 15781, -1, 15664, 15666, 15833, -1, 15833, 15666, 15834, -1, 15834, 15666, 15835, -1, 15833, 15662, 15664, -1, 15836, 15662, 15833, -1, 15666, 15668, 15835, -1, 15835, 15670, 15837, -1, 15668, 15670, 15835, -1, 15670, 15672, 15837, -1, 15837, 15672, 15838, -1, 15662, 15772, 15660, -1, 15660, 15772, 15659, -1, 15771, 15772, 15715, -1, 15715, 15772, 15839, -1, 15839, 15772, 15836, -1, 15836, 15772, 15662, -1, 15772, 15840, 15659, -1, 15672, 15674, 15838, -1, 15838, 15674, 15841, -1, 15772, 15842, 15840, -1, 15674, 15676, 15841, -1, 15841, 15676, 15843, -1, 15772, 15844, 15842, -1, 15843, 15678, 15845, -1, 15676, 15678, 15843, -1, 15845, 15678, 15846, -1, 15678, 15680, 15846, -1, 15844, 15775, 15847, -1, 15847, 15775, 15848, -1, 15772, 15775, 15844, -1, 15775, 15849, 15848, -1, 15775, 15850, 15849, -1, 15775, 15851, 15850, -1, 15775, 15852, 15851, -1, 15781, 15750, 15782, -1, 15748, 15750, 15734, -1, 15732, 15750, 15781, -1, 15734, 15750, 15732, -1, 15734, 15746, 15748, -1, 15738, 15746, 15736, -1, 15736, 15746, 15734, -1, 15750, 15752, 15782, -1, 15738, 15744, 15746, -1, 15752, 15754, 15782, -1, 15738, 15743, 15744, -1, 15740, 15743, 15738, -1, 15782, 15756, 15777, -1, 15754, 15756, 15782, -1, 15740, 15853, 15743, -1, 15854, 15853, 15740, -1, 15756, 15758, 15777, -1, 15854, 15855, 15853, -1, 15846, 15855, 15854, -1, 15758, 15760, 15777, -1, 15760, 15762, 15777, -1, 15762, 15764, 15777, -1, 15764, 15766, 15777, -1, 15766, 15768, 15777, -1, 15856, 15692, 15857, -1, 15692, 15694, 15857, -1, 15682, 15690, 15680, -1, 15680, 15690, 15846, -1, 15846, 15690, 15855, -1, 15856, 15690, 15692, -1, 15855, 15690, 15856, -1, 15694, 15696, 15857, -1, 15857, 15696, 15858, -1, 15682, 15688, 15690, -1, 15696, 15698, 15858, -1, 15858, 15698, 15859, -1, 15684, 15687, 15682, -1, 15682, 15687, 15688, -1, 15698, 15700, 15859, -1, 15859, 15700, 15860, -1, 15861, 15862, 15684, -1, 15684, 15862, 15687, -1, 15700, 15702, 15860, -1, 15860, 15702, 15863, -1, 15864, 15865, 15861, -1, 15861, 15865, 15862, -1, 15702, 15704, 15863, -1, 15863, 15704, 15866, -1, 15867, 15868, 15864, -1, 15864, 15868, 15865, -1, 15866, 15706, 15869, -1, 15704, 15706, 15866, -1, 15852, 15870, 15867, -1, 15867, 15870, 15868, -1, 15869, 15708, 15871, -1, 15706, 15708, 15869, -1, 15708, 15778, 15871, -1, 15871, 15778, 15872, -1, 15872, 15778, 15768, -1, 15712, 15778, 15710, -1, 15710, 15778, 15708, -1, 15873, 15778, 15874, -1, 15874, 15778, 15875, -1, 15875, 15778, 15712, -1, 15768, 15778, 15777, -1, 15873, 15776, 15778, -1, 15870, 15776, 15876, -1, 15876, 15776, 15877, -1, 15877, 15776, 15878, -1, 15878, 15776, 15879, -1, 15879, 15776, 15880, -1, 15880, 15776, 15873, -1, 15775, 15776, 15852, -1, 15852, 15776, 15870, -1, 15767, 15824, 15768, -1, 15768, 15824, 15872, -1, 15872, 15822, 15871, -1, 15824, 15822, 15872, -1, 15871, 15819, 15869, -1, 15822, 15819, 15871, -1, 15869, 15818, 15866, -1, 15819, 15818, 15869, -1, 15866, 15815, 15863, -1, 15818, 15815, 15866, -1, 15863, 15812, 15860, -1, 15815, 15812, 15863, -1, 15860, 15811, 15859, -1, 15812, 15811, 15860, -1, 15859, 15810, 15858, -1, 15811, 15810, 15859, -1, 15858, 15809, 15857, -1, 15810, 15809, 15858, -1, 15857, 15808, 15856, -1, 15809, 15808, 15857, -1, 15856, 15807, 15855, -1, 15808, 15807, 15856, -1, 15855, 15805, 15853, -1, 15807, 15805, 15855, -1, 15853, 15741, 15743, -1, 15805, 15741, 15853, -1, 15739, 15806, 15740, -1, 15740, 15806, 15854, -1, 15854, 15798, 15846, -1, 15806, 15798, 15854, -1, 15846, 15796, 15845, -1, 15798, 15796, 15846, -1, 15845, 15795, 15843, -1, 15796, 15795, 15845, -1, 15843, 15793, 15841, -1, 15795, 15793, 15843, -1, 15841, 15790, 15838, -1, 15793, 15790, 15841, -1, 15838, 15789, 15837, -1, 15790, 15789, 15838, -1, 15837, 15788, 15835, -1, 15789, 15788, 15837, -1, 15835, 15787, 15834, -1, 15788, 15787, 15835, -1, 15834, 15786, 15833, -1, 15787, 15786, 15834, -1, 15833, 15785, 15836, -1, 15786, 15785, 15833, -1, 15836, 15791, 15839, -1, 15785, 15791, 15836, -1, 15839, 15713, 15715, -1, 15791, 15713, 15839, -1, 15711, 15827, 15712, -1, 15712, 15827, 15875, -1, 15875, 15826, 15874, -1, 15827, 15826, 15875, -1, 15874, 15825, 15873, -1, 15826, 15825, 15874, -1, 15873, 15832, 15880, -1, 15825, 15832, 15873, -1, 15880, 15831, 15879, -1, 15832, 15831, 15880, -1, 15879, 15830, 15878, -1, 15831, 15830, 15879, -1, 15878, 15829, 15877, -1, 15830, 15829, 15878, -1, 15877, 15828, 15876, -1, 15829, 15828, 15877, -1, 15876, 15823, 15870, -1, 15828, 15823, 15876, -1, 15870, 15820, 15868, -1, 15823, 15820, 15870, -1, 15868, 15816, 15865, -1, 15820, 15816, 15868, -1, 15865, 15813, 15862, -1, 15816, 15813, 15865, -1, 15862, 15685, 15687, -1, 15813, 15685, 15862, -1, 15683, 15814, 15684, -1, 15684, 15814, 15861, -1, 15861, 15817, 15864, -1, 15814, 15817, 15861, -1, 15864, 15821, 15867, -1, 15817, 15821, 15864, -1, 15867, 15804, 15852, -1, 15821, 15804, 15867, -1, 15852, 15803, 15851, -1, 15804, 15803, 15852, -1, 15851, 15802, 15850, -1, 15803, 15802, 15851, -1, 15850, 15801, 15849, -1, 15802, 15801, 15850, -1, 15849, 15800, 15848, -1, 15801, 15800, 15849, -1, 15848, 15799, 15847, -1, 15800, 15799, 15848, -1, 15847, 15797, 15844, -1, 15799, 15797, 15847, -1, 15844, 15794, 15842, -1, 15797, 15794, 15844, -1, 15842, 15792, 15840, -1, 15794, 15792, 15842, -1, 15840, 15657, 15659, -1, 15792, 15657, 15840, -1, 15784, 15782, 15779, -1, 15779, 15782, 15777, -1, 15769, 15771, 15783, -1, 15783, 15771, 15781, -1, 15780, 15778, 15774, -1, 15774, 15778, 15776, -1, 15773, 15775, 15770, -1, 15770, 15775, 15772, -1, 15881, 15882, 15883, -1, 15884, 15885, 15886, -1, 15887, 15888, 15889, -1, 15890, 15881, 15891, -1, 15887, 15892, 15888, -1, 15893, 15890, 15891, -1, 15893, 15894, 15895, -1, 15893, 15891, 15894, -1, 15896, 15897, 15898, -1, 15899, 15900, 15901, -1, 15896, 15902, 15903, -1, 15896, 15903, 15897, -1, 15899, 15901, 15904, -1, 15896, 15898, 15905, -1, 15906, 15907, 15908, -1, 15909, 15896, 15905, -1, 15909, 15910, 15911, -1, 15909, 15912, 15910, -1, 15909, 15905, 15912, -1, 15913, 15914, 15915, -1, 15913, 15915, 15916, -1, 15917, 15918, 15919, -1, 15906, 15908, 15920, -1, 15917, 15921, 15918, -1, 15913, 15922, 15914, -1, 15923, 15924, 15925, -1, 15926, 15889, 15927, -1, 15913, 15928, 15922, -1, 15929, 15913, 15916, -1, 15926, 15927, 15930, -1, 15929, 15916, 15931, -1, 15932, 15933, 15934, -1, 15929, 15931, 15935, -1, 15932, 15936, 15933, -1, 15929, 15935, 15937, -1, 15938, 15939, 15882, -1, 15923, 15904, 15924, -1, 15938, 15882, 15881, -1, 15940, 15941, 15942, -1, 15940, 15943, 15944, -1, 15938, 15881, 15890, -1, 15940, 15944, 15941, -1, 15940, 15942, 15945, -1, 15938, 15946, 15939, -1, 15947, 15893, 15895, -1, 15947, 15890, 15893, -1, 15948, 15920, 15949, -1, 15947, 15895, 15950, -1, 15947, 15938, 15890, -1, 15948, 15949, 15951, -1, 15952, 15902, 15896, -1, 15953, 15954, 15955, -1, 15956, 15957, 15958, -1, 15953, 15955, 15959, -1, 15953, 15960, 15954, -1, 15956, 15925, 15957, -1, 15953, 15959, 15961, -1, 15952, 15962, 15902, -1, 15963, 15964, 15907, -1, 15965, 15952, 15896, -1, 15963, 15907, 15906, -1, 15966, 15967, 15968, -1, 15966, 15968, 15969, -1, 15970, 15909, 15911, -1, 15970, 15965, 15896, -1, 15971, 15885, 15884, -1, 15970, 15896, 15909, -1, 15970, 15911, 15972, -1, 15973, 15951, 15974, -1, 15975, 15928, 15913, -1, 15902, 15976, 15903, -1, 15971, 15977, 15885, -1, 15975, 15919, 15928, -1, 15978, 15975, 15913, -1, 15979, 15900, 15899, -1, 15902, 15930, 15976, -1, 15980, 15961, 15892, -1, 15981, 15913, 15929, -1, 15980, 15892, 15887, -1, 15981, 15929, 15937, -1, 15979, 15982, 15900, -1, 15981, 15978, 15913, -1, 15981, 15937, 15983, -1, 15984, 15985, 15946, -1, 15984, 15946, 15938, -1, 15986, 15921, 15917, -1, 15986, 15945, 15921, -1, 15987, 15887, 15889, -1, 15988, 15984, 15938, -1, 15987, 15889, 15926, -1, 15989, 15950, 15990, -1, 15989, 15947, 15950, -1, 15989, 15938, 15947, -1, 15989, 15988, 15938, -1, 15991, 15904, 15923, -1, 15992, 15993, 15962, -1, 15994, 15906, 15920, -1, 15994, 15920, 15948, -1, 15992, 15962, 15952, -1, 15991, 15899, 15904, -1, 15992, 15952, 15965, -1, 15995, 15936, 15932, -1, 15996, 15972, 15997, -1, 15998, 15925, 15956, -1, 15996, 15970, 15972, -1, 15995, 15999, 15936, -1, 15996, 15965, 15970, -1, 15998, 15923, 15925, -1, 15996, 15992, 15965, -1, 16000, 15958, 15977, -1, 16001, 15917, 15919, -1, 16001, 15919, 15975, -1, 16000, 15977, 15971, -1, 16002, 15948, 15951, -1, 16001, 15975, 15978, -1, 16002, 15951, 15973, -1, 16003, 15967, 15966, -1, 16004, 15978, 15981, -1, 16003, 16005, 15967, -1, 16006, 15964, 15963, -1, 16004, 15981, 15983, -1, 16004, 16001, 15978, -1, 16006, 15934, 15964, -1, 16004, 15983, 16007, -1, 16008, 16009, 15985, -1, 16008, 15985, 15984, -1, 16010, 15969, 15982, -1, 16010, 15982, 15979, -1, 16008, 15984, 15988, -1, 16011, 15990, 16012, -1, 16011, 15989, 15990, -1, 16013, 15963, 15906, -1, 16011, 15988, 15989, -1, 16011, 16008, 15988, -1, 16014, 15993, 15992, -1, 16013, 15906, 15994, -1, 16015, 15958, 16000, -1, 16014, 16016, 15993, -1, 16014, 15992, 15996, -1, 16015, 15956, 15958, -1, 15962, 15926, 15930, -1, 16017, 15945, 15986, -1, 15962, 15930, 15902, -1, 16017, 15943, 15940, -1, 16017, 15940, 15945, -1, 16018, 15960, 15953, -1, 16018, 15953, 15961, -1, 16019, 16014, 15996, -1, 16018, 15961, 15980, -1, 16020, 15997, 16021, -1, 16020, 16019, 15996, -1, 16022, 15980, 15887, -1, 16020, 15996, 15997, -1, 16023, 15986, 15917, -1, 16022, 15887, 15987, -1, 16024, 15979, 15899, -1, 16025, 15999, 15995, -1, 16023, 15917, 16001, -1, 16024, 15899, 15991, -1, 16023, 16001, 16004, -1, 16025, 16026, 15999, -1, 16027, 15994, 15948, -1, 16028, 16023, 16004, -1, 16029, 16007, 16030, -1, 16031, 15991, 15923, -1, 16029, 16004, 16007, -1, 16031, 15923, 15998, -1, 16029, 16028, 16004, -1, 16032, 15935, 16005, -1, 16027, 15948, 16002, -1, 16033, 16034, 16009, -1, 16032, 16005, 16003, -1, 16035, 15974, 16036, -1, 16033, 16009, 16008, -1, 16033, 16008, 16011, -1, 16035, 15973, 15974, -1, 16037, 16033, 16011, -1, 16038, 15966, 15969, -1, 16038, 15969, 16010, -1, 16039, 15932, 15934, -1, 16039, 15934, 16006, -1, 16040, 16037, 16011, -1, 16040, 16012, 16041, -1, 16040, 16011, 16012, -1, 16042, 16016, 16014, -1, 16042, 16043, 16016, -1, 16044, 15998, 15956, -1, 16042, 16014, 16019, -1, 16044, 15956, 16015, -1, 16045, 16021, 16046, -1, 16045, 16042, 16019, -1, 16045, 16020, 16021, -1, 16045, 16019, 16020, -1, 16047, 16023, 16028, -1, 16048, 15963, 16013, -1, 16047, 16017, 15986, -1, 16048, 16006, 15963, -1, 15993, 15926, 15962, -1, 16047, 15986, 16023, -1, 16049, 16038, 16010, -1, 16050, 16029, 16030, -1, 16050, 16028, 16029, -1, 16050, 16030, 16051, -1, 16049, 16010, 15979, -1, 15993, 15987, 15926, -1, 16050, 16047, 16028, -1, 16049, 15979, 16024, -1, 16052, 16033, 16037, -1, 16053, 16013, 15994, -1, 16052, 16054, 16034, -1, 16052, 16034, 16033, -1, 16055, 16024, 15991, -1, 16053, 15994, 16027, -1, 16056, 16040, 16041, -1, 16056, 16037, 16040, -1, 16055, 15991, 16031, -1, 16057, 16018, 15980, -1, 16057, 16058, 15960, -1, 16056, 16041, 16059, -1, 16056, 16052, 16037, -1, 16057, 15960, 16018, -1, 16057, 15980, 16022, -1, 16060, 15937, 15935, -1, 16061, 16043, 16042, -1, 16060, 15935, 16032, -1, 16061, 16058, 16043, -1, 16062, 16026, 16025, -1, 16063, 16058, 16061, -1, 16063, 16064, 16058, -1, 16062, 16065, 16026, -1, 16063, 16061, 16042, -1, 16066, 16002, 15973, -1, 16067, 16042, 16045, -1, 16067, 16063, 16042, -1, 16067, 16064, 16063, -1, 16067, 16045, 16046, -1, 16068, 15966, 16038, -1, 16066, 15973, 16035, -1, 16067, 16046, 16064, -1, 16069, 16017, 16047, -1, 16068, 16003, 15966, -1, 16069, 15943, 16017, -1, 16070, 16031, 15998, -1, 16071, 16069, 16047, -1, 16072, 15932, 16039, -1, 16070, 15998, 16044, -1, 16071, 15943, 16069, -1, 16071, 16073, 15943, -1, 16074, 16050, 16051, -1, 16072, 15995, 15932, -1, 16074, 16047, 16050, -1, 16074, 16071, 16047, -1, 16016, 16022, 15987, -1, 16074, 16073, 16071, -1, 16074, 16051, 16073, -1, 16075, 16076, 16054, -1, 16016, 15987, 15993, -1, 16077, 16038, 16049, -1, 16075, 16054, 16052, -1, 16078, 16076, 16075, -1, 16078, 16079, 16076, -1, 16078, 16075, 16052, -1, 16080, 16059, 16079, -1, 16080, 16056, 16059, -1, 16080, 16052, 16056, -1, 16081, 16024, 16055, -1, 16080, 16079, 16078, -1, 16082, 16006, 16048, -1, 16080, 16078, 16052, -1, 16081, 16049, 16024, -1, 16082, 16039, 16006, -1, 16083, 16013, 16053, -1, 16084, 15937, 16060, -1, 16083, 16048, 16013, -1, 16084, 15983, 15937, -1, 16085, 16003, 16068, -1, 16086, 16002, 16066, -1, 16086, 16027, 16002, -1, 16085, 16032, 16003, -1, 16087, 16088, 16065, -1, 16089, 16038, 16077, -1, 16089, 16068, 16038, -1, 16087, 16065, 16062, -1, 16090, 16091, 16092, -1, 16090, 16092, 16093, -1, 16094, 15995, 16072, -1, 16095, 16096, 16091, -1, 16097, 16031, 16070, -1, 16094, 16025, 15995, -1, 16098, 16027, 16086, -1, 16097, 16055, 16031, -1, 16098, 16053, 16027, -1, 16099, 16077, 16049, -1, 16095, 16091, 16090, -1, 16100, 16101, 16096, -1, 16100, 16096, 16095, -1, 16099, 16049, 16081, -1, 16102, 15983, 16084, -1, 16043, 16022, 16016, -1, 16043, 16057, 16022, -1, 16102, 16007, 15983, -1, 16043, 16058, 16057, -1, 16103, 16060, 16032, -1, 16104, 16072, 16039, -1, 16103, 16032, 16085, -1, 16104, 16039, 16082, -1, 16105, 16101, 16100, -1, 16106, 16048, 16083, -1, 16107, 16103, 16085, -1, 16105, 16108, 16101, -1, 16107, 16068, 16089, -1, 16106, 16082, 16048, -1, 16109, 16093, 16110, -1, 16107, 16085, 16068, -1, 16109, 16090, 16093, -1, 16111, 16081, 16055, -1, 16112, 16088, 16087, -1, 16112, 15910, 16088, -1, 16113, 16095, 16090, -1, 16111, 16055, 16097, -1, 16113, 16090, 16109, -1, 16114, 16108, 16105, -1, 16115, 16089, 16077, -1, 16116, 16062, 16025, -1, 16116, 16025, 16094, -1, 16115, 16077, 16099, -1, 16114, 16117, 16108, -1, 16118, 16030, 16007, -1, 16119, 16110, 16120, -1, 16119, 16109, 16110, -1, 16118, 16007, 16102, -1, 16121, 16095, 16113, -1, 16122, 16084, 16060, -1, 16122, 16060, 16103, -1, 16123, 16083, 16053, -1, 16123, 16053, 16098, -1, 16121, 16100, 16095, -1, 16124, 16103, 16107, -1, 16124, 16122, 16103, -1, 16125, 16094, 16072, -1, 16126, 16127, 16117, -1, 16126, 16117, 16114, -1, 16128, 16099, 16081, -1, 16125, 16072, 16104, -1, 16129, 16109, 16119, -1, 16128, 16081, 16111, -1, 16130, 16107, 16089, -1, 16129, 16113, 16109, -1, 16131, 16104, 16082, -1, 16131, 16082, 16106, -1, 16130, 16089, 16115, -1, 16132, 16105, 16100, -1, 16133, 16051, 16030, -1, 16134, 15911, 15910, -1, 16132, 16100, 16121, -1, 16133, 16030, 16118, -1, 16134, 15972, 15911, -1, 16133, 16135, 16073, -1, 16134, 15910, 16112, -1, 16133, 16073, 16051, -1, 16136, 16084, 16122, -1, 16137, 16119, 16120, -1, 16136, 16102, 16084, -1, 16138, 16121, 16113, -1, 16138, 16113, 16129, -1, 16139, 16087, 16062, -1, 16140, 16099, 16128, -1, 16140, 16115, 16099, -1, 16139, 16062, 16116, -1, 16141, 16142, 16127, -1, 16141, 16127, 16126, -1, 16143, 16122, 16124, -1, 16144, 16083, 16123, -1, 16145, 16129, 16119, -1, 16146, 16107, 16130, -1, 16145, 16119, 16137, -1, 16146, 16124, 16107, -1, 16144, 16106, 16083, -1, 16147, 16094, 16125, -1, 16148, 16118, 16102, -1, 16149, 16105, 16132, -1, 16149, 16114, 16105, -1, 16147, 16116, 16094, -1, 16148, 16102, 16136, -1, 16150, 16125, 16104, -1, 16151, 16121, 16138, -1, 16150, 16104, 16131, -1, 16151, 16132, 16121, -1, 15939, 16130, 16115, -1, 16152, 16142, 16141, -1, 15939, 16115, 16140, -1, 16153, 16136, 16122, -1, 16153, 16122, 16143, -1, 16152, 16154, 16142, -1, 16155, 16138, 16129, -1, 16156, 16143, 16124, -1, 16156, 16124, 16146, -1, 16155, 16129, 16145, -1, 16157, 15972, 16134, -1, 16158, 16159, 16135, -1, 16158, 16118, 16148, -1, 16160, 16112, 16087, -1, 16161, 16120, 16162, -1, 16158, 16133, 16118, -1, 16158, 16135, 16133, -1, 16161, 16137, 16120, -1, 15946, 16146, 16130, -1, 16160, 16087, 16139, -1, 16163, 16116, 16147, -1, 15946, 16130, 15939, -1, 16164, 16126, 16114, -1, 16163, 16139, 16116, -1, 16164, 16114, 16149, -1, 16165, 16136, 16153, -1, 16165, 16148, 16136, -1, 16165, 16158, 16148, -1, 16166, 16132, 16151, -1, 16166, 16149, 16132, -1, 16167, 16151, 16138, -1, 16168, 16153, 16143, -1, 16168, 16143, 16156, -1, 16167, 16138, 16155, -1, 16169, 16131, 16106, -1, 15985, 16146, 15946, -1, 15985, 16156, 16146, -1, 16169, 16106, 16144, -1, 16170, 16154, 16152, -1, 16171, 16159, 16158, -1, 16172, 16173, 16174, -1, 16170, 16175, 16154, -1, 16171, 16158, 16165, -1, 16176, 16153, 16168, -1, 16172, 16177, 16173, -1, 16176, 16165, 16153, -1, 16009, 16168, 16156, -1, 16178, 16125, 16150, -1, 16179, 16137, 16161, -1, 16179, 16145, 16137, -1, 16178, 16147, 16125, -1, 16009, 16156, 15985, -1, 16180, 15997, 15972, -1, 16181, 16171, 16165, -1, 16182, 16141, 16126, -1, 16181, 16165, 16176, -1, 16182, 16126, 16164, -1, 16181, 16076, 16159, -1, 16181, 16159, 16171, -1, 16180, 15972, 16157, -1, 16183, 16134, 16112, -1, 16183, 16112, 16160, -1, 16184, 16164, 16149, -1, 16034, 16176, 16168, -1, 16184, 16149, 16166, -1, 16034, 16168, 16009, -1, 16054, 16181, 16176, -1, 16054, 16176, 16034, -1, 16054, 16076, 16181, -1, 16185, 16166, 16151, -1, 16186, 16187, 16177, -1, 16185, 16151, 16167, -1, 16186, 16177, 16172, -1, 16188, 16161, 16162, -1, 16188, 16179, 16161, -1, 16189, 16160, 16139, -1, 16190, 16179, 16188, -1, 16189, 16139, 16163, -1, 16190, 16188, 16162, -1, 16191, 16155, 16145, -1, 16191, 16145, 16179, -1, 16192, 16162, 16193, -1, 16192, 16190, 16162, -1, 16194, 16195, 16175, -1, 16196, 16197, 16198, -1, 16194, 16175, 16170, -1, 16196, 16192, 16193, -1, 16196, 16193, 16197, -1, 16199, 16191, 16179, -1, 16200, 16152, 16141, -1, 16201, 16131, 16169, -1, 16199, 16179, 16190, -1, 16201, 16150, 16131, -1, 16199, 16190, 16192, -1, 16199, 16198, 16202, -1, 16200, 16141, 16182, -1, 16199, 16196, 16198, -1, 16199, 16192, 16196, -1, 16203, 16163, 16147, -1, 16204, 16205, 16206, -1, 16206, 16167, 16155, -1, 16206, 16155, 16191, -1, 16203, 16147, 16178, -1, 16204, 16207, 15933, -1, 16208, 16046, 16021, -1, 16209, 15933, 15936, -1, 16208, 16021, 15997, -1, 16209, 16210, 16205, -1, 16208, 15997, 16180, -1, 16209, 16205, 16204, -1, 16209, 16204, 15933, -1, 16211, 16164, 16184, -1, 16211, 16182, 16164, -1, 16212, 16209, 15936, -1, 16213, 16166, 16185, -1, 16212, 16210, 16209, -1, 16214, 16187, 16186, -1, 16213, 16184, 16166, -1, 16214, 16215, 16187, -1, 16216, 16195, 16194, -1, 16217, 16035, 16036, -1, 16217, 16066, 16035, -1, 16218, 16157, 16134, -1, 16216, 16219, 16195, -1, 16220, 16066, 16217, -1, 16218, 16134, 16183, -1, 16220, 16217, 16036, -1, 16221, 16160, 16189, -1, 16222, 16036, 16173, -1, 16221, 16183, 16160, -1, 16222, 16220, 16036, -1, 16223, 16177, 16187, -1, 16223, 16222, 16173, -1, 16223, 16173, 16177, -1, 16224, 16220, 16222, -1, 16225, 16170, 16152, -1, 16224, 16066, 16220, -1, 16225, 16152, 16200, -1, 16224, 16187, 16215, -1, 16224, 16223, 16187, -1, 16224, 16086, 16066, -1, 16205, 16185, 16167, -1, 16224, 16222, 16223, -1, 16205, 16167, 16206, -1, 16226, 16150, 16201, -1, 16226, 16178, 16150, -1, 16227, 16200, 16182, -1, 16228, 16229, 16230, -1, 16228, 16123, 16098, -1, 16231, 16228, 16230, -1, 16231, 16123, 16228, -1, 16232, 16189, 16163, -1, 16232, 16163, 16203, -1, 16231, 16144, 16123, -1, 16227, 16182, 16211, -1, 16231, 16230, 16233, -1, 16234, 16184, 16213, -1, 16234, 16211, 16184, -1, 16235, 16144, 16231, -1, 16236, 16219, 16216, -1, 16235, 16231, 16233, -1, 16237, 16229, 16215, -1, 16237, 16215, 16214, -1, 16238, 16239, 16064, -1, 16236, 16240, 16219, -1, 16241, 15971, 15884, -1, 16238, 16064, 16046, -1, 16241, 15884, 16242, -1, 16238, 16046, 16208, -1, 16243, 16242, 16244, -1, 16243, 16244, 16245, -1, 16246, 16174, 16247, -1, 16243, 16241, 16242, -1, 16246, 16172, 16174, -1, 16248, 16194, 16170, -1, 16248, 16170, 16225, -1, 16249, 16044, 16015, -1, 16250, 16180, 16157, -1, 16250, 16157, 16218, -1, 16251, 16070, 16044, -1, 16251, 16249, 16252, -1, 16253, 16178, 16226, -1, 16210, 16185, 16205, -1, 16251, 16252, 16254, -1, 16210, 16213, 16185, -1, 16251, 16044, 16249, -1, 16255, 16070, 16251, -1, 16253, 16203, 16178, -1, 16256, 16200, 16227, -1, 16256, 16225, 16200, -1, 16255, 16251, 16254, -1, 16257, 16206, 16191, -1, 16257, 16204, 16206, -1, 16258, 16218, 16183, -1, 16257, 16191, 16199, -1, 16258, 16183, 16221, -1, 16257, 16207, 16204, -1, 16257, 16199, 16202, -1, 16257, 16202, 16207, -1, 16259, 16227, 16211, -1, 16260, 16261, 16262, -1, 16260, 16262, 16210, -1, 16260, 16210, 16212, -1, 16259, 16211, 16234, -1, 16263, 16189, 16232, -1, 16264, 16260, 16212, -1, 16263, 16221, 16189, -1, 16265, 15936, 15999, -1, 16265, 16212, 15936, -1, 16265, 16264, 16212, -1, 16266, 16240, 16236, -1, 16265, 15999, 16026, -1, 16267, 16172, 16246, -1, 16268, 16224, 16215, -1, 16268, 16086, 16224, -1, 16268, 16228, 16098, -1, 16266, 16269, 16240, -1, 16268, 16229, 16228, -1, 16270, 16194, 16248, -1, 16268, 16098, 16086, -1, 16267, 16186, 16172, -1, 16270, 16216, 16194, -1, 16268, 16215, 16229, -1, 15901, 16229, 16237, -1, 16271, 16169, 16144, -1, 16271, 16144, 16235, -1, 16271, 16201, 16169, -1, 16272, 16248, 16225, -1, 15901, 16230, 16229, -1, 16272, 16225, 16256, -1, 16273, 16271, 16235, -1, 16274, 16246, 16247, -1, 16274, 16247, 15886, -1, 16275, 16273, 16235, -1, 16275, 16276, 15968, -1, 16275, 16233, 16276, -1, 16275, 16235, 16233, -1, 16277, 16000, 15971, -1, 16278, 16180, 16250, -1, 16277, 15971, 16241, -1, 16262, 16213, 16210, -1, 16277, 16241, 16243, -1, 16262, 16234, 16213, -1, 16279, 16000, 16277, -1, 16278, 16208, 16180, -1, 16279, 16015, 16000, -1, 15922, 16203, 16253, -1, 16279, 16249, 16015, -1, 16280, 16193, 16281, -1, 16282, 16249, 16279, -1, 15922, 16232, 16203, -1, 16282, 16279, 16277, -1, 16283, 16250, 16218, -1, 16282, 16277, 16243, -1, 16280, 16197, 16193, -1, 16284, 16256, 16227, -1, 16285, 16282, 16243, -1, 16285, 16245, 16286, -1, 16283, 16218, 16258, -1, 16284, 16227, 16259, -1, 16285, 16243, 16245, -1, 16287, 16285, 16286, -1, 16287, 16252, 16249, -1, 16287, 16288, 16252, -1, 16287, 16286, 16288, -1, 16287, 16282, 16285, -1, 16287, 16249, 16282, -1, 16289, 16290, 16269, -1, 16289, 16269, 16266, -1, 16291, 16097, 16070, -1, 16291, 16111, 16097, -1, 16292, 16216, 16270, -1, 16291, 16070, 16255, -1, 16292, 16236, 16216, -1, 16293, 16186, 16267, -1, 16294, 16291, 16255, -1, 16295, 16296, 16297, -1, 16293, 16214, 16186, -1, 16295, 16254, 16296, -1, 15908, 16198, 16197, -1, 16295, 16294, 16255, -1, 15918, 16221, 16263, -1, 16295, 16255, 16254, -1, 15908, 16197, 16280, -1, 16298, 16299, 16261, -1, 15918, 16258, 16221, -1, 16300, 16270, 16248, -1, 16298, 16261, 16260, -1, 16300, 16248, 16272, -1, 16298, 16260, 16264, -1, 16301, 16298, 16264, -1, 15900, 16233, 16230, -1, 15900, 16230, 15901, -1, 16302, 16301, 16264, -1, 16302, 16026, 16065, -1, 16261, 16234, 16262, -1, 16302, 16264, 16265, -1, 16302, 16265, 16026, -1, 16303, 16246, 16274, -1, 16304, 16271, 16273, -1, 16304, 16201, 16271, -1, 16303, 16267, 16246, -1, 16305, 16238, 16208, -1, 16261, 16259, 16234, -1, 16305, 15944, 16239, -1, 16304, 16226, 16201, -1, 16305, 16239, 16238, -1, 16306, 16272, 16256, -1, 16305, 16208, 16278, -1, 16306, 16256, 16284, -1, 15924, 16237, 16214, -1, 16307, 16304, 16273, -1, 15924, 16214, 16293, -1, 15959, 16308, 16290, -1, 16309, 16273, 16275, -1, 16309, 16275, 15968, -1, 15959, 16290, 16289, -1, 16309, 15968, 15967, -1, 16309, 16307, 16273, -1, 15885, 16274, 15886, -1, 15907, 16202, 16198, -1, 16310, 16111, 16291, -1, 16310, 16291, 16294, -1, 15907, 16198, 15908, -1, 16310, 16128, 16111, -1, 15928, 16232, 15922, -1, 15928, 16263, 16232, -1, 16311, 16310, 16294, -1, 15942, 16250, 16283, -1, 15888, 16236, 16292, -1, 15888, 16266, 16236, -1, 16312, 16297, 16313, -1, 16312, 16295, 16297, -1, 16312, 16294, 16295, -1, 16312, 16311, 16294, -1, 15927, 16292, 16270, -1, 15942, 16278, 16250, -1, 15927, 16270, 16300, -1, 16314, 16315, 16299, -1, 16314, 16298, 16301, -1, 16314, 16299, 16298, -1, 16316, 16301, 16302, -1, 16316, 16065, 16088, -1, 15921, 16283, 16258, -1, 16316, 16302, 16065, -1, 16316, 16314, 16301, -1, 15921, 16258, 15918, -1, 16299, 16284, 16259, -1, 16317, 16253, 16226, -1, 16317, 16226, 16304, -1, 16299, 16259, 16261, -1, 16317, 16304, 16307, -1, 15957, 16293, 16267, -1, 15957, 16267, 16303, -1, 16318, 15967, 16005, -1, 15976, 16300, 16272, -1, 16318, 16309, 15967, -1, 15976, 16272, 16306, -1, 16318, 16307, 16309, -1, 16318, 16317, 16307, -1, 16319, 16128, 16310, -1, 16319, 16310, 16311, -1, 15964, 16207, 16202, -1, 16319, 16140, 16128, -1, 15964, 16202, 15907, -1, 15982, 16233, 15900, -1, 15955, 15954, 16320, -1, 15891, 16313, 15894, -1, 15982, 16276, 16233, -1, 15955, 16320, 16321, -1, 15891, 16312, 16313, -1, 15955, 16321, 16308, -1, 15891, 16311, 16312, -1, 15955, 16308, 15959, -1, 15891, 16319, 16311, -1, 15977, 16274, 15885, -1, 15949, 16281, 16322, -1, 15977, 16303, 16274, -1, 15897, 15903, 16315, -1, 15897, 16315, 16314, -1, 15949, 16280, 16281, -1, 16323, 16314, 16316, -1, 15892, 16266, 15888, -1, 16323, 15897, 16314, -1, 15904, 15901, 16237, -1, 15904, 16237, 15924, -1, 15892, 16289, 16266, -1, 16315, 16306, 16284, -1, 15898, 15897, 16323, -1, 16315, 16284, 16299, -1, 15889, 15888, 16292, -1, 15905, 16323, 16316, -1, 15905, 15898, 16323, -1, 15941, 16305, 16278, -1, 15912, 16316, 16088, -1, 15941, 15944, 16305, -1, 15889, 16292, 15927, -1, 15941, 16278, 15942, -1, 15912, 15905, 16316, -1, 15912, 16088, 15910, -1, 15919, 16263, 15928, -1, 15919, 15918, 16263, -1, 15914, 16253, 16317, -1, 15914, 15922, 16253, -1, 15930, 15927, 16300, -1, 16324, 16317, 16318, -1, 16324, 15914, 16317, -1, 15925, 16293, 15957, -1, 15925, 15924, 16293, -1, 15930, 16300, 15976, -1, 15915, 15914, 16324, -1, 15920, 16280, 15949, -1, 15920, 15908, 16280, -1, 15916, 15915, 16324, -1, 15945, 15942, 16283, -1, 15945, 16283, 15921, -1, 15969, 16276, 15982, -1, 15934, 15933, 16207, -1, 15916, 16324, 16318, -1, 15931, 15916, 16318, -1, 15969, 15968, 16276, -1, 15931, 16005, 15935, -1, 15931, 16318, 16005, -1, 15934, 16207, 15964, -1, 15951, 16322, 15974, -1, 15882, 16140, 16319, -1, 15951, 15949, 16322, -1, 15882, 15939, 16140, -1, 15883, 15882, 16319, -1, 15961, 15959, 16289, -1, 15958, 15957, 16303, -1, 15883, 16319, 15891, -1, 15961, 16289, 15892, -1, 15881, 15883, 15891, -1, 15958, 16303, 15977, -1, 15903, 16306, 16315, -1, 15903, 15976, 16306, -1, 15884, 15886, 16242, -1, 16325, 16326, 16327, -1, 16328, 16329, 16330, -1, 16325, 16331, 16332, -1, 16325, 16333, 16331, -1, 16325, 16327, 16333, -1, 16334, 16335, 16336, -1, 16337, 16338, 16339, -1, 16334, 16336, 16340, -1, 16337, 16339, 16341, -1, 16337, 16342, 16338, -1, 16343, 16344, 16345, -1, 16346, 16341, 16347, -1, 16343, 16348, 16344, -1, 16346, 16337, 16341, -1, 16349, 16346, 16347, -1, 16350, 16351, 16352, -1, 16349, 16353, 16354, -1, 16349, 16347, 16353, -1, 16350, 16352, 16355, -1, 16356, 16357, 16358, -1, 16359, 16360, 16361, -1, 16359, 16362, 16360, -1, 16356, 16363, 16357, -1, 16364, 16340, 16365, -1, 16364, 16365, 16366, -1, 16367, 16345, 16368, -1, 16369, 16370, 16371, -1, 16372, 16359, 16361, -1, 16369, 16371, 16373, -1, 16374, 16361, 16375, -1, 16367, 16368, 16376, -1, 16374, 16375, 16377, -1, 16378, 16376, 16379, -1, 16374, 16372, 16361, -1, 16374, 16377, 16380, -1, 16381, 16355, 16382, -1, 16383, 16358, 16384, -1, 16383, 16384, 16326, -1, 16378, 16379, 16385, -1, 16381, 16382, 16386, -1, 16387, 16388, 16389, -1, 16387, 16390, 16391, -1, 16392, 16383, 16326, -1, 16387, 16393, 16388, -1, 16394, 16395, 16351, -1, 16387, 16389, 16390, -1, 16396, 16397, 16398, -1, 16399, 16325, 16332, -1, 16394, 16351, 16350, -1, 16399, 16332, 16400, -1, 16399, 16392, 16326, -1, 16399, 16326, 16325, -1, 16401, 16402, 16403, -1, 16404, 16342, 16337, -1, 16401, 16405, 16402, -1, 16404, 16337, 16346, -1, 16396, 16406, 16397, -1, 16401, 16407, 16405, -1, 16401, 16403, 16408, -1, 16409, 16329, 16328, -1, 16404, 16410, 16342, -1, 16411, 16386, 16412, -1, 16413, 16346, 16349, -1, 16413, 16404, 16346, -1, 16360, 16414, 16415, -1, 16416, 16349, 16354, -1, 16409, 16417, 16329, -1, 16416, 16354, 16418, -1, 16419, 16420, 16348, -1, 16416, 16413, 16349, -1, 16360, 16366, 16414, -1, 16421, 16408, 16335, -1, 16421, 16335, 16334, -1, 16422, 16423, 16362, -1, 16419, 16348, 16343, -1, 16422, 16362, 16359, -1, 16422, 16359, 16372, -1, 16424, 16380, 16425, -1, 16424, 16374, 16380, -1, 16424, 16372, 16374, -1, 16426, 16391, 16363, -1, 16424, 16422, 16372, -1, 16427, 16383, 16392, -1, 16428, 16334, 16340, -1, 16427, 16358, 16383, -1, 16428, 16340, 16364, -1, 16426, 16363, 16356, -1, 16429, 16343, 16345, -1, 16427, 16356, 16358, -1, 16430, 16350, 16355, -1, 16431, 16427, 16392, -1, 16431, 16399, 16400, -1, 16430, 16355, 16381, -1, 16431, 16392, 16399, -1, 16431, 16400, 16432, -1, 16429, 16345, 16367, -1, 16433, 16376, 16378, -1, 16434, 16410, 16404, -1, 16435, 16436, 16370, -1, 16434, 16404, 16413, -1, 16435, 16370, 16369, -1, 16433, 16367, 16376, -1, 16434, 16437, 16410, -1, 16438, 16385, 16417, -1, 16439, 16413, 16416, -1, 16439, 16434, 16413, -1, 16440, 16381, 16386, -1, 16441, 16416, 16418, -1, 16440, 16386, 16411, -1, 16438, 16417, 16409, -1, 16441, 16418, 16442, -1, 16441, 16439, 16416, -1, 16443, 16406, 16396, -1, 16444, 16373, 16395, -1, 16444, 16395, 16394, -1, 16445, 16423, 16422, -1, 16445, 16446, 16423, -1, 16443, 16447, 16406, -1, 16445, 16422, 16424, -1, 16448, 16445, 16424, -1, 16449, 16420, 16419, -1, 16450, 16425, 16451, -1, 16450, 16424, 16425, -1, 16449, 16398, 16420, -1, 16450, 16448, 16424, -1, 16362, 16364, 16366, -1, 16362, 16366, 16360, -1, 16452, 16427, 16431, -1, 16452, 16356, 16427, -1, 16453, 16394, 16350, -1, 16452, 16426, 16356, -1, 16453, 16350, 16430, -1, 16454, 16452, 16431, -1, 16455, 16385, 16438, -1, 16456, 16407, 16401, -1, 16455, 16378, 16385, -1, 16456, 16401, 16408, -1, 16457, 16387, 16391, -1, 16456, 16408, 16421, -1, 16458, 16454, 16431, -1, 16457, 16391, 16426, -1, 16458, 16431, 16432, -1, 16457, 16393, 16387, -1, 16458, 16432, 16459, -1, 16460, 16437, 16434, -1, 16461, 16421, 16334, -1, 16461, 16334, 16428, -1, 16460, 16434, 16439, -1, 16460, 16462, 16437, -1, 16463, 16419, 16343, -1, 16463, 16343, 16429, -1, 16464, 16436, 16435, -1, 16463, 16449, 16419, -1, 16464, 16465, 16436, -1, 16466, 16439, 16441, -1, 16466, 16460, 16439, -1, 16467, 16367, 16433, -1, 16468, 16381, 16440, -1, 16467, 16429, 16367, -1, 16469, 16466, 16441, -1, 16470, 16469, 16441, -1, 16468, 16430, 16381, -1, 16471, 16331, 16447, -1, 16470, 16441, 16442, -1, 16471, 16447, 16443, -1, 16472, 16412, 16473, -1, 16474, 16470, 16442, -1, 16475, 16396, 16398, -1, 16472, 16411, 16412, -1, 16474, 16476, 16477, -1, 16474, 16442, 16476, -1, 16475, 16398, 16449, -1, 16478, 16373, 16444, -1, 16479, 16445, 16448, -1, 16479, 16480, 16446, -1, 16479, 16446, 16445, -1, 16478, 16369, 16373, -1, 16481, 16451, 16482, -1, 16481, 16479, 16448, -1, 16481, 16450, 16451, -1, 16481, 16448, 16450, -1, 16483, 16457, 16426, -1, 16483, 16452, 16454, -1, 16483, 16426, 16452, -1, 16423, 16364, 16362, -1, 16484, 16483, 16454, -1, 16484, 16459, 16485, -1, 16486, 16433, 16378, -1, 16484, 16454, 16458, -1, 16484, 16458, 16459, -1, 16486, 16378, 16455, -1, 16487, 16488, 16462, -1, 16423, 16428, 16364, -1, 16489, 16394, 16453, -1, 16487, 16466, 16469, -1, 16487, 16462, 16460, -1, 16489, 16444, 16394, -1, 16487, 16460, 16466, -1, 16490, 16449, 16463, -1, 16491, 16469, 16470, -1, 16492, 16453, 16430, -1, 16491, 16474, 16477, -1, 16491, 16470, 16474, -1, 16493, 16463, 16429, -1, 16491, 16487, 16469, -1, 16493, 16429, 16467, -1, 16494, 16480, 16479, -1, 16492, 16430, 16468, -1, 16495, 16332, 16331, -1, 16496, 16456, 16421, -1, 16496, 16421, 16461, -1, 16494, 16497, 16480, -1, 16495, 16331, 16471, -1, 16496, 16497, 16407, -1, 16498, 16497, 16494, -1, 16496, 16407, 16456, -1, 16498, 16499, 16497, -1, 16500, 16465, 16464, -1, 16498, 16494, 16479, -1, 16501, 16479, 16481, -1, 16501, 16498, 16479, -1, 16501, 16499, 16498, -1, 16501, 16482, 16499, -1, 16502, 16443, 16396, -1, 16500, 16503, 16465, -1, 16501, 16481, 16482, -1, 16504, 16457, 16483, -1, 16502, 16396, 16475, -1, 16505, 16440, 16411, -1, 16504, 16393, 16457, -1, 16506, 16504, 16483, -1, 16506, 16393, 16504, -1, 16506, 16507, 16393, -1, 16505, 16411, 16472, -1, 16508, 16467, 16433, -1, 16509, 16506, 16483, -1, 16510, 16369, 16478, -1, 16509, 16507, 16506, -1, 16509, 16484, 16485, -1, 16509, 16485, 16507, -1, 16509, 16483, 16484, -1, 16508, 16433, 16486, -1, 16510, 16435, 16369, -1, 16511, 16512, 16488, -1, 16511, 16488, 16487, -1, 16513, 16475, 16449, -1, 16513, 16449, 16490, -1, 16514, 16511, 16487, -1, 16514, 16487, 16491, -1, 16446, 16428, 16423, -1, 16446, 16461, 16428, -1, 16515, 16511, 16514, -1, 16516, 16490, 16463, -1, 16515, 16514, 16491, -1, 16516, 16463, 16493, -1, 16517, 16478, 16444, -1, 16515, 16512, 16511, -1, 16517, 16444, 16489, -1, 16518, 16512, 16515, -1, 16519, 16400, 16332, -1, 16518, 16515, 16491, -1, 16518, 16520, 16512, -1, 16519, 16332, 16495, -1, 16518, 16521, 16520, -1, 16518, 16522, 16521, -1, 16523, 16489, 16453, -1, 16524, 16491, 16477, -1, 16524, 16525, 16522, -1, 16526, 16443, 16502, -1, 16524, 16477, 16525, -1, 16524, 16518, 16491, -1, 16524, 16522, 16518, -1, 16526, 16471, 16443, -1, 16523, 16453, 16492, -1, 16527, 16468, 16440, -1, 16528, 16475, 16513, -1, 16527, 16440, 16505, -1, 16528, 16526, 16502, -1, 16528, 16502, 16475, -1, 16529, 16503, 16500, -1, 16529, 16530, 16503, -1, 16531, 16532, 16533, -1, 16534, 16435, 16510, -1, 16534, 16464, 16435, -1, 16535, 16536, 16537, -1, 16535, 16537, 16538, -1, 16539, 16493, 16467, -1, 16539, 16467, 16508, -1, 16540, 16513, 16490, -1, 16541, 16542, 16536, -1, 16541, 16536, 16535, -1, 16540, 16490, 16516, -1, 16543, 16492, 16468, -1, 16544, 16400, 16519, -1, 16545, 16542, 16541, -1, 16543, 16468, 16527, -1, 16544, 16432, 16400, -1, 16545, 16546, 16542, -1, 16547, 16495, 16471, -1, 16480, 16497, 16496, -1, 16480, 16461, 16446, -1, 16480, 16496, 16461, -1, 16547, 16471, 16526, -1, 16548, 16510, 16478, -1, 16548, 16478, 16517, -1, 16549, 16517, 16489, -1, 16550, 16546, 16545, -1, 16549, 16489, 16523, -1, 16551, 16538, 16552, -1, 16553, 16526, 16528, -1, 16338, 16516, 16493, -1, 16338, 16493, 16539, -1, 16551, 16535, 16538, -1, 16554, 16530, 16529, -1, 16555, 16541, 16535, -1, 16554, 16556, 16530, -1, 16557, 16513, 16540, -1, 16555, 16535, 16551, -1, 16557, 16528, 16513, -1, 16558, 16559, 16546, -1, 16560, 16500, 16464, -1, 16561, 16432, 16544, -1, 16558, 16546, 16550, -1, 16560, 16464, 16534, -1, 16561, 16459, 16432, -1, 16562, 16552, 16563, -1, 16564, 16495, 16547, -1, 16562, 16551, 16552, -1, 16565, 16545, 16541, -1, 16564, 16519, 16495, -1, 16565, 16541, 16555, -1, 16566, 16547, 16526, -1, 16566, 16526, 16553, -1, 16567, 16568, 16569, -1, 16570, 16523, 16492, -1, 16567, 16569, 16559, -1, 16570, 16492, 16543, -1, 16571, 16534, 16510, -1, 16567, 16559, 16558, -1, 16342, 16516, 16338, -1, 16342, 16540, 16516, -1, 16571, 16510, 16548, -1, 16572, 16551, 16562, -1, 16573, 16553, 16528, -1, 16573, 16528, 16557, -1, 16572, 16555, 16551, -1, 16574, 16548, 16517, -1, 16574, 16517, 16549, -1, 16575, 16377, 16556, -1, 16576, 16577, 16507, -1, 16576, 16485, 16459, -1, 16575, 16556, 16554, -1, 16576, 16459, 16561, -1, 16576, 16507, 16485, -1, 16578, 16545, 16565, -1, 16578, 16550, 16545, -1, 16579, 16562, 16563, -1, 16580, 16519, 16564, -1, 16580, 16544, 16519, -1, 16581, 16555, 16572, -1, 16581, 16565, 16555, -1, 16582, 16529, 16500, -1, 16410, 16540, 16342, -1, 16582, 16500, 16560, -1, 16410, 16557, 16540, -1, 16583, 16564, 16547, -1, 16583, 16547, 16566, -1, 16584, 16568, 16567, -1, 16585, 16523, 16570, -1, 16586, 16572, 16562, -1, 16587, 16553, 16573, -1, 16587, 16566, 16553, -1, 16586, 16562, 16579, -1, 16585, 16549, 16523, -1, 16588, 16534, 16571, -1, 16588, 16560, 16534, -1, 16589, 16561, 16544, -1, 16590, 16550, 16578, -1, 16589, 16544, 16580, -1, 16590, 16558, 16550, -1, 16591, 16565, 16581, -1, 16437, 16573, 16557, -1, 16592, 16571, 16548, -1, 16591, 16578, 16565, -1, 16592, 16548, 16574, -1, 16437, 16557, 16410, -1, 16593, 16594, 16568, -1, 16595, 16580, 16564, -1, 16593, 16568, 16584, -1, 16595, 16564, 16583, -1, 16596, 16583, 16566, -1, 16597, 16377, 16575, -1, 16598, 16581, 16572, -1, 16596, 16566, 16587, -1, 16597, 16380, 16377, -1, 16599, 16577, 16576, -1, 16599, 16600, 16577, -1, 16598, 16572, 16586, -1, 16599, 16576, 16561, -1, 16601, 16529, 16582, -1, 16602, 16563, 16603, -1, 16599, 16561, 16589, -1, 16602, 16579, 16563, -1, 16601, 16554, 16529, -1, 16604, 16582, 16560, -1, 16462, 16573, 16437, -1, 16605, 16567, 16558, -1, 16462, 16587, 16573, -1, 16605, 16558, 16590, -1, 16604, 16560, 16588, -1, 16606, 16580, 16595, -1, 16606, 16589, 16580, -1, 16607, 16583, 16596, -1, 16608, 16578, 16591, -1, 16608, 16590, 16578, -1, 16607, 16595, 16583, -1, 16609, 16591, 16581, -1, 16609, 16581, 16598, -1, 16488, 16596, 16587, -1, 16610, 16574, 16549, -1, 16611, 16612, 16594, -1, 16610, 16549, 16585, -1, 16611, 16594, 16593, -1, 16488, 16587, 16462, -1, 16613, 16589, 16606, -1, 16613, 16600, 16599, -1, 16614, 16615, 16616, -1, 16613, 16599, 16589, -1, 16614, 16616, 16617, -1, 16618, 16595, 16607, -1, 16619, 16586, 16579, -1, 16618, 16606, 16595, -1, 16620, 16588, 16571, -1, 16512, 16596, 16488, -1, 16620, 16571, 16592, -1, 16619, 16579, 16602, -1, 16621, 16567, 16605, -1, 16622, 16425, 16380, -1, 16621, 16584, 16567, -1, 16512, 16607, 16596, -1, 16622, 16380, 16597, -1, 16623, 16600, 16613, -1, 16623, 16606, 16618, -1, 16623, 16532, 16600, -1, 16623, 16613, 16606, -1, 16624, 16575, 16554, -1, 16625, 16590, 16608, -1, 16520, 16607, 16512, -1, 16625, 16605, 16590, -1, 16520, 16618, 16607, -1, 16624, 16554, 16601, -1, 16626, 16623, 16618, -1, 16627, 16591, 16609, -1, 16626, 16532, 16623, -1, 16626, 16520, 16521, -1, 16628, 16615, 16614, -1, 16626, 16521, 16533, -1, 16626, 16618, 16520, -1, 16627, 16608, 16591, -1, 16626, 16533, 16532, -1, 16629, 16602, 16603, -1, 16630, 16598, 16586, -1, 16629, 16619, 16602, -1, 16628, 16631, 16615, -1, 16632, 16619, 16629, -1, 16633, 16582, 16604, -1, 16630, 16586, 16619, -1, 16632, 16629, 16603, -1, 16633, 16601, 16582, -1, 16634, 16612, 16611, -1, 16635, 16603, 16636, -1, 16635, 16632, 16603, -1, 16637, 16638, 16639, -1, 16637, 16636, 16638, -1, 16634, 16640, 16612, -1, 16637, 16635, 16636, -1, 16641, 16630, 16619, -1, 16641, 16632, 16635, -1, 16642, 16574, 16610, -1, 16641, 16637, 16639, -1, 16642, 16592, 16574, -1, 16641, 16635, 16637, -1, 16643, 16584, 16621, -1, 16641, 16639, 16644, -1, 16643, 16593, 16584, -1, 16641, 16619, 16632, -1, 16645, 16604, 16588, -1, 16646, 16598, 16630, -1, 16647, 16648, 16646, -1, 16645, 16588, 16620, -1, 16646, 16609, 16598, -1, 16647, 16649, 16371, -1, 16650, 16371, 16370, -1, 16651, 16451, 16425, -1, 16650, 16652, 16648, -1, 16651, 16425, 16622, -1, 16653, 16605, 16625, -1, 16650, 16647, 16371, -1, 16653, 16621, 16605, -1, 16650, 16648, 16647, -1, 16654, 16608, 16627, -1, 16655, 16650, 16370, -1, 16655, 16652, 16650, -1, 16654, 16625, 16608, -1, 16656, 16472, 16473, -1, 16657, 16640, 16634, -1, 16658, 16659, 16631, -1, 16656, 16505, 16472, -1, 16658, 16631, 16628, -1, 16657, 16660, 16640, -1, 16661, 16656, 16473, -1, 16662, 16597, 16575, -1, 16661, 16505, 16656, -1, 16662, 16575, 16624, -1, 16663, 16473, 16616, -1, 16663, 16661, 16473, -1, 16664, 16624, 16601, -1, 16664, 16601, 16633, -1, 16665, 16616, 16615, -1, 16665, 16663, 16616, -1, 16666, 16593, 16643, -1, 16665, 16615, 16631, -1, 16667, 16527, 16505, -1, 16667, 16631, 16659, -1, 16666, 16611, 16593, -1, 16667, 16661, 16663, -1, 16667, 16663, 16665, -1, 16667, 16665, 16631, -1, 16648, 16609, 16646, -1, 16667, 16505, 16661, -1, 16668, 16620, 16592, -1, 16668, 16592, 16642, -1, 16669, 16670, 16671, -1, 16648, 16627, 16609, -1, 16672, 16621, 16653, -1, 16669, 16570, 16543, -1, 16673, 16671, 16674, -1, 16673, 16585, 16570, -1, 16675, 16633, 16604, -1, 16675, 16604, 16645, -1, 16672, 16643, 16621, -1, 16673, 16669, 16671, -1, 16676, 16625, 16654, -1, 16673, 16570, 16669, -1, 16676, 16672, 16653, -1, 16677, 16670, 16659, -1, 16676, 16653, 16625, -1, 16678, 16585, 16673, -1, 16679, 16660, 16657, -1, 16678, 16673, 16674, -1, 16680, 16409, 16328, -1, 16677, 16659, 16658, -1, 16681, 16482, 16451, -1, 16680, 16328, 16682, -1, 16681, 16683, 16499, -1, 16679, 16684, 16660, -1, 16681, 16499, 16482, -1, 16681, 16451, 16651, -1, 16685, 16617, 16686, -1, 16687, 16409, 16680, -1, 16685, 16614, 16617, -1, 16687, 16680, 16682, -1, 16688, 16682, 16689, -1, 16688, 16687, 16682, -1, 16690, 16691, 16692, -1, 16690, 16689, 16691, -1, 16693, 16622, 16597, -1, 16694, 16611, 16666, -1, 16690, 16688, 16689, -1, 16694, 16634, 16611, -1, 16695, 16438, 16409, -1, 16693, 16597, 16662, -1, 16652, 16627, 16648, -1, 16695, 16409, 16687, -1, 16695, 16687, 16688, -1, 16695, 16690, 16692, -1, 16695, 16688, 16690, -1, 16696, 16620, 16668, -1, 16652, 16654, 16627, -1, 16697, 16666, 16643, -1, 16698, 16646, 16630, -1, 16696, 16645, 16620, -1, 16698, 16630, 16641, -1, 16697, 16643, 16672, -1, 16698, 16641, 16644, -1, 16698, 16649, 16647, -1, 16698, 16647, 16646, -1, 16698, 16644, 16649, -1, 16699, 16652, 16655, -1, 16700, 16662, 16624, -1, 16699, 16701, 16652, -1, 16700, 16624, 16664, -1, 16702, 16672, 16676, -1, 16699, 16703, 16701, -1, 16704, 16699, 16655, -1, 16705, 16370, 16436, -1, 16705, 16655, 16370, -1, 16706, 16633, 16675, -1, 16705, 16436, 16465, -1, 16707, 16684, 16679, -1, 16705, 16704, 16655, -1, 16708, 16659, 16670, -1, 16708, 16527, 16667, -1, 16706, 16664, 16633, -1, 16708, 16667, 16659, -1, 16708, 16670, 16669, -1, 16707, 16709, 16684, -1, 16708, 16669, 16543, -1, 16708, 16543, 16527, -1, 16710, 16657, 16634, -1, 16711, 16610, 16585, -1, 16712, 16614, 16685, -1, 16711, 16585, 16678, -1, 16710, 16634, 16694, -1, 16711, 16642, 16610, -1, 16712, 16628, 16614, -1, 16713, 16711, 16678, -1, 16714, 16666, 16697, -1, 16714, 16694, 16666, -1, 16344, 16671, 16670, -1, 16715, 16674, 16716, -1, 16715, 16716, 16397, -1, 16344, 16670, 16677, -1, 16715, 16678, 16674, -1, 16717, 16686, 16330, -1, 16715, 16713, 16678, -1, 16718, 16455, 16438, -1, 16717, 16685, 16686, -1, 16718, 16486, 16455, -1, 16719, 16718, 16438, -1, 16701, 16676, 16654, -1, 16720, 16651, 16622, -1, 16719, 16438, 16695, -1, 16720, 16622, 16693, -1, 16701, 16654, 16652, -1, 16721, 16719, 16695, -1, 16722, 16675, 16645, -1, 16723, 16636, 16724, -1, 16722, 16645, 16696, -1, 16723, 16638, 16636, -1, 16725, 16726, 16721, -1, 16725, 16692, 16727, -1, 16728, 16693, 16662, -1, 16725, 16727, 16726, -1, 16729, 16697, 16672, -1, 16725, 16721, 16695, -1, 16725, 16695, 16692, -1, 16729, 16672, 16702, -1, 16730, 16699, 16704, -1, 16728, 16662, 16700, -1, 16730, 16703, 16699, -1, 16730, 16731, 16703, -1, 16732, 16730, 16704, -1, 16733, 16734, 16709, -1, 16733, 16709, 16707, -1, 16735, 16657, 16710, -1, 16735, 16679, 16657, -1, 16736, 16465, 16503, -1, 16737, 16628, 16712, -1, 16736, 16732, 16704, -1, 16736, 16705, 16465, -1, 16736, 16704, 16705, -1, 16738, 16668, 16642, -1, 16352, 16639, 16638, -1, 16352, 16638, 16723, -1, 16738, 16642, 16711, -1, 16738, 16711, 16713, -1, 16737, 16658, 16628, -1, 16357, 16700, 16664, -1, 16357, 16664, 16706, -1, 16739, 16710, 16694, -1, 16348, 16671, 16344, -1, 16739, 16694, 16714, -1, 16740, 16738, 16713, -1, 16348, 16674, 16671, -1, 16741, 16715, 16397, -1, 16741, 16740, 16713, -1, 16741, 16397, 16406, -1, 16741, 16713, 16715, -1, 16742, 16718, 16719, -1, 16742, 16508, 16486, -1, 16742, 16486, 16718, -1, 16743, 16712, 16685, -1, 16703, 16702, 16676, -1, 16743, 16685, 16717, -1, 16703, 16676, 16701, -1, 16744, 16742, 16719, -1, 16744, 16719, 16721, -1, 16745, 16714, 16697, -1, 16746, 16721, 16726, -1, 16745, 16697, 16729, -1, 16746, 16726, 16747, -1, 16368, 16677, 16658, -1, 16745, 16739, 16714, -1, 16746, 16744, 16721, -1, 16368, 16658, 16737, -1, 16748, 16731, 16730, -1, 16749, 16683, 16681, -1, 16403, 16750, 16734, -1, 16748, 16751, 16731, -1, 16749, 16681, 16651, -1, 16749, 16388, 16683, -1, 16748, 16730, 16732, -1, 16403, 16734, 16733, -1, 16752, 16732, 16736, -1, 16752, 16736, 16503, -1, 16749, 16651, 16720, -1, 16351, 16644, 16639, -1, 16752, 16503, 16530, -1, 16351, 16639, 16352, -1, 16752, 16748, 16732, -1, 16753, 16668, 16738, -1, 16753, 16738, 16740, -1, 16329, 16717, 16330, -1, 16384, 16706, 16675, -1, 16384, 16675, 16722, -1, 16336, 16707, 16679, -1, 16753, 16696, 16668, -1, 16754, 16741, 16406, -1, 16754, 16740, 16741, -1, 16754, 16753, 16740, -1, 16336, 16679, 16735, -1, 16390, 16720, 16693, -1, 16754, 16406, 16447, -1, 16755, 16742, 16744, -1, 16365, 16735, 16710, -1, 16755, 16539, 16508, -1, 16365, 16710, 16739, -1, 16755, 16508, 16742, -1, 16390, 16693, 16728, -1, 16756, 16755, 16744, -1, 16731, 16702, 16703, -1, 16756, 16744, 16746, -1, 16363, 16728, 16700, -1, 16757, 16747, 16758, -1, 16363, 16700, 16357, -1, 16757, 16746, 16747, -1, 16731, 16729, 16702, -1, 16757, 16756, 16746, -1, 16379, 16737, 16712, -1, 16759, 16415, 16751, -1, 16759, 16751, 16748, -1, 16379, 16712, 16743, -1, 16414, 16739, 16745, -1, 16760, 16748, 16752, -1, 16760, 16759, 16748, -1, 16420, 16716, 16674, -1, 16395, 16644, 16351, -1, 16420, 16674, 16348, -1, 16395, 16649, 16644, -1, 16402, 16750, 16403, -1, 16761, 16760, 16752, -1, 16402, 16405, 16762, -1, 16761, 16759, 16760, -1, 16402, 16762, 16763, -1, 16402, 16763, 16750, -1, 16417, 16743, 16717, -1, 16382, 16724, 16764, -1, 16765, 16761, 16752, -1, 16417, 16717, 16329, -1, 16382, 16723, 16724, -1, 16766, 16765, 16752, -1, 16766, 16752, 16530, -1, 16766, 16530, 16556, -1, 16345, 16344, 16677, -1, 16767, 16722, 16696, -1, 16345, 16677, 16368, -1, 16767, 16696, 16753, -1, 16335, 16707, 16336, -1, 16335, 16733, 16707, -1, 16768, 16753, 16754, -1, 16768, 16767, 16753, -1, 16751, 16729, 16731, -1, 16751, 16745, 16729, -1, 16340, 16336, 16735, -1, 16769, 16768, 16754, -1, 16769, 16767, 16768, -1, 16340, 16735, 16365, -1, 16358, 16357, 16706, -1, 16358, 16706, 16384, -1, 16327, 16769, 16754, -1, 16333, 16447, 16331, -1, 16333, 16754, 16447, -1, 16333, 16327, 16754, -1, 16376, 16737, 16379, -1, 16366, 16365, 16739, -1, 16339, 16539, 16755, -1, 16376, 16368, 16737, -1, 16366, 16739, 16414, -1, 16339, 16755, 16756, -1, 16389, 16720, 16390, -1, 16339, 16338, 16539, -1, 16389, 16388, 16749, -1, 16389, 16749, 16720, -1, 16341, 16339, 16756, -1, 16355, 16352, 16723, -1, 16341, 16756, 16757, -1, 16391, 16728, 16363, -1, 16347, 16341, 16757, -1, 16347, 16758, 16353, -1, 16391, 16390, 16728, -1, 16355, 16723, 16382, -1, 16347, 16757, 16758, -1, 16373, 16649, 16395, -1, 16361, 16360, 16415, -1, 16398, 16397, 16716, -1, 16373, 16371, 16649, -1, 16361, 16415, 16759, -1, 16398, 16716, 16420, -1, 16361, 16759, 16761, -1, 16361, 16761, 16765, -1, 16386, 16764, 16412, -1, 16386, 16382, 16764, -1, 16375, 16556, 16377, -1, 16375, 16766, 16556, -1, 16408, 16403, 16733, -1, 16375, 16361, 16765, -1, 16408, 16733, 16335, -1, 16375, 16765, 16766, -1, 16326, 16384, 16722, -1, 16385, 16379, 16743, -1, 16385, 16743, 16417, -1, 16415, 16414, 16745, -1, 16326, 16722, 16767, -1, 16415, 16745, 16751, -1, 16326, 16767, 16769, -1, 16328, 16330, 16682, -1, 16326, 16769, 16327, -1, 16770, 16771, 16772, -1, 16772, 16771, 16773, -1, 16773, 16774, 16775, -1, 16771, 16774, 16773, -1, 16775, 16776, 16777, -1, 16774, 16776, 16775, -1, 16777, 16778, 16779, -1, 16776, 16778, 16777, -1, 16779, 16780, 16781, -1, 16778, 16780, 16779, -1, 16781, 16782, 16783, -1, 16780, 16782, 16781, -1, 16783, 16784, 16785, -1, 16782, 16784, 16783, -1, 16786, 16787, 16788, -1, 16788, 16787, 16789, -1, 16789, 16790, 16791, -1, 16787, 16790, 16789, -1, 16791, 16792, 16793, -1, 16790, 16792, 16791, -1, 16793, 16794, 16795, -1, 16792, 16794, 16793, -1, 16795, 16796, 16797, -1, 16794, 16796, 16795, -1, 16797, 16798, 16799, -1, 16796, 16798, 16797, -1, 16799, 16800, 16801, -1, 16798, 16800, 16799, -1, 16802, 16803, 16804, -1, 16804, 16803, 16805, -1, 16805, 16806, 16807, -1, 16803, 16806, 16805, -1, 16807, 16808, 16809, -1, 16806, 16808, 16807, -1, 16809, 16810, 16811, -1, 16808, 16810, 16809, -1, 16811, 16812, 16813, -1, 16810, 16812, 16811, -1, 16813, 16814, 16815, -1, 16812, 16814, 16813, -1, 16815, 16816, 16817, -1, 16814, 16816, 16815, -1, 16818, 16819, 16820, -1, 16820, 16819, 16821, -1, 16821, 16822, 16823, -1, 16819, 16822, 16821, -1, 16823, 16824, 16825, -1, 16822, 16824, 16823, -1, 16825, 16826, 16827, -1, 16824, 16826, 16825, -1, 16827, 16828, 16829, -1, 16826, 16828, 16827, -1, 16829, 16830, 16831, -1, 16828, 16830, 16829, -1, 16831, 16832, 16833, -1, 16830, 16832, 16831, -1, 16834, 16835, 16836, -1, 16837, 16836, 16838, -1, 16837, 16834, 16836, -1, 16839, 16838, 16531, -1, 16839, 16837, 16838, -1, 16320, 16531, 16533, -1, 16320, 16839, 16531, -1, 16321, 16533, 16521, -1, 16321, 16320, 16533, -1, 16308, 16521, 16522, -1, 16308, 16321, 16521, -1, 16290, 16522, 16525, -1, 16290, 16308, 16522, -1, 16269, 16525, 16477, -1, 16269, 16290, 16525, -1, 16240, 16477, 16476, -1, 16240, 16269, 16477, -1, 16219, 16476, 16442, -1, 16219, 16240, 16476, -1, 16195, 16442, 16418, -1, 16195, 16219, 16442, -1, 16175, 16418, 16354, -1, 16175, 16195, 16418, -1, 16154, 16354, 16353, -1, 16154, 16175, 16354, -1, 16142, 16353, 16758, -1, 16142, 16154, 16353, -1, 16127, 16758, 16747, -1, 16127, 16142, 16758, -1, 16117, 16747, 16726, -1, 16117, 16127, 16747, -1, 16108, 16117, 16726, -1, 16101, 16108, 16726, -1, 16101, 16726, 16727, -1, 16840, 16841, 16842, -1, 16843, 16842, 16844, -1, 16843, 16840, 16842, -1, 16845, 16844, 16846, -1, 16845, 16843, 16844, -1, 16847, 16846, 16848, -1, 16847, 16845, 16846, -1, 16849, 16850, 16851, -1, 16849, 16848, 16850, -1, 16849, 16847, 16848, -1, 16852, 16851, 16853, -1, 16852, 16849, 16851, -1, 16854, 16853, 16855, -1, 16854, 16852, 16853, -1, 16856, 16855, 16857, -1, 16856, 16854, 16855, -1, 16762, 16857, 16858, -1, 16762, 16856, 16857, -1, 16763, 16858, 16859, -1, 16763, 16762, 16858, -1, 16750, 16859, 16860, -1, 16750, 16763, 16859, -1, 16734, 16860, 16861, -1, 16734, 16750, 16860, -1, 16709, 16861, 16862, -1, 16709, 16734, 16861, -1, 16684, 16862, 16863, -1, 16684, 16709, 16862, -1, 16660, 16863, 16864, -1, 16660, 16684, 16863, -1, 16640, 16660, 16864, -1, 16640, 16864, 16865, -1, 16612, 16865, 16866, -1, 16612, 16640, 16865, -1, 16867, 16313, 16297, -1, 16867, 16868, 16313, -1, 16869, 16297, 16296, -1, 16869, 16867, 16297, -1, 16870, 16296, 16254, -1, 16870, 16869, 16296, -1, 16871, 16254, 16252, -1, 16871, 16870, 16254, -1, 16872, 16871, 16252, -1, 16873, 16252, 16288, -1, 16873, 16872, 16252, -1, 16874, 16288, 16286, -1, 16874, 16873, 16288, -1, 16875, 16286, 16245, -1, 16875, 16874, 16286, -1, 16876, 16245, 16244, -1, 16876, 16875, 16245, -1, 16877, 16244, 16878, -1, 16877, 16876, 16244, -1, 16879, 16878, 16880, -1, 16879, 16877, 16878, -1, 16881, 16880, 16882, -1, 16881, 16879, 16880, -1, 16883, 16882, 16884, -1, 16883, 16881, 16882, -1, 16885, 16884, 16886, -1, 16885, 16883, 16884, -1, 16887, 16886, 16888, -1, 16887, 16885, 16886, -1, 16889, 16888, 16890, -1, 16889, 16887, 16888, -1, 16891, 16889, 16890, -1, 16891, 16890, 16892, -1, 16893, 16891, 16892, -1, 16894, 16893, 16892, -1, 16894, 16892, 16895, -1, 16896, 16895, 16897, -1, 16896, 16894, 16895, -1, 16898, 16897, 16899, -1, 16898, 16896, 16897, -1, 16900, 16899, 16901, -1, 16900, 16898, 16899, -1, 16902, 16900, 16901, -1, 16903, 16901, 16904, -1, 16903, 16902, 16901, -1, 16905, 16904, 16906, -1, 16905, 16903, 16904, -1, 16907, 16906, 16908, -1, 16907, 16905, 16906, -1, 16909, 16908, 16079, -1, 16909, 16907, 16908, -1, 16910, 16079, 16059, -1, 16910, 16909, 16079, -1, 16911, 16059, 16041, -1, 16911, 16910, 16059, -1, 16912, 16041, 16012, -1, 16912, 16911, 16041, -1, 16913, 16012, 15990, -1, 16913, 16912, 16012, -1, 16914, 15990, 15950, -1, 16914, 16913, 15990, -1, 16915, 15950, 15895, -1, 16915, 16914, 15950, -1, 16916, 15895, 15894, -1, 16916, 16915, 15895, -1, 16917, 16916, 15894, -1, 16917, 15894, 16313, -1, 16868, 16917, 16313, -1, 16612, 16866, 16918, -1, 16594, 16918, 16919, -1, 16594, 16612, 16918, -1, 16568, 16919, 16920, -1, 16568, 16594, 16919, -1, 16569, 16920, 16921, -1, 16569, 16568, 16920, -1, 16559, 16922, 16923, -1, 16559, 16921, 16922, -1, 16559, 16569, 16921, -1, 16546, 16923, 16924, -1, 16546, 16559, 16923, -1, 16542, 16924, 16925, -1, 16542, 16546, 16924, -1, 16536, 16925, 16926, -1, 16536, 16542, 16925, -1, 16537, 16926, 16927, -1, 16537, 16536, 16926, -1, 16928, 16927, 16929, -1, 16928, 16537, 16927, -1, 16930, 16929, 16931, -1, 16930, 16928, 16929, -1, 16932, 16931, 16933, -1, 16932, 16930, 16931, -1, 16934, 16933, 16935, -1, 16934, 16932, 16933, -1, 16936, 16935, 16937, -1, 16936, 16934, 16935, -1, 16938, 16937, 16939, -1, 16938, 16936, 16937, -1, 16940, 16939, 16941, -1, 16940, 16938, 16939, -1, 16840, 16941, 16841, -1, 16840, 16940, 16941, -1, 16942, 16943, 16944, -1, 16942, 16944, 16945, -1, 16942, 16946, 16943, -1, 16947, 16942, 16945, -1, 16948, 16949, 16950, -1, 16947, 16946, 16942, -1, 16951, 16952, 16953, -1, 16954, 16955, 16956, -1, 16951, 16953, 16946, -1, 16954, 16957, 16955, -1, 16951, 16946, 16947, -1, 16958, 16959, 16960, -1, 16961, 16962, 16532, -1, 16963, 16950, 16964, -1, 16961, 16532, 16531, -1, 16963, 16964, 16965, -1, 16958, 16966, 16959, -1, 16958, 16967, 16966, -1, 16961, 16531, 16838, -1, 16968, 16967, 16958, -1, 16969, 16970, 16971, -1, 16972, 16973, 16974, -1, 16969, 16971, 16975, -1, 16976, 16977, 16978, -1, 16979, 16967, 16968, -1, 16979, 16980, 16981, -1, 16979, 16981, 16982, -1, 16979, 16982, 16967, -1, 16972, 16983, 16973, -1, 16976, 16978, 16984, -1, 16985, 16986, 16987, -1, 16985, 16988, 16986, -1, 16989, 16974, 16990, -1, 16985, 16991, 16988, -1, 16985, 16987, 16992, -1, 16993, 16991, 16985, -1, 16989, 16990, 16994, -1, 16995, 16965, 16996, -1, 16993, 16997, 16998, -1, 16999, 17000, 17001, -1, 16995, 16996, 17002, -1, 16993, 17003, 16997, -1, 16993, 16998, 16991, -1, 17004, 16945, 16944, -1, 16999, 17005, 17006, -1, 17007, 17003, 17008, -1, 17004, 16947, 16945, -1, 16999, 17006, 17000, -1, 17007, 17008, 17009, -1, 17004, 17010, 17011, -1, 17004, 16944, 17010, -1, 17012, 16951, 16947, -1, 17013, 16984, 17014, -1, 17012, 16952, 16951, -1, 17012, 16947, 17004, -1, 17012, 17015, 16952, -1, 17016, 16957, 16954, -1, 17013, 17014, 17017, -1, 17018, 16960, 17019, -1, 17018, 16958, 16960, -1, 17018, 16968, 16958, -1, 17020, 16977, 16976, -1, 17021, 16992, 17022, -1, 17016, 16994, 16957, -1, 17023, 17024, 17025, -1, 17020, 17026, 16977, -1, 17021, 16985, 16992, -1, 17027, 16552, 16538, -1, 17023, 16412, 17024, -1, 17023, 17025, 17005, -1, 17027, 16538, 17028, -1, 17027, 17028, 17029, -1, 17027, 17029, 16948, -1, 17030, 16985, 17021, -1, 17031, 16388, 16393, -1, 17032, 17008, 17003, -1, 17031, 17017, 16388, -1, 17032, 17003, 16993, -1, 17033, 16953, 17034, -1, 17032, 16985, 17030, -1, 17032, 16993, 16985, -1, 17033, 17035, 16953, -1, 17036, 16950, 16963, -1, 17037, 17004, 17011, -1, 17036, 16948, 16950, -1, 17038, 16961, 16838, -1, 17038, 16838, 16836, -1, 17037, 17011, 17039, -1, 17040, 17004, 17037, -1, 17038, 16956, 16962, -1, 17038, 16962, 16961, -1, 17041, 16995, 17002, -1, 17041, 17002, 16970, -1, 17041, 16970, 16969, -1, 17042, 17043, 16983, -1, 17044, 17012, 17004, -1, 17042, 16983, 16972, -1, 17044, 17015, 17012, -1, 17044, 17004, 17040, -1, 17044, 17045, 17015, -1, 17046, 17018, 17019, -1, 17047, 16972, 16974, -1, 17046, 17019, 17048, -1, 17049, 16963, 16965, -1, 17049, 16965, 16995, -1, 17050, 17018, 17046, -1, 17047, 16974, 16989, -1, 17051, 16984, 17013, -1, 17052, 17005, 16999, -1, 17051, 16976, 16984, -1, 17053, 17022, 17054, -1, 17053, 17021, 17022, -1, 17053, 17030, 17021, -1, 17055, 17003, 17007, -1, 17053, 17054, 17056, -1, 17057, 17058, 17008, -1, 17057, 17032, 17030, -1, 17057, 17056, 17059, -1, 17060, 16994, 17016, -1, 17055, 16997, 17003, -1, 17057, 17008, 17032, -1, 17057, 17030, 17053, -1, 17057, 17053, 17056, -1, 17057, 17059, 17058, -1, 17061, 17040, 17037, -1, 17060, 16989, 16994, -1, 17062, 17013, 17017, -1, 17061, 17037, 17039, -1, 17062, 17017, 17031, -1, 17063, 17038, 16836, -1, 17063, 16956, 17038, -1, 17061, 17039, 17064, -1, 17063, 16836, 16835, -1, 17061, 17064, 17065, -1, 17066, 17065, 17067, -1, 17066, 17068, 17045, -1, 17069, 17009, 17026, -1, 17066, 17067, 17068, -1, 17063, 16954, 16956, -1, 17066, 17061, 17065, -1, 17066, 17040, 17061, -1, 17066, 17044, 17040, -1, 17069, 17026, 17020, -1, 17066, 17045, 17044, -1, 17070, 17048, 17071, -1, 17070, 17046, 17048, -1, 17072, 17020, 16976, -1, 17073, 17074, 17035, -1, 17070, 17050, 17046, -1, 17075, 16979, 16968, -1, 17073, 17035, 17033, -1, 17075, 16980, 16979, -1, 17072, 16976, 17051, -1, 17075, 17018, 17050, -1, 17076, 16563, 16552, -1, 17075, 16968, 17018, -1, 17076, 16552, 17027, -1, 17075, 17077, 16980, -1, 17075, 17050, 17078, -1, 17079, 17043, 17042, -1, 17076, 16948, 17036, -1, 17075, 17078, 17077, -1, 17076, 17027, 16948, -1, 17080, 17071, 17081, -1, 17082, 16995, 17041, -1, 17080, 17070, 17071, -1, 17079, 17034, 17043, -1, 17083, 17042, 16972, -1, 17084, 17085, 17080, -1, 17084, 17081, 17086, -1, 17083, 16972, 17047, -1, 17084, 17087, 17085, -1, 17084, 17086, 17088, -1, 17084, 17088, 17087, -1, 17084, 17080, 17081, -1, 17089, 17050, 17070, -1, 17086, 16835, 17088, -1, 17090, 17036, 16963, -1, 17089, 17070, 17080, -1, 17086, 16954, 17063, -1, 17086, 17016, 16954, -1, 17086, 17063, 16835, -1, 17090, 16963, 17049, -1, 17091, 16473, 16412, -1, 17092, 16997, 17055, -1, 17093, 17089, 17080, -1, 17091, 16412, 17023, -1, 17094, 17078, 17050, -1, 17091, 17023, 17005, -1, 17092, 17095, 16997, -1, 17094, 17050, 17089, -1, 17091, 17005, 17052, -1, 17094, 17089, 17093, -1, 17096, 17080, 17085, -1, 17096, 17097, 17077, -1, 17096, 17085, 17097, -1, 17098, 17013, 17062, -1, 17096, 17077, 17078, -1, 17096, 17093, 17080, -1, 17096, 17078, 17094, -1, 17096, 17094, 17093, -1, 17099, 16989, 17060, -1, 17098, 17051, 17013, -1, 17099, 17047, 16989, -1, 17100, 17031, 16393, -1, 17101, 17009, 17069, -1, 17102, 17074, 17073, -1, 17102, 17103, 17074, -1, 17101, 17007, 17009, -1, 17104, 17020, 17072, -1, 17105, 17033, 17034, -1, 17105, 17034, 17079, -1, 17104, 17069, 17020, -1, 17106, 16995, 17082, -1, 17106, 17090, 17049, -1, 17107, 17042, 17083, -1, 17106, 17049, 16995, -1, 17107, 17079, 17042, -1, 17081, 17060, 17016, -1, 17108, 17072, 17051, -1, 17081, 17016, 17086, -1, 17108, 17051, 17098, -1, 17109, 17076, 17036, -1, 17110, 17083, 17047, -1, 17109, 17036, 17090, -1, 17109, 16563, 17076, -1, 17110, 17047, 17099, -1, 17111, 17095, 17092, -1, 17111, 17112, 17095, -1, 17113, 17062, 17031, -1, 17114, 17115, 17103, -1, 17114, 17103, 17102, -1, 17113, 17031, 17100, -1, 17116, 17033, 17105, -1, 17116, 17073, 17033, -1, 17117, 17007, 17101, -1, 17117, 17055, 17007, -1, 17071, 17099, 17060, -1, 17071, 17060, 17081, -1, 17118, 17069, 17104, -1, 17118, 17101, 17069, -1, 17119, 17090, 17106, -1, 17120, 17105, 17079, -1, 17120, 17079, 17107, -1, 17121, 17072, 17108, -1, 17122, 17107, 17083, -1, 17122, 17083, 17110, -1, 17121, 17104, 17072, -1, 17123, 17115, 17114, -1, 17065, 17062, 17113, -1, 17124, 16856, 16762, -1, 17123, 17125, 17115, -1, 17124, 16762, 16405, -1, 17065, 17098, 17062, -1, 17126, 16856, 17124, -1, 17127, 17073, 17116, -1, 17128, 17112, 17111, -1, 17128, 17129, 17112, -1, 17127, 17102, 17073, -1, 17126, 16854, 16856, -1, 17130, 17092, 17055, -1, 17131, 16854, 17126, -1, 17048, 17099, 17071, -1, 17131, 16852, 16854, -1, 17130, 17055, 17117, -1, 17048, 17110, 17099, -1, 17132, 17117, 17101, -1, 17132, 17101, 17118, -1, 17133, 17105, 17120, -1, 17064, 17108, 17098, -1, 17134, 16849, 16852, -1, 17134, 16852, 17131, -1, 17133, 17116, 17105, -1, 17064, 17098, 17065, -1, 17135, 17124, 16405, -1, 17135, 16405, 16407, -1, 17136, 16603, 16563, -1, 17137, 17120, 17107, -1, 17137, 17107, 17122, -1, 17136, 17109, 17090, -1, 17136, 17090, 17119, -1, 17136, 16563, 17109, -1, 17138, 17124, 17135, -1, 17139, 17125, 17123, -1, 17138, 17126, 17124, -1, 17139, 17140, 17125, -1, 17141, 17118, 17104, -1, 17142, 16849, 17134, -1, 17141, 17104, 17121, -1, 17143, 17102, 17127, -1, 17143, 17114, 17102, -1, 17019, 17122, 17110, -1, 17144, 17145, 17129, -1, 17019, 17110, 17048, -1, 17146, 17135, 16407, -1, 17144, 17129, 17128, -1, 17147, 17126, 17138, -1, 17148, 17100, 16393, -1, 17148, 16393, 16507, -1, 17149, 17116, 17133, -1, 17147, 17131, 17126, -1, 17150, 17092, 17130, -1, 17150, 17111, 17092, -1, 17149, 17127, 17116, -1, 17151, 16845, 16847, -1, 17152, 17120, 17137, -1, 17151, 16847, 16849, -1, 17151, 16849, 17142, -1, 17153, 17117, 17132, -1, 17152, 17133, 17120, -1, 17153, 17130, 17117, -1, 17154, 17135, 17146, -1, 17154, 17138, 17135, -1, 17155, 17140, 17139, -1, 17155, 17156, 17140, -1, 17157, 17134, 17131, -1, 17158, 17123, 17114, -1, 17039, 17121, 17108, -1, 17039, 17108, 17064, -1, 17157, 17131, 17147, -1, 17158, 17114, 17143, -1, 17159, 16407, 16497, -1, 17159, 17146, 16407, -1, 17160, 17143, 17127, -1, 17160, 17127, 17149, -1, 17161, 17118, 17141, -1, 17161, 17132, 17118, -1, 16960, 17137, 17122, -1, 17162, 17138, 17154, -1, 16960, 17122, 17019, -1, 17162, 17147, 17138, -1, 17163, 17164, 17145, -1, 17163, 17165, 17164, -1, 17163, 17145, 17144, -1, 17166, 17133, 17152, -1, 17167, 17113, 17100, -1, 17168, 16845, 17151, -1, 17166, 17160, 17149, -1, 17167, 17100, 17148, -1, 17169, 17146, 17159, -1, 17166, 17149, 17133, -1, 17170, 16617, 16616, -1, 17170, 17171, 17156, -1, 17169, 17154, 17146, -1, 17170, 17156, 17155, -1, 17170, 16616, 17171, -1, 17172, 17142, 17134, -1, 17173, 17139, 17123, -1, 17172, 17134, 17157, -1, 17174, 17128, 17111, -1, 17173, 17123, 17158, -1, 17174, 17111, 17150, -1, 17011, 17121, 17039, -1, 17175, 17143, 17160, -1, 17176, 17157, 17147, -1, 17175, 17158, 17143, -1, 17011, 17141, 17121, -1, 17176, 17147, 17162, -1, 17177, 16845, 17168, -1, 16959, 17137, 16960, -1, 17177, 16840, 16843, -1, 17177, 16843, 16845, -1, 16959, 17152, 17137, -1, 17178, 17150, 17130, -1, 17179, 17162, 17154, -1, 17178, 17130, 17153, -1, 17180, 17175, 17160, -1, 17181, 17132, 17161, -1, 17179, 17154, 17169, -1, 17180, 17160, 17166, -1, 17181, 17153, 17132, -1, 17182, 17159, 16497, -1, 17183, 17139, 17173, -1, 17183, 17155, 17139, -1, 17067, 17113, 17167, -1, 17184, 17173, 17158, -1, 17184, 17158, 17175, -1, 17185, 17142, 17172, -1, 17067, 17065, 17113, -1, 17185, 17151, 17142, -1, 17186, 17166, 17152, -1, 17187, 17157, 17176, -1, 17188, 17165, 17163, -1, 17187, 17172, 17157, -1, 17186, 17152, 16959, -1, 17189, 17176, 17162, -1, 17190, 17175, 17180, -1, 17191, 17128, 17174, -1, 17189, 17162, 17179, -1, 17192, 16686, 16617, -1, 17191, 17144, 17128, -1, 17192, 16617, 17170, -1, 17192, 17170, 17155, -1, 17010, 17161, 17141, -1, 17192, 17155, 17183, -1, 17010, 17141, 17011, -1, 17193, 17173, 17184, -1, 17194, 16840, 17177, -1, 17193, 17183, 17173, -1, 17195, 17169, 17159, -1, 17195, 17159, 17182, -1, 17196, 17180, 17166, -1, 17196, 17166, 17186, -1, 17197, 17151, 17185, -1, 17197, 17168, 17151, -1, 17198, 17184, 17175, -1, 17198, 17175, 17190, -1, 17198, 17193, 17184, -1, 17199, 17185, 17172, -1, 17200, 16330, 16686, -1, 17200, 16686, 17192, -1, 17201, 17174, 17150, -1, 17201, 17150, 17178, -1, 17199, 17172, 17187, -1, 17200, 17192, 17183, -1, 17200, 17183, 17193, -1, 17202, 17148, 16507, -1, 17203, 17176, 17189, -1, 17202, 16507, 16577, -1, 17203, 17187, 17176, -1, 17204, 17180, 17196, -1, 17204, 17190, 17180, -1, 17205, 17193, 17198, -1, 17206, 17178, 17153, -1, 17206, 17153, 17181, -1, 17056, 17169, 17195, -1, 17056, 17179, 17169, -1, 17207, 17198, 17190, -1, 17208, 17165, 17188, -1, 17207, 17190, 17204, -1, 17208, 17209, 17210, -1, 17211, 16940, 16840, -1, 17208, 17210, 17165, -1, 17211, 16840, 17194, -1, 17212, 16330, 17200, -1, 17212, 17200, 17193, -1, 17212, 17193, 17205, -1, 17213, 17163, 17144, -1, 17213, 17188, 17163, -1, 17214, 17177, 17168, -1, 17213, 17144, 17191, -1, 17215, 17205, 17198, -1, 17214, 17168, 17197, -1, 17215, 17198, 17207, -1, 17216, 17212, 17205, -1, 17217, 17148, 17202, -1, 17216, 16682, 16330, -1, 17216, 16330, 17212, -1, 17218, 17197, 17185, -1, 17216, 17205, 17215, -1, 17218, 17185, 17199, -1, 17217, 17167, 17148, -1, 17054, 17179, 17056, -1, 17219, 17161, 17010, -1, 17054, 17189, 17179, -1, 17220, 17082, 17041, -1, 17219, 17181, 17161, -1, 17221, 17187, 17203, -1, 17220, 17164, 17165, -1, 17220, 17041, 17222, -1, 17220, 17222, 17164, -1, 17223, 17220, 17165, -1, 17221, 17199, 17187, -1, 17223, 17106, 17082, -1, 17223, 17165, 17210, -1, 17223, 17082, 17220, -1, 17224, 17223, 17210, -1, 17224, 17210, 17209, -1, 17225, 16938, 16940, -1, 17224, 17106, 17223, -1, 17226, 17191, 17174, -1, 17225, 16940, 17211, -1, 17224, 17119, 17106, -1, 17226, 17174, 17201, -1, 17227, 17178, 17206, -1, 17228, 16497, 16499, -1, 17229, 17119, 17224, -1, 17227, 17201, 17178, -1, 17228, 17182, 16497, -1, 17229, 17136, 17119, -1, 17230, 17209, 17208, -1, 17231, 17229, 17224, -1, 17232, 17194, 17177, -1, 17232, 17177, 17214, -1, 17233, 17224, 17209, -1, 17233, 17231, 17224, -1, 17234, 17067, 17167, -1, 17233, 17209, 17235, -1, 17234, 17167, 17217, -1, 17236, 17214, 17197, -1, 17236, 17197, 17218, -1, 17022, 17189, 17054, -1, 17022, 17203, 17189, -1, 17237, 17001, 17238, -1, 17237, 17238, 17239, -1, 17240, 17188, 17213, -1, 17237, 17239, 17115, -1, 17237, 17115, 17125, -1, 17241, 16999, 17001, -1, 17242, 17199, 17221, -1, 17241, 17237, 17125, -1, 17241, 17001, 17237, -1, 17242, 17218, 17199, -1, 17241, 17125, 17140, -1, 17243, 16999, 17241, -1, 17243, 17052, 16999, -1, 17243, 17241, 17140, -1, 17244, 17213, 17191, -1, 17245, 16936, 16938, -1, 17244, 17191, 17226, -1, 17245, 16938, 17225, -1, 17243, 17140, 17156, -1, 17246, 17195, 17182, -1, 17247, 17052, 17243, -1, 17247, 17091, 17052, -1, 17248, 17206, 17181, -1, 17246, 17182, 17228, -1, 17248, 17181, 17219, -1, 17249, 17247, 17243, -1, 17250, 17226, 17201, -1, 17251, 17211, 17194, -1, 17252, 17156, 17171, -1, 17250, 17201, 17227, -1, 17252, 17249, 17243, -1, 17252, 17243, 17156, -1, 17251, 17194, 17232, -1, 17253, 17067, 17234, -1, 17253, 17068, 17067, -1, 16992, 17203, 17022, -1, 17254, 17215, 17207, -1, 16992, 17221, 17203, -1, 17255, 16724, 16636, -1, 17255, 16764, 16724, -1, 17254, 17256, 17257, -1, 17255, 17209, 17230, -1, 17254, 17258, 17256, -1, 17255, 17235, 17209, -1, 17259, 17214, 17236, -1, 17254, 17207, 17258, -1, 17255, 16636, 17235, -1, 17259, 17232, 17214, -1, 17260, 17216, 17215, -1, 17261, 17202, 16577, -1, 17261, 16577, 16600, -1, 17260, 17215, 17254, -1, 17262, 17236, 17218, -1, 17262, 17218, 17242, -1, 17059, 17056, 17195, -1, 17263, 17260, 17254, -1, 17264, 17254, 17257, -1, 17265, 17230, 17208, -1, 17264, 17257, 17266, -1, 17265, 17188, 17240, -1, 17059, 17195, 17246, -1, 17265, 17208, 17188, -1, 17264, 17263, 17254, -1, 17267, 17222, 17041, -1, 17267, 16969, 16975, -1, 17267, 17041, 16969, -1, 17268, 17222, 17267, -1, 17269, 16934, 16936, -1, 17269, 16936, 17245, -1, 17270, 17211, 17251, -1, 17271, 17145, 17164, -1, 17271, 17222, 17268, -1, 17272, 17240, 17213, -1, 17271, 17129, 17145, -1, 17272, 17213, 17244, -1, 17270, 17225, 17211, -1, 17271, 17164, 17222, -1, 17273, 17206, 17248, -1, 17274, 17136, 17229, -1, 17274, 17229, 17231, -1, 17274, 16603, 17136, -1, 17273, 17227, 17206, -1, 17275, 16636, 16603, -1, 17276, 17244, 17226, -1, 16987, 17242, 17221, -1, 17275, 16603, 17274, -1, 17276, 17226, 17250, -1, 16987, 17221, 16992, -1, 17275, 17274, 17231, -1, 17277, 16636, 17275, -1, 17277, 17231, 17233, -1, 17277, 17233, 17235, -1, 17277, 17235, 16636, -1, 17277, 17275, 17231, -1, 17278, 17279, 17273, -1, 17278, 17239, 17238, -1, 17280, 17217, 17202, -1, 17280, 17202, 17261, -1, 17278, 17238, 17279, -1, 17281, 17251, 17232, -1, 17282, 17239, 17278, -1, 16973, 17045, 17068, -1, 17281, 17232, 17259, -1, 17283, 17239, 17282, -1, 17284, 17228, 16499, -1, 17283, 17074, 17103, -1, 17284, 16499, 16683, -1, 17283, 17115, 17239, -1, 16973, 17068, 17253, -1, 17283, 17103, 17115, -1, 17285, 17261, 16600, -1, 17286, 17247, 17249, -1, 17287, 17236, 17262, -1, 17286, 16473, 17091, -1, 17287, 17259, 17236, -1, 17286, 17091, 17247, -1, 17288, 17286, 17249, -1, 17288, 16616, 16473, -1, 17288, 16473, 17286, -1, 17289, 17230, 17265, -1, 16949, 16932, 16934, -1, 16949, 16934, 17269, -1, 17290, 17288, 17249, -1, 17290, 17171, 16616, -1, 17290, 16616, 17288, -1, 17290, 17252, 17171, -1, 17290, 17249, 17252, -1, 17291, 17204, 17196, -1, 17291, 17207, 17204, -1, 17292, 17245, 17225, -1, 17291, 17258, 17207, -1, 17292, 17225, 17270, -1, 17293, 17240, 17272, -1, 17294, 17258, 17291, -1, 17293, 17265, 17240, -1, 16978, 17228, 17284, -1, 17279, 17227, 17273, -1, 16978, 17246, 17228, -1, 17279, 17250, 17227, -1, 17295, 17258, 17294, -1, 17295, 17296, 17256, -1, 17295, 17297, 17296, -1, 17295, 17256, 17258, -1, 17298, 17216, 17260, -1, 17298, 16682, 17216, -1, 17299, 17262, 17242, -1, 17299, 17242, 16987, -1, 17300, 17217, 17280, -1, 17301, 17260, 17263, -1, 17301, 17298, 17260, -1, 17300, 17234, 17217, -1, 17302, 16682, 17298, -1, 17302, 17298, 17301, -1, 17303, 16689, 16682, -1, 17000, 17272, 17244, -1, 17304, 17270, 17251, -1, 17303, 17301, 17263, -1, 17000, 17244, 17276, -1, 17304, 17251, 17281, -1, 17303, 16682, 17302, -1, 17303, 17302, 17301, -1, 16983, 17045, 16973, -1, 17303, 17266, 16689, -1, 17303, 17264, 17266, -1, 17303, 17263, 17264, -1, 17305, 17268, 17267, -1, 17305, 16975, 17306, -1, 16971, 17281, 17259, -1, 16971, 17259, 17287, -1, 17305, 17267, 16975, -1, 16983, 17015, 17045, -1, 16955, 17261, 17285, -1, 17307, 17268, 17305, -1, 17029, 16930, 16932, -1, 16955, 17280, 17261, -1, 17029, 16932, 16949, -1, 17308, 17112, 17129, -1, 16990, 17234, 17300, -1, 17308, 17268, 17307, -1, 17308, 17271, 17268, -1, 17308, 17129, 17271, -1, 16977, 17059, 17246, -1, 17309, 17282, 17278, -1, 16977, 17246, 16978, -1, 17309, 17278, 17273, -1, 16990, 17253, 17234, -1, 17309, 17273, 17248, -1, 16964, 17269, 17245, -1, 17310, 17255, 17230, -1, 17310, 17230, 17289, -1, 17311, 17282, 17309, -1, 16964, 17245, 17292, -1, 17310, 16764, 17255, -1, 16962, 17285, 16600, -1, 16962, 16600, 16532, -1, 17312, 17074, 17283, -1, 17312, 17282, 17311, -1, 17312, 17283, 17282, -1, 17312, 17035, 17074, -1, 17025, 17289, 17265, -1, 17313, 17294, 17291, -1, 17025, 17265, 17293, -1, 16996, 17270, 17304, -1, 16996, 17292, 17270, -1, 17313, 17196, 17186, -1, 17238, 17276, 17250, -1, 17313, 17291, 17196, -1, 17238, 17000, 17276, -1, 17238, 17250, 17279, -1, 17306, 17262, 17299, -1, 17314, 17294, 17313, -1, 17306, 17287, 17262, -1, 17315, 17297, 17295, -1, 17315, 17316, 17297, -1, 17315, 17294, 17314, -1, 17315, 17295, 17294, -1, 16970, 17304, 17281, -1, 16970, 17281, 16971, -1, 17317, 17305, 17306, -1, 17006, 17293, 17272, -1, 17028, 16538, 16537, -1, 17317, 17307, 17305, -1, 17006, 17272, 17000, -1, 17028, 16537, 16928, -1, 17317, 17306, 17299, -1, 17028, 16928, 16930, -1, 17028, 16930, 17029, -1, 17318, 17112, 17308, -1, 17026, 17059, 16977, -1, 17318, 17308, 17307, -1, 17318, 17307, 17317, -1, 17318, 17095, 17112, -1, 16957, 17300, 17280, -1, 16943, 17248, 17219, -1, 16957, 17280, 16955, -1, 16943, 17311, 17309, -1, 17026, 17058, 17059, -1, 16943, 17309, 17248, -1, 17014, 16683, 16388, -1, 16946, 17311, 16943, -1, 17014, 17284, 16683, -1, 16946, 17312, 17311, -1, 16946, 17035, 17312, -1, 17043, 17015, 16983, -1, 16946, 16953, 17035, -1, 17043, 16952, 17015, -1, 16966, 17314, 17313, -1, 16956, 17285, 16962, -1, 16950, 16949, 17269, -1, 16966, 17313, 17186, -1, 16950, 17269, 16964, -1, 16956, 16955, 17285, -1, 16966, 17186, 16959, -1, 16967, 17314, 16966, -1, 16974, 16973, 17253, -1, 16974, 17253, 16990, -1, 16982, 16981, 17316, -1, 16965, 17292, 16996, -1, 16982, 17316, 17315, -1, 16982, 17315, 17314, -1, 16965, 16964, 17292, -1, 16982, 17314, 16967, -1, 16986, 17317, 17299, -1, 16994, 16990, 17300, -1, 16986, 17299, 16987, -1, 16994, 17300, 16957, -1, 16975, 17287, 17306, -1, 17024, 16412, 16764, -1, 16975, 16971, 17287, -1, 17024, 17289, 17025, -1, 17024, 16764, 17310, -1, 17024, 17310, 17289, -1, 17002, 16996, 17304, -1, 17319, 16988, 17318, -1, 17319, 17318, 17317, -1, 17002, 17304, 16970, -1, 17319, 17317, 16986, -1, 17319, 16986, 16988, -1, 17001, 17000, 17238, -1, 16991, 17318, 16988, -1, 16984, 17284, 17014, -1, 16984, 16978, 17284, -1, 16998, 16997, 17095, -1, 16998, 17095, 17318, -1, 16998, 17318, 16991, -1, 16944, 17219, 17010, -1, 16944, 16943, 17219, -1, 17009, 17058, 17026, -1, 17009, 17008, 17058, -1, 17005, 17293, 17006, -1, 17005, 17025, 17293, -1, 17017, 17014, 16388, -1, 17034, 16952, 17043, -1, 16948, 17029, 16949, -1, 17034, 16953, 16952, -1, 16101, 16727, 16692, -1, 16096, 16692, 16691, -1, 16096, 16101, 16692, -1, 16091, 16691, 16689, -1, 16091, 16096, 16691, -1, 16092, 16689, 17266, -1, 16092, 16091, 16689, -1, 17320, 17266, 17257, -1, 17320, 16092, 17266, -1, 17321, 17257, 17256, -1, 17321, 17320, 17257, -1, 17322, 17256, 17296, -1, 17322, 17321, 17256, -1, 17323, 17296, 17297, -1, 17323, 17322, 17296, -1, 17324, 17297, 17316, -1, 17324, 17323, 17297, -1, 17325, 17324, 17316, -1, 17326, 17316, 16981, -1, 17326, 17325, 17316, -1, 17327, 16981, 16980, -1, 17327, 17326, 16981, -1, 17328, 16980, 17077, -1, 17328, 17327, 16980, -1, 17329, 17077, 17097, -1, 17329, 17328, 17077, -1, 17330, 17097, 17085, -1, 17330, 17329, 17097, -1, 17331, 17085, 17087, -1, 17331, 17330, 17085, -1, 17332, 17331, 17087, -1, 17332, 17087, 17088, -1, 16834, 17332, 17088, -1, 16834, 17088, 16835, -1, 17333, 17334, 17335, -1, 17336, 17337, 17338, -1, 17339, 17340, 17341, -1, 17342, 17337, 17336, -1, 17343, 17335, 17344, -1, 17342, 17345, 17346, -1, 17342, 17346, 17337, -1, 17339, 17341, 17347, -1, 17348, 17349, 17350, -1, 17348, 17351, 17349, -1, 17343, 17344, 17352, -1, 17353, 17354, 17355, -1, 17353, 17355, 17356, -1, 17357, 17358, 17359, -1, 17357, 17360, 17358, -1, 17361, 17362, 17351, -1, 17361, 17351, 17348, -1, 17361, 17348, 17363, -1, 17364, 17361, 17363, -1, 17364, 17362, 17361, -1, 17365, 17366, 17367, -1, 17365, 17367, 17368, -1, 17369, 17362, 17364, -1, 17370, 16076, 16079, -1, 17369, 17360, 17362, -1, 17371, 17372, 17373, -1, 17369, 17358, 17360, -1, 17370, 16079, 16908, -1, 17370, 17374, 16076, -1, 17371, 17375, 17372, -1, 17376, 17377, 17378, -1, 17376, 17379, 17377, -1, 17380, 17352, 17381, -1, 17380, 17381, 17382, -1, 17383, 17384, 17385, -1, 17383, 17385, 17386, -1, 17387, 17379, 17376, -1, 17388, 17389, 17390, -1, 17387, 17376, 17391, -1, 17392, 17393, 17394, -1, 17387, 17395, 17379, -1, 17392, 17396, 17393, -1, 17397, 17387, 17391, -1, 17397, 17395, 17387, -1, 17388, 17347, 17389, -1, 17398, 17373, 17399, -1, 17398, 17399, 17400, -1, 17401, 17395, 17397, -1, 17402, 16110, 16093, -1, 17401, 16897, 16895, -1, 17401, 16895, 17395, -1, 17402, 16093, 17403, -1, 17402, 17403, 17404, -1, 17405, 17336, 17338, -1, 17406, 17407, 17408, -1, 17405, 17409, 17410, -1, 17402, 17404, 17333, -1, 17405, 17411, 17409, -1, 17405, 17338, 17411, -1, 17412, 17342, 17336, -1, 17412, 17345, 17342, -1, 17406, 17386, 17407, -1, 17412, 17336, 17405, -1, 17413, 17340, 17339, -1, 17414, 17375, 17371, -1, 17412, 17396, 17345, -1, 17414, 17415, 17375, -1, 17416, 17348, 17350, -1, 17416, 17364, 17363, -1, 17417, 15944, 15943, -1, 17413, 15974, 17418, -1, 17413, 17418, 17340, -1, 17417, 17400, 15944, -1, 17416, 17350, 17419, -1, 17420, 17408, 17366, -1, 17416, 17363, 17348, -1, 17420, 17366, 17365, -1, 17421, 17422, 17358, -1, 17423, 17333, 17335, -1, 17421, 17369, 17364, -1, 17421, 17358, 17369, -1, 17421, 17364, 17416, -1, 17423, 17335, 17343, -1, 17424, 17376, 17378, -1, 17425, 17360, 17357, -1, 17424, 17391, 17376, -1, 17424, 17378, 17426, -1, 17427, 17382, 17354, -1, 17427, 17354, 17353, -1, 17424, 17397, 17391, -1, 17428, 17401, 17397, -1, 17428, 16897, 17401, -1, 17428, 16899, 16897, -1, 17425, 17429, 17360, -1, 17428, 17397, 17424, -1, 17430, 17410, 17431, -1, 17432, 17370, 16908, -1, 17432, 17374, 17370, -1, 17430, 17405, 17410, -1, 17432, 16908, 16906, -1, 17432, 17368, 17374, -1, 17433, 17352, 17380, -1, 17434, 17359, 17384, -1, 17433, 17343, 17352, -1, 16093, 16092, 17320, -1, 17434, 17384, 17383, -1, 17435, 17405, 17430, -1, 17436, 17371, 17373, -1, 17437, 17412, 17405, -1, 17437, 17396, 17412, -1, 17437, 17393, 17396, -1, 17437, 17405, 17435, -1, 17438, 17419, 17439, -1, 17440, 17347, 17388, -1, 17436, 17373, 17398, -1, 17438, 17416, 17419, -1, 17440, 17413, 17339, -1, 17440, 17339, 17347, -1, 17441, 17345, 17396, -1, 17442, 17416, 17438, -1, 17441, 17396, 17392, -1, 17443, 17421, 17416, -1, 17443, 17416, 17442, -1, 17444, 17383, 17386, -1, 17445, 17398, 17400, -1, 17443, 17446, 17422, -1, 17444, 17434, 17383, -1, 17445, 17400, 17417, -1, 17443, 17422, 17421, -1, 17447, 17426, 17448, -1, 17447, 17424, 17426, -1, 17444, 17386, 17406, -1, 17449, 17394, 17415, -1, 17450, 17424, 17447, -1, 17449, 17415, 17414, -1, 17451, 17406, 17408, -1, 17451, 17408, 17420, -1, 17452, 16120, 16110, -1, 17452, 16110, 17402, -1, 17453, 16901, 16899, -1, 17452, 17333, 17423, -1, 17453, 16899, 17428, -1, 17452, 17402, 17333, -1, 17453, 17428, 17424, -1, 17453, 17424, 17450, -1, 17454, 17365, 17368, -1, 17455, 17430, 17431, -1, 17456, 17380, 17382, -1, 17455, 17457, 17458, -1, 17456, 17382, 17427, -1, 17455, 17435, 17430, -1, 17454, 17368, 17432, -1, 17455, 17431, 17457, -1, 17459, 17458, 17460, -1, 17459, 17393, 17437, -1, 17459, 17437, 17435, -1, 17461, 17429, 17425, -1, 17459, 17460, 17462, -1, 17459, 17435, 17455, -1, 17459, 17455, 17458, -1, 17461, 17463, 17429, -1, 17459, 17462, 17393, -1, 17464, 17414, 17371, -1, 17465, 17439, 17466, -1, 17465, 17438, 17439, -1, 17467, 17359, 17434, -1, 17465, 17442, 17438, -1, 17465, 17466, 17468, -1, 17464, 17371, 17436, -1, 17469, 17470, 17471, -1, 17469, 17468, 17470, -1, 17469, 17442, 17465, -1, 17472, 17423, 17343, -1, 17469, 17443, 17442, -1, 17469, 17446, 17443, -1, 17472, 17343, 17433, -1, 17469, 17471, 17446, -1, 17469, 17465, 17468, -1, 17467, 17357, 17359, -1, 17473, 17474, 17454, -1, 17475, 16036, 15974, -1, 17473, 17447, 17448, -1, 17476, 17345, 17441, -1, 17475, 15974, 17413, -1, 17473, 17450, 17447, -1, 17475, 17413, 17440, -1, 17473, 17448, 17474, -1, 17476, 17346, 17345, -1, 17477, 16904, 16901, -1, 17477, 16901, 17453, -1, 17478, 17398, 17445, -1, 17477, 17453, 17450, -1, 17478, 17436, 17398, -1, 17477, 17450, 17473, -1, 17479, 17454, 17432, -1, 17479, 17432, 16906, -1, 17474, 17420, 17365, -1, 17479, 16906, 16904, -1, 17474, 17365, 17454, -1, 17479, 16904, 17477, -1, 17479, 17473, 17454, -1, 17479, 17477, 17473, -1, 17480, 17417, 15943, -1, 17481, 17394, 17449, -1, 17482, 17434, 17444, -1, 17483, 17482, 17444, -1, 17481, 17392, 17394, -1, 17483, 17406, 17451, -1, 17484, 17380, 17456, -1, 17483, 17444, 17406, -1, 17484, 17433, 17380, -1, 17485, 17463, 17461, -1, 17485, 17486, 17463, -1, 17487, 17449, 17414, -1, 17487, 17414, 17464, -1, 17488, 17357, 17467, -1, 17488, 17425, 17357, -1, 17489, 17452, 17423, -1, 17489, 17423, 17472, -1, 17489, 16120, 17452, -1, 17490, 17464, 17436, -1, 17448, 17451, 17420, -1, 17448, 17420, 17474, -1, 17490, 17436, 17478, -1, 17491, 17467, 17434, -1, 17492, 17493, 17346, -1, 17492, 17346, 17476, -1, 17491, 17434, 17482, -1, 17494, 17445, 17417, -1, 17491, 17488, 17467, -1, 17494, 17417, 17480, -1, 17495, 17482, 17483, -1, 17496, 17441, 17392, -1, 17496, 17392, 17481, -1, 17497, 17498, 17486, -1, 17497, 17486, 17485, -1, 17499, 17472, 17433, -1, 17499, 17433, 17484, -1, 17500, 17461, 17425, -1, 17500, 17425, 17488, -1, 17501, 17481, 17449, -1, 17501, 17449, 17487, -1, 17426, 17451, 17448, -1, 17502, 17487, 17464, -1, 17502, 17464, 17490, -1, 17426, 17483, 17451, -1, 17503, 17500, 17488, -1, 17504, 16839, 16320, -1, 17468, 17478, 17445, -1, 17504, 16320, 15954, -1, 17503, 17488, 17491, -1, 17468, 17445, 17494, -1, 17505, 16839, 17504, -1, 17506, 17491, 17482, -1, 17506, 17503, 17491, -1, 17507, 17508, 17493, -1, 17505, 16837, 16839, -1, 17506, 17482, 17495, -1, 17507, 17493, 17492, -1, 17509, 17498, 17497, -1, 17510, 17476, 17441, -1, 17511, 16834, 16837, -1, 17509, 17512, 17498, -1, 17511, 16837, 17505, -1, 17513, 17461, 17500, -1, 17510, 17441, 17496, -1, 17513, 17485, 17461, -1, 17514, 16162, 16120, -1, 17514, 17489, 17472, -1, 17514, 16120, 17489, -1, 17514, 17472, 17499, -1, 17515, 17332, 16834, -1, 17515, 16834, 17511, -1, 17516, 17504, 15954, -1, 17517, 17500, 17503, -1, 17516, 15954, 15960, -1, 17518, 17496, 17481, -1, 17518, 17481, 17501, -1, 17517, 17513, 17500, -1, 17378, 17483, 17426, -1, 17519, 17504, 17516, -1, 17466, 17490, 17478, -1, 17519, 17505, 17504, -1, 17378, 17495, 17483, -1, 17466, 17478, 17468, -1, 17520, 17517, 17503, -1, 17521, 17487, 17502, -1, 17521, 17501, 17487, -1, 17522, 17331, 17332, -1, 17520, 17503, 17506, -1, 17522, 17332, 17515, -1, 17523, 17512, 17509, -1, 17524, 17516, 15960, -1, 17523, 17525, 17512, -1, 17526, 17508, 17507, -1, 17527, 17505, 17519, -1, 17528, 17497, 17485, -1, 17528, 17485, 17513, -1, 17526, 17529, 17508, -1, 17530, 17480, 15943, -1, 17530, 15943, 16073, -1, 17527, 17511, 17505, -1, 17531, 17513, 17517, -1, 17532, 17476, 17510, -1, 17532, 17492, 17476, -1, 17533, 17330, 17331, -1, 17533, 17331, 17522, -1, 17377, 17495, 17378, -1, 17534, 17519, 17516, -1, 17377, 17506, 17495, -1, 17534, 17516, 17524, -1, 17535, 17531, 17517, -1, 17536, 17511, 17527, -1, 17537, 17496, 17518, -1, 17537, 17510, 17496, -1, 17536, 17515, 17511, -1, 17535, 17517, 17520, -1, 17538, 17525, 17523, -1, 17539, 17524, 15960, -1, 17439, 17490, 17466, -1, 17539, 15960, 16058, -1, 17538, 17540, 17525, -1, 17439, 17502, 17490, -1, 17541, 17497, 17528, -1, 17541, 17509, 17497, -1, 17542, 17518, 17501, -1, 17543, 17527, 17519, -1, 17544, 17528, 17513, -1, 17542, 17501, 17521, -1, 17543, 17519, 17534, -1, 17544, 17513, 17531, -1, 17545, 17546, 17529, -1, 17547, 17329, 17330, -1, 17545, 17529, 17526, -1, 17547, 17330, 17533, -1, 17548, 17494, 17480, -1, 17549, 17534, 17524, -1, 17550, 17520, 17506, -1, 17550, 17506, 17377, -1, 17551, 17531, 17535, -1, 17548, 17480, 17530, -1, 17549, 17524, 17539, -1, 17552, 17515, 17536, -1, 17553, 16174, 16173, -1, 17552, 17522, 17515, -1, 17554, 17492, 17532, -1, 17553, 16173, 17555, -1, 17553, 17540, 17538, -1, 17553, 17555, 17540, -1, 17554, 17507, 17492, -1, 17556, 17523, 17509, -1, 17557, 17527, 17543, -1, 17557, 17536, 17527, -1, 17556, 17509, 17541, -1, 17558, 17328, 17329, -1, 17559, 17532, 17510, -1, 17560, 17520, 17550, -1, 17559, 17510, 17537, -1, 17558, 17329, 17547, -1, 17560, 17535, 17520, -1, 17561, 17528, 17544, -1, 17562, 17543, 17534, -1, 17561, 17541, 17528, -1, 17419, 17502, 17439, -1, 17419, 17521, 17502, -1, 17562, 17534, 17549, -1, 17563, 17537, 17518, -1, 17564, 17539, 16058, -1, 17565, 17544, 17531, -1, 17565, 17531, 17551, -1, 17563, 17518, 17542, -1, 17566, 17522, 17552, -1, 17567, 17523, 17556, -1, 17470, 17494, 17548, -1, 17566, 17533, 17522, -1, 17567, 17538, 17523, -1, 17470, 17468, 17494, -1, 17568, 17536, 17557, -1, 17568, 17552, 17536, -1, 17569, 17551, 17535, -1, 17569, 17535, 17560, -1, 17570, 17546, 17545, -1, 17570, 17571, 17546, -1, 17572, 17543, 17562, -1, 17573, 17541, 17561, -1, 17572, 17557, 17543, -1, 17573, 17556, 17541, -1, 17574, 17507, 17554, -1, 17574, 17526, 17507, -1, 17575, 17561, 17544, -1, 17575, 17544, 17565, -1, 17576, 17327, 17328, -1, 17576, 17328, 17558, -1, 17577, 16247, 16174, -1, 17577, 17553, 17538, -1, 17578, 17554, 17532, -1, 17577, 16174, 17553, -1, 17578, 17532, 17559, -1, 17579, 17549, 17539, -1, 17579, 17539, 17564, -1, 17577, 17538, 17567, -1, 17580, 17567, 17556, -1, 17581, 17533, 17566, -1, 17580, 17556, 17573, -1, 17350, 17542, 17521, -1, 17581, 17547, 17533, -1, 17580, 17577, 17567, -1, 17350, 17521, 17419, -1, 17582, 17551, 17569, -1, 17582, 17565, 17551, -1, 17583, 17552, 17568, -1, 17583, 17566, 17552, -1, 17584, 17561, 17575, -1, 17584, 17573, 17561, -1, 17585, 17568, 17557, -1, 17585, 17557, 17572, -1, 17586, 16073, 16135, -1, 17587, 17575, 17565, -1, 17586, 17530, 16073, -1, 17587, 17565, 17582, -1, 17458, 17562, 17549, -1, 17588, 15886, 16247, -1, 17588, 16247, 17577, -1, 17589, 17559, 17537, -1, 17458, 17549, 17579, -1, 17588, 17577, 17580, -1, 17589, 17537, 17563, -1, 17590, 17591, 17571, -1, 17592, 17580, 17573, -1, 17592, 17588, 17580, -1, 17593, 17326, 17327, -1, 17592, 17573, 17584, -1, 17594, 17575, 17587, -1, 17590, 17571, 17570, -1, 17593, 17327, 17576, -1, 17594, 17584, 17575, -1, 17595, 17545, 17526, -1, 17596, 17558, 17547, -1, 17597, 17588, 17592, -1, 17596, 17547, 17581, -1, 17595, 17526, 17574, -1, 17598, 17548, 17530, -1, 17597, 15886, 17588, -1, 17599, 17584, 17594, -1, 17599, 17592, 17584, -1, 17598, 17530, 17586, -1, 17600, 17581, 17566, -1, 17600, 17566, 17583, -1, 17457, 17562, 17458, -1, 17601, 16242, 15886, -1, 17601, 17592, 17599, -1, 17601, 15886, 17597, -1, 17602, 17574, 17554, -1, 17602, 17554, 17578, -1, 17457, 17572, 17562, -1, 17601, 17597, 17592, -1, 17603, 17568, 17585, -1, 17349, 17542, 17350, -1, 17603, 17583, 17568, -1, 17349, 17563, 17542, -1, 17604, 17456, 17427, -1, 17604, 17605, 17546, -1, 17606, 17325, 17326, -1, 17604, 17546, 17571, -1, 17606, 17326, 17593, -1, 17604, 17427, 17605, -1, 17607, 17571, 17591, -1, 17607, 17484, 17456, -1, 17607, 17456, 17604, -1, 17607, 17604, 17571, -1, 17608, 16058, 16064, -1, 17609, 17591, 17610, -1, 17609, 17484, 17607, -1, 17608, 17564, 16058, -1, 17611, 17578, 17559, -1, 17609, 17499, 17484, -1, 17611, 17559, 17589, -1, 17612, 17558, 17596, -1, 17609, 17607, 17591, -1, 17613, 17610, 17591, -1, 17614, 17499, 17609, -1, 17613, 17591, 17590, -1, 17612, 17576, 17558, -1, 17614, 17514, 17499, -1, 17615, 17470, 17548, -1, 17616, 17596, 17581, -1, 17616, 17581, 17600, -1, 17617, 17614, 17609, -1, 17431, 17585, 17572, -1, 17615, 17548, 17598, -1, 17618, 17610, 17619, -1, 17618, 17617, 17609, -1, 17618, 17609, 17610, -1, 17431, 17572, 17457, -1, 17620, 17570, 17545, -1, 17621, 17583, 17603, -1, 17620, 17545, 17595, -1, 17621, 17600, 17583, -1, 17622, 17623, 17498, -1, 17624, 17595, 17574, -1, 17625, 17325, 17606, -1, 17622, 17626, 17623, -1, 17622, 17498, 17512, -1, 17624, 17574, 17602, -1, 17622, 17390, 17626, -1, 17627, 17388, 17390, -1, 17628, 17589, 17563, -1, 17625, 17324, 17325, -1, 17627, 17622, 17512, -1, 17627, 17512, 17525, -1, 17627, 17390, 17622, -1, 17628, 17563, 17349, -1, 17629, 17388, 17627, -1, 17629, 17440, 17388, -1, 17630, 17564, 17608, -1, 17629, 17627, 17525, -1, 17629, 17525, 17540, -1, 17630, 17579, 17564, -1, 17631, 17440, 17629, -1, 17632, 17593, 17576, -1, 17631, 17475, 17440, -1, 17633, 17602, 17578, -1, 17632, 17576, 17612, -1, 17410, 17585, 17431, -1, 17633, 17578, 17611, -1, 17634, 17631, 17629, -1, 17635, 16281, 16193, -1, 17636, 17629, 17540, -1, 17635, 16193, 17619, -1, 17410, 17603, 17585, -1, 17635, 17619, 17610, -1, 17636, 17634, 17629, -1, 17636, 17540, 17555, -1, 17635, 17610, 17613, -1, 17637, 17471, 17470, -1, 17638, 17596, 17616, -1, 17639, 17640, 16886, -1, 17637, 17470, 17615, -1, 17638, 17612, 17596, -1, 17641, 17616, 17600, -1, 17639, 16886, 16884, -1, 17639, 17582, 17640, -1, 17642, 16135, 16159, -1, 17641, 17600, 17621, -1, 17639, 17587, 17582, -1, 17643, 17594, 17587, -1, 17642, 17586, 16135, -1, 17460, 17458, 17579, -1, 17643, 16884, 16882, -1, 17643, 17639, 16884, -1, 17643, 17587, 17639, -1, 17460, 17579, 17630, -1, 17644, 17599, 17594, -1, 17645, 17590, 17570, -1, 17644, 16882, 16880, -1, 17645, 17570, 17620, -1, 17644, 17594, 17643, -1, 17644, 17643, 16882, -1, 17646, 17601, 17599, -1, 17647, 17323, 17324, -1, 17647, 17324, 17625, -1, 17648, 17620, 17595, -1, 17646, 17599, 17644, -1, 17648, 17595, 17624, -1, 17649, 17606, 17593, -1, 17650, 17611, 17589, -1, 17651, 17646, 17644, -1, 17650, 17589, 17628, -1, 17652, 17644, 16880, -1, 17649, 17593, 17632, -1, 17652, 16880, 16878, -1, 17652, 17651, 17644, -1, 17653, 17632, 17612, -1, 17653, 17612, 17638, -1, 17654, 17427, 17353, -1, 17654, 17353, 17356, -1, 17654, 17605, 17427, -1, 17409, 17621, 17603, -1, 17655, 17624, 17602, -1, 17656, 17605, 17654, -1, 17409, 17603, 17410, -1, 17655, 17602, 17633, -1, 17657, 17605, 17656, -1, 17658, 17586, 17642, -1, 17657, 17546, 17605, -1, 17657, 17529, 17546, -1, 17657, 17508, 17529, -1, 17658, 17598, 17586, -1, 17659, 17514, 17614, -1, 17659, 17614, 17617, -1, 17659, 16162, 17514, -1, 17660, 17608, 16064, -1, 17661, 16193, 16162, -1, 17385, 17471, 17637, -1, 17660, 16064, 16239, -1, 17661, 16162, 17659, -1, 17661, 17659, 17617, -1, 17662, 17661, 17617, -1, 17662, 17619, 16193, -1, 17662, 16193, 17661, -1, 17663, 17638, 17616, -1, 17662, 17618, 17619, -1, 17663, 17616, 17641, -1, 17662, 17617, 17618, -1, 17385, 17446, 17471, -1, 17664, 17623, 17626, -1, 17664, 17665, 17650, -1, 17666, 17642, 16159, -1, 17334, 17322, 17323, -1, 17664, 17626, 17665, -1, 17334, 17323, 17647, -1, 17667, 17623, 17664, -1, 17668, 17613, 17590, -1, 17669, 17625, 17606, -1, 17668, 17590, 17645, -1, 17670, 17463, 17486, -1, 17670, 17498, 17623, -1, 17341, 17645, 17620, -1, 17670, 17486, 17498, -1, 17341, 17620, 17648, -1, 17669, 17606, 17649, -1, 17670, 17623, 17667, -1, 17671, 17475, 17631, -1, 17372, 17630, 17608, -1, 17671, 16036, 17475, -1, 17665, 17633, 17611, -1, 17671, 17631, 17634, -1, 17372, 17608, 17660, -1, 17672, 16173, 16036, -1, 17672, 17671, 17634, -1, 17665, 17611, 17650, -1, 17672, 16036, 17671, -1, 17673, 17632, 17653, -1, 17673, 17649, 17632, -1, 17674, 16173, 17672, -1, 17674, 17672, 17634, -1, 17674, 17555, 16173, -1, 17674, 17636, 17555, -1, 17674, 17634, 17636, -1, 17675, 17621, 17409, -1, 17676, 17640, 17582, -1, 17675, 17641, 17621, -1, 17676, 17582, 17569, -1, 17677, 17598, 17658, -1, 17676, 17569, 17560, -1, 17678, 17640, 17676, -1, 17677, 17615, 17598, -1, 17679, 16886, 17640, -1, 17679, 17640, 17678, -1, 17389, 17648, 17624, -1, 17679, 16888, 16886, -1, 17679, 16890, 16888, -1, 17680, 16242, 17601, -1, 17680, 17601, 17646, -1, 17355, 17638, 17663, -1, 17389, 17624, 17655, -1, 17355, 17653, 17638, -1, 17384, 17446, 17385, -1, 17681, 17680, 17646, -1, 17681, 17646, 17651, -1, 17404, 17322, 17334, -1, 17404, 17321, 17322, -1, 17384, 17422, 17446, -1, 17682, 16242, 17680, -1, 17682, 17680, 17681, -1, 17367, 17642, 17666, -1, 17367, 17658, 17642, -1, 17375, 17630, 17372, -1, 17683, 16242, 17682, -1, 17683, 17681, 17651, -1, 17375, 17460, 17630, -1, 17683, 17682, 17681, -1, 17683, 17651, 17652, -1, 17684, 16244, 16242, -1, 17684, 16242, 17683, -1, 17685, 16322, 16281, -1, 17684, 17683, 17652, -1, 17684, 16878, 16244, -1, 17685, 17635, 17613, -1, 17344, 17647, 17625, -1, 17684, 17652, 16878, -1, 17344, 17625, 17669, -1, 17685, 17613, 17668, -1, 17685, 16281, 17635, -1, 17686, 17656, 17654, -1, 17686, 17654, 17356, -1, 17686, 17356, 17687, -1, 17407, 17615, 17677, -1, 17381, 17669, 17649, -1, 17381, 17649, 17673, -1, 17688, 17656, 17686, -1, 17407, 17637, 17615, -1, 17374, 17666, 16159, -1, 17689, 17493, 17508, -1, 17374, 16159, 16076, -1, 17687, 17663, 17641, -1, 17689, 17657, 17656, -1, 17687, 17641, 17675, -1, 17689, 17656, 17688, -1, 17689, 17508, 17657, -1, 17340, 17645, 17341, -1, 17690, 17650, 17628, -1, 17340, 17668, 17645, -1, 17690, 17667, 17664, -1, 17690, 17664, 17650, -1, 17626, 17655, 17633, -1, 17691, 17667, 17690, -1, 17626, 17633, 17665, -1, 17354, 17673, 17653, -1, 17354, 17653, 17355, -1, 17692, 17463, 17670, -1, 17692, 17670, 17667, -1, 17403, 17321, 17404, -1, 17692, 17667, 17691, -1, 17403, 16093, 17320, -1, 17692, 17429, 17463, -1, 17403, 17320, 17321, -1, 17415, 17460, 17375, -1, 17693, 17560, 17550, -1, 17347, 17648, 17389, -1, 17693, 17678, 17676, -1, 17693, 17676, 17560, -1, 17347, 17341, 17648, -1, 17415, 17462, 17460, -1, 17366, 17658, 17367, -1, 17399, 16239, 15944, -1, 17694, 17678, 17693, -1, 17399, 17660, 16239, -1, 17695, 17679, 17678, -1, 17695, 16890, 17679, -1, 17695, 16892, 16890, -1, 17695, 17678, 17694, -1, 17366, 17677, 17658, -1, 17696, 17687, 17675, -1, 17359, 17358, 17422, -1, 17335, 17334, 17647, -1, 17696, 17688, 17686, -1, 17335, 17647, 17344, -1, 17359, 17422, 17384, -1, 17696, 17686, 17687, -1, 17352, 17344, 17669, -1, 17337, 17346, 17493, -1, 17352, 17669, 17381, -1, 17337, 17493, 17689, -1, 17337, 17689, 17688, -1, 17337, 17688, 17696, -1, 17368, 17666, 17374, -1, 17368, 17367, 17666, -1, 17351, 17691, 17690, -1, 17356, 17663, 17687, -1, 17351, 17690, 17628, -1, 17356, 17355, 17663, -1, 17351, 17628, 17349, -1, 17362, 17691, 17351, -1, 17362, 17692, 17691, -1, 17362, 17429, 17692, -1, 17362, 17360, 17429, -1, 17386, 17385, 17637, -1, 17386, 17637, 17407, -1, 17382, 17673, 17354, -1, 17379, 17693, 17550, -1, 17418, 16322, 17685, -1, 17379, 17550, 17377, -1, 17418, 15974, 16322, -1, 17382, 17381, 17673, -1, 17379, 17694, 17693, -1, 17418, 17668, 17340, -1, 17418, 17685, 17668, -1, 17395, 16895, 16892, -1, 17395, 16892, 17695, -1, 17373, 17660, 17399, -1, 17395, 17695, 17694, -1, 17390, 17655, 17626, -1, 17395, 17694, 17379, -1, 17411, 17696, 17675, -1, 17411, 17675, 17409, -1, 17390, 17389, 17655, -1, 17373, 17372, 17660, -1, 17394, 17462, 17415, -1, 17394, 17393, 17462, -1, 17697, 17337, 17696, -1, 17697, 17696, 17411, -1, 17697, 17338, 17337, -1, 17400, 17399, 15944, -1, 17697, 17411, 17338, -1, 17333, 17404, 17334, -1, 17408, 17407, 17677, -1, 17408, 17677, 17366, -1, 17698, 15545, 15547, -1, 17698, 15547, 17699, -1, 15551, 17700, 17701, -1, 15551, 17701, 15549, -1, 17702, 15559, 15558, -1, 17702, 15558, 17703, -1, 17704, 17699, 17705, -1, 17706, 17705, 17699, -1, 17706, 17699, 17701, -1, 17707, 17699, 17704, -1, 17708, 17706, 17701, -1, 17709, 17699, 17707, -1, 17710, 17708, 17701, -1, 17711, 17699, 17709, -1, 17712, 17710, 17701, -1, 17713, 17712, 17701, -1, 17714, 17715, 17716, -1, 17714, 17717, 17715, -1, 17718, 17716, 17715, -1, 17718, 17715, 17719, -1, 17720, 17721, 17717, -1, 17720, 17717, 17714, -1, 17722, 17719, 17723, -1, 17722, 17718, 17719, -1, 17724, 17699, 17711, -1, 17724, 17711, 17721, -1, 17724, 17721, 17720, -1, 17725, 17723, 17726, -1, 17725, 17722, 17723, -1, 16933, 17727, 17728, -1, 16933, 17729, 17727, -1, 16935, 16933, 17728, -1, 16935, 17728, 17730, -1, 17731, 17726, 16800, -1, 17731, 17725, 17726, -1, 16931, 17732, 17729, -1, 16931, 16786, 17732, -1, 16931, 17729, 16933, -1, 16937, 17713, 17701, -1, 16937, 17730, 17713, -1, 16937, 16935, 17730, -1, 16929, 16787, 16786, -1, 16929, 16790, 16787, -1, 16929, 16786, 16931, -1, 17733, 17731, 16800, -1, 17733, 16800, 16798, -1, 16939, 16937, 17701, -1, 17734, 16798, 16796, -1, 17734, 17733, 16798, -1, 16927, 16792, 16790, -1, 16927, 16794, 16792, -1, 16927, 16790, 16929, -1, 16941, 16939, 17701, -1, 16926, 17735, 17734, -1, 16926, 16796, 16794, -1, 16926, 17734, 16796, -1, 16926, 16794, 16927, -1, 16841, 16941, 17701, -1, 16925, 17736, 17735, -1, 16925, 17735, 16926, -1, 16924, 17736, 16925, -1, 16924, 17737, 17736, -1, 16924, 17738, 17737, -1, 16923, 16771, 16770, -1, 16923, 17738, 16924, -1, 16923, 16770, 17738, -1, 17698, 17739, 17740, -1, 17698, 17741, 17739, -1, 17698, 17742, 17741, -1, 17698, 17743, 17742, -1, 17698, 17744, 17743, -1, 17698, 17745, 17744, -1, 16922, 16774, 16771, -1, 16922, 16776, 16774, -1, 16922, 16771, 16923, -1, 17703, 17740, 16784, -1, 17703, 16782, 16780, -1, 17703, 16784, 16782, -1, 17703, 17698, 17740, -1, 16921, 16778, 16776, -1, 16921, 16776, 16922, -1, 17700, 16844, 16842, -1, 17700, 16842, 16841, -1, 17700, 16841, 17701, -1, 17700, 16850, 16848, -1, 17700, 16848, 16846, -1, 17700, 16846, 16844, -1, 16851, 16850, 17700, -1, 16920, 16780, 16778, -1, 16920, 17703, 16780, -1, 16920, 16778, 16921, -1, 16919, 17703, 16920, -1, 17746, 16851, 17700, -1, 17746, 16853, 16851, -1, 16918, 17703, 16919, -1, 16855, 16853, 17746, -1, 16857, 16855, 17746, -1, 16858, 16857, 17746, -1, 17702, 17703, 16918, -1, 17702, 16918, 16866, -1, 17702, 16866, 16865, -1, 17702, 16865, 16864, -1, 17702, 16864, 16863, -1, 17747, 16858, 17746, -1, 17747, 17702, 16863, -1, 17747, 16863, 16862, -1, 17747, 16862, 16861, -1, 17747, 16861, 16860, -1, 17747, 16860, 16859, -1, 17747, 16859, 16858, -1, 17698, 17699, 17724, -1, 17698, 17724, 17745, -1, 17748, 17749, 17750, -1, 17751, 16791, 17752, -1, 17751, 16789, 16791, -1, 17753, 17754, 17755, -1, 17751, 15555, 16789, -1, 17753, 17755, 15547, -1, 17756, 17757, 16797, -1, 17753, 17748, 17754, -1, 17758, 17759, 15551, -1, 17756, 16797, 16799, -1, 17760, 15551, 17759, -1, 17761, 17762, 15547, -1, 17763, 17758, 15551, -1, 16772, 15555, 17751, -1, 16772, 15556, 15555, -1, 17764, 15551, 17760, -1, 17765, 17763, 15551, -1, 17766, 17756, 16799, -1, 15545, 17767, 17768, -1, 17766, 16799, 16801, -1, 15545, 17768, 17769, -1, 16788, 15551, 17764, -1, 15545, 17769, 17770, -1, 15545, 17770, 17771, -1, 15545, 17771, 17772, -1, 15545, 17772, 17773, -1, 17755, 17761, 15547, -1, 16789, 15555, 15551, -1, 15558, 16781, 16783, -1, 16789, 15551, 16788, -1, 15558, 16783, 16785, -1, 15558, 16785, 17767, -1, 15558, 15559, 16781, -1, 15558, 17767, 15545, -1, 16773, 15556, 16772, -1, 15547, 15545, 17773, -1, 15547, 17773, 17753, -1, 16773, 15559, 15556, -1, 15549, 17774, 17765, -1, 15549, 17765, 15551, -1, 16775, 15559, 16773, -1, 17775, 17774, 15549, -1, 16777, 15559, 16775, -1, 17776, 17775, 15549, -1, 16779, 15559, 16777, -1, 17777, 17766, 16801, -1, 17777, 16801, 17778, -1, 17779, 17776, 15549, -1, 16781, 15559, 16779, -1, 15547, 17779, 15549, -1, 17780, 17778, 17781, -1, 17780, 17777, 17778, -1, 17782, 17779, 15547, -1, 17783, 17782, 15547, -1, 17762, 17783, 15547, -1, 17784, 17781, 17785, -1, 17784, 17780, 17781, -1, 17786, 16795, 17787, -1, 17788, 17785, 17789, -1, 17786, 16793, 16795, -1, 17788, 17784, 17785, -1, 17757, 17787, 16795, -1, 17749, 17789, 17750, -1, 17757, 16795, 16797, -1, 17749, 17788, 17789, -1, 17752, 16793, 17786, -1, 17752, 16791, 16793, -1, 17748, 17750, 17754, -1, 15773, 17790, 17791, -1, 15773, 17791, 15774, -1, 15769, 17792, 17793, -1, 15769, 17793, 15770, -1, 17794, 15783, 15784, -1, 17794, 15784, 17795, -1, 17793, 17796, 17797, -1, 17793, 17798, 17796, -1, 17797, 17799, 17793, -1, 17793, 17799, 17790, -1, 17793, 17800, 17798, -1, 17799, 17801, 17790, -1, 17801, 17802, 17790, -1, 17793, 16802, 17800, -1, 17793, 16803, 16802, -1, 17802, 17803, 17790, -1, 17803, 17804, 17790, -1, 16806, 17805, 16808, -1, 16808, 17806, 16810, -1, 17805, 17806, 16808, -1, 16810, 17807, 16812, -1, 17806, 17807, 16810, -1, 16803, 17808, 16806, -1, 16806, 17808, 17805, -1, 16803, 17809, 17808, -1, 17793, 17809, 16803, -1, 16812, 17810, 16814, -1, 17807, 17810, 16812, -1, 17793, 16818, 17809, -1, 16814, 17811, 16816, -1, 17810, 17811, 16814, -1, 17812, 16883, 17813, -1, 17813, 16883, 17814, -1, 16883, 16885, 17814, -1, 17814, 16885, 17815, -1, 16816, 17816, 17817, -1, 17817, 17816, 17818, -1, 17811, 17816, 16816, -1, 17819, 16881, 17812, -1, 17812, 16881, 16883, -1, 17815, 16887, 17804, -1, 17804, 16887, 17790, -1, 16885, 16887, 17815, -1, 17820, 16879, 17821, -1, 17821, 16879, 17819, -1, 17819, 16879, 16881, -1, 17816, 17822, 17818, -1, 16887, 16889, 17790, -1, 17818, 17823, 17824, -1, 17822, 17823, 17818, -1, 17825, 16877, 17826, -1, 17826, 16877, 17820, -1, 17820, 16877, 16879, -1, 16889, 16891, 17790, -1, 17825, 16876, 16877, -1, 17823, 16876, 17824, -1, 17824, 16876, 17825, -1, 16891, 16893, 17790, -1, 17823, 16875, 16876, -1, 17827, 16875, 17828, -1, 17828, 16875, 17823, -1, 17827, 16874, 16875, -1, 17829, 16874, 17830, -1, 17830, 16874, 17827, -1, 17831, 16873, 17832, -1, 17832, 16873, 17829, -1, 17829, 16873, 16874, -1, 16818, 17792, 16819, -1, 16819, 17792, 16822, -1, 16822, 17792, 16824, -1, 16824, 17792, 16826, -1, 16826, 17792, 16828, -1, 16828, 17792, 16830, -1, 16830, 17792, 16832, -1, 17831, 16872, 16873, -1, 17833, 16872, 17831, -1, 16832, 17794, 17834, -1, 17834, 17794, 17835, -1, 17792, 17794, 16832, -1, 17836, 16871, 17833, -1, 17833, 16871, 16872, -1, 16902, 17791, 16900, -1, 16900, 17791, 16898, -1, 16898, 17791, 16896, -1, 16896, 17791, 16894, -1, 16894, 17791, 16893, -1, 16893, 17791, 17790, -1, 16902, 16903, 17791, -1, 17835, 16870, 17837, -1, 17837, 16870, 17836, -1, 17836, 16870, 16871, -1, 17794, 16870, 17835, -1, 17794, 16869, 16870, -1, 16903, 17838, 17791, -1, 16905, 17838, 16903, -1, 17794, 16867, 16869, -1, 16905, 16907, 17838, -1, 16907, 16909, 17838, -1, 16909, 16910, 17838, -1, 16915, 17839, 16914, -1, 16914, 17839, 16913, -1, 16913, 17839, 16912, -1, 16912, 17839, 16911, -1, 16911, 17839, 16910, -1, 16910, 17839, 17838, -1, 17794, 17795, 16867, -1, 16868, 17795, 16917, -1, 16917, 17795, 16916, -1, 16916, 17795, 16915, -1, 16915, 17795, 17839, -1, 16867, 17795, 16868, -1, 17793, 17792, 16818, -1, 16820, 15770, 17840, -1, 15769, 16820, 16821, -1, 15769, 16821, 16823, -1, 15769, 16823, 16825, -1, 15769, 16825, 16827, -1, 15769, 16827, 16829, -1, 15769, 16829, 16831, -1, 17841, 16815, 16817, -1, 15769, 16831, 16833, -1, 17841, 17842, 16815, -1, 17843, 15770, 17844, -1, 15783, 16833, 17845, -1, 15783, 17845, 17846, -1, 15783, 17846, 17847, -1, 15783, 15769, 16833, -1, 17848, 15770, 17843, -1, 15774, 17849, 15773, -1, 17850, 15770, 15773, -1, 15774, 17851, 17852, -1, 15774, 17852, 17853, -1, 15774, 17853, 17854, -1, 17850, 17844, 15770, -1, 15774, 17854, 17855, -1, 15774, 17855, 17856, -1, 15774, 17856, 17857, -1, 15774, 17857, 17849, -1, 17858, 15770, 17848, -1, 17859, 17850, 15773, -1, 15780, 17860, 17861, -1, 15780, 17861, 17851, -1, 17862, 17859, 15773, -1, 15780, 17851, 15774, -1, 15779, 17860, 15780, -1, 15779, 17863, 17864, -1, 15779, 17864, 17860, -1, 16804, 15770, 17858, -1, 15784, 17847, 17865, -1, 15784, 17865, 17866, -1, 15784, 17866, 17863, -1, 16805, 15770, 16804, -1, 15784, 15783, 17847, -1, 15784, 17863, 15779, -1, 15769, 15770, 16820, -1, 17867, 16817, 17868, -1, 17867, 17841, 16817, -1, 17869, 17862, 15773, -1, 17867, 17868, 17870, -1, 17849, 17869, 15773, -1, 17871, 17867, 17870, -1, 17872, 17870, 17873, -1, 17872, 17873, 17874, -1, 17872, 17871, 17870, -1, 17875, 17872, 17874, -1, 17876, 17874, 17877, -1, 17876, 17877, 17851, -1, 17878, 16807, 16809, -1, 17876, 17875, 17874, -1, 17861, 17876, 17851, -1, 17879, 16809, 16811, -1, 17879, 17878, 16809, -1, 17880, 16811, 16813, -1, 17880, 17879, 16811, -1, 17881, 16807, 17878, -1, 17881, 16805, 16807, -1, 17840, 15770, 16805, -1, 17840, 16805, 17881, -1, 17842, 16813, 16815, -1, 17842, 17880, 16813, -1, 17838, 15779, 15780, -1, 17839, 15779, 17838, -1, 15556, 17747, 15555, -1, 15555, 17747, 17746, -1, 17811, 17810, 17841, -1, 17841, 17810, 17842, -1, 17842, 17807, 17880, -1, 17810, 17807, 17842, -1, 17880, 17806, 17879, -1, 17807, 17806, 17880, -1, 17879, 17805, 17878, -1, 17806, 17805, 17879, -1, 17878, 17808, 17881, -1, 17805, 17808, 17878, -1, 17881, 17809, 17840, -1, 17808, 17809, 17881, -1, 17840, 16818, 16820, -1, 17809, 16818, 17840, -1, 17811, 17841, 17816, -1, 17816, 17841, 17867, -1, 17834, 17835, 17845, -1, 17845, 17835, 17846, -1, 17846, 17837, 17847, -1, 17835, 17837, 17846, -1, 17847, 17836, 17865, -1, 17837, 17836, 17847, -1, 17865, 17833, 17866, -1, 17836, 17833, 17865, -1, 17866, 17831, 17863, -1, 17833, 17831, 17866, -1, 17863, 17832, 17864, -1, 17831, 17832, 17863, -1, 17864, 17829, 17860, -1, 17832, 17829, 17864, -1, 17860, 17830, 17861, -1, 17829, 17830, 17860, -1, 17861, 17827, 17876, -1, 17830, 17827, 17861, -1, 17876, 17828, 17875, -1, 17827, 17828, 17876, -1, 17875, 17823, 17872, -1, 17828, 17823, 17875, -1, 17872, 17822, 17871, -1, 17823, 17822, 17872, -1, 17871, 17816, 17867, -1, 17822, 17816, 17871, -1, 17845, 16832, 17834, -1, 16833, 16832, 17845, -1, 17802, 17801, 17862, -1, 17862, 17801, 17859, -1, 17859, 17799, 17850, -1, 17801, 17799, 17859, -1, 17850, 17797, 17844, -1, 17799, 17797, 17850, -1, 17844, 17796, 17843, -1, 17797, 17796, 17844, -1, 17843, 17798, 17848, -1, 17796, 17798, 17843, -1, 17848, 17800, 17858, -1, 17798, 17800, 17848, -1, 17858, 16802, 16804, -1, 17800, 16802, 17858, -1, 17802, 17862, 17803, -1, 17803, 17862, 17869, -1, 17817, 17818, 17868, -1, 17868, 17818, 17870, -1, 17870, 17824, 17873, -1, 17818, 17824, 17870, -1, 17873, 17825, 17874, -1, 17824, 17825, 17873, -1, 17874, 17826, 17877, -1, 17825, 17826, 17874, -1, 17877, 17820, 17851, -1, 17826, 17820, 17877, -1, 17851, 17821, 17852, -1, 17820, 17821, 17851, -1, 17852, 17819, 17853, -1, 17821, 17819, 17852, -1, 17853, 17812, 17854, -1, 17819, 17812, 17853, -1, 17854, 17813, 17855, -1, 17812, 17813, 17854, -1, 17855, 17814, 17856, -1, 17813, 17814, 17855, -1, 17856, 17815, 17857, -1, 17814, 17815, 17856, -1, 17857, 17804, 17849, -1, 17815, 17804, 17857, -1, 17849, 17803, 17869, -1, 17804, 17803, 17849, -1, 17868, 16816, 17817, -1, 16817, 16816, 17868, -1, 17726, 17723, 17778, -1, 17778, 17723, 17781, -1, 17781, 17719, 17785, -1, 17723, 17719, 17781, -1, 17785, 17715, 17789, -1, 17719, 17715, 17785, -1, 17789, 17717, 17750, -1, 17715, 17717, 17789, -1, 17750, 17721, 17754, -1, 17717, 17721, 17750, -1, 17754, 17711, 17755, -1, 17721, 17711, 17754, -1, 17755, 17709, 17761, -1, 17711, 17709, 17755, -1, 17761, 17707, 17762, -1, 17709, 17707, 17761, -1, 17762, 17704, 17783, -1, 17707, 17704, 17762, -1, 17783, 17705, 17782, -1, 17704, 17705, 17783, -1, 17782, 17706, 17779, -1, 17705, 17706, 17782, -1, 17779, 17708, 17776, -1, 17706, 17708, 17779, -1, 17776, 17710, 17775, -1, 17708, 17710, 17776, -1, 17778, 16800, 17726, -1, 16801, 16800, 17778, -1, 17712, 17713, 17774, -1, 17774, 17713, 17765, -1, 17765, 17730, 17763, -1, 17713, 17730, 17765, -1, 17763, 17728, 17758, -1, 17730, 17728, 17763, -1, 17758, 17727, 17759, -1, 17728, 17727, 17758, -1, 17759, 17729, 17760, -1, 17727, 17729, 17759, -1, 17760, 17732, 17764, -1, 17729, 17732, 17760, -1, 17764, 16786, 16788, -1, 17732, 16786, 17764, -1, 17712, 17774, 17710, -1, 17710, 17774, 17775, -1, 17740, 17739, 17767, -1, 17767, 17739, 17768, -1, 17768, 17741, 17769, -1, 17739, 17741, 17768, -1, 17769, 17742, 17770, -1, 17741, 17742, 17769, -1, 17770, 17743, 17771, -1, 17742, 17743, 17770, -1, 17771, 17744, 17772, -1, 17743, 17744, 17771, -1, 17772, 17745, 17773, -1, 17744, 17745, 17772, -1, 17773, 17724, 17753, -1, 17745, 17724, 17773, -1, 17753, 17720, 17748, -1, 17724, 17720, 17753, -1, 17748, 17714, 17749, -1, 17720, 17714, 17748, -1, 17749, 17716, 17788, -1, 17714, 17716, 17749, -1, 17788, 17718, 17784, -1, 17716, 17718, 17788, -1, 17784, 17722, 17780, -1, 17718, 17722, 17784, -1, 17780, 17725, 17777, -1, 17722, 17725, 17780, -1, 17767, 16784, 17740, -1, 16785, 16784, 17767, -1, 17731, 17733, 17766, -1, 17766, 17733, 17756, -1, 17756, 17734, 17757, -1, 17733, 17734, 17756, -1, 17757, 17735, 17787, -1, 17734, 17735, 17757, -1, 17787, 17736, 17786, -1, 17735, 17736, 17787, -1, 17786, 17737, 17752, -1, 17736, 17737, 17786, -1, 17752, 17738, 17751, -1, 17737, 17738, 17752, -1, 17751, 16770, 16772, -1, 17738, 16770, 17751, -1, 17731, 17766, 17725, -1, 17725, 17766, 17777, -1, 17838, 15780, 15774, -1, 17838, 15774, 17791, -1, 17790, 15773, 17793, -1, 17793, 15773, 15770, -1, 15783, 17794, 15769, -1, 15769, 17794, 17792, -1, 17795, 15784, 15779, -1, 17795, 15779, 17839, -1, 17699, 15547, 17701, -1, 17701, 15547, 15549, -1, 17747, 15556, 15559, -1, 17747, 15559, 17702, -1, 17700, 15551, 15555, -1, 17700, 15555, 17746, -1, 15545, 17698, 15558, -1, 15558, 17698, 17703, -1, 17882, 17883, 17884, -1, 17885, 17882, 17884, -1, 17886, 17887, 17888, -1, 17889, 17884, 17890, -1, 17886, 17888, 17891, -1, 17892, 17893, 17894, -1, 17895, 17885, 17884, -1, 17892, 17896, 17893, -1, 17895, 17884, 17889, -1, 17897, 17898, 17899, -1, 17900, 17890, 17901, -1, 17897, 17899, 17902, -1, 17900, 17901, 17903, -1, 17904, 17891, 17905, -1, 17900, 17895, 17889, -1, 17900, 17889, 17890, -1, 17906, 17907, 17908, -1, 17909, 17910, 17911, -1, 17906, 17908, 17912, -1, 17904, 17905, 17913, -1, 17909, 17911, 17914, -1, 17906, 17912, 17915, -1, 17916, 17915, 17917, -1, 17918, 17914, 17919, -1, 17916, 17917, 17920, -1, 17921, 17922, 17923, -1, 17916, 17920, 17924, -1, 17921, 17923, 17925, -1, 17926, 17927, 17928, -1, 17916, 17906, 17915, -1, 17929, 17930, 17931, -1, 17926, 17932, 17927, -1, 17929, 17933, 17934, -1, 17935, 17936, 17937, -1, 17929, 17934, 17930, -1, 17935, 17937, 17938, -1, 17939, 17940, 17941, -1, 17935, 17942, 17936, -1, 17943, 17929, 17931, -1, 17943, 17944, 17945, -1, 17943, 17931, 17946, -1, 17939, 17941, 17947, -1, 17908, 17948, 17949, -1, 17943, 17946, 17944, -1, 17908, 17894, 17948, -1, 17950, 17882, 17885, -1, 17950, 17951, 17882, -1, 17950, 17952, 17951, -1, 17953, 17947, 17887, -1, 17954, 17885, 17895, -1, 17955, 17956, 17957, -1, 17954, 17900, 17903, -1, 17953, 17887, 17886, -1, 17954, 17895, 17900, -1, 17955, 17958, 17956, -1, 17954, 17950, 17885, -1, 17959, 17898, 17897, -1, 17960, 17907, 17906, -1, 17960, 17961, 17907, -1, 17962, 17906, 17916, -1, 17959, 17913, 17898, -1, 17963, 17886, 17891, -1, 17962, 17960, 17906, -1, 17964, 17896, 17892, -1, 17964, 17938, 17896, -1, 17963, 17891, 17904, -1, 17965, 17957, 17910, -1, 17966, 17962, 17916, -1, 17967, 17922, 17921, -1, 17966, 17960, 17962, -1, 17967, 17968, 17922, -1, 17965, 17910, 17909, -1, 17969, 17966, 17916, -1, 17970, 17925, 17940, -1, 17971, 17916, 17924, -1, 17971, 17969, 17916, -1, 17971, 17924, 17972, -1, 17973, 17909, 17914, -1, 17971, 17972, 17974, -1, 17973, 17914, 17918, -1, 17975, 17932, 17926, -1, 17975, 17976, 17932, -1, 17977, 17933, 17929, -1, 17970, 17940, 17939, -1, 17977, 17978, 17933, -1, 17979, 17929, 17943, -1, 17979, 17977, 17929, -1, 17907, 17892, 17894, -1, 17907, 17894, 17908, -1, 17980, 17979, 17943, -1, 17980, 17977, 17979, -1, 17981, 17947, 17953, -1, 17982, 17928, 17958, -1, 17981, 17939, 17947, -1, 17983, 17904, 17913, -1, 17983, 17913, 17959, -1, 17982, 17958, 17955, -1, 17984, 17980, 17943, -1, 17985, 17986, 17987, -1, 17985, 17943, 17945, -1, 17985, 17984, 17943, -1, 17988, 17953, 17886, -1, 17985, 17945, 17986, -1, 17989, 17952, 17950, -1, 17989, 17990, 17952, -1, 17991, 17989, 17950, -1, 17988, 17886, 17963, -1, 17992, 17993, 17942, -1, 17992, 17942, 17935, -1, 17994, 17945, 17968, -1, 17992, 17935, 17938, -1, 17991, 17950, 17954, -1, 17992, 17938, 17964, -1, 17995, 17991, 17954, -1, 17996, 17957, 17965, -1, 17994, 17968, 17967, -1, 17995, 17989, 17991, -1, 17997, 17925, 17970, -1, 17996, 17955, 17957, -1, 17997, 17921, 17925, -1, 17998, 17995, 17954, -1, 17999, 17919, 18000, -1, 17999, 17918, 17919, -1, 18001, 17998, 17954, -1, 18001, 18002, 18003, -1, 18001, 17903, 18002, -1, 18001, 17954, 17903, -1, 18004, 17965, 17909, -1, 18005, 17970, 17939, -1, 18004, 17909, 17973, -1, 18006, 17966, 17969, -1, 18006, 17961, 17960, -1, 18006, 17960, 17966, -1, 18005, 17939, 17981, -1, 18007, 18006, 17969, -1, 18007, 17974, 18008, -1, 18009, 17976, 17975, -1, 18010, 17963, 17904, -1, 18009, 18011, 17976, -1, 18007, 17969, 17971, -1, 17961, 17892, 17907, -1, 18007, 17971, 17974, -1, 18010, 17904, 17983, -1, 18012, 17978, 17977, -1, 17961, 17964, 17892, -1, 18012, 17977, 17980, -1, 18013, 17926, 17928, -1, 18012, 17980, 17984, -1, 18014, 18012, 17984, -1, 18015, 17953, 17988, -1, 18013, 17928, 17982, -1, 18014, 17985, 17987, -1, 18015, 17981, 17953, -1, 18014, 17987, 18016, -1, 18014, 17984, 17985, -1, 18017, 17989, 17995, -1, 18018, 17945, 17994, -1, 18017, 17995, 17998, -1, 18018, 17986, 17945, -1, 18017, 17990, 17989, -1, 18019, 17967, 17921, -1, 18020, 18017, 17998, -1, 18020, 17998, 18001, -1, 18021, 17982, 17955, -1, 18020, 18001, 18003, -1, 18019, 17921, 17997, -1, 18021, 17955, 17996, -1, 18020, 18003, 18022, -1, 18023, 17961, 18006, -1, 18023, 18024, 17961, -1, 18025, 17970, 18005, -1, 18023, 17993, 18024, -1, 18026, 17918, 17999, -1, 18025, 17997, 17970, -1, 18027, 17993, 18023, -1, 18027, 18028, 17993, -1, 18026, 17973, 17918, -1, 18027, 18023, 18006, -1, 18029, 17996, 17965, -1, 18029, 17965, 18004, -1, 18030, 17963, 18010, -1, 18030, 17988, 17963, -1, 18031, 18006, 18007, -1, 18032, 18028, 18027, -1, 18033, 18011, 18009, -1, 18032, 18027, 18006, -1, 18032, 18006, 18031, -1, 18034, 18008, 18028, -1, 18034, 18031, 18007, -1, 18033, 18035, 18011, -1, 18034, 18032, 18031, -1, 18034, 18007, 18008, -1, 18036, 18005, 17981, -1, 18024, 17992, 17964, -1, 18034, 18028, 18032, -1, 18036, 17981, 18015, -1, 18024, 17964, 17961, -1, 18037, 18038, 17978, -1, 18039, 17987, 17986, -1, 18037, 17978, 18012, -1, 18024, 17993, 17992, -1, 18040, 17926, 18013, -1, 18039, 17986, 18018, -1, 18037, 18041, 18038, -1, 18042, 18037, 18012, -1, 18042, 18041, 18037, -1, 18042, 18043, 18041, -1, 18044, 17994, 17967, -1, 18044, 17967, 18019, -1, 18040, 17975, 17926, -1, 18045, 18012, 18014, -1, 18046, 18042, 18012, -1, 18047, 17997, 18025, -1, 18046, 18043, 18042, -1, 18046, 18012, 18045, -1, 18048, 17982, 18021, -1, 18049, 18014, 18016, -1, 18047, 18019, 17997, -1, 18048, 18013, 17982, -1, 18049, 18045, 18014, -1, 18049, 18046, 18045, -1, 18049, 18043, 18046, -1, 18049, 18016, 18043, -1, 18050, 17990, 18017, -1, 18051, 18004, 17973, -1, 18052, 18015, 17988, -1, 18051, 17973, 18026, -1, 18052, 17988, 18030, -1, 18050, 18053, 18054, -1, 18050, 18054, 17990, -1, 18055, 18050, 18017, -1, 18055, 18056, 18053, -1, 18057, 17996, 18029, -1, 18055, 18053, 18050, -1, 18057, 18021, 17996, -1, 18058, 18025, 18005, -1, 18058, 18005, 18036, -1, 18059, 18060, 18043, -1, 18061, 18062, 18035, -1, 18063, 18017, 18020, -1, 18059, 18043, 18016, -1, 18061, 18035, 18033, -1, 18064, 18055, 18017, -1, 18059, 17987, 18039, -1, 18059, 18016, 17987, -1, 18064, 18056, 18055, -1, 18064, 18017, 18063, -1, 18065, 18020, 18022, -1, 18065, 18022, 18056, -1, 18066, 18009, 17975, -1, 18065, 18063, 18020, -1, 18065, 18056, 18064, -1, 18067, 18018, 17994, -1, 18065, 18064, 18063, -1, 18067, 17994, 18044, -1, 18068, 18044, 18019, -1, 18068, 18019, 18047, -1, 18066, 17975, 18040, -1, 18069, 18015, 18052, -1, 18070, 18040, 18013, -1, 18069, 18036, 18015, -1, 18070, 18013, 18048, -1, 18071, 18047, 18025, -1, 18072, 18029, 18004, -1, 18072, 18004, 18051, -1, 18071, 18025, 18058, -1, 18073, 18018, 18067, -1, 18073, 18039, 18018, -1, 18074, 18075, 18076, -1, 18074, 18076, 18077, -1, 18078, 18067, 18044, -1, 18079, 18048, 18021, -1, 18078, 18044, 18068, -1, 18079, 18021, 18057, -1, 17883, 18036, 18069, -1, 18079, 18070, 18048, -1, 18080, 18081, 18075, -1, 18082, 18083, 18062, -1, 18080, 18075, 18074, -1, 17883, 18058, 18036, -1, 18082, 18062, 18061, -1, 18084, 18068, 18047, -1, 18084, 18047, 18071, -1, 18085, 18086, 18081, -1, 18087, 18060, 18059, -1, 18087, 18059, 18039, -1, 18088, 18009, 18066, -1, 18085, 18081, 18080, -1, 18088, 18033, 18009, -1, 18087, 18039, 18073, -1, 18089, 18077, 18090, -1, 18087, 18091, 18060, -1, 18092, 18073, 18067, -1, 18089, 18074, 18077, -1, 18092, 18067, 18078, -1, 18093, 18058, 17883, -1, 18094, 18040, 18070, -1, 18093, 18071, 18058, -1, 18094, 18066, 18040, -1, 18095, 18096, 18086, -1, 18097, 18029, 18072, -1, 18097, 18057, 18029, -1, 18095, 18086, 18085, -1, 18098, 18068, 18084, -1, 18098, 18078, 18068, -1, 18099, 18074, 18089, -1, 18100, 18073, 18092, -1, 18099, 18080, 18074, -1, 18100, 18087, 18073, -1, 18101, 18090, 18102, -1, 18100, 18091, 18087, -1, 18101, 18089, 18090, -1, 17951, 18071, 18093, -1, 18103, 18070, 18079, -1, 17951, 18084, 18071, -1, 18104, 17924, 18083, -1, 18105, 18106, 18096, -1, 18107, 18078, 18098, -1, 18105, 18096, 18095, -1, 18107, 18092, 18078, -1, 18104, 18083, 18082, -1, 18108, 18033, 18088, -1, 18109, 18085, 18080, -1, 18108, 18061, 18033, -1, 18109, 18080, 18099, -1, 17952, 18098, 18084, -1, 17952, 18084, 17951, -1, 18110, 18100, 18092, -1, 18110, 18091, 18100, -1, 18111, 18099, 18089, -1, 18110, 18092, 18107, -1, 18110, 18053, 18091, -1, 18111, 18089, 18101, -1, 18112, 18088, 18066, -1, 18112, 18066, 18094, -1, 17990, 18107, 18098, -1, 18113, 18101, 18102, -1, 17990, 18110, 18107, -1, 17990, 18098, 17952, -1, 18114, 18079, 18057, -1, 18114, 18057, 18097, -1, 18115, 18116, 18106, -1, 18054, 18053, 18110, -1, 18115, 18106, 18105, -1, 18054, 18110, 17990, -1, 18117, 18118, 18119, -1, 18120, 18095, 18085, -1, 18120, 18085, 18109, -1, 18121, 18070, 18103, -1, 18121, 18094, 18070, -1, 18122, 18123, 18124, -1, 18125, 18109, 18099, -1, 18126, 18118, 18117, -1, 18126, 18124, 18127, -1, 18125, 18099, 18111, -1, 18126, 18128, 18118, -1, 18129, 17972, 17924, -1, 18129, 17924, 18104, -1, 18130, 18101, 18113, -1, 18126, 18117, 18131, -1, 18126, 18131, 18122, -1, 18126, 18122, 18124, -1, 18130, 18111, 18101, -1, 18132, 18133, 18128, -1, 18134, 18135, 18136, -1, 18132, 18127, 18137, -1, 18134, 18138, 18135, -1, 18132, 18126, 18127, -1, 18132, 18128, 18126, -1, 18139, 18140, 18116, -1, 18141, 18142, 18133, -1, 18143, 18082, 18061, -1, 18141, 18133, 18132, -1, 18139, 18116, 18115, -1, 18141, 18132, 18137, -1, 18141, 18137, 17927, -1, 18143, 18061, 18108, -1, 18144, 18095, 18120, -1, 18145, 18088, 18112, -1, 18146, 18142, 18141, -1, 18146, 18141, 17927, -1, 18145, 18108, 18088, -1, 18144, 18105, 18095, -1, 18147, 18103, 18079, -1, 18148, 18026, 17999, -1, 18147, 18079, 18114, -1, 18149, 18120, 18109, -1, 18149, 18109, 18125, -1, 18119, 18102, 18150, -1, 18119, 18113, 18102, -1, 18151, 18138, 18152, -1, 18153, 18151, 18152, -1, 18154, 18125, 18111, -1, 18153, 18155, 18151, -1, 18153, 18152, 18156, -1, 18154, 18111, 18130, -1, 18153, 18051, 18026, -1, 18157, 18112, 18094, -1, 18157, 18094, 18121, -1, 18153, 18026, 18148, -1, 18153, 18148, 18155, -1, 18158, 18051, 18153, -1, 18159, 18160, 18161, -1, 18158, 18156, 18162, -1, 18157, 18145, 18112, -1, 18159, 18161, 18140, -1, 18159, 18140, 18139, -1, 18163, 17972, 18129, -1, 18158, 18072, 18051, -1, 18158, 18153, 18156, -1, 18164, 18072, 18158, -1, 18164, 18158, 18162, -1, 18163, 18008, 17974, -1, 18163, 17974, 17972, -1, 18164, 18162, 18165, -1, 18166, 18115, 18105, -1, 18167, 18138, 18134, -1, 18166, 18105, 18144, -1, 18164, 18097, 18072, -1, 18168, 18097, 18164, -1, 18168, 18164, 18165, -1, 18167, 18152, 18138, -1, 18169, 18120, 18149, -1, 18170, 18104, 18082, -1, 18170, 18082, 18143, -1, 18169, 18144, 18120, -1, 18118, 18130, 18113, -1, 18118, 18113, 18119, -1, 18171, 17902, 18172, -1, 18173, 18143, 18108, -1, 18173, 18108, 18145, -1, 18174, 18149, 18125, -1, 18175, 18121, 18103, -1, 18175, 18103, 18147, -1, 18174, 18125, 18154, -1, 18176, 18177, 18178, -1, 18179, 17902, 18171, -1, 18179, 17897, 17902, -1, 18179, 18180, 18176, -1, 18179, 18176, 18178, -1, 18181, 18160, 18159, -1, 18179, 18178, 18182, -1, 18183, 18115, 18166, -1, 18179, 18171, 18180, -1, 18184, 17897, 18179, -1, 18184, 18179, 18182, -1, 18184, 17959, 17897, -1, 18184, 18182, 18185, -1, 18186, 18145, 18157, -1, 18183, 18139, 18115, -1, 18187, 18184, 18185, -1, 18187, 18185, 18188, -1, 18189, 18166, 18144, -1, 18187, 17983, 17959, -1, 18190, 18028, 18008, -1, 18187, 17959, 18184, -1, 18190, 18008, 18163, -1, 18190, 18191, 18028, -1, 18192, 17983, 18187, -1, 18189, 18144, 18169, -1, 18193, 18156, 18152, -1, 18192, 18187, 18188, -1, 18128, 18130, 18118, -1, 18128, 18154, 18130, -1, 18193, 18152, 18167, -1, 18194, 18117, 18119, -1, 18194, 18119, 18150, -1, 18195, 18169, 18149, -1, 18196, 18194, 18150, -1, 18197, 18129, 18104, -1, 18195, 18149, 18174, -1, 18197, 18104, 18170, -1, 18198, 18196, 18150, -1, 18199, 18200, 18160, -1, 18198, 18122, 18131, -1, 18201, 18170, 18143, -1, 18202, 18196, 18198, -1, 18199, 18160, 18181, -1, 18202, 18198, 18131, -1, 18201, 18143, 18173, -1, 18202, 18117, 18194, -1, 18202, 18131, 18117, -1, 18202, 18194, 18196, -1, 18203, 18150, 18204, -1, 18203, 18198, 18150, -1, 18203, 18122, 18198, -1, 18205, 18157, 18121, -1, 18203, 18123, 18122, -1, 18206, 18159, 18139, -1, 18203, 18204, 18123, -1, 18206, 18139, 18183, -1, 18207, 18208, 18142, -1, 18207, 18209, 18208, -1, 18205, 18121, 18175, -1, 18207, 18142, 18146, -1, 18210, 18136, 18211, -1, 18212, 18183, 18166, -1, 18212, 18166, 18189, -1, 18213, 18207, 18146, -1, 18210, 18134, 18136, -1, 18214, 17932, 17976, -1, 18214, 18213, 18146, -1, 18214, 18146, 17927, -1, 18133, 18174, 18154, -1, 18214, 17927, 17932, -1, 18133, 18154, 18128, -1, 18215, 17999, 18000, -1, 18215, 18148, 17999, -1, 18216, 18173, 18145, -1, 18217, 18215, 18000, -1, 18218, 18169, 18195, -1, 18216, 18145, 18186, -1, 18219, 18151, 18155, -1, 18220, 18162, 18156, -1, 18219, 18217, 18000, -1, 18218, 18189, 18169, -1, 18221, 18148, 18215, -1, 18221, 18219, 18155, -1, 18221, 18215, 18217, -1, 18221, 18217, 18219, -1, 18222, 18223, 18200, -1, 18221, 18155, 18148, -1, 18224, 18000, 18135, -1, 18222, 18200, 18199, -1, 18224, 18135, 18138, -1, 18220, 18156, 18193, -1, 18224, 18151, 18219, -1, 18225, 18129, 18197, -1, 18224, 18219, 18000, -1, 18224, 18138, 18151, -1, 18226, 18147, 18114, -1, 18227, 18159, 18206, -1, 18226, 18097, 18168, -1, 18226, 18114, 18097, -1, 18225, 18163, 18129, -1, 18228, 18197, 18170, -1, 18227, 18181, 18159, -1, 18228, 18170, 18201, -1, 18229, 18206, 18183, -1, 18230, 18226, 18168, -1, 18231, 18186, 18157, -1, 18229, 18183, 18212, -1, 18232, 18233, 18234, -1, 18142, 18174, 18133, -1, 18232, 18168, 18165, -1, 18231, 18157, 18205, -1, 18142, 18195, 18174, -1, 18232, 18230, 18168, -1, 18232, 18165, 18233, -1, 18235, 18171, 18172, -1, 18236, 18134, 18210, -1, 18236, 18167, 18134, -1, 18235, 18172, 18237, -1, 18235, 18180, 18171, -1, 18238, 18180, 18235, -1, 18238, 18237, 18239, -1, 18238, 18235, 18237, -1, 18240, 18176, 18180, -1, 18240, 18177, 18176, -1, 18240, 18239, 18177, -1, 18240, 18180, 18238, -1, 18241, 18189, 18218, -1, 18240, 18238, 18239, -1, 18242, 17983, 18192, -1, 18241, 18212, 18189, -1, 18242, 18010, 17983, -1, 18242, 18030, 18010, -1, 18243, 18201, 18173, -1, 18244, 18245, 18223, -1, 18243, 18173, 18216, -1, 18246, 18242, 18192, -1, 18247, 18211, 18248, -1, 18244, 18223, 18222, -1, 18249, 18199, 18181, -1, 18250, 18246, 18192, -1, 18250, 18192, 18188, -1, 18247, 18210, 18211, -1, 18250, 18251, 18252, -1, 18250, 18188, 18251, -1, 18249, 18181, 18227, -1, 18253, 18206, 18229, -1, 18254, 18209, 18207, -1, 18254, 18207, 18213, -1, 18255, 18165, 18162, -1, 18254, 18256, 18209, -1, 18255, 18162, 18220, -1, 18253, 18227, 18206, -1, 18257, 18254, 18213, -1, 18208, 18218, 18195, -1, 18258, 18259, 18191, -1, 18258, 18190, 18163, -1, 18258, 18191, 18190, -1, 18258, 18163, 18225, -1, 18208, 18195, 18142, -1, 18260, 18257, 18213, -1, 18260, 18213, 18214, -1, 18260, 18214, 17976, -1, 18261, 18225, 18197, -1, 18260, 17976, 18011, -1, 18262, 18147, 18226, -1, 18261, 18197, 18228, -1, 18262, 18175, 18147, -1, 18262, 18226, 18230, -1, 18263, 18186, 18231, -1, 18264, 18229, 18212, -1, 18263, 18216, 18186, -1, 18264, 18212, 18241, -1, 18265, 18262, 18230, -1, 18266, 18234, 18267, -1, 18268, 18269, 18245, -1, 18266, 18232, 18234, -1, 18268, 18245, 18244, -1, 18266, 18265, 18230, -1, 18266, 18230, 18232, -1, 18270, 18193, 18167, -1, 18270, 18167, 18236, -1, 18271, 18052, 18030, -1, 18272, 18204, 18273, -1, 18271, 18030, 18242, -1, 18271, 18242, 18246, -1, 18274, 18271, 18246, -1, 18272, 18123, 18204, -1, 18275, 18222, 18199, -1, 18275, 18199, 18249, -1, 18276, 18252, 18277, -1, 18278, 18201, 18243, -1, 18276, 18274, 18246, -1, 18278, 18228, 18201, -1, 18276, 18246, 18250, -1, 18279, 18249, 18227, -1, 18276, 18250, 18252, -1, 18280, 18210, 18247, -1, 18279, 18227, 18253, -1, 18281, 18254, 18257, -1, 18281, 18282, 18256, -1, 18209, 18241, 18218, -1, 18281, 18256, 18254, -1, 18209, 18218, 18208, -1, 18283, 18257, 18260, -1, 18280, 18236, 18210, -1, 18283, 18260, 18011, -1, 18284, 18247, 18248, -1, 18283, 18011, 18035, -1, 18285, 18175, 18262, -1, 18286, 18165, 18255, -1, 18285, 18205, 18175, -1, 18285, 18262, 18265, -1, 18287, 18265, 18266, -1, 18287, 18266, 18267, -1, 18286, 18233, 18165, -1, 18288, 18253, 18229, -1, 18287, 18267, 17923, -1, 18289, 18258, 18225, -1, 18288, 18229, 18264, -1, 18289, 18259, 18258, -1, 18289, 18225, 18261, -1, 18290, 18069, 18052, -1, 17934, 18243, 18216, -1, 18291, 18292, 18269, -1, 18290, 18271, 18274, -1, 18290, 18052, 18271, -1, 18291, 18269, 18268, -1, 18293, 18276, 18277, -1, 17934, 18216, 18263, -1, 18293, 18274, 18276, -1, 18294, 18193, 18270, -1, 18293, 18277, 18295, -1, 18296, 18282, 18281, -1, 18296, 18297, 18282, -1, 18298, 18123, 18272, -1, 18298, 18124, 18123, -1, 18294, 18220, 18193, -1, 18299, 18244, 18222, -1, 18300, 18296, 18281, -1, 18300, 18281, 18257, -1, 18299, 18222, 18275, -1, 18300, 18257, 18283, -1, 18301, 18275, 18249, -1, 18301, 18249, 18279, -1, 18302, 18296, 18300, -1, 18303, 18261, 18228, -1, 18303, 18289, 18261, -1, 18256, 18264, 18241, -1, 18303, 18228, 18278, -1, 18256, 18241, 18209, -1, 18304, 18300, 18283, -1, 18305, 18270, 18236, -1, 18304, 18302, 18300, -1, 18305, 18236, 18280, -1, 18306, 18283, 18035, -1, 18306, 18035, 18062, -1, 18306, 18304, 18283, -1, 18307, 18231, 18205, -1, 17899, 18280, 18247, -1, 18307, 18205, 18285, -1, 18308, 18285, 18265, -1, 18308, 18265, 18287, -1, 17899, 18247, 18284, -1, 18309, 18279, 18253, -1, 17941, 18234, 18233, -1, 18309, 18253, 18288, -1, 18308, 18307, 18285, -1, 18310, 18311, 18312, -1, 18310, 18312, 18292, -1, 18310, 18313, 18311, -1, 18310, 18292, 18291, -1, 18314, 18307, 18308, -1, 17956, 18127, 18124, -1, 17941, 18233, 18286, -1, 18315, 18314, 18308, -1, 17933, 18243, 17934, -1, 17956, 18124, 18298, -1, 17933, 18278, 18243, -1, 18315, 18308, 18287, -1, 17888, 18255, 18220, -1, 18316, 18287, 17923, -1, 18316, 17923, 17922, -1, 17888, 18220, 18294, -1, 18316, 18315, 18287, -1, 18317, 17883, 18069, -1, 18318, 18268, 18244, -1, 18318, 18244, 18299, -1, 18317, 18069, 18290, -1, 18319, 18290, 18274, -1, 17893, 18275, 18301, -1, 18319, 18274, 18293, -1, 17893, 18299, 18275, -1, 18319, 18317, 18290, -1, 18320, 18317, 18319, -1, 18282, 18288, 18264, -1, 18321, 18259, 18289, -1, 18321, 18041, 18259, -1, 18282, 18264, 18256, -1, 18321, 18289, 18303, -1, 17911, 18272, 18273, -1, 17905, 18270, 18305, -1, 17911, 18273, 18322, -1, 18323, 18320, 18319, -1, 18323, 18319, 18293, -1, 18324, 18295, 18325, -1, 17905, 18294, 18270, -1, 18324, 18293, 18295, -1, 18172, 18248, 18237, -1, 18324, 18323, 18293, -1, 18172, 18284, 18248, -1, 18326, 18297, 18296, -1, 18326, 18296, 18302, -1, 18326, 18302, 18304, -1, 17898, 18280, 17899, -1, 17948, 18301, 18279, -1, 18327, 18062, 18083, -1, 17948, 18279, 18309, -1, 18327, 18326, 18304, -1, 18327, 18306, 18062, -1, 17898, 18305, 18280, -1, 18327, 18304, 18306, -1, 17940, 18267, 18234, -1, 17958, 18137, 18127, -1, 18328, 18231, 18307, -1, 17940, 18234, 17941, -1, 17958, 18127, 17956, -1, 18328, 18314, 18315, -1, 18328, 18307, 18314, -1, 18329, 17922, 17968, -1, 17937, 18268, 18318, -1, 17978, 18278, 17933, -1, 18329, 18316, 17922, -1, 18329, 18315, 18316, -1, 17978, 18303, 18278, -1, 17937, 18291, 18268, -1, 18329, 18328, 18315, -1, 17884, 17883, 18317, -1, 17896, 18318, 18299, -1, 17887, 18286, 18255, -1, 17884, 18317, 18320, -1, 17896, 18299, 17893, -1, 17884, 18320, 18323, -1, 17890, 17884, 18323, -1, 17887, 18255, 17888, -1, 18297, 18288, 18282, -1, 17890, 18325, 17901, -1, 17890, 18324, 18325, -1, 17890, 18323, 18324, -1, 18297, 18309, 18288, -1, 17912, 18297, 18326, -1, 17912, 17908, 17949, -1, 17912, 17949, 18297, -1, 17910, 18298, 18272, -1, 17910, 18272, 17911, -1, 17915, 17912, 18326, -1, 17891, 17888, 18294, -1, 17891, 18294, 17905, -1, 18330, 18326, 18327, -1, 17902, 18284, 18172, -1, 17894, 17893, 18301, -1, 17902, 17899, 18284, -1, 17917, 18326, 18330, -1, 17917, 17915, 18326, -1, 17894, 18301, 17948, -1, 17920, 18330, 18327, -1, 17914, 18322, 17919, -1, 17920, 17917, 18330, -1, 17920, 18327, 18083, -1, 17920, 18083, 17924, -1, 17914, 17911, 18322, -1, 17928, 18137, 17958, -1, 17930, 17934, 18263, -1, 17913, 17905, 18305, -1, 17930, 18231, 18328, -1, 17930, 18263, 18231, -1, 17913, 18305, 17898, -1, 17928, 17927, 18137, -1, 17931, 17930, 18328, -1, 17936, 18310, 18291, -1, 17925, 17923, 18267, -1, 17936, 18313, 18310, -1, 17925, 18267, 17940, -1, 17936, 17942, 18313, -1, 17936, 18291, 17937, -1, 17938, 17937, 18318, -1, 17938, 18318, 17896, -1, 18038, 18041, 18321, -1, 18038, 18321, 18303, -1, 18331, 18328, 18329, -1, 18038, 18303, 17978, -1, 17946, 17931, 18328, -1, 17949, 17948, 18309, -1, 17946, 18328, 18331, -1, 17944, 17968, 17945, -1, 17947, 17941, 18286, -1, 17944, 18331, 18329, -1, 17949, 18309, 18297, -1, 17944, 17946, 18331, -1, 17944, 18329, 17968, -1, 17947, 18286, 17887, -1, 17957, 18298, 17910, -1, 17882, 17951, 18093, -1, 17882, 18093, 17883, -1, 17957, 17956, 18298, -1, 18332, 18333, 18334, -1, 18335, 18336, 18337, -1, 18338, 18339, 18340, -1, 18341, 18340, 18342, -1, 18332, 18343, 18333, -1, 18344, 18338, 18340, -1, 18344, 18340, 18341, -1, 18345, 18346, 18347, -1, 18348, 18342, 18349, -1, 18345, 18347, 18350, -1, 18351, 18352, 18353, -1, 18348, 18349, 18354, -1, 18351, 18355, 18352, -1, 18348, 18341, 18342, -1, 18356, 18334, 18357, -1, 18348, 18344, 18341, -1, 18358, 18359, 18360, -1, 18358, 18360, 18361, -1, 18358, 18361, 18362, -1, 18363, 18364, 18365, -1, 18356, 18357, 18366, -1, 18367, 18362, 18368, -1, 18363, 18365, 18369, -1, 18367, 18368, 18370, -1, 18367, 18370, 18371, -1, 18367, 18358, 18362, -1, 18372, 18373, 18374, -1, 18375, 18369, 18376, -1, 18377, 18378, 18379, -1, 18380, 18381, 18382, -1, 18377, 18383, 18384, -1, 18377, 18379, 18383, -1, 18385, 18386, 18387, -1, 18380, 18388, 18381, -1, 18389, 18384, 18390, -1, 18385, 18391, 18386, -1, 18389, 18392, 18393, -1, 18389, 18390, 18392, -1, 18394, 18395, 18396, -1, 18394, 18396, 18397, -1, 18389, 18377, 18384, -1, 18394, 18398, 18395, -1, 18360, 18399, 18400, -1, 18401, 18402, 18339, -1, 18401, 18339, 18338, -1, 18401, 18403, 18402, -1, 18360, 18351, 18353, -1, 18404, 18387, 18343, -1, 18360, 18353, 18399, -1, 18405, 18401, 18338, -1, 18405, 18338, 18344, -1, 18405, 18348, 18354, -1, 18404, 18343, 18332, -1, 18405, 18344, 18348, -1, 18406, 18336, 18335, -1, 18407, 18408, 18359, -1, 18409, 18346, 18345, -1, 18407, 18359, 18358, -1, 18406, 18410, 18336, -1, 18411, 18358, 18367, -1, 18409, 18366, 18346, -1, 18411, 18407, 18358, -1, 18412, 18332, 18334, -1, 18413, 18397, 18355, -1, 18414, 18407, 18411, -1, 18412, 18334, 18356, -1, 18414, 18411, 18367, -1, 18415, 18373, 18372, -1, 18413, 18355, 18351, -1, 18416, 18414, 18367, -1, 18417, 18335, 18364, -1, 18415, 18418, 18373, -1, 18419, 18374, 18391, -1, 18417, 18364, 18363, -1, 18419, 18391, 18385, -1, 18420, 18367, 18371, -1, 18420, 18371, 18421, -1, 18420, 18416, 18367, -1, 18420, 18421, 18422, -1, 18423, 18363, 18369, -1, 18424, 18378, 18377, -1, 18424, 18425, 18378, -1, 18423, 18369, 18375, -1, 18426, 18388, 18380, -1, 18427, 18377, 18389, -1, 18426, 18428, 18388, -1, 18427, 18424, 18377, -1, 18429, 18385, 18387, -1, 18430, 18427, 18389, -1, 18359, 18351, 18360, -1, 18430, 18424, 18427, -1, 18429, 18387, 18404, -1, 18431, 18356, 18366, -1, 18431, 18366, 18409, -1, 18432, 18382, 18410, -1, 18433, 18430, 18389, -1, 18432, 18410, 18406, -1, 18434, 18435, 18436, -1, 18434, 18393, 18435, -1, 18434, 18389, 18393, -1, 18434, 18433, 18389, -1, 18437, 18403, 18401, -1, 18438, 18404, 18332, -1, 18437, 18439, 18403, -1, 18440, 18437, 18401, -1, 18438, 18332, 18412, -1, 18441, 18435, 18393, -1, 18441, 18418, 18415, -1, 18440, 18401, 18405, -1, 18442, 18397, 18413, -1, 18442, 18443, 18398, -1, 18444, 18440, 18405, -1, 18442, 18398, 18394, -1, 18442, 18394, 18397, -1, 18441, 18393, 18418, -1, 18445, 18374, 18419, -1, 18444, 18437, 18440, -1, 18445, 18372, 18374, -1, 18446, 18335, 18417, -1, 18446, 18406, 18335, -1, 18447, 18444, 18405, -1, 18448, 18376, 18449, -1, 18450, 18447, 18405, -1, 18450, 18405, 18354, -1, 18448, 18375, 18376, -1, 18450, 18451, 18452, -1, 18450, 18354, 18451, -1, 18453, 18408, 18407, -1, 18454, 18419, 18385, -1, 18455, 18417, 18363, -1, 18453, 18407, 18414, -1, 18453, 18414, 18416, -1, 18455, 18363, 18423, -1, 18454, 18385, 18429, -1, 18456, 18453, 18416, -1, 18456, 18416, 18420, -1, 18456, 18420, 18422, -1, 18456, 18422, 18457, -1, 18458, 18356, 18431, -1, 18458, 18412, 18356, -1, 18459, 18428, 18426, -1, 18459, 18460, 18428, -1, 18461, 18425, 18424, -1, 18408, 18351, 18359, -1, 18461, 18424, 18430, -1, 18461, 18430, 18433, -1, 18462, 18429, 18404, -1, 18408, 18413, 18351, -1, 18463, 18461, 18433, -1, 18463, 18434, 18436, -1, 18462, 18404, 18438, -1, 18463, 18436, 18464, -1, 18465, 18380, 18382, -1, 18463, 18433, 18434, -1, 18466, 18439, 18437, -1, 18467, 18435, 18441, -1, 18465, 18382, 18432, -1, 18466, 18437, 18444, -1, 18466, 18444, 18447, -1, 18468, 18450, 18452, -1, 18469, 18372, 18445, -1, 18468, 18452, 18470, -1, 18468, 18447, 18450, -1, 18468, 18466, 18447, -1, 18471, 18432, 18406, -1, 18469, 18415, 18372, -1, 18472, 18473, 18408, -1, 18474, 18419, 18454, -1, 18474, 18445, 18419, -1, 18472, 18408, 18453, -1, 18471, 18406, 18446, -1, 18472, 18443, 18473, -1, 18475, 18375, 18448, -1, 18476, 18443, 18472, -1, 18476, 18472, 18453, -1, 18476, 18477, 18443, -1, 18475, 18423, 18375, -1, 18478, 18438, 18412, -1, 18479, 18446, 18417, -1, 18480, 18453, 18456, -1, 18478, 18412, 18458, -1, 18481, 18477, 18476, -1, 18481, 18476, 18453, -1, 18479, 18417, 18455, -1, 18481, 18453, 18480, -1, 18482, 18457, 18477, -1, 18483, 18460, 18459, -1, 18482, 18480, 18456, -1, 18484, 18429, 18462, -1, 18482, 18481, 18480, -1, 18484, 18454, 18429, -1, 18482, 18477, 18481, -1, 18482, 18456, 18457, -1, 18483, 18485, 18460, -1, 18486, 18487, 18425, -1, 18488, 18436, 18435, -1, 18488, 18435, 18467, -1, 18473, 18443, 18442, -1, 18486, 18425, 18461, -1, 18473, 18413, 18408, -1, 18486, 18489, 18487, -1, 18473, 18442, 18413, -1, 18490, 18380, 18465, -1, 18491, 18489, 18486, -1, 18491, 18492, 18489, -1, 18491, 18486, 18461, -1, 18493, 18415, 18469, -1, 18493, 18441, 18415, -1, 18494, 18461, 18463, -1, 18490, 18426, 18380, -1, 18495, 18491, 18461, -1, 18495, 18492, 18491, -1, 18496, 18469, 18445, -1, 18495, 18461, 18494, -1, 18496, 18445, 18474, -1, 18497, 18463, 18464, -1, 18497, 18494, 18463, -1, 18497, 18492, 18495, -1, 18498, 18432, 18471, -1, 18497, 18495, 18494, -1, 18498, 18465, 18432, -1, 18497, 18464, 18492, -1, 18499, 18439, 18466, -1, 18500, 18462, 18438, -1, 18500, 18438, 18478, -1, 18501, 18423, 18475, -1, 18499, 18502, 18503, -1, 18501, 18455, 18423, -1, 18499, 18503, 18439, -1, 18504, 18499, 18466, -1, 18504, 18505, 18502, -1, 18506, 18474, 18454, -1, 18504, 18502, 18499, -1, 18506, 18454, 18484, -1, 18507, 18466, 18468, -1, 18508, 18498, 18471, -1, 18508, 18471, 18446, -1, 18509, 18510, 18492, -1, 18508, 18446, 18479, -1, 18509, 18464, 18436, -1, 18511, 18504, 18466, -1, 18509, 18436, 18488, -1, 18511, 18466, 18507, -1, 18509, 18492, 18464, -1, 18512, 18513, 18485, -1, 18511, 18505, 18504, -1, 18514, 18468, 18470, -1, 18514, 18470, 18505, -1, 18514, 18507, 18468, -1, 18515, 18467, 18441, -1, 18514, 18511, 18507, -1, 18514, 18505, 18511, -1, 18515, 18441, 18493, -1, 18512, 18485, 18483, -1, 18516, 18459, 18426, -1, 18517, 18493, 18469, -1, 18516, 18426, 18490, -1, 18517, 18469, 18496, -1, 18518, 18462, 18500, -1, 18518, 18484, 18462, -1, 18519, 18490, 18465, -1, 18520, 18496, 18474, -1, 18519, 18465, 18498, -1, 18520, 18474, 18506, -1, 18521, 18479, 18455, -1, 18522, 18467, 18515, -1, 18522, 18488, 18467, -1, 18521, 18455, 18501, -1, 18523, 18493, 18517, -1, 18523, 18515, 18493, -1, 18524, 18525, 18526, -1, 18524, 18526, 18527, -1, 18528, 18484, 18518, -1, 18529, 18498, 18508, -1, 18530, 18531, 18525, -1, 18528, 18506, 18484, -1, 18532, 18533, 18513, -1, 18534, 18496, 18520, -1, 18534, 18517, 18496, -1, 18530, 18525, 18524, -1, 18532, 18513, 18512, -1, 18535, 18509, 18488, -1, 18536, 18459, 18516, -1, 18535, 18488, 18522, -1, 18537, 18538, 18531, -1, 18535, 18539, 18510, -1, 18535, 18510, 18509, -1, 18536, 18483, 18459, -1, 18540, 18515, 18523, -1, 18540, 18522, 18515, -1, 18537, 18531, 18530, -1, 18541, 18527, 18542, -1, 18543, 18520, 18506, -1, 18543, 18506, 18528, -1, 18544, 18516, 18490, -1, 18541, 18524, 18527, -1, 18544, 18490, 18519, -1, 18545, 18479, 18521, -1, 18546, 18523, 18517, -1, 18547, 18548, 18538, -1, 18545, 18508, 18479, -1, 18547, 18538, 18537, -1, 18546, 18517, 18534, -1, 18549, 18522, 18540, -1, 18549, 18539, 18535, -1, 18550, 18524, 18541, -1, 18549, 18535, 18522, -1, 18550, 18530, 18524, -1, 18551, 18542, 18552, -1, 18402, 18520, 18543, -1, 18551, 18541, 18542, -1, 18553, 18519, 18498, -1, 18402, 18534, 18520, -1, 18553, 18498, 18529, -1, 18554, 18540, 18523, -1, 18553, 18544, 18519, -1, 18554, 18523, 18546, -1, 18555, 18533, 18532, -1, 18555, 18371, 18533, -1, 18556, 18557, 18548, -1, 18556, 18548, 18547, -1, 18403, 18546, 18534, -1, 18558, 18537, 18530, -1, 18403, 18534, 18402, -1, 18559, 18512, 18483, -1, 18560, 18549, 18540, -1, 18558, 18530, 18550, -1, 18560, 18540, 18554, -1, 18559, 18483, 18536, -1, 18560, 18539, 18549, -1, 18560, 18502, 18539, -1, 18561, 18550, 18541, -1, 18439, 18554, 18546, -1, 18561, 18541, 18551, -1, 18562, 18536, 18516, -1, 18439, 18546, 18403, -1, 18562, 18516, 18544, -1, 18563, 18551, 18552, -1, 18503, 18560, 18554, -1, 18503, 18554, 18439, -1, 18503, 18502, 18560, -1, 18564, 18529, 18508, -1, 18564, 18508, 18545, -1, 18565, 18566, 18557, -1, 18567, 18568, 18569, -1, 18565, 18557, 18556, -1, 18570, 18547, 18537, -1, 18570, 18537, 18558, -1, 18571, 18544, 18553, -1, 18572, 18573, 18574, -1, 18575, 18568, 18567, -1, 18575, 18574, 18576, -1, 18575, 18577, 18568, -1, 18578, 18421, 18371, -1, 18579, 18558, 18550, -1, 18575, 18567, 18580, -1, 18578, 18371, 18555, -1, 18575, 18580, 18572, -1, 18579, 18550, 18561, -1, 18575, 18572, 18574, -1, 18581, 18582, 18577, -1, 18583, 18551, 18563, -1, 18581, 18576, 18584, -1, 18581, 18575, 18576, -1, 18585, 18586, 18587, -1, 18583, 18561, 18551, -1, 18581, 18577, 18575, -1, 18585, 18588, 18586, -1, 18589, 18590, 18582, -1, 18589, 18582, 18581, -1, 18589, 18581, 18584, -1, 18591, 18512, 18559, -1, 18592, 18593, 18566, -1, 18589, 18584, 18381, -1, 18592, 18566, 18565, -1, 18591, 18532, 18512, -1, 18594, 18547, 18570, -1, 18595, 18590, 18589, -1, 18595, 18589, 18381, -1, 18596, 18536, 18562, -1, 18597, 18475, 18448, -1, 18596, 18559, 18536, -1, 18598, 18553, 18529, -1, 18594, 18556, 18547, -1, 18599, 18570, 18558, -1, 18598, 18529, 18564, -1, 18599, 18558, 18579, -1, 18600, 18588, 18601, -1, 18569, 18552, 18602, -1, 18603, 18604, 18600, -1, 18603, 18601, 18605, -1, 18569, 18563, 18552, -1, 18603, 18501, 18475, -1, 18603, 18475, 18597, -1, 18606, 18579, 18561, -1, 18603, 18600, 18601, -1, 18603, 18597, 18604, -1, 18607, 18596, 18562, -1, 18607, 18544, 18571, -1, 18606, 18561, 18583, -1, 18608, 18605, 18609, -1, 18608, 18521, 18501, -1, 18608, 18501, 18603, -1, 18607, 18562, 18544, -1, 18608, 18603, 18605, -1, 18610, 18611, 18593, -1, 18612, 18608, 18609, -1, 18613, 18421, 18578, -1, 18610, 18593, 18592, -1, 18612, 18609, 18614, -1, 18612, 18521, 18608, -1, 18612, 18545, 18521, -1, 18613, 18422, 18421, -1, 18615, 18588, 18585, -1, 18616, 18545, 18612, -1, 18615, 18601, 18588, -1, 18617, 18565, 18556, -1, 18617, 18556, 18594, -1, 18616, 18612, 18614, -1, 18618, 18570, 18599, -1, 18619, 18532, 18591, -1, 18620, 18350, 18621, -1, 18618, 18594, 18570, -1, 18619, 18555, 18532, -1, 18568, 18583, 18563, -1, 18622, 18591, 18559, -1, 18568, 18563, 18569, -1, 18622, 18559, 18596, -1, 18623, 18599, 18579, -1, 18624, 18625, 18626, -1, 18627, 18350, 18620, -1, 18627, 18345, 18350, -1, 18628, 18553, 18598, -1, 18627, 18629, 18624, -1, 18628, 18571, 18553, -1, 18627, 18624, 18626, -1, 18623, 18579, 18606, -1, 18627, 18626, 18630, -1, 18631, 18632, 18611, -1, 18627, 18620, 18629, -1, 18633, 18345, 18627, -1, 18631, 18611, 18610, -1, 18633, 18627, 18630, -1, 18633, 18409, 18345, -1, 18633, 18630, 18634, -1, 18635, 18565, 18617, -1, 18636, 18633, 18634, -1, 18637, 18596, 18607, -1, 18636, 18634, 18638, -1, 18636, 18409, 18633, -1, 18635, 18592, 18565, -1, 18636, 18431, 18409, -1, 18639, 18477, 18457, -1, 18640, 18431, 18636, -1, 18639, 18422, 18613, -1, 18641, 18617, 18594, -1, 18639, 18642, 18477, -1, 18639, 18457, 18422, -1, 18640, 18636, 18638, -1, 18643, 18605, 18601, -1, 18641, 18594, 18618, -1, 18644, 18567, 18569, -1, 18644, 18569, 18602, -1, 18577, 18583, 18568, -1, 18577, 18606, 18583, -1, 18645, 18644, 18602, -1, 18643, 18601, 18615, -1, 18646, 18618, 18599, -1, 18647, 18578, 18555, -1, 18646, 18599, 18623, -1, 18648, 18645, 18602, -1, 18647, 18555, 18619, -1, 18648, 18572, 18580, -1, 18649, 18645, 18648, -1, 18649, 18648, 18580, -1, 18649, 18567, 18644, -1, 18649, 18580, 18567, -1, 18650, 18619, 18591, -1, 18649, 18644, 18645, -1, 18651, 18652, 18632, -1, 18653, 18602, 18654, -1, 18653, 18648, 18602, -1, 18651, 18632, 18631, -1, 18653, 18572, 18648, -1, 18650, 18591, 18622, -1, 18653, 18573, 18572, -1, 18653, 18654, 18573, -1, 18655, 18607, 18571, -1, 18656, 18657, 18590, -1, 18655, 18571, 18628, -1, 18656, 18658, 18657, -1, 18659, 18610, 18592, -1, 18656, 18590, 18595, -1, 18659, 18592, 18635, -1, 18660, 18587, 18661, -1, 18662, 18656, 18595, -1, 18663, 18635, 18617, -1, 18660, 18585, 18587, -1, 18663, 18617, 18641, -1, 18664, 18388, 18428, -1, 18664, 18662, 18595, -1, 18664, 18595, 18381, -1, 18664, 18381, 18388, -1, 18665, 18448, 18449, -1, 18665, 18597, 18448, -1, 18582, 18623, 18606, -1, 18582, 18606, 18577, -1, 18666, 18665, 18449, -1, 18667, 18622, 18596, -1, 18667, 18596, 18637, -1, 18668, 18600, 18604, -1, 18668, 18666, 18449, -1, 18669, 18618, 18646, -1, 18670, 18597, 18665, -1, 18670, 18665, 18666, -1, 18670, 18668, 18604, -1, 18670, 18666, 18668, -1, 18671, 18609, 18605, -1, 18670, 18604, 18597, -1, 18672, 18449, 18586, -1, 18671, 18605, 18643, -1, 18669, 18641, 18618, -1, 18672, 18586, 18588, -1, 18672, 18668, 18449, -1, 18672, 18600, 18668, -1, 18672, 18588, 18600, -1, 18673, 18674, 18652, -1, 18675, 18545, 18616, -1, 18676, 18613, 18578, -1, 18673, 18652, 18651, -1, 18675, 18598, 18564, -1, 18676, 18578, 18647, -1, 18675, 18564, 18545, -1, 18677, 18610, 18659, -1, 18678, 18647, 18619, -1, 18678, 18619, 18650, -1, 18677, 18631, 18610, -1, 18679, 18675, 18616, -1, 18680, 18616, 18614, -1, 18681, 18659, 18635, -1, 18680, 18614, 18682, -1, 18683, 18637, 18607, -1, 18680, 18679, 18616, -1, 18680, 18682, 18684, -1, 18681, 18635, 18663, -1, 18685, 18620, 18621, -1, 18683, 18607, 18655, -1, 18590, 18623, 18582, -1, 18590, 18646, 18623, -1, 18685, 18621, 18686, -1, 18685, 18629, 18620, -1, 18687, 18629, 18685, -1, 18688, 18615, 18585, -1, 18687, 18686, 18689, -1, 18687, 18685, 18686, -1, 18688, 18585, 18660, -1, 18690, 18624, 18629, -1, 18690, 18625, 18624, -1, 18690, 18689, 18625, -1, 18690, 18629, 18687, -1, 18690, 18687, 18689, -1, 18691, 18431, 18640, -1, 18691, 18478, 18458, -1, 18692, 18641, 18669, -1, 18691, 18458, 18431, -1, 18693, 18650, 18622, -1, 18692, 18663, 18641, -1, 18693, 18622, 18667, -1, 18694, 18691, 18640, -1, 18695, 18696, 18674, -1, 18693, 18678, 18650, -1, 18697, 18640, 18638, -1, 18698, 18661, 18699, -1, 18697, 18700, 18701, -1, 18697, 18638, 18700, -1, 18695, 18674, 18673, -1, 18697, 18694, 18640, -1, 18702, 18651, 18631, -1, 18698, 18660, 18661, -1, 18703, 18658, 18656, -1, 18703, 18656, 18662, -1, 18702, 18631, 18677, -1, 18703, 18704, 18658, -1, 18705, 18614, 18609, -1, 18706, 18659, 18681, -1, 18707, 18703, 18662, -1, 18705, 18682, 18614, -1, 18705, 18609, 18671, -1, 18706, 18677, 18659, -1, 18657, 18669, 18646, -1, 18708, 18613, 18676, -1, 18709, 18707, 18662, -1, 18708, 18710, 18642, -1, 18709, 18662, 18664, -1, 18708, 18639, 18613, -1, 18709, 18664, 18428, -1, 18708, 18642, 18639, -1, 18709, 18428, 18460, -1, 18657, 18646, 18590, -1, 18711, 18628, 18598, -1, 18712, 18676, 18647, -1, 18711, 18598, 18675, -1, 18712, 18647, 18678, -1, 18711, 18675, 18679, -1, 18713, 18711, 18679, -1, 18714, 18667, 18637, -1, 18715, 18681, 18663, -1, 18715, 18663, 18692, -1, 18714, 18637, 18683, -1, 18716, 18684, 18717, -1, 18716, 18713, 18679, -1, 18718, 18615, 18688, -1, 18716, 18680, 18684, -1, 18716, 18679, 18680, -1, 18719, 18720, 18696, -1, 18721, 18500, 18478, -1, 18719, 18696, 18695, -1, 18718, 18643, 18615, -1, 18721, 18478, 18691, -1, 18721, 18691, 18694, -1, 18722, 18654, 18723, -1, 18724, 18721, 18694, -1, 18722, 18573, 18654, -1, 18725, 18724, 18694, -1, 18726, 18673, 18651, -1, 18725, 18701, 18727, -1, 18728, 18678, 18693, -1, 18725, 18697, 18701, -1, 18725, 18694, 18697, -1, 18726, 18651, 18702, -1, 18729, 18703, 18707, -1, 18730, 18660, 18698, -1, 18729, 18731, 18704, -1, 18732, 18702, 18677, -1, 18729, 18704, 18703, -1, 18732, 18677, 18706, -1, 18733, 18707, 18709, -1, 18730, 18688, 18660, -1, 18733, 18709, 18460, -1, 18658, 18692, 18669, -1, 18658, 18669, 18657, -1, 18733, 18460, 18485, -1, 18734, 18698, 18699, -1, 18735, 18711, 18713, -1, 18735, 18628, 18711, -1, 18736, 18682, 18705, -1, 18735, 18655, 18628, -1, 18737, 18716, 18717, -1, 18737, 18717, 18738, -1, 18737, 18713, 18716, -1, 18739, 18518, 18500, -1, 18740, 18676, 18712, -1, 18739, 18721, 18724, -1, 18741, 18706, 18681, -1, 18740, 18708, 18676, -1, 18740, 18710, 18708, -1, 18741, 18681, 18715, -1, 18739, 18500, 18721, -1, 18742, 18724, 18725, -1, 18742, 18725, 18727, -1, 18379, 18667, 18714, -1, 18743, 18744, 18720, -1, 18379, 18693, 18667, -1, 18742, 18727, 18745, -1, 18743, 18720, 18719, -1, 18746, 18643, 18718, -1, 18747, 18731, 18729, -1, 18747, 18748, 18731, -1, 18749, 18707, 18733, -1, 18749, 18747, 18729, -1, 18746, 18671, 18643, -1, 18337, 18573, 18722, -1, 18749, 18729, 18707, -1, 18337, 18574, 18573, -1, 18750, 18695, 18673, -1, 18750, 18719, 18695, -1, 18750, 18673, 18726, -1, 18751, 18747, 18749, -1, 18752, 18726, 18702, -1, 18753, 18678, 18728, -1, 18752, 18702, 18732, -1, 18754, 18749, 18733, -1, 18754, 18751, 18749, -1, 18753, 18712, 18678, -1, 18704, 18715, 18692, -1, 18755, 18688, 18730, -1, 18756, 18733, 18485, -1, 18756, 18485, 18513, -1, 18704, 18692, 18658, -1, 18756, 18754, 18733, -1, 18757, 18683, 18655, -1, 18755, 18718, 18688, -1, 18347, 18730, 18698, -1, 18757, 18655, 18735, -1, 18347, 18698, 18734, -1, 18758, 18735, 18713, -1, 18758, 18757, 18735, -1, 18758, 18713, 18737, -1, 18759, 18732, 18706, -1, 18386, 18717, 18684, -1, 18760, 18757, 18758, -1, 18759, 18706, 18741, -1, 18761, 18762, 18763, -1, 18386, 18682, 18736, -1, 18761, 18763, 18744, -1, 18386, 18684, 18682, -1, 18761, 18764, 18762, -1, 18378, 18728, 18693, -1, 18761, 18744, 18743, -1, 18336, 18576, 18574, -1, 18765, 18758, 18737, -1, 18378, 18693, 18379, -1, 18765, 18760, 18758, -1, 18336, 18574, 18337, -1, 18766, 18765, 18737, -1, 18766, 18737, 18738, -1, 18766, 18738, 18373, -1, 18767, 18518, 18739, -1, 18767, 18528, 18518, -1, 18333, 18671, 18746, -1, 18333, 18705, 18671, -1, 18768, 18739, 18724, -1, 18769, 18719, 18750, -1, 18768, 18724, 18742, -1, 18768, 18767, 18739, -1, 18352, 18726, 18752, -1, 18352, 18750, 18726, -1, 18770, 18740, 18712, -1, 18770, 18710, 18740, -1, 18771, 18767, 18768, -1, 18770, 18489, 18710, -1, 18770, 18712, 18753, -1, 18731, 18741, 18715, -1, 18731, 18715, 18704, -1, 18357, 18746, 18718, -1, 18772, 18768, 18742, -1, 18365, 18722, 18723, -1, 18365, 18723, 18773, -1, 18772, 18771, 18768, -1, 18774, 18745, 18775, -1, 18357, 18718, 18755, -1, 18774, 18742, 18745, -1, 18774, 18772, 18742, -1, 18621, 18699, 18686, -1, 18776, 18748, 18747, -1, 18776, 18747, 18751, -1, 18621, 18734, 18699, -1, 18776, 18751, 18754, -1, 18346, 18755, 18730, -1, 18777, 18513, 18533, -1, 18777, 18756, 18513, -1, 18777, 18754, 18756, -1, 18346, 18730, 18347, -1, 18399, 18752, 18732, -1, 18777, 18776, 18754, -1, 18399, 18732, 18759, -1, 18778, 18683, 18757, -1, 18778, 18757, 18760, -1, 18778, 18760, 18765, -1, 18391, 18717, 18386, -1, 18410, 18584, 18576, -1, 18779, 18765, 18766, -1, 18410, 18576, 18336, -1, 18779, 18766, 18373, -1, 18779, 18373, 18418, -1, 18779, 18778, 18765, -1, 18425, 18753, 18728, -1, 18425, 18728, 18378, -1, 18396, 18719, 18769, -1, 18396, 18743, 18719, -1, 18340, 18528, 18767, -1, 18340, 18767, 18771, -1, 18355, 18769, 18750, -1, 18340, 18771, 18772, -1, 18355, 18750, 18352, -1, 18343, 18736, 18705, -1, 18342, 18775, 18349, -1, 18343, 18705, 18333, -1, 18342, 18340, 18772, -1, 18342, 18774, 18775, -1, 18342, 18772, 18774, -1, 18361, 18748, 18776, -1, 18748, 18741, 18731, -1, 18361, 18360, 18400, -1, 18361, 18400, 18748, -1, 18748, 18759, 18741, -1, 18364, 18337, 18722, -1, 18364, 18722, 18365, -1, 18362, 18361, 18776, -1, 18334, 18333, 18746, -1, 18334, 18746, 18357, -1, 18780, 18776, 18777, -1, 18368, 18362, 18776, -1, 18350, 18734, 18621, -1, 18350, 18347, 18734, -1, 18368, 18776, 18780, -1, 18353, 18352, 18752, -1, 18370, 18780, 18777, -1, 18370, 18368, 18780, -1, 18370, 18533, 18371, -1, 18370, 18777, 18533, -1, 18353, 18752, 18399, -1, 18383, 18379, 18714, -1, 18369, 18773, 18376, -1, 18383, 18714, 18683, -1, 18383, 18683, 18778, -1, 18366, 18357, 18755, -1, 18369, 18365, 18773, -1, 18366, 18755, 18346, -1, 18382, 18584, 18410, -1, 18374, 18738, 18717, -1, 18384, 18383, 18778, -1, 18374, 18373, 18738, -1, 18382, 18381, 18584, -1, 18374, 18717, 18391, -1, 18395, 18761, 18743, -1, 18395, 18764, 18761, -1, 18781, 18778, 18779, -1, 18487, 18753, 18425, -1, 18395, 18398, 18764, -1, 18395, 18743, 18396, -1, 18487, 18489, 18770, -1, 18397, 18396, 18769, -1, 18390, 18384, 18778, -1, 18487, 18770, 18753, -1, 18397, 18769, 18355, -1, 18390, 18778, 18781, -1, 18392, 18781, 18779, -1, 18387, 18386, 18736, -1, 18387, 18736, 18343, -1, 18400, 18399, 18759, -1, 18392, 18390, 18781, -1, 18392, 18418, 18393, -1, 18392, 18779, 18418, -1, 18339, 18528, 18340, -1, 18400, 18759, 18748, -1, 18339, 18402, 18543, -1, 18335, 18337, 18364, -1, 18339, 18543, 18528, -1, 18782, 18783, 18784, -1, 18784, 18783, 18785, -1, 18785, 18786, 18787, -1, 18783, 18786, 18785, -1, 18787, 18788, 18789, -1, 18786, 18788, 18787, -1, 18789, 18790, 18791, -1, 18788, 18790, 18789, -1, 18791, 18792, 18793, -1, 18790, 18792, 18791, -1, 18793, 18794, 18795, -1, 18792, 18794, 18793, -1, 18795, 18796, 18797, -1, 18794, 18796, 18795, -1, 18798, 18799, 18800, -1, 18800, 18799, 18801, -1, 18801, 18802, 18803, -1, 18799, 18802, 18801, -1, 18803, 18804, 18805, -1, 18802, 18804, 18803, -1, 18805, 18806, 18807, -1, 18804, 18806, 18805, -1, 18807, 18808, 18809, -1, 18806, 18808, 18807, -1, 18809, 18810, 18811, -1, 18808, 18810, 18809, -1, 18811, 18812, 18813, -1, 18810, 18812, 18811, -1, 18814, 18239, 18815, -1, 18814, 18816, 18239, -1, 18817, 18815, 18818, -1, 18817, 18814, 18815, -1, 18819, 18818, 18820, -1, 18819, 18817, 18818, -1, 18821, 18820, 18822, -1, 18821, 18819, 18820, -1, 18823, 18822, 18824, -1, 18823, 18821, 18822, -1, 18825, 18824, 18826, -1, 18825, 18823, 18824, -1, 18827, 18826, 18828, -1, 18827, 18825, 18826, -1, 18829, 18828, 18830, -1, 18829, 18827, 18828, -1, 18831, 18830, 18832, -1, 18831, 18829, 18830, -1, 18833, 18832, 18834, -1, 18833, 18831, 18832, -1, 18835, 18834, 18836, -1, 18835, 18833, 18834, -1, 18837, 18836, 18838, -1, 18837, 18835, 18836, -1, 18839, 18838, 18840, -1, 18839, 18837, 18838, -1, 18841, 18840, 18842, -1, 18841, 18839, 18840, -1, 18843, 18842, 18844, -1, 18843, 18841, 18842, -1, 18845, 18844, 18056, -1, 18845, 18843, 18844, -1, 18846, 18845, 18056, -1, 18847, 18689, 18848, -1, 18847, 18848, 18849, -1, 18847, 18076, 18689, -1, 18850, 18849, 18851, -1, 18850, 18847, 18849, -1, 18852, 18851, 18853, -1, 18852, 18850, 18851, -1, 18854, 18853, 18855, -1, 18854, 18852, 18853, -1, 18856, 18854, 18855, -1, 18857, 18855, 18858, -1, 18857, 18856, 18855, -1, 18859, 18858, 18860, -1, 18859, 18857, 18858, -1, 18861, 18860, 18862, -1, 18861, 18859, 18860, -1, 18863, 18862, 18864, -1, 18863, 18861, 18862, -1, 18865, 18864, 18866, -1, 18865, 18863, 18864, -1, 18867, 18866, 18868, -1, 18867, 18865, 18866, -1, 18869, 18868, 18870, -1, 18869, 18867, 18868, -1, 18871, 18870, 18872, -1, 18871, 18869, 18870, -1, 18873, 18872, 18874, -1, 18873, 18871, 18872, -1, 18875, 18874, 18876, -1, 18875, 18876, 18505, -1, 18875, 18873, 18874, -1, 18311, 18875, 18505, -1, 18526, 18877, 18878, -1, 18879, 18878, 18880, -1, 18879, 18526, 18878, -1, 18881, 18880, 18882, -1, 18881, 18879, 18880, -1, 18883, 18882, 18884, -1, 18883, 18881, 18882, -1, 18885, 18884, 18886, -1, 18885, 18883, 18884, -1, 18887, 18886, 18888, -1, 18887, 18885, 18886, -1, 18889, 18888, 18890, -1, 18889, 18887, 18888, -1, 18891, 18890, 18892, -1, 18891, 18889, 18890, -1, 18893, 18892, 18894, -1, 18893, 18891, 18892, -1, 18895, 18894, 18896, -1, 18895, 18893, 18894, -1, 18897, 18896, 18898, -1, 18897, 18895, 18896, -1, 18899, 18898, 18900, -1, 18899, 18897, 18898, -1, 18901, 18900, 18902, -1, 18901, 18899, 18900, -1, 18903, 18902, 18904, -1, 18903, 18901, 18902, -1, 18905, 18904, 18906, -1, 18905, 18903, 18904, -1, 18907, 18906, 18908, -1, 18907, 18905, 18906, -1, 18762, 18907, 18908, -1, 18762, 18908, 18909, -1, 18762, 18909, 18910, -1, 18763, 18910, 18911, -1, 18763, 18762, 18910, -1, 18744, 18911, 18912, -1, 18744, 18763, 18911, -1, 18720, 18912, 18913, -1, 18720, 18744, 18912, -1, 18696, 18913, 18914, -1, 18696, 18720, 18913, -1, 18674, 18914, 18915, -1, 18674, 18696, 18914, -1, 18652, 18915, 18916, -1, 18652, 18674, 18915, -1, 18632, 18916, 18917, -1, 18632, 18652, 18916, -1, 18611, 18917, 18918, -1, 18611, 18632, 18917, -1, 18593, 18918, 18919, -1, 18593, 18611, 18918, -1, 18566, 18919, 18920, -1, 18566, 18593, 18919, -1, 18557, 18920, 18921, -1, 18557, 18566, 18920, -1, 18548, 18921, 18922, -1, 18548, 18557, 18921, -1, 18538, 18922, 18923, -1, 18538, 18548, 18922, -1, 18531, 18923, 18924, -1, 18531, 18538, 18923, -1, 18525, 18924, 18925, -1, 18525, 18531, 18924, -1, 18526, 18525, 18925, -1, 18526, 18925, 18877, -1, 18926, 18927, 18928, -1, 18926, 18929, 18927, -1, 18930, 18931, 18932, -1, 18926, 18933, 18934, -1, 18926, 18934, 18929, -1, 18935, 18936, 18937, -1, 18938, 18449, 18376, -1, 18935, 18939, 18936, -1, 18938, 18376, 18940, -1, 18938, 18940, 18941, -1, 18935, 18942, 18939, -1, 18938, 18941, 18943, -1, 18944, 18945, 18946, -1, 18930, 18932, 18947, -1, 18948, 18942, 18935, -1, 18944, 18946, 18949, -1, 18950, 18942, 18948, -1, 18951, 18942, 18950, -1, 18952, 18953, 18954, -1, 18952, 18954, 18955, -1, 18951, 18956, 18942, -1, 18957, 18951, 18950, -1, 18958, 18947, 18959, -1, 18957, 18956, 18951, -1, 18957, 18870, 18868, -1, 18957, 18868, 18956, -1, 18958, 18959, 18960, -1, 18961, 18962, 18963, -1, 18964, 18965, 18966, -1, 18961, 18949, 18962, -1, 18967, 18710, 18489, -1, 18964, 18968, 18969, -1, 18964, 18966, 18968, -1, 18967, 18960, 18710, -1, 18970, 18965, 18964, -1, 18970, 18971, 18965, -1, 18970, 18972, 18971, -1, 18970, 18973, 18972, -1, 18974, 18975, 18976, -1, 18977, 18978, 18979, -1, 18974, 18980, 18975, -1, 18977, 18979, 18981, -1, 18982, 18983, 18984, -1, 18985, 18986, 18987, -1, 18985, 18963, 18986, -1, 18982, 18988, 18989, -1, 18990, 18552, 18542, -1, 18990, 18991, 18992, -1, 18982, 18984, 18988, -1, 18990, 18992, 18993, -1, 18994, 18928, 18983, -1, 18994, 18983, 18982, -1, 18990, 18542, 18991, -1, 18994, 18926, 18928, -1, 18994, 18933, 18926, -1, 18995, 18996, 18997, -1, 18998, 18999, 19000, -1, 18995, 18997, 19001, -1, 18998, 18952, 18955, -1, 18998, 18955, 18999, -1, 19002, 18937, 18977, -1, 19003, 18945, 18944, -1, 19004, 19005, 18931, -1, 19002, 18948, 18935, -1, 19002, 18935, 18937, -1, 19004, 18931, 18930, -1, 19006, 18950, 18948, -1, 19006, 18957, 18950, -1, 19006, 18870, 18957, -1, 19006, 18948, 19002, -1, 19003, 19007, 18945, -1, 19008, 18969, 19009, -1, 19008, 18964, 18969, -1, 19010, 18949, 18961, -1, 19011, 18953, 18952, -1, 19011, 18993, 18953, -1, 19012, 19013, 18970, -1, 19012, 18970, 18964, -1, 19012, 18964, 19008, -1, 19010, 18944, 18949, -1, 19012, 19008, 19013, -1, 19014, 18947, 18958, -1, 18937, 18978, 18977, -1, 19014, 18930, 18947, -1, 19015, 18970, 19013, -1, 19016, 18973, 18970, -1, 18937, 18987, 18978, -1, 19017, 18961, 18963, -1, 19016, 19018, 19019, -1, 19020, 18958, 18960, -1, 18527, 18526, 18879, -1, 19016, 19019, 18973, -1, 19020, 18960, 18967, -1, 19016, 18970, 19015, -1, 19021, 18989, 19022, -1, 19021, 18982, 18989, -1, 19023, 18980, 18974, -1, 19023, 19024, 18980, -1, 19017, 18963, 18985, -1, 19025, 19026, 18996, -1, 19025, 18996, 18995, -1, 19027, 19028, 18994, -1, 19029, 18952, 18998, -1, 19027, 18994, 18982, -1, 19027, 18982, 19021, -1, 19027, 19021, 19028, -1, 19030, 19007, 19003, -1, 19031, 19005, 19004, -1, 19031, 18976, 19005, -1, 19032, 18994, 19028, -1, 19033, 18933, 18994, -1, 19030, 19001, 19007, -1, 19033, 19034, 19035, -1, 19033, 19035, 18933, -1, 19033, 18994, 19032, -1, 19036, 18977, 18981, -1, 19036, 19002, 18977, -1, 19037, 18944, 19010, -1, 19038, 18990, 18993, -1, 19038, 18993, 19011, -1, 19038, 18552, 18990, -1, 19037, 19003, 18944, -1, 19039, 19006, 19002, -1, 18936, 18985, 18987, -1, 19039, 19002, 19036, -1, 19039, 19040, 19006, -1, 19039, 19036, 19040, -1, 19041, 18930, 19014, -1, 19041, 19004, 18930, -1, 18936, 18987, 18937, -1, 19042, 18967, 18489, -1, 19043, 19006, 19040, -1, 19044, 19010, 18961, -1, 19045, 19006, 19043, -1, 19045, 18872, 18870, -1, 19045, 18874, 18872, -1, 19045, 18870, 19006, -1, 19044, 18961, 19017, -1, 19046, 19014, 18958, -1, 19047, 19048, 19049, -1, 19046, 18958, 19020, -1, 19050, 19008, 19009, -1, 19047, 19026, 19025, -1, 19050, 19013, 19008, -1, 19050, 19015, 19013, -1, 19051, 19015, 19050, -1, 19052, 19024, 19023, -1, 19047, 19049, 19026, -1, 19051, 19053, 19018, -1, 19052, 19054, 19024, -1, 19051, 19016, 19015, -1, 19055, 18995, 19001, -1, 19051, 19018, 19016, -1, 19056, 18952, 19029, -1, 19057, 19021, 19022, -1, 19055, 19001, 19030, -1, 19056, 19011, 18952, -1, 19057, 19028, 19021, -1, 19057, 19032, 19028, -1, 19058, 19059, 19034, -1, 19058, 19032, 19057, -1, 19060, 18974, 18976, -1, 19058, 19034, 19033, -1, 19058, 19033, 19032, -1, 19060, 18976, 19031, -1, 19061, 19043, 19040, -1, 19062, 19003, 19037, -1, 19061, 19036, 18981, -1, 19062, 19030, 19003, -1, 19061, 19040, 19036, -1, 18939, 19017, 18985, -1, 19063, 19045, 19043, -1, 18939, 18985, 18936, -1, 19063, 19043, 19061, -1, 19063, 18876, 18874, -1, 19063, 18874, 19045, -1, 19064, 19004, 19041, -1, 19065, 19009, 19066, -1, 19065, 19050, 19009, -1, 19067, 19010, 19044, -1, 19064, 19031, 19004, -1, 19065, 19066, 18443, -1, 19022, 18967, 19042, -1, 19068, 19050, 19065, -1, 19068, 19065, 18443, -1, 19067, 19037, 19010, -1, 19068, 18443, 18477, -1, 19069, 19048, 19047, -1, 19022, 19020, 18967, -1, 19070, 19068, 18477, -1, 19070, 19050, 19068, -1, 19071, 19041, 19014, -1, 19072, 19050, 19070, -1, 19073, 18995, 19055, -1, 19072, 19051, 19050, -1, 19073, 19025, 18995, -1, 19071, 19014, 19046, -1, 19074, 19053, 19051, -1, 19074, 18477, 19053, -1, 19074, 19070, 18477, -1, 19074, 19051, 19072, -1, 19075, 19054, 19052, -1, 19074, 19072, 19070, -1, 19075, 19076, 19054, -1, 19077, 19022, 19042, -1, 19078, 18602, 18552, -1, 19077, 19042, 18489, -1, 19079, 19055, 19030, -1, 19077, 19057, 19022, -1, 19078, 19011, 19056, -1, 19080, 19077, 18489, -1, 19079, 19030, 19062, -1, 19078, 19038, 19011, -1, 19080, 19057, 19077, -1, 19078, 18552, 19038, -1, 19080, 18489, 18492, -1, 19081, 19044, 19017, -1, 19082, 19057, 19080, -1, 19083, 18974, 19060, -1, 19082, 19080, 18492, -1, 19081, 19017, 18939, -1, 19084, 19058, 19057, -1, 19083, 19023, 18974, -1, 19084, 19057, 19082, -1, 19085, 19059, 19058, -1, 19085, 19058, 19084, -1, 19086, 19062, 19037, -1, 19085, 19082, 18492, -1, 19085, 19084, 19082, -1, 19085, 18492, 19059, -1, 19086, 19037, 19067, -1, 19087, 18981, 19088, -1, 19089, 19048, 19069, -1, 19090, 19060, 19031, -1, 19087, 19088, 18502, -1, 19090, 19031, 19064, -1, 19089, 19091, 19048, -1, 19087, 19061, 18981, -1, 19092, 19061, 19087, -1, 19093, 19047, 19025, -1, 19092, 18502, 18505, -1, 18989, 19020, 19022, -1, 19092, 19087, 18502, -1, 19093, 19025, 19073, -1, 18989, 19046, 19020, -1, 19094, 19061, 19092, -1, 19094, 19092, 18505, -1, 19095, 19063, 19061, -1, 19096, 19064, 19041, -1, 19095, 19061, 19094, -1, 19097, 19073, 19055, -1, 19098, 18876, 19063, -1, 19096, 19041, 19071, -1, 19098, 19063, 19095, -1, 19098, 18505, 18876, -1, 19097, 19055, 19079, -1, 19098, 19094, 18505, -1, 19099, 19067, 19044, -1, 19098, 19095, 19094, -1, 19099, 19044, 19081, -1, 19100, 19076, 19075, -1, 19100, 19101, 19076, -1, 19102, 19052, 19023, -1, 19103, 19062, 19086, -1, 19102, 19023, 19083, -1, 19103, 19079, 19062, -1, 19104, 18587, 18586, -1, 19104, 18586, 19105, -1, 19104, 19105, 19091, -1, 19104, 19091, 19089, -1, 19106, 19060, 19090, -1, 19107, 19069, 19047, -1, 19106, 19083, 19060, -1, 19107, 19047, 19093, -1, 19108, 19093, 19073, -1, 19109, 18907, 18762, -1, 19109, 18762, 18764, -1, 18988, 19071, 19046, -1, 19110, 18907, 19109, -1, 19108, 19073, 19097, -1, 18988, 19046, 18989, -1, 19110, 18903, 18905, -1, 19110, 18905, 18907, -1, 19111, 19086, 19067, -1, 19111, 19067, 19099, -1, 19112, 19097, 19079, -1, 19113, 19090, 19064, -1, 19113, 19064, 19096, -1, 19112, 19079, 19103, -1, 19113, 19106, 19090, -1, 19114, 18903, 19110, -1, 19115, 19069, 19107, -1, 19116, 19109, 18764, -1, 19117, 19101, 19100, -1, 19116, 18764, 18398, -1, 19115, 19089, 19069, -1, 19117, 19118, 19101, -1, 19119, 19107, 19093, -1, 19120, 19052, 19102, -1, 19119, 19093, 19108, -1, 19121, 19086, 19111, -1, 19120, 19075, 19052, -1, 19122, 18901, 18903, -1, 19122, 18903, 19114, -1, 19121, 19103, 19086, -1, 19123, 19108, 19097, -1, 19124, 19109, 19116, -1, 19123, 19097, 19112, -1, 19125, 19102, 19083, -1, 19124, 19110, 19109, -1, 19125, 19083, 19106, -1, 19126, 18661, 18587, -1, 19127, 19116, 18398, -1, 19126, 19104, 19089, -1, 19126, 19089, 19115, -1, 19128, 19096, 19071, -1, 19126, 18587, 19104, -1, 19128, 19071, 18988, -1, 19129, 19115, 19107, -1, 19130, 18899, 18901, -1, 19129, 19107, 19119, -1, 19130, 18901, 19122, -1, 19131, 19112, 19103, -1, 19131, 19103, 19121, -1, 19132, 19110, 19124, -1, 19133, 19119, 19108, -1, 19132, 19114, 19110, -1, 19134, 19124, 19116, -1, 19135, 19106, 19113, -1, 19133, 19108, 19123, -1, 19136, 19126, 19115, -1, 19134, 19116, 19127, -1, 19136, 18699, 18661, -1, 19136, 19115, 19129, -1, 19136, 18661, 19126, -1, 19137, 18398, 18443, -1, 19138, 19118, 19117, -1, 19139, 19112, 19131, -1, 19138, 19140, 19118, -1, 19137, 19127, 18398, -1, 19141, 18899, 19130, -1, 19142, 19100, 19075, -1, 19139, 19123, 19112, -1, 19142, 19075, 19120, -1, 19143, 19129, 19119, -1, 19141, 18897, 18899, -1, 19143, 19119, 19133, -1, 19144, 19114, 19132, -1, 19145, 19133, 19123, -1, 19145, 19123, 19139, -1, 19144, 19122, 19114, -1, 19146, 19120, 19102, -1, 19146, 19102, 19125, -1, 19147, 18699, 19136, -1, 19147, 19129, 19143, -1, 19147, 19136, 19129, -1, 19148, 19096, 19128, -1, 19149, 19124, 19134, -1, 19150, 19133, 19145, -1, 19148, 19113, 19096, -1, 19150, 19143, 19133, -1, 19149, 19132, 19124, -1, 19151, 19134, 19127, -1, 19152, 18686, 18699, -1, 19152, 18699, 19147, -1, 19151, 19127, 19137, -1, 19152, 19147, 19143, -1, 19152, 19143, 19150, -1, 19153, 18893, 18895, -1, 19154, 19106, 19135, -1, 19153, 18895, 18897, -1, 19154, 19146, 19125, -1, 19153, 18897, 19141, -1, 19154, 19125, 19106, -1, 19155, 19000, 19156, -1, 19157, 19140, 19138, -1, 19155, 19156, 19118, -1, 19158, 19122, 19144, -1, 19155, 18998, 19000, -1, 19158, 19130, 19122, -1, 19155, 19118, 19140, -1, 19159, 19029, 18998, -1, 19157, 19160, 19140, -1, 19159, 19140, 19160, -1, 19159, 18998, 19155, -1, 19159, 19155, 19140, -1, 19161, 18492, 18510, -1, 19162, 19144, 19132, -1, 19163, 19160, 19164, -1, 19162, 19132, 19149, -1, 19161, 19059, 18492, -1, 19163, 19056, 19029, -1, 19163, 19029, 19159, -1, 19165, 19100, 19142, -1, 19066, 19137, 18443, -1, 19163, 19159, 19160, -1, 19165, 19117, 19100, -1, 19166, 19078, 19056, -1, 19166, 19056, 19163, -1, 19167, 19134, 19151, -1, 19168, 19120, 19146, -1, 19167, 19149, 19134, -1, 19168, 19142, 19120, -1, 19169, 19166, 19163, -1, 19170, 19135, 19113, -1, 19171, 19164, 19172, -1, 19171, 19163, 19164, -1, 19170, 19113, 19148, -1, 19171, 19169, 19163, -1, 19173, 18893, 19153, -1, 19174, 19130, 19158, -1, 19174, 19141, 19130, -1, 19175, 19176, 19177, -1, 19175, 19177, 19178, -1, 19175, 19178, 19026, -1, 19175, 19026, 19049, -1, 19179, 19175, 19049, -1, 19180, 19144, 19162, -1, 19179, 19181, 19176, -1, 19179, 19049, 19048, -1, 19180, 19158, 19144, -1, 19009, 19137, 19066, -1, 19179, 19176, 19175, -1, 19182, 19146, 19154, -1, 19183, 19181, 19179, -1, 19183, 19048, 19091, -1, 19184, 19164, 19160, -1, 19009, 19151, 19137, -1, 19183, 18943, 19181, -1, 19183, 19179, 19048, -1, 19184, 19160, 19157, -1, 19185, 19162, 19149, -1, 19186, 18943, 19183, -1, 19187, 19034, 19059, -1, 19185, 19149, 19167, -1, 19187, 19059, 19161, -1, 19186, 18938, 18943, -1, 19188, 19186, 19183, -1, 19189, 18891, 18893, -1, 19189, 18893, 19173, -1, 19190, 19183, 19091, -1, 19191, 19138, 19117, -1, 19190, 19188, 19183, -1, 19191, 19117, 19165, -1, 19190, 19091, 19105, -1, 19192, 19153, 19141, -1, 19193, 19165, 19142, -1, 19192, 19141, 19174, -1, 19193, 19142, 19168, -1, 19194, 19195, 18855, -1, 19196, 19174, 19158, -1, 19194, 19131, 19195, -1, 19196, 19158, 19180, -1, 19194, 19139, 19131, -1, 19197, 19135, 19170, -1, 19194, 18855, 18853, -1, 19198, 19139, 19194, -1, 18969, 19151, 19009, -1, 19197, 19154, 19135, -1, 19198, 18853, 18851, -1, 18969, 19167, 19151, -1, 19198, 19194, 18853, -1, 19198, 19145, 19139, -1, 19199, 19145, 19198, -1, 19199, 18851, 18849, -1, 19199, 19198, 18851, -1, 19200, 19180, 19162, -1, 19200, 19162, 19185, -1, 19199, 19150, 19145, -1, 19201, 19150, 19199, -1, 19202, 19168, 19146, -1, 19202, 19146, 19182, -1, 19203, 18891, 19189, -1, 19201, 19152, 19150, -1, 19204, 18723, 18654, -1, 19205, 19201, 19199, -1, 19203, 18889, 18891, -1, 19204, 19172, 19164, -1, 19204, 19164, 19184, -1, 19204, 18654, 19172, -1, 19206, 19205, 19199, -1, 19207, 19035, 19034, -1, 19206, 18849, 18848, -1, 19208, 19153, 19192, -1, 19206, 19199, 18849, -1, 19209, 19156, 19000, -1, 19208, 19173, 19153, -1, 19209, 19210, 19211, -1, 19209, 19000, 19210, -1, 19207, 19034, 19187, -1, 19212, 19174, 19196, -1, 19213, 19138, 19191, -1, 19212, 19192, 19174, -1, 19214, 19156, 19209, -1, 19213, 19157, 19138, -1, 18968, 19167, 18969, -1, 19215, 19156, 19214, -1, 19215, 19076, 19101, -1, 19215, 19118, 19156, -1, 18968, 19185, 19167, -1, 19215, 19101, 19118, -1, 19216, 19191, 19165, -1, 19216, 19165, 19193, -1, 19217, 19166, 19169, -1, 19217, 18602, 19078, -1, 19217, 19078, 19166, -1, 19218, 18654, 18602, -1, 19219, 19182, 19154, -1, 19218, 19217, 19169, -1, 19219, 19154, 19197, -1, 19220, 19180, 19200, -1, 19218, 18602, 19217, -1, 19221, 19161, 18510, -1, 19221, 18510, 18539, -1, 19222, 18654, 19218, -1, 19222, 19218, 19169, -1, 19220, 19196, 19180, -1, 19222, 19172, 18654, -1, 19222, 19171, 19172, -1, 19222, 19169, 19171, -1, 19223, 18889, 19203, -1, 19224, 19177, 19225, -1, 19224, 19178, 19177, -1, 19223, 18887, 18889, -1, 19224, 19225, 19219, -1, 19226, 19178, 19224, -1, 19227, 19173, 19208, -1, 19228, 18997, 18996, -1, 19229, 19193, 19168, -1, 19229, 19168, 19202, -1, 19227, 19189, 19173, -1, 19228, 18996, 19026, -1, 19228, 19026, 19178, -1, 19228, 19178, 19226, -1, 19230, 19186, 19188, -1, 19230, 18938, 19186, -1, 19231, 19208, 19192, -1, 19232, 18933, 19035, -1, 19231, 19192, 19212, -1, 19230, 18449, 18938, -1, 19233, 19230, 19188, -1, 19232, 19035, 19207, -1, 19233, 18586, 18449, -1, 19234, 19185, 18968, -1, 19233, 18449, 19230, -1, 19235, 19188, 19190, -1, 19236, 19184, 19157, -1, 19234, 19200, 19185, -1, 19235, 19190, 19105, -1, 19235, 19105, 18586, -1, 19235, 18586, 19233, -1, 19235, 19233, 19188, -1, 19236, 19157, 19213, -1, 19237, 19121, 19111, -1, 19237, 19195, 19131, -1, 19238, 19213, 19191, -1, 19237, 19131, 19121, -1, 19238, 19191, 19216, -1, 19239, 19196, 19220, -1, 19240, 19195, 19237, -1, 19225, 19202, 19182, -1, 19239, 19212, 19196, -1, 19241, 18855, 19195, -1, 19225, 19182, 19219, -1, 19241, 18858, 18855, -1, 19241, 18860, 18858, -1, 19242, 19187, 19161, -1, 19241, 19195, 19240, -1, 19242, 19161, 19221, -1, 19243, 18885, 18887, -1, 19243, 18887, 19223, -1, 19244, 19152, 19201, -1, 19244, 18686, 19152, -1, 19245, 19203, 19189, -1, 19246, 19201, 19205, -1, 19245, 19189, 19227, -1, 19246, 19244, 19201, -1, 19247, 18686, 19244, -1, 19247, 19244, 19246, -1, 19248, 19208, 19231, -1, 19249, 19205, 19206, -1, 19249, 18686, 19247, -1, 19248, 19227, 19208, -1, 19249, 19246, 19205, -1, 19249, 19247, 19246, -1, 19250, 19193, 19229, -1, 19251, 18689, 18686, -1, 19250, 19216, 19193, -1, 19251, 19206, 18848, -1, 19251, 18848, 18689, -1, 19250, 19238, 19216, -1, 19251, 18686, 19249, -1, 19251, 19249, 19206, -1, 19252, 19221, 18539, -1, 19253, 19200, 19234, -1, 19254, 19209, 19211, -1, 19254, 19211, 19255, -1, 19253, 19220, 19200, -1, 19254, 19214, 19209, -1, 19256, 18934, 18933, -1, 19257, 19214, 19254, -1, 19256, 18933, 19232, -1, 19258, 19215, 19214, -1, 19258, 19076, 19215, -1, 19259, 18773, 18723, -1, 19260, 19231, 19212, -1, 19258, 19054, 19076, -1, 19260, 19212, 19239, -1, 19258, 19214, 19257, -1, 19259, 18723, 19204, -1, 19259, 19184, 19236, -1, 19261, 19219, 19197, -1, 19259, 19204, 19184, -1, 19262, 18885, 19243, -1, 19261, 19226, 19224, -1, 19263, 19213, 19238, -1, 19262, 18881, 18883, -1, 19262, 18883, 18885, -1, 19261, 19224, 19219, -1, 19264, 19226, 19261, -1, 19263, 19236, 19213, -1, 19177, 19202, 19225, -1, 19265, 19053, 18477, -1, 19265, 18477, 18642, -1, 19266, 18997, 19228, -1, 19177, 19229, 19202, -1, 19266, 19226, 19264, -1, 19266, 19267, 18997, -1, 19266, 19228, 19226, -1, 19268, 19237, 19111, -1, 19268, 19111, 19099, -1, 19269, 19203, 19245, -1, 19268, 19240, 19237, -1, 19270, 19207, 19187, -1, 19269, 19223, 19203, -1, 19270, 19187, 19242, -1, 19271, 19240, 19268, -1, 19272, 19245, 19227, -1, 19272, 19227, 19248, -1, 19273, 18862, 18860, -1, 19274, 19239, 19220, -1, 19273, 19240, 19271, -1, 19273, 18860, 19241, -1, 19273, 19241, 19240, -1, 19275, 19255, 19274, -1, 19274, 19220, 19253, -1, 19275, 19254, 19255, -1, 19275, 19257, 19254, -1, 19276, 19238, 19250, -1, 19277, 19054, 19258, -1, 19277, 19258, 19257, -1, 19278, 19221, 19252, -1, 19277, 19024, 19054, -1, 19278, 19242, 19221, -1, 19279, 19252, 18539, -1, 19280, 19231, 19260, -1, 19281, 19197, 19170, -1, 19279, 18539, 18502, -1, 19280, 19248, 19231, -1, 19281, 19264, 19261, -1, 18946, 19282, 19283, -1, 19281, 19261, 19197, -1, 19284, 19267, 19266, -1, 19285, 18881, 19262, -1, 19284, 19282, 19267, -1, 18946, 18934, 19256, -1, 19284, 19266, 19264, -1, 18932, 19018, 19053, -1, 19286, 19268, 19099, -1, 19286, 19271, 19268, -1, 18946, 19283, 18934, -1, 19287, 18376, 18773, -1, 18932, 19053, 19265, -1, 19286, 19099, 19081, -1, 19287, 19259, 19236, -1, 19287, 19236, 19263, -1, 19288, 18862, 19273, -1, 19287, 18773, 19259, -1, 19288, 19273, 19271, -1, 19289, 19262, 19243, -1, 19288, 18864, 18862, -1, 19176, 19229, 19177, -1, 19289, 19243, 19223, -1, 19289, 19223, 19269, -1, 19176, 19250, 19229, -1, 19290, 19275, 19274, -1, 19291, 19207, 19270, -1, 19290, 19274, 19253, -1, 19292, 19245, 19272, -1, 19292, 19269, 19245, -1, 19291, 19232, 19207, -1, 19293, 19257, 19275, -1, 19255, 19260, 19239, -1, 19293, 19275, 19290, -1, 19255, 19239, 19274, -1, 19293, 19290, 19294, -1, 19293, 19277, 19257, -1, 19295, 19293, 19294, -1, 18941, 19263, 19238, -1, 19295, 19277, 19293, -1, 19296, 19024, 19277, -1, 18941, 19238, 19276, -1, 19296, 18980, 19024, -1, 19296, 19277, 19295, -1, 19297, 19272, 19248, -1, 19298, 19281, 19170, -1, 19299, 19242, 19278, -1, 19297, 19248, 19280, -1, 19299, 19270, 19242, -1, 19298, 19170, 19148, -1, 19300, 18879, 18881, -1, 19300, 18881, 19285, -1, 19300, 18527, 18879, -1, 18979, 19278, 19252, -1, 18979, 19252, 19279, -1, 19301, 19281, 19298, -1, 18931, 19019, 19018, -1, 19301, 19284, 19264, -1, 19301, 19298, 19302, -1, 18931, 19018, 18932, -1, 19301, 19264, 19281, -1, 19303, 19284, 19301, -1, 19304, 19262, 19289, -1, 19303, 19301, 19302, -1, 18945, 19282, 18946, -1, 19305, 19283, 19282, -1, 19305, 19282, 19284, -1, 19305, 19284, 19303, -1, 19181, 19276, 19250, -1, 19306, 19286, 19081, -1, 18954, 19289, 19269, -1, 19181, 19250, 19176, -1, 18954, 19269, 19292, -1, 18962, 19232, 19291, -1, 19306, 19081, 18939, -1, 18962, 19256, 19232, -1, 19211, 19280, 19260, -1, 19211, 19260, 19255, -1, 19307, 19288, 19271, -1, 19307, 19286, 19306, -1, 19307, 19306, 19308, -1, 18959, 18642, 18710, -1, 19307, 19271, 19286, -1, 18959, 19265, 18642, -1, 19309, 19288, 19307, -1, 19309, 19307, 19308, -1, 18940, 18376, 19287, -1, 19310, 18864, 19288, -1, 18940, 19287, 19263, -1, 19310, 18866, 18864, -1, 19310, 19288, 19309, -1, 18940, 19263, 18941, -1, 19311, 19294, 19290, -1, 18986, 19291, 19270, -1, 19311, 19295, 19294, -1, 18986, 19270, 19299, -1, 18999, 19292, 19272, -1, 18999, 19272, 19297, -1, 19311, 19290, 19253, -1, 19312, 18975, 18980, -1, 19312, 19295, 19311, -1, 19312, 19296, 19295, -1, 19088, 19279, 18502, -1, 19312, 18980, 19296, -1, 19005, 18973, 19019, -1, 19005, 19019, 18931, -1, 18978, 19278, 18979, -1, 19313, 19298, 19148, -1, 18978, 19299, 19278, -1, 18992, 19262, 19304, -1, 19313, 19302, 19298, -1, 19313, 19303, 19302, -1, 18992, 19285, 19262, -1, 18929, 19305, 19303, -1, 18953, 19304, 19289, -1, 18929, 18934, 19283, -1, 18929, 19303, 19313, -1, 18929, 19283, 19305, -1, 18953, 19289, 18954, -1, 19007, 19267, 19282, -1, 18942, 19308, 19306, -1, 18942, 19306, 18939, -1, 19007, 18997, 19267, -1, 19210, 19297, 19280, -1, 18942, 19309, 19308, -1, 19210, 19280, 19211, -1, 19007, 19282, 18945, -1, 18956, 18868, 18866, -1, 18956, 19309, 18942, -1, 18956, 18866, 19310, -1, 18943, 18941, 19276, -1, 18956, 19310, 19309, -1, 18943, 19276, 19181, -1, 18966, 19311, 19253, -1, 18947, 18932, 19265, -1, 18966, 19253, 19234, -1, 18966, 19234, 18968, -1, 18949, 18946, 19256, -1, 18947, 19265, 18959, -1, 18949, 19256, 18962, -1, 18965, 19311, 18966, -1, 18971, 19311, 18965, -1, 18955, 18954, 19292, -1, 19314, 19311, 18971, -1, 18955, 19292, 18999, -1, 18960, 18959, 18710, -1, 19314, 19312, 19311, -1, 18963, 18962, 19291, -1, 18972, 19314, 18971, -1, 18972, 19312, 19314, -1, 18972, 18975, 19312, -1, 18972, 18973, 18975, -1, 18963, 19291, 18986, -1, 18984, 19148, 19128, -1, 18976, 18973, 19005, -1, 18984, 19128, 18988, -1, 18981, 18979, 19279, -1, 18984, 19313, 19148, -1, 18976, 18975, 18973, -1, 18991, 19300, 19285, -1, 18991, 18542, 18527, -1, 18983, 19313, 18984, -1, 18991, 19285, 18992, -1, 18981, 19279, 19088, -1, 18991, 18527, 19300, -1, 18993, 19304, 18953, -1, 18993, 18992, 19304, -1, 18928, 19313, 18983, -1, 18987, 18986, 19299, -1, 18987, 19299, 18978, -1, 18927, 19313, 18928, -1, 19000, 18999, 19297, -1, 18927, 18929, 19313, -1, 19000, 19297, 19210, -1, 19001, 18997, 19007, -1, 18312, 18311, 18505, -1, 18312, 18505, 18470, -1, 18292, 18470, 18452, -1, 18292, 18452, 18451, -1, 18292, 18312, 18470, -1, 18269, 18292, 18451, -1, 18245, 18451, 18354, -1, 18245, 18269, 18451, -1, 18223, 18354, 18349, -1, 18223, 18245, 18354, -1, 18200, 18349, 18775, -1, 18200, 18223, 18349, -1, 18160, 18775, 18745, -1, 18160, 18200, 18775, -1, 18161, 18745, 18727, -1, 18161, 18160, 18745, -1, 18140, 18727, 18701, -1, 18140, 18161, 18727, -1, 18116, 18701, 18700, -1, 18116, 18140, 18701, -1, 18106, 18700, 18638, -1, 18106, 18116, 18700, -1, 18096, 18638, 18634, -1, 18096, 18106, 18638, -1, 18086, 18634, 18630, -1, 18086, 18096, 18634, -1, 18081, 18630, 18626, -1, 18081, 18086, 18630, -1, 18075, 18626, 18625, -1, 18075, 18081, 18626, -1, 18076, 18075, 18625, -1, 18076, 18625, 18689, -1, 19315, 19316, 19317, -1, 19315, 19318, 19316, -1, 19319, 19320, 19321, -1, 19322, 19323, 19324, -1, 19319, 19321, 19325, -1, 19326, 19322, 19327, -1, 19326, 19323, 19322, -1, 19326, 19328, 19323, -1, 19329, 19330, 19331, -1, 19326, 19332, 19328, -1, 19329, 19331, 19333, -1, 19334, 19335, 19336, -1, 19337, 19338, 19339, -1, 19337, 19340, 19338, -1, 19337, 19341, 19340, -1, 19342, 18000, 17919, -1, 19334, 19336, 19343, -1, 19344, 19341, 19337, -1, 19342, 17919, 19345, -1, 19342, 19346, 19347, -1, 19342, 19345, 19346, -1, 19348, 19349, 19350, -1, 19351, 19341, 19344, -1, 19352, 19353, 19354, -1, 19355, 19341, 19351, -1, 19355, 19356, 19341, -1, 19357, 18836, 19356, -1, 19352, 19354, 19358, -1, 19357, 19355, 19351, -1, 19357, 19356, 19355, -1, 19359, 19343, 19360, -1, 19357, 18838, 18836, -1, 19361, 19362, 19363, -1, 19364, 19365, 19366, -1, 19359, 19360, 19367, -1, 19361, 19363, 19368, -1, 19369, 18259, 18041, -1, 19361, 19368, 19370, -1, 19371, 19362, 19361, -1, 19364, 19350, 19365, -1, 19369, 19367, 18259, -1, 19371, 19372, 19362, -1, 19371, 19373, 19372, -1, 19371, 19374, 19373, -1, 19375, 19376, 19377, -1, 19378, 19379, 19380, -1, 19381, 19317, 19382, -1, 19378, 19383, 19379, -1, 19381, 19382, 19384, -1, 19375, 19377, 19385, -1, 19378, 19380, 19386, -1, 19387, 19318, 19315, -1, 19388, 18102, 18090, -1, 19387, 19366, 19318, -1, 19388, 18090, 19389, -1, 19388, 19389, 19390, -1, 19391, 19327, 19383, -1, 19388, 19390, 19392, -1, 19391, 19326, 19327, -1, 19391, 19332, 19326, -1, 19393, 19320, 19319, -1, 19393, 19358, 19320, -1, 19391, 19383, 19378, -1, 19394, 19344, 19337, -1, 19395, 19330, 19329, -1, 19395, 19396, 19330, -1, 19394, 19337, 19339, -1, 19397, 19335, 19334, -1, 19394, 19339, 19381, -1, 19397, 19398, 19335, -1, 19399, 19351, 19344, -1, 19399, 19357, 19351, -1, 19399, 18838, 19357, -1, 19399, 19344, 19394, -1, 19400, 19349, 19348, -1, 19401, 19361, 19370, -1, 19400, 19333, 19349, -1, 19401, 19370, 19402, -1, 19403, 19350, 19364, -1, 19404, 19392, 19353, -1, 19404, 19353, 19352, -1, 19405, 19406, 19371, -1, 19405, 19371, 19361, -1, 19405, 19361, 19401, -1, 19405, 19401, 19406, -1, 19403, 19348, 19350, -1, 19407, 19371, 19406, -1, 19339, 19315, 19317, -1, 19408, 19343, 19359, -1, 18077, 18076, 18847, -1, 19408, 19334, 19343, -1, 19409, 19410, 19411, -1, 19409, 19371, 19407, -1, 19409, 19374, 19371, -1, 19412, 19359, 19367, -1, 19409, 19411, 19374, -1, 19339, 19317, 19381, -1, 19412, 19367, 19369, -1, 19413, 19364, 19366, -1, 19414, 19378, 19386, -1, 19413, 19366, 19387, -1, 19414, 19386, 19415, -1, 19416, 19376, 19375, -1, 19413, 19403, 19364, -1, 19416, 19417, 19376, -1, 19418, 19414, 19419, -1, 19418, 19391, 19378, -1, 19420, 19358, 19393, -1, 19418, 19378, 19414, -1, 19421, 19396, 19395, -1, 19420, 19352, 19358, -1, 19418, 19419, 19391, -1, 19421, 19422, 19396, -1, 19423, 19333, 19400, -1, 19424, 19391, 19419, -1, 19425, 19385, 19398, -1, 19423, 19395, 19329, -1, 19425, 19398, 19397, -1, 19426, 19427, 19428, -1, 19426, 19428, 19332, -1, 19426, 19332, 19391, -1, 19423, 19329, 19333, -1, 19426, 19391, 19424, -1, 19429, 19381, 19384, -1, 19429, 19394, 19381, -1, 19430, 19348, 19403, -1, 19431, 18102, 19388, -1, 19431, 19388, 19392, -1, 19432, 19399, 19394, -1, 19431, 19392, 19404, -1, 19432, 19394, 19429, -1, 19432, 19433, 19399, -1, 19434, 19397, 19334, -1, 19432, 19429, 19433, -1, 19430, 19400, 19348, -1, 19338, 19315, 19339, -1, 19434, 19334, 19408, -1, 19435, 19399, 19433, -1, 19436, 19399, 19435, -1, 19338, 19387, 19315, -1, 19437, 19369, 18041, -1, 19436, 18840, 18838, -1, 19436, 18842, 18840, -1, 19436, 18838, 19399, -1, 19438, 19401, 19402, -1, 19439, 19403, 19413, -1, 19440, 19408, 19359, -1, 19438, 19407, 19406, -1, 19440, 19359, 19412, -1, 19438, 19406, 19401, -1, 19441, 19442, 19422, -1, 19443, 19444, 19410, -1, 19443, 19407, 19438, -1, 19441, 19422, 19421, -1, 19443, 19410, 19409, -1, 19443, 19409, 19407, -1, 19445, 19446, 19417, -1, 19447, 19419, 19414, -1, 19445, 19417, 19416, -1, 19448, 19352, 19420, -1, 19447, 19414, 19415, -1, 19449, 19395, 19423, -1, 19447, 19424, 19419, -1, 19448, 19404, 19352, -1, 19450, 19424, 19447, -1, 19450, 19427, 19426, -1, 19450, 19426, 19424, -1, 19450, 19451, 19427, -1, 19452, 19423, 19400, -1, 19453, 19375, 19385, -1, 19454, 19435, 19433, -1, 19453, 19385, 19425, -1, 19452, 19400, 19430, -1, 19454, 19429, 19384, -1, 19454, 19433, 19429, -1, 19455, 19435, 19454, -1, 19455, 19436, 19435, -1, 19340, 19387, 19338, -1, 19455, 18844, 18842, -1, 19340, 19413, 19387, -1, 19455, 18842, 19436, -1, 19456, 19438, 19402, -1, 19456, 19457, 17993, -1, 19458, 19425, 19397, -1, 19459, 19430, 19403, -1, 19458, 19397, 19434, -1, 19456, 19402, 19457, -1, 19459, 19403, 19439, -1, 19460, 17993, 18028, -1, 19460, 19456, 17993, -1, 19415, 19369, 19437, -1, 19460, 19438, 19456, -1, 19415, 19412, 19369, -1, 19461, 19438, 19460, -1, 19461, 19460, 18028, -1, 19462, 19463, 19442, -1, 19464, 19443, 19438, -1, 19462, 19442, 19441, -1, 19465, 19434, 19408, -1, 19464, 19438, 19461, -1, 19465, 19408, 19440, -1, 19466, 19444, 19443, -1, 19466, 19443, 19464, -1, 19466, 19461, 18028, -1, 19466, 19464, 19461, -1, 19467, 19395, 19449, -1, 19466, 18028, 19444, -1, 19468, 19415, 19437, -1, 19469, 19446, 19445, -1, 19467, 19421, 19395, -1, 19468, 19447, 19415, -1, 19468, 19437, 18041, -1, 19469, 19470, 19446, -1, 19471, 18150, 18102, -1, 19472, 19423, 19452, -1, 19472, 19449, 19423, -1, 19471, 18102, 19431, -1, 19473, 18041, 18043, -1, 19471, 19404, 19448, -1, 19473, 19468, 18041, -1, 19471, 19431, 19404, -1, 19473, 19447, 19468, -1, 19474, 19439, 19413, -1, 19475, 19375, 19453, -1, 19476, 19447, 19473, -1, 19476, 19473, 18043, -1, 19475, 19416, 19375, -1, 19477, 19450, 19447, -1, 19477, 19447, 19476, -1, 19474, 19413, 19340, -1, 19478, 19450, 19477, -1, 19478, 19451, 19450, -1, 19478, 19476, 18043, -1, 19478, 19477, 19476, -1, 19478, 18043, 19451, -1, 19479, 19452, 19430, -1, 19479, 19430, 19459, -1, 19480, 19384, 19481, -1, 19480, 19481, 18053, -1, 19482, 19475, 19453, -1, 19479, 19472, 19452, -1, 19482, 19425, 19458, -1, 19480, 19454, 19384, -1, 19483, 19454, 19480, -1, 19484, 19485, 19463, -1, 19482, 19453, 19425, -1, 19484, 19463, 19462, -1, 19483, 18053, 18056, -1, 19386, 19440, 19412, -1, 19483, 19480, 18053, -1, 19486, 19421, 19467, -1, 19486, 19441, 19421, -1, 19487, 19454, 19483, -1, 19386, 19412, 19415, -1, 19487, 19483, 18056, -1, 19488, 19455, 19454, -1, 19488, 19454, 19487, -1, 19489, 19458, 19434, -1, 19490, 18844, 19455, -1, 19490, 19455, 19488, -1, 19489, 19434, 19465, -1, 19490, 18056, 18844, -1, 19490, 19487, 18056, -1, 19491, 19467, 19449, -1, 19490, 19488, 19487, -1, 19491, 19449, 19472, -1, 19492, 19493, 19470, -1, 19494, 19459, 19439, -1, 19492, 19470, 19469, -1, 19494, 19439, 19474, -1, 19495, 19445, 19416, -1, 19495, 19416, 19475, -1, 19496, 19472, 19479, -1, 19497, 18136, 18135, -1, 19497, 18211, 18136, -1, 19497, 19498, 19485, -1, 19497, 19485, 19484, -1, 19497, 18135, 19498, -1, 19499, 19441, 19486, -1, 19500, 18875, 18311, -1, 19501, 19475, 19482, -1, 19500, 18311, 18313, -1, 19499, 19462, 19441, -1, 19502, 19486, 19467, -1, 19503, 18875, 19500, -1, 19380, 19440, 19386, -1, 19380, 19465, 19440, -1, 19502, 19467, 19491, -1, 19503, 18873, 18875, -1, 19504, 19479, 19459, -1, 19504, 19459, 19494, -1, 19505, 19491, 19472, -1, 19506, 19482, 19458, -1, 19507, 18871, 18873, -1, 19507, 18873, 19503, -1, 19506, 19458, 19489, -1, 19505, 19472, 19496, -1, 19508, 19500, 18313, -1, 19509, 19484, 19462, -1, 19510, 19511, 19493, -1, 19508, 18313, 17942, -1, 19510, 19493, 19492, -1, 19509, 19462, 19499, -1, 19512, 19469, 19445, -1, 19513, 19499, 19486, -1, 19513, 19486, 19502, -1, 19514, 18869, 18871, -1, 19515, 19496, 19479, -1, 19512, 19445, 19495, -1, 19514, 18871, 19507, -1, 19516, 19500, 19508, -1, 19515, 19479, 19504, -1, 19517, 19491, 19505, -1, 19516, 19503, 19500, -1, 19518, 19495, 19475, -1, 19518, 19475, 19501, -1, 19519, 19508, 17942, -1, 19517, 19502, 19491, -1, 19520, 19497, 19484, -1, 19520, 19484, 19509, -1, 19520, 18211, 19497, -1, 19521, 19489, 19465, -1, 19522, 18867, 18869, -1, 19521, 19465, 19380, -1, 19522, 18869, 19514, -1, 19523, 19509, 19499, -1, 19523, 19499, 19513, -1, 19524, 19496, 19515, -1, 19524, 19505, 19496, -1, 19525, 19503, 19516, -1, 19525, 19507, 19503, -1, 19526, 19516, 19508, -1, 19527, 19513, 19502, -1, 19528, 19482, 19506, -1, 19527, 19502, 19517, -1, 19528, 19501, 19482, -1, 19526, 19508, 19519, -1, 19529, 18248, 18211, -1, 19530, 17942, 17993, -1, 19531, 19511, 19510, -1, 19529, 19520, 19509, -1, 19531, 19532, 19511, -1, 19530, 19519, 17942, -1, 19529, 19509, 19523, -1, 19529, 18211, 19520, -1, 19533, 19517, 19505, -1, 19533, 19505, 19524, -1, 19534, 18867, 19522, -1, 19535, 19492, 19469, -1, 19534, 18865, 18867, -1, 19536, 19523, 19513, -1, 19535, 19469, 19512, -1, 19536, 19513, 19527, -1, 19537, 19514, 19507, -1, 19538, 19527, 19517, -1, 19538, 19517, 19533, -1, 19539, 19535, 19512, -1, 19537, 19507, 19525, -1, 19539, 19495, 19518, -1, 19540, 19523, 19536, -1, 19539, 19512, 19495, -1, 19540, 19529, 19523, -1, 19540, 18248, 19529, -1, 19541, 19516, 19526, -1, 19541, 19525, 19516, -1, 19542, 19489, 19521, -1, 19543, 19526, 19519, -1, 19544, 19527, 19538, -1, 19542, 19506, 19489, -1, 19544, 19536, 19527, -1, 19543, 19519, 19530, -1, 19545, 18237, 18248, -1, 19545, 18248, 19540, -1, 19545, 19540, 19536, -1, 19545, 19536, 19544, -1, 19546, 18863, 18865, -1, 19546, 18865, 19534, -1, 19547, 19501, 19528, -1, 19547, 19518, 19501, -1, 19548, 19514, 19537, -1, 19549, 19393, 19319, -1, 19549, 19511, 19532, -1, 19548, 19522, 19514, -1, 19549, 19550, 19511, -1, 19549, 19319, 19550, -1, 19551, 19552, 19532, -1, 19553, 19420, 19393, -1, 19551, 19532, 19531, -1, 19553, 19532, 19552, -1, 19554, 19525, 19541, -1, 19553, 19549, 19532, -1, 19554, 19537, 19525, -1, 19553, 19393, 19549, -1, 19555, 18043, 18060, -1, 19556, 19448, 19420, -1, 19457, 19530, 17993, -1, 19556, 19420, 19553, -1, 19555, 19451, 18043, -1, 19556, 19553, 19552, -1, 19556, 19552, 19557, -1, 19558, 19510, 19492, -1, 19559, 19526, 19543, -1, 19558, 19492, 19535, -1, 19560, 19471, 19448, -1, 19559, 19541, 19526, -1, 19560, 19448, 19556, -1, 19561, 19535, 19539, -1, 19562, 18861, 18863, -1, 19563, 19560, 19556, -1, 19564, 19557, 19565, -1, 19564, 19556, 19557, -1, 19562, 18863, 19546, -1, 19566, 19506, 19542, -1, 19564, 19563, 19556, -1, 19566, 19528, 19506, -1, 19567, 19534, 19522, -1, 19567, 19522, 19548, -1, 19568, 19422, 19442, -1, 19569, 19537, 19554, -1, 19568, 19570, 19571, -1, 19568, 19571, 19572, -1, 19569, 19548, 19537, -1, 19568, 19572, 19422, -1, 19573, 19574, 19570, -1, 19573, 19570, 19568, -1, 19402, 19530, 19457, -1, 19573, 19442, 19463, -1, 19575, 19539, 19518, -1, 19573, 19568, 19442, -1, 19575, 19518, 19547, -1, 19402, 19543, 19530, -1, 19576, 19463, 19485, -1, 19576, 19347, 19574, -1, 19577, 19552, 19551, -1, 19576, 19574, 19573, -1, 19576, 19573, 19463, -1, 19578, 19541, 19559, -1, 19579, 19347, 19576, -1, 19578, 19554, 19541, -1, 19577, 19557, 19552, -1, 19579, 19342, 19347, -1, 19580, 19451, 19555, -1, 19581, 18859, 18861, -1, 19582, 19579, 19576, -1, 19580, 19427, 19451, -1, 19581, 18861, 19562, -1, 19583, 19582, 19576, -1, 19584, 19546, 19534, -1, 19583, 19576, 19485, -1, 19583, 19485, 19498, -1, 19585, 19531, 19510, -1, 19585, 19510, 19558, -1, 19584, 19534, 19567, -1, 19586, 19558, 19535, -1, 19586, 19535, 19561, -1, 19587, 19567, 19548, -1, 19588, 19589, 18824, -1, 19588, 19524, 19589, -1, 19587, 19548, 19569, -1, 19588, 19533, 19524, -1, 19588, 18824, 18822, -1, 19590, 19533, 19588, -1, 19591, 19528, 19566, -1, 19590, 19588, 18822, -1, 19370, 19559, 19543, -1, 19591, 19547, 19528, -1, 19370, 19543, 19402, -1, 19590, 18822, 18820, -1, 19590, 19538, 19533, -1, 19592, 19538, 19590, -1, 19593, 19554, 19578, -1, 19592, 18820, 18818, -1, 19593, 19569, 19554, -1, 19592, 19590, 18820, -1, 19592, 19544, 19538, -1, 19594, 19544, 19592, -1, 19595, 19539, 19575, -1, 19594, 19545, 19544, -1, 19596, 18857, 18859, -1, 19595, 19561, 19539, -1, 19597, 19594, 19592, -1, 19596, 18859, 19581, -1, 19598, 18273, 18204, -1, 19598, 19565, 19557, -1, 19598, 18204, 19565, -1, 19598, 19557, 19577, -1, 19599, 19597, 19592, -1, 19600, 19428, 19427, -1, 19600, 19427, 19580, -1, 19599, 18818, 18815, -1, 19601, 19562, 19546, -1, 19599, 19592, 18818, -1, 19601, 19546, 19584, -1, 19602, 19325, 19603, -1, 19602, 19319, 19325, -1, 19602, 19550, 19319, -1, 19604, 19567, 19587, -1, 19604, 19584, 19567, -1, 19605, 19550, 19602, -1, 19606, 19531, 19585, -1, 19607, 19470, 19493, -1, 19606, 19551, 19531, -1, 19607, 19493, 19511, -1, 19368, 19578, 19559, -1, 19607, 19550, 19605, -1, 19608, 19558, 19586, -1, 19368, 19559, 19370, -1, 19607, 19511, 19550, -1, 19608, 19585, 19558, -1, 19609, 18150, 19471, -1, 19609, 19471, 19560, -1, 19609, 19560, 19563, -1, 19610, 18204, 18150, -1, 19611, 19569, 19593, -1, 19610, 18150, 19609, -1, 19612, 19575, 19547, -1, 19612, 19547, 19591, -1, 19610, 19609, 19563, -1, 19611, 19587, 19569, -1, 19613, 19565, 18204, -1, 19614, 18060, 18091, -1, 19613, 19610, 19563, -1, 19613, 18204, 19610, -1, 19613, 19564, 19565, -1, 19615, 18857, 19596, -1, 19613, 19563, 19564, -1, 19614, 19555, 18060, -1, 19616, 19571, 19617, -1, 19615, 18856, 18857, -1, 19616, 19572, 19571, -1, 19616, 19617, 19612, -1, 19618, 19572, 19616, -1, 19619, 19562, 19601, -1, 19620, 19330, 19396, -1, 19619, 19581, 19562, -1, 19620, 19572, 19618, -1, 19620, 19422, 19572, -1, 19621, 19586, 19561, -1, 19622, 19601, 19584, -1, 19620, 19396, 19422, -1, 19621, 19561, 19595, -1, 19623, 19342, 19579, -1, 19622, 19584, 19604, -1, 19624, 19332, 19428, -1, 19623, 19579, 19582, -1, 19624, 19428, 19600, -1, 19623, 18000, 19342, -1, 19625, 19623, 19582, -1, 19626, 19578, 19368, -1, 19625, 18135, 18000, -1, 19625, 18000, 19623, -1, 19627, 19582, 19583, -1, 19626, 19593, 19578, -1, 19627, 19583, 19498, -1, 19627, 19625, 19582, -1, 19628, 19577, 19551, -1, 19627, 18135, 19625, -1, 19627, 19498, 18135, -1, 19628, 19551, 19606, -1, 19629, 19515, 19504, -1, 19629, 19524, 19515, -1, 19629, 19589, 19524, -1, 19630, 19606, 19585, -1, 19630, 19585, 19608, -1, 19631, 19587, 19611, -1, 19631, 19604, 19587, -1, 19632, 19589, 19629, -1, 19633, 18824, 19589, -1, 19633, 18826, 18824, -1, 19617, 19595, 19575, -1, 19633, 18828, 18826, -1, 19617, 19575, 19612, -1, 19634, 18854, 18856, -1, 19633, 19589, 19632, -1, 19634, 18856, 19615, -1, 19635, 19580, 19555, -1, 19636, 19545, 19594, -1, 19635, 19555, 19614, -1, 19636, 18237, 19545, -1, 19637, 19596, 19581, -1, 19638, 19594, 19597, -1, 19638, 19636, 19594, -1, 19637, 19581, 19619, -1, 19639, 19601, 19622, -1, 19640, 18237, 19636, -1, 19639, 19619, 19601, -1, 19640, 19636, 19638, -1, 19641, 19597, 19599, -1, 19641, 19638, 19597, -1, 19641, 18237, 19640, -1, 19642, 19611, 19593, -1, 19641, 19640, 19638, -1, 19643, 18239, 18237, -1, 19643, 19599, 18815, -1, 19644, 19608, 19586, -1, 19643, 18815, 18239, -1, 19644, 19586, 19621, -1, 19643, 18237, 19641, -1, 19643, 19641, 19599, -1, 19645, 19603, 19646, -1, 19647, 19614, 18091, -1, 19642, 19593, 19626, -1, 19645, 19605, 19602, -1, 19645, 19602, 19603, -1, 19648, 19328, 19332, -1, 19649, 19605, 19645, -1, 19648, 19332, 19624, -1, 19650, 19605, 19649, -1, 19650, 19607, 19605, -1, 19651, 19622, 19604, -1, 19650, 19470, 19607, -1, 19652, 19577, 19628, -1, 19651, 19604, 19631, -1, 19650, 19446, 19470, -1, 19652, 19598, 19577, -1, 19652, 18322, 18273, -1, 19652, 18273, 19598, -1, 19653, 18852, 18854, -1, 19654, 19616, 19612, -1, 19653, 18854, 19634, -1, 19654, 19618, 19616, -1, 19655, 19606, 19630, -1, 19654, 19612, 19591, -1, 19655, 19628, 19606, -1, 19656, 19618, 19654, -1, 19571, 19595, 19617, -1, 19657, 18028, 18191, -1, 19657, 19444, 18028, -1, 19658, 19618, 19656, -1, 19659, 19615, 19596, -1, 19658, 19331, 19330, -1, 19571, 19621, 19595, -1, 19658, 19330, 19620, -1, 19658, 19620, 19618, -1, 19660, 19504, 19494, -1, 19661, 19600, 19580, -1, 19660, 19629, 19504, -1, 19659, 19596, 19637, -1, 19660, 19632, 19629, -1, 19661, 19580, 19635, -1, 19662, 19637, 19619, -1, 19663, 19632, 19660, -1, 19662, 19619, 19639, -1, 19664, 19632, 19663, -1, 19665, 19631, 19611, -1, 19664, 18830, 18828, -1, 19664, 18828, 19633, -1, 19664, 19633, 19632, -1, 19665, 19611, 19642, -1, 19666, 19649, 19645, -1, 19667, 19608, 19644, -1, 19666, 19645, 19646, -1, 19666, 19646, 19665, -1, 19667, 19630, 19608, -1, 19668, 19446, 19650, -1, 19668, 19650, 19649, -1, 19668, 19417, 19446, -1, 19669, 19639, 19622, -1, 19670, 19614, 19647, -1, 19671, 19654, 19591, -1, 19670, 19635, 19614, -1, 19672, 19647, 18091, -1, 19669, 19622, 19651, -1, 19671, 19656, 19654, -1, 19672, 18091, 18053, -1, 19671, 19591, 19566, -1, 19673, 18850, 18852, -1, 19674, 19658, 19656, -1, 19674, 19331, 19658, -1, 19674, 19675, 19331, -1, 19676, 19677, 19328, -1, 19673, 18852, 19653, -1, 19336, 19410, 19444, -1, 19678, 19494, 19474, -1, 19678, 19663, 19660, -1, 19336, 19444, 19657, -1, 19676, 19328, 19648, -1, 19678, 19660, 19494, -1, 19679, 17919, 18322, -1, 19679, 19628, 19655, -1, 19680, 19664, 19663, -1, 19679, 18322, 19652, -1, 19680, 18830, 19664, -1, 19679, 19652, 19628, -1, 19680, 18832, 18830, -1, 19681, 19634, 19615, -1, 19570, 19644, 19621, -1, 19681, 19615, 19659, -1, 19682, 19666, 19665, -1, 19570, 19621, 19571, -1, 19682, 19665, 19642, -1, 19683, 19600, 19661, -1, 19684, 19659, 19637, -1, 19684, 19637, 19662, -1, 19683, 19624, 19600, -1, 19685, 19668, 19649, -1, 19646, 19651, 19631, -1, 19685, 19666, 19682, -1, 19646, 19631, 19665, -1, 19685, 19682, 19686, -1, 19685, 19649, 19666, -1, 19687, 19668, 19685, -1, 19687, 19685, 19686, -1, 19688, 19417, 19668, -1, 19346, 19655, 19630, -1, 19688, 19668, 19687, -1, 19346, 19630, 19667, -1, 19321, 19639, 19669, -1, 19688, 19376, 19417, -1, 19321, 19662, 19639, -1, 19689, 19671, 19566, -1, 19316, 19635, 19670, -1, 19689, 19566, 19542, -1, 19316, 19661, 19635, -1, 19690, 18847, 18850, -1, 19690, 18850, 19673, -1, 19690, 18077, 18847, -1, 19335, 19411, 19410, -1, 19691, 19656, 19671, -1, 19335, 19410, 19336, -1, 19691, 19674, 19656, -1, 19691, 19671, 19689, -1, 19691, 19689, 19692, -1, 19382, 19670, 19647, -1, 19382, 19647, 19672, -1, 19693, 19634, 19681, -1, 19693, 19653, 19634, -1, 19694, 19674, 19691, -1, 19694, 19691, 19692, -1, 19349, 19675, 19677, -1, 19695, 19675, 19674, -1, 19695, 19677, 19675, -1, 19349, 19677, 19676, -1, 19695, 19674, 19694, -1, 19696, 19678, 19474, -1, 19574, 19644, 19570, -1, 19354, 19681, 19659, -1, 19574, 19667, 19644, -1, 19354, 19659, 19684, -1, 19696, 19474, 19340, -1, 19365, 19648, 19624, -1, 19603, 19669, 19651, -1, 19603, 19651, 19646, -1, 19697, 19680, 19663, -1, 19697, 19678, 19696, -1, 19360, 18191, 18259, -1, 19697, 19696, 19698, -1, 19365, 19624, 19683, -1, 19697, 19698, 19680, -1, 19360, 19657, 18191, -1, 19697, 19663, 19678, -1, 19699, 19680, 19698, -1, 19700, 18832, 19680, -1, 19700, 18834, 18832, -1, 19700, 19680, 19699, -1, 19345, 17919, 19679, -1, 19345, 19655, 19346, -1, 19345, 19679, 19655, -1, 19701, 19682, 19642, -1, 19701, 19686, 19682, -1, 19318, 19661, 19316, -1, 19320, 19684, 19662, -1, 19701, 19687, 19686, -1, 19320, 19662, 19321, -1, 19702, 19687, 19701, -1, 19702, 19377, 19376, -1, 19318, 19683, 19661, -1, 19702, 19688, 19687, -1, 19398, 19411, 19335, -1, 19702, 19376, 19688, -1, 19324, 19694, 19692, -1, 19481, 19672, 18053, -1, 19398, 19374, 19411, -1, 19324, 19689, 19542, -1, 19324, 19692, 19689, -1, 19390, 19653, 19693, -1, 19317, 19670, 19382, -1, 19390, 19673, 19653, -1, 19323, 19328, 19677, -1, 19317, 19316, 19670, -1, 19323, 19694, 19324, -1, 19323, 19677, 19695, -1, 19323, 19695, 19694, -1, 19353, 19681, 19354, -1, 19353, 19693, 19681, -1, 19341, 19698, 19696, -1, 19333, 19331, 19675, -1, 19341, 19696, 19340, -1, 19325, 19669, 19603, -1, 19341, 19699, 19698, -1, 19333, 19675, 19349, -1, 19356, 18836, 18834, -1, 19325, 19321, 19669, -1, 19356, 19699, 19341, -1, 19356, 18834, 19700, -1, 19356, 19700, 19699, -1, 19347, 19346, 19667, -1, 19343, 19657, 19360, -1, 19363, 19626, 19368, -1, 19347, 19667, 19574, -1, 19363, 19642, 19626, -1, 19343, 19336, 19657, -1, 19363, 19701, 19642, -1, 19350, 19648, 19365, -1, 19350, 19349, 19676, -1, 19362, 19701, 19363, -1, 19350, 19676, 19648, -1, 19358, 19354, 19684, -1, 19372, 19701, 19362, -1, 19703, 19701, 19372, -1, 19358, 19684, 19320, -1, 19703, 19702, 19701, -1, 19367, 19360, 18259, -1, 19373, 19703, 19372, -1, 19373, 19702, 19703, -1, 19373, 19374, 19377, -1, 19373, 19377, 19702, -1, 19379, 19324, 19542, -1, 19385, 19377, 19374, -1, 19379, 19521, 19380, -1, 19385, 19374, 19398, -1, 19366, 19365, 19683, -1, 19366, 19683, 19318, -1, 19379, 19542, 19521, -1, 19389, 18090, 18077, -1, 19384, 19382, 19672, -1, 19389, 19673, 19390, -1, 19389, 19690, 19673, -1, 19389, 18077, 19690, -1, 19383, 19324, 19379, -1, 19384, 19672, 19481, -1, 19392, 19693, 19353, -1, 19327, 19324, 19383, -1, 19392, 19390, 19693, -1, 19322, 19324, 19327, -1, 19704, 18846, 18056, -1, 19704, 18056, 18022, -1, 19705, 18022, 18003, -1, 19705, 19704, 18022, -1, 19706, 18003, 18002, -1, 19706, 19705, 18003, -1, 19707, 18002, 17903, -1, 19707, 19706, 18002, -1, 19708, 17903, 17901, -1, 19708, 19707, 17903, -1, 19709, 17901, 18325, -1, 19709, 19708, 17901, -1, 19710, 18325, 18295, -1, 19710, 19709, 18325, -1, 19711, 18295, 18277, -1, 19711, 19710, 18295, -1, 19712, 18277, 18252, -1, 19712, 19711, 18277, -1, 19713, 18252, 18251, -1, 19713, 19712, 18252, -1, 19714, 18251, 18188, -1, 19714, 19713, 18251, -1, 19715, 18188, 18185, -1, 19715, 19714, 18188, -1, 19716, 18185, 18182, -1, 19716, 19715, 18185, -1, 19717, 18182, 18178, -1, 19717, 19716, 18182, -1, 19718, 18178, 18177, -1, 19718, 19717, 18178, -1, 19719, 19718, 18177, -1, 19719, 18177, 18239, -1, 18816, 19719, 18239, -1, 19720, 19721, 19722, -1, 19720, 19723, 19721, -1, 19724, 19725, 19726, -1, 19724, 19727, 19725, -1, 19728, 18924, 19729, -1, 19723, 18890, 18888, -1, 19730, 19731, 19732, -1, 18911, 19733, 18912, -1, 18912, 19733, 19727, -1, 19731, 19734, 19732, -1, 18911, 18910, 19733, -1, 19732, 19735, 19730, -1, 19732, 19736, 19724, -1, 18920, 18919, 19724, -1, 19734, 19736, 19732, -1, 19728, 18925, 18924, -1, 19732, 19737, 19735, -1, 19738, 18925, 19739, -1, 19739, 18925, 19728, -1, 19732, 18782, 19737, -1, 18796, 19723, 19740, -1, 19736, 19741, 19724, -1, 18910, 18909, 19733, -1, 18794, 19723, 18796, -1, 19740, 19723, 19742, -1, 19743, 19723, 18794, -1, 19738, 18877, 18925, -1, 19744, 18877, 19738, -1, 18919, 18918, 19724, -1, 19741, 19745, 19724, -1, 19745, 19746, 19724, -1, 19744, 18878, 18877, -1, 19747, 18878, 19748, -1, 19748, 18878, 19744, -1, 18894, 19720, 18896, -1, 19749, 18880, 19750, -1, 18896, 19720, 18898, -1, 19750, 18880, 19747, -1, 18898, 19720, 18900, -1, 19747, 18880, 18878, -1, 18900, 19720, 18902, -1, 18902, 19720, 18904, -1, 19720, 19751, 18904, -1, 18904, 19751, 18906, -1, 18906, 19751, 18908, -1, 18908, 19751, 18909, -1, 18909, 19751, 19733, -1, 19742, 18882, 19749, -1, 19723, 19720, 18894, -1, 19723, 18894, 18892, -1, 19749, 18882, 18880, -1, 19723, 18892, 18890, -1, 18782, 19743, 18783, -1, 18783, 19743, 18786, -1, 18786, 19743, 18788, -1, 18788, 19743, 18790, -1, 18790, 19743, 18792, -1, 18792, 19743, 18794, -1, 19732, 19743, 18782, -1, 19742, 18884, 18882, -1, 19723, 18884, 19742, -1, 19746, 18922, 19724, -1, 19723, 18886, 18884, -1, 18922, 18921, 19724, -1, 19746, 18923, 18922, -1, 19729, 18923, 19752, -1, 18918, 19727, 19724, -1, 19752, 18923, 19746, -1, 18913, 19727, 18914, -1, 18914, 19727, 18915, -1, 18915, 19727, 18916, -1, 18916, 19727, 18917, -1, 18917, 19727, 18918, -1, 18913, 18912, 19727, -1, 18921, 18920, 19724, -1, 19729, 18924, 18923, -1, 19723, 18888, 18886, -1, 19721, 18795, 18797, -1, 19721, 18797, 19753, -1, 19721, 19753, 19754, -1, 19721, 19754, 19755, -1, 19721, 19756, 18795, -1, 19725, 19757, 19758, -1, 19725, 19758, 19759, -1, 19725, 19759, 19760, -1, 19725, 19760, 19761, -1, 19725, 19761, 19726, -1, 19762, 19763, 19764, -1, 19722, 19721, 19755, -1, 19722, 19755, 19765, -1, 19766, 19762, 19764, -1, 19722, 19765, 19767, -1, 19722, 19767, 19768, -1, 19722, 19768, 19769, -1, 19722, 19769, 19757, -1, 19770, 19764, 19763, -1, 19722, 19757, 19725, -1, 19771, 19764, 19726, -1, 19772, 19725, 19773, -1, 19772, 19722, 19725, -1, 19771, 19766, 19764, -1, 19774, 19764, 19770, -1, 18784, 19764, 19774, -1, 19775, 19771, 19726, -1, 19776, 19775, 19726, -1, 19777, 19776, 19726, -1, 19761, 19777, 19726, -1, 19756, 18784, 18785, -1, 19756, 18785, 18787, -1, 19756, 18787, 18789, -1, 19756, 18789, 18791, -1, 19756, 18791, 18793, -1, 19756, 18793, 18795, -1, 19756, 19764, 18784, -1, 19756, 19743, 19732, -1, 19756, 19732, 19764, -1, 19751, 19772, 19773, -1, 19751, 19773, 19733, -1, 19778, 19779, 19780, -1, 19778, 19780, 19781, -1, 19782, 19783, 19784, -1, 19782, 19785, 19783, -1, 18827, 19778, 18825, -1, 19786, 19705, 19706, -1, 19787, 19788, 19789, -1, 19786, 19706, 19782, -1, 19790, 19789, 19788, -1, 19704, 19705, 19786, -1, 19791, 19788, 19787, -1, 19713, 19714, 19785, -1, 19792, 19790, 19788, -1, 19719, 19793, 19718, -1, 19794, 19788, 19791, -1, 19795, 19788, 19785, -1, 19719, 19796, 19793, -1, 19795, 19792, 19788, -1, 19778, 19797, 18812, -1, 18846, 19704, 19786, -1, 19778, 18812, 18810, -1, 19778, 19798, 19797, -1, 18816, 19796, 19719, -1, 18816, 18799, 18798, -1, 18816, 18798, 19796, -1, 19799, 19795, 19785, -1, 19712, 19713, 19785, -1, 19800, 19799, 19785, -1, 18814, 18799, 18816, -1, 18814, 18802, 18799, -1, 18814, 18804, 18802, -1, 19779, 18831, 18833, -1, 19779, 18833, 18835, -1, 19779, 18835, 18837, -1, 19779, 18837, 18839, -1, 19779, 18839, 18841, -1, 18817, 18806, 18804, -1, 18817, 18804, 18814, -1, 19801, 19779, 18841, -1, 19801, 18841, 18843, -1, 19801, 18843, 18845, -1, 19801, 18845, 18846, -1, 19801, 18846, 19786, -1, 19779, 19778, 18831, -1, 18831, 19778, 18829, -1, 18829, 19778, 18827, -1, 19798, 19802, 19797, -1, 18819, 18806, 18817, -1, 19798, 19803, 19802, -1, 19798, 19804, 19803, -1, 19798, 19805, 19804, -1, 18819, 18808, 18806, -1, 19798, 19806, 19805, -1, 18819, 18810, 18808, -1, 19798, 19807, 19806, -1, 19798, 19794, 19807, -1, 19798, 19788, 19794, -1, 18821, 19778, 18810, -1, 18821, 18810, 18819, -1, 19716, 19800, 19785, -1, 19715, 19716, 19785, -1, 19717, 19800, 19716, -1, 19717, 19808, 19800, -1, 19717, 19809, 19808, -1, 18823, 19778, 18821, -1, 19782, 19707, 19708, -1, 19782, 19708, 19709, -1, 19782, 19709, 19710, -1, 19782, 19710, 19711, -1, 19782, 19711, 19712, -1, 19782, 19712, 19785, -1, 19706, 19707, 19782, -1, 19714, 19715, 19785, -1, 19718, 19809, 19717, -1, 18825, 19778, 18823, -1, 19718, 19810, 19809, -1, 19718, 19793, 19810, -1, 19811, 19784, 19812, -1, 19813, 19784, 19811, -1, 19814, 19784, 19813, -1, 18800, 19784, 19814, -1, 19812, 19784, 19783, -1, 19815, 19816, 19817, -1, 19784, 19780, 19818, -1, 18801, 19780, 18800, -1, 18803, 19780, 18801, -1, 18805, 19780, 18803, -1, 18807, 19780, 18805, -1, 19817, 19819, 19815, -1, 18800, 19780, 19784, -1, 19781, 19780, 18807, -1, 19815, 19820, 19816, -1, 19780, 19821, 19818, -1, 19819, 19822, 19815, -1, 19815, 19823, 19820, -1, 19815, 19824, 19783, -1, 19822, 19824, 19815, -1, 19824, 19825, 19783, -1, 19825, 19826, 19783, -1, 19826, 19827, 19783, -1, 19827, 19812, 19783, -1, 19828, 19829, 19830, -1, 19831, 19829, 19828, -1, 19832, 19829, 19831, -1, 19833, 19829, 19832, -1, 19834, 19829, 19833, -1, 19835, 19829, 19834, -1, 19823, 19829, 19835, -1, 19815, 19829, 19823, -1, 19830, 19781, 18813, -1, 18809, 19781, 18807, -1, 18811, 19781, 18809, -1, 18813, 19781, 18811, -1, 19829, 19781, 19830, -1, 19821, 19801, 19786, -1, 19821, 19786, 19818, -1, 19798, 19829, 19815, -1, 19798, 19815, 19788, -1, 19797, 19802, 19830, -1, 19830, 19802, 19828, -1, 19828, 19803, 19831, -1, 19802, 19803, 19828, -1, 19831, 19804, 19832, -1, 19803, 19804, 19831, -1, 19832, 19805, 19833, -1, 19804, 19805, 19832, -1, 19833, 19806, 19834, -1, 19805, 19806, 19833, -1, 19834, 19807, 19835, -1, 19806, 19807, 19834, -1, 19835, 19794, 19823, -1, 19807, 19794, 19835, -1, 19823, 19791, 19820, -1, 19794, 19791, 19823, -1, 19820, 19787, 19816, -1, 19791, 19787, 19820, -1, 19816, 19789, 19817, -1, 19787, 19789, 19816, -1, 19817, 19790, 19819, -1, 19789, 19790, 19817, -1, 19819, 19792, 19822, -1, 19790, 19792, 19819, -1, 19822, 19795, 19824, -1, 19792, 19795, 19822, -1, 18813, 19797, 19830, -1, 18812, 19797, 18813, -1, 19799, 19800, 19825, -1, 19825, 19800, 19826, -1, 19826, 19808, 19827, -1, 19800, 19808, 19826, -1, 19827, 19809, 19812, -1, 19808, 19809, 19827, -1, 19812, 19810, 19811, -1, 19809, 19810, 19812, -1, 19811, 19793, 19813, -1, 19810, 19793, 19811, -1, 19813, 19796, 19814, -1, 19793, 19796, 19813, -1, 19814, 18798, 18800, -1, 19796, 18798, 19814, -1, 19824, 19799, 19825, -1, 19795, 19799, 19824, -1, 19741, 19736, 19775, -1, 19775, 19736, 19771, -1, 19771, 19734, 19766, -1, 19736, 19734, 19771, -1, 19766, 19731, 19762, -1, 19734, 19731, 19766, -1, 19762, 19730, 19763, -1, 19731, 19730, 19762, -1, 19763, 19735, 19770, -1, 19730, 19735, 19763, -1, 19770, 19737, 19774, -1, 19735, 19737, 19770, -1, 19774, 18782, 18784, -1, 19737, 18782, 19774, -1, 19776, 19741, 19775, -1, 19745, 19741, 19776, -1, 19740, 19742, 19753, -1, 19753, 19742, 19754, -1, 19754, 19749, 19755, -1, 19742, 19749, 19754, -1, 19755, 19750, 19765, -1, 19749, 19750, 19755, -1, 19765, 19747, 19767, -1, 19750, 19747, 19765, -1, 19767, 19748, 19768, -1, 19747, 19748, 19767, -1, 19768, 19744, 19769, -1, 19748, 19744, 19768, -1, 19769, 19738, 19757, -1, 19744, 19738, 19769, -1, 19757, 19739, 19758, -1, 19738, 19739, 19757, -1, 19758, 19728, 19759, -1, 19739, 19728, 19758, -1, 19759, 19729, 19760, -1, 19728, 19729, 19759, -1, 19760, 19752, 19761, -1, 19729, 19752, 19760, -1, 19761, 19746, 19777, -1, 19752, 19746, 19761, -1, 19777, 19745, 19776, -1, 19746, 19745, 19777, -1, 18797, 19740, 19753, -1, 18796, 19740, 18797, -1, 19720, 19722, 19751, -1, 19751, 19722, 19772, -1, 19743, 19756, 19723, -1, 19723, 19756, 19721, -1, 19724, 19726, 19732, -1, 19732, 19726, 19764, -1, 19733, 19773, 19727, -1, 19727, 19773, 19725, -1, 19801, 19821, 19779, -1, 19779, 19821, 19780, -1, 19782, 19784, 19786, -1, 19786, 19784, 19818, -1, 19788, 19815, 19785, -1, 19785, 19815, 19783, -1, 19778, 19781, 19798, -1, 19798, 19781, 19829, -1, 19836, 19837, 19838, -1, 19838, 19837, 19839, -1, 19839, 19840, 19841, -1, 19837, 19840, 19839, -1, 19841, 19842, 19843, -1, 19840, 19842, 19841, -1, 19843, 19844, 19845, -1, 19842, 19844, 19843, -1, 19845, 19846, 19847, -1, 19844, 19846, 19845, -1, 19847, 19848, 19849, -1, 19846, 19848, 19847, -1, 19849, 19850, 19851, -1, 19848, 19850, 19849, -1, 19851, 19852, 19853, -1, 19850, 19852, 19851, -1, 19853, 19854, 19855, -1, 19852, 19854, 19853, -1, 19855, 19856, 19857, -1, 19854, 19856, 19855, -1, 19857, 19858, 19859, -1, 19856, 19858, 19857, -1, 19859, 19860, 19861, -1, 19858, 19860, 19859, -1, 19861, 19862, 19863, -1, 19860, 19862, 19861, -1, 19864, 19865, 19866, -1, 19866, 19865, 19867, -1, 19867, 19868, 19869, -1, 19865, 19868, 19867, -1, 19869, 19870, 19871, -1, 19868, 19870, 19869, -1, 19871, 19872, 19873, -1, 19870, 19872, 19871, -1, 19873, 19874, 19875, -1, 19872, 19874, 19873, -1, 19875, 19876, 19877, -1, 19874, 19876, 19875, -1, 19877, 19878, 19879, -1, 19876, 19878, 19877, -1, 19879, 19880, 19881, -1, 19878, 19880, 19879, -1, 19881, 19882, 19883, -1, 19880, 19882, 19881, -1, 19883, 19884, 19885, -1, 19882, 19884, 19883, -1, 19885, 19886, 19887, -1, 19884, 19886, 19885, -1, 19887, 19888, 19889, -1, 19886, 19888, 19887, -1, 19889, 19890, 19891, -1, 19888, 19890, 19889, -1, 19892, 19893, 19894, -1, 19892, 19895, 19893, -1, 19895, 19896, 19893, -1, 19895, 19897, 19896, -1, 19897, 19898, 19896, -1, 19897, 19899, 19898, -1, 19899, 19900, 19898, -1, 19899, 19901, 19900, -1, 19901, 19902, 19900, -1, 19901, 19903, 19902, -1, 19903, 19904, 19902, -1, 19903, 19905, 19904, -1, 19905, 19906, 19904, -1, 19905, 19907, 19906, -1, 19907, 19908, 19906, -1, 19907, 19909, 19908, -1, 19909, 19910, 19908, -1, 19909, 19911, 19910, -1, 19911, 19912, 19910, -1, 19911, 19913, 19912, -1, 19913, 19914, 19912, -1, 19913, 19915, 19914, -1, 19915, 19916, 19914, -1, 19915, 19917, 19916, -1, 19916, 19918, 19919, -1, 19917, 19918, 19916, -1, 19920, 19921, 19922, -1, 19920, 19923, 19921, -1, 19923, 19924, 19921, -1, 19923, 19925, 19924, -1, 19925, 19926, 19924, -1, 19925, 19927, 19926, -1, 19927, 19928, 19926, -1, 19927, 19929, 19928, -1, 19929, 19930, 19928, -1, 19929, 19931, 19930, -1, 19931, 19932, 19930, -1, 19931, 19933, 19932, -1, 19933, 19934, 19932, -1, 19933, 19935, 19934, -1, 19935, 19936, 19934, -1, 19935, 19937, 19936, -1, 19937, 19938, 19936, -1, 19937, 19939, 19938, -1, 19938, 19940, 19941, -1, 19939, 19940, 19938, -1, 19940, 19942, 19941, -1, 19940, 19943, 19942, -1, 19943, 19944, 19942, -1, 19943, 19945, 19944, -1, 19944, 19946, 19947, -1, 19945, 19946, 19944, -1, 19922, 19921, 19948, -1, 19948, 19921, 19949, -1, 19949, 19924, 19950, -1, 19921, 19924, 19949, -1, 19950, 19926, 19951, -1, 19924, 19926, 19950, -1, 19951, 19928, 19952, -1, 19926, 19928, 19951, -1, 19952, 19930, 19953, -1, 19928, 19930, 19952, -1, 19953, 19932, 19954, -1, 19930, 19932, 19953, -1, 19954, 19934, 19955, -1, 19932, 19934, 19954, -1, 19955, 19936, 19956, -1, 19934, 19936, 19955, -1, 19956, 19938, 19957, -1, 19936, 19938, 19956, -1, 19957, 19941, 19958, -1, 19938, 19941, 19957, -1, 19958, 19942, 19959, -1, 19941, 19942, 19958, -1, 19959, 19944, 19960, -1, 19942, 19944, 19959, -1, 19960, 19947, 19961, -1, 19944, 19947, 19960, -1, 19894, 19893, 19962, -1, 19962, 19893, 19963, -1, 19963, 19893, 19964, -1, 19964, 19896, 19965, -1, 19893, 19896, 19964, -1, 19965, 19898, 19966, -1, 19896, 19898, 19965, -1, 19966, 19900, 19967, -1, 19898, 19900, 19966, -1, 19967, 19902, 19968, -1, 19900, 19902, 19967, -1, 19968, 19904, 19969, -1, 19902, 19904, 19968, -1, 19969, 19906, 19970, -1, 19904, 19906, 19969, -1, 19970, 19908, 19971, -1, 19906, 19908, 19970, -1, 19971, 19910, 19972, -1, 19908, 19910, 19971, -1, 19972, 19912, 19973, -1, 19910, 19912, 19972, -1, 19973, 19914, 19974, -1, 19912, 19914, 19973, -1, 19974, 19916, 19975, -1, 19914, 19916, 19974, -1, 19916, 19919, 19975, -1, 19976, 19977, 19978, -1, 19978, 19977, 19979, -1, 19979, 19980, 19981, -1, 19977, 19980, 19979, -1, 19981, 19982, 19983, -1, 19980, 19982, 19981, -1, 19983, 19984, 19985, -1, 19982, 19984, 19983, -1, 19985, 19986, 19987, -1, 19984, 19986, 19985, -1, 19987, 19988, 19989, -1, 19986, 19988, 19987, -1, 19989, 19990, 19991, -1, 19988, 19990, 19989, -1, 19991, 19992, 19993, -1, 19990, 19992, 19991, -1, 19993, 19994, 19995, -1, 19992, 19994, 19993, -1, 19995, 19996, 19997, -1, 19994, 19996, 19995, -1, 19997, 19998, 19999, -1, 19996, 19998, 19997, -1, 19999, 20000, 20001, -1, 19998, 20000, 19999, -1, 20001, 20002, 20003, -1, 20000, 20002, 20001, -1, 20004, 20005, 20006, -1, 20006, 20005, 20007, -1, 20007, 20008, 20009, -1, 20005, 20008, 20007, -1, 20009, 20010, 20011, -1, 20008, 20010, 20009, -1, 20011, 20012, 20013, -1, 20010, 20012, 20011, -1, 20013, 20014, 20015, -1, 20012, 20014, 20013, -1, 20015, 20016, 20017, -1, 20014, 20016, 20015, -1, 20017, 20018, 20019, -1, 20016, 20018, 20017, -1, 20019, 20020, 20021, -1, 20018, 20020, 20019, -1, 20021, 20022, 20023, -1, 20020, 20022, 20021, -1, 20023, 20024, 20025, -1, 20022, 20024, 20023, -1, 20025, 20026, 20027, -1, 20024, 20026, 20025, -1, 20027, 20028, 20029, -1, 20026, 20028, 20027, -1, 20029, 20030, 20031, -1, 20028, 20030, 20029, -1, 20032, 20033, 20034, -1, 20034, 20033, 20035, -1, 20035, 20036, 20037, -1, 20033, 20036, 20035, -1, 20037, 20038, 20039, -1, 20036, 20038, 20037, -1, 20039, 20040, 20041, -1, 20038, 20040, 20039, -1, 20041, 20042, 20043, -1, 20040, 20042, 20041, -1, 20043, 20044, 20045, -1, 20042, 20044, 20043, -1, 20045, 20046, 20047, -1, 20044, 20046, 20045, -1, 20047, 20048, 20049, -1, 20046, 20048, 20047, -1, 20049, 20050, 20051, -1, 20048, 20050, 20049, -1, 20051, 20052, 20053, -1, 20050, 20052, 20051, -1, 20053, 20054, 20055, -1, 20052, 20054, 20053, -1, 20055, 20056, 20057, -1, 20054, 20056, 20055, -1, 20057, 20058, 20059, -1, 20056, 20058, 20057, -1, 20058, 20060, 20059, -1, 20059, 20060, 20061, -1, 20061, 20060, 20062, -1, 20062, 20063, 20064, -1, 20060, 20063, 20062, -1, 20064, 20065, 20066, -1, 20063, 20065, 20064, -1, 20066, 20067, 20068, -1, 20065, 20067, 20066, -1, 20068, 20069, 20070, -1, 20067, 20069, 20068, -1, 20070, 20071, 20072, -1, 20069, 20071, 20070, -1, 20072, 20073, 20074, -1, 20071, 20073, 20072, -1, 20074, 20075, 20076, -1, 20073, 20075, 20074, -1, 20076, 20077, 20078, -1, 20075, 20077, 20076, -1, 20078, 20079, 20080, -1, 20077, 20079, 20078, -1, 20080, 20081, 20082, -1, 20079, 20081, 20080, -1, 20082, 20083, 20034, -1, 20081, 20083, 20082, -1, 20083, 20032, 20034, -1, 20084, 19872, 19870, -1, 19870, 19868, 20084, -1, 20084, 19874, 19872, -1, 19868, 19865, 20084, -1, 20084, 19876, 19874, -1, 20085, 19878, 20084, -1, 20084, 19878, 19876, -1, 20085, 19880, 19878, -1, 20085, 19882, 19880, -1, 20085, 19884, 19882, -1, 20085, 19886, 19884, -1, 20085, 19888, 19886, -1, 20086, 19927, 19864, -1, 20087, 19929, 20088, -1, 20088, 19929, 20086, -1, 20086, 19929, 19927, -1, 19864, 19925, 19865, -1, 19865, 19925, 20084, -1, 19927, 19925, 19864, -1, 20089, 19931, 20090, -1, 20090, 19931, 20087, -1, 20087, 19931, 19929, -1, 19925, 19923, 20084, -1, 20091, 19933, 20092, -1, 20092, 19933, 20089, -1, 20089, 19933, 19931, -1, 19923, 19920, 20084, -1, 20093, 19935, 20091, -1, 20091, 19935, 19933, -1, 20093, 19937, 19935, -1, 20094, 19937, 20095, -1, 20095, 19937, 20093, -1, 20096, 19939, 20097, -1, 20097, 19939, 20094, -1, 20094, 19939, 19937, -1, 19890, 19940, 20096, -1, 20096, 19940, 19939, -1, 19888, 19943, 19890, -1, 20085, 19943, 19888, -1, 19890, 19943, 19940, -1, 20085, 19945, 19943, -1, 20098, 19983, 20099, -1, 19983, 19985, 20099, -1, 20098, 19981, 19983, -1, 20100, 19981, 20098, -1, 19985, 19987, 20099, -1, 20099, 19987, 20101, -1, 20100, 19979, 19981, -1, 19987, 19989, 20101, -1, 20101, 19989, 20102, -1, 20100, 19978, 19979, -1, 20103, 19978, 20100, -1, 20103, 20104, 19978, -1, 20103, 20105, 20104, -1, 20106, 20105, 20103, -1, 20106, 20107, 20105, -1, 20108, 20107, 20106, -1, 20108, 20109, 20107, -1, 20108, 20110, 20109, -1, 20111, 20110, 20108, -1, 20112, 20113, 20111, -1, 20111, 20113, 20110, -1, 19993, 19899, 19991, -1, 19995, 19901, 19993, -1, 19997, 19901, 19995, -1, 19993, 19901, 19899, -1, 19991, 19897, 19989, -1, 19989, 19897, 20102, -1, 19899, 19897, 19991, -1, 19999, 19903, 19997, -1, 19997, 19903, 19901, -1, 19897, 19895, 20102, -1, 20102, 19895, 20114, -1, 19999, 19905, 19903, -1, 20001, 19905, 19999, -1, 20003, 19905, 20001, -1, 19895, 19892, 20114, -1, 20114, 19892, 19920, -1, 20115, 19907, 20003, -1, 20116, 19907, 20115, -1, 20003, 19907, 19905, -1, 20117, 19909, 20116, -1, 20116, 19909, 19907, -1, 20118, 19911, 20117, -1, 20119, 19911, 20118, -1, 20117, 19911, 19909, -1, 20120, 19913, 20119, -1, 20119, 19913, 19911, -1, 20113, 19915, 20120, -1, 20120, 19915, 19913, -1, 20112, 19915, 20113, -1, 20121, 19915, 20112, -1, 20121, 19917, 19915, -1, 20122, 19842, 20123, -1, 20122, 19844, 19842, -1, 19842, 19840, 20123, -1, 20122, 19846, 19844, -1, 20124, 19846, 20122, -1, 19840, 19837, 20123, -1, 20123, 19837, 20125, -1, 20124, 19848, 19846, -1, 20126, 19848, 20124, -1, 19837, 19836, 20125, -1, 20125, 19836, 20127, -1, 20126, 19850, 19848, -1, 19836, 20128, 20127, -1, 20126, 19852, 19850, -1, 20129, 19852, 20126, -1, 20129, 19854, 19852, -1, 20129, 19856, 19854, -1, 20130, 19856, 20129, -1, 20130, 19858, 19856, -1, 20131, 19860, 20130, -1, 20130, 19860, 19858, -1, 20132, 19862, 20131, -1, 20131, 19862, 19860, -1, 20132, 20133, 19862, -1, 20134, 20135, 20136, -1, 20136, 20135, 20137, -1, 20137, 20135, 20138, -1, 20138, 20135, 20139, -1, 20139, 20135, 20128, -1, 20128, 20135, 20127, -1, 19920, 20135, 20084, -1, 20140, 20135, 19892, -1, 20127, 20135, 20140, -1, 19892, 20135, 19920, -1, 20141, 20142, 20132, -1, 20133, 20142, 20143, -1, 20143, 20142, 20144, -1, 20144, 20142, 20145, -1, 20145, 20142, 20146, -1, 20146, 20142, 20147, -1, 20147, 20142, 20134, -1, 20134, 20142, 20135, -1, 20132, 20142, 20133, -1, 20085, 20142, 19946, -1, 20085, 19946, 19945, -1, 19946, 20142, 20121, -1, 20121, 20142, 19918, -1, 20121, 19918, 19917, -1, 19918, 20142, 20141, -1, 20148, 20149, 20150, -1, 20150, 20149, 20151, -1, 20152, 20153, 20154, -1, 20155, 20153, 20152, -1, 20156, 20157, 20158, -1, 20159, 20157, 20156, -1, 20160, 20159, 20156, -1, 20161, 20159, 20160, -1, 20162, 20161, 20160, -1, 20163, 20161, 20162, -1, 20164, 20165, 20166, -1, 20167, 20165, 19891, -1, 20168, 20165, 20169, -1, 19879, 20165, 19877, -1, 19881, 20165, 19879, -1, 19883, 20165, 19881, -1, 19885, 20165, 19883, -1, 19887, 20165, 19885, -1, 19889, 20165, 19887, -1, 19891, 20165, 19889, -1, 19877, 20165, 20170, -1, 20166, 20165, 20167, -1, 20171, 20172, 20173, -1, 20174, 20165, 20175, -1, 20175, 20165, 20168, -1, 20173, 20176, 20171, -1, 20171, 20177, 20172, -1, 20176, 20178, 20171, -1, 20171, 20179, 20177, -1, 20178, 19838, 20171, -1, 19838, 19839, 20171, -1, 20180, 20174, 19863, -1, 20181, 20174, 20180, -1, 20182, 20174, 20181, -1, 20183, 20174, 20182, -1, 20184, 20174, 20183, -1, 20185, 20174, 20184, -1, 20179, 20174, 20185, -1, 19863, 20174, 19861, -1, 20171, 20174, 20179, -1, 19845, 20052, 19843, -1, 19843, 20050, 19841, -1, 20052, 20050, 19843, -1, 19847, 20054, 19845, -1, 19845, 20054, 20052, -1, 19841, 20048, 19839, -1, 19839, 20048, 20171, -1, 20050, 20048, 19841, -1, 19849, 20056, 19847, -1, 19847, 20056, 20054, -1, 20048, 20046, 20171, -1, 19851, 20058, 19849, -1, 19849, 20058, 20056, -1, 20046, 20044, 20171, -1, 19851, 20060, 20058, -1, 19853, 20060, 19851, -1, 19853, 20063, 20060, -1, 19855, 20063, 19853, -1, 19855, 20065, 20063, -1, 19857, 20065, 19855, -1, 19859, 20067, 19857, -1, 19857, 20067, 20065, -1, 19859, 20069, 20067, -1, 19861, 20069, 19859, -1, 20174, 20069, 19861, -1, 20174, 20071, 20069, -1, 20174, 20073, 20071, -1, 20036, 19996, 20038, -1, 19996, 19994, 20038, -1, 20038, 19994, 20040, -1, 20036, 19998, 19996, -1, 20033, 19998, 20036, -1, 19994, 19992, 20040, -1, 20040, 19992, 20042, -1, 20033, 20000, 19998, -1, 20032, 20000, 20033, -1, 19992, 19990, 20042, -1, 20042, 19990, 20044, -1, 20044, 19990, 20171, -1, 20032, 20002, 20000, -1, 20032, 20186, 20002, -1, 20083, 20186, 20032, -1, 20083, 20187, 20186, -1, 20081, 20187, 20083, -1, 20079, 20188, 20081, -1, 20081, 20188, 20187, -1, 20077, 20189, 20079, -1, 20079, 20189, 20188, -1, 20075, 20190, 20077, -1, 20077, 20190, 20189, -1, 20174, 20175, 20073, -1, 20075, 20175, 20190, -1, 20073, 20175, 20075, -1, 19982, 20024, 19984, -1, 19984, 20022, 19986, -1, 20024, 20022, 19984, -1, 19980, 20026, 19982, -1, 19982, 20026, 20024, -1, 20022, 20020, 19986, -1, 19986, 20020, 19988, -1, 19980, 20028, 20026, -1, 19977, 20028, 19980, -1, 20020, 20018, 19988, -1, 19977, 20030, 20028, -1, 20191, 20030, 19976, -1, 19976, 20030, 19977, -1, 20191, 20192, 20030, -1, 20193, 20192, 20191, -1, 20193, 20194, 20192, -1, 20195, 20194, 20193, -1, 20195, 20196, 20194, -1, 20197, 20196, 20195, -1, 20197, 20198, 20196, -1, 20199, 20198, 20197, -1, 20199, 20200, 20198, -1, 20168, 20200, 20199, -1, 20168, 20169, 20200, -1, 20014, 20170, 20016, -1, 20016, 20170, 20018, -1, 19990, 20170, 20171, -1, 20018, 20170, 19988, -1, 19988, 20170, 19990, -1, 20010, 20201, 20012, -1, 20008, 20202, 20010, -1, 20010, 20202, 20201, -1, 20012, 20203, 20014, -1, 20201, 20203, 20012, -1, 20005, 20204, 20008, -1, 20008, 20204, 20202, -1, 20014, 20205, 20170, -1, 20203, 20205, 20014, -1, 20004, 20206, 20005, -1, 20005, 20206, 20204, -1, 20205, 19866, 20170, -1, 20207, 20208, 20004, -1, 20004, 20208, 20206, -1, 19866, 19867, 20170, -1, 20209, 20210, 20207, -1, 20207, 20210, 20208, -1, 19867, 19869, 20170, -1, 20211, 20212, 20209, -1, 20209, 20212, 20210, -1, 19869, 19871, 20170, -1, 20213, 20214, 20211, -1, 20211, 20214, 20212, -1, 19871, 19873, 20170, -1, 20166, 20215, 20213, -1, 20213, 20215, 20214, -1, 19873, 19875, 20170, -1, 20166, 20167, 20215, -1, 19875, 19877, 20170, -1, 20169, 20165, 20164, -1, 20216, 20217, 20218, -1, 20219, 20217, 20216, -1, 20220, 20219, 20216, -1, 20221, 20219, 20220, -1, 20222, 20221, 20220, -1, 20223, 20221, 20222, -1, 20224, 20225, 20226, -1, 20227, 20225, 20224, -1, 20228, 20229, 20230, -1, 20231, 20229, 20228, -1, 20153, 20159, 20232, -1, 20155, 20159, 20153, -1, 20157, 20159, 20155, -1, 20165, 20161, 20163, -1, 20159, 20161, 20232, -1, 20174, 20219, 20165, -1, 20217, 20219, 20174, -1, 20165, 20219, 20161, -1, 20225, 20221, 20223, -1, 20225, 20227, 20221, -1, 20221, 20233, 20219, -1, 20227, 20233, 20221, -1, 20233, 20232, 20219, -1, 20219, 20232, 20161, -1, 20156, 20152, 20154, -1, 20156, 20154, 20234, -1, 20156, 20158, 20152, -1, 20160, 20170, 20162, -1, 20160, 20156, 20234, -1, 20216, 20218, 20171, -1, 20216, 20171, 20170, -1, 20216, 20170, 20160, -1, 20220, 20226, 20222, -1, 20224, 20226, 20220, -1, 20235, 20220, 20216, -1, 20235, 20224, 20220, -1, 20234, 20235, 20216, -1, 20234, 20216, 20160, -1, 20155, 20152, 20157, -1, 20157, 20152, 20158, -1, 20163, 20162, 20165, -1, 20165, 20162, 20170, -1, 20223, 20222, 20225, -1, 20225, 20222, 20226, -1, 20174, 20171, 20217, -1, 20217, 20171, 20218, -1, 20230, 20235, 20228, -1, 20224, 20235, 20230, -1, 20229, 20224, 20230, -1, 20227, 20224, 20229, -1, 20135, 20228, 20235, -1, 20142, 20228, 20135, -1, 20231, 20228, 20142, -1, 20229, 20233, 20227, -1, 20229, 20231, 20233, -1, 20235, 20234, 20084, -1, 20235, 20084, 20135, -1, 20142, 20233, 20231, -1, 20084, 20234, 20151, -1, 20149, 20084, 20151, -1, 20085, 20084, 20149, -1, 20142, 20232, 20233, -1, 20142, 20085, 20232, -1, 20234, 20154, 20150, -1, 20234, 20150, 20151, -1, 20232, 20085, 20149, -1, 20153, 20150, 20154, -1, 20148, 20150, 20153, -1, 20149, 20148, 20232, -1, 20232, 20148, 20153, -1, 20030, 20192, 20031, -1, 20031, 20192, 20236, -1, 20236, 20194, 20237, -1, 20192, 20194, 20236, -1, 20237, 20196, 20238, -1, 20194, 20196, 20237, -1, 20238, 20198, 20239, -1, 20196, 20198, 20238, -1, 20239, 20200, 20240, -1, 20198, 20200, 20239, -1, 20240, 20169, 20241, -1, 20200, 20169, 20240, -1, 20241, 20164, 20242, -1, 20169, 20164, 20241, -1, 20242, 20166, 20243, -1, 20164, 20166, 20242, -1, 20243, 20213, 20244, -1, 20166, 20213, 20243, -1, 20244, 20211, 20245, -1, 20213, 20211, 20244, -1, 20245, 20209, 20246, -1, 20211, 20209, 20245, -1, 20246, 20207, 20247, -1, 20209, 20207, 20246, -1, 20247, 20004, 20006, -1, 20207, 20004, 20247, -1, 20002, 20186, 20003, -1, 20003, 20186, 20115, -1, 20115, 20187, 20116, -1, 20186, 20187, 20115, -1, 20116, 20188, 20117, -1, 20187, 20188, 20116, -1, 20117, 20189, 20118, -1, 20188, 20189, 20117, -1, 20118, 20190, 20119, -1, 20189, 20190, 20118, -1, 20119, 20175, 20120, -1, 20190, 20175, 20119, -1, 20120, 20168, 20113, -1, 20175, 20168, 20120, -1, 20113, 20199, 20110, -1, 20168, 20199, 20113, -1, 20110, 20197, 20109, -1, 20199, 20197, 20110, -1, 20109, 20195, 20107, -1, 20197, 20195, 20109, -1, 20107, 20193, 20105, -1, 20195, 20193, 20107, -1, 20105, 20191, 20104, -1, 20193, 20191, 20105, -1, 20104, 19976, 19978, -1, 20191, 19976, 20104, -1, 19973, 20076, 19972, -1, 19973, 20074, 20076, -1, 20248, 20055, 20057, -1, 20248, 20249, 20055, -1, 20039, 19965, 19966, -1, 19974, 20074, 19973, -1, 20041, 19964, 19965, -1, 20041, 19965, 20039, -1, 19974, 20072, 20074, -1, 20037, 19966, 19967, -1, 20037, 20039, 19966, -1, 20043, 19963, 19964, -1, 20043, 19964, 20041, -1, 20035, 19967, 19968, -1, 20035, 20037, 19967, -1, 20045, 19962, 19963, -1, 20250, 20248, 20057, -1, 20250, 20057, 20059, -1, 20045, 19963, 20043, -1, 19975, 20070, 20072, -1, 19975, 20072, 19974, -1, 20034, 19968, 19969, -1, 20251, 20059, 20061, -1, 20034, 20035, 19968, -1, 20047, 20252, 19962, -1, 20251, 20250, 20059, -1, 20047, 19962, 20045, -1, 20253, 20068, 20070, -1, 20253, 20070, 19975, -1, 20254, 20251, 20061, -1, 20082, 19969, 19970, -1, 20254, 20061, 20062, -1, 20082, 20034, 19969, -1, 20255, 20068, 20253, -1, 20049, 20256, 20252, -1, 20255, 20066, 20068, -1, 20049, 20252, 20047, -1, 20257, 20254, 20062, -1, 20257, 20062, 20064, -1, 20080, 19970, 19971, -1, 20258, 20257, 20064, -1, 20258, 20064, 20066, -1, 20258, 20066, 20255, -1, 20080, 20082, 19970, -1, 20051, 20256, 20049, -1, 20259, 20256, 20051, -1, 20078, 20080, 19971, -1, 20053, 20259, 20051, -1, 19972, 20078, 19971, -1, 20076, 20078, 19972, -1, 20249, 20053, 20055, -1, 20249, 20259, 20053, -1, 19919, 20260, 19975, -1, 19975, 20260, 20253, -1, 20253, 20261, 20255, -1, 20260, 20261, 20253, -1, 20255, 20262, 20258, -1, 20261, 20262, 20255, -1, 20258, 20263, 20257, -1, 20262, 20263, 20258, -1, 20257, 20264, 20254, -1, 20263, 20264, 20257, -1, 20254, 20265, 20251, -1, 20264, 20265, 20254, -1, 20251, 20266, 20250, -1, 20265, 20266, 20251, -1, 20250, 20267, 20248, -1, 20266, 20267, 20250, -1, 20248, 20268, 20249, -1, 20267, 20268, 20248, -1, 20249, 20269, 20259, -1, 20268, 20269, 20249, -1, 20259, 20270, 20256, -1, 20269, 20270, 20259, -1, 20256, 20271, 20252, -1, 20270, 20271, 20256, -1, 20252, 19894, 19962, -1, 20271, 19894, 20252, -1, 20013, 19950, 19951, -1, 20015, 19950, 20013, -1, 20272, 20273, 20237, -1, 20237, 20273, 20236, -1, 20017, 19949, 20015, -1, 20015, 19949, 19950, -1, 19958, 20245, 19957, -1, 19959, 20244, 19958, -1, 19958, 20244, 20245, -1, 19957, 20246, 19956, -1, 20245, 20246, 19957, -1, 19960, 20243, 19959, -1, 19959, 20243, 20244, -1, 19956, 20247, 19955, -1, 20273, 20274, 20236, -1, 20236, 20274, 20031, -1, 20246, 20247, 19956, -1, 20019, 19948, 20017, -1, 19961, 20242, 19960, -1, 20017, 19948, 19949, -1, 20031, 20275, 20029, -1, 19960, 20242, 20243, -1, 20274, 20275, 20031, -1, 19955, 20006, 19954, -1, 20021, 20276, 20019, -1, 20247, 20006, 19955, -1, 20019, 20276, 19948, -1, 20277, 20241, 19961, -1, 20029, 20278, 20027, -1, 20275, 20278, 20029, -1, 19961, 20241, 20242, -1, 20021, 20279, 20276, -1, 20023, 20279, 20021, -1, 19954, 20007, 19953, -1, 20027, 20280, 20025, -1, 20278, 20280, 20027, -1, 20025, 20281, 20023, -1, 20006, 20007, 19954, -1, 20023, 20281, 20279, -1, 20282, 20240, 20277, -1, 20280, 20281, 20025, -1, 20277, 20240, 20241, -1, 19953, 20009, 19952, -1, 20007, 20009, 19953, -1, 20282, 20239, 20240, -1, 20282, 20283, 20239, -1, 20009, 20011, 19952, -1, 20283, 20238, 20239, -1, 20011, 19951, 19952, -1, 20011, 20013, 19951, -1, 20283, 20272, 20238, -1, 20238, 20272, 20237, -1, 19947, 20284, 19961, -1, 19961, 20284, 20277, -1, 20277, 20285, 20282, -1, 20284, 20285, 20277, -1, 20282, 20286, 20283, -1, 20285, 20286, 20282, -1, 20283, 20287, 20272, -1, 20286, 20287, 20283, -1, 20272, 20288, 20273, -1, 20287, 20288, 20272, -1, 20273, 20289, 20274, -1, 20288, 20289, 20273, -1, 20274, 20290, 20275, -1, 20289, 20290, 20274, -1, 20275, 20291, 20278, -1, 20290, 20291, 20275, -1, 20278, 20292, 20280, -1, 20291, 20292, 20278, -1, 20280, 20293, 20281, -1, 20292, 20293, 20280, -1, 20281, 20294, 20279, -1, 20293, 20294, 20281, -1, 20279, 20295, 20276, -1, 20294, 20295, 20279, -1, 20276, 19922, 19948, -1, 20295, 19922, 20276, -1, 19946, 20284, 19947, -1, 19946, 20121, 20284, -1, 20121, 20285, 20284, -1, 20121, 20112, 20285, -1, 20112, 20286, 20285, -1, 20112, 20111, 20286, -1, 20111, 20287, 20286, -1, 20111, 20108, 20287, -1, 20108, 20288, 20287, -1, 20108, 20106, 20288, -1, 20106, 20289, 20288, -1, 20106, 20103, 20289, -1, 20103, 20290, 20289, -1, 20103, 20100, 20290, -1, 20100, 20291, 20290, -1, 20100, 20098, 20291, -1, 20098, 20292, 20291, -1, 20098, 20099, 20292, -1, 20099, 20293, 20292, -1, 20099, 20101, 20293, -1, 20101, 20294, 20293, -1, 20101, 20102, 20294, -1, 20102, 20295, 20294, -1, 20102, 20114, 20295, -1, 20114, 19922, 20295, -1, 20114, 19920, 19922, -1, 19918, 20260, 19919, -1, 19918, 20141, 20260, -1, 20141, 20261, 20260, -1, 20141, 20132, 20261, -1, 20132, 20262, 20261, -1, 20132, 20131, 20262, -1, 20131, 20263, 20262, -1, 20131, 20130, 20263, -1, 20130, 20264, 20263, -1, 20130, 20129, 20264, -1, 20129, 20265, 20264, -1, 20129, 20126, 20265, -1, 20126, 20266, 20265, -1, 20126, 20124, 20266, -1, 20124, 20267, 20266, -1, 20124, 20122, 20267, -1, 20122, 20268, 20267, -1, 20122, 20123, 20268, -1, 20123, 20269, 20268, -1, 20123, 20125, 20269, -1, 20125, 20270, 20269, -1, 20125, 20127, 20270, -1, 20127, 20271, 20270, -1, 20127, 20140, 20271, -1, 20140, 19894, 20271, -1, 20140, 19892, 19894, -1, 19890, 20096, 19891, -1, 19891, 20096, 20167, -1, 20167, 20097, 20215, -1, 20096, 20097, 20167, -1, 20215, 20094, 20214, -1, 20097, 20094, 20215, -1, 20214, 20095, 20212, -1, 20094, 20095, 20214, -1, 20212, 20093, 20210, -1, 20095, 20093, 20212, -1, 20210, 20091, 20208, -1, 20093, 20091, 20210, -1, 20208, 20092, 20206, -1, 20091, 20092, 20208, -1, 20206, 20089, 20204, -1, 20092, 20089, 20206, -1, 20204, 20090, 20202, -1, 20089, 20090, 20204, -1, 20202, 20087, 20201, -1, 20090, 20087, 20202, -1, 20201, 20088, 20203, -1, 20087, 20088, 20201, -1, 20203, 20086, 20205, -1, 20088, 20086, 20203, -1, 20205, 19864, 19866, -1, 20086, 19864, 20205, -1, 19862, 20133, 19863, -1, 19863, 20133, 20180, -1, 20180, 20143, 20181, -1, 20133, 20143, 20180, -1, 20181, 20144, 20182, -1, 20143, 20144, 20181, -1, 20182, 20145, 20183, -1, 20144, 20145, 20182, -1, 20183, 20146, 20184, -1, 20145, 20146, 20183, -1, 20184, 20147, 20185, -1, 20146, 20147, 20184, -1, 20185, 20134, 20179, -1, 20147, 20134, 20185, -1, 20179, 20136, 20177, -1, 20134, 20136, 20179, -1, 20177, 20137, 20172, -1, 20136, 20137, 20177, -1, 20172, 20138, 20173, -1, 20137, 20138, 20172, -1, 20173, 20139, 20176, -1, 20138, 20139, 20173, -1, 20176, 20128, 20178, -1, 20139, 20128, 20176, -1, 20178, 19836, 19838, -1, 20128, 19836, 20178, -1, 20296, 20297, 20298, -1, 20298, 20299, 20300, -1, 20297, 20299, 20298, -1, 20300, 20301, 20302, -1, 20299, 20301, 20300, -1, 20302, 20303, 20304, -1, 20301, 20303, 20302, -1, 20304, 20305, 20306, -1, 20303, 20305, 20304, -1, 20306, 20307, 20308, -1, 20305, 20307, 20306, -1, 20308, 20309, 20310, -1, 20307, 20309, 20308, -1, 20310, 20311, 20312, -1, 20309, 20311, 20310, -1, 20312, 20313, 20314, -1, 20311, 20313, 20312, -1, 20314, 20315, 20316, -1, 20313, 20315, 20314, -1, 20316, 20317, 20318, -1, 20315, 20317, 20316, -1, 20318, 20319, 20320, -1, 20317, 20319, 20318, -1, 20320, 20321, 20322, -1, 20319, 20321, 20320, -1, 20321, 20323, 20322, -1, 20324, 20325, 20326, -1, 20326, 20327, 20328, -1, 20325, 20327, 20326, -1, 20328, 20329, 20330, -1, 20327, 20329, 20328, -1, 20330, 20331, 20332, -1, 20329, 20331, 20330, -1, 20332, 20333, 20334, -1, 20331, 20333, 20332, -1, 20334, 20335, 20336, -1, 20333, 20335, 20334, -1, 20336, 20337, 20338, -1, 20335, 20337, 20336, -1, 20338, 20339, 20340, -1, 20337, 20339, 20338, -1, 20340, 20341, 20342, -1, 20339, 20341, 20340, -1, 20342, 20343, 20344, -1, 20341, 20343, 20342, -1, 20344, 20345, 20346, -1, 20343, 20345, 20344, -1, 20346, 20347, 20348, -1, 20345, 20347, 20346, -1, 20348, 20349, 20350, -1, 20347, 20349, 20348, -1, 20349, 20351, 20350, -1, 20301, 20299, 20352, -1, 20352, 20299, 20353, -1, 20354, 20309, 20307, -1, 20355, 20333, 20331, -1, 20356, 20309, 20354, -1, 20353, 20297, 20325, -1, 20331, 20329, 20355, -1, 20325, 20297, 20355, -1, 20299, 20297, 20353, -1, 20355, 20335, 20333, -1, 20356, 20311, 20309, -1, 20329, 20327, 20355, -1, 20355, 20337, 20335, -1, 20357, 20311, 20356, -1, 20327, 20325, 20355, -1, 20358, 20339, 20355, -1, 20355, 20339, 20337, -1, 20357, 20313, 20311, -1, 20359, 20313, 20357, -1, 20358, 20341, 20339, -1, 20360, 20315, 20359, -1, 20359, 20315, 20313, -1, 20358, 20343, 20341, -1, 20361, 20317, 20360, -1, 20360, 20317, 20315, -1, 20358, 20345, 20343, -1, 20361, 20319, 20317, -1, 20358, 20347, 20345, -1, 20362, 20319, 20361, -1, 20358, 20349, 20347, -1, 20363, 20321, 20362, -1, 20362, 20321, 20319, -1, 20358, 20351, 20349, -1, 20364, 20365, 20366, -1, 20366, 20365, 20367, -1, 20367, 20365, 20368, -1, 20368, 20365, 20369, -1, 20369, 20365, 20370, -1, 20370, 20365, 20371, -1, 20371, 20365, 20297, -1, 20297, 20365, 20355, -1, 20372, 20305, 20373, -1, 20323, 20374, 20375, -1, 20373, 20305, 20303, -1, 20375, 20374, 20376, -1, 20376, 20374, 20377, -1, 20377, 20374, 20378, -1, 20373, 20301, 20352, -1, 20378, 20374, 20379, -1, 20379, 20374, 20364, -1, 20364, 20374, 20365, -1, 20303, 20301, 20373, -1, 20358, 20374, 20351, -1, 20351, 20374, 20363, -1, 20363, 20374, 20321, -1, 20321, 20374, 20323, -1, 20372, 20307, 20305, -1, 20354, 20307, 20372, -1, 20380, 20381, 20382, -1, 20382, 20381, 20383, -1, 20384, 20385, 20386, -1, 20385, 20387, 20386, -1, 20388, 20389, 20390, -1, 20391, 20389, 20388, -1, 20392, 20391, 20388, -1, 20393, 20391, 20392, -1, 20394, 20393, 20392, -1, 20395, 20393, 20394, -1, 20396, 20397, 20300, -1, 20300, 20397, 20298, -1, 20398, 20399, 20400, -1, 20304, 20401, 20402, -1, 20306, 20401, 20304, -1, 20400, 20403, 20398, -1, 20397, 20404, 20298, -1, 20398, 20405, 20399, -1, 20298, 20404, 20398, -1, 20308, 20406, 20306, -1, 20403, 20407, 20398, -1, 20398, 20408, 20405, -1, 20306, 20406, 20401, -1, 20407, 20296, 20398, -1, 20409, 20410, 20398, -1, 20308, 20411, 20406, -1, 20398, 20410, 20408, -1, 20310, 20411, 20308, -1, 20296, 20298, 20398, -1, 20312, 20412, 20310, -1, 20409, 20413, 20410, -1, 20310, 20412, 20411, -1, 20409, 20414, 20413, -1, 20312, 20415, 20412, -1, 20314, 20415, 20312, -1, 20409, 20416, 20414, -1, 20316, 20417, 20314, -1, 20314, 20417, 20415, -1, 20409, 20418, 20416, -1, 20318, 20419, 20316, -1, 20316, 20419, 20417, -1, 20409, 20420, 20418, -1, 20320, 20421, 20318, -1, 20318, 20421, 20419, -1, 20409, 20322, 20420, -1, 20409, 20320, 20322, -1, 20404, 20422, 20398, -1, 20324, 20422, 20404, -1, 20326, 20422, 20324, -1, 20328, 20422, 20326, -1, 20330, 20422, 20328, -1, 20332, 20422, 20330, -1, 20334, 20422, 20332, -1, 20336, 20422, 20334, -1, 20338, 20422, 20336, -1, 20421, 20423, 20350, -1, 20340, 20423, 20338, -1, 20342, 20423, 20340, -1, 20302, 20396, 20300, -1, 20344, 20423, 20342, -1, 20304, 20396, 20302, -1, 20346, 20423, 20344, -1, 20348, 20423, 20346, -1, 20350, 20423, 20348, -1, 20338, 20423, 20422, -1, 20409, 20423, 20320, -1, 20320, 20423, 20421, -1, 20304, 20402, 20396, -1, 20424, 20425, 20426, -1, 20427, 20425, 20424, -1, 20428, 20427, 20424, -1, 20429, 20427, 20428, -1, 20430, 20429, 20428, -1, 20431, 20429, 20430, -1, 20432, 20433, 20434, -1, 20435, 20433, 20432, -1, 20436, 20437, 20438, -1, 20439, 20437, 20436, -1, 20387, 20391, 20440, -1, 20385, 20391, 20387, -1, 20389, 20391, 20385, -1, 20423, 20393, 20395, -1, 20391, 20393, 20440, -1, 20409, 20427, 20423, -1, 20425, 20427, 20409, -1, 20423, 20427, 20393, -1, 20433, 20429, 20431, -1, 20433, 20435, 20429, -1, 20429, 20441, 20427, -1, 20435, 20441, 20429, -1, 20441, 20440, 20427, -1, 20427, 20440, 20393, -1, 20388, 20384, 20386, -1, 20388, 20386, 20442, -1, 20388, 20390, 20384, -1, 20392, 20422, 20394, -1, 20392, 20388, 20442, -1, 20424, 20426, 20398, -1, 20424, 20398, 20422, -1, 20424, 20422, 20392, -1, 20428, 20434, 20430, -1, 20432, 20434, 20428, -1, 20443, 20428, 20424, -1, 20443, 20432, 20428, -1, 20442, 20443, 20424, -1, 20442, 20424, 20392, -1, 20385, 20390, 20389, -1, 20385, 20384, 20390, -1, 20395, 20394, 20423, -1, 20423, 20394, 20422, -1, 20431, 20430, 20433, -1, 20433, 20430, 20434, -1, 20409, 20398, 20425, -1, 20425, 20398, 20426, -1, 20438, 20443, 20436, -1, 20432, 20443, 20438, -1, 20437, 20432, 20438, -1, 20435, 20432, 20437, -1, 20365, 20436, 20443, -1, 20374, 20436, 20365, -1, 20439, 20436, 20374, -1, 20437, 20441, 20435, -1, 20437, 20439, 20441, -1, 20443, 20442, 20355, -1, 20443, 20355, 20365, -1, 20374, 20441, 20439, -1, 20355, 20442, 20383, -1, 20358, 20383, 20381, -1, 20358, 20355, 20383, -1, 20374, 20358, 20441, -1, 20441, 20358, 20440, -1, 20442, 20386, 20382, -1, 20442, 20382, 20383, -1, 20440, 20358, 20381, -1, 20387, 20382, 20386, -1, 20380, 20382, 20387, -1, 20381, 20380, 20440, -1, 20440, 20380, 20387, -1, 20351, 20363, 20350, -1, 20350, 20363, 20421, -1, 20421, 20362, 20419, -1, 20363, 20362, 20421, -1, 20419, 20361, 20417, -1, 20362, 20361, 20419, -1, 20417, 20360, 20415, -1, 20361, 20360, 20417, -1, 20415, 20359, 20412, -1, 20360, 20359, 20415, -1, 20412, 20357, 20411, -1, 20359, 20357, 20412, -1, 20411, 20356, 20406, -1, 20357, 20356, 20411, -1, 20406, 20354, 20401, -1, 20356, 20354, 20406, -1, 20401, 20372, 20402, -1, 20354, 20372, 20401, -1, 20402, 20373, 20396, -1, 20372, 20373, 20402, -1, 20396, 20352, 20397, -1, 20373, 20352, 20396, -1, 20397, 20353, 20404, -1, 20352, 20353, 20397, -1, 20404, 20325, 20324, -1, 20353, 20325, 20404, -1, 20323, 20375, 20322, -1, 20322, 20375, 20420, -1, 20420, 20376, 20418, -1, 20375, 20376, 20420, -1, 20418, 20377, 20416, -1, 20376, 20377, 20418, -1, 20416, 20378, 20414, -1, 20377, 20378, 20416, -1, 20414, 20379, 20413, -1, 20378, 20379, 20414, -1, 20413, 20364, 20410, -1, 20379, 20364, 20413, -1, 20410, 20366, 20408, -1, 20364, 20366, 20410, -1, 20408, 20367, 20405, -1, 20366, 20367, 20408, -1, 20405, 20368, 20399, -1, 20367, 20368, 20405, -1, 20399, 20369, 20400, -1, 20368, 20369, 20399, -1, 20400, 20370, 20403, -1, 20369, 20370, 20400, -1, 20403, 20371, 20407, -1, 20370, 20371, 20403, -1, 20407, 20297, 20296, -1, 20371, 20297, 20407, -1, 20444, 20445, 20446, -1, 20446, 20447, 20448, -1, 20445, 20447, 20446, -1, 20448, 20449, 20450, -1, 20447, 20449, 20448, -1, 20450, 20451, 20452, -1, 20449, 20451, 20450, -1, 20452, 20453, 20454, -1, 20451, 20453, 20452, -1, 20454, 20455, 20456, -1, 20453, 20455, 20454, -1, 20456, 20457, 20458, -1, 20455, 20457, 20456, -1, 20458, 20459, 20460, -1, 20457, 20459, 20458, -1, 20460, 20461, 20462, -1, 20459, 20461, 20460, -1, 20462, 20463, 20464, -1, 20461, 20463, 20462, -1, 20464, 20465, 20466, -1, 20463, 20465, 20464, -1, 20466, 20467, 20468, -1, 20465, 20467, 20466, -1, 20468, 20469, 20470, -1, 20467, 20469, 20468, -1, 20469, 20471, 20470, -1, 20472, 20473, 20474, -1, 20474, 20473, 20475, -1, 20475, 20476, 20477, -1, 20473, 20476, 20475, -1, 20477, 20478, 20479, -1, 20476, 20478, 20477, -1, 20479, 20480, 20481, -1, 20478, 20480, 20479, -1, 20481, 20482, 20483, -1, 20480, 20482, 20481, -1, 20483, 20484, 20485, -1, 20482, 20484, 20483, -1, 20485, 20486, 20487, -1, 20484, 20486, 20485, -1, 20487, 20488, 20489, -1, 20486, 20488, 20487, -1, 20489, 20490, 20491, -1, 20488, 20490, 20489, -1, 20491, 20492, 20493, -1, 20490, 20492, 20491, -1, 20493, 20494, 20495, -1, 20492, 20494, 20493, -1, 20495, 20496, 20497, -1, 20494, 20496, 20495, -1, 20497, 20498, 20499, -1, 20496, 20498, 20497, -1, 20449, 20447, 20500, -1, 20501, 20457, 20455, -1, 20502, 20480, 20478, -1, 20478, 20476, 20502, -1, 20503, 20457, 20501, -1, 20447, 20445, 20500, -1, 20502, 20482, 20480, -1, 20500, 20445, 20472, -1, 20472, 20445, 20502, -1, 20476, 20473, 20502, -1, 20503, 20459, 20457, -1, 20504, 20459, 20505, -1, 20505, 20459, 20503, -1, 20502, 20484, 20482, -1, 20473, 20472, 20502, -1, 20506, 20486, 20502, -1, 20502, 20486, 20484, -1, 20504, 20461, 20459, -1, 20507, 20461, 20504, -1, 20506, 20488, 20486, -1, 20507, 20463, 20461, -1, 20506, 20490, 20488, -1, 20507, 20465, 20463, -1, 20508, 20465, 20507, -1, 20506, 20492, 20490, -1, 20506, 20494, 20492, -1, 20509, 20467, 20508, -1, 20508, 20467, 20465, -1, 20506, 20496, 20494, -1, 20510, 20469, 20509, -1, 20509, 20469, 20467, -1, 20506, 20498, 20496, -1, 20511, 20512, 20513, -1, 20513, 20512, 20514, -1, 20514, 20512, 20515, -1, 20515, 20512, 20516, -1, 20516, 20512, 20517, -1, 20517, 20512, 20518, -1, 20518, 20512, 20445, -1, 20519, 20451, 20520, -1, 20445, 20512, 20502, -1, 20520, 20451, 20521, -1, 20471, 20522, 20523, -1, 20523, 20522, 20524, -1, 20524, 20522, 20525, -1, 20525, 20522, 20526, -1, 20526, 20522, 20527, -1, 20527, 20522, 20511, -1, 20511, 20522, 20512, -1, 20506, 20522, 20498, -1, 20501, 20453, 20519, -1, 20498, 20522, 20510, -1, 20519, 20453, 20451, -1, 20510, 20522, 20469, -1, 20469, 20522, 20471, -1, 20521, 20449, 20500, -1, 20451, 20449, 20521, -1, 20501, 20455, 20453, -1, 20528, 20529, 20530, -1, 20529, 20531, 20530, -1, 20532, 20533, 20534, -1, 20535, 20533, 20532, -1, 20536, 20537, 20538, -1, 20537, 20539, 20538, -1, 20540, 20537, 20536, -1, 20541, 20537, 20540, -1, 20542, 20541, 20540, -1, 20543, 20541, 20542, -1, 20452, 20544, 20545, -1, 20546, 20547, 20448, -1, 20448, 20547, 20446, -1, 20548, 20549, 20550, -1, 20454, 20551, 20544, -1, 20456, 20551, 20454, -1, 20458, 20551, 20456, -1, 20550, 20552, 20548, -1, 20548, 20553, 20549, -1, 20552, 20554, 20548, -1, 20548, 20555, 20553, -1, 20458, 20556, 20551, -1, 20554, 20444, 20548, -1, 20458, 20557, 20556, -1, 20558, 20559, 20548, -1, 20460, 20557, 20458, -1, 20462, 20557, 20460, -1, 20548, 20559, 20555, -1, 20444, 20446, 20548, -1, 20464, 20560, 20462, -1, 20558, 20561, 20559, -1, 20462, 20560, 20557, -1, 20558, 20562, 20561, -1, 20464, 20563, 20560, -1, 20558, 20564, 20562, -1, 20466, 20565, 20464, -1, 20468, 20565, 20466, -1, 20464, 20565, 20563, -1, 20558, 20566, 20564, -1, 20468, 20567, 20565, -1, 20558, 20568, 20566, -1, 20558, 20470, 20568, -1, 20558, 20468, 20470, -1, 20547, 20569, 20446, -1, 20474, 20569, 20547, -1, 20475, 20569, 20474, -1, 20477, 20569, 20475, -1, 20479, 20569, 20477, -1, 20481, 20569, 20479, -1, 20483, 20569, 20481, -1, 20485, 20569, 20483, -1, 20446, 20569, 20548, -1, 20567, 20570, 20499, -1, 20487, 20570, 20485, -1, 20489, 20570, 20487, -1, 20491, 20570, 20489, -1, 20493, 20570, 20491, -1, 20495, 20570, 20493, -1, 20452, 20545, 20450, -1, 20497, 20570, 20495, -1, 20499, 20570, 20497, -1, 20485, 20570, 20569, -1, 20558, 20570, 20468, -1, 20468, 20570, 20567, -1, 20450, 20545, 20571, -1, 20450, 20546, 20448, -1, 20571, 20546, 20450, -1, 20454, 20544, 20452, -1, 20572, 20573, 20574, -1, 20573, 20575, 20574, -1, 20576, 20577, 20572, -1, 20577, 20573, 20572, -1, 20578, 20577, 20576, -1, 20579, 20577, 20578, -1, 20580, 20581, 20582, -1, 20581, 20583, 20582, -1, 20584, 20585, 20586, -1, 20585, 20587, 20586, -1, 20533, 20537, 20588, -1, 20535, 20537, 20533, -1, 20539, 20537, 20535, -1, 20570, 20541, 20543, -1, 20537, 20541, 20588, -1, 20558, 20573, 20570, -1, 20575, 20573, 20558, -1, 20570, 20573, 20541, -1, 20583, 20577, 20579, -1, 20583, 20581, 20577, -1, 20577, 20589, 20573, -1, 20581, 20589, 20577, -1, 20589, 20588, 20573, -1, 20573, 20588, 20541, -1, 20536, 20532, 20534, -1, 20536, 20534, 20590, -1, 20536, 20538, 20532, -1, 20540, 20569, 20542, -1, 20540, 20536, 20590, -1, 20572, 20574, 20548, -1, 20572, 20548, 20569, -1, 20572, 20569, 20540, -1, 20576, 20582, 20578, -1, 20580, 20582, 20576, -1, 20591, 20576, 20572, -1, 20591, 20580, 20576, -1, 20590, 20591, 20572, -1, 20590, 20572, 20540, -1, 20535, 20538, 20539, -1, 20535, 20532, 20538, -1, 20543, 20542, 20570, -1, 20570, 20542, 20569, -1, 20579, 20578, 20583, -1, 20583, 20578, 20582, -1, 20558, 20548, 20575, -1, 20575, 20548, 20574, -1, 20586, 20591, 20584, -1, 20580, 20591, 20586, -1, 20587, 20580, 20586, -1, 20581, 20580, 20587, -1, 20512, 20584, 20591, -1, 20585, 20512, 20522, -1, 20585, 20584, 20512, -1, 20587, 20589, 20581, -1, 20587, 20585, 20589, -1, 20512, 20590, 20502, -1, 20591, 20590, 20512, -1, 20522, 20589, 20585, -1, 20502, 20590, 20530, -1, 20531, 20502, 20530, -1, 20506, 20502, 20531, -1, 20522, 20588, 20589, -1, 20522, 20506, 20588, -1, 20590, 20534, 20528, -1, 20590, 20528, 20530, -1, 20588, 20506, 20531, -1, 20529, 20534, 20533, -1, 20529, 20528, 20534, -1, 20531, 20529, 20588, -1, 20588, 20529, 20533, -1, 20498, 20510, 20499, -1, 20499, 20510, 20567, -1, 20567, 20509, 20565, -1, 20510, 20509, 20567, -1, 20565, 20508, 20563, -1, 20509, 20508, 20565, -1, 20563, 20507, 20560, -1, 20508, 20507, 20563, -1, 20560, 20504, 20557, -1, 20507, 20504, 20560, -1, 20557, 20505, 20556, -1, 20504, 20505, 20557, -1, 20556, 20503, 20551, -1, 20505, 20503, 20556, -1, 20551, 20501, 20544, -1, 20503, 20501, 20551, -1, 20544, 20519, 20545, -1, 20501, 20519, 20544, -1, 20545, 20520, 20571, -1, 20519, 20520, 20545, -1, 20571, 20521, 20546, -1, 20520, 20521, 20571, -1, 20546, 20500, 20547, -1, 20521, 20500, 20546, -1, 20547, 20472, 20474, -1, 20500, 20472, 20547, -1, 20471, 20523, 20470, -1, 20470, 20523, 20568, -1, 20568, 20524, 20566, -1, 20523, 20524, 20568, -1, 20566, 20525, 20564, -1, 20524, 20525, 20566, -1, 20564, 20526, 20562, -1, 20525, 20526, 20564, -1, 20562, 20527, 20561, -1, 20526, 20527, 20562, -1, 20561, 20511, 20559, -1, 20527, 20511, 20561, -1, 20559, 20513, 20555, -1, 20511, 20513, 20559, -1, 20555, 20514, 20553, -1, 20513, 20514, 20555, -1, 20553, 20515, 20549, -1, 20514, 20515, 20553, -1, 20549, 20516, 20550, -1, 20515, 20516, 20549, -1, 20550, 20517, 20552, -1, 20516, 20517, 20550, -1, 20552, 20518, 20554, -1, 20517, 20518, 20552, -1, 20554, 20445, 20444, -1, 20518, 20445, 20554, -1 - ] - } - } - DEF mounting_rails Shape { - appearance Appearance { - material Material { - } - texture ImageTexture { - url [ - "textures/metal.jpg" - ] - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - 0.28249946 0.16245353 -0.1132903, 0.28300196 0.16245356 -0.11335131, 0.28249946 0.1604535 -0.1132903, 0.28300196 0.16045354 -0.11335152, 0.28347543 0.16245343 -0.11353081, 0.28347543 0.16045345 -0.11353087, 0.28389201 0.1624535 -0.1138184, 0.28389201 0.16045351 -0.11381858, 0.28422764 0.16245358 -0.11419737, 0.28422782 0.1604535 -0.11419746, 0.28446296 0.16245361 -0.11464556, 0.28446299 0.16045353 -0.11464577, 0.28458413 0.16245355 -0.11513709, 0.28458408 0.16045357 -0.11513727, 0.28458413 0.16245361 -0.11564346, 0.28458413 0.16045363 -0.11564346, 0.2844629 0.1624537 -0.11613511, 0.28446296 0.16045363 -0.11613511, 0.28422764 0.16245367 -0.11658322, 0.2842277 0.16045363 -0.11658331, 0.28389198 0.16245374 -0.11696204, 0.28389198 0.16045369 -0.11696231, 0.28347543 0.16245365 -0.11724984, 0.2834754 0.16045359 -0.11724984, 0.28300193 0.16245371 -0.11742937, 0.28300196 0.16045369 -0.11742937, 0.28249937 0.16245377 -0.11749025, 0.2824994 0.16045375 -0.1174904, -0.28750098 0.16244981 -0.1132903, -0.28699839 0.16244984 -0.11335131, -0.28750101 0.16044988 -0.1132903, -0.28699833 0.16044989 -0.11335131, -0.28652507 0.16244993 -0.11353081, -0.28652519 0.16045001 -0.11353087, -0.28610849 0.16244993 -0.1138184, -0.28610843 0.16044986 -0.11381858, -0.28577277 0.16044986 -0.11419737, -0.28577271 0.16244988 -0.11419737, -0.28553754 0.16044992 -0.11464577, -0.28553736 0.16244991 -0.11464556, -0.28541631 0.16044986 -0.11513727, -0.28541639 0.16244999 -0.11513709, -0.28541633 0.16045 -0.11564334, -0.28541639 0.16244999 -0.11564326, -0.28553733 0.16044992 -0.11613511, -0.28553754 0.16245005 -0.11613487, -0.28577274 0.16045004 -0.11658322, -0.28577262 0.16244997 -0.11658322, -0.28610846 0.16045007 -0.11696219, -0.2861084 0.16245003 -0.11696219, -0.2865251 0.16045001 -0.11724984, -0.28652504 0.16244996 -0.11724984, -0.28699842 0.16044992 -0.11742937, -0.28699842 0.16244997 -0.11742937, -0.28750101 0.16045006 -0.1174904, -0.28750098 0.16245003 -0.11749025, 0.39749941 0.16345385 -0.10689741, 0.39749947 0.16364887 -0.10687809, -0.40250096 0.16344875 -0.10689741, -0.40250111 0.16364373 -0.1068783, 0.39749941 0.16383651 -0.10682141, -0.40250099 0.16383138 -0.10682132, 0.3974995 0.16400939 -0.10672893, -0.40250117 0.16400428 -0.10672893, 0.3974995 0.16416091 -0.1066046, -0.40250108 0.16415581 -0.10660445, -0.40250105 0.16266833 -0.13301387, -0.40250114 0.1607776 -0.13482565, -0.40250117 0.16059887 -0.13454121, -0.40250102 0.16048792 -0.13422436, -0.40250114 0.16045028 -0.13389036, -0.40250105 0.1628267 -0.13317218, -0.40250096 0.16195035 -0.13539034, -0.40250108 0.16161668 -0.13535279, -0.40250117 0.16129953 -0.13524196, -0.40250108 0.16101506 -0.13506311, -0.40250102 0.16301633 -0.13329127, -0.40250117 0.1625493 -0.13282421, -0.40250096 0.16247524 -0.13261274, -0.40250105 0.1632276 -0.13336509, -0.40250102 0.16245018 -0.13239032, -0.4025012 0.1634502 -0.13339016, -0.40250096 0.16244961 -0.12488296, -0.40250126 0.17345023 -0.13338968, -0.40250126 0.17495033 -0.13538945, -0.40250102 0.17367274 -0.13336471, -0.40250114 0.17388402 -0.13329059, -0.40250114 0.17407379 -0.13317153, -0.40250114 0.17588557 -0.13506222, -0.40250102 0.17560117 -0.13524115, -0.40250129 0.17528413 -0.13535187, -0.40250126 0.17612307 -0.13482481, -0.40250102 0.17423202 -0.13301304, -0.40250126 0.17630178 -0.13454029, -0.40250126 0.17641263 -0.13422325, -0.40250126 0.1764503 -0.1338895, -0.40250117 0.17442514 -0.13261214, -0.40250102 0.17445017 -0.13238966, -0.40250123 0.17435116 -0.13282338, -0.4025012 0.16844976 -0.12563992, -0.4025012 0.16762155 -0.12763995, -0.40250117 0.1641569 -0.12417566, -0.40250117 0.16244949 -0.11964031, -0.40250117 0.16247727 -0.1246494, -0.40250096 0.16255869 -0.12442886, -0.40250102 0.16268931 -0.12423333, -0.40250102 0.16286187 -0.12407389, -0.40250108 0.16306701 -0.12395894, -0.40250108 0.16329332 -0.12389528, -0.40250111 0.16352813 -0.12388586, -0.40250111 0.16375871 -0.12393164, -0.40250105 0.16397218 -0.12403022, -0.40250117 0.17344986 -0.12763953, -0.40250114 0.17444992 -0.1286397, -0.40250123 0.17442483 -0.12841716, -0.40250126 0.17444968 -0.12563959, -0.40250111 0.17367247 -0.12766457, -0.40250126 0.17388374 -0.1277386, -0.40250126 0.17407343 -0.12785769, -0.40250126 0.17423174 -0.128016, -0.40250105 0.17435089 -0.12820566, -0.40250114 0.17444955 -0.12158953, -0.40250108 0.17197411 -0.12158977, -0.40250126 0.17197409 -0.1195898, -0.40250096 0.16266675 -0.10652115, -0.40250108 0.16282527 -0.10667955, -0.40250102 0.16244899 -0.11114036, -0.40250096 0.16301472 -0.10679855, -0.40250117 0.16254774 -0.10633149, -0.40250108 0.16322617 -0.10687237, -0.40250117 0.16247377 -0.10612004, -0.40250126 0.17594947 -0.11958956, -0.40250126 0.17644946 -0.12008952, -0.40250126 0.17643698 -0.11997818, -0.40250126 0.1761664 -0.11963903, -0.40250126 0.17606069 -0.1196022, -0.40250117 0.17639998 -0.11987244, -0.40250096 0.1624486 -0.1058976, -0.40250126 0.1763404 -0.11977779, -0.40250105 0.17626114 -0.11969864, -0.40250096 0.16044815 -0.096890442, -0.40250105 0.16244823 -0.098390184, -0.40250096 0.16247322 -0.09816774, -0.4025012 0.16762021 -0.10313999, -0.40250114 0.16844869 -0.10513984, -0.40250117 0.16254728 -0.097956501, -0.40250105 0.16266637 -0.09776675, -0.40250108 0.16048579 -0.096556626, -0.40250117 0.16059664 -0.09623953, -0.40250108 0.16077533 -0.095955096, -0.40250126 0.17616589 -0.11113986, -0.40250117 0.17606026 -0.1111769, -0.40250126 0.17594908 -0.11118954, -0.40250114 0.17444891 -0.10918968, -0.4025012 0.17197366 -0.11118969, -0.40250123 0.17197347 -0.10918968, -0.40250102 0.16101283 -0.095717393, -0.4025012 0.16282474 -0.097608291, -0.40250126 0.17643647 -0.1108008, -0.40250129 0.17639939 -0.11090641, -0.40250117 0.17633992 -0.11100113, -0.40250117 0.17626071 -0.11108022, -0.40250126 0.17644891 -0.11068948, -0.40250114 0.16129723 -0.095538698, -0.40250102 0.16161431 -0.095427893, -0.40250117 0.16194807 -0.095390163, -0.40250102 0.16301431 -0.09748935, -0.4025012 0.16322565 -0.09741541, -0.40250099 0.16344818 -0.097390138, -0.40250129 0.17444874 -0.10513955, -0.40250114 0.17344852 -0.10313954, -0.40250102 0.17367098 -0.1031146, -0.40250102 0.1738824 -0.10304069, -0.40250117 0.17407209 -0.10292139, -0.40250126 0.17423038 -0.1027632, -0.40250126 0.17434937 -0.10257336, -0.40250126 0.17442341 -0.10236203, -0.40250123 0.17344819 -0.09738978, -0.40250126 0.17494801 -0.095389538, -0.40250114 0.17367071 -0.097414576, -0.40250126 0.17388207 -0.097488694, -0.40250126 0.17407173 -0.097607933, -0.40250114 0.17644815 -0.096889578, -0.40250126 0.17434923 -0.097955666, -0.40250105 0.17423001 -0.097766005, -0.40250114 0.17442316 -0.098167144, -0.40250105 0.17444816 -0.098389588, -0.40250123 0.17444843 -0.10213958, -0.40250102 0.17528185 -0.095427208, -0.40250114 0.17641048 -0.096555553, -0.40250126 0.17559893 -0.095538102, -0.40250117 0.17629963 -0.096238576, -0.40250114 0.17588334 -0.095716558, -0.40250126 0.17612092 -0.095954262, 0.39749944 0.16195546 -0.13539034, 0.39749947 0.16283181 -0.13317218, 0.39749953 0.16162165 -0.13535279, 0.39749947 0.16130462 -0.13524181, 0.39749941 0.16102017 -0.13506311, 0.39749941 0.16078271 -0.13482586, 0.39749944 0.1626735 -0.13301387, 0.39749947 0.16060397 -0.13454121, 0.39749944 0.160493 -0.13422436, 0.39749953 0.16045542 -0.13389036, 0.39749944 0.16255435 -0.13282421, 0.39749941 0.16302145 -0.13329127, 0.39749941 0.16248038 -0.13261274, 0.39749941 0.16323283 -0.13336512, 0.39749947 0.16345534 -0.13339016, 0.39749959 0.16245528 -0.13239017, 0.39749956 0.16245477 -0.12488281, 0.39749941 0.17345533 -0.13338983, 0.39749944 0.1749554 -0.13538966, 0.39749935 0.17367785 -0.13336471, 0.39749941 0.1738892 -0.13329071, 0.39749941 0.17407887 -0.13317153, 0.39749941 0.17589068 -0.13506222, 0.39749935 0.17560624 -0.13524115, 0.39749938 0.17528924 -0.13535187, 0.39749941 0.17612813 -0.13482481, 0.39749944 0.17423718 -0.13301304, 0.39749944 0.17630687 -0.13454029, 0.39749938 0.17641768 -0.13422325, 0.39749953 0.17443021 -0.13261214, 0.39749941 0.17645536 -0.13388959, 0.39749944 0.17445527 -0.13238966, 0.39749944 0.17435627 -0.13282338, 0.39749947 0.16762665 -0.12763995, 0.39749935 0.1684549 -0.12563992, 0.39749941 0.16416195 -0.12417566, 0.39749947 0.16248241 -0.12464928, 0.39749953 0.16245461 -0.11964031, 0.39749953 0.16256393 -0.12442886, 0.39749941 0.16269436 -0.12423333, 0.39749941 0.16286704 -0.12407374, 0.39749944 0.1630722 -0.12395894, 0.39749947 0.16329841 -0.12389528, 0.39749947 0.16353332 -0.12388595, 0.39749947 0.1637639 -0.12393179, 0.39749941 0.16397735 -0.12403022, 0.39749941 0.17345497 -0.1276398, 0.39749944 0.17445512 -0.12863961, 0.39749944 0.17443009 -0.12841716, 0.39749941 0.1736775 -0.12766483, 0.39749947 0.17445487 -0.12563959, 0.39749941 0.17388883 -0.1277386, 0.39749944 0.17407854 -0.12785769, 0.39749944 0.17423697 -0.12801626, 0.39749941 0.17435603 -0.12820566, 0.39749944 0.17197928 -0.12158962, 0.39749944 0.1744547 -0.12158953, 0.39749944 0.1719792 -0.11958956, 0.39749947 0.16283038 -0.10667955, 0.39749944 0.16267201 -0.10652115, 0.39749953 0.16245405 -0.11114027, 0.39749941 0.16301987 -0.10679846, 0.39749947 0.1625528 -0.10633134, 0.39749947 0.16323128 -0.10687246, 0.39749953 0.16247892 -0.10612004, 0.39749935 0.17595461 -0.11958956, 0.39749941 0.1764546 -0.12008952, 0.39749941 0.17644209 -0.11997818, 0.39749935 0.17617145 -0.11963903, 0.39749935 0.17606583 -0.1196022, 0.39749941 0.17640509 -0.11987244, 0.39749947 0.1624538 -0.1058976, 0.39749947 0.17626628 -0.11969864, 0.39749941 0.17634553 -0.11977779, 0.39749959 0.16045322 -0.096890442, 0.39749965 0.16245341 -0.098390184, 0.39749953 0.16247846 -0.09816774, 0.39749953 0.16845381 -0.10513984, 0.39749941 0.16762532 -0.10313999, 0.3974995 0.16255243 -0.097956352, 0.39749941 0.16267149 -0.097766839, 0.39749965 0.16049081 -0.096556626, 0.39749941 0.16060178 -0.096239768, 0.39749953 0.16078046 -0.095955096, 0.39749941 0.17606537 -0.1111769, 0.39749941 0.17617112 -0.11114006, 0.39749935 0.17595416 -0.11118954, 0.39749944 0.17197874 -0.11118969, 0.39749956 0.17445397 -0.10918968, 0.39749956 0.17197862 -0.10918968, 0.39749941 0.16101794 -0.095717601, 0.39749953 0.16282988 -0.097608529, 0.39749947 0.17644146 -0.1108008, 0.39749935 0.17640454 -0.11090641, 0.39749935 0.17634499 -0.11100113, 0.39749956 0.17626578 -0.11108022, 0.39749944 0.17645401 -0.11068948, 0.39749953 0.1613024 -0.095538907, 0.39749947 0.16161945 -0.095427893, 0.39749941 0.16301945 -0.09748935, 0.39749947 0.16195318 -0.095390163, 0.39749941 0.16323081 -0.09741541, 0.39749947 0.16345331 -0.097390138, 0.39749941 0.17445377 -0.10513955, 0.39749938 0.17345366 -0.10313978, 0.39749944 0.17367621 -0.10311451, 0.39749941 0.17388752 -0.10304042, 0.39749941 0.17407718 -0.10292139, 0.39749944 0.17423554 -0.10276302, 0.39749944 0.17435455 -0.10257327, 0.39749935 0.17442857 -0.10236203, 0.39749941 0.17345333 -0.09738978, 0.39749944 0.17435427 -0.097955577, 0.39749944 0.17645329 -0.096889578, 0.39749935 0.17423515 -0.097766005, 0.39749944 0.17442824 -0.098167144, 0.39749941 0.1744533 -0.098389588, 0.39749944 0.17445369 -0.10213958, 0.39749944 0.17495318 -0.095389329, 0.39749935 0.17367582 -0.097414576, 0.39749938 0.17388722 -0.097488694, 0.39749944 0.17407681 -0.097607695, 0.39749935 0.17641565 -0.096555643, 0.39749935 0.17528692 -0.095427208, 0.39749947 0.17560405 -0.095538102, 0.39749956 0.17630464 -0.096238576, 0.39749935 0.1758884 -0.095716767, 0.39749941 0.17612594 -0.095954262, 0.28041467 0.1604536 -0.11564346, 0.28053588 0.16045362 -0.11613511, 0.2804147 0.16045357 -0.11513727, 0.28053591 0.16045354 -0.11464577, 0.28077123 0.16045344 -0.11419737, 0.2811068 0.1604535 -0.11381858, -0.2880035 0.16045004 -0.11742937, -0.28847691 0.16045 -0.11724984, -0.28889349 0.16044998 -0.11696219, -0.28922921 0.16044997 -0.11658322, -0.2894645 0.16044991 -0.11613511, -0.28958565 0.16044989 -0.11564346, -0.28958565 0.16044989 -0.11513727, -0.2894645 0.16044983 -0.11464577, -0.28922933 0.16045001 -0.11419746, -0.28889355 0.16044994 -0.11381858, -0.28847697 0.16044994 -0.11353087, -0.28800347 0.16044985 -0.11335131, 0.28110689 0.1604536 -0.11696231, 0.28077108 0.16045365 -0.11658322, 0.28199685 0.1604535 -0.11335152, 0.28152347 0.16045359 -0.11353087, 0.28152347 0.16045374 -0.11724984, 0.28199691 0.1604536 -0.11742937, 0.28077114 0.16245359 -0.11658322, 0.28041467 0.16245365 -0.11564326, 0.28041479 0.16245353 -0.11513709, 0.28053591 0.16245358 -0.11464556, 0.28077117 0.16245347 -0.11419737, 0.2811068 0.16245347 -0.11381834, 0.28152362 0.16245344 -0.11353081, -0.28800347 0.16245008 -0.11742937, -0.28847697 0.16245002 -0.11724984, -0.28889346 0.16245 -0.11696219, -0.28922933 0.16245003 -0.11658322, -0.28946459 0.16245005 -0.11613487, -0.28958583 0.16245003 -0.11564346, -0.28958568 0.1624499 -0.11513709, -0.2894645 0.16244979 -0.11464556, -0.28922915 0.16244979 -0.11419737, -0.28889352 0.16244985 -0.11381834, -0.28847688 0.16244982 -0.11353081, -0.2880035 0.16244973 -0.11335119, 0.28199694 0.1624537 -0.11742937, 0.28152359 0.16245368 -0.11724972, 0.28199688 0.16245347 -0.11335131, 0.28110686 0.16245359 -0.11696219, 0.28053588 0.16245368 -0.11613511, 0.28249934 0.16244051 0.11750973, 0.28300199 0.16244042 0.1174487, 0.28249937 0.16044056 0.11750973, 0.2830019 0.16044046 0.1174487, 0.28347531 0.16244046 0.11726926, 0.28347543 0.16044039 0.11726917, 0.28389201 0.16244042 0.11698184, 0.28389201 0.16044039 0.11698178, 0.28422764 0.16244067 0.11660264, 0.28422776 0.16044053 0.11660246, 0.28446299 0.16244055 0.11615456, 0.28446305 0.16044064 0.11615435, 0.28458405 0.16244061 0.11566309, 0.28458408 0.16044073 0.11566288, 0.28458402 0.16244067 0.11515681, 0.28458411 0.16044064 0.11515657, 0.28446284 0.1624407 0.11466516, 0.28446305 0.16044064 0.11466504, 0.28422764 0.16044065 0.11421681, 0.2842277 0.16244061 0.11421681, 0.28389198 0.16044064 0.11383788, 0.28389195 0.16244067 0.11383788, 0.28347531 0.16044062 0.11355019, 0.28347543 0.16244066 0.11355034, 0.28300202 0.16044068 0.11337075, 0.28300199 0.16244063 0.11337075, 0.28249943 0.1604407 0.11330978, 0.2824994 0.16244076 0.11330978, -0.28750098 0.1624368 0.11750982, -0.28699842 0.16243675 0.11744878, -0.28750095 0.16043679 0.11750982, -0.28699842 0.16043684 0.11744878, -0.2865251 0.16243681 0.11726926, -0.28652504 0.16043681 0.1172689, -0.28610837 0.16243681 0.11698184, -0.2861084 0.16043684 0.11698157, -0.28577274 0.16243702 0.11660264, -0.28577268 0.16043697 0.11660264, -0.28553748 0.16243696 0.11615456, -0.28553751 0.16043699 0.11615435, -0.28541633 0.16243695 0.11566309, -0.28541631 0.16043696 0.11566288, -0.28541636 0.16243702 0.11515681, -0.28541631 0.16043696 0.11515657, -0.28553751 0.16043705 0.11466504, -0.28553748 0.16243711 0.11466516, -0.28577271 0.16043708 0.11421681, -0.28577274 0.16243702 0.11421696, -0.2861084 0.16043699 0.11383788, -0.28610852 0.16243708 0.11383811, -0.2865251 0.16043705 0.11355019, -0.28652507 0.1624371 0.11355034, -0.28699839 0.16043699 0.11337055, -0.28699842 0.16243701 0.11337075, -0.28750101 0.16043706 0.11330978, -0.28750098 0.16243699 0.11330978, 0.39749941 0.16344091 0.12390254, 0.3974995 0.16363597 0.12392185, -0.40250105 0.16343573 0.12390254, -0.40250108 0.16363095 0.12392185, 0.39749947 0.16382357 0.12397883, -0.40250108 0.1638186 0.12397883, 0.39749947 0.16399638 0.12407122, -0.40250108 0.1639913 0.12407122, 0.3974995 0.16414797 0.12419555, -0.40250108 0.16414283 0.12419531, -0.40250117 0.16265546 0.097786285, -0.40250102 0.16076446 0.095974572, -0.40250102 0.16058572 0.096258886, -0.40250108 0.16047484 0.096575774, -0.40250102 0.16043726 0.096909888, -0.4025012 0.16281374 0.097628124, -0.40250108 0.16193736 0.095409907, -0.40250108 0.16160351 0.095447548, -0.40250102 0.16128637 0.095558174, -0.40250108 0.16100204 0.095737137, -0.40250102 0.16300331 0.097508796, -0.40250108 0.16253632 0.097975947, -0.40250102 0.16246231 0.098187454, -0.40250117 0.16321471 0.097434886, -0.40250108 0.16343729 0.097409971, -0.40250117 0.16243732 0.098409779, -0.40250108 0.16243675 0.10591713, -0.40250117 0.17343734 0.097410418, -0.40250114 0.17493743 0.095410831, -0.40250114 0.17365976 0.097435482, -0.40250117 0.17387113 0.097509392, -0.40250117 0.17406079 0.097628571, -0.40250126 0.17587259 0.095737733, -0.40250117 0.17558819 0.095559247, -0.40250126 0.17527103 0.095448203, -0.40250126 0.17611013 0.095975406, -0.40250114 0.17421909 0.09778703, -0.40250117 0.17628884 0.09625984, -0.4025012 0.1763996 0.096576817, -0.40250114 0.17643715 0.096910812, -0.40250126 0.17441225 0.098187931, -0.40250114 0.17443722 0.098410375, -0.40250114 0.17433819 0.097976483, -0.40250117 0.16243652 0.11115996, -0.40250108 0.16246435 0.10615055, -0.40250108 0.16254576 0.10637126, -0.40250102 0.16267629 0.10656656, -0.40250117 0.16284899 0.10672645, -0.40250105 0.163054 0.10684095, -0.40250108 0.16328034 0.10690514, -0.40250123 0.16351524 0.10691432, -0.40250105 0.16374572 0.1068683, -0.40250105 0.16395916 0.10676984, -0.4025012 0.16414386 0.10662437, -0.40250108 0.16843669 0.10516021, -0.4025012 0.16760859 0.10316012, -0.40250114 0.17443694 0.10216046, -0.40250114 0.1734369 0.10316033, -0.40250114 0.17441191 0.10238323, -0.40250126 0.17443687 0.10516078, -0.40250126 0.17365953 0.1031353, -0.40250114 0.17387079 0.10306145, -0.40250114 0.17406043 0.10294221, -0.40250114 0.17421874 0.1027839, -0.40250117 0.17433798 0.10259447, -0.40250117 0.17443657 0.10921044, -0.40250114 0.17196119 0.10921041, -0.40250114 0.17196119 0.11121026, -0.40250108 0.16265389 0.124279, -0.40250105 0.16281225 0.12412069, -0.40250102 0.16243596 0.11965988, -0.40250117 0.16300195 0.1240016, -0.40250117 0.1625348 0.12446866, -0.40250105 0.16321315 0.12392757, -0.40250117 0.16246091 0.12468002, -0.40250129 0.1764366 0.11071066, -0.40250129 0.17593656 0.11121056, -0.4025012 0.17642392 0.11082212, -0.40250114 0.17604776 0.11119822, -0.40250108 0.16243574 0.12490246, -0.40250129 0.17632753 0.11102239, -0.40250126 0.17638701 0.11092774, -0.40250114 0.17624822 0.11110178, -0.40250131 0.17615354 0.11116103, -0.40250105 0.1604351 0.13390982, -0.40250108 0.16243529 0.13240981, -0.40250108 0.16246033 0.13263226, -0.40250114 0.1676071 0.12765998, -0.40250114 0.16843559 0.12566027, -0.40250102 0.16253425 0.13284364, -0.40250102 0.16265349 0.13303331, -0.40250102 0.16047272 0.13424349, -0.40250117 0.16058373 0.13456061, -0.40250108 0.16076235 0.13484514, -0.40250126 0.17624782 0.11971975, -0.4025012 0.17615297 0.1196603, -0.40250117 0.1760473 0.11962304, -0.40250126 0.17443585 0.12161062, -0.40250126 0.17593615 0.11961076, -0.40250123 0.17196065 0.11961026, -0.40250123 0.17196049 0.12161053, -0.40250117 0.16099998 0.13508257, -0.40250117 0.16281174 0.13319185, -0.40250117 0.17638654 0.11989374, -0.40250114 0.17632695 0.11979888, -0.40250114 0.17643596 0.12011052, -0.40250126 0.17642353 0.11999951, -0.40250102 0.16128422 0.1352613, -0.4025012 0.16160141 0.13537228, -0.40250117 0.16193514 0.13540995, -0.40250117 0.1630014 0.13331091, -0.40250108 0.16321278 0.1333847, -0.40250105 0.16343522 0.13341001, -0.40250126 0.17443572 0.1256606, -0.40250126 0.17343563 0.1276606, -0.40250114 0.17365803 0.12768546, -0.40250114 0.17386943 0.12775952, -0.40250114 0.17405909 0.12787876, -0.40250114 0.17421736 0.12803707, -0.40250126 0.17433658 0.12822679, -0.40250114 0.17441046 0.12843797, -0.40250117 0.17343533 0.13341045, -0.40250117 0.17643517 0.13391069, -0.40250114 0.17433621 0.13284448, -0.40250117 0.1742171 0.13303375, -0.40250126 0.17441025 0.13263324, -0.40250117 0.17443526 0.13241053, -0.40250126 0.17443556 0.1286605, -0.40250126 0.17493504 0.13541067, -0.40250114 0.17365773 0.13338521, -0.40250126 0.1738691 0.13331154, -0.40250126 0.17405877 0.13319245, -0.40250114 0.17526884 0.13537303, -0.40250117 0.17639753 0.13424453, -0.40250117 0.1755859 0.13526201, -0.40250126 0.17628664 0.13456139, -0.40250126 0.1758704 0.13508344, -0.40250126 0.17610794 0.1348457, 0.39749953 0.16076969 0.095974453, 0.39749953 0.16266052 0.097786285, 0.39749953 0.1605909 0.096258886, 0.39749953 0.16047987 0.096575774, 0.39749956 0.16044226 0.096909888, 0.39749953 0.16281883 0.097628005, 0.39749947 0.16194251 0.095409907, 0.39749947 0.16160867 0.095447309, 0.39749953 0.1612916 0.095558293, 0.39749941 0.16100715 0.095737107, 0.3974995 0.16254136 0.097975858, 0.39749935 0.1630085 0.097508796, 0.39749944 0.16246741 0.098187454, 0.39749947 0.16321984 0.097435005, 0.39749953 0.16244234 0.098409779, 0.39749953 0.16344231 0.097409852, 0.3974995 0.16244191 0.10591713, 0.39749944 0.17344229 0.097410418, 0.39749953 0.17494242 0.095410503, 0.39749944 0.17366478 0.097435601, 0.39749944 0.17387624 0.097509392, 0.39749944 0.17406581 0.09762872, 0.39749941 0.17587762 0.095737733, 0.39749959 0.17559321 0.095559247, 0.39749953 0.17527609 0.095448203, 0.39749947 0.17611508 0.095975406, 0.39749947 0.17422414 0.09778703, 0.39749941 0.17629382 0.09625984, 0.39749947 0.17640463 0.096576817, 0.39749947 0.17441724 0.09818805, 0.39749941 0.17644238 0.096910723, 0.39749947 0.17444228 0.098410495, 0.39749941 0.17434326 0.097976483, 0.39749941 0.16246948 0.10615055, 0.39749953 0.16244158 0.11115996, 0.39749953 0.16255082 0.10637126, 0.39749947 0.16268143 0.10656656, 0.39749941 0.16285408 0.10672645, 0.39749941 0.1630592 0.10684095, 0.39749953 0.16328536 0.10690484, 0.3974995 0.16352028 0.10691432, 0.39749953 0.16375083 0.1068683, 0.39749947 0.1639643 0.10677011, 0.39749941 0.1641489 0.10662452, 0.3974995 0.16761376 0.10316, 0.39749959 0.16844188 0.10516021, 0.39749947 0.17344204 0.10316051, 0.39749941 0.17444204 0.10216046, 0.39749947 0.17441702 0.10238323, 0.39749935 0.17366461 0.1031353, 0.39749935 0.17444192 0.10516051, 0.39749935 0.17387597 0.10306145, 0.39749947 0.17406556 0.10294221, 0.39749944 0.17422388 0.1027839, 0.39749947 0.17434299 0.10259447, 0.39749944 0.1624411 0.11965988, 0.39749944 0.17196618 0.10921041, 0.39749938 0.17444167 0.10921044, 0.39749944 0.17196625 0.11121026, 0.39749953 0.1628174 0.12412057, 0.39749953 0.16265902 0.12427912, 0.39749953 0.16300702 0.1240016, 0.39749953 0.16253982 0.12446866, 0.39749953 0.16321835 0.12392769, 0.39749953 0.16246592 0.1246799, 0.39749938 0.17644167 0.11071045, 0.39749938 0.17594168 0.11121056, 0.39749938 0.1760529 0.11119822, 0.39749941 0.17642915 0.11082212, 0.39749953 0.16244082 0.12490246, 0.39749941 0.17625344 0.11110178, 0.39749938 0.17615852 0.11116124, 0.39749941 0.1763325 0.11102239, 0.39749944 0.17639214 0.11092774, 0.39749947 0.16044024 0.1339097, 0.3974995 0.1624404 0.13240981, 0.39749953 0.16246551 0.13263226, 0.39749947 0.16844077 0.12566027, 0.39749941 0.1676123 0.12766021, 0.39749953 0.16253936 0.13284349, 0.3974995 0.16265856 0.13303331, 0.39749947 0.16047779 0.13424349, 0.39749953 0.16058882 0.13456035, 0.39749953 0.16076753 0.13484502, 0.39749935 0.17605244 0.11962331, 0.39749941 0.17615806 0.1196603, 0.39749941 0.17594117 0.11961076, 0.39749953 0.17196572 0.11961026, 0.39749938 0.17444095 0.12161053, 0.39749941 0.17196563 0.12161038, 0.39749953 0.16100495 0.13508257, 0.39749953 0.16281685 0.13319159, 0.39749935 0.17644115 0.12011061, 0.39749941 0.17642869 0.11999951, 0.39749941 0.17639159 0.11989374, 0.39749935 0.17633207 0.119799, 0.39749938 0.17625293 0.11971984, 0.39749953 0.16128932 0.1352613, 0.39749965 0.1616064 0.13537228, 0.39749944 0.1619402 0.13540995, 0.39749953 0.16300647 0.13331091, 0.39749953 0.16321784 0.1333847, 0.3974995 0.16344035 0.13340974, 0.39749941 0.1744407 0.1256606, 0.39749935 0.17344068 0.12766027, 0.39749935 0.17366318 0.12768546, 0.39749935 0.17387454 0.12775952, 0.39749938 0.17406423 0.12787843, 0.39749935 0.17422251 0.12803689, 0.39749941 0.17434162 0.12822655, 0.39749941 0.17441559 0.12843797, 0.39749935 0.17344044 0.13341045, 0.39749935 0.17434137 0.13284421, 0.39749947 0.17644024 0.13391066, 0.39749935 0.17422225 0.13303387, 0.39749944 0.17441542 0.13263297, 0.39749944 0.17444046 0.13241053, 0.39749935 0.17444067 0.1286605, 0.39749941 0.17494023 0.13541067, 0.39749944 0.17366298 0.1333853, 0.39749947 0.17387432 0.13331148, 0.39749941 0.17406395 0.13319245, 0.39749941 0.17640255 0.13424435, 0.39749938 0.17527398 0.13537323, 0.39749944 0.17559107 0.13526201, 0.39749932 0.17629176 0.13456154, 0.39749941 0.17587543 0.13508344, 0.39749941 0.17611301 0.1348457, 0.28152347 0.16044071 0.11355019, 0.28041467 0.16044067 0.11515657, 0.28053591 0.16044062 0.11466492, 0.28199685 0.16044065 0.11337055, 0.28041467 0.16044067 0.11566279, 0.28053588 0.16044056 0.11615435, 0.28077108 0.16044062 0.11660264, 0.28110683 0.16044043 0.11698157, -0.28800353 0.160437 0.11337075, -0.28847697 0.16043712 0.11355019, -0.28889352 0.16043702 0.11383788, -0.28922927 0.16043706 0.11421681, -0.28946456 0.16043706 0.11466504, -0.28958574 0.16043706 0.11515657, -0.28958574 0.160437 0.11566309, -0.2894645 0.16043694 0.11615435, -0.28922921 0.16043687 0.11660264, -0.28889364 0.16043688 0.11698184, -0.28847691 0.16043676 0.11726917, -0.28800359 0.16043681 0.11744878, 0.28199691 0.16044052 0.11744864, 0.28152347 0.16044047 0.1172689, 0.28077117 0.16044068 0.11421681, 0.28110689 0.16044068 0.11383788, 0.28199688 0.16244069 0.11337075, 0.28152362 0.16244061 0.11355019, 0.28199682 0.16244042 0.11744878, 0.2811068 0.16244066 0.11383788, 0.28152353 0.16244036 0.11726926, 0.28077117 0.1624407 0.11421696, 0.28053588 0.16244066 0.11466504, 0.28041473 0.16244061 0.11515657, 0.28041473 0.16244058 0.11566309, 0.28053597 0.16244054 0.11615456, 0.28077114 0.1624406 0.11660264, 0.28110686 0.16244042 0.11698184, -0.2880035 0.16243701 0.11337075, -0.28847691 0.16243699 0.11355019, -0.28889355 0.16243701 0.11383788, -0.28922921 0.16243699 0.11421696, -0.2894645 0.16243698 0.11466504, -0.28958556 0.16243684 0.11515657, -0.28958565 0.16243698 0.11566309, -0.28946459 0.16243698 0.11615456, -0.28922915 0.16243687 0.11660264, -0.28889352 0.16243671 0.11698184, -0.28847697 0.16243678 0.11726926, -0.28800347 0.16243669 0.11744878 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 2, 1, 3, -1, 3, 4, 5, -1, 1, 4, 3, -1, 5, 6, 7, -1, 4, 6, 5, -1, 7, 8, 9, -1, 6, 8, 7, -1, 9, 10, 11, -1, 8, 10, 9, -1, 11, 12, 13, -1, 10, 12, 11, -1, 13, 14, 15, -1, 12, 14, 13, -1, 15, 16, 17, -1, 14, 16, 15, -1, 17, 18, 19, -1, 16, 18, 17, -1, 19, 20, 21, -1, 18, 20, 19, -1, 21, 22, 23, -1, 20, 22, 21, -1, 23, 24, 25, -1, 22, 24, 23, -1, 25, 26, 27, -1, 24, 26, 25, -1, 28, 29, 30, -1, 30, 29, 31, -1, 31, 32, 33, -1, 29, 32, 31, -1, 33, 34, 35, -1, 35, 34, 36, -1, 32, 34, 33, -1, 36, 37, 38, -1, 34, 37, 36, -1, 38, 39, 40, -1, 37, 39, 38, -1, 40, 41, 42, -1, 39, 41, 40, -1, 42, 43, 44, -1, 41, 43, 42, -1, 44, 45, 46, -1, 43, 45, 44, -1, 46, 47, 48, -1, 45, 47, 46, -1, 48, 49, 50, -1, 47, 49, 48, -1, 50, 51, 52, -1, 49, 51, 50, -1, 52, 53, 54, -1, 51, 53, 52, -1, 53, 55, 54, -1, 56, 57, 58, -1, 58, 57, 59, -1, 59, 60, 61, -1, 57, 60, 59, -1, 61, 62, 63, -1, 60, 62, 61, -1, 63, 64, 65, -1, 62, 64, 63, -1, 66, 67, 68, -1, 66, 68, 69, -1, 66, 69, 70, -1, 71, 72, 73, -1, 71, 73, 74, -1, 71, 74, 75, -1, 71, 75, 67, -1, 71, 67, 66, -1, 76, 72, 71, -1, 77, 66, 70, -1, 78, 77, 70, -1, 79, 72, 76, -1, 80, 78, 70, -1, 81, 72, 79, -1, 82, 80, 70, -1, 83, 84, 72, -1, 83, 72, 81, -1, 85, 84, 83, -1, 86, 84, 85, -1, 87, 84, 86, -1, 87, 88, 89, -1, 87, 89, 90, -1, 87, 90, 84, -1, 91, 88, 87, -1, 91, 87, 92, -1, 93, 91, 92, -1, 94, 93, 92, -1, 95, 94, 92, -1, 95, 96, 97, -1, 95, 98, 96, -1, 95, 92, 98, -1, 99, 100, 101, -1, 102, 103, 82, -1, 102, 104, 103, -1, 102, 105, 104, -1, 102, 106, 105, -1, 102, 107, 106, -1, 102, 108, 107, -1, 102, 109, 108, -1, 102, 82, 70, -1, 102, 110, 109, -1, 102, 111, 110, -1, 102, 101, 111, -1, 112, 100, 99, -1, 113, 95, 97, -1, 114, 95, 113, -1, 115, 112, 99, -1, 115, 95, 114, -1, 115, 116, 112, -1, 115, 117, 116, -1, 115, 118, 117, -1, 115, 119, 118, -1, 115, 120, 119, -1, 115, 114, 120, -1, 121, 122, 123, -1, 124, 125, 126, -1, 127, 126, 125, -1, 128, 124, 126, -1, 129, 126, 127, -1, 130, 128, 126, -1, 131, 121, 123, -1, 132, 95, 115, -1, 132, 115, 121, -1, 132, 121, 131, -1, 133, 132, 131, -1, 134, 131, 135, -1, 136, 133, 131, -1, 58, 126, 129, -1, 137, 130, 126, -1, 138, 136, 131, -1, 139, 131, 134, -1, 139, 138, 131, -1, 59, 126, 58, -1, 61, 126, 59, -1, 63, 126, 61, -1, 65, 126, 63, -1, 140, 102, 70, -1, 140, 126, 102, -1, 140, 137, 126, -1, 141, 137, 140, -1, 142, 141, 140, -1, 143, 144, 65, -1, 145, 142, 140, -1, 146, 145, 140, -1, 146, 140, 147, -1, 146, 147, 148, -1, 146, 148, 149, -1, 150, 151, 152, -1, 153, 152, 154, -1, 153, 154, 155, -1, 156, 157, 146, -1, 156, 146, 149, -1, 158, 150, 152, -1, 158, 159, 160, -1, 158, 160, 161, -1, 158, 161, 150, -1, 162, 152, 153, -1, 162, 158, 152, -1, 163, 157, 156, -1, 164, 157, 163, -1, 165, 166, 157, -1, 165, 167, 166, -1, 165, 168, 167, -1, 165, 157, 164, -1, 169, 162, 153, -1, 170, 169, 144, -1, 170, 144, 143, -1, 171, 169, 170, -1, 172, 169, 171, -1, 173, 169, 172, -1, 174, 169, 173, -1, 175, 169, 174, -1, 176, 169, 175, -1, 177, 168, 165, -1, 178, 177, 165, -1, 178, 179, 177, -1, 178, 180, 179, -1, 178, 181, 180, -1, 182, 183, 184, -1, 182, 185, 183, -1, 182, 186, 185, -1, 182, 162, 169, -1, 182, 176, 187, -1, 182, 169, 176, -1, 182, 187, 186, -1, 188, 181, 178, -1, 189, 182, 184, -1, 190, 181, 188, -1, 191, 189, 184, -1, 192, 181, 190, -1, 193, 184, 181, -1, 193, 181, 192, -1, 193, 191, 184, -1, 144, 126, 65, -1, 102, 99, 101, -1, 194, 195, 196, -1, 196, 195, 197, -1, 197, 195, 198, -1, 198, 195, 199, -1, 195, 200, 199, -1, 199, 200, 201, -1, 201, 200, 202, -1, 202, 200, 203, -1, 200, 204, 203, -1, 194, 205, 195, -1, 204, 206, 203, -1, 194, 207, 205, -1, 194, 208, 207, -1, 206, 209, 203, -1, 209, 210, 203, -1, 194, 211, 208, -1, 212, 211, 194, -1, 212, 213, 211, -1, 212, 214, 213, -1, 212, 215, 214, -1, 216, 215, 217, -1, 217, 215, 218, -1, 218, 215, 212, -1, 216, 219, 215, -1, 215, 219, 220, -1, 219, 221, 220, -1, 221, 222, 220, -1, 223, 224, 225, -1, 226, 224, 223, -1, 220, 224, 226, -1, 222, 224, 220, -1, 227, 228, 229, -1, 230, 231, 210, -1, 232, 231, 230, -1, 233, 231, 232, -1, 234, 231, 233, -1, 235, 231, 234, -1, 236, 231, 235, -1, 237, 231, 236, -1, 238, 231, 237, -1, 239, 231, 238, -1, 229, 231, 239, -1, 210, 231, 203, -1, 227, 240, 228, -1, 224, 241, 225, -1, 224, 242, 241, -1, 243, 244, 240, -1, 245, 244, 243, -1, 246, 244, 245, -1, 247, 244, 246, -1, 248, 244, 247, -1, 242, 244, 248, -1, 240, 244, 228, -1, 224, 244, 242, -1, 249, 250, 251, -1, 252, 253, 254, -1, 254, 255, 252, -1, 253, 256, 254, -1, 254, 257, 255, -1, 256, 258, 254, -1, 250, 259, 251, -1, 244, 260, 250, -1, 224, 260, 244, -1, 250, 260, 259, -1, 260, 261, 259, -1, 259, 262, 263, -1, 261, 264, 259, -1, 254, 56, 257, -1, 258, 265, 254, -1, 259, 266, 262, -1, 264, 267, 259, -1, 259, 267, 266, -1, 254, 57, 56, -1, 254, 60, 57, -1, 254, 62, 60, -1, 254, 64, 62, -1, 231, 268, 203, -1, 254, 268, 231, -1, 265, 268, 254, -1, 265, 269, 268, -1, 269, 270, 268, -1, 271, 272, 64, -1, 270, 273, 268, -1, 273, 274, 268, -1, 268, 274, 275, -1, 275, 274, 276, -1, 276, 274, 277, -1, 278, 279, 280, -1, 281, 282, 283, -1, 280, 282, 281, -1, 274, 284, 277, -1, 285, 284, 274, -1, 279, 286, 280, -1, 287, 286, 288, -1, 288, 286, 289, -1, 289, 286, 279, -1, 286, 290, 280, -1, 280, 290, 282, -1, 285, 291, 284, -1, 285, 292, 291, -1, 293, 294, 285, -1, 295, 294, 293, -1, 296, 294, 295, -1, 285, 294, 292, -1, 290, 297, 282, -1, 297, 298, 271, -1, 271, 298, 272, -1, 297, 299, 298, -1, 297, 300, 299, -1, 297, 301, 300, -1, 297, 302, 301, -1, 297, 303, 302, -1, 297, 304, 303, -1, 296, 305, 294, -1, 306, 307, 308, -1, 309, 307, 306, -1, 310, 307, 309, -1, 311, 307, 310, -1, 304, 307, 311, -1, 290, 307, 297, -1, 297, 307, 304, -1, 305, 312, 294, -1, 313, 312, 305, -1, 314, 312, 313, -1, 315, 312, 314, -1, 307, 316, 308, -1, 315, 317, 312, -1, 315, 318, 317, -1, 316, 319, 308, -1, 315, 320, 318, -1, 315, 321, 320, -1, 319, 321, 308, -1, 308, 321, 315, -1, 228, 231, 229, -1, 254, 271, 64, -1, 251, 123, 249, -1, 249, 123, 122, -1, 259, 131, 251, -1, 251, 131, 123, -1, 260, 132, 133, -1, 261, 260, 133, -1, 264, 133, 136, -1, 264, 261, 133, -1, 267, 136, 138, -1, 267, 264, 136, -1, 266, 138, 139, -1, 266, 267, 138, -1, 262, 134, 135, -1, 262, 139, 134, -1, 262, 266, 139, -1, 263, 262, 135, -1, 259, 135, 131, -1, 259, 263, 135, -1, 95, 260, 224, -1, 132, 260, 95, -1, 212, 84, 90, -1, 218, 212, 90, -1, 217, 90, 89, -1, 217, 218, 90, -1, 216, 89, 88, -1, 216, 217, 89, -1, 219, 88, 91, -1, 219, 216, 88, -1, 221, 93, 94, -1, 221, 91, 93, -1, 221, 219, 91, -1, 222, 221, 94, -1, 224, 94, 95, -1, 224, 222, 94, -1, 72, 212, 194, -1, 84, 212, 72, -1, 203, 70, 69, -1, 202, 203, 69, -1, 201, 69, 68, -1, 201, 202, 69, -1, 199, 68, 67, -1, 199, 201, 68, -1, 198, 67, 75, -1, 198, 199, 67, -1, 197, 74, 73, -1, 197, 75, 74, -1, 197, 198, 75, -1, 196, 197, 73, -1, 194, 73, 72, -1, 194, 196, 73, -1, 322, 42, 323, -1, 323, 42, 44, -1, 27, 54, 203, -1, 203, 19, 21, -1, 52, 54, 27, -1, 324, 40, 322, -1, 21, 23, 203, -1, 203, 17, 19, -1, 322, 40, 42, -1, 23, 25, 203, -1, 325, 38, 324, -1, 326, 38, 325, -1, 268, 15, 203, -1, 324, 38, 40, -1, 203, 15, 17, -1, 25, 27, 203, -1, 268, 13, 15, -1, 326, 36, 38, -1, 268, 11, 13, -1, 327, 35, 326, -1, 326, 35, 36, -1, 268, 9, 11, -1, 268, 7, 9, -1, 268, 5, 7, -1, 268, 3, 5, -1, 268, 2, 3, -1, 328, 70, 54, -1, 329, 70, 328, -1, 330, 70, 329, -1, 54, 70, 203, -1, 331, 70, 330, -1, 332, 70, 331, -1, 333, 70, 332, -1, 334, 70, 333, -1, 335, 140, 334, -1, 336, 140, 335, -1, 337, 140, 336, -1, 338, 140, 337, -1, 339, 140, 338, -1, 30, 140, 339, -1, 340, 46, 48, -1, 334, 140, 70, -1, 341, 46, 340, -1, 268, 140, 30, -1, 268, 30, 31, -1, 268, 31, 33, -1, 268, 33, 35, -1, 268, 35, 2, -1, 2, 35, 342, -1, 342, 35, 343, -1, 343, 35, 327, -1, 48, 50, 340, -1, 344, 50, 345, -1, 340, 50, 344, -1, 323, 44, 341, -1, 341, 44, 46, -1, 345, 52, 27, -1, 50, 52, 345, -1, 294, 165, 164, -1, 292, 294, 164, -1, 291, 164, 163, -1, 291, 292, 164, -1, 284, 163, 156, -1, 284, 291, 163, -1, 277, 156, 149, -1, 277, 284, 156, -1, 276, 148, 147, -1, 276, 149, 148, -1, 276, 277, 149, -1, 275, 276, 147, -1, 268, 147, 140, -1, 268, 275, 147, -1, 312, 178, 294, -1, 294, 178, 165, -1, 307, 182, 189, -1, 316, 307, 189, -1, 319, 189, 191, -1, 319, 316, 189, -1, 321, 191, 193, -1, 321, 319, 191, -1, 320, 193, 192, -1, 320, 321, 193, -1, 318, 190, 188, -1, 318, 192, 190, -1, 318, 320, 192, -1, 317, 318, 188, -1, 312, 188, 178, -1, 312, 317, 188, -1, 182, 290, 162, -1, 182, 307, 290, -1, 278, 280, 152, -1, 278, 152, 151, -1, 279, 151, 150, -1, 279, 278, 151, -1, 289, 150, 161, -1, 289, 279, 150, -1, 288, 161, 160, -1, 288, 289, 161, -1, 287, 160, 159, -1, 287, 288, 160, -1, 286, 159, 158, -1, 286, 287, 159, -1, 290, 158, 162, -1, 290, 286, 158, -1, 281, 152, 280, -1, 154, 152, 281, -1, 283, 155, 281, -1, 155, 154, 281, -1, 282, 153, 283, -1, 283, 153, 155, -1, 297, 153, 282, -1, 297, 169, 153, -1, 271, 144, 297, -1, 144, 169, 297, -1, 254, 144, 271, -1, 126, 144, 254, -1, 47, 45, 346, -1, 347, 43, 348, -1, 45, 43, 347, -1, 20, 18, 231, -1, 231, 22, 20, -1, 18, 16, 231, -1, 43, 41, 348, -1, 231, 24, 22, -1, 348, 39, 349, -1, 349, 39, 350, -1, 41, 39, 348, -1, 16, 14, 231, -1, 39, 37, 350, -1, 231, 12, 254, -1, 14, 12, 231, -1, 350, 34, 351, -1, 351, 34, 352, -1, 37, 34, 350, -1, 12, 10, 254, -1, 34, 32, 352, -1, 10, 8, 254, -1, 8, 6, 254, -1, 6, 4, 254, -1, 4, 1, 254, -1, 55, 102, 353, -1, 353, 102, 354, -1, 354, 102, 355, -1, 355, 102, 356, -1, 356, 102, 357, -1, 357, 102, 358, -1, 358, 126, 359, -1, 359, 126, 360, -1, 360, 126, 361, -1, 361, 126, 362, -1, 362, 126, 363, -1, 363, 126, 364, -1, 364, 126, 28, -1, 102, 126, 358, -1, 231, 102, 26, -1, 231, 26, 24, -1, 26, 102, 365, -1, 365, 102, 366, -1, 366, 102, 55, -1, 366, 55, 53, -1, 366, 53, 51, -1, 126, 254, 28, -1, 28, 254, 29, -1, 29, 254, 32, -1, 32, 254, 0, -1, 32, 0, 367, -1, 49, 47, 368, -1, 32, 367, 352, -1, 368, 47, 346, -1, 0, 254, 1, -1, 368, 51, 49, -1, 366, 51, 368, -1, 346, 45, 369, -1, 369, 45, 347, -1, 228, 102, 231, -1, 99, 102, 228, -1, 244, 99, 228, -1, 115, 99, 244, -1, 250, 121, 244, -1, 244, 121, 115, -1, 122, 250, 249, -1, 121, 250, 122, -1, 101, 227, 229, -1, 101, 100, 227, -1, 100, 240, 227, -1, 100, 112, 240, -1, 113, 241, 114, -1, 241, 242, 114, -1, 114, 248, 120, -1, 242, 248, 114, -1, 120, 247, 119, -1, 248, 247, 120, -1, 119, 246, 118, -1, 247, 246, 119, -1, 117, 245, 116, -1, 118, 245, 117, -1, 246, 245, 118, -1, 245, 243, 116, -1, 116, 240, 112, -1, 243, 240, 116, -1, 225, 113, 97, -1, 241, 113, 225, -1, 83, 211, 85, -1, 211, 213, 85, -1, 85, 214, 86, -1, 213, 214, 85, -1, 86, 215, 87, -1, 214, 215, 86, -1, 87, 220, 92, -1, 215, 220, 87, -1, 92, 226, 98, -1, 220, 226, 92, -1, 98, 223, 96, -1, 226, 223, 98, -1, 96, 225, 97, -1, 223, 225, 96, -1, 211, 83, 81, -1, 211, 81, 208, -1, 80, 209, 78, -1, 209, 206, 78, -1, 78, 204, 77, -1, 206, 204, 78, -1, 77, 200, 66, -1, 204, 200, 77, -1, 66, 195, 71, -1, 200, 195, 66, -1, 71, 205, 76, -1, 195, 205, 71, -1, 76, 207, 79, -1, 205, 207, 76, -1, 79, 208, 81, -1, 207, 208, 79, -1, 82, 210, 209, -1, 82, 209, 80, -1, 101, 229, 111, -1, 111, 239, 110, -1, 229, 239, 111, -1, 110, 238, 109, -1, 239, 238, 110, -1, 109, 237, 108, -1, 238, 237, 109, -1, 108, 236, 107, -1, 237, 236, 108, -1, 107, 235, 106, -1, 236, 235, 107, -1, 106, 234, 105, -1, 235, 234, 106, -1, 105, 233, 104, -1, 234, 233, 105, -1, 104, 232, 103, -1, 233, 232, 104, -1, 103, 230, 82, -1, 232, 230, 103, -1, 230, 210, 82, -1, 186, 310, 185, -1, 310, 309, 185, -1, 185, 306, 183, -1, 309, 306, 185, -1, 183, 308, 184, -1, 306, 308, 183, -1, 184, 315, 181, -1, 308, 315, 184, -1, 180, 314, 179, -1, 181, 314, 180, -1, 315, 314, 181, -1, 179, 313, 177, -1, 314, 313, 179, -1, 313, 305, 177, -1, 311, 186, 187, -1, 310, 186, 311, -1, 298, 299, 170, -1, 170, 299, 171, -1, 171, 300, 172, -1, 299, 300, 171, -1, 172, 301, 173, -1, 300, 301, 172, -1, 173, 302, 174, -1, 301, 302, 173, -1, 174, 303, 175, -1, 302, 303, 174, -1, 175, 304, 176, -1, 303, 304, 175, -1, 176, 311, 187, -1, 304, 311, 176, -1, 170, 272, 298, -1, 170, 143, 272, -1, 143, 64, 272, -1, 143, 65, 64, -1, 137, 265, 130, -1, 130, 258, 128, -1, 265, 258, 130, -1, 128, 256, 124, -1, 258, 256, 128, -1, 124, 253, 125, -1, 256, 253, 124, -1, 125, 252, 127, -1, 253, 252, 125, -1, 127, 255, 129, -1, 252, 255, 127, -1, 129, 257, 58, -1, 255, 257, 129, -1, 257, 56, 58, -1, 141, 269, 265, -1, 141, 265, 137, -1, 168, 296, 167, -1, 296, 295, 167, -1, 167, 293, 166, -1, 295, 293, 167, -1, 166, 285, 157, -1, 293, 285, 166, -1, 157, 274, 146, -1, 285, 274, 157, -1, 145, 273, 142, -1, 146, 273, 145, -1, 274, 273, 146, -1, 273, 270, 142, -1, 142, 269, 141, -1, 270, 269, 142, -1, 177, 305, 296, -1, 177, 296, 168, -1, 55, 353, 54, -1, 54, 353, 328, -1, 328, 354, 329, -1, 353, 354, 328, -1, 329, 355, 330, -1, 354, 355, 329, -1, 330, 356, 331, -1, 355, 356, 330, -1, 331, 357, 332, -1, 356, 357, 331, -1, 332, 358, 333, -1, 357, 358, 332, -1, 333, 359, 334, -1, 358, 359, 333, -1, 334, 360, 335, -1, 359, 360, 334, -1, 335, 361, 336, -1, 360, 361, 335, -1, 336, 362, 337, -1, 361, 362, 336, -1, 337, 363, 338, -1, 362, 363, 337, -1, 338, 364, 339, -1, 363, 364, 338, -1, 339, 28, 30, -1, 364, 28, 339, -1, 26, 365, 27, -1, 27, 365, 345, -1, 345, 365, 344, -1, 344, 366, 340, -1, 365, 366, 344, -1, 340, 368, 341, -1, 366, 368, 340, -1, 341, 346, 323, -1, 368, 346, 341, -1, 323, 369, 322, -1, 346, 369, 323, -1, 322, 347, 324, -1, 369, 347, 322, -1, 324, 348, 325, -1, 347, 348, 324, -1, 325, 349, 326, -1, 348, 349, 325, -1, 326, 350, 327, -1, 349, 350, 326, -1, 327, 351, 343, -1, 350, 351, 327, -1, 343, 352, 342, -1, 351, 352, 343, -1, 342, 367, 2, -1, 352, 367, 342, -1, 367, 0, 2, -1, 370, 371, 372, -1, 372, 371, 373, -1, 373, 374, 375, -1, 371, 374, 373, -1, 375, 376, 377, -1, 374, 376, 375, -1, 377, 378, 379, -1, 376, 378, 377, -1, 379, 380, 381, -1, 378, 380, 379, -1, 381, 382, 383, -1, 380, 382, 381, -1, 383, 384, 385, -1, 382, 384, 383, -1, 385, 386, 387, -1, 387, 386, 388, -1, 384, 386, 385, -1, 388, 389, 390, -1, 386, 389, 388, -1, 390, 391, 392, -1, 389, 391, 390, -1, 392, 393, 394, -1, 391, 393, 392, -1, 394, 395, 396, -1, 393, 395, 394, -1, 395, 397, 396, -1, 398, 399, 400, -1, 400, 399, 401, -1, 401, 402, 403, -1, 399, 402, 401, -1, 403, 404, 405, -1, 402, 404, 403, -1, 405, 406, 407, -1, 404, 406, 405, -1, 407, 408, 409, -1, 406, 408, 407, -1, 409, 410, 411, -1, 408, 410, 409, -1, 411, 412, 413, -1, 413, 412, 414, -1, 410, 412, 411, -1, 414, 415, 416, -1, 412, 415, 414, -1, 416, 417, 418, -1, 415, 417, 416, -1, 418, 419, 420, -1, 417, 419, 418, -1, 420, 421, 422, -1, 419, 421, 420, -1, 422, 423, 424, -1, 421, 423, 422, -1, 423, 425, 424, -1, 426, 427, 428, -1, 428, 427, 429, -1, 429, 430, 431, -1, 427, 430, 429, -1, 431, 432, 433, -1, 430, 432, 431, -1, 433, 434, 435, -1, 432, 434, 433, -1, 436, 437, 438, -1, 436, 438, 439, -1, 436, 439, 440, -1, 441, 442, 443, -1, 441, 443, 444, -1, 441, 444, 445, -1, 441, 445, 437, -1, 441, 437, 436, -1, 446, 442, 441, -1, 447, 436, 440, -1, 448, 447, 440, -1, 449, 442, 446, -1, 450, 442, 449, -1, 451, 448, 440, -1, 452, 451, 440, -1, 453, 454, 442, -1, 453, 442, 450, -1, 455, 454, 453, -1, 456, 454, 455, -1, 457, 454, 456, -1, 457, 458, 459, -1, 457, 459, 460, -1, 457, 460, 454, -1, 461, 458, 457, -1, 461, 457, 462, -1, 463, 461, 462, -1, 464, 463, 462, -1, 465, 464, 462, -1, 465, 466, 467, -1, 465, 468, 466, -1, 465, 462, 468, -1, 469, 470, 452, -1, 469, 471, 470, -1, 469, 472, 471, -1, 469, 473, 472, -1, 469, 474, 473, -1, 469, 475, 474, -1, 469, 476, 475, -1, 469, 452, 440, -1, 469, 477, 476, -1, 469, 478, 477, -1, 469, 479, 478, -1, 480, 481, 479, -1, 482, 465, 467, -1, 483, 481, 480, -1, 484, 465, 482, -1, 485, 483, 480, -1, 485, 465, 484, -1, 485, 486, 483, -1, 485, 487, 486, -1, 485, 488, 487, -1, 485, 489, 488, -1, 485, 490, 489, -1, 485, 484, 490, -1, 491, 492, 493, -1, 494, 495, 496, -1, 497, 496, 495, -1, 498, 494, 496, -1, 499, 496, 497, -1, 500, 498, 496, -1, 501, 465, 485, -1, 501, 485, 491, -1, 502, 501, 491, -1, 502, 491, 493, -1, 503, 502, 504, -1, 503, 501, 502, -1, 505, 500, 496, -1, 428, 496, 499, -1, 506, 507, 503, -1, 508, 504, 509, -1, 508, 503, 504, -1, 508, 506, 503, -1, 429, 496, 428, -1, 431, 496, 429, -1, 433, 496, 431, -1, 435, 496, 433, -1, 510, 496, 469, -1, 510, 505, 496, -1, 510, 469, 440, -1, 511, 505, 510, -1, 512, 511, 510, -1, 513, 514, 435, -1, 515, 512, 510, -1, 516, 515, 510, -1, 516, 510, 517, -1, 516, 517, 518, -1, 516, 518, 519, -1, 520, 521, 522, -1, 523, 524, 525, -1, 523, 525, 526, -1, 527, 528, 516, -1, 527, 516, 519, -1, 529, 530, 520, -1, 531, 520, 522, -1, 531, 529, 520, -1, 531, 524, 523, -1, 531, 532, 529, -1, 531, 522, 524, -1, 533, 528, 527, -1, 534, 528, 533, -1, 535, 536, 528, -1, 535, 537, 536, -1, 535, 538, 537, -1, 535, 528, 534, -1, 539, 531, 523, -1, 540, 514, 513, -1, 540, 539, 514, -1, 541, 539, 540, -1, 542, 539, 541, -1, 543, 539, 542, -1, 544, 539, 543, -1, 545, 539, 544, -1, 546, 539, 545, -1, 547, 538, 535, -1, 548, 549, 550, -1, 548, 551, 549, -1, 548, 552, 551, -1, 548, 546, 553, -1, 548, 539, 546, -1, 548, 531, 539, -1, 548, 553, 552, -1, 554, 547, 535, -1, 554, 555, 547, -1, 554, 556, 555, -1, 554, 557, 556, -1, 558, 557, 554, -1, 559, 548, 550, -1, 560, 557, 558, -1, 561, 559, 550, -1, 562, 550, 557, -1, 562, 557, 560, -1, 563, 561, 550, -1, 563, 550, 562, -1, 514, 496, 435, -1, 469, 480, 479, -1, 564, 565, 566, -1, 566, 565, 567, -1, 567, 565, 568, -1, 564, 569, 565, -1, 570, 569, 571, -1, 571, 569, 572, -1, 572, 569, 573, -1, 573, 569, 564, -1, 565, 574, 568, -1, 570, 575, 569, -1, 574, 576, 568, -1, 570, 577, 575, -1, 576, 578, 568, -1, 570, 579, 577, -1, 578, 580, 568, -1, 570, 581, 579, -1, 582, 581, 570, -1, 582, 583, 581, -1, 582, 584, 583, -1, 582, 585, 584, -1, 586, 585, 587, -1, 587, 585, 588, -1, 588, 585, 582, -1, 586, 589, 585, -1, 585, 589, 590, -1, 589, 591, 590, -1, 591, 592, 590, -1, 593, 594, 595, -1, 596, 594, 593, -1, 590, 594, 596, -1, 592, 594, 590, -1, 597, 598, 580, -1, 599, 598, 597, -1, 600, 598, 599, -1, 601, 598, 600, -1, 602, 598, 601, -1, 603, 598, 602, -1, 604, 598, 603, -1, 605, 598, 604, -1, 606, 598, 605, -1, 607, 598, 606, -1, 580, 598, 568, -1, 608, 609, 607, -1, 608, 610, 609, -1, 594, 611, 595, -1, 594, 612, 611, -1, 613, 614, 610, -1, 615, 614, 613, -1, 616, 614, 615, -1, 617, 614, 616, -1, 618, 614, 617, -1, 612, 614, 618, -1, 610, 614, 609, -1, 594, 614, 612, -1, 598, 619, 568, -1, 620, 621, 622, -1, 623, 624, 619, -1, 619, 625, 623, -1, 624, 626, 619, -1, 619, 627, 625, -1, 626, 628, 619, -1, 614, 629, 621, -1, 594, 629, 614, -1, 629, 630, 621, -1, 621, 630, 622, -1, 629, 631, 630, -1, 629, 632, 631, -1, 619, 426, 627, -1, 628, 633, 619, -1, 631, 634, 635, -1, 632, 636, 631, -1, 631, 636, 634, -1, 637, 636, 632, -1, 619, 427, 426, -1, 619, 430, 427, -1, 619, 432, 430, -1, 619, 434, 432, -1, 633, 638, 619, -1, 619, 638, 568, -1, 633, 639, 638, -1, 639, 640, 638, -1, 641, 642, 434, -1, 640, 643, 638, -1, 643, 644, 638, -1, 638, 644, 645, -1, 645, 644, 646, -1, 646, 644, 647, -1, 648, 649, 650, -1, 651, 652, 653, -1, 650, 652, 651, -1, 644, 654, 647, -1, 655, 654, 644, -1, 649, 656, 650, -1, 657, 656, 658, -1, 658, 656, 659, -1, 659, 656, 660, -1, 660, 656, 649, -1, 650, 656, 652, -1, 655, 661, 654, -1, 655, 662, 661, -1, 655, 663, 662, -1, 664, 663, 655, -1, 665, 663, 664, -1, 666, 663, 665, -1, 656, 667, 652, -1, 667, 668, 641, -1, 641, 668, 642, -1, 667, 669, 668, -1, 667, 670, 669, -1, 667, 671, 670, -1, 667, 672, 671, -1, 667, 673, 672, -1, 667, 674, 673, -1, 666, 675, 663, -1, 676, 677, 678, -1, 679, 677, 676, -1, 680, 677, 679, -1, 681, 677, 680, -1, 674, 677, 681, -1, 667, 677, 674, -1, 656, 677, 667, -1, 675, 682, 663, -1, 683, 682, 675, -1, 684, 682, 683, -1, 685, 682, 684, -1, 677, 686, 678, -1, 685, 687, 682, -1, 685, 688, 687, -1, 686, 689, 678, -1, 685, 690, 688, -1, 685, 691, 690, -1, 689, 691, 678, -1, 678, 691, 685, -1, 609, 598, 607, -1, 619, 641, 434, -1, 622, 493, 620, -1, 620, 493, 492, -1, 630, 502, 622, -1, 622, 502, 493, -1, 632, 629, 501, -1, 632, 501, 503, -1, 637, 503, 507, -1, 637, 632, 503, -1, 636, 507, 506, -1, 636, 637, 507, -1, 634, 506, 508, -1, 634, 636, 506, -1, 635, 508, 509, -1, 635, 634, 508, -1, 631, 509, 504, -1, 631, 635, 509, -1, 630, 504, 502, -1, 630, 631, 504, -1, 465, 629, 594, -1, 501, 629, 465, -1, 588, 582, 454, -1, 588, 454, 460, -1, 587, 460, 459, -1, 587, 588, 460, -1, 586, 459, 458, -1, 586, 587, 459, -1, 589, 458, 461, -1, 589, 586, 458, -1, 591, 461, 463, -1, 591, 589, 461, -1, 592, 463, 464, -1, 592, 591, 463, -1, 594, 464, 465, -1, 594, 592, 464, -1, 454, 570, 442, -1, 454, 582, 570, -1, 568, 440, 439, -1, 567, 439, 438, -1, 567, 568, 439, -1, 566, 567, 438, -1, 564, 438, 437, -1, 564, 566, 438, -1, 573, 437, 445, -1, 573, 564, 437, -1, 572, 444, 443, -1, 572, 445, 444, -1, 572, 573, 445, -1, 571, 572, 443, -1, 570, 443, 442, -1, 570, 571, 443, -1, 420, 422, 692, -1, 693, 413, 694, -1, 694, 413, 414, -1, 695, 424, 396, -1, 422, 424, 695, -1, 568, 388, 390, -1, 390, 392, 568, -1, 396, 424, 568, -1, 696, 411, 693, -1, 568, 387, 388, -1, 693, 411, 413, -1, 392, 394, 568, -1, 697, 409, 696, -1, 568, 385, 387, -1, 696, 409, 411, -1, 394, 396, 568, -1, 638, 383, 568, -1, 698, 407, 697, -1, 699, 407, 698, -1, 568, 383, 385, -1, 697, 407, 409, -1, 638, 381, 383, -1, 699, 405, 407, -1, 638, 379, 381, -1, 638, 377, 379, -1, 638, 375, 377, -1, 638, 373, 375, -1, 638, 372, 373, -1, 700, 440, 424, -1, 701, 440, 700, -1, 702, 440, 701, -1, 703, 440, 702, -1, 424, 440, 568, -1, 704, 440, 703, -1, 705, 440, 704, -1, 706, 440, 705, -1, 707, 510, 706, -1, 708, 510, 707, -1, 709, 510, 708, -1, 710, 510, 709, -1, 711, 510, 710, -1, 400, 510, 711, -1, 706, 510, 440, -1, 638, 510, 372, -1, 372, 510, 712, -1, 712, 510, 713, -1, 713, 510, 699, -1, 699, 510, 400, -1, 699, 400, 401, -1, 699, 401, 403, -1, 699, 403, 405, -1, 714, 416, 715, -1, 715, 416, 418, -1, 715, 420, 692, -1, 418, 420, 715, -1, 694, 414, 714, -1, 714, 414, 416, -1, 692, 422, 695, -1, 663, 535, 534, -1, 662, 663, 534, -1, 661, 534, 533, -1, 661, 662, 534, -1, 654, 533, 527, -1, 654, 661, 533, -1, 647, 527, 519, -1, 647, 654, 527, -1, 646, 518, 517, -1, 646, 519, 518, -1, 646, 647, 519, -1, 645, 646, 517, -1, 638, 517, 510, -1, 638, 645, 517, -1, 682, 554, 663, -1, 663, 554, 535, -1, 686, 677, 548, -1, 686, 548, 559, -1, 689, 559, 561, -1, 689, 686, 559, -1, 691, 561, 563, -1, 691, 689, 561, -1, 690, 563, 562, -1, 690, 691, 563, -1, 688, 562, 560, -1, 688, 690, 562, -1, 687, 560, 558, -1, 687, 688, 560, -1, 682, 558, 554, -1, 682, 687, 558, -1, 531, 677, 656, -1, 548, 677, 531, -1, 648, 650, 524, -1, 648, 524, 522, -1, 649, 522, 521, -1, 649, 648, 522, -1, 660, 521, 520, -1, 660, 649, 521, -1, 659, 520, 530, -1, 659, 660, 520, -1, 658, 530, 529, -1, 658, 659, 530, -1, 657, 529, 532, -1, 657, 658, 529, -1, 656, 532, 531, -1, 656, 657, 532, -1, 651, 524, 650, -1, 525, 524, 651, -1, 653, 525, 651, -1, 526, 525, 653, -1, 652, 523, 653, -1, 653, 523, 526, -1, 667, 539, 652, -1, 652, 539, 523, -1, 641, 539, 667, -1, 514, 539, 641, -1, 619, 514, 641, -1, 496, 514, 619, -1, 716, 421, 717, -1, 496, 619, 370, -1, 496, 370, 718, -1, 719, 421, 419, -1, 496, 718, 720, -1, 721, 415, 722, -1, 496, 720, 398, -1, 370, 619, 371, -1, 398, 720, 399, -1, 399, 720, 402, -1, 417, 415, 721, -1, 391, 389, 598, -1, 722, 412, 723, -1, 598, 393, 391, -1, 389, 386, 598, -1, 415, 412, 722, -1, 598, 395, 393, -1, 723, 410, 724, -1, 386, 384, 598, -1, 412, 410, 723, -1, 598, 382, 619, -1, 724, 408, 725, -1, 384, 382, 598, -1, 410, 408, 724, -1, 382, 380, 619, -1, 725, 406, 726, -1, 408, 406, 725, -1, 380, 378, 619, -1, 406, 404, 726, -1, 726, 404, 727, -1, 378, 376, 619, -1, 727, 402, 720, -1, 404, 402, 727, -1, 376, 374, 619, -1, 374, 371, 619, -1, 425, 469, 728, -1, 728, 469, 729, -1, 729, 469, 730, -1, 730, 469, 731, -1, 731, 469, 732, -1, 732, 469, 733, -1, 733, 469, 734, -1, 719, 419, 721, -1, 734, 496, 735, -1, 735, 496, 736, -1, 736, 496, 737, -1, 419, 417, 721, -1, 737, 496, 738, -1, 738, 496, 739, -1, 739, 496, 398, -1, 469, 496, 734, -1, 598, 469, 425, -1, 598, 425, 423, -1, 598, 423, 421, -1, 598, 421, 397, -1, 717, 421, 719, -1, 598, 397, 395, -1, 397, 421, 716, -1, 609, 480, 598, -1, 480, 469, 598, -1, 614, 480, 609, -1, 485, 480, 614, -1, 621, 491, 614, -1, 614, 491, 485, -1, 492, 621, 620, -1, 491, 621, 492, -1, 481, 608, 607, -1, 479, 481, 607, -1, 481, 610, 608, -1, 481, 483, 610, -1, 611, 612, 482, -1, 482, 612, 484, -1, 484, 618, 490, -1, 612, 618, 484, -1, 490, 617, 489, -1, 618, 617, 490, -1, 489, 616, 488, -1, 617, 616, 489, -1, 488, 615, 487, -1, 616, 615, 488, -1, 487, 613, 486, -1, 615, 613, 487, -1, 486, 610, 483, -1, 613, 610, 486, -1, 595, 482, 467, -1, 611, 482, 595, -1, 581, 583, 453, -1, 453, 583, 455, -1, 455, 584, 456, -1, 583, 584, 455, -1, 456, 585, 457, -1, 584, 585, 456, -1, 457, 590, 462, -1, 585, 590, 457, -1, 462, 596, 468, -1, 590, 596, 462, -1, 468, 593, 466, -1, 596, 593, 468, -1, 466, 595, 467, -1, 593, 595, 466, -1, 579, 453, 450, -1, 581, 453, 579, -1, 451, 578, 448, -1, 448, 576, 447, -1, 578, 576, 448, -1, 576, 574, 447, -1, 447, 565, 436, -1, 574, 565, 447, -1, 436, 569, 441, -1, 565, 569, 436, -1, 446, 575, 449, -1, 441, 575, 446, -1, 569, 575, 441, -1, 575, 577, 449, -1, 449, 579, 450, -1, 577, 579, 449, -1, 451, 580, 578, -1, 452, 580, 451, -1, 479, 607, 478, -1, 478, 606, 477, -1, 607, 606, 478, -1, 477, 605, 476, -1, 606, 605, 477, -1, 476, 604, 475, -1, 605, 604, 476, -1, 475, 603, 474, -1, 604, 603, 475, -1, 474, 602, 473, -1, 603, 602, 474, -1, 473, 601, 472, -1, 602, 601, 473, -1, 472, 600, 471, -1, 601, 600, 472, -1, 471, 599, 470, -1, 600, 599, 471, -1, 470, 597, 452, -1, 599, 597, 470, -1, 597, 580, 452, -1, 680, 679, 552, -1, 552, 679, 551, -1, 551, 676, 549, -1, 679, 676, 551, -1, 549, 678, 550, -1, 676, 678, 549, -1, 550, 685, 557, -1, 678, 685, 550, -1, 557, 684, 556, -1, 685, 684, 557, -1, 556, 683, 555, -1, 684, 683, 556, -1, 555, 675, 547, -1, 683, 675, 555, -1, 681, 552, 553, -1, 680, 552, 681, -1, 668, 669, 540, -1, 540, 669, 541, -1, 541, 670, 542, -1, 669, 670, 541, -1, 542, 671, 543, -1, 670, 671, 542, -1, 543, 672, 544, -1, 671, 672, 543, -1, 544, 673, 545, -1, 672, 673, 544, -1, 545, 674, 546, -1, 673, 674, 545, -1, 546, 681, 553, -1, 674, 681, 546, -1, 540, 642, 668, -1, 540, 513, 642, -1, 513, 434, 642, -1, 513, 435, 434, -1, 505, 633, 500, -1, 633, 628, 500, -1, 500, 626, 498, -1, 628, 626, 500, -1, 498, 624, 494, -1, 626, 624, 498, -1, 494, 623, 495, -1, 624, 623, 494, -1, 497, 625, 499, -1, 495, 625, 497, -1, 623, 625, 495, -1, 625, 627, 499, -1, 499, 426, 428, -1, 627, 426, 499, -1, 511, 639, 633, -1, 511, 633, 505, -1, 538, 666, 537, -1, 537, 665, 536, -1, 666, 665, 537, -1, 536, 664, 528, -1, 665, 664, 536, -1, 528, 655, 516, -1, 664, 655, 528, -1, 516, 644, 515, -1, 655, 644, 516, -1, 515, 643, 512, -1, 644, 643, 515, -1, 512, 640, 511, -1, 643, 640, 512, -1, 640, 639, 511, -1, 547, 675, 666, -1, 547, 666, 538, -1, 425, 728, 424, -1, 424, 728, 700, -1, 700, 729, 701, -1, 728, 729, 700, -1, 701, 730, 702, -1, 729, 730, 701, -1, 702, 731, 703, -1, 730, 731, 702, -1, 703, 732, 704, -1, 731, 732, 703, -1, 704, 733, 705, -1, 732, 733, 704, -1, 705, 734, 706, -1, 733, 734, 705, -1, 706, 735, 707, -1, 734, 735, 706, -1, 707, 736, 708, -1, 735, 736, 707, -1, 708, 737, 709, -1, 736, 737, 708, -1, 709, 738, 710, -1, 737, 738, 709, -1, 710, 739, 711, -1, 738, 739, 710, -1, 711, 398, 400, -1, 739, 398, 711, -1, 397, 716, 396, -1, 396, 716, 695, -1, 695, 717, 692, -1, 716, 717, 695, -1, 692, 719, 715, -1, 717, 719, 692, -1, 715, 721, 714, -1, 719, 721, 715, -1, 714, 722, 694, -1, 721, 722, 714, -1, 694, 723, 693, -1, 722, 723, 694, -1, 693, 724, 696, -1, 723, 724, 693, -1, 696, 725, 697, -1, 724, 725, 696, -1, 697, 726, 698, -1, 725, 726, 697, -1, 698, 727, 699, -1, 726, 727, 698, -1, 699, 720, 713, -1, 727, 720, 699, -1, 713, 718, 712, -1, 720, 718, 713, -1, 712, 370, 372, -1, 718, 370, 712, -1 - ] - } - castShadows FALSE - } - DEF mounting_rail_ends Shape { - appearance Appearance { - material Material { - diffuseColor 0 0 0 - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.42425939 0.16044985 -0.13339084, -0.42847395 0.15544991 -0.13339108, -0.42845494 0.15544991 -0.13339141, -0.42847395 0.16962059 -0.13339037, -0.42200077 0.16044989 -0.13339084, -0.42200091 0.1749565 -0.13339037, -0.42539352 0.17495647 -0.13339007, -0.42539346 0.17495552 -0.11638995, -0.42200083 0.17495549 -0.11639001, -0.42000079 0.16044794 -0.097390734, -0.42000091 0.17495453 -0.097390197, -0.40400073 0.17495443 -0.097390197, -0.40400076 0.16044804 -0.097390912, -0.40400094 0.17495495 -0.10364001, -0.42000097 0.17495482 -0.10364001, -0.40400088 0.16782698 -0.10364043, -0.42000082 0.16782686 -0.10364052, -0.39250088 0.17289826 -0.10159015, -0.40050083 0.1728981 -0.098940067, -0.40050086 0.17289826 -0.10159024, -0.39250085 0.17289814 -0.098940216, -0.40050077 0.16399828 -0.10159077, -0.39250082 0.16399838 -0.10159063, -0.40050068 0.16399808 -0.098940812, -0.39250067 0.16399819 -0.098940603, -0.39250091 0.1729001 -0.13184008, -0.40050071 0.16399992 -0.13184074, -0.39250094 0.16400012 -0.13184074, -0.40050095 0.17289996 -0.13184014, -0.4005008 0.16399986 -0.12919089, -0.39250094 0.16399996 -0.12919071, -0.40050083 0.17289978 -0.12919033, -0.39250088 0.17289992 -0.12919021, -0.4040007 0.16449824 -0.10109072, -0.40400082 0.16044869 -0.11101966, -0.40400085 0.16449815 -0.099440746, -0.4040007 0.17239818 -0.10109019, -0.40400082 0.17239819 -0.09944015, -0.40250081 0.16138618 -0.13506201, -0.40250081 0.16166089 -0.13515845, -0.40250102 0.16113967 -0.13490716, -0.40250081 0.16093382 -0.13470146, -0.40250093 0.16068274 -0.13418022, -0.40250081 0.1607789 -0.13445491, -0.40250096 0.16195013 -0.13519078, -0.40250081 0.16065004 -0.13389072, -0.40250084 0.16353139 -0.13269407, -0.40250093 0.16314644 -0.13230923, -0.40250093 0.16308427 -0.13223356, -0.40250081 0.16360715 -0.13275635, -0.40250093 0.16303807 -0.13214722, -0.40250081 0.16369359 -0.13280252, -0.40250081 0.16300963 -0.13205335, -0.40250084 0.16378748 -0.13283101, -0.40250075 0.1629999 -0.13195589, -0.40250099 0.16388501 -0.13284054, -0.40250081 0.1629997 -0.12869084, -0.40250084 0.16301233 -0.12857941, -0.4025009 0.17495666 -0.13518983, -0.40250099 0.1730151 -0.1328401, -0.40250099 0.17311271 -0.13283047, -0.40250087 0.17320642 -0.13280198, -0.40250087 0.17329292 -0.13275591, -0.40250099 0.17336871 -0.1326938, -0.4025009 0.17552079 -0.13506141, -0.4025009 0.17576729 -0.13490632, -0.40250093 0.17524603 -0.1351575, -0.4025009 0.17597316 -0.13470057, -0.4025009 0.17375354 -0.13230875, -0.40250087 0.17622404 -0.13417917, -0.40250102 0.176128 -0.13445395, -0.40250093 0.17625663 -0.13389018, -0.4025009 0.17381576 -0.13223305, -0.4025009 0.17386191 -0.13214648, -0.40250099 0.17389037 -0.13205266, -0.40250111 0.17390007 -0.13195503, -0.40250093 0.1634998 -0.12819076, -0.4025009 0.16260073 -0.12007495, -0.4025009 0.16338858 -0.12820327, -0.40250093 0.16328286 -0.12824032, -0.40250093 0.16318803 -0.12829983, -0.40250084 0.16310892 -0.12837893, -0.40250081 0.16304934 -0.12847379, -0.40250087 0.16801532 -0.12548909, -0.40250099 0.16819721 -0.12563813, -0.40250093 0.16245165 -0.11989319, -0.40250099 0.16840462 -0.12574914, -0.40250081 0.1623407 -0.11968573, -0.40250099 0.16862972 -0.12581754, -0.4025009 0.16227232 -0.11946066, -0.40250084 0.1622493 -0.11922642, -0.40250105 0.17389986 -0.12907505, -0.40250093 0.17625624 -0.12663996, -0.40250087 0.17389019 -0.12897754, -0.4025009 0.17386173 -0.12888363, -0.40250087 0.17381559 -0.12879717, -0.40250087 0.17375343 -0.12872151, -0.4025009 0.17336832 -0.12833646, -0.40250093 0.17545626 -0.12583995, -0.40250099 0.17329268 -0.12827435, -0.40250087 0.17320618 -0.12822807, -0.40250087 0.17311236 -0.1281997, -0.40250099 0.17301483 -0.12819025, -0.40250096 0.16886383 -0.1258404, -0.40250087 0.17563418 -0.1258601, -0.40250087 0.17623618 -0.12646198, -0.40250099 0.17617711 -0.12629285, -0.40250099 0.17580333 -0.1259191, -0.40250093 0.17608172 -0.12614107, -0.40250087 0.175955 -0.12601444, -0.40250084 0.16224879 -0.11155485, -0.40250081 0.16260026 -0.11070647, -0.4025009 0.16318661 -0.10248157, -0.40250093 0.16310744 -0.10240241, -0.40250093 0.162451 -0.11088824, -0.4025009 0.16304782 -0.10230755, -0.40250081 0.16234009 -0.11109554, -0.40250093 0.16328153 -0.1025412, -0.4025009 0.16301087 -0.10220193, -0.4025009 0.16338703 -0.10257816, -0.40250093 0.16349831 -0.10259052, -0.40250096 0.1680142 -0.10529193, -0.40250087 0.16819604 -0.10514256, -0.40250081 0.16840345 -0.10503181, -0.40250087 0.16862848 -0.1049635, -0.40250084 0.16227189 -0.11132085, -0.40250075 0.16064794 -0.096890859, -0.40250084 0.16299832 -0.1020908, -0.40250093 0.16299811 -0.098825656, -0.40250093 0.16300774 -0.098728143, -0.40250084 0.16303626 -0.098634325, -0.40250084 0.16308248 -0.098547958, -0.40250081 0.16314468 -0.09847226, -0.40250075 0.16068061 -0.096601449, -0.4025009 0.16093154 -0.096080445, -0.40250087 0.16077675 -0.096326731, -0.40250081 0.16113727 -0.095874362, -0.40250084 0.16352946 -0.098087035, -0.40250081 0.16165872 -0.095623456, -0.40250081 0.16138393 -0.09571927, -0.40250081 0.16194786 -0.095590852, -0.40250096 0.16388296 -0.097940557, -0.40250084 0.16378546 -0.097950123, -0.40250081 0.16369158 -0.097978674, -0.40250081 0.16360511 -0.098024838, -0.40250087 0.16886261 -0.10494041, -0.40250099 0.17545505 -0.1049399, -0.40250087 0.1730133 -0.10259005, -0.40250099 0.17311093 -0.10258042, -0.40250099 0.17320476 -0.10255214, -0.40250084 0.1732911 -0.10250591, -0.40250099 0.17336692 -0.10244354, -0.40250081 0.17375177 -0.10205864, -0.40250099 0.17563307 -0.10491975, -0.40250102 0.17625499 -0.10413992, -0.40250099 0.17580217 -0.10486075, -0.40250087 0.17595381 -0.10476526, -0.40250087 0.17608041 -0.10463869, -0.4025009 0.17617582 -0.10448705, -0.40250093 0.17623496 -0.10431807, -0.40250087 0.17381407 -0.10198288, -0.40250099 0.17386021 -0.10189649, -0.40250099 0.1738887 -0.10180282, -0.40250093 0.17389834 -0.10170516, -0.40250102 0.17301315 -0.09794011, -0.40250099 0.17389823 -0.098824911, -0.40250099 0.17625463 -0.096890084, -0.40250087 0.17388855 -0.098727338, -0.40250093 0.17386007 -0.098633729, -0.40250093 0.17381388 -0.098547153, -0.40250087 0.1737517 -0.098471455, -0.40250099 0.17495443 -0.095590048, -0.40250099 0.17336671 -0.098086618, -0.40250087 0.17329094 -0.098024331, -0.40250087 0.1732045 -0.097978167, -0.40250087 0.17311077 -0.097949646, -0.4025009 0.17524381 -0.095622562, -0.40250087 0.17622203 -0.096600823, -0.40250093 0.17612585 -0.096325777, -0.40250102 0.17576501 -0.095873527, -0.40250081 0.17597088 -0.096079491, -0.40250087 0.17551857 -0.095718674, -0.43336761 0.16114286 -0.097390823, -0.43047404 0.16615449 -0.097390465, -0.43047398 0.15824944 -0.097391121, -0.42847395 0.16961859 -0.097390436, -0.42539337 0.17495441 -0.097390078, -0.42200089 0.17495444 -0.097390197, -0.42200091 0.16044791 -0.097390912, -0.42425957 0.16044798 -0.097391061, -0.42847389 0.15544783 -0.0973913, -0.42845494 0.15544789 -0.0973913, -0.40400094 0.17495665 -0.13339022, -0.42000091 0.17495643 -0.13339022, -0.42000088 0.16044991 -0.13339102, -0.40400088 0.16045001 -0.13339084, -0.43200064 0.15977718 -0.11439099, -0.43200082 0.15977678 -0.10676967, -0.42850077 0.15627722 -0.11439111, -0.4333674 0.16114327 -0.10540279, -0.43047392 0.15824963 -0.1001003, -0.42850077 0.15627635 -0.1001003, -0.43336749 0.16114482 -0.13339102, -0.43047401 0.15825126 -0.13068172, -0.43047401 0.15825155 -0.13339102, -0.43336758 0.16114445 -0.12537885, -0.43200088 0.15977782 -0.12401222, -0.42850077 0.15627824 -0.13068172, -0.43200076 0.15977727 -0.11639076, -0.42850074 0.15627734 -0.11639103, -0.43200067 0.16351092 -0.11439057, -0.42539346 0.17495538 -0.11439016, -0.43200088 0.16351056 -0.10676932, -0.43047404 0.16615461 -0.10009991, -0.42847419 0.16961877 -0.1000995, -0.43047404 0.16615634 -0.13068119, -0.4304741 0.16615656 -0.13339061, -0.43200088 0.16351157 -0.12401208, -0.42847401 0.16962053 -0.13068113, -0.43200082 0.16351111 -0.11639079, -0.42200089 0.17495546 -0.1143901, -0.40400085 0.17495623 -0.12714016, -0.42000097 0.17495613 -0.12714016, -0.42200091 0.16044892 -0.11439099, -0.42200083 0.16044867 -0.1110196, -0.42200089 0.16667484 -0.10479256, -0.42200083 0.16689362 -0.10451504, -0.42200071 0.16704127 -0.1041938, -0.42200089 0.16710971 -0.10384702, -0.42200089 0.16709504 -0.10349392, -0.42200094 0.16699822 -0.10315385, -0.42200071 0.16682455 -0.10284602, -0.42200071 0.16658354 -0.10258733, -0.42200077 0.16658495 -0.12819371, -0.42200089 0.16682598 -0.12793505, -0.42200083 0.16699965 -0.12762713, -0.42200083 0.16709639 -0.12728718, -0.42200083 0.16711105 -0.12693402, -0.42200083 0.16704266 -0.12658703, -0.42200091 0.16044925 -0.11976223, -0.42200077 0.16044901 -0.11639085, -0.42200094 0.16689481 -0.12626597, -0.42200083 0.16667615 -0.12598833, -0.43358278 0.15853123 -0.12361919, -0.43367985 0.15862823 -0.12376591, -0.43058878 0.15553786 -0.13389105, -0.43379366 0.15874228 -0.12389597, -0.43348861 0.15843697 -0.12341379, -0.43343163 0.15838008 -0.12319653, -0.43533811 0.16028653 -0.12582386, -0.43533802 0.16028708 -0.13389102, -0.43341291 0.15836138 -0.12297674, -0.43513945 0.160088 -0.12524152, -0.43528271 0.16023137 -0.12548062, -0.43532291 0.16027141 -0.12563753, -0.43533427 0.16028284 -0.1257304, -0.43521976 0.16016828 -0.12534568, -0.43522719 0.16017468 -0.10542356, -0.43518561 0.16013296 -0.10548686, -0.43513945 0.16008693 -0.10554, -0.43528301 0.16023035 -0.10530066, -0.43532291 0.16027047 -0.10514354, -0.43533817 0.16028544 -0.10495778, -0.43379366 0.15874131 -0.10688578, -0.43058854 0.15553555 -0.096891068, -0.43360579 0.15855321 -0.10712399, -0.43349567 0.15844317 -0.10734906, -0.43343407 0.15838167 -0.10757195, -0.43341815 0.1583658 -0.10768878, -0.43341291 0.15836056 -0.10780521, -0.43533802 0.16028494 -0.096890859, -0.43350089 0.16364449 -0.10780477, -0.43350089 0.16364537 -0.1229765, -0.43350077 0.15857346 -0.12297686, -0.43350089 0.15857267 -0.10780513, -0.43395272 0.16313085 -0.12439059, -0.43538576 0.16064927 -0.13389102, -0.43538576 0.16064866 -0.12582409, -0.43375111 0.16347992 -0.12415516, -0.42654806 0.1759565 -0.13389006, -0.43338037 0.1641221 -0.12320789, -0.43336689 0.16414544 -0.1229765, -0.43342131 0.16405095 -0.12344002, -0.43349016 0.16393185 -0.12366765, -0.43358591 0.16376638 -0.12388595, -0.43538576 0.16064709 -0.096890859, -0.43395269 0.16312979 -0.10639068, -0.43538582 0.16064754 -0.10495757, -0.43363643 0.16367769 -0.10680219, -0.4265483 0.17595455 -0.096890025, -0.43336678 0.16414459 -0.10780477, -0.43348905 0.16393295 -0.10711645, -0.43337741 0.16412637 -0.10759985, -0.40270084 0.17495443 -0.095390223, -0.42495891 0.1619477 -0.09539061, -0.40270081 0.1619478 -0.095391057, -0.42539346 0.17495437 -0.095390014, -0.43362635 0.16069445 -0.095390819, -0.42948508 0.15655337 -0.095391206, -0.42050096 0.16886266 -0.10514029, -0.40270087 0.17545512 -0.10514008, -0.40270084 0.16886267 -0.10514044, -0.42050079 0.1754549 -0.10514008, -0.40270093 0.16274163 -0.11084809, -0.4205007 0.16815546 -0.10543331, -0.40270072 0.16815566 -0.10543319, -0.42050067 0.16274133 -0.11084779, -0.40270078 0.16244921 -0.11922663, -0.42050079 0.16244909 -0.11922654, -0.40270093 0.16244896 -0.11155494, -0.42050093 0.16244882 -0.11155494, -0.4027009 0.16815665 -0.12534761, -0.42050081 0.16274203 -0.11993357, -0.40270093 0.16274223 -0.11993369, -0.42050081 0.16815652 -0.12534761, -0.4027009 0.1754562 -0.12564006, -0.4205007 0.16886362 -0.12564042, -0.40270084 0.16886377 -0.12564042, -0.42050087 0.17545608 -0.12564, -0.42150101 0.17645617 -0.12663993, -0.40270096 0.17645672 -0.13389018, -0.42568213 0.17645644 -0.13389006, -0.4027009 0.17645629 -0.12664008, -0.42568219 0.17645447 -0.096890025, -0.42150086 0.1764548 -0.10413992, -0.40270078 0.17645454 -0.096890084, -0.40270075 0.17645486 -0.10414004, -0.43362632 0.16069676 -0.13539073, -0.42495897 0.16195008 -0.13539073, -0.42948514 0.15655571 -0.13539127, -0.42539346 0.17495653 -0.13538998, -0.40270096 0.17495677 -0.13539022, -0.40270084 0.1619502 -0.13539103, -0.42050096 0.1683082 -0.12547195, -0.42050087 0.16848108 -0.12556434, -0.42050093 0.16261774 -0.11978214, -0.42050081 0.16246834 -0.11942156, -0.42050081 0.16252533 -0.11960932, -0.42050096 0.1686686 -0.1256212, -0.42050081 0.16252486 -0.1111721, -0.42050081 0.16246802 -0.11135974, -0.42050079 0.16261718 -0.11099934, -0.42050096 0.1684798 -0.10521661, -0.42050073 0.16830692 -0.105309, -0.42050081 0.16866751 -0.10515963, -0.43379369 0.16263083 -0.12368353, -0.43513945 0.16030011 -0.12502944, -0.43379372 0.15895432 -0.1236838, -0.43513942 0.16029902 -0.10575231, -0.43379369 0.1626299 -0.10709783, -0.43379378 0.1589534 -0.10709821, -0.42000091 0.16667493 -0.10479256, -0.40400076 0.16044921 -0.1197622, -0.40270084 0.16045016 -0.1338909, -0.42425939 0.16044988 -0.1338909, -0.40270066 0.16044798 -0.096890859, -0.42465162 0.16044885 -0.11439093, -0.42465156 0.16044889 -0.11639094, -0.42425939 0.16044787 -0.096890859, -0.42000091 0.16667606 -0.12598833, -0.42000085 0.16782825 -0.12714043, -0.40400076 0.16782832 -0.12714052, -0.4040007 0.16449976 -0.12969071, -0.40400088 0.16449989 -0.13134077, -0.40400085 0.17239991 -0.13134038, -0.4040007 0.1723997 -0.12969032, -0.43016517 0.1554478 -0.096311264, -0.43037674 0.15544789 -0.096891068, -0.42845494 0.15544789 -0.096891217, -0.42995244 0.15544765 -0.096097611, -0.42848966 0.15544784 -0.096610002, -0.42859611 0.15544783 -0.096332215, -0.42962283 0.15544772 -0.095893674, -0.43037653 0.15544982 -0.13389117, -0.42850059 0.15544887 -0.11639114, -0.42850083 0.15544885 -0.11439132, -0.42934293 0.15545003 -0.13499549, -0.42915785 0.15544994 -0.13504249, -0.42884403 0.15545006 -0.13478866, -0.42952466 0.15545003 -0.1349315, -0.42976797 0.15544996 -0.1348117, -0.42862988 0.15544993 -0.13451093, -0.42845482 0.15544984 -0.13389125, -0.42998207 0.15544997 -0.1346603, -0.42850733 0.15544975 -0.13423637, -0.42846775 0.15544979 -0.13406339, -0.43015528 0.1554499 -0.13448349, -0.43028009 0.15544981 -0.13428989, -0.43035334 0.15544984 -0.13408926, -0.42850083 0.15544976 -0.13068199, -0.42847401 0.15544967 -0.13068199, -0.42850089 0.15544799 -0.10010048, -0.42847395 0.1554479 -0.10010048, -0.42877102 0.15544774 -0.096074097, -0.42895025 0.15544769 -0.095893912, -0.42915791 0.15544769 -0.095739983, -0.43029523 0.15544787 -0.096523933, -0.43035674 0.15544769 -0.096708946, -0.40270084 0.1683071 -0.105309, -0.4027009 0.16847998 -0.10521661, -0.40270084 0.16866755 -0.10515963, -0.40270066 0.162468 -0.11136007, -0.40270084 0.16252497 -0.1111721, -0.40270084 0.16261736 -0.11099949, -0.40270084 0.16261786 -0.11978229, -0.40270084 0.16252548 -0.1196092, -0.40270078 0.16246849 -0.11942177, -0.40270084 0.16866872 -0.12562117, -0.40270084 0.16848114 -0.12556434, -0.40270084 0.16830829 -0.12547183, -0.42050987 0.17558822 -0.10513099, -0.4027009 0.17567757 -0.1051149, -0.42053804 0.17572518 -0.10510301, -0.40270096 0.1758889 -0.10504102, -0.42060879 0.17590655 -0.10503205, -0.40270075 0.17607841 -0.10492178, -0.42072737 0.17608857 -0.10491353, -0.40270078 0.17623682 -0.10476359, -0.42092529 0.17627263 -0.10471543, -0.4027009 0.17635597 -0.10457393, -0.42117923 0.17640173 -0.10446187, -0.40270087 0.1764299 -0.10436248, -0.42117923 0.17640293 -0.12631848, -0.42092538 0.17627391 -0.12606451, -0.42072749 0.17608981 -0.12586632, -0.42060882 0.17590773 -0.12574801, -0.42053807 0.17572638 -0.1256772, -0.42050999 0.17558946 -0.12564895, -0.40270096 0.17643124 -0.12641752, -0.40270084 0.17635721 -0.12620619, -0.4027009 0.17623813 -0.12601647, -0.40270102 0.17607975 -0.12585828, -0.40270096 0.17589012 -0.12573907, -0.4027009 0.17567874 -0.12566507, -0.43364918 0.15876625 -0.12350079, -0.43363559 0.16317868 -0.1234779, -0.43356431 0.15865614 -0.12332793, -0.43355542 0.16345626 -0.12330245, -0.43352038 0.15859887 -0.12317347, -0.43352798 0.16355197 -0.12320706, -0.43351343 0.16360171 -0.12313481, -0.43350565 0.1585799 -0.12307485, -0.43350387 0.16363458 -0.12305542, -0.43350172 0.16364284 -0.12301566, -0.43537918 0.16060123 -0.12557364, -0.43398076 0.16303036 -0.12418862, -0.43396261 0.16290934 -0.12399697, -0.43533292 0.16052508 -0.12535998, -0.43526056 0.16043337 -0.12519166, -0.43389925 0.16277373 -0.12382575, -0.43520358 0.1603688 -0.12510395, -0.43348575 0.16381904 -0.1229765, -0.43343121 0.16401634 -0.12311339, -0.43344051 0.1639874 -0.1229765, -0.43344933 0.16398385 -0.12325119, -0.43347222 0.16389345 -0.12309345, -0.4334771 0.16393398 -0.12337848, -0.43348831 0.16386096 -0.12321087, -0.43349671 0.16376625 -0.12307393, -0.4335134 0.16381134 -0.12331899, -0.43351007 0.1637336 -0.12317201, -0.43354231 0.16381693 -0.12357517, -0.43353063 0.16368355 -0.12326216, -0.43357179 0.16369444 -0.12348612, -0.43357879 0.16356575 -0.1234016, -0.43368119 0.16356808 -0.12384196, -0.433696 0.16344595 -0.12371095, -0.43368086 0.16331513 -0.12358855, -0.43344045 0.16398658 -0.10780477, -0.43348575 0.1638183 -0.10780477, -0.43538821 0.16062881 -0.1050837, -0.43398079 0.16302942 -0.10659274, -0.43537891 0.16059977 -0.1052091, -0.43396276 0.16290835 -0.10678443, -0.43533266 0.1605237 -0.10542258, -0.43389916 0.16277273 -0.10695561, -0.4352504 0.16042042 -0.10560789, -0.43363559 0.16317779 -0.10730373, -0.43350166 0.16364187 -0.10776543, -0.43368119 0.16356711 -0.10693919, -0.43369588 0.16344501 -0.10707032, -0.43368077 0.16331422 -0.10719287, -0.43352902 0.16384007 -0.10724007, -0.43355989 0.16371743 -0.10732388, -0.43356884 0.16358884 -0.10740387, -0.43355542 0.16345541 -0.10747888, -0.43352798 0.16355112 -0.10757398, -0.43344933 0.16398288 -0.10753032, -0.43343115 0.16401529 -0.10766803, -0.43348834 0.16386017 -0.10757052, -0.4334721 0.16389255 -0.10768803, -0.43351001 0.16373262 -0.10760915, -0.4335134 0.16360077 -0.10764646, -0.43349674 0.16376545 -0.10770725, -0.43350381 0.16363378 -0.10772597, -0.43370855 0.15884279 -0.10719501, -0.4336355 0.15874785 -0.10730388, -0.43357694 0.15867172 -0.10742234, -0.4335345 0.15861647 -0.10754775, -0.43350911 0.15858348 -0.1076765, -0.42589012 0.17643265 -0.096890025, -0.42589015 0.17643467 -0.13389006, -0.42608905 0.17636807 -0.096889876, -0.42608884 0.17636998 -0.13389018, -0.42626998 0.17626338 -0.096890025, -0.42626989 0.17626546 -0.13388997, -0.4264254 0.17612356 -0.096890025, -0.42642534 0.1761256 -0.13389006, -0.42495856 0.16041712 -0.11439093, -0.42575264 0.15996747 -0.11439099, -0.42593783 0.15972066 -0.11439111, -0.4255209 0.16017115 -0.11439093, -0.42525232 0.16032323 -0.11439099, -0.42593783 0.1597207 -0.11639114, -0.42575258 0.15996757 -0.11639094, -0.4255209 0.16017132 -0.11639094, -0.42525226 0.16032329 -0.11639103, -0.42495841 0.1604172 -0.11639094, -0.43057525 0.1555393 -0.13406926, -0.43530461 0.16029508 -0.1341863, -0.43053335 0.15554379 -0.1342496, -0.43519688 0.16032088 -0.13448733, -0.43041205 0.15555739 -0.13452151, -0.43501106 0.16036536 -0.13477245, -0.43019891 0.15558107 -0.13479927, -0.43475395 0.16042697 -0.13501945, -0.4298923 0.15561529 -0.13504958, -0.43444312 0.16050133 -0.13520911, -0.42944622 0.15566482 -0.13526481, -0.43410364 0.1605825 -0.13533142, -0.42946541 0.15610054 -0.13535932, -0.43386173 0.16064031 -0.13537663, -0.42567533 0.17520069 -0.13534468, -0.4340556 0.16068524 -0.13534564, -0.4259308 0.17542179 -0.13521776, -0.43448687 0.16067362 -0.13519913, -0.42614222 0.17560498 -0.13503209, -0.43483555 0.16066413 -0.13498059, -0.42631829 0.17575753 -0.1347883, -0.43508834 0.1606573 -0.13472539, -0.4264468 0.17586873 -0.13450462, -0.4352656 0.1606524 -0.1344358, -0.42652273 0.1759343 -0.13420397, -0.43535712 0.16064997 -0.1341601, -0.42654216 0.17595127 -0.13404483, -0.42546389 0.17532264 -0.13534468, -0.42568076 0.17644851 -0.13404483, -0.42585301 0.17547511 -0.13523406, -0.42569476 0.17557068 -0.13524193, -0.42552778 0.17565446 -0.13521785, -0.42558068 0.17592905 -0.13503209, -0.42620254 0.17587112 -0.13482317, -0.42593125 0.17605112 -0.13484076, -0.42562467 0.17615785 -0.1347883, -0.42565691 0.1763249 -0.13450474, -0.42639971 0.17609625 -0.13422328, -0.42607039 0.17633246 -0.13423321, -0.42567581 0.17642319 -0.13420397, -0.42610061 0.17618136 -0.13455525, -0.4027009 0.1752905 -0.13535255, -0.40270096 0.17560755 -0.13524145, -0.40270096 0.17589197 -0.13506275, -0.40270096 0.17612949 -0.13482529, -0.40270096 0.1763082 -0.13454083, -0.4027009 0.176419 -0.13422394, -0.43531013 0.16029167 -0.096621655, -0.43055534 0.15553932 -0.096612595, -0.43522131 0.16031292 -0.096346073, -0.43045187 0.15555087 -0.096333437, -0.43504876 0.16035423 -0.096056275, -0.43027776 0.15557019 -0.096070699, -0.43004131 0.15559623 -0.095839791, -0.43480283 0.16041298 -0.095801286, -0.42975777 0.15562794 -0.095653318, -0.43446368 0.16049419 -0.095582388, -0.42944628 0.15566249 -0.095517419, -0.43404412 0.16059448 -0.095436357, -0.42946529 0.15609826 -0.095423184, -0.43386832 0.16068804 -0.095405124, -0.42560369 0.17513642 -0.095415048, -0.43411699 0.16068128 -0.095450453, -0.4258185 0.17532246 -0.095495336, -0.43446597 0.16067185 -0.095572554, -0.42606461 0.17553549 -0.095669203, -0.43478519 0.16066329 -0.095762126, -0.42627472 0.17571752 -0.095920704, -0.43504962 0.16065617 -0.096009068, -0.42642969 0.17585163 -0.096228056, -0.43524072 0.16065098 -0.096294634, -0.42652017 0.17593028 -0.096561156, -0.43535125 0.16064817 -0.096595548, -0.42544609 0.17522725 -0.095415048, -0.42567521 0.17641799 -0.096561007, -0.42556626 0.17547238 -0.095484994, -0.42549971 0.17550653 -0.095495485, -0.42556131 0.17582606 -0.095669173, -0.42563039 0.17543726 -0.095479779, -0.42569321 0.17540093 -0.095479988, -0.42575568 0.17536287 -0.095484994, -0.4257614 0.17605396 -0.095886968, -0.42561388 0.17609912 -0.095920704, -0.42590314 0.17599206 -0.095869921, -0.42603725 0.17591451 -0.095869921, -0.42616165 0.1758226 -0.095886819, -0.42583275 0.17626448 -0.096194647, -0.4256525 0.17630044 -0.096228056, -0.42600536 0.17619897 -0.096177749, -0.42616564 0.17610657 -0.0961776, -0.42630845 0.17598981 -0.096194647, -0.4258762 0.17639199 -0.096540861, -0.42606854 0.1763269 -0.09653049, -0.42624456 0.17622523 -0.09653049, -0.4263972 0.1760913 -0.096541069, -0.4027009 0.17641701 -0.096556239, -0.40270096 0.17630598 -0.096239232, -0.40270078 0.17612718 -0.095954917, -0.4027009 0.17588976 -0.095717244, -0.40270096 0.17560537 -0.095538519, -0.40270096 0.17528825 -0.095427804, -0.42427641 0.16048643 -0.13421968, -0.40270093 0.16048761 -0.13422471, -0.42432386 0.16058834 -0.13452014, -0.40270084 0.16059865 -0.13454166, -0.42439407 0.16073863 -0.13477546, -0.40270081 0.16077748 -0.13482633, -0.42448777 0.1609398 -0.13499954, -0.4027009 0.16101494 -0.1350635, -0.42459995 0.16118018 -0.13517803, -0.40270084 0.16129938 -0.13524249, -0.42472327 0.16144457 -0.13530317, -0.40270084 0.16161644 -0.13535318, -0.42484254 0.16170044 -0.13536999, -0.4027009 0.16161415 -0.095428489, -0.42478824 0.16158165 -0.095435999, -0.4027009 0.16129699 -0.095539384, -0.42461687 0.16121416 -0.095582508, -0.40270075 0.16101272 -0.095718049, -0.42447808 0.16091673 -0.095801257, -0.40270081 0.16077513 -0.095955752, -0.42437756 0.16070133 -0.096056275, -0.40270084 0.1605965 -0.096240066, -0.42430717 0.16055028 -0.096346073, -0.40270093 0.16048558 -0.096557043, -0.42427078 0.16047217 -0.096621774, -0.40254456 0.1755726 -0.095606349, -0.40254456 0.17527153 -0.095501088, -0.40252075 0.17526303 -0.095537983, -0.40257633 0.17637454 -0.096565865, -0.40254468 0.17637934 -0.096890084, -0.40257615 0.17641094 -0.096890084, -0.40257621 0.1762666 -0.096258186, -0.40254456 0.17623803 -0.096271805, -0.40252084 0.17555626 -0.095640354, -0.4025445 0.1763436 -0.096572809, -0.40265632 0.17630143 -0.096241288, -0.40265638 0.17612337 -0.095957778, -0.40252078 0.1758191 -0.095805578, -0.40250605 0.175538 -0.09567859, -0.40261415 0.17611179 -0.095967047, -0.40261424 0.17628813 -0.096247725, -0.40250599 0.17579275 -0.095838718, -0.40261415 0.17639771 -0.09656053, -0.40261418 0.1764347 -0.096890084, -0.40250587 0.17600562 -0.096051745, -0.40265644 0.17641206 -0.096557073, -0.40265638 0.17644957 -0.096890084, -0.40261415 0.17528389 -0.095446967, -0.40261412 0.17495447 -0.095409863, -0.40257609 0.17495441 -0.095433764, -0.40257621 0.17527846 -0.095470361, -0.40257627 0.1755864 -0.095577858, -0.40254447 0.17584272 -0.095776044, -0.40252087 0.17603886 -0.09602537, -0.40265644 0.17528717 -0.095432691, -0.40265644 0.17495447 -0.095394902, -0.4025059 0.17616585 -0.096306823, -0.40261412 0.17559677 -0.095556311, -0.40257621 0.17586249 -0.095751427, -0.4025445 0.17606834 -0.096001767, -0.40252084 0.17620403 -0.096288256, -0.4026565 0.17560309 -0.095543198, -0.40250587 0.17626539 -0.096590899, -0.40250599 0.17629911 -0.096890084, -0.40261412 0.1758773 -0.095732711, -0.40257615 0.17609316 -0.095982008, -0.40250599 0.17525364 -0.09557908, -0.40250587 0.17495449 -0.095545523, -0.40252084 0.17630664 -0.096581511, -0.40252066 0.17634134 -0.096889995, -0.40252072 0.17495447 -0.095503353, -0.40265644 0.17588659 -0.095721267, -0.4025445 0.17495447 -0.095465414, -0.40265632 0.16194783 -0.095395856, -0.40261409 0.16194789 -0.095410727, -0.40257615 0.16194792 -0.095434569, -0.40254447 0.16194788 -0.095466159, -0.40252057 0.16194782 -0.095503978, -0.40250593 0.16194792 -0.095546298, -0.4026565 0.17644994 -0.10414004, -0.40261418 0.17643511 -0.10413992, -0.40257615 0.17641124 -0.10413992, -0.40254468 0.1763797 -0.10413992, -0.40252072 0.17634176 -0.10413989, -0.40250587 0.17629948 -0.10414004, -0.402576 0.16052808 -0.096566699, -0.40254438 0.16052327 -0.096890859, -0.40254435 0.16055901 -0.096573763, -0.40261406 0.16130573 -0.095557116, -0.40261394 0.16102502 -0.095733337, -0.40257615 0.1610399 -0.095752053, -0.40257618 0.16131604 -0.095578693, -0.40254438 0.16066429 -0.096272849, -0.40252054 0.160596 -0.096582316, -0.4025206 0.16069852 -0.096288852, -0.40257603 0.16162385 -0.095470898, -0.4025445 0.16163085 -0.095501803, -0.40254438 0.16132972 -0.095607184, -0.4025206 0.16086364 -0.096026205, -0.40250579 0.16073655 -0.096307449, -0.40250579 0.16089673 -0.096052431, -0.40265647 0.16129927 -0.095543675, -0.40265632 0.16101576 -0.095721923, -0.40261418 0.16161856 -0.095447622, -0.40250593 0.16110958 -0.095839553, -0.40265644 0.16161516 -0.095433466, -0.402614 0.16050485 -0.096561573, -0.402614 0.16046785 -0.09689083, -0.402576 0.16049166 -0.096890859, -0.40257615 0.1606358 -0.09625902, -0.40254438 0.16083406 -0.096002512, -0.4025206 0.16108324 -0.095806532, -0.4026562 0.16049044 -0.096557967, -0.40265635 0.16045299 -0.096890859, -0.40250587 0.1613645 -0.095679335, -0.402614 0.16061427 -0.09624856, -0.40257618 0.16080922 -0.095982812, -0.40254447 0.16105959 -0.095776878, -0.40252066 0.16134623 -0.095641248, -0.40265629 0.16060103 -0.096242242, -0.40250593 0.16164877 -0.095580123, -0.40261406 0.16079071 -0.095967941, -0.40250576 0.16063716 -0.096591733, -0.40250582 0.16060343 -0.096890859, -0.40252054 0.16056122 -0.096890859, -0.40252057 0.1616393 -0.095538788, -0.4026562 0.1607791 -0.095958613, -0.40261412 0.17588034 -0.10502326, -0.4025763 0.17605135 -0.1048876, -0.40257633 0.17586997 -0.10500168, -0.40257621 0.1756679 -0.10507234, -0.40254456 0.17545502 -0.10506462, -0.40257609 0.17545511 -0.10509627, -0.40254456 0.17628807 -0.10454126, -0.40252066 0.17631949 -0.10433733, -0.40252072 0.17625394 -0.10452472, -0.4025445 0.17585622 -0.10497307, -0.4025445 0.17566086 -0.10504159, -0.4025445 0.17635641 -0.10434579, -0.40265656 0.17588681 -0.10503634, -0.40265656 0.17607543 -0.10491785, -0.40252072 0.17614822 -0.10469281, -0.40250587 0.17621584 -0.10450646, -0.40250599 0.17611524 -0.10466655, -0.40261415 0.1760661 -0.10490628, -0.4026143 0.17567319 -0.10509574, -0.40261406 0.17545503 -0.10512029, -0.40250599 0.17598154 -0.10480022, -0.4026565 0.17567647 -0.10511001, -0.40265626 0.17545502 -0.10513505, -0.40261415 0.1764106 -0.10435807, -0.40257627 0.17638737 -0.10435271, -0.40257621 0.1763166 -0.10455485, -0.4025445 0.17617798 -0.1047165, -0.40252078 0.17600791 -0.10483324, -0.40265638 0.17642494 -0.10436129, -0.40250593 0.17582147 -0.10490095, -0.40261415 0.17633815 -0.10456523, -0.40257615 0.17620273 -0.10473632, -0.4025445 0.17603162 -0.10486277, -0.40252078 0.17583984 -0.10493898, -0.40265644 0.17635138 -0.10457169, -0.40250599 0.17564292 -0.10496315, -0.40250599 0.17545503 -0.10498448, -0.40261412 0.17622131 -0.10475122, -0.40250599 0.17627825 -0.104328, -0.40252072 0.17565244 -0.1050043, -0.40252066 0.17545503 -0.1050268, -0.40265632 0.1762328 -0.1047604, -0.40265632 0.16045511 -0.1338909, -0.40261418 0.16046986 -0.1338909, -0.40257618 0.16049379 -0.1338909, -0.40254453 0.16052544 -0.1338909, -0.40252069 0.16056329 -0.13389072, -0.40250587 0.16060552 -0.13389072, -0.40265638 0.16886261 -0.10513519, -0.40261412 0.1688627 -0.10512062, -0.40257609 0.16886263 -0.10509678, -0.40254438 0.16886263 -0.10506519, -0.4025206 0.1688626 -0.10502716, -0.40250593 0.16886261 -0.10498487, -0.40257609 0.16053015 -0.13421503, -0.40254444 0.16133204 -0.13517433, -0.40252066 0.16164158 -0.13524279, -0.40252066 0.16134854 -0.13514033, -0.40257624 0.16063797 -0.13452274, -0.4025445 0.16066644 -0.13450903, -0.40254462 0.16056111 -0.1342079, -0.40254444 0.16163313 -0.13527972, -0.40265635 0.16060328 -0.13453943, -0.40252075 0.16108568 -0.13497511, -0.40250587 0.16136685 -0.13510221, -0.40250587 0.16111195 -0.13494197, -0.40250584 0.16195019 -0.13523528, -0.40265632 0.16078129 -0.13482288, -0.40261406 0.16079295 -0.1348137, -0.40261406 0.16061659 -0.13453323, -0.40261406 0.16050701 -0.1342203, -0.40250599 0.16089903 -0.13472906, -0.40265632 0.16049251 -0.13422352, -0.40261421 0.16162087 -0.13533384, -0.40261415 0.16195023 -0.13537091, -0.40257618 0.1619502 -0.13534707, -0.40257612 0.16162607 -0.13531068, -0.40257603 0.16131829 -0.13520303, -0.40254444 0.16106185 -0.13500479, -0.40252066 0.16086589 -0.13475552, -0.40265641 0.16161743 -0.13534835, -0.40265644 0.16195011 -0.13538578, -0.40250587 0.1607388 -0.13447422, -0.40261406 0.16130792 -0.13522437, -0.40257621 0.16104218 -0.13502952, -0.40254438 0.16083625 -0.13477913, -0.40252066 0.16070084 -0.13449249, -0.40265632 0.16130148 -0.13523775, -0.4025059 0.16063926 -0.13418999, -0.40261418 0.16102731 -0.13504809, -0.40257615 0.16081156 -0.13479891, -0.40250596 0.16165105 -0.1352016, -0.40252069 0.16195013 -0.1352776, -0.40252075 0.16059817 -0.13419956, -0.40265641 0.1610181 -0.13505974, -0.40254462 0.16195014 -0.13531557, -0.4025445 0.16845113 -0.105147, -0.40257615 0.16828284 -0.10527252, -0.40257615 0.16846326 -0.10517632, -0.40257627 0.16865911 -0.10511684, -0.40261412 0.16847239 -0.10519811, -0.40261412 0.16866376 -0.10514017, -0.40250593 0.16822064 -0.10517954, -0.40250582 0.16804563 -0.10532352, -0.4025206 0.16807547 -0.1053532, -0.40252072 0.16824426 -0.1052148, -0.40252072 0.16843668 -0.10511195, -0.40254444 0.16826525 -0.1052463, -0.4025445 0.16865295 -0.10508596, -0.40250576 0.1684204 -0.10507297, -0.40252072 0.16864556 -0.10504862, -0.40250593 0.16863725 -0.10500716, -0.40265644 0.16830429 -0.1053048, -0.40265632 0.16815205 -0.10542973, -0.40261418 0.16829614 -0.1052924, -0.40261406 0.1681415 -0.10541927, -0.40265644 0.1684781 -0.10521173, -0.40257609 0.16812471 -0.10540243, -0.40265626 0.16866657 -0.10515475, -0.4025445 0.16810232 -0.10538017, -0.40265644 0.17495665 -0.1353851, -0.40261412 0.17495665 -0.13537028, -0.40257627 0.17495674 -0.13534668, -0.40254468 0.17495669 -0.13531473, -0.40252087 0.17495674 -0.13527676, -0.40250599 0.17495671 -0.13523445, -0.40265644 0.16273822 -0.11084449, -0.40261421 0.16272774 -0.11083397, -0.40257603 0.16271082 -0.11081695, -0.4025445 0.16268845 -0.11079478, -0.40252075 0.16266167 -0.11076771, -0.40250593 0.16263175 -0.11073782, -0.402614 0.17559893 -0.13522378, -0.40261418 0.17587954 -0.13504735, -0.40257621 0.17586479 -0.13502869, -0.40257627 0.17558864 -0.1352022, -0.40254456 0.17624028 -0.13450807, -0.40254444 0.17634562 -0.13420704, -0.40252078 0.17630871 -0.1341987, -0.4025763 0.17528091 -0.13531008, -0.40252075 0.17620619 -0.13449174, -0.40254456 0.1755749 -0.13517371, -0.4025445 0.17527378 -0.13527903, -0.40265644 0.17560539 -0.13523701, -0.40252084 0.17604104 -0.13475448, -0.40250605 0.17616811 -0.13447344, -0.40250587 0.1760079 -0.13472825, -0.4026565 0.17588888 -0.13505891, -0.40261424 0.17528611 -0.13533315, -0.40250593 0.175795 -0.13494119, -0.4026565 0.17528938 -0.13534755, -0.4026143 0.17639975 -0.13421932, -0.40261412 0.17643684 -0.13389018, -0.40257621 0.17641303 -0.13389018, -0.40257633 0.17637648 -0.13421419, -0.40257627 0.17626885 -0.13452211, -0.40254474 0.17607066 -0.13477832, -0.40252078 0.17582145 -0.13497427, -0.40265644 0.17645167 -0.13389018, -0.40265644 0.17641427 -0.13422269, -0.40250605 0.17554012 -0.13510147, -0.40261424 0.17629027 -0.13453224, -0.40257621 0.17609525 -0.13479805, -0.40254456 0.17584504 -0.13500389, -0.40252078 0.17555849 -0.1351395, -0.4026565 0.17630357 -0.13453859, -0.40250599 0.17525588 -0.13520077, -0.40261427 0.17611402 -0.13481301, -0.4025059 0.17626743 -0.13418925, -0.40250599 0.1763012 -0.13389006, -0.40252078 0.17634344 -0.13388997, -0.40252075 0.17526536 -0.13524204, -0.40265644 0.17612545 -0.13482228, -0.40254468 0.17638128 -0.13389018, -0.40257615 0.16258101 -0.11097526, -0.40261406 0.16250663 -0.11116474, -0.40261409 0.16260076 -0.11098837, -0.40257615 0.16248462 -0.11115562, -0.40250587 0.1623155 -0.11132943, -0.40250599 0.16229337 -0.11155494, -0.40252066 0.16233569 -0.11155509, -0.40252075 0.16235705 -0.11133798, -0.40252066 0.16242029 -0.11112895, -0.40254456 0.16239424 -0.11134519, -0.40254444 0.16245539 -0.11114361, -0.40254462 0.16255467 -0.11095762, -0.40250596 0.16238123 -0.11111283, -0.40252066 0.16252314 -0.1109364, -0.40250582 0.16248803 -0.11091312, -0.40265644 0.16246308 -0.1113589, -0.40265629 0.16244382 -0.11155509, -0.40261406 0.16244863 -0.11135604, -0.40261406 0.16242906 -0.11155494, -0.40265641 0.16252035 -0.11117043, -0.40257609 0.16242525 -0.11135139, -0.40257618 0.16240522 -0.11155494, -0.40265632 0.16261309 -0.11099672, -0.4025445 0.16237351 -0.11155494, -0.4026565 0.17645128 -0.12663996, -0.40261424 0.17643645 -0.12663996, -0.40257627 0.17641275 -0.12664008, -0.40254456 0.17638101 -0.12664008, -0.40252087 0.1763432 -0.12663996, -0.40250599 0.17630084 -0.12663996, -0.40265638 0.1624442 -0.11922654, -0.40261406 0.16242936 -0.11922654, -0.40257609 0.16240561 -0.11922663, -0.40254456 0.16237387 -0.11922642, -0.40252054 0.16233593 -0.11922642, -0.40250599 0.16229379 -0.11922642, -0.40261424 0.17633945 -0.12621474, -0.40261418 0.17622253 -0.12602898, -0.40257621 0.17620401 -0.1260438, -0.40257621 0.17631793 -0.12622499, -0.40254456 0.17585735 -0.12580705, -0.40254456 0.17566197 -0.12573838, -0.40252078 0.17565355 -0.12577546, -0.40257633 0.17638868 -0.12642726, -0.40252072 0.17584088 -0.12584102, -0.40254447 0.17628938 -0.12623894, -0.4025445 0.17635787 -0.12643421, -0.40265644 0.17635281 -0.12620831, -0.4025209 0.17600919 -0.12594652, -0.40250599 0.17582256 -0.12587917, -0.40250611 0.17598282 -0.12597975, -0.4026565 0.17623407 -0.12601975, -0.40261412 0.1764119 -0.12642181, -0.40250599 0.1761166 -0.1261133, -0.40265626 0.17642626 -0.12641862, -0.40261412 0.17567417 -0.12568435, -0.40261418 0.17545617 -0.12565991, -0.40257633 0.17545617 -0.12568375, -0.4025763 0.175669 -0.12570772, -0.40257621 0.17587101 -0.12577853, -0.40254462 0.17603284 -0.12591693, -0.40252075 0.1761495 -0.12608719, -0.40265644 0.1754562 -0.12564501, -0.4026565 0.17567757 -0.12566996, -0.40250593 0.17621711 -0.12627363, -0.40261424 0.17588145 -0.12575686, -0.40257627 0.17605242 -0.12589228, -0.40254462 0.1761792 -0.12606359, -0.40252084 0.17625532 -0.12625515, -0.4026565 0.17588787 -0.12574363, -0.40250605 0.17627965 -0.126452, -0.40261418 0.17606726 -0.12587377, -0.4025059 0.17564413 -0.1258167, -0.40250593 0.17545612 -0.12579536, -0.40252078 0.17545618 -0.1257534, -0.40252066 0.17632079 -0.12644279, -0.4026565 0.17607652 -0.12586203, -0.40254456 0.17545623 -0.12571532, -0.40257609 0.16242567 -0.11943027, -0.40261406 0.16244908 -0.11942538, -0.40261406 0.16250716 -0.11961683, -0.40257615 0.16248503 -0.11962601, -0.40250599 0.16248864 -0.11986848, -0.40250602 0.16263236 -0.12004348, -0.40252063 0.16252369 -0.11984514, -0.40265638 0.16273867 -0.11993726, -0.40252075 0.16242093 -0.11965262, -0.40254456 0.16255528 -0.11982401, -0.40254456 0.16245577 -0.11963814, -0.4025445 0.16239458 -0.11943641, -0.40250593 0.16238187 -0.11966871, -0.40252066 0.1623574 -0.11944371, -0.40250584 0.16231592 -0.11945205, -0.40265638 0.16261369 -0.11978479, -0.402614 0.16272815 -0.11994775, -0.40261415 0.16260132 -0.11979314, -0.40257615 0.1627114 -0.11996459, -0.40265632 0.16252069 -0.11961123, -0.40257615 0.16258152 -0.11980637, -0.4025445 0.16268899 -0.119987, -0.40265644 0.16246359 -0.11942267, -0.40252066 0.16266219 -0.12001374, -0.40265641 0.16886379 -0.1256454, -0.40261412 0.16886391 -0.1256603, -0.40257615 0.16886371 -0.12568411, -0.40254456 0.16886383 -0.12571582, -0.40252084 0.16886383 -0.12575373, -0.40250593 0.16886377 -0.12579605, -0.40265638 0.16815314 -0.12535095, -0.40261424 0.16814277 -0.12536153, -0.40257615 0.16812584 -0.12537837, -0.40254465 0.16810352 -0.12540069, -0.40252072 0.16807672 -0.12542769, -0.40250593 0.16804674 -0.12545741, -0.40254465 0.16845229 -0.12563396, -0.40254444 0.16865404 -0.12569523, -0.40257627 0.16866012 -0.12566411, -0.40257627 0.16828401 -0.12550828, -0.40257615 0.16846444 -0.12560466, -0.40261406 0.16847354 -0.12558258, -0.402614 0.16829716 -0.12548837, -0.40250593 0.16863839 -0.12577379, -0.40252072 0.16864677 -0.1257323, -0.40252072 0.16843779 -0.12566891, -0.40254462 0.16826642 -0.12553439, -0.40250593 0.16842157 -0.12570801, -0.40252066 0.16824535 -0.1255661, -0.40250593 0.16822183 -0.12560129, -0.40265635 0.16866773 -0.12562621, -0.40261424 0.16866481 -0.12564075, -0.40265638 0.16847926 -0.12556887, -0.40265638 0.16830546 -0.12547612, -0.40200078 0.16349824 -0.10259052, -0.40200084 0.16338699 -0.10257825, -0.40200087 0.16328132 -0.10254132, -0.40200084 0.16318648 -0.10248166, -0.40200087 0.16310734 -0.10240241, -0.40200081 0.16304776 -0.10230755, -0.40200078 0.16301085 -0.10220193, -0.40200087 0.16299826 -0.10209083, -0.40200078 0.1730132 -0.10259014, -0.40200087 0.17336696 -0.10244363, -0.40200096 0.17329116 -0.10250577, -0.40200087 0.17320457 -0.10255214, -0.40200078 0.17311098 -0.10258042, -0.40200078 0.1737518 -0.1020587, -0.40200096 0.17389823 -0.10170519, -0.4020009 0.17388853 -0.10180282, -0.40200108 0.17386027 -0.10189664, -0.40200087 0.17381409 -0.101983, -0.4020009 0.1738981 -0.098824911, -0.4020009 0.17375162 -0.098471664, -0.40200099 0.17381394 -0.098547153, -0.40200096 0.17385997 -0.098633818, -0.4020009 0.17388847 -0.098727547, -0.40200087 0.17336667 -0.098086469, -0.4020009 0.17301306 -0.09794011, -0.40200078 0.17311068 -0.097949676, -0.40200087 0.17320439 -0.097978167, -0.40200087 0.17329083 -0.098024331, -0.40200081 0.16388294 -0.097940706, -0.40200093 0.16352943 -0.098087035, -0.40200084 0.16360514 -0.098024987, -0.40200084 0.16369157 -0.097978674, -0.40200084 0.16378544 -0.097950272, -0.40200084 0.16314451 -0.098471962, -0.40200078 0.16299815 -0.098825745, -0.40200084 0.16300766 -0.098728143, -0.40200076 0.16303612 -0.098634325, -0.4020007 0.1630823 -0.098547809, -0.39250088 0.17301315 -0.09794011, -0.39250085 0.17336681 -0.098086469, -0.39250088 0.17320456 -0.097978137, -0.39250073 0.17329103 -0.098024331, -0.39250082 0.17381395 -0.098547153, -0.39250088 0.17375177 -0.098471455, -0.39250088 0.17389819 -0.098824911, -0.39250094 0.16304794 -0.10230755, -0.39250079 0.16299836 -0.10209068, -0.39250088 0.16301091 -0.10220208, -0.39250094 0.16310745 -0.10240241, -0.39250079 0.16349843 -0.10259073, -0.39250076 0.16318662 -0.10248166, -0.39250085 0.16328147 -0.10254117, -0.39250082 0.16338713 -0.10257825, -0.39250079 0.16299815 -0.098825596, -0.39250076 0.16303624 -0.098634265, -0.39250088 0.16300783 -0.098728143, -0.39250076 0.16308244 -0.098547809, -0.39250082 0.16314466 -0.098472051, -0.39250088 0.16352949 -0.098087035, -0.39250079 0.16369162 -0.097978674, -0.39250076 0.16360523 -0.098024838, -0.39250097 0.16388309 -0.097940706, -0.39250082 0.1637855 -0.097950272, -0.39250088 0.17301345 -0.10258996, -0.39250088 0.17311102 -0.10258057, -0.392501 0.17320476 -0.10255214, -0.39250076 0.17329122 -0.10250591, -0.39250091 0.17336705 -0.10244363, -0.39250073 0.17375179 -0.1020587, -0.39250088 0.17381415 -0.10198294, -0.39250088 0.17386022 -0.10189649, -0.39250073 0.17388868 -0.10180282, -0.39250085 0.17389834 -0.10170519, -0.39250088 0.17388862 -0.098727487, -0.392501 0.17386013 -0.098633669, -0.39250088 0.17311072 -0.097949676, -0.39300084 0.16249843 -0.1020908, -0.40150082 0.1624983 -0.1020908, -0.40150094 0.16252342 -0.10231324, -0.39300078 0.16252339 -0.10231324, -0.4015007 0.16259728 -0.10252463, -0.39300075 0.16259736 -0.10252451, -0.4015007 0.16271658 -0.10271414, -0.39300084 0.16271663 -0.10271417, -0.40150079 0.16287489 -0.10287248, -0.39300081 0.16287491 -0.10287257, -0.40150082 0.16306457 -0.10299178, -0.39300096 0.16306466 -0.10299154, -0.40150082 0.1632759 -0.10306575, -0.39300087 0.16327596 -0.1030656, -0.40150082 0.16349831 -0.10309064, -0.39300081 0.16349837 -0.10309073, -0.40150088 0.17372051 -0.10279723, -0.39300078 0.17372051 -0.10279714, -0.39300081 0.17356901 -0.10292157, -0.40150094 0.17356908 -0.10292169, -0.3930009 0.17339616 -0.1030141, -0.40150088 0.1733961 -0.10301404, -0.39300093 0.17320859 -0.10307103, -0.40150079 0.1732085 -0.10307103, -0.3930009 0.17301355 -0.10309004, -0.40150088 0.1730134 -0.10309025, -0.3930009 0.17372026 -0.097733013, -0.40150079 0.17372017 -0.097733013, -0.40150079 0.17356879 -0.097608589, -0.39300096 0.1735688 -0.097608827, -0.39300084 0.17339584 -0.097516231, -0.40150088 0.17339578 -0.097516201, -0.39300087 0.17320825 -0.097459249, -0.40150079 0.17320821 -0.097459458, -0.39300084 0.17301315 -0.097440265, -0.40150088 0.17301309 -0.097440265, -0.4015007 0.16332729 -0.097609274, -0.40150073 0.1631759 -0.097733758, -0.39300078 0.16317593 -0.09773355, -0.39300084 0.16332746 -0.097609274, -0.40150079 0.16350019 -0.097516827, -0.39300084 0.16350026 -0.097516827, -0.40150082 0.16368777 -0.097459905, -0.39300072 0.16368781 -0.097459905, -0.40150094 0.16388296 -0.097440742, -0.39300084 0.16388303 -0.097440653, -0.39300075 0.16266665 -0.0982702, -0.39300078 0.16279103 -0.098118566, -0.40150082 0.16279092 -0.098118596, -0.40150079 0.16266657 -0.098269992, -0.39300075 0.16257426 -0.098442964, -0.40150073 0.1625742 -0.098442934, -0.39300084 0.16251732 -0.09863057, -0.40150082 0.16251734 -0.0986306, -0.39300078 0.16249819 -0.098825745, -0.40150082 0.16249812 -0.098825656, -0.40150088 0.1741052 -0.09811797, -0.3930009 0.17410527 -0.098117761, -0.3930009 0.17422961 -0.098269396, -0.40150079 0.17422952 -0.098269604, -0.39300084 0.1743221 -0.098442428, -0.40150079 0.17432186 -0.098442368, -0.39300093 0.17437905 -0.098629825, -0.40150094 0.1743789 -0.098629825, -0.39300105 0.1743983 -0.09882497, -0.40150079 0.17439806 -0.098825119, -0.39300081 0.17410547 -0.10241219, -0.40150082 0.17410542 -0.10241234, -0.40150076 0.17422974 -0.1022607, -0.3930009 0.1742298 -0.1022607, -0.40150079 0.17432211 -0.10208773, -0.3930009 0.17432219 -0.10208782, -0.40150088 0.17437901 -0.10190027, -0.39300093 0.17437905 -0.10190009, -0.40150079 0.17439823 -0.10170516, -0.3930009 0.17439839 -0.10170516, -0.40200096 0.163885 -0.13284057, -0.40200084 0.16378747 -0.13283104, -0.4020009 0.16369358 -0.13280267, -0.40200073 0.16360721 -0.1327565, -0.40200076 0.16353127 -0.13269424, -0.4020009 0.17301515 -0.1328401, -0.4020009 0.17336863 -0.1326938, -0.40200078 0.17329291 -0.13275591, -0.4020009 0.17320646 -0.13280207, -0.40200096 0.17311279 -0.13283047, -0.40200081 0.17375356 -0.13230878, -0.4020009 0.17389998 -0.1319553, -0.40200087 0.17389038 -0.13205281, -0.40200096 0.17386186 -0.13214663, -0.40200096 0.1738158 -0.13223305, -0.40200096 0.17389975 -0.12907517, -0.40200078 0.17375334 -0.12872157, -0.4020009 0.17381552 -0.12879717, -0.4020009 0.17386176 -0.12888387, -0.40200081 0.17389014 -0.12897763, -0.4020009 0.17336828 -0.12833661, -0.40200099 0.17301483 -0.12819016, -0.40200078 0.17311241 -0.1281997, -0.40200087 0.17320608 -0.12822822, -0.40200078 0.17329271 -0.12827435, -0.40200093 0.16349974 -0.12819076, -0.40200084 0.16299978 -0.12869084, -0.40200078 0.16301227 -0.12857956, -0.40200084 0.16304936 -0.12847379, -0.4020009 0.16310884 -0.12837911, -0.40200087 0.16318792 -0.12829992, -0.4020009 0.16328281 -0.12824038, -0.40200093 0.16338852 -0.12820327, -0.40200084 0.16299991 -0.13195589, -0.4020009 0.16314647 -0.13230959, -0.40200093 0.16308421 -0.13223356, -0.4020009 0.163038 -0.13214722, -0.40200078 0.16300954 -0.13205335, -0.39250085 0.17301494 -0.12819016, -0.39250091 0.1732063 -0.12822819, -0.39250088 0.17311245 -0.12819982, -0.39250085 0.17389032 -0.12897754, -0.39250085 0.17381573 -0.12879726, -0.39250103 0.17390001 -0.12907505, -0.392501 0.17386183 -0.12888372, -0.39250073 0.16314645 -0.13230938, -0.39250091 0.16303819 -0.13214722, -0.39250094 0.16308422 -0.13223356, -0.39250091 0.17329279 -0.12827444, -0.39250094 0.17336857 -0.12833661, -0.39250094 0.1737535 -0.12872151, -0.39250079 0.16300961 -0.13205341, -0.39250088 0.16300003 -0.13195568, -0.39250067 0.1636072 -0.1327565, -0.39250076 0.163885 -0.13284057, -0.39250088 0.16353156 -0.13269424, -0.39250061 0.16369358 -0.13280267, -0.39250067 0.16378745 -0.13283116, -0.39250082 0.16299976 -0.12869084, -0.39250082 0.16328292 -0.12824023, -0.39250082 0.16349988 -0.12819076, -0.39250082 0.16338868 -0.12820327, -0.39250091 0.16318813 -0.12829992, -0.39250088 0.16310908 -0.12837911, -0.39250082 0.16304941 -0.12847373, -0.39250076 0.1630124 -0.1285795, -0.39250088 0.1730151 -0.13283998, -0.3925007 0.17311266 -0.13283047, -0.39250088 0.17320648 -0.13280207, -0.39250073 0.17329289 -0.13275591, -0.39250082 0.17336872 -0.1326938, -0.39250085 0.17375356 -0.13230875, -0.39250103 0.17381585 -0.13223293, -0.39250088 0.17386195 -0.1321466, -0.39250085 0.17389041 -0.13205272, -0.39250094 0.17390004 -0.13195503, -0.40150088 0.17320989 -0.12770927, -0.40150079 0.17301467 -0.12769011, -0.3930009 0.1730148 -0.12769011, -0.3930009 0.17320994 -0.12770936, -0.40150079 0.17339745 -0.12776613, -0.39300093 0.17339754 -0.12776613, -0.40150088 0.17357029 -0.12785864, -0.3930009 0.17357042 -0.12785873, -0.40150088 0.17372181 -0.12798291, -0.39300081 0.17372197 -0.12798291, -0.39300081 0.16251919 -0.13215089, -0.39300081 0.16250005 -0.13195568, -0.40150082 0.16249993 -0.13195589, -0.40150079 0.16251917 -0.13215104, -0.40150085 0.16257615 -0.13233852, -0.39300081 0.16257612 -0.13233855, -0.40150082 0.16266854 -0.13251132, -0.39300075 0.16266862 -0.13251132, -0.4015007 0.16279285 -0.13266292, -0.39300081 0.16279298 -0.13266289, -0.40150073 0.16388497 -0.13334063, -0.39300084 0.16388506 -0.13334075, -0.39300081 0.16368982 -0.13332167, -0.40150073 0.16368982 -0.13332158, -0.39300078 0.16350229 -0.1332646, -0.40150079 0.16350222 -0.13326448, -0.39300066 0.16332938 -0.13317209, -0.40150073 0.16332926 -0.1331723, -0.39300084 0.16317797 -0.13304794, -0.40150082 0.16317788 -0.13304809, -0.3930009 0.17438053 -0.12887982, -0.39300084 0.17439981 -0.12907484, -0.40150082 0.17439976 -0.12907496, -0.40150088 0.1743805 -0.1288799, -0.3930009 0.17432372 -0.12869227, -0.40150082 0.17432365 -0.12869233, -0.3930009 0.17423134 -0.12851951, -0.40150082 0.17423126 -0.12851956, -0.3930009 0.174107 -0.1283679, -0.40150082 0.17410694 -0.1283679, -0.40150094 0.17438075 -0.13215023, -0.40150079 0.17439996 -0.13195509, -0.39300096 0.17440011 -0.13195509, -0.39300093 0.17438087 -0.13215023, -0.40150076 0.17432375 -0.13233775, -0.3930009 0.17432405 -0.13233787, -0.40150088 0.17423147 -0.13251084, -0.3930009 0.17423159 -0.13251069, -0.40150088 0.17410715 -0.13266224, -0.39300096 0.17410727 -0.13266224, -0.39300093 0.17301522 -0.13334015, -0.40150088 0.17301513 -0.13334015, -0.40150088 0.17321023 -0.13332084, -0.39300081 0.17321026 -0.13332087, -0.40150088 0.17339773 -0.13326389, -0.3930009 0.17339791 -0.13326389, -0.40150079 0.17357063 -0.13317162, -0.3930009 0.1735708 -0.13317171, -0.40150088 0.1737221 -0.13304728, -0.3930009 0.17372224 -0.13304728, -0.39300084 0.16327722 -0.12771598, -0.39300084 0.16349979 -0.12769079, -0.40150082 0.16349971 -0.1276907, -0.40150079 0.16327715 -0.12771598, -0.39300081 0.16306596 -0.12778974, -0.40150073 0.16306581 -0.12778986, -0.39300084 0.16287628 -0.12790886, -0.40150082 0.16287619 -0.12790903, -0.39300084 0.16271788 -0.12806734, -0.40150079 0.16271795 -0.12806734, -0.39300084 0.16259886 -0.12825692, -0.40150079 0.1625988 -0.12825701, -0.39300081 0.16252497 -0.12846825, -0.40150082 0.16252494 -0.12846825, -0.39300078 0.16249989 -0.12869084, -0.40150082 0.16249982 -0.12869084, -0.40050089 0.16449998 -0.13134086, -0.40050071 0.16449979 -0.12969092, -0.40050083 0.17239974 -0.12969026, -0.40050077 0.17239995 -0.13134038, -0.40050077 0.17239812 -0.099440269, -0.40050077 0.16449818 -0.099440746, -0.40050083 0.17239828 -0.10109019, -0.40050071 0.1644982 -0.10109072, -0.42000073 0.16658357 -0.10258739, -0.42000085 0.16699822 -0.10315379, -0.42000073 0.16682449 -0.10284611, -0.42000079 0.16709505 -0.10349377, -0.42000085 0.16710977 -0.10384702, -0.42000091 0.16704126 -0.1041938, -0.42000091 0.16689359 -0.10451495, -0.42000079 0.16658498 -0.12819371, -0.42000091 0.16689481 -0.12626597, -0.42000091 0.16704257 -0.12658715, -0.42000091 0.16711105 -0.12693402, -0.42000091 0.16709639 -0.12728712, -0.42000079 0.16699958 -0.12762713, -0.42000097 0.16682592 -0.12793493, -0.43027866 0.15549521 -0.13458231, -0.43030256 0.1555171 -0.1346015, -0.43041122 0.15548871 -0.13435522, -0.43025687 0.15547979 -0.13456482, -0.43038785 0.15547557 -0.13434356, -0.43054324 0.15550047 -0.13389102, -0.43020749 0.15545756 -0.13452548, -0.43033534 0.15545642 -0.13431725, -0.43017828 0.15545142 -0.13450193, -0.43030417 0.15545127 -0.13430172, -0.43011421 0.15553023 -0.1348162, -0.43009335 0.15550426 -0.13479152, -0.43007404 0.15548579 -0.13476875, -0.43002963 0.15545909 -0.13471621, -0.43000311 0.15545167 -0.13468495, -0.42988366 0.15558651 -0.13503471, -0.4298687 0.15554781 -0.13500899, -0.42985189 0.15551625 -0.13497975, -0.4298358 0.15549383 -0.1349521, -0.42979807 0.15546112 -0.13488716, -0.4297753 0.15545207 -0.1348483, -0.42944241 0.15562901 -0.13525197, -0.42944112 0.1556292 -0.13525265, -0.4294295 0.15559626 -0.13523844, -0.42943418 0.15557978 -0.1352258, -0.42941293 0.15556662 -0.13522205, -0.42942411 0.15553838 -0.13519281, -0.42939186 0.15554012 -0.13520446, -0.42941388 0.1555087 -0.13515988, -0.42935878 0.15551051 -0.13517919, -0.42938858 0.15546478 -0.13507861, -0.42931741 0.15548503 -0.13514927, -0.4293732 0.15545277 -0.13502878, -0.43051717 0.15550217 -0.13412812, -0.42930561 0.15546553 -0.13510522, -0.42925805 0.15546255 -0.13510838, -0.42929173 0.15545288 -0.13505358, -0.42920858 0.15545303 -0.1350753, -0.43048966 0.15548508 -0.13412157, -0.43049133 0.15547277 -0.13389105, -0.43046522 0.15547308 -0.13411579, -0.43043512 0.15545566 -0.13389117, -0.43041053 0.15545583 -0.134103, -0.43037826 0.15545097 -0.13409534, -0.43043759 0.15550768 -0.13436845, -0.43043506 0.15545367 -0.096891068, -0.43049133 0.15547062 -0.096891068, -0.43054307 0.15549825 -0.096891068, -0.43021756 0.15545523 -0.096270137, -0.42999899 0.15545715 -0.096039556, -0.43004346 0.15548524 -0.095984243, -0.43026787 0.15547773 -0.096230887, -0.43016541 0.15544778 -0.096310668, -0.42995292 0.15544774 -0.096097134, -0.43044591 0.15549831 -0.096455745, -0.43040472 0.15547341 -0.096474431, -0.43035066 0.15545431 -0.09649875, -0.42944315 0.15563612 -0.095526151, -0.42944002 0.15561064 -0.095537655, -0.42943645 0.1556109 -0.095535927, -0.42943123 0.15556401 -0.095565848, -0.42941353 0.15556502 -0.095559292, -0.42930698 0.15546325 -0.095677517, -0.42926019 0.15546076 -0.09567263, -0.42931932 0.15548375 -0.095631741, -0.42941427 0.15550731 -0.095621102, -0.42937303 0.15551971 -0.095592313, -0.42938852 0.15546241 -0.095703624, -0.42974687 0.15558301 -0.095675729, -0.42973351 0.15554379 -0.095703624, -0.42970935 0.15549673 -0.095753483, -0.42967463 0.15545985 -0.095825128, -0.43007562 0.15552157 -0.09594398, -0.43030596 0.15550701 -0.096201323, -0.43541199 0.16058728 -0.096890859, -0.43540782 0.16039452 -0.096890859, -0.43542331 0.16045797 -0.096890859, -0.4353787 0.16033597 -0.096890859, -0.43405053 0.16063868 -0.0954329, -0.43404639 0.16060972 -0.09543436, -0.43446499 0.16064227 -0.095565848, -0.43445951 0.16058481 -0.095560722, -0.4344497 0.16052796 -0.095565848, -0.43478793 0.1606227 -0.095750622, -0.43478382 0.16054212 -0.095741682, -0.43476701 0.16046305 -0.095750622, -0.43505925 0.16060683 -0.095994644, -0.43505871 0.16050589 -0.095982842, -0.4350332 0.16040821 -0.095994644, -0.43525842 0.16059573 -0.096280985, -0.43526334 0.16047893 -0.096270137, -0.43522844 0.16036738 -0.096281104, -0.43537515 0.16058931 -0.096587472, -0.43542475 0.16052327 -0.096890859, -0.43538478 0.16046308 -0.096580915, -0.43534306 0.1603435 -0.096587799, -0.43541202 0.1605877 -0.10495778, -0.43542477 0.16052379 -0.10495778, -0.43542331 0.16045848 -0.10495778, -0.43540794 0.16039498 -0.10495778, -0.43537903 0.16033638 -0.10495778, -0.43528116 0.16028902 -0.10552039, -0.43535459 0.1604166 -0.1053917, -0.43528274 0.16033496 -0.10554766, -0.43535081 0.16036429 -0.10537191, -0.43522874 0.1602771 -0.10562872, -0.43516028 0.16024806 -0.1057223, -0.43517092 0.16019933 -0.10568412, -0.4352757 0.160383 -0.1055709, -0.43522 0.16032159 -0.10565578, -0.43527135 0.16024628 -0.10549041, -0.43533713 0.16031468 -0.10534965, -0.43522948 0.16023502 -0.10559761, -0.43517092 0.16015504 -0.10563966, -0.43525326 0.16020772 -0.10545754, -0.43531442 0.16026953 -0.10532569, -0.43522251 0.16019642 -0.10556316, -0.43516028 0.16011699 -0.10559105, -0.43520778 0.16016203 -0.10552593, -0.43539828 0.16054262 -0.10520171, -0.43540612 0.16048351 -0.10519301, -0.43540207 0.16042459 -0.10518261, -0.43538648 0.16036791 -0.10517045, -0.43534839 0.16047013 -0.10540839, -0.43535978 0.16031592 -0.10515722, -0.43381459 0.15877131 -0.1069368, -0.43382531 0.15880941 -0.10698544, -0.43382519 0.15885375 -0.10703, -0.43381441 0.15890244 -0.1070677, -0.43345034 0.15840599 -0.10780521, -0.43345463 0.15840763 -0.10764667, -0.43347889 0.1584477 -0.10765516, -0.43347794 0.15845783 -0.10780521, -0.43349594 0.15849061 -0.10766276, -0.43349493 0.15851401 -0.10780521, -0.43350631 0.15853627 -0.10767018, -0.43348706 0.15844047 -0.10748836, -0.43351018 0.15848047 -0.10750519, -0.43352601 0.15852359 -0.10752105, -0.43353426 0.15856935 -0.10753547, -0.43354118 0.15849495 -0.10733461, -0.43356216 0.15853466 -0.10735988, -0.43357539 0.15857802 -0.10738324, -0.43358058 0.15862414 -0.10740431, -0.43363196 0.15858687 -0.10716113, -0.4336499 0.15862614 -0.10719594, -0.43365869 0.15866978 -0.10722839, -0.4336586 0.15871674 -0.10725736, -0.4334951 0.15851502 -0.12297674, -0.43347791 0.15845878 -0.12297674, -0.4334501 0.15840679 -0.12297674, -0.43350244 0.15853247 -0.12307986, -0.43349183 0.15848696 -0.12308522, -0.43351871 0.15855177 -0.12318321, -0.43350947 0.15850626 -0.12319418, -0.43381453 0.15877225 -0.12384497, -0.43382525 0.15881036 -0.12379643, -0.43382517 0.15885463 -0.12375187, -0.43381453 0.15890338 -0.12371396, -0.43363219 0.15858781 -0.12362098, -0.43364984 0.15862699 -0.12358602, -0.43365884 0.1586708 -0.12355363, -0.4336586 0.15871757 -0.12352475, -0.43352515 0.15847996 -0.12340828, -0.43354675 0.15851952 -0.1233853, -0.43356103 0.1585629 -0.12336382, -0.43356702 0.15860888 -0.12334441, -0.43346894 0.15842301 -0.12321886, -0.43349266 0.15846302 -0.1232061, -0.43344998 0.1584039 -0.12309762, -0.43347421 0.15844388 -0.1230913, -0.43516028 0.16024907 -0.12505972, -0.43517095 0.16020051 -0.12509775, -0.43517095 0.16015613 -0.1251421, -0.43516028 0.160118 -0.12519082, -0.43540201 0.16042548 -0.12559843, -0.43535036 0.16036497 -0.12540913, -0.43535426 0.16041739 -0.12538922, -0.43540594 0.16048445 -0.12558782, -0.4354206 0.16050941 -0.12570524, -0.43541211 0.16058902 -0.12582386, -0.4354248 0.16052487 -0.12582386, -0.43539816 0.1605435 -0.125579, -0.43541068 0.1605711 -0.12570095, -0.43538651 0.16036896 -0.12561056, -0.43533713 0.16031569 -0.1254313, -0.43541759 0.16044715 -0.12571058, -0.43542337 0.16045955 -0.12582386, -0.4353596 0.16031688 -0.12562373, -0.43531427 0.16027047 -0.12545538, -0.43540174 0.16038693 -0.12571657, -0.43540794 0.16039625 -0.12582386, -0.43537354 0.16033138 -0.12572336, -0.435379 0.1603374 -0.12582386, -0.4352659 0.16037311 -0.12519383, -0.43527323 0.16032568 -0.12521812, -0.43527192 0.16028042 -0.12524593, -0.43526259 0.16023831 -0.12527704, -0.43534809 0.16047093 -0.12537265, -0.43524504 0.16020064 -0.12531051, -0.43541211 0.16058949 -0.13389102, -0.43542477 0.16052537 -0.13389102, -0.43542337 0.16046011 -0.13389102, -0.43540794 0.16039667 -0.13389081, -0.43537891 0.16033795 -0.13389102, -0.43405035 0.16064093 -0.13534871, -0.43405402 0.16066986 -0.13534752, -0.43444973 0.16053012 -0.13521582, -0.43445948 0.16058709 -0.13522094, -0.43446487 0.16064441 -0.13521573, -0.43476719 0.16046539 -0.13503096, -0.43478388 0.1605444 -0.13504019, -0.43478829 0.16062501 -0.13503096, -0.4350332 0.16041043 -0.13478723, -0.43505871 0.1605081 -0.13479891, -0.43505928 0.1606092 -0.13478726, -0.43522835 0.16036965 -0.13450077, -0.43526334 0.16048115 -0.13451165, -0.43525839 0.16059788 -0.13450077, -0.43534303 0.1603457 -0.1341942, -0.43538481 0.16046506 -0.13420096, -0.43537527 0.16059147 -0.1341942, 0.41699946 0.17496175 -0.13339022, 0.4234727 0.16962612 -0.13339037, 0.42039204 0.17496185 -0.13339022, 0.4234727 0.15545531 -0.1333912, 0.41925821 0.16045526 -0.13339096, 0.42345363 0.15545535 -0.1333912, 0.41699961 0.16045529 -0.13339096, 0.42039198 0.17496093 -0.11639004, 0.41699946 0.1749609 -0.1163901, 0.39899963 0.16045319 -0.097390912, 0.39899951 0.17495963 -0.097389929, 0.41499949 0.17495972 -0.097389929, 0.41499966 0.16045319 -0.097390674, 0.41499943 0.17496011 -0.10363992, 0.39899939 0.17496003 -0.10364001, 0.41499949 0.16783231 -0.10364031, 0.39899942 0.16783218 -0.10364031, 0.38749951 0.17290317 -0.098940097, 0.39549941 0.17290328 -0.10159, 0.39549947 0.17290324 -0.098940097, 0.38749951 0.17290321 -0.10159015, 0.38749951 0.16400328 -0.10159063, 0.39549959 0.16400331 -0.10159063, 0.38749945 0.16400318 -0.098940603, 0.39549965 0.16400315 -0.098940603, 0.39549947 0.17290504 -0.13184017, 0.38749957 0.16400498 -0.13184074, 0.39549962 0.16400498 -0.13184059, 0.38749945 0.17290495 -0.13183999, 0.38749951 0.16400494 -0.12919071, 0.39549959 0.16400497 -0.1291905, 0.38749939 0.17290485 -0.12919012, 0.39549947 0.17290483 -0.12919012, 0.39899939 0.17240337 -0.10109013, 0.39899945 0.17240326 -0.09944015, 0.39899963 0.1645034 -0.10109063, 0.39899957 0.16045383 -0.11101948, 0.39899957 0.16450325 -0.099440716, 0.39749947 0.17552586 -0.13506141, 0.39749944 0.17525116 -0.13515741, 0.39749938 0.17577231 -0.13490632, 0.3974995 0.17597811 -0.13470057, 0.39749944 0.1762291 -0.13417917, 0.39749944 0.17613301 -0.13445392, 0.39749944 0.17496182 -0.13518983, 0.39749947 0.17626174 -0.13388997, 0.39749944 0.17375852 -0.13230875, 0.39749944 0.17337368 -0.13269359, 0.3974995 0.17382082 -0.13223299, 0.39749956 0.17329799 -0.13275588, 0.3974995 0.17386705 -0.13214663, 0.39749944 0.17321154 -0.13280198, 0.3974995 0.17389542 -0.13205278, 0.39749944 0.17311768 -0.13283047, 0.39749938 0.17302021 -0.13283998, 0.3974995 0.17390507 -0.13195509, 0.39749944 0.17390491 -0.12907496, 0.39749941 0.17626131 -0.12663996, 0.39749944 0.17389537 -0.12897745, 0.39749944 0.17386688 -0.12888363, 0.39749944 0.17382069 -0.12879705, 0.39749944 0.17375842 -0.12872136, 0.39749944 0.17618211 -0.12629285, 0.39749944 0.17624132 -0.12646186, 0.39749947 0.17608678 -0.12614095, 0.39749938 0.17596023 -0.12601444, 0.39749944 0.17580839 -0.12591901, 0.39749956 0.17563921 -0.12585989, 0.39749944 0.17337351 -0.12833646, 0.3974995 0.17546122 -0.12584004, 0.39749944 0.17329769 -0.1282742, 0.3974995 0.17321122 -0.12822819, 0.3974995 0.17311756 -0.1281997, 0.3974995 0.1730199 -0.1281901, 0.39749953 0.16195525 -0.1351907, 0.3974995 0.16388999 -0.13284054, 0.39749968 0.16379251 -0.13283104, 0.39749962 0.16369864 -0.13280255, 0.3974995 0.16361225 -0.13275626, 0.39749944 0.16353643 -0.13269424, 0.39749968 0.16139117 -0.13506201, 0.3974995 0.16114467 -0.13490716, 0.39749962 0.16166598 -0.13515836, 0.39749956 0.16078395 -0.13445476, 0.39749953 0.16068779 -0.13418001, 0.39749956 0.16093875 -0.1347014, 0.39749944 0.16886885 -0.1258404, 0.39749956 0.16065517 -0.13389072, 0.39749953 0.16315147 -0.13230926, 0.3974995 0.16301468 -0.13205341, 0.39749956 0.16300505 -0.13195568, 0.39749953 0.16304302 -0.13214707, 0.39749956 0.16308931 -0.1322335, 0.39749947 0.16863477 -0.12581718, 0.3974995 0.16350475 -0.12819076, 0.39749947 0.16840971 -0.12574908, 0.3974995 0.16820221 -0.12563804, 0.3974995 0.16802041 -0.12548909, 0.39749956 0.16300476 -0.12869075, 0.39749965 0.16301739 -0.12857941, 0.39749965 0.16339356 -0.12820327, 0.3974995 0.16260582 -0.12007495, 0.3974995 0.16328792 -0.12824032, 0.39749965 0.16319311 -0.12829983, 0.39749965 0.16311395 -0.12837887, 0.3974995 0.16305438 -0.12847364, 0.3974995 0.16245657 -0.11989313, 0.39749956 0.16234571 -0.11968573, 0.39749953 0.16227734 -0.11946055, 0.39749956 0.17546013 -0.10494005, 0.39749941 0.17626008 -0.10413992, 0.39749956 0.17563808 -0.1049199, 0.39749944 0.17580725 -0.10486075, 0.39749944 0.17595884 -0.1047655, 0.39749944 0.17608559 -0.10463875, 0.39749941 0.17618093 -0.10448726, 0.3974995 0.17624 -0.10431799, 0.39749962 0.17337191 -0.10244354, 0.39749956 0.17375684 -0.10205858, 0.39749959 0.17381908 -0.10198288, 0.39749956 0.17329626 -0.10250591, 0.39749938 0.17386529 -0.10189664, 0.39749944 0.17320977 -0.10255208, 0.39749944 0.17389376 -0.10180276, 0.39749944 0.17311595 -0.10258063, 0.39749956 0.17301838 -0.10259005, 0.39749956 0.17390332 -0.1017051, 0.39749968 0.16886769 -0.10494041, 0.39749956 0.17625961 -0.096890025, 0.39749959 0.17390318 -0.09882497, 0.3974995 0.17389357 -0.098727547, 0.39749944 0.17386521 -0.098633729, 0.39749944 0.17381896 -0.098547153, 0.3974995 0.17375675 -0.098471455, 0.39749947 0.17622705 -0.096600793, 0.39749944 0.17577007 -0.095873527, 0.39749941 0.17613086 -0.096325897, 0.39749944 0.17597596 -0.096079282, 0.39749941 0.17552361 -0.095718674, 0.39749944 0.17524885 -0.095622621, 0.39749956 0.17495954 -0.095589899, 0.39749944 0.1733717 -0.098086469, 0.39749944 0.17329602 -0.098024301, 0.3974995 0.17320949 -0.097977929, 0.39749938 0.17311577 -0.097949646, 0.3974995 0.17301817 -0.097939901, 0.3974995 0.16801925 -0.10529193, 0.39749956 0.16350324 -0.10259043, 0.39749962 0.16820106 -0.10514244, 0.39749953 0.16840848 -0.10503169, 0.39749947 0.16863364 -0.10496341, 0.39749953 0.16260529 -0.11070632, 0.39749956 0.16339205 -0.10257816, 0.39749965 0.16328639 -0.10254117, 0.39749953 0.16319168 -0.10248157, 0.39749956 0.16311248 -0.10240232, 0.39749953 0.16305281 -0.10230752, 0.39749965 0.16234511 -0.11109554, 0.39749956 0.16245601 -0.11088824, 0.3974995 0.16301593 -0.10220199, 0.39749953 0.16314965 -0.098472051, 0.39749953 0.16065301 -0.09689083, 0.39749944 0.16353449 -0.098087035, 0.39749956 0.16308749 -0.098547809, 0.3974995 0.16304114 -0.098634325, 0.39749953 0.1630128 -0.098728083, 0.39749953 0.16300316 -0.098825507, 0.39749962 0.16300331 -0.10209074, 0.39749956 0.16227697 -0.11132064, 0.39749953 0.16195299 -0.095590644, 0.39749953 0.16388807 -0.097940706, 0.39749944 0.16379052 -0.097950183, 0.3974995 0.16369671 -0.097978674, 0.39749944 0.16361029 -0.098024778, 0.39749956 0.16166365 -0.095623426, 0.39749947 0.16068561 -0.096601628, 0.39749965 0.16093656 -0.096080326, 0.39749956 0.16138884 -0.095719509, 0.3974995 0.16114244 -0.095874362, 0.39749953 0.16078182 -0.096326731, 0.3974995 0.16225427 -0.11922654, 0.39749962 0.16225386 -0.11155485, 0.4254728 0.15825494 -0.097391032, 0.42547262 0.16615997 -0.097390585, 0.42836615 0.16114832 -0.097390734, 0.4169994 0.17495985 -0.097390078, 0.4203921 0.17495979 -0.097390078, 0.42347282 0.16962403 -0.097390436, 0.42347276 0.15545335 -0.097391121, 0.41925818 0.16045323 -0.097390823, 0.42345363 0.15545322 -0.097391121, 0.4169997 0.16045326 -0.097390912, 0.39899963 0.16045512 -0.13339084, 0.41499963 0.16045523 -0.13339081, 0.41499954 0.17496185 -0.13339022, 0.39899945 0.17496173 -0.13339022, 0.42547283 0.15825501 -0.10010015, 0.42836618 0.1611488 -0.10540279, 0.42699957 0.15978222 -0.10676955, 0.42349958 0.15628183 -0.1001003, 0.42699963 0.15978257 -0.11439087, 0.42349958 0.15628266 -0.11439099, 0.42699963 0.15978274 -0.11639076, 0.42699966 0.15978324 -0.12401211, 0.42349964 0.15628271 -0.11639103, 0.42836618 0.16114989 -0.1253787, 0.42547274 0.15825681 -0.13068151, 0.42836618 0.1611504 -0.13339081, 0.4254728 0.15825696 -0.13339084, 0.42349955 0.15628351 -0.13068151, 0.42039204 0.17496069 -0.1143901, 0.42347273 0.16962419 -0.1000995, 0.42699951 0.16351642 -0.11439072, 0.42699951 0.16351599 -0.10676952, 0.4254728 0.16616002 -0.10009985, 0.42347288 0.16962592 -0.13068104, 0.4254728 0.16616201 -0.13339046, 0.42547268 0.16616185 -0.13068104, 0.42699957 0.16351701 -0.12401202, 0.42699957 0.16351657 -0.11639076, 0.4169994 0.17496076 -0.1143901, 0.39899951 0.17496136 -0.12714002, 0.41499954 0.17496136 -0.12713993, 0.4169997 0.16045399 -0.1110196, 0.41699958 0.16045415 -0.11439093, 0.41699946 0.16668026 -0.10479265, 0.41699949 0.16689891 -0.1045148, 0.41699955 0.16704661 -0.10419356, 0.41699952 0.16711511 -0.10384702, 0.41699946 0.1671005 -0.10349392, 0.41699949 0.1670036 -0.10315391, 0.41699958 0.16682982 -0.10284599, 0.41699958 0.16658887 -0.10258742, 0.41699958 0.16683125 -0.12793505, 0.41699952 0.16659038 -0.12819371, 0.41699946 0.16700505 -0.12762704, 0.41699955 0.16710174 -0.12728712, 0.41699958 0.16711637 -0.12693393, 0.41699952 0.16704787 -0.12658703, 0.41699964 0.16690016 -0.12626588, 0.41699946 0.16668139 -0.12598825, 0.41699955 0.16045459 -0.11976223, 0.41699958 0.16045433 -0.11639094, 0.43033677 0.1602921 -0.12582386, 0.42558748 0.15554324 -0.13389125, 0.4303368 0.16029257 -0.13389072, 0.43013817 0.16009343 -0.12524164, 0.4302814 0.16023684 -0.12548041, 0.43021852 0.16017379 -0.12534532, 0.43032163 0.16027686 -0.1256375, 0.43033302 0.16028839 -0.12573025, 0.42879239 0.15874773 -0.12389588, 0.42867863 0.15863374 -0.12376558, 0.42858139 0.15853673 -0.12361907, 0.42848748 0.15844257 -0.12341379, 0.42843056 0.15838559 -0.12319645, 0.42841175 0.15836683 -0.12297695, 0.43013808 0.16009237 -0.10554015, 0.43018427 0.16013843 -0.10548686, 0.430226 0.16018015 -0.10542344, 0.43028176 0.1602359 -0.10530066, 0.43032181 0.16027592 -0.10514348, 0.4303368 0.16029093 -0.10495769, 0.42879242 0.15874663 -0.10688578, 0.42558748 0.15554114 -0.096891128, 0.42860448 0.1585587 -0.10712396, 0.42849433 0.15844864 -0.10734891, 0.42843276 0.15838709 -0.10757204, 0.42841697 0.15837122 -0.1076889, 0.42841163 0.15836604 -0.10780513, 0.4303368 0.16029045 -0.09689083, 0.42849961 0.16365007 -0.10780477, 0.42849964 0.15857901 -0.12297686, 0.42849952 0.16365078 -0.12297636, 0.42849952 0.15857819 -0.10780501, 0.42848873 0.16393739 -0.12366771, 0.42858446 0.16377185 -0.12388604, 0.42154676 0.17596194 -0.13388985, 0.4287498 0.16348542 -0.12415516, 0.43038458 0.16065469 -0.13389081, 0.42842007 0.16405654 -0.12343987, 0.42895141 0.16313627 -0.12439059, 0.42837906 0.16412757 -0.12320789, 0.42836559 0.16415088 -0.12297641, 0.43038458 0.16065422 -0.12582386, 0.42154685 0.17595981 -0.096890025, 0.42836571 0.16415004 -0.10780489, 0.42837617 0.16413176 -0.10759997, 0.42848772 0.16393839 -0.10711669, 0.42863506 0.16368319 -0.1068021, 0.43038452 0.16065252 -0.09689083, 0.43038458 0.16065302 -0.10495769, 0.42895144 0.16313528 -0.10639083, 0.42039204 0.17495973 -0.095389985, 0.41995761 0.16195311 -0.09539064, 0.42862514 0.16069995 -0.095390819, 0.42448401 0.1565588 -0.095391177, 0.39769945 0.17495954 -0.095389985, 0.39769951 0.161953 -0.09539064, 0.41549945 0.17546031 -0.10513993, 0.39769965 0.16886774 -0.10514023, 0.39769942 0.17546023 -0.10514008, 0.41549951 0.16886789 -0.10514032, 0.41549969 0.16274685 -0.11084779, 0.39769953 0.16274668 -0.11084794, 0.41549948 0.16816083 -0.10543319, 0.39769953 0.16816069 -0.1054331, 0.41549945 0.16245441 -0.11922639, 0.39769956 0.16245429 -0.11922639, 0.41549969 0.16245407 -0.11155485, 0.39769959 0.16245386 -0.11155485, 0.41549951 0.1681619 -0.1253475, 0.39769959 0.16274734 -0.11993369, 0.41549954 0.16274735 -0.11993348, 0.39769948 0.16816184 -0.1253475, 0.39769953 0.17546132 -0.12564, 0.41549951 0.168869 -0.12564027, 0.41549951 0.17546143 -0.12563992, 0.39769945 0.16886891 -0.12564027, 0.4164995 0.17646022 -0.10413983, 0.39769959 0.17645967 -0.096890025, 0.42068076 0.17645974 -0.096889995, 0.39769945 0.17646016 -0.10413992, 0.41649941 0.17646146 -0.12663993, 0.4206807 0.17646189 -0.13388982, 0.39769953 0.17646179 -0.13388997, 0.39769948 0.17646135 -0.12663996, 0.42862502 0.16070215 -0.13539073, 0.41995776 0.16195537 -0.13539067, 0.42039216 0.17496198 -0.13538998, 0.42448401 0.15656105 -0.13539127, 0.39769942 0.17496178 -0.13538986, 0.39769962 0.16195524 -0.13539067, 0.41549954 0.16831344 -0.12547183, 0.4154996 0.16848633 -0.12556434, 0.41549951 0.1686739 -0.12562117, 0.41549957 0.16247368 -0.11942142, 0.41549951 0.16253066 -0.11960917, 0.41549957 0.16262297 -0.11978202, 0.41549957 0.16253008 -0.11117207, 0.41549951 0.16262245 -0.11099934, 0.4154996 0.16247332 -0.11135974, 0.41549954 0.16867281 -0.10515963, 0.41549939 0.16848524 -0.10521647, 0.41549951 0.16831233 -0.105309, 0.42879239 0.15895976 -0.1236838, 0.43013805 0.16030562 -0.12502944, 0.42879248 0.16263628 -0.12368345, 0.43013808 0.16030449 -0.10575222, 0.42879242 0.15895893 -0.10709807, 0.42879248 0.16263543 -0.10709783, 0.41499954 0.16668011 -0.10479247, 0.41925812 0.16045536 -0.13389102, 0.39769959 0.16045526 -0.13389081, 0.41965038 0.1604543 -0.11639079, 0.41965026 0.16045421 -0.11439087, 0.39899954 0.16045447 -0.11976214, 0.41925818 0.16045323 -0.096890651, 0.39769956 0.16045316 -0.096890859, 0.41499949 0.16668127 -0.12598848, 0.39899948 0.16783349 -0.12714043, 0.41499954 0.16783355 -0.12714043, 0.39899957 0.17240478 -0.1296902, 0.39899945 0.17240506 -0.13134015, 0.39899951 0.164505 -0.13134074, 0.39899957 0.1645048 -0.12969065, 0.4253754 0.15545535 -0.13389117, 0.42527884 0.1554554 -0.13428968, 0.42535204 0.15545534 -0.13408926, 0.42384279 0.15545535 -0.13478845, 0.4245235 0.15545535 -0.13493165, 0.42476687 0.15545544 -0.1348117, 0.42434174 0.15545537 -0.13499549, 0.42415661 0.15545537 -0.13504246, 0.42362863 0.15545535 -0.1345109, 0.42498088 0.15545544 -0.13466027, 0.42350626 0.15545528 -0.13423637, 0.42346668 0.15545528 -0.13406324, 0.42515427 0.15545537 -0.1344834, 0.42345381 0.15545529 -0.13389105, 0.42349952 0.15545516 -0.13068181, 0.42347276 0.15545514 -0.13068178, 0.42349958 0.15545438 -0.11639114, 0.42349958 0.15545423 -0.11439111, 0.4253754 0.15545321 -0.096891217, 0.42349955 0.15545343 -0.10010048, 0.4252941 0.15545321 -0.096523933, 0.4253557 0.15545326 -0.096708916, 0.42516398 0.15545322 -0.096311234, 0.42347276 0.15545341 -0.10010036, 0.42345363 0.15545322 -0.096891128, 0.42348838 0.15545321 -0.096609764, 0.42495126 0.15545315 -0.096097402, 0.42359471 0.15545321 -0.096332036, 0.4246217 0.15545321 -0.095893644, 0.42376977 0.15545312 -0.096074007, 0.42394912 0.15545319 -0.095893882, 0.42415676 0.15545313 -0.095739864, 0.39769959 0.16867271 -0.10515963, 0.39769962 0.16848499 -0.10521647, 0.39769959 0.16831215 -0.10530885, 0.39769959 0.16262233 -0.11099934, 0.39769956 0.16253002 -0.11117207, 0.39769962 0.16247314 -0.11135995, 0.39769962 0.16247356 -0.11942153, 0.39769953 0.16253048 -0.1196092, 0.39769953 0.16262293 -0.11978202, 0.39769951 0.16831324 -0.1254718, 0.39769951 0.16848621 -0.12556419, 0.39769951 0.16867392 -0.12562105, 0.39769942 0.17643495 -0.10436257, 0.41617778 0.17640701 -0.10446178, 0.39769953 0.17636105 -0.10457372, 0.41592389 0.17627797 -0.10471534, 0.39769942 0.1762419 -0.10476359, 0.41572595 0.17609394 -0.10491353, 0.39769945 0.17608365 -0.10492169, 0.41560736 0.17591205 -0.10503184, 0.39769953 0.17589404 -0.10504093, 0.41553676 0.17573066 -0.1051028, 0.39769948 0.17568262 -0.10511481, 0.41550839 0.1755936 -0.10513099, 0.41550851 0.17559469 -0.12564886, 0.4155367 0.17573175 -0.12567714, 0.41560733 0.1759132 -0.1257478, 0.41572589 0.17609501 -0.12586632, 0.41592395 0.17627916 -0.12606439, 0.41617778 0.17640823 -0.12631842, 0.39769945 0.17568377 -0.12566507, 0.39769953 0.17589505 -0.12573907, 0.39769948 0.17608483 -0.12585816, 0.39769948 0.17624313 -0.12601647, 0.39769948 0.17636228 -0.12620595, 0.39769942 0.17643635 -0.12641749, 0.42850032 0.16364825 -0.12301566, 0.42850277 0.16364011 -0.12305521, 0.42850447 0.15858521 -0.12307473, 0.42851222 0.16360714 -0.12313461, 0.42852658 0.16355741 -0.12320706, 0.4285191 0.15860437 -0.12317344, 0.42855409 0.16346173 -0.1233023, 0.42856312 0.15866165 -0.12332769, 0.42863417 0.16318423 -0.1234779, 0.42864794 0.15877175 -0.12350067, 0.43020239 0.16037437 -0.12510377, 0.42889807 0.16277918 -0.1238256, 0.43025923 0.16043894 -0.12519166, 0.4289614 0.16291478 -0.12399685, 0.43033174 0.16053064 -0.12535998, 0.4303779 0.16060674 -0.12557352, 0.42897964 0.16303588 -0.12418853, 0.42848447 0.16382445 -0.12297636, 0.42849538 0.16377172 -0.12307378, 0.4285087 0.16373898 -0.12317189, 0.42847091 0.16389892 -0.12309333, 0.42843926 0.16399296 -0.12297641, 0.42852926 0.16368884 -0.12326216, 0.42848712 0.16386651 -0.12321075, 0.42842984 0.16402175 -0.12311327, 0.42851198 0.16381669 -0.12331899, 0.42844808 0.16398928 -0.12325116, 0.42857736 0.16357116 -0.12340152, 0.42847589 0.16393945 -0.12337848, 0.42857054 0.16369992 -0.12348603, 0.42854106 0.16382247 -0.12357505, 0.42867953 0.16332065 -0.12358849, 0.42869475 0.16345134 -0.12371086, 0.42867994 0.16357358 -0.12384196, 0.4284845 0.16382366 -0.10780477, 0.42843935 0.16399203 -0.10780489, 0.43024927 0.16042596 -0.10560774, 0.42889798 0.16277826 -0.10695561, 0.43033135 0.16052923 -0.10542258, 0.4289614 0.16291377 -0.10678457, 0.43037778 0.16060534 -0.10520896, 0.42897952 0.16303492 -0.10659274, 0.43038702 0.16063422 -0.1050837, 0.42863435 0.16318336 -0.10730358, 0.42850029 0.16364734 -0.10776531, 0.42867962 0.16331968 -0.10719278, 0.4286947 0.16345055 -0.10707041, 0.42867982 0.16357259 -0.10693919, 0.42856753 0.16359442 -0.10740387, 0.42855427 0.16346091 -0.10747888, 0.42852652 0.16355652 -0.10757407, 0.42855859 0.16372295 -0.10732397, 0.42852777 0.16384555 -0.10723998, 0.42850867 0.16373819 -0.10760929, 0.42851228 0.16360629 -0.10764646, 0.42849526 0.16377087 -0.10770734, 0.42850274 0.1636392 -0.10772597, 0.42848712 0.16386566 -0.10757052, 0.42847094 0.16389807 -0.10768809, 0.42844805 0.16398844 -0.10753023, 0.42842984 0.1640209 -0.10766803, 0.42850786 0.15858898 -0.10767638, 0.42853332 0.15862201 -0.10754766, 0.42857569 0.158677 -0.10742234, 0.42863432 0.15875326 -0.10730373, 0.42870736 0.1588483 -0.10719474, 0.42142382 0.17613104 -0.13388985, 0.42142391 0.17612886 -0.096889995, 0.42126843 0.17627095 -0.13388985, 0.42126864 0.17626874 -0.096889995, 0.4210875 0.17637552 -0.13388985, 0.42108756 0.17637335 -0.096889876, 0.4208886 0.17644009 -0.13389018, 0.42088866 0.17643802 -0.096890025, 0.42051968 0.16017656 -0.11439087, 0.42075136 0.15997286 -0.11439087, 0.42093652 0.15972596 -0.11439093, 0.42025116 0.16032858 -0.11439087, 0.41995713 0.16042259 -0.11439087, 0.42075145 0.15997289 -0.11639076, 0.42051974 0.16017662 -0.11639076, 0.4209365 0.15972613 -0.11639103, 0.42025107 0.16032867 -0.11639079, 0.41995728 0.16042264 -0.11639088, 0.42886049 0.16064595 -0.1353766, 0.42446423 0.156106 -0.13535932, 0.42910245 0.16058806 -0.13533142, 0.42444509 0.15567029 -0.13526469, 0.42944187 0.16050681 -0.13520911, 0.42489102 0.15562069 -0.13504961, 0.42975268 0.16043243 -0.13501945, 0.42519766 0.15558653 -0.13479927, 0.43000987 0.16037104 -0.13477251, 0.42541081 0.15556294 -0.13452142, 0.43019575 0.16032641 -0.1344873, 0.42553216 0.15554935 -0.13424939, 0.43030328 0.16030064 -0.134186, 0.425574 0.15554474 -0.13406914, 0.4215405 0.17595656 -0.13404483, 0.43035591 0.16065547 -0.13416004, 0.42152119 0.1759398 -0.13420397, 0.43026438 0.16065791 -0.13443559, 0.42144537 0.1758741 -0.13450459, 0.43008697 0.16066279 -0.13472536, 0.42131674 0.1757628 -0.1347883, 0.42983431 0.16066971 -0.1349805, 0.42114064 0.17561035 -0.13503209, 0.4294855 0.16067898 -0.13519913, 0.42092925 0.17542723 -0.13521776, 0.42905438 0.16069067 -0.13534564, 0.42067379 0.1752059 -0.13534451, 0.42046249 0.17532806 -0.13534465, 0.42067927 0.17645393 -0.13404471, 0.42061132 0.17561932 -0.13523385, 0.42052644 0.17565989 -0.13521776, 0.42057925 0.17593446 -0.13503209, 0.42077321 0.17552996 -0.13524166, 0.42077953 0.17611982 -0.13482317, 0.42062336 0.17616324 -0.1347883, 0.42065534 0.17633024 -0.13450468, 0.42107105 0.17597494 -0.13484076, 0.42087588 0.17640309 -0.13422316, 0.42067432 0.17642868 -0.13420382, 0.42124534 0.17623606 -0.13423315, 0.42109925 0.17618684 -0.13455525, 0.39769945 0.17642412 -0.13422373, 0.39769945 0.17631319 -0.13454083, 0.39769948 0.1761346 -0.13482529, 0.39769953 0.17589708 -0.13506275, 0.39769948 0.1756127 -0.13524154, 0.39769948 0.17529555 -0.1353524, 0.42446417 0.15610372 -0.095423006, 0.42904291 0.16059992 -0.095436238, 0.42444515 0.15566801 -0.095517419, 0.42946213 0.16049963 -0.095582508, 0.42475665 0.15563338 -0.095653318, 0.42980161 0.16041854 -0.095801316, 0.42504013 0.15560186 -0.095839761, 0.43004739 0.16035968 -0.096056275, 0.42527664 0.15557562 -0.09607067, 0.4254508 0.15555632 -0.096333437, 0.43021995 0.16031848 -0.096346073, 0.42555434 0.15554483 -0.096612595, 0.430309 0.1602971 -0.096621566, 0.43035004 0.16065359 -0.096595578, 0.42151874 0.17593534 -0.096561156, 0.43023938 0.16065659 -0.096294574, 0.42142826 0.17585719 -0.096228056, 0.43004844 0.16066161 -0.096009068, 0.42127329 0.17572281 -0.095920585, 0.42978394 0.1606687 -0.095762216, 0.42106307 0.17554086 -0.095669203, 0.42946473 0.16067725 -0.095572524, 0.42081708 0.17532784 -0.095495336, 0.42911577 0.16068672 -0.095450304, 0.42060214 0.17514178 -0.095415048, 0.42886701 0.16069342 -0.095405035, 0.42044461 0.17523269 -0.095415018, 0.42067385 0.1764233 -0.096561126, 0.42075425 0.17536816 -0.095484786, 0.42069179 0.17540625 -0.095479779, 0.42062896 0.17544268 -0.095479779, 0.42055988 0.17583133 -0.095669173, 0.42056477 0.17547765 -0.095484875, 0.42049831 0.17551182 -0.095495246, 0.42116046 0.17582808 -0.095886819, 0.42103583 0.17591994 -0.095869832, 0.42090172 0.17599735 -0.095869921, 0.42075998 0.17605938 -0.095886759, 0.42061234 0.17610438 -0.095920704, 0.42130703 0.1759951 -0.096194647, 0.4211641 0.17611197 -0.0961776, 0.42100388 0.17620441 -0.09617772, 0.42083123 0.17626977 -0.096194647, 0.42065111 0.17630585 -0.096228056, 0.42139584 0.17609653 -0.096540831, 0.42124307 0.17623065 -0.09653046, 0.42106712 0.17633227 -0.09653046, 0.42087471 0.17639746 -0.096541069, 0.39769953 0.17529333 -0.095427446, 0.39769948 0.17561038 -0.0955384, 0.39769942 0.17589474 -0.095717005, 0.39769942 0.17613232 -0.095954679, 0.39769948 0.17631103 -0.096239023, 0.39769953 0.17642206 -0.09655609, 0.41984123 0.16170578 -0.13536987, 0.39769953 0.16162148 -0.13535303, 0.41972187 0.16144991 -0.13530317, 0.39769956 0.1613044 -0.13524213, 0.41959867 0.16118555 -0.1351783, 0.39769953 0.16101997 -0.13506344, 0.41948646 0.16094509 -0.13499954, 0.39769962 0.16078253 -0.13482603, 0.41939282 0.16074398 -0.13477546, 0.39769953 0.16060379 -0.13454166, 0.41932273 0.16059364 -0.13452008, 0.39769965 0.16049273 -0.13422456, 0.41927516 0.16049184 -0.13421968, 0.41926938 0.16047753 -0.096621446, 0.39769959 0.16049066 -0.096556924, 0.41930592 0.16055577 -0.096346043, 0.39769956 0.16060151 -0.096239857, 0.41937634 0.16070674 -0.096056275, 0.39769953 0.16078024 -0.095955603, 0.41947678 0.16092215 -0.095801257, 0.39769956 0.1610177 -0.09571787, 0.41961557 0.16121961 -0.095582329, 0.39769956 0.16130219 -0.095539175, 0.41978696 0.1615871 -0.095436029, 0.39769953 0.16161908 -0.095428281, 0.39765495 0.17589158 -0.095720939, 0.39765495 0.17612837 -0.095957778, 0.39761263 0.17611678 -0.095966958, 0.39757478 0.17637947 -0.096565865, 0.39754319 0.17638436 -0.096890025, 0.3975431 0.17634866 -0.096572958, 0.39761269 0.17560185 -0.095556282, 0.39757478 0.17586757 -0.095751248, 0.39757478 0.17559142 -0.09557762, 0.39761275 0.17588243 -0.095732532, 0.39754313 0.17624323 -0.096271776, 0.39751929 0.17631161 -0.096581481, 0.39751923 0.17620903 -0.096288227, 0.39757484 0.17528374 -0.095470212, 0.39754319 0.17495956 -0.095465116, 0.39757484 0.17495956 -0.095433764, 0.39754313 0.17527665 -0.095500968, 0.39754307 0.17557774 -0.095606349, 0.39751923 0.17604375 -0.096025161, 0.39750445 0.176171 -0.096306585, 0.39750451 0.17601073 -0.096051596, 0.39765498 0.17560822 -0.095542841, 0.39750445 0.17579779 -0.095838688, 0.39761269 0.17528893 -0.095446788, 0.39761263 0.17495956 -0.095409863, 0.39761266 0.17640275 -0.096560501, 0.39761272 0.1764399 -0.096889995, 0.39757478 0.17641605 -0.096890025, 0.39765501 0.17529224 -0.095432542, 0.39765498 0.17495954 -0.095394902, 0.39757484 0.17627162 -0.096257977, 0.39754319 0.1760734 -0.096001558, 0.39751932 0.17582418 -0.095805876, 0.39765495 0.17641711 -0.096557073, 0.39765501 0.17645459 -0.096889995, 0.39750457 0.17554291 -0.095678382, 0.39761269 0.17629319 -0.096247606, 0.39757478 0.17609824 -0.095981978, 0.39754325 0.17584792 -0.095776014, 0.39751929 0.17556132 -0.095640562, 0.39765495 0.1763065 -0.096241258, 0.39750451 0.17525883 -0.09557908, 0.39750451 0.17495954 -0.095545463, 0.39750451 0.17627044 -0.09659069, 0.39750457 0.17630421 -0.096890025, 0.39751929 0.17634645 -0.096890025, 0.39751923 0.17526814 -0.095537953, 0.39751929 0.17495954 -0.095503144, 0.39750466 0.16195302 -0.095546298, 0.39751932 0.16195296 -0.095503949, 0.39754313 0.16195293 -0.095465951, 0.39757481 0.16195299 -0.09543436, 0.39761269 0.16195303 -0.095410399, 0.39765507 0.16195297 -0.095395736, 0.39750457 0.17630459 -0.10413989, 0.39751929 0.17634681 -0.10413989, 0.3975431 0.17638478 -0.10413992, 0.39757484 0.17641646 -0.10413992, 0.39761281 0.17644021 -0.10413983, 0.39765486 0.17645502 -0.10413992, 0.39757493 0.16053309 -0.096566699, 0.39754316 0.16052838 -0.096890859, 0.3975749 0.1604967 -0.096890859, 0.39754316 0.16133481 -0.095607094, 0.39754319 0.16163595 -0.095501713, 0.39751935 0.1616444 -0.095538788, 0.39754313 0.1606694 -0.09627261, 0.39754322 0.16056414 -0.096573763, 0.39751929 0.16135126 -0.095641308, 0.39757487 0.16064088 -0.096258812, 0.39765507 0.16060615 -0.096242242, 0.39751941 0.16108833 -0.095806621, 0.3975046 0.16136964 -0.095679425, 0.39765507 0.16078421 -0.095958643, 0.39761272 0.16079578 -0.095967703, 0.39761281 0.16061945 -0.09624856, 0.39750454 0.16111472 -0.095839553, 0.39761281 0.16050991 -0.096561365, 0.39761281 0.16047283 -0.096890859, 0.39750457 0.16090184 -0.09605258, 0.39765507 0.16049553 -0.096558116, 0.39765507 0.16045809 -0.096890859, 0.39761272 0.16162363 -0.095447622, 0.39757481 0.16162887 -0.095470838, 0.39757484 0.16132116 -0.095578693, 0.39754319 0.16106467 -0.095776848, 0.39751932 0.16086875 -0.096026115, 0.39765516 0.16162033 -0.095433377, 0.39750466 0.1607417 -0.096307419, 0.39761275 0.16131073 -0.095557027, 0.39757484 0.16104488 -0.095752023, 0.39754322 0.1608391 -0.096002392, 0.39751938 0.16070354 -0.096289091, 0.39765507 0.1613043 -0.095543884, 0.39750463 0.16064225 -0.096591733, 0.39750457 0.16060859 -0.09689083, 0.39761272 0.16103011 -0.095733546, 0.39757493 0.16081434 -0.095982604, 0.39750454 0.16165382 -0.095580034, 0.39751932 0.160601 -0.096582316, 0.39751941 0.16056623 -0.09689083, 0.39765498 0.16102082 -0.095721893, 0.39761275 0.17634319 -0.10456514, 0.39761266 0.17622641 -0.10475098, 0.39757484 0.17620786 -0.10473632, 0.39757484 0.17567295 -0.10507222, 0.39754313 0.17546017 -0.10506474, 0.39754307 0.17566593 -0.10504159, 0.39757478 0.17632166 -0.10455476, 0.39754316 0.17586133 -0.10497304, 0.39751929 0.17565742 -0.10500454, 0.39757481 0.17639247 -0.10435271, 0.39754319 0.17629319 -0.10454126, 0.39754313 0.17636158 -0.10434567, 0.39751932 0.17584486 -0.10493886, 0.39750445 0.17546023 -0.1049844, 0.39765498 0.17635649 -0.10457169, 0.39751929 0.17601293 -0.10483321, 0.39750445 0.17582655 -0.10490095, 0.39750451 0.17598665 -0.10480022, 0.39765495 0.17623794 -0.10476031, 0.39761269 0.17641564 -0.10435804, 0.39750439 0.17612031 -0.10466634, 0.39765489 0.17643005 -0.1043615, 0.39761272 0.17567825 -0.1050955, 0.39761263 0.17546025 -0.10512017, 0.39757469 0.17546023 -0.10509642, 0.39757475 0.1758751 -0.10500144, 0.39754313 0.1760367 -0.10486283, 0.39751929 0.17615338 -0.10469278, 0.39765501 0.17568158 -0.10510992, 0.39765495 0.17546013 -0.10513484, 0.39750451 0.17622088 -0.10450637, 0.39761269 0.17588538 -0.10502302, 0.39757478 0.17605639 -0.10488745, 0.39754307 0.17618303 -0.10471638, 0.39751929 0.17625904 -0.10452472, 0.39765507 0.17589189 -0.10503634, 0.39750433 0.17628334 -0.10432785, 0.39761269 0.1760713 -0.10490616, 0.39750448 0.17564808 -0.10496315, 0.39751923 0.17546014 -0.1050268, 0.39751929 0.17632455 -0.1043373, 0.39765495 0.17608044 -0.10491785, 0.39750457 0.16061069 -0.13389072, 0.39751932 0.16056849 -0.13389081, 0.39754322 0.16053042 -0.13389072, 0.39757481 0.16049883 -0.13389081, 0.39761281 0.16047502 -0.13389081, 0.39765507 0.16046017 -0.13389081, 0.39750457 0.16886769 -0.10498472, 0.39751932 0.16886777 -0.10502716, 0.39754319 0.16886775 -0.10506507, 0.3975749 0.16886775 -0.10509669, 0.39761275 0.16886775 -0.10512062, 0.39765504 0.16886775 -0.10513528, 0.39761281 0.16131303 -0.13522437, 0.39761278 0.16103245 -0.13504797, 0.39757487 0.1610471 -0.13502938, 0.39757487 0.16132338 -0.13520283, 0.39754313 0.16067152 -0.13450885, 0.39754322 0.1605662 -0.13420787, 0.39751932 0.16060318 -0.13419932, 0.39757487 0.16163118 -0.13531068, 0.39754313 0.16195518 -0.13531548, 0.39757487 0.16195524 -0.13534707, 0.39751941 0.16070573 -0.13449243, 0.39754322 0.16163822 -0.13527963, 0.39754316 0.16133705 -0.13517433, 0.3976551 0.16130657 -0.1352376, 0.3976551 0.16102307 -0.13505965, 0.39751932 0.16087104 -0.13475543, 0.39750457 0.16074379 -0.1344741, 0.39750457 0.16090406 -0.13472906, 0.39761278 0.16162588 -0.13533375, 0.39761275 0.16195515 -0.13537088, 0.39750466 0.16111685 -0.13494197, 0.39765504 0.16162254 -0.13534814, 0.39765495 0.16195525 -0.13538578, 0.39761281 0.1605121 -0.13422027, 0.39757484 0.16053534 -0.13421482, 0.39757496 0.16064306 -0.13452271, 0.39754313 0.16084139 -0.13477913, 0.39751923 0.16109057 -0.13497511, 0.39765507 0.16049761 -0.1342234, 0.39750454 0.16137186 -0.13510221, 0.39761278 0.16062166 -0.13453308, 0.39750454 0.16195521 -0.13523528, 0.39757487 0.16081659 -0.13479874, 0.39754319 0.1610669 -0.13500449, 0.39751935 0.16135354 -0.13514012, 0.39765507 0.16060832 -0.13453943, 0.39750457 0.1616561 -0.1352016, 0.39761278 0.16079809 -0.13481373, 0.3975046 0.16064437 -0.13418978, 0.39751938 0.16164662 -0.13524279, 0.39751932 0.16195524 -0.13527754, 0.3976551 0.16078644 -0.13482291, 0.39754313 0.16845623 -0.105147, 0.39754319 0.168658 -0.10508581, 0.39757487 0.16866416 -0.10511672, 0.39757487 0.16846839 -0.10517608, 0.39757484 0.16828795 -0.1052724, 0.39761287 0.16814657 -0.10541912, 0.39757487 0.16812977 -0.10540234, 0.39761272 0.16847748 -0.10519811, 0.39761272 0.16830114 -0.10529231, 0.39750451 0.1686424 -0.10500704, 0.39751935 0.16865057 -0.1050485, 0.39751935 0.16844176 -0.10511183, 0.39754307 0.16827029 -0.1052463, 0.39754322 0.16810739 -0.10537996, 0.39750466 0.16842556 -0.10507288, 0.39751935 0.16824923 -0.10521468, 0.39751935 0.16808057 -0.10535311, 0.39750457 0.16822577 -0.10517963, 0.39750454 0.16805069 -0.10532343, 0.39765501 0.16867167 -0.1051546, 0.39761287 0.16866881 -0.10513993, 0.39765501 0.16848315 -0.10521173, 0.39765507 0.16830938 -0.10530471, 0.39765501 0.16815704 -0.10542964, 0.39750445 0.17496184 -0.13523445, 0.39751929 0.17496182 -0.13527676, 0.39754313 0.17496179 -0.13531476, 0.39757478 0.17496176 -0.13534632, 0.39761269 0.17496173 -0.13537028, 0.39765501 0.17496182 -0.13538498, 0.39750451 0.1626368 -0.11073773, 0.39751941 0.16266665 -0.11076774, 0.39754313 0.16269349 -0.11079454, 0.3975749 0.16271585 -0.11081683, 0.39761275 0.16273274 -0.11083367, 0.39765495 0.16274323 -0.11084443, 0.39757469 0.1763816 -0.1342141, 0.39754307 0.17638637 -0.13388985, 0.39757478 0.17641813 -0.13388997, 0.39754307 0.17557991 -0.13517362, 0.39751923 0.17527039 -0.13524204, 0.39751929 0.1755636 -0.13513964, 0.39757487 0.17627396 -0.13452187, 0.39754307 0.17624536 -0.13450807, 0.39754301 0.17635068 -0.13420704, 0.39754313 0.17527886 -0.13527903, 0.39765501 0.17630868 -0.13453859, 0.39751923 0.17582646 -0.13497427, 0.39750451 0.17554514 -0.13510147, 0.39765501 0.17613067 -0.13482219, 0.39761272 0.17611907 -0.13481274, 0.39761266 0.1762954 -0.13453224, 0.39750445 0.17580009 -0.13494113, 0.39761266 0.17640477 -0.13421932, 0.39761269 0.17644194 -0.13388985, 0.39750454 0.17601296 -0.13472822, 0.39765489 0.17641918 -0.13422257, 0.39765501 0.17645673 -0.13388985, 0.39761275 0.17529115 -0.13533315, 0.39757478 0.17528586 -0.13530985, 0.39757478 0.17559372 -0.13520199, 0.39754313 0.17585015 -0.13500375, 0.39751923 0.17604598 -0.13475439, 0.39765486 0.17529447 -0.13534755, 0.39750451 0.17617317 -0.13447338, 0.39761269 0.17560408 -0.13522378, 0.39757478 0.17586985 -0.13502854, 0.3975431 0.17607576 -0.13477829, 0.39751929 0.17621115 -0.13449174, 0.39765495 0.17561042 -0.13523677, 0.39750445 0.17627253 -0.13418916, 0.39750457 0.17630623 -0.13388997, 0.39761269 0.17588475 -0.13504726, 0.39757478 0.17610048 -0.13479805, 0.39750445 0.17526099 -0.1352008, 0.39751923 0.17631373 -0.13419849, 0.39751923 0.17634855 -0.13388985, 0.39765495 0.1758939 -0.1350587, 0.39757484 0.16243039 -0.11135115, 0.39761275 0.16243398 -0.11155485, 0.39757496 0.1624102 -0.11155485, 0.39761281 0.16245365 -0.11135589, 0.39761281 0.16251175 -0.11116465, 0.39757493 0.16248973 -0.11115562, 0.39750454 0.16249314 -0.11091303, 0.39751935 0.16252822 -0.1109364, 0.39751941 0.16242535 -0.11112892, 0.39754313 0.16255975 -0.11095741, 0.39754319 0.16246048 -0.11114349, 0.39754325 0.1623992 -0.11134505, 0.39754319 0.16237859 -0.11155485, 0.39750454 0.16238627 -0.11111271, 0.39751938 0.1623621 -0.11133771, 0.39751938 0.16234061 -0.11155485, 0.39750469 0.16232061 -0.11132943, 0.39750457 0.16229837 -0.11155479, 0.39765495 0.16261812 -0.11099663, 0.39761281 0.16260587 -0.11098837, 0.39765507 0.16252539 -0.11117028, 0.39757487 0.16258609 -0.11097514, 0.39765507 0.16246819 -0.11135887, 0.39765513 0.1624489 -0.11155485, 0.39750445 0.17630592 -0.12663996, 0.39751929 0.17634815 -0.12663993, 0.39754313 0.17638604 -0.12663993, 0.39757478 0.17641775 -0.12663993, 0.39761272 0.17644162 -0.12663984, 0.39765495 0.17645629 -0.12663984, 0.39750457 0.16229884 -0.11922642, 0.39751935 0.16234106 -0.11922642, 0.39754319 0.16237904 -0.11922642, 0.3975749 0.16241069 -0.11922642, 0.39761281 0.16243441 -0.11922642, 0.39765507 0.16244924 -0.11922642, 0.39757484 0.17567407 -0.12570763, 0.39754304 0.17546125 -0.12571537, 0.39757478 0.17546135 -0.12568367, 0.39754304 0.17629445 -0.12623882, 0.39751932 0.17632593 -0.12644279, 0.39751929 0.17626023 -0.12625515, 0.39757472 0.17587619 -0.12577829, 0.39754313 0.17586248 -0.12580672, 0.39754313 0.17566703 -0.12573847, 0.39754307 0.17636292 -0.12643412, 0.39765507 0.17589304 -0.12574351, 0.39751932 0.1761546 -0.12608695, 0.39750436 0.17622216 -0.12627348, 0.39765489 0.17608158 -0.12586197, 0.39761269 0.17607233 -0.12587357, 0.39761269 0.17588641 -0.12575674, 0.39750445 0.17612152 -0.12611341, 0.39761269 0.17567927 -0.12568426, 0.39761281 0.17546129 -0.1256597, 0.39750448 0.17598791 -0.12597963, 0.39765507 0.17568268 -0.12566996, 0.39765495 0.17546117 -0.12564516, 0.39761263 0.17641696 -0.12642169, 0.39757478 0.17639381 -0.12642705, 0.39757478 0.176323 -0.12622476, 0.3975431 0.17618433 -0.12606335, 0.39751929 0.17601416 -0.1259464, 0.39765486 0.17643146 -0.12641847, 0.39750445 0.17582768 -0.12587896, 0.39761272 0.17634447 -0.12621459, 0.39757472 0.17620908 -0.12604365, 0.39754301 0.17603788 -0.12591693, 0.39751929 0.17584598 -0.12584069, 0.39765495 0.17635779 -0.12620822, 0.39750457 0.17564912 -0.12581658, 0.39750451 0.17546126 -0.12579551, 0.39761263 0.17622767 -0.12602887, 0.39757484 0.17605752 -0.12589204, 0.39750445 0.1762847 -0.126452, 0.39751923 0.17565854 -0.12577543, 0.39751929 0.17546123 -0.12575325, 0.39765495 0.17623925 -0.1260196, 0.3975749 0.1625866 -0.11980628, 0.39757484 0.16271643 -0.11996432, 0.39754319 0.16269402 -0.119987, 0.3975749 0.16249013 -0.11962586, 0.39761275 0.16251214 -0.11961671, 0.39761281 0.16260648 -0.11979305, 0.39750454 0.162321 -0.11945193, 0.39751938 0.16236249 -0.1194435, 0.39751932 0.16242594 -0.11965262, 0.39754319 0.16239969 -0.1194362, 0.39754313 0.16246091 -0.11963805, 0.39754313 0.16256039 -0.11982387, 0.39751929 0.16266724 -0.12001356, 0.39750466 0.16238686 -0.11966871, 0.39751947 0.16252868 -0.119845, 0.39750451 0.16263731 -0.12004345, 0.39750463 0.16249366 -0.1198686, 0.39765507 0.16274373 -0.11993726, 0.39765507 0.16246855 -0.11942252, 0.39761275 0.16245414 -0.11942538, 0.3976551 0.16252585 -0.1196112, 0.39757484 0.16243078 -0.11943009, 0.39765507 0.1626187 -0.11978488, 0.39761275 0.16273332 -0.11994775, 0.39750451 0.1688689 -0.12579581, 0.39751935 0.16886891 -0.12575352, 0.39754313 0.16886893 -0.12571546, 0.3975749 0.16886897 -0.12568411, 0.39761275 0.16886888 -0.12566006, 0.39765501 0.16886893 -0.12564531, 0.39750442 0.1680519 -0.12545753, 0.39751923 0.16808172 -0.1254276, 0.39754322 0.16810852 -0.12540063, 0.39757481 0.16813093 -0.12537825, 0.39761278 0.1681478 -0.12536132, 0.39765495 0.1681582 -0.12535092, 0.39754307 0.1684573 -0.12563381, 0.39757478 0.16828902 -0.12550804, 0.39757484 0.16846947 -0.12560448, 0.39754298 0.16827148 -0.1255343, 0.39757484 0.16866533 -0.12566397, 0.39761269 0.16866998 -0.12564051, 0.39761278 0.16847864 -0.12558258, 0.39750451 0.16822694 -0.12560096, 0.39751929 0.16825044 -0.12556595, 0.39751935 0.16844286 -0.12566885, 0.39754319 0.16865918 -0.12569499, 0.39750457 0.16842659 -0.12570786, 0.39751923 0.16865179 -0.12573215, 0.39750454 0.16864349 -0.12577367, 0.39765501 0.16831055 -0.12547609, 0.39761275 0.16830243 -0.12548828, 0.39765501 0.16848437 -0.12556881, 0.39765501 0.16867286 -0.12562606, 0.39699966 0.16300333 -0.10209074, 0.39699966 0.16301592 -0.10220178, 0.39699957 0.16305283 -0.10230752, 0.3969996 0.16311234 -0.10240232, 0.39699963 0.16319156 -0.10248157, 0.3969996 0.16328648 -0.10254111, 0.39699966 0.16339205 -0.10257804, 0.39699963 0.16350335 -0.10259049, 0.39699954 0.17301838 -0.1025902, 0.39699948 0.17311607 -0.10258042, 0.39699954 0.17320977 -0.10255193, 0.39699948 0.17329629 -0.10250577, 0.39699948 0.17337197 -0.10244354, 0.39699954 0.17375688 -0.10205858, 0.39699954 0.17381917 -0.10198294, 0.39699948 0.17386527 -0.10189649, 0.39699954 0.17389382 -0.10180255, 0.39699948 0.17390335 -0.10170519, 0.39699954 0.17390321 -0.098824911, 0.39699948 0.17389359 -0.098727547, 0.39699954 0.17386512 -0.098633729, 0.39699948 0.1738189 -0.098547153, 0.39699954 0.1737567 -0.098471455, 0.39699948 0.17337181 -0.098086409, 0.39699948 0.17329606 -0.098024301, 0.39699942 0.17320956 -0.097978137, 0.39699954 0.17311575 -0.097949646, 0.39699954 0.17301822 -0.09794011, 0.39699954 0.1638881 -0.097940557, 0.39699948 0.16379052 -0.097950183, 0.39699963 0.16369668 -0.097978674, 0.39699954 0.16361022 -0.098024748, 0.39699954 0.16353449 -0.098087035, 0.39699954 0.16314967 -0.098472051, 0.39699963 0.16308749 -0.098547719, 0.39699957 0.16304132 -0.098634265, 0.39699954 0.16301289 -0.098728083, 0.3969996 0.16300319 -0.098825507, 0.38749951 0.16388801 -0.097940706, 0.38749963 0.16369662 -0.097978674, 0.38749939 0.16379046 -0.097950183, 0.38749951 0.16353443 -0.098087035, 0.38749939 0.17375681 -0.10205858, 0.38749939 0.17386526 -0.10189643, 0.38749945 0.17381908 -0.10198288, 0.38749951 0.16361025 -0.098024778, 0.38749951 0.16308744 -0.098547749, 0.38749951 0.16314963 -0.098472111, 0.38749951 0.16304125 -0.098634265, 0.38749951 0.16301276 -0.098728083, 0.38749954 0.16300315 -0.098825507, 0.38749945 0.17389376 -0.10180255, 0.38749945 0.1739033 -0.10170516, 0.38749945 0.17311591 -0.10258042, 0.38749945 0.17301834 -0.10258984, 0.38749945 0.17320973 -0.10255193, 0.38749945 0.17329621 -0.10250577, 0.38749945 0.17337199 -0.10244363, 0.38749957 0.17390312 -0.098824821, 0.38749945 0.17386502 -0.098633669, 0.38749951 0.1738935 -0.098727338, 0.38749951 0.1738189 -0.098547153, 0.38749939 0.17375669 -0.098471455, 0.38749945 0.17337172 -0.098086618, 0.38749939 0.17320946 -0.097978137, 0.38749939 0.17329597 -0.098024331, 0.38749939 0.1730181 -0.09794002, 0.38749939 0.17311567 -0.097949676, 0.38749945 0.16328637 -0.1025412, 0.38749966 0.16319154 -0.10248166, 0.38749963 0.16339201 -0.10257816, 0.3874996 0.16350324 -0.10259043, 0.38749951 0.16301581 -0.10220187, 0.38749951 0.1630033 -0.10209074, 0.3874996 0.16305274 -0.10230752, 0.38749951 0.16311233 -0.10240241, 0.38799959 0.16328086 -0.1030656, 0.38799948 0.16350336 -0.10309064, 0.3964996 0.16350344 -0.10309073, 0.39649966 0.16328096 -0.1030656, 0.38799959 0.16306953 -0.10299163, 0.39649954 0.16306958 -0.10299163, 0.38799959 0.1628799 -0.10287245, 0.39649969 0.16287987 -0.10287254, 0.38799959 0.16272159 -0.10271417, 0.3964996 0.16272156 -0.10271408, 0.38799948 0.16260228 -0.10252451, 0.39649957 0.16260237 -0.10252463, 0.38799959 0.16252828 -0.10231318, 0.39649957 0.16252834 -0.10231318, 0.38799956 0.16250324 -0.10209074, 0.39649951 0.16250341 -0.10209074, 0.39649951 0.17301847 -0.10309004, 0.38799942 0.17301844 -0.1030898, 0.38799953 0.17321357 -0.10307094, 0.39649945 0.17321365 -0.10307103, 0.38799953 0.17340106 -0.10301387, 0.39649948 0.17340121 -0.10301387, 0.38799953 0.17357403 -0.10292148, 0.39649948 0.17357409 -0.10292157, 0.38799953 0.17372555 -0.10279723, 0.3964994 0.17372566 -0.10279714, 0.38799953 0.17301813 -0.097440146, 0.39649945 0.17301817 -0.097440146, 0.39649948 0.17321327 -0.097459458, 0.38799942 0.17321324 -0.097459368, 0.39649951 0.17340079 -0.097516201, 0.38799959 0.17340077 -0.097515963, 0.39649948 0.17357372 -0.097608589, 0.38799948 0.17357366 -0.097608618, 0.3964996 0.17372531 -0.097733013, 0.38799953 0.17372528 -0.097732954, 0.39649957 0.16388796 -0.097440742, 0.38799953 0.16388796 -0.097440533, 0.38799956 0.16369297 -0.097459845, 0.39649951 0.16369291 -0.097459905, 0.38799953 0.16350527 -0.097516619, 0.39649954 0.16350529 -0.097516827, 0.39649954 0.1633324 -0.097609214, 0.38799948 0.1633324 -0.097609185, 0.39649943 0.16318101 -0.097733758, 0.38799953 0.1631809 -0.09773355, 0.38799956 0.16252238 -0.098630391, 0.38799948 0.16250312 -0.098825507, 0.3964996 0.1625032 -0.098825507, 0.39649957 0.16252244 -0.09863057, 0.39649951 0.16257931 -0.098442964, 0.3879995 0.16257925 -0.098442934, 0.38799959 0.16267164 -0.098269992, 0.39649945 0.16267177 -0.098269992, 0.38799948 0.16279608 -0.098118596, 0.39649954 0.16279596 -0.098118417, 0.39649945 0.17440322 -0.098824911, 0.38799948 0.17440307 -0.09882497, 0.38799953 0.17438389 -0.098629825, 0.39649948 0.17438388 -0.098629765, 0.38799942 0.17432694 -0.098442338, 0.39649945 0.17432711 -0.098442338, 0.38799948 0.17423457 -0.098269396, 0.39649957 0.17423461 -0.098269396, 0.38799942 0.17411016 -0.098117881, 0.39649951 0.17411028 -0.098117761, 0.38799948 0.17440332 -0.1017051, 0.3964994 0.17440334 -0.10170516, 0.39649934 0.17438418 -0.10190003, 0.38799948 0.1743841 -0.10190003, 0.39649951 0.17432721 -0.10208773, 0.38799942 0.17432715 -0.10208773, 0.3964994 0.17423484 -0.1022607, 0.38799953 0.17423478 -0.10226058, 0.39649948 0.17411047 -0.10241219, 0.38799942 0.17411043 -0.10241219, 0.39699942 0.1635365 -0.13269424, 0.3969996 0.16361228 -0.13275635, 0.39699954 0.1636987 -0.13280252, 0.39699954 0.16379243 -0.13283101, 0.39699954 0.16389003 -0.13284054, 0.39699948 0.17302017 -0.13283998, 0.39699942 0.17311773 -0.13283047, 0.39699948 0.17321149 -0.13280198, 0.39699948 0.17329802 -0.13275576, 0.39699948 0.1733737 -0.13269368, 0.39699954 0.17375858 -0.13230875, 0.39699954 0.17382079 -0.13223293, 0.39699948 0.173867 -0.1321466, 0.39699948 0.17389549 -0.13205281, 0.39699954 0.17390504 -0.13195518, 0.39699948 0.17390493 -0.12907505, 0.39699954 0.17389528 -0.12897745, 0.39699954 0.17386676 -0.12888363, 0.3969996 0.1738207 -0.12879717, 0.39699948 0.17375843 -0.12872136, 0.39699948 0.17337351 -0.12833646, 0.39699954 0.17329773 -0.12827429, 0.39699954 0.17321129 -0.12822804, 0.39699948 0.17311753 -0.12819958, 0.39699954 0.17302001 -0.12819004, 0.39699966 0.16350485 -0.12819064, 0.39699954 0.16339359 -0.12820327, 0.39699954 0.16328785 -0.12824017, 0.39699954 0.16319317 -0.12829971, 0.39699963 0.16311395 -0.12837878, 0.39699966 0.16305429 -0.12847364, 0.39699954 0.16301745 -0.12857935, 0.39699954 0.16300485 -0.1286906, 0.39699963 0.16300505 -0.13195577, 0.39699948 0.16301471 -0.13205335, 0.39699948 0.16304308 -0.13214707, 0.39699954 0.16308933 -0.13223353, 0.39699954 0.16315156 -0.13230923, 0.38749945 0.16350479 -0.12819055, 0.38749957 0.16328785 -0.12824032, 0.38749951 0.16339359 -0.12820315, 0.38749957 0.16319305 -0.12829983, 0.38749945 0.16305424 -0.12847364, 0.38749951 0.1631138 -0.12837893, 0.38749945 0.17375855 -0.13230875, 0.38749945 0.17386694 -0.1321466, 0.38749951 0.17382066 -0.13223305, 0.38749945 0.17389537 -0.13205278, 0.38749939 0.17390496 -0.13195509, 0.38749939 0.17311765 -0.13283047, 0.38749957 0.17302005 -0.13283995, 0.38749957 0.17321144 -0.13280192, 0.38749951 0.17329787 -0.13275588, 0.38749945 0.17337362 -0.1326938, 0.38749951 0.17390482 -0.1290749, 0.38749939 0.17382061 -0.12879729, 0.38749945 0.17389524 -0.12897745, 0.38749939 0.17386681 -0.12888357, 0.38749945 0.17375839 -0.12872136, 0.38749945 0.17337345 -0.12833661, 0.38749939 0.17301983 -0.12819004, 0.38749945 0.17329764 -0.12827435, 0.38749939 0.17321117 -0.12822804, 0.38749945 0.17311746 -0.12819958, 0.38749951 0.16369866 -0.13280267, 0.38749957 0.16361222 -0.13275638, 0.38749951 0.16379248 -0.13283116, 0.38749945 0.16388993 -0.13284075, 0.38749951 0.1635364 -0.13269424, 0.38749954 0.16315143 -0.13230938, 0.38749945 0.16308925 -0.13223353, 0.38749945 0.16304305 -0.13214707, 0.38749951 0.16301462 -0.13205335, 0.38749951 0.16300502 -0.13195589, 0.38749951 0.16300485 -0.1286906, 0.38749945 0.16301732 -0.12857941, 0.39649951 0.17372701 -0.12798291, 0.38799948 0.1737269 -0.12798285, 0.3879995 0.17357542 -0.12785852, 0.39649948 0.1735754 -0.12785852, 0.38799948 0.17340247 -0.12776625, 0.39649945 0.17340252 -0.12776613, 0.38799942 0.1732149 -0.12770942, 0.39649948 0.17321491 -0.12770936, 0.38799948 0.17301978 -0.12768996, 0.39649948 0.17301986 -0.12769011, 0.38799959 0.16267358 -0.13251123, 0.38799956 0.16279799 -0.13266271, 0.39649945 0.16279803 -0.13266292, 0.39649954 0.16267365 -0.13251132, 0.38799948 0.16258118 -0.13233835, 0.39649957 0.16258121 -0.13233852, 0.38799942 0.16252425 -0.13215092, 0.39649951 0.16252427 -0.13215089, 0.38799956 0.16250497 -0.13195589, 0.39649957 0.16250503 -0.13195568, 0.39649945 0.16333444 -0.13317221, 0.39649951 0.16318297 -0.13304809, 0.38799959 0.16318287 -0.13304776, 0.38799968 0.16333446 -0.13317221, 0.39649951 0.16350739 -0.1332646, 0.38799948 0.16350727 -0.13326448, 0.39649954 0.16369504 -0.13332146, 0.38799948 0.1636949 -0.13332143, 0.39649957 0.16389006 -0.13334054, 0.38799959 0.16389002 -0.13334045, 0.38799953 0.17411193 -0.12836787, 0.39649945 0.17411201 -0.1283679, 0.39649945 0.17423642 -0.12851951, 0.38799953 0.1742363 -0.12851936, 0.39649951 0.17432868 -0.12869212, 0.38799942 0.17432874 -0.12869218, 0.39649945 0.17438564 -0.1288799, 0.38799942 0.17438556 -0.12887979, 0.39649945 0.17440495 -0.12907496, 0.38799942 0.17440481 -0.12907496, 0.39649948 0.1741122 -0.13266233, 0.38799953 0.17411214 -0.13266209, 0.38799953 0.17423651 -0.13251066, 0.39649951 0.17423655 -0.13251069, 0.38799948 0.17432894 -0.13233772, 0.39649951 0.17432894 -0.13233775, 0.38799942 0.17438565 -0.13215023, 0.39649945 0.17438585 -0.13215011, 0.38799948 0.17440501 -0.13195503, 0.39649948 0.1744051 -0.13195503, 0.38799948 0.17372732 -0.13304716, 0.39649945 0.17372724 -0.13304713, 0.3964996 0.17357579 -0.13317162, 0.38799953 0.17357573 -0.13317162, 0.39649951 0.17340285 -0.13326389, 0.38799948 0.1734028 -0.13326389, 0.39649951 0.17321537 -0.13332099, 0.38799953 0.17321521 -0.13332087, 0.39649951 0.1730202 -0.13334015, 0.38799942 0.17302012 -0.13334, 0.38799956 0.16252984 -0.12846816, 0.38799965 0.16250478 -0.12869075, 0.39649951 0.16250484 -0.12869075, 0.3964996 0.1625299 -0.12846816, 0.39649945 0.16260387 -0.1282568, 0.38799953 0.16260387 -0.12825692, 0.39649957 0.16272295 -0.12806726, 0.38799953 0.16272295 -0.12806714, 0.39649945 0.16288121 -0.12790895, 0.38799948 0.16288114 -0.12790886, 0.39649945 0.16307087 -0.12778986, 0.38799959 0.16307081 -0.12778974, 0.39649966 0.16328233 -0.12771598, 0.38799953 0.16328222 -0.12771583, 0.39649954 0.16350478 -0.1276907, 0.38799953 0.16350468 -0.1276907, 0.39549953 0.16450489 -0.12969065, 0.3954995 0.16450502 -0.13134074, 0.39549956 0.17240492 -0.1296902, 0.39549953 0.17240502 -0.1313403, 0.39549941 0.17240325 -0.09944015, 0.39549953 0.16450323 -0.099440746, 0.39549947 0.17240329 -0.10109004, 0.39549959 0.16450335 -0.10109063, 0.4149996 0.16658886 -0.10258733, 0.41499966 0.16689888 -0.10451492, 0.41499949 0.16704656 -0.1041938, 0.41499954 0.16711499 -0.10384702, 0.41499946 0.16710037 -0.10349377, 0.41499954 0.16700357 -0.10315379, 0.41499949 0.16682993 -0.10284602, 0.41499954 0.16659036 -0.12819371, 0.41499949 0.16690011 -0.12626609, 0.41499954 0.16704777 -0.12658703, 0.41499946 0.16711634 -0.12693393, 0.41499954 0.16710164 -0.12728691, 0.4149996 0.16700502 -0.12762699, 0.41499954 0.16683121 -0.12793493, 0.42533398 0.15546192 -0.1343171, 0.42537719 0.15545654 -0.13409534, 0.42530292 0.15545666 -0.13430193, 0.42540944 0.15546136 -0.13410285, 0.42538664 0.15548098 -0.13434342, 0.42546397 0.15547864 -0.13411579, 0.42540997 0.15549421 -0.13435522, 0.42548853 0.1554905 -0.13412157, 0.42543638 0.15551306 -0.13436836, 0.42517713 0.15545687 -0.13450187, 0.425542 0.15550594 -0.13389125, 0.42520636 0.155463 -0.13452548, 0.4252556 0.15548533 -0.13456482, 0.42527735 0.15550061 -0.13458231, 0.42530143 0.15552253 -0.13460141, 0.42500186 0.15545711 -0.13468495, 0.42502838 0.15546456 -0.13471642, 0.42507279 0.15549131 -0.13476875, 0.42509204 0.1555097 -0.13479152, 0.42511296 0.15553574 -0.13481611, 0.42513239 0.15556814 -0.13483903, 0.42477405 0.15545759 -0.13484821, 0.42479688 0.15546654 -0.13488737, 0.42483467 0.15549931 -0.1349521, 0.42485064 0.15552169 -0.13497955, 0.42486751 0.15555333 -0.13500878, 0.42488256 0.15559199 -0.13503471, 0.42437199 0.15545818 -0.13502878, 0.4243874 0.15547019 -0.1350787, 0.42431623 0.15549046 -0.13514927, 0.42435753 0.15551589 -0.13517919, 0.42429054 0.15545832 -0.13505366, 0.42420739 0.15545845 -0.13507524, 0.4242568 0.15546805 -0.13510829, 0.42441258 0.15551406 -0.13515988, 0.42439049 0.15554568 -0.13520437, 0.4243044 0.15547095 -0.13510516, 0.4244228 0.15554373 -0.13519272, 0.42441165 0.15557201 -0.13522199, 0.42543387 0.15546116 -0.13389105, 0.42443305 0.15558529 -0.13522571, 0.42442858 0.15560172 -0.13523823, 0.42444119 0.15563448 -0.13525197, 0.42444009 0.15563458 -0.13525257, 0.42549008 0.15547824 -0.13389105, 0.42551613 0.15550765 -0.13412812, 0.42554349 0.15552936 -0.13413444, 0.42554206 0.15550378 -0.096891217, 0.42549008 0.15547615 -0.096891217, 0.42543381 0.15545899 -0.096891217, 0.42475146 0.15561041 -0.095663927, 0.42444238 0.15564157 -0.09552636, 0.42443305 0.15558289 -0.09555652, 0.42499393 0.15546104 -0.096044444, 0.42467034 0.15546329 -0.095831655, 0.42502135 0.15547481 -0.09601035, 0.42469192 0.15548144 -0.095787071, 0.42504945 0.15549737 -0.095975392, 0.42471361 0.1555109 -0.095742486, 0.42508057 0.15553573 -0.09593644, 0.42521185 0.15545957 -0.096273445, 0.4252429 0.15547062 -0.096249394, 0.42527503 0.15548863 -0.096224211, 0.42531192 0.1555196 -0.096195512, 0.42534474 0.1554586 -0.096501134, 0.42537779 0.15546808 -0.096486025, 0.42541236 0.15548344 -0.096470408, 0.42545277 0.15550987 -0.09645205, 0.4243038 0.15546602 -0.095685296, 0.42425901 0.15546624 -0.095672511, 0.42431802 0.15548921 -0.095631562, 0.4243851 0.15546542 -0.095711283, 0.4244011 0.1554874 -0.095659189, 0.42437196 0.15552507 -0.095592313, 0.4244169 0.15552336 -0.095608376, 0.42441243 0.15557054 -0.095559292, 0.42443532 0.15561631 -0.095535927, 0.42444208 0.15564144 -0.095526122, 0.42473674 0.15556048 -0.095694594, 0.43037763 0.16034147 -0.09689083, 0.4304066 0.1604 -0.096890859, 0.43042225 0.16046342 -0.096890859, 0.43041095 0.16059287 -0.096890859, 0.42904526 0.16061524 -0.095434569, 0.42904919 0.16064408 -0.09543293, 0.42905265 0.16067308 -0.095434599, 0.4294486 0.1605334 -0.095565848, 0.42945829 0.1605902 -0.095560722, 0.4294636 0.16064769 -0.095565848, 0.42978245 0.16054761 -0.095741682, 0.42978683 0.16062826 -0.095750622, 0.43005747 0.16051139 -0.095982842, 0.43005803 0.16061237 -0.095994614, 0.43026221 0.16048442 -0.096269988, 0.43025702 0.16060123 -0.096280955, 0.43034169 0.16034895 -0.096587591, 0.43038356 0.16046849 -0.096580915, 0.43042368 0.16052872 -0.096890859, 0.43037403 0.16059482 -0.096587442, 0.43037757 0.16034199 -0.10495769, 0.4304066 0.16040047 -0.10495793, 0.43042207 0.16046388 -0.10495769, 0.43042347 0.16052927 -0.10495769, 0.43041089 0.16059329 -0.10495769, 0.43028 0.16029465 -0.10552033, 0.43034947 0.16036969 -0.10537171, 0.43033615 0.16032019 -0.10534965, 0.43027017 0.16025177 -0.10549017, 0.43022126 0.16020194 -0.10556301, 0.43015906 0.16012253 -0.10559105, 0.4301697 0.16016056 -0.10563978, 0.43020654 0.16016757 -0.10552593, 0.43025205 0.16021316 -0.10545754, 0.43028155 0.16034049 -0.10554751, 0.43035331 0.160422 -0.10539161, 0.43022829 0.16024064 -0.10559758, 0.43016973 0.16020481 -0.10568418, 0.43027449 0.16038857 -0.1055709, 0.43034726 0.16047573 -0.1054083, 0.43022752 0.16028266 -0.10562869, 0.43015909 0.16025345 -0.10572215, 0.43021876 0.16032708 -0.10565563, 0.4303585 0.16032133 -0.10515737, 0.43038523 0.16037345 -0.10517036, 0.43040091 0.16043006 -0.10518249, 0.43040487 0.16048893 -0.10519301, 0.4303132 0.16027494 -0.10532569, 0.43039712 0.16054818 -0.10520156, 0.42881337 0.15890804 -0.10706782, 0.42882386 0.15885928 -0.10702988, 0.42882398 0.15881494 -0.10698553, 0.42881334 0.15877691 -0.10693657, 0.42844898 0.15841146 -0.10780521, 0.42850512 0.15854168 -0.10767006, 0.42849377 0.15851954 -0.10780501, 0.42849487 0.15849617 -0.10766276, 0.42847678 0.15846333 -0.10780521, 0.42847759 0.15845311 -0.10765492, 0.42845345 0.15841319 -0.10764658, 0.42853314 0.15857491 -0.10753532, 0.42852479 0.15852922 -0.1075209, 0.42850903 0.15848593 -0.10750519, 0.42848584 0.15844607 -0.10748827, 0.42857933 0.1586297 -0.10740411, 0.42857432 0.15858345 -0.10738312, 0.42856094 0.1585401 -0.10735973, 0.42853993 0.15850042 -0.10733449, 0.42865729 0.15872216 -0.10725688, 0.42865741 0.15867527 -0.10722812, 0.42864859 0.15863164 -0.10719594, 0.42863089 0.15859236 -0.1071608, 0.428449 0.15841231 -0.12297695, 0.42847678 0.15846413 -0.12297665, 0.42849398 0.15852034 -0.12297665, 0.42844892 0.15840934 -0.12309762, 0.42847303 0.15844931 -0.12309142, 0.42849153 0.15846854 -0.12320622, 0.42881334 0.15890889 -0.12371381, 0.42881337 0.15877776 -0.12384491, 0.42882386 0.15881589 -0.12379622, 0.42882407 0.15886022 -0.12375184, 0.42865729 0.15872312 -0.12352466, 0.42865738 0.15867627 -0.1235536, 0.42864853 0.15863256 -0.12358593, 0.42863089 0.15859333 -0.12362074, 0.42856571 0.15861437 -0.12334426, 0.42855972 0.1585684 -0.12336393, 0.42854565 0.15852508 -0.12338527, 0.42852396 0.15848531 -0.12340831, 0.42851758 0.15855727 -0.123183, 0.42850813 0.15851161 -0.12319418, 0.42850131 0.15853783 -0.12307986, 0.42846781 0.15842853 -0.12321886, 0.4284907 0.15849239 -0.12308513, 0.43015903 0.16012359 -0.12519076, 0.43016958 0.1601617 -0.12514198, 0.43016958 0.16020603 -0.12509775, 0.43015903 0.1602546 -0.12505949, 0.43040064 0.160431 -0.1255984, 0.43034917 0.16037059 -0.12540898, 0.43033564 0.16032124 -0.12543118, 0.43038499 0.16037454 -0.12561044, 0.43040049 0.16039249 -0.12571645, 0.43037766 0.16034311 -0.12582386, 0.43040657 0.16040151 -0.12582394, 0.43037218 0.1603369 -0.12572333, 0.43035847 0.1603224 -0.12562373, 0.43040466 0.16048992 -0.12558791, 0.43035302 0.16042286 -0.12538922, 0.43041635 0.1604526 -0.12571049, 0.4304221 0.16046494 -0.12582394, 0.43039691 0.16054904 -0.12557888, 0.43034697 0.16047654 -0.12537265, 0.43041933 0.16051491 -0.12570521, 0.43042356 0.16053022 -0.12582394, 0.43040946 0.16057663 -0.12570095, 0.43041077 0.16059446 -0.12582394, 0.43024385 0.16020608 -0.12531051, 0.43026137 0.16024393 -0.12527713, 0.43027076 0.16028586 -0.12524578, 0.43027186 0.16033125 -0.12521797, 0.4303129 0.16027583 -0.12545526, 0.43026453 0.1603785 -0.1251938, 0.43037766 0.1603436 -0.13389081, 0.4304066 0.1604021 -0.13389081, 0.43042204 0.16046558 -0.13389081, 0.43042356 0.16053091 -0.13389081, 0.43041074 0.16059493 -0.13389081, 0.42905277 0.16067535 -0.13534731, 0.42904916 0.16064633 -0.13534886, 0.42904517 0.16061743 -0.13534731, 0.42946357 0.16064993 -0.13521567, 0.42945826 0.16059265 -0.13522092, 0.42944863 0.16053566 -0.13521567, 0.42978248 0.16054983 -0.13504019, 0.42976594 0.16047089 -0.13503096, 0.43005759 0.16051367 -0.13479874, 0.43003172 0.16041595 -0.13478726, 0.43026221 0.16048673 -0.13451165, 0.43022722 0.16037519 -0.13450056, 0.43037391 0.16059698 -0.1341942, 0.43038368 0.16047063 -0.13420075, 0.43034169 0.16035107 -0.13419408, 0.41699946 0.17494889 0.09741009, 0.42347261 0.16961311 0.097409733, 0.4203921 0.17494884 0.097410031, 0.42347276 0.15544234 0.097409107, 0.41925806 0.16044235 0.097409196, 0.42345363 0.15544236 0.097409107, 0.41699958 0.16044222 0.097409166, 0.42039204 0.17494784 0.11441023, 0.4169994 0.17494793 0.11441011, 0.39899948 0.16044028 0.13340932, 0.39899945 0.17494674 0.13341036, 0.41499949 0.17494692 0.13341016, 0.41499957 0.16044025 0.13340941, 0.41499954 0.17494708 0.12716013, 0.39899945 0.17494696 0.12716013, 0.41499949 0.16781934 0.12715971, 0.39899939 0.16781926 0.12715977, 0.38749951 0.17289019 0.13185996, 0.39549953 0.17289035 0.12920982, 0.39549935 0.17289025 0.13185996, 0.38749939 0.17289031 0.12920982, 0.39549959 0.16399038 0.12920946, 0.38749951 0.16399038 0.12920931, 0.39549953 0.16399023 0.13185948, 0.38749945 0.16399018 0.13185948, 0.39549941 0.17289211 0.098959811, 0.38749951 0.16399212 0.098959483, 0.39549947 0.16399211 0.098959483, 0.38749939 0.17289203 0.098960079, 0.38749945 0.16399188 0.10160951, 0.39549941 0.16399185 0.10160951, 0.38749939 0.17289191 0.10161004, 0.39549941 0.17289194 0.10161004, 0.39899939 0.17239043 0.1297099, 0.39899945 0.17239031 0.13135988, 0.39899945 0.16449034 0.12970918, 0.39899954 0.16044088 0.11978067, 0.39899951 0.16449022 0.13135949, 0.39749944 0.17596509 0.096099503, 0.39749947 0.17624871 0.096910127, 0.39749956 0.17612 0.096346147, 0.39749938 0.17621616 0.096620835, 0.39749944 0.175238 0.095642604, 0.39749938 0.17494871 0.095610149, 0.39749956 0.17551282 0.095738836, 0.39749947 0.17575918 0.095893897, 0.3974995 0.17374566 0.098491259, 0.39749947 0.17336076 0.098106511, 0.39749938 0.17380787 0.098566957, 0.39749944 0.17328496 0.098044343, 0.39749938 0.1738541 0.098653592, 0.39749944 0.17319848 0.09799815, 0.39749944 0.17388253 0.09874741, 0.39749959 0.17310484 0.097969688, 0.39749944 0.17389211 0.098844953, 0.39749938 0.17300732 0.097960003, 0.3974995 0.17389184 0.1017252, 0.39749944 0.17624825 0.10416017, 0.39749944 0.17388232 0.10182262, 0.3974995 0.17385374 0.10191632, 0.39749962 0.17380759 0.10200275, 0.39749938 0.17374548 0.10207868, 0.39749944 0.17616913 0.1045071, 0.39749941 0.17579529 0.10488091, 0.3974995 0.17607366 0.10465885, 0.39749947 0.17594703 0.10478566, 0.39749944 0.1754483 0.10496009, 0.3974995 0.17622817 0.10433818, 0.39749938 0.17562626 0.10493992, 0.39749938 0.17336051 0.10246352, 0.39749944 0.17328472 0.10252581, 0.39749938 0.1731983 0.10257197, 0.39749944 0.17310457 0.10260016, 0.39749938 0.17300698 0.10260985, 0.39749953 0.1619422 0.095609255, 0.3974995 0.16387701 0.097959556, 0.39749953 0.1637795 0.097969152, 0.39749965 0.16368568 0.097997583, 0.39749956 0.16165298 0.095641799, 0.39749941 0.16137819 0.09573821, 0.39749953 0.16359928 0.098043956, 0.39749941 0.16352351 0.098105915, 0.39749938 0.16113167 0.095893063, 0.39749953 0.16092582 0.096098818, 0.39749953 0.16885585 0.10495979, 0.39749947 0.16064216 0.096909352, 0.39749965 0.16313857 0.098490722, 0.39749965 0.16067475 0.096620001, 0.39749938 0.16077095 0.096345313, 0.39749956 0.16300161 0.098746814, 0.39749956 0.16299202 0.098844416, 0.39749944 0.16303018 0.098653086, 0.39749953 0.1630764 0.09856648, 0.3974995 0.16862176 0.1049828, 0.39749953 0.16349185 0.10260937, 0.39749947 0.16839677 0.10505102, 0.39749953 0.16818914 0.10516185, 0.3974995 0.16800737 0.10531101, 0.39749953 0.16299187 0.10210941, 0.39749953 0.16300446 0.10222075, 0.39749953 0.16338062 0.10259686, 0.39749944 0.16259286 0.11072523, 0.39749962 0.1632749 0.10255981, 0.3974995 0.16318014 0.10250057, 0.39749953 0.16310102 0.10242117, 0.39749944 0.16304138 0.10232637, 0.39749953 0.1624437 0.11090714, 0.39749956 0.16233276 0.11111433, 0.39749947 0.16226448 0.11133943, 0.39749944 0.17579414 0.12593949, 0.39749935 0.17616794 0.12631294, 0.39749938 0.17594591 0.12603465, 0.39749944 0.17607257 0.1261614, 0.39749938 0.1756251 0.12588018, 0.39749944 0.17622706 0.12648201, 0.39749944 0.176247 0.12666008, 0.39749944 0.17544717 0.12586004, 0.39749944 0.17374404 0.12874144, 0.3974995 0.17335902 0.12835661, 0.3974995 0.17328332 0.12829438, 0.39749959 0.17380619 0.12881714, 0.39749938 0.17319685 0.12824807, 0.3974995 0.17385229 0.1289036, 0.39749938 0.17310317 0.12821949, 0.39749944 0.17388089 0.12899739, 0.3974995 0.17389035 0.12909502, 0.3974995 0.17300545 0.12820995, 0.39749947 0.16885477 0.12585965, 0.39749941 0.17624655 0.13391009, 0.39749938 0.17389022 0.13197526, 0.39749944 0.17388059 0.13207272, 0.39749938 0.17385225 0.13216633, 0.39749938 0.17611793 0.1344741, 0.39749938 0.1762141 0.1341995, 0.39749938 0.17380606 0.13225272, 0.3974995 0.17374372 0.13232872, 0.39749947 0.175963 0.13472074, 0.39749944 0.17575717 0.13492659, 0.39749938 0.17551063 0.13508135, 0.39749938 0.17523585 0.1351774, 0.39749938 0.17494662 0.13521019, 0.39749932 0.17335886 0.13271368, 0.3974995 0.17328303 0.13277578, 0.39749938 0.17319657 0.1328221, 0.39749944 0.1731029 0.13285044, 0.39749944 0.17300524 0.13286009, 0.39749938 0.16800626 0.12550819, 0.39749956 0.16349034 0.12820944, 0.3974995 0.16818811 0.12565729, 0.39749944 0.1683955 0.12576839, 0.3974995 0.1686206 0.12583655, 0.39749944 0.16259237 0.12009383, 0.39749944 0.16337916 0.1282219, 0.39749962 0.16327347 0.12825891, 0.39749944 0.16317867 0.12831852, 0.39749944 0.16309956 0.12839773, 0.39749956 0.16233225 0.11970428, 0.3974995 0.16303992 0.12849244, 0.39749944 0.16244316 0.11991192, 0.39749953 0.16300303 0.12859815, 0.39749953 0.16307455 0.13225204, 0.39749944 0.16064002 0.13390926, 0.39749944 0.16313666 0.13232809, 0.3974995 0.1630283 0.13216576, 0.39749944 0.16299987 0.13207212, 0.39749947 0.1629902 0.13197449, 0.39749944 0.16299048 0.12870938, 0.39749953 0.16226399 0.11947919, 0.39749944 0.16194001 0.13520938, 0.39749944 0.16352153 0.13271299, 0.3974995 0.16387507 0.13285953, 0.3974995 0.16377762 0.13284996, 0.3974995 0.1636838 0.13282147, 0.3974995 0.16359732 0.13277546, 0.39749953 0.1616507 0.1351766, 0.39749956 0.1613759 0.13508075, 0.39749938 0.16067268 0.13419858, 0.39749968 0.16076875 0.13447326, 0.39749944 0.16112943 0.13492587, 0.39749968 0.16092359 0.13471985, 0.39749947 0.16224141 0.11157364, 0.39749947 0.16224095 0.11924518, 0.42547274 0.15824203 0.13340932, 0.4254728 0.1661469 0.1334095, 0.42836627 0.16113545 0.1334095, 0.41699946 0.17494686 0.13341025, 0.42039204 0.17494689 0.13341016, 0.42347273 0.16961117 0.1334098, 0.42347264 0.15544039 0.13340896, 0.41925821 0.1604403 0.13340932, 0.42345366 0.15544041 0.13340896, 0.41699958 0.1604403 0.13340932, 0.39899954 0.1604421 0.097409256, 0.41499951 0.16044228 0.097409256, 0.41499949 0.17494872 0.097410001, 0.39899939 0.17494878 0.097410001, 0.4254728 0.158242 0.1306999, 0.42836607 0.16113573 0.12539721, 0.42699957 0.15976919 0.12403066, 0.42349952 0.15626889 0.13069978, 0.42699948 0.15976973 0.11640925, 0.42349952 0.15626976 0.11640919, 0.42699951 0.15976982 0.11440928, 0.42699948 0.15977024 0.10678787, 0.42349958 0.15626974 0.11440913, 0.42836607 0.16113696 0.10542119, 0.4254728 0.15824373 0.10011844, 0.42836615 0.16113745 0.097409166, 0.4254728 0.15824391 0.097409166, 0.42349967 0.15627047 0.10011847, 0.42039198 0.17494777 0.11641008, 0.42347267 0.16961111 0.13070044, 0.42699957 0.16350345 0.11640937, 0.42699963 0.16350313 0.12403066, 0.42547268 0.1661471 0.13070032, 0.4234727 0.16961294 0.10011912, 0.42547268 0.16614901 0.097409733, 0.4254728 0.16614863 0.10011897, 0.42699957 0.16350405 0.10678814, 0.42699945 0.16350356 0.11440933, 0.4169994 0.17494789 0.11641029, 0.39899945 0.17494838 0.10366023, 0.41499937 0.17494847 0.10366011, 0.41699961 0.16044104 0.11978058, 0.41699943 0.16044129 0.11640919, 0.41699955 0.16666707 0.12600753, 0.41699937 0.1668859 0.12628502, 0.41699952 0.1670336 0.12660643, 0.41699952 0.1671021 0.1269531, 0.41699955 0.16708741 0.12730631, 0.41699946 0.16699067 0.1276463, 0.41699952 0.16681679 0.12795419, 0.4169994 0.16657604 0.12821272, 0.41699946 0.16681828 0.10286499, 0.4169994 0.1665774 0.10260654, 0.41699937 0.16699202 0.10317311, 0.41699949 0.16708878 0.10351286, 0.41699952 0.16710342 0.10386608, 0.41699952 0.16703478 0.10421301, 0.41699943 0.16688713 0.10453413, 0.41699952 0.16666831 0.10481177, 0.41699958 0.1604415 0.11103771, 0.41699949 0.16044128 0.11440928, 0.4303368 0.16027912 0.1049763, 0.42558736 0.15553023 0.096908964, 0.43033677 0.16027963 0.096909441, 0.43013823 0.16008043 0.1055587, 0.43028152 0.16022374 0.10531972, 0.43021849 0.16016082 0.10545478, 0.43032163 0.16026399 0.10516251, 0.43033305 0.16027537 0.10506979, 0.42879254 0.15873469 0.10690437, 0.42867851 0.1586208 0.1070343, 0.42858148 0.15852374 0.10718093, 0.42848748 0.15842961 0.10738618, 0.42843044 0.15837267 0.10760356, 0.42841166 0.158354 0.10782314, 0.43013817 0.1600793 0.12525982, 0.43018413 0.16012545 0.12531304, 0.430226 0.16016713 0.12537658, 0.43028167 0.16022284 0.12549934, 0.43032181 0.16026281 0.1256566, 0.4303368 0.1602779 0.12584242, 0.42879239 0.15873377 0.1239141, 0.42558753 0.15552805 0.13390893, 0.42860442 0.15854573 0.12367616, 0.42849439 0.1584356 0.12345115, 0.42843276 0.15837407 0.12322796, 0.42841691 0.15835823 0.12311114, 0.42841175 0.158353 0.12299491, 0.43033665 0.16027746 0.13390917, 0.42849946 0.16363701 0.12299538, 0.42849964 0.15856601 0.10782332, 0.42849946 0.16363785 0.10782383, 0.42849955 0.15856506 0.12299479, 0.42848873 0.16392457 0.10713229, 0.42858434 0.1637589 0.10691399, 0.42154673 0.17594887 0.096910246, 0.4287498 0.1634724 0.10664497, 0.43038443 0.16064183 0.096909352, 0.42842016 0.16404362 0.1073601, 0.42895147 0.16312326 0.10640941, 0.42837903 0.16411456 0.10759235, 0.42836562 0.16413794 0.10782368, 0.43038443 0.16064133 0.1049763, 0.42836553 0.1641371 0.12299524, 0.4215467 0.17594676 0.13391009, 0.42837602 0.16411892 0.1232003, 0.42848772 0.16392545 0.12368358, 0.42863509 0.16367018 0.1239979, 0.43038452 0.16063952 0.13390937, 0.43038455 0.16063999 0.12584242, 0.42895132 0.16312236 0.12440933, 0.42039204 0.1749467 0.13541022, 0.41995773 0.16194007 0.13540941, 0.42862496 0.16068697 0.13540927, 0.42448401 0.15654585 0.13540912, 0.39769948 0.17494661 0.13541022, 0.39769956 0.16193996 0.13540941, 0.41549951 0.17544718 0.12566021, 0.39769951 0.16885473 0.12565982, 0.39769942 0.17544721 0.12566015, 0.41549951 0.16885483 0.12565982, 0.41549957 0.16273399 0.11995233, 0.39769942 0.16273381 0.11995221, 0.41549936 0.16814771 0.12536678, 0.39769953 0.16814762 0.12536678, 0.41549957 0.16244151 0.11157364, 0.39769956 0.16244097 0.11924521, 0.41549957 0.16244103 0.11924533, 0.39769953 0.16244131 0.11157364, 0.41549942 0.16814888 0.10545249, 0.39769942 0.16273437 0.11086641, 0.41549951 0.16273445 0.11086664, 0.39769953 0.1681488 0.10545254, 0.39769953 0.1754483 0.10516015, 0.41549957 0.16885598 0.10515989, 0.41549945 0.17544851 0.10516033, 0.39769953 0.16885586 0.10515989, 0.41649929 0.17644726 0.12666032, 0.39769945 0.17644668 0.13391, 0.42068073 0.17644677 0.13391021, 0.39769945 0.17644709 0.12666023, 0.4206807 0.17644902 0.096910186, 0.4164995 0.17644843 0.10416032, 0.39769948 0.17644876 0.096910127, 0.39769945 0.17644823 0.10416017, 0.42862511 0.16068923 0.095409222, 0.41995749 0.16194239 0.095409341, 0.42039198 0.17494908 0.095410205, 0.42448395 0.1565482 0.095408954, 0.39769953 0.1749489 0.095410205, 0.39769951 0.16194227 0.09540955, 0.41549942 0.16830048 0.10532821, 0.41549951 0.1684733 0.10523585, 0.41549951 0.16866095 0.10517893, 0.41549945 0.16261016 0.11101804, 0.41549954 0.16251767 0.11119098, 0.41549951 0.16246079 0.11137841, 0.41549951 0.16847214 0.12558368, 0.41549939 0.16865985 0.12564036, 0.41549945 0.1682993 0.12549114, 0.41549957 0.1625172 0.11962784, 0.41549954 0.16260958 0.11980072, 0.41549951 0.16246028 0.11944032, 0.42879248 0.1589468 0.1071162, 0.43013817 0.1602926 0.10577068, 0.42879248 0.16262336 0.10711644, 0.4301382 0.1602916 0.12504774, 0.42879248 0.15894583 0.12370203, 0.42879245 0.16262239 0.1237023, 0.41499949 0.16666712 0.12600744, 0.41925818 0.16044232 0.096909441, 0.39769962 0.16044213 0.096909232, 0.41965023 0.16044132 0.11440933, 0.41965041 0.1604412 0.11640919, 0.39899954 0.16044147 0.11103783, 0.41925818 0.16044018 0.13390926, 0.39769953 0.16044003 0.13390926, 0.41499954 0.16666825 0.10481177, 0.39899948 0.16782047 0.10365973, 0.41499957 0.16782057 0.10365973, 0.39899945 0.17239183 0.10110963, 0.39899945 0.17239204 0.099459685, 0.39899957 0.16449209 0.099459298, 0.39899951 0.16449188 0.1011093, 0.42537516 0.15544237 0.096908964, 0.4252789 0.15544236 0.096510209, 0.42535204 0.1554424 0.096710958, 0.42384276 0.15544234 0.096011557, 0.42452341 0.15544237 0.095868416, 0.42476687 0.15544242 0.0959884, 0.42434174 0.15544237 0.095804311, 0.42415667 0.15544239 0.09575776, 0.42362869 0.15544228 0.096289314, 0.42498088 0.15544233 0.096139945, 0.42350629 0.15544233 0.096563853, 0.4234665 0.15544237 0.096736826, 0.42515409 0.15544237 0.096316822, 0.42345357 0.15544239 0.096908964, 0.42349958 0.15544216 0.10011829, 0.42347279 0.15544213 0.10011829, 0.42349952 0.15544133 0.11440892, 0.42537528 0.15544017 0.13390893, 0.42349958 0.15544043 0.13069957, 0.42349958 0.15544121 0.11640895, 0.42529398 0.15544014 0.13427606, 0.42535573 0.15544014 0.13409129, 0.42516387 0.15544014 0.13448912, 0.42347279 0.15544048 0.13069972, 0.42345366 0.15544011 0.13390893, 0.42348847 0.15544018 0.13419023, 0.42495126 0.1554402 0.13470262, 0.42359471 0.15544018 0.13446799, 0.42462164 0.15544024 0.13490656, 0.42376977 0.15544018 0.13472608, 0.42394894 0.15544014 0.13490611, 0.42415673 0.15544018 0.13506013, 0.39769951 0.16865967 0.12564045, 0.39769948 0.16847205 0.12558362, 0.39769956 0.16829923 0.12549129, 0.39769951 0.16260946 0.11980072, 0.39769951 0.16251715 0.11962775, 0.39769953 0.16246021 0.11944006, 0.39769948 0.16246061 0.1113785, 0.39769953 0.16251755 0.11119086, 0.39769951 0.16260988 0.11101801, 0.39769948 0.1683003 0.10532824, 0.39769953 0.16847311 0.10523591, 0.39769953 0.16866077 0.10517893, 0.39769942 0.1764221 0.12643772, 0.41617769 0.17639406 0.12633848, 0.39769942 0.17634811 0.12622613, 0.41592383 0.17626496 0.12608472, 0.39769936 0.17622888 0.12603652, 0.41572577 0.17608093 0.12588656, 0.39769945 0.17607057 0.12587821, 0.41560736 0.17589897 0.12576813, 0.39769942 0.17588104 0.12575918, 0.41553661 0.17571758 0.12569734, 0.39769953 0.17566964 0.12568519, 0.41550839 0.1755805 0.12566915, 0.41550833 0.17558168 0.10515127, 0.4155367 0.17571871 0.1051229, 0.41560739 0.17590018 0.10505224, 0.41572583 0.17608196 0.10493363, 0.41592389 0.17626613 0.10473571, 0.41617766 0.1763953 0.10448176, 0.39769948 0.17567082 0.10513509, 0.39769942 0.17588221 0.10506112, 0.39769945 0.17607164 0.104942, 0.39769945 0.17623007 0.10478363, 0.39769953 0.17634925 0.10459397, 0.39769948 0.17642315 0.10438273, 0.42850029 0.16363528 0.10778428, 0.42850262 0.16362724 0.10774482, 0.42850447 0.1585723 0.10772521, 0.4285121 0.16359428 0.10766537, 0.42852652 0.16354457 0.10759292, 0.42851907 0.15859152 0.10762677, 0.42855415 0.1634489 0.10749767, 0.42856312 0.15864873 0.10747252, 0.42863429 0.16317123 0.10732228, 0.42864794 0.15875877 0.10729942, 0.43020228 0.16036135 0.10569627, 0.42889792 0.16276632 0.10697458, 0.43025911 0.16042592 0.10560859, 0.4289614 0.1629018 0.10680313, 0.43033174 0.16051754 0.10544015, 0.43037793 0.16059379 0.10522664, 0.42897952 0.16302294 0.10661159, 0.42848426 0.16381156 0.10782368, 0.42849532 0.16375884 0.1077261, 0.4285087 0.16372611 0.10762829, 0.42847085 0.16388601 0.10770664, 0.4284392 0.16397993 0.10782368, 0.4285292 0.1636761 0.10753763, 0.42848718 0.16385348 0.10758943, 0.42842972 0.1640089 0.10768674, 0.42851201 0.16380391 0.10748095, 0.42844808 0.1639763 0.10754905, 0.42857724 0.16355836 0.10739858, 0.42847586 0.16392654 0.10742164, 0.42857045 0.16368711 0.10731385, 0.428541 0.16380961 0.10722501, 0.42867947 0.16330776 0.1072116, 0.4286947 0.16343845 0.10708929, 0.42867988 0.16356064 0.10695813, 0.42848447 0.16381072 0.12299547, 0.4284392 0.16397911 0.12299538, 0.43024909 0.16041304 0.12519237, 0.42889801 0.16276529 0.12384439, 0.4303315 0.16051602 0.1253776, 0.42896137 0.16290087 0.1240157, 0.43037778 0.16059226 0.12559113, 0.42897952 0.16302207 0.12420738, 0.43038696 0.16062127 0.1257163, 0.42863411 0.16317032 0.12349651, 0.42850029 0.16363436 0.1230346, 0.4286795 0.16330677 0.12360729, 0.4286947 0.16343759 0.12372968, 0.42867982 0.16355966 0.12386069, 0.42856753 0.1635814 0.12339637, 0.42855412 0.16344795 0.12332118, 0.42852652 0.16354364 0.12322599, 0.42855859 0.16370992 0.12347636, 0.42852768 0.16383252 0.12356014, 0.4285087 0.16372515 0.12319077, 0.42851225 0.16359337 0.12315346, 0.42849529 0.16375789 0.12309266, 0.42850265 0.16362633 0.12307403, 0.42848712 0.16385263 0.12322963, 0.42847073 0.16388512 0.12311206, 0.42844805 0.16397542 0.12326992, 0.42842984 0.1640079 0.12313212, 0.42850792 0.15857582 0.12312365, 0.42853335 0.15860896 0.12325225, 0.42857575 0.15866409 0.12337754, 0.42863435 0.1587403 0.12349618, 0.42870736 0.15883519 0.12360526, 0.42142379 0.17611594 0.13391009, 0.42142391 0.17611791 0.096910395, 0.42126846 0.1762559 0.13391, 0.42126858 0.17625795 0.096910186, 0.42108738 0.17636038 0.13391021, 0.42108741 0.1763625 0.096910395, 0.4208886 0.17642492 0.13391009, 0.4208886 0.17642707 0.096910127, 0.42051983 0.16016354 0.11640925, 0.42075136 0.1599599 0.11640934, 0.42093652 0.15971309 0.11640904, 0.42025116 0.16031562 0.11640931, 0.41995719 0.16040955 0.11640919, 0.42075136 0.15995997 0.11440933, 0.42051962 0.16016369 0.11440933, 0.42093641 0.1597131 0.11440925, 0.4202511 0.16031575 0.11440928, 0.4199571 0.16040967 0.11440913, 0.42886037 0.16063291 0.095423408, 0.42446417 0.15609294 0.095440902, 0.42910242 0.16057499 0.095468558, 0.42444509 0.15565717 0.095535196, 0.4294419 0.16049373 0.095591106, 0.42489111 0.15560758 0.095750637, 0.42975268 0.1604194 0.095780768, 0.4251976 0.15557352 0.096000947, 0.43000996 0.16035789 0.096027441, 0.42541075 0.15554985 0.096278824, 0.43019566 0.16031343 0.096312918, 0.4255321 0.15553644 0.096550383, 0.43030328 0.16028763 0.09661407, 0.42557397 0.15553176 0.096731193, 0.42154056 0.17594354 0.096755303, 0.43035591 0.16064245 0.096640147, 0.42152125 0.17592669 0.096596338, 0.43026435 0.1606449 0.096364416, 0.4214454 0.17586103 0.096295632, 0.430087 0.16064981 0.096074887, 0.4213168 0.17574982 0.096012004, 0.42983431 0.16065659 0.09581966, 0.42114055 0.17559724 0.095768012, 0.4294855 0.16066594 0.095600881, 0.42092925 0.17541422 0.095582403, 0.42905438 0.16067758 0.095454611, 0.42067373 0.17519288 0.095455386, 0.42046255 0.17531498 0.095455505, 0.42067909 0.17644085 0.096755393, 0.42061132 0.1756063 0.095566072, 0.42052633 0.17564695 0.095582403, 0.42057914 0.17592153 0.095768012, 0.42077315 0.17551698 0.095558561, 0.42077959 0.17610681 0.095977105, 0.42062318 0.17615023 0.096011914, 0.42065537 0.17631726 0.096295632, 0.42107111 0.17596179 0.095959701, 0.42087603 0.17639004 0.096576847, 0.42067432 0.17641571 0.096596427, 0.4212454 0.17622313 0.096567072, 0.42109925 0.1761737 0.096244998, 0.39769948 0.17641112 0.096576281, 0.39769942 0.1763002 0.096259393, 0.39769945 0.1761215 0.095974751, 0.39769953 0.17588395 0.095737554, 0.39769948 0.17559968 0.095558591, 0.39769948 0.17528246 0.095447816, 0.42446417 0.15609078 0.13537708, 0.42904282 0.160587 0.13536394, 0.42444509 0.15565509 0.13528267, 0.42946213 0.16048667 0.1352177, 0.42475665 0.15562028 0.13514689, 0.42980158 0.16040547 0.13499874, 0.42504019 0.15558885 0.13496023, 0.43004751 0.16034672 0.13474375, 0.42527658 0.15556251 0.13472953, 0.42545056 0.15554331 0.13446659, 0.43022007 0.16030541 0.13445404, 0.42555428 0.1555317 0.13418776, 0.43030888 0.16028407 0.13417843, 0.43035004 0.16064052 0.13420454, 0.4215185 0.17592253 0.13423896, 0.43023953 0.16064361 0.13450566, 0.42142817 0.17584418 0.13457197, 0.43004844 0.16064854 0.13479093, 0.42127323 0.1757099 0.13487938, 0.42978409 0.16065583 0.13503769, 0.42106313 0.1755278 0.13513082, 0.42946476 0.16066438 0.13522747, 0.4208172 0.17531483 0.13530475, 0.42911565 0.16067374 0.13534966, 0.42060214 0.17512867 0.13538507, 0.42886698 0.16068044 0.13539505, 0.42044461 0.17521967 0.13538498, 0.42067367 0.17641029 0.13423896, 0.42075419 0.17535514 0.13531521, 0.42069185 0.17539322 0.13532025, 0.42055973 0.17581843 0.13513082, 0.42062891 0.17542966 0.13532025, 0.42056477 0.17546466 0.1353153, 0.42049825 0.17549895 0.13530475, 0.42116034 0.17581517 0.13491327, 0.42103595 0.17590691 0.13493031, 0.42090166 0.17598452 0.13493031, 0.42075998 0.17604631 0.13491327, 0.42061239 0.17609148 0.13487938, 0.42130709 0.17598222 0.13460556, 0.4211641 0.17609908 0.13462248, 0.42100394 0.17619161 0.13462242, 0.42083132 0.17625692 0.13460544, 0.42065111 0.17629287 0.13457197, 0.42139572 0.17608359 0.13425916, 0.42124307 0.1762176 0.13426962, 0.421067 0.17631917 0.13426971, 0.42087469 0.17638424 0.13425937, 0.39769942 0.17528044 0.13537258, 0.39769942 0.1755975 0.13526157, 0.39769945 0.17588177 0.13508299, 0.39769942 0.17611939 0.13484532, 0.39769948 0.1762981 0.134561, 0.39769945 0.17640895 0.13424414, 0.41984126 0.1616929 0.095430292, 0.39769953 0.16160846 0.095447011, 0.41972187 0.16143689 0.095497049, 0.39769951 0.16129144 0.095558025, 0.41959864 0.16117249 0.095621921, 0.39769942 0.16100694 0.095736571, 0.41948655 0.16093193 0.095800675, 0.39769936 0.16076952 0.095973916, 0.41939282 0.16073097 0.09602458, 0.39769956 0.16059072 0.096258558, 0.41932267 0.16058056 0.096280016, 0.39769956 0.16047974 0.096575417, 0.41927508 0.16047888 0.096580334, 0.4192695 0.1604645 0.13417843, 0.39769956 0.16047764 0.13424307, 0.41930583 0.16054262 0.13445392, 0.39769945 0.16058861 0.13456011, 0.41937634 0.16069372 0.13474384, 0.39769959 0.16076723 0.13484457, 0.41947687 0.16090916 0.13499883, 0.39769956 0.16100472 0.13508216, 0.41961566 0.16120648 0.1352177, 0.39769953 0.1612892 0.13526085, 0.41978687 0.16157402 0.135364, 0.39769953 0.16160625 0.13537183, 0.39757478 0.17527069 0.13532987, 0.39754301 0.17494661 0.13533491, 0.39757472 0.17494656 0.13536647, 0.39754313 0.17623028 0.13452831, 0.39751911 0.17629866 0.1342186, 0.39751935 0.17619605 0.13451189, 0.39757469 0.17557858 0.13522238, 0.39754313 0.17556478 0.13519374, 0.39754304 0.17526361 0.13529912, 0.39754301 0.17633563 0.13422695, 0.39765495 0.17559525 0.13525718, 0.39750445 0.17629117 0.13391009, 0.39765495 0.1758787 0.13507903, 0.39751917 0.17603081 0.13477486, 0.39750445 0.17615806 0.1344935, 0.39761266 0.17586946 0.13506749, 0.39761257 0.17558883 0.13524371, 0.39750457 0.17599781 0.1347484, 0.39761275 0.17527598 0.13535312, 0.39761269 0.17494658 0.1353904, 0.39750445 0.17578486 0.13496131, 0.39765489 0.17527923 0.13536769, 0.39765495 0.17494659 0.13540533, 0.39761263 0.17638969 0.13423961, 0.39761266 0.17642686 0.13391021, 0.39757484 0.17640299 0.13391021, 0.39757478 0.17636646 0.13423437, 0.39757472 0.17625873 0.1345419, 0.39754313 0.17606051 0.13479856, 0.39751917 0.17581122 0.13499445, 0.39765483 0.17640401 0.13424292, 0.39765486 0.17644162 0.13391021, 0.39750445 0.17552996 0.13512141, 0.39761257 0.17628025 0.13455236, 0.39757478 0.17608526 0.13481823, 0.39754307 0.17583494 0.13502398, 0.39751923 0.17554832 0.13515967, 0.39765489 0.17629354 0.13455895, 0.39750445 0.17524575 0.13522094, 0.39750445 0.17494652 0.13525468, 0.39761269 0.17610383 0.13483313, 0.39757466 0.17585465 0.13504866, 0.39750457 0.17625739 0.13420931, 0.39751914 0.17633334 0.13391021, 0.39751917 0.17525519 0.13526207, 0.39751917 0.17494661 0.13529697, 0.39765495 0.1761155 0.13484231, 0.39754304 0.17637132 0.13391021, 0.3975046 0.16193996 0.13525382, 0.39751923 0.16193999 0.13529626, 0.39754322 0.16194005 0.13533401, 0.39757481 0.16193996 0.13536566, 0.39761269 0.16193993 0.13538963, 0.39765495 0.16194001 0.13540423, 0.39750457 0.17629163 0.12666008, 0.39751923 0.17633389 0.12666023, 0.39754304 0.17637174 0.12666023, 0.39757472 0.17640342 0.12666023, 0.39761257 0.17642732 0.12666023, 0.39765495 0.17644204 0.12666023, 0.39757496 0.16161592 0.13532928, 0.39754322 0.16162296 0.13529831, 0.39761266 0.16060647 0.13455147, 0.39761269 0.16078277 0.1348322, 0.39757496 0.16080129 0.13481751, 0.39757487 0.16062799 0.13454121, 0.39754313 0.16132188 0.13519299, 0.39751932 0.16163146 0.13526124, 0.39757478 0.16052014 0.13423353, 0.39754313 0.16051531 0.13390937, 0.39757481 0.16048366 0.13390937, 0.39751923 0.16133827 0.13515869, 0.39754316 0.16065638 0.13452759, 0.39754322 0.16055103 0.13422623, 0.39751923 0.16107531 0.13499355, 0.3975046 0.16135661 0.13512075, 0.3975046 0.16110162 0.13496056, 0.39765495 0.16059303 0.13455805, 0.39765507 0.16077122 0.13484147, 0.39761272 0.16049697 0.13423866, 0.39761263 0.16045992 0.13390937, 0.3975046 0.16088878 0.13474756, 0.3976551 0.16048248 0.13424188, 0.39765504 0.16044503 0.13390937, 0.39761272 0.16161062 0.13535243, 0.39757481 0.16130809 0.13522154, 0.39754316 0.16105168 0.13502315, 0.39751932 0.16085579 0.13477388, 0.39765495 0.1616073 0.1353668, 0.39750454 0.16072869 0.13449267, 0.39761278 0.16129772 0.13524312, 0.39750457 0.16059552 0.1339094, 0.39757484 0.16103186 0.13504818, 0.39754313 0.1608261 0.13479763, 0.39751923 0.16069067 0.13451102, 0.39765507 0.16129133 0.13525635, 0.39750457 0.16062924 0.1342085, 0.39761281 0.1610171 0.13506669, 0.39750451 0.16164082 0.13522011, 0.39751932 0.16058798 0.13421792, 0.39751926 0.16055329 0.13390917, 0.39765507 0.16100785 0.13507834, 0.39761272 0.17633022 0.12623501, 0.3976126 0.17621341 0.12604898, 0.39757478 0.1761948 0.12606364, 0.39757472 0.17565998 0.12572777, 0.39754307 0.17544717 0.12573552, 0.39754307 0.17565286 0.12575868, 0.39757478 0.17630877 0.12624523, 0.39754304 0.17584832 0.12582713, 0.39751929 0.1756444 0.1257956, 0.39757472 0.17637947 0.12644735, 0.39754301 0.17634857 0.12645441, 0.39751914 0.17583179 0.12586129, 0.39754304 0.1762802 0.12625888, 0.39765489 0.17634356 0.12622854, 0.39765495 0.17622499 0.12603983, 0.39751923 0.17599995 0.12596676, 0.39750436 0.17581351 0.1258994, 0.39750445 0.17597359 0.12600002, 0.39761263 0.17640275 0.12644213, 0.39750448 0.17610735 0.12613356, 0.39765483 0.17641717 0.12643871, 0.39761257 0.17566521 0.12570462, 0.39761263 0.17544715 0.12567997, 0.39757472 0.17544717 0.12570381, 0.39757469 0.17586206 0.12579858, 0.39754313 0.17602368 0.12593716, 0.39751917 0.1761404 0.12610716, 0.39765486 0.17566852 0.12569019, 0.39765498 0.17544714 0.12566531, 0.39750451 0.17620794 0.12629363, 0.3976126 0.17587236 0.12577713, 0.39757472 0.17604332 0.12591255, 0.3975431 0.17617008 0.12608358, 0.39751923 0.17624605 0.1262753, 0.39765495 0.17587876 0.12576374, 0.39750445 0.1762704 0.12647229, 0.39761269 0.17605828 0.12589392, 0.39750436 0.17563505 0.12583703, 0.39750457 0.17544709 0.12581584, 0.39751923 0.17544708 0.12577334, 0.39751929 0.17631161 0.12646267, 0.39765495 0.17606743 0.12588227, 0.39750457 0.16059755 0.096909352, 0.39751938 0.16055544 0.096909441, 0.39754322 0.16051748 0.096909441, 0.39757493 0.16048582 0.096909441, 0.39761269 0.16046195 0.096909441, 0.39765495 0.16044712 0.096909203, 0.39750454 0.16885473 0.12581536, 0.39751935 0.16885471 0.12577301, 0.3975431 0.16885473 0.12573516, 0.39757475 0.16885473 0.12570342, 0.39761278 0.16885471 0.12567946, 0.39765495 0.16885468 0.1256648, 0.39757478 0.16161823 0.095489539, 0.39754313 0.16194215 0.095484652, 0.39757484 0.16194215 0.095452972, 0.39754316 0.16065848 0.096291192, 0.39751941 0.16059005 0.096600719, 0.39751935 0.16069277 0.096307434, 0.3975431 0.16162521 0.095520325, 0.39757478 0.16131036 0.095597275, 0.39754301 0.16132407 0.095625676, 0.39754313 0.1605532 0.096592136, 0.39765495 0.16129355 0.095562406, 0.39765495 0.16101007 0.095740505, 0.39761272 0.16101937 0.095752038, 0.39751923 0.16085796 0.096044935, 0.39750445 0.16073087 0.096326031, 0.39761269 0.16130002 0.095575698, 0.39750457 0.16089101 0.096071161, 0.39761278 0.16161282 0.095466413, 0.39761272 0.16194226 0.0954291, 0.39750445 0.1611039 0.095858194, 0.39765507 0.16160953 0.095451958, 0.39761278 0.16049905 0.096579976, 0.39765495 0.16194224 0.095414318, 0.39757493 0.16052227 0.096585341, 0.39757481 0.16063003 0.096277364, 0.39754301 0.16082841 0.096021093, 0.39751932 0.16107754 0.095825113, 0.3976551 0.16048463 0.096576728, 0.39750454 0.16135883 0.095697917, 0.39761278 0.16060854 0.096266933, 0.39757478 0.16080363 0.096001215, 0.39754301 0.16105396 0.09579543, 0.39751932 0.16134049 0.095659889, 0.39750457 0.161643 0.095598616, 0.39750457 0.16194208 0.095564879, 0.39765495 0.16059522 0.096260585, 0.39761281 0.160785 0.095986314, 0.39757478 0.16103421 0.095770754, 0.39750466 0.16063137 0.096610107, 0.39751929 0.16163364 0.095557369, 0.39751932 0.16194221 0.09552262, 0.39765495 0.16077343 0.095977224, 0.39754307 0.16844323 0.12565324, 0.3975431 0.16864492 0.12571433, 0.39757472 0.16865113 0.12568328, 0.39757478 0.16845538 0.12562391, 0.39757472 0.16827497 0.12552744, 0.39761275 0.16813354 0.12538087, 0.39757484 0.16811679 0.12539786, 0.39761272 0.16846442 0.12560207, 0.39761263 0.16828823 0.1255078, 0.39750451 0.16862926 0.12579319, 0.39751926 0.16863766 0.12575144, 0.39751923 0.16842875 0.12568808, 0.39754319 0.16825734 0.12555382, 0.3975431 0.16809438 0.12542018, 0.39750442 0.1684126 0.12572718, 0.39751923 0.16823627 0.1255852, 0.39751926 0.16806754 0.12544689, 0.39750439 0.16821273 0.12562042, 0.39750439 0.16803768 0.12547663, 0.39765489 0.16865867 0.12564549, 0.39761272 0.16865572 0.12565991, 0.39765489 0.16847003 0.12558836, 0.39765501 0.16829634 0.12549543, 0.39765501 0.16814408 0.12537041, 0.39750451 0.17494868 0.095565714, 0.39751929 0.17494875 0.095523395, 0.39754301 0.17494869 0.095485486, 0.39757478 0.17494874 0.095453568, 0.39761269 0.17494881 0.095429964, 0.39765495 0.1749488 0.095415272, 0.39750451 0.16262381 0.12006227, 0.39751938 0.16265371 0.12003235, 0.39754319 0.16268066 0.12000553, 0.39757481 0.16270299 0.11998317, 0.39761269 0.16271985 0.1199664, 0.39765495 0.16273022 0.11995561, 0.39761269 0.17628229 0.096268006, 0.39757478 0.17608745 0.096002139, 0.39757478 0.17626084 0.096278109, 0.39761281 0.17610598 0.095987268, 0.39754307 0.17556688 0.095626511, 0.39754307 0.17526583 0.095520921, 0.39751932 0.17525734 0.095558055, 0.39757484 0.17636859 0.096586056, 0.39754304 0.17633772 0.09659297, 0.39754307 0.17637335 0.096910246, 0.39757478 0.17640507 0.096910246, 0.39751929 0.17555052 0.095660515, 0.39754307 0.17623238 0.096291937, 0.39751914 0.17581342 0.095825948, 0.39750436 0.17553218 0.095698602, 0.39765498 0.17629562 0.096261568, 0.39765498 0.17611755 0.09597794, 0.39750448 0.17578703 0.095859088, 0.39750448 0.17599992 0.096071847, 0.39761269 0.17639178 0.09658093, 0.39761269 0.17642903 0.096910276, 0.39761263 0.17527814 0.0954668, 0.39765495 0.17640616 0.096577682, 0.39765495 0.1764437 0.096910246, 0.39757478 0.17527291 0.095490016, 0.39757478 0.17558064 0.095598049, 0.39754319 0.17583704 0.095796384, 0.39751929 0.17603302 0.096045561, 0.39765495 0.17528142 0.095452495, 0.39750451 0.17616014 0.096326776, 0.39761269 0.17559099 0.095576443, 0.39757478 0.17585677 0.095771618, 0.39754307 0.17606266 0.096021779, 0.39751914 0.17619821 0.096308298, 0.39765501 0.17559744 0.09556324, 0.39750451 0.17625953 0.096610852, 0.39750445 0.17629321 0.096910127, 0.39761263 0.17587161 0.095752873, 0.39750451 0.17524786 0.095599212, 0.39751923 0.17630067 0.096601523, 0.39751923 0.17633553 0.096910246, 0.39765489 0.17588083 0.095741339, 0.39757478 0.16241738 0.11944855, 0.39761269 0.16242112 0.11924533, 0.39757484 0.16239727 0.11924533, 0.39757487 0.16247681 0.11964441, 0.39761281 0.16249873 0.11963547, 0.39761275 0.16244078 0.11944405, 0.39750454 0.16248024 0.119887, 0.39751932 0.16251528 0.11986373, 0.39751932 0.16241249 0.11967126, 0.39754307 0.16254686 0.11984266, 0.39754313 0.16244745 0.11965684, 0.39754316 0.16238634 0.11945499, 0.39754316 0.16236557 0.11924518, 0.39750457 0.16237336 0.11968745, 0.39751935 0.1623491 0.1194625, 0.39751932 0.16232774 0.11924533, 0.3975046 0.16230758 0.11947072, 0.39750457 0.16228545 0.11924533, 0.39765501 0.16243587 0.11924533, 0.39765495 0.16260524 0.11980359, 0.39761272 0.16259296 0.11981178, 0.39765501 0.16251242 0.11962972, 0.39757478 0.16257316 0.11982495, 0.39765504 0.16245528 0.1194414, 0.39750457 0.17629279 0.10416017, 0.39751932 0.17633499 0.10416017, 0.39754304 0.17637292 0.10416017, 0.39757484 0.17640468 0.10416029, 0.39761272 0.17642851 0.10416029, 0.39765495 0.17644328 0.10416029, 0.39750457 0.16228582 0.11157364, 0.39751929 0.16232818 0.11157364, 0.39754316 0.16236606 0.11157364, 0.39757484 0.16239773 0.11157364, 0.39761263 0.1624216 0.11157364, 0.39765501 0.16243629 0.11157364, 0.39757472 0.17566115 0.10509253, 0.39754313 0.17544825 0.10508487, 0.39757469 0.1754483 0.10511646, 0.39754319 0.17628139 0.10456131, 0.39754304 0.17634982 0.10436577, 0.39751929 0.17631283 0.10435713, 0.39754307 0.17584948 0.10499323, 0.39754304 0.17565407 0.10506178, 0.39751929 0.17624727 0.10454477, 0.39757484 0.17586318 0.10502175, 0.39765495 0.17587997 0.10505656, 0.39751914 0.17614157 0.10471306, 0.39750445 0.17620914 0.10452641, 0.39765486 0.17606857 0.10493792, 0.39761263 0.17605944 0.10492656, 0.39761275 0.17587349 0.10504324, 0.39750445 0.17610854 0.10468668, 0.39761263 0.17566638 0.10511575, 0.39761269 0.17544837 0.10514034, 0.39750445 0.17597485 0.10482047, 0.39765498 0.17566967 0.10513023, 0.39765495 0.17544827 0.10515524, 0.39761275 0.17640388 0.10437847, 0.39757478 0.17638071 0.10437296, 0.39757472 0.1763099 0.10457525, 0.39754307 0.17617123 0.10473666, 0.39751923 0.17600116 0.1048534, 0.39765495 0.17641838 0.10438169, 0.39750436 0.17581464 0.10492093, 0.39761281 0.17633134 0.10458563, 0.39757472 0.17619593 0.10475645, 0.39754307 0.17602476 0.10488317, 0.39751923 0.17583302 0.10495911, 0.39765501 0.17634471 0.10459173, 0.39750451 0.17563617 0.10498355, 0.39750445 0.17544824 0.10500465, 0.39761269 0.17621455 0.10477123, 0.39757478 0.17604449 0.104908, 0.39750445 0.17627156 0.10434795, 0.39751923 0.17564553 0.10502479, 0.39751923 0.17544834 0.10504676, 0.39765495 0.17622608 0.1047805, 0.39754307 0.16244793 0.11116216, 0.39757478 0.16241789 0.11136995, 0.39757484 0.16247725 0.11117408, 0.39757484 0.16257365 0.11099384, 0.39757478 0.16270344 0.11083574, 0.39754313 0.16268106 0.11081309, 0.39761272 0.16259347 0.11100719, 0.39761281 0.16249916 0.11118335, 0.39750454 0.16230814 0.11134804, 0.39751938 0.16234958 0.11135656, 0.39751932 0.16241291 0.11114762, 0.39754313 0.16238672 0.11136384, 0.39754313 0.16254736 0.11097617, 0.39751929 0.16265424 0.11078627, 0.39750457 0.16237387 0.11113153, 0.39751938 0.16251582 0.1109551, 0.39750445 0.16262437 0.11075658, 0.39750457 0.16248061 0.11093149, 0.39765507 0.16245568 0.11137757, 0.39761281 0.16244113 0.11137471, 0.39765495 0.16251284 0.11118875, 0.39765495 0.16260567 0.11101527, 0.39765501 0.16273083 0.1108628, 0.39761281 0.16272034 0.11085243, 0.39750451 0.16885585 0.10500429, 0.39751929 0.16885588 0.10504646, 0.39754307 0.16885588 0.10508446, 0.39757475 0.16885588 0.10511614, 0.39761269 0.16885592 0.10514007, 0.39765504 0.16885588 0.10515485, 0.39750442 0.16803885 0.10534249, 0.39751923 0.16806872 0.10537256, 0.39754307 0.16809545 0.10539935, 0.39757475 0.1681179 0.10542173, 0.39761269 0.16813479 0.10543848, 0.39765492 0.16814522 0.10544888, 0.39754304 0.1684444 0.10516606, 0.39757478 0.16827613 0.10529206, 0.39757487 0.16845649 0.10519553, 0.39754313 0.1682585 0.10526551, 0.3975749 0.16865221 0.10513628, 0.39761269 0.1686569 0.10515962, 0.39761275 0.16846569 0.10521755, 0.39750457 0.16821383 0.10519893, 0.39751929 0.16823737 0.105234, 0.39751929 0.1684299 0.10513104, 0.39754319 0.16864611 0.10510505, 0.39750454 0.16841374 0.10509188, 0.39751917 0.16863877 0.10506783, 0.39750448 0.1686303 0.10502637, 0.39765501 0.16829756 0.10532401, 0.39761266 0.16828936 0.10531173, 0.39765492 0.16847123 0.10523117, 0.39765492 0.16865988 0.10517395, 0.39699957 0.16299045 0.12870926, 0.39699957 0.16300297 0.12859815, 0.39699954 0.16303988 0.12849253, 0.39699957 0.16309953 0.12839767, 0.39699954 0.1631787 0.12831852, 0.39699948 0.16327351 0.12825891, 0.39699948 0.16337913 0.12822184, 0.39699948 0.16349041 0.12820944, 0.39699948 0.17300555 0.12820989, 0.39699948 0.17310308 0.12821954, 0.39699942 0.17319679 0.12824813, 0.39699948 0.17328322 0.12829438, 0.39699948 0.17335904 0.12835661, 0.39699942 0.17374395 0.12874141, 0.39699954 0.17380621 0.12881714, 0.39699942 0.17385231 0.12890357, 0.39699942 0.17388082 0.12899742, 0.39699942 0.17389037 0.1290949, 0.39699942 0.17389016 0.13197526, 0.39699942 0.17388062 0.13207266, 0.39699948 0.17385212 0.13216633, 0.39699948 0.173806 0.13225287, 0.39699942 0.17374381 0.13232857, 0.39699948 0.17335887 0.13271362, 0.39699942 0.17328307 0.13277578, 0.39699942 0.17319667 0.13282201, 0.39699948 0.17310287 0.13285044, 0.39699948 0.17300525 0.13286009, 0.39699948 0.16387513 0.13285953, 0.39699948 0.16377756 0.13284999, 0.39699948 0.1636838 0.1328215, 0.39699948 0.16359729 0.13277525, 0.39699948 0.16352162 0.13271302, 0.39699948 0.16313666 0.13232797, 0.39699954 0.16307443 0.13225228, 0.39699948 0.16302823 0.13216594, 0.39699948 0.16299981 0.13207212, 0.39699951 0.16299023 0.13197449, 0.38749954 0.16302818 0.13216594, 0.38749945 0.16307436 0.13225225, 0.38749945 0.16299014 0.13197449, 0.38749945 0.16387506 0.13285944, 0.38749951 0.1635215 0.13271302, 0.38749945 0.1637775 0.13284996, 0.38749945 0.16368368 0.13282147, 0.38749939 0.16359732 0.1327751, 0.38749939 0.17328316 0.12829438, 0.38749939 0.17319681 0.12824804, 0.38749939 0.17335896 0.12835625, 0.38749945 0.16313659 0.13232797, 0.38749939 0.17374383 0.12874126, 0.38749939 0.17385228 0.1289036, 0.38749951 0.17380612 0.1288172, 0.38749939 0.17310303 0.12821954, 0.38749939 0.17388077 0.12899742, 0.38749951 0.17389028 0.12909502, 0.38749939 0.17300542 0.12821004, 0.38749939 0.17389011 0.13197502, 0.38749933 0.17374372 0.13232866, 0.38749951 0.1738805 0.13207272, 0.38749939 0.17385215 0.13216633, 0.38749939 0.17380586 0.13225272, 0.38749933 0.1733588 0.13271359, 0.38749933 0.17319652 0.13282201, 0.38749939 0.17328304 0.1327756, 0.38749939 0.17310277 0.1328505, 0.38749945 0.17300518 0.13286012, 0.38749945 0.16327344 0.12825865, 0.38749945 0.16317861 0.12831843, 0.38749954 0.16337915 0.12822184, 0.38749945 0.16349034 0.12820944, 0.38749954 0.16300298 0.12859806, 0.38749945 0.16299032 0.12870941, 0.38749945 0.16303986 0.12849244, 0.38749945 0.16309942 0.12839752, 0.38749945 0.16299973 0.13207212, 0.38799968 0.16349037 0.12770924, 0.39649951 0.16349049 0.12770924, 0.39649951 0.16326794 0.12773448, 0.38799953 0.1632679 0.12773448, 0.39649969 0.16305655 0.12780854, 0.38799956 0.16305651 0.12780854, 0.39649951 0.16286696 0.1279276, 0.38799956 0.16286685 0.12792766, 0.39649957 0.16270864 0.12808597, 0.38799948 0.16270849 0.12808597, 0.39649954 0.16258946 0.12827533, 0.38799956 0.16258943 0.12827542, 0.38799953 0.16251537 0.12848684, 0.39649951 0.16251545 0.12848681, 0.39649945 0.16249047 0.12870926, 0.38799948 0.16249034 0.12870947, 0.39649948 0.17320058 0.12772915, 0.39649945 0.17300545 0.1277099, 0.38799953 0.1730054 0.12771004, 0.38799936 0.17320053 0.12772927, 0.3964994 0.17338821 0.1277861, 0.38799953 0.17338812 0.12778613, 0.38799936 0.17356105 0.12787849, 0.39649951 0.17356116 0.12787849, 0.38799948 0.17371254 0.12800306, 0.39649945 0.17371263 0.12800306, 0.38799948 0.17320037 0.13334087, 0.38799942 0.17300516 0.13335994, 0.39649934 0.17300533 0.13335994, 0.39649937 0.17320031 0.13334078, 0.38799948 0.17338787 0.13328403, 0.39649934 0.17338796 0.133284, 0.38799948 0.17356075 0.1331915, 0.3964994 0.17356077 0.13319162, 0.38799936 0.17371233 0.13306707, 0.3964994 0.1737124 0.13306707, 0.39649945 0.16367999 0.13334018, 0.39649945 0.16387506 0.13335949, 0.38799956 0.163875 0.13335949, 0.38799942 0.16368002 0.13334018, 0.39649954 0.16349244 0.13328341, 0.38799953 0.16349228 0.13328344, 0.39649945 0.16331947 0.13319081, 0.38799956 0.16331954 0.13319102, 0.39649957 0.16316806 0.13306645, 0.38799948 0.16316801 0.13306648, 0.38799959 0.1625094 0.13216957, 0.38799953 0.16249011 0.13197449, 0.39649957 0.16249022 0.13197464, 0.39649945 0.16250937 0.13216957, 0.38799948 0.16256616 0.13235721, 0.39649954 0.16256636 0.13235718, 0.38799942 0.16265868 0.13253012, 0.39649945 0.16265874 0.13253003, 0.38799948 0.16278315 0.13268167, 0.39649945 0.16278313 0.13268158, 0.3964994 0.17437096 0.13217038, 0.39649945 0.17439026 0.13197508, 0.38799936 0.17439021 0.13197508, 0.38799948 0.17437087 0.13217038, 0.39649937 0.17431408 0.13235801, 0.38799948 0.1743141 0.13235787, 0.3964994 0.17422166 0.1325306, 0.38799948 0.17422162 0.13253063, 0.3964994 0.17409733 0.13268223, 0.38799936 0.17409728 0.13268223, 0.38799953 0.17437112 0.1288999, 0.3879995 0.17439036 0.12909502, 0.3964994 0.17439039 0.1290949, 0.39649937 0.17437115 0.12889975, 0.38799942 0.17431416 0.12871239, 0.39649945 0.17431432 0.12871227, 0.38799936 0.17422183 0.12853935, 0.39649934 0.17422189 0.12853929, 0.38799942 0.17409743 0.12838775, 0.39649948 0.1740976 0.12838775, 0.39699948 0.16352348 0.098105915, 0.39699951 0.16359921 0.098043866, 0.39699954 0.16368569 0.097997643, 0.39699948 0.16377962 0.097969092, 0.39699954 0.16387708 0.097959526, 0.39699948 0.17300728 0.097960003, 0.39699948 0.17310493 0.097969599, 0.39699948 0.17319854 0.097997971, 0.39699948 0.17328502 0.098044343, 0.39699948 0.17336072 0.098106481, 0.39699948 0.17374577 0.098491229, 0.39699948 0.17380793 0.098567255, 0.39699936 0.17385405 0.098653592, 0.39699948 0.17388256 0.09874735, 0.39699948 0.17389216 0.098844923, 0.39699948 0.17389195 0.10172499, 0.39699954 0.17388232 0.10182256, 0.39699954 0.17385383 0.10191629, 0.39699942 0.17380767 0.10200275, 0.39699954 0.17374533 0.10207868, 0.39699939 0.17336048 0.1024634, 0.39699954 0.17328471 0.10252593, 0.3969996 0.17319819 0.10257197, 0.39699954 0.17310454 0.10260022, 0.39699948 0.17300691 0.10261, 0.39699954 0.16349186 0.1026094, 0.39699954 0.16338056 0.10259701, 0.39699954 0.16327502 0.10255987, 0.39699954 0.16318007 0.1025003, 0.39699948 0.16310094 0.10242126, 0.39699954 0.16304138 0.10232631, 0.39699954 0.16300435 0.10222075, 0.39699954 0.16299191 0.10210944, 0.39699948 0.16299218 0.098844416, 0.39699948 0.16300179 0.098746814, 0.39699948 0.1630301 0.098652996, 0.39699954 0.16307631 0.098566689, 0.39699948 0.16313866 0.098490722, 0.38749945 0.16300435 0.10222078, 0.38749945 0.16304131 0.10232637, 0.38749945 0.16349176 0.1026094, 0.38749945 0.16327487 0.10255987, 0.38749945 0.16338049 0.10259686, 0.38749954 0.16318013 0.1025003, 0.38749951 0.16310088 0.10242108, 0.38749939 0.17374565 0.098491229, 0.3874993 0.17385401 0.098653592, 0.38749945 0.17380787 0.098566957, 0.38749945 0.17388244 0.09874741, 0.38749945 0.17389208 0.098844953, 0.38749939 0.17310479 0.097969688, 0.38749933 0.17300716 0.097960003, 0.38749939 0.1731984 0.097997971, 0.38749939 0.17328498 0.098044313, 0.38749951 0.17336066 0.098106511, 0.38749939 0.17389184 0.10172511, 0.38749939 0.17374542 0.10207868, 0.38749939 0.17388232 0.10182262, 0.38749939 0.17385378 0.10191638, 0.38749945 0.17380762 0.10200275, 0.38749939 0.17336042 0.1024634, 0.38749939 0.17300685 0.10261, 0.38749951 0.17328472 0.10252593, 0.38749945 0.17319822 0.10257176, 0.38749939 0.17310442 0.10260016, 0.38749945 0.16377945 0.097969092, 0.38749951 0.16368563 0.097997583, 0.38749957 0.16387694 0.097959466, 0.38749945 0.16359919 0.098043717, 0.38749945 0.16352338 0.098105915, 0.38749951 0.1631386 0.098490722, 0.38749945 0.16307633 0.098566569, 0.38749939 0.16303013 0.098652996, 0.3874996 0.16300166 0.098746844, 0.38749945 0.16299197 0.098844416, 0.38749954 0.16299178 0.10210944, 0.39649945 0.17371406 0.1028171, 0.38799942 0.173714 0.1028171, 0.38799948 0.17356242 0.10294149, 0.3964994 0.1735625 0.10294152, 0.38799953 0.17338955 0.10303391, 0.39649948 0.17338961 0.10303391, 0.38799948 0.17320199 0.10309068, 0.39649945 0.17320202 0.10309068, 0.38799936 0.17300683 0.10310996, 0.39649951 0.1730068 0.10310996, 0.38799948 0.16266054 0.098288782, 0.38799953 0.16278489 0.098137297, 0.39649945 0.16278496 0.098137178, 0.39649957 0.16266072 0.098288663, 0.38799956 0.16256811 0.098461695, 0.39649945 0.16256823 0.098461904, 0.3879995 0.16251127 0.098649271, 0.39649954 0.16251132 0.098649271, 0.38799953 0.16249205 0.098844416, 0.39649945 0.16249211 0.098844416, 0.39649945 0.16316997 0.097752221, 0.38799956 0.16316992 0.097752281, 0.38799953 0.16332142 0.097627945, 0.39649954 0.16332152 0.097627886, 0.38799948 0.16349432 0.097535558, 0.39649945 0.16349438 0.097535707, 0.38799948 0.16368194 0.097478576, 0.39649945 0.163682 0.097478636, 0.38799956 0.16387694 0.097459473, 0.39649951 0.16387706 0.097459503, 0.38799936 0.17409892 0.10243214, 0.39649945 0.17409897 0.10243208, 0.39649937 0.17422342 0.10228065, 0.38799942 0.17422338 0.10228065, 0.3964994 0.17431587 0.10210777, 0.38799948 0.17431575 0.10210777, 0.3964994 0.17437264 0.10192034, 0.38799942 0.17437263 0.10192014, 0.39649937 0.17439193 0.10172523, 0.38799948 0.17439198 0.10172511, 0.3964994 0.17409921 0.098137774, 0.38799948 0.17409915 0.098137863, 0.38799948 0.17422348 0.098289408, 0.39649948 0.17422357 0.098289259, 0.3964994 0.17431596 0.09846244, 0.38799942 0.17431588 0.09846238, 0.38799942 0.17437284 0.098650016, 0.39649945 0.17437288 0.098650016, 0.3964994 0.17439212 0.098844923, 0.38799942 0.17439206 0.098844923, 0.38799942 0.17371424 0.097752966, 0.39649945 0.17371427 0.097752877, 0.3964994 0.17356277 0.097628541, 0.38799942 0.17356278 0.097628422, 0.39649945 0.17338987 0.097536094, 0.38799948 0.17338978 0.097536243, 0.3964994 0.17320231 0.097479232, 0.38799942 0.17320229 0.097479232, 0.3964994 0.17300716 0.097460009, 0.38799942 0.17300719 0.097460069, 0.38799956 0.16251682 0.102332, 0.3879995 0.16249184 0.10210941, 0.39649951 0.16249189 0.10210941, 0.3964996 0.16251688 0.102332, 0.38799959 0.16259085 0.10254312, 0.39649957 0.16259089 0.10254312, 0.38799948 0.16270992 0.10273293, 0.3964996 0.16270997 0.1027329, 0.38799956 0.16286828 0.10289121, 0.39649957 0.16286826 0.10289121, 0.3879995 0.16305788 0.1030103, 0.39649957 0.16305794 0.1030103, 0.38799953 0.16326924 0.10308442, 0.39649951 0.1632693 0.10308433, 0.38799948 0.16349176 0.10310955, 0.39649966 0.16349179 0.10310946, 0.3954995 0.16449216 0.099459417, 0.39549944 0.16449186 0.10110939, 0.39549944 0.17239189 0.10110999, 0.39549938 0.17239216 0.099459685, 0.39549962 0.16449022 0.1313594, 0.39549941 0.17239022 0.13135996, 0.39549953 0.17239024 0.12970987, 0.39549959 0.16449019 0.12970918, 0.41499949 0.16657595 0.12821266, 0.41499946 0.16688588 0.12628514, 0.41499949 0.16703363 0.12660643, 0.41499949 0.16710217 0.12695298, 0.41499954 0.16708735 0.12730631, 0.41499954 0.16699053 0.12764627, 0.41499949 0.16681682 0.12795386, 0.41499954 0.16657723 0.10260654, 0.41499949 0.16688703 0.10453401, 0.41499949 0.16703485 0.10421301, 0.4149996 0.16710342 0.10386608, 0.41499957 0.16708878 0.10351298, 0.41499946 0.16699201 0.10317294, 0.41499954 0.16681828 0.1028652, 0.42533398 0.1554489 0.096482821, 0.42537707 0.15544356 0.096704639, 0.4253028 0.15544373 0.096498288, 0.42540935 0.15544832 0.096697398, 0.42538649 0.15546811 0.096456595, 0.42546397 0.15546563 0.096684165, 0.42541003 0.15548123 0.096445002, 0.42548847 0.15547754 0.096678443, 0.42543626 0.15550016 0.096431769, 0.42517713 0.15544377 0.096298493, 0.425542 0.15549284 0.096908964, 0.42520633 0.1554499 0.09627489, 0.42525554 0.15547228 0.096234985, 0.42527729 0.15548754 0.096217938, 0.42530131 0.15550943 0.096198596, 0.4250018 0.15544407 0.096114941, 0.42502832 0.15545152 0.096083589, 0.42507273 0.15547822 0.096031465, 0.42509204 0.1554966 0.096008696, 0.42511284 0.15552273 0.095984049, 0.42513227 0.15555511 0.095961042, 0.42477399 0.15544462 0.095951743, 0.42479688 0.15545343 0.095912851, 0.42483467 0.15548618 0.095848002, 0.42485058 0.15550864 0.095820464, 0.42486751 0.15554023 0.095791169, 0.42488253 0.15557888 0.09576527, 0.4243719 0.15544511 0.09577129, 0.4243874 0.15545717 0.09572155, 0.42431617 0.15547746 0.095650949, 0.42435759 0.15550277 0.095621027, 0.42429054 0.15544532 0.095746554, 0.42420727 0.15544535 0.095724978, 0.42425668 0.15545499 0.095691837, 0.42441267 0.15550087 0.095640339, 0.42439055 0.15553251 0.095595755, 0.42430437 0.15545784 0.095695056, 0.4244228 0.15553069 0.095607556, 0.42441165 0.15555894 0.095578171, 0.42543381 0.15544817 0.096908964, 0.42443311 0.15557216 0.095574446, 0.42442846 0.15558875 0.09556181, 0.4244411 0.15562142 0.095548101, 0.42443994 0.15562156 0.095547386, 0.42549002 0.15546523 0.096908964, 0.42551613 0.15549468 0.096672095, 0.42554343 0.15551642 0.096665569, 0.42554203 0.15549076 0.13390893, 0.42549002 0.15546302 0.13390902, 0.42543387 0.15544595 0.13390893, 0.4247514 0.15559748 0.13513607, 0.42444235 0.15562856 0.13527364, 0.42443299 0.15556997 0.13524336, 0.42499387 0.15544812 0.13475576, 0.42467034 0.15545033 0.13496843, 0.42502129 0.15546191 0.13478988, 0.42469203 0.15546846 0.1350131, 0.42504936 0.15548445 0.13482478, 0.42471361 0.15549798 0.13505772, 0.4250806 0.15552275 0.134864, 0.42521194 0.1554465 0.1345264, 0.4252429 0.15545762 0.13455072, 0.42527497 0.15547554 0.13457566, 0.42531186 0.15550663 0.1346046, 0.42534465 0.15544558 0.1342991, 0.42537779 0.15545502 0.13431412, 0.42541242 0.15547036 0.13432962, 0.42545271 0.15549688 0.13434809, 0.42430365 0.15545315 0.13511473, 0.42425895 0.15545321 0.13512757, 0.42431808 0.15547608 0.1351687, 0.42438501 0.15545246 0.1350891, 0.42440104 0.15547448 0.13514081, 0.42437187 0.15551221 0.13520771, 0.4244169 0.15551035 0.13519183, 0.42441231 0.15555762 0.13524073, 0.4244352 0.15560335 0.1352641, 0.42444193 0.15562853 0.13527408, 0.42473668 0.15554743 0.1351054, 0.43037751 0.16032843 0.13390937, 0.43040657 0.16038693 0.13390917, 0.43042207 0.16045049 0.13390926, 0.43041071 0.16057986 0.13390926, 0.42904502 0.16060224 0.13536564, 0.42904928 0.16063115 0.13536695, 0.42905277 0.16066021 0.13536564, 0.42944852 0.16052049 0.13523412, 0.42945817 0.16057734 0.13523927, 0.42946348 0.16063474 0.13523418, 0.42978263 0.16053461 0.13505855, 0.42978683 0.16061524 0.1350494, 0.4300575 0.16049841 0.13481718, 0.43005791 0.1605994 0.13480547, 0.43026218 0.16047142 0.1345301, 0.43025708 0.16058823 0.13451925, 0.43034169 0.16033588 0.13421255, 0.43038356 0.16045547 0.13421935, 0.43042353 0.16051573 0.13390926, 0.43037391 0.16058181 0.13421264, 0.43037763 0.16032889 0.12584242, 0.4304066 0.1603874 0.12584242, 0.43042207 0.16045085 0.12584242, 0.43042356 0.16051619 0.12584242, 0.43041077 0.16058031 0.12584242, 0.43027997 0.16028164 0.12527972, 0.43034941 0.16035676 0.1254282, 0.43033606 0.16030718 0.12545061, 0.4302702 0.1602387 0.12530982, 0.43022126 0.16018894 0.12523705, 0.43015894 0.16010939 0.12520906, 0.43016955 0.1601475 0.12516028, 0.43020654 0.16015452 0.12527391, 0.43025193 0.16020018 0.1253427, 0.43028152 0.16032752 0.12525266, 0.43035328 0.16040902 0.12540835, 0.43022814 0.16022749 0.12520233, 0.4301697 0.16019179 0.12511581, 0.43027446 0.16037551 0.12522924, 0.43034714 0.16046263 0.12539184, 0.43022752 0.16026963 0.12517142, 0.43015903 0.16024053 0.12507793, 0.43021882 0.1603141 0.12514451, 0.43035847 0.16030829 0.12564287, 0.43038523 0.16036038 0.12562978, 0.43040079 0.16041702 0.1256175, 0.43040484 0.16047598 0.12560689, 0.43031317 0.1602619 0.12547454, 0.43039703 0.1605351 0.12559834, 0.42881322 0.15889497 0.12373222, 0.42882395 0.15884638 0.12377013, 0.42882395 0.15880194 0.12381453, 0.42881322 0.15876389 0.12386347, 0.42844898 0.1583984 0.12299491, 0.42850509 0.15852879 0.12312997, 0.42849374 0.15850659 0.12299479, 0.42849478 0.15848319 0.12313709, 0.42847675 0.15845032 0.12299479, 0.4284775 0.15844002 0.12314523, 0.42845348 0.15840012 0.12315325, 0.4285332 0.1585618 0.12326465, 0.4285247 0.15851615 0.12327922, 0.428509 0.1584729 0.12329478, 0.42848593 0.15843304 0.12331165, 0.42857945 0.15861662 0.12339569, 0.42857426 0.15857054 0.12341703, 0.42856103 0.15852718 0.12344039, 0.42853981 0.15848745 0.12346566, 0.42865738 0.15870918 0.12354294, 0.4286575 0.15866227 0.12357194, 0.42864859 0.15861861 0.12360416, 0.42863089 0.15857945 0.12363917, 0.42844898 0.15839936 0.10782314, 0.42847675 0.15845121 0.10782332, 0.42849386 0.15850742 0.10782332, 0.42844892 0.15839638 0.10770256, 0.42847317 0.15843637 0.10770891, 0.42849144 0.15845564 0.10759378, 0.42881337 0.15889594 0.1070861, 0.42881328 0.15876479 0.10695527, 0.42882383 0.15880288 0.1070039, 0.42882386 0.1588473 0.10704825, 0.42865729 0.15871014 0.10727534, 0.42865738 0.15866329 0.10724641, 0.42864859 0.15861963 0.10721419, 0.42863089 0.15858042 0.10717929, 0.42856568 0.15860142 0.10745583, 0.42855954 0.15855539 0.10743625, 0.42854556 0.15851212 0.10741482, 0.4285239 0.15847237 0.10739157, 0.42851752 0.15854433 0.10761679, 0.42850816 0.15849875 0.10760603, 0.4285011 0.15852508 0.10772023, 0.42846781 0.15841554 0.10758112, 0.42849064 0.1584795 0.10771484, 0.43015894 0.16011049 0.10560942, 0.4301697 0.16014855 0.105658, 0.4301697 0.16019297 0.10570241, 0.43015891 0.16024165 0.10574052, 0.43040049 0.16041809 0.10520185, 0.43034914 0.16035759 0.10539121, 0.43033564 0.16030821 0.10536895, 0.43038511 0.16036156 0.10518975, 0.43040019 0.16037948 0.10508359, 0.4303776 0.16033016 0.1049763, 0.43040654 0.16038868 0.1049763, 0.43037218 0.16032387 0.10507689, 0.43035835 0.16030937 0.10517643, 0.43040472 0.160477 0.10521243, 0.43035299 0.16040988 0.10541082, 0.43041623 0.16043966 0.10508976, 0.43042207 0.16045201 0.1049763, 0.43039688 0.16053611 0.10522092, 0.43034685 0.16046347 0.10542745, 0.43041924 0.16050191 0.10509516, 0.43042356 0.16051729 0.1049763, 0.43040931 0.16056362 0.10509918, 0.43041074 0.16058151 0.1049763, 0.43024382 0.1601931 0.10548983, 0.43026122 0.16023104 0.10552321, 0.43027073 0.16027299 0.10555432, 0.43027177 0.16031823 0.1055823, 0.43031275 0.16026291 0.10534466, 0.43026453 0.16036548 0.1056063, 0.4303776 0.16033058 0.096909203, 0.43040657 0.16038917 0.096909232, 0.43042207 0.16045257 0.096909232, 0.43042356 0.1605178 0.096909232, 0.43041074 0.16058202 0.096909232, 0.42905265 0.16066232 0.095452704, 0.42904916 0.16063324 0.095451511, 0.42904514 0.16060437 0.095452942, 0.42946354 0.16063698 0.09558443, 0.42945823 0.16057947 0.095579304, 0.4294486 0.16052268 0.09558443, 0.42978263 0.16053684 0.095760055, 0.42976582 0.16045777 0.095768996, 0.43005747 0.1605006 0.096001215, 0.43003187 0.16040291 0.096012749, 0.43026212 0.16047367 0.09628848, 0.4302271 0.16036215 0.096299477, 0.43037388 0.16058394 0.096605934, 0.43038353 0.16045767 0.096599407, 0.43034166 0.16033807 0.096606113, -0.42425942 0.16043696 0.097409196, -0.42847389 0.15543674 0.097408958, -0.42845485 0.1554368 0.097408958, -0.42847389 0.16960749 0.097409733, -0.4220008 0.1604369 0.097409166, -0.42200077 0.17494336 0.097410001, -0.4253934 0.17494325 0.09741015, -0.42539346 0.1749424 0.11441023, -0.42200089 0.17494239 0.11441011, -0.42000091 0.17494141 0.13341036, -0.40400082 0.17494158 0.13341016, -0.40400064 0.16043489 0.1334092, -0.42000079 0.16043492 0.13340932, -0.42000085 0.17494172 0.12716022, -0.40400088 0.1749419 0.12716013, -0.42000073 0.16781384 0.12715977, -0.40400076 0.16781405 0.12715968, -0.39250085 0.17288533 0.12920991, -0.40050083 0.17288508 0.13185984, -0.40050077 0.17288524 0.12920982, -0.39250073 0.17288512 0.13186008, -0.39250082 0.16398524 0.12920946, -0.40050066 0.16398516 0.12920925, -0.40050063 0.16398498 0.13185948, -0.39250082 0.16398524 0.13185945, -0.40050083 0.17288692 0.09895996, -0.39250082 0.16398706 0.098959483, -0.39250085 0.17288706 0.098960079, -0.4005008 0.16398692 0.098959424, -0.40050089 0.1639868 0.10160951, -0.39250082 0.16398685 0.10160951, -0.4005008 0.1728868 0.10161004, -0.39250073 0.17288676 0.10161004, -0.40400064 0.16448505 0.12970921, -0.40400079 0.1604358 0.11978067, -0.40400067 0.16448504 0.13135964, -0.40400076 0.1723851 0.1297099, -0.40400076 0.1723851 0.13135988, -0.40250081 0.16076575 0.096345462, -0.40250069 0.16063699 0.09690956, -0.40250078 0.16066965 0.09662009, -0.40250069 0.16092056 0.096098818, -0.40250069 0.16112641 0.095893063, -0.40250081 0.16193701 0.095609374, -0.40250081 0.16137293 0.095738091, -0.40250081 0.16164778 0.095641799, -0.40250093 0.16351837 0.098105915, -0.40250081 0.16313335 0.098490871, -0.40250075 0.16359405 0.098043747, -0.40250081 0.16307127 0.098566569, -0.40250069 0.1636806 0.097997434, -0.40250093 0.16302508 0.098652996, -0.40250081 0.16377437 0.097969092, -0.40250075 0.16299653 0.098746844, -0.40250075 0.16298689 0.098844416, -0.40250069 0.16387178 0.097959466, -0.40250081 0.16298674 0.10210944, -0.40250081 0.1629992 0.10222078, -0.40250081 0.1749436 0.09560997, -0.40250081 0.17300197 0.097960003, -0.40250078 0.17309953 0.097969688, -0.40250078 0.17319328 0.097997971, -0.40250087 0.17523295 0.095642395, -0.40250087 0.17550755 0.095738806, -0.40250078 0.17327979 0.098044343, -0.40250087 0.17335559 0.098106511, -0.40250105 0.17575414 0.095893897, -0.40250081 0.1759599 0.096099652, -0.4025009 0.17374057 0.098491259, -0.40250093 0.17624359 0.096910395, -0.40250078 0.17380267 0.098566957, -0.40250087 0.17384888 0.098653592, -0.40250078 0.17387736 0.098747499, -0.4025009 0.17388694 0.098844953, -0.40250087 0.17611489 0.096346147, -0.40250093 0.17621106 0.096620835, -0.40250078 0.16348675 0.10260949, -0.40250075 0.16258772 0.11072526, -0.40250084 0.16337545 0.10259686, -0.40250078 0.16326982 0.10256017, -0.40250069 0.163175 0.10250057, -0.40250075 0.16309582 0.10242108, -0.40250078 0.1630362 0.10232652, -0.40250075 0.1680021 0.10531122, -0.40250087 0.16818407 0.10516191, -0.40250081 0.16243848 0.11090714, -0.40250075 0.16839141 0.10505114, -0.40250081 0.16232747 0.11111433, -0.40250075 0.16861659 0.10498289, -0.40250069 0.16225924 0.11133943, -0.40250069 0.16223614 0.11157367, -0.40250087 0.17388673 0.10172523, -0.4025009 0.17624311 0.10416032, -0.40250087 0.17387716 0.10182262, -0.40250084 0.17384872 0.10191644, -0.40250087 0.17380248 0.10200299, -0.40250075 0.17374021 0.10207868, -0.40250087 0.17335539 0.10246358, -0.40250087 0.17544317 0.10496009, -0.40250081 0.17327963 0.10252581, -0.40250081 0.17319314 0.10257197, -0.40250081 0.1730994 0.10260025, -0.4025009 0.17300181 0.10261, -0.40250081 0.16885075 0.10495961, -0.40250081 0.17622307 0.10433818, -0.40250081 0.17562108 0.10494015, -0.40250093 0.17616402 0.1045073, -0.40250081 0.17579022 0.10488094, -0.40250087 0.1760686 0.10465885, -0.40250081 0.1759419 0.10478569, -0.40250081 0.16258721 0.12009383, -0.40250075 0.16317342 0.12831852, -0.40250084 0.16309442 0.12839773, -0.40250081 0.16243806 0.11991192, -0.40250084 0.16303474 0.12849244, -0.40250075 0.16232711 0.11970425, -0.40250075 0.16326834 0.12825912, -0.40250069 0.16299781 0.12859815, -0.40250078 0.16337401 0.1282219, -0.40250078 0.16348532 0.12820944, -0.40250087 0.16800107 0.12550825, -0.40250087 0.16818289 0.12565756, -0.40250084 0.16839036 0.12576824, -0.40250075 0.1686154 0.12583658, -0.40250081 0.16223575 0.11924542, -0.40250069 0.16063482 0.13390937, -0.40250081 0.16225877 0.11947919, -0.40250084 0.16298527 0.12870947, -0.40250078 0.16298512 0.13197449, -0.40250075 0.16299464 0.13207215, -0.40250081 0.16302314 0.13216576, -0.40250069 0.16076349 0.13447347, -0.40250075 0.16066754 0.13419867, -0.40250075 0.1630692 0.13225225, -0.40250093 0.16313159 0.13232812, -0.40250078 0.1609185 0.13471991, -0.40250069 0.16112426 0.13492575, -0.40250075 0.16351633 0.13271293, -0.40250069 0.16137072 0.13508075, -0.40250081 0.16164553 0.1351766, -0.40250084 0.16193488 0.13520923, -0.40250093 0.1638701 0.13285953, -0.40250081 0.16377243 0.13284996, -0.40250075 0.1636786 0.13282141, -0.40250075 0.1635922 0.13277525, -0.40250075 0.1688495 0.12585965, -0.40250081 0.17544183 0.12586004, -0.40250084 0.17300029 0.12820989, -0.40250081 0.17309789 0.12821963, -0.40250081 0.17319164 0.12824816, -0.40250081 0.17327806 0.12829438, -0.4025009 0.17335391 0.1283567, -0.40250081 0.17561987 0.12588009, -0.40250087 0.17578894 0.12593949, -0.40250087 0.17594072 0.12603465, -0.40250087 0.17616275 0.12631294, -0.40250081 0.17606738 0.12616155, -0.40250087 0.17373879 0.12874144, -0.40250093 0.17622185 0.12648201, -0.40250087 0.1762419 0.12666032, -0.40250087 0.17380105 0.12881735, -0.40250093 0.17384726 0.12890381, -0.40250081 0.17387551 0.12899742, -0.40250078 0.1738852 0.12909511, -0.40250087 0.17300017 0.13286009, -0.40250087 0.17388509 0.13197511, -0.40250099 0.17624149 0.13391009, -0.40250087 0.17387553 0.13207272, -0.40250087 0.17384702 0.13216642, -0.40250087 0.17380084 0.13225284, -0.40250093 0.17373869 0.13232872, -0.40250081 0.1749413 0.13521028, -0.40250078 0.17335372 0.13271368, -0.40250087 0.17327784 0.13277584, -0.4025009 0.17319147 0.13282195, -0.40250087 0.17309761 0.13285044, -0.40250081 0.17523068 0.13517764, -0.40250081 0.17620882 0.1341995, -0.40250081 0.17611265 0.13447419, -0.40250087 0.17550543 0.13508135, -0.40250093 0.1759578 0.13472071, -0.4025009 0.17575197 0.13492671, -0.43336734 0.16112982 0.13340941, -0.43047398 0.1661415 0.13340956, -0.43047392 0.1582364 0.13340932, -0.42847395 0.1696056 0.1334098, -0.42539343 0.17494145 0.13341036, -0.42200089 0.17494145 0.13341025, -0.42200077 0.16043493 0.13340932, -0.42425925 0.16043472 0.13340932, -0.42847398 0.15543482 0.13340905, -0.42845482 0.15543482 0.13340896, -0.40400073 0.16043699 0.097409405, -0.42000097 0.17494349 0.09741009, -0.42000079 0.16043676 0.097409256, -0.40400088 0.17494354 0.09741009, -0.43200064 0.1597642 0.11640919, -0.43200058 0.15976366 0.12403066, -0.42850062 0.15626414 0.11640913, -0.43336737 0.16113013 0.12539721, -0.43047386 0.15823655 0.13069978, -0.42850071 0.15626323 0.13069957, -0.43336743 0.16113187 0.097409196, -0.43047404 0.15823819 0.10011876, -0.43047392 0.15823849 0.097409256, -0.43336734 0.16113132 0.10542119, -0.43200082 0.15976477 0.10678793, -0.42850077 0.15626501 0.10011844, -0.43200055 0.15976414 0.11440928, -0.42850071 0.15626425 0.11440904, -0.43200082 0.16349797 0.11640958, -0.42539337 0.17494243 0.11641014, -0.43200061 0.16349746 0.12403096, -0.43047398 0.16614157 0.13070032, -0.42847404 0.1696057 0.13070053, -0.43047398 0.16614316 0.10011897, -0.43047398 0.16614343 0.097409733, -0.4320007 0.16349848 0.10678817, -0.42847401 0.16960742 0.10011903, -0.43200073 0.16349795 0.11440957, -0.42200077 0.17494236 0.11641002, -0.42000097 0.17494315 0.10366023, -0.40400088 0.17494336 0.10366023, -0.42200083 0.16043586 0.11640925, -0.42200065 0.16043556 0.11978052, -0.42200077 0.16666175 0.12600753, -0.42200083 0.16688056 0.12628514, -0.42200077 0.16702826 0.12660629, -0.42200083 0.1670966 0.12695304, -0.42200077 0.16708204 0.12730631, -0.42200077 0.16698518 0.1276463, -0.42200071 0.16681147 0.12795398, -0.42200071 0.16657057 0.12821257, -0.42200083 0.16657196 0.10260654, -0.42200083 0.16681291 0.10286502, -0.42200071 0.1669866 0.10317314, -0.42200071 0.16708335 0.10351301, -0.42200089 0.16709808 0.10386623, -0.42200071 0.16702934 0.10421301, -0.42200071 0.16043605 0.1110378, -0.42200083 0.16043589 0.11440913, -0.42200083 0.1668817 0.10453413, -0.42200071 0.16666296 0.10481185, -0.43358269 0.15851814 0.10718108, -0.43367982 0.15861525 0.10703418, -0.43058872 0.15552472 0.096908964, -0.43379366 0.15872918 0.10690425, -0.43348861 0.15842403 0.10738624, -0.43343163 0.15836705 0.10760359, -0.43533814 0.1602736 0.10497615, -0.43533805 0.160274 0.096909352, -0.43341291 0.15834843 0.10782323, -0.43513942 0.16007492 0.10555861, -0.43528265 0.16021805 0.10531963, -0.43532294 0.16025834 0.10516239, -0.43533427 0.16026974 0.10506976, -0.43521976 0.16015521 0.10545457, -0.4352271 0.16016144 0.12537658, -0.43518546 0.16011973 0.1253131, -0.4351393 0.16007373 0.12526017, -0.43528304 0.16021724 0.12549958, -0.43532288 0.16025728 0.12565669, -0.43533814 0.16027226 0.12584242, -0.43379366 0.1587282 0.1239141, -0.4305886 0.15552247 0.13390902, -0.43360573 0.15854026 0.12367613, -0.43349558 0.15843008 0.12345115, -0.43343401 0.15836863 0.12322802, -0.4334181 0.15835263 0.12311137, -0.43341297 0.15834749 0.12299479, -0.43533799 0.16027182 0.13390926, -0.43350089 0.1636315 0.12299547, -0.43350071 0.16363235 0.10782374, -0.43350077 0.15856053 0.10782332, -0.43350068 0.15855956 0.122995, -0.43395269 0.16311784 0.10640941, -0.43538564 0.16063604 0.096909203, -0.43538556 0.16063561 0.10497618, -0.43375096 0.16346669 0.10664488, -0.42654812 0.17594342 0.096910097, -0.43338025 0.16410904 0.10759229, -0.43336684 0.16413239 0.10782368, -0.43342131 0.16403805 0.10736022, -0.43349004 0.16391884 0.10713253, -0.43358582 0.16375326 0.10691402, -0.43538564 0.16063398 0.13390937, -0.43395275 0.16311684 0.12440953, -0.43538564 0.16063455 0.12584242, -0.43363637 0.1636647 0.12399781, -0.42654818 0.17594133 0.13391021, -0.43336678 0.16413145 0.12299538, -0.43348902 0.16391985 0.12368367, -0.43337741 0.16411334 0.1232003, -0.40270084 0.17494138 0.13541022, -0.42495877 0.16193464 0.13540941, -0.4027009 0.16193476 0.13540941, -0.42539334 0.17494111 0.13541022, -0.43362617 0.16068132 0.13540941, -0.42948502 0.15654029 0.13540894, -0.42050087 0.16884948 0.1256597, -0.40270078 0.17544188 0.12565997, -0.40270078 0.16884951 0.1256597, -0.42050076 0.17544171 0.12566021, -0.40270084 0.16272858 0.11995221, -0.4205007 0.16814232 0.12536678, -0.40270078 0.16814248 0.12536666, -0.42050073 0.16272846 0.11995233, -0.40270066 0.16243622 0.11157364, -0.42050079 0.16243552 0.11924521, -0.40270066 0.16243574 0.11924518, -0.42050081 0.16243613 0.11157364, -0.40270072 0.16814353 0.10545257, -0.42050081 0.16814345 0.10545249, -0.40270075 0.1627291 0.11086641, -0.42050079 0.162729 0.11086655, -0.40270096 0.1754432 0.10516012, -0.42050081 0.1688505 0.10515983, -0.40270066 0.16885062 0.10515989, -0.42050076 0.1754429 0.10516048, -0.42150086 0.17644298 0.10416032, -0.40270072 0.1764435 0.096910186, -0.42568216 0.1764434 0.096910127, -0.40270087 0.17644322 0.10416029, -0.42150095 0.17644183 0.12666029, -0.42568216 0.17644124 0.13391024, -0.40270084 0.17644133 0.13391, -0.4027009 0.17644182 0.12666017, -0.43362629 0.16068378 0.095409431, -0.42495883 0.16193701 0.09540955, -0.42948508 0.15654258 0.095408954, -0.42539346 0.17494349 0.095410146, -0.40270084 0.17494382 0.095410176, -0.40270069 0.16193701 0.095409431, -0.42050084 0.168295 0.10532845, -0.42050087 0.16846798 0.10523606, -0.42050084 0.1686554 0.10517893, -0.4205007 0.16251214 0.11119092, -0.42050079 0.16245529 0.11137862, -0.4205007 0.16260457 0.11101804, -0.42050081 0.16251183 0.11962775, -0.4205007 0.16260408 0.11980072, -0.42050064 0.16245475 0.11944021, -0.42050067 0.16829383 0.12549111, -0.42050076 0.16865422 0.12564039, -0.42050084 0.16846678 0.12558368, -0.43379372 0.16261774 0.10711635, -0.43513921 0.16028701 0.10577068, -0.4337936 0.1589414 0.1071162, -0.43513942 0.16028591 0.12504792, -0.43379366 0.16261683 0.12370241, -0.43379366 0.15894033 0.12370203, -0.42000079 0.16666169 0.12600753, -0.40400052 0.16043612 0.11103783, -0.40270078 0.16043702 0.096909232, -0.42425933 0.1604367 0.096909232, -0.40270075 0.1604348 0.13390917, -0.42465144 0.16043566 0.11640931, -0.42465162 0.16043589 0.11440933, -0.42425939 0.16043468 0.13390917, -0.42000085 0.16666295 0.10481156, -0.42000079 0.1678153 0.10365988, -0.40400076 0.16781534 0.10365973, -0.4040007 0.16448674 0.1011093, -0.40400058 0.16448675 0.099459417, -0.4040007 0.17238688 0.099459685, -0.4040007 0.1723866 0.10110963, -0.43016499 0.15543464 0.13448897, -0.43037653 0.15543465 0.13390914, -0.42845482 0.15543465 0.13390893, -0.4299525 0.15543461 0.13470256, -0.42848945 0.15543461 0.13419023, -0.42859587 0.15543465 0.13446799, -0.42962265 0.15543464 0.13490656, -0.43037659 0.15543681 0.096909054, -0.42850074 0.15543588 0.11440892, -0.42850086 0.15543582 0.11640895, -0.42934281 0.15543681 0.095804371, -0.42915782 0.15543681 0.09575776, -0.42884398 0.15543683 0.096011467, -0.42952466 0.15543684 0.095868297, -0.42976791 0.15543687 0.095988341, -0.42862985 0.15543681 0.096289344, -0.42845485 0.15543668 0.096908964, -0.42998204 0.1554368 0.096139736, -0.42850745 0.15543684 0.096563883, -0.42846775 0.15543674 0.096736826, -0.43015528 0.15543678 0.096316405, -0.43028009 0.15543681 0.096510209, -0.43035334 0.15543678 0.096710958, -0.42850062 0.15543656 0.10011844, -0.42847395 0.15543661 0.10011844, -0.42850071 0.15543495 0.13069978, -0.42847383 0.15543486 0.13069978, -0.42877084 0.15543458 0.13472617, -0.4289501 0.15543459 0.13490611, -0.42915785 0.15543455 0.13506013, -0.43029514 0.15543461 0.13427606, -0.43035668 0.15543462 0.13409129, -0.4027009 0.16829398 0.12549129, -0.40270078 0.16846682 0.12558347, -0.4027009 0.16865452 0.12564045, -0.40270075 0.16245498 0.11944021, -0.40270084 0.16251186 0.11962775, -0.40270078 0.16260421 0.11980072, -0.40270078 0.1626047 0.11101804, -0.40270087 0.16251233 0.11119086, -0.40270075 0.16245539 0.11137841, -0.40270084 0.16865557 0.10517887, -0.40270066 0.16846797 0.10523603, -0.40270084 0.16829517 0.10532842, -0.42050982 0.17557511 0.125669, -0.40270078 0.1756644 0.1256851, -0.42053804 0.17571212 0.12569731, -0.4027009 0.17587587 0.12575921, -0.4206087 0.17589347 0.12576795, -0.40270078 0.1760654 0.1258783, -0.42072722 0.17607549 0.12588656, -0.40270078 0.17622374 0.12603661, -0.42092538 0.17625958 0.12608466, -0.40270096 0.17634287 0.12622634, -0.42117918 0.1763887 0.12633848, -0.40270072 0.17641675 0.12643775, -0.42117912 0.17638977 0.10448167, -0.42092538 0.17626069 0.10473565, -0.42072725 0.17607668 0.10493384, -0.4206087 0.17589462 0.10505224, -0.42053807 0.17571329 0.10512278, -0.42050996 0.1755763 0.10515139, -0.40270087 0.1764181 0.10438273, -0.40270084 0.17634411 0.10459397, -0.40270087 0.17622498 0.10478363, -0.40270084 0.17606667 0.10494197, -0.4027009 0.17587702 0.10506103, -0.40270084 0.17566557 0.10513509, -0.43364906 0.15875323 0.10729919, -0.43363544 0.16316563 0.10732228, -0.43356436 0.15864326 0.10747261, -0.43355539 0.1634433 0.10749767, -0.43352032 0.15858597 0.10762686, -0.43352777 0.16353887 0.10759304, -0.43351331 0.16358873 0.10766543, -0.43350559 0.15856682 0.10772521, -0.43350387 0.1636216 0.10774503, -0.43350145 0.16362962 0.10778437, -0.43537915 0.16058822 0.10522658, -0.43398067 0.16301733 0.1066115, -0.43396264 0.16289628 0.10680319, -0.43533283 0.16051197 0.10544015, -0.43526044 0.16042025 0.10560853, -0.43389904 0.16276062 0.10697467, -0.43520358 0.16035561 0.10569627, -0.43348563 0.16380608 0.10782383, -0.43343115 0.16400319 0.10768674, -0.43344045 0.16397429 0.10782374, -0.43344927 0.16397075 0.10754905, -0.43347222 0.16388042 0.10770676, -0.43347713 0.16392103 0.10742185, -0.43348825 0.16384794 0.10758946, -0.43349653 0.16375323 0.10772631, -0.43351343 0.16379827 0.1074811, -0.43350998 0.1637205 0.10762832, -0.43354219 0.16380391 0.10722501, -0.43353054 0.16367042 0.10753796, -0.43357176 0.16368154 0.10731385, -0.43357873 0.16355264 0.10739864, -0.43368119 0.16355497 0.10695804, -0.43369597 0.16343291 0.10708914, -0.43368062 0.16330205 0.10721154, -0.43344057 0.16397355 0.12299538, -0.43348563 0.1638051 0.12299547, -0.43538809 0.16061562 0.12571615, -0.43398076 0.16301635 0.12420738, -0.43537891 0.16058663 0.12559092, -0.43396264 0.16289532 0.1240157, -0.43533275 0.16051055 0.12537763, -0.43389904 0.16275971 0.1238443, -0.43525025 0.1604073 0.12519237, -0.43363544 0.16316462 0.12349651, -0.4335016 0.16362876 0.12303469, -0.43368122 0.16355416 0.12386084, -0.43369597 0.16343197 0.12372983, -0.43368062 0.16330117 0.12360737, -0.43352896 0.16382694 0.12356008, -0.43355972 0.16370434 0.12347636, -0.43356884 0.16357587 0.12339637, -0.43355542 0.16344231 0.12332103, -0.43352777 0.16353789 0.12322617, -0.43344918 0.1639698 0.12327004, -0.43343124 0.16400233 0.12313212, -0.43348846 0.16384706 0.12322963, -0.43347216 0.16387954 0.12311206, -0.43350995 0.16371959 0.12319101, -0.43351334 0.16358773 0.12315346, -0.43349665 0.16375232 0.1230929, -0.43350387 0.16362059 0.12307439, -0.43370858 0.15882976 0.12360514, -0.43363541 0.15873465 0.12349618, -0.43357691 0.15865852 0.12337757, -0.43353438 0.15860336 0.1232524, -0.43350911 0.15857051 0.12312365, -0.42589009 0.17641941 0.13391024, -0.42589003 0.17642149 0.096910246, -0.42608887 0.1763548 0.13391021, -0.42608881 0.17635691 0.096910395, -0.42626983 0.17625022 0.13391024, -0.42626977 0.17625238 0.096910246, -0.42642534 0.17611039 0.13391024, -0.4264254 0.17611256 0.096910276, -0.42495829 0.16040398 0.11640931, -0.4257524 0.15995429 0.11640931, -0.42593765 0.15970746 0.11640919, -0.42552084 0.16015828 0.11640931, -0.42525226 0.16031015 0.11640934, -0.42593783 0.15970771 0.11440933, -0.42575261 0.15995444 0.11440933, -0.42552096 0.16015831 0.1144091, -0.42525232 0.1603103 0.11440925, -0.42495847 0.16040412 0.11440913, -0.43057513 0.15552616 0.096730985, -0.43530446 0.16028194 0.096613951, -0.43053323 0.15553083 0.096550472, -0.43519688 0.16030785 0.096312918, -0.43041199 0.15554443 0.096278735, -0.43501109 0.16035229 0.096027441, -0.43019885 0.15556791 0.096000709, -0.43475392 0.16041371 0.095780768, -0.42989236 0.1556021 0.095750608, -0.43444303 0.16048819 0.095591106, -0.42944628 0.15565154 0.095535316, -0.43410364 0.16056938 0.095468648, -0.42946523 0.15608744 0.095440902, -0.43386179 0.16062748 0.095423467, -0.42567521 0.17518748 0.095455565, -0.43405557 0.16067205 0.095454611, -0.42593074 0.17540869 0.095582403, -0.43448675 0.16066051 0.095600881, -0.42614204 0.17559171 0.095768012, -0.43483564 0.1606511 0.09581966, -0.42631835 0.17574432 0.096011914, -0.43508825 0.16064417 0.096074887, -0.4264468 0.17585559 0.096295513, -0.43526548 0.16063939 0.096364416, -0.42652255 0.17592128 0.096596278, -0.43535703 0.16063681 0.096639998, -0.42654204 0.17593813 0.096755303, -0.42546397 0.17530951 0.095455386, -0.42568064 0.17643552 0.096755303, -0.42585313 0.17546199 0.095566072, -0.42569476 0.17555758 0.095558353, -0.42552781 0.17564137 0.095582403, -0.42558056 0.17591588 0.095768012, -0.42620242 0.17585801 0.095976777, -0.42593122 0.17603798 0.095959492, -0.42562461 0.17614473 0.096011914, -0.4256568 0.17631175 0.096295513, -0.42639959 0.17608303 0.096576847, -0.42607027 0.17631948 0.096566953, -0.42567569 0.17641023 0.096596546, -0.42610055 0.17616829 0.096244819, -0.4027009 0.17527738 0.095447816, -0.40270096 0.17559448 0.09555871, -0.40270084 0.17587875 0.095737375, -0.40270084 0.17611639 0.095974959, -0.40270084 0.1762951 0.096259333, -0.40270084 0.17640592 0.096576251, -0.43531007 0.16027848 0.13417843, -0.43055528 0.15552607 0.13418776, -0.43522114 0.16029985 0.13445371, -0.43045169 0.15553769 0.13446659, -0.43504876 0.16034116 0.13474375, -0.43027771 0.15555702 0.13472944, -0.43004125 0.15558331 0.13496044, -0.43480268 0.16039987 0.13499874, -0.42975777 0.15561496 0.13514692, -0.43446341 0.16048113 0.1352177, -0.42944616 0.15564941 0.13528267, -0.43404406 0.1605814 0.13536394, -0.42946523 0.15608521 0.13537708, -0.43386829 0.16067494 0.13539511, -0.42560345 0.17512318 0.13538507, -0.43411693 0.16066808 0.13534978, -0.42581838 0.1753093 0.13530493, -0.43446589 0.16065878 0.13522735, -0.42606449 0.17552237 0.13513082, -0.43478504 0.16065007 0.13503781, -0.42627466 0.17570436 0.13487959, -0.43504962 0.16064297 0.13479093, -0.42642972 0.17583859 0.13457197, -0.43524063 0.16063796 0.13450554, -0.42651999 0.1759169 0.13423896, -0.43535125 0.16063489 0.13420466, -0.42544585 0.17521416 0.13538507, -0.42567503 0.17640485 0.13423911, -0.42556614 0.17545922 0.13531521, -0.42549962 0.17549345 0.13530475, -0.42556119 0.17581283 0.13513091, -0.42563033 0.1754242 0.13532045, -0.42569309 0.1753877 0.13532048, -0.42575562 0.17534977 0.13531536, -0.42576116 0.17604084 0.13491327, -0.42561376 0.17608605 0.13487938, -0.42590308 0.17597888 0.13493031, -0.42603725 0.1759015 0.13493031, -0.42616165 0.17580965 0.13491327, -0.42583263 0.1762514 0.13460535, -0.42565244 0.17628734 0.13457197, -0.42600524 0.17618595 0.13462225, -0.4261654 0.1760935 0.13462228, -0.42630833 0.1759766 0.13460556, -0.42587599 0.17637879 0.13425937, -0.42606848 0.17631377 0.13426971, -0.42624453 0.17621213 0.13426962, -0.42639709 0.17607798 0.13425937, -0.40270084 0.17640391 0.13424411, -0.40270087 0.17629284 0.13456097, -0.40270072 0.17611414 0.13484532, -0.40270096 0.17587662 0.13508287, -0.40270096 0.17559229 0.13526157, -0.40270084 0.17527522 0.13537258, -0.42427629 0.16047321 0.096580423, -0.40270081 0.16047457 0.096575417, -0.42432386 0.16057523 0.096280016, -0.40270066 0.16058557 0.096258558, -0.42439401 0.16072546 0.09602455, -0.40270081 0.16076432 0.095973916, -0.42448771 0.16092651 0.095800765, -0.40270075 0.16100176 0.095736571, -0.42459977 0.16116703 0.095621951, -0.40270054 0.16128615 0.095557757, -0.42472315 0.16143134 0.095497049, -0.40270078 0.1616033 0.095446981, -0.4248426 0.16168736 0.095430322, -0.40270084 0.16160107 0.13537183, -0.42478809 0.16156854 0.135364, -0.40270078 0.161284 0.13526079, -0.42461675 0.16120112 0.1352177, -0.40270078 0.16099954 0.13508204, -0.42447811 0.16090377 0.13499895, -0.40270075 0.16076221 0.13484448, -0.42437768 0.16068828 0.13474384, -0.40270078 0.16058344 0.13456002, -0.42430711 0.16053711 0.13445416, -0.40270075 0.16047235 0.13424307, -0.42427075 0.16045903 0.13417843, -0.40261412 0.17627504 0.13455242, -0.40261406 0.17609853 0.13483316, -0.40257603 0.17607997 0.13481811, -0.40257621 0.17625359 0.13454205, -0.40254444 0.17555951 0.13519365, -0.40254438 0.17525841 0.135299, -0.40252066 0.1752499 0.13526207, -0.40257621 0.17636131 0.13423434, -0.40254468 0.17636617 0.13391021, -0.40257621 0.17639768 0.13391021, -0.40252072 0.17554319 0.13515961, -0.40254435 0.17622504 0.13452858, -0.4025445 0.17633051 0.13422722, -0.40265644 0.17628841 0.13455907, -0.40265626 0.17611015 0.13484216, -0.40252078 0.17580608 0.13499439, -0.40250587 0.17552474 0.13512149, -0.40250582 0.17577961 0.13496128, -0.40261412 0.17638446 0.13423961, -0.40261406 0.17642166 0.13391021, -0.40250579 0.1759925 0.1347484, -0.40265641 0.17639896 0.13424295, -0.40265641 0.17643642 0.13391024, -0.40261412 0.17527084 0.13535312, -0.40261406 0.17494138 0.13539022, -0.40257603 0.17494139 0.13536647, -0.402576 0.17526552 0.13532987, -0.40257615 0.17557327 0.13522232, -0.40254456 0.17582966 0.13502422, -0.40252078 0.17602561 0.13477486, -0.40265638 0.17494139 0.13540512, -0.40265638 0.17527403 0.13536769, -0.40250599 0.17615278 0.13449374, -0.40261406 0.17558357 0.13524395, -0.40250593 0.17628589 0.13391009, -0.40257615 0.17584939 0.13504866, -0.40254444 0.17605528 0.13479868, -0.40252066 0.17619078 0.13451189, -0.40265629 0.17559001 0.13525718, -0.40250587 0.17625228 0.13420919, -0.402614 0.17586429 0.13506752, -0.40250579 0.17524049 0.1352208, -0.40250587 0.17494138 0.13525453, -0.40252066 0.17494139 0.13529688, -0.40252066 0.17629345 0.13421908, -0.40252066 0.17632817 0.13391021, -0.40265632 0.17587341 0.13507903, -0.40254444 0.17494139 0.13533485, -0.40265632 0.16193485 0.13540429, -0.40261409 0.16193491 0.13538936, -0.40257621 0.16193491 0.13536552, -0.40254444 0.16193482 0.13533393, -0.4025206 0.1619349 0.13529605, -0.4025059 0.16193485 0.13525382, -0.40265644 0.17643686 0.12666032, -0.40261415 0.17642203 0.12666029, -0.40257621 0.17639814 0.12666023, -0.40254456 0.17636654 0.12666041, -0.40252072 0.1763287 0.12666041, -0.40250599 0.17628638 0.12666023, -0.40257606 0.16161072 0.13532904, -0.40254444 0.16065124 0.13452759, -0.40252048 0.16058281 0.13421789, -0.40252066 0.16068554 0.13451102, -0.40257609 0.16130295 0.13522154, -0.40254438 0.16131666 0.13519299, -0.40254438 0.16161776 0.13529828, -0.40254432 0.16054587 0.13422626, -0.40265629 0.16128609 0.1352562, -0.40252051 0.16085064 0.13477397, -0.40250579 0.16072352 0.13449275, -0.40250579 0.16088374 0.13474768, -0.40250579 0.16059034 0.13390937, -0.40265635 0.16100276 0.1350781, -0.40261406 0.16101201 0.13506654, -0.402614 0.16129254 0.13524306, -0.40261406 0.16160552 0.13535252, -0.40250587 0.1610966 0.13496068, -0.4026562 0.16160218 0.13536686, -0.402614 0.16049173 0.13423866, -0.40261406 0.16045462 0.13390917, -0.40257591 0.16047843 0.13390937, -0.40257603 0.16051498 0.13423339, -0.40257609 0.16062281 0.13454109, -0.40254438 0.16082096 0.13479772, -0.40252057 0.1610702 0.13499334, -0.40265632 0.16047734 0.13424188, -0.40265629 0.16043986 0.13390917, -0.40250584 0.16135143 0.13512045, -0.40261394 0.16060126 0.13455138, -0.40257606 0.1607962 0.13481727, -0.40254438 0.16104659 0.13502315, -0.40252054 0.16133305 0.13515872, -0.4026562 0.16058788 0.13455811, -0.40250579 0.16163565 0.1352202, -0.40261415 0.1607777 0.13483238, -0.40257615 0.16102676 0.13504797, -0.40250582 0.16062412 0.13420859, -0.40252057 0.16054812 0.13390937, -0.4025206 0.16162616 0.13526124, -0.40265629 0.16076604 0.13484132, -0.40254435 0.16051008 0.13390937, -0.4025445 0.17627504 0.12625882, -0.40254447 0.17634341 0.12645435, -0.40252066 0.17630646 0.12646291, -0.40257615 0.17565463 0.12572783, -0.40254444 0.17544182 0.12573537, -0.40257615 0.17544194 0.12570381, -0.40254444 0.17584319 0.12582716, -0.40254444 0.17564765 0.12575874, -0.40252066 0.17624085 0.12627536, -0.40257615 0.17585687 0.12579858, -0.40265632 0.17587356 0.12576374, -0.40261406 0.17605303 0.12589401, -0.402614 0.17586716 0.12577698, -0.40252066 0.17613518 0.12610734, -0.40250593 0.1762028 0.12629369, -0.4025059 0.17610216 0.12613362, -0.40265638 0.17606236 0.12588221, -0.40261412 0.17566007 0.12570471, -0.40261418 0.17544192 0.12568006, -0.40250587 0.17596838 0.12600002, -0.40265638 0.17566332 0.12569019, -0.40265626 0.17544186 0.12566504, -0.40261412 0.17639749 0.12644207, -0.40257609 0.17637426 0.12644735, -0.40257621 0.17630345 0.12624523, -0.40254438 0.17616487 0.12608367, -0.40252066 0.17599478 0.12596697, -0.40265638 0.17641196 0.1264388, -0.40250582 0.1758083 0.12589931, -0.40261412 0.17632511 0.12623507, -0.40257612 0.17618957 0.12606364, -0.40254444 0.17601845 0.12593716, -0.40252066 0.1758267 0.12586135, -0.40265644 0.17633842 0.12622854, -0.40250587 0.17562979 0.12583703, -0.40250582 0.17544179 0.12581566, -0.40261406 0.17620827 0.12604898, -0.40257603 0.17603813 0.1259124, -0.4025059 0.17626527 0.12647229, -0.4025206 0.17563923 0.1257956, -0.4025206 0.1754418 0.12577313, -0.40265641 0.17621979 0.12603983, -0.40265623 0.16044191 0.096909441, -0.40261412 0.16045685 0.096909441, -0.402576 0.16048054 0.096909441, -0.40254438 0.16051231 0.096909441, -0.40252054 0.16055022 0.09690956, -0.4025057 0.16059239 0.096909203, -0.40265638 0.16884962 0.1256648, -0.40261394 0.16884953 0.12567943, -0.40257609 0.16884953 0.12570331, -0.4025445 0.16884959 0.12573513, -0.40252054 0.16884953 0.12577301, -0.40250593 0.1688495 0.12581536, -0.402614 0.16060334 0.096267141, -0.40261406 0.1607797 0.095986314, -0.40257603 0.16079837 0.096001215, -0.40257591 0.16062485 0.096277304, -0.40257606 0.1605171 0.096585222, -0.40254435 0.16054793 0.096592344, -0.40254435 0.16131879 0.095625676, -0.40252045 0.1616285 0.095557369, -0.40252054 0.16133533 0.095659919, -0.40254438 0.16065344 0.096291341, -0.40254438 0.16161996 0.095520325, -0.40250582 0.16193685 0.095564641, -0.40265632 0.16058999 0.096260674, -0.40252066 0.1610724 0.095825203, -0.40250584 0.16135372 0.095698155, -0.40250579 0.16109861 0.095858254, -0.4026562 0.16076815 0.095977135, -0.40261394 0.16049391 0.096579976, -0.40250584 0.16088584 0.096071161, -0.40265629 0.16047944 0.096576728, -0.40261415 0.16160762 0.095466204, -0.402614 0.16193704 0.095429249, -0.40257609 0.16193694 0.095452972, -0.4026562 0.16193704 0.095414527, -0.40257591 0.16161288 0.095489331, -0.402576 0.16130508 0.095597275, -0.40254441 0.16104873 0.095795669, -0.40252057 0.16085276 0.096044727, -0.4026562 0.16160433 0.095451869, -0.40250587 0.16072556 0.096326031, -0.40261394 0.1612947 0.095575638, -0.402576 0.16102891 0.095770754, -0.40254441 0.16082317 0.096021093, -0.40252051 0.16068754 0.096307792, -0.4026562 0.16128837 0.095562406, -0.40250582 0.16062617 0.096610315, -0.40261394 0.16101401 0.095752038, -0.40250579 0.1616378 0.095598646, -0.40252054 0.16193694 0.09552256, -0.40252054 0.16058487 0.096600719, -0.4026562 0.16100489 0.095740505, -0.40254441 0.16193701 0.095484443, -0.40254441 0.16843811 0.12565321, -0.4025445 0.1682522 0.1255537, -0.40257609 0.16826975 0.12552723, -0.40257615 0.16845012 0.12562391, -0.40257615 0.16864589 0.12568328, -0.40261406 0.1684593 0.12560174, -0.40261412 0.16865064 0.12565997, -0.40250582 0.16820763 0.12562045, -0.40250582 0.16803247 0.12547678, -0.4025206 0.16806237 0.12544689, -0.40252072 0.16823114 0.12558538, -0.40252066 0.16842359 0.12568808, -0.40254444 0.16863972 0.12571433, -0.40250584 0.16840747 0.12572718, -0.40252054 0.16863239 0.12575155, -0.40250587 0.16862413 0.1257931, -0.40265632 0.16829114 0.12549543, -0.40265632 0.16813889 0.12537047, -0.40261412 0.16828306 0.12550774, -0.402614 0.1681284 0.12538084, -0.40265638 0.16846502 0.12558827, -0.40257615 0.16811159 0.12539786, -0.40265632 0.16865341 0.1256454, -0.4025445 0.16808921 0.12542018, -0.40265641 0.17494372 0.095415272, -0.40261415 0.17494373 0.095429935, -0.40257612 0.17494357 0.095453538, -0.40254444 0.17494354 0.095485337, -0.40252066 0.1749436 0.095523395, -0.40250611 0.1749436 0.095565833, -0.40265635 0.16272515 0.11995567, -0.40261406 0.16271465 0.1199664, -0.40257609 0.16269776 0.11998323, -0.40254438 0.16267535 0.1200055, -0.4025206 0.16264857 0.12003247, -0.40250593 0.16261865 0.12006239, -0.40257621 0.17526767 0.095490225, -0.40254456 0.17556182 0.09562654, -0.40254438 0.17526057 0.095520891, -0.40254447 0.17622721 0.096291937, -0.40252075 0.17629562 0.096601672, -0.40252072 0.17619312 0.096308507, -0.40257621 0.17557549 0.095598049, -0.40254444 0.17633255 0.096593179, -0.4026565 0.17559215 0.09556324, -0.40265638 0.17587568 0.095741101, -0.40252078 0.17602785 0.096045561, -0.40250593 0.17615494 0.096326746, -0.40250593 0.17599478 0.096071906, -0.40250579 0.17628792 0.096910186, -0.40261424 0.1758666 0.095752902, -0.40261412 0.17558587 0.095576473, -0.40261412 0.175273 0.095467009, -0.40250599 0.17578195 0.095859088, -0.40265641 0.17527625 0.095452584, -0.40261406 0.17638649 0.0965809, -0.40261406 0.17642373 0.096910395, -0.40257609 0.17639987 0.096910395, -0.40257603 0.17636335 0.096586056, -0.40257621 0.17625576 0.096278198, -0.40254462 0.17605761 0.096021958, -0.40252078 0.1758083 0.095825948, -0.40265641 0.17640111 0.096577622, -0.40265626 0.17643839 0.096910127, -0.40250593 0.17552699 0.095698513, -0.40261412 0.17627719 0.096267886, -0.402576 0.17608215 0.096002229, -0.40254444 0.17583193 0.095796324, -0.40252072 0.17554539 0.095660724, -0.40265638 0.1762905 0.096261419, -0.40250611 0.17524275 0.095599301, -0.40261412 0.17610094 0.095987119, -0.40257612 0.17585164 0.09577138, -0.40250599 0.1762543 0.09661106, -0.40252066 0.17525217 0.095558025, -0.40252066 0.17633019 0.096910395, -0.40265638 0.17611237 0.09597794, -0.40254444 0.17636827 0.096910395, -0.40254426 0.16244225 0.11965684, -0.40257615 0.16241217 0.11944855, -0.40257603 0.16247153 0.11964444, -0.40257594 0.162568 0.11982492, -0.40261403 0.16249356 0.11963547, -0.40261388 0.16258775 0.11981178, -0.40250582 0.16230243 0.11947063, -0.40250582 0.1622802 0.11924533, -0.40252054 0.16232251 0.11924536, -0.40252063 0.16234398 0.1194625, -0.40252054 0.16240725 0.11967126, -0.40254438 0.16238107 0.11945499, -0.40254438 0.16254163 0.11984266, -0.40250584 0.16236827 0.11968745, -0.40252054 0.16251004 0.11986388, -0.40250587 0.16247495 0.119887, -0.40265629 0.16244988 0.1194414, -0.40265629 0.16243066 0.11924518, -0.40261394 0.16243553 0.11944405, -0.40261394 0.1624158 0.11924521, -0.40265632 0.16250724 0.11962972, -0.40257609 0.16239209 0.11924521, -0.4026562 0.16260001 0.11980379, -0.40254435 0.16236044 0.11924542, -0.40265638 0.17643806 0.10416017, -0.40261412 0.1764234 0.10416017, -0.40257621 0.17639957 0.10416032, -0.40254462 0.17636785 0.10416032, -0.40252075 0.17632994 0.10416032, -0.40250593 0.1762877 0.10416002, -0.4026562 0.16243123 0.11157364, -0.402614 0.16241634 0.11157355, -0.402576 0.1623926 0.11157367, -0.40254435 0.16236088 0.11157367, -0.4025206 0.16232294 0.11157364, -0.40250582 0.16228077 0.11157367, -0.40261412 0.17632627 0.10458563, -0.40261406 0.17620946 0.10477123, -0.40257615 0.17619093 0.10475636, -0.40257621 0.1763048 0.10457513, -0.40254444 0.17584434 0.10499323, -0.40254444 0.17564893 0.10506151, -0.40252078 0.17564061 0.10502479, -0.40257621 0.17637552 0.10437296, -0.4025206 0.17582788 0.1049592, -0.40254456 0.17634468 0.10436583, -0.40254444 0.17627618 0.10456122, -0.40265641 0.17633966 0.10459194, -0.40252066 0.17599593 0.10485343, -0.40250587 0.17580947 0.10492099, -0.4025059 0.1759697 0.10482047, -0.40265632 0.176221 0.1047805, -0.40261406 0.17639883 0.10437832, -0.40250593 0.17610335 0.10468674, -0.40265644 0.17641313 0.10438169, -0.40261412 0.17566118 0.10511578, -0.40261406 0.17544305 0.10514043, -0.40257609 0.17544313 0.10511646, -0.40257621 0.17565596 0.10509262, -0.40257621 0.17585807 0.10502172, -0.40254444 0.17601961 0.10488326, -0.40252066 0.17613631 0.10471306, -0.40265641 0.17544311 0.10515521, -0.40265644 0.17566447 0.10513014, -0.40250593 0.17620398 0.10452641, -0.40261412 0.17586839 0.10504324, -0.40257621 0.17603938 0.104908, -0.4025445 0.1761661 0.10473681, -0.40252072 0.17624222 0.10454489, -0.4026565 0.17587483 0.10505647, -0.40250587 0.1762664 0.10434804, -0.40261406 0.17605422 0.10492647, -0.40250599 0.17563108 0.10498355, -0.40250605 0.17544323 0.10500465, -0.40252066 0.17544305 0.1050467, -0.40252078 0.17630771 0.10435749, -0.40265638 0.17606351 0.10493804, -0.40254444 0.17544308 0.10508487, -0.40257606 0.1624126 0.11136995, -0.40257609 0.16247199 0.11117423, -0.402614 0.1624939 0.11118335, -0.402614 0.1624359 0.11137471, -0.40250587 0.16247553 0.11093161, -0.4025057 0.16261916 0.11075658, -0.40252048 0.16251062 0.11095522, -0.40252054 0.16240767 0.11114771, -0.40254429 0.16254212 0.11097617, -0.40254438 0.16244274 0.11116213, -0.40254438 0.1623815 0.11136384, -0.40250579 0.16236858 0.11113153, -0.4025206 0.1623444 0.11135668, -0.40250587 0.16230285 0.11134804, -0.40265629 0.16260059 0.11101527, -0.40265632 0.16272557 0.11086295, -0.402614 0.16271506 0.11085267, -0.402614 0.16258822 0.11100728, -0.40257615 0.16269822 0.11083574, -0.40265632 0.16250771 0.11118896, -0.40257612 0.16256844 0.11099381, -0.40254435 0.16267587 0.11081336, -0.40265629 0.16245039 0.11137757, -0.40252054 0.16264905 0.11078662, -0.40265632 0.16885068 0.10515485, -0.402614 0.1688506 0.10514007, -0.40257609 0.16885063 0.10511614, -0.40254438 0.16885068 0.10508464, -0.40252057 0.16885068 0.10504652, -0.40250576 0.16885069 0.10500429, -0.40265626 0.16813996 0.10544903, -0.402614 0.16812959 0.10543857, -0.40257591 0.16811271 0.10542173, -0.40254438 0.16809033 0.10539956, -0.4025206 0.16806352 0.10537256, -0.40250576 0.16803369 0.10534263, -0.40254438 0.16843913 0.1051662, -0.40254444 0.16864102 0.10510505, -0.40257597 0.1686469 0.10513622, -0.40257597 0.16845128 0.10519556, -0.40257615 0.1682709 0.10529197, -0.40261409 0.16846044 0.10521764, -0.402614 0.16828406 0.10531176, -0.40250587 0.16862528 0.10502646, -0.4025206 0.16863345 0.10506783, -0.4025206 0.16842465 0.1051314, -0.40254438 0.16825329 0.10526574, -0.40250582 0.16840854 0.10509215, -0.4025206 0.16823225 0.10523424, -0.40250584 0.16820863 0.10519893, -0.40265632 0.1686547 0.10517416, -0.402614 0.16865176 0.10515974, -0.40265626 0.16846603 0.10523129, -0.40265635 0.16829237 0.10532416, -0.40200064 0.16348524 0.12820944, -0.40200073 0.16337407 0.1282219, -0.4020007 0.1632683 0.12825891, -0.40200061 0.16317345 0.12831852, -0.40200073 0.16309437 0.12839767, -0.40200064 0.16303469 0.12849265, -0.40200073 0.16299778 0.12859815, -0.40200064 0.16298518 0.12870941, -0.40200067 0.17300025 0.1282098, -0.40200078 0.17335387 0.1283564, -0.40200067 0.17327812 0.12829438, -0.4020009 0.17319164 0.12824804, -0.40200067 0.17309786 0.12821954, -0.40200078 0.17373879 0.12874144, -0.4020009 0.17388517 0.12909469, -0.40200078 0.17387562 0.12899733, -0.4020007 0.17384706 0.1289036, -0.4020007 0.17380096 0.12881714, -0.40200087 0.17388499 0.13197488, -0.40200087 0.17373857 0.13232872, -0.4020009 0.1738009 0.13225284, -0.4020007 0.17384695 0.13216633, -0.40200081 0.17387548 0.1320726, -0.4020009 0.17335352 0.13271359, -0.40200081 0.1730001 0.13285989, -0.40200078 0.17309757 0.13285032, -0.40200067 0.17319135 0.13282186, -0.40200067 0.17327784 0.13277584, -0.40200084 0.1638699 0.13285953, -0.40200078 0.16351634 0.13271299, -0.40200078 0.16359217 0.13277534, -0.40200084 0.16367854 0.1328215, -0.40200073 0.16377243 0.1328499, -0.40200078 0.16313142 0.13232809, -0.4020007 0.16298503 0.13197449, -0.40200078 0.16299456 0.13207212, -0.40200084 0.16302308 0.13216576, -0.40200073 0.16306922 0.13225213, -0.39250085 0.17300031 0.13286012, -0.39250085 0.17335379 0.13271359, -0.39250073 0.173278 0.13277569, -0.3925007 0.1738755 0.1320726, -0.39250088 0.17373863 0.13232857, -0.39250082 0.17388511 0.13197532, -0.39250088 0.17384711 0.13216633, -0.392501 0.17380089 0.13225284, -0.39250064 0.16326834 0.12825897, -0.39250082 0.16337411 0.12822208, -0.39250076 0.1631736 0.12831852, -0.39250076 0.16303481 0.12849265, -0.39250082 0.16298522 0.12870961, -0.39250079 0.16299781 0.12859836, -0.39250079 0.16309442 0.12839782, -0.3925007 0.1634853 0.12820944, -0.39250073 0.16298507 0.13197452, -0.3925007 0.16302316 0.13216576, -0.39250082 0.16313164 0.13232812, -0.39250076 0.16306941 0.13225213, -0.39250067 0.16299471 0.13207215, -0.39250082 0.16351648 0.13271293, -0.39250076 0.16359216 0.13277525, -0.39250082 0.16377248 0.13284996, -0.39250076 0.16367869 0.1328215, -0.39250082 0.16387005 0.1328595, -0.39250088 0.17300044 0.12820995, -0.39250079 0.17309794 0.12821966, -0.39250073 0.17319173 0.12824807, -0.3925007 0.17327814 0.12829432, -0.39250073 0.17335391 0.1283564, -0.3925007 0.17373873 0.12874141, -0.39250079 0.17380112 0.1288172, -0.39250085 0.17384729 0.1289036, -0.39250073 0.17387566 0.12899739, -0.39250091 0.17388538 0.1290949, -0.39250091 0.17309782 0.13285044, -0.39250079 0.17319155 0.13282195, -0.39300084 0.16251028 0.12848705, -0.39300066 0.16248526 0.12870947, -0.4015007 0.1624852 0.12870938, -0.4015007 0.16251019 0.12848696, -0.39300069 0.16258439 0.12827536, -0.40150073 0.16258428 0.12827536, -0.39300081 0.16270362 0.12808597, -0.40150067 0.16270339 0.12808603, -0.39300078 0.16286193 0.12792772, -0.4015007 0.16286178 0.12792766, -0.39300081 0.16305155 0.12780866, -0.40150079 0.16305146 0.12780854, -0.39300072 0.1632628 0.12773469, -0.4015007 0.16326259 0.12773448, -0.39300072 0.16348533 0.12770936, -0.40150073 0.16348524 0.12770951, -0.40150082 0.17370732 0.12800309, -0.39300075 0.17370746 0.12800309, -0.39300084 0.173556 0.12787849, -0.40150079 0.17355597 0.12787849, -0.3930009 0.17338307 0.1277861, -0.40150079 0.173383 0.1277861, -0.39300075 0.17319553 0.12772939, -0.40150076 0.17319544 0.12772915, -0.3930009 0.17300047 0.12771004, -0.40150079 0.17300034 0.12770998, -0.3930009 0.17370735 0.13306707, -0.40150076 0.17370725 0.13306707, -0.40150079 0.17355567 0.13319162, -0.3930009 0.17355572 0.13319162, -0.40150088 0.17338277 0.133284, -0.3930009 0.17338282 0.13328403, -0.40150094 0.17319523 0.13334098, -0.39300081 0.1731953 0.13334078, -0.40150079 0.17300013 0.13335994, -0.3930009 0.17300014 0.13335997, -0.4015007 0.16316287 0.13306648, -0.39300078 0.16316293 0.13306656, -0.39300084 0.16331448 0.13319102, -0.4015007 0.16331434 0.13319102, -0.39300087 0.16348736 0.13328356, -0.40150094 0.16348732 0.13328329, -0.39300078 0.16367494 0.13334018, -0.40150076 0.16367477 0.13334018, -0.39300078 0.16386999 0.13335949, -0.40150079 0.16386995 0.13335943, -0.39300069 0.16265368 0.13253024, -0.39300078 0.16277798 0.13268152, -0.4015007 0.1627779 0.13268143, -0.40150073 0.16265368 0.13253012, -0.39300069 0.16256113 0.13235706, -0.40150073 0.16256106 0.13235727, -0.39300084 0.1625043 0.13216957, -0.40150067 0.16250414 0.13216966, -0.39300069 0.16248509 0.13197449, -0.4015007 0.16248499 0.13197452, -0.40150079 0.17421649 0.13253048, -0.40150079 0.17409216 0.13268203, -0.39300075 0.17409217 0.13268223, -0.39300084 0.1742166 0.13253063, -0.40150082 0.1743089 0.13235795, -0.3930009 0.17430905 0.13235801, -0.40150103 0.17436589 0.13217026, -0.3930009 0.17436591 0.13217011, -0.40150076 0.174385 0.13197502, -0.39300075 0.17438506 0.13197508, -0.39300078 0.17409241 0.12838796, -0.40150076 0.17409232 0.12838775, -0.40150088 0.17421666 0.12853926, -0.39300078 0.17421675 0.12853929, -0.40150079 0.17430905 0.12871248, -0.39300075 0.17430922 0.12871233, -0.40150088 0.17436603 0.12889987, -0.39300081 0.17436615 0.12889975, -0.40150076 0.17438516 0.12909511, -0.3930009 0.17438525 0.1290949, -0.40200076 0.16387179 0.097959436, -0.40200073 0.16377428 0.097969092, -0.40200078 0.16368048 0.097997583, -0.40200078 0.16359407 0.098043747, -0.40200061 0.16351824 0.098105915, -0.4020007 0.17300195 0.097960003, -0.40200081 0.17335555 0.098106213, -0.40200078 0.17327978 0.098044313, -0.40200067 0.1731932 0.097997971, -0.40200078 0.17309956 0.097969688, -0.40200096 0.17374052 0.098491259, -0.40200081 0.17388695 0.098844923, -0.40200087 0.17387745 0.09874735, -0.4020009 0.17384896 0.098653592, -0.4020009 0.17380278 0.098566957, -0.4020007 0.17388669 0.10172511, -0.4020009 0.17374018 0.10207868, -0.40200078 0.17380252 0.1020029, -0.40200078 0.17384858 0.10191632, -0.4020007 0.17387708 0.1018225, -0.40200078 0.17335527 0.10246352, -0.40200081 0.17300183 0.10261, -0.40200078 0.17309938 0.10260025, -0.40200078 0.17319308 0.10257197, -0.40200078 0.1732796 0.10252596, -0.40200064 0.16348669 0.1026094, -0.40200064 0.1629867 0.10210944, -0.40200061 0.1629992 0.10222075, -0.40200084 0.16303624 0.10232637, -0.40200061 0.16309576 0.10242102, -0.40200073 0.16317496 0.1025003, -0.4020007 0.16326973 0.10255981, -0.40200061 0.16337542 0.10259686, -0.40200078 0.16298693 0.098844416, -0.40200078 0.16313335 0.098490722, -0.40200084 0.16307114 0.09856648, -0.40200084 0.16302495 0.098652996, -0.4020007 0.16299649 0.098746844, -0.39250085 0.17300183 0.10261021, -0.39250079 0.17319319 0.10257197, -0.39250073 0.17309934 0.10260046, -0.3925007 0.17387716 0.10182271, -0.39250079 0.17380247 0.10200278, -0.39250082 0.17388675 0.1017252, -0.39250082 0.17384878 0.10191632, -0.3925007 0.16359416 0.098043866, -0.39250064 0.16368057 0.097997583, -0.39250079 0.16351841 0.098105974, -0.39250088 0.17335534 0.10246349, -0.3925007 0.17327963 0.10252581, -0.39250094 0.17374034 0.10207868, -0.39250082 0.1630251 0.098653115, -0.39250067 0.16298695 0.098844118, -0.39250079 0.16299663 0.098746844, -0.39250082 0.16307129 0.098566569, -0.39250076 0.16313352 0.098490722, -0.39250082 0.16377442 0.097969152, -0.39250082 0.16387187 0.097959436, -0.39250082 0.16298681 0.10210944, -0.39250082 0.16326992 0.10255981, -0.39250076 0.16348679 0.1026094, -0.39250082 0.16337563 0.10259686, -0.39250082 0.16317506 0.1025003, -0.39250082 0.16309594 0.10242102, -0.39250076 0.16303633 0.10232637, -0.39250082 0.16299935 0.10222075, -0.39250088 0.17309973 0.097969688, -0.39250079 0.17319337 0.097997971, -0.39250085 0.17300212 0.097960003, -0.39250079 0.17327985 0.098044343, -0.39250085 0.1733557 0.098106511, -0.39250088 0.17374057 0.098491259, -0.39250073 0.1738489 0.098653592, -0.39250079 0.17387736 0.09874741, -0.39250085 0.17380282 0.098566957, -0.39250085 0.17388704 0.098845072, -0.40150064 0.17300178 0.10311014, -0.39300078 0.17300187 0.1031102, -0.39300084 0.17319699 0.10309089, -0.40150076 0.17319687 0.10309089, -0.39300075 0.17338452 0.10303415, -0.40150079 0.17338443 0.10303391, -0.39300081 0.17355743 0.10294143, -0.40150088 0.17355731 0.10294152, -0.39300075 0.17370896 0.10281719, -0.40150076 0.17370877 0.10281722, -0.39300081 0.16250616 0.098649271, -0.39300069 0.16248696 0.098844416, -0.4015007 0.16248691 0.098844118, -0.40150079 0.16250607 0.098649032, -0.39300075 0.16256317 0.098461635, -0.40150067 0.16256294 0.098461904, -0.39300072 0.16265555 0.098288722, -0.40150073 0.1626555 0.098288782, -0.39300081 0.16277987 0.098137297, -0.40150082 0.16277984 0.098137297, -0.4015007 0.16367663 0.097478516, -0.4015007 0.16387188 0.097459324, -0.39300084 0.16387196 0.097459324, -0.39300078 0.16367687 0.097478516, -0.40150073 0.16348913 0.097535558, -0.39300072 0.16348918 0.097535498, -0.40150067 0.16331622 0.097628035, -0.39300075 0.16331637 0.097627886, -0.40150073 0.16316476 0.09775237, -0.39300075 0.16316482 0.097752221, -0.39300084 0.17436759 0.10192034, -0.39300078 0.17438687 0.10172523, -0.40150064 0.17438672 0.10172523, -0.40150088 0.17436752 0.10192034, -0.39300078 0.17431067 0.10210798, -0.40150079 0.17431043 0.10210798, -0.39300084 0.17421824 0.10228065, -0.40150067 0.1742181 0.10228059, -0.39300078 0.17409384 0.10243229, -0.40150076 0.17409369 0.10243208, -0.40150076 0.17436762 0.098649867, -0.40150076 0.17438683 0.098844953, -0.39300078 0.17438698 0.098845072, -0.3930009 0.17436787 0.098649867, -0.40150076 0.17431082 0.0984625, -0.39300093 0.17431098 0.09846244, -0.40150088 0.17421843 0.098289259, -0.3930009 0.17421851 0.098289408, -0.40150082 0.17409413 0.098137833, -0.3930009 0.17409417 0.098137863, -0.3930009 0.1731973 0.097479232, -0.39300084 0.17300209 0.09745992, -0.40150076 0.17300199 0.097460009, -0.40150088 0.17319717 0.097479172, -0.39300081 0.17338474 0.097536154, -0.40150076 0.17338468 0.097536094, -0.39300093 0.17355774 0.097628422, -0.40150076 0.17355765 0.09762875, -0.39300081 0.17370924 0.097752966, -0.40150079 0.17370908 0.097752966, -0.39300072 0.16326423 0.10308451, -0.39300081 0.16348684 0.10310946, -0.40150082 0.16348669 0.10310946, -0.40150073 0.16326407 0.10308451, -0.39300072 0.16305286 0.10301054, -0.4015007 0.16305266 0.10301054, -0.39300069 0.16286327 0.10289145, -0.40150067 0.16286311 0.10289121, -0.39300084 0.16270499 0.1027329, -0.4015007 0.16270481 0.1027329, -0.39300072 0.16258584 0.10254318, -0.40150067 0.16258574 0.10254324, -0.39300075 0.16251189 0.102332, -0.40150079 0.16251175 0.10233185, -0.39300081 0.16248669 0.10210944, -0.4015007 0.16248658 0.10210923, -0.40050063 0.16448669 0.1011093, -0.40050071 0.16448683 0.099459417, -0.40050077 0.1723866 0.10110975, -0.40050063 0.17238678 0.099459775, -0.40050071 0.1644851 0.13135964, -0.40050083 0.17238508 0.13135988, -0.40050086 0.17238505 0.1297099, -0.40050063 0.16448501 0.12970918, -0.42000085 0.16657047 0.12821266, -0.42000085 0.16698523 0.12764627, -0.42000079 0.16681148 0.12795398, -0.42000067 0.16708201 0.12730643, -0.42000085 0.16709672 0.12695304, -0.42000067 0.16702819 0.12660649, -0.42000079 0.16688056 0.12628514, -0.42000079 0.16657205 0.10260654, -0.42000079 0.1668817 0.10453413, -0.42000085 0.16702946 0.10421301, -0.42000079 0.167098 0.10386623, -0.42000082 0.16708335 0.10351286, -0.42000079 0.16698658 0.10317311, -0.42000085 0.16681293 0.10286493, -0.43027854 0.15548207 0.096217938, -0.43030256 0.15550399 0.096198715, -0.43041113 0.15547566 0.096444763, -0.43025672 0.15546666 0.096235044, -0.43038774 0.15546247 0.096456595, -0.43054309 0.15548733 0.096908994, -0.43020743 0.15544444 0.096274681, -0.4303351 0.15544342 0.096482821, -0.43017828 0.15543827 0.096298285, -0.43030405 0.1554381 0.096498318, -0.43011415 0.15551721 0.095984019, -0.43009323 0.15549104 0.096008696, -0.43007398 0.1554727 0.096031465, -0.43002942 0.15544587 0.096083589, -0.4300029 0.15543853 0.096114911, -0.42988372 0.15557335 0.09576536, -0.42986861 0.15553474 0.095791407, -0.42985177 0.15550306 0.095820315, -0.4298358 0.15548065 0.095847972, -0.42979807 0.15544805 0.095912881, -0.42977524 0.15543903 0.095951714, -0.42944241 0.15561596 0.095547952, -0.42944115 0.15561599 0.095547356, -0.42942953 0.15558314 0.09556181, -0.42943406 0.15556654 0.095574416, -0.42941284 0.15555355 0.095577903, -0.42942405 0.15552528 0.095607229, -0.42939174 0.15552697 0.095595635, -0.42941374 0.15549543 0.095640339, -0.42935878 0.15549737 0.095621027, -0.42938852 0.15545164 0.09572152, -0.42931733 0.15547194 0.09565071, -0.42937315 0.15543972 0.09577129, -0.43051714 0.15548892 0.096672036, -0.42930543 0.15545242 0.095694728, -0.42925781 0.15544935 0.095691688, -0.42929173 0.15543979 0.095746554, -0.42920855 0.15543991 0.095724978, -0.4304896 0.15547192 0.096678443, -0.43049133 0.15545958 0.096908994, -0.43046516 0.15546001 0.096684285, -0.430435 0.15544245 0.096908964, -0.4304105 0.15544273 0.096697159, -0.4303782 0.1554379 0.096704729, -0.43043756 0.15549465 0.096431799, -0.43043506 0.15544039 0.13390914, -0.43049121 0.15545738 0.13390902, -0.43054307 0.15548518 0.13390902, -0.43021744 0.15544218 0.1345301, -0.42999893 0.15544404 0.13476053, -0.4300434 0.15547225 0.13481569, -0.43026793 0.15546468 0.13456935, -0.43016541 0.1554347 0.13448945, -0.4299528 0.15543458 0.13470307, -0.43044564 0.15548518 0.13434449, -0.43040451 0.15546027 0.13432577, -0.4303506 0.15544112 0.13430133, -0.42944306 0.15562299 0.13527387, -0.42944002 0.15559754 0.13526261, -0.42943636 0.15559784 0.13526431, -0.42943132 0.15555099 0.13523418, -0.42941353 0.155552 0.13524073, -0.42930692 0.15545025 0.13512269, -0.42926019 0.15544789 0.13512772, -0.42931932 0.15547077 0.1351687, -0.42941415 0.15549429 0.13517898, -0.42937315 0.1555067 0.13520765, -0.42938861 0.15544949 0.13509655, -0.42974699 0.15557007 0.13512436, -0.42973357 0.15553075 0.13509661, -0.42970937 0.15548374 0.13504654, -0.42967474 0.15544692 0.13497511, -0.43007559 0.15550853 0.13485605, -0.43030578 0.15549394 0.13459903, -0.43541196 0.16057415 0.13390917, -0.43540779 0.16038133 0.13390937, -0.43542334 0.16044487 0.13390937, -0.43537888 0.16032284 0.13390917, -0.43405026 0.16062558 0.13536707, -0.43404636 0.1605967 0.13536566, -0.43446484 0.16062912 0.13523418, -0.43445933 0.16057166 0.13523927, -0.43444958 0.16051489 0.13523412, -0.43478805 0.16060963 0.13504937, -0.43478385 0.16052897 0.13505855, -0.43476704 0.16044998 0.13504949, -0.43505916 0.16059381 0.13480559, -0.43505853 0.16049276 0.13481739, -0.43503308 0.16039507 0.13480559, -0.43525833 0.16058271 0.13451904, -0.43526322 0.16046582 0.1345301, -0.43522835 0.16035435 0.13451904, -0.43537515 0.16057611 0.13421264, -0.43542477 0.16051012 0.13390937, -0.43538481 0.16044992 0.13421935, -0.43534291 0.16033044 0.13421264, -0.43541187 0.16057457 0.12584242, -0.43542492 0.16051067 0.12584257, -0.43542331 0.16044535 0.12584257, -0.4354077 0.16038178 0.12584242, -0.43537885 0.16032334 0.12584242, -0.43528104 0.16027582 0.12527978, -0.43535438 0.16040345 0.12540838, -0.43528274 0.16032191 0.12525266, -0.43535066 0.1603511 0.1254282, -0.43522865 0.16026403 0.12517127, -0.43516016 0.16023508 0.12507793, -0.43517083 0.16018619 0.12511581, -0.43527573 0.16036999 0.12522924, -0.43522 0.16030854 0.1251443, -0.4352712 0.1602331 0.12530982, -0.43533716 0.16030169 0.12545049, -0.43522954 0.16022196 0.12520254, -0.43517083 0.16014193 0.12516046, -0.43525305 0.16019458 0.12534267, -0.4353143 0.1602564 0.1254746, -0.43522245 0.16018324 0.12523696, -0.43516013 0.16010375 0.12520909, -0.43520764 0.1601488 0.12527418, -0.43539816 0.16052946 0.12559834, -0.43540606 0.16047041 0.12560707, -0.43540218 0.1604114 0.12561765, -0.43538636 0.16035485 0.1256294, -0.43534836 0.16045703 0.12539166, -0.43535969 0.16030276 0.12564287, -0.43381441 0.15875821 0.12386347, -0.43382519 0.15879636 0.12381462, -0.43382514 0.15884063 0.12377033, -0.43381441 0.15888937 0.12373222, -0.43345022 0.15839285 0.122995, -0.43345451 0.15839453 0.12315346, -0.43347862 0.15843447 0.12314511, -0.43347794 0.15844472 0.12299479, -0.433496 0.1584776 0.123137, -0.43349504 0.15850109 0.12299479, -0.43350628 0.15852316 0.12312994, -0.433487 0.15842736 0.12331177, -0.43351018 0.1584674 0.12329487, -0.43352592 0.15851051 0.12327922, -0.4335342 0.15855633 0.1232648, -0.43354097 0.15848187 0.12346566, -0.43356204 0.15852159 0.12344051, -0.43357545 0.15856512 0.12341703, -0.43358046 0.15861107 0.12339569, -0.43363208 0.15857387 0.12363929, -0.43364975 0.15861306 0.12360416, -0.43365854 0.15865667 0.12357176, -0.43365842 0.15870357 0.12354288, -0.43349507 0.15850195 0.10782323, -0.433478 0.15844566 0.10782332, -0.43345022 0.1583938 0.10782332, -0.43350244 0.15851952 0.10772038, -0.43351871 0.15853883 0.107617, -0.43350953 0.15849319 0.10760603, -0.43349195 0.15847397 0.1077149, -0.43381447 0.15875925 0.10695512, -0.43382519 0.15879738 0.10700382, -0.43382531 0.15884179 0.10704813, -0.43381453 0.15889035 0.10708628, -0.43363208 0.15857488 0.10717926, -0.43364987 0.15861405 0.10721431, -0.43365872 0.15865777 0.1072465, -0.43365854 0.15870464 0.10727514, -0.43352509 0.15846683 0.10739166, -0.43354678 0.1585066 0.10741467, -0.43356085 0.1585498 0.10743625, -0.43356693 0.1585959 0.10745595, -0.433469 0.15840995 0.10758112, -0.43349266 0.15845008 0.10759396, -0.43344998 0.15839092 0.10770247, -0.43347424 0.15843089 0.10770888, -0.43516016 0.16023603 0.10574052, -0.43517095 0.16018748 0.10570235, -0.43517083 0.16014294 0.10565791, -0.43516004 0.16010496 0.10560936, -0.43540192 0.16041228 0.10520182, -0.43535039 0.16035184 0.10539112, -0.43535411 0.16040425 0.10541076, -0.43540582 0.1604712 0.10521243, -0.43542063 0.16049623 0.10509501, -0.4354119 0.16057588 0.10497618, -0.43542463 0.16051176 0.10497639, -0.43539813 0.1605304 0.10522092, -0.43541053 0.16055804 0.1050993, -0.43538624 0.16035575 0.10518966, -0.43533689 0.16030243 0.10536895, -0.43541738 0.16043401 0.10508961, -0.43542334 0.16044647 0.10497615, -0.43535972 0.16030382 0.10517631, -0.43531403 0.16025722 0.10534466, -0.43540159 0.16037382 0.10508353, -0.43540773 0.16038306 0.10497618, -0.43537343 0.16031843 0.10507689, -0.43537873 0.16032447 0.10497598, -0.43526578 0.16035986 0.10560641, -0.43527299 0.16031247 0.1055821, -0.43527189 0.16026729 0.10555408, -0.4352625 0.16022526 0.10552321, -0.43534803 0.16045786 0.10542745, -0.43524492 0.16018739 0.10548962, -0.43541187 0.16057625 0.096909352, -0.43542475 0.16051218 0.096909352, -0.43542334 0.16044694 0.096909352, -0.43540776 0.16038339 0.096909352, -0.43537873 0.16032489 0.096909203, -0.43405044 0.16062772 0.095451511, -0.4340539 0.16065675 0.095452733, -0.43444973 0.16051707 0.095584549, -0.43445942 0.16057396 0.095579304, -0.43446481 0.16063134 0.095584221, -0.43476716 0.16045235 0.095768996, -0.4347837 0.16053124 0.095760025, -0.43478796 0.16061179 0.095768996, -0.43503308 0.16039738 0.096012779, -0.43505871 0.16049495 0.096001215, -0.43505913 0.16059601 0.096012779, -0.43522835 0.16035663 0.096299447, -0.43526345 0.16046815 0.096288361, -0.43525845 0.16058475 0.096299447, -0.43534288 0.16033256 0.096605934, -0.43538472 0.16045201 0.096599258, -0.43537512 0.16057833 0.096606113 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 3, 0, 4, -1, 3, 1, 0, -1, 5, 6, 3, -1, 5, 3, 4, -1, 7, 6, 5, -1, 8, 7, 5, -1, 9, 10, 11, -1, 9, 11, 12, -1, 13, 10, 14, -1, 11, 10, 13, -1, 15, 14, 16, -1, 13, 14, 15, -1, 17, 18, 19, -1, 20, 18, 17, -1, 17, 21, 22, -1, 19, 21, 17, -1, 22, 23, 24, -1, 21, 23, 22, -1, 18, 20, 23, -1, 23, 20, 24, -1, 25, 26, 27, -1, 28, 26, 25, -1, 27, 29, 30, -1, 26, 29, 27, -1, 30, 31, 32, -1, 29, 31, 30, -1, 32, 31, 25, -1, 31, 28, 25, -1, 33, 34, 12, -1, 15, 34, 33, -1, 35, 33, 12, -1, 13, 15, 36, -1, 11, 37, 35, -1, 11, 36, 37, -1, 11, 35, 12, -1, 11, 13, 36, -1, 33, 36, 15, -1, 38, 39, 40, -1, 41, 42, 43, -1, 40, 42, 41, -1, 42, 44, 45, -1, 39, 44, 40, -1, 40, 44, 42, -1, 44, 46, 45, -1, 46, 47, 45, -1, 47, 48, 45, -1, 44, 49, 46, -1, 48, 50, 45, -1, 44, 51, 49, -1, 50, 52, 45, -1, 44, 53, 51, -1, 52, 54, 45, -1, 44, 55, 53, -1, 54, 56, 45, -1, 56, 57, 45, -1, 58, 59, 44, -1, 44, 59, 55, -1, 58, 60, 59, -1, 58, 61, 60, -1, 58, 62, 61, -1, 58, 63, 62, -1, 64, 65, 66, -1, 65, 67, 66, -1, 66, 67, 58, -1, 58, 68, 63, -1, 67, 69, 58, -1, 70, 69, 67, -1, 58, 71, 68, -1, 68, 71, 72, -1, 69, 71, 58, -1, 72, 71, 73, -1, 73, 71, 74, -1, 74, 71, 75, -1, 76, 77, 78, -1, 78, 77, 79, -1, 79, 77, 80, -1, 80, 77, 81, -1, 81, 77, 82, -1, 83, 77, 76, -1, 76, 84, 83, -1, 77, 85, 82, -1, 76, 86, 84, -1, 82, 87, 57, -1, 85, 87, 82, -1, 57, 87, 45, -1, 76, 88, 86, -1, 87, 89, 45, -1, 89, 90, 45, -1, 71, 91, 75, -1, 91, 92, 93, -1, 93, 92, 94, -1, 94, 92, 95, -1, 95, 92, 96, -1, 71, 92, 91, -1, 97, 98, 99, -1, 99, 98, 100, -1, 100, 98, 101, -1, 101, 98, 102, -1, 96, 98, 97, -1, 92, 98, 96, -1, 102, 98, 103, -1, 92, 104, 98, -1, 105, 106, 92, -1, 92, 107, 104, -1, 106, 108, 92, -1, 92, 109, 107, -1, 108, 109, 92, -1, 90, 110, 45, -1, 111, 112, 113, -1, 114, 115, 116, -1, 111, 115, 114, -1, 113, 115, 111, -1, 111, 117, 112, -1, 115, 118, 116, -1, 111, 119, 117, -1, 111, 120, 119, -1, 111, 121, 120, -1, 121, 122, 120, -1, 122, 123, 120, -1, 123, 124, 120, -1, 125, 126, 110, -1, 116, 126, 125, -1, 118, 126, 116, -1, 127, 126, 118, -1, 110, 126, 45, -1, 127, 128, 126, -1, 128, 129, 126, -1, 129, 130, 126, -1, 130, 131, 126, -1, 131, 132, 126, -1, 133, 134, 135, -1, 133, 136, 134, -1, 132, 137, 126, -1, 136, 138, 139, -1, 126, 138, 133, -1, 133, 138, 136, -1, 137, 140, 126, -1, 126, 140, 138, -1, 141, 140, 142, -1, 142, 140, 143, -1, 143, 140, 144, -1, 144, 140, 137, -1, 145, 146, 147, -1, 146, 148, 147, -1, 146, 149, 148, -1, 146, 150, 149, -1, 146, 151, 150, -1, 146, 152, 151, -1, 153, 154, 146, -1, 155, 154, 153, -1, 156, 154, 155, -1, 157, 154, 156, -1, 158, 154, 157, -1, 159, 154, 158, -1, 146, 154, 152, -1, 152, 154, 160, -1, 160, 154, 161, -1, 161, 154, 162, -1, 154, 163, 162, -1, 141, 164, 140, -1, 165, 166, 167, -1, 167, 166, 168, -1, 168, 166, 169, -1, 169, 166, 170, -1, 163, 166, 165, -1, 154, 166, 163, -1, 164, 171, 140, -1, 166, 171, 170, -1, 172, 171, 173, -1, 173, 171, 174, -1, 174, 171, 175, -1, 175, 171, 164, -1, 170, 171, 172, -1, 166, 176, 171, -1, 177, 176, 166, -1, 178, 179, 177, -1, 180, 179, 178, -1, 177, 179, 176, -1, 176, 179, 181, -1, 147, 120, 145, -1, 145, 120, 124, -1, 76, 102, 103, -1, 76, 103, 88, -1, 182, 183, 184, -1, 185, 186, 187, -1, 188, 185, 187, -1, 189, 185, 188, -1, 190, 189, 191, -1, 190, 185, 189, -1, 192, 193, 194, -1, 192, 194, 195, -1, 196, 197, 198, -1, 199, 200, 197, -1, 182, 200, 199, -1, 182, 184, 200, -1, 197, 201, 198, -1, 200, 201, 197, -1, 202, 203, 204, -1, 202, 205, 203, -1, 203, 206, 207, -1, 205, 206, 203, -1, 208, 209, 206, -1, 206, 209, 207, -1, 210, 211, 212, -1, 199, 213, 182, -1, 212, 213, 199, -1, 213, 183, 182, -1, 211, 214, 212, -1, 212, 214, 213, -1, 214, 186, 185, -1, 211, 186, 214, -1, 202, 215, 205, -1, 216, 215, 202, -1, 215, 217, 205, -1, 215, 218, 217, -1, 3, 6, 218, -1, 217, 7, 219, -1, 6, 7, 218, -1, 218, 7, 217, -1, 186, 211, 220, -1, 187, 186, 220, -1, 221, 222, 193, -1, 221, 193, 192, -1, 220, 223, 224, -1, 225, 220, 224, -1, 226, 220, 225, -1, 227, 220, 226, -1, 187, 227, 228, -1, 187, 228, 229, -1, 187, 229, 230, -1, 187, 230, 231, -1, 187, 231, 232, -1, 187, 232, 188, -1, 187, 220, 227, -1, 5, 4, 233, -1, 5, 233, 234, -1, 5, 234, 235, -1, 5, 235, 236, -1, 5, 236, 237, -1, 5, 237, 238, -1, 8, 239, 240, -1, 8, 238, 241, -1, 8, 241, 242, -1, 8, 242, 239, -1, 8, 5, 238, -1, 210, 212, 196, -1, 196, 212, 197, -1, 217, 208, 206, -1, 217, 219, 208, -1, 243, 244, 245, -1, 246, 245, 244, -1, 247, 243, 245, -1, 248, 247, 245, -1, 249, 250, 245, -1, 249, 245, 246, -1, 251, 248, 245, -1, 252, 253, 254, -1, 252, 254, 255, -1, 252, 255, 249, -1, 252, 249, 246, -1, 256, 253, 252, -1, 257, 258, 259, -1, 260, 257, 259, -1, 261, 260, 259, -1, 262, 259, 263, -1, 262, 261, 259, -1, 264, 263, 265, -1, 264, 265, 266, -1, 264, 266, 267, -1, 264, 267, 268, -1, 264, 268, 269, -1, 264, 269, 251, -1, 264, 251, 245, -1, 264, 262, 263, -1, 270, 262, 264, -1, 271, 272, 273, -1, 271, 273, 274, -1, 205, 217, 206, -1, 212, 199, 197, -1, 275, 276, 277, -1, 278, 276, 275, -1, 279, 280, 281, -1, 279, 282, 280, -1, 279, 283, 282, -1, 279, 284, 283, -1, 279, 278, 284, -1, 279, 276, 278, -1, 285, 286, 287, -1, 285, 288, 286, -1, 289, 281, 290, -1, 289, 291, 288, -1, 289, 292, 291, -1, 289, 290, 292, -1, 289, 279, 281, -1, 289, 288, 285, -1, 293, 294, 295, -1, 296, 294, 293, -1, 296, 297, 294, -1, 297, 298, 294, -1, 299, 300, 301, -1, 302, 300, 299, -1, 303, 304, 305, -1, 306, 304, 303, -1, 307, 308, 309, -1, 308, 310, 309, -1, 311, 312, 313, -1, 314, 312, 311, -1, 315, 316, 317, -1, 315, 318, 316, -1, 319, 320, 321, -1, 319, 322, 320, -1, 319, 323, 324, -1, 321, 323, 319, -1, 324, 325, 326, -1, 323, 325, 324, -1, 327, 328, 329, -1, 327, 330, 328, -1, 328, 331, 332, -1, 330, 331, 328, -1, 333, 334, 314, -1, 335, 336, 337, -1, 334, 338, 314, -1, 312, 308, 335, -1, 335, 308, 336, -1, 338, 316, 314, -1, 314, 318, 312, -1, 312, 318, 308, -1, 316, 318, 314, -1, 318, 310, 308, -1, 310, 339, 340, -1, 310, 341, 339, -1, 310, 306, 341, -1, 304, 342, 343, -1, 342, 299, 344, -1, 304, 299, 342, -1, 306, 302, 304, -1, 318, 302, 310, -1, 310, 302, 306, -1, 304, 302, 299, -1, 345, 346, 347, -1, 348, 349, 350, -1, 351, 224, 34, -1, 351, 34, 15, -1, 16, 351, 15, -1, 225, 224, 351, -1, 352, 195, 353, -1, 194, 353, 195, -1, 354, 194, 4, -1, 0, 354, 4, -1, 240, 239, 352, -1, 240, 352, 34, -1, 355, 352, 353, -1, 355, 34, 352, -1, 12, 34, 355, -1, 223, 240, 34, -1, 356, 357, 240, -1, 356, 240, 223, -1, 224, 223, 34, -1, 9, 12, 355, -1, 358, 189, 188, -1, 358, 188, 9, -1, 354, 353, 194, -1, 355, 358, 9, -1, 359, 360, 361, -1, 359, 361, 352, -1, 239, 242, 359, -1, 239, 359, 352, -1, 222, 221, 361, -1, 222, 361, 360, -1, 216, 202, 204, -1, 362, 363, 195, -1, 352, 362, 195, -1, 352, 361, 362, -1, 192, 363, 364, -1, 192, 195, 363, -1, 365, 192, 364, -1, 221, 365, 361, -1, 221, 192, 365, -1, 365, 362, 361, -1, 366, 367, 368, -1, 369, 370, 371, -1, 369, 371, 372, -1, 369, 366, 370, -1, 367, 373, 374, -1, 367, 374, 375, -1, 376, 377, 378, -1, 379, 376, 378, -1, 380, 378, 381, -1, 380, 379, 378, -1, 1, 382, 2, -1, 383, 381, 384, -1, 383, 384, 385, -1, 383, 380, 381, -1, 386, 385, 382, -1, 386, 383, 385, -1, 387, 386, 382, -1, 373, 388, 387, -1, 373, 382, 1, -1, 373, 387, 382, -1, 389, 1, 390, -1, 389, 373, 1, -1, 374, 373, 389, -1, 190, 391, 392, -1, 368, 190, 191, -1, 367, 375, 391, -1, 367, 190, 368, -1, 367, 391, 190, -1, 372, 371, 393, -1, 372, 393, 394, -1, 372, 394, 395, -1, 396, 397, 367, -1, 366, 396, 367, -1, 366, 368, 370, -1, 304, 343, 305, -1, 305, 343, 398, -1, 398, 342, 399, -1, 343, 342, 398, -1, 399, 344, 400, -1, 342, 344, 399, -1, 400, 299, 301, -1, 344, 299, 400, -1, 309, 310, 401, -1, 401, 340, 402, -1, 310, 340, 401, -1, 402, 339, 403, -1, 340, 339, 402, -1, 403, 341, 303, -1, 339, 341, 403, -1, 341, 306, 303, -1, 312, 335, 313, -1, 313, 335, 404, -1, 404, 337, 405, -1, 335, 337, 404, -1, 405, 336, 406, -1, 337, 336, 405, -1, 406, 308, 307, -1, 336, 308, 406, -1, 316, 338, 317, -1, 407, 338, 408, -1, 317, 338, 407, -1, 408, 334, 409, -1, 338, 334, 408, -1, 409, 333, 311, -1, 334, 333, 409, -1, 333, 314, 311, -1, 300, 302, 410, -1, 411, 410, 412, -1, 411, 300, 410, -1, 413, 412, 414, -1, 413, 411, 412, -1, 415, 414, 416, -1, 415, 413, 414, -1, 417, 416, 418, -1, 417, 415, 416, -1, 419, 418, 420, -1, 419, 417, 418, -1, 421, 420, 324, -1, 421, 419, 420, -1, 326, 421, 324, -1, 422, 324, 420, -1, 422, 319, 324, -1, 423, 420, 418, -1, 423, 422, 420, -1, 424, 418, 416, -1, 424, 423, 418, -1, 425, 416, 414, -1, 425, 424, 416, -1, 426, 414, 412, -1, 426, 425, 414, -1, 427, 412, 410, -1, 427, 426, 412, -1, 318, 410, 302, -1, 318, 427, 410, -1, 428, 322, 319, -1, 428, 319, 422, -1, 429, 422, 423, -1, 429, 428, 422, -1, 430, 423, 424, -1, 430, 429, 423, -1, 431, 424, 425, -1, 431, 430, 424, -1, 432, 425, 426, -1, 432, 431, 425, -1, 433, 426, 427, -1, 433, 432, 426, -1, 315, 427, 318, -1, 315, 433, 427, -1, 345, 434, 435, -1, 347, 434, 345, -1, 435, 436, 437, -1, 434, 436, 435, -1, 437, 438, 439, -1, 439, 438, 440, -1, 436, 438, 437, -1, 440, 441, 442, -1, 442, 441, 443, -1, 438, 441, 440, -1, 443, 273, 272, -1, 441, 273, 443, -1, 275, 277, 444, -1, 445, 275, 444, -1, 446, 444, 447, -1, 446, 447, 448, -1, 446, 445, 444, -1, 449, 448, 450, -1, 449, 446, 448, -1, 345, 450, 346, -1, 345, 449, 450, -1, 443, 272, 451, -1, 445, 278, 275, -1, 446, 278, 445, -1, 345, 435, 449, -1, 452, 453, 281, -1, 452, 281, 280, -1, 454, 280, 282, -1, 454, 452, 280, -1, 455, 451, 453, -1, 455, 453, 452, -1, 456, 282, 283, -1, 456, 454, 282, -1, 457, 455, 452, -1, 457, 452, 454, -1, 458, 440, 442, -1, 458, 442, 443, -1, 458, 451, 455, -1, 458, 443, 451, -1, 459, 454, 456, -1, 459, 457, 454, -1, 460, 439, 440, -1, 460, 458, 455, -1, 460, 440, 458, -1, 460, 455, 457, -1, 461, 283, 284, -1, 461, 456, 283, -1, 462, 437, 439, -1, 462, 439, 460, -1, 462, 460, 457, -1, 462, 457, 459, -1, 463, 459, 456, -1, 463, 456, 461, -1, 464, 435, 437, -1, 464, 437, 462, -1, 464, 462, 459, -1, 464, 459, 463, -1, 465, 284, 278, -1, 465, 461, 284, -1, 466, 446, 449, -1, 466, 463, 461, -1, 466, 465, 278, -1, 466, 461, 465, -1, 466, 278, 446, -1, 467, 435, 464, -1, 467, 449, 435, -1, 467, 464, 463, -1, 467, 463, 466, -1, 467, 466, 449, -1, 290, 281, 453, -1, 468, 453, 451, -1, 468, 290, 453, -1, 469, 451, 272, -1, 469, 468, 451, -1, 271, 469, 272, -1, 470, 287, 286, -1, 470, 286, 471, -1, 472, 471, 473, -1, 472, 470, 471, -1, 474, 473, 475, -1, 474, 472, 473, -1, 476, 475, 349, -1, 476, 474, 475, -1, 348, 476, 349, -1, 288, 471, 286, -1, 477, 349, 475, -1, 271, 478, 469, -1, 479, 288, 291, -1, 479, 471, 288, -1, 480, 475, 473, -1, 480, 473, 471, -1, 480, 471, 479, -1, 481, 477, 475, -1, 481, 475, 480, -1, 482, 479, 291, -1, 483, 480, 479, -1, 483, 479, 482, -1, 484, 485, 477, -1, 484, 486, 485, -1, 484, 477, 481, -1, 484, 481, 480, -1, 484, 480, 483, -1, 487, 291, 292, -1, 487, 482, 291, -1, 488, 292, 290, -1, 488, 290, 468, -1, 488, 487, 292, -1, 489, 482, 487, -1, 489, 483, 482, -1, 490, 468, 469, -1, 490, 487, 488, -1, 490, 488, 468, -1, 490, 489, 487, -1, 491, 492, 486, -1, 491, 484, 483, -1, 491, 483, 489, -1, 491, 486, 484, -1, 493, 494, 492, -1, 493, 478, 494, -1, 493, 492, 491, -1, 493, 469, 478, -1, 493, 490, 469, -1, 493, 489, 490, -1, 493, 491, 489, -1, 350, 349, 495, -1, 496, 477, 497, -1, 495, 477, 496, -1, 349, 477, 495, -1, 497, 485, 498, -1, 477, 485, 497, -1, 498, 486, 499, -1, 485, 486, 498, -1, 486, 492, 499, -1, 499, 494, 274, -1, 492, 494, 499, -1, 494, 478, 274, -1, 478, 271, 274, -1, 500, 323, 321, -1, 500, 321, 501, -1, 502, 501, 503, -1, 502, 500, 501, -1, 504, 503, 505, -1, 504, 502, 503, -1, 506, 505, 507, -1, 506, 504, 505, -1, 289, 507, 279, -1, 289, 506, 507, -1, 220, 356, 223, -1, 211, 356, 220, -1, 211, 508, 356, -1, 509, 210, 510, -1, 511, 210, 509, -1, 512, 210, 511, -1, 508, 210, 512, -1, 211, 210, 508, -1, 210, 196, 510, -1, 196, 198, 510, -1, 198, 375, 510, -1, 209, 513, 374, -1, 208, 513, 209, -1, 219, 513, 208, -1, 219, 514, 513, -1, 219, 515, 514, -1, 219, 516, 515, -1, 219, 517, 516, -1, 517, 7, 357, -1, 219, 7, 517, -1, 357, 8, 240, -1, 7, 8, 357, -1, 216, 204, 203, -1, 215, 216, 203, -1, 3, 218, 390, -1, 3, 390, 1, -1, 207, 389, 390, -1, 215, 203, 207, -1, 218, 215, 207, -1, 390, 218, 207, -1, 201, 213, 214, -1, 200, 213, 201, -1, 391, 201, 392, -1, 214, 392, 201, -1, 185, 190, 392, -1, 214, 185, 392, -1, 213, 200, 184, -1, 183, 213, 184, -1, 518, 245, 250, -1, 518, 250, 519, -1, 520, 519, 521, -1, 520, 518, 519, -1, 522, 521, 523, -1, 522, 520, 521, -1, 524, 523, 525, -1, 524, 522, 523, -1, 526, 525, 527, -1, 526, 524, 525, -1, 528, 527, 529, -1, 528, 526, 527, -1, 530, 529, 531, -1, 530, 528, 529, -1, 329, 531, 327, -1, 329, 530, 531, -1, 532, 330, 327, -1, 532, 327, 533, -1, 534, 533, 535, -1, 534, 532, 533, -1, 536, 535, 537, -1, 536, 534, 535, -1, 538, 537, 539, -1, 538, 536, 537, -1, 540, 539, 541, -1, 540, 538, 539, -1, 542, 541, 543, -1, 542, 540, 541, -1, 544, 543, 276, -1, 544, 542, 543, -1, 279, 544, 276, -1, 545, 330, 532, -1, 507, 544, 279, -1, 321, 546, 501, -1, 547, 532, 534, -1, 547, 534, 536, -1, 548, 549, 545, -1, 548, 550, 549, -1, 548, 532, 547, -1, 548, 545, 532, -1, 548, 547, 536, -1, 548, 536, 550, -1, 551, 536, 538, -1, 551, 538, 540, -1, 552, 553, 550, -1, 552, 554, 553, -1, 552, 536, 551, -1, 552, 550, 536, -1, 555, 540, 542, -1, 555, 542, 544, -1, 555, 507, 505, -1, 555, 544, 507, -1, 556, 503, 501, -1, 556, 505, 503, -1, 556, 557, 554, -1, 556, 546, 557, -1, 556, 501, 546, -1, 556, 555, 505, -1, 558, 554, 552, -1, 558, 552, 551, -1, 558, 540, 555, -1, 558, 556, 554, -1, 558, 551, 540, -1, 558, 555, 556, -1, 559, 331, 330, -1, 559, 330, 545, -1, 560, 545, 549, -1, 560, 559, 545, -1, 561, 549, 550, -1, 561, 560, 549, -1, 562, 550, 553, -1, 562, 561, 550, -1, 563, 553, 554, -1, 563, 562, 553, -1, 564, 554, 557, -1, 564, 557, 546, -1, 564, 563, 554, -1, 320, 546, 321, -1, 320, 564, 546, -1, 565, 264, 566, -1, 565, 270, 264, -1, 567, 566, 568, -1, 567, 565, 566, -1, 569, 568, 570, -1, 569, 570, 571, -1, 569, 567, 568, -1, 572, 571, 573, -1, 572, 569, 571, -1, 574, 573, 575, -1, 574, 572, 573, -1, 576, 575, 577, -1, 576, 574, 575, -1, 297, 577, 298, -1, 297, 576, 577, -1, 578, 297, 296, -1, 578, 296, 579, -1, 580, 579, 581, -1, 580, 578, 579, -1, 582, 581, 583, -1, 582, 580, 581, -1, 584, 583, 585, -1, 584, 582, 583, -1, 586, 585, 587, -1, 586, 584, 585, -1, 588, 587, 589, -1, 588, 586, 587, -1, 590, 589, 289, -1, 590, 588, 589, -1, 285, 590, 289, -1, 579, 296, 591, -1, 500, 592, 323, -1, 289, 589, 506, -1, 593, 594, 595, -1, 593, 591, 594, -1, 596, 579, 591, -1, 596, 591, 593, -1, 596, 593, 595, -1, 597, 579, 596, -1, 597, 595, 583, -1, 597, 596, 595, -1, 598, 583, 581, -1, 598, 581, 579, -1, 598, 579, 597, -1, 598, 597, 583, -1, 599, 595, 600, -1, 601, 595, 599, -1, 602, 583, 595, -1, 602, 595, 601, -1, 603, 585, 583, -1, 603, 583, 602, -1, 604, 605, 592, -1, 604, 600, 605, -1, 604, 599, 600, -1, 606, 601, 599, -1, 606, 599, 604, -1, 607, 602, 601, -1, 607, 601, 606, -1, 608, 589, 587, -1, 608, 587, 585, -1, 608, 585, 603, -1, 608, 603, 602, -1, 608, 602, 607, -1, 609, 604, 592, -1, 609, 592, 500, -1, 610, 500, 502, -1, 610, 606, 604, -1, 610, 609, 500, -1, 610, 604, 609, -1, 611, 502, 504, -1, 611, 606, 610, -1, 611, 607, 606, -1, 611, 610, 502, -1, 612, 504, 506, -1, 612, 589, 608, -1, 612, 611, 504, -1, 612, 506, 589, -1, 612, 608, 607, -1, 612, 607, 611, -1, 325, 323, 592, -1, 613, 325, 592, -1, 614, 592, 605, -1, 614, 613, 592, -1, 615, 605, 600, -1, 615, 614, 605, -1, 616, 600, 595, -1, 616, 615, 600, -1, 617, 595, 594, -1, 617, 616, 595, -1, 618, 594, 591, -1, 618, 617, 594, -1, 293, 591, 296, -1, 293, 618, 591, -1, 353, 354, 619, -1, 620, 619, 621, -1, 620, 353, 619, -1, 622, 621, 623, -1, 622, 620, 621, -1, 624, 623, 625, -1, 624, 622, 623, -1, 626, 625, 627, -1, 626, 624, 625, -1, 628, 627, 629, -1, 628, 626, 627, -1, 630, 629, 631, -1, 630, 628, 629, -1, 332, 631, 328, -1, 332, 630, 631, -1, 632, 295, 294, -1, 632, 294, 633, -1, 634, 633, 635, -1, 634, 632, 633, -1, 636, 635, 637, -1, 636, 634, 635, -1, 638, 637, 639, -1, 638, 636, 637, -1, 640, 639, 641, -1, 640, 638, 639, -1, 642, 641, 643, -1, 642, 640, 641, -1, 355, 643, 358, -1, 355, 642, 643, -1, 644, 645, 646, -1, 647, 648, 649, -1, 647, 650, 651, -1, 644, 646, 652, -1, 647, 651, 653, -1, 647, 653, 648, -1, 654, 614, 615, -1, 654, 615, 655, -1, 656, 652, 657, -1, 654, 655, 658, -1, 654, 658, 659, -1, 656, 657, 660, -1, 661, 649, 662, -1, 661, 647, 649, -1, 663, 180, 178, -1, 661, 650, 647, -1, 663, 660, 180, -1, 661, 659, 650, -1, 664, 665, 325, -1, 664, 662, 665, -1, 664, 613, 614, -1, 666, 667, 668, -1, 664, 325, 613, -1, 664, 614, 654, -1, 664, 661, 662, -1, 666, 668, 669, -1, 664, 654, 659, -1, 664, 659, 661, -1, 670, 669, 645, -1, 670, 645, 644, -1, 671, 652, 656, -1, 671, 644, 652, -1, 672, 656, 660, -1, 672, 660, 663, -1, 673, 674, 667, -1, 673, 618, 674, -1, 673, 667, 666, -1, 618, 293, 674, -1, 675, 178, 177, -1, 675, 663, 178, -1, 676, 669, 670, -1, 676, 666, 669, -1, 677, 670, 644, -1, 677, 644, 671, -1, 678, 671, 656, -1, 678, 656, 672, -1, 679, 672, 663, -1, 679, 663, 675, -1, 680, 666, 676, -1, 680, 617, 618, -1, 680, 618, 673, -1, 680, 673, 666, -1, 681, 166, 682, -1, 681, 177, 166, -1, 681, 675, 177, -1, 683, 676, 670, -1, 683, 670, 677, -1, 684, 671, 678, -1, 684, 677, 671, -1, 685, 686, 171, -1, 685, 176, 181, -1, 651, 678, 672, -1, 685, 171, 176, -1, 651, 672, 679, -1, 687, 682, 688, -1, 646, 689, 686, -1, 687, 679, 675, -1, 687, 675, 681, -1, 687, 681, 682, -1, 690, 616, 617, -1, 690, 676, 683, -1, 646, 686, 685, -1, 690, 680, 676, -1, 657, 181, 179, -1, 690, 617, 680, -1, 657, 685, 181, -1, 658, 677, 684, -1, 645, 691, 689, -1, 658, 683, 677, -1, 645, 689, 646, -1, 650, 678, 651, -1, 650, 684, 678, -1, 652, 685, 657, -1, 653, 688, 648, -1, 652, 646, 685, -1, 653, 687, 688, -1, 653, 679, 687, -1, 653, 651, 679, -1, 660, 179, 180, -1, 660, 657, 179, -1, 655, 615, 616, -1, 655, 616, 690, -1, 655, 690, 683, -1, 655, 683, 658, -1, 669, 668, 691, -1, 669, 691, 645, -1, 659, 658, 684, -1, 659, 684, 650, -1, 674, 293, 295, -1, 674, 295, 692, -1, 667, 692, 693, -1, 667, 674, 692, -1, 668, 693, 694, -1, 668, 667, 693, -1, 691, 694, 695, -1, 691, 668, 694, -1, 689, 695, 696, -1, 689, 691, 695, -1, 686, 696, 697, -1, 686, 689, 696, -1, 171, 697, 140, -1, 171, 686, 697, -1, 698, 325, 665, -1, 698, 326, 325, -1, 699, 665, 662, -1, 699, 698, 665, -1, 700, 662, 649, -1, 700, 699, 662, -1, 701, 649, 648, -1, 701, 700, 649, -1, 702, 648, 688, -1, 702, 701, 648, -1, 703, 688, 682, -1, 703, 702, 688, -1, 154, 682, 166, -1, 154, 703, 682, -1, 704, 705, 706, -1, 707, 708, 709, -1, 707, 709, 710, -1, 711, 706, 712, -1, 711, 712, 713, -1, 714, 695, 694, -1, 714, 715, 695, -1, 714, 710, 716, -1, 714, 716, 715, -1, 717, 718, 719, -1, 720, 636, 721, -1, 720, 634, 636, -1, 717, 713, 718, -1, 720, 721, 708, -1, 720, 708, 707, -1, 722, 694, 693, -1, 723, 134, 136, -1, 722, 714, 694, -1, 722, 707, 710, -1, 722, 710, 714, -1, 723, 719, 134, -1, 724, 693, 692, -1, 725, 726, 727, -1, 724, 632, 634, -1, 724, 634, 720, -1, 724, 707, 722, -1, 724, 722, 693, -1, 725, 727, 704, -1, 724, 720, 707, -1, 724, 692, 632, -1, 728, 704, 706, -1, 728, 706, 711, -1, 729, 713, 717, -1, 729, 711, 713, -1, 730, 719, 723, -1, 730, 717, 719, -1, 731, 642, 355, -1, 731, 732, 726, -1, 731, 355, 732, -1, 731, 726, 725, -1, 733, 136, 139, -1, 733, 723, 136, -1, 734, 725, 704, -1, 734, 704, 728, -1, 735, 728, 711, -1, 735, 711, 729, -1, 736, 729, 717, -1, 736, 717, 730, -1, 737, 730, 723, -1, 737, 723, 733, -1, 738, 640, 642, -1, 738, 642, 731, -1, 738, 725, 734, -1, 738, 731, 725, -1, 739, 140, 697, -1, 739, 138, 140, -1, 739, 139, 138, -1, 739, 733, 139, -1, 740, 734, 728, -1, 740, 728, 735, -1, 295, 632, 692, -1, 741, 742, 126, -1, 709, 735, 729, -1, 709, 729, 736, -1, 741, 126, 133, -1, 712, 743, 742, -1, 716, 730, 737, -1, 716, 736, 730, -1, 744, 697, 696, -1, 712, 742, 741, -1, 744, 733, 739, -1, 744, 739, 697, -1, 744, 737, 733, -1, 718, 133, 135, -1, 745, 640, 738, -1, 745, 638, 640, -1, 718, 741, 133, -1, 745, 738, 734, -1, 745, 734, 740, -1, 706, 705, 743, -1, 708, 735, 709, -1, 708, 740, 735, -1, 706, 743, 712, -1, 713, 741, 718, -1, 710, 736, 716, -1, 713, 712, 741, -1, 710, 709, 736, -1, 715, 696, 695, -1, 715, 716, 737, -1, 719, 135, 134, -1, 715, 737, 744, -1, 719, 718, 135, -1, 715, 744, 696, -1, 721, 636, 638, -1, 721, 745, 740, -1, 704, 727, 705, -1, 721, 740, 708, -1, 721, 638, 745, -1, 746, 747, 748, -1, 749, 750, 751, -1, 752, 753, 754, -1, 749, 748, 755, -1, 749, 756, 750, -1, 752, 757, 753, -1, 749, 755, 756, -1, 758, 413, 415, -1, 159, 703, 154, -1, 758, 415, 759, -1, 760, 761, 762, -1, 760, 754, 761, -1, 758, 759, 763, -1, 758, 763, 746, -1, 764, 751, 765, -1, 766, 156, 155, -1, 764, 749, 751, -1, 764, 748, 749, -1, 764, 746, 748, -1, 766, 762, 156, -1, 767, 768, 300, -1, 767, 765, 768, -1, 769, 699, 700, -1, 767, 411, 413, -1, 767, 300, 411, -1, 767, 413, 758, -1, 769, 700, 770, -1, 767, 764, 765, -1, 767, 758, 746, -1, 767, 746, 764, -1, 771, 770, 757, -1, 771, 757, 752, -1, 772, 754, 760, -1, 772, 752, 754, -1, 773, 760, 762, -1, 773, 762, 766, -1, 774, 326, 698, -1, 774, 698, 699, -1, 774, 421, 326, -1, 774, 699, 769, -1, 775, 155, 153, -1, 775, 766, 155, -1, 776, 770, 771, -1, 776, 769, 770, -1, 777, 771, 752, -1, 777, 752, 772, -1, 778, 760, 773, -1, 778, 772, 760, -1, 779, 766, 775, -1, 779, 773, 766, -1, 780, 769, 776, -1, 780, 419, 421, -1, 780, 421, 774, -1, 780, 774, 769, -1, 781, 153, 146, -1, 781, 146, 782, -1, 781, 775, 153, -1, 783, 771, 777, -1, 783, 776, 771, -1, 747, 777, 772, -1, 747, 772, 778, -1, 755, 778, 773, -1, 784, 159, 158, -1, 784, 703, 159, -1, 755, 773, 779, -1, 753, 702, 703, -1, 785, 781, 782, -1, 785, 775, 781, -1, 785, 782, 786, -1, 753, 703, 784, -1, 785, 779, 775, -1, 787, 776, 783, -1, 787, 417, 419, -1, 761, 158, 157, -1, 761, 784, 158, -1, 787, 780, 776, -1, 787, 419, 780, -1, 763, 777, 747, -1, 757, 701, 702, -1, 763, 783, 777, -1, 757, 702, 753, -1, 748, 747, 778, -1, 754, 753, 784, -1, 748, 778, 755, -1, 756, 755, 779, -1, 756, 779, 785, -1, 754, 784, 761, -1, 756, 786, 750, -1, 762, 157, 156, -1, 756, 785, 786, -1, 759, 415, 417, -1, 762, 761, 157, -1, 759, 417, 787, -1, 759, 783, 763, -1, 759, 787, 783, -1, 770, 700, 701, -1, 746, 763, 747, -1, 770, 701, 757, -1, 732, 355, 353, -1, 732, 353, 788, -1, 726, 789, 790, -1, 726, 788, 789, -1, 726, 732, 788, -1, 727, 726, 790, -1, 705, 791, 792, -1, 705, 790, 791, -1, 705, 727, 790, -1, 743, 792, 793, -1, 743, 705, 792, -1, 742, 793, 45, -1, 742, 743, 793, -1, 126, 742, 45, -1, 794, 300, 768, -1, 794, 301, 300, -1, 795, 768, 765, -1, 795, 794, 768, -1, 796, 765, 751, -1, 796, 795, 765, -1, 797, 751, 750, -1, 797, 796, 751, -1, 798, 750, 786, -1, 798, 797, 750, -1, 799, 786, 782, -1, 799, 798, 786, -1, 145, 782, 146, -1, 145, 799, 782, -1, 800, 791, 790, -1, 801, 802, 803, -1, 800, 804, 805, -1, 800, 806, 791, -1, 800, 805, 806, -1, 801, 807, 802, -1, 808, 622, 624, -1, 809, 810, 811, -1, 39, 812, 44, -1, 808, 624, 813, -1, 808, 813, 814, -1, 809, 803, 810, -1, 808, 814, 815, -1, 816, 790, 789, -1, 816, 800, 790, -1, 817, 41, 43, -1, 816, 815, 804, -1, 816, 804, 800, -1, 817, 811, 41, -1, 818, 789, 788, -1, 818, 620, 622, -1, 818, 622, 808, -1, 819, 820, 821, -1, 818, 808, 815, -1, 818, 815, 816, -1, 819, 821, 822, -1, 818, 816, 789, -1, 818, 788, 620, -1, 823, 822, 807, -1, 823, 807, 801, -1, 824, 801, 803, -1, 824, 803, 809, -1, 825, 809, 811, -1, 825, 811, 817, -1, 826, 630, 332, -1, 826, 827, 820, -1, 826, 332, 827, -1, 826, 820, 819, -1, 828, 43, 42, -1, 828, 817, 43, -1, 829, 822, 823, -1, 829, 819, 822, -1, 830, 801, 824, -1, 830, 823, 801, -1, 831, 809, 825, -1, 831, 824, 809, -1, 832, 825, 817, -1, 832, 817, 828, -1, 833, 819, 829, -1, 833, 628, 630, -1, 833, 630, 826, -1, 833, 826, 819, -1, 834, 45, 793, -1, 834, 42, 45, -1, 834, 828, 42, -1, 835, 829, 823, -1, 835, 823, 830, -1, 836, 830, 824, -1, 353, 620, 788, -1, 836, 824, 831, -1, 837, 39, 38, -1, 805, 831, 825, -1, 837, 812, 39, -1, 805, 825, 832, -1, 802, 838, 812, -1, 839, 793, 792, -1, 839, 832, 828, -1, 839, 828, 834, -1, 802, 812, 837, -1, 839, 834, 793, -1, 840, 626, 628, -1, 840, 829, 835, -1, 810, 38, 40, -1, 840, 833, 829, -1, 840, 628, 833, -1, 810, 837, 38, -1, 814, 835, 830, -1, 807, 841, 838, -1, 814, 830, 836, -1, 807, 838, 802, -1, 804, 836, 831, -1, 803, 837, 810, -1, 804, 831, 805, -1, 803, 802, 837, -1, 806, 792, 791, -1, 806, 839, 792, -1, 806, 805, 832, -1, 806, 832, 839, -1, 811, 40, 41, -1, 813, 624, 626, -1, 811, 810, 40, -1, 813, 626, 840, -1, 813, 835, 814, -1, 813, 840, 835, -1, 822, 821, 841, -1, 822, 841, 807, -1, 815, 814, 836, -1, 815, 836, 804, -1, 842, 843, 844, -1, 845, 795, 796, -1, 845, 846, 847, -1, 845, 847, 795, -1, 845, 844, 846, -1, 848, 123, 122, -1, 848, 849, 850, -1, 848, 850, 851, -1, 848, 122, 849, -1, 852, 853, 842, -1, 852, 851, 853, -1, 854, 796, 797, -1, 854, 845, 796, -1, 854, 842, 844, -1, 854, 844, 845, -1, 855, 124, 123, -1, 855, 123, 848, -1, 855, 848, 851, -1, 855, 851, 852, -1, 856, 797, 798, -1, 856, 854, 797, -1, 856, 852, 842, -1, 856, 842, 854, -1, 857, 798, 799, -1, 857, 799, 124, -1, 857, 124, 855, -1, 857, 856, 798, -1, 857, 855, 852, -1, 794, 400, 301, -1, 857, 852, 856, -1, 122, 121, 849, -1, 145, 124, 799, -1, 858, 859, 305, -1, 858, 305, 398, -1, 860, 861, 859, -1, 860, 859, 858, -1, 862, 398, 399, -1, 862, 858, 398, -1, 843, 863, 861, -1, 843, 861, 860, -1, 846, 858, 862, -1, 846, 860, 858, -1, 864, 399, 400, -1, 864, 862, 399, -1, 864, 400, 794, -1, 853, 865, 863, -1, 853, 863, 843, -1, 844, 860, 846, -1, 844, 843, 860, -1, 847, 794, 795, -1, 847, 862, 864, -1, 847, 846, 862, -1, 847, 864, 794, -1, 851, 850, 865, -1, 851, 865, 853, -1, 842, 853, 843, -1, 827, 332, 331, -1, 827, 331, 866, -1, 820, 866, 867, -1, 820, 827, 866, -1, 821, 867, 868, -1, 821, 820, 867, -1, 841, 868, 869, -1, 841, 821, 868, -1, 838, 869, 870, -1, 838, 841, 869, -1, 812, 870, 871, -1, 812, 838, 870, -1, 44, 871, 58, -1, 44, 812, 871, -1, 303, 305, 859, -1, 872, 859, 861, -1, 872, 303, 859, -1, 873, 861, 863, -1, 873, 872, 861, -1, 874, 863, 865, -1, 874, 873, 863, -1, 875, 865, 850, -1, 875, 874, 865, -1, 876, 850, 849, -1, 876, 875, 850, -1, 877, 849, 121, -1, 877, 876, 849, -1, 111, 877, 121, -1, 878, 879, 880, -1, 878, 880, 881, -1, 882, 883, 884, -1, 885, 869, 868, -1, 882, 884, 886, -1, 885, 881, 887, -1, 885, 887, 888, -1, 885, 888, 869, -1, 889, 560, 561, -1, 890, 891, 892, -1, 889, 561, 893, -1, 890, 886, 891, -1, 889, 893, 879, -1, 889, 879, 878, -1, 894, 868, 867, -1, 894, 885, 868, -1, 894, 881, 885, -1, 895, 67, 65, -1, 894, 878, 881, -1, 895, 892, 67, -1, 896, 867, 866, -1, 896, 866, 331, -1, 896, 559, 560, -1, 897, 898, 899, -1, 896, 331, 559, -1, 896, 560, 889, -1, 896, 894, 867, -1, 897, 899, 900, -1, 896, 889, 878, -1, 896, 878, 894, -1, 901, 900, 883, -1, 901, 883, 882, -1, 902, 882, 886, -1, 902, 886, 890, -1, 903, 890, 892, -1, 903, 892, 895, -1, 564, 320, 904, -1, 905, 904, 898, -1, 905, 564, 904, -1, 905, 898, 897, -1, 906, 65, 64, -1, 906, 895, 65, -1, 907, 900, 901, -1, 907, 897, 900, -1, 871, 66, 58, -1, 908, 882, 902, -1, 908, 901, 882, -1, 909, 890, 903, -1, 909, 902, 890, -1, 910, 903, 895, -1, 910, 895, 906, -1, 911, 897, 907, -1, 911, 563, 564, -1, 911, 564, 905, -1, 911, 905, 897, -1, 912, 64, 66, -1, 912, 66, 871, -1, 912, 906, 64, -1, 913, 907, 901, -1, 913, 901, 908, -1, 880, 908, 902, -1, 914, 915, 71, -1, 880, 902, 909, -1, 914, 71, 69, -1, 887, 909, 903, -1, 887, 903, 910, -1, 884, 916, 915, -1, 917, 871, 870, -1, 917, 910, 906, -1, 917, 906, 912, -1, 917, 912, 871, -1, 884, 915, 914, -1, 918, 562, 563, -1, 918, 907, 913, -1, 891, 69, 70, -1, 918, 563, 911, -1, 918, 911, 907, -1, 891, 914, 69, -1, 879, 908, 880, -1, 883, 919, 916, -1, 879, 913, 908, -1, 883, 916, 884, -1, 881, 880, 909, -1, 886, 914, 891, -1, 881, 909, 887, -1, 886, 884, 914, -1, 888, 870, 869, -1, 888, 917, 870, -1, 888, 887, 910, -1, 892, 70, 67, -1, 888, 910, 917, -1, 892, 891, 70, -1, 893, 562, 918, -1, 893, 561, 562, -1, 893, 918, 913, -1, 893, 913, 879, -1, 900, 899, 919, -1, 900, 919, 883, -1, 920, 874, 875, -1, 920, 921, 922, -1, 920, 923, 921, -1, 920, 922, 874, -1, 924, 125, 110, -1, 924, 925, 926, -1, 924, 110, 925, -1, 924, 926, 927, -1, 928, 929, 930, -1, 928, 927, 929, -1, 931, 920, 875, -1, 931, 930, 923, -1, 931, 923, 920, -1, 932, 116, 125, -1, 932, 125, 924, -1, 932, 924, 927, -1, 932, 927, 928, -1, 933, 875, 876, -1, 933, 928, 930, -1, 933, 931, 875, -1, 933, 930, 931, -1, 934, 876, 877, -1, 934, 114, 116, -1, 934, 877, 114, -1, 934, 933, 876, -1, 934, 116, 932, -1, 934, 932, 928, -1, 934, 928, 933, -1, 872, 403, 303, -1, 111, 114, 877, -1, 935, 936, 309, -1, 935, 309, 401, -1, 937, 938, 936, -1, 937, 936, 935, -1, 939, 401, 402, -1, 939, 935, 401, -1, 940, 941, 938, -1, 940, 938, 937, -1, 921, 935, 939, -1, 921, 937, 935, -1, 942, 872, 873, -1, 942, 402, 403, -1, 942, 939, 402, -1, 942, 403, 872, -1, 929, 943, 941, -1, 929, 941, 940, -1, 923, 940, 937, -1, 923, 937, 921, -1, 922, 873, 874, -1, 922, 939, 942, -1, 922, 942, 873, -1, 922, 921, 939, -1, 927, 926, 943, -1, 927, 943, 929, -1, 930, 929, 940, -1, 930, 940, 923, -1, 904, 320, 322, -1, 904, 322, 944, -1, 898, 944, 945, -1, 898, 904, 944, -1, 899, 945, 946, -1, 899, 898, 945, -1, 919, 946, 947, -1, 919, 899, 946, -1, 916, 947, 948, -1, 916, 919, 947, -1, 915, 948, 949, -1, 915, 916, 948, -1, 71, 949, 92, -1, 71, 915, 949, -1, 307, 309, 936, -1, 950, 936, 938, -1, 950, 307, 936, -1, 951, 938, 941, -1, 951, 950, 938, -1, 952, 941, 943, -1, 952, 951, 941, -1, 953, 943, 926, -1, 953, 952, 943, -1, 954, 926, 925, -1, 954, 953, 926, -1, 955, 925, 110, -1, 955, 954, 925, -1, 90, 955, 110, -1, 956, 957, 958, -1, 956, 958, 959, -1, 960, 961, 962, -1, 963, 947, 946, -1, 960, 962, 964, -1, 963, 959, 965, -1, 963, 965, 966, -1, 963, 966, 947, -1, 967, 429, 430, -1, 968, 969, 970, -1, 967, 430, 971, -1, 968, 964, 969, -1, 967, 971, 957, -1, 967, 957, 956, -1, 972, 946, 945, -1, 972, 963, 946, -1, 972, 959, 963, -1, 973, 109, 108, -1, 972, 956, 959, -1, 973, 970, 109, -1, 974, 945, 944, -1, 974, 944, 322, -1, 974, 428, 429, -1, 975, 976, 977, -1, 974, 322, 428, -1, 974, 429, 967, -1, 974, 972, 945, -1, 975, 977, 978, -1, 974, 967, 956, -1, 974, 956, 972, -1, 979, 978, 961, -1, 979, 961, 960, -1, 980, 960, 964, -1, 980, 964, 968, -1, 981, 968, 970, -1, 981, 970, 973, -1, 433, 315, 982, -1, 983, 982, 976, -1, 983, 433, 982, -1, 983, 976, 975, -1, 984, 108, 106, -1, 984, 973, 108, -1, 985, 978, 979, -1, 985, 975, 978, -1, 949, 105, 92, -1, 986, 960, 980, -1, 986, 979, 960, -1, 987, 968, 981, -1, 987, 980, 968, -1, 988, 981, 973, -1, 988, 973, 984, -1, 989, 975, 985, -1, 989, 432, 433, -1, 989, 433, 983, -1, 989, 983, 975, -1, 990, 106, 105, -1, 990, 105, 949, -1, 990, 984, 106, -1, 991, 985, 979, -1, 991, 979, 986, -1, 958, 986, 980, -1, 992, 993, 98, -1, 958, 980, 987, -1, 992, 98, 104, -1, 965, 987, 981, -1, 965, 981, 988, -1, 962, 994, 993, -1, 995, 949, 948, -1, 995, 988, 984, -1, 995, 984, 990, -1, 995, 990, 949, -1, 962, 993, 992, -1, 996, 431, 432, -1, 996, 985, 991, -1, 969, 104, 107, -1, 996, 432, 989, -1, 996, 989, 985, -1, 969, 992, 104, -1, 957, 986, 958, -1, 961, 997, 994, -1, 957, 991, 986, -1, 961, 994, 962, -1, 959, 958, 987, -1, 964, 992, 969, -1, 959, 987, 965, -1, 964, 962, 992, -1, 966, 948, 947, -1, 966, 995, 948, -1, 966, 965, 988, -1, 970, 107, 109, -1, 966, 988, 995, -1, 970, 969, 107, -1, 971, 431, 996, -1, 971, 430, 431, -1, 971, 996, 991, -1, 971, 991, 957, -1, 978, 977, 997, -1, 978, 997, 961, -1, 998, 951, 952, -1, 998, 999, 951, -1, 998, 1000, 999, -1, 998, 1001, 1000, -1, 1002, 85, 1003, -1, 1002, 1003, 1004, -1, 404, 1005, 313, -1, 1006, 1004, 1007, -1, 1006, 1007, 1008, -1, 1009, 952, 953, -1, 1009, 998, 952, -1, 1009, 1008, 1001, -1, 1009, 1001, 998, -1, 1010, 87, 85, -1, 1010, 89, 87, -1, 1010, 85, 1002, -1, 1010, 1002, 1004, -1, 1010, 1004, 1006, -1, 1011, 953, 954, -1, 1011, 1009, 953, -1, 1011, 1006, 1008, -1, 1011, 1008, 1009, -1, 1012, 954, 955, -1, 1012, 89, 1010, -1, 1012, 1011, 954, -1, 1012, 955, 89, -1, 1012, 1010, 1006, -1, 1012, 1006, 1011, -1, 85, 77, 1003, -1, 90, 89, 955, -1, 1013, 1014, 1005, -1, 1013, 1005, 404, -1, 1015, 1016, 1014, -1, 1015, 1014, 1013, -1, 1017, 404, 405, -1, 1017, 1013, 404, -1, 1018, 1019, 1016, -1, 1018, 1016, 1015, -1, 1000, 1013, 1017, -1, 1000, 1015, 1013, -1, 1020, 307, 950, -1, 1020, 406, 307, -1, 1020, 405, 406, -1, 1020, 1017, 405, -1, 1007, 1021, 1019, -1, 1007, 1019, 1018, -1, 1001, 1018, 1015, -1, 1001, 1015, 1000, -1, 999, 950, 951, -1, 999, 1020, 950, -1, 999, 1000, 1017, -1, 999, 1017, 1020, -1, 1004, 1003, 1021, -1, 1004, 1021, 1007, -1, 1008, 1007, 1018, -1, 1008, 1018, 1001, -1, 982, 315, 317, -1, 982, 317, 1022, -1, 976, 1022, 1023, -1, 976, 982, 1022, -1, 977, 1023, 1024, -1, 977, 976, 1023, -1, 997, 1024, 1025, -1, 997, 977, 1024, -1, 994, 1025, 1026, -1, 994, 997, 1025, -1, 993, 1026, 1027, -1, 993, 994, 1026, -1, 98, 1027, 103, -1, 98, 993, 1027, -1, 311, 313, 1005, -1, 1028, 1005, 1014, -1, 1028, 311, 1005, -1, 1029, 1014, 1016, -1, 1029, 1028, 1014, -1, 1030, 1016, 1019, -1, 1030, 1029, 1016, -1, 1031, 1019, 1021, -1, 1031, 1030, 1019, -1, 1032, 1021, 1003, -1, 1032, 1031, 1021, -1, 1033, 1003, 77, -1, 1033, 1032, 1003, -1, 83, 1033, 77, -1, 1034, 1035, 1036, -1, 1037, 1029, 1030, -1, 1037, 1038, 1039, -1, 1037, 1040, 1029, -1, 1037, 1039, 1040, -1, 1041, 103, 1027, -1, 407, 1022, 317, -1, 1041, 1027, 1026, -1, 1041, 88, 103, -1, 1041, 1026, 1042, -1, 1043, 1042, 1035, -1, 1043, 1035, 1034, -1, 1044, 1030, 1031, -1, 1044, 1038, 1037, -1, 1044, 1037, 1030, -1, 1044, 1034, 1038, -1, 1045, 86, 88, -1, 1045, 88, 1041, -1, 1045, 1041, 1042, -1, 1045, 1042, 1043, -1, 1046, 1031, 1032, -1, 1046, 1043, 1034, -1, 1046, 1044, 1031, -1, 1046, 1034, 1044, -1, 1047, 1032, 1033, -1, 1047, 84, 86, -1, 1047, 86, 1045, -1, 1047, 1033, 84, -1, 1047, 1046, 1032, -1, 1047, 1043, 1046, -1, 1047, 1045, 1043, -1, 83, 84, 1033, -1, 1048, 1022, 407, -1, 1049, 1023, 1022, -1, 1049, 1022, 1048, -1, 1050, 407, 408, -1, 1050, 1048, 407, -1, 1036, 1024, 1023, -1, 1036, 1023, 1049, -1, 1039, 1048, 1050, -1, 1039, 1049, 1048, -1, 1051, 409, 311, -1, 1051, 408, 409, -1, 1051, 311, 1028, -1, 1051, 1050, 408, -1, 1035, 1025, 1024, -1, 1035, 1024, 1036, -1, 1038, 1036, 1049, -1, 1038, 1049, 1039, -1, 1040, 1028, 1029, -1, 1040, 1051, 1028, -1, 1040, 1050, 1051, -1, 1040, 1039, 1050, -1, 1042, 1026, 1025, -1, 1042, 1025, 1035, -1, 1034, 1036, 1038, -1, 119, 120, 1052, -1, 119, 1052, 1053, -1, 117, 1053, 1054, -1, 117, 119, 1053, -1, 112, 1054, 1055, -1, 112, 117, 1054, -1, 113, 1055, 1056, -1, 113, 112, 1055, -1, 115, 1056, 1057, -1, 115, 113, 1056, -1, 118, 1057, 1058, -1, 118, 115, 1057, -1, 127, 1058, 1059, -1, 127, 118, 1058, -1, 120, 1060, 1052, -1, 147, 1060, 120, -1, 151, 1061, 1062, -1, 150, 1062, 1063, -1, 150, 151, 1062, -1, 149, 1063, 1064, -1, 149, 150, 1063, -1, 148, 1064, 1060, -1, 148, 149, 1064, -1, 147, 148, 1060, -1, 1061, 152, 1065, -1, 151, 152, 1061, -1, 162, 163, 1066, -1, 162, 1066, 1067, -1, 161, 1067, 1068, -1, 161, 162, 1067, -1, 160, 1068, 1069, -1, 160, 161, 1068, -1, 152, 1069, 1065, -1, 152, 160, 1069, -1, 1066, 165, 1070, -1, 163, 165, 1066, -1, 170, 1071, 1072, -1, 169, 1072, 1073, -1, 169, 170, 1072, -1, 168, 1073, 1074, -1, 168, 169, 1073, -1, 167, 1074, 1070, -1, 167, 168, 1074, -1, 165, 167, 1070, -1, 1071, 172, 1075, -1, 170, 172, 1071, -1, 175, 164, 1076, -1, 175, 1076, 1077, -1, 174, 1077, 1078, -1, 174, 175, 1077, -1, 173, 1078, 1079, -1, 173, 174, 1078, -1, 172, 1079, 1075, -1, 172, 173, 1079, -1, 1080, 164, 141, -1, 1076, 164, 1080, -1, 144, 137, 1081, -1, 144, 1081, 1082, -1, 143, 1082, 1083, -1, 143, 144, 1082, -1, 142, 1083, 1084, -1, 142, 143, 1083, -1, 141, 1084, 1080, -1, 141, 142, 1084, -1, 1081, 132, 1085, -1, 137, 132, 1081, -1, 129, 128, 1086, -1, 129, 1086, 1087, -1, 130, 1087, 1088, -1, 130, 129, 1087, -1, 131, 1088, 1089, -1, 131, 130, 1088, -1, 132, 1089, 1085, -1, 132, 131, 1089, -1, 1059, 128, 127, -1, 1086, 128, 1059, -1, 1090, 1091, 1092, -1, 1092, 1091, 1093, -1, 20, 1091, 1090, -1, 1094, 1095, 1096, -1, 20, 1095, 1091, -1, 1096, 1095, 20, -1, 1097, 1098, 1099, -1, 1100, 1101, 1097, -1, 1102, 1101, 1100, -1, 1103, 1101, 1102, -1, 1104, 1101, 1103, -1, 1097, 1101, 1098, -1, 1101, 22, 1098, -1, 22, 1105, 1098, -1, 1105, 1106, 1107, -1, 1105, 1108, 1106, -1, 1105, 1109, 1108, -1, 22, 24, 1105, -1, 1105, 24, 1109, -1, 24, 1110, 1109, -1, 1110, 1111, 1112, -1, 1111, 1113, 1114, -1, 24, 1113, 1110, -1, 1110, 1113, 1111, -1, 1101, 1115, 22, -1, 1116, 1117, 1115, -1, 1117, 1118, 1115, -1, 1118, 1119, 1115, -1, 1115, 17, 22, -1, 1119, 17, 1115, -1, 1119, 1120, 17, -1, 1121, 1122, 1120, -1, 1122, 1123, 1120, -1, 1120, 1124, 17, -1, 1123, 1124, 1120, -1, 20, 1090, 24, -1, 24, 1090, 1113, -1, 17, 1096, 20, -1, 1124, 1096, 17, -1, 1125, 1126, 1096, -1, 1090, 1092, 1127, -1, 1126, 1094, 1096, -1, 1128, 1129, 1130, -1, 1131, 1130, 1132, -1, 1131, 1128, 1130, -1, 1133, 1132, 1134, -1, 1133, 1131, 1132, -1, 1135, 1134, 1136, -1, 1135, 1133, 1134, -1, 1137, 1136, 1138, -1, 1137, 1135, 1136, -1, 1139, 1138, 1140, -1, 1139, 1137, 1138, -1, 1141, 1140, 1142, -1, 1141, 1139, 1140, -1, 1143, 1141, 1142, -1, 1144, 1145, 1146, -1, 1147, 1146, 1148, -1, 1147, 1144, 1146, -1, 1149, 1148, 1150, -1, 1149, 1147, 1148, -1, 1151, 1150, 1152, -1, 1151, 1149, 1150, -1, 1153, 1151, 1152, -1, 1154, 1155, 1156, -1, 1157, 1154, 1156, -1, 1158, 1156, 1159, -1, 1158, 1157, 1156, -1, 1160, 1159, 1161, -1, 1160, 1158, 1159, -1, 1162, 1161, 1163, -1, 1162, 1160, 1161, -1, 1164, 1165, 1166, -1, 1164, 1166, 1167, -1, 1168, 1167, 1169, -1, 1168, 1164, 1167, -1, 1170, 1169, 1171, -1, 1170, 1168, 1169, -1, 1172, 1171, 1173, -1, 1172, 1170, 1171, -1, 1174, 1175, 1176, -1, 1174, 1176, 1177, -1, 1178, 1177, 1179, -1, 1178, 1174, 1177, -1, 1180, 1179, 1181, -1, 1180, 1178, 1179, -1, 1182, 1181, 1183, -1, 1182, 1180, 1181, -1, 1165, 1176, 1175, -1, 1165, 1175, 1166, -1, 1162, 1172, 1173, -1, 1162, 1163, 1172, -1, 1184, 1185, 1186, -1, 1187, 1186, 1188, -1, 1187, 1184, 1186, -1, 1189, 1188, 1190, -1, 1189, 1187, 1188, -1, 1191, 1190, 1192, -1, 1191, 1189, 1190, -1, 1193, 1191, 1192, -1, 1185, 1155, 1154, -1, 1184, 1155, 1185, -1, 1194, 1195, 1196, -1, 1197, 1196, 1198, -1, 1197, 1194, 1196, -1, 1199, 1198, 1200, -1, 1199, 1197, 1198, -1, 1201, 1200, 1202, -1, 1201, 1199, 1200, -1, 1203, 1201, 1202, -1, 1202, 1192, 1203, -1, 1193, 1192, 1202, -1, 1195, 1194, 1145, -1, 1144, 1195, 1145, -1, 1153, 1152, 1143, -1, 1153, 1143, 1142, -1, 1182, 1129, 1128, -1, 1183, 1129, 1182, -1, 55, 1204, 1205, -1, 53, 1205, 1206, -1, 53, 55, 1205, -1, 51, 1206, 1207, -1, 51, 53, 1206, -1, 49, 1207, 1208, -1, 49, 51, 1207, -1, 46, 49, 1208, -1, 55, 1209, 1204, -1, 59, 1209, 55, -1, 62, 63, 1210, -1, 62, 1210, 1211, -1, 61, 1211, 1212, -1, 61, 62, 1211, -1, 60, 1212, 1213, -1, 60, 61, 1212, -1, 59, 1213, 1209, -1, 59, 60, 1213, -1, 1210, 68, 1214, -1, 63, 68, 1210, -1, 75, 1215, 1216, -1, 74, 1216, 1217, -1, 74, 75, 1216, -1, 73, 1217, 1218, -1, 73, 74, 1217, -1, 72, 1218, 1214, -1, 72, 73, 1218, -1, 68, 72, 1214, -1, 75, 91, 1215, -1, 91, 1219, 1215, -1, 96, 1220, 1221, -1, 95, 1221, 1222, -1, 95, 96, 1221, -1, 94, 1222, 1223, -1, 94, 95, 1222, -1, 93, 1223, 1219, -1, 93, 94, 1223, -1, 91, 93, 1219, -1, 1220, 97, 1224, -1, 96, 97, 1220, -1, 101, 102, 1225, -1, 101, 1225, 1226, -1, 100, 1226, 1227, -1, 100, 101, 1226, -1, 99, 1227, 1228, -1, 99, 100, 1227, -1, 97, 1228, 1224, -1, 97, 99, 1228, -1, 1229, 102, 76, -1, 1225, 102, 1229, -1, 57, 56, 1230, -1, 57, 1230, 1231, -1, 82, 1231, 1232, -1, 82, 57, 1231, -1, 81, 1232, 1233, -1, 81, 82, 1232, -1, 80, 1233, 1234, -1, 80, 81, 1233, -1, 79, 1234, 1235, -1, 79, 80, 1234, -1, 78, 1235, 1236, -1, 78, 79, 1235, -1, 76, 1236, 1229, -1, 76, 78, 1236, -1, 1237, 56, 54, -1, 1230, 56, 1237, -1, 47, 1238, 1239, -1, 48, 1239, 1240, -1, 48, 47, 1239, -1, 50, 1240, 1241, -1, 50, 48, 1240, -1, 52, 1241, 1237, -1, 52, 50, 1241, -1, 54, 52, 1237, -1, 1238, 46, 1208, -1, 47, 46, 1238, -1, 1242, 1243, 1244, -1, 1245, 1246, 1247, -1, 1248, 1246, 1245, -1, 1249, 1250, 1251, -1, 1242, 1252, 1243, -1, 1242, 1253, 1252, -1, 32, 1253, 1242, -1, 1246, 1254, 1247, -1, 32, 1254, 1253, -1, 1247, 1254, 32, -1, 1249, 1255, 1250, -1, 1249, 1256, 1255, -1, 1257, 1258, 1259, -1, 1260, 1258, 1257, -1, 1261, 1258, 1260, -1, 1259, 27, 1249, -1, 1258, 27, 1259, -1, 1249, 27, 1256, -1, 1256, 30, 1262, -1, 27, 30, 1256, -1, 1263, 1264, 1265, -1, 1266, 1264, 1263, -1, 1267, 1264, 1266, -1, 1268, 1264, 1267, -1, 1269, 1264, 1268, -1, 1262, 1264, 1269, -1, 30, 1264, 1262, -1, 1258, 1270, 27, -1, 1271, 1272, 1270, -1, 1272, 1273, 1270, -1, 1273, 1274, 1270, -1, 1270, 25, 27, -1, 1274, 25, 1270, -1, 1274, 1275, 25, -1, 1276, 1277, 1275, -1, 1277, 1278, 1275, -1, 1275, 1279, 25, -1, 1278, 1279, 1275, -1, 32, 1242, 30, -1, 30, 1242, 1264, -1, 25, 1247, 32, -1, 1279, 1247, 25, -1, 1280, 1281, 1282, -1, 1280, 1282, 1283, -1, 1284, 1283, 1285, -1, 1284, 1280, 1283, -1, 1286, 1285, 1287, -1, 1286, 1284, 1285, -1, 1288, 1287, 1289, -1, 1288, 1286, 1287, -1, 1290, 1291, 1292, -1, 1290, 1292, 1293, -1, 1290, 1293, 1294, -1, 1295, 1294, 1296, -1, 1295, 1290, 1294, -1, 1297, 1296, 1298, -1, 1297, 1295, 1296, -1, 1299, 1297, 1298, -1, 1300, 1301, 1302, -1, 1303, 1302, 1304, -1, 1303, 1300, 1302, -1, 1305, 1304, 1306, -1, 1305, 1303, 1304, -1, 1307, 1306, 1308, -1, 1307, 1305, 1306, -1, 1309, 1307, 1308, -1, 1310, 1311, 1312, -1, 1310, 1312, 1313, -1, 1314, 1313, 1315, -1, 1314, 1310, 1313, -1, 1316, 1315, 1317, -1, 1316, 1314, 1315, -1, 1318, 1317, 1319, -1, 1318, 1316, 1317, -1, 1320, 1321, 1322, -1, 1320, 1322, 1323, -1, 1324, 1323, 1325, -1, 1324, 1320, 1323, -1, 1326, 1325, 1327, -1, 1326, 1324, 1325, -1, 1328, 1327, 1329, -1, 1328, 1326, 1327, -1, 1312, 1311, 1322, -1, 1312, 1322, 1321, -1, 1330, 1331, 1332, -1, 1333, 1332, 1334, -1, 1333, 1330, 1332, -1, 1335, 1334, 1336, -1, 1335, 1333, 1334, -1, 1337, 1336, 1338, -1, 1337, 1335, 1336, -1, 1339, 1337, 1338, -1, 1338, 1328, 1329, -1, 1338, 1329, 1339, -1, 1300, 1331, 1301, -1, 1331, 1330, 1301, -1, 1299, 1298, 1308, -1, 1298, 1309, 1308, -1, 1340, 1341, 1342, -1, 1340, 1342, 1343, -1, 1344, 1343, 1345, -1, 1344, 1340, 1343, -1, 1346, 1345, 1347, -1, 1346, 1344, 1345, -1, 1348, 1347, 1349, -1, 1348, 1346, 1347, -1, 1350, 1349, 1351, -1, 1350, 1348, 1349, -1, 1352, 1351, 1353, -1, 1352, 1350, 1351, -1, 1354, 1353, 1355, -1, 1354, 1352, 1353, -1, 1355, 1292, 1291, -1, 1355, 1291, 1354, -1, 1282, 1342, 1341, -1, 1281, 1342, 1282, -1, 1318, 1288, 1289, -1, 1319, 1288, 1318, -1, 1215, 1312, 1321, -1, 1215, 1219, 1312, -1, 1313, 1312, 1219, -1, 1313, 1219, 1223, -1, 1315, 1223, 1222, -1, 1315, 1313, 1223, -1, 1317, 1221, 1220, -1, 1317, 1222, 1221, -1, 1317, 1315, 1222, -1, 1319, 1317, 1220, -1, 1328, 1214, 1218, -1, 1326, 1328, 1218, -1, 1324, 1218, 1217, -1, 1324, 1326, 1218, -1, 1320, 1217, 1216, -1, 1320, 1324, 1217, -1, 1321, 1216, 1215, -1, 1321, 1320, 1216, -1, 1319, 1220, 1288, -1, 1220, 1224, 1288, -1, 1338, 1214, 1328, -1, 1210, 1214, 1338, -1, 1288, 1224, 1228, -1, 1286, 1228, 1227, -1, 1286, 1288, 1228, -1, 1284, 1286, 1227, -1, 1280, 1227, 1226, -1, 1280, 1284, 1227, -1, 1281, 1226, 1225, -1, 1281, 1280, 1226, -1, 1331, 1209, 1213, -1, 1332, 1213, 1212, -1, 1332, 1331, 1213, -1, 1334, 1212, 1211, -1, 1334, 1332, 1212, -1, 1336, 1211, 1210, -1, 1336, 1334, 1211, -1, 1338, 1336, 1210, -1, 1225, 1229, 1281, -1, 1281, 1229, 1342, -1, 1300, 1209, 1331, -1, 1204, 1209, 1300, -1, 1343, 1342, 1229, -1, 1343, 1229, 1236, -1, 1345, 1236, 1235, -1, 1345, 1343, 1236, -1, 1347, 1235, 1234, -1, 1347, 1345, 1235, -1, 1349, 1234, 1233, -1, 1349, 1347, 1234, -1, 1351, 1233, 1232, -1, 1351, 1349, 1233, -1, 1353, 1232, 1231, -1, 1353, 1351, 1232, -1, 1355, 1231, 1230, -1, 1355, 1353, 1231, -1, 1307, 1309, 1208, -1, 1307, 1207, 1206, -1, 1307, 1208, 1207, -1, 1305, 1206, 1205, -1, 1305, 1307, 1206, -1, 1303, 1205, 1204, -1, 1303, 1305, 1205, -1, 1300, 1303, 1204, -1, 1230, 1237, 1355, -1, 1355, 1237, 1292, -1, 1298, 1208, 1309, -1, 1238, 1208, 1298, -1, 1293, 1292, 1237, -1, 1293, 1241, 1240, -1, 1293, 1237, 1241, -1, 1294, 1240, 1239, -1, 1294, 1293, 1240, -1, 1296, 1239, 1238, -1, 1296, 1294, 1239, -1, 1298, 1296, 1238, -1, 1202, 1070, 1193, -1, 1066, 1070, 1202, -1, 1191, 1193, 1070, -1, 1191, 1070, 1074, -1, 1189, 1074, 1073, -1, 1189, 1191, 1074, -1, 1187, 1072, 1071, -1, 1187, 1073, 1072, -1, 1187, 1189, 1073, -1, 1184, 1187, 1071, -1, 1196, 1195, 1065, -1, 1196, 1065, 1069, -1, 1198, 1069, 1068, -1, 1198, 1196, 1069, -1, 1200, 1067, 1066, -1, 1200, 1068, 1067, -1, 1200, 1198, 1068, -1, 1202, 1200, 1066, -1, 1071, 1075, 1155, -1, 1071, 1155, 1184, -1, 1061, 1065, 1195, -1, 1061, 1195, 1144, -1, 1155, 1075, 1079, -1, 1156, 1155, 1079, -1, 1159, 1079, 1078, -1, 1159, 1156, 1079, -1, 1161, 1078, 1077, -1, 1161, 1159, 1078, -1, 1163, 1077, 1076, -1, 1163, 1161, 1077, -1, 1151, 1153, 1060, -1, 1151, 1060, 1064, -1, 1149, 1063, 1062, -1, 1149, 1064, 1063, -1, 1149, 1151, 1064, -1, 1147, 1062, 1061, -1, 1147, 1149, 1062, -1, 1144, 1147, 1061, -1, 1076, 1080, 1172, -1, 1076, 1172, 1163, -1, 1052, 1060, 1153, -1, 1052, 1153, 1142, -1, 1172, 1080, 1084, -1, 1170, 1084, 1083, -1, 1170, 1172, 1084, -1, 1168, 1083, 1082, -1, 1168, 1170, 1083, -1, 1164, 1082, 1081, -1, 1164, 1168, 1082, -1, 1165, 1164, 1081, -1, 1130, 1129, 1059, -1, 1130, 1058, 1057, -1, 1130, 1059, 1058, -1, 1132, 1057, 1056, -1, 1132, 1130, 1057, -1, 1134, 1056, 1055, -1, 1134, 1132, 1056, -1, 1136, 1055, 1054, -1, 1136, 1134, 1055, -1, 1138, 1054, 1053, -1, 1138, 1136, 1054, -1, 1140, 1053, 1052, -1, 1140, 1138, 1053, -1, 1142, 1140, 1052, -1, 1081, 1085, 1176, -1, 1081, 1176, 1165, -1, 1086, 1059, 1129, -1, 1086, 1129, 1183, -1, 1177, 1176, 1085, -1, 1177, 1089, 1088, -1, 1177, 1085, 1089, -1, 1179, 1088, 1087, -1, 1179, 1177, 1088, -1, 1181, 1087, 1086, -1, 1181, 1179, 1087, -1, 1183, 1181, 1086, -1, 1249, 1299, 1259, -1, 1299, 1308, 1259, -1, 1301, 1258, 1261, -1, 1302, 1261, 1260, -1, 1302, 1301, 1261, -1, 1304, 1260, 1257, -1, 1304, 1302, 1260, -1, 1306, 1304, 1257, -1, 1308, 1257, 1259, -1, 1308, 1306, 1257, -1, 1299, 1249, 1251, -1, 1297, 1299, 1251, -1, 1295, 1250, 1255, -1, 1295, 1251, 1250, -1, 1295, 1297, 1251, -1, 1290, 1255, 1256, -1, 1290, 1295, 1255, -1, 1291, 1290, 1256, -1, 1301, 1330, 1258, -1, 1258, 1330, 1270, -1, 1291, 1262, 1354, -1, 1256, 1262, 1291, -1, 1337, 1339, 1274, -1, 1337, 1274, 1273, -1, 1335, 1273, 1272, -1, 1335, 1337, 1273, -1, 1333, 1272, 1271, -1, 1333, 1335, 1272, -1, 1330, 1271, 1270, -1, 1330, 1333, 1271, -1, 1354, 1262, 1269, -1, 1352, 1354, 1269, -1, 1350, 1269, 1268, -1, 1350, 1352, 1269, -1, 1348, 1268, 1267, -1, 1348, 1350, 1268, -1, 1346, 1267, 1266, -1, 1346, 1348, 1267, -1, 1344, 1266, 1263, -1, 1344, 1346, 1266, -1, 1340, 1263, 1265, -1, 1340, 1344, 1263, -1, 1341, 1265, 1264, -1, 1341, 1340, 1265, -1, 1274, 1339, 1329, -1, 1275, 1274, 1329, -1, 1282, 1264, 1242, -1, 1282, 1341, 1264, -1, 1322, 1279, 1278, -1, 1323, 1278, 1277, -1, 1323, 1322, 1278, -1, 1325, 1277, 1276, -1, 1325, 1323, 1277, -1, 1327, 1325, 1276, -1, 1329, 1276, 1275, -1, 1329, 1327, 1276, -1, 1282, 1242, 1244, -1, 1283, 1244, 1243, -1, 1283, 1282, 1244, -1, 1285, 1243, 1252, -1, 1285, 1283, 1243, -1, 1287, 1252, 1253, -1, 1287, 1285, 1252, -1, 1289, 1287, 1253, -1, 1311, 1279, 1322, -1, 1247, 1279, 1311, -1, 1254, 1318, 1253, -1, 1318, 1289, 1253, -1, 1318, 1254, 1246, -1, 1316, 1246, 1248, -1, 1316, 1318, 1246, -1, 1314, 1248, 1245, -1, 1314, 1316, 1248, -1, 1310, 1314, 1245, -1, 1311, 1245, 1247, -1, 1311, 1310, 1245, -1, 1185, 1154, 1095, -1, 1095, 1154, 1091, -1, 1162, 1090, 1127, -1, 1160, 1162, 1127, -1, 1158, 1127, 1092, -1, 1158, 1160, 1127, -1, 1157, 1092, 1093, -1, 1157, 1158, 1092, -1, 1154, 1093, 1091, -1, 1154, 1157, 1093, -1, 1186, 1185, 1095, -1, 1186, 1095, 1094, -1, 1188, 1094, 1126, -1, 1188, 1186, 1094, -1, 1190, 1126, 1125, -1, 1190, 1188, 1126, -1, 1192, 1125, 1096, -1, 1192, 1190, 1125, -1, 1113, 1090, 1162, -1, 1113, 1162, 1173, -1, 1203, 1096, 1124, -1, 1203, 1192, 1096, -1, 1166, 1110, 1112, -1, 1167, 1112, 1111, -1, 1167, 1166, 1112, -1, 1169, 1111, 1114, -1, 1169, 1167, 1111, -1, 1171, 1169, 1114, -1, 1173, 1114, 1113, -1, 1173, 1171, 1114, -1, 1201, 1203, 1124, -1, 1201, 1124, 1123, -1, 1199, 1123, 1122, -1, 1199, 1201, 1123, -1, 1197, 1122, 1121, -1, 1197, 1199, 1122, -1, 1194, 1121, 1120, -1, 1194, 1197, 1121, -1, 1109, 1110, 1166, -1, 1109, 1166, 1175, -1, 1120, 1119, 1145, -1, 1120, 1145, 1194, -1, 1180, 1182, 1105, -1, 1180, 1107, 1106, -1, 1180, 1105, 1107, -1, 1178, 1106, 1108, -1, 1178, 1180, 1106, -1, 1174, 1108, 1109, -1, 1174, 1178, 1108, -1, 1175, 1174, 1109, -1, 1145, 1119, 1118, -1, 1146, 1118, 1117, -1, 1146, 1145, 1118, -1, 1148, 1117, 1116, -1, 1148, 1146, 1117, -1, 1150, 1116, 1115, -1, 1150, 1148, 1116, -1, 1152, 1150, 1115, -1, 1182, 1128, 1105, -1, 1105, 1128, 1098, -1, 1115, 1101, 1143, -1, 1115, 1143, 1152, -1, 1143, 1101, 1104, -1, 1141, 1143, 1104, -1, 1139, 1104, 1103, -1, 1139, 1141, 1104, -1, 1137, 1103, 1102, -1, 1137, 1139, 1103, -1, 1135, 1102, 1100, -1, 1135, 1137, 1102, -1, 1133, 1100, 1097, -1, 1133, 1135, 1100, -1, 1131, 1099, 1098, -1, 1131, 1097, 1099, -1, 1131, 1133, 1097, -1, 1128, 1131, 1098, -1, 362, 1356, 363, -1, 362, 1357, 1356, -1, 362, 1358, 1357, -1, 365, 1358, 362, -1, 1359, 365, 364, -1, 1358, 365, 1359, -1, 1356, 364, 363, -1, 1359, 364, 1356, -1, 1356, 29, 26, -1, 1356, 1357, 29, -1, 28, 1359, 26, -1, 26, 1359, 1356, -1, 1358, 31, 1357, -1, 1359, 31, 1358, -1, 1357, 31, 29, -1, 28, 31, 1359, -1, 35, 1360, 1361, -1, 37, 1360, 35, -1, 1362, 37, 36, -1, 1360, 37, 1362, -1, 1363, 36, 33, -1, 1362, 36, 1363, -1, 35, 1363, 33, -1, 35, 1361, 1363, -1, 21, 1361, 23, -1, 1363, 1361, 21, -1, 21, 1362, 1363, -1, 21, 19, 1362, -1, 1361, 1360, 23, -1, 1362, 18, 1360, -1, 1360, 18, 23, -1, 19, 18, 1362, -1, 207, 209, 374, -1, 207, 374, 389, -1, 375, 201, 391, -1, 198, 201, 375, -1, 188, 1364, 9, -1, 188, 232, 1364, -1, 1365, 16, 1366, -1, 1367, 16, 1365, -1, 1368, 16, 1367, -1, 1369, 16, 1368, -1, 1370, 16, 1369, -1, 351, 16, 1370, -1, 1364, 10, 9, -1, 1366, 10, 1364, -1, 14, 10, 16, -1, 16, 10, 1366, -1, 233, 194, 1371, -1, 233, 4, 194, -1, 360, 359, 1372, -1, 360, 1372, 1373, -1, 360, 1373, 1374, -1, 360, 1374, 1375, -1, 360, 1375, 1376, -1, 360, 1376, 1377, -1, 193, 222, 360, -1, 193, 1377, 1371, -1, 193, 1371, 194, -1, 193, 360, 1377, -1, 513, 375, 374, -1, 510, 375, 513, -1, 0, 382, 354, -1, 2, 382, 0, -1, 189, 358, 368, -1, 189, 368, 191, -1, 1378, 522, 1379, -1, 1378, 1379, 524, -1, 1378, 1380, 522, -1, 1381, 1382, 1380, -1, 1381, 1380, 1378, -1, 518, 1383, 245, -1, 1384, 1382, 1381, -1, 1384, 1385, 1382, -1, 1386, 386, 387, -1, 1386, 1387, 1385, -1, 1386, 387, 1387, -1, 1386, 1385, 1384, -1, 1388, 524, 526, -1, 1389, 524, 1388, -1, 1389, 1378, 524, -1, 1390, 1381, 1378, -1, 1390, 1378, 1389, -1, 1391, 1381, 1390, -1, 1391, 1384, 1381, -1, 1392, 1391, 380, -1, 1392, 1384, 1391, -1, 1392, 383, 386, -1, 1392, 380, 383, -1, 1392, 386, 1386, -1, 1392, 1386, 1384, -1, 1393, 526, 528, -1, 1393, 1388, 526, -1, 1394, 1388, 1393, -1, 1395, 1388, 1394, -1, 1395, 1389, 1388, -1, 1396, 1389, 1395, -1, 1396, 1390, 1389, -1, 1396, 1395, 379, -1, 1397, 380, 1391, -1, 1397, 1390, 1396, -1, 1397, 1396, 379, -1, 1397, 1391, 1390, -1, 1398, 379, 380, -1, 1398, 1397, 379, -1, 1398, 380, 1397, -1, 1399, 528, 1400, -1, 1399, 1400, 1401, -1, 1399, 1393, 528, -1, 1402, 1401, 1403, -1, 1402, 1394, 1393, -1, 1402, 1399, 1401, -1, 1402, 1393, 1399, -1, 1404, 1403, 1405, -1, 1404, 1394, 1402, -1, 1404, 1395, 1394, -1, 1404, 379, 1395, -1, 1404, 1402, 1403, -1, 1406, 1405, 1407, -1, 1406, 1404, 1405, -1, 1406, 379, 1404, -1, 1408, 1407, 1409, -1, 1408, 1406, 1407, -1, 1408, 379, 1406, -1, 1410, 376, 379, -1, 1410, 379, 1408, -1, 1411, 518, 520, -1, 1412, 1409, 1413, -1, 1412, 1408, 1409, -1, 1414, 1413, 1415, -1, 1416, 1417, 1383, -1, 1414, 1415, 377, -1, 1414, 377, 376, -1, 1416, 1383, 518, -1, 1414, 376, 1410, -1, 1414, 1410, 1408, -1, 1416, 1411, 520, -1, 1414, 1412, 1413, -1, 1414, 1408, 1412, -1, 1416, 518, 1411, -1, 1418, 1419, 1417, -1, 1418, 1417, 1416, -1, 1420, 1419, 1418, -1, 1421, 388, 373, -1, 1421, 387, 388, -1, 1421, 373, 1419, -1, 1421, 1419, 1420, -1, 1422, 520, 522, -1, 1380, 520, 1422, -1, 1380, 1416, 520, -1, 1380, 1422, 522, -1, 1382, 1418, 1416, -1, 1382, 1416, 1380, -1, 1385, 1420, 1418, -1, 1385, 1418, 1382, -1, 1387, 387, 1421, -1, 1387, 1421, 1420, -1, 1387, 1420, 1385, -1, 1379, 522, 524, -1, 1419, 373, 367, -1, 1419, 367, 1423, -1, 1417, 1424, 1425, -1, 1417, 1423, 1424, -1, 1417, 1419, 1423, -1, 1383, 1417, 1425, -1, 245, 1425, 264, -1, 245, 1383, 1425, -1, 1426, 1427, 1428, -1, 1426, 1428, 1429, -1, 1430, 396, 366, -1, 1430, 366, 1431, -1, 1430, 1431, 1427, -1, 1430, 1427, 1426, -1, 1432, 568, 566, -1, 1433, 568, 1432, -1, 1433, 566, 397, -1, 1433, 1429, 568, -1, 1433, 1432, 566, -1, 1434, 397, 396, -1, 1434, 396, 1430, -1, 1434, 1426, 1429, -1, 1434, 1430, 1426, -1, 1434, 1433, 397, -1, 1434, 1429, 1433, -1, 573, 1435, 575, -1, 1425, 566, 264, -1, 1424, 566, 1425, -1, 1424, 397, 566, -1, 1423, 397, 1424, -1, 367, 397, 1423, -1, 1436, 1437, 1435, -1, 1438, 1439, 1437, -1, 1438, 1437, 1436, -1, 1440, 395, 1441, -1, 1440, 1441, 1442, -1, 1443, 1442, 1444, -1, 1443, 1444, 1439, -1, 1443, 1439, 1438, -1, 1445, 372, 395, -1, 1445, 1440, 1442, -1, 1445, 395, 1440, -1, 1445, 1442, 1443, -1, 1446, 573, 571, -1, 1446, 1435, 573, -1, 1446, 1436, 1435, -1, 1447, 1436, 1446, -1, 1447, 1438, 1436, -1, 1447, 1446, 571, -1, 1448, 1443, 1438, -1, 1448, 1438, 1447, -1, 1448, 1447, 571, -1, 1449, 369, 372, -1, 1449, 372, 1445, -1, 1449, 1443, 1448, -1, 1449, 1445, 1443, -1, 1450, 571, 570, -1, 1428, 1448, 571, -1, 1428, 1450, 570, -1, 1428, 571, 1450, -1, 1427, 1448, 1428, -1, 1427, 1449, 1448, -1, 1431, 366, 369, -1, 1431, 369, 1449, -1, 1431, 1449, 1427, -1, 1451, 570, 568, -1, 1429, 570, 1451, -1, 1429, 1428, 570, -1, 1429, 1451, 568, -1, 576, 297, 578, -1, 1452, 590, 285, -1, 1453, 565, 1454, -1, 1455, 565, 1453, -1, 270, 565, 1455, -1, 1456, 578, 580, -1, 1457, 576, 578, -1, 1457, 578, 1456, -1, 1457, 1456, 580, -1, 1458, 580, 582, -1, 1459, 580, 1458, -1, 1460, 574, 576, -1, 1460, 1457, 580, -1, 1460, 576, 1457, -1, 1460, 580, 1459, -1, 1460, 1459, 574, -1, 1461, 584, 586, -1, 1461, 582, 584, -1, 1461, 1458, 582, -1, 1462, 1458, 1461, -1, 1462, 1459, 1458, -1, 1462, 574, 1459, -1, 1463, 572, 574, -1, 1463, 1462, 572, -1, 1463, 574, 1462, -1, 1464, 1461, 586, -1, 1465, 1462, 1461, -1, 1465, 572, 1462, -1, 1465, 1461, 1464, -1, 1466, 569, 572, -1, 1466, 572, 1465, -1, 1466, 1465, 569, -1, 1467, 588, 590, -1, 1467, 586, 588, -1, 1467, 1464, 586, -1, 1468, 569, 1465, -1, 1468, 1465, 1464, -1, 1468, 1464, 1467, -1, 1469, 567, 569, -1, 1469, 1468, 567, -1, 1469, 569, 1468, -1, 1470, 1452, 1471, -1, 1470, 1467, 590, -1, 1470, 590, 1452, -1, 1472, 1471, 1454, -1, 1472, 567, 1468, -1, 1472, 1470, 1471, -1, 1472, 1454, 565, -1, 1472, 1468, 1467, -1, 1472, 1467, 1470, -1, 1473, 565, 567, -1, 1473, 1472, 565, -1, 1473, 567, 1472, -1, 1452, 285, 287, -1, 1452, 287, 1474, -1, 1471, 1474, 1475, -1, 1471, 1452, 1474, -1, 1454, 1475, 1476, -1, 1454, 1471, 1475, -1, 1453, 1476, 1477, -1, 1453, 1454, 1476, -1, 1455, 1477, 1478, -1, 1455, 1453, 1477, -1, 270, 1478, 262, -1, 270, 1455, 1478, -1, 1479, 1480, 1481, -1, 1479, 1482, 1480, -1, 1483, 1484, 1485, -1, 470, 1474, 287, -1, 1483, 1481, 1486, -1, 1483, 1487, 1484, -1, 1483, 1486, 1487, -1, 1488, 1489, 1482, -1, 1475, 1474, 470, -1, 1488, 1482, 1479, -1, 1490, 1485, 1491, -1, 1490, 1479, 1481, -1, 1490, 1483, 1485, -1, 1490, 1481, 1483, -1, 1492, 257, 260, -1, 1492, 1489, 1488, -1, 1492, 260, 1493, -1, 1492, 1493, 1489, -1, 1494, 1491, 1495, -1, 1494, 1479, 1490, -1, 1494, 1490, 1491, -1, 1494, 1488, 1479, -1, 1496, 1495, 259, -1, 261, 262, 1478, -1, 1496, 258, 257, -1, 1496, 259, 258, -1, 1496, 257, 1492, -1, 1496, 1494, 1495, -1, 1496, 1492, 1488, -1, 1496, 1488, 1494, -1, 1497, 470, 472, -1, 1498, 1475, 470, -1, 1498, 470, 1497, -1, 1499, 1476, 1475, -1, 1499, 1475, 1498, -1, 1500, 1477, 1476, -1, 1500, 1476, 1499, -1, 1501, 472, 474, -1, 1501, 1497, 472, -1, 1502, 1478, 1477, -1, 1502, 260, 261, -1, 1502, 261, 1478, -1, 1502, 1477, 1500, -1, 1480, 1497, 1501, -1, 1480, 1498, 1497, -1, 1482, 1499, 1498, -1, 1482, 1498, 1480, -1, 1489, 1499, 1482, -1, 1489, 1500, 1499, -1, 1486, 474, 476, -1, 1486, 1501, 474, -1, 1493, 1500, 1489, -1, 1493, 260, 1502, -1, 1493, 1502, 1500, -1, 1481, 1480, 1501, -1, 1481, 1501, 1486, -1, 1487, 476, 348, -1, 1487, 348, 1484, -1, 1487, 1486, 476, -1, 263, 259, 1495, -1, 1503, 1495, 1491, -1, 1503, 263, 1495, -1, 1504, 1491, 1485, -1, 1504, 1503, 1491, -1, 1505, 1485, 1484, -1, 1505, 1504, 1485, -1, 1506, 1484, 348, -1, 1506, 1505, 1484, -1, 350, 1506, 348, -1, 268, 1507, 269, -1, 1505, 495, 1504, -1, 1506, 495, 1505, -1, 350, 495, 1506, -1, 1508, 268, 267, -1, 1508, 1507, 268, -1, 1509, 1510, 1507, -1, 1509, 1508, 267, -1, 1509, 1507, 1508, -1, 1511, 1512, 1510, -1, 1511, 1510, 1509, -1, 1513, 499, 274, -1, 1513, 498, 499, -1, 1513, 274, 1512, -1, 1513, 1512, 1511, -1, 1514, 267, 266, -1, 1515, 1509, 267, -1, 1515, 267, 1514, -1, 1516, 1511, 1509, -1, 1516, 1509, 1515, -1, 1517, 497, 498, -1, 1517, 498, 1513, -1, 1517, 1513, 1511, -1, 1517, 1511, 1516, -1, 1518, 266, 265, -1, 1518, 1514, 266, -1, 1519, 1515, 1514, -1, 1519, 1514, 1518, -1, 1520, 1515, 1519, -1, 1520, 1516, 1515, -1, 1521, 496, 497, -1, 1521, 497, 1517, -1, 1521, 1517, 1516, -1, 1521, 1516, 1520, -1, 1522, 263, 1503, -1, 1522, 265, 263, -1, 1522, 1518, 265, -1, 1523, 1503, 1504, -1, 1523, 1519, 1518, -1, 1523, 1504, 495, -1, 1523, 1522, 1503, -1, 1523, 1518, 1522, -1, 1524, 1523, 495, -1, 1524, 1519, 1523, -1, 1524, 1520, 1519, -1, 1525, 495, 496, -1, 1525, 496, 1521, -1, 1525, 1521, 1520, -1, 1525, 1524, 495, -1, 1525, 1520, 1524, -1, 274, 273, 1526, -1, 1512, 1526, 1527, -1, 1512, 274, 1526, -1, 1510, 1512, 1527, -1, 1507, 1527, 1528, -1, 1507, 1510, 1527, -1, 269, 1528, 251, -1, 269, 1507, 1528, -1, 1529, 441, 438, -1, 1529, 273, 441, -1, 1529, 1530, 1526, -1, 1529, 438, 1531, -1, 1529, 1531, 1532, -1, 1529, 1532, 1530, -1, 244, 1533, 246, -1, 244, 1534, 1533, -1, 244, 1535, 1534, -1, 434, 347, 1536, -1, 1537, 244, 243, -1, 1538, 1537, 243, -1, 1538, 244, 1537, -1, 1539, 1535, 244, -1, 1539, 244, 1538, -1, 1540, 436, 434, -1, 1540, 1536, 1535, -1, 1540, 1535, 1539, -1, 1540, 434, 1536, -1, 1541, 243, 247, -1, 1542, 1538, 243, -1, 1542, 243, 1541, -1, 1543, 1539, 1538, -1, 1543, 1538, 1542, -1, 1544, 436, 1540, -1, 1544, 1540, 1539, -1, 1544, 1539, 1543, -1, 1545, 247, 248, -1, 1545, 1541, 247, -1, 1546, 1542, 1541, -1, 1546, 1541, 1545, -1, 1532, 1542, 1546, -1, 1532, 1543, 1542, -1, 1547, 251, 1528, -1, 1547, 248, 251, -1, 1547, 1545, 248, -1, 1531, 438, 436, -1, 1531, 436, 1544, -1, 1531, 1544, 1543, -1, 1531, 1543, 1532, -1, 1548, 1528, 1527, -1, 1548, 1547, 1528, -1, 1548, 1546, 1545, -1, 1548, 1545, 1547, -1, 1530, 1527, 1526, -1, 1530, 1548, 1527, -1, 1530, 1532, 1546, -1, 1530, 1546, 1548, -1, 1529, 1526, 273, -1, 1536, 347, 346, -1, 1536, 346, 1549, -1, 1535, 1549, 1550, -1, 1535, 1536, 1549, -1, 1534, 1550, 1551, -1, 1534, 1535, 1550, -1, 1533, 1551, 1552, -1, 1533, 1534, 1551, -1, 246, 1552, 252, -1, 246, 1533, 1552, -1, 1553, 1554, 1555, -1, 1553, 1555, 1556, -1, 1557, 1558, 1559, -1, 450, 1549, 346, -1, 1557, 1556, 1560, -1, 1557, 1561, 1558, -1, 1557, 1560, 1561, -1, 1562, 1563, 1554, -1, 1562, 1554, 1553, -1, 1564, 1559, 1565, -1, 1564, 1557, 1559, -1, 1564, 1553, 1556, -1, 1564, 1556, 1557, -1, 1566, 254, 253, -1, 1566, 253, 1567, -1, 1566, 1563, 1562, -1, 1566, 1567, 1563, -1, 1568, 1565, 1569, -1, 1568, 1564, 1565, -1, 1568, 1562, 1553, -1, 1568, 1553, 1564, -1, 1570, 1569, 1571, -1, 1570, 255, 254, -1, 1570, 1571, 255, -1, 1570, 1562, 1568, -1, 1570, 254, 1566, -1, 1570, 1566, 1562, -1, 1570, 1568, 1569, -1, 249, 255, 1571, -1, 1572, 450, 448, -1, 1573, 1550, 1549, -1, 1573, 1549, 450, -1, 1573, 450, 1572, -1, 1574, 1551, 1550, -1, 1574, 1550, 1573, -1, 1575, 1552, 1551, -1, 1575, 1551, 1574, -1, 1576, 448, 447, -1, 1576, 1572, 448, -1, 1577, 252, 1552, -1, 1577, 256, 252, -1, 1577, 253, 256, -1, 1577, 1552, 1575, -1, 1555, 1572, 1576, -1, 1555, 1573, 1572, -1, 1554, 1574, 1573, -1, 1554, 1573, 1555, -1, 1563, 1574, 1554, -1, 1563, 1575, 1574, -1, 1560, 447, 444, -1, 1560, 1576, 447, -1, 1567, 1577, 1575, -1, 1567, 1575, 1563, -1, 1567, 253, 1577, -1, 1556, 1555, 1576, -1, 1556, 1576, 1560, -1, 1561, 444, 277, -1, 1561, 277, 1558, -1, 1561, 1560, 444, -1, 1558, 277, 276, -1, 1558, 276, 1578, -1, 1559, 1578, 1579, -1, 1559, 1558, 1578, -1, 1565, 1579, 1580, -1, 1565, 1559, 1579, -1, 1569, 1580, 1581, -1, 1569, 1565, 1580, -1, 1571, 1581, 1582, -1, 1571, 1569, 1581, -1, 249, 1582, 250, -1, 249, 1571, 1582, -1, 533, 327, 531, -1, 1582, 519, 250, -1, 1579, 543, 1580, -1, 1578, 543, 1579, -1, 276, 543, 1578, -1, 1583, 531, 529, -1, 1584, 533, 531, -1, 1584, 531, 1583, -1, 1584, 1583, 529, -1, 1585, 529, 527, -1, 1586, 529, 1585, -1, 1587, 535, 533, -1, 1587, 1584, 529, -1, 1587, 533, 1584, -1, 1587, 1586, 535, -1, 1587, 529, 1586, -1, 1588, 525, 523, -1, 1588, 527, 525, -1, 1588, 1585, 527, -1, 1589, 1585, 1588, -1, 1589, 535, 1586, -1, 1589, 1586, 1585, -1, 1590, 537, 535, -1, 1590, 1589, 537, -1, 1590, 535, 1589, -1, 1591, 1588, 523, -1, 1592, 1589, 1588, -1, 1592, 537, 1589, -1, 1592, 1588, 1591, -1, 1593, 539, 537, -1, 1593, 537, 1592, -1, 1593, 1592, 539, -1, 1594, 521, 519, -1, 1594, 523, 521, -1, 1594, 1591, 523, -1, 1595, 539, 1592, -1, 1595, 1592, 1591, -1, 1595, 1591, 1594, -1, 1596, 541, 539, -1, 1596, 1595, 541, -1, 1596, 539, 1595, -1, 1597, 1582, 1581, -1, 1597, 1594, 519, -1, 1597, 519, 1582, -1, 1598, 1581, 1580, -1, 1598, 541, 1595, -1, 1598, 1597, 1581, -1, 1598, 1580, 543, -1, 1598, 1595, 1594, -1, 1598, 1594, 1597, -1, 1599, 543, 541, -1, 1599, 1598, 543, -1, 1599, 541, 1598, -1, 356, 508, 357, -1, 357, 508, 517, -1, 517, 512, 516, -1, 508, 512, 517, -1, 516, 511, 515, -1, 512, 511, 516, -1, 515, 509, 514, -1, 514, 509, 513, -1, 511, 509, 515, -1, 509, 510, 513, -1, 351, 1370, 225, -1, 225, 1370, 226, -1, 226, 1369, 227, -1, 1370, 1369, 226, -1, 227, 1368, 228, -1, 1369, 1368, 227, -1, 228, 1367, 229, -1, 1368, 1367, 228, -1, 229, 1365, 230, -1, 1367, 1365, 229, -1, 230, 1366, 231, -1, 1365, 1366, 230, -1, 231, 1364, 232, -1, 1366, 1364, 231, -1, 1371, 1377, 233, -1, 233, 1377, 234, -1, 234, 1377, 235, -1, 235, 1376, 236, -1, 1377, 1376, 235, -1, 236, 1375, 237, -1, 1376, 1375, 236, -1, 237, 1374, 238, -1, 1375, 1374, 237, -1, 238, 1373, 241, -1, 1374, 1373, 238, -1, 241, 1372, 242, -1, 1373, 1372, 241, -1, 1372, 359, 242, -1, 329, 328, 631, -1, 530, 631, 629, -1, 530, 329, 631, -1, 528, 629, 627, -1, 528, 530, 629, -1, 1400, 528, 627, -1, 1401, 1400, 627, -1, 1403, 1401, 627, -1, 1405, 1403, 627, -1, 1407, 1405, 627, -1, 1409, 1407, 627, -1, 1413, 627, 625, -1, 1413, 1409, 627, -1, 1415, 1413, 625, -1, 377, 1415, 625, -1, 378, 625, 623, -1, 378, 377, 625, -1, 381, 623, 621, -1, 381, 378, 623, -1, 384, 621, 619, -1, 384, 381, 621, -1, 385, 619, 354, -1, 385, 384, 619, -1, 382, 385, 354, -1, 368, 358, 643, -1, 370, 643, 641, -1, 370, 368, 643, -1, 371, 641, 639, -1, 371, 370, 641, -1, 393, 371, 639, -1, 394, 639, 637, -1, 394, 393, 639, -1, 395, 394, 637, -1, 1441, 637, 635, -1, 1441, 395, 637, -1, 1442, 1441, 635, -1, 1444, 1442, 635, -1, 1439, 1444, 635, -1, 1437, 1439, 635, -1, 1435, 1437, 635, -1, 575, 635, 633, -1, 575, 1435, 635, -1, 577, 575, 633, -1, 298, 633, 294, -1, 298, 577, 633, -1, 1600, 1601, 1602, -1, 1603, 1601, 1604, -1, 1605, 1603, 1604, -1, 1606, 1601, 1600, -1, 1606, 1604, 1601, -1, 1600, 1602, 1607, -1, 1600, 1607, 1608, -1, 1609, 1610, 1611, -1, 1609, 1611, 1612, -1, 1610, 1613, 1611, -1, 1614, 1613, 1610, -1, 1614, 1615, 1613, -1, 1616, 1615, 1614, -1, 1617, 1618, 1619, -1, 1620, 1618, 1617, -1, 1618, 1621, 1622, -1, 1620, 1621, 1618, -1, 1622, 1623, 1624, -1, 1621, 1623, 1622, -1, 1619, 1624, 1617, -1, 1624, 1623, 1617, -1, 1625, 1626, 1627, -1, 1628, 1626, 1625, -1, 1627, 1629, 1630, -1, 1626, 1629, 1627, -1, 1630, 1631, 1632, -1, 1629, 1631, 1630, -1, 1632, 1631, 1625, -1, 1631, 1628, 1625, -1, 1610, 1633, 1614, -1, 1634, 1633, 1610, -1, 1616, 1614, 1633, -1, 1635, 1636, 1616, -1, 1637, 1634, 1610, -1, 1609, 1635, 1637, -1, 1609, 1636, 1635, -1, 1609, 1637, 1610, -1, 1633, 1635, 1616, -1, 1638, 1639, 1640, -1, 1641, 1642, 1643, -1, 1640, 1644, 1641, -1, 1642, 1644, 1645, -1, 1641, 1644, 1642, -1, 1639, 1644, 1640, -1, 1644, 1646, 1645, -1, 1647, 1646, 1644, -1, 1646, 1648, 1645, -1, 1644, 1649, 1647, -1, 1648, 1650, 1645, -1, 1644, 1651, 1649, -1, 1650, 1652, 1645, -1, 1644, 1653, 1651, -1, 1644, 1654, 1653, -1, 1652, 1655, 1645, -1, 1655, 1656, 1645, -1, 1656, 1657, 1645, -1, 1656, 1658, 1657, -1, 1658, 1659, 1657, -1, 1659, 1660, 1657, -1, 1660, 1661, 1657, -1, 1657, 1662, 1663, -1, 1657, 1664, 1662, -1, 1657, 1665, 1664, -1, 1657, 1666, 1665, -1, 1657, 1667, 1666, -1, 1668, 1669, 1661, -1, 1670, 1669, 1668, -1, 1671, 1669, 1670, -1, 1672, 1669, 1671, -1, 1657, 1669, 1667, -1, 1661, 1669, 1657, -1, 1672, 1673, 1669, -1, 1644, 1674, 1654, -1, 1674, 1675, 1654, -1, 1674, 1676, 1675, -1, 1674, 1677, 1676, -1, 1674, 1678, 1677, -1, 1674, 1679, 1678, -1, 1680, 1681, 1682, -1, 1682, 1681, 1674, -1, 1683, 1684, 1685, -1, 1685, 1684, 1681, -1, 1681, 1684, 1674, -1, 1673, 1686, 1669, -1, 1679, 1687, 1688, -1, 1674, 1687, 1679, -1, 1689, 1687, 1690, -1, 1691, 1687, 1689, -1, 1692, 1687, 1691, -1, 1688, 1687, 1692, -1, 1684, 1687, 1674, -1, 1693, 1694, 1695, -1, 1695, 1694, 1696, -1, 1696, 1694, 1697, -1, 1687, 1698, 1690, -1, 1687, 1699, 1698, -1, 1700, 1701, 1694, -1, 1702, 1701, 1700, -1, 1703, 1701, 1702, -1, 1704, 1701, 1703, -1, 1705, 1701, 1704, -1, 1694, 1701, 1697, -1, 1705, 1706, 1701, -1, 1699, 1707, 1705, -1, 1705, 1707, 1706, -1, 1687, 1707, 1699, -1, 1687, 1708, 1707, -1, 1709, 1710, 1711, -1, 1711, 1710, 1712, -1, 1712, 1710, 1713, -1, 1713, 1710, 1714, -1, 1714, 1710, 1715, -1, 1715, 1710, 1716, -1, 1717, 1718, 1709, -1, 1709, 1718, 1710, -1, 1718, 1719, 1710, -1, 1709, 1720, 1717, -1, 1719, 1721, 1710, -1, 1709, 1722, 1720, -1, 1721, 1723, 1710, -1, 1709, 1724, 1722, -1, 1709, 1725, 1724, -1, 1723, 1726, 1710, -1, 1709, 1727, 1725, -1, 1726, 1728, 1710, -1, 1726, 1729, 1728, -1, 1729, 1730, 1728, -1, 1730, 1731, 1728, -1, 1731, 1732, 1728, -1, 1732, 1733, 1728, -1, 1734, 1735, 1736, -1, 1736, 1735, 1737, -1, 1734, 1738, 1735, -1, 1728, 1739, 1734, -1, 1734, 1739, 1738, -1, 1733, 1740, 1728, -1, 1728, 1740, 1739, -1, 1741, 1740, 1733, -1, 1742, 1740, 1741, -1, 1743, 1740, 1742, -1, 1744, 1740, 1743, -1, 1745, 1740, 1744, -1, 1746, 1747, 1748, -1, 1748, 1747, 1749, -1, 1749, 1747, 1750, -1, 1751, 1747, 1746, -1, 1751, 1752, 1747, -1, 1751, 1753, 1752, -1, 1751, 1754, 1753, -1, 1751, 1755, 1754, -1, 1751, 1756, 1755, -1, 1757, 1756, 1758, -1, 1758, 1756, 1751, -1, 1757, 1759, 1756, -1, 1760, 1761, 1762, -1, 1763, 1761, 1760, -1, 1764, 1761, 1763, -1, 1765, 1761, 1764, -1, 1766, 1761, 1765, -1, 1767, 1761, 1766, -1, 1768, 1761, 1757, -1, 1759, 1761, 1767, -1, 1757, 1761, 1759, -1, 1761, 1769, 1762, -1, 1745, 1769, 1740, -1, 1770, 1769, 1745, -1, 1771, 1769, 1770, -1, 1772, 1769, 1771, -1, 1773, 1769, 1772, -1, 1762, 1769, 1773, -1, 1761, 1774, 1769, -1, 1761, 1775, 1774, -1, 1775, 1776, 1774, -1, 1774, 1776, 1777, -1, 1777, 1776, 1778, -1, 1779, 1776, 1775, -1, 1687, 1761, 1780, -1, 1687, 1780, 1708, -1, 1780, 1761, 1781, -1, 1781, 1761, 1768, -1, 1747, 1725, 1727, -1, 1747, 1727, 1750, -1, 1673, 1694, 1686, -1, 1686, 1694, 1693, -1, 1782, 1783, 1784, -1, 1785, 1786, 1787, -1, 1788, 1789, 1787, -1, 1790, 1789, 1788, -1, 1791, 1785, 1787, -1, 1791, 1787, 1789, -1, 1792, 1793, 1794, -1, 1792, 1794, 1795, -1, 1784, 1796, 1782, -1, 1784, 1797, 1796, -1, 1796, 1798, 1799, -1, 1797, 1798, 1796, -1, 1800, 1801, 1798, -1, 1798, 1801, 1799, -1, 1802, 1803, 1804, -1, 1805, 1806, 1803, -1, 1807, 1806, 1805, -1, 1807, 1808, 1806, -1, 1803, 1809, 1804, -1, 1806, 1809, 1803, -1, 1810, 1811, 1786, -1, 1812, 1813, 1810, -1, 1810, 1813, 1811, -1, 1811, 1787, 1786, -1, 1813, 1814, 1811, -1, 1813, 1797, 1814, -1, 1814, 1784, 1783, -1, 1797, 1784, 1814, -1, 1601, 1815, 1602, -1, 1816, 1807, 1817, -1, 1815, 1607, 1602, -1, 1817, 1818, 1815, -1, 1815, 1818, 1607, -1, 1817, 1805, 1818, -1, 1807, 1805, 1817, -1, 1818, 1819, 1607, -1, 1810, 1786, 1785, -1, 1820, 1810, 1785, -1, 1821, 1794, 1822, -1, 1795, 1794, 1821, -1, 1823, 1824, 1820, -1, 1825, 1823, 1820, -1, 1826, 1825, 1820, -1, 1827, 1820, 1785, -1, 1827, 1826, 1820, -1, 1828, 1827, 1785, -1, 1829, 1828, 1785, -1, 1830, 1829, 1785, -1, 1831, 1830, 1785, -1, 1832, 1831, 1785, -1, 1791, 1832, 1785, -1, 1833, 1834, 1600, -1, 1835, 1833, 1600, -1, 1836, 1835, 1600, -1, 1837, 1836, 1600, -1, 1606, 1600, 1834, -1, 1838, 1837, 1600, -1, 1608, 1839, 1838, -1, 1608, 1840, 1839, -1, 1608, 1838, 1600, -1, 1841, 1840, 1608, -1, 1842, 1841, 1608, -1, 1800, 1813, 1812, -1, 1800, 1798, 1813, -1, 1818, 1802, 1819, -1, 1803, 1802, 1818, -1, 1843, 1844, 1845, -1, 1846, 1847, 1848, -1, 1846, 1849, 1847, -1, 1846, 1850, 1849, -1, 1846, 1843, 1850, -1, 1851, 1844, 1843, -1, 1851, 1843, 1846, -1, 1852, 1844, 1851, -1, 1853, 1844, 1852, -1, 1854, 1844, 1853, -1, 1855, 1844, 1854, -1, 1856, 1844, 1855, -1, 1857, 1858, 1859, -1, 1860, 1857, 1859, -1, 1861, 1857, 1860, -1, 1862, 1857, 1861, -1, 1863, 1857, 1862, -1, 1864, 1865, 1863, -1, 1864, 1866, 1865, -1, 1864, 1867, 1866, -1, 1864, 1868, 1867, -1, 1864, 1869, 1868, -1, 1864, 1862, 1870, -1, 1864, 1863, 1862, -1, 1864, 1844, 1856, -1, 1864, 1856, 1869, -1, 1871, 1872, 1873, -1, 1874, 1872, 1871, -1, 1805, 1803, 1818, -1, 1798, 1797, 1813, -1, 1875, 1876, 1877, -1, 1878, 1879, 1877, -1, 1878, 1877, 1876, -1, 1880, 1875, 1877, -1, 1881, 1879, 1878, -1, 1882, 1880, 1877, -1, 1883, 1882, 1877, -1, 1884, 1879, 1881, -1, 1885, 1883, 1877, -1, 1886, 1883, 1885, -1, 1887, 1886, 1885, -1, 1888, 1887, 1885, -1, 1889, 1888, 1885, -1, 1890, 1891, 1892, -1, 1890, 1892, 1889, -1, 1890, 1889, 1885, -1, 1893, 1894, 1895, -1, 1894, 1896, 1895, -1, 1893, 1897, 1894, -1, 1897, 1898, 1894, -1, 1899, 1900, 1901, -1, 1902, 1900, 1899, -1, 1903, 1904, 1905, -1, 1904, 1906, 1905, -1, 1907, 1908, 1909, -1, 1908, 1910, 1909, -1, 1911, 1912, 1913, -1, 1914, 1912, 1911, -1, 1915, 1916, 1917, -1, 1918, 1916, 1915, -1, 1919, 1920, 1921, -1, 1919, 1922, 1920, -1, 1921, 1923, 1919, -1, 1921, 1924, 1923, -1, 1923, 1925, 1926, -1, 1924, 1925, 1923, -1, 1927, 1928, 1929, -1, 1927, 1930, 1928, -1, 1928, 1931, 1929, -1, 1928, 1932, 1931, -1, 1916, 1911, 1917, -1, 1933, 1911, 1934, -1, 1934, 1911, 1935, -1, 1935, 1911, 1916, -1, 1911, 1913, 1917, -1, 1936, 1907, 1937, -1, 1937, 1907, 1938, -1, 1938, 1907, 1913, -1, 1913, 1907, 1917, -1, 1917, 1909, 1899, -1, 1907, 1909, 1917, -1, 1939, 1940, 1941, -1, 1941, 1940, 1909, -1, 1899, 1905, 1902, -1, 1902, 1905, 1942, -1, 1942, 1905, 1943, -1, 1943, 1905, 1944, -1, 1909, 1903, 1899, -1, 1940, 1903, 1909, -1, 1899, 1903, 1905, -1, 1945, 1946, 1947, -1, 1948, 1949, 1950, -1, 1951, 1823, 1825, -1, 1636, 1823, 1951, -1, 1616, 1951, 1615, -1, 1616, 1636, 1951, -1, 1606, 1952, 1604, -1, 1793, 1952, 1606, -1, 1953, 1793, 1792, -1, 1824, 1842, 1954, -1, 1824, 1954, 1955, -1, 1956, 1841, 1842, -1, 1956, 1842, 1824, -1, 1956, 1953, 1792, -1, 1791, 1789, 1957, -1, 1612, 1791, 1957, -1, 1636, 1824, 1823, -1, 1636, 1956, 1824, -1, 1958, 1636, 1609, -1, 1958, 1609, 1612, -1, 1957, 1958, 1612, -1, 1958, 1953, 1636, -1, 1636, 1953, 1956, -1, 1953, 1952, 1793, -1, 1841, 1959, 1840, -1, 1960, 1961, 1959, -1, 1956, 1959, 1841, -1, 1956, 1960, 1959, -1, 1961, 1960, 1821, -1, 1961, 1821, 1822, -1, 1808, 1807, 1816, -1, 1962, 1795, 1821, -1, 1962, 1963, 1795, -1, 1964, 1795, 1963, -1, 1960, 1962, 1821, -1, 1792, 1964, 1965, -1, 1792, 1795, 1964, -1, 1956, 1792, 1965, -1, 1956, 1965, 1960, -1, 1965, 1962, 1960, -1, 1966, 1967, 1968, -1, 1969, 1970, 1971, -1, 1969, 1972, 1970, -1, 1969, 1973, 1972, -1, 1974, 1971, 1975, -1, 1974, 1969, 1971, -1, 1976, 1974, 1975, -1, 1977, 1975, 1978, -1, 1977, 1976, 1975, -1, 1979, 1978, 1967, -1, 1979, 1977, 1978, -1, 1979, 1967, 1966, -1, 1603, 1979, 1966, -1, 1605, 1979, 1603, -1, 1980, 1603, 1966, -1, 1981, 1603, 1980, -1, 1982, 1980, 1966, -1, 1983, 1982, 1966, -1, 1984, 1985, 1983, -1, 1984, 1983, 1966, -1, 1986, 1984, 1987, -1, 1988, 1984, 1986, -1, 1788, 1989, 1985, -1, 1788, 1985, 1984, -1, 1990, 1790, 1788, -1, 1990, 1984, 1988, -1, 1990, 1788, 1984, -1, 1991, 1988, 1992, -1, 1991, 1990, 1988, -1, 1993, 1992, 1994, -1, 1993, 1991, 1992, -1, 1995, 1993, 1994, -1, 1996, 1995, 1994, -1, 1996, 1994, 1997, -1, 1900, 1942, 1998, -1, 1902, 1942, 1900, -1, 1998, 1943, 1999, -1, 1942, 1943, 1998, -1, 1999, 1944, 2000, -1, 1943, 1944, 1999, -1, 2000, 1905, 1906, -1, 1944, 1905, 2000, -1, 1904, 1940, 2001, -1, 1903, 1940, 1904, -1, 2001, 1939, 2002, -1, 1940, 1939, 2001, -1, 2002, 1941, 2003, -1, 1939, 1941, 2002, -1, 2003, 1909, 1910, -1, 1941, 1909, 2003, -1, 1908, 1907, 2004, -1, 2004, 1936, 2005, -1, 1907, 1936, 2004, -1, 1936, 1937, 2005, -1, 2005, 1938, 2006, -1, 1937, 1938, 2005, -1, 2006, 1913, 1912, -1, 1938, 1913, 2006, -1, 1914, 1933, 2007, -1, 1911, 1933, 1914, -1, 2007, 1934, 2008, -1, 2008, 1934, 2009, -1, 1933, 1934, 2007, -1, 2009, 1935, 1918, -1, 1934, 1935, 2009, -1, 1935, 1916, 1918, -1, 2010, 1922, 1919, -1, 2010, 1919, 2011, -1, 2012, 2011, 2013, -1, 2012, 2010, 2011, -1, 2014, 2013, 2015, -1, 2014, 2012, 2013, -1, 2016, 2015, 2017, -1, 2016, 2014, 2015, -1, 2018, 2017, 2019, -1, 2018, 2016, 2017, -1, 2020, 2019, 2021, -1, 2020, 2018, 2019, -1, 1901, 2021, 1899, -1, 1901, 2020, 2021, -1, 2022, 2021, 2019, -1, 2022, 1899, 2021, -1, 2022, 1917, 1899, -1, 2023, 2022, 2019, -1, 2024, 2019, 2017, -1, 2024, 2023, 2019, -1, 2025, 2017, 2015, -1, 2025, 2024, 2017, -1, 2026, 2013, 2011, -1, 2026, 2015, 2013, -1, 2026, 2025, 2015, -1, 2027, 2011, 1919, -1, 2027, 2026, 2011, -1, 1923, 2027, 1919, -1, 1915, 1917, 2022, -1, 2028, 2022, 2023, -1, 2028, 1915, 2022, -1, 2029, 2023, 2024, -1, 2029, 2028, 2023, -1, 2030, 2024, 2025, -1, 2030, 2029, 2024, -1, 2031, 2025, 2026, -1, 2031, 2030, 2025, -1, 2032, 2026, 2027, -1, 2032, 2031, 2026, -1, 2033, 2027, 1923, -1, 2033, 2032, 2027, -1, 1926, 2033, 1923, -1, 1873, 1872, 2034, -1, 2035, 2036, 2037, -1, 2034, 2036, 2035, -1, 1872, 2036, 2034, -1, 2038, 2039, 2040, -1, 2037, 2039, 2038, -1, 2036, 2039, 2037, -1, 2040, 2041, 2042, -1, 2039, 2041, 2040, -1, 2042, 2043, 1947, -1, 2041, 2043, 2042, -1, 2043, 1945, 1947, -1, 1947, 1946, 2044, -1, 2045, 2044, 2046, -1, 2045, 1947, 2044, -1, 2047, 2048, 2049, -1, 2047, 2046, 2048, -1, 2047, 2045, 2046, -1, 2050, 2047, 2049, -1, 1881, 2049, 1884, -1, 1881, 2050, 2049, -1, 2051, 1873, 2034, -1, 2045, 2042, 1947, -1, 2050, 1878, 2047, -1, 1881, 1878, 2050, -1, 2052, 2035, 2037, -1, 2052, 2034, 2035, -1, 2052, 2051, 2034, -1, 2053, 2037, 2038, -1, 2053, 2052, 2037, -1, 2054, 2055, 2051, -1, 2054, 2051, 2052, -1, 2056, 2038, 2040, -1, 2056, 2053, 2038, -1, 2057, 2052, 2053, -1, 2057, 2054, 2052, -1, 2058, 1882, 1883, -1, 2058, 1883, 2055, -1, 2058, 2055, 2054, -1, 2059, 2053, 2056, -1, 2059, 2057, 2053, -1, 2060, 1880, 1882, -1, 2060, 2054, 2057, -1, 2060, 1882, 2058, -1, 2060, 2058, 2054, -1, 2061, 2040, 2042, -1, 2061, 2056, 2040, -1, 2062, 1875, 1880, -1, 2062, 2057, 2059, -1, 2062, 1880, 2060, -1, 2062, 2060, 2057, -1, 2063, 2059, 2056, -1, 2063, 2056, 2061, -1, 2064, 1876, 1875, -1, 2064, 1875, 2062, -1, 2064, 2062, 2059, -1, 2064, 2059, 2063, -1, 2065, 2045, 2047, -1, 2065, 2061, 2042, -1, 2065, 2042, 2045, -1, 2066, 2065, 2047, -1, 2066, 2063, 2061, -1, 2066, 2047, 1878, -1, 2066, 2061, 2065, -1, 2067, 1878, 1876, -1, 2067, 2066, 1878, -1, 2067, 1876, 2064, -1, 2067, 2064, 2063, -1, 2067, 2063, 2066, -1, 1871, 1873, 2051, -1, 2068, 1871, 2051, -1, 2069, 2051, 2055, -1, 2069, 2068, 2051, -1, 1886, 2055, 1883, -1, 1886, 2069, 2055, -1, 2070, 1948, 1950, -1, 2070, 1950, 2071, -1, 2072, 2071, 2073, -1, 2072, 2070, 2071, -1, 2074, 2073, 2075, -1, 2074, 2072, 2073, -1, 2076, 2075, 1892, -1, 2076, 2074, 2075, -1, 1891, 2076, 1892, -1, 2077, 2071, 1950, -1, 1889, 1892, 2075, -1, 2068, 2078, 1871, -1, 2079, 2073, 2071, -1, 2079, 2071, 2077, -1, 2080, 2073, 2079, -1, 2081, 1888, 1889, -1, 2081, 2075, 2073, -1, 2081, 1889, 2075, -1, 2081, 2073, 2080, -1, 2082, 2077, 2083, -1, 2082, 2083, 2084, -1, 2082, 2079, 2077, -1, 2085, 2079, 2082, -1, 2085, 2080, 2079, -1, 2086, 2081, 2080, -1, 2086, 2080, 2085, -1, 2086, 1888, 2081, -1, 2087, 2084, 2088, -1, 2087, 2082, 2084, -1, 2089, 2088, 2090, -1, 2089, 2090, 2078, -1, 2089, 2078, 2068, -1, 2089, 2087, 2088, -1, 2091, 2085, 2082, -1, 2091, 2082, 2087, -1, 2092, 2068, 2069, -1, 2092, 2087, 2089, -1, 2092, 2089, 2068, -1, 2092, 2091, 2087, -1, 2093, 1887, 1888, -1, 2093, 2086, 2085, -1, 2093, 1888, 2086, -1, 2093, 2085, 2091, -1, 2094, 1886, 1887, -1, 2094, 2069, 1886, -1, 2094, 1887, 2093, -1, 2094, 2092, 2069, -1, 2094, 2091, 2092, -1, 2094, 2093, 2091, -1, 1871, 2078, 1874, -1, 1874, 2090, 2095, -1, 2078, 2090, 1874, -1, 2090, 2088, 2095, -1, 2095, 2084, 2096, -1, 2088, 2084, 2095, -1, 2096, 2083, 2097, -1, 2084, 2083, 2096, -1, 2097, 2077, 2098, -1, 2098, 2077, 2099, -1, 2083, 2077, 2097, -1, 2099, 1950, 1949, -1, 2077, 1950, 2099, -1, 1885, 1877, 2100, -1, 2101, 2100, 2102, -1, 2101, 1885, 2100, -1, 2103, 2102, 2104, -1, 2103, 2101, 2102, -1, 2105, 2104, 2106, -1, 2105, 2103, 2104, -1, 2107, 2106, 1924, -1, 2107, 2105, 2106, -1, 1921, 2107, 1924, -1, 1812, 2108, 2109, -1, 1812, 2110, 1800, -1, 2109, 2110, 1812, -1, 1812, 2111, 2108, -1, 1810, 2112, 1812, -1, 1812, 2112, 2111, -1, 1820, 1955, 1810, -1, 1810, 1955, 2112, -1, 2110, 1801, 1800, -1, 2110, 1983, 1801, -1, 1820, 1824, 1955, -1, 2113, 2114, 1819, -1, 1802, 2115, 1819, -1, 1819, 2115, 2113, -1, 2114, 2116, 1819, -1, 1819, 2117, 1607, -1, 2116, 2117, 1819, -1, 1607, 1954, 1608, -1, 2117, 1954, 1607, -1, 1802, 1804, 2115, -1, 1804, 1982, 2115, -1, 1954, 1842, 1608, -1, 1809, 1981, 1980, -1, 1817, 1809, 1806, -1, 1815, 1981, 1809, -1, 1815, 1809, 1817, -1, 1981, 1815, 1601, -1, 1603, 1981, 1601, -1, 1808, 1816, 1817, -1, 1806, 1808, 1817, -1, 1796, 1814, 1783, -1, 1782, 1796, 1783, -1, 1989, 1788, 1787, -1, 1989, 1787, 1811, -1, 1799, 1814, 1796, -1, 1989, 1799, 1985, -1, 1989, 1811, 1799, -1, 1799, 1811, 1814, -1, 1930, 1927, 2118, -1, 2119, 2118, 2120, -1, 2119, 1930, 2118, -1, 2121, 2120, 2122, -1, 2121, 2119, 2120, -1, 2123, 2122, 2124, -1, 2123, 2121, 2122, -1, 2125, 2124, 2126, -1, 2125, 2123, 2124, -1, 2127, 2126, 2128, -1, 2127, 2125, 2126, -1, 2129, 2128, 2130, -1, 2129, 2127, 2128, -1, 2131, 2130, 1845, -1, 2131, 2129, 2130, -1, 1844, 2131, 1845, -1, 2132, 1877, 1879, -1, 2132, 1879, 2133, -1, 2134, 2133, 2135, -1, 2134, 2132, 2133, -1, 2136, 2135, 2137, -1, 2136, 2134, 2135, -1, 2138, 2137, 2139, -1, 2138, 2136, 2137, -1, 2140, 2139, 2141, -1, 2140, 2138, 2139, -1, 2142, 2141, 2143, -1, 2142, 2140, 2141, -1, 2144, 2143, 1927, -1, 2144, 2142, 2143, -1, 1929, 2144, 1927, -1, 2144, 1929, 2145, -1, 2106, 2146, 1924, -1, 1877, 2132, 2100, -1, 2147, 2145, 2148, -1, 2147, 2148, 2149, -1, 2150, 2142, 2144, -1, 2150, 2140, 2142, -1, 2150, 2144, 2145, -1, 2150, 2149, 2140, -1, 2150, 2145, 2147, -1, 2150, 2147, 2149, -1, 2151, 2149, 2152, -1, 2151, 2152, 2153, -1, 2154, 2138, 2140, -1, 2154, 2136, 2138, -1, 2154, 2140, 2149, -1, 2154, 2149, 2151, -1, 2155, 2153, 2156, -1, 2155, 2156, 2146, -1, 2155, 2106, 2104, -1, 2155, 2146, 2106, -1, 2157, 2134, 2136, -1, 2157, 2132, 2134, -1, 2157, 2104, 2102, -1, 2157, 2102, 2100, -1, 2157, 2155, 2104, -1, 2157, 2100, 2132, -1, 2158, 2136, 2154, -1, 2158, 2154, 2151, -1, 2158, 2157, 2136, -1, 2158, 2155, 2157, -1, 2158, 2151, 2153, -1, 2158, 2153, 2155, -1, 1925, 1924, 2146, -1, 2159, 2156, 2153, -1, 2159, 2146, 2156, -1, 2159, 1925, 2146, -1, 2160, 2153, 2152, -1, 2160, 2159, 2153, -1, 2161, 2152, 2149, -1, 2161, 2160, 2152, -1, 2162, 2149, 2148, -1, 2162, 2161, 2149, -1, 2163, 2148, 2145, -1, 2163, 2162, 2148, -1, 2164, 2145, 1929, -1, 2164, 2163, 2145, -1, 1931, 2164, 1929, -1, 1895, 1896, 2165, -1, 2166, 2165, 2167, -1, 2166, 1895, 2165, -1, 2168, 2167, 2169, -1, 2168, 2166, 2167, -1, 2170, 2169, 2171, -1, 2170, 2168, 2169, -1, 2172, 2173, 2174, -1, 2172, 2171, 2173, -1, 2172, 2170, 2171, -1, 2175, 2174, 2176, -1, 2175, 2172, 2174, -1, 2177, 2176, 1864, -1, 2177, 2175, 2176, -1, 1870, 2177, 1864, -1, 2178, 1890, 1885, -1, 2178, 1885, 2179, -1, 2180, 2179, 2181, -1, 2180, 2178, 2179, -1, 2182, 2181, 2183, -1, 2182, 2180, 2181, -1, 2184, 2183, 2185, -1, 2184, 2182, 2183, -1, 2186, 2185, 2187, -1, 2186, 2184, 2185, -1, 2188, 2187, 2189, -1, 2188, 2186, 2187, -1, 2190, 2189, 1893, -1, 2190, 2188, 2189, -1, 1895, 2190, 1893, -1, 2191, 1893, 2189, -1, 2101, 2179, 1885, -1, 1921, 2192, 2107, -1, 2193, 2187, 2185, -1, 2193, 2189, 2187, -1, 2194, 2191, 2189, -1, 2194, 2189, 2193, -1, 2194, 2193, 2185, -1, 2195, 2191, 2194, -1, 2195, 2185, 2196, -1, 2195, 2194, 2185, -1, 2197, 2196, 2198, -1, 2197, 2198, 2191, -1, 2197, 2191, 2195, -1, 2197, 2195, 2196, -1, 2199, 2185, 2183, -1, 2200, 2185, 2199, -1, 2200, 2196, 2185, -1, 2201, 2196, 2200, -1, 2202, 2203, 2196, -1, 2202, 2196, 2201, -1, 2204, 2181, 2179, -1, 2204, 2183, 2181, -1, 2204, 2199, 2183, -1, 2205, 2200, 2199, -1, 2205, 2199, 2204, -1, 2206, 2201, 2200, -1, 2206, 2200, 2205, -1, 2207, 2192, 2208, -1, 2207, 2208, 2203, -1, 2207, 2202, 2201, -1, 2207, 2203, 2202, -1, 2207, 2201, 2206, -1, 2209, 2204, 2179, -1, 2209, 2179, 2101, -1, 2210, 2101, 2103, -1, 2210, 2205, 2204, -1, 2210, 2209, 2101, -1, 2210, 2204, 2209, -1, 2211, 2103, 2105, -1, 2211, 2210, 2103, -1, 2211, 2205, 2210, -1, 2211, 2206, 2205, -1, 2212, 2105, 2107, -1, 2212, 2192, 2207, -1, 2212, 2107, 2192, -1, 2212, 2207, 2206, -1, 2212, 2211, 2105, -1, 2212, 2206, 2211, -1, 1897, 1893, 2191, -1, 2213, 2191, 2198, -1, 2213, 1897, 2191, -1, 2214, 2198, 2196, -1, 2214, 2213, 2198, -1, 2215, 2196, 2203, -1, 2215, 2214, 2196, -1, 2216, 2203, 2208, -1, 2216, 2215, 2203, -1, 2217, 2208, 2192, -1, 2217, 2216, 2208, -1, 2218, 2217, 2192, -1, 1920, 2192, 1921, -1, 1920, 2218, 2192, -1, 1932, 1928, 2219, -1, 2220, 2219, 2221, -1, 2220, 1932, 2219, -1, 2222, 2221, 2223, -1, 2222, 2220, 2221, -1, 2224, 2223, 2225, -1, 2224, 2222, 2223, -1, 2226, 2225, 2227, -1, 2226, 2224, 2225, -1, 2228, 2227, 2229, -1, 2228, 2226, 2227, -1, 2230, 2229, 2231, -1, 2230, 2228, 2229, -1, 1953, 2231, 1952, -1, 1953, 2230, 2231, -1, 1958, 1957, 2232, -1, 2233, 2232, 2234, -1, 2233, 1958, 2232, -1, 2235, 2234, 2236, -1, 2235, 2233, 2234, -1, 2237, 2236, 2238, -1, 2237, 2235, 2236, -1, 2239, 2238, 2240, -1, 2239, 2237, 2238, -1, 2241, 2240, 2242, -1, 2241, 2239, 2240, -1, 2243, 2242, 1894, -1, 2243, 2241, 2242, -1, 1898, 2243, 1894, -1, 2244, 2245, 2246, -1, 2247, 2248, 2249, -1, 2250, 2251, 2252, -1, 2250, 2253, 2251, -1, 2254, 2249, 2255, -1, 2254, 2255, 2256, -1, 2257, 2258, 2259, -1, 2257, 2260, 2258, -1, 2257, 2252, 2261, -1, 2257, 2261, 2260, -1, 2262, 2263, 2264, -1, 2265, 2244, 2253, -1, 2262, 2256, 2263, -1, 2265, 2214, 2215, -1, 2265, 2215, 2244, -1, 2265, 2253, 2250, -1, 2266, 1737, 1735, -1, 2267, 2259, 2268, -1, 2267, 2257, 2259, -1, 2267, 2250, 2252, -1, 2267, 2252, 2257, -1, 2266, 2264, 1737, -1, 2269, 2270, 2271, -1, 2272, 2268, 2273, -1, 2272, 2213, 2214, -1, 2272, 2250, 2267, -1, 2269, 2271, 2247, -1, 2272, 2267, 2268, -1, 2272, 2214, 2265, -1, 2272, 2265, 2250, -1, 2272, 2273, 2213, -1, 2274, 2249, 2254, -1, 2274, 2247, 2249, -1, 2275, 2254, 2256, -1, 2275, 2256, 2262, -1, 2276, 2264, 2266, -1, 2276, 2262, 2264, -1, 2277, 1920, 2278, -1, 2277, 2278, 2270, -1, 2277, 2218, 1920, -1, 2277, 2270, 2269, -1, 2279, 1735, 1738, -1, 2279, 2266, 1735, -1, 2280, 2269, 2247, -1, 2280, 2247, 2274, -1, 2281, 2254, 2275, -1, 2281, 2274, 2254, -1, 2282, 2275, 2262, -1, 2282, 2262, 2276, -1, 2283, 2276, 2266, -1, 2283, 2266, 2279, -1, 2284, 2217, 2218, -1, 2284, 2269, 2280, -1, 2284, 2218, 2277, -1, 2284, 2277, 2269, -1, 2285, 1738, 1739, -1, 2285, 1739, 1740, -1, 2285, 1740, 2286, -1, 2285, 2279, 1738, -1, 2246, 2280, 2274, -1, 2246, 2274, 2281, -1, 2251, 2281, 2275, -1, 1897, 2213, 2273, -1, 2287, 2288, 1728, -1, 2287, 1728, 1734, -1, 2251, 2275, 2282, -1, 2261, 2282, 2276, -1, 2255, 2289, 2288, -1, 2261, 2276, 2283, -1, 2290, 2279, 2285, -1, 2290, 2283, 2279, -1, 2255, 2288, 2287, -1, 2290, 2286, 2291, -1, 2290, 2285, 2286, -1, 2263, 1734, 1736, -1, 2245, 2284, 2280, -1, 2263, 2287, 1734, -1, 2245, 2216, 2217, -1, 2245, 2280, 2246, -1, 2245, 2217, 2284, -1, 2253, 2281, 2251, -1, 2249, 2248, 2289, -1, 2253, 2246, 2281, -1, 2249, 2289, 2255, -1, 2252, 2282, 2261, -1, 2256, 2287, 2263, -1, 2252, 2251, 2282, -1, 2256, 2255, 2287, -1, 2260, 2291, 2258, -1, 2264, 1736, 1737, -1, 2260, 2283, 2290, -1, 2260, 2261, 2283, -1, 2260, 2290, 2291, -1, 2244, 2246, 2253, -1, 2264, 2263, 1736, -1, 2244, 2215, 2216, -1, 2244, 2216, 2245, -1, 2247, 2271, 2248, -1, 2286, 1740, 1769, -1, 2286, 1769, 2292, -1, 2291, 2292, 2293, -1, 2291, 2286, 2292, -1, 2258, 2293, 2294, -1, 2258, 2291, 2293, -1, 2259, 2294, 2295, -1, 2259, 2258, 2294, -1, 2268, 2295, 2296, -1, 2268, 2259, 2295, -1, 2273, 2296, 2297, -1, 2273, 2268, 2296, -1, 1897, 2297, 1898, -1, 1897, 2273, 2297, -1, 2298, 1728, 2288, -1, 2298, 1710, 1728, -1, 2299, 2288, 2289, -1, 2299, 2298, 2288, -1, 2300, 2289, 2248, -1, 2300, 2299, 2289, -1, 2301, 2248, 2271, -1, 2301, 2300, 2248, -1, 2302, 2271, 2270, -1, 2302, 2301, 2271, -1, 2303, 2270, 2278, -1, 2303, 2302, 2270, -1, 1922, 2278, 1920, -1, 1922, 2303, 2278, -1, 2304, 2305, 2306, -1, 2307, 2308, 2309, -1, 2304, 2310, 2311, -1, 2307, 2309, 2312, -1, 2304, 2313, 2310, -1, 2304, 2311, 2305, -1, 2314, 2235, 2237, -1, 2315, 2312, 2316, -1, 2314, 2317, 2318, -1, 2314, 2318, 2319, -1, 2315, 2316, 2320, -1, 2314, 2237, 2317, -1, 2321, 2306, 2322, -1, 2323, 1776, 1779, -1, 2321, 2319, 2313, -1, 2321, 2313, 2304, -1, 2323, 2320, 1776, -1, 2321, 2304, 2306, -1, 2324, 2322, 2325, -1, 2326, 2296, 2295, -1, 2324, 2325, 1958, -1, 2324, 1958, 2233, -1, 2324, 2321, 2322, -1, 2324, 2233, 2235, -1, 2324, 2235, 2314, -1, 2324, 2314, 2319, -1, 2326, 2295, 2327, -1, 2324, 2319, 2321, -1, 2328, 2327, 2308, -1, 2328, 2308, 2307, -1, 2329, 2312, 2315, -1, 2329, 2307, 2312, -1, 2330, 2315, 2320, -1, 2330, 2320, 2323, -1, 2331, 2297, 2296, -1, 2331, 2296, 2326, -1, 2331, 2243, 2297, -1, 2243, 1898, 2297, -1, 2332, 1779, 1775, -1, 2332, 2323, 1779, -1, 2333, 2327, 2328, -1, 2333, 2326, 2327, -1, 2334, 2328, 2307, -1, 2334, 2307, 2329, -1, 2335, 2329, 2315, -1, 2335, 2315, 2330, -1, 2336, 2323, 2332, -1, 2336, 2330, 2323, -1, 2337, 2326, 2333, -1, 2337, 2241, 2243, -1, 2337, 2243, 2331, -1, 2337, 2331, 2326, -1, 2338, 1775, 1761, -1, 2338, 1761, 2339, -1, 2338, 2332, 1775, -1, 2340, 2328, 2334, -1, 2340, 2333, 2328, -1, 2341, 2334, 2329, -1, 2341, 2329, 2335, -1, 2342, 2292, 1769, -1, 2310, 2335, 2330, -1, 2342, 1769, 1774, -1, 2342, 1774, 1777, -1, 2310, 2330, 2336, -1, 2309, 2293, 2292, -1, 2343, 2336, 2332, -1, 2343, 2339, 2344, -1, 2343, 2338, 2339, -1, 2343, 2332, 2338, -1, 2345, 2333, 2340, -1, 2309, 2292, 2342, -1, 2316, 1777, 1778, -1, 2345, 2239, 2241, -1, 2345, 2337, 2333, -1, 2345, 2241, 2337, -1, 2316, 2342, 1777, -1, 2318, 2334, 2341, -1, 2308, 2294, 2293, -1, 2318, 2340, 2334, -1, 2308, 2293, 2309, -1, 2313, 2341, 2335, -1, 2313, 2335, 2310, -1, 2312, 2342, 2316, -1, 2311, 2336, 2343, -1, 2311, 2310, 2336, -1, 2311, 2344, 2305, -1, 2312, 2309, 2342, -1, 2311, 2343, 2344, -1, 2320, 1778, 1776, -1, 2317, 2237, 2239, -1, 2317, 2239, 2345, -1, 2317, 2340, 2318, -1, 2320, 2316, 1778, -1, 2327, 2295, 2294, -1, 2317, 2345, 2340, -1, 2327, 2294, 2308, -1, 2319, 2318, 2341, -1, 2319, 2341, 2313, -1, 2346, 2347, 2348, -1, 2349, 2350, 2351, -1, 2346, 2348, 2352, -1, 2353, 2351, 2354, -1, 2355, 2356, 2357, -1, 2355, 2300, 2301, -1, 2355, 2357, 2300, -1, 2353, 2354, 2358, -1, 1711, 2359, 1709, -1, 2355, 2352, 2356, -1, 2360, 2012, 2014, -1, 2361, 2362, 2363, -1, 2360, 2364, 2347, -1, 2361, 2358, 2362, -1, 2360, 2347, 2346, -1, 2360, 2014, 2364, -1, 2365, 2301, 2302, -1, 2366, 1713, 1714, -1, 2365, 2355, 2301, -1, 2365, 2352, 2355, -1, 2366, 2363, 1713, -1, 2365, 2346, 2352, -1, 2367, 2303, 1922, -1, 2367, 2302, 2303, -1, 2367, 1922, 2010, -1, 2367, 2010, 2012, -1, 2368, 2369, 2370, -1, 2367, 2365, 2302, -1, 2368, 2370, 2349, -1, 2367, 2360, 2346, -1, 2367, 2346, 2365, -1, 2367, 2012, 2360, -1, 2371, 2351, 2353, -1, 2371, 2349, 2351, -1, 2372, 2353, 2358, -1, 2372, 2358, 2361, -1, 2373, 2363, 2366, -1, 2373, 2361, 2363, -1, 2374, 2020, 1901, -1, 2374, 1901, 2375, -1, 2374, 2375, 2369, -1, 2374, 2369, 2368, -1, 2376, 1714, 1715, -1, 2376, 2366, 1714, -1, 2377, 2368, 2349, -1, 2377, 2349, 2371, -1, 2298, 1716, 1710, -1, 2378, 2371, 2353, -1, 2378, 2353, 2372, -1, 2379, 2372, 2361, -1, 2379, 2361, 2373, -1, 2380, 2373, 2366, -1, 2380, 2366, 2376, -1, 2381, 2368, 2377, -1, 2381, 2018, 2020, -1, 2381, 2020, 2374, -1, 2381, 2374, 2368, -1, 2382, 1715, 1716, -1, 2382, 2376, 1715, -1, 2382, 1716, 2298, -1, 2383, 2377, 2371, -1, 2383, 2371, 2378, -1, 2348, 2378, 2372, -1, 2348, 2372, 2379, -1, 2384, 2359, 1711, -1, 2356, 2379, 2373, -1, 2356, 2373, 2380, -1, 2354, 2385, 2359, -1, 2386, 2298, 2299, -1, 2386, 2380, 2376, -1, 2386, 2376, 2382, -1, 2354, 2359, 2384, -1, 2386, 2382, 2298, -1, 2362, 1711, 1712, -1, 2387, 2377, 2383, -1, 2387, 2016, 2018, -1, 2362, 2384, 1711, -1, 2387, 2381, 2377, -1, 2387, 2018, 2381, -1, 2347, 2383, 2378, -1, 2351, 2350, 2385, -1, 2347, 2378, 2348, -1, 2351, 2385, 2354, -1, 2358, 2384, 2362, -1, 2352, 2348, 2379, -1, 2352, 2379, 2356, -1, 2358, 2354, 2384, -1, 2357, 2299, 2300, -1, 2357, 2356, 2380, -1, 2363, 1712, 1713, -1, 2357, 2386, 2299, -1, 2357, 2380, 2386, -1, 2363, 2362, 1712, -1, 2364, 2014, 2016, -1, 2364, 2016, 2387, -1, 2364, 2383, 2347, -1, 2364, 2387, 2383, -1, 2349, 2370, 2350, -1, 2339, 1761, 1687, -1, 2339, 1687, 2388, -1, 2344, 2388, 2389, -1, 2344, 2389, 2390, -1, 2344, 2339, 2388, -1, 2305, 2344, 2390, -1, 2306, 2390, 2391, -1, 2306, 2391, 2392, -1, 2306, 2305, 2390, -1, 2322, 2392, 2393, -1, 2322, 2306, 2392, -1, 2325, 2393, 1953, -1, 2325, 2322, 2393, -1, 1958, 2325, 1953, -1, 2394, 1709, 2359, -1, 2394, 1727, 1709, -1, 2395, 2359, 2385, -1, 2395, 2394, 2359, -1, 2396, 2385, 2350, -1, 2396, 2395, 2385, -1, 2397, 2350, 2370, -1, 2397, 2396, 2350, -1, 2398, 2370, 2369, -1, 2398, 2397, 2370, -1, 2399, 2369, 2375, -1, 2399, 2398, 2369, -1, 1900, 2375, 1901, -1, 1900, 2399, 2375, -1, 2400, 2401, 2402, -1, 2400, 2402, 2403, -1, 2404, 2405, 2406, -1, 2407, 2408, 2409, -1, 2404, 2406, 2410, -1, 2407, 2411, 2408, -1, 2407, 2412, 2411, -1, 2407, 2403, 2412, -1, 2413, 2414, 2401, -1, 2415, 2416, 2417, -1, 2413, 2222, 2224, -1, 2415, 2410, 2416, -1, 2413, 2401, 2400, -1, 2413, 2224, 2414, -1, 2418, 2409, 2419, -1, 2420, 1685, 1681, -1, 2418, 2407, 2409, -1, 2418, 2400, 2403, -1, 2418, 2403, 2407, -1, 2420, 2417, 1685, -1, 2421, 2419, 2422, -1, 2423, 2392, 2391, -1, 2421, 2422, 1932, -1, 2421, 1932, 2220, -1, 2421, 2220, 2222, -1, 2421, 2400, 2418, -1, 2421, 2222, 2413, -1, 2423, 2391, 2424, -1, 2421, 2413, 2400, -1, 2421, 2418, 2419, -1, 2425, 2405, 2404, -1, 2425, 2424, 2405, -1, 2426, 2404, 2410, -1, 2426, 2410, 2415, -1, 2427, 2415, 2417, -1, 2427, 2417, 2420, -1, 2428, 2393, 2392, -1, 2230, 1953, 2393, -1, 2428, 2230, 2393, -1, 2428, 2392, 2423, -1, 2429, 1681, 1680, -1, 2429, 2420, 1681, -1, 2430, 2423, 2424, -1, 2430, 2424, 2425, -1, 2431, 1682, 1674, -1, 2432, 2404, 2426, -1, 2432, 2425, 2404, -1, 2433, 2415, 2427, -1, 2433, 2426, 2415, -1, 2434, 2427, 2420, -1, 2434, 2420, 2429, -1, 2435, 2228, 2230, -1, 2435, 2423, 2430, -1, 2435, 2230, 2428, -1, 2435, 2428, 2423, -1, 2436, 1680, 1682, -1, 2436, 1682, 2431, -1, 2436, 2429, 1680, -1, 2437, 2430, 2425, -1, 2437, 2425, 2432, -1, 2402, 2432, 2426, -1, 2438, 2388, 1687, -1, 2402, 2426, 2433, -1, 2438, 1687, 1684, -1, 2412, 2433, 2427, -1, 2406, 2389, 2388, -1, 2412, 2427, 2434, -1, 2439, 2434, 2429, -1, 2439, 2431, 2440, -1, 2439, 2436, 2431, -1, 2406, 2388, 2438, -1, 2439, 2429, 2436, -1, 2441, 2435, 2430, -1, 2416, 1684, 1683, -1, 2441, 2226, 2228, -1, 2441, 2430, 2437, -1, 2441, 2228, 2435, -1, 2416, 2438, 1684, -1, 2401, 2437, 2432, -1, 2405, 2390, 2389, -1, 2401, 2432, 2402, -1, 2405, 2389, 2406, -1, 2403, 2433, 2412, -1, 2403, 2402, 2433, -1, 2410, 2438, 2416, -1, 2411, 2439, 2440, -1, 2410, 2406, 2438, -1, 2411, 2434, 2439, -1, 2411, 2440, 2408, -1, 2417, 1683, 1685, -1, 2411, 2412, 2434, -1, 2414, 2437, 2401, -1, 2414, 2224, 2226, -1, 2417, 2416, 1683, -1, 2414, 2226, 2441, -1, 2414, 2441, 2437, -1, 2424, 2391, 2390, -1, 2424, 2390, 2405, -1, 2442, 2443, 2444, -1, 2442, 2444, 2445, -1, 2446, 2447, 2448, -1, 2446, 2445, 2449, -1, 2446, 2449, 2450, -1, 2446, 2450, 2447, -1, 2451, 2394, 2395, -1, 2451, 2395, 2452, -1, 2451, 1750, 2394, -1, 2453, 2452, 2443, -1, 2453, 2443, 2442, -1, 2454, 2448, 2455, -1, 2454, 2445, 2446, -1, 2454, 2442, 2445, -1, 2454, 2446, 2448, -1, 2456, 1749, 1750, -1, 2456, 2452, 2453, -1, 2456, 1750, 2451, -1, 2456, 2451, 2452, -1, 2457, 2455, 2458, -1, 2457, 2454, 2455, -1, 2457, 2453, 2442, -1, 2457, 2442, 2454, -1, 2459, 2458, 2460, -1, 2459, 1748, 1749, -1, 2459, 1749, 2456, -1, 2459, 2460, 1748, -1, 2459, 2457, 2458, -1, 2459, 2456, 2453, -1, 2459, 2453, 2457, -1, 1750, 1727, 2394, -1, 1746, 1748, 2460, -1, 2461, 2399, 1900, -1, 2461, 1900, 1998, -1, 2462, 2398, 2399, -1, 2462, 2399, 2461, -1, 2463, 1998, 1999, -1, 2463, 2461, 1998, -1, 2444, 2397, 2398, -1, 2444, 2398, 2462, -1, 2449, 2461, 2463, -1, 2449, 2462, 2461, -1, 2464, 1999, 2000, -1, 2464, 2000, 1906, -1, 2464, 1906, 2465, -1, 2464, 2463, 1999, -1, 2443, 2396, 2397, -1, 2443, 2397, 2444, -1, 2445, 2444, 2462, -1, 2445, 2462, 2449, -1, 2450, 2465, 2447, -1, 2450, 2464, 2465, -1, 2450, 2463, 2464, -1, 2450, 2449, 2463, -1, 2452, 2395, 2396, -1, 2452, 2396, 2443, -1, 2431, 1674, 1644, -1, 2431, 1644, 2466, -1, 2440, 2466, 2467, -1, 2440, 2431, 2466, -1, 2408, 2467, 2468, -1, 2408, 2440, 2467, -1, 2409, 2468, 2469, -1, 2409, 2408, 2468, -1, 2419, 2469, 2470, -1, 2419, 2409, 2469, -1, 2422, 2470, 2471, -1, 2422, 2419, 2470, -1, 1932, 2471, 1931, -1, 1932, 2422, 2471, -1, 1751, 1746, 2460, -1, 2472, 2460, 2458, -1, 2472, 1751, 2460, -1, 2473, 2458, 2455, -1, 2473, 2472, 2458, -1, 2474, 2455, 2448, -1, 2474, 2473, 2455, -1, 2475, 2474, 2448, -1, 2476, 2448, 2447, -1, 2476, 2475, 2448, -1, 2477, 2447, 2465, -1, 2477, 2476, 2447, -1, 1904, 2465, 1906, -1, 1904, 2477, 2465, -1, 2478, 2479, 2480, -1, 2481, 2482, 2483, -1, 2478, 2484, 2485, -1, 2478, 2486, 2479, -1, 2478, 2485, 2486, -1, 2481, 2487, 2482, -1, 2488, 2160, 2161, -1, 2489, 2483, 2490, -1, 1639, 2466, 1644, -1, 2488, 2161, 2491, -1, 2488, 2492, 2493, -1, 2488, 2491, 2492, -1, 2489, 2490, 2494, -1, 2495, 2480, 2496, -1, 2497, 1641, 1643, -1, 2495, 2484, 2478, -1, 2495, 2478, 2480, -1, 2495, 2493, 2484, -1, 2497, 2494, 1641, -1, 2498, 2496, 2499, -1, 2500, 2470, 2469, -1, 2498, 2159, 2160, -1, 2498, 2160, 2488, -1, 2498, 2488, 2493, -1, 2498, 2493, 2495, -1, 2498, 2495, 2496, -1, 2498, 2499, 2159, -1, 2500, 2469, 2501, -1, 2502, 2487, 2481, -1, 2502, 2501, 2487, -1, 2503, 2481, 2483, -1, 2503, 2483, 2489, -1, 2504, 2494, 2497, -1, 2504, 2489, 2494, -1, 2505, 2471, 2470, -1, 2505, 1931, 2471, -1, 2505, 2164, 1931, -1, 2505, 2470, 2500, -1, 2506, 1643, 1642, -1, 2506, 2497, 1643, -1, 2507, 2500, 2501, -1, 2507, 2501, 2502, -1, 2508, 2481, 2503, -1, 2508, 2502, 2481, -1, 2509, 2503, 2489, -1, 2509, 2489, 2504, -1, 2510, 2504, 2497, -1, 2510, 2497, 2506, -1, 2511, 2163, 2164, -1, 2511, 2500, 2507, -1, 2511, 2164, 2505, -1, 2511, 2505, 2500, -1, 2512, 1642, 1645, -1, 2512, 1645, 2513, -1, 2512, 2506, 1642, -1, 2514, 2507, 2502, -1, 2514, 2502, 2508, -1, 2515, 2508, 2503, -1, 1925, 2159, 2499, -1, 2515, 2503, 2509, -1, 2485, 2504, 2510, -1, 2516, 1639, 1638, -1, 2485, 2509, 2504, -1, 2516, 2466, 1639, -1, 2482, 2467, 2466, -1, 2517, 2506, 2512, -1, 2517, 2510, 2506, -1, 2517, 2513, 2518, -1, 2517, 2512, 2513, -1, 2482, 2466, 2516, -1, 2519, 2511, 2507, -1, 2490, 1638, 1640, -1, 2519, 2162, 2163, -1, 2519, 2507, 2514, -1, 2490, 2516, 1638, -1, 2519, 2163, 2511, -1, 2492, 2514, 2508, -1, 2487, 2468, 2467, -1, 2492, 2508, 2515, -1, 2487, 2467, 2482, -1, 2484, 2509, 2485, -1, 2484, 2515, 2509, -1, 2483, 2516, 2490, -1, 2486, 2518, 2479, -1, 2486, 2510, 2517, -1, 2483, 2482, 2516, -1, 2494, 1640, 1641, -1, 2486, 2517, 2518, -1, 2486, 2485, 2510, -1, 2491, 2514, 2492, -1, 2491, 2161, 2162, -1, 2491, 2162, 2519, -1, 2494, 2490, 1640, -1, 2491, 2519, 2514, -1, 2501, 2469, 2468, -1, 2501, 2468, 2487, -1, 2493, 2492, 2515, -1, 2493, 2515, 2484, -1, 2520, 2521, 2522, -1, 2520, 2523, 2521, -1, 2520, 2524, 2523, -1, 2520, 2525, 2524, -1, 2526, 2472, 2527, -1, 2526, 1758, 2472, -1, 2001, 2477, 1904, -1, 2528, 2529, 2530, -1, 2528, 2527, 2529, -1, 2531, 2522, 2532, -1, 2531, 2520, 2522, -1, 2531, 2530, 2525, -1, 2531, 2525, 2520, -1, 2533, 1757, 1758, -1, 2533, 1758, 2526, -1, 2533, 2526, 2527, -1, 2533, 2527, 2528, -1, 2534, 2532, 2535, -1, 2534, 2531, 2532, -1, 2534, 2528, 2530, -1, 2534, 2530, 2531, -1, 2536, 2535, 2537, -1, 2536, 1768, 1757, -1, 2536, 2534, 2535, -1, 2536, 1757, 2533, -1, 2536, 2537, 1768, -1, 2536, 2533, 2528, -1, 2536, 2528, 2534, -1, 1758, 1751, 2472, -1, 1781, 1768, 2537, -1, 2538, 2476, 2477, -1, 2538, 2477, 2001, -1, 2539, 2475, 2476, -1, 2539, 2476, 2538, -1, 2540, 2001, 2002, -1, 2540, 2538, 2001, -1, 2541, 2474, 2475, -1, 2541, 2475, 2539, -1, 2524, 2538, 2540, -1, 2524, 2539, 2538, -1, 2542, 2002, 2003, -1, 2542, 2003, 1910, -1, 2542, 1910, 2543, -1, 2542, 2540, 2002, -1, 2529, 2473, 2474, -1, 2529, 2474, 2541, -1, 2525, 2539, 2524, -1, 2525, 2541, 2539, -1, 2523, 2543, 2521, -1, 2523, 2542, 2543, -1, 2523, 2524, 2540, -1, 2523, 2540, 2542, -1, 2527, 2472, 2473, -1, 2527, 2473, 2529, -1, 2530, 2529, 2541, -1, 2530, 2541, 2525, -1, 2513, 1645, 1657, -1, 2513, 1657, 2544, -1, 2518, 2544, 2545, -1, 2518, 2513, 2544, -1, 2479, 2545, 2546, -1, 2479, 2518, 2545, -1, 2480, 2546, 2547, -1, 2480, 2479, 2546, -1, 2496, 2547, 2548, -1, 2496, 2480, 2547, -1, 2499, 2548, 2549, -1, 2499, 2496, 2548, -1, 1925, 2549, 1926, -1, 1925, 2499, 2549, -1, 1780, 1781, 2537, -1, 2550, 2537, 2535, -1, 2550, 1780, 2537, -1, 2551, 2535, 2532, -1, 2551, 2550, 2535, -1, 2552, 2532, 2522, -1, 2552, 2551, 2532, -1, 2553, 2522, 2521, -1, 2553, 2552, 2522, -1, 2554, 2521, 2543, -1, 2554, 2553, 2521, -1, 2555, 2543, 1910, -1, 2555, 2554, 2543, -1, 1908, 2555, 1910, -1, 2556, 2557, 2558, -1, 2559, 2560, 2561, -1, 2556, 2562, 2563, -1, 2556, 2564, 2557, -1, 2556, 2563, 2564, -1, 2559, 2565, 2560, -1, 2566, 2029, 2030, -1, 2567, 2561, 2568, -1, 1663, 2544, 1657, -1, 2566, 2030, 2569, -1, 2566, 2570, 2571, -1, 2566, 2569, 2570, -1, 2567, 2568, 2572, -1, 2573, 2558, 2574, -1, 2575, 1665, 1666, -1, 2573, 2562, 2556, -1, 2573, 2556, 2558, -1, 2573, 2571, 2562, -1, 2575, 2572, 1665, -1, 2576, 2574, 2577, -1, 2578, 2548, 2547, -1, 2576, 2028, 2029, -1, 2576, 2029, 2566, -1, 2576, 2566, 2571, -1, 2576, 2571, 2573, -1, 2576, 2573, 2574, -1, 2576, 2577, 2028, -1, 2578, 2547, 2579, -1, 2580, 2565, 2559, -1, 2580, 2579, 2565, -1, 2581, 2559, 2561, -1, 2581, 2561, 2567, -1, 2582, 2572, 2575, -1, 2582, 2567, 2572, -1, 2583, 2549, 2548, -1, 2583, 1926, 2549, -1, 2583, 2033, 1926, -1, 2583, 2548, 2578, -1, 2584, 1666, 1667, -1, 2584, 2575, 1666, -1, 2585, 2578, 2579, -1, 2585, 2579, 2580, -1, 2586, 2559, 2581, -1, 2586, 2580, 2559, -1, 2587, 2581, 2567, -1, 2587, 2567, 2582, -1, 2588, 2582, 2575, -1, 2588, 2575, 2584, -1, 2589, 2032, 2033, -1, 2589, 2578, 2585, -1, 2589, 2033, 2583, -1, 2589, 2583, 2578, -1, 2590, 1667, 1669, -1, 2590, 1669, 2591, -1, 2590, 2584, 1667, -1, 2592, 2585, 2580, -1, 2592, 2580, 2586, -1, 2593, 2586, 2581, -1, 1915, 2028, 2577, -1, 2593, 2581, 2587, -1, 2563, 2582, 2588, -1, 2594, 1663, 1662, -1, 2563, 2587, 2582, -1, 2594, 2544, 1663, -1, 2560, 2545, 2544, -1, 2595, 2584, 2590, -1, 2595, 2588, 2584, -1, 2595, 2591, 2596, -1, 2595, 2590, 2591, -1, 2560, 2544, 2594, -1, 2597, 2589, 2585, -1, 2568, 1662, 1664, -1, 2597, 2031, 2032, -1, 2597, 2585, 2592, -1, 2568, 2594, 1662, -1, 2597, 2032, 2589, -1, 2570, 2592, 2586, -1, 2565, 2546, 2545, -1, 2570, 2586, 2593, -1, 2565, 2545, 2560, -1, 2562, 2587, 2563, -1, 2562, 2593, 2587, -1, 2561, 2594, 2568, -1, 2564, 2596, 2557, -1, 2564, 2588, 2595, -1, 2561, 2560, 2594, -1, 2572, 1664, 1665, -1, 2564, 2595, 2596, -1, 2564, 2563, 2588, -1, 2569, 2592, 2570, -1, 2569, 2030, 2031, -1, 2569, 2031, 2597, -1, 2572, 2568, 1664, -1, 2569, 2597, 2592, -1, 2579, 2547, 2546, -1, 2579, 2546, 2565, -1, 2571, 2570, 2593, -1, 2571, 2593, 2562, -1, 2598, 2599, 2600, -1, 2598, 2601, 2602, -1, 2598, 2603, 2599, -1, 2598, 2602, 2603, -1, 2604, 2550, 2551, -1, 2604, 2551, 2605, -1, 2604, 1708, 2550, -1, 2606, 2607, 2608, -1, 2606, 2605, 2607, -1, 2609, 2600, 2610, -1, 2609, 2598, 2600, -1, 2609, 2601, 2598, -1, 2609, 2608, 2601, -1, 2611, 1707, 1708, -1, 2611, 1708, 2604, -1, 2611, 2604, 2605, -1, 2611, 2605, 2606, -1, 2612, 2610, 2613, -1, 2612, 2606, 2608, -1, 2612, 2609, 2610, -1, 2612, 2608, 2609, -1, 2614, 1706, 1707, -1, 2614, 1707, 2611, -1, 2614, 2612, 2613, -1, 2614, 2613, 1706, -1, 2614, 2606, 2612, -1, 2614, 2611, 2606, -1, 2615, 2006, 1912, -1, 1708, 1780, 2550, -1, 1701, 1706, 2613, -1, 2616, 2555, 1908, -1, 2616, 1908, 2004, -1, 2617, 2554, 2555, -1, 2617, 2555, 2616, -1, 2618, 2004, 2005, -1, 2618, 2616, 2004, -1, 2619, 2553, 2554, -1, 2619, 2554, 2617, -1, 2602, 2616, 2618, -1, 2602, 2617, 2616, -1, 2620, 2005, 2006, -1, 2620, 2615, 2621, -1, 2620, 2006, 2615, -1, 2620, 2618, 2005, -1, 2607, 2552, 2553, -1, 2607, 2553, 2619, -1, 2601, 2619, 2617, -1, 2601, 2617, 2602, -1, 2603, 2621, 2599, -1, 2603, 2618, 2620, -1, 2603, 2620, 2621, -1, 2603, 2602, 2618, -1, 2605, 2551, 2552, -1, 2605, 2552, 2607, -1, 2608, 2607, 2619, -1, 2608, 2619, 2601, -1, 2591, 1669, 1686, -1, 2591, 1686, 2622, -1, 2596, 2622, 2623, -1, 2596, 2591, 2622, -1, 2557, 2623, 2624, -1, 2557, 2596, 2623, -1, 2558, 2624, 2625, -1, 2558, 2557, 2624, -1, 2574, 2625, 2626, -1, 2574, 2558, 2625, -1, 2577, 2626, 2627, -1, 2577, 2574, 2626, -1, 1915, 2627, 1918, -1, 1915, 2577, 2627, -1, 2628, 1701, 2613, -1, 2628, 1697, 1701, -1, 2629, 2613, 2610, -1, 2629, 2628, 2613, -1, 2630, 2610, 2600, -1, 2630, 2629, 2610, -1, 2631, 2600, 2599, -1, 2631, 2630, 2600, -1, 2632, 2599, 2621, -1, 2632, 2631, 2599, -1, 2633, 2621, 2615, -1, 2633, 2632, 2621, -1, 1914, 2615, 1912, -1, 1914, 2633, 2615, -1, 2634, 2635, 2636, -1, 2634, 2637, 2635, -1, 2638, 2626, 2625, -1, 2638, 2639, 2626, -1, 2638, 2640, 2639, -1, 2638, 2636, 2640, -1, 2641, 1695, 1696, -1, 2641, 2628, 2629, -1, 2641, 2629, 2642, -1, 2641, 1696, 2628, -1, 2643, 2642, 2637, -1, 2643, 2637, 2634, -1, 2644, 2625, 2624, -1, 2644, 2638, 2625, -1, 2644, 2634, 2636, -1, 2644, 2636, 2638, -1, 2645, 1695, 2641, -1, 2645, 2642, 2643, -1, 2645, 2641, 2642, -1, 2646, 2624, 2623, -1, 2646, 2644, 2624, -1, 2646, 2643, 2634, -1, 2646, 2634, 2644, -1, 2647, 2622, 1686, -1, 2647, 2623, 2622, -1, 2647, 1686, 1693, -1, 2647, 1693, 1695, -1, 2627, 2009, 1918, -1, 2647, 1695, 2645, -1, 2647, 2646, 2623, -1, 2647, 2645, 2643, -1, 2647, 2643, 2646, -1, 1696, 1697, 2628, -1, 2648, 2633, 1914, -1, 2648, 1914, 2007, -1, 2649, 2632, 2633, -1, 2649, 2633, 2648, -1, 2650, 2007, 2008, -1, 2650, 2648, 2007, -1, 2635, 2631, 2632, -1, 2635, 2632, 2649, -1, 2640, 2649, 2648, -1, 2640, 2648, 2650, -1, 2651, 2008, 2009, -1, 2651, 2650, 2008, -1, 2651, 2009, 2627, -1, 2637, 2630, 2631, -1, 2637, 2631, 2635, -1, 2636, 2649, 2640, -1, 2636, 2635, 2649, -1, 2639, 2627, 2626, -1, 2639, 2640, 2650, -1, 2639, 2651, 2627, -1, 2639, 2650, 2651, -1, 2642, 2629, 2630, -1, 2642, 2630, 2637, -1, 1759, 1767, 2652, -1, 1759, 2652, 2653, -1, 1756, 2653, 2654, -1, 1756, 1759, 2653, -1, 1755, 2654, 2655, -1, 1755, 1756, 2654, -1, 1754, 2655, 2656, -1, 1754, 1755, 2655, -1, 1753, 2656, 2657, -1, 1753, 1754, 2656, -1, 1752, 2657, 2658, -1, 1752, 1753, 2657, -1, 1747, 2658, 2659, -1, 1747, 1752, 2658, -1, 1725, 2659, 2660, -1, 1747, 2659, 1725, -1, 1724, 1725, 2660, -1, 1724, 2660, 2661, -1, 1722, 2661, 2662, -1, 1722, 1724, 2661, -1, 1720, 2662, 2663, -1, 1720, 1722, 2662, -1, 1717, 2663, 2664, -1, 1717, 1720, 2663, -1, 1717, 2665, 1718, -1, 2664, 2665, 1717, -1, 1719, 1718, 2665, -1, 1719, 2665, 2666, -1, 1721, 2666, 2667, -1, 1721, 1719, 2666, -1, 1723, 2667, 2668, -1, 1723, 1721, 2667, -1, 1726, 2668, 2669, -1, 1726, 1723, 2668, -1, 1726, 2670, 1729, -1, 2669, 2670, 1726, -1, 1730, 1729, 2670, -1, 1730, 2670, 2671, -1, 1731, 2671, 2672, -1, 1731, 1730, 2671, -1, 1732, 2672, 2673, -1, 1732, 1731, 2672, -1, 1733, 2673, 2674, -1, 1733, 1732, 2673, -1, 1733, 2675, 1741, -1, 2674, 2675, 1733, -1, 1741, 2675, 2676, -1, 1742, 2676, 2677, -1, 1742, 1741, 2676, -1, 1743, 2677, 2678, -1, 1743, 1742, 2677, -1, 1744, 2678, 2679, -1, 1744, 1743, 2678, -1, 1745, 1744, 2679, -1, 2679, 1770, 1745, -1, 2680, 1770, 2679, -1, 1770, 2680, 2681, -1, 1771, 2681, 2682, -1, 1771, 1770, 2681, -1, 1772, 2682, 2683, -1, 1772, 1771, 2682, -1, 1773, 2683, 2684, -1, 1773, 1772, 2683, -1, 1762, 1773, 2684, -1, 1762, 2685, 1760, -1, 2684, 2685, 1762, -1, 1760, 2685, 2686, -1, 1763, 2686, 2687, -1, 1763, 1760, 2686, -1, 1764, 2687, 2688, -1, 1764, 1763, 2687, -1, 1765, 2688, 2689, -1, 1765, 1764, 2688, -1, 1766, 1765, 2689, -1, 2689, 1767, 1766, -1, 2652, 1767, 2689, -1, 2690, 2691, 2692, -1, 1623, 2693, 2690, -1, 2694, 2695, 2696, -1, 2691, 2693, 2697, -1, 2690, 2693, 2691, -1, 2698, 2699, 2700, -1, 2700, 2699, 2701, -1, 2701, 2699, 2702, -1, 1623, 2699, 2693, -1, 2702, 2699, 1623, -1, 2694, 2703, 2695, -1, 2694, 2704, 2703, -1, 2705, 2706, 2707, -1, 2707, 2706, 2708, -1, 2708, 2706, 2709, -1, 2709, 1620, 2694, -1, 2706, 1620, 2709, -1, 2694, 1620, 2704, -1, 2710, 2711, 2712, -1, 2710, 2713, 2711, -1, 2710, 2714, 2713, -1, 2704, 1617, 2710, -1, 1620, 1617, 2704, -1, 2710, 1617, 2714, -1, 1617, 2715, 2714, -1, 2715, 2716, 2717, -1, 2716, 2718, 2719, -1, 1617, 2718, 2715, -1, 2715, 2718, 2716, -1, 2720, 2721, 2722, -1, 2723, 1621, 2706, -1, 2706, 1621, 1620, -1, 2724, 2725, 2726, -1, 2726, 2725, 2727, -1, 2727, 2725, 2721, -1, 2722, 2725, 2723, -1, 2723, 2725, 1621, -1, 2721, 2725, 2722, -1, 1617, 1623, 2718, -1, 1621, 2702, 1623, -1, 2725, 2702, 1621, -1, 1623, 2690, 2718, -1, 2728, 2729, 2730, -1, 2728, 2730, 2731, -1, 2732, 2731, 2733, -1, 2732, 2728, 2731, -1, 2734, 2733, 2735, -1, 2734, 2732, 2733, -1, 2736, 2735, 2737, -1, 2736, 2734, 2735, -1, 2738, 2737, 2739, -1, 2738, 2736, 2737, -1, 2740, 2739, 2741, -1, 2740, 2738, 2739, -1, 2742, 2741, 2743, -1, 2742, 2740, 2741, -1, 2744, 2745, 2746, -1, 2747, 2746, 2748, -1, 2747, 2744, 2746, -1, 2749, 2748, 2750, -1, 2749, 2747, 2748, -1, 2751, 2750, 2752, -1, 2751, 2749, 2750, -1, 2753, 2751, 2752, -1, 2754, 2755, 2756, -1, 2757, 2756, 2758, -1, 2757, 2754, 2756, -1, 2759, 2758, 2760, -1, 2759, 2757, 2758, -1, 2761, 2760, 2762, -1, 2761, 2759, 2760, -1, 2763, 2761, 2762, -1, 2764, 2765, 2766, -1, 2767, 2766, 2768, -1, 2767, 2764, 2766, -1, 2769, 2767, 2768, -1, 2770, 2768, 2771, -1, 2770, 2769, 2768, -1, 2772, 2771, 2773, -1, 2772, 2770, 2771, -1, 2774, 2775, 2776, -1, 2774, 2777, 2778, -1, 2774, 2776, 2777, -1, 2779, 2774, 2778, -1, 2780, 2778, 2781, -1, 2780, 2779, 2778, -1, 2782, 2781, 2783, -1, 2782, 2780, 2781, -1, 2773, 2782, 2783, -1, 2773, 2783, 2772, -1, 2765, 2764, 2755, -1, 2765, 2755, 2754, -1, 2784, 2785, 2786, -1, 2787, 2786, 2788, -1, 2787, 2784, 2786, -1, 2789, 2788, 2790, -1, 2789, 2787, 2788, -1, 2791, 2790, 2792, -1, 2791, 2789, 2790, -1, 2793, 2791, 2792, -1, 2793, 2763, 2762, -1, 2792, 2763, 2793, -1, 2794, 2795, 2796, -1, 2797, 2796, 2798, -1, 2797, 2794, 2796, -1, 2799, 2798, 2800, -1, 2799, 2797, 2798, -1, 2801, 2800, 2802, -1, 2801, 2799, 2800, -1, 2803, 2801, 2802, -1, 2795, 2785, 2784, -1, 2795, 2794, 2785, -1, 2752, 2803, 2802, -1, 2752, 2802, 2753, -1, 2730, 2745, 2744, -1, 2730, 2729, 2745, -1, 2776, 2775, 2743, -1, 2775, 2742, 2743, -1, 1678, 1679, 2804, -1, 1678, 2804, 2805, -1, 1677, 2805, 2806, -1, 1677, 1678, 2805, -1, 1676, 2806, 2807, -1, 1676, 1677, 2806, -1, 1675, 2807, 2808, -1, 1675, 1676, 2807, -1, 1654, 2808, 2809, -1, 1675, 2808, 1654, -1, 1653, 1654, 2809, -1, 1653, 2810, 2811, -1, 1653, 2809, 2810, -1, 1651, 2811, 2812, -1, 1651, 1653, 2811, -1, 1649, 1651, 2812, -1, 1647, 2812, 2813, -1, 1647, 1649, 2812, -1, 1647, 2814, 1646, -1, 2813, 2814, 1647, -1, 1648, 1646, 2814, -1, 1648, 2814, 2815, -1, 1650, 2815, 2816, -1, 1650, 1648, 2815, -1, 1652, 2816, 2817, -1, 1652, 1650, 2816, -1, 1655, 2817, 2818, -1, 1655, 1652, 2817, -1, 1656, 1655, 2819, -1, 1655, 2818, 2819, -1, 1658, 1656, 2819, -1, 1658, 2819, 2820, -1, 1659, 2820, 2821, -1, 1659, 1658, 2820, -1, 1660, 2821, 2822, -1, 1660, 1659, 2821, -1, 1661, 2822, 2823, -1, 1661, 1660, 2822, -1, 1661, 2824, 1668, -1, 2823, 2824, 1661, -1, 1668, 2824, 2825, -1, 1670, 2825, 2826, -1, 1670, 1668, 2825, -1, 1671, 2826, 2827, -1, 1671, 1670, 2826, -1, 1672, 2827, 2828, -1, 1672, 1671, 2827, -1, 1673, 1672, 2828, -1, 2828, 1694, 1673, -1, 2829, 1694, 2828, -1, 1694, 2829, 2830, -1, 1700, 2830, 2831, -1, 1700, 1694, 2830, -1, 1702, 2831, 2832, -1, 1702, 1700, 2831, -1, 1703, 2832, 2833, -1, 1703, 1702, 2832, -1, 1704, 2833, 2834, -1, 1704, 1703, 2833, -1, 1705, 2834, 2835, -1, 1705, 1704, 2834, -1, 1699, 2835, 2836, -1, 1699, 1705, 2835, -1, 1698, 1699, 2836, -1, 2836, 1690, 1698, -1, 2837, 1690, 2836, -1, 1689, 1690, 2837, -1, 1689, 2837, 2838, -1, 1691, 2838, 2839, -1, 1691, 1689, 2838, -1, 1692, 2839, 2840, -1, 1692, 1691, 2839, -1, 1688, 2840, 2841, -1, 1688, 1692, 2840, -1, 1688, 2804, 1679, -1, 2841, 2804, 1688, -1, 2842, 2843, 2844, -1, 2842, 2845, 2843, -1, 2846, 2847, 2842, -1, 2842, 2847, 2845, -1, 2848, 2849, 2850, -1, 2848, 2851, 2849, -1, 2848, 2852, 2851, -1, 2853, 2854, 2855, -1, 2855, 2854, 2856, -1, 2856, 2854, 2857, -1, 2857, 1628, 2848, -1, 2854, 1628, 2857, -1, 2848, 1628, 2852, -1, 1628, 2858, 2852, -1, 2858, 2859, 2860, -1, 2860, 2859, 2861, -1, 2858, 2862, 2859, -1, 1628, 1631, 2858, -1, 2858, 1631, 2862, -1, 1631, 2863, 2862, -1, 2863, 2864, 2865, -1, 2865, 2864, 2866, -1, 2866, 2864, 2867, -1, 1631, 2864, 2863, -1, 2868, 2869, 2870, -1, 2870, 2869, 2871, -1, 2869, 2872, 2871, -1, 2872, 1626, 2871, -1, 2871, 1626, 2854, -1, 2854, 1626, 1628, -1, 2872, 2873, 1626, -1, 2874, 2875, 2873, -1, 2875, 2876, 2873, -1, 2873, 2877, 1626, -1, 2876, 2877, 2873, -1, 2877, 1629, 1626, -1, 1631, 1629, 2864, -1, 1629, 2842, 2864, -1, 2877, 2878, 1629, -1, 1629, 2878, 2842, -1, 2878, 2879, 2842, -1, 2879, 2846, 2842, -1, 2880, 2881, 2882, -1, 2883, 2882, 2884, -1, 2883, 2880, 2882, -1, 2885, 2884, 2886, -1, 2885, 2883, 2884, -1, 2887, 2886, 2888, -1, 2887, 2885, 2886, -1, 2889, 2887, 2888, -1, 2890, 2891, 2892, -1, 2890, 2892, 2893, -1, 2894, 2893, 2895, -1, 2894, 2890, 2893, -1, 2896, 2895, 2897, -1, 2896, 2894, 2895, -1, 2898, 2897, 2899, -1, 2898, 2896, 2897, -1, 2900, 2901, 2902, -1, 2900, 2902, 2903, -1, 2904, 2903, 2905, -1, 2904, 2900, 2903, -1, 2906, 2905, 2907, -1, 2906, 2904, 2905, -1, 2908, 2907, 2909, -1, 2908, 2906, 2907, -1, 2910, 2911, 2912, -1, 2913, 2912, 2914, -1, 2913, 2910, 2912, -1, 2915, 2914, 2916, -1, 2915, 2913, 2914, -1, 2917, 2916, 2918, -1, 2917, 2915, 2916, -1, 2919, 2917, 2918, -1, 2920, 2921, 2922, -1, 2923, 2922, 2924, -1, 2923, 2920, 2922, -1, 2925, 2924, 2926, -1, 2925, 2923, 2924, -1, 2927, 2926, 2928, -1, 2927, 2925, 2926, -1, 2929, 2927, 2928, -1, 2929, 2919, 2918, -1, 2929, 2928, 2919, -1, 2930, 2931, 2932, -1, 2933, 2932, 2934, -1, 2933, 2930, 2932, -1, 2935, 2934, 2936, -1, 2935, 2933, 2934, -1, 2937, 2936, 2938, -1, 2937, 2935, 2936, -1, 2939, 2937, 2938, -1, 2921, 2920, 2931, -1, 2930, 2921, 2931, -1, 2938, 2909, 2939, -1, 2908, 2909, 2938, -1, 2892, 2902, 2901, -1, 2891, 2902, 2892, -1, 2940, 2941, 2942, -1, 2940, 2943, 2944, -1, 2940, 2942, 2943, -1, 2945, 2944, 2946, -1, 2945, 2940, 2944, -1, 2947, 2946, 2948, -1, 2947, 2945, 2946, -1, 2949, 2948, 2950, -1, 2949, 2947, 2948, -1, 2951, 2950, 2952, -1, 2951, 2949, 2950, -1, 2953, 2952, 2954, -1, 2953, 2951, 2952, -1, 2955, 2953, 2954, -1, 2941, 2898, 2899, -1, 2941, 2899, 2942, -1, 2889, 2955, 2954, -1, 2888, 2955, 2889, -1, 2911, 2910, 2880, -1, 2910, 2881, 2880, -1, 2929, 2918, 2818, -1, 2818, 2918, 2819, -1, 2912, 2911, 2823, -1, 2912, 2823, 2822, -1, 2912, 2822, 2821, -1, 2914, 2821, 2820, -1, 2914, 2912, 2821, -1, 2916, 2914, 2820, -1, 2918, 2820, 2819, -1, 2918, 2916, 2820, -1, 2929, 2818, 2817, -1, 2927, 2817, 2816, -1, 2927, 2929, 2817, -1, 2925, 2816, 2815, -1, 2925, 2927, 2816, -1, 2923, 2815, 2814, -1, 2923, 2925, 2815, -1, 2920, 2923, 2814, -1, 2911, 2880, 2823, -1, 2823, 2880, 2824, -1, 2813, 2931, 2814, -1, 2931, 2920, 2814, -1, 2889, 2828, 2827, -1, 2887, 2889, 2827, -1, 2885, 2827, 2826, -1, 2885, 2887, 2827, -1, 2883, 2826, 2825, -1, 2883, 2885, 2826, -1, 2880, 2825, 2824, -1, 2880, 2883, 2825, -1, 2932, 2931, 2813, -1, 2932, 2813, 2812, -1, 2934, 2812, 2811, -1, 2934, 2932, 2812, -1, 2936, 2811, 2810, -1, 2936, 2934, 2811, -1, 2938, 2810, 2809, -1, 2938, 2936, 2810, -1, 2889, 2954, 2828, -1, 2828, 2954, 2829, -1, 2908, 2809, 2808, -1, 2908, 2938, 2809, -1, 2943, 2942, 2836, -1, 2943, 2836, 2835, -1, 2943, 2835, 2834, -1, 2944, 2834, 2833, -1, 2944, 2943, 2834, -1, 2946, 2833, 2832, -1, 2946, 2944, 2833, -1, 2948, 2832, 2831, -1, 2948, 2946, 2832, -1, 2950, 2831, 2830, -1, 2950, 2948, 2831, -1, 2952, 2830, 2829, -1, 2952, 2950, 2830, -1, 2954, 2952, 2829, -1, 2906, 2908, 2808, -1, 2906, 2808, 2807, -1, 2904, 2807, 2806, -1, 2904, 2906, 2807, -1, 2900, 2806, 2805, -1, 2900, 2805, 2804, -1, 2900, 2904, 2806, -1, 2901, 2900, 2804, -1, 2942, 2899, 2836, -1, 2836, 2899, 2837, -1, 2841, 2901, 2804, -1, 2892, 2901, 2841, -1, 2893, 2892, 2841, -1, 2893, 2841, 2840, -1, 2895, 2840, 2839, -1, 2895, 2893, 2840, -1, 2897, 2839, 2838, -1, 2897, 2838, 2837, -1, 2897, 2895, 2839, -1, 2899, 2897, 2837, -1, 2669, 2784, 2670, -1, 2795, 2784, 2669, -1, 2791, 2793, 2674, -1, 2791, 2674, 2673, -1, 2791, 2673, 2672, -1, 2789, 2672, 2671, -1, 2789, 2791, 2672, -1, 2787, 2789, 2671, -1, 2784, 2671, 2670, -1, 2784, 2787, 2671, -1, 2796, 2795, 2669, -1, 2796, 2669, 2668, -1, 2796, 2668, 2667, -1, 2798, 2667, 2666, -1, 2798, 2796, 2667, -1, 2800, 2666, 2665, -1, 2800, 2798, 2666, -1, 2802, 2800, 2665, -1, 2793, 2762, 2675, -1, 2793, 2675, 2674, -1, 2753, 2802, 2665, -1, 2753, 2665, 2664, -1, 2755, 2679, 2678, -1, 2756, 2678, 2677, -1, 2756, 2755, 2678, -1, 2758, 2677, 2676, -1, 2758, 2756, 2677, -1, 2760, 2758, 2676, -1, 2762, 2676, 2675, -1, 2762, 2760, 2676, -1, 2751, 2753, 2664, -1, 2751, 2664, 2663, -1, 2749, 2663, 2662, -1, 2749, 2662, 2661, -1, 2749, 2751, 2663, -1, 2747, 2661, 2660, -1, 2747, 2749, 2661, -1, 2744, 2747, 2660, -1, 2755, 2764, 2680, -1, 2755, 2680, 2679, -1, 2730, 2744, 2660, -1, 2730, 2660, 2659, -1, 2772, 2684, 2683, -1, 2770, 2772, 2683, -1, 2769, 2683, 2682, -1, 2769, 2770, 2683, -1, 2767, 2682, 2681, -1, 2767, 2769, 2682, -1, 2764, 2681, 2680, -1, 2764, 2767, 2681, -1, 2731, 2730, 2659, -1, 2731, 2659, 2658, -1, 2733, 2658, 2657, -1, 2733, 2731, 2658, -1, 2735, 2657, 2656, -1, 2735, 2733, 2657, -1, 2737, 2656, 2655, -1, 2737, 2735, 2656, -1, 2739, 2655, 2654, -1, 2739, 2737, 2655, -1, 2741, 2654, 2653, -1, 2741, 2739, 2654, -1, 2743, 2653, 2652, -1, 2743, 2741, 2653, -1, 2783, 2685, 2684, -1, 2772, 2783, 2684, -1, 2689, 2743, 2652, -1, 2776, 2743, 2689, -1, 2776, 2689, 2688, -1, 2777, 2776, 2688, -1, 2778, 2688, 2687, -1, 2778, 2777, 2688, -1, 2781, 2687, 2686, -1, 2781, 2686, 2685, -1, 2781, 2778, 2687, -1, 2783, 2781, 2685, -1, 2873, 2872, 2891, -1, 2891, 2872, 2902, -1, 2903, 2902, 2872, -1, 2903, 2872, 2869, -1, 2905, 2869, 2868, -1, 2905, 2903, 2869, -1, 2907, 2868, 2870, -1, 2907, 2905, 2868, -1, 2909, 2870, 2871, -1, 2909, 2907, 2870, -1, 2898, 2877, 2876, -1, 2896, 2876, 2875, -1, 2896, 2898, 2876, -1, 2894, 2875, 2874, -1, 2894, 2896, 2875, -1, 2890, 2894, 2874, -1, 2891, 2874, 2873, -1, 2891, 2890, 2874, -1, 2871, 2854, 2909, -1, 2909, 2854, 2939, -1, 2898, 2941, 2878, -1, 2898, 2878, 2877, -1, 2939, 2854, 2853, -1, 2937, 2853, 2855, -1, 2937, 2939, 2853, -1, 2935, 2855, 2856, -1, 2935, 2937, 2855, -1, 2933, 2856, 2857, -1, 2933, 2935, 2856, -1, 2930, 2933, 2857, -1, 2955, 2842, 2844, -1, 2953, 2844, 2843, -1, 2953, 2955, 2844, -1, 2951, 2843, 2845, -1, 2951, 2953, 2843, -1, 2949, 2845, 2847, -1, 2949, 2951, 2845, -1, 2947, 2847, 2846, -1, 2947, 2949, 2847, -1, 2945, 2846, 2879, -1, 2945, 2947, 2846, -1, 2940, 2945, 2879, -1, 2941, 2879, 2878, -1, 2941, 2940, 2879, -1, 2921, 2930, 2857, -1, 2921, 2857, 2848, -1, 2888, 2842, 2955, -1, 2864, 2842, 2888, -1, 2921, 2848, 2850, -1, 2922, 2850, 2849, -1, 2922, 2921, 2850, -1, 2924, 2849, 2851, -1, 2924, 2922, 2849, -1, 2926, 2851, 2852, -1, 2926, 2924, 2851, -1, 2928, 2926, 2852, -1, 2881, 2863, 2865, -1, 2882, 2881, 2865, -1, 2884, 2865, 2866, -1, 2884, 2882, 2865, -1, 2886, 2866, 2867, -1, 2886, 2884, 2866, -1, 2888, 2867, 2864, -1, 2888, 2886, 2867, -1, 2919, 2928, 2852, -1, 2919, 2852, 2858, -1, 2910, 2863, 2881, -1, 2862, 2863, 2910, -1, 2919, 2858, 2860, -1, 2917, 2919, 2860, -1, 2915, 2860, 2861, -1, 2915, 2917, 2860, -1, 2913, 2861, 2859, -1, 2913, 2859, 2862, -1, 2913, 2915, 2861, -1, 2910, 2913, 2862, -1, 2714, 2715, 2792, -1, 2792, 2715, 2763, -1, 2763, 2715, 2717, -1, 2761, 2763, 2717, -1, 2759, 2717, 2716, -1, 2759, 2761, 2717, -1, 2757, 2716, 2719, -1, 2757, 2759, 2716, -1, 2754, 2719, 2718, -1, 2754, 2757, 2719, -1, 2786, 2785, 2710, -1, 2786, 2710, 2712, -1, 2786, 2712, 2711, -1, 2788, 2711, 2713, -1, 2788, 2786, 2711, -1, 2790, 2713, 2714, -1, 2790, 2788, 2713, -1, 2792, 2790, 2714, -1, 2765, 2754, 2718, -1, 2765, 2718, 2690, -1, 2704, 2785, 2794, -1, 2704, 2710, 2785, -1, 2765, 2690, 2692, -1, 2766, 2765, 2692, -1, 2768, 2692, 2691, -1, 2768, 2766, 2692, -1, 2771, 2691, 2697, -1, 2771, 2768, 2691, -1, 2773, 2697, 2693, -1, 2773, 2771, 2697, -1, 2801, 2803, 2694, -1, 2801, 2694, 2696, -1, 2799, 2696, 2695, -1, 2799, 2801, 2696, -1, 2797, 2695, 2703, -1, 2797, 2703, 2704, -1, 2797, 2799, 2695, -1, 2794, 2797, 2704, -1, 2782, 2773, 2693, -1, 2782, 2693, 2699, -1, 2803, 2752, 2709, -1, 2803, 2709, 2694, -1, 2780, 2782, 2699, -1, 2780, 2699, 2698, -1, 2779, 2698, 2700, -1, 2779, 2780, 2698, -1, 2774, 2700, 2701, -1, 2774, 2779, 2700, -1, 2775, 2701, 2702, -1, 2775, 2774, 2701, -1, 2746, 2745, 2706, -1, 2746, 2706, 2705, -1, 2746, 2705, 2707, -1, 2748, 2707, 2708, -1, 2748, 2746, 2707, -1, 2750, 2708, 2709, -1, 2750, 2748, 2708, -1, 2752, 2750, 2709, -1, 2702, 2742, 2775, -1, 2702, 2725, 2742, -1, 2745, 2729, 2723, -1, 2745, 2723, 2706, -1, 2740, 2742, 2725, -1, 2740, 2725, 2724, -1, 2740, 2724, 2726, -1, 2738, 2726, 2727, -1, 2738, 2740, 2726, -1, 2736, 2727, 2721, -1, 2736, 2738, 2727, -1, 2734, 2721, 2720, -1, 2734, 2736, 2721, -1, 2732, 2720, 2722, -1, 2732, 2734, 2720, -1, 2728, 2722, 2723, -1, 2728, 2732, 2722, -1, 2729, 2728, 2723, -1, 1964, 2956, 1965, -1, 1964, 2957, 2956, -1, 1962, 2956, 2958, -1, 1965, 2956, 1962, -1, 2958, 1963, 1962, -1, 2959, 1963, 2958, -1, 2959, 1964, 1963, -1, 2957, 1964, 2959, -1, 2959, 1632, 1625, -1, 2959, 2958, 1632, -1, 1627, 2957, 1625, -1, 1625, 2957, 2959, -1, 2958, 2956, 1632, -1, 2957, 1630, 2956, -1, 1627, 1630, 2957, -1, 2956, 1630, 1632, -1, 1634, 1637, 2960, -1, 1637, 2961, 2960, -1, 2960, 1633, 1634, -1, 2962, 1633, 2960, -1, 2962, 1635, 1633, -1, 2963, 1635, 2962, -1, 1635, 2961, 1637, -1, 1635, 2963, 2961, -1, 2962, 1619, 1618, -1, 2962, 2960, 1619, -1, 1618, 1622, 2962, -1, 1622, 2963, 2962, -1, 2961, 1624, 2960, -1, 2963, 1624, 2961, -1, 2960, 1624, 1619, -1, 1622, 1624, 2963, -1, 1809, 1982, 1804, -1, 1980, 1982, 1809, -1, 1983, 1799, 1801, -1, 1983, 1985, 1799, -1, 1612, 1832, 1791, -1, 1612, 2964, 1832, -1, 1613, 1615, 1611, -1, 1951, 2965, 1615, -1, 2965, 2966, 1615, -1, 2966, 2967, 1615, -1, 2967, 2968, 1615, -1, 2968, 2969, 1615, -1, 1615, 2970, 1611, -1, 2969, 2970, 1615, -1, 2970, 2964, 1611, -1, 2964, 1612, 1611, -1, 1834, 1793, 1606, -1, 2971, 1793, 1834, -1, 1961, 1822, 1794, -1, 2972, 1959, 1961, -1, 2973, 2972, 1961, -1, 2974, 2973, 1961, -1, 2975, 2974, 1961, -1, 2976, 2975, 1961, -1, 2977, 1961, 1794, -1, 2977, 2976, 1961, -1, 2971, 2977, 1794, -1, 1793, 2971, 1794, -1, 2115, 1983, 2110, -1, 2115, 1982, 1983, -1, 1605, 1952, 1979, -1, 1604, 1952, 1605, -1, 1990, 1957, 1789, -1, 1790, 1990, 1789, -1, 2978, 2979, 2980, -1, 2978, 2981, 2979, -1, 2982, 2981, 2978, -1, 2982, 2983, 2981, -1, 2984, 2985, 2983, -1, 2984, 2983, 2982, -1, 2984, 2129, 2985, -1, 2986, 2127, 2129, -1, 2986, 2129, 2984, -1, 2986, 2984, 2127, -1, 2987, 1967, 1978, -1, 2987, 2980, 1967, -1, 2131, 1844, 2988, -1, 2989, 2978, 2980, -1, 2989, 2980, 2987, -1, 2990, 2982, 2978, -1, 2990, 2978, 2989, -1, 2991, 2984, 2982, -1, 2991, 2127, 2984, -1, 2991, 2982, 2990, -1, 2992, 2125, 2127, -1, 2992, 2127, 2991, -1, 2992, 2991, 2125, -1, 2993, 1978, 1975, -1, 2993, 1975, 1971, -1, 2993, 2987, 1978, -1, 2994, 2993, 1971, -1, 2994, 2989, 2987, -1, 2994, 2987, 2993, -1, 2995, 2989, 2994, -1, 2995, 2990, 2989, -1, 2996, 2990, 2995, -1, 2996, 2125, 2991, -1, 2996, 2991, 2990, -1, 2997, 2125, 2996, -1, 2998, 2123, 2125, -1, 2998, 2125, 2997, -1, 2999, 1971, 1970, -1, 3000, 1971, 2999, -1, 3000, 2994, 1971, -1, 3000, 2999, 1970, -1, 3001, 2994, 3000, -1, 3001, 3000, 1970, -1, 3001, 2995, 2994, -1, 3002, 3001, 1970, -1, 3002, 2995, 3001, -1, 3002, 2996, 2995, -1, 3003, 2997, 2996, -1, 3003, 2996, 3002, -1, 3004, 2121, 2123, -1, 3004, 2123, 2998, -1, 3004, 2998, 2997, -1, 3004, 2997, 3003, -1, 3005, 1970, 1972, -1, 3006, 3007, 3008, -1, 3006, 1970, 3005, -1, 3009, 1972, 1973, -1, 3009, 3010, 3011, -1, 3009, 1973, 3010, -1, 3009, 3005, 1972, -1, 3012, 3008, 3013, -1, 3012, 3006, 3008, -1, 3012, 1970, 3006, -1, 3014, 3011, 3007, -1, 3014, 3009, 3011, -1, 3014, 3006, 3005, -1, 3014, 3005, 3009, -1, 3014, 3007, 3006, -1, 3015, 3013, 3016, -1, 3015, 3002, 1970, -1, 2979, 3017, 1966, -1, 2979, 1966, 1968, -1, 3015, 1970, 3012, -1, 2979, 1968, 1967, -1, 3015, 3012, 3013, -1, 3018, 3002, 3015, -1, 3018, 3016, 3019, -1, 3018, 3003, 3002, -1, 3018, 3015, 3016, -1, 2981, 3017, 2979, -1, 3020, 3021, 2121, -1, 3020, 3019, 3021, -1, 2983, 3022, 3017, -1, 3020, 2121, 3004, -1, 3020, 3004, 3003, -1, 2983, 3017, 2981, -1, 3020, 3018, 3019, -1, 3020, 3003, 3018, -1, 2985, 2988, 3022, -1, 2985, 2131, 2988, -1, 2985, 3022, 2983, -1, 3023, 2131, 2985, -1, 3023, 2985, 2129, -1, 3024, 2129, 2131, -1, 3024, 3023, 2129, -1, 3024, 2131, 3023, -1, 2980, 2979, 1967, -1, 2988, 1844, 1864, -1, 2988, 1864, 3025, -1, 3022, 3025, 3026, -1, 3022, 2988, 3025, -1, 3017, 3026, 3027, -1, 3017, 3022, 3026, -1, 1966, 3027, 1984, -1, 1966, 3017, 3027, -1, 3028, 3029, 3030, -1, 3031, 1992, 1988, -1, 3031, 3032, 1992, -1, 3033, 3034, 3032, -1, 3033, 3032, 3031, -1, 3035, 3034, 3033, -1, 3035, 2171, 3036, -1, 3035, 3036, 3034, -1, 3037, 2173, 2171, -1, 3037, 3035, 2173, -1, 3037, 2171, 3035, -1, 3038, 1988, 1986, -1, 3038, 3031, 1988, -1, 3039, 3033, 3031, -1, 3039, 3031, 3038, -1, 3040, 2173, 3035, -1, 3040, 3035, 3033, -1, 3040, 3033, 3039, -1, 3041, 2174, 2173, -1, 3041, 2173, 3040, -1, 3041, 3040, 2174, -1, 3042, 1986, 1987, -1, 3042, 3038, 1986, -1, 3043, 3038, 3042, -1, 3043, 3042, 1987, -1, 3043, 3039, 3038, -1, 3044, 3043, 1987, -1, 3044, 3039, 3043, -1, 3044, 1987, 2176, -1, 3044, 2174, 3040, -1, 3044, 3040, 3039, -1, 3045, 3044, 2176, -1, 3045, 2174, 3044, -1, 3045, 2176, 2174, -1, 3027, 1987, 1984, -1, 3026, 2176, 1987, -1, 3026, 1987, 3027, -1, 3025, 2176, 3026, -1, 1864, 2176, 3025, -1, 3046, 3047, 1997, -1, 3046, 3048, 3047, -1, 3049, 1997, 1994, -1, 3049, 3046, 1997, -1, 3050, 3051, 3048, -1, 3050, 3046, 3049, -1, 3050, 3048, 3046, -1, 3052, 3053, 3051, -1, 3052, 3051, 3050, -1, 3030, 3054, 3053, -1, 3030, 3053, 3052, -1, 3029, 3055, 3054, -1, 3029, 2167, 3055, -1, 3029, 3054, 3030, -1, 3032, 1994, 1992, -1, 3032, 3049, 1994, -1, 3034, 3050, 3049, -1, 3034, 3049, 3032, -1, 3036, 3052, 3050, -1, 3036, 3050, 3034, -1, 3056, 3036, 2171, -1, 3056, 3030, 3052, -1, 3056, 3052, 3036, -1, 3028, 2171, 2169, -1, 3028, 2169, 2167, -1, 3028, 3030, 3056, -1, 3028, 3056, 2171, -1, 3028, 2167, 3029, -1, 2190, 1895, 2166, -1, 3057, 2177, 1870, -1, 3058, 2177, 3057, -1, 3059, 2177, 3058, -1, 1890, 2178, 3060, -1, 3061, 2190, 2166, -1, 3062, 3061, 2188, -1, 3062, 2190, 3061, -1, 3063, 2188, 2190, -1, 3063, 3062, 2188, -1, 3063, 2190, 3062, -1, 3064, 2166, 2168, -1, 3064, 3061, 2166, -1, 3064, 2188, 3061, -1, 3065, 2188, 3064, -1, 3065, 3064, 2168, -1, 3066, 2186, 2188, -1, 3066, 2188, 3065, -1, 3067, 2168, 2170, -1, 3067, 3065, 2168, -1, 3068, 2182, 2184, -1, 3068, 2184, 2186, -1, 3068, 2186, 3066, -1, 3068, 3066, 3065, -1, 3068, 3065, 3067, -1, 3069, 2170, 2172, -1, 3069, 3067, 2170, -1, 3070, 3068, 3067, -1, 3070, 2182, 3068, -1, 3070, 3067, 3069, -1, 3071, 2172, 2175, -1, 3071, 3069, 2172, -1, 3072, 2178, 2180, -1, 3072, 2180, 2182, -1, 3072, 3070, 3069, -1, 3072, 2182, 3070, -1, 3072, 3069, 3071, -1, 3073, 2175, 2177, -1, 3074, 3059, 3075, -1, 3074, 3071, 2175, -1, 3074, 2175, 3073, -1, 3074, 2177, 3059, -1, 3074, 3073, 2177, -1, 3076, 3075, 3060, -1, 3076, 3071, 3074, -1, 3076, 3060, 2178, -1, 3076, 2178, 3072, -1, 3076, 3072, 3071, -1, 3076, 3074, 3075, -1, 3057, 1870, 1862, -1, 3057, 1862, 3077, -1, 3058, 3077, 3078, -1, 3058, 3057, 3077, -1, 3059, 3078, 3079, -1, 3059, 3058, 3078, -1, 3075, 3079, 3080, -1, 3075, 3059, 3079, -1, 3060, 3080, 3081, -1, 3060, 3075, 3080, -1, 1890, 3081, 1891, -1, 1890, 3060, 3081, -1, 3082, 3083, 3084, -1, 3082, 3084, 3085, -1, 3086, 3087, 3088, -1, 3086, 3089, 3087, -1, 3086, 3085, 3090, -1, 3086, 3090, 3089, -1, 3091, 3092, 3083, -1, 3091, 3083, 3082, -1, 1861, 3077, 1862, -1, 3093, 3088, 3094, -1, 3093, 3086, 3088, -1, 3093, 3082, 3085, -1, 3093, 3085, 3086, -1, 3095, 2070, 2072, -1, 3095, 3092, 3091, -1, 3095, 2072, 3096, -1, 3095, 3096, 3092, -1, 3097, 3094, 3098, -1, 3097, 3093, 3094, -1, 3097, 3091, 3082, -1, 2076, 3081, 3080, -1, 3097, 3082, 3093, -1, 2076, 1891, 3081, -1, 3099, 3098, 1948, -1, 3099, 1948, 2070, -1, 3099, 3095, 3091, -1, 3099, 2070, 3095, -1, 3099, 3097, 3098, -1, 3099, 3091, 3097, -1, 3100, 1861, 1860, -1, 3100, 3077, 1861, -1, 3101, 3078, 3077, -1, 3101, 3077, 3100, -1, 3102, 3079, 3078, -1, 3102, 3078, 3101, -1, 3103, 3080, 3079, -1, 3103, 2076, 3080, -1, 3103, 3079, 3102, -1, 3104, 3100, 1860, -1, 3105, 2074, 2076, -1, 3105, 2076, 3103, -1, 3084, 3100, 3104, -1, 3084, 3101, 3100, -1, 3083, 3102, 3101, -1, 3083, 3101, 3084, -1, 3092, 3103, 3102, -1, 3092, 3102, 3083, -1, 3090, 1860, 1859, -1, 3090, 3104, 1860, -1, 3096, 2072, 2074, -1, 3096, 3103, 3092, -1, 3096, 3105, 3103, -1, 3096, 2074, 3105, -1, 3085, 3084, 3104, -1, 3085, 3104, 3090, -1, 3089, 1859, 1858, -1, 3089, 1858, 1857, -1, 3089, 1857, 3087, -1, 3089, 3090, 1859, -1, 3106, 1948, 3098, -1, 3106, 1949, 1948, -1, 3107, 3098, 3094, -1, 3107, 3106, 3098, -1, 3108, 3094, 3088, -1, 3108, 3107, 3094, -1, 3109, 3088, 3087, -1, 3109, 3108, 3088, -1, 1863, 3087, 1857, -1, 1863, 3109, 3087, -1, 1868, 1869, 3110, -1, 3106, 2099, 1949, -1, 3107, 2099, 3106, -1, 3108, 2099, 3107, -1, 3111, 3112, 1874, -1, 3111, 1874, 2095, -1, 3111, 2095, 2096, -1, 3113, 3114, 3112, -1, 3113, 3112, 3111, -1, 3115, 3110, 3114, -1, 3115, 3114, 3113, -1, 3116, 1867, 1868, -1, 3116, 1868, 3110, -1, 3116, 3115, 1867, -1, 3116, 3110, 3115, -1, 3117, 2096, 2097, -1, 3117, 3111, 2096, -1, 3118, 3113, 3111, -1, 3118, 3111, 3117, -1, 3119, 3115, 3113, -1, 3119, 3113, 3118, -1, 3119, 1867, 3115, -1, 3120, 1866, 1867, -1, 3120, 1867, 3119, -1, 3121, 2097, 2098, -1, 3121, 3117, 2097, -1, 3122, 3118, 3117, -1, 3122, 3117, 3121, -1, 3123, 3119, 3118, -1, 3123, 3118, 3122, -1, 3124, 1865, 1866, -1, 3124, 3120, 3119, -1, 3124, 3119, 3123, -1, 3124, 1866, 3120, -1, 3125, 2098, 2099, -1, 3125, 3121, 2098, -1, 3126, 3122, 3121, -1, 3126, 3125, 2099, -1, 3126, 3121, 3125, -1, 3127, 3108, 3109, -1, 3127, 3126, 2099, -1, 3127, 3122, 3126, -1, 3127, 2099, 3108, -1, 3127, 3123, 3122, -1, 3128, 3109, 1863, -1, 3128, 1863, 1865, -1, 3128, 1865, 3124, -1, 3128, 3127, 3109, -1, 3128, 3124, 3123, -1, 3128, 3123, 3127, -1, 1869, 1856, 3129, -1, 3110, 3129, 3130, -1, 3110, 1869, 3129, -1, 3114, 3130, 3131, -1, 3114, 3110, 3130, -1, 3112, 3131, 1872, -1, 3112, 3114, 3131, -1, 1874, 3112, 1872, -1, 3132, 3133, 3129, -1, 3132, 3134, 3133, -1, 2043, 3135, 1945, -1, 1852, 1851, 3136, -1, 1852, 3136, 3137, -1, 1852, 3137, 3138, -1, 3139, 3138, 3135, -1, 3139, 2043, 2041, -1, 3139, 3135, 2043, -1, 3140, 1852, 3138, -1, 3140, 3138, 3139, -1, 3141, 1852, 3140, -1, 3142, 1853, 1852, -1, 3142, 3141, 1853, -1, 3142, 1852, 3141, -1, 3143, 3139, 2041, -1, 3144, 3140, 3139, -1, 3144, 3139, 3143, -1, 3145, 3140, 3144, -1, 3145, 1853, 3141, -1, 3145, 3141, 3140, -1, 3146, 1854, 1853, -1, 3146, 1853, 3145, -1, 3147, 2041, 2039, -1, 3147, 3143, 2041, -1, 3148, 3144, 3143, -1, 3148, 3143, 3147, -1, 3134, 3145, 3144, -1, 3134, 3144, 3148, -1, 3149, 1872, 3131, -1, 3149, 2039, 2036, -1, 3149, 2036, 1872, -1, 3149, 3147, 2039, -1, 3150, 1855, 1854, -1, 3150, 1854, 3146, -1, 3150, 3146, 3145, -1, 3150, 3145, 3134, -1, 3151, 3131, 3130, -1, 3151, 3148, 3147, -1, 3151, 3147, 3149, -1, 3151, 3149, 3131, -1, 3133, 3130, 3129, -1, 3133, 3134, 3148, -1, 3133, 3148, 3151, -1, 3133, 3151, 3130, -1, 3132, 3129, 1856, -1, 3132, 1856, 1855, -1, 3132, 1855, 3150, -1, 3132, 3150, 3134, -1, 3136, 1851, 1846, -1, 3136, 1846, 3152, -1, 3137, 3152, 3153, -1, 3137, 3136, 3152, -1, 3138, 3153, 3154, -1, 3138, 3137, 3153, -1, 3135, 3154, 3155, -1, 3135, 3138, 3154, -1, 1945, 3155, 1946, -1, 1945, 3135, 3155, -1, 3156, 3157, 3158, -1, 3156, 3158, 3159, -1, 3160, 3161, 3162, -1, 3160, 3163, 3161, -1, 3160, 3159, 3164, -1, 3160, 3164, 3163, -1, 3165, 3166, 3157, -1, 3165, 3157, 3156, -1, 3167, 3162, 3168, -1, 3167, 3160, 3162, -1, 3167, 3156, 3159, -1, 3167, 3159, 3160, -1, 3169, 2049, 2048, -1, 3169, 2048, 3170, -1, 3169, 3166, 3165, -1, 3169, 3170, 3166, -1, 2044, 1946, 3155, -1, 3171, 3168, 3172, -1, 3171, 3165, 3156, -1, 3171, 3156, 3167, -1, 3171, 3167, 3168, -1, 3173, 3172, 3174, -1, 3173, 3174, 1884, -1, 3173, 1884, 2049, -1, 3173, 3165, 3171, -1, 3173, 3171, 3172, -1, 3173, 2049, 3169, -1, 3173, 3169, 3165, -1, 3161, 1850, 1843, -1, 3175, 3152, 1846, -1, 3175, 1846, 1848, -1, 3175, 1848, 1847, -1, 3176, 3153, 3152, -1, 3176, 3152, 3175, -1, 3177, 3154, 3153, -1, 3177, 3153, 3176, -1, 3178, 3155, 3154, -1, 3178, 2044, 3155, -1, 3178, 3154, 3177, -1, 3179, 3175, 1847, -1, 3180, 2046, 2044, -1, 3180, 2044, 3178, -1, 3158, 3175, 3179, -1, 3158, 3176, 3175, -1, 3157, 3177, 3176, -1, 3157, 3176, 3158, -1, 3166, 3178, 3177, -1, 3166, 3177, 3157, -1, 3164, 1847, 1849, -1, 3164, 3179, 1847, -1, 3170, 2048, 2046, -1, 3170, 3178, 3166, -1, 3170, 3180, 3178, -1, 3170, 2046, 3180, -1, 3159, 3158, 3179, -1, 3159, 3179, 3164, -1, 3163, 1849, 1850, -1, 3163, 3164, 1849, -1, 3163, 1850, 3161, -1, 3161, 1843, 1845, -1, 3161, 1845, 3181, -1, 3162, 3181, 3182, -1, 3162, 3161, 3181, -1, 3168, 3182, 3183, -1, 3168, 3162, 3182, -1, 3172, 3183, 3184, -1, 3172, 3184, 3185, -1, 3172, 3168, 3183, -1, 3174, 3185, 1879, -1, 3174, 3172, 3185, -1, 1884, 3174, 1879, -1, 2118, 1927, 2143, -1, 3185, 2133, 1879, -1, 3184, 2133, 3185, -1, 3183, 2133, 3184, -1, 1845, 2130, 3181, -1, 3186, 2118, 2143, -1, 3187, 3186, 2120, -1, 3187, 2118, 3186, -1, 3188, 2120, 2118, -1, 3188, 3187, 2120, -1, 3188, 2118, 3187, -1, 3189, 2143, 2141, -1, 3189, 3186, 2143, -1, 3189, 2120, 3186, -1, 3190, 2120, 3189, -1, 3190, 3189, 2141, -1, 3191, 2122, 2120, -1, 3191, 2120, 3190, -1, 3192, 2141, 2139, -1, 3192, 3190, 2141, -1, 3193, 2126, 2124, -1, 3193, 2124, 2122, -1, 3193, 2122, 3191, -1, 3193, 3191, 3190, -1, 3193, 3190, 3192, -1, 3194, 2139, 2137, -1, 3194, 3192, 2139, -1, 3195, 3193, 3192, -1, 3195, 2126, 3193, -1, 3195, 3192, 3194, -1, 3196, 2137, 2135, -1, 3196, 3194, 2137, -1, 3197, 2130, 2128, -1, 3197, 2128, 2126, -1, 3197, 3195, 3194, -1, 3197, 2126, 3195, -1, 3197, 3194, 3196, -1, 3198, 2135, 2133, -1, 3199, 3183, 3182, -1, 3199, 3196, 2135, -1, 3199, 2135, 3198, -1, 3199, 2133, 3183, -1, 3199, 3198, 2133, -1, 3200, 3182, 3181, -1, 3200, 3196, 3199, -1, 3200, 3181, 2130, -1, 3200, 2130, 3197, -1, 3200, 3197, 3196, -1, 3200, 3199, 3182, -1, 2110, 2109, 2115, -1, 2113, 2109, 2114, -1, 2115, 2109, 2113, -1, 2114, 2108, 2116, -1, 2109, 2108, 2114, -1, 2116, 2111, 2117, -1, 2108, 2111, 2116, -1, 2117, 2112, 1954, -1, 2111, 2112, 2117, -1, 2112, 1955, 1954, -1, 1832, 2964, 1831, -1, 2964, 2970, 1831, -1, 1831, 2969, 1830, -1, 2970, 2969, 1831, -1, 1830, 2968, 1829, -1, 2969, 2968, 1830, -1, 1829, 2967, 1828, -1, 2968, 2967, 1829, -1, 1828, 2966, 1827, -1, 2967, 2966, 1828, -1, 1827, 2965, 1826, -1, 2966, 2965, 1827, -1, 1826, 1951, 1825, -1, 2965, 1951, 1826, -1, 1840, 1959, 1839, -1, 1839, 2972, 1838, -1, 1959, 2972, 1839, -1, 1838, 2973, 1837, -1, 2972, 2973, 1838, -1, 1837, 2974, 1836, -1, 2973, 2974, 1837, -1, 1836, 2975, 1835, -1, 2974, 2975, 1836, -1, 1835, 2976, 1833, -1, 2975, 2976, 1835, -1, 1833, 2977, 1834, -1, 2976, 2977, 1833, -1, 2977, 2971, 1834, -1, 1977, 1952, 2231, -1, 1977, 1979, 1952, -1, 1976, 2231, 2229, -1, 1976, 1977, 2231, -1, 1974, 2229, 2227, -1, 1974, 1976, 2229, -1, 1969, 2227, 2225, -1, 1969, 1974, 2227, -1, 1973, 1969, 2225, -1, 3010, 1973, 2225, -1, 3011, 2225, 2223, -1, 3011, 3010, 2225, -1, 3007, 3011, 2223, -1, 3008, 3007, 2223, -1, 3013, 3008, 2223, -1, 3016, 3013, 2223, -1, 3019, 3016, 2223, -1, 3021, 3019, 2223, -1, 2121, 2223, 2221, -1, 2121, 3021, 2223, -1, 2119, 2221, 2219, -1, 2119, 2121, 2221, -1, 1930, 2219, 1928, -1, 1930, 2119, 2219, -1, 1896, 1894, 2242, -1, 2165, 1896, 2242, -1, 2167, 2242, 2240, -1, 2167, 2165, 2242, -1, 3055, 2167, 2240, -1, 3054, 3055, 2240, -1, 3053, 3054, 2240, -1, 3051, 3053, 2240, -1, 3048, 3051, 2240, -1, 3047, 2240, 2238, -1, 3047, 3048, 2240, -1, 1997, 3047, 2238, -1, 1996, 2238, 2236, -1, 1996, 1997, 2238, -1, 1995, 1996, 2236, -1, 1993, 2236, 2234, -1, 1993, 1995, 2236, -1, 1991, 2234, 2232, -1, 1991, 1993, 2234, -1, 1990, 2232, 1957, -1, 1990, 1991, 2232, -1, 3201, 3202, 3203, -1, 3204, 3202, 3205, -1, 3206, 3204, 3205, -1, 3207, 3202, 3201, -1, 3207, 3205, 3202, -1, 3203, 3208, 3209, -1, 3201, 3203, 3209, -1, 3210, 3211, 3212, -1, 3210, 3212, 3213, -1, 3211, 3214, 3212, -1, 3215, 3214, 3211, -1, 3215, 3216, 3214, -1, 3217, 3216, 3215, -1, 3218, 3219, 3220, -1, 3221, 3219, 3218, -1, 3221, 3222, 3219, -1, 3221, 3223, 3222, -1, 3222, 3223, 3224, -1, 3223, 3225, 3224, -1, 3220, 3224, 3218, -1, 3224, 3225, 3218, -1, 3226, 3227, 3228, -1, 3229, 3227, 3226, -1, 3228, 3230, 3231, -1, 3227, 3230, 3228, -1, 3231, 3232, 3233, -1, 3230, 3232, 3231, -1, 3233, 3229, 3226, -1, 3232, 3229, 3233, -1, 3211, 3234, 3215, -1, 3235, 3234, 3211, -1, 3217, 3215, 3234, -1, 3236, 3237, 3217, -1, 3238, 3235, 3211, -1, 3210, 3236, 3238, -1, 3210, 3237, 3236, -1, 3210, 3238, 3211, -1, 3234, 3236, 3217, -1, 3239, 3240, 3241, -1, 3241, 3240, 3242, -1, 3243, 3244, 3245, -1, 3245, 3244, 3246, -1, 3246, 3244, 3239, -1, 3239, 3244, 3240, -1, 3244, 3247, 3240, -1, 3248, 3247, 3244, -1, 3247, 3249, 3240, -1, 3244, 3250, 3248, -1, 3249, 3251, 3240, -1, 3244, 3252, 3250, -1, 3251, 3253, 3240, -1, 3244, 3254, 3252, -1, 3253, 3255, 3240, -1, 3244, 3256, 3254, -1, 3255, 3257, 3240, -1, 3257, 3258, 3240, -1, 3257, 3259, 3258, -1, 3259, 3260, 3258, -1, 3260, 3261, 3258, -1, 3261, 3262, 3258, -1, 3263, 3264, 3265, -1, 3265, 3264, 3266, -1, 3263, 3267, 3264, -1, 3258, 3267, 3268, -1, 3268, 3267, 3263, -1, 3264, 3267, 3269, -1, 3270, 3267, 3262, -1, 3271, 3267, 3270, -1, 3272, 3267, 3271, -1, 3273, 3267, 3272, -1, 3262, 3267, 3258, -1, 3273, 3274, 3267, -1, 3244, 3275, 3256, -1, 3275, 3276, 3256, -1, 3275, 3277, 3276, -1, 3275, 3278, 3277, -1, 3279, 3280, 3275, -1, 3275, 3281, 3278, -1, 3275, 3282, 3281, -1, 3280, 3283, 3275, -1, 3283, 3284, 3275, -1, 3274, 3285, 3267, -1, 3282, 3286, 3287, -1, 3275, 3286, 3282, -1, 3288, 3286, 3289, -1, 3289, 3286, 3284, -1, 3284, 3286, 3275, -1, 3290, 3286, 3291, -1, 3292, 3286, 3290, -1, 3293, 3286, 3292, -1, 3287, 3286, 3293, -1, 3294, 3295, 3296, -1, 3296, 3295, 3297, -1, 3297, 3295, 3298, -1, 3286, 3299, 3291, -1, 3286, 3300, 3299, -1, 3301, 3302, 3295, -1, 3303, 3302, 3301, -1, 3304, 3302, 3303, -1, 3305, 3302, 3304, -1, 3306, 3302, 3305, -1, 3295, 3302, 3298, -1, 3306, 3307, 3302, -1, 3300, 3308, 3306, -1, 3306, 3308, 3307, -1, 3286, 3308, 3300, -1, 3286, 3309, 3308, -1, 3310, 3311, 3312, -1, 3312, 3311, 3313, -1, 3314, 3315, 3310, -1, 3310, 3315, 3311, -1, 3314, 3316, 3315, -1, 3317, 3316, 3314, -1, 3317, 3318, 3316, -1, 3317, 3319, 3318, -1, 3317, 3320, 3319, -1, 3318, 3321, 3316, -1, 3317, 3322, 3320, -1, 3321, 3323, 3316, -1, 3317, 3324, 3322, -1, 3323, 3325, 3316, -1, 3325, 3326, 3316, -1, 3317, 3327, 3324, -1, 3317, 3328, 3327, -1, 3326, 3329, 3316, -1, 3326, 3330, 3329, -1, 3330, 3331, 3329, -1, 3331, 3332, 3329, -1, 3329, 3333, 3334, -1, 3332, 3335, 3329, -1, 3335, 3336, 3329, -1, 3329, 3337, 3333, -1, 3329, 3338, 3337, -1, 3329, 3339, 3338, -1, 3329, 3340, 3339, -1, 3336, 3341, 3329, -1, 3329, 3341, 3340, -1, 3342, 3341, 3336, -1, 3343, 3341, 3342, -1, 3344, 3341, 3343, -1, 3345, 3341, 3344, -1, 3346, 3341, 3345, -1, 3347, 3348, 3349, -1, 3349, 3348, 3350, -1, 3350, 3348, 3351, -1, 3352, 3348, 3347, -1, 3352, 3353, 3348, -1, 3352, 3354, 3353, -1, 3352, 3355, 3354, -1, 3352, 3356, 3355, -1, 3357, 3358, 3359, -1, 3359, 3358, 3352, -1, 3352, 3358, 3356, -1, 3357, 3360, 3358, -1, 3361, 3362, 3363, -1, 3364, 3362, 3361, -1, 3365, 3362, 3364, -1, 3366, 3362, 3365, -1, 3367, 3362, 3366, -1, 3368, 3362, 3357, -1, 3360, 3362, 3367, -1, 3357, 3362, 3360, -1, 3363, 3369, 3370, -1, 3362, 3369, 3363, -1, 3346, 3369, 3341, -1, 3371, 3369, 3346, -1, 3372, 3369, 3371, -1, 3373, 3369, 3372, -1, 3374, 3369, 3373, -1, 3370, 3369, 3374, -1, 3362, 3375, 3369, -1, 3362, 3376, 3375, -1, 3377, 3378, 3362, -1, 3362, 3379, 3376, -1, 3378, 3380, 3362, -1, 3362, 3380, 3379, -1, 3286, 3362, 3381, -1, 3286, 3381, 3309, -1, 3381, 3362, 3382, -1, 3382, 3362, 3368, -1, 3348, 3327, 3328, -1, 3348, 3328, 3351, -1, 3274, 3295, 3285, -1, 3285, 3295, 3294, -1, 3383, 3384, 3385, -1, 3386, 3387, 3388, -1, 3389, 3390, 3388, -1, 3391, 3390, 3389, -1, 3392, 3386, 3388, -1, 3392, 3388, 3390, -1, 3393, 3394, 3395, -1, 3393, 3395, 3396, -1, 3385, 3397, 3383, -1, 3385, 3398, 3397, -1, 3397, 3399, 3400, -1, 3398, 3399, 3397, -1, 3401, 3402, 3399, -1, 3399, 3402, 3400, -1, 3403, 3404, 3405, -1, 3406, 3407, 3404, -1, 3408, 3407, 3406, -1, 3408, 3409, 3407, -1, 3404, 3410, 3405, -1, 3407, 3410, 3404, -1, 3411, 3412, 3387, -1, 3413, 3414, 3411, -1, 3411, 3414, 3412, -1, 3412, 3388, 3387, -1, 3414, 3415, 3412, -1, 3414, 3398, 3415, -1, 3415, 3385, 3384, -1, 3398, 3385, 3415, -1, 3202, 3416, 3203, -1, 3417, 3408, 3418, -1, 3416, 3208, 3203, -1, 3418, 3419, 3416, -1, 3416, 3419, 3208, -1, 3418, 3406, 3419, -1, 3408, 3406, 3418, -1, 3419, 3420, 3208, -1, 3421, 3411, 3387, -1, 3421, 3387, 3386, -1, 3422, 3395, 3423, -1, 3396, 3395, 3422, -1, 3424, 3425, 3421, -1, 3426, 3424, 3421, -1, 3427, 3426, 3421, -1, 3428, 3421, 3386, -1, 3428, 3427, 3421, -1, 3429, 3428, 3386, -1, 3430, 3429, 3386, -1, 3431, 3430, 3386, -1, 3432, 3431, 3386, -1, 3433, 3432, 3386, -1, 3392, 3433, 3386, -1, 3434, 3435, 3201, -1, 3436, 3434, 3201, -1, 3437, 3436, 3201, -1, 3438, 3437, 3201, -1, 3207, 3201, 3435, -1, 3439, 3438, 3201, -1, 3209, 3440, 3439, -1, 3209, 3441, 3440, -1, 3209, 3439, 3201, -1, 3442, 3441, 3209, -1, 3443, 3442, 3209, -1, 3401, 3414, 3413, -1, 3401, 3399, 3414, -1, 3419, 3403, 3420, -1, 3404, 3403, 3419, -1, 3444, 3445, 3446, -1, 3447, 3448, 3449, -1, 3447, 3450, 3448, -1, 3447, 3451, 3450, -1, 3447, 3444, 3451, -1, 3452, 3445, 3444, -1, 3452, 3444, 3447, -1, 3453, 3445, 3452, -1, 3454, 3445, 3453, -1, 3455, 3445, 3454, -1, 3456, 3445, 3455, -1, 3457, 3445, 3456, -1, 3458, 3459, 3460, -1, 3461, 3458, 3460, -1, 3462, 3458, 3461, -1, 3463, 3458, 3462, -1, 3464, 3458, 3463, -1, 3465, 3466, 3464, -1, 3465, 3467, 3466, -1, 3465, 3468, 3467, -1, 3465, 3469, 3468, -1, 3465, 3470, 3469, -1, 3465, 3463, 3471, -1, 3465, 3464, 3463, -1, 3465, 3445, 3457, -1, 3465, 3457, 3470, -1, 3472, 3473, 3474, -1, 3475, 3473, 3472, -1, 3406, 3404, 3419, -1, 3399, 3398, 3414, -1, 3476, 3477, 3478, -1, 3479, 3480, 3478, -1, 3479, 3478, 3477, -1, 3481, 3476, 3478, -1, 3482, 3480, 3479, -1, 3483, 3481, 3478, -1, 3484, 3483, 3478, -1, 3485, 3480, 3482, -1, 3486, 3478, 3487, -1, 3486, 3484, 3478, -1, 3488, 3486, 3487, -1, 3489, 3488, 3487, -1, 3490, 3489, 3487, -1, 3491, 3492, 3493, -1, 3491, 3493, 3490, -1, 3491, 3490, 3487, -1, 3494, 3495, 3496, -1, 3495, 3497, 3496, -1, 3494, 3498, 3495, -1, 3498, 3499, 3495, -1, 3500, 3501, 3502, -1, 3503, 3501, 3500, -1, 3504, 3505, 3506, -1, 3505, 3507, 3506, -1, 3508, 3509, 3510, -1, 3511, 3509, 3508, -1, 3512, 3513, 3514, -1, 3515, 3513, 3512, -1, 3516, 3517, 3518, -1, 3519, 3517, 3516, -1, 3520, 3521, 3522, -1, 3520, 3523, 3521, -1, 3520, 3524, 3525, -1, 3522, 3524, 3520, -1, 3525, 3526, 3527, -1, 3524, 3526, 3525, -1, 3528, 3529, 3530, -1, 3528, 3531, 3529, -1, 3529, 3532, 3530, -1, 3529, 3533, 3532, -1, 3517, 3512, 3518, -1, 3534, 3512, 3535, -1, 3535, 3512, 3536, -1, 3536, 3512, 3517, -1, 3512, 3514, 3518, -1, 3537, 3538, 3514, -1, 3538, 3539, 3514, -1, 3514, 3508, 3518, -1, 3539, 3508, 3514, -1, 3518, 3510, 3500, -1, 3508, 3510, 3518, -1, 3503, 3540, 3541, -1, 3503, 3542, 3540, -1, 3543, 3544, 3545, -1, 3545, 3544, 3510, -1, 3500, 3506, 3503, -1, 3503, 3506, 3542, -1, 3510, 3504, 3500, -1, 3544, 3504, 3510, -1, 3500, 3504, 3506, -1, 3546, 3547, 3548, -1, 3549, 3550, 3551, -1, 3552, 3424, 3426, -1, 3237, 3424, 3552, -1, 3217, 3552, 3216, -1, 3217, 3237, 3552, -1, 3207, 3553, 3205, -1, 3394, 3553, 3207, -1, 3554, 3394, 3393, -1, 3425, 3443, 3555, -1, 3425, 3555, 3556, -1, 3557, 3442, 3443, -1, 3557, 3554, 3393, -1, 3392, 3390, 3558, -1, 3213, 3392, 3558, -1, 3237, 3425, 3424, -1, 3237, 3557, 3443, -1, 3237, 3443, 3425, -1, 3559, 3237, 3210, -1, 3559, 3210, 3213, -1, 3558, 3559, 3213, -1, 3559, 3554, 3237, -1, 3237, 3554, 3557, -1, 3554, 3553, 3394, -1, 3442, 3560, 3441, -1, 3561, 3562, 3560, -1, 3557, 3560, 3442, -1, 3557, 3561, 3560, -1, 3423, 3561, 3422, -1, 3562, 3561, 3423, -1, 3409, 3408, 3417, -1, 3563, 3396, 3422, -1, 3563, 3564, 3396, -1, 3565, 3396, 3564, -1, 3561, 3563, 3422, -1, 3393, 3565, 3566, -1, 3393, 3396, 3565, -1, 3557, 3393, 3566, -1, 3557, 3566, 3561, -1, 3566, 3563, 3561, -1, 3567, 3568, 3569, -1, 3570, 3571, 3572, -1, 3570, 3573, 3571, -1, 3570, 3574, 3573, -1, 3575, 3572, 3576, -1, 3575, 3570, 3572, -1, 3577, 3575, 3576, -1, 3578, 3576, 3579, -1, 3578, 3577, 3576, -1, 3580, 3579, 3568, -1, 3580, 3578, 3579, -1, 3580, 3568, 3567, -1, 3204, 3580, 3567, -1, 3206, 3580, 3204, -1, 3581, 3204, 3567, -1, 3582, 3204, 3581, -1, 3583, 3581, 3567, -1, 3584, 3585, 3586, -1, 3584, 3586, 3583, -1, 3584, 3583, 3567, -1, 3587, 3584, 3588, -1, 3589, 3584, 3587, -1, 3389, 3590, 3585, -1, 3389, 3585, 3584, -1, 3591, 3391, 3389, -1, 3591, 3584, 3589, -1, 3591, 3389, 3584, -1, 3592, 3589, 3593, -1, 3592, 3591, 3589, -1, 3594, 3593, 3595, -1, 3594, 3592, 3593, -1, 3596, 3594, 3595, -1, 3597, 3596, 3595, -1, 3597, 3595, 3598, -1, 3501, 3503, 3599, -1, 3599, 3541, 3600, -1, 3503, 3541, 3599, -1, 3541, 3540, 3600, -1, 3600, 3542, 3601, -1, 3540, 3542, 3600, -1, 3601, 3506, 3507, -1, 3542, 3506, 3601, -1, 3505, 3544, 3602, -1, 3504, 3544, 3505, -1, 3602, 3543, 3603, -1, 3544, 3543, 3602, -1, 3603, 3545, 3604, -1, 3543, 3545, 3603, -1, 3604, 3510, 3509, -1, 3545, 3510, 3604, -1, 3511, 3539, 3605, -1, 3508, 3539, 3511, -1, 3605, 3538, 3606, -1, 3539, 3538, 3605, -1, 3606, 3537, 3607, -1, 3538, 3537, 3606, -1, 3607, 3514, 3513, -1, 3537, 3514, 3607, -1, 3515, 3534, 3608, -1, 3512, 3534, 3515, -1, 3608, 3535, 3609, -1, 3534, 3535, 3608, -1, 3609, 3536, 3610, -1, 3610, 3536, 3519, -1, 3535, 3536, 3609, -1, 3536, 3517, 3519, -1, 3611, 3523, 3520, -1, 3611, 3520, 3612, -1, 3613, 3612, 3614, -1, 3613, 3611, 3612, -1, 3615, 3614, 3616, -1, 3615, 3613, 3614, -1, 3617, 3616, 3618, -1, 3617, 3615, 3616, -1, 3619, 3618, 3620, -1, 3619, 3617, 3618, -1, 3621, 3620, 3622, -1, 3621, 3619, 3620, -1, 3502, 3622, 3500, -1, 3502, 3621, 3622, -1, 3623, 3500, 3622, -1, 3623, 3518, 3500, -1, 3624, 3620, 3618, -1, 3624, 3622, 3620, -1, 3624, 3623, 3622, -1, 3625, 3618, 3616, -1, 3625, 3624, 3618, -1, 3626, 3625, 3616, -1, 3627, 3616, 3614, -1, 3627, 3626, 3616, -1, 3628, 3614, 3612, -1, 3628, 3627, 3614, -1, 3525, 3612, 3520, -1, 3525, 3628, 3612, -1, 3516, 3518, 3623, -1, 3629, 3623, 3624, -1, 3629, 3516, 3623, -1, 3630, 3624, 3625, -1, 3630, 3629, 3624, -1, 3631, 3625, 3626, -1, 3631, 3630, 3625, -1, 3632, 3626, 3627, -1, 3632, 3631, 3626, -1, 3633, 3627, 3628, -1, 3633, 3632, 3627, -1, 3634, 3628, 3525, -1, 3634, 3633, 3628, -1, 3527, 3634, 3525, -1, 3474, 3473, 3635, -1, 3636, 3637, 3638, -1, 3635, 3637, 3636, -1, 3473, 3637, 3635, -1, 3639, 3640, 3641, -1, 3638, 3640, 3639, -1, 3637, 3640, 3638, -1, 3641, 3642, 3643, -1, 3640, 3642, 3641, -1, 3643, 3644, 3548, -1, 3642, 3644, 3643, -1, 3644, 3546, 3548, -1, 3548, 3547, 3645, -1, 3646, 3645, 3647, -1, 3646, 3548, 3645, -1, 3648, 3649, 3650, -1, 3648, 3647, 3649, -1, 3648, 3646, 3647, -1, 3651, 3648, 3650, -1, 3482, 3650, 3485, -1, 3482, 3651, 3650, -1, 3652, 3474, 3635, -1, 3646, 3643, 3548, -1, 3651, 3479, 3648, -1, 3482, 3479, 3651, -1, 3653, 3636, 3638, -1, 3653, 3635, 3636, -1, 3653, 3652, 3635, -1, 3654, 3638, 3639, -1, 3654, 3653, 3638, -1, 3655, 3656, 3652, -1, 3655, 3652, 3653, -1, 3657, 3639, 3641, -1, 3657, 3654, 3639, -1, 3658, 3653, 3654, -1, 3658, 3655, 3653, -1, 3659, 3483, 3484, -1, 3659, 3484, 3656, -1, 3659, 3656, 3655, -1, 3660, 3654, 3657, -1, 3660, 3658, 3654, -1, 3661, 3481, 3483, -1, 3661, 3655, 3658, -1, 3661, 3483, 3659, -1, 3661, 3659, 3655, -1, 3662, 3641, 3643, -1, 3662, 3657, 3641, -1, 3663, 3476, 3481, -1, 3663, 3658, 3660, -1, 3663, 3481, 3661, -1, 3663, 3661, 3658, -1, 3664, 3660, 3657, -1, 3664, 3657, 3662, -1, 3665, 3477, 3476, -1, 3665, 3476, 3663, -1, 3665, 3663, 3660, -1, 3665, 3660, 3664, -1, 3666, 3662, 3643, -1, 3666, 3643, 3646, -1, 3667, 3646, 3648, -1, 3667, 3664, 3662, -1, 3667, 3666, 3646, -1, 3667, 3648, 3479, -1, 3667, 3662, 3666, -1, 3668, 3479, 3477, -1, 3668, 3664, 3667, -1, 3668, 3477, 3665, -1, 3668, 3665, 3664, -1, 3668, 3667, 3479, -1, 3669, 3474, 3652, -1, 3669, 3472, 3474, -1, 3670, 3652, 3656, -1, 3670, 3669, 3652, -1, 3486, 3656, 3484, -1, 3486, 3670, 3656, -1, 3671, 3549, 3551, -1, 3671, 3551, 3672, -1, 3673, 3672, 3674, -1, 3673, 3671, 3672, -1, 3675, 3674, 3676, -1, 3675, 3673, 3674, -1, 3677, 3676, 3493, -1, 3677, 3675, 3676, -1, 3492, 3677, 3493, -1, 3678, 3672, 3551, -1, 3490, 3493, 3676, -1, 3669, 3679, 3472, -1, 3680, 3672, 3678, -1, 3681, 3674, 3672, -1, 3681, 3672, 3680, -1, 3682, 3489, 3490, -1, 3682, 3676, 3674, -1, 3682, 3674, 3681, -1, 3682, 3490, 3676, -1, 3683, 3678, 3684, -1, 3683, 3684, 3685, -1, 3683, 3680, 3678, -1, 3686, 3680, 3683, -1, 3686, 3681, 3680, -1, 3687, 3682, 3681, -1, 3687, 3489, 3682, -1, 3687, 3681, 3686, -1, 3688, 3685, 3689, -1, 3688, 3683, 3685, -1, 3690, 3689, 3691, -1, 3690, 3691, 3679, -1, 3690, 3688, 3689, -1, 3690, 3679, 3669, -1, 3692, 3683, 3688, -1, 3692, 3686, 3683, -1, 3693, 3669, 3670, -1, 3693, 3688, 3690, -1, 3693, 3690, 3669, -1, 3693, 3692, 3688, -1, 3694, 3488, 3489, -1, 3694, 3687, 3686, -1, 3694, 3489, 3687, -1, 3694, 3686, 3692, -1, 3695, 3486, 3488, -1, 3695, 3670, 3486, -1, 3695, 3693, 3670, -1, 3695, 3488, 3694, -1, 3695, 3692, 3693, -1, 3695, 3694, 3692, -1, 3472, 3679, 3475, -1, 3475, 3691, 3696, -1, 3679, 3691, 3475, -1, 3691, 3689, 3696, -1, 3696, 3685, 3697, -1, 3689, 3685, 3696, -1, 3697, 3684, 3698, -1, 3685, 3684, 3697, -1, 3698, 3678, 3699, -1, 3699, 3678, 3700, -1, 3684, 3678, 3698, -1, 3700, 3551, 3550, -1, 3678, 3551, 3700, -1, 3701, 3487, 3478, -1, 3701, 3478, 3702, -1, 3703, 3702, 3704, -1, 3703, 3701, 3702, -1, 3705, 3704, 3706, -1, 3705, 3703, 3704, -1, 3707, 3706, 3708, -1, 3707, 3705, 3706, -1, 3522, 3708, 3524, -1, 3522, 3707, 3708, -1, 3413, 3709, 3710, -1, 3413, 3711, 3401, -1, 3710, 3711, 3413, -1, 3413, 3712, 3709, -1, 3411, 3713, 3413, -1, 3413, 3713, 3712, -1, 3421, 3556, 3411, -1, 3411, 3556, 3713, -1, 3711, 3402, 3401, -1, 3711, 3586, 3402, -1, 3421, 3425, 3556, -1, 3714, 3715, 3420, -1, 3403, 3716, 3420, -1, 3420, 3716, 3714, -1, 3715, 3717, 3420, -1, 3420, 3718, 3208, -1, 3717, 3718, 3420, -1, 3208, 3555, 3209, -1, 3718, 3555, 3208, -1, 3403, 3405, 3716, -1, 3405, 3583, 3716, -1, 3555, 3443, 3209, -1, 3410, 3582, 3581, -1, 3418, 3410, 3407, -1, 3416, 3582, 3410, -1, 3416, 3410, 3418, -1, 3582, 3416, 3202, -1, 3204, 3582, 3202, -1, 3407, 3409, 3417, -1, 3407, 3417, 3418, -1, 3383, 3397, 3415, -1, 3383, 3415, 3384, -1, 3590, 3389, 3388, -1, 3590, 3388, 3412, -1, 3400, 3415, 3397, -1, 3590, 3400, 3585, -1, 3590, 3412, 3400, -1, 3400, 3412, 3415, -1, 3531, 3528, 3719, -1, 3720, 3719, 3721, -1, 3720, 3531, 3719, -1, 3722, 3721, 3723, -1, 3722, 3720, 3721, -1, 3724, 3723, 3725, -1, 3724, 3722, 3723, -1, 3726, 3725, 3727, -1, 3726, 3724, 3725, -1, 3728, 3727, 3729, -1, 3728, 3726, 3727, -1, 3730, 3729, 3731, -1, 3730, 3728, 3729, -1, 3732, 3731, 3446, -1, 3732, 3730, 3731, -1, 3445, 3732, 3446, -1, 3733, 3478, 3480, -1, 3733, 3480, 3734, -1, 3735, 3734, 3736, -1, 3735, 3733, 3734, -1, 3737, 3736, 3738, -1, 3737, 3735, 3736, -1, 3739, 3738, 3740, -1, 3739, 3737, 3738, -1, 3741, 3740, 3742, -1, 3741, 3739, 3740, -1, 3743, 3742, 3744, -1, 3743, 3741, 3742, -1, 3745, 3744, 3528, -1, 3745, 3743, 3744, -1, 3530, 3745, 3528, -1, 3745, 3530, 3746, -1, 3708, 3747, 3524, -1, 3478, 3733, 3702, -1, 3748, 3746, 3749, -1, 3748, 3749, 3750, -1, 3751, 3743, 3745, -1, 3751, 3741, 3743, -1, 3751, 3745, 3746, -1, 3751, 3750, 3741, -1, 3751, 3746, 3748, -1, 3751, 3748, 3750, -1, 3752, 3750, 3753, -1, 3752, 3753, 3754, -1, 3755, 3739, 3741, -1, 3755, 3737, 3739, -1, 3755, 3741, 3750, -1, 3755, 3750, 3752, -1, 3756, 3754, 3757, -1, 3756, 3757, 3747, -1, 3756, 3708, 3706, -1, 3756, 3747, 3708, -1, 3758, 3735, 3737, -1, 3758, 3733, 3735, -1, 3758, 3706, 3704, -1, 3758, 3704, 3702, -1, 3758, 3756, 3706, -1, 3758, 3702, 3733, -1, 3759, 3737, 3755, -1, 3759, 3755, 3752, -1, 3759, 3758, 3737, -1, 3759, 3756, 3758, -1, 3759, 3752, 3754, -1, 3759, 3754, 3756, -1, 3526, 3524, 3747, -1, 3760, 3757, 3754, -1, 3760, 3747, 3757, -1, 3760, 3526, 3747, -1, 3761, 3754, 3753, -1, 3761, 3760, 3754, -1, 3762, 3753, 3750, -1, 3762, 3761, 3753, -1, 3763, 3750, 3749, -1, 3763, 3762, 3750, -1, 3764, 3749, 3746, -1, 3764, 3763, 3749, -1, 3765, 3746, 3530, -1, 3765, 3764, 3746, -1, 3532, 3765, 3530, -1, 3496, 3497, 3766, -1, 3767, 3766, 3768, -1, 3767, 3496, 3766, -1, 3769, 3768, 3770, -1, 3769, 3767, 3768, -1, 3771, 3770, 3772, -1, 3771, 3769, 3770, -1, 3773, 3774, 3775, -1, 3773, 3772, 3774, -1, 3773, 3771, 3772, -1, 3776, 3775, 3777, -1, 3776, 3773, 3775, -1, 3778, 3777, 3465, -1, 3778, 3776, 3777, -1, 3471, 3778, 3465, -1, 3779, 3491, 3487, -1, 3779, 3487, 3780, -1, 3781, 3780, 3782, -1, 3781, 3779, 3780, -1, 3783, 3782, 3784, -1, 3783, 3781, 3782, -1, 3785, 3784, 3786, -1, 3785, 3783, 3784, -1, 3787, 3786, 3788, -1, 3787, 3785, 3786, -1, 3789, 3788, 3790, -1, 3789, 3787, 3788, -1, 3791, 3790, 3494, -1, 3791, 3789, 3790, -1, 3496, 3791, 3494, -1, 3792, 3494, 3790, -1, 3701, 3780, 3487, -1, 3522, 3793, 3707, -1, 3794, 3788, 3786, -1, 3794, 3790, 3788, -1, 3795, 3792, 3790, -1, 3795, 3786, 3796, -1, 3795, 3790, 3794, -1, 3795, 3794, 3786, -1, 3797, 3792, 3795, -1, 3797, 3795, 3796, -1, 3798, 3796, 3799, -1, 3798, 3799, 3792, -1, 3798, 3792, 3797, -1, 3798, 3797, 3796, -1, 3800, 3786, 3784, -1, 3801, 3796, 3786, -1, 3801, 3786, 3800, -1, 3802, 3796, 3801, -1, 3803, 3804, 3796, -1, 3803, 3796, 3802, -1, 3805, 3782, 3780, -1, 3805, 3784, 3782, -1, 3805, 3800, 3784, -1, 3806, 3800, 3805, -1, 3806, 3801, 3800, -1, 3807, 3801, 3806, -1, 3807, 3802, 3801, -1, 3808, 3793, 3809, -1, 3808, 3809, 3804, -1, 3808, 3803, 3802, -1, 3808, 3804, 3803, -1, 3808, 3802, 3807, -1, 3810, 3701, 3703, -1, 3810, 3780, 3701, -1, 3810, 3805, 3780, -1, 3811, 3806, 3805, -1, 3811, 3810, 3703, -1, 3811, 3805, 3810, -1, 3812, 3703, 3705, -1, 3812, 3806, 3811, -1, 3812, 3811, 3703, -1, 3812, 3807, 3806, -1, 3813, 3705, 3707, -1, 3813, 3707, 3793, -1, 3813, 3793, 3808, -1, 3813, 3808, 3807, -1, 3813, 3812, 3705, -1, 3813, 3807, 3812, -1, 3498, 3494, 3792, -1, 3814, 3792, 3799, -1, 3814, 3498, 3792, -1, 3815, 3799, 3796, -1, 3815, 3814, 3799, -1, 3816, 3796, 3804, -1, 3816, 3815, 3796, -1, 3817, 3804, 3809, -1, 3817, 3816, 3804, -1, 3818, 3809, 3793, -1, 3818, 3817, 3809, -1, 3819, 3818, 3793, -1, 3521, 3793, 3522, -1, 3521, 3819, 3793, -1, 3533, 3529, 3820, -1, 3821, 3820, 3822, -1, 3821, 3533, 3820, -1, 3823, 3822, 3824, -1, 3823, 3821, 3822, -1, 3825, 3824, 3826, -1, 3825, 3823, 3824, -1, 3827, 3826, 3828, -1, 3827, 3825, 3826, -1, 3829, 3828, 3830, -1, 3829, 3827, 3828, -1, 3831, 3830, 3832, -1, 3831, 3829, 3830, -1, 3554, 3832, 3553, -1, 3554, 3831, 3832, -1, 3559, 3558, 3833, -1, 3834, 3833, 3835, -1, 3834, 3559, 3833, -1, 3836, 3835, 3837, -1, 3836, 3834, 3835, -1, 3838, 3837, 3839, -1, 3838, 3836, 3837, -1, 3840, 3839, 3841, -1, 3840, 3838, 3839, -1, 3842, 3841, 3843, -1, 3842, 3840, 3841, -1, 3844, 3843, 3495, -1, 3844, 3842, 3843, -1, 3499, 3844, 3495, -1, 3845, 3846, 3847, -1, 3848, 3849, 3850, -1, 3845, 3851, 3852, -1, 3845, 3853, 3846, -1, 3845, 3852, 3853, -1, 3848, 3854, 3849, -1, 3855, 3815, 3816, -1, 3334, 3856, 3329, -1, 3855, 3816, 3857, -1, 3858, 3850, 3859, -1, 3855, 3860, 3861, -1, 3855, 3857, 3860, -1, 3858, 3859, 3862, -1, 3863, 3847, 3864, -1, 3865, 3338, 3339, -1, 3863, 3851, 3845, -1, 3863, 3845, 3847, -1, 3863, 3861, 3851, -1, 3865, 3862, 3338, -1, 3866, 3864, 3867, -1, 3866, 3814, 3815, -1, 3868, 3869, 3870, -1, 3866, 3815, 3855, -1, 3866, 3855, 3861, -1, 3866, 3861, 3863, -1, 3866, 3863, 3864, -1, 3868, 3870, 3871, -1, 3866, 3867, 3814, -1, 3872, 3854, 3848, -1, 3872, 3871, 3854, -1, 3873, 3850, 3858, -1, 3873, 3848, 3850, -1, 3874, 3862, 3865, -1, 3874, 3858, 3862, -1, 3875, 3521, 3876, -1, 3875, 3876, 3869, -1, 3875, 3819, 3521, -1, 3875, 3869, 3868, -1, 3877, 3339, 3340, -1, 3877, 3865, 3339, -1, 3878, 3868, 3871, -1, 3878, 3871, 3872, -1, 3879, 3872, 3848, -1, 3879, 3848, 3873, -1, 3880, 3873, 3858, -1, 3880, 3858, 3874, -1, 3881, 3874, 3865, -1, 3881, 3865, 3877, -1, 3882, 3818, 3819, -1, 3882, 3868, 3878, -1, 3882, 3819, 3875, -1, 3882, 3875, 3868, -1, 3883, 3340, 3341, -1, 3883, 3341, 3884, -1, 3883, 3877, 3340, -1, 3885, 3878, 3872, -1, 3885, 3872, 3879, -1, 3886, 3879, 3873, -1, 3498, 3814, 3867, -1, 3886, 3873, 3880, -1, 3852, 3880, 3874, -1, 3887, 3334, 3333, -1, 3887, 3856, 3334, -1, 3852, 3874, 3881, -1, 3849, 3888, 3856, -1, 3889, 3877, 3883, -1, 3889, 3881, 3877, -1, 3889, 3884, 3890, -1, 3889, 3883, 3884, -1, 3849, 3856, 3887, -1, 3891, 3882, 3878, -1, 3859, 3333, 3337, -1, 3891, 3817, 3818, -1, 3891, 3878, 3885, -1, 3859, 3887, 3333, -1, 3891, 3818, 3882, -1, 3860, 3885, 3879, -1, 3854, 3892, 3888, -1, 3860, 3879, 3886, -1, 3854, 3888, 3849, -1, 3851, 3880, 3852, -1, 3851, 3886, 3880, -1, 3850, 3887, 3859, -1, 3853, 3890, 3846, -1, 3853, 3881, 3889, -1, 3850, 3849, 3887, -1, 3862, 3337, 3338, -1, 3853, 3852, 3881, -1, 3853, 3889, 3890, -1, 3857, 3885, 3860, -1, 3857, 3816, 3817, -1, 3857, 3817, 3891, -1, 3862, 3859, 3337, -1, 3857, 3891, 3885, -1, 3871, 3870, 3892, -1, 3871, 3892, 3854, -1, 3861, 3860, 3886, -1, 3861, 3886, 3851, -1, 3884, 3341, 3369, -1, 3884, 3369, 3893, -1, 3890, 3893, 3894, -1, 3890, 3884, 3893, -1, 3846, 3894, 3895, -1, 3846, 3890, 3894, -1, 3847, 3895, 3896, -1, 3847, 3846, 3895, -1, 3864, 3896, 3897, -1, 3864, 3847, 3896, -1, 3867, 3897, 3898, -1, 3867, 3864, 3897, -1, 3498, 3898, 3499, -1, 3498, 3867, 3898, -1, 3899, 3329, 3856, -1, 3899, 3316, 3329, -1, 3900, 3856, 3888, -1, 3900, 3899, 3856, -1, 3901, 3888, 3892, -1, 3901, 3900, 3888, -1, 3902, 3892, 3870, -1, 3902, 3901, 3892, -1, 3903, 3870, 3869, -1, 3903, 3902, 3870, -1, 3904, 3869, 3876, -1, 3904, 3903, 3869, -1, 3523, 3876, 3521, -1, 3523, 3904, 3876, -1, 3905, 3895, 3906, -1, 3907, 3908, 3909, -1, 3907, 3909, 3910, -1, 3911, 3906, 3912, -1, 3913, 3914, 3915, -1, 3911, 3912, 3916, -1, 3913, 3917, 3918, -1, 3913, 3910, 3917, -1, 3913, 3918, 3914, -1, 3919, 3920, 3921, -1, 3922, 3836, 3838, -1, 3919, 3916, 3920, -1, 3922, 3908, 3907, -1, 3922, 3923, 3908, -1, 3922, 3838, 3923, -1, 3924, 3915, 3925, -1, 3926, 3379, 3380, -1, 3924, 3907, 3910, -1, 3924, 3910, 3913, -1, 3924, 3913, 3915, -1, 3926, 3921, 3379, -1, 3927, 3925, 3928, -1, 3929, 3897, 3896, -1, 3927, 3928, 3559, -1, 3927, 3559, 3834, -1, 3927, 3834, 3836, -1, 3927, 3836, 3922, -1, 3927, 3907, 3924, -1, 3929, 3896, 3905, -1, 3927, 3924, 3925, -1, 3927, 3922, 3907, -1, 3930, 3906, 3911, -1, 3930, 3905, 3906, -1, 3931, 3911, 3916, -1, 3931, 3916, 3919, -1, 3932, 3919, 3921, -1, 3932, 3921, 3926, -1, 3844, 3499, 3898, -1, 3933, 3898, 3897, -1, 3933, 3844, 3898, -1, 3933, 3897, 3929, -1, 3934, 3380, 3378, -1, 3934, 3926, 3380, -1, 3935, 3929, 3905, -1, 3935, 3905, 3930, -1, 3936, 3377, 3362, -1, 3937, 3911, 3931, -1, 3937, 3930, 3911, -1, 3938, 3919, 3932, -1, 3938, 3931, 3919, -1, 3939, 3926, 3934, -1, 3939, 3932, 3926, -1, 3940, 3842, 3844, -1, 3940, 3929, 3935, -1, 3940, 3844, 3933, -1, 3940, 3933, 3929, -1, 3941, 3378, 3377, -1, 3941, 3377, 3936, -1, 3941, 3934, 3378, -1, 3942, 3935, 3930, -1, 3942, 3930, 3937, -1, 3909, 3937, 3931, -1, 3943, 3893, 3369, -1, 3909, 3931, 3938, -1, 3943, 3369, 3375, -1, 3917, 3938, 3932, -1, 3912, 3894, 3893, -1, 3917, 3932, 3939, -1, 3944, 3936, 3945, -1, 3944, 3941, 3936, -1, 3944, 3934, 3941, -1, 3912, 3893, 3943, -1, 3944, 3939, 3934, -1, 3946, 3940, 3935, -1, 3920, 3375, 3376, -1, 3946, 3840, 3842, -1, 3946, 3935, 3942, -1, 3920, 3943, 3375, -1, 3946, 3842, 3940, -1, 3908, 3937, 3909, -1, 3906, 3895, 3894, -1, 3908, 3942, 3937, -1, 3906, 3894, 3912, -1, 3916, 3943, 3920, -1, 3910, 3909, 3938, -1, 3910, 3938, 3917, -1, 3918, 3939, 3944, -1, 3916, 3912, 3943, -1, 3918, 3917, 3939, -1, 3918, 3945, 3914, -1, 3921, 3376, 3379, -1, 3918, 3944, 3945, -1, 3923, 3838, 3840, -1, 3921, 3920, 3376, -1, 3923, 3946, 3942, -1, 3905, 3896, 3895, -1, 3923, 3840, 3946, -1, 3923, 3942, 3908, -1, 3947, 3948, 3949, -1, 3950, 3951, 3952, -1, 3947, 3949, 3953, -1, 3954, 3952, 3955, -1, 3956, 3901, 3902, -1, 3956, 3957, 3901, -1, 3954, 3955, 3958, -1, 3956, 3953, 3959, -1, 3956, 3959, 3957, -1, 3960, 3615, 3961, -1, 3962, 3963, 3964, -1, 3960, 3613, 3615, -1, 3960, 3961, 3948, -1, 3962, 3958, 3963, -1, 3960, 3948, 3947, -1, 3965, 3902, 3903, -1, 3966, 3312, 3313, -1, 3965, 3947, 3953, -1, 3966, 3964, 3312, -1, 3965, 3953, 3956, -1, 3965, 3956, 3902, -1, 3967, 3904, 3523, -1, 3967, 3903, 3904, -1, 3967, 3523, 3611, -1, 3968, 3969, 3970, -1, 3967, 3611, 3613, -1, 3968, 3970, 3950, -1, 3967, 3965, 3903, -1, 3967, 3613, 3960, -1, 3967, 3960, 3947, -1, 3967, 3947, 3965, -1, 3971, 3950, 3952, -1, 3971, 3952, 3954, -1, 3972, 3954, 3958, -1, 3972, 3958, 3962, -1, 3973, 3962, 3964, -1, 3973, 3964, 3966, -1, 3974, 3621, 3502, -1, 3974, 3502, 3975, -1, 3974, 3975, 3969, -1, 3974, 3969, 3968, -1, 3976, 3313, 3311, -1, 3976, 3966, 3313, -1, 3977, 3968, 3950, -1, 3977, 3950, 3971, -1, 3978, 3954, 3972, -1, 3978, 3971, 3954, -1, 3979, 3962, 3973, -1, 3979, 3972, 3962, -1, 3980, 3973, 3966, -1, 3980, 3966, 3976, -1, 3981, 3619, 3621, -1, 3981, 3621, 3974, -1, 3981, 3968, 3977, -1, 3981, 3974, 3968, -1, 3982, 3316, 3899, -1, 3982, 3311, 3315, -1, 3982, 3315, 3316, -1, 3982, 3976, 3311, -1, 3983, 3977, 3971, -1, 3983, 3971, 3978, -1, 3949, 3978, 3972, -1, 3984, 3985, 3317, -1, 3984, 3317, 3314, -1, 3949, 3972, 3979, -1, 3959, 3979, 3973, -1, 3959, 3973, 3980, -1, 3955, 3986, 3985, -1, 3987, 3899, 3900, -1, 3987, 3980, 3976, -1, 3987, 3976, 3982, -1, 3955, 3985, 3984, -1, 3987, 3982, 3899, -1, 3963, 3314, 3310, -1, 3988, 3981, 3977, -1, 3988, 3617, 3619, -1, 3963, 3984, 3314, -1, 3988, 3619, 3981, -1, 3988, 3977, 3983, -1, 3948, 3978, 3949, -1, 3948, 3983, 3978, -1, 3952, 3951, 3986, -1, 3952, 3986, 3955, -1, 3953, 3949, 3979, -1, 3958, 3984, 3963, -1, 3958, 3955, 3984, -1, 3953, 3979, 3959, -1, 3957, 3900, 3901, -1, 3957, 3987, 3900, -1, 3964, 3310, 3312, -1, 3957, 3980, 3987, -1, 3957, 3959, 3980, -1, 3964, 3963, 3310, -1, 3961, 3615, 3617, -1, 3961, 3988, 3983, -1, 3961, 3983, 3948, -1, 3961, 3617, 3988, -1, 3950, 3970, 3951, -1, 3936, 3362, 3286, -1, 3936, 3286, 3989, -1, 3945, 3989, 3990, -1, 3945, 3990, 3991, -1, 3945, 3936, 3989, -1, 3914, 3945, 3991, -1, 3915, 3991, 3992, -1, 3915, 3992, 3993, -1, 3915, 3914, 3991, -1, 3925, 3993, 3994, -1, 3925, 3915, 3993, -1, 3928, 3994, 3554, -1, 3928, 3925, 3994, -1, 3559, 3928, 3554, -1, 3995, 3317, 3985, -1, 3995, 3328, 3317, -1, 3996, 3985, 3986, -1, 3996, 3995, 3985, -1, 3997, 3986, 3951, -1, 3997, 3996, 3986, -1, 3998, 3951, 3970, -1, 3998, 3997, 3951, -1, 3999, 3970, 3969, -1, 3999, 3998, 3970, -1, 4000, 3969, 3975, -1, 4000, 3999, 3969, -1, 3501, 3975, 3502, -1, 3501, 4000, 3975, -1, 4001, 4002, 4003, -1, 4004, 4005, 4006, -1, 4001, 4007, 4002, -1, 4001, 4008, 4009, -1, 4001, 4009, 4007, -1, 4004, 4010, 4005, -1, 4011, 4012, 4013, -1, 4014, 4006, 4015, -1, 4011, 3823, 3825, -1, 3288, 3989, 3286, -1, 4011, 3825, 4012, -1, 4011, 4013, 4016, -1, 4014, 4015, 4017, -1, 4018, 4003, 4019, -1, 4020, 3283, 3280, -1, 4018, 4001, 4003, -1, 4018, 4016, 4008, -1, 4020, 4017, 3283, -1, 4018, 4008, 4001, -1, 4021, 4018, 4019, -1, 4022, 3993, 3992, -1, 4021, 4019, 4023, -1, 4021, 4023, 3533, -1, 4021, 3533, 3821, -1, 4021, 3821, 3823, -1, 4021, 3823, 4011, -1, 4021, 4011, 4016, -1, 4022, 3992, 4024, -1, 4021, 4016, 4018, -1, 4025, 4024, 4010, -1, 4025, 4010, 4004, -1, 4026, 4004, 4006, -1, 4026, 4006, 4014, -1, 4027, 4017, 4020, -1, 4027, 4014, 4017, -1, 4028, 3994, 3993, -1, 4028, 3993, 4022, -1, 4028, 3831, 3994, -1, 3831, 3554, 3994, -1, 4029, 3280, 3279, -1, 4029, 4020, 3280, -1, 4030, 4024, 4025, -1, 4030, 4022, 4024, -1, 4031, 4004, 4026, -1, 4031, 4025, 4004, -1, 4032, 4026, 4014, -1, 4032, 4014, 4027, -1, 4033, 4027, 4020, -1, 4033, 4020, 4029, -1, 4034, 3279, 3275, -1, 4034, 3275, 4035, -1, 4034, 4029, 3279, -1, 4036, 4022, 4030, -1, 4036, 3829, 3831, -1, 4036, 3831, 4028, -1, 4036, 4028, 4022, -1, 4037, 4030, 4025, -1, 4037, 4025, 4031, -1, 4038, 4031, 4026, -1, 4038, 4026, 4032, -1, 4009, 4032, 4027, -1, 4039, 3288, 3289, -1, 4039, 3989, 3288, -1, 4009, 4027, 4033, -1, 4005, 3990, 3989, -1, 4040, 4033, 4029, -1, 4040, 4034, 4035, -1, 4040, 4035, 4041, -1, 4040, 4029, 4034, -1, 4005, 3989, 4039, -1, 4042, 3829, 4036, -1, 4042, 3827, 3829, -1, 4015, 3289, 3284, -1, 4042, 4036, 4030, -1, 4042, 4030, 4037, -1, 4015, 4039, 3289, -1, 4013, 4031, 4038, -1, 4013, 4037, 4031, -1, 4010, 3991, 3990, -1, 4010, 3990, 4005, -1, 4008, 4038, 4032, -1, 4008, 4032, 4009, -1, 4006, 4039, 4015, -1, 4007, 4033, 4040, -1, 4007, 4041, 4002, -1, 4006, 4005, 4039, -1, 4007, 4009, 4033, -1, 4007, 4040, 4041, -1, 4017, 3284, 3283, -1, 4012, 4042, 4037, -1, 4012, 4037, 4013, -1, 4012, 3825, 3827, -1, 4017, 4015, 3284, -1, 4012, 3827, 4042, -1, 4024, 3992, 3991, -1, 4024, 3991, 4010, -1, 4016, 4038, 4008, -1, 4016, 4013, 4038, -1, 4043, 4044, 4045, -1, 4043, 4045, 4046, -1, 4047, 4048, 4049, -1, 4047, 4046, 4050, -1, 4047, 4050, 4051, -1, 4047, 4051, 4048, -1, 4052, 3995, 3996, -1, 4052, 3328, 3995, -1, 4052, 3351, 3328, -1, 4052, 3996, 4053, -1, 4054, 4053, 4044, -1, 4054, 4044, 4043, -1, 4055, 4049, 4056, -1, 4055, 4047, 4049, -1, 4055, 4046, 4047, -1, 4055, 4043, 4046, -1, 4057, 3350, 3351, -1, 4057, 3351, 4052, -1, 4057, 4052, 4053, -1, 4057, 4053, 4054, -1, 4058, 4056, 4059, -1, 4058, 4055, 4056, -1, 4058, 4054, 4043, -1, 4058, 4043, 4055, -1, 4060, 4059, 4061, -1, 4060, 4061, 3347, -1, 4060, 3347, 3349, -1, 4060, 3349, 3350, -1, 4060, 3350, 4057, -1, 4060, 4058, 4059, -1, 4060, 4057, 4054, -1, 4060, 4054, 4058, -1, 4062, 4000, 3501, -1, 4062, 3501, 3599, -1, 4063, 3999, 4000, -1, 4063, 4000, 4062, -1, 4064, 3599, 3600, -1, 4064, 4062, 3599, -1, 4045, 3998, 3999, -1, 4045, 3999, 4063, -1, 4050, 4062, 4064, -1, 4050, 4063, 4062, -1, 4065, 3600, 3601, -1, 4065, 3601, 3507, -1, 4065, 3507, 4066, -1, 4065, 4064, 3600, -1, 4044, 3997, 3998, -1, 4044, 3998, 4045, -1, 4046, 4045, 4063, -1, 4046, 4063, 4050, -1, 4051, 4066, 4048, -1, 4051, 4065, 4066, -1, 4051, 4064, 4065, -1, 4051, 4050, 4064, -1, 4053, 3996, 3997, -1, 4053, 3997, 4044, -1, 4035, 3275, 3244, -1, 4035, 3244, 4067, -1, 4041, 4067, 4068, -1, 4041, 4035, 4067, -1, 4002, 4068, 4069, -1, 4002, 4041, 4068, -1, 4003, 4069, 4070, -1, 4003, 4002, 4069, -1, 4019, 4070, 4071, -1, 4019, 4003, 4070, -1, 4023, 4071, 4072, -1, 4023, 4019, 4071, -1, 3533, 4072, 3532, -1, 3533, 4023, 4072, -1, 4073, 3347, 4061, -1, 4073, 3352, 3347, -1, 4074, 4061, 4059, -1, 4074, 4073, 4061, -1, 4075, 4059, 4056, -1, 4075, 4074, 4059, -1, 4076, 4056, 4049, -1, 4076, 4075, 4056, -1, 4077, 4049, 4048, -1, 4077, 4076, 4049, -1, 4078, 4048, 4066, -1, 4078, 4077, 4048, -1, 3505, 4066, 3507, -1, 3505, 4078, 4066, -1, 4079, 4080, 4081, -1, 4079, 4082, 4080, -1, 4083, 4084, 4085, -1, 4086, 4087, 4088, -1, 4086, 4088, 4089, -1, 4083, 4085, 4090, -1, 3243, 4067, 3244, -1, 4086, 4081, 4091, -1, 4086, 4091, 4087, -1, 4092, 4090, 4093, -1, 4094, 3762, 4095, -1, 4092, 4093, 4096, -1, 4094, 3761, 3762, -1, 4094, 4095, 4082, -1, 4094, 4082, 4079, -1, 4097, 3246, 3239, -1, 4098, 4089, 4099, -1, 4098, 4086, 4089, -1, 4098, 4079, 4081, -1, 4097, 4096, 3246, -1, 4098, 4081, 4086, -1, 4100, 4071, 4070, -1, 4101, 4099, 4102, -1, 4101, 3760, 3761, -1, 4101, 3761, 4094, -1, 4101, 4094, 4079, -1, 4101, 4079, 4098, -1, 4101, 4098, 4099, -1, 4100, 4070, 4103, -1, 4101, 4102, 3760, -1, 4104, 4084, 4083, -1, 4104, 4103, 4084, -1, 4105, 4090, 4092, -1, 4105, 4083, 4090, -1, 4106, 4092, 4096, -1, 4106, 4096, 4097, -1, 4107, 4072, 4071, -1, 4107, 3532, 4072, -1, 4107, 3765, 3532, -1, 4107, 4071, 4100, -1, 4108, 3239, 3241, -1, 4108, 4097, 3239, -1, 4109, 4100, 4103, -1, 4109, 4103, 4104, -1, 4110, 4104, 4083, -1, 4110, 4083, 4105, -1, 4111, 4092, 4106, -1, 4111, 4105, 4092, -1, 4112, 4097, 4108, -1, 4112, 4106, 4097, -1, 4113, 3764, 3765, -1, 4113, 4100, 4109, -1, 4113, 3765, 4107, -1, 4113, 4107, 4100, -1, 4114, 3241, 3242, -1, 4114, 3242, 3240, -1, 4114, 3240, 4115, -1, 4114, 4108, 3241, -1, 4116, 4109, 4104, -1, 4116, 4104, 4110, -1, 4080, 4105, 4111, -1, 4080, 4110, 4105, -1, 3526, 3760, 4102, -1, 4117, 4067, 3243, -1, 4085, 4068, 4067, -1, 4091, 4111, 4106, -1, 4091, 4106, 4112, -1, 4118, 4115, 4119, -1, 4085, 4067, 4117, -1, 4118, 4114, 4115, -1, 4118, 4108, 4114, -1, 4093, 3243, 3245, -1, 4118, 4112, 4108, -1, 4120, 4113, 4109, -1, 4093, 4117, 3243, -1, 4120, 3763, 3764, -1, 4120, 3764, 4113, -1, 4084, 4069, 4068, -1, 4120, 4109, 4116, -1, 4084, 4068, 4085, -1, 4082, 4116, 4110, -1, 4082, 4110, 4080, -1, 4081, 4080, 4111, -1, 4090, 4117, 4093, -1, 4090, 4085, 4117, -1, 4081, 4111, 4091, -1, 4087, 4119, 4088, -1, 4096, 3245, 3246, -1, 4087, 4118, 4119, -1, 4087, 4112, 4118, -1, 4087, 4091, 4112, -1, 4095, 3762, 3763, -1, 4096, 4093, 3245, -1, 4095, 4120, 4116, -1, 4103, 4070, 4069, -1, 4095, 3763, 4120, -1, 4095, 4116, 4082, -1, 4103, 4069, 4084, -1, 4121, 4122, 4123, -1, 4121, 4124, 4125, -1, 4121, 4126, 4122, -1, 4121, 4125, 4126, -1, 4127, 3352, 4073, -1, 4127, 3359, 3352, -1, 4127, 4073, 4128, -1, 4129, 4128, 4130, -1, 4129, 4130, 4131, -1, 4132, 4123, 4133, -1, 4132, 4121, 4123, -1, 4132, 4124, 4121, -1, 4132, 4131, 4124, -1, 4134, 3357, 3359, -1, 4134, 3359, 4127, -1, 4134, 4127, 4128, -1, 4134, 4128, 4129, -1, 4135, 4133, 4136, -1, 4135, 4132, 4133, -1, 4135, 4129, 4131, -1, 4135, 4131, 4132, -1, 4137, 4136, 4138, -1, 4137, 4138, 3382, -1, 4137, 3382, 3368, -1, 4137, 3368, 3357, -1, 4137, 3357, 4134, -1, 4137, 4135, 4136, -1, 4137, 4134, 4129, -1, 4137, 4129, 4135, -1, 4139, 3604, 3509, -1, 4140, 4078, 3505, -1, 4140, 4077, 4078, -1, 4140, 3505, 3602, -1, 4141, 4076, 4077, -1, 4141, 4077, 4140, -1, 4142, 3602, 3603, -1, 4142, 4140, 3602, -1, 4143, 4075, 4076, -1, 4143, 4076, 4141, -1, 4125, 4140, 4142, -1, 4125, 4141, 4140, -1, 4144, 3603, 3604, -1, 4144, 3604, 4139, -1, 4144, 4142, 3603, -1, 4130, 4074, 4075, -1, 4130, 4075, 4143, -1, 4124, 4143, 4141, -1, 4124, 4141, 4125, -1, 4126, 4139, 4122, -1, 4126, 4144, 4139, -1, 4126, 4125, 4142, -1, 4126, 4142, 4144, -1, 4128, 4073, 4074, -1, 4128, 4074, 4130, -1, 4131, 4143, 4124, -1, 4131, 4130, 4143, -1, 4115, 3240, 3258, -1, 4115, 3258, 4145, -1, 4119, 4145, 4146, -1, 4119, 4115, 4145, -1, 4088, 4146, 4147, -1, 4088, 4119, 4146, -1, 4089, 4147, 4148, -1, 4089, 4088, 4147, -1, 4099, 4148, 4149, -1, 4099, 4089, 4148, -1, 4102, 4149, 4150, -1, 4102, 4099, 4149, -1, 3526, 4150, 3527, -1, 3526, 4102, 4150, -1, 4151, 3382, 4138, -1, 4151, 3381, 3382, -1, 4152, 4138, 4136, -1, 4152, 4151, 4138, -1, 4153, 4136, 4133, -1, 4153, 4152, 4136, -1, 4154, 4133, 4123, -1, 4154, 4153, 4133, -1, 4155, 4123, 4122, -1, 4155, 4154, 4123, -1, 4156, 4122, 4139, -1, 4156, 4155, 4122, -1, 3511, 4139, 3509, -1, 3511, 4156, 4139, -1, 4157, 4158, 4159, -1, 4160, 4161, 4162, -1, 4157, 4163, 4164, -1, 4160, 4162, 4165, -1, 4157, 4166, 4163, -1, 4157, 4164, 4158, -1, 4167, 3630, 3631, -1, 4168, 4165, 4169, -1, 4167, 4170, 4171, -1, 4167, 4171, 4172, -1, 4168, 4169, 4173, -1, 4167, 3631, 4170, -1, 4174, 4159, 4175, -1, 4176, 3266, 3264, -1, 4174, 4172, 4166, -1, 4174, 4166, 4157, -1, 4176, 4173, 3266, -1, 4174, 4157, 4159, -1, 4177, 4175, 4178, -1, 4179, 4149, 4148, -1, 4177, 4178, 3516, -1, 4177, 3516, 3629, -1, 4177, 4174, 4175, -1, 4177, 3629, 3630, -1, 4177, 3630, 4167, -1, 4177, 4167, 4172, -1, 4179, 4148, 4180, -1, 4177, 4172, 4174, -1, 4181, 4180, 4161, -1, 4181, 4161, 4160, -1, 4182, 4165, 4168, -1, 4182, 4160, 4165, -1, 4183, 4168, 4173, -1, 4183, 4173, 4176, -1, 4184, 4150, 4149, -1, 4184, 4149, 4179, -1, 3634, 3527, 4150, -1, 4184, 3634, 4150, -1, 4185, 3264, 3269, -1, 4185, 4176, 3264, -1, 4186, 4180, 4181, -1, 4186, 4179, 4180, -1, 4187, 4181, 4160, -1, 4187, 4160, 4182, -1, 4188, 4182, 4168, -1, 4188, 4168, 4183, -1, 4189, 4176, 4185, -1, 4189, 4183, 4176, -1, 4190, 4179, 4186, -1, 4190, 3633, 3634, -1, 4190, 3634, 4184, -1, 4190, 4184, 4179, -1, 4191, 3269, 3267, -1, 4191, 3267, 4192, -1, 4191, 4185, 3269, -1, 4193, 4181, 4187, -1, 4193, 4186, 4181, -1, 4194, 4187, 4182, -1, 4194, 4182, 4188, -1, 4195, 4145, 3258, -1, 4163, 4188, 4183, -1, 4195, 3258, 3268, -1, 4195, 3268, 3263, -1, 4163, 4183, 4189, -1, 4162, 4146, 4145, -1, 4196, 4189, 4185, -1, 4196, 4192, 4197, -1, 4196, 4191, 4192, -1, 4196, 4185, 4191, -1, 4198, 4186, 4193, -1, 4162, 4145, 4195, -1, 4169, 3263, 3265, -1, 4198, 3632, 3633, -1, 4198, 4190, 4186, -1, 4198, 3633, 4190, -1, 4169, 4195, 3263, -1, 4171, 4187, 4194, -1, 4161, 4147, 4146, -1, 4171, 4193, 4187, -1, 4161, 4146, 4162, -1, 4166, 4194, 4188, -1, 4166, 4188, 4163, -1, 4165, 4195, 4169, -1, 4164, 4189, 4196, -1, 4164, 4163, 4189, -1, 4164, 4197, 4158, -1, 4165, 4162, 4195, -1, 4164, 4196, 4197, -1, 4173, 3265, 3266, -1, 4170, 3631, 3632, -1, 4170, 3632, 4198, -1, 4170, 4193, 4171, -1, 4173, 4169, 3265, -1, 4180, 4148, 4147, -1, 4170, 4198, 4193, -1, 4180, 4147, 4161, -1, 4172, 4171, 4194, -1, 4172, 4194, 4166, -1, 4199, 4200, 4201, -1, 4202, 4203, 4204, -1, 4202, 4205, 4203, -1, 4202, 4201, 4206, -1, 4202, 4206, 4205, -1, 4207, 4151, 4152, -1, 4207, 3381, 4151, -1, 4207, 3309, 3381, -1, 4207, 4152, 4208, -1, 4209, 4210, 4199, -1, 4209, 4208, 4210, -1, 4211, 4204, 4212, -1, 4211, 4202, 4204, -1, 4211, 4199, 4201, -1, 4211, 4201, 4202, -1, 4213, 3308, 3309, -1, 4213, 3309, 4207, -1, 4213, 4207, 4208, -1, 4213, 4208, 4209, -1, 4214, 4212, 4215, -1, 4214, 4211, 4212, -1, 4214, 4209, 4199, -1, 4214, 4199, 4211, -1, 4216, 4215, 3302, -1, 4216, 3302, 3307, -1, 4216, 3307, 3308, -1, 4216, 3308, 4213, -1, 4216, 4214, 4215, -1, 4216, 4213, 4209, -1, 4216, 4209, 4214, -1, 4217, 4156, 3511, -1, 4217, 3511, 3605, -1, 4218, 4155, 4156, -1, 4218, 4156, 4217, -1, 4219, 3605, 3606, -1, 4219, 4217, 3605, -1, 4200, 4154, 4155, -1, 4200, 4155, 4218, -1, 4206, 4217, 4219, -1, 4206, 4218, 4217, -1, 4220, 3606, 3607, -1, 4220, 3607, 3513, -1, 4220, 3513, 4221, -1, 4220, 4221, 4222, -1, 4220, 4219, 3606, -1, 4210, 4153, 4154, -1, 4210, 4154, 4200, -1, 4201, 4200, 4218, -1, 4201, 4218, 4206, -1, 4205, 4222, 4203, -1, 4205, 4219, 4220, -1, 4205, 4220, 4222, -1, 4205, 4206, 4219, -1, 4208, 4152, 4153, -1, 4208, 4153, 4210, -1, 4199, 4210, 4200, -1, 4192, 3267, 3285, -1, 4192, 3285, 4223, -1, 4197, 4223, 4224, -1, 4197, 4192, 4223, -1, 4158, 4224, 4225, -1, 4158, 4197, 4224, -1, 4159, 4225, 4226, -1, 4159, 4158, 4225, -1, 4175, 4226, 4227, -1, 4175, 4159, 4226, -1, 4178, 4227, 4228, -1, 4178, 4175, 4227, -1, 3516, 4228, 3519, -1, 3516, 4178, 4228, -1, 4229, 3302, 4215, -1, 4229, 3298, 3302, -1, 4230, 4215, 4212, -1, 4230, 4229, 4215, -1, 4231, 4212, 4204, -1, 4231, 4230, 4212, -1, 4232, 4204, 4203, -1, 4232, 4231, 4204, -1, 4233, 4203, 4222, -1, 4233, 4232, 4203, -1, 4234, 4222, 4221, -1, 4234, 4233, 4222, -1, 3515, 4221, 3513, -1, 3515, 4234, 4221, -1, 4235, 4236, 4237, -1, 4235, 4238, 4236, -1, 4239, 4227, 4226, -1, 4239, 4240, 4227, -1, 4239, 4237, 4241, -1, 4239, 4241, 4240, -1, 4242, 3297, 3298, -1, 4242, 4229, 4230, -1, 4242, 3298, 4229, -1, 4242, 4230, 4243, -1, 4244, 4243, 4238, -1, 4244, 4238, 4235, -1, 4245, 4226, 4225, -1, 4245, 4239, 4226, -1, 4245, 4235, 4237, -1, 4245, 4237, 4239, -1, 4246, 3296, 3297, -1, 4246, 3297, 4242, -1, 4246, 4242, 4243, -1, 4246, 4243, 4244, -1, 4247, 4225, 4224, -1, 4247, 4245, 4225, -1, 4247, 4244, 4235, -1, 4247, 4235, 4245, -1, 4248, 4224, 4223, -1, 4248, 3294, 3296, -1, 4248, 4223, 3294, -1, 4248, 3296, 4246, -1, 4248, 4247, 4224, -1, 4248, 4246, 4244, -1, 4248, 4244, 4247, -1, 3285, 3294, 4223, -1, 4249, 4234, 3515, -1, 4249, 3515, 3608, -1, 4250, 4233, 4234, -1, 4250, 4234, 4249, -1, 4251, 3608, 3609, -1, 4251, 3609, 3610, -1, 4251, 4249, 3608, -1, 4236, 4232, 4233, -1, 4236, 4233, 4250, -1, 4241, 4250, 4249, -1, 4241, 4249, 4251, -1, 4252, 3519, 4228, -1, 4252, 3610, 3519, -1, 4252, 4251, 3610, -1, 4238, 4231, 4232, -1, 4238, 4232, 4236, -1, 4237, 4250, 4241, -1, 4237, 4236, 4250, -1, 4240, 4228, 4227, -1, 4240, 4241, 4251, -1, 4240, 4252, 4228, -1, 4240, 4251, 4252, -1, 4243, 4230, 4231, -1, 4243, 4231, 4238, -1, 3360, 3367, 4253, -1, 3360, 4253, 4254, -1, 3358, 4254, 4255, -1, 3358, 3360, 4254, -1, 3356, 4255, 4256, -1, 3356, 3358, 4255, -1, 3355, 4256, 4257, -1, 3355, 3356, 4256, -1, 3354, 4257, 4258, -1, 3354, 3355, 4257, -1, 3353, 4258, 4259, -1, 3353, 3354, 4258, -1, 3348, 4259, 4260, -1, 3348, 3353, 4259, -1, 3327, 4260, 4261, -1, 3348, 4260, 3327, -1, 3327, 4261, 4262, -1, 3324, 4262, 4263, -1, 3324, 3327, 4262, -1, 3322, 4263, 4264, -1, 3322, 3324, 4263, -1, 3320, 4264, 4265, -1, 3320, 3322, 4264, -1, 3319, 3320, 4265, -1, 3319, 4266, 3318, -1, 4265, 4266, 3319, -1, 3318, 4266, 4267, -1, 3321, 4267, 4268, -1, 3321, 3318, 4267, -1, 3323, 4268, 4269, -1, 3323, 3321, 4268, -1, 3325, 4269, 4270, -1, 3325, 3323, 4269, -1, 3326, 3325, 4270, -1, 3326, 4271, 3330, -1, 4270, 4271, 3326, -1, 3331, 3330, 4271, -1, 3331, 4271, 4272, -1, 3332, 4272, 4273, -1, 3332, 3331, 4272, -1, 3335, 4273, 4274, -1, 3335, 3332, 4273, -1, 3336, 4274, 4275, -1, 3336, 3335, 4274, -1, 3336, 4276, 3342, -1, 4275, 4276, 3336, -1, 3343, 3342, 4276, -1, 3343, 4276, 4277, -1, 3344, 4277, 4278, -1, 3344, 3343, 4277, -1, 3345, 4278, 4279, -1, 3345, 3344, 4278, -1, 3346, 4279, 4280, -1, 3346, 3345, 4279, -1, 4280, 4281, 3346, -1, 4281, 3371, 3346, -1, 3371, 4281, 4282, -1, 3372, 4282, 4283, -1, 3372, 3371, 4282, -1, 3373, 4283, 4284, -1, 3373, 3372, 4283, -1, 3374, 4284, 4285, -1, 3374, 3373, 4284, -1, 3370, 3374, 4285, -1, 3370, 4286, 3363, -1, 4285, 4286, 3370, -1, 3361, 3363, 4286, -1, 3361, 4286, 4287, -1, 3364, 4287, 4288, -1, 3364, 3361, 4287, -1, 3365, 4288, 4289, -1, 3365, 3364, 4288, -1, 3366, 4289, 4290, -1, 3366, 3365, 4289, -1, 4290, 3367, 3366, -1, 4253, 3367, 4290, -1, 4291, 4292, 4293, -1, 4294, 4295, 4296, -1, 3225, 4295, 4294, -1, 4296, 4295, 4297, -1, 4297, 4295, 4298, -1, 4299, 4300, 4301, -1, 4292, 4302, 4293, -1, 3225, 4302, 4295, -1, 4303, 4304, 4305, -1, 4293, 4302, 3225, -1, 4300, 4306, 4301, -1, 4303, 4307, 4304, -1, 4303, 4308, 4307, -1, 4306, 4309, 4301, -1, 4301, 3221, 4303, -1, 4303, 3221, 4308, -1, 4309, 3221, 4301, -1, 4310, 4311, 4312, -1, 4312, 4311, 4313, -1, 4313, 4311, 4314, -1, 4308, 3218, 4310, -1, 3221, 3218, 4308, -1, 4310, 3218, 4311, -1, 3218, 4315, 4311, -1, 4315, 4316, 4317, -1, 4315, 4318, 4316, -1, 3218, 4319, 4315, -1, 4315, 4319, 4318, -1, 4320, 4321, 4322, -1, 4323, 3223, 4309, -1, 4309, 3223, 3221, -1, 4324, 4325, 4326, -1, 4326, 4325, 4327, -1, 4327, 4325, 4321, -1, 4322, 4325, 4323, -1, 4323, 4325, 3223, -1, 4321, 4325, 4322, -1, 3218, 3225, 4319, -1, 3223, 4293, 3225, -1, 4325, 4293, 3223, -1, 3225, 4294, 4319, -1, 4328, 4291, 4293, -1, 4329, 4330, 4331, -1, 4332, 4331, 4333, -1, 4332, 4329, 4331, -1, 4334, 4333, 4335, -1, 4334, 4332, 4333, -1, 4336, 4335, 4337, -1, 4336, 4334, 4335, -1, 4338, 4337, 4339, -1, 4338, 4336, 4337, -1, 4340, 4338, 4339, -1, 4341, 4342, 4343, -1, 4341, 4339, 4342, -1, 4341, 4340, 4339, -1, 4344, 4341, 4343, -1, 4345, 4346, 4347, -1, 4345, 4347, 4348, -1, 4349, 4350, 4351, -1, 4349, 4348, 4350, -1, 4349, 4345, 4348, -1, 4352, 4351, 4353, -1, 4352, 4349, 4351, -1, 4354, 4352, 4353, -1, 4355, 4356, 4357, -1, 4355, 4357, 4358, -1, 4359, 4358, 4360, -1, 4359, 4355, 4358, -1, 4361, 4360, 4362, -1, 4361, 4359, 4360, -1, 4363, 4362, 4364, -1, 4363, 4361, 4362, -1, 4365, 4366, 4367, -1, 4365, 4367, 4368, -1, 4369, 4368, 4370, -1, 4369, 4365, 4368, -1, 4371, 4370, 4372, -1, 4371, 4369, 4370, -1, 4373, 4372, 4374, -1, 4373, 4371, 4372, -1, 4375, 4376, 4377, -1, 4375, 4377, 4378, -1, 4379, 4378, 4380, -1, 4379, 4375, 4378, -1, 4381, 4380, 4382, -1, 4381, 4379, 4380, -1, 4383, 4382, 4384, -1, 4383, 4381, 4382, -1, 4374, 4383, 4384, -1, 4374, 4384, 4373, -1, 4366, 4357, 4356, -1, 4367, 4366, 4356, -1, 4385, 4386, 4387, -1, 4385, 4387, 4388, -1, 4389, 4388, 4390, -1, 4389, 4385, 4388, -1, 4391, 4390, 4392, -1, 4391, 4389, 4390, -1, 4393, 4392, 4394, -1, 4393, 4391, 4392, -1, 4393, 4363, 4364, -1, 4394, 4363, 4393, -1, 4395, 4396, 4397, -1, 4395, 4397, 4398, -1, 4399, 4398, 4400, -1, 4399, 4395, 4398, -1, 4401, 4400, 4402, -1, 4401, 4399, 4400, -1, 4403, 4402, 4404, -1, 4403, 4401, 4402, -1, 4386, 4396, 4387, -1, 4397, 4396, 4386, -1, 4403, 4404, 4354, -1, 4353, 4403, 4354, -1, 4330, 4347, 4346, -1, 4330, 4329, 4347, -1, 4377, 4344, 4343, -1, 4376, 4344, 4377, -1, 3282, 4405, 4406, -1, 3281, 4406, 4407, -1, 3281, 3282, 4406, -1, 3278, 4407, 4408, -1, 3278, 3281, 4407, -1, 3277, 4408, 4409, -1, 3277, 3278, 4408, -1, 3276, 3277, 4409, -1, 3256, 3276, 4410, -1, 3276, 4409, 4410, -1, 3256, 4410, 4411, -1, 3254, 4411, 4412, -1, 3254, 3256, 4411, -1, 3252, 4412, 4413, -1, 3252, 3254, 4412, -1, 3250, 4413, 4414, -1, 3250, 3252, 4413, -1, 3248, 3250, 4414, -1, 3248, 4415, 3247, -1, 4414, 4415, 3248, -1, 3247, 4415, 4416, -1, 3249, 4416, 4417, -1, 3249, 3247, 4416, -1, 3251, 4417, 4418, -1, 3251, 3249, 4417, -1, 3253, 4418, 4419, -1, 3253, 3251, 4418, -1, 3255, 3253, 4419, -1, 3257, 4419, 4420, -1, 3255, 4419, 3257, -1, 3257, 4420, 4421, -1, 3259, 4421, 4422, -1, 3259, 3257, 4421, -1, 3260, 4422, 4423, -1, 3260, 3259, 4422, -1, 3261, 4423, 4424, -1, 3261, 3260, 4423, -1, 3262, 3261, 4424, -1, 3262, 4425, 3270, -1, 4424, 4425, 3262, -1, 3270, 4425, 4426, -1, 3271, 4426, 4427, -1, 3271, 3270, 4426, -1, 3272, 4427, 4428, -1, 3272, 3271, 4427, -1, 3273, 4428, 4429, -1, 3273, 3272, 4428, -1, 3274, 3273, 4429, -1, 4429, 3295, 3274, -1, 4430, 3295, 4429, -1, 3301, 3295, 4430, -1, 3301, 4430, 4431, -1, 3303, 4431, 4432, -1, 3303, 3301, 4431, -1, 3304, 4432, 4433, -1, 3304, 3303, 4432, -1, 3305, 4433, 4434, -1, 3305, 3304, 4433, -1, 3306, 4434, 4435, -1, 3306, 3305, 4434, -1, 3300, 4435, 4436, -1, 3300, 3306, 4435, -1, 3299, 4436, 4437, -1, 3299, 3300, 4436, -1, 4437, 3291, 3299, -1, 4438, 3291, 4437, -1, 3291, 4438, 4439, -1, 3290, 4439, 4440, -1, 3290, 3291, 4439, -1, 3292, 4440, 4441, -1, 3292, 3290, 4440, -1, 3293, 4441, 4442, -1, 3293, 3292, 4441, -1, 3287, 3293, 4442, -1, 3287, 4405, 3282, -1, 4442, 4405, 3287, -1, 4443, 4444, 4445, -1, 4445, 4446, 4447, -1, 4445, 4448, 4446, -1, 4444, 4449, 4445, -1, 4445, 4449, 4448, -1, 4450, 4451, 4452, -1, 4450, 4453, 4451, -1, 4450, 4454, 4453, -1, 4455, 4456, 4457, -1, 4457, 4456, 4458, -1, 4458, 4456, 4459, -1, 4459, 3229, 4450, -1, 4456, 3229, 4459, -1, 4450, 3229, 4454, -1, 4460, 4461, 4462, -1, 4462, 4461, 4463, -1, 4463, 4461, 4464, -1, 4454, 3232, 4460, -1, 3229, 3232, 4454, -1, 4460, 3232, 4461, -1, 3232, 4465, 4461, -1, 4465, 4466, 4467, -1, 4467, 4466, 4468, -1, 4468, 4466, 4469, -1, 3232, 4466, 4465, -1, 4470, 4471, 4472, -1, 4471, 4473, 4472, -1, 4473, 4474, 4472, -1, 4474, 3227, 4472, -1, 4472, 3227, 4456, -1, 4456, 3227, 3229, -1, 4474, 4475, 3227, -1, 4476, 4477, 4475, -1, 4477, 4478, 4475, -1, 4475, 4479, 3227, -1, 4478, 4479, 4475, -1, 4479, 3230, 3227, -1, 3232, 3230, 4466, -1, 3230, 4445, 4466, -1, 4479, 4480, 3230, -1, 3230, 4480, 4445, -1, 4480, 4443, 4445, -1, 4481, 4482, 4483, -1, 4484, 4483, 4485, -1, 4484, 4481, 4483, -1, 4486, 4485, 4487, -1, 4486, 4484, 4485, -1, 4488, 4487, 4489, -1, 4488, 4486, 4487, -1, 4490, 4488, 4489, -1, 4491, 4492, 4493, -1, 4491, 4493, 4494, -1, 4495, 4494, 4496, -1, 4495, 4491, 4494, -1, 4497, 4496, 4498, -1, 4497, 4495, 4496, -1, 4499, 4498, 4500, -1, 4499, 4497, 4498, -1, 4501, 4502, 4503, -1, 4504, 4503, 4505, -1, 4504, 4501, 4503, -1, 4506, 4505, 4507, -1, 4506, 4504, 4505, -1, 4508, 4507, 4509, -1, 4508, 4506, 4507, -1, 4510, 4508, 4509, -1, 4511, 4512, 4513, -1, 4514, 4513, 4515, -1, 4514, 4511, 4513, -1, 4516, 4515, 4517, -1, 4516, 4514, 4515, -1, 4518, 4517, 4519, -1, 4518, 4516, 4517, -1, 4520, 4518, 4519, -1, 4521, 4522, 4523, -1, 4524, 4521, 4523, -1, 4525, 4526, 4527, -1, 4525, 4523, 4526, -1, 4525, 4524, 4523, -1, 4528, 4525, 4527, -1, 4529, 4527, 4530, -1, 4529, 4528, 4527, -1, 4529, 4520, 4519, -1, 4529, 4530, 4520, -1, 4531, 4532, 4533, -1, 4534, 4533, 4535, -1, 4534, 4531, 4533, -1, 4536, 4535, 4537, -1, 4536, 4534, 4535, -1, 4538, 4537, 4539, -1, 4538, 4536, 4537, -1, 4540, 4538, 4539, -1, 4531, 4522, 4521, -1, 4531, 4521, 4532, -1, 4539, 4509, 4540, -1, 4510, 4509, 4539, -1, 4493, 4502, 4501, -1, 4492, 4502, 4493, -1, 4541, 4542, 4543, -1, 4541, 4543, 4544, -1, 4545, 4544, 4546, -1, 4545, 4541, 4544, -1, 4547, 4546, 4548, -1, 4547, 4545, 4546, -1, 4549, 4548, 4550, -1, 4549, 4547, 4548, -1, 4551, 4550, 4552, -1, 4551, 4549, 4550, -1, 4553, 4552, 4554, -1, 4553, 4551, 4552, -1, 4555, 4554, 4556, -1, 4555, 4553, 4554, -1, 4542, 4499, 4500, -1, 4542, 4500, 4543, -1, 4489, 4556, 4490, -1, 4489, 4555, 4556, -1, 4512, 4482, 4481, -1, 4511, 4482, 4512, -1, 4529, 4519, 4419, -1, 4419, 4519, 4420, -1, 4513, 4512, 4424, -1, 4513, 4424, 4423, -1, 4515, 4423, 4422, -1, 4515, 4513, 4423, -1, 4517, 4422, 4421, -1, 4517, 4421, 4420, -1, 4517, 4515, 4422, -1, 4519, 4517, 4420, -1, 4528, 4529, 4419, -1, 4528, 4419, 4418, -1, 4528, 4418, 4417, -1, 4525, 4417, 4416, -1, 4525, 4528, 4417, -1, 4524, 4416, 4415, -1, 4524, 4525, 4416, -1, 4521, 4524, 4415, -1, 4512, 4481, 4424, -1, 4424, 4481, 4425, -1, 4414, 4532, 4415, -1, 4532, 4521, 4415, -1, 4490, 4429, 4428, -1, 4488, 4428, 4427, -1, 4488, 4490, 4428, -1, 4486, 4427, 4426, -1, 4486, 4488, 4427, -1, 4484, 4486, 4426, -1, 4481, 4426, 4425, -1, 4481, 4484, 4426, -1, 4532, 4414, 4413, -1, 4533, 4532, 4413, -1, 4535, 4413, 4412, -1, 4535, 4533, 4413, -1, 4537, 4412, 4411, -1, 4537, 4535, 4412, -1, 4539, 4411, 4410, -1, 4539, 4537, 4411, -1, 4490, 4556, 4429, -1, 4429, 4556, 4430, -1, 4409, 4539, 4410, -1, 4510, 4539, 4409, -1, 4544, 4543, 4437, -1, 4544, 4437, 4436, -1, 4544, 4436, 4435, -1, 4546, 4435, 4434, -1, 4546, 4544, 4435, -1, 4548, 4434, 4433, -1, 4548, 4546, 4434, -1, 4550, 4433, 4432, -1, 4550, 4548, 4433, -1, 4552, 4432, 4431, -1, 4552, 4550, 4432, -1, 4554, 4552, 4431, -1, 4556, 4431, 4430, -1, 4556, 4554, 4431, -1, 4510, 4409, 4408, -1, 4508, 4510, 4408, -1, 4506, 4408, 4407, -1, 4506, 4407, 4406, -1, 4506, 4508, 4408, -1, 4504, 4406, 4405, -1, 4504, 4506, 4406, -1, 4501, 4504, 4405, -1, 4543, 4500, 4437, -1, 4437, 4500, 4438, -1, 4442, 4493, 4405, -1, 4493, 4501, 4405, -1, 4494, 4493, 4442, -1, 4494, 4442, 4441, -1, 4496, 4441, 4440, -1, 4496, 4494, 4441, -1, 4498, 4440, 4439, -1, 4498, 4439, 4438, -1, 4498, 4496, 4440, -1, 4500, 4498, 4438, -1, 4397, 4386, 4271, -1, 4397, 4271, 4270, -1, 4393, 4275, 4274, -1, 4391, 4274, 4273, -1, 4391, 4393, 4274, -1, 4389, 4273, 4272, -1, 4389, 4391, 4273, -1, 4385, 4272, 4271, -1, 4385, 4389, 4272, -1, 4386, 4385, 4271, -1, 4398, 4397, 4270, -1, 4398, 4270, 4269, -1, 4398, 4269, 4268, -1, 4400, 4268, 4267, -1, 4400, 4398, 4268, -1, 4402, 4267, 4266, -1, 4402, 4400, 4267, -1, 4404, 4402, 4266, -1, 4364, 4276, 4275, -1, 4393, 4364, 4275, -1, 4354, 4404, 4266, -1, 4354, 4266, 4265, -1, 4358, 4357, 4280, -1, 4358, 4280, 4279, -1, 4360, 4279, 4278, -1, 4360, 4358, 4279, -1, 4362, 4278, 4277, -1, 4362, 4360, 4278, -1, 4364, 4277, 4276, -1, 4364, 4362, 4277, -1, 4354, 4265, 4264, -1, 4352, 4354, 4264, -1, 4349, 4264, 4263, -1, 4349, 4352, 4264, -1, 4345, 4263, 4262, -1, 4345, 4349, 4263, -1, 4346, 4262, 4261, -1, 4346, 4345, 4262, -1, 4357, 4366, 4281, -1, 4357, 4281, 4280, -1, 4260, 4346, 4261, -1, 4330, 4346, 4260, -1, 4373, 4285, 4284, -1, 4371, 4284, 4283, -1, 4371, 4373, 4284, -1, 4369, 4283, 4282, -1, 4369, 4371, 4283, -1, 4365, 4282, 4281, -1, 4365, 4369, 4282, -1, 4366, 4365, 4281, -1, 4331, 4330, 4260, -1, 4331, 4260, 4259, -1, 4333, 4259, 4258, -1, 4333, 4331, 4259, -1, 4335, 4258, 4257, -1, 4335, 4333, 4258, -1, 4337, 4257, 4256, -1, 4337, 4335, 4257, -1, 4339, 4256, 4255, -1, 4339, 4337, 4256, -1, 4342, 4255, 4254, -1, 4342, 4254, 4253, -1, 4342, 4339, 4255, -1, 4343, 4342, 4253, -1, 4384, 4286, 4285, -1, 4373, 4384, 4285, -1, 4377, 4343, 4253, -1, 4377, 4253, 4290, -1, 4378, 4377, 4290, -1, 4378, 4290, 4289, -1, 4380, 4289, 4288, -1, 4380, 4378, 4289, -1, 4382, 4288, 4287, -1, 4382, 4287, 4286, -1, 4382, 4380, 4288, -1, 4384, 4382, 4286, -1, 4492, 4475, 4502, -1, 4475, 4474, 4502, -1, 4503, 4502, 4474, -1, 4503, 4474, 4473, -1, 4503, 4473, 4471, -1, 4505, 4471, 4470, -1, 4505, 4503, 4471, -1, 4507, 4470, 4472, -1, 4507, 4505, 4470, -1, 4509, 4507, 4472, -1, 4497, 4499, 4479, -1, 4497, 4479, 4478, -1, 4497, 4478, 4477, -1, 4495, 4477, 4476, -1, 4495, 4497, 4477, -1, 4491, 4476, 4475, -1, 4491, 4495, 4476, -1, 4492, 4491, 4475, -1, 4472, 4456, 4509, -1, 4509, 4456, 4540, -1, 4499, 4542, 4480, -1, 4499, 4480, 4479, -1, 4540, 4456, 4455, -1, 4538, 4455, 4457, -1, 4538, 4540, 4455, -1, 4536, 4457, 4458, -1, 4536, 4538, 4457, -1, 4534, 4458, 4459, -1, 4534, 4536, 4458, -1, 4531, 4534, 4459, -1, 4555, 4445, 4447, -1, 4553, 4555, 4447, -1, 4551, 4447, 4446, -1, 4551, 4553, 4447, -1, 4549, 4446, 4448, -1, 4549, 4551, 4446, -1, 4547, 4448, 4449, -1, 4547, 4549, 4448, -1, 4545, 4449, 4444, -1, 4545, 4547, 4449, -1, 4541, 4444, 4443, -1, 4541, 4443, 4480, -1, 4541, 4545, 4444, -1, 4542, 4541, 4480, -1, 4522, 4531, 4459, -1, 4522, 4459, 4450, -1, 4489, 4445, 4555, -1, 4466, 4445, 4489, -1, 4523, 4522, 4450, -1, 4523, 4450, 4452, -1, 4526, 4452, 4451, -1, 4526, 4523, 4452, -1, 4527, 4451, 4453, -1, 4527, 4453, 4454, -1, 4527, 4526, 4451, -1, 4530, 4527, 4454, -1, 4483, 4482, 4465, -1, 4483, 4465, 4467, -1, 4483, 4467, 4468, -1, 4485, 4468, 4469, -1, 4485, 4483, 4468, -1, 4487, 4485, 4469, -1, 4489, 4469, 4466, -1, 4489, 4487, 4469, -1, 4520, 4530, 4454, -1, 4520, 4454, 4460, -1, 4511, 4461, 4482, -1, 4461, 4465, 4482, -1, 4518, 4520, 4460, -1, 4518, 4460, 4462, -1, 4518, 4462, 4463, -1, 4516, 4463, 4464, -1, 4516, 4518, 4463, -1, 4514, 4464, 4461, -1, 4514, 4516, 4464, -1, 4511, 4514, 4461, -1, 4311, 4315, 4394, -1, 4394, 4315, 4363, -1, 4361, 4363, 4315, -1, 4361, 4315, 4317, -1, 4361, 4317, 4316, -1, 4359, 4361, 4316, -1, 4355, 4316, 4318, -1, 4355, 4359, 4316, -1, 4356, 4318, 4319, -1, 4356, 4355, 4318, -1, 4388, 4387, 4310, -1, 4388, 4310, 4312, -1, 4388, 4312, 4313, -1, 4390, 4313, 4314, -1, 4390, 4388, 4313, -1, 4392, 4314, 4311, -1, 4392, 4390, 4314, -1, 4394, 4392, 4311, -1, 4367, 4356, 4319, -1, 4367, 4319, 4294, -1, 4396, 4310, 4387, -1, 4308, 4310, 4396, -1, 4368, 4367, 4294, -1, 4368, 4294, 4296, -1, 4370, 4296, 4297, -1, 4370, 4368, 4296, -1, 4372, 4297, 4298, -1, 4372, 4298, 4295, -1, 4372, 4370, 4297, -1, 4374, 4372, 4295, -1, 4401, 4403, 4303, -1, 4401, 4303, 4305, -1, 4399, 4305, 4304, -1, 4399, 4401, 4305, -1, 4395, 4304, 4307, -1, 4395, 4307, 4308, -1, 4395, 4399, 4304, -1, 4396, 4395, 4308, -1, 4383, 4374, 4295, -1, 4383, 4295, 4302, -1, 4403, 4353, 4301, -1, 4403, 4301, 4303, -1, 4381, 4383, 4302, -1, 4381, 4302, 4292, -1, 4381, 4292, 4291, -1, 4379, 4291, 4328, -1, 4379, 4381, 4291, -1, 4375, 4328, 4293, -1, 4375, 4379, 4328, -1, 4376, 4375, 4293, -1, 4348, 4347, 4309, -1, 4348, 4309, 4306, -1, 4350, 4306, 4300, -1, 4350, 4348, 4306, -1, 4351, 4300, 4299, -1, 4351, 4299, 4301, -1, 4351, 4350, 4300, -1, 4353, 4351, 4301, -1, 4293, 4325, 4376, -1, 4376, 4325, 4344, -1, 4347, 4329, 4323, -1, 4347, 4323, 4309, -1, 4341, 4344, 4325, -1, 4341, 4325, 4324, -1, 4341, 4324, 4326, -1, 4340, 4326, 4327, -1, 4340, 4341, 4326, -1, 4338, 4327, 4321, -1, 4338, 4340, 4327, -1, 4336, 4321, 4320, -1, 4336, 4338, 4321, -1, 4334, 4320, 4322, -1, 4334, 4336, 4320, -1, 4332, 4322, 4323, -1, 4332, 4334, 4322, -1, 4329, 4332, 4323, -1, 3566, 4557, 4558, -1, 3565, 4557, 3566, -1, 3563, 4558, 4559, -1, 3566, 4558, 3563, -1, 4559, 3564, 3563, -1, 4560, 3564, 4559, -1, 4560, 3565, 3564, -1, 4557, 3565, 4560, -1, 4559, 3233, 4560, -1, 4560, 3233, 3226, -1, 3228, 4557, 3226, -1, 3226, 4557, 4560, -1, 4559, 4558, 3233, -1, 4557, 3231, 4558, -1, 3228, 3231, 4557, -1, 4558, 3231, 3233, -1, 3235, 4561, 4562, -1, 3238, 4561, 3235, -1, 4562, 3234, 3235, -1, 4563, 3234, 4562, -1, 4563, 3236, 3234, -1, 4564, 3236, 4563, -1, 3238, 4564, 4561, -1, 3236, 4564, 3238, -1, 3219, 4562, 3220, -1, 4563, 4562, 3219, -1, 3219, 4564, 4563, -1, 3219, 3222, 4564, -1, 4562, 4561, 3220, -1, 3222, 4561, 4564, -1, 4561, 3224, 3220, -1, 3222, 3224, 4561, -1, 3410, 3583, 3405, -1, 3581, 3583, 3410, -1, 3586, 3400, 3402, -1, 3586, 3585, 3400, -1, 3392, 4565, 3433, -1, 3213, 4565, 3392, -1, 3214, 3216, 3212, -1, 3552, 4566, 3216, -1, 4566, 4567, 3216, -1, 4567, 4568, 3216, -1, 4568, 4569, 3216, -1, 4569, 4570, 3216, -1, 3216, 4571, 3212, -1, 4570, 4571, 3216, -1, 4571, 4565, 3212, -1, 4565, 3213, 3212, -1, 3435, 3394, 3207, -1, 4572, 3394, 3435, -1, 3562, 3423, 3395, -1, 4573, 3560, 3562, -1, 4574, 4573, 3562, -1, 4575, 4574, 3562, -1, 4576, 4575, 3562, -1, 4577, 4576, 3562, -1, 4578, 3562, 3395, -1, 4578, 4577, 3562, -1, 4572, 4578, 3395, -1, 3394, 4572, 3395, -1, 3711, 3583, 3586, -1, 3716, 3583, 3711, -1, 3206, 3553, 3580, -1, 3205, 3553, 3206, -1, 3391, 3558, 3390, -1, 3391, 3591, 3558, -1, 4579, 4580, 4581, -1, 4579, 4582, 4580, -1, 4583, 4582, 4579, -1, 4583, 4584, 4582, -1, 4585, 4586, 4584, -1, 4585, 4584, 4583, -1, 4585, 3730, 4586, -1, 4587, 3728, 3730, -1, 4587, 3730, 4585, -1, 4587, 4585, 3728, -1, 4588, 3568, 3579, -1, 4588, 4581, 3568, -1, 3732, 3445, 4589, -1, 4590, 4579, 4581, -1, 4590, 4581, 4588, -1, 4591, 4583, 4579, -1, 4591, 4579, 4590, -1, 4592, 4585, 4583, -1, 4592, 3728, 4585, -1, 4592, 4583, 4591, -1, 4593, 3726, 3728, -1, 4593, 3728, 4592, -1, 4593, 4592, 3726, -1, 4594, 3579, 3576, -1, 4594, 3576, 3572, -1, 4594, 4588, 3579, -1, 4595, 4594, 3572, -1, 4595, 4590, 4588, -1, 4595, 4588, 4594, -1, 4596, 4590, 4595, -1, 4596, 4591, 4590, -1, 4597, 4591, 4596, -1, 4597, 3726, 4592, -1, 4597, 4592, 4591, -1, 4598, 3726, 4597, -1, 4599, 3724, 3726, -1, 4599, 3726, 4598, -1, 4600, 3572, 3571, -1, 4601, 3572, 4600, -1, 4601, 4595, 3572, -1, 4601, 4600, 3571, -1, 4602, 4595, 4601, -1, 4602, 4601, 3571, -1, 4602, 4596, 4595, -1, 4603, 4602, 3571, -1, 4603, 4596, 4602, -1, 4603, 4597, 4596, -1, 4604, 4598, 4597, -1, 4604, 4597, 4603, -1, 4605, 3722, 3724, -1, 4605, 3724, 4599, -1, 4605, 4599, 4598, -1, 4605, 4598, 4604, -1, 4606, 3571, 3573, -1, 4607, 4608, 4609, -1, 4607, 3571, 4606, -1, 4610, 3573, 3574, -1, 4610, 4611, 4612, -1, 4610, 3574, 4611, -1, 4610, 4606, 3573, -1, 4613, 4609, 4614, -1, 4613, 4607, 4609, -1, 4613, 3571, 4607, -1, 4615, 4612, 4608, -1, 4615, 4610, 4612, -1, 4615, 4607, 4606, -1, 4615, 4606, 4610, -1, 4615, 4608, 4607, -1, 4616, 4614, 4617, -1, 4616, 4603, 3571, -1, 4580, 4618, 3567, -1, 4580, 3567, 3569, -1, 4616, 3571, 4613, -1, 4580, 3569, 3568, -1, 4616, 4613, 4614, -1, 4619, 4603, 4616, -1, 4619, 4617, 4620, -1, 4619, 4604, 4603, -1, 4619, 4616, 4617, -1, 4582, 4618, 4580, -1, 4621, 4622, 3722, -1, 4621, 4620, 4622, -1, 4584, 4623, 4618, -1, 4621, 3722, 4605, -1, 4621, 4605, 4604, -1, 4584, 4618, 4582, -1, 4621, 4619, 4620, -1, 4621, 4604, 4619, -1, 4586, 4589, 4623, -1, 4586, 3732, 4589, -1, 4586, 4623, 4584, -1, 4624, 3732, 4586, -1, 4624, 4586, 3730, -1, 4625, 3730, 3732, -1, 4625, 4624, 3730, -1, 4625, 3732, 4624, -1, 4581, 4580, 3568, -1, 3445, 3465, 4626, -1, 4589, 3445, 4626, -1, 4623, 4626, 4627, -1, 4623, 4589, 4626, -1, 4618, 4627, 4628, -1, 4618, 4623, 4627, -1, 3567, 4628, 3584, -1, 3567, 4618, 4628, -1, 4629, 4630, 4631, -1, 4632, 3593, 3589, -1, 4632, 4633, 3593, -1, 4634, 4635, 4633, -1, 4634, 4633, 4632, -1, 4636, 4635, 4634, -1, 4636, 3772, 4637, -1, 4636, 4637, 4635, -1, 4638, 3774, 3772, -1, 4638, 4636, 3774, -1, 4638, 3772, 4636, -1, 4639, 3589, 3587, -1, 4639, 4632, 3589, -1, 4640, 4634, 4632, -1, 4640, 4632, 4639, -1, 4641, 3774, 4636, -1, 4641, 4636, 4634, -1, 4641, 4634, 4640, -1, 4642, 3775, 3774, -1, 4642, 3774, 4641, -1, 4642, 4641, 3775, -1, 4643, 3587, 3588, -1, 4643, 4639, 3587, -1, 4644, 4639, 4643, -1, 4644, 4643, 3588, -1, 4644, 4640, 4639, -1, 4645, 4644, 3588, -1, 4645, 4640, 4644, -1, 4645, 3588, 3777, -1, 4645, 3775, 4641, -1, 4645, 4641, 4640, -1, 4646, 4645, 3777, -1, 4646, 3775, 4645, -1, 4646, 3777, 3775, -1, 4628, 3588, 3584, -1, 4627, 3777, 3588, -1, 4627, 3588, 4628, -1, 4626, 3777, 4627, -1, 3465, 3777, 4626, -1, 4647, 4648, 3598, -1, 4647, 4649, 4648, -1, 4650, 3598, 3595, -1, 4650, 4647, 3598, -1, 4651, 4652, 4649, -1, 4651, 4647, 4650, -1, 4651, 4649, 4647, -1, 4653, 4654, 4652, -1, 4653, 4652, 4651, -1, 4631, 4655, 4654, -1, 4631, 4654, 4653, -1, 4630, 4656, 4655, -1, 4630, 3768, 4656, -1, 4630, 4655, 4631, -1, 4633, 3595, 3593, -1, 4633, 4650, 3595, -1, 4635, 4651, 4650, -1, 4635, 4650, 4633, -1, 4637, 4653, 4651, -1, 4637, 4651, 4635, -1, 4657, 4637, 3772, -1, 4657, 4631, 4653, -1, 4657, 4653, 4637, -1, 4629, 3772, 3770, -1, 4629, 3770, 3768, -1, 4629, 4631, 4657, -1, 4629, 4657, 3772, -1, 4629, 3768, 4630, -1, 3791, 3496, 3767, -1, 4658, 3778, 3471, -1, 4659, 3778, 4658, -1, 4660, 3778, 4659, -1, 3491, 3779, 4661, -1, 4662, 3791, 3767, -1, 4663, 4662, 3789, -1, 4663, 3791, 4662, -1, 4664, 3789, 3791, -1, 4664, 4663, 3789, -1, 4664, 3791, 4663, -1, 4665, 3767, 3769, -1, 4665, 4662, 3767, -1, 4665, 3789, 4662, -1, 4666, 3789, 4665, -1, 4666, 4665, 3769, -1, 4667, 3787, 3789, -1, 4667, 3789, 4666, -1, 4668, 3769, 3771, -1, 4668, 4666, 3769, -1, 4669, 3783, 3785, -1, 4669, 3785, 3787, -1, 4669, 3787, 4667, -1, 4669, 4667, 4666, -1, 4669, 4666, 4668, -1, 4670, 3771, 3773, -1, 4670, 4668, 3771, -1, 4671, 4669, 4668, -1, 4671, 3783, 4669, -1, 4671, 4668, 4670, -1, 4672, 3773, 3776, -1, 4672, 4670, 3773, -1, 4673, 3779, 3781, -1, 4673, 3781, 3783, -1, 4673, 4671, 4670, -1, 4673, 3783, 4671, -1, 4673, 4670, 4672, -1, 4674, 3776, 3778, -1, 4675, 4660, 4676, -1, 4675, 4672, 3776, -1, 4675, 3776, 4674, -1, 4675, 3778, 4660, -1, 4675, 4674, 3778, -1, 4677, 4676, 4661, -1, 4677, 4672, 4675, -1, 4677, 4661, 3779, -1, 4677, 3779, 4673, -1, 4677, 4673, 4672, -1, 4677, 4675, 4676, -1, 4658, 3471, 3463, -1, 4658, 3463, 4678, -1, 4659, 4678, 4679, -1, 4659, 4658, 4678, -1, 4660, 4679, 4680, -1, 4660, 4659, 4679, -1, 4676, 4680, 4681, -1, 4676, 4660, 4680, -1, 4661, 4681, 4682, -1, 4661, 4676, 4681, -1, 3491, 4682, 3492, -1, 3491, 4661, 4682, -1, 4683, 4684, 4685, -1, 4683, 4685, 4686, -1, 4687, 4688, 4689, -1, 4687, 4690, 4688, -1, 4687, 4686, 4691, -1, 4687, 4691, 4690, -1, 4692, 4693, 4684, -1, 4692, 4684, 4683, -1, 3462, 4678, 3463, -1, 4694, 4689, 4695, -1, 4694, 4687, 4689, -1, 4694, 4683, 4686, -1, 4694, 4686, 4687, -1, 4696, 3671, 3673, -1, 4696, 4693, 4692, -1, 4696, 3673, 4697, -1, 4696, 4697, 4693, -1, 4698, 4695, 4699, -1, 4698, 4694, 4695, -1, 4698, 4692, 4683, -1, 3677, 4682, 4681, -1, 4698, 4683, 4694, -1, 3677, 3492, 4682, -1, 4700, 4699, 3549, -1, 4700, 3549, 3671, -1, 4700, 4696, 4692, -1, 4700, 3671, 4696, -1, 4700, 4698, 4699, -1, 4700, 4692, 4698, -1, 4701, 3462, 3461, -1, 4701, 4678, 3462, -1, 4702, 4679, 4678, -1, 4702, 4678, 4701, -1, 4703, 4680, 4679, -1, 4703, 4679, 4702, -1, 4704, 4681, 4680, -1, 4704, 3677, 4681, -1, 4704, 4680, 4703, -1, 4705, 4701, 3461, -1, 4706, 3675, 3677, -1, 4706, 3677, 4704, -1, 4685, 4701, 4705, -1, 4685, 4702, 4701, -1, 4684, 4703, 4702, -1, 4684, 4702, 4685, -1, 4693, 4704, 4703, -1, 4693, 4703, 4684, -1, 4691, 3461, 3460, -1, 4691, 4705, 3461, -1, 4697, 3673, 3675, -1, 4697, 4704, 4693, -1, 4697, 4706, 4704, -1, 4697, 3675, 4706, -1, 4686, 4685, 4705, -1, 4686, 4705, 4691, -1, 4690, 3460, 3459, -1, 4690, 3459, 3458, -1, 4690, 3458, 4688, -1, 4690, 4691, 3460, -1, 4707, 3549, 4699, -1, 4707, 3550, 3549, -1, 4708, 4699, 4695, -1, 4708, 4707, 4699, -1, 4709, 4695, 4689, -1, 4709, 4708, 4695, -1, 4710, 4689, 4688, -1, 4710, 4709, 4689, -1, 3464, 4688, 3458, -1, 3464, 4710, 4688, -1, 3469, 3470, 4711, -1, 4707, 3700, 3550, -1, 4708, 3700, 4707, -1, 4709, 3700, 4708, -1, 4712, 4713, 3475, -1, 4712, 3475, 3696, -1, 4712, 3696, 3697, -1, 4714, 4715, 4713, -1, 4714, 4713, 4712, -1, 4716, 4711, 4715, -1, 4716, 4715, 4714, -1, 4717, 3468, 3469, -1, 4717, 3469, 4711, -1, 4717, 4716, 3468, -1, 4717, 4711, 4716, -1, 4718, 3697, 3698, -1, 4718, 4712, 3697, -1, 4719, 4714, 4712, -1, 4719, 4712, 4718, -1, 4720, 4716, 4714, -1, 4720, 4714, 4719, -1, 4720, 3468, 4716, -1, 4721, 3467, 3468, -1, 4721, 3468, 4720, -1, 4722, 3698, 3699, -1, 4722, 4718, 3698, -1, 4723, 4719, 4718, -1, 4723, 4718, 4722, -1, 4724, 4720, 4719, -1, 4724, 4719, 4723, -1, 4725, 3466, 3467, -1, 4725, 4721, 4720, -1, 4725, 4720, 4724, -1, 4725, 3467, 4721, -1, 4726, 3699, 3700, -1, 4726, 4722, 3699, -1, 4727, 4723, 4722, -1, 4727, 4726, 3700, -1, 4727, 4722, 4726, -1, 4728, 4727, 3700, -1, 4728, 4723, 4727, -1, 4728, 3700, 4709, -1, 4728, 4724, 4723, -1, 4729, 4710, 3464, -1, 4729, 4709, 4710, -1, 4729, 3464, 3466, -1, 4729, 3466, 4725, -1, 4729, 4728, 4709, -1, 4729, 4725, 4724, -1, 4729, 4724, 4728, -1, 3470, 3457, 4730, -1, 4711, 4730, 4731, -1, 4711, 3470, 4730, -1, 4715, 4731, 4732, -1, 4715, 4711, 4731, -1, 4713, 4732, 3473, -1, 4713, 4715, 4732, -1, 3475, 4713, 3473, -1, 4733, 4734, 4730, -1, 4733, 4735, 4734, -1, 3644, 4736, 3546, -1, 3453, 3452, 4737, -1, 3453, 4737, 4738, -1, 3453, 4738, 4739, -1, 4740, 4739, 4736, -1, 4740, 3644, 3642, -1, 4740, 4736, 3644, -1, 4741, 3453, 4739, -1, 4741, 4739, 4740, -1, 4742, 3453, 4741, -1, 4743, 3454, 3453, -1, 4743, 4742, 3454, -1, 4743, 3453, 4742, -1, 4744, 4740, 3642, -1, 4745, 4741, 4740, -1, 4745, 4740, 4744, -1, 4746, 4741, 4745, -1, 4746, 3454, 4742, -1, 4746, 4742, 4741, -1, 4747, 3455, 3454, -1, 4747, 3454, 4746, -1, 4748, 3642, 3640, -1, 4748, 4744, 3642, -1, 4749, 4745, 4744, -1, 4749, 4744, 4748, -1, 4735, 4746, 4745, -1, 4735, 4745, 4749, -1, 4750, 3473, 4732, -1, 4750, 3640, 3637, -1, 4750, 3637, 3473, -1, 4750, 4748, 3640, -1, 4751, 3456, 3455, -1, 4751, 3455, 4747, -1, 4751, 4747, 4746, -1, 4751, 4746, 4735, -1, 4752, 4732, 4731, -1, 4752, 4749, 4748, -1, 4752, 4748, 4750, -1, 4752, 4750, 4732, -1, 4734, 4731, 4730, -1, 4734, 4735, 4749, -1, 4734, 4749, 4752, -1, 4734, 4752, 4731, -1, 4733, 4730, 3457, -1, 4733, 3457, 3456, -1, 4733, 3456, 4751, -1, 4733, 4751, 4735, -1, 4737, 3452, 3447, -1, 4737, 3447, 4753, -1, 4738, 4753, 4754, -1, 4738, 4737, 4753, -1, 4739, 4754, 4755, -1, 4739, 4738, 4754, -1, 4736, 4755, 4756, -1, 4736, 4739, 4755, -1, 3546, 4756, 3547, -1, 3546, 4736, 4756, -1, 4757, 4758, 4759, -1, 4757, 4759, 4760, -1, 4761, 4762, 4763, -1, 4761, 4764, 4762, -1, 4761, 4760, 4765, -1, 4761, 4765, 4764, -1, 4766, 4767, 4758, -1, 4766, 4758, 4757, -1, 4768, 4763, 4769, -1, 4768, 4761, 4763, -1, 4768, 4757, 4760, -1, 4768, 4760, 4761, -1, 4770, 3650, 3649, -1, 4770, 3649, 4771, -1, 4770, 4767, 4766, -1, 4770, 4771, 4767, -1, 3645, 3547, 4756, -1, 4772, 4769, 4773, -1, 4772, 4766, 4757, -1, 4772, 4757, 4768, -1, 4772, 4768, 4769, -1, 4774, 4773, 4775, -1, 4774, 4775, 3485, -1, 4774, 3485, 3650, -1, 4774, 4766, 4772, -1, 4774, 4772, 4773, -1, 4774, 3650, 4770, -1, 4774, 4770, 4766, -1, 4762, 3451, 3444, -1, 4776, 4753, 3447, -1, 4776, 3447, 3449, -1, 4776, 3449, 3448, -1, 4777, 4754, 4753, -1, 4777, 4753, 4776, -1, 4778, 4755, 4754, -1, 4778, 4754, 4777, -1, 4779, 4756, 4755, -1, 4779, 3645, 4756, -1, 4779, 4755, 4778, -1, 4780, 4776, 3448, -1, 4781, 3647, 3645, -1, 4781, 3645, 4779, -1, 4759, 4776, 4780, -1, 4759, 4777, 4776, -1, 4758, 4778, 4777, -1, 4758, 4777, 4759, -1, 4767, 4779, 4778, -1, 4767, 4778, 4758, -1, 4765, 3448, 3450, -1, 4765, 4780, 3448, -1, 4771, 3649, 3647, -1, 4771, 4779, 4767, -1, 4771, 4781, 4779, -1, 4771, 3647, 4781, -1, 4760, 4759, 4780, -1, 4760, 4780, 4765, -1, 4764, 3450, 3451, -1, 4764, 4765, 3450, -1, 4764, 3451, 4762, -1, 4762, 3444, 3446, -1, 4762, 3446, 4782, -1, 4763, 4782, 4783, -1, 4763, 4762, 4782, -1, 4769, 4783, 4784, -1, 4769, 4763, 4783, -1, 4773, 4784, 4785, -1, 4773, 4785, 4786, -1, 4773, 4769, 4784, -1, 4775, 4786, 3480, -1, 4775, 4773, 4786, -1, 3485, 4775, 3480, -1, 3719, 3528, 3744, -1, 4786, 3734, 3480, -1, 4785, 3734, 4786, -1, 4784, 3734, 4785, -1, 3446, 3731, 4782, -1, 4787, 3719, 3744, -1, 4788, 4787, 3721, -1, 4788, 3719, 4787, -1, 4789, 3721, 3719, -1, 4789, 4788, 3721, -1, 4789, 3719, 4788, -1, 4790, 3744, 3742, -1, 4790, 4787, 3744, -1, 4790, 3721, 4787, -1, 4791, 3721, 4790, -1, 4791, 4790, 3742, -1, 4792, 3723, 3721, -1, 4792, 3721, 4791, -1, 4793, 3742, 3740, -1, 4793, 4791, 3742, -1, 4794, 3727, 3725, -1, 4794, 3725, 3723, -1, 4794, 3723, 4792, -1, 4794, 4792, 4791, -1, 4794, 4791, 4793, -1, 4795, 3740, 3738, -1, 4795, 4793, 3740, -1, 4796, 4794, 4793, -1, 4796, 3727, 4794, -1, 4796, 4793, 4795, -1, 4797, 3738, 3736, -1, 4797, 4795, 3738, -1, 4798, 3731, 3729, -1, 4798, 3729, 3727, -1, 4798, 4796, 4795, -1, 4798, 3727, 4796, -1, 4798, 4795, 4797, -1, 4799, 3736, 3734, -1, 4800, 4784, 4783, -1, 4800, 4797, 3736, -1, 4800, 3736, 4799, -1, 4800, 3734, 4784, -1, 4800, 4799, 3734, -1, 4801, 4783, 4782, -1, 4801, 4797, 4800, -1, 4801, 4782, 3731, -1, 4801, 3731, 4798, -1, 4801, 4798, 4797, -1, 4801, 4800, 4783, -1, 3711, 3710, 3716, -1, 3714, 3710, 3715, -1, 3716, 3710, 3714, -1, 3715, 3709, 3717, -1, 3710, 3709, 3715, -1, 3717, 3712, 3718, -1, 3709, 3712, 3717, -1, 3718, 3713, 3555, -1, 3712, 3713, 3718, -1, 3713, 3556, 3555, -1, 3433, 4565, 3432, -1, 3432, 4571, 3431, -1, 4565, 4571, 3432, -1, 3431, 4570, 3430, -1, 4571, 4570, 3431, -1, 3430, 4569, 3429, -1, 4570, 4569, 3430, -1, 3429, 4568, 3428, -1, 4569, 4568, 3429, -1, 3428, 4567, 3427, -1, 4568, 4567, 3428, -1, 3427, 4566, 3426, -1, 4567, 4566, 3427, -1, 4566, 3552, 3426, -1, 3560, 4573, 3441, -1, 3441, 4573, 3440, -1, 3440, 4574, 3439, -1, 4573, 4574, 3440, -1, 3439, 4575, 3438, -1, 4574, 4575, 3439, -1, 3438, 4576, 3437, -1, 4575, 4576, 3438, -1, 3437, 4577, 3436, -1, 4576, 4577, 3437, -1, 3436, 4578, 3434, -1, 4577, 4578, 3436, -1, 3434, 4572, 3435, -1, 4578, 4572, 3434, -1, 3578, 3553, 3832, -1, 3578, 3580, 3553, -1, 3577, 3832, 3830, -1, 3577, 3578, 3832, -1, 3575, 3830, 3828, -1, 3575, 3577, 3830, -1, 3570, 3828, 3826, -1, 3570, 3575, 3828, -1, 3574, 3570, 3826, -1, 4611, 3574, 3826, -1, 4612, 3826, 3824, -1, 4612, 4611, 3826, -1, 4608, 4612, 3824, -1, 4609, 4608, 3824, -1, 4614, 4609, 3824, -1, 4617, 4614, 3824, -1, 4620, 4617, 3824, -1, 4622, 4620, 3824, -1, 3722, 3824, 3822, -1, 3722, 4622, 3824, -1, 3720, 3822, 3820, -1, 3720, 3722, 3822, -1, 3531, 3820, 3529, -1, 3531, 3720, 3820, -1, 3497, 3495, 3843, -1, 3766, 3497, 3843, -1, 3768, 3843, 3841, -1, 3768, 3766, 3843, -1, 4656, 3768, 3841, -1, 4655, 4656, 3841, -1, 4654, 4655, 3841, -1, 4652, 4654, 3841, -1, 4649, 4652, 3841, -1, 4648, 3841, 3839, -1, 4648, 4649, 3841, -1, 3598, 4648, 3839, -1, 3597, 3839, 3837, -1, 3597, 3598, 3839, -1, 3596, 3597, 3837, -1, 3594, 3837, 3835, -1, 3594, 3596, 3837, -1, 3592, 3835, 3833, -1, 3592, 3594, 3835, -1, 3591, 3833, 3558, -1, 3591, 3592, 3833, -1, 4802, 4803, 4804, -1, 4805, 4802, 4806, -1, 4805, 4803, 4802, -1, 4807, 4808, 4805, -1, 4807, 4805, 4806, -1, 4809, 4808, 4807, -1, 4810, 4809, 4807, -1, 4811, 4812, 4813, -1, 4814, 4811, 4813, -1, 4812, 4811, 4815, -1, 4812, 4815, 4816, -1, 4816, 4815, 4817, -1, 4816, 4817, 4818, -1, 4819, 4820, 4821, -1, 4822, 4820, 4819, -1, 4821, 4823, 4819, -1, 4821, 4824, 4823, -1, 4823, 4825, 4826, -1, 4824, 4825, 4823, -1, 4825, 4820, 4826, -1, 4820, 4822, 4826, -1, 4827, 4828, 4829, -1, 4827, 4830, 4828, -1, 4828, 4831, 4832, -1, 4830, 4831, 4828, -1, 4832, 4833, 4834, -1, 4831, 4833, 4832, -1, 4834, 4827, 4829, -1, 4833, 4827, 4834, -1, 4835, 4836, 4813, -1, 4818, 4836, 4835, -1, 4837, 4835, 4813, -1, 4816, 4818, 4838, -1, 4812, 4839, 4837, -1, 4812, 4838, 4839, -1, 4812, 4837, 4813, -1, 4812, 4816, 4838, -1, 4835, 4838, 4818, -1, 4840, 4841, 4842, -1, 4843, 4841, 4840, -1, 4844, 4845, 4843, -1, 4846, 4845, 4844, -1, 4847, 4845, 4846, -1, 4843, 4845, 4841, -1, 4845, 4848, 4841, -1, 4841, 4848, 4849, -1, 4845, 4850, 4848, -1, 4849, 4851, 4841, -1, 4845, 4852, 4850, -1, 4851, 4853, 4841, -1, 4845, 4854, 4852, -1, 4853, 4855, 4841, -1, 4855, 4856, 4841, -1, 4845, 4857, 4854, -1, 4856, 4858, 4841, -1, 4858, 4859, 4841, -1, 4860, 4861, 4845, -1, 4845, 4861, 4857, -1, 4860, 4862, 4861, -1, 4860, 4863, 4862, -1, 4864, 4865, 4860, -1, 4860, 4866, 4863, -1, 4860, 4867, 4866, -1, 4865, 4868, 4860, -1, 4868, 4869, 4860, -1, 4860, 4870, 4867, -1, 4860, 4871, 4870, -1, 4869, 4871, 4860, -1, 4870, 4871, 4872, -1, 4872, 4871, 4873, -1, 4873, 4871, 4874, -1, 4874, 4871, 4875, -1, 4876, 4871, 4869, -1, 4877, 4871, 4876, -1, 4878, 4879, 4880, -1, 4880, 4879, 4881, -1, 4881, 4879, 4882, -1, 4882, 4879, 4883, -1, 4883, 4879, 4884, -1, 4878, 4885, 4879, -1, 4878, 4886, 4885, -1, 4879, 4887, 4884, -1, 4878, 4888, 4886, -1, 4884, 4889, 4859, -1, 4887, 4889, 4884, -1, 4859, 4889, 4841, -1, 4878, 4890, 4888, -1, 4889, 4891, 4841, -1, 4891, 4892, 4841, -1, 4871, 4893, 4875, -1, 4893, 4894, 4895, -1, 4895, 4894, 4896, -1, 4896, 4894, 4897, -1, 4897, 4894, 4898, -1, 4871, 4894, 4893, -1, 4899, 4900, 4901, -1, 4901, 4900, 4902, -1, 4902, 4900, 4903, -1, 4903, 4900, 4904, -1, 4898, 4900, 4899, -1, 4904, 4900, 4905, -1, 4894, 4900, 4898, -1, 4906, 4907, 4894, -1, 4894, 4907, 4900, -1, 4908, 4909, 4906, -1, 4906, 4909, 4907, -1, 4910, 4911, 4908, -1, 4908, 4911, 4909, -1, 4912, 4913, 4914, -1, 4915, 4916, 4917, -1, 4912, 4916, 4915, -1, 4914, 4916, 4912, -1, 4912, 4918, 4913, -1, 4916, 4919, 4917, -1, 4912, 4920, 4918, -1, 4912, 4921, 4920, -1, 4912, 4922, 4921, -1, 4922, 4923, 4921, -1, 4923, 4924, 4921, -1, 4924, 4925, 4921, -1, 4926, 4927, 4892, -1, 4928, 4927, 4926, -1, 4917, 4927, 4928, -1, 4919, 4927, 4917, -1, 4892, 4927, 4841, -1, 4929, 4927, 4919, -1, 4929, 4930, 4927, -1, 4930, 4931, 4927, -1, 4931, 4932, 4927, -1, 4927, 4933, 4934, -1, 4932, 4935, 4927, -1, 4935, 4936, 4927, -1, 4927, 4937, 4933, -1, 4927, 4938, 4937, -1, 4936, 4939, 4927, -1, 4927, 4940, 4938, -1, 4927, 4941, 4940, -1, 4939, 4942, 4927, -1, 4927, 4942, 4941, -1, 4943, 4942, 4944, -1, 4944, 4942, 4945, -1, 4945, 4942, 4946, -1, 4946, 4942, 4939, -1, 4947, 4948, 4949, -1, 4948, 4950, 4949, -1, 4948, 4951, 4950, -1, 4948, 4952, 4951, -1, 4948, 4953, 4952, -1, 4954, 4955, 4948, -1, 4956, 4957, 4955, -1, 4958, 4957, 4956, -1, 4955, 4957, 4948, -1, 4948, 4959, 4953, -1, 4957, 4960, 4948, -1, 4948, 4961, 4959, -1, 4960, 4961, 4948, -1, 4959, 4961, 4962, -1, 4962, 4961, 4963, -1, 4963, 4961, 4964, -1, 4961, 4965, 4964, -1, 4943, 4966, 4942, -1, 4967, 4968, 4969, -1, 4969, 4968, 4970, -1, 4970, 4968, 4971, -1, 4971, 4968, 4972, -1, 4965, 4968, 4967, -1, 4961, 4968, 4965, -1, 4968, 4973, 4972, -1, 4966, 4973, 4942, -1, 4974, 4973, 4975, -1, 4975, 4973, 4976, -1, 4976, 4973, 4977, -1, 4977, 4973, 4966, -1, 4972, 4973, 4974, -1, 4968, 4978, 4973, -1, 4979, 4980, 4968, -1, 4968, 4981, 4978, -1, 4980, 4982, 4968, -1, 4968, 4983, 4981, -1, 4982, 4983, 4968, -1, 4949, 4921, 4947, -1, 4947, 4921, 4925, -1, 4878, 4904, 4905, -1, 4878, 4905, 4890, -1, 4984, 4985, 4986, -1, 4987, 4988, 4989, -1, 4990, 4987, 4989, -1, 4991, 4987, 4990, -1, 4992, 4991, 4993, -1, 4992, 4987, 4991, -1, 4994, 4995, 4996, -1, 4997, 4995, 4994, -1, 4998, 4999, 5000, -1, 5001, 5002, 4999, -1, 4984, 5002, 5001, -1, 4984, 4986, 5002, -1, 4999, 5003, 5000, -1, 5002, 5003, 4999, -1, 5004, 5005, 5006, -1, 5004, 5007, 5005, -1, 5005, 5008, 5009, -1, 5007, 5008, 5005, -1, 5010, 5011, 5008, -1, 5008, 5011, 5009, -1, 5012, 5013, 5014, -1, 5001, 5015, 4984, -1, 5014, 5015, 5001, -1, 5015, 4985, 4984, -1, 5013, 5016, 5014, -1, 5014, 5016, 5015, -1, 5016, 4988, 4987, -1, 5013, 4988, 5016, -1, 5004, 5017, 5007, -1, 5018, 5017, 5004, -1, 5017, 5019, 5007, -1, 5017, 5020, 5019, -1, 4805, 4808, 5020, -1, 5019, 4809, 5021, -1, 4808, 4809, 5020, -1, 5020, 4809, 5019, -1, 4989, 4988, 5013, -1, 4989, 5013, 5022, -1, 4997, 5023, 4995, -1, 5024, 5023, 4997, -1, 5022, 5025, 5026, -1, 5027, 5022, 5026, -1, 5028, 5022, 5027, -1, 5029, 5022, 5028, -1, 4989, 5029, 5030, -1, 4989, 5030, 5031, -1, 4989, 5031, 5032, -1, 4989, 5032, 5033, -1, 4989, 5033, 5034, -1, 4989, 5034, 4990, -1, 4989, 5022, 5029, -1, 4807, 4806, 5035, -1, 4807, 5035, 5036, -1, 4807, 5036, 5037, -1, 4807, 5037, 5038, -1, 4807, 5038, 5039, -1, 4807, 5039, 5040, -1, 4810, 5041, 5042, -1, 4810, 5040, 5043, -1, 4810, 5043, 5044, -1, 4810, 5044, 5041, -1, 4810, 4807, 5040, -1, 5012, 5014, 4998, -1, 4998, 5014, 4999, -1, 5019, 5010, 5008, -1, 5019, 5021, 5010, -1, 5045, 5046, 5047, -1, 5048, 5047, 5046, -1, 5049, 5045, 5047, -1, 5050, 5049, 5047, -1, 5051, 5052, 5047, -1, 5051, 5047, 5048, -1, 5053, 5050, 5047, -1, 5054, 5055, 5056, -1, 5054, 5056, 5057, -1, 5054, 5057, 5051, -1, 5054, 5051, 5048, -1, 5058, 5055, 5054, -1, 5059, 5060, 5061, -1, 5062, 5059, 5061, -1, 5063, 5062, 5061, -1, 5064, 5061, 5065, -1, 5064, 5063, 5061, -1, 5066, 5065, 5067, -1, 5066, 5067, 5068, -1, 5066, 5068, 5069, -1, 5066, 5069, 5070, -1, 5066, 5070, 5071, -1, 5066, 5071, 5053, -1, 5066, 5053, 5047, -1, 5066, 5064, 5065, -1, 5072, 5064, 5066, -1, 5073, 5074, 5075, -1, 5073, 5075, 5076, -1, 5007, 5019, 5008, -1, 5014, 5001, 4999, -1, 5077, 5078, 5079, -1, 5080, 5078, 5077, -1, 5081, 5082, 5083, -1, 5081, 5084, 5082, -1, 5081, 5085, 5084, -1, 5081, 5086, 5085, -1, 5081, 5080, 5086, -1, 5081, 5078, 5080, -1, 5087, 5088, 5089, -1, 5087, 5090, 5088, -1, 5091, 5083, 5092, -1, 5091, 5093, 5090, -1, 5091, 5094, 5093, -1, 5091, 5092, 5094, -1, 5091, 5081, 5083, -1, 5091, 5090, 5087, -1, 5095, 5096, 5097, -1, 5098, 5096, 5095, -1, 5098, 5099, 5096, -1, 5099, 5100, 5096, -1, 5101, 5102, 5103, -1, 5104, 5102, 5101, -1, 5105, 5106, 5107, -1, 5108, 5106, 5105, -1, 5109, 5110, 5111, -1, 5112, 5110, 5109, -1, 5113, 5114, 5115, -1, 5114, 5116, 5115, -1, 5117, 5118, 5119, -1, 5117, 5120, 5118, -1, 5121, 5122, 5123, -1, 5121, 5124, 5122, -1, 5123, 5125, 5121, -1, 5123, 5126, 5125, -1, 5125, 5127, 5128, -1, 5126, 5127, 5125, -1, 5129, 5130, 5131, -1, 5129, 5132, 5130, -1, 5130, 5133, 5134, -1, 5132, 5133, 5130, -1, 5135, 5118, 5114, -1, 5136, 5118, 5135, -1, 5137, 5118, 5136, -1, 5138, 5112, 5139, -1, 5140, 5112, 5138, -1, 5116, 5112, 5140, -1, 5114, 5120, 5116, -1, 5116, 5120, 5112, -1, 5118, 5120, 5114, -1, 5120, 5110, 5112, -1, 5141, 5108, 5142, -1, 5143, 5108, 5141, -1, 5110, 5108, 5143, -1, 5144, 5145, 5146, -1, 5106, 5145, 5144, -1, 5106, 5101, 5145, -1, 5108, 5104, 5106, -1, 5120, 5104, 5110, -1, 5110, 5104, 5108, -1, 5106, 5104, 5101, -1, 5147, 5148, 5149, -1, 5150, 5151, 5152, -1, 5153, 5026, 4836, -1, 5153, 4836, 4818, -1, 4817, 5153, 4818, -1, 5027, 5026, 5153, -1, 5154, 4994, 5155, -1, 4996, 5155, 4994, -1, 5156, 4996, 4806, -1, 4802, 5156, 4806, -1, 5042, 5041, 5154, -1, 5042, 5154, 4836, -1, 5157, 5154, 5155, -1, 5157, 4836, 5154, -1, 4813, 4836, 5157, -1, 5025, 5042, 4836, -1, 5158, 5159, 5042, -1, 5158, 5042, 5025, -1, 5026, 5025, 4836, -1, 4814, 4813, 5157, -1, 5160, 4991, 4990, -1, 5160, 4990, 4814, -1, 5156, 5155, 4996, -1, 5157, 5160, 4814, -1, 5161, 5162, 5163, -1, 5161, 5163, 5154, -1, 5041, 5044, 5161, -1, 5041, 5161, 5154, -1, 5162, 5024, 5163, -1, 5023, 5024, 5162, -1, 5018, 5004, 5006, -1, 5164, 5165, 4994, -1, 5154, 5164, 4994, -1, 5163, 5164, 5154, -1, 4997, 5165, 5166, -1, 4997, 4994, 5165, -1, 5167, 4997, 5166, -1, 5024, 5167, 5163, -1, 5024, 4997, 5167, -1, 5167, 5164, 5163, -1, 5168, 5169, 5170, -1, 5171, 5172, 5173, -1, 5171, 5173, 5174, -1, 5171, 5168, 5172, -1, 5169, 5175, 5176, -1, 5169, 5176, 5177, -1, 5178, 5179, 5180, -1, 5181, 5178, 5180, -1, 5182, 5180, 5183, -1, 5182, 5181, 5180, -1, 4803, 5184, 4804, -1, 5185, 5183, 5186, -1, 5185, 5186, 5187, -1, 5185, 5182, 5183, -1, 5188, 5187, 5184, -1, 5188, 5185, 5187, -1, 5189, 5188, 5184, -1, 5175, 5190, 5189, -1, 5175, 5184, 4803, -1, 5175, 5189, 5184, -1, 5191, 4803, 5192, -1, 5191, 5175, 4803, -1, 5176, 5175, 5191, -1, 4992, 5193, 5194, -1, 5170, 4992, 4993, -1, 5169, 5177, 5193, -1, 5169, 4992, 5170, -1, 5169, 5193, 4992, -1, 5174, 5173, 5195, -1, 5174, 5195, 5196, -1, 5174, 5196, 5197, -1, 5198, 5199, 5169, -1, 5168, 5198, 5169, -1, 5168, 5170, 5172, -1, 5106, 5144, 5107, -1, 5107, 5144, 5200, -1, 5201, 5146, 5202, -1, 5200, 5146, 5201, -1, 5144, 5146, 5200, -1, 5146, 5145, 5202, -1, 5202, 5101, 5103, -1, 5145, 5101, 5202, -1, 5111, 5110, 5203, -1, 5203, 5143, 5204, -1, 5110, 5143, 5203, -1, 5204, 5141, 5205, -1, 5143, 5141, 5204, -1, 5141, 5142, 5205, -1, 5205, 5108, 5105, -1, 5142, 5108, 5205, -1, 5116, 5140, 5115, -1, 5115, 5140, 5206, -1, 5206, 5138, 5207, -1, 5140, 5138, 5206, -1, 5207, 5139, 5208, -1, 5138, 5139, 5207, -1, 5208, 5112, 5109, -1, 5139, 5112, 5208, -1, 5119, 5118, 5209, -1, 5118, 5137, 5209, -1, 5209, 5136, 5210, -1, 5137, 5136, 5209, -1, 5210, 5135, 5211, -1, 5136, 5135, 5210, -1, 5211, 5114, 5113, -1, 5135, 5114, 5211, -1, 5102, 5104, 5212, -1, 5213, 5212, 5214, -1, 5213, 5102, 5212, -1, 5215, 5214, 5216, -1, 5215, 5213, 5214, -1, 5217, 5216, 5218, -1, 5217, 5215, 5216, -1, 5219, 5218, 5220, -1, 5219, 5217, 5218, -1, 5221, 5220, 5222, -1, 5221, 5219, 5220, -1, 5223, 5222, 5125, -1, 5223, 5221, 5222, -1, 5128, 5223, 5125, -1, 5224, 5125, 5222, -1, 5224, 5121, 5125, -1, 5225, 5222, 5220, -1, 5225, 5220, 5218, -1, 5225, 5224, 5222, -1, 5226, 5225, 5218, -1, 5227, 5218, 5216, -1, 5227, 5226, 5218, -1, 5228, 5216, 5214, -1, 5228, 5227, 5216, -1, 5229, 5214, 5212, -1, 5229, 5212, 5104, -1, 5229, 5228, 5214, -1, 5120, 5229, 5104, -1, 5230, 5124, 5121, -1, 5230, 5121, 5224, -1, 5231, 5224, 5225, -1, 5231, 5230, 5224, -1, 5232, 5225, 5226, -1, 5232, 5231, 5225, -1, 5233, 5226, 5227, -1, 5233, 5232, 5226, -1, 5234, 5227, 5228, -1, 5234, 5233, 5227, -1, 5235, 5228, 5229, -1, 5235, 5234, 5228, -1, 5117, 5229, 5120, -1, 5117, 5235, 5229, -1, 5147, 5236, 5237, -1, 5149, 5236, 5147, -1, 5237, 5238, 5239, -1, 5236, 5238, 5237, -1, 5239, 5240, 5241, -1, 5241, 5240, 5242, -1, 5238, 5240, 5239, -1, 5242, 5243, 5244, -1, 5244, 5243, 5245, -1, 5240, 5243, 5242, -1, 5245, 5075, 5074, -1, 5243, 5075, 5245, -1, 5077, 5079, 5246, -1, 5247, 5077, 5246, -1, 5248, 5246, 5249, -1, 5248, 5249, 5250, -1, 5248, 5247, 5246, -1, 5251, 5250, 5252, -1, 5251, 5248, 5250, -1, 5147, 5252, 5148, -1, 5147, 5251, 5252, -1, 5245, 5074, 5253, -1, 5247, 5080, 5077, -1, 5248, 5080, 5247, -1, 5147, 5237, 5251, -1, 5254, 5255, 5083, -1, 5254, 5083, 5082, -1, 5256, 5082, 5084, -1, 5256, 5254, 5082, -1, 5257, 5253, 5255, -1, 5257, 5255, 5254, -1, 5258, 5084, 5085, -1, 5258, 5256, 5084, -1, 5259, 5257, 5254, -1, 5259, 5254, 5256, -1, 5260, 5242, 5244, -1, 5260, 5244, 5245, -1, 5260, 5253, 5257, -1, 5260, 5245, 5253, -1, 5261, 5256, 5258, -1, 5261, 5259, 5256, -1, 5262, 5241, 5242, -1, 5262, 5260, 5257, -1, 5262, 5242, 5260, -1, 5262, 5257, 5259, -1, 5263, 5085, 5086, -1, 5263, 5258, 5085, -1, 5264, 5239, 5241, -1, 5264, 5241, 5262, -1, 5264, 5262, 5259, -1, 5264, 5259, 5261, -1, 5265, 5261, 5258, -1, 5265, 5258, 5263, -1, 5266, 5237, 5239, -1, 5266, 5239, 5264, -1, 5266, 5264, 5261, -1, 5266, 5261, 5265, -1, 5267, 5086, 5080, -1, 5267, 5263, 5086, -1, 5268, 5265, 5263, -1, 5268, 5267, 5080, -1, 5268, 5263, 5267, -1, 5268, 5080, 5248, -1, 5269, 5248, 5251, -1, 5269, 5237, 5266, -1, 5269, 5251, 5237, -1, 5269, 5266, 5265, -1, 5269, 5265, 5268, -1, 5269, 5268, 5248, -1, 5270, 5083, 5255, -1, 5270, 5092, 5083, -1, 5271, 5255, 5253, -1, 5271, 5253, 5074, -1, 5271, 5270, 5255, -1, 5073, 5271, 5074, -1, 5272, 5089, 5088, -1, 5272, 5088, 5273, -1, 5274, 5273, 5275, -1, 5274, 5272, 5273, -1, 5276, 5275, 5277, -1, 5276, 5274, 5275, -1, 5278, 5277, 5151, -1, 5278, 5276, 5277, -1, 5150, 5278, 5151, -1, 5090, 5273, 5088, -1, 5279, 5151, 5277, -1, 5073, 5280, 5271, -1, 5281, 5090, 5093, -1, 5281, 5273, 5090, -1, 5282, 5275, 5273, -1, 5282, 5273, 5281, -1, 5283, 5277, 5275, -1, 5283, 5279, 5277, -1, 5283, 5275, 5282, -1, 5284, 5281, 5093, -1, 5285, 5282, 5281, -1, 5285, 5281, 5284, -1, 5286, 5287, 5279, -1, 5286, 5288, 5287, -1, 5286, 5279, 5283, -1, 5286, 5283, 5282, -1, 5286, 5282, 5285, -1, 5289, 5093, 5094, -1, 5289, 5284, 5093, -1, 5290, 5094, 5092, -1, 5290, 5092, 5270, -1, 5290, 5289, 5094, -1, 5291, 5284, 5289, -1, 5291, 5285, 5284, -1, 5292, 5270, 5271, -1, 5292, 5289, 5290, -1, 5292, 5290, 5270, -1, 5292, 5291, 5289, -1, 5293, 5294, 5288, -1, 5293, 5288, 5286, -1, 5293, 5286, 5285, -1, 5293, 5285, 5291, -1, 5295, 5296, 5294, -1, 5295, 5280, 5296, -1, 5295, 5294, 5293, -1, 5295, 5271, 5280, -1, 5295, 5292, 5271, -1, 5295, 5291, 5292, -1, 5295, 5293, 5291, -1, 5152, 5151, 5297, -1, 5298, 5279, 5299, -1, 5297, 5279, 5298, -1, 5151, 5279, 5297, -1, 5299, 5287, 5300, -1, 5279, 5287, 5299, -1, 5300, 5288, 5301, -1, 5287, 5288, 5300, -1, 5288, 5294, 5301, -1, 5301, 5296, 5076, -1, 5294, 5296, 5301, -1, 5296, 5280, 5076, -1, 5280, 5073, 5076, -1, 5302, 5126, 5123, -1, 5302, 5123, 5303, -1, 5304, 5303, 5305, -1, 5304, 5302, 5303, -1, 5306, 5305, 5307, -1, 5306, 5304, 5305, -1, 5308, 5307, 5309, -1, 5308, 5306, 5307, -1, 5091, 5309, 5081, -1, 5091, 5308, 5309, -1, 5022, 5158, 5025, -1, 5013, 5158, 5022, -1, 5013, 5310, 5158, -1, 5311, 5012, 5312, -1, 5313, 5012, 5311, -1, 5314, 5012, 5313, -1, 5310, 5012, 5314, -1, 5013, 5012, 5310, -1, 5012, 4998, 5312, -1, 4998, 5000, 5312, -1, 5000, 5177, 5312, -1, 5011, 5315, 5176, -1, 5010, 5315, 5011, -1, 5021, 5315, 5010, -1, 5021, 5316, 5315, -1, 5021, 5317, 5316, -1, 5021, 5318, 5317, -1, 5021, 5319, 5318, -1, 5319, 4809, 5159, -1, 5021, 4809, 5319, -1, 5159, 4810, 5042, -1, 4809, 4810, 5159, -1, 5017, 5018, 5006, -1, 5017, 5006, 5005, -1, 4805, 5020, 5192, -1, 4805, 5192, 4803, -1, 5009, 5191, 5192, -1, 5017, 5005, 5009, -1, 5020, 5017, 5009, -1, 5192, 5020, 5009, -1, 5003, 5015, 5016, -1, 5002, 5015, 5003, -1, 5193, 5003, 5194, -1, 5016, 5194, 5003, -1, 4987, 4992, 5194, -1, 5016, 4987, 5194, -1, 4985, 5015, 5002, -1, 4985, 5002, 4986, -1, 5320, 5047, 5052, -1, 5320, 5052, 5321, -1, 5322, 5321, 5323, -1, 5322, 5320, 5321, -1, 5324, 5323, 5325, -1, 5324, 5322, 5323, -1, 5326, 5325, 5327, -1, 5326, 5324, 5325, -1, 5328, 5327, 5329, -1, 5328, 5326, 5327, -1, 5330, 5329, 5331, -1, 5330, 5328, 5329, -1, 5332, 5331, 5333, -1, 5332, 5330, 5331, -1, 5131, 5333, 5129, -1, 5131, 5332, 5333, -1, 5334, 5132, 5129, -1, 5334, 5129, 5335, -1, 5336, 5335, 5337, -1, 5336, 5334, 5335, -1, 5338, 5337, 5339, -1, 5338, 5336, 5337, -1, 5340, 5339, 5341, -1, 5340, 5338, 5339, -1, 5342, 5341, 5343, -1, 5342, 5340, 5341, -1, 5344, 5343, 5345, -1, 5344, 5342, 5343, -1, 5346, 5345, 5078, -1, 5346, 5344, 5345, -1, 5081, 5346, 5078, -1, 5347, 5132, 5334, -1, 5309, 5346, 5081, -1, 5123, 5348, 5303, -1, 5349, 5334, 5336, -1, 5349, 5336, 5338, -1, 5350, 5351, 5347, -1, 5350, 5352, 5351, -1, 5350, 5334, 5349, -1, 5350, 5347, 5334, -1, 5350, 5349, 5338, -1, 5350, 5338, 5352, -1, 5353, 5338, 5340, -1, 5353, 5340, 5342, -1, 5354, 5355, 5352, -1, 5354, 5356, 5355, -1, 5354, 5338, 5353, -1, 5354, 5352, 5338, -1, 5357, 5342, 5344, -1, 5357, 5344, 5346, -1, 5357, 5309, 5307, -1, 5357, 5346, 5309, -1, 5358, 5305, 5303, -1, 5358, 5307, 5305, -1, 5358, 5359, 5356, -1, 5358, 5348, 5359, -1, 5358, 5303, 5348, -1, 5358, 5357, 5307, -1, 5360, 5356, 5354, -1, 5360, 5354, 5353, -1, 5360, 5342, 5357, -1, 5360, 5358, 5356, -1, 5360, 5353, 5342, -1, 5360, 5357, 5358, -1, 5361, 5133, 5132, -1, 5361, 5132, 5347, -1, 5362, 5347, 5351, -1, 5362, 5361, 5347, -1, 5363, 5351, 5352, -1, 5363, 5362, 5351, -1, 5364, 5352, 5355, -1, 5364, 5363, 5352, -1, 5365, 5355, 5356, -1, 5365, 5364, 5355, -1, 5366, 5356, 5359, -1, 5366, 5359, 5348, -1, 5366, 5365, 5356, -1, 5122, 5348, 5123, -1, 5122, 5366, 5348, -1, 5367, 5066, 5368, -1, 5367, 5072, 5066, -1, 5369, 5368, 5370, -1, 5369, 5367, 5368, -1, 5371, 5370, 5372, -1, 5371, 5372, 5373, -1, 5371, 5369, 5370, -1, 5374, 5373, 5375, -1, 5374, 5371, 5373, -1, 5376, 5375, 5377, -1, 5376, 5374, 5375, -1, 5378, 5377, 5379, -1, 5378, 5376, 5377, -1, 5099, 5379, 5100, -1, 5099, 5378, 5379, -1, 5380, 5099, 5098, -1, 5380, 5098, 5381, -1, 5382, 5381, 5383, -1, 5382, 5380, 5381, -1, 5384, 5383, 5385, -1, 5384, 5382, 5383, -1, 5386, 5385, 5387, -1, 5386, 5384, 5385, -1, 5388, 5387, 5389, -1, 5388, 5386, 5387, -1, 5390, 5389, 5391, -1, 5390, 5388, 5389, -1, 5392, 5391, 5091, -1, 5392, 5390, 5391, -1, 5087, 5392, 5091, -1, 5381, 5098, 5393, -1, 5302, 5394, 5126, -1, 5091, 5391, 5308, -1, 5395, 5396, 5397, -1, 5395, 5393, 5396, -1, 5398, 5381, 5393, -1, 5398, 5393, 5395, -1, 5398, 5395, 5397, -1, 5399, 5381, 5398, -1, 5399, 5397, 5385, -1, 5399, 5398, 5397, -1, 5400, 5385, 5383, -1, 5400, 5383, 5381, -1, 5400, 5381, 5399, -1, 5400, 5399, 5385, -1, 5401, 5397, 5402, -1, 5403, 5397, 5401, -1, 5404, 5385, 5397, -1, 5404, 5397, 5403, -1, 5405, 5387, 5385, -1, 5405, 5385, 5404, -1, 5406, 5407, 5394, -1, 5406, 5402, 5407, -1, 5406, 5401, 5402, -1, 5408, 5403, 5401, -1, 5408, 5401, 5406, -1, 5409, 5404, 5403, -1, 5409, 5403, 5408, -1, 5410, 5391, 5389, -1, 5410, 5389, 5387, -1, 5410, 5387, 5405, -1, 5410, 5405, 5404, -1, 5410, 5404, 5409, -1, 5411, 5406, 5394, -1, 5411, 5394, 5302, -1, 5412, 5302, 5304, -1, 5412, 5408, 5406, -1, 5412, 5411, 5302, -1, 5412, 5406, 5411, -1, 5413, 5304, 5306, -1, 5413, 5408, 5412, -1, 5413, 5409, 5408, -1, 5413, 5412, 5304, -1, 5414, 5306, 5308, -1, 5414, 5391, 5410, -1, 5414, 5413, 5306, -1, 5414, 5308, 5391, -1, 5414, 5410, 5409, -1, 5414, 5409, 5413, -1, 5127, 5126, 5394, -1, 5415, 5127, 5394, -1, 5416, 5394, 5407, -1, 5416, 5415, 5394, -1, 5417, 5407, 5402, -1, 5417, 5416, 5407, -1, 5418, 5402, 5397, -1, 5418, 5417, 5402, -1, 5419, 5397, 5396, -1, 5419, 5418, 5397, -1, 5420, 5396, 5393, -1, 5420, 5419, 5396, -1, 5095, 5393, 5098, -1, 5095, 5420, 5393, -1, 5155, 5156, 5421, -1, 5422, 5421, 5423, -1, 5422, 5155, 5421, -1, 5424, 5423, 5425, -1, 5424, 5422, 5423, -1, 5426, 5425, 5427, -1, 5426, 5424, 5425, -1, 5428, 5427, 5429, -1, 5428, 5426, 5427, -1, 5430, 5429, 5431, -1, 5430, 5428, 5429, -1, 5432, 5431, 5433, -1, 5432, 5430, 5431, -1, 5134, 5433, 5130, -1, 5134, 5432, 5433, -1, 5434, 5097, 5096, -1, 5434, 5096, 5435, -1, 5436, 5435, 5437, -1, 5436, 5434, 5435, -1, 5438, 5437, 5439, -1, 5438, 5436, 5437, -1, 5440, 5439, 5441, -1, 5440, 5438, 5439, -1, 5442, 5441, 5443, -1, 5442, 5440, 5441, -1, 5444, 5443, 5445, -1, 5444, 5442, 5443, -1, 5157, 5445, 5160, -1, 5157, 5444, 5445, -1, 5446, 5447, 5448, -1, 5446, 5448, 5449, -1, 5450, 5451, 5452, -1, 5453, 5454, 5455, -1, 5450, 5452, 5456, -1, 5453, 5449, 5457, -1, 5453, 5458, 5454, -1, 5453, 5457, 5458, -1, 5459, 5416, 5417, -1, 5459, 5417, 5460, -1, 5461, 5462, 5463, -1, 5459, 5460, 5447, -1, 5459, 5447, 5446, -1, 5461, 5456, 5462, -1, 5464, 5455, 5465, -1, 5464, 5446, 5449, -1, 5464, 5449, 5453, -1, 5466, 4983, 4982, -1, 5464, 5453, 5455, -1, 5467, 5468, 5127, -1, 5466, 5463, 4983, -1, 5467, 5465, 5468, -1, 5467, 5446, 5464, -1, 5467, 5415, 5416, -1, 5469, 5470, 5471, -1, 5467, 5127, 5415, -1, 5467, 5416, 5459, -1, 5469, 5471, 5472, -1, 5467, 5464, 5465, -1, 5467, 5459, 5446, -1, 5473, 5472, 5451, -1, 5473, 5451, 5450, -1, 5474, 5450, 5456, -1, 5474, 5456, 5461, -1, 5475, 5461, 5463, -1, 5475, 5463, 5466, -1, 5420, 5095, 5476, -1, 5477, 5476, 5470, -1, 5477, 5420, 5476, -1, 5477, 5470, 5469, -1, 5478, 4982, 4980, -1, 5478, 5466, 4982, -1, 5479, 5472, 5473, -1, 5479, 5469, 5472, -1, 5480, 4979, 4968, -1, 5481, 5450, 5474, -1, 5481, 5473, 5450, -1, 5482, 5461, 5475, -1, 5482, 5474, 5461, -1, 5483, 5466, 5478, -1, 5483, 5475, 5466, -1, 5484, 5469, 5479, -1, 5484, 5419, 5420, -1, 5484, 5420, 5477, -1, 5484, 5477, 5469, -1, 5485, 4980, 4979, -1, 5485, 4979, 5480, -1, 5485, 5478, 4980, -1, 5486, 5479, 5473, -1, 5486, 5473, 5481, -1, 5448, 5474, 5482, -1, 5487, 5488, 4973, -1, 5448, 5481, 5474, -1, 5487, 4973, 4978, -1, 5457, 5482, 5475, -1, 5457, 5475, 5483, -1, 5452, 5489, 5488, -1, 5490, 5480, 5491, -1, 5490, 5485, 5480, -1, 5490, 5478, 5485, -1, 5490, 5483, 5478, -1, 5452, 5488, 5487, -1, 5492, 5418, 5419, -1, 5492, 5479, 5486, -1, 5462, 4978, 4981, -1, 5492, 5484, 5479, -1, 5492, 5419, 5484, -1, 5462, 5487, 4978, -1, 5447, 5486, 5481, -1, 5447, 5481, 5448, -1, 5451, 5493, 5489, -1, 5451, 5489, 5452, -1, 5456, 5487, 5462, -1, 5449, 5448, 5482, -1, 5449, 5482, 5457, -1, 5456, 5452, 5487, -1, 5458, 5491, 5454, -1, 5458, 5457, 5483, -1, 5458, 5483, 5490, -1, 5458, 5490, 5491, -1, 5463, 4981, 4983, -1, 5460, 5417, 5418, -1, 5463, 5462, 4981, -1, 5460, 5418, 5492, -1, 5460, 5492, 5486, -1, 5460, 5486, 5447, -1, 5472, 5471, 5493, -1, 5472, 5493, 5451, -1, 5476, 5095, 5097, -1, 5476, 5097, 5494, -1, 5470, 5494, 5495, -1, 5470, 5476, 5494, -1, 5471, 5495, 5496, -1, 5471, 5470, 5495, -1, 5493, 5496, 5497, -1, 5493, 5471, 5496, -1, 5489, 5497, 5498, -1, 5489, 5493, 5497, -1, 5488, 5498, 5499, -1, 5488, 5489, 5498, -1, 4973, 5499, 4942, -1, 4973, 5488, 5499, -1, 5500, 5127, 5468, -1, 5500, 5128, 5127, -1, 5501, 5468, 5465, -1, 5501, 5500, 5468, -1, 5502, 5465, 5455, -1, 5502, 5501, 5465, -1, 5503, 5455, 5454, -1, 5503, 5502, 5455, -1, 5504, 5454, 5491, -1, 5504, 5503, 5454, -1, 5505, 5491, 5480, -1, 5505, 5504, 5491, -1, 4961, 5480, 4968, -1, 4961, 5505, 5480, -1, 5506, 5497, 5496, -1, 5507, 5508, 5509, -1, 5506, 5510, 5511, -1, 5506, 5512, 5497, -1, 5506, 5511, 5512, -1, 5507, 5513, 5508, -1, 5514, 5436, 5438, -1, 5515, 5516, 5517, -1, 4934, 5518, 4927, -1, 5514, 5438, 5519, -1, 5514, 5519, 5520, -1, 5515, 5509, 5516, -1, 5514, 5520, 5521, -1, 5522, 5496, 5495, -1, 5522, 5506, 5496, -1, 5523, 4938, 4940, -1, 5522, 5521, 5510, -1, 5522, 5510, 5506, -1, 5523, 5517, 4938, -1, 5524, 5495, 5494, -1, 5524, 5434, 5436, -1, 5524, 5436, 5514, -1, 5525, 5526, 5527, -1, 5524, 5514, 5521, -1, 5524, 5521, 5522, -1, 5525, 5527, 5528, -1, 5524, 5522, 5495, -1, 5524, 5494, 5434, -1, 5529, 5528, 5513, -1, 5529, 5513, 5507, -1, 5530, 5507, 5509, -1, 5530, 5509, 5515, -1, 5531, 5515, 5517, -1, 5531, 5517, 5523, -1, 5532, 5444, 5157, -1, 5532, 5533, 5526, -1, 5532, 5157, 5533, -1, 5532, 5526, 5525, -1, 5534, 4940, 4941, -1, 5534, 5523, 4940, -1, 5535, 5528, 5529, -1, 5535, 5525, 5528, -1, 5536, 5507, 5530, -1, 5536, 5529, 5507, -1, 5537, 5515, 5531, -1, 5537, 5530, 5515, -1, 5538, 5531, 5523, -1, 5538, 5523, 5534, -1, 5539, 5525, 5535, -1, 5539, 5442, 5444, -1, 5539, 5444, 5532, -1, 5539, 5532, 5525, -1, 5540, 4942, 5499, -1, 5540, 4941, 4942, -1, 5540, 5534, 4941, -1, 5541, 5535, 5529, -1, 5541, 5529, 5536, -1, 5542, 5536, 5530, -1, 5097, 5434, 5494, -1, 5542, 5530, 5537, -1, 5543, 4934, 4933, -1, 5511, 5537, 5531, -1, 5543, 5518, 4934, -1, 5511, 5531, 5538, -1, 5508, 5544, 5518, -1, 5545, 5499, 5498, -1, 5545, 5538, 5534, -1, 5545, 5534, 5540, -1, 5508, 5518, 5543, -1, 5545, 5540, 5499, -1, 5546, 5440, 5442, -1, 5546, 5535, 5541, -1, 5516, 4933, 4937, -1, 5546, 5539, 5535, -1, 5546, 5442, 5539, -1, 5516, 5543, 4933, -1, 5520, 5541, 5536, -1, 5513, 5547, 5544, -1, 5520, 5536, 5542, -1, 5513, 5544, 5508, -1, 5510, 5542, 5537, -1, 5509, 5543, 5516, -1, 5510, 5537, 5511, -1, 5509, 5508, 5543, -1, 5512, 5498, 5497, -1, 5512, 5545, 5498, -1, 5512, 5511, 5538, -1, 5512, 5538, 5545, -1, 5517, 4937, 4938, -1, 5519, 5438, 5440, -1, 5517, 5516, 4937, -1, 5519, 5440, 5546, -1, 5519, 5541, 5520, -1, 5519, 5546, 5541, -1, 5528, 5527, 5547, -1, 5528, 5547, 5513, -1, 5521, 5520, 5542, -1, 5521, 5542, 5510, -1, 5548, 5549, 5550, -1, 5551, 5552, 5553, -1, 5551, 5554, 5555, -1, 5548, 5550, 5556, -1, 5551, 5557, 5554, -1, 5551, 5555, 5552, -1, 5558, 5559, 5560, -1, 5558, 5215, 5217, -1, 5561, 5562, 5563, -1, 5558, 5217, 5564, -1, 5561, 5556, 5562, -1, 5558, 5564, 5559, -1, 5565, 5553, 5566, -1, 5567, 4956, 4955, -1, 5565, 5551, 5553, -1, 5565, 5560, 5557, -1, 5565, 5557, 5551, -1, 5567, 5563, 4956, -1, 5568, 5560, 5565, -1, 5568, 5569, 5102, -1, 5570, 5501, 5502, -1, 5568, 5566, 5569, -1, 5568, 5213, 5215, -1, 5568, 5102, 5213, -1, 5570, 5502, 5571, -1, 5568, 5215, 5558, -1, 5568, 5565, 5566, -1, 5568, 5558, 5560, -1, 5572, 5549, 5548, -1, 5572, 5571, 5549, -1, 5573, 5556, 5561, -1, 5573, 5548, 5556, -1, 5574, 5561, 5563, -1, 5574, 5563, 5567, -1, 5575, 5128, 5500, -1, 5575, 5500, 5501, -1, 5575, 5223, 5128, -1, 5575, 5501, 5570, -1, 5576, 4955, 4954, -1, 5576, 5567, 4955, -1, 5577, 5570, 5571, -1, 5577, 5571, 5572, -1, 5578, 5572, 5548, -1, 5578, 5548, 5573, -1, 5579, 5573, 5561, -1, 5579, 5561, 5574, -1, 5580, 5567, 5576, -1, 5580, 5574, 5567, -1, 5581, 5221, 5223, -1, 5581, 5223, 5575, -1, 5581, 5570, 5577, -1, 5581, 5575, 5570, -1, 5582, 4954, 4948, -1, 5582, 4948, 5583, -1, 5582, 5576, 4954, -1, 5584, 5577, 5572, -1, 5584, 5572, 5578, -1, 5585, 5578, 5573, -1, 5585, 5573, 5579, -1, 5554, 5579, 5574, -1, 5586, 5505, 4961, -1, 5586, 4960, 4957, -1, 5586, 4961, 4960, -1, 5554, 5574, 5580, -1, 5550, 5504, 5505, -1, 5587, 5582, 5583, -1, 5587, 5576, 5582, -1, 5587, 5583, 5588, -1, 5587, 5580, 5576, -1, 5550, 5505, 5586, -1, 5589, 5221, 5581, -1, 5589, 5577, 5584, -1, 5589, 5219, 5221, -1, 5562, 4957, 4958, -1, 5562, 5586, 4957, -1, 5589, 5581, 5577, -1, 5559, 5578, 5585, -1, 5549, 5503, 5504, -1, 5559, 5584, 5578, -1, 5549, 5504, 5550, -1, 5557, 5585, 5579, -1, 5556, 5586, 5562, -1, 5557, 5579, 5554, -1, 5556, 5550, 5586, -1, 5555, 5554, 5580, -1, 5555, 5580, 5587, -1, 5555, 5588, 5552, -1, 5555, 5587, 5588, -1, 5563, 4958, 4956, -1, 5564, 5217, 5219, -1, 5564, 5219, 5589, -1, 5563, 5562, 4958, -1, 5564, 5584, 5559, -1, 5564, 5589, 5584, -1, 5571, 5502, 5503, -1, 5571, 5503, 5549, -1, 5560, 5559, 5585, -1, 5560, 5585, 5557, -1, 5533, 5157, 5155, -1, 5533, 5155, 5590, -1, 5526, 5591, 5592, -1, 5526, 5590, 5591, -1, 5526, 5533, 5590, -1, 5527, 5526, 5592, -1, 5547, 5593, 5594, -1, 5547, 5592, 5593, -1, 5547, 5527, 5592, -1, 5544, 5594, 5595, -1, 5544, 5547, 5594, -1, 5518, 5595, 4841, -1, 5518, 5544, 5595, -1, 4927, 5518, 4841, -1, 5596, 5102, 5569, -1, 5596, 5103, 5102, -1, 5597, 5569, 5566, -1, 5597, 5596, 5569, -1, 5598, 5566, 5553, -1, 5598, 5597, 5566, -1, 5599, 5553, 5552, -1, 5599, 5598, 5553, -1, 5600, 5552, 5588, -1, 5600, 5599, 5552, -1, 5601, 5588, 5583, -1, 5601, 5600, 5588, -1, 4947, 5583, 4948, -1, 4947, 5601, 5583, -1, 5602, 5603, 5604, -1, 5602, 5604, 5605, -1, 5606, 5593, 5592, -1, 5606, 5607, 5593, -1, 5608, 5609, 5610, -1, 5606, 5611, 5607, -1, 5606, 5605, 5611, -1, 5608, 5612, 5609, -1, 4847, 5613, 4845, -1, 5614, 5424, 5426, -1, 5615, 5616, 5617, -1, 5614, 5426, 5618, -1, 5615, 5610, 5616, -1, 5614, 5618, 5603, -1, 5614, 5603, 5602, -1, 5619, 5592, 5591, -1, 5619, 5606, 5592, -1, 5619, 5605, 5606, -1, 5620, 4844, 4843, -1, 5619, 5602, 5605, -1, 5621, 5591, 5590, -1, 5620, 5617, 4844, -1, 5621, 5422, 5424, -1, 5621, 5424, 5614, -1, 5621, 5619, 5591, -1, 5622, 5623, 5624, -1, 5621, 5614, 5602, -1, 5622, 5625, 5623, -1, 5621, 5602, 5619, -1, 5622, 5624, 5626, -1, 5621, 5590, 5422, -1, 5627, 5626, 5612, -1, 5627, 5612, 5608, -1, 5628, 5610, 5615, -1, 5628, 5608, 5610, -1, 5629, 5615, 5617, -1, 5629, 5617, 5620, -1, 5630, 5432, 5134, -1, 5630, 5134, 5625, -1, 5630, 5625, 5622, -1, 5631, 4843, 4840, -1, 5631, 5620, 4843, -1, 5632, 5622, 5626, -1, 5632, 5626, 5627, -1, 5595, 4842, 4841, -1, 5633, 5627, 5608, -1, 5633, 5608, 5628, -1, 5634, 5615, 5629, -1, 5634, 5628, 5615, -1, 5635, 5629, 5620, -1, 5635, 5620, 5631, -1, 5636, 5430, 5432, -1, 5636, 5432, 5630, -1, 5636, 5622, 5632, -1, 5636, 5630, 5622, -1, 5637, 4840, 4842, -1, 5637, 4842, 5595, -1, 5637, 5631, 4840, -1, 5638, 5632, 5627, -1, 5638, 5627, 5633, -1, 5604, 5633, 5628, -1, 5155, 5422, 5590, -1, 5639, 5640, 5613, -1, 5604, 5628, 5634, -1, 5639, 5613, 4847, -1, 5611, 5629, 5635, -1, 5611, 5634, 5629, -1, 5641, 5595, 5594, -1, 5641, 5635, 5631, -1, 5609, 5640, 5639, -1, 5641, 5631, 5637, -1, 5641, 5637, 5595, -1, 5642, 5636, 5632, -1, 5642, 5428, 5430, -1, 5616, 4847, 4846, -1, 5642, 5632, 5638, -1, 5616, 5639, 4847, -1, 5642, 5430, 5636, -1, 5603, 5633, 5604, -1, 5603, 5638, 5633, -1, 5612, 5643, 5640, -1, 5612, 5624, 5643, -1, 5612, 5640, 5609, -1, 5610, 5639, 5616, -1, 5605, 5634, 5611, -1, 5605, 5604, 5634, -1, 5610, 5609, 5639, -1, 5607, 5611, 5635, -1, 5607, 5594, 5593, -1, 5607, 5641, 5594, -1, 5607, 5635, 5641, -1, 5617, 4846, 4844, -1, 5618, 5426, 5428, -1, 5617, 5616, 4846, -1, 5618, 5642, 5638, -1, 5618, 5638, 5603, -1, 5618, 5428, 5642, -1, 5626, 5624, 5612, -1, 5644, 5645, 5646, -1, 5644, 5646, 5647, -1, 5648, 5597, 5598, -1, 5648, 5647, 5649, -1, 5648, 5650, 5597, -1, 5648, 5649, 5650, -1, 5651, 4924, 4923, -1, 5651, 5652, 5653, -1, 5651, 4923, 5652, -1, 5651, 5653, 5654, -1, 5655, 5645, 5644, -1, 5655, 5654, 5645, -1, 5656, 5598, 5599, -1, 5656, 5648, 5598, -1, 5656, 5647, 5648, -1, 5656, 5644, 5647, -1, 5657, 4925, 4924, -1, 5657, 4924, 5651, -1, 5657, 5651, 5654, -1, 5657, 5654, 5655, -1, 5658, 5599, 5600, -1, 5658, 5656, 5599, -1, 5658, 5655, 5644, -1, 5658, 5644, 5656, -1, 5659, 5600, 5601, -1, 5659, 5601, 4947, -1, 5659, 4947, 4925, -1, 5596, 5202, 5103, -1, 5659, 5658, 5600, -1, 5659, 4925, 5657, -1, 5659, 5657, 5655, -1, 5659, 5655, 5658, -1, 4923, 4922, 5652, -1, 5660, 5661, 5107, -1, 5660, 5107, 5200, -1, 5662, 5663, 5661, -1, 5662, 5661, 5660, -1, 5664, 5200, 5201, -1, 5664, 5660, 5200, -1, 5646, 5665, 5663, -1, 5646, 5663, 5662, -1, 5649, 5660, 5664, -1, 5649, 5662, 5660, -1, 5666, 5201, 5202, -1, 5666, 5664, 5201, -1, 5666, 5202, 5596, -1, 5645, 5667, 5665, -1, 5645, 5665, 5646, -1, 5647, 5662, 5649, -1, 5647, 5646, 5662, -1, 5650, 5596, 5597, -1, 5650, 5664, 5666, -1, 5650, 5649, 5664, -1, 5650, 5666, 5596, -1, 5654, 5653, 5667, -1, 5654, 5667, 5645, -1, 5625, 5134, 5133, -1, 5625, 5133, 5668, -1, 5623, 5668, 5669, -1, 5623, 5625, 5668, -1, 5624, 5669, 5670, -1, 5624, 5623, 5669, -1, 5643, 5670, 5671, -1, 5643, 5624, 5670, -1, 5640, 5671, 5672, -1, 5640, 5643, 5671, -1, 5613, 5672, 5673, -1, 5613, 5640, 5672, -1, 4845, 5673, 4860, -1, 4845, 5613, 5673, -1, 5674, 5107, 5661, -1, 5674, 5105, 5107, -1, 5675, 5661, 5663, -1, 5675, 5674, 5661, -1, 5676, 5663, 5665, -1, 5676, 5675, 5663, -1, 5677, 5665, 5667, -1, 5677, 5676, 5665, -1, 5678, 5667, 5653, -1, 5678, 5677, 5667, -1, 5679, 5653, 5652, -1, 5679, 5652, 4922, -1, 5679, 5678, 5653, -1, 4912, 5679, 4922, -1, 5680, 5681, 5682, -1, 5683, 5684, 5685, -1, 5680, 5682, 5671, -1, 5680, 5686, 5681, -1, 5683, 5687, 5684, -1, 5688, 5362, 5363, -1, 5688, 5363, 5689, -1, 5690, 5691, 5692, -1, 5690, 5685, 5691, -1, 4877, 5693, 4871, -1, 5688, 5689, 5694, -1, 5688, 5694, 5695, -1, 5696, 5670, 5669, -1, 5696, 5680, 5670, -1, 5696, 5695, 5686, -1, 5697, 4868, 4865, -1, 5696, 5686, 5680, -1, 5697, 5692, 4868, -1, 5698, 5669, 5668, -1, 5698, 5668, 5133, -1, 5698, 5361, 5362, -1, 5698, 5133, 5361, -1, 5699, 5700, 5701, -1, 5698, 5696, 5669, -1, 5698, 5688, 5695, -1, 5698, 5695, 5696, -1, 5698, 5362, 5688, -1, 5699, 5701, 5702, -1, 5703, 5687, 5683, -1, 5703, 5702, 5687, -1, 5704, 5685, 5690, -1, 5704, 5683, 5685, -1, 5705, 5690, 5692, -1, 5705, 5692, 5697, -1, 5706, 5707, 5700, -1, 5706, 5366, 5707, -1, 5706, 5700, 5699, -1, 5366, 5122, 5707, -1, 5708, 4865, 4864, -1, 5708, 5697, 4865, -1, 5709, 5699, 5702, -1, 5709, 5702, 5703, -1, 5710, 5703, 5683, -1, 5710, 5683, 5704, -1, 5673, 4864, 4860, -1, 5711, 5704, 5690, -1, 5711, 5690, 5705, -1, 5712, 5705, 5697, -1, 5712, 5697, 5708, -1, 5713, 5699, 5709, -1, 5713, 5365, 5366, -1, 5713, 5366, 5706, -1, 5713, 5706, 5699, -1, 5714, 4864, 5673, -1, 5714, 5708, 4864, -1, 5715, 5709, 5703, -1, 5715, 5703, 5710, -1, 5716, 5704, 5711, -1, 5716, 5710, 5704, -1, 5681, 5711, 5705, -1, 5717, 4877, 4876, -1, 5717, 5693, 4877, -1, 5681, 5705, 5712, -1, 5718, 5673, 5672, -1, 5718, 5712, 5708, -1, 5684, 5719, 5693, -1, 5718, 5708, 5714, -1, 5718, 5714, 5673, -1, 5720, 5364, 5365, -1, 5684, 5693, 5717, -1, 5720, 5709, 5715, -1, 5720, 5365, 5713, -1, 5720, 5713, 5709, -1, 5691, 4876, 4869, -1, 5694, 5710, 5716, -1, 5691, 5717, 4876, -1, 5687, 5721, 5719, -1, 5694, 5715, 5710, -1, 5686, 5711, 5681, -1, 5687, 5719, 5684, -1, 5686, 5716, 5711, -1, 5685, 5717, 5691, -1, 5682, 5672, 5671, -1, 5682, 5718, 5672, -1, 5685, 5684, 5717, -1, 5682, 5712, 5718, -1, 5682, 5681, 5712, -1, 5689, 5363, 5364, -1, 5692, 4869, 4868, -1, 5689, 5364, 5720, -1, 5689, 5720, 5715, -1, 5692, 5691, 4869, -1, 5689, 5715, 5694, -1, 5702, 5701, 5721, -1, 5695, 5694, 5716, -1, 5702, 5721, 5687, -1, 5695, 5716, 5686, -1, 5680, 5671, 5670, -1, 5722, 5723, 5724, -1, 5725, 5676, 5677, -1, 5725, 5724, 5726, -1, 5725, 5726, 5727, -1, 5725, 5727, 5676, -1, 5728, 4928, 4926, -1, 5728, 5729, 5730, -1, 5728, 4926, 5729, -1, 5728, 5730, 5731, -1, 5732, 5731, 5733, -1, 5732, 5733, 5722, -1, 5734, 5677, 5678, -1, 5734, 5724, 5725, -1, 5734, 5725, 5677, -1, 5734, 5722, 5724, -1, 5735, 4917, 4928, -1, 5735, 4928, 5728, -1, 5735, 5728, 5731, -1, 5735, 5731, 5732, -1, 5736, 5678, 5679, -1, 5736, 5734, 5678, -1, 5736, 5732, 5722, -1, 5736, 5722, 5734, -1, 5737, 5679, 4912, -1, 5737, 4915, 4917, -1, 5737, 4912, 4915, -1, 5737, 4917, 5735, -1, 5737, 5736, 5679, -1, 5737, 5735, 5732, -1, 5737, 5732, 5736, -1, 5674, 5205, 5105, -1, 5738, 5739, 5111, -1, 5738, 5111, 5203, -1, 5740, 5741, 5739, -1, 5740, 5739, 5738, -1, 5742, 5203, 5204, -1, 5742, 5738, 5203, -1, 5723, 5743, 5741, -1, 5723, 5741, 5740, -1, 5726, 5738, 5742, -1, 5726, 5740, 5738, -1, 5744, 5674, 5675, -1, 5744, 5204, 5205, -1, 5744, 5742, 5204, -1, 5744, 5205, 5674, -1, 5733, 5745, 5743, -1, 5733, 5743, 5723, -1, 5724, 5723, 5740, -1, 5724, 5740, 5726, -1, 5727, 5675, 5676, -1, 5727, 5742, 5744, -1, 5727, 5744, 5675, -1, 5727, 5726, 5742, -1, 5731, 5730, 5745, -1, 5731, 5745, 5733, -1, 5722, 5733, 5723, -1, 5707, 5122, 5124, -1, 5707, 5124, 5746, -1, 5700, 5746, 5747, -1, 5700, 5707, 5746, -1, 5701, 5747, 5748, -1, 5701, 5700, 5747, -1, 5721, 5748, 5749, -1, 5721, 5701, 5748, -1, 5719, 5749, 5750, -1, 5719, 5721, 5749, -1, 5693, 5750, 5751, -1, 5693, 5719, 5750, -1, 4871, 5751, 4894, -1, 4871, 5693, 5751, -1, 5752, 5111, 5739, -1, 5752, 5109, 5111, -1, 5753, 5739, 5741, -1, 5753, 5752, 5739, -1, 5754, 5741, 5743, -1, 5754, 5753, 5741, -1, 5755, 5743, 5745, -1, 5755, 5754, 5743, -1, 5756, 5745, 5730, -1, 5756, 5755, 5745, -1, 5757, 5730, 5729, -1, 5757, 5756, 5730, -1, 4892, 5729, 4926, -1, 4892, 5757, 5729, -1, 5758, 5759, 5760, -1, 5758, 5760, 5761, -1, 5762, 5763, 5764, -1, 5765, 5749, 5748, -1, 5762, 5764, 5766, -1, 5765, 5767, 5749, -1, 5765, 5761, 5768, -1, 5765, 5768, 5767, -1, 5769, 5231, 5232, -1, 5770, 5771, 5772, -1, 5769, 5232, 5773, -1, 5770, 5766, 5771, -1, 5769, 5773, 5759, -1, 5769, 5759, 5758, -1, 5774, 5748, 5747, -1, 5774, 5765, 5748, -1, 5775, 4911, 4910, -1, 5774, 5761, 5765, -1, 5774, 5758, 5761, -1, 5775, 5772, 4911, -1, 5776, 5231, 5769, -1, 5776, 5747, 5746, -1, 5777, 5778, 5779, -1, 5776, 5746, 5124, -1, 5776, 5230, 5231, -1, 5777, 5779, 5780, -1, 5776, 5124, 5230, -1, 5776, 5769, 5758, -1, 5776, 5758, 5774, -1, 5776, 5774, 5747, -1, 5781, 5780, 5763, -1, 5781, 5763, 5762, -1, 5782, 5762, 5766, -1, 5782, 5766, 5770, -1, 5783, 5770, 5772, -1, 5783, 5772, 5775, -1, 5235, 5117, 5784, -1, 5785, 5784, 5778, -1, 5785, 5235, 5784, -1, 5785, 5778, 5777, -1, 5786, 4910, 4908, -1, 5786, 5775, 4910, -1, 5787, 5780, 5781, -1, 5787, 5777, 5780, -1, 5788, 5762, 5782, -1, 5788, 5781, 5762, -1, 5789, 5770, 5783, -1, 5789, 5782, 5770, -1, 5790, 5783, 5775, -1, 5790, 5775, 5786, -1, 5791, 5777, 5787, -1, 5791, 5234, 5235, -1, 5791, 5235, 5785, -1, 5791, 5785, 5777, -1, 5792, 4894, 5751, -1, 5792, 4906, 4894, -1, 5792, 4908, 4906, -1, 5792, 5786, 4908, -1, 5793, 5787, 5781, -1, 5793, 5781, 5788, -1, 5760, 5788, 5782, -1, 5794, 5795, 4900, -1, 5760, 5782, 5789, -1, 5794, 4900, 4907, -1, 5768, 5789, 5783, -1, 5768, 5783, 5790, -1, 5764, 5796, 5795, -1, 5797, 5751, 5750, -1, 5797, 5790, 5786, -1, 5764, 5795, 5794, -1, 5797, 5786, 5792, -1, 5797, 5792, 5751, -1, 5798, 5233, 5234, -1, 5798, 5787, 5793, -1, 5771, 4907, 4909, -1, 5798, 5791, 5787, -1, 5771, 5794, 4907, -1, 5798, 5234, 5791, -1, 5763, 5799, 5796, -1, 5759, 5793, 5788, -1, 5763, 5796, 5764, -1, 5759, 5788, 5760, -1, 5766, 5794, 5771, -1, 5761, 5760, 5789, -1, 5761, 5789, 5768, -1, 5766, 5764, 5794, -1, 5767, 5750, 5749, -1, 5767, 5797, 5750, -1, 5767, 5790, 5797, -1, 5772, 4909, 4911, -1, 5772, 5771, 4909, -1, 5767, 5768, 5790, -1, 5773, 5232, 5233, -1, 5773, 5233, 5798, -1, 5773, 5798, 5793, -1, 5773, 5793, 5759, -1, 5780, 5779, 5799, -1, 5780, 5799, 5763, -1, 5800, 5753, 5754, -1, 5800, 5801, 5802, -1, 5800, 5802, 5803, -1, 5800, 5803, 5753, -1, 5804, 4889, 4887, -1, 5804, 4887, 5805, -1, 5804, 5805, 5806, -1, 5807, 5806, 5808, -1, 5807, 5808, 5809, -1, 5810, 5754, 5755, -1, 5810, 5809, 5801, -1, 5810, 5800, 5754, -1, 5810, 5801, 5800, -1, 5811, 4891, 4889, -1, 5811, 4889, 5804, -1, 5811, 5804, 5806, -1, 5811, 5806, 5807, -1, 5812, 5755, 5756, -1, 5812, 5809, 5810, -1, 5812, 5810, 5755, -1, 5812, 5807, 5809, -1, 5813, 5756, 5757, -1, 5813, 5757, 4892, -1, 5813, 4892, 4891, -1, 5813, 4891, 5811, -1, 5813, 5812, 5756, -1, 5813, 5811, 5807, -1, 5813, 5807, 5812, -1, 5752, 5208, 5109, -1, 4887, 4879, 5805, -1, 5814, 5815, 5115, -1, 5814, 5816, 5815, -1, 5814, 5115, 5206, -1, 5817, 5818, 5816, -1, 5817, 5816, 5814, -1, 5819, 5206, 5207, -1, 5819, 5814, 5206, -1, 5820, 5821, 5818, -1, 5820, 5818, 5817, -1, 5802, 5814, 5819, -1, 5802, 5817, 5814, -1, 5822, 5207, 5208, -1, 5822, 5819, 5207, -1, 5822, 5208, 5752, -1, 5808, 5823, 5821, -1, 5808, 5821, 5820, -1, 5801, 5820, 5817, -1, 5801, 5817, 5802, -1, 5803, 5752, 5753, -1, 5803, 5819, 5822, -1, 5803, 5802, 5819, -1, 5803, 5822, 5752, -1, 5806, 5805, 5823, -1, 5806, 5823, 5808, -1, 5809, 5820, 5801, -1, 5809, 5808, 5820, -1, 5784, 5117, 5119, -1, 5784, 5119, 5824, -1, 5778, 5824, 5825, -1, 5778, 5784, 5824, -1, 5779, 5825, 5826, -1, 5779, 5778, 5825, -1, 5799, 5826, 5827, -1, 5799, 5779, 5826, -1, 5796, 5827, 5828, -1, 5796, 5799, 5827, -1, 5795, 5828, 5829, -1, 5795, 5796, 5828, -1, 4900, 5829, 4905, -1, 4900, 5795, 5829, -1, 5830, 5115, 5815, -1, 5830, 5113, 5115, -1, 5831, 5815, 5816, -1, 5831, 5830, 5815, -1, 5832, 5816, 5818, -1, 5832, 5831, 5816, -1, 5833, 5818, 5821, -1, 5833, 5832, 5818, -1, 5834, 5821, 5823, -1, 5834, 5823, 5805, -1, 5834, 5833, 5821, -1, 5835, 5834, 5805, -1, 4885, 5805, 4879, -1, 4885, 5835, 5805, -1, 5836, 5837, 5838, -1, 5836, 5838, 5839, -1, 5840, 5831, 5832, -1, 5840, 5839, 5841, -1, 5840, 5841, 5842, -1, 5840, 5842, 5831, -1, 5209, 5824, 5119, -1, 5843, 4905, 5829, -1, 5843, 5829, 5828, -1, 5843, 4890, 4905, -1, 5843, 5828, 5844, -1, 5845, 5844, 5837, -1, 5845, 5837, 5836, -1, 5846, 5832, 5833, -1, 5846, 5839, 5840, -1, 5846, 5836, 5839, -1, 5846, 5840, 5832, -1, 5847, 4888, 4890, -1, 5847, 4890, 5843, -1, 5847, 5844, 5845, -1, 5847, 5843, 5844, -1, 5848, 5833, 5834, -1, 5848, 5846, 5833, -1, 5848, 5845, 5836, -1, 5848, 5836, 5846, -1, 5849, 5834, 5835, -1, 5849, 4886, 4888, -1, 5849, 4888, 5847, -1, 5849, 5835, 4886, -1, 5849, 5848, 5834, -1, 5849, 5847, 5845, -1, 5849, 5845, 5848, -1, 4885, 4886, 5835, -1, 5850, 5824, 5209, -1, 5851, 5825, 5824, -1, 5851, 5824, 5850, -1, 5852, 5209, 5210, -1, 5852, 5850, 5209, -1, 5838, 5826, 5825, -1, 5838, 5825, 5851, -1, 5841, 5850, 5852, -1, 5841, 5851, 5850, -1, 5853, 5211, 5113, -1, 5853, 5210, 5211, -1, 5853, 5113, 5830, -1, 5853, 5852, 5210, -1, 5837, 5827, 5826, -1, 5837, 5826, 5838, -1, 5839, 5838, 5851, -1, 5839, 5851, 5841, -1, 5842, 5830, 5831, -1, 5842, 5853, 5830, -1, 5842, 5841, 5852, -1, 5842, 5852, 5853, -1, 5844, 5828, 5827, -1, 5844, 5827, 5837, -1, 4920, 4921, 5854, -1, 4920, 5854, 5855, -1, 4918, 5855, 5856, -1, 4918, 4920, 5855, -1, 4913, 5856, 5857, -1, 4913, 4918, 5856, -1, 4914, 5857, 5858, -1, 4914, 4913, 5857, -1, 4916, 5858, 5859, -1, 4916, 4914, 5858, -1, 4919, 5859, 5860, -1, 4919, 4916, 5859, -1, 4929, 5860, 5861, -1, 4929, 4919, 5860, -1, 4921, 4949, 5854, -1, 4949, 5862, 5854, -1, 4953, 5863, 5864, -1, 4952, 5864, 5865, -1, 4952, 4953, 5864, -1, 4951, 5865, 5866, -1, 4951, 4952, 5865, -1, 4950, 5866, 5862, -1, 4950, 4951, 5866, -1, 4949, 4950, 5862, -1, 5863, 4959, 5867, -1, 4953, 4959, 5863, -1, 4964, 4965, 5868, -1, 4964, 5868, 5869, -1, 4963, 5869, 5870, -1, 4963, 4964, 5869, -1, 4962, 5870, 5871, -1, 4962, 4963, 5870, -1, 4959, 5871, 5867, -1, 4959, 4962, 5871, -1, 5868, 4967, 5872, -1, 4965, 4967, 5868, -1, 4971, 4972, 5873, -1, 4971, 5873, 5874, -1, 4970, 5874, 5875, -1, 4970, 4971, 5874, -1, 4969, 5875, 5876, -1, 4969, 4970, 5875, -1, 4967, 5876, 5872, -1, 4967, 4969, 5876, -1, 5873, 4974, 5877, -1, 4972, 4974, 5873, -1, 4977, 4966, 5878, -1, 4977, 5878, 5879, -1, 4976, 5879, 5880, -1, 4976, 4977, 5879, -1, 4975, 5880, 5881, -1, 4975, 4976, 5880, -1, 4974, 5881, 5877, -1, 4974, 4975, 5881, -1, 5882, 4966, 4943, -1, 5878, 4966, 5882, -1, 4939, 5883, 5884, -1, 4946, 5884, 5885, -1, 4946, 4939, 5884, -1, 4945, 5885, 5886, -1, 4945, 4946, 5885, -1, 4944, 5886, 5882, -1, 4944, 4945, 5886, -1, 4943, 4944, 5882, -1, 5883, 4936, 5887, -1, 4939, 4936, 5883, -1, 4931, 4930, 5888, -1, 4931, 5888, 5889, -1, 4932, 5889, 5890, -1, 4932, 4931, 5889, -1, 4935, 5890, 5891, -1, 4935, 4932, 5890, -1, 4936, 5891, 5887, -1, 4936, 4935, 5891, -1, 5861, 4930, 4929, -1, 5888, 4930, 5861, -1, 5892, 5893, 5894, -1, 4822, 5893, 5892, -1, 5895, 5896, 5897, -1, 5898, 5896, 5895, -1, 5899, 5896, 5898, -1, 4822, 5896, 5893, -1, 5897, 5896, 4822, -1, 5900, 5901, 5902, -1, 5903, 5904, 5905, -1, 5906, 5904, 5903, -1, 5902, 5904, 5906, -1, 5907, 5904, 5901, -1, 5901, 5904, 5902, -1, 5907, 4823, 5904, -1, 4823, 5908, 5904, -1, 5909, 5910, 5911, -1, 5912, 5910, 5909, -1, 5908, 5910, 5912, -1, 4823, 4826, 5908, -1, 5908, 4826, 5910, -1, 4826, 5913, 5910, -1, 5914, 5915, 5916, -1, 5913, 5917, 5914, -1, 4826, 5917, 5913, -1, 5914, 5917, 5915, -1, 5907, 5918, 4823, -1, 5919, 5920, 5918, -1, 5920, 5921, 5918, -1, 5921, 5922, 5918, -1, 5918, 4819, 4823, -1, 5922, 4819, 5918, -1, 5922, 5923, 4819, -1, 5924, 5925, 5923, -1, 5925, 5926, 5923, -1, 5923, 5927, 4819, -1, 5926, 5927, 5923, -1, 4822, 5892, 4826, -1, 4826, 5892, 5917, -1, 4819, 5897, 4822, -1, 5927, 5897, 4819, -1, 5928, 5894, 5929, -1, 5892, 5894, 5928, -1, 5930, 5931, 5932, -1, 5930, 5932, 5933, -1, 5934, 5933, 5935, -1, 5934, 5930, 5933, -1, 5936, 5935, 5937, -1, 5936, 5934, 5935, -1, 5938, 5937, 5939, -1, 5938, 5936, 5937, -1, 5940, 5939, 5941, -1, 5940, 5938, 5939, -1, 5942, 5941, 5943, -1, 5942, 5940, 5941, -1, 5944, 5943, 5945, -1, 5944, 5942, 5943, -1, 5946, 5947, 5948, -1, 5949, 5948, 5950, -1, 5949, 5946, 5948, -1, 5951, 5950, 5952, -1, 5951, 5949, 5950, -1, 5953, 5952, 5954, -1, 5953, 5951, 5952, -1, 5955, 5953, 5954, -1, 5956, 5957, 5958, -1, 5959, 5958, 5960, -1, 5959, 5956, 5958, -1, 5961, 5960, 5962, -1, 5961, 5959, 5960, -1, 5963, 5962, 5964, -1, 5963, 5961, 5962, -1, 5965, 5963, 5964, -1, 5966, 5967, 5968, -1, 5969, 5968, 5970, -1, 5969, 5966, 5968, -1, 5971, 5970, 5972, -1, 5971, 5969, 5970, -1, 5973, 5972, 5974, -1, 5973, 5971, 5972, -1, 5975, 5973, 5974, -1, 5976, 5977, 5978, -1, 5976, 5978, 5979, -1, 5980, 5979, 5981, -1, 5980, 5976, 5979, -1, 5982, 5981, 5983, -1, 5982, 5980, 5981, -1, 5984, 5983, 5985, -1, 5984, 5982, 5983, -1, 5966, 5978, 5977, -1, 5966, 5977, 5967, -1, 5964, 5975, 5974, -1, 5965, 5964, 5974, -1, 5986, 5987, 5988, -1, 5986, 5988, 5989, -1, 5990, 5989, 5991, -1, 5990, 5986, 5989, -1, 5992, 5991, 5993, -1, 5992, 5990, 5991, -1, 5994, 5993, 5995, -1, 5994, 5992, 5993, -1, 5988, 5957, 5956, -1, 5987, 5957, 5988, -1, 5996, 5997, 5998, -1, 5999, 5998, 6000, -1, 5999, 5996, 5998, -1, 6001, 6000, 6002, -1, 6001, 5999, 6000, -1, 6003, 6002, 6004, -1, 6003, 6001, 6002, -1, 6005, 6003, 6004, -1, 6004, 5995, 6005, -1, 5994, 5995, 6004, -1, 5997, 5996, 5947, -1, 5946, 5997, 5947, -1, 5955, 5954, 5944, -1, 5955, 5944, 5945, -1, 5984, 5932, 5931, -1, 5985, 5932, 5984, -1, 4857, 6006, 6007, -1, 4854, 6007, 6008, -1, 4854, 4857, 6007, -1, 4852, 6008, 6009, -1, 4852, 4854, 6008, -1, 4850, 6009, 6010, -1, 4850, 4852, 6009, -1, 4848, 4850, 6010, -1, 4857, 4861, 6006, -1, 4861, 6011, 6006, -1, 4867, 6012, 6013, -1, 4866, 6013, 6014, -1, 4866, 4867, 6013, -1, 4863, 6014, 6015, -1, 4863, 4866, 6014, -1, 4862, 6015, 6011, -1, 4862, 4863, 6015, -1, 4861, 4862, 6011, -1, 6012, 4870, 6016, -1, 4867, 4870, 6012, -1, 4875, 6017, 6018, -1, 4874, 6018, 6019, -1, 4874, 4875, 6018, -1, 4873, 6019, 6020, -1, 4873, 4874, 6019, -1, 4872, 6020, 6016, -1, 4872, 4873, 6020, -1, 4870, 4872, 6016, -1, 4875, 6021, 6017, -1, 4893, 6021, 4875, -1, 4897, 4898, 6022, -1, 4897, 6022, 6023, -1, 4896, 6023, 6024, -1, 4896, 4897, 6023, -1, 4895, 6024, 6025, -1, 4895, 4896, 6024, -1, 4893, 6025, 6021, -1, 4893, 4895, 6025, -1, 6022, 4899, 6026, -1, 4898, 4899, 6022, -1, 4904, 6027, 6028, -1, 4903, 6028, 6029, -1, 4903, 4904, 6028, -1, 4902, 6029, 6030, -1, 4902, 4903, 6029, -1, 4901, 6030, 6026, -1, 4901, 4902, 6030, -1, 4899, 4901, 6026, -1, 6031, 4904, 4878, -1, 6027, 4904, 6031, -1, 4859, 4858, 6032, -1, 4859, 6032, 6033, -1, 4884, 6033, 6034, -1, 4884, 4859, 6033, -1, 4883, 6034, 6035, -1, 4883, 4884, 6034, -1, 4882, 6035, 6036, -1, 4882, 4883, 6035, -1, 4881, 6036, 6037, -1, 4881, 4882, 6036, -1, 4880, 6037, 6038, -1, 4880, 4881, 6037, -1, 4878, 6038, 6031, -1, 4878, 4880, 6038, -1, 6039, 4858, 4856, -1, 6032, 4858, 6039, -1, 4849, 6040, 6041, -1, 4851, 6041, 6042, -1, 4851, 4849, 6041, -1, 4853, 6042, 6043, -1, 4853, 4851, 6042, -1, 4855, 6043, 6039, -1, 4855, 4853, 6043, -1, 4856, 4855, 6039, -1, 6040, 4848, 6010, -1, 4849, 4848, 6040, -1, 6044, 6045, 6046, -1, 6047, 6048, 6049, -1, 6050, 6048, 6047, -1, 6051, 6052, 6053, -1, 6045, 6054, 6055, -1, 6044, 6054, 6045, -1, 4834, 6054, 6044, -1, 6048, 6056, 6049, -1, 4834, 6056, 6054, -1, 6049, 6056, 4834, -1, 6057, 6058, 6059, -1, 6060, 6058, 6057, -1, 6061, 6058, 6060, -1, 6062, 6063, 6052, -1, 6052, 6063, 6053, -1, 6053, 4828, 6061, -1, 6061, 4828, 6058, -1, 6063, 4828, 6053, -1, 6058, 4832, 6064, -1, 4828, 4832, 6058, -1, 6065, 6066, 6067, -1, 6068, 6066, 6065, -1, 6069, 6066, 6068, -1, 6070, 6066, 6069, -1, 6071, 6066, 6070, -1, 6064, 6066, 6071, -1, 4832, 6066, 6064, -1, 6072, 6073, 6074, -1, 6075, 6076, 6073, -1, 6073, 6076, 6074, -1, 6074, 4829, 6063, -1, 6063, 4829, 4828, -1, 6076, 4829, 6074, -1, 6076, 6077, 4829, -1, 6078, 6079, 6080, -1, 6079, 6081, 6080, -1, 6080, 6081, 6077, -1, 6077, 6081, 4829, -1, 4834, 6044, 4832, -1, 4832, 6044, 6066, -1, 4829, 6049, 4834, -1, 6081, 6049, 4829, -1, 6082, 6083, 6084, -1, 6085, 6084, 6086, -1, 6085, 6082, 6084, -1, 6087, 6086, 6088, -1, 6087, 6085, 6086, -1, 6089, 6088, 6090, -1, 6089, 6087, 6088, -1, 6091, 6089, 6090, -1, 6092, 6093, 6094, -1, 6092, 6094, 6095, -1, 6096, 6095, 6097, -1, 6096, 6092, 6095, -1, 6098, 6097, 6099, -1, 6098, 6096, 6097, -1, 6100, 6099, 6101, -1, 6100, 6098, 6099, -1, 6102, 6103, 6104, -1, 6102, 6104, 6105, -1, 6106, 6105, 6107, -1, 6106, 6102, 6105, -1, 6108, 6107, 6109, -1, 6108, 6106, 6107, -1, 6110, 6109, 6111, -1, 6110, 6108, 6109, -1, 6112, 6113, 6114, -1, 6112, 6114, 6115, -1, 6116, 6115, 6117, -1, 6116, 6112, 6115, -1, 6118, 6117, 6119, -1, 6118, 6116, 6117, -1, 6120, 6119, 6121, -1, 6120, 6118, 6119, -1, 6122, 6123, 6124, -1, 6122, 6124, 6125, -1, 6126, 6125, 6127, -1, 6126, 6122, 6125, -1, 6128, 6127, 6129, -1, 6128, 6126, 6127, -1, 6130, 6129, 6131, -1, 6130, 6128, 6129, -1, 6114, 6113, 6124, -1, 6114, 6124, 6123, -1, 6132, 6133, 6134, -1, 6132, 6134, 6135, -1, 6136, 6135, 6137, -1, 6136, 6132, 6135, -1, 6138, 6137, 6139, -1, 6138, 6136, 6137, -1, 6140, 6139, 6141, -1, 6140, 6138, 6139, -1, 6141, 6130, 6131, -1, 6141, 6131, 6140, -1, 6103, 6134, 6104, -1, 6134, 6133, 6104, -1, 6100, 6110, 6111, -1, 6101, 6110, 6100, -1, 6142, 6143, 6144, -1, 6142, 6144, 6145, -1, 6146, 6145, 6147, -1, 6146, 6142, 6145, -1, 6148, 6147, 6149, -1, 6148, 6146, 6147, -1, 6150, 6149, 6151, -1, 6150, 6148, 6149, -1, 6152, 6151, 6153, -1, 6152, 6150, 6151, -1, 6154, 6153, 6155, -1, 6154, 6152, 6153, -1, 6156, 6155, 6157, -1, 6156, 6154, 6155, -1, 6157, 6094, 6093, -1, 6157, 6093, 6156, -1, 6082, 6143, 6083, -1, 6082, 6144, 6143, -1, 6120, 6091, 6090, -1, 6121, 6091, 6120, -1, 6017, 6021, 6123, -1, 6123, 6021, 6114, -1, 6115, 6114, 6021, -1, 6115, 6025, 6024, -1, 6115, 6021, 6025, -1, 6117, 6024, 6023, -1, 6117, 6115, 6024, -1, 6119, 6023, 6022, -1, 6119, 6117, 6023, -1, 6121, 6119, 6022, -1, 6128, 6130, 6016, -1, 6128, 6020, 6019, -1, 6128, 6016, 6020, -1, 6126, 6019, 6018, -1, 6126, 6128, 6019, -1, 6122, 6018, 6017, -1, 6122, 6126, 6018, -1, 6123, 6122, 6017, -1, 6022, 6026, 6121, -1, 6121, 6026, 6091, -1, 6141, 6012, 6130, -1, 6012, 6016, 6130, -1, 6091, 6026, 6030, -1, 6089, 6091, 6030, -1, 6087, 6030, 6029, -1, 6087, 6089, 6030, -1, 6085, 6029, 6028, -1, 6085, 6087, 6029, -1, 6082, 6028, 6027, -1, 6082, 6085, 6028, -1, 6134, 6011, 6015, -1, 6135, 6134, 6015, -1, 6137, 6015, 6014, -1, 6137, 6135, 6015, -1, 6139, 6014, 6013, -1, 6139, 6137, 6014, -1, 6141, 6013, 6012, -1, 6141, 6139, 6013, -1, 6027, 6031, 6082, -1, 6082, 6031, 6144, -1, 6103, 6011, 6134, -1, 6006, 6011, 6103, -1, 6144, 6031, 6038, -1, 6145, 6144, 6038, -1, 6147, 6038, 6037, -1, 6147, 6145, 6038, -1, 6149, 6037, 6036, -1, 6149, 6147, 6037, -1, 6151, 6036, 6035, -1, 6151, 6149, 6036, -1, 6153, 6035, 6034, -1, 6153, 6151, 6035, -1, 6155, 6033, 6032, -1, 6155, 6034, 6033, -1, 6155, 6153, 6034, -1, 6157, 6155, 6032, -1, 6110, 6010, 6009, -1, 6108, 6009, 6008, -1, 6108, 6110, 6009, -1, 6106, 6008, 6007, -1, 6106, 6108, 6008, -1, 6102, 6106, 6007, -1, 6103, 6007, 6006, -1, 6103, 6102, 6007, -1, 6032, 6039, 6157, -1, 6157, 6039, 6094, -1, 6101, 6010, 6110, -1, 6040, 6010, 6101, -1, 6095, 6094, 6039, -1, 6095, 6039, 6043, -1, 6097, 6043, 6042, -1, 6097, 6095, 6043, -1, 6099, 6041, 6040, -1, 6099, 6042, 6041, -1, 6099, 6097, 6042, -1, 6101, 6099, 6040, -1, 5868, 5872, 5994, -1, 5868, 5994, 6004, -1, 5992, 5994, 5872, -1, 5992, 5876, 5875, -1, 5992, 5872, 5876, -1, 5990, 5875, 5874, -1, 5990, 5992, 5875, -1, 5986, 5990, 5874, -1, 5987, 5874, 5873, -1, 5987, 5986, 5874, -1, 5998, 5997, 5867, -1, 5998, 5867, 5871, -1, 6000, 5871, 5870, -1, 6000, 5998, 5871, -1, 6002, 5869, 5868, -1, 6002, 5870, 5869, -1, 6002, 6000, 5870, -1, 6004, 6002, 5868, -1, 5877, 5957, 5987, -1, 5873, 5877, 5987, -1, 5863, 5867, 5997, -1, 5863, 5997, 5946, -1, 5958, 5957, 5877, -1, 5958, 5877, 5881, -1, 5960, 5881, 5880, -1, 5960, 5958, 5881, -1, 5962, 5880, 5879, -1, 5962, 5960, 5880, -1, 5964, 5879, 5878, -1, 5964, 5962, 5879, -1, 5953, 5955, 5862, -1, 5953, 5862, 5866, -1, 5951, 5866, 5865, -1, 5951, 5953, 5866, -1, 5949, 5864, 5863, -1, 5949, 5865, 5864, -1, 5949, 5951, 5865, -1, 5946, 5949, 5863, -1, 5878, 5882, 5975, -1, 5878, 5975, 5964, -1, 5854, 5862, 5955, -1, 5854, 5955, 5945, -1, 5973, 5975, 5882, -1, 5973, 5882, 5886, -1, 5971, 5886, 5885, -1, 5971, 5973, 5886, -1, 5969, 5884, 5883, -1, 5969, 5885, 5884, -1, 5969, 5971, 5885, -1, 5966, 5969, 5883, -1, 5933, 5932, 5861, -1, 5933, 5860, 5859, -1, 5933, 5861, 5860, -1, 5935, 5859, 5858, -1, 5935, 5933, 5859, -1, 5937, 5858, 5857, -1, 5937, 5935, 5858, -1, 5939, 5857, 5856, -1, 5939, 5937, 5857, -1, 5941, 5856, 5855, -1, 5941, 5939, 5856, -1, 5943, 5855, 5854, -1, 5943, 5941, 5855, -1, 5945, 5943, 5854, -1, 5887, 5978, 5966, -1, 5883, 5887, 5966, -1, 5888, 5861, 5932, -1, 5888, 5932, 5985, -1, 5978, 5887, 5891, -1, 5979, 5891, 5890, -1, 5979, 5978, 5891, -1, 5981, 5890, 5889, -1, 5981, 5979, 5890, -1, 5983, 5889, 5888, -1, 5983, 5981, 5889, -1, 5985, 5983, 5888, -1, 6100, 6111, 6061, -1, 6061, 6111, 6053, -1, 6104, 6063, 6062, -1, 6105, 6062, 6052, -1, 6105, 6104, 6062, -1, 6107, 6105, 6052, -1, 6109, 6052, 6051, -1, 6109, 6107, 6052, -1, 6111, 6051, 6053, -1, 6111, 6109, 6051, -1, 6098, 6100, 6061, -1, 6098, 6060, 6057, -1, 6098, 6061, 6060, -1, 6096, 6057, 6059, -1, 6096, 6098, 6057, -1, 6092, 6059, 6058, -1, 6092, 6096, 6059, -1, 6093, 6092, 6058, -1, 6104, 6133, 6063, -1, 6063, 6133, 6074, -1, 6058, 6064, 6156, -1, 6058, 6156, 6093, -1, 6140, 6076, 6075, -1, 6138, 6075, 6073, -1, 6138, 6140, 6075, -1, 6136, 6073, 6072, -1, 6136, 6138, 6073, -1, 6132, 6136, 6072, -1, 6133, 6072, 6074, -1, 6133, 6132, 6072, -1, 6154, 6156, 6064, -1, 6154, 6071, 6070, -1, 6154, 6064, 6071, -1, 6152, 6070, 6069, -1, 6152, 6154, 6070, -1, 6150, 6069, 6068, -1, 6150, 6152, 6069, -1, 6148, 6068, 6065, -1, 6148, 6150, 6068, -1, 6146, 6065, 6067, -1, 6146, 6148, 6065, -1, 6142, 6146, 6067, -1, 6143, 6067, 6066, -1, 6143, 6142, 6067, -1, 6076, 6140, 6131, -1, 6077, 6076, 6131, -1, 6044, 6143, 6066, -1, 6083, 6143, 6044, -1, 6125, 6124, 6081, -1, 6125, 6081, 6079, -1, 6127, 6079, 6078, -1, 6127, 6125, 6079, -1, 6129, 6080, 6077, -1, 6129, 6078, 6080, -1, 6129, 6127, 6078, -1, 6131, 6129, 6077, -1, 6083, 6044, 6046, -1, 6084, 6046, 6045, -1, 6084, 6083, 6046, -1, 6086, 6045, 6055, -1, 6086, 6084, 6045, -1, 6088, 6086, 6055, -1, 6090, 6055, 6054, -1, 6090, 6088, 6055, -1, 6049, 6081, 6124, -1, 6049, 6124, 6113, -1, 6056, 6120, 6054, -1, 6120, 6090, 6054, -1, 6118, 6120, 6056, -1, 6118, 6048, 6050, -1, 6118, 6056, 6048, -1, 6116, 6050, 6047, -1, 6116, 6118, 6050, -1, 6112, 6047, 6049, -1, 6112, 6116, 6047, -1, 6113, 6112, 6049, -1, 5988, 5956, 5896, -1, 5896, 5956, 5893, -1, 5963, 5965, 5892, -1, 5963, 5892, 5928, -1, 5961, 5928, 5929, -1, 5961, 5963, 5928, -1, 5959, 5894, 5893, -1, 5959, 5929, 5894, -1, 5959, 5961, 5929, -1, 5956, 5959, 5893, -1, 5988, 5896, 5899, -1, 5989, 5899, 5898, -1, 5989, 5988, 5899, -1, 5991, 5898, 5895, -1, 5991, 5989, 5898, -1, 5993, 5895, 5897, -1, 5993, 5991, 5895, -1, 5995, 5993, 5897, -1, 5917, 5892, 5965, -1, 5917, 5965, 5974, -1, 5927, 5995, 5897, -1, 6005, 5995, 5927, -1, 5968, 5967, 5913, -1, 5968, 5914, 5916, -1, 5968, 5913, 5914, -1, 5970, 5916, 5915, -1, 5970, 5968, 5916, -1, 5972, 5915, 5917, -1, 5972, 5970, 5915, -1, 5974, 5972, 5917, -1, 6003, 6005, 5927, -1, 6003, 5926, 5925, -1, 6003, 5927, 5926, -1, 6001, 5925, 5924, -1, 6001, 6003, 5925, -1, 5999, 5924, 5923, -1, 5999, 6001, 5924, -1, 5996, 5999, 5923, -1, 5910, 5913, 5967, -1, 5910, 5967, 5977, -1, 5923, 5922, 5947, -1, 5923, 5947, 5996, -1, 5982, 5984, 5908, -1, 5982, 5912, 5909, -1, 5982, 5908, 5912, -1, 5980, 5909, 5911, -1, 5980, 5982, 5909, -1, 5976, 5980, 5911, -1, 5977, 5911, 5910, -1, 5977, 5976, 5911, -1, 5948, 5947, 5922, -1, 5948, 5922, 5921, -1, 5950, 5921, 5920, -1, 5950, 5948, 5921, -1, 5952, 5919, 5918, -1, 5952, 5920, 5919, -1, 5952, 5950, 5920, -1, 5954, 5952, 5918, -1, 5984, 5931, 5908, -1, 5908, 5931, 5904, -1, 5918, 5907, 5944, -1, 5918, 5944, 5954, -1, 5942, 5944, 5907, -1, 5942, 5907, 5901, -1, 5940, 5901, 5900, -1, 5940, 5942, 5901, -1, 5938, 5900, 5902, -1, 5938, 5940, 5900, -1, 5936, 5902, 5906, -1, 5936, 5938, 5902, -1, 5934, 5906, 5903, -1, 5934, 5936, 5906, -1, 5930, 5905, 5904, -1, 5930, 5903, 5905, -1, 5930, 5934, 5903, -1, 5931, 5930, 5904, -1, 5165, 6158, 6159, -1, 5164, 6158, 5165, -1, 5164, 5167, 6158, -1, 5167, 6160, 6158, -1, 6161, 5167, 5166, -1, 6160, 5167, 6161, -1, 6159, 5166, 5165, -1, 6161, 5166, 6159, -1, 6159, 4831, 4830, -1, 6159, 6158, 4831, -1, 4830, 4827, 6159, -1, 4827, 6161, 6159, -1, 6160, 4833, 6158, -1, 6161, 4833, 6160, -1, 6158, 4833, 4831, -1, 4827, 4833, 6161, -1, 4837, 4839, 6162, -1, 4839, 6163, 6162, -1, 6164, 4839, 4838, -1, 6163, 4839, 6164, -1, 6165, 4838, 4835, -1, 6164, 4838, 6165, -1, 4835, 6162, 6165, -1, 4837, 6162, 4835, -1, 4824, 6162, 4825, -1, 6165, 6162, 4824, -1, 4824, 6164, 6165, -1, 4824, 4821, 6164, -1, 6162, 6163, 4825, -1, 4821, 6163, 6164, -1, 6163, 4820, 4825, -1, 4821, 4820, 6163, -1, 5009, 5011, 5176, -1, 5009, 5176, 5191, -1, 5177, 5003, 5193, -1, 5000, 5003, 5177, -1, 4814, 5034, 6166, -1, 4990, 5034, 4814, -1, 6167, 4817, 6168, -1, 6169, 4817, 6167, -1, 6170, 4817, 6169, -1, 6171, 4817, 6170, -1, 6172, 4817, 6171, -1, 5153, 4817, 6172, -1, 6166, 4811, 4814, -1, 6168, 4811, 6166, -1, 4815, 4811, 4817, -1, 4817, 4811, 6168, -1, 5035, 4996, 6173, -1, 5035, 4806, 4996, -1, 5162, 5161, 6174, -1, 5162, 6174, 6175, -1, 5162, 6175, 6176, -1, 5162, 6176, 6177, -1, 5162, 6177, 6178, -1, 5162, 6178, 6179, -1, 4995, 5023, 5162, -1, 4995, 6179, 6173, -1, 4995, 6173, 4996, -1, 4995, 5162, 6179, -1, 5315, 5177, 5176, -1, 5312, 5177, 5315, -1, 4802, 5184, 5156, -1, 4804, 5184, 4802, -1, 4991, 5160, 5170, -1, 4991, 5170, 4993, -1, 6180, 5324, 6181, -1, 6180, 6181, 5326, -1, 6180, 6182, 5324, -1, 6183, 6184, 6182, -1, 6183, 6182, 6180, -1, 5320, 6185, 5047, -1, 6186, 6184, 6183, -1, 6186, 6187, 6184, -1, 6188, 5188, 5189, -1, 6188, 6189, 6187, -1, 6188, 5189, 6189, -1, 6188, 6187, 6186, -1, 6190, 5326, 5328, -1, 6191, 5326, 6190, -1, 6191, 6180, 5326, -1, 6192, 6183, 6180, -1, 6192, 6180, 6191, -1, 6193, 6183, 6192, -1, 6193, 6186, 6183, -1, 6194, 6193, 5182, -1, 6194, 6186, 6193, -1, 6194, 5185, 5188, -1, 6194, 5182, 5185, -1, 6194, 5188, 6188, -1, 6194, 6188, 6186, -1, 6195, 5328, 5330, -1, 6195, 6190, 5328, -1, 6196, 6190, 6195, -1, 6197, 6190, 6196, -1, 6197, 6191, 6190, -1, 6198, 6191, 6197, -1, 6198, 6192, 6191, -1, 6198, 6197, 5181, -1, 6199, 5182, 6193, -1, 6199, 6192, 6198, -1, 6199, 6198, 5181, -1, 6199, 6193, 6192, -1, 6200, 5181, 5182, -1, 6200, 6199, 5181, -1, 6200, 5182, 6199, -1, 6201, 5330, 6202, -1, 6201, 6202, 6203, -1, 6201, 6195, 5330, -1, 6204, 6203, 6205, -1, 6204, 6196, 6195, -1, 6204, 6201, 6203, -1, 6204, 6195, 6201, -1, 6206, 6205, 6207, -1, 6206, 6196, 6204, -1, 6206, 6197, 6196, -1, 6206, 5181, 6197, -1, 6206, 6204, 6205, -1, 6208, 6207, 6209, -1, 6208, 6206, 6207, -1, 6208, 5181, 6206, -1, 6210, 6209, 6211, -1, 6210, 6208, 6209, -1, 6210, 5181, 6208, -1, 6212, 5178, 5181, -1, 6212, 5181, 6210, -1, 6213, 5320, 5322, -1, 6214, 6211, 6215, -1, 6214, 6210, 6211, -1, 6216, 6215, 6217, -1, 6218, 6219, 6185, -1, 6216, 6217, 5179, -1, 6216, 5179, 5178, -1, 6218, 6185, 5320, -1, 6216, 5178, 6212, -1, 6216, 6212, 6210, -1, 6218, 6213, 5322, -1, 6216, 6214, 6215, -1, 6216, 6210, 6214, -1, 6218, 5320, 6213, -1, 6220, 6221, 6219, -1, 6220, 6219, 6218, -1, 6222, 6221, 6220, -1, 6223, 5190, 5175, -1, 6223, 5189, 5190, -1, 6223, 5175, 6221, -1, 6223, 6221, 6222, -1, 6224, 5322, 5324, -1, 6182, 5322, 6224, -1, 6182, 6218, 5322, -1, 6182, 6224, 5324, -1, 6184, 6220, 6218, -1, 6184, 6218, 6182, -1, 6187, 6222, 6220, -1, 6187, 6220, 6184, -1, 6189, 5189, 6223, -1, 6189, 6223, 6222, -1, 6189, 6222, 6187, -1, 6181, 5324, 5326, -1, 6221, 5175, 5169, -1, 6221, 6225, 6226, -1, 6221, 5169, 6225, -1, 6219, 6226, 6227, -1, 6219, 6221, 6226, -1, 6185, 6227, 5066, -1, 6185, 6219, 6227, -1, 5047, 6185, 5066, -1, 6228, 6229, 6230, -1, 6228, 6230, 6231, -1, 6232, 5198, 5168, -1, 6232, 5168, 6233, -1, 6232, 6233, 6229, -1, 6232, 6229, 6228, -1, 6234, 5370, 5368, -1, 6235, 5370, 6234, -1, 6235, 5368, 5199, -1, 6235, 6231, 5370, -1, 6235, 6234, 5368, -1, 6236, 5199, 5198, -1, 6236, 5198, 6232, -1, 6236, 6228, 6231, -1, 6236, 6232, 6228, -1, 6236, 6235, 5199, -1, 6236, 6231, 6235, -1, 5375, 6237, 5377, -1, 6227, 5368, 5066, -1, 6226, 5368, 6227, -1, 6226, 5199, 5368, -1, 6225, 5199, 6226, -1, 5169, 5199, 6225, -1, 6238, 6239, 6237, -1, 6240, 6241, 6239, -1, 6240, 6239, 6238, -1, 6242, 5197, 6243, -1, 6242, 6243, 6244, -1, 6245, 6244, 6246, -1, 6245, 6246, 6241, -1, 6245, 6241, 6240, -1, 6247, 5174, 5197, -1, 6247, 6242, 6244, -1, 6247, 5197, 6242, -1, 6247, 6244, 6245, -1, 6248, 5375, 5373, -1, 6248, 6237, 5375, -1, 6248, 6238, 6237, -1, 6249, 6238, 6248, -1, 6249, 6240, 6238, -1, 6249, 6248, 5373, -1, 6250, 6245, 6240, -1, 6250, 6240, 6249, -1, 6250, 6249, 5373, -1, 6251, 5171, 5174, -1, 6251, 5174, 6247, -1, 6251, 6245, 6250, -1, 6251, 6247, 6245, -1, 6252, 5373, 5372, -1, 6230, 6250, 5373, -1, 6230, 6252, 5372, -1, 6230, 5373, 6252, -1, 6229, 6250, 6230, -1, 6229, 6251, 6250, -1, 6233, 5168, 5171, -1, 6233, 5171, 6251, -1, 6233, 6251, 6229, -1, 6253, 5372, 5370, -1, 6231, 5372, 6253, -1, 6231, 6230, 5372, -1, 6231, 6253, 5370, -1, 5378, 5099, 5380, -1, 6254, 5392, 5087, -1, 6255, 5367, 6256, -1, 6257, 5367, 6255, -1, 5072, 5367, 6257, -1, 6258, 5380, 5382, -1, 6259, 5378, 5380, -1, 6259, 5380, 6258, -1, 6259, 6258, 5382, -1, 6260, 5382, 5384, -1, 6261, 5382, 6260, -1, 6262, 5376, 5378, -1, 6262, 6259, 5382, -1, 6262, 5378, 6259, -1, 6262, 5382, 6261, -1, 6262, 6261, 5376, -1, 6263, 5386, 5388, -1, 6263, 5384, 5386, -1, 6263, 6260, 5384, -1, 6264, 6260, 6263, -1, 6264, 6261, 6260, -1, 6264, 5376, 6261, -1, 6265, 5374, 5376, -1, 6265, 6264, 5374, -1, 6265, 5376, 6264, -1, 6266, 6263, 5388, -1, 6267, 6264, 6263, -1, 6267, 5374, 6264, -1, 6267, 6263, 6266, -1, 6268, 5371, 5374, -1, 6268, 5374, 6267, -1, 6268, 6267, 5371, -1, 6269, 5390, 5392, -1, 6269, 5388, 5390, -1, 6269, 6266, 5388, -1, 6270, 5371, 6267, -1, 6270, 6267, 6266, -1, 6270, 6266, 6269, -1, 6271, 5369, 5371, -1, 6271, 6270, 5369, -1, 6271, 5371, 6270, -1, 6272, 6254, 6273, -1, 6272, 6269, 5392, -1, 6272, 5392, 6254, -1, 6274, 6273, 6256, -1, 6274, 5369, 6270, -1, 6274, 6272, 6273, -1, 6274, 6256, 5367, -1, 6274, 6270, 6269, -1, 6274, 6269, 6272, -1, 6275, 5367, 5369, -1, 6275, 6274, 5367, -1, 6275, 5369, 6274, -1, 6254, 5087, 5089, -1, 6254, 5089, 6276, -1, 6273, 6276, 6277, -1, 6273, 6254, 6276, -1, 6256, 6277, 6278, -1, 6256, 6273, 6277, -1, 6255, 6278, 6279, -1, 6255, 6256, 6278, -1, 6257, 6279, 6280, -1, 6257, 6255, 6279, -1, 5072, 6280, 5064, -1, 5072, 6257, 6280, -1, 6281, 6282, 6283, -1, 6281, 6284, 6282, -1, 6285, 6286, 6287, -1, 5272, 6276, 5089, -1, 6285, 6283, 6288, -1, 6285, 6289, 6286, -1, 6285, 6288, 6289, -1, 6290, 6291, 6284, -1, 6277, 6276, 5272, -1, 6290, 6284, 6281, -1, 6292, 6287, 6293, -1, 6292, 6281, 6283, -1, 6292, 6285, 6287, -1, 6292, 6283, 6285, -1, 6294, 5059, 5062, -1, 6294, 6291, 6290, -1, 6294, 5062, 6295, -1, 6294, 6295, 6291, -1, 6296, 6293, 6297, -1, 6296, 6281, 6292, -1, 6296, 6292, 6293, -1, 6296, 6290, 6281, -1, 6298, 6297, 5061, -1, 5063, 5064, 6280, -1, 6298, 5060, 5059, -1, 6298, 5061, 5060, -1, 6298, 5059, 6294, -1, 6298, 6296, 6297, -1, 6298, 6294, 6290, -1, 6298, 6290, 6296, -1, 6299, 5272, 5274, -1, 6300, 6277, 5272, -1, 6300, 5272, 6299, -1, 6301, 6278, 6277, -1, 6301, 6277, 6300, -1, 6302, 6279, 6278, -1, 6302, 6278, 6301, -1, 6303, 5274, 5276, -1, 6303, 6299, 5274, -1, 6304, 6280, 6279, -1, 6304, 5062, 5063, -1, 6304, 5063, 6280, -1, 6304, 6279, 6302, -1, 6282, 6299, 6303, -1, 6282, 6300, 6299, -1, 6284, 6301, 6300, -1, 6284, 6300, 6282, -1, 6291, 6301, 6284, -1, 6291, 6302, 6301, -1, 6288, 5276, 5278, -1, 6288, 6303, 5276, -1, 6295, 6302, 6291, -1, 6295, 5062, 6304, -1, 6295, 6304, 6302, -1, 6283, 6282, 6303, -1, 6283, 6303, 6288, -1, 6289, 5278, 5150, -1, 6289, 5150, 6286, -1, 6289, 6288, 5278, -1, 6305, 5061, 6297, -1, 6305, 5065, 5061, -1, 6306, 6297, 6293, -1, 6306, 6305, 6297, -1, 6307, 6293, 6287, -1, 6307, 6306, 6293, -1, 6308, 6287, 6286, -1, 6308, 6307, 6287, -1, 5152, 6286, 5150, -1, 5152, 6308, 6286, -1, 5070, 6309, 5071, -1, 6307, 5297, 6306, -1, 6308, 5297, 6307, -1, 5152, 5297, 6308, -1, 6310, 5070, 5069, -1, 6310, 6309, 5070, -1, 6311, 6312, 6309, -1, 6311, 6310, 5069, -1, 6311, 6309, 6310, -1, 6313, 6314, 6312, -1, 6313, 6312, 6311, -1, 6315, 5301, 5076, -1, 6315, 5300, 5301, -1, 6315, 5076, 6314, -1, 6315, 6314, 6313, -1, 6316, 5069, 5068, -1, 6317, 6311, 5069, -1, 6317, 5069, 6316, -1, 6318, 6313, 6311, -1, 6318, 6311, 6317, -1, 6319, 5299, 5300, -1, 6319, 5300, 6315, -1, 6319, 6315, 6313, -1, 6319, 6313, 6318, -1, 6320, 5068, 5067, -1, 6320, 6316, 5068, -1, 6321, 6317, 6316, -1, 6321, 6316, 6320, -1, 6322, 6317, 6321, -1, 6322, 6318, 6317, -1, 6323, 5298, 5299, -1, 6323, 5299, 6319, -1, 6323, 6319, 6318, -1, 6323, 6318, 6322, -1, 6324, 5065, 6305, -1, 6324, 5067, 5065, -1, 6324, 6320, 5067, -1, 6325, 6305, 6306, -1, 6325, 6321, 6320, -1, 6325, 6306, 5297, -1, 6325, 6324, 6305, -1, 6325, 6320, 6324, -1, 6326, 6325, 5297, -1, 6326, 6321, 6325, -1, 6326, 6322, 6321, -1, 6327, 5297, 5298, -1, 6327, 5298, 6323, -1, 6327, 6323, 6322, -1, 6327, 6326, 5297, -1, 6327, 6322, 6326, -1, 6314, 5076, 5075, -1, 6314, 5075, 6328, -1, 6312, 6328, 6329, -1, 6312, 6314, 6328, -1, 6309, 6329, 6330, -1, 6309, 6312, 6329, -1, 5071, 6330, 5053, -1, 5071, 6309, 6330, -1, 6331, 5240, 6332, -1, 6331, 6333, 6334, -1, 6331, 6332, 6333, -1, 6331, 6334, 6328, -1, 5046, 6335, 5048, -1, 5046, 6336, 6335, -1, 5046, 6337, 6336, -1, 5236, 5149, 6338, -1, 6339, 5046, 5045, -1, 6340, 6339, 5045, -1, 6340, 5046, 6339, -1, 6341, 6338, 6337, -1, 6341, 6337, 5046, -1, 6341, 5046, 6340, -1, 6342, 5238, 5236, -1, 6342, 6338, 6341, -1, 6342, 5236, 6338, -1, 6343, 5045, 5049, -1, 6344, 6340, 5045, -1, 6344, 5045, 6343, -1, 6345, 6341, 6340, -1, 6345, 6340, 6344, -1, 6346, 5238, 6342, -1, 6346, 6342, 6341, -1, 6346, 6341, 6345, -1, 6347, 5049, 5050, -1, 6347, 6343, 5049, -1, 6348, 6344, 6343, -1, 6348, 6343, 6347, -1, 6333, 6344, 6348, -1, 6333, 6345, 6344, -1, 6349, 5053, 6330, -1, 6349, 5050, 5053, -1, 6349, 6347, 5050, -1, 6332, 5240, 5238, -1, 6332, 5238, 6346, -1, 6332, 6346, 6345, -1, 6332, 6345, 6333, -1, 6350, 6330, 6329, -1, 6350, 6349, 6330, -1, 6350, 6348, 6347, -1, 6350, 6347, 6349, -1, 6334, 6329, 6328, -1, 6334, 6333, 6348, -1, 6334, 6350, 6329, -1, 6334, 6348, 6350, -1, 6331, 6328, 5075, -1, 6331, 5243, 5240, -1, 6331, 5075, 5243, -1, 5149, 5148, 6351, -1, 6338, 5149, 6351, -1, 6337, 6351, 6352, -1, 6337, 6338, 6351, -1, 6336, 6352, 6353, -1, 6336, 6337, 6352, -1, 6335, 6353, 6354, -1, 6335, 6336, 6353, -1, 5048, 6354, 5054, -1, 5048, 6335, 6354, -1, 6355, 6356, 6357, -1, 6355, 6357, 6358, -1, 6359, 6360, 6361, -1, 5252, 6351, 5148, -1, 6359, 6358, 6362, -1, 6359, 6363, 6360, -1, 6359, 6362, 6363, -1, 6364, 6365, 6356, -1, 6364, 6356, 6355, -1, 6366, 6361, 6367, -1, 6366, 6359, 6361, -1, 6366, 6355, 6358, -1, 6366, 6358, 6359, -1, 6368, 5056, 5055, -1, 6368, 5055, 6369, -1, 6368, 6365, 6364, -1, 6368, 6369, 6365, -1, 6370, 6367, 6371, -1, 6370, 6366, 6367, -1, 6370, 6364, 6355, -1, 6370, 6355, 6366, -1, 6372, 6371, 6373, -1, 6372, 5057, 5056, -1, 6372, 6373, 5057, -1, 6372, 6364, 6370, -1, 6372, 5056, 6368, -1, 6372, 6368, 6364, -1, 6372, 6370, 6371, -1, 5051, 5057, 6373, -1, 6374, 5252, 5250, -1, 6375, 6352, 6351, -1, 6375, 6351, 5252, -1, 6375, 5252, 6374, -1, 6376, 6353, 6352, -1, 6376, 6352, 6375, -1, 6377, 6354, 6353, -1, 6377, 6353, 6376, -1, 6378, 5250, 5249, -1, 6378, 6374, 5250, -1, 6379, 5054, 6354, -1, 6379, 5058, 5054, -1, 6379, 5055, 5058, -1, 6379, 6354, 6377, -1, 6357, 6374, 6378, -1, 6357, 6375, 6374, -1, 6356, 6376, 6375, -1, 6356, 6375, 6357, -1, 6365, 6376, 6356, -1, 6365, 6377, 6376, -1, 6362, 5249, 5246, -1, 6362, 6378, 5249, -1, 6369, 6379, 6377, -1, 6369, 6377, 6365, -1, 6369, 5055, 6379, -1, 6358, 6357, 6378, -1, 6358, 6378, 6362, -1, 6363, 5246, 5079, -1, 6363, 5079, 6360, -1, 6363, 6362, 5246, -1, 6360, 5079, 5078, -1, 6360, 5078, 6380, -1, 6361, 6380, 6381, -1, 6361, 6360, 6380, -1, 6367, 6381, 6382, -1, 6367, 6361, 6381, -1, 6371, 6382, 6383, -1, 6371, 6367, 6382, -1, 6373, 6383, 6384, -1, 6373, 6371, 6383, -1, 5051, 6384, 5052, -1, 5051, 6373, 6384, -1, 5335, 5129, 5333, -1, 6384, 5321, 5052, -1, 6381, 5345, 6382, -1, 6380, 5345, 6381, -1, 5078, 5345, 6380, -1, 6385, 5333, 5331, -1, 6386, 5335, 5333, -1, 6386, 5333, 6385, -1, 6386, 6385, 5331, -1, 6387, 5331, 5329, -1, 6388, 5331, 6387, -1, 6389, 5337, 5335, -1, 6389, 6386, 5331, -1, 6389, 5335, 6386, -1, 6389, 6388, 5337, -1, 6389, 5331, 6388, -1, 6390, 5327, 5325, -1, 6390, 5329, 5327, -1, 6390, 6387, 5329, -1, 6391, 6387, 6390, -1, 6391, 5337, 6388, -1, 6391, 6388, 6387, -1, 6392, 5339, 5337, -1, 6392, 6391, 5339, -1, 6392, 5337, 6391, -1, 6393, 6390, 5325, -1, 6394, 6391, 6390, -1, 6394, 5339, 6391, -1, 6394, 6390, 6393, -1, 6395, 5341, 5339, -1, 6395, 5339, 6394, -1, 6395, 6394, 5341, -1, 6396, 5323, 5321, -1, 6396, 5325, 5323, -1, 6396, 6393, 5325, -1, 6397, 5341, 6394, -1, 6397, 6394, 6393, -1, 6397, 6393, 6396, -1, 6398, 5343, 5341, -1, 6398, 6397, 5343, -1, 6398, 5341, 6397, -1, 6399, 6384, 6383, -1, 6399, 6396, 5321, -1, 6399, 5321, 6384, -1, 6400, 6383, 6382, -1, 6400, 5343, 6397, -1, 6400, 6399, 6383, -1, 6400, 6382, 5345, -1, 6400, 6397, 6396, -1, 6400, 6396, 6399, -1, 6401, 5345, 5343, -1, 6401, 6400, 5345, -1, 6401, 5343, 6400, -1, 5158, 5310, 5159, -1, 5159, 5310, 5319, -1, 5319, 5314, 5318, -1, 5310, 5314, 5319, -1, 5318, 5313, 5317, -1, 5314, 5313, 5318, -1, 5317, 5311, 5316, -1, 5313, 5311, 5317, -1, 5316, 5312, 5315, -1, 5311, 5312, 5316, -1, 5027, 5153, 5028, -1, 5028, 6172, 5029, -1, 5153, 6172, 5028, -1, 5029, 6171, 5030, -1, 6172, 6171, 5029, -1, 5030, 6170, 5031, -1, 6171, 6170, 5030, -1, 5031, 6169, 5032, -1, 6170, 6169, 5031, -1, 5032, 6167, 5033, -1, 6169, 6167, 5032, -1, 5033, 6168, 5034, -1, 6167, 6168, 5033, -1, 6168, 6166, 5034, -1, 6173, 6179, 5035, -1, 5035, 6179, 5036, -1, 5036, 6178, 5037, -1, 6179, 6178, 5036, -1, 5037, 6177, 5038, -1, 6178, 6177, 5037, -1, 5038, 6176, 5039, -1, 6177, 6176, 5038, -1, 5039, 6175, 5040, -1, 6176, 6175, 5039, -1, 5040, 6174, 5043, -1, 6175, 6174, 5040, -1, 5043, 5161, 5044, -1, 6174, 5161, 5043, -1, 5131, 5130, 5433, -1, 5332, 5433, 5431, -1, 5332, 5131, 5433, -1, 5330, 5431, 5429, -1, 5330, 5332, 5431, -1, 6202, 5330, 5429, -1, 6203, 6202, 5429, -1, 6205, 6203, 5429, -1, 6207, 6205, 5429, -1, 6209, 6207, 5429, -1, 6211, 6209, 5429, -1, 6215, 5429, 5427, -1, 6215, 6211, 5429, -1, 6217, 6215, 5427, -1, 5179, 6217, 5427, -1, 5180, 5427, 5425, -1, 5180, 5179, 5427, -1, 5183, 5425, 5423, -1, 5183, 5180, 5425, -1, 5186, 5423, 5421, -1, 5186, 5183, 5423, -1, 5187, 5421, 5156, -1, 5187, 5186, 5421, -1, 5184, 5187, 5156, -1, 5170, 5160, 5445, -1, 5172, 5445, 5443, -1, 5172, 5170, 5445, -1, 5173, 5443, 5441, -1, 5173, 5172, 5443, -1, 5195, 5173, 5441, -1, 5196, 5441, 5439, -1, 5196, 5195, 5441, -1, 5197, 5196, 5439, -1, 6243, 5439, 5437, -1, 6243, 5197, 5439, -1, 6244, 6243, 5437, -1, 6246, 6244, 5437, -1, 6241, 6246, 5437, -1, 6239, 6241, 5437, -1, 6237, 6239, 5437, -1, 5377, 5437, 5435, -1, 5377, 6237, 5437, -1, 5379, 5377, 5435, -1, 5100, 5435, 5096, -1, 5100, 5379, 5435, -1 - ] - } - castShadows FALSE - } - DEF suspension Shape { - appearance Appearance { - material Material { - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - 0.30166513 0.026999786 -0.25766695, 0.30049995 0.052031234 -0.15711282, 0.30174479 0.05189693 -0.15719055, 0.30050009 0.027071729 -0.25778204, 0.30277744 0.0267874 -0.25734663, 0.30292726 0.051513061 -0.15739782, 0.30388024 0.026409984 -0.2568357, 0.30400378 0.050923124 -0.15767582, 0.30487233 0.025879949 -0.25621712, 0.30496538 0.050161257 -0.15796898, 0.305733 0.025202274 -0.2555548, 0.30579913 0.049254581 -0.15822877, 0.306454 0.024369508 -0.25489056, 0.30649227 0.048224196 -0.15841602, 0.3070063 0.023390561 -0.25427377, 0.30702263 0.04709436 -0.15849565, 0.30736369 0.022277445 -0.25374621, 0.3073684 0.045882851 -0.15843903, 0.30749941 0.021064028 -0.25334793, 0.30749938 0.044646412 -0.15822648, 0.30740505 0.043448299 -0.15786158, 0.30740213 0.019816324 -0.25310838, 0.3070918 0.042330459 -0.15736277, 0.30707973 0.018576249 -0.25302905, 0.30658484 0.04133898 -0.15677033, 0.30655846 0.017408788 -0.25309533, 0.30591202 0.040489972 -0.1561255, 0.30586725 0.016346604 -0.25327682, 0.30509466 0.039786011 -0.15546794, 0.30503014 0.015414178 -0.25353646, 0.30415452 0.039230183 -0.15484641, 0.30406198 0.014630079 -0.25383317, 0.30309111 0.038815588 -0.15430553, 0.30297217 0.014020979 -0.25411803, 0.30192465 0.038551018 -0.1539156, 0.30177107 0.013623014 -0.25433195, 0.30121544 0.038469717 -0.15378721, 0.30050033 0.013483092 -0.25441283, 0.30050015 0.038442761 -0.15374379, 0.34866518 0.026999936 -0.25766695, 0.34750009 0.052031457 -0.15711291, 0.34874475 0.051897362 -0.15719043, 0.34750015 0.027072042 -0.2577821, 0.34977728 0.026787713 -0.25734663, 0.34992743 0.051513463 -0.15739782, 0.35088018 0.026410341 -0.2568357, 0.35100383 0.050923318 -0.15767597, 0.35187218 0.025880381 -0.25621724, 0.35196549 0.050161481 -0.15796907, 0.35273308 0.025202572 -0.2555548, 0.35279912 0.049254984 -0.15822883, 0.35345393 0.024369806 -0.25489056, 0.35349232 0.048224643 -0.15841602, 0.35400635 0.023390844 -0.25427377, 0.3540225 0.047094539 -0.15849586, 0.35436374 0.022277743 -0.25374621, 0.35436848 0.045883104 -0.15843903, 0.35449946 0.021064371 -0.25334793, 0.3544994 0.04464677 -0.15822648, 0.35440493 0.043448731 -0.15786158, 0.35440236 0.019816607 -0.25310826, 0.35409182 0.042330757 -0.15736274, 0.35407978 0.018576592 -0.25302911, 0.35358489 0.041339308 -0.15677048, 0.35355854 0.017409146 -0.25309539, 0.35291213 0.040490285 -0.15612565, 0.35286728 0.016346961 -0.25327688, 0.35209462 0.039786205 -0.15546794, 0.35203016 0.015414655 -0.25353646, 0.35115466 0.039230406 -0.15484641, 0.35106194 0.014630452 -0.25383317, 0.35009122 0.03881593 -0.15430553, 0.34997228 0.014021248 -0.25411808, 0.34892458 0.038551286 -0.1539156, 0.3487711 0.013623416 -0.25433195, 0.34821546 0.038469851 -0.15378739, 0.34750032 0.013483331 -0.25441283, 0.34750009 0.038442895 -0.15374379, 0.29280007 0.037249446 -0.14609028, 0.35520005 0.037249893 -0.14609019, 0.35520011 0.037905812 -0.14424299, 0.29280007 0.037905455 -0.14424299, 0.35520011 0.038909495 -0.14255916, 0.29280007 0.038909093 -0.14255901, 0.35520005 0.0402226 -0.14110343, 0.29280007 0.040222228 -0.14110349, 0.35520017 0.041794166 -0.1399319, 0.29280004 0.041793928 -0.1399319, 0.35520008 0.043564349 -0.13908942, 0.29280004 0.043564022 -0.13908942, 0.35520002 0.045464844 -0.13860856, 0.29280022 0.045464337 -0.13860856, 0.35519999 0.047422588 -0.13850771, 0.29279995 0.047422111 -0.13850759, 0.35520005 0.049362481 -0.13879056, 0.29280007 0.049361959 -0.1387908, 0.35520005 0.051209703 -0.13944669, 0.29279998 0.05120936 -0.13944669, 0.35519999 0.052893624 -0.14045046, 0.29280004 0.052893147 -0.14045046, 0.35519999 0.054349318 -0.14176337, 0.29280004 0.054348826 -0.14176337, 0.35519999 0.055520847 -0.14333509, 0.29279995 0.0555204 -0.14333509, 0.35519993 0.056363299 -0.1451052, 0.29280001 0.056362852 -0.14510514, 0.35519999 0.05684413 -0.14700584, 0.29279995 0.056843683 -0.14700566, 0.35520005 0.056944937 -0.14896341, 0.29280001 0.056944579 -0.14896341, 0.35520011 0.056661904 -0.15090327, 0.29280001 0.056661636 -0.15090318, 0.29279992 0.053749755 -0.15018131, 0.29280001 0.053204596 -0.15165095, 0.35519999 0.053750217 -0.15018131, 0.35519996 0.053204983 -0.15165095, 0.29279998 0.052346036 -0.1529624, 0.35520011 0.052346423 -0.1529624, 0.29279989 0.051217213 -0.15405016, 0.35520005 0.051217526 -0.15404995, 0.29280007 0.049874529 -0.15485899, 0.35520005 0.049875095 -0.15485899, 0.29280001 0.048385799 -0.15534909, 0.35519999 0.048386142 -0.15534909, 0.29280001 0.046825051 -0.15549548, 0.35520005 0.046825469 -0.15549548, 0.29280007 0.045270905 -0.15529095, 0.35520005 0.045271292 -0.15529107, 0.35520008 0.04380168 -0.15474568, 0.2928001 0.043801337 -0.15474589, 0.3552002 0.042490184 -0.15388729, 0.29280019 0.042489797 -0.15388735, 0.29280001 0.041402251 -0.15275846, 0.35520017 0.041402712 -0.15275832, 0.29280004 0.040593237 -0.15141587, 0.35520008 0.040593669 -0.15141587, 0.29280013 0.040103137 -0.14992683, 0.35520017 0.040103421 -0.14992698, 0.2928001 0.039956719 -0.14836626, 0.35520017 0.039957121 -0.14836638, 0.29280013 0.040161237 -0.14681233, 0.35520011 0.04016158 -0.1468121, 0.29249999 0.054040998 -0.15025346, 0.29249999 0.05347234 -0.15178625, 0.29249999 0.052576989 -0.15315382, 0.2924999 0.051399872 -0.15428801, 0.29250002 0.049999714 -0.15513177, 0.29250005 0.048447043 -0.15564273, 0.29250005 0.046819478 -0.15579541, 0.29250002 0.045198739 -0.15558229, 0.29250005 0.043666124 -0.15501375, 0.29250014 0.042298451 -0.15411849, 0.29250002 0.041164339 -0.15294121, 0.29250008 0.040320724 -0.15154113, 0.29249996 0.039809525 -0.14998819, 0.29250014 0.039656654 -0.14836077, 0.29250008 0.039869905 -0.14674009, 0.3555001 0.039870441 -0.14673989, 0.35550022 0.039657116 -0.14836089, 0.3555001 0.039809823 -0.14998825, 0.35550016 0.040320858 -0.15154104, 0.35550004 0.041164696 -0.15294121, 0.3555001 0.042298898 -0.15411828, 0.35550016 0.043666467 -0.15501378, 0.35550007 0.045199037 -0.15558229, 0.35550013 0.046819896 -0.15579541, 0.35550004 0.048447371 -0.15564273, 0.35550004 0.050000146 -0.15513162, 0.35550004 0.05140014 -0.15428795, 0.35550007 0.052577406 -0.15315394, 0.3555001 0.053472772 -0.15178616, 0.35550004 0.054041326 -0.15025346, 0.35550019 0.038177043 -0.14437048, 0.35550022 0.037541017 -0.14616244, 0.35550016 0.039150923 -0.14273725, 0.35550016 0.040424421 -0.14132525, 0.35550016 0.041949093 -0.14018865, 0.3555001 0.043666065 -0.13937174, 0.35550016 0.045509622 -0.13890527, 0.35550004 0.047408581 -0.13880725, 0.35550004 0.049290076 -0.1390817, 0.35550016 0.051082075 -0.13971813, 0.3555001 0.052715316 -0.14069171, 0.35550016 0.05412744 -0.14196543, 0.35550001 0.055263758 -0.14349012, 0.35550004 0.056081071 -0.14520694, 0.35550004 0.056547388 -0.1470504, 0.35549998 0.056645185 -0.14894943, 0.35549998 0.056370705 -0.15083103, 0.29249999 0.056644961 -0.14894943, 0.29249996 0.056370407 -0.15083112, 0.2924999 0.056547016 -0.14705043, 0.29249999 0.05608055 -0.14520694, 0.29249996 0.055263579 -0.14349012, 0.29250008 0.054127082 -0.14196537, 0.29249999 0.052715093 -0.14069192, 0.29249996 0.051081717 -0.13971813, 0.29250002 0.049289793 -0.13908191, 0.29250014 0.047408178 -0.1388074, 0.29250008 0.045509115 -0.13890527, 0.29250005 0.043665797 -0.13937171, 0.29250002 0.041948691 -0.14018865, 0.29250014 0.040424123 -0.14132525, 0.29250014 0.039150521 -0.14273717, 0.29250008 0.038176835 -0.1443706, 0.29250008 0.037540555 -0.14616244, 0.29250017 0.02824825 -0.26348186, 0.29280019 0.02826488 -0.26543552, 0.29250017 0.027973726 -0.26536322, 0.29280013 0.028547868 -0.26349574, 0.29250008 0.02815035 -0.26158279, 0.29280019 0.028446913 -0.26153803, 0.29250008 0.027683839 -0.2597394, 0.29280013 0.027966201 -0.25963759, 0.29250017 0.026866674 -0.25802219, 0.2928001 0.02712366 -0.2578674, 0.29250026 0.025730312 -0.25649786, 0.29280013 0.025952145 -0.25629568, 0.29250011 0.024318367 -0.25522411, 0.29280019 0.024496555 -0.25498259, 0.29250011 0.022684976 -0.25425047, 0.29280019 0.022812575 -0.25397885, 0.2925002 0.020892978 -0.25361419, 0.29280025 0.020965189 -0.2533229, 0.2925002 0.019011468 -0.25333959, 0.29280025 0.019025519 -0.25304008, 0.29250023 0.017112345 -0.25343752, 0.29280019 0.01706773 -0.25314081, 0.29250029 0.015269056 -0.25390393, 0.29280025 0.015167296 -0.2536217, 0.29250026 0.013551995 -0.25472105, 0.29280031 0.013397127 -0.25446415, 0.29250032 0.012027368 -0.25585735, 0.29280031 0.011825472 -0.25563568, 0.2925002 0.010753796 -0.2572695, 0.29280031 0.010512337 -0.25709128, 0.29250023 0.0097800642 -0.25890279, 0.29280031 0.0095085651 -0.25877512, 0.29250026 0.009143889 -0.26069486, 0.29280031 0.0088526458 -0.26062262, 0.35550034 0.0097803921 -0.25890279, 0.35520026 0.0088530183 -0.26062262, 0.35550022 0.0091442168 -0.26069486, 0.35520029 0.0095089376 -0.25877517, 0.35550028 0.010754123 -0.2572695, 0.35520029 0.010512695 -0.25709128, 0.35550028 0.012027875 -0.25585735, 0.35520029 0.011825815 -0.25563556, 0.35550034 0.013552308 -0.25472105, 0.35520026 0.013397485 -0.25446415, 0.35550034 0.015269399 -0.25390393, 0.35520026 0.015167654 -0.2536217, 0.35550034 0.017112866 -0.25343752, 0.35520026 0.017068177 -0.25314087, 0.35550025 0.019011781 -0.25333959, 0.35520023 0.019025788 -0.25303996, 0.35550022 0.02089341 -0.25361413, 0.35520017 0.020965666 -0.25332296, 0.35550028 0.022685304 -0.25425047, 0.35520023 0.022813022 -0.25397885, 0.35550028 0.02431874 -0.25522411, 0.35520017 0.024496853 -0.25498265, 0.35550028 0.025730655 -0.25649762, 0.35520017 0.025952563 -0.25629574, 0.35550025 0.026867211 -0.25802207, 0.35520017 0.027124122 -0.25786757, 0.35550025 0.027684197 -0.25973916, 0.35520017 0.027966633 -0.25963748, 0.35550022 0.028150707 -0.26158279, 0.35520023 0.0284473 -0.26153809, 0.35550019 0.028248519 -0.26348162, 0.35520023 0.02854839 -0.26349574, 0.35550028 0.02797398 -0.26536334, 0.35520014 0.028265238 -0.26543552, 0.29250011 0.025644258 -0.26478595, 0.2925002 0.025075778 -0.2663185, 0.29280025 0.02535297 -0.26471359, 0.29280031 0.024807885 -0.2661832, 0.2925002 0.024180263 -0.26768613, 0.29280016 0.023949251 -0.26749486, 0.29250026 0.023003057 -0.26882023, 0.29280022 0.022820443 -0.26858228, 0.29250026 0.021602914 -0.26966405, 0.29280013 0.021477923 -0.26939136, 0.29250023 0.020050198 -0.2701751, 0.29280025 0.019988924 -0.26988143, 0.29250023 0.018422693 -0.27032793, 0.29280019 0.018428236 -0.27002782, 0.29250017 0.016802102 -0.27011448, 0.29280016 0.016874149 -0.26982325, 0.2925002 0.015269324 -0.26954603, 0.29280025 0.015404612 -0.26927811, 0.29250023 0.013901606 -0.26865059, 0.29280031 0.014093146 -0.26841968, 0.29250026 0.012767524 -0.2674734, 0.29280028 0.01300548 -0.26729083, 0.29250029 0.011923879 -0.26607329, 0.29280022 0.012196526 -0.26594824, 0.29250032 0.011412725 -0.26452059, 0.29280022 0.011706337 -0.26445919, 0.29250026 0.011260003 -0.26289302, 0.29280031 0.011559919 -0.26289868, 0.29250038 0.011473298 -0.26127225, 0.29280028 0.011764348 -0.26134443, 0.35550037 0.011473566 -0.26127243, 0.35520029 0.011560351 -0.26289856, 0.35520032 0.011764839 -0.26134437, 0.35550034 0.011260375 -0.26289302, 0.35520029 0.011706769 -0.26445925, 0.35550028 0.011413127 -0.26452047, 0.35520023 0.012196898 -0.26594812, 0.35550037 0.011924207 -0.26607329, 0.35520026 0.013005927 -0.26729083, 0.35550028 0.012767851 -0.2674734, 0.35520029 0.014093488 -0.26841968, 0.35550028 0.013902128 -0.26865065, 0.35520032 0.01540494 -0.26927811, 0.35550031 0.015269771 -0.26954603, 0.35520023 0.016874537 -0.26982331, 0.35550034 0.016802385 -0.27011436, 0.35520035 0.018428698 -0.27002782, 0.35550019 0.01842308 -0.27032775, 0.35520026 0.019989401 -0.26988131, 0.35550034 0.02005069 -0.27017486, 0.35520017 0.021478266 -0.26939136, 0.35550034 0.021603271 -0.26966405, 0.35520026 0.022820815 -0.26858222, 0.35550028 0.023003429 -0.26882023, 0.35520017 0.023949668 -0.26749462, 0.35550028 0.02418074 -0.26768607, 0.3552002 0.024808317 -0.2661832, 0.35550031 0.025076121 -0.26631838, 0.35520017 0.025353357 -0.26471359, 0.35550019 0.0256446 -0.26478595, 0.34678495 0.013527513 -0.25438708, 0.34607571 0.013659373 -0.25431156, 0.29978508 0.013527304 -0.25438702, 0.29907584 0.01365909 -0.25431174, 0.34490934 0.014075533 -0.25409043, 0.29790929 0.014075235 -0.25409043, 0.34384587 0.014694706 -0.25380588, 0.29684585 0.014694452 -0.25380588, 0.34290573 0.015476674 -0.25351608, 0.34208822 0.016406208 -0.25326359, 0.29508823 0.016405821 -0.25326347, 0.29590571 0.015476316 -0.25351608, 0.34141555 0.017458051 -0.25308996, 0.34090835 0.018611491 -0.25302935, 0.29390842 0.018611148 -0.25302911, 0.29441559 0.017457783 -0.25308996, 0.34059536 0.019833013 -0.25311041, 0.34050083 0.021062791 -0.25334764, 0.34063184 0.022255063 -0.25373709, 0.29359537 0.019832566 -0.25311035, 0.34097761 0.023352742 -0.25425279, 0.29363191 0.022254899 -0.25373709, 0.29350084 0.021062419 -0.25334752, 0.34150788 0.024314642 -0.25485146, 0.34220114 0.025138319 -0.25549811, 0.29397774 0.023352504 -0.25425279, 0.29450783 0.024314314 -0.25485146, 0.34303489 0.025818467 -0.25615144, 0.34399644 0.026355162 -0.25676644, 0.29520103 0.025137976 -0.25549829, 0.29603487 0.02581811 -0.25615144, 0.34507275 0.026746899 -0.25728822, 0.34625533 0.026989669 -0.25765061, 0.29699638 0.026354998 -0.25676662, 0.29925543 0.026989251 -0.25765049, 0.29807281 0.026746705 -0.2572881, 0.29280019 0.027608857 -0.26728278, 0.35520023 0.027609184 -0.2672829, 0.29280013 0.026605144 -0.26896673, 0.35520017 0.026605502 -0.26896667, 0.29280016 0.025292143 -0.27042234, 0.35520011 0.025292575 -0.27042234, 0.29280022 0.02372025 -0.27159399, 0.35520017 0.023720711 -0.27159399, 0.29280016 0.02195029 -0.27243644, 0.35520029 0.021950707 -0.27243638, 0.29280016 0.02004987 -0.27291727, 0.35520023 0.020050228 -0.27291727, 0.29280019 0.018092155 -0.27301824, 0.35520023 0.018092558 -0.27301806, 0.29280019 0.016152322 -0.27273518, 0.3552002 0.01615268 -0.27273518, 0.29280028 0.014304847 -0.27207917, 0.35520029 0.014305234 -0.27207905, 0.29280028 0.012621105 -0.27107543, 0.35520023 0.012621567 -0.27107537, 0.29280025 0.01116538 -0.26976246, 0.35520035 0.011165708 -0.26976246, 0.29280031 0.0099938065 -0.26819068, 0.35520029 0.0099942982 -0.26819056, 0.29280037 0.0091514736 -0.26642066, 0.35520029 0.0091518462 -0.26642066, 0.29280031 0.0086706132 -0.26452017, 0.35520029 0.0086709112 -0.26452011, 0.29280031 0.0085696578 -0.26256245, 0.35520026 0.008570075 -0.26256245, 0.35550034 0.025090501 -0.27020073, 0.35550016 0.026364028 -0.26878858, 0.35550028 0.017067626 -0.25588322, 0.35550028 0.018695205 -0.25573039, 0.35550028 0.027337849 -0.26715529, 0.35550034 0.0094340444 -0.26631868, 0.3555004 0.010251179 -0.26803595, 0.35550034 0.020315871 -0.25594366, 0.35550043 0.011387527 -0.26956052, 0.35550034 0.0089676678 -0.26447541, 0.35550034 0.012799561 -0.27083403, 0.35550034 0.0088696629 -0.26257646, 0.3555004 0.014432937 -0.27180761, 0.35550031 0.025857866 -0.263165, 0.35550028 0.016224861 -0.27244419, 0.35550031 0.02184853 -0.25651228, 0.35550022 0.018106431 -0.27271849, 0.35550019 0.02570504 -0.26153761, 0.35550016 0.023216233 -0.25740731, 0.35550022 0.012042269 -0.25973976, 0.35550028 0.025194094 -0.25998485, 0.35550031 0.020005539 -0.27262056, 0.35550028 0.02435039 -0.25858474, 0.35550028 0.012937576 -0.25837195, 0.35550028 0.021848872 -0.27215409, 0.35550034 0.014114827 -0.25723779, 0.35550028 0.023565948 -0.27133709, 0.35550034 0.01551488 -0.25639415, 0.2925002 0.017067268 -0.2558831, 0.2925002 0.026363686 -0.26878858, 0.29250014 0.018694878 -0.25573033, 0.29250008 0.027337462 -0.26715529, 0.29250014 0.020315513 -0.25594366, 0.29250032 0.010250837 -0.26803571, 0.29250023 0.011387125 -0.26956046, 0.2925002 0.0094336867 -0.26631874, 0.29250026 0.012799174 -0.27083403, 0.2925002 0.0089672059 -0.26447541, 0.29250026 0.014432535 -0.27180761, 0.2925002 0.0088692605 -0.26257628, 0.29250011 0.025857523 -0.26316512, 0.2925002 0.021848083 -0.25651217, 0.29250017 0.016224563 -0.27244407, 0.29250014 0.018106103 -0.27271861, 0.29250026 0.025704697 -0.26153767, 0.29250014 0.02321592 -0.25740755, 0.29250011 0.025193751 -0.25998485, 0.2925002 0.012041837 -0.25973964, 0.29250014 0.020005107 -0.27262056, 0.29250011 0.024349958 -0.25858474, 0.2925002 0.012937307 -0.25837195, 0.29250014 0.021848544 -0.27215415, 0.29250026 0.014114365 -0.25723791, 0.2925002 0.02356559 -0.27133709, 0.29250029 0.015514478 -0.25639415, 0.29250023 0.025090054 -0.27020061, 0.29280022 0.012309626 -0.25987494, 0.35520029 0.012310043 -0.25987494, 0.29280019 0.013168216 -0.2585634, 0.35520026 0.013168544 -0.2585634, 0.35520026 0.014297485 -0.25747585, 0.29280031 0.014297143 -0.25747585, 0.35520023 0.015640065 -0.25666678, 0.29280028 0.015639618 -0.25666678, 0.35520023 0.017129064 -0.25617671, 0.29280031 0.017128497 -0.25617671, 0.35520029 0.018689662 -0.2560302, 0.29280025 0.018689215 -0.2560302, 0.35520023 0.020243764 -0.25623482, 0.29280019 0.020243332 -0.25623477, 0.35520023 0.021713376 -0.25677979, 0.29280025 0.021712959 -0.25677991, 0.3552002 0.023024887 -0.25763845, 0.29280031 0.023024425 -0.25763845, 0.35520017 0.024112388 -0.25876749, 0.29280016 0.024111986 -0.25876749, 0.3552002 0.024921417 -0.26011002, 0.29280016 0.024921015 -0.26011002, 0.29280025 0.025411144 -0.26159883, 0.35520017 0.025411561 -0.26159883, 0.29280013 0.025557563 -0.26315951, 0.35520017 0.025558069 -0.26315951, 0.29250014 0.037266031 -0.14804403, 0.29280007 0.036966324 -0.14803006, 0.29250011 0.037363902 -0.14994301, 0.29280007 0.037067294 -0.14998774, 0.29250008 0.037830383 -0.1517864, 0.29280007 0.037548155 -0.15188827, 0.29250002 0.038647532 -0.15350346, 0.29280007 0.038390607 -0.15365838, 0.29250008 0.039783835 -0.15502812, 0.29280013 0.039562047 -0.15523024, 0.29250008 0.041196018 -0.15630169, 0.2928001 0.041017815 -0.15654324, 0.29250011 0.04282926 -0.15727542, 0.29280001 0.042701572 -0.15754695, 0.29249993 0.044621319 -0.15791176, 0.29280004 0.044548959 -0.15820281, 0.29249996 0.046502814 -0.15818612, 0.29280013 0.046488822 -0.15848573, 0.29250002 0.048401818 -0.15808843, 0.29280007 0.048446491 -0.1583849, 0.2924999 0.05024524 -0.15762182, 0.29280004 0.050346971 -0.15790407, 0.2924999 0.051962242 -0.15680455, 0.29280004 0.052117094 -0.15706156, 0.29249993 0.053486973 -0.15566836, 0.29279998 0.053688973 -0.15589006, 0.29249993 0.054760516 -0.1542563, 0.29280001 0.055001885 -0.1544344, 0.29249999 0.055734128 -0.15262286, 0.29279995 0.056005657 -0.15275057, 0.35519993 0.056006148 -0.15275066, 0.35550016 0.0557345 -0.15262301, 0.35519996 0.055002213 -0.15443455, 0.35550001 0.054760858 -0.1542563, 0.35519999 0.053689286 -0.15589012, 0.35550004 0.053487346 -0.15566821, 0.35520005 0.052117646 -0.15706153, 0.35550004 0.051962614 -0.15680455, 0.35520011 0.050347403 -0.1579041, 0.3555001 0.050245568 -0.15762185, 0.35520005 0.048446879 -0.1583849, 0.35550016 0.048402116 -0.15808843, 0.35520005 0.046489224 -0.15848596, 0.3555001 0.046503246 -0.15818612, 0.35520005 0.04454945 -0.15820299, 0.35550013 0.044621661 -0.15791161, 0.35520011 0.042702034 -0.15754686, 0.35550016 0.042829618 -0.15727527, 0.35520017 0.041018113 -0.15654315, 0.35550016 0.041196346 -0.15630184, 0.35520011 0.039562494 -0.15523018, 0.35550016 0.039784297 -0.15502812, 0.35520017 0.038390964 -0.15365832, 0.3555001 0.03864792 -0.15350346, 0.35520011 0.037548542 -0.15188833, 0.35550016 0.037830696 -0.15178649, 0.35520011 0.037067771 -0.14998786, 0.35550016 0.037364334 -0.14994301, 0.35520023 0.036966801 -0.14802985, 0.35550016 0.037266448 -0.14804403, 0.3551999 0.053954735 -0.14862733, 0.35550004 0.054254532 -0.14863281, 0.35550001 0.054101855 -0.14700522, 0.35520008 0.053808063 -0.14706649, 0.3555001 0.053590834 -0.14545242, 0.35519999 0.053318128 -0.14557768, 0.35550004 0.052746996 -0.14405249, 0.35519999 0.052509114 -0.14423503, 0.35549998 0.051612884 -0.14287521, 0.35519999 0.051421598 -0.14310621, 0.3555001 0.050245225 -0.1419798, 0.35520005 0.050110176 -0.14224766, 0.35550016 0.048712581 -0.14141132, 0.35519999 0.04864046 -0.14170264, 0.35549998 0.047091812 -0.1411979, 0.35520005 0.047086313 -0.14149795, 0.3555001 0.045464292 -0.14135073, 0.35520005 0.045525745 -0.14164458, 0.35550013 0.043911546 -0.14186175, 0.35520011 0.044036731 -0.14213441, 0.35550013 0.042511567 -0.1427056, 0.35520017 0.042694196 -0.14294352, 0.35550022 0.041334361 -0.14383958, 0.35520017 0.041565344 -0.14403097, 0.3555001 0.040438846 -0.14520745, 0.35520011 0.040706903 -0.1453426, 0.29250008 0.040438622 -0.14520745, 0.29280004 0.040706486 -0.14534269, 0.29280016 0.041564941 -0.14403121, 0.29250011 0.041333929 -0.14383973, 0.29250008 0.042511106 -0.1427056, 0.2928001 0.042693809 -0.14294361, 0.29280004 0.044036299 -0.14213435, 0.29250011 0.043911263 -0.1418619, 0.29280007 0.045525327 -0.14164458, 0.29250002 0.045464009 -0.14135067, 0.29249996 0.047091603 -0.1411979, 0.29280001 0.047085971 -0.14149784, 0.29280001 0.048640072 -0.1417024, 0.29250002 0.048712343 -0.14141117, 0.29280004 0.050109595 -0.14224772, 0.29250005 0.050244883 -0.14197989, 0.29280007 0.051421165 -0.14310621, 0.29250002 0.051612407 -0.14287512, 0.29279998 0.052508697 -0.14423524, 0.29249999 0.052746743 -0.14405249, 0.29249993 0.053590417 -0.14545242, 0.29280004 0.053317785 -0.14557754, 0.29280001 0.053807855 -0.14706673, 0.29249993 0.054101586 -0.14700525, 0.29249996 0.054254279 -0.14863281, 0.29280004 0.053954244 -0.14862733, 0.34633502 0.051914081 -0.15718101, 0.34522289 0.051576674 -0.15736516, 0.29933497 0.051913664 -0.15718101, 0.34412003 0.05100438 -0.15764056, 0.29822296 0.051576406 -0.15736519, 0.34312797 0.05024679 -0.15793975, 0.29712003 0.051004022 -0.15764053, 0.34226722 0.049338043 -0.15820892, 0.34154618 0.048291534 -0.15840708, 0.29526728 0.04933767 -0.15820871, 0.29612792 0.050246537 -0.15793966, 0.34099394 0.047137856 -0.15849511, 0.34063646 0.04590708 -0.15844153, 0.29399398 0.047137499 -0.15849517, 0.29454628 0.048291206 -0.15840717, 0.34050068 0.044648334 -0.15822674, 0.29363656 0.045906797 -0.15844174, 0.29350087 0.044647992 -0.15822689, 0.34059802 0.043433249 -0.15785585, 0.34092057 0.042299688 -0.15734668, 0.29359803 0.043432876 -0.15785576, 0.34144184 0.041298419 -0.15674259, 0.29392049 0.0422993 -0.15734647, 0.29444191 0.041298077 -0.15674268, 0.34213322 0.040443957 -0.15608595, 0.34297019 0.03974089 -0.15542112, 0.34393847 0.039186224 -0.15479229, 0.29513311 0.040443733 -0.15608604, 0.2959702 0.039740682 -0.155421, 0.34502804 0.038780719 -0.15425585, 0.34622931 0.038528919 -0.15388058, 0.2969383 0.039185882 -0.15479229, 0.29922917 0.038528517 -0.15388076, 0.29802811 0.038780421 -0.15425585, -0.30166495 0.026966795 0.25767136, -0.30050018 0.052009866 0.15712021, -0.30174506 0.051875517 0.15719776, -0.30050004 0.027038798 0.25778639, -0.30277711 0.026754603 0.25735092, -0.30292755 0.051491588 0.15740488, -0.30387998 0.026377231 0.25684011, -0.3040038 0.050901443 0.15768312, -0.30487204 0.025847226 0.25622165, -0.30496547 0.050139576 0.15797602, -0.30573279 0.025169566 0.25555885, -0.30579925 0.04923299 0.15823556, -0.30645373 0.024336979 0.25489461, -0.30649245 0.0482025 0.1584229, -0.307006 0.023357868 0.25427783, -0.30702272 0.047072619 0.1585023, -0.30736351 0.02224493 0.25375009, -0.30736864 0.045861185 0.15844561, -0.30749926 0.021031618 0.25335169, -0.30749941 0.044624805 0.15823279, -0.30740494 0.043426603 0.15786798, -0.3074021 0.019783884 0.25311196, -0.30709201 0.042308882 0.15736903, -0.30707937 0.018543795 0.25303251, -0.30658481 0.041317478 0.15677647, -0.30655813 0.017376184 0.25309861, -0.30591214 0.04046835 0.1561314, -0.30586696 0.016314089 0.25328004, -0.30509457 0.039764509 0.15547384, -0.30502987 0.015381709 0.25353932, -0.30415452 0.039208829 0.15485217, -0.30406165 0.014597669 0.25383615, -0.30309111 0.038794428 0.15431122, -0.3029719 0.013988405 0.25412083, -0.30192477 0.038529918 0.15392138, -0.30177069 0.013590455 0.25433481, -0.30121541 0.038448468 0.15379296, -0.30049989 0.013450608 0.25441581, -0.30050004 0.038421497 0.1537496, -0.348665 0.026966497 0.25767142, -0.34750026 0.052009404 0.15712003, -0.34874496 0.05187504 0.15719782, -0.34750003 0.027038515 0.25778639, -0.34977716 0.026754275 0.25735104, -0.34992743 0.051491186 0.15740491, -0.35088009 0.026376873 0.25684011, -0.35100386 0.05090116 0.15768312, -0.35187209 0.025847033 0.25622165, -0.35196546 0.050139204 0.15797593, -0.35273284 0.025169209 0.25555897, -0.35279921 0.049232572 0.15823571, -0.35345387 0.024336666 0.25489438, -0.35349253 0.048202291 0.15842284, -0.35400617 0.023357853 0.25427783, -0.35402274 0.047072232 0.15850244, -0.35436362 0.022244617 0.25375009, -0.35436845 0.045860782 0.15844561, -0.35449919 0.021031335 0.25335169, -0.35449946 0.044624418 0.15823288, -0.35440505 0.043426275 0.15786774, -0.35440201 0.019783556 0.25311208, -0.35409182 0.042308524 0.15736903, -0.35407946 0.018543378 0.25303251, -0.35358477 0.041317195 0.15677668, -0.35355839 0.01737608 0.25309861, -0.35291216 0.040468112 0.1561314, -0.35286707 0.01631391 0.25328004, -0.35209459 0.03976424 0.15547384, -0.35202986 0.0153815 0.25353932, -0.3511546 0.039208516 0.15485223, -0.3510617 0.014597267 0.25383604, -0.3500911 0.038794115 0.15431114, -0.34997189 0.013988107 0.25412089, -0.34892467 0.03852956 0.1539212, -0.34877074 0.013590187 0.25433481, -0.34821534 0.038448021 0.15379311, -0.34750003 0.013450325 0.25441587, -0.34750009 0.038421273 0.15374936, -0.29280007 0.037229121 0.14609568, -0.35520017 0.037228823 0.14609568, -0.35520017 0.037884861 0.14424847, -0.29280001 0.037885308 0.14424859, -0.35520023 0.038888901 0.14256488, -0.29279995 0.038889304 0.142565, -0.35520026 0.0402022 0.14110921, -0.29280004 0.040202454 0.14110936, -0.35520017 0.041774064 0.13993792, -0.2928001 0.041774407 0.13993801, -0.35520017 0.043544173 0.13909577, -0.29280013 0.043544531 0.13909589, -0.35520023 0.045444638 0.13861494, -0.29280007 0.045445085 0.138615, -0.35520026 0.047402486 0.1385143, -0.29280016 0.047402889 0.1385145, -0.35520005 0.049342111 0.13879754, -0.29280019 0.049342632 0.13879769, -0.35520023 0.051189423 0.13945366, -0.2928001 0.05118978 0.13945387, -0.35520029 0.052873224 0.14045776, -0.29280013 0.052873552 0.14045776, -0.35520023 0.054328814 0.14177097, -0.29280019 0.054329276 0.14177094, -0.35520023 0.055500031 0.14334284, -0.29280019 0.055500478 0.14334284, -0.35520032 0.056342304 0.14511283, -0.29280019 0.056342721 0.14511283, -0.35520029 0.056822956 0.14701371, -0.29280016 0.056823283 0.14701359, -0.35520038 0.056923777 0.14897148, -0.29280013 0.056924075 0.14897133, -0.35520032 0.056640491 0.15091096, -0.29280013 0.056640804 0.15091096, -0.29280019 0.053729102 0.1501887, -0.29280025 0.053183734 0.15165846, -0.35520029 0.0537287 0.15018885, -0.35520023 0.053183347 0.15165819, -0.29280004 0.052324951 0.15296973, -0.35520023 0.052324772 0.15296973, -0.29280004 0.051196054 0.15405728, -0.35520023 0.051195696 0.15405725, -0.2928001 0.049853325 0.154866, -0.35520011 0.049852982 0.154866, -0.29280007 0.048364282 0.15535606, -0.35520014 0.048364013 0.15535586, -0.29280016 0.046803832 0.1555021, -0.35520023 0.046803281 0.15550219, -0.29280013 0.045249611 0.15529741, -0.35520029 0.045249373 0.15529756, -0.29280019 0.043780044 0.15475218, -0.35520011 0.043779597 0.15475218, -0.2928001 0.042468786 0.1538934, -0.35520017 0.042468384 0.1538934, -0.2928001 0.04138127 0.15276445, -0.35520011 0.041380882 0.15276437, -0.29279998 0.040572286 0.15142192, -0.35520029 0.040572003 0.15142189, -0.29280004 0.040082484 0.14993294, -0.35520014 0.040082157 0.14993288, -0.29279995 0.039936274 0.14837225, -0.35519993 0.039935812 0.14837225, -0.29280004 0.040140837 0.14681791, -0.35520017 0.040140435 0.146818, -0.29250014 0.05402033 0.15026064, -0.29250002 0.053451419 0.15179341, -0.2925002 0.052556008 0.15316106, -0.29250011 0.051378652 0.15429498, -0.29250005 0.049978435 0.15513872, -0.29249999 0.048425555 0.15564953, -0.29250008 0.04679814 0.15580215, -0.29250008 0.0451774 0.15558864, -0.29250002 0.043644771 0.15501986, -0.29250014 0.042277455 0.15412463, -0.29250005 0.041143194 0.15294696, -0.29249996 0.040299729 0.15154685, -0.29250005 0.039788857 0.14999415, -0.29249993 0.039636254 0.14836662, -0.29250011 0.039849713 0.14674573, -0.35550022 0.039849252 0.14674588, -0.35550013 0.039635807 0.14836647, -0.3555001 0.03978847 0.14999415, -0.35550016 0.040299192 0.151547, -0.35550019 0.041142955 0.15294702, -0.35550016 0.042277053 0.15412463, -0.35550022 0.043644443 0.15502001, -0.35550022 0.045177013 0.15558864, -0.3555001 0.046797797 0.15580226, -0.35550016 0.048425257 0.15564953, -0.35550016 0.049977943 0.15513872, -0.35550019 0.05137834 0.15429498, -0.35550028 0.052555621 0.15316106, -0.35550016 0.053451166 0.15179341, -0.35550022 0.054019853 0.15026094, -0.35550016 0.037520021 0.14616792, -0.35550007 0.038156405 0.14437611, -0.35550019 0.039130241 0.14274289, -0.35550019 0.040404201 0.14133121, -0.35550013 0.041928753 0.14019488, -0.35550022 0.043645918 0.13937788, -0.35550016 0.045489267 0.13891165, -0.3555001 0.04738836 0.13881408, -0.35550019 0.049270034 0.13908876, -0.35550019 0.051061779 0.13972525, -0.35550034 0.052695125 0.14069904, -0.35550022 0.054106832 0.14197288, -0.35550028 0.055243149 0.14349745, -0.35550022 0.05606018 0.14521475, -0.35550019 0.056526273 0.14705814, -0.35550034 0.056624055 0.14895721, -0.35550022 0.056349263 0.15083887, -0.29250014 0.05634965 0.15083878, -0.29250008 0.056624383 0.14895721, -0.2925002 0.056526765 0.14705805, -0.2925002 0.056060612 0.14521472, -0.2925002 0.055243552 0.14349748, -0.2925002 0.054107368 0.14197288, -0.2925002 0.052695587 0.14069889, -0.29250005 0.051062241 0.13972519, -0.29250008 0.049270332 0.13908876, -0.29250014 0.047388777 0.13881408, -0.29250014 0.045489818 0.13891159, -0.29250008 0.043646321 0.13937794, -0.29249993 0.041929096 0.14019479, -0.29250005 0.040404513 0.14133121, -0.29249996 0.039130554 0.14274286, -0.29250002 0.038156807 0.14437605, -0.29249996 0.037520334 0.14616819, -0.29250002 0.028214797 0.26348633, -0.29280001 0.028231174 0.26544017, -0.29249996 0.02793996 0.26536793, -0.29280001 0.028514385 0.26350039, -0.2924999 0.028116986 0.26158744, -0.29279995 0.028413743 0.26154262, -0.29249996 0.027650878 0.25974369, -0.29279995 0.027933046 0.25964212, -0.29249996 0.026833937 0.25802672, -0.29279995 0.027090877 0.25787187, -0.29249984 0.02569744 0.25650191, -0.29279995 0.025919527 0.25629997, -0.29250002 0.024285898 0.25522816, -0.29279995 0.024463862 0.25498676, -0.29249993 0.022652537 0.25425422, -0.29279992 0.022780269 0.25398284, -0.29249987 0.020860702 0.25361782, -0.29279992 0.020932853 0.25332659, -0.29249978 0.018979043 0.25334299, -0.29280001 0.018993169 0.25304329, -0.29250002 0.017080158 0.25344062, -0.29279995 0.017035425 0.25314415, -0.29249978 0.015236557 0.25390708, -0.29279989 0.015134901 0.2536248, -0.29249984 0.013519511 0.25472409, -0.29279992 0.013364762 0.25446713, -0.29249987 0.011995003 0.25586021, -0.29279974 0.011792749 0.25563848, -0.29249987 0.010720938 0.25727195, -0.29279989 0.010479659 0.25709379, -0.2924999 0.0097471327 0.25890523, -0.29279989 0.0094756782 0.25877762, -0.29249978 0.0091106743 0.26069707, -0.29279983 0.0088195503 0.26062465, -0.35549992 0.0097467899 0.25890523, -0.35519987 0.0088191181 0.26062489, -0.35549992 0.0091100782 0.26069695, -0.35519993 0.0094753653 0.25877768, -0.35549992 0.010720715 0.25727206, -0.35519981 0.010479242 0.25709379, -0.35549998 0.011994526 0.25586009, -0.35520002 0.011792362 0.25563824, -0.35549992 0.013519168 0.25472409, -0.35519999 0.013364315 0.25446701, -0.35549992 0.015236244 0.25390685, -0.35519999 0.015134558 0.2536248, -0.3555001 0.017079726 0.25344086, -0.35520005 0.017035171 0.25314432, -0.35549998 0.0189787 0.25334311, -0.35519981 0.018992662 0.25304335, -0.35550013 0.020860255 0.25361782, -0.35519999 0.020932555 0.25332654, -0.3555001 0.022652209 0.25425422, -0.35519999 0.022779807 0.25398266, -0.3555001 0.024285346 0.25522816, -0.35520017 0.024463609 0.25498676, -0.3555001 0.025697201 0.25650185, -0.35519999 0.025919124 0.25629985, -0.3555001 0.026833549 0.25802672, -0.35520011 0.027090386 0.25787199, -0.35549998 0.027650416 0.25974387, -0.35520005 0.027932718 0.25964212, -0.35550004 0.028116584 0.2615872, -0.35520023 0.02841337 0.26154256, -0.3555001 0.02821441 0.26348633, -0.35520005 0.028514042 0.26350021, -0.3552002 0.028230831 0.26544017, -0.35550004 0.027939528 0.26536793, -0.29249996 0.02561067 0.26478988, -0.29279995 0.024774015 0.26618743, -0.29279995 0.025319546 0.264718, -0.29249996 0.025041893 0.26632267, -0.29279992 0.023915574 0.26749861, -0.29250002 0.024146482 0.26769018, -0.29280001 0.022786409 0.26858622, -0.29249993 0.022969112 0.2688241, -0.29279971 0.02144374 0.26939499, -0.29249993 0.021568894 0.26966798, -0.29279998 0.019954711 0.26988512, -0.29249993 0.020016015 0.27017868, -0.29279995 0.018394202 0.27003121, -0.2924999 0.01838842 0.27033114, -0.29279995 0.016840041 0.26982665, -0.2924999 0.01676783 0.27011764, -0.29279989 0.015370399 0.26928115, -0.29249996 0.015235156 0.26954901, -0.29279995 0.014059067 0.26842254, -0.29249996 0.013867781 0.26865351, -0.29279998 0.012971669 0.26729369, -0.29249993 0.012733787 0.26747608, -0.29279992 0.012162656 0.26595098, -0.29249981 0.011889979 0.26607609, -0.29279992 0.011672825 0.26446205, -0.29249993 0.011379272 0.26452321, -0.29279983 0.011526585 0.26290143, -0.29249987 0.01122658 0.26289552, -0.29279986 0.011731267 0.26134723, -0.29249987 0.011440068 0.26127487, -0.35549989 0.011439562 0.26127499, -0.3551999 0.011526138 0.26290137, -0.35520002 0.01173079 0.26134723, -0.35549995 0.011226267 0.26289552, -0.35519993 0.011672616 0.26446187, -0.35549992 0.011378899 0.26452321, -0.35519996 0.012162313 0.26595098, -0.35549992 0.011889651 0.26607609, -0.35519984 0.012971207 0.26729369, -0.35549998 0.01273337 0.26747608, -0.35520011 0.014058694 0.26842254, -0.35549998 0.013867289 0.26865351, -0.35519999 0.015370041 0.26928133, -0.3555001 0.015234888 0.26954895, -0.35520005 0.016839609 0.26982671, -0.35549989 0.016767487 0.27011776, -0.35549986 0.018388063 0.2703312, -0.35520008 0.018393695 0.27003133, -0.35520002 0.019954413 0.26988494, -0.35549995 0.020015627 0.27017868, -0.35520017 0.021443337 0.26939499, -0.35550016 0.021568373 0.2696678, -0.35520005 0.022786051 0.26858616, -0.35550007 0.022968873 0.26882422, -0.35550013 0.02414602 0.26769012, -0.35520011 0.023914993 0.26749873, -0.35519999 0.024773732 0.26618749, -0.3555001 0.025041535 0.26632255, -0.3555001 0.025610149 0.26478994, -0.35520005 0.025319129 0.26471782, -0.34678477 0.013494566 0.25438976, -0.34607548 0.013626486 0.25431442, -0.29978454 0.01349479 0.25439, -0.29907537 0.01362671 0.25431442, -0.34490901 0.014042556 0.25409341, -0.29790884 0.014042705 0.25409353, -0.34384537 0.014661789 0.25380909, -0.29684532 0.014661908 0.25380909, -0.34290552 0.015443563 0.25351894, -0.34208798 0.016373232 0.25326681, -0.29508799 0.01637347 0.25326681, -0.29590553 0.015443876 0.25351894, -0.34141523 0.017425299 0.25309324, -0.34090829 0.018578604 0.2530328, -0.29390806 0.018578872 0.25303251, -0.29441524 0.017425567 0.25309324, -0.34059522 0.019799918 0.2531141, -0.34050074 0.02102977 0.25335133, -0.34063166 0.022222131 0.25374091, -0.29359517 0.019800246 0.2531141, -0.34097746 0.02331984 0.25425684, -0.29363164 0.022222459 0.25374091, -0.29350069 0.021030217 0.25335133, -0.34150791 0.02428171 0.25485575, -0.34220082 0.025105149 0.25550246, -0.29397747 0.023320168 0.25425696, -0.29450774 0.02428183 0.25485545, -0.34303468 0.025785327 0.25615573, -0.34399605 0.026321858 0.25677085, -0.29520088 0.025105447 0.2555024, -0.29603475 0.025785625 0.25615573, -0.34507257 0.02671355 0.25729251, -0.3462553 0.026956141 0.25765491, -0.29699618 0.026322141 0.25677073, -0.29925525 0.026956379 0.25765491, -0.29807264 0.026713789 0.25729245, -0.29279995 0.027575016 0.26728737, -0.35520017 0.027574673 0.26728749, -0.29279995 0.026571065 0.26897109, -0.35520005 0.026570827 0.2689712, -0.29280001 0.025257945 0.27042675, -0.35520005 0.025257468 0.27042669, -0.29280004 0.023686007 0.2715981, -0.35520017 0.023685619 0.2715981, -0.29279992 0.021915823 0.27244014, -0.35520002 0.021915466 0.27244014, -0.29279995 0.020015329 0.27292085, -0.35520005 0.020014986 0.27292073, -0.29279989 0.018057555 0.27302146, -0.35519999 0.018057376 0.2730217, -0.29279989 0.016117871 0.27273834, -0.35520005 0.016117379 0.27273834, -0.29280001 0.014270514 0.27208215, -0.35520017 0.014270067 0.27208215, -0.29279989 0.012586683 0.27107823, -0.35519999 0.01258646 0.27107799, -0.29279983 0.011131227 0.26976484, -0.35519996 0.011130825 0.26976508, -0.29279992 0.0099599361 0.26819319, -0.35519993 0.0099595189 0.26819324, -0.29279995 0.009117648 0.26642305, -0.35519987 0.0091171414 0.26642293, -0.29279989 0.0086370409 0.26452249, -0.35519993 0.0086366534 0.26452237, -0.29279983 0.0085363388 0.2625646, -0.35519993 0.0085359514 0.2625646, -0.35550004 0.017034307 0.2558862, -0.35549992 0.026329353 0.26879317, -0.35549998 0.025055528 0.27020454, -0.35550004 0.018661872 0.25573385, -0.35549986 0.010216445 0.26803833, -0.35549986 0.011352554 0.26956296, -0.35550007 0.020282567 0.25594723, -0.35550016 0.027303234 0.2671597, -0.35549992 0.0093994141 0.26632106, -0.35549995 0.012764663 0.27083683, -0.35550004 0.0089331716 0.26447803, -0.35549992 0.014397785 0.27181077, -0.35550001 0.0088354945 0.26257861, -0.35550004 0.021814927 0.25651604, -0.35550004 0.01618968 0.27244711, -0.35549998 0.018071353 0.27272189, -0.35550004 0.025823548 0.26316935, -0.35549998 0.023182511 0.25741148, -0.35549995 0.012008369 0.25974226, -0.3555001 0.025671095 0.26154184, -0.35550001 0.024316713 0.25858873, -0.35549998 0.019970238 0.27262437, -0.35550004 0.025160387 0.25998896, -0.35550007 0.012903988 0.25837493, -0.35549998 0.021813646 0.27215785, -0.35550004 0.01408127 0.25724077, -0.35549998 0.023530766 0.27134109, -0.35550004 0.015481547 0.25639725, -0.29250002 0.026329666 0.26879293, -0.29250002 0.025055945 0.27020466, -0.2924999 0.01703462 0.25588632, -0.2924999 0.018662393 0.25573385, -0.29249978 0.010216817 0.26803833, -0.29249978 0.011353061 0.26956296, -0.29249996 0.027303562 0.26715988, -0.29249978 0.0093998611 0.26632106, -0.29249987 0.020283014 0.25594711, -0.29249981 0.012764901 0.27083683, -0.29249984 0.0089336932 0.26447767, -0.29249984 0.014398083 0.27181077, -0.29249984 0.0088359863 0.26257861, -0.29250002 0.016190112 0.27244711, -0.29249996 0.018071622 0.27272189, -0.29250002 0.025824159 0.26316917, -0.29249981 0.012008771 0.25974226, -0.29249999 0.02181533 0.25651598, -0.2924999 0.0199707 0.27262431, -0.29249996 0.025671616 0.2615419, -0.29249999 0.023183018 0.2574113, -0.29249996 0.025160715 0.2599889, -0.29249993 0.012904316 0.25837493, -0.29249993 0.021814093 0.27215785, -0.29249987 0.024317011 0.25858879, -0.29249996 0.014081642 0.25724077, -0.29249987 0.023531124 0.27134109, -0.29249996 0.015481994 0.25639725, -0.29279989 0.012276649 0.25987756, -0.35520005 0.012276232 0.25987762, -0.29279995 0.013135493 0.25856638, -0.35519999 0.013134971 0.25856638, -0.29279995 0.014264286 0.25747871, -0.35519993 0.014263928 0.25747871, -0.29279989 0.01560691 0.25666994, -0.35520005 0.015606552 0.25667, -0.29279989 0.017095953 0.25618005, -0.35520005 0.017095685 0.25617993, -0.29279995 0.018656701 0.25603354, -0.35520008 0.018656313 0.25603384, -0.29279998 0.020210654 0.25623834, -0.35520011 0.020210192 0.25623834, -0.35520008 0.021679878 0.25678396, -0.29279992 0.021680087 0.25678396, -0.35520005 0.022991091 0.25764245, -0.29279992 0.022991538 0.25764233, -0.35520011 0.024078563 0.25877154, -0.29280001 0.024078965 0.25877154, -0.35520017 0.024887756 0.26011425, -0.29279995 0.024888068 0.26011407, -0.35520011 0.025377527 0.26160312, -0.29280001 0.02537784 0.26160306, -0.35520005 0.025523812 0.26316386, -0.29280001 0.025524169 0.26316386, -0.29249996 0.037245467 0.14804952, -0.29280007 0.036945909 0.14803569, -0.29250011 0.037343368 0.14994864, -0.29280013 0.037046656 0.14999332, -0.29249996 0.037809476 0.15179206, -0.29280013 0.037527427 0.15189393, -0.29250008 0.038626492 0.15350927, -0.2928001 0.038369626 0.1536641, -0.29250014 0.039762735 0.15503399, -0.2928001 0.039540857 0.15523578, -0.29250011 0.041174516 0.15630795, -0.29280004 0.040996432 0.15654911, -0.29250005 0.042807728 0.15728153, -0.29280019 0.042680204 0.1575533, -0.29250002 0.044599608 0.15791811, -0.29280007 0.044527471 0.15820919, -0.29250014 0.046481267 0.15819295, -0.29280001 0.046467289 0.15849243, -0.29250008 0.048380211 0.15809514, -0.2928001 0.048424989 0.15839185, -0.29250005 0.050223753 0.15762876, -0.2928001 0.050325394 0.1579112, -0.29250023 0.051940784 0.15681185, -0.29280022 0.052095696 0.15706904, -0.29250008 0.05346556 0.1556756, -0.29280019 0.053667545 0.1558976, -0.29250014 0.054739431 0.15426393, -0.29280025 0.054980829 0.15444206, -0.29250008 0.055713162 0.1526307, -0.29280019 0.055984616 0.15275829, -0.35520032 0.055984348 0.1527582, -0.35550022 0.055712804 0.15263085, -0.35550022 0.054738998 0.15426384, -0.35520029 0.054980382 0.15444194, -0.35550016 0.053465068 0.15567555, -0.35520017 0.053667128 0.1558976, -0.35550025 0.051940456 0.15681194, -0.35520041 0.052095234 0.15706895, -0.35550028 0.050223365 0.15762891, -0.35520011 0.050325125 0.15791114, -0.35550028 0.048379824 0.15809499, -0.3552002 0.048424512 0.15839179, -0.35550016 0.046480864 0.15819289, -0.35520017 0.046466812 0.15849243, -0.35550016 0.044599175 0.15791811, -0.35520023 0.044527113 0.15820937, -0.35550016 0.042807341 0.15728147, -0.35520014 0.042679682 0.15755321, -0.3555001 0.041174039 0.1563078, -0.35520023 0.040995985 0.15654911, -0.3555001 0.039762244 0.15503411, -0.3552002 0.03954047 0.15523608, -0.35550019 0.03862606 0.1535091, -0.35520017 0.038369223 0.15366404, -0.3555001 0.037809044 0.15179197, -0.35520011 0.037526846 0.15189384, -0.35550016 0.037342966 0.14994867, -0.35520017 0.037046239 0.14999323, -0.35549995 0.037245154 0.14804964, -0.35520011 0.036945596 0.14803569, -0.35550028 0.054233313 0.14864032, -0.35520029 0.053933382 0.14863472, -0.35550028 0.05408074 0.14701255, -0.35520023 0.053787068 0.14707397, -0.35550028 0.053570017 0.14545988, -0.35520023 0.053297237 0.1455851, -0.35550022 0.052726194 0.14405949, -0.35520029 0.052488282 0.14424224, -0.35550025 0.051592141 0.1428823, -0.35520029 0.051400855 0.14311348, -0.35550028 0.050224811 0.14198686, -0.35520026 0.050089478 0.1422547, -0.35550019 0.048692167 0.14141817, -0.35520023 0.048619971 0.14170931, -0.35550022 0.047071561 0.14120482, -0.35520011 0.047065854 0.14150475, -0.35550022 0.045443803 0.1413572, -0.35520011 0.045505211 0.1416509, -0.35550004 0.043891028 0.14186795, -0.35520023 0.044016078 0.14214088, -0.35550028 0.0424909 0.14271174, -0.35520023 0.042673439 0.14294969, -0.35550028 0.041313589 0.14384569, -0.3552002 0.041544557 0.14403729, -0.3555001 0.040418014 0.14521323, -0.35520008 0.040685862 0.14534853, -0.29250017 0.040418625 0.14521326, -0.2928001 0.04068616 0.14534847, -0.29249999 0.041313991 0.14384575, -0.29280016 0.041545078 0.14403723, -0.29250014 0.042491198 0.14271162, -0.29280019 0.04267402 0.14294983, -0.29250014 0.043891594 0.14186822, -0.29280013 0.0440166 0.14214082, -0.29250008 0.04544434 0.14135729, -0.29280019 0.045505643 0.1416509, -0.29250008 0.0470718 0.14120482, -0.29279995 0.047066286 0.1415046, -0.29250002 0.04869245 0.14141823, -0.29280001 0.048620343 0.14170946, -0.29250011 0.050225213 0.14198674, -0.29280019 0.050089821 0.14225455, -0.29250005 0.051592633 0.14288218, -0.29280019 0.051401287 0.14311348, -0.29250008 0.052726731 0.14405976, -0.29280013 0.052488595 0.14424236, -0.29250014 0.053570405 0.14546008, -0.29280001 0.053297505 0.1455849, -0.29250014 0.054081097 0.14701255, -0.29280019 0.053787455 0.14707397, -0.29250008 0.054233715 0.14864032, -0.29279998 0.053933755 0.1486346, -0.34633529 0.051892057 0.1571884, -0.3452231 0.051554561 0.15737213, -0.29933518 0.051892221 0.1571884, -0.3441202 0.050982222 0.15764771, -0.29822308 0.051554859 0.1573721, -0.34312811 0.050224617 0.1579466, -0.29712024 0.050982609 0.15764762, -0.3422673 0.0493159 0.15821575, -0.3415463 0.048269406 0.15841402, -0.29526728 0.049316138 0.15821587, -0.29612812 0.050224841 0.1579466, -0.34099421 0.047115669 0.1585017, -0.34063655 0.045884907 0.15844817, -0.29399395 0.047115907 0.15850176, -0.29454628 0.048269719 0.15841402, -0.34050083 0.044626147 0.15823339, -0.29363662 0.045885295 0.15844847, -0.2935009 0.044626325 0.15823327, -0.34059799 0.043411016 0.15786205, -0.3409206 0.042277575 0.15735267, -0.29359812 0.043411404 0.15786205, -0.3414419 0.041276425 0.15674855, -0.29392067 0.042278007 0.15735282, -0.29444167 0.041276649 0.15674864, -0.34213322 0.040421993 0.15609191, -0.34297031 0.039718971 0.15542684, -0.34393844 0.039164335 0.15479802, -0.2951332 0.04042232 0.156092, -0.29597014 0.039719239 0.15542687, -0.34502816 0.038758904 0.1542616, -0.34622929 0.038507313 0.15388654, -0.2969383 0.039164647 0.15479805, -0.2992292 0.038507342 0.15388633, -0.29802811 0.038759246 0.1542616, 0.3463352 0.026970983 0.25767118, 0.34750003 0.052013859 0.15712, 0.3462553 0.051879629 0.15719773, 0.34750021 0.027042866 0.25778639, 0.34522331 0.026758626 0.25735092, 0.3450726 0.051495746 0.157405, 0.34412035 0.026381344 0.25683993, 0.34399635 0.05090566 0.15768303, 0.34312817 0.025851429 0.25622153, 0.34303474 0.05014357 0.15797593, 0.34226748 0.025173783 0.25555885, 0.34220093 0.049237058 0.15823556, 0.34154651 0.024341121 0.25489438, 0.3415077 0.048206687 0.15842284, 0.34099418 0.02336213 0.25427759, 0.34097767 0.047076747 0.15850236, 0.34063691 0.022249013 0.25374997, 0.34063193 0.045865253 0.15844537, 0.34050101 0.021035641 0.25335169, 0.34050098 0.044628903 0.15823279, 0.34059542 0.043430686 0.15786789, 0.34059817 0.019787967 0.25311196, 0.34090832 0.04231292 0.15736912, 0.34092075 0.018547893 0.25303251, 0.34141549 0.041321635 0.15677629, 0.34144214 0.017380476 0.25309849, 0.34208822 0.040472552 0.15613119, 0.3421334 0.016318157 0.25328004, 0.3429057 0.039768696 0.15547387, 0.34297046 0.015385926 0.25353944, 0.34384555 0.039212883 0.15485223, 0.34393859 0.014601722 0.25383604, 0.34490931 0.038798466 0.15431128, 0.3450284 0.013992652 0.25412089, 0.34607577 0.038533866 0.15392126, 0.34622943 0.013594627 0.25433469, 0.34678495 0.038452625 0.15379287, 0.34750044 0.013454616 0.25441575, 0.34750032 0.038425609 0.15374936, 0.29933527 0.026970625 0.25767124, 0.30049998 0.052013561 0.15712009, 0.29925525 0.051879272 0.15719773, 0.30050033 0.027042642 0.25778639, 0.29822314 0.026758283 0.25735086, 0.29807273 0.051495224 0.157405, 0.29712018 0.026381001 0.25683987, 0.29699636 0.050905317 0.15768303, 0.29612809 0.025851116 0.25622129, 0.29603484 0.050143257 0.15797593, 0.2952674 0.025173292 0.25555885, 0.295201 0.049236715 0.15823551, 0.29454637 0.024340808 0.25489444, 0.2945078 0.048206344 0.15842284, 0.29399416 0.023361892 0.25427771, 0.29397759 0.047076344 0.15850221, 0.29363677 0.022248864 0.25374997, 0.29363173 0.045864865 0.15844561, 0.29350108 0.021035373 0.25335169, 0.29350081 0.04462859 0.15823279, 0.29359543 0.043430388 0.15786774, 0.29359803 0.019787744 0.25311196, 0.29390833 0.042312711 0.15736906, 0.29392079 0.018547624 0.25303251, 0.29441541 0.041321278 0.15677617, 0.294442 0.017380118 0.25309861, 0.29508811 0.040472254 0.15613125, 0.29513335 0.016317964 0.25327998, 0.29590571 0.039768308 0.15547405, 0.29597035 0.015385568 0.25353944, 0.29684561 0.039212584 0.15485208, 0.29693863 0.014601514 0.25383604, 0.29790917 0.038798332 0.15431108, 0.29802844 0.013992265 0.25412089, 0.29907572 0.038533613 0.15392138, 0.2992295 0.013594389 0.25433481, 0.29978496 0.038452312 0.15379302, 0.30050033 0.013454422 0.25441581, 0.30050007 0.038425431 0.15374939, 0.35520011 0.037233368 0.14609568, 0.29280019 0.037232861 0.14609556, 0.29280007 0.037889123 0.14424844, 0.35520029 0.037889361 0.14424832, 0.29280022 0.038893029 0.14256488, 0.35520023 0.038893402 0.14256479, 0.29280019 0.040206194 0.14110921, 0.35520017 0.040206537 0.14110936, 0.29280013 0.041778103 0.13993798, 0.3552002 0.041778386 0.13993801, 0.29280013 0.043548271 0.13909562, 0.35520005 0.043548778 0.13909568, 0.29280007 0.04544884 0.13861479, 0.35520005 0.045449302 0.13861494, 0.29280007 0.047406614 0.1385143, 0.35520017 0.047406867 0.1385145, 0.29280007 0.049346358 0.13879754, 0.35520011 0.04934673 0.13879739, 0.29280007 0.051193655 0.13945387, 0.35520011 0.051193953 0.13945366, 0.29279998 0.052877307 0.14045794, 0.35519999 0.052877858 0.14045773, 0.29280007 0.054332972 0.14177094, 0.35520014 0.054333284 0.14177094, 0.29279995 0.055504218 0.1433426, 0.35519999 0.055504709 0.14334284, 0.29280007 0.056346655 0.1451128, 0.35520005 0.056346849 0.14511283, 0.29280007 0.056827188 0.14701347, 0.35520005 0.056827411 0.14701347, 0.29280007 0.056927711 0.14897101, 0.35519996 0.056928232 0.14897101, 0.29280007 0.056644619 0.15091078, 0.35519999 0.056644946 0.15091102, 0.35520002 0.053733319 0.15018885, 0.35520023 0.053187788 0.15165819, 0.29280004 0.053732842 0.15018876, 0.29279995 0.05318737 0.15165846, 0.35520008 0.052329093 0.15296964, 0.2928001 0.052328706 0.15296949, 0.35520023 0.051200271 0.15405692, 0.29280013 0.051199734 0.15405704, 0.35519999 0.049857527 0.154866, 0.29280019 0.04985705 0.154866, 0.35520011 0.048368499 0.15535586, 0.29280001 0.048368216 0.15535583, 0.35520011 0.046807826 0.15550219, 0.29280013 0.046807483 0.15550219, 0.35520005 0.045253843 0.15529732, 0.29280019 0.045253336 0.15529732, 0.35520011 0.043784171 0.15475203, 0.29280016 0.043783814 0.15475194, 0.35520008 0.042472929 0.15389346, 0.2928001 0.042472482 0.15389331, 0.35520017 0.041385517 0.15276445, 0.29280013 0.041384995 0.15276445, 0.35520029 0.040576473 0.15142183, 0.29280025 0.040576071 0.15142192, 0.35520029 0.040086642 0.14993279, 0.2928001 0.040086284 0.14993279, 0.35519999 0.039940313 0.1483721, 0.29280019 0.039940059 0.14837198, 0.35520026 0.040144891 0.14681791, 0.29280013 0.040144593 0.14681791, 0.35550007 0.054024458 0.15026094, 0.35550016 0.053455606 0.15179329, 0.35550016 0.052560195 0.15316106, 0.3555001 0.051382795 0.1542951, 0.35550016 0.049982563 0.15513851, 0.35550022 0.048429817 0.15564971, 0.35550016 0.046802223 0.15580212, 0.35550004 0.045181602 0.15558864, 0.35550025 0.043649018 0.15501986, 0.35550022 0.042281613 0.15412439, 0.35550016 0.041147411 0.15294696, 0.35550016 0.040303841 0.15154685, 0.3555001 0.039792955 0.14999415, 0.35550022 0.039640427 0.14836662, 0.35550019 0.039853901 0.14674564, 0.2925002 0.039853483 0.14674573, 0.29250026 0.039640158 0.14836662, 0.2925002 0.039792582 0.14999406, 0.29250008 0.040303558 0.15154676, 0.29250008 0.041147053 0.15294696, 0.29250008 0.042281151 0.15412433, 0.29250005 0.043648601 0.15501986, 0.29250005 0.045181215 0.15558861, 0.29250014 0.046801776 0.15580221, 0.29250002 0.04842937 0.15564965, 0.29250002 0.049982309 0.15513872, 0.29250005 0.051382467 0.15429498, 0.29250005 0.052559718 0.15316103, 0.29249999 0.053455353 0.15179329, 0.29250005 0.05402416 0.15026055, 0.2925002 0.038160563 0.14437605, 0.29250008 0.037524104 0.14616816, 0.29250008 0.039134353 0.14274286, 0.29250008 0.040408164 0.14133118, 0.29250017 0.041932926 0.140195, 0.29250017 0.043650076 0.13937788, 0.2925002 0.045493424 0.13891159, 0.29250002 0.047392517 0.13881408, 0.29249996 0.049274206 0.13908891, 0.29250002 0.051065981 0.13972519, 0.29250002 0.052699268 0.14069889, 0.29249996 0.054111302 0.14197288, 0.29249999 0.055247247 0.14349745, 0.29249996 0.056064188 0.14521475, 0.29250002 0.056530535 0.14705805, 0.29250011 0.056628227 0.14895706, 0.29249996 0.05635336 0.15083878, 0.35550022 0.05662851 0.14895718, 0.3555001 0.056353807 0.15083887, 0.3555001 0.056530878 0.14705805, 0.35550013 0.056064725 0.14521472, 0.35550022 0.055247664 0.14349733, 0.35550016 0.054111466 0.14197288, 0.35550016 0.052699581 0.14069889, 0.35550019 0.051066369 0.13972525, 0.35550016 0.049274549 0.13908862, 0.35550022 0.04739292 0.13881408, 0.35550022 0.045493886 0.13891159, 0.35550016 0.043650404 0.13937788, 0.35550028 0.041933358 0.14019494, 0.35550022 0.040408522 0.14133106, 0.35550022 0.03913483 0.14274286, 0.35550025 0.038160905 0.14437605, 0.35550025 0.037524477 0.14616816, 0.35550034 0.02821888 0.26348633, 0.35520017 0.028235286 0.26543987, 0.35550031 0.027944222 0.26536793, 0.35520017 0.028518707 0.26350003, 0.35550031 0.028121218 0.26158708, 0.35520035 0.02841787 0.26154244, 0.35550031 0.027654991 0.25974369, 0.35520023 0.027937308 0.25964206, 0.35550031 0.026838079 0.25802654, 0.35520029 0.027094945 0.25787199, 0.35550031 0.025701731 0.25650185, 0.35520023 0.025923744 0.25629973, 0.35550034 0.024289936 0.2552281, 0.35520014 0.024468154 0.25498682, 0.35550022 0.022656828 0.25425416, 0.3552002 0.022784308 0.25398284, 0.35550046 0.020864725 0.25361764, 0.35520035 0.020937055 0.25332654, 0.3555004 0.018983275 0.25334299, 0.35520023 0.018997401 0.25304317, 0.35550034 0.017084166 0.25344062, 0.35520035 0.017039567 0.25314409, 0.35550034 0.015240714 0.25390697, 0.35520023 0.015139058 0.25362468, 0.3555004 0.013523683 0.25472391, 0.35520047 0.013368845 0.25446683, 0.35550037 0.011998892 0.25586009, 0.35520047 0.011797071 0.25563836, 0.3555004 0.010725126 0.25727201, 0.35520023 0.010483786 0.25709385, 0.35550052 0.0097514093 0.25890517, 0.35520038 0.0094797909 0.25877762, 0.35550043 0.0091147423 0.26069713, 0.35520026 0.008823812 0.26062483, 0.29250041 0.0097509772 0.25890523, 0.29280031 0.0088234395 0.26062489, 0.29250029 0.0091143399 0.26069707, 0.29280037 0.0094795078 0.25877762, 0.29250038 0.010724694 0.25727212, 0.29280037 0.010483384 0.25709379, 0.29250026 0.011998653 0.25585985, 0.29280028 0.011796653 0.25563824, 0.29250044 0.013523251 0.25472409, 0.29280034 0.013368517 0.25446701, 0.29250026 0.015240386 0.25390685, 0.29280034 0.015138626 0.2536248, 0.2925002 0.017083958 0.25344056, 0.29280028 0.01703912 0.25314391, 0.2925002 0.018982917 0.25334311, 0.29280013 0.018997014 0.25304347, 0.29250026 0.020864472 0.25361776, 0.29280031 0.020936787 0.25332665, 0.2925002 0.022656336 0.2542541, 0.29280028 0.022783965 0.25398278, 0.29250032 0.024289697 0.25522798, 0.29280025 0.024467722 0.25498676, 0.29250023 0.025701255 0.25650185, 0.29280028 0.025923371 0.25629973, 0.2925002 0.026837662 0.25802666, 0.29280025 0.027094573 0.25787187, 0.29250014 0.027654707 0.25974369, 0.29280007 0.027936861 0.25964206, 0.29250014 0.02812086 0.26158702, 0.29280019 0.028417498 0.26154238, 0.29250011 0.028218552 0.26348621, 0.29280025 0.028518289 0.26350021, 0.29250032 0.027943775 0.26536781, 0.29280034 0.028234869 0.26543981, 0.35550031 0.025614887 0.26478994, 0.35520029 0.024778128 0.26618725, 0.35520023 0.025323778 0.26471776, 0.35550034 0.025046006 0.26632243, 0.35520041 0.023919493 0.26749873, 0.3555004 0.02415058 0.26769018, 0.35520035 0.022790551 0.26858628, 0.35550037 0.022973254 0.2688241, 0.35520023 0.021447897 0.26939499, 0.35550022 0.021573067 0.26966786, 0.35520041 0.019958928 0.26988482, 0.35550034 0.020020172 0.27017862, 0.35520041 0.018398136 0.27003127, 0.35550028 0.018392593 0.27033103, 0.35520023 0.016844109 0.26982641, 0.35550031 0.016771853 0.27011788, 0.35520041 0.015374631 0.26928103, 0.35550034 0.015239388 0.26954895, 0.35520035 0.014063329 0.26842254, 0.35550034 0.013871908 0.26865333, 0.35520023 0.012975767 0.26729351, 0.3555004 0.01273784 0.26747596, 0.35520035 0.012166977 0.26595086, 0.35550037 0.011894286 0.26607603, 0.35520041 0.011677086 0.26446187, 0.35550052 0.011383265 0.26452309, 0.35520035 0.011530787 0.26290125, 0.35550043 0.011230752 0.26289552, 0.35520035 0.011735305 0.26134723, 0.35550034 0.011444166 0.26127487, 0.29250026 0.011443868 0.26127481, 0.29250032 0.011230394 0.26289564, 0.29280019 0.011735052 0.26134723, 0.29280031 0.011530459 0.26290137, 0.29250026 0.011383012 0.26452309, 0.29280037 0.011676624 0.26446182, 0.29250026 0.011893809 0.26607585, 0.29280031 0.012166545 0.2659508, 0.2925002 0.012737527 0.26747596, 0.29280037 0.012975544 0.26729351, 0.29250029 0.013871536 0.26865333, 0.29280031 0.014062926 0.26842254, 0.29250035 0.015238926 0.26954895, 0.29280034 0.015374094 0.26928103, 0.29250023 0.016771734 0.27011764, 0.29280034 0.016843677 0.26982671, 0.29250014 0.01839228 0.2703312, 0.29280031 0.018397763 0.27003127, 0.29250026 0.02001968 0.27017868, 0.29280013 0.019958526 0.26988477, 0.29250032 0.02157253 0.26966786, 0.29280025 0.02144748 0.26939499, 0.29250032 0.022972807 0.26882404, 0.29280025 0.022790045 0.26858622, 0.2925002 0.024150237 0.26769018, 0.29280025 0.02391918 0.26749873, 0.2925002 0.025045708 0.26632267, 0.29280028 0.024777785 0.26618743, 0.29250026 0.02561447 0.26478994, 0.29280016 0.025323287 0.26471782, 0.30121565 0.013498604 0.25438976, 0.30192479 0.013630494 0.25431442, 0.34821576 0.013498917 0.25438982, 0.34892505 0.013630837 0.25431436, 0.30309132 0.014046729 0.25409341, 0.35009134 0.014046848 0.25409341, 0.30415484 0.014665753 0.25380886, 0.35115483 0.01466608 0.25380886, 0.30509484 0.015447736 0.25351894, 0.30591232 0.01637724 0.25326681, 0.3529124 0.016377538 0.25326657, 0.35209471 0.015448093 0.25351888, 0.30658498 0.017429337 0.25309318, 0.3070921 0.018582791 0.25303245, 0.35409212 0.018583104 0.25303251, 0.35358515 0.01742959 0.25309324, 0.30740514 0.01980415 0.2531141, 0.30749965 0.021034032 0.25335121, 0.30736858 0.022226378 0.25374079, 0.35440505 0.019804329 0.25311387, 0.30702275 0.023324013 0.25425673, 0.35436854 0.022226676 0.25374079, 0.35449964 0.021034315 0.25335121, 0.30649266 0.024285659 0.25485539, 0.30579939 0.025109276 0.25550258, 0.3540228 0.023324281 0.25425684, 0.35349247 0.024286091 0.25485545, 0.30496556 0.02578944 0.25615567, 0.30400395 0.026326045 0.25677067, 0.35279936 0.025109634 0.25550246, 0.35196561 0.025789723 0.25615543, 0.30292755 0.026717797 0.25729233, 0.30174506 0.026960149 0.25765491, 0.35100406 0.026326194 0.25677067, 0.34874508 0.026960552 0.25765491, 0.34992763 0.026717931 0.25729227, 0.35520011 0.027579218 0.26728737, 0.29280019 0.027578846 0.26728743, 0.35520038 0.026575178 0.26897103, 0.29280034 0.02657488 0.26897109, 0.35520017 0.025261983 0.27042663, 0.29280028 0.02526167 0.27042645, 0.35520023 0.023690253 0.27159798, 0.29280016 0.023689792 0.27159786, 0.35520041 0.021919891 0.2724402, 0.29280034 0.021919608 0.27244014, 0.35520029 0.020019546 0.27292073, 0.2928004 0.020019114 0.27292085, 0.35520023 0.018061906 0.27302122, 0.29280025 0.01806128 0.27302134, 0.35520038 0.016121924 0.27273858, 0.29280025 0.016121551 0.27273834, 0.35520044 0.014274657 0.27208209, 0.29280028 0.014274225 0.27208209, 0.35520047 0.012590885 0.27107823, 0.29280037 0.012590602 0.27107799, 0.35520038 0.011135355 0.26976502, 0.29280031 0.011134997 0.2697649, 0.35520041 0.0099640787 0.26819313, 0.29280025 0.0099636912 0.26819319, 0.35520029 0.0091218352 0.26642299, 0.29280025 0.0091214031 0.26642305, 0.35520029 0.0086412281 0.26452237, 0.29280025 0.0086408108 0.26452237, 0.35520041 0.0085404813 0.2625646, 0.29280037 0.0085400343 0.2625646, 0.29250026 0.02505967 0.27020466, 0.2925002 0.017038494 0.2558862, 0.29250023 0.015485704 0.25639725, 0.29250017 0.02633363 0.26879299, 0.29250026 0.010220677 0.26803833, 0.29250032 0.011356816 0.26956278, 0.29250038 0.018666044 0.25573379, 0.29250044 0.0094037652 0.266321, 0.29250038 0.012768656 0.27083683, 0.29250032 0.02028662 0.25594705, 0.29250032 0.0089375228 0.26447767, 0.29250017 0.027307302 0.26715976, 0.29250017 0.014402106 0.27181065, 0.29250032 0.0088397712 0.26257861, 0.29250011 0.016193852 0.27244699, 0.29250032 0.018075377 0.27272165, 0.2925002 0.021819174 0.25651574, 0.29250026 0.012012571 0.25974226, 0.29250035 0.025827855 0.26316911, 0.29250014 0.023186922 0.25741112, 0.29250032 0.019974291 0.27262425, 0.29250029 0.025675222 0.26154172, 0.2925002 0.024320781 0.25858879, 0.29250032 0.012908041 0.25837475, 0.29250011 0.0251645 0.25998908, 0.29250032 0.021817952 0.27215785, 0.29250017 0.014085412 0.25724071, 0.29250023 0.023534939 0.27134109, 0.35550031 0.025060147 0.27020454, 0.35550046 0.017038837 0.2558862, 0.3555004 0.015485942 0.25639725, 0.35550022 0.026333794 0.26879293, 0.3555004 0.018666506 0.25573379, 0.35550037 0.010221049 0.26803803, 0.35550034 0.011357039 0.26956284, 0.35550046 0.0094039887 0.26632124, 0.35550043 0.012769103 0.27083683, 0.35550028 0.027307779 0.2671597, 0.35550034 0.0089378655 0.26447767, 0.35550034 0.020287037 0.25594705, 0.3555004 0.014402255 0.27181077, 0.35550058 0.0088401139 0.26257873, 0.35550028 0.016194239 0.27244729, 0.3555004 0.018075719 0.27272177, 0.35550034 0.025828302 0.26316911, 0.35550028 0.012013137 0.2597422, 0.35550028 0.021819547 0.25651586, 0.35550028 0.019974858 0.27262414, 0.35550037 0.025675625 0.26154166, 0.35550034 0.023187146 0.25741136, 0.3555004 0.012908503 0.25837493, 0.35550034 0.025164887 0.25998884, 0.35550028 0.02181834 0.27215779, 0.35550034 0.024321184 0.25858873, 0.35550049 0.01408574 0.25724071, 0.35550028 0.023535475 0.27134109, 0.35520026 0.012280762 0.25987762, 0.2928004 0.012280405 0.25987756, 0.35520032 0.013139457 0.2585662, 0.29280028 0.013139069 0.2585662, 0.29280028 0.014268056 0.25747871, 0.35520041 0.014268488 0.25747871, 0.29280031 0.01561065 0.2566697, 0.35520032 0.015611053 0.25666976, 0.29280019 0.017099723 0.25617987, 0.35520029 0.01710017 0.25617993, 0.29280031 0.018660367 0.25603366, 0.35520035 0.018660888 0.2560336, 0.29280025 0.020214573 0.25623828, 0.35520023 0.020214796 0.25623834, 0.29280025 0.021683991 0.25678366, 0.35520029 0.021684423 0.25678366, 0.29280013 0.022995472 0.25764227, 0.35520026 0.022995844 0.25764245, 0.29280022 0.02408278 0.25877136, 0.35520035 0.024083287 0.25877136, 0.29280028 0.024891943 0.26011401, 0.35520014 0.024892151 0.26011384, 0.35520029 0.025381923 0.26160312, 0.29280028 0.02538158 0.26160294, 0.35520029 0.025528252 0.26316386, 0.29280028 0.025527835 0.26316369, 0.35550028 0.037249714 0.14804952, 0.35520029 0.036950037 0.14803569, 0.35550025 0.037347436 0.14994864, 0.35520017 0.037050754 0.14999332, 0.35550028 0.037813574 0.15179197, 0.35520023 0.037531391 0.15189369, 0.35550022 0.038630635 0.15350904, 0.35520023 0.038373619 0.15366389, 0.35550016 0.039766729 0.15503408, 0.35520011 0.039545029 0.15523578, 0.35550022 0.041178629 0.15630759, 0.35520017 0.041000471 0.15654899, 0.35550028 0.042812034 0.15728156, 0.35520014 0.042684302 0.15755306, 0.35550022 0.044603869 0.15791814, 0.3552002 0.044531554 0.15820919, 0.3555001 0.046485379 0.15819298, 0.35520011 0.046471417 0.15849231, 0.3555001 0.048384428 0.15809508, 0.35520011 0.048429057 0.15839209, 0.35550016 0.050227866 0.15762885, 0.35520017 0.050329551 0.15791105, 0.35550016 0.051944941 0.15681194, 0.35520011 0.052099854 0.15706895, 0.35550007 0.053469509 0.15567566, 0.35519996 0.053671718 0.15589736, 0.35550013 0.054743558 0.15426384, 0.35520008 0.054984778 0.15444194, 0.35550016 0.055717215 0.15263055, 0.35520008 0.055988759 0.15275826, 0.29250002 0.055716947 0.15263061, 0.29280001 0.055988491 0.15275835, 0.29250002 0.054743126 0.15426378, 0.29280001 0.05498457 0.15444188, 0.29249996 0.05346936 0.15567555, 0.29279995 0.053671181 0.15589751, 0.29250005 0.05194445 0.15681194, 0.29280007 0.052099437 0.1570688, 0.29250002 0.050227582 0.15762876, 0.29280013 0.050329179 0.15791105, 0.29250014 0.048383921 0.15809508, 0.29280007 0.048428655 0.15839179, 0.29250014 0.046484962 0.15819289, 0.29280007 0.046471 0.15849231, 0.29250023 0.044603467 0.15791805, 0.29280001 0.044531077 0.15820928, 0.29250002 0.042811632 0.15728153, 0.29279998 0.042683855 0.15755321, 0.29250008 0.041178346 0.1563078, 0.29280019 0.041000187 0.15654905, 0.29250011 0.039766505 0.15503399, 0.29280013 0.039544567 0.15523578, 0.29250014 0.038630202 0.15350933, 0.29280007 0.038373217 0.15366413, 0.29250011 0.037813216 0.15179197, 0.29280007 0.037531078 0.15189384, 0.29250026 0.037347108 0.14994864, 0.29280013 0.037050396 0.14999346, 0.29250008 0.037249446 0.1480494, 0.29280013 0.036949724 0.14803569, 0.2924999 0.05423753 0.14864008, 0.2928001 0.053937525 0.1486346, 0.29250002 0.054084852 0.14701246, 0.2928001 0.053791195 0.14707394, 0.29250005 0.053574115 0.14545996, 0.29280016 0.053301334 0.14558481, 0.29249999 0.052730471 0.14405976, 0.29280007 0.052492365 0.14424224, 0.29250011 0.051596507 0.14288224, 0.2928001 0.051404938 0.14311324, 0.29250014 0.050228894 0.14198671, 0.29280019 0.050093532 0.14225446, 0.29250011 0.048696309 0.14141817, 0.29280001 0.048624098 0.14170919, 0.29250008 0.047075644 0.14120467, 0.29280007 0.047070086 0.14150454, 0.29250014 0.04544805 0.14135726, 0.29280013 0.045509398 0.1416509, 0.29249999 0.043895364 0.14186807, 0.29280013 0.04402028 0.14214061, 0.29250011 0.042495057 0.14271162, 0.2928001 0.042677686 0.14294969, 0.29249996 0.041317776 0.14384569, 0.29280019 0.041548789 0.14403714, 0.29250008 0.040422142 0.14521323, 0.2928001 0.040690064 0.14534847, 0.35550022 0.040422559 0.14521323, 0.35520011 0.040690511 0.14534838, 0.35520014 0.041549087 0.14403702, 0.35550016 0.041318089 0.1438456, 0.35519999 0.042678043 0.14294969, 0.35550016 0.042495444 0.14271162, 0.35520017 0.044020653 0.14214073, 0.35550022 0.043895617 0.14186807, 0.35520005 0.045509741 0.1416509, 0.3555001 0.045448437 0.14135729, 0.3555001 0.047076106 0.14120482, 0.35520011 0.047070414 0.1415046, 0.35520005 0.048624486 0.14170919, 0.35550016 0.048696727 0.14141823, 0.35550028 0.050229341 0.14198674, 0.35520017 0.050093964 0.1422547, 0.35550022 0.051596671 0.1428823, 0.35520011 0.051405311 0.14311342, 0.35520017 0.052492812 0.14424224, 0.35550016 0.052730784 0.1440597, 0.35550019 0.053574428 0.14545996, 0.35520011 0.053301722 0.14558481, 0.3555001 0.054085284 0.14701252, 0.35520017 0.053791642 0.14707391, 0.35550013 0.054237753 0.14864032, 0.35520005 0.053937986 0.1486346, 0.30166519 0.051895991 0.15718825, 0.30277711 0.051558912 0.15737213, 0.34866518 0.051896363 0.15718831, 0.3038801 0.050986364 0.15764762, 0.34977722 0.051559031 0.1573721, 0.30487221 0.050228685 0.1579466, 0.35088003 0.050986767 0.15764762, 0.30573285 0.049320057 0.15821587, 0.30645388 0.048273459 0.15841411, 0.3527329 0.04932031 0.15821569, 0.35187221 0.050229087 0.1579466, 0.3070063 0.047119811 0.15850161, 0.30736369 0.04588908 0.15844823, 0.3540062 0.047120154 0.15850161, 0.35345393 0.048273861 0.15841396, 0.30749938 0.044630319 0.15823324, 0.35436374 0.045889378 0.15844823, 0.35449931 0.044630572 0.15823327, 0.30740225 0.043415263 0.15786196, 0.30707964 0.042281702 0.15735258, 0.3544023 0.043415442 0.1578619, 0.30655846 0.041280568 0.15674855, 0.35407972 0.042282 0.15735267, 0.35355842 0.041280687 0.15674864, 0.30586714 0.04042621 0.15609191, 0.30503017 0.039723217 0.15542664, 0.30406183 0.039168417 0.15479805, 0.35286716 0.040426493 0.15609182, 0.3520301 0.039723441 0.15542687, 0.30297217 0.038763046 0.15426151, 0.30177099 0.038511276 0.15388633, 0.35106185 0.03916879 0.15479802, 0.34877104 0.038511619 0.15388633, 0.34997216 0.03876327 0.15426157, -0.34633511 0.026995659 -0.25766695, -0.34750032 0.052027106 -0.15711282, -0.34625554 0.051893041 -0.15719043, -0.34750009 0.027067661 -0.25778192, -0.34522289 0.026783317 -0.25734663, -0.34507287 0.051508993 -0.15739773, -0.34412014 0.026405975 -0.2568357, -0.34399638 0.050918967 -0.15767615, -0.34312797 0.025875896 -0.25621718, -0.34303483 0.050157011 -0.15796907, -0.34226716 0.025198162 -0.2555548, -0.34220111 0.049250558 -0.15822886, -0.34154624 0.024365455 -0.25489056, -0.341508 0.048220143 -0.15841602, -0.340994 0.023386568 -0.25427365, -0.34097767 0.047090366 -0.15849565, -0.34063649 0.022273183 -0.25374621, -0.3406319 0.045878753 -0.15843903, -0.34050071 0.021059841 -0.25334793, -0.34050095 0.044642374 -0.15822645, -0.34059536 0.043444306 -0.15786169, -0.34059796 0.019812331 -0.25310838, -0.34090847 0.042326301 -0.15736301, -0.34092045 0.018572167 -0.25302911, -0.34141544 0.041335016 -0.15677033, -0.34144181 0.017404795 -0.25309539, -0.34208819 0.040485784 -0.15612529, -0.3421331 0.01634258 -0.25327682, -0.3429057 0.039781958 -0.15546788, -0.34297007 0.01541014 -0.25353646, -0.3438457 0.03922607 -0.15484641, -0.34393829 0.014626071 -0.25383312, -0.34490916 0.03881152 -0.15430547, -0.34502798 0.014016852 -0.25411785, -0.34607559 0.038546935 -0.15391548, -0.34622931 0.013618976 -0.25433183, -0.34678486 0.038465425 -0.1537873, -0.34749994 0.013479054 -0.25441289, -0.34750009 0.038438469 -0.15374379, -0.29933512 0.026995957 -0.25766695, -0.30050021 0.052027464 -0.15711282, -0.29925543 0.051893175 -0.15719043, -0.30050004 0.027067855 -0.2577821, -0.29822296 0.026783496 -0.25734663, -0.29807287 0.051509321 -0.15739797, -0.29711992 0.026406184 -0.25683546, -0.29699644 0.050919339 -0.15767615, -0.29612786 0.02587612 -0.25621712, -0.29603496 0.050157443 -0.15796907, -0.29526734 0.02519846 -0.2555548, -0.29520103 0.049250901 -0.15822886, -0.29454622 0.024365678 -0.25489056, -0.29450789 0.048220366 -0.1584159, -0.29399398 0.023386747 -0.25427377, -0.29397774 0.04709059 -0.15849565, -0.29363647 0.02227366 -0.25374615, -0.29363185 0.045879036 -0.15843926, -0.29350081 0.021060333 -0.25334793, -0.29350096 0.044642746 -0.15822648, -0.29359543 0.043444544 -0.15786169, -0.29359776 0.019812629 -0.25310826, -0.29390842 0.04232651 -0.15736292, -0.29392052 0.018572465 -0.25302899, -0.29441544 0.0413353 -0.15677033, -0.2944417 0.017405003 -0.25309557, -0.2950882 0.040486142 -0.15612547, -0.29513294 0.016342759 -0.25327682, -0.29590562 0.039782092 -0.15546797, -0.29597002 0.015410453 -0.25353622, -0.2968457 0.039226368 -0.1548465, -0.29693824 0.014626339 -0.25383306, -0.29790917 0.038811922 -0.15430547, -0.29802802 0.01401712 -0.25411808, -0.29907566 0.038547277 -0.1539156, -0.29922909 0.013619214 -0.25433207, -0.29978493 0.038465798 -0.15378721, -0.30050001 0.013479337 -0.25441283, -0.30050004 0.038438842 -0.15374373, -0.35520005 0.037245169 -0.14609028, -0.29280007 0.037245661 -0.14609019, -0.29280013 0.037901565 -0.1442429, -0.35520011 0.037901118 -0.14424305, -0.29280013 0.038905367 -0.14255892, -0.35520011 0.038905099 -0.14255907, -0.29280016 0.040218398 -0.14110343, -0.35520023 0.040217996 -0.14110349, -0.29280013 0.041790068 -0.13993178, -0.35520029 0.0417898 -0.1399319, -0.29280013 0.043560177 -0.13908945, -0.35520035 0.043560028 -0.1390893, -0.29280013 0.045460701 -0.13860856, -0.35520029 0.045460254 -0.13860865, -0.29280013 0.047418386 -0.13850759, -0.3552002 0.047418088 -0.13850759, -0.2928001 0.049358234 -0.1387905, -0.35520035 0.049357966 -0.13879071, -0.29280025 0.051205665 -0.13944669, -0.35520035 0.051205233 -0.13944669, -0.29280025 0.052889481 -0.14045046, -0.35520023 0.052889034 -0.14045034, -0.29280031 0.054345086 -0.14176337, -0.35520035 0.054344818 -0.14176331, -0.29280025 0.055516705 -0.14333509, -0.35520038 0.055516332 -0.14333524, -0.29280025 0.056359068 -0.14510523, -0.35520029 0.056358874 -0.14510523, -0.29280007 0.056839809 -0.14700566, -0.35520044 0.056839556 -0.14700566, -0.29280031 0.056940928 -0.1489635, -0.35520032 0.056940407 -0.1489635, -0.29280019 0.056658 -0.15090312, -0.35520017 0.056657359 -0.15090318, -0.29280031 0.053746 -0.15018137, -0.35520029 0.053745687 -0.15018137, -0.29280019 0.053200871 -0.1516508, -0.35520035 0.053200468 -0.15165086, -0.29280022 0.052342281 -0.1529624, -0.35520023 0.052341804 -0.1529624, -0.35520035 0.051213101 -0.15404998, -0.29280016 0.051213518 -0.15405004, -0.35520035 0.049870521 -0.15485905, -0.2928001 0.049870864 -0.15485899, -0.35520023 0.048381567 -0.15534909, -0.29280019 0.04838191 -0.1553493, -0.35520029 0.046820879 -0.1554956, -0.29280013 0.046821296 -0.15549554, -0.35520017 0.045266762 -0.15529107, -0.29280019 0.045267254 -0.15529107, -0.35520029 0.043797269 -0.15474577, -0.29280013 0.043797493 -0.15474589, -0.35520023 0.04248561 -0.15388735, -0.29280013 0.042486072 -0.1538875, -0.35520035 0.041398227 -0.15275832, -0.29280019 0.04139851 -0.15275832, -0.35520035 0.040589079 -0.15141596, -0.29280013 0.040589556 -0.15141587, -0.35520014 0.040099114 -0.14992698, -0.29280019 0.040099502 -0.14992683, -0.35520023 0.039952561 -0.14836638, -0.2928001 0.039953023 -0.14836623, -0.35520023 0.04015705 -0.14681225, -0.29280004 0.040157437 -0.14681213, -0.35550034 0.054036915 -0.15025346, -0.35550028 0.053468168 -0.1517861, -0.35550022 0.052572817 -0.15315394, -0.35550028 0.051395729 -0.15428801, -0.35550031 0.049995601 -0.15513177, -0.35550025 0.04844293 -0.15564273, -0.35550022 0.046815306 -0.15579556, -0.35550016 0.045194581 -0.15558229, -0.35550022 0.043661892 -0.15501361, -0.35550022 0.042294264 -0.15411837, -0.35550001 0.041160107 -0.152941, -0.35550013 0.040316343 -0.15154104, -0.3555001 0.039805412 -0.14998825, -0.35550022 0.039652646 -0.14836077, -0.35550022 0.039865896 -0.14674, -0.29250023 0.039866313 -0.14673989, -0.29250014 0.039653003 -0.14836074, -0.29250002 0.039805815 -0.14998825, -0.29250011 0.040316805 -0.15154113, -0.29250014 0.041160509 -0.15294106, -0.29250014 0.0422948 -0.15411837, -0.29250026 0.043662459 -0.15501367, -0.2925002 0.045194954 -0.15558229, -0.29250014 0.046815768 -0.15579556, -0.29250014 0.048443303 -0.15564273, -0.29250017 0.049996018 -0.15513177, -0.2925002 0.051396117 -0.15428795, -0.2925002 0.052573323 -0.15315394, -0.2925002 0.053468615 -0.15178616, -0.2925002 0.054037169 -0.15025355, -0.29250014 0.038173139 -0.14437048, -0.29250008 0.037536874 -0.14616244, -0.29250011 0.039146692 -0.14273717, -0.29250017 0.040420473 -0.14132513, -0.29250014 0.04194504 -0.14018871, -0.29250014 0.043662056 -0.1393715, -0.29250014 0.045505494 -0.13890527, -0.29250008 0.047404513 -0.13880725, -0.29250017 0.049286097 -0.13908191, -0.29250014 0.051078022 -0.13971807, -0.2925002 0.052711338 -0.14069183, -0.2925002 0.054123357 -0.14196537, -0.29250002 0.055259675 -0.14348994, -0.2925002 0.056076944 -0.14520691, -0.2925002 0.05654332 -0.1470504, -0.2925002 0.056641176 -0.14894952, -0.29250026 0.056366682 -0.15083103, -0.35550022 0.056640744 -0.14894943, -0.35550034 0.056366161 -0.15083112, -0.35550028 0.056542948 -0.14705043, -0.35550028 0.056076601 -0.14520691, -0.35550022 0.055259287 -0.14349012, -0.35550022 0.054122925 -0.14196537, -0.35550034 0.05271104 -0.14069171, -0.35550016 0.05107747 -0.13971828, -0.35550022 0.049285635 -0.13908185, -0.35550007 0.047404096 -0.1388074, -0.3555001 0.045505047 -0.13890521, -0.35550028 0.043661624 -0.13937159, -0.35550028 0.041944683 -0.1401888, -0.35550013 0.040419996 -0.14132525, -0.3555001 0.039146364 -0.14273725, -0.35550022 0.038172647 -0.14437069, -0.35550007 0.037536398 -0.14616252, -0.35550004 0.028244078 -0.26348162, -0.35520014 0.028260708 -0.26543552, -0.35550016 0.027969569 -0.26536351, -0.35520014 0.028543741 -0.26349574, -0.3555001 0.028146267 -0.26158267, -0.35520029 0.02844286 -0.26153791, -0.35550016 0.02767989 -0.2597391, -0.35520011 0.027962103 -0.25963759, -0.35550004 0.026862681 -0.25802231, -0.35520005 0.027119622 -0.25786746, -0.35550004 0.025726125 -0.2564978, -0.35520011 0.025948018 -0.25629568, -0.35550001 0.024314195 -0.25522411, -0.35519999 0.024492353 -0.25498265, -0.35550004 0.022680834 -0.25425041, -0.35520011 0.022808582 -0.25397885, -0.35550004 0.020888895 -0.25361413, -0.35520017 0.020961151 -0.25332296, -0.3555001 0.0190074 -0.25333959, -0.35519999 0.019021347 -0.25304002, -0.35550004 0.017108336 -0.25343752, -0.35520011 0.017063588 -0.25314081, -0.35549995 0.015264899 -0.25390393, -0.35520005 0.015163049 -0.2536217, -0.35549998 0.013547838 -0.25472105, -0.35519999 0.013393044 -0.25446421, -0.35549998 0.012023345 -0.25585735, -0.35519999 0.011821315 -0.25563568, -0.35549995 0.010749489 -0.2572695, -0.3551999 0.010508209 -0.25709128, -0.35550004 0.0097760409 -0.25890279, -0.35519999 0.0095045567 -0.25877523, -0.35550007 0.0091397315 -0.26069486, -0.35519993 0.0088485479 -0.26062262, -0.29249993 0.0097763985 -0.25890279, -0.29279989 0.0088488758 -0.26062256, -0.29249996 0.0091400892 -0.26069486, -0.29279983 0.0095048547 -0.25877523, -0.2924999 0.01075004 -0.2572695, -0.29279992 0.010508686 -0.25709128, -0.29249987 0.012023643 -0.25585747, -0.29279986 0.011821657 -0.25563568, -0.2924999 0.01354824 -0.25472105, -0.29279998 0.013393477 -0.25446415, -0.29249996 0.015265331 -0.25390393, -0.29280001 0.015163571 -0.2536217, -0.29250008 0.017108768 -0.25343752, -0.29280001 0.01706408 -0.25314075, -0.29249996 0.019007728 -0.25333959, -0.29279989 0.01902172 -0.25304008, -0.29249987 0.020889267 -0.25361413, -0.29280004 0.020961434 -0.25332296, -0.29249999 0.022681236 -0.25425041, -0.29279992 0.02280876 -0.25397885, -0.29250008 0.024314582 -0.25522411, -0.29280007 0.024492666 -0.25498265, -0.29250002 0.025726661 -0.25649762, -0.29279995 0.025948286 -0.25629556, -0.29250002 0.026863143 -0.25802225, -0.29280007 0.027119979 -0.25786746, -0.29250008 0.027680248 -0.2597391, -0.29279989 0.027962357 -0.25963748, -0.29250002 0.028146669 -0.26158279, -0.29280013 0.028443202 -0.26153809, -0.29250002 0.02824448 -0.26348156, -0.29280001 0.028544158 -0.26349574, -0.29250002 0.027970031 -0.26536351, -0.29280001 0.028261095 -0.26543552, -0.35550004 0.025640145 -0.26478595, -0.3555001 0.025071666 -0.26631838, -0.35520017 0.025348976 -0.26471359, -0.35520017 0.024803713 -0.26618344, -0.35550004 0.02417618 -0.26768607, -0.35520005 0.023945212 -0.26749474, -0.35550013 0.022998959 -0.26882023, -0.35520005 0.022816345 -0.26858228, -0.35550016 0.021598935 -0.26966399, -0.35520023 0.02147387 -0.26939124, -0.3555001 0.020046175 -0.2701751, -0.35519999 0.019984826 -0.26988143, -0.35550004 0.018418685 -0.27032793, -0.35520014 0.018424183 -0.27002782, -0.35550004 0.0167979 -0.27011448, -0.35520005 0.016870022 -0.26982337, -0.35549992 0.015265197 -0.26954603, -0.35520005 0.015400454 -0.26927811, -0.35549986 0.013897508 -0.26865065, -0.35519999 0.014088988 -0.26841968, -0.35550007 0.012763545 -0.26747328, -0.35520011 0.013001487 -0.26729065, -0.35549995 0.011919707 -0.26607329, -0.35519996 0.012192369 -0.26594824, -0.3555001 0.011408642 -0.26452059, -0.35520005 0.011702269 -0.26445925, -0.35549998 0.011255905 -0.26289302, -0.35519999 0.01155588 -0.26289856, -0.35549998 0.0114692 -0.26127243, -0.35520005 0.011760339 -0.26134437, -0.29249993 0.011469573 -0.26127243, -0.29279998 0.011556268 -0.26289856, -0.29279992 0.011760712 -0.26134443, -0.29249993 0.011256382 -0.26289302, -0.29279992 0.011702687 -0.26445919, -0.29250005 0.011409044 -0.26452059, -0.29279998 0.012192801 -0.26594824, -0.29249993 0.011920124 -0.26607329, -0.29279998 0.013001889 -0.26729065, -0.29250008 0.012763739 -0.2674734, -0.29279998 0.01408945 -0.26841968, -0.29249993 0.013897941 -0.26865065, -0.29279995 0.015400857 -0.26927811, -0.2924999 0.015265584 -0.26954603, -0.29279995 0.01687035 -0.26982325, -0.29249996 0.016798317 -0.27011466, -0.29280001 0.018424615 -0.2700277, -0.29250002 0.018419147 -0.27032775, -0.29280004 0.019985139 -0.26988131, -0.29250002 0.020046562 -0.27017492, -0.29280007 0.021474168 -0.26939136, -0.29250005 0.021599263 -0.26966405, -0.29280016 0.022816703 -0.26858222, -0.29250011 0.022999376 -0.26882046, -0.29280001 0.023945451 -0.26749462, -0.29249996 0.024176508 -0.26768619, -0.29279995 0.024804026 -0.2661832, -0.29249996 0.025071815 -0.2663185, -0.29280013 0.025349393 -0.26471359, -0.2924999 0.025640532 -0.26478583, -0.30121529 0.0135234 -0.25438708, -0.30192447 0.013655335 -0.25431156, -0.34821528 0.013523176 -0.25438708, -0.34892458 0.013654992 -0.25431156, -0.30309099 0.014071494 -0.25409049, -0.35009116 0.014071211 -0.25409049, -0.30415452 0.014690638 -0.25380588, -0.35115451 0.01469034 -0.25380588, -0.30509454 0.015472367 -0.25351596, -0.3059119 0.016401976 -0.25326359, -0.35291207 0.016401738 -0.25326359, -0.35209447 0.015472159 -0.25351608, -0.3065846 0.017454043 -0.2530899, -0.30709183 0.018607453 -0.25302911, -0.35409176 0.01860705 -0.25302911, -0.35358477 0.017453745 -0.25308985, -0.30740488 0.019828901 -0.25311041, -0.30749935 0.021058604 -0.25334752, -0.30736843 0.022251025 -0.25373703, -0.35440499 0.019828439 -0.25311059, -0.30702269 0.023348868 -0.25425279, -0.35436845 0.022250727 -0.25373721, -0.35449946 0.02105844 -0.2533474, -0.3064923 0.024310634 -0.25485134, -0.30579919 0.025134146 -0.25549811, -0.35402262 0.023348451 -0.25425291, -0.35349244 0.024310246 -0.25485146, -0.30496532 0.025814354 -0.25615144, -0.30400378 0.026351154 -0.25676644, -0.35279924 0.025133863 -0.25549835, -0.35196543 0.025814101 -0.25615144, -0.30292743 0.026742801 -0.25728786, -0.30174482 0.02698563 -0.25765061, -0.35100383 0.026350856 -0.25676644, -0.34874487 0.026985347 -0.25765067, -0.34992743 0.026742578 -0.25728798, -0.35520011 0.027604744 -0.2672829, -0.29279995 0.027605176 -0.2672829, -0.35520011 0.026601046 -0.26896673, -0.29280001 0.026601434 -0.26896673, -0.35520005 0.02528809 -0.2704224, -0.29280007 0.025288448 -0.27042234, -0.35520005 0.023716241 -0.27159411, -0.29280001 0.023716599 -0.27159399, -0.35520002 0.021946192 -0.27243644, -0.29279986 0.021946549 -0.27243644, -0.35520023 0.020045683 -0.27291727, -0.29280004 0.020046145 -0.27291727, -0.35520002 0.018087998 -0.27301818, -0.29279983 0.018088356 -0.27301818, -0.35520011 0.016148254 -0.27273518, -0.29279995 0.016148508 -0.27273518, -0.35520005 0.014300808 -0.27207923, -0.29279986 0.014301196 -0.27207923, -0.35520005 0.012616977 -0.27107543, -0.29279986 0.01261729 -0.27107531, -0.35520002 0.011161298 -0.26976246, -0.29279995 0.01116167 -0.26976234, -0.35520002 0.0099897087 -0.26819068, -0.29279989 0.0099900663 -0.26819056, -0.35519999 0.0091474354 -0.26642054, -0.29279995 0.0091477633 -0.26642054, -0.35520005 0.0086664408 -0.26451999, -0.29279995 0.0086667985 -0.26452005, -0.35519993 0.0085655302 -0.26256245, -0.29279995 0.0085659474 -0.26256245, -0.29250002 0.026360095 -0.26878858, -0.29250008 0.025086507 -0.27020061, -0.29249996 0.017063543 -0.25588322, -0.29250002 0.018691063 -0.25573039, -0.29250002 0.027333662 -0.26715523, -0.29249993 0.010247156 -0.26803583, -0.29249999 0.011383444 -0.26956052, -0.29249996 0.020311818 -0.25594366, -0.29249984 0.0094299763 -0.26631874, -0.29249996 0.012795582 -0.27083403, -0.29249984 0.0089634955 -0.26447529, -0.2924999 0.014428794 -0.27180761, -0.29249996 0.0088656545 -0.26257646, -0.29250008 0.025853783 -0.263165, -0.29249996 0.016220838 -0.27244395, -0.29250002 0.018102393 -0.27271849, -0.29249987 0.021844327 -0.25651205, -0.29250008 0.025701135 -0.26153761, -0.29249987 0.012038156 -0.25973964, -0.29249993 0.023212016 -0.25740755, -0.29249996 0.025189981 -0.25998485, -0.29250002 0.020001307 -0.27262056, -0.29249996 0.024346128 -0.25858474, -0.29249999 0.012933522 -0.25837189, -0.29250002 0.021844745 -0.27215415, -0.29249981 0.01411061 -0.25723791, -0.29250005 0.023561746 -0.27133709, -0.29250002 0.015510708 -0.25639415, -0.35549992 0.017063156 -0.25588298, -0.3555001 0.026359618 -0.2687887, -0.35549998 0.018690705 -0.25573033, -0.35550004 0.027333304 -0.26715529, -0.35549995 0.020311296 -0.25594366, -0.35550001 0.010246694 -0.26803589, -0.35550007 0.011383116 -0.26956052, -0.35549989 0.009429574 -0.26631874, -0.35550004 0.01279512 -0.27083421, -0.35549992 0.0089630485 -0.26447541, -0.35550004 0.014428511 -0.27180773, -0.35549992 0.0088652223 -0.26257646, -0.35550001 0.02585341 -0.263165, -0.35550001 0.021844059 -0.25651228, -0.3555001 0.025700659 -0.26153761, -0.35549998 0.016220316 -0.27244407, -0.35550004 0.01810196 -0.27271849, -0.35550013 0.023211718 -0.25740755, -0.35550016 0.025189564 -0.25998485, -0.35549998 0.01203768 -0.25973964, -0.35550007 0.020001039 -0.27262056, -0.3555001 0.02434583 -0.25858474, -0.35549995 0.012933031 -0.25837195, -0.35550004 0.021844521 -0.27215409, -0.35549998 0.014110282 -0.25723779, -0.35549998 0.023561373 -0.27133703, -0.35550004 0.01551047 -0.25639415, -0.35550001 0.025086001 -0.27020061, -0.35520002 0.012305588 -0.25987494, -0.29279998 0.012306049 -0.25987458, -0.35520005 0.013164043 -0.2585634, -0.29279995 0.01316455 -0.2585634, -0.35519999 0.01429303 -0.25747585, -0.29279989 0.014293253 -0.25747585, -0.35520017 0.01563555 -0.25666672, -0.29280001 0.015635982 -0.25666678, -0.35520002 0.017124414 -0.25617671, -0.29280007 0.017124876 -0.25617671, -0.35520014 0.018685117 -0.25603032, -0.29280001 0.018685564 -0.2560302, -0.29279992 0.020239621 -0.25623465, -0.35520011 0.020239219 -0.25623477, -0.29280004 0.021709099 -0.25677985, -0.35520011 0.021708727 -0.25677991, -0.35520005 0.023020357 -0.25763863, -0.29279995 0.023020715 -0.25763845, -0.35520017 0.024107873 -0.25876725, -0.29279998 0.024108171 -0.25876725, -0.35520005 0.024917006 -0.2601099, -0.29279995 0.024917275 -0.26010978, -0.29280019 0.025407478 -0.26159883, -0.35520017 0.025407091 -0.26159883, -0.29280007 0.025553808 -0.26315951, -0.35520017 0.02555351 -0.26315928, -0.35550022 0.037261859 -0.14804412, -0.35520017 0.036962241 -0.14803021, -0.35550016 0.037359774 -0.14994316, -0.35520029 0.037063241 -0.14998774, -0.3555001 0.037826359 -0.15178661, -0.35520017 0.037544161 -0.15188842, -0.35550016 0.03864345 -0.15350352, -0.35520026 0.03838639 -0.15365838, -0.3555001 0.039779708 -0.15502812, -0.3552002 0.039558053 -0.15523024, -0.35550013 0.041191936 -0.15630163, -0.35520029 0.041013613 -0.15654324, -0.35550013 0.042825133 -0.15727542, -0.35520023 0.042697519 -0.15754695, -0.35550028 0.044617087 -0.15791176, -0.35520035 0.04454498 -0.15820299, -0.35550022 0.046498746 -0.15818615, -0.35520032 0.046484783 -0.15848596, -0.35550025 0.04839775 -0.15808843, -0.35520014 0.048442394 -0.1583849, -0.35550016 0.050240979 -0.15762202, -0.35520029 0.050342768 -0.15790425, -0.35550034 0.051958159 -0.1568047, -0.35520041 0.052113026 -0.15706177, -0.35550028 0.053482711 -0.15566836, -0.35520029 0.053684786 -0.15589027, -0.35550034 0.054756463 -0.1542563, -0.35520035 0.054997757 -0.15443455, -0.35550022 0.055730075 -0.15262301, -0.35520023 0.056001499 -0.15275066, -0.29280025 0.056001887 -0.15275057, -0.2925002 0.055730432 -0.15262295, -0.29280019 0.05499804 -0.15443449, -0.29250026 0.054756716 -0.15425639, -0.29280025 0.053685173 -0.15589027, -0.2925002 0.053483173 -0.15566836, -0.29280019 0.052113354 -0.15706156, -0.2925002 0.051958531 -0.15680476, -0.29280016 0.050343245 -0.15790395, -0.29250011 0.050241455 -0.15762182, -0.29280025 0.048442885 -0.15838505, -0.29250023 0.048398137 -0.15808843, -0.29280025 0.046485156 -0.15848587, -0.29250014 0.046499178 -0.15818612, -0.29280013 0.044545352 -0.15820284, -0.29250002 0.04461737 -0.15791176, -0.29280013 0.042697906 -0.15754686, -0.29249996 0.042825431 -0.15727527, -0.2928001 0.041014045 -0.15654324, -0.29250011 0.041192278 -0.15630163, -0.2928001 0.039558321 -0.15523024, -0.29250017 0.039780125 -0.15502812, -0.29280013 0.038386866 -0.15365838, -0.29250014 0.038643733 -0.15350352, -0.29280013 0.037544414 -0.15188842, -0.29250008 0.037826642 -0.15178655, -0.29280007 0.037063569 -0.14998774, -0.29250002 0.037360266 -0.14994301, -0.29280013 0.036962703 -0.14803009, -0.29250008 0.037262365 -0.14804412, -0.29280025 0.053950533 -0.1486273, -0.2925002 0.054250553 -0.1486329, -0.2925002 0.054097757 -0.14700525, -0.29280025 0.053804055 -0.14706658, -0.2925002 0.053586751 -0.14545251, -0.29280031 0.053314134 -0.1455778, -0.29250005 0.052742884 -0.14405249, -0.29280019 0.052504927 -0.14423503, -0.29250014 0.051608801 -0.14287506, -0.29280019 0.051417381 -0.14310621, -0.29250023 0.050241187 -0.14197989, -0.29280022 0.050105974 -0.14224772, -0.2925002 0.048708513 -0.14141117, -0.29280019 0.048636362 -0.14170255, -0.2925002 0.047087818 -0.14119814, -0.29280007 0.04708223 -0.14149795, -0.29250014 0.045460269 -0.14135067, -0.29280007 0.045521632 -0.14164446, -0.2925002 0.043907508 -0.14186178, -0.29280013 0.044032663 -0.14213435, -0.29250014 0.04250747 -0.1427056, -0.29280019 0.042690143 -0.14294352, -0.29250023 0.041330263 -0.14383982, -0.29280016 0.041561276 -0.14403121, -0.29250005 0.040434882 -0.14520745, -0.2928001 0.04070279 -0.14534248, -0.35520026 0.040702328 -0.14534269, -0.35550025 0.040434539 -0.14520739, -0.35550019 0.041329846 -0.14383958, -0.35520029 0.041560873 -0.14403106, -0.35550013 0.042507097 -0.1427056, -0.35520023 0.042689681 -0.14294361, -0.35550022 0.043907121 -0.14186178, -0.35520029 0.044032231 -0.14213456, -0.35550028 0.045459822 -0.14135073, -0.35520023 0.04552114 -0.14164458, -0.35550007 0.047087267 -0.14119805, -0.35520026 0.047081828 -0.14149795, -0.35550019 0.048708171 -0.14141132, -0.35520011 0.04863587 -0.1417024, -0.35550031 0.050240755 -0.14197989, -0.35520032 0.050105467 -0.14224772, -0.35550034 0.051608473 -0.14287506, -0.35520035 0.051417008 -0.14310612, -0.35550016 0.052742541 -0.14405255, -0.35520023 0.052504584 -0.14423524, -0.35550022 0.053586364 -0.14545242, -0.35520017 0.053313613 -0.14557774, -0.35550022 0.05409728 -0.14700525, -0.35520029 0.053803682 -0.14706658, -0.35550028 0.054250121 -0.14863281, -0.35520017 0.053950012 -0.14862733, -0.30166522 0.051909953 -0.1571811, -0.30277738 0.05157271 -0.1573651, -0.34866524 0.051909655 -0.15718101, -0.30388024 0.051000267 -0.15764053, -0.34977728 0.051572233 -0.15736519, -0.30487221 0.050242692 -0.15793966, -0.35088021 0.05099991 -0.15764053, -0.30573305 0.04933393 -0.1582088, -0.30645394 0.048287466 -0.15840717, -0.35273305 0.049333602 -0.1582088, -0.35187235 0.050242335 -0.15793951, -0.3070063 0.047133818 -0.15849511, -0.30736387 0.045903027 -0.15844153, -0.35400638 0.04713352 -0.15849517, -0.35345408 0.048287079 -0.15840696, -0.30749941 0.044644073 -0.15822689, -0.35436386 0.045902759 -0.15844174, -0.35449946 0.044643819 -0.15822695, -0.30740222 0.043428987 -0.15785585, -0.30707958 0.042295396 -0.15734656, -0.35440236 0.043428853 -0.1578557, -0.30655846 0.041294232 -0.15674268, -0.35407972 0.042295218 -0.15734662, -0.35355854 0.041293964 -0.15674268, -0.30586717 0.040439889 -0.15608604, -0.30502996 0.039736763 -0.15542097, -0.30406192 0.039182156 -0.15479238, -0.35286713 0.040439621 -0.15608616, -0.35202998 0.03973642 -0.15542097, -0.30297214 0.038776547 -0.15425585, -0.30177099 0.038524777 -0.15388067, -0.35106185 0.039181739 -0.15479229, -0.34877101 0.038524494 -0.15388067, -0.34997216 0.038776264 -0.15425585 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 0, 3, 1, -1, 4, 2, 5, -1, 4, 0, 2, -1, 6, 5, 7, -1, 6, 4, 5, -1, 8, 7, 9, -1, 8, 6, 7, -1, 10, 9, 11, -1, 10, 8, 9, -1, 12, 11, 13, -1, 12, 10, 11, -1, 14, 13, 15, -1, 14, 12, 13, -1, 16, 15, 17, -1, 16, 14, 15, -1, 18, 17, 19, -1, 18, 19, 20, -1, 18, 16, 17, -1, 21, 20, 22, -1, 21, 18, 20, -1, 23, 22, 24, -1, 23, 21, 22, -1, 25, 24, 26, -1, 25, 23, 24, -1, 27, 26, 28, -1, 27, 25, 26, -1, 29, 28, 30, -1, 29, 27, 28, -1, 31, 29, 30, -1, 31, 30, 32, -1, 33, 31, 32, -1, 33, 32, 34, -1, 35, 33, 34, -1, 35, 34, 36, -1, 37, 35, 36, -1, 37, 36, 38, -1, 39, 40, 41, -1, 39, 42, 40, -1, 43, 41, 44, -1, 43, 39, 41, -1, 45, 44, 46, -1, 45, 43, 44, -1, 47, 46, 48, -1, 47, 45, 46, -1, 49, 48, 50, -1, 49, 47, 48, -1, 51, 50, 52, -1, 51, 49, 50, -1, 53, 52, 54, -1, 53, 51, 52, -1, 55, 54, 56, -1, 55, 53, 54, -1, 57, 56, 58, -1, 57, 58, 59, -1, 57, 55, 56, -1, 60, 59, 61, -1, 60, 57, 59, -1, 62, 61, 63, -1, 62, 60, 61, -1, 64, 63, 65, -1, 64, 62, 63, -1, 66, 65, 67, -1, 66, 64, 65, -1, 68, 67, 69, -1, 68, 66, 67, -1, 70, 68, 69, -1, 70, 69, 71, -1, 72, 70, 71, -1, 72, 71, 73, -1, 74, 72, 73, -1, 74, 73, 75, -1, 76, 74, 75, -1, 76, 75, 77, -1, 78, 79, 80, -1, 81, 80, 82, -1, 81, 78, 80, -1, 83, 82, 84, -1, 83, 81, 82, -1, 85, 84, 86, -1, 85, 83, 84, -1, 87, 86, 88, -1, 87, 85, 86, -1, 89, 88, 90, -1, 89, 87, 88, -1, 91, 90, 92, -1, 91, 89, 90, -1, 93, 92, 94, -1, 93, 91, 92, -1, 95, 94, 96, -1, 95, 93, 94, -1, 97, 96, 98, -1, 97, 95, 96, -1, 99, 98, 100, -1, 99, 97, 98, -1, 101, 100, 102, -1, 101, 99, 100, -1, 103, 102, 104, -1, 103, 101, 102, -1, 105, 104, 106, -1, 105, 103, 104, -1, 107, 106, 108, -1, 107, 105, 106, -1, 109, 108, 110, -1, 109, 107, 108, -1, 111, 109, 110, -1, 112, 113, 114, -1, 114, 113, 115, -1, 115, 116, 117, -1, 113, 116, 115, -1, 117, 118, 119, -1, 116, 118, 117, -1, 119, 120, 121, -1, 118, 120, 119, -1, 121, 122, 123, -1, 120, 122, 121, -1, 123, 124, 125, -1, 122, 124, 123, -1, 125, 126, 127, -1, 124, 126, 125, -1, 128, 129, 130, -1, 127, 129, 128, -1, 126, 129, 127, -1, 129, 131, 130, -1, 130, 132, 133, -1, 131, 132, 130, -1, 133, 134, 135, -1, 132, 134, 133, -1, 135, 136, 137, -1, 134, 136, 135, -1, 137, 138, 139, -1, 136, 138, 137, -1, 139, 140, 141, -1, 138, 140, 139, -1, 142, 143, 112, -1, 112, 143, 113, -1, 113, 144, 116, -1, 143, 144, 113, -1, 116, 145, 118, -1, 144, 145, 116, -1, 118, 146, 120, -1, 145, 146, 118, -1, 120, 147, 122, -1, 146, 147, 120, -1, 122, 148, 124, -1, 147, 148, 122, -1, 124, 149, 126, -1, 148, 149, 124, -1, 126, 150, 129, -1, 149, 150, 126, -1, 129, 151, 131, -1, 150, 151, 129, -1, 131, 152, 132, -1, 151, 152, 131, -1, 132, 153, 134, -1, 152, 153, 132, -1, 134, 154, 136, -1, 153, 154, 134, -1, 136, 155, 138, -1, 154, 155, 136, -1, 155, 140, 138, -1, 155, 156, 140, -1, 157, 158, 141, -1, 141, 158, 139, -1, 139, 159, 137, -1, 158, 159, 139, -1, 137, 160, 135, -1, 159, 160, 137, -1, 135, 161, 133, -1, 160, 161, 135, -1, 133, 162, 130, -1, 161, 162, 133, -1, 130, 163, 128, -1, 162, 163, 130, -1, 128, 164, 127, -1, 163, 164, 128, -1, 127, 165, 125, -1, 164, 165, 127, -1, 125, 166, 123, -1, 165, 166, 125, -1, 123, 167, 121, -1, 166, 167, 123, -1, 121, 168, 119, -1, 167, 168, 121, -1, 119, 169, 117, -1, 168, 169, 119, -1, 117, 170, 115, -1, 169, 170, 117, -1, 115, 171, 114, -1, 170, 171, 115, -1, 172, 79, 173, -1, 80, 79, 172, -1, 174, 80, 172, -1, 82, 80, 174, -1, 175, 82, 174, -1, 84, 82, 175, -1, 176, 84, 175, -1, 86, 84, 176, -1, 177, 86, 176, -1, 88, 86, 177, -1, 178, 88, 177, -1, 90, 88, 178, -1, 179, 90, 178, -1, 92, 90, 179, -1, 180, 92, 179, -1, 94, 92, 180, -1, 181, 94, 180, -1, 96, 94, 181, -1, 182, 96, 181, -1, 98, 96, 182, -1, 183, 98, 182, -1, 100, 98, 183, -1, 184, 100, 183, -1, 102, 100, 184, -1, 185, 102, 184, -1, 104, 102, 185, -1, 186, 104, 185, -1, 106, 104, 186, -1, 187, 106, 186, -1, 108, 106, 187, -1, 188, 108, 187, -1, 110, 108, 188, -1, 189, 111, 190, -1, 109, 111, 189, -1, 191, 109, 189, -1, 107, 109, 191, -1, 192, 107, 191, -1, 105, 107, 192, -1, 193, 105, 192, -1, 103, 105, 193, -1, 194, 103, 193, -1, 101, 103, 194, -1, 195, 101, 194, -1, 99, 101, 195, -1, 196, 99, 195, -1, 97, 99, 196, -1, 197, 97, 196, -1, 95, 97, 197, -1, 198, 95, 197, -1, 93, 95, 198, -1, 199, 93, 198, -1, 91, 93, 199, -1, 200, 91, 199, -1, 89, 91, 200, -1, 201, 89, 200, -1, 87, 89, 201, -1, 202, 87, 201, -1, 85, 87, 202, -1, 203, 85, 202, -1, 83, 85, 203, -1, 204, 83, 203, -1, 81, 83, 204, -1, 205, 81, 204, -1, 78, 81, 205, -1, 206, 207, 208, -1, 209, 207, 206, -1, 210, 209, 206, -1, 211, 209, 210, -1, 212, 211, 210, -1, 213, 211, 212, -1, 214, 213, 212, -1, 215, 213, 214, -1, 216, 215, 214, -1, 217, 215, 216, -1, 218, 217, 216, -1, 219, 217, 218, -1, 220, 219, 218, -1, 221, 219, 220, -1, 222, 221, 220, -1, 223, 221, 222, -1, 224, 223, 222, -1, 225, 223, 224, -1, 226, 225, 224, -1, 227, 225, 226, -1, 228, 227, 226, -1, 229, 227, 228, -1, 230, 229, 228, -1, 231, 229, 230, -1, 232, 231, 230, -1, 233, 231, 232, -1, 234, 233, 232, -1, 235, 233, 234, -1, 236, 235, 234, -1, 237, 235, 236, -1, 238, 237, 236, -1, 239, 237, 238, -1, 240, 241, 242, -1, 243, 241, 240, -1, 244, 243, 240, -1, 245, 243, 244, -1, 246, 245, 244, -1, 247, 245, 246, -1, 248, 247, 246, -1, 249, 247, 248, -1, 250, 249, 248, -1, 251, 249, 250, -1, 252, 251, 250, -1, 253, 251, 252, -1, 254, 253, 252, -1, 255, 253, 254, -1, 256, 255, 254, -1, 257, 255, 256, -1, 258, 257, 256, -1, 259, 257, 258, -1, 260, 259, 258, -1, 261, 259, 260, -1, 262, 261, 260, -1, 263, 261, 262, -1, 264, 263, 262, -1, 265, 263, 264, -1, 266, 265, 264, -1, 267, 265, 266, -1, 268, 267, 266, -1, 269, 267, 268, -1, 270, 269, 268, -1, 271, 269, 270, -1, 272, 271, 270, -1, 273, 271, 272, -1, 274, 275, 276, -1, 276, 275, 277, -1, 277, 278, 279, -1, 275, 278, 277, -1, 279, 280, 281, -1, 278, 280, 279, -1, 281, 282, 283, -1, 280, 282, 281, -1, 283, 284, 285, -1, 282, 284, 283, -1, 285, 286, 287, -1, 284, 286, 285, -1, 287, 288, 289, -1, 286, 288, 287, -1, 289, 290, 291, -1, 288, 290, 289, -1, 291, 292, 293, -1, 290, 292, 291, -1, 293, 294, 295, -1, 292, 294, 293, -1, 295, 296, 297, -1, 294, 296, 295, -1, 297, 298, 299, -1, 296, 298, 297, -1, 299, 300, 301, -1, 298, 300, 299, -1, 301, 302, 303, -1, 300, 302, 301, -1, 304, 305, 306, -1, 304, 307, 305, -1, 307, 308, 305, -1, 307, 309, 308, -1, 309, 310, 308, -1, 309, 311, 310, -1, 311, 312, 310, -1, 311, 313, 312, -1, 313, 314, 312, -1, 313, 315, 314, -1, 315, 316, 314, -1, 315, 317, 316, -1, 317, 318, 316, -1, 317, 319, 318, -1, 319, 320, 318, -1, 319, 321, 320, -1, 321, 322, 320, -1, 321, 323, 322, -1, 323, 324, 322, -1, 323, 325, 324, -1, 325, 326, 324, -1, 325, 327, 326, -1, 327, 328, 326, -1, 327, 329, 328, -1, 329, 330, 328, -1, 329, 331, 330, -1, 331, 332, 330, -1, 331, 333, 332, -1, 276, 277, 332, -1, 332, 277, 330, -1, 330, 279, 328, -1, 277, 279, 330, -1, 326, 281, 324, -1, 328, 281, 326, -1, 279, 281, 328, -1, 281, 283, 324, -1, 322, 285, 320, -1, 324, 285, 322, -1, 283, 285, 324, -1, 320, 287, 318, -1, 285, 287, 320, -1, 287, 289, 318, -1, 316, 291, 314, -1, 318, 291, 316, -1, 289, 291, 318, -1, 314, 293, 312, -1, 291, 293, 314, -1, 312, 295, 310, -1, 293, 295, 312, -1, 295, 297, 310, -1, 310, 299, 308, -1, 297, 299, 310, -1, 308, 301, 305, -1, 299, 301, 308, -1, 305, 303, 306, -1, 301, 303, 305, -1, 237, 239, 241, -1, 237, 241, 243, -1, 235, 237, 243, -1, 235, 243, 245, -1, 76, 247, 249, -1, 74, 76, 249, -1, 233, 235, 245, -1, 233, 245, 247, -1, 72, 74, 249, -1, 70, 72, 249, -1, 251, 70, 249, -1, 37, 76, 334, -1, 37, 247, 76, -1, 37, 233, 247, -1, 35, 334, 335, -1, 35, 37, 334, -1, 231, 233, 37, -1, 231, 37, 336, -1, 337, 231, 336, -1, 33, 335, 338, -1, 33, 35, 335, -1, 66, 68, 251, -1, 339, 231, 337, -1, 31, 338, 340, -1, 31, 33, 338, -1, 253, 66, 251, -1, 341, 231, 339, -1, 29, 340, 342, -1, 29, 31, 340, -1, 229, 231, 341, -1, 27, 342, 343, -1, 27, 29, 342, -1, 62, 64, 253, -1, 255, 62, 253, -1, 344, 229, 345, -1, 25, 343, 346, -1, 25, 27, 343, -1, 227, 229, 344, -1, 23, 346, 347, -1, 23, 25, 346, -1, 257, 60, 255, -1, 348, 227, 349, -1, 225, 227, 348, -1, 21, 347, 350, -1, 21, 23, 347, -1, 55, 57, 257, -1, 259, 55, 257, -1, 18, 21, 350, -1, 18, 351, 352, -1, 18, 350, 351, -1, 223, 225, 353, -1, 16, 352, 354, -1, 16, 18, 352, -1, 261, 51, 53, -1, 261, 53, 259, -1, 355, 223, 356, -1, 221, 223, 355, -1, 14, 354, 357, -1, 14, 16, 354, -1, 263, 49, 261, -1, 47, 49, 263, -1, 12, 357, 358, -1, 12, 14, 357, -1, 219, 359, 360, -1, 219, 221, 359, -1, 10, 358, 361, -1, 10, 12, 358, -1, 265, 43, 45, -1, 265, 45, 263, -1, 39, 43, 265, -1, 8, 361, 362, -1, 8, 10, 361, -1, 42, 39, 265, -1, 217, 363, 364, -1, 217, 219, 363, -1, 6, 362, 365, -1, 6, 8, 362, -1, 4, 365, 366, -1, 4, 6, 365, -1, 267, 42, 265, -1, 0, 366, 42, -1, 0, 4, 366, -1, 3, 0, 42, -1, 215, 217, 367, -1, 215, 368, 3, -1, 215, 369, 368, -1, 215, 367, 369, -1, 213, 215, 3, -1, 213, 3, 42, -1, 213, 42, 267, -1, 211, 213, 267, -1, 211, 267, 269, -1, 209, 211, 269, -1, 209, 269, 271, -1, 207, 209, 271, -1, 207, 271, 273, -1, 68, 70, 251, -1, 64, 66, 253, -1, 60, 62, 255, -1, 57, 60, 257, -1, 53, 55, 259, -1, 49, 51, 261, -1, 45, 47, 263, -1, 364, 367, 217, -1, 360, 363, 219, -1, 355, 359, 221, -1, 353, 356, 223, -1, 348, 353, 225, -1, 344, 349, 227, -1, 341, 345, 229, -1, 370, 207, 273, -1, 370, 273, 371, -1, 372, 371, 373, -1, 372, 370, 371, -1, 374, 373, 375, -1, 374, 372, 373, -1, 376, 375, 377, -1, 376, 374, 375, -1, 378, 377, 379, -1, 378, 376, 377, -1, 380, 379, 381, -1, 380, 378, 379, -1, 382, 381, 383, -1, 382, 380, 381, -1, 384, 383, 385, -1, 384, 382, 383, -1, 386, 385, 387, -1, 386, 384, 385, -1, 388, 387, 389, -1, 388, 386, 387, -1, 390, 389, 391, -1, 390, 388, 389, -1, 392, 391, 393, -1, 392, 390, 391, -1, 394, 393, 395, -1, 394, 392, 393, -1, 396, 395, 397, -1, 396, 394, 395, -1, 398, 397, 399, -1, 398, 396, 397, -1, 239, 398, 399, -1, 239, 399, 241, -1, 329, 327, 400, -1, 401, 329, 400, -1, 252, 250, 402, -1, 403, 252, 402, -1, 331, 329, 401, -1, 404, 333, 331, -1, 404, 331, 401, -1, 311, 405, 406, -1, 254, 403, 407, -1, 254, 252, 403, -1, 313, 406, 408, -1, 313, 311, 406, -1, 309, 409, 405, -1, 309, 405, 311, -1, 256, 254, 407, -1, 315, 408, 410, -1, 272, 333, 404, -1, 315, 313, 408, -1, 307, 411, 409, -1, 307, 409, 309, -1, 317, 410, 412, -1, 317, 315, 410, -1, 270, 413, 333, -1, 270, 333, 272, -1, 319, 412, 414, -1, 258, 407, 415, -1, 319, 414, 416, -1, 319, 317, 412, -1, 258, 256, 407, -1, 268, 417, 413, -1, 268, 413, 270, -1, 304, 242, 411, -1, 304, 240, 242, -1, 304, 411, 307, -1, 260, 415, 418, -1, 419, 240, 304, -1, 260, 258, 415, -1, 266, 420, 417, -1, 266, 417, 268, -1, 321, 319, 416, -1, 421, 321, 416, -1, 262, 418, 422, -1, 244, 240, 419, -1, 262, 260, 418, -1, 264, 422, 420, -1, 264, 420, 266, -1, 423, 244, 419, -1, 264, 262, 422, -1, 323, 321, 421, -1, 424, 323, 421, -1, 246, 244, 423, -1, 425, 246, 423, -1, 325, 323, 424, -1, 426, 325, 424, -1, 248, 246, 425, -1, 427, 248, 425, -1, 327, 325, 426, -1, 400, 327, 426, -1, 250, 248, 427, -1, 402, 250, 427, -1, 228, 226, 428, -1, 278, 275, 429, -1, 226, 430, 428, -1, 274, 431, 275, -1, 275, 431, 429, -1, 430, 224, 432, -1, 226, 224, 430, -1, 433, 294, 434, -1, 435, 296, 433, -1, 433, 296, 294, -1, 274, 208, 431, -1, 434, 292, 436, -1, 294, 292, 434, -1, 224, 222, 432, -1, 437, 298, 435, -1, 435, 298, 296, -1, 436, 290, 438, -1, 292, 290, 436, -1, 439, 300, 437, -1, 440, 206, 274, -1, 437, 300, 298, -1, 274, 206, 208, -1, 432, 220, 441, -1, 442, 288, 443, -1, 438, 288, 442, -1, 222, 220, 432, -1, 290, 288, 438, -1, 444, 210, 440, -1, 440, 210, 206, -1, 238, 302, 439, -1, 236, 302, 238, -1, 441, 218, 445, -1, 439, 302, 300, -1, 220, 218, 441, -1, 288, 286, 443, -1, 446, 212, 444, -1, 236, 447, 302, -1, 444, 212, 210, -1, 286, 448, 443, -1, 445, 216, 449, -1, 218, 216, 445, -1, 449, 214, 446, -1, 236, 234, 447, -1, 446, 214, 212, -1, 286, 284, 448, -1, 216, 214, 449, -1, 234, 450, 447, -1, 284, 451, 448, -1, 234, 232, 450, -1, 284, 282, 451, -1, 232, 452, 450, -1, 282, 453, 451, -1, 232, 230, 452, -1, 282, 280, 453, -1, 230, 454, 452, -1, 280, 455, 453, -1, 230, 228, 454, -1, 280, 278, 455, -1, 228, 428, 454, -1, 278, 429, 455, -1, 303, 456, 306, -1, 306, 456, 457, -1, 457, 458, 459, -1, 456, 458, 457, -1, 460, 461, 462, -1, 459, 461, 460, -1, 458, 461, 459, -1, 461, 463, 462, -1, 464, 465, 466, -1, 462, 465, 464, -1, 463, 465, 462, -1, 466, 467, 468, -1, 465, 467, 466, -1, 467, 469, 468, -1, 470, 471, 472, -1, 468, 471, 470, -1, 469, 471, 468, -1, 472, 473, 474, -1, 471, 473, 472, -1, 474, 475, 476, -1, 473, 475, 474, -1, 475, 477, 476, -1, 476, 478, 479, -1, 477, 478, 476, -1, 479, 480, 481, -1, 478, 480, 479, -1, 481, 276, 332, -1, 480, 276, 481, -1, 333, 413, 332, -1, 332, 413, 481, -1, 481, 417, 479, -1, 413, 417, 481, -1, 479, 420, 476, -1, 417, 420, 479, -1, 476, 422, 474, -1, 420, 422, 476, -1, 474, 418, 472, -1, 422, 418, 474, -1, 472, 415, 470, -1, 418, 415, 472, -1, 470, 407, 468, -1, 415, 407, 470, -1, 468, 403, 466, -1, 407, 403, 468, -1, 466, 402, 464, -1, 403, 402, 466, -1, 464, 427, 462, -1, 402, 427, 464, -1, 462, 425, 460, -1, 427, 425, 462, -1, 460, 423, 459, -1, 425, 423, 460, -1, 459, 419, 457, -1, 423, 419, 459, -1, 457, 304, 306, -1, 419, 304, 457, -1, 302, 456, 303, -1, 302, 447, 456, -1, 447, 458, 456, -1, 447, 450, 458, -1, 450, 461, 458, -1, 450, 452, 461, -1, 452, 463, 461, -1, 452, 454, 463, -1, 454, 465, 463, -1, 454, 428, 465, -1, 428, 467, 465, -1, 428, 430, 467, -1, 430, 469, 467, -1, 430, 432, 469, -1, 432, 471, 469, -1, 432, 441, 471, -1, 441, 473, 471, -1, 441, 445, 473, -1, 445, 475, 473, -1, 445, 449, 475, -1, 449, 477, 475, -1, 449, 446, 477, -1, 446, 478, 477, -1, 446, 444, 478, -1, 444, 480, 478, -1, 444, 440, 480, -1, 440, 276, 480, -1, 440, 274, 276, -1, 404, 273, 272, -1, 371, 273, 404, -1, 401, 371, 404, -1, 373, 371, 401, -1, 400, 373, 401, -1, 375, 373, 400, -1, 426, 375, 400, -1, 377, 375, 426, -1, 424, 377, 426, -1, 379, 377, 424, -1, 421, 379, 424, -1, 381, 379, 421, -1, 416, 381, 421, -1, 383, 381, 416, -1, 414, 383, 416, -1, 385, 383, 414, -1, 412, 385, 414, -1, 387, 385, 412, -1, 410, 387, 412, -1, 389, 387, 410, -1, 408, 389, 410, -1, 391, 389, 408, -1, 406, 391, 408, -1, 393, 391, 406, -1, 405, 393, 406, -1, 395, 393, 405, -1, 409, 395, 405, -1, 397, 395, 409, -1, 411, 397, 409, -1, 399, 397, 411, -1, 242, 399, 411, -1, 241, 399, 242, -1, 439, 239, 238, -1, 398, 239, 439, -1, 437, 398, 439, -1, 396, 398, 437, -1, 435, 396, 437, -1, 394, 396, 435, -1, 433, 394, 435, -1, 392, 394, 433, -1, 434, 392, 433, -1, 390, 392, 434, -1, 436, 390, 434, -1, 388, 390, 436, -1, 438, 388, 436, -1, 386, 388, 438, -1, 442, 386, 438, -1, 384, 386, 442, -1, 443, 384, 442, -1, 382, 384, 443, -1, 448, 382, 443, -1, 380, 382, 448, -1, 451, 380, 448, -1, 378, 380, 451, -1, 453, 378, 451, -1, 376, 378, 453, -1, 455, 376, 453, -1, 374, 376, 455, -1, 429, 374, 455, -1, 372, 374, 429, -1, 431, 372, 429, -1, 370, 372, 431, -1, 208, 370, 431, -1, 207, 370, 208, -1, 482, 78, 205, -1, 483, 78, 482, -1, 484, 483, 482, -1, 485, 483, 484, -1, 486, 485, 484, -1, 487, 485, 486, -1, 488, 487, 486, -1, 489, 487, 488, -1, 490, 489, 488, -1, 491, 489, 490, -1, 492, 491, 490, -1, 493, 491, 492, -1, 494, 493, 492, -1, 495, 493, 494, -1, 496, 495, 494, -1, 497, 495, 496, -1, 498, 497, 496, -1, 499, 497, 498, -1, 500, 499, 498, -1, 501, 499, 500, -1, 502, 501, 500, -1, 503, 501, 502, -1, 504, 503, 502, -1, 505, 503, 504, -1, 506, 505, 504, -1, 507, 505, 506, -1, 508, 507, 506, -1, 509, 507, 508, -1, 510, 509, 508, -1, 511, 509, 510, -1, 190, 511, 510, -1, 111, 511, 190, -1, 512, 110, 188, -1, 512, 188, 513, -1, 514, 513, 515, -1, 514, 512, 513, -1, 516, 515, 517, -1, 516, 514, 515, -1, 518, 517, 519, -1, 518, 516, 517, -1, 520, 519, 521, -1, 520, 518, 519, -1, 522, 521, 523, -1, 522, 520, 521, -1, 524, 523, 525, -1, 524, 522, 523, -1, 526, 525, 527, -1, 526, 524, 525, -1, 528, 527, 529, -1, 528, 526, 527, -1, 530, 529, 531, -1, 530, 528, 529, -1, 532, 531, 533, -1, 532, 530, 531, -1, 534, 533, 535, -1, 534, 532, 533, -1, 536, 535, 537, -1, 536, 534, 535, -1, 538, 537, 539, -1, 538, 536, 537, -1, 540, 539, 541, -1, 540, 538, 539, -1, 79, 541, 173, -1, 79, 540, 541, -1, 171, 542, 114, -1, 171, 543, 542, -1, 542, 544, 545, -1, 543, 544, 542, -1, 545, 546, 547, -1, 544, 546, 545, -1, 547, 548, 549, -1, 546, 548, 547, -1, 549, 550, 551, -1, 548, 550, 549, -1, 551, 552, 553, -1, 550, 552, 551, -1, 553, 554, 555, -1, 552, 554, 553, -1, 555, 556, 557, -1, 554, 556, 555, -1, 557, 558, 559, -1, 556, 558, 557, -1, 559, 560, 561, -1, 558, 560, 559, -1, 561, 562, 563, -1, 560, 562, 561, -1, 563, 564, 565, -1, 562, 564, 563, -1, 565, 566, 567, -1, 564, 566, 565, -1, 567, 157, 141, -1, 566, 157, 567, -1, 156, 568, 140, -1, 140, 568, 569, -1, 568, 570, 569, -1, 568, 571, 570, -1, 570, 572, 573, -1, 571, 572, 570, -1, 572, 574, 573, -1, 572, 575, 574, -1, 575, 576, 574, -1, 575, 577, 576, -1, 576, 578, 579, -1, 577, 578, 576, -1, 578, 580, 579, -1, 578, 581, 580, -1, 581, 582, 580, -1, 581, 583, 582, -1, 583, 584, 582, -1, 583, 585, 584, -1, 585, 586, 584, -1, 585, 587, 586, -1, 586, 588, 589, -1, 587, 588, 586, -1, 588, 590, 589, -1, 588, 591, 590, -1, 590, 592, 593, -1, 591, 592, 590, -1, 593, 142, 112, -1, 592, 142, 593, -1, 140, 569, 141, -1, 141, 569, 567, -1, 567, 570, 565, -1, 569, 570, 567, -1, 565, 573, 563, -1, 570, 573, 565, -1, 563, 574, 561, -1, 573, 574, 563, -1, 561, 576, 559, -1, 574, 576, 561, -1, 559, 579, 557, -1, 576, 579, 559, -1, 557, 580, 555, -1, 579, 580, 557, -1, 555, 582, 553, -1, 580, 582, 555, -1, 553, 584, 551, -1, 582, 584, 553, -1, 551, 586, 549, -1, 584, 586, 551, -1, 549, 589, 547, -1, 586, 589, 549, -1, 547, 590, 545, -1, 589, 590, 547, -1, 545, 593, 542, -1, 590, 593, 545, -1, 542, 112, 114, -1, 593, 112, 542, -1, 195, 194, 585, -1, 484, 154, 486, -1, 155, 154, 484, -1, 583, 195, 585, -1, 196, 583, 581, -1, 196, 195, 583, -1, 146, 504, 502, -1, 482, 156, 155, -1, 482, 155, 484, -1, 145, 506, 504, -1, 145, 504, 146, -1, 147, 502, 500, -1, 147, 146, 502, -1, 197, 196, 581, -1, 144, 508, 506, -1, 144, 506, 145, -1, 205, 156, 482, -1, 148, 500, 498, -1, 148, 147, 500, -1, 143, 510, 508, -1, 143, 508, 144, -1, 149, 498, 496, -1, 149, 496, 494, -1, 149, 148, 498, -1, 198, 581, 578, -1, 198, 197, 581, -1, 204, 568, 156, -1, 142, 190, 510, -1, 204, 156, 205, -1, 142, 189, 190, -1, 142, 510, 143, -1, 199, 578, 577, -1, 150, 149, 494, -1, 199, 198, 578, -1, 592, 189, 142, -1, 203, 571, 568, -1, 191, 189, 592, -1, 203, 568, 204, -1, 492, 150, 494, -1, 200, 577, 575, -1, 200, 199, 577, -1, 151, 150, 492, -1, 202, 572, 571, -1, 202, 571, 203, -1, 591, 191, 592, -1, 201, 575, 572, -1, 192, 191, 591, -1, 201, 572, 202, -1, 201, 200, 575, -1, 490, 151, 492, -1, 152, 151, 490, -1, 588, 192, 591, -1, 193, 192, 588, -1, 488, 152, 490, -1, 153, 152, 488, -1, 587, 193, 588, -1, 194, 193, 587, -1, 486, 153, 488, -1, 154, 153, 486, -1, 585, 194, 587, -1, 159, 539, 537, -1, 183, 182, 550, -1, 182, 552, 550, -1, 159, 158, 539, -1, 517, 168, 519, -1, 157, 541, 158, -1, 158, 541, 539, -1, 552, 181, 554, -1, 519, 167, 521, -1, 182, 181, 552, -1, 168, 167, 519, -1, 515, 169, 517, -1, 517, 169, 168, -1, 521, 166, 523, -1, 157, 173, 541, -1, 167, 166, 521, -1, 181, 180, 554, -1, 513, 170, 515, -1, 515, 170, 169, -1, 523, 165, 525, -1, 166, 165, 523, -1, 566, 172, 157, -1, 157, 172, 173, -1, 188, 171, 513, -1, 187, 171, 188, -1, 554, 179, 556, -1, 180, 179, 554, -1, 513, 171, 170, -1, 527, 164, 529, -1, 564, 174, 566, -1, 525, 164, 527, -1, 165, 164, 525, -1, 566, 174, 172, -1, 187, 543, 171, -1, 556, 178, 558, -1, 179, 178, 556, -1, 164, 163, 529, -1, 562, 175, 564, -1, 163, 531, 529, -1, 564, 175, 174, -1, 187, 186, 543, -1, 558, 177, 560, -1, 178, 177, 558, -1, 186, 544, 543, -1, 560, 176, 562, -1, 562, 176, 175, -1, 163, 162, 531, -1, 177, 176, 560, -1, 162, 533, 531, -1, 186, 185, 544, -1, 185, 546, 544, -1, 162, 161, 533, -1, 161, 535, 533, -1, 185, 184, 546, -1, 184, 548, 546, -1, 161, 160, 535, -1, 160, 537, 535, -1, 184, 183, 548, -1, 183, 550, 548, -1, 160, 159, 537, -1, 511, 111, 110, -1, 511, 110, 512, -1, 509, 512, 514, -1, 509, 511, 512, -1, 40, 516, 518, -1, 41, 40, 518, -1, 507, 514, 516, -1, 507, 509, 514, -1, 44, 41, 518, -1, 46, 44, 518, -1, 520, 46, 518, -1, 1, 40, 594, -1, 1, 516, 40, -1, 1, 507, 516, -1, 2, 594, 595, -1, 2, 1, 594, -1, 505, 507, 1, -1, 505, 1, 596, -1, 5, 595, 597, -1, 5, 2, 595, -1, 598, 505, 596, -1, 50, 48, 520, -1, 7, 597, 599, -1, 7, 5, 597, -1, 600, 505, 598, -1, 522, 50, 520, -1, 9, 599, 601, -1, 9, 7, 599, -1, 503, 505, 600, -1, 54, 52, 522, -1, 11, 601, 602, -1, 11, 9, 601, -1, 603, 503, 604, -1, 524, 54, 522, -1, 13, 602, 605, -1, 13, 11, 602, -1, 501, 503, 603, -1, 15, 605, 606, -1, 15, 13, 605, -1, 526, 58, 56, -1, 526, 56, 524, -1, 607, 501, 608, -1, 17, 15, 606, -1, 17, 606, 609, -1, 499, 501, 607, -1, 528, 59, 526, -1, 19, 17, 609, -1, 497, 499, 610, -1, 497, 610, 611, -1, 20, 19, 609, -1, 20, 609, 612, -1, 530, 61, 528, -1, 530, 63, 61, -1, 22, 20, 612, -1, 22, 612, 613, -1, 495, 497, 614, -1, 24, 22, 613, -1, 24, 613, 615, -1, 532, 65, 530, -1, 532, 67, 65, -1, 493, 616, 617, -1, 493, 495, 616, -1, 26, 24, 615, -1, 26, 615, 618, -1, 28, 26, 618, -1, 28, 618, 619, -1, 534, 69, 532, -1, 534, 71, 69, -1, 534, 73, 71, -1, 75, 73, 534, -1, 77, 75, 534, -1, 30, 619, 620, -1, 30, 28, 619, -1, 491, 621, 622, -1, 491, 493, 621, -1, 32, 30, 620, -1, 32, 620, 623, -1, 536, 77, 534, -1, 34, 32, 623, -1, 34, 623, 624, -1, 36, 34, 624, -1, 36, 624, 77, -1, 38, 36, 77, -1, 489, 491, 625, -1, 489, 626, 38, -1, 489, 627, 626, -1, 489, 625, 627, -1, 487, 38, 77, -1, 487, 77, 536, -1, 487, 489, 38, -1, 485, 536, 538, -1, 485, 487, 536, -1, 483, 538, 540, -1, 483, 485, 538, -1, 78, 540, 79, -1, 78, 483, 540, -1, 622, 625, 491, -1, 617, 621, 493, -1, 614, 616, 495, -1, 611, 614, 497, -1, 607, 610, 499, -1, 603, 608, 501, -1, 600, 604, 503, -1, 48, 46, 520, -1, 52, 50, 522, -1, 56, 54, 524, -1, 59, 58, 526, -1, 61, 59, 528, -1, 65, 63, 530, -1, 69, 67, 532, -1, 334, 76, 77, -1, 334, 77, 624, -1, 335, 624, 623, -1, 335, 334, 624, -1, 338, 623, 620, -1, 338, 335, 623, -1, 340, 620, 619, -1, 340, 338, 620, -1, 342, 619, 618, -1, 342, 340, 619, -1, 343, 618, 615, -1, 343, 342, 618, -1, 346, 615, 613, -1, 346, 343, 615, -1, 347, 613, 612, -1, 347, 346, 613, -1, 350, 612, 609, -1, 350, 347, 612, -1, 351, 350, 609, -1, 352, 609, 606, -1, 352, 351, 609, -1, 354, 606, 605, -1, 354, 352, 606, -1, 357, 605, 602, -1, 357, 354, 605, -1, 358, 602, 601, -1, 358, 357, 602, -1, 361, 601, 599, -1, 361, 358, 601, -1, 362, 361, 599, -1, 362, 599, 597, -1, 365, 362, 597, -1, 365, 597, 595, -1, 366, 365, 595, -1, 366, 595, 594, -1, 42, 366, 594, -1, 42, 594, 40, -1, 336, 37, 38, -1, 336, 38, 626, -1, 337, 626, 627, -1, 337, 336, 626, -1, 339, 627, 625, -1, 339, 337, 627, -1, 341, 625, 622, -1, 341, 339, 625, -1, 345, 622, 621, -1, 345, 341, 622, -1, 344, 621, 617, -1, 344, 345, 621, -1, 349, 617, 616, -1, 349, 344, 617, -1, 348, 616, 614, -1, 348, 349, 616, -1, 353, 614, 611, -1, 353, 348, 614, -1, 356, 353, 611, -1, 355, 611, 610, -1, 355, 356, 611, -1, 359, 610, 607, -1, 359, 355, 610, -1, 360, 607, 608, -1, 360, 359, 607, -1, 363, 608, 603, -1, 363, 360, 608, -1, 364, 603, 604, -1, 364, 363, 603, -1, 367, 364, 604, -1, 367, 604, 600, -1, 369, 367, 600, -1, 369, 600, 598, -1, 368, 369, 598, -1, 368, 598, 596, -1, 3, 368, 596, -1, 3, 596, 1, -1, 628, 629, 630, -1, 628, 631, 629, -1, 632, 630, 633, -1, 632, 628, 630, -1, 634, 633, 635, -1, 634, 632, 633, -1, 636, 635, 637, -1, 636, 634, 635, -1, 638, 637, 639, -1, 638, 636, 637, -1, 640, 639, 641, -1, 640, 638, 639, -1, 642, 641, 643, -1, 642, 640, 641, -1, 644, 643, 645, -1, 644, 642, 643, -1, 646, 645, 647, -1, 646, 647, 648, -1, 646, 644, 645, -1, 649, 648, 650, -1, 649, 646, 648, -1, 651, 650, 652, -1, 651, 649, 650, -1, 653, 652, 654, -1, 653, 651, 652, -1, 655, 654, 656, -1, 655, 653, 654, -1, 657, 656, 658, -1, 657, 655, 656, -1, 659, 657, 658, -1, 659, 658, 660, -1, 661, 659, 660, -1, 661, 660, 662, -1, 663, 661, 662, -1, 663, 662, 664, -1, 665, 663, 664, -1, 665, 664, 666, -1, 667, 668, 669, -1, 667, 670, 668, -1, 671, 669, 672, -1, 671, 667, 669, -1, 673, 672, 674, -1, 673, 671, 672, -1, 675, 674, 676, -1, 675, 673, 674, -1, 677, 676, 678, -1, 677, 675, 676, -1, 679, 678, 680, -1, 679, 677, 678, -1, 681, 680, 682, -1, 681, 679, 680, -1, 683, 682, 684, -1, 683, 681, 682, -1, 685, 684, 686, -1, 685, 686, 687, -1, 685, 683, 684, -1, 688, 687, 689, -1, 688, 685, 687, -1, 690, 689, 691, -1, 690, 688, 689, -1, 692, 691, 693, -1, 692, 690, 691, -1, 694, 693, 695, -1, 694, 692, 693, -1, 696, 695, 697, -1, 696, 694, 695, -1, 698, 696, 697, -1, 698, 697, 699, -1, 700, 698, 699, -1, 700, 699, 701, -1, 702, 700, 701, -1, 702, 701, 703, -1, 704, 702, 703, -1, 704, 703, 705, -1, 706, 707, 708, -1, 709, 708, 710, -1, 709, 706, 708, -1, 711, 710, 712, -1, 711, 709, 710, -1, 713, 712, 714, -1, 713, 711, 712, -1, 715, 714, 716, -1, 715, 713, 714, -1, 717, 716, 718, -1, 717, 715, 716, -1, 719, 718, 720, -1, 719, 717, 718, -1, 721, 720, 722, -1, 721, 719, 720, -1, 723, 722, 724, -1, 723, 721, 722, -1, 725, 724, 726, -1, 725, 723, 724, -1, 727, 726, 728, -1, 727, 725, 726, -1, 729, 728, 730, -1, 729, 727, 728, -1, 731, 730, 732, -1, 731, 729, 730, -1, 733, 732, 734, -1, 733, 731, 732, -1, 735, 734, 736, -1, 735, 733, 734, -1, 737, 736, 738, -1, 737, 735, 736, -1, 739, 737, 738, -1, 740, 741, 742, -1, 742, 741, 743, -1, 743, 744, 745, -1, 741, 744, 743, -1, 745, 746, 747, -1, 744, 746, 745, -1, 747, 748, 749, -1, 746, 748, 747, -1, 749, 750, 751, -1, 748, 750, 749, -1, 751, 752, 753, -1, 750, 752, 751, -1, 753, 754, 755, -1, 752, 754, 753, -1, 755, 756, 757, -1, 754, 756, 755, -1, 757, 758, 759, -1, 756, 758, 757, -1, 759, 760, 761, -1, 758, 760, 759, -1, 761, 762, 763, -1, 760, 762, 761, -1, 763, 764, 765, -1, 762, 764, 763, -1, 765, 766, 767, -1, 764, 766, 765, -1, 767, 768, 769, -1, 766, 768, 767, -1, 770, 741, 740, -1, 770, 771, 741, -1, 771, 744, 741, -1, 771, 772, 744, -1, 772, 746, 744, -1, 772, 773, 746, -1, 773, 748, 746, -1, 773, 774, 748, -1, 774, 750, 748, -1, 774, 775, 750, -1, 775, 752, 750, -1, 775, 776, 752, -1, 776, 754, 752, -1, 776, 777, 754, -1, 777, 756, 754, -1, 777, 778, 756, -1, 778, 758, 756, -1, 778, 779, 758, -1, 779, 760, 758, -1, 779, 780, 760, -1, 780, 762, 760, -1, 780, 781, 762, -1, 781, 764, 762, -1, 781, 782, 764, -1, 782, 766, 764, -1, 782, 783, 766, -1, 783, 768, 766, -1, 783, 784, 768, -1, 785, 767, 769, -1, 785, 786, 767, -1, 767, 787, 765, -1, 786, 787, 767, -1, 765, 788, 763, -1, 787, 788, 765, -1, 763, 789, 761, -1, 788, 789, 763, -1, 761, 790, 759, -1, 789, 790, 761, -1, 759, 791, 757, -1, 790, 791, 759, -1, 757, 792, 755, -1, 791, 792, 757, -1, 755, 793, 753, -1, 792, 793, 755, -1, 753, 794, 751, -1, 793, 794, 753, -1, 751, 795, 749, -1, 794, 795, 751, -1, 749, 796, 747, -1, 795, 796, 749, -1, 747, 797, 745, -1, 796, 797, 747, -1, 745, 798, 743, -1, 797, 798, 745, -1, 743, 799, 742, -1, 798, 799, 743, -1, 708, 800, 801, -1, 708, 707, 800, -1, 710, 801, 802, -1, 710, 708, 801, -1, 712, 802, 803, -1, 712, 710, 802, -1, 714, 803, 804, -1, 714, 712, 803, -1, 716, 804, 805, -1, 716, 714, 804, -1, 718, 805, 806, -1, 718, 716, 805, -1, 720, 806, 807, -1, 720, 718, 806, -1, 722, 807, 808, -1, 722, 720, 807, -1, 724, 808, 809, -1, 724, 722, 808, -1, 726, 809, 810, -1, 726, 724, 809, -1, 728, 810, 811, -1, 728, 726, 810, -1, 730, 811, 812, -1, 730, 728, 811, -1, 732, 812, 813, -1, 732, 730, 812, -1, 734, 813, 814, -1, 734, 732, 813, -1, 736, 814, 815, -1, 736, 734, 814, -1, 738, 815, 816, -1, 738, 736, 815, -1, 737, 817, 818, -1, 737, 739, 817, -1, 735, 818, 819, -1, 735, 737, 818, -1, 733, 819, 820, -1, 733, 735, 819, -1, 731, 820, 821, -1, 731, 733, 820, -1, 729, 821, 822, -1, 729, 731, 821, -1, 727, 822, 823, -1, 727, 729, 822, -1, 725, 823, 824, -1, 725, 727, 823, -1, 723, 824, 825, -1, 723, 725, 824, -1, 721, 825, 826, -1, 721, 723, 825, -1, 719, 826, 827, -1, 719, 721, 826, -1, 717, 827, 828, -1, 717, 719, 827, -1, 715, 828, 829, -1, 715, 717, 828, -1, 713, 829, 830, -1, 713, 715, 829, -1, 711, 830, 831, -1, 711, 713, 830, -1, 709, 831, 832, -1, 709, 711, 831, -1, 706, 832, 833, -1, 706, 709, 832, -1, 834, 835, 836, -1, 837, 835, 834, -1, 838, 837, 834, -1, 839, 837, 838, -1, 840, 839, 838, -1, 841, 839, 840, -1, 842, 841, 840, -1, 843, 841, 842, -1, 844, 843, 842, -1, 845, 843, 844, -1, 846, 845, 844, -1, 847, 845, 846, -1, 848, 847, 846, -1, 849, 847, 848, -1, 850, 849, 848, -1, 851, 849, 850, -1, 852, 851, 850, -1, 853, 851, 852, -1, 854, 853, 852, -1, 855, 853, 854, -1, 856, 855, 854, -1, 857, 855, 856, -1, 858, 857, 856, -1, 859, 857, 858, -1, 860, 859, 858, -1, 861, 859, 860, -1, 862, 861, 860, -1, 863, 861, 862, -1, 864, 863, 862, -1, 865, 863, 864, -1, 866, 865, 864, -1, 867, 865, 866, -1, 868, 869, 870, -1, 871, 869, 868, -1, 872, 871, 868, -1, 873, 871, 872, -1, 874, 873, 872, -1, 875, 873, 874, -1, 876, 875, 874, -1, 877, 875, 876, -1, 878, 877, 876, -1, 879, 877, 878, -1, 880, 879, 878, -1, 881, 879, 880, -1, 882, 881, 880, -1, 883, 881, 882, -1, 884, 883, 882, -1, 885, 883, 884, -1, 886, 885, 884, -1, 887, 885, 886, -1, 888, 887, 886, -1, 889, 887, 888, -1, 890, 889, 888, -1, 891, 889, 890, -1, 892, 891, 890, -1, 893, 891, 892, -1, 894, 893, 892, -1, 895, 893, 894, -1, 896, 895, 894, -1, 897, 895, 896, -1, 898, 897, 896, -1, 899, 897, 898, -1, 900, 898, 901, -1, 900, 899, 898, -1, 902, 903, 904, -1, 902, 905, 903, -1, 905, 906, 903, -1, 905, 907, 906, -1, 907, 908, 906, -1, 907, 909, 908, -1, 909, 910, 908, -1, 909, 911, 910, -1, 911, 912, 910, -1, 911, 913, 912, -1, 913, 914, 912, -1, 913, 915, 914, -1, 915, 916, 914, -1, 915, 917, 916, -1, 917, 918, 916, -1, 917, 919, 918, -1, 919, 920, 918, -1, 919, 921, 920, -1, 921, 922, 920, -1, 921, 923, 922, -1, 923, 924, 922, -1, 923, 925, 924, -1, 925, 926, 924, -1, 925, 927, 926, -1, 927, 928, 926, -1, 927, 929, 928, -1, 929, 930, 928, -1, 929, 931, 930, -1, 932, 933, 934, -1, 932, 935, 933, -1, 935, 936, 933, -1, 935, 937, 936, -1, 937, 938, 936, -1, 937, 939, 938, -1, 939, 940, 938, -1, 939, 941, 940, -1, 941, 942, 940, -1, 941, 943, 942, -1, 943, 944, 942, -1, 943, 945, 944, -1, 945, 946, 944, -1, 945, 947, 946, -1, 946, 948, 949, -1, 947, 948, 946, -1, 948, 950, 949, -1, 948, 951, 950, -1, 951, 952, 950, -1, 951, 953, 952, -1, 953, 954, 952, -1, 953, 955, 954, -1, 954, 956, 957, -1, 955, 956, 954, -1, 956, 958, 957, -1, 956, 959, 958, -1, 958, 960, 961, -1, 959, 960, 958, -1, 904, 903, 961, -1, 961, 903, 958, -1, 958, 906, 957, -1, 903, 906, 958, -1, 957, 908, 954, -1, 906, 908, 957, -1, 954, 910, 952, -1, 908, 910, 954, -1, 952, 912, 950, -1, 910, 912, 952, -1, 950, 914, 949, -1, 912, 914, 950, -1, 949, 916, 946, -1, 914, 916, 949, -1, 944, 918, 942, -1, 946, 918, 944, -1, 916, 918, 946, -1, 918, 920, 942, -1, 940, 922, 938, -1, 942, 922, 940, -1, 920, 922, 942, -1, 922, 924, 938, -1, 936, 926, 933, -1, 938, 926, 936, -1, 924, 926, 938, -1, 933, 928, 934, -1, 926, 928, 933, -1, 928, 930, 934, -1, 865, 867, 869, -1, 865, 869, 871, -1, 863, 865, 871, -1, 863, 871, 873, -1, 704, 875, 877, -1, 702, 704, 877, -1, 861, 863, 873, -1, 861, 873, 875, -1, 700, 702, 877, -1, 698, 700, 877, -1, 879, 698, 877, -1, 665, 704, 962, -1, 665, 875, 704, -1, 665, 861, 875, -1, 663, 962, 963, -1, 663, 665, 962, -1, 859, 861, 665, -1, 859, 665, 964, -1, 965, 859, 964, -1, 661, 963, 966, -1, 661, 663, 963, -1, 694, 696, 879, -1, 967, 859, 965, -1, 659, 966, 968, -1, 659, 661, 966, -1, 881, 694, 879, -1, 969, 859, 967, -1, 657, 968, 970, -1, 657, 659, 968, -1, 857, 859, 969, -1, 655, 970, 971, -1, 655, 657, 970, -1, 690, 692, 881, -1, 883, 690, 881, -1, 972, 857, 973, -1, 653, 971, 974, -1, 653, 655, 971, -1, 855, 857, 972, -1, 651, 974, 975, -1, 651, 653, 974, -1, 885, 688, 883, -1, 976, 855, 977, -1, 853, 855, 976, -1, 649, 975, 978, -1, 649, 651, 975, -1, 683, 685, 885, -1, 887, 683, 885, -1, 646, 649, 978, -1, 646, 979, 980, -1, 646, 978, 979, -1, 851, 853, 981, -1, 644, 980, 982, -1, 644, 646, 980, -1, 889, 679, 681, -1, 889, 681, 887, -1, 983, 851, 984, -1, 849, 851, 983, -1, 642, 982, 985, -1, 642, 644, 982, -1, 891, 677, 889, -1, 675, 677, 891, -1, 640, 985, 986, -1, 640, 642, 985, -1, 847, 987, 988, -1, 847, 849, 987, -1, 638, 986, 989, -1, 638, 640, 986, -1, 893, 671, 673, -1, 893, 673, 891, -1, 667, 671, 893, -1, 636, 989, 990, -1, 636, 638, 989, -1, 670, 667, 893, -1, 845, 991, 992, -1, 845, 847, 991, -1, 634, 990, 993, -1, 634, 636, 990, -1, 632, 993, 994, -1, 632, 634, 993, -1, 895, 670, 893, -1, 628, 994, 670, -1, 628, 632, 994, -1, 631, 628, 670, -1, 843, 845, 995, -1, 843, 996, 631, -1, 843, 997, 996, -1, 843, 995, 997, -1, 841, 843, 631, -1, 841, 631, 670, -1, 841, 670, 895, -1, 839, 841, 895, -1, 839, 895, 897, -1, 837, 839, 897, -1, 837, 897, 899, -1, 835, 837, 899, -1, 835, 899, 900, -1, 696, 698, 879, -1, 692, 694, 881, -1, 688, 690, 883, -1, 685, 688, 885, -1, 681, 683, 887, -1, 677, 679, 889, -1, 673, 675, 891, -1, 992, 995, 845, -1, 988, 991, 847, -1, 983, 987, 849, -1, 981, 984, 851, -1, 976, 981, 853, -1, 972, 977, 855, -1, 969, 973, 857, -1, 998, 835, 900, -1, 998, 900, 999, -1, 1000, 999, 1001, -1, 1000, 998, 999, -1, 1002, 1001, 1003, -1, 1002, 1000, 1001, -1, 1004, 1003, 1005, -1, 1004, 1002, 1003, -1, 1006, 1005, 1007, -1, 1006, 1004, 1005, -1, 1008, 1007, 1009, -1, 1008, 1006, 1007, -1, 1010, 1009, 1011, -1, 1010, 1008, 1009, -1, 1012, 1011, 1013, -1, 1012, 1010, 1011, -1, 1014, 1013, 1015, -1, 1014, 1012, 1013, -1, 1016, 1015, 1017, -1, 1016, 1014, 1015, -1, 1018, 1017, 1019, -1, 1018, 1016, 1017, -1, 1020, 1019, 1021, -1, 1020, 1018, 1019, -1, 1022, 1021, 1023, -1, 1022, 1020, 1021, -1, 1024, 1023, 1025, -1, 1024, 1022, 1023, -1, 1026, 1025, 1027, -1, 1026, 1024, 1025, -1, 867, 1026, 1027, -1, 867, 1027, 869, -1, 880, 878, 1028, -1, 1029, 956, 1030, -1, 959, 956, 1029, -1, 1031, 880, 1028, -1, 941, 1032, 1033, -1, 882, 1031, 1034, -1, 882, 880, 1031, -1, 1035, 960, 959, -1, 939, 1036, 1032, -1, 1035, 959, 1029, -1, 939, 1032, 941, -1, 943, 1033, 1037, -1, 943, 941, 1033, -1, 937, 1038, 1036, -1, 937, 1036, 939, -1, 884, 882, 1034, -1, 901, 960, 1035, -1, 945, 1037, 1039, -1, 945, 943, 1037, -1, 935, 1040, 1038, -1, 935, 1038, 937, -1, 886, 1034, 1041, -1, 947, 1039, 1042, -1, 947, 1042, 1043, -1, 886, 884, 1034, -1, 947, 945, 1039, -1, 898, 1044, 960, -1, 898, 960, 901, -1, 932, 870, 1040, -1, 888, 1041, 1045, -1, 932, 868, 870, -1, 932, 1040, 935, -1, 888, 886, 1041, -1, 948, 947, 1043, -1, 1046, 868, 932, -1, 896, 1047, 1044, -1, 896, 1044, 898, -1, 890, 1045, 1048, -1, 872, 868, 1046, -1, 1049, 948, 1043, -1, 890, 888, 1045, -1, 951, 948, 1049, -1, 894, 1050, 1047, -1, 894, 1047, 896, -1, 892, 1048, 1050, -1, 892, 1050, 894, -1, 1051, 872, 1046, -1, 892, 890, 1048, -1, 874, 872, 1051, -1, 1052, 951, 1049, -1, 953, 951, 1052, -1, 1053, 874, 1051, -1, 876, 874, 1053, -1, 1054, 953, 1052, -1, 955, 953, 1054, -1, 1055, 876, 1053, -1, 878, 876, 1055, -1, 1030, 955, 1054, -1, 956, 955, 1030, -1, 1028, 878, 1055, -1, 907, 1056, 1057, -1, 856, 854, 1058, -1, 907, 905, 1056, -1, 854, 1059, 1058, -1, 1060, 923, 1061, -1, 905, 1062, 1056, -1, 902, 1062, 905, -1, 1063, 925, 1060, -1, 1059, 852, 1064, -1, 1060, 925, 923, -1, 854, 852, 1059, -1, 1061, 921, 1065, -1, 923, 921, 1061, -1, 1066, 927, 1063, -1, 1063, 927, 925, -1, 852, 850, 1064, -1, 902, 836, 1062, -1, 1065, 919, 1067, -1, 921, 919, 1065, -1, 1068, 929, 1066, -1, 1066, 929, 927, -1, 1069, 917, 1070, -1, 1067, 917, 1069, -1, 919, 917, 1067, -1, 1071, 834, 902, -1, 866, 931, 1068, -1, 864, 931, 866, -1, 1068, 931, 929, -1, 902, 834, 836, -1, 917, 915, 1070, -1, 864, 1072, 931, -1, 1064, 848, 1073, -1, 850, 848, 1064, -1, 915, 1074, 1070, -1, 1075, 838, 1071, -1, 1071, 838, 834, -1, 864, 862, 1072, -1, 915, 913, 1074, -1, 1073, 846, 1076, -1, 848, 846, 1073, -1, 1077, 840, 1075, -1, 862, 1078, 1072, -1, 1075, 840, 838, -1, 913, 1079, 1074, -1, 1076, 844, 1080, -1, 862, 860, 1078, -1, 846, 844, 1076, -1, 913, 911, 1079, -1, 1080, 842, 1077, -1, 1077, 842, 840, -1, 844, 842, 1080, -1, 860, 1081, 1078, -1, 911, 1082, 1079, -1, 860, 858, 1081, -1, 911, 909, 1082, -1, 858, 1083, 1081, -1, 909, 1057, 1082, -1, 858, 856, 1083, -1, 909, 907, 1057, -1, 856, 1058, 1083, -1, 930, 1084, 934, -1, 934, 1084, 1085, -1, 1085, 1086, 1087, -1, 1084, 1086, 1085, -1, 1087, 1088, 1089, -1, 1086, 1088, 1087, -1, 1089, 1090, 1091, -1, 1088, 1090, 1089, -1, 1091, 1092, 1093, -1, 1090, 1092, 1091, -1, 1093, 1094, 1095, -1, 1092, 1094, 1093, -1, 1095, 1096, 1097, -1, 1094, 1096, 1095, -1, 1098, 1099, 1100, -1, 1097, 1099, 1098, -1, 1096, 1099, 1097, -1, 1099, 1101, 1100, -1, 1102, 1103, 1104, -1, 1100, 1103, 1102, -1, 1101, 1103, 1100, -1, 1103, 1105, 1104, -1, 1106, 1107, 1108, -1, 1104, 1107, 1106, -1, 1105, 1107, 1104, -1, 1108, 1109, 961, -1, 1107, 1109, 1108, -1, 1109, 904, 961, -1, 960, 1044, 961, -1, 961, 1044, 1108, -1, 1108, 1047, 1106, -1, 1044, 1047, 1108, -1, 1106, 1050, 1104, -1, 1047, 1050, 1106, -1, 1104, 1048, 1102, -1, 1050, 1048, 1104, -1, 1102, 1045, 1100, -1, 1048, 1045, 1102, -1, 1100, 1041, 1098, -1, 1045, 1041, 1100, -1, 1098, 1034, 1097, -1, 1041, 1034, 1098, -1, 1097, 1031, 1095, -1, 1034, 1031, 1097, -1, 1095, 1028, 1093, -1, 1031, 1028, 1095, -1, 1093, 1055, 1091, -1, 1028, 1055, 1093, -1, 1091, 1053, 1089, -1, 1055, 1053, 1091, -1, 1089, 1051, 1087, -1, 1053, 1051, 1089, -1, 1087, 1046, 1085, -1, 1051, 1046, 1087, -1, 1085, 932, 934, -1, 1046, 932, 1085, -1, 931, 1072, 930, -1, 930, 1072, 1084, -1, 1084, 1078, 1086, -1, 1072, 1078, 1084, -1, 1086, 1081, 1088, -1, 1078, 1081, 1086, -1, 1088, 1083, 1090, -1, 1081, 1083, 1088, -1, 1090, 1058, 1092, -1, 1083, 1058, 1090, -1, 1092, 1059, 1094, -1, 1058, 1059, 1092, -1, 1094, 1064, 1096, -1, 1059, 1064, 1094, -1, 1096, 1073, 1099, -1, 1064, 1073, 1096, -1, 1099, 1076, 1101, -1, 1073, 1076, 1099, -1, 1101, 1080, 1103, -1, 1076, 1080, 1101, -1, 1103, 1077, 1105, -1, 1080, 1077, 1103, -1, 1105, 1075, 1107, -1, 1077, 1075, 1105, -1, 1107, 1071, 1109, -1, 1075, 1071, 1107, -1, 1109, 902, 904, -1, 1071, 902, 1109, -1, 1035, 900, 901, -1, 999, 900, 1035, -1, 1029, 999, 1035, -1, 1001, 999, 1029, -1, 1030, 1001, 1029, -1, 1003, 1001, 1030, -1, 1054, 1003, 1030, -1, 1005, 1003, 1054, -1, 1052, 1005, 1054, -1, 1007, 1005, 1052, -1, 1049, 1007, 1052, -1, 1009, 1007, 1049, -1, 1043, 1009, 1049, -1, 1011, 1009, 1043, -1, 1042, 1011, 1043, -1, 1013, 1011, 1042, -1, 1039, 1013, 1042, -1, 1015, 1013, 1039, -1, 1037, 1015, 1039, -1, 1017, 1015, 1037, -1, 1033, 1017, 1037, -1, 1019, 1017, 1033, -1, 1032, 1019, 1033, -1, 1021, 1019, 1032, -1, 1036, 1021, 1032, -1, 1023, 1021, 1036, -1, 1038, 1023, 1036, -1, 1025, 1023, 1038, -1, 1040, 1025, 1038, -1, 1027, 1025, 1040, -1, 870, 1027, 1040, -1, 869, 1027, 870, -1, 1026, 867, 866, -1, 1026, 866, 1068, -1, 1024, 1068, 1066, -1, 1024, 1026, 1068, -1, 1022, 1066, 1063, -1, 1022, 1024, 1066, -1, 1020, 1063, 1060, -1, 1020, 1022, 1063, -1, 1018, 1060, 1061, -1, 1018, 1020, 1060, -1, 1016, 1061, 1065, -1, 1016, 1018, 1061, -1, 1014, 1065, 1067, -1, 1014, 1016, 1065, -1, 1012, 1067, 1069, -1, 1012, 1014, 1067, -1, 1010, 1069, 1070, -1, 1010, 1012, 1069, -1, 1008, 1070, 1074, -1, 1008, 1010, 1070, -1, 1006, 1074, 1079, -1, 1006, 1008, 1074, -1, 1004, 1079, 1082, -1, 1004, 1006, 1079, -1, 1002, 1082, 1057, -1, 1002, 1004, 1082, -1, 1000, 1057, 1056, -1, 1000, 1002, 1057, -1, 998, 1056, 1062, -1, 998, 1000, 1056, -1, 835, 1062, 836, -1, 835, 998, 1062, -1, 1110, 706, 833, -1, 1111, 706, 1110, -1, 1112, 1111, 1110, -1, 1113, 1111, 1112, -1, 1114, 1113, 1112, -1, 1115, 1113, 1114, -1, 1116, 1115, 1114, -1, 1117, 1115, 1116, -1, 1118, 1117, 1116, -1, 1119, 1117, 1118, -1, 1120, 1119, 1118, -1, 1121, 1119, 1120, -1, 1122, 1121, 1120, -1, 1123, 1121, 1122, -1, 1124, 1123, 1122, -1, 1125, 1123, 1124, -1, 1126, 1125, 1124, -1, 1127, 1125, 1126, -1, 1128, 1127, 1126, -1, 1129, 1127, 1128, -1, 1130, 1129, 1128, -1, 1131, 1129, 1130, -1, 1132, 1131, 1130, -1, 1133, 1131, 1132, -1, 1134, 1133, 1132, -1, 1135, 1133, 1134, -1, 1136, 1135, 1134, -1, 1137, 1135, 1136, -1, 1138, 1137, 1136, -1, 1139, 1137, 1138, -1, 817, 1139, 1138, -1, 739, 1139, 817, -1, 1140, 738, 816, -1, 1140, 816, 1141, -1, 1142, 1140, 1141, -1, 1143, 1140, 1142, -1, 1144, 1143, 1142, -1, 1145, 1143, 1144, -1, 1146, 1145, 1144, -1, 1147, 1145, 1146, -1, 1148, 1147, 1146, -1, 1149, 1147, 1148, -1, 1150, 1149, 1148, -1, 1151, 1149, 1150, -1, 1152, 1151, 1150, -1, 1153, 1151, 1152, -1, 1154, 1153, 1152, -1, 1155, 1153, 1154, -1, 1156, 1155, 1154, -1, 1157, 1155, 1156, -1, 1158, 1157, 1156, -1, 1159, 1157, 1158, -1, 1160, 1159, 1158, -1, 1161, 1159, 1160, -1, 1162, 1161, 1160, -1, 1163, 1161, 1162, -1, 1164, 1163, 1162, -1, 1165, 1163, 1164, -1, 1166, 1165, 1164, -1, 1167, 1165, 1166, -1, 1168, 1167, 1166, -1, 1169, 1167, 1168, -1, 800, 1169, 1168, -1, 707, 1169, 800, -1, 799, 1170, 742, -1, 742, 1170, 1171, -1, 1171, 1172, 1173, -1, 1170, 1172, 1171, -1, 1173, 1174, 1175, -1, 1172, 1174, 1173, -1, 1175, 1176, 1177, -1, 1174, 1176, 1175, -1, 1177, 1178, 1179, -1, 1176, 1178, 1177, -1, 1179, 1180, 1181, -1, 1178, 1180, 1179, -1, 1181, 1182, 1183, -1, 1180, 1182, 1181, -1, 1183, 1184, 1185, -1, 1182, 1184, 1183, -1, 1185, 1186, 1187, -1, 1184, 1186, 1185, -1, 1187, 1188, 1189, -1, 1186, 1188, 1187, -1, 1189, 1190, 1191, -1, 1188, 1190, 1189, -1, 1191, 1192, 1193, -1, 1190, 1192, 1191, -1, 1193, 1194, 1195, -1, 1192, 1194, 1193, -1, 1195, 785, 769, -1, 1194, 785, 1195, -1, 784, 1196, 768, -1, 768, 1196, 1197, -1, 1197, 1198, 1199, -1, 1196, 1198, 1197, -1, 1199, 1200, 1201, -1, 1198, 1200, 1199, -1, 1201, 1202, 1203, -1, 1200, 1202, 1201, -1, 1203, 1204, 1205, -1, 1202, 1204, 1203, -1, 1205, 1206, 1207, -1, 1204, 1206, 1205, -1, 1207, 1208, 1209, -1, 1206, 1208, 1207, -1, 1209, 1210, 1211, -1, 1208, 1210, 1209, -1, 1211, 1212, 1213, -1, 1210, 1212, 1211, -1, 1213, 1214, 1215, -1, 1212, 1214, 1213, -1, 1215, 1216, 1217, -1, 1214, 1216, 1215, -1, 1217, 1218, 1219, -1, 1216, 1218, 1217, -1, 1219, 1220, 1221, -1, 1218, 1220, 1219, -1, 1221, 770, 740, -1, 1220, 770, 1221, -1, 769, 768, 1195, -1, 1195, 1197, 1193, -1, 768, 1197, 1195, -1, 1193, 1199, 1191, -1, 1197, 1199, 1193, -1, 1191, 1201, 1189, -1, 1199, 1201, 1191, -1, 1189, 1203, 1187, -1, 1201, 1203, 1189, -1, 1187, 1205, 1185, -1, 1203, 1205, 1187, -1, 1185, 1207, 1183, -1, 1205, 1207, 1185, -1, 1183, 1209, 1181, -1, 1207, 1209, 1183, -1, 1181, 1211, 1179, -1, 1209, 1211, 1181, -1, 1179, 1213, 1177, -1, 1211, 1213, 1179, -1, 1177, 1215, 1175, -1, 1213, 1215, 1177, -1, 1175, 1217, 1173, -1, 1215, 1217, 1175, -1, 1173, 1219, 1171, -1, 1217, 1219, 1173, -1, 1171, 1221, 742, -1, 1219, 1221, 1171, -1, 1221, 740, 742, -1, 1114, 781, 1116, -1, 822, 821, 1214, -1, 1212, 822, 1214, -1, 782, 781, 1114, -1, 1112, 782, 1114, -1, 823, 822, 1212, -1, 1210, 823, 1212, -1, 773, 1134, 1132, -1, 774, 1132, 1130, -1, 783, 782, 1112, -1, 774, 773, 1132, -1, 772, 1136, 1134, -1, 772, 1134, 773, -1, 775, 1130, 1128, -1, 775, 774, 1130, -1, 1110, 784, 783, -1, 1110, 783, 1112, -1, 824, 1210, 1208, -1, 771, 1138, 1136, -1, 771, 1136, 772, -1, 824, 823, 1210, -1, 776, 1128, 1126, -1, 776, 775, 1128, -1, 825, 824, 1208, -1, 833, 784, 1110, -1, 770, 817, 1138, -1, 770, 818, 817, -1, 770, 1138, 771, -1, 777, 1126, 1124, -1, 777, 1124, 1122, -1, 777, 776, 1126, -1, 1220, 818, 770, -1, 778, 777, 1122, -1, 832, 1196, 784, -1, 832, 784, 833, -1, 826, 1208, 1206, -1, 1120, 778, 1122, -1, 819, 818, 1220, -1, 826, 825, 1208, -1, 831, 1198, 1196, -1, 831, 1196, 832, -1, 1218, 819, 1220, -1, 827, 1206, 1204, -1, 779, 778, 1120, -1, 827, 826, 1206, -1, 1118, 779, 1120, -1, 830, 1200, 1198, -1, 830, 1198, 831, -1, 820, 819, 1218, -1, 828, 1204, 1202, -1, 828, 827, 1204, -1, 829, 1202, 1200, -1, 829, 1200, 830, -1, 829, 828, 1202, -1, 1216, 820, 1218, -1, 780, 779, 1118, -1, 1116, 780, 1118, -1, 821, 820, 1216, -1, 1214, 821, 1216, -1, 781, 780, 1116, -1, 811, 1178, 1176, -1, 788, 787, 1164, -1, 811, 810, 1178, -1, 787, 1166, 1164, -1, 810, 1180, 1178, -1, 787, 786, 1166, -1, 1144, 796, 1146, -1, 1146, 795, 1148, -1, 1180, 809, 1182, -1, 796, 795, 1146, -1, 810, 809, 1180, -1, 785, 1168, 786, -1, 1142, 797, 1144, -1, 786, 1168, 1166, -1, 1144, 797, 796, -1, 1148, 794, 1150, -1, 795, 794, 1148, -1, 809, 808, 1182, -1, 785, 800, 1168, -1, 1141, 798, 1142, -1, 1142, 798, 797, -1, 1150, 793, 1152, -1, 794, 793, 1150, -1, 1182, 807, 1184, -1, 808, 807, 1182, -1, 816, 799, 1141, -1, 815, 799, 816, -1, 1194, 801, 785, -1, 1141, 799, 798, -1, 1154, 792, 1156, -1, 785, 801, 800, -1, 1152, 792, 1154, -1, 793, 792, 1152, -1, 1184, 806, 1186, -1, 815, 1170, 799, -1, 807, 806, 1184, -1, 1192, 802, 1194, -1, 792, 791, 1156, -1, 1194, 802, 801, -1, 815, 814, 1170, -1, 791, 1158, 1156, -1, 1186, 805, 1188, -1, 806, 805, 1186, -1, 1190, 803, 1192, -1, 814, 1172, 1170, -1, 1192, 803, 802, -1, 791, 790, 1158, -1, 1188, 804, 1190, -1, 805, 804, 1188, -1, 1190, 804, 803, -1, 814, 813, 1172, -1, 790, 1160, 1158, -1, 813, 1174, 1172, -1, 790, 789, 1160, -1, 813, 812, 1174, -1, 789, 1162, 1160, -1, 812, 1176, 1174, -1, 789, 788, 1162, -1, 812, 811, 1176, -1, 788, 1164, 1162, -1, 1139, 739, 738, -1, 1139, 738, 1140, -1, 1137, 1140, 1143, -1, 1137, 1139, 1140, -1, 668, 1145, 1147, -1, 669, 668, 1147, -1, 1135, 1143, 1145, -1, 1135, 1137, 1143, -1, 672, 669, 1147, -1, 674, 672, 1147, -1, 1149, 674, 1147, -1, 629, 668, 1222, -1, 629, 1145, 668, -1, 629, 1135, 1145, -1, 630, 1222, 1223, -1, 630, 629, 1222, -1, 1133, 1135, 629, -1, 1133, 629, 1224, -1, 633, 1223, 1225, -1, 633, 630, 1223, -1, 1226, 1133, 1224, -1, 678, 676, 1149, -1, 635, 1225, 1227, -1, 635, 633, 1225, -1, 1228, 1133, 1226, -1, 1151, 678, 1149, -1, 637, 1227, 1229, -1, 637, 635, 1227, -1, 1131, 1133, 1228, -1, 682, 680, 1151, -1, 639, 1229, 1230, -1, 639, 637, 1229, -1, 1231, 1131, 1232, -1, 1153, 682, 1151, -1, 641, 1230, 1233, -1, 641, 639, 1230, -1, 1129, 1131, 1231, -1, 643, 1233, 1234, -1, 643, 641, 1233, -1, 1155, 686, 684, -1, 1155, 684, 1153, -1, 1235, 1129, 1236, -1, 645, 643, 1234, -1, 645, 1234, 1237, -1, 1127, 1129, 1235, -1, 1157, 687, 1155, -1, 647, 645, 1237, -1, 1125, 1127, 1238, -1, 1125, 1238, 1239, -1, 648, 647, 1237, -1, 648, 1237, 1240, -1, 1159, 689, 1157, -1, 1159, 691, 689, -1, 650, 648, 1240, -1, 650, 1240, 1241, -1, 1123, 1125, 1242, -1, 652, 650, 1241, -1, 652, 1241, 1243, -1, 1161, 693, 1159, -1, 1161, 695, 693, -1, 1121, 1244, 1245, -1, 1121, 1123, 1244, -1, 654, 652, 1243, -1, 654, 1243, 1246, -1, 656, 654, 1246, -1, 656, 1246, 1247, -1, 1163, 697, 1161, -1, 1163, 699, 697, -1, 1163, 701, 699, -1, 703, 701, 1163, -1, 705, 703, 1163, -1, 658, 1247, 1248, -1, 658, 656, 1247, -1, 1119, 1249, 1250, -1, 1119, 1121, 1249, -1, 660, 658, 1248, -1, 660, 1248, 1251, -1, 1165, 705, 1163, -1, 662, 660, 1251, -1, 662, 1251, 1252, -1, 664, 662, 1252, -1, 664, 1252, 705, -1, 666, 664, 705, -1, 1117, 1119, 1253, -1, 1117, 1254, 666, -1, 1117, 1255, 1254, -1, 1117, 1253, 1255, -1, 1115, 666, 705, -1, 1115, 705, 1165, -1, 1115, 1117, 666, -1, 1113, 1165, 1167, -1, 1113, 1115, 1165, -1, 1111, 1167, 1169, -1, 1111, 1113, 1167, -1, 706, 1169, 707, -1, 706, 1111, 1169, -1, 1250, 1253, 1119, -1, 1245, 1249, 1121, -1, 1242, 1244, 1123, -1, 1239, 1242, 1125, -1, 1235, 1238, 1127, -1, 1231, 1236, 1129, -1, 1228, 1232, 1131, -1, 676, 674, 1149, -1, 680, 678, 1151, -1, 684, 682, 1153, -1, 687, 686, 1155, -1, 689, 687, 1157, -1, 693, 691, 1159, -1, 697, 695, 1161, -1, 962, 704, 705, -1, 962, 705, 1252, -1, 963, 1252, 1251, -1, 963, 962, 1252, -1, 966, 1251, 1248, -1, 966, 963, 1251, -1, 968, 1248, 1247, -1, 968, 966, 1248, -1, 970, 1247, 1246, -1, 970, 968, 1247, -1, 971, 1246, 1243, -1, 971, 970, 1246, -1, 974, 1243, 1241, -1, 974, 971, 1243, -1, 975, 1241, 1240, -1, 975, 974, 1241, -1, 978, 1240, 1237, -1, 978, 975, 1240, -1, 979, 978, 1237, -1, 980, 1237, 1234, -1, 980, 979, 1237, -1, 982, 1234, 1233, -1, 982, 980, 1234, -1, 985, 1233, 1230, -1, 985, 982, 1233, -1, 986, 1230, 1229, -1, 986, 985, 1230, -1, 989, 1229, 1227, -1, 989, 986, 1229, -1, 990, 989, 1227, -1, 990, 1227, 1225, -1, 993, 990, 1225, -1, 993, 1225, 1223, -1, 994, 993, 1223, -1, 994, 1223, 1222, -1, 670, 994, 1222, -1, 670, 1222, 668, -1, 964, 665, 666, -1, 964, 666, 1254, -1, 965, 1254, 1255, -1, 965, 964, 1254, -1, 967, 1255, 1253, -1, 967, 965, 1255, -1, 969, 1253, 1250, -1, 969, 967, 1253, -1, 973, 1250, 1249, -1, 973, 969, 1250, -1, 972, 1249, 1245, -1, 972, 973, 1249, -1, 977, 1245, 1244, -1, 977, 972, 1245, -1, 976, 1244, 1242, -1, 976, 977, 1244, -1, 981, 1242, 1239, -1, 981, 976, 1242, -1, 984, 981, 1239, -1, 983, 1239, 1238, -1, 983, 984, 1239, -1, 987, 1238, 1235, -1, 987, 983, 1238, -1, 988, 1235, 1236, -1, 988, 987, 1235, -1, 991, 1236, 1231, -1, 991, 988, 1236, -1, 992, 1231, 1232, -1, 992, 991, 1231, -1, 995, 992, 1232, -1, 995, 1232, 1228, -1, 997, 995, 1228, -1, 997, 1228, 1226, -1, 996, 997, 1226, -1, 996, 1226, 1224, -1, 631, 996, 1224, -1, 631, 1224, 629, -1, 1256, 1257, 1258, -1, 1256, 1259, 1257, -1, 1260, 1258, 1261, -1, 1260, 1256, 1258, -1, 1262, 1261, 1263, -1, 1262, 1260, 1261, -1, 1264, 1263, 1265, -1, 1264, 1262, 1263, -1, 1266, 1265, 1267, -1, 1266, 1264, 1265, -1, 1268, 1267, 1269, -1, 1268, 1266, 1267, -1, 1270, 1269, 1271, -1, 1270, 1268, 1269, -1, 1272, 1271, 1273, -1, 1272, 1270, 1271, -1, 1274, 1273, 1275, -1, 1274, 1275, 1276, -1, 1274, 1272, 1273, -1, 1277, 1276, 1278, -1, 1277, 1274, 1276, -1, 1279, 1278, 1280, -1, 1279, 1277, 1278, -1, 1281, 1280, 1282, -1, 1281, 1279, 1280, -1, 1283, 1282, 1284, -1, 1283, 1281, 1282, -1, 1285, 1284, 1286, -1, 1285, 1283, 1284, -1, 1287, 1285, 1286, -1, 1287, 1286, 1288, -1, 1289, 1287, 1288, -1, 1289, 1288, 1290, -1, 1291, 1289, 1290, -1, 1291, 1290, 1292, -1, 1293, 1291, 1292, -1, 1293, 1292, 1294, -1, 1295, 1296, 1297, -1, 1295, 1298, 1296, -1, 1299, 1297, 1300, -1, 1299, 1295, 1297, -1, 1301, 1300, 1302, -1, 1301, 1299, 1300, -1, 1303, 1302, 1304, -1, 1303, 1301, 1302, -1, 1305, 1304, 1306, -1, 1305, 1303, 1304, -1, 1307, 1306, 1308, -1, 1307, 1305, 1306, -1, 1309, 1308, 1310, -1, 1309, 1307, 1308, -1, 1311, 1310, 1312, -1, 1311, 1309, 1310, -1, 1313, 1312, 1314, -1, 1313, 1314, 1315, -1, 1313, 1311, 1312, -1, 1316, 1315, 1317, -1, 1316, 1313, 1315, -1, 1318, 1317, 1319, -1, 1318, 1316, 1317, -1, 1320, 1319, 1321, -1, 1320, 1318, 1319, -1, 1322, 1321, 1323, -1, 1322, 1320, 1321, -1, 1324, 1323, 1325, -1, 1324, 1322, 1323, -1, 1326, 1324, 1325, -1, 1326, 1325, 1327, -1, 1328, 1326, 1327, -1, 1328, 1327, 1329, -1, 1330, 1328, 1329, -1, 1330, 1329, 1331, -1, 1332, 1330, 1331, -1, 1332, 1331, 1333, -1, 1334, 1335, 1336, -1, 1337, 1336, 1338, -1, 1337, 1334, 1336, -1, 1339, 1338, 1340, -1, 1339, 1337, 1338, -1, 1341, 1340, 1342, -1, 1341, 1339, 1340, -1, 1343, 1342, 1344, -1, 1343, 1341, 1342, -1, 1345, 1344, 1346, -1, 1345, 1343, 1344, -1, 1347, 1346, 1348, -1, 1347, 1345, 1346, -1, 1349, 1348, 1350, -1, 1349, 1347, 1348, -1, 1351, 1350, 1352, -1, 1351, 1349, 1350, -1, 1353, 1352, 1354, -1, 1353, 1351, 1352, -1, 1355, 1354, 1356, -1, 1355, 1353, 1354, -1, 1357, 1356, 1358, -1, 1357, 1355, 1356, -1, 1359, 1358, 1360, -1, 1359, 1357, 1358, -1, 1361, 1360, 1362, -1, 1361, 1359, 1360, -1, 1363, 1362, 1364, -1, 1363, 1361, 1362, -1, 1365, 1364, 1366, -1, 1365, 1363, 1364, -1, 1367, 1365, 1366, -1, 1368, 1369, 1370, -1, 1370, 1369, 1371, -1, 1371, 1372, 1373, -1, 1369, 1372, 1371, -1, 1373, 1374, 1375, -1, 1372, 1374, 1373, -1, 1375, 1376, 1377, -1, 1374, 1376, 1375, -1, 1377, 1378, 1379, -1, 1376, 1378, 1377, -1, 1379, 1380, 1381, -1, 1378, 1380, 1379, -1, 1381, 1382, 1383, -1, 1380, 1382, 1381, -1, 1383, 1384, 1385, -1, 1382, 1384, 1383, -1, 1385, 1386, 1387, -1, 1384, 1386, 1385, -1, 1387, 1388, 1389, -1, 1386, 1388, 1387, -1, 1389, 1390, 1391, -1, 1388, 1390, 1389, -1, 1391, 1392, 1393, -1, 1390, 1392, 1391, -1, 1393, 1394, 1395, -1, 1392, 1394, 1393, -1, 1395, 1396, 1397, -1, 1394, 1396, 1395, -1, 1398, 1369, 1368, -1, 1398, 1399, 1369, -1, 1399, 1372, 1369, -1, 1399, 1400, 1372, -1, 1400, 1374, 1372, -1, 1400, 1401, 1374, -1, 1401, 1376, 1374, -1, 1401, 1402, 1376, -1, 1402, 1378, 1376, -1, 1402, 1403, 1378, -1, 1403, 1380, 1378, -1, 1403, 1404, 1380, -1, 1404, 1382, 1380, -1, 1404, 1405, 1382, -1, 1405, 1384, 1382, -1, 1405, 1406, 1384, -1, 1406, 1386, 1384, -1, 1406, 1407, 1386, -1, 1407, 1388, 1386, -1, 1407, 1408, 1388, -1, 1408, 1390, 1388, -1, 1408, 1409, 1390, -1, 1409, 1392, 1390, -1, 1409, 1410, 1392, -1, 1410, 1394, 1392, -1, 1410, 1411, 1394, -1, 1411, 1396, 1394, -1, 1411, 1412, 1396, -1, 1413, 1395, 1397, -1, 1413, 1414, 1395, -1, 1414, 1393, 1395, -1, 1414, 1415, 1393, -1, 1415, 1391, 1393, -1, 1415, 1416, 1391, -1, 1416, 1389, 1391, -1, 1416, 1417, 1389, -1, 1417, 1387, 1389, -1, 1417, 1418, 1387, -1, 1418, 1385, 1387, -1, 1418, 1419, 1385, -1, 1385, 1420, 1383, -1, 1419, 1420, 1385, -1, 1420, 1381, 1383, -1, 1420, 1421, 1381, -1, 1381, 1422, 1379, -1, 1421, 1422, 1381, -1, 1422, 1377, 1379, -1, 1422, 1423, 1377, -1, 1423, 1375, 1377, -1, 1423, 1424, 1375, -1, 1424, 1373, 1375, -1, 1424, 1425, 1373, -1, 1373, 1426, 1371, -1, 1425, 1426, 1373, -1, 1426, 1370, 1371, -1, 1426, 1427, 1370, -1, 1428, 1335, 1429, -1, 1336, 1335, 1428, -1, 1430, 1336, 1428, -1, 1338, 1336, 1430, -1, 1431, 1338, 1430, -1, 1340, 1338, 1431, -1, 1432, 1340, 1431, -1, 1342, 1340, 1432, -1, 1433, 1342, 1432, -1, 1344, 1342, 1433, -1, 1434, 1344, 1433, -1, 1346, 1344, 1434, -1, 1435, 1346, 1434, -1, 1348, 1346, 1435, -1, 1436, 1348, 1435, -1, 1350, 1348, 1436, -1, 1437, 1350, 1436, -1, 1352, 1350, 1437, -1, 1438, 1352, 1437, -1, 1354, 1352, 1438, -1, 1439, 1354, 1438, -1, 1356, 1354, 1439, -1, 1440, 1356, 1439, -1, 1358, 1356, 1440, -1, 1441, 1358, 1440, -1, 1360, 1358, 1441, -1, 1442, 1360, 1441, -1, 1362, 1360, 1442, -1, 1443, 1362, 1442, -1, 1364, 1362, 1443, -1, 1366, 1443, 1444, -1, 1366, 1364, 1443, -1, 1445, 1367, 1446, -1, 1365, 1367, 1445, -1, 1447, 1365, 1445, -1, 1363, 1365, 1447, -1, 1448, 1363, 1447, -1, 1361, 1363, 1448, -1, 1449, 1361, 1448, -1, 1359, 1361, 1449, -1, 1450, 1359, 1449, -1, 1357, 1359, 1450, -1, 1451, 1357, 1450, -1, 1355, 1357, 1451, -1, 1452, 1355, 1451, -1, 1353, 1355, 1452, -1, 1453, 1353, 1452, -1, 1351, 1353, 1453, -1, 1454, 1351, 1453, -1, 1349, 1351, 1454, -1, 1455, 1349, 1454, -1, 1347, 1349, 1455, -1, 1456, 1347, 1455, -1, 1345, 1347, 1456, -1, 1457, 1345, 1456, -1, 1343, 1345, 1457, -1, 1458, 1343, 1457, -1, 1341, 1343, 1458, -1, 1459, 1341, 1458, -1, 1339, 1341, 1459, -1, 1460, 1339, 1459, -1, 1337, 1339, 1460, -1, 1461, 1337, 1460, -1, 1334, 1337, 1461, -1, 1462, 1463, 1464, -1, 1465, 1463, 1462, -1, 1466, 1465, 1462, -1, 1467, 1465, 1466, -1, 1468, 1467, 1466, -1, 1469, 1467, 1468, -1, 1470, 1469, 1468, -1, 1471, 1469, 1470, -1, 1472, 1471, 1470, -1, 1473, 1471, 1472, -1, 1474, 1473, 1472, -1, 1475, 1473, 1474, -1, 1476, 1475, 1474, -1, 1477, 1475, 1476, -1, 1478, 1477, 1476, -1, 1479, 1477, 1478, -1, 1480, 1479, 1478, -1, 1481, 1479, 1480, -1, 1482, 1481, 1480, -1, 1483, 1481, 1482, -1, 1484, 1483, 1482, -1, 1485, 1483, 1484, -1, 1486, 1485, 1484, -1, 1487, 1485, 1486, -1, 1488, 1487, 1486, -1, 1489, 1487, 1488, -1, 1490, 1489, 1488, -1, 1491, 1489, 1490, -1, 1492, 1491, 1490, -1, 1493, 1491, 1492, -1, 1494, 1493, 1492, -1, 1495, 1493, 1494, -1, 1496, 1497, 1498, -1, 1499, 1497, 1496, -1, 1500, 1499, 1496, -1, 1501, 1499, 1500, -1, 1502, 1501, 1500, -1, 1503, 1501, 1502, -1, 1504, 1503, 1502, -1, 1505, 1503, 1504, -1, 1506, 1505, 1504, -1, 1507, 1505, 1506, -1, 1508, 1507, 1506, -1, 1509, 1507, 1508, -1, 1510, 1509, 1508, -1, 1511, 1509, 1510, -1, 1512, 1511, 1510, -1, 1513, 1511, 1512, -1, 1514, 1513, 1512, -1, 1515, 1513, 1514, -1, 1516, 1515, 1514, -1, 1517, 1515, 1516, -1, 1518, 1517, 1516, -1, 1519, 1517, 1518, -1, 1520, 1519, 1518, -1, 1521, 1519, 1520, -1, 1522, 1521, 1520, -1, 1523, 1521, 1522, -1, 1524, 1523, 1522, -1, 1525, 1523, 1524, -1, 1526, 1525, 1524, -1, 1527, 1525, 1526, -1, 1528, 1527, 1526, -1, 1529, 1527, 1528, -1, 1530, 1531, 1532, -1, 1530, 1533, 1531, -1, 1533, 1534, 1531, -1, 1533, 1535, 1534, -1, 1535, 1536, 1534, -1, 1535, 1537, 1536, -1, 1537, 1538, 1536, -1, 1537, 1539, 1538, -1, 1539, 1540, 1538, -1, 1539, 1541, 1540, -1, 1541, 1542, 1540, -1, 1541, 1543, 1542, -1, 1543, 1544, 1542, -1, 1543, 1545, 1544, -1, 1545, 1546, 1544, -1, 1545, 1547, 1546, -1, 1547, 1548, 1546, -1, 1547, 1549, 1548, -1, 1549, 1550, 1548, -1, 1549, 1551, 1550, -1, 1551, 1552, 1550, -1, 1551, 1553, 1552, -1, 1553, 1554, 1552, -1, 1553, 1555, 1554, -1, 1555, 1556, 1554, -1, 1555, 1557, 1556, -1, 1557, 1558, 1556, -1, 1557, 1559, 1558, -1, 1560, 1561, 1562, -1, 1562, 1561, 1563, -1, 1563, 1564, 1565, -1, 1561, 1564, 1563, -1, 1565, 1566, 1567, -1, 1564, 1566, 1565, -1, 1567, 1568, 1569, -1, 1566, 1568, 1567, -1, 1569, 1570, 1571, -1, 1568, 1570, 1569, -1, 1571, 1572, 1573, -1, 1570, 1572, 1571, -1, 1573, 1574, 1575, -1, 1572, 1574, 1573, -1, 1575, 1576, 1577, -1, 1574, 1576, 1575, -1, 1577, 1578, 1579, -1, 1576, 1578, 1577, -1, 1579, 1580, 1581, -1, 1578, 1580, 1579, -1, 1581, 1582, 1583, -1, 1580, 1582, 1581, -1, 1583, 1584, 1585, -1, 1582, 1584, 1583, -1, 1585, 1586, 1587, -1, 1584, 1586, 1585, -1, 1587, 1588, 1589, -1, 1586, 1588, 1587, -1, 1532, 1531, 1589, -1, 1589, 1531, 1587, -1, 1587, 1534, 1585, -1, 1531, 1534, 1587, -1, 1583, 1536, 1581, -1, 1585, 1536, 1583, -1, 1534, 1536, 1585, -1, 1536, 1538, 1581, -1, 1579, 1540, 1577, -1, 1581, 1540, 1579, -1, 1538, 1540, 1581, -1, 1577, 1542, 1575, -1, 1540, 1542, 1577, -1, 1542, 1544, 1575, -1, 1573, 1546, 1571, -1, 1575, 1546, 1573, -1, 1544, 1546, 1575, -1, 1571, 1548, 1569, -1, 1546, 1548, 1571, -1, 1569, 1550, 1567, -1, 1548, 1550, 1569, -1, 1550, 1552, 1567, -1, 1567, 1554, 1565, -1, 1552, 1554, 1567, -1, 1565, 1556, 1563, -1, 1554, 1556, 1565, -1, 1563, 1558, 1562, -1, 1556, 1558, 1563, -1, 1493, 1495, 1497, -1, 1493, 1497, 1499, -1, 1491, 1493, 1499, -1, 1491, 1499, 1501, -1, 1332, 1503, 1505, -1, 1330, 1332, 1505, -1, 1489, 1491, 1501, -1, 1489, 1501, 1503, -1, 1328, 1330, 1505, -1, 1326, 1328, 1505, -1, 1507, 1326, 1505, -1, 1293, 1332, 1590, -1, 1293, 1503, 1332, -1, 1293, 1489, 1503, -1, 1291, 1590, 1591, -1, 1291, 1293, 1590, -1, 1487, 1489, 1293, -1, 1487, 1293, 1592, -1, 1593, 1487, 1592, -1, 1289, 1591, 1594, -1, 1289, 1291, 1591, -1, 1322, 1324, 1507, -1, 1595, 1487, 1593, -1, 1287, 1594, 1596, -1, 1287, 1289, 1594, -1, 1509, 1322, 1507, -1, 1597, 1487, 1595, -1, 1285, 1596, 1598, -1, 1285, 1287, 1596, -1, 1485, 1487, 1597, -1, 1283, 1598, 1599, -1, 1283, 1285, 1598, -1, 1318, 1320, 1509, -1, 1511, 1318, 1509, -1, 1600, 1485, 1601, -1, 1281, 1599, 1602, -1, 1281, 1283, 1599, -1, 1483, 1485, 1600, -1, 1279, 1602, 1603, -1, 1279, 1281, 1602, -1, 1513, 1316, 1511, -1, 1604, 1483, 1605, -1, 1481, 1483, 1604, -1, 1277, 1603, 1606, -1, 1277, 1279, 1603, -1, 1311, 1313, 1513, -1, 1515, 1311, 1513, -1, 1274, 1277, 1606, -1, 1274, 1607, 1608, -1, 1274, 1606, 1607, -1, 1479, 1481, 1609, -1, 1272, 1608, 1610, -1, 1272, 1274, 1608, -1, 1517, 1307, 1309, -1, 1517, 1309, 1515, -1, 1611, 1479, 1612, -1, 1477, 1479, 1611, -1, 1270, 1610, 1613, -1, 1270, 1272, 1610, -1, 1519, 1305, 1517, -1, 1303, 1305, 1519, -1, 1268, 1613, 1614, -1, 1268, 1270, 1613, -1, 1475, 1615, 1616, -1, 1475, 1477, 1615, -1, 1266, 1614, 1617, -1, 1266, 1268, 1614, -1, 1521, 1299, 1301, -1, 1521, 1301, 1519, -1, 1295, 1299, 1521, -1, 1264, 1617, 1618, -1, 1264, 1266, 1617, -1, 1298, 1295, 1521, -1, 1473, 1619, 1620, -1, 1473, 1475, 1619, -1, 1262, 1618, 1621, -1, 1262, 1264, 1618, -1, 1260, 1621, 1622, -1, 1260, 1262, 1621, -1, 1523, 1298, 1521, -1, 1256, 1622, 1298, -1, 1256, 1260, 1622, -1, 1259, 1256, 1298, -1, 1471, 1473, 1623, -1, 1471, 1624, 1259, -1, 1471, 1625, 1624, -1, 1471, 1623, 1625, -1, 1469, 1471, 1259, -1, 1469, 1259, 1298, -1, 1469, 1298, 1523, -1, 1467, 1469, 1523, -1, 1467, 1523, 1525, -1, 1465, 1467, 1525, -1, 1465, 1525, 1527, -1, 1463, 1465, 1527, -1, 1463, 1527, 1529, -1, 1324, 1326, 1507, -1, 1320, 1322, 1509, -1, 1316, 1318, 1511, -1, 1313, 1316, 1513, -1, 1309, 1311, 1515, -1, 1305, 1307, 1517, -1, 1301, 1303, 1519, -1, 1620, 1623, 1473, -1, 1616, 1619, 1475, -1, 1611, 1615, 1477, -1, 1609, 1612, 1479, -1, 1604, 1609, 1481, -1, 1600, 1605, 1483, -1, 1597, 1601, 1485, -1, 1626, 1463, 1529, -1, 1626, 1529, 1627, -1, 1628, 1627, 1629, -1, 1628, 1626, 1627, -1, 1630, 1629, 1631, -1, 1630, 1628, 1629, -1, 1632, 1631, 1633, -1, 1632, 1630, 1631, -1, 1634, 1633, 1635, -1, 1634, 1632, 1633, -1, 1636, 1635, 1637, -1, 1636, 1634, 1635, -1, 1638, 1637, 1639, -1, 1638, 1636, 1637, -1, 1640, 1639, 1641, -1, 1640, 1638, 1639, -1, 1642, 1641, 1643, -1, 1642, 1640, 1641, -1, 1644, 1643, 1645, -1, 1644, 1642, 1643, -1, 1646, 1645, 1647, -1, 1646, 1644, 1645, -1, 1648, 1647, 1649, -1, 1648, 1646, 1647, -1, 1650, 1649, 1651, -1, 1650, 1648, 1649, -1, 1652, 1651, 1653, -1, 1652, 1650, 1651, -1, 1654, 1653, 1655, -1, 1654, 1652, 1653, -1, 1495, 1654, 1655, -1, 1495, 1655, 1497, -1, 1584, 1582, 1656, -1, 1657, 1506, 1658, -1, 1508, 1506, 1657, -1, 1659, 1584, 1656, -1, 1586, 1584, 1659, -1, 1568, 1660, 1661, -1, 1662, 1508, 1657, -1, 1566, 1663, 1660, -1, 1566, 1660, 1568, -1, 1570, 1661, 1664, -1, 1570, 1568, 1661, -1, 1510, 1662, 1665, -1, 1564, 1666, 1663, -1, 1564, 1663, 1566, -1, 1510, 1508, 1662, -1, 1667, 1588, 1586, -1, 1667, 1586, 1659, -1, 1572, 1664, 1668, -1, 1572, 1570, 1664, -1, 1512, 1510, 1665, -1, 1561, 1669, 1666, -1, 1561, 1666, 1564, -1, 1528, 1588, 1667, -1, 1574, 1668, 1670, -1, 1574, 1670, 1671, -1, 1574, 1572, 1668, -1, 1560, 1498, 1669, -1, 1514, 1665, 1672, -1, 1560, 1496, 1498, -1, 1560, 1669, 1561, -1, 1514, 1512, 1665, -1, 1576, 1574, 1671, -1, 1673, 1496, 1560, -1, 1526, 1674, 1588, -1, 1526, 1588, 1528, -1, 1500, 1496, 1673, -1, 1516, 1672, 1675, -1, 1676, 1576, 1671, -1, 1516, 1514, 1672, -1, 1578, 1576, 1676, -1, 1524, 1677, 1674, -1, 1524, 1674, 1526, -1, 1518, 1675, 1678, -1, 1679, 1500, 1673, -1, 1518, 1516, 1675, -1, 1502, 1500, 1679, -1, 1522, 1680, 1677, -1, 1681, 1578, 1676, -1, 1522, 1677, 1524, -1, 1580, 1578, 1681, -1, 1520, 1678, 1680, -1, 1520, 1680, 1522, -1, 1520, 1518, 1678, -1, 1682, 1502, 1679, -1, 1504, 1502, 1682, -1, 1683, 1580, 1681, -1, 1582, 1580, 1683, -1, 1658, 1504, 1682, -1, 1506, 1504, 1658, -1, 1656, 1582, 1683, -1, 1537, 1535, 1684, -1, 1484, 1685, 1686, -1, 1535, 1687, 1684, -1, 1484, 1482, 1685, -1, 1535, 1533, 1687, -1, 1482, 1688, 1685, -1, 1689, 1551, 1690, -1, 1691, 1553, 1689, -1, 1689, 1553, 1551, -1, 1690, 1549, 1692, -1, 1551, 1549, 1690, -1, 1530, 1693, 1533, -1, 1694, 1555, 1691, -1, 1533, 1693, 1687, -1, 1691, 1555, 1553, -1, 1688, 1480, 1695, -1, 1482, 1480, 1688, -1, 1692, 1547, 1696, -1, 1549, 1547, 1692, -1, 1530, 1464, 1693, -1, 1697, 1557, 1694, -1, 1480, 1478, 1695, -1, 1694, 1557, 1555, -1, 1698, 1545, 1699, -1, 1696, 1545, 1698, -1, 1547, 1545, 1696, -1, 1494, 1559, 1697, -1, 1492, 1559, 1494, -1, 1697, 1559, 1557, -1, 1700, 1462, 1530, -1, 1545, 1543, 1699, -1, 1530, 1462, 1464, -1, 1492, 1701, 1559, -1, 1695, 1476, 1702, -1, 1543, 1703, 1699, -1, 1478, 1476, 1695, -1, 1704, 1466, 1700, -1, 1492, 1490, 1701, -1, 1700, 1466, 1462, -1, 1543, 1541, 1703, -1, 1702, 1474, 1705, -1, 1476, 1474, 1702, -1, 1490, 1706, 1701, -1, 1707, 1468, 1704, -1, 1541, 1708, 1703, -1, 1704, 1468, 1466, -1, 1705, 1472, 1709, -1, 1490, 1488, 1706, -1, 1474, 1472, 1705, -1, 1709, 1470, 1707, -1, 1707, 1470, 1468, -1, 1541, 1539, 1708, -1, 1472, 1470, 1709, -1, 1488, 1710, 1706, -1, 1539, 1711, 1708, -1, 1488, 1486, 1710, -1, 1539, 1537, 1711, -1, 1486, 1686, 1710, -1, 1537, 1684, 1711, -1, 1486, 1484, 1686, -1, 1558, 1712, 1562, -1, 1562, 1712, 1713, -1, 1713, 1714, 1715, -1, 1712, 1714, 1713, -1, 1716, 1717, 1718, -1, 1715, 1717, 1716, -1, 1714, 1717, 1715, -1, 1717, 1719, 1718, -1, 1720, 1721, 1722, -1, 1718, 1721, 1720, -1, 1719, 1721, 1718, -1, 1722, 1723, 1724, -1, 1721, 1723, 1722, -1, 1723, 1725, 1724, -1, 1726, 1727, 1728, -1, 1724, 1727, 1726, -1, 1725, 1727, 1724, -1, 1728, 1729, 1730, -1, 1727, 1729, 1728, -1, 1730, 1731, 1732, -1, 1729, 1731, 1730, -1, 1731, 1733, 1732, -1, 1732, 1734, 1735, -1, 1733, 1734, 1732, -1, 1735, 1736, 1737, -1, 1734, 1736, 1735, -1, 1737, 1532, 1589, -1, 1736, 1532, 1737, -1, 1588, 1674, 1589, -1, 1589, 1674, 1737, -1, 1737, 1677, 1735, -1, 1674, 1677, 1737, -1, 1735, 1680, 1732, -1, 1677, 1680, 1735, -1, 1732, 1678, 1730, -1, 1680, 1678, 1732, -1, 1730, 1675, 1728, -1, 1678, 1675, 1730, -1, 1728, 1672, 1726, -1, 1675, 1672, 1728, -1, 1726, 1665, 1724, -1, 1672, 1665, 1726, -1, 1724, 1662, 1722, -1, 1665, 1662, 1724, -1, 1722, 1657, 1720, -1, 1662, 1657, 1722, -1, 1720, 1658, 1718, -1, 1657, 1658, 1720, -1, 1718, 1682, 1716, -1, 1658, 1682, 1718, -1, 1716, 1679, 1715, -1, 1682, 1679, 1716, -1, 1715, 1673, 1713, -1, 1679, 1673, 1715, -1, 1713, 1560, 1562, -1, 1673, 1560, 1713, -1, 1559, 1701, 1558, -1, 1558, 1701, 1712, -1, 1712, 1706, 1714, -1, 1701, 1706, 1712, -1, 1714, 1710, 1717, -1, 1706, 1710, 1714, -1, 1717, 1686, 1719, -1, 1710, 1686, 1717, -1, 1719, 1685, 1721, -1, 1686, 1685, 1719, -1, 1721, 1688, 1723, -1, 1685, 1688, 1721, -1, 1723, 1695, 1725, -1, 1688, 1695, 1723, -1, 1725, 1702, 1727, -1, 1695, 1702, 1725, -1, 1727, 1705, 1729, -1, 1702, 1705, 1727, -1, 1729, 1709, 1731, -1, 1705, 1709, 1729, -1, 1731, 1707, 1733, -1, 1709, 1707, 1731, -1, 1733, 1704, 1734, -1, 1707, 1704, 1733, -1, 1734, 1700, 1736, -1, 1704, 1700, 1734, -1, 1736, 1530, 1532, -1, 1700, 1530, 1736, -1, 1667, 1529, 1528, -1, 1627, 1529, 1667, -1, 1659, 1627, 1667, -1, 1629, 1627, 1659, -1, 1656, 1629, 1659, -1, 1631, 1629, 1656, -1, 1683, 1631, 1656, -1, 1633, 1631, 1683, -1, 1681, 1633, 1683, -1, 1635, 1633, 1681, -1, 1676, 1635, 1681, -1, 1637, 1635, 1676, -1, 1671, 1637, 1676, -1, 1639, 1637, 1671, -1, 1670, 1639, 1671, -1, 1641, 1639, 1670, -1, 1668, 1641, 1670, -1, 1643, 1641, 1668, -1, 1664, 1643, 1668, -1, 1645, 1643, 1664, -1, 1661, 1645, 1664, -1, 1647, 1645, 1661, -1, 1660, 1647, 1661, -1, 1649, 1647, 1660, -1, 1663, 1649, 1660, -1, 1651, 1649, 1663, -1, 1666, 1651, 1663, -1, 1653, 1651, 1666, -1, 1669, 1653, 1666, -1, 1655, 1653, 1669, -1, 1497, 1655, 1669, -1, 1497, 1669, 1498, -1, 1654, 1495, 1494, -1, 1654, 1494, 1697, -1, 1694, 1654, 1697, -1, 1652, 1654, 1694, -1, 1691, 1652, 1694, -1, 1650, 1652, 1691, -1, 1689, 1650, 1691, -1, 1648, 1650, 1689, -1, 1690, 1648, 1689, -1, 1646, 1648, 1690, -1, 1692, 1646, 1690, -1, 1644, 1646, 1692, -1, 1696, 1644, 1692, -1, 1642, 1644, 1696, -1, 1698, 1642, 1696, -1, 1640, 1642, 1698, -1, 1699, 1640, 1698, -1, 1638, 1640, 1699, -1, 1703, 1638, 1699, -1, 1636, 1638, 1703, -1, 1708, 1636, 1703, -1, 1634, 1636, 1708, -1, 1711, 1634, 1708, -1, 1632, 1634, 1711, -1, 1684, 1632, 1711, -1, 1630, 1632, 1684, -1, 1687, 1630, 1684, -1, 1628, 1630, 1687, -1, 1693, 1628, 1687, -1, 1626, 1628, 1693, -1, 1464, 1626, 1693, -1, 1463, 1626, 1464, -1, 1738, 1334, 1461, -1, 1739, 1334, 1738, -1, 1740, 1739, 1738, -1, 1741, 1739, 1740, -1, 1742, 1741, 1740, -1, 1743, 1741, 1742, -1, 1744, 1743, 1742, -1, 1745, 1743, 1744, -1, 1746, 1745, 1744, -1, 1747, 1745, 1746, -1, 1748, 1747, 1746, -1, 1749, 1747, 1748, -1, 1750, 1749, 1748, -1, 1751, 1749, 1750, -1, 1752, 1751, 1750, -1, 1753, 1751, 1752, -1, 1754, 1753, 1752, -1, 1755, 1753, 1754, -1, 1756, 1755, 1754, -1, 1757, 1755, 1756, -1, 1758, 1757, 1756, -1, 1759, 1757, 1758, -1, 1760, 1759, 1758, -1, 1761, 1759, 1760, -1, 1762, 1761, 1760, -1, 1763, 1761, 1762, -1, 1764, 1763, 1762, -1, 1765, 1763, 1764, -1, 1766, 1765, 1764, -1, 1767, 1765, 1766, -1, 1446, 1767, 1766, -1, 1367, 1767, 1446, -1, 1768, 1366, 1444, -1, 1769, 1366, 1768, -1, 1770, 1769, 1768, -1, 1771, 1769, 1770, -1, 1772, 1771, 1770, -1, 1773, 1771, 1772, -1, 1774, 1773, 1772, -1, 1775, 1773, 1774, -1, 1776, 1775, 1774, -1, 1777, 1775, 1776, -1, 1778, 1777, 1776, -1, 1779, 1777, 1778, -1, 1780, 1779, 1778, -1, 1781, 1779, 1780, -1, 1782, 1781, 1780, -1, 1783, 1781, 1782, -1, 1784, 1783, 1782, -1, 1785, 1783, 1784, -1, 1786, 1785, 1784, -1, 1787, 1785, 1786, -1, 1788, 1787, 1786, -1, 1789, 1787, 1788, -1, 1790, 1789, 1788, -1, 1791, 1789, 1790, -1, 1792, 1791, 1790, -1, 1793, 1791, 1792, -1, 1794, 1793, 1792, -1, 1795, 1793, 1794, -1, 1796, 1795, 1794, -1, 1797, 1795, 1796, -1, 1429, 1797, 1796, -1, 1335, 1797, 1429, -1, 1427, 1798, 1370, -1, 1370, 1798, 1799, -1, 1799, 1800, 1801, -1, 1798, 1800, 1799, -1, 1801, 1802, 1803, -1, 1800, 1802, 1801, -1, 1803, 1804, 1805, -1, 1802, 1804, 1803, -1, 1805, 1806, 1807, -1, 1804, 1806, 1805, -1, 1807, 1808, 1809, -1, 1806, 1808, 1807, -1, 1809, 1810, 1811, -1, 1808, 1810, 1809, -1, 1811, 1812, 1813, -1, 1810, 1812, 1811, -1, 1813, 1814, 1815, -1, 1812, 1814, 1813, -1, 1815, 1816, 1817, -1, 1814, 1816, 1815, -1, 1817, 1818, 1819, -1, 1816, 1818, 1817, -1, 1819, 1820, 1821, -1, 1818, 1820, 1819, -1, 1821, 1822, 1823, -1, 1820, 1822, 1821, -1, 1823, 1413, 1397, -1, 1822, 1413, 1823, -1, 1412, 1824, 1396, -1, 1396, 1824, 1825, -1, 1824, 1826, 1825, -1, 1824, 1827, 1826, -1, 1827, 1828, 1826, -1, 1827, 1829, 1828, -1, 1829, 1830, 1828, -1, 1829, 1831, 1830, -1, 1831, 1832, 1830, -1, 1831, 1833, 1832, -1, 1832, 1834, 1835, -1, 1833, 1834, 1832, -1, 1834, 1836, 1835, -1, 1834, 1837, 1836, -1, 1836, 1838, 1839, -1, 1837, 1838, 1836, -1, 1839, 1840, 1841, -1, 1838, 1840, 1839, -1, 1840, 1842, 1841, -1, 1840, 1843, 1842, -1, 1842, 1844, 1845, -1, 1843, 1844, 1842, -1, 1845, 1846, 1847, -1, 1844, 1846, 1845, -1, 1847, 1848, 1849, -1, 1846, 1848, 1847, -1, 1848, 1368, 1849, -1, 1848, 1398, 1368, -1, 1397, 1396, 1823, -1, 1823, 1825, 1821, -1, 1396, 1825, 1823, -1, 1821, 1826, 1819, -1, 1825, 1826, 1821, -1, 1819, 1828, 1817, -1, 1826, 1828, 1819, -1, 1817, 1830, 1815, -1, 1828, 1830, 1817, -1, 1815, 1832, 1813, -1, 1830, 1832, 1815, -1, 1813, 1835, 1811, -1, 1832, 1835, 1813, -1, 1811, 1836, 1809, -1, 1835, 1836, 1811, -1, 1809, 1839, 1807, -1, 1836, 1839, 1809, -1, 1807, 1841, 1805, -1, 1839, 1841, 1807, -1, 1805, 1842, 1803, -1, 1841, 1842, 1805, -1, 1803, 1845, 1801, -1, 1842, 1845, 1803, -1, 1801, 1847, 1799, -1, 1845, 1847, 1801, -1, 1799, 1849, 1370, -1, 1847, 1849, 1799, -1, 1849, 1368, 1370, -1, 1742, 1409, 1744, -1, 1450, 1449, 1843, -1, 1840, 1450, 1843, -1, 1410, 1409, 1742, -1, 1740, 1410, 1742, -1, 1451, 1450, 1840, -1, 1401, 1762, 1760, -1, 1838, 1451, 1840, -1, 1402, 1760, 1758, -1, 1402, 1401, 1760, -1, 1411, 1410, 1740, -1, 1400, 1764, 1762, -1, 1400, 1762, 1401, -1, 1403, 1758, 1756, -1, 1403, 1402, 1758, -1, 1738, 1412, 1411, -1, 1738, 1411, 1740, -1, 1399, 1766, 1764, -1, 1399, 1764, 1400, -1, 1452, 1451, 1838, -1, 1452, 1838, 1837, -1, 1404, 1756, 1754, -1, 1404, 1403, 1756, -1, 1461, 1412, 1738, -1, 1398, 1446, 1766, -1, 1398, 1445, 1446, -1, 1453, 1452, 1837, -1, 1398, 1766, 1399, -1, 1405, 1754, 1752, -1, 1405, 1752, 1750, -1, 1405, 1404, 1754, -1, 1848, 1445, 1398, -1, 1406, 1405, 1750, -1, 1748, 1406, 1750, -1, 1460, 1824, 1412, -1, 1460, 1412, 1461, -1, 1447, 1445, 1848, -1, 1454, 1837, 1834, -1, 1454, 1453, 1837, -1, 1459, 1827, 1824, -1, 1846, 1447, 1848, -1, 1459, 1824, 1460, -1, 1407, 1406, 1748, -1, 1455, 1834, 1833, -1, 1746, 1407, 1748, -1, 1455, 1454, 1834, -1, 1458, 1829, 1827, -1, 1448, 1447, 1846, -1, 1458, 1827, 1459, -1, 1456, 1833, 1831, -1, 1456, 1455, 1833, -1, 1844, 1448, 1846, -1, 1457, 1831, 1829, -1, 1408, 1407, 1746, -1, 1457, 1829, 1458, -1, 1457, 1456, 1831, -1, 1744, 1408, 1746, -1, 1449, 1448, 1844, -1, 1843, 1449, 1844, -1, 1409, 1408, 1744, -1, 1440, 1439, 1804, -1, 1416, 1792, 1790, -1, 1439, 1806, 1804, -1, 1416, 1415, 1792, -1, 1439, 1438, 1806, -1, 1415, 1794, 1792, -1, 1772, 1424, 1774, -1, 1438, 1808, 1806, -1, 1774, 1423, 1776, -1, 1424, 1423, 1774, -1, 1415, 1414, 1794, -1, 1770, 1425, 1772, -1, 1772, 1425, 1424, -1, 1776, 1422, 1778, -1, 1423, 1422, 1776, -1, 1808, 1437, 1810, -1, 1438, 1437, 1808, -1, 1768, 1426, 1770, -1, 1413, 1796, 1414, -1, 1770, 1426, 1425, -1, 1414, 1796, 1794, -1, 1778, 1421, 1780, -1, 1422, 1421, 1778, -1, 1437, 1436, 1810, -1, 1413, 1429, 1796, -1, 1444, 1427, 1768, -1, 1443, 1427, 1444, -1, 1768, 1427, 1426, -1, 1782, 1420, 1784, -1, 1780, 1420, 1782, -1, 1421, 1420, 1780, -1, 1443, 1798, 1427, -1, 1810, 1435, 1812, -1, 1420, 1419, 1784, -1, 1436, 1435, 1810, -1, 1443, 1442, 1798, -1, 1822, 1428, 1413, -1, 1419, 1786, 1784, -1, 1413, 1428, 1429, -1, 1812, 1434, 1814, -1, 1435, 1434, 1812, -1, 1442, 1800, 1798, -1, 1820, 1430, 1822, -1, 1419, 1418, 1786, -1, 1822, 1430, 1428, -1, 1442, 1441, 1800, -1, 1814, 1433, 1816, -1, 1418, 1788, 1786, -1, 1434, 1433, 1814, -1, 1818, 1431, 1820, -1, 1820, 1431, 1430, -1, 1816, 1432, 1818, -1, 1433, 1432, 1816, -1, 1818, 1432, 1431, -1, 1441, 1802, 1800, -1, 1418, 1417, 1788, -1, 1441, 1440, 1802, -1, 1417, 1790, 1788, -1, 1440, 1804, 1802, -1, 1417, 1416, 1790, -1, 1767, 1367, 1366, -1, 1767, 1366, 1769, -1, 1765, 1769, 1771, -1, 1765, 1767, 1769, -1, 1296, 1773, 1775, -1, 1297, 1296, 1775, -1, 1763, 1771, 1773, -1, 1763, 1765, 1771, -1, 1300, 1297, 1775, -1, 1302, 1300, 1775, -1, 1777, 1302, 1775, -1, 1257, 1296, 1850, -1, 1257, 1773, 1296, -1, 1257, 1763, 1773, -1, 1258, 1850, 1851, -1, 1258, 1257, 1850, -1, 1761, 1763, 1257, -1, 1761, 1257, 1852, -1, 1261, 1851, 1853, -1, 1261, 1258, 1851, -1, 1854, 1761, 1852, -1, 1306, 1304, 1777, -1, 1263, 1853, 1855, -1, 1263, 1261, 1853, -1, 1856, 1761, 1854, -1, 1779, 1306, 1777, -1, 1265, 1855, 1857, -1, 1265, 1263, 1855, -1, 1759, 1761, 1856, -1, 1310, 1308, 1779, -1, 1267, 1857, 1858, -1, 1267, 1265, 1857, -1, 1859, 1759, 1860, -1, 1781, 1310, 1779, -1, 1269, 1858, 1861, -1, 1269, 1267, 1858, -1, 1757, 1759, 1859, -1, 1271, 1861, 1862, -1, 1271, 1269, 1861, -1, 1783, 1314, 1312, -1, 1783, 1312, 1781, -1, 1863, 1757, 1864, -1, 1273, 1271, 1862, -1, 1273, 1862, 1865, -1, 1755, 1757, 1863, -1, 1785, 1315, 1783, -1, 1275, 1273, 1865, -1, 1753, 1755, 1866, -1, 1753, 1866, 1867, -1, 1276, 1275, 1865, -1, 1276, 1865, 1868, -1, 1787, 1317, 1785, -1, 1787, 1319, 1317, -1, 1278, 1276, 1868, -1, 1278, 1868, 1869, -1, 1751, 1753, 1870, -1, 1280, 1278, 1869, -1, 1280, 1869, 1871, -1, 1789, 1321, 1787, -1, 1789, 1323, 1321, -1, 1749, 1872, 1873, -1, 1749, 1751, 1872, -1, 1282, 1280, 1871, -1, 1282, 1871, 1874, -1, 1284, 1282, 1874, -1, 1284, 1874, 1875, -1, 1791, 1325, 1789, -1, 1791, 1327, 1325, -1, 1791, 1329, 1327, -1, 1331, 1329, 1791, -1, 1333, 1331, 1791, -1, 1286, 1875, 1876, -1, 1286, 1284, 1875, -1, 1747, 1877, 1878, -1, 1747, 1749, 1877, -1, 1288, 1286, 1876, -1, 1288, 1876, 1879, -1, 1793, 1333, 1791, -1, 1290, 1288, 1879, -1, 1290, 1879, 1880, -1, 1292, 1290, 1880, -1, 1292, 1880, 1333, -1, 1294, 1292, 1333, -1, 1745, 1747, 1881, -1, 1745, 1882, 1294, -1, 1745, 1883, 1882, -1, 1745, 1881, 1883, -1, 1743, 1294, 1333, -1, 1743, 1333, 1793, -1, 1743, 1745, 1294, -1, 1741, 1793, 1795, -1, 1741, 1743, 1793, -1, 1739, 1795, 1797, -1, 1739, 1741, 1795, -1, 1334, 1797, 1335, -1, 1334, 1739, 1797, -1, 1878, 1881, 1747, -1, 1873, 1877, 1749, -1, 1870, 1872, 1751, -1, 1867, 1870, 1753, -1, 1863, 1866, 1755, -1, 1859, 1864, 1757, -1, 1856, 1860, 1759, -1, 1304, 1302, 1777, -1, 1308, 1306, 1779, -1, 1312, 1310, 1781, -1, 1315, 1314, 1783, -1, 1317, 1315, 1785, -1, 1321, 1319, 1787, -1, 1325, 1323, 1789, -1, 1590, 1332, 1333, -1, 1590, 1333, 1880, -1, 1591, 1880, 1879, -1, 1591, 1590, 1880, -1, 1594, 1879, 1876, -1, 1594, 1591, 1879, -1, 1596, 1876, 1875, -1, 1596, 1594, 1876, -1, 1598, 1875, 1874, -1, 1598, 1596, 1875, -1, 1599, 1874, 1871, -1, 1599, 1598, 1874, -1, 1602, 1871, 1869, -1, 1602, 1599, 1871, -1, 1603, 1869, 1868, -1, 1603, 1602, 1869, -1, 1606, 1868, 1865, -1, 1606, 1603, 1868, -1, 1607, 1606, 1865, -1, 1608, 1865, 1862, -1, 1608, 1607, 1865, -1, 1610, 1862, 1861, -1, 1610, 1608, 1862, -1, 1613, 1861, 1858, -1, 1613, 1610, 1861, -1, 1614, 1858, 1857, -1, 1614, 1613, 1858, -1, 1617, 1857, 1855, -1, 1617, 1614, 1857, -1, 1618, 1617, 1855, -1, 1618, 1855, 1853, -1, 1621, 1618, 1853, -1, 1621, 1853, 1851, -1, 1622, 1621, 1851, -1, 1622, 1851, 1850, -1, 1298, 1622, 1850, -1, 1298, 1850, 1296, -1, 1592, 1293, 1294, -1, 1592, 1294, 1882, -1, 1593, 1882, 1883, -1, 1593, 1592, 1882, -1, 1595, 1883, 1881, -1, 1595, 1593, 1883, -1, 1597, 1881, 1878, -1, 1597, 1595, 1881, -1, 1601, 1878, 1877, -1, 1601, 1597, 1878, -1, 1600, 1877, 1873, -1, 1600, 1601, 1877, -1, 1605, 1873, 1872, -1, 1605, 1600, 1873, -1, 1604, 1872, 1870, -1, 1604, 1605, 1872, -1, 1609, 1870, 1867, -1, 1609, 1604, 1870, -1, 1612, 1609, 1867, -1, 1611, 1867, 1866, -1, 1611, 1612, 1867, -1, 1615, 1866, 1863, -1, 1615, 1611, 1866, -1, 1616, 1863, 1864, -1, 1616, 1615, 1863, -1, 1619, 1864, 1859, -1, 1619, 1616, 1864, -1, 1620, 1859, 1860, -1, 1620, 1619, 1859, -1, 1623, 1620, 1860, -1, 1623, 1860, 1856, -1, 1625, 1623, 1856, -1, 1625, 1856, 1854, -1, 1624, 1625, 1854, -1, 1624, 1854, 1852, -1, 1259, 1624, 1852, -1, 1259, 1852, 1257, -1, 1884, 1885, 1886, -1, 1884, 1887, 1885, -1, 1888, 1886, 1889, -1, 1888, 1884, 1886, -1, 1890, 1889, 1891, -1, 1890, 1888, 1889, -1, 1892, 1891, 1893, -1, 1892, 1890, 1891, -1, 1894, 1893, 1895, -1, 1894, 1892, 1893, -1, 1896, 1895, 1897, -1, 1896, 1894, 1895, -1, 1898, 1897, 1899, -1, 1898, 1896, 1897, -1, 1900, 1899, 1901, -1, 1900, 1898, 1899, -1, 1902, 1901, 1903, -1, 1902, 1903, 1904, -1, 1902, 1900, 1901, -1, 1905, 1904, 1906, -1, 1905, 1902, 1904, -1, 1907, 1906, 1908, -1, 1907, 1905, 1906, -1, 1909, 1908, 1910, -1, 1909, 1907, 1908, -1, 1911, 1910, 1912, -1, 1911, 1909, 1910, -1, 1913, 1912, 1914, -1, 1913, 1911, 1912, -1, 1915, 1913, 1914, -1, 1915, 1914, 1916, -1, 1917, 1915, 1916, -1, 1917, 1916, 1918, -1, 1919, 1917, 1918, -1, 1919, 1918, 1920, -1, 1921, 1919, 1920, -1, 1921, 1920, 1922, -1, 1923, 1924, 1925, -1, 1923, 1926, 1924, -1, 1927, 1925, 1928, -1, 1927, 1923, 1925, -1, 1929, 1928, 1930, -1, 1929, 1927, 1928, -1, 1931, 1930, 1932, -1, 1931, 1929, 1930, -1, 1933, 1932, 1934, -1, 1933, 1931, 1932, -1, 1935, 1934, 1936, -1, 1935, 1933, 1934, -1, 1937, 1936, 1938, -1, 1937, 1935, 1936, -1, 1939, 1938, 1940, -1, 1939, 1937, 1938, -1, 1941, 1940, 1942, -1, 1941, 1942, 1943, -1, 1941, 1939, 1940, -1, 1944, 1943, 1945, -1, 1944, 1941, 1943, -1, 1946, 1945, 1947, -1, 1946, 1944, 1945, -1, 1948, 1947, 1949, -1, 1948, 1946, 1947, -1, 1950, 1949, 1951, -1, 1950, 1948, 1949, -1, 1952, 1951, 1953, -1, 1952, 1950, 1951, -1, 1954, 1952, 1953, -1, 1954, 1953, 1955, -1, 1956, 1954, 1955, -1, 1956, 1955, 1957, -1, 1958, 1956, 1957, -1, 1958, 1957, 1959, -1, 1960, 1958, 1959, -1, 1960, 1959, 1961, -1, 1962, 1963, 1964, -1, 1965, 1964, 1966, -1, 1965, 1962, 1964, -1, 1967, 1966, 1968, -1, 1967, 1965, 1966, -1, 1969, 1968, 1970, -1, 1969, 1967, 1968, -1, 1971, 1970, 1972, -1, 1971, 1969, 1970, -1, 1973, 1972, 1974, -1, 1973, 1971, 1972, -1, 1975, 1974, 1976, -1, 1975, 1973, 1974, -1, 1977, 1976, 1978, -1, 1977, 1975, 1976, -1, 1979, 1978, 1980, -1, 1979, 1977, 1978, -1, 1981, 1980, 1982, -1, 1981, 1979, 1980, -1, 1983, 1982, 1984, -1, 1983, 1981, 1982, -1, 1985, 1984, 1986, -1, 1985, 1983, 1984, -1, 1987, 1986, 1988, -1, 1987, 1985, 1986, -1, 1989, 1988, 1990, -1, 1989, 1987, 1988, -1, 1991, 1990, 1992, -1, 1991, 1989, 1990, -1, 1993, 1992, 1994, -1, 1993, 1991, 1992, -1, 1995, 1993, 1994, -1, 1996, 1997, 1998, -1, 1998, 1999, 2000, -1, 1997, 1999, 1998, -1, 1999, 2001, 2000, -1, 2000, 2002, 2003, -1, 2001, 2002, 2000, -1, 2003, 2004, 2005, -1, 2002, 2004, 2003, -1, 2005, 2006, 2007, -1, 2004, 2006, 2005, -1, 2007, 2008, 2009, -1, 2006, 2008, 2007, -1, 2009, 2010, 2011, -1, 2008, 2010, 2009, -1, 2011, 2012, 2013, -1, 2010, 2012, 2011, -1, 2013, 2014, 2015, -1, 2012, 2014, 2013, -1, 2015, 2016, 2017, -1, 2014, 2016, 2015, -1, 2017, 2018, 2019, -1, 2016, 2018, 2017, -1, 2019, 2020, 2021, -1, 2018, 2020, 2019, -1, 2021, 2022, 2023, -1, 2020, 2022, 2021, -1, 2023, 2024, 2025, -1, 2022, 2024, 2023, -1, 2026, 1999, 1997, -1, 2026, 2027, 1999, -1, 1999, 2028, 2001, -1, 2027, 2028, 1999, -1, 2028, 2002, 2001, -1, 2028, 2029, 2002, -1, 2029, 2004, 2002, -1, 2029, 2030, 2004, -1, 2030, 2006, 2004, -1, 2030, 2031, 2006, -1, 2031, 2008, 2006, -1, 2031, 2032, 2008, -1, 2032, 2010, 2008, -1, 2032, 2033, 2010, -1, 2010, 2034, 2012, -1, 2033, 2034, 2010, -1, 2034, 2014, 2012, -1, 2034, 2035, 2014, -1, 2014, 2036, 2016, -1, 2035, 2036, 2014, -1, 2036, 2018, 2016, -1, 2036, 2037, 2018, -1, 2018, 2038, 2020, -1, 2037, 2038, 2018, -1, 2020, 2039, 2022, -1, 2038, 2039, 2020, -1, 2022, 2040, 2024, -1, 2039, 2040, 2022, -1, 2041, 2042, 2025, -1, 2025, 2042, 2023, -1, 2023, 2043, 2021, -1, 2042, 2043, 2023, -1, 2021, 2044, 2019, -1, 2043, 2044, 2021, -1, 2019, 2045, 2017, -1, 2044, 2045, 2019, -1, 2045, 2015, 2017, -1, 2045, 2046, 2015, -1, 2046, 2013, 2015, -1, 2046, 2047, 2013, -1, 2013, 2048, 2011, -1, 2047, 2048, 2013, -1, 2011, 2049, 2009, -1, 2048, 2049, 2011, -1, 2009, 2050, 2007, -1, 2049, 2050, 2009, -1, 2007, 2051, 2005, -1, 2050, 2051, 2007, -1, 2005, 2052, 2003, -1, 2051, 2052, 2005, -1, 2003, 2053, 2000, -1, 2052, 2053, 2003, -1, 2000, 2054, 1998, -1, 2053, 2054, 2000, -1, 1998, 2055, 1996, -1, 2054, 2055, 1998, -1, 2056, 1963, 2057, -1, 1964, 1963, 2056, -1, 2058, 1964, 2056, -1, 1966, 1964, 2058, -1, 2059, 1966, 2058, -1, 1968, 1966, 2059, -1, 2060, 1968, 2059, -1, 1970, 1968, 2060, -1, 2061, 1970, 2060, -1, 1972, 1970, 2061, -1, 2062, 1972, 2061, -1, 1974, 1972, 2062, -1, 2063, 1974, 2062, -1, 1976, 1974, 2063, -1, 2064, 1976, 2063, -1, 1978, 1976, 2064, -1, 2065, 1978, 2064, -1, 1980, 1978, 2065, -1, 2066, 1980, 2065, -1, 1982, 1980, 2066, -1, 2067, 1982, 2066, -1, 1984, 1982, 2067, -1, 2068, 1984, 2067, -1, 1986, 1984, 2068, -1, 2069, 1986, 2068, -1, 1988, 1986, 2069, -1, 2070, 1988, 2069, -1, 1990, 1988, 2070, -1, 2071, 1990, 2070, -1, 1992, 1990, 2071, -1, 2072, 1992, 2071, -1, 1994, 1992, 2072, -1, 2073, 1995, 2074, -1, 1993, 1995, 2073, -1, 2075, 1993, 2073, -1, 1991, 1993, 2075, -1, 2076, 1991, 2075, -1, 1989, 1991, 2076, -1, 2077, 1989, 2076, -1, 1987, 1989, 2077, -1, 2078, 1987, 2077, -1, 1985, 1987, 2078, -1, 2079, 1985, 2078, -1, 1983, 1985, 2079, -1, 2080, 1983, 2079, -1, 1981, 1983, 2080, -1, 2081, 1981, 2080, -1, 1979, 1981, 2081, -1, 2082, 1979, 2081, -1, 1977, 1979, 2082, -1, 2083, 1977, 2082, -1, 1975, 1977, 2083, -1, 2084, 1975, 2083, -1, 1973, 1975, 2084, -1, 2085, 1973, 2084, -1, 1971, 1973, 2085, -1, 2086, 1971, 2085, -1, 1969, 1971, 2086, -1, 2087, 1969, 2086, -1, 1967, 1969, 2087, -1, 2088, 1967, 2087, -1, 1965, 1967, 2088, -1, 2089, 1965, 2088, -1, 1962, 1965, 2089, -1, 2090, 2091, 2092, -1, 2093, 2091, 2090, -1, 2094, 2093, 2090, -1, 2095, 2093, 2094, -1, 2096, 2095, 2094, -1, 2097, 2095, 2096, -1, 2098, 2097, 2096, -1, 2099, 2097, 2098, -1, 2100, 2099, 2098, -1, 2101, 2099, 2100, -1, 2102, 2101, 2100, -1, 2103, 2101, 2102, -1, 2104, 2103, 2102, -1, 2105, 2103, 2104, -1, 2106, 2105, 2104, -1, 2107, 2105, 2106, -1, 2108, 2107, 2106, -1, 2109, 2107, 2108, -1, 2110, 2109, 2108, -1, 2111, 2109, 2110, -1, 2112, 2111, 2110, -1, 2113, 2111, 2112, -1, 2114, 2113, 2112, -1, 2115, 2113, 2114, -1, 2116, 2115, 2114, -1, 2117, 2115, 2116, -1, 2118, 2117, 2116, -1, 2119, 2117, 2118, -1, 2120, 2119, 2118, -1, 2121, 2119, 2120, -1, 2122, 2121, 2120, -1, 2123, 2121, 2122, -1, 2124, 2125, 2126, -1, 2127, 2125, 2124, -1, 2128, 2127, 2124, -1, 2129, 2127, 2128, -1, 2130, 2129, 2128, -1, 2131, 2129, 2130, -1, 2132, 2131, 2130, -1, 2133, 2131, 2132, -1, 2134, 2133, 2132, -1, 2135, 2133, 2134, -1, 2136, 2135, 2134, -1, 2137, 2135, 2136, -1, 2138, 2137, 2136, -1, 2139, 2137, 2138, -1, 2140, 2139, 2138, -1, 2141, 2139, 2140, -1, 2142, 2141, 2140, -1, 2143, 2141, 2142, -1, 2144, 2143, 2142, -1, 2145, 2143, 2144, -1, 2146, 2145, 2144, -1, 2147, 2145, 2146, -1, 2148, 2147, 2146, -1, 2149, 2147, 2148, -1, 2150, 2149, 2148, -1, 2151, 2149, 2150, -1, 2152, 2151, 2150, -1, 2153, 2151, 2152, -1, 2154, 2153, 2152, -1, 2155, 2153, 2154, -1, 2156, 2155, 2154, -1, 2157, 2155, 2156, -1, 2158, 2159, 2160, -1, 2160, 2159, 2161, -1, 2161, 2162, 2163, -1, 2159, 2162, 2161, -1, 2163, 2164, 2165, -1, 2162, 2164, 2163, -1, 2165, 2166, 2167, -1, 2164, 2166, 2165, -1, 2167, 2168, 2169, -1, 2166, 2168, 2167, -1, 2169, 2170, 2171, -1, 2168, 2170, 2169, -1, 2171, 2172, 2173, -1, 2170, 2172, 2171, -1, 2173, 2174, 2175, -1, 2172, 2174, 2173, -1, 2175, 2176, 2177, -1, 2174, 2176, 2175, -1, 2177, 2178, 2179, -1, 2176, 2178, 2177, -1, 2179, 2180, 2181, -1, 2178, 2180, 2179, -1, 2181, 2182, 2183, -1, 2180, 2182, 2181, -1, 2183, 2184, 2185, -1, 2182, 2184, 2183, -1, 2185, 2186, 2187, -1, 2184, 2186, 2185, -1, 2188, 2189, 2190, -1, 2188, 2191, 2189, -1, 2191, 2192, 2189, -1, 2191, 2193, 2192, -1, 2193, 2194, 2192, -1, 2193, 2195, 2194, -1, 2195, 2196, 2194, -1, 2195, 2197, 2196, -1, 2197, 2198, 2196, -1, 2197, 2199, 2198, -1, 2199, 2200, 2198, -1, 2199, 2201, 2200, -1, 2201, 2202, 2200, -1, 2201, 2203, 2202, -1, 2203, 2204, 2202, -1, 2203, 2205, 2204, -1, 2205, 2206, 2204, -1, 2205, 2207, 2206, -1, 2207, 2208, 2206, -1, 2207, 2209, 2208, -1, 2209, 2210, 2208, -1, 2209, 2211, 2210, -1, 2211, 2212, 2210, -1, 2211, 2213, 2212, -1, 2213, 2214, 2212, -1, 2213, 2215, 2214, -1, 2215, 2216, 2214, -1, 2215, 2217, 2216, -1, 2160, 2161, 2216, -1, 2216, 2161, 2214, -1, 2214, 2163, 2212, -1, 2161, 2163, 2214, -1, 2212, 2165, 2210, -1, 2163, 2165, 2212, -1, 2210, 2167, 2208, -1, 2165, 2167, 2210, -1, 2208, 2169, 2206, -1, 2167, 2169, 2208, -1, 2206, 2171, 2204, -1, 2169, 2171, 2206, -1, 2202, 2173, 2200, -1, 2204, 2173, 2202, -1, 2171, 2173, 2204, -1, 2173, 2175, 2200, -1, 2200, 2177, 2198, -1, 2175, 2177, 2200, -1, 2198, 2179, 2196, -1, 2177, 2179, 2198, -1, 2196, 2181, 2194, -1, 2179, 2181, 2196, -1, 2192, 2183, 2189, -1, 2194, 2183, 2192, -1, 2181, 2183, 2194, -1, 2183, 2185, 2189, -1, 2189, 2187, 2190, -1, 2185, 2187, 2189, -1, 2121, 2123, 2125, -1, 2121, 2125, 2127, -1, 2119, 2121, 2127, -1, 2119, 2127, 2129, -1, 1960, 2131, 2133, -1, 1958, 1960, 2133, -1, 2117, 2119, 2129, -1, 2117, 2129, 2131, -1, 1956, 1958, 2133, -1, 1954, 1956, 2133, -1, 2135, 1954, 2133, -1, 1921, 1960, 2218, -1, 1921, 2131, 1960, -1, 1921, 2117, 2131, -1, 1919, 2218, 2219, -1, 1919, 1921, 2218, -1, 2115, 2117, 1921, -1, 2115, 1921, 2220, -1, 2221, 2115, 2220, -1, 1917, 2219, 2222, -1, 1917, 1919, 2219, -1, 1950, 1952, 2135, -1, 2223, 2115, 2221, -1, 1915, 2222, 2224, -1, 1915, 1917, 2222, -1, 2137, 1950, 2135, -1, 2225, 2115, 2223, -1, 1913, 2224, 2226, -1, 1913, 1915, 2224, -1, 2113, 2115, 2225, -1, 1911, 2226, 2227, -1, 1911, 1913, 2226, -1, 1946, 1948, 2137, -1, 2139, 1946, 2137, -1, 2228, 2113, 2229, -1, 1909, 2227, 2230, -1, 1909, 1911, 2227, -1, 2111, 2113, 2228, -1, 1907, 2230, 2231, -1, 1907, 1909, 2230, -1, 2141, 1944, 2139, -1, 2232, 2111, 2233, -1, 2109, 2111, 2232, -1, 1905, 2231, 2234, -1, 1905, 1907, 2231, -1, 1939, 1941, 2141, -1, 2143, 1939, 2141, -1, 1902, 1905, 2234, -1, 1902, 2235, 2236, -1, 1902, 2234, 2235, -1, 2107, 2109, 2237, -1, 1900, 2236, 2238, -1, 1900, 1902, 2236, -1, 2145, 1935, 1937, -1, 2145, 1937, 2143, -1, 2239, 2107, 2240, -1, 2105, 2107, 2239, -1, 1898, 2238, 2241, -1, 1898, 1900, 2238, -1, 2147, 1933, 2145, -1, 1931, 1933, 2147, -1, 1896, 2241, 2242, -1, 1896, 1898, 2241, -1, 2103, 2243, 2244, -1, 2103, 2105, 2243, -1, 1894, 2242, 2245, -1, 1894, 1896, 2242, -1, 2149, 1927, 1929, -1, 2149, 1929, 2147, -1, 1923, 1927, 2149, -1, 1892, 2245, 2246, -1, 1892, 1894, 2245, -1, 1926, 1923, 2149, -1, 2101, 2247, 2248, -1, 2101, 2103, 2247, -1, 1890, 2246, 2249, -1, 1890, 1892, 2246, -1, 1888, 2249, 2250, -1, 1888, 1890, 2249, -1, 2151, 1926, 2149, -1, 1884, 2250, 1926, -1, 1884, 1888, 2250, -1, 1887, 1884, 1926, -1, 2099, 2101, 2251, -1, 2099, 2252, 1887, -1, 2099, 2253, 2252, -1, 2099, 2251, 2253, -1, 2097, 2099, 1887, -1, 2097, 1887, 1926, -1, 2097, 1926, 2151, -1, 2095, 2097, 2151, -1, 2095, 2151, 2153, -1, 2093, 2095, 2153, -1, 2093, 2153, 2155, -1, 2091, 2093, 2155, -1, 2091, 2155, 2157, -1, 1952, 1954, 2135, -1, 1948, 1950, 2137, -1, 1944, 1946, 2139, -1, 1941, 1944, 2141, -1, 1937, 1939, 2143, -1, 1933, 1935, 2145, -1, 1929, 1931, 2147, -1, 2248, 2251, 2101, -1, 2244, 2247, 2103, -1, 2239, 2243, 2105, -1, 2237, 2240, 2107, -1, 2232, 2237, 2109, -1, 2228, 2233, 2111, -1, 2225, 2229, 2113, -1, 2254, 2091, 2157, -1, 2254, 2157, 2255, -1, 2256, 2255, 2257, -1, 2256, 2254, 2255, -1, 2258, 2257, 2259, -1, 2258, 2256, 2257, -1, 2260, 2259, 2261, -1, 2260, 2258, 2259, -1, 2262, 2261, 2263, -1, 2262, 2260, 2261, -1, 2264, 2263, 2265, -1, 2264, 2262, 2263, -1, 2266, 2265, 2267, -1, 2266, 2264, 2265, -1, 2268, 2267, 2269, -1, 2268, 2266, 2267, -1, 2270, 2269, 2271, -1, 2270, 2268, 2269, -1, 2272, 2271, 2273, -1, 2272, 2270, 2271, -1, 2274, 2273, 2275, -1, 2274, 2272, 2273, -1, 2276, 2275, 2277, -1, 2276, 2274, 2275, -1, 2278, 2277, 2279, -1, 2278, 2276, 2277, -1, 2280, 2279, 2281, -1, 2280, 2278, 2279, -1, 2282, 2281, 2283, -1, 2282, 2280, 2281, -1, 2123, 2282, 2283, -1, 2123, 2283, 2125, -1, 2284, 2213, 2285, -1, 2136, 2134, 2286, -1, 2287, 2136, 2286, -1, 2215, 2213, 2284, -1, 2288, 2217, 2215, -1, 2288, 2215, 2284, -1, 2197, 2289, 2290, -1, 2138, 2287, 2291, -1, 2138, 2136, 2287, -1, 2195, 2292, 2289, -1, 2195, 2289, 2197, -1, 2199, 2290, 2293, -1, 2199, 2197, 2290, -1, 2140, 2138, 2291, -1, 2156, 2217, 2288, -1, 2193, 2294, 2292, -1, 2193, 2292, 2195, -1, 2201, 2293, 2295, -1, 2201, 2199, 2293, -1, 2191, 2296, 2294, -1, 2191, 2294, 2193, -1, 2154, 2297, 2217, -1, 2154, 2217, 2156, -1, 2203, 2295, 2298, -1, 2203, 2298, 2299, -1, 2203, 2201, 2295, -1, 2142, 2291, 2300, -1, 2142, 2140, 2291, -1, 2152, 2301, 2297, -1, 2188, 2126, 2296, -1, 2152, 2297, 2154, -1, 2188, 2124, 2126, -1, 2188, 2296, 2191, -1, 2302, 2124, 2188, -1, 2144, 2300, 2303, -1, 2144, 2142, 2300, -1, 2205, 2203, 2299, -1, 2150, 2304, 2301, -1, 2150, 2301, 2152, -1, 2305, 2205, 2299, -1, 2128, 2124, 2302, -1, 2146, 2303, 2306, -1, 2146, 2144, 2303, -1, 2307, 2128, 2302, -1, 2148, 2306, 2304, -1, 2148, 2304, 2150, -1, 2207, 2205, 2305, -1, 2148, 2146, 2306, -1, 2308, 2207, 2305, -1, 2130, 2128, 2307, -1, 2309, 2130, 2307, -1, 2209, 2207, 2308, -1, 2310, 2209, 2308, -1, 2132, 2130, 2309, -1, 2311, 2132, 2309, -1, 2211, 2209, 2310, -1, 2285, 2211, 2310, -1, 2134, 2132, 2311, -1, 2286, 2134, 2311, -1, 2213, 2211, 2285, -1, 2112, 2110, 2312, -1, 2162, 2159, 2313, -1, 2110, 2314, 2312, -1, 2158, 2315, 2159, -1, 2159, 2315, 2313, -1, 2314, 2108, 2316, -1, 2110, 2108, 2314, -1, 2317, 2178, 2318, -1, 2319, 2180, 2317, -1, 2317, 2180, 2178, -1, 2318, 2176, 2320, -1, 2158, 2092, 2315, -1, 2178, 2176, 2318, -1, 2108, 2106, 2316, -1, 2321, 2182, 2319, -1, 2319, 2182, 2180, -1, 2320, 2174, 2322, -1, 2176, 2174, 2320, -1, 2323, 2184, 2321, -1, 2324, 2090, 2158, -1, 2321, 2184, 2182, -1, 2158, 2090, 2092, -1, 2316, 2104, 2325, -1, 2106, 2104, 2316, -1, 2122, 2186, 2323, -1, 2326, 2094, 2324, -1, 2120, 2186, 2122, -1, 2323, 2186, 2184, -1, 2324, 2094, 2090, -1, 2327, 2172, 2328, -1, 2322, 2172, 2327, -1, 2174, 2172, 2322, -1, 2325, 2102, 2329, -1, 2104, 2102, 2325, -1, 2172, 2170, 2328, -1, 2330, 2096, 2326, -1, 2326, 2096, 2094, -1, 2120, 2331, 2186, -1, 2170, 2332, 2328, -1, 2329, 2100, 2333, -1, 2102, 2100, 2329, -1, 2120, 2118, 2331, -1, 2333, 2098, 2330, -1, 2330, 2098, 2096, -1, 2170, 2168, 2332, -1, 2100, 2098, 2333, -1, 2118, 2334, 2331, -1, 2168, 2335, 2332, -1, 2118, 2116, 2334, -1, 2168, 2166, 2335, -1, 2116, 2336, 2334, -1, 2166, 2337, 2335, -1, 2116, 2114, 2336, -1, 2166, 2164, 2337, -1, 2114, 2338, 2336, -1, 2164, 2339, 2337, -1, 2114, 2112, 2338, -1, 2164, 2162, 2339, -1, 2112, 2312, 2338, -1, 2162, 2313, 2339, -1, 2187, 2340, 2190, -1, 2190, 2340, 2341, -1, 2341, 2342, 2343, -1, 2340, 2342, 2341, -1, 2343, 2344, 2345, -1, 2342, 2344, 2343, -1, 2345, 2346, 2347, -1, 2344, 2346, 2345, -1, 2347, 2348, 2349, -1, 2346, 2348, 2347, -1, 2349, 2350, 2351, -1, 2348, 2350, 2349, -1, 2352, 2353, 2354, -1, 2351, 2353, 2352, -1, 2350, 2353, 2351, -1, 2353, 2355, 2354, -1, 2354, 2356, 2357, -1, 2355, 2356, 2354, -1, 2357, 2358, 2359, -1, 2356, 2358, 2357, -1, 2359, 2360, 2361, -1, 2358, 2360, 2359, -1, 2362, 2363, 2364, -1, 2361, 2363, 2362, -1, 2360, 2363, 2361, -1, 2363, 2365, 2364, -1, 2364, 2160, 2216, -1, 2365, 2160, 2364, -1, 2217, 2297, 2216, -1, 2216, 2297, 2364, -1, 2364, 2301, 2362, -1, 2297, 2301, 2364, -1, 2362, 2304, 2361, -1, 2301, 2304, 2362, -1, 2361, 2306, 2359, -1, 2304, 2306, 2361, -1, 2359, 2303, 2357, -1, 2306, 2303, 2359, -1, 2357, 2300, 2354, -1, 2303, 2300, 2357, -1, 2354, 2291, 2352, -1, 2300, 2291, 2354, -1, 2352, 2287, 2351, -1, 2291, 2287, 2352, -1, 2351, 2286, 2349, -1, 2287, 2286, 2351, -1, 2349, 2311, 2347, -1, 2286, 2311, 2349, -1, 2347, 2309, 2345, -1, 2311, 2309, 2347, -1, 2345, 2307, 2343, -1, 2309, 2307, 2345, -1, 2343, 2302, 2341, -1, 2307, 2302, 2343, -1, 2341, 2188, 2190, -1, 2302, 2188, 2341, -1, 2186, 2340, 2187, -1, 2186, 2331, 2340, -1, 2331, 2342, 2340, -1, 2331, 2334, 2342, -1, 2334, 2344, 2342, -1, 2334, 2336, 2344, -1, 2336, 2346, 2344, -1, 2336, 2338, 2346, -1, 2338, 2348, 2346, -1, 2338, 2312, 2348, -1, 2312, 2350, 2348, -1, 2312, 2314, 2350, -1, 2314, 2353, 2350, -1, 2314, 2316, 2353, -1, 2316, 2355, 2353, -1, 2316, 2325, 2355, -1, 2325, 2356, 2355, -1, 2325, 2329, 2356, -1, 2329, 2358, 2356, -1, 2329, 2333, 2358, -1, 2333, 2360, 2358, -1, 2333, 2330, 2360, -1, 2330, 2363, 2360, -1, 2330, 2326, 2363, -1, 2326, 2365, 2363, -1, 2326, 2324, 2365, -1, 2324, 2160, 2365, -1, 2324, 2158, 2160, -1, 2288, 2157, 2156, -1, 2255, 2157, 2288, -1, 2284, 2255, 2288, -1, 2257, 2255, 2284, -1, 2285, 2257, 2284, -1, 2259, 2257, 2285, -1, 2310, 2259, 2285, -1, 2261, 2259, 2310, -1, 2308, 2261, 2310, -1, 2263, 2261, 2308, -1, 2305, 2263, 2308, -1, 2265, 2263, 2305, -1, 2299, 2265, 2305, -1, 2267, 2265, 2299, -1, 2298, 2267, 2299, -1, 2269, 2267, 2298, -1, 2295, 2269, 2298, -1, 2271, 2269, 2295, -1, 2293, 2271, 2295, -1, 2273, 2271, 2293, -1, 2290, 2273, 2293, -1, 2275, 2273, 2290, -1, 2289, 2275, 2290, -1, 2277, 2275, 2289, -1, 2292, 2277, 2289, -1, 2279, 2277, 2292, -1, 2294, 2279, 2292, -1, 2281, 2279, 2294, -1, 2296, 2281, 2294, -1, 2283, 2281, 2296, -1, 2126, 2283, 2296, -1, 2125, 2283, 2126, -1, 2323, 2123, 2122, -1, 2282, 2123, 2323, -1, 2321, 2282, 2323, -1, 2280, 2282, 2321, -1, 2319, 2280, 2321, -1, 2278, 2280, 2319, -1, 2317, 2278, 2319, -1, 2276, 2278, 2317, -1, 2318, 2276, 2317, -1, 2274, 2276, 2318, -1, 2320, 2274, 2318, -1, 2272, 2274, 2320, -1, 2322, 2272, 2320, -1, 2270, 2272, 2322, -1, 2327, 2270, 2322, -1, 2268, 2270, 2327, -1, 2328, 2268, 2327, -1, 2266, 2268, 2328, -1, 2332, 2266, 2328, -1, 2264, 2266, 2332, -1, 2335, 2264, 2332, -1, 2262, 2264, 2335, -1, 2337, 2262, 2335, -1, 2260, 2262, 2337, -1, 2339, 2260, 2337, -1, 2258, 2260, 2339, -1, 2313, 2258, 2339, -1, 2256, 2258, 2313, -1, 2315, 2256, 2313, -1, 2254, 2256, 2315, -1, 2092, 2254, 2315, -1, 2091, 2254, 2092, -1, 2366, 1962, 2089, -1, 2367, 1962, 2366, -1, 2368, 2367, 2366, -1, 2369, 2367, 2368, -1, 2370, 2369, 2368, -1, 2371, 2369, 2370, -1, 2372, 2371, 2370, -1, 2373, 2371, 2372, -1, 2374, 2373, 2372, -1, 2375, 2373, 2374, -1, 2376, 2375, 2374, -1, 2377, 2375, 2376, -1, 2378, 2377, 2376, -1, 2379, 2377, 2378, -1, 2380, 2379, 2378, -1, 2381, 2379, 2380, -1, 2382, 2381, 2380, -1, 2383, 2381, 2382, -1, 2384, 2383, 2382, -1, 2385, 2383, 2384, -1, 2386, 2385, 2384, -1, 2387, 2385, 2386, -1, 2388, 2387, 2386, -1, 2389, 2387, 2388, -1, 2390, 2389, 2388, -1, 2391, 2389, 2390, -1, 2392, 2391, 2390, -1, 2393, 2391, 2392, -1, 2394, 2393, 2392, -1, 2395, 2393, 2394, -1, 2074, 2395, 2394, -1, 1995, 2395, 2074, -1, 2396, 1994, 2072, -1, 2396, 2072, 2397, -1, 2398, 2397, 2399, -1, 2398, 2396, 2397, -1, 2400, 2399, 2401, -1, 2400, 2398, 2399, -1, 2402, 2401, 2403, -1, 2402, 2400, 2401, -1, 2404, 2403, 2405, -1, 2404, 2402, 2403, -1, 2406, 2405, 2407, -1, 2406, 2404, 2405, -1, 2408, 2407, 2409, -1, 2408, 2406, 2407, -1, 2410, 2409, 2411, -1, 2410, 2408, 2409, -1, 2412, 2411, 2413, -1, 2412, 2410, 2411, -1, 2414, 2413, 2415, -1, 2414, 2412, 2413, -1, 2416, 2415, 2417, -1, 2416, 2414, 2415, -1, 2418, 2417, 2419, -1, 2418, 2416, 2417, -1, 2420, 2419, 2421, -1, 2420, 2418, 2419, -1, 2422, 2421, 2423, -1, 2422, 2420, 2421, -1, 2424, 2423, 2425, -1, 2424, 2422, 2423, -1, 1963, 2425, 2057, -1, 1963, 2424, 2425, -1, 2055, 2426, 1996, -1, 2055, 2427, 2426, -1, 2426, 2428, 2429, -1, 2427, 2428, 2426, -1, 2429, 2430, 2431, -1, 2428, 2430, 2429, -1, 2431, 2432, 2433, -1, 2430, 2432, 2431, -1, 2433, 2434, 2435, -1, 2432, 2434, 2433, -1, 2435, 2436, 2437, -1, 2434, 2436, 2435, -1, 2437, 2438, 2439, -1, 2436, 2438, 2437, -1, 2439, 2440, 2441, -1, 2438, 2440, 2439, -1, 2441, 2442, 2443, -1, 2440, 2442, 2441, -1, 2443, 2444, 2445, -1, 2442, 2444, 2443, -1, 2445, 2446, 2447, -1, 2444, 2446, 2445, -1, 2447, 2448, 2449, -1, 2446, 2448, 2447, -1, 2449, 2450, 2451, -1, 2448, 2450, 2449, -1, 2451, 2041, 2025, -1, 2450, 2041, 2451, -1, 2040, 2452, 2024, -1, 2040, 2453, 2452, -1, 2452, 2454, 2455, -1, 2453, 2454, 2452, -1, 2455, 2456, 2457, -1, 2454, 2456, 2455, -1, 2457, 2458, 2459, -1, 2456, 2458, 2457, -1, 2459, 2460, 2461, -1, 2458, 2460, 2459, -1, 2461, 2462, 2463, -1, 2460, 2462, 2461, -1, 2463, 2464, 2465, -1, 2462, 2464, 2463, -1, 2465, 2466, 2467, -1, 2464, 2466, 2465, -1, 2467, 2468, 2469, -1, 2466, 2468, 2467, -1, 2469, 2470, 2471, -1, 2468, 2470, 2469, -1, 2471, 2472, 2473, -1, 2470, 2472, 2471, -1, 2473, 2474, 2475, -1, 2472, 2474, 2473, -1, 2475, 2476, 2477, -1, 2474, 2476, 2475, -1, 2477, 2026, 1997, -1, 2476, 2026, 2477, -1, 2024, 2452, 2025, -1, 2025, 2452, 2451, -1, 2451, 2455, 2449, -1, 2452, 2455, 2451, -1, 2449, 2457, 2447, -1, 2455, 2457, 2449, -1, 2447, 2459, 2445, -1, 2457, 2459, 2447, -1, 2445, 2461, 2443, -1, 2459, 2461, 2445, -1, 2443, 2463, 2441, -1, 2461, 2463, 2443, -1, 2441, 2465, 2439, -1, 2463, 2465, 2441, -1, 2439, 2467, 2437, -1, 2465, 2467, 2439, -1, 2437, 2469, 2435, -1, 2467, 2469, 2437, -1, 2435, 2471, 2433, -1, 2469, 2471, 2435, -1, 2433, 2473, 2431, -1, 2471, 2473, 2433, -1, 2431, 2475, 2429, -1, 2473, 2475, 2431, -1, 2429, 2477, 2426, -1, 2475, 2477, 2429, -1, 2426, 1997, 1996, -1, 2477, 1997, 2426, -1, 2370, 2037, 2372, -1, 2038, 2037, 2370, -1, 2468, 2078, 2470, -1, 2079, 2078, 2468, -1, 2368, 2038, 2370, -1, 2039, 2038, 2368, -1, 2030, 2388, 2386, -1, 2466, 2079, 2468, -1, 2029, 2390, 2388, -1, 2029, 2388, 2030, -1, 2031, 2386, 2384, -1, 2080, 2466, 2464, -1, 2031, 2030, 2386, -1, 2080, 2079, 2466, -1, 2366, 2040, 2039, -1, 2028, 2392, 2390, -1, 2366, 2039, 2368, -1, 2028, 2390, 2029, -1, 2032, 2384, 2382, -1, 2032, 2031, 2384, -1, 2089, 2040, 2366, -1, 2027, 2394, 2392, -1, 2081, 2080, 2464, -1, 2027, 2392, 2028, -1, 2033, 2382, 2380, -1, 2033, 2380, 2378, -1, 2033, 2032, 2382, -1, 2026, 2074, 2394, -1, 2026, 2073, 2074, -1, 2026, 2394, 2027, -1, 2034, 2033, 2378, -1, 2476, 2073, 2026, -1, 2082, 2464, 2462, -1, 2082, 2081, 2464, -1, 2075, 2073, 2476, -1, 2376, 2034, 2378, -1, 2088, 2453, 2040, -1, 2088, 2040, 2089, -1, 2035, 2034, 2376, -1, 2083, 2462, 2460, -1, 2474, 2075, 2476, -1, 2083, 2082, 2462, -1, 2087, 2454, 2453, -1, 2076, 2075, 2474, -1, 2087, 2453, 2088, -1, 2084, 2460, 2458, -1, 2084, 2083, 2460, -1, 2374, 2035, 2376, -1, 2036, 2035, 2374, -1, 2086, 2456, 2454, -1, 2086, 2454, 2087, -1, 2085, 2458, 2456, -1, 2085, 2456, 2086, -1, 2085, 2084, 2458, -1, 2472, 2076, 2474, -1, 2077, 2076, 2472, -1, 2372, 2036, 2374, -1, 2037, 2036, 2372, -1, 2470, 2077, 2472, -1, 2078, 2077, 2470, -1, 2044, 2043, 2421, -1, 2067, 2066, 2434, -1, 2043, 2423, 2421, -1, 2066, 2436, 2434, -1, 2043, 2042, 2423, -1, 2401, 2052, 2403, -1, 2436, 2065, 2438, -1, 2066, 2065, 2436, -1, 2041, 2425, 2042, -1, 2042, 2425, 2423, -1, 2403, 2051, 2405, -1, 2052, 2051, 2403, -1, 2399, 2053, 2401, -1, 2401, 2053, 2052, -1, 2405, 2050, 2407, -1, 2065, 2064, 2438, -1, 2051, 2050, 2405, -1, 2041, 2057, 2425, -1, 2397, 2054, 2399, -1, 2399, 2054, 2053, -1, 2407, 2049, 2409, -1, 2050, 2049, 2407, -1, 2438, 2063, 2440, -1, 2064, 2063, 2438, -1, 2450, 2056, 2041, -1, 2411, 2048, 2413, -1, 2041, 2056, 2057, -1, 2409, 2048, 2411, -1, 2049, 2048, 2409, -1, 2440, 2062, 2442, -1, 2063, 2062, 2440, -1, 2448, 2058, 2450, -1, 2072, 2055, 2397, -1, 2071, 2055, 2072, -1, 2450, 2058, 2056, -1, 2397, 2055, 2054, -1, 2071, 2427, 2055, -1, 2442, 2061, 2444, -1, 2062, 2061, 2442, -1, 2048, 2047, 2413, -1, 2446, 2059, 2448, -1, 2071, 2070, 2427, -1, 2448, 2059, 2058, -1, 2444, 2060, 2446, -1, 2047, 2415, 2413, -1, 2061, 2060, 2444, -1, 2446, 2060, 2059, -1, 2070, 2428, 2427, -1, 2047, 2046, 2415, -1, 2070, 2069, 2428, -1, 2046, 2417, 2415, -1, 2069, 2430, 2428, -1, 2046, 2045, 2417, -1, 2069, 2068, 2430, -1, 2045, 2419, 2417, -1, 2068, 2432, 2430, -1, 2045, 2044, 2419, -1, 2068, 2067, 2432, -1, 2044, 2421, 2419, -1, 2067, 2434, 2432, -1, 1995, 1994, 2396, -1, 2395, 1995, 2396, -1, 2393, 2396, 2398, -1, 2393, 2395, 2396, -1, 1924, 2400, 2402, -1, 1925, 1924, 2402, -1, 2391, 2398, 2400, -1, 2391, 2393, 2398, -1, 1928, 1925, 2402, -1, 1930, 1928, 2402, -1, 2404, 1930, 2402, -1, 1885, 1924, 2478, -1, 1885, 2400, 1924, -1, 1885, 2391, 2400, -1, 1886, 2478, 2479, -1, 1886, 1885, 2478, -1, 2389, 2391, 1885, -1, 2389, 1885, 2480, -1, 1889, 2479, 2481, -1, 1889, 1886, 2479, -1, 2482, 2389, 2480, -1, 1934, 1932, 2404, -1, 1891, 2481, 2483, -1, 1891, 1889, 2481, -1, 2484, 2389, 2482, -1, 2406, 1934, 2404, -1, 1893, 2483, 2485, -1, 1893, 1891, 2483, -1, 2387, 2389, 2484, -1, 1938, 1936, 2406, -1, 1895, 2485, 2486, -1, 1895, 1893, 2485, -1, 2487, 2387, 2488, -1, 2408, 1938, 2406, -1, 1897, 2486, 2489, -1, 1897, 1895, 2486, -1, 2385, 2387, 2487, -1, 1899, 2489, 2490, -1, 1899, 1897, 2489, -1, 2410, 1942, 1940, -1, 2410, 1940, 2408, -1, 2491, 2385, 2492, -1, 1901, 1899, 2490, -1, 1901, 2490, 2493, -1, 2383, 2385, 2491, -1, 2412, 1943, 2410, -1, 1903, 1901, 2493, -1, 2381, 2383, 2494, -1, 2381, 2494, 2495, -1, 1904, 1903, 2493, -1, 1904, 2493, 2496, -1, 2414, 1945, 2412, -1, 2414, 1947, 1945, -1, 1906, 1904, 2496, -1, 1906, 2496, 2497, -1, 2379, 2381, 2498, -1, 1908, 1906, 2497, -1, 1908, 2497, 2499, -1, 2416, 1949, 2414, -1, 2416, 1951, 1949, -1, 2377, 2500, 2501, -1, 2377, 2379, 2500, -1, 1910, 1908, 2499, -1, 1910, 2499, 2502, -1, 1912, 1910, 2502, -1, 1912, 2502, 2503, -1, 2418, 1953, 2416, -1, 2418, 1955, 1953, -1, 2418, 1957, 1955, -1, 1959, 1957, 2418, -1, 1961, 1959, 2418, -1, 1914, 2503, 2504, -1, 1914, 1912, 2503, -1, 2375, 2505, 2506, -1, 2375, 2377, 2505, -1, 1916, 1914, 2504, -1, 1916, 2504, 2507, -1, 2420, 1961, 2418, -1, 1918, 1916, 2507, -1, 1918, 2507, 2508, -1, 1920, 1918, 2508, -1, 1920, 2508, 1961, -1, 1922, 1920, 1961, -1, 2373, 2375, 2509, -1, 2373, 2510, 1922, -1, 2373, 2511, 2510, -1, 2373, 2509, 2511, -1, 2371, 1922, 1961, -1, 2371, 1961, 2420, -1, 2371, 2373, 1922, -1, 2369, 2420, 2422, -1, 2369, 2371, 2420, -1, 2367, 2422, 2424, -1, 2367, 2369, 2422, -1, 1962, 2424, 1963, -1, 1962, 2367, 2424, -1, 2506, 2509, 2375, -1, 2501, 2505, 2377, -1, 2498, 2500, 2379, -1, 2495, 2498, 2381, -1, 2491, 2494, 2383, -1, 2487, 2492, 2385, -1, 2484, 2488, 2387, -1, 1932, 1930, 2404, -1, 1936, 1934, 2406, -1, 1940, 1938, 2408, -1, 1943, 1942, 2410, -1, 1945, 1943, 2412, -1, 1949, 1947, 2414, -1, 1953, 1951, 2416, -1, 2218, 1960, 1961, -1, 2218, 1961, 2508, -1, 2219, 2508, 2507, -1, 2219, 2218, 2508, -1, 2222, 2507, 2504, -1, 2222, 2219, 2507, -1, 2224, 2504, 2503, -1, 2224, 2222, 2504, -1, 2226, 2503, 2502, -1, 2226, 2224, 2503, -1, 2227, 2502, 2499, -1, 2227, 2226, 2502, -1, 2230, 2499, 2497, -1, 2230, 2227, 2499, -1, 2231, 2497, 2496, -1, 2231, 2230, 2497, -1, 2234, 2496, 2493, -1, 2234, 2231, 2496, -1, 2235, 2234, 2493, -1, 2236, 2493, 2490, -1, 2236, 2235, 2493, -1, 2238, 2490, 2489, -1, 2238, 2236, 2490, -1, 2241, 2489, 2486, -1, 2241, 2238, 2489, -1, 2242, 2486, 2485, -1, 2242, 2241, 2486, -1, 2245, 2485, 2483, -1, 2245, 2242, 2485, -1, 2246, 2245, 2483, -1, 2246, 2483, 2481, -1, 2249, 2246, 2481, -1, 2249, 2481, 2479, -1, 2250, 2249, 2479, -1, 2250, 2479, 2478, -1, 1926, 2250, 2478, -1, 1926, 2478, 1924, -1, 2220, 1921, 1922, -1, 2220, 1922, 2510, -1, 2221, 2510, 2511, -1, 2221, 2220, 2510, -1, 2223, 2511, 2509, -1, 2223, 2221, 2511, -1, 2225, 2509, 2506, -1, 2225, 2223, 2509, -1, 2229, 2506, 2505, -1, 2229, 2225, 2506, -1, 2228, 2505, 2501, -1, 2228, 2229, 2505, -1, 2233, 2501, 2500, -1, 2233, 2228, 2501, -1, 2232, 2500, 2498, -1, 2232, 2233, 2500, -1, 2237, 2498, 2495, -1, 2237, 2232, 2498, -1, 2240, 2237, 2495, -1, 2239, 2495, 2494, -1, 2239, 2240, 2495, -1, 2243, 2494, 2491, -1, 2243, 2239, 2494, -1, 2244, 2491, 2492, -1, 2244, 2243, 2491, -1, 2247, 2492, 2487, -1, 2247, 2244, 2492, -1, 2248, 2487, 2488, -1, 2248, 2247, 2487, -1, 2251, 2248, 2488, -1, 2251, 2488, 2484, -1, 2253, 2251, 2484, -1, 2253, 2484, 2482, -1, 2252, 2253, 2482, -1, 2252, 2482, 2480, -1, 1887, 2252, 2480, -1, 1887, 2480, 1885, -1 - ] - } - castShadows FALSE - } - DEF mounting_plates Shape { - appearance Appearance { - material Material { - diffuseColor 0.3 0.3 0.3 - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - 0.1963993 0.16644935 -0.049989924, 0.19635145 0.16644923 -0.049595192, 0.19639927 0.16944937 -0.049989834, 0.19635133 0.16944931 -0.049595013, 0.19621038 0.16644931 -0.049223199, 0.19621038 0.1694492 -0.049222931, 0.19598442 0.16644931 -0.048895821, 0.19598436 0.16944925 -0.048895702, 0.19568659 0.16644928 -0.048632219, 0.19568667 0.1694492 -0.048631921, 0.19533443 0.16644922 -0.048447266, 0.19533443 0.1694492 -0.048446998, 0.19494823 0.16644922 -0.048352197, 0.19494817 0.16944925 -0.04835175, 0.19455048 0.16644923 -0.048352018, 0.19455038 0.16944924 -0.048352018, 0.19416419 0.16644929 -0.048447266, 0.19416425 0.16944925 -0.048447117, 0.19381207 0.16644922 -0.048632041, 0.19381198 0.16944925 -0.048631921, 0.19351432 0.16644928 -0.048895702, 0.19351429 0.16944927 -0.048895702, 0.19328837 0.16644925 -0.049223199, 0.1932883 0.16944927 -0.049222931, 0.19314726 0.16644928 -0.049595192, 0.19314727 0.16944927 -0.049595013, 0.19309938 0.16644934 -0.049989924, 0.19309932 0.1694493 -0.049989775, 0.19639939 0.16644792 -0.024989977, 0.19635138 0.16644786 -0.024595246, 0.19639936 0.16944788 -0.024989828, 0.19635135 0.16944794 -0.024595007, 0.19621041 0.16644786 -0.024223164, 0.19621037 0.16944784 -0.024222985, 0.19598435 0.16644788 -0.023895845, 0.19598438 0.16944784 -0.023895606, 0.19568673 0.16644773 -0.023632035, 0.19568661 0.16944787 -0.023631826, 0.19533445 0.1664478 -0.02344726, 0.19533437 0.16944782 -0.023446992, 0.19494829 0.16644786 -0.023352012, 0.19494823 0.16944782 -0.023352012, 0.19455045 0.16644786 -0.023352012, 0.19455038 0.16944781 -0.023351803, 0.19416419 0.16644786 -0.02344726, 0.19416419 0.16944775 -0.023446992, 0.19381207 0.16644779 -0.023632035, 0.19381207 0.16944781 -0.023631915, 0.19351421 0.16644785 -0.023895845, 0.19351426 0.16944781 -0.023895606, 0.19328831 0.16644785 -0.024223164, 0.19328824 0.16944787 -0.024222985, 0.19314721 0.16644791 -0.024595246, 0.19314724 0.16944793 -0.024595007, 0.19309929 0.16644791 -0.024989977, 0.19309928 0.16944793 -0.024989828, 0.1963993 0.16644514 0.025009945, 0.19635144 0.16644514 0.025404826, 0.19639935 0.16944502 0.025010094, 0.19635147 0.16944508 0.025405064, 0.19621029 0.16644514 0.02577664, 0.19621028 0.16944502 0.025777087, 0.19598433 0.16644514 0.026104197, 0.19598439 0.16944502 0.026104316, 0.19568661 0.16644512 0.026368037, 0.19568661 0.16944502 0.026368037, 0.19533443 0.16644499 0.026552901, 0.1953344 0.16944502 0.026552901, 0.19494829 0.16644499 0.026648059, 0.19494826 0.16944502 0.026648059, 0.19455048 0.16644506 0.026648059, 0.19455042 0.16944501 0.026648059, 0.19416426 0.16644499 0.026552901, 0.19416417 0.16944507 0.026552901, 0.1938121 0.16644502 0.026368037, 0.19381201 0.1694451 0.026368126, 0.19351426 0.16644505 0.026104257, 0.19351426 0.16944507 0.026104316, 0.19328833 0.16644505 0.025776967, 0.19328833 0.16944507 0.025777027, 0.19314732 0.16644505 0.025405064, 0.19314732 0.16944507 0.025405064, 0.19309932 0.16644505 0.025010005, 0.19309931 0.16944507 0.025010094, 0.1963993 0.16644369 0.05001007, 0.19635135 0.16644369 0.050404981, 0.19639939 0.16944365 0.050010368, 0.19635144 0.16944359 0.050404981, 0.19621029 0.16644363 0.050776795, 0.19621028 0.16944359 0.050777003, 0.19598433 0.16644378 0.051104233, 0.19598445 0.16944359 0.051104471, 0.19568665 0.16644363 0.051367953, 0.19568661 0.16944358 0.051368162, 0.19533437 0.16644369 0.051552698, 0.19533446 0.16944365 0.051552966, 0.19494829 0.16644356 0.051647976, 0.19494815 0.16944365 0.051648185, 0.19455053 0.16644356 0.051647976, 0.19455042 0.16944365 0.051648185, 0.19416419 0.16644362 0.051552728, 0.19416423 0.16944364 0.051552966, 0.19381212 0.16644359 0.051367953, 0.19381204 0.16944358 0.051368162, 0.19351433 0.16644368 0.051104233, 0.19351432 0.16944358 0.051104471, 0.19328839 0.16644359 0.050776795, 0.1932883 0.16944367 0.050777003, 0.19314724 0.16644362 0.050404981, 0.19314723 0.16944364 0.050404981, 0.19309929 0.16644368 0.050010249, 0.19309926 0.16944364 0.050010368, 0.19639933 0.16644655 9.9390745e-06, 0.19635138 0.16644655 0.00040484965, 0.19639936 0.16944653 1.0296702e-05, 0.19635139 0.16944647 0.00040499866, 0.19621035 0.16644652 0.00077666342, 0.19621028 0.16944647 0.00077717006, 0.19598442 0.16644652 0.0011041313, 0.19598436 0.1694465 0.0011043996, 0.19568664 0.16644637 0.0013679117, 0.19568668 0.16944635 0.0013680607, 0.1953344 0.16644636 0.0015528351, 0.19533439 0.16944638 0.0015530735, 0.19494823 0.16644636 0.0016479343, 0.19494815 0.16944638 0.0016480833, 0.19455045 0.16644642 0.0016479939, 0.19455041 0.16944638 0.0016480833, 0.19416419 0.16644643 0.0015528351, 0.19416419 0.16944641 0.0015528351, 0.19381204 0.16644642 0.0013679117, 0.19381201 0.16944644 0.0013680607, 0.19351438 0.16644646 0.0011041313, 0.19351429 0.1694465 0.0011043996, 0.19328831 0.16644648 0.00077681243, 0.19328836 0.16944644 0.00077717006, 0.1931473 0.16644648 0.00040484965, 0.19314724 0.1694465 0.00040499866, 0.19309933 0.16644654 9.9390745e-06, 0.19309936 0.16944648 1.0296702e-05, 0.30439949 0.16645005 -0.049989924, 0.30435148 0.16644996 -0.049595281, 0.30439943 0.16945003 -0.049989775, 0.30435145 0.16944993 -0.049595013, 0.30421045 0.16644996 -0.049223199, 0.30421042 0.16944993 -0.04922305, 0.30398443 0.16644998 -0.048895702, 0.3039844 0.16944996 -0.048895702, 0.30368683 0.16644996 -0.048632041, 0.30368674 0.16944994 -0.048632041, 0.30333456 0.16644993 -0.048447266, 0.30333453 0.1694499 -0.048446998, 0.30294836 0.16644993 -0.048352018, 0.3029483 0.16944991 -0.048351899, 0.30255058 0.16644983 -0.048352018, 0.30255052 0.1694499 -0.048351899, 0.30216435 0.16644983 -0.048447266, 0.30216429 0.1694499 -0.048446998, 0.30181217 0.16644993 -0.048632041, 0.30181208 0.16944993 -0.048631921, 0.30151436 0.16644998 -0.048895821, 0.30151433 0.16944991 -0.048895702, 0.30128846 0.16644993 -0.049223199, 0.30128837 0.16944988 -0.04922305, 0.30114743 0.16644995 -0.049595192, 0.3011474 0.1694499 -0.049595013, 0.30109942 0.16645004 -0.049989924, 0.30109948 0.16944996 -0.049989834, 0.30439946 0.16644859 -0.024989977, 0.30435154 0.16644859 -0.024595097, 0.30439943 0.16944866 -0.024989828, 0.30435151 0.16944866 -0.024595007, 0.30421039 0.16644856 -0.024223164, 0.30421036 0.16944858 -0.024222985, 0.30398449 0.16644841 -0.023895845, 0.30398446 0.16944855 -0.023895606, 0.30368677 0.16644847 -0.023632035, 0.30368674 0.16944851 -0.023631915, 0.3033345 0.16644856 -0.02344726, 0.30333441 0.16944852 -0.023446903, 0.30294833 0.16644852 -0.023352101, 0.30294824 0.16944849 -0.023351803, 0.30255058 0.16644852 -0.023352012, 0.30255052 0.16944842 -0.023351803, 0.30216435 0.16644855 -0.023447141, 0.30216432 0.16944842 -0.023446992, 0.30181208 0.16644852 -0.023632035, 0.30181211 0.16944852 -0.023631826, 0.30151442 0.16644853 -0.023895845, 0.30151436 0.16944852 -0.023895606, 0.3012884 0.16644856 -0.024223164, 0.30128837 0.16944848 -0.024222985, 0.30114737 0.16644864 -0.024595246, 0.30114734 0.16944857 -0.024595007, 0.30109945 0.16644864 -0.024989977, 0.30109936 0.1694486 -0.024989828, 0.30439946 0.16644587 0.025010005, 0.30435148 0.16644579 0.025405064, 0.30439946 0.16944572 0.025010243, 0.30435142 0.1694458 0.025405064, 0.30421039 0.16644578 0.025776967, 0.30421045 0.16944574 0.025777027, 0.30398434 0.16644588 0.026104197, 0.3039844 0.16944577 0.026104316, 0.30368671 0.16644581 0.026368037, 0.30368668 0.16944572 0.026368126, 0.30333456 0.16644576 0.026552901, 0.30333453 0.16944572 0.026552901, 0.30294836 0.16644576 0.026648059, 0.30294836 0.16944574 0.026648059, 0.30255058 0.16644566 0.026648059, 0.30255046 0.16944572 0.026648059, 0.30216435 0.16644566 0.026552901, 0.30216438 0.1694456 0.026553139, 0.30181208 0.16644575 0.026368037, 0.30181205 0.16944571 0.026368037, 0.30151436 0.16644581 0.026104257, 0.30151439 0.16944575 0.026104316, 0.30128857 0.16644566 0.025776967, 0.30128852 0.16944571 0.025777027, 0.30114737 0.16644576 0.025405064, 0.3011474 0.16944568 0.025405064, 0.30109951 0.16644578 0.025009945, 0.30109942 0.16944574 0.025010094, 0.30439946 0.16644442 0.050010249, 0.30435148 0.16644436 0.050404981, 0.30439946 0.16944438 0.050010368, 0.30435151 0.16944434 0.050404981, 0.30421045 0.16644436 0.050776795, 0.30421042 0.16944432 0.050777003, 0.30398449 0.16644439 0.051104233, 0.30398446 0.16944438 0.051104471, 0.30368671 0.16644438 0.051367953, 0.30368662 0.16944434 0.051368162, 0.30333444 0.16644438 0.051552728, 0.30333441 0.16944435 0.051552966, 0.30294839 0.16644433 0.051647976, 0.30294833 0.16944432 0.051648185, 0.30255058 0.16644423 0.051647976, 0.30255058 0.16944432 0.051648185, 0.30216435 0.16644436 0.051552728, 0.30216435 0.16944432 0.051552966, 0.30181208 0.16644432 0.051367953, 0.30181211 0.16944429 0.051368162, 0.30151436 0.16644435 0.051104024, 0.30151439 0.16944431 0.051104471, 0.30128843 0.16644435 0.050776795, 0.30128843 0.16944428 0.050777003, 0.30114743 0.16644435 0.050404981, 0.3011474 0.16944431 0.050404981, 0.30109951 0.16644435 0.05001007, 0.30109948 0.16944435 0.050010249, 0.30439946 0.16644721 9.9390745e-06, 0.30435148 0.16644722 0.00040484965, 0.30439946 0.16944715 1.0296702e-05, 0.30435151 0.16944718 0.00040508807, 0.30421045 0.1664471 0.00077666342, 0.30421036 0.16944721 0.00077690184, 0.30398455 0.1664471 0.0011041313, 0.30398446 0.16944715 0.0011043996, 0.30368668 0.16644704 0.0013679117, 0.30368668 0.16944718 0.0013680607, 0.30333456 0.16644704 0.0015528351, 0.30333447 0.16944715 0.0015528351, 0.30294821 0.16644709 0.0016479939, 0.30294818 0.16944718 0.0016480833, 0.30255058 0.16644709 0.0016480833, 0.30255046 0.16944705 0.0016480833, 0.30216435 0.16644712 0.0015528351, 0.30216426 0.16944705 0.0015528351, 0.3018122 0.16644713 0.0013679117, 0.30181205 0.16944705 0.0013679713, 0.30151436 0.16644709 0.0011041313, 0.30151442 0.16944717 0.0011043996, 0.30128843 0.16644716 0.00077666342, 0.30128837 0.16944714 0.00077717006, 0.30114737 0.16644718 0.00040484965, 0.3011474 0.16944715 0.00040508807, 0.30109945 0.16644718 9.9390745e-06, 0.30109945 0.16944714 1.0296702e-05, 0.34439945 0.16645034 -0.049989924, 0.34435144 0.16645028 -0.049595192, 0.34439939 0.16945031 -0.049989834, 0.3443515 0.16945022 -0.049595013, 0.34421048 0.16645025 -0.049223199, 0.34421045 0.16945024 -0.04922305, 0.34398457 0.16645025 -0.048895821, 0.34398445 0.16945019 -0.048895702, 0.34368667 0.16645023 -0.048632219, 0.34368673 0.16945019 -0.048631921, 0.34333459 0.16645022 -0.048447266, 0.34333456 0.16945018 -0.048446998, 0.34294835 0.16645022 -0.048352018, 0.34294826 0.16945025 -0.048351899, 0.34255061 0.16645022 -0.048352018, 0.34255061 0.16945016 -0.048351899, 0.34216443 0.16645011 -0.048447266, 0.34216437 0.16945016 -0.048446998, 0.34181216 0.16645023 -0.048632041, 0.34181207 0.16945016 -0.048631921, 0.34151444 0.16645011 -0.048895702, 0.34151438 0.16945016 -0.048895702, 0.34128842 0.16645014 -0.049223199, 0.34128839 0.16945016 -0.04922305, 0.34114751 0.16645022 -0.049595192, 0.34114736 0.16945025 -0.049595013, 0.34109953 0.16645026 -0.049989924, 0.3410995 0.16945028 -0.049989834, 0.34439948 0.16644885 -0.024989977, 0.34435144 0.16644888 -0.024595097, 0.34439942 0.1694489 -0.024989828, 0.34435153 0.16944887 -0.024595007, 0.34421048 0.1664488 -0.024223074, 0.34421051 0.16944876 -0.024222985, 0.34398443 0.16644891 -0.023895845, 0.34398443 0.16944876 -0.023895606, 0.34368679 0.1664488 -0.023632035, 0.3436867 0.16944875 -0.023631915, 0.34333456 0.1664488 -0.02344726, 0.34333456 0.16944875 -0.023446903, 0.34294829 0.1664488 -0.023352101, 0.34294832 0.16944875 -0.023351893, 0.34255055 0.16644876 -0.023352012, 0.34255052 0.16944884 -0.023351893, 0.34216443 0.16644874 -0.02344726, 0.34216434 0.16944873 -0.023446903, 0.34181222 0.1664488 -0.023632124, 0.34181222 0.16944879 -0.023631915, 0.34151432 0.16644876 -0.023895755, 0.34151438 0.16944873 -0.023895606, 0.34128848 0.16644871 -0.024223074, 0.34128839 0.16944873 -0.024222985, 0.34114739 0.1664488 -0.024595246, 0.34114736 0.16944882 -0.024595097, 0.34109941 0.16644889 -0.024989977, 0.34109941 0.16944885 -0.024989828, 0.34439942 0.16644607 0.025009945, 0.3443515 0.16644606 0.025405064, 0.34439942 0.16944605 0.025010094, 0.3443515 0.16944601 0.025405064, 0.34421042 0.16644599 0.025776967, 0.34421039 0.16944601 0.025777027, 0.34398451 0.16644597 0.026104197, 0.34398454 0.16944601 0.026104316, 0.34368673 0.1664461 0.026367798, 0.34368676 0.16944599 0.026368037, 0.34333453 0.16644602 0.026552901, 0.3433345 0.16944599 0.026552901, 0.34294829 0.16644597 0.026648059, 0.34294835 0.16944598 0.026648149, 0.34255058 0.16644603 0.026648059, 0.34255061 0.16944599 0.026648059, 0.34216437 0.16644605 0.026552901, 0.34216437 0.16944599 0.026552901, 0.34181216 0.166446 0.026368037, 0.34181216 0.16944601 0.026368126, 0.34151444 0.16644594 0.026104197, 0.34151438 0.16944599 0.026104316, 0.34128842 0.16644606 0.02577664, 0.34128839 0.16944608 0.025777087, 0.34114739 0.16644606 0.025404826, 0.34114736 0.16944608 0.025405064, 0.34109941 0.16644606 0.025009945, 0.34109938 0.16944608 0.025010094, 0.34439954 0.16644463 0.050010249, 0.34435144 0.16644466 0.050404981, 0.34439945 0.16944467 0.050010368, 0.34435147 0.16944458 0.050404981, 0.34421042 0.16644455 0.050776795, 0.34421039 0.16944458 0.050776795, 0.34398451 0.16644464 0.051104233, 0.34398454 0.16944458 0.051104471, 0.34368679 0.1664446 0.051367953, 0.34368679 0.16944461 0.051368162, 0.34333459 0.16644455 0.051552728, 0.34333456 0.16944453 0.051552966, 0.34294829 0.16644454 0.051647976, 0.34294826 0.16944456 0.051648185, 0.34255055 0.16644464 0.051647976, 0.34255058 0.16944458 0.051648185, 0.34216443 0.16644451 0.051552728, 0.34216437 0.16944456 0.051552966, 0.34181216 0.16644457 0.051367953, 0.34181213 0.16944456 0.051367953, 0.34151444 0.16644457 0.051104233, 0.34151438 0.16944456 0.051104471, 0.34128848 0.1664446 0.050776795, 0.34128839 0.16944465 0.050777003, 0.34114739 0.16644464 0.050404981, 0.34114733 0.16944468 0.050404981, 0.34109941 0.16644463 0.05001007, 0.34109938 0.16944465 0.050010398, 0.34439942 0.16644748 9.9390745e-06, 0.3443515 0.16644748 0.00040484965, 0.34439948 0.16944744 1.0296702e-05, 0.3443515 0.16944742 0.00040499866, 0.34421048 0.16644739 0.00077681243, 0.34421048 0.16944742 0.00077717006, 0.34398451 0.16644746 0.0011043996, 0.34398451 0.16944748 0.0011043996, 0.34368667 0.16644733 0.0013678223, 0.3436867 0.16944732 0.0013680607, 0.34333459 0.16644736 0.0015528351, 0.34333444 0.1694473 0.0015528351, 0.34294829 0.16644739 0.0016479343, 0.34294835 0.16944727 0.0016480833, 0.34255067 0.16644728 0.0016479343, 0.34255058 0.16944732 0.0016480833, 0.34216443 0.16644731 0.0015528351, 0.34216434 0.1694473 0.0015528351, 0.34181216 0.16644737 0.0013679117, 0.34181213 0.16944739 0.0013679713, 0.34151438 0.16644746 0.0011041313, 0.34151438 0.16944741 0.0011043996, 0.34128854 0.1664474 0.00077666342, 0.34128848 0.16944742 0.00077690184, 0.34114739 0.16644745 0.00040484965, 0.34114733 0.16944754 0.00040499866, 0.34109941 0.16644752 9.9390745e-06, 0.34109944 0.16944751 1.0296702e-05, 0.38439944 0.16645055 -0.049989924, 0.38435152 0.16645046 -0.049595281, 0.38439956 0.16945046 -0.049989834, 0.38435149 0.16945043 -0.049595013, 0.3842105 0.16645041 -0.049223199, 0.38421047 0.16945043 -0.04922305, 0.38398448 0.16645047 -0.048895821, 0.38398448 0.16945049 -0.048895702, 0.38368675 0.16645053 -0.048632041, 0.38368684 0.16945043 -0.048631921, 0.38333455 0.1664505 -0.048447266, 0.38333461 0.1694504 -0.048446998, 0.38294837 0.16645046 -0.048352018, 0.38294831 0.16945042 -0.04835175, 0.38255063 0.16645049 -0.048352197, 0.3825506 0.16945043 -0.048351899, 0.38216439 0.16645041 -0.048447266, 0.38216439 0.16945039 -0.048446998, 0.3818123 0.16645052 -0.048632041, 0.3818123 0.16945054 -0.048631772, 0.3815144 0.1664505 -0.048895821, 0.38151446 0.16945045 -0.048895702, 0.38128856 0.16645038 -0.049223199, 0.38128844 0.16945046 -0.04922305, 0.38114741 0.16645049 -0.049595192, 0.38114735 0.16945052 -0.049595013, 0.38109943 0.16645052 -0.049990043, 0.38109943 0.16945052 -0.049989834, 0.38439944 0.16644914 -0.024989977, 0.38435152 0.16644913 -0.024595097, 0.3843995 0.16944908 -0.024989828, 0.38435158 0.16944908 -0.024595007, 0.38421044 0.16644907 -0.024223164, 0.38421047 0.169449 -0.024222985, 0.3839846 0.16644903 -0.023895755, 0.38398454 0.16944905 -0.023895606, 0.38368669 0.16644904 -0.023632035, 0.38368681 0.16944908 -0.023631915, 0.38333461 0.16644904 -0.02344726, 0.38333461 0.16944894 -0.023446992, 0.38294849 0.16644907 -0.023352101, 0.38294831 0.16944897 -0.023351893, 0.38255063 0.16644898 -0.023352012, 0.3825506 0.16944899 -0.023351893, 0.38216439 0.16644898 -0.02344726, 0.38216436 0.16944899 -0.023446992, 0.38181213 0.16644901 -0.023632124, 0.38181213 0.16944908 -0.023631915, 0.38151452 0.16644892 -0.023895845, 0.38151452 0.16944908 -0.023895606, 0.38128844 0.16644906 -0.024223164, 0.3812885 0.169449 -0.024222985, 0.38114741 0.16644914 -0.024595246, 0.38114747 0.16944914 -0.024595007, 0.38109949 0.16644911 -0.024989977, 0.3810994 0.16944915 -0.024989828, 0.38439956 0.16644628 0.025010005, 0.38435158 0.16644628 0.025405064, 0.38439938 0.16944632 0.025010094, 0.38435158 0.16944629 0.025405064, 0.3842105 0.16644624 0.025776967, 0.3842105 0.1694462 0.025777027, 0.38398442 0.16644633 0.026104257, 0.38398451 0.16944623 0.026104316, 0.38368681 0.16644619 0.026368037, 0.38368684 0.16944629 0.026368037, 0.38333467 0.16644619 0.026552573, 0.3833347 0.16944617 0.026552901, 0.38294837 0.16644624 0.026648059, 0.38294837 0.1694462 0.026648059, 0.38255057 0.16644619 0.026648059, 0.38255057 0.16944629 0.026648059, 0.38216445 0.16644621 0.026552573, 0.38216436 0.16944624 0.026552901, 0.38181219 0.1664463 0.026367798, 0.38181216 0.16944622 0.026368037, 0.38151458 0.16644621 0.026104197, 0.38151452 0.16944624 0.026104316, 0.38128856 0.16644616 0.025776967, 0.3812885 0.16944626 0.025777087, 0.38114759 0.16644618 0.025404826, 0.38114741 0.16944629 0.025405064, 0.38109955 0.16644631 0.025010005, 0.38109955 0.16944629 0.025010243, 0.38439944 0.16644496 0.05001007, 0.38435152 0.16644481 0.050404981, 0.38439944 0.16944492 0.050010368, 0.38435158 0.16944486 0.050404981, 0.3842105 0.16644481 0.050776795, 0.38421056 0.16944483 0.050777003, 0.3839846 0.16644487 0.051104024, 0.38398457 0.16944486 0.051104471, 0.38368669 0.1664449 0.051367953, 0.38368684 0.16944486 0.051368162, 0.38333461 0.16644491 0.051552728, 0.38333461 0.16944478 0.051552966, 0.38294837 0.16644481 0.051647976, 0.38294834 0.16944483 0.051648214, 0.38255063 0.16644476 0.051647976, 0.38255051 0.16944487 0.051648185, 0.38216439 0.16644481 0.051552728, 0.38216439 0.16944477 0.051552966, 0.38181224 0.16644475 0.051367953, 0.3818121 0.16944481 0.051368162, 0.3815144 0.16644481 0.051104024, 0.38151437 0.16944481 0.051104471, 0.38128856 0.16644473 0.050776795, 0.3812885 0.16944477 0.050777003, 0.38114741 0.16644488 0.050404981, 0.38114747 0.16944478 0.050405219, 0.38109949 0.16644485 0.050010249, 0.38109943 0.1694449 0.050010368, 0.38439944 0.16644768 9.9390745e-06, 0.38435152 0.16644768 0.00040484965, 0.38439941 0.16944769 1.0177493e-05, 0.38435158 0.16944769 0.00040499866, 0.3842105 0.16644768 0.00077666342, 0.38421056 0.16944769 0.00077690184, 0.38398454 0.16644764 0.0011043996, 0.38398457 0.1694476 0.0011043996, 0.38368681 0.16644767 0.0013678223, 0.38368681 0.1694476 0.0013680607, 0.38333461 0.16644756 0.0015528351, 0.38333455 0.1694476 0.0015528351, 0.38294849 0.16644764 0.0016479343, 0.38294834 0.16944756 0.0016480833, 0.38255057 0.16644762 0.0016479343, 0.38255057 0.16944753 0.0016480833, 0.38216439 0.16644762 0.0015528351, 0.38216439 0.1694476 0.0015530735, 0.3818123 0.16644764 0.0013678223, 0.38181216 0.16944765 0.0013680607, 0.38151458 0.16644764 0.0011041313, 0.38151443 0.16944765 0.0011043996, 0.38128862 0.16644761 0.00077666342, 0.3812885 0.16944771 0.00077717006, 0.3811475 0.16644767 0.00040493906, 0.38114735 0.16944773 0.00040499866, 0.38109949 0.16644759 9.9390745e-06, 0.38109943 0.16944771 1.0296702e-05, 0.18544939 0.1694468 -0.0059898943, 0.18551615 0.1694468 -0.0054392964, 0.18544927 0.16644681 -0.0059898943, 0.18551615 0.16644679 -0.0054394752, 0.18571271 0.16944669 -0.0049209148, 0.18571278 0.16644669 -0.0049210638, 0.18602774 0.16944669 -0.0044644624, 0.18602777 0.16644667 -0.0044647008, 0.18644272 0.16944677 -0.0040969402, 0.18644279 0.16644667 -0.0040970594, 0.18693364 0.16944671 -0.0038393289, 0.18693376 0.16644669 -0.0038393289, 0.18747208 0.16944671 -0.0037066489, 0.18747206 0.16644669 -0.003706798, 0.18802658 0.16944662 -0.0037064999, 0.18802655 0.16644669 -0.003706798, 0.18856496 0.16944665 -0.0038393289, 0.18856499 0.16644663 -0.0038393289, 0.18905583 0.16944671 -0.0040969402, 0.18905587 0.16644669 -0.0040970594, 0.18947095 0.16944668 -0.0044646114, 0.18947095 0.16644669 -0.0044646114, 0.18978579 0.16944677 -0.0049209148, 0.18978593 0.16644669 -0.0049211532, 0.18998247 0.1694468 -0.0054392964, 0.18998241 0.16644682 -0.0054394752, 0.19004926 0.16944683 -0.0059897453, 0.19004942 0.16644681 -0.0059900135, 0.18544942 0.16944602 0.0060101897, 0.18551612 0.16944607 0.0065606683, 0.1854493 0.16644612 0.0060100108, 0.18551615 0.16644612 0.0065602809, 0.18571275 0.16944604 0.0070790797, 0.18571284 0.16644607 0.0070787817, 0.18602782 0.16944596 0.0075354427, 0.18602777 0.16644602 0.0075351447, 0.18644273 0.16944605 0.0079029649, 0.18644275 0.16644597 0.0079029649, 0.18693373 0.16944598 0.008160606, 0.1869337 0.16644603 0.008160457, 0.18747209 0.16944602 0.0082934946, 0.18747211 0.16644597 0.008293137, 0.18802661 0.16944593 0.0082933456, 0.18802655 0.16644603 0.0082933456, 0.18856496 0.16944593 0.008160606, 0.18856497 0.16644597 0.008160457, 0.18905582 0.16944605 0.0079029649, 0.18905579 0.16644609 0.0079029649, 0.18947087 0.16944605 0.0075354427, 0.18947086 0.16644603 0.0075352937, 0.1897859 0.16944611 0.0070789903, 0.18978593 0.16644609 0.0070787817, 0.1899825 0.16944608 0.0065606683, 0.18998249 0.16644609 0.0065604597, 0.19004938 0.16944611 0.0060101002, 0.19004934 0.16644609 0.0060100108, 0.38744947 0.16944736 0.0060101897, 0.38751629 0.16944747 0.0065606683, 0.38744953 0.16644743 0.0060100108, 0.38751641 0.16644734 0.0065604597, 0.38771287 0.16944729 0.0070790797, 0.38771293 0.16644734 0.0070787817, 0.38802794 0.16944723 0.0075354427, 0.388028 0.16644742 0.0075351447, 0.38844296 0.16944727 0.0079030544, 0.38844284 0.1664473 0.0079029649, 0.38893393 0.16944723 0.008160606, 0.38893399 0.16644742 0.0081605166, 0.38947228 0.16944726 0.0082934946, 0.38947222 0.16644737 0.0082933456, 0.39002663 0.1694473 0.0082934946, 0.39002678 0.16644724 0.0082931966, 0.39056507 0.16944735 0.008160606, 0.39056513 0.16644725 0.008160457, 0.39105594 0.1694473 0.0079029649, 0.39105603 0.16644725 0.0079029649, 0.39147109 0.16944736 0.0075354427, 0.39147112 0.16644733 0.0075351447, 0.39178607 0.16944739 0.0070790797, 0.39178604 0.16644736 0.0070787817, 0.39198264 0.16944739 0.0065606683, 0.3919827 0.16644743 0.0065603703, 0.39204952 0.16944732 0.0060101897, 0.39204952 0.16644734 0.0060100108, 0.38744959 0.16944812 -0.0059897453, 0.38751635 0.16944808 -0.0054393858, 0.38744959 0.16644807 -0.0059900135, 0.38751635 0.16644807 -0.0054396242, 0.38771281 0.16944799 -0.0049209148, 0.38771299 0.16644794 -0.0049211532, 0.38802782 0.169448 -0.0044646114, 0.388028 0.16644792 -0.0044646114, 0.38844296 0.16944787 -0.0040969402, 0.38844296 0.16644794 -0.0040970594, 0.38893399 0.16944797 -0.0038393289, 0.38893405 0.16644798 -0.0038394779, 0.38947219 0.16944802 -0.0037064999, 0.38947222 0.16644797 -0.003706798, 0.39002672 0.169448 -0.0037066489, 0.39002672 0.16644801 -0.003706798, 0.39056504 0.169448 -0.0038393289, 0.39056513 0.16644797 -0.0038393289, 0.39105603 0.16944802 -0.0040969402, 0.39105603 0.16644804 -0.0040970594, 0.39147109 0.16944802 -0.0044646114, 0.39147112 0.16644798 -0.0044646114, 0.39178604 0.169448 -0.0049209148, 0.39178601 0.1664481 -0.0049211532, 0.39198261 0.169448 -0.0054393858, 0.3919827 0.16644815 -0.0054394752, 0.39204955 0.16944802 -0.0059897453, 0.39204946 0.16644813 -0.0059898943, 0.22639941 0.16644958 -0.049989924, 0.22635148 0.16644949 -0.049595192, 0.22639939 0.16944951 -0.049989834, 0.22635141 0.16944951 -0.049595013, 0.22621042 0.16644943 -0.049223199, 0.22621031 0.16944954 -0.04922305, 0.22598448 0.16644949 -0.048895821, 0.22598445 0.16944945 -0.048895702, 0.22568668 0.16644943 -0.048632041, 0.22568658 0.16944945 -0.048631772, 0.22533447 0.16644949 -0.048447266, 0.22533447 0.16944948 -0.048446998, 0.22494827 0.16644944 -0.048352018, 0.22494827 0.16944948 -0.048351899, 0.22455052 0.16644934 -0.048352018, 0.22455047 0.16944939 -0.048351899, 0.22416419 0.16644943 -0.048447117, 0.22416426 0.16944943 -0.048446998, 0.22381209 0.16644947 -0.048632041, 0.22381203 0.16944948 -0.048631921, 0.22351432 0.16644944 -0.048895702, 0.22351435 0.16944943 -0.048895702, 0.22328833 0.1664494 -0.049223199, 0.2232883 0.16944951 -0.04922305, 0.22314727 0.1664494 -0.049595192, 0.22314729 0.16944951 -0.049595013, 0.22309932 0.16644955 -0.049990043, 0.22309934 0.16944954 -0.049989834, 0.22639941 0.16644809 -0.024989977, 0.22635143 0.16644806 -0.024595097, 0.22639939 0.16944806 -0.024989828, 0.22635144 0.16944808 -0.024595007, 0.2262104 0.16644806 -0.024223164, 0.22621034 0.16944814 -0.024222985, 0.22598445 0.16644806 -0.023895755, 0.22598445 0.169448 -0.023895606, 0.22568667 0.16644806 -0.023632035, 0.22568671 0.169448 -0.023631826, 0.22533438 0.16644806 -0.02344726, 0.22533445 0.169448 -0.023446903, 0.22494823 0.166448 -0.023352101, 0.22494827 0.16944805 -0.023351893, 0.22455049 0.16644804 -0.023352012, 0.22455053 0.16944802 -0.023351803, 0.22416425 0.16644812 -0.02344726, 0.22416429 0.16944803 -0.023446903, 0.22381204 0.16644809 -0.023632124, 0.22381203 0.16944803 -0.023631915, 0.22351432 0.16644809 -0.023895755, 0.2235143 0.16944803 -0.023895606, 0.22328842 0.16644804 -0.024223074, 0.22328831 0.16944803 -0.024222985, 0.22314735 0.16644812 -0.024595246, 0.22314733 0.16944811 -0.024595007, 0.22309932 0.16644812 -0.024989977, 0.22309929 0.16944814 -0.024989828, 0.22639933 0.16644672 9.9390745e-06, 0.22635156 0.16644669 0.00040493906, 0.22639942 0.16944671 1.0296702e-05, 0.22635138 0.16944668 0.00040499866, 0.2262104 0.16644663 0.00077666342, 0.22621039 0.16944671 0.00077690184, 0.22598442 0.16644669 0.0011043996, 0.22598439 0.16944668 0.0011043996, 0.22568674 0.16644657 0.0013679117, 0.22568658 0.16944665 0.0013680607, 0.22533448 0.16644657 0.0015528351, 0.22533447 0.16944659 0.0015528351, 0.22494826 0.1664466 0.0016479343, 0.22494817 0.16944659 0.0016480833, 0.22455049 0.1664466 0.0016479939, 0.22455049 0.16944659 0.0016480833, 0.22416428 0.16644667 0.0015528351, 0.22416423 0.16944659 0.0015528351, 0.22381201 0.16644667 0.0013679117, 0.223812 0.16944656 0.0013680607, 0.22351432 0.16644666 0.0011041313, 0.22351433 0.16944665 0.0011043996, 0.22328837 0.1664466 0.00077666342, 0.22328833 0.16944668 0.00077690184, 0.2231473 0.16644669 0.00040493906, 0.2231473 0.16944665 0.00040508807, 0.22309935 0.16644669 9.9390745e-06, 0.22309935 0.16944668 1.0296702e-05, 0.22639941 0.16644531 0.025010005, 0.22635145 0.16644529 0.025405064, 0.22639941 0.16944528 0.025010094, 0.22635141 0.16944525 0.025405064, 0.2262104 0.1664452 0.02577664, 0.22621027 0.16944528 0.025777027, 0.22598433 0.16644529 0.026104257, 0.22598439 0.16944525 0.026104316, 0.22568668 0.16644526 0.026368037, 0.22568657 0.16944526 0.026368037, 0.22533447 0.16644526 0.026552573, 0.22533441 0.16944523 0.026552901, 0.22494826 0.16644531 0.026648059, 0.2249482 0.16944528 0.026648059, 0.22455043 0.16644524 0.026648059, 0.22455047 0.16944522 0.026648059, 0.2241642 0.16644529 0.026552901, 0.22416423 0.16944522 0.026552901, 0.22381204 0.16644517 0.026367798, 0.223812 0.16944526 0.026368037, 0.22351426 0.1664453 0.026104257, 0.22351435 0.16944513 0.026104316, 0.2232884 0.16644526 0.02577664, 0.22328839 0.16944526 0.025777027, 0.22314733 0.16644529 0.025405064, 0.22314732 0.16944531 0.025405064, 0.22309932 0.16644526 0.025009945, 0.22309923 0.16944537 0.025010094, 0.22639945 0.16644382 0.050010249, 0.22635143 0.16644388 0.050404981, 0.22639936 0.16944385 0.050010398, 0.22635147 0.16944382 0.050404981, 0.2262104 0.16644388 0.050776795, 0.22621036 0.16944385 0.050776795, 0.22598439 0.16644388 0.051104233, 0.22598441 0.16944385 0.051104471, 0.22568661 0.16644385 0.051367953, 0.22568667 0.16944379 0.051368162, 0.22533447 0.16644394 0.051552728, 0.22533447 0.16944382 0.051552966, 0.22494829 0.16644382 0.051647976, 0.22494812 0.16944385 0.051648185, 0.22455043 0.16644381 0.051647976, 0.2245504 0.16944382 0.051647976, 0.22416428 0.16644379 0.051552728, 0.22416425 0.16944382 0.051552966, 0.22381204 0.16644391 0.051367953, 0.22381198 0.16944388 0.051368162, 0.22351436 0.16644387 0.051104233, 0.22351436 0.16944382 0.051104471, 0.2232884 0.16644382 0.050776795, 0.22328836 0.16944394 0.050777003, 0.22314739 0.16644379 0.050404981, 0.22314715 0.16944388 0.050405219, 0.22309941 0.16644385 0.05001007, 0.22309932 0.16944388 0.050010368, 0.37274948 0.16944335 0.078010187, 0.39774951 0.16644345 0.078010127, 0.39774948 0.16944344 0.078010187, 0.37274942 0.1664433 0.078010127, 0.21674925 0.16944236 0.078010187, 0.36074945 0.16644327 0.078010127, 0.36074954 0.16944318 0.078010336, 0.21674925 0.16644233 0.078010127, 0.36074954 0.16945197 -0.077989861, 0.21674927 0.1664511 -0.07799001, 0.2167493 0.16945109 -0.077989742, 0.36074945 0.16645198 -0.07799001, 0.20474935 0.16945095 -0.077989861, 0.17974937 0.16645077 -0.07799001, 0.17974925 0.16945082 -0.077989861, 0.20474932 0.16645102 -0.07799001, 0.22314733 0.16644385 0.049615219, 0.22314718 0.16944396 0.049615219, 0.22328839 0.16644385 0.049243078, 0.22328842 0.16944388 0.049243405, 0.22351436 0.16644387 0.048916146, 0.22351435 0.16944385 0.048916176, 0.22381212 0.16644397 0.048652247, 0.22381207 0.16944402 0.048652455, 0.22416438 0.16644397 0.048467234, 0.22416423 0.16944414 0.048467472, 0.22455047 0.16644408 0.048372224, 0.22455049 0.16944402 0.048372224, 0.22494827 0.16644405 0.048371986, 0.22494814 0.16944398 0.048372224, 0.22533448 0.16644397 0.048467234, 0.22533438 0.16944411 0.048467681, 0.2256867 0.166444 0.048652247, 0.22568667 0.16944402 0.048652455, 0.22598442 0.16644393 0.048916146, 0.22598441 0.16944385 0.048916176, 0.2262104 0.16644388 0.049243078, 0.22621039 0.16944389 0.049243405, 0.22635143 0.16644388 0.049615219, 0.22635144 0.16944385 0.049615219, 0.22314738 0.16644526 0.024615154, 0.22314735 0.16944525 0.024615362, 0.22328831 0.16644534 0.02424325, 0.22328839 0.16944526 0.02424325, 0.2235143 0.16644534 0.023915783, 0.22351435 0.16944531 0.02391611, 0.22381212 0.1664454 0.023652092, 0.22381198 0.16944531 0.023652241, 0.22416431 0.16644534 0.023467407, 0.22416431 0.16944525 0.023467466, 0.22455059 0.1664454 0.023372069, 0.22455053 0.16944546 0.023372158, 0.22494826 0.16644543 0.023372069, 0.22494818 0.1694455 0.023372307, 0.22533441 0.16644536 0.023467407, 0.2253345 0.16944531 0.023467466, 0.22568673 0.16644531 0.023652092, 0.22568661 0.16944528 0.023652241, 0.22598445 0.16644531 0.023915783, 0.22598433 0.16944528 0.02391611, 0.22621039 0.16644531 0.02424325, 0.22621033 0.1694454 0.02424325, 0.22635144 0.16644526 0.024615154, 0.22635138 0.16944528 0.024615362, 0.22314735 0.1664466 -0.00038485229, 0.22314727 0.16944668 -0.00038464367, 0.22328836 0.16644669 -0.00075669587, 0.2232884 0.16944668 -0.00075666606, 0.22351432 0.16644675 -0.0010841936, 0.2235143 0.16944674 -0.0010839254, 0.22381204 0.16644675 -0.0013478547, 0.22381198 0.16944683 -0.0013476163, 0.22416425 0.16644682 -0.0015326291, 0.22416425 0.16944674 -0.0015324801, 0.2245505 0.16644673 -0.001628086, 0.22455049 0.16944675 -0.0016278476, 0.22494821 0.16644682 -0.001628086, 0.2249482 0.16944683 -0.0016278476, 0.22533441 0.16644683 -0.0015328377, 0.22533441 0.16944681 -0.0015324801, 0.22568664 0.16644682 -0.0013478249, 0.22568662 0.16944677 -0.0013476163, 0.22598436 0.16644682 -0.001084134, 0.22598439 0.16944677 -0.0010839254, 0.22621033 0.16644675 -0.00075669587, 0.22621039 0.16944674 -0.00075666606, 0.22635144 0.16644681 -0.00038485229, 0.22635145 0.16944671 -0.00038464367, 0.22314732 0.16644815 -0.025384888, 0.22314739 0.16944805 -0.02538465, 0.22328833 0.16644809 -0.025756821, 0.2232884 0.16944811 -0.025756583, 0.2235143 0.16644815 -0.026084051, 0.22351435 0.16944817 -0.026083931, 0.2238121 0.16644815 -0.02634798, 0.22381209 0.1694482 -0.026347622, 0.22416431 0.16644818 -0.026532754, 0.22416428 0.16944823 -0.026532635, 0.22455053 0.16644822 -0.026628003, 0.22455052 0.16944818 -0.026627794, 0.22494823 0.1664483 -0.026628003, 0.22494817 0.16944826 -0.026627794, 0.22533441 0.16644827 -0.026532754, 0.22533441 0.16944824 -0.026532754, 0.2256867 0.16644818 -0.02634798, 0.22568665 0.1694482 -0.026347622, 0.22598433 0.16644824 -0.026084051, 0.22598439 0.16944814 -0.026083931, 0.22621033 0.16644818 -0.025756821, 0.22621039 0.1694482 -0.025756583, 0.2263515 0.16644812 -0.025384888, 0.22635144 0.16944814 -0.02538465, 0.22314739 0.16644955 -0.050385013, 0.22314724 0.16944957 -0.050384745, 0.22328831 0.16644958 -0.050756678, 0.22328842 0.16944948 -0.050756589, 0.22351432 0.16644952 -0.051084146, 0.22351433 0.16944958 -0.051083937, 0.22381204 0.16644953 -0.051347986, 0.22381207 0.16944961 -0.051347658, 0.22416431 0.16644953 -0.05153276, 0.22416428 0.16944954 -0.051532432, 0.22455052 0.16644958 -0.051628008, 0.2245505 0.16944957 -0.051627681, 0.22494818 0.16644958 -0.051628008, 0.2249482 0.16944963 -0.051627681, 0.22533441 0.16644959 -0.05153276, 0.22533447 0.16944963 -0.05153276, 0.22568667 0.16644958 -0.051347777, 0.22568671 0.16944963 -0.051347658, 0.22598442 0.16644961 -0.051084146, 0.22598439 0.16944957 -0.051084056, 0.22621036 0.16644956 -0.050756827, 0.22621033 0.16944957 -0.050756589, 0.22635141 0.16644949 -0.050384894, 0.22635141 0.16944951 -0.050384745, 0.1899825 0.16644683 -0.0065402836, 0.19494829 0.1664466 -0.001628086, 0.30216429 0.16644588 0.023467407, 0.3018122 0.16644585 0.023652092, 0.38947228 0.16644816 -0.0082732588, 0.19533446 0.16644661 -0.0015328377, 0.18747211 0.16644627 0.0037268549, 0.39056519 0.1664481 -0.0081404299, 0.39002666 0.16644822 -0.0082733482, 0.18693376 0.16644619 0.0038595945, 0.30151442 0.16644579 0.023915783, 0.1897859 0.16644683 -0.007058844, 0.38893387 0.16644827 -0.0081404299, 0.40274957 0.16644371 0.073010132, 0.4026241 0.16644369 0.074122563, 0.40225437 0.16644353 0.075179502, 0.40165868 0.16644356 0.076127395, 0.40086696 0.16644356 0.076919094, 0.39991888 0.16644347 0.077514812, 0.39886209 0.16644345 0.077884659, 0.39105603 0.16644819 -0.0078828186, 0.30128846 0.16644578 0.024243012, 0.28274938 0.16644488 0.039010063, 0.17487468 0.16644225 0.074122563, 0.1797493 0.16644204 0.078010127, 0.17584027 0.16644201 0.076127663, 0.18644278 0.16644624 0.0041170269, 0.17524451 0.16644207 0.075179502, 0.38844284 0.16644825 -0.0078829676, 0.39147106 0.16644818 -0.0075151771, 0.18602777 0.16644622 0.0044847578, 0.37184846 0.1664433 0.077443734, 0.37212595 0.16644329 0.077791974, 0.37196761 0.16644336 0.077633634, 0.38802794 0.16644819 -0.0075151771, 0.37177446 0.16644338 0.077232495, 0.37252691 0.16644335 0.077985093, 0.37231562 0.16644332 0.077911034, 0.38435152 0.16644914 -0.025384888, 0.3917861 0.16644816 -0.0070587248, 0.18571278 0.16644618 0.0049411207, 0.37174943 0.16644333 0.07701017, 0.38771299 0.16644803 -0.0070587248, 0.38216427 0.16644782 -0.0015328377, 0.37174943 0.16644363 0.073010221, 0.37049207 0.16645154 -0.069674388, 0.38255057 0.16645057 -0.051628008, 0.38216445 0.16645053 -0.05153276, 0.1747493 0.16644228 0.073010221, 0.37160414 0.16644359 0.07181339, 0.18551615 0.16644612 0.0054595321, 0.36958984 0.16645151 -0.068875298, 0.38181213 0.16644788 -0.0013478547, 0.38181219 0.16645053 -0.051347986, 0.38151446 0.1664505 -0.051084146, 0.2089763 0.16644278 0.068335012, 0.20790908 0.16644275 0.068895295, 0.3815144 0.16644783 -0.0010841936, 0.37117678 0.16645151 -0.070666537, 0.38294843 0.16645057 -0.051628008, 0.36118332 0.1664433 0.077911034, 0.36153129 0.16644323 0.077633664, 0.36137298 0.1664433 0.077791974, 0.38128844 0.16644774 -0.00075669587, 0.36852255 0.16645141 -0.068314895, 0.21014664 0.16644278 0.068046674, 0.3812885 0.16645052 -0.050756827, 0.37160408 0.16645171 -0.071793452, 0.39774957 0.16645218 -0.07799001, 0.20700681 0.16644269 0.069694534, 0.36735216 0.16645144 -0.068026528, 0.38114741 0.16645057 -0.050385013, 0.3617495 0.16644326 0.07701017, 0.36172441 0.16644323 0.077232733, 0.36165044 0.16644329 0.077443972, 0.36097196 0.16644329 0.077985093, 0.23734352 0.16644913 -0.041593388, 0.23689979 0.16644907 -0.04032509, 0.37174949 0.16645171 -0.072989985, 0.36614677 0.16645148 -0.068026528, 0.20632198 0.16644262 0.070686385, 0.23805836 0.16644913 -0.042731091, 0.23674935 0.16644895 -0.038990065, 0.20589474 0.16644251 0.071813539, 0.23900844 0.16644929 -0.04368107, 0.34421042 0.16644885 -0.025756702, 0.34398457 0.16644892 -0.026084051, 0.19635144 0.16644371 0.049615219, 0.36174944 0.16644351 0.073010221, 0.34368667 0.16644891 -0.02634798, 0.19621029 0.16644369 0.049243376, 0.37117675 0.16644366 0.070686385, 0.24014612 0.16644928 -0.044395879, 0.19598436 0.16644374 0.048916146, 0.37049195 0.16644379 0.069694534, 0.34333459 0.16644891 -0.026532754, 0.37274942 0.16645207 -0.07799001, 0.37174949 0.16645195 -0.076990053, 0.38435152 0.1664449 0.049615219, 0.27674943 0.16644441 0.045009926, 0.24141428 0.16644937 -0.044839486, 0.30435148 0.16644436 0.049615219, 0.34114739 0.16644464 0.049614981, 0.36958984 0.16644379 0.068895087, 0.34128848 0.16644463 0.049243078, 0.24274935 0.16644928 -0.044989929, 0.28274944 0.1664492 -0.038990065, 0.30128846 0.16644719 -0.00075669587, 0.30114737 0.16644718 -0.00038485229, 0.34294835 0.16644903 -0.026628003, 0.30421045 0.16644436 0.049243376, 0.30114734 0.16644861 -0.025384888, 0.30128837 0.16644861 -0.025756702, 0.30151442 0.16644861 -0.0260842, 0.30181208 0.16644864 -0.02634798, 0.37177452 0.16645201 -0.077212647, 0.37231556 0.16645207 -0.077891037, 0.37252694 0.16645207 -0.077964976, 0.37184843 0.16645202 -0.077424034, 0.36497641 0.16645142 -0.068315044, 0.37212601 0.16645202 -0.077771857, 0.19314732 0.16644368 0.049615219, 0.37196764 0.16645201 -0.077613547, 0.3685225 0.16644377 0.068335012, 0.21631545 0.1664423 0.077911034, 0.21652687 0.16644232 0.077985093, 0.36735222 0.16644374 0.068046674, 0.34255061 0.16644901 -0.026628003, 0.34435153 0.16645034 -0.050384894, 0.28259894 0.16644929 -0.04032509, 0.21612579 0.16644233 0.077791974, 0.36614689 0.16644375 0.068046674, 0.28215525 0.16644949 -0.041593418, 0.34216437 0.16644889 -0.026532754, 0.19598436 0.16644661 -0.0010841936, 0.21596748 0.16644233 0.077633664, 0.28144041 0.16644941 -0.042731091, 0.34421042 0.16645031 -0.050756827, 0.36390916 0.1664515 -0.068875298, 0.28049031 0.16644952 -0.04368107, 0.30114734 0.16645004 -0.050384894, 0.30128846 0.16645004 -0.050756827, 0.21584837 0.16644239 0.077443972, 0.27935269 0.16644952 -0.044395879, 0.30151439 0.16645007 -0.051084146, 0.19568665 0.16644658 -0.0013478547, 0.34181213 0.16644889 -0.02634798, 0.27808449 0.16644952 -0.044839486, 0.30181214 0.16645005 -0.051347777, 0.38421068 0.16644484 0.049243376, 0.3839846 0.16644487 0.048915848, 0.34398451 0.16644612 0.023915783, 0.34398445 0.16645034 -0.051084146, 0.36300692 0.16645148 -0.069674388, 0.21574926 0.16644239 0.07701017, 0.2157744 0.16644239 0.077232733, 0.27674946 0.1664495 -0.044989929, 0.30216429 0.16645005 -0.05153276, 0.38368681 0.16644502 0.048652008, 0.34368673 0.1664461 0.023652092, 0.18947089 0.16644692 -0.0075151771, 0.34421045 0.16644607 0.024243012, 0.34151438 0.16644889 -0.0260842, 0.38333455 0.16644514 0.048467234, 0.34368676 0.16645034 -0.051347986, 0.34128848 0.16644888 -0.025756821, 0.34333453 0.16644597 0.023467317, 0.38294837 0.16644509 0.048372224, 0.18905585 0.16644692 -0.0078829676, 0.36232218 0.16645154 -0.070666328, 0.34333459 0.16645026 -0.05153276, 0.38255051 0.16644503 0.048372224, 0.34294835 0.16644616 0.023372069, 0.18856491 0.16644692 -0.0081404299, 0.38114741 0.16644783 -0.00038485229, 0.19635138 0.16644792 -0.025384888, 0.38216427 0.16644503 0.048467234, 0.23674943 0.1664446 0.039010063, 0.34255061 0.16644616 0.023372069, 0.3443515 0.16644745 -0.00038485229, 0.18802655 0.16644698 -0.0082732588, 0.38181207 0.16644508 0.048652008, 0.19621037 0.16644798 -0.025756821, 0.3815144 0.16644493 0.048915848, 0.34216443 0.16644597 0.023467407, 0.34421048 0.16644745 -0.00075669587, 0.36189476 0.16645159 -0.071793452, 0.19598436 0.16644806 -0.0260842, 0.34294829 0.16645034 -0.051628008, 0.3812885 0.16644482 0.049243376, 0.21574934 0.16644257 0.073010132, 0.34181222 0.16644605 0.023652092, 0.18747206 0.16644698 -0.0082732588, 0.3617495 0.1664516 -0.072989985, 0.34255064 0.16645032 -0.051628008, 0.18693367 0.16644691 -0.0081405789, 0.34151441 0.16644615 0.023915783, 0.24274933 0.16644432 0.045010194, 0.18644285 0.16644692 -0.0078828186, 0.34128848 0.16644606 0.02424325, 0.18602777 0.16644691 -0.0075150579, 0.19314733 0.16644791 -0.025385007, 0.18571278 0.16644679 -0.0070587248, 0.38435152 0.16644633 0.024615064, 0.36153129 0.16645202 -0.077613547, 0.36165044 0.16645196 -0.077424034, 0.36172447 0.16645195 -0.077212796, 0.36174944 0.16645193 -0.076990053, 0.38421056 0.16644628 0.02424325, 0.36137304 0.16645196 -0.077771857, 0.19568659 0.16644797 -0.02634798, 0.38398454 0.16644633 0.023915783, 0.3839846 0.16644914 -0.0260842, 0.38368681 0.16644914 -0.02634798, 0.38368675 0.16644637 0.023652092, 0.38333455 0.16644636 0.023467317, 0.1953344 0.16644804 -0.026532754, 0.3842105 0.16644913 -0.025756821, 0.20518318 0.16644232 0.077910885, 0.20553103 0.16644226 0.077633634, 0.20537272 0.16644225 0.077791974, 0.38294831 0.16644658 0.023372069, 0.38333461 0.1664492 -0.026532754, 0.36097208 0.16645192 -0.077964976, 0.36118332 0.16645198 -0.077891037, 0.19568665 0.16644381 0.048652247, 0.38255051 0.16644646 0.023372069, 0.19494823 0.16644804 -0.026628003, 0.20497182 0.16644232 0.077985093, 0.20574924 0.16644232 0.07701017, 0.38216427 0.16644634 0.023467407, 0.20572418 0.16644233 0.077232495, 0.20565027 0.16644226 0.077443734, 0.20474929 0.16644225 0.078010127, 0.38294849 0.16644919 -0.026628003, 0.19533443 0.16644388 0.048467234, 0.19455045 0.16644803 -0.026628003, 0.34216452 0.16645023 -0.05153276, 0.34181228 0.16645032 -0.051347777, 0.19635144 0.16644931 -0.050385013, 0.3639091 0.16644368 0.068895295, 0.36300692 0.16644365 0.069694534, 0.38255057 0.16644919 -0.026628003, 0.19416422 0.16644804 -0.026532754, 0.36232212 0.1664436 0.070686385, 0.1949482 0.16644381 0.048371986, 0.36497641 0.16644375 0.068335012, 0.38216445 0.16644922 -0.026532993, 0.36189476 0.1664435 0.07181339, 0.19381204 0.16644791 -0.02634798, 0.30421034 0.16644722 -0.00075669587, 0.30398443 0.16644734 -0.001084134, 0.19455045 0.1664439 0.048372224, 0.38181213 0.16644919 -0.02634798, 0.19635135 0.16644514 0.024615154, 0.21449196 0.16645059 -0.069674388, 0.38151446 0.16644916 -0.026084051, 0.30368671 0.16644733 -0.0013478547, 0.19416422 0.16644387 0.048467234, 0.21358965 0.16645056 -0.068875298, 0.19621035 0.16644512 0.02424325, 0.19351432 0.16644791 -0.0260842, 0.3812885 0.16644911 -0.025756702, 0.19381207 0.16644379 0.048652008, 0.30333462 0.16644728 -0.0015326291, 0.19598442 0.16644514 0.023915783, 0.21517666 0.16645059 -0.070666328, 0.21252239 0.16645041 -0.068314895, 0.34435144 0.16644466 0.049615219, 0.3811475 0.16644484 0.049615219, 0.19351423 0.16644374 0.048916146, 0.30294836 0.16644734 -0.001628086, 0.19328836 0.16644791 -0.025756821, 0.21560405 0.16645066 -0.071793452, 0.19328833 0.16644374 0.049243376, 0.34114739 0.16644888 -0.025384888, 0.34421042 0.16644466 0.049243078, 0.30255052 0.16644728 -0.0016278774, 0.21135208 0.16645047 -0.068026528, 0.30435148 0.16644865 -0.025384888, 0.30398449 0.16644442 0.048916146, 0.30368683 0.16644448 0.048652247, 0.2057493 0.16644257 0.073010221, 0.21574937 0.16645074 -0.072989985, 0.30216435 0.16644721 -0.0015326291, 0.30421039 0.16644865 -0.025756702, 0.3033345 0.16644458 0.048467234, 0.40274945 0.1664519 -0.072989985, 0.38368675 0.16645055 -0.051347986, 0.38333461 0.16645056 -0.05153276, 0.38398454 0.16645059 -0.051084325, 0.39198259 0.16644813 -0.0065404028, 0.3842105 0.16645057 -0.050756827, 0.38435152 0.16645057 -0.050385013, 0.30181202 0.16644731 -0.0013478547, 0.21014664 0.1664504 -0.068026528, 0.19621037 0.16644938 -0.050756678, 0.2089763 0.16645044 -0.068315044, 0.3015143 0.16644734 -0.0010841936, 0.30294839 0.16644448 0.048372224, 0.19598438 0.16644941 -0.051084146, 0.20790905 0.1664505 -0.068875298, 0.34114739 0.16644606 0.024615064, 0.19568665 0.16644938 -0.051347986, 0.19533449 0.1664494 -0.05153276, 0.30255058 0.16644448 0.048372224, 0.30255046 0.16645008 -0.051628008, 0.21574935 0.16645099 -0.076990053, 0.30435142 0.16644585 0.024615064, 0.24141425 0.16644421 0.044859663, 0.21584846 0.16645102 -0.077424034, 0.21577445 0.16645096 -0.077212647, 0.39178601 0.16644748 0.0049412102, 0.39147112 0.16644748 0.0044849664, 0.30216429 0.16644457 0.048467234, 0.21631546 0.16645104 -0.077891037, 0.21652684 0.16645104 -0.077964976, 0.21596758 0.16645104 -0.077613547, 0.21612594 0.16645102 -0.077771857, 0.39105603 0.16644759 0.0041171461, 0.2070068 0.16645056 -0.069674268, 0.21560395 0.16644268 0.071813539, 0.30421039 0.16644582 0.02424325, 0.19494829 0.16644929 -0.051628008, 0.39198261 0.16644745 0.0054597408, 0.30181208 0.16644453 0.048652008, 0.20632207 0.16645056 -0.070666328, 0.24014606 0.16644439 0.044415817, 0.19455045 0.1664494 -0.051628008, 0.21517654 0.16644268 0.070686534, 0.39056501 0.16644743 0.0038595349, 0.20589462 0.16645063 -0.071793452, 0.39002672 0.16644745 0.0037267059, 0.40225431 0.16645209 -0.075159505, 0.40262419 0.16645199 -0.074102715, 0.23900847 0.16644438 0.043700978, 0.38947228 0.16644759 0.0037267059, 0.20565033 0.16645096 -0.077424124, 0.2057243 0.16645086 -0.077212647, 0.2057493 0.16645096 -0.076989934, 0.20553121 0.16645096 -0.077613547, 0.38802794 0.16644743 0.0044847578, 0.38771299 0.16644743 0.0049411207, 0.2144919 0.16644272 0.069694325, 0.20518324 0.16645098 -0.077891037, 0.20537286 0.16645096 -0.077771857, 0.38844296 0.16644752 0.0041170269, 0.23805833 0.16644435 0.04275094, 0.40165868 0.16645211 -0.076107457, 0.20497194 0.16645096 -0.077964976, 0.38751629 0.16644743 0.0054595321, 0.20574933 0.16645071 -0.072989985, 0.38893393 0.16644749 0.0038595349, 0.17474931 0.16645047 -0.072989985, 0.18551621 0.16644679 -0.0065402836, 0.2804904 0.1664446 0.043701038, 0.1931473 0.16644934 -0.050385013, 0.19328836 0.16644928 -0.050756827, 0.19351432 0.16644934 -0.051084146, 0.2135897 0.16644281 0.068895087, 0.19381207 0.16644934 -0.051347986, 0.19416428 0.16644941 -0.051532999, 0.19568673 0.16644514 0.023652092, 0.28144041 0.16644463 0.04275097, 0.17524448 0.16645065 -0.075159505, 0.17487465 0.16645053 -0.074102715, 0.19533443 0.16644512 0.023467407, 0.1949482 0.16644529 0.023372069, 0.30114743 0.16644435 0.049615219, 0.17757998 0.1664508 -0.077494934, 0.17863679 0.1664508 -0.077864721, 0.23734348 0.16644445 0.041613266, 0.17663187 0.16645065 -0.076899245, 0.17584014 0.16645065 -0.076107547, 0.27935281 0.16644458 0.044415876, 0.38435152 0.16644768 -0.00038485229, 0.21252239 0.16644278 0.068335012, 0.28215531 0.16644463 0.041613266, 0.19455048 0.16644523 0.023372069, 0.30128852 0.16644432 0.049243078, 0.27808458 0.16644441 0.044859633, 0.21135211 0.16644272 0.068046674, 0.23689973 0.16644463 0.040345237, 0.3842105 0.16644768 -0.00075669587, 0.28259903 0.16644482 0.040345237, 0.3015143 0.16644445 0.048915848, 0.38181213 0.16644637 0.023652092, 0.19416422 0.16644517 0.023467407, 0.30114749 0.16644575 0.024615154, 0.38398454 0.16644782 -0.001084134, 0.38151452 0.16644631 0.023915783, 0.39886209 0.16645227 -0.077864721, 0.39991888 0.16645218 -0.077494934, 0.40086696 0.16645211 -0.076899245, 0.38368681 0.16644782 -0.0013478249, 0.3812885 0.16644625 0.02424325, 0.19381204 0.16644517 0.023652092, 0.19351432 0.16644517 0.023915783, 0.38333461 0.1664477 -0.0015328377, 0.19635135 0.16644657 -0.00038485229, 0.34398448 0.16644756 -0.0010841936, 0.3436867 0.16644761 -0.0013478249, 0.17758 0.16644202 0.077514872, 0.17863679 0.16644201 0.077884659, 0.19328836 0.16644511 0.02424325, 0.38294837 0.16644783 -0.001628086, 0.34333441 0.16644759 -0.0015328377, 0.30398437 0.16644865 -0.026084051, 0.38255063 0.16644783 -0.0016278774, 0.38751641 0.16644806 -0.0065402836, 0.19621031 0.16644654 -0.00075690448, 0.18998252 0.1664461 0.0054595321, 0.30368668 0.16644862 -0.02634798, 0.34294835 0.16644756 -0.001628086, 0.19314732 0.16644505 0.024615064, 0.3033345 0.16644871 -0.026532754, 0.3811475 0.1664491 -0.025384799, 0.34255055 0.16644754 -0.001628086, 0.18978582 0.16644621 0.0049412102, 0.30294827 0.16644865 -0.026628003, 0.34435144 0.16644888 -0.025384888, 0.34114739 0.16645029 -0.050385013, 0.3421644 0.16644759 -0.0015328377, 0.30255058 0.16644865 -0.026628003, 0.30435142 0.16645002 -0.050384894, 0.34398445 0.1664447 0.048916146, 0.1894709 0.16644621 0.0044847578, 0.30216435 0.16644864 -0.026532754, 0.34181216 0.16644755 -0.0013478547, 0.17663191 0.16644202 0.076919362, 0.34368673 0.16644479 0.048652247, 0.30421039 0.16645005 -0.050756827, 0.34128848 0.16645032 -0.050756827, 0.34151438 0.16645032 -0.051084146, 0.3415145 0.16644752 -0.0010841936, 0.18905589 0.16644621 0.0041170269, 0.34333459 0.16644473 0.048467234, 0.3039844 0.16645007 -0.051084146, 0.34128848 0.1664474 -0.00075669587, 0.30368677 0.16645005 -0.051347986, 0.34294835 0.16644484 0.048371986, 0.38114735 0.16644633 0.024615154, 0.34255061 0.16644482 0.048371986, 0.3443515 0.16644606 0.024615154, 0.18856496 0.16644621 0.0038595945, 0.34216443 0.16644469 0.048467234, 0.30333444 0.16645013 -0.05153276, 0.18802661 0.16644621 0.0037267059, 0.34181228 0.16644469 0.048652247, 0.30398449 0.16644585 0.023915783, 0.3415145 0.16644461 0.048916146, 0.30368677 0.16644585 0.023652092, 0.30294827 0.16645008 -0.051628008, 0.19351421 0.16644666 -0.0010841936, 0.19328845 0.16644642 -0.00075669587, 0.30333444 0.16644596 0.023467317, 0.1931473 0.16644648 -0.00038485229, 0.19381204 0.1664466 -0.0013478249, 0.19416431 0.1664466 -0.0015328377, 0.30294833 0.16644596 0.023372069, 0.34114739 0.16644745 -0.00038488209, 0.19455045 0.16644664 -0.001628086, 0.30255046 0.16644591 0.023372069, 0.30435142 0.16644722 -0.00038485229, 0.30216435 0.16944577 0.023467466, 0.30181211 0.16944572 0.023652241, 0.38947228 0.16944823 -0.0082731098, 0.18747202 0.16944627 0.0037268549, 0.39056507 0.16944827 -0.0081403106, 0.39002672 0.16944823 -0.0082731098, 0.18693367 0.16944629 0.0038596839, 0.30151436 0.1694458 0.02391611, 0.19533443 0.16944663 -0.0015324801, 0.18978588 0.16944686 -0.0070586056, 0.1899825 0.1694468 -0.0065401644, 0.38893396 0.16944821 -0.0081401616, 0.39886209 0.16944349 0.077884927, 0.40274957 0.16944376 0.073010221, 0.39991894 0.1694434 0.077515021, 0.39105594 0.16944823 -0.0078825802, 0.40086702 0.16944349 0.076919362, 0.40165868 0.16944349 0.076127812, 0.40225443 0.16944349 0.075179622, 0.30128837 0.16944578 0.02424325, 0.4026241 0.1694437 0.074122742, 0.28274941 0.16944486 0.039010212, 0.18644272 0.16944632 0.0041173846, 0.38844296 0.1694482 -0.0078826994, 0.39147109 0.16944823 -0.0075149387, 0.18602775 0.16944622 0.0044849664, 0.37212589 0.16944331 0.077792034, 0.37184846 0.16944331 0.077444002, 0.37196758 0.16944331 0.077633724, 0.38802806 0.16944812 -0.0075150579, 0.37231556 0.16944331 0.077911273, 0.37177449 0.16944334 0.077232763, 0.37252697 0.16944331 0.077985212, 0.18571277 0.16944614 0.0049413592, 0.39178619 0.16944815 -0.0070586056, 0.38435158 0.16944908 -0.02538465, 0.37174955 0.16944331 0.077010319, 0.37174943 0.16944352 0.073010221, 0.38771293 0.16944808 -0.0070586056, 0.3825506 0.16945064 -0.051627681, 0.37049201 0.16945155 -0.069674268, 0.38216439 0.16945055 -0.051532432, 0.38216427 0.16944782 -0.0015324801, 0.37160423 0.1694435 0.071813688, 0.18551619 0.16944608 0.0054597408, 0.17974928 0.16944206 0.078010187, 0.17474928 0.16944227 0.073010221, 0.17524442 0.16944215 0.075179622, 0.17487468 0.16944221 0.074122742, 0.38181213 0.16944784 -0.0013478249, 0.38181207 0.1694506 -0.051347658, 0.3695899 0.16945142 -0.06887494, 0.38151434 0.1694506 -0.051084056, 0.3815144 0.16944781 -0.0010839254, 0.20897636 0.16944277 0.068335161, 0.20790899 0.16944277 0.068895444, 0.37117669 0.16945155 -0.070666328, 0.38294834 0.16945064 -0.051627681, 0.38128844 0.16944776 -0.00075666606, 0.36153135 0.16944323 0.077633992, 0.36118329 0.16944319 0.077911392, 0.36137298 0.1694432 0.077792183, 0.21014661 0.1694428 0.068046674, 0.36852244 0.16945146 -0.068314895, 0.3812885 0.16945052 -0.050756589, 0.37160411 0.16945165 -0.071793184, 0.39774951 0.16945222 -0.077989861, 0.2070068 0.16944271 0.069694713, 0.36735222 0.16945139 -0.068026289, 0.38114735 0.1694506 -0.050384745, 0.3617495 0.16944326 0.077010319, 0.23734355 0.16944911 -0.041593179, 0.36097196 0.1694432 0.077985331, 0.23689978 0.16944903 -0.040324882, 0.3616505 0.1694432 0.077444002, 0.36172447 0.16944323 0.077232763, 0.37174943 0.16945179 -0.072989866, 0.36614671 0.1694514 -0.068026289, 0.23805828 0.16944918 -0.042730793, 0.20632204 0.16944258 0.070686683, 0.23674941 0.16944891 -0.038989767, 0.23900843 0.1694493 -0.043680772, 0.20589453 0.16944256 0.071813688, 0.34421039 0.16944887 -0.025756583, 0.34398448 0.16944894 -0.026084051, 0.19635135 0.16944371 0.049615219, 0.36174944 0.16944355 0.073010221, 0.34368679 0.16944891 -0.026347771, 0.19621025 0.16944377 0.049243405, 0.37117681 0.16944361 0.070686683, 0.2401461 0.16944924 -0.04439567, 0.19598439 0.1694437 0.048916146, 0.37049189 0.16944379 0.069694623, 0.34333462 0.16944896 -0.026532754, 0.37274948 0.16945207 -0.077989742, 0.24141425 0.1694493 -0.044839486, 0.38435146 0.16944499 0.049615219, 0.37174949 0.16945195 -0.076989844, 0.27674937 0.16944446 0.045010194, 0.36958984 0.16944376 0.068895444, 0.30435148 0.16944438 0.049615219, 0.34114736 0.16944465 0.049615219, 0.34128851 0.16944462 0.049243405, 0.24274942 0.16944937 -0.04498969, 0.28274941 0.16944923 -0.038989767, 0.34294835 0.169449 -0.026627794, 0.30128843 0.16944715 -0.00075666606, 0.30421036 0.16944435 0.049243405, 0.30114731 0.1694472 -0.00038464367, 0.30181205 0.16944863 -0.026347771, 0.37177452 0.16945195 -0.077212438, 0.3011474 0.16944852 -0.02538465, 0.30128843 0.16944852 -0.025756583, 0.30151442 0.1694486 -0.026084051, 0.37252691 0.16945209 -0.077964857, 0.37231559 0.16945206 -0.077890947, 0.36497635 0.16945149 -0.068314895, 0.36852261 0.1694437 0.068335161, 0.37196761 0.16945207 -0.077613339, 0.37212601 0.16945209 -0.077771857, 0.37184846 0.16945204 -0.077423885, 0.19314724 0.16944364 0.049615219, 0.36735225 0.16944371 0.068046674, 0.21631542 0.16944236 0.077911392, 0.21652673 0.16944236 0.077985212, 0.34255052 0.16944896 -0.026627794, 0.34435141 0.16945031 -0.050384745, 0.36614677 0.16944379 0.068046674, 0.21612576 0.16944236 0.077791974, 0.28259894 0.16944931 -0.04032509, 0.34216434 0.16944897 -0.026532635, 0.28215519 0.16944948 -0.041593179, 0.28144035 0.16944948 -0.042730793, 0.21596746 0.16944236 0.077633664, 0.19598441 0.16944657 -0.0010839254, 0.36390916 0.16945161 -0.06887494, 0.34421045 0.1694503 -0.050756589, 0.3011474 0.16944996 -0.050384745, 0.28049034 0.16944954 -0.043680772, 0.30128843 0.16944996 -0.050756589, 0.2158483 0.16944231 0.077444002, 0.19568665 0.1694466 -0.0013476163, 0.27935275 0.16944948 -0.04439567, 0.38421035 0.16944483 0.049243405, 0.38398448 0.16944493 0.048916176, 0.34181213 0.16944888 -0.026347622, 0.30151436 0.16945012 -0.051084056, 0.27808446 0.1694496 -0.044839248, 0.38368666 0.16944508 0.048652455, 0.30181211 0.1694501 -0.051347658, 0.34398451 0.16945039 -0.051084056, 0.36300686 0.16945156 -0.069674268, 0.34398454 0.16944614 0.023915783, 0.34368679 0.16944605 0.023652241, 0.18947092 0.16944695 -0.0075149387, 0.2767494 0.16944952 -0.044989809, 0.21574935 0.1694423 0.077010319, 0.38333467 0.16944502 0.048467472, 0.34421048 0.16944599 0.02424325, 0.21577437 0.16944236 0.077232733, 0.30216435 0.16944997 -0.051532611, 0.34151435 0.16944891 -0.026083931, 0.34368679 0.16945028 -0.051347658, 0.38294846 0.16944502 0.048372492, 0.34128839 0.16944894 -0.025756583, 0.3433345 0.16944608 0.023467466, 0.18905585 0.16944695 -0.0078825802, 0.36232212 0.16945158 -0.070666328, 0.34333453 0.16945028 -0.05153276, 0.34294829 0.1694462 0.023372158, 0.18856496 0.16944687 -0.0081403106, 0.38255057 0.16944502 0.048372224, 0.38114747 0.16944769 -0.00038464367, 0.19635138 0.16944794 -0.025384799, 0.38216436 0.16944502 0.048467472, 0.23674928 0.16944462 0.039010212, 0.34255046 0.16944629 0.023372069, 0.18802655 0.16944689 -0.0082731098, 0.3443515 0.16944742 -0.00038485229, 0.38181213 0.16944502 0.048652455, 0.19621025 0.16944794 -0.025756463, 0.34216434 0.16944608 0.023467466, 0.38151452 0.1694449 0.048916176, 0.34421054 0.16944744 -0.00075666606, 0.19598439 0.16944794 -0.026083931, 0.3618947 0.16945161 -0.071793184, 0.38128844 0.1694449 0.049243405, 0.34294835 0.1694503 -0.0516278, 0.34181213 0.16944608 0.023652241, 0.21574934 0.16944259 0.073010221, 0.18747216 0.16944689 -0.0082731098, 0.36174938 0.16945171 -0.072989866, 0.18693374 0.16944695 -0.0081401616, 0.34255069 0.16945025 -0.0516278, 0.34151441 0.16944608 0.02391611, 0.24274927 0.16944434 0.045010194, 0.18644276 0.16944695 -0.0078825802, 0.34128848 0.16944604 0.024243489, 0.18602771 0.16944693 -0.0075150579, 0.19314726 0.16944793 -0.02538465, 0.18571281 0.1694468 -0.0070586056, 0.38435149 0.16944635 0.024615362, 0.36172447 0.16945188 -0.077212289, 0.36153129 0.16945198 -0.07761319, 0.3617495 0.16945188 -0.076989844, 0.3616505 0.16945191 -0.077423885, 0.38421044 0.16944633 0.02424325, 0.3613731 0.16945192 -0.077771857, 0.19568659 0.169448 -0.026347771, 0.38398457 0.16944629 0.02391611, 0.38368675 0.16944636 0.023652241, 0.38333467 0.16944633 0.023467466, 0.38398457 0.16944924 -0.026084051, 0.38368666 0.16944921 -0.026347622, 0.19533443 0.169448 -0.026532635, 0.38421047 0.16944912 -0.025756463, 0.20553122 0.16944218 0.077633724, 0.20518327 0.16944216 0.077911273, 0.20537281 0.16944224 0.077792183, 0.38294831 0.16944645 0.023372307, 0.36118338 0.16945186 -0.077890947, 0.36097196 0.16945197 -0.077964857, 0.38333452 0.16944927 -0.026532635, 0.19568658 0.16944389 0.048652455, 0.38255063 0.16944638 0.023372158, 0.19494818 0.16944808 -0.026627794, 0.20497191 0.16944224 0.077985212, 0.2056503 0.16944224 0.077444062, 0.20572434 0.16944218 0.077232763, 0.38294837 0.16944924 -0.026627794, 0.38216436 0.16944624 0.023467466, 0.20574947 0.1694421 0.077010319, 0.19455044 0.16944805 -0.026627883, 0.19533443 0.16944382 0.048467472, 0.20474932 0.16944224 0.078010336, 0.19635132 0.16944939 -0.050384745, 0.3421644 0.16945031 -0.051532432, 0.34181213 0.16945031 -0.051347658, 0.38255057 0.16944933 -0.026627794, 0.36390907 0.16944368 0.068895444, 0.36300683 0.16944376 0.069694534, 0.19416419 0.16944806 -0.026532635, 0.36232218 0.16944359 0.070686683, 0.19494818 0.16944383 0.048372224, 0.38216439 0.16944924 -0.026532635, 0.3649765 0.16944373 0.06833525, 0.193812 0.16944793 -0.026347622, 0.36189476 0.16944356 0.071813688, 0.38181219 0.16944918 -0.026347771, 0.19455054 0.16944382 0.048372224, 0.21449187 0.16945058 -0.069674268, 0.30421048 0.16944718 -0.00075666606, 0.3039844 0.16944736 -0.001084134, 0.38151452 0.16944908 -0.026084051, 0.19635138 0.1694451 0.024615422, 0.21358962 0.16945055 -0.068874881, 0.19416428 0.16944382 0.048467472, 0.38128868 0.16944909 -0.025756463, 0.3036868 0.16944724 -0.0013476163, 0.19351426 0.16944793 -0.026084051, 0.19621037 0.1694451 0.024243489, 0.21517663 0.16945066 -0.070666179, 0.19381207 0.16944376 0.048652515, 0.30333453 0.16944724 -0.0015324801, 0.19598426 0.16944522 0.02391611, 0.34435147 0.16944458 0.049615219, 0.21252231 0.16945043 -0.068314895, 0.19351433 0.16944364 0.048916176, 0.38114741 0.16944493 0.049615219, 0.19328836 0.16944793 -0.025756463, 0.21560399 0.1694507 -0.071793184, 0.30294842 0.16944724 -0.0016278476, 0.19328834 0.16944364 0.049243405, 0.34114724 0.16944885 -0.02538465, 0.34421048 0.16944464 0.049243405, 0.21135202 0.16945042 -0.068026319, 0.3039844 0.16944444 0.048916176, 0.30255064 0.16944717 -0.0016278476, 0.30435154 0.16944863 -0.02538465, 0.30368674 0.16944455 0.048652455, 0.20574933 0.16944245 0.073010221, 0.21574938 0.16945082 -0.072989866, 0.30333453 0.1694445 0.048467472, 0.30216432 0.16944723 -0.0015324801, 0.40274945 0.16945188 -0.072989866, 0.30421045 0.16944855 -0.025756463, 0.38368666 0.16945064 -0.051347658, 0.38333461 0.16945063 -0.051532611, 0.38398454 0.16945061 -0.051083937, 0.38421056 0.16945051 -0.050756589, 0.38435158 0.16945051 -0.050384745, 0.39198264 0.16944811 -0.0065401644, 0.30181211 0.1694473 -0.0013478249, 0.21014667 0.1694504 -0.068026319, 0.19621034 0.16944937 -0.050756589, 0.20897636 0.1694504 -0.068314895, 0.30294836 0.16944452 0.048372224, 0.19598438 0.16944937 -0.051084056, 0.34114745 0.16944604 0.024615422, 0.20790899 0.16945054 -0.06887494, 0.30151448 0.1694473 -0.0010839254, 0.19568661 0.16944937 -0.051347658, 0.1953344 0.16944945 -0.051532611, 0.30255061 0.16945006 -0.051627681, 0.30255064 0.16944443 0.048372224, 0.21574932 0.16945094 -0.076989844, 0.30435148 0.16944577 0.024615362, 0.21652687 0.16945098 -0.077964708, 0.21631543 0.16945109 -0.077890947, 0.21584831 0.16945106 -0.077423885, 0.21577452 0.16945095 -0.077212289, 0.30216438 0.16944444 0.048467472, 0.24141431 0.16944417 0.044859782, 0.21596751 0.16945101 -0.07761319, 0.2161258 0.16945104 -0.077771857, 0.39178601 0.16944751 0.0049412102, 0.39147106 0.16944747 0.0044849664, 0.20700681 0.16945046 -0.069674268, 0.19494814 0.16944943 -0.051627681, 0.30421045 0.16944581 0.02424325, 0.21560413 0.16944253 0.071813688, 0.39105603 0.16944751 0.0041172355, 0.20632198 0.16945057 -0.070666328, 0.19455045 0.16944943 -0.051627681, 0.30181211 0.16944446 0.048652455, 0.39198264 0.16944739 0.0054597408, 0.24014616 0.16944432 0.044415966, 0.20589465 0.16945064 -0.071793184, 0.3905651 0.16944751 0.0038596243, 0.21517664 0.16944256 0.070686683, 0.39002672 0.16944751 0.0037268549, 0.4026241 0.16945197 -0.074102357, 0.40225431 0.16945209 -0.075159147, 0.23900844 0.16944432 0.043701276, 0.38947234 0.16944739 0.0037268549, 0.20572434 0.16945082 -0.077212289, 0.20565031 0.16945097 -0.077423885, 0.20574936 0.16945088 -0.076989844, 0.388028 0.16944747 0.0044849664, 0.38771293 0.1694475 0.0049412102, 0.20553121 0.16945092 -0.077613339, 0.21449189 0.16944274 0.069694623, 0.38844296 0.16944741 0.0041172355, 0.20537278 0.16945104 -0.077771708, 0.20518324 0.16945092 -0.077890947, 0.2380583 0.16944438 0.042751089, 0.38751629 0.16944747 0.0054597408, 0.20497182 0.16945098 -0.077964857, 0.40165868 0.16945212 -0.076107368, 0.38893393 0.1694475 0.0038596243, 0.20574936 0.16945063 -0.072989866, 0.19416426 0.16944936 -0.051532611, 0.17474928 0.16945049 -0.072989866, 0.18551624 0.1694468 -0.0065401644, 0.19314724 0.16944936 -0.050384745, 0.19328828 0.16944936 -0.050756589, 0.19351427 0.16944936 -0.051084056, 0.21358967 0.16944274 0.068895444, 0.19381204 0.16944936 -0.051347658, 0.19568658 0.16944513 0.023652241, 0.28049034 0.16944465 0.043701276, 0.19533437 0.1694451 0.023467526, 0.19494826 0.16944528 0.023372158, 0.3011474 0.16944426 0.049615219, 0.28144032 0.16944472 0.042751089, 0.17757982 0.16945079 -0.077494696, 0.1786367 0.16945082 -0.077864483, 0.17524448 0.16945061 -0.075159147, 0.17487466 0.16945049 -0.074102357, 0.23734358 0.16944444 0.041613623, 0.38435149 0.16944778 -0.00038464367, 0.27935269 0.16944459 0.044415966, 0.17584015 0.16945061 -0.076107368, 0.1766319 0.16945069 -0.076899037, 0.19455042 0.16944528 0.023372158, 0.21252245 0.16944274 0.06833525, 0.30128843 0.16944431 0.049243405, 0.28215516 0.16944474 0.041613623, 0.27808449 0.16944446 0.04485999, 0.21135202 0.16944286 0.068046883, 0.38421044 0.16944776 -0.00075645745, 0.282599 0.16944489 0.040345445, 0.23689982 0.16944456 0.040345535, 0.30151436 0.16944435 0.048916176, 0.38181219 0.1694463 0.023652241, 0.19416428 0.1694451 0.023467466, 0.3011474 0.16944574 0.024615362, 0.38398448 0.16944779 -0.001084134, 0.38151452 0.16944633 0.02391611, 0.4008669 0.16945215 -0.076899037, 0.39886221 0.16945221 -0.077864483, 0.399919 0.16945221 -0.077494696, 0.38368669 0.16944785 -0.0013476163, 0.19381206 0.16944507 0.023652241, 0.19351432 0.16944513 0.02391611, 0.3812885 0.16944629 0.02424325, 0.38333461 0.16944782 -0.0015324801, 0.19635139 0.16944647 -0.00038464367, 0.34398454 0.16944757 -0.001084134, 0.3436867 0.16944753 -0.0013478249, 0.19328839 0.16944501 0.02424325, 0.38294849 0.16944776 -0.0016278476, 0.17757991 0.16944206 0.077515021, 0.17863673 0.16944198 0.077884927, 0.34333456 0.16944757 -0.0015324801, 0.19621037 0.16944647 -0.00075666606, 0.30398437 0.16944867 -0.026084051, 0.38751641 0.16944811 -0.0065401644, 0.38255063 0.16944781 -0.0016278476, 0.1899825 0.16944613 0.0054597408, 0.30368674 0.16944864 -0.026347622, 0.34294829 0.16944763 -0.0016278476, 0.19314723 0.16944507 0.024615362, 0.38114735 0.16944917 -0.02538465, 0.30333441 0.16944876 -0.026532635, 0.18978591 0.16944623 0.0049414188, 0.34255055 0.16944756 -0.0016278476, 0.3029483 0.16944867 -0.026627794, 0.34435153 0.16944887 -0.02538465, 0.34114733 0.16945028 -0.050384745, 0.3421644 0.1694476 -0.0015324801, 0.30255055 0.16944867 -0.026627794, 0.30435148 0.16945009 -0.050384745, 0.18947095 0.16944617 0.0044849664, 0.34398448 0.16944456 0.048916176, 0.30216432 0.16944867 -0.026532635, 0.34181219 0.16944751 -0.0013478249, 0.34368676 0.16944477 0.048652455, 0.17663179 0.1694421 0.076919362, 0.30421045 0.16944999 -0.050756589, 0.34128833 0.16945028 -0.050756589, 0.34151441 0.16945031 -0.051083937, 0.34151441 0.1694476 -0.0010839254, 0.18905585 0.16944623 0.0041173846, 0.3433345 0.16944481 0.048467472, 0.30398443 0.16945007 -0.051083937, 0.34128839 0.16944751 -0.00075645745, 0.30368683 0.1694501 -0.051347658, 0.34294826 0.16944477 0.048372224, 0.38114741 0.16944633 0.024615362, 0.34255052 0.16944478 0.048372224, 0.34435147 0.16944607 0.024615362, 0.18856493 0.16944623 0.0038596243, 0.17584011 0.1694421 0.076127931, 0.34216434 0.16944474 0.048467472, 0.18802653 0.16944623 0.0037268549, 0.30333444 0.16945006 -0.051532611, 0.34181219 0.16944477 0.048652455, 0.30398446 0.16944584 0.02391611, 0.34151441 0.16944465 0.048916176, 0.30368668 0.16944587 0.023652241, 0.19351436 0.16944656 -0.0010839254, 0.19328828 0.1694465 -0.00075666606, 0.30294833 0.16945007 -0.051627681, 0.19314724 0.1694465 -0.00038485229, 0.30333447 0.16944581 0.023467466, 0.19381207 0.16944656 -0.0013478249, 0.19416425 0.16944662 -0.0015324801, 0.3029483 0.16944593 0.023372158, 0.19455045 0.16944657 -0.0016278476, 0.34114736 0.16944751 -0.00038464367, 0.30255061 0.16944589 0.023372158, 0.30435151 0.16944718 -0.00038485229, 0.19494829 0.16944656 -0.0016278476, -0.19640084 0.16944686 -0.049989834, -0.19635287 0.16944681 -0.049595013, -0.19640082 0.16644686 -0.049989924, -0.19635284 0.16644683 -0.049595013, -0.19621183 0.16944678 -0.04922305, -0.1962117 0.16644666 -0.049223199, -0.19598588 0.16944683 -0.048895702, -0.19598579 0.16644666 -0.04889597, -0.19568816 0.16944669 -0.048631921, -0.19568804 0.1664467 -0.048632041, -0.19533589 0.16944669 -0.048446998, -0.19533581 0.16644669 -0.048447266, -0.19494978 0.16944677 -0.048351899, -0.19494969 0.16644683 -0.048352018, -0.19455191 0.16944675 -0.048351899, -0.19455189 0.16644673 -0.048352107, -0.19416563 0.16944674 -0.048446998, -0.19416565 0.16644675 -0.048447266, -0.19381347 0.16944671 -0.048631772, -0.19381338 0.16644669 -0.048632041, -0.19351564 0.16944674 -0.048895702, -0.19351566 0.16644669 -0.048895821, -0.19328983 0.16944677 -0.04922305, -0.19328982 0.16644681 -0.049223199, -0.19314876 0.16944677 -0.049595013, -0.19314879 0.16644683 -0.049595192, -0.19310082 0.16944686 -0.049989775, -0.19310081 0.16644686 -0.049989924, -0.19640091 0.1694455 -0.024989828, -0.19635281 0.16944538 -0.024595007, -0.19640076 0.16644542 -0.024989977, -0.19635284 0.16644546 -0.024595097, -0.19621184 0.16944531 -0.024222925, -0.19621183 0.16644536 -0.024223074, -0.19598587 0.16944538 -0.023895696, -0.19598584 0.16644539 -0.023895696, -0.19568805 0.16944528 -0.023631766, -0.19568819 0.16644539 -0.023632035, -0.19533579 0.16944528 -0.023446992, -0.19533587 0.16644536 -0.023447111, -0.19494972 0.16944532 -0.023352012, -0.19494969 0.1664453 -0.023352012, -0.19455191 0.16944532 -0.023351863, -0.19455194 0.16644537 -0.023352012, -0.19416568 0.16944534 -0.023446992, -0.19416571 0.16644537 -0.02344726, -0.19381337 0.16944531 -0.023631886, -0.19381338 0.16644526 -0.023632124, -0.19351564 0.16944531 -0.023895606, -0.19351578 0.1664454 -0.023895845, -0.19328979 0.16944532 -0.024222836, -0.19328976 0.1664453 -0.024223164, -0.19314873 0.1694454 -0.024595007, -0.19314867 0.1664454 -0.024595246, -0.19310072 0.1694454 -0.024989828, -0.19310085 0.16644549 -0.024990067, -0.19640079 0.16944258 0.025010124, -0.19635287 0.16944258 0.025405154, -0.19640075 0.16644262 0.025010005, -0.19635278 0.16644256 0.025405064, -0.19621176 0.16944255 0.025777027, -0.19621181 0.16644262 0.025777027, -0.19598587 0.16944258 0.026104465, -0.19598575 0.16644248 0.026104257, -0.19568808 0.16944247 0.026368037, -0.19568813 0.16644253 0.026368037, -0.19533582 0.16944247 0.026552901, -0.19533587 0.16644253 0.026552901, -0.19494966 0.16944252 0.026648059, -0.19494969 0.1664426 0.026648059, -0.19455191 0.16944252 0.026648059, -0.19455186 0.16644254 0.026648059, -0.19416568 0.16944253 0.026552901, -0.19416565 0.16644263 0.026552662, -0.1938134 0.16944253 0.026368037, -0.19381344 0.16644257 0.026367798, -0.19351575 0.16944259 0.026104346, -0.19351572 0.16644257 0.026104197, -0.19328979 0.16944252 0.025777027, -0.19328982 0.16644257 0.025776967, -0.1931487 0.16944253 0.025405064, -0.19314879 0.16644263 0.025404826, -0.19310084 0.16944259 0.025010124, -0.19310081 0.16644257 0.025010005, -0.19640079 0.16944115 0.050010368, -0.19635281 0.16944115 0.05040504, -0.19640064 0.16644111 0.05001007, -0.19635281 0.16644108 0.050404981, -0.19621184 0.16944113 0.050777003, -0.19621176 0.16644113 0.050776854, -0.19598587 0.16944115 0.05110462, -0.19598579 0.16644111 0.051104233, -0.19568816 0.16944115 0.051368162, -0.19568813 0.16644111 0.051368043, -0.19533589 0.16944115 0.051552966, -0.19533585 0.16644107 0.051552817, -0.19494967 0.16944113 0.051648185, -0.19494969 0.16644111 0.051648065, -0.1945519 0.1694411 0.051648185, -0.19455194 0.16644116 0.051647976, -0.19416574 0.16944116 0.051553026, -0.19416565 0.1664412 0.051552698, -0.19381338 0.16944104 0.051368192, -0.19381347 0.16644117 0.051368043, -0.19351566 0.1694411 0.05110462, -0.19351584 0.16644123 0.051104233, -0.19328983 0.16944116 0.050777003, -0.19328982 0.1664412 0.050776795, -0.1931487 0.1694411 0.05040504, -0.19314867 0.16644108 0.050404981, -0.19310078 0.16944116 0.050010249, -0.19310085 0.1664412 0.050010249, -0.19640085 0.16944401 1.0296702e-05, -0.19635284 0.16944399 0.00040508807, -0.19640084 0.16644399 1.0177493e-05, -0.19635281 0.16644394 0.00040484965, -0.19621187 0.16944401 0.00077690184, -0.19621181 0.16644405 0.00077690184, -0.19598587 0.16944395 0.0011043996, -0.19598585 0.16644399 0.0011043996, -0.1956881 0.16944388 0.0013681799, -0.19568801 0.16644387 0.0013679117, -0.19533584 0.16944388 0.0015529543, -0.19533578 0.16644384 0.0015528351, -0.19494972 0.16944389 0.0016482025, -0.19494969 0.16644393 0.0016480833, -0.19455197 0.16944402 0.0016482025, -0.19455183 0.16644388 0.0016479343, -0.19416565 0.16944388 0.0015529543, -0.19416565 0.16644388 0.0015528351, -0.19381338 0.16944388 0.0013680607, -0.19381335 0.16644385 0.0013678223, -0.19351569 0.16944396 0.0011043996, -0.19351578 0.166444 0.0011041313, -0.19328979 0.16944396 0.00077690184, -0.19328982 0.166444 0.00077690184, -0.1931487 0.16944388 0.00040508807, -0.1931487 0.166444 0.00040484965, -0.19310078 0.16944402 1.0177493e-05, -0.19310081 0.166444 9.9390745e-06, -0.30440089 0.16944614 -0.049989775, -0.30435291 0.16944608 -0.049595013, -0.30440098 0.16644619 -0.049989924, -0.30435288 0.16644609 -0.049595103, -0.30421177 0.16944602 -0.049222931, -0.30421188 0.16644599 -0.049223199, -0.30398589 0.16944604 -0.048895553, -0.30398595 0.166446 -0.048895702, -0.30368817 0.16944604 -0.048631772, -0.30368817 0.16644606 -0.048632041, -0.30333588 0.16944602 -0.048446998, -0.30333591 0.16644606 -0.048447266, -0.30294982 0.16944617 -0.04835175, -0.30294973 0.16644609 -0.048352018, -0.3025519 0.16944599 -0.048352018, -0.30255198 0.1664461 -0.048352107, -0.30216572 0.16944602 -0.048446998, -0.30216575 0.1664461 -0.048447266, -0.30181351 0.16944607 -0.048631921, -0.30181357 0.16644613 -0.048632041, -0.30151573 0.1694461 -0.048895553, -0.30151582 0.16644613 -0.04889597, -0.30128977 0.16944599 -0.049222931, -0.30128992 0.16644615 -0.049223199, -0.30114886 0.16944617 -0.049595103, -0.30114883 0.1664461 -0.049595013, -0.30110082 0.16944613 -0.049989834, -0.30110097 0.16644621 -0.049989924, -0.30440083 0.16944468 -0.024989679, -0.30435285 0.16944471 -0.024595007, -0.30440089 0.16644476 -0.024990067, -0.30435294 0.16644481 -0.024595097, -0.30421177 0.16944459 -0.024222836, -0.3042118 0.16644469 -0.024223074, -0.30398583 0.16944459 -0.023895606, -0.30398601 0.16644475 -0.023895696, -0.30368811 0.16944461 -0.023631766, -0.30368817 0.16644469 -0.023632035, -0.30333593 0.16944461 -0.023446992, -0.30333596 0.16644469 -0.023447111, -0.30294976 0.16944459 -0.023351863, -0.30294973 0.16644469 -0.023352012, -0.30255198 0.16944464 -0.023351744, -0.30255198 0.16644467 -0.023352012, -0.30216572 0.16944465 -0.023446992, -0.30216569 0.16644463 -0.023447111, -0.30181345 0.16944458 -0.023632035, -0.30181354 0.16644463 -0.023632035, -0.30151573 0.16944465 -0.023895606, -0.30151588 0.16644466 -0.023895815, -0.30128986 0.1694447 -0.024222925, -0.30128986 0.16644467 -0.024223074, -0.30114886 0.1694448 -0.024595007, -0.30114871 0.16644473 -0.024595246, -0.30110094 0.1694448 -0.024989828, -0.30110085 0.16644476 -0.024989977, -0.30440077 0.16944185 0.025010124, -0.30435291 0.16944188 0.025405064, -0.30440095 0.16644201 0.025010005, -0.30435297 0.16644195 0.025405064, -0.30421183 0.16944185 0.025777027, -0.30421185 0.16644192 0.025776967, -0.30398592 0.16944185 0.026104346, -0.30398595 0.16644192 0.026104257, -0.3036882 0.16944185 0.026368037, -0.30368808 0.16644184 0.026367798, -0.30333593 0.16944185 0.026552901, -0.30333591 0.1664419 0.026552662, -0.30294976 0.16944188 0.026648149, -0.30294985 0.16644193 0.026648059, -0.30255198 0.16944183 0.026648149, -0.30255198 0.16644193 0.026648059, -0.30216566 0.16944185 0.026552901, -0.30216575 0.16644193 0.026552901, -0.30181345 0.1694417 0.026368037, -0.3018136 0.16644189 0.026368037, -0.30151591 0.16944195 0.026104465, -0.3015157 0.16644187 0.026104257, -0.30128989 0.16944192 0.025777027, -0.30128986 0.16644183 0.025776967, -0.30114883 0.16944195 0.025405064, -0.30114883 0.16644193 0.025405064, -0.30110094 0.16944195 0.025010124, -0.30110085 0.16644193 0.025010005, -0.30440083 0.16944048 0.050010368, -0.30435291 0.16944045 0.05040504, -0.3044008 0.16644049 0.050010249, -0.304353 0.16644058 0.050404981, -0.30421177 0.16944039 0.050777003, -0.30421185 0.16644049 0.050776854, -0.30398583 0.16944034 0.051104471, -0.30398595 0.16644058 0.051104233, -0.30368811 0.16944034 0.051368192, -0.30368817 0.16644047 0.051368043, -0.30333599 0.16944045 0.051552966, -0.30333591 0.16644037 0.051552698, -0.30294982 0.16944046 0.051648214, -0.30294979 0.16644046 0.051647976, -0.30255201 0.1694404 0.051648185, -0.30255195 0.16644041 0.051647976, -0.30216578 0.16944043 0.051553026, -0.30216575 0.16644041 0.051552698, -0.30181357 0.16944049 0.051368162, -0.30181354 0.16644041 0.051367953, -0.30151585 0.16944049 0.051104471, -0.30151582 0.16644046 0.051104233, -0.30128989 0.16944049 0.050777033, -0.30128986 0.1664405 0.050776854, -0.30114886 0.16944055 0.05040504, -0.30114877 0.16644047 0.050404981, -0.30110085 0.16944052 0.050010368, -0.30110085 0.1664405 0.050010249, -0.30440083 0.16944328 1.0296702e-05, -0.30435285 0.16944323 0.00040508807, -0.30440098 0.16644332 9.9390745e-06, -0.30435297 0.16644332 0.00040484965, -0.30421183 0.16944328 0.00077717006, -0.30421194 0.16644338 0.00077690184, -0.30398598 0.16944331 0.0011043996, -0.30398589 0.16644327 0.0011043996, -0.3036882 0.16944319 0.0013680607, -0.30368811 0.1664432 0.0013678223, -0.30333585 0.16944316 0.0015529543, -0.30333591 0.16644323 0.0015528351, -0.30294976 0.16944322 0.0016482025, -0.30294985 0.16644326 0.0016479343, -0.30255198 0.16944326 0.0016482025, -0.30255198 0.16644324 0.0016480833, -0.30216572 0.16944315 0.0015530735, -0.30216578 0.16644326 0.0015527457, -0.30181351 0.16944322 0.0013682991, -0.30181354 0.16644326 0.0013679117, -0.30151573 0.16944322 0.001104489, -0.30151576 0.16644333 0.0011043996, -0.30128989 0.16944329 0.00077717006, -0.30128986 0.16644336 0.00077690184, -0.30114877 0.16944332 0.00040499866, -0.30114871 0.16644321 0.00040484965, -0.30110088 0.16944335 1.0296702e-05, -0.30110085 0.16644333 9.9390745e-06, -0.34440073 0.16944577 -0.049989775, -0.34435287 0.16944571 -0.049595013, -0.34440088 0.16644593 -0.049989834, -0.3443529 0.16644579 -0.049595103, -0.34421191 0.1694458 -0.049222931, -0.34421188 0.16644594 -0.049223199, -0.34398583 0.16944577 -0.048895702, -0.34398592 0.16644584 -0.048895821, -0.3436881 0.16944577 -0.048631772, -0.34368828 0.16644582 -0.048632041, -0.3433359 0.16944565 -0.048446998, -0.34333602 0.16644582 -0.048447266, -0.34294972 0.16944578 -0.04835175, -0.34294978 0.16644581 -0.048352018, -0.34255198 0.16944581 -0.04835175, -0.34255201 0.16644588 -0.048352018, -0.34216574 0.1694458 -0.048447117, -0.34216583 0.16644588 -0.048447266, -0.34181359 0.16944578 -0.048631921, -0.3418135 0.16644585 -0.04863213, -0.34151581 0.16944583 -0.048895702, -0.34151578 0.16644585 -0.048895821, -0.34128991 0.16944578 -0.04922305, -0.34128991 0.16644582 -0.049223199, -0.34114888 0.16944592 -0.049595013, -0.34114882 0.16644582 -0.049595103, -0.3411009 0.16944596 -0.049989775, -0.3411009 0.16644596 -0.049989924, -0.34440085 0.16944452 -0.024989828, -0.34435299 0.16944446 -0.024595007, -0.34440082 0.1664445 -0.024989977, -0.3443529 0.1664445 -0.024595246, -0.34421185 0.16944434 -0.024222925, -0.34421188 0.16644442 -0.024223074, -0.34398589 0.16944435 -0.023895606, -0.34398592 0.16644439 -0.023895815, -0.34368822 0.16944431 -0.023631886, -0.34368819 0.16644439 -0.023632035, -0.34333596 0.16944432 -0.023446992, -0.34333596 0.1664443 -0.02344726, -0.34294972 0.16944435 -0.023351863, -0.34294975 0.16644433 -0.023352101, -0.34255204 0.1694444 -0.023352012, -0.34255198 0.16644445 -0.023352012, -0.3421658 0.1694444 -0.023446992, -0.34216571 0.16644426 -0.023447111, -0.34181365 0.16944447 -0.023632035, -0.34181356 0.16644445 -0.023631886, -0.34151581 0.16944446 -0.023895606, -0.34151584 0.16644445 -0.023895815, -0.34128991 0.16944435 -0.024222925, -0.34128991 0.16644445 -0.024223164, -0.34114894 0.16944453 -0.024594858, -0.34114882 0.16644445 -0.024595097, -0.34110084 0.16944447 -0.024989828, -0.3411009 0.16644453 -0.024989828, -0.34440091 0.16944166 0.025010124, -0.34435293 0.16944163 0.025405064, -0.34440082 0.16644162 0.025009945, -0.3443529 0.16644162 0.025404826, -0.34421191 0.16944171 0.025777027, -0.34421188 0.16644162 0.025776967, -0.34398594 0.16944163 0.026104346, -0.34398592 0.16644159 0.026104257, -0.34368822 0.16944163 0.026368037, -0.34368828 0.16644171 0.026368037, -0.34333596 0.16944155 0.026552901, -0.34333599 0.16644162 0.026552901, -0.34294984 0.1694416 0.026648149, -0.34294978 0.16644163 0.026648059, -0.3425521 0.16944166 0.026648059, -0.34255189 0.16644162 0.026648059, -0.34216574 0.1694416 0.026552901, -0.34216577 0.16644166 0.026552901, -0.34181365 0.16944158 0.026368037, -0.3418135 0.1664416 0.026368037, -0.34151581 0.1694416 0.026104465, -0.3415159 0.16644165 0.026104257, -0.34128985 0.16944161 0.025777027, -0.34128991 0.16644165 0.025776967, -0.34114894 0.16944169 0.025405064, -0.34114873 0.16644162 0.025405064, -0.3411009 0.16944164 0.025010243, -0.34110081 0.16644165 0.025010005, -0.34440091 0.16944021 0.050010249, -0.34435293 0.16944028 0.05040504, -0.34440082 0.16644019 0.05001007, -0.3443529 0.16644025 0.050404981, -0.34421191 0.16944017 0.050777003, -0.34421188 0.16644017 0.050776854, -0.343986 0.1694403 0.051104471, -0.34398586 0.16644016 0.051104084, -0.34368828 0.16944021 0.051368192, -0.34368816 0.16644011 0.051368043, -0.34333596 0.16944021 0.051552966, -0.34333605 0.16644023 0.051552817, -0.34294972 0.16944006 0.051648185, -0.34294978 0.16644028 0.051648065, -0.34255198 0.16944018 0.051648185, -0.3425521 0.1664402 0.051648065, -0.3421658 0.16944019 0.051552966, -0.34216577 0.16644023 0.051552817, -0.34181359 0.16944021 0.051368162, -0.34181353 0.16644019 0.051367953, -0.34151593 0.16944027 0.051104471, -0.34151575 0.16644014 0.051104084, -0.34128997 0.16944021 0.050777003, -0.34128997 0.1664402 0.050776854, -0.34114894 0.16944031 0.05040504, -0.34114888 0.1664402 0.050404981, -0.34110084 0.16944018 0.050010368, -0.3411009 0.16644028 0.050010249, -0.34440091 0.16944309 1.0296702e-05, -0.34435293 0.16944315 0.00040499866, -0.34440082 0.16644305 9.9390745e-06, -0.3443529 0.16644309 0.00040499866, -0.34421191 0.16944294 0.00077717006, -0.34421188 0.16644305 0.00077690184, -0.34398583 0.16944298 0.0011043996, -0.343986 0.16644308 0.0011043996, -0.34368828 0.16944295 0.0013681799, -0.34368825 0.16644296 0.0013679117, -0.34333602 0.16944297 0.0015530735, -0.34333599 0.16644296 0.0015528351, -0.34294972 0.16944292 0.0016482025, -0.34294981 0.16644295 0.0016479343, -0.3425521 0.169443 0.0016480833, -0.34255195 0.16644296 0.0016480833, -0.3421658 0.16944303 0.0015530735, -0.34216577 0.16644304 0.0015528351, -0.34181353 0.16944292 0.0013680607, -0.34181353 0.16644299 0.0013679117, -0.34151581 0.16944303 0.0011043996, -0.3415159 0.16644302 0.0011043996, -0.34128997 0.16944312 0.00077717006, -0.34129 0.16644302 0.00077678263, -0.34114888 0.16944307 0.00040508807, -0.34114879 0.16644311 0.00040484965, -0.34110084 0.16944304 1.0296702e-05, -0.34110084 0.16644302 1.0177493e-05, -0.38440081 0.16944565 -0.049989775, -0.38435301 0.16944559 -0.049595013, -0.38440093 0.16644564 -0.049989924, -0.38435298 0.16644552 -0.049595103, -0.38421199 0.16944559 -0.04922305, -0.38421199 0.16644558 -0.049223199, -0.38398585 0.1694455 -0.048895702, -0.38398597 0.1664456 -0.048895702, -0.38368818 0.16944554 -0.048631772, -0.38368824 0.16644555 -0.048632041, -0.3833361 0.16944557 -0.048446998, -0.38333604 0.16644557 -0.048447266, -0.38294986 0.16944554 -0.048351899, -0.3829498 0.16644557 -0.048352018, -0.382552 0.16944553 -0.048352018, -0.382552 0.16644557 -0.048352018, -0.38216576 0.16944557 -0.048446998, -0.38216576 0.16644555 -0.048447266, -0.3818135 0.16944548 -0.048631921, -0.3818135 0.16644549 -0.048632041, -0.38151577 0.16944553 -0.048895702, -0.3815158 0.16644561 -0.048895702, -0.38128987 0.16944553 -0.04922305, -0.38128999 0.16644557 -0.049223199, -0.38114884 0.16944557 -0.049595013, -0.38114882 0.16644558 -0.049595103, -0.38110092 0.16944563 -0.049989834, -0.38110092 0.1664456 -0.049989924, -0.38440093 0.16944428 -0.024989828, -0.38435301 0.16944428 -0.024595007, -0.38440087 0.16644423 -0.024989977, -0.38435289 0.1664442 -0.024595246, -0.38421187 0.16944407 -0.024222925, -0.38421199 0.16644415 -0.024223164, -0.38398585 0.16944407 -0.023895606, -0.38398585 0.16644406 -0.023895696, -0.38368818 0.16944414 -0.023631886, -0.38368815 0.16644409 -0.023632035, -0.3833361 0.16944408 -0.023446992, -0.38333604 0.16644405 -0.02344726, -0.3829498 0.16944407 -0.023351863, -0.38294986 0.16644415 -0.023352012, -0.38255194 0.16944411 -0.023352012, -0.38255197 0.16644406 -0.023352012, -0.3821657 0.16944407 -0.023446992, -0.38216576 0.16644417 -0.023447111, -0.3818135 0.16944413 -0.023632035, -0.3818135 0.16644412 -0.023632035, -0.38151577 0.16944413 -0.023895606, -0.38151577 0.16644414 -0.023895696, -0.38128987 0.16944414 -0.024223074, -0.38128999 0.16644417 -0.024223164, -0.38114867 0.16944411 -0.024595007, -0.38114884 0.16644426 -0.024595097, -0.38110092 0.16944426 -0.024989828, -0.38110086 0.16644429 -0.024990067, -0.38440099 0.16944145 0.025010124, -0.38435289 0.16944139 0.025405064, -0.38440093 0.16644141 0.025009945, -0.38435298 0.16644144 0.025404826, -0.38421184 0.16944136 0.025777027, -0.38421184 0.16644135 0.025776967, -0.38398585 0.16944133 0.026104346, -0.38398585 0.16644135 0.026104197, -0.38368824 0.1694414 0.026368037, -0.38368818 0.1664414 0.026368037, -0.38333598 0.16944134 0.026552901, -0.3833361 0.16644138 0.026552901, -0.38294986 0.16944133 0.026648059, -0.38294992 0.16644132 0.026648059, -0.38255206 0.16944133 0.026648059, -0.38255206 0.16644132 0.026648059, -0.38216576 0.16944136 0.026552901, -0.38216576 0.16644131 0.026552662, -0.38181356 0.16944136 0.026368037, -0.3818135 0.16644131 0.026368037, -0.38151571 0.16944134 0.026104346, -0.38151577 0.16644143 0.026104257, -0.38128993 0.16944134 0.025777027, -0.38128999 0.16644143 0.025776967, -0.38114884 0.16944136 0.025405064, -0.38114884 0.1664414 0.025405064, -0.38110092 0.16944136 0.025010124, -0.38110086 0.16644141 0.025010005, -0.38440081 0.16943991 0.050010249, -0.38435301 0.16943999 0.05040504, -0.38440081 0.16644 0.050010249, -0.38435289 0.16643994 0.050404981, -0.38421187 0.16943993 0.050777003, -0.38421196 0.16643992 0.050776854, -0.38398591 0.16943994 0.051104471, -0.38398585 0.16643994 0.051104084, -0.38368824 0.16943991 0.051368162, -0.38368818 0.16643988 0.051368043, -0.38333604 0.1694399 0.051552966, -0.38333592 0.16643985 0.051552817, -0.38294974 0.16943991 0.051648185, -0.38294986 0.16643998 0.051648185, -0.382552 0.16944 0.051648185, -0.38255188 0.16643979 0.051648065, -0.3821657 0.1694399 0.051552966, -0.38216582 0.16643995 0.051552817, -0.3818135 0.16943993 0.051368162, -0.38181353 0.16643992 0.051368043, -0.38151583 0.16943996 0.051104471, -0.38151583 0.16644004 0.051104084, -0.38128981 0.16943994 0.050776854, -0.38128999 0.16644013 0.050776854, -0.38114879 0.16943985 0.05040504, -0.38114884 0.16644 0.050404981, -0.38110092 0.16943993 0.050010398, -0.38110086 0.16643997 0.05001007, -0.38440081 0.16944277 1.0296702e-05, -0.38435289 0.16944283 0.00040499866, -0.3844009 0.16644284 9.9390745e-06, -0.38435301 0.16644284 0.00040499866, -0.38421199 0.1694428 0.00077717006, -0.38421196 0.16644278 0.00077678263, -0.38398591 0.16944285 0.0011043996, -0.38398582 0.16644281 0.0011043996, -0.38368818 0.16944268 0.0013680607, -0.38368812 0.16644266 0.0013679117, -0.38333604 0.16944274 0.0015529543, -0.3833361 0.16644274 0.0015529543, -0.38294986 0.16944268 0.0016482025, -0.38294983 0.16644272 0.0016479343, -0.382552 0.16944268 0.0016480833, -0.382552 0.16644268 0.0016479343, -0.38216576 0.1694427 0.0015529543, -0.38216576 0.16644269 0.0015528351, -0.38181356 0.16944262 0.0013679117, -0.3818135 0.16644262 0.0013679117, -0.38151577 0.16944279 0.0011043996, -0.3815158 0.16644278 0.0011043996, -0.38128987 0.16944267 0.00077717006, -0.38128999 0.16644283 0.00077678263, -0.38114879 0.16944273 0.00040508807, -0.38114882 0.16644284 0.00040484965, -0.38110095 0.16944277 1.0296702e-05, -0.38110086 0.16644277 9.9390745e-06, -0.18545073 0.16644442 -0.0059900135, -0.18551752 0.16644439 -0.0054394752, -0.18545075 0.16944444 -0.0059897453, -0.1855177 0.16944444 -0.0054392964, -0.1857142 0.1664443 -0.0049211532, -0.18571427 0.16944431 -0.0049209148, -0.18602912 0.16644423 -0.0044646114, -0.18602927 0.16944434 -0.0044644624, -0.18644433 0.16644435 -0.0040969402, -0.18644425 0.16944429 -0.0040970594, -0.18693519 0.16644429 -0.0038394779, -0.18693528 0.16944431 -0.0038393289, -0.1874736 0.16644433 -0.0037066489, -0.18747357 0.16944429 -0.0037066489, -0.18802798 0.1664443 -0.003706798, -0.18802805 0.16944423 -0.0037066489, -0.18856639 0.16644433 -0.0038393289, -0.18856639 0.16944429 -0.0038392395, -0.18905741 0.1664443 -0.0040970594, -0.18905723 0.1694442 -0.0040969402, -0.18947238 0.16644433 -0.0044646114, -0.18947232 0.16944429 -0.0044646114, -0.18978739 0.1664443 -0.0049211532, -0.18978742 0.16944429 -0.0049209148, -0.18998393 0.16644432 -0.0054394752, -0.18998393 0.16944435 -0.0054393858, -0.19005074 0.16644439 -0.0059898943, -0.19005075 0.16944441 -0.0059897453, -0.18545079 0.16644369 0.0060100108, -0.18551761 0.16644374 0.0065604597, -0.18545078 0.1694437 0.0060101897, -0.1855177 0.16944373 0.0065606683, -0.18571432 0.16644377 0.0070787817, -0.18571414 0.16944362 0.007079199, -0.1860292 0.16644362 0.0075352341, -0.18602914 0.16944361 0.0075354427, -0.18644427 0.16644366 0.0079029649, -0.1864443 0.16944365 0.0079030544, -0.18693519 0.16644369 0.008160457, -0.18693514 0.16944358 0.008160606, -0.18747354 0.16644356 0.0082933456, -0.18747358 0.16944361 0.0082933456, -0.18802807 0.16644362 0.008293286, -0.18802799 0.16944352 0.0082934946, -0.18856636 0.16644359 0.008160457, -0.18856636 0.16944364 0.008160606, -0.18905729 0.16644359 0.0079029649, -0.18905729 0.16944358 0.0079029649, -0.18947235 0.16644359 0.0075352341, -0.18947238 0.16944364 0.0075354427, -0.18978733 0.16644362 0.0070787817, -0.18978739 0.1694437 0.0070790797, -0.1899839 0.1664436 0.0065604597, -0.18998393 0.16944364 0.0065606683, -0.19005078 0.16644369 0.0060100406, -0.19005069 0.16944367 0.0060101897, -0.38745078 0.16644236 0.0060100406, -0.38751766 0.16644238 0.0065604597, -0.3874509 0.16944245 0.0060101897, -0.38751766 0.16944242 0.0065606683, -0.38771436 0.16644235 0.0070787817, -0.3877143 0.16944237 0.0070787817, -0.38802928 0.16644239 0.0075352937, -0.38802919 0.16944227 0.0075352937, -0.38844433 0.16644226 0.0079029649, -0.38844427 0.16944224 0.0079029649, -0.3889353 0.16644228 0.008160457, -0.38893536 0.1694423 0.008160606, -0.38947365 0.16644232 0.008293286, -0.38947353 0.16944221 0.0082934946, -0.39002827 0.16644236 0.008293286, -0.39002809 0.16944222 0.0082933456, -0.39056659 0.16644233 0.008160457, -0.39056644 0.1694423 0.008160606, -0.39105743 0.16644228 0.0079029649, -0.39105752 0.16944234 0.0079029649, -0.39147246 0.16644229 0.0075354427, -0.39147237 0.16944225 0.0075354427, -0.39178738 0.16644236 0.0070789903, -0.39178738 0.16944237 0.0070790797, -0.39198411 0.16644241 0.0065604597, -0.39198408 0.16944237 0.0065604597, -0.39205101 0.16644244 0.0060100406, -0.39205083 0.16944237 0.0060101897, -0.38745102 0.16644312 -0.0059898943, -0.38751778 0.16644309 -0.0054394752, -0.38745078 0.16944306 -0.0059897453, -0.38751766 0.16944301 -0.0054394752, -0.38771424 0.16644301 -0.0049211532, -0.38771424 0.16944303 -0.0049210638, -0.38802943 0.16644304 -0.0044646114, -0.38802919 0.16944298 -0.0044646114, -0.38844433 0.16644305 -0.0040970594, -0.38844427 0.16944304 -0.0040969402, -0.38893542 0.16644304 -0.0038393289, -0.38893536 0.16944301 -0.0038393289, -0.38947371 0.16644302 -0.003706798, -0.38947353 0.16944298 -0.0037066489, -0.39002812 0.16644305 -0.0037066489, -0.39002815 0.16944303 -0.0037066489, -0.39056656 0.16644304 -0.0038393289, -0.39056656 0.16944306 -0.0038393289, -0.39105758 0.16644301 -0.0040970594, -0.39105752 0.16944303 -0.0040969402, -0.39147258 0.16644305 -0.0044646114, -0.39147243 0.16944301 -0.0044646114, -0.39178738 0.16644296 -0.0049211532, -0.39178738 0.16944297 -0.0049209148, -0.39198408 0.16644312 -0.0054394752, -0.39198408 0.169443 -0.0054393858, -0.39205083 0.16644308 -0.0059900135, -0.39205101 0.16944318 -0.0059897453, -0.22640073 0.16944659 -0.049989775, -0.22635278 0.1694465 -0.049595013, -0.22640087 0.16644669 -0.049989924, -0.2263529 0.16644669 -0.049595192, -0.22621188 0.16944662 -0.049222931, -0.22621185 0.16644663 -0.049223199, -0.22598585 0.1694465 -0.048895553, -0.22598587 0.16644654 -0.048895821, -0.22568813 0.16944651 -0.048631772, -0.22568819 0.16644664 -0.048632041, -0.22533587 0.16944651 -0.048446998, -0.22533603 0.16644666 -0.048447266, -0.22494963 0.16944651 -0.04835175, -0.22494972 0.16644654 -0.048352018, -0.22455192 0.16944659 -0.04835175, -0.22455198 0.16644664 -0.048352018, -0.22416568 0.16944659 -0.048446998, -0.22416574 0.16644666 -0.048447266, -0.22381341 0.16944656 -0.048631921, -0.22381347 0.16644666 -0.04863213, -0.22351578 0.16944665 -0.048895702, -0.22351575 0.16644666 -0.048895821, -0.22328982 0.16944659 -0.049223199, -0.2232898 0.16644657 -0.049223199, -0.22314882 0.16944668 -0.049595013, -0.22314873 0.1664466 -0.049595103, -0.22310086 0.16944668 -0.049989834, -0.22310087 0.16644669 -0.049989924, -0.22640082 0.16944519 -0.024989679, -0.2263529 0.16944519 -0.024595007, -0.22640079 0.16644523 -0.024989977, -0.22635287 0.16644529 -0.024595246, -0.22621174 0.16944507 -0.024222925, -0.22621192 0.16644523 -0.024223074, -0.22598585 0.1694451 -0.023895606, -0.2259858 0.16644511 -0.023895815, -0.2256881 0.1694451 -0.023631886, -0.22568816 0.16644517 -0.023632124, -0.22533581 0.16944505 -0.023446992, -0.22533593 0.1664452 -0.02344726, -0.22494972 0.1694451 -0.023351863, -0.22494975 0.16644523 -0.023352101, -0.22455189 0.16944513 -0.023351863, -0.22455192 0.16644511 -0.023352012, -0.22416568 0.16944519 -0.023446992, -0.22416562 0.16644511 -0.023447111, -0.22381353 0.16944516 -0.023632035, -0.22381347 0.1664452 -0.023632035, -0.22351581 0.16944519 -0.023895606, -0.22351569 0.16644512 -0.023895815, -0.22328986 0.16944519 -0.024223074, -0.22328976 0.16644511 -0.024223164, -0.22314882 0.16944526 -0.024594858, -0.22314866 0.1664452 -0.024595097, -0.22310081 0.16944519 -0.024989828, -0.22310075 0.16644527 -0.024989828, -0.22640085 0.16944382 1.0296702e-05, -0.22635284 0.16944376 0.00040508807, -0.22640081 0.16644379 9.9390745e-06, -0.22635287 0.16644385 0.00040499866, -0.22621182 0.16944376 0.00077717006, -0.2262118 0.16644379 0.00077678263, -0.22598574 0.16944367 0.0011043996, -0.22598587 0.16644385 0.0011043996, -0.22568816 0.1694437 0.0013681799, -0.22568822 0.16644377 0.0013679117, -0.22533584 0.16944367 0.0015530735, -0.22533594 0.16644372 0.0015529543, -0.22494966 0.16944361 0.0016482025, -0.22494972 0.16644368 0.0016479343, -0.22455192 0.1694437 0.0016480833, -0.22455198 0.16644377 0.0016479343, -0.22416568 0.16944374 0.0015530735, -0.22416574 0.16644375 0.0015528351, -0.2238135 0.16944379 0.0013680607, -0.22381346 0.16644368 0.0013679117, -0.22351575 0.16944382 0.0011043996, -0.22351575 0.16644382 0.0011043996, -0.22328988 0.16944385 0.00077717006, -0.22328982 0.16644385 0.00077678263, -0.22314879 0.16944382 0.00040508807, -0.22314878 0.16644382 0.00040484965, -0.22310087 0.16944385 1.0296702e-05, -0.22310078 0.16644385 9.9390745e-06, -0.22640082 0.16944245 0.025010124, -0.22635287 0.16944236 0.025405064, -0.22640079 0.16644245 0.025009945, -0.22635287 0.16644233 0.025404826, -0.22621182 0.16944233 0.025777027, -0.22621185 0.16644245 0.02577664, -0.22598574 0.16944233 0.026104346, -0.22598585 0.16644233 0.026104257, -0.22568807 0.1694423 0.026368037, -0.22568819 0.16644247 0.026368037, -0.22533587 0.1694423 0.026552901, -0.22533593 0.16644247 0.026552901, -0.22494975 0.16944233 0.026648059, -0.22494963 0.16644233 0.026648059, -0.22455201 0.16944239 0.026648059, -0.22455186 0.16644233 0.026648059, -0.22416568 0.16944231 0.026552901, -0.22416572 0.16644245 0.026552901, -0.2238135 0.16944234 0.026368037, -0.22381353 0.16644245 0.026368037, -0.22351578 0.16944234 0.026104257, -0.22351581 0.16644245 0.026104257, -0.22328982 0.16944239 0.025777027, -0.2232898 0.16644245 0.025777027, -0.22314873 0.16944236 0.025405064, -0.22314878 0.16644245 0.025405064, -0.22310081 0.16944242 0.025010243, -0.22310078 0.16644242 0.025010005, -0.22640082 0.16944095 0.050010249, -0.22635293 0.16944095 0.05040504, -0.22640076 0.16644096 0.050010249, -0.22635287 0.16644102 0.050404981, -0.22621185 0.16944093 0.050777003, -0.22621188 0.16644105 0.050776854, -0.22598588 0.16944098 0.051104471, -0.22598583 0.16644093 0.051104084, -0.22568816 0.16944098 0.051368192, -0.22568816 0.16644093 0.051368043, -0.2253359 0.16944095 0.051552966, -0.22533588 0.1664409 0.051552817, -0.22494973 0.16944091 0.051648185, -0.22494972 0.16644102 0.051648065, -0.22455198 0.16944093 0.051648185, -0.22455201 0.16644104 0.051648065, -0.22416571 0.16944093 0.051552966, -0.22416565 0.16644099 0.051552817, -0.2238135 0.16944098 0.051368162, -0.22381355 0.16644102 0.051367953, -0.22351578 0.16944098 0.051104471, -0.22351575 0.16644095 0.051104084, -0.22328986 0.16944098 0.050777003, -0.22328982 0.16644099 0.050776854, -0.22314876 0.16944098 0.05040504, -0.22314879 0.16644095 0.050404981, -0.22310081 0.16944098 0.050010368, -0.2231008 0.16644102 0.050010249, -0.37275076 0.16643858 0.078010127, -0.39775082 0.16943838 0.078010246, -0.39775079 0.16643831 0.078010127, -0.37275088 0.16943857 0.078010246, -0.21675088 0.16643962 0.078010127, -0.36075088 0.16943859 0.078010246, -0.36075091 0.1664387 0.078010127, -0.21675074 0.16943944 0.078010246, -0.36075079 0.16644733 -0.07799001, -0.21675082 0.16944826 -0.077989742, -0.21675074 0.16644827 -0.07799001, -0.36075088 0.16944735 -0.07799001, -0.20475078 0.16644835 -0.07799001, -0.17975083 0.16944851 -0.077989653, -0.1797509 0.16644856 -0.07799001, -0.20475073 0.16944824 -0.077989742, -0.22314876 0.16944098 0.049615279, -0.22314873 0.16644099 0.049615219, -0.22328982 0.16944104 0.049243405, -0.22328982 0.16644099 0.049243376, -0.22351569 0.16944107 0.048916176, -0.22351569 0.16644105 0.048915848, -0.22381343 0.16944109 0.048652455, -0.22381347 0.1664412 0.048652247, -0.22416568 0.16944113 0.048467472, -0.22416569 0.16644108 0.048467293, -0.22455192 0.16944112 0.048372284, -0.22455189 0.16644113 0.048372224, -0.22494966 0.16944107 0.048372284, -0.22494975 0.16644113 0.048372224, -0.22533593 0.16944109 0.048467472, -0.22533587 0.16644114 0.048467293, -0.22568817 0.16944113 0.048652247, -0.22568813 0.16644111 0.048652247, -0.22598585 0.16944104 0.048916176, -0.22598583 0.16644101 0.048916146, -0.22621185 0.16944104 0.049243405, -0.22621186 0.16644105 0.049243078, -0.2263529 0.16944101 0.049615487, -0.22635287 0.16644102 0.049615219, -0.22314873 0.16944236 0.024615362, -0.22314879 0.16644242 0.024615154, -0.22328979 0.16944242 0.02424334, -0.2232898 0.16644245 0.02424325, -0.22351572 0.16944242 0.02391611, -0.22351569 0.16644245 0.023915872, -0.22381347 0.16944247 0.02365233, -0.22381341 0.16644245 0.023652092, -0.22416571 0.16944246 0.023467466, -0.22416569 0.16644242 0.023467407, -0.22455192 0.16944255 0.023372158, -0.22455186 0.1664425 0.023372069, -0.22494967 0.16944256 0.023372158, -0.22494966 0.16644254 0.023372069, -0.22533588 0.16944242 0.023467407, -0.22533593 0.16644247 0.023467407, -0.22568817 0.16944249 0.023652241, -0.22568807 0.16644239 0.023652092, -0.22598588 0.16944239 0.02391611, -0.22598588 0.1664425 0.023915872, -0.22621188 0.16944245 0.024243489, -0.22621185 0.16644245 0.02424325, -0.2263529 0.16944245 0.024615362, -0.22635287 0.16644248 0.024615154, -0.22314879 0.16944382 -0.00038464367, -0.22314878 0.16644382 -0.00038485229, -0.22328985 0.16944388 -0.00075645745, -0.22328976 0.16644385 -0.00075669587, -0.22351575 0.16944389 -0.0010839254, -0.22351575 0.16644394 -0.0010840446, -0.22381347 0.16944396 -0.0013478249, -0.22381347 0.16644394 -0.0013478249, -0.22416565 0.16944391 -0.0015324801, -0.22416568 0.16644399 -0.0015324801, -0.22455195 0.16944394 -0.0016278476, -0.22455189 0.1664439 -0.0016280264, -0.22494967 0.16944394 -0.0016278476, -0.22494966 0.16644391 -0.0016280264, -0.22533593 0.16944392 -0.0015324801, -0.2253359 0.16644393 -0.0015326291, -0.22568813 0.16944388 -0.0013476163, -0.22568813 0.16644397 -0.0013478547, -0.22598585 0.16944388 -0.0010840446, -0.22598593 0.16644394 -0.0010840446, -0.22621188 0.16944391 -0.00075666606, -0.22621176 0.16644382 -0.00075669587, -0.2263529 0.16944391 -0.00038485229, -0.22635287 0.16644385 -0.00038485229, -0.22314873 0.16944522 -0.02538465, -0.22314873 0.16644527 -0.025384739, -0.22328982 0.16944525 -0.025756583, -0.22328976 0.16644527 -0.025756672, -0.2235157 0.16944526 -0.026084051, -0.22351567 0.16644529 -0.026084051, -0.22381355 0.16944534 -0.026347712, -0.22381353 0.16644531 -0.026347831, -0.22416571 0.16944532 -0.026532546, -0.22416568 0.16644542 -0.026532754, -0.22455189 0.16944535 -0.026627854, -0.22455189 0.16644533 -0.026628003, -0.2249496 0.16944534 -0.026627854, -0.22494972 0.16644534 -0.026628003, -0.22533596 0.1694454 -0.026532754, -0.22533584 0.16644543 -0.026532754, -0.22568813 0.16944525 -0.026347712, -0.2256882 0.16644531 -0.02634798, -0.22598585 0.16944525 -0.026084051, -0.2259858 0.16644526 -0.026084051, -0.22621188 0.16944531 -0.025756672, -0.22621185 0.16644529 -0.025756583, -0.22635283 0.16944525 -0.02538465, -0.2263529 0.16644531 -0.025384739, -0.22314879 0.16944671 -0.050384745, -0.22314879 0.16644669 -0.050384894, -0.22328976 0.16944665 -0.050756678, -0.22328982 0.16644675 -0.050756827, -0.22351575 0.16944666 -0.051084056, -0.22351581 0.16644675 -0.051084146, -0.22381356 0.16944677 -0.051347658, -0.22381347 0.16644669 -0.051347986, -0.22416568 0.16944674 -0.051532611, -0.22416566 0.16644672 -0.05153276, -0.22455195 0.16944671 -0.0516278, -0.22455189 0.16644675 -0.051628008, -0.22494966 0.16944665 -0.0516278, -0.22494972 0.16644672 -0.051628008, -0.2253359 0.16944665 -0.051532611, -0.22533584 0.1664467 -0.05153276, -0.22568816 0.16944674 -0.051347658, -0.22568816 0.16644667 -0.051347777, -0.22598585 0.16944669 -0.051084056, -0.22598585 0.16644672 -0.051084146, -0.22621188 0.16944677 -0.050756678, -0.22621185 0.16644672 -0.050756678, -0.22635287 0.16944662 -0.050384745, -0.2263529 0.16644669 -0.050385013, -0.38844427 0.16944318 -0.0078825802, -0.38802925 0.16944318 -0.0075150579, -0.36959118 0.16944677 -0.06887494, -0.37049344 0.16944681 -0.069674209, -0.38216564 0.16944569 -0.051532611, -0.18571433 0.16944388 0.0049414188, -0.18551756 0.1694437 0.0054597706, -0.38181356 0.16944566 -0.051347658, -0.38151583 0.16944566 -0.051084056, -0.38435289 0.16944426 -0.025384739, -0.39178744 0.16944313 -0.0070584863, -0.39147243 0.1694432 -0.0075150579, -0.20897773 0.16944012 0.06833525, -0.20791045 0.16944009 0.068895295, -0.38771424 0.1694431 -0.0070587248, -0.38216576 0.16944289 -0.0015324801, -0.17475076 0.16944003 0.073010221, -0.40275094 0.16943862 0.073010221, -0.40262556 0.16943857 0.074122861, -0.4022558 0.16943841 0.075179681, -0.40166 0.16943836 0.076127663, -0.37117809 0.16944675 -0.070666328, -0.38255194 0.1694456 -0.051627681, -0.40086839 0.16943835 0.076919362, -0.39992025 0.16943835 0.077514932, -0.39886346 0.16943838 0.077884927, -0.38294986 0.16944568 -0.051627681, -0.21014807 0.16943997 0.068046674, -0.38181356 0.16944295 -0.0013478249, -0.20700821 0.16944006 0.069694623, -0.36852393 0.16944675 -0.068314895, -0.38128999 0.16944571 -0.050756589, -0.38151583 0.16944295 -0.0010838956, -0.37160549 0.16944693 -0.071793184, -0.39775082 0.16944705 -0.077989653, -0.36735365 0.16944672 -0.068026528, -0.38128987 0.16944279 -0.00075645745, -0.38114879 0.16944562 -0.050384745, -0.20632355 0.16943996 0.070686683, -0.23734504 0.16944608 -0.04159306, -0.23690122 0.16944599 -0.040324882, -0.37175098 0.16943856 0.077010378, -0.3725284 0.1694385 0.077985302, -0.37231699 0.1694385 0.077911273, -0.37212744 0.16943851 0.077792183, -0.37196913 0.16943856 0.077633992, -0.37184986 0.16943854 0.077444002, -0.37177601 0.16943859 0.077232823, -0.37175095 0.16944699 -0.072989777, -0.37175104 0.16943884 0.073010221, -0.36614814 0.16944668 -0.06802617, -0.23805979 0.16944614 -0.042730793, -0.20589608 0.16943985 0.071813688, -0.37160555 0.16943884 0.071813688, -0.23675084 0.16944599 -0.038989857, -0.17975087 0.16943982 0.078010246, -0.19635281 0.16944115 0.049615279, -0.2390099 0.16944619 -0.043680891, -0.34421191 0.16944449 -0.025756672, -0.34398594 0.16944455 -0.026084051, -0.19621179 0.16944115 0.049243405, -0.36165181 0.16943856 0.077444002, -0.36153272 0.16943862 0.077633992, -0.36137435 0.16943862 0.077792183, -0.36118481 0.16943853 0.077911392, -0.34368822 0.16944449 -0.026347712, -0.19598576 0.16944109 0.048916146, -0.3617259 0.16943863 0.077232823, -0.36175087 0.16943862 0.077010378, -0.36097333 0.16943862 0.077985302, -0.24014759 0.16944626 -0.044395521, -0.34333596 0.16944456 -0.026532546, -0.27675083 0.16944095 0.045010462, -0.37275085 0.1694473 -0.077989653, -0.24141577 0.1694462 -0.044839248, -0.3717508 0.16944714 -0.076989844, -0.28275087 0.16944565 -0.038989767, -0.30128989 0.16944338 -0.00075666606, -0.30114877 0.16944332 -0.00038464367, -0.30114886 0.1694448 -0.025384739, -0.30128986 0.16944484 -0.025756583, -0.30151585 0.16944477 -0.026084051, -0.30181345 0.16944475 -0.026347712, -0.24275079 0.16944622 -0.04498969, -0.34294972 0.16944456 -0.026627854, -0.37252828 0.16944718 -0.077964619, -0.30435291 0.16944045 0.049615487, -0.34114888 0.16944021 0.049615279, -0.34128997 0.16944024 0.049243405, -0.36175087 0.16943884 0.073010221, -0.30421177 0.16944039 0.049243405, -0.19314878 0.16944119 0.049615279, -0.36497787 0.16944677 -0.068314657, -0.37117812 0.16943885 0.070686683, -0.37196901 0.16944721 -0.07761319, -0.37177595 0.16944723 -0.077212289, -0.37184986 0.16944718 -0.077423885, -0.37212732 0.16944723 -0.077771857, -0.37231693 0.16944726 -0.077890709, -0.21631689 0.1694396 0.077911273, -0.21652824 0.16943944 0.077985302, -0.37049344 0.16943897 0.069694623, -0.34255204 0.16944458 -0.026627854, -0.38435289 0.16943996 0.049615487, -0.34435293 0.16944601 -0.050384745, -0.21612728 0.16943952 0.077792093, -0.28260055 0.16944575 -0.040324882, -0.36959127 0.169439 0.068895444, -0.3421658 0.16944458 -0.026532546, -0.28215668 0.16944584 -0.041593179, -0.21596894 0.16943954 0.077633664, -0.34421191 0.16944595 -0.050756589, -0.36391053 0.16944681 -0.06887494, -0.28144184 0.16944587 -0.042730793, -0.28049174 0.16944593 -0.043680772, -0.30114874 0.16944608 -0.050384745, -0.30128989 0.16944624 -0.050756589, -0.21584982 0.16943957 0.077444002, -0.19598578 0.16944405 -0.0010840446, -0.27935407 0.16944593 -0.04439567, -0.30151585 0.16944624 -0.051084056, -0.34181365 0.16944453 -0.026347712, -0.36852393 0.16943911 0.06833525, -0.34398589 0.16944586 -0.051084056, -0.27808598 0.16944599 -0.044839337, -0.30181357 0.16944616 -0.051347658, -0.36300835 0.16944684 -0.069674209, -0.19568807 0.1694441 -0.0013476163, -0.21575075 0.16943957 0.077010378, -0.21577582 0.16943954 0.077232733, -0.36735365 0.16943917 0.068046674, -0.27675083 0.16944601 -0.044989809, -0.30216584 0.16944624 -0.051532611, -0.19533587 0.16944405 -0.0015324801, -0.18978742 0.16944447 -0.0070587248, -0.36614814 0.16943909 0.068046674, -0.34151581 0.1694445 -0.026084051, -0.34368822 0.16944598 -0.051347658, -0.34398594 0.16944163 0.02391611, -0.18947238 0.1694445 -0.0075150579, -0.34368822 0.16944169 0.023652241, -0.34128991 0.1694445 -0.025756583, -0.34421191 0.16944171 0.024243489, -0.36232361 0.16944681 -0.070666179, -0.34333596 0.16944593 -0.051532611, -0.18905738 0.16944456 -0.0078826994, -0.34333596 0.1694417 0.023467466, -0.38421187 0.16944002 0.049243405, -0.38398588 0.16944 0.048916176, -0.23675087 0.16944161 0.039010301, -0.18856634 0.16944447 -0.0081403106, -0.38368806 0.16944011 0.048652455, -0.34294978 0.16944179 0.023372158, -0.19635287 0.16944544 -0.02538465, -0.38114879 0.16944273 -0.00038464367, -0.38333604 0.16944011 0.048467472, -0.18802801 0.16944453 -0.0082731098, -0.34255204 0.16944183 0.023372158, -0.19621177 0.16944543 -0.025756583, -0.34435293 0.16944315 -0.00038485229, -0.36189625 0.16944697 -0.071793184, -0.34294978 0.16944596 -0.0516278, -0.38294986 0.16944019 0.048372492, -0.21575084 0.16943982 0.073010221, -0.19598579 0.16944543 -0.026083902, -0.3421658 0.16944171 0.023467466, -0.382552 0.16944014 0.048372284, -0.36175093 0.16944697 -0.072989836, -0.34255204 0.16944598 -0.051627681, -0.34421191 0.16944306 -0.00075666606, -0.18747351 0.16944455 -0.0082729906, -0.24275082 0.16944113 0.045010194, -0.38216576 0.16944014 0.048467472, -0.34181353 0.1694417 0.023652241, -0.18693519 0.16944455 -0.0081403106, -0.3818135 0.16944009 0.048652515, -0.34151581 0.16944164 0.02391611, -0.18644419 0.16944449 -0.0078826994, -0.38151577 0.16943996 0.048916176, -0.18602921 0.16944455 -0.0075149387, -0.34128991 0.16944161 0.02424334, -0.38128981 0.16943994 0.049243405, -0.36165193 0.16944736 -0.077423885, -0.36172584 0.1694473 -0.077212408, -0.36175087 0.16944721 -0.076989844, -0.1931487 0.16944534 -0.02538465, -0.18571416 0.16944437 -0.0070587248, -0.36153266 0.16944726 -0.077613547, -0.36137435 0.16944727 -0.077771857, -0.36118481 0.16944738 -0.077890947, -0.19568808 0.16944546 -0.026347712, -0.38398576 0.16944423 -0.026083812, -0.38368824 0.16944429 -0.026347622, -0.19533585 0.1694455 -0.026532635, -0.38435289 0.16944139 0.024615362, -0.36097333 0.16944727 -0.077964976, -0.19568808 0.16944128 0.048652515, -0.38421184 0.16944425 -0.025756583, -0.38333616 0.16944437 -0.026532546, -0.38421184 0.16944136 0.02424334, -0.3421658 0.16944592 -0.051532611, -0.34181365 0.16944599 -0.051347658, -0.19494969 0.16944554 -0.026627645, -0.19533578 0.16944127 0.048467472, -0.38398585 0.16944145 0.02391611, -0.20475078 0.16943964 0.078010246, -0.20575078 0.1694396 0.077010378, -0.2057257 0.16943963 0.077232763, -0.20565172 0.16943961 0.077444002, -0.20553263 0.1694396 0.077633724, -0.2053742 0.1694396 0.077792093, -0.20518459 0.16943954 0.077911034, -0.20497324 0.16943955 0.077985302, -0.19455197 0.1694455 -0.026627734, -0.38294968 0.16944429 -0.026627854, -0.38368818 0.16944142 0.023652241, -0.38333616 0.16944151 0.023467466, -0.19635287 0.16944683 -0.050384626, -0.19494966 0.16944136 0.048372284, -0.19416568 0.16944551 -0.026532546, -0.38294986 0.16944154 0.023372307, -0.38255188 0.16944435 -0.026627734, -0.38255188 0.16944149 0.023372158, -0.30421188 0.16944331 -0.00075645745, -0.30398583 0.16944338 -0.0010838956, -0.38216576 0.16944431 -0.026532546, -0.19381337 0.16944537 -0.026347622, -0.194552 0.1694414 0.048372284, -0.19635284 0.16944259 0.024615362, -0.38216564 0.1694414 0.023467466, -0.30368817 0.16944352 -0.0013476163, -0.3818135 0.16944419 -0.026347712, -0.36391053 0.16943905 0.068895444, -0.36300835 0.16943897 0.069694623, -0.34128997 0.16944312 -0.00075645745, -0.21449336 0.16944787 -0.069674209, -0.19416572 0.16944134 0.048467472, -0.19621179 0.16944258 0.02424334, -0.21359105 0.16944784 -0.06887494, -0.38151577 0.16944431 -0.026084051, -0.36232361 0.16943888 0.070686683, -0.30333591 0.16944352 -0.0015324801, -0.36497787 0.16943905 0.06833525, -0.19351564 0.16944537 -0.026083902, -0.19381338 0.16944125 0.048652247, -0.19598572 0.16944255 0.02391611, -0.38128981 0.16944419 -0.025756583, -0.21517804 0.16944784 -0.070666179, -0.36189625 0.16943888 0.071813688, -0.30294982 0.16944349 -0.0016278476, -0.19351566 0.16944125 0.048916176, -0.21252382 0.16944769 -0.068314657, -0.1932898 0.16944551 -0.025756463, -0.19328983 0.16944122 0.049243405, -0.34114876 0.1694445 -0.025384739, -0.21560544 0.16944784 -0.071793184, -0.30255201 0.16944343 -0.0016278476, -0.30435291 0.16944474 -0.02538465, -0.21135338 0.1694476 -0.06802617, -0.30398589 0.16944049 0.048916176, -0.34435293 0.16944028 0.049615487, -0.38114879 0.16943991 0.049615279, -0.20575076 0.16943982 0.073010221, -0.30368832 0.16944072 0.048652455, -0.30216578 0.16944343 -0.0015324801, -0.30421188 0.16944474 -0.025756583, -0.21575078 0.16944793 -0.072989836, -0.34421191 0.16944021 0.049243405, -0.30333593 0.16944058 0.048467293, -0.40275088 0.16944671 -0.072989836, -0.30181357 0.16944344 -0.0013478249, -0.30151579 0.16944338 -0.0010840446, -0.38368824 0.16944566 -0.051347598, -0.3833361 0.16944574 -0.051532432, -0.38398588 0.16944569 -0.051084056, -0.39198402 0.16944312 -0.0065401644, -0.38421184 0.16944568 -0.050756678, -0.38435289 0.16944569 -0.050384745, -0.21014807 0.16944773 -0.068026289, -0.19621179 0.16944681 -0.050756589, -0.30294976 0.16944066 0.048372284, -0.20897774 0.16944772 -0.068314895, -0.19598585 0.16944687 -0.051084056, -0.34114882 0.16944161 0.024615362, -0.20791045 0.16944787 -0.06887494, -0.1956881 0.16944689 -0.051347658, -0.19533587 0.16944687 -0.051532432, -0.24141563 0.1694411 0.044859782, -0.30255201 0.16944076 0.048372284, -0.30255201 0.16944627 -0.051627681, -0.21575084 0.16944817 -0.076989844, -0.30435297 0.16944197 0.024615422, -0.21652833 0.16944829 -0.077964976, -0.21560547 0.16943985 0.071813896, -0.30216572 0.16944063 0.048467293, -0.21631697 0.16944829 -0.077890947, -0.21577588 0.16944817 -0.077212408, -0.21584991 0.1694483 -0.077423647, -0.21612731 0.16944826 -0.077771857, -0.24014753 0.16944125 0.044415966, -0.215969 0.16944824 -0.07761319, -0.20700818 0.16944784 -0.069674209, -0.30421183 0.16944185 0.024243489, -0.21517813 0.16943984 0.070686683, -0.19494972 0.16944684 -0.051627681, -0.30181357 0.16944058 0.048652455, -0.20632353 0.16944794 -0.070666179, -0.19455186 0.16944683 -0.051627681, -0.20589605 0.16944799 -0.071793184, -0.23900983 0.1694413 0.043701068, -0.39147255 0.1694425 0.0044851452, -0.39105746 0.16944255 0.0041172355, -0.39178744 0.16944242 0.0049414188, -0.39198396 0.1694423 0.0054597408, -0.40225568 0.1694469 -0.075159147, -0.40262565 0.16944681 -0.074102357, -0.39056644 0.1694425 0.0038595945, -0.20565172 0.16944832 -0.077423885, -0.2057257 0.16944824 -0.077212289, -0.20575078 0.16944824 -0.076989844, -0.39002827 0.16944259 0.0037269443, -0.21449333 0.16944 0.069694623, -0.23805985 0.16944136 0.042751089, -0.38947365 0.16944252 0.0037269443, -0.20537417 0.16944823 -0.077771857, -0.20553263 0.16944824 -0.07761319, -0.20518459 0.1694483 -0.077890947, -0.20497325 0.16944829 -0.077964708, -0.38802919 0.1694424 0.0044849962, -0.38771424 0.16944247 0.0049412102, -0.20575076 0.16944797 -0.072989836, -0.21359116 0.16944009 0.068895444, -0.2804918 0.16944107 0.043701276, -0.17475076 0.1694482 -0.072989777, -0.18551758 0.16944437 -0.0065401644, -0.1931487 0.16944683 -0.050384745, -0.19328982 0.16944683 -0.050756589, -0.38844433 0.16944247 0.0041172355, -0.19351566 0.1694468 -0.051084056, -0.19381346 0.16944689 -0.051347658, -0.19416568 0.16944695 -0.051532432, -0.28144184 0.16944106 0.042751089, -0.19568799 0.16944255 0.02365233, -0.30114874 0.16944051 0.049615279, -0.40086839 0.16944699 -0.076898977, -0.40166005 0.169447 -0.076107457, -0.23734501 0.16944137 0.041613623, -0.38751766 0.16944247 0.0054597706, -0.17863816 0.16944852 -0.077864483, -0.19533587 0.16944268 0.023467556, -0.19494966 0.16944279 0.023372307, -0.17758127 0.16944851 -0.077494696, -0.17487617 0.16944832 -0.074102357, -0.1752459 0.16944838 -0.075159147, -0.38893518 0.16944252 0.0038596243, -0.2793541 0.16944097 0.044415966, -0.1758416 0.16944832 -0.076107219, -0.21252379 0.16944003 0.068335041, -0.17663327 0.16944841 -0.076898977, -0.28275093 0.16944133 0.039010301, -0.28215674 0.1694411 0.041613623, -0.21135345 0.16944003 0.068046674, -0.30128989 0.16944049 0.049243405, -0.19455186 0.1694428 0.023372158, -0.27808592 0.16944088 0.044859782, -0.23690119 0.16944149 0.040345535, -0.28260037 0.16944116 0.040345445, -0.30151585 0.16944049 0.048916146, -0.39992025 0.16944692 -0.077494696, -0.38435289 0.16944283 -0.00038464367, -0.19416578 0.16944271 0.023467466, -0.30114874 0.16944185 0.024615362, -0.30128983 0.16944191 0.02424334, -0.3988634 0.16944706 -0.077864483, -0.38421187 0.16944274 -0.00075666606, -0.3818135 0.16944145 0.023652092, -0.34398594 0.16944312 -0.0010840446, -0.38398588 0.16944295 -0.0010839254, -0.19381352 0.16944271 0.023652241, -0.19351569 0.16944265 0.02391611, -0.34368822 0.16944312 -0.0013476163, -0.17758133 0.16943978 0.077515021, -0.17863815 0.16943976 0.077884927, -0.38151571 0.16944134 0.02391611, -0.19635284 0.16944396 -0.00038464367, -0.30398583 0.16944474 -0.026083812, -0.38368824 0.16944295 -0.0013476163, -0.34333596 0.16944313 -0.0015324801, -0.19328982 0.16944265 0.02424334, -0.38128993 0.16944134 0.02424334, -0.30368811 0.16944474 -0.026347622, -0.38333592 0.16944289 -0.0015324801, -0.19621187 0.16944401 -0.00075645745, -0.18998396 0.16944364 0.0054597706, -0.30333585 0.16944481 -0.026532635, -0.34294972 0.16944313 -0.0016278476, -0.38294968 0.16944288 -0.0016278476, -0.38114884 0.16944426 -0.02538465, -0.1931487 0.16944253 0.024615154, -0.34255204 0.1694432 -0.0016278476, -0.30294976 0.16944489 -0.026627854, -0.34435293 0.16944449 -0.025384739, -0.1897873 0.1694437 0.0049414188, -0.30255201 0.16944486 -0.026627854, -0.38255188 0.16944286 -0.0016278476, -0.38751766 0.1694431 -0.0065401644, -0.34216574 0.16944313 -0.0015324801, -0.30435297 0.1694462 -0.050384745, -0.34114888 0.16944592 -0.050384745, -0.30216578 0.1694448 -0.026532635, -0.34181365 0.16944319 -0.0013478249, -0.1766333 0.16943978 0.076919362, -0.18947235 0.16944382 0.0044849962, -0.30421177 0.16944611 -0.050756589, -0.34128997 0.16944596 -0.050756678, -0.34151575 0.16944587 -0.051084056, -0.34151581 0.16944315 -0.0010839254, -0.30398592 0.16944623 -0.051083937, -0.18905729 0.16944376 0.0041172355, -0.34398594 0.16944028 0.048916176, -0.30368808 0.16944614 -0.051347658, -0.34368816 0.16944033 0.048652455, -0.34333596 0.16944039 0.048467472, -0.1758416 0.16943978 0.076127991, -0.18856637 0.16944382 0.0038596243, -0.30333588 0.16944617 -0.051532432, -0.34294972 0.16944037 0.048372284, -0.38114884 0.16944136 0.024615362, -0.18802801 0.16944385 0.0037269443, -0.34255198 0.16944037 0.048372284, -0.34435293 0.16944163 0.024615362, -0.30398598 0.16944201 0.02391611, -0.30368826 0.16944197 0.023652241, -0.30294976 0.16944623 -0.0516278, -0.3421658 0.16944037 0.048467472, -0.34181356 0.16944042 0.048652515, -0.30333599 0.16944203 0.023467466, -0.19351567 0.16944408 -0.0010839254, -0.19328979 0.16944396 -0.00075645745, -0.34151581 0.16944027 0.048916176, -0.1931487 0.16944396 -0.00038485229, -0.30294976 0.16944206 0.023372158, -0.1938134 0.16944408 -0.0013476163, -0.19416568 0.16944407 -0.0015324801, -0.34114888 0.16944307 -0.00038464367, -0.30255201 0.16944206 0.023372158, -0.30435297 0.1694434 -0.00038464367, -0.19455196 0.1694442 -0.0016276389, -0.30216572 0.16944198 0.023467407, -0.1949497 0.16944414 -0.0016278476, -0.30181351 0.169442 0.02365233, -0.30151585 0.16944192 0.02391611, -0.1874736 0.1694438 0.0037269443, -0.18998399 0.16944441 -0.0065402836, -0.39002821 0.16944326 -0.0082729906, -0.38947371 0.16944332 -0.0082731098, -0.18693525 0.16944389 0.0038596243, -0.17487617 0.16944003 0.074122742, -0.17524593 0.16943982 0.075179681, -0.39056644 0.1694432 -0.0081401616, -0.18644425 0.16944385 0.0041172355, -0.38893524 0.1694432 -0.0081403106, -0.39105752 0.16944323 -0.0078826994, -0.18602929 0.16944386 0.0044849962, -0.18602926 0.16644381 0.0044849068, -0.18571424 0.16644388 0.0049411207, -0.38844427 0.1664432 -0.0078829676, -0.38802931 0.16644324 -0.0075152963, -0.38181368 0.16644569 -0.051347986, -0.36959124 0.16644678 -0.068875179, -0.38151589 0.1664457 -0.051084146, -0.40166011 0.16643839 0.076127663, -0.40225574 0.16643842 0.075179592, -0.40086839 0.16643846 0.076919362, -0.38216579 0.16644567 -0.05153285, -0.18551761 0.16644374 0.0054596812, -0.39147243 0.16644317 -0.0075151771, -0.38435298 0.16644421 -0.025384739, -0.20897777 0.1664401 0.068335041, -0.20791055 0.16644016 0.068895295, -0.39178744 0.16644308 -0.0070587248, -0.37049347 0.16644678 -0.069674388, -0.38771436 0.16644318 -0.0070587248, -0.38216576 0.16644292 -0.0015327781, -0.17475075 0.16644007 0.073010221, -0.39886346 0.16643845 0.077884719, -0.40275082 0.16643852 0.073010221, -0.39992034 0.1664384 0.077514932, -0.4026255 0.16643852 0.074122563, -0.38294986 0.1664457 -0.0516278, -0.37117809 0.16644683 -0.070666328, -0.38255206 0.16644566 -0.051628008, -0.21014816 0.16644016 0.068046436, -0.3818135 0.16644292 -0.0013480037, -0.36852399 0.16644679 -0.068314895, -0.38128999 0.16644569 -0.050756827, -0.20700821 0.16644004 0.069694534, -0.38151577 0.16644292 -0.001084283, -0.37212732 0.16643845 0.077791974, -0.37184998 0.16643861 0.077443972, -0.37196907 0.16643853 0.077633664, -0.39775088 0.16644713 -0.07799001, -0.3716056 0.16644697 -0.071793392, -0.36735359 0.16644679 -0.068026528, -0.38114884 0.16644569 -0.050385013, -0.38128993 0.16644284 -0.00075669587, -0.37175092 0.16643853 0.07701005, -0.37177598 0.16643858 0.077232733, -0.3723169 0.16643849 0.077911273, -0.37252825 0.16643845 0.077985153, -0.20632353 0.16643997 0.070686534, -0.37175095 0.16643882 0.073010221, -0.23734501 0.16644609 -0.041593418, -0.37175098 0.16644695 -0.072989985, -0.36614814 0.16644681 -0.068026528, -0.23690124 0.16644597 -0.04032515, -0.3716056 0.16643883 0.071813539, -0.23805985 0.16644619 -0.042730883, -0.20589617 0.16643997 0.071813539, -0.1797508 0.16643973 0.078010127, -0.19635284 0.16644125 0.049615219, -0.23675087 0.16644594 -0.038990065, -0.23900989 0.16644624 -0.043680981, -0.34421197 0.16644451 -0.025756672, -0.34398592 0.16644447 -0.026084051, -0.19621189 0.16644126 0.049243376, -0.36137435 0.16643867 0.077791974, -0.36165193 0.16643858 0.077443734, -0.36118475 0.16643865 0.077910945, -0.34368819 0.16644447 -0.026347831, -0.36153266 0.16643859 0.077633634, -0.19598591 0.16644125 0.048916146, -0.3617259 0.16643862 0.077232495, -0.36175081 0.16643859 0.07701017, -0.36097345 0.16643859 0.077985153, -0.2401475 0.16644615 -0.04439579, -0.34333599 0.16644453 -0.026532754, -0.2767508 0.16644092 0.045010194, -0.2827509 0.16644572 -0.038990065, -0.37275091 0.16644725 -0.07799001, -0.37175089 0.16644715 -0.076989934, -0.24141568 0.16644627 -0.044839486, -0.30128986 0.16644336 -0.00075669587, -0.30114883 0.16644336 -0.00038485229, -0.30181354 0.16644478 -0.026347712, -0.30114871 0.16644473 -0.025384858, -0.3012898 0.16644475 -0.025756821, -0.30151591 0.16644476 -0.0260842, -0.34294978 0.16644453 -0.026627854, -0.24275079 0.16644618 -0.044989929, -0.37252828 0.16644725 -0.077964976, -0.37177601 0.16644716 -0.077212647, -0.30435288 0.16644049 0.049615219, -0.36175093 0.16643888 0.073010132, -0.34114879 0.16644025 0.049615219, -0.34128997 0.1664402 0.049243376, -0.30421194 0.1664405 0.049243376, -0.19314873 0.1664412 0.049615219, -0.37117809 0.16643891 0.070686534, -0.3649779 0.16644676 -0.068315044, -0.37231711 0.16644727 -0.077890947, -0.37212738 0.16644725 -0.077771857, -0.37196907 0.1664473 -0.077613547, -0.37184986 0.16644733 -0.077423885, -0.37049347 0.16643903 0.069694534, -0.21631688 0.1664395 0.077910945, -0.21652827 0.16643956 0.077985153, -0.34255201 0.16644461 -0.026628003, -0.38435283 0.16643997 0.049615219, -0.3443529 0.16644594 -0.050385013, -0.36959127 0.16643903 0.068895295, -0.21612737 0.16643958 0.077791974, -0.28260034 0.16644572 -0.04032515, -0.34216571 0.16644455 -0.026532754, -0.28215662 0.16644581 -0.041593269, -0.21596898 0.16643962 0.077633634, -0.28144172 0.16644578 -0.042730883, -0.36391065 0.16644683 -0.06887494, -0.34421188 0.16644594 -0.050756678, -0.28049183 0.16644594 -0.04368113, -0.30114883 0.16644613 -0.050385013, -0.21584988 0.16643964 0.077443734, -0.30128986 0.16644622 -0.050756678, -0.27935404 0.16644591 -0.04439579, -0.34181362 0.16644454 -0.026347831, -0.3685239 0.16643904 0.068335041, -0.19598591 0.16644417 -0.0010841936, -0.30151576 0.16644621 -0.051084265, -0.27808589 0.16644593 -0.044839486, -0.36735347 0.16643903 0.068046674, -0.343986 0.16644596 -0.051084146, -0.19568819 0.16644417 -0.0013478249, -0.36300829 0.16644682 -0.069674388, -0.30181357 0.16644613 -0.051347986, -0.21575083 0.16643962 0.07701017, -0.27675086 0.16644605 -0.044989809, -0.21577588 0.16643962 0.077232733, -0.34151581 0.16644451 -0.026084051, -0.30216566 0.16644616 -0.05153285, -0.3661482 0.16643909 0.068046674, -0.19533585 0.16644417 -0.0015327781, -0.18978733 0.16644439 -0.007058844, -0.34368819 0.1664459 -0.051347777, -0.18947223 0.16644448 -0.0075151771, -0.343986 0.16644171 0.023915872, -0.34368816 0.16644169 0.023652092, -0.34128991 0.16644453 -0.025756672, -0.34421182 0.16644162 0.02424325, -0.36232373 0.16644691 -0.070666328, -0.34333593 0.16644591 -0.05153276, -0.18905735 0.16644451 -0.0078828186, -0.34333593 0.1664416 0.023467407, -0.38421184 0.16643992 0.049243078, -0.38398585 0.16643995 0.048916146, -0.38368833 0.16644022 0.048652068, -0.23675081 0.16644162 0.039010063, -0.34294966 0.16644177 0.023372069, -0.1885663 0.16644448 -0.0081403106, -0.38114882 0.16644284 -0.00038485229, -0.19635284 0.16644546 -0.025384858, -0.38333607 0.16644019 0.048467293, -0.34255198 0.16644177 0.023372069, -0.1880279 0.16644442 -0.0082733482, -0.3829498 0.16644016 0.048372224, -0.3443529 0.16644305 -0.00038485229, -0.19621176 0.16644542 -0.025756672, -0.36189607 0.16644691 -0.071793392, -0.34294981 0.16644599 -0.051628008, -0.21575071 0.16643973 0.073010221, -0.34216571 0.16644166 0.023467407, -0.34421188 0.16644305 -0.00075669587, -0.19598591 0.16644554 -0.0260842, -0.382552 0.16644017 0.048372045, -0.36175093 0.16644697 -0.072989866, -0.34255198 0.16644597 -0.051628008, -0.2427509 0.1664411 0.045009986, -0.18747345 0.16644448 -0.0082732588, -0.3418135 0.16644168 0.023652241, -0.38216576 0.16644016 0.048467234, -0.18693517 0.16644453 -0.0081403106, -0.34151581 0.1664416 0.023915872, -0.3818135 0.1664401 0.048652247, -0.18644422 0.16644457 -0.0078828186, -0.34128991 0.16644165 0.02424325, -0.38151583 0.16644007 0.048915848, -0.1860292 0.16644448 -0.0075151771, -0.3617259 0.16644736 -0.077212647, -0.36165193 0.16644736 -0.077423885, -0.36175093 0.16644715 -0.076989844, -0.38128999 0.16644013 0.049243078, -0.19314878 0.16644549 -0.025385007, -0.18571424 0.16644448 -0.0070587248, -0.36153272 0.16644737 -0.077613547, -0.36137438 0.16644736 -0.077771857, -0.36118472 0.16644736 -0.077890947, -0.19568807 0.16644545 -0.02634798, -0.36097333 0.16644734 -0.077964976, -0.19568811 0.16644137 0.048652068, -0.38435289 0.16644146 0.024615154, -0.38398582 0.16644424 -0.026084051, -0.38368818 0.16644426 -0.026347831, -0.19533592 0.16644554 -0.026532754, -0.38421199 0.16644427 -0.025756672, -0.38421181 0.16644138 0.02424325, -0.34216574 0.16644596 -0.05153276, -0.34181362 0.16644588 -0.051347986, -0.3833361 0.16644438 -0.026532754, -0.19533592 0.16644143 0.048467293, -0.19494969 0.16644555 -0.026628003, -0.20518464 0.16643965 0.077911273, -0.20475075 0.16643962 0.078010127, -0.20497319 0.16643961 0.077985153, -0.38398585 0.1664414 0.023915872, -0.2053743 0.16643965 0.077791974, -0.2055326 0.16643964 0.077633664, -0.2056517 0.16643959 0.077443972, -0.20572573 0.16643965 0.077232733, -0.20575075 0.16643958 0.07701017, -0.38294983 0.16644439 -0.026627854, -0.38368818 0.1664414 0.023652092, -0.3833361 0.16644152 0.023467407, -0.19455189 0.16644555 -0.026628003, -0.19494969 0.16644144 0.048372045, -0.19635281 0.16644683 -0.050384894, -0.38255206 0.16644435 -0.026628003, -0.38294983 0.16644165 0.023372069, -0.19416565 0.16644555 -0.026532754, -0.19455189 0.16644138 0.048372224, -0.38216576 0.16644435 -0.026532754, -0.382552 0.16644168 0.023372069, -0.30421185 0.16644329 -0.00075669587, -0.30398595 0.16644342 -0.0010840446, -0.19635278 0.16644256 0.024615154, -0.19381344 0.16644543 -0.02634798, -0.38216579 0.1664415 0.023467407, -0.3818135 0.16644429 -0.02634798, -0.19416571 0.16644138 0.048467293, -0.30368817 0.16644342 -0.0013478249, -0.21449333 0.16644782 -0.069674388, -0.34128976 0.16644305 -0.00075669587, -0.19621181 0.16644269 0.02424325, -0.36391053 0.16643904 0.068895295, -0.36300829 0.16643907 0.069694325, -0.38151577 0.16644427 -0.026084051, -0.21359102 0.16644779 -0.068875179, -0.36232361 0.16643888 0.070686534, -0.19381344 0.16644138 0.048652247, -0.38128996 0.16644436 -0.025756672, -0.30333591 0.16644342 -0.0015327781, -0.19598591 0.16644268 0.023915872, -0.36497787 0.16643916 0.068335041, -0.1935157 0.16644546 -0.0260842, -0.21517807 0.16644786 -0.070666447, -0.36189625 0.16643888 0.07181339, -0.19351572 0.1664412 0.048916146, -0.30294979 0.16644347 -0.0016278476, -0.21252379 0.16644773 -0.068315044, -0.19328988 0.16644126 0.049243376, -0.34114873 0.16644451 -0.025384739, -0.19328979 0.16644549 -0.025756672, -0.2156055 0.16644797 -0.071793392, -0.30255198 0.16644341 -0.0016280264, -0.30435288 0.16644487 -0.025385007, -0.21135356 0.16644776 -0.068026528, -0.30398595 0.16644058 0.048916146, -0.3443529 0.16644025 0.049615219, -0.38114884 0.16644 0.04961504, -0.20575076 0.16643982 0.073010132, -0.30368823 0.16644061 0.048652247, -0.30216575 0.16644345 -0.0015327781, -0.30421185 0.16644481 -0.025756821, -0.34421188 0.16644017 0.049243376, -0.30333591 0.16644068 0.048467472, -0.402751 0.16644685 -0.072989985, -0.21575084 0.16644797 -0.072989985, -0.38368818 0.1664457 -0.051347777, -0.3833361 0.16644572 -0.05153276, -0.30181342 0.16644339 -0.0013478249, -0.30151582 0.16644345 -0.0010840446, -0.38398585 0.16644566 -0.051084146, -0.38421184 0.16644566 -0.050756827, -0.38435298 0.1664457 -0.050384745, -0.39198413 0.16644317 -0.0065402836, -0.21014816 0.16644779 -0.068026528, -0.30294976 0.16644067 0.048372224, -0.19621176 0.16644685 -0.050756827, -0.20897779 0.16644783 -0.068315044, -0.34114885 0.16644168 0.024615362, -0.19598579 0.16644686 -0.051084265, -0.20791042 0.16644785 -0.068875179, -0.30255198 0.16644071 0.048372045, -0.19568811 0.16644697 -0.051347986, -0.19533592 0.16644691 -0.05153285, -0.24141572 0.16644117 0.044859782, -0.30255198 0.16644613 -0.051628008, -0.30435288 0.16644192 0.024615064, -0.21575081 0.16644815 -0.076989934, -0.21652821 0.16644818 -0.077964976, -0.30216575 0.16644073 0.048467472, -0.2156055 0.16643986 0.071813539, -0.30421185 0.16644192 0.02424325, -0.24014755 0.16644135 0.044415876, -0.21596897 0.16644822 -0.077613547, -0.21631688 0.16644827 -0.077890947, -0.21612726 0.16644825 -0.077771857, -0.21577582 0.16644821 -0.077212647, -0.21584988 0.16644828 -0.077423885, -0.21517807 0.16643988 0.070686534, -0.30181354 0.16644065 0.048652247, -0.20700811 0.16644782 -0.069674388, -0.19494969 0.16644698 -0.051628008, -0.20632356 0.16644798 -0.070666447, -0.19455186 0.16644689 -0.051628008, -0.23900983 0.16644134 0.043701068, -0.39147255 0.16644253 0.0044847578, -0.20589605 0.16644798 -0.071793392, -0.39105752 0.1664425 0.0041171461, -0.39178753 0.16644256 0.0049412102, -0.39198408 0.16644248 0.0054595321, -0.40262565 0.16644686 -0.074102715, -0.40225574 0.16644697 -0.075159505, -0.39056644 0.16644259 0.0038596243, -0.39002809 0.16644253 0.0037268549, -0.21449339 0.16644008 0.069694325, -0.20572577 0.16644831 -0.077212647, -0.20565175 0.16644828 -0.077423885, -0.2057507 0.16644822 -0.076989934, -0.23805983 0.16644135 0.042751089, -0.38947365 0.1664425 0.0037267059, -0.2053743 0.1664484 -0.077771857, -0.20553252 0.16644825 -0.077613547, -0.38802919 0.1664425 0.0044847578, -0.38771436 0.16644247 0.0049411207, -0.2051847 0.16644835 -0.077890947, -0.21359117 0.16644007 0.068895087, -0.20497334 0.1664484 -0.077964976, -0.20575067 0.166448 -0.072989866, -0.38844433 0.16644247 0.0041171461, -0.28049171 0.16644096 0.043701068, -0.19568811 0.16644274 0.023652092, -0.3875176 0.16644248 0.0054595321, -0.19416562 0.16644689 -0.05153276, -0.30114877 0.16644047 0.04961504, -0.28144181 0.16644104 0.042751089, -0.237345 0.16644135 0.041613266, -0.17475086 0.1664483 -0.072989985, -0.18551768 0.16644448 -0.0065402836, -0.19533581 0.16644263 0.023467317, -0.19494963 0.16644281 0.023372069, -0.1931487 0.16644689 -0.050385013, -0.40166011 0.16644701 -0.076107457, -0.40086833 0.16644695 -0.076899245, -0.19328991 0.16644698 -0.050756678, -0.19351581 0.16644686 -0.051084146, -0.19381344 0.16644686 -0.051347986, -0.3889353 0.16644257 0.0038596243, -0.27935416 0.16644102 0.044415817, -0.21252382 0.16644007 0.06833525, -0.17863813 0.1664485 -0.077864721, -0.17524588 0.16644832 -0.075159505, -0.17487612 0.16644832 -0.074102715, -0.30128983 0.16644052 0.049243376, -0.28215665 0.16644113 0.041613266, -0.17758143 0.16644862 -0.077494934, -0.21135348 0.16644007 0.068046436, -0.19455194 0.16644281 0.023372069, -0.27808589 0.16644089 0.044859782, -0.17584169 0.16644844 -0.076107457, -0.2369011 0.16644153 0.040345088, -0.17663339 0.16644852 -0.076899245, -0.28275082 0.16644125 0.039010063, -0.2826004 0.16644129 0.040345237, -0.30151582 0.16644059 0.048916146, -0.39992034 0.16644716 -0.077494934, -0.38435286 0.16644283 -0.00038485229, -0.19416565 0.16644263 0.023467317, -0.30114877 0.16644196 0.024615154, -0.30128983 0.16644199 0.02424325, -0.39886352 0.16644718 -0.077864721, -0.38421193 0.16644283 -0.00075669587, -0.34398594 0.16644312 -0.0010840446, -0.3818135 0.16644143 0.023652092, -0.38398582 0.16644281 -0.0010840446, -0.19381344 0.1664426 0.023652092, -0.19351578 0.16644269 0.023915872, -0.17758128 0.16643977 0.077514932, -0.17863815 0.16643974 0.077884719, -0.34368822 0.16644312 -0.0013478547, -0.19635281 0.16644394 -0.00038485229, -0.38151583 0.16644138 0.023915783, -0.38368818 0.16644292 -0.0013478547, -0.30398583 0.16644475 -0.026084051, -0.19328988 0.16644269 0.02424325, -0.34333593 0.16644323 -0.0015326291, -0.38128999 0.16644143 0.024243101, -0.30368811 0.16644475 -0.026347831, -0.3833361 0.16644298 -0.0015326291, -0.19621176 0.16644399 -0.00075669587, -0.1899839 0.16644371 0.0054595321, -0.30333596 0.1664449 -0.026532754, -0.34294978 0.16644314 -0.0016280264, -0.3829498 0.16644292 -0.0016280264, -0.38114884 0.16644426 -0.025384858, -0.30294973 0.1664449 -0.026628003, -0.19314885 0.16644269 0.024615154, -0.34255201 0.16644318 -0.0016280264, -0.3443529 0.1664445 -0.025384739, -0.38751766 0.16644318 -0.0065404028, -0.38255194 0.16644289 -0.0016280264, -0.18978734 0.16644385 0.0049411207, -0.30255198 0.16644488 -0.026628003, -0.30435297 0.16644618 -0.050385013, -0.34114888 0.1664459 -0.050384894, -0.3421658 0.16644321 -0.0015324801, -0.30216575 0.16644488 -0.026532754, -0.1766333 0.16643986 0.076919094, -0.34181347 0.16644315 -0.0013478249, -0.3042118 0.16644615 -0.050756678, -0.18947235 0.16644382 0.0044847578, -0.34128985 0.16644588 -0.050756678, -0.34151584 0.16644594 -0.051084056, -0.34151584 0.16644308 -0.0010840446, -0.30398589 0.16644618 -0.051084146, -0.30368823 0.1664463 -0.051347777, -0.18905741 0.16644385 0.0041171461, -0.34398592 0.16644022 0.048916146, -0.34368822 0.16644041 0.048652247, -0.34333596 0.16644034 0.048467293, -0.17584154 0.1664398 0.076127663, -0.30333585 0.16644618 -0.05153276, -0.18856645 0.16644385 0.0038595945, -0.34294969 0.16644035 0.048372224, -0.18802804 0.16644385 0.0037267059, -0.38114884 0.1664414 0.024615064, -0.30398595 0.16644195 0.023915783, -0.34255201 0.16644035 0.048372224, -0.3443529 0.16644162 0.024615154, -0.30368817 0.16644198 0.023652092, -0.30294979 0.16644634 -0.051628008, -0.34216577 0.16644037 0.048467234, -0.30333591 0.1664419 0.023467407, -0.19351578 0.16644418 -0.0010841936, -0.19328982 0.16644406 -0.00075666606, -0.34181353 0.16644041 0.048652247, -0.19314873 0.16644406 -0.00038485229, -0.30294979 0.16644217 0.023372069, -0.34151575 0.16644014 0.048916146, -0.1938135 0.16644418 -0.0013478547, -0.19416565 0.16644412 -0.0015326291, -0.34114888 0.16644309 -0.00038485229, -0.30255193 0.16644213 0.023372069, -0.19455194 0.16644418 -0.0016280264, -0.30435291 0.16644338 -0.00038485229, -0.30216569 0.16644196 0.023467407, -0.17524591 0.16643995 0.075179592, -0.19494969 0.16644411 -0.0016278774, -0.30181348 0.16644193 0.023652092, -0.30151582 0.16644196 0.023915783, -0.18747348 0.16644385 0.0037268549, -0.18998396 0.16644442 -0.0065404028, -0.39002809 0.16644321 -0.0082733482, -0.38947365 0.16644326 -0.0082733482, -0.18693522 0.16644387 0.0038595945, -0.39056644 0.16644317 -0.0081403106, -0.18644422 0.16644385 0.0041171461, -0.3889353 0.16644329 -0.0081404299, -0.39105752 0.16644321 -0.0078826994, -0.17487615 0.16644001 0.074122563 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 2, 1, 3, -1, 3, 4, 5, -1, 1, 4, 3, -1, 5, 6, 7, -1, 4, 6, 5, -1, 7, 8, 9, -1, 6, 8, 7, -1, 9, 10, 11, -1, 8, 10, 9, -1, 11, 12, 13, -1, 10, 12, 11, -1, 13, 14, 15, -1, 12, 14, 13, -1, 15, 16, 17, -1, 14, 16, 15, -1, 17, 18, 19, -1, 16, 18, 17, -1, 19, 20, 21, -1, 18, 20, 19, -1, 21, 22, 23, -1, 20, 22, 21, -1, 23, 24, 25, -1, 22, 24, 23, -1, 25, 26, 27, -1, 24, 26, 25, -1, 28, 29, 30, -1, 30, 29, 31, -1, 31, 32, 33, -1, 29, 32, 31, -1, 33, 34, 35, -1, 32, 34, 33, -1, 35, 36, 37, -1, 34, 36, 35, -1, 37, 38, 39, -1, 36, 38, 37, -1, 39, 40, 41, -1, 38, 40, 39, -1, 41, 42, 43, -1, 40, 42, 41, -1, 43, 44, 45, -1, 42, 44, 43, -1, 45, 46, 47, -1, 44, 46, 45, -1, 47, 48, 49, -1, 46, 48, 47, -1, 49, 50, 51, -1, 48, 50, 49, -1, 51, 52, 53, -1, 50, 52, 51, -1, 53, 54, 55, -1, 52, 54, 53, -1, 56, 57, 58, -1, 58, 57, 59, -1, 59, 60, 61, -1, 57, 60, 59, -1, 61, 62, 63, -1, 60, 62, 61, -1, 63, 64, 65, -1, 62, 64, 63, -1, 65, 66, 67, -1, 64, 66, 65, -1, 67, 68, 69, -1, 66, 68, 67, -1, 69, 70, 71, -1, 68, 70, 69, -1, 71, 72, 73, -1, 70, 72, 71, -1, 73, 74, 75, -1, 72, 74, 73, -1, 75, 76, 77, -1, 74, 76, 75, -1, 77, 78, 79, -1, 76, 78, 77, -1, 79, 80, 81, -1, 78, 80, 79, -1, 81, 82, 83, -1, 80, 82, 81, -1, 84, 85, 86, -1, 86, 85, 87, -1, 87, 88, 89, -1, 85, 88, 87, -1, 89, 90, 91, -1, 88, 90, 89, -1, 91, 92, 93, -1, 90, 92, 91, -1, 93, 94, 95, -1, 92, 94, 93, -1, 95, 96, 97, -1, 94, 96, 95, -1, 97, 98, 99, -1, 96, 98, 97, -1, 99, 100, 101, -1, 98, 100, 99, -1, 101, 102, 103, -1, 100, 102, 101, -1, 103, 104, 105, -1, 102, 104, 103, -1, 105, 106, 107, -1, 104, 106, 105, -1, 107, 108, 109, -1, 106, 108, 107, -1, 109, 110, 111, -1, 108, 110, 109, -1, 112, 113, 114, -1, 114, 113, 115, -1, 115, 116, 117, -1, 113, 116, 115, -1, 117, 118, 119, -1, 116, 118, 117, -1, 119, 120, 121, -1, 118, 120, 119, -1, 121, 122, 123, -1, 120, 122, 121, -1, 123, 124, 125, -1, 122, 124, 123, -1, 125, 126, 127, -1, 124, 126, 125, -1, 127, 128, 129, -1, 126, 128, 127, -1, 129, 130, 131, -1, 128, 130, 129, -1, 131, 132, 133, -1, 130, 132, 131, -1, 133, 134, 135, -1, 132, 134, 133, -1, 135, 136, 137, -1, 134, 136, 135, -1, 137, 138, 139, -1, 136, 138, 137, -1, 140, 141, 142, -1, 142, 141, 143, -1, 143, 144, 145, -1, 141, 144, 143, -1, 145, 146, 147, -1, 144, 146, 145, -1, 147, 148, 149, -1, 146, 148, 147, -1, 149, 150, 151, -1, 148, 150, 149, -1, 151, 152, 153, -1, 150, 152, 151, -1, 153, 154, 155, -1, 152, 154, 153, -1, 155, 156, 157, -1, 154, 156, 155, -1, 157, 158, 159, -1, 156, 158, 157, -1, 159, 160, 161, -1, 158, 160, 159, -1, 161, 162, 163, -1, 160, 162, 161, -1, 163, 164, 165, -1, 162, 164, 163, -1, 165, 166, 167, -1, 164, 166, 165, -1, 168, 169, 170, -1, 170, 169, 171, -1, 171, 172, 173, -1, 169, 172, 171, -1, 173, 174, 175, -1, 172, 174, 173, -1, 175, 176, 177, -1, 174, 176, 175, -1, 177, 178, 179, -1, 176, 178, 177, -1, 179, 180, 181, -1, 178, 180, 179, -1, 181, 182, 183, -1, 180, 182, 181, -1, 183, 184, 185, -1, 182, 184, 183, -1, 185, 186, 187, -1, 184, 186, 185, -1, 187, 188, 189, -1, 186, 188, 187, -1, 189, 190, 191, -1, 188, 190, 189, -1, 191, 192, 193, -1, 190, 192, 191, -1, 193, 194, 195, -1, 192, 194, 193, -1, 196, 197, 198, -1, 198, 197, 199, -1, 199, 200, 201, -1, 197, 200, 199, -1, 201, 202, 203, -1, 200, 202, 201, -1, 203, 204, 205, -1, 202, 204, 203, -1, 205, 206, 207, -1, 204, 206, 205, -1, 207, 208, 209, -1, 206, 208, 207, -1, 209, 210, 211, -1, 208, 210, 209, -1, 211, 212, 213, -1, 210, 212, 211, -1, 213, 214, 215, -1, 212, 214, 213, -1, 215, 216, 217, -1, 214, 216, 215, -1, 217, 218, 219, -1, 216, 218, 217, -1, 219, 220, 221, -1, 218, 220, 219, -1, 221, 222, 223, -1, 220, 222, 221, -1, 224, 225, 226, -1, 226, 225, 227, -1, 227, 228, 229, -1, 225, 228, 227, -1, 229, 230, 231, -1, 228, 230, 229, -1, 231, 232, 233, -1, 230, 232, 231, -1, 233, 234, 235, -1, 232, 234, 233, -1, 235, 236, 237, -1, 234, 236, 235, -1, 237, 238, 239, -1, 236, 238, 237, -1, 239, 240, 241, -1, 238, 240, 239, -1, 241, 242, 243, -1, 240, 242, 241, -1, 243, 244, 245, -1, 242, 244, 243, -1, 245, 246, 247, -1, 244, 246, 245, -1, 247, 248, 249, -1, 246, 248, 247, -1, 249, 250, 251, -1, 248, 250, 249, -1, 252, 253, 254, -1, 254, 253, 255, -1, 255, 256, 257, -1, 253, 256, 255, -1, 257, 258, 259, -1, 256, 258, 257, -1, 259, 260, 261, -1, 258, 260, 259, -1, 261, 262, 263, -1, 260, 262, 261, -1, 263, 264, 265, -1, 262, 264, 263, -1, 265, 266, 267, -1, 264, 266, 265, -1, 267, 268, 269, -1, 266, 268, 267, -1, 269, 270, 271, -1, 268, 270, 269, -1, 271, 272, 273, -1, 270, 272, 271, -1, 273, 274, 275, -1, 272, 274, 273, -1, 275, 276, 277, -1, 274, 276, 275, -1, 277, 278, 279, -1, 276, 278, 277, -1, 280, 281, 282, -1, 282, 281, 283, -1, 283, 284, 285, -1, 281, 284, 283, -1, 285, 286, 287, -1, 284, 286, 285, -1, 287, 288, 289, -1, 286, 288, 287, -1, 289, 290, 291, -1, 288, 290, 289, -1, 291, 292, 293, -1, 290, 292, 291, -1, 293, 294, 295, -1, 292, 294, 293, -1, 295, 296, 297, -1, 294, 296, 295, -1, 297, 298, 299, -1, 296, 298, 297, -1, 299, 300, 301, -1, 298, 300, 299, -1, 301, 302, 303, -1, 300, 302, 301, -1, 303, 304, 305, -1, 302, 304, 303, -1, 305, 306, 307, -1, 304, 306, 305, -1, 308, 309, 310, -1, 310, 309, 311, -1, 311, 312, 313, -1, 309, 312, 311, -1, 313, 314, 315, -1, 312, 314, 313, -1, 315, 316, 317, -1, 314, 316, 315, -1, 317, 318, 319, -1, 316, 318, 317, -1, 319, 320, 321, -1, 318, 320, 319, -1, 321, 322, 323, -1, 320, 322, 321, -1, 323, 324, 325, -1, 322, 324, 323, -1, 325, 326, 327, -1, 324, 326, 325, -1, 327, 328, 329, -1, 326, 328, 327, -1, 329, 330, 331, -1, 328, 330, 329, -1, 331, 332, 333, -1, 330, 332, 331, -1, 333, 334, 335, -1, 332, 334, 333, -1, 336, 337, 338, -1, 338, 337, 339, -1, 339, 340, 341, -1, 337, 340, 339, -1, 341, 342, 343, -1, 340, 342, 341, -1, 343, 344, 345, -1, 342, 344, 343, -1, 345, 346, 347, -1, 344, 346, 345, -1, 347, 348, 349, -1, 346, 348, 347, -1, 349, 350, 351, -1, 348, 350, 349, -1, 351, 352, 353, -1, 350, 352, 351, -1, 353, 354, 355, -1, 352, 354, 353, -1, 355, 356, 357, -1, 354, 356, 355, -1, 357, 358, 359, -1, 356, 358, 357, -1, 359, 360, 361, -1, 358, 360, 359, -1, 361, 362, 363, -1, 360, 362, 361, -1, 364, 365, 366, -1, 366, 365, 367, -1, 367, 368, 369, -1, 365, 368, 367, -1, 369, 370, 371, -1, 368, 370, 369, -1, 371, 372, 373, -1, 370, 372, 371, -1, 373, 374, 375, -1, 372, 374, 373, -1, 375, 376, 377, -1, 374, 376, 375, -1, 377, 378, 379, -1, 376, 378, 377, -1, 379, 380, 381, -1, 378, 380, 379, -1, 381, 382, 383, -1, 380, 382, 381, -1, 383, 384, 385, -1, 382, 384, 383, -1, 385, 386, 387, -1, 384, 386, 385, -1, 387, 388, 389, -1, 386, 388, 387, -1, 389, 390, 391, -1, 388, 390, 389, -1, 392, 393, 394, -1, 394, 393, 395, -1, 395, 396, 397, -1, 393, 396, 395, -1, 397, 398, 399, -1, 396, 398, 397, -1, 399, 400, 401, -1, 398, 400, 399, -1, 401, 402, 403, -1, 400, 402, 401, -1, 403, 404, 405, -1, 402, 404, 403, -1, 405, 406, 407, -1, 404, 406, 405, -1, 407, 408, 409, -1, 406, 408, 407, -1, 409, 410, 411, -1, 408, 410, 409, -1, 411, 412, 413, -1, 410, 412, 411, -1, 413, 414, 415, -1, 412, 414, 413, -1, 415, 416, 417, -1, 414, 416, 415, -1, 417, 418, 419, -1, 416, 418, 417, -1, 420, 421, 422, -1, 422, 421, 423, -1, 423, 424, 425, -1, 421, 424, 423, -1, 425, 426, 427, -1, 424, 426, 425, -1, 427, 428, 429, -1, 426, 428, 427, -1, 429, 430, 431, -1, 428, 430, 429, -1, 431, 432, 433, -1, 430, 432, 431, -1, 433, 434, 435, -1, 432, 434, 433, -1, 435, 436, 437, -1, 434, 436, 435, -1, 437, 438, 439, -1, 436, 438, 437, -1, 439, 440, 441, -1, 438, 440, 439, -1, 441, 442, 443, -1, 440, 442, 441, -1, 443, 444, 445, -1, 442, 444, 443, -1, 445, 446, 447, -1, 444, 446, 445, -1, 448, 449, 450, -1, 450, 449, 451, -1, 451, 452, 453, -1, 449, 452, 451, -1, 453, 454, 455, -1, 452, 454, 453, -1, 455, 456, 457, -1, 454, 456, 455, -1, 457, 458, 459, -1, 456, 458, 457, -1, 459, 460, 461, -1, 458, 460, 459, -1, 461, 462, 463, -1, 460, 462, 461, -1, 463, 464, 465, -1, 462, 464, 463, -1, 465, 466, 467, -1, 464, 466, 465, -1, 467, 468, 469, -1, 466, 468, 467, -1, 469, 470, 471, -1, 468, 470, 469, -1, 471, 472, 473, -1, 470, 472, 471, -1, 473, 474, 475, -1, 472, 474, 473, -1, 476, 477, 478, -1, 478, 477, 479, -1, 479, 480, 481, -1, 477, 480, 479, -1, 481, 482, 483, -1, 480, 482, 481, -1, 483, 484, 485, -1, 482, 484, 483, -1, 485, 486, 487, -1, 484, 486, 485, -1, 487, 488, 489, -1, 486, 488, 487, -1, 489, 490, 491, -1, 488, 490, 489, -1, 491, 492, 493, -1, 490, 492, 491, -1, 493, 494, 495, -1, 492, 494, 493, -1, 495, 496, 497, -1, 494, 496, 495, -1, 497, 498, 499, -1, 496, 498, 497, -1, 499, 500, 501, -1, 498, 500, 499, -1, 501, 502, 503, -1, 500, 502, 501, -1, 504, 505, 506, -1, 506, 505, 507, -1, 507, 508, 509, -1, 505, 508, 507, -1, 509, 510, 511, -1, 508, 510, 509, -1, 511, 512, 513, -1, 510, 512, 511, -1, 513, 514, 515, -1, 512, 514, 513, -1, 515, 516, 517, -1, 514, 516, 515, -1, 517, 518, 519, -1, 516, 518, 517, -1, 519, 520, 521, -1, 518, 520, 519, -1, 521, 522, 523, -1, 520, 522, 521, -1, 523, 524, 525, -1, 522, 524, 523, -1, 525, 526, 527, -1, 524, 526, 525, -1, 527, 528, 529, -1, 526, 528, 527, -1, 529, 530, 531, -1, 528, 530, 529, -1, 532, 533, 534, -1, 534, 533, 535, -1, 535, 536, 537, -1, 533, 536, 535, -1, 537, 538, 539, -1, 536, 538, 537, -1, 539, 540, 541, -1, 538, 540, 539, -1, 541, 542, 543, -1, 540, 542, 541, -1, 543, 544, 545, -1, 542, 544, 543, -1, 545, 546, 547, -1, 544, 546, 545, -1, 547, 548, 549, -1, 546, 548, 547, -1, 549, 550, 551, -1, 548, 550, 549, -1, 551, 552, 553, -1, 550, 552, 551, -1, 553, 554, 555, -1, 552, 554, 553, -1, 555, 556, 557, -1, 554, 556, 555, -1, 557, 558, 559, -1, 556, 558, 557, -1, 560, 561, 562, -1, 562, 561, 563, -1, 563, 564, 565, -1, 561, 564, 563, -1, 565, 566, 567, -1, 564, 566, 565, -1, 567, 568, 569, -1, 566, 568, 567, -1, 569, 570, 571, -1, 568, 570, 569, -1, 571, 572, 573, -1, 570, 572, 571, -1, 573, 574, 575, -1, 572, 574, 573, -1, 575, 576, 577, -1, 574, 576, 575, -1, 577, 578, 579, -1, 576, 578, 577, -1, 579, 580, 581, -1, 578, 580, 579, -1, 581, 582, 583, -1, 580, 582, 581, -1, 583, 584, 585, -1, 582, 584, 583, -1, 585, 586, 587, -1, 584, 586, 585, -1, 588, 589, 590, -1, 590, 589, 591, -1, 591, 592, 593, -1, 589, 592, 591, -1, 593, 594, 595, -1, 592, 594, 593, -1, 595, 596, 597, -1, 594, 596, 595, -1, 597, 598, 599, -1, 596, 598, 597, -1, 599, 600, 601, -1, 598, 600, 599, -1, 601, 602, 603, -1, 600, 602, 601, -1, 603, 604, 605, -1, 602, 604, 603, -1, 605, 606, 607, -1, 604, 606, 605, -1, 607, 608, 609, -1, 606, 608, 607, -1, 609, 610, 611, -1, 608, 610, 609, -1, 611, 612, 613, -1, 610, 612, 611, -1, 613, 614, 615, -1, 612, 614, 613, -1, 616, 617, 618, -1, 618, 617, 619, -1, 619, 620, 621, -1, 617, 620, 619, -1, 621, 622, 623, -1, 620, 622, 621, -1, 623, 624, 625, -1, 622, 624, 623, -1, 625, 626, 627, -1, 624, 626, 625, -1, 627, 628, 629, -1, 626, 628, 627, -1, 629, 630, 631, -1, 628, 630, 629, -1, 631, 632, 633, -1, 630, 632, 631, -1, 633, 634, 635, -1, 632, 634, 633, -1, 635, 636, 637, -1, 634, 636, 635, -1, 637, 638, 639, -1, 636, 638, 637, -1, 639, 640, 641, -1, 638, 640, 639, -1, 641, 642, 643, -1, 640, 642, 641, -1, 644, 645, 646, -1, 646, 645, 647, -1, 647, 648, 649, -1, 645, 648, 647, -1, 649, 650, 651, -1, 648, 650, 649, -1, 651, 652, 653, -1, 650, 652, 651, -1, 653, 654, 655, -1, 652, 654, 653, -1, 655, 656, 657, -1, 654, 656, 655, -1, 657, 658, 659, -1, 656, 658, 657, -1, 659, 660, 661, -1, 658, 660, 659, -1, 661, 662, 663, -1, 660, 662, 661, -1, 663, 664, 665, -1, 662, 664, 663, -1, 665, 666, 667, -1, 664, 666, 665, -1, 667, 668, 669, -1, 666, 668, 667, -1, 669, 670, 671, -1, 668, 670, 669, -1, 672, 673, 674, -1, 674, 673, 675, -1, 675, 676, 677, -1, 673, 676, 675, -1, 677, 678, 679, -1, 676, 678, 677, -1, 679, 680, 681, -1, 678, 680, 679, -1, 681, 682, 683, -1, 680, 682, 681, -1, 683, 684, 685, -1, 682, 684, 683, -1, 685, 686, 687, -1, 684, 686, 685, -1, 687, 688, 689, -1, 686, 688, 687, -1, 689, 690, 691, -1, 688, 690, 689, -1, 691, 692, 693, -1, 690, 692, 691, -1, 693, 694, 695, -1, 692, 694, 693, -1, 695, 696, 697, -1, 694, 696, 695, -1, 697, 698, 699, -1, 696, 698, 697, -1, 700, 701, 702, -1, 702, 701, 703, -1, 703, 704, 705, -1, 701, 704, 703, -1, 705, 706, 707, -1, 704, 706, 705, -1, 707, 708, 709, -1, 706, 708, 707, -1, 709, 710, 711, -1, 708, 710, 709, -1, 711, 712, 713, -1, 710, 712, 711, -1, 713, 714, 715, -1, 712, 714, 713, -1, 715, 716, 717, -1, 714, 716, 715, -1, 717, 718, 719, -1, 716, 718, 717, -1, 719, 720, 721, -1, 718, 720, 719, -1, 721, 722, 723, -1, 720, 722, 721, -1, 723, 724, 725, -1, 722, 724, 723, -1, 725, 726, 727, -1, 724, 726, 725, -1, 728, 729, 730, -1, 730, 729, 731, -1, 731, 732, 733, -1, 729, 732, 731, -1, 733, 734, 735, -1, 732, 734, 733, -1, 735, 736, 737, -1, 734, 736, 735, -1, 737, 738, 739, -1, 736, 738, 737, -1, 739, 740, 741, -1, 738, 740, 739, -1, 741, 742, 743, -1, 740, 742, 741, -1, 743, 744, 745, -1, 742, 744, 743, -1, 745, 746, 747, -1, 744, 746, 745, -1, 747, 748, 749, -1, 746, 748, 747, -1, 749, 750, 751, -1, 748, 750, 749, -1, 751, 752, 753, -1, 750, 752, 751, -1, 753, 754, 755, -1, 752, 754, 753, -1, 756, 757, 758, -1, 758, 757, 759, -1, 759, 760, 761, -1, 757, 760, 759, -1, 761, 762, 763, -1, 760, 762, 761, -1, 763, 764, 765, -1, 762, 764, 763, -1, 765, 766, 767, -1, 764, 766, 765, -1, 767, 768, 769, -1, 766, 768, 767, -1, 769, 770, 771, -1, 768, 770, 769, -1, 771, 772, 773, -1, 770, 772, 771, -1, 773, 774, 775, -1, 772, 774, 773, -1, 775, 776, 777, -1, 774, 776, 775, -1, 777, 778, 779, -1, 776, 778, 777, -1, 779, 780, 781, -1, 778, 780, 779, -1, 781, 782, 783, -1, 780, 782, 781, -1, 784, 785, 786, -1, 786, 785, 787, -1, 787, 788, 789, -1, 785, 788, 787, -1, 789, 790, 791, -1, 788, 790, 789, -1, 791, 792, 793, -1, 790, 792, 791, -1, 793, 794, 795, -1, 792, 794, 793, -1, 795, 796, 797, -1, 794, 796, 795, -1, 797, 798, 799, -1, 796, 798, 797, -1, 799, 800, 801, -1, 798, 800, 799, -1, 801, 802, 803, -1, 800, 802, 801, -1, 803, 804, 805, -1, 802, 804, 803, -1, 805, 806, 807, -1, 804, 806, 805, -1, 807, 808, 809, -1, 806, 808, 807, -1, 809, 810, 811, -1, 808, 810, 809, -1, 812, 813, 814, -1, 815, 813, 812, -1, 816, 817, 818, -1, 819, 817, 816, -1, 820, 821, 822, -1, 823, 821, 820, -1, 824, 825, 826, -1, 827, 825, 824, -1, 810, 828, 811, -1, 811, 828, 829, -1, 829, 830, 831, -1, 828, 830, 829, -1, 831, 832, 833, -1, 830, 832, 831, -1, 833, 834, 835, -1, 832, 834, 833, -1, 835, 836, 837, -1, 834, 836, 835, -1, 837, 838, 839, -1, 836, 838, 837, -1, 839, 840, 841, -1, 838, 840, 839, -1, 841, 842, 843, -1, 840, 842, 841, -1, 843, 844, 845, -1, 842, 844, 843, -1, 845, 846, 847, -1, 844, 846, 845, -1, 847, 848, 849, -1, 846, 848, 847, -1, 849, 850, 851, -1, 848, 850, 849, -1, 851, 784, 786, -1, 850, 784, 851, -1, 782, 852, 783, -1, 783, 852, 853, -1, 853, 854, 855, -1, 852, 854, 853, -1, 855, 856, 857, -1, 854, 856, 855, -1, 857, 858, 859, -1, 856, 858, 857, -1, 859, 860, 861, -1, 858, 860, 859, -1, 861, 862, 863, -1, 860, 862, 861, -1, 863, 864, 865, -1, 862, 864, 863, -1, 865, 866, 867, -1, 864, 866, 865, -1, 867, 868, 869, -1, 866, 868, 867, -1, 869, 870, 871, -1, 868, 870, 869, -1, 871, 872, 873, -1, 870, 872, 871, -1, 873, 874, 875, -1, 872, 874, 873, -1, 875, 756, 758, -1, 874, 756, 875, -1, 754, 876, 755, -1, 755, 876, 877, -1, 877, 878, 879, -1, 876, 878, 877, -1, 879, 880, 881, -1, 878, 880, 879, -1, 881, 882, 883, -1, 880, 882, 881, -1, 883, 884, 885, -1, 882, 884, 883, -1, 885, 886, 887, -1, 884, 886, 885, -1, 887, 888, 889, -1, 886, 888, 887, -1, 889, 890, 891, -1, 888, 890, 889, -1, 891, 892, 893, -1, 890, 892, 891, -1, 893, 894, 895, -1, 892, 894, 893, -1, 895, 896, 897, -1, 894, 896, 895, -1, 897, 898, 899, -1, 896, 898, 897, -1, 899, 728, 730, -1, 898, 728, 899, -1, 726, 900, 727, -1, 727, 900, 901, -1, 901, 902, 903, -1, 900, 902, 901, -1, 903, 904, 905, -1, 902, 904, 903, -1, 905, 906, 907, -1, 904, 906, 905, -1, 907, 908, 909, -1, 906, 908, 907, -1, 909, 910, 911, -1, 908, 910, 909, -1, 911, 912, 913, -1, 910, 912, 911, -1, 913, 914, 915, -1, 912, 914, 913, -1, 915, 916, 917, -1, 914, 916, 915, -1, 917, 918, 919, -1, 916, 918, 917, -1, 919, 920, 921, -1, 918, 920, 919, -1, 921, 922, 923, -1, 920, 922, 921, -1, 923, 700, 702, -1, 922, 700, 923, -1, 698, 924, 699, -1, 699, 924, 925, -1, 925, 926, 927, -1, 924, 926, 925, -1, 927, 928, 929, -1, 926, 928, 927, -1, 929, 930, 931, -1, 928, 930, 929, -1, 931, 932, 933, -1, 930, 932, 931, -1, 933, 934, 935, -1, 932, 934, 933, -1, 935, 936, 937, -1, 934, 936, 935, -1, 937, 938, 939, -1, 936, 938, 937, -1, 939, 940, 941, -1, 938, 940, 939, -1, 941, 942, 943, -1, 940, 942, 941, -1, 943, 944, 945, -1, 942, 944, 943, -1, 945, 946, 947, -1, 944, 946, 945, -1, 947, 672, 674, -1, 946, 672, 947, -1, 948, 949, 587, -1, 270, 950, 951, -1, 456, 454, 952, -1, 948, 953, 949, -1, 571, 573, 954, -1, 776, 774, 834, -1, 452, 955, 956, -1, 776, 834, 832, -1, 452, 956, 454, -1, 272, 270, 951, -1, 458, 456, 952, -1, 571, 954, 957, -1, 272, 951, 958, -1, 959, 953, 948, -1, 458, 952, 960, -1, 961, 962, 963, -1, 961, 963, 964, -1, 961, 964, 965, -1, 569, 571, 957, -1, 961, 965, 966, -1, 449, 955, 452, -1, 961, 966, 967, -1, 961, 967, 813, -1, 449, 968, 955, -1, 274, 272, 958, -1, 274, 969, 970, -1, 971, 972, 973, -1, 274, 958, 969, -1, 569, 957, 974, -1, 460, 458, 960, -1, 971, 973, 975, -1, 460, 960, 976, -1, 448, 977, 968, -1, 567, 569, 974, -1, 276, 274, 970, -1, 448, 968, 449, -1, 567, 974, 978, -1, 462, 460, 976, -1, 979, 980, 981, -1, 462, 976, 982, -1, 983, 984, 985, -1, 983, 985, 980, -1, 565, 567, 978, -1, 983, 980, 979, -1, 986, 987, 977, -1, 565, 978, 988, -1, 989, 815, 984, -1, 986, 977, 448, -1, 464, 990, 991, -1, 989, 984, 983, -1, 464, 982, 990, -1, 992, 813, 815, -1, 464, 462, 982, -1, 993, 994, 995, -1, 992, 815, 989, -1, 996, 972, 971, -1, 997, 813, 992, -1, 563, 988, 998, -1, 563, 565, 988, -1, 999, 993, 995, -1, 466, 991, 1000, -1, 466, 464, 991, -1, 999, 1001, 1002, -1, 562, 563, 998, -1, 999, 995, 1001, -1, 562, 998, 590, -1, 562, 590, 996, -1, 90, 1003, 1004, -1, 468, 466, 1000, -1, 468, 1000, 1005, -1, 1006, 994, 993, -1, 1006, 1007, 994, -1, 1008, 1009, 1010, -1, 470, 1005, 1011, -1, 92, 90, 1004, -1, 470, 468, 1005, -1, 1012, 999, 1002, -1, 88, 1013, 1003, -1, 1012, 1002, 1014, -1, 88, 1003, 90, -1, 1015, 1007, 1006, -1, 1015, 1016, 1007, -1, 94, 1004, 1017, -1, 94, 92, 1004, -1, 1018, 1012, 1014, -1, 1018, 1014, 1019, -1, 1020, 1021, 1022, -1, 85, 808, 1013, -1, 1020, 1022, 1009, -1, 1020, 1008, 1023, -1, 680, 1024, 1025, -1, 1020, 1023, 817, -1, 85, 1013, 88, -1, 1020, 1009, 1008, -1, 1026, 1016, 1015, -1, 680, 678, 1024, -1, 1027, 1019, 446, -1, 96, 1017, 1028, -1, 96, 94, 1017, -1, 676, 1029, 1024, -1, 1027, 1018, 1019, -1, 84, 810, 808, -1, 676, 1024, 678, -1, 682, 1025, 1030, -1, 84, 828, 810, -1, 682, 680, 1025, -1, 84, 808, 85, -1, 98, 1028, 1031, -1, 98, 96, 1028, -1, 98, 1031, 972, -1, 512, 510, 961, -1, 673, 1032, 1029, -1, 673, 1029, 676, -1, 508, 961, 510, -1, 514, 961, 813, -1, 232, 230, 384, -1, 684, 1030, 912, -1, 232, 384, 382, -1, 286, 1033, 1034, -1, 1035, 828, 84, -1, 232, 382, 817, -1, 228, 384, 230, -1, 514, 512, 961, -1, 100, 98, 972, -1, 100, 972, 996, -1, 684, 682, 1030, -1, 228, 386, 384, -1, 228, 388, 386, -1, 1036, 1020, 817, -1, 672, 1032, 673, -1, 505, 961, 508, -1, 288, 1034, 1037, -1, 288, 286, 1034, -1, 1038, 830, 828, -1, 234, 232, 817, -1, 1038, 828, 1035, -1, 516, 997, 1039, -1, 686, 912, 910, -1, 516, 813, 997, -1, 284, 442, 1033, -1, 686, 684, 912, -1, 516, 514, 813, -1, 284, 1033, 286, -1, 102, 100, 996, -1, 284, 444, 442, -1, 225, 388, 228, -1, 225, 390, 388, -1, 504, 961, 505, -1, 946, 1040, 1032, -1, 1041, 832, 830, -1, 236, 234, 817, -1, 946, 1032, 672, -1, 1041, 830, 1038, -1, 518, 1039, 1042, -1, 104, 102, 996, -1, 290, 1037, 1043, -1, 518, 516, 1039, -1, 290, 288, 1037, -1, 1044, 1016, 1026, -1, 688, 910, 908, -1, 224, 390, 225, -1, 688, 686, 910, -1, 1045, 1044, 1026, -1, 819, 240, 238, -1, 1046, 961, 504, -1, 238, 236, 817, -1, 819, 238, 817, -1, 819, 1047, 240, -1, 944, 1048, 1040, -1, 106, 104, 996, -1, 944, 1040, 946, -1, 1049, 1050, 390, -1, 520, 1042, 1051, -1, 1049, 1052, 1050, -1, 281, 444, 284, -1, 520, 518, 1042, -1, 1049, 390, 224, -1, 690, 908, 906, -1, 690, 688, 908, -1, 942, 1053, 1048, -1, 942, 1048, 944, -1, 1054, 1055, 1056, -1, 292, 1043, 1057, -1, 1054, 160, 158, -1, 1058, 358, 1052, -1, 292, 290, 1043, -1, 1054, 1059, 194, -1, 692, 906, 904, -1, 1054, 1060, 1059, -1, 1054, 1061, 1060, -1, 522, 520, 1051, -1, 1058, 1052, 1049, -1, 1054, 1062, 1061, -1, 692, 690, 906, -1, 1054, 190, 1055, -1, 1054, 192, 190, -1, 1063, 1044, 1045, -1, 1054, 194, 192, -1, 1054, 158, 1062, -1, 1064, 1065, 1044, -1, 940, 1053, 942, -1, 108, 106, 996, -1, 1066, 1044, 1063, -1, 110, 108, 996, -1, 280, 1027, 446, -1, 280, 446, 444, -1, 280, 1067, 1027, -1, 280, 444, 281, -1, 1068, 1064, 1044, -1, 1069, 110, 996, -1, 1070, 1044, 1066, -1, 1070, 1068, 1044, -1, 524, 1051, 1071, -1, 1072, 819, 1073, -1, 524, 522, 1051, -1, 294, 292, 1057, -1, 526, 524, 1071, -1, 526, 1071, 1074, -1, 294, 1057, 1075, -1, 1076, 1067, 280, -1, 1077, 162, 160, -1, 1078, 819, 1072, -1, 528, 1074, 1079, -1, 528, 526, 1074, -1, 1077, 160, 1054, -1, 530, 528, 1079, -1, 296, 294, 1075, -1, 1080, 164, 162, -1, 1080, 162, 1077, -1, 296, 1075, 1081, -1, 34, 720, 1082, -1, 1083, 819, 1078, -1, 1084, 166, 164, -1, 1084, 164, 1080, -1, 1085, 1067, 1076, -1, 1085, 1086, 1067, -1, 1087, 1088, 166, -1, 1087, 1089, 1088, -1, 1087, 166, 1084, -1, 1090, 819, 1083, -1, 36, 34, 1082, -1, 1091, 1092, 1089, -1, 298, 296, 1081, -1, 1091, 1089, 1087, -1, 36, 1082, 1093, -1, 32, 720, 34, -1, 298, 1081, 1094, -1, 1095, 1096, 1092, -1, 32, 722, 720, -1, 482, 1097, 1098, -1, 32, 724, 722, -1, 1095, 1092, 1091, -1, 400, 398, 1099, -1, 1100, 1086, 1085, -1, 38, 953, 959, -1, 1100, 1101, 1086, -1, 1102, 1090, 1103, -1, 38, 36, 1093, -1, 1104, 1105, 1096, -1, 484, 1098, 1106, -1, 484, 482, 1098, -1, 1102, 819, 1090, -1, 1104, 1096, 1095, -1, 400, 1099, 1107, -1, 480, 1046, 1097, -1, 38, 959, 1108, -1, 480, 1097, 482, -1, 396, 554, 1109, -1, 300, 298, 1094, -1, 38, 1093, 953, -1, 396, 1099, 398, -1, 734, 872, 870, -1, 300, 1094, 1110, -1, 396, 556, 554, -1, 486, 1106, 1111, -1, 29, 724, 32, -1, 486, 484, 1106, -1, 396, 1109, 1099, -1, 1112, 1101, 1100, -1, 477, 961, 1046, -1, 402, 400, 1107, -1, 477, 1046, 480, -1, 40, 38, 1108, -1, 302, 300, 1110, -1, 302, 1110, 1113, -1, 402, 1107, 1114, -1, 736, 870, 868, -1, 736, 734, 870, -1, 488, 1111, 1115, -1, 40, 1108, 1116, -1, 488, 486, 1111, -1, 28, 724, 29, -1, 393, 556, 396, -1, 732, 874, 872, -1, 1117, 1101, 1112, -1, 732, 872, 734, -1, 1117, 1112, 1118, -1, 393, 558, 556, -1, 28, 726, 724, -1, 404, 402, 1114, -1, 490, 1115, 1119, -1, 490, 488, 1115, -1, 738, 868, 866, -1, 404, 1114, 1120, -1, 738, 736, 868, -1, 42, 1116, 1121, -1, 392, 1122, 558, -1, 42, 40, 1116, -1, 1123, 726, 28, -1, 392, 558, 393, -1, 1123, 900, 726, -1, 1123, 902, 900, -1, 492, 1119, 1124, -1, 492, 490, 1119, -1, 729, 874, 732, -1, 406, 404, 1120, -1, 44, 42, 1121, -1, 729, 1125, 874, -1, 406, 1120, 1126, -1, 740, 866, 864, -1, 1127, 1122, 392, -1, 44, 1121, 1128, -1, 740, 738, 866, -1, 494, 1124, 1129, -1, 494, 492, 1124, -1, 1127, 1011, 1122, -1, 1130, 902, 1123, -1, 408, 406, 1126, -1, 46, 44, 1128, -1, 496, 1129, 1131, -1, 742, 864, 862, -1, 742, 740, 864, -1, 496, 494, 1129, -1, 408, 1126, 1132, -1, 1133, 1011, 1127, -1, 1134, 1117, 1118, -1, 1135, 902, 1130, -1, 1134, 1118, 1136, -1, 1135, 904, 902, -1, 498, 496, 1131, -1, 498, 1131, 1137, -1, 1138, 819, 1102, -1, 744, 862, 860, -1, 410, 408, 1132, -1, 744, 742, 862, -1, 410, 1132, 1139, -1, 48, 1128, 1140, -1, 1141, 1134, 1136, -1, 48, 46, 1128, -1, 1141, 1136, 1142, -1, 746, 860, 858, -1, 746, 744, 860, -1, 50, 1140, 1143, -1, 412, 1139, 1144, -1, 1145, 1047, 819, -1, 50, 48, 1140, -1, 412, 410, 1139, -1, 748, 858, 856, -1, 748, 746, 858, -1, 52, 1143, 1146, -1, 414, 412, 1144, -1, 52, 50, 1143, -1, 414, 1144, 1147, -1, 54, 1146, 1148, -1, 54, 52, 1146, -1, 1149, 54, 1148, -1, 1149, 1148, 1150, -1, 637, 477, 476, -1, 635, 637, 476, -1, 635, 476, 1151, -1, 639, 477, 637, -1, 639, 961, 477, -1, 1152, 1153, 1154, -1, 633, 635, 1151, -1, 1152, 1154, 1155, -1, 6, 904, 1135, -1, 633, 1151, 1156, -1, 641, 961, 639, -1, 1157, 1152, 1155, -1, 6, 692, 904, -1, 631, 633, 1156, -1, 8, 1135, 1158, -1, 631, 1156, 1159, -1, 8, 6, 1135, -1, 643, 961, 641, -1, 629, 631, 1159, -1, 4, 692, 6, -1, 62, 778, 776, -1, 4, 694, 692, -1, 428, 1160, 1161, -1, 4, 696, 694, -1, 629, 1162, 1163, -1, 62, 776, 832, -1, 629, 1159, 1162, -1, 10, 1158, 1164, -1, 428, 426, 1160, -1, 10, 8, 1158, -1, 424, 1165, 1160, -1, 424, 986, 1165, -1, 1166, 1167, 1168, -1, 62, 832, 1041, -1, 627, 1163, 1169, -1, 627, 629, 1163, -1, 424, 1160, 426, -1, 430, 1161, 1170, -1, 430, 428, 1161, -1, 1, 696, 4, -1, 1171, 1172, 1157, -1, 1171, 1157, 1155, -1, 64, 1041, 1173, -1, 64, 62, 1041, -1, 625, 1169, 1174, -1, 12, 1164, 1175, -1, 625, 627, 1169, -1, 421, 986, 424, -1, 12, 10, 1164, -1, 1176, 1167, 1166, -1, 60, 778, 62, -1, 1177, 1167, 1176, -1, 623, 625, 1174, -1, 623, 1174, 1178, -1, 1177, 1179, 1180, -1, 1177, 1180, 1167, -1, 432, 430, 1170, -1, 0, 696, 1, -1, 0, 698, 696, -1, 1181, 1177, 1176, -1, 432, 1170, 1182, -1, 66, 1173, 1183, -1, 66, 64, 1173, -1, 14, 1175, 1184, -1, 823, 1171, 1155, -1, 823, 1185, 1186, -1, 823, 1142, 1185, -1, 57, 780, 778, -1, 823, 1141, 1142, -1, 14, 12, 1175, -1, 57, 782, 780, -1, 434, 432, 1182, -1, 1187, 698, 0, -1, 823, 1155, 1141, -1, 370, 1188, 1189, -1, 1187, 924, 698, -1, 57, 778, 60, -1, 434, 1182, 1190, -1, 16, 1184, 1191, -1, 68, 66, 1183, -1, 372, 1189, 1192, -1, 372, 370, 1189, -1, 16, 14, 1184, -1, 68, 1183, 1193, -1, 436, 434, 1190, -1, 368, 1194, 1188, -1, 56, 852, 782, -1, 436, 1190, 1195, -1, 368, 1188, 370, -1, 374, 1192, 1196, -1, 18, 1191, 1197, -1, 56, 782, 57, -1, 18, 16, 1191, -1, 70, 68, 1193, -1, 374, 372, 1192, -1, 438, 436, 1195, -1, 174, 1198, 1199, -1, 621, 623, 1178, -1, 70, 1193, 1200, -1, 438, 1195, 1201, -1, 1202, 852, 56, -1, 1202, 854, 852, -1, 365, 1194, 368, -1, 440, 438, 1201, -1, 1203, 934, 932, -1, 72, 70, 1200, -1, 440, 1201, 1204, -1, 176, 1199, 1205, -1, 376, 1196, 1036, -1, 176, 174, 1199, -1, 72, 1200, 1206, -1, 376, 374, 1196, -1, 172, 1198, 174, -1, 172, 330, 1198, -1, 1207, 932, 930, -1, 1207, 1203, 932, -1, 442, 440, 1204, -1, 1208, 854, 1202, -1, 20, 1197, 1209, -1, 364, 1079, 1194, -1, 364, 530, 1079, -1, 442, 1204, 1210, -1, 172, 332, 330, -1, 20, 18, 1197, -1, 74, 72, 1206, -1, 364, 1194, 365, -1, 378, 1036, 817, -1, 74, 1206, 1211, -1, 178, 1205, 1212, -1, 1213, 854, 1208, -1, 1214, 936, 934, -1, 1213, 856, 854, -1, 178, 176, 1205, -1, 1214, 938, 936, -1, 378, 376, 1036, -1, 1214, 934, 1203, -1, 169, 332, 172, -1, 76, 74, 1211, -1, 1215, 930, 928, -1, 169, 334, 332, -1, 1216, 1217, 530, -1, 1216, 1137, 1217, -1, 1215, 1207, 930, -1, 76, 1211, 1218, -1, 1216, 530, 364, -1, 180, 1212, 1219, -1, 22, 1209, 1220, -1, 180, 178, 1212, -1, 22, 20, 1209, -1, 78, 76, 1218, -1, 168, 334, 169, -1, 1221, 938, 1214, -1, 78, 1218, 1222, -1, 380, 378, 817, -1, 168, 1223, 334, -1, 1221, 940, 938, -1, 80, 1069, 996, -1, 80, 78, 1222, -1, 24, 1220, 1149, -1, 1224, 1137, 1216, -1, 80, 1222, 1069, -1, 182, 1219, 1225, -1, 24, 22, 1220, -1, 182, 180, 1219, -1, 1226, 926, 924, -1, 1226, 928, 926, -1, 382, 380, 817, -1, 1227, 1223, 168, -1, 202, 1058, 1228, -1, 1226, 1215, 928, -1, 1227, 1113, 1223, -1, 204, 202, 1228, -1, 204, 1228, 1229, -1, 200, 360, 358, -1, 200, 358, 1058, -1, 1230, 1177, 1181, -1, 1231, 940, 1221, -1, 200, 1058, 202, -1, 184, 1225, 1232, -1, 184, 182, 1225, -1, 206, 204, 1229, -1, 1233, 1113, 1227, -1, 206, 1229, 1234, -1, 1235, 961, 643, -1, 1233, 302, 1113, -1, 1235, 643, 671, -1, 1235, 987, 986, -1, 1235, 1236, 1237, -1, 706, 896, 894, -1, 1235, 1238, 1236, -1, 1235, 1239, 987, -1, 1235, 1240, 1238, -1, 1235, 671, 1239, -1, 1235, 1241, 1240, -1, 1235, 420, 1241, -1, 186, 1232, 1242, -1, 1235, 421, 420, -1, 708, 706, 894, -1, 1235, 986, 421, -1, 197, 362, 360, -1, 197, 360, 200, -1, 186, 184, 1232, -1, 1243, 1226, 924, -1, 708, 894, 892, -1, 1243, 924, 1187, -1, 704, 896, 706, -1, 704, 898, 896, -1, 208, 206, 1234, -1, 1243, 1187, 1244, -1, 1245, 1243, 1244, -1, 710, 708, 892, -1, 188, 1242, 1246, -1, 208, 1234, 1247, -1, 196, 362, 197, -1, 710, 892, 890, -1, 188, 186, 1242, -1, 1245, 1244, 1248, -1, 1249, 1245, 1248, -1, 701, 898, 704, -1, 196, 1250, 362, -1, 1249, 1251, 1252, -1, 1249, 1248, 1251, -1, 712, 710, 890, -1, 210, 208, 1247, -1, 712, 890, 888, -1, 210, 1247, 1253, -1, 821, 1104, 1053, -1, 821, 1254, 1105, -1, 821, 823, 1254, -1, 821, 1105, 1104, -1, 821, 1231, 1255, -1, 821, 1053, 940, -1, 821, 940, 1231, -1, 1256, 1147, 1250, -1, 1256, 1250, 196, -1, 714, 712, 888, -1, 790, 1257, 1145, -1, 714, 888, 886, -1, 1258, 1255, 1259, -1, 665, 1260, 1261, -1, 212, 1253, 1262, -1, 212, 210, 1253, -1, 1263, 1264, 821, -1, 190, 1246, 1055, -1, 190, 188, 1246, -1, 1265, 1255, 1258, -1, 1265, 1263, 821, -1, 1265, 821, 1255, -1, 716, 886, 884, -1, 716, 714, 886, -1, 1266, 1263, 1265, -1, 663, 1261, 1267, -1, 1268, 1249, 1252, -1, 792, 1138, 1269, -1, 1270, 414, 1147, -1, 718, 716, 884, -1, 663, 665, 1261, -1, 792, 819, 1138, -1, 1270, 1147, 1256, -1, 792, 1145, 819, -1, 792, 790, 1145, -1, 1268, 1252, 1271, -1, 718, 882, 880, -1, 667, 1272, 1260, -1, 718, 884, 882, -1, 214, 1262, 1273, -1, 214, 212, 1262, -1, 1274, 1268, 1271, -1, 667, 1260, 665, -1, 788, 1275, 1257, -1, 788, 1257, 790, -1, 661, 663, 1267, -1, 720, 718, 880, -1, 1274, 1271, 1276, -1, 794, 1269, 1277, -1, 661, 1267, 1278, -1, 1279, 1274, 1276, -1, 794, 792, 1269, -1, 669, 1272, 667, -1, 659, 661, 1278, -1, 659, 1278, 1280, -1, 1281, 1282, 1235, -1, 671, 643, 1272, -1, 671, 1272, 669, -1, 785, 1283, 1275, -1, 785, 1275, 788, -1, 657, 659, 1280, -1, 657, 1280, 1284, -1, 796, 794, 1277, -1, 1285, 1286, 1287, -1, 1288, 1285, 1287, -1, 784, 1283, 785, -1, 1030, 914, 912, -1, 538, 1289, 1290, -1, 1030, 916, 914, -1, 1030, 918, 916, -1, 1030, 920, 918, -1, 1030, 922, 920, -1, 1030, 700, 922, -1, 1030, 701, 700, -1, 540, 538, 1290, -1, 1030, 898, 701, -1, 798, 1277, 1291, -1, 798, 796, 1277, -1, 536, 1289, 538, -1, 1292, 1293, 1288, -1, 536, 1294, 1289, -1, 850, 1295, 1283, -1, 850, 1283, 784, -1, 542, 540, 1290, -1, 1296, 1281, 1235, -1, 1297, 1288, 1287, -1, 1297, 1292, 1288, -1, 542, 1290, 1298, -1, 533, 1294, 536, -1, 827, 1297, 1287, -1, 827, 1287, 1299, -1, 533, 1300, 1294, -1, 118, 748, 856, -1, 1301, 26, 24, -1, 1301, 1302, 562, -1, 1301, 1150, 1302, -1, 1301, 1149, 1150, -1, 1301, 562, 996, -1, 118, 750, 748, -1, 1303, 248, 246, -1, 1303, 250, 248, -1, 118, 856, 1213, -1, 120, 118, 1213, -1, 544, 542, 1298, -1, 1301, 1304, 26, -1, 1301, 1305, 1304, -1, 1301, 1306, 1305, -1, 800, 1291, 1307, -1, 1301, 1308, 1306, -1, 1301, 1309, 1308, -1, 1301, 24, 1149, -1, 800, 798, 1291, -1, 544, 1298, 618, -1, 825, 1309, 1301, -1, 825, 1279, 1276, -1, 532, 657, 1284, -1, 120, 1213, 1310, -1, 825, 1299, 1279, -1, 825, 827, 1299, -1, 825, 1276, 1309, -1, 1311, 250, 1303, -1, 532, 655, 657, -1, 532, 1300, 533, -1, 532, 1284, 1300, -1, 1312, 825, 1301, -1, 1312, 1301, 1313, -1, 609, 1314, 1315, -1, 1311, 1316, 250, -1, 1317, 1318, 825, -1, 848, 1319, 1295, -1, 848, 1295, 850, -1, 546, 544, 618, -1, 1320, 825, 1312, -1, 1320, 1312, 1321, -1, 546, 618, 619, -1, 1322, 246, 244, -1, 1320, 1317, 825, -1, 1322, 1303, 246, -1, 1323, 655, 532, -1, 970, 1054, 278, -1, 116, 750, 118, -1, 278, 1054, 1056, -1, 802, 800, 1307, -1, 1323, 653, 655, -1, 970, 278, 276, -1, 1030, 1125, 728, -1, 607, 609, 1315, -1, 728, 1125, 729, -1, 1030, 728, 898, -1, 802, 1307, 1324, -1, 1325, 1316, 1311, -1, 607, 1315, 1326, -1, 846, 1319, 848, -1, 122, 120, 1310, -1, 1325, 1327, 1316, -1, 122, 1310, 1314, -1, 548, 621, 1178, -1, 1328, 244, 242, -1, 548, 546, 619, -1, 611, 122, 1314, -1, 804, 1324, 1329, -1, 548, 619, 621, -1, 804, 802, 1324, -1, 1328, 1322, 244, -1, 611, 1314, 609, -1, 113, 750, 116, -1, 844, 1330, 1319, -1, 844, 1319, 846, -1, 1331, 653, 1323, -1, 1332, 1327, 1325, -1, 1331, 651, 653, -1, 550, 548, 1178, -1, 113, 752, 750, -1, 113, 754, 752, -1, 806, 804, 1329, -1, 1332, 1333, 1327, -1, 550, 1178, 1334, -1, 605, 607, 1326, -1, 842, 1125, 1330, -1, 842, 1330, 844, -1, 970, 214, 1273, -1, 605, 1326, 1335, -1, 808, 1329, 1013, -1, 808, 806, 1329, -1, 970, 1333, 1332, -1, 970, 1336, 222, -1, 970, 969, 1336, -1, 1337, 651, 1331, -1, 970, 216, 214, -1, 970, 218, 216, -1, 840, 1125, 842, -1, 970, 220, 218, -1, 970, 222, 220, -1, 970, 1273, 1333, -1, 1047, 242, 240, -1, 649, 651, 1337, -1, 1047, 1328, 242, -1, 552, 1334, 1338, -1, 613, 124, 122, -1, 552, 550, 1334, -1, 1339, 1340, 1341, -1, 1339, 1341, 1296, -1, 613, 122, 611, -1, 112, 754, 113, -1, 1339, 1296, 1235, -1, 1342, 649, 1337, -1, 603, 605, 1335, -1, 554, 1338, 1343, -1, 603, 1344, 1345, -1, 554, 552, 1338, -1, 603, 1335, 1344, -1, 1346, 647, 649, -1, 1346, 649, 1342, -1, 615, 126, 124, -1, 615, 124, 613, -1, 1347, 754, 112, -1, 972, 1031, 1230, -1, 316, 1348, 1349, -1, 316, 314, 1348, -1, 1347, 876, 754, -1, 972, 1230, 1181, -1, 312, 472, 470, -1, 1347, 878, 876, -1, 312, 1133, 1348, -1, 312, 1348, 314, -1, 312, 1011, 1133, -1, 312, 470, 1011, -1, 1350, 972, 1351, -1, 601, 1345, 1352, -1, 1353, 646, 647, -1, 1353, 647, 1346, -1, 318, 316, 1349, -1, 601, 603, 1345, -1, 318, 1349, 1354, -1, 146, 1233, 1355, -1, 1016, 1235, 1237, -1, 1016, 1339, 1235, -1, 1016, 1237, 1007, -1, 309, 474, 472, -1, 1356, 1357, 646, -1, 1358, 878, 1347, -1, 309, 472, 312, -1, 1359, 128, 126, -1, 1356, 646, 1353, -1, 148, 1355, 1360, -1, 1359, 126, 615, -1, 148, 146, 1355, -1, 144, 302, 1233, -1, 144, 304, 302, -1, 320, 1354, 1361, -1, 320, 318, 1354, -1, 144, 1233, 146, -1, 308, 474, 309, -1, 991, 990, 1357, -1, 599, 1352, 1362, -1, 599, 601, 1352, -1, 150, 1360, 1363, -1, 150, 148, 1360, -1, 991, 1357, 1356, -1, 308, 1364, 474, -1, 322, 1361, 1365, -1, 141, 306, 304, -1, 141, 304, 144, -1, 1082, 878, 1358, -1, 1082, 880, 878, -1, 322, 320, 1361, -1, 1082, 720, 880, -1, 1366, 130, 128, -1, 152, 1363, 1367, -1, 1366, 128, 1359, -1, 1368, 1364, 308, -1, 152, 150, 1363, -1, 132, 130, 1366, -1, 140, 306, 141, -1, 140, 1369, 306, -1, 597, 599, 1362, -1, 1368, 1210, 1364, -1, 597, 1362, 82, -1, 154, 152, 1367, -1, 324, 1365, 1370, -1, 324, 322, 1365, -1, 154, 1367, 1371, -1, 1033, 442, 1210, -1, 1033, 1210, 1368, -1, 1372, 1369, 140, -1, 156, 154, 1371, -1, 342, 1224, 1373, -1, 1374, 134, 132, -1, 156, 1375, 1062, -1, 156, 1371, 1375, -1, 1374, 132, 1366, -1, 326, 1370, 1376, -1, 326, 324, 1370, -1, 1377, 972, 1350, -1, 344, 1373, 1378, -1, 344, 342, 1373, -1, 340, 1224, 342, -1, 1379, 1380, 1369, -1, 595, 82, 80, -1, 1379, 1381, 1380, -1, 328, 326, 1376, -1, 595, 597, 82, -1, 1379, 1369, 1372, -1, 328, 1376, 1382, -1, 340, 1137, 1224, -1, 340, 498, 1137, -1, 158, 156, 1062, -1, 1383, 136, 134, -1, 1383, 134, 1374, -1, 346, 1378, 1384, -1, 330, 328, 1382, -1, 1385, 1381, 1379, -1, 346, 344, 1378, -1, 330, 1382, 1386, -1, 337, 500, 498, -1, 337, 502, 500, -1, 337, 498, 340, -1, 1387, 1186, 1381, -1, 1387, 823, 1186, -1, 1387, 1381, 1385, -1, 593, 80, 996, -1, 593, 595, 80, -1, 348, 1384, 1388, -1, 348, 346, 1384, -1, 336, 502, 337, -1, 336, 1389, 502, -1, 350, 348, 1388, -1, 764, 762, 1125, -1, 350, 1388, 1390, -1, 760, 1125, 762, -1, 1391, 1343, 1389, -1, 1391, 1389, 336, -1, 1392, 138, 136, -1, 1392, 136, 1383, -1, 973, 972, 1377, -1, 352, 1390, 1393, -1, 766, 764, 1125, -1, 352, 350, 1390, -1, 591, 593, 996, -1, 1394, 823, 1387, -1, 1109, 1343, 1391, -1, 1395, 138, 1392, -1, 1109, 554, 1343, -1, 590, 591, 996, -1, 354, 1393, 1396, -1, 757, 1125, 760, -1, 354, 352, 1393, -1, 768, 1125, 840, -1, 768, 766, 1125, -1, 356, 354, 1396, -1, 258, 1270, 1397, -1, 356, 1396, 1398, -1, 260, 258, 1397, -1, 756, 1125, 757, -1, 260, 1397, 1399, -1, 256, 1270, 258, -1, 256, 414, 1270, -1, 358, 1398, 1052, -1, 1400, 823, 1394, -1, 770, 768, 840, -1, 256, 416, 414, -1, 358, 356, 1398, -1, 770, 840, 838, -1, 262, 260, 1399, -1, 581, 1401, 1402, -1, 874, 1125, 756, -1, 262, 1399, 1403, -1, 253, 416, 256, -1, 579, 581, 1402, -1, 579, 1402, 1404, -1, 1254, 823, 1400, -1, 253, 418, 416, -1, 583, 1401, 581, -1, 264, 262, 1403, -1, 583, 1405, 1401, -1, 583, 1406, 1405, -1, 772, 770, 838, -1, 577, 579, 1404, -1, 264, 1403, 1407, -1, 772, 838, 836, -1, 252, 418, 253, -1, 252, 1408, 418, -1, 577, 1404, 138, -1, 266, 264, 1407, -1, 585, 1406, 583, -1, 585, 1409, 1406, -1, 266, 1407, 1410, -1, 575, 577, 138, -1, 1411, 1408, 252, -1, 575, 138, 1395, -1, 268, 266, 1410, -1, 587, 1409, 585, -1, 587, 949, 1409, -1, 268, 1410, 950, -1, 454, 956, 952, -1, 1198, 1408, 1411, -1, 774, 772, 836, -1, 1198, 1386, 1408, -1, 573, 575, 1395, -1, 1198, 330, 1386, -1, 774, 836, 834, -1, 573, 1395, 954, -1, 270, 268, 950, -1, 1412, 271, 1413, -1, 269, 271, 1412, -1, 455, 457, 1414, -1, 572, 570, 1415, -1, 1416, 453, 1417, -1, 1417, 453, 455, -1, 1415, 570, 1418, -1, 835, 777, 833, -1, 1413, 273, 1419, -1, 271, 273, 1413, -1, 1420, 1421, 1422, -1, 775, 777, 835, -1, 1414, 459, 1423, -1, 457, 459, 1414, -1, 1424, 1425, 814, -1, 570, 568, 1418, -1, 1426, 1425, 1424, -1, 1427, 451, 1416, -1, 1428, 1425, 1426, -1, 1429, 1425, 1428, -1, 1430, 1425, 1429, -1, 1419, 275, 1431, -1, 1432, 1425, 1430, -1, 1416, 451, 453, -1, 1431, 275, 1433, -1, 273, 275, 1419, -1, 1418, 568, 1434, -1, 459, 461, 1423, -1, 1423, 461, 1435, -1, 568, 566, 1434, -1, 1436, 450, 1427, -1, 275, 277, 1433, -1, 1434, 566, 1437, -1, 1427, 450, 451, -1, 461, 463, 1435, -1, 1438, 1439, 1440, -1, 1435, 463, 1441, -1, 1442, 1443, 1438, -1, 1444, 1443, 1442, -1, 566, 564, 1437, -1, 1437, 564, 1445, -1, 1438, 1443, 1439, -1, 1446, 1447, 1436, -1, 812, 1448, 1444, -1, 1436, 1447, 450, -1, 1444, 1448, 1443, -1, 814, 1449, 812, -1, 1441, 465, 1450, -1, 812, 1449, 1448, -1, 1451, 1452, 1453, -1, 564, 561, 1445, -1, 463, 465, 1441, -1, 1450, 465, 1454, -1, 814, 1455, 1449, -1, 1445, 561, 1456, -1, 1457, 1458, 1459, -1, 1459, 1458, 1460, -1, 1454, 467, 1461, -1, 561, 560, 1456, -1, 1462, 1463, 1464, -1, 1456, 560, 588, -1, 465, 467, 1454, -1, 588, 560, 1458, -1, 1453, 1463, 1462, -1, 1452, 1463, 1453, -1, 1461, 469, 1465, -1, 1466, 91, 1467, -1, 467, 469, 1461, -1, 1451, 1468, 1452, -1, 1469, 1468, 1451, -1, 1465, 471, 1470, -1, 469, 471, 1465, -1, 1471, 1472, 1473, -1, 91, 93, 1467, -1, 1474, 89, 1466, -1, 1464, 1475, 1476, -1, 1466, 89, 91, -1, 1463, 1475, 1464, -1, 1469, 1477, 1468, -1, 1478, 1477, 1469, -1, 1467, 95, 1479, -1, 1476, 1480, 1481, -1, 93, 95, 1467, -1, 1471, 1482, 1472, -1, 679, 681, 1483, -1, 1484, 1482, 818, -1, 1483, 681, 1485, -1, 1472, 1482, 1484, -1, 1486, 1482, 1471, -1, 1487, 1482, 1486, -1, 809, 87, 1474, -1, 1475, 1480, 1476, -1, 1478, 1488, 1477, -1, 1481, 1489, 447, -1, 1483, 677, 679, -1, 1490, 677, 1483, -1, 1474, 87, 89, -1, 1479, 97, 1491, -1, 95, 97, 1479, -1, 1480, 1489, 1481, -1, 1485, 683, 1492, -1, 829, 86, 811, -1, 681, 683, 1485, -1, 809, 86, 87, -1, 811, 86, 809, -1, 1490, 675, 677, -1, 1493, 675, 1490, -1, 1491, 99, 1494, -1, 511, 513, 1425, -1, 97, 99, 1491, -1, 1425, 509, 511, -1, 1494, 99, 1457, -1, 231, 233, 385, -1, 1495, 287, 1496, -1, 683, 685, 1492, -1, 829, 1497, 86, -1, 1492, 685, 913, -1, 383, 233, 818, -1, 1425, 515, 814, -1, 385, 233, 383, -1, 385, 229, 231, -1, 513, 515, 1425, -1, 1493, 674, 675, -1, 1457, 101, 1458, -1, 1482, 1498, 818, -1, 99, 101, 1457, -1, 387, 229, 385, -1, 1496, 289, 1499, -1, 831, 1500, 829, -1, 1425, 507, 509, -1, 389, 229, 387, -1, 287, 289, 1496, -1, 233, 235, 818, -1, 829, 1500, 1497, -1, 685, 687, 913, -1, 515, 517, 814, -1, 389, 227, 229, -1, 1455, 517, 1501, -1, 443, 285, 1495, -1, 913, 687, 911, -1, 814, 517, 1455, -1, 445, 285, 443, -1, 1425, 506, 507, -1, 101, 103, 1458, -1, 1502, 947, 1493, -1, 1495, 285, 287, -1, 391, 227, 389, -1, 833, 1503, 831, -1, 1493, 947, 674, -1, 831, 1503, 1500, -1, 1501, 519, 1504, -1, 235, 237, 818, -1, 1499, 291, 1505, -1, 517, 519, 1501, -1, 391, 226, 227, -1, 289, 291, 1499, -1, 687, 689, 911, -1, 103, 105, 1458, -1, 1478, 1506, 1488, -1, 911, 689, 909, -1, 1507, 945, 1502, -1, 1425, 1508, 506, -1, 237, 239, 818, -1, 1506, 1509, 1488, -1, 239, 816, 818, -1, 1502, 945, 947, -1, 1510, 816, 241, -1, 241, 816, 239, -1, 1504, 521, 1511, -1, 519, 521, 1504, -1, 105, 107, 1458, -1, 909, 691, 907, -1, 445, 283, 285, -1, 689, 691, 909, -1, 391, 1512, 226, -1, 1513, 1512, 391, -1, 1514, 1512, 1513, -1, 1515, 943, 1507, -1, 193, 1516, 191, -1, 1507, 943, 945, -1, 195, 1516, 193, -1, 1505, 293, 1517, -1, 191, 1516, 1518, -1, 1514, 1519, 1512, -1, 291, 293, 1505, -1, 907, 693, 905, -1, 691, 693, 907, -1, 1518, 1516, 1520, -1, 359, 1519, 1514, -1, 521, 523, 1511, -1, 159, 1516, 1521, -1, 161, 1516, 159, -1, 1506, 1522, 1509, -1, 1515, 941, 943, -1, 1523, 1516, 195, -1, 1524, 1516, 1523, -1, 1525, 1516, 1524, -1, 1521, 1516, 1525, -1, 107, 109, 1458, -1, 1526, 1527, 1506, -1, 447, 282, 445, -1, 1528, 282, 1489, -1, 109, 111, 1458, -1, 1489, 282, 447, -1, 1511, 525, 1529, -1, 445, 282, 283, -1, 523, 525, 1511, -1, 1506, 1530, 1522, -1, 1527, 1530, 1506, -1, 1531, 1530, 1527, -1, 1522, 1530, 1532, -1, 111, 1533, 1458, -1, 1529, 527, 1534, -1, 816, 1535, 1536, -1, 525, 527, 1529, -1, 1517, 295, 1537, -1, 293, 295, 1517, -1, 527, 529, 1534, -1, 1528, 1538, 282, -1, 1534, 529, 1539, -1, 816, 1540, 1535, -1, 163, 1541, 161, -1, 529, 531, 1539, -1, 161, 1541, 1516, -1, 1537, 297, 1542, -1, 165, 1543, 163, -1, 163, 1543, 1541, -1, 295, 297, 1537, -1, 165, 1544, 1543, -1, 816, 1545, 1540, -1, 721, 35, 1546, -1, 1547, 1548, 1528, -1, 167, 1544, 165, -1, 1528, 1548, 1538, -1, 1549, 1550, 167, -1, 1551, 1550, 1549, -1, 167, 1550, 1544, -1, 816, 1552, 1545, -1, 1546, 37, 1553, -1, 1551, 1554, 1550, -1, 1555, 483, 1556, -1, 35, 37, 1546, -1, 723, 33, 721, -1, 725, 33, 723, -1, 1542, 299, 1557, -1, 721, 33, 35, -1, 1558, 1554, 1551, -1, 297, 299, 1542, -1, 1558, 1559, 1554, -1, 1556, 485, 1560, -1, 483, 485, 1556, -1, 37, 39, 1553, -1, 1561, 1559, 1558, -1, 1547, 1562, 1548, -1, 1563, 1562, 1547, -1, 1564, 401, 1565, -1, 1508, 481, 1555, -1, 1421, 39, 1566, -1, 1420, 39, 1421, -1, 1561, 1567, 1559, -1, 399, 401, 1564, -1, 816, 1568, 1552, -1, 1555, 481, 483, -1, 1553, 39, 1420, -1, 725, 31, 33, -1, 1560, 487, 1569, -1, 555, 397, 1570, -1, 1552, 1568, 1571, -1, 1572, 1567, 1561, -1, 485, 487, 1560, -1, 557, 397, 555, -1, 1557, 301, 1573, -1, 1570, 397, 1564, -1, 299, 301, 1557, -1, 1564, 397, 399, -1, 1425, 479, 1508, -1, 1508, 479, 481, -1, 1563, 1574, 1562, -1, 1569, 489, 1575, -1, 1573, 303, 1576, -1, 1565, 403, 1577, -1, 873, 735, 871, -1, 301, 303, 1573, -1, 487, 489, 1569, -1, 1566, 41, 1578, -1, 39, 41, 1566, -1, 401, 403, 1565, -1, 727, 30, 725, -1, 557, 395, 397, -1, 735, 737, 871, -1, 559, 395, 557, -1, 725, 30, 31, -1, 871, 737, 869, -1, 489, 491, 1575, -1, 1563, 1579, 1574, -1, 1574, 1579, 1580, -1, 873, 733, 735, -1, 875, 733, 873, -1, 1577, 405, 1581, -1, 1578, 43, 1582, -1, 1575, 491, 1583, -1, 403, 405, 1577, -1, 41, 43, 1578, -1, 1584, 394, 559, -1, 737, 739, 869, -1, 559, 394, 395, -1, 491, 493, 1583, -1, 727, 1585, 30, -1, 901, 1585, 727, -1, 903, 1585, 901, -1, 869, 739, 867, -1, 1583, 493, 1586, -1, 1587, 731, 875, -1, 875, 731, 733, -1, 1581, 407, 1588, -1, 43, 45, 1582, -1, 1582, 45, 1589, -1, 405, 407, 1581, -1, 493, 495, 1586, -1, 1470, 1590, 1584, -1, 1586, 495, 1591, -1, 1584, 1590, 394, -1, 739, 741, 867, -1, 903, 1592, 1585, -1, 407, 409, 1588, -1, 867, 741, 865, -1, 495, 497, 1591, -1, 1588, 409, 1593, -1, 1591, 497, 1594, -1, 45, 47, 1589, -1, 741, 743, 865, -1, 1470, 1595, 1590, -1, 903, 1596, 1592, -1, 865, 743, 863, -1, 905, 1596, 903, -1, 1579, 1597, 1580, -1, 497, 499, 1594, -1, 47, 49, 1589, -1, 1594, 499, 1598, -1, 1580, 1597, 1599, -1, 1593, 411, 1600, -1, 816, 1601, 1568, -1, 409, 411, 1593, -1, 1589, 49, 1602, -1, 743, 745, 863, -1, 411, 413, 1600, -1, 863, 745, 861, -1, 1597, 1603, 1599, -1, 1602, 51, 1604, -1, 1599, 1603, 1605, -1, 49, 51, 1602, -1, 1600, 413, 1606, -1, 1510, 1607, 816, -1, 861, 747, 859, -1, 745, 747, 861, -1, 1604, 53, 1608, -1, 51, 53, 1604, -1, 1606, 415, 1609, -1, 413, 415, 1606, -1, 1608, 55, 1610, -1, 859, 749, 857, -1, 747, 749, 859, -1, 53, 55, 1608, -1, 1610, 1611, 1612, -1, 55, 1611, 1610, -1, 479, 636, 478, -1, 636, 634, 478, -1, 478, 634, 1613, -1, 1425, 638, 479, -1, 479, 638, 636, -1, 634, 632, 1613, -1, 1614, 1615, 1616, -1, 1617, 1615, 1614, -1, 905, 7, 1596, -1, 1613, 632, 1618, -1, 693, 7, 905, -1, 1425, 640, 638, -1, 1615, 1619, 1616, -1, 7, 9, 1596, -1, 632, 630, 1618, -1, 1596, 9, 1620, -1, 1618, 630, 1621, -1, 1425, 642, 640, -1, 695, 5, 693, -1, 697, 5, 695, -1, 630, 628, 1621, -1, 693, 5, 7, -1, 1622, 628, 1623, -1, 1621, 628, 1622, -1, 1624, 429, 1625, -1, 427, 429, 1624, -1, 1620, 11, 1626, -1, 9, 11, 1620, -1, 628, 626, 1623, -1, 1627, 425, 1624, -1, 1628, 1629, 1630, -1, 1447, 425, 1627, -1, 1624, 425, 427, -1, 833, 63, 1503, -1, 779, 63, 777, -1, 1623, 626, 1631, -1, 429, 431, 1625, -1, 697, 3, 5, -1, 777, 63, 833, -1, 1632, 1633, 1619, -1, 1619, 1633, 1616, -1, 626, 624, 1631, -1, 1625, 431, 1634, -1, 1503, 65, 1635, -1, 1631, 624, 1636, -1, 1626, 13, 1637, -1, 1447, 423, 425, -1, 11, 13, 1626, -1, 63, 65, 1503, -1, 1628, 1638, 1629, -1, 431, 433, 1634, -1, 1639, 1640, 1628, -1, 624, 622, 1636, -1, 699, 2, 697, -1, 697, 2, 3, -1, 1634, 433, 1641, -1, 779, 61, 63, -1, 1636, 622, 1642, -1, 1628, 1643, 1638, -1, 1640, 1643, 1628, -1, 1637, 15, 1644, -1, 1635, 67, 1645, -1, 13, 15, 1637, -1, 1643, 1646, 1638, -1, 925, 1647, 699, -1, 65, 67, 1635, -1, 433, 435, 1641, -1, 1616, 820, 1603, -1, 1603, 820, 1605, -1, 699, 1647, 2, -1, 1648, 820, 1649, -1, 1641, 435, 1650, -1, 1605, 820, 1648, -1, 1633, 820, 1616, -1, 1651, 371, 1652, -1, 781, 59, 779, -1, 783, 59, 781, -1, 779, 59, 61, -1, 371, 373, 1652, -1, 1644, 17, 1653, -1, 15, 17, 1644, -1, 1652, 373, 1654, -1, 1651, 369, 371, -1, 1645, 69, 1655, -1, 1650, 437, 1656, -1, 435, 437, 1650, -1, 67, 69, 1645, -1, 1657, 369, 1651, -1, 373, 375, 1654, -1, 1653, 19, 1658, -1, 853, 58, 783, -1, 437, 439, 1656, -1, 17, 19, 1653, -1, 1654, 375, 1659, -1, 783, 58, 59, -1, 622, 620, 1642, -1, 1656, 439, 1660, -1, 1655, 71, 1661, -1, 69, 71, 1655, -1, 935, 1662, 933, -1, 1657, 367, 369, -1, 439, 441, 1660, -1, 1663, 175, 1664, -1, 1660, 441, 1665, -1, 853, 1666, 58, -1, 855, 1666, 853, -1, 375, 377, 1659, -1, 175, 177, 1664, -1, 933, 1667, 931, -1, 1659, 377, 1498, -1, 1662, 1667, 933, -1, 1661, 73, 1668, -1, 1665, 443, 1669, -1, 1664, 177, 1670, -1, 531, 366, 1539, -1, 71, 73, 1661, -1, 1657, 366, 367, -1, 1658, 21, 1671, -1, 19, 21, 1658, -1, 855, 1672, 1666, -1, 441, 443, 1665, -1, 331, 173, 1663, -1, 333, 173, 331, -1, 935, 1673, 1662, -1, 1663, 173, 175, -1, 937, 1673, 935, -1, 1539, 366, 1657, -1, 939, 1673, 937, -1, 377, 379, 1498, -1, 1498, 379, 818, -1, 1668, 75, 1674, -1, 177, 179, 1670, -1, 73, 75, 1668, -1, 1670, 179, 1675, -1, 855, 1676, 1672, -1, 531, 1677, 366, -1, 931, 1678, 929, -1, 857, 1676, 855, -1, 335, 171, 333, -1, 1667, 1678, 931, -1, 333, 171, 173, -1, 75, 77, 1674, -1, 1674, 77, 1679, -1, 1680, 1677, 531, -1, 1598, 1677, 1680, -1, 1671, 23, 1681, -1, 21, 23, 1671, -1, 179, 181, 1675, -1, 941, 1682, 939, -1, 1675, 181, 1683, -1, 77, 79, 1679, -1, 1679, 79, 1684, -1, 379, 381, 818, -1, 939, 1682, 1673, -1, 1685, 170, 335, -1, 335, 170, 171, -1, 23, 25, 1681, -1, 1598, 1686, 1677, -1, 1681, 25, 1611, -1, 1684, 81, 1533, -1, 79, 81, 1684, -1, 927, 1687, 925, -1, 1533, 81, 1458, -1, 929, 1687, 927, -1, 1678, 1687, 929, -1, 181, 183, 1683, -1, 381, 383, 818, -1, 1519, 203, 1688, -1, 1683, 183, 1689, -1, 1576, 1690, 1685, -1, 1685, 1690, 170, -1, 1688, 205, 1691, -1, 203, 205, 1688, -1, 359, 201, 1519, -1, 1519, 201, 203, -1, 361, 201, 359, -1, 1643, 1692, 1646, -1, 941, 1693, 1682, -1, 183, 185, 1689, -1, 1691, 207, 1694, -1, 1689, 185, 1695, -1, 205, 207, 1691, -1, 1447, 1696, 423, -1, 1425, 1696, 642, -1, 303, 1697, 1576, -1, 1576, 1697, 1690, -1, 1698, 1696, 1699, -1, 642, 1696, 670, -1, 1700, 1696, 1698, -1, 1701, 1696, 1700, -1, 897, 707, 895, -1, 1702, 1696, 1701, -1, 422, 1696, 1702, -1, 423, 1696, 422, -1, 1703, 1696, 1446, -1, 670, 1696, 1703, -1, 1446, 1696, 1447, -1, 185, 187, 1695, -1, 361, 199, 201, -1, 363, 199, 361, -1, 895, 709, 893, -1, 1695, 187, 1704, -1, 707, 709, 895, -1, 1647, 1705, 1706, -1, 1687, 1705, 925, -1, 925, 1705, 1647, -1, 899, 705, 897, -1, 1705, 1707, 1706, -1, 897, 705, 707, -1, 1694, 209, 1708, -1, 207, 209, 1694, -1, 1706, 1707, 1709, -1, 893, 711, 891, -1, 1710, 198, 363, -1, 187, 189, 1704, -1, 363, 198, 199, -1, 1707, 1711, 1709, -1, 1704, 189, 1712, -1, 709, 711, 893, -1, 1713, 1711, 1714, -1, 1709, 1711, 1713, -1, 899, 703, 705, -1, 820, 822, 1715, -1, 941, 822, 1693, -1, 1572, 822, 1567, -1, 1567, 822, 1515, -1, 1715, 822, 1572, -1, 1708, 211, 1716, -1, 1515, 822, 941, -1, 891, 713, 889, -1, 209, 211, 1708, -1, 822, 1717, 1693, -1, 711, 713, 891, -1, 1609, 1718, 1710, -1, 1710, 1718, 198, -1, 1719, 1720, 822, -1, 889, 715, 887, -1, 822, 1721, 1717, -1, 713, 715, 889, -1, 1717, 1721, 1722, -1, 1716, 213, 1723, -1, 1724, 791, 1607, -1, 211, 213, 1716, -1, 1720, 1725, 822, -1, 822, 1725, 1721, -1, 1726, 1725, 1720, -1, 887, 717, 885, -1, 1727, 664, 1728, -1, 1712, 191, 1518, -1, 189, 191, 1712, -1, 1714, 1729, 1730, -1, 415, 1731, 1609, -1, 1711, 1729, 1714, -1, 715, 717, 887, -1, 664, 662, 1728, -1, 1609, 1731, 1718, -1, 1601, 793, 1732, -1, 816, 793, 1601, -1, 1607, 793, 816, -1, 1728, 662, 1733, -1, 1727, 666, 664, -1, 1730, 1734, 1735, -1, 883, 719, 881, -1, 1723, 215, 1736, -1, 885, 719, 883, -1, 791, 793, 1607, -1, 717, 719, 885, -1, 1737, 666, 1727, -1, 213, 215, 1723, -1, 1729, 1734, 1730, -1, 662, 660, 1733, -1, 1738, 789, 1724, -1, 1724, 789, 791, -1, 1734, 1739, 1735, -1, 1733, 660, 1740, -1, 719, 721, 881, -1, 1737, 668, 666, -1, 1732, 795, 1741, -1, 793, 795, 1732, -1, 660, 658, 1740, -1, 1740, 658, 1742, -1, 1737, 670, 668, -1, 1743, 1744, 1696, -1, 642, 670, 1737, -1, 658, 656, 1742, -1, 1745, 787, 1738, -1, 1738, 787, 789, -1, 1742, 656, 1746, -1, 795, 797, 1741, -1, 1747, 1748, 1749, -1, 899, 1492, 703, -1, 1750, 539, 1751, -1, 915, 1492, 913, -1, 917, 1492, 915, -1, 919, 1492, 917, -1, 1745, 786, 787, -1, 921, 1492, 919, -1, 1748, 1752, 1749, -1, 923, 1492, 921, -1, 702, 1492, 923, -1, 703, 1492, 702, -1, 539, 541, 1751, -1, 1741, 799, 1753, -1, 797, 799, 1741, -1, 1754, 537, 1750, -1, 1750, 537, 539, -1, 541, 543, 1751, -1, 1755, 1756, 1752, -1, 1757, 851, 1745, -1, 1751, 543, 1758, -1, 1752, 1759, 1749, -1, 1745, 851, 786, -1, 1756, 1759, 1752, -1, 857, 119, 1676, -1, 1744, 1760, 1696, -1, 751, 119, 749, -1, 1754, 535, 537, -1, 749, 119, 857, -1, 1761, 535, 1754, -1, 1759, 824, 1749, -1, 1749, 824, 1762, -1, 543, 545, 1758, -1, 1735, 826, 1763, -1, 1739, 826, 1735, -1, 824, 826, 1762, -1, 1758, 545, 616, -1, 1762, 826, 1739, -1, 119, 121, 1676, -1, 25, 1764, 1611, -1, 1765, 1764, 560, -1, 1612, 1764, 1765, -1, 1766, 1764, 27, -1, 1767, 1764, 1766, -1, 1768, 1764, 1767, -1, 1753, 801, 1769, -1, 1770, 1764, 1768, -1, 1676, 121, 1771, -1, 656, 534, 1746, -1, 1763, 1764, 1770, -1, 654, 534, 656, -1, 249, 1772, 247, -1, 826, 1764, 1763, -1, 799, 801, 1753, -1, 1761, 534, 535, -1, 251, 1772, 249, -1, 560, 1764, 1458, -1, 27, 1764, 25, -1, 1611, 1764, 1612, -1, 1746, 534, 1761, -1, 1773, 608, 1774, -1, 1775, 1776, 251, -1, 826, 1777, 1764, -1, 545, 547, 616, -1, 251, 1776, 1772, -1, 1778, 1777, 826, -1, 1777, 1779, 1764, -1, 616, 547, 617, -1, 1764, 1779, 1780, -1, 1781, 849, 1757, -1, 751, 117, 119, -1, 1757, 849, 851, -1, 654, 1782, 534, -1, 1772, 1783, 247, -1, 1777, 1784, 1779, -1, 652, 1782, 654, -1, 608, 606, 1774, -1, 1785, 1784, 1777, -1, 247, 1783, 245, -1, 1587, 1492, 730, -1, 1587, 730, 731, -1, 730, 1492, 899, -1, 1516, 1433, 279, -1, 1516, 279, 1520, -1, 279, 1433, 277, -1, 1774, 606, 1786, -1, 1769, 803, 1787, -1, 547, 549, 617, -1, 121, 123, 1771, -1, 801, 803, 1769, -1, 1788, 1789, 1775, -1, 617, 549, 620, -1, 620, 549, 1642, -1, 1775, 1789, 1776, -1, 1771, 123, 1773, -1, 1773, 610, 608, -1, 123, 610, 1773, -1, 1783, 1790, 245, -1, 1781, 847, 849, -1, 245, 1790, 243, -1, 1787, 805, 1791, -1, 803, 805, 1787, -1, 753, 115, 751, -1, 650, 1792, 652, -1, 755, 115, 753, -1, 652, 1792, 1782, -1, 1788, 1793, 1789, -1, 1781, 845, 847, -1, 549, 551, 1642, -1, 1794, 845, 1781, -1, 1795, 1793, 1788, -1, 751, 115, 117, -1, 606, 604, 1786, -1, 805, 807, 1791, -1, 1642, 551, 1796, -1, 1786, 604, 1797, -1, 1794, 843, 845, -1, 215, 1433, 1736, -1, 1798, 1433, 223, -1, 1431, 1433, 1798, -1, 1587, 843, 1794, -1, 217, 1433, 215, -1, 219, 1433, 217, -1, 221, 1433, 219, -1, 650, 1799, 1792, -1, 223, 1433, 221, -1, 1791, 809, 1474, -1, 1736, 1433, 1795, -1, 1795, 1433, 1793, -1, 807, 809, 1791, -1, 650, 648, 1799, -1, 1587, 841, 843, -1, 123, 612, 610, -1, 551, 553, 1796, -1, 1790, 1510, 243, -1, 243, 1510, 241, -1, 125, 612, 123, -1, 1796, 553, 1800, -1, 755, 114, 115, -1, 1801, 1802, 1760, -1, 1803, 1802, 1801, -1, 1760, 1802, 1696, -1, 648, 1804, 1799, -1, 604, 602, 1797, -1, 553, 555, 1800, -1, 1805, 602, 1806, -1, 1797, 602, 1805, -1, 1800, 555, 1807, -1, 645, 1808, 648, -1, 125, 614, 612, -1, 648, 1808, 1804, -1, 127, 614, 125, -1, 877, 1809, 755, -1, 879, 1809, 877, -1, 315, 317, 1810, -1, 755, 1809, 114, -1, 1494, 1457, 1692, -1, 1810, 317, 1811, -1, 1692, 1457, 1646, -1, 1595, 313, 1810, -1, 602, 600, 1806, -1, 1810, 313, 315, -1, 1806, 600, 1812, -1, 644, 1813, 645, -1, 1457, 1814, 1815, -1, 473, 313, 471, -1, 645, 1813, 1808, -1, 1470, 313, 1595, -1, 471, 313, 1470, -1, 317, 319, 1811, -1, 1811, 319, 1816, -1, 879, 1817, 1809, -1, 1699, 1478, 1469, -1, 1696, 1478, 1699, -1, 1802, 1478, 1696, -1, 1697, 147, 1818, -1, 1819, 1820, 644, -1, 127, 1821, 614, -1, 129, 1821, 127, -1, 644, 1820, 1813, -1, 147, 149, 1818, -1, 475, 311, 473, -1, 473, 311, 313, -1, 1818, 149, 1822, -1, 305, 145, 303, -1, 303, 145, 1697, -1, 319, 321, 1816, -1, 1697, 145, 147, -1, 1816, 321, 1823, -1, 600, 598, 1812, -1, 149, 151, 1822, -1, 1812, 598, 1824, -1, 1450, 1454, 1819, -1, 1825, 310, 475, -1, 881, 1546, 879, -1, 1819, 1454, 1820, -1, 475, 310, 311, -1, 879, 1546, 1817, -1, 1822, 151, 1826, -1, 307, 143, 305, -1, 721, 1546, 881, -1, 321, 323, 1823, -1, 305, 143, 145, -1, 129, 1827, 1821, -1, 1823, 323, 1828, -1, 131, 1827, 129, -1, 151, 153, 1826, -1, 131, 133, 1827, -1, 598, 596, 1824, -1, 1826, 153, 1829, -1, 1669, 1830, 1825, -1, 1825, 1830, 310, -1, 307, 142, 143, -1, 1824, 596, 83, -1, 1831, 142, 307, -1, 323, 325, 1828, -1, 153, 155, 1829, -1, 1828, 325, 1832, -1, 1669, 1495, 1830, -1, 1829, 155, 1833, -1, 443, 1495, 1669, -1, 1831, 1834, 142, -1, 135, 1835, 133, -1, 133, 1835, 1827, -1, 1686, 343, 1836, -1, 155, 157, 1833, -1, 325, 327, 1832, -1, 1837, 157, 1521, -1, 596, 594, 83, -1, 1833, 157, 1837, -1, 83, 594, 81, -1, 1832, 327, 1838, -1, 1836, 345, 1839, -1, 343, 345, 1836, -1, 1457, 1840, 1814, -1, 1598, 341, 1686, -1, 1686, 341, 343, -1, 1831, 1841, 1834, -1, 499, 341, 1598, -1, 1842, 1841, 1831, -1, 1843, 1841, 1842, -1, 327, 329, 1838, -1, 1838, 329, 1844, -1, 345, 347, 1839, -1, 157, 159, 1521, -1, 137, 1845, 135, -1, 135, 1845, 1835, -1, 1839, 347, 1846, -1, 499, 339, 341, -1, 1843, 1847, 1841, -1, 329, 331, 1844, -1, 1844, 331, 1848, -1, 501, 339, 499, -1, 503, 339, 501, -1, 81, 592, 1458, -1, 820, 1849, 1649, -1, 594, 592, 81, -1, 347, 349, 1846, -1, 1843, 1849, 1847, -1, 1649, 1849, 1843, -1, 1846, 349, 1850, -1, 1851, 338, 503, -1, 503, 338, 339, -1, 349, 351, 1850, -1, 1850, 351, 1852, -1, 763, 765, 1587, -1, 1851, 1853, 338, -1, 1807, 1853, 1851, -1, 139, 1854, 137, -1, 1587, 761, 763, -1, 137, 1854, 1845, -1, 351, 353, 1852, -1, 592, 589, 1458, -1, 1457, 1855, 1840, -1, 1852, 353, 1856, -1, 139, 1857, 1854, -1, 1807, 1570, 1853, -1, 765, 767, 1587, -1, 589, 588, 1458, -1, 555, 1570, 1807, -1, 820, 1858, 1849, -1, 353, 355, 1856, -1, 1856, 355, 1859, -1, 1587, 759, 761, -1, 767, 769, 1587, -1, 1731, 259, 1860, -1, 1587, 769, 841, -1, 355, 357, 1859, -1, 1859, 357, 1861, -1, 1587, 758, 759, -1, 1860, 261, 1862, -1, 259, 261, 1860, -1, 1863, 580, 1864, -1, 357, 359, 1861, -1, 1731, 257, 259, -1, 417, 257, 415, -1, 820, 1865, 1858, -1, 1861, 359, 1514, -1, 415, 257, 1731, -1, 841, 771, 839, -1, 769, 771, 841, -1, 1864, 578, 1866, -1, 1862, 263, 1867, -1, 1587, 875, 758, -1, 580, 578, 1864, -1, 261, 263, 1862, -1, 417, 255, 257, -1, 1863, 582, 580, -1, 1868, 582, 1863, -1, 419, 255, 417, -1, 1869, 582, 1868, -1, 820, 1715, 1865, -1, 578, 576, 1866, -1, 1866, 576, 139, -1, 1867, 265, 1870, -1, 263, 265, 1867, -1, 839, 773, 837, -1, 419, 254, 255, -1, 771, 773, 839, -1, 1871, 584, 1869, -1, 1869, 584, 582, -1, 1872, 254, 419, -1, 265, 267, 1870, -1, 139, 574, 1857, -1, 576, 574, 139, -1, 1870, 267, 1873, -1, 1872, 1874, 254, -1, 1871, 586, 584, -1, 1875, 586, 1871, -1, 267, 269, 1873, -1, 1873, 269, 1412, -1, 574, 572, 1857, -1, 1417, 455, 1414, -1, 1457, 1459, 1855, -1, 1872, 1663, 1874, -1, 773, 775, 837, -1, 1857, 572, 1415, -1, 1875, 1422, 586, -1, 1848, 1663, 1872, -1, 1420, 1422, 1875, -1, 331, 1663, 1848, -1, 837, 775, 835, -1, 961, 1696, 1425, -1, 961, 1235, 1696, -1, 1457, 1181, 1646, -1, 972, 1181, 1457, -1, 1764, 996, 1458, -1, 1301, 996, 1764, -1, 1478, 1044, 1506, -1, 1016, 1044, 1478, -1, 670, 1703, 671, -1, 671, 1703, 1239, -1, 1239, 1446, 987, -1, 1703, 1446, 1239, -1, 987, 1436, 977, -1, 1446, 1436, 987, -1, 977, 1427, 968, -1, 1436, 1427, 977, -1, 968, 1416, 955, -1, 1427, 1416, 968, -1, 955, 1417, 956, -1, 1416, 1417, 955, -1, 956, 1414, 952, -1, 1417, 1414, 956, -1, 952, 1423, 960, -1, 1414, 1423, 952, -1, 960, 1435, 976, -1, 1423, 1435, 960, -1, 976, 1441, 982, -1, 1435, 1441, 976, -1, 982, 1450, 990, -1, 1441, 1450, 982, -1, 990, 1819, 1357, -1, 1450, 1819, 990, -1, 1357, 644, 646, -1, 1819, 644, 1357, -1, 642, 1737, 643, -1, 643, 1737, 1272, -1, 1272, 1727, 1260, -1, 1737, 1727, 1272, -1, 1260, 1728, 1261, -1, 1727, 1728, 1260, -1, 1261, 1733, 1267, -1, 1728, 1733, 1261, -1, 1267, 1740, 1278, -1, 1733, 1740, 1267, -1, 1278, 1742, 1280, -1, 1740, 1742, 1278, -1, 1280, 1746, 1284, -1, 1742, 1746, 1280, -1, 1284, 1761, 1300, -1, 1746, 1761, 1284, -1, 1300, 1754, 1294, -1, 1761, 1754, 1300, -1, 1294, 1750, 1289, -1, 1754, 1750, 1294, -1, 1289, 1751, 1290, -1, 1750, 1751, 1289, -1, 1290, 1758, 1298, -1, 1751, 1758, 1290, -1, 1298, 616, 618, -1, 1758, 616, 1298, -1, 614, 1821, 615, -1, 615, 1821, 1359, -1, 1359, 1827, 1366, -1, 1821, 1827, 1359, -1, 1366, 1835, 1374, -1, 1827, 1835, 1366, -1, 1374, 1845, 1383, -1, 1835, 1845, 1374, -1, 1383, 1854, 1392, -1, 1845, 1854, 1383, -1, 1392, 1857, 1395, -1, 1854, 1857, 1392, -1, 1395, 1415, 954, -1, 1857, 1415, 1395, -1, 954, 1418, 957, -1, 1415, 1418, 954, -1, 957, 1434, 974, -1, 1418, 1434, 957, -1, 974, 1437, 978, -1, 1434, 1437, 974, -1, 978, 1445, 988, -1, 1437, 1445, 978, -1, 988, 1456, 998, -1, 1445, 1456, 988, -1, 998, 588, 590, -1, 1456, 588, 998, -1, 586, 1422, 587, -1, 587, 1422, 948, -1, 948, 1421, 959, -1, 1422, 1421, 948, -1, 959, 1566, 1108, -1, 1421, 1566, 959, -1, 1108, 1578, 1116, -1, 1566, 1578, 1108, -1, 1116, 1582, 1121, -1, 1578, 1582, 1116, -1, 1121, 1589, 1128, -1, 1582, 1589, 1121, -1, 1128, 1602, 1140, -1, 1589, 1602, 1128, -1, 1140, 1604, 1143, -1, 1602, 1604, 1140, -1, 1143, 1608, 1146, -1, 1604, 1608, 1143, -1, 1146, 1610, 1148, -1, 1608, 1610, 1146, -1, 1148, 1612, 1150, -1, 1610, 1612, 1148, -1, 1150, 1765, 1302, -1, 1612, 1765, 1150, -1, 1302, 560, 562, -1, 1765, 560, 1302, -1, 826, 825, 1318, -1, 1778, 1318, 1317, -1, 1778, 826, 1318, -1, 1777, 1317, 1320, -1, 1777, 1778, 1317, -1, 1785, 1320, 1321, -1, 1785, 1777, 1320, -1, 1784, 1321, 1312, -1, 1784, 1785, 1321, -1, 1779, 1312, 1313, -1, 1779, 1784, 1312, -1, 1780, 1313, 1301, -1, 1780, 1779, 1313, -1, 1764, 1780, 1301, -1, 1460, 996, 971, -1, 1460, 1458, 996, -1, 1459, 971, 975, -1, 1459, 1460, 971, -1, 1855, 975, 973, -1, 1855, 1459, 975, -1, 1840, 973, 1377, -1, 1840, 1855, 973, -1, 1814, 1377, 1350, -1, 1814, 1840, 1377, -1, 1815, 1350, 1351, -1, 1815, 1814, 1350, -1, 1457, 1351, 972, -1, 1457, 1815, 1351, -1, 1424, 813, 967, -1, 1424, 814, 813, -1, 1426, 967, 966, -1, 1426, 1424, 967, -1, 1428, 966, 965, -1, 1428, 1426, 966, -1, 1429, 965, 964, -1, 1429, 1428, 965, -1, 1430, 964, 963, -1, 1430, 1429, 964, -1, 1432, 963, 962, -1, 1432, 1430, 963, -1, 1425, 962, 961, -1, 1425, 1432, 962, -1, 1743, 1235, 1282, -1, 1743, 1696, 1235, -1, 1744, 1282, 1281, -1, 1744, 1743, 1282, -1, 1760, 1281, 1296, -1, 1760, 1744, 1281, -1, 1801, 1296, 1341, -1, 1801, 1760, 1296, -1, 1803, 1341, 1340, -1, 1803, 1801, 1341, -1, 1802, 1340, 1339, -1, 1802, 1803, 1340, -1, 1478, 1339, 1016, -1, 1478, 1802, 1339, -1, 1433, 1516, 970, -1, 1516, 1054, 970, -1, 1515, 1053, 1567, -1, 1567, 1053, 1104, -1, 1030, 1492, 1125, -1, 1125, 1492, 1587, -1, 1145, 1607, 1047, -1, 1047, 1607, 1510, -1, 1515, 1507, 1053, -1, 1053, 1507, 1048, -1, 1048, 1502, 1040, -1, 1507, 1502, 1048, -1, 1040, 1493, 1032, -1, 1502, 1493, 1040, -1, 1032, 1490, 1029, -1, 1493, 1490, 1032, -1, 1029, 1483, 1024, -1, 1490, 1483, 1029, -1, 1024, 1485, 1025, -1, 1483, 1485, 1024, -1, 1025, 1492, 1030, -1, 1485, 1492, 1025, -1, 1054, 1516, 1077, -1, 1077, 1541, 1080, -1, 1516, 1541, 1077, -1, 1080, 1543, 1084, -1, 1541, 1543, 1080, -1, 1084, 1544, 1087, -1, 1543, 1544, 1084, -1, 1087, 1550, 1091, -1, 1544, 1550, 1087, -1, 1091, 1554, 1095, -1, 1550, 1554, 1091, -1, 1095, 1559, 1104, -1, 1554, 1559, 1095, -1, 1559, 1567, 1104, -1, 1125, 1587, 1330, -1, 1330, 1794, 1319, -1, 1587, 1794, 1330, -1, 1319, 1781, 1295, -1, 1794, 1781, 1319, -1, 1295, 1757, 1283, -1, 1781, 1757, 1295, -1, 1283, 1745, 1275, -1, 1757, 1745, 1283, -1, 1275, 1738, 1257, -1, 1745, 1738, 1275, -1, 1257, 1724, 1145, -1, 1738, 1724, 1257, -1, 1724, 1607, 1145, -1, 1510, 1790, 1047, -1, 1047, 1790, 1328, -1, 1328, 1783, 1322, -1, 1790, 1783, 1328, -1, 1322, 1772, 1303, -1, 1783, 1772, 1322, -1, 1303, 1776, 1311, -1, 1772, 1776, 1303, -1, 1311, 1789, 1325, -1, 1776, 1789, 1311, -1, 1325, 1793, 1332, -1, 1789, 1793, 1325, -1, 1332, 1433, 970, -1, 1793, 1433, 1332, -1, 558, 1122, 559, -1, 559, 1122, 1584, -1, 1584, 1011, 1470, -1, 1122, 1011, 1584, -1, 1470, 1005, 1465, -1, 1011, 1005, 1470, -1, 1465, 1000, 1461, -1, 1005, 1000, 1465, -1, 1461, 991, 1454, -1, 1000, 991, 1461, -1, 1454, 1356, 1820, -1, 991, 1356, 1454, -1, 1820, 1353, 1813, -1, 1356, 1353, 1820, -1, 1813, 1346, 1808, -1, 1353, 1346, 1813, -1, 1808, 1342, 1804, -1, 1346, 1342, 1808, -1, 1804, 1337, 1799, -1, 1342, 1337, 1804, -1, 1799, 1331, 1792, -1, 1337, 1331, 1799, -1, 1792, 1323, 1782, -1, 1331, 1323, 1792, -1, 1782, 532, 534, -1, 1323, 532, 1782, -1, 530, 1217, 531, -1, 531, 1217, 1680, -1, 1680, 1137, 1598, -1, 1217, 1137, 1680, -1, 1598, 1131, 1594, -1, 1137, 1131, 1598, -1, 1594, 1129, 1591, -1, 1131, 1129, 1594, -1, 1591, 1124, 1586, -1, 1129, 1124, 1591, -1, 1586, 1119, 1583, -1, 1124, 1119, 1586, -1, 1583, 1115, 1575, -1, 1119, 1115, 1583, -1, 1575, 1111, 1569, -1, 1115, 1111, 1575, -1, 1569, 1106, 1560, -1, 1111, 1106, 1569, -1, 1560, 1098, 1556, -1, 1106, 1098, 1560, -1, 1556, 1097, 1555, -1, 1098, 1097, 1556, -1, 1555, 1046, 1508, -1, 1097, 1046, 1555, -1, 1508, 504, 506, -1, 1046, 504, 1508, -1, 502, 1389, 503, -1, 503, 1389, 1851, -1, 1851, 1343, 1807, -1, 1389, 1343, 1851, -1, 1807, 1338, 1800, -1, 1343, 1338, 1807, -1, 1800, 1334, 1796, -1, 1338, 1334, 1800, -1, 1796, 1178, 1642, -1, 1334, 1178, 1796, -1, 1642, 1174, 1636, -1, 1178, 1174, 1642, -1, 1636, 1169, 1631, -1, 1174, 1169, 1636, -1, 1631, 1163, 1623, -1, 1169, 1163, 1631, -1, 1623, 1162, 1622, -1, 1163, 1162, 1623, -1, 1622, 1159, 1621, -1, 1162, 1159, 1622, -1, 1621, 1156, 1618, -1, 1159, 1156, 1621, -1, 1618, 1151, 1613, -1, 1156, 1151, 1618, -1, 1613, 476, 478, -1, 1151, 476, 1613, -1, 474, 1364, 475, -1, 475, 1364, 1825, -1, 1825, 1210, 1669, -1, 1364, 1210, 1825, -1, 1669, 1204, 1665, -1, 1210, 1204, 1669, -1, 1665, 1201, 1660, -1, 1204, 1201, 1665, -1, 1660, 1195, 1656, -1, 1201, 1195, 1660, -1, 1656, 1190, 1650, -1, 1195, 1190, 1656, -1, 1650, 1182, 1641, -1, 1190, 1182, 1650, -1, 1641, 1170, 1634, -1, 1182, 1170, 1641, -1, 1634, 1161, 1625, -1, 1170, 1161, 1634, -1, 1625, 1160, 1624, -1, 1161, 1160, 1625, -1, 1624, 1165, 1627, -1, 1160, 1165, 1624, -1, 1627, 986, 1447, -1, 1165, 986, 1627, -1, 1447, 448, 450, -1, 986, 448, 1447, -1, 446, 1019, 447, -1, 447, 1019, 1481, -1, 1481, 1014, 1476, -1, 1019, 1014, 1481, -1, 1476, 1002, 1464, -1, 1014, 1002, 1476, -1, 1464, 1001, 1462, -1, 1002, 1001, 1464, -1, 1462, 995, 1453, -1, 1001, 995, 1462, -1, 1453, 994, 1451, -1, 995, 994, 1453, -1, 1451, 1007, 1469, -1, 994, 1007, 1451, -1, 1469, 1237, 1699, -1, 1007, 1237, 1469, -1, 1699, 1236, 1698, -1, 1237, 1236, 1699, -1, 1698, 1238, 1700, -1, 1236, 1238, 1698, -1, 1700, 1240, 1701, -1, 1238, 1240, 1700, -1, 1701, 1241, 1702, -1, 1240, 1241, 1701, -1, 1702, 420, 422, -1, 1241, 420, 1702, -1, 418, 1408, 419, -1, 419, 1408, 1872, -1, 1872, 1386, 1848, -1, 1408, 1386, 1872, -1, 1848, 1382, 1844, -1, 1386, 1382, 1848, -1, 1844, 1376, 1838, -1, 1382, 1376, 1844, -1, 1838, 1370, 1832, -1, 1376, 1370, 1838, -1, 1832, 1365, 1828, -1, 1370, 1365, 1832, -1, 1828, 1361, 1823, -1, 1365, 1361, 1828, -1, 1823, 1354, 1816, -1, 1361, 1354, 1823, -1, 1816, 1349, 1811, -1, 1354, 1349, 1816, -1, 1811, 1348, 1810, -1, 1349, 1348, 1811, -1, 1810, 1133, 1595, -1, 1348, 1133, 1810, -1, 1595, 1127, 1590, -1, 1133, 1127, 1595, -1, 1590, 392, 394, -1, 1127, 392, 1590, -1, 390, 1050, 391, -1, 391, 1050, 1513, -1, 1513, 1052, 1514, -1, 1050, 1052, 1513, -1, 1514, 1398, 1861, -1, 1052, 1398, 1514, -1, 1861, 1396, 1859, -1, 1398, 1396, 1861, -1, 1859, 1393, 1856, -1, 1396, 1393, 1859, -1, 1856, 1390, 1852, -1, 1393, 1390, 1856, -1, 1852, 1388, 1850, -1, 1390, 1388, 1852, -1, 1850, 1384, 1846, -1, 1388, 1384, 1850, -1, 1846, 1378, 1839, -1, 1384, 1378, 1846, -1, 1839, 1373, 1836, -1, 1378, 1373, 1839, -1, 1836, 1224, 1686, -1, 1373, 1224, 1836, -1, 1686, 1216, 1677, -1, 1224, 1216, 1686, -1, 1677, 364, 366, -1, 1216, 364, 1677, -1, 362, 1250, 363, -1, 363, 1250, 1710, -1, 1710, 1147, 1609, -1, 1250, 1147, 1710, -1, 1609, 1144, 1606, -1, 1147, 1144, 1609, -1, 1606, 1139, 1600, -1, 1144, 1139, 1606, -1, 1600, 1132, 1593, -1, 1139, 1132, 1600, -1, 1593, 1126, 1588, -1, 1132, 1126, 1593, -1, 1588, 1120, 1581, -1, 1126, 1120, 1588, -1, 1581, 1114, 1577, -1, 1120, 1114, 1581, -1, 1577, 1107, 1565, -1, 1114, 1107, 1577, -1, 1565, 1099, 1564, -1, 1107, 1099, 1565, -1, 1564, 1109, 1570, -1, 1099, 1109, 1564, -1, 1570, 1391, 1853, -1, 1109, 1391, 1570, -1, 1853, 336, 338, -1, 1391, 336, 1853, -1, 334, 1223, 335, -1, 335, 1223, 1685, -1, 1685, 1113, 1576, -1, 1223, 1113, 1685, -1, 1576, 1110, 1573, -1, 1113, 1110, 1576, -1, 1573, 1094, 1557, -1, 1110, 1094, 1573, -1, 1557, 1081, 1542, -1, 1094, 1081, 1557, -1, 1542, 1075, 1537, -1, 1081, 1075, 1542, -1, 1537, 1057, 1517, -1, 1075, 1057, 1537, -1, 1517, 1043, 1505, -1, 1057, 1043, 1517, -1, 1505, 1037, 1499, -1, 1043, 1037, 1505, -1, 1499, 1034, 1496, -1, 1037, 1034, 1499, -1, 1496, 1033, 1495, -1, 1034, 1033, 1496, -1, 1495, 1368, 1830, -1, 1033, 1368, 1495, -1, 1830, 308, 310, -1, 1368, 308, 1830, -1, 306, 1369, 307, -1, 307, 1369, 1831, -1, 1831, 1380, 1842, -1, 1369, 1380, 1831, -1, 1842, 1381, 1843, -1, 1380, 1381, 1842, -1, 1843, 1186, 1649, -1, 1381, 1186, 1843, -1, 1649, 1185, 1648, -1, 1186, 1185, 1649, -1, 1648, 1142, 1605, -1, 1185, 1142, 1648, -1, 1605, 1136, 1599, -1, 1142, 1136, 1605, -1, 1599, 1118, 1580, -1, 1136, 1118, 1599, -1, 1580, 1112, 1574, -1, 1118, 1112, 1580, -1, 1574, 1100, 1562, -1, 1112, 1100, 1574, -1, 1562, 1085, 1548, -1, 1100, 1085, 1562, -1, 1548, 1076, 1538, -1, 1085, 1076, 1548, -1, 1538, 280, 282, -1, 1076, 280, 1538, -1, 278, 1056, 279, -1, 279, 1056, 1520, -1, 1520, 1055, 1518, -1, 1056, 1055, 1520, -1, 1518, 1246, 1712, -1, 1055, 1246, 1518, -1, 1712, 1242, 1704, -1, 1246, 1242, 1712, -1, 1704, 1232, 1695, -1, 1242, 1232, 1704, -1, 1695, 1225, 1689, -1, 1232, 1225, 1695, -1, 1689, 1219, 1683, -1, 1225, 1219, 1689, -1, 1683, 1212, 1675, -1, 1219, 1212, 1683, -1, 1675, 1205, 1670, -1, 1212, 1205, 1675, -1, 1670, 1199, 1664, -1, 1205, 1199, 1670, -1, 1664, 1198, 1663, -1, 1199, 1198, 1664, -1, 1663, 1411, 1874, -1, 1198, 1411, 1663, -1, 1874, 252, 254, -1, 1411, 252, 1874, -1, 250, 1316, 251, -1, 251, 1316, 1775, -1, 1775, 1327, 1788, -1, 1316, 1327, 1775, -1, 1788, 1333, 1795, -1, 1327, 1333, 1788, -1, 1795, 1273, 1736, -1, 1333, 1273, 1795, -1, 1736, 1262, 1723, -1, 1273, 1262, 1736, -1, 1723, 1253, 1716, -1, 1262, 1253, 1723, -1, 1716, 1247, 1708, -1, 1253, 1247, 1716, -1, 1708, 1234, 1694, -1, 1247, 1234, 1708, -1, 1694, 1229, 1691, -1, 1234, 1229, 1694, -1, 1691, 1228, 1688, -1, 1229, 1228, 1691, -1, 1688, 1058, 1519, -1, 1228, 1058, 1688, -1, 1519, 1049, 1512, -1, 1058, 1049, 1519, -1, 1512, 224, 226, -1, 1049, 224, 1512, -1, 222, 1336, 223, -1, 223, 1336, 1798, -1, 1798, 969, 1431, -1, 1336, 969, 1798, -1, 1431, 958, 1419, -1, 969, 958, 1431, -1, 1419, 951, 1413, -1, 958, 951, 1419, -1, 1413, 950, 1412, -1, 951, 950, 1413, -1, 1412, 1410, 1873, -1, 950, 1410, 1412, -1, 1873, 1407, 1870, -1, 1410, 1407, 1873, -1, 1870, 1403, 1867, -1, 1407, 1403, 1870, -1, 1867, 1399, 1862, -1, 1403, 1399, 1867, -1, 1862, 1397, 1860, -1, 1399, 1397, 1862, -1, 1860, 1270, 1731, -1, 1397, 1270, 1860, -1, 1731, 1256, 1718, -1, 1270, 1256, 1731, -1, 1718, 196, 198, -1, 1256, 196, 1718, -1, 194, 1059, 195, -1, 195, 1059, 1523, -1, 1523, 1060, 1524, -1, 1059, 1060, 1523, -1, 1524, 1061, 1525, -1, 1060, 1061, 1524, -1, 1525, 1062, 1521, -1, 1061, 1062, 1525, -1, 1521, 1375, 1837, -1, 1062, 1375, 1521, -1, 1837, 1371, 1833, -1, 1375, 1371, 1837, -1, 1833, 1367, 1829, -1, 1371, 1367, 1833, -1, 1829, 1363, 1826, -1, 1367, 1363, 1829, -1, 1826, 1360, 1822, -1, 1363, 1360, 1826, -1, 1822, 1355, 1818, -1, 1360, 1355, 1822, -1, 1818, 1233, 1697, -1, 1355, 1233, 1818, -1, 1697, 1227, 1690, -1, 1233, 1227, 1697, -1, 1690, 168, 170, -1, 1227, 168, 1690, -1, 166, 1088, 167, -1, 167, 1088, 1549, -1, 1549, 1089, 1551, -1, 1088, 1089, 1549, -1, 1551, 1092, 1558, -1, 1089, 1092, 1551, -1, 1558, 1096, 1561, -1, 1092, 1096, 1558, -1, 1561, 1105, 1572, -1, 1096, 1105, 1561, -1, 1572, 1254, 1715, -1, 1105, 1254, 1572, -1, 1715, 1400, 1865, -1, 1254, 1400, 1715, -1, 1865, 1394, 1858, -1, 1400, 1394, 1865, -1, 1858, 1387, 1849, -1, 1394, 1387, 1858, -1, 1849, 1385, 1847, -1, 1387, 1385, 1849, -1, 1847, 1379, 1841, -1, 1385, 1379, 1847, -1, 1841, 1372, 1834, -1, 1379, 1372, 1841, -1, 1834, 140, 142, -1, 1372, 140, 1834, -1, 138, 1404, 139, -1, 139, 1404, 1866, -1, 1866, 1402, 1864, -1, 1404, 1402, 1866, -1, 1864, 1401, 1863, -1, 1402, 1401, 1864, -1, 1863, 1405, 1868, -1, 1401, 1405, 1863, -1, 1868, 1406, 1869, -1, 1405, 1406, 1868, -1, 1869, 1409, 1871, -1, 1406, 1409, 1869, -1, 1871, 949, 1875, -1, 1409, 949, 1871, -1, 1875, 953, 1420, -1, 949, 953, 1875, -1, 1420, 1093, 1553, -1, 953, 1093, 1420, -1, 1553, 1082, 1546, -1, 1093, 1082, 1553, -1, 1546, 1358, 1817, -1, 1082, 1358, 1546, -1, 1817, 1347, 1809, -1, 1358, 1347, 1817, -1, 1809, 112, 114, -1, 1347, 112, 1809, -1, 110, 1069, 111, -1, 111, 1069, 1533, -1, 1533, 1222, 1684, -1, 1069, 1222, 1533, -1, 1684, 1218, 1679, -1, 1222, 1218, 1684, -1, 1679, 1211, 1674, -1, 1218, 1211, 1679, -1, 1674, 1206, 1668, -1, 1211, 1206, 1674, -1, 1668, 1200, 1661, -1, 1206, 1200, 1668, -1, 1661, 1193, 1655, -1, 1200, 1193, 1661, -1, 1655, 1183, 1645, -1, 1193, 1183, 1655, -1, 1645, 1173, 1635, -1, 1183, 1173, 1645, -1, 1635, 1041, 1503, -1, 1173, 1041, 1635, -1, 1503, 1038, 1500, -1, 1041, 1038, 1503, -1, 1500, 1035, 1497, -1, 1038, 1035, 1500, -1, 1497, 84, 86, -1, 1035, 84, 1497, -1, 82, 1362, 83, -1, 83, 1362, 1824, -1, 1824, 1352, 1812, -1, 1362, 1352, 1824, -1, 1812, 1345, 1806, -1, 1352, 1345, 1812, -1, 1806, 1344, 1805, -1, 1345, 1344, 1806, -1, 1805, 1335, 1797, -1, 1344, 1335, 1805, -1, 1797, 1326, 1786, -1, 1335, 1326, 1797, -1, 1786, 1315, 1774, -1, 1326, 1315, 1786, -1, 1774, 1314, 1773, -1, 1315, 1314, 1774, -1, 1773, 1310, 1771, -1, 1314, 1310, 1773, -1, 1771, 1213, 1676, -1, 1310, 1213, 1771, -1, 1676, 1208, 1672, -1, 1213, 1208, 1676, -1, 1672, 1202, 1666, -1, 1208, 1202, 1672, -1, 1666, 56, 58, -1, 1202, 56, 1666, -1, 54, 1149, 55, -1, 55, 1149, 1611, -1, 1611, 1220, 1681, -1, 1149, 1220, 1611, -1, 1681, 1209, 1671, -1, 1220, 1209, 1681, -1, 1671, 1197, 1658, -1, 1209, 1197, 1671, -1, 1658, 1191, 1653, -1, 1197, 1191, 1658, -1, 1653, 1184, 1644, -1, 1191, 1184, 1653, -1, 1644, 1175, 1637, -1, 1184, 1175, 1644, -1, 1637, 1164, 1626, -1, 1175, 1164, 1637, -1, 1626, 1158, 1620, -1, 1164, 1158, 1626, -1, 1620, 1135, 1596, -1, 1158, 1135, 1620, -1, 1596, 1130, 1592, -1, 1135, 1130, 1596, -1, 1592, 1123, 1585, -1, 1130, 1123, 1592, -1, 1585, 28, 30, -1, 1123, 28, 1585, -1, 26, 1304, 27, -1, 27, 1304, 1766, -1, 1766, 1305, 1767, -1, 1304, 1305, 1766, -1, 1767, 1306, 1768, -1, 1305, 1306, 1767, -1, 1768, 1308, 1770, -1, 1306, 1308, 1768, -1, 1770, 1309, 1763, -1, 1308, 1309, 1770, -1, 1763, 1276, 1735, -1, 1309, 1276, 1763, -1, 1735, 1271, 1730, -1, 1276, 1271, 1735, -1, 1730, 1252, 1714, -1, 1271, 1252, 1730, -1, 1714, 1251, 1713, -1, 1252, 1251, 1714, -1, 1713, 1248, 1709, -1, 1251, 1248, 1713, -1, 1709, 1244, 1706, -1, 1248, 1244, 1709, -1, 1706, 1187, 1647, -1, 1244, 1187, 1706, -1, 1647, 0, 2, -1, 1187, 0, 1647, -1, 1693, 1221, 1682, -1, 1682, 1221, 1673, -1, 1231, 1221, 1693, -1, 1673, 1214, 1662, -1, 1221, 1214, 1673, -1, 1662, 1203, 1667, -1, 1214, 1203, 1662, -1, 1667, 1207, 1678, -1, 1203, 1207, 1667, -1, 1678, 1215, 1687, -1, 1207, 1215, 1678, -1, 1687, 1226, 1705, -1, 1215, 1226, 1687, -1, 1705, 1243, 1707, -1, 1226, 1243, 1705, -1, 1707, 1245, 1711, -1, 1243, 1245, 1707, -1, 1711, 1249, 1729, -1, 1245, 1249, 1711, -1, 1729, 1268, 1734, -1, 1249, 1268, 1729, -1, 1734, 1274, 1739, -1, 1268, 1274, 1734, -1, 1739, 1279, 1762, -1, 1274, 1279, 1739, -1, 1279, 1299, 1762, -1, 1287, 1749, 1299, -1, 1299, 1749, 1762, -1, 1717, 1255, 1693, -1, 1693, 1255, 1231, -1, 1488, 1015, 1477, -1, 1026, 1015, 1488, -1, 1477, 1006, 1468, -1, 1015, 1006, 1477, -1, 1468, 993, 1452, -1, 1006, 993, 1468, -1, 1452, 999, 1463, -1, 993, 999, 1452, -1, 1463, 1012, 1475, -1, 999, 1012, 1463, -1, 1475, 1018, 1480, -1, 1012, 1018, 1475, -1, 1480, 1027, 1489, -1, 1018, 1027, 1480, -1, 1489, 1067, 1528, -1, 1027, 1067, 1489, -1, 1528, 1086, 1547, -1, 1067, 1086, 1528, -1, 1547, 1101, 1563, -1, 1086, 1101, 1547, -1, 1563, 1117, 1579, -1, 1101, 1117, 1563, -1, 1579, 1134, 1597, -1, 1117, 1134, 1579, -1, 1597, 1141, 1603, -1, 1134, 1141, 1597, -1, 1155, 1616, 1141, -1, 1141, 1616, 1603, -1, 1509, 1045, 1488, -1, 1488, 1045, 1026, -1, 1692, 1031, 1494, -1, 1230, 1031, 1692, -1, 1494, 1028, 1491, -1, 1031, 1028, 1494, -1, 1491, 1017, 1479, -1, 1028, 1017, 1491, -1, 1479, 1004, 1467, -1, 1017, 1004, 1479, -1, 1467, 1003, 1466, -1, 1004, 1003, 1467, -1, 1466, 1013, 1474, -1, 1003, 1013, 1466, -1, 1474, 1329, 1791, -1, 1013, 1329, 1474, -1, 1791, 1324, 1787, -1, 1329, 1324, 1791, -1, 1787, 1307, 1769, -1, 1324, 1307, 1787, -1, 1769, 1291, 1753, -1, 1307, 1291, 1769, -1, 1753, 1277, 1741, -1, 1291, 1277, 1753, -1, 1741, 1269, 1732, -1, 1277, 1269, 1741, -1, 1732, 1138, 1601, -1, 1269, 1138, 1732, -1, 1568, 1138, 1102, -1, 1601, 1138, 1568, -1, 1177, 1692, 1643, -1, 1230, 1692, 1177, -1, 1498, 1196, 1659, -1, 1036, 1196, 1498, -1, 1659, 1192, 1654, -1, 1196, 1192, 1659, -1, 1654, 1189, 1652, -1, 1192, 1189, 1654, -1, 1652, 1188, 1651, -1, 1189, 1188, 1652, -1, 1651, 1194, 1657, -1, 1188, 1194, 1651, -1, 1657, 1079, 1539, -1, 1194, 1079, 1657, -1, 1539, 1074, 1534, -1, 1079, 1074, 1539, -1, 1534, 1071, 1529, -1, 1074, 1071, 1534, -1, 1529, 1051, 1511, -1, 1071, 1051, 1529, -1, 1511, 1042, 1504, -1, 1051, 1042, 1511, -1, 1504, 1039, 1501, -1, 1042, 1039, 1504, -1, 1501, 997, 1455, -1, 1039, 997, 1501, -1, 1455, 992, 1449, -1, 997, 992, 1455, -1, 1448, 992, 989, -1, 1449, 992, 1448, -1, 1020, 1498, 1482, -1, 1036, 1498, 1020, -1, 1073, 816, 1536, -1, 1073, 819, 816, -1, 1072, 1536, 1535, -1, 1072, 1073, 1536, -1, 1078, 1535, 1540, -1, 1078, 1072, 1535, -1, 1083, 1540, 1545, -1, 1083, 1078, 1540, -1, 1090, 1545, 1552, -1, 1090, 1083, 1545, -1, 1103, 1552, 1571, -1, 1103, 1090, 1552, -1, 1102, 1571, 1568, -1, 1102, 1103, 1571, -1, 1638, 1181, 1176, -1, 1638, 1646, 1181, -1, 1629, 1176, 1166, -1, 1629, 1638, 1176, -1, 1630, 1166, 1168, -1, 1630, 1629, 1166, -1, 1628, 1168, 1167, -1, 1628, 1630, 1168, -1, 1639, 1167, 1180, -1, 1639, 1628, 1167, -1, 1640, 1180, 1179, -1, 1640, 1639, 1180, -1, 1643, 1179, 1177, -1, 1643, 1640, 1179, -1, 1484, 817, 1023, -1, 1484, 818, 817, -1, 1472, 1023, 1008, -1, 1472, 1484, 1023, -1, 1473, 1008, 1010, -1, 1473, 1472, 1008, -1, 1471, 1010, 1009, -1, 1471, 1473, 1010, -1, 1486, 1009, 1022, -1, 1486, 1471, 1009, -1, 1487, 1022, 1021, -1, 1487, 1486, 1022, -1, 1482, 1021, 1020, -1, 1482, 1487, 1021, -1, 984, 812, 1444, -1, 984, 815, 812, -1, 985, 1444, 1442, -1, 985, 984, 1444, -1, 980, 1442, 1438, -1, 980, 985, 1442, -1, 981, 1438, 1440, -1, 981, 980, 1438, -1, 979, 1440, 1439, -1, 979, 981, 1440, -1, 983, 1439, 1443, -1, 983, 979, 1439, -1, 989, 1443, 1448, -1, 989, 983, 1443, -1, 1526, 1044, 1065, -1, 1526, 1506, 1044, -1, 1527, 1065, 1064, -1, 1527, 1526, 1065, -1, 1531, 1064, 1068, -1, 1531, 1527, 1064, -1, 1530, 1068, 1070, -1, 1530, 1531, 1068, -1, 1532, 1070, 1066, -1, 1532, 1530, 1070, -1, 1522, 1066, 1063, -1, 1522, 1532, 1066, -1, 1509, 1063, 1045, -1, 1509, 1522, 1063, -1, 1171, 820, 1633, -1, 1171, 823, 820, -1, 1172, 1633, 1632, -1, 1172, 1171, 1633, -1, 1157, 1632, 1619, -1, 1157, 1172, 1632, -1, 1152, 1619, 1615, -1, 1152, 1157, 1619, -1, 1153, 1615, 1617, -1, 1153, 1152, 1615, -1, 1154, 1617, 1614, -1, 1154, 1153, 1617, -1, 1155, 1614, 1616, -1, 1155, 1154, 1614, -1, 1719, 821, 1264, -1, 1719, 822, 821, -1, 1720, 1264, 1263, -1, 1720, 1719, 1264, -1, 1726, 1263, 1266, -1, 1726, 1720, 1263, -1, 1725, 1266, 1265, -1, 1725, 1726, 1266, -1, 1721, 1265, 1258, -1, 1721, 1725, 1265, -1, 1722, 1258, 1259, -1, 1722, 1721, 1258, -1, 1717, 1259, 1255, -1, 1717, 1722, 1259, -1, 1297, 824, 1759, -1, 1297, 827, 824, -1, 1292, 1756, 1755, -1, 1292, 1759, 1756, -1, 1292, 1297, 1759, -1, 1293, 1755, 1752, -1, 1293, 1292, 1755, -1, 1288, 1752, 1748, -1, 1288, 1293, 1752, -1, 1285, 1748, 1747, -1, 1285, 1288, 1748, -1, 1286, 1747, 1749, -1, 1286, 1285, 1747, -1, 1287, 1286, 1749, -1, 1876, 1877, 1878, -1, 1878, 1877, 1879, -1, 1879, 1880, 1881, -1, 1877, 1880, 1879, -1, 1881, 1882, 1883, -1, 1880, 1882, 1881, -1, 1883, 1884, 1885, -1, 1882, 1884, 1883, -1, 1885, 1886, 1887, -1, 1884, 1886, 1885, -1, 1887, 1888, 1889, -1, 1886, 1888, 1887, -1, 1889, 1890, 1891, -1, 1888, 1890, 1889, -1, 1891, 1892, 1893, -1, 1890, 1892, 1891, -1, 1893, 1894, 1895, -1, 1892, 1894, 1893, -1, 1895, 1896, 1897, -1, 1894, 1896, 1895, -1, 1897, 1898, 1899, -1, 1896, 1898, 1897, -1, 1899, 1900, 1901, -1, 1898, 1900, 1899, -1, 1901, 1902, 1903, -1, 1900, 1902, 1901, -1, 1904, 1905, 1906, -1, 1906, 1905, 1907, -1, 1907, 1908, 1909, -1, 1905, 1908, 1907, -1, 1909, 1910, 1911, -1, 1908, 1910, 1909, -1, 1911, 1912, 1913, -1, 1910, 1912, 1911, -1, 1913, 1914, 1915, -1, 1912, 1914, 1913, -1, 1915, 1916, 1917, -1, 1914, 1916, 1915, -1, 1917, 1918, 1919, -1, 1916, 1918, 1917, -1, 1919, 1920, 1921, -1, 1918, 1920, 1919, -1, 1921, 1922, 1923, -1, 1920, 1922, 1921, -1, 1923, 1924, 1925, -1, 1922, 1924, 1923, -1, 1925, 1926, 1927, -1, 1924, 1926, 1925, -1, 1927, 1928, 1929, -1, 1926, 1928, 1927, -1, 1929, 1930, 1931, -1, 1928, 1930, 1929, -1, 1932, 1933, 1934, -1, 1934, 1933, 1935, -1, 1935, 1936, 1937, -1, 1933, 1936, 1935, -1, 1937, 1938, 1939, -1, 1936, 1938, 1937, -1, 1939, 1940, 1941, -1, 1938, 1940, 1939, -1, 1941, 1942, 1943, -1, 1940, 1942, 1941, -1, 1943, 1944, 1945, -1, 1942, 1944, 1943, -1, 1945, 1946, 1947, -1, 1944, 1946, 1945, -1, 1947, 1948, 1949, -1, 1946, 1948, 1947, -1, 1949, 1950, 1951, -1, 1948, 1950, 1949, -1, 1951, 1952, 1953, -1, 1950, 1952, 1951, -1, 1953, 1954, 1955, -1, 1952, 1954, 1953, -1, 1955, 1956, 1957, -1, 1954, 1956, 1955, -1, 1957, 1958, 1959, -1, 1956, 1958, 1957, -1, 1960, 1961, 1962, -1, 1962, 1961, 1963, -1, 1963, 1964, 1965, -1, 1961, 1964, 1963, -1, 1965, 1966, 1967, -1, 1964, 1966, 1965, -1, 1967, 1968, 1969, -1, 1966, 1968, 1967, -1, 1969, 1970, 1971, -1, 1968, 1970, 1969, -1, 1971, 1972, 1973, -1, 1970, 1972, 1971, -1, 1973, 1974, 1975, -1, 1972, 1974, 1973, -1, 1975, 1976, 1977, -1, 1974, 1976, 1975, -1, 1977, 1978, 1979, -1, 1976, 1978, 1977, -1, 1979, 1980, 1981, -1, 1978, 1980, 1979, -1, 1981, 1982, 1983, -1, 1980, 1982, 1981, -1, 1983, 1984, 1985, -1, 1982, 1984, 1983, -1, 1985, 1986, 1987, -1, 1984, 1986, 1985, -1, 1988, 1989, 1990, -1, 1990, 1989, 1991, -1, 1991, 1992, 1993, -1, 1989, 1992, 1991, -1, 1993, 1994, 1995, -1, 1992, 1994, 1993, -1, 1995, 1996, 1997, -1, 1994, 1996, 1995, -1, 1997, 1998, 1999, -1, 1996, 1998, 1997, -1, 1999, 2000, 2001, -1, 1998, 2000, 1999, -1, 2001, 2002, 2003, -1, 2000, 2002, 2001, -1, 2003, 2004, 2005, -1, 2002, 2004, 2003, -1, 2005, 2006, 2007, -1, 2004, 2006, 2005, -1, 2007, 2008, 2009, -1, 2006, 2008, 2007, -1, 2009, 2010, 2011, -1, 2008, 2010, 2009, -1, 2011, 2012, 2013, -1, 2010, 2012, 2011, -1, 2013, 2014, 2015, -1, 2012, 2014, 2013, -1, 2016, 2017, 2018, -1, 2018, 2017, 2019, -1, 2019, 2020, 2021, -1, 2017, 2020, 2019, -1, 2021, 2022, 2023, -1, 2020, 2022, 2021, -1, 2023, 2024, 2025, -1, 2022, 2024, 2023, -1, 2025, 2026, 2027, -1, 2024, 2026, 2025, -1, 2027, 2028, 2029, -1, 2026, 2028, 2027, -1, 2029, 2030, 2031, -1, 2028, 2030, 2029, -1, 2031, 2032, 2033, -1, 2030, 2032, 2031, -1, 2033, 2034, 2035, -1, 2032, 2034, 2033, -1, 2035, 2036, 2037, -1, 2034, 2036, 2035, -1, 2037, 2038, 2039, -1, 2036, 2038, 2037, -1, 2039, 2040, 2041, -1, 2038, 2040, 2039, -1, 2041, 2042, 2043, -1, 2040, 2042, 2041, -1, 2044, 2045, 2046, -1, 2046, 2045, 2047, -1, 2047, 2048, 2049, -1, 2045, 2048, 2047, -1, 2049, 2050, 2051, -1, 2048, 2050, 2049, -1, 2051, 2052, 2053, -1, 2050, 2052, 2051, -1, 2053, 2054, 2055, -1, 2052, 2054, 2053, -1, 2055, 2056, 2057, -1, 2054, 2056, 2055, -1, 2057, 2058, 2059, -1, 2056, 2058, 2057, -1, 2059, 2060, 2061, -1, 2058, 2060, 2059, -1, 2061, 2062, 2063, -1, 2060, 2062, 2061, -1, 2063, 2064, 2065, -1, 2062, 2064, 2063, -1, 2065, 2066, 2067, -1, 2064, 2066, 2065, -1, 2067, 2068, 2069, -1, 2066, 2068, 2067, -1, 2069, 2070, 2071, -1, 2068, 2070, 2069, -1, 2072, 2073, 2074, -1, 2074, 2073, 2075, -1, 2075, 2076, 2077, -1, 2073, 2076, 2075, -1, 2077, 2078, 2079, -1, 2076, 2078, 2077, -1, 2079, 2080, 2081, -1, 2078, 2080, 2079, -1, 2081, 2082, 2083, -1, 2080, 2082, 2081, -1, 2083, 2084, 2085, -1, 2082, 2084, 2083, -1, 2085, 2086, 2087, -1, 2084, 2086, 2085, -1, 2087, 2088, 2089, -1, 2086, 2088, 2087, -1, 2089, 2090, 2091, -1, 2088, 2090, 2089, -1, 2091, 2092, 2093, -1, 2090, 2092, 2091, -1, 2093, 2094, 2095, -1, 2092, 2094, 2093, -1, 2095, 2096, 2097, -1, 2094, 2096, 2095, -1, 2097, 2098, 2099, -1, 2096, 2098, 2097, -1, 2100, 2101, 2102, -1, 2102, 2101, 2103, -1, 2103, 2104, 2105, -1, 2101, 2104, 2103, -1, 2105, 2106, 2107, -1, 2104, 2106, 2105, -1, 2107, 2108, 2109, -1, 2106, 2108, 2107, -1, 2109, 2110, 2111, -1, 2108, 2110, 2109, -1, 2111, 2112, 2113, -1, 2110, 2112, 2111, -1, 2113, 2114, 2115, -1, 2112, 2114, 2113, -1, 2115, 2116, 2117, -1, 2114, 2116, 2115, -1, 2117, 2118, 2119, -1, 2116, 2118, 2117, -1, 2119, 2120, 2121, -1, 2118, 2120, 2119, -1, 2121, 2122, 2123, -1, 2120, 2122, 2121, -1, 2123, 2124, 2125, -1, 2122, 2124, 2123, -1, 2125, 2126, 2127, -1, 2124, 2126, 2125, -1, 2128, 2129, 2130, -1, 2130, 2129, 2131, -1, 2131, 2132, 2133, -1, 2129, 2132, 2131, -1, 2133, 2134, 2135, -1, 2132, 2134, 2133, -1, 2135, 2136, 2137, -1, 2134, 2136, 2135, -1, 2137, 2138, 2139, -1, 2136, 2138, 2137, -1, 2139, 2140, 2141, -1, 2138, 2140, 2139, -1, 2141, 2142, 2143, -1, 2140, 2142, 2141, -1, 2143, 2144, 2145, -1, 2142, 2144, 2143, -1, 2145, 2146, 2147, -1, 2144, 2146, 2145, -1, 2147, 2148, 2149, -1, 2146, 2148, 2147, -1, 2149, 2150, 2151, -1, 2148, 2150, 2149, -1, 2151, 2152, 2153, -1, 2150, 2152, 2151, -1, 2153, 2154, 2155, -1, 2152, 2154, 2153, -1, 2156, 2157, 2158, -1, 2158, 2157, 2159, -1, 2159, 2160, 2161, -1, 2157, 2160, 2159, -1, 2161, 2162, 2163, -1, 2160, 2162, 2161, -1, 2163, 2164, 2165, -1, 2162, 2164, 2163, -1, 2165, 2166, 2167, -1, 2164, 2166, 2165, -1, 2167, 2168, 2169, -1, 2166, 2168, 2167, -1, 2169, 2170, 2171, -1, 2168, 2170, 2169, -1, 2171, 2172, 2173, -1, 2170, 2172, 2171, -1, 2173, 2174, 2175, -1, 2172, 2174, 2173, -1, 2175, 2176, 2177, -1, 2174, 2176, 2175, -1, 2177, 2178, 2179, -1, 2176, 2178, 2177, -1, 2179, 2180, 2181, -1, 2178, 2180, 2179, -1, 2181, 2182, 2183, -1, 2180, 2182, 2181, -1, 2184, 2185, 2186, -1, 2186, 2185, 2187, -1, 2187, 2188, 2189, -1, 2185, 2188, 2187, -1, 2189, 2190, 2191, -1, 2188, 2190, 2189, -1, 2191, 2192, 2193, -1, 2190, 2192, 2191, -1, 2193, 2194, 2195, -1, 2192, 2194, 2193, -1, 2195, 2196, 2197, -1, 2194, 2196, 2195, -1, 2197, 2198, 2199, -1, 2196, 2198, 2197, -1, 2199, 2200, 2201, -1, 2198, 2200, 2199, -1, 2201, 2202, 2203, -1, 2200, 2202, 2201, -1, 2203, 2204, 2205, -1, 2202, 2204, 2203, -1, 2205, 2206, 2207, -1, 2204, 2206, 2205, -1, 2207, 2208, 2209, -1, 2206, 2208, 2207, -1, 2209, 2210, 2211, -1, 2208, 2210, 2209, -1, 2212, 2213, 2214, -1, 2214, 2213, 2215, -1, 2215, 2216, 2217, -1, 2213, 2216, 2215, -1, 2217, 2218, 2219, -1, 2216, 2218, 2217, -1, 2219, 2220, 2221, -1, 2218, 2220, 2219, -1, 2221, 2222, 2223, -1, 2220, 2222, 2221, -1, 2223, 2224, 2225, -1, 2222, 2224, 2223, -1, 2225, 2226, 2227, -1, 2224, 2226, 2225, -1, 2227, 2228, 2229, -1, 2226, 2228, 2227, -1, 2229, 2230, 2231, -1, 2228, 2230, 2229, -1, 2231, 2232, 2233, -1, 2230, 2232, 2231, -1, 2233, 2234, 2235, -1, 2232, 2234, 2233, -1, 2235, 2236, 2237, -1, 2234, 2236, 2235, -1, 2237, 2238, 2239, -1, 2236, 2238, 2237, -1, 2240, 2241, 2242, -1, 2242, 2241, 2243, -1, 2243, 2244, 2245, -1, 2241, 2244, 2243, -1, 2245, 2246, 2247, -1, 2244, 2246, 2245, -1, 2247, 2248, 2249, -1, 2246, 2248, 2247, -1, 2249, 2250, 2251, -1, 2248, 2250, 2249, -1, 2251, 2252, 2253, -1, 2250, 2252, 2251, -1, 2253, 2254, 2255, -1, 2252, 2254, 2253, -1, 2255, 2256, 2257, -1, 2254, 2256, 2255, -1, 2257, 2258, 2259, -1, 2256, 2258, 2257, -1, 2259, 2260, 2261, -1, 2258, 2260, 2259, -1, 2261, 2262, 2263, -1, 2260, 2262, 2261, -1, 2263, 2264, 2265, -1, 2262, 2264, 2263, -1, 2265, 2266, 2267, -1, 2264, 2266, 2265, -1, 2268, 2269, 2270, -1, 2270, 2269, 2271, -1, 2271, 2272, 2273, -1, 2269, 2272, 2271, -1, 2273, 2274, 2275, -1, 2272, 2274, 2273, -1, 2275, 2276, 2277, -1, 2274, 2276, 2275, -1, 2277, 2278, 2279, -1, 2276, 2278, 2277, -1, 2279, 2280, 2281, -1, 2278, 2280, 2279, -1, 2281, 2282, 2283, -1, 2280, 2282, 2281, -1, 2283, 2284, 2285, -1, 2282, 2284, 2283, -1, 2285, 2286, 2287, -1, 2284, 2286, 2285, -1, 2287, 2288, 2289, -1, 2286, 2288, 2287, -1, 2289, 2290, 2291, -1, 2288, 2290, 2289, -1, 2291, 2292, 2293, -1, 2290, 2292, 2291, -1, 2293, 2294, 2295, -1, 2292, 2294, 2293, -1, 2296, 2297, 2298, -1, 2298, 2297, 2299, -1, 2299, 2300, 2301, -1, 2297, 2300, 2299, -1, 2301, 2302, 2303, -1, 2300, 2302, 2301, -1, 2303, 2304, 2305, -1, 2302, 2304, 2303, -1, 2305, 2306, 2307, -1, 2304, 2306, 2305, -1, 2307, 2308, 2309, -1, 2306, 2308, 2307, -1, 2309, 2310, 2311, -1, 2308, 2310, 2309, -1, 2311, 2312, 2313, -1, 2310, 2312, 2311, -1, 2313, 2314, 2315, -1, 2312, 2314, 2313, -1, 2315, 2316, 2317, -1, 2314, 2316, 2315, -1, 2317, 2318, 2319, -1, 2316, 2318, 2317, -1, 2319, 2320, 2321, -1, 2318, 2320, 2319, -1, 2321, 2322, 2323, -1, 2320, 2322, 2321, -1, 2324, 2325, 2326, -1, 2326, 2325, 2327, -1, 2327, 2328, 2329, -1, 2325, 2328, 2327, -1, 2329, 2330, 2331, -1, 2328, 2330, 2329, -1, 2331, 2332, 2333, -1, 2330, 2332, 2331, -1, 2333, 2334, 2335, -1, 2332, 2334, 2333, -1, 2335, 2336, 2337, -1, 2334, 2336, 2335, -1, 2337, 2338, 2339, -1, 2336, 2338, 2337, -1, 2339, 2340, 2341, -1, 2338, 2340, 2339, -1, 2341, 2342, 2343, -1, 2340, 2342, 2341, -1, 2343, 2344, 2345, -1, 2342, 2344, 2343, -1, 2345, 2346, 2347, -1, 2344, 2346, 2345, -1, 2347, 2348, 2349, -1, 2346, 2348, 2347, -1, 2349, 2350, 2351, -1, 2348, 2350, 2349, -1, 2352, 2353, 2354, -1, 2354, 2353, 2355, -1, 2355, 2356, 2357, -1, 2353, 2356, 2355, -1, 2357, 2358, 2359, -1, 2356, 2358, 2357, -1, 2359, 2360, 2361, -1, 2358, 2360, 2359, -1, 2361, 2362, 2363, -1, 2360, 2362, 2361, -1, 2363, 2364, 2365, -1, 2362, 2364, 2363, -1, 2365, 2366, 2367, -1, 2364, 2366, 2365, -1, 2367, 2368, 2369, -1, 2366, 2368, 2367, -1, 2369, 2370, 2371, -1, 2368, 2370, 2369, -1, 2371, 2372, 2373, -1, 2370, 2372, 2371, -1, 2373, 2374, 2375, -1, 2372, 2374, 2373, -1, 2375, 2376, 2377, -1, 2374, 2376, 2375, -1, 2377, 2378, 2379, -1, 2376, 2378, 2377, -1, 2380, 2381, 2382, -1, 2382, 2381, 2383, -1, 2383, 2384, 2385, -1, 2381, 2384, 2383, -1, 2385, 2386, 2387, -1, 2384, 2386, 2385, -1, 2387, 2388, 2389, -1, 2386, 2388, 2387, -1, 2389, 2390, 2391, -1, 2388, 2390, 2389, -1, 2391, 2392, 2393, -1, 2390, 2392, 2391, -1, 2393, 2394, 2395, -1, 2392, 2394, 2393, -1, 2395, 2396, 2397, -1, 2394, 2396, 2395, -1, 2397, 2398, 2399, -1, 2396, 2398, 2397, -1, 2399, 2400, 2401, -1, 2398, 2400, 2399, -1, 2401, 2402, 2403, -1, 2400, 2402, 2401, -1, 2403, 2404, 2405, -1, 2402, 2404, 2403, -1, 2405, 2406, 2407, -1, 2404, 2406, 2405, -1, 2408, 2409, 2410, -1, 2410, 2409, 2411, -1, 2411, 2412, 2413, -1, 2409, 2412, 2411, -1, 2413, 2414, 2415, -1, 2412, 2414, 2413, -1, 2415, 2416, 2417, -1, 2414, 2416, 2415, -1, 2417, 2418, 2419, -1, 2416, 2418, 2417, -1, 2419, 2420, 2421, -1, 2418, 2420, 2419, -1, 2421, 2422, 2423, -1, 2420, 2422, 2421, -1, 2423, 2424, 2425, -1, 2422, 2424, 2423, -1, 2425, 2426, 2427, -1, 2424, 2426, 2425, -1, 2427, 2428, 2429, -1, 2426, 2428, 2427, -1, 2429, 2430, 2431, -1, 2428, 2430, 2429, -1, 2431, 2432, 2433, -1, 2430, 2432, 2431, -1, 2433, 2434, 2435, -1, 2432, 2434, 2433, -1, 2436, 2437, 2438, -1, 2438, 2437, 2439, -1, 2439, 2440, 2441, -1, 2437, 2440, 2439, -1, 2441, 2442, 2443, -1, 2440, 2442, 2441, -1, 2443, 2444, 2445, -1, 2442, 2444, 2443, -1, 2445, 2446, 2447, -1, 2444, 2446, 2445, -1, 2447, 2448, 2449, -1, 2446, 2448, 2447, -1, 2449, 2450, 2451, -1, 2448, 2450, 2449, -1, 2451, 2452, 2453, -1, 2450, 2452, 2451, -1, 2453, 2454, 2455, -1, 2452, 2454, 2453, -1, 2455, 2456, 2457, -1, 2454, 2456, 2455, -1, 2457, 2458, 2459, -1, 2456, 2458, 2457, -1, 2459, 2460, 2461, -1, 2458, 2460, 2459, -1, 2461, 2462, 2463, -1, 2460, 2462, 2461, -1, 2464, 2465, 2466, -1, 2466, 2465, 2467, -1, 2467, 2468, 2469, -1, 2465, 2468, 2467, -1, 2469, 2470, 2471, -1, 2468, 2470, 2469, -1, 2471, 2472, 2473, -1, 2470, 2472, 2471, -1, 2473, 2474, 2475, -1, 2472, 2474, 2473, -1, 2475, 2476, 2477, -1, 2474, 2476, 2475, -1, 2477, 2478, 2479, -1, 2476, 2478, 2477, -1, 2479, 2480, 2481, -1, 2478, 2480, 2479, -1, 2481, 2482, 2483, -1, 2480, 2482, 2481, -1, 2483, 2484, 2485, -1, 2482, 2484, 2483, -1, 2485, 2486, 2487, -1, 2484, 2486, 2485, -1, 2487, 2488, 2489, -1, 2486, 2488, 2487, -1, 2489, 2490, 2491, -1, 2488, 2490, 2489, -1, 2492, 2493, 2494, -1, 2494, 2493, 2495, -1, 2495, 2496, 2497, -1, 2493, 2496, 2495, -1, 2497, 2498, 2499, -1, 2496, 2498, 2497, -1, 2499, 2500, 2501, -1, 2498, 2500, 2499, -1, 2501, 2502, 2503, -1, 2500, 2502, 2501, -1, 2503, 2504, 2505, -1, 2502, 2504, 2503, -1, 2505, 2506, 2507, -1, 2504, 2506, 2505, -1, 2507, 2508, 2509, -1, 2506, 2508, 2507, -1, 2509, 2510, 2511, -1, 2508, 2510, 2509, -1, 2511, 2512, 2513, -1, 2510, 2512, 2511, -1, 2513, 2514, 2515, -1, 2512, 2514, 2513, -1, 2515, 2516, 2517, -1, 2514, 2516, 2515, -1, 2517, 2518, 2519, -1, 2516, 2518, 2517, -1, 2520, 2521, 2522, -1, 2522, 2521, 2523, -1, 2523, 2524, 2525, -1, 2521, 2524, 2523, -1, 2525, 2526, 2527, -1, 2524, 2526, 2525, -1, 2527, 2528, 2529, -1, 2526, 2528, 2527, -1, 2529, 2530, 2531, -1, 2528, 2530, 2529, -1, 2531, 2532, 2533, -1, 2530, 2532, 2531, -1, 2533, 2534, 2535, -1, 2532, 2534, 2533, -1, 2535, 2536, 2537, -1, 2534, 2536, 2535, -1, 2537, 2538, 2539, -1, 2536, 2538, 2537, -1, 2539, 2540, 2541, -1, 2538, 2540, 2539, -1, 2541, 2542, 2543, -1, 2540, 2542, 2541, -1, 2543, 2544, 2545, -1, 2542, 2544, 2543, -1, 2545, 2546, 2547, -1, 2544, 2546, 2545, -1, 2548, 2549, 2550, -1, 2550, 2549, 2551, -1, 2551, 2552, 2553, -1, 2549, 2552, 2551, -1, 2553, 2554, 2555, -1, 2552, 2554, 2553, -1, 2555, 2556, 2557, -1, 2554, 2556, 2555, -1, 2557, 2558, 2559, -1, 2556, 2558, 2557, -1, 2559, 2560, 2561, -1, 2558, 2560, 2559, -1, 2561, 2562, 2563, -1, 2560, 2562, 2561, -1, 2563, 2564, 2565, -1, 2562, 2564, 2563, -1, 2565, 2566, 2567, -1, 2564, 2566, 2565, -1, 2567, 2568, 2569, -1, 2566, 2568, 2567, -1, 2569, 2570, 2571, -1, 2568, 2570, 2569, -1, 2571, 2572, 2573, -1, 2570, 2572, 2571, -1, 2573, 2574, 2575, -1, 2572, 2574, 2573, -1, 2576, 2577, 2578, -1, 2578, 2577, 2579, -1, 2579, 2580, 2581, -1, 2577, 2580, 2579, -1, 2581, 2582, 2583, -1, 2580, 2582, 2581, -1, 2583, 2584, 2585, -1, 2582, 2584, 2583, -1, 2585, 2586, 2587, -1, 2584, 2586, 2585, -1, 2587, 2588, 2589, -1, 2586, 2588, 2587, -1, 2589, 2590, 2591, -1, 2588, 2590, 2589, -1, 2591, 2592, 2593, -1, 2590, 2592, 2591, -1, 2593, 2594, 2595, -1, 2592, 2594, 2593, -1, 2595, 2596, 2597, -1, 2594, 2596, 2595, -1, 2597, 2598, 2599, -1, 2596, 2598, 2597, -1, 2599, 2600, 2601, -1, 2598, 2600, 2599, -1, 2601, 2602, 2603, -1, 2600, 2602, 2601, -1, 2604, 2605, 2606, -1, 2606, 2605, 2607, -1, 2607, 2608, 2609, -1, 2605, 2608, 2607, -1, 2609, 2610, 2611, -1, 2608, 2610, 2609, -1, 2611, 2612, 2613, -1, 2610, 2612, 2611, -1, 2613, 2614, 2615, -1, 2612, 2614, 2613, -1, 2615, 2616, 2617, -1, 2614, 2616, 2615, -1, 2617, 2618, 2619, -1, 2616, 2618, 2617, -1, 2619, 2620, 2621, -1, 2618, 2620, 2619, -1, 2621, 2622, 2623, -1, 2620, 2622, 2621, -1, 2623, 2624, 2625, -1, 2622, 2624, 2623, -1, 2625, 2626, 2627, -1, 2624, 2626, 2625, -1, 2627, 2628, 2629, -1, 2626, 2628, 2627, -1, 2629, 2630, 2631, -1, 2628, 2630, 2629, -1, 2632, 2633, 2634, -1, 2634, 2633, 2635, -1, 2635, 2636, 2637, -1, 2633, 2636, 2635, -1, 2637, 2638, 2639, -1, 2636, 2638, 2637, -1, 2639, 2640, 2641, -1, 2638, 2640, 2639, -1, 2641, 2642, 2643, -1, 2640, 2642, 2641, -1, 2643, 2644, 2645, -1, 2642, 2644, 2643, -1, 2645, 2646, 2647, -1, 2644, 2646, 2645, -1, 2647, 2648, 2649, -1, 2646, 2648, 2647, -1, 2649, 2650, 2651, -1, 2648, 2650, 2649, -1, 2651, 2652, 2653, -1, 2650, 2652, 2651, -1, 2653, 2654, 2655, -1, 2652, 2654, 2653, -1, 2655, 2656, 2657, -1, 2654, 2656, 2655, -1, 2657, 2658, 2659, -1, 2656, 2658, 2657, -1, 2660, 2661, 2662, -1, 2662, 2661, 2663, -1, 2663, 2664, 2665, -1, 2661, 2664, 2663, -1, 2665, 2666, 2667, -1, 2664, 2666, 2665, -1, 2667, 2668, 2669, -1, 2666, 2668, 2667, -1, 2669, 2670, 2671, -1, 2668, 2670, 2669, -1, 2671, 2672, 2673, -1, 2670, 2672, 2671, -1, 2673, 2674, 2675, -1, 2672, 2674, 2673, -1, 2675, 2676, 2677, -1, 2674, 2676, 2675, -1, 2677, 2678, 2679, -1, 2676, 2678, 2677, -1, 2679, 2680, 2681, -1, 2678, 2680, 2679, -1, 2681, 2682, 2683, -1, 2680, 2682, 2681, -1, 2683, 2684, 2685, -1, 2682, 2684, 2683, -1, 2685, 2686, 2687, -1, 2684, 2686, 2685, -1, 2688, 2689, 2690, -1, 2691, 2689, 2688, -1, 2692, 2693, 2694, -1, 2695, 2693, 2692, -1, 2696, 2697, 2698, -1, 2699, 2697, 2696, -1, 2700, 2701, 2702, -1, 2703, 2701, 2700, -1, 2686, 2704, 2687, -1, 2687, 2704, 2705, -1, 2705, 2706, 2707, -1, 2704, 2706, 2705, -1, 2707, 2708, 2709, -1, 2706, 2708, 2707, -1, 2709, 2710, 2711, -1, 2708, 2710, 2709, -1, 2711, 2712, 2713, -1, 2710, 2712, 2711, -1, 2713, 2714, 2715, -1, 2712, 2714, 2713, -1, 2715, 2716, 2717, -1, 2714, 2716, 2715, -1, 2717, 2718, 2719, -1, 2716, 2718, 2717, -1, 2719, 2720, 2721, -1, 2718, 2720, 2719, -1, 2721, 2722, 2723, -1, 2720, 2722, 2721, -1, 2723, 2724, 2725, -1, 2722, 2724, 2723, -1, 2725, 2726, 2727, -1, 2724, 2726, 2725, -1, 2727, 2660, 2662, -1, 2726, 2660, 2727, -1, 2658, 2728, 2659, -1, 2659, 2728, 2729, -1, 2729, 2730, 2731, -1, 2728, 2730, 2729, -1, 2731, 2732, 2733, -1, 2730, 2732, 2731, -1, 2733, 2734, 2735, -1, 2732, 2734, 2733, -1, 2735, 2736, 2737, -1, 2734, 2736, 2735, -1, 2737, 2738, 2739, -1, 2736, 2738, 2737, -1, 2739, 2740, 2741, -1, 2738, 2740, 2739, -1, 2741, 2742, 2743, -1, 2740, 2742, 2741, -1, 2743, 2744, 2745, -1, 2742, 2744, 2743, -1, 2745, 2746, 2747, -1, 2744, 2746, 2745, -1, 2747, 2748, 2749, -1, 2746, 2748, 2747, -1, 2749, 2750, 2751, -1, 2748, 2750, 2749, -1, 2751, 2632, 2634, -1, 2750, 2632, 2751, -1, 2630, 2752, 2631, -1, 2631, 2752, 2753, -1, 2753, 2754, 2755, -1, 2752, 2754, 2753, -1, 2755, 2756, 2757, -1, 2754, 2756, 2755, -1, 2757, 2758, 2759, -1, 2756, 2758, 2757, -1, 2759, 2760, 2761, -1, 2758, 2760, 2759, -1, 2761, 2762, 2763, -1, 2760, 2762, 2761, -1, 2763, 2764, 2765, -1, 2762, 2764, 2763, -1, 2765, 2766, 2767, -1, 2764, 2766, 2765, -1, 2767, 2768, 2769, -1, 2766, 2768, 2767, -1, 2769, 2770, 2771, -1, 2768, 2770, 2769, -1, 2771, 2772, 2773, -1, 2770, 2772, 2771, -1, 2773, 2774, 2775, -1, 2772, 2774, 2773, -1, 2775, 2604, 2606, -1, 2774, 2604, 2775, -1, 2602, 2776, 2603, -1, 2603, 2776, 2777, -1, 2777, 2778, 2779, -1, 2776, 2778, 2777, -1, 2779, 2780, 2781, -1, 2778, 2780, 2779, -1, 2781, 2782, 2783, -1, 2780, 2782, 2781, -1, 2783, 2784, 2785, -1, 2782, 2784, 2783, -1, 2785, 2786, 2787, -1, 2784, 2786, 2785, -1, 2787, 2788, 2789, -1, 2786, 2788, 2787, -1, 2789, 2790, 2791, -1, 2788, 2790, 2789, -1, 2791, 2792, 2793, -1, 2790, 2792, 2791, -1, 2793, 2794, 2795, -1, 2792, 2794, 2793, -1, 2795, 2796, 2797, -1, 2794, 2796, 2795, -1, 2797, 2798, 2799, -1, 2796, 2798, 2797, -1, 2799, 2576, 2578, -1, 2798, 2576, 2799, -1, 2574, 2800, 2575, -1, 2575, 2800, 2801, -1, 2801, 2802, 2803, -1, 2800, 2802, 2801, -1, 2803, 2804, 2805, -1, 2802, 2804, 2803, -1, 2805, 2806, 2807, -1, 2804, 2806, 2805, -1, 2807, 2808, 2809, -1, 2806, 2808, 2807, -1, 2809, 2810, 2811, -1, 2808, 2810, 2809, -1, 2811, 2812, 2813, -1, 2810, 2812, 2811, -1, 2813, 2814, 2815, -1, 2812, 2814, 2813, -1, 2815, 2816, 2817, -1, 2814, 2816, 2815, -1, 2817, 2818, 2819, -1, 2816, 2818, 2817, -1, 2819, 2820, 2821, -1, 2818, 2820, 2819, -1, 2821, 2822, 2823, -1, 2820, 2822, 2821, -1, 2823, 2548, 2550, -1, 2822, 2548, 2823, -1, 2338, 2824, 2825, -1, 2826, 2827, 2828, -1, 2338, 2336, 2824, -1, 2439, 2829, 2830, -1, 2439, 2441, 2829, -1, 2826, 2831, 2832, -1, 2826, 2828, 2831, -1, 2833, 2834, 2835, -1, 1966, 2836, 2837, -1, 2833, 2835, 2324, -1, 2340, 2838, 2839, -1, 2340, 2338, 2825, -1, 2438, 2830, 2466, -1, 2438, 2439, 2830, -1, 2340, 2825, 2838, -1, 2438, 2466, 2840, -1, 1968, 1966, 2837, -1, 2841, 2842, 2843, -1, 2841, 2843, 2844, -1, 2845, 2846, 2827, -1, 2841, 2844, 2847, -1, 2841, 2847, 2848, -1, 2841, 2848, 2849, -1, 2845, 2850, 2846, -1, 2841, 2849, 2689, -1, 1964, 2851, 2836, -1, 2342, 2340, 2839, -1, 1964, 2836, 1966, -1, 2342, 2839, 2852, -1, 1970, 2837, 2853, -1, 2854, 2832, 2855, -1, 2344, 2342, 2852, -1, 1970, 1968, 2837, -1, 2344, 2852, 2856, -1, 1961, 2686, 2684, -1, 2854, 2826, 2832, -1, 2857, 2850, 2845, -1, 2857, 2858, 2850, -1, 1961, 2684, 2851, -1, 1961, 2851, 1964, -1, 2859, 2854, 2855, -1, 2346, 2856, 2860, -1, 2859, 2855, 2861, -1, 1972, 2853, 2862, -1, 2346, 2344, 2856, -1, 2556, 2863, 2864, -1, 2865, 2691, 2866, -1, 1972, 1970, 2853, -1, 2865, 2866, 2867, -1, 2865, 2867, 2868, -1, 2865, 2868, 2869, -1, 2865, 2869, 2870, -1, 2865, 2870, 2871, -1, 2872, 2858, 2857, -1, 2873, 2689, 2691, -1, 2556, 2554, 2863, -1, 2874, 2861, 2322, -1, 1960, 2686, 1961, -1, 2873, 2691, 2865, -1, 2552, 2875, 2863, -1, 2874, 2859, 2861, -1, 1974, 2862, 2876, -1, 2877, 2689, 2873, -1, 2552, 2863, 2554, -1, 1974, 1972, 2862, -1, 2558, 2864, 2878, -1, 1974, 2876, 2879, -1, 2880, 2686, 1960, -1, 2880, 2704, 2686, -1, 2558, 2556, 2864, -1, 1976, 2879, 2840, -1, 2549, 2881, 2875, -1, 1976, 1974, 2879, -1, 2549, 2875, 2552, -1, 2162, 2882, 2883, -1, 2884, 2706, 2704, -1, 2884, 2704, 2880, -1, 2560, 2558, 2878, -1, 2560, 2878, 2788, -1, 1978, 1976, 2840, -1, 2885, 2886, 2887, -1, 2885, 2887, 2888, -1, 2164, 2883, 2889, -1, 2164, 2162, 2883, -1, 2548, 2881, 2549, -1, 2106, 2262, 2260, -1, 2890, 2708, 2706, -1, 2890, 2706, 2884, -1, 2160, 2318, 2882, -1, 2108, 2106, 2260, -1, 2160, 2882, 2162, -1, 1980, 1978, 2840, -1, 2108, 2260, 2258, -1, 2562, 2788, 2786, -1, 2891, 2885, 2888, -1, 2562, 2560, 2788, -1, 2108, 2258, 2693, -1, 2892, 2888, 2893, -1, 2822, 2894, 2881, -1, 2104, 2264, 2262, -1, 2822, 2881, 2548, -1, 2892, 2891, 2888, -1, 2104, 2262, 2106, -1, 1982, 1980, 2840, -1, 2166, 2889, 2895, -1, 2693, 2892, 2893, -1, 2166, 2164, 2889, -1, 2695, 2116, 2114, -1, 2110, 2108, 2693, -1, 2695, 2114, 2693, -1, 2564, 2786, 2784, -1, 2695, 2896, 2116, -1, 2564, 2562, 2786, -1, 2101, 2266, 2264, -1, 2897, 2858, 2872, -1, 2820, 2898, 2894, -1, 2101, 2264, 2104, -1, 2897, 2872, 2899, -1, 2820, 2894, 2822, -1, 2900, 2901, 2902, -1, 2900, 2036, 2034, -1, 2112, 2110, 2693, -1, 2157, 2318, 2160, -1, 2157, 2320, 2318, -1, 2157, 2322, 2320, -1, 2900, 2903, 2070, -1, 2900, 2904, 2903, -1, 2566, 2784, 2782, -1, 2900, 2905, 2904, -1, 2900, 2906, 2905, -1, 2900, 2068, 2066, -1, 2566, 2564, 2784, -1, 2900, 2070, 2068, -1, 2900, 2066, 2901, -1, 2900, 2034, 2906, -1, 2100, 2266, 2101, -1, 2818, 2907, 2898, -1, 2388, 2386, 2841, -1, 2168, 2895, 2908, -1, 2818, 2898, 2820, -1, 1984, 1982, 2840, -1, 2114, 2112, 2693, -1, 2168, 2166, 2895, -1, 2384, 2841, 2386, -1, 2390, 2841, 2689, -1, 2568, 2782, 2780, -1, 2909, 2897, 2899, -1, 2910, 2911, 2266, -1, 2910, 2912, 2911, -1, 2568, 2566, 2782, -1, 2390, 2388, 2841, -1, 1986, 1984, 2840, -1, 2910, 2266, 2100, -1, 2816, 2907, 2818, -1, 2913, 2892, 2693, -1, 2381, 2841, 2384, -1, 2156, 2874, 2322, -1, 2914, 2234, 2912, -1, 2914, 2912, 2910, -1, 2156, 2322, 2157, -1, 2915, 1986, 2840, -1, 2156, 2916, 2874, -1, 2392, 2877, 2917, -1, 2918, 2919, 2920, -1, 2392, 2689, 2877, -1, 2918, 2909, 2899, -1, 2392, 2390, 2689, -1, 2918, 2899, 2919, -1, 2921, 2909, 2918, -1, 2380, 2841, 2381, -1, 2921, 2922, 2909, -1, 2923, 2695, 2924, -1, 2394, 2917, 2925, -1, 2394, 2392, 2917, -1, 2170, 2908, 2926, -1, 2170, 2168, 2908, -1, 2927, 2841, 2380, -1, 2928, 2916, 2156, -1, 2929, 2695, 2923, -1, 2930, 2038, 2036, -1, 2396, 2925, 2931, -1, 2930, 2036, 2900, -1, 2396, 2394, 2925, -1, 2172, 2926, 2932, -1, 2933, 2040, 2038, -1, 2172, 2170, 2926, -1, 2933, 2038, 2930, -1, 2934, 2695, 2929, -1, 2398, 2396, 2931, -1, 2935, 2916, 2928, -1, 2935, 2936, 2916, -1, 2937, 2042, 2040, -1, 2937, 2040, 2933, -1, 2938, 2939, 2042, -1, 2938, 2940, 2939, -1, 2941, 2695, 2934, -1, 1910, 2598, 2596, -1, 2938, 2042, 2937, -1, 1910, 2596, 2942, -1, 2943, 2940, 2938, -1, 2174, 2172, 2932, -1, 2943, 2944, 2940, -1, 2174, 2932, 2945, -1, 2400, 2931, 2946, -1, 2400, 2398, 2931, -1, 2947, 2936, 2935, -1, 1912, 1910, 2942, -1, 2948, 2949, 2944, -1, 2947, 2950, 2936, -1, 1912, 2942, 2951, -1, 2948, 2944, 2943, -1, 2952, 2941, 2953, -1, 2402, 2400, 2946, -1, 2402, 2946, 2954, -1, 2952, 2695, 2941, -1, 2176, 2174, 2945, -1, 2955, 2956, 2949, -1, 1908, 2598, 1910, -1, 1914, 2957, 2958, -1, 2404, 2954, 2959, -1, 1914, 1912, 2951, -1, 2955, 2949, 2948, -1, 2176, 2945, 2960, -1, 2404, 2402, 2954, -1, 2961, 2950, 2947, -1, 2276, 2274, 2962, -1, 1914, 2958, 2963, -1, 2406, 2404, 2959, -1, 2178, 2176, 2960, -1, 1914, 2951, 2957, -1, 2276, 2962, 2964, -1, 2178, 2960, 2965, -1, 1905, 2598, 1908, -1, 1905, 2600, 2598, -1, 2272, 2430, 2966, -1, 1905, 2602, 2600, -1, 2272, 2962, 2274, -1, 2272, 2432, 2430, -1, 2967, 2950, 2961, -1, 2967, 2961, 2968, -1, 1916, 1914, 2963, -1, 2272, 2966, 2962, -1, 2612, 2746, 2744, -1, 2612, 2610, 2746, -1, 2278, 2276, 2964, -1, 1916, 2963, 2969, -1, 2608, 2748, 2746, -1, 2608, 2750, 2748, -1, 2278, 2964, 2970, -1, 2608, 2746, 2610, -1, 2269, 2432, 2272, -1, 1904, 2602, 1905, -1, 2358, 2971, 2972, -1, 2614, 2744, 2742, -1, 1918, 1916, 2969, -1, 2614, 2612, 2744, -1, 2280, 2278, 2970, -1, 2605, 2973, 2750, -1, 1918, 2969, 2974, -1, 2360, 2972, 2975, -1, 2280, 2970, 2976, -1, 2360, 2358, 2972, -1, 2977, 2776, 2602, -1, 2977, 2778, 2776, -1, 2605, 2750, 2608, -1, 2268, 2432, 2269, -1, 2356, 2927, 2971, -1, 2356, 2971, 2358, -1, 2616, 2614, 2742, -1, 2268, 2978, 2434, -1, 2977, 2602, 1904, -1, 2268, 2434, 2432, -1, 2616, 2742, 2740, -1, 1920, 1918, 2974, -1, 2362, 2975, 2979, -1, 2282, 2280, 2976, -1, 2362, 2360, 2975, -1, 1920, 2974, 2980, -1, 2353, 2927, 2356, -1, 2282, 2976, 2981, -1, 2353, 2841, 2927, -1, 2982, 2780, 2778, -1, 2982, 2778, 2977, -1, 2983, 2978, 2268, -1, 2984, 2968, 2985, -1, 2983, 2860, 2978, -1, 2618, 2740, 2738, -1, 2618, 2616, 2740, -1, 2364, 2979, 2986, -1, 2984, 2967, 2968, -1, 2364, 2362, 2979, -1, 2284, 2282, 2981, -1, 2987, 2695, 2952, -1, 1922, 1920, 2980, -1, 2366, 2364, 2986, -1, 2988, 2780, 2982, -1, 2620, 2738, 2736, -1, 2284, 2981, 2989, -1, 2366, 2986, 2990, -1, 2988, 2568, 2780, -1, 2991, 2985, 2992, -1, 2620, 2618, 2738, -1, 2991, 2984, 2985, -1, 2993, 2860, 2983, -1, 1924, 2980, 2994, -1, 2368, 2366, 2990, -1, 1924, 1922, 2980, -1, 2995, 2896, 2695, -1, 2286, 2284, 2989, -1, 2368, 2990, 2996, -1, 2622, 2736, 2734, -1, 2286, 2989, 2997, -1, 1926, 2994, 2998, -1, 2622, 2620, 2736, -1, 1926, 1924, 2994, -1, 2624, 2734, 2732, -1, 2370, 2996, 2999, -1, 2370, 2368, 2996, -1, 2624, 2622, 2734, -1, 2288, 2997, 3000, -1, 1928, 2998, 3001, -1, 2288, 2286, 2997, -1, 1928, 1926, 2998, -1, 2290, 2288, 3000, -1, 2372, 2999, 3002, -1, 1930, 3001, 3003, -1, 2372, 2370, 2999, -1, 1930, 1928, 3001, -1, 2290, 3000, 3004, -1, 2374, 3002, 3005, -1, 2374, 2372, 3002, -1, 3006, 3007, 3008, -1, 3009, 3003, 3010, -1, 3009, 1930, 3003, -1, 3011, 3006, 3008, -1, 3012, 3011, 3008, -1, 1882, 2568, 2988, -1, 3013, 3012, 3008, -1, 1882, 2570, 2568, -1, 1884, 2988, 3014, -1, 1884, 1882, 2988, -1, 1938, 2652, 2708, -1, 2513, 2353, 2352, -1, 1880, 2570, 1882, -1, 1880, 2572, 2570, -1, 1938, 2708, 2890, -1, 2304, 3015, 3016, -1, 1886, 3014, 3017, -1, 2511, 2352, 3018, -1, 2511, 2513, 2352, -1, 2515, 2353, 2513, -1, 3019, 3013, 3008, -1, 2304, 2302, 3015, -1, 1886, 1884, 3014, -1, 2515, 2841, 2353, -1, 1940, 2890, 3020, -1, 2300, 3021, 3015, -1, 1940, 1938, 2890, -1, 2300, 2833, 3021, -1, 2509, 2511, 3018, -1, 1936, 2654, 2652, -1, 2300, 3015, 2302, -1, 1877, 2572, 1880, -1, 2306, 3016, 3022, -1, 1877, 2574, 2572, -1, 2306, 2304, 3016, -1, 2509, 3018, 3023, -1, 2699, 3019, 3008, -1, 1936, 2652, 1938, -1, 2699, 3024, 3025, -1, 2517, 2841, 2515, -1, 2699, 2992, 3024, -1, 1888, 3017, 3026, -1, 2699, 2991, 2992, -1, 2699, 3008, 2991, -1, 1888, 1886, 3017, -1, 2507, 2509, 3023, -1, 2297, 2833, 2300, -1, 1876, 2574, 1877, -1, 1876, 2800, 2574, -1, 1942, 3020, 3027, -1, 1942, 1940, 3020, -1, 2507, 3023, 3028, -1, 3029, 3030, 3031, -1, 3029, 3031, 3032, -1, 2308, 2306, 3022, -1, 3029, 3032, 3033, -1, 1933, 2654, 1936, -1, 2519, 2841, 2517, -1, 3029, 3033, 3034, -1, 1933, 2656, 2654, -1, 3029, 3034, 3035, -1, 1933, 2658, 2656, -1, 3029, 3035, 3036, -1, 1890, 3026, 3037, -1, 2505, 2507, 3028, -1, 2308, 3022, 3038, -1, 2505, 3039, 3040, -1, 1890, 1888, 3026, -1, 2505, 3028, 3039, -1, 3041, 2800, 1876, -1, 2310, 2308, 3038, -1, 1944, 3027, 3042, -1, 1944, 1942, 3027, -1, 1892, 3037, 3043, -1, 2503, 3040, 3044, -1, 2503, 2505, 3040, -1, 2310, 3038, 3045, -1, 1892, 1890, 3037, -1, 1932, 2658, 1933, -1, 2312, 2310, 3045, -1, 2501, 2503, 3044, -1, 1946, 1944, 3042, -1, 2501, 3044, 3046, -1, 2050, 3047, 3048, -1, 2312, 3045, 3049, -1, 1894, 3043, 3050, -1, 1946, 3042, 3051, -1, 3052, 2728, 2658, -1, 3052, 2730, 2728, -1, 2499, 3046, 3053, -1, 1894, 1892, 3043, -1, 2314, 2312, 3049, -1, 2499, 2501, 3046, -1, 3052, 2658, 1932, -1, 2052, 3048, 3054, -1, 1948, 1946, 3051, -1, 2314, 3049, 3055, -1, 2052, 2050, 3048, -1, 2048, 3047, 2050, -1, 2246, 3056, 3057, -1, 2048, 2206, 3058, -1, 2048, 3058, 3047, -1, 3059, 2810, 2808, -1, 1948, 3051, 3060, -1, 3061, 2732, 2730, -1, 2316, 2314, 3055, -1, 3062, 3059, 2808, -1, 2316, 3055, 3063, -1, 2048, 2208, 2206, -1, 2248, 3057, 3064, -1, 2248, 2246, 3057, -1, 3061, 2730, 3052, -1, 3062, 2808, 2806, -1, 1950, 1948, 3060, -1, 2244, 3056, 2246, -1, 2054, 3054, 3065, -1, 2244, 3066, 3056, -1, 1896, 3050, 3067, -1, 2054, 2052, 3054, -1, 2318, 2316, 3063, -1, 1950, 3060, 3068, -1, 3069, 2732, 3061, -1, 1896, 1894, 3050, -1, 2045, 2208, 2048, -1, 2318, 3063, 3070, -1, 3071, 2810, 3059, -1, 2250, 3064, 3072, -1, 2250, 2248, 3064, -1, 3071, 2812, 2810, -1, 3071, 2814, 2812, -1, 1952, 1950, 3068, -1, 2497, 2499, 3053, -1, 2056, 3065, 3073, -1, 1952, 3068, 3074, -1, 3075, 2806, 2804, -1, 2056, 2054, 3065, -1, 1954, 1952, 3074, -1, 2241, 3066, 2244, -1, 3075, 3062, 2806, -1, 2044, 2208, 2045, -1, 1898, 3067, 3076, -1, 1954, 3074, 3077, -1, 2252, 3072, 2913, -1, 2044, 3078, 2210, -1, 2044, 2210, 2208, -1, 1898, 1896, 3067, -1, 2252, 2250, 3072, -1, 3079, 2814, 3071, -1, 1956, 2915, 2840, -1, 1956, 1954, 3077, -1, 2240, 3066, 2241, -1, 3079, 2816, 2814, -1, 2240, 2959, 3066, -1, 1956, 3077, 2915, -1, 2058, 3073, 3080, -1, 2240, 2406, 2959, -1, 2254, 2913, 2693, -1, 1900, 1898, 3076, -1, 2058, 2056, 3073, -1, 1900, 3076, 3009, -1, 2254, 2252, 2913, -1, 3081, 3078, 2044, -1, 3082, 2802, 2800, -1, 3082, 2804, 2802, -1, 3082, 3075, 2804, -1, 2078, 2914, 3083, -1, 3084, 3085, 2406, -1, 3084, 3005, 3085, -1, 3086, 3030, 3029, -1, 2080, 2078, 3083, -1, 3084, 2406, 2240, -1, 2080, 3083, 3087, -1, 2076, 2914, 2078, -1, 2076, 2236, 2234, -1, 2060, 3080, 3088, -1, 2256, 2254, 2693, -1, 2076, 2234, 2914, -1, 2060, 2058, 3080, -1, 3089, 3078, 3081, -1, 3089, 2178, 2965, -1, 2082, 2080, 3087, -1, 3090, 2816, 3079, -1, 3091, 2374, 3005, -1, 3089, 2965, 3078, -1, 3091, 3005, 3084, -1, 2082, 3087, 3092, -1, 3093, 2841, 2519, -1, 2062, 3094, 3095, -1, 2062, 3088, 3094, -1, 3093, 2519, 2547, -1, 2584, 2582, 2770, -1, 2258, 2256, 2693, -1, 2062, 2060, 3088, -1, 3093, 3096, 3097, -1, 3093, 3098, 3096, -1, 3093, 3099, 2834, -1, 2584, 2770, 2768, -1, 3093, 3100, 3098, -1, 3093, 2547, 3099, -1, 3093, 3101, 3100, -1, 2580, 2770, 2582, -1, 3093, 2296, 3101, -1, 3093, 2834, 2833, -1, 3093, 2297, 2296, -1, 2580, 2772, 2770, -1, 3093, 2833, 2297, -1, 2580, 2774, 2772, -1, 2073, 2236, 2076, -1, 2586, 2584, 2768, -1, 3102, 2800, 3041, -1, 2064, 2062, 3095, -1, 3102, 3082, 2800, -1, 2586, 2768, 2766, -1, 2084, 2082, 3092, -1, 2577, 2774, 2580, -1, 3102, 3041, 3103, -1, 2084, 3092, 3104, -1, 3105, 3102, 3103, -1, 2072, 2238, 2236, -1, 2588, 2586, 2766, -1, 3105, 3103, 3106, -1, 2588, 2766, 2764, -1, 2072, 2236, 2073, -1, 2072, 3107, 2238, -1, 3108, 3105, 3106, -1, 3108, 3109, 3110, -1, 3108, 3106, 3109, -1, 2086, 2084, 3104, -1, 2590, 2588, 2764, -1, 2666, 3111, 2995, -1, 2086, 3104, 3112, -1, 2590, 2764, 2762, -1, 2697, 2955, 2907, -1, 2697, 2816, 3090, -1, 2066, 3095, 2901, -1, 2697, 3113, 2956, -1, 2066, 2064, 3095, -1, 2697, 2699, 3113, -1, 2697, 3090, 3114, -1, 2697, 2956, 2955, -1, 3115, 3107, 2072, -1, 2697, 2907, 2816, -1, 3116, 2697, 3114, -1, 2592, 2762, 2760, -1, 2592, 2590, 2762, -1, 2668, 2987, 3117, -1, 2088, 3112, 3118, -1, 2088, 2086, 3112, -1, 2668, 2695, 2987, -1, 2668, 2995, 2695, -1, 2668, 2666, 2995, -1, 3119, 3116, 3114, -1, 3119, 3114, 3120, -1, 3119, 3120, 3121, -1, 3122, 3119, 3121, -1, 2594, 2760, 2758, -1, 2594, 2592, 2760, -1, 2664, 3123, 3111, -1, 3122, 3121, 3124, -1, 3125, 3108, 3110, -1, 2664, 3111, 2666, -1, 3126, 2290, 3004, -1, 3126, 3004, 3107, -1, 3126, 3107, 3115, -1, 2596, 2594, 2758, -1, 2670, 3117, 3127, -1, 3125, 3110, 3128, -1, 2090, 3118, 3129, -1, 2670, 2668, 3117, -1, 2090, 2088, 3118, -1, 2596, 2758, 2756, -1, 3130, 3125, 3128, -1, 3130, 3128, 3131, -1, 3132, 3130, 3131, -1, 2661, 3133, 3123, -1, 2539, 3134, 3135, -1, 2661, 3123, 2664, -1, 2539, 2541, 3134, -1, 2543, 3136, 3134, -1, 2543, 3137, 3136, -1, 3138, 3139, 3093, -1, 2543, 3134, 2541, -1, 2672, 2670, 3127, -1, 2537, 2539, 3135, -1, 2537, 3135, 3140, -1, 2545, 2519, 3137, -1, 2545, 3137, 2543, -1, 2660, 3133, 2661, -1, 2535, 2537, 3140, -1, 3141, 3142, 3143, -1, 2535, 3140, 3144, -1, 2878, 2790, 2788, -1, 2547, 2519, 2545, -1, 2878, 2792, 2790, -1, 2878, 2794, 2792, -1, 2878, 2796, 2794, -1, 2674, 2672, 3127, -1, 2878, 2798, 2796, -1, 2878, 2576, 2798, -1, 2878, 2577, 2576, -1, 2878, 2774, 2577, -1, 2674, 3127, 3145, -1, 2533, 2535, 3144, -1, 2726, 3146, 3133, -1, 2533, 3144, 3147, -1, 3148, 3149, 3141, -1, 3148, 3141, 3143, -1, 2726, 3133, 2660, -1, 3150, 3148, 3143, -1, 3151, 3150, 3143, -1, 2414, 3152, 3153, -1, 2703, 3143, 3154, -1, 1994, 2624, 2732, -1, 2703, 3151, 3143, -1, 2676, 3145, 3155, -1, 3156, 2124, 2122, -1, 2676, 2674, 3145, -1, 3156, 2126, 2124, -1, 2416, 2414, 3153, -1, 3157, 1902, 1900, -1, 3157, 3158, 2438, -1, 1994, 2732, 3069, -1, 3157, 3010, 3158, -1, 3157, 3009, 3010, -1, 3157, 1900, 3009, -1, 3157, 2438, 2840, -1, 1996, 1994, 3069, -1, 2412, 3152, 2414, -1, 3157, 3159, 1902, -1, 3157, 3160, 3159, -1, 2412, 3161, 3152, -1, 3157, 3162, 3160, -1, 3157, 3163, 3162, -1, 3157, 3164, 3163, -1, 3165, 2126, 3156, -1, 2701, 3164, 3157, -1, 1996, 3069, 3166, -1, 2701, 3132, 3131, -1, 2701, 3154, 3132, -1, 2701, 2703, 3154, -1, 2701, 3131, 3164, -1, 2418, 2416, 3153, -1, 3165, 3167, 2126, -1, 3168, 3169, 3138, -1, 2724, 3170, 3146, -1, 2418, 3153, 3171, -1, 2724, 3146, 2726, -1, 3172, 2701, 3157, -1, 2485, 3173, 3174, -1, 2409, 3161, 2412, -1, 1992, 2624, 1994, -1, 3175, 3157, 3176, -1, 3175, 3176, 3177, -1, 2409, 3178, 3161, -1, 3175, 3172, 3157, -1, 3179, 2122, 2120, -1, 3180, 3175, 3177, -1, 2678, 3155, 3181, -1, 3179, 3156, 2122, -1, 2678, 2676, 3155, -1, 3182, 3175, 3180, -1, 3183, 2900, 2154, -1, 1992, 2626, 2624, -1, 2154, 2900, 2902, -1, 3183, 2154, 2152, -1, 2878, 2973, 2604, -1, 2604, 2973, 2605, -1, 2722, 3170, 2724, -1, 3184, 3167, 3165, -1, 2878, 2604, 2774, -1, 2483, 2485, 3174, -1, 2420, 2418, 3171, -1, 2680, 3181, 3185, -1, 2680, 2678, 3181, -1, 3184, 3186, 3167, -1, 2483, 3174, 3187, -1, 2420, 3171, 2494, -1, 2408, 3178, 2409, -1, 3188, 2120, 2118, -1, 1998, 1996, 3166, -1, 2720, 3189, 3170, -1, 2408, 2533, 3147, -1, 2408, 2531, 2533, -1, 2720, 3170, 2722, -1, 1998, 3166, 3173, -1, 2408, 3147, 3178, -1, 3188, 3179, 2120, -1, 2487, 1998, 3173, -1, 2487, 3173, 2485, -1, 3190, 3186, 3184, -1, 1989, 2626, 1992, -1, 2682, 2680, 3185, -1, 2718, 2973, 3189, -1, 3190, 3191, 3186, -1, 2718, 3189, 2720, -1, 2422, 2420, 2494, -1, 3192, 3168, 3138, -1, 2684, 3185, 2851, -1, 1989, 2628, 2626, -1, 2422, 2494, 2495, -1, 2481, 2483, 3187, -1, 2896, 2118, 2116, -1, 2684, 2682, 3185, -1, 3193, 2531, 2408, -1, 2716, 2973, 2718, -1, 3193, 2529, 2531, -1, 2896, 3188, 2118, -1, 2481, 3187, 3194, -1, 3183, 2090, 3129, -1, 3183, 3191, 3190, -1, 3183, 3195, 2098, -1, 3183, 3196, 3195, -1, 3183, 2092, 2090, -1, 3183, 2094, 2092, -1, 2424, 2497, 3053, -1, 3183, 2096, 2094, -1, 3183, 2098, 2096, -1, 2424, 2422, 2495, -1, 3183, 3129, 3191, -1, 2424, 2495, 2497, -1, 3197, 3192, 3138, -1, 3197, 3138, 3093, -1, 2489, 2000, 1998, -1, 2489, 1998, 2487, -1, 1988, 2628, 1989, -1, 3198, 2529, 3193, -1, 3198, 2527, 2529, -1, 1988, 2752, 2630, -1, 2426, 3053, 3199, -1, 2190, 2993, 3200, -1, 2426, 2424, 3053, -1, 1988, 2630, 2628, -1, 2479, 2481, 3194, -1, 2879, 2876, 3086, -1, 2879, 3086, 3029, -1, 3201, 2527, 3198, -1, 2479, 3202, 3203, -1, 2479, 3194, 3202, -1, 2525, 2527, 3201, -1, 2192, 3200, 3204, -1, 2192, 2190, 3200, -1, 2491, 2002, 2000, -1, 3205, 2879, 3206, -1, 2188, 2346, 2860, -1, 2188, 2348, 2346, -1, 2491, 2000, 2489, -1, 2428, 3199, 3207, -1, 2428, 2426, 3199, -1, 2188, 2993, 2190, -1, 2188, 2860, 2993, -1, 3208, 2754, 2752, -1, 3208, 2752, 1988, -1, 2022, 3089, 3209, -1, 2477, 2479, 3203, -1, 3210, 2525, 3201, -1, 2194, 3204, 3211, -1, 2194, 2192, 3204, -1, 2477, 3203, 3212, -1, 2024, 2022, 3209, -1, 2858, 3093, 3097, -1, 2430, 3207, 3213, -1, 2858, 3197, 3093, -1, 2024, 3209, 3214, -1, 2858, 3097, 2850, -1, 2430, 2428, 3207, -1, 3215, 2523, 2525, -1, 2020, 3089, 2022, -1, 2185, 2350, 2348, -1, 3215, 2525, 3210, -1, 3216, 2754, 3208, -1, 2020, 2178, 3089, -1, 2185, 2348, 2188, -1, 3216, 2756, 2754, -1, 3217, 2004, 2002, -1, 2026, 3214, 3218, -1, 2196, 3211, 3219, -1, 2026, 2024, 3214, -1, 3217, 2002, 2491, -1, 2196, 2194, 3211, -1, 2184, 2350, 2185, -1, 3220, 2522, 2523, -1, 2017, 2180, 2178, -1, 2017, 2178, 2020, -1, 3220, 2523, 3215, -1, 2017, 2182, 2180, -1, 2184, 3221, 2350, -1, 2475, 3212, 3222, -1, 2475, 2477, 3212, -1, 2198, 3219, 3223, -1, 2198, 2196, 3219, -1, 2028, 3218, 3224, -1, 2028, 2026, 3218, -1, 2942, 2756, 3216, -1, 2016, 2182, 2017, -1, 2942, 2596, 2756, -1, 3225, 3221, 2184, -1, 3226, 2006, 2004, -1, 3226, 2004, 3217, -1, 3225, 3070, 3221, -1, 2030, 3224, 3227, -1, 3228, 3229, 2522, -1, 3228, 2522, 3220, -1, 2030, 2028, 3224, -1, 2200, 3223, 3230, -1, 2008, 2006, 3226, -1, 3231, 3232, 2182, -1, 2200, 2198, 3223, -1, 2473, 3222, 1958, -1, 2473, 2475, 3222, -1, 3231, 2182, 2016, -1, 2882, 3070, 3225, -1, 2882, 2318, 3070, -1, 2032, 3227, 3233, -1, 2032, 2030, 3227, -1, 2839, 2838, 3229, -1, 2202, 3230, 3234, -1, 3235, 2879, 3205, -1, 2839, 3229, 3228, -1, 2202, 2200, 3230, -1, 3236, 2010, 2008, -1, 3236, 2008, 3226, -1, 3237, 3238, 3232, -1, 3237, 3239, 3238, -1, 3237, 3232, 3231, -1, 2034, 3233, 2906, -1, 2204, 3234, 3240, -1, 2034, 2032, 3233, -1, 2471, 1958, 1956, -1, 2204, 2202, 3234, -1, 2471, 2473, 1958, -1, 3241, 3239, 3237, -1, 3242, 2012, 2010, -1, 2218, 3091, 3243, -1, 3242, 2010, 3236, -1, 3244, 3025, 3239, -1, 3244, 2699, 3025, -1, 2206, 3240, 3058, -1, 3244, 3239, 3241, -1, 2206, 2204, 3240, -1, 2220, 2218, 3243, -1, 2220, 3243, 3245, -1, 2469, 1956, 2840, -1, 2469, 2471, 1956, -1, 2216, 2376, 2374, -1, 2216, 2374, 3091, -1, 2640, 2638, 2973, -1, 2216, 3091, 2218, -1, 2222, 2220, 3245, -1, 2222, 3245, 3246, -1, 2636, 2973, 2638, -1, 3247, 2879, 3235, -1, 2213, 2376, 2216, -1, 2213, 2378, 2376, -1, 3248, 2014, 2012, -1, 2642, 2640, 2973, -1, 3248, 2012, 3242, -1, 3249, 2699, 3244, -1, 2224, 3246, 3250, -1, 2224, 2222, 3246, -1, 2467, 2469, 2840, -1, 2633, 2973, 2636, -1, 2212, 3251, 2378, -1, 3252, 2014, 3248, -1, 2644, 2973, 2716, -1, 2644, 2642, 2973, -1, 2212, 2378, 2213, -1, 2466, 2467, 2840, -1, 2226, 3250, 3253, -1, 2226, 2224, 3250, -1, 3254, 3251, 2212, -1, 2134, 3126, 3255, -1, 3254, 3213, 3251, -1, 2136, 2134, 3255, -1, 2632, 2973, 2633, -1, 2136, 3255, 3256, -1, 3257, 2699, 3249, -1, 2132, 3126, 2134, -1, 2228, 3253, 3258, -1, 2132, 2290, 3126, -1, 2228, 2226, 3253, -1, 2132, 2292, 2290, -1, 2966, 2430, 3213, -1, 2646, 2716, 2714, -1, 2646, 2644, 2716, -1, 2138, 2136, 3256, -1, 2966, 3213, 3254, -1, 2750, 2973, 2632, -1, 2230, 3258, 3259, -1, 2138, 3256, 3260, -1, 2230, 2228, 3258, -1, 2457, 3261, 3262, -1, 3113, 2699, 3257, -1, 2129, 2292, 2132, -1, 2140, 2138, 3260, -1, 2455, 2457, 3262, -1, 2232, 3259, 3263, -1, 2648, 2646, 2714, -1, 2232, 2230, 3259, -1, 2455, 3262, 3264, -1, 2140, 3260, 3265, -1, 2648, 2714, 2712, -1, 2128, 2292, 2129, -1, 2459, 3266, 3261, -1, 2459, 3267, 3266, -1, 2128, 3268, 2294, -1, 2459, 3261, 2457, -1, 2128, 2294, 2292, -1, 2234, 3263, 2912, -1, 2453, 2455, 3264, -1, 2234, 2232, 3263, -1, 2142, 2140, 3265, -1, 2453, 3264, 2014, -1, 2142, 3265, 3269, -1, 3270, 3268, 2128, -1, 2461, 3267, 2459, -1, 2461, 3271, 3267, -1, 2451, 2453, 2014, -1, 2144, 2142, 3269, -1, 2451, 2014, 3252, -1, 2650, 2648, 2712, -1, 2144, 3269, 3272, -1, 3047, 3268, 3270, -1, 2463, 3271, 2461, -1, 2650, 2712, 2710, -1, 3047, 3058, 3268, -1, 2463, 3273, 3271, -1, 2449, 2451, 3252, -1, 2146, 2144, 3272, -1, 2146, 3274, 3275, -1, 2146, 3272, 3274, -1, 2449, 3252, 3276, -1, 2652, 2650, 2710, -1, 2652, 2710, 2708, -1, 3277, 3273, 2463, -1, 3277, 2957, 3273, -1, 2148, 2146, 3275, -1, 2447, 2449, 3276, -1, 2330, 3278, 3279, -1, 2447, 3276, 3280, -1, 3281, 2879, 3247, -1, 3281, 3247, 3282, -1, 2150, 3196, 3183, -1, 2958, 2957, 3277, -1, 2150, 2148, 3275, -1, 2150, 3275, 3196, -1, 2332, 2330, 3279, -1, 2445, 2447, 3280, -1, 2328, 3283, 3278, -1, 2328, 3278, 2330, -1, 2445, 3280, 3284, -1, 2152, 2150, 3183, -1, 2334, 2332, 3279, -1, 2334, 3279, 3285, -1, 2325, 3283, 2328, -1, 2325, 3286, 3283, -1, 2443, 3284, 3287, -1, 2443, 2445, 3284, -1, 2336, 2334, 3285, -1, 2840, 2879, 3281, -1, 2336, 3285, 2824, -1, 2441, 2443, 3287, -1, 2827, 2846, 2828, -1, 2441, 3287, 2829, -1, 2324, 2835, 3286, -1, 2324, 3286, 2325, -1, 3288, 2440, 3289, -1, 3290, 2339, 3291, -1, 2337, 2339, 3290, -1, 2440, 2437, 3289, -1, 3292, 3293, 3294, -1, 3295, 3296, 3297, -1, 3298, 3293, 3292, -1, 3289, 2437, 3299, -1, 3300, 3301, 2326, -1, 3302, 1967, 3303, -1, 3304, 3301, 3300, -1, 3305, 3293, 3298, -1, 3306, 2341, 3307, -1, 3291, 2341, 3306, -1, 2437, 2436, 3299, -1, 3299, 2436, 2464, -1, 2464, 2436, 3308, -1, 3309, 3310, 2690, -1, 3311, 3310, 3309, -1, 2339, 2341, 3291, -1, 3297, 3310, 3311, -1, 3312, 3310, 3296, -1, 3296, 3310, 3297, -1, 1967, 1969, 3303, -1, 3313, 3314, 3315, -1, 3315, 3314, 3305, -1, 3316, 1965, 3302, -1, 2341, 2343, 3307, -1, 3307, 2343, 3317, -1, 3302, 1965, 1967, -1, 3293, 3318, 3294, -1, 3294, 3318, 3319, -1, 3303, 1971, 3320, -1, 3317, 2345, 3321, -1, 1969, 1971, 3303, -1, 3322, 3323, 3324, -1, 2685, 1963, 3316, -1, 2343, 2345, 3317, -1, 3325, 3326, 3313, -1, 3313, 3326, 3314, -1, 3316, 1963, 1965, -1, 2687, 1963, 2685, -1, 3318, 3327, 3319, -1, 3319, 3327, 3328, -1, 3321, 2347, 3329, -1, 3323, 3330, 3331, -1, 3332, 3330, 3322, -1, 3333, 3330, 3332, -1, 2688, 3330, 3333, -1, 3320, 1973, 3334, -1, 2345, 2347, 3321, -1, 3322, 3330, 3323, -1, 1971, 1973, 3320, -1, 2690, 3335, 2688, -1, 2555, 2557, 3336, -1, 2688, 3335, 3330, -1, 3325, 3337, 3326, -1, 3328, 3338, 2323, -1, 3336, 2557, 3339, -1, 2690, 3340, 3335, -1, 2687, 1962, 1963, -1, 3336, 2553, 2555, -1, 3341, 2553, 3336, -1, 3334, 1975, 3342, -1, 3327, 3338, 3328, -1, 1973, 1975, 3334, -1, 3342, 1975, 3343, -1, 2705, 3344, 2687, -1, 3339, 2559, 3345, -1, 2687, 3344, 1962, -1, 2557, 2559, 3339, -1, 3341, 2551, 2553, -1, 3346, 2551, 3341, -1, 1975, 1977, 3343, -1, 3343, 1977, 3308, -1, 3347, 2163, 3348, -1, 2707, 3349, 2705, -1, 2705, 3349, 3344, -1, 2559, 2561, 3345, -1, 3350, 3351, 3352, -1, 3348, 2165, 3353, -1, 3354, 3351, 3350, -1, 1977, 1979, 3308, -1, 3345, 2561, 2789, -1, 2709, 3355, 2707, -1, 2707, 3355, 3349, -1, 2163, 2165, 3348, -1, 3351, 3356, 3352, -1, 3346, 2550, 2551, -1, 1979, 1981, 3308, -1, 2263, 2107, 2261, -1, 2107, 2109, 2261, -1, 3347, 2161, 2163, -1, 2319, 2161, 3347, -1, 2259, 2109, 2694, -1, 2561, 2563, 2789, -1, 3356, 3357, 3352, -1, 2261, 2109, 2259, -1, 2263, 2105, 2107, -1, 3352, 3357, 3358, -1, 2789, 2563, 2787, -1, 3359, 2823, 3346, -1, 3357, 2694, 3358, -1, 3353, 2167, 3360, -1, 1981, 1983, 3308, -1, 2165, 2167, 3353, -1, 3346, 2823, 2550, -1, 2265, 2105, 2263, -1, 2109, 2111, 2694, -1, 3361, 2692, 2117, -1, 2115, 2692, 2694, -1, 2117, 2692, 2115, -1, 2069, 3362, 2067, -1, 2265, 2103, 2105, -1, 2071, 3362, 2069, -1, 2563, 2565, 2787, -1, 3325, 3363, 3337, -1, 2787, 2565, 2785, -1, 3363, 3364, 3337, -1, 3365, 2821, 3359, -1, 2267, 2103, 2265, -1, 2321, 2159, 2319, -1, 2323, 2159, 2321, -1, 3359, 2821, 2823, -1, 3366, 3362, 3367, -1, 2067, 3362, 3366, -1, 2111, 2113, 2694, -1, 2037, 3362, 2035, -1, 2319, 2159, 2161, -1, 2267, 2102, 2103, -1, 2035, 3362, 3368, -1, 3369, 3362, 2071, -1, 3370, 3362, 3369, -1, 3371, 3362, 3370, -1, 3368, 3362, 3371, -1, 2387, 2389, 3310, -1, 3360, 2169, 3372, -1, 2785, 2567, 2783, -1, 1983, 1985, 3308, -1, 2565, 2567, 2785, -1, 3373, 2819, 3365, -1, 3310, 2385, 2387, -1, 2167, 2169, 3360, -1, 3365, 2819, 2821, -1, 2113, 2115, 2694, -1, 3363, 3374, 3364, -1, 3374, 3375, 3364, -1, 3310, 2391, 2690, -1, 2389, 2391, 3310, -1, 2783, 2569, 2781, -1, 2267, 3376, 2102, -1, 2567, 2569, 2783, -1, 3357, 3377, 2694, -1, 3378, 3376, 2267, -1, 3379, 3376, 3378, -1, 3373, 2817, 2819, -1, 1985, 1987, 3308, -1, 3310, 2383, 2385, -1, 3379, 3380, 3376, -1, 3338, 2158, 2323, -1, 2391, 2393, 2690, -1, 1987, 3381, 3308, -1, 3340, 2393, 3382, -1, 3383, 2158, 3338, -1, 2235, 3380, 3379, -1, 2323, 2158, 2159, -1, 2690, 2393, 3340, -1, 3310, 2382, 2383, -1, 3384, 3385, 3374, -1, 3374, 3386, 3375, -1, 3385, 3386, 3374, -1, 3375, 3386, 3387, -1, 3382, 2395, 3388, -1, 2692, 3389, 3390, -1, 2393, 2395, 3382, -1, 3372, 2171, 3391, -1, 2169, 2171, 3372, -1, 3310, 3392, 2382, -1, 3383, 3393, 2158, -1, 3388, 2397, 3394, -1, 2395, 2397, 3388, -1, 2692, 3395, 3389, -1, 2039, 3396, 2037, -1, 2037, 3396, 3362, -1, 3391, 2173, 3397, -1, 2171, 2173, 3391, -1, 2039, 3398, 3396, -1, 2692, 3399, 3395, -1, 2041, 3398, 2039, -1, 2041, 3400, 3398, -1, 3401, 3402, 3383, -1, 2397, 2399, 3394, -1, 3383, 3402, 3393, -1, 2599, 1911, 2597, -1, 2043, 3400, 2041, -1, 2043, 3403, 3400, -1, 3404, 3403, 2043, -1, 2692, 3405, 3399, -1, 3406, 3403, 3404, -1, 3406, 3407, 3403, -1, 3397, 2175, 3408, -1, 3394, 2401, 3409, -1, 2399, 2401, 3394, -1, 2597, 1911, 3410, -1, 3411, 3407, 3406, -1, 2173, 2175, 3397, -1, 3411, 3412, 3407, -1, 3409, 2403, 3413, -1, 3401, 3414, 3402, -1, 3410, 1913, 3415, -1, 3416, 3414, 3401, -1, 3417, 3412, 3411, -1, 2401, 2403, 3409, -1, 1911, 1913, 3410, -1, 2692, 3418, 3405, -1, 3417, 3419, 3412, -1, 3405, 3418, 3420, -1, 2599, 1909, 1911, -1, 3408, 2177, 3421, -1, 2403, 2405, 3413, -1, 3422, 3419, 3417, -1, 1913, 1915, 3415, -1, 3413, 2405, 3423, -1, 2175, 2177, 3408, -1, 3424, 1915, 3425, -1, 3416, 3426, 3414, -1, 2405, 2407, 3423, -1, 3425, 1915, 3427, -1, 3428, 2277, 3429, -1, 3421, 2179, 3430, -1, 3415, 1915, 3424, -1, 2177, 2179, 3421, -1, 2275, 2277, 3428, -1, 2601, 1907, 2599, -1, 2603, 1907, 2601, -1, 2431, 2273, 3431, -1, 2433, 2273, 2431, -1, 3431, 2273, 3428, -1, 2599, 1907, 1909, -1, 2611, 2613, 2747, -1, 3428, 2273, 2275, -1, 3416, 3432, 3426, -1, 3426, 3432, 3433, -1, 2747, 2613, 2745, -1, 2277, 2279, 3429, -1, 3427, 1917, 3434, -1, 3429, 2279, 3435, -1, 2747, 2609, 2611, -1, 1915, 1917, 3427, -1, 2749, 2609, 2747, -1, 2751, 2609, 2749, -1, 3436, 2359, 3437, -1, 2433, 2271, 2273, -1, 2603, 1906, 1907, -1, 2613, 2615, 2745, -1, 3437, 2361, 3438, -1, 2745, 2615, 2743, -1, 2359, 2361, 3437, -1, 3439, 2607, 2751, -1, 3435, 2281, 3440, -1, 2751, 2607, 2609, -1, 3434, 1919, 3441, -1, 2279, 2281, 3435, -1, 1917, 1919, 3434, -1, 3392, 2357, 3436, -1, 3442, 2270, 2435, -1, 3436, 2357, 2359, -1, 2435, 2270, 2433, -1, 2603, 3443, 1906, -1, 2433, 2270, 2271, -1, 3438, 2363, 3444, -1, 2361, 2363, 3438, -1, 2777, 3443, 2603, -1, 2779, 3443, 2777, -1, 2615, 2617, 2743, -1, 1919, 1921, 3441, -1, 2743, 2617, 2741, -1, 2281, 2283, 3440, -1, 3310, 2355, 3392, -1, 3440, 2283, 3445, -1, 3441, 1921, 3446, -1, 3392, 2355, 2357, -1, 3444, 2365, 3447, -1, 3329, 3448, 3442, -1, 2363, 2365, 3444, -1, 2779, 3449, 3443, -1, 3442, 3448, 2270, -1, 3432, 3450, 3433, -1, 2617, 2619, 2741, -1, 2781, 3449, 2779, -1, 2741, 2619, 2739, -1, 3433, 3450, 3451, -1, 2692, 3452, 3418, -1, 1921, 1923, 3446, -1, 3445, 2285, 3453, -1, 2365, 2367, 3447, -1, 2283, 2285, 3445, -1, 3329, 3454, 3448, -1, 2781, 3455, 3449, -1, 3447, 2367, 3456, -1, 3450, 3457, 3451, -1, 2569, 3455, 2781, -1, 2619, 2621, 2739, -1, 3451, 3457, 3458, -1, 2739, 2621, 2737, -1, 3361, 3459, 2692, -1, 3446, 1925, 3460, -1, 2367, 2369, 3456, -1, 1923, 1925, 3446, -1, 3453, 2287, 3461, -1, 2285, 2287, 3453, -1, 3456, 2369, 3462, -1, 2737, 2623, 2735, -1, 2621, 2623, 2737, -1, 3460, 1927, 3463, -1, 1925, 1927, 3460, -1, 2369, 2371, 3462, -1, 2287, 2289, 3461, -1, 3461, 2289, 3464, -1, 3462, 2371, 3465, -1, 2735, 2625, 2733, -1, 2623, 2625, 2735, -1, 3463, 1929, 3466, -1, 1927, 1929, 3463, -1, 2371, 2373, 3465, -1, 2289, 2291, 3464, -1, 3464, 2291, 3467, -1, 3465, 2373, 3468, -1, 3466, 1931, 3469, -1, 1929, 1931, 3466, -1, 2373, 2375, 3468, -1, 3470, 3471, 3472, -1, 3468, 2375, 3473, -1, 3469, 3474, 3475, -1, 1931, 3474, 3469, -1, 3471, 3476, 3472, -1, 3476, 3477, 3472, -1, 2569, 1883, 3455, -1, 2571, 1883, 2569, -1, 3477, 3478, 3472, -1, 1883, 1885, 3455, -1, 3455, 1885, 3479, -1, 2653, 1939, 2709, -1, 2571, 1881, 1883, -1, 2355, 2512, 2354, -1, 2573, 1881, 2571, -1, 2512, 2510, 2354, -1, 2709, 1939, 3355, -1, 3478, 3480, 3472, -1, 3355, 1941, 3481, -1, 2354, 2510, 3482, -1, 3483, 2305, 3484, -1, 2355, 2514, 2512, -1, 2303, 2305, 3483, -1, 1939, 1941, 3355, -1, 3310, 2514, 2355, -1, 3479, 1887, 3485, -1, 1885, 1887, 3479, -1, 2653, 1937, 1939, -1, 2510, 2508, 3482, -1, 3486, 2301, 3483, -1, 3301, 2301, 3486, -1, 3483, 2301, 2303, -1, 2573, 1879, 1881, -1, 2575, 1879, 2573, -1, 2655, 1937, 2653, -1, 2305, 2307, 3484, -1, 3472, 2696, 3457, -1, 3482, 2508, 3487, -1, 3310, 2516, 2514, -1, 3457, 2696, 3458, -1, 3488, 2696, 3489, -1, 3484, 2307, 3490, -1, 3458, 2696, 3488, -1, 3480, 2696, 3472, -1, 3481, 1943, 3491, -1, 2508, 2506, 3487, -1, 3485, 1889, 3492, -1, 3301, 2299, 2301, -1, 1887, 1889, 3485, -1, 1941, 1943, 3481, -1, 2801, 1878, 2575, -1, 3493, 3494, 3495, -1, 3487, 2506, 3496, -1, 3497, 3494, 3493, -1, 3498, 3494, 3497, -1, 2575, 1878, 1879, -1, 2307, 2309, 3490, -1, 3499, 3494, 3498, -1, 3310, 2518, 2516, -1, 3500, 3494, 3499, -1, 3501, 3494, 3500, -1, 2657, 1935, 2655, -1, 2506, 2504, 3496, -1, 2659, 1935, 2657, -1, 2655, 1935, 1937, -1, 3490, 2309, 3502, -1, 3503, 2504, 3504, -1, 3496, 2504, 3503, -1, 3492, 1891, 3505, -1, 3491, 1945, 3506, -1, 1889, 1891, 3492, -1, 1943, 1945, 3491, -1, 2309, 2311, 3502, -1, 2801, 3507, 1878, -1, 2504, 2502, 3504, -1, 3502, 2311, 3508, -1, 3504, 2502, 3509, -1, 2659, 1934, 1935, -1, 3505, 1893, 3510, -1, 1891, 1893, 3505, -1, 2311, 2313, 3508, -1, 2502, 2500, 3509, -1, 3506, 1947, 3511, -1, 3508, 2313, 3512, -1, 3509, 2500, 3513, -1, 1945, 1947, 3506, -1, 3514, 2051, 3515, -1, 2500, 2498, 3513, -1, 2659, 3516, 1934, -1, 3510, 1895, 3517, -1, 1893, 1895, 3510, -1, 3513, 2498, 3518, -1, 2729, 3516, 2659, -1, 2051, 2053, 3515, -1, 2731, 3516, 2729, -1, 3512, 2315, 3519, -1, 2313, 2315, 3512, -1, 3511, 1949, 3520, -1, 3515, 2053, 3521, -1, 1947, 1949, 3511, -1, 2811, 3522, 2809, -1, 2315, 2317, 3519, -1, 3523, 2049, 3514, -1, 2731, 3524, 3516, -1, 3525, 2247, 3526, -1, 2209, 2049, 2207, -1, 3519, 2317, 3527, -1, 3514, 2049, 2051, -1, 2247, 2249, 3526, -1, 2733, 3524, 2731, -1, 3522, 3528, 2809, -1, 2207, 2049, 3523, -1, 3526, 2249, 3529, -1, 2809, 3528, 2807, -1, 2053, 2055, 3521, -1, 3525, 2245, 2247, -1, 3520, 1951, 3530, -1, 2317, 2319, 3527, -1, 1895, 1897, 3517, -1, 3527, 2319, 3531, -1, 1949, 1951, 3520, -1, 3521, 2055, 3532, -1, 2733, 3533, 3524, -1, 3534, 2245, 3525, -1, 3517, 1897, 3535, -1, 2249, 2251, 3529, -1, 2813, 3536, 2811, -1, 2209, 2047, 2049, -1, 2815, 3536, 2813, -1, 3529, 2251, 3537, -1, 3530, 1953, 3538, -1, 2498, 2496, 3518, -1, 2811, 3536, 3522, -1, 1951, 1953, 3530, -1, 2055, 2057, 3532, -1, 3534, 2243, 2245, -1, 3532, 2057, 3539, -1, 2807, 3540, 2805, -1, 3538, 1955, 3541, -1, 3542, 2046, 2211, -1, 3528, 3540, 2807, -1, 1953, 1955, 3538, -1, 2211, 2046, 2209, -1, 2209, 2046, 2047, -1, 2251, 2253, 3537, -1, 3537, 2253, 3377, -1, 3535, 1899, 3543, -1, 3541, 1957, 3381, -1, 1955, 1957, 3541, -1, 1897, 1899, 3535, -1, 3381, 1957, 3308, -1, 3534, 2242, 2243, -1, 2407, 2242, 3423, -1, 2817, 3544, 2815, -1, 2057, 2059, 3539, -1, 2815, 3544, 3536, -1, 3539, 2059, 3545, -1, 3423, 2242, 3534, -1, 2253, 2255, 3377, -1, 3377, 2255, 2694, -1, 1899, 1901, 3543, -1, 3542, 3546, 2046, -1, 3543, 1901, 3474, -1, 2803, 3547, 2801, -1, 2805, 3547, 2803, -1, 3540, 3547, 2805, -1, 3380, 2079, 3548, -1, 2079, 2081, 3548, -1, 2407, 3549, 2242, -1, 3550, 3549, 2407, -1, 3473, 3549, 3550, -1, 3501, 3551, 3494, -1, 3548, 2081, 3552, -1, 2059, 2061, 3545, -1, 3380, 2077, 2079, -1, 2235, 2077, 3380, -1, 3545, 2061, 3553, -1, 2255, 2257, 2694, -1, 2237, 2077, 2235, -1, 3430, 3554, 3542, -1, 2179, 3554, 3430, -1, 3542, 3554, 3546, -1, 3473, 3555, 3549, -1, 2375, 3555, 3473, -1, 3552, 2083, 3556, -1, 2081, 2083, 3552, -1, 2518, 3557, 2546, -1, 2817, 3558, 3544, -1, 2771, 2585, 2769, -1, 2061, 2063, 3553, -1, 3559, 3557, 3560, -1, 2257, 2259, 2694, -1, 3310, 3557, 2518, -1, 2583, 2585, 2771, -1, 3561, 2063, 3562, -1, 3301, 3557, 2299, -1, 3553, 2063, 3561, -1, 3563, 3557, 3559, -1, 3564, 3557, 3563, -1, 3565, 3557, 3564, -1, 2773, 2581, 2771, -1, 2298, 3557, 3565, -1, 2775, 2581, 2773, -1, 2299, 3557, 2298, -1, 3566, 3557, 3304, -1, 2771, 2581, 2583, -1, 2546, 3557, 3566, -1, 3304, 3557, 3301, -1, 2769, 2587, 2767, -1, 2585, 2587, 2769, -1, 2237, 2075, 2077, -1, 2063, 2065, 3562, -1, 3547, 3567, 2801, -1, 2775, 2579, 2581, -1, 3556, 2085, 3568, -1, 3507, 3567, 3569, -1, 2767, 2589, 2765, -1, 2083, 2085, 3556, -1, 2801, 3567, 3507, -1, 2587, 2589, 2767, -1, 2237, 2074, 2075, -1, 3567, 3570, 3569, -1, 3571, 2074, 2239, -1, 2239, 2074, 2237, -1, 3569, 3570, 3572, -1, 3570, 3573, 3572, -1, 2765, 2591, 2763, -1, 3568, 2087, 3574, -1, 2589, 2591, 2765, -1, 3575, 3573, 3576, -1, 3577, 2667, 3459, -1, 3572, 3573, 3575, -1, 2085, 2087, 3568, -1, 3373, 2698, 2817, -1, 2817, 2698, 3558, -1, 2696, 2698, 3578, -1, 3419, 2698, 3373, -1, 3422, 2698, 3419, -1, 3578, 2698, 3422, -1, 3571, 3579, 2074, -1, 2763, 2593, 2761, -1, 3562, 2067, 3366, -1, 2698, 3580, 3558, -1, 2065, 2067, 3562, -1, 2591, 2593, 2763, -1, 2698, 3581, 3580, -1, 3574, 2089, 3582, -1, 3452, 2669, 3583, -1, 2692, 2669, 3452, -1, 2667, 2669, 3459, -1, 2087, 2089, 3574, -1, 3459, 2669, 2692, -1, 2761, 2595, 2759, -1, 2593, 2595, 2761, -1, 3467, 3584, 3571, -1, 3585, 2665, 3577, -1, 2291, 3584, 3467, -1, 3571, 3584, 3579, -1, 3581, 3586, 3580, -1, 3577, 2665, 2667, -1, 3587, 3586, 3581, -1, 3588, 3586, 3587, -1, 3589, 3586, 3590, -1, 2759, 2597, 2757, -1, 3580, 3586, 3589, -1, 3583, 2671, 3591, -1, 3582, 2091, 3592, -1, 2595, 2597, 2759, -1, 2669, 2671, 3583, -1, 2089, 2091, 3582, -1, 3576, 3593, 3594, -1, 3573, 3593, 3576, -1, 3594, 3595, 3596, -1, 3593, 3595, 3594, -1, 3597, 2663, 3585, -1, 2540, 2538, 3598, -1, 3585, 2663, 2665, -1, 3595, 3599, 3596, -1, 3598, 2538, 3600, -1, 3598, 2542, 2540, -1, 3601, 2542, 3598, -1, 3602, 2542, 3601, -1, 3603, 3604, 3557, -1, 2538, 2536, 3600, -1, 2671, 2673, 3591, -1, 3600, 2536, 3605, -1, 3602, 2544, 2542, -1, 2518, 2544, 3602, -1, 2536, 2534, 3605, -1, 3597, 2662, 2663, -1, 3605, 2534, 3606, -1, 2518, 2546, 2544, -1, 2775, 3345, 2579, -1, 2791, 3345, 2789, -1, 2793, 3345, 2791, -1, 2795, 3345, 2793, -1, 2797, 3345, 2795, -1, 3591, 2675, 3607, -1, 2799, 3345, 2797, -1, 2534, 2532, 3606, -1, 2578, 3345, 2799, -1, 2673, 2675, 3591, -1, 2579, 3345, 2578, -1, 3608, 3609, 3610, -1, 3597, 2727, 2662, -1, 3611, 2727, 3597, -1, 3606, 2532, 3612, -1, 3609, 3613, 3610, -1, 3614, 3613, 3609, -1, 3615, 2415, 3616, -1, 3613, 3617, 3610, -1, 2625, 1995, 2733, -1, 3607, 2677, 3618, -1, 2675, 2677, 3607, -1, 2733, 1995, 3533, -1, 3617, 3619, 3610, -1, 2415, 2417, 3616, -1, 3619, 2700, 3610, -1, 3610, 2700, 3620, -1, 3621, 2413, 3615, -1, 2125, 3622, 2123, -1, 2127, 3622, 2125, -1, 3615, 2413, 2415, -1, 3599, 2702, 3596, -1, 3533, 1997, 3623, -1, 2417, 2419, 3616, -1, 1995, 1997, 3533, -1, 3616, 2419, 3624, -1, 3596, 2702, 3625, -1, 3626, 3627, 2127, -1, 2127, 3627, 3622, -1, 2700, 2702, 3620, -1, 3628, 2725, 3611, -1, 3620, 2702, 3599, -1, 1901, 3629, 3474, -1, 3630, 3629, 2436, -1, 3475, 3629, 3630, -1, 3631, 2484, 3632, -1, 3611, 2725, 2727, -1, 3633, 3629, 1903, -1, 3634, 3635, 3604, -1, 3636, 3629, 3633, -1, 3637, 3629, 3636, -1, 3621, 2411, 2413, -1, 3638, 3629, 3637, -1, 3639, 2411, 3621, -1, 3625, 3629, 3638, -1, 2436, 3629, 3308, -1, 2627, 1993, 2625, -1, 1903, 3629, 1901, -1, 3622, 3640, 2123, -1, 3474, 3629, 3475, -1, 3618, 2679, 3641, -1, 2702, 3629, 3625, -1, 2677, 2679, 3618, -1, 2123, 3640, 2121, -1, 2625, 1993, 1995, -1, 2702, 3642, 3629, -1, 2484, 2482, 3632, -1, 3628, 2723, 2725, -1, 2419, 2421, 3624, -1, 3624, 2421, 2492, -1, 3629, 3643, 3644, -1, 3645, 3646, 3626, -1, 3642, 3647, 3629, -1, 3641, 2681, 3648, -1, 3632, 2482, 3649, -1, 2679, 2681, 3641, -1, 3626, 3646, 3627, -1, 1997, 1999, 3623, -1, 3639, 2410, 2411, -1, 3628, 2721, 2723, -1, 2532, 2410, 3612, -1, 2530, 2410, 2532, -1, 3640, 3650, 2121, -1, 3629, 3651, 3643, -1, 3652, 2721, 3628, -1, 3647, 3651, 3629, -1, 2121, 3650, 2119, -1, 3653, 3651, 3647, -1, 3623, 1999, 3631, -1, 3612, 2410, 3639, -1, 3439, 3345, 2606, -1, 3439, 2606, 2607, -1, 1999, 2486, 3631, -1, 2606, 3345, 2775, -1, 3631, 2486, 2484, -1, 3362, 3654, 2155, -1, 3362, 2155, 3367, -1, 3645, 3655, 3646, -1, 2155, 3654, 2153, -1, 2681, 2683, 3648, -1, 3656, 3655, 3645, -1, 3652, 2719, 2721, -1, 2421, 2423, 2492, -1, 2629, 1991, 2627, -1, 3439, 2719, 3652, -1, 2492, 2423, 2493, -1, 2627, 1991, 1993, -1, 3648, 2685, 3316, -1, 3635, 3657, 3604, -1, 2482, 2480, 3649, -1, 2683, 2685, 3648, -1, 3439, 2717, 2719, -1, 2528, 3658, 2530, -1, 2530, 3658, 2410, -1, 3650, 3361, 2119, -1, 2119, 3361, 2117, -1, 3649, 2480, 3659, -1, 2091, 3654, 3592, -1, 3660, 3654, 2099, -1, 3661, 3654, 3660, -1, 2496, 2425, 3518, -1, 2093, 3654, 2091, -1, 2095, 3654, 2093, -1, 2097, 3654, 2095, -1, 2493, 2425, 2496, -1, 2423, 2425, 2493, -1, 2099, 3654, 2097, -1, 3656, 3654, 3655, -1, 3592, 3654, 3656, -1, 3657, 3662, 3604, -1, 1999, 2488, 2486, -1, 2526, 3663, 2528, -1, 3604, 3662, 3557, -1, 2001, 2488, 1999, -1, 3454, 2191, 3664, -1, 2753, 1990, 2631, -1, 2528, 3663, 3658, -1, 2425, 2427, 3518, -1, 2631, 1990, 2629, -1, 2629, 1990, 1991, -1, 3518, 2427, 3665, -1, 3342, 3343, 3551, -1, 2480, 2478, 3659, -1, 3551, 3343, 3494, -1, 2526, 3666, 3663, -1, 3667, 2478, 3668, -1, 3659, 2478, 3667, -1, 2191, 2193, 3664, -1, 2526, 2524, 3666, -1, 3343, 3669, 3670, -1, 2001, 2490, 2488, -1, 3664, 2193, 3671, -1, 2003, 2490, 2001, -1, 2427, 2429, 3665, -1, 2755, 3672, 2753, -1, 3454, 2189, 2191, -1, 3665, 2429, 3673, -1, 2753, 3672, 1990, -1, 2347, 2189, 3329, -1, 2349, 2189, 2347, -1, 3329, 2189, 3454, -1, 2478, 2476, 3668, -1, 2524, 3674, 3666, -1, 2193, 2195, 3671, -1, 3554, 2023, 3675, -1, 3668, 2476, 3676, -1, 2429, 2431, 3673, -1, 2023, 2025, 3675, -1, 3671, 2195, 3677, -1, 3673, 2431, 3678, -1, 3560, 3325, 3313, -1, 3662, 3325, 3557, -1, 3675, 2025, 3679, -1, 3557, 3325, 3560, -1, 3554, 2021, 2023, -1, 2521, 3680, 2524, -1, 2179, 2021, 3554, -1, 2524, 3680, 3674, -1, 2757, 3681, 2755, -1, 2755, 3681, 3672, -1, 2349, 2187, 2189, -1, 2351, 2187, 2349, -1, 2025, 2027, 3679, -1, 2003, 3682, 2490, -1, 2195, 2197, 3677, -1, 2005, 3682, 2003, -1, 3679, 2027, 3683, -1, 2181, 2019, 2179, -1, 2183, 2019, 2181, -1, 3677, 2197, 3684, -1, 2351, 2186, 2187, -1, 2179, 2019, 2021, -1, 2520, 3685, 2521, -1, 2521, 3685, 3680, -1, 3686, 2186, 2351, -1, 2027, 2029, 3683, -1, 2476, 2474, 3676, -1, 2197, 2199, 3684, -1, 3683, 2029, 3687, -1, 3676, 2474, 3688, -1, 3684, 2199, 3689, -1, 2183, 2018, 2019, -1, 2757, 3410, 3681, -1, 2597, 3410, 2757, -1, 3531, 3690, 3686, -1, 3686, 3690, 2186, -1, 2029, 2031, 3687, -1, 3691, 3692, 2520, -1, 2520, 3692, 3685, -1, 2005, 3693, 3682, -1, 2007, 3693, 2005, -1, 3687, 2031, 3694, -1, 2183, 3695, 2018, -1, 2199, 2201, 3689, -1, 2007, 2009, 3693, -1, 3696, 3695, 2183, -1, 3689, 2201, 3697, -1, 2474, 2472, 3688, -1, 3688, 2472, 1959, -1, 2031, 2033, 3694, -1, 2319, 3347, 3531, -1, 3531, 3347, 3690, -1, 3694, 2033, 3698, -1, 3306, 3307, 3691, -1, 3343, 3699, 3669, -1, 3691, 3307, 3692, -1, 2201, 2203, 3697, -1, 3697, 2203, 3700, -1, 3696, 3701, 3695, -1, 2009, 3702, 3693, -1, 2011, 3702, 2009, -1, 3703, 3701, 3696, -1, 3704, 3701, 3703, -1, 1959, 2470, 1957, -1, 2033, 2035, 3698, -1, 2472, 2470, 1959, -1, 3698, 2035, 3368, -1, 2203, 2205, 3700, -1, 3700, 2205, 3705, -1, 3704, 3706, 3701, -1, 2696, 3707, 3489, -1, 3704, 3707, 3706, -1, 3489, 3707, 3704, -1, 2013, 3708, 2011, -1, 2011, 3708, 3702, -1, 3555, 2219, 3709, -1, 2205, 2207, 3705, -1, 3705, 2207, 3523, -1, 2219, 2221, 3709, -1, 2470, 2468, 1957, -1, 3709, 2221, 3710, -1, 1957, 2468, 3308, -1, 2375, 2217, 3555, -1, 3555, 2217, 2219, -1, 2377, 2217, 2375, -1, 2639, 2641, 3439, -1, 2221, 2223, 3710, -1, 3439, 2637, 2639, -1, 3710, 2223, 3711, -1, 3343, 3712, 3699, -1, 2377, 2215, 2217, -1, 2379, 2215, 2377, -1, 2223, 2225, 3711, -1, 2641, 2643, 3439, -1, 2696, 3713, 3707, -1, 2015, 3714, 2013, -1, 2013, 3714, 3708, -1, 3711, 2225, 3715, -1, 2468, 2465, 3308, -1, 2379, 2214, 2215, -1, 3439, 2635, 2637, -1, 2015, 3716, 3714, -1, 3439, 2645, 2717, -1, 3717, 2214, 2379, -1, 2465, 2464, 3308, -1, 2643, 2645, 3439, -1, 2225, 2227, 3715, -1, 3584, 2135, 3718, -1, 3715, 2227, 3719, -1, 3717, 3720, 2214, -1, 3678, 3720, 3717, -1, 3718, 2137, 3721, -1, 3439, 2634, 2635, -1, 2227, 2229, 3719, -1, 2135, 2137, 3718, -1, 2696, 3722, 3713, -1, 2293, 2133, 2291, -1, 3719, 2229, 3723, -1, 2717, 2647, 2715, -1, 3584, 2133, 2135, -1, 2291, 2133, 3584, -1, 3678, 3431, 3720, -1, 2645, 2647, 2717, -1, 2431, 3431, 3678, -1, 3721, 2139, 3724, -1, 2229, 2231, 3723, -1, 3725, 2456, 3726, -1, 2137, 2139, 3721, -1, 2293, 2131, 2133, -1, 3723, 2231, 3727, -1, 3439, 2751, 2634, -1, 2696, 3578, 3722, -1, 3726, 2454, 3728, -1, 2647, 2649, 2715, -1, 2231, 2233, 3727, -1, 3724, 2141, 3729, -1, 2456, 2454, 3726, -1, 2715, 2649, 2713, -1, 3727, 2233, 3730, -1, 2139, 2141, 3724, -1, 3731, 2458, 3725, -1, 2293, 2130, 2131, -1, 3732, 2458, 3731, -1, 2295, 2130, 2293, -1, 3725, 2458, 2456, -1, 2233, 2235, 3730, -1, 3733, 2130, 2295, -1, 2454, 2452, 3728, -1, 3728, 2452, 2015, -1, 3730, 2235, 3379, -1, 2141, 2143, 3729, -1, 3729, 2143, 3734, -1, 3735, 2460, 3732, -1, 3733, 3736, 2130, -1, 3732, 2460, 2458, -1, 2143, 2145, 3734, -1, 2452, 2450, 2015, -1, 2015, 2450, 3716, -1, 3734, 2145, 3737, -1, 3343, 3738, 3712, -1, 2649, 2651, 2713, -1, 2713, 2651, 2711, -1, 3735, 2462, 2460, -1, 3739, 2462, 3735, -1, 3733, 3514, 3736, -1, 3523, 3514, 3733, -1, 3740, 2147, 3741, -1, 3737, 2147, 3740, -1, 2145, 2147, 3737, -1, 2450, 2448, 3716, -1, 2711, 2653, 2709, -1, 2651, 2653, 2711, -1, 3716, 2448, 3742, -1, 3424, 3743, 3739, -1, 2147, 2149, 3741, -1, 3739, 3743, 2462, -1, 2448, 2446, 3742, -1, 3744, 2331, 3745, -1, 3742, 2446, 3746, -1, 3741, 2151, 3661, -1, 2331, 2333, 3745, -1, 2149, 2151, 3741, -1, 3661, 2151, 3654, -1, 3424, 3425, 3743, -1, 3744, 2329, 2331, -1, 3747, 2329, 3744, -1, 2446, 2444, 3746, -1, 2333, 2335, 3745, -1, 2151, 2153, 3654, -1, 3746, 2444, 3748, -1, 3745, 2335, 3749, -1, 3750, 2327, 3747, -1, 2444, 2442, 3748, -1, 3747, 2327, 2329, -1, 2335, 2337, 3749, -1, 3748, 2442, 3288, -1, 3343, 3308, 3738, -1, 3749, 2337, 3290, -1, 3738, 3308, 3751, -1, 3315, 3305, 3298, -1, 3750, 2326, 2327, -1, 2442, 2440, 3288, -1, 3300, 2326, 3750, -1, 3310, 3093, 3557, -1, 2841, 3093, 3310, -1, 3343, 3029, 3494, -1, 2879, 3029, 3343, -1, 3629, 2840, 3308, -1, 3157, 2840, 3629, -1, 3325, 2897, 3363, -1, 2858, 2897, 3325, -1, 2546, 3566, 2547, -1, 2547, 3566, 3099, -1, 3099, 3304, 2834, -1, 3566, 3304, 3099, -1, 2834, 3300, 2835, -1, 3304, 3300, 2834, -1, 2835, 3750, 3286, -1, 3300, 3750, 2835, -1, 3286, 3747, 3283, -1, 3750, 3747, 3286, -1, 3283, 3744, 3278, -1, 3747, 3744, 3283, -1, 3278, 3745, 3279, -1, 3744, 3745, 3278, -1, 3279, 3749, 3285, -1, 3745, 3749, 3279, -1, 3285, 3290, 2824, -1, 3749, 3290, 3285, -1, 2824, 3291, 2825, -1, 3290, 3291, 2824, -1, 2825, 3306, 2838, -1, 3291, 3306, 2825, -1, 2838, 3691, 3229, -1, 3306, 3691, 2838, -1, 3229, 2520, 2522, -1, 3691, 2520, 3229, -1, 2518, 3602, 2519, -1, 2519, 3602, 3137, -1, 3137, 3601, 3136, -1, 3602, 3601, 3137, -1, 3136, 3598, 3134, -1, 3601, 3598, 3136, -1, 3134, 3600, 3135, -1, 3598, 3600, 3134, -1, 3135, 3605, 3140, -1, 3600, 3605, 3135, -1, 3140, 3606, 3144, -1, 3605, 3606, 3140, -1, 3144, 3612, 3147, -1, 3606, 3612, 3144, -1, 3147, 3639, 3178, -1, 3612, 3639, 3147, -1, 3178, 3621, 3161, -1, 3639, 3621, 3178, -1, 3161, 3615, 3152, -1, 3621, 3615, 3161, -1, 3152, 3616, 3153, -1, 3615, 3616, 3152, -1, 3153, 3624, 3171, -1, 3616, 3624, 3153, -1, 3171, 2492, 2494, -1, 3624, 2492, 3171, -1, 2490, 3682, 2491, -1, 2491, 3682, 3217, -1, 3217, 3693, 3226, -1, 3682, 3693, 3217, -1, 3226, 3702, 3236, -1, 3693, 3702, 3226, -1, 3236, 3708, 3242, -1, 3702, 3708, 3236, -1, 3242, 3714, 3248, -1, 3708, 3714, 3242, -1, 3248, 3716, 3252, -1, 3714, 3716, 3248, -1, 3252, 3742, 3276, -1, 3716, 3742, 3252, -1, 3276, 3746, 3280, -1, 3742, 3746, 3276, -1, 3280, 3748, 3284, -1, 3746, 3748, 3280, -1, 3284, 3288, 3287, -1, 3748, 3288, 3284, -1, 3287, 3289, 2829, -1, 3288, 3289, 3287, -1, 2829, 3299, 2830, -1, 3289, 3299, 2829, -1, 2830, 2464, 2466, -1, 3299, 2464, 2830, -1, 2462, 3743, 2463, -1, 2463, 3743, 3277, -1, 3277, 3425, 2958, -1, 3743, 3425, 3277, -1, 2958, 3427, 2963, -1, 3425, 3427, 2958, -1, 2963, 3434, 2969, -1, 3427, 3434, 2963, -1, 2969, 3441, 2974, -1, 3434, 3441, 2969, -1, 2974, 3446, 2980, -1, 3441, 3446, 2974, -1, 2980, 3460, 2994, -1, 3446, 3460, 2980, -1, 2994, 3463, 2998, -1, 3460, 3463, 2994, -1, 2998, 3466, 3001, -1, 3463, 3466, 2998, -1, 3001, 3469, 3003, -1, 3466, 3469, 3001, -1, 3003, 3475, 3010, -1, 3469, 3475, 3003, -1, 3010, 3630, 3158, -1, 3475, 3630, 3010, -1, 3158, 2436, 2438, -1, 3630, 2436, 3158, -1, 2702, 2701, 3172, -1, 3642, 3172, 3175, -1, 3642, 2702, 3172, -1, 3647, 3175, 3182, -1, 3647, 3642, 3175, -1, 3653, 3182, 3180, -1, 3653, 3647, 3182, -1, 3651, 3180, 3177, -1, 3651, 3653, 3180, -1, 3643, 3177, 3176, -1, 3643, 3651, 3177, -1, 3644, 3176, 3157, -1, 3644, 3643, 3176, -1, 3629, 3644, 3157, -1, 3751, 2840, 3281, -1, 3751, 3308, 2840, -1, 3738, 3281, 3282, -1, 3738, 3751, 3281, -1, 3712, 3282, 3247, -1, 3712, 3738, 3282, -1, 3699, 3247, 3235, -1, 3699, 3712, 3247, -1, 3669, 3235, 3205, -1, 3669, 3699, 3235, -1, 3670, 3205, 3206, -1, 3670, 3669, 3205, -1, 3343, 3206, 2879, -1, 3343, 3670, 3206, -1, 3309, 2689, 2849, -1, 3309, 2690, 2689, -1, 3311, 2849, 2848, -1, 3311, 3309, 2849, -1, 3297, 2848, 2847, -1, 3297, 3311, 2848, -1, 3295, 2847, 2844, -1, 3295, 3297, 2847, -1, 3296, 2844, 2843, -1, 3296, 3295, 2844, -1, 3312, 2843, 2842, -1, 3312, 3296, 2843, -1, 3310, 2842, 2841, -1, 3310, 3312, 2842, -1, 3603, 3093, 3139, -1, 3603, 3557, 3093, -1, 3604, 3139, 3138, -1, 3604, 3603, 3139, -1, 3634, 3138, 3169, -1, 3634, 3604, 3138, -1, 3635, 3169, 3168, -1, 3635, 3634, 3169, -1, 3657, 3168, 3192, -1, 3657, 3635, 3168, -1, 3662, 3192, 3197, -1, 3662, 3657, 3192, -1, 3325, 3197, 2858, -1, 3325, 3662, 3197, -1, 3362, 2900, 3654, -1, 3654, 2900, 3183, -1, 3373, 2907, 3419, -1, 3419, 2907, 2955, -1, 2878, 3345, 2973, -1, 2973, 3345, 3439, -1, 2896, 2995, 3361, -1, 2995, 3459, 3361, -1, 3373, 3365, 2907, -1, 2907, 3365, 2898, -1, 2898, 3359, 2894, -1, 3365, 3359, 2898, -1, 2894, 3346, 2881, -1, 3359, 3346, 2894, -1, 2881, 3341, 2875, -1, 3346, 3341, 2881, -1, 2875, 3336, 2863, -1, 3341, 3336, 2875, -1, 2863, 3339, 2864, -1, 3336, 3339, 2863, -1, 2864, 3345, 2878, -1, 3339, 3345, 2864, -1, 3362, 3396, 2900, -1, 2900, 3396, 2930, -1, 2930, 3398, 2933, -1, 3396, 3398, 2930, -1, 2933, 3400, 2937, -1, 3398, 3400, 2933, -1, 2937, 3403, 2938, -1, 3400, 3403, 2937, -1, 2938, 3407, 2943, -1, 3403, 3407, 2938, -1, 2943, 3412, 2948, -1, 3407, 3412, 2943, -1, 2948, 3419, 2955, -1, 3412, 3419, 2948, -1, 3439, 3652, 2973, -1, 2973, 3652, 3189, -1, 3189, 3628, 3170, -1, 3652, 3628, 3189, -1, 3170, 3611, 3146, -1, 3628, 3611, 3170, -1, 3146, 3597, 3133, -1, 3611, 3597, 3146, -1, 3133, 3585, 3123, -1, 3597, 3585, 3133, -1, 3123, 3577, 3111, -1, 3585, 3577, 3123, -1, 3111, 3459, 2995, -1, 3577, 3459, 3111, -1, 2896, 3361, 3188, -1, 3188, 3650, 3179, -1, 3361, 3650, 3188, -1, 3179, 3640, 3156, -1, 3650, 3640, 3179, -1, 3156, 3622, 3165, -1, 3640, 3622, 3156, -1, 3165, 3627, 3184, -1, 3622, 3627, 3165, -1, 3184, 3646, 3190, -1, 3627, 3646, 3184, -1, 3190, 3655, 3183, -1, 3646, 3655, 3190, -1, 3655, 3654, 3183, -1, 2434, 2978, 2435, -1, 2435, 2978, 3442, -1, 3442, 2860, 3329, -1, 2978, 2860, 3442, -1, 3329, 2856, 3321, -1, 2860, 2856, 3329, -1, 3321, 2852, 3317, -1, 2856, 2852, 3321, -1, 3317, 2839, 3307, -1, 2852, 2839, 3317, -1, 3307, 3228, 3692, -1, 2839, 3228, 3307, -1, 3692, 3220, 3685, -1, 3228, 3220, 3692, -1, 3685, 3215, 3680, -1, 3220, 3215, 3685, -1, 3680, 3210, 3674, -1, 3215, 3210, 3680, -1, 3674, 3201, 3666, -1, 3210, 3201, 3674, -1, 3666, 3198, 3663, -1, 3201, 3198, 3666, -1, 3663, 3193, 3658, -1, 3198, 3193, 3663, -1, 3658, 2408, 2410, -1, 3193, 2408, 3658, -1, 2406, 3085, 2407, -1, 2407, 3085, 3550, -1, 3550, 3005, 3473, -1, 3085, 3005, 3550, -1, 3473, 3002, 3468, -1, 3005, 3002, 3473, -1, 3468, 2999, 3465, -1, 3002, 2999, 3468, -1, 3465, 2996, 3462, -1, 2999, 2996, 3465, -1, 3462, 2990, 3456, -1, 2996, 2990, 3462, -1, 3456, 2986, 3447, -1, 2990, 2986, 3456, -1, 3447, 2979, 3444, -1, 2986, 2979, 3447, -1, 3444, 2975, 3438, -1, 2979, 2975, 3444, -1, 3438, 2972, 3437, -1, 2975, 2972, 3438, -1, 3437, 2971, 3436, -1, 2972, 2971, 3437, -1, 3436, 2927, 3392, -1, 2971, 2927, 3436, -1, 3392, 2380, 2382, -1, 2927, 2380, 3392, -1, 2378, 3251, 2379, -1, 2379, 3251, 3717, -1, 3717, 3213, 3678, -1, 3251, 3213, 3717, -1, 3678, 3207, 3673, -1, 3213, 3207, 3678, -1, 3673, 3199, 3665, -1, 3207, 3199, 3673, -1, 3665, 3053, 3518, -1, 3199, 3053, 3665, -1, 3518, 3046, 3513, -1, 3053, 3046, 3518, -1, 3513, 3044, 3509, -1, 3046, 3044, 3513, -1, 3509, 3040, 3504, -1, 3044, 3040, 3509, -1, 3504, 3039, 3503, -1, 3040, 3039, 3504, -1, 3503, 3028, 3496, -1, 3039, 3028, 3503, -1, 3496, 3023, 3487, -1, 3028, 3023, 3496, -1, 3487, 3018, 3482, -1, 3023, 3018, 3487, -1, 3482, 2352, 2354, -1, 3018, 2352, 3482, -1, 2350, 3221, 2351, -1, 2351, 3221, 3686, -1, 3686, 3070, 3531, -1, 3221, 3070, 3686, -1, 3531, 3063, 3527, -1, 3070, 3063, 3531, -1, 3527, 3055, 3519, -1, 3063, 3055, 3527, -1, 3519, 3049, 3512, -1, 3055, 3049, 3519, -1, 3512, 3045, 3508, -1, 3049, 3045, 3512, -1, 3508, 3038, 3502, -1, 3045, 3038, 3508, -1, 3502, 3022, 3490, -1, 3038, 3022, 3502, -1, 3490, 3016, 3484, -1, 3022, 3016, 3490, -1, 3484, 3015, 3483, -1, 3016, 3015, 3484, -1, 3483, 3021, 3486, -1, 3015, 3021, 3483, -1, 3486, 2833, 3301, -1, 3021, 2833, 3486, -1, 3301, 2324, 2326, -1, 2833, 2324, 3301, -1, 2322, 2861, 2323, -1, 2323, 2861, 3328, -1, 3328, 2855, 3319, -1, 2861, 2855, 3328, -1, 3319, 2832, 3294, -1, 2855, 2832, 3319, -1, 3294, 2831, 3292, -1, 2832, 2831, 3294, -1, 3292, 2828, 3298, -1, 2831, 2828, 3292, -1, 3298, 2846, 3315, -1, 2828, 2846, 3298, -1, 3315, 2850, 3313, -1, 2846, 2850, 3315, -1, 3313, 3097, 3560, -1, 2850, 3097, 3313, -1, 3560, 3096, 3559, -1, 3097, 3096, 3560, -1, 3559, 3098, 3563, -1, 3096, 3098, 3559, -1, 3563, 3100, 3564, -1, 3098, 3100, 3563, -1, 3564, 3101, 3565, -1, 3100, 3101, 3564, -1, 3565, 2296, 2298, -1, 3101, 2296, 3565, -1, 2294, 3268, 2295, -1, 2295, 3268, 3733, -1, 3733, 3058, 3523, -1, 3268, 3058, 3733, -1, 3523, 3240, 3705, -1, 3058, 3240, 3523, -1, 3705, 3234, 3700, -1, 3240, 3234, 3705, -1, 3700, 3230, 3697, -1, 3234, 3230, 3700, -1, 3697, 3223, 3689, -1, 3230, 3223, 3697, -1, 3689, 3219, 3684, -1, 3223, 3219, 3689, -1, 3684, 3211, 3677, -1, 3219, 3211, 3684, -1, 3677, 3204, 3671, -1, 3211, 3204, 3677, -1, 3671, 3200, 3664, -1, 3204, 3200, 3671, -1, 3664, 2993, 3454, -1, 3200, 2993, 3664, -1, 3454, 2983, 3448, -1, 2993, 2983, 3454, -1, 3448, 2268, 2270, -1, 2983, 2268, 3448, -1, 2266, 2911, 2267, -1, 2267, 2911, 3378, -1, 3378, 2912, 3379, -1, 2911, 2912, 3378, -1, 3379, 3263, 3730, -1, 2912, 3263, 3379, -1, 3730, 3259, 3727, -1, 3263, 3259, 3730, -1, 3727, 3258, 3723, -1, 3259, 3258, 3727, -1, 3723, 3253, 3719, -1, 3258, 3253, 3723, -1, 3719, 3250, 3715, -1, 3253, 3250, 3719, -1, 3715, 3246, 3711, -1, 3250, 3246, 3715, -1, 3711, 3245, 3710, -1, 3246, 3245, 3711, -1, 3710, 3243, 3709, -1, 3245, 3243, 3710, -1, 3709, 3091, 3555, -1, 3243, 3091, 3709, -1, 3555, 3084, 3549, -1, 3091, 3084, 3555, -1, 3549, 2240, 2242, -1, 3084, 2240, 3549, -1, 2238, 3107, 2239, -1, 2239, 3107, 3571, -1, 3571, 3004, 3467, -1, 3107, 3004, 3571, -1, 3467, 3000, 3464, -1, 3004, 3000, 3467, -1, 3464, 2997, 3461, -1, 3000, 2997, 3464, -1, 3461, 2989, 3453, -1, 2997, 2989, 3461, -1, 3453, 2981, 3445, -1, 2989, 2981, 3453, -1, 3445, 2976, 3440, -1, 2981, 2976, 3445, -1, 3440, 2970, 3435, -1, 2976, 2970, 3440, -1, 3435, 2964, 3429, -1, 2970, 2964, 3435, -1, 3429, 2962, 3428, -1, 2964, 2962, 3429, -1, 3428, 2966, 3431, -1, 2962, 2966, 3428, -1, 3431, 3254, 3720, -1, 2966, 3254, 3431, -1, 3720, 2212, 2214, -1, 3254, 2212, 3720, -1, 2210, 3078, 2211, -1, 2211, 3078, 3542, -1, 3542, 2965, 3430, -1, 3078, 2965, 3542, -1, 3430, 2960, 3421, -1, 2965, 2960, 3430, -1, 3421, 2945, 3408, -1, 2960, 2945, 3421, -1, 3408, 2932, 3397, -1, 2945, 2932, 3408, -1, 3397, 2926, 3391, -1, 2932, 2926, 3397, -1, 3391, 2908, 3372, -1, 2926, 2908, 3391, -1, 3372, 2895, 3360, -1, 2908, 2895, 3372, -1, 3360, 2889, 3353, -1, 2895, 2889, 3360, -1, 3353, 2883, 3348, -1, 2889, 2883, 3353, -1, 3348, 2882, 3347, -1, 2883, 2882, 3348, -1, 3347, 3225, 3690, -1, 2882, 3225, 3347, -1, 3690, 2184, 2186, -1, 3225, 2184, 3690, -1, 2182, 3232, 2183, -1, 2183, 3232, 3696, -1, 3696, 3238, 3703, -1, 3232, 3238, 3696, -1, 3703, 3239, 3704, -1, 3238, 3239, 3703, -1, 3704, 3025, 3489, -1, 3239, 3025, 3704, -1, 3489, 3024, 3488, -1, 3025, 3024, 3489, -1, 3488, 2992, 3458, -1, 3024, 2992, 3488, -1, 3458, 2985, 3451, -1, 2992, 2985, 3458, -1, 3451, 2968, 3433, -1, 2985, 2968, 3451, -1, 3433, 2961, 3426, -1, 2968, 2961, 3433, -1, 3426, 2947, 3414, -1, 2961, 2947, 3426, -1, 3414, 2935, 3402, -1, 2947, 2935, 3414, -1, 3402, 2928, 3393, -1, 2935, 2928, 3402, -1, 3393, 2156, 2158, -1, 2928, 2156, 3393, -1, 2154, 2902, 2155, -1, 2155, 2902, 3367, -1, 3367, 2901, 3366, -1, 2902, 2901, 3367, -1, 3366, 3095, 3562, -1, 2901, 3095, 3366, -1, 3562, 3094, 3561, -1, 3095, 3094, 3562, -1, 3561, 3088, 3553, -1, 3094, 3088, 3561, -1, 3553, 3080, 3545, -1, 3088, 3080, 3553, -1, 3545, 3073, 3539, -1, 3080, 3073, 3545, -1, 3539, 3065, 3532, -1, 3073, 3065, 3539, -1, 3532, 3054, 3521, -1, 3065, 3054, 3532, -1, 3521, 3048, 3515, -1, 3054, 3048, 3521, -1, 3515, 3047, 3514, -1, 3048, 3047, 3515, -1, 3514, 3270, 3736, -1, 3047, 3270, 3514, -1, 3736, 2128, 2130, -1, 3270, 2128, 3736, -1, 2126, 3167, 2127, -1, 2127, 3167, 3626, -1, 3626, 3186, 3645, -1, 3167, 3186, 3626, -1, 3645, 3191, 3656, -1, 3186, 3191, 3645, -1, 3656, 3129, 3592, -1, 3191, 3129, 3656, -1, 3592, 3118, 3582, -1, 3129, 3118, 3592, -1, 3582, 3112, 3574, -1, 3118, 3112, 3582, -1, 3574, 3104, 3568, -1, 3112, 3104, 3574, -1, 3568, 3092, 3556, -1, 3104, 3092, 3568, -1, 3556, 3087, 3552, -1, 3092, 3087, 3556, -1, 3552, 3083, 3548, -1, 3087, 3083, 3552, -1, 3548, 2914, 3380, -1, 3083, 2914, 3548, -1, 3380, 2910, 3376, -1, 2914, 2910, 3380, -1, 3376, 2100, 2102, -1, 2910, 2100, 3376, -1, 2098, 3195, 2099, -1, 2099, 3195, 3660, -1, 3660, 3196, 3661, -1, 3195, 3196, 3660, -1, 3661, 3275, 3741, -1, 3196, 3275, 3661, -1, 3741, 3274, 3740, -1, 3275, 3274, 3741, -1, 3740, 3272, 3737, -1, 3274, 3272, 3740, -1, 3737, 3269, 3734, -1, 3272, 3269, 3737, -1, 3734, 3265, 3729, -1, 3269, 3265, 3734, -1, 3729, 3260, 3724, -1, 3265, 3260, 3729, -1, 3724, 3256, 3721, -1, 3260, 3256, 3724, -1, 3721, 3255, 3718, -1, 3256, 3255, 3721, -1, 3718, 3126, 3584, -1, 3255, 3126, 3718, -1, 3584, 3115, 3579, -1, 3126, 3115, 3584, -1, 3579, 2072, 2074, -1, 3115, 2072, 3579, -1, 2070, 2903, 2071, -1, 2071, 2903, 3369, -1, 3369, 2904, 3370, -1, 2903, 2904, 3369, -1, 3370, 2905, 3371, -1, 2904, 2905, 3370, -1, 3371, 2906, 3368, -1, 2905, 2906, 3371, -1, 3368, 3233, 3698, -1, 2906, 3233, 3368, -1, 3698, 3227, 3694, -1, 3233, 3227, 3698, -1, 3694, 3224, 3687, -1, 3227, 3224, 3694, -1, 3687, 3218, 3683, -1, 3224, 3218, 3687, -1, 3683, 3214, 3679, -1, 3218, 3214, 3683, -1, 3679, 3209, 3675, -1, 3214, 3209, 3679, -1, 3675, 3089, 3554, -1, 3209, 3089, 3675, -1, 3554, 3081, 3546, -1, 3089, 3081, 3554, -1, 3546, 2044, 2046, -1, 3081, 2044, 3546, -1, 2042, 2939, 2043, -1, 2043, 2939, 3404, -1, 3404, 2940, 3406, -1, 2939, 2940, 3404, -1, 3406, 2944, 3411, -1, 2940, 2944, 3406, -1, 3411, 2949, 3417, -1, 2944, 2949, 3411, -1, 3417, 2956, 3422, -1, 2949, 2956, 3417, -1, 3422, 3113, 3578, -1, 2956, 3113, 3422, -1, 3578, 3257, 3722, -1, 3113, 3257, 3578, -1, 3722, 3249, 3713, -1, 3257, 3249, 3722, -1, 3713, 3244, 3707, -1, 3249, 3244, 3713, -1, 3707, 3241, 3706, -1, 3244, 3241, 3707, -1, 3706, 3237, 3701, -1, 3241, 3237, 3706, -1, 3701, 3231, 3695, -1, 3237, 3231, 3701, -1, 3695, 2016, 2018, -1, 3231, 2016, 3695, -1, 2014, 3264, 2015, -1, 2015, 3264, 3728, -1, 3728, 3262, 3726, -1, 3264, 3262, 3728, -1, 3726, 3261, 3725, -1, 3262, 3261, 3726, -1, 3725, 3266, 3731, -1, 3261, 3266, 3725, -1, 3731, 3267, 3732, -1, 3266, 3267, 3731, -1, 3732, 3271, 3735, -1, 3267, 3271, 3732, -1, 3735, 3273, 3739, -1, 3271, 3273, 3735, -1, 3739, 2957, 3424, -1, 3273, 2957, 3739, -1, 3424, 2951, 3415, -1, 2957, 2951, 3424, -1, 3415, 2942, 3410, -1, 2951, 2942, 3415, -1, 3410, 3216, 3681, -1, 2942, 3216, 3410, -1, 3681, 3208, 3672, -1, 3216, 3208, 3681, -1, 3672, 1988, 1990, -1, 3208, 1988, 3672, -1, 1986, 2915, 1987, -1, 1987, 2915, 3381, -1, 3381, 3077, 3541, -1, 2915, 3077, 3381, -1, 3541, 3074, 3538, -1, 3077, 3074, 3541, -1, 3538, 3068, 3530, -1, 3074, 3068, 3538, -1, 3530, 3060, 3520, -1, 3068, 3060, 3530, -1, 3520, 3051, 3511, -1, 3060, 3051, 3520, -1, 3511, 3042, 3506, -1, 3051, 3042, 3511, -1, 3506, 3027, 3491, -1, 3042, 3027, 3506, -1, 3491, 3020, 3481, -1, 3027, 3020, 3491, -1, 3481, 2890, 3355, -1, 3020, 2890, 3481, -1, 3355, 2884, 3349, -1, 2890, 2884, 3355, -1, 3349, 2880, 3344, -1, 2884, 2880, 3349, -1, 3344, 1960, 1962, -1, 2880, 1960, 3344, -1, 1958, 3222, 1959, -1, 1959, 3222, 3688, -1, 3688, 3212, 3676, -1, 3222, 3212, 3688, -1, 3676, 3203, 3668, -1, 3212, 3203, 3676, -1, 3668, 3202, 3667, -1, 3203, 3202, 3668, -1, 3667, 3194, 3659, -1, 3202, 3194, 3667, -1, 3659, 3187, 3649, -1, 3194, 3187, 3659, -1, 3649, 3174, 3632, -1, 3187, 3174, 3649, -1, 3632, 3173, 3631, -1, 3174, 3173, 3632, -1, 3631, 3166, 3623, -1, 3173, 3166, 3631, -1, 3623, 3069, 3533, -1, 3166, 3069, 3623, -1, 3533, 3061, 3524, -1, 3069, 3061, 3533, -1, 3524, 3052, 3516, -1, 3061, 3052, 3524, -1, 3516, 1932, 1934, -1, 3052, 1932, 3516, -1, 1930, 3009, 1931, -1, 1931, 3009, 3474, -1, 3474, 3076, 3543, -1, 3009, 3076, 3474, -1, 3543, 3067, 3535, -1, 3076, 3067, 3543, -1, 3535, 3050, 3517, -1, 3067, 3050, 3535, -1, 3517, 3043, 3510, -1, 3050, 3043, 3517, -1, 3510, 3037, 3505, -1, 3043, 3037, 3510, -1, 3505, 3026, 3492, -1, 3037, 3026, 3505, -1, 3492, 3017, 3485, -1, 3026, 3017, 3492, -1, 3485, 3014, 3479, -1, 3017, 3014, 3485, -1, 3479, 2988, 3455, -1, 3014, 2988, 3479, -1, 3455, 2982, 3449, -1, 2988, 2982, 3455, -1, 3449, 2977, 3443, -1, 2982, 2977, 3449, -1, 3443, 1904, 1906, -1, 2977, 1904, 3443, -1, 1902, 3159, 1903, -1, 1903, 3159, 3633, -1, 3633, 3160, 3636, -1, 3159, 3160, 3633, -1, 3636, 3162, 3637, -1, 3160, 3162, 3636, -1, 3637, 3163, 3638, -1, 3162, 3163, 3637, -1, 3638, 3164, 3625, -1, 3163, 3164, 3638, -1, 3625, 3131, 3596, -1, 3164, 3131, 3625, -1, 3596, 3128, 3594, -1, 3131, 3128, 3596, -1, 3594, 3110, 3576, -1, 3128, 3110, 3594, -1, 3576, 3109, 3575, -1, 3110, 3109, 3576, -1, 3575, 3106, 3572, -1, 3109, 3106, 3575, -1, 3572, 3103, 3569, -1, 3106, 3103, 3572, -1, 3569, 3041, 3507, -1, 3103, 3041, 3569, -1, 3507, 1876, 1878, -1, 3041, 1876, 3507, -1, 3558, 3079, 3544, -1, 3544, 3079, 3536, -1, 3090, 3079, 3558, -1, 3536, 3071, 3522, -1, 3079, 3071, 3536, -1, 3522, 3059, 3528, -1, 3071, 3059, 3522, -1, 3528, 3062, 3540, -1, 3059, 3062, 3528, -1, 3540, 3075, 3547, -1, 3062, 3075, 3540, -1, 3547, 3082, 3567, -1, 3075, 3082, 3547, -1, 3567, 3102, 3570, -1, 3082, 3102, 3567, -1, 3570, 3105, 3573, -1, 3102, 3105, 3570, -1, 3573, 3108, 3593, -1, 3105, 3108, 3573, -1, 3593, 3125, 3595, -1, 3108, 3125, 3593, -1, 3595, 3130, 3599, -1, 3125, 3130, 3595, -1, 3599, 3132, 3620, -1, 3130, 3132, 3599, -1, 3132, 3154, 3620, -1, 3143, 3610, 3154, -1, 3154, 3610, 3620, -1, 3580, 3114, 3558, -1, 3558, 3114, 3090, -1, 3337, 2857, 3326, -1, 2872, 2857, 3337, -1, 3326, 2845, 3314, -1, 2857, 2845, 3326, -1, 3314, 2827, 3305, -1, 2845, 2827, 3314, -1, 3305, 2826, 3293, -1, 2827, 2826, 3305, -1, 3293, 2854, 3318, -1, 2826, 2854, 3293, -1, 3318, 2859, 3327, -1, 2854, 2859, 3318, -1, 3327, 2874, 3338, -1, 2859, 2874, 3327, -1, 3338, 2916, 3383, -1, 2874, 2916, 3338, -1, 3383, 2936, 3401, -1, 2916, 2936, 3383, -1, 3401, 2950, 3416, -1, 2936, 2950, 3401, -1, 3416, 2967, 3432, -1, 2950, 2967, 3416, -1, 3432, 2984, 3450, -1, 2967, 2984, 3432, -1, 3450, 2991, 3457, -1, 2984, 2991, 3450, -1, 3008, 3472, 2991, -1, 2991, 3472, 3457, -1, 3364, 2899, 3337, -1, 3337, 2899, 2872, -1, 3551, 2876, 3342, -1, 3086, 2876, 3551, -1, 3342, 2862, 3334, -1, 2876, 2862, 3342, -1, 3334, 2853, 3320, -1, 2862, 2853, 3334, -1, 3320, 2837, 3303, -1, 2853, 2837, 3320, -1, 3303, 2836, 3302, -1, 2837, 2836, 3303, -1, 3302, 2851, 3316, -1, 2836, 2851, 3302, -1, 3316, 3185, 3648, -1, 2851, 3185, 3316, -1, 3648, 3181, 3641, -1, 3185, 3181, 3648, -1, 3641, 3155, 3618, -1, 3181, 3155, 3641, -1, 3618, 3145, 3607, -1, 3155, 3145, 3618, -1, 3607, 3127, 3591, -1, 3145, 3127, 3607, -1, 3591, 3117, 3583, -1, 3127, 3117, 3591, -1, 3583, 2987, 3452, -1, 3117, 2987, 3583, -1, 3418, 2987, 2952, -1, 3452, 2987, 3418, -1, 3030, 3551, 3501, -1, 3086, 3551, 3030, -1, 3377, 3072, 3537, -1, 2913, 3072, 3377, -1, 3537, 3064, 3529, -1, 3072, 3064, 3537, -1, 3529, 3057, 3526, -1, 3064, 3057, 3529, -1, 3526, 3056, 3525, -1, 3057, 3056, 3526, -1, 3525, 3066, 3534, -1, 3056, 3066, 3525, -1, 3534, 2959, 3423, -1, 3066, 2959, 3534, -1, 3423, 2954, 3413, -1, 2959, 2954, 3423, -1, 3413, 2946, 3409, -1, 2954, 2946, 3413, -1, 3409, 2931, 3394, -1, 2946, 2931, 3409, -1, 3394, 2925, 3388, -1, 2931, 2925, 3394, -1, 3388, 2917, 3382, -1, 2925, 2917, 3388, -1, 3382, 2877, 3340, -1, 2917, 2877, 3382, -1, 3340, 2873, 3335, -1, 2877, 2873, 3340, -1, 3330, 2873, 2865, -1, 3335, 2873, 3330, -1, 2892, 3377, 3357, -1, 2913, 3377, 2892, -1, 2924, 2692, 3390, -1, 2924, 2695, 2692, -1, 2923, 3390, 3389, -1, 2923, 2924, 3390, -1, 2929, 3389, 3395, -1, 2929, 2923, 3389, -1, 2934, 3399, 3405, -1, 2934, 3395, 3399, -1, 2934, 2929, 3395, -1, 2941, 3405, 3420, -1, 2941, 2934, 3405, -1, 2953, 3420, 3418, -1, 2953, 2941, 3420, -1, 2952, 2953, 3418, -1, 3495, 3029, 3036, -1, 3495, 3494, 3029, -1, 3493, 3036, 3035, -1, 3493, 3495, 3036, -1, 3497, 3035, 3034, -1, 3497, 3493, 3035, -1, 3498, 3034, 3033, -1, 3498, 3497, 3034, -1, 3499, 3033, 3032, -1, 3499, 3498, 3033, -1, 3500, 3032, 3031, -1, 3500, 3499, 3032, -1, 3501, 3031, 3030, -1, 3501, 3500, 3031, -1, 3358, 2693, 2893, -1, 3358, 2694, 2693, -1, 3352, 2893, 2888, -1, 3352, 3358, 2893, -1, 3350, 2888, 2887, -1, 3350, 3352, 2888, -1, 3354, 2887, 2886, -1, 3354, 3350, 2887, -1, 3351, 2886, 2885, -1, 3351, 3354, 2886, -1, 3356, 2885, 2891, -1, 3356, 3351, 2885, -1, 3357, 2891, 2892, -1, 3357, 3356, 2891, -1, 2866, 2688, 3333, -1, 2866, 2691, 2688, -1, 2867, 3333, 3332, -1, 2867, 2866, 3333, -1, 2868, 3332, 3322, -1, 2868, 2867, 3332, -1, 2869, 3322, 3324, -1, 2869, 2868, 3322, -1, 2870, 3324, 3323, -1, 2870, 2869, 3324, -1, 2871, 3323, 3331, -1, 2871, 2870, 3323, -1, 2865, 3331, 3330, -1, 2865, 2871, 3331, -1, 3374, 2897, 2909, -1, 3374, 3363, 2897, -1, 3384, 2909, 2922, -1, 3384, 3374, 2909, -1, 3385, 2922, 2921, -1, 3385, 3384, 2922, -1, 3386, 2921, 2918, -1, 3386, 3385, 2921, -1, 3387, 2918, 2920, -1, 3387, 3386, 2918, -1, 3375, 2920, 2919, -1, 3375, 3387, 2920, -1, 3364, 2919, 2899, -1, 3364, 3375, 2919, -1, 3019, 2696, 3480, -1, 3019, 2699, 2696, -1, 3013, 3480, 3478, -1, 3013, 3019, 3480, -1, 3012, 3478, 3477, -1, 3012, 3013, 3478, -1, 3011, 3477, 3476, -1, 3011, 3012, 3477, -1, 3006, 3476, 3471, -1, 3006, 3011, 3476, -1, 3007, 3471, 3470, -1, 3007, 3006, 3471, -1, 3008, 3470, 3472, -1, 3008, 3007, 3470, -1, 3581, 2697, 3116, -1, 3581, 2698, 2697, -1, 3587, 3116, 3119, -1, 3587, 3581, 3116, -1, 3588, 3119, 3122, -1, 3588, 3587, 3119, -1, 3586, 3122, 3124, -1, 3586, 3588, 3122, -1, 3590, 3124, 3121, -1, 3590, 3586, 3124, -1, 3589, 3121, 3120, -1, 3589, 3590, 3121, -1, 3580, 3120, 3114, -1, 3580, 3589, 3120, -1, 2703, 2700, 3619, -1, 3151, 3619, 3617, -1, 3151, 2703, 3619, -1, 3150, 3617, 3613, -1, 3150, 3151, 3617, -1, 3148, 3613, 3614, -1, 3148, 3150, 3613, -1, 3149, 3614, 3609, -1, 3149, 3148, 3614, -1, 3141, 3609, 3608, -1, 3141, 3149, 3609, -1, 3142, 3608, 3610, -1, 3142, 3141, 3608, -1, 3143, 3142, 3610, -1 - ] - } - castShadows FALSE - } - DEF vent Shape { - appearance Appearance { - material Material { - diffuseColor 0 0 0 - } - texture ImageTexture { - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.15457782 -0.022302806 0.1402345, -0.1490013 -0.022310242 0.14016761, -0.1490013 -0.022302777 0.1402345, -0.15457773 -0.022310317 0.1401678, -0.15457784 -0.022280604 0.14029801, -0.14900133 -0.022280484 0.14029802, -0.15457788 -0.022244826 0.1403549, -0.14900124 -0.02224493 0.14035478, -0.15457787 -0.022197396 0.14040251, -0.14900133 -0.022197306 0.14040238, -0.15457782 -0.022140443 0.14043811, -0.1490013 -0.022140369 0.14043809, -0.15457794 -0.022077128 0.14046031, -0.14900135 -0.022077069 0.1404603, -0.15457779 -0.022010237 0.14046779, -0.1490013 -0.022010237 0.14046767, -0.12338108 0.10352217 0.22902556, -0.12338108 0.10363202 0.2290131, -0.11454242 0.10352226 0.22902551, -0.11454248 0.10363202 0.22901326, -0.12338114 0.1037365 0.22897722, -0.11454242 0.10373656 0.2289772, -0.12338127 0.10383044 0.22891909, -0.11454241 0.10383056 0.2289191, -0.12338114 0.10390936 0.22884171, -0.11454235 0.10390942 0.22884174, -0.12338111 0.10396941 0.22874899, -0.11454237 0.10396953 0.22874901, -0.12385143 0.10343371 0.22933775, -0.12386917 0.10339256 0.22942451, -0.12392855 0.10352407 0.22935893, -0.12394896 0.10347511 0.2294596, -0.12400174 0.10340415 0.22975804, -0.12394582 0.10342012 0.22957391, -0.12391159 0.10336263 0.22969528, -0.12404311 0.10347305 0.22961725, -0.12404764 0.10353886 0.22948365, -0.12378263 0.10308407 0.22927679, -0.12376946 0.10322367 0.22925825, -0.12376964 0.10311577 0.22920436, -0.1237538 0.10313506 0.22916278, -0.12373307 0.1032616 0.22917859, -0.12375814 0.10337286 0.2292185, -0.12379748 0.10333173 0.22930349, -0.12381293 0.10329635 0.22938058, -0.12386687 0.10334688 0.22952358, -0.12383793 0.10329933 0.22962931, -0.12378338 0.10319163 0.22933049, -0.12381086 0.10325749 0.22946922, -0.12378488 0.10321769 0.22956385, -0.12426424 0.10349272 0.22970213, -0.12410353 0.10342152 0.22981396, -0.12421106 0.10341366 0.22986022, -0.12378061 0.10315691 0.22941364, -0.12375534 0.1031221 0.22950225, -0.12377812 0.10305054 0.22935984, -0.12373328 0.10315369 0.22912444, -0.12375081 0.10301809 0.2294483, -0.1240617 0.1037254 0.22920436, -0.12413277 0.10364877 0.22935826, -0.12416609 0.1037647 0.22915846, -0.12424839 0.10367523 0.22933735, -0.12396321 0.10366245 0.22923474, -0.12402435 0.10359722 0.22936599, -0.1241594 0.1035801 0.22949551, -0.12428038 0.10357697 0.22953388, -0.12387656 0.10357912 0.22924748, -0.12415314 0.10350262 0.22965075, -0.12380683 0.1034808 0.22924186, -0.12915544 0.10972482 0.21662252, -0.12915538 0.10983433 0.21660998, -0.12031671 0.10972476 0.21662228, -0.12031679 0.10983446 0.21661001, -0.12915553 0.10993893 0.21657404, -0.12031676 0.10993898 0.21657407, -0.12915544 0.11003286 0.21651594, -0.1203167 0.11003292 0.21651599, -0.12915549 0.1101118 0.21643871, -0.12031685 0.11011189 0.21643868, -0.12915553 0.11017187 0.21634588, -0.12031676 0.110172 0.21634582, -0.11444575 0.10826975 0.21947221, -0.11924706 0.10956222 0.21688727, -0.1143342 0.10833688 0.21952263, -0.11921725 0.10967475 0.21688806, -0.11426707 0.10839155 0.21953782, -0.11917613 0.10978121 0.21686485, -0.11422694 0.1084349 0.21953648, -0.11420086 0.10847196 0.21952648, -0.11418329 0.10850641 0.21950999, -0.11912607 0.10987562 0.21681908, -0.11417192 0.10854112 0.21948695, -0.11416708 0.10857527 0.21945737, -0.11906964 0.10995308 0.21675314, -0.11416875 0.10860853 0.21942197, -0.11418028 0.10865135 0.21936633, -0.1141995 0.10868773 0.21930888, -0.11901015 0.11000952 0.21667059, -0.11422648 0.10872169 0.21924628, -0.12673864 0.10653491 0.22313614, -0.12675627 0.10649377 0.2232229, -0.12681565 0.10662515 0.22315757, -0.12683603 0.1065764 0.22325794, -0.12688896 0.10650511 0.22355635, -0.12683305 0.10652132 0.22337241, -0.12679872 0.10646375 0.22349374, -0.12693474 0.10664006 0.22328202, -0.12693033 0.10657425 0.22341566, -0.12666972 0.1061853 0.22307521, -0.12665667 0.10632473 0.22305678, -0.12665673 0.10621683 0.22300285, -0.12664126 0.10623637 0.22296126, -0.12662026 0.10636289 0.22297697, -0.12664531 0.10647407 0.22301705, -0.12668459 0.10643294 0.22310229, -0.1267001 0.10639749 0.22317906, -0.12675413 0.10644813 0.22332196, -0.12672505 0.10640056 0.22342785, -0.12667057 0.10629268 0.22312896, -0.12669806 0.10635868 0.22326751, -0.126672 0.10631879 0.22336216, -0.12715134 0.10659392 0.22350065, -0.12699065 0.10652263 0.22361247, -0.12709822 0.10651487 0.22365867, -0.12666768 0.10625826 0.22321196, -0.12664242 0.1062234 0.22330062, -0.12666517 0.10615169 0.22315829, -0.1266205 0.10625489 0.22292276, -0.12663795 0.10611922 0.22324656, -0.12694877 0.10682665 0.22300287, -0.12701997 0.10674985 0.22315662, -0.12705325 0.10686579 0.22295697, -0.12713547 0.1067764 0.22313565, -0.1268502 0.10676354 0.22303312, -0.12691145 0.1066983 0.22316463, -0.12704656 0.1066813 0.22329395, -0.12716742 0.10667819 0.22333221, -0.12676372 0.10668045 0.22304581, -0.1270403 0.10660388 0.22344939, -0.12669393 0.106582 0.2230403, -0.11742963 0.10662349 0.22282372, -0.12626836 0.10662337 0.22282369, -0.11742964 0.10673341 0.22281177, -0.12626833 0.10673319 0.2228118, -0.11742955 0.10683781 0.22277568, -0.12626836 0.10683759 0.22277541, -0.11742963 0.10693175 0.22271746, -0.12626828 0.10693163 0.22271763, -0.11742958 0.10701065 0.22264034, -0.12626824 0.10701056 0.22264023, -0.12626824 0.10707077 0.22254744, -0.11742954 0.1070708 0.22254738, -0.118077 0.097231328 0.24174105, -0.11809467 0.097190291 0.24182768, -0.11815412 0.097321689 0.24176227, -0.1181744 0.097272605 0.24186265, -0.1182273 0.09720169 0.24216129, -0.11817154 0.097217694 0.24197714, -0.11813726 0.097160161 0.24209844, -0.11827324 0.097336441 0.24188693, -0.11826877 0.097270757 0.24202038, -0.11800817 0.096881643 0.24168004, -0.11799513 0.097021133 0.2416615, -0.1179952 0.096913442 0.24160756, -0.11797957 0.096932694 0.24156606, -0.11795868 0.09705919 0.24158166, -0.11798367 0.097170442 0.24162197, -0.11802302 0.097129241 0.24170682, -0.11803855 0.097093999 0.24178372, -0.11809254 0.097144455 0.24192688, -0.11806352 0.097096741 0.24203251, -0.11800906 0.096989051 0.24173374, -0.11803642 0.097055092 0.2418723, -0.11801049 0.097015157 0.24196689, -0.11848983 0.097290367 0.24210548, -0.11832903 0.097219035 0.24221718, -0.11843674 0.097211286 0.24226344, -0.11800621 0.096954539 0.24181679, -0.11798094 0.096919745 0.24190547, -0.1180037 0.0968481 0.24176311, -0.1179589 0.096951395 0.24152786, -0.11797638 0.096815825 0.24185126, -0.11828712 0.097523108 0.24160768, -0.11835845 0.097446367 0.24176133, -0.11839169 0.097562358 0.24156182, -0.11847402 0.097472847 0.24174045, -0.11818875 0.097459972 0.24163793, -0.11824992 0.097394839 0.24176933, -0.11838502 0.097377703 0.24189882, -0.11850585 0.097374618 0.24193703, -0.11810221 0.097376764 0.24165069, -0.11837865 0.097300231 0.24205409, -0.11803246 0.097278401 0.24164517, -0.11760664 0.097319812 0.2414287, -0.11760668 0.097429663 0.24141659, -0.10876805 0.097319871 0.24142875, -0.108768 0.097429618 0.2414165, -0.11760667 0.09753406 0.24138024, -0.108768 0.097533926 0.24138014, -0.1176067 0.097627982 0.24132229, -0.108768 0.097628042 0.24132247, -0.11760671 0.097707048 0.241245, -0.10876806 0.097706974 0.24124494, -0.11760677 0.097767055 0.24115227, -0.10876812 0.0977671 0.24115233, -0.11518969 0.094130218 0.24794285, -0.11520764 0.094088987 0.2480294, -0.11526692 0.094220445 0.24796401, -0.11528732 0.094171464 0.24806432, -0.11534017 0.094100475 0.24836293, -0.1152842 0.094116375 0.24817859, -0.11525004 0.094058976 0.24830019, -0.11538607 0.094235227 0.24808855, -0.11538173 0.094169497 0.24822222, -0.11512105 0.093780443 0.24788177, -0.11510792 0.093920007 0.24786292, -0.11510804 0.093812227 0.24780914, -0.11509243 0.093831435 0.24776758, -0.11507155 0.093958005 0.24778342, -0.11509658 0.094069287 0.2478233, -0.11513589 0.09402816 0.24790841, -0.11515141 0.093992516 0.24798535, -0.11520541 0.09404324 0.24812852, -0.11517644 0.093995616 0.24823402, -0.11512184 0.093887851 0.24793528, -0.11514936 0.093953893 0.24807388, -0.11512329 0.093914047 0.24816856, -0.11560275 0.094189063 0.24830696, -0.11544183 0.094117895 0.24841879, -0.11554964 0.094110176 0.24846518, -0.11511898 0.09385328 0.24801849, -0.11509368 0.093818441 0.24810712, -0.11511648 0.093746945 0.24796472, -0.11507168 0.093850151 0.24772941, -0.1150893 0.093714282 0.24805279, -0.11539996 0.094421789 0.24780916, -0.11547136 0.094345137 0.24796318, -0.11550452 0.094461069 0.24776316, -0.11558676 0.094371721 0.24794216, -0.11530158 0.094358698 0.24783938, -0.11536267 0.094293609 0.24797095, -0.11549795 0.094276413 0.24810062, -0.11561871 0.094273135 0.24813841, -0.11521506 0.094275638 0.24785219, -0.11549152 0.094199076 0.24825582, -0.11514534 0.094177186 0.24784677, -0.1147196 0.094218567 0.24763025, -0.11471958 0.094328448 0.24761808, -0.10588087 0.094218627 0.24763025, -0.10588087 0.094328478 0.24761803, -0.1147196 0.094432905 0.24758185, -0.1058809 0.094432995 0.24758191, -0.11471955 0.094526872 0.24752396, -0.10588102 0.094527021 0.24752401, -0.11471963 0.094605908 0.24744661, -0.10588087 0.094605848 0.24744658, -0.11471952 0.09466581 0.24735373, -0.10588102 0.0946659 0.24735381, -0.11230274 0.091028839 0.25414425, -0.11232041 0.090987727 0.25423098, -0.11237983 0.09111923 0.25416553, -0.11240014 0.09107016 0.25426596, -0.11245306 0.090999275 0.25456458, -0.11239724 0.091015264 0.25438029, -0.1123628 0.090957776 0.2545017, -0.11249894 0.091133967 0.25429022, -0.11249442 0.091068193 0.25442362, -0.11223383 0.090679243 0.25408331, -0.11222079 0.090818763 0.25406456, -0.11222081 0.090710953 0.25401083, -0.1122053 0.090730295 0.25396943, -0.11218441 0.090856925 0.25398511, -0.11220941 0.090967879 0.25402498, -0.11224873 0.090926796 0.25410998, -0.11226444 0.09089154 0.25418717, -0.11231837 0.090942115 0.25433016, -0.11228926 0.090894505 0.25443578, -0.11223486 0.090786561 0.25413704, -0.11226209 0.090852663 0.25427568, -0.1122362 0.090812802 0.25437024, -0.11271566 0.091087937 0.25450876, -0.11255476 0.091016635 0.25462055, -0.11266235 0.091008931 0.25466675, -0.11223182 0.090751991 0.25421989, -0.11220659 0.09071739 0.25430867, -0.11222954 0.090645686 0.25416622, -0.11218466 0.090748876 0.25393093, -0.11220212 0.090613276 0.25425476, -0.11251286 0.0913205 0.25401086, -0.11258411 0.091243878 0.25416464, -0.11261745 0.091359764 0.25396496, -0.1126997 0.091270357 0.25414389, -0.11241442 0.091257468 0.25404119, -0.11247557 0.091192245 0.25417247, -0.11261073 0.091175303 0.25430208, -0.11273156 0.091172144 0.25434017, -0.11232784 0.091174349 0.25405371, -0.11260441 0.091097817 0.25445735, -0.11225818 0.091075942 0.25404835, -0.1118324 0.091117308 0.25383204, -0.11183237 0.09122698 0.25381958, -0.10299371 0.091117367 0.25383207, -0.10299368 0.091227189 0.25381964, -0.11183253 0.091331586 0.2537834, -0.10299377 0.091331586 0.2537834, -0.11183237 0.091425464 0.25372553, -0.1029938 0.091425702 0.25372556, -0.11183237 0.09150438 0.25364804, -0.10299374 0.091504559 0.25364816, -0.11183257 0.091564566 0.25355542, -0.10299376 0.091564581 0.25355548, -0.10941556 0.087927833 0.26034588, -0.10943326 0.087886587 0.26043248, -0.10949257 0.088018075 0.2603671, -0.109513 0.08796902 0.26046741, -0.10956596 0.087898031 0.26076612, -0.10950994 0.087914094 0.26058185, -0.10947576 0.087856427 0.26070327, -0.10961173 0.088032886 0.26049167, -0.10960726 0.087967023 0.26062524, -0.10934672 0.087578073 0.2602849, -0.1093336 0.087717548 0.2602663, -0.1093335 0.087609753 0.26021236, -0.10931811 0.087629095 0.2601707, -0.10929725 0.087755695 0.26018679, -0.10932216 0.087866798 0.26022649, -0.10936156 0.087825552 0.26031166, -0.10937716 0.087790355 0.26038891, -0.10943115 0.0878409 0.26053166, -0.10940212 0.087793395 0.26063746, -0.10934751 0.087685451 0.26033872, -0.10937513 0.087751612 0.26047713, -0.10934901 0.087711677 0.26057184, -0.10982834 0.087986574 0.26071018, -0.10966767 0.087915346 0.26082218, -0.10977516 0.087907568 0.26086831, -0.10934469 0.087651029 0.26042163, -0.10931946 0.087616131 0.26051021, -0.10934225 0.087544575 0.26036805, -0.10929756 0.087647781 0.26013261, -0.10931501 0.08751215 0.2604562, -0.10962567 0.088219419 0.26021242, -0.10969687 0.088142738 0.26036632, -0.10973009 0.088258639 0.26016653, -0.10981238 0.088169202 0.26034522, -0.10952727 0.088156328 0.2602427, -0.10958846 0.08809112 0.26037407, -0.10972357 0.088074073 0.26050365, -0.10984428 0.088070974 0.2605418, -0.10944059 0.088073149 0.26025552, -0.10971738 0.087996766 0.2606591, -0.10937093 0.087974772 0.26024991, -0.10894521 0.088016108 0.2600334, -0.10894527 0.088125929 0.26002103, -0.10010657 0.088016108 0.26003343, -0.10010651 0.088125989 0.26002109, -0.10894527 0.088230535 0.25998509, -0.10010645 0.088230446 0.25998509, -0.10894528 0.088324443 0.25992697, -0.10010657 0.088324502 0.25992712, -0.10894525 0.08840327 0.25984985, -0.1001066 0.088403478 0.25984997, -0.10894524 0.088463441 0.25975713, -0.10010657 0.0884635 0.25975713, -0.10652834 0.084826455 0.26654768, -0.10654595 0.084785238 0.26663417, -0.10660554 0.084916726 0.26656869, -0.10662593 0.08486785 0.26666918, -0.10667872 0.084796771 0.26696759, -0.10662282 0.084812865 0.2667836, -0.10658857 0.084755197 0.26690483, -0.10672462 0.084931478 0.26669335, -0.1067201 0.084865823 0.2668269, -0.10645962 0.084476814 0.26648647, -0.1064465 0.084616289 0.26646787, -0.1064465 0.084508404 0.26641393, -0.10643087 0.084527746 0.26637241, -0.10641006 0.084654346 0.26638824, -0.10643512 0.084765479 0.26642829, -0.1064744 0.084724292 0.26651317, -0.10648994 0.084689006 0.2665903, -0.10654402 0.084739551 0.26673323, -0.10651492 0.084692016 0.26683888, -0.10646036 0.084584132 0.26654011, -0.10648775 0.084650144 0.26667887, -0.1064619 0.084610358 0.26677337, -0.10694122 0.084885463 0.2669118, -0.10678041 0.084814176 0.26702374, -0.10688804 0.084806457 0.26706991, -0.10645758 0.084549621 0.26662305, -0.10643226 0.084514901 0.26671201, -0.10645509 0.084443077 0.26656955, -0.10641026 0.084546551 0.26633424, -0.10642783 0.084410802 0.26665786, -0.10673857 0.08511804 0.26641411, -0.10680988 0.085041299 0.26656777, -0.10684311 0.08515732 0.26636815, -0.10692526 0.085067853 0.26654702, -0.10664009 0.085055098 0.26644427, -0.10670125 0.084989831 0.26657563, -0.10683638 0.084972724 0.26670539, -0.1069572 0.084969744 0.26674342, -0.10655355 0.08497189 0.26645702, -0.10683011 0.084895298 0.2668606, -0.10648382 0.084873423 0.26645166, -0.10605806 0.084914848 0.26623493, -0.10605809 0.085024729 0.26622283, -0.097219422 0.084914878 0.26623496, -0.097219422 0.085024789 0.2662228, -0.10605814 0.085129127 0.26618677, -0.097219452 0.085129246 0.26618683, -0.10605812 0.085223064 0.26612866, -0.097219393 0.085223064 0.26612872, -0.10605806 0.08530204 0.26605135, -0.097219393 0.08530204 0.26605135, -0.10605799 0.085362092 0.26595864, -0.097219303 0.085362151 0.26595876, -0.11450334 -0.032814428 0.21487342, -0.1140058 -0.032814607 0.21608827, -0.11450364 -0.032797232 0.21487346, -0.11400603 -0.032797202 0.21608843, -0.11400689 -0.032780126 0.21608873, -0.11450435 -0.032780096 0.21487387, -0.11400829 -0.03276293 0.21608953, -0.11450578 -0.0327629 0.21487442, -0.1176223 -0.033303335 0.20575345, -0.11747965 -0.033314034 0.20563518, -0.11764398 -0.033313975 0.2056527, -0.11760157 -0.033271745 0.20584968, -0.11747971 -0.033303127 0.2057392, -0.11758254 -0.033220485 0.20593733, -0.11747967 -0.033270881 0.20583841, -0.11747974 -0.033218697 0.20592888, -0.11756621 -0.03315179 0.20601299, -0.11747959 -0.03314887 0.20600651, -0.11755326 -0.033068642 0.2060733, -0.11751685 -0.033067629 0.20606802, -0.11747973 -0.03306444 0.20606792, -0.12089668 -0.033302829 0.19775812, -0.12075405 -0.033313498 0.19764023, -0.12091832 -0.033313617 0.19765751, -0.12087606 -0.033271179 0.19785462, -0.12075405 -0.03330259 0.19774424, -0.12075396 -0.033270463 0.19784333, -0.12085687 -0.033219919 0.19794224, -0.12075411 -0.03321813 0.19793402, -0.12084052 -0.033151314 0.19801795, -0.12075394 -0.033148363 0.19801158, -0.12082754 -0.033068225 0.19807832, -0.12079118 -0.033067212 0.1980729, -0.12075396 -0.033063933 0.19807293, -0.1241708 -0.033302456 0.18976308, -0.12402813 -0.033313215 0.18964495, -0.12419261 -0.033313304 0.18966247, -0.12415008 -0.033270895 0.18985929, -0.12402822 -0.033302188 0.18974893, -0.12402815 -0.033269972 0.1898481, -0.1241311 -0.033219606 0.18994714, -0.12402812 -0.033217743 0.18993875, -0.12411468 -0.033150911 0.19002287, -0.1240281 -0.033147961 0.1900164, -0.12410179 -0.033067822 0.19008319, -0.12406527 -0.033066705 0.19007801, -0.12402825 -0.033063412 0.19007759, -0.12744509 -0.033301964 0.18176797, -0.12730238 -0.033312723 0.18164973, -0.1274668 -0.033312798 0.18166739, -0.12742428 -0.033270359 0.18186411, -0.12730235 -0.033301756 0.18175362, -0.12730238 -0.033269584 0.18185298, -0.1274053 -0.033219069 0.18195209, -0.1273023 -0.033217356 0.1819436, -0.12738913 -0.03315042 0.18202786, -0.12730239 -0.033147469 0.18202129, -0.12737602 -0.033067226 0.18208794, -0.12733954 -0.033066258 0.18208268, -0.12730245 -0.033062935 0.18208274, -0.13071927 -0.033301502 0.17377295, -0.13057661 -0.033312291 0.17365474, -0.13074103 -0.033312216 0.1736723, -0.13069847 -0.033269867 0.17386921, -0.13057664 -0.033301368 0.17375861, -0.13057658 -0.033269078 0.17385782, -0.13067946 -0.033218652 0.17395689, -0.13057664 -0.033216938 0.1739486, -0.13066331 -0.033149973 0.17403267, -0.13057676 -0.033147082 0.17402621, -0.13065022 -0.033066779 0.17409304, -0.13061374 -0.033065811 0.17408781, -0.13057676 -0.033062533 0.17408754, -0.13399351 -0.033301041 0.16577767, -0.13385078 -0.033311784 0.16565959, -0.13401534 -0.033311784 0.16567719, -0.13397269 -0.033269435 0.16587412, -0.13385096 -0.033300921 0.16576339, -0.13395381 -0.03321819 0.16596173, -0.13385096 -0.033268586 0.16586284, -0.13385081 -0.033216402 0.16595326, -0.13393752 -0.033149496 0.16603756, -0.13385096 -0.03314662 0.16603105, -0.13392454 -0.033066407 0.16609766, -0.13388804 -0.033065364 0.16609253, -0.13385093 -0.033062026 0.1660925, -0.14054209 -0.033300176 0.1497876, -0.14039935 -0.033310875 0.14966942, -0.1405637 -0.033310935 0.14968678, -0.14052127 -0.033268556 0.1498837, -0.14039952 -0.033299938 0.1497733, -0.14050235 -0.033217296 0.14997162, -0.14039938 -0.033267722 0.14987265, -0.14039943 -0.033215567 0.14996311, -0.14048594 -0.033148661 0.15004724, -0.1403994 -0.033145621 0.15004098, -0.14047299 -0.033065543 0.15010756, -0.1404365 -0.03306447 0.15010223, -0.1403994 -0.033061281 0.15010232, -0.14381635 -0.033299878 0.14179242, -0.14367361 -0.033310458 0.14167435, -0.14383803 -0.033310473 0.14169191, -0.14379552 -0.033268183 0.14188856, -0.14367366 -0.033299521 0.14177819, -0.14367364 -0.033267245 0.14187749, -0.14377654 -0.033216849 0.14197639, -0.1436736 -0.03321512 0.14196807, -0.14376013 -0.033148423 0.14205222, -0.14367361 -0.033145323 0.14204584, -0.14374721 -0.033065215 0.14211252, -0.14371084 -0.033064082 0.14210726, -0.14367358 -0.033060923 0.14210705, -0.12096418 0.10033256 0.23553936, -0.12098202 0.10029152 0.23562628, -0.12104134 0.10042271 0.23556067, -0.12106164 0.10037386 0.23566119, -0.12111446 0.10030285 0.23595959, -0.12105879 0.10031891 0.23577562, -0.12102446 0.10026136 0.23589677, -0.12116046 0.1004377 0.23568545, -0.12115598 0.10037184 0.23581895, -0.12089548 0.099982888 0.23547858, -0.12088227 0.10012233 0.23545977, -0.12088241 0.10001457 0.23540591, -0.12086675 0.10003379 0.23536438, -0.12084593 0.10016048 0.2353804, -0.12087092 0.10027158 0.23542026, -0.12091026 0.10023049 0.2355054, -0.1209259 0.10019508 0.23558226, -0.12097986 0.10024559 0.23572521, -0.12095067 0.10019806 0.23583096, -0.12089635 0.10009015 0.23553215, -0.12092361 0.10015634 0.23567086, -0.12089767 0.10011649 0.23576532, -0.12137708 0.10039148 0.23590395, -0.12121624 0.10032037 0.23601568, -0.12132394 0.1003125 0.23606196, -0.12089336 0.10005572 0.23561516, -0.12086815 0.10002097 0.23570374, -0.12089092 0.09994939 0.23556161, -0.12084623 0.1000526 0.23532622, -0.12086365 0.099916846 0.23564988, -0.12117445 0.10062411 0.23540607, -0.12124562 0.10054746 0.23555985, -0.12127893 0.10066333 0.2353601, -0.12136121 0.10057408 0.23553906, -0.12107596 0.10056105 0.23543638, -0.12113711 0.10049585 0.23556775, -0.12127224 0.10047895 0.23569724, -0.1213932 0.1004757 0.23573557, -0.12098929 0.10047796 0.23544902, -0.12126598 0.10040143 0.23585278, -0.12091967 0.10037959 0.2354435, -0.11165532 0.10042101 0.23522715, -0.12049398 0.10042098 0.23522717, -0.11165527 0.10053086 0.23521487, -0.12049398 0.10053077 0.23521489, -0.11165532 0.10063535 0.23517875, -0.12049384 0.10063541 0.23517875, -0.11165527 0.10072941 0.23512088, -0.12049404 0.10072941 0.23512086, -0.11165521 0.10080837 0.23504329, -0.12049392 0.10080832 0.23504326, -0.11165515 0.10086833 0.2349506, -0.12049386 0.10086825 0.23495048, -0.13726775 -0.033300623 0.15778269, -0.13712507 -0.033311412 0.15766445, -0.13728955 -0.033311427 0.15768221, -0.13724701 -0.033269033 0.15787889, -0.13712518 -0.033300519 0.15776823, -0.13712518 -0.033268273 0.15786786, -0.13722803 -0.033217743 0.15796663, -0.13712519 -0.033216029 0.15795828, -0.1372117 -0.033149213 0.15804236, -0.13712506 -0.033146203 0.15803583, -0.13719876 -0.033065915 0.15810275, -0.13716234 -0.033064932 0.15809755, -0.13712518 -0.033061758 0.15809745, -0.11355907 -0.033831641 0.2242194, -0.11345688 -0.033656195 0.224517, -0.11292793 -0.033059284 0.22372223, -0.1128097 -0.032863334 0.22400968, -0.11337605 -0.033405975 0.22478296, -0.11272529 -0.032612994 0.22426571, -0.11266938 -0.032316282 0.22447528, -0.11332057 -0.033092842 0.22500436, -0.11266625 -0.032292232 0.22448914, -0.13802372 -0.032526061 0.13446762, -0.13880698 -0.032526106 0.1344675, -0.13880698 -0.032526106 0.1344675, -0.13802372 -0.032526061 0.13446762, -0.13802372 -0.032526061 0.13446762, -0.14671282 -0.032440796 0.13647139, -0.14672488 -0.032266319 0.13648722, -0.14677383 -0.032283798 0.13647258, -0.1466731 -0.032419354 0.13648203, -0.14688078 -0.032108203 0.13646764, -0.1467209 -0.031875044 0.13654009, -0.14667958 -0.032250106 0.13651058, -0.14667343 -0.031869739 0.13659254, -0.14663574 -0.032399133 0.1364994, -0.14662625 -0.032230884 0.13655466, -0.14663924 -0.031865954 0.1366545, -0.14659892 -0.032245561 0.13657762, -0.1463713 -0.032628208 0.13650055, -0.14639808 -0.032608896 0.13650788, -0.14637218 -0.032634631 0.13649726, -0.14637055 -0.032621995 0.1365038, -0.14636989 -0.032615781 0.1365075, -0.14643422 -0.032663465 0.13648061, -0.14684556 -0.031889066 0.13647595, -0.14691536 -0.031896904 0.13646764, -0.14677931 -0.031881601 0.13650054, -0.14644922 -0.03264907 0.13648285, -0.14650209 -0.032680467 0.13647079, -0.14657299 -0.032686055 0.13646761, -0.14655103 -0.032657176 0.13646966, -0.14666884 -0.032592595 0.13646761, -0.14645411 -0.032573551 0.13651383, -0.14643361 -0.032613054 0.13649927, -0.14642586 -0.032595158 0.13651018, -0.1465304 -0.032629758 0.13647598, -0.14651069 -0.032603651 0.13648582, -0.14663705 -0.032566577 0.1364702, -0.1467544 -0.032463238 0.13646761, -0.14648987 -0.032532483 0.13652152, -0.14648534 -0.032570034 0.13650495, -0.14660694 -0.032541782 0.13647822, -0.14657824 -0.032518223 0.13649124, -0.14653344 -0.032456368 0.13653591, -0.14654191 -0.03248854 0.13651639, -0.1468254 -0.032302275 0.13646749, -0.081663772 0.073634997 0.28755176, -0.081680343 0.07328774 0.28743231, -0.081693068 0.073312446 0.28739208, -0.081847891 0.073537365 0.28781202, -0.081877142 0.073191658 0.28764057, -0.081829071 0.073190138 0.28763276, -0.081650481 0.073615983 0.28759536, -0.081653938 0.073975518 0.28766918, -0.081640407 0.073962942 0.28771481, -0.081648991 0.07359685 0.28764054, -0.081638873 0.073950127 0.28776231, -0.081679389 0.073263183 0.28747451, -0.081659541 0.073578969 0.28768498, -0.081649274 0.073937431 0.28780854, -0.081690162 0.073240235 0.28751624, -0.081681535 0.073563114 0.28772601, -0.081671298 0.073925838 0.28785092, -0.081703216 0.073915944 0.28788698, -0.081712157 0.073220626 0.2875551, -0.081713349 0.073550329 0.28776085, -0.081743389 0.073908463 0.28791451, -0.081743985 0.073205128 0.28758883, -0.081783682 0.073194638 0.28761527, -0.081753448 0.073541448 0.28778791, -0.08178927 0.073903605 0.28793168, -0.081799209 0.073537067 0.28780523, -0.081838027 0.073902115 0.28793734, -0.13786171 0.11771458 0.20570698, -0.13781323 0.11771759 0.20571506, -0.13781069 0.11772674 0.20569658, -0.13785933 0.117724 0.2056886, -0.13790493 0.11771065 0.2056753, -0.13790742 0.11770086 0.20569485, -0.13794465 0.11768714 0.2056582, -0.13794748 0.11767709 0.20567849, -0.13797639 0.11765546 0.20563769, -0.13797916 0.11764476 0.20565957, -0.13799821 0.11761719 0.20561543, -0.13800107 0.11760563 0.20563897, -0.13800848 0.11757477 0.20559278, -0.13801147 0.11756226 0.20561782, -0.12059045 0.11890088 0.2078079, -0.13670444 0.11980863 0.20599237, -0.13669887 0.11983256 0.20595521, -0.12058491 0.11892472 0.20777082, -0.13669382 0.11986417 0.20592463, -0.12057979 0.11895625 0.20774017, -0.13668898 0.11990176 0.20590174, -0.12057497 0.1189938 0.20771734, -0.13668504 0.11994348 0.2058875, -0.12057105 0.11903577 0.20770305, -0.13668212 0.11998753 0.20588291, -0.12056804 0.11907969 0.20769846, -0.10364109 0.081725284 0.27274901, -0.10365899 0.081684217 0.27283582, -0.10371828 0.081815526 0.27277035, -0.10373862 0.08176662 0.27287084, -0.10379155 0.081695661 0.27316937, -0.10373567 0.081711695 0.2729851, -0.10370143 0.081654266 0.27310646, -0.10383748 0.081830427 0.27289498, -0.10383303 0.081764683 0.27302858, -0.10357244 0.081375584 0.27268812, -0.10355936 0.081515208 0.27266943, -0.10355926 0.081407353 0.27261561, -0.10354376 0.081426606 0.27257413, -0.1035229 0.081553146 0.27258998, -0.10354792 0.081664339 0.27262974, -0.10358725 0.081623152 0.27271485, -0.1036028 0.081587866 0.27279192, -0.10365687 0.08163844 0.27293476, -0.10362774 0.081590816 0.27304065, -0.10357319 0.081483021 0.27274168, -0.10360073 0.081549093 0.27288043, -0.10357474 0.081509188 0.27297509, -0.104054 0.081784323 0.27311364, -0.10389327 0.081713036 0.27322543, -0.10400091 0.081705227 0.27327168, -0.1035704 0.081448421 0.27282465, -0.10354514 0.081413612 0.27291343, -0.10356784 0.081342146 0.27277106, -0.10352314 0.081445262 0.27253574, -0.1035406 0.081309661 0.27285945, -0.10385139 0.082017049 0.27261576, -0.10392256 0.081940308 0.27276951, -0.10395592 0.082056269 0.27256966, -0.10403803 0.081966832 0.27274862, -0.10375296 0.081954047 0.27264607, -0.10381418 0.081888899 0.27277744, -0.10394917 0.081871524 0.27290678, -0.10407008 0.081868485 0.27294493, -0.10366641 0.08187075 0.27265871, -0.1039429 0.081794098 0.27306217, -0.10359655 0.081772193 0.27265295, -0.10317089 0.081813738 0.27243656, -0.10317086 0.0819235 0.27242434, -0.094332278 0.081813827 0.27243659, -0.094332203 0.081923559 0.27242434, -0.10317078 0.082027987 0.27238843, -0.094332129 0.082028016 0.27238846, -0.10317095 0.082122043 0.2723304, -0.094332278 0.082122043 0.27233046, -0.10317098 0.0822009 0.27225292, -0.094332248 0.082200989 0.2722531, -0.10317086 0.082260862 0.27216017, -0.094332248 0.082261011 0.27216023, -0.093001485 0.076991156 0.27764249, -0.093001947 0.077084318 0.27763379, -0.092439294 0.076991186 0.27764261, -0.092439294 0.077101067 0.27763033, -0.093005374 0.07717447 0.27760756, -0.092439413 0.077205643 0.27759445, -0.093013451 0.077257767 0.27756599, -0.092439443 0.077299669 0.27753639, -0.093028024 0.077330753 0.27750969, -0.092439368 0.077378437 0.27745903, -0.093049675 0.077391341 0.27744246, -0.092439443 0.077438667 0.2773664, -0.093078449 0.077438518 0.2773664, -0.10028374 0.078712448 0.27863824, -0.10028374 0.0788223 0.27862591, -0.098984241 0.078712448 0.27863824, -0.098984271 0.07882233 0.27862602, -0.10028371 0.078926697 0.2785899, -0.098984361 0.078926727 0.2785899, -0.10028374 0.079020783 0.27853185, -0.09898439 0.079020694 0.27853197, -0.10028365 0.07909967 0.27845469, -0.098984271 0.07909961 0.2784546, -0.10028377 0.079159692 0.27836174, -0.098984241 0.079159662 0.27836162, -0.097429603 0.077680662 0.27735221, -0.097409442 0.07763578 0.27746007, -0.098606229 0.079039618 0.27813846, -0.098585904 0.078994855 0.2782464, -0.097411633 0.077574953 0.27756202, -0.098588228 0.07893388 0.27834827, -0.09743616 0.077501431 0.27765235, -0.098612756 0.078860596 0.27843857, -0.097481683 0.077419773 0.27772543, -0.098658323 0.078778848 0.27851152, -0.097545594 0.07733424 0.27777755, -0.098722219 0.078693435 0.27856368, -0.097624302 0.07724987 0.27780569, -0.098800838 0.078608975 0.27859181, -0.097713426 0.077171221 0.27780828, -0.098889917 0.078530446 0.2785942, -0.097807661 0.077103004 0.27778488, -0.098984331 0.078462198 0.27857101, -0.096937656 0.076991305 0.27764249, -0.096937656 0.077101216 0.27763045, -0.095501259 0.076991096 0.27764249, -0.095500201 0.077112898 0.27762747, -0.096937805 0.077205673 0.27759445, -0.095494196 0.077216342 0.27758902, -0.096937686 0.07729955 0.27753624, -0.095483109 0.07729502 0.27754003, -0.095466405 0.077358589 0.27748168, -0.096937746 0.077378646 0.27745911, -0.095447645 0.077402964 0.27742648, -0.096937776 0.077438638 0.27736622, -0.095424294 0.077438667 0.27736628, -0.080485314 0.076641366 0.29169744, -0.095302925 0.076641247 0.29169732, -0.080486074 0.076678738 0.29169607, -0.080488726 0.07671614 0.29169178, -0.095316678 0.076732531 0.29168919, -0.080496788 0.076778129 0.29167825, -0.080509946 0.076836571 0.29165778, -0.09533751 0.076823786 0.29166287, -0.080528826 0.076890633 0.29163069, -0.095369816 0.076922223 0.29161072, -0.080575868 0.076975212 0.29156941, -0.080604658 0.077012166 0.29153287, -0.095413372 0.077014729 0.29152983, -0.08063437 0.077045158 0.29149219, -0.095466137 0.077088431 0.29142109, -0.080682889 0.07708849 0.29142106, -0.137348 0.11689445 0.20429012, -0.13735293 0.11793131 0.20485878, -0.13718221 0.11794859 0.20481756, -0.13711882 0.11689493 0.20426017, -0.13701472 0.11795229 0.2048035, -0.13809001 0.11638555 0.2053827, -0.13761356 0.12065963 0.20774943, -0.13767567 0.12076144 0.20755762, -0.13804123 0.11631459 0.2055161, -0.13778894 0.11973208 0.20663136, -0.13768801 0.12086277 0.20736086, -0.13766614 0.12093382 0.20721835, -0.13811432 0.11645718 0.20524529, -0.13772431 0.11982541 0.20644373, -0.13761728 0.12100333 0.20707577, -0.1375415 0.12106727 0.20693964, -0.13810933 0.11654899 0.205064, -0.13760796 0.1199135 0.2062636, -0.13806306 0.11663665 0.20488581, -0.1379541 0.1176737 0.20539427, -0.13733631 0.12116475 0.2067208, -0.13744378 0.11998852 0.20610788, -0.13720374 0.12120068 0.20663252, -0.13797563 0.11671761 0.20471594, -0.13784301 0.11776872 0.20520082, -0.13785705 0.11678404 0.20457056, -0.13769601 0.11784297 0.20504749, -0.13724302 0.12004346 0.20599127, -0.13707012 0.12122388 0.20656911, -0.13770327 0.11683863 0.20444396, -0.13753341 0.11789542 0.20493677, -0.13702384 0.12007432 0.20592135, -0.13692752 0.12123708 0.20652384, -0.13681546 0.12124042 0.20650238, -0.13753173 0.11687523 0.20435059, -0.13680522 0.12008178 0.20589808, -0.13669138 0.12123716 0.20649186, -0.13667946 0.12007624 0.20590419, -0.13656613 0.12122677 0.20649546, -0.094251558 0.083095863 0.28431222, -0.093461141 0.083139554 0.28422511, -0.094251499 0.082872227 0.28364149, -0.093582585 0.082909092 0.28356767, -0.092954069 0.083017662 0.28335056, -0.092718184 0.083267793 0.28396869, -0.092403263 0.08319141 0.28300333, -0.092067212 0.083473042 0.28355804, -0.09196353 0.083419845 0.28254664, -0.091547549 0.083742961 0.28301835, -0.091661185 0.083689049 0.28200784, -0.091190189 0.08406122 0.28238168, -0.091514349 0.083983287 0.28141987, -0.091016561 0.084408894 0.2816864, -0.091037422 0.084765032 0.28097448, -0.091531962 0.084284618 0.28081718, -0.091712862 0.084575072 0.28023645, -0.091251314 0.085108206 0.28028822, -0.099889323 -0.015864 0.24062243, -0.099225447 -0.015110418 0.24048075, -0.099889427 -0.015180811 0.24043991, -0.099104688 -0.015780792 0.24067059, -0.098600879 -0.014903203 0.24060047, -0.098366454 -0.015535876 0.24081217, -0.098052368 -0.014571741 0.24079217, -0.097718194 -0.015144154 0.2410389, -0.097612545 -0.014135286 0.24104467, -0.097198725 -0.014628246 0.24133733, -0.097307518 -0.013619974 0.24134278, -0.096838132 -0.014019266 0.24168932, -0.097155333 -0.013056174 0.24166882, -0.09665826 -0.013352975 0.24207474, -0.090164497 0.067242339 0.28638127, -0.090164408 0.066491291 0.28767961, -0.090547398 0.067202166 0.28635812, -0.090547428 0.066451177 0.28765649, -0.090908065 0.067083672 0.28628954, -0.090908036 0.066332743 0.28758794, -0.09122555 0.06689398 0.2861799, -0.091225341 0.066142991 0.28747821, -0.091481283 0.066644266 0.28603521, -0.091481254 0.065893039 0.28733367, -0.091660425 0.066348538 0.28586411, -0.091660455 0.06559743 0.28716269, -0.091752812 0.066024408 0.28567666, -0.091752812 0.06527321 0.28697515, -0.091752842 0.065690473 0.28548363, -0.091752842 0.064939335 0.28678194, -0.091660485 0.065366313 0.28529602, -0.091660455 0.064615086 0.28659454, -0.091481283 0.065070704 0.28512526, -0.091481254 0.064319476 0.28642362, -0.091225475 0.064820752 0.2849806, -0.091225371 0.064069673 0.2862789, -0.090907902 0.06463103 0.2848708, -0.090907991 0.063879862 0.28616944, -0.090547353 0.064512596 0.28480238, -0.090547234 0.063761577 0.28610063, -0.090164363 0.063721374 0.28607741, -0.090164363 0.064472511 0.2847791, -0.099889442 -0.010664299 0.24131964, -0.099889442 -0.011415258 0.24261796, -0.10027231 -0.010704592 0.24129637, -0.10027234 -0.011455551 0.24259461, -0.10063295 -0.010823026 0.24122787, -0.10063303 -0.011573836 0.2425262, -0.10095045 -0.011012539 0.24111797, -0.10095057 -0.011763677 0.2424164, -0.10120621 -0.011262611 0.24097355, -0.10120623 -0.01201354 0.24227205, -0.10138552 -0.01155819 0.24080232, -0.1013855 -0.012309209 0.24210107, -0.10147776 -0.011882409 0.2406151, -0.10147771 -0.012633368 0.24191351, -0.10147765 -0.012216315 0.24042192, -0.10147774 -0.012967214 0.24172029, -0.10138543 -0.012540504 0.24023445, -0.10138549 -0.013291374 0.24153294, -0.10120614 -0.012836203 0.24006332, -0.10120627 -0.013587192 0.24136177, -0.10095041 -0.013085976 0.23991875, -0.10095038 -0.013837054 0.24121732, -0.10063311 -0.013275668 0.23980892, -0.10063307 -0.014026657 0.24110739, -0.10027228 -0.013394043 0.23974051, -0.10027233 -0.014145121 0.24103905, -0.099889413 -0.013434306 0.2397175, -0.099889442 -0.014185414 0.24101582, -0.092889607 0.065072164 0.28079402, -0.092030704 0.064671025 0.28052914, -0.092074364 0.064585045 0.28051227, -0.090164408 0.071173564 0.28423712, -0.09110488 0.071074829 0.28417975, -0.090164497 0.071225271 0.28432029, -0.090164393 0.071139231 0.28414524, -0.090164438 0.0640883 0.28023612, -0.091147959 0.064280853 0.28033626, -0.090164483 0.064177617 0.28027666, -0.091125414 0.071124151 0.28426191, -0.092119634 0.064505443 0.28047729, -0.091171324 0.064194188 0.28029728, -0.091147944 0.071188822 0.28433183, -0.092030719 0.070827112 0.28408992, -0.09207423 0.070884749 0.28415632, -0.090164438 0.071292266 0.28439182, -0.091171339 0.071266159 0.28438783, -0.090164497 0.071371898 0.2844488, -0.091955304 0.064849719 0.28050745, -0.09199053 0.064760491 0.28052759, -0.092719734 0.065306529 0.28077149, -0.09211953 0.070954725 0.28420776, -0.092889592 0.070397571 0.28387427, -0.092954203 0.070455924 0.28391927, -0.09277007 0.065226391 0.28079692, -0.09282741 0.065147236 0.28080466, -0.091125429 0.064373955 0.28035736, -0.090164483 0.064272925 0.28029919, -0.091955304 0.070756957 0.2839241, -0.091990605 0.070784077 0.28401166, -0.09108676 0.071042225 0.28408915, -0.091104835 0.064469829 0.2803593, -0.090164453 0.064370945 0.28030217, -0.092827484 0.070351079 0.28381476, -0.090164423 0.064467773 0.28028625, -0.091086686 0.06456469 0.28034258, -0.093546584 0.069755659 0.28350306, -0.093626902 0.069798782 0.28353927, -0.092719749 0.070300087 0.28366005, -0.092770174 0.070318207 0.28374207, -0.093469337 0.06972377 0.28345168, -0.09400709 0.068996355 0.28306389, -0.094098315 0.069021478 0.28308961, -0.093335912 0.069698349 0.28331178, -0.093398288 0.069704399 0.28338718, -0.093919322 0.068981782 0.28302258, -0.094244108 0.068163708 0.28258222, -0.094340995 0.068169102 0.28259635, -0.093838409 0.068978414 0.28296709, -0.093767598 0.068986222 0.28289986, -0.094150856 0.068168148 0.28255177, -0.094244167 0.067305967 0.28208625, -0.094340906 0.067291066 0.28208864, -0.094065145 0.068182275 0.2825067, -0.093989924 0.068205401 0.28244841, -0.094151065 0.067330137 0.28206712, -0.094007 0.066473529 0.28160453, -0.094098195 0.06643872 0.28159559, -0.094065264 0.067362294 0.28203225, -0.093989894 0.067401305 0.28198332, -0.093919307 0.066516474 0.28159687, -0.09354645 0.065714017 0.28116551, -0.093626797 0.065661266 0.2811462, -0.093767554 0.066620603 0.28153154, -0.093838558 0.066566184 0.28157204, -0.093469486 0.065774515 0.2811673, -0.092954218 0.065004155 0.28076601, -0.093335807 0.065908417 0.2811197, -0.093398154 0.06584011 0.28115189, -0.08884865 0.067426786 0.27990055, -0.088460267 0.067670926 0.28009522, -0.088791341 0.067347482 0.27990833, -0.088791266 0.070030943 0.28146026, -0.088741124 0.070049092 0.2815426, -0.08839798 0.069713578 0.28134853, -0.088608593 0.06779708 0.28008187, -0.088689029 0.06784986 0.28010142, -0.088488072 0.068181172 0.28029299, -0.088309199 0.068103388 0.28029177, -0.088531464 0.0677367 0.28007975, -0.089202136 0.070276394 0.28160217, -0.088396847 0.068146393 0.28028387, -0.089668855 0.066948935 0.27967745, -0.089650691 0.066854045 0.27969456, -0.090164363 0.066800103 0.27966344, -0.090164453 0.066896811 0.27964729, -0.090164527 0.070481852 0.28172114, -0.090164468 0.070516244 0.28181285, -0.08965081 0.070462093 0.28178167, -0.089202195 0.06710209 0.27976626, -0.08924228 0.070233211 0.28152382, -0.0896689 0.070429698 0.28169093, -0.089689508 0.070380077 0.28160876, -0.089711979 0.070315585 0.28153849, -0.089735299 0.070238307 0.28148291, -0.090164438 0.070283517 0.28150886, -0.089242399 0.067191467 0.27976441, -0.090164468 0.070363119 0.28156614, -0.090164587 0.070430234 0.28163779, -0.088910937 0.067501828 0.27991098, -0.088975489 0.067569718 0.27993941, -0.088460237 0.069707468 0.28127313, -0.088157445 0.069316939 0.28111911, -0.089689672 0.06704466 0.2796796, -0.090164363 0.066994712 0.27965063, -0.08884865 0.06999813 0.28138793, -0.08928588 0.067277744 0.27978146, -0.089331329 0.067357287 0.27981639, -0.08928591 0.070175633 0.28145766, -0.08933118 0.070105687 0.2814061, -0.089712083 0.067137763 0.27970046, -0.090164483 0.067090198 0.27967298, -0.089735329 0.067224488 0.27973974, -0.088228226 0.069324836 0.28105181, -0.088033617 0.068882212 0.28086758, -0.088531375 0.069688067 0.28120846, -0.088910758 0.069951579 0.28132814, -0.088975519 0.069893196 0.28128338, -0.088108927 0.068905428 0.28080913, -0.088033706 0.068434194 0.28060839, -0.088309139 0.069321409 0.28099656, -0.088608652 0.069656268 0.28115731, -0.08868891 0.069613084 0.28112113, -0.088108867 0.068473235 0.28055918, -0.088157475 0.067999229 0.280357, -0.088194758 0.068919495 0.28076398, -0.088396817 0.069306806 0.28095528, -0.088488013 0.069281712 0.28092945, -0.088228315 0.068053618 0.28031647, -0.08839801 0.067602709 0.28012764, -0.088194698 0.068505302 0.28052449, -0.08828795 0.068923935 0.28073376, -0.088384658 0.068918481 0.28071934, -0.088741124 0.067267284 0.27993345, -0.088287801 0.068529502 0.28050554, -0.088384598 0.068544462 0.28050297, -0.089166865 0.067012951 0.27978641, -0.090164483 0.067179546 0.27971351, -0.089166939 0.070303425 0.28168952, -0.10179934 -0.013321862 0.23545066, -0.10087274 -0.013625965 0.23527478, -0.10184456 -0.013401493 0.23541559, -0.099889502 -0.0067329258 0.23917514, -0.10082991 -0.0068319291 0.23911817, -0.099889457 -0.0066813082 0.23925842, -0.10089628 -0.01371263 0.23523574, -0.099889442 -0.0137292 0.23521487, -0.10081168 -0.013342425 0.23528065, -0.1017154 -0.013146326 0.2354659, -0.10168017 -0.013057068 0.23544569, -0.10081169 -0.0068645328 0.23902752, -0.10249515 -0.012680367 0.23573549, -0.10085052 -0.0067823976 0.23919991, -0.1025524 -0.012759551 0.23574279, -0.10175554 -0.013235673 0.23546736, -0.10087298 -0.0067177266 0.23927033, -0.10175578 -0.0070795566 0.23902832, -0.10179937 -0.0070218891 0.23909448, -0.10085054 -0.013532802 0.23529579, -0.099889383 -0.013633713 0.23523729, -0.1018445 -0.0069518834 0.23914582, -0.10261461 -0.0075090975 0.23881258, -0.10267922 -0.0074506849 0.2388574, -0.10082974 -0.013437137 0.23529775, -0.099889517 -0.013535783 0.23524056, -0.099889472 -0.013439104 0.2352245, -0.10244486 -0.0076064914 0.23859836, -0.10171549 -0.0071227103 0.23894997, -0.10168026 -0.007149592 0.23886257, -0.10255238 -0.0075556189 0.23875292, -0.10327159 -0.0081509799 0.23844159, -0.10335182 -0.0081078261 0.23847747, -0.10306096 -0.0082083791 0.23825, -0.10249516 -0.007588461 0.23868062, -0.099889427 -0.0067674667 0.23908333, -0.10319448 -0.0081827492 0.23839007, -0.10373199 -0.0089104027 0.23800223, -0.1038232 -0.0088852495 0.23802781, -0.10349257 -0.0089204758 0.23783828, -0.10312334 -0.0082023293 0.23832549, -0.10364422 -0.0089248866 0.23796089, -0.10396908 -0.0097430795 0.23752061, -0.104066 -0.0097377151 0.23753467, -0.10371485 -0.0097013265 0.23738666, -0.10356343 -0.008928284 0.23790549, -0.10387598 -0.0097386688 0.23749033, -0.10396902 -0.010600641 0.23702453, -0.10406585 -0.010615751 0.23702718, -0.10379004 -0.0097245127 0.23744516, -0.10371491 -0.010505423 0.23692158, -0.10387592 -0.010576651 0.23700558, -0.10373189 -0.011433318 0.23654313, -0.10382304 -0.011468038 0.23653391, -0.10349262 -0.011286244 0.23646975, -0.10379013 -0.010544524 0.23697081, -0.10364418 -0.011390314 0.23653488, -0.10327156 -0.012192622 0.23610373, -0.10335179 -0.012245461 0.23608412, -0.10306104 -0.011998221 0.23605801, -0.10356341 -0.011340603 0.2365102, -0.10319437 -0.012132242 0.23610587, -0.099889427 -0.013818458 0.23517437, -0.10261466 -0.012834594 0.23573245, -0.10267934 -0.012902603 0.23570421, -0.10244475 -0.012600169 0.23570989, -0.10312331 -0.012066647 0.23609024, -0.099889547 -0.0066144019 0.23933022, -0.099889562 -0.0065346807 0.23938741, -0.10089642 -0.0066406876 0.23932612, -0.09892717 -0.010804459 0.23470442, -0.098516315 -0.010559127 0.23484637, -0.098466009 -0.010639414 0.2348718, -0.099414542 -0.0075266212 0.2365471, -0.099889427 -0.0074251145 0.23665914, -0.099393934 -0.0074770898 0.23662928, -0.098516405 -0.0078758746 0.23639858, -0.098892003 -0.0076033324 0.23662798, -0.098466143 -0.0078579038 0.23648067, -0.0985737 -0.010479912 0.23483883, -0.098185211 -0.010235712 0.23503347, -0.098927245 -0.0076302737 0.23654057, -0.098256573 -0.010169968 0.23501833, -0.098333627 -0.010109678 0.23502019, -0.098413914 -0.010056719 0.23503953, -0.098213017 -0.009725526 0.2352314, -0.098121762 -0.0097603947 0.23522212, -0.098034114 -0.0098033994 0.23523015, -0.098967403 -0.0076734275 0.23646227, -0.099393979 -0.010957733 0.23461591, -0.098891839 -0.010893807 0.23472472, -0.099375799 -0.011052504 0.23463295, -0.099437088 -0.0075911731 0.23647705, -0.099889472 -0.0075436085 0.23650442, -0.099889442 -0.0074768513 0.23657592, -0.099460393 -0.0076684207 0.2364212, -0.099889442 -0.011009797 0.2345859, -0.098967388 -0.010715172 0.23470293, -0.098185509 -0.0081992 0.23621136, -0.098122895 -0.0081932098 0.23628688, -0.098573729 -0.007908687 0.23632623, -0.098636001 -0.01040481 0.23484939, -0.098700613 -0.010336801 0.23487774, -0.099010959 -0.007731095 0.23639618, -0.099056363 -0.0078011602 0.23634422, -0.099414542 -0.010861978 0.23461787, -0.099889427 -0.010911867 0.23458906, -0.099889353 -0.0076233 0.23644738, -0.099010915 -0.010629043 0.23471993, -0.099056184 -0.010549441 0.23475468, -0.097953379 -0.0085818321 0.23599005, -0.097882435 -0.0085896999 0.23605742, -0.099437132 -0.010768905 0.23463903, -0.099889442 -0.010816291 0.23461141, -0.099889517 -0.010727271 0.2346518, -0.099460289 -0.010682061 0.23467793, -0.098256394 -0.0082186013 0.23614682, -0.098635927 -0.007955268 0.2362663, -0.098700613 -0.0080135316 0.23622134, -0.097833917 -0.0090015978 0.23574735, -0.097758636 -0.0090246052 0.23580594, -0.098034143 -0.0085852593 0.2359347, -0.098333657 -0.0082505494 0.23609555, -0.0984139 -0.0082936138 0.23605929, -0.097833842 -0.0094335526 0.23549739, -0.097758681 -0.0094725043 0.23554686, -0.097919628 -0.0089872926 0.23570217, -0.098121881 -0.008599773 0.23589362, -0.098213121 -0.0086248666 0.23586799, -0.09795329 -0.0098531693 0.23525491, -0.097882405 -0.0099075586 0.23529522, -0.097919673 -0.0094013065 0.23546273, -0.09801285 -0.0089829415 0.23567189, -0.098109677 -0.0089883357 0.2356578, -0.099889442 -0.011106595 0.23460163, -0.098122925 -0.010304019 0.23506573, -0.098012775 -0.009377405 0.2354435, -0.098109692 -0.0093623847 0.23544148, -0.099889472 -0.0073905736 0.23675096, -0.099375829 -0.0074444562 0.23671967, -0.099889368 -0.0080932826 0.23617545, -0.099889353 -0.010021761 0.23950948, -0.10018858 -0.0081247538 0.23615733, -0.10018858 -0.010053203 0.23949122, -0.10047035 -0.0082173198 0.23610367, -0.10047032 -0.01014562 0.23943801, -0.10071847 -0.0083653778 0.236018, -0.1007182 -0.010293826 0.23935214, -0.1009181 -0.0085606724 0.23590524, -0.10091807 -0.010489061 0.23923929, -0.10105826 -0.0087916404 0.23577134, -0.10105824 -0.010720059 0.23910564, -0.1011304 -0.0090449005 0.23562494, -0.10113032 -0.01097329 0.23895897, -0.10113029 -0.0093057007 0.23547401, -0.10113013 -0.011234328 0.23880838, -0.10105832 -0.0095589012 0.23532771, -0.10105817 -0.011487499 0.238662, -0.10091825 -0.0097898096 0.23519395, -0.10091813 -0.011718377 0.23852803, -0.10071847 -0.0099850148 0.23508111, -0.10071833 -0.011913642 0.23841526, -0.10047041 -0.010133132 0.23499544, -0.10047035 -0.01206176 0.23832951, -0.10018858 -0.010225698 0.23494187, -0.10018858 -0.012154385 0.238276, -0.099889368 -0.012185857 0.23825788, -0.099889472 -0.01025714 0.23492371, -0.090164483 0.069813654 0.28123724, -0.090164497 0.067885026 0.28457129, -0.090463698 0.069782183 0.28121912, -0.090463594 0.067853555 0.28455305, -0.090745404 0.069689617 0.28116548, -0.090745419 0.067760989 0.28449941, -0.090993419 0.069541439 0.28107959, -0.09099336 0.067612872 0.28441358, -0.091193259 0.069346055 0.28096688, -0.091193274 0.067417726 0.2843008, -0.091333181 0.069115236 0.28083313, -0.091333255 0.067186728 0.28416741, -0.091405302 0.068861976 0.2806868, -0.091405347 0.066933379 0.28402078, -0.091405332 0.068600938 0.28053588, -0.091405377 0.066672578 0.28387007, -0.09133321 0.068347797 0.28038931, -0.091333181 0.066419259 0.28372353, -0.091193259 0.068116769 0.28025591, -0.09119311 0.06618841 0.28358993, -0.0909933 0.067921475 0.2801429, -0.090993345 0.065993056 0.28347707, -0.0907453 0.067773357 0.28005719, -0.090745419 0.065844908 0.28339124, -0.090463579 0.067680702 0.28000367, -0.090463579 0.065752372 0.28333771, -0.090164408 0.065720901 0.28331953, -0.090164378 0.067649409 0.27998543, -0.089401871 0.065125182 0.28017363, -0.088373601 0.064849719 0.28050733, -0.08924228 0.06456469 0.28034258, -0.089591891 0.06627287 0.27985126, -0.088862836 0.065891013 0.28012359, -0.089591846 0.070616081 0.2823635, -0.088862732 0.070570335 0.28283012, -0.089401886 0.070909038 0.283519, -0.08924219 0.071042225 0.28408921, -0.088373587 0.070757106 0.28392422, -0.087609142 0.065306678 0.28077149, -0.08781898 0.066611692 0.28054029, -0.086561322 0.066620633 0.28153151, -0.086993068 0.065908507 0.28111982, -0.087239653 0.067652836 0.28114259, -0.086339027 0.067401305 0.28198332, -0.087239653 0.068808809 0.28181118, -0.086561233 0.068986252 0.28290007, -0.086339027 0.068205491 0.28244835, -0.08781895 0.069849864 0.28241336, -0.087609097 0.070300236 0.28365988, -0.08699289 0.069698229 0.28331178, -0.098587796 -0.0073363036 0.23776849, -0.098098576 -0.0071497709 0.2388624, -0.097334102 -0.0076064318 0.23859833, -0.09754397 -0.0080568343 0.23735158, -0.099316895 -0.011633888 0.2347898, -0.098587692 -0.012015596 0.23506188, -0.09912686 -0.012781546 0.23511206, -0.098098606 -0.013057098 0.23544577, -0.098967165 -0.013342336 0.23528065, -0.099316821 -0.0072906762 0.23730201, -0.099126995 -0.0069976896 0.23845753, -0.098967165 -0.0068645626 0.23902754, -0.097333953 -0.012600288 0.23570992, -0.09754391 -0.011295184 0.23547862, -0.096286312 -0.011286214 0.23646991, -0.096717969 -0.0119984 0.23605801, -0.096964523 -0.010253891 0.2360809, -0.096063897 -0.0097012371 0.2373866, -0.096063897 -0.010505423 0.23692153, -0.096964613 -0.0090981871 0.23674928, -0.096286237 -0.0089204758 0.23783809, -0.096717998 -0.0082082897 0.23824997, -0.12500598 0.11167194 0.20895968, -0.12548082 0.11177771 0.20885165, -0.12498525 0.11175086 0.20890555, -0.12451851 0.11003138 0.21234354, -0.12410773 0.11015834 0.21208988, -0.12405741 0.11018856 0.21216848, -0.12410761 0.11154486 0.20931731, -0.1244833 0.11175723 0.20903157, -0.12405744 0.11162578 0.20929462, -0.12416515 0.11014597 0.2120114, -0.12377678 0.11032544 0.21175571, -0.1245185 0.11167167 0.20906399, -0.12384792 0.11030616 0.21169122, -0.12392503 0.1103044 0.2116307, -0.12400533 0.1103207 0.21157692, -0.12380452 0.11049183 0.21123467, -0.12371327 0.11048502 0.21126992, -0.12455873 0.11159621 0.20911159, -0.12362555 0.1104954 0.21131226, -0.12502839 0.11160572 0.20902865, -0.12505175 0.11155476 0.20910881, -0.12548088 0.11157808 0.20906243, -0.1249852 0.10995232 0.21250199, -0.12448323 0.110057 0.21243154, -0.12496708 0.10997497 0.21259554, -0.12548074 0.11163019 0.20897937, -0.12548085 0.11169767 0.20890814, -0.12548074 0.10992526 0.21255565, -0.1245587 0.11002435 0.21225451, -0.12377675 0.11137761 0.20965166, -0.12371434 0.11145248 0.20964085, -0.12416507 0.11147459 0.20935456, -0.1242272 0.1101519 0.21193585, -0.12429188 0.11017595 0.21186636, -0.12460236 0.11153351 0.2091731, -0.1246476 0.1114863 0.20924614, -0.12500595 0.10994844 0.21240632, -0.12548086 0.10992263 0.21245778, -0.12460221 0.11003603 0.21216737, -0.1246476 0.11006604 0.21208595, -0.12354471 0.11117984 0.21004687, -0.12347388 0.11124755 0.21005079, -0.12502836 0.10996376 0.21231197, -0.12548082 0.10993926 0.21236117, -0.12548082 0.10997407 0.21226962, -0.12505181 0.10999747 0.21222292, -0.1238479 0.11131446 0.20967495, -0.1242273 0.11141761 0.20940463, -0.12429191 0.11137636 0.20946567, -0.12342526 0.11096312 0.21048032, -0.12335007 0.11102276 0.2105002, -0.12362553 0.11112477 0.21005355, -0.12392519 0.11126523 0.20971005, -0.12400545 0.11123182 0.20975508, -0.12342535 0.11073981 0.21092696, -0.1233501 0.11079139 0.21096274, -0.12351109 0.11091711 0.21046911, -0.12371325 0.11108454 0.2100707, -0.12380438 0.11106041 0.2100974, -0.12354466 0.110523 0.21136037, -0.12347378 0.11056675 0.21141221, -0.12351111 0.11070319 0.21089682, -0.12360431 0.11088671 0.21046652, -0.12370096 0.11087273 0.21047281, -0.12548082 0.10994713 0.21265133, -0.12371428 0.11036183 0.21182196, -0.12360419 0.11068286 0.21087395, -0.12370101 0.11067942 0.21085937, -0.12548086 0.11186717 0.20881164, -0.12496711 0.11183919 0.2088673, -0.12739062 0.1109288 0.21481079, -0.12644188 0.11078696 0.21503079, -0.12646437 0.11077169 0.21512502, -0.1282707 0.1139735 0.20874421, -0.12820606 0.11393222 0.20880498, -0.12894318 0.11363384 0.20942295, -0.12739059 0.11418387 0.20830166, -0.12548082 0.11073472 0.21513507, -0.12642121 0.11078307 0.21493503, -0.12548082 0.11073205 0.21503718, -0.12640302 0.11076044 0.21484154, -0.12727158 0.11090778 0.21454686, -0.12730685 0.11093342 0.21463475, -0.12734704 0.11094038 0.21472371, -0.12727162 0.11396 0.20844305, -0.12730683 0.11404569 0.20841101, -0.126403 0.11410736 0.20814872, -0.12644184 0.11427473 0.20805609, -0.12734699 0.11412123 0.20836323, -0.12642115 0.11419587 0.20811057, -0.12548079 0.11439431 0.20788082, -0.12648763 0.11439191 0.20790692, -0.12548091 0.11444649 0.20779777, -0.12814388 0.11387524 0.20885503, -0.1288629 0.11360039 0.2094681, -0.12941456 0.11323214 0.21022624, -0.12803614 0.11372408 0.20891497, -0.12808645 0.11380497 0.20889229, -0.1287857 0.11355123 0.20950305, -0.12932342 0.1132081 0.21025287, -0.12965727 0.11279163 0.21110687, -0.12865219 0.11341295 0.20953715, -0.12871456 0.11348793 0.20952627, -0.1292356 0.11316773 0.21026993, -0.12956041 0.11277783 0.21111313, -0.12965724 0.11233816 0.2120142, -0.12908396 0.1130451 0.21027267, -0.12915479 0.1131126 0.21027656, -0.12946734 0.11274731 0.21111047, -0.12956044 0.1123348 0.21199934, -0.12941456 0.11189771 0.21289486, -0.12938146 0.11270134 0.21109927, -0.12930626 0.11264172 0.21107945, -0.12946726 0.11231434 0.21197645, -0.12932342 0.11190459 0.21285969, -0.12894335 0.11149609 0.21369824, -0.12930629 0.11222622 0.21191037, -0.12938151 0.1122776 0.21194637, -0.12923564 0.11189401 0.21281712, -0.12886286 0.11151215 0.213644, -0.12827075 0.11115643 0.21437702, -0.12908389 0.11182274 0.21271715, -0.12915489 0.11186644 0.21276891, -0.12878576 0.11151057 0.21358383, -0.1282061 0.1111805 0.21430747, -0.12743589 0.1108987 0.21489227, -0.12865226 0.11145501 0.21345294, -0.12871461 0.11149122 0.21351919, -0.12814376 0.11118636 0.21423197, -0.12648781 0.1107379 0.21521407, -0.12548083 0.11071041 0.21494147, -0.12803626 0.11114398 0.21407467, -0.12808649 0.111174 0.21415338, -0.12646432 0.11434099 0.20798746, -0.12743597 0.11423104 0.20822871, -0.1254808 0.11432694 0.20795178, -0.12548089 0.11068326 0.21532336, -0.12548074 0.11071822 0.2152319, -0.12548079 0.11415741 0.20804858, -0.12548079 0.11424696 0.20800838, -0.12417917 0.11287953 0.20869567, -0.12369008 0.11396007 0.20844312, -0.12292552 0.11372401 0.20891502, -0.12313527 0.11250724 0.20944044, -0.12490822 0.1101668 0.21316625, -0.12417912 0.11046158 0.21353066, -0.12471832 0.11055779 0.21429227, -0.12369002 0.11090767 0.2145469, -0.12455864 0.11076045 0.21484165, -0.12490828 0.11241089 0.20867862, -0.12471841 0.11354662 0.20831613, -0.12455863 0.11410739 0.20814881, -0.12292546 0.11114399 0.21407497, -0.12313536 0.11083397 0.21278633, -0.12187776 0.11182289 0.21271724, -0.12230936 0.11145486 0.21345291, -0.12255605 0.11137195 0.21171032, -0.12165539 0.11264171 0.21107946, -0.12165533 0.11222623 0.21191047, -0.12255614 0.11196901 0.21051596, -0.12187766 0.11304511 0.21027271, -0.12230949 0.11341317 0.20953719, -0.094847828 0.076739982 0.27872866, -0.094832286 0.08030881 0.28052247, -0.094559133 0.076689675 0.27882975, -0.095080256 0.080385402 0.28036952, -0.094550639 0.080261037 0.28061813, -0.094251543 0.07667236 0.2788642, -0.094251484 0.080244884 0.28065062, -0.094251603 0.081363007 0.27841461, -0.094550699 0.081346676 0.27844709, -0.094251469 0.077804193 0.27663511, -0.094552875 0.077787772 0.27666804, -0.09483242 0.081298962 0.27854258, -0.094836459 0.077739254 0.27676511, -0.095080405 0.08122246 0.27869588, -0.095085502 0.077661589 0.27692044, -0.09528029 0.081121519 0.27889761, -0.09528549 0.077559277 0.27712497, -0.095497519 0.077187464 0.27783388, -0.095499784 0.076820537 0.27761251, -0.09549956 0.076740935 0.27757555, -0.095500618 0.07690458 0.27763516, -0.095420271 0.081002101 0.27913618, -0.095492393 0.08087121 0.27939785, -0.095492423 0.080736473 0.27966732, -0.095435023 0.077051833 0.27810538, -0.095420241 0.080605701 0.27992904, -0.09529987 0.076926991 0.27835494, -0.09528017 0.080486253 0.28016782, -0.095099956 0.076820925 0.27856722, -0.12548085 0.11490758 0.21133444, -0.12577997 0.11489125 0.21136698, -0.12548089 0.11133532 0.20954794, -0.12577988 0.11131898 0.2095803, -0.12606168 0.11484346 0.21146235, -0.12606165 0.11127113 0.20967591, -0.12630974 0.11476699 0.21161552, -0.1263096 0.11119466 0.20982939, -0.12650952 0.11466613 0.21181729, -0.12650938 0.11109361 0.21003103, -0.12664963 0.11454667 0.21205601, -0.12664954 0.11097424 0.21026953, -0.12672171 0.11441591 0.21231762, -0.12672174 0.11084341 0.21053112, -0.12672172 0.11428115 0.21258719, -0.12672159 0.11070858 0.21080065, -0.12664954 0.11415033 0.21284902, -0.12664959 0.11057781 0.21106255, -0.12650958 0.11403091 0.21308766, -0.12650956 0.11045851 0.21130119, -0.12630975 0.11393008 0.21328929, -0.12630972 0.11035775 0.21150279, -0.12606165 0.11385342 0.21344221, -0.12606165 0.11028098 0.21165597, -0.12578005 0.11380568 0.21353802, -0.12577999 0.11023317 0.21175152, -0.12548082 0.11021701 0.21178398, -0.12548082 0.1137896 0.21357048, -0.12548089 0.11684778 0.21191329, -0.12548089 0.11836252 0.21267089, -0.12586379 0.1168271 0.21195492, -0.12586367 0.11834165 0.21271244, -0.12622443 0.1182805 0.21283472, -0.12622437 0.11676583 0.21207726, -0.12654182 0.11818238 0.21303062, -0.12654188 0.11666764 0.21227317, -0.12679753 0.11805335 0.21328881, -0.12679759 0.11653858 0.21253151, -0.12697673 0.11790058 0.21359417, -0.12697676 0.11638582 0.21283695, -0.12706912 0.11773309 0.21392915, -0.12706915 0.11621833 0.21317193, -0.12706923 0.11756051 0.21427447, -0.1270691 0.11604592 0.21351691, -0.12697682 0.11739299 0.21460938, -0.12697685 0.11587831 0.21385178, -0.12679771 0.11724031 0.21491477, -0.12679768 0.11572561 0.21415743, -0.12654176 0.1171111 0.21517308, -0.12654176 0.11559637 0.21441565, -0.1262244 0.11701316 0.2153689, -0.1262244 0.11549839 0.21461156, -0.12586376 0.116952 0.21549138, -0.12586364 0.11543724 0.21473384, -0.12548077 0.11693102 0.21553281, -0.12548074 0.11541626 0.21477532, -0.094251513 0.083303109 0.27899352, -0.094251603 0.084817901 0.27975094, -0.094634384 0.083282217 0.27903515, -0.094634444 0.08479698 0.27979264, -0.094995052 0.084735885 0.27991477, -0.094995111 0.083221182 0.2791574, -0.095312461 0.084637836 0.28011066, -0.095312461 0.083123162 0.27935326, -0.095568314 0.084508732 0.28036913, -0.09556824 0.08299394 0.27961165, -0.095747635 0.084355995 0.28067446, -0.09574753 0.082841232 0.27991703, -0.095839813 0.084188625 0.2810095, -0.095839798 0.082673863 0.28025201, -0.095839843 0.08401604 0.28135458, -0.095839798 0.082501248 0.28059691, -0.095747575 0.083848551 0.28168958, -0.09574759 0.082333818 0.28093204, -0.095568255 0.083695695 0.281995, -0.09556821 0.082181022 0.28123754, -0.095312521 0.083566561 0.28225324, -0.095312536 0.082051948 0.28149584, -0.094995096 0.083468601 0.28244907, -0.094994962 0.081953958 0.28169158, -0.09463428 0.083407238 0.28257146, -0.094634354 0.081892565 0.28181401, -0.094251499 0.083386496 0.28261295, -0.094251484 0.081871942 0.28185558, -0.10837626 0.10198762 0.23203442, -0.11347273 0.10335998 0.2292906, -0.10839631 0.10209031 0.2320139, -0.11344291 0.10347238 0.22929141, -0.10842828 0.10219866 0.23196521, -0.11340186 0.10357866 0.22926821, -0.10847136 0.10230671 0.23188937, -0.1133517 0.10367326 0.22922224, -0.1085234 0.10240822 0.23179018, -0.11329536 0.10375069 0.22915645, -0.1085811 0.10249715 0.2316736, -0.11323565 0.10380714 0.229074, -0.10864078 0.10256988 0.23154789, -0.1112632 0.10508908 0.22583289, -0.11636005 0.10646111 0.22308907, -0.11128327 0.10519142 0.22581199, -0.11633012 0.10657349 0.22308977, -0.11131543 0.10529993 0.22576344, -0.11628906 0.10667983 0.22306654, -0.11135864 0.10540818 0.2256878, -0.11623889 0.10677445 0.2230209, -0.11141059 0.10550942 0.22558859, -0.11618248 0.10685191 0.22295482, -0.11146827 0.10559855 0.22547208, -0.11612287 0.10690817 0.22287221, -0.11152788 0.10567121 0.22534622, -0.10260187 0.095785275 0.24443762, -0.10769838 0.097157508 0.24169387, -0.10262188 0.095887884 0.24441689, -0.10766846 0.097269803 0.24169458, -0.10265389 0.095996246 0.24436831, -0.10762738 0.097376063 0.24167158, -0.10269699 0.096104339 0.24429271, -0.1075774 0.097470701 0.2416257, -0.10274909 0.096205607 0.24419336, -0.107521 0.097548172 0.2415598, -0.10280669 0.096294746 0.24407685, -0.10746151 0.097604692 0.24147724, -0.1028664 0.096367493 0.24395104, -0.099714682 0.092684045 0.2506392, -0.10481124 0.094056144 0.24789537, -0.099734828 0.092786804 0.25061858, -0.1047813 0.094168529 0.24789619, -0.099766731 0.092895076 0.25056997, -0.10474017 0.094274953 0.24787286, -0.09980996 0.093003139 0.25049418, -0.10469012 0.094369426 0.24782728, -0.099861905 0.093104556 0.25039509, -0.10463376 0.094447121 0.24776141, -0.099919677 0.093193486 0.25027841, -0.10457413 0.094503418 0.24767886, -0.099979237 0.093266234 0.25015241, -0.096827433 0.089582905 0.25684077, -0.10192394 0.090954885 0.25409687, -0.096847579 0.089685425 0.25682008, -0.10189416 0.091067329 0.25409782, -0.096879601 0.089793846 0.25677189, -0.10185303 0.091173664 0.25407457, -0.096922606 0.089901879 0.25669596, -0.10180283 0.091268137 0.25402874, -0.096974701 0.090003237 0.25659657, -0.10174657 0.091345683 0.25396276, -0.097032398 0.090092346 0.25648004, -0.101687 0.091402158 0.25388041, -0.097092077 0.090165183 0.25635421, -0.093940333 0.086481616 0.26304239, -0.099036813 0.087853685 0.26029867, -0.093960419 0.086584374 0.26302159, -0.09900701 0.087966219 0.26029938, -0.093992427 0.086692676 0.26297319, -0.098965868 0.088072583 0.2602762, -0.094035432 0.086800829 0.26289746, -0.098915651 0.088167027 0.26023054, -0.094087526 0.086902037 0.26279798, -0.098859474 0.088244602 0.2601645, -0.094145134 0.086991176 0.26268172, -0.09879984 0.088300958 0.26008189, -0.094204828 0.087063864 0.26255563, -0.091053247 0.083380476 0.26924416, -0.096149668 0.084752485 0.26650035, -0.09107323 0.083483055 0.26922339, -0.096119896 0.08486487 0.2665011, -0.091105118 0.083591476 0.26917481, -0.096078709 0.084971264 0.26647782, -0.091148451 0.083699539 0.26909906, -0.096028641 0.085065678 0.26643214, -0.091200426 0.083800927 0.26899967, -0.095972255 0.085143343 0.26636618, -0.091258004 0.083889976 0.26888338, -0.09591262 0.085199699 0.26628375, -0.091317758 0.083962724 0.26875728, -0.10548918 0.098886579 0.23823598, -0.11058566 0.10025853 0.23549227, -0.1055091 0.098989248 0.23821525, -0.1105556 0.10037109 0.23549291, -0.10554108 0.09909758 0.23816682, -0.11051451 0.10047737 0.23546958, -0.10558423 0.099205464 0.23809089, -0.1104646 0.10057181 0.23542391, -0.10563628 0.09930703 0.23799172, -0.11040822 0.10064954 0.23535798, -0.10569403 0.099395961 0.23787518, -0.11034861 0.1007058 0.23527549, -0.10575362 0.099468917 0.23774955, -0.088165984 0.080279127 0.27544567, -0.093262494 0.081651345 0.27270183, -0.088185951 0.080381766 0.27542475, -0.093232572 0.081763759 0.27270284, -0.088218018 0.080490127 0.27537647, -0.093191639 0.081870124 0.27267945, -0.088261053 0.08059825 0.27530053, -0.093141377 0.081964567 0.27263349, -0.088313073 0.080699697 0.27520132, -0.09308511 0.082042113 0.2725676, -0.088370904 0.080788687 0.27508488, -0.093025506 0.082098439 0.27248508, -0.088430598 0.080861434 0.27495897, -0.085278943 0.077178106 0.28164738, -0.089761585 0.078384891 0.27923378, -0.085298821 0.077280715 0.28162652, -0.089731872 0.078497246 0.27923447, -0.085330769 0.077389017 0.28157794, -0.089690566 0.078603521 0.2792114, -0.085373983 0.07749702 0.28150228, -0.089640617 0.078698054 0.2791656, -0.085426018 0.077598408 0.28140271, -0.089584351 0.078775659 0.27909988, -0.085483715 0.077687398 0.28128648, -0.089524612 0.078832045 0.27901739, -0.085543409 0.077760205 0.28116059, -0.083253428 0.074213222 0.28578192, -0.099499092 0.074213102 0.28578192, -0.083306506 0.074569747 0.28575003, -0.099570557 0.074579969 0.28574824, -0.083387211 0.07492654 0.28565049, -0.099675238 0.07493268 0.28564811, -0.083493575 0.075264648 0.28548324, -0.09980987 0.075261638 0.28548503, -0.083620414 0.075565293 0.28525567, -0.099970385 0.075555965 0.28526419, -0.083760694 0.075813875 0.28498101, -0.10015152 0.07580547 0.28499216, -0.083906576 0.076002017 0.28467652, -0.10034825 0.076001957 0.28467655, -0.13067095 -0.033310443 0.1406953, -0.13063049 -0.03330934 0.14067577, -0.13064125 -0.03330566 0.14065103, -0.13062166 -0.033310458 0.14081568, -0.13061997 -0.033313051 0.14070065, -0.13059901 -0.033321023 0.14074969, -0.13058965 -0.033324078 0.14077169, -0.13058482 -0.033310294 0.14090574, -0.13057843 -0.033323899 0.14086227, -0.13057993 -0.033326745 0.14079499, -0.13057002 -0.033331051 0.14081776, -0.13055633 -0.033330798 0.14090896, -0.1305522 -0.033343896 0.14085792, -0.13056095 -0.033338055 0.14083806, -0.13056557 -0.033334449 0.14082807, -0.13052969 -0.033350661 0.14090925, -0.13053872 -0.033349141 0.1408897, -0.13054539 -0.033347055 0.14087358, -0.11406691 -0.033310056 0.18112248, -0.11414623 -0.033312574 0.18113361, -0.11406593 -0.033312634 0.1811803, -0.11412889 -0.03331165 0.1811076, -0.11411157 -0.033308759 0.18108182, -0.1140946 -0.033303946 0.18105638, -0.10595134 0.084114596 0.2684536, -0.12004352 0.099590451 0.23750582, -0.1183017 0.097620904 0.24144422, -0.12021518 0.099597842 0.23749128, -0.1061134 0.084152833 0.26837671, -0.10560751 0.084084287 0.26851386, -0.10337384 0.082250789 0.27218091, -0.10357244 0.08221899 0.2722443, -0.12038729 0.09962061 0.23744577, -0.11800823 0.097725004 0.24123621, -0.11818606 0.097673103 0.24134009, -0.10625491 0.084204987 0.2682727, -0.1374217 0.11598152 0.20472839, -0.137467 0.11591369 0.2048637, -0.13745299 0.1159488 0.20479348, -0.12054929 0.099658996 0.23736888, -0.11780953 0.097756714 0.24117276, -0.1063683 0.084267125 0.26814812, -0.12069081 0.09971121 0.23726471, -0.13746275 0.11587833 0.20493448, -0.13737485 0.11601001 0.20467117, -0.13744101 0.11584467 0.20500171, -0.10644937 0.084335193 0.26801234, -0.13731389 0.11603315 0.20462474, -0.13724357 0.1160495 0.2045922, -0.13716592 0.11605839 0.20457453, -0.13712054 0.11605975 0.20457169, -0.13707492 0.11605853 0.20457411, -0.12080409 0.099773347 0.23714034, -0.12088522 0.099841267 0.23700422, -0.09644033 0.084084585 0.26851389, -0.11087622 0.099590391 0.23750585, -0.124474 0.11439185 0.20790692, -0.12095027 0.11515011 0.20639099, -0.12352578 0.11423124 0.2082286, -0.096168205 0.084073529 0.26853615, -0.095902488 0.084040388 0.26860213, -0.09565632 0.083986983 0.26870906, -0.11060414 0.099579513 0.23752801, -0.11033842 0.099546492 0.23759393, -0.12269108 0.11397339 0.20874403, -0.093878567 0.082242623 0.27219698, -0.11009227 0.099493116 0.23770097, -0.12037104 0.115054 0.20658302, -0.12003221 0.11491047 0.20687003, -0.1206485 0.11511685 0.20645747, -0.12018649 0.11498834 0.20671414, -0.10272034 0.080983117 0.27471554, -0.10100505 0.0789987 0.2786839, -0.10289201 0.080990508 0.27470097, -0.10831444 0.097748637 0.241189, -0.10086206 0.079066113 0.2785489, -0.10068186 0.080983117 0.27471554, -0.10069409 0.079115584 0.27844974, -0.11986899 0.11478253 0.20712623, -0.11994188 0.11484887 0.20699356, -0.12201858 0.1136338 0.20942289, -0.11529894 0.094571874 0.24754155, -0.11541465 0.094519809 0.24764593, -0.11715624 0.096489325 0.24370746, -0.10306425 0.081013277 0.27465522, -0.10110959 0.078917876 0.27884549, -0.10322623 0.081051663 0.27457833, -0.12973389 0.11007828 0.21653301, -0.11732796 0.096496716 0.24369298, -0.10049629 0.079148456 0.27838451, -0.1175001 0.096519485 0.24364699, -0.10116887 0.078830168 0.27902061, -0.10336791 0.081103757 0.2744745, -0.12987676 0.11001095 0.21666774, -0.1151211 0.094623819 0.24743764, -0.12956588 0.11012787 0.21643381, -0.12998141 0.10993007 0.21682955, -0.117662 0.096557885 0.24357058, -0.10118237 0.078742817 0.27919537, -0.10348113 0.081165984 0.27434981, -0.12936795 0.11016056 0.21636856, -0.11492236 0.094655648 0.24737445, -0.1300405 0.10984239 0.21700472, -0.11780369 0.096609876 0.24346633, -0.13005404 0.10975504 0.21717928, -0.10116056 0.078669503 0.27934223, -0.13003221 0.10968161 0.2173261, -0.11791688 0.096672103 0.24334182, -0.12998536 0.10961628 0.21745735, -0.11799797 0.096740142 0.24320595, -0.12154721 0.11323221 0.21022616, -0.12954664 0.10914487 0.21839938, -0.12130442 0.1127917 0.21110708, -0.089989722 0.082461372 0.27175957, -0.089901164 0.082441196 0.27179998, -0.10798921 0.09648937 0.24370757, -0.10356207 0.081233934 0.27421379, -0.10111368 0.078604028 0.27947313, -0.10067493 0.078132734 0.28041536, -0.10059395 0.078064755 0.28055149, -0.10048057 0.078002647 0.28067595, -0.10033897 0.077950552 0.28078002, -0.10017717 0.077912137 0.28085691, -0.10000491 0.077889487 0.28090233, -0.09983325 0.077881977 0.28091699, -0.090666145 0.077882037 0.28091723, -0.10771698 0.096478403 0.24372952, -0.10745119 0.096445143 0.24379563, -0.090393871 0.07787101 0.28093916, -0.090128139 0.077837989 0.28100526, -0.10720511 0.096391767 0.2439025, -0.089882016 0.077784434 0.2811119, -0.10542731 0.094647542 0.24739052, -0.084215447 0.076258913 0.28416285, -0.084126934 0.076238707 0.28420317, -0.11511075 0.093638912 0.24940763, -0.11222376 0.090537682 0.25560918, -0.10933641 0.087436453 0.26181072, -0.12352575 0.11089873 0.21489213, -0.12447394 0.1107378 0.215214, -0.12269101 0.11115645 0.21437699, -0.12201847 0.11149605 0.2136981, -0.11426912 0.093388036 0.24990907, -0.11252755 0.091418505 0.25384757, -0.11444072 0.093395412 0.24989448, -0.12377247 0.10294273 0.23080283, -0.11241175 0.091470644 0.25374335, -0.12665957 0.10604374 0.22460105, -0.12154716 0.11189775 0.21289492, -0.11986311 0.11015365 0.21638227, -0.12870488 0.10889396 0.2189011, -0.11953773 0.10889414 0.2189011, -0.11461292 0.093418077 0.24984875, -0.11875367 0.10879663 0.21909602, -0.11308719 0.10727125 0.22214681, -0.11653313 0.10699733 0.22269419, -0.1169759 0.10705228 0.22258422, -0.1129986 0.10725085 0.2221871, -0.11586662 0.10569549 0.22529766, -0.11020005 0.1041698 0.22834852, -0.11364612 0.10389607 0.22889584, -0.11223395 0.0915225 0.25363946, -0.11408873 0.10395111 0.22878583, -0.11011145 0.10414965 0.2283887, -0.11297941 0.10259418 0.23149925, -0.10731278 0.10106874 0.23454991, -0.11075884 0.100795 0.23509748, -0.11120161 0.10084993 0.2349873, -0.10722426 0.10104853 0.23459046, -0.1044257 0.097967461 0.24075165, -0.11477511 0.093456551 0.24977213, -0.10787165 0.097693771 0.24129917, -0.12684755 0.10697666 0.22273536, -0.12696323 0.10692449 0.2228394, -0.10433701 0.09794715 0.24079199, -0.10153843 0.094866261 0.24695323, -0.10498448 0.094592556 0.24750082, -0.12887669 0.10890129 0.21888652, -0.10144995 0.094846144 0.24699359, -0.10431784 0.093290627 0.25010407, -0.098651201 0.091764942 0.25315464, -0.10209729 0.091491237 0.25370234, -0.10254018 0.091546282 0.25359219, -0.1120353 0.091554269 0.2535761, -0.098562792 0.091744766 0.25319511, -0.10143062 0.090189442 0.25630587, -0.095764011 0.088663772 0.25935644, -0.12904879 0.10892421 0.2188409, -0.099210009 0.088390097 0.25990385, -0.099653006 0.088445202 0.25979379, -0.11491641 0.093508586 0.24966811, -0.095675558 0.088643715 0.25939685, -0.098543614 0.087088183 0.26250735, -0.092876866 0.085562423 0.26555786, -0.12666984 0.10702854 0.22263138, -0.096322998 0.085288748 0.26610553, -0.096765712 0.085343793 0.26599523, -0.092788294 0.085542277 0.26559839, -0.09343569 0.082187518 0.27230704, -0.12921076 0.1089626 0.21876399, -0.11502969 0.093570754 0.24954329, -0.12647112 0.10706037 0.22256808, -0.12935242 0.10901457 0.21865982, -0.12130444 0.1123382 0.21201406, -0.11942033 0.11009851 0.21649259, -0.12946558 0.1090768 0.21853539, -0.1051019 0.093387917 0.249909, -0.10482968 0.093377128 0.2499312, -0.10456398 0.093344018 0.24999732, -0.11926559 0.10888307 0.21892327, -0.11899987 0.10885012 0.21898912, -0.10952455 0.088369474 0.2599448, -0.10964029 0.088317439 0.26004916, -0.1113819 0.090286806 0.25611073, -0.11155373 0.090294138 0.25609621, -0.11172585 0.090316936 0.25605041, -0.10934679 0.088421389 0.25984102, -0.12396047 0.10387547 0.22893687, -0.12407614 0.10382326 0.22904107, -0.12581763 0.10579284 0.22510259, -0.1118878 0.090355322 0.25597358, -0.1259895 0.10580014 0.22508822, -0.109148 0.088453189 0.25977778, -0.12616169 0.10582297 0.22504245, -0.1237826 0.10392745 0.22883292, -0.11202922 0.090407357 0.25586945, -0.12632357 0.10586128 0.22496559, -0.123584 0.10395916 0.22876973, -0.11214267 0.090469703 0.25574505, -0.12646505 0.10591348 0.22486158, -0.12657839 0.10597573 0.22473709, -0.10221462 0.090286866 0.25611073, -0.11665055 0.10579288 0.22510265, -0.10194249 0.090275928 0.25613284, -0.10167682 0.090242848 0.25619876, -0.1163784 0.10578185 0.22512464, -0.11611268 0.10574892 0.22519083, -0.10663746 0.085268185 0.26614654, -0.10675314 0.08521606 0.26625067, -0.10849471 0.087185487 0.26231217, -0.10866642 0.087192819 0.26229763, -0.1088386 0.087215766 0.26225197, -0.10645974 0.08532016 0.26604271, -0.12293051 0.10269168 0.23130424, -0.12118895 0.10072231 0.23524277, -0.12310229 0.10269895 0.2312897, -0.12107332 0.10077441 0.23513858, -0.10900053 0.087254182 0.26217544, -0.12327455 0.10272184 0.23124392, -0.10626101 0.08535181 0.26597935, -0.12089559 0.10082629 0.23503464, -0.10914208 0.087306127 0.26207119, -0.12343641 0.10276008 0.23116712, -0.12069675 0.10085806 0.23497114, -0.1092554 0.087368324 0.26194662, -0.12357804 0.10281232 0.23106331, -0.12369144 0.10287455 0.23093858, -0.099327534 0.087185696 0.26231235, -0.11376333 0.10269172 0.23130414, -0.09905532 0.087174669 0.26233435, -0.098789662 0.087141529 0.26240039, -0.11349124 0.10268073 0.23132646, -0.11322559 0.10264756 0.23139252, -0.10386592 0.08211486 0.27245241, -0.10577926 0.084091768 0.26849926, -0.10375021 0.082167074 0.27234805, -0.090990663 0.080406889 0.2758677, -0.087102562 0.079360023 0.27796119, -0.087014154 0.079339996 0.2780017, -0.10429761 -0.033004269 0.2144333, -0.090447158 0.077951923 0.27861118, -0.099330485 -0.033004358 0.21776885, -0.085274294 0.076981232 0.28160477, -0.099027798 -0.033198789 0.21787582, -0.089782536 0.078194872 0.27917767, -0.087389439 0.079249665 0.27706057, -0.092659101 0.079445556 0.27361885, -0.10135435 -0.032624319 0.21235193, -0.090733021 0.080149665 0.27526045, -0.10664846 -0.03262414 0.20879686, -0.099496216 0.073211834 0.2855134, -0.089157641 0.064194128 0.28029722, -0.098882645 -0.006640628 0.2393261, -0.088209361 0.064505473 0.2804774, -0.097934246 -0.006951943 0.23914598, -0.087374628 0.065004215 0.28076589, -0.097099468 -0.0074507743 0.23885764, -0.096427038 -0.0081078559 0.23847745, -0.088209376 0.070954815 0.28420779, -0.083251342 0.073211864 0.28551328, -0.087374553 0.070455924 0.28391922, -0.089157656 0.07126604 0.28438777, -0.086702049 0.069798812 0.28353918, -0.086230665 0.069021359 0.28308958, -0.085987985 0.068169102 0.28259647, -0.085988 0.067291155 0.28208867, -0.086230665 0.06643869 0.28159544, -0.09888263 -0.013712689 0.23523559, -0.097342759 -0.032316193 0.22447513, -0.097934172 -0.013401374 0.23541562, -0.097099468 -0.012902692 0.23570408, -0.096518293 -0.033070043 0.22403902, -0.096427009 -0.012245491 0.23608412, -0.095955789 -0.011468038 0.23653382, -0.095713019 -0.010615632 0.23702702, -0.09571296 -0.0097377151 0.2375347, -0.095955819 -0.0088852495 0.23802775, -0.086702079 0.065661326 0.28114608, -0.13054822 -0.033404469 0.13889717, -0.095058769 -0.033760414 0.22546045, -0.13036333 -0.034601569 0.1390215, -0.094157934 -0.034606263 0.22742884, -0.09405233 -0.033760563 0.22791797, -0.090210497 0.0050798506 0.24792583, -0.11916131 0.11647919 0.20771004, -0.11283736 0.10847855 0.22096345, -0.11926882 0.11538674 0.20714869, -0.090141147 0.0056354254 0.24824736, -0.084407821 0.051563904 0.27481264, -0.084338456 0.052119657 0.27513403, -0.081678852 0.074540928 0.28776306, -0.08175759 0.075143471 0.28773519, -0.082610533 0.077218667 0.28622067, -0.081893131 0.075749174 0.28757, -0.082077369 0.076305166 0.28727248, -0.082321092 0.076816931 0.28681743, -0.11337395 0.10716052 0.22124602, -0.11849591 0.10853922 0.21848838, -0.13085692 -0.032896474 0.14023608, -0.13615103 -0.03289628 0.13668101, -0.084502295 0.076148257 0.28326195, -0.089624047 0.077527151 0.28050435, -0.098080084 -0.032624826 0.2203472, -0.10337417 -0.032624617 0.21679215, -0.1104867 0.10405932 0.2274477, -0.11560878 0.10543841 0.22469012, -0.12754823 -0.032620952 0.1483908, -0.13284232 -0.032620698 0.14483571, -0.13376577 -0.033000454 0.14247736, -0.11638084 0.10627124 0.22303279, -0.12879877 -0.033000425 0.14581269, -0.11125886 0.10489221 0.22579029, -0.12849596 -0.033194929 0.14591953, -0.1075996 0.10095794 0.23364906, -0.11272162 0.10233694 0.23089157, -0.12427408 -0.032621339 0.15638608, -0.12956813 -0.032621175 0.15283099, -0.13049158 -0.033000678 0.15047248, -0.11349367 0.10316995 0.22923419, -0.1255244 -0.033000976 0.15380765, -0.10837154 0.10179096 0.23199192, -0.12522174 -0.033195406 0.15391494, -0.10471241 0.097856626 0.23985077, -0.10983428 0.099235773 0.23709331, -0.1209998 -0.032621846 0.16438125, -0.12629393 -0.032621637 0.1608261, -0.12721731 -0.033001304 0.15846737, -0.1106064 0.10006863 0.23543589, -0.12225018 -0.033001363 0.16180278, -0.1054844 0.098689914 0.23819356, -0.12194754 -0.033195838 0.16190998, -0.10182531 0.094755635 0.24605234, -0.1069472 0.096134573 0.24329484, -0.11772561 -0.032622203 0.1723763, -0.12301964 -0.032622084 0.16882123, -0.12394303 -0.033001646 0.16646245, -0.1077192 0.096967563 0.24163751, -0.11897592 -0.033001825 0.16979793, -0.1025973 0.095588431 0.24439508, -0.11867324 -0.0331963 0.16990508, -0.098938078 0.091654316 0.25225401, -0.10406013 0.093033269 0.24949647, -0.1144513 -0.032622725 0.1803713, -0.11974539 -0.032622516 0.17681636, -0.12066884 -0.033002019 0.17445771, -0.1048321 0.093866363 0.24783908, -0.11570169 -0.033002317 0.17779326, -0.099710077 0.092487261 0.25059664, -0.11539902 -0.033196762 0.17790009, -0.096050948 0.088553235 0.25845563, -0.10117275 0.089932069 0.25569791, -0.11117719 -0.032622829 0.18836647, -0.11647114 -0.032622993 0.1848114, -0.11739466 -0.033002511 0.1824529, -0.10194492 0.090765074 0.25404072, -0.11242738 -0.033002838 0.18578833, -0.096822828 0.089386061 0.25679833, -0.11212473 -0.033197239 0.18589526, -0.093163714 0.085452065 0.2646575, -0.098285645 0.08683081 0.26189977, -0.10790293 -0.032623455 0.19636181, -0.11319695 -0.032623306 0.19280666, -0.11412033 -0.033002928 0.19044788, -0.099057674 0.087663814 0.2602424, -0.10915324 -0.033003196 0.19378337, -0.093935803 0.086284921 0.26299995, -0.10885049 -0.033197775 0.19389044, -0.090276465 0.082350746 0.27085888, -0.095398501 0.08372964 0.2681013, -0.10462864 -0.032623872 0.20435682, -0.10992263 -0.032623693 0.20080182, -0.11084603 -0.033003375 0.198443, -0.096170411 0.084562406 0.26644385, -0.10587902 -0.033003554 0.20177855, -0.091048628 0.083183542 0.26920164, -0.10557626 -0.033198044 0.20188563, -0.10757183 -0.033003882 0.20643824, -0.093283355 0.081461444 0.27264586, -0.10260475 -0.033003911 0.20977366, -0.088161469 0.080082491 0.27540314, -0.10230197 -0.033198491 0.20988069, -0.099463627 0.073528275 0.28566122, -0.083226249 0.07352753 0.28566083, -0.083227053 0.073866293 0.28575164, -0.099464744 0.073865458 0.28575146, -0.084491417 0.076205388 0.28330374, -0.089630395 0.077622429 0.28056362, -0.084473684 0.076256618 0.28336132, -0.089649349 0.077703014 0.28063932, -0.084439903 0.076310053 0.28345817, -0.089680031 0.07776539 0.28072727, -0.084384844 0.076348439 0.28360319, -0.089720994 0.0778061 0.28082377, -0.08976984 0.077823237 0.28092325, -0.084294006 0.076350644 0.28382593, -0.089824468 0.077815965 0.28102094, -0.084174559 0.076283589 0.28409931, -0.084188029 0.076276675 0.28412092, -0.084201679 0.076268449 0.28414208, -0.089780092 0.078256264 0.27920371, -0.085270002 0.077042148 0.28163195, -0.085271493 0.077108309 0.28164619, -0.089773059 0.078320011 0.27922273, -0.093280971 0.081522778 0.27267188, -0.088157162 0.080143288 0.27543035, -0.088158712 0.080209449 0.27544454, -0.093273908 0.081586465 0.27269053, -0.087378666 0.079306737 0.27710238, -0.090739295 0.080244854 0.27531955, -0.087360859 0.079357877 0.27715975, -0.090758234 0.080325618 0.2753953, -0.087327152 0.079411253 0.27725673, -0.090788722 0.080387786 0.27548325, -0.087272003 0.079449728 0.27740189, -0.090829805 0.080428645 0.27557951, -0.090878755 0.080445841 0.27567935, -0.087181166 0.079451934 0.27762416, -0.090933472 0.08043845 0.27577698, -0.087061718 0.079384878 0.27789757, -0.087075189 0.079377905 0.27791944, -0.087088898 0.079369619 0.27794072, -0.096698388 -0.033309773 0.22366673, -0.096881866 -0.033208147 0.22354937, -0.096939102 -0.033089831 0.22379392, -0.096649066 -0.033354625 0.22364202, -0.096869096 -0.033297017 0.22329158, -0.096901283 -0.033354595 0.2230261, -0.11222546 -0.033352613 0.18560715, -0.11237463 -0.033271074 0.18550764, -0.11238383 -0.033250824 0.18555099, -0.11237362 -0.0332876 0.18545631, -0.11239018 -0.033305809 0.18535665, -0.11243406 -0.033312902 0.1852265, -0.11399895 -0.03335239 0.18127634, -0.11404054 -0.033312634 0.18130416, -0.10895114 -0.033353016 0.19360223, -0.10904957 -0.033309802 0.19350265, -0.10906313 -0.033280984 0.19356264, -0.10904606 -0.033333823 0.19343297, -0.10905258 -0.033353016 0.19335464, -0.10567687 -0.033353493 0.20159748, -0.10577524 -0.03331013 0.20149779, -0.10578892 -0.033281401 0.20155779, -0.10577181 -0.033334211 0.20142797, -0.10577831 -0.033353284 0.20134965, -0.10240266 -0.03335382 0.20959264, -0.10250106 -0.033310488 0.2094928, -0.10251471 -0.033281818 0.20955282, -0.10249755 -0.033334538 0.20942339, -0.10250412 -0.033353731 0.20934476, -0.09912844 -0.033354208 0.21758766, -0.099226922 -0.033310935 0.21748792, -0.099240422 -0.033282235 0.21754809, -0.099223301 -0.033335105 0.21741848, -0.099229828 -0.033354267 0.21733989, -0.11549963 -0.033352092 0.17761196, -0.11559819 -0.033308879 0.17751215, -0.11561172 -0.033280089 0.17757253, -0.11559455 -0.033332899 0.17744271, -0.11560112 -0.033352107 0.17736435, -0.11877385 -0.033351734 0.16961694, -0.11887237 -0.033308461 0.16951723, -0.11888596 -0.033279568 0.16957751, -0.11886874 -0.033332497 0.16944745, -0.11887541 -0.03335169 0.16936913, -0.12204807 -0.033351198 0.16162185, -0.12214641 -0.033308044 0.16152184, -0.12216024 -0.033279195 0.16158216, -0.122143 -0.033332065 0.16145243, -0.12214948 -0.033351168 0.16137414, -0.12532234 -0.033350855 0.1536267, -0.1254207 -0.033307686 0.1535268, -0.1254344 -0.033278853 0.15358712, -0.12541713 -0.033331782 0.1534573, -0.12542373 -0.033350796 0.15337904, -0.12859656 -0.033350363 0.14563146, -0.1287459 -0.03326878 0.14553201, -0.12875496 -0.03324841 0.14557552, -0.12874483 -0.033285245 0.14548063, -0.1287614 -0.033303484 0.14538097, -0.12880526 -0.033310518 0.14525092, -0.12100454 -0.032685742 0.16435255, -0.12627593 -0.032739535 0.1607994, -0.12100245 -0.032754496 0.16433807, -0.12099473 -0.032818869 0.16433944, -0.12627451 -0.032861724 0.16079716, -0.12098281 -0.032877788 0.1643528, -0.12096596 -0.03293626 0.16437763, -0.12628955 -0.032980844 0.16081958, -0.1209449 -0.032992825 0.16441384, -0.12091067 -0.03306371 0.1644778, -0.12632017 -0.03308998 0.16086526, -0.12085991 -0.033142313 0.16458037, -0.12636486 -0.033182397 0.1609316, -0.12080409 -0.033205971 0.16469935, -0.12080328 -0.033241943 0.16476299, -0.12642053 -0.033252701 0.16101459, -0.12079684 -0.033269033 0.16483083, -0.12648419 -0.0332966 0.16110934, -0.120773 -0.033301935 0.16497126, -0.12655178 -0.033311591 0.16121005, -0.12073927 -0.033311829 0.16511323, -0.12223189 -0.033110246 0.16174491, -0.12195481 -0.033238515 0.16188054, -0.12196533 -0.033275262 0.16184466, -0.12198405 -0.033313051 0.16178887, -0.12220111 -0.033205479 0.16166945, -0.12200965 -0.033339605 0.16171865, -0.11060411 0.10013011 0.23546232, -0.10548019 0.098750621 0.23822065, -0.10548171 0.098816887 0.23823509, -0.11059693 0.10019374 0.23548095, -0.10470174 0.097913966 0.23989283, -0.10984075 0.099330872 0.23715247, -0.10468394 0.097965181 0.23995017, -0.10985962 0.099411607 0.23722808, -0.10465008 0.098018467 0.2400469, -0.10989027 0.099473953 0.23731631, -0.10459511 0.098057017 0.24019222, -0.10993108 0.099514723 0.23741232, -0.10998008 0.099531829 0.23751192, -0.10450426 0.098059207 0.24041457, -0.11003478 0.099524438 0.23760977, -0.10438474 0.097992301 0.24068812, -0.10439838 0.097985208 0.24070993, -0.10441194 0.097977027 0.24073111, -0.12755288 -0.032684967 0.14836219, -0.13282429 -0.032738611 0.14480916, -0.12755108 -0.032753497 0.1483478, -0.12754335 -0.032818124 0.14834908, -0.13282293 -0.03286092 0.14480679, -0.12753132 -0.032876849 0.14836255, -0.12751451 -0.032935381 0.14838734, -0.13283794 -0.032979995 0.14482924, -0.12749347 -0.032991901 0.14842352, -0.12745918 -0.033062771 0.14848751, -0.13286863 -0.033089086 0.14487496, -0.12740842 -0.033141375 0.14859003, -0.13291334 -0.033181518 0.14494152, -0.12735258 -0.033205092 0.14870888, -0.12735175 -0.033240959 0.14877281, -0.13296901 -0.033251688 0.14502445, -0.12734537 -0.033268139 0.14884058, -0.13303258 -0.033295766 0.14511907, -0.12732171 -0.033300936 0.14898103, -0.13310018 -0.033310562 0.14521988, -0.12728789 -0.033310845 0.14912283, -0.12879692 -0.033098817 0.14574873, -0.12850346 -0.033237576 0.1458903, -0.12851383 -0.033274338 0.14585453, -0.12853253 -0.033312172 0.14579862, -0.12878197 -0.033183575 0.14566784, -0.12855834 -0.03333877 0.14572839, -0.12427874 -0.03268531 0.15635736, -0.1295501 -0.032739103 0.15280417, -0.12427685 -0.032754108 0.15634295, -0.12426905 -0.032818571 0.1563441, -0.12954867 -0.032861292 0.1528019, -0.12425701 -0.032877296 0.15635763, -0.12424029 -0.032935858 0.15638264, -0.12956373 -0.032980427 0.15282449, -0.1242191 -0.032992378 0.15641861, -0.12418494 -0.033063143 0.15648259, -0.12959448 -0.033089548 0.15287013, -0.12413423 -0.033141837 0.15658517, -0.12963895 -0.033181891 0.15293667, -0.12407844 -0.033205524 0.15670399, -0.12407748 -0.033241406 0.15676801, -0.12969474 -0.033252224 0.15301952, -0.12407105 -0.033268556 0.15683587, -0.12975833 -0.033296138 0.15311433, -0.12404741 -0.033301473 0.15697618, -0.1298259 -0.033311039 0.15321502, -0.12401359 -0.033311263 0.15711801, -0.12550607 -0.033110008 0.15374975, -0.12522902 -0.033238202 0.15388538, -0.12523951 -0.03327477 0.15384965, -0.12525825 -0.033312589 0.1537938, -0.1254753 -0.033204988 0.1536742, -0.12528396 -0.033339292 0.15372361, -0.11773024 -0.032686263 0.17234744, -0.12300162 -0.032739982 0.16879438, -0.11772834 -0.032754928 0.17233314, -0.11772065 -0.03281942 0.17233458, -0.12300019 -0.032862082 0.16879201, -0.11770867 -0.032878235 0.17234786, -0.11769181 -0.032936618 0.17237261, -0.12301527 -0.032981262 0.1688146, -0.1176706 -0.032993287 0.17240882, -0.11763644 -0.033064052 0.17247292, -0.12304603 -0.033090353 0.1688605, -0.1175857 -0.03314276 0.17257547, -0.12309055 -0.033182755 0.16892672, -0.11752991 -0.033206314 0.17269446, -0.11752902 -0.033242315 0.17275818, -0.12314634 -0.033253089 0.16900969, -0.1175227 -0.03326948 0.17282589, -0.12320989 -0.033296928 0.16910459, -0.11749892 -0.033302397 0.1729665, -0.12327759 -0.033311978 0.16920531, -0.11746512 -0.033312112 0.17310849, -0.11895768 -0.033110678 0.16974011, -0.11868061 -0.033238918 0.16987555, -0.11869106 -0.033275649 0.16983972, -0.11870983 -0.033313468 0.16978383, -0.11892673 -0.033205837 0.16966458, -0.11873549 -0.033340096 0.16971394, -0.11405732 -0.033312604 0.18125024, -0.11402176 -0.033347532 0.18122239, -0.11404435 -0.033333257 0.18117076, -0.11406331 -0.033312529 0.18121545, -0.11445591 -0.032685846 0.18034281, -0.11972742 -0.032740459 0.17678954, -0.11445469 -0.032747567 0.18032925, -0.11444835 -0.032806486 0.1803284, -0.11972603 -0.032862633 0.17678738, -0.11443698 -0.032867312 0.18033962, -0.11442025 -0.03292872 0.18036354, -0.11974114 -0.032981783 0.17680982, -0.11439821 -0.032989353 0.18040074, -0.11437123 -0.033047646 0.18045095, -0.11977176 -0.033090815 0.17685546, -0.11432862 -0.033119202 0.18053512, -0.11981624 -0.033183292 0.17692173, -0.11427404 -0.033187926 0.18064988, -0.11987202 -0.033253536 0.17700495, -0.1141957 -0.033256158 0.18082222, -0.11414407 -0.033285752 0.18094027, -0.11993569 -0.033297449 0.17709984, -0.12000327 -0.033312425 0.17720033, -0.11568342 -0.03311123 0.17773513, -0.11540629 -0.03323932 0.17787068, -0.1154169 -0.033276036 0.17783503, -0.11543566 -0.033313885 0.17777908, -0.11565261 -0.03320618 0.17765968, -0.11546127 -0.033340439 0.17770915, -0.11118193 -0.032686964 0.1883378, -0.11645325 -0.032740816 0.18478492, -0.11117989 -0.032755688 0.18832351, -0.11117211 -0.032820091 0.18832462, -0.11645178 -0.032862917 0.18478239, -0.1111601 -0.032879069 0.18833794, -0.11114334 -0.032937303 0.1883629, -0.11646682 -0.032982111 0.18480495, -0.11112219 -0.032993987 0.18839912, -0.11108798 -0.033064798 0.18846314, -0.11649767 -0.033091143 0.1848506, -0.11103719 -0.033143595 0.18856578, -0.116542 -0.033183709 0.18491709, -0.11098137 -0.033207163 0.18868451, -0.1109806 -0.033243105 0.18874855, -0.11659788 -0.033253953 0.18500009, -0.11097407 -0.033270314 0.18881609, -0.11666146 -0.033297822 0.18509488, -0.11095048 -0.033303156 0.1889568, -0.11672907 -0.033312738 0.18519551, -0.11091667 -0.033313051 0.18909882, -0.11242567 -0.033101097 0.18572432, -0.11213197 -0.033239886 0.18586579, -0.11214259 -0.033276662 0.18583006, -0.11216128 -0.033314452 0.18577428, -0.11241078 -0.033185914 0.18564321, -0.11218703 -0.03334102 0.18570419, -0.10913481 -0.033112153 0.19372544, -0.1088578 -0.033240363 0.19386092, -0.10886833 -0.03327699 0.19382516, -0.108887 -0.033314869 0.19376937, -0.10910407 -0.033207104 0.19364992, -0.10891272 -0.033341572 0.19369915, -0.10790759 -0.032689705 0.19633213, -0.11317904 -0.032741234 0.19277979, -0.10790583 -0.032753572 0.19631898, -0.10789888 -0.032813802 0.196319, -0.11317745 -0.032863334 0.19277741, -0.10788693 -0.032874927 0.19633161, -0.10786983 -0.032935664 0.1963571, -0.11319254 -0.032982543 0.19280005, -0.10784779 -0.032994732 0.19639434, -0.10781185 -0.033068523 0.19646151, -0.11322334 -0.0330915 0.19284587, -0.10776465 -0.033141717 0.19655702, -0.11326781 -0.033184126 0.19291215, -0.10772857 -0.033185467 0.19663322, -0.10769126 -0.033222392 0.19671455, -0.11332358 -0.03325443 0.19299516, -0.10769527 -0.033265963 0.19679999, -0.11338714 -0.033298329 0.19308989, -0.10768484 -0.033296987 0.19690461, -0.10766844 -0.033308968 0.1969889, -0.11345476 -0.033313319 0.19319038, -0.10764229 -0.033313379 0.19709378, -0.10586078 -0.033112541 0.20172043, -0.10558355 -0.033240721 0.2018559, -0.10559435 -0.033277377 0.20182039, -0.1056129 -0.033315197 0.20176451, -0.10582995 -0.033207521 0.20164521, -0.1056385 -0.03334184 0.20169437, -0.10463333 -0.032690093 0.20432726, -0.10990459 -0.032741532 0.20077498, -0.10463154 -0.032754108 0.2043139, -0.10462472 -0.032814309 0.20431419, -0.10990317 -0.0328639 0.20077288, -0.10461257 -0.032875225 0.20432699, -0.10459554 -0.032936022 0.20435205, -0.10991822 -0.03298299 0.20079504, -0.1045735 -0.03299506 0.20438957, -0.10453779 -0.033068821 0.20445679, -0.10994904 -0.033092067 0.20084073, -0.10449046 -0.033141956 0.20455222, -0.10999361 -0.033184513 0.2009072, -0.10445438 -0.033185795 0.20462826, -0.10441704 -0.03322275 0.20470954, -0.11004928 -0.033254728 0.20099017, -0.10442093 -0.033266351 0.2047949, -0.11011292 -0.033298746 0.2010849, -0.10441062 -0.033297434 0.20489974, -0.10439426 -0.033309326 0.20498408, -0.11018053 -0.033313617 0.20118555, -0.10436819 -0.033313826 0.20508876, -0.096661195 -0.033308819 0.22373539, -0.096619174 -0.033345208 0.22371748, -0.096617833 -0.033298329 0.22379941, -0.096592426 -0.03331916 0.22378951, -0.096569315 -0.033278808 0.22385743, -0.097240165 -0.032560453 0.22431508, -0.096531138 -0.033152059 0.22398478, -0.096548468 -0.033222362 0.22392352, -0.097132802 -0.032784656 0.22413008, -0.10135899 -0.032688305 0.21232314, -0.10663043 -0.032741949 0.20877001, -0.10135709 -0.032756999 0.21230878, -0.10134937 -0.032821521 0.21230988, -0.106629 -0.032864198 0.20876792, -0.10133736 -0.032880291 0.2123235, -0.10132055 -0.032938734 0.21234836, -0.10664402 -0.032983407 0.20879009, -0.10129926 -0.032995418 0.2123847, -0.10126519 -0.033066228 0.2124486, -0.10667481 -0.033092514 0.20883596, -0.10121451 -0.033144787 0.21255113, -0.10671943 -0.033184871 0.20890243, -0.1011586 -0.033208475 0.21266986, -0.10115778 -0.033244446 0.21273398, -0.10677509 -0.033255145 0.20898536, -0.10115139 -0.033271536 0.21280153, -0.1068386 -0.033299103 0.20908016, -0.10112774 -0.033304527 0.21294212, -0.10690628 -0.033314094 0.20918086, -0.10109378 -0.033314213 0.21308397, -0.10258639 -0.033112958 0.20971555, -0.10230935 -0.033241227 0.20985121, -0.10231987 -0.033277676 0.20981547, -0.10233855 -0.033315524 0.2097595, -0.10255563 -0.033207908 0.20964003, -0.1023643 -0.033342108 0.20968953, -0.099312142 -0.033113375 0.21771072, -0.099035069 -0.033241525 0.21784644, -0.099045649 -0.033278212 0.21781068, -0.099064305 -0.033316031 0.21775471, -0.099281356 -0.033208385 0.2176352, -0.099090025 -0.033342615 0.21768467, -0.098084792 -0.032690957 0.22031754, -0.10335633 -0.032742515 0.21676527, -0.098083124 -0.032755092 0.22030419, -0.098076209 -0.032815054 0.22030455, -0.10335477 -0.032864645 0.21676295, -0.098064348 -0.032876149 0.22031718, -0.098047107 -0.032937035 0.22034234, -0.10336982 -0.032983914 0.21678527, -0.098025069 -0.032996014 0.22037977, -0.097989216 -0.033069804 0.22044712, -0.1034005 -0.03309302 0.21683121, -0.097942084 -0.03314285 0.22054252, -0.10344514 -0.033185259 0.2168974, -0.097905859 -0.033186749 0.22061867, -0.097868457 -0.033223733 0.22069982, -0.10350086 -0.033255562 0.21698062, -0.097872481 -0.033267215 0.2207852, -0.1035644 -0.033299819 0.21707515, -0.097862184 -0.033298269 0.22088991, -0.097845718 -0.033310309 0.22097427, -0.10363205 -0.033314541 0.21717589, -0.097819731 -0.03331472 0.22107905, -0.13085972 -0.032934308 0.14021909, -0.13614035 -0.032966971 0.13666511, -0.13085885 -0.03297165 0.14021063, -0.13085516 -0.03300713 0.14021039, -0.13613939 -0.033040285 0.13666379, -0.13084814 -0.033043742 0.14021729, -0.13083802 -0.033080816 0.14023185, -0.13614833 -0.033111811 0.13667703, -0.13082469 -0.033117294 0.14025448, -0.13080835 -0.033152357 0.14028488, -0.13616684 -0.033177271 0.13670456, -0.13078256 -0.033195406 0.14033592, -0.13619368 -0.033232674 0.13674445, -0.13074954 -0.033236727 0.14040518, -0.13622712 -0.0332748 0.13679422, -0.13070212 -0.033277392 0.14050972, -0.1306711 -0.033294961 0.14058098, -0.13626526 -0.03330119 0.13685106, -0.13630567 -0.033310086 0.13691141, -0.12720828 -0.033321664 0.14912036, -0.12717009 -0.033334762 0.14911887, -0.12724762 -0.033313558 0.14912155, -0.12728323 -0.033310786 0.14918649, -0.12727301 -0.033310875 0.14924905, -0.12719294 -0.033315867 0.1493258, -0.12724321 -0.033310875 0.14934644, -0.12714435 -0.0333305 0.14930591, -0.12709904 -0.033354416 0.14928734, -0.12568979 -0.03331098 0.15313967, -0.12563942 -0.033316076 0.15311904, -0.12559083 -0.033330783 0.15309899, -0.12554544 -0.033354744 0.15308063, -0.12560587 -0.033306211 0.1532789, -0.12549533 -0.03325513 0.15355302, -0.12552656 -0.033264354 0.1535037, -0.12552874 -0.033248961 0.1535385, -0.12551828 -0.033302665 0.15338264, -0.12555109 -0.03329201 0.15339758, -0.12548231 -0.03331618 0.15338032, -0.12550248 -0.033290178 0.15344693, -0.12553199 -0.033277616 0.15346222, -0.12544821 -0.033334225 0.1533791, -0.12547018 -0.033302069 0.15344982, -0.12549688 -0.033273786 0.15350316, -0.12543941 -0.033317462 0.15345369, -0.12546816 -0.033283591 0.15351085, -0.12546372 -0.033265144 0.15356947, -0.12544051 -0.033296108 0.15351979, -0.12393396 -0.033321992 0.15711538, -0.12389593 -0.033335343 0.15711384, -0.12397343 -0.033314064 0.15711671, -0.124009 -0.033311322 0.15718175, -0.12399878 -0.033311233 0.15724425, -0.12391873 -0.03331621 0.15732093, -0.12396903 -0.033311307 0.15734152, -0.12387006 -0.033330932 0.15730099, -0.12382476 -0.033354938 0.15728232, -0.12241547 -0.033311501 0.16113465, -0.12236525 -0.033316359 0.16111426, -0.12231676 -0.033331051 0.16109435, -0.12227139 -0.033355072 0.16107573, -0.12233169 -0.033306763 0.16127391, -0.12222119 -0.033255503 0.16154821, -0.12225224 -0.033264622 0.16149859, -0.12225449 -0.033249393 0.16153362, -0.12224405 -0.033303037 0.16137771, -0.12227678 -0.033292383 0.1613926, -0.12220815 -0.033316582 0.16137536, -0.12222835 -0.033290431 0.16144213, -0.12225775 -0.033278003 0.16145723, -0.12217407 -0.033334628 0.16137414, -0.12219593 -0.033302471 0.16144487, -0.12222268 -0.033274159 0.16149811, -0.12216522 -0.033318013 0.16144876, -0.12219383 -0.033283934 0.16150598, -0.12218957 -0.033265486 0.16156442, -0.12216638 -0.033296511 0.16151492, -0.12065963 -0.033322528 0.16511048, -0.12062173 -0.03333582 0.16510923, -0.12069918 -0.033314452 0.16511181, -0.12073462 -0.03331174 0.16517682, -0.12072445 -0.03331171 0.16523948, -0.12064438 -0.033316717 0.165316, -0.12069476 -0.033311784 0.16533658, -0.12059578 -0.033331394 0.16529638, -0.12055044 -0.03335534 0.16527751, -0.11914125 -0.033311933 0.16912974, -0.11909094 -0.03331694 0.16910924, -0.11904243 -0.033331588 0.16908932, -0.11899707 -0.033355564 0.1690708, -0.1190574 -0.03330718 0.169269, -0.11894694 -0.033255905 0.16954328, -0.11897805 -0.033265084 0.16949381, -0.11898021 -0.033249795 0.16952887, -0.11896971 -0.033303589 0.16937281, -0.11900255 -0.033292919 0.16938771, -0.11893383 -0.033317059 0.16937043, -0.11895412 -0.033291042 0.16943716, -0.11898352 -0.033278435 0.16945246, -0.11889973 -0.03333506 0.16936935, -0.11892179 -0.033302933 0.16943994, -0.11894837 -0.033274621 0.16949321, -0.11889087 -0.033318445 0.16944394, -0.11891957 -0.033284277 0.16950113, -0.11891529 -0.033265918 0.16955967, -0.1188921 -0.033297047 0.16950995, -0.11738555 -0.033322901 0.17310549, -0.11734752 -0.033336237 0.17310417, -0.11742489 -0.033314794 0.17310704, -0.11746056 -0.033312142 0.17317186, -0.11745034 -0.033312157 0.17323466, -0.11737029 -0.033317178 0.17331113, -0.11742048 -0.033312172 0.17333175, -0.11732164 -0.033331826 0.17329137, -0.11727634 -0.033355847 0.17327279, -0.11586706 -0.033312395 0.1771249, -0.11581683 -0.033317298 0.17710426, -0.11576831 -0.03333196 0.17708448, -0.11572297 -0.033355981 0.17706594, -0.11578314 -0.033307642 0.17726417, -0.11567254 -0.033256352 0.1775385, -0.11570404 -0.033265486 0.17748903, -0.11570606 -0.033250213 0.17752388, -0.11569561 -0.033303931 0.17736782, -0.11572847 -0.033293203 0.17738277, -0.1156597 -0.033317477 0.1773655, -0.11567988 -0.033291414 0.17743231, -0.11570935 -0.033278778 0.1774476, -0.11562563 -0.033335507 0.1773645, -0.11564757 -0.03330344 0.17743519, -0.11567411 -0.033275098 0.17748839, -0.11561669 -0.033318833 0.17743899, -0.1156455 -0.033284739 0.17749625, -0.11564101 -0.03326638 0.17755486, -0.11561789 -0.033297479 0.17750517, -0.11083709 -0.03332372 0.18909585, -0.11079906 -0.033336952 0.18909466, -0.11087649 -0.033315703 0.18909732, -0.110912 -0.033313021 0.18916221, -0.11090177 -0.033312991 0.18922488, -0.11082172 -0.033317938 0.18930139, -0.11087209 -0.03331311 0.18932201, -0.11077328 -0.03333278 0.18928151, -0.11072795 -0.033356592 0.1892629, -0.10931855 -0.033313289 0.19311526, -0.10926826 -0.033318236 0.19309448, -0.10921963 -0.033333048 0.19307487, -0.10917434 -0.03335689 0.19305623, -0.10923456 -0.033308491 0.1932545, -0.1091242 -0.033257291 0.19352904, -0.10915536 -0.03326644 0.19347936, -0.10915749 -0.033251211 0.19351414, -0.10914701 -0.033304825 0.19335821, -0.10917981 -0.033294186 0.19337313, -0.10911106 -0.033318415 0.19335569, -0.10913129 -0.033292279 0.19342236, -0.10916087 -0.033279702 0.1934379, -0.10907707 -0.033336326 0.19335471, -0.10909896 -0.033304289 0.19342525, -0.10912575 -0.033275947 0.19347869, -0.1090682 -0.033319756 0.19342926, -0.10909681 -0.033285782 0.1934866, -0.10909252 -0.033267304 0.19354513, -0.10906927 -0.033298358 0.19349535, -0.1076059 -0.033295795 0.19690272, -0.10762976 -0.033293739 0.1969021, -0.10761963 -0.033309206 0.19698921, -0.10752465 -0.033337459 0.19708942, -0.10756271 -0.033324108 0.19709094, -0.10760222 -0.033316061 0.19709219, -0.10763763 -0.033313528 0.1971572, -0.10762741 -0.033313617 0.19721983, -0.10754746 -0.033318445 0.1972965, -0.10759778 -0.033313528 0.19731699, -0.10749896 -0.033333197 0.1972767, -0.10745361 -0.033357039 0.19725809, -0.10604428 -0.033313558 0.20111027, -0.10599409 -0.033318475 0.20108978, -0.10594548 -0.033333227 0.20106986, -0.10590014 -0.033357099 0.20105138, -0.1059604 -0.0333087 0.20124963, -0.10584989 -0.033257559 0.20152405, -0.10588118 -0.033266857 0.20147434, -0.10588321 -0.033251598 0.20150927, -0.10587287 -0.033305243 0.20135331, -0.10590565 -0.033294395 0.20136833, -0.10583696 -0.033318654 0.20135085, -0.1058571 -0.033292666 0.20141788, -0.10588655 -0.03328003 0.20143317, -0.10580288 -0.033336684 0.20134977, -0.10582487 -0.033304617 0.20142065, -0.10585156 -0.033276185 0.20147374, -0.10579406 -0.033320114 0.20142427, -0.10582252 -0.03328605 0.20148158, -0.10581839 -0.033267602 0.20154017, -0.10579506 -0.033298805 0.20149043, -0.10433172 -0.033296153 0.20489788, -0.10435565 -0.033294156 0.20489711, -0.10434544 -0.033309624 0.20498434, -0.10425042 -0.033337906 0.20508471, -0.10428855 -0.033324555 0.20508623, -0.10432795 -0.033316448 0.20508754, -0.1043635 -0.033313796 0.20515235, -0.10435317 -0.033313796 0.20521498, -0.10427332 -0.033318803 0.20529173, -0.10432349 -0.033313707 0.20531216, -0.10422476 -0.033333436 0.20527181, -0.10417932 -0.033357427 0.20525308, -0.10277003 -0.033314005 0.20910549, -0.10271978 -0.033318982 0.2090849, -0.10267116 -0.033333734 0.20906492, -0.10262582 -0.033357665 0.20904645, -0.10268611 -0.033309266 0.20924476, -0.10257564 -0.033258125 0.20951913, -0.10260676 -0.033267185 0.20946957, -0.10260892 -0.033251897 0.20950437, -0.10259853 -0.03330569 0.20934846, -0.10263142 -0.033294931 0.2093634, -0.10256265 -0.03331916 0.20934607, -0.10258268 -0.033293054 0.2094128, -0.1026123 -0.033280477 0.2094283, -0.10252866 -0.033337131 0.2093448, -0.10255051 -0.033305034 0.2094157, -0.10257716 -0.033276752 0.20946895, -0.10251969 -0.033320472 0.20941952, -0.10254826 -0.033286408 0.20947666, -0.10254405 -0.03326802 0.20953526, -0.10252079 -0.033299133 0.20948562, -0.097783193 -0.033297226 0.22088821, -0.097807154 -0.033294991 0.2208876, -0.097796962 -0.033310637 0.22097448, -0.097701937 -0.033338711 0.22107498, -0.097740084 -0.033325478 0.22107644, -0.097779468 -0.033317462 0.22107762, -0.097814932 -0.03331466 0.22114259, -0.097804785 -0.03331472 0.22120523, -0.097724751 -0.033319697 0.22128186, -0.097774968 -0.03331472 0.22130246, -0.097676188 -0.0333343 0.22126202, -0.097630769 -0.03335838 0.22124346, -0.097184762 -0.033314899 0.22274393, -0.097134456 -0.033319786 0.22272331, -0.097085848 -0.033334568 0.2227034, -0.097040519 -0.033358529 0.2226848, -0.097127959 -0.03331019 0.22287947, -0.096992597 -0.033067897 0.22376412, -0.097051859 -0.033058181 0.22373867, -0.097035676 -0.033301994 0.22300486, -0.097085148 -0.033296391 0.22301535, -0.097047076 -0.033253625 0.22323495, -0.096987337 -0.033316478 0.22299582, -0.096941754 -0.033338889 0.22298852, -0.096997991 -0.033258155 0.22323245, -0.096950009 -0.033270851 0.22323233, -0.096904248 -0.033291385 0.22323427, -0.097002402 -0.033179596 0.22347778, -0.097051844 -0.033177748 0.22347172, -0.097114056 -0.033060834 0.22371945, -0.096954271 -0.033189401 0.22348693, -0.096908614 -0.033206567 0.22349873, -0.10101433 -0.033324942 0.21308123, -0.10097611 -0.033338323 0.2130799, -0.10105371 -0.033316985 0.21308252, -0.10108919 -0.033314303 0.21314763, -0.10107909 -0.033314243 0.21321006, -0.100999 -0.03331919 0.21328676, -0.10104917 -0.033314332 0.2133074, -0.10095049 -0.033333763 0.21326701, -0.10090518 -0.033357933 0.21324837, -0.099495828 -0.033314481 0.21710059, -0.099445656 -0.033319429 0.21707995, -0.099396989 -0.033334091 0.21706019, -0.099351689 -0.033358112 0.21704154, -0.09941189 -0.033309713 0.21723978, -0.099301502 -0.033258513 0.21751426, -0.099332705 -0.033267602 0.21746461, -0.099334687 -0.033252433 0.21749964, -0.099324465 -0.033306018 0.21734355, -0.099357173 -0.033295408 0.2173584, -0.099288464 -0.033319697 0.21734127, -0.09930867 -0.03329353 0.21740806, -0.099338099 -0.033281103 0.21742325, -0.099254325 -0.033337578 0.21733977, -0.09927623 -0.033305481 0.21741082, -0.099303067 -0.033277228 0.21746403, -0.099245548 -0.033320978 0.21741474, -0.099274084 -0.033287063 0.21747176, -0.099269897 -0.033268467 0.21753034, -0.099246666 -0.03329958 0.2174807, -0.096167997 0.084623888 0.26647016, -0.091044307 0.083244428 0.26922885, -0.091045827 0.083310589 0.26924309, -0.096161082 0.084687725 0.26648921, -0.090265825 0.082407936 0.27090091, -0.095404774 0.083824828 0.26816055, -0.090248048 0.082459018 0.27095795, -0.095423684 0.083905503 0.26823616, -0.090214327 0.082512483 0.27105504, -0.095454365 0.083967879 0.26832435, -0.090159208 0.082550898 0.27120012, -0.095495313 0.084008649 0.26842058, -0.095544174 0.084025756 0.26851997, -0.090068325 0.082553163 0.27142262, -0.095598862 0.084018454 0.26861781, -0.089948848 0.082486138 0.27169615, -0.089962438 0.082479224 0.27171767, -0.089975953 0.082470939 0.27173901, -0.099055201 0.087725237 0.26026851, -0.093931451 0.086345658 0.26302701, -0.093932942 0.086411819 0.2630412, -0.099048346 0.087789014 0.26028752, -0.093152955 0.085509136 0.26469907, -0.098291963 0.086925939 0.26195878, -0.093135312 0.085560337 0.26475641, -0.098310918 0.087006763 0.26203445, -0.093101457 0.085613683 0.26485348, -0.098341554 0.08706902 0.26212287, -0.093046293 0.085652098 0.26499844, -0.098382413 0.087109759 0.26221892, -0.098431438 0.087126926 0.26231852, -0.092955545 0.085654333 0.26522109, -0.098485917 0.087119624 0.26241612, -0.092835978 0.085587218 0.26549459, -0.092849568 0.085580304 0.26551625, -0.092863157 0.08557196 0.26553735, -0.10194241 0.090826556 0.25406703, -0.096818537 0.089446858 0.25682542, -0.096820086 0.089513078 0.25683969, -0.10193545 0.090890124 0.25408587, -0.0960401 0.088610366 0.25849757, -0.10117905 0.090027288 0.25575727, -0.096022338 0.088661507 0.25855488, -0.10119803 0.090108082 0.25583303, -0.095988601 0.088714913 0.25865179, -0.10122874 0.09017019 0.25592107, -0.095933601 0.088753447 0.25879699, -0.10126956 0.090210959 0.25601721, -0.10131854 0.090228364 0.25611675, -0.095842719 0.088755623 0.25901955, -0.10137315 0.090220854 0.25621462, -0.095723197 0.088688657 0.25929284, -0.095736712 0.088681534 0.25931472, -0.095750421 0.088673517 0.25933582, -0.10482959 0.093927637 0.24786533, -0.099705786 0.092548057 0.25062382, -0.09970741 0.092614308 0.25063813, -0.10482255 0.093991354 0.24788406, -0.098927334 0.091711387 0.25229585, -0.1040663 0.093128428 0.24955575, -0.098909616 0.091762707 0.25235328, -0.10408524 0.093209103 0.24963132, -0.098875836 0.091815934 0.25245023, -0.10411592 0.093271568 0.2497196, -0.098820686 0.091854587 0.25259531, -0.10415675 0.093312159 0.24981557, -0.10420568 0.093329266 0.24991505, -0.098729849 0.091856733 0.25281775, -0.10426034 0.093322054 0.25001287, -0.098610327 0.091789678 0.25309131, -0.098623842 0.091782823 0.25311297, -0.098637566 0.091774479 0.25313419, -0.10771683 0.097028971 0.24166374, -0.10259293 0.095649377 0.244422, -0.10259444 0.095715389 0.24443644, -0.10770987 0.097092569 0.24168265, -0.10181442 0.094812825 0.24609438, -0.10695358 0.096229702 0.24335405, -0.10179679 0.094863907 0.24615179, -0.10697249 0.096310407 0.24342985, -0.101763 0.094917133 0.24624862, -0.10700314 0.096372843 0.24351791, -0.10170798 0.094955876 0.24639361, -0.10704391 0.096413493 0.24361411, -0.10709286 0.096430719 0.2437136, -0.10161702 0.094958022 0.24661632, -0.10714754 0.096423119 0.24381132, -0.10149758 0.094890967 0.24688973, -0.10151106 0.094884023 0.24691147, -0.10152474 0.094875768 0.24693242, -0.1163784 0.10633259 0.223059, -0.11125448 0.10495289 0.22581747, -0.11125603 0.10501926 0.22583193, -0.11637144 0.10639623 0.22307774, -0.11047605 0.10411651 0.22748956, -0.1156151 0.10553342 0.22474925, -0.11045824 0.10416766 0.22754689, -0.11563389 0.10561419 0.22482485, -0.11042464 0.10422094 0.22764388, -0.11566469 0.10567644 0.22491308, -0.11036944 0.10425948 0.22778875, -0.11570558 0.10571712 0.22500913, -0.11575454 0.10573423 0.22510861, -0.11027844 0.10426162 0.22801127, -0.11580899 0.10572699 0.22520651, -0.11015902 0.10419454 0.22828482, -0.1101726 0.10418768 0.22830668, -0.1101862 0.10417934 0.22832771, -0.11336322 0.10721768 0.22128792, -0.11850224 0.10863441 0.21854749, -0.11334543 0.10726872 0.22134504, -0.11852121 0.10871527 0.21862318, -0.11331174 0.10732214 0.22144204, -0.11855185 0.10877761 0.21871139, -0.1132566 0.10736081 0.22158737, -0.11859272 0.10881847 0.21880773, -0.11864172 0.10883558 0.21890706, -0.11316571 0.10736291 0.2218098, -0.1186962 0.10882813 0.21900478, -0.11304626 0.10729589 0.2220833, -0.11305986 0.10728902 0.222105, -0.11307345 0.10728079 0.22212633, -0.10727187 0.10109344 0.23448664, -0.10728547 0.1010865 0.23450814, -0.10729912 0.10107821 0.23452936, -0.10758884 0.10101531 0.23369114, -0.11272782 0.10243218 0.23095083, -0.10757111 0.10106631 0.23374848, -0.11274686 0.10251285 0.2310265, -0.10753734 0.10111979 0.23384553, -0.11277744 0.10257511 0.23111457, -0.1074823 0.10115841 0.23399055, -0.1128182 0.10261591 0.23121096, -0.10739146 0.10116038 0.23421291, -0.11286721 0.10263304 0.23131043, -0.11292186 0.10262574 0.23140833, -0.11349121 0.10323144 0.22926053, -0.10836743 0.10185176 0.23201904, -0.10836886 0.1019178 0.23203343, -0.11348413 0.10329503 0.22927934, -0.14622873 -0.022896349 0.14045143, -0.14635669 -0.022679389 0.1403572, -0.14630871 -0.022914916 0.14043096, -0.14641038 -0.022670165 0.14034313, -0.14635599 -0.022672728 0.14034575, -0.14628592 -0.022680506 0.14038059, -0.14626455 -0.022673011 0.14037791, -0.1462654 -0.022678435 0.14038858, -0.14617799 -0.022651106 0.14041752, -0.14615488 -0.022875771 0.14048865, -0.14617932 -0.022656202 0.14042798, -0.14616777 -0.022651136 0.14043435, -0.14610358 -0.022609621 0.14046076, -0.14663425 -0.022536412 0.14032501, -0.14658262 -0.022572815 0.14030668, -0.14663078 -0.022525847 0.14030883, -0.14609195 -0.022854343 0.14054024, -0.14610583 -0.022614717 0.14047199, -0.14607443 -0.022587359 0.14049563, -0.14604619 -0.022553772 0.14050412, -0.1460495 -0.02255927 0.14051667, -0.14600395 -0.022482932 0.14054781, -0.14601249 -0.02256912 0.14067781, -0.14601365 -0.022677392 0.14068164, -0.14599261 -0.022422984 0.14062285, -0.14600845 -0.022489429 0.1405628, -0.14599769 -0.022439942 0.14063725, -0.14600158 -0.022457942 0.14064828, -0.14600611 -0.022486433 0.14066055, -0.14598696 -0.022410512 0.14060652, -0.14598115 -0.022402674 0.14058867, -0.14598709 -0.022410512 0.14060658, -0.14648987 -0.022945181 0.14044726, -0.14639781 -0.022931874 0.14042836, -0.14655498 -0.022803798 0.14042896, -0.14604333 -0.02283369 0.14060161, -0.14602372 -0.022823408 0.14063644, -0.14600821 -0.022813827 0.14067212, -0.14661102 -0.022657841 0.14039445, -0.1465852 -0.022584081 0.14032352, -0.14663132 -0.022581488 0.14036146, -0.14663497 -0.022551209 0.14034027, -0.14653327 -0.022620022 0.14032456, -0.14652273 -0.022615373 0.14031044, -0.14652456 -0.022625029 0.1403254, -0.1464442 -0.022652134 0.14032307, -0.1464451 -0.022660136 0.14033598, -0.14630295 -0.023346007 0.14046785, -0.14620958 -0.023335516 0.14047903, -0.14612165 -0.023325667 0.14051196, -0.14604369 -0.023316994 0.14056462, -0.14598024 -0.023309872 0.14063418, -0.14593469 -0.02330476 0.14071697, -0.14643601 -0.022654518 0.14029917, -0.14634457 -0.022678629 0.14033228, -0.14641881 -0.022666872 0.14028403, -0.14633515 -0.022687778 0.14032194, -0.14644688 -0.022648543 0.14030895, -0.14635089 -0.02267383 0.14033851, -0.14632672 -0.022695526 0.1403109, -0.1462564 -0.022688299 0.14035347, -0.1462418 -0.022694647 0.14034685, -0.14656138 -0.022557601 0.1401972, -0.14647615 -0.022642136 0.14021912, -0.14653267 -0.022590339 0.14016768, -0.14635494 -0.02267243 0.14034361, -0.1462599 -0.02267909 0.14036408, -0.1462622 -0.022674337 0.14037079, -0.14617829 -0.022670835 0.14038241, -0.14615589 -0.022673845 0.14037281, -0.14626399 -0.022672668 0.14037591, -0.14662626 -0.022520289 0.14029488, -0.14617778 -0.022659123 0.140398, -0.14662011 -0.02251783 0.1402804, -0.14661279 -0.022518292 0.14026597, -0.14660528 -0.022521168 0.14025337, -0.14617719 -0.022652924 0.14040789, -0.14610495 -0.02263695 0.14040598, -0.14607359 -0.022635162 0.14038786, -0.1461774 -0.022650629 0.14041501, -0.14610364 -0.022620276 0.14043015, -0.14610229 -0.022611678 0.14044541, -0.14604042 -0.022589713 0.14042288, -0.14599884 -0.022580937 0.14039123, -0.14610267 -0.022608742 0.14045671, -0.14604171 -0.022566944 0.1404573, -0.14604236 -0.022555768 0.14048013, -0.14604442 -0.022552371 0.14049709, -0.1459671 -0.022507831 0.1404303, -0.14595842 -0.02254121 0.1403878, -0.14592351 -0.022497207 0.1403797, -0.14594413 -0.022430688 0.14046517, -0.1459759 -0.022475213 0.14047906, -0.14595862 -0.022405624 0.14051715, -0.14598334 -0.022460595 0.14051482, -0.14596897 -0.022398666 0.14055103, -0.14597525 -0.022398978 0.14057043, -0.14659299 -0.022528708 0.14023551, -0.14649683 -0.022622332 0.14024068, -0.1465214 -0.022602707 0.14026418, -0.14653701 -0.022594556 0.14028241, -0.14640617 -0.022677645 0.14026764, -0.14645374 -0.022647142 0.14031711, -0.095205471 -0.033581004 0.22588244, -0.090394482 0.0049588233 0.24817441, -0.090512753 0.0047918111 0.24807774, -0.090671599 0.0046520978 0.24799688, -0.098648593 -0.01123406 0.2388082, -0.098720729 -0.01148738 0.23866186, -0.10990608 -0.033581153 0.22588255, -0.099590272 -0.012154266 0.238276, -0.099308565 -0.012061939 0.23832943, -0.099060476 -0.011913702 0.23841524, -0.098860726 -0.011718437 0.23852803, -0.099590257 -0.010053113 0.23949136, -0.10515749 0.0044591874 0.24788542, -0.098860666 -0.010489032 0.23923932, -0.09130089 0.0044592768 0.24788532, -0.099060491 -0.010293826 0.23935212, -0.099308506 -0.010145709 0.23943785, -0.098720714 -0.01071997 0.23910557, -0.091075912 0.0044814199 0.2478981, -0.098648623 -0.0109732 0.23895921, -0.090862468 0.0045467764 0.24793586, -0.091300875 0.0061902851 0.24888681, -0.099354997 0.05094333 0.27477217, -0.10494147 0.0061904043 0.24888664, -0.091077775 0.00616844 0.24887398, -0.085498318 0.050943479 0.27477211, -0.090866029 0.0061042458 0.2488368, -0.085273281 0.050965562 0.27478492, -0.090676129 0.0060007125 0.24877697, -0.085059866 0.051031068 0.27482271, -0.09051764 0.0058630258 0.24869725, -0.084868848 0.051136151 0.27488372, -0.090325147 0.005514577 0.24849571, -0.084592089 0.051443234 0.27506122, -0.09039861 0.0056981891 0.24860179, -0.084710255 0.051276013 0.27496451, -0.093868554 0.083407268 0.28257155, -0.093868554 0.081892595 0.28181398, -0.093507916 0.083468452 0.28244919, -0.093507856 0.081953838 0.28169149, -0.093190521 0.083566502 0.28225318, -0.093190521 0.082051829 0.28149584, -0.092934668 0.083695516 0.28199494, -0.092934728 0.082180962 0.28123766, -0.092755586 0.083848491 0.28168958, -0.092755377 0.082333729 0.28093201, -0.092663199 0.08401598 0.28135461, -0.092663109 0.082501218 0.28059691, -0.092663258 0.084188655 0.28100958, -0.092663169 0.082673773 0.28025204, -0.092755586 0.084355965 0.28067452, -0.092755467 0.082841292 0.27991718, -0.092934787 0.084508821 0.28036904, -0.092934817 0.08299394 0.27961174, -0.093190491 0.084637925 0.28011078, -0.093190461 0.083123133 0.27935326, -0.093507975 0.084736004 0.27991498, -0.093507931 0.083221152 0.27915734, -0.093868554 0.084797069 0.27979261, -0.093868494 0.083282366 0.27903515, -0.12509792 0.11543718 0.21473391, -0.1250979 0.11695203 0.21549138, -0.12473728 0.11549842 0.21461128, -0.12473732 0.11701314 0.21536909, -0.12441994 0.11559641 0.21441548, -0.12441985 0.11711112 0.21517308, -0.124164 0.11572553 0.21415743, -0.12416404 0.11724024 0.21491475, -0.12398484 0.11587834 0.21385178, -0.12398487 0.11739291 0.21460928, -0.12389258 0.11604597 0.21351688, -0.12389256 0.11756054 0.21427454, -0.12389249 0.11621834 0.21317185, -0.12389244 0.11773315 0.21392931, -0.12398478 0.11638594 0.21283686, -0.12398478 0.11790061 0.21359432, -0.12416404 0.11653866 0.21253143, -0.12416402 0.11805335 0.21328881, -0.12441987 0.11666776 0.21227325, -0.12441987 0.11818255 0.21303065, -0.12473732 0.11676581 0.21207727, -0.12473732 0.11828054 0.21283473, -0.12509792 0.11682689 0.211955, -0.12509793 0.1183417 0.21271248, -0.10028367 0.078462169 0.27857095, -0.097442642 0.076842144 0.27763408, -0.093003228 0.076740965 0.27757549, -0.093005255 0.077187464 0.27783394, -0.097208917 0.07676886 0.27759171, -0.11420552 -0.033064649 0.2140633, -0.097073168 0.07674785 0.27757955, -0.10536674 -0.033064589 0.21406332, -0.096937656 0.076741084 0.27757561, -0.092439294 0.076740965 0.27757549, -0.092156202 0.076771125 0.2775929, -0.091886088 0.076861039 0.2776449, -0.09176521 0.076925948 0.27768263, -0.091624051 0.077028468 0.27774179, -0.091657639 0.077001706 0.27772626, -0.09935455 0.079288587 0.2731927, -0.099505246 0.079427287 0.27327299, -0.10272041 0.080786243 0.27405915, -0.11686973 -0.032563731 0.20849684, -0.099163935 0.079176918 0.27312812, -0.10770248 -0.032563731 0.20849666, -0.098905802 0.079092786 0.27307951, -0.10068178 0.080786094 0.2740593, -0.098635286 0.079065099 0.2730636, -0.094136983 0.07906507 0.27306363, -0.094031125 0.079069242 0.27306566, -0.093925714 0.079081878 0.2730732, -0.093761444 0.079118565 0.27309436, -0.1041811 0.0052633137 0.25048953, -0.09859477 0.050016388 0.27637503, -0.095296338 0.076554492 0.29168981, -0.095296264 0.076469705 0.2916671, -0.095302492 0.076390877 0.29163039, -0.096577749 0.073191717 0.28764081, -0.098378628 0.051747605 0.27737641, -0.099138826 0.052674577 0.27577358, -0.096539453 0.073686764 0.28786978, -0.096544862 0.074249312 0.28801101, -0.096600831 0.074854657 0.28803957, -0.096709371 0.075467899 0.28794214, -0.096865624 0.07604976 0.2877197, -0.097058609 0.076564237 0.28738916, -0.09727402 0.076986179 0.28697866, -0.097417697 0.077203467 0.28668737, -0.097560629 0.077376798 0.28638554, -0.10776357 0.090297207 0.26500678, -0.1079289 0.088513836 0.26411492, -0.12650108 0.11042407 0.22475852, -0.10859634 0.091191873 0.26321793, -0.1087617 0.089408174 0.26232618, -0.12666644 0.10864049 0.22386692, -0.13483122 0.11937176 0.20686591, -0.127334 0.11131845 0.22296995, -0.12749931 0.10953505 0.22207804, -0.13497202 0.11756177 0.20602652, -0.15395617 -0.023775235 0.13646761, -0.15457796 -0.022610217 0.13646768, -0.15431264 -0.023910254 0.13646764, -0.15357791 -0.023729235 0.13646768, -0.15495609 -0.022652775 0.1364678, -0.1560601 -0.027707368 0.13646758, -0.15594816 -0.027794033 0.13646753, -0.15615234 -0.027599901 0.13646758, -0.15626356 -0.027340919 0.13646767, -0.15622109 -0.027476132 0.13646758, -0.14726472 -0.028780088 0.1364677, -0.14757738 -0.033010274 0.13646758, -0.15119955 -0.026845291 0.1364677, -0.15084311 -0.026710019 0.13646774, -0.15627784 -0.027200043 0.13646758, -0.15027669 -0.026208237 0.13646775, -0.14725992 -0.028340593 0.13646775, -0.15009975 -0.025870845 0.13646781, -0.15052947 -0.02649352 0.1364677, -0.15462628 -0.026493594 0.13646775, -0.15487897 -0.026208311 0.1364677, -0.15431261 -0.026710108 0.13646775, -0.15505606 -0.02587074 0.13646781, -0.15157786 -0.02372922 0.13646773, -0.15395617 -0.026845232 0.13646773, -0.15514731 -0.025500774 0.13646773, -0.15627789 -0.024310231 0.13646761, -0.15357789 -0.026891172 0.13646768, -0.15514724 -0.025119618 0.1364677, -0.1490013 -0.022610143 0.13646777, -0.15119939 -0.023775145 0.13646765, -0.15084317 -0.023910239 0.13646764, -0.15052953 -0.024126902 0.13646765, -0.15027684 -0.024412021 0.13646778, -0.15009961 -0.024749592 0.13646781, -0.15505613 -0.024749547 0.13646777, -0.14658768 -0.033010259 0.13646756, -0.14662392 -0.032686099 0.13646767, -0.14862789 -0.022651717 0.13646784, -0.15000831 -0.025500759 0.13646786, -0.14676334 -0.024363205 0.13646773, -0.15000844 -0.025119662 0.1364678, -0.15623517 -0.023931906 0.13646773, -0.15487891 -0.024412081 0.13646761, -0.15610944 -0.023572594 0.13646768, -0.14827253 -0.022774264 0.13646784, -0.14795294 -0.022971824 0.13646778, -0.14768457 -0.023235038 0.13646774, -0.15590696 -0.023250297 0.1364677, -0.15462628 -0.024126813 0.13646775, -0.15563798 -0.022981122 0.13646787, -0.15157789 -0.026891187 0.13646759, -0.15531543 -0.022778675 0.13646775, -0.12173797 -0.033312157 0.17365469, -0.12407373 -0.033311948 0.16895398, -0.10731407 -0.033313915 0.20605412, -0.13324067 -0.033312127 0.16895379, -0.13792223 -0.033311397 0.15829185, -0.140137 -0.033311099 0.15288593, -0.14030378 -0.033311099 0.15278687, -0.11346486 -0.033315018 0.22274402, -0.11410992 -0.033314511 0.21674788, -0.1142579 -0.033314481 0.21661365, -0.1378164 -0.033311397 0.15806323, -0.11437894 -0.033314541 0.21645327, -0.11394303 -0.033314511 0.21684682, -0.11446849 -0.033314541 0.21627808, -0.11376797 -0.033314481 0.21690574, -0.10773547 -0.033314005 0.20582449, -0.14057302 -0.03331098 0.15249224, -0.14066242 -0.033311099 0.15231676, -0.13788576 -0.033311605 0.15909712, -0.13996212 -0.033311099 0.15294482, -0.11359535 -0.033314601 0.2169247, -0.11496609 -0.033314511 0.21506301, -0.13978939 -0.033311099 0.15296365, -0.13768186 -0.033311442 0.15789594, -0.13754047 -0.033311322 0.15778424, -0.13741533 -0.033311427 0.15772052, -0.12353033 -0.033311903 0.16906753, -0.12380025 -0.033311918 0.16898213, -0.12128203 -0.033312172 0.17370209, -0.12814921 -0.033312604 0.1825293, -0.13062891 -0.03331244 0.17663801, -0.12813908 -0.033312798 0.18280783, -0.13048102 -0.033312425 0.17677222, -0.12809941 -0.033312574 0.18227708, -0.11505321 -0.033314392 0.2145239, -0.11753213 -0.033314183 0.20861852, -0.11504078 -0.033314571 0.21479699, -0.13075012 -0.0333125 0.17647766, -0.12806298 -0.033312723 0.18308264, -0.11191531 -0.033313468 0.19764024, -0.114251 -0.033313289 0.19293922, -0.11738405 -0.033314213 0.20875256, -0.11500688 -0.033314541 0.21427201, -0.12041101 -0.033312306 0.17407361, -0.12341811 -0.033313304 0.19293934, -0.1303142 -0.03331244 0.17687118, -0.11765333 -0.033314124 0.20845801, -0.12799376 -0.033312663 0.18204871, -0.11721738 -0.033314064 0.2088517, -0.11490318 -0.033314362 0.21403992, -0.1308396 -0.033312351 0.17630216, -0.11774284 -0.033314064 0.20828281, -0.1301392 -0.03331244 0.17693007, -0.11704233 -0.033314213 0.20891033, -0.12083234 -0.033312157 0.17384411, -0.1168696 -0.033314094 0.2089294, -0.1147677 -0.033314481 0.21386725, -0.1146224 -0.033314422 0.21375124, -0.11446609 -0.033314392 0.21367544, -0.1143335 -0.033314392 0.21364097, -0.11420539 -0.033314362 0.21363038, -0.12996659 -0.03331244 0.1769489, -0.12785935 -0.033312678 0.18188149, -0.12771772 -0.033312693 0.18176976, -0.11824025 -0.033314154 0.20706764, -0.12759252 -0.033312693 0.1817058, -0.11370769 -0.03331323 0.19305278, -0.11397746 -0.03331323 0.19296731, -0.11145942 -0.033313528 0.19768748, -0.14124632 -0.033311084 0.15054899, -0.14372604 -0.033310667 0.14465757, -0.14123625 -0.033310965 0.15082705, -0.14119639 -0.033310875 0.15029646, -0.14357795 -0.033310711 0.14479183, -0.11058825 -0.033313408 0.1980591, -0.14384712 -0.033310771 0.14449723, -0.12501222 -0.03331168 0.16565968, -0.12734798 -0.033311501 0.16095878, -0.11832644 -0.033314094 0.20651457, -0.1208062 -0.033313677 0.20062344, -0.11831644 -0.033314094 0.2067932, -0.13651513 -0.033311605 0.16095868, -0.14109054 -0.033310756 0.15006807, -0.14341117 -0.033310577 0.14489065, -0.12065825 -0.033313707 0.20075744, -0.11827669 -0.033314094 0.20626254, -0.12092756 -0.033313617 0.20046292, -0.11100958 -0.033313438 0.19782943, -0.14323625 -0.033310786 0.14494962, -0.10442831 -0.033314481 0.21692471, -0.12049155 -0.033313736 0.2008566, -0.11817102 -0.033313945 0.20603406, -0.1409563 -0.03331092 0.14990075, -0.14306356 -0.033310577 0.14496838, -0.14081468 -0.03331098 0.14978911, -0.12101704 -0.033313707 0.20028776, -0.14068954 -0.033310875 0.1497253, -0.12031648 -0.033313677 0.20091546, -0.12680458 -0.033311531 0.16107239, -0.12707442 -0.033311531 0.16098718, -0.12014389 -0.033313707 0.20093437, -0.12455636 -0.03331171 0.16570702, -0.11803654 -0.033313975 0.20586668, -0.11789508 -0.033314005 0.20575517, -0.11776988 -0.033313945 0.20569134, -0.10388477 -0.033314601 0.21703814, -0.10415471 -0.033314511 0.21695286, -0.13142346 -0.033312321 0.17453426, -0.13390328 -0.033312097 0.16864276, -0.1314134 -0.033312306 0.1748126, -0.14766306 -0.033310443 0.13923807, -0.14115995 -0.033311084 0.15110183, -0.14393666 -0.033310696 0.14432162, -0.1444342 -0.033310726 0.14310692, -0.14451028 -0.033310667 0.1428321, -0.14452042 -0.033310652 0.14255376, -0.13137361 -0.033312216 0.17428209, -0.13375522 -0.033312097 0.16877711, -0.14447044 -0.033310607 0.14230134, -0.13402435 -0.033312052 0.1684825, -0.13133731 -0.033312306 0.17508726, -0.14436476 -0.033310667 0.14207311, -0.11752513 -0.033312887 0.18494418, -0.12669234 -0.033312976 0.18494418, -0.11518939 -0.033313051 0.18964499, -0.13126785 -0.033312261 0.17405353, -0.13358839 -0.033312157 0.16887605, -0.14423047 -0.033310488 0.14190556, -0.12368523 -0.033311769 0.16607857, -0.13411391 -0.033312008 0.16830705, -0.13341345 -0.033311978 0.16893494, -0.14408888 -0.033310518 0.14179413, -0.13113353 -0.033312231 0.17388619, -0.13099192 -0.033312127 0.17377469, -0.13086674 -0.033312231 0.17371084, -0.12410659 -0.03331171 0.16584912, -0.14396368 -0.033310488 0.14173032, -0.11698186 -0.033312812 0.18505777, -0.11725166 -0.033312887 0.18497255, -0.11473349 -0.03331311 0.18969227, -0.12160081 -0.033313647 0.19851968, -0.12408061 -0.033313185 0.19262834, -0.1215907 -0.033313617 0.19879809, -0.12155102 -0.033313617 0.19826733, -0.12393254 -0.03331323 0.19276243, -0.11386247 -0.033313051 0.19006377, -0.13062236 -0.033311099 0.15296359, -0.12828651 -0.033311367 0.15766446, -0.12420167 -0.033313185 0.19246775, -0.12151454 -0.033313677 0.19907276, -0.10770257 -0.033314005 0.20892966, -0.10536674 -0.033314273 0.21363047, -0.12144516 -0.033313617 0.19803898, -0.12376589 -0.03331323 0.19286162, -0.14643119 -0.033310279 0.13676758, -0.14766306 -0.033310205 0.1367676, -0.11428389 -0.033313125 0.18983431, -0.12429135 -0.03331323 0.19229268, -0.13007891 -0.033311069 0.15307729, -0.13034867 -0.033311173 0.15299198, -0.12783051 -0.033311278 0.15771188, -0.12359075 -0.033313289 0.19292037, -0.12131076 -0.033313617 0.19787161, -0.12116925 -0.033313647 0.19776003, -0.12104405 -0.033313677 0.19769622, -0.12695938 -0.033311442 0.15808342, -0.10715912 -0.033314154 0.209043, -0.10742892 -0.033314124 0.20895785, -0.10491081 -0.033314303 0.21367763, -0.12738077 -0.033311382 0.15785389, -0.13469777 -0.033311889 0.16653897, -0.13717751 -0.033311591 0.16064765, -0.13468766 -0.033311859 0.16681732, -0.13464797 -0.033311814 0.1662868, -0.13702945 -0.033311725 0.16078196, -0.13156071 -0.03331092 0.14966948, -0.13389637 -0.033310682 0.14496827, -0.13729863 -0.033311591 0.16048743, -0.1346115 -0.033311814 0.16709214, -0.12079951 -0.033312425 0.17694893, -0.1184638 -0.033312708 0.18164979, -0.10403974 -0.033314303 0.21404903, -0.13454217 -0.033311859 0.16605832, -0.13686271 -0.033311605 0.16088097, -0.13335301 -0.033310682 0.14508224, -0.13362283 -0.033310726 0.14499669, -0.13110487 -0.033310875 0.14971682, -0.13738815 -0.033311591 0.16031183, -0.13023365 -0.03331089 0.15008841, -0.13668777 -0.033311576 0.16093998, -0.10446115 -0.033314303 0.21381955, -0.13440779 -0.033311769 0.16589119, -0.13426627 -0.033311829 0.16577938, -0.134141 -0.033311769 0.16571547, -0.13065496 -0.033310965 0.14985852, -0.12025617 -0.033312485 0.17706247, -0.12052597 -0.033312395 0.17697741, -0.11800769 -0.033312693 0.18169717, -0.13483496 -0.033310279 0.14167427, -0.13720825 -0.03331013 0.13662666, -0.1464888 -0.033310294 0.13662665, -0.12487496 -0.033313036 0.19052443, -0.12735491 -0.033312976 0.18463328, -0.12486495 -0.033313215 0.19080289, -0.1365924 -0.033310071 0.13675554, -0.13689806 -0.03331022 0.13665889, -0.12482518 -0.03331323 0.19027215, -0.1272067 -0.033312902 0.18476734, -0.13437898 -0.033310428 0.14172159, -0.12747586 -0.033312827 0.18447265, -0.12478881 -0.033313125 0.19107755, -0.10864092 -0.033313975 0.20563522, -0.11097671 -0.033313647 0.20093434, -0.13350798 -0.033310473 0.14209321, -0.13392924 -0.033310473 0.14186348, -0.12703992 -0.033312857 0.18486652, -0.12471944 -0.03331311 0.19004391, -0.1275654 -0.033312842 0.1842975, -0.11713673 -0.033312649 0.18206887, -0.11755815 -0.033312693 0.18183915, -0.12686506 -0.033312917 0.18492515, -0.10818502 -0.033314064 0.2056825, -0.12458509 -0.03331317 0.18987659, -0.12444359 -0.03331314 0.18976474, -0.12431827 -0.03331311 0.18970105, -0.11043338 -0.033313677 0.20104791, -0.11070317 -0.033313647 0.20096256, -0.13797195 -0.033311456 0.15854405, -0.14045183 -0.033311099 0.15265252, -0.13796191 -0.033311471 0.15882219, -0.14602795 -0.024894819 0.14005479, -0.14644378 -0.024385631 0.13917863, -0.14698841 -0.028749198 0.13665462, -0.14600658 -0.024918288 0.14009985, -0.14598671 -0.02493538 0.14014405, -0.14595754 -0.024949461 0.14021125, -0.1459284 -0.024947166 0.14028323, -0.14590311 -0.024926841 0.14035031, -0.14588065 -0.02488789 0.14041583, -0.14586417 -0.024839729 0.14046979, -0.14584959 -0.024773791 0.14052302, -0.12908636 0.10874933 0.21798728, -0.14585258 -0.024037734 0.14071703, -0.12952529 0.10922056 0.21704505, -0.14583583 -0.024663329 0.14058688, -0.14582823 -0.024386436 0.14068109, -0.14843713 -0.035297632 0.13516751, -0.14713392 -0.03529799 0.14016746, -0.14843704 -0.035297886 0.14016761, -0.13681042 -0.035297573 0.13516746, -0.13105005 -0.035297781 0.13903534, -0.1309828 -0.035297796 0.13909109, -0.13088661 -0.035297781 0.13923573, -0.13092771 -0.035297707 0.13915855, -0.11107174 -0.035302654 0.2282251, -0.094875693 -0.035302475 0.22716798, -0.094818592 -0.035302535 0.2282251, -0.11136228 -0.034218445 0.22947805, -0.11132789 -0.034025565 0.22961469, -0.11141297 -0.034383371 0.22930919, -0.11147518 -0.034510151 0.22912233, -0.11171605 -0.034674838 0.22848922, -0.11364895 -0.033912703 0.22397788, -0.11370987 -0.033940151 0.22382185, -0.11377363 -0.03394933 0.22366349, -0.097543031 0.076703742 0.29357052, -0.097554713 0.076878503 0.29358906, -0.097558931 0.076279178 0.29341573, -0.097581565 0.077086017 0.29358053, -0.097614512 0.077259734 0.29354757, -0.097655892 0.077425763 0.29349187, -0.097723335 0.077632859 0.29338366, -0.097813413 0.077838197 0.2932204, -0.097896188 0.077979878 0.29305685, -0.097984657 0.078092709 0.29287165, -0.10009652 0.072843686 0.28627864, -0.10006565 0.0732124 0.28645471, -0.10006206 0.073603436 0.28657115, -0.10008067 0.073952392 0.28662103, -0.10012627 0.074353591 0.28661972, -0.10019626 0.074749961 0.28655714, -0.10027684 0.07508643 0.28645205, -0.10044925 0.075612113 0.28617513, -0.10068326 0.07610409 0.28573817, -0.10094856 0.076471731 0.28519088, -0.14776351 -0.034669995 0.14046745, -0.14784476 -0.033944696 0.14046754, -0.14696212 -0.02837795 0.13676757, -0.14646575 -0.024400443 0.13906844, -0.14646569 -0.024400309 0.1367678, -0.12031668 0.10947457 0.2165549, -0.14571227 -0.023162723 0.13983659, -0.1291554 0.10947427 0.216555, -0.1386153 -0.032293424 0.13455559, -0.13802372 -0.032375976 0.13450779, -0.13864063 -0.032375857 0.13450779, -0.13861023 -0.032193705 0.13461329, -0.13862695 -0.032077953 0.13468002, -0.13868393 -0.031902954 0.13478135, -0.13904493 -0.031328171 0.13511385, -0.14655174 -0.033273593 0.13648309, -0.14653681 -0.033204094 0.13653858, -0.14652015 -0.033301026 0.13655247, -0.14658053 -0.033231765 0.13642438, -0.14650887 -0.0332544 0.13659324, -0.14660677 -0.033174649 0.13637562, -0.14656012 -0.033142671 0.1364982, -0.14647876 -0.033289269 0.13665701, -0.14662597 -0.03311415 0.13634513, -0.14657725 -0.033075944 0.13647498, -0.14663865 -0.033055782 0.13633005, -0.14645399 -0.033305198 0.13671292, -0.14664651 -0.032997966 0.13632683, -0.14664961 -0.032943636 0.13633409, -0.14664899 -0.032899141 0.13634792, -0.14664564 -0.03286007 0.13636696, -0.080506578 0.076390907 0.29163015, -0.080560505 0.075934127 0.29136589, -0.085498273 0.051747665 0.27737641, -0.10439716 0.0035319477 0.24948813, -0.094231129 -0.033581182 0.22802167, -0.10902999 -0.033581272 0.22802156, -0.091300875 0.0035320371 0.24948846, -0.091061532 0.0035573095 0.24950258, -0.090836152 0.0036313087 0.24954565, -0.090637803 0.0037498027 0.24961409, -0.085258946 0.051722452 0.27736175, -0.090477884 0.0039059967 0.24970441, -0.090365812 0.0040908009 0.24981138, -0.084505588 0.050777689 0.27681527, -0.084505618 0.050986335 0.27693594, -0.085033476 0.051648423 0.27731907, -0.0845633 0.050575063 0.27669817, -0.084675297 0.050390288 0.2765913, -0.09030804 0.0042933077 0.24992836, -0.090308219 0.0045021325 0.25004917, -0.090365827 0.0047046989 0.25016648, -0.084835038 0.051529929 0.27725029, -0.084675297 0.051373765 0.27716017, -0.08456324 0.05118899 0.27705336, -0.091300845 0.0052634031 0.25048947, -0.085498318 0.050016448 0.27637482, -0.085258946 0.050041541 0.27638954, -0.091061443 0.0052381307 0.25047505, -0.08503367 0.050115451 0.27643222, -0.090836197 0.0051642209 0.25043231, -0.084835261 0.050234094 0.27650082, -0.090637699 0.0050456375 0.25036371, -0.090477794 0.0048893839 0.25027335, -0.10203083 -0.015166983 0.24102558, -0.10255013 -0.014666185 0.24131528, -0.11068353 -0.034303889 0.22995667, -0.10138896 -0.015546545 0.24080609, -0.10291722 -0.014073059 0.24165832, -0.094697043 -0.034303799 0.22995669, -0.10066131 -0.015783414 0.24066903, -0.10311112 -0.013421401 0.2420354, -0.10312061 -0.012748346 0.24242452, -0.093395755 0.065158233 0.28748626, -0.096914485 0.076000884 0.29375756, -0.093218267 0.065818742 0.2878685, -0.092863277 0.066423431 0.28821796, -0.092351511 0.066936925 0.28851524, -0.091712669 0.06732966 0.28874213, -0.090983748 0.067578599 0.28888625, -0.090207294 0.067668989 0.28893843, -0.089428395 0.067596242 0.28889629, -0.088692203 0.067364141 0.28876209, -0.080927864 0.076001033 0.29375762, -0.088041618 0.066986278 0.28854358, -0.087514311 0.066484615 0.28825343, -0.087141171 0.065888271 0.28790855, -0.086943582 0.065231904 0.28752881, -0.0869333 0.064553812 0.2871367, -0.096359596 0.08344312 0.28361821, -0.096878007 0.083693251 0.28311777, -0.097340345 0.078790978 0.29292089, -0.095724866 0.083253637 0.28399652, -0.12635942 0.1194936 0.21152698, -0.12065312 0.12064102 0.20923269, -0.13665366 0.12154241 0.2074298, -0.12558496 0.11954686 0.21142015, -0.097251847 0.083990648 0.28252316, -0.12480471 0.11951581 0.21148229, -0.12406358 0.11940211 0.21170959, -0.12340485 0.11921243 0.21208912, -0.12286681 0.11895783 0.21259843, -0.095009074 0.083135918 0.2842325, -0.11961533 0.12028748 0.20993929, -0.12248056 0.11865276 0.21320789, -0.12014082 0.12056103 0.20939228, -0.12038739 0.12061313 0.20928831, -0.080982909 0.078791067 0.29292089, -0.11974607 0.12039468 0.20972516, -0.11992377 0.12048715 0.20954004, -0.12848102 0.11753523 0.21544278, -0.13696924 0.12135796 0.20779866, -0.13698971 0.12139149 0.2077308, -0.13697629 0.12145263 0.20760936, -0.13699071 0.12142253 0.20766917, -0.13698192 0.1213744 0.20776531, -0.13694683 0.12148009 0.20755404, -0.13690451 0.12150393 0.20750642, -0.12869292 0.11787258 0.21476817, -0.13685079 0.12152293 0.20746839, -0.1367885 0.12153623 0.20744205, -0.12871806 0.11822289 0.2140677, -0.12855513 0.11856559 0.21338239, -0.12821333 0.11888099 0.21275161, -0.12771305 0.11915053 0.21221255, -0.12708266 0.11935878 0.21179615, -0.13743976 0.11967276 0.20626378, -0.1375922 0.11952312 0.20656338, -0.13753402 0.11960359 0.20640239, -0.1373229 0.11972709 0.20615533, -0.13718201 0.11976954 0.20607015, -0.13702635 0.11979759 0.20601431, -0.13686691 0.1198104 0.20598865, -0.13678414 0.11981137 0.20598665, -0.12022279 0.11886211 0.20788492, -0.11988129 0.11879031 0.2080292, -0.11958081 0.11868791 0.20823348, -0.11915369 0.1184117 0.20878609, -0.11933477 0.11855987 0.20848989, -0.11408374 0.11131851 0.22296983, -0.11384454 0.11130568 0.22299595, -0.11361915 0.11126739 0.22307251, -0.11342071 0.11120622 0.22319479, -0.11326084 0.11112542 0.22335616, -0.11314885 0.11102986 0.22354707, -0.11408392 0.1104243 0.22475873, -0.11384451 0.11043715 0.2247328, -0.11361919 0.11047536 0.22465619, -0.095346302 0.091192022 0.2632181, -0.1134208 0.11053671 0.22453372, -0.11326097 0.11061746 0.22437236, -0.095106915 0.091178849 0.26324385, -0.11314893 0.11071283 0.22418158, -0.09488149 0.091140583 0.26332033, -0.11309122 0.1108176 0.22397228, -0.094683155 0.091079399 0.26344281, -0.1130912 0.11092536 0.22375661, -0.095346317 0.090297416 0.26500672, -0.095107004 0.09031041 0.26498091, -0.094881609 0.090348706 0.26490441, -0.094683126 0.090409979 0.26478174, -0.094523266 0.090490744 0.26462033, -0.09441115 0.090586171 0.26442951, -0.094353512 0.090690866 0.26422027, -0.094353572 0.090798512 0.26400459, -0.094411239 0.090903208 0.2637952, -0.094523251 0.090998694 0.26360434, -0.13772935 0.119581 0.20657107, -0.13775742 0.11961396 0.20658222, -0.13777736 0.11965106 0.20659614, -0.13769436 0.11955459 0.2065638, -0.13778806 0.11969109 0.20661303, -0.13765411 0.11953562 0.20656067, -0.13762367 0.11952706 0.20656064, -0.088995636 0.066419229 0.28372359, -0.088923514 0.066672549 0.28387004, -0.088923618 0.066933498 0.2840209, -0.08899574 0.067186579 0.28416729, -0.089135796 0.067417577 0.28430089, -0.089335591 0.067612961 0.28441378, -0.089583516 0.067761168 0.28449947, -0.089865252 0.067853585 0.28455323, -0.084714994 0.052347347 0.27558398, -0.084873646 0.052484915 0.27566379, -0.08452259 0.051998928 0.27538252, -0.084596172 0.05218251 0.27548873, -0.085498318 0.052674785 0.27577347, -0.089865193 0.065752372 0.28333789, -0.089583457 0.065844879 0.28339136, -0.085275188 0.052652851 0.27576083, -0.089335531 0.065993026 0.28347707, -0.089135706 0.066188201 0.28358996, -0.085063428 0.052588448 0.27572352, -0.093952358 0.080261067 0.28061801, -0.093670487 0.080308869 0.28052247, -0.082794592 0.077376977 0.28638551, -0.093422651 0.080385402 0.28036937, -0.093222693 0.080486342 0.28016767, -0.093082666 0.080605581 0.27992904, -0.093010545 0.080736592 0.27966738, -0.093010664 0.080871299 0.27939782, -0.093082726 0.081002071 0.27913612, -0.093222708 0.08112143 0.27889758, -0.095346376 0.088513985 0.26411504, -0.095106915 0.08852689 0.26408893, -0.093952388 0.081346735 0.27844709, -0.093670651 0.081298903 0.2785427, -0.09488152 0.088565066 0.26401228, -0.093422651 0.08122237 0.27869579, -0.094683126 0.08862637 0.26388997, -0.094523147 0.088707075 0.26372862, -0.094411179 0.088802591 0.26353779, -0.094353572 0.088907346 0.26332849, -0.094353512 0.089015052 0.26311249, -0.13779606 0.11776313 0.20562398, -0.13777222 0.11780009 0.2055501, -0.13769987 0.11786847 0.20541364, -0.13759212 0.11793053 0.2052896, -0.13745454 0.1179813 0.20518786, -0.13729618 0.11801702 0.2051163, -0.13711147 0.1180371 0.20507613, -0.13691387 0.11803705 0.20507684, -0.11408392 0.10864064 0.22386678, -0.11384463 0.10865365 0.22384095, -0.12518173 0.11380576 0.21353792, -0.11361921 0.10869174 0.22376436, -0.095346287 0.089408442 0.26232618, -0.12490001 0.11385353 0.21344243, -0.11342075 0.10875317 0.22364183, -0.11326097 0.10883383 0.22348054, -0.095106915 0.08939524 0.26235211, -0.094881609 0.089357182 0.2624287, -0.11314884 0.10892925 0.22328933, -0.094683126 0.089295879 0.26255101, -0.11309114 0.10903391 0.22308011, -0.1140838 0.10953531 0.22207816, -0.12465192 0.11393011 0.21328913, -0.12445219 0.11403096 0.2130876, -0.12431203 0.11415026 0.2128491, -0.11309123 0.10914175 0.22286481, -0.12078923 0.1171284 0.20689346, -0.12465197 0.11476699 0.21161553, -0.12489988 0.11484349 0.21146248, -0.12518167 0.11489126 0.21136662, -0.11934543 0.1166376 0.20787516, -0.12047809 0.1170983 0.2069536, -0.11314897 0.1092464 0.22265539, -0.11326094 0.10934199 0.22246413, -0.11342077 0.10942283 0.22230276, -0.11361918 0.10948388 0.22218031, -0.1138446 0.10952215 0.22210401, -0.12423994 0.11428106 0.2125871, -0.12423992 0.11441594 0.21231756, -0.12431212 0.11454678 0.21205609, -0.12445213 0.1146661 0.21181737, -0.12017454 0.11704217 0.20706593, -0.11954242 0.11679605 0.20755781, -0.11982483 0.11693516 0.20727994, -0.094411284 0.089119747 0.26290333, -0.094523311 0.089215294 0.26271239, -0.13744424 -0.03274174 0.13446771, -0.13730852 -0.032867357 0.13446765, -0.13718282 -0.033018753 0.1344675, -0.14876415 -0.021610186 0.13446799, -0.15052952 -0.024126798 0.13446791, -0.15084314 -0.023910388 0.13446775, -0.13698554 -0.033286557 0.13446751, -0.13698542 -0.034597442 0.13446747, -0.14906955 -0.034597576 0.13446753, -0.14828071 -0.021664008 0.13446777, -0.15027678 -0.02441211 0.13446778, -0.14782099 -0.021822572 0.13446777, -0.14740729 -0.022078335 0.13446775, -0.1564496 -0.022090226 0.13446803, -0.15462622 -0.024126858 0.13446772, -0.15679795 -0.022438586 0.13446788, -0.1560325 -0.021828055 0.13446794, -0.15556744 -0.021665245 0.13446797, -0.15722282 -0.023320615 0.13446778, -0.15487911 -0.02441214 0.13446781, -0.15727794 -0.023810282 0.13446766, -0.15706006 -0.02285561 0.13446791, -0.15507783 -0.021610215 0.13446784, -0.15431246 -0.023910373 0.13446775, -0.14705992 -0.022418797 0.13446775, -0.15009966 -0.024749503 0.13446775, -0.15000844 -0.025119632 0.13446775, -0.15000841 -0.025500715 0.13446772, -0.15505607 -0.024749562 0.13446786, -0.15395615 -0.023775309 0.13446772, -0.15009972 -0.025870904 0.1344678, -0.15514727 -0.025119707 0.13446786, -0.15357786 -0.023729265 0.13446772, -0.15514731 -0.025500745 0.13446778, -0.15727776 -0.027755201 0.1344676, -0.15157783 -0.026891232 0.13446775, -0.15021737 -0.032543421 0.13446775, -0.15357788 -0.026891172 0.13446768, -0.15052944 -0.02649349 0.13446777, -0.15084311 -0.026710048 0.13446772, -0.15119953 -0.026845187 0.13446772, -0.15722102 -0.02803117 0.13446772, -0.1572634 -0.027896076 0.1344676, -0.15694794 -0.028349251 0.13446772, -0.14981176 -0.032864764 0.13446778, -0.15027675 -0.026208222 0.13446772, -0.15505607 -0.025870889 0.13446771, -0.14948814 -0.03326872 0.13446751, -0.15487891 -0.026208341 0.13446772, -0.15715235 -0.028155059 0.13446774, -0.15706007 -0.028262556 0.13446763, -0.15462619 -0.02649349 0.13446772, -0.1515779 -0.023729295 0.13446774, -0.14912263 -0.034439042 0.13446748, -0.1491068 -0.034501612 0.13446747, -0.15431258 -0.026710093 0.13446771, -0.14913274 -0.034375563 0.13446754, -0.14914809 -0.034239337 0.1344675, -0.14926308 -0.033734858 0.13446759, -0.15119945 -0.023775265 0.13446774, -0.15395615 -0.026845187 0.13446772, -0.13782357 -0.032549903 0.1344675, -0.13762917 -0.03262198 0.13446771, -0.13688909 0.11794682 0.2048097, -0.12086867 0.11597647 0.20608084, -0.13699338 0.11688501 0.20426396, -0.12076426 0.11703841 0.20662647, -0.12056541 0.11916839 0.20771968, -0.1205655 0.12032536 0.20829821, -0.13683079 -0.033172652 0.13453712, -0.13702811 -0.03290467 0.13453709, -0.13679063 -0.033218861 0.13454105, -0.13096434 -0.033219129 0.13845362, -0.11926796 0.10937254 0.21683107, -0.11475255 0.10815674 0.21926242, -0.11326927 0.10853715 0.22044626, -0.10442829 -0.032564208 0.21649188, -0.099833116 0.077685013 0.28026074, -0.11359541 -0.032564208 0.21649183, -0.090666026 0.077685133 0.28026053, -0.10065338 0.078208402 0.27906084, -0.10021472 0.077737197 0.28000331, -0.10317086 0.081563368 0.27236938, -0.108641 -0.03306438 0.20606796, -0.094332159 0.081563488 0.27236953, -0.11728255 -0.032762602 0.20809424, -0.11778006 -0.032762513 0.2068793, -0.10310192 0.080838278 0.27380168, -0.10605806 0.084664568 0.26616782, -0.11191522 -0.033063814 0.19807297, -0.097219422 0.084664598 0.26616785, -0.11097658 -0.032563344 0.2005015, -0.10560751 0.083887562 0.26785749, -0.12014391 -0.032563373 0.20050158, -0.09644033 0.083887592 0.26785755, -0.10598908 0.083939597 0.26760018, -0.12055688 -0.032762036 0.20009927, -0.12105416 -0.032762155 0.19888417, -0.10894519 0.087765917 0.25996637, -0.11518946 -0.033063427 0.19007765, -0.10010648 0.087765858 0.25996631, -0.11425105 -0.032562807 0.19250645, -0.10849473 0.086988643 0.26165599, -0.12341814 -0.032562867 0.19250636, -0.099327534 0.086988643 0.26165587, -0.1088762 0.087040678 0.26139843, -0.123831 -0.032761648 0.19210404, -0.12432848 -0.032761559 0.19088922, -0.11183245 0.090866953 0.25376457, -0.11846371 -0.033062905 0.18208276, -0.10299376 0.090867117 0.25376451, -0.11752529 -0.032562509 0.18451136, -0.11138192 0.090089902 0.25545424, -0.12669231 -0.032562658 0.18451124, -0.10221486 0.090090021 0.25545433, -0.11176348 0.090142146 0.25519705, -0.12710525 -0.032761186 0.18410906, -0.12760274 -0.032761082 0.18289405, -0.11471948 0.093968287 0.24756305, -0.121738 -0.033062562 0.17408754, -0.10588087 0.093968406 0.24756314, -0.12079944 -0.032561973 0.17651619, -0.11426897 0.093191177 0.24925257, -0.12996662 -0.032562152 0.17651616, -0.10510197 0.093191132 0.24925262, -0.11465055 0.093243316 0.24899553, -0.13037941 -0.032760888 0.17611374, -0.13087696 -0.03276065 0.17489889, -0.11760665 0.097069442 0.24136136, -0.12501222 -0.033062026 0.16609268, -0.10876802 0.097069442 0.24136142, -0.12407379 -0.032561541 0.16852117, -0.11715615 0.096292362 0.24305104, -0.13324085 -0.032561705 0.16852106, -0.10798904 0.096292317 0.24305104, -0.11753775 0.096344531 0.24279378, -0.13365363 -0.032760441 0.16811863, -0.13415131 -0.032760262 0.16690372, -0.12049383 0.10017088 0.23515975, -0.12828632 -0.033061638 0.15809749, -0.11165524 0.10017076 0.23515971, -0.12734789 -0.032561257 0.16052584, -0.12004346 0.099393576 0.23684946, -0.13651508 -0.032561213 0.16052595, -0.11087617 0.099393666 0.23684959, -0.12042499 0.099445611 0.23659208, -0.13692801 -0.032759994 0.16012348, -0.1374255 -0.032759786 0.15890861, -0.12338111 0.10327186 0.22895823, -0.13156071 -0.033061221 0.1501023, -0.11454239 0.10327193 0.22895832, -0.13062215 -0.032560766 0.15253083, -0.12293056 0.10249487 0.23064777, -0.13978943 -0.032560766 0.15253079, -0.11376336 0.102495 0.23064792, -0.12331207 0.1025468 0.23039049, -0.14020233 -0.032759517 0.15212835, -0.14069979 -0.032759532 0.15091346, -0.12626833 0.10637306 0.22275655, -0.13483492 -0.033060849 0.14210731, -0.1174296 0.10637325 0.22275659, -0.13389641 -0.032560408 0.14453571, -0.12581761 0.10559601 0.22444634, -0.14306356 -0.032560334 0.14453571, -0.1166506 0.10559598 0.2244463, -0.12619923 0.10564812 0.22418889, -0.14347658 -0.032759055 0.14413342, -0.14397381 -0.032759145 0.14291836, -0.1463448 -0.032616496 0.13650791, -0.13720818 -0.032859921 0.13636689, -0.12870488 0.10869727 0.21824473, -0.11953782 0.10869747 0.21824446, -0.11896911 0.11978184 0.20938557, -0.080498204 0.077301726 0.2914418, -0.11896919 0.11862481 0.20880684, -0.080437869 0.077223346 0.29156464, -0.080336794 0.078285262 0.29236716, -0.080391183 0.077143088 0.2916497, -0.080467939 0.077265814 0.29150516, -0.080246225 0.078171685 0.29255366, -0.080108941 0.077606961 0.29310295, -0.080128089 0.077331141 0.29322699, -0.080361813 0.075815484 0.29152858, -0.080152795 0.077034339 0.29328507, -0.080174372 0.076804742 0.29328203, -0.080197468 0.076582149 0.29323894, -0.08021456 0.076430365 0.29318565, -0.080231875 0.076286271 0.29311398, -0.094045624 -0.033713862 0.22796246, -0.09404929 -0.033737168 0.227936, -0.09404017 -0.033684 0.2280114, -0.094030887 -0.033643767 0.22811189, -0.09415637 -0.034667626 0.2275641, -0.094122544 -0.034667656 0.22818765, -0.094021514 -0.033612594 0.2282345, -0.094113261 -0.03465791 0.22834556, -0.094102144 -0.034629092 0.22850083, -0.094084039 -0.034557357 0.22871143, -0.094001144 -0.034018412 0.22931315, -0.094063178 -0.034448668 0.22890946, -0.094032899 -0.034256503 0.22913572, -0.14602217 -0.023215428 0.1394906, -0.13935471 -0.031380922 0.13476743, -0.14682764 -0.022228912 0.13476764, -0.14621474 -0.022979766 0.13966337, -0.14682759 -0.022229135 0.14016768, -0.14639182 -0.022762686 0.13989857, -0.14876415 -0.021310136 0.13476792, -0.15507793 -0.02131018 0.1347679, -0.15507782 -0.021310195 0.13646798, -0.14876413 -0.021310315 0.14016776, -0.15507787 -0.02131024 0.14016771, -0.15757787 -0.023810267 0.13646774, -0.15757786 -0.023810208 0.13476765, -0.1575779 -0.027755186 0.13476771, -0.15757786 -0.027755201 0.14016777, -0.15757792 -0.023810267 0.14016789, -0.1494308 -0.034409225 0.14016761, -0.14944616 -0.03427279 0.1401677, -0.14943087 -0.034408987 0.13476758, -0.14944617 -0.034272835 0.13476756, -0.15037596 -0.032797992 0.13476758, -0.15710673 -0.028603882 0.14016759, -0.15710673 -0.028603762 0.13476753, -0.15037604 -0.032798186 0.14016755, -0.13670672 -0.034659877 0.1345526, -0.13094351 -0.03340891 0.13842262, -0.13073322 -0.034659982 0.13856363, -0.13670669 -0.033408806 0.13455261, -0.13092631 -0.033409983 0.13843407, -0.14653087 -0.024173379 0.13676757, -0.14653094 -0.024173528 0.13906839, -0.14745213 -0.023045331 0.13676777, -0.14607155 -0.024736047 0.14016774, -0.14745216 -0.023045391 0.14016759, -0.14648739 -0.0242268 0.13929155, -0.1465261 -0.024179548 0.1391513, -0.14651142 -0.024197459 0.13922647, -0.14706005 -0.022418797 0.14046773, -0.14721982 -0.022855744 0.14046773, -0.14622088 -0.024078995 0.14046767, -0.15021728 -0.032543451 0.14046744, -0.15626544 -0.028303325 0.14046764, -0.15694796 -0.02834931 0.14046763, -0.15601195 -0.022512227 0.14046772, -0.15603241 -0.0218281 0.14046779, -0.15644962 -0.022090197 0.1404677, -0.15679801 -0.022438601 0.14046782, -0.156376 -0.022876367 0.14046767, -0.15706006 -0.022855774 0.1404677, -0.15665011 -0.023312271 0.14046766, -0.15722273 -0.023320675 0.14046769, -0.15557589 -0.022238046 0.14046772, -0.15556741 -0.021665409 0.14046778, -0.15508965 -0.022067919 0.14046779, -0.15507793 -0.021610349 0.14046782, -0.15682027 -0.023798391 0.14046767, -0.15727784 -0.023810312 0.14046769, -0.14926317 -0.033734813 0.14046749, -0.14914799 -0.034239471 0.14046744, -0.14913282 -0.034375787 0.14046746, -0.14909644 -0.034532964 0.14046766, -0.1490196 -0.034686148 0.14046744, -0.14891672 -0.034807622 0.14046744, -0.14880256 -0.034894973 0.14046748, -0.14759031 -0.033709288 0.14046775, -0.14981171 -0.032864809 0.14046751, -0.14948811 -0.033268854 0.14046744, -0.15687785 -0.024310321 0.14046764, -0.14867534 -0.034955978 0.14046745, -0.15457779 -0.022010237 0.14046779, -0.148555 -0.034987867 0.14046742, -0.15687793 -0.027200148 0.14046782, -0.14843717 -0.03499794 0.14046775, -0.15727782 -0.027755171 0.14046776, -0.15685117 -0.027461827 0.14046761, -0.14737074 -0.034997851 0.14046766, -0.15677251 -0.027712867 0.14046769, -0.15726349 -0.027896076 0.14046749, -0.15722108 -0.028031319 0.14046782, -0.15715228 -0.028155118 0.14046775, -0.15664467 -0.027942747 0.14046776, -0.15706013 -0.028262645 0.14046784, -0.15647335 -0.028142422 0.14046776, -0.14876413 -0.021610245 0.14046769, -0.1490013 -0.022010237 0.14046767, -0.14849597 -0.022066593 0.1404677, -0.14828078 -0.021663979 0.14046784, -0.14801547 -0.022232234 0.14046779, -0.14782095 -0.021822631 0.14046785, -0.14740744 -0.022078529 0.1404677, -0.14758304 -0.022499695 0.1404677, -0.15610681 -0.028048769 0.14016783, -0.15610686 -0.028048679 0.13676758, -0.14743544 -0.033452153 0.14016752, -0.15457785 -0.022310197 0.13676779, -0.14900118 -0.022310168 0.13676775, -0.15657783 -0.024310082 0.1367678, -0.15652767 -0.023865268 0.13676772, -0.15657778 -0.024310321 0.14016774, -0.15652771 -0.023865297 0.14016789, -0.15637983 -0.023442432 0.13676779, -0.15637979 -0.023442432 0.14016786, -0.1561415 -0.023063228 0.13676789, -0.15614167 -0.023063317 0.14016765, -0.15582487 -0.022746533 0.13676788, -0.1558249 -0.022746667 0.14016762, -0.15544565 -0.022508293 0.13676779, -0.15544569 -0.022508368 0.14016762, -0.15502283 -0.02236028 0.13676775, -0.15502286 -0.02236037 0.14016785, -0.15657791 -0.027199924 0.13676773, -0.15657775 -0.027200192 0.14016774, -0.15751514 -0.023253888 0.13646771, -0.15751527 -0.023253903 0.14016803, -0.15733029 -0.022725612 0.14016767, -0.15733029 -0.022725523 0.13646773, -0.15703236 -0.022251531 0.1401677, -0.15703252 -0.022251531 0.13646778, -0.15663661 -0.021855697 0.14016774, -0.1566366 -0.021855712 0.13646786, -0.1561625 -0.021557912 0.14016762, -0.15616253 -0.021557719 0.13646795, -0.15563419 -0.021372929 0.14016786, -0.15563424 -0.021372855 0.13646799, -0.15751514 -0.023253888 0.13476779, -0.15733027 -0.022725403 0.13476789, -0.15703237 -0.022251487 0.13476782, -0.15663658 -0.021855637 0.13476768, -0.15616262 -0.021557748 0.13476788, -0.15563419 -0.021372989 0.13476788, -0.13688527 -0.03333275 0.13447775, -0.13690083 -0.034604698 0.13447487, -0.13681783 -0.03462638 0.13449645, -0.13680233 -0.033365771 0.13450228, -0.13675308 -0.033387184 0.1345247, -0.13674054 -0.034661502 0.13453181, -0.13094594 -0.033344179 0.13842598, -0.1367396 -0.033322647 0.13453947, -0.13095292 -0.033280522 0.13843645, -0.1367638 -0.033269837 0.13453804, -0.14821482 -0.02137126 0.1401678, -0.14821482 -0.021371201 0.13476777, -0.14769238 -0.021551579 0.13476785, -0.14769238 -0.021551609 0.14016758, -0.14722241 -0.021842077 0.13476788, -0.14722231 -0.02184239 0.14016777, -0.14776801 -0.0227357 0.13676776, -0.14776796 -0.022735819 0.14016761, -0.14814395 -0.022503212 0.13676782, -0.14814392 -0.022503361 0.14016768, -0.14856185 -0.022359043 0.13676754, -0.14856187 -0.022359148 0.14016762, -0.08452183 0.051622525 0.27516469, -0.084498346 0.051810816 0.27527374, -0.090324283 0.0051382333 0.24827819, -0.090300858 0.0053263754 0.24838693, -0.095112056 -0.033580944 0.22585548, -0.095141202 -0.033581093 0.22587022, -0.095172808 -0.033580974 0.22587955, -0.094224855 -0.033581153 0.2280218, -0.098635346 0.079261795 0.27371988, -0.093217403 0.077559307 0.27712488, -0.093417287 0.077661529 0.27692017, -0.094137028 0.079261824 0.27371991, -0.093949914 0.077787772 0.2766678, -0.093666315 0.077739224 0.27676499, -0.09860906 0.079042748 0.27812898, -0.099130198 0.079507187 0.27369606, -0.097432435 0.077683792 0.27734256, -0.10030675 0.080866322 0.27448249, -0.093246654 0.079506919 0.27428198, -0.091987565 0.077503309 0.27757275, -0.093662351 0.079302445 0.27397513, -0.091320783 0.080211118 0.27592361, -0.089854538 0.078636244 0.27907294, -0.09051919 0.078393236 0.27850649, -0.090965629 0.078191712 0.27816021, -0.091451854 0.077899233 0.2778492, -0.091953933 0.077530101 0.27758813, -0.10038041 0.080930665 0.27454901, -0.098682761 0.07910721 0.27819508, -0.09877336 0.079149529 0.27825862, -0.10047109 0.080973044 0.2746121, -0.098875761 0.079167351 0.27831519, -0.10057332 0.080990806 0.27466893, -0.098712832 0.079275981 0.27370068, -0.097128317 0.077485606 0.27732679, -0.098790675 0.079296932 0.27368575, -0.098923817 0.079351261 0.27367187, -0.097271383 0.077552781 0.27731752, -0.099039733 0.079423472 0.27367574, -0.09736082 0.077614859 0.27732456, -0.094027519 0.079253301 0.27375436, -0.092276335 0.077430561 0.27742064, -0.093920618 0.07925801 0.2737965, -0.09212026 0.077453032 0.27749205, -0.093827248 0.079269752 0.27384567, -0.093741566 0.079284266 0.27390635, -0.0912503 0.080281243 0.27592611, -0.089784145 0.078706279 0.27907532, -0.091169715 0.080338582 0.27591717, -0.08970356 0.078763738 0.27906626, -0.091082022 0.08038111 0.27589747, -0.089615911 0.078806177 0.27904665, -0.12445222 0.11045854 0.21130081, -0.1243121 0.11057787 0.21106243, -0.12590981 0.11155473 0.20910895, -0.12631389 0.11148618 0.20924604, -0.12666973 0.11017595 0.21186626, -0.12695631 0.11032061 0.21157718, -0.12715721 0.1104918 0.21123475, -0.12424 0.11070867 0.21080075, -0.12631401 0.11006604 0.2120859, -0.12726063 0.11067943 0.2108593, -0.12590978 0.1099975 0.21222293, -0.12726068 0.11087264 0.21047291, -0.12518173 0.11131899 0.20958042, -0.12423992 0.11084346 0.21053118, -0.12431206 0.11097433 0.21026959, -0.12445222 0.11109374 0.21003087, -0.12518169 0.11023332 0.21175157, -0.1249 0.11127116 0.20967592, -0.12715718 0.11106037 0.21009743, -0.12465204 0.11119474 0.2098292, -0.12489974 0.11028107 0.21165588, -0.12695634 0.11123173 0.20975512, -0.12465192 0.11035766 0.21150278, -0.12666969 0.1113764 0.20946571, -0.093943715 0.076689556 0.27882969, -0.09365499 0.076740161 0.27872869, -0.093403041 0.076820925 0.27856714, -0.093203098 0.076927021 0.27835506, -0.093067795 0.077051714 0.27810562, -0.093002915 0.076820448 0.27761245, -0.09300217 0.076904669 0.2776351, -0.1260533 0.11241077 0.2086786, -0.12647831 0.1117572 0.20903176, -0.12678242 0.1128795 0.20869565, -0.12624338 0.11354648 0.20831609, -0.12605336 0.1101668 0.21316616, -0.12647828 0.11005698 0.21243155, -0.12599441 0.10997497 0.21259546, -0.12678246 0.11046164 0.21353066, -0.12624344 0.110558 0.21429235, -0.12690413 0.11162578 0.20929456, -0.12782632 0.11250713 0.20944031, -0.12724718 0.11145245 0.20964086, -0.12748773 0.11124747 0.21005075, -0.12840554 0.11196899 0.2105161, -0.12761162 0.11102273 0.21050015, -0.12840557 0.11137187 0.21171027, -0.12761168 0.11079122 0.21096286, -0.12748782 0.11056663 0.21141216, -0.12782626 0.11083393 0.2127862, -0.12724732 0.11036168 0.21182209, -0.12690412 0.11018859 0.21216863, -0.12599444 0.11183916 0.20886743, -0.1244974 0.11434104 0.20798759, -0.12365486 0.1140459 0.20841114, -0.12287521 0.11380507 0.20889238, -0.12454042 0.11078313 0.21493497, -0.12281792 0.11387528 0.20885502, -0.12361464 0.11412133 0.20836321, -0.12451972 0.1107868 0.21503089, -0.12361456 0.11094046 0.21472381, -0.12449735 0.11077169 0.21512505, -0.12357099 0.11092883 0.21481071, -0.12451975 0.11427476 0.20805611, -0.12357104 0.11418389 0.20830166, -0.12275566 0.11118044 0.21430741, -0.12454043 0.1141959 0.20811056, -0.12365474 0.11093342 0.2146347, -0.12281793 0.11118631 0.21423197, -0.12209871 0.11151227 0.2136444, -0.1228752 0.11117397 0.21415351, -0.12217595 0.11151059 0.21358387, -0.12163831 0.1119047 0.21285979, -0.122247 0.11149116 0.21351938, -0.12172611 0.11189409 0.21281706, -0.1214013 0.1123348 0.21199928, -0.12180687 0.11186643 0.21276908, -0.12149446 0.11231436 0.21197645, -0.12140124 0.1127779 0.21111305, -0.12158026 0.11227767 0.21194641, -0.12149446 0.11274733 0.21111046, -0.12163834 0.11320795 0.21025296, -0.12158015 0.11270137 0.21109924, -0.12172614 0.1131679 0.21026988, -0.12209892 0.1136006 0.20946825, -0.1218069 0.11311276 0.21027653, -0.12217598 0.11355115 0.20950304, -0.12275569 0.11393215 0.20880483, -0.12224706 0.11348794 0.20952632, -0.12597629 0.11175071 0.20890546, -0.12595575 0.10994843 0.21240613, -0.12644307 0.11167163 0.20906401, -0.12597644 0.10995232 0.212502, -0.12640296 0.11159597 0.20911165, -0.12685394 0.11154471 0.20931733, -0.12685388 0.11015826 0.21208996, -0.12679665 0.11147462 0.2093548, -0.126443 0.11003135 0.21234345, -0.12673435 0.1114177 0.20940477, -0.12703657 0.11126508 0.20970997, -0.12711379 0.11131428 0.20967495, -0.12595558 0.11167197 0.20895976, -0.12640294 0.11002432 0.21225446, -0.12593324 0.10996373 0.21231188, -0.12635934 0.11153351 0.2091732, -0.12718496 0.11032531 0.21175575, -0.12593329 0.11160566 0.20902857, -0.12679666 0.11014594 0.21201149, -0.12635924 0.11003603 0.21216746, -0.12741689 0.11052303 0.21136045, -0.12711382 0.11030591 0.2116912, -0.12673442 0.11015192 0.21193585, -0.12753642 0.11073968 0.21092686, -0.12733611 0.11049542 0.21131241, -0.12703666 0.11030446 0.21163076, -0.12753646 0.11096302 0.2104803, -0.12745056 0.1107032 0.21089697, -0.12724844 0.11048493 0.21126999, -0.12741694 0.11117981 0.21004701, -0.12745057 0.11091708 0.21046923, -0.12735748 0.11068271 0.21087408, -0.12718496 0.11137758 0.20965159, -0.12733613 0.1111248 0.21005352, -0.12735745 0.11088659 0.21046653, -0.12724848 0.11108446 0.21007091, -0.096035227 0.083166137 0.28305408, -0.095498189 0.083005801 0.28337419, -0.12801962 0.11717403 0.21504733, -0.12294212 0.11811975 0.21315637, -0.12326901 0.11837763 0.21264033, -0.12683621 0.11871701 0.21196163, -0.12736957 0.11854088 0.21231399, -0.127793 0.11831273 0.21277031, -0.094892517 0.082906052 0.28357375, -0.12622423 0.11883096 0.21173388, -0.12808217 0.11804593 0.21330391, -0.12556902 0.11887616 0.21164346, -0.12821996 0.11775586 0.21388373, -0.1249087 0.11884984 0.2116961, -0.12819891 0.11745954 0.21447644, -0.1242817 0.11875382 0.21188834, -0.096790239 0.083629355 0.28212738, -0.12372428 0.11859313 0.21220943, -0.096474037 0.083377734 0.28263068, -0.10072264 -0.0078011006 0.23634437, -0.09872067 -0.0095589608 0.23532781, -0.098648593 -0.0093056411 0.23547418, -0.10072264 -0.010549411 0.23475489, -0.10107841 -0.010336861 0.23487778, -0.10136501 -0.010056779 0.23503964, -0.10031848 -0.0076684803 0.23642124, -0.10031849 -0.010682002 0.2346781, -0.10156585 -0.0097255558 0.23523124, -0.098648608 -0.0090449005 0.23562498, -0.10166925 -0.0093625337 0.23544121, -0.10166928 -0.0089884251 0.23565781, -0.099590421 -0.0081246048 0.23615725, -0.098720789 -0.008791551 0.23577142, -0.099590287 -0.010225818 0.23494186, -0.098860741 -0.0085606426 0.23590505, -0.10156584 -0.0086250156 0.23586786, -0.099308535 -0.0082171708 0.23610367, -0.099060476 -0.0083654672 0.23601794, -0.09930858 -0.010133311 0.23499539, -0.10136497 -0.008293733 0.23605931, -0.099060461 -0.0099851638 0.23508109, -0.10107836 -0.0080136508 0.23622146, -0.09886083 -0.00978975 0.235194, -0.090997741 0.070105746 0.28140613, -0.091353402 0.069893256 0.28128326, -0.089135706 0.068116769 0.28025568, -0.088995695 0.068347797 0.28038925, -0.090593591 0.070238575 0.28148299, -0.091353357 0.067569718 0.27993941, -0.091639996 0.0678498 0.28010142, -0.091840863 0.068181083 0.28029293, -0.090997517 0.067357168 0.27981627, -0.091944188 0.068544343 0.28050306, -0.088923514 0.068600997 0.2805357, -0.090593636 0.067224547 0.27973968, -0.091944322 0.068918481 0.28071928, -0.091840968 0.069281772 0.28092963, -0.089865297 0.06768097 0.28000355, -0.088923484 0.068861857 0.2806868, -0.089583516 0.067773327 0.28005719, -0.089865267 0.069782123 0.28121901, -0.088995606 0.069115117 0.28083313, -0.091639951 0.069613144 0.28112131, -0.089335501 0.06954132 0.28107965, -0.089583561 0.069689497 0.28116548, -0.089135587 0.069346055 0.28096688, -0.08933562 0.067921564 0.28014284, -0.10065205 -0.0069975704 0.23845735, -0.10046206 -0.0072906464 0.23730186, -0.10119098 -0.0073363632 0.23776846, -0.10046205 -0.011633828 0.23478974, -0.10088699 -0.010893628 0.23472486, -0.10040316 -0.011052653 0.23463297, -0.10119109 -0.012015685 0.23506193, -0.10065195 -0.012781605 0.23511174, -0.1008869 -0.0076034814 0.23662792, -0.10131274 -0.007857874 0.23648077, -0.10223499 -0.0080568939 0.23735179, -0.10165603 -0.0081932396 0.23628679, -0.10189636 -0.0085897595 0.23605765, -0.1028143 -0.0090980381 0.23674956, -0.10202035 -0.0090247244 0.23580602, -0.10202026 -0.0094727129 0.23554683, -0.10281435 -0.010253802 0.23608091, -0.10189638 -0.0099075288 0.2352953, -0.10223493 -0.011295184 0.23547867, -0.10165605 -0.010304078 0.23506573, -0.1013128 -0.010639414 0.23487191, -0.10040317 -0.0074446052 0.2367198, -0.091466129 0.065891072 0.28012359, -0.092509776 0.066611663 0.28054041, -0.091587812 0.067267314 0.27993363, -0.09073706 0.070616111 0.28236353, -0.090678141 0.070462242 0.28178161, -0.091162041 0.070303306 0.28168952, -0.091466263 0.070570573 0.28283018, -0.09092699 0.070909098 0.28351906, -0.090737045 0.06627284 0.2798512, -0.091162026 0.067012772 0.27978635, -0.09067817 0.066854075 0.27969447, -0.090926975 0.065125182 0.28017369, -0.091587827 0.070049003 0.28154254, -0.092510059 0.069849953 0.28241348, -0.091930941 0.069713578 0.28134847, -0.092171535 0.069316939 0.28111917, -0.093089297 0.068808779 0.281811, -0.092295215 0.068882123 0.28086776, -0.092295259 0.068434194 0.28060859, -0.093089268 0.067652956 0.28114265, -0.092171431 0.067999348 0.28035694, -0.091931045 0.067602739 0.28012764, -0.10038495 -0.0074772686 0.23662913, -0.10036433 -0.010861918 0.2346178, -0.10085177 -0.0076303631 0.23654053, -0.10038504 -0.010957763 0.23461607, -0.10081159 -0.0076735765 0.23646225, -0.10126258 -0.0078758746 0.23639862, -0.10120526 -0.0079087764 0.2363261, -0.10126258 -0.010559037 0.23484655, -0.10114299 -0.007955268 0.23626631, -0.10085171 -0.010804579 0.23470443, -0.10144521 -0.0082505196 0.23609559, -0.10152246 -0.0082186908 0.23614697, -0.10036425 -0.0075266212 0.23654713, -0.10081166 -0.010715201 0.234703, -0.10034184 -0.010768875 0.23463883, -0.10076806 -0.0077310652 0.23639601, -0.10159354 -0.010235593 0.23503374, -0.10034184 -0.0075912327 0.23647679, -0.10120526 -0.010479942 0.23483863, -0.1007679 -0.010629043 0.2347198, -0.10182559 -0.0098531991 0.23525491, -0.10152252 -0.010170028 0.23501827, -0.10114311 -0.01040493 0.23484944, -0.10194501 -0.0094336122 0.2354975, -0.1017447 -0.0098033398 0.23523019, -0.10144521 -0.010109618 0.23502012, -0.10194497 -0.0090015084 0.23574738, -0.1018593 -0.0094014257 0.23546258, -0.10165705 -0.0097602755 0.23522218, -0.10182557 -0.0085819215 0.23599005, -0.10185918 -0.0089874119 0.23570225, -0.10176614 -0.009377405 0.23544374, -0.10159361 -0.0081992596 0.23621139, -0.10174474 -0.0085853189 0.23593476, -0.10176605 -0.0089829713 0.235672, -0.10165712 -0.0085998625 0.23589364, -0.097979501 -0.0070219189 0.23909442, -0.098928392 -0.0067825168 0.23920009, -0.098905891 -0.0067178458 0.23927031, -0.097164333 -0.012834683 0.23573241, -0.09797959 -0.013321862 0.23545067, -0.098949045 -0.0068319291 0.23911808, -0.098928437 -0.013532743 0.23529576, -0.098063275 -0.013146386 0.23546593, -0.098023221 -0.013235673 0.23546748, -0.098063305 -0.0071227103 0.23895, -0.098023146 -0.0070795268 0.23902825, -0.09894903 -0.013437077 0.23529769, -0.097226396 -0.012759611 0.23574288, -0.096507192 -0.012192652 0.2361035, -0.09728384 -0.012680456 0.23573551, -0.096584484 -0.012132272 0.23610567, -0.09604682 -0.011433348 0.23654296, -0.096655771 -0.012066618 0.23609024, -0.096134603 -0.011390284 0.23653483, -0.095809743 -0.010600641 0.23702444, -0.096215472 -0.011340603 0.23651038, -0.09590292 -0.010576621 0.23700538, -0.095809877 -0.0097430199 0.23752061, -0.095988691 -0.010544345 0.23697081, -0.09590286 -0.009738639 0.2374903, -0.096046895 -0.0089103431 0.23800209, -0.095988765 -0.0097245723 0.23744504, -0.096134633 -0.0089248866 0.23796085, -0.096507356 -0.0081509203 0.23844144, -0.096215531 -0.008928284 0.2379054, -0.096584514 -0.0081828386 0.23838995, -0.097164348 -0.0075090379 0.23881279, -0.096655682 -0.0082022399 0.23832522, -0.097226545 -0.0075555593 0.23875286, -0.09728387 -0.0075884908 0.23868035, -0.098905891 -0.013625905 0.23527479, -0.09148021 0.069998071 0.28138775, -0.091868684 0.069707528 0.28127331, -0.09153755 0.070030913 0.28146017, -0.091797397 0.069688097 0.2812086, -0.091126829 0.067102149 0.27976617, -0.090660036 0.066948876 0.27967751, -0.090639263 0.067044631 0.27967966, -0.091720238 0.069656298 0.28115731, -0.091932133 0.069306955 0.2809552, -0.092019901 0.069321468 0.28099662, -0.09066008 0.070429698 0.28169087, -0.091537684 0.067347601 0.27990836, -0.091126755 0.070276484 0.28160226, -0.091086581 0.070233449 0.28152406, -0.091086417 0.067191437 0.27976429, -0.091418073 0.069951668 0.28132814, -0.090616882 0.067137703 0.27970052, -0.090639368 0.070380196 0.28160888, -0.091868669 0.067671075 0.2800954, -0.091042951 0.070175633 0.28145754, -0.091480255 0.067426726 0.27990055, -0.090616852 0.070315555 0.28153849, -0.091042936 0.067277774 0.27978146, -0.092100531 0.068053558 0.28031659, -0.091797471 0.06773673 0.2800799, -0.091418028 0.067501888 0.27991122, -0.092220038 0.068473235 0.28055933, -0.092019737 0.068103358 0.28029197, -0.091720194 0.06779708 0.28008187, -0.092220023 0.068905219 0.28080904, -0.092134327 0.068505362 0.28052458, -0.091931969 0.068146303 0.2802839, -0.092100695 0.069324836 0.28105175, -0.092134193 0.068919405 0.28076398, -0.092041194 0.068529412 0.2805056, -0.092041209 0.068923935 0.2807337, -0.088298202 0.070827171 0.28408986, -0.089224175 0.071074829 0.28417981, -0.089203313 0.071124181 0.2842617, -0.087439299 0.065072283 0.28079402, -0.08825472 0.064585045 0.28051221, -0.089203417 0.064373955 0.28035736, -0.088338405 0.064760521 0.28052735, -0.088298112 0.064671293 0.28052908, -0.0892241 0.064469799 0.28035933, -0.087501496 0.065147236 0.28080457, -0.086782426 0.065714136 0.28116548, -0.087558895 0.065226391 0.28079697, -0.086859435 0.065774575 0.28116739, -0.086322039 0.066473618 0.28160465, -0.086930722 0.0658402 0.28115207, -0.086409718 0.066516533 0.28159672, -0.086084932 0.067306057 0.28208613, -0.086490482 0.066566244 0.2815721, -0.086178035 0.067330196 0.28206724, -0.086084932 0.068163648 0.28258204, -0.086263821 0.067362323 0.28203243, -0.086178035 0.068168059 0.28255188, -0.086321905 0.068996295 0.28306398, -0.086263716 0.068182334 0.28250682, -0.086409628 0.068981752 0.28302252, -0.086782426 0.069755688 0.28350294, -0.086490482 0.068978444 0.28296742, -0.086859465 0.06972383 0.28345174, -0.087439224 0.070397511 0.28387445, -0.086930603 0.069704428 0.28338727, -0.087501451 0.07035102 0.28381461, -0.088254765 0.070884809 0.28415596, -0.087558791 0.070318177 0.28374216, -0.089180887 0.064280912 0.28033644, -0.089180902 0.071188912 0.28433192, -0.08833845 0.070783958 0.28401148, -0.087439075 0.065424368 0.28706253, -0.087606266 0.065979823 0.28738397, -0.088668361 0.065597519 0.28716278, -0.088575974 0.065273151 0.28697515, -0.087430313 0.064850494 0.28673071, -0.088576093 0.064939365 0.28678197, -0.1005425 -0.015112713 0.24047945, -0.10115816 -0.014912322 0.2405953, -0.088668391 0.064615205 0.28659463, -0.088847652 0.064319476 0.28642362, -0.089103386 0.064069644 0.28627911, -0.08942084 0.063879922 0.28616929, -0.10262355 -0.012544617 0.24196471, -0.092898563 0.065362051 0.28702644, -0.091474473 0.067199424 0.28808928, -0.092015103 0.066867188 0.28789702, -0.09244813 0.066432729 0.28764582, -0.099506363 -0.014145032 0.24103904, -0.090857744 0.067410037 0.28821093, -0.09882836 -0.011763647 0.2424165, -0.098572567 -0.012013629 0.24227178, -0.098393366 -0.012309238 0.24210104, -0.092748538 0.065921143 0.28734988, -0.098301068 -0.012633398 0.24191326, -0.098301157 -0.012967303 0.24172033, -0.0991458 -0.014026746 0.24110736, -0.090200737 0.067486599 0.28825536, -0.098393321 -0.013291374 0.2415327, -0.089541644 0.067425057 0.28821966, -0.098828435 -0.013836995 0.24121737, -0.098572701 -0.013587043 0.24136171, -0.089781657 0.066451028 0.2876564, -0.088918746 0.0672286 0.28810608, -0.10261545 -0.013113961 0.24163549, -0.099506587 -0.011455521 0.24259473, -0.089781463 0.063761547 0.28610066, -0.089421004 0.066332713 0.28758815, -0.10245138 -0.013665482 0.24131647, -0.088368177 0.066908792 0.28792113, -0.099145919 -0.011574045 0.24252605, -0.089103416 0.066142872 0.28747812, -0.10214081 -0.014167324 0.2410263, -0.087922007 0.066484377 0.28767574, -0.088847667 0.065893099 0.28733385, -0.10170141 -0.014591083 0.24078122, -0.099506542 -0.010704473 0.24129643, -0.098301038 -0.011882409 0.2406151, -0.098393559 -0.011558101 0.24080242, -0.098572671 -0.011262551 0.24097356, -0.09882839 -0.011012658 0.24111797, -0.099145845 -0.010822937 0.24122782, -0.098301217 -0.012216166 0.24042191, -0.098393455 -0.012540475 0.24023427, -0.099145904 -0.013275728 0.23980884, -0.099506527 -0.013394013 0.23974037, -0.098572731 -0.012836143 0.24006332, -0.098828465 -0.013085976 0.23991871, -0.089781612 0.067202225 0.28635806, -0.089781463 0.064512566 0.28480235, -0.088668346 0.065366372 0.28529602, -0.088576108 0.065690473 0.28548357, -0.088576049 0.066024318 0.2856766, -0.089420855 0.06463106 0.28487077, -0.089420959 0.067083791 0.28628954, -0.088847727 0.065070704 0.28512505, -0.088668406 0.066348538 0.28586435, -0.089103371 0.064820632 0.28498054, -0.088847622 0.066644296 0.28603512, -0.089103416 0.06689404 0.28617978, -0.080342054 0.077023789 0.2917406, -0.080162019 0.078001902 0.29274842, -0.080308899 0.076887295 0.29181057, -0.080116481 0.077812955 0.29293293, -0.080291376 0.076736972 0.29185373, -0.080287904 0.076579913 0.29186535, -0.080294579 0.076425418 0.29184228, -0.080307767 0.076279745 0.29178402, -0.11932348 0.11661962 0.2074334, -0.1194915 0.11557259 0.20679452, -0.11954528 0.11674938 0.20717891, -0.11980072 0.11573352 0.2064949, -0.11986512 0.11687633 0.20693202, -0.12017861 0.11586036 0.20626745, -0.12027751 0.11697866 0.20673592, -0.12047979 0.11592661 0.20615512, -0.12015694 0.11912553 0.20780551, -0.12015696 0.12028258 0.20838411, -0.11977743 0.11904557 0.20796563, -0.11977749 0.1202025 0.20854406, -0.11944366 0.11893187 0.20819271, -0.11944352 0.12008877 0.20877133, -0.11917028 0.11878951 0.20847747, -0.11917025 0.11994658 0.20905608, -0.15002324 -0.033077538 0.14016762, -0.15002321 -0.033077568 0.13476768, -0.14974196 -0.033428818 0.14016755, -0.14974189 -0.033428729 0.13476746, -0.14954615 -0.03383404 0.14016762, -0.14954618 -0.03383401 0.13476755, -0.14857681 -0.035287842 0.13515791, -0.14866595 -0.035271198 0.14016758, -0.14871682 -0.035257727 0.13512772, -0.14889562 -0.035186574 0.14016762, -0.14889382 -0.035187274 0.13505733, -0.14906596 -0.035075217 0.13494527, -0.14908442 -0.035060078 0.1401675, -0.1492265 -0.034911647 0.14016782, -0.14923704 -0.034897506 0.13476758, -0.14933351 -0.034740925 0.14016762, -0.14933018 -0.034747526 0.13476744, -0.14939576 -0.034582019 0.13476758, -0.14939782 -0.034575135 0.14016762, -0.15755729 -0.027956486 0.13476764, -0.15755738 -0.02795653 0.14016776, -0.1574968 -0.02814956 0.14016777, -0.15749684 -0.028149426 0.13476759, -0.15739857 -0.028326467 0.14016777, -0.15739855 -0.028326362 0.13476765, -0.15726671 -0.028480142 0.14016783, -0.1572668 -0.028479874 0.13476765, -0.15655734 -0.027401268 0.13676751, -0.15655744 -0.027401328 0.14016777, -0.15649676 -0.027594358 0.13676758, -0.1564967 -0.027594507 0.14016771, -0.15639858 -0.027771264 0.13676763, -0.15639849 -0.027771413 0.1401678, -0.1562667 -0.027924836 0.13676751, -0.15626669 -0.027924865 0.14016777, -0.11365971 -0.03257449 0.2164802, -0.099910647 0.077679113 0.28024882, -0.11372611 -0.032591358 0.21645296, -0.099988461 0.077678964 0.28022259, -0.11381279 -0.032623693 0.21639185, -0.1000618 0.077685133 0.28018224, -0.11391616 -0.032680735 0.2162725, -0.10012597 0.077697739 0.28012985, -0.10017762 0.077715471 0.28006876, -0.11426327 -0.033068731 0.21406573, -0.10035273 0.078452066 0.27857184, -0.11431636 -0.033067957 0.21407953, -0.1004248 0.078436688 0.27858511, -0.1143636 -0.033062533 0.21410315, -0.10050362 0.078412697 0.27861601, -0.11440898 -0.033052608 0.21413739, -0.1144509 -0.033037797 0.21418309, -0.10057458 0.078382447 0.27866483, -0.11448757 -0.033018246 0.21423931, -0.10063112 0.078347728 0.27872974, -0.11452618 -0.032985404 0.21432865, -0.11455283 -0.032941356 0.21444356, -0.10068497 0.078275755 0.27888671, -0.11456117 -0.032892898 0.21456522, -0.11454524 -0.032825038 0.21472938, -0.10068029 0.07824038 0.278974, -0.10306481 0.080816701 0.27386728, -0.11719036 -0.032680467 0.20827746, -0.10301307 0.080798641 0.27392814, -0.10294886 0.080786303 0.27398074, -0.11708722 -0.032623157 0.20839685, -0.10287556 0.080780104 0.27402088, -0.1170003 -0.03259097 0.20845774, -0.10279787 0.080780134 0.27404726, -0.11693397 -0.032574043 0.20848499, -0.11781114 -0.032807782 0.2067741, -0.11783056 -0.032856539 0.20665789, -0.11783431 -0.03291209 0.20652133, -0.11781591 -0.032964066 0.20638831, -0.11778076 -0.033003911 0.20628253, -0.10347019 0.081479445 0.27247107, -0.11774448 -0.033027992 0.20621513, -0.1033989 0.081510946 0.27241874, -0.11770168 -0.033046469 0.20616037, -0.11765416 -0.033059254 0.20611852, -0.10331412 0.081537321 0.27238381, -0.11760391 -0.033066437 0.20608988, -0.10324259 0.081552878 0.27237064, -0.10595202 0.083917841 0.26766557, -0.12046479 -0.032679901 0.20028244, -0.10590039 0.083900079 0.26772648, -0.10583615 0.083887503 0.26777899, -0.12036149 -0.032622799 0.20040171, -0.10576285 0.083881155 0.2678192, -0.12027462 -0.032590523 0.20046265, -0.10568504 0.083881542 0.26784569, -0.12020822 -0.032573566 0.20048979, -0.12108533 -0.032807365 0.19877915, -0.12110476 -0.032855973 0.1986628, -0.12110849 -0.032911703 0.19852604, -0.12108998 -0.032963768 0.19839327, -0.12105511 -0.033003435 0.19828759, -0.10635734 0.084580526 0.26626951, -0.12101881 -0.033027455 0.19822018, -0.10628605 0.084612116 0.26621717, -0.1209759 -0.033046022 0.19816522, -0.12092835 -0.033058718 0.19812351, -0.10620129 0.084638342 0.26618224, -0.1208782 -0.033066019 0.19809489, -0.10612983 0.084653959 0.26616889, -0.10883912 0.087019101 0.261464, -0.12373891 -0.032679513 0.19228742, -0.10878763 0.087001219 0.2615248, -0.10872337 0.086988822 0.26157737, -0.12363574 -0.032622263 0.19240662, -0.10865004 0.086982593 0.26161778, -0.12354892 -0.032590106 0.19246751, -0.10857226 0.086982533 0.26164424, -0.12348254 -0.032573178 0.19249482, -0.1243595 -0.032806873 0.1907839, -0.12437905 -0.032855511 0.19066779, -0.12438267 -0.032911122 0.19053105, -0.12436432 -0.032963291 0.19039789, -0.12432922 -0.033003092 0.19029252, -0.10924444 0.087681785 0.26006794, -0.12429295 -0.033027202 0.19022492, -0.1091733 0.087713405 0.26001543, -0.1242501 -0.033045709 0.19016995, -0.12420265 -0.03305833 0.19012846, -0.10908839 0.087739721 0.2599808, -0.12415253 -0.033065647 0.19009961, -0.10901704 0.087755218 0.25996739, -0.11172633 0.09012039 0.25526252, -0.12701315 -0.032679006 0.18429206, -0.11167473 0.090102568 0.25532329, -0.11161046 0.090090111 0.25537577, -0.12690987 -0.032622024 0.18441123, -0.11153716 0.090083703 0.25541595, -0.1268232 -0.032589734 0.18447241, -0.11145942 0.090084001 0.25544256, -0.12675668 -0.03257288 0.18449965, -0.12763374 -0.032806456 0.18278891, -0.12765332 -0.032855153 0.18267265, -0.127657 -0.03291069 0.18253592, -0.12763855 -0.032962978 0.18240301, -0.1276034 -0.033002511 0.18229726, -0.11213179 0.09078303 0.25386631, -0.1275674 -0.033026561 0.18222985, -0.11206038 0.090814501 0.2538141, -0.12752427 -0.033045098 0.18217498, -0.12747683 -0.033057764 0.1821332, -0.11197571 0.090840876 0.25377929, -0.12742677 -0.033065051 0.18210453, -0.1119042 0.090856433 0.25376579, -0.1146134 0.093221471 0.24906081, -0.13028747 -0.032678738 0.17629708, -0.11456186 0.093203738 0.24912165, -0.1144976 0.093191102 0.24917404, -0.13018419 -0.032621533 0.17641622, -0.11442432 0.093184918 0.24921453, -0.1300973 -0.032589421 0.176477, -0.11434647 0.093185037 0.24924076, -0.13003096 -0.032572553 0.17650469, -0.13090803 -0.032806054 0.1747936, -0.13092753 -0.032854587 0.17467763, -0.13093129 -0.032910332 0.17454095, -0.1309128 -0.032962456 0.17440784, -0.1308777 -0.033002049 0.174302, -0.11501876 0.093884245 0.24766456, -0.13084148 -0.033026263 0.17423484, -0.11494754 0.093915865 0.2476123, -0.1307985 -0.033044666 0.17417988, -0.13075098 -0.033057362 0.17413796, -0.11486283 0.09394218 0.24757753, -0.13070099 -0.033064634 0.17410952, -0.11479124 0.093957737 0.24756409, -0.13418235 -0.032805547 0.1667985, -0.13420179 -0.032854125 0.16668238, -0.13420549 -0.032909796 0.16654576, -0.13418701 -0.032961905 0.1664127, -0.13415194 -0.033001706 0.16630696, -0.11790594 0.09698543 0.24146318, -0.13411567 -0.033025682 0.16623966, -0.1178347 0.09701699 0.2414106, -0.13407278 -0.033044204 0.16618474, -0.13402531 -0.033056974 0.16614293, -0.11774994 0.097043335 0.24137591, -0.13397531 -0.033064187 0.1661143, -0.11767848 0.097058937 0.24136245, -0.11750065 0.096322849 0.24285915, -0.13356161 -0.032678291 0.16830193, -0.11744893 0.096305013 0.24292016, -0.11738478 0.09629254 0.24297243, -0.13345835 -0.032621071 0.16842104, -0.11731155 0.096286297 0.24301283, -0.13337153 -0.032588825 0.16848193, -0.11723359 0.096286461 0.24303925, -0.13330524 -0.032572046 0.16850948, -0.12038788 0.099423915 0.23665768, -0.13683586 -0.032677874 0.16030671, -0.12033634 0.099406213 0.23671855, -0.12027194 0.099393547 0.23677103, -0.13673261 -0.032620609 0.16042605, -0.12019879 0.099387378 0.23681119, -0.13664585 -0.032588512 0.16048685, -0.12012091 0.099387527 0.23683757, -0.13657948 -0.032571554 0.16051447, -0.13745654 -0.03280513 0.15880331, -0.13747598 -0.032853797 0.15868749, -0.13747971 -0.032909453 0.15855069, -0.1374612 -0.032961667 0.1584177, -0.13742618 -0.033001289 0.15831174, -0.12079312 0.10008663 0.23526137, -0.13738999 -0.033025295 0.15824455, -0.12072194 0.10011831 0.23520902, -0.13734701 -0.033043802 0.15818968, -0.13729949 -0.033056587 0.15814792, -0.12063713 0.10014462 0.23517434, -0.13724945 -0.03306374 0.1581192, -0.12056568 0.10016018 0.23516092, -0.12327501 0.10252526 0.23045605, -0.14011018 -0.032677382 0.1523117, -0.1232235 0.10250734 0.23051685, -0.12315913 0.10249496 0.23056941, -0.14000691 -0.032620251 0.15243082, -0.12308583 0.10248859 0.23060979, -0.13992016 -0.03258802 0.15249176, -0.12300795 0.10248888 0.23063606, -0.13985375 -0.032571048 0.15251914, -0.14073078 -0.032804713 0.1508082, -0.14075033 -0.032853454 0.15069224, -0.14075397 -0.032909021 0.15055555, -0.14073549 -0.032960951 0.15042256, -0.14070049 -0.033000752 0.15031669, -0.12368031 0.10318786 0.22905986, -0.14066428 -0.033024862 0.15024936, -0.12360904 0.10321946 0.22900756, -0.14062135 -0.03304325 0.15019439, -0.1405739 -0.03305608 0.15015285, -0.12352431 0.10324566 0.22897278, -0.14052379 -0.033063188 0.15012407, -0.12345289 0.10326131 0.22895923, -0.14400493 -0.032804325 0.14281322, -0.14402451 -0.032852992 0.14269702, -0.14402822 -0.032908648 0.14256042, -0.14400974 -0.032960743 0.14242738, -0.14397472 -0.033000544 0.14232165, -0.12656745 0.10628898 0.22285835, -0.1439385 -0.033024475 0.14225434, -0.12649618 0.10632065 0.22280581, -0.14389552 -0.033043012 0.1421992, -0.14384803 -0.033055753 0.14215769, -0.12641148 0.10634688 0.22277124, -0.1437978 -0.03306295 0.1421289, -0.12633999 0.10636252 0.22275774, -0.12616223 0.10562639 0.22425427, -0.14338438 -0.03267695 0.14431663, -0.12611063 0.10560864 0.22431521, -0.12604639 0.10559602 0.22436769, -0.14328115 -0.03261973 0.14443584, -0.12597305 0.10558973 0.22440808, -0.14319432 -0.032587618 0.14449656, -0.12589525 0.10558996 0.22443439, -0.1431279 -0.032570675 0.14452408, -0.1287825 0.10869126 0.21823275, -0.12886024 0.10869107 0.21820652, -0.12893352 0.10869738 0.21816617, -0.1289978 0.1087099 0.21811378, -0.12904942 0.10872777 0.21805273, -0.12922446 0.10946423 0.21655576, -0.14581999 -0.022850677 0.14004979, -0.12929654 0.10944873 0.21656892, -0.12937534 0.10942477 0.21659991, -0.14587826 -0.022662118 0.14021166, -0.12944616 0.10939464 0.21664901, -0.12950301 0.10935992 0.21671399, -0.12955676 0.10928781 0.21687052, -0.12955223 0.10925257 0.21695803, -0.13093072 -0.033226877 0.13847329, -0.1130887 0.10856451 0.22061011, -0.13077444 -0.033277541 0.13858892, -0.11295444 0.10854864 0.22076868, -0.13064447 -0.033338055 0.13873334, -0.1128889 0.10851996 0.22086662, -0.13092333 -0.033347741 0.13844074, -0.13092493 -0.033286288 0.13845402, -0.13077137 -0.033404022 0.13856174, -0.13064291 -0.033402219 0.13871932, -0.13045144 -0.034618959 0.13885099, -0.13056478 -0.034637094 0.13870585, -0.084474429 0.051997408 0.27537483, -0.084429055 0.052001879 0.27535719, -0.084389314 0.05201225 0.27533066, -0.084357485 0.052027747 0.27529693, -0.084335625 0.052047566 0.27525812, -0.084324822 0.052070245 0.27521628, -0.08432585 0.052094772 0.2751742, -0.084426865 0.051472083 0.27497572, -0.08440493 0.051491812 0.27493668, -0.084458694 0.051456645 0.27500927, -0.084498316 0.051446244 0.2750358, -0.084543809 0.051441744 0.27505326, -0.084345058 0.051886424 0.27510419, -0.0843952 0.051539227 0.27485281, -0.084394231 0.05151473 0.27489507, -0.084366933 0.051848933 0.27517694, -0.084420308 0.05182223 0.27523673, -0.090276971 0.0055131465 0.24848816, -0.090231746 0.0055176467 0.24847028, -0.090191871 0.0055279285 0.24844398, -0.090160191 0.0055434555 0.24841042, -0.090138286 0.0055631548 0.24837132, -0.090127468 0.0055860728 0.2483297, -0.090128452 0.0056106597 0.24828734, -0.090229571 0.0049877614 0.24808876, -0.090207472 0.0050074607 0.24804994, -0.090261355 0.0049723238 0.24812253, -0.090301037 0.0049619228 0.2481489, -0.090346366 0.0049573928 0.2481667, -0.090147838 0.0054021031 0.24821763, -0.090197712 0.0050550252 0.24796595, -0.090196729 0.0050303489 0.24800812, -0.090169579 0.005364731 0.2482902, -0.090222985 0.0053380579 0.24835002, -0.09509334 -0.033582494 0.22584085, -0.095076114 -0.033586428 0.22582178, -0.095060751 -0.033593431 0.22579783, -0.095047653 -0.033603534 0.22576916, -0.095034957 -0.033621624 0.22572483, -0.0950277 -0.033647701 0.2256678, -0.095030308 -0.033688977 0.22558622, -0.095041439 -0.03372474 0.22552145, -0.14647318 -0.024399385 0.13670087, -0.14696966 -0.028376892 0.13670093, -0.1464951 -0.024396583 0.13663748, -0.1469916 -0.028374285 0.13663748, -0.14653054 -0.024392202 0.13658071, -0.14702708 -0.028369814 0.13658065, -0.14657776 -0.024386331 0.13653331, -0.14707434 -0.028363928 0.13653326, -0.14663409 -0.024379313 0.13649738, -0.1471307 -0.028356805 0.13649732, -0.14669706 -0.024371356 0.13647521, -0.14719352 -0.028348967 0.13647512, -0.09472473 -0.034625664 0.22972549, -0.11072916 -0.034669772 0.22968511, -0.09474729 -0.034857556 0.2294831, -0.11080003 -0.034964159 0.22933857, -0.094775409 -0.035099104 0.22910415, -0.11089192 -0.03517203 0.22893611, -0.094799548 -0.035250857 0.22867708, -0.11097585 -0.035268232 0.22859469, -0.080892429 0.078616187 0.29320747, -0.097234324 0.078575924 0.29326069, -0.080837458 0.078451082 0.29340526, -0.080808386 0.078256294 0.29358441, -0.080804974 0.078032717 0.29374066, -0.09698315 0.077595696 0.29393643, -0.080820769 0.077675149 0.29390973, -0.080840752 0.07729204 0.29400536, -0.096933067 0.07720153 0.29401648, -0.080866814 0.076854095 0.29402101, -0.096903801 0.076799318 0.29401597, -0.08089532 0.076430276 0.29394275, -0.096896619 0.076405481 0.29393524, -0.096902236 0.076198623 0.29385775, -0.080495551 0.076470211 0.29166725, -0.080487892 0.076554462 0.29168987, -0.082670256 0.077216581 0.28666717, -0.082545891 0.077019796 0.28693837, -0.082347646 0.076616392 0.28734684, -0.082169995 0.076128915 0.287678, -0.082024246 0.075581416 0.28790939, -0.081919163 0.075006381 0.28802752, -0.081857592 0.074436769 0.28803265, -0.093596607 0.079154506 0.27312246, -0.093438119 0.079196945 0.27316761, -0.10733929 -0.032576248 0.20852734, -0.093199879 0.079280004 0.27327168, -0.1069821 -0.032596692 0.20862892, -0.09292078 0.079380259 0.27343524, -0.10500045 -0.03305237 0.21410845, -0.091076091 0.07752274 0.27809525, -0.10463814 -0.033031777 0.21423383, -0.090749085 0.077767208 0.27834672, -0.13684431 -0.032867461 0.13640031, -0.11917602 0.10867375 0.21826878, -0.13648604 -0.032879755 0.13650705, -0.11882307 0.10862032 0.21835154, -0.13781011 -0.032399416 0.13450767, -0.1199529 0.1094687 0.21658939, -0.13760076 -0.032464311 0.13451029, -0.11959732 0.10943404 0.21668299, -0.13732946 -0.03261818 0.13451923, -0.13353325 -0.032572761 0.1445663, -0.1162889 0.10557261 0.22447051, -0.13317595 -0.032593295 0.14466789, -0.11593574 0.10551918 0.22455333, -0.13446859 -0.033048451 0.14215225, -0.11706574 0.10636736 0.22279124, -0.13410617 -0.033028021 0.1422774, -0.11671023 0.10633281 0.22288463, -0.13025904 -0.032573164 0.15256135, -0.11340164 0.1024714 0.23067208, -0.12990184 -0.032593742 0.15266317, -0.11304864 0.10241792 0.23075475, -0.13119449 -0.033048704 0.15014726, -0.11417851 0.10326616 0.22899288, -0.13083208 -0.033028424 0.15027265, -0.11382297 0.10323159 0.22908616, -0.12698476 -0.032573715 0.1605566, -0.11051446 0.099370211 0.2368737, -0.12662755 -0.032594264 0.16065826, -0.11016145 0.099316716 0.2369564, -0.12792018 -0.033049196 0.1581424, -0.11129138 0.10016495 0.23519461, -0.12755775 -0.033028618 0.15826778, -0.1109359 0.10013026 0.23528795, -0.12371056 -0.032574147 0.16855162, -0.1076273 0.096268982 0.2430755, -0.12335341 -0.032594576 0.16865337, -0.1072742 0.096215397 0.24315806, -0.12464592 -0.033049688 0.16613747, -0.10840414 0.09706372 0.24139583, -0.12428375 -0.033029154 0.16626304, -0.10804875 0.09702915 0.24148956, -0.12043637 -0.032574609 0.1765469, -0.1047401 0.093167663 0.24927694, -0.12007913 -0.032595024 0.17664841, -0.10438696 0.093114212 0.2493594, -0.12137172 -0.03305006 0.17413251, -0.10551687 0.093962505 0.24759768, -0.12100933 -0.033029512 0.17425819, -0.10516146 0.09392792 0.24769114, -0.11716214 -0.032575026 0.18454216, -0.10185301 0.090066537 0.25547838, -0.1168049 -0.032595426 0.1846437, -0.10149996 0.090013012 0.25556126, -0.11809747 -0.033050627 0.18212762, -0.10262965 0.090861097 0.2537992, -0.1177351 -0.033030063 0.18225326, -0.10227422 0.090826705 0.25389248, -0.10827465 -0.033051863 0.20611322, -0.093968213 0.081557527 0.27240387, -0.10791239 -0.033031419 0.2062386, -0.093612745 0.081522986 0.27249736, -0.11482318 -0.03305091 0.19012278, -0.099742606 0.087760016 0.26000071, -0.11446081 -0.033030391 0.19024827, -0.099387124 0.087725475 0.2600944, -0.11388788 -0.032575265 0.19253708, -0.098965764 0.086965248 0.26168019, -0.11353071 -0.032595798 0.19263889, -0.098612636 0.086911753 0.26176292, -0.11154906 -0.033051267 0.19811806, -0.096855476 0.084658816 0.26620242, -0.11118661 -0.033030912 0.19824344, -0.096499994 0.084624186 0.266296, -0.11061352 -0.032575712 0.20053227, -0.09607853 0.083863989 0.2678819, -0.11025636 -0.032596275 0.2006339, -0.095725447 0.083810523 0.26796433, -0.10406508 -0.032576576 0.21652262, -0.090304255 0.077661619 0.280285, -0.10370784 -0.032597139 0.21662416, -0.089951038 0.077608094 0.28036749, -0.096937671 0.07682021 0.27761239, -0.096937805 0.076904252 0.27763507, -0.097329363 0.077237263 0.27767187, -0.09737888 0.077125743 0.2777023, -0.097062796 0.076828435 0.27761686, -0.097244173 0.076863721 0.27763674, -0.09742415 0.077038333 0.27770478, -0.097193807 0.077041104 0.27766109, -0.097218186 0.076950744 0.27765748, -0.097291946 0.077342495 0.27761316, -0.097052768 0.076914772 0.27763927, -0.097167015 0.077155635 0.277641, -0.097269341 0.07743372 0.27753031, -0.097043246 0.077003732 0.2776458, -0.097146004 0.077263311 0.27759349, -0.09703283 0.077116534 0.2776309, -0.097262517 0.077503756 0.27743131, -0.097132206 0.077357456 0.27752215, -0.097024471 0.077222899 0.27759072, -0.097270131 0.077549741 0.27732712, -0.097431511 0.077682868 0.27734587, -0.097430557 0.077681735 0.27734876, -0.097126141 0.077431634 0.27743334, -0.097018525 0.07731767 0.27752739, -0.097127721 0.07748206 0.27733582, -0.0970155 0.077394113 0.27744651, -0.097015262 0.07744883 0.27735555, -0.097472519 0.076955393 0.27768886, -0.098608106 0.079041794 0.27813184, -0.098607153 0.079040721 0.27813494, -0.098984331 0.078625575 0.27863067, -0.098984361 0.078541204 0.27860802, -0.098833203 0.07914643 0.27833539, -0.098696068 0.079105809 0.27824914, -0.098833084 0.079067633 0.27845603, -0.098696083 0.079054728 0.2783615, -0.098833054 0.078956559 0.27854753, -0.098696113 0.078972384 0.27845341, -0.098833084 0.078822955 0.27860188, -0.098696142 0.078866199 0.27851671, -0.098833025 0.078679428 0.27861351, -0.10028379 0.078541204 0.27860814, -0.10028377 0.078625515 0.27863055, -0.10075045 0.078811571 0.27880317, -0.10081783 0.078759447 0.27890727, -0.10082778 0.078893259 0.27877927, -0.10047448 0.078588292 0.27866822, -0.10055101 0.078560516 0.27871245, -0.10048825 0.078675732 0.2786817, -0.10042299 0.078915074 0.27860683, -0.10044536 0.079009846 0.2785511, -0.10057008 0.078647062 0.27873033, -0.10060784 0.078755215 0.27873385, -0.10063952 0.078611895 0.27879608, -0.10068655 0.078716025 0.27880871, -0.10047007 0.079088971 0.2784757, -0.10059476 0.078983232 0.27860171, -0.1006431 0.079059586 0.2785334, -0.10078967 0.079015777 0.27862054, -0.10090646 0.078832403 0.27890086, -0.10096097 0.078736946 0.27909309, -0.10100567 0.078886077 0.2788797, -0.10106799 0.078774825 0.27910304, -0.10040444 0.078809485 0.27864021, -0.10074452 0.078671053 0.27889842, -0.10055125 0.078890547 0.27865088, -0.10054219 0.078476235 0.27868205, -0.1004678 0.078503534 0.27864021, -0.1010614 0.078692481 0.27926779, -0.10100603 0.078611895 0.27942699, -0.10072076 0.078944609 0.2786774, -0.10061586 0.078527138 0.27877325, -0.1009143 0.078956708 0.27873856, -0.10086513 0.078678414 0.27907223, -0.10039055 0.07869868 0.27864963, -0.10069051 0.078572109 0.27887496, -0.1009562 0.078666434 0.27923596, -0.10090432 0.078594342 0.27937073, -0.10051495 0.078786239 0.27867788, -0.10060525 0.078443691 0.27874047, -0.10065913 0.078856215 0.27871573, -0.10066366 0.078490123 0.27884698, -0.10038307 0.078610733 0.2786395, -0.10078558 0.078602329 0.27904135, -0.10086185 0.078618988 0.27919543, -0.10081413 0.078552917 0.27930814, -0.10065138 0.078407809 0.27881175, -0.10072666 0.078512773 0.27900141, -0.10078332 0.07855244 0.27914834, -0.10074043 0.078489468 0.2792421, -0.10037959 0.078526065 0.27861434, -0.10069695 0.078435734 0.27896553, -0.1007247 0.078470334 0.27909684, -0.10068733 0.078407869 0.27917665, -0.10068291 0.078355655 0.27892691, -0.10069457 0.078397408 0.27905521, -0.10065791 0.078312293 0.2791152, -0.10067961 0.078319982 0.27901378, -0.10056731 0.078140572 0.28036916, -0.10046566 0.078123257 0.28031319, -0.10037547 0.078081712 0.28025037, -0.10030179 0.078018382 0.28018457, -0.10024875 0.077936694 0.28011906, -0.10021916 0.077841297 0.28005755, -0.10040045 0.078026697 0.28059894, -0.10013559 0.077946737 0.28076023, -0.10021119 0.07790868 0.28019017, -0.10025951 0.07798411 0.28026384, -0.10019901 0.077952698 0.28033844, -0.10032621 0.07803984 0.28034085, -0.10025546 0.078001037 0.28042525, -0.10032403 0.078026339 0.28051406, -0.10009602 0.077957705 0.28065726, -0.099984378 0.077926174 0.28080195, -0.099833161 0.077919438 0.28081626, -0.10018331 0.077817544 0.28012395, -0.10015732 0.077883407 0.28025758, -0.10006049 0.077944472 0.28055295, -0.099964827 0.077940181 0.28069544, -0.09983325 0.077934489 0.28070962, -0.10013244 0.077797011 0.28018677, -0.10003063 0.077907816 0.28045291, -0.099947304 0.077930585 0.28058809, -0.09983325 0.077926442 0.28060216, -0.10000813 0.077849492 0.28036189, -0.099932492 0.077897415 0.28048533, -0.099833161 0.077895477 0.28049904, -0.099993855 0.077772096 0.28028363, -0.099921197 0.077843145 0.28039217, -0.099833056 0.077843115 0.28040498, -0.099833101 0.077771977 0.28032437, -0.10049859 0.078081205 0.28048927, -0.099913806 0.077769414 0.28031212, -0.10040766 0.078072891 0.28041774, -0.090666056 0.077919558 0.2808162, -0.090666056 0.077934638 0.28070959, -0.090666056 0.077926353 0.28060222, -0.090665907 0.077895507 0.28049916, -0.090666026 0.077843323 0.2804049, -0.090666145 0.077772036 0.28032419, -0.089956284 0.077699736 0.28042853, -0.08996971 0.077777013 0.28050685, -0.089990973 0.077835217 0.28059864, -0.090019017 0.077871516 0.28069931, -0.090052217 0.077884331 0.28080413, -0.090089172 0.077872887 0.2809076, -0.089827746 0.078304902 0.27918324, -0.089855522 0.078419462 0.27916706, -0.089811891 0.078528419 0.2791768, -0.089864641 0.078531966 0.27912927, -0.089794993 0.078682169 0.27909112, -0.089728028 0.078680143 0.27914226, -0.090529263 0.078288987 0.2785629, -0.09051998 0.078176484 0.27860034, -0.090492234 0.078061894 0.27861691, -0.091699034 0.077105001 0.27777171, -0.091928363 0.077453747 0.27766496, -0.091887757 0.077368751 0.27772406, -0.091834247 0.077279404 0.27776277, -0.091770157 0.077189937 0.27777886, -0.091133356 0.077599868 0.2781105, -0.091183469 0.077681735 0.27810892, -0.091256693 0.077849671 0.27805758, -0.091277719 0.077930555 0.27800977, -0.090793923 0.077843234 0.27835584, -0.090830848 0.0779223 0.27835208, -0.090878457 0.078081504 0.27830729, -0.090888143 0.078158483 0.27826726, -0.09196201 0.077427015 0.27764952, -0.091921329 0.077341869 0.27770841, -0.091867685 0.077252463 0.27774704, -0.091803715 0.077163056 0.27776346, -0.091732502 0.077078059 0.27775621, -0.092276514 0.0774308 0.27742112, -0.09227109 0.077351555 0.27751791, -0.09210591 0.077373043 0.27757743, -0.092078879 0.077277467 0.27764273, -0.092258334 0.077249661 0.27759334, -0.092439488 0.076820239 0.27761263, -0.092175752 0.076844051 0.27762723, -0.092194825 0.076920971 0.27764857, -0.092439458 0.076904252 0.27763519, -0.092214108 0.077006891 0.27765667, -0.091923028 0.076923564 0.27767408, -0.092238903 0.077131882 0.27764091, -0.091958165 0.076989397 0.27769184, -0.091994166 0.077063307 0.27769804, -0.092041045 0.077172115 0.27768397, -0.094332203 0.081642553 0.27240649, -0.094332278 0.081726864 0.27242905, -0.093473822 0.082132086 0.27239197, -0.093509942 0.082058653 0.27246195, -0.093542472 0.081970647 0.27251431, -0.093570292 0.081872419 0.27254695, -0.093591645 0.081767783 0.27255782, -0.093603671 0.081683829 0.27255148, -0.093610823 0.081601456 0.27253109, -0.093943179 0.081946328 0.2724458, -0.10317095 0.081642494 0.27240643, -0.10317086 0.081726804 0.27242911, -0.10360868 0.082045659 0.27247629, -0.10352272 0.082162604 0.27232838, -0.10367773 0.082116827 0.27241978, -0.10347532 0.082086042 0.27239728, -0.10327297 0.081800744 0.27244705, -0.10328625 0.08191146 0.27243733, -0.10339743 0.08188878 0.27247405, -0.10330397 0.082017168 0.27240384, -0.10343266 0.081993148 0.27244657, -0.10354686 0.081957266 0.27251476, -0.10326599 0.081712916 0.2724371, -0.10337113 0.081778184 0.2724781, -0.10326241 0.081628218 0.27241206, -0.10349567 0.081856355 0.27253255, -0.10335761 0.081690833 0.27246469, -0.10345779 0.081748202 0.27252901, -0.10335122 0.081606045 0.27243721, -0.10343875 0.081661656 0.27251112, -0.1034299 0.081577435 0.27248085, -0.10334885 0.082191035 0.27227217, -0.10332523 0.082111999 0.27234769, -0.10310631 0.080942467 0.27385581, -0.103136 0.081037924 0.27391738, -0.10318913 0.081119493 0.27398288, -0.10326274 0.081182823 0.27404889, -0.10335286 0.081224397 0.27411163, -0.10345444 0.081241682 0.27416775, -0.1032877 0.081127807 0.27439737, -0.1030228 0.081047848 0.27455866, -0.10309845 0.08100979 0.2739886, -0.10314684 0.08108528 0.27406204, -0.10308608 0.081053689 0.27413663, -0.10321356 0.08114107 0.27413952, -0.10314259 0.081102207 0.27422377, -0.10321118 0.08112736 0.27431226, -0.10298322 0.081058934 0.27445555, -0.10287151 0.081027344 0.27460024, -0.10272045 0.081020549 0.27461457, -0.10307056 0.080918774 0.27392256, -0.1030446 0.080984667 0.27405593, -0.10294767 0.081045702 0.27435148, -0.10285217 0.08104144 0.27449369, -0.10272045 0.081035689 0.27450812, -0.10301967 0.080898359 0.27398527, -0.10291785 0.081008837 0.27425116, -0.10283454 0.081031546 0.27438638, -0.10272045 0.081027523 0.27440086, -0.10289519 0.080950573 0.27416015, -0.10281964 0.080998674 0.2742838, -0.10272034 0.080996618 0.27429757, -0.10288094 0.080873325 0.2740823, -0.10280831 0.080944285 0.2741904, -0.10272036 0.080944255 0.27420342, -0.10272029 0.080873027 0.27412269, -0.10338576 0.081182346 0.27428755, -0.10280089 0.080870464 0.27411044, -0.10329491 0.08117412 0.27421606, -0.10068196 0.081020579 0.27461457, -0.10068198 0.081035629 0.27450815, -0.10068198 0.081027523 0.27440086, -0.10068186 0.080996588 0.27429748, -0.10068186 0.080944255 0.27420342, -0.10068183 0.080873117 0.27412271, -0.10058554 0.080841437 0.27410808, -0.10041516 0.080895558 0.27426931, -0.10054238 0.080934033 0.27422354, -0.10049486 0.080878481 0.27417946, -0.10054238 0.080995873 0.27435398, -0.1003512 0.080891445 0.27437234, -0.10041383 0.080917314 0.2743111, -0.10054231 0.081016049 0.27449703, -0.10041398 0.080953941 0.27443302, -0.099174619 0.07953237 0.27358627, -0.099238634 0.079536542 0.27348328, -0.099318266 0.079519555 0.27339351, -0.099408939 0.079482391 0.27332187, -0.099179193 0.07941772 0.27335081, -0.099019676 0.079336599 0.27331272, -0.099056885 0.079293266 0.27323756, -0.099230573 0.079383865 0.27328607, -0.098945111 0.079376057 0.27354369, -0.098799631 0.079329506 0.2735506, -0.098817751 0.079323784 0.27340993, -0.098980278 0.079368547 0.273415, -0.099124357 0.07944198 0.27344072, -0.098923847 0.079351202 0.27367172, -0.099073336 0.079445854 0.27355632, -0.09863545 0.079299524 0.2736192, -0.098635301 0.07922323 0.2732079, -0.0988819 0.079172835 0.27313775, -0.098635435 0.079152033 0.27312714, -0.098859429 0.079238757 0.273211, -0.099097639 0.079236224 0.27317312, -0.098635405 0.079306319 0.27340505, -0.098838851 0.07928814 0.27329573, -0.098635331 0.079275563 0.27330196, -0.098635346 0.079314366 0.27351233, -0.099286139 0.079338238 0.27323133, -0.094136983 0.079151973 0.27312693, -0.094137102 0.079223111 0.2732079, -0.094136953 0.079275504 0.27330193, -0.094136983 0.079306319 0.27340519, -0.094137028 0.079314336 0.27351236, -0.094136909 0.079299256 0.27361906, -0.093798637 0.079207137 0.27316141, -0.093833879 0.079277322 0.27324879, -0.093890429 0.079346851 0.27346373, -0.093865156 0.079324827 0.27335143, -0.09390901 0.079342917 0.27357975, -0.093919307 0.079312667 0.27369261, -0.093655497 0.079377428 0.27389374, -0.09326981 0.079358891 0.27330676, -0.093491226 0.079273656 0.27321315, -0.093342766 0.07942225 0.27336097, -0.093544379 0.079335853 0.27327436, -0.09341535 0.07946755 0.2734319, -0.093595698 0.079381749 0.27334833, -0.093544796 0.079495117 0.27360868, -0.093643516 0.07941021 0.27343178, -0.093483865 0.079492167 0.27351582, -0.093595326 0.079476193 0.27370572, -0.093692303 0.079420164 0.2735368, -0.093632817 0.079436406 0.27380216, -0.093735933 0.079401597 0.27365971, -0.093764052 0.079352394 0.27377725, -0.093430176 0.079504713 0.27404243, -0.093217358 0.079598501 0.27420822, -0.093170077 0.079669878 0.2741223, -0.093395814 0.07957007 0.27395189, -0.093346462 0.079613402 0.27385655, -0.093107969 0.079716757 0.27402949, -0.093285292 0.079632774 0.27376056, -0.093034729 0.079736724 0.27393481, -0.092954665 0.079728439 0.27384424, -0.093214393 0.079627231 0.27366841, -0.092872098 0.07969217 0.27376294, -0.093137965 0.079596654 0.27358517, -0.092792377 0.079630449 0.27369598, -0.093060613 0.07954298 0.2735163, -0.092719883 0.079546586 0.27364683, -0.092987001 0.079469159 0.27346563, -0.091297001 0.080289856 0.2758621, -0.091260314 0.080354318 0.27579129, -0.091212437 0.080402449 0.27571449, -0.091149464 0.080433533 0.27562714, -0.09107852 0.080440983 0.27554095, -0.091003329 0.080424383 0.27545989, -0.090927333 0.080384269 0.275388, -0.090854764 0.080322966 0.27532887, -0.090788826 0.080243483 0.27528557, -0.090924948 0.080445543 0.27554631, -0.091035351 0.080457523 0.27566257, -0.091017485 0.080438808 0.27550364, -0.091096669 0.080422357 0.27580202, -0.090990737 0.080457374 0.27569258, -0.091086671 0.08045049 0.27564844, -0.091138616 0.080437347 0.27565199, -0.091184735 0.080419645 0.27567279, -0.091156408 0.08041735 0.27575943, -0.091241032 0.080361947 0.27580464, -0.091224581 0.080348805 0.27585375, -0.091192275 0.080341801 0.27589619, -0.090778455 0.080283359 0.27532783, -0.090905905 0.080382898 0.27539194, -0.090958357 0.080450401 0.27573466, -0.14646424 -0.024392307 0.13908741, -0.14646222 -0.024385989 0.13910553, -0.14645791 -0.024380028 0.13913187, -0.14645399 -0.024378955 0.1391494, -0.1464491 -0.024380818 0.13916492, -0.080516234 0.075927392 0.29136789, -0.094190627 -0.033583716 0.22802512, -0.09415783 -0.033590183 0.2280331, -0.080474421 0.075916156 0.29137871, -0.094125211 -0.033599541 0.22804655, -0.080436602 0.075900689 0.29139721, -0.094102919 -0.03360717 0.2280602, -0.094082966 -0.033614323 0.2280775, -0.080405161 0.075881913 0.29142272, -0.094065458 -0.033620015 0.2280985, -0.080381408 0.075860634 0.29145432, -0.09404555 -0.033623829 0.22813366, -0.080366731 0.075837985 0.29149029, -0.09402971 -0.033621505 0.22818071, -0.080463856 0.076385185 0.29163224, -0.080423132 0.076374784 0.29164207, -0.080386132 0.076360628 0.29165977, -0.080354974 0.076343045 0.291684, -0.080330893 0.076323017 0.29171354, -0.0803148 0.076301768 0.29174745, -0.080303118 0.076438352 0.29180312, -0.080319986 0.076450989 0.29176706, -0.080370948 0.076593503 0.29173133, -0.080375284 0.076473162 0.29170889, -0.080411524 0.076481923 0.29168957, -0.080406234 0.076595888 0.29171178, -0.080446243 0.076680318 0.29169998, -0.080445021 0.076597735 0.29169965, -0.080340371 0.076590464 0.29175764, -0.080344439 0.076462641 0.29173514, -0.08040823 0.076682433 0.2917116, -0.080315694 0.076587245 0.29178935, -0.08037357 0.076684996 0.2917304, -0.080297887 0.076583698 0.29182574, -0.08034341 0.076687828 0.2917555, -0.08045806 0.076783881 0.29168046, -0.080318674 0.076690927 0.29178607, -0.080420747 0.076791272 0.29169023, -0.080300376 0.076694116 0.29182145, -0.080471918 0.076844588 0.2916581, -0.080386892 0.076800212 0.29170647, -0.08053185 0.076991573 0.29156244, -0.080435321 0.076855376 0.29166573, -0.080490321 0.07701464 0.29156405, -0.080357119 0.076810583 0.2917293, -0.080401406 0.076868191 0.2916801, -0.080453679 0.077043161 0.2915743, -0.080402628 0.077109113 0.29161835, -0.080423847 0.077075198 0.29159299, -0.080332503 0.076821581 0.29175699, -0.080451354 0.07648842 0.29167813, -0.08037214 0.076882944 0.29170054, -0.080314025 0.076833293 0.29178983, -0.080347702 0.076898769 0.29172623, -0.080329463 0.076915368 0.2917566, -0.080582991 0.077045932 0.29149902, -0.08054556 0.07706596 0.29149568, -0.080612317 0.077075794 0.29145494, -0.080641717 0.077100649 0.29140797, -0.080511823 0.077091351 0.29149818, -0.0805742 0.077096149 0.29144913, -0.080602735 0.077121124 0.29139996, -0.080567762 0.077149019 0.29139763, -0.080483139 0.077121064 0.2915071, -0.080539718 0.077122942 0.29144943, -0.080460519 0.077154025 0.29152143, -0.08051078 0.0771548 0.29145551, -0.080538407 0.077182665 0.29140079, -0.080516443 0.077220783 0.29140985, -0.080445066 0.077188388 0.29154086, -0.080488488 0.077190384 0.29146701, -0.080473885 0.077227935 0.29148388, -0.080502838 0.077261135 0.29142374, -0.1191127 0.11842375 0.20877302, -0.1190737 0.11844425 0.20876525, -0.11903867 0.11847214 0.20876265, -0.11900938 0.11850579 0.20876607, -0.11898734 0.1185438 0.20877492, -0.11897367 0.1185842 0.20878863, -0.11983666 0.11884038 0.20797193, -0.11952192 0.11873321 0.20818627, -0.1195507 0.11870678 0.2082071, -0.11985847 0.11881141 0.20799744, -0.11918734 0.11870475 0.20844816, -0.1192071 0.11866538 0.20844395, -0.12020835 0.1188852 0.20784986, -0.11947438 0.1188045 0.20816553, -0.11923304 0.1186295 0.20844597, -0.11949609 0.11876632 0.20817228, -0.11981699 0.11887567 0.20795345, -0.11917433 0.1187485 0.20846006, -0.12019449 0.11891584 0.20782101, -0.11945796 0.11884563 0.20816666, -0.11980063 0.1189156 0.20794332, -0.12018213 0.11895268 0.20779955, -0.11944704 0.11889048 0.20817618, -0.11978827 0.11895801 0.20794185, -0.12017161 0.1189938 0.20778668, -0.11978 0.11900382 0.2079494, -0.12016378 0.11903729 0.20778342, -0.12056671 0.11911018 0.2077011, -0.12015866 0.11908354 0.20778973, -0.1205658 0.11914007 0.20770818, -0.1192985 0.11857539 0.20846954, -0.11926407 0.1185991 0.20845473, -0.13668051 0.12001805 0.20588535, -0.13667969 0.12004793 0.20589256, -0.13752002 0.11972578 0.2062206, -0.13735586 0.11975928 0.20611259, -0.13748801 0.11969824 0.20623448, -0.13744357 0.11998849 0.20610791, -0.13724279 0.12004323 0.20599148, -0.13724165 0.12000281 0.20597428, -0.13699329 0.11983724 0.20595583, -0.13698676 0.1198179 0.20597857, -0.13744238 0.11994819 0.20608979, -0.13680512 0.12004144 0.2058827, -0.13754785 0.11975916 0.20621315, -0.13740361 0.11982472 0.20608035, -0.13738136 0.1197893 0.20609289, -0.13680521 0.11999916 0.20587635, -0.13700184 0.11986987 0.20592928, -0.13757029 0.11979716 0.20621258, -0.13742179 0.11986442 0.20607582, -0.13680518 0.11987896 0.20591006, -0.13680512 0.12008162 0.20589808, -0.1375865 0.11983781 0.20621914, -0.13743505 0.11990617 0.20607883, -0.13700929 0.1199076 0.20591021, -0.13680509 0.11991619 0.20589042, -0.13756192 0.11961146 0.20639184, -0.13701564 0.11994846 0.2058998, -0.13680518 0.11995669 0.20587876, -0.13746403 0.1196835 0.20624825, -0.13702016 0.11999124 0.20589802, -0.13758969 0.11962385 0.20638368, -0.13716927 0.11979006 0.20603502, -0.13759556 0.11987929 0.20623225, -0.13702291 0.12003358 0.20590547, -0.13762638 0.11964802 0.20637679, -0.13718227 0.11980836 0.20601386, -0.1376587 0.11967868 0.20637548, -0.13719952 0.11984022 0.20598975, -0.13702369 0.12007399 0.20592204, -0.13768446 0.11971433 0.2063798, -0.13721481 0.11987726 0.20597321, -0.137703 0.11975355 0.20639011, -0.13722721 0.1199178 0.20596486, -0.13762331 0.11952801 0.20655891, -0.13723627 0.11996047 0.2059651, -0.13771316 0.11979423 0.20640522, -0.13765323 0.11953719 0.20655695, -0.13733652 0.11974226 0.20613015, -0.13769317 0.1195574 0.2065582, -0.13772792 0.11958458 0.20656416, -0.13775592 0.11961776 0.20657438, -0.13777582 0.11965483 0.20658869, -0.13778663 0.11969467 0.20660606, -0.13680509 0.1198269 0.20596039, -0.13680509 0.11984621 0.2059375, -0.13780092 0.11786062 0.20534074, -0.13784967 0.11779624 0.20551792, -0.1377698 0.11787134 0.20536748, -0.13701473 0.11805505 0.20502937, -0.13690841 0.1180521 0.20503488, -0.13788401 0.11778253 0.20549762, -0.13782741 0.11784241 0.2053135, -0.13717853 0.11801487 0.20487514, -0.13735807 0.11799456 0.20492002, -0.13734968 0.11801693 0.2049565, -0.13717468 0.11803719 0.20491263, -0.13791324 0.1177617 0.20547581, -0.13784824 0.11781698 0.20528665, -0.13701485 0.11806077 0.20498538, -0.13690314 0.11805767 0.20499089, -0.13793631 0.11773446 0.20545304, -0.13762288 0.11793953 0.20526108, -0.1377355 0.11787388 0.20539212, -0.13716315 0.11805493 0.20499757, -0.13718115 0.11798473 0.20484307, -0.13786243 0.11778587 0.20526144, -0.13736345 0.11796489 0.20488882, -0.1379521 0.11770234 0.20543075, -0.13701476 0.1180564 0.20494097, -0.13689837 0.11805338 0.20494655, -0.13716923 0.11805087 0.20495453, -0.13765191 0.11794001 0.20522979, -0.13701475 0.1180428 0.20489889, -0.13689446 0.11803898 0.20490426, -0.13767825 0.1179319 0.20519701, -0.13701475 0.11801991 0.2048606, -0.13689147 0.11801554 0.20486614, -0.13770051 0.11791566 0.20516488, -0.13701475 0.11798933 0.20482841, -0.13688965 0.11798434 0.2048341, -0.13771813 0.11789191 0.20513403, -0.13747789 0.11799321 0.2051535, -0.1377299 0.1178616 0.20510605, -0.13750036 0.11799619 0.20511672, -0.13752042 0.1179902 0.20507911, -0.13753746 0.11797541 0.20504251, -0.13755088 0.1179527 0.20500866, -0.13731121 0.11803085 0.20507839, -0.13755952 0.11792308 0.20497862, -0.13732563 0.11803538 0.2050375, -0.1373387 0.11803074 0.20499632, -0.13781177 0.1178022 0.2055358, -0.13715614 0.11804941 0.2050406, -0.12078376 0.11714374 0.20685188, -0.12077844 0.11714916 0.20680767, -0.12077364 0.11714472 0.20676318, -0.1207698 0.11713049 0.2067209, -0.12076676 0.11710714 0.2066828, -0.12076491 0.11707589 0.20665081, -0.11945295 0.11676882 0.20760059, -0.11930233 0.1166406 0.20785649, -0.11941606 0.11676511 0.2075723, -0.11926168 0.11663367 0.20783409, -0.1193831 0.11675136 0.207542, -0.11922553 0.11661713 0.20780891, -0.11959764 0.11687475 0.20729612, -0.11935619 0.11672844 0.20751116, -0.11919613 0.11659172 0.20778263, -0.11957437 0.11685434 0.20726158, -0.11933678 0.1166977 0.20748176, -0.11917487 0.11655907 0.20775646, -0.11955726 0.11682557 0.2072295, -0.11932582 0.11666074 0.20745553, -0.1191631 0.11652093 0.20773184, -0.11954749 0.11678995 0.20720151, -0.12031892 0.11709647 0.20691186, -0.12030476 0.11709061 0.20686902, -0.12029323 0.11707471 0.20682818, -0.12028442 0.11705007 0.20679112, -0.12027925 0.11701754 0.20676006, -0.11992866 0.11700311 0.20709755, -0.11990649 0.11699501 0.20705797, -0.11988837 0.11697707 0.20701976, -0.11987489 0.11695032 0.206985, -0.11986703 0.11691609 0.20695521, -0.1196261 0.11688587 0.20733137, -0.082751498 0.077380076 0.28636709, -0.082710907 0.077373043 0.28634465, -0.082674757 0.077356443 0.28631973, -0.082645342 0.0773312 0.28629315, -0.082624123 0.077298537 0.28626692, -0.082612231 0.077260301 0.28624225, -0.081885949 0.075785562 0.28765649, -0.081884131 0.075768545 0.28761265, -0.081898257 0.075799242 0.28769946, -0.081920341 0.075809166 0.28773963, -0.081951052 0.0758145 0.28777444, -0.081988752 0.075815424 0.28780252, -0.082031518 0.075811282 0.28782189, -0.082071349 0.076332882 0.28730911, -0.082075432 0.076357707 0.2873472, -0.082088873 0.07637848 0.28738511, -0.082111046 0.076394454 0.28742096, -0.082140878 0.076404676 0.28745294, -0.082176968 0.076408878 0.28747976, -0.082217738 0.076406851 0.2874999, -0.082318619 0.076850936 0.28684622, -0.082325146 0.076881662 0.28687656, -0.082339898 0.076907977 0.28690714, -0.0823621 0.076928988 0.28693664, -0.082391068 0.076943889 0.28696465, -0.082425341 0.076952174 0.28698954, -0.082463786 0.076953188 0.28700981, -0.082531705 0.077190444 0.2865836, -0.082559779 0.07720761 0.28660822, -0.08259289 0.07721813 0.28663096, -0.082630232 0.077221319 0.2866509, -0.081665874 0.07453917 0.28781009, -0.081664711 0.074536189 0.28785908, -0.08167538 0.074532285 0.28790665, -0.081697285 0.074527755 0.28795022, -0.081729174 0.074522719 0.28798711, -0.081769049 0.074517444 0.28801468, -0.081814557 0.074512467 0.28803217, -0.081746206 0.07515265 0.28778127, -0.081746131 0.075160161 0.28782904, -0.081757501 0.075165436 0.28787553, -0.08177954 0.075168088 0.28791833, -0.081810981 0.075168297 0.28795478, -0.081850007 0.075165793 0.287983, -0.081894338 0.075160787 0.28800127, -0.14920813 -0.034632683 0.13450257, -0.14913477 -0.034604207 0.1344741, -0.14923954 -0.03465718 0.13452701, -0.14917362 -0.034615576 0.13448565, -0.14910267 -0.034599274 0.13446906, -0.14926498 -0.034689352 0.1345593, -0.14927161 -0.034837425 0.13470738, -0.14928585 -0.03477335 0.134643, -0.14927904 -0.034720466 0.13459042, -0.14728665 -0.035071179 0.14045829, -0.14721055 -0.035144553 0.14042936, -0.14716163 -0.035198569 0.14039038, -0.14713316 -0.035236388 0.14034949, -0.14712311 -0.035296232 0.14019896, -0.14711608 -0.035291106 0.14023091, -0.14711347 -0.035280704 0.14026766, -0.14711832 -0.035263091 0.14030771, -0.11458932 0.1082072 0.21938363, -0.11320877 -0.033257827 0.22321849, -0.11335135 -0.033300743 0.22298282, -0.14756717 -0.033687115 0.14046602, -0.14754407 -0.033664018 0.14046086, -0.14750318 -0.033618599 0.14044107, -0.14746818 -0.033573627 0.1404079, -0.14744233 -0.033532321 0.14036204, -0.14742438 -0.033469826 0.14024068, -0.1474275 -0.03349784 0.14030714, -0.1471947 -0.028772265 0.1364761, -0.14712857 -0.028764799 0.13650078, -0.14707014 -0.028758302 0.13654023, -0.1470225 -0.028753012 0.13659263, -0.14934802 -0.034691036 0.13470082, -0.14938854 -0.034579799 0.13470063, -0.14936721 -0.034573495 0.13463728, -0.14932781 -0.034682214 0.13463734, -0.14932342 -0.03474398 0.13470078, -0.1493035 -0.034734249 0.13463728, -0.14919908 -0.034383014 0.13447487, -0.14917207 -0.034515679 0.13447492, -0.14926207 -0.034390032 0.13449733, -0.14924306 -0.03453666 0.13450263, -0.14931858 -0.03439635 0.13453309, -0.14914095 -0.03460151 0.13447516, -0.14931512 -0.034558117 0.13455932, -0.14936593 -0.03440161 0.13458061, -0.14920896 -0.03463079 0.13450254, -0.14940132 -0.034405619 0.1346373, -0.14927791 -0.034660667 0.1345593, -0.14942342 -0.034408152 0.13470064, -0.14921442 -0.034246787 0.13447516, -0.1492774 -0.034253791 0.13449717, -0.14933386 -0.034260079 0.13453308, -0.14938103 -0.034265518 0.13458052, -0.14941657 -0.034269392 0.13463728, -0.14943877 -0.034271926 0.13470079, -0.14964634 -0.033368528 0.13453303, -0.14943972 -0.033796594 0.13453308, -0.14948441 -0.033812419 0.13458031, -0.14997713 -0.033031091 0.13458033, -0.15036023 -0.032772839 0.13463728, -0.15034138 -0.0327425 0.13458052, -0.15000236 -0.033056438 0.13463728, -0.14971673 -0.033412993 0.13463716, -0.1496865 -0.03339389 0.13458028, -0.1493261 -0.033756867 0.13447499, -0.14938605 -0.033777893 0.13449733, -0.1495983 -0.03333813 0.13449727, -0.14994353 -0.032997429 0.13453303, -0.15031615 -0.032702252 0.13453306, -0.1495446 -0.033304274 0.13447504, -0.14990355 -0.032957092 0.13449728, -0.15028608 -0.032653987 0.13449733, -0.14985882 -0.032912135 0.13447502, -0.15025263 -0.032600194 0.13447502, -0.14953911 -0.033831537 0.13470082, -0.14951813 -0.033824265 0.13463716, -0.14973563 -0.033424735 0.1347007, -0.15001786 -0.033072174 0.13470082, -0.15037191 -0.032791674 0.13470082, -0.15698332 -0.028405845 0.13447499, -0.15701687 -0.028459698 0.1344974, -0.15704694 -0.028508112 0.13453311, -0.15707207 -0.028548256 0.13458064, -0.15709098 -0.028578684 0.13463725, -0.15710267 -0.028597444 0.13470089, -0.15710616 -0.028310969 0.13447517, -0.15720716 -0.02819328 0.13447505, -0.1575281 -0.02795057 0.13463727, -0.15754823 -0.027755052 0.13463759, -0.1575124 -0.027755111 0.13458061, -0.15749317 -0.027943194 0.13458061, -0.15743661 -0.028123647 0.13458061, -0.1574467 -0.027933642 0.13453314, -0.15739295 -0.028104991 0.13453305, -0.15730582 -0.02826193 0.13453303, -0.15734071 -0.02808255 0.1344974, -0.15725921 -0.02822949 0.13449742, -0.1571497 -0.02835685 0.13449743, -0.15754998 -0.027954966 0.13470078, -0.15757036 -0.027755216 0.13470095, -0.15746951 -0.028137818 0.1346375, -0.15734476 -0.02828902 0.13458061, -0.15718889 -0.028398156 0.13453308, -0.1574899 -0.028146535 0.13470089, -0.15737408 -0.028309405 0.13463748, -0.15722167 -0.028432518 0.13458057, -0.15739235 -0.028322071 0.13470089, -0.15724631 -0.028458461 0.13463731, -0.15726151 -0.02847454 0.13470085, -0.15732892 -0.027909443 0.13447513, -0.15734458 -0.027755231 0.13447517, -0.15739103 -0.027922317 0.13449742, -0.157408 -0.02775526 0.13449743, -0.15728247 -0.028057545 0.13447508, -0.15746485 -0.027755052 0.13453303, -0.15757036 -0.023810282 0.13470095, -0.15754817 -0.023810193 0.13463762, -0.15751244 -0.023810104 0.13458073, -0.15746491 -0.023810238 0.13453305, -0.15740812 -0.023810267 0.13449745, -0.15734461 -0.023810297 0.13447525, -0.15730357 -0.022738576 0.13463752, -0.15698126 -0.022292271 0.13458063, -0.15727139 -0.022754028 0.13458069, -0.15745129 -0.023268536 0.13458073, -0.15722859 -0.022774577 0.13453333, -0.15611361 -0.021659538 0.13453344, -0.15560903 -0.021483004 0.13453344, -0.15559646 -0.021538466 0.13449766, -0.15740508 -0.02327913 0.13453333, -0.15608883 -0.021710813 0.13449763, -0.15507793 -0.021543503 0.13447528, -0.15732357 -0.022728771 0.13470115, -0.15702653 -0.022256255 0.13470118, -0.15653065 -0.021988362 0.1344976, -0.15606135 -0.021768034 0.13447528, -0.1564911 -0.022038102 0.13447534, -0.15700915 -0.022269994 0.13463761, -0.15748614 -0.023260638 0.13463746, -0.15685001 -0.022397071 0.13447537, -0.15750784 -0.023255646 0.13470106, -0.15562758 -0.021401852 0.13463761, -0.15507796 -0.021339968 0.13463767, -0.15507796 -0.021375701 0.13458082, -0.1556195 -0.02143681 0.13458078, -0.15613413 -0.021616831 0.13458078, -0.1565662 -0.021943927 0.13453315, -0.15689969 -0.022357404 0.13449763, -0.15563236 -0.021380156 0.13470103, -0.1550779 -0.021317795 0.13470094, -0.15712008 -0.022826642 0.13447525, -0.15614963 -0.02158463 0.13463764, -0.15659583 -0.021906793 0.13458084, -0.15694416 -0.022321939 0.13453333, -0.15717734 -0.022799253 0.13449758, -0.1561594 -0.021564618 0.13470118, -0.15728778 -0.023305818 0.13447522, -0.15661812 -0.021878853 0.13463776, -0.15558231 -0.021600366 0.13447528, -0.15507793 -0.021480083 0.13449745, -0.15734956 -0.023291677 0.13449754, -0.15663184 -0.021861494 0.13470115, -0.15507796 -0.021423146 0.13453314, -0.14876407 -0.021317691 0.13470109, -0.14876407 -0.021339983 0.13463755, -0.14876409 -0.021375686 0.13458085, -0.14876403 -0.021423087 0.13453302, -0.14876413 -0.021480024 0.13449764, -0.14876418 -0.021543503 0.13447528, -0.14772047 -0.021610662 0.13458076, -0.14726269 -0.021893665 0.13458076, -0.14729194 -0.021931022 0.13453312, -0.14823964 -0.021481469 0.13453338, -0.14825214 -0.021536812 0.13449749, -0.14776522 -0.021704957 0.13449761, -0.14774072 -0.021653593 0.13453329, -0.14722697 -0.021848008 0.13470088, -0.14683352 -0.022233665 0.13470113, -0.14685072 -0.022247717 0.1346375, -0.14724073 -0.021865562 0.13463753, -0.14770508 -0.021578491 0.13463759, -0.14822926 -0.021435186 0.13458088, -0.14769557 -0.021558404 0.13470098, -0.14822139 -0.021400258 0.13463762, -0.1482165 -0.021378562 0.13470116, -0.14736633 -0.022025749 0.13447516, -0.14700831 -0.022376493 0.13447532, -0.14732717 -0.02197586 0.13449743, -0.14695919 -0.022336349 0.13449761, -0.14779237 -0.021762341 0.13447511, -0.14691523 -0.022300437 0.13453311, -0.14826608 -0.021598861 0.13447538, -0.14687842 -0.022270396 0.13458072, -0.13900186 -0.031854674 0.13464449, -0.13881503 -0.032201931 0.13454284, -0.13879953 -0.032258436 0.134524, -0.13879578 -0.03230229 0.13450773, -0.13880052 -0.032397673 0.13447998, -0.13880368 -0.03246136 0.13447066, -0.13873045 -0.03245683 0.1344756, -0.13802378 -0.032473966 0.13447218, -0.13868414 -0.032414958 0.13448884, -0.13802372 -0.032423377 0.13448557, -0.13712727 -0.032977864 0.13447548, -0.13707486 -0.032939121 0.13449909, -0.13739859 -0.032703325 0.13447346, -0.13736287 -0.032659322 0.13449082, -0.13760473 -0.032574221 0.13447259, -0.1375811 -0.032527283 0.13448738, -0.13781144 -0.032499596 0.13447212, -0.13779961 -0.032450721 0.1344855, -0.13687757 -0.033207074 0.13449907, -0.13692997 -0.033245727 0.13447548, -0.13681845 -0.033254787 0.13451116, -0.13685022 -0.033293054 0.13448979, -0.14604369 -0.024782732 0.14012757, -0.14645934 -0.024273336 0.1392512, -0.14644451 -0.024327189 0.13921288, -0.14602874 -0.02483657 0.14008909, -0.1464975 -0.024224177 0.13906837, -0.14647499 -0.024280325 0.13906819, -0.14646423 -0.02433987 0.13906842, -0.14649752 -0.024223998 0.13676757, -0.14647512 -0.02428025 0.1367676, -0.14646432 -0.024339706 0.13676779, -0.14653671 -0.024178207 0.13670078, -0.1466707 -0.024362132 0.13648239, -0.14667432 -0.02433759 0.13648245, -0.14671157 -0.02432093 0.1364751, -0.14668417 -0.024314806 0.13648251, -0.14666246 -0.024280801 0.13649726, -0.14658871 -0.024337605 0.13652492, -0.14660192 -0.024292037 0.13652495, -0.14661837 -0.02424483 0.13653317, -0.14658168 -0.024214938 0.13658065, -0.14652061 -0.024360716 0.13659135, -0.14653017 -0.02429615 0.13659143, -0.14655653 -0.024236277 0.13659137, -0.14655395 -0.024192184 0.13663748, -0.14648105 -0.024321824 0.13667506, -0.14650217 -0.024248078 0.136675, -0.14745791 -0.023049936 0.13670114, -0.14747526 -0.023064047 0.13663748, -0.14750277 -0.023086637 0.13658068, -0.14753963 -0.023116633 0.13653317, -0.14758372 -0.023152664 0.1364975, -0.14763285 -0.023192868 0.13647541, -0.14857616 -0.022422895 0.13658068, -0.14819239 -0.022605315 0.13653326, -0.14817204 -0.02256237 0.13658078, -0.14858674 -0.022469178 0.13653314, -0.14780824 -0.022787288 0.13658077, -0.14778624 -0.02275908 0.13663745, -0.14815666 -0.022530109 0.1366376, -0.14861315 -0.022586554 0.13647538, -0.14900136 -0.022543475 0.13647547, -0.1490012 -0.022479966 0.13649727, -0.14859918 -0.02252467 0.13649735, -0.14821678 -0.022656754 0.13649756, -0.14783765 -0.02282469 0.13653329, -0.14824384 -0.022713989 0.1364754, -0.1478727 -0.022869512 0.13649753, -0.1479118 -0.022919461 0.13647547, -0.14900123 -0.022317663 0.13670097, -0.14856364 -0.022366315 0.13670102, -0.14900133 -0.02233994 0.13663757, -0.14856844 -0.022388056 0.13663751, -0.14814712 -0.022510082 0.13670102, -0.14900136 -0.022375613 0.13658062, -0.14777254 -0.022741586 0.13670117, -0.14900133 -0.022423193 0.13653323, -0.15457787 -0.022317797 0.13670106, -0.15457775 -0.022339925 0.13663767, -0.15457788 -0.022375733 0.13658066, -0.15457782 -0.022423208 0.13653314, -0.15457793 -0.022479981 0.13649738, -0.15457802 -0.022543535 0.13647541, -0.15651235 -0.024310261 0.13658068, -0.15641749 -0.023890406 0.13653326, -0.15646391 -0.023879617 0.13658084, -0.15575445 -0.022834852 0.13653336, -0.1553719 -0.022661328 0.13649754, -0.15539658 -0.022610068 0.13653319, -0.15499769 -0.022470519 0.13653328, -0.15632096 -0.023470923 0.1365808, -0.15649879 -0.023871779 0.13663772, -0.15541734 -0.022567213 0.13658084, -0.15500826 -0.022424147 0.13658074, -0.15635301 -0.023455322 0.13663746, -0.15534449 -0.022718549 0.13647547, -0.15657043 -0.024310231 0.13670102, -0.15571889 -0.022879332 0.13649751, -0.15567935 -0.022929072 0.13647537, -0.15637301 -0.023445651 0.13670114, -0.15611829 -0.023081854 0.13663751, -0.15613565 -0.023067921 0.13670112, -0.15498519 -0.022526026 0.13649753, -0.15582015 -0.022752479 0.13670117, -0.154971 -0.022587895 0.13647535, -0.15640812 -0.024310142 0.13649754, -0.15636218 -0.023903012 0.13649753, -0.15646476 -0.024310291 0.13653326, -0.15627798 -0.023491502 0.13653319, -0.15609029 -0.023104116 0.13658063, -0.15580627 -0.022769898 0.13663764, -0.15634468 -0.024310276 0.13647516, -0.15630035 -0.023917109 0.13647549, -0.15544236 -0.022515178 0.13670115, -0.15622678 -0.023516238 0.13649754, -0.15605316 -0.023133636 0.13653319, -0.155784 -0.022797763 0.13658071, -0.15543273 -0.022535056 0.13663764, -0.15616962 -0.023543686 0.13647535, -0.15502113 -0.022367641 0.13670114, -0.15600868 -0.023169085 0.13649766, -0.15652034 -0.023866862 0.13670099, -0.15654813 -0.024310187 0.13663764, -0.15501621 -0.022389382 0.13663763, -0.15595901 -0.023208767 0.13647534, -0.1565704 -0.027199954 0.13670099, -0.15654819 -0.027199954 0.13663748, -0.15651232 -0.027199954 0.1365806, -0.15646505 -0.027199879 0.13653319, -0.15640801 -0.027199924 0.1364975, -0.15634456 -0.027200028 0.13647515, -0.14759299 -0.033064857 0.13647249, -0.14760885 -0.033120781 0.13648844, -0.14762728 -0.033184603 0.13652343, -0.14764278 -0.033239082 0.13657355, -0.14765438 -0.033279553 0.13663509, -0.14766099 -0.033302933 0.13670188, -0.15654993 -0.027399749 0.13670081, -0.15648985 -0.027591437 0.13670081, -0.15598342 -0.027850717 0.13647532, -0.15614974 -0.027801707 0.13649732, -0.15601699 -0.027904466 0.13649738, -0.15618894 -0.027842969 0.13653314, -0.15610263 -0.028042287 0.13670078, -0.15630589 -0.027706787 0.13653325, -0.15622164 -0.027877301 0.13658063, -0.15634489 -0.027733892 0.13658077, -0.15637422 -0.027754337 0.13663745, -0.15643661 -0.027568534 0.13658071, -0.15646954 -0.027582735 0.13663767, -0.15652829 -0.027395308 0.13663745, -0.15610614 -0.027755782 0.13647515, -0.15625927 -0.027674183 0.13649738, -0.15639299 -0.027549803 0.13653314, -0.1564932 -0.027388185 0.13658075, -0.15620716 -0.027638122 0.13647518, -0.15634075 -0.027527377 0.13649732, -0.1564467 -0.027378634 0.13653332, -0.1562825 -0.027502403 0.13647516, -0.15639102 -0.027367026 0.1364975, -0.15632886 -0.0273543 0.13647521, -0.15609097 -0.028023511 0.13663745, -0.15626155 -0.027919322 0.13670097, -0.15607208 -0.027993143 0.13658047, -0.15624629 -0.027903229 0.13663743, -0.15639243 -0.027767032 0.13670075, -0.15604706 -0.027952895 0.13653333, -0.14843704 -0.035064578 0.14046006, -0.14843713 -0.035127968 0.14043786, -0.14843704 -0.03518489 0.14040209, -0.1484371 -0.035232499 0.14035447, -0.14843711 -0.035268188 0.14029752, -0.14843708 -0.03529045 0.14023437, -0.14921424 -0.034815937 0.14035454, -0.14935052 -0.034623668 0.14029756, -0.14924395 -0.034835741 0.14029768, -0.14917481 -0.034789622 0.14040211, -0.14931695 -0.034611717 0.14035459, -0.14927213 -0.034595728 0.1404022, -0.14911723 -0.03502053 0.14023426, -0.14942336 -0.034408391 0.14023438, -0.14926255 -0.034848019 0.14023438, -0.14912745 -0.034758121 0.14043787, -0.14921868 -0.03457658 0.14043787, -0.14910208 -0.035004348 0.14029779, -0.1490747 -0.034722999 0.14045995, -0.14915892 -0.034555361 0.14046007, -0.14907753 -0.034978449 0.14035442, -0.14895503 -0.035144031 0.14023449, -0.14904502 -0.034943923 0.14040211, -0.14919913 -0.034383237 0.14046016, -0.14894345 -0.035125136 0.14029776, -0.14900599 -0.034902424 0.14043786, -0.14892484 -0.035094708 0.14035462, -0.1489626 -0.03485617 0.14046003, -0.14877476 -0.035230517 0.1402344, -0.14890006 -0.035054207 0.14040199, -0.14876713 -0.035209537 0.14029758, -0.14887023 -0.035005748 0.14043787, -0.14875498 -0.035176039 0.1403545, -0.14937147 -0.034631044 0.14023438, -0.14940128 -0.034405857 0.14029768, -0.14883724 -0.034951672 0.14046004, -0.14936577 -0.034401864 0.14035453, -0.14873888 -0.035131335 0.14040212, -0.14931862 -0.034396619 0.14040218, -0.14871944 -0.035077929 0.14043777, -0.14869787 -0.035018325 0.14046006, -0.14926204 -0.034390241 0.14043775, -0.14943877 -0.03427206 0.14023438, -0.14941664 -0.034269512 0.14029767, -0.14938104 -0.034265578 0.14035442, -0.14933388 -0.034260303 0.14040203, -0.14927737 -0.03425397 0.14043792, -0.14921443 -0.034246936 0.14046021, -0.14994346 -0.032997519 0.14040211, -0.15031622 -0.032702237 0.14040211, -0.15034135 -0.032742754 0.14035454, -0.14964627 -0.033368617 0.14040211, -0.1495983 -0.033338219 0.14043795, -0.14990352 -0.032957122 0.14043802, -0.14953916 -0.033831626 0.14023443, -0.14951812 -0.033824295 0.14029767, -0.14971672 -0.033413082 0.14029765, -0.14948456 -0.033812404 0.14035477, -0.14968659 -0.033393919 0.14035454, -0.14997707 -0.033031136 0.14035466, -0.15036026 -0.032772869 0.14029774, -0.14973556 -0.033424765 0.14023426, -0.15000224 -0.033056468 0.14029767, -0.15037195 -0.032791778 0.14023425, -0.15001793 -0.033072263 0.14023431, -0.15025257 -0.032600194 0.14046004, -0.14932613 -0.033756986 0.14046009, -0.14938591 -0.033777922 0.14043786, -0.14954466 -0.033304483 0.14045997, -0.14943974 -0.033796757 0.14040218, -0.14985873 -0.032912284 0.14045991, -0.15028618 -0.032653973 0.1404379, -0.15710276 -0.028597638 0.14023453, -0.15709108 -0.028578684 0.14029783, -0.15707219 -0.028548419 0.14035472, -0.15704696 -0.028508157 0.14040211, -0.15701681 -0.028459728 0.14043796, -0.15698333 -0.028405994 0.14046025, -0.15726149 -0.028474718 0.14023447, -0.15739231 -0.028322309 0.1402345, -0.15739101 -0.027922437 0.14043814, -0.15734455 -0.027755231 0.14046013, -0.15740806 -0.027755171 0.14043799, -0.15744662 -0.027933836 0.14040214, -0.15757036 -0.02775532 0.14023456, -0.1573928 -0.02810508 0.14040208, -0.15749316 -0.027943462 0.1403546, -0.15743668 -0.028123841 0.14035459, -0.15734488 -0.028289139 0.14035463, -0.1574695 -0.028137863 0.14029783, -0.15737411 -0.028309554 0.1402978, -0.15724631 -0.028458625 0.14029779, -0.15732892 -0.027909577 0.14046034, -0.15734071 -0.02808255 0.14043808, -0.15730588 -0.028262109 0.14040211, -0.15722162 -0.028432637 0.14035466, -0.1572824 -0.028057605 0.14046025, -0.1572592 -0.028229445 0.14043796, -0.157189 -0.028398171 0.1404022, -0.15720707 -0.028193295 0.14046001, -0.15714975 -0.028357059 0.14043798, -0.15710613 -0.028310984 0.14046013, -0.15755004 -0.027954966 0.1402346, -0.15754817 -0.027755201 0.14029783, -0.15752824 -0.027950615 0.14029783, -0.15751235 -0.027755231 0.1403546, -0.15748993 -0.02814661 0.14023456, -0.15746486 -0.027755231 0.14040214, -0.15734458 -0.023810327 0.14046024, -0.15740812 -0.023810267 0.14043811, -0.15746501 -0.023810297 0.14040238, -0.15751249 -0.023810282 0.14035478, -0.15754816 -0.023810208 0.14029801, -0.15757036 -0.023810387 0.1402345, -0.15717731 -0.022799283 0.14043832, -0.15689974 -0.022357494 0.14043827, -0.1569442 -0.022322029 0.14040244, -0.15722862 -0.022774711 0.14040238, -0.15613414 -0.021616906 0.14035469, -0.15561962 -0.021436796 0.14035478, -0.15562767 -0.021401972 0.14029786, -0.15614977 -0.021584645 0.14029783, -0.15740512 -0.023279056 0.14040247, -0.15727134 -0.022754043 0.14035484, -0.15745139 -0.023268566 0.14035478, -0.15661813 -0.021878973 0.14029799, -0.15615942 -0.021564752 0.14023466, -0.15663192 -0.021861613 0.14023447, -0.1571202 -0.022826746 0.14046022, -0.15685017 -0.022396937 0.14046016, -0.15734956 -0.023291752 0.14043811, -0.15702654 -0.02225624 0.14023462, -0.15728781 -0.023305818 0.14046028, -0.15559639 -0.021538526 0.14043815, -0.15507793 -0.021480098 0.14043818, -0.1550779 -0.021423161 0.14040238, -0.15560903 -0.021483183 0.14040221, -0.15611351 -0.021659687 0.1404025, -0.15659587 -0.021906987 0.14035481, -0.15700911 -0.022270128 0.14029792, -0.1555824 -0.021600321 0.14046025, -0.15507784 -0.021543533 0.14046031, -0.1573236 -0.022728816 0.14023469, -0.15608881 -0.021710873 0.14043812, -0.15656613 -0.021943972 0.14040235, -0.15698132 -0.022292331 0.14035489, -0.15730351 -0.022738501 0.14029795, -0.15606138 -0.021768048 0.14046034, -0.1575079 -0.023255706 0.14023438, -0.15653077 -0.021988541 0.14043804, -0.15563256 -0.021380305 0.14023465, -0.15507787 -0.021317884 0.14023465, -0.15507787 -0.021340042 0.14029789, -0.1574861 -0.023260638 0.14029776, -0.15649129 -0.022038087 0.14046016, -0.15507787 -0.02137582 0.14035481, -0.14876413 -0.021543488 0.14046028, -0.14876415 -0.021480024 0.14043817, -0.1487641 -0.021423236 0.14040218, -0.1487641 -0.02137588 0.14035483, -0.14876415 -0.021339893 0.14029801, -0.14876419 -0.021317661 0.14023471, -0.14774072 -0.021653771 0.14040235, -0.14729196 -0.021931157 0.14040233, -0.14726262 -0.021893784 0.14035483, -0.14822927 -0.021435216 0.1403549, -0.14822128 -0.021400318 0.14029786, -0.14770523 -0.021578535 0.14029786, -0.14772061 -0.021610752 0.14035481, -0.14736618 -0.022025883 0.14046034, -0.14700828 -0.022376597 0.14046019, -0.14695913 -0.022336468 0.14043809, -0.14732717 -0.021975905 0.14043826, -0.14776522 -0.021705076 0.14043814, -0.14823963 -0.021481693 0.14040217, -0.1477924 -0.021762252 0.14046019, -0.14825213 -0.021537051 0.14043799, -0.14826609 -0.021598876 0.14046022, -0.14722696 -0.021848217 0.14023462, -0.14683358 -0.022233933 0.14023459, -0.14724067 -0.021865591 0.14029776, -0.14685075 -0.022248 0.14029801, -0.14769566 -0.021558508 0.14023462, -0.14687829 -0.022270486 0.14035483, -0.14821652 -0.021378741 0.14023456, -0.14691511 -0.022300616 0.1404025, -0.11305444 -0.033177897 0.22347145, -0.097212628 -0.032863155 0.22400993, -0.097284272 -0.032612249 0.22426602, -0.12734787 -0.032667831 0.16047977, -0.12734786 -0.03329803 0.16084339, -0.12697592 -0.032680407 0.16051497, -0.12734793 -0.032782242 0.16045968, -0.12697235 -0.03279385 0.16049822, -0.12734799 -0.032898083 0.16046624, -0.12697402 -0.032907993 0.16050698, -0.12734798 -0.03300938 0.16049953, -0.12698101 -0.033016667 0.16054104, -0.12734798 -0.033109888 0.16055761, -0.12699285 -0.033114806 0.16059817, -0.12734786 -0.033194438 0.16063727, -0.12700918 -0.033197179 0.1606759, -0.12734787 -0.033258334 0.16073434, -0.12702885 -0.033259496 0.16076973, -0.12705098 -0.033298299 0.16087545, -0.1365152 -0.032667726 0.16047975, -0.13651517 -0.032782152 0.16045976, -0.13651513 -0.032898203 0.1604663, -0.13651507 -0.03300938 0.16049954, -0.13651514 -0.033109948 0.1605576, -0.13651513 -0.033194542 0.16063729, -0.13651504 -0.033258408 0.1607341, -0.13651516 -0.033297986 0.16084342, -0.13661973 -0.033197492 0.16062941, -0.13673271 -0.033202499 0.16059761, -0.13664028 -0.03325963 0.16072309, -0.13677181 -0.033261746 0.16068308, -0.13681592 -0.03329882 0.16077904, -0.13690351 -0.033264607 0.16061199, -0.13696449 -0.03329955 0.16069414, -0.13658857 -0.032999799 0.1604875, -0.1366028 -0.033115327 0.16055194, -0.13669997 -0.033124119 0.16052631, -0.13712399 -0.033300504 0.16054989, -0.13727854 -0.033297271 0.16026723, -0.13684909 -0.033209026 0.16053835, -0.13658108 -0.032853454 0.16045313, -0.13704926 -0.033268735 0.16048661, -0.13717525 -0.033255443 0.16022469, -0.13667195 -0.033013731 0.16046561, -0.13680297 -0.033135906 0.16047618, -0.13698202 -0.033218428 0.1604301, -0.13708396 -0.033188313 0.16018747, -0.13658302 -0.032707021 0.16046236, -0.13665558 -0.032872885 0.16043, -0.1367624 -0.033032477 0.16042161, -0.13692456 -0.033152387 0.16038147, -0.13701005 -0.03309983 0.16015704, -0.13665693 -0.03272967 0.16043277, -0.13673656 -0.032898843 0.16038647, -0.13666329 -0.033298373 0.16082847, -0.13687189 -0.033058643 0.16033702, -0.13673343 -0.032760561 0.16038229, -0.13683395 -0.032935843 0.16030504, -0.13695759 -0.032994673 0.16013566, -0.136822 -0.032805637 0.16029514, -0.13692971 -0.032879353 0.16012399, -0.13742727 -0.032879159 0.15890935, -0.1374552 -0.032994568 0.15892091, -0.13750751 -0.033099532 0.15894222, -0.13758148 -0.03318806 0.15897252, -0.13767271 -0.033255443 0.15900983, -0.13777606 -0.033297405 0.15905215, -0.1374945 -0.03320089 0.15815392, -0.13743584 -0.033208594 0.15808262, -0.13755465 -0.033253357 0.15810153, -0.13748549 -0.03325744 0.15802272, -0.13740797 -0.033260226 0.15796173, -0.13752998 -0.033286408 0.15796889, -0.1377507 -0.033263475 0.15878977, -0.1377756 -0.033271 0.15855995, -0.13785289 -0.033299163 0.15880568, -0.13787068 -0.033300951 0.1585523, -0.13744235 -0.033287659 0.15790275, -0.13754244 -0.033190668 0.15823992, -0.1374345 -0.033120707 0.15820576, -0.13765924 -0.033206686 0.1587757, -0.13768958 -0.03322348 0.15856713, -0.13747446 -0.03310357 0.15828206, -0.13742617 -0.033001244 0.1583119, -0.13783278 -0.033302456 0.1583205, -0.13736962 -0.033213973 0.15802768, -0.1374951 -0.032975405 0.15875062, -0.13756701 -0.033112168 0.1587615, -0.13738564 -0.033133641 0.15814307, -0.13738994 -0.033025354 0.15824462, -0.13774902 -0.033277199 0.1583474, -0.13733034 -0.033142552 0.1580949, -0.13734715 -0.033043817 0.15818965, -0.13759977 -0.033143908 0.15857437, -0.13767259 -0.033237085 0.15837218, -0.13774543 -0.033303723 0.15811445, -0.13752204 -0.033026561 0.15858072, -0.13767613 -0.033282116 0.15815724, -0.13759035 -0.03316991 0.15839854, -0.13766815 -0.033304289 0.15800311, -0.13761237 -0.033247948 0.15819679, -0.13760917 -0.03328453 0.15805413, -0.137578 -0.033304885 0.1579109, -0.13751425 -0.033069089 0.1584232, -0.13747934 -0.033305109 0.15783945, -0.12828651 -0.03330043 0.15776826, -0.12828648 -0.033268213 0.15786777, -0.12828636 -0.033216 0.15795825, -0.12828644 -0.033146098 0.15803592, -0.12702461 -0.033297434 0.1581807, -0.12708628 -0.033256665 0.15827231, -0.12714091 -0.033190876 0.15835369, -0.12718539 -0.033104256 0.15841983, -0.1278524 -0.033299878 0.15781659, -0.12787329 -0.03326574 0.15791638, -0.12789197 -0.033210948 0.15800661, -0.12790778 -0.033137888 0.15808292, -0.12226698 -0.033184484 0.16163553, -0.12226546 -0.033099726 0.16172755, -0.11165525 0.10024986 0.23519689, -0.11165524 0.10033408 0.23521931, -0.11079696 0.10073948 0.23518257, -0.11083302 0.10066599 0.23525231, -0.11086564 0.10057807 0.23530477, -0.11089323 0.10047954 0.23533714, -0.11091475 0.10037494 0.23534817, -0.11092684 0.10029119 0.23534171, -0.11093387 0.10020882 0.23532121, -0.1112663 0.10055387 0.23523611, -0.12049398 0.1002498 0.23519689, -0.12049398 0.10033411 0.23521936, -0.12093171 0.10065278 0.23526666, -0.12084572 0.10076997 0.23511888, -0.12100071 0.10072413 0.23521018, -0.12079838 0.10069349 0.23518762, -0.12059571 0.10040802 0.23523729, -0.12060924 0.10051894 0.23522775, -0.12072048 0.10049596 0.23526448, -0.12062702 0.10062441 0.23519418, -0.12075576 0.10060051 0.23523694, -0.12086987 0.10056451 0.2353051, -0.12058891 0.10032028 0.23522739, -0.12069416 0.10038558 0.2352685, -0.1205854 0.10023558 0.23520248, -0.1208187 0.10046348 0.23532292, -0.12068059 0.10029811 0.23525517, -0.12078077 0.10035542 0.23531961, -0.1206741 0.10021344 0.23522764, -0.12076172 0.10026905 0.23530158, -0.12075277 0.10018468 0.23527126, -0.12067193 0.10079831 0.23506251, -0.12064835 0.10071924 0.23513812, -0.12042949 0.09954977 0.23664644, -0.12045902 0.099645287 0.23670793, -0.1205121 0.099726826 0.23677343, -0.12058577 0.099790126 0.23683935, -0.12067586 0.099831611 0.236902, -0.12077755 0.099849015 0.23695815, -0.1206108 0.099735171 0.2371878, -0.12034573 0.09965539 0.23734914, -0.12042141 0.099617153 0.23677889, -0.1204699 0.099692494 0.23685259, -0.12040925 0.099661022 0.23692694, -0.12053664 0.099748373 0.23692982, -0.12046584 0.09970963 0.23701409, -0.12053427 0.099734694 0.23710269, -0.12030621 0.099666238 0.23724608, -0.12019476 0.099634677 0.23739058, -0.12004353 0.099627972 0.23740505, -0.12004346 0.099643022 0.23729837, -0.12039363 0.099526048 0.23671278, -0.12036762 0.099592 0.23684627, -0.12027067 0.099653155 0.23714185, -0.12017514 0.099648654 0.23728411, -0.12034282 0.099505574 0.23677558, -0.12024076 0.099616349 0.2370417, -0.12015757 0.099638909 0.23717675, -0.12004341 0.099634945 0.23719113, -0.12021835 0.099558055 0.2369505, -0.12014283 0.099605918 0.23707412, -0.12004341 0.099603891 0.23708783, -0.12020396 0.099480659 0.23687269, -0.12013149 0.099551708 0.23698071, -0.12004335 0.099551678 0.23699372, -0.12004352 0.09948042 0.236913, -0.12070891 0.099789768 0.23707825, -0.120124 0.099478006 0.23690091, -0.12061796 0.099781424 0.23700637, -0.11087617 0.09962815 0.23740499, -0.11087622 0.099642962 0.23729831, -0.11087614 0.099634856 0.23719104, -0.1108762 0.099603981 0.23708792, -0.11087614 0.099551648 0.23699386, -0.11087617 0.09948045 0.23691289, -0.11016656 0.099408329 0.23701727, -0.11017996 0.099485427 0.23709573, -0.11020112 0.09954378 0.23718758, -0.11022919 0.09958002 0.23728825, -0.11026248 0.099592865 0.23739271, -0.11029962 0.09958142 0.23749648, -0.13389637 -0.032666892 0.14448944, -0.13389637 -0.033297151 0.14485314, -0.13352428 -0.032679603 0.1445246, -0.13389641 -0.032781243 0.14446948, -0.13352083 -0.032792896 0.14450808, -0.13389638 -0.032897159 0.14447622, -0.13352242 -0.032907158 0.1445169, -0.13389634 -0.033008561 0.14450939, -0.13352944 -0.033015877 0.14455068, -0.13389637 -0.033109158 0.1445674, -0.13354121 -0.033114016 0.14460802, -0.13389651 -0.033193603 0.14464706, -0.13355759 -0.033196315 0.14468546, -0.13389637 -0.03325741 0.14474401, -0.13357724 -0.033258647 0.14477947, -0.13359942 -0.033297449 0.14488515, -0.14306366 -0.032666877 0.14448965, -0.1430636 -0.032781318 0.14446956, -0.14306353 -0.032897308 0.14447616, -0.14306356 -0.033008441 0.14450936, -0.14306356 -0.033109173 0.14456742, -0.14306363 -0.033193722 0.14464706, -0.14306356 -0.03325747 0.14474408, -0.14306359 -0.033297196 0.14485331, -0.14316823 -0.033196554 0.14463906, -0.14328109 -0.033201531 0.14460732, -0.14318861 -0.033258781 0.14473288, -0.14332034 -0.033260807 0.14469282, -0.14336444 -0.033297881 0.14478879, -0.14345206 -0.033263549 0.14462177, -0.14351298 -0.033298597 0.14470391, -0.14313708 -0.032998875 0.14449741, -0.14315119 -0.033114523 0.14456171, -0.14324833 -0.03312324 0.14453594, -0.14367262 -0.033299536 0.14455956, -0.14382711 -0.033296436 0.14427704, -0.14339748 -0.033208206 0.14454791, -0.1431296 -0.032852575 0.14446293, -0.14359772 -0.033267692 0.14449656, -0.14372382 -0.033254474 0.14423443, -0.14322041 -0.033012852 0.14447509, -0.14335141 -0.033134997 0.14448595, -0.14353047 -0.033217505 0.14443995, -0.1436324 -0.033187345 0.14419724, -0.14313157 -0.032706186 0.14447196, -0.14320411 -0.032871962 0.14443989, -0.14331098 -0.033031434 0.14443146, -0.14347304 -0.033151492 0.14439122, -0.14355852 -0.033098802 0.14416699, -0.14320527 -0.032728747 0.14444257, -0.14328499 -0.032897845 0.14439641, -0.14321181 -0.033297509 0.14483818, -0.14342038 -0.033057705 0.14434691, -0.14328186 -0.032759681 0.14439221, -0.14338244 -0.032934904 0.14431496, -0.14350626 -0.032993764 0.14414558, -0.14337052 -0.032804593 0.14430492, -0.14347832 -0.032878414 0.144134, -0.14397563 -0.032878384 0.14291911, -0.14400366 -0.032993838 0.14293069, -0.14405607 -0.033098653 0.14295198, -0.14412989 -0.033187374 0.14298253, -0.1442212 -0.033254623 0.14301963, -0.14432451 -0.033296451 0.14306207, -0.14403382 -0.033256575 0.1420323, -0.14395647 -0.033259302 0.14197148, -0.14407842 -0.033285499 0.14197867, -0.14429919 -0.033262745 0.14279957, -0.14432403 -0.033270255 0.14256977, -0.14440142 -0.033298329 0.14281537, -0.14441912 -0.033300176 0.14256211, -0.1439908 -0.03328675 0.14191253, -0.14409094 -0.033189908 0.14224978, -0.1439831 -0.033119932 0.14221567, -0.14404289 -0.03320004 0.14216368, -0.14420761 -0.033205852 0.14278547, -0.14423813 -0.033222482 0.1425768, -0.14402284 -0.03310284 0.1422918, -0.14397472 -0.033000544 0.14232165, -0.14438114 -0.0333018 0.1423303, -0.14391793 -0.033213124 0.14203744, -0.14398424 -0.033207908 0.14209218, -0.14404337 -0.032974735 0.14276023, -0.14411549 -0.033111468 0.1427712, -0.14393416 -0.033132881 0.14215273, -0.14393841 -0.033024594 0.14225437, -0.1442975 -0.033276439 0.14235719, -0.14387883 -0.033141851 0.14210482, -0.14389558 -0.033043116 0.14219914, -0.14414826 -0.033143252 0.14258415, -0.14422087 -0.033236399 0.14238186, -0.14429377 -0.033303097 0.14212416, -0.14407063 -0.033025816 0.14259048, -0.14422451 -0.033281401 0.14216711, -0.14413877 -0.03316921 0.1424083, -0.1442166 -0.033303484 0.14201291, -0.14416076 -0.033247352 0.14220639, -0.14415751 -0.033283785 0.14206387, -0.1441264 -0.033303931 0.14192058, -0.14406271 -0.033068344 0.14243291, -0.14410315 -0.033252761 0.14211132, -0.1440278 -0.033304349 0.14184922, -0.13483489 -0.033299655 0.14177819, -0.1348349 -0.033267394 0.14187746, -0.13483489 -0.033214986 0.14196816, -0.134835 -0.033145383 0.14204581, -0.13357323 -0.03329657 0.14219038, -0.13363491 -0.033255875 0.14228201, -0.13368934 -0.033190235 0.14236324, -0.13373388 -0.033103317 0.14242958, -0.13440087 -0.033298925 0.14182636, -0.13442169 -0.033265054 0.14192595, -0.13444032 -0.033210129 0.1420161, -0.13445626 -0.033137143 0.14209272, -0.13062224 -0.032667354 0.1524846, -0.1306223 -0.033297509 0.15284814, -0.13025013 -0.032680064 0.1525199, -0.13062231 -0.032781646 0.15246454, -0.13024664 -0.032793343 0.15250318, -0.13062215 -0.032897532 0.15247123, -0.13024826 -0.032907501 0.15251178, -0.13062215 -0.033008873 0.15250437, -0.13025525 -0.033016354 0.15254577, -0.13062228 -0.033109501 0.15256244, -0.13026714 -0.033114374 0.15260319, -0.1306223 -0.033193916 0.15264203, -0.1302835 -0.033196718 0.15268095, -0.13062228 -0.033257797 0.15273911, -0.13030306 -0.033259064 0.15277477, -0.13032508 -0.033297837 0.15288036, -0.13978934 -0.032667428 0.15248466, -0.13978937 -0.032781661 0.15246448, -0.13978939 -0.032897681 0.15247108, -0.13978945 -0.033008903 0.1525045, -0.13978939 -0.033109576 0.15256245, -0.13978933 -0.033194035 0.15264209, -0.13978939 -0.033257812 0.15273918, -0.13978939 -0.033297628 0.15284826, -0.13989393 -0.033197016 0.15263428, -0.14000694 -0.033201903 0.15260233, -0.13991456 -0.033259124 0.15272786, -0.14004616 -0.033261225 0.15268798, -0.14009027 -0.033298343 0.152784, -0.14017788 -0.033264011 0.15261687, -0.14023878 -0.033299044 0.15269901, -0.13986306 -0.032999367 0.15249242, -0.13987702 -0.033114791 0.15255672, -0.13997412 -0.033123672 0.15253097, -0.14039841 -0.033299968 0.15255471, -0.1405528 -0.033296913 0.15227176, -0.14012326 -0.033208534 0.15254316, -0.13985541 -0.032852948 0.15245804, -0.14032356 -0.033268183 0.15249158, -0.14044949 -0.033254921 0.15222967, -0.13994624 -0.033013299 0.15247025, -0.14007728 -0.033135384 0.15248121, -0.14025633 -0.033217877 0.15243496, -0.14035821 -0.033187807 0.15219241, -0.13985738 -0.032706559 0.15246701, -0.13992992 -0.032872289 0.15243474, -0.14003679 -0.03303194 0.15242657, -0.14019887 -0.03315191 0.15238638, -0.14028427 -0.033099234 0.15216196, -0.13993113 -0.032729238 0.1524377, -0.14001076 -0.032898277 0.15239133, -0.13993756 -0.033297867 0.15283324, -0.14014618 -0.033058137 0.15234186, -0.14000772 -0.032760113 0.15238734, -0.14010827 -0.032935351 0.15231003, -0.14023195 -0.032994241 0.15214045, -0.14009628 -0.032805026 0.15230012, -0.14020415 -0.032878801 0.1521291, -0.14070149 -0.032878846 0.15091415, -0.14072947 -0.032994255 0.15092562, -0.14078182 -0.0330991 0.15094718, -0.14085571 -0.033187732 0.15097751, -0.14094697 -0.033255056 0.15101473, -0.14105032 -0.033296898 0.15105703, -0.14076871 -0.033200398 0.1501587, -0.14071007 -0.033208162 0.15008725, -0.14082898 -0.033252984 0.15010639, -0.14075966 -0.033256918 0.15002753, -0.14068224 -0.03325972 0.14996673, -0.14080422 -0.033285961 0.14997362, -0.14102499 -0.033263147 0.15079455, -0.14104997 -0.033270672 0.15056495, -0.14112724 -0.033298776 0.15081052, -0.14114489 -0.033300623 0.15055706, -0.14071669 -0.033287257 0.14990772, -0.14081673 -0.033190116 0.15024482, -0.1407087 -0.03312014 0.15021075, -0.14093351 -0.033206299 0.15078038, -0.14096397 -0.033223048 0.150572, -0.14074866 -0.033103213 0.15028678, -0.14070049 -0.033000752 0.15031669, -0.14110698 -0.033302039 0.15032543, -0.14064384 -0.033213422 0.15003268, -0.14076917 -0.032975122 0.15075524, -0.1408412 -0.0331119 0.15076645, -0.14065981 -0.033133119 0.15014786, -0.14066423 -0.033024892 0.15024938, -0.14102331 -0.033276662 0.15035227, -0.14060451 -0.033142075 0.15009989, -0.1406215 -0.03304334 0.15019445, -0.14087404 -0.033143505 0.15057923, -0.14094678 -0.033236548 0.15037701, -0.14101966 -0.033303335 0.15011923, -0.14079635 -0.033026204 0.15058552, -0.14095038 -0.033281699 0.15016228, -0.14086466 -0.033169448 0.15040354, -0.14094239 -0.033303872 0.15000802, -0.1408866 -0.033247545 0.15020156, -0.14088343 -0.033284053 0.15005918, -0.14085238 -0.033304393 0.1499155, -0.14078853 -0.033068702 0.15042803, -0.14075367 -0.033304691 0.14984427, -0.13156071 -0.033300072 0.14977331, -0.13156056 -0.033267811 0.14987256, -0.13156071 -0.033215597 0.14996295, -0.13156076 -0.0331458 0.15004092, -0.13029897 -0.033297017 0.15018536, -0.13036057 -0.033256128 0.15027733, -0.1304151 -0.033190504 0.15035844, -0.13045968 -0.033103719 0.15042472, -0.13112664 -0.033299387 0.14982156, -0.13114741 -0.033265382 0.14992113, -0.13116618 -0.03321059 0.15001118, -0.13118209 -0.033137336 0.15008771, -0.1255412 -0.033184126 0.15364049, -0.12553966 -0.033099324 0.15373255, -0.1240737 -0.032668188 0.16847484, -0.1240738 -0.033298478 0.16883852, -0.12370171 -0.032680929 0.16851017, -0.12407373 -0.03278254 0.16845486, -0.12369789 -0.032794222 0.16849342, -0.12407379 -0.03289856 0.16846132, -0.12369969 -0.032908306 0.16850202, -0.12407391 -0.033009782 0.1684947, -0.12370671 -0.033017263 0.16853598, -0.12407376 -0.033110365 0.16855267, -0.12371866 -0.033115283 0.16859329, -0.12407379 -0.033194914 0.16863227, -0.123735 -0.033197656 0.16867101, -0.12407371 -0.033258602 0.16872947, -0.12375467 -0.033259884 0.16876483, -0.12377672 -0.033298746 0.16887057, -0.13324085 -0.032668278 0.16847505, -0.13324086 -0.03278257 0.16845477, -0.13324077 -0.03289862 0.16846132, -0.13324085 -0.033009842 0.16849466, -0.13324082 -0.033110499 0.16855268, -0.13324082 -0.033194944 0.16863225, -0.13324082 -0.033258796 0.16872935, -0.13324086 -0.033298478 0.16883865, -0.13334547 -0.033198014 0.1686243, -0.13345842 -0.033202857 0.16859272, -0.13336594 -0.033260062 0.1687181, -0.13349764 -0.033262253 0.16867825, -0.13354167 -0.033299491 0.16877414, -0.13362922 -0.03326501 0.16860712, -0.13369024 -0.033299968 0.16868936, -0.13331439 -0.03300029 0.1684826, -0.13332838 -0.033115804 0.16854708, -0.13342561 -0.033124462 0.16852152, -0.13384975 -0.033300892 0.16854513, -0.13400425 -0.033297792 0.16826224, -0.13357462 -0.033209532 0.16853338, -0.13330688 -0.032854035 0.16844839, -0.13377488 -0.033269092 0.16848181, -0.13390085 -0.03325586 0.16821994, -0.1333977 -0.033014223 0.16846059, -0.13352872 -0.033136263 0.16847134, -0.13370778 -0.033218876 0.16842508, -0.1338097 -0.03318879 0.16818267, -0.13330893 -0.032707512 0.16845748, -0.13338137 -0.032873198 0.16842531, -0.13348831 -0.033032849 0.16841668, -0.1336502 -0.033152834 0.1683768, -0.13373581 -0.033100113 0.16815247, -0.13338265 -0.032730147 0.16842796, -0.13346228 -0.032899305 0.16838159, -0.133389 -0.033298805 0.1688237, -0.13359758 -0.033059046 0.16833235, -0.13345921 -0.032761022 0.16837762, -0.13355955 -0.03293626 0.16830029, -0.13368329 -0.032995149 0.16813077, -0.13354772 -0.032806098 0.1682903, -0.1336555 -0.032879785 0.16811931, -0.1341531 -0.032879531 0.16690437, -0.13418099 -0.032994986 0.16691598, -0.13423328 -0.033100024 0.16693723, -0.1343073 -0.033188581 0.16696779, -0.13439858 -0.033255622 0.16700493, -0.13450179 -0.033297583 0.16704728, -0.13422024 -0.033201262 0.16614901, -0.1341615 -0.033209011 0.16607763, -0.13428047 -0.033253789 0.16609661, -0.13421115 -0.033257842 0.16601786, -0.13413376 -0.033260569 0.16595696, -0.13425578 -0.03328687 0.16596401, -0.13447654 -0.033263937 0.16678502, -0.13450141 -0.033271357 0.16655514, -0.13457872 -0.03329958 0.16680062, -0.13459626 -0.033301398 0.16654731, -0.13416812 -0.033288121 0.16589782, -0.13426824 -0.03319107 0.166235, -0.13416032 -0.033121124 0.166201, -0.13438493 -0.033207074 0.16677071, -0.13441543 -0.033223927 0.16656205, -0.1342003 -0.033103928 0.1662773, -0.13415198 -0.033001676 0.16630697, -0.13455847 -0.033302844 0.16631542, -0.13409536 -0.033214286 0.16602296, -0.13422076 -0.032975927 0.16674566, -0.13429272 -0.033112571 0.1667565, -0.13411129 -0.033134028 0.16613828, -0.13411574 -0.033025801 0.16623971, -0.13447478 -0.033277571 0.1663426, -0.13405615 -0.033142939 0.16609003, -0.13407293 -0.033044219 0.16618471, -0.13432553 -0.03314428 0.16656937, -0.13439821 -0.033237487 0.1663672, -0.13447109 -0.03330414 0.16610946, -0.13424788 -0.033027008 0.16657603, -0.13440195 -0.033282518 0.16615216, -0.13431613 -0.033170357 0.16639388, -0.13439381 -0.033304736 0.16599809, -0.13433811 -0.033248425 0.16619156, -0.13433494 -0.033284947 0.16604927, -0.13430384 -0.033305213 0.16590585, -0.13424021 -0.033069506 0.16641833, -0.13420516 -0.033305541 0.16583444, -0.1250122 -0.033300862 0.16576341, -0.12501213 -0.033268601 0.16586275, -0.12501222 -0.033216342 0.16595319, -0.12501216 -0.033146545 0.16603105, -0.12375051 -0.033297881 0.16617575, -0.12381217 -0.033256993 0.16626753, -0.12386665 -0.033191368 0.16634865, -0.12391122 -0.033104613 0.16641492, -0.12457816 -0.033300295 0.16581166, -0.12459892 -0.033266172 0.16591135, -0.12461768 -0.033211395 0.16600156, -0.12463365 -0.033138335 0.16607797, -0.11899264 -0.03318496 0.16963065, -0.11899129 -0.033100232 0.16972274, -0.12079948 -0.03266865 0.17646992, -0.12079951 -0.033298954 0.17683366, -0.12042741 -0.032681331 0.1765051, -0.1207995 -0.032783002 0.17644989, -0.12042378 -0.032794669 0.17648859, -0.12079942 -0.032898992 0.17645642, -0.12042557 -0.032908708 0.17649733, -0.12079956 -0.033010185 0.17648984, -0.12043248 -0.033017665 0.17653118, -0.1207995 -0.033110827 0.17654788, -0.1204444 -0.033115774 0.17658852, -0.12079941 -0.033195287 0.1766275, -0.12046073 -0.033198029 0.1766661, -0.1207995 -0.033259124 0.17672455, -0.12048034 -0.033260316 0.17676029, -0.12050261 -0.033299088 0.17686592, -0.12996663 -0.032668605 0.17647016, -0.12996663 -0.032783061 0.17644984, -0.12996663 -0.032899007 0.17645667, -0.12996656 -0.033010274 0.17648971, -0.12996663 -0.033110917 0.17654784, -0.12996656 -0.033195406 0.1766274, -0.1299666 -0.033259243 0.17672445, -0.12996656 -0.033298999 0.17683351, -0.13007116 -0.033198342 0.17661947, -0.13018399 -0.033203274 0.17658782, -0.1300918 -0.033260465 0.17671339, -0.13022339 -0.033262536 0.17667332, -0.1302675 -0.033299729 0.17676917, -0.130355 -0.033265427 0.17660213, -0.13041601 -0.033300295 0.1766845, -0.13004014 -0.033000588 0.17647767, -0.13005421 -0.033116102 0.17654216, -0.13015142 -0.033125028 0.17651644, -0.13057536 -0.033301383 0.17654015, -0.13073 -0.033298165 0.17625727, -0.13030055 -0.033210024 0.17652836, -0.1300326 -0.032854453 0.17644347, -0.13050069 -0.033269554 0.1764769, -0.13062662 -0.033256322 0.17621495, -0.13012338 -0.03301464 0.1764558, -0.13025443 -0.033136651 0.17646645, -0.13043347 -0.033219323 0.17642026, -0.13053548 -0.033189192 0.17617761, -0.13003451 -0.03270784 0.17645265, -0.13010728 -0.032873645 0.17642044, -0.13021392 -0.033033282 0.17641176, -0.13037603 -0.033153251 0.17637169, -0.13046157 -0.03310056 0.1761476, -0.1301083 -0.032730609 0.17642309, -0.13018781 -0.032899648 0.17637672, -0.13011481 -0.033299148 0.17681868, -0.13032335 -0.033059388 0.17632748, -0.13018498 -0.03276144 0.17637263, -0.13028535 -0.032936737 0.17629541, -0.13040914 -0.032995552 0.176126, -0.13027345 -0.032806531 0.17628539, -0.13038127 -0.032880113 0.17611453, -0.13087872 -0.032880083 0.17489944, -0.13090655 -0.032995492 0.17491104, -0.13095894 -0.033100471 0.17493258, -0.13103296 -0.033189073 0.17496276, -0.13112408 -0.033256203 0.17500021, -0.13122761 -0.03329809 0.17504241, -0.13093702 -0.033258349 0.17401284, -0.13085946 -0.033261195 0.173952, -0.13098143 -0.033287331 0.17395899, -0.13120219 -0.033264309 0.17478003, -0.13122711 -0.033271953 0.17455025, -0.13130444 -0.033299983 0.17479585, -0.13132221 -0.033301815 0.17454259, -0.1308938 -0.033288509 0.17389311, -0.13099393 -0.033191592 0.17423023, -0.13088612 -0.033121616 0.17419618, -0.13094589 -0.033201724 0.17414404, -0.13111067 -0.033207625 0.174766, -0.13114122 -0.033224359 0.17455731, -0.13092598 -0.033104554 0.17427219, -0.13087772 -0.033002138 0.17430228, -0.13128418 -0.03330332 0.17431067, -0.13082108 -0.033214822 0.17401792, -0.13088742 -0.033209547 0.17407294, -0.13094655 -0.032976404 0.17474078, -0.13101846 -0.033113107 0.17475188, -0.13083713 -0.03313452 0.1741333, -0.13084148 -0.033026263 0.17423484, -0.13120055 -0.033277959 0.1743378, -0.13078183 -0.033143312 0.17408541, -0.1307985 -0.033044666 0.17417988, -0.1310512 -0.033144727 0.17456472, -0.13112399 -0.033237964 0.17436232, -0.13119683 -0.033304602 0.17410482, -0.13097373 -0.033027396 0.17457099, -0.13112757 -0.033283025 0.17414738, -0.13104193 -0.033170849 0.17438883, -0.13111958 -0.033305198 0.17399336, -0.13106382 -0.033248976 0.17418687, -0.13106075 -0.033285454 0.17404439, -0.13102964 -0.033305779 0.17390107, -0.1309658 -0.033069879 0.17441358, -0.13100621 -0.033254296 0.17409159, -0.13093078 -0.033306077 0.1738296, -0.12173797 -0.03330119 0.17375864, -0.12173797 -0.033269003 0.17385782, -0.12173791 -0.033216819 0.17394848, -0.12173788 -0.033147082 0.17402603, -0.12047622 -0.033298478 0.17417076, -0.12053789 -0.033257365 0.17426263, -0.12059245 -0.033191904 0.17434373, -0.1206369 -0.033105195 0.17440994, -0.1213039 -0.033300787 0.17380665, -0.12132467 -0.033266693 0.17390676, -0.12134342 -0.033211812 0.1739967, -0.1213593 -0.033138812 0.17407329, -0.1157185 -0.033185422 0.17762581, -0.11571704 -0.033100635 0.17771782, -0.11752522 -0.032669052 0.18446536, -0.11752521 -0.033299372 0.18482867, -0.11715323 -0.032681867 0.18450041, -0.11752525 -0.032783434 0.18444507, -0.11714956 -0.032795131 0.18448357, -0.11752526 -0.032899454 0.18445174, -0.11715131 -0.032909259 0.18449244, -0.11752516 -0.033010662 0.184485, -0.11715826 -0.033018202 0.18452652, -0.11752525 -0.0331112 0.18454303, -0.11717026 -0.033116117 0.18458377, -0.11752523 -0.033195645 0.18462262, -0.11718646 -0.033198625 0.18466122, -0.11752519 -0.033259645 0.18471964, -0.11720604 -0.033260763 0.18475525, -0.11722815 -0.033299685 0.18486086, -0.12669235 -0.032669157 0.1844652, -0.12669231 -0.032783523 0.18444517, -0.12669243 -0.032899335 0.1844517, -0.12669232 -0.033010736 0.18448508, -0.12669243 -0.033111349 0.1845428, -0.12669244 -0.033195823 0.18462269, -0.12669231 -0.033259705 0.18471968, -0.12669243 -0.033299312 0.18482885, -0.12679686 -0.033198848 0.18461457, -0.12690987 -0.033203736 0.18458298, -0.12681745 -0.033260956 0.18470842, -0.12694913 -0.033262998 0.18466856, -0.12699319 -0.033300206 0.18476456, -0.12708069 -0.033265904 0.18459737, -0.12714186 -0.033300787 0.18467984, -0.12676586 -0.033001199 0.18447271, -0.12677994 -0.033116668 0.18453734, -0.12687719 -0.03312549 0.1845116, -0.12730135 -0.033301771 0.18453535, -0.12745573 -0.033298567 0.18425238, -0.12702624 -0.033210441 0.18452376, -0.12675835 -0.03285481 0.1844385, -0.12722637 -0.033270046 0.18447214, -0.12735255 -0.033256635 0.18421009, -0.12684916 -0.033015117 0.18445083, -0.1269802 -0.033137098 0.1844615, -0.12715925 -0.033219829 0.18441525, -0.12726118 -0.033189535 0.18417269, -0.12676032 -0.032708287 0.18444756, -0.12683298 -0.032873988 0.18441552, -0.12693974 -0.033033758 0.18440683, -0.12710169 -0.033153653 0.1843669, -0.12718739 -0.033100933 0.18414256, -0.12683405 -0.032731101 0.18441826, -0.1269137 -0.032900095 0.18437167, -0.12684059 -0.033299744 0.18481377, -0.1270491 -0.03305985 0.18432251, -0.12691067 -0.032761961 0.18436772, -0.12701119 -0.032937005 0.18429053, -0.12713495 -0.032996029 0.18412095, -0.12699915 -0.032806918 0.18428057, -0.12710704 -0.03288047 0.18410963, -0.1276045 -0.03288047 0.18289477, -0.12763253 -0.032995909 0.18290609, -0.12768488 -0.033100918 0.1829277, -0.12775876 -0.03318958 0.18295807, -0.12784998 -0.03325665 0.18299517, -0.12795348 -0.033298448 0.1830377, -0.1276717 -0.033202186 0.18213919, -0.12761308 -0.033209965 0.18206793, -0.12773205 -0.033254698 0.18208659, -0.12766264 -0.033258811 0.18200794, -0.12758526 -0.033261552 0.18194711, -0.12770723 -0.033287778 0.18195418, -0.12792788 -0.033264771 0.18277529, -0.12795286 -0.033272281 0.18254527, -0.12803029 -0.033300415 0.18279117, -0.12804794 -0.033302292 0.18253776, -0.12761961 -0.033288971 0.18188825, -0.12771966 -0.03319189 0.1822252, -0.12761189 -0.033121988 0.18219119, -0.12783645 -0.033207998 0.1827614, -0.12786689 -0.033224791 0.18255252, -0.12765183 -0.033104867 0.18226752, -0.12760347 -0.0330026 0.18229726, -0.12801005 -0.033303782 0.18230599, -0.12754686 -0.03321515 0.18201306, -0.12767218 -0.032976761 0.18273583, -0.12774421 -0.033113509 0.18274692, -0.12756297 -0.033134833 0.18212831, -0.12756743 -0.033026576 0.18222982, -0.12792626 -0.03327848 0.18233268, -0.12750758 -0.033143848 0.18208048, -0.12752445 -0.033045143 0.18217498, -0.12777705 -0.033145264 0.18255979, -0.12784977 -0.033238411 0.18235734, -0.12792267 -0.03330496 0.18209973, -0.12769924 -0.033027902 0.18256608, -0.12785341 -0.033283308 0.18214262, -0.12776774 -0.033171281 0.18238392, -0.12784541 -0.033305705 0.18198839, -0.1277896 -0.033249348 0.18218207, -0.12778638 -0.033285871 0.18203953, -0.12775554 -0.033306062 0.1818963, -0.12769166 -0.033070415 0.18240839, -0.12765659 -0.033306524 0.18182462, -0.11846384 -0.033301562 0.1817539, -0.11846367 -0.033269539 0.18185298, -0.1184637 -0.033217296 0.18194357, -0.11846364 -0.033147439 0.18202116, -0.11720189 -0.033298761 0.18216594, -0.11726356 -0.033257797 0.18225777, -0.11731815 -0.033192337 0.1823387, -0.11736271 -0.033105463 0.18240513, -0.11802976 -0.033301204 0.18180171, -0.11805046 -0.03326717 0.18190187, -0.1180691 -0.033212245 0.18199165, -0.11808503 -0.033139214 0.18206824, -0.11392775 -0.033299223 0.19016133, -0.11398932 -0.033258215 0.19025303, -0.11404388 -0.033192709 0.19033402, -0.10916989 -0.033186361 0.19361594, -0.11408839 -0.033105925 0.19040044, -0.10916846 -0.033101603 0.19370809, -0.11518933 -0.033147886 0.19001633, -0.11518945 -0.033302262 0.18974906, -0.11475541 -0.033301651 0.189797, -0.11518948 -0.033269912 0.18984805, -0.11477622 -0.033267587 0.1898969, -0.11518945 -0.033217743 0.18993872, -0.11479495 -0.033212751 0.18998682, -0.11481084 -0.03313978 0.19006342, -0.12438852 -0.033259258 0.19000292, -0.12431104 -0.033262014 0.18994246, -0.12443295 -0.033288196 0.18994936, -0.12465374 -0.033265233 0.19077019, -0.12467855 -0.033272803 0.19054034, -0.12475602 -0.033300936 0.19078614, -0.12477379 -0.033302635 0.19053276, -0.12434535 -0.033289522 0.18988331, -0.12444553 -0.033192471 0.19022003, -0.12433757 -0.033122301 0.19018635, -0.12439755 -0.033202693 0.1901342, -0.12456232 -0.033208355 0.19075644, -0.12459275 -0.033225253 0.19054762, -0.12437753 -0.033105224 0.19026239, -0.12432922 -0.033003092 0.19029252, -0.12473573 -0.033304214 0.19030111, -0.1242726 -0.033215672 0.19000818, -0.12433881 -0.033210441 0.19006297, -0.12439802 -0.032977238 0.19073099, -0.12433034 -0.032881007 0.19088979, -0.12435825 -0.032996267 0.19090135, -0.12428874 -0.033135444 0.19012365, -0.12447013 -0.033113986 0.19074203, -0.12429303 -0.033027127 0.19022495, -0.12465204 -0.033278972 0.1903279, -0.12423335 -0.033144325 0.19007553, -0.1242501 -0.033045709 0.19016995, -0.12450279 -0.033145934 0.19055487, -0.12457553 -0.033238888 0.19035248, -0.12464842 -0.033305421 0.19009507, -0.12442508 -0.033028364 0.1905611, -0.12457909 -0.033283859 0.19013776, -0.12449339 -0.033171669 0.1903792, -0.1245711 -0.033306122 0.18998365, -0.12451532 -0.033249855 0.19017713, -0.12451212 -0.033286393 0.19003464, -0.1244811 -0.033306628 0.18989135, -0.12441744 -0.033070803 0.19040363, -0.12445778 -0.033255264 0.19008204, -0.12457575 -0.033257157 0.19099034, -0.12467912 -0.033298865 0.19103283, -0.12438227 -0.033306956 0.18981998, -0.12441054 -0.033101276 0.19092259, -0.12448452 -0.033189923 0.19095282, -0.12383287 -0.032880887 0.19210489, -0.1238607 -0.032996371 0.19211604, -0.1239132 -0.033101276 0.19213769, -0.12398717 -0.033189863 0.19216789, -0.12407829 -0.033256993 0.19220524, -0.12418155 -0.033298984 0.19224755, -0.12354335 -0.03326115 0.19270362, -0.12363583 -0.033204034 0.19257826, -0.12367497 -0.033263385 0.19266368, -0.12352282 -0.033199146 0.19260985, -0.12371895 -0.033300474 0.19275969, -0.12380664 -0.033266202 0.19259255, -0.12386754 -0.03330113 0.19267485, -0.12341814 -0.032899752 0.19244675, -0.12349169 -0.033001617 0.19246791, -0.12341823 -0.033011064 0.19248013, -0.12350591 -0.033116892 0.19253238, -0.12360303 -0.033125669 0.19250681, -0.12402718 -0.033302009 0.1925306, -0.123752 -0.03321071 0.19251895, -0.12341814 -0.032783881 0.19244008, -0.12348431 -0.032855108 0.19243377, -0.12395221 -0.033270314 0.19246715, -0.12357499 -0.033015355 0.19244592, -0.12370603 -0.033137575 0.19245677, -0.12341817 -0.032669455 0.19246037, -0.12388508 -0.033220083 0.19241048, -0.12348622 -0.0327086 0.19244272, -0.12355874 -0.032874346 0.19241069, -0.12366556 -0.033034027 0.19240202, -0.12382747 -0.033153996 0.19236188, -0.12355997 -0.03273128 0.19241337, -0.12363952 -0.032900408 0.19236678, -0.12377493 -0.033060208 0.19231765, -0.1234182 -0.033299729 0.1928238, -0.12356639 -0.033299863 0.19280881, -0.12363648 -0.032762215 0.19236296, -0.12341811 -0.033259973 0.19271486, -0.12373702 -0.032937467 0.19228575, -0.1237251 -0.032807246 0.19227545, -0.12341814 -0.033196107 0.1926177, -0.12341826 -0.033111766 0.19253801, -0.114251 -0.03266944 0.19246046, -0.114251 -0.032783762 0.19244008, -0.11425106 -0.032899693 0.19244689, -0.11425099 -0.033011094 0.19248001, -0.11425105 -0.033111528 0.19253804, -0.11425105 -0.033196047 0.19261779, -0.11425106 -0.033260003 0.19271469, -0.11425105 -0.03329964 0.19282381, -0.11387895 -0.032682166 0.19249561, -0.11387524 -0.032795563 0.19247867, -0.11387697 -0.032909587 0.19248749, -0.11388414 -0.033018366 0.19252168, -0.11389594 -0.033116624 0.19257882, -0.11391218 -0.033198848 0.19265635, -0.11393197 -0.033261105 0.19275036, -0.11395405 -0.033299938 0.19285613, -0.11065355 -0.03329955 0.19815622, -0.11071521 -0.033258781 0.19824786, -0.11076969 -0.033193007 0.19832923, -0.10589576 -0.033186689 0.20161119, -0.1108142 -0.033106372 0.19839543, -0.10589425 -0.033101961 0.20170341, -0.11191534 -0.033148155 0.19801152, -0.11191523 -0.033302531 0.19774403, -0.11148128 -0.033301875 0.19779222, -0.11191531 -0.033270285 0.19784343, -0.11150192 -0.03326802 0.19789201, -0.11191528 -0.03321816 0.197934, -0.11152077 -0.033213302 0.19798203, -0.11153668 -0.033140108 0.1980585, -0.12111418 -0.033259735 0.19799833, -0.12103686 -0.033262327 0.19793731, -0.12115876 -0.033288613 0.19794457, -0.12137952 -0.033265665 0.19876561, -0.12140447 -0.033273235 0.19853565, -0.12148187 -0.033301279 0.19878137, -0.12149949 -0.033303246 0.19852819, -0.1210712 -0.033289894 0.19787847, -0.12117128 -0.033192858 0.19821553, -0.12106335 -0.033122823 0.19818157, -0.12112325 -0.03320308 0.19812948, -0.12128806 -0.033208892 0.19875151, -0.12131853 -0.0332257 0.19854273, -0.12110315 -0.033105835 0.19825761, -0.12105511 -0.033003435 0.19828759, -0.12146147 -0.033304617 0.19829626, -0.12099843 -0.033216104 0.19800346, -0.12106453 -0.033210918 0.19805817, -0.1211237 -0.032977834 0.19872618, -0.12105604 -0.032881424 0.19888486, -0.12108392 -0.032996729 0.19889635, -0.1210143 -0.033135965 0.19811863, -0.12119573 -0.033114389 0.1987372, -0.12101887 -0.033027515 0.19822012, -0.12137781 -0.033279404 0.19832288, -0.12095903 -0.033144757 0.19807081, -0.12097596 -0.033046111 0.19816528, -0.12122852 -0.033146158 0.19854996, -0.12130137 -0.03323935 0.1983477, -0.12137419 -0.033305958 0.19809014, -0.12115082 -0.033028796 0.19855636, -0.12130497 -0.033284411 0.19813298, -0.1212192 -0.033172145 0.1983742, -0.12129684 -0.033306643 0.19797875, -0.12124103 -0.033250287 0.19817239, -0.12123796 -0.033286795 0.19802967, -0.12120694 -0.033307031 0.19788653, -0.12114303 -0.033071324 0.19839881, -0.12118344 -0.033255681 0.19807689, -0.12130146 -0.033257499 0.1989855, -0.12140492 -0.033299461 0.1990279, -0.12110804 -0.033307359 0.19781522, -0.12113635 -0.033101782 0.19891779, -0.12121026 -0.033190414 0.19894825, -0.1205586 -0.032881364 0.20009999, -0.1205864 -0.032996818 0.20011133, -0.12063892 -0.033101842 0.20013274, -0.12071277 -0.033190325 0.20016308, -0.12080406 -0.03325747 0.20020054, -0.12090731 -0.033299491 0.20024282, -0.12026905 -0.033261642 0.20069872, -0.12036152 -0.03320466 0.20057346, -0.12040064 -0.033263877 0.20065884, -0.12024853 -0.033199623 0.20060484, -0.1204447 -0.033300981 0.20075479, -0.12053233 -0.033266768 0.20058754, -0.12059328 -0.033301666 0.20066993, -0.12014386 -0.032900259 0.20044196, -0.12021737 -0.033002034 0.2004631, -0.12014396 -0.033011541 0.20047535, -0.12023148 -0.033117458 0.20052743, -0.12032869 -0.03312631 0.20050201, -0.12075286 -0.033302531 0.20052543, -0.12047775 -0.033211216 0.20051387, -0.12014385 -0.032784387 0.2004353, -0.12020998 -0.032855496 0.20042877, -0.12067801 -0.033270851 0.20046231, -0.12030071 -0.033015922 0.20044118, -0.12043171 -0.033138052 0.20045178, -0.12014385 -0.032669917 0.20045562, -0.12061082 -0.033220574 0.20040576, -0.12021178 -0.032709137 0.20043787, -0.12028442 -0.032874987 0.20040564, -0.12039129 -0.033034578 0.20039706, -0.12055333 -0.033154592 0.20035709, -0.12028567 -0.032731906 0.20040838, -0.12036519 -0.032900944 0.20036201, -0.12050079 -0.033060655 0.20031296, -0.12014382 -0.033300236 0.20081906, -0.12029213 -0.033300474 0.20080394, -0.12036231 -0.032762721 0.200358, -0.12014395 -0.033260569 0.20070985, -0.12046273 -0.032937929 0.20028086, -0.12045078 -0.032807723 0.2002707, -0.12014383 -0.033196673 0.20061293, -0.12014385 -0.033112183 0.20053311, -0.11097656 -0.032669947 0.20045549, -0.1109767 -0.032784387 0.20043536, -0.11097668 -0.032900259 0.20044202, -0.11097671 -0.033011541 0.20047516, -0.11097671 -0.033112064 0.2005332, -0.1109767 -0.033196583 0.20061296, -0.1109767 -0.03326048 0.20070976, -0.11097674 -0.033300087 0.20081888, -0.11060472 -0.032682583 0.20049083, -0.11060111 -0.032795921 0.20047387, -0.11060266 -0.032910034 0.20048262, -0.1106098 -0.033018932 0.20051667, -0.11062157 -0.033117011 0.2005738, -0.11063787 -0.033199385 0.20065157, -0.11065754 -0.033261612 0.20074563, -0.11067978 -0.033300385 0.20085093, -0.10770248 -0.032670245 0.2084507, -0.10770239 -0.033300534 0.20881408, -0.10733047 -0.032682881 0.20848583, -0.10770245 -0.032784656 0.20843035, -0.10732687 -0.032796279 0.20846902, -0.10770252 -0.032900587 0.20843706, -0.10732853 -0.032910362 0.20847796, -0.10770251 -0.033011928 0.20847017, -0.10733557 -0.033019289 0.20851193, -0.10770251 -0.033112541 0.2085284, -0.10734747 -0.033117458 0.20856902, -0.10770251 -0.033196941 0.20860797, -0.10736378 -0.033199623 0.20864671, -0.10770251 -0.033260837 0.20870525, -0.10738346 -0.03326188 0.20874085, -0.10740556 -0.033300772 0.20884627, -0.11686966 -0.032670364 0.20845072, -0.1168696 -0.032784685 0.20843028, -0.1168696 -0.032900795 0.20843695, -0.11686963 -0.033011869 0.20847015, -0.11686966 -0.033112451 0.20852838, -0.11686964 -0.03319709 0.208608, -0.11686973 -0.033260897 0.20870495, -0.11686957 -0.033300593 0.20881404, -0.11697428 -0.033199981 0.20860004, -0.11708722 -0.033204958 0.20856832, -0.11699477 -0.033262119 0.20869361, -0.11712649 -0.033264264 0.20865391, -0.11717048 -0.033301339 0.20874976, -0.11725806 -0.033267036 0.20858264, -0.11731921 -0.033302113 0.2086651, -0.11694315 -0.033002362 0.2084582, -0.11695722 -0.033117875 0.20852269, -0.11705449 -0.033126697 0.20849703, -0.11747864 -0.033303007 0.20852067, -0.11763309 -0.033299878 0.20823783, -0.11720359 -0.033211604 0.20850909, -0.11693572 -0.032856032 0.20842394, -0.11740373 -0.033271208 0.20845735, -0.11752979 -0.033257917 0.20819545, -0.11702648 -0.033016309 0.20843612, -0.11715765 -0.03313835 0.20844698, -0.11733668 -0.033220962 0.20840073, -0.11743858 -0.033190712 0.2081582, -0.11693762 -0.032709613 0.20843291, -0.11701019 -0.032875374 0.20840085, -0.11711699 -0.033034995 0.20839229, -0.11727905 -0.03315492 0.20835233, -0.1173646 -0.033102229 0.20812786, -0.11701153 -0.032732174 0.20840356, -0.11709112 -0.032901362 0.20835717, -0.11701778 -0.033300862 0.20879899, -0.11722654 -0.033061102 0.20830782, -0.11708805 -0.032763049 0.20835304, -0.11718859 -0.032938406 0.20827594, -0.11731227 -0.032997295 0.20810625, -0.11717656 -0.032808051 0.20826589, -0.11728433 -0.032881901 0.20809519, -0.11778179 -0.032881841 0.20687996, -0.11780968 -0.032997236 0.2068914, -0.11786203 -0.033102259 0.20691296, -0.11793612 -0.033190772 0.20694336, -0.11802723 -0.033257887 0.20698074, -0.1181307 -0.033299878 0.20702296, -0.11784905 -0.033203647 0.20612445, -0.1177903 -0.033211336 0.20605317, -0.11790934 -0.033256158 0.2060722, -0.11783996 -0.033260211 0.20599304, -0.11776249 -0.033262864 0.20593256, -0.11788455 -0.03328906 0.20593964, -0.11810525 -0.033266112 0.2067605, -0.11813021 -0.033273652 0.20653059, -0.11820762 -0.033301786 0.20677614, -0.11822528 -0.033303574 0.20652302, -0.11779696 -0.033290341 0.20587371, -0.11789703 -0.033193424 0.20621066, -0.11778904 -0.033123359 0.20617649, -0.1180138 -0.033209369 0.20674649, -0.11804417 -0.033225939 0.20653787, -0.11782907 -0.033106223 0.20625269, -0.11778075 -0.033004001 0.2062826, -0.11818714 -0.033305064 0.20629126, -0.11772412 -0.033216611 0.20599835, -0.11784951 -0.032978162 0.20672128, -0.1179215 -0.033114895 0.20673226, -0.11774009 -0.033136323 0.20611364, -0.11774454 -0.033028051 0.20621513, -0.1181035 -0.033279851 0.2063179, -0.1176848 -0.033145145 0.20606577, -0.11770169 -0.033046469 0.2061604, -0.11795443 -0.033146665 0.20654503, -0.11802697 -0.033239797 0.2063427, -0.11809996 -0.033306345 0.20608507, -0.11787671 -0.033029154 0.20655139, -0.11803062 -0.033284709 0.20612797, -0.11794487 -0.033172593 0.20636906, -0.11802271 -0.033307061 0.20597373, -0.1179668 -0.033250794 0.20616721, -0.11796385 -0.033287182 0.20602502, -0.11793271 -0.033307567 0.2058816, -0.1178689 -0.033071831 0.2063936, -0.11783402 -0.033307865 0.20580995, -0.10864106 -0.033303156 0.20573922, -0.10864097 -0.033270761 0.20583852, -0.10864098 -0.033218637 0.20592892, -0.10864095 -0.03314878 0.20600659, -0.10737921 -0.033300176 0.20615143, -0.10744074 -0.033259228 0.20624308, -0.10749541 -0.033193573 0.20632449, -0.10753994 -0.033106819 0.20639068, -0.10820697 -0.03330256 0.2057873, -0.10822761 -0.033268616 0.20588706, -0.10824651 -0.03321375 0.20597729, -0.10826223 -0.033140555 0.20605356, -0.10262142 -0.033187076 0.2096063, -0.10262002 -0.033102229 0.20969827, -0.1041051 -0.033300564 0.21414633, -0.1041666 -0.033259645 0.21423808, -0.10422122 -0.033193961 0.21431932, -0.099347189 -0.033187523 0.21760152, -0.10426569 -0.033107266 0.2143856, -0.099345699 -0.033102736 0.21769349, -0.10536678 -0.033149078 0.21400182, -0.10536671 -0.033303335 0.21373434, -0.10493265 -0.033302739 0.21378244, -0.10536672 -0.033271179 0.21383367, -0.10495354 -0.033268794 0.21388207, -0.10536678 -0.033218935 0.21392427, -0.10497223 -0.033213928 0.21397234, -0.10498814 -0.033140823 0.214049, -0.11420539 -0.033303455 0.21373439, -0.11420552 -0.033271119 0.2138337, -0.11420535 -0.033219025 0.2139241, -0.11420545 -0.033149078 0.21400183, -0.11467743 -0.033205375 0.21494487, -0.11475365 -0.033221319 0.21475045, -0.11476517 -0.03326498 0.21498063, -0.11452858 -0.033308879 0.21378227, -0.11484136 -0.033271983 0.21476473, -0.11462294 -0.0333087 0.21384214, -0.11459671 -0.033071563 0.21439783, -0.1145571 -0.033107325 0.21425091, -0.11467217 -0.033171698 0.21437459, -0.11493823 -0.033303633 0.21478045, -0.11495765 -0.033305213 0.21453057, -0.11462466 -0.033193305 0.2142096, -0.11486723 -0.03327854 0.2145368, -0.11461423 -0.033264801 0.21402137, -0.11454317 -0.033267632 0.21395218, -0.11466187 -0.033291385 0.21397343, -0.11458161 -0.033292785 0.21389931, -0.11454917 -0.033031479 0.21489255, -0.11464563 -0.033114269 0.21473324, -0.11460431 -0.03312628 0.21491502, -0.11449687 -0.033293679 0.21384363, -0.11478473 -0.033235833 0.21454258, -0.11454973 -0.033207789 0.21408617, -0.11470628 -0.033258066 0.21415994, -0.11492194 -0.033306554 0.21429767, -0.11443076 -0.033308998 0.21374023, -0.11457455 -0.032979056 0.21472189, -0.11452125 -0.033038184 0.21427254, -0.11451492 -0.032925799 0.21487826, -0.11446749 -0.033269569 0.21390085, -0.1148421 -0.033283904 0.21432245, -0.11440894 -0.033294097 0.21380484, -0.11467944 -0.033145592 0.21454982, -0.11449069 -0.033213899 0.21402493, -0.11455104 -0.032878116 0.21471816, -0.11449473 -0.033131316 0.21414141, -0.11476852 -0.033247992 0.21434493, -0.11438856 -0.033270732 0.21386516, -0.11483318 -0.033307716 0.21408263, -0.11442724 -0.033218071 0.21397923, -0.11446412 -0.033069119 0.2141722, -0.11460273 -0.033029154 0.21455519, -0.11444531 -0.033141986 0.21408729, -0.11476725 -0.033288404 0.21412268, -0.11436069 -0.033220217 0.21394786, -0.11441942 -0.033082858 0.21412303, -0.11457035 -0.032939449 0.21455753, -0.11439209 -0.033148721 0.2140476, -0.11471313 -0.033308402 0.21392208, -0.11437188 -0.033091828 0.21408693, -0.11433634 -0.033152297 0.21402031, -0.11432205 -0.033096477 0.21406242, -0.11456029 -0.032992437 0.21440904, -0.1148631 -0.033301935 0.21502081, -0.11436559 -0.033301964 0.21623568, -0.11426769 -0.033265039 0.21619555, -0.11418 -0.033205524 0.21615976, -0.11410677 -0.03312622 0.21612963, -0.11405165 -0.033031508 0.21610723, -0.11401735 -0.032925889 0.21609299, -0.11392331 -0.032977924 0.21627858, -0.11390364 -0.032856986 0.21626201, -0.11382224 -0.032944158 0.21635993, -0.11389624 -0.033301726 0.21674493, -0.11404487 -0.033302441 0.21666037, -0.11382863 -0.032650724 0.21636844, -0.11382195 -0.032687619 0.21635944, -0.11390719 -0.032735065 0.21626502, -0.11359535 -0.033112898 0.21652368, -0.11368307 -0.033118382 0.21651791, -0.11359546 -0.033197537 0.21660315, -0.11381222 -0.032814488 0.21634613, -0.11369996 -0.033200547 0.21659541, -0.11391267 -0.032698765 0.21626973, -0.11381294 -0.033205435 0.21656352, -0.11372051 -0.033262506 0.21668898, -0.11385228 -0.033264652 0.21664891, -0.11398382 -0.033267364 0.21657784, -0.11359535 -0.032901093 0.21643226, -0.11367045 -0.033020303 0.21646063, -0.11359547 -0.033012286 0.21646538, -0.11378013 -0.033127114 0.21649234, -0.1142043 -0.033303455 0.21651573, -0.11392918 -0.033211961 0.21650428, -0.11359552 -0.032785192 0.21642572, -0.1136627 -0.032902285 0.21642499, -0.11375548 -0.033033565 0.21643837, -0.11412954 -0.033271655 0.21645245, -0.11388329 -0.033138886 0.21644205, -0.11359538 -0.032670811 0.21644576, -0.11366154 -0.032763198 0.21642001, -0.11373909 -0.032920167 0.21640287, -0.11406234 -0.033221439 0.21639609, -0.11384764 -0.033051148 0.21639401, -0.11400475 -0.033155397 0.21634741, -0.11366829 -0.032632247 0.21645117, -0.11373474 -0.032784954 0.2163934, -0.11359535 -0.033301011 0.2168093, -0.11374365 -0.03330119 0.21679425, -0.11367179 -0.032595351 0.21646674, -0.1135954 -0.033261374 0.2167003, -0.1139587 -0.033075854 0.21630852, -0.1137452 -0.032655522 0.21641617, -0.10442819 -0.032670751 0.21644585, -0.10442819 -0.032785192 0.21642558, -0.10442829 -0.032901093 0.21643227, -0.10442823 -0.033012345 0.21646541, -0.10442837 -0.033112958 0.21652369, -0.10442825 -0.033197418 0.21660303, -0.10442825 -0.033261344 0.21670018, -0.10442819 -0.033301011 0.21680932, -0.10405625 -0.032683417 0.21648084, -0.1040526 -0.032796755 0.21646415, -0.10405436 -0.032910898 0.21647307, -0.10406123 -0.033019856 0.21650691, -0.10407323 -0.033117846 0.21656424, -0.10408944 -0.033200219 0.21664184, -0.10410918 -0.033262387 0.21673588, -0.10413134 -0.033301279 0.2168414, -0.13720809 -0.032923982 0.1363392, -0.13720824 -0.033301994 0.13655744, -0.13683908 -0.032931536 0.13637568, -0.13720821 -0.032992616 0.13632716, -0.1368368 -0.032999545 0.13636562, -0.13720812 -0.033062026 0.13633119, -0.13683768 -0.033068061 0.1363707, -0.13720809 -0.033128902 0.136351, -0.13684192 -0.033133298 0.13639101, -0.13720809 -0.033189222 0.13638581, -0.13684919 -0.033192173 0.13642561, -0.13720815 -0.033239931 0.13643374, -0.13685885 -0.033241525 0.13647199, -0.13720827 -0.033278272 0.13649182, -0.13687067 -0.033278912 0.13652839, -0.13688396 -0.033302233 0.13659193, -0.13649213 -0.033169627 0.13652194, -0.097219422 0.084743574 0.2662048, -0.097219333 0.084828064 0.26622748, -0.096361116 0.085233286 0.26619062, -0.096397117 0.085159793 0.26626036, -0.096429721 0.085071996 0.2663129, -0.096457437 0.084973529 0.26634526, -0.096478894 0.084868923 0.26635644, -0.096490815 0.084785059 0.26634976, -0.096497938 0.084702715 0.26632947, -0.096830443 0.085047677 0.26624429, -0.10605814 0.084743604 0.26620489, -0.10605808 0.084827945 0.26622742, -0.10649578 0.08514677 0.26627475, -0.10640985 0.085263833 0.26612699, -0.10656488 0.085217938 0.26621825, -0.10636246 0.085187301 0.26619548, -0.10616004 0.084901735 0.26624537, -0.10617346 0.085012898 0.26623571, -0.10628454 0.08498992 0.26627257, -0.10619116 0.085118398 0.26620233, -0.10631992 0.085094348 0.26624492, -0.10643399 0.085058436 0.26631314, -0.1061531 0.084814146 0.26623541, -0.10625838 0.084879473 0.26627639, -0.10614954 0.084729448 0.26621053, -0.10638276 0.084957376 0.2663309, -0.1062447 0.084791973 0.26626316, -0.10634507 0.084849283 0.2663275, -0.10623823 0.084707066 0.26623547, -0.10632589 0.084762827 0.26630956, -0.10631707 0.084678546 0.26627916, -0.10623609 0.085292235 0.26607069, -0.10621235 0.085212961 0.26614618, -0.10599358 0.084043637 0.26765427, -0.10602312 0.084139034 0.26771563, -0.10607621 0.084220752 0.26778138, -0.10614991 0.084284052 0.26784724, -0.10623996 0.084325597 0.26791006, -0.10634169 0.084342882 0.26796603, -0.10617484 0.084229007 0.26819566, -0.10590996 0.084149137 0.26835683, -0.10598555 0.08411096 0.26778686, -0.10603403 0.08418642 0.26786047, -0.10597332 0.084154919 0.26793495, -0.10610068 0.08424221 0.26793784, -0.1060299 0.084203497 0.26802212, -0.10609841 0.08422862 0.26811081, -0.10587037 0.084160194 0.26825422, -0.10575885 0.084128752 0.26839864, -0.10560757 0.084121898 0.26841301, -0.10595764 0.084019914 0.26772085, -0.10593173 0.084085837 0.26785433, -0.10583472 0.084146872 0.26814979, -0.10573931 0.08414267 0.26829237, -0.10560763 0.084136978 0.26830631, -0.10590686 0.08399941 0.26778355, -0.10580504 0.084110245 0.26804978, -0.10572171 0.084132925 0.26818472, -0.10560749 0.084128812 0.26819912, -0.10578249 0.084051952 0.2679587, -0.10570684 0.084099814 0.2680819, -0.10560752 0.084097877 0.26809588, -0.10576805 0.083974585 0.26788056, -0.10569555 0.084045514 0.26798886, -0.10560757 0.084045574 0.26800197, -0.10560751 0.083974347 0.26792115, -0.106273 0.084283635 0.26808602, -0.10568807 0.083971843 0.26790869, -0.1061821 0.08427535 0.26801449, -0.09644036 0.084122047 0.26841319, -0.096440509 0.084137037 0.26830623, -0.09644042 0.084128842 0.26819885, -0.09644039 0.084097937 0.26809597, -0.09644039 0.084045604 0.26800177, -0.09644039 0.083974436 0.26792121, -0.095730767 0.083902344 0.26802528, -0.095744088 0.083979443 0.26810369, -0.095765308 0.084037736 0.2681956, -0.095793322 0.084073976 0.26829621, -0.095826581 0.084086671 0.26840085, -0.095863655 0.084075406 0.2685045, -0.1001066 0.087845042 0.26000327, -0.10010669 0.087929323 0.26002568, -0.09924829 0.088334486 0.25998884, -0.099284381 0.088261202 0.26005876, -0.099316955 0.088173285 0.26011115, -0.099344537 0.088074788 0.26014376, -0.099365979 0.087970093 0.2601549, -0.099378094 0.087886378 0.26014817, -0.099385113 0.087803915 0.26012778, -0.099717617 0.088148966 0.26004258, -0.10894522 0.087844983 0.26000321, -0.10894527 0.087929174 0.26002562, -0.10938308 0.088248089 0.26007324, -0.10929696 0.088365063 0.25992525, -0.10945201 0.088319227 0.26001662, -0.10924955 0.088288531 0.25999391, -0.10904729 0.088003144 0.26004374, -0.10906054 0.088114038 0.26003417, -0.10917172 0.08809121 0.26007098, -0.10907829 0.088219628 0.26000059, -0.10920718 0.088195577 0.26004344, -0.10932113 0.088159725 0.26011133, -0.10904019 0.087915406 0.26003391, -0.10914548 0.087980703 0.260075, -0.10903668 0.087830648 0.26000869, -0.10926989 0.088058725 0.26012939, -0.10913187 0.087893233 0.2600615, -0.10923219 0.087950692 0.26012588, -0.10912538 0.087808475 0.26003397, -0.10921305 0.087864146 0.26010811, -0.10920419 0.087779805 0.26007771, -0.10912302 0.088393465 0.25986904, -0.10909955 0.08831434 0.2599445, -0.10888055 0.087144867 0.26145262, -0.10891032 0.087240264 0.26151419, -0.10896334 0.087322012 0.26157975, -0.10903697 0.087385133 0.26164562, -0.10912713 0.087426797 0.26170838, -0.109229 0.087444082 0.26176435, -0.10906196 0.087330148 0.26199412, -0.10879704 0.087250367 0.26215553, -0.10887265 0.08721225 0.26158541, -0.10892111 0.08728765 0.26165891, -0.10886045 0.087256059 0.26173329, -0.10898778 0.08734335 0.26173615, -0.10891691 0.087304607 0.2618205, -0.10898551 0.087329879 0.26190925, -0.10875764 0.087261334 0.26205248, -0.10864596 0.087229952 0.26219696, -0.10849473 0.087223068 0.26221144, -0.10884485 0.087121144 0.26151907, -0.1088189 0.087186977 0.26165283, -0.10872194 0.087248102 0.26194799, -0.10862651 0.08724393 0.26209062, -0.10849473 0.087238088 0.26210463, -0.10879397 0.087100551 0.26158166, -0.10869214 0.087211385 0.26184809, -0.10860887 0.087234035 0.26198322, -0.1084947 0.087229893 0.26199728, -0.10866964 0.087153181 0.26175702, -0.10859402 0.087201014 0.26188055, -0.10849477 0.087199017 0.26189435, -0.10865526 0.087075755 0.26167887, -0.10858269 0.087146655 0.26178721, -0.1084947 0.087146744 0.26180017, -0.1084947 0.087075457 0.26171935, -0.10857531 0.087072983 0.26170707, -0.10916013 0.087384686 0.26188433, -0.1090692 0.08737649 0.26181281, -0.099327594 0.087223187 0.26221144, -0.099327654 0.087238148 0.26210481, -0.099327698 0.087230012 0.26199758, -0.099327654 0.087199107 0.26189446, -0.099327534 0.087146834 0.26180023, -0.099327654 0.087075666 0.26171964, -0.098617762 0.087003544 0.26182383, -0.098631293 0.087080553 0.26190197, -0.098652482 0.087138817 0.26199394, -0.098680466 0.087175205 0.26209468, -0.098713756 0.087187931 0.26219922, -0.0987508 0.087176517 0.26230294, -0.1029938 0.090946242 0.25380161, -0.10299374 0.091030493 0.25382423, -0.1021353 0.091435626 0.25378719, -0.10217153 0.091362253 0.25385725, -0.10220402 0.091274366 0.25390965, -0.10223177 0.091175869 0.25394207, -0.10225323 0.091071323 0.25395316, -0.10226521 0.090987369 0.2539463, -0.10227235 0.090905115 0.25392616, -0.10260479 0.091250047 0.25384098, -0.11183232 0.090946093 0.2538017, -0.1118324 0.091030285 0.25382417, -0.11227019 0.091349274 0.25387162, -0.11218412 0.091466114 0.2537235, -0.11233912 0.091420338 0.25381494, -0.11213675 0.091389641 0.25379235, -0.11193445 0.091104269 0.25384229, -0.11194785 0.091215283 0.25383276, -0.11205886 0.09119232 0.25386927, -0.11196557 0.091320857 0.25379914, -0.11209424 0.091296718 0.25384164, -0.11220841 0.09126085 0.25390995, -0.11192746 0.091016561 0.25383228, -0.1120327 0.091082036 0.25387341, -0.11192387 0.090931773 0.25380734, -0.11215727 0.091159865 0.25392777, -0.11201923 0.090994403 0.25386006, -0.11211927 0.091051623 0.25392413, -0.11201257 0.0909096 0.25383237, -0.11210027 0.090965256 0.25390649, -0.11209123 0.090880945 0.253876, -0.11201032 0.091494486 0.25366724, -0.11198671 0.09141545 0.25374293, -0.11176792 0.090246126 0.25525111, -0.11179751 0.090341434 0.25531247, -0.1118505 0.090423241 0.25537825, -0.11192425 0.090486571 0.25544399, -0.11201435 0.090527996 0.25550678, -0.11211596 0.090545341 0.25556278, -0.11194918 0.090431497 0.25579256, -0.11168426 0.090351567 0.25595394, -0.11175998 0.090313479 0.25538367, -0.11180831 0.090388671 0.25545719, -0.11174768 0.090357319 0.25553179, -0.11187491 0.090444669 0.25553453, -0.11180417 0.090405896 0.25561887, -0.11187267 0.090431109 0.25570774, -0.1116448 0.090362683 0.255851, -0.11153316 0.090331212 0.25599551, -0.11138187 0.090324327 0.25600982, -0.11138175 0.090339348 0.25590312, -0.11173196 0.090222403 0.25531763, -0.11170617 0.090288267 0.25545114, -0.11160904 0.090349451 0.25574648, -0.11151363 0.09034504 0.25588897, -0.11168137 0.090201959 0.25538033, -0.11157931 0.090312615 0.25564638, -0.11149591 0.090335265 0.25578153, -0.11138183 0.090331182 0.25579587, -0.11155683 0.090254411 0.2555553, -0.11148128 0.090302512 0.25567895, -0.11138184 0.090300128 0.25569254, -0.11154252 0.090177044 0.25547746, -0.11146989 0.090247974 0.25558561, -0.11138195 0.090248004 0.25559843, -0.1113819 0.090176716 0.25551787, -0.1114625 0.090174183 0.25550562, -0.11204726 0.090486065 0.25568283, -0.11195642 0.090477839 0.25561115, -0.10221469 0.090324387 0.2560097, -0.10221472 0.090339348 0.25590318, -0.10221465 0.090331241 0.25579584, -0.10221478 0.090300426 0.25569266, -0.10221489 0.090248063 0.25559872, -0.10221465 0.090176865 0.2555179, -0.10150506 0.090104833 0.25562227, -0.10151844 0.090181813 0.25570038, -0.10153973 0.090240225 0.25579226, -0.10156775 0.090276465 0.25589299, -0.10160089 0.09028922 0.25599754, -0.101638 0.090277895 0.25610128, -0.10588093 0.094047442 0.24759988, -0.10588087 0.094131723 0.24762274, -0.10502258 0.094536766 0.24758542, -0.10505871 0.094463661 0.24765544, -0.1050912 0.094375685 0.24770795, -0.10511892 0.094277158 0.24774037, -0.10514049 0.094172493 0.24775161, -0.1051524 0.094088852 0.24774502, -0.10515943 0.094006255 0.24772468, -0.10549194 0.094351277 0.24763948, -0.1147195 0.094047353 0.2475999, -0.11471958 0.094131663 0.24762264, -0.11515737 0.094450578 0.24767013, -0.11507136 0.094567582 0.24752207, -0.11522636 0.094521657 0.24761336, -0.11502391 0.094491109 0.2475908, -0.11482155 0.094205663 0.24764057, -0.1148349 0.094316527 0.24763079, -0.11494601 0.094293699 0.24766777, -0.11485265 0.094422027 0.24759752, -0.11498141 0.094398186 0.24764, -0.11509547 0.094362155 0.24770825, -0.11481462 0.094117925 0.24763066, -0.11491978 0.094183192 0.24767171, -0.11481096 0.094033167 0.2476055, -0.1150443 0.094261214 0.24772604, -0.11490633 0.094095767 0.24765842, -0.11500645 0.094153091 0.24772258, -0.11489978 0.094010964 0.24763082, -0.11498734 0.094066575 0.24770485, -0.11497845 0.093982264 0.24767441, -0.11489752 0.094595984 0.2474658, -0.11487381 0.094516769 0.24754128, -0.11465499 0.093347386 0.24904932, -0.11468452 0.093442753 0.24911092, -0.11473773 0.093524322 0.2491765, -0.11481129 0.093587741 0.24924242, -0.11490145 0.093629166 0.24930523, -0.11500318 0.093646556 0.24936123, -0.11483622 0.093532607 0.24959086, -0.11457139 0.093452781 0.24975213, -0.11464708 0.093414769 0.24918211, -0.11469549 0.093490079 0.24925582, -0.11463475 0.093458638 0.24933012, -0.11476208 0.093545929 0.24933299, -0.11469132 0.093507171 0.24941745, -0.11475994 0.09353222 0.24950597, -0.11453192 0.093463838 0.24964939, -0.11442032 0.093432367 0.24979386, -0.11426902 0.093425512 0.24980813, -0.11461918 0.093323633 0.24911582, -0.11459309 0.093389466 0.24924944, -0.11449617 0.093450576 0.24954492, -0.11440073 0.093446314 0.24968736, -0.11426902 0.093440548 0.24970146, -0.11456835 0.093303099 0.24917863, -0.11446646 0.09341386 0.24944484, -0.1143831 0.093436494 0.24957983, -0.11426896 0.093432397 0.24959406, -0.114444 0.093355611 0.24935392, -0.11436844 0.093403593 0.24947734, -0.11426902 0.093401447 0.24949117, -0.11442973 0.093278334 0.2492758, -0.11435702 0.093349248 0.24938405, -0.11426896 0.093349189 0.24939689, -0.11426906 0.093277991 0.24931626, -0.11493441 0.093587205 0.24948128, -0.11434963 0.093275458 0.24930382, -0.11484347 0.093578756 0.2494096, -0.10510185 0.093425587 0.24980822, -0.10510194 0.093440592 0.24970149, -0.10510191 0.093432412 0.24959409, -0.1051019 0.093401626 0.24949111, -0.10510194 0.093349278 0.24939702, -0.10510191 0.093278006 0.2493163, -0.10439207 0.093205988 0.24942046, -0.10440554 0.093282953 0.24949886, -0.10442694 0.093341306 0.24959062, -0.10445487 0.09337765 0.24969147, -0.10448815 0.09339036 0.24979602, -0.10452512 0.093379006 0.24989957, -0.10876812 0.097148642 0.24139862, -0.10876797 0.097232893 0.24142097, -0.10790969 0.097638056 0.24138398, -0.10794584 0.097564787 0.24145412, -0.10797851 0.097476929 0.24150646, -0.1080061 0.097378343 0.24153879, -0.10802756 0.097273782 0.24154986, -0.1080395 0.097189978 0.2415432, -0.10804655 0.097107396 0.24152295, -0.10837914 0.097452506 0.24143781, -0.11760662 0.097148523 0.24139845, -0.11760662 0.097232834 0.24142095, -0.11804447 0.097551838 0.24146838, -0.11795849 0.097668692 0.24132054, -0.11811353 0.097622812 0.24141179, -0.1179111 0.097592101 0.2413892, -0.1177087 0.097306788 0.24143885, -0.117722 0.097417668 0.24142955, -0.11783324 0.097394839 0.24146602, -0.11773981 0.097523272 0.2413957, -0.11786856 0.097499192 0.24143861, -0.1179826 0.097463265 0.24150662, -0.11770178 0.09721905 0.24142908, -0.11780696 0.097284347 0.24147035, -0.11769821 0.097134292 0.24140392, -0.11793138 0.097362339 0.24152456, -0.11779355 0.097196832 0.24145672, -0.11789364 0.097254321 0.2415209, -0.1177869 0.097112119 0.24142908, -0.1178745 0.09716782 0.24150333, -0.11786567 0.097083345 0.24147305, -0.11778472 0.097697094 0.24126425, -0.11776099 0.097617954 0.24133968, -0.11754228 0.096448481 0.24284779, -0.1175718 0.096544102 0.24290942, -0.11762485 0.096625701 0.24297492, -0.11769859 0.096689135 0.24304093, -0.11778873 0.096730575 0.24310364, -0.11789027 0.09674789 0.2431594, -0.11772358 0.096633956 0.24338956, -0.11745858 0.096553966 0.24355064, -0.11753425 0.096515968 0.24298058, -0.11758259 0.096591368 0.24305402, -0.11752202 0.096559897 0.24312875, -0.11764932 0.096647188 0.2431315, -0.11757851 0.096608445 0.24321555, -0.11764699 0.096633658 0.24330463, -0.117419 0.096565172 0.24344765, -0.1173075 0.096533701 0.24359214, -0.11715615 0.096526787 0.24360655, -0.1175064 0.096424878 0.24291442, -0.11748028 0.096490785 0.24304782, -0.11738348 0.09655188 0.24334334, -0.1172879 0.096547619 0.24348567, -0.11715613 0.096541852 0.24349995, -0.11745557 0.096404329 0.24297695, -0.11735366 0.096515104 0.24324328, -0.11727035 0.096537754 0.24337839, -0.11715618 0.096533731 0.24339266, -0.11733112 0.096456841 0.24315225, -0.11725555 0.096504733 0.2432757, -0.11715621 0.096502706 0.24328957, -0.11731669 0.096379533 0.2430741, -0.11724424 0.096450433 0.24318261, -0.11715615 0.096450433 0.24319528, -0.11715619 0.09637931 0.24311449, -0.11782162 0.096688613 0.24327964, -0.11723681 0.096376583 0.24310231, -0.11773074 0.096680209 0.24320789, -0.10798906 0.096526682 0.24360657, -0.10798912 0.096541867 0.24350001, -0.10798907 0.096533716 0.24339269, -0.10798921 0.096502721 0.24328962, -0.10798912 0.096450552 0.24319531, -0.107989 0.09637922 0.24311468, -0.10727938 0.096307278 0.24321905, -0.10729279 0.096384287 0.24329716, -0.10731418 0.096442491 0.24338901, -0.10734208 0.096478879 0.24348968, -0.10737528 0.096491754 0.24359456, -0.10741229 0.09648034 0.24369809, -0.11742957 0.10645212 0.2227935, -0.11742964 0.10653658 0.22281608, -0.11657134 0.10694191 0.22277923, -0.11660728 0.10686843 0.22284907, -0.11663996 0.10678059 0.22290143, -0.11666761 0.10668212 0.2229341, -0.11668915 0.10657735 0.22294512, -0.11670114 0.10649365 0.22293848, -0.11670825 0.10641114 0.22291809, -0.11704063 0.10675614 0.2228331, -0.12626834 0.10645215 0.22279352, -0.12626825 0.10653642 0.22281606, -0.12670597 0.10685523 0.2228636, -0.12661998 0.10697225 0.22271557, -0.126775 0.1069264 0.22280701, -0.12657258 0.10689576 0.22278433, -0.12637028 0.10661037 0.22283404, -0.12638363 0.10672112 0.22282462, -0.12649474 0.10669835 0.22286122, -0.12640128 0.10682687 0.22279105, -0.12653002 0.10680279 0.22283378, -0.12664412 0.10676685 0.22290178, -0.12636323 0.10652262 0.22282426, -0.12646851 0.10658784 0.22286539, -0.12635973 0.10643792 0.22279936, -0.12659293 0.10666595 0.22291987, -0.12645504 0.10650034 0.22285183, -0.12655514 0.10655771 0.22291602, -0.12644854 0.10641576 0.22282441, -0.1265361 0.10647137 0.22289844, -0.12652726 0.10638708 0.22286813, -0.12644632 0.10700075 0.22265941, -0.12642257 0.10692158 0.22273476, -0.12620363 0.10575207 0.22424285, -0.12623332 0.10584757 0.22430457, -0.12628649 0.10592923 0.22437002, -0.12636016 0.10599265 0.22443594, -0.12645027 0.10603411 0.2244987, -0.12655197 0.10605153 0.22455479, -0.12638494 0.10593756 0.22478457, -0.12612018 0.10585769 0.22494586, -0.12619577 0.10581943 0.22437574, -0.12624419 0.10589485 0.22444938, -0.12618349 0.10586342 0.22452368, -0.12631081 0.1059508 0.22452654, -0.12624012 0.10591194 0.22461082, -0.12630855 0.10593721 0.22469951, -0.1260806 0.10586865 0.22484286, -0.12596893 0.10583721 0.22498722, -0.12581769 0.10583045 0.22500174, -0.12616788 0.10572836 0.22430946, -0.12614197 0.10579436 0.22444297, -0.12604497 0.10585544 0.22473837, -0.12594949 0.10585114 0.22488083, -0.12581773 0.10584539 0.22489516, -0.12611707 0.10570806 0.22437219, -0.12601529 0.10581872 0.22463848, -0.12593196 0.10584135 0.22477344, -0.12581776 0.10583726 0.22478779, -0.12599264 0.1057605 0.22454756, -0.12591706 0.10580835 0.22467078, -0.12581772 0.10580634 0.22468464, -0.12597834 0.10568306 0.2244692, -0.12590572 0.10575397 0.22457771, -0.12581767 0.105754 0.2245906, -0.12581773 0.10568281 0.22450981, -0.12648316 0.10599208 0.22467469, -0.12589818 0.10568033 0.22449748, -0.12639223 0.10598382 0.22460331, -0.11665057 0.10583055 0.22500175, -0.1166507 0.10584548 0.22489519, -0.11665064 0.10583737 0.22478797, -0.11665057 0.10580638 0.22468469, -0.11665058 0.10575405 0.2245905, -0.11665061 0.10568291 0.22450982, -0.11594093 0.10561088 0.2246141, -0.11595437 0.10568801 0.22469242, -0.11597559 0.10574618 0.22478421, -0.11600348 0.10578254 0.22488518, -0.11603688 0.10579529 0.22498989, -0.11607379 0.10578385 0.22509338, -0.11926542 0.10943389 0.21685725, -0.11925855 0.10949749 0.21687619, -0.12031686 0.10955355 0.21659197, -0.12031685 0.10963786 0.21661443, -0.11945848 0.11004314 0.21657756, -0.11949459 0.10996974 0.21664761, -0.11952724 0.10988176 0.21669984, -0.119555 0.10978332 0.21673234, -0.11957632 0.10967869 0.21674338, -0.11958827 0.10959482 0.21673667, -0.11959542 0.1095126 0.21671647, -0.11992797 0.10985744 0.21663134, -0.1291554 0.10955337 0.21659198, -0.12915552 0.10963771 0.2166146, -0.12962231 0.10982385 0.21678695, -0.12968962 0.10977174 0.21689126, -0.12969965 0.1099056 0.21676317, -0.12934622 0.10960051 0.21665221, -0.12942287 0.10957289 0.21669665, -0.12936001 0.1096881 0.21666567, -0.12929487 0.10992727 0.21659076, -0.12931706 0.11002202 0.21653494, -0.12944186 0.10965937 0.21671435, -0.12947974 0.10976738 0.21671778, -0.12951121 0.10962406 0.21678004, -0.12955825 0.10972828 0.21679287, -0.12934193 0.11010107 0.21645969, -0.12946649 0.10999544 0.2165859, -0.12951498 0.11007184 0.21651749, -0.12966141 0.110028 0.21660477, -0.12977834 0.10984464 0.216885, -0.12983274 0.10974911 0.21707717, -0.12987731 0.10989828 0.21686384, -0.12993982 0.10978696 0.21708688, -0.12927628 0.10982189 0.21662438, -0.12961626 0.10968331 0.21688238, -0.12942301 0.10990264 0.21663478, -0.12941405 0.10948855 0.21666628, -0.12933964 0.10951573 0.2166245, -0.1299331 0.10970479 0.21725176, -0.12987773 0.10962397 0.21741073, -0.12959252 0.10995682 0.21666142, -0.12948772 0.10953924 0.21675724, -0.1297861 0.10996899 0.21672267, -0.12973683 0.10969061 0.21705632, -0.12926234 0.10971072 0.21663357, -0.1295623 0.10958435 0.21685907, -0.12982795 0.10967857 0.21721989, -0.12977608 0.1096067 0.21735504, -0.12938698 0.10979839 0.21666196, -0.12947704 0.10945584 0.21672472, -0.12953088 0.10986838 0.2166999, -0.12953535 0.1095024 0.21683106, -0.12925492 0.10962313 0.21662353, -0.12965737 0.10961448 0.21702522, -0.12973361 0.10963108 0.21717963, -0.12968592 0.1095652 0.21729212, -0.12952328 0.10942 0.21679577, -0.1295986 0.10952483 0.21698552, -0.12965521 0.10956466 0.21713248, -0.12961231 0.10950178 0.21722625, -0.12925129 0.10953833 0.2165986, -0.12956867 0.10944781 0.21694964, -0.12959644 0.1094825 0.21708101, -0.12955928 0.10942009 0.21716061, -0.12955475 0.10936791 0.21691081, -0.1295663 0.10940959 0.21703914, -0.1295296 0.10932449 0.21709898, -0.1295515 0.10933211 0.21699759, -0.12943904 0.10915262 0.2183532, -0.12933743 0.10913533 0.21829721, -0.12924716 0.10909373 0.21823436, -0.12917361 0.10903046 0.21816856, -0.12912045 0.10894889 0.21810292, -0.12909088 0.1088534 0.21804136, -0.12927218 0.10903867 0.21858314, -0.12900721 0.1089588 0.21874425, -0.12908283 0.10892092 0.21817406, -0.12913132 0.10899615 0.21824765, -0.12907073 0.10896462 0.21832222, -0.12919806 0.1090519 0.21832487, -0.12912723 0.10901314 0.21840912, -0.12919578 0.10903832 0.21849781, -0.12896787 0.10896981 0.21864127, -0.12885609 0.10893838 0.21878581, -0.12870486 0.1089315 0.21880034, -0.12905501 0.10882975 0.21810785, -0.12902918 0.10889563 0.21824154, -0.12893215 0.10895663 0.218537, -0.12883662 0.1089523 0.21867934, -0.12870491 0.1089465 0.2186937, -0.12900421 0.1088092 0.21817058, -0.12890244 0.10891977 0.21843675, -0.12881911 0.10894254 0.21857193, -0.12870502 0.10893834 0.21858627, -0.1288799 0.10886176 0.21834598, -0.12880416 0.10890964 0.21846934, -0.12870488 0.10890746 0.218483, -0.12886548 0.10878447 0.21826783, -0.12879285 0.1088551 0.2183761, -0.12870477 0.10885514 0.21838883, -0.12870491 0.10878411 0.21830836, -0.12937032 0.1090932 0.21847323, -0.12878546 0.10878155 0.21829587, -0.12927935 0.10908493 0.21840173, -0.11953771 0.10893169 0.21880026, -0.1195378 0.10894668 0.21869366, -0.11953773 0.10893849 0.21858615, -0.11953771 0.10890761 0.21848305, -0.11953768 0.10885538 0.21838889, -0.11953773 0.10878426 0.2183083, -0.11882807 0.10871211 0.21841258, -0.11884147 0.10878912 0.21849073, -0.11886285 0.10884732 0.21858242, -0.11889075 0.10888368 0.21868339, -0.11892408 0.10889646 0.21878798, -0.11896099 0.10888509 0.21889196, -0.11376342 0.10258178 0.23071152, -0.11376344 0.10265307 0.23079212, -0.11376336 0.10270526 0.23088619, -0.11376357 0.10274427 0.23109692, -0.11376336 0.10273628 0.23098934, -0.11376351 0.10272914 0.23120342, -0.11305374 0.10250957 0.23081568, -0.11306719 0.10258685 0.23089384, -0.11308846 0.10264497 0.23098594, -0.11311641 0.10268117 0.23108658, -0.11314958 0.10269397 0.23119138, -0.11318663 0.10268256 0.23129494, -0.12293062 0.10272911 0.23120338, -0.12293062 0.10274401 0.23109692, -0.1229306 0.10273613 0.23098961, -0.1229305 0.10270527 0.2308864, -0.12293062 0.10265294 0.23079246, -0.12293053 0.10258165 0.23071137, -0.12349781 0.10283649 0.23098633, -0.12323293 0.10275629 0.23114759, -0.12334618 0.10274664 0.23050612, -0.1233086 0.10271847 0.23057717, -0.12339929 0.10282829 0.23057184, -0.12335701 0.10279381 0.23065095, -0.12329628 0.10276246 0.23072539, -0.12342373 0.10284966 0.23072824, -0.12335286 0.10281087 0.23081248, -0.12319331 0.10276745 0.23104447, -0.12342146 0.10283607 0.23090121, -0.12308168 0.10273606 0.23118895, -0.12328079 0.10262746 0.23051116, -0.12331662 0.102651 0.23044464, -0.12325487 0.10269329 0.23064479, -0.12315781 0.10275435 0.23094015, -0.12306221 0.10274993 0.23108262, -0.12322994 0.10260701 0.23057394, -0.12312803 0.10271764 0.23084006, -0.1230447 0.1027402 0.23097521, -0.12310553 0.10265937 0.23074904, -0.12302989 0.10270709 0.2308723, -0.12309113 0.10258207 0.23067111, -0.1230185 0.10265297 0.23077923, -0.12301113 0.10257924 0.23069929, -0.12366463 0.10295045 0.23075651, -0.12359595 0.10289103 0.23087639, -0.12356299 0.10293305 0.23070043, -0.12350503 0.10288271 0.23080486, -0.123473 0.10289158 0.2306377, -0.12381884 0.10375412 0.22906514, -0.12373294 0.10387109 0.2289173, -0.12388791 0.1038252 0.2290085, -0.12368552 0.10379453 0.22898588, -0.12348314 0.10350919 0.22903572, -0.12349632 0.10362007 0.22902627, -0.12360752 0.10359715 0.22906296, -0.12351418 0.10372566 0.2289926, -0.12364304 0.10370168 0.22903544, -0.12375703 0.10366584 0.22910349, -0.12338111 0.10343523 0.22901781, -0.12347615 0.10342143 0.22902577, -0.12358141 0.10348688 0.2290671, -0.12347247 0.10333665 0.22900078, -0.12338112 0.10335107 0.22899511, -0.12370586 0.10356472 0.22912134, -0.12356782 0.10339926 0.22905354, -0.12366802 0.10345671 0.22911784, -0.1235614 0.10331462 0.2290259, -0.12364894 0.10337012 0.22910012, -0.12364 0.10328589 0.2290699, -0.12355912 0.10389958 0.2288609, -0.12353556 0.10382052 0.22893652, -0.11454241 0.1033511 0.22899516, -0.11454245 0.1034352 0.22901779, -0.11368418 0.10384063 0.2289806, -0.11372022 0.10376726 0.22905071, -0.11375278 0.10367925 0.22910312, -0.11378045 0.10358085 0.22913559, -0.11380199 0.1034763 0.22914669, -0.11381383 0.10339244 0.22913991, -0.11382115 0.10331003 0.22911984, -0.11415353 0.10365494 0.22903463, -0.14604332 -0.024768606 0.1401993, -0.14744641 -0.023040608 0.14023465, -0.14600737 -0.024796635 0.14024988, -0.14599755 -0.024799928 0.14026713, -0.14602478 -0.024785906 0.1402227, -0.14742915 -0.02302663 0.1402978, -0.14597909 -0.024789557 0.14031371, -0.14597559 -0.024777517 0.14033118, -0.14598465 -0.024796963 0.14029601, -0.14599024 -0.024799734 0.14028245, -0.14740133 -0.023003995 0.14035484, -0.14597443 -0.024758339 0.1403496, -0.1459787 -0.024715319 0.14037728, -0.14736474 -0.02297388 0.14040235, -0.14599128 -0.024658233 0.14040127, -0.14603412 -0.024524286 0.14043468, -0.14732054 -0.022937864 0.14043832, -0.14727154 -0.022897854 0.14046019, -0.14852455 -0.022193462 0.14043802, -0.14807111 -0.02234982 0.14043809, -0.14804395 -0.022292525 0.14046016, -0.14774954 -0.022712573 0.14029792, -0.14772755 -0.022684455 0.14035481, -0.14811587 -0.022444233 0.1403549, -0.1476983 -0.022646964 0.14040241, -0.14809555 -0.022401392 0.14040232, -0.14853704 -0.022248849 0.14040235, -0.14776325 -0.022729948 0.14023453, -0.14813131 -0.022476405 0.14029798, -0.14854766 -0.022295296 0.14035484, -0.14814071 -0.022496507 0.14023462, -0.14855541 -0.022330105 0.14029798, -0.1485603 -0.022351801 0.14023468, -0.147624 -0.022552311 0.14046031, -0.14766315 -0.022602186 0.14043829, -0.14851072 -0.022131547 0.14046022, -0.15503746 -0.022296667 0.14035493, -0.15640661 -0.023429558 0.14029792, -0.15619279 -0.023022443 0.14035483, -0.15643883 -0.02341415 0.14035484, -0.15504798 -0.022250354 0.14040235, -0.15659165 -0.023850784 0.14035478, -0.15648162 -0.023393467 0.1404025, -0.15663792 -0.0238401 0.14040239, -0.15664323 -0.024310321 0.14035478, -0.15660766 -0.02431038 0.14029783, -0.15549475 -0.022406593 0.14040235, -0.15506065 -0.022194862 0.14043799, -0.1563866 -0.023439273 0.14023462, -0.15614739 -0.023058668 0.14023454, -0.15551932 -0.022355273 0.14043833, -0.15616474 -0.02304478 0.14029789, -0.15655673 -0.023858652 0.14029792, -0.15658535 -0.02431038 0.14023454, -0.15593076 -0.022613868 0.14043823, -0.15554687 -0.022298262 0.14046019, -0.15597034 -0.022564277 0.14046016, -0.15653515 -0.023863658 0.14023462, -0.15632387 -0.022917941 0.14046031, -0.15502957 -0.022331491 0.14029792, -0.15547407 -0.022449389 0.14035498, -0.15589523 -0.022658333 0.14040235, -0.15627445 -0.02295728 0.14043838, -0.15502456 -0.022353157 0.14023456, -0.1565899 -0.023341313 0.14046028, -0.15545852 -0.02248162 0.14029789, -0.15586573 -0.022695541 0.14035493, -0.15622985 -0.022992924 0.1404025, -0.15653291 -0.02336885 0.14043814, -0.15544891 -0.022501573 0.14023462, -0.15675509 -0.023813352 0.14046028, -0.15681121 -0.024310201 0.14046025, -0.15674767 -0.024310291 0.14043796, -0.15584339 -0.022723392 0.14029795, -0.15507485 -0.022133023 0.14046033, -0.15669334 -0.023827419 0.14043811, -0.15669081 -0.024310291 0.14040232, -0.15582956 -0.022740752 0.14023466, -0.15658534 -0.027200133 0.14023447, -0.15660743 -0.027200192 0.1402978, -0.15664324 -0.027200073 0.14035475, -0.15669084 -0.027200133 0.14040239, -0.15674767 -0.027200073 0.14043796, -0.15681113 -0.027200028 0.1404603, -0.1564274 -0.028094113 0.14046013, -0.15623006 -0.028246731 0.14046013, -0.15619661 -0.028192922 0.14043789, -0.15658998 -0.02790466 0.14046021, -0.15658641 -0.027407438 0.14029796, -0.15662144 -0.027414471 0.14035474, -0.15655693 -0.027620286 0.14035463, -0.15666801 -0.027424157 0.14040232, -0.15660058 -0.027639091 0.14040214, -0.15649128 -0.027835876 0.14040232, -0.15665287 -0.027661502 0.14043808, -0.15653796 -0.02786845 0.14043793, -0.1563838 -0.028048083 0.14043804, -0.15616651 -0.028144643 0.14040217, -0.15656468 -0.027402967 0.14023447, -0.15652412 -0.027606294 0.14029795, -0.15645219 -0.027808845 0.14035463, -0.15634467 -0.028006837 0.14040224, -0.15614142 -0.02810435 0.14035468, -0.15650357 -0.027597487 0.14023447, -0.15642294 -0.027788371 0.14029789, -0.15631188 -0.027972385 0.1403548, -0.15612254 -0.028073937 0.14029786, -0.15640467 -0.027775705 0.14023447, -0.15628719 -0.027946353 0.14029783, -0.15611076 -0.028055191 0.14023453, -0.15627204 -0.027930439 0.14023452, -0.15678586 -0.027448341 0.14046018, -0.15672371 -0.027435645 0.14043799, -0.15671119 -0.027686447 0.14046013, -0.14600821 -0.024842292 0.14015499, -0.1460021 -0.024869651 0.14014173, -0.14599004 -0.024859324 0.14019006, -0.14598322 -0.024886116 0.14018086, -0.14592128 -0.024878263 0.14033186, -0.14592844 -0.024944499 0.14028405, -0.14593118 -0.024686292 0.14043558, -0.14594957 -0.024540469 0.14047757, -0.14594103 -0.024893939 0.14027986, -0.14595459 -0.024947688 0.14021894, -0.14596333 -0.024894506 0.14022572, -0.145905 -0.02470234 0.14045674, -0.14591256 -0.024551257 0.14050683, -0.1459296 -0.024748817 0.14040416, -0.14588189 -0.024719656 0.14048097, -0.14588013 -0.024563417 0.14054069, -0.14614294 -0.024070367 0.14047568, -0.14590837 -0.024767414 0.14042056, -0.14606813 -0.024061933 0.14049858, -0.14599885 -0.024054185 0.14053583, -0.14593399 -0.024796426 0.14036784, -0.14593866 -0.02404736 0.14058626, -0.14588916 -0.024041891 0.14064732, -0.14588979 -0.024786964 0.14043897, -0.14593959 -0.024818122 0.14034364, -0.14591692 -0.024817035 0.14037934, -0.14594655 -0.024832219 0.14032078, -0.14592452 -0.024839997 0.14035156, -0.14590192 -0.024838775 0.14039204, -0.14593281 -0.024854794 0.14032578, -0.14596164 -0.024844885 0.1402792, -0.14591146 -0.024862647 0.14036074, -0.14598112 -0.024843216 0.14023626, -0.14595027 -0.024868995 0.14027897, -0.14599931 -0.02483356 0.14020041, -0.14601722 -0.024816155 0.14016911, -0.14597113 -0.024868399 0.14023057, -0.14598702 -0.023238897 0.13958073, -0.14579308 -0.023205936 0.13979757, -0.14585876 -0.022878706 0.14004648, -0.14592052 -0.02291517 0.14003268, -0.14586873 -0.02323398 0.13973901, -0.14602633 -0.022955909 0.13998787, -0.14591669 -0.022697926 0.14021492, -0.14593484 -0.023245245 0.1396654, -0.14608718 -0.022966921 0.13995001, -0.14614415 -0.022967324 0.13990477, -0.1459821 -0.02274549 0.14021054, -0.1462159 -0.022949576 0.13982955, -0.14610401 -0.022800222 0.14017826, -0.14617795 -0.022814855 0.14014508, -0.1462492 -0.022815242 0.1401034, -0.14634036 -0.022790775 0.14003174, -0.13931955 -0.031404302 0.13485776, -0.13926721 -0.031410724 0.13494243, -0.1392013 -0.031399414 0.13501619, -0.13912569 -0.031371415 0.13507463, -0.13874602 -0.032330155 0.1345153, -0.13891032 -0.031932905 0.13467136, -0.13885944 -0.031934381 0.13471018, -0.13878395 -0.031926796 0.13475119, -0.13878599 -0.032180101 0.13457403, -0.13874429 -0.032187358 0.13459004, -0.13876615 -0.032259032 0.13454057, -0.13868603 -0.03219302 0.13460529, -0.13872999 -0.032270223 0.13454914, -0.13869391 -0.032354996 0.13451518, -0.13867985 -0.032282516 0.13455571, -0.13861538 -0.032293364 0.13455556, -0.15457788 -0.021994472 -0.14046894, -0.14900133 -0.021994397 -0.14046898, -0.14900133 -0.021994397 -0.14046898, -0.15457788 -0.021994472 -0.14046894, -0.12338114 0.10354796 -0.22901247, -0.12338111 0.10346091 -0.22900485, -0.11454237 0.10354804 -0.22901246, -0.11454234 0.10346109 -0.22900485, -0.12338114 0.10337678 -0.2289822, -0.11454251 0.10337682 -0.22898227, -0.12338108 0.10329774 -0.22894518, -0.11454248 0.1032977 -0.2289452, -0.12392837 0.1035496 -0.22934602, -0.12394869 0.1035008 -0.22944647, -0.12385121 0.1034594 -0.22932485, -0.12386897 0.10341839 -0.22941157, -0.12378472 0.10324349 -0.22955084, -0.1238668 0.10337247 -0.22951061, -0.12383792 0.10332513 -0.22961627, -0.12381274 0.10332169 -0.22936758, -0.1238105 0.10328284 -0.22945599, -0.12373334 0.10317945 -0.22911154, -0.12373307 0.1032875 -0.22916576, -0.12375396 0.10316089 -0.22914998, -0.12424821 0.103701 -0.22932421, -0.12413239 0.10367437 -0.22934529, -0.12416607 0.10379049 -0.22914545, -0.12406152 0.1037512 -0.22919148, -0.12396321 0.10368814 -0.22922167, -0.12402377 0.10362279 -0.22935306, -0.12404713 0.1035645 -0.22947071, -0.12394565 0.1034459 -0.22956061, -0.12391162 0.10338838 -0.2296823, -0.1242803 0.10360277 -0.2295209, -0.12415883 0.10360575 -0.22948276, -0.12404275 0.10349871 -0.22960407, -0.12400171 0.10342991 -0.2297449, -0.12415254 0.10352834 -0.22963783, -0.1241034 0.10344747 -0.22980098, -0.12426418 0.10351872 -0.22968931, -0.12421101 0.10343957 -0.22984742, -0.12376961 0.10314158 -0.22919135, -0.12376949 0.10324895 -0.22924517, -0.12378266 0.10310988 -0.22926399, -0.12375808 0.10339864 -0.22920555, -0.12379715 0.10335699 -0.2292905, -0.12378332 0.10321677 -0.22931741, -0.1238068 0.10350645 -0.22922908, -0.12375087 0.10304393 -0.22943521, -0.12378058 0.10318223 -0.22940032, -0.12375531 0.10314798 -0.22948931, -0.12377807 0.10307637 -0.22934701, -0.12387657 0.10360499 -0.22923443, -0.1291554 0.10974914 -0.21660857, -0.12915549 0.10966215 -0.21660097, -0.12031689 0.10974909 -0.21660852, -0.12031689 0.10966219 -0.21660101, -0.12915546 0.10957786 -0.21657826, -0.12031674 0.10957779 -0.21657836, -0.1203168 0.1094989 -0.21654147, -0.12915546 0.10949883 -0.21654142, -0.11924717 0.1095867 -0.21687374, -0.11925858 0.10952179 -0.21686253, -0.11444587 0.10829434 -0.21945895, -0.11458936 0.10823198 -0.21937025, -0.11926547 0.10945813 -0.21684378, -0.11475253 0.10818142 -0.21924852, -0.119268 0.10939668 -0.21681765, -0.12681547 0.10665025 -0.22314426, -0.12683588 0.10660134 -0.22324461, -0.12673834 0.1065599 -0.22312294, -0.12675625 0.10651888 -0.22320959, -0.12667212 0.10634409 -0.22334895, -0.12675393 0.10647303 -0.22330864, -0.12672505 0.10642563 -0.22341451, -0.12669784 0.10638352 -0.223254, -0.12669986 0.10642229 -0.22316557, -0.12662044 0.10627998 -0.22290963, -0.12662026 0.10638796 -0.22296378, -0.12664109 0.10626151 -0.22294793, -0.12713549 0.10680161 -0.22312254, -0.12701949 0.10677491 -0.22314343, -0.12705317 0.10689093 -0.22294363, -0.12694868 0.1068518 -0.22298953, -0.12685028 0.10678856 -0.22301978, -0.12691095 0.10672314 -0.22315124, -0.12693435 0.106665 -0.22326872, -0.12683287 0.10654645 -0.22335896, -0.12679884 0.10648905 -0.22348043, -0.1271674 0.10670339 -0.2233189, -0.12704611 0.1067064 -0.22328091, -0.12692976 0.10659926 -0.22340223, -0.12688887 0.10653044 -0.22354308, -0.12703973 0.10662903 -0.22343609, -0.12699062 0.10654785 -0.22359902, -0.12715134 0.10661925 -0.22348729, -0.12709817 0.10654017 -0.22364543, -0.12665659 0.10624214 -0.22298959, -0.12665659 0.10634947 -0.22304313, -0.12666973 0.10621046 -0.22306201, -0.12664509 0.10649912 -0.22300383, -0.12668437 0.10645759 -0.22308846, -0.12667042 0.10631739 -0.22311538, -0.12669411 0.10660723 -0.2230271, -0.12663803 0.10614453 -0.22323331, -0.12666756 0.1062829 -0.22319844, -0.12664253 0.10624851 -0.22328755, -0.12666526 0.1061769 -0.22314507, -0.12676361 0.1067055 -0.2230325, -0.11742955 0.10664859 -0.2228104, -0.12626818 0.10664859 -0.22281061, -0.11742958 0.10656168 -0.22280285, -0.12626818 0.1065615 -0.22280291, -0.11742949 0.10647735 -0.22278027, -0.12626821 0.10647725 -0.22278029, -0.11742964 0.1063983 -0.22274342, -0.1262683 0.10639815 -0.22274333, -0.11815396 0.097348705 -0.24175, -0.11817437 0.097299784 -0.24185039, -0.11807689 0.0972583 -0.2417288, -0.11809453 0.097217157 -0.24181536, -0.11801043 0.097042441 -0.24195497, -0.11809239 0.0971715 -0.24191442, -0.11806354 0.097124055 -0.24202028, -0.11803636 0.097081974 -0.24185994, -0.11795887 0.096978515 -0.24151541, -0.11795872 0.09708643 -0.24156968, -0.11797962 0.096959814 -0.24155387, -0.11803848 0.097120732 -0.24177153, -0.11847407 0.097500056 -0.24172838, -0.11835793 0.097473279 -0.24174929, -0.11839169 0.097589478 -0.24154943, -0.11828712 0.097550228 -0.24159548, -0.1181888 0.097487167 -0.24162564, -0.11824951 0.09742175 -0.24175692, -0.11827299 0.097363442 -0.24187468, -0.1181713 0.097244695 -0.24196482, -0.11813721 0.097187474 -0.24208623, -0.11850601 0.097401857 -0.24192478, -0.11838454 0.097404703 -0.24188668, -0.11826831 0.097297609 -0.24200819, -0.11822733 0.097228959 -0.24214891, -0.11837813 0.097327307 -0.24204174, -0.11832914 0.097246259 -0.24220498, -0.11848974 0.097317606 -0.24209328, -0.11843666 0.097238615 -0.24225119, -0.11799508 0.096940532 -0.24159527, -0.11799511 0.09704791 -0.24164891, -0.1180082 0.096908793 -0.24166793, -0.11798373 0.097197548 -0.24160957, -0.11802286 0.097156033 -0.24169439, -0.118009 0.097015798 -0.24172141, -0.11803252 0.097305551 -0.24163294, -0.11797649 0.096842855 -0.24183933, -0.11800608 0.096981242 -0.24180415, -0.11798093 0.09694691 -0.24189332, -0.11800364 0.09687525 -0.24175097, -0.11810207 0.097403929 -0.24163836, -0.11760658 0.097346902 -0.24141638, -0.1176067 0.097260013 -0.24140882, -0.10876805 0.097346947 -0.24141625, -0.10876805 0.097260058 -0.24140878, -0.11760673 0.097175702 -0.24138618, -0.10876817 0.097175747 -0.24138619, -0.1176067 0.097096667 -0.24134928, -0.10876793 0.097096667 -0.24134931, -0.1152668 0.094248176 -0.24795206, -0.1152873 0.094199315 -0.24805236, -0.11518976 0.094157919 -0.24793068, -0.11520752 0.094116807 -0.24801736, -0.11512339 0.093941942 -0.24815667, -0.11520526 0.094071016 -0.2481164, -0.11517656 0.0940236 -0.24822232, -0.1151492 0.0939814 -0.24806198, -0.1150718 0.093877941 -0.24771746, -0.11507171 0.093986034 -0.24777167, -0.11509261 0.093859434 -0.24775569, -0.11515123 0.094020277 -0.24797334, -0.11558685 0.094399571 -0.24793033, -0.11547083 0.094372809 -0.24795125, -0.1155045 0.094488934 -0.24775141, -0.11540005 0.094449759 -0.2477973, -0.11530164 0.094386727 -0.24782757, -0.11536226 0.094321117 -0.24795893, -0.11538565 0.094262972 -0.24807656, -0.11528429 0.094144344 -0.24816673, -0.11525014 0.094086885 -0.24828823, -0.11561874 0.094301254 -0.24812667, -0.1154975 0.094304293 -0.24808858, -0.11538109 0.094197139 -0.24820998, -0.11534032 0.094128489 -0.2483509, -0.11549115 0.094226971 -0.24824381, -0.11544189 0.094145641 -0.24840695, -0.11560276 0.094217092 -0.24829523, -0.1155495 0.094138041 -0.24845323, -0.1151081 0.093840107 -0.24779725, -0.11510801 0.093947425 -0.24785087, -0.11512122 0.093808502 -0.24786977, -0.11509657 0.094097033 -0.24781156, -0.1151357 0.094055682 -0.24789636, -0.11512178 0.093915358 -0.24792331, -0.1151453 0.094205126 -0.24783495, -0.11508924 0.0937424 -0.24804117, -0.11511904 0.093880892 -0.24800639, -0.1150938 0.09384656 -0.2480952, -0.11511654 0.09377493 -0.24795288, -0.11521515 0.094303608 -0.24784033, -0.10588095 0.094246462 -0.24761841, -0.11471969 0.094246492 -0.24761829, -0.10588092 0.094159588 -0.24761063, -0.11471969 0.094159469 -0.24761066, -0.10588083 0.094075277 -0.24758807, -0.11471972 0.094075218 -0.24758807, -0.10588092 0.093996093 -0.2475512, -0.11471957 0.093996182 -0.24755123, -0.11237955 0.091147691 -0.25415385, -0.11240011 0.091098666 -0.2542544, -0.11230254 0.09105733 -0.25413269, -0.11232036 0.091016293 -0.25421935, -0.11223614 0.090841442 -0.25435871, -0.11231819 0.090970546 -0.25431842, -0.11228919 0.090923101 -0.25442421, -0.11226201 0.090880901 -0.25426376, -0.11226422 0.090919614 -0.25417548, -0.11218464 0.090777427 -0.25391936, -0.11218441 0.090885431 -0.25397348, -0.11220518 0.09075883 -0.25395769, -0.11269957 0.091298938 -0.25413203, -0.11258364 0.091272354 -0.25415313, -0.1126174 0.091388464 -0.2539534, -0.11251289 0.091349214 -0.25399929, -0.11241439 0.091286093 -0.25402945, -0.11247522 0.091220737 -0.25416094, -0.1124984 0.091162413 -0.25427842, -0.11239704 0.0910438 -0.25436866, -0.11236292 0.090986371 -0.2544902, -0.11273155 0.091200739 -0.25432867, -0.11261019 0.091203719 -0.2542904, -0.11249396 0.091096669 -0.25441188, -0.11245298 0.091027886 -0.25455284, -0.11260399 0.091126353 -0.25444579, -0.11255479 0.09104529 -0.25460887, -0.11271563 0.091116577 -0.25449705, -0.11266235 0.091037542 -0.25465518, -0.11222091 0.090739638 -0.25399923, -0.11222076 0.090846926 -0.25405288, -0.11223391 0.090707809 -0.25407177, -0.11220938 0.090996653 -0.25401342, -0.11224854 0.09095493 -0.2540983, -0.11223465 0.090814859 -0.25412512, -0.11225823 0.091104627 -0.25403684, -0.11220205 0.090641886 -0.25424308, -0.11223176 0.090780288 -0.25420815, -0.11220667 0.090745956 -0.2542972, -0.11222935 0.09067443 -0.2541548, -0.11232781 0.091203004 -0.25404227, -0.11183241 0.091145903 -0.2538203, -0.11183244 0.091058969 -0.25381273, -0.10299358 0.091145977 -0.25382027, -0.10299379 0.091059014 -0.2538127, -0.11183232 0.090974748 -0.25379014, -0.10299367 0.090974733 -0.25379011, -0.11183241 0.090895563 -0.25375313, -0.10299379 0.090895668 -0.25375336, -0.10949254 0.088047192 -0.2603558, -0.10951295 0.087998182 -0.26045632, -0.10941544 0.087956816 -0.26033461, -0.10943311 0.087915763 -0.26042134, -0.10934916 0.087740928 -0.26056075, -0.10943097 0.087869987 -0.26052034, -0.10940203 0.087822571 -0.26062611, -0.10937482 0.087780401 -0.26046577, -0.109377 0.087819174 -0.26037726, -0.1092976 0.087676898 -0.26012138, -0.10929722 0.087784871 -0.26017553, -0.10931811 0.087658301 -0.26015964, -0.10981244 0.088198408 -0.26033413, -0.10969633 0.088171706 -0.26035506, -0.10973004 0.08828786 -0.26015532, -0.10962567 0.088248625 -0.26020125, -0.10952729 0.088185593 -0.26023144, -0.109588 0.088120118 -0.26036289, -0.10961133 0.088061914 -0.26048046, -0.10950989 0.08794336 -0.2605707, -0.10947576 0.087885916 -0.26069218, -0.10984439 0.088100269 -0.26053074, -0.10972303 0.08810316 -0.26049244, -0.10960668 0.08799623 -0.2606138, -0.10956582 0.087927356 -0.26075485, -0.10971665 0.088025749 -0.26064759, -0.10966757 0.087944776 -0.26081073, -0.10982832 0.088015959 -0.26069909, -0.10977516 0.087936908 -0.26085705, -0.10933363 0.087638974 -0.26020139, -0.10933354 0.087746412 -0.26025468, -0.10934672 0.087607339 -0.26027378, -0.10932213 0.087896094 -0.26021534, -0.10936132 0.087854415 -0.2603004, -0.10934737 0.087714225 -0.26032722, -0.10937101 0.088003978 -0.26023874, -0.10931486 0.087541327 -0.260445, -0.10934451 0.087679699 -0.26040998, -0.10931945 0.087645456 -0.26049909, -0.10934213 0.087573797 -0.26035678, -0.10944062 0.088102505 -0.26024428, -0.10894516 0.088045388 -0.26002228, -0.10894528 0.087958381 -0.2600145, -0.10010642 0.088045388 -0.26002222, -0.1001066 0.087958619 -0.26001453, -0.10894525 0.087874129 -0.25999212, -0.1001066 0.087874219 -0.25999188, -0.10894516 0.087795049 -0.25995505, -0.10010651 0.087795094 -0.25995502, -0.10660529 0.084946662 -0.26655787, -0.10662574 0.084897786 -0.26665819, -0.10652807 0.084856361 -0.26653665, -0.10654587 0.084815264 -0.26662308, -0.10646176 0.084640503 -0.26676261, -0.10654381 0.084769577 -0.26672238, -0.10651484 0.084722131 -0.26682812, -0.10648769 0.084679842 -0.26666766, -0.10648969 0.084718585 -0.26657927, -0.10641035 0.084576458 -0.26632333, -0.10641009 0.084684461 -0.26637751, -0.10643095 0.084557772 -0.26636177, -0.10692519 0.085098028 -0.26653606, -0.10680932 0.085071325 -0.26655704, -0.10684305 0.085187405 -0.2663573, -0.10673839 0.085148156 -0.2664032, -0.1066401 0.085085094 -0.26643336, -0.10670069 0.085019678 -0.26656479, -0.10672408 0.084961474 -0.26668239, -0.10662276 0.084842801 -0.26677257, -0.10658851 0.084785372 -0.26689416, -0.10695735 0.08499971 -0.26673251, -0.10683584 0.08500281 -0.26669443, -0.10671967 0.084895641 -0.26681578, -0.10667872 0.084826916 -0.26695687, -0.10682946 0.084925324 -0.26684964, -0.10678032 0.084844172 -0.26701272, -0.10694113 0.084915519 -0.26690102, -0.106888 0.084836483 -0.26705909, -0.10644644 0.08453849 -0.26640308, -0.1064463 0.084645838 -0.26645678, -0.10645953 0.08450684 -0.26647568, -0.10643515 0.084795713 -0.26641732, -0.10647428 0.084753931 -0.26650208, -0.10646027 0.08461383 -0.26652914, -0.10648379 0.084903508 -0.26644081, -0.10642776 0.084440798 -0.2666471, -0.10645756 0.084579468 -0.26661211, -0.10643223 0.084544957 -0.2667011, -0.10645509 0.084473312 -0.26655871, -0.10655352 0.085001796 -0.26644617, -0.10605803 0.084944874 -0.26622421, -0.10605809 0.084857941 -0.26621646, -0.097219408 0.084944889 -0.26622418, -0.097219288 0.084857926 -0.26621643, -0.10605797 0.08477363 -0.26619405, -0.097219437 0.084773675 -0.26619399, -0.10605809 0.084694505 -0.26615697, -0.097219408 0.084694549 -0.266157, -0.11450332 -0.032790363 -0.21487598, -0.11400571 -0.032790244 -0.21609081, -0.11451486 -0.032901451 -0.21488059, -0.11401731 -0.032901466 -0.21609549, -0.11454922 -0.033007205 -0.21489458, -0.11405161 -0.033007085 -0.21610947, -0.11460429 -0.03310205 -0.21491718, -0.11410671 -0.033101976 -0.21613221, -0.11467758 -0.03318128 -0.21494733, -0.11417994 -0.033181116 -0.21616223, -0.1147652 -0.033240736 -0.21498315, -0.11426762 -0.033240736 -0.21619813, -0.11486307 -0.03327769 -0.21502329, -0.11436549 -0.033277601 -0.21623816, -0.11496606 -0.033290207 -0.21506537, -0.11446837 -0.033290207 -0.2162803, -0.1175532 -0.033045352 -0.2060758, -0.11756629 -0.033128589 -0.20601557, -0.11751685 -0.033044279 -0.20607056, -0.11758265 -0.033197224 -0.20593999, -0.11747965 -0.033125579 -0.20600905, -0.11747971 -0.03304112 -0.20607059, -0.11747968 -0.033195451 -0.20593154, -0.11760157 -0.033248439 -0.20585221, -0.11747962 -0.033247679 -0.20584102, -0.11762238 -0.033280089 -0.20575577, -0.11747971 -0.03328 -0.20574152, -0.11764416 -0.033290803 -0.20565511, -0.11747977 -0.033290923 -0.20563762, -0.12082744 -0.033045873 -0.1980806, -0.12084058 -0.033128977 -0.19802053, -0.12079111 -0.03304483 -0.1980755, -0.12085691 -0.033197656 -0.19794485, -0.12075377 -0.033125997 -0.19801389, -0.120754 -0.033041507 -0.19807543, -0.12075391 -0.033195853 -0.19793616, -0.12087578 -0.033248961 -0.19785701, -0.12075385 -0.033248156 -0.19784589, -0.12089655 -0.033280566 -0.19776067, -0.12075379 -0.033280373 -0.19774638, -0.12091836 -0.033291295 -0.19766006, -0.12075388 -0.03329134 -0.19764243, -0.1241017 -0.033046246 -0.19008563, -0.1241146 -0.033129498 -0.1900253, -0.12406522 -0.033045217 -0.19008031, -0.12413093 -0.033198163 -0.1899496, -0.12402803 -0.033126488 -0.19001889, -0.12402815 -0.033042014 -0.19008033, -0.1241501 -0.033249319 -0.18986182, -0.12402815 -0.03319639 -0.18994121, -0.12402806 -0.033248588 -0.18985066, -0.12417084 -0.033281013 -0.1897656, -0.12402806 -0.033280775 -0.18975124, -0.12419263 -0.033291668 -0.18966503, -0.12402815 -0.033291742 -0.18964747, -0.12737581 -0.033046782 -0.18209033, -0.12738889 -0.033129945 -0.18203026, -0.12733957 -0.033045679 -0.18208517, -0.12740529 -0.03319867 -0.18195462, -0.12730241 -0.033127025 -0.18202376, -0.12730241 -0.03304252 -0.18208517, -0.12742421 -0.033249915 -0.18186663, -0.12730238 -0.033196867 -0.18194596, -0.12730241 -0.03324908 -0.18185548, -0.1274451 -0.03328152 -0.18177044, -0.12730241 -0.033281267 -0.18175624, -0.1274668 -0.033292234 -0.18166988, -0.12730244 -0.033292279 -0.18165234, -0.13065016 -0.033047259 -0.17409526, -0.13066334 -0.033130378 -0.17403503, -0.13061371 -0.03304626 -0.17408997, -0.13067952 -0.033199042 -0.17395933, -0.13057673 -0.033127546 -0.17402856, -0.13057667 -0.033043012 -0.17408994, -0.13069853 -0.033250391 -0.17387168, -0.13057676 -0.033197358 -0.17395079, -0.13057667 -0.033249483 -0.17386046, -0.13071939 -0.033282056 -0.1737752, -0.13057661 -0.033281744 -0.17376105, -0.13074109 -0.033292785 -0.17367458, -0.13057664 -0.033292711 -0.17365716, -0.13392445 -0.033047721 -0.16610017, -0.13393742 -0.033130884 -0.16603993, -0.13388807 -0.033046722 -0.166095, -0.13395369 -0.033199608 -0.16596441, -0.13385093 -0.033127919 -0.16603357, -0.13385093 -0.033043429 -0.16609493, -0.13397262 -0.033250839 -0.16587652, -0.13385078 -0.033197805 -0.16595581, -0.13385078 -0.033250019 -0.16586545, -0.13399354 -0.033282489 -0.1657802, -0.13385099 -0.03328222 -0.16576599, -0.13401538 -0.033293113 -0.16567948, -0.13385096 -0.033293262 -0.16566211, -0.14047298 -0.033048645 -0.15010995, -0.14048591 -0.033131778 -0.15004985, -0.14043656 -0.033047616 -0.15010469, -0.14050215 -0.033200487 -0.14997402, -0.14039934 -0.033128843 -0.15004316, -0.14039937 -0.033044398 -0.15010457, -0.14039931 -0.033198729 -0.14996558, -0.14052126 -0.033251658 -0.14988631, -0.14039928 -0.033250913 -0.14987513, -0.14054212 -0.033283368 -0.14978987, -0.14039949 -0.033283189 -0.14977568, -0.14056361 -0.033294067 -0.14968923, -0.14039946 -0.033294111 -0.14967199, -0.1437473 -0.033049121 -0.14211482, -0.14376014 -0.033132181 -0.14205459, -0.14371073 -0.033048019 -0.1421096, -0.14377648 -0.033200905 -0.14197907, -0.1436736 -0.03312926 -0.14204821, -0.14367363 -0.03304483 -0.14210951, -0.14379546 -0.033252195 -0.14189118, -0.1436736 -0.033199176 -0.14197043, -0.1436736 -0.03325133 -0.14187989, -0.14381623 -0.033283859 -0.14179493, -0.14367354 -0.033283591 -0.1417806, -0.14383802 -0.033294573 -0.14169425, -0.14367363 -0.033294573 -0.14167672, -0.12104115 0.10044923 -0.23554806, -0.12106165 0.10040039 -0.2356485, -0.12096408 0.10035893 -0.23552684, -0.12098184 0.10031784 -0.23561348, -0.12089768 0.10014309 -0.23575282, -0.12097961 0.10027218 -0.23571254, -0.12095073 0.10022461 -0.2358184, -0.12092355 0.10018243 -0.23565802, -0.12092558 0.10022116 -0.23556949, -0.12084606 0.10007906 -0.23531355, -0.12084597 0.10018694 -0.23536779, -0.12086684 0.10006046 -0.23535182, -0.12136108 0.1006006 -0.23552646, -0.12124518 0.10057391 -0.23554716, -0.12127894 0.10069004 -0.23534755, -0.12117451 0.10065079 -0.23539342, -0.12107593 0.10058764 -0.23542364, -0.12113675 0.10052222 -0.23555504, -0.12116006 0.10046388 -0.23567268, -0.12105855 0.10034543 -0.23576282, -0.12102443 0.10028803 -0.23588432, -0.12139314 0.10050237 -0.2357228, -0.12127185 0.10050541 -0.23568462, -0.1211555 0.10039833 -0.23580621, -0.12111461 0.10032943 -0.235947, -0.12126553 0.1004279 -0.23583995, -0.1212163 0.10034683 -0.23600315, -0.12137705 0.10041818 -0.23589121, -0.12132397 0.10033906 -0.23604931, -0.12088233 0.10004106 -0.23539345, -0.1208823 0.10014832 -0.23544718, -0.12089539 0.10000937 -0.23546591, -0.12087086 0.10029805 -0.23540761, -0.12090993 0.10025653 -0.23549251, -0.12089613 0.10011637 -0.23551942, -0.1209197 0.10040608 -0.23543106, -0.12086362 0.099943399 -0.23563732, -0.12089327 0.10008182 -0.23560226, -0.12086821 0.10004753 -0.23569141, -0.12089089 0.099975958 -0.23554882, -0.12098938 0.10050452 -0.23543634, -0.12049398 0.10044745 -0.2352144, -0.12049398 0.10036045 -0.23520686, -0.11165529 0.10044761 -0.23521438, -0.11165527 0.10036062 -0.2352069, -0.12049392 0.10027625 -0.23518419, -0.11165535 0.10027631 -0.23518428, -0.11165521 0.10019721 -0.23514733, -0.12049386 0.10019715 -0.23514724, -0.13719872 -0.033048138 -0.15810511, -0.13721168 -0.033131287 -0.15804484, -0.13716233 -0.03304714 -0.15810005, -0.13722798 -0.033199951 -0.15796921, -0.13712519 -0.033128485 -0.15803835, -0.1371251 -0.033043891 -0.15809985, -0.13724685 -0.033251211 -0.15788141, -0.13712516 -0.033198312 -0.15796077, -0.13712502 -0.033250377 -0.15787032, -0.13726777 -0.033282891 -0.157785, -0.13712505 -0.033282727 -0.15777083, -0.13728955 -0.033293664 -0.15768443, -0.13712507 -0.033293635 -0.157667, -0.11292785 -0.033033997 -0.2237248, -0.11355904 -0.033806503 -0.22422184, -0.11305451 -0.033152565 -0.22347388, -0.1136488 -0.033887565 -0.22398044, -0.11370972 -0.033914953 -0.22382419, -0.11320871 -0.033232599 -0.22322099, -0.1137737 -0.033924013 -0.22366564, -0.13802361 -0.032408163 -0.1344882, -0.13864073 -0.032360807 -0.13451034, -0.13868415 -0.032399878 -0.13449135, -0.13802376 -0.032360822 -0.13451041, -0.13802373 -0.032458752 -0.13447459, -0.13873041 -0.032441705 -0.13447805, -0.13802379 -0.032510966 -0.13447006, -0.13880706 -0.032510921 -0.13447002, -0.14660692 -0.032526523 -0.13648082, -0.14671281 -0.032425404 -0.13647358, -0.14667317 -0.032403991 -0.13648453, -0.14667326 -0.031854421 -0.13659485, -0.14667958 -0.032234699 -0.13651289, -0.14672086 -0.0318598 -0.13654235, -0.14663577 -0.03238377 -0.13650192, -0.14658985 -0.032359004 -0.13653551, -0.14662641 -0.03221561 -0.1365571, -0.14688075 -0.032092959 -0.13646986, -0.14672494 -0.032250971 -0.13648941, -0.14682549 -0.032286897 -0.13647008, -0.1467739 -0.03226845 -0.136475, -0.14675441 -0.032447949 -0.13647008, -0.14637065 -0.032606691 -0.13650633, -0.14639798 -0.032593489 -0.13651042, -0.14636981 -0.032600373 -0.13650979, -0.14637148 -0.03261289 -0.136503, -0.14637211 -0.032619298 -0.13649981, -0.14643413 -0.032648101 -0.13648307, -0.14677945 -0.031866372 -0.13650309, -0.14684537 -0.031873703 -0.13647835, -0.14691523 -0.031881586 -0.1364699, -0.14642584 -0.032579869 -0.13651253, -0.14643353 -0.032597691 -0.1365018, -0.14645404 -0.032558218 -0.13651633, -0.14650196 -0.032665163 -0.13647319, -0.1464493 -0.032633722 -0.13648538, -0.14648536 -0.032554626 -0.13650744, -0.14648998 -0.032517165 -0.13652386, -0.14651069 -0.032588288 -0.13648823, -0.14653039 -0.032614559 -0.1364782, -0.14654183 -0.032473177 -0.13651873, -0.14653355 -0.032441035 -0.13653827, -0.14666885 -0.032577187 -0.13646998, -0.14655107 -0.032641798 -0.13647212, -0.14657292 -0.032670781 -0.13646987, -0.14657828 -0.032502815 -0.13649371, -0.14659899 -0.032230228 -0.13657983, -0.14663711 -0.032551184 -0.1364727, -0.14663929 -0.031850502 -0.13665691, -0.081847936 0.073569804 -0.28780234, -0.081829011 0.073222697 -0.28762352, -0.081876963 0.073224068 -0.28763127, -0.081663728 0.073667407 -0.28754246, -0.081692934 0.073344857 -0.28738266, -0.081680298 0.073320031 -0.28742266, -0.081799269 0.073569655 -0.28779578, -0.081838042 0.073934495 -0.28792775, -0.081789166 0.073936135 -0.28792202, -0.081783682 0.073227227 -0.28760576, -0.081753492 0.073574215 -0.2877785, -0.081743389 0.073940903 -0.28790486, -0.081713527 0.073583037 -0.2877515, -0.081703275 0.073948383 -0.2878775, -0.081743836 0.073237419 -0.2875793, -0.081681609 0.073595881 -0.28771651, -0.081671298 0.073958218 -0.28784132, -0.081649333 0.073969781 -0.28779888, -0.081712157 0.073252976 -0.28754568, -0.081659555 0.073611617 -0.28767538, -0.081638813 0.073982477 -0.28775257, -0.081679344 0.073295504 -0.28746498, -0.081690192 0.073272616 -0.28750676, -0.081649095 0.073629647 -0.28763092, -0.081640393 0.073995382 -0.28770518, -0.081650376 0.073648602 -0.28758568, -0.081653923 0.074007988 -0.28765959, -0.13800088 0.11762884 -0.20562448, -0.13801152 0.11758527 -0.20560341, -0.13800851 0.11759777 -0.20557839, -0.13799816 0.11764026 -0.20560105, -0.13797918 0.11766787 -0.20564514, -0.13797656 0.11767864 -0.20562302, -0.13794738 0.11770031 -0.20566408, -0.13794476 0.11771046 -0.20564353, -0.13790737 0.11772387 -0.20568001, -0.13790494 0.11773372 -0.20566089, -0.13786182 0.11773774 -0.20569257, -0.13785926 0.1177471 -0.20567407, -0.13781071 0.11774984 -0.20568208, -0.13781312 0.11774066 -0.20570041, -0.12056533 0.11919177 -0.20770504, -0.13667934 0.12009941 -0.20588934, -0.13667957 0.12007098 -0.2058776, -0.1205658 0.11916327 -0.20769338, -0.13668059 0.12004119 -0.20587049, -0.12056667 0.11913362 -0.20768629, -0.12056807 0.11910307 -0.20768382, -0.13668196 0.12001066 -0.20586807, -0.10371819 0.081846118 -0.27275985, -0.10373849 0.081797153 -0.27286035, -0.10364106 0.081755787 -0.27273858, -0.10365885 0.08171472 -0.27282512, -0.10357466 0.081539899 -0.2729646, -0.10365677 0.081668913 -0.27292424, -0.10362771 0.081621438 -0.27303004, -0.1036005 0.081579387 -0.27286977, -0.10352314 0.081475884 -0.27252519, -0.10352296 0.081583828 -0.27257931, -0.10354376 0.081457287 -0.27256364, -0.10360256 0.0816181 -0.27278125, -0.10403809 0.081997454 -0.27273804, -0.1039221 0.081970751 -0.2727589, -0.10395578 0.082086802 -0.27255911, -0.10385132 0.082047462 -0.272605, -0.10375276 0.08198455 -0.27263534, -0.10381356 0.081919014 -0.27276671, -0.10383689 0.081860781 -0.27288431, -0.10373554 0.081742257 -0.27297449, -0.10370144 0.081684768 -0.27309602, -0.10407004 0.081899107 -0.27293462, -0.1039485 0.081902117 -0.27289629, -0.10383242 0.081795186 -0.27301764, -0.10379151 0.081726253 -0.27315867, -0.10394239 0.081824839 -0.27305162, -0.10389319 0.081743702 -0.27321467, -0.10405406 0.081814945 -0.27310294, -0.10400087 0.081736043 -0.27326104, -0.10355935 0.081438005 -0.27260518, -0.10355935 0.081545293 -0.27265877, -0.10357246 0.081406325 -0.27267766, -0.10354781 0.08169499 -0.27261925, -0.10358703 0.081653416 -0.27270406, -0.10357323 0.081513256 -0.27273101, -0.10359666 0.081802994 -0.27264267, -0.10354057 0.081340224 -0.27284884, -0.10357034 0.081478655 -0.27281398, -0.10354504 0.081444383 -0.27290308, -0.10356778 0.081372947 -0.27276063, -0.10366642 0.081901371 -0.27264804, -0.10317099 0.081844389 -0.27242607, -0.10317093 0.081757396 -0.2724185, -0.094332248 0.081844494 -0.27242607, -0.094332248 0.081757411 -0.27241856, -0.1031709 0.081673175 -0.27239585, -0.094332159 0.08167316 -0.27239588, -0.1031709 0.08159408 -0.27235895, -0.094332218 0.081594065 -0.27235898, -0.092439324 0.077022552 -0.27763277, -0.093001604 0.077022538 -0.27763271, -0.092439413 0.076935515 -0.27762508, -0.0930022 0.076935872 -0.2776252, -0.092439294 0.076851234 -0.27760243, -0.093002915 0.076851591 -0.27760267, -0.093003154 0.076772198 -0.2775656, -0.092439413 0.076772153 -0.27756566, -0.098984301 0.078743815 -0.27862817, -0.10028374 0.078743845 -0.27862805, -0.098984241 0.078656971 -0.27862054, -0.10028365 0.078656942 -0.27862048, -0.09898439 0.078572541 -0.27859795, -0.10028377 0.078572661 -0.27859783, -0.09898439 0.07849364 -0.27856103, -0.10028365 0.07849367 -0.278561, -0.097429603 0.077711895 -0.27734223, -0.097430617 0.077712938 -0.27733901, -0.098606259 0.079071075 -0.27812803, -0.098607361 0.079072118 -0.27812493, -0.09743154 0.077713907 -0.27733588, -0.098608017 0.079073146 -0.27812174, -0.097432375 0.077714995 -0.27733266, -0.09860909 0.0790741 -0.27811852, -0.096937656 0.077022627 -0.27763283, -0.096937686 0.076935619 -0.27762508, -0.095501274 0.077022508 -0.27763274, -0.095500618 0.076935798 -0.27762508, -0.095499843 0.0768518 -0.27760267, -0.096937686 0.076851264 -0.27760255, -0.095499724 0.076772243 -0.27756566, -0.096937716 0.076772153 -0.27756554, -0.09530291 0.076674163 -0.29168749, -0.095296353 0.07658726 -0.29167986, -0.080485135 0.076674163 -0.29168755, -0.080487818 0.076587334 -0.29167992, -0.080495536 0.076503098 -0.29165733, -0.095295995 0.076502621 -0.29165709, -0.080506504 0.076423794 -0.29162031, -0.095302314 0.076423705 -0.29162055, -0.13656616 0.12125009 -0.20648052, -0.13669138 0.12126051 -0.20647693, -0.1368051 0.12010483 -0.2058832, -0.13699341 0.11690791 -0.20424953, -0.13688904 0.11796974 -0.20479503, -0.13701479 0.11797526 -0.20478897, -0.1371187 0.11691792 -0.20424572, -0.094251454 0.082904205 -0.28363103, -0.094251484 0.083127812 -0.28430179, -0.094892442 0.082937941 -0.28356314, -0.095008999 0.083167806 -0.28422162, -0.095724791 0.083285585 -0.28398594, -0.095498085 0.0830376 -0.28336376, -0.096359491 0.08347486 -0.28360742, -0.096035182 0.083197817 -0.2830435, -0.096877873 0.083724961 -0.28310704, -0.096473932 0.083409533 -0.28261995, -0.097251832 0.084022388 -0.28251207, -0.096790195 0.083661199 -0.28211671, -0.099889398 -0.01583685 -0.24062288, -0.10066125 -0.015756324 -0.24066946, -0.099889457 -0.015153721 -0.24044037, -0.10054249 -0.015085652 -0.24047983, -0.1013889 -0.015519544 -0.24080637, -0.10115835 -0.014885142 -0.24059558, -0.10203075 -0.015139833 -0.24102601, -0.10170126 -0.014563963 -0.24078146, -0.10255012 -0.014638975 -0.2413156, -0.10214072 -0.014140174 -0.24102655, -0.10291728 -0.01404579 -0.24165869, -0.10245141 -0.013638243 -0.24131665, -0.10311106 -0.013394132 -0.24203542, -0.10261548 -0.013086617 -0.24163572, -0.10312065 -0.012721241 -0.24242462, -0.10262355 -0.012517273 -0.24196504, -0.090164483 0.067274541 -0.28637242, -0.090164483 0.066523761 -0.28767085, -0.089781523 0.067234397 -0.28634918, -0.089781612 0.066483468 -0.2876476, -0.089420855 0.067115992 -0.28628063, -0.089420855 0.066365093 -0.28757918, -0.089103401 0.06692633 -0.28617096, -0.08910358 0.066175461 -0.28746951, -0.088847607 0.066676348 -0.28602648, -0.088847697 0.065925449 -0.28732502, -0.088668406 0.066380739 -0.28585535, -0.088668466 0.06562987 -0.28715396, -0.088576138 0.066056579 -0.28566802, -0.088576078 0.06530565 -0.2869665, -0.088576078 0.065722615 -0.2854749, -0.088576198 0.064971685 -0.28677356, -0.088668495 0.065398365 -0.2852875, -0.088668406 0.064647526 -0.28658593, -0.088847727 0.065102786 -0.28511637, -0.088847637 0.064351797 -0.2864151, -0.089103431 0.064852804 -0.28497183, -0.08910355 0.064101905 -0.2862705, -0.089420915 0.064663023 -0.28486222, -0.089420944 0.063912153 -0.28616077, -0.089781582 0.064544648 -0.28479373, -0.089781582 0.063793778 -0.28609222, -0.090164542 0.063753515 -0.28606904, -0.090164393 0.064504325 -0.28477055, -0.099889487 -0.010637105 -0.24131931, -0.099889487 -0.01138787 -0.24261796, -0.099506587 -0.010677263 -0.24129605, -0.099506587 -0.011428177 -0.24259461, -0.099145859 -0.010795772 -0.24122764, -0.09914583 -0.011546627 -0.2425262, -0.098828346 -0.010985494 -0.24111806, -0.098828316 -0.011736408 -0.24241653, -0.098572731 -0.011235371 -0.24097344, -0.098572701 -0.0119863 -0.24227202, -0.098393351 -0.01153104 -0.24080262, -0.09839341 -0.012281939 -0.24210107, -0.098301142 -0.01185517 -0.24061501, -0.098301172 -0.012606218 -0.2419135, -0.098301142 -0.012189075 -0.24042177, -0.098301142 -0.012940094 -0.24172044, -0.098393381 -0.012513399 -0.2402346, -0.09839341 -0.013264224 -0.24153292, -0.098572701 -0.012809083 -0.24006343, -0.098572701 -0.013559863 -0.24136198, -0.098828465 -0.013059005 -0.23991898, -0.098828435 -0.01380986 -0.24121739, -0.099145859 -0.013248608 -0.23980927, -0.099145919 -0.013999462 -0.24110772, -0.099506646 -0.013366938 -0.23974086, -0.099506497 -0.014117852 -0.24103931, -0.099889368 -0.014158174 -0.24101603, -0.099889487 -0.01340729 -0.2397175, -0.087609142 0.065338105 -0.28076303, -0.088338315 0.064792007 -0.28051901, -0.087558866 0.065257952 -0.28078851, -0.090164512 0.071257353 -0.284311, -0.08922419 0.071106642 -0.28417051, -0.089203447 0.071156234 -0.28425235, -0.087501526 0.065178797 -0.28079593, -0.088298142 0.0647026 -0.28052056, -0.090164363 0.064209059 -0.28026807, -0.089203447 0.064405397 -0.28034887, -0.090164363 0.064304426 -0.28029037, -0.089180917 0.071220845 -0.28432274, -0.088298291 0.070859045 -0.28408068, -0.08825472 0.070916682 -0.2841469, -0.088254631 0.064616531 -0.28050375, -0.089180917 0.064312294 -0.28032792, -0.088209361 0.070986718 -0.28419828, -0.087439299 0.070429504 -0.28386515, -0.087374538 0.070487887 -0.28390998, -0.090164542 0.071324199 -0.28438246, -0.089157671 0.071297973 -0.28437841, -0.090164423 0.071403831 -0.28443974, -0.08922416 0.064501241 -0.28035092, -0.090164512 0.064402416 -0.2802937, -0.089242131 0.064596072 -0.28033385, -0.088373572 0.06488122 -0.28049877, -0.088373631 0.07078895 -0.2839148, -0.088338464 0.070815891 -0.28400242, -0.08924219 0.071074218 -0.28407967, -0.087501556 0.070382982 -0.28380537, -0.086782336 0.069787621 -0.283494, -0.086702019 0.069830686 -0.28353, -0.087558836 0.07035014 -0.28373289, -0.087609023 0.07033214 -0.28365088, -0.090164483 0.071171075 -0.28413594, -0.090164542 0.071205586 -0.28422761, -0.086859524 0.069755793 -0.28344268, -0.086322099 0.069028169 -0.28305471, -0.086230725 0.069053382 -0.28308046, -0.086993039 0.069730163 -0.28330284, -0.086930603 0.069736332 -0.28337801, -0.086409628 0.069013715 -0.28301346, -0.086084962 0.068195462 -0.28257322, -0.085988075 0.068200856 -0.28258747, -0.086561292 0.069017977 -0.28289092, -0.086490482 0.069010109 -0.28295815, -0.086178094 0.068199903 -0.28254306, -0.086084962 0.067337871 -0.28207731, -0.085988075 0.067322761 -0.28207982, -0.086338967 0.068237275 -0.28243923, -0.086263895 0.068214059 -0.2824977, -0.086178035 0.067361876 -0.28205833, -0.086322039 0.066505164 -0.28159571, -0.086230695 0.06647037 -0.28158677, -0.086339116 0.067433119 -0.28197432, -0.086263746 0.067393988 -0.28202355, -0.086409599 0.066548124 -0.28158778, -0.086782396 0.065745816 -0.28115666, -0.086702138 0.065692946 -0.28113732, -0.086561322 0.066652298 -0.28152275, -0.086490482 0.06659779 -0.28156316, -0.086859554 0.065806001 -0.2811588, -0.087439269 0.06510374 -0.28078556, -0.087374628 0.065035671 -0.28075719, -0.086993098 0.065940142 -0.28111106, -0.086930722 0.065871686 -0.28114337, -0.088209361 0.064537048 -0.28046882, -0.090164393 0.064499125 -0.28027782, -0.090164393 0.064119637 -0.2802276, -0.089157671 0.064225629 -0.28028882, -0.091537595 0.070062608 -0.28145111, -0.091587901 0.070080608 -0.28153336, -0.091930956 0.069745272 -0.28133941, -0.091720283 0.067828447 -0.28007293, -0.091639996 0.067881346 -0.2800923, -0.091840863 0.068212584 -0.28028408, -0.092019767 0.068134874 -0.28028297, -0.091797441 0.067768186 -0.28007114, -0.091126829 0.07030797 -0.28159308, -0.091931999 0.068177879 -0.28027505, -0.090660095 0.066980332 -0.27966881, -0.090678126 0.066885576 -0.27968574, -0.090164453 0.066831455 -0.27965456, -0.090164512 0.066928238 -0.27963865, -0.090164542 0.070513338 -0.2817117, -0.090164542 0.070547789 -0.28180349, -0.090678215 0.070493907 -0.28177226, -0.091126829 0.067133531 -0.27975723, -0.091086626 0.070264921 -0.28151476, -0.090639412 0.070411697 -0.28159964, -0.090660095 0.070461243 -0.28168166, -0.090616912 0.07034713 -0.28152937, -0.090593576 0.070270032 -0.28147364, -0.090164423 0.070315093 -0.28149986, -0.090164453 0.07039462 -0.2815569, -0.090164483 0.070461676 -0.28162861, -0.091086477 0.067222923 -0.27975571, -0.091537565 0.067379072 -0.27989924, -0.091480285 0.067458272 -0.27989179, -0.091868699 0.069739133 -0.28126419, -0.092171401 0.069348663 -0.28111005, -0.091418117 0.067533225 -0.27990222, -0.091353416 0.067601174 -0.27993059, -0.090639383 0.067076087 -0.27967077, -0.090164512 0.067026228 -0.27964199, -0.091480374 0.070029706 -0.28137875, -0.091042936 0.067309082 -0.2797727, -0.090997607 0.067388698 -0.27980745, -0.091043025 0.070207223 -0.28144866, -0.090997636 0.070137307 -0.28139687, -0.090616941 0.067169279 -0.27969182, -0.090164512 0.067121595 -0.27966416, -0.090593547 0.067256063 -0.2797308, -0.09210059 0.069356531 -0.28104281, -0.092295259 0.068913788 -0.28085864, -0.091797471 0.069719762 -0.28119957, -0.091418147 0.069983214 -0.28131902, -0.091353327 0.069924757 -0.28127396, -0.092220068 0.068936914 -0.28080022, -0.092295319 0.068465695 -0.28059936, -0.092019796 0.069353074 -0.2809875, -0.091720253 0.069687828 -0.2811482, -0.091639966 0.069644779 -0.28111196, -0.092220008 0.068504721 -0.28055012, -0.09217152 0.068030834 -0.28034812, -0.092134207 0.0689511 -0.28075492, -0.091932088 0.069338471 -0.28094614, -0.091840804 0.069313407 -0.28092057, -0.09210071 0.068085045 -0.28030765, -0.091931015 0.067634076 -0.2801187, -0.092134327 0.068536878 -0.28051561, -0.092041135 0.068955392 -0.28072464, -0.091944307 0.068950027 -0.28071034, -0.091868639 0.067702502 -0.28008628, -0.091587871 0.067298844 -0.27992487, -0.092041194 0.068560958 -0.28049654, -0.091944337 0.068575829 -0.28049409, -0.091161996 0.067044362 -0.27977762, -0.090164512 0.067210898 -0.27970472, -0.091161937 0.070334971 -0.28168052, -0.098967284 -0.0068375319 -0.23902678, -0.098949075 -0.0068050176 -0.23911747, -0.099889398 -0.0067061484 -0.23917471, -0.099889487 -0.0066544265 -0.23925802, -0.098928452 -0.0067555308 -0.23919953, -0.099889338 -0.013702691 -0.23521505, -0.098928332 -0.013506189 -0.23529589, -0.099889368 -0.013607323 -0.23523735, -0.098905951 -0.013599336 -0.23527499, -0.098023027 -0.013209149 -0.2354677, -0.097979605 -0.013295233 -0.23545085, -0.09890601 -0.0066908002 -0.23926984, -0.098023266 -0.0070525855 -0.23902762, -0.097979635 -0.0069950074 -0.23909399, -0.099889398 -0.013509199 -0.23524073, -0.098949075 -0.013410479 -0.23529799, -0.098967254 -0.013315618 -0.23528086, -0.099889517 -0.0065874457 -0.23932947, -0.098882645 -0.0066136569 -0.2393254, -0.099889517 -0.0065078139 -0.23938669, -0.09806326 -0.013119638 -0.23546611, -0.097934335 -0.0069250315 -0.23914552, -0.097164363 -0.0074821413 -0.23881228, -0.097099632 -0.0074238032 -0.23885712, -0.097334027 -0.0075795054 -0.23859777, -0.098063439 -0.0070958436 -0.2389494, -0.098098606 -0.0071227998 -0.23886192, -0.09722659 -0.0075287074 -0.23875237, -0.0965074 -0.0081241429 -0.23844098, -0.096427053 -0.008081004 -0.23847699, -0.096717924 -0.0081816167 -0.23824954, -0.09728384 -0.0075615793 -0.23868006, -0.099889487 -0.0067406297 -0.23908295, -0.096584648 -0.0081559718 -0.2383896, -0.096046925 -0.0088836551 -0.23800181, -0.0959557 -0.008858487 -0.23802757, -0.096655697 -0.0081752986 -0.238325, -0.096286237 -0.0088937283 -0.23783801, -0.096134663 -0.0088981986 -0.23796056, -0.095809788 -0.0097161978 -0.23752031, -0.095713049 -0.0097109377 -0.23753457, -0.096063912 -0.0096745491 -0.23738657, -0.096215427 -0.0089015514 -0.23790529, -0.095902979 -0.0097118616 -0.23749013, -0.095809937 -0.010573909 -0.23702455, -0.095713109 -0.010588929 -0.23702675, -0.09598875 -0.0096977204 -0.23744488, -0.096063942 -0.01047878 -0.23692131, -0.095902979 -0.010549888 -0.23700544, -0.096046895 -0.01140663 -0.23654287, -0.09595567 -0.011441395 -0.23653376, -0.096286386 -0.011259601 -0.23646975, -0.09598887 -0.010517761 -0.23697063, -0.096134603 -0.01136364 -0.23653492, -0.096507192 -0.012166142 -0.23610376, -0.096426994 -0.012218878 -0.23608434, -0.096717954 -0.011971667 -0.23605803, -0.096215457 -0.01131396 -0.23651016, -0.096584529 -0.012105718 -0.23610583, -0.097164184 -0.01280801 -0.23573261, -0.097099572 -0.012876078 -0.23570415, -0.097334057 -0.012573659 -0.2357101, -0.096655637 -0.012040064 -0.2360903, -0.097226411 -0.012733042 -0.23574303, -0.097934246 -0.01337482 -0.23541588, -0.099889427 -0.01341249 -0.23522484, -0.098098546 -0.013030469 -0.23544584, -0.097283751 -0.012653798 -0.23573537, -0.099889487 -0.013791859 -0.23517452, -0.098882616 -0.013686121 -0.2352358, -0.10126248 -0.0078492016 -0.23639816, -0.10131276 -0.007831201 -0.23648036, -0.1016559 -0.0081665516 -0.23628657, -0.10144526 -0.010083288 -0.23502006, -0.10136503 -0.010030359 -0.23503949, -0.10156581 -0.0096991956 -0.23523106, -0.1017448 -0.0097769797 -0.23522998, -0.10152239 -0.010143578 -0.235018, -0.10085174 -0.0076037198 -0.23654011, -0.10165697 -0.0097338855 -0.23522206, -0.10038504 -0.010931462 -0.2346157, -0.10040316 -0.011026233 -0.23463295, -0.099889457 -0.011080191 -0.23460159, -0.099889338 -0.010983407 -0.23458569, -0.099889368 -0.0073984414 -0.23665884, -0.099889398 -0.0073640198 -0.23675048, -0.10040316 -0.0074178725 -0.23671949, -0.10085171 -0.010778248 -0.23470448, -0.10081157 -0.0076468736 -0.23646167, -0.1003643 -0.0075000077 -0.23654678, -0.10038507 -0.0074504465 -0.2366288, -0.10034189 -0.0075646043 -0.23647644, -0.10031852 -0.0076417625 -0.23642077, -0.099889398 -0.0075967163 -0.23644674, -0.099889368 -0.0075170547 -0.23650399, -0.099889457 -0.0074500889 -0.23657542, -0.10081154 -0.010688752 -0.23470278, -0.10126269 -0.010532737 -0.23484646, -0.1012052 -0.010453582 -0.23483871, -0.10159355 -0.0081726164 -0.23621112, -0.10189638 -0.0085631311 -0.23605703, -0.10114306 -0.010378569 -0.23484935, -0.10107821 -0.010310605 -0.23487756, -0.1003643 -0.010835618 -0.23461784, -0.099889368 -0.010885507 -0.23458891, -0.10120517 -0.0078820735 -0.23632577, -0.10076794 -0.010602713 -0.23471962, -0.10072264 -0.010523051 -0.2347547, -0.10076791 -0.0077045411 -0.2363956, -0.10072258 -0.0077744424 -0.23634402, -0.10034189 -0.010742515 -0.23463871, -0.099889487 -0.01079005 -0.23461126, -0.10031849 -0.010655716 -0.234678, -0.10182559 -0.0085554272 -0.2359899, -0.10202023 -0.0089981556 -0.2358055, -0.10152245 -0.0081921667 -0.23614645, -0.10114306 -0.0079285949 -0.23626596, -0.10107833 -0.0079869777 -0.2362211, -0.10194492 -0.0089749396 -0.23574711, -0.10202023 -0.0094461441 -0.23554654, -0.10174462 -0.0085588098 -0.23593442, -0.10144523 -0.0082239807 -0.23609512, -0.10136494 -0.0082671195 -0.2360591, -0.10194501 -0.0094070137 -0.23549737, -0.10189635 -0.0098809898 -0.23529504, -0.10185918 -0.0089608431 -0.23570202, -0.101657 -0.0085732639 -0.23589315, -0.10156584 -0.0085984468 -0.23586749, -0.10182559 -0.0098266602 -0.23525472, -0.1016559 -0.010277599 -0.23506568, -0.10185915 -0.0093749315 -0.23546252, -0.10176605 -0.0089563131 -0.23567168, -0.10166922 -0.0089617074 -0.23565759, -0.10159358 -0.010209173 -0.23503329, -0.10131285 -0.010613054 -0.23487176, -0.10176611 -0.0093508959 -0.23544355, -0.10166922 -0.0093359649 -0.2354411, -0.10088703 -0.010867327 -0.23472475, -0.099889457 -0.010700762 -0.23465179, -0.10088691 -0.0075767785 -0.23662761, -0.099889457 -0.0099946558 -0.23950945, -0.099590272 -0.010026276 -0.23949136, -0.099889487 -0.0080666095 -0.23617497, -0.099590302 -0.0080980957 -0.23615696, -0.09930858 -0.010118648 -0.2394377, -0.09930861 -0.0081905872 -0.23610333, -0.099060506 -0.010266826 -0.23935199, -0.099060506 -0.0083387792 -0.23601778, -0.098860711 -0.01046209 -0.2392391, -0.09886077 -0.0085341483 -0.23590487, -0.09872067 -0.010693133 -0.2391056, -0.098720789 -0.0087650269 -0.23577115, -0.098648518 -0.010946319 -0.23895895, -0.098648489 -0.009018302 -0.23562466, -0.098648489 -0.011207223 -0.23880826, -0.098648638 -0.0092791766 -0.23547387, -0.09872064 -0.011460468 -0.23866165, -0.09872064 -0.0095324963 -0.23532736, -0.098860711 -0.011691496 -0.23852822, -0.09886077 -0.0097635239 -0.23519403, -0.099060565 -0.011886835 -0.23841526, -0.099060535 -0.0099588037 -0.235081, -0.099308491 -0.012035027 -0.23832959, -0.09930861 -0.010106891 -0.23499544, -0.099590391 -0.012127474 -0.23827603, -0.099590212 -0.010199398 -0.23494174, -0.099889427 -0.012159005 -0.23825797, -0.099889368 -0.010230899 -0.23492359, -0.090164363 0.067917079 -0.28456223, -0.089865267 0.067885488 -0.28454411, -0.090164542 0.069845185 -0.28122798, -0.089865446 0.069813699 -0.28120971, -0.089583486 0.067793131 -0.28449059, -0.089583516 0.069721192 -0.28115642, -0.08933571 0.067644864 -0.28440487, -0.089335561 0.069572896 -0.28107059, -0.089135736 0.067449659 -0.2842921, -0.089135796 0.069377661 -0.28095776, -0.088995665 0.067218632 -0.28415847, -0.088995695 0.069146723 -0.28082407, -0.088923663 0.066965312 -0.28401208, -0.088923693 0.068893522 -0.28067768, -0.088923544 0.066704363 -0.28386116, -0.088923603 0.068632483 -0.28052682, -0.088995695 0.066451192 -0.28371483, -0.088995755 0.068379194 -0.28038037, -0.089135766 0.066220164 -0.2835812, -0.089135826 0.068148285 -0.28024685, -0.089335501 0.066024989 -0.28346825, -0.08933565 0.06795308 -0.28013384, -0.089583457 0.065876812 -0.28338253, -0.089583576 0.067804947 -0.28004825, -0.089865327 0.067712277 -0.27999461, -0.089865386 0.065784305 -0.28332901, -0.090164542 0.067680806 -0.27997649, -0.090164423 0.065752774 -0.28331077, -0.091466188 0.070602387 -0.28282094, -0.091955304 0.07078895 -0.28391492, -0.092719913 0.07033214 -0.28365076, -0.092510104 0.069881648 -0.2824043, -0.090736955 0.066304162 -0.27984262, -0.091466129 0.065922499 -0.28011489, -0.090926975 0.065156654 -0.28016511, -0.091086686 0.064596131 -0.28033388, -0.091955245 0.06488128 -0.28049874, -0.090737104 0.070647806 -0.28235435, -0.090927064 0.070940822 -0.28350991, -0.091086745 0.071074098 -0.28407979, -0.092719764 0.06533809 -0.28076303, -0.092509896 0.066643074 -0.28053156, -0.093335837 0.065940097 -0.281111, -0.093767703 0.066652164 -0.2815229, -0.093089193 0.067684531 -0.28113383, -0.093989938 0.067432955 -0.28197432, -0.093990058 0.068237275 -0.28243947, -0.093089193 0.068840355 -0.28180206, -0.093767494 0.069018096 -0.28289104, -0.093335837 0.069730252 -0.28330266, -0.10119113 -0.0073095113 -0.23776796, -0.10168028 -0.0071228743 -0.23886202, -0.1024448 -0.0075796247 -0.23859777, -0.10223496 -0.0080301762 -0.23735128, -0.10046199 -0.011607483 -0.23478973, -0.10119104 -0.011989295 -0.23506205, -0.10065201 -0.012755111 -0.23511207, -0.10081169 -0.013315737 -0.23528086, -0.10168028 -0.013030529 -0.23544581, -0.10046205 -0.0072639734 -0.23730138, -0.10065207 -0.0069708377 -0.23845688, -0.10081172 -0.0068376958 -0.23902704, -0.10244471 -0.012573659 -0.23571007, -0.10223493 -0.011268586 -0.23547874, -0.1030609 -0.011971712 -0.23605804, -0.10349259 -0.011259675 -0.23646973, -0.10281423 -0.010227367 -0.23608077, -0.10371488 -0.010478809 -0.2369214, -0.10371491 -0.0096746534 -0.23738647, -0.10281429 -0.0090714395 -0.23674919, -0.10349259 -0.0088936985 -0.23783793, -0.10306093 -0.0081815273 -0.23824981, -0.12685397 0.1115683 -0.20930366, -0.12690413 0.11164926 -0.20928061, -0.12724721 0.11147593 -0.20962706, -0.1267966 0.11016974 -0.21199767, -0.12718502 0.11034918 -0.21174203, -0.12685388 0.11018206 -0.21207625, -0.12703672 0.1103282 -0.2116171, -0.12695634 0.11034438 -0.21156324, -0.12715727 0.11051551 -0.21122079, -0.12644309 0.11169504 -0.20905, -0.12733617 0.11051929 -0.21129857, -0.12711385 0.11032982 -0.21167749, -0.12724841 0.11050865 -0.21125616, -0.12640303 0.11161952 -0.20909765, -0.12597638 0.11177436 -0.20889167, -0.12597629 0.10997602 -0.21248819, -0.12599441 0.10999891 -0.2125818, -0.12548074 0.10997102 -0.21263771, -0.1254808 0.10994937 -0.21254212, -0.12548074 0.11180116 -0.20883796, -0.12548074 0.11189057 -0.2087979, -0.12599456 0.11186276 -0.2088536, -0.126443 0.11005518 -0.21232988, -0.1259557 0.11169539 -0.20894599, -0.12593329 0.11162923 -0.20901489, -0.12590995 0.1115782 -0.20909525, -0.12548083 0.11160152 -0.20904863, -0.12548083 0.11165373 -0.20896566, -0.12548077 0.11172114 -0.20889449, -0.12640283 0.11004815 -0.21224071, -0.12718499 0.11140107 -0.20963776, -0.12748778 0.11127111 -0.21003701, -0.12673441 0.11017573 -0.21192227, -0.12666976 0.11019979 -0.21185258, -0.12595567 0.10997221 -0.21239249, -0.12548062 0.10994646 -0.2124442, -0.1267966 0.11149809 -0.20934094, -0.12635934 0.11005992 -0.21215387, -0.12635946 0.11155699 -0.20915926, -0.12631407 0.11150977 -0.20923235, -0.12631389 0.11008987 -0.21207227, -0.12593314 0.10998771 -0.21229832, -0.12548074 0.10996303 -0.21234752, -0.12590978 0.11002132 -0.21220939, -0.12741697 0.11120352 -0.2100331, -0.12761167 0.11104651 -0.21048635, -0.12711373 0.1113378 -0.20966116, -0.12673441 0.11144115 -0.20939091, -0.12666965 0.11139987 -0.20945191, -0.12753642 0.11098668 -0.21046664, -0.1276117 0.11081508 -0.21094911, -0.12733603 0.11114845 -0.21003981, -0.12703669 0.11128865 -0.20969597, -0.12695643 0.1112553 -0.2097412, -0.12753648 0.11076358 -0.21091323, -0.12748778 0.11059043 -0.21139862, -0.1274507 0.1109408 -0.21045533, -0.12724841 0.11110815 -0.21005692, -0.12715721 0.11108407 -0.21008362, -0.127417 0.11054695 -0.21134673, -0.12724721 0.11038563 -0.21180846, -0.12745059 0.11072692 -0.21088316, -0.12735754 0.11091021 -0.21045269, -0.12726057 0.11089644 -0.21045889, -0.12690425 0.1102123 -0.21215488, -0.12735742 0.11070658 -0.21086031, -0.12726057 0.1107032 -0.21084549, -0.12647834 0.11008087 -0.21241774, -0.12548077 0.10999799 -0.21225603, -0.1264784 0.11178078 -0.20901784, -0.12357086 0.11095297 -0.21479706, -0.12449741 0.11079594 -0.21511121, -0.12352562 0.11092295 -0.21487856, -0.1245586 0.11413075 -0.2081345, -0.12454063 0.11421935 -0.20809641, -0.12548077 0.11427031 -0.20799422, -0.1245586 0.11078463 -0.21482787, -0.12365472 0.11095758 -0.21462104, -0.12368998 0.11093187 -0.21453302, -0.12287521 0.1111982 -0.2141397, -0.12548077 0.1143503 -0.2079376, -0.12451985 0.11429818 -0.20804209, -0.12281787 0.11121048 -0.21421814, -0.12361455 0.11096467 -0.21471, -0.12548074 0.11074243 -0.2152181, -0.12451971 0.11081113 -0.2150172, -0.12548074 0.110759 -0.21512154, -0.12361458 0.1141447 -0.20834908, -0.12449747 0.11436431 -0.20797339, -0.12357107 0.11420728 -0.20828745, -0.12352568 0.11425464 -0.20821476, -0.12275568 0.11395563 -0.20879087, -0.12269092 0.11399685 -0.20872986, -0.12454045 0.11080737 -0.21492144, -0.12548086 0.11075637 -0.21502359, -0.12548074 0.11073455 -0.21492796, -0.12292552 0.11374769 -0.20890106, -0.12365475 0.11406912 -0.20839688, -0.12369004 0.11398341 -0.20842913, -0.1228179 0.11389889 -0.20884094, -0.1220988 0.11362398 -0.20945419, -0.12201852 0.11365741 -0.20940889, -0.12230939 0.11343664 -0.2095231, -0.12287515 0.11382858 -0.20887828, -0.1254808 0.11418082 -0.20803437, -0.12217593 0.11357474 -0.20948912, -0.12163827 0.11323178 -0.21023886, -0.12154701 0.11325574 -0.21021219, -0.12224701 0.11351147 -0.20951234, -0.12187767 0.11306879 -0.2102588, -0.12172604 0.11319146 -0.21025582, -0.12140125 0.1128017 -0.21109925, -0.12130427 0.11281559 -0.21109302, -0.12165534 0.11266544 -0.21106561, -0.12180674 0.11313644 -0.21026252, -0.12149417 0.11277118 -0.21109663, -0.12140119 0.11235866 -0.2119853, -0.12130436 0.11236207 -0.21200022, -0.12158012 0.11272517 -0.2110853, -0.12165546 0.11225012 -0.21189664, -0.12149441 0.11233827 -0.21196242, -0.12163833 0.11192846 -0.21284576, -0.12154719 0.11192167 -0.21288101, -0.12187761 0.1118467 -0.21270338, -0.12158018 0.1123016 -0.21193245, -0.12172604 0.11191788 -0.21280335, -0.12209868 0.11153618 -0.2136303, -0.12201846 0.11152004 -0.21368435, -0.12230945 0.11147889 -0.21343918, -0.12180686 0.11189035 -0.21275519, -0.12217593 0.11153463 -0.21357022, -0.12447396 0.11076216 -0.21520025, -0.12548086 0.11070751 -0.21530965, -0.12275565 0.11120464 -0.21429372, -0.12269092 0.11118056 -0.21436322, -0.12292543 0.11116794 -0.2140611, -0.12224707 0.11151528 -0.21350543, -0.12548077 0.11441766 -0.20786646, -0.12548077 0.11446987 -0.20778358, -0.12447405 0.11441539 -0.20789289, -0.12678245 0.11290297 -0.20868184, -0.12727153 0.1139835 -0.20842898, -0.1280362 0.11374746 -0.20890111, -0.12782633 0.11253069 -0.20942628, -0.12605336 0.11019078 -0.21315245, -0.12678251 0.11048563 -0.21351701, -0.12624332 0.11058208 -0.21427847, -0.12640306 0.11078462 -0.21482782, -0.12727156 0.11093189 -0.21453315, -0.12605342 0.1124344 -0.20866475, -0.12624326 0.11356987 -0.20830193, -0.12640297 0.11413072 -0.20813441, -0.12803626 0.11116788 -0.21406107, -0.12782633 0.1108578 -0.21277243, -0.12865222 0.11147889 -0.21343912, -0.12908396 0.11184661 -0.21270347, -0.1284056 0.11139579 -0.21169657, -0.12930638 0.11225 -0.21189658, -0.12930632 0.11266539 -0.21106566, -0.12840557 0.11199269 -0.2105024, -0.12908399 0.11306868 -0.21025875, -0.12865222 0.11343645 -0.20952296, -0.09365496 0.076771557 -0.27871877, -0.093670487 0.080340326 -0.28051227, -0.093943864 0.076721072 -0.27881992, -0.093422562 0.080416963 -0.28035921, -0.093952298 0.080292657 -0.28060782, -0.094251513 0.076703891 -0.27885425, -0.094251424 0.080276474 -0.28064018, -0.094251513 0.081394345 -0.27840412, -0.093952417 0.081378013 -0.27843678, -0.094251513 0.077835396 -0.27662483, -0.093950033 0.077818826 -0.27665797, -0.093670607 0.081330255 -0.2785323, -0.093666434 0.077770427 -0.27675489, -0.093422532 0.081253722 -0.27868524, -0.093417317 0.077692688 -0.27691036, -0.093222708 0.081152946 -0.27888715, -0.093217462 0.077590406 -0.27711481, -0.093005329 0.077205703 -0.27759776, -0.0930053 0.077218875 -0.27782393, -0.093001962 0.07711561 -0.27762389, -0.093078643 0.077469751 -0.27735639, -0.093082607 0.081033602 -0.27912587, -0.093049645 0.077422693 -0.27743235, -0.093010545 0.080902889 -0.27938738, -0.093028069 0.077361897 -0.27749971, -0.093013525 0.077288821 -0.27755585, -0.093010545 0.080767944 -0.27965701, -0.093067765 0.077083096 -0.27809548, -0.093082726 0.080637127 -0.27991867, -0.093203068 0.076958284 -0.27834499, -0.093222797 0.080517784 -0.28015745, -0.093402982 0.076852426 -0.27855718, -0.12548077 0.11135875 -0.20953417, -0.12548083 0.1149314 -0.21132021, -0.12518159 0.11134256 -0.20956674, -0.1251817 0.11491516 -0.21135269, -0.12489989 0.11486736 -0.21144842, -0.12489989 0.11129476 -0.20966217, -0.12465194 0.11479083 -0.21160148, -0.12465191 0.1112182 -0.20981526, -0.12445217 0.11469001 -0.21180324, -0.12445202 0.11111738 -0.21001723, -0.12431207 0.11457065 -0.21204184, -0.12431207 0.11099811 -0.2102558, -0.12424001 0.1144397 -0.21230362, -0.12423992 0.1108671 -0.21051747, -0.12424007 0.114305 -0.21257308, -0.1242398 0.11073233 -0.21078688, -0.12431204 0.11417425 -0.21283476, -0.12431204 0.11060168 -0.21104857, -0.12445217 0.11405486 -0.21307342, -0.12445211 0.11048229 -0.21128732, -0.12465182 0.1139541 -0.21327518, -0.12465191 0.11038142 -0.21148904, -0.12489992 0.11387748 -0.2134283, -0.12489992 0.11030476 -0.21164227, -0.12518159 0.11025706 -0.2117378, -0.12518167 0.11382972 -0.21352378, -0.12548074 0.11024079 -0.21177022, -0.1254808 0.11381343 -0.21355639, -0.12548077 0.1168716 -0.21189894, -0.12548077 0.11838627 -0.21265616, -0.12509793 0.11685076 -0.21194039, -0.12509799 0.11836562 -0.21269782, -0.12473729 0.11678961 -0.21206282, -0.12473729 0.1183044 -0.21282016, -0.12441987 0.11669174 -0.21225868, -0.12441987 0.11820644 -0.2130162, -0.12416402 0.11656252 -0.21251701, -0.12416404 0.11807734 -0.21327452, -0.12398493 0.11640987 -0.2128226, -0.1239849 0.11792466 -0.21357988, -0.12389249 0.11624232 -0.21315752, -0.12389246 0.11775711 -0.21391474, -0.12389258 0.1160699 -0.21350247, -0.12389246 0.11758462 -0.21425985, -0.12398478 0.11590247 -0.21383744, -0.12398481 0.11741723 -0.21459487, -0.12416399 0.11574961 -0.21414295, -0.12416402 0.11726451 -0.2149003, -0.12441972 0.11562049 -0.21440129, -0.12441987 0.11713535 -0.21515851, -0.12473732 0.11552253 -0.21459721, -0.12473729 0.11703742 -0.21535449, -0.1250979 0.11546132 -0.21471961, -0.12509793 0.11697629 -0.21547674, -0.12548083 0.11695549 -0.21551846, -0.12548077 0.11544049 -0.21476106, -0.094251424 0.083334431 -0.27898273, -0.094251454 0.084849223 -0.27973998, -0.093868524 0.083313629 -0.27902436, -0.093868524 0.084828392 -0.27978167, -0.093507797 0.083252594 -0.27914679, -0.093507767 0.084767237 -0.27990407, -0.093190461 0.083154485 -0.27934265, -0.093190491 0.084669366 -0.28010002, -0.092934757 0.0830255 -0.27960101, -0.092934757 0.084540293 -0.2803582, -0.092755407 0.082872719 -0.27990663, -0.092755497 0.084387556 -0.28066385, -0.092663139 0.08270514 -0.28024143, -0.092663229 0.084220186 -0.28099874, -0.092663199 0.082532808 -0.28058645, -0.09266308 0.084047601 -0.28134382, -0.092755467 0.0823652 -0.28092155, -0.092755526 0.083880231 -0.28167877, -0.092934698 0.082212597 -0.28122687, -0.092934638 0.083727375 -0.28198421, -0.093190461 0.082083508 -0.28148526, -0.093190491 0.083598241 -0.28224242, -0.093507916 0.081985518 -0.28168112, -0.093507916 0.083500162 -0.28243837, -0.093868583 0.081924319 -0.28180355, -0.093868494 0.083439156 -0.28256083, -0.094251484 0.081903517 -0.28184515, -0.094251513 0.083418354 -0.28260237, -0.11347288 0.10338564 -0.22927761, -0.11348414 0.10332079 -0.22926652, -0.10837626 0.10201381 -0.23202154, -0.10836899 0.10194407 -0.23202059, -0.10836738 0.10187803 -0.23200637, -0.11349115 0.10325713 -0.2292476, -0.10837162 0.101817 -0.2319791, -0.11349353 0.10319579 -0.22922142, -0.11635995 0.10648601 -0.22307563, -0.11637142 0.10642131 -0.22306448, -0.11126333 0.10511434 -0.22581963, -0.11125597 0.10504465 -0.22581857, -0.11125442 0.1049784 -0.22580421, -0.11637831 0.10635768 -0.22304565, -0.11125883 0.1049176 -0.22577715, -0.11638078 0.10629624 -0.22301947, -0.10769838 0.097184584 -0.24168158, -0.10770974 0.097119763 -0.2416704, -0.10260189 0.095812738 -0.24442555, -0.10259452 0.09574303 -0.24442457, -0.10259303 0.095676944 -0.24441019, -0.10771677 0.097056165 -0.24165145, -0.10259727 0.095616072 -0.24438308, -0.10771915 0.096994713 -0.24162534, -0.10481128 0.094084054 -0.24788345, -0.10482261 0.094019145 -0.24787231, -0.099714607 0.092712164 -0.25062752, -0.099707216 0.092642426 -0.25062644, -0.099705726 0.092576236 -0.2506122, -0.10482952 0.093955532 -0.24785358, -0.099710047 0.092515558 -0.25058484, -0.10483211 0.093894154 -0.24782731, -0.10192403 0.090983465 -0.25408542, -0.10193542 0.090918705 -0.25407431, -0.096827477 0.08961156 -0.25682938, -0.096820146 0.089541838 -0.2568284, -0.096818537 0.089475766 -0.25681415, -0.10194239 0.090855107 -0.25405535, -0.096822917 0.089414999 -0.256787, -0.10194501 0.090793625 -0.25402933, -0.099036902 0.087883011 -0.26028758, -0.099048197 0.087818146 -0.2602762, -0.093940407 0.086511284 -0.26303148, -0.093932986 0.086441562 -0.26303029, -0.093931377 0.086375281 -0.26301599, -0.099055201 0.087754458 -0.2602573, -0.093935847 0.08631447 -0.26298887, -0.099057645 0.087693125 -0.26023108, -0.096149713 0.084782377 -0.26648939, -0.096161216 0.084717587 -0.26647812, -0.091053069 0.08341077 -0.26923352, -0.091045827 0.083340913 -0.26923233, -0.091044366 0.083274752 -0.26921809, -0.096168101 0.084653959 -0.26645938, -0.091048598 0.083213955 -0.26919085, -0.096170455 0.084592476 -0.26643312, -0.1105856 0.10028504 -0.23547956, -0.11059698 0.10022034 -0.23546842, -0.10548899 0.098913237 -0.23822376, -0.10548165 0.0988435 -0.23822254, -0.10548013 0.098777309 -0.23820832, -0.11060396 0.10015649 -0.2354496, -0.10548437 0.098716512 -0.23818108, -0.11060637 0.10009523 -0.23542336, -0.093262523 0.081681982 -0.27269128, -0.093273908 0.081617162 -0.2726801, -0.088166028 0.080310166 -0.27543539, -0.088158607 0.080240354 -0.27543435, -0.088157117 0.080174178 -0.27542001, -0.093280941 0.081553414 -0.27266142, -0.088161379 0.080113366 -0.2753928, -0.093283325 0.081491992 -0.2726351, -0.089761615 0.078416333 -0.27922368, -0.089773178 0.078351527 -0.27921253, -0.085278779 0.077209607 -0.28163728, -0.085271448 0.077139765 -0.28163636, -0.085269839 0.077073708 -0.28162184, -0.089780092 0.078287825 -0.27919364, -0.08527422 0.077012882 -0.28159475, -0.089782476 0.078226417 -0.27916735, -0.099499017 0.074245244 -0.28577232, -0.099464804 0.073897392 -0.28574187, -0.083253384 0.074245363 -0.28577232, -0.083226919 0.073898345 -0.2857421, -0.083226204 0.073559433 -0.28565103, -0.099463642 0.073560268 -0.28565139, -0.083251327 0.073244095 -0.28550375, -0.099496275 0.073243886 -0.28550375, -0.13063064 -0.033293545 -0.14067839, -0.13067108 -0.033294544 -0.14069775, -0.13064116 -0.033289835 -0.14065346, -0.13062018 -0.03329733 -0.1407031, -0.13062173 -0.033294544 -0.14081815, -0.13059893 -0.033305258 -0.14075209, -0.13058963 -0.033308342 -0.14077419, -0.13057846 -0.033308014 -0.14086464, -0.1305849 -0.033294544 -0.14090815, -0.13058001 -0.033310995 -0.14079741, -0.13056996 -0.033315271 -0.1408204, -0.13055634 -0.033314884 -0.14091145, -0.13055208 -0.033328146 -0.14086045, -0.13056108 -0.033322111 -0.14084065, -0.13056543 -0.03331849 -0.14083053, -0.13053861 -0.033333242 -0.14089189, -0.13052967 -0.033334851 -0.14091186, -0.13054541 -0.033331245 -0.14087613, -0.1140669 -0.033289596 -0.18112478, -0.11411157 -0.033288285 -0.18108431, -0.11409435 -0.033283561 -0.18105884, -0.11412877 -0.033291161 -0.18111007, -0.11406592 -0.033292145 -0.18118264, -0.11414611 -0.033292115 -0.18113594, -0.098651171 0.091793537 -0.25314313, -0.10431796 0.093318731 -0.25009245, -0.1016871 0.091430709 -0.25386879, -0.10209736 0.091519728 -0.25369066, -0.10254002 0.091574833 -0.25358054, -0.12581775 0.10581812 -0.22508945, -0.12378272 0.10395324 -0.22881992, -0.12358397 0.10398504 -0.22875647, -0.10457429 0.094531342 -0.24766675, -0.099979162 0.093294352 -0.25014073, -0.10153839 0.094893992 -0.24694122, -0.098543614 0.087117806 -0.26249608, -0.097219318 0.085392192 -0.26594782, -0.096765727 0.085373893 -0.26598442, -0.10144979 0.094873875 -0.24698167, -0.10720509 0.096419245 -0.2438903, -0.099327534 0.087215096 -0.26230121, -0.10498446 0.094620287 -0.24748863, -0.10542735 0.094675437 -0.24737862, -0.10746133 0.097631752 -0.24146493, -0.10286638 0.096394941 -0.24393883, -0.10442555 0.097994626 -0.24073942, -0.10433704 0.09797436 -0.24077974, -0.11009225 0.099519834 -0.2376883, -0.10787156 0.097720802 -0.24128674, -0.10831445 0.097775862 -0.24117661, -0.11034855 0.10073228 -0.2352629, -0.10575363 0.099495471 -0.2377369, -0.10731271 0.10109508 -0.23453729, -0.10722417 0.10107484 -0.23457785, -0.11426899 0.093416199 -0.24989715, -0.11183235 0.091593027 -0.25354385, -0.105102 0.093416259 -0.2498973, -0.11297947 0.10262027 -0.23148651, -0.12037125 0.11507753 -0.20656846, -0.1198689 0.11480585 -0.20711176, -0.12013364 0.11498819 -0.2067472, -0.11075881 0.10082133 -0.23508492, -0.11998287 0.11490235 -0.20691879, -0.11120167 0.10087629 -0.23497471, -0.11323568 0.10383289 -0.22906107, -0.10864079 0.10259604 -0.23153494, -0.11019987 0.10419564 -0.22833544, -0.11011136 0.10417533 -0.2283759, -0.11586666 0.1057208 -0.22528446, -0.11364591 0.10392188 -0.22888285, -0.10299376 0.091593102 -0.25354391, -0.1140888 0.1039768 -0.22877264, -0.11612287 0.10693331 -0.22285905, -0.11152777 0.10569647 -0.22533305, -0.11308709 0.10729606 -0.22213346, -0.11203533 0.091582865 -0.25356442, -0.12064829 0.11514035 -0.2064427, -0.11299863 0.10727592 -0.22217387, -0.1187537 0.10882129 -0.21908259, -0.11653307 0.10702236 -0.22268099, -0.11697593 0.10707743 -0.22257093, -0.11953786 0.1089188 -0.21888757, -0.12870488 0.10891862 -0.21888754, -0.12626812 0.10709582 -0.22253415, -0.12095022 0.11517334 -0.20637669, -0.12915537 0.11019619 -0.21633217, -0.12031686 0.11019625 -0.2163322, -0.12648755 0.11076221 -0.21520032, -0.12396041 0.10390122 -0.22892389, -0.13744107 0.1158677 -0.20498739, -0.10034835 0.07603398 -0.28466666, -0.12954673 0.10916957 -0.21838577, -0.12998539 0.10964081 -0.21744348, -0.12665954 0.10606912 -0.22458778, -0.11223403 0.091551185 -0.25362784, -0.12377241 0.10296854 -0.23078971, -0.12088525 0.099867985 -0.23699164, -0.11799797 0.096767485 -0.24319367, -0.11511084 0.093667015 -0.24939552, -0.11222365 0.090566412 -0.25559753, -0.10933638 0.087465882 -0.26179945, -0.10644931 0.084365368 -0.26800138, -0.12407622 0.10384917 -0.22902809, -0.11241171 0.091499239 -0.25373161, -0.12598935 0.10582545 -0.22507475, -0.12648764 0.1144153 -0.20789281, -0.11252767 0.091447234 -0.25383598, -0.12616158 0.10584836 -0.22502908, -0.1144408 0.093423501 -0.24988264, -0.10771704 0.096505627 -0.24371734, -0.10798916 0.096516639 -0.24369539, -0.10745114 0.096472666 -0.24378335, -0.11901009 0.11003388 -0.21665716, -0.11422649 0.10874638 -0.21923254, -0.12632361 0.10588674 -0.22495234, -0.11942038 0.11012292 -0.21647887, -0.11461297 0.093446285 -0.24983697, -0.12646517 0.10593876 -0.22484837, -0.11986318 0.11017792 -0.21636885, -0.096168339 0.084103733 -0.26852518, -0.096440375 0.084114641 -0.26850319, -0.095902413 0.084070742 -0.26859123, -0.095656306 0.084017098 -0.2686981, -0.12657842 0.10600099 -0.22472383, -0.11477503 0.093484744 -0.24976018, -0.11491641 0.09353672 -0.24965599, -0.11502975 0.093598977 -0.2495316, -0.089901119 0.082471669 -0.27178943, -0.093025357 0.082129166 -0.27247477, -0.088430583 0.080892459 -0.27494875, -0.089989722 0.082491904 -0.27174908, -0.11899993 0.10887469 -0.21897572, -0.11926571 0.10890774 -0.21890953, -0.10588107 0.09469381 -0.24734192, -0.11376351 0.1027178 -0.23129147, -0.12049392 0.1008946 -0.23493813, -0.11165535 0.10089476 -0.234938, -0.12293059 0.10271773 -0.23129146, -0.13707487 0.11608154 -0.20455967, -0.12743598 0.1142544 -0.20821467, -0.12827057 0.11399685 -0.20872992, -0.1289432 0.11365746 -0.20940888, -0.12069678 0.1008845 -0.23495863, -0.094332308 0.082291499 -0.27214965, -0.1208955 0.10085277 -0.2350221, -0.093878567 0.08227329 -0.27218634, -0.11138186 0.090315729 -0.25609922, -0.10894516 0.088492662 -0.25974572, -0.10221472 0.090315625 -0.25609919, -0.10010663 0.088492587 -0.25974569, -0.10914809 0.08848238 -0.2597664, -0.10934681 0.08845067 -0.25982982, -0.12107328 0.10080077 -0.23512566, -0.11742958 0.1070959 -0.22253408, -0.10952452 0.08839874 -0.25993359, -0.12310228 0.10272506 -0.2312768, -0.12118894 0.10074869 -0.23523013, -0.1115537 0.090322986 -0.25608462, -0.10964021 0.088346615 -0.26003793, -0.11172575 0.09034577 -0.2560389, -0.12327448 0.10274786 -0.23123117, -0.13746695 0.1159371 -0.2048485, -0.13746293 0.11590183 -0.20491935, -0.13745281 0.11597209 -0.20477864, -0.13742141 0.11600469 -0.20471355, -0.11188781 0.09038417 -0.25596216, -0.10482967 0.093405202 -0.24991933, -0.10456404 0.093372166 -0.24998526, -0.12941456 0.11325583 -0.21021225, -0.12965727 0.11281547 -0.21109287, -0.13737436 0.11603333 -0.20465648, -0.13731372 0.11605626 -0.20461039, -0.13724315 0.1160726 -0.20457773, -0.13716602 0.11608142 -0.20456024, -0.13712054 0.1160828 -0.2045573, -0.11202934 0.090436235 -0.25585812, -0.12965727 0.112362 -0.21200018, -0.12343648 0.10278635 -0.23115441, -0.11214256 0.090498477 -0.25573367, -0.12357798 0.10283832 -0.23105034, -0.12369141 0.10290055 -0.23092571, -0.11637843 0.10580723 -0.22511157, -0.11665061 0.10581823 -0.22508937, -0.11611271 0.10577421 -0.22517753, -0.084215313 0.076290905 -0.28415298, -0.083906561 0.076034129 -0.28466666, -0.08412683 0.076270729 -0.28419346, -0.10849476 0.087215111 -0.2623013, -0.10605809 0.085392118 -0.26594788, -0.10626081 0.085381866 -0.2659682, -0.10645965 0.085350096 -0.26603162, -0.11454239 0.10399516 -0.22873601, -0.12827072 0.11118053 -0.21436325, -0.12743586 0.1109229 -0.2148786, -0.089882016 0.077816114 -0.28110206, -0.11087617 0.099617139 -0.23749331, -0.1176067 0.097794175 -0.24113993, -0.10876814 0.097794205 -0.2411399, -0.1200434 0.099617168 -0.23749331, -0.1289432 0.11152002 -0.21368413, -0.12936801 0.11018488 -0.21635474, -0.10663739 0.08529821 -0.26613575, -0.11780944 0.097783878 -0.24116048, -0.12956575 0.11015224 -0.2164201, -0.10866636 0.087222382 -0.2622866, -0.10675308 0.085246086 -0.26623982, -0.11800832 0.097752094 -0.24122398, -0.12941468 0.11192164 -0.21288101, -0.12973389 0.11010262 -0.21651928, -0.10883859 0.087245256 -0.26224095, -0.090393782 0.07790266 -0.28092909, -0.090666056 0.077913627 -0.28090706, -0.090128183 0.077869639 -0.28099525, -0.11818609 0.097700208 -0.24132778, -0.10900056 0.087283552 -0.26216406, -0.12987655 0.11003527 -0.21665411, -0.12021509 0.099624529 -0.23747873, -0.11830181 0.097648144 -0.241432, -0.10914209 0.087335587 -0.26205999, -0.1134913 0.10270664 -0.23131345, -0.11322558 0.10267374 -0.23137961, -0.10925546 0.087397844 -0.26193547, -0.1299814 0.10995434 -0.21681574, -0.12038729 0.099647313 -0.237433, -0.1300405 0.10986683 -0.21699108, -0.10194254 0.090304717 -0.25612134, -0.10167688 0.090271637 -0.25618741, -0.10143068 0.090218246 -0.25629431, -0.13005406 0.10977957 -0.21716575, -0.13003212 0.10970625 -0.21731247, -0.12054923 0.099685684 -0.23735619, -0.12069073 0.099737763 -0.23725213, -0.10560745 0.084114581 -0.26850325, -0.10317093 0.082291603 -0.27214962, -0.12080419 0.09980002 -0.23712777, -0.10337377 0.082281321 -0.27217036, -0.10357249 0.082249582 -0.27223361, -0.10375014 0.082197696 -0.27233756, -0.10386586 0.082145482 -0.27244174, -0.10577932 0.084121943 -0.26848853, -0.10595146 0.084144771 -0.26844275, -0.10611334 0.084183097 -0.2683661, -0.10625482 0.084235162 -0.26826203, -0.1264711 0.10708547 -0.22255464, -0.10636824 0.084297389 -0.26813751, -0.099652946 0.088474318 -0.25978237, -0.11471963 0.094693795 -0.24734193, -0.11715621 0.096516728 -0.24369545, -0.12666991 0.10705373 -0.22261824, -0.11492249 0.094683409 -0.24736254, -0.11512116 0.094651684 -0.24742591, -0.12684759 0.10700192 -0.22272196, -0.12887666 0.10892615 -0.21887292, -0.1269632 0.1069497 -0.22282621, -0.11529899 0.094599813 -0.24752976, -0.10068187 0.081013992 -0.27470514, -0.10028371 0.079191044 -0.27835169, -0.098984301 0.079190984 -0.27835172, -0.10049626 0.079179794 -0.27837431, -0.12904888 0.1089488 -0.21882738, -0.11541468 0.094547719 -0.24763416, -0.10272029 0.081014052 -0.27470514, -0.10069415 0.0791471 -0.27843976, -0.11732805 0.096523941 -0.24368076, -0.11060399 0.099606171 -0.23751542, -0.11033839 0.09957315 -0.23758158, -0.10086215 0.079097524 -0.27853888, -0.1292108 0.10898724 -0.21875061, -0.10100505 0.079030067 -0.27867365, -0.11750013 0.096546769 -0.2436351, -0.099055409 0.087204099 -0.2623232, -0.098789752 0.087171063 -0.2623893, -0.12935242 0.1090394 -0.21864636, -0.10289204 0.081021324 -0.27469048, -0.10110974 0.078949168 -0.27883524, -0.12946564 0.1091015 -0.21852188, -0.10322618 0.081082523 -0.27456808, -0.10306418 0.081044212 -0.27464485, -0.10116875 0.078861609 -0.27901047, -0.11766201 0.096585155 -0.24355833, -0.10336781 0.081134573 -0.27446389, -0.11780378 0.096637219 -0.24345429, -0.10118234 0.078774229 -0.27918521, -0.10348102 0.08119683 -0.27433929, -0.11791703 0.096699446 -0.24332978, -0.10116041 0.07870093 -0.2793321, -0.099833161 0.077913508 -0.28090703, -0.10067493 0.07816416 -0.28040534, -0.10059389 0.078096181 -0.2805413, -0.10048053 0.078034192 -0.28066587, -0.10033906 0.077982098 -0.28076994, -0.10017699 0.077943683 -0.28084677, -0.10000491 0.077920824 -0.28089237, -0.10111359 0.07863532 -0.27946305, -0.103562 0.081264868 -0.2742033, -0.12338114 0.10399511 -0.22873603, -0.093435675 0.082218096 -0.27229643, -0.095912665 0.08522965 -0.26627284, -0.091317594 0.083992898 -0.26874667, -0.092876881 0.085592389 -0.26554716, -0.092788309 0.085572183 -0.26558757, -0.096322954 0.08531867 -0.26609465, -0.098799795 0.088330209 -0.2600708, -0.094204783 0.087093413 -0.26254481, -0.09576413 0.088692933 -0.25934517, -0.095675558 0.088672653 -0.25938562, -0.099210083 0.088419303 -0.25989258, -0.097092092 0.090193942 -0.25634289, -0.098562717 0.091773272 -0.25318366, -0.08701399 0.079371229 -0.27799147, -0.089524627 0.078863487 -0.27900696, -0.085543394 0.077791989 -0.28115064, -0.087102443 0.079391345 -0.277951, -0.090990812 0.080437854 -0.2758576, -0.090447068 0.077983379 -0.27860105, -0.10429764 -0.032980174 -0.21443574, -0.099330485 -0.032979846 -0.2177711, -0.099027872 -0.033174455 -0.21787824, -0.08738929 0.07928063 -0.27705005, -0.092659056 0.079476342 -0.27360854, -0.090732932 0.0801806 -0.27524987, -0.10135436 -0.032600507 -0.21235433, -0.10664839 -0.032600656 -0.20879921, -0.11266619 -0.03226684 -0.22449139, -0.11266938 -0.032290995 -0.22447743, -0.097342819 -0.032290921 -0.22447759, -0.096518159 -0.033044875 -0.22404151, -0.10406587 -0.0097109973 -0.23753454, -0.10382316 -0.0088585317 -0.23802747, -0.1033518 -0.0080810487 -0.23847716, -0.091171235 0.064225554 -0.28028888, -0.10089624 -0.0066138357 -0.23932552, -0.092119634 0.064537004 -0.28046882, -0.092954248 0.065035656 -0.28075719, -0.10184452 -0.0069250762 -0.23914556, -0.093626827 0.065692976 -0.28113732, -0.10267922 -0.007423833 -0.23885706, -0.091171384 0.071297973 -0.28437841, -0.092119664 0.070986629 -0.28419846, -0.092954367 0.070487827 -0.28391004, -0.093626827 0.069830745 -0.28353012, -0.094098181 0.069053382 -0.28308052, -0.094340891 0.068200797 -0.28258747, -0.094340712 0.067322686 -0.28207985, -0.094098181 0.066470459 -0.28158677, -0.10089621 -0.013686121 -0.2352358, -0.10406584 -0.010588899 -0.23702675, -0.10382316 -0.011441454 -0.23653388, -0.10335177 -0.012218922 -0.23608436, -0.10267919 -0.012876064 -0.23570438, -0.10184455 -0.013374895 -0.23541586, -0.11926883 0.11541006 -0.20713444, -0.11283743 0.1085033 -0.22094971, -0.11916131 0.11650267 -0.20769583, -0.081678867 0.074573308 -0.28775334, -0.082610399 0.077251017 -0.28621066, -0.082321018 0.076849222 -0.28680766, -0.082077354 0.076337606 -0.2872628, -0.081893235 0.075781643 -0.28756034, -0.081757694 0.075175941 -0.28772557, -0.084338516 0.052150548 -0.27512693, -0.084407836 0.051594958 -0.27480558, -0.090141118 0.0056633353 -0.24824531, -0.090210468 0.0051075816 -0.24792399, -0.13036332 -0.034585774 -0.13902418, -0.095058829 -0.033735052 -0.22546318, -0.13054833 -0.033388913 -0.13889997, -0.094157934 -0.034580648 -0.2274314, -0.094052434 -0.033734873 -0.22792038, -0.11337388 0.1071853 -0.22123273, -0.13085705 -0.032880649 -0.14023855, -0.11849588 0.10856383 -0.21847489, -0.13615105 -0.032880858 -0.13668352, -0.084502101 0.0761801 -0.28325212, -0.098080158 -0.032599971 -0.22034937, -0.089624107 0.077558786 -0.28049445, -0.10337427 -0.032600254 -0.21679442, -0.11048678 0.10408485 -0.22743456, -0.12754831 -0.032604247 -0.14839335, -0.11560878 0.10546358 -0.22467685, -0.13284236 -0.032604575 -0.14483826, -0.12879872 -0.032984123 -0.14581504, -0.13376573 -0.032984242 -0.14247945, -0.1284959 -0.033178747 -0.14592211, -0.10759956 0.10098426 -0.23363644, -0.12427393 -0.032603741 -0.15638857, -0.11272159 0.10236295 -0.23087883, -0.12956807 -0.032603994 -0.15283334, -0.12552443 -0.032983631 -0.15381022, -0.13049155 -0.032984018 -0.15047471, -0.12522179 -0.033178151 -0.15391724, -0.10471243 0.09788388 -0.23983844, -0.12099987 -0.032603309 -0.16438362, -0.10983443 0.099262461 -0.23708069, -0.1262939 -0.032603502 -0.16082846, -0.1222502 -0.032983214 -0.16180529, -0.12721732 -0.032983378 -0.15846992, -0.12194759 -0.033177719 -0.16191235, -0.10182515 0.094783247 -0.24604036, -0.11772555 -0.032602862 -0.17237866, -0.10694721 0.096162036 -0.24328277, -0.12301964 -0.032603055 -0.16882361, -0.11897588 -0.032982692 -0.16980043, -0.123943 -0.03298296 -0.16646504, -0.11867332 -0.033177242 -0.16990748, -0.098938107 0.091682732 -0.25224233, -0.11445132 -0.032602295 -0.18037388, -0.10406008 0.093061373 -0.24948457, -0.1197454 -0.032602623 -0.17681873, -0.11570162 -0.032982156 -0.1777955, -0.12066874 -0.032982469 -0.17446022, -0.11539903 -0.033176854 -0.1779027, -0.096050978 0.088582173 -0.25844425, -0.11117709 -0.032601908 -0.18836886, -0.10117283 0.089960814 -0.2556867, -0.11647111 -0.032602057 -0.18481377, -0.11242735 -0.032981828 -0.18579066, -0.11739463 -0.032981917 -0.18245533, -0.11212474 -0.033176348 -0.18589786, -0.093163788 0.085481703 -0.26464623, -0.10790294 -0.032601401 -0.19636402, -0.098285645 0.086860314 -0.26188856, -0.11319685 -0.032601669 -0.19280896, -0.10915321 -0.032981217 -0.19378595, -0.11412027 -0.03298156 -0.19045034, -0.10885054 -0.033175856 -0.19389282, -0.09027651 0.08238107 -0.27084833, -0.10462859 -0.032600895 -0.20435908, -0.095398486 0.083759755 -0.26809049, -0.10992256 -0.032601163 -0.20080411, -0.10587892 -0.032980934 -0.20178109, -0.11084613 -0.032981083 -0.19844553, -0.10557631 -0.033175498 -0.20188807, -0.10260475 -0.032980427 -0.2097761, -0.10757187 -0.032980666 -0.2064406, -0.10230199 -0.033174902 -0.20988323, -0.10015324 0.075839579 -0.28497964, -0.083760709 0.075845957 -0.28497124, -0.099972159 0.075590879 -0.28525168, -0.083620399 0.075597405 -0.28524601, -0.099811226 0.07529664 -0.2854737, -0.083493382 0.07529676 -0.28547353, -0.099675804 0.07496658 -0.28563762, -0.083387107 0.074958682 -0.28564072, -0.099570543 0.074612111 -0.28573841, -0.083306402 0.074601889 -0.28574026, -0.084201664 0.076300383 -0.28413236, -0.084187925 0.076308697 -0.28411126, -0.089824528 0.0778476 -0.28101093, -0.084174424 0.076315701 -0.28408951, -0.084293962 0.076382518 -0.28381598, -0.089769989 0.077854961 -0.28091323, -0.089720845 0.077837691 -0.28081357, -0.084384859 0.076380432 -0.28359342, -0.089680076 0.077796921 -0.28071737, -0.084439874 0.076341867 -0.28344834, -0.08964932 0.077734575 -0.28062928, -0.08447364 0.076288491 -0.2833513, -0.089630365 0.077653855 -0.28055358, -0.084491372 0.076237321 -0.28329396, -0.08548367 0.077719077 -0.28127635, -0.089584231 0.07880722 -0.27908957, -0.085426003 0.077630058 -0.28139287, -0.089640766 0.0787296 -0.27915549, -0.085373998 0.077528685 -0.28149217, -0.089690685 0.078635082 -0.27920139, -0.085330814 0.077420592 -0.28156793, -0.089731812 0.078528747 -0.2792244, -0.085298836 0.077312276 -0.28161654, -0.08837086 0.080819637 -0.27507448, -0.093084991 0.082072869 -0.27255717, -0.088313133 0.080730632 -0.27519098, -0.093141526 0.081995174 -0.27262312, -0.088261127 0.080629185 -0.2752904, -0.093191534 0.081900761 -0.27266884, -0.088218004 0.080521151 -0.27536613, -0.093232572 0.081794396 -0.27269211, -0.088186026 0.080412701 -0.27541459, -0.087088853 0.079401001 -0.27793038, -0.087075144 0.079409108 -0.27790904, -0.090933353 0.080469415 -0.27576643, -0.087061644 0.079416141 -0.27788746, -0.087181151 0.079483166 -0.27761406, -0.090878695 0.080476761 -0.27566868, -0.090829641 0.080459639 -0.27556926, -0.087271959 0.079480991 -0.27739164, -0.090788871 0.08041878 -0.27547279, -0.087327152 0.079442367 -0.27724636, -0.090758175 0.080356479 -0.27538478, -0.087360829 0.079389021 -0.27714941, -0.09073931 0.080275819 -0.27530923, -0.087378621 0.07933782 -0.2770921, -0.096698463 -0.033284575 -0.22366919, -0.096881777 -0.033182904 -0.2235519, -0.096649021 -0.033329442 -0.22364458, -0.096939087 -0.033064619 -0.2237964, -0.096869141 -0.033271834 -0.22329399, -0.096901298 -0.033329442 -0.22302851, -0.11238378 -0.033229768 -0.1855536, -0.11237457 -0.03324993 -0.18551022, -0.11222538 -0.033331543 -0.18560965, -0.11237362 -0.033266589 -0.18545893, -0.11239016 -0.033284858 -0.18535888, -0.11243409 -0.033291996 -0.18522917, -0.11399892 -0.033331856 -0.1812788, -0.11404046 -0.033292145 -0.18130668, -0.10906321 -0.033259168 -0.1935651, -0.1090495 -0.033287913 -0.193505, -0.10895121 -0.033331215 -0.19360487, -0.10904598 -0.033311978 -0.19343546, -0.10905266 -0.033331215 -0.19335707, -0.10578889 -0.033258691 -0.20156029, -0.10577524 -0.033287421 -0.20150009, -0.10567686 -0.033330783 -0.20159996, -0.10577169 -0.03331165 -0.20143044, -0.10577834 -0.033330664 -0.20135212, -0.10251462 -0.033258185 -0.20955554, -0.10250103 -0.033287033 -0.20949525, -0.10240272 -0.033330262 -0.20959495, -0.10249737 -0.033311158 -0.20942573, -0.10250407 -0.033330247 -0.20934719, -0.099240422 -0.033257797 -0.21755055, -0.099226803 -0.033286512 -0.21749033, -0.099128395 -0.03332971 -0.21758997, -0.099223226 -0.033310592 -0.21742071, -0.099229813 -0.033329815 -0.21734239, -0.11561164 -0.033260077 -0.17757483, -0.11559802 -0.033288881 -0.17751482, -0.11549968 -0.033332154 -0.17761454, -0.11559436 -0.033312961 -0.17744508, -0.11560118 -0.033332109 -0.17736678, -0.11888593 -0.033260569 -0.16957971, -0.11887226 -0.033289388 -0.16951966, -0.11877388 -0.033332571 -0.16961929, -0.11886874 -0.033313408 -0.16945016, -0.11887535 -0.033332661 -0.16937172, -0.12216011 -0.033261061 -0.1615846, -0.12214643 -0.03328982 -0.16152449, -0.12204808 -0.033333033 -0.16162421, -0.122143 -0.033313975 -0.16145495, -0.12214962 -0.033333063 -0.16137658, -0.12543431 -0.033261493 -0.15358955, -0.12542084 -0.033290237 -0.15352948, -0.12532237 -0.03333351 -0.15362926, -0.12541714 -0.033314437 -0.15345986, -0.12542379 -0.033333585 -0.1533812, -0.12875491 -0.033232123 -0.14557792, -0.12874576 -0.033252418 -0.14553462, -0.12859657 -0.033334002 -0.14563408, -0.12874475 -0.033268929 -0.14548306, -0.12876132 -0.033287287 -0.14538334, -0.12880531 -0.03329432 -0.14525358, -0.12073943 -0.033293083 -0.16511559, -0.12655169 -0.033293471 -0.16121253, -0.12077323 -0.033283353 -0.16497384, -0.12648407 -0.033278421 -0.16111171, -0.12079683 -0.033250451 -0.16483317, -0.12642065 -0.033234552 -0.16101706, -0.12080333 -0.033223286 -0.16476554, -0.12080416 -0.033187404 -0.16470164, -0.12636459 -0.033164307 -0.16093412, -0.12085977 -0.033123747 -0.16458273, -0.12632027 -0.03307189 -0.16086775, -0.12091082 -0.033045158 -0.1644803, -0.12094492 -0.032974273 -0.16441621, -0.12628961 -0.032962725 -0.16082188, -0.1209659 -0.032917723 -0.1643801, -0.1209828 -0.032859311 -0.16435501, -0.12627435 -0.032843634 -0.16079953, -0.12099484 -0.032800421 -0.16434178, -0.12100258 -0.032735929 -0.16434059, -0.1262759 -0.03272137 -0.16080172, -0.12100446 -0.032667145 -0.16435465, -0.12200975 -0.03332147 -0.16172118, -0.12220111 -0.03318727 -0.16167186, -0.12198403 -0.033294916 -0.16179131, -0.1222319 -0.033092186 -0.16174743, -0.12196532 -0.033257008 -0.16184722, -0.12195483 -0.033220276 -0.16188309, -0.10569391 0.099422723 -0.23786272, -0.11040816 0.10067581 -0.23534551, -0.10563618 0.099333763 -0.2379791, -0.11046448 0.10059832 -0.23541138, -0.10558423 0.099232331 -0.23807856, -0.11051461 0.10050386 -0.23545735, -0.10554108 0.099124357 -0.23815417, -0.11055574 0.10039745 -0.23548037, -0.10550898 0.099015877 -0.23820281, -0.10441193 0.098004133 -0.24071874, -0.10439825 0.098012388 -0.24069758, -0.11003479 0.099551156 -0.23759726, -0.10438472 0.098019183 -0.24067567, -0.1045042 0.098086268 -0.24040224, -0.10998008 0.099558577 -0.23749954, -0.10993114 0.099541381 -0.23739994, -0.10459504 0.098084122 -0.24017979, -0.10989028 0.099500641 -0.23730367, -0.10465023 0.098045498 -0.2400348, -0.10985956 0.099438205 -0.23721564, -0.10468394 0.097992122 -0.23993774, -0.10984048 0.099357501 -0.23713997, -0.10470173 0.097940952 -0.23988046, -0.12728775 -0.033294126 -0.14912531, -0.13310015 -0.033294261 -0.14522235, -0.12732163 -0.033284262 -0.14898366, -0.13303244 -0.033279374 -0.14512157, -0.12734511 -0.03325139 -0.14884314, -0.13296902 -0.033235371 -0.14502697, -0.12735167 -0.03322418 -0.14877528, -0.12735263 -0.033188313 -0.14871152, -0.13291326 -0.033165202 -0.1449438, -0.12740836 -0.03312473 -0.14859244, -0.1328688 -0.033072859 -0.14487751, -0.12745914 -0.033046037 -0.14849015, -0.12749323 -0.032975227 -0.14842601, -0.13283798 -0.032963678 -0.14483169, -0.12751451 -0.032918543 -0.14838989, -0.12753126 -0.032860175 -0.14836496, -0.13282284 -0.032844633 -0.14480944, -0.12754321 -0.03280139 -0.14835165, -0.12755111 -0.032736868 -0.14835019, -0.13282436 -0.032722458 -0.14481142, -0.12755284 -0.032668129 -0.14836448, -0.12878188 -0.033167303 -0.14567022, -0.12855816 -0.033322439 -0.14573088, -0.12853238 -0.03329581 -0.14580093, -0.12879682 -0.03308247 -0.14575127, -0.12851369 -0.033257931 -0.14585675, -0.12850317 -0.03322129 -0.14589277, -0.12401363 -0.033293664 -0.15712051, -0.12982607 -0.033293873 -0.15321739, -0.12404737 -0.033283815 -0.15697894, -0.12975839 -0.033278897 -0.15311664, -0.12407103 -0.033250913 -0.15683809, -0.12969482 -0.033234984 -0.15302201, -0.12407753 -0.033223808 -0.15677051, -0.12407836 -0.033187851 -0.15670654, -0.12963909 -0.03316471 -0.15293892, -0.12413403 -0.033124223 -0.15658772, -0.12959442 -0.033072248 -0.15287256, -0.12418482 -0.033045545 -0.1564852, -0.12421915 -0.03297478 -0.15642111, -0.12956372 -0.032963216 -0.15282683, -0.12424019 -0.032918096 -0.15638487, -0.12425703 -0.032859653 -0.1563601, -0.12954861 -0.032844022 -0.15280443, -0.12426889 -0.032800928 -0.15634668, -0.12427685 -0.03273648 -0.15634541, -0.12955007 -0.032721892 -0.15280664, -0.12427866 -0.032667786 -0.15635957, -0.12528399 -0.033321947 -0.15372618, -0.12547532 -0.033187658 -0.1536767, -0.12525818 -0.033295423 -0.15379615, -0.12550601 -0.033092633 -0.15375221, -0.12523958 -0.033257514 -0.15385194, -0.125229 -0.033220813 -0.15388784, -0.11746496 -0.033292726 -0.17311072, -0.12327754 -0.033292875 -0.1692076, -0.11749887 -0.033282891 -0.17296886, -0.12320983 -0.033277988 -0.16910701, -0.11752254 -0.033249989 -0.1728285, -0.12314633 -0.033234045 -0.16901234, -0.11752898 -0.033222869 -0.17276073, -0.1175299 -0.033186823 -0.17269672, -0.1230906 -0.033163741 -0.1689291, -0.11758557 -0.033123359 -0.17257795, -0.12304607 -0.03307128 -0.1688628, -0.11763638 -0.033044651 -0.17247546, -0.1176706 -0.032973841 -0.17241132, -0.12301537 -0.032962278 -0.16881704, -0.11769173 -0.032917246 -0.17237523, -0.11770856 -0.032858863 -0.17235035, -0.1230002 -0.032843098 -0.1687946, -0.11772063 -0.032799989 -0.17233707, -0.11772829 -0.032735541 -0.17233562, -0.12300172 -0.032720923 -0.16879688, -0.1177302 -0.032666817 -0.17234987, -0.11873552 -0.033320978 -0.16971636, -0.11892691 -0.033186823 -0.1696669, -0.11870977 -0.033294395 -0.16978645, -0.11895767 -0.033091798 -0.16974247, -0.11869109 -0.033256456 -0.16984245, -0.11868057 -0.033219829 -0.16987807, -0.11404434 -0.033312783 -0.18117329, -0.11402139 -0.033327028 -0.18122503, -0.11406311 -0.033292145 -0.1812181, -0.1140573 -0.033292115 -0.18125264, -0.12000322 -0.033292383 -0.17720284, -0.1199356 -0.033277512 -0.17710213, -0.11414397 -0.033265412 -0.18094282, -0.1141957 -0.033235833 -0.18082473, -0.11987194 -0.033233523 -0.17700736, -0.11427402 -0.033167541 -0.18065207, -0.11981621 -0.033163264 -0.17692429, -0.11432859 -0.033098802 -0.18053743, -0.11977172 -0.033070832 -0.17685808, -0.11437127 -0.033027261 -0.18045314, -0.11439818 -0.032969043 -0.18040332, -0.11974099 -0.03296183 -0.17681226, -0.11442021 -0.032908291 -0.18036605, -0.11443692 -0.032846868 -0.18034194, -0.11972582 -0.032842666 -0.17678978, -0.11444846 -0.032786086 -0.18033075, -0.11445472 -0.032727212 -0.18033154, -0.11972728 -0.032720521 -0.17679197, -0.114456 -0.032665357 -0.18034539, -0.11546126 -0.033320561 -0.17771131, -0.11565259 -0.033186242 -0.17766216, -0.11543551 -0.033293918 -0.17778158, -0.11568344 -0.033091173 -0.17773762, -0.11541677 -0.033255994 -0.17783742, -0.11540627 -0.033219397 -0.17787336, -0.11091655 -0.033291712 -0.18910104, -0.11672905 -0.033291891 -0.18519789, -0.11095041 -0.033281937 -0.18895918, -0.11666146 -0.033277169 -0.18509728, -0.11097398 -0.033248886 -0.18881866, -0.11659771 -0.033233106 -0.18500255, -0.11098054 -0.033221826 -0.18875095, -0.11098143 -0.033185944 -0.188687, -0.11654204 -0.033162892 -0.18491964, -0.11103714 -0.033122331 -0.1885681, -0.11649752 -0.033070445 -0.18485312, -0.11108792 -0.033043638 -0.18846574, -0.11112207 -0.032972828 -0.18840164, -0.11646676 -0.032961324 -0.18480736, -0.11114329 -0.032916203 -0.18836552, -0.11116004 -0.03285785 -0.18834051, -0.11645165 -0.032842189 -0.18478496, -0.11117214 -0.03279902 -0.18832713, -0.11117974 -0.032734543 -0.18832587, -0.1164532 -0.032719925 -0.18478709, -0.11118183 -0.03266567 -0.18834011, -0.11241069 -0.033164889 -0.18564577, -0.11218697 -0.033320025 -0.18570656, -0.11216125 -0.033293471 -0.18577668, -0.11242571 -0.033080056 -0.18572694, -0.11214262 -0.033255577 -0.1858326, -0.11213198 -0.03321889 -0.18586846, -0.10891274 -0.033319578 -0.19370171, -0.10910407 -0.033185348 -0.19365212, -0.1088869 -0.033293024 -0.19377172, -0.10913476 -0.033090279 -0.19372788, -0.1088683 -0.033255115 -0.19382775, -0.10885778 -0.033218384 -0.19386335, -0.10764235 -0.033291236 -0.19709608, -0.11345476 -0.033291519 -0.193193, -0.10766968 -0.033284679 -0.19698253, -0.11338717 -0.033276618 -0.19309227, -0.10768667 -0.033266917 -0.19688353, -0.1076948 -0.033236474 -0.196788, -0.11332363 -0.033232629 -0.19299762, -0.1076912 -0.033200264 -0.19671689, -0.10772869 -0.033163354 -0.19663593, -0.11326781 -0.03316243 -0.19291458, -0.10776478 -0.03311947 -0.1965595, -0.11322331 -0.033069968 -0.19284825, -0.10781196 -0.033046365 -0.19646417, -0.10784778 -0.032972589 -0.19639698, -0.1131925 -0.032960951 -0.1928025, -0.1078698 -0.032913595 -0.19635935, -0.10788691 -0.032852799 -0.19633417, -0.11317754 -0.032841668 -0.19277993, -0.10789889 -0.032791778 -0.19632149, -0.10790581 -0.032731563 -0.1963212, -0.11317894 -0.032719582 -0.19278227, -0.10790753 -0.032667547 -0.19633453, -0.1056385 -0.033319131 -0.20169687, -0.10582983 -0.033184841 -0.20164743, -0.10561264 -0.033292577 -0.20176691, -0.10586071 -0.033089861 -0.20172298, -0.10559413 -0.033254698 -0.20182282, -0.10558358 -0.033218056 -0.2018586, -0.10436812 -0.033290774 -0.20509122, -0.11018044 -0.033290997 -0.20118827, -0.10439542 -0.033284217 -0.2049775, -0.11011291 -0.033276096 -0.20108745, -0.10441253 -0.0332665 -0.20487875, -0.10442042 -0.033235908 -0.20478298, -0.11004934 -0.033232197 -0.20099294, -0.10441706 -0.033199862 -0.20471206, -0.10445434 -0.033162847 -0.204631, -0.10999358 -0.033161893 -0.20090973, -0.10449061 -0.033119038 -0.20455474, -0.10994896 -0.033069417 -0.20084339, -0.10453776 -0.033045918 -0.20445938, -0.10457367 -0.032972172 -0.2043919, -0.10991836 -0.032960311 -0.20079753, -0.10459542 -0.032913208 -0.20435466, -0.10461271 -0.032852411 -0.20432936, -0.10990316 -0.03284125 -0.20077503, -0.10462472 -0.032791331 -0.20431665, -0.10463154 -0.032731175 -0.20431639, -0.10990465 -0.032719031 -0.20077738, -0.10463333 -0.032667175 -0.20432964, -0.096617937 -0.033273146 -0.22380188, -0.096592396 -0.033293784 -0.2237923, -0.09656918 -0.033253476 -0.22385973, -0.09666124 -0.033283621 -0.22373785, -0.096619189 -0.033319935 -0.22371989, -0.097132772 -0.032759175 -0.2241326, -0.096548438 -0.03319709 -0.22392598, -0.097240239 -0.032535136 -0.22431748, -0.096531242 -0.033126786 -0.22398743, -0.10109389 -0.033290267 -0.21308632, -0.10690627 -0.03329061 -0.20918322, -0.10112774 -0.033280477 -0.21294457, -0.10683861 -0.033275649 -0.20908251, -0.10115138 -0.03324762 -0.21280392, -0.10677496 -0.033231646 -0.20898794, -0.10115781 -0.033220544 -0.21273628, -0.10115868 -0.033184558 -0.21267243, -0.10671932 -0.033161417 -0.20890483, -0.10121447 -0.033120915 -0.21255356, -0.10667476 -0.03306894 -0.20883849, -0.10126525 -0.033042312 -0.21245106, -0.10129938 -0.032971561 -0.21238701, -0.10664403 -0.032959953 -0.20879284, -0.10132051 -0.032914922 -0.21235082, -0.10133722 -0.032856494 -0.21232586, -0.10662892 -0.032840833 -0.20877019, -0.10134929 -0.032797694 -0.21231265, -0.10135716 -0.032733113 -0.21231119, -0.10663044 -0.032718599 -0.20877247, -0.10135898 -0.032664448 -0.21232553, -0.10236427 -0.033318609 -0.2096919, -0.10255566 -0.033184424 -0.20964265, -0.10233849 -0.033292085 -0.2097619, -0.10258639 -0.033089325 -0.20971793, -0.10231984 -0.033254132 -0.20981792, -0.10230929 -0.03321746 -0.20985381, -0.09908998 -0.033318117 -0.21768704, -0.09928143 -0.033183768 -0.21763781, -0.099064261 -0.033291563 -0.21775714, -0.099312216 -0.033088908 -0.21771312, -0.099045664 -0.033253774 -0.21781301, -0.099035114 -0.033216998 -0.21784878, -0.097819746 -0.03328988 -0.2210813, -0.10363212 -0.033290088 -0.21717848, -0.097846895 -0.033283159 -0.22096795, -0.1035645 -0.033275157 -0.21707775, -0.097864032 -0.033265516 -0.22086886, -0.0978719 -0.033234999 -0.22077328, -0.1035009 -0.033231243 -0.21698299, -0.097868562 -0.033198878 -0.22070235, -0.097905934 -0.033161953 -0.2206212, -0.10344511 -0.033161014 -0.21690013, -0.097941995 -0.033118054 -0.22054496, -0.10340056 -0.033068433 -0.21683362, -0.097989231 -0.033044875 -0.22044952, -0.098025143 -0.032971174 -0.22038223, -0.10336983 -0.032959551 -0.21678789, -0.098047078 -0.032912225 -0.22034483, -0.098064125 -0.032851443 -0.22031957, -0.10335472 -0.032840267 -0.21676534, -0.098076284 -0.032790288 -0.22030681, -0.098083049 -0.032730207 -0.22030652, -0.10335621 -0.032718077 -0.2167677, -0.098084867 -0.032666191 -0.22031981, -0.13630572 -0.033294916 -0.136914, -0.13626513 -0.033285797 -0.13685368, -0.13067105 -0.03327924 -0.14058344, -0.13070217 -0.033261731 -0.14051211, -0.13622701 -0.033259496 -0.13679686, -0.13074949 -0.033220947 -0.14040785, -0.13619354 -0.033217296 -0.13674691, -0.13078266 -0.033179626 -0.14033827, -0.13616684 -0.033161879 -0.13670711, -0.13080844 -0.033136621 -0.14028716, -0.13082471 -0.033101618 -0.14025687, -0.13614839 -0.033096418 -0.13667956, -0.13083804 -0.033065021 -0.14023446, -0.13084823 -0.033027992 -0.14021966, -0.13613945 -0.033024892 -0.13666609, -0.13085526 -0.032991394 -0.1402128, -0.13085905 -0.032955885 -0.1402133, -0.13614029 -0.032951578 -0.13666752, -0.13085964 -0.032918662 -0.14022137, -0.12720808 -0.033304855 -0.14912257, -0.12724766 -0.033296838 -0.14912409, -0.12717012 -0.033318132 -0.14912136, -0.12728307 -0.033294111 -0.14918895, -0.12714437 -0.033313721 -0.1493084, -0.12709904 -0.033337533 -0.14928971, -0.12727293 -0.033294126 -0.14925155, -0.12719288 -0.033299044 -0.14932817, -0.12724313 -0.033293992 -0.14934893, -0.12554556 -0.033337414 -0.15308301, -0.12559095 -0.033313483 -0.15310152, -0.12563953 -0.033298761 -0.15312155, -0.12568974 -0.033293843 -0.15314208, -0.12560573 -0.033289045 -0.15328141, -0.12552857 -0.033231661 -0.15354094, -0.12552652 -0.033247024 -0.153506, -0.12549528 -0.033237711 -0.15355563, -0.1254482 -0.033317 -0.15338142, -0.12548235 -0.033298939 -0.15338261, -0.12543941 -0.03330034 -0.15345614, -0.12551823 -0.033285365 -0.15338501, -0.12555113 -0.03327474 -0.15340014, -0.12547013 -0.033284798 -0.15345216, -0.12544051 -0.033278793 -0.15352221, -0.12546381 -0.033247724 -0.15357184, -0.1255025 -0.033272833 -0.15344949, -0.12553206 -0.033260301 -0.15346485, -0.12546796 -0.033266202 -0.15351331, -0.12549686 -0.033256575 -0.15350553, -0.12393397 -0.033304304 -0.1571178, -0.12397337 -0.033296257 -0.15711917, -0.12389585 -0.033317745 -0.15711652, -0.12400898 -0.033293664 -0.15718405, -0.12387002 -0.033313289 -0.15730345, -0.12382475 -0.033337221 -0.15728489, -0.12399873 -0.033293664 -0.15724663, -0.1239185 -0.033298627 -0.15732336, -0.12396893 -0.03329362 -0.15734398, -0.12227124 -0.033336967 -0.16107811, -0.12231666 -0.033313021 -0.1610966, -0.12236515 -0.033298373 -0.16111647, -0.12241545 -0.033293366 -0.16113721, -0.12233153 -0.033288598 -0.16127644, -0.1222544 -0.033231258 -0.16153608, -0.12225226 -0.033246517 -0.16150127, -0.12222117 -0.033237323 -0.16155079, -0.12217405 -0.033316493 -0.16137658, -0.12220806 -0.033298463 -0.1613778, -0.12216511 -0.033299804 -0.16145121, -0.12224412 -0.033284932 -0.16138007, -0.12227681 -0.033274174 -0.16139506, -0.1221959 -0.033284277 -0.16144742, -0.1221664 -0.033278376 -0.16151716, -0.12218955 -0.033247337 -0.16156694, -0.12222829 -0.033272386 -0.16144465, -0.12225774 -0.033259764 -0.16145992, -0.12219384 -0.03326571 -0.16150843, -0.12222275 -0.033255994 -0.16150068, -0.12065977 -0.033303902 -0.16511294, -0.12069923 -0.033295855 -0.16511425, -0.12062177 -0.033317164 -0.16511166, -0.12073475 -0.033293098 -0.16517921, -0.12059587 -0.033312783 -0.16529867, -0.12055039 -0.033336759 -0.16527997, -0.12072462 -0.033293158 -0.16524197, -0.12064454 -0.03329809 -0.16531837, -0.12069476 -0.033293173 -0.16533914, -0.11899707 -0.033336475 -0.16907322, -0.1190424 -0.033312544 -0.16909173, -0.11909112 -0.033297852 -0.16911173, -0.11914137 -0.033292919 -0.16913225, -0.11905727 -0.033288196 -0.16927147, -0.1189802 -0.033230796 -0.16953123, -0.11897811 -0.033245996 -0.1694963, -0.11894694 -0.033236891 -0.16954578, -0.11889973 -0.033316046 -0.16937174, -0.11893389 -0.03329803 -0.16937286, -0.11889097 -0.033299282 -0.16944635, -0.1189698 -0.03328453 -0.16937527, -0.11900264 -0.033273801 -0.16939017, -0.1189217 -0.033283874 -0.16944239, -0.1188921 -0.033277899 -0.16951241, -0.11891535 -0.033246905 -0.16956212, -0.11895409 -0.033271939 -0.16943969, -0.1189836 -0.033259347 -0.16945505, -0.11891961 -0.033265218 -0.16950366, -0.11894855 -0.033255517 -0.16949581, -0.11738539 -0.03330341 -0.17310812, -0.11742485 -0.033295408 -0.17310941, -0.11734742 -0.033316746 -0.17310673, -0.1174604 -0.033292636 -0.17317423, -0.11732155 -0.033312276 -0.17329359, -0.11727607 -0.033336312 -0.17327513, -0.11745012 -0.033292726 -0.17323691, -0.11737016 -0.033297703 -0.17331359, -0.11742041 -0.033292711 -0.17333417, -0.11572281 -0.033336088 -0.17706832, -0.11576822 -0.033312067 -0.17708698, -0.11581668 -0.033297405 -0.17710695, -0.11586702 -0.033292413 -0.17712753, -0.11578313 -0.03328757 -0.17726675, -0.11570594 -0.033230171 -0.17752638, -0.11570388 -0.033245489 -0.17749146, -0.11567262 -0.033236355 -0.17754103, -0.11562556 -0.033315524 -0.17736694, -0.11565956 -0.033297509 -0.17736812, -0.11561668 -0.033298925 -0.17744148, -0.11569566 -0.033283994 -0.1773704, -0.11572829 -0.033273324 -0.17738542, -0.11564746 -0.033283278 -0.17743769, -0.11561778 -0.033277437 -0.17750755, -0.11564103 -0.033246383 -0.17755732, -0.1156798 -0.033271357 -0.17743483, -0.11570919 -0.033258855 -0.17745017, -0.11564529 -0.033264831 -0.1774987, -0.11567411 -0.03325507 -0.1774909, -0.11083698 -0.033302456 -0.18909834, -0.1108765 -0.033294454 -0.18909961, -0.11079901 -0.033315793 -0.18909711, -0.11091197 -0.033291727 -0.1891645, -0.11077309 -0.033311397 -0.18928395, -0.11072779 -0.033335358 -0.18926524, -0.1109018 -0.033291742 -0.18922719, -0.11082169 -0.033296689 -0.1893039, -0.11087209 -0.033291712 -0.18932444, -0.10917431 -0.033335105 -0.19305867, -0.10921979 -0.033311084 -0.19307706, -0.10926825 -0.033296481 -0.19309705, -0.10931858 -0.03329137 -0.19311769, -0.10923454 -0.033286735 -0.19325694, -0.10915738 -0.033229366 -0.19351655, -0.10915533 -0.03324461 -0.19348164, -0.10912412 -0.033235446 -0.19353122, -0.10907707 -0.033314496 -0.19335707, -0.1091111 -0.033296585 -0.19335826, -0.10906821 -0.033297896 -0.19343169, -0.10914698 -0.0332831 -0.19336054, -0.10917991 -0.0332724 -0.19337565, -0.10909894 -0.033282384 -0.19342789, -0.10906929 -0.033276573 -0.19349772, -0.10909256 -0.033245355 -0.19354756, -0.10913125 -0.033270478 -0.19342501, -0.10916084 -0.033257961 -0.19344027, -0.10909671 -0.033263937 -0.1934889, -0.10912558 -0.033254072 -0.19348106, -0.1076059 -0.033273742 -0.19690514, -0.10760215 -0.033293888 -0.19709486, -0.10763127 -0.033266708 -0.19688642, -0.10762087 -0.03328599 -0.19698271, -0.10752472 -0.033315346 -0.19709206, -0.10756272 -0.033302039 -0.19709341, -0.10763767 -0.033291265 -0.19715971, -0.10749894 -0.03331092 -0.19727905, -0.1074535 -0.033334866 -0.19726047, -0.10762742 -0.033291206 -0.19722223, -0.10754746 -0.033296257 -0.19729899, -0.10759777 -0.033291236 -0.19731948, -0.10590008 -0.033334643 -0.20105381, -0.10594535 -0.033310696 -0.20107228, -0.10599402 -0.033296019 -0.2010922, -0.10604426 -0.033291027 -0.20111281, -0.10596028 -0.033286244 -0.20125206, -0.10588321 -0.033228889 -0.20151168, -0.10588109 -0.033244133 -0.20147683, -0.10584992 -0.033235028 -0.20152646, -0.10580283 -0.033314183 -0.2013523, -0.10583699 -0.033296064 -0.20135334, -0.10579395 -0.033297464 -0.20142692, -0.10587284 -0.033282652 -0.20135573, -0.10590556 -0.033271939 -0.20137067, -0.10582471 -0.033281922 -0.20142294, -0.10579503 -0.033276081 -0.2014928, -0.10581833 -0.033245012 -0.20154262, -0.1058571 -0.033269972 -0.20142014, -0.10588661 -0.033257529 -0.20143542, -0.1058225 -0.03326346 -0.20148399, -0.10585147 -0.033253685 -0.20147625, -0.1043317 -0.033273295 -0.20490032, -0.10432798 -0.03329356 -0.20508987, -0.104357 -0.033266187 -0.20488165, -0.10434663 -0.033285499 -0.20497791, -0.10425052 -0.033314809 -0.20508742, -0.10428852 -0.033301532 -0.20508854, -0.10436344 -0.033290744 -0.20515491, -0.10422459 -0.033310443 -0.20527421, -0.10417938 -0.033334374 -0.20525555, -0.10435322 -0.033290789 -0.20521727, -0.10427323 -0.033295646 -0.20529404, -0.10432354 -0.033290774 -0.20531453, -0.10262573 -0.033334121 -0.20904902, -0.1026713 -0.033310235 -0.20906745, -0.10271969 -0.033295542 -0.20908742, -0.10276997 -0.033290491 -0.20910791, -0.10268608 -0.033285752 -0.2092472, -0.10260892 -0.033228382 -0.2095069, -0.10260677 -0.033243641 -0.20947197, -0.10257554 -0.033234507 -0.20952149, -0.1025286 -0.033313632 -0.20934744, -0.10256264 -0.033295691 -0.20934854, -0.10251963 -0.033297047 -0.2094219, -0.10259849 -0.033282191 -0.20935084, -0.10263124 -0.033271462 -0.20936586, -0.10255042 -0.033281595 -0.20941795, -0.10252073 -0.033275634 -0.20948793, -0.10254395 -0.033244476 -0.20953777, -0.10258284 -0.033269644 -0.2094153, -0.10261226 -0.033256993 -0.20943061, -0.10254827 -0.033262998 -0.20947923, -0.10257712 -0.033253223 -0.20947139, -0.097783267 -0.033272371 -0.22089067, -0.097779483 -0.033292592 -0.22108005, -0.097808659 -0.033265337 -0.22087187, -0.097798258 -0.03328459 -0.22096816, -0.097701997 -0.033313856 -0.2210775, -0.097739995 -0.033300623 -0.22107881, -0.097815096 -0.03328976 -0.22114493, -0.097676188 -0.033309504 -0.22126451, -0.097630829 -0.033333525 -0.22124594, -0.097804815 -0.033289835 -0.22120768, -0.097724676 -0.033294871 -0.22128439, -0.097775161 -0.033289865 -0.22130498, -0.097040564 -0.033333346 -0.22268716, -0.097085863 -0.033309385 -0.22270575, -0.097134441 -0.033294663 -0.22272581, -0.097184807 -0.033289716 -0.22274631, -0.097127974 -0.033285156 -0.22288191, -0.096992493 -0.033042744 -0.22376633, -0.097051889 -0.033032939 -0.22374108, -0.096941918 -0.033313617 -0.22299105, -0.096987396 -0.033291146 -0.22299832, -0.097035736 -0.033276767 -0.22300725, -0.09704715 -0.033228412 -0.2232374, -0.097085148 -0.033271238 -0.22301766, -0.096949846 -0.033245727 -0.22323471, -0.096998036 -0.033232957 -0.22323503, -0.096908629 -0.033181369 -0.22350116, -0.096954107 -0.033164099 -0.22348952, -0.097002417 -0.033154294 -0.22348037, -0.097113997 -0.033035561 -0.22372171, -0.097051889 -0.033152506 -0.22347397, -0.10101432 -0.033301011 -0.21308365, -0.10105363 -0.033292994 -0.21308506, -0.10097623 -0.033314303 -0.21308243, -0.10108915 -0.033290267 -0.2131498, -0.10095036 -0.033309907 -0.21326928, -0.10090506 -0.033333853 -0.21325076, -0.10107896 -0.033290252 -0.21321267, -0.10099891 -0.033295274 -0.21328916, -0.10104918 -0.033290237 -0.21330981, -0.099351645 -0.033333719 -0.21704401, -0.099396974 -0.033309788 -0.21706261, -0.099445522 -0.033295035 -0.21708243, -0.099495798 -0.033290014 -0.217103, -0.099411875 -0.03328523 -0.21724226, -0.099334747 -0.033227891 -0.21750189, -0.099332571 -0.033243135 -0.2174671, -0.099301398 -0.03323397 -0.21751653, -0.099254131 -0.03331311 -0.21734253, -0.099288493 -0.033295155 -0.21734355, -0.099245459 -0.03329657 -0.21741703, -0.099324375 -0.033281669 -0.21734595, -0.099357158 -0.033270836 -0.21736099, -0.099276215 -0.033280939 -0.2174132, -0.099246502 -0.033275083 -0.21748307, -0.099269748 -0.033243954 -0.21753304, -0.09930861 -0.033269003 -0.21741036, -0.099338055 -0.033256486 -0.21742576, -0.099274129 -0.033262432 -0.21747427, -0.099303007 -0.033252686 -0.21746649, -0.091257989 0.083920091 -0.2688725, -0.09597224 0.085173413 -0.26635519, -0.091200352 0.083831131 -0.26898915, -0.096028656 0.085095778 -0.26642114, -0.091148317 0.083729774 -0.26908827, -0.096078664 0.085001245 -0.26646698, -0.091105133 0.083621562 -0.2691642, -0.096119821 0.084894821 -0.26649007, -0.091073185 0.083513319 -0.2692126, -0.089976013 0.082501441 -0.27172846, -0.089962274 0.082509696 -0.27170718, -0.095598906 0.084048629 -0.26860702, -0.089948863 0.082516581 -0.27168554, -0.090068251 0.082583487 -0.27141201, -0.0955441 0.08405593 -0.26850927, -0.095495194 0.084038794 -0.26840985, -0.090159118 0.08258146 -0.27118957, -0.095454335 0.083998054 -0.26831347, -0.090214431 0.082542926 -0.27104449, -0.095423669 0.083935797 -0.26822525, -0.090248019 0.08248958 -0.27094758, -0.095404744 0.083854944 -0.26814973, -0.090265781 0.082438409 -0.27089012, -0.094145179 0.087020665 -0.26267052, -0.098859519 0.088273898 -0.26015314, -0.094087571 0.086931601 -0.26278704, -0.098915786 0.088196188 -0.26021916, -0.094035476 0.086830273 -0.26288635, -0.098965913 0.088101715 -0.26026493, -0.093992412 0.08672218 -0.26296216, -0.099006921 0.08799541 -0.26028812, -0.093960375 0.086613908 -0.26301056, -0.092863172 0.085601985 -0.26552659, -0.092849553 0.085610181 -0.26550525, -0.098486006 0.087149188 -0.26240513, -0.092836052 0.085617125 -0.2654835, -0.0929555 0.085684121 -0.26521015, -0.098431379 0.087156415 -0.26230729, -0.098382443 0.087139383 -0.26220781, -0.093046337 0.085681975 -0.26498759, -0.098341525 0.087098524 -0.26211157, -0.093101472 0.08564344 -0.26484239, -0.098310828 0.087036178 -0.26202342, -0.093135267 0.085590035 -0.26474553, -0.098291963 0.086955443 -0.26194781, -0.09315294 0.085538924 -0.26468813, -0.097032398 0.090121135 -0.25646871, -0.10174662 0.091374323 -0.25395134, -0.096974671 0.090032145 -0.25658509, -0.10180297 0.091296837 -0.25401714, -0.096922606 0.089930683 -0.25668436, -0.10185313 0.091202334 -0.25406301, -0.096879601 0.089822784 -0.25676027, -0.10189414 0.091095909 -0.25408629, -0.096847624 0.089714423 -0.25680867, -0.095750272 0.088702485 -0.25932458, -0.095736712 0.0887108 -0.25930327, -0.10137323 0.090249717 -0.25620311, -0.095723003 0.088717714 -0.25928167, -0.09584257 0.088784605 -0.25900817, -0.10131863 0.090257108 -0.25610536, -0.10126963 0.090239942 -0.25600582, -0.095933527 0.088782459 -0.25878567, -0.10122874 0.090199053 -0.25590962, -0.095988601 0.088743836 -0.25864065, -0.10119826 0.090136796 -0.25582141, -0.096022367 0.088690519 -0.25854355, -0.10117918 0.090055987 -0.25574607, -0.09604013 0.088639393 -0.25848633, -0.099919617 0.093221724 -0.25026667, -0.10463375 0.094474956 -0.24774936, -0.09986192 0.093132645 -0.2503832, -0.10469005 0.094397277 -0.24781524, -0.099809736 0.093031406 -0.25048256, -0.1047402 0.094302818 -0.24786106, -0.099766642 0.092923224 -0.25055826, -0.10478142 0.094196513 -0.24788427, -0.099734783 0.092814893 -0.25060678, -0.09863764 0.091803014 -0.25312263, -0.098623961 0.091811299 -0.25310135, -0.10426018 0.093350291 -0.25000125, -0.098610401 0.091818213 -0.25307959, -0.098729908 0.091885239 -0.25280625, -0.10420579 0.093357474 -0.24990349, -0.10415682 0.093340337 -0.24980383, -0.098820657 0.091883063 -0.25258374, -0.10411602 0.093299672 -0.24970761, -0.09887588 0.091844499 -0.25243866, -0.10408524 0.093237326 -0.24961939, -0.098909616 0.091791153 -0.25234157, -0.10406628 0.093156442 -0.24954388, -0.098927379 0.091739953 -0.25228429, -0.10280669 0.096322179 -0.2440647, -0.10752112 0.097575456 -0.24154736, -0.10274905 0.096233189 -0.24418129, -0.10757738 0.097497866 -0.24161327, -0.1026971 0.096131846 -0.24428061, -0.10762745 0.097403333 -0.24165913, -0.10265389 0.096023783 -0.24435633, -0.10766852 0.097297102 -0.24168219, -0.10262188 0.095915481 -0.24440482, -0.10152468 0.094903529 -0.2469206, -0.10151106 0.094911739 -0.2468994, -0.10714754 0.096450761 -0.24379906, -0.10149735 0.094918698 -0.2468776, -0.10161692 0.094985694 -0.24660425, -0.10709286 0.096458122 -0.24370146, -0.10704395 0.096440926 -0.24360198, -0.10170785 0.094983622 -0.24638167, -0.10700318 0.096400172 -0.24350564, -0.10176295 0.094944984 -0.24623664, -0.10697237 0.096337795 -0.24341746, -0.10179666 0.094891608 -0.24613966, -0.10695344 0.096257016 -0.24334207, -0.10181454 0.094840452 -0.24608245, -0.11146817 0.10562375 -0.22545882, -0.11618242 0.10687703 -0.2229415, -0.11141056 0.10553479 -0.22557525, -0.11623898 0.10679944 -0.22300735, -0.11135852 0.10543346 -0.22567461, -0.1162889 0.10670488 -0.22305322, -0.11131549 0.10532542 -0.22575033, -0.11633006 0.10659857 -0.22307649, -0.11128336 0.10521692 -0.22579895, -0.11018616 0.10420516 -0.22831483, -0.11017263 0.10421336 -0.22829352, -0.11580908 0.10575221 -0.22519335, -0.11015904 0.1042203 -0.22827186, -0.11027855 0.10428731 -0.22799844, -0.11575449 0.10575961 -0.2250956, -0.11570549 0.10574244 -0.22499603, -0.11036944 0.10428521 -0.22777589, -0.11566472 0.10570173 -0.22489977, -0.11042464 0.1042466 -0.22763079, -0.11563393 0.10563941 -0.22481167, -0.1104582 0.10419324 -0.2275338, -0.11561501 0.10555862 -0.22473606, -0.11047602 0.10414204 -0.22747655, -0.11307341 0.10730565 -0.22211282, -0.11305979 0.10731384 -0.22209145, -0.11869618 0.10885274 -0.21899132, -0.1130462 0.10732076 -0.22206987, -0.11316577 0.10738787 -0.22179641, -0.11864164 0.10886006 -0.21889368, -0.11859265 0.10884289 -0.21879417, -0.1132566 0.10738561 -0.22157396, -0.11855173 0.10880221 -0.21869791, -0.1133115 0.10734722 -0.22142889, -0.11852112 0.10873978 -0.21860978, -0.11334556 0.1072938 -0.22133189, -0.11850226 0.10865904 -0.21853411, -0.11336309 0.10724252 -0.22127445, -0.10728535 0.10111275 -0.2344956, -0.10727188 0.10111976 -0.23447369, -0.10729909 0.1011046 -0.23451683, -0.11292189 0.10265176 -0.23139524, -0.11286727 0.10265906 -0.23129746, -0.10739121 0.10118675 -0.23420034, -0.11281824 0.10264191 -0.23119803, -0.10748219 0.10118455 -0.23397784, -0.11277744 0.10260113 -0.23110175, -0.10753733 0.10114601 -0.23383279, -0.1127468 0.10253878 -0.23101354, -0.10757101 0.10109268 -0.23373577, -0.11272785 0.10245812 -0.23093803, -0.10758877 0.10104141 -0.23367836, -0.10858113 0.10252319 -0.23166087, -0.11329529 0.10377641 -0.22914338, -0.10852346 0.10243417 -0.2317774, -0.1133517 0.10369892 -0.22920942, -0.1084713 0.10233279 -0.23187664, -0.11340177 0.10360451 -0.22925523, -0.10842812 0.1022248 -0.23195244, -0.11344296 0.10349803 -0.2292783, -0.10839623 0.10211657 -0.23200089, -0.14603946 -0.022708341 -0.14061406, -0.1460743 -0.022741556 -0.14056085, -0.14606982 -0.022665009 -0.14055982, -0.14633402 -0.02271907 -0.14039674, -0.14641055 -0.022679776 -0.14036597, -0.14634478 -0.022688091 -0.14038138, -0.14653799 -0.022601932 -0.14032634, -0.14654833 -0.022582948 -0.14030932, -0.14648557 -0.022619352 -0.14031652, -0.14610344 -0.022615179 -0.14049783, -0.14615393 -0.022629082 -0.14044373, -0.14609984 -0.022594422 -0.14047803, -0.14637536 -0.022766829 -0.14039998, -0.1464372 -0.022759527 -0.1403947, -0.14646521 -0.022699505 -0.14037521, -0.14655057 -0.022594064 -0.14032568, -0.14606449 -0.02256158 -0.14050527, -0.14609745 -0.022589058 -0.14046611, -0.14639977 -0.022714108 -0.14038242, -0.14605069 -0.022543609 -0.14050131, -0.14657447 -0.022651628 -0.14037991, -0.1466099 -0.022645116 -0.14039658, -0.14663106 -0.022567019 -0.1403636, -0.14658973 -0.022600845 -0.14035678, -0.14624393 -0.022814453 -0.14044015, -0.14622685 -0.022887141 -0.14045413, -0.14629209 -0.022822797 -0.14042513, -0.14631501 -0.02276668 -0.14041205, -0.14637333 -0.022766933 -0.1404002, -0.14626002 -0.022760272 -0.14042936, -0.14639747 -0.022714436 -0.14038293, -0.14624119 -0.022813737 -0.14044122, -0.14625683 -0.022759527 -0.14043058, -0.14628151 -0.022686332 -0.14040191, -0.14634982 -0.022664636 -0.14036091, -0.14654449 -0.022629768 -0.14035381, -0.1465947 -0.022561312 -0.14032601, -0.14628488 -0.022665024 -0.14038275, -0.14605406 -0.022549361 -0.14051451, -0.1465919 -0.022548974 -0.14030795, -0.14663294 -0.022515148 -0.14031889, -0.14663082 -0.022510037 -0.1403102, -0.14653188 -0.022636518 -0.14035371, -0.14627767 -0.022685826 -0.14040332, -0.14628085 -0.022664711 -0.14038435, -0.14615825 -0.022727996 -0.14048083, -0.14620209 -0.02274555 -0.14045517, -0.14620975 -0.02270034 -0.1404437, -0.14648691 -0.022628635 -0.14033116, -0.14641836 -0.02264449 -0.14032997, -0.14616126 -0.0226807 -0.14047085, -0.14640146 -0.022828922 -0.14041141, -0.14631197 -0.022906393 -0.14043339, -0.14640075 -0.02292119 -0.14043143, -0.1464467 -0.022826552 -0.14041333, -0.14648616 -0.022748411 -0.14039569, -0.14652875 -0.022675604 -0.14037491, -0.14610577 -0.022645652 -0.14051096, -0.146155 -0.022648871 -0.14046232, -0.14621487 -0.022652596 -0.14041211, -0.14628005 -0.022658765 -0.14037304, -0.14621374 -0.022647351 -0.14040114, -0.14615431 -0.022677273 -0.14047535, -0.14654374 -0.022728801 -0.14040326, -0.14655396 -0.022789881 -0.14043048, -0.14615202 -0.022724986 -0.14048503, -0.14627367 -0.022714958 -0.140416, -0.1465162 -0.022681177 -0.14037447, -0.14607 -0.022583842 -0.1405264, -0.14605993 -0.022572026 -0.1405361, -0.14627019 -0.022714406 -0.14041741, -0.14648032 -0.022659659 -0.14035629, -0.14641917 -0.022652566 -0.140343, -0.1461933 -0.022800893 -0.14046301, -0.14614975 -0.022865236 -0.14049391, -0.14641669 -0.022653192 -0.14034368, -0.14634919 -0.022657812 -0.14034908, -0.14621377 -0.022672653 -0.14043055, -0.14607421 -0.022616476 -0.1405402, -0.14649853 -0.02274482 -0.14039674, -0.14616144 -0.022632658 -0.14043944, -0.14615241 -0.022623748 -0.14043255, -0.14606455 -0.022605747 -0.14055063, -0.14634585 -0.022827923 -0.140415, -0.14610773 -0.022698149 -0.14052001, -0.14634395 -0.022827804 -0.14041524, -0.14601231 -0.022482514 -0.14055948, -0.1460056 -0.022470504 -0.14054711, -0.14598712 -0.022395208 -0.14060855, -0.14599267 -0.02240786 -0.14062466, -0.146413 -0.022679299 -0.14036556, -0.14615464 -0.022787035 -0.1404864, -0.14650166 -0.022819817 -0.14042203, -0.14648989 -0.022929281 -0.1404487, -0.14598113 -0.022386894 -0.14058998, -0.14614919 -0.02278468 -0.14049025, -0.14602068 -0.022508591 -0.14058508, -0.14599749 -0.022424057 -0.14063841, -0.14600161 -0.022443146 -0.14065005, -0.14616245 -0.022652373 -0.14045814, -0.14607871 -0.022674084 -0.14054941, -0.14602765 -0.022547394 -0.14060207, -0.14600599 -0.022471607 -0.14066212, -0.14601266 -0.022554278 -0.14067923, -0.14610931 -0.022765011 -0.14052261, -0.14608395 -0.022841513 -0.1405503, -0.14645842 -0.022825509 -0.14041455, -0.14608261 -0.022747844 -0.14055051, -0.14603475 -0.022617072 -0.14061363, -0.14601371 -0.022665054 -0.14068301, -0.14663494 -0.022536337 -0.1403424, -0.14663419 -0.022521347 -0.14032723, -0.1460402 -0.022820473 -0.14060794, -0.14600831 -0.022798002 -0.14067315, -0.14593482 -0.023288906 -0.14071839, -0.14598012 -0.023293972 -0.14063559, -0.14604366 -0.023301065 -0.14056598, -0.14612165 -0.023309797 -0.14051308, -0.14620975 -0.023319751 -0.14048012, -0.14630294 -0.023330152 -0.14046912, -0.14636067 -0.022667974 -0.14031221, -0.14641872 -0.022651047 -0.14028521, -0.14635274 -0.022676677 -0.14029951, -0.14645073 -0.022631496 -0.14031424, -0.14649534 -0.022607744 -0.14024274, -0.14654079 -0.022579163 -0.14029212, -0.14629495 -0.022674382 -0.14033954, -0.14629033 -0.022682056 -0.14032903, -0.14623132 -0.022677392 -0.14035173, -0.14638263 -0.022652149 -0.14033316, -0.14647627 -0.022626519 -0.14022039, -0.14656112 -0.022541836 -0.14019859, -0.14653265 -0.022574544 -0.14016913, -0.14623484 -0.022669405 -0.14036293, -0.14617714 -0.022665113 -0.14036866, -0.14630675 -0.022659957 -0.14035802, -0.14618063 -0.022655919 -0.14038247, -0.14612392 -0.022645801 -0.14038135, -0.14623901 -0.022653654 -0.14038479, -0.14612824 -0.022634014 -0.14040008, -0.1460728 -0.022619784 -0.14038943, -0.14662588 -0.02250427 -0.14029543, -0.14661995 -0.022502035 -0.14028116, -0.14661267 -0.022502452 -0.14026721, -0.1466046 -0.022505507 -0.14025369, -0.14617991 -0.022636592 -0.14041142, -0.14612523 -0.022609442 -0.14043947, -0.14603135 -0.022565693 -0.1404257, -0.14602491 -0.022587329 -0.14039297, -0.14598107 -0.022549376 -0.14039174, -0.14603549 -0.02252768 -0.14049521, -0.14594451 -0.022415251 -0.1404651, -0.14595062 -0.022516713 -0.14038768, -0.14592347 -0.022481397 -0.14038074, -0.14595801 -0.022390902 -0.14051424, -0.14596805 -0.022383124 -0.14054842, -0.14597449 -0.022382885 -0.1405694, -0.14659289 -0.022512764 -0.14023663, -0.14640662 -0.022662491 -0.14026912, -0.091300845 0.004487142 -0.24788347, -0.10515738 0.0044869334 -0.24788359, -0.10018861 -0.010026172 -0.23949119, -0.10047039 -0.010118663 -0.23943771, -0.10071832 -0.01026684 -0.239352, -0.1009182 -0.01046215 -0.23923901, -0.095205426 -0.033555552 -0.22588512, -0.10105821 -0.010693118 -0.23910558, -0.10113037 -0.010946363 -0.23895903, -0.10990602 -0.033555642 -0.22588521, -0.10113037 -0.011207312 -0.23880823, -0.10018858 -0.012127608 -0.23827605, -0.1004703 -0.012034982 -0.23832937, -0.10071832 -0.011886775 -0.23841523, -0.10091811 -0.011691481 -0.2385283, -0.10105819 -0.011460483 -0.23866163, -0.09067148 0.0046800375 -0.24799503, -0.090512902 0.0048198402 -0.24807598, -0.090862453 0.0045747161 -0.24793424, -0.090394437 0.0049868822 -0.24817266, -0.091075778 0.0045093149 -0.24789631, -0.09067598 0.0060286075 -0.24877501, -0.084868997 0.051167235 -0.27487665, -0.09051764 0.0058909655 -0.24869527, -0.08471027 0.051307067 -0.27495745, -0.090398699 0.0057263225 -0.24860007, -0.09086597 0.0061322153 -0.24883489, -0.085059881 0.051061973 -0.27481571, -0.084591985 0.051474214 -0.27505422, -0.090325117 0.0055426359 -0.24849392, -0.091077775 0.006196633 -0.24887213, -0.085273296 0.050996631 -0.27477795, -0.091300756 0.0062184185 -0.24888468, -0.085498214 0.050974369 -0.27476525, -0.10494146 0.0062183738 -0.24888472, -0.099355072 0.05097422 -0.27476501, -0.094634354 0.081924289 -0.28180361, -0.094634324 0.083439127 -0.28256074, -0.094994992 0.083500221 -0.28243843, -0.094995081 0.081985578 -0.28168106, -0.095312446 0.083598286 -0.28224248, -0.095312506 0.082083479 -0.28148511, -0.09556818 0.083727345 -0.28198424, -0.095568329 0.082212582 -0.28122681, -0.09574753 0.083880007 -0.28167862, -0.095747441 0.082365304 -0.2809214, -0.095839769 0.084047571 -0.28134367, -0.095839828 0.082532778 -0.28058654, -0.095839769 0.084220067 -0.2809988, -0.095839798 0.082705244 -0.28024137, -0.09574753 0.084387526 -0.28066373, -0.095747501 0.082872584 -0.27990645, -0.095568299 0.084540188 -0.28035831, -0.095568329 0.083025455 -0.27960098, -0.095312446 0.084669322 -0.28010011, -0.095312506 0.083154604 -0.27934262, -0.094994992 0.084767312 -0.27990401, -0.094994962 0.083252579 -0.27914679, -0.094634354 0.084828481 -0.2797817, -0.094634354 0.083313718 -0.27902439, -0.12586373 0.11697629 -0.21547674, -0.1258637 0.11546135 -0.21471958, -0.12622446 0.11703748 -0.2153544, -0.12622428 0.1155225 -0.21459718, -0.12654173 0.11713538 -0.21515845, -0.12654179 0.11562055 -0.21440138, -0.12679768 0.11726448 -0.21490024, -0.12679756 0.1157496 -0.21414293, -0.12697691 0.1174171 -0.21459483, -0.12697685 0.1159023 -0.21383755, -0.12706915 0.11758468 -0.21425985, -0.12706918 0.11606997 -0.21350257, -0.12706923 0.11775717 -0.21391474, -0.12706918 0.11624245 -0.21315747, -0.12697688 0.11792454 -0.21358, -0.12697685 0.11640978 -0.21282257, -0.12679759 0.11807728 -0.21327429, -0.12679762 0.11656255 -0.21251716, -0.126542 0.11820649 -0.21301606, -0.12654188 0.11669168 -0.21225877, -0.12622446 0.11830443 -0.21282019, -0.12622452 0.11678958 -0.21206285, -0.12586373 0.11836559 -0.21269779, -0.12586355 0.11685073 -0.21194054, -0.095497489 0.077218831 -0.27782387, -0.097807616 0.077134326 -0.27777496, -0.097442716 0.076873496 -0.27762416, -0.091657549 0.077032894 -0.27771628, -0.1053668 -0.033040583 -0.2140656, -0.091624051 0.077059761 -0.27773184, -0.092156053 0.076802239 -0.27758288, -0.091886044 0.076892242 -0.27763498, -0.091765225 0.076957226 -0.27767259, -0.097208887 0.076799899 -0.27758157, -0.097073168 0.076778963 -0.27756944, -0.11420539 -0.033040613 -0.21406563, -0.10770243 -0.032540336 -0.20849892, -0.093925565 0.079112366 -0.27306286, -0.093761355 0.079149142 -0.27308413, -0.094030946 0.079099968 -0.2730557, -0.094137043 0.079095766 -0.27305335, -0.098635286 0.079095781 -0.27305335, -0.11686963 -0.032540381 -0.20849909, -0.098905534 0.079123408 -0.2730692, -0.09916386 0.079207599 -0.27311802, -0.099505275 0.079457998 -0.27326286, -0.10272047 0.080817059 -0.27404869, -0.10068193 0.080817074 -0.27404875, -0.099354506 0.079319164 -0.27318254, -0.1041812 0.0052914023 -0.25048769, -0.098594755 0.050047383 -0.27636811, -0.095413357 0.077047527 -0.29151994, -0.095466256 0.077121198 -0.29141104, -0.095369846 0.07695511 -0.29160094, -0.09533754 0.076856673 -0.29165292, -0.095316529 0.076765358 -0.29167914, -0.097273946 0.077018559 -0.28696871, -0.097058624 0.076596677 -0.28737926, -0.096865505 0.07608217 -0.28770995, -0.097417742 0.077235729 -0.28667742, -0.097560614 0.077409327 -0.28637552, -0.096709371 0.075500309 -0.2879324, -0.09660086 0.074887037 -0.28802979, -0.096544653 0.074281722 -0.28800094, -0.096539468 0.073719203 -0.28786027, -0.096577764 0.073224038 -0.28763115, -0.10776338 0.090327144 -0.26499546, -0.10792878 0.088543415 -0.26410353, -0.098378628 0.051778659 -0.27736923, -0.099138886 0.052705675 -0.27576625, -0.12650105 0.11044939 -0.22474509, -0.10876158 0.089437768 -0.26231468, -0.1085963 0.091221407 -0.26320642, -0.12666643 0.10866581 -0.22385323, -0.13483118 0.11939506 -0.20685112, -0.12749919 0.10955997 -0.22206444, -0.12733379 0.11134364 -0.22295597, -0.1349721 0.117585 -0.20601197, -0.15606004 -0.02769196 -0.13646953, -0.15615228 -0.027584553 -0.13646953, -0.15594807 -0.027778745 -0.13646953, -0.14662391 -0.032670826 -0.13646992, -0.15622103 -0.027460709 -0.13646954, -0.15626359 -0.02732566 -0.13646956, -0.15462616 -0.026478276 -0.13646927, -0.15627787 -0.027184755 -0.13646944, -0.15487909 -0.026193038 -0.13646942, -0.14757735 -0.032994896 -0.13647003, -0.14658767 -0.032994941 -0.13647002, -0.15505612 -0.025855526 -0.13646922, -0.15514734 -0.025485367 -0.1364695, -0.14726463 -0.028764784 -0.13646971, -0.15052959 -0.026478171 -0.13646941, -0.15027672 -0.026192874 -0.13646932, -0.14725995 -0.028325349 -0.13646944, -0.15084302 -0.026694626 -0.1364695, -0.15009972 -0.025855482 -0.13646947, -0.14676327 -0.024347872 -0.1364692, -0.15119955 -0.026829913 -0.13646942, -0.15357792 -0.023713842 -0.13646919, -0.15457776 -0.022594899 -0.13646902, -0.15157795 -0.023713961 -0.13646919, -0.14900133 -0.022594899 -0.13646902, -0.15431267 -0.023894951 -0.13646922, -0.15395629 -0.023759857 -0.13646919, -0.15000847 -0.025485367 -0.13646938, -0.15627787 -0.024294883 -0.13646926, -0.15514728 -0.025104299 -0.13646919, -0.15505621 -0.024734274 -0.13646919, -0.15487888 -0.024396628 -0.13646926, -0.15157789 -0.026875794 -0.13646971, -0.15495607 -0.022637516 -0.13646902, -0.15000832 -0.02510424 -0.1364693, -0.14768448 -0.023219675 -0.13646902, -0.15462619 -0.024111435 -0.13646922, -0.15623534 -0.023916498 -0.13646919, -0.15009958 -0.024734199 -0.13646923, -0.15531546 -0.022763252 -0.13646905, -0.14795303 -0.02295661 -0.13646911, -0.15610954 -0.023557335 -0.13646914, -0.14827257 -0.022758961 -0.13646905, -0.15590703 -0.023234963 -0.13646911, -0.15563783 -0.022965699 -0.13646902, -0.14862779 -0.022636384 -0.1364689, -0.15027663 -0.024396688 -0.13646914, -0.15052944 -0.024111509 -0.13646917, -0.15357789 -0.026875883 -0.1364695, -0.15084317 -0.023894876 -0.13646926, -0.15119946 -0.023759916 -0.13646919, -0.15395612 -0.026829958 -0.13646929, -0.15431252 -0.02669473 -0.13646942, -0.12471944 -0.033291742 -0.19004622, -0.12669238 -0.033292085 -0.18494649, -0.12458506 -0.033291712 -0.18987888, -0.1244435 -0.033291712 -0.1897673, -0.13156065 -0.033294007 -0.14967194, -0.13389635 -0.03329438 -0.14497082, -0.12431824 -0.033291757 -0.18970363, -0.12686494 -0.033292025 -0.18492766, -0.12704009 -0.033292055 -0.18486892, -0.12482515 -0.033291668 -0.19027467, -0.12720674 -0.033292085 -0.18476982, -0.12487504 -0.033291712 -0.1905269, -0.12486482 -0.033291712 -0.19080538, -0.12735483 -0.033292115 -0.18463568, -0.13350815 -0.033294439 -0.14209567, -0.11846372 -0.033292145 -0.18165238, -0.11800787 -0.033292145 -0.18169959, -0.13392916 -0.033294529 -0.14186592, -0.12747589 -0.0332921 -0.18447515, -0.12478873 -0.033291727 -0.19108017, -0.10442838 -0.033290043 -0.21692696, -0.10388488 -0.033290133 -0.21704057, -0.1041548 -0.033290029 -0.21695547, -0.13437909 -0.033294559 -0.14172392, -0.12756535 -0.033292115 -0.18429963, -0.12079942 -0.033292457 -0.17695132, -0.1202561 -0.033292398 -0.17706499, -0.12052599 -0.033292517 -0.17697999, -0.14306363 -0.033294454 -0.14497083, -0.14109057 -0.033294067 -0.15007064, -0.14095628 -0.033294111 -0.14990337, -0.14081475 -0.033294097 -0.14979166, -0.10403976 -0.033290327 -0.21405165, -0.14068952 -0.033294141 -0.14972799, -0.10446113 -0.033290282 -0.21382216, -0.14323625 -0.033294335 -0.14495212, -0.11346489 -0.033289835 -0.22274634, -0.14119637 -0.033294067 -0.15029898, -0.14341119 -0.03329441 -0.14489324, -0.14124623 -0.033294067 -0.15055117, -0.14357808 -0.03329438 -0.14479427, -0.14123613 -0.033294097 -0.15082985, -0.14372611 -0.033294365 -0.14466003, -0.1135954 -0.033290148 -0.21692701, -0.11376804 -0.033290207 -0.21690823, -0.14384702 -0.033294424 -0.14449951, -0.11394307 -0.033290252 -0.21684927, -0.13483495 -0.033294559 -0.14167671, -0.11410981 -0.033290207 -0.21675028, -0.11425787 -0.033290207 -0.21661611, -0.1053668 -0.033290297 -0.21363275, -0.10491076 -0.033290252 -0.21368021, -0.11437887 -0.033290207 -0.21645571, -0.13720801 -0.033294752 -0.13662928, -0.1365923 -0.033294916 -0.13675795, -0.13689801 -0.033294857 -0.13666122, -0.12041086 -0.033292681 -0.17407615, -0.12083223 -0.033292606 -0.17384654, -0.10770258 -0.03329061 -0.20893204, -0.10715905 -0.03329055 -0.20904553, -0.10742888 -0.03329055 -0.20896038, -0.147663 -0.033294782 -0.13924041, -0.14393666 -0.033294424 -0.14432427, -0.14115995 -0.033294097 -0.15110439, -0.12996653 -0.033292606 -0.17695135, -0.12799376 -0.033292264 -0.18205114, -0.12785935 -0.033292264 -0.18188383, -0.12771776 -0.033292159 -0.18177214, -0.12759253 -0.033292234 -0.18170826, -0.1444343 -0.033294514 -0.14310926, -0.14451039 -0.033294603 -0.14283469, -0.14452046 -0.033294544 -0.14255622, -0.14447063 -0.033294544 -0.14230397, -0.14436486 -0.033294588 -0.14207549, -0.14423048 -0.033294663 -0.14190832, -0.14408895 -0.033294573 -0.14179641, -0.14396369 -0.033294559 -0.14173292, -0.13013926 -0.033292606 -0.17693251, -0.14643115 -0.033294812 -0.13676995, -0.11420536 -0.033290312 -0.21363285, -0.14648882 -0.033294812 -0.13662916, -0.13031426 -0.033292606 -0.17687374, -0.12809935 -0.033292234 -0.18227945, -0.14766324 -0.033294886 -0.13677014, -0.13023362 -0.033294022 -0.15009074, -0.12814927 -0.033292249 -0.18253183, -0.13048103 -0.033292592 -0.17677467, -0.1273807 -0.033293515 -0.15785624, -0.12783054 -0.033293679 -0.15771437, -0.12695938 -0.033293545 -0.15808593, -0.12410656 -0.033293158 -0.16585143, -0.12455636 -0.033293113 -0.16570935, -0.12368527 -0.033293158 -0.16608103, -0.12128201 -0.033292696 -0.17370453, -0.12813908 -0.033292264 -0.18281014, -0.13062894 -0.033292592 -0.17664038, -0.117558 -0.033292115 -0.18184166, -0.11713672 -0.033292159 -0.1820713, -0.11428383 -0.033291668 -0.1898367, -0.11473358 -0.033291668 -0.18969466, -0.11386251 -0.033291698 -0.19006626, -0.1110096 -0.033291265 -0.19783187, -0.11145934 -0.033291265 -0.19769001, -0.11058819 -0.033291146 -0.19806147, -0.10773531 -0.033290774 -0.20582698, -0.10818496 -0.033290789 -0.20568493, -0.10731399 -0.033290774 -0.20605667, -0.12173787 -0.033292636 -0.17365715, -0.12806293 -0.033292234 -0.18308489, -0.13075009 -0.033292621 -0.17648007, -0.14066243 -0.033293903 -0.15231918, -0.13788569 -0.03329359 -0.15909967, -0.13738808 -0.033293411 -0.16031447, -0.13461146 -0.033293098 -0.16709478, -0.13411391 -0.033293068 -0.16830949, -0.13133731 -0.033292592 -0.17508982, -0.13083962 -0.033292592 -0.17630468, -0.12429124 -0.033291519 -0.19229488, -0.12151462 -0.03329128 -0.19907509, -0.12101707 -0.033291012 -0.20028998, -0.1182403 -0.033290833 -0.20707031, -0.11774269 -0.03329064 -0.20828527, -0.13065499 -0.033294067 -0.14986113, -0.13110486 -0.033294037 -0.14971918, -0.12407377 -0.033292934 -0.16895631, -0.12353036 -0.033292979 -0.16906978, -0.12380028 -0.033292875 -0.1689848, -0.11490315 -0.033290327 -0.21404223, -0.11686969 -0.03329061 -0.20893201, -0.11476767 -0.033290386 -0.21386974, -0.11462232 -0.033290356 -0.21375369, -0.11446595 -0.033290386 -0.21367769, -0.11433348 -0.033290341 -0.21364346, -0.11704221 -0.033290595 -0.20891304, -0.11721736 -0.03329055 -0.20885423, -0.11500698 -0.033290386 -0.21427436, -0.11738399 -0.033290595 -0.20875524, -0.11505324 -0.033290327 -0.21452622, -0.11753213 -0.033290625 -0.20862104, -0.11504081 -0.033290312 -0.21479955, -0.10864094 -0.033290789 -0.2056376, -0.11765319 -0.033290684 -0.20846058, -0.11097667 -0.033291057 -0.20093694, -0.11043334 -0.033290997 -0.20105025, -0.11070314 -0.033291027 -0.20096523, -0.13126791 -0.033292741 -0.17405601, -0.13324082 -0.033292934 -0.16895631, -0.13113347 -0.033292711 -0.17388855, -0.13099194 -0.033292711 -0.17377697, -0.1308668 -0.033292711 -0.17371319, -0.13341346 -0.033292964 -0.16893739, -0.13358843 -0.033292964 -0.16887861, -0.13137361 -0.033292711 -0.17428438, -0.13375521 -0.033292964 -0.16877955, -0.13142338 -0.033292741 -0.1745366, -0.13390324 -0.033292994 -0.16864529, -0.13141334 -0.033292592 -0.17481504, -0.12501222 -0.033293173 -0.16566208, -0.13402426 -0.033293068 -0.16848485, -0.12734795 -0.033293411 -0.16096112, -0.12680465 -0.033293352 -0.16107485, -0.12707445 -0.033293322 -0.16098946, -0.12014404 -0.033291101 -0.20093675, -0.11817095 -0.033290803 -0.20603658, -0.1180366 -0.033290803 -0.20586921, -0.11789507 -0.033290774 -0.20575745, -0.11776984 -0.033290818 -0.20569366, -0.12031657 -0.033291042 -0.20091783, -0.1182768 -0.033290803 -0.20626499, -0.12049156 -0.033291161 -0.20085903, -0.11832651 -0.033290803 -0.20651723, -0.12065837 -0.033291057 -0.2007601, -0.11831638 -0.033290803 -0.20679547, -0.1208064 -0.033291087 -0.20062584, -0.11191523 -0.033291265 -0.19764245, -0.12092748 -0.033291101 -0.2004654, -0.11425099 -0.033291504 -0.1929417, -0.11370751 -0.033291534 -0.19305527, -0.11397743 -0.033291534 -0.19297001, -0.13651511 -0.033293411 -0.16096112, -0.13454196 -0.033293158 -0.16606094, -0.13440767 -0.033293217 -0.16589345, -0.13426623 -0.033293173 -0.16578189, -0.13414106 -0.033293203 -0.16571814, -0.13668773 -0.033293411 -0.16094235, -0.13464788 -0.033292994 -0.16628936, -0.13686273 -0.033293411 -0.16088346, -0.13702944 -0.033293441 -0.16078448, -0.13469774 -0.033293128 -0.16654168, -0.13468757 -0.033293098 -0.16681994, -0.13717753 -0.033293486 -0.1606503, -0.12828654 -0.033293575 -0.157667, -0.13729861 -0.033293441 -0.16048986, -0.13062221 -0.033293754 -0.15296604, -0.13007882 -0.033293918 -0.15307969, -0.13034859 -0.033293843 -0.15299456, -0.12341812 -0.033291548 -0.19294168, -0.12144524 -0.03329128 -0.1980413, -0.12131086 -0.033291355 -0.19787395, -0.12116921 -0.03329134 -0.19776236, -0.12104416 -0.03329137 -0.19769849, -0.12359065 -0.033291593 -0.19292283, -0.12376586 -0.033291534 -0.19286376, -0.12155095 -0.03329134 -0.19826983, -0.12393263 -0.033291593 -0.19276494, -0.12160078 -0.033291221 -0.19852196, -0.12408048 -0.033291578 -0.19263075, -0.12159067 -0.033291206 -0.19880036, -0.11518955 -0.033291698 -0.18964748, -0.12420166 -0.033291578 -0.19247024, -0.11752534 -0.033291921 -0.18494639, -0.11698192 -0.033292055 -0.18506013, -0.11725172 -0.03329204 -0.18497488, -0.13978943 -0.033293873 -0.1529661, -0.13781628 -0.03329356 -0.15806574, -0.13768202 -0.03329362 -0.15789837, -0.13754046 -0.033293635 -0.15778662, -0.13741526 -0.033293679 -0.15772301, -0.13996199 -0.033293888 -0.1529471, -0.13792202 -0.03329356 -0.15829408, -0.14013699 -0.033293948 -0.15288839, -0.13797197 -0.03329356 -0.15854645, -0.14030382 -0.033293873 -0.15278943, -0.14045179 -0.033293918 -0.15265518, -0.13796189 -0.03329359 -0.15882477, -0.14057297 -0.033293948 -0.1524947, -0.13335299 -0.033294261 -0.14508455, -0.13362274 -0.03329441 -0.14499922, -0.12952527 0.10924503 -0.21703143, -0.12908646 0.1087738 -0.21797366, -0.14585277 -0.024021819 -0.1407184, -0.1458281 -0.02437751 -0.14068094, -0.14698848 -0.02873373 -0.13665651, -0.14644372 -0.024369895 -0.13917987, -0.14602786 -0.024879083 -0.14005616, -0.14594817 -0.024933517 -0.14023559, -0.14592046 -0.024925694 -0.14030579, -0.14597687 -0.024926573 -0.14016743, -0.14599955 -0.024910018 -0.14011684, -0.14585921 -0.024805874 -0.14048769, -0.14584547 -0.024733439 -0.14054137, -0.14587915 -0.02486819 -0.14042257, -0.14590204 -0.0249089 -0.1403551, -0.14583051 -0.02456665 -0.14062355, -0.13105017 -0.035281986 -0.13903834, -0.1308867 -0.035282075 -0.13923852, -0.13098273 -0.035282075 -0.13909392, -0.13092756 -0.035282075 -0.13916151, -0.13681042 -0.035282344 -0.13517012, -0.14713407 -0.035282165 -0.14017023, -0.1484372 -0.035282403 -0.13517024, -0.14843714 -0.035282135 -0.14017014, -0.094875813 -0.035276845 -0.2271708, -0.11107165 -0.03527692 -0.22822781, -0.094818622 -0.035276845 -0.22822782, -0.11171609 -0.034649044 -0.22849186, -0.1477634 -0.034654289 -0.1404701, -0.14784461 -0.033929035 -0.14047, -0.097540945 0.076568067 -0.29351878, -0.097558856 0.076312214 -0.29340571, -0.097548813 0.076842129 -0.29357469, -0.097581834 0.077121913 -0.29357046, -0.097638577 0.077394307 -0.29350662, -0.097716212 0.077646673 -0.29338592, -0.097811341 0.077867329 -0.2932139, -0.097895205 0.078011319 -0.29304871, -0.097984642 0.078125656 -0.2928617, -0.10044512 0.075634539 -0.28617233, -0.10068116 0.076133043 -0.28573257, -0.10027283 0.075103402 -0.28644836, -0.10094854 0.076503783 -0.28518093, -0.10015765 0.074582607 -0.28658682, -0.10008574 0.074044406 -0.28661513, -0.10006014 0.07351172 -0.28653193, -0.10006857 0.073185235 -0.28642178, -0.10009655 0.072876155 -0.28626919, -0.13761368 0.12068292 -0.20773439, -0.13804126 0.11633755 -0.20550171, -0.11132795 -0.03399983 -0.22961707, -0.11135578 -0.034165308 -0.22950363, -0.11139598 -0.034311235 -0.22936599, -0.11147532 -0.034484446 -0.22912483, -0.11158675 -0.034607187 -0.22881895, -0.11332041 -0.033067629 -0.22500679, -0.11337617 -0.033380568 -0.22478534, -0.1134569 -0.033630893 -0.22451946, -0.14696217 -0.028362483 -0.13676943, -0.14646554 -0.024384961 -0.13676921, -0.1464656 -0.024384722 -0.13906971, -0.14571238 -0.023147032 -0.13983813, -0.13904476 -0.031313166 -0.13511601, -0.138684 -0.031887785 -0.13478369, -0.13862705 -0.032062754 -0.13468257, -0.13861015 -0.032178536 -0.1346156, -0.13861531 -0.032278359 -0.13455801, -0.14664558 -0.032844782 -0.13636939, -0.14663884 -0.033040524 -0.13633262, -0.14664668 -0.032982722 -0.13632929, -0.14664981 -0.032928228 -0.13633667, -0.14664906 -0.032883838 -0.13635045, -0.14660674 -0.03315945 -0.13637823, -0.14657715 -0.033060685 -0.13647741, -0.14662609 -0.033098742 -0.13634756, -0.14656022 -0.033127308 -0.13650064, -0.14658058 -0.033216327 -0.1364267, -0.14653665 -0.03318879 -0.13654108, -0.14655176 -0.033258319 -0.13648538, -0.14652017 -0.033285677 -0.13655512, -0.14650875 -0.033239037 -0.13659568, -0.1464788 -0.033273712 -0.1366595, -0.14645389 -0.033289805 -0.13671535, -0.091300845 0.0035601556 -0.24948646, -0.094231188 -0.033555508 -0.2280242, -0.091061473 0.0035853088 -0.24950112, -0.090836048 0.0036593527 -0.24954385, -0.090637714 0.0037779361 -0.24961242, -0.090477794 0.0039341599 -0.2497026, -0.090365797 0.0041188896 -0.24980955, -0.09030807 0.004321456 -0.24992688, -0.10439718 0.0035602003 -0.24948648, -0.080560505 0.075967014 -0.29135621, -0.10902995 -0.033555523 -0.22802418, -0.084505558 0.050808862 -0.27680844, -0.084835142 0.051561102 -0.27724341, -0.084675223 0.051404938 -0.27715293, -0.085033447 0.051679596 -0.27731207, -0.084563255 0.051220134 -0.27704614, -0.085258871 0.05175361 -0.27735484, -0.084505588 0.051017508 -0.27692893, -0.085498154 0.051778764 -0.27736926, -0.085033536 0.050146654 -0.27642542, -0.090637743 0.0050738156 -0.2503618, -0.084835231 0.050265253 -0.27649391, -0.090477794 0.0049176216 -0.25027144, -0.084675312 0.050421432 -0.27658433, -0.085258961 0.050072625 -0.27638263, -0.090836108 0.0051923096 -0.25043029, -0.090365797 0.0047328919 -0.25016463, -0.084563166 0.050606236 -0.27669123, -0.085498214 0.050047383 -0.27636805, -0.091061443 0.005266428 -0.25047314, -0.0903081 0.0045302212 -0.25004745, -0.091300845 0.0052915514 -0.25048763, -0.096914381 0.07603389 -0.29374778, -0.093395621 0.065190673 -0.28747761, -0.097718179 -0.01511693 -0.24103926, -0.097198576 -0.014601156 -0.24133742, -0.094696879 -0.034277976 -0.2299592, -0.09836638 -0.015508786 -0.2408126, -0.096838087 -0.013992116 -0.24168968, -0.099104673 -0.015753672 -0.24067107, -0.09665817 -0.013325751 -0.2420751, -0.11068353 -0.03427799 -0.2299591, -0.086933345 0.064586133 -0.28712797, -0.080927968 0.07603395 -0.29374784, -0.089428395 0.067628711 -0.28888738, -0.088692248 0.067396522 -0.28875321, -0.088041633 0.067018628 -0.28853476, -0.087514371 0.066516995 -0.28824449, -0.087141126 0.065920711 -0.28789961, -0.086943567 0.065264314 -0.28752017, -0.093218267 0.065851182 -0.28785956, -0.092863262 0.06645596 -0.28820926, -0.092351407 0.066969514 -0.28850627, -0.091712683 0.067362159 -0.28873318, -0.090983778 0.06761089 -0.28887713, -0.090207279 0.067701548 -0.28892958, -0.12821332 0.1189048 -0.21273707, -0.13665372 0.1215657 -0.20741461, -0.12771291 0.11917439 -0.21219791, -0.12708262 0.11938272 -0.21178165, -0.092067242 0.083504945 -0.2835474, -0.091547549 0.083774984 -0.28300762, -0.080983073 0.078823984 -0.29291075, -0.12635937 0.11951733 -0.21151213, -0.12065285 0.12066427 -0.20921765, -0.13696915 0.12138128 -0.20778345, -0.097340316 0.078823879 -0.29291084, -0.092718035 0.083299696 -0.2839579, -0.09119013 0.084093034 -0.28237098, -0.13672225 0.12156598 -0.20741385, -0.093460947 0.083171412 -0.28421456, -0.13699089 0.12144558 -0.20765486, -0.13697655 0.12147553 -0.20759508, -0.13698952 0.12141505 -0.20771594, -0.13698189 0.12139776 -0.20775039, -0.09101668 0.084440649 -0.2816757, -0.13678938 0.1215595 -0.20742701, -0.13694732 0.12150314 -0.20753963, -0.13685128 0.12154612 -0.2074535, -0.091037452 0.084796712 -0.28096369, -0.1369049 0.12152719 -0.20749174, -0.11961538 0.12031113 -0.20992437, -0.091251135 0.085139707 -0.28027728, -0.12848118 0.11755951 -0.21542835, -0.12248066 0.1186769 -0.21319358, -0.12286687 0.11898172 -0.21258391, -0.11992392 0.12051076 -0.20952524, -0.11974603 0.12041816 -0.2097104, -0.1234048 0.11923631 -0.21207431, -0.12014088 0.12058467 -0.20937742, -0.12038741 0.12063652 -0.20927326, -0.12406337 0.11942589 -0.21169476, -0.12480453 0.11953962 -0.21146755, -0.12558514 0.11957069 -0.21140543, -0.12869304 0.11789674 -0.21475358, -0.1287179 0.11824676 -0.21405314, -0.12855497 0.11858961 -0.21336769, -0.11988124 0.11881357 -0.20801441, -0.12022284 0.11888562 -0.20787027, -0.11958086 0.11871132 -0.20821898, -0.11933476 0.11858323 -0.2084751, -0.12059054 0.1189242 -0.20779301, -0.11915383 0.11843497 -0.20877163, -0.11342072 0.1112313 -0.22318099, -0.11326087 0.11115059 -0.2233424, -0.11361915 0.11129247 -0.22305849, -0.11314887 0.11105511 -0.22353347, -0.11384469 0.11133096 -0.22298224, -0.11408386 0.11134385 -0.22295609, -0.13670436 0.11983177 -0.20597728, -0.13686679 0.11983341 -0.20597385, -0.13759227 0.11954625 -0.20654854, -0.13678412 0.11983447 -0.20597187, -0.13753383 0.1196267 -0.2063875, -0.13743976 0.11969593 -0.20624907, -0.13732293 0.11975029 -0.20614024, -0.13718194 0.1197927 -0.20605551, -0.13702618 0.11982065 -0.20599936, -0.11309123 0.11084278 -0.22395825, -0.0946832 0.091109127 -0.26343143, -0.11309123 0.11095054 -0.22374272, -0.094523281 0.091028333 -0.26359284, -0.094881594 0.091170385 -0.26330888, -0.11314899 0.11073801 -0.22416778, -0.0951069 0.091208473 -0.26323247, -0.1132609 0.11064254 -0.22435874, -0.095346332 0.091221601 -0.26320642, -0.11361912 0.11050069 -0.22464244, -0.11342078 0.11056194 -0.22452001, -0.11408392 0.11044955 -0.22474496, -0.11384466 0.11046241 -0.22471899, -0.09468317 0.090439737 -0.26477033, -0.09452334 0.090520412 -0.26460898, -0.094411254 0.090615779 -0.26441807, -0.094881594 0.090378523 -0.26489294, -0.094353527 0.090720534 -0.26420873, -0.095106959 0.090340286 -0.26496941, -0.095346302 0.090327144 -0.26499528, -0.080682874 0.077121377 -0.29141104, -0.094353646 0.090828359 -0.26399308, -0.094411254 0.090932995 -0.26378375, -0.13765414 0.11955889 -0.2065458, -0.13762364 0.11955045 -0.2065461, -0.1376943 0.11957799 -0.20654908, -0.13772939 0.11960439 -0.20655644, -0.13775747 0.11963707 -0.20656739, -0.13778897 0.11975534 -0.20661673, -0.13778798 0.11971456 -0.20659815, -0.13777725 0.11967438 -0.20658158, -0.090463609 0.067885488 -0.28454411, -0.090745419 0.067793101 -0.28449059, -0.090993375 0.067644924 -0.28440487, -0.091193199 0.067449391 -0.28429204, -0.091333091 0.067218632 -0.28415847, -0.091405302 0.066965342 -0.28401202, -0.091405302 0.066704452 -0.28386116, -0.09133321 0.066451162 -0.28371465, -0.085498333 0.05270578 -0.27576643, -0.085275173 0.052683964 -0.27575374, -0.085063338 0.052619591 -0.27571642, -0.084873438 0.052515998 -0.27565664, -0.090463579 0.065784305 -0.28332901, -0.084596127 0.052213416 -0.27548161, -0.084522516 0.052029833 -0.27537552, -0.084715098 0.052378222 -0.27557698, -0.09074533 0.065876871 -0.28338265, -0.090993345 0.066024989 -0.28346813, -0.09119308 0.066220194 -0.28358114, -0.082794517 0.077409148 -0.28637552, -0.09455061 0.080292538 -0.28060785, -0.094832361 0.0803404 -0.28051227, -0.095080405 0.080416963 -0.28035909, -0.095280111 0.080517784 -0.28015724, -0.095420241 0.080637053 -0.2799187, -0.095492423 0.080768049 -0.27965695, -0.095492244 0.08090277 -0.27938741, -0.094683111 0.088656008 -0.26387864, -0.094523281 0.088736683 -0.26371723, -0.094881535 0.088594854 -0.26400119, -0.094411165 0.088832051 -0.26352632, -0.09510693 0.088556617 -0.26407766, -0.094353497 0.088936821 -0.26331696, -0.095346183 0.088543564 -0.26410353, -0.09455061 0.081378058 -0.27843669, -0.094832331 0.081330344 -0.27853221, -0.095080376 0.081253722 -0.27868536, -0.094353467 0.089044616 -0.26310137, -0.094411254 0.089149252 -0.26289198, -0.09528017 0.08115299 -0.27888718, -0.095420301 0.081033602 -0.27912587, -0.095346332 0.089437857 -0.26231477, -0.11326084 0.10885899 -0.22346693, -0.095106959 0.089424878 -0.26234072, -0.11342067 0.10877821 -0.22362836, -0.11361918 0.10871701 -0.2237508, -0.1131489 0.10895441 -0.22327593, -0.094881564 0.089386702 -0.26241726, -0.11384457 0.10867877 -0.22382718, -0.11309117 0.10905907 -0.22306664, -0.0946832 0.089325547 -0.26253968, -0.11408386 0.10866579 -0.22385325, -0.11309129 0.10916683 -0.22285099, -0.0945234 0.089244768 -0.26270106, -0.11408392 0.10956022 -0.22206439, -0.1132609 0.10936697 -0.22245076, -0.11934522 0.11666095 -0.20786072, -0.11314887 0.10927147 -0.22264166, -0.11342078 0.10944766 -0.2222894, -0.11361909 0.1095088 -0.22216678, -0.11384457 0.10954709 -0.2220903, -0.12578002 0.11382976 -0.21352397, -0.12606174 0.11387748 -0.2134283, -0.12630975 0.11395405 -0.21327522, -0.11982483 0.11695859 -0.20726533, -0.11954242 0.11681941 -0.20754372, -0.12650955 0.11405493 -0.2130734, -0.12017453 0.11706552 -0.20705144, -0.12664962 0.11417425 -0.21283479, -0.12047821 0.11712161 -0.20693909, -0.12078932 0.11715184 -0.20687905, -0.12578005 0.11491507 -0.21135275, -0.12606171 0.11486728 -0.21144834, -0.12630969 0.11479083 -0.21160154, -0.12650955 0.11468993 -0.21180308, -0.12664974 0.11457059 -0.21204199, -0.12672174 0.11443983 -0.21230355, -0.12672174 0.114305 -0.21257308, -0.13691401 0.11805989 -0.20506197, -0.13711134 0.11806016 -0.20506155, -0.13779622 0.11778629 -0.20560931, -0.13777223 0.11782317 -0.20553553, -0.13729613 0.11804 -0.20510168, -0.1376999 0.1178913 -0.20539919, -0.13745442 0.11800437 -0.20517313, -0.13759232 0.11795348 -0.20527484, -0.15556738 -0.02165021 -0.13446897, -0.15431261 -0.0238951 -0.13446921, -0.15507793 -0.021595061 -0.13446902, -0.1539562 -0.023759946 -0.13446906, -0.15395617 -0.026830018 -0.13446943, -0.15694803 -0.028334066 -0.13446948, -0.15357798 -0.026875913 -0.13446949, -0.15431258 -0.026694804 -0.13446952, -0.1546264 -0.026478261 -0.1344694, -0.15727785 -0.027739897 -0.13446963, -0.15021729 -0.032528132 -0.13447, -0.15644962 -0.022075042 -0.13446894, -0.15462628 -0.024111599 -0.13446929, -0.15603256 -0.021812901 -0.134469, -0.15715241 -0.02813977 -0.13446955, -0.15706015 -0.028247297 -0.13446955, -0.1572212 -0.028015971 -0.13446955, -0.15679792 -0.022423357 -0.13446905, -0.15487897 -0.024396896 -0.13446926, -0.15706003 -0.022840485 -0.13446912, -0.13782364 -0.032534778 -0.13447003, -0.13802379 -0.032510966 -0.13447006, -0.13762906 -0.03260687 -0.13447, -0.13744429 -0.032726556 -0.13447, -0.13730854 -0.032852203 -0.13447006, -0.13718286 -0.033003479 -0.13447, -0.15722263 -0.023305491 -0.13446909, -0.13880706 -0.032510921 -0.13447002, -0.13698548 -0.034582347 -0.13447012, -0.13698554 -0.033271432 -0.13447003, -0.14876413 -0.021594986 -0.134469, -0.15027678 -0.024396896 -0.13446908, -0.14828077 -0.021648735 -0.13446899, -0.14782083 -0.021807313 -0.13446902, -0.14740732 -0.022063106 -0.13446905, -0.1470601 -0.022403568 -0.13446905, -0.15052947 -0.024111718 -0.13446923, -0.15514725 -0.025104463 -0.13446926, -0.15727788 -0.023794949 -0.13446914, -0.15514734 -0.025485486 -0.1344694, -0.15084314 -0.023895085 -0.13446926, -0.15505612 -0.024734259 -0.13446932, -0.15009961 -0.024734348 -0.13446911, -0.15119958 -0.023759976 -0.13446909, -0.15000841 -0.025104433 -0.13446929, -0.1505295 -0.026478365 -0.13446927, -0.14981169 -0.032849595 -0.13447002, -0.15027678 -0.026193142 -0.13446932, -0.15157786 -0.023714021 -0.13446903, -0.15000841 -0.025485545 -0.13446929, -0.14948821 -0.03325358 -0.13447006, -0.15009955 -0.025855511 -0.1344694, -0.15084308 -0.026694819 -0.13446936, -0.15119949 -0.026830032 -0.13446939, -0.15157795 -0.026875973 -0.13446949, -0.14926305 -0.033719614 -0.13447005, -0.14914808 -0.034224138 -0.13447013, -0.15357789 -0.023713961 -0.13446909, -0.14913282 -0.034360334 -0.13447013, -0.14906967 -0.034582347 -0.13447024, -0.14910668 -0.034486324 -0.13447012, -0.1491226 -0.034423858 -0.1344703, -0.15487897 -0.026193097 -0.13446945, -0.15505612 -0.025855556 -0.13446933, -0.15726349 -0.027880862 -0.13446951, -0.1207644 0.1170616 -0.20661214, -0.12086874 0.11599961 -0.20606659, -0.12056541 0.12034878 -0.20828347, -0.13683072 -0.033157498 -0.13453962, -0.13679066 -0.033203721 -0.1345437, -0.13702816 -0.032889426 -0.13453965, -0.1309644 -0.033203408 -0.13845602, -0.11326924 0.10856222 -0.22043291, -0.10442826 -0.03253977 -0.21649414, -0.099833101 0.077716589 -0.28025073, -0.090666115 0.077716619 -0.28025067, -0.11359543 -0.032539904 -0.21649416, -0.11400831 -0.032738686 -0.21609171, -0.11450583 -0.032738701 -0.21487689, -0.10065341 0.078239799 -0.27905101, -0.10021481 0.077768698 -0.27999341, -0.10864106 -0.033041045 -0.20607054, -0.10310185 0.080869243 -0.27379146, -0.11728254 -0.032739133 -0.20809661, -0.11778009 -0.032739148 -0.20688185, -0.11191535 -0.033041432 -0.19807547, -0.1109767 -0.032540783 -0.20050395, -0.10560745 0.083917648 -0.2678467, -0.096440345 0.083917722 -0.26784673, -0.12014386 -0.032540768 -0.2005039, -0.10598913 0.083969682 -0.26758933, -0.12055686 -0.032739609 -0.20010154, -0.12105429 -0.032739669 -0.19888665, -0.1151894 -0.033041984 -0.1900803, -0.11425096 -0.032541215 -0.19250886, -0.1084947 0.087018237 -0.26164472, -0.099327505 0.087018296 -0.26164466, -0.12341818 -0.03254132 -0.19250891, -0.10887626 0.087070256 -0.26138747, -0.12383097 -0.032740057 -0.19210641, -0.12432852 -0.032740131 -0.19089156, -0.11846364 -0.033042371 -0.1820852, -0.11752525 -0.032541707 -0.18451363, -0.11138192 0.090118676 -0.2554428, -0.10221478 0.090118662 -0.25544286, -0.1266923 -0.032541782 -0.18451376, -0.11176342 0.090170771 -0.25518537, -0.12710524 -0.032740563 -0.18411119, -0.12760273 -0.032740593 -0.18289642, -0.12173796 -0.033042923 -0.17408997, -0.12079942 -0.032542244 -0.1765185, -0.11426908 0.093219295 -0.24924091, -0.10510188 0.09321931 -0.24924095, -0.12996662 -0.032542273 -0.17651847, -0.11465052 0.093271285 -0.24898355, -0.13037953 -0.03274107 -0.17611627, -0.13087708 -0.032741055 -0.17490128, -0.12501228 -0.033043429 -0.16609481, -0.12407365 -0.032542616 -0.16852333, -0.11715624 0.096319765 -0.24303897, -0.10798907 0.096319795 -0.24303888, -0.1332407 -0.032542631 -0.16852346, -0.11753783 0.09637174 -0.24278165, -0.1336537 -0.032741547 -0.16812102, -0.13415125 -0.032741502 -0.16690618, -0.12828639 -0.033043802 -0.15809987, -0.12734786 -0.032543138 -0.1605283, -0.12004337 0.099420249 -0.23683701, -0.11087629 0.099420324 -0.23683694, -0.13651499 -0.032543108 -0.16052833, -0.12042481 0.099472344 -0.23657967, -0.1369279 -0.032741904 -0.16012608, -0.13742554 -0.032742038 -0.15891117, -0.13156062 -0.033044413 -0.1501047, -0.13062206 -0.03254354 -0.15253322, -0.12293062 0.1025207 -0.23063515, -0.11376351 0.10252087 -0.23063493, -0.13978928 -0.032543644 -0.1525332, -0.12331221 0.1025728 -0.23037766, -0.14020219 -0.032742471 -0.1521308, -0.14069986 -0.032742545 -0.15091577, -0.13483489 -0.03304489 -0.14210957, -0.13389635 -0.032544076 -0.14453809, -0.12581763 0.10562119 -0.22443296, -0.11665058 0.10562126 -0.22443295, -0.1430636 -0.032544121 -0.14453813, -0.12619933 0.10567328 -0.22417568, -0.14347646 -0.032742813 -0.14413583, -0.14397392 -0.032742992 -0.14292079, -0.1463449 -0.032601088 -0.13651027, -0.1372081 -0.032844663 -0.13636939, -0.12870488 0.10872176 -0.21823122, -0.11953786 0.10872187 -0.21823099, -0.11896914 0.11980537 -0.20937072, -0.080498219 0.077334672 -0.29143167, -0.08033666 0.078318238 -0.29235703, -0.11896911 0.11864829 -0.20879246, -0.08046785 0.077298701 -0.29149514, -0.080437809 0.077256143 -0.29155481, -0.080391258 0.077176094 -0.29163975, -0.080246061 0.078204513 -0.29254347, -0.080108941 0.077639759 -0.29309291, -0.080361754 0.075848252 -0.29151857, -0.080127925 0.07736434 -0.29321745, -0.080152631 0.077067643 -0.293275, -0.080181599 0.076765567 -0.29326248, -0.080206305 0.076535285 -0.29320389, -0.080231935 0.076319277 -0.29310411, -0.094001055 -0.033992708 -0.2293155, -0.09402144 -0.033586934 -0.22823712, -0.094032884 -0.034231007 -0.22913857, -0.094063044 -0.034423053 -0.2289121, -0.094049335 -0.033711433 -0.22793828, -0.094045639 -0.033688143 -0.22796509, -0.094040155 -0.033658326 -0.22801386, -0.094030917 -0.033617973 -0.22811444, -0.094090104 -0.034558594 -0.22864793, -0.094108135 -0.034620911 -0.22842298, -0.094122589 -0.034641862 -0.22819026, -0.094156265 -0.034641936 -0.22756681, -0.14682758 -0.02221334 -0.14016913, -0.14639178 -0.022746891 -0.13989992, -0.14621475 -0.022963971 -0.13966484, -0.14682764 -0.022213787 -0.13476898, -0.13935477 -0.031365782 -0.13476969, -0.14602226 -0.023199856 -0.1394919, -0.15507799 -0.021294743 -0.1364689, -0.14876416 -0.021294981 -0.13476898, -0.14876419 -0.021294475 -0.14016901, -0.15507779 -0.021294996 -0.13476899, -0.15507796 -0.02129446 -0.14016894, -0.15757772 -0.027739972 -0.13476957, -0.15757778 -0.023794979 -0.13476922, -0.15757784 -0.023794949 -0.13646911, -0.1575779 -0.027739421 -0.1401695, -0.15757775 -0.023794577 -0.14016923, -0.14943087 -0.034393474 -0.14017019, -0.14943087 -0.034393594 -0.13477007, -0.14944607 -0.034257084 -0.14017011, -0.14944619 -0.034257576 -0.13477018, -0.15037599 -0.032782853 -0.13476984, -0.15710688 -0.028588071 -0.14016962, -0.15037596 -0.032782361 -0.14017001, -0.1571067 -0.028588533 -0.13476954, -0.13670668 -0.034644648 -0.13455501, -0.1309436 -0.033393428 -0.13842496, -0.13670668 -0.033393472 -0.13455488, -0.13073316 -0.034644544 -0.13856636, -0.13092631 -0.033394426 -0.13843645, -0.14648744 -0.024211079 -0.13929303, -0.14745224 -0.023029566 -0.14016913, -0.14607155 -0.024720252 -0.14016919, -0.14653096 -0.024157792 -0.13906969, -0.14652607 -0.024163857 -0.13915259, -0.14651132 -0.024181664 -0.13922779, -0.14653096 -0.024158046 -0.13676909, -0.14745218 -0.023029774 -0.13676913, -0.14843708 -0.034982055 -0.14047016, -0.14737067 -0.034981981 -0.14047015, -0.14913264 -0.034359962 -0.14047016, -0.14914808 -0.034223735 -0.14047019, -0.14855516 -0.034971997 -0.14047018, -0.14909634 -0.034517244 -0.14047003, -0.14867538 -0.034940243 -0.14047013, -0.14721975 -0.022839755 -0.14046897, -0.14705998 -0.022403002 -0.140469, -0.14880258 -0.034879088 -0.14047013, -0.14758286 -0.022483915 -0.14046909, -0.14740735 -0.022062525 -0.14046898, -0.14901954 -0.034670413 -0.14047019, -0.14891681 -0.034791782 -0.14047015, -0.14801538 -0.022216558 -0.14046918, -0.14782095 -0.021806777 -0.14046888, -0.14828074 -0.021648243 -0.14046896, -0.15687788 -0.027184412 -0.14046952, -0.15727782 -0.023794562 -0.14046915, -0.15687791 -0.02429457 -0.14046931, -0.14622083 -0.0240632 -0.14046915, -0.14849603 -0.02205056 -0.140469, -0.14876419 -0.021594346 -0.14046894, -0.15507776 -0.021594495 -0.14046903, -0.15727776 -0.027739465 -0.14046942, -0.15508953 -0.022052184 -0.14046901, -0.15685126 -0.027445987 -0.14046955, -0.15677261 -0.027696863 -0.14046955, -0.15556741 -0.021649674 -0.14046896, -0.15557572 -0.022222251 -0.14046897, -0.15726349 -0.027880281 -0.14046957, -0.15603229 -0.021812394 -0.14046901, -0.15722114 -0.028015524 -0.14046957, -0.15601191 -0.022496283 -0.140469, -0.15694812 -0.028333426 -0.14046971, -0.15647337 -0.028126538 -0.1404696, -0.15626547 -0.02828756 -0.14046963, -0.15664482 -0.027927026 -0.14046946, -0.15644959 -0.02207458 -0.14046888, -0.15679795 -0.022422835 -0.14046898, -0.15021735 -0.03252767 -0.14047, -0.15637609 -0.022860602 -0.14046896, -0.15715232 -0.028139353 -0.14046971, -0.15706009 -0.028246805 -0.14046958, -0.15705988 -0.022839978 -0.14046901, -0.14759025 -0.033693448 -0.14047003, -0.15665001 -0.023296595 -0.14046906, -0.15722263 -0.023305058 -0.14046912, -0.15682021 -0.023782745 -0.14046925, -0.14948818 -0.033253133 -0.14047007, -0.14981171 -0.032849088 -0.14046997, -0.14926308 -0.033719093 -0.14047004, -0.15610674 -0.028033257 -0.13676946, -0.15610677 -0.028032899 -0.14016955, -0.14743543 -0.033436403 -0.14017001, -0.14900136 -0.02229476 -0.13676904, -0.15457782 -0.022294581 -0.14016907, -0.14900133 -0.022294492 -0.14016898, -0.15457785 -0.02229476 -0.13676904, -0.15502292 -0.022344902 -0.13676906, -0.15502298 -0.022344738 -0.1401691, -0.15544567 -0.022492811 -0.13676909, -0.15544564 -0.022492573 -0.14016905, -0.15582496 -0.022731081 -0.13676906, -0.15582484 -0.022730887 -0.14016907, -0.15614155 -0.023047745 -0.13676922, -0.15614155 -0.023047477 -0.14016904, -0.15637976 -0.02342701 -0.13676922, -0.15637979 -0.023426831 -0.14016907, -0.15652773 -0.023849756 -0.13676919, -0.15652776 -0.023849517 -0.1401691, -0.15657783 -0.024294525 -0.14016922, -0.15657789 -0.024294719 -0.13676921, -0.15657777 -0.027184397 -0.1401694, -0.15657786 -0.027184486 -0.13676946, -0.15563414 -0.021357596 -0.13646875, -0.15563416 -0.021357253 -0.14016891, -0.15616256 -0.02154246 -0.1364689, -0.15616235 -0.021542192 -0.14016889, -0.1566366 -0.021840379 -0.13646892, -0.15663669 -0.021839917 -0.14016895, -0.1570324 -0.022236228 -0.13646905, -0.1570324 -0.022235781 -0.1401691, -0.1573303 -0.022710085 -0.13646899, -0.15733039 -0.022709772 -0.14016911, -0.15751514 -0.023238719 -0.13646899, -0.15751529 -0.023238227 -0.14016911, -0.15563416 -0.02135767 -0.13476902, -0.15616247 -0.021542579 -0.13476898, -0.15663663 -0.021840319 -0.13476899, -0.15703252 -0.022236302 -0.13476908, -0.15733042 -0.022710279 -0.1347692, -0.15751514 -0.023238674 -0.13476914, -0.13674051 -0.034646407 -0.13453424, -0.13675311 -0.033372045 -0.13452737, -0.13681793 -0.03461124 -0.13449901, -0.13680249 -0.033350512 -0.13450482, -0.13688537 -0.033317626 -0.1344801, -0.13690069 -0.034589529 -0.13447736, -0.13676384 -0.033254638 -0.13454038, -0.13095284 -0.033264935 -0.13843893, -0.13673949 -0.033307478 -0.13454196, -0.1309458 -0.033328578 -0.13842836, -0.14722234 -0.021826953 -0.13476898, -0.14722222 -0.021826506 -0.14016895, -0.14769238 -0.021535873 -0.14016895, -0.14769235 -0.02153632 -0.13476898, -0.14821485 -0.02135554 -0.14016886, -0.14821485 -0.021356001 -0.13476896, -0.14856198 -0.02234365 -0.13676894, -0.14856192 -0.022343352 -0.14016914, -0.14814404 -0.022487745 -0.13676909, -0.14814392 -0.022487611 -0.1401691, -0.14776796 -0.022720292 -0.13676906, -0.14776799 -0.022720054 -0.14016914, -0.084498197 0.051841721 -0.27526668, -0.0845218 0.051653594 -0.27515781, -0.090300798 0.0053544044 -0.24838509, -0.090324312 0.0051662326 -0.24827625, -0.095141321 -0.033555686 -0.22587283, -0.095112056 -0.033555537 -0.22585778, -0.095172942 -0.033555597 -0.22588198, -0.094224811 -0.033555448 -0.22802423, -0.092439413 0.077469781 -0.27735642, -0.096937746 0.077469781 -0.27735642, -0.095424265 0.077469781 -0.27735642, -0.095285416 0.077590421 -0.27711466, -0.095085621 0.077692702 -0.27691031, -0.094136953 0.079292729 -0.2737098, -0.094836563 0.077770382 -0.27675486, -0.094552904 0.077818811 -0.27665788, -0.098635286 0.079292715 -0.27370977, -0.099130034 0.079537913 -0.27368608, -0.10030669 0.080897197 -0.274472, -0.091320723 0.080242038 -0.27591336, -0.090965629 0.078223094 -0.27815017, -0.09051916 0.078424603 -0.27849627, -0.091451883 0.077930555 -0.27783895, -0.089854509 0.078667536 -0.2790626, -0.091953874 0.077561483 -0.27757823, -0.091987491 0.077534541 -0.27756274, -0.093246579 0.079537824 -0.27427176, -0.093662351 0.079333141 -0.27396503, -0.10057336 0.081021786 -0.27465856, -0.098875791 0.079198629 -0.27830505, -0.10047081 0.0810038 -0.27460194, -0.09877333 0.079180911 -0.27824855, -0.1003803 0.08096163 -0.27453855, -0.098682791 0.079138428 -0.27818513, -0.097360909 0.077645943 -0.27731472, -0.099039674 0.079454228 -0.27366555, -0.097271413 0.077583864 -0.27730751, -0.098923802 0.079381987 -0.27366164, -0.097128242 0.07751675 -0.27731684, -0.098790616 0.079327822 -0.27367538, -0.098712891 0.079306841 -0.2736904, -0.093741506 0.079315141 -0.27389601, -0.09212029 0.077484235 -0.27748212, -0.093827218 0.079300597 -0.27383533, -0.093920708 0.079288915 -0.2737861, -0.092276454 0.077461943 -0.27741072, -0.094027549 0.079284117 -0.27374399, -0.089615941 0.078837693 -0.2790367, -0.091082156 0.080412135 -0.27588713, -0.089703649 0.078795135 -0.27905601, -0.091169745 0.080369666 -0.27590683, -0.089784294 0.078737825 -0.27906501, -0.0912503 0.080312222 -0.27591562, -0.1250518 0.11157815 -0.20909524, -0.12464765 0.11150976 -0.20923224, -0.12664962 0.11060151 -0.21104874, -0.12672174 0.11073241 -0.21078695, -0.12464753 0.11008993 -0.2120723, -0.12429187 0.11019978 -0.2118526, -0.12400541 0.11034456 -0.21156318, -0.12505183 0.11002144 -0.21220939, -0.12672162 0.11086711 -0.21051742, -0.12380445 0.11051561 -0.21122095, -0.12578011 0.11134255 -0.20956649, -0.1260618 0.11129473 -0.2096622, -0.12664977 0.11099799 -0.21025577, -0.12630978 0.11121811 -0.20981541, -0.12370095 0.1107031 -0.2108455, -0.12650949 0.11111727 -0.21001725, -0.12370095 0.11089645 -0.21045887, -0.12380448 0.11108415 -0.2100836, -0.12577984 0.110257 -0.21173783, -0.12606165 0.1103048 -0.21164228, -0.12400535 0.11125518 -0.20974109, -0.12630975 0.11038134 -0.21148922, -0.12429193 0.1113999 -0.20945188, -0.12650961 0.11048219 -0.2112873, -0.094559193 0.076721147 -0.27881983, -0.095099956 0.076852366 -0.27855718, -0.09529981 0.076958343 -0.2783452, -0.094847918 0.076771572 -0.27871886, -0.095435113 0.077083185 -0.27809551, -0.09550032 0.077144101 -0.27761748, -0.09549427 0.077247575 -0.2775791, -0.095483184 0.077326253 -0.27752987, -0.095466256 0.077389777 -0.27747172, -0.09544751 0.077434018 -0.27741638, -0.12490815 0.11243442 -0.2086647, -0.12448329 0.11178069 -0.20901778, -0.12417915 0.11290301 -0.20868167, -0.1247184 0.11356987 -0.20830211, -0.12490821 0.11019075 -0.21315263, -0.12496713 0.10999885 -0.2125818, -0.12448335 0.11008091 -0.21241778, -0.12417924 0.11048567 -0.21351705, -0.12471831 0.11058211 -0.21427844, -0.12405744 0.11164929 -0.20928058, -0.12313539 0.11253063 -0.2094264, -0.12371442 0.11147608 -0.20962712, -0.12347388 0.11127116 -0.21003696, -0.12255597 0.11199273 -0.21050224, -0.12334991 0.11104645 -0.21048638, -0.12255603 0.11139573 -0.21169654, -0.12334996 0.11081517 -0.21094908, -0.12347382 0.11059058 -0.21139862, -0.12313527 0.11085787 -0.21277247, -0.12371433 0.11038567 -0.21180841, -0.12405741 0.11021233 -0.21215494, -0.12496713 0.11186267 -0.20885363, -0.1273905 0.11420725 -0.20828748, -0.12644184 0.11429821 -0.20804203, -0.12646428 0.1143644 -0.20797327, -0.12820601 0.11120446 -0.21429369, -0.12642115 0.11421946 -0.20809631, -0.12739053 0.11095287 -0.21479708, -0.12730679 0.11095759 -0.21462075, -0.12730682 0.11406909 -0.20839691, -0.12734705 0.11414471 -0.20834903, -0.12644181 0.11081119 -0.21501723, -0.12734693 0.11096463 -0.21471001, -0.12642106 0.11080739 -0.2149214, -0.12814373 0.11121048 -0.21421808, -0.12886286 0.11153634 -0.21363035, -0.12808651 0.1111981 -0.21413963, -0.12878573 0.11153457 -0.21357004, -0.12932324 0.11192843 -0.21284582, -0.12871474 0.11151518 -0.21350542, -0.12923563 0.11191782 -0.21280329, -0.1295605 0.11235864 -0.21198538, -0.12915492 0.1118903 -0.21275523, -0.12946737 0.11233816 -0.2119626, -0.12956035 0.11280164 -0.21109916, -0.12938142 0.11230156 -0.21193244, -0.12946725 0.11277111 -0.21109673, -0.12932324 0.11323163 -0.21023886, -0.1293816 0.11272515 -0.21108547, -0.12923563 0.11319134 -0.21025576, -0.12886274 0.11362396 -0.20945418, -0.12915483 0.11313637 -0.21026269, -0.12878573 0.11357473 -0.20948911, -0.1282059 0.1139556 -0.2087909, -0.12871456 0.11351131 -0.20951223, -0.12814379 0.11389884 -0.20884098, -0.12808645 0.11382852 -0.20887816, -0.12646434 0.11079594 -0.21511127, -0.12416506 0.11149798 -0.20934084, -0.1238479 0.11133783 -0.20966113, -0.1237767 0.1114011 -0.20963761, -0.12410772 0.11156832 -0.2093035, -0.12500596 0.10997236 -0.21239255, -0.123925 0.11128868 -0.20969591, -0.12362537 0.11114846 -0.21003988, -0.12498522 0.10997617 -0.21248828, -0.12371314 0.1111082 -0.21005687, -0.12498525 0.11177428 -0.20889169, -0.12410769 0.11018214 -0.21207635, -0.12451839 0.11169504 -0.20904997, -0.12451848 0.1100553 -0.21233003, -0.12455869 0.11161958 -0.20909762, -0.12455869 0.11004817 -0.21224092, -0.1242272 0.11144115 -0.20939091, -0.12502834 0.10998759 -0.21229835, -0.12500596 0.11169539 -0.20894599, -0.12377667 0.11034919 -0.21174213, -0.12460238 0.11155693 -0.20915937, -0.12416506 0.11016965 -0.21199773, -0.1250284 0.11162914 -0.20901474, -0.12460232 0.11005986 -0.2121539, -0.12354463 0.11054695 -0.21134664, -0.12384784 0.11032988 -0.2116774, -0.1242272 0.11017562 -0.21192223, -0.12342516 0.11076353 -0.21091312, -0.12362552 0.1105193 -0.21129856, -0.12392506 0.11032832 -0.21161701, -0.12342525 0.11098672 -0.21046659, -0.12351096 0.11072685 -0.2108832, -0.12371314 0.11050858 -0.21125612, -0.12354469 0.11120345 -0.21003315, -0.12351096 0.11094071 -0.21045521, -0.12360421 0.11070649 -0.21086037, -0.12360418 0.11091031 -0.21045277, -0.12821999 0.11777982 -0.2138692, -0.092954069 0.083049551 -0.28334007, -0.092403412 0.083223328 -0.2829926, -0.12808204 0.11806981 -0.21328935, -0.12819877 0.11748347 -0.21446191, -0.12372413 0.11861709 -0.21219479, -0.1232689 0.11840147 -0.21262579, -0.12801957 0.11719818 -0.21503282, -0.12294212 0.11814366 -0.21314186, -0.12428162 0.11877756 -0.21187383, -0.12490866 0.11887366 -0.21168129, -0.09358263 0.08294104 -0.28355718, -0.091712892 0.084606662 -0.28022578, -0.12556884 0.11890003 -0.21162881, -0.12622416 0.11885476 -0.21171917, -0.091531903 0.084316283 -0.28080642, -0.091514379 0.084014937 -0.28140894, -0.12683633 0.1187409 -0.21194702, -0.1273694 0.11856472 -0.21229948, -0.091661125 0.083720952 -0.28199732, -0.12779295 0.11833666 -0.21275556, -0.09196347 0.083451644 -0.28253594, -0.099460453 -0.0076417476 -0.23642075, -0.099056214 -0.0077744275 -0.23634401, -0.10113031 -0.0092792213 -0.23547389, -0.10113034 -0.0090183914 -0.23562469, -0.099056184 -0.010523021 -0.23475467, -0.098700613 -0.010310471 -0.23487754, -0.098413914 -0.010030434 -0.23503944, -0.099460423 -0.010655686 -0.23467776, -0.10105819 -0.0087651759 -0.23577115, -0.10018858 -0.0080980808 -0.23615685, -0.10047033 -0.0081906617 -0.23610334, -0.098213047 -0.0096990317 -0.23523101, -0.10091814 -0.0085340291 -0.23590472, -0.1007182 -0.0083388537 -0.23601782, -0.098109603 -0.009335801 -0.23544109, -0.098109603 -0.0089617223 -0.23565757, -0.10018861 -0.010199428 -0.23494183, -0.098213047 -0.0085983723 -0.23586768, -0.10047039 -0.010106891 -0.23499532, -0.098413944 -0.008267045 -0.23605908, -0.10071829 -0.0099587291 -0.23508087, -0.098700613 -0.0079869479 -0.23622113, -0.10091814 -0.0097634792 -0.23519383, -0.10105816 -0.0095324963 -0.23532748, -0.089331269 0.070137352 -0.28139699, -0.091193229 0.068148255 -0.28024685, -0.09133324 0.068379283 -0.28038043, -0.089735389 0.070269912 -0.28147364, -0.088975638 0.067601293 -0.27993047, -0.08868897 0.067881331 -0.28009245, -0.088488191 0.068212599 -0.28028393, -0.089331299 0.067388698 -0.27980745, -0.091405362 0.068632424 -0.28052682, -0.088384628 0.068575993 -0.28049403, -0.089735508 0.067255944 -0.2797308, -0.088384718 0.068950146 -0.2807104, -0.091405511 0.068893433 -0.28067756, -0.090463698 0.069813654 -0.28120971, -0.088488072 0.069313407 -0.28092057, -0.090745479 0.069721222 -0.28115636, -0.090463638 0.067712277 -0.27999473, -0.09133324 0.069146723 -0.28082407, -0.090993434 0.06957297 -0.28107059, -0.091193289 0.06937775 -0.28095782, -0.090745419 0.067804903 -0.28004813, -0.08868897 0.06964466 -0.28111207, -0.090993404 0.067952961 -0.28013384, -0.088975579 0.069924727 -0.28127402, -0.099316865 -0.0072640032 -0.23730147, -0.099375814 -0.0074178725 -0.23671952, -0.098891944 -0.0075766295 -0.23662758, -0.0985879 -0.0073095262 -0.23776792, -0.099126905 -0.0069708079 -0.23845661, -0.099316895 -0.011607468 -0.23478971, -0.099375755 -0.011026174 -0.23463292, -0.098891914 -0.010867387 -0.23472472, -0.098587781 -0.011989251 -0.23506197, -0.099126905 -0.012755096 -0.23511206, -0.098466188 -0.0078311116 -0.23648039, -0.097543895 -0.0080301166 -0.23735119, -0.098122925 -0.0081664771 -0.23628649, -0.097882509 -0.0085630864 -0.23605704, -0.096964717 -0.0090714097 -0.23674919, -0.097758651 -0.0089981109 -0.23580548, -0.096964598 -0.010227337 -0.2360808, -0.097758591 -0.0094460249 -0.23554654, -0.097882599 -0.0098809451 -0.23529515, -0.097543895 -0.011268571 -0.23547867, -0.098122925 -0.010277554 -0.2350657, -0.098466098 -0.010612935 -0.23487188, -0.089591861 0.070647806 -0.28235424, -0.089166999 0.070335001 -0.28168046, -0.088862896 0.070602417 -0.28282106, -0.08940196 0.070940942 -0.28350985, -0.089591801 0.066304296 -0.27984273, -0.08965084 0.066885591 -0.2796858, -0.089166939 0.067044348 -0.27977765, -0.088862807 0.065922439 -0.28011483, -0.08940196 0.065156624 -0.28016496, -0.088741183 0.070080489 -0.28153336, -0.08781904 0.069881737 -0.2824043, -0.088398069 0.069745302 -0.28133947, -0.088157535 0.069348693 -0.28111011, -0.087239742 0.068840265 -0.28180206, -0.088033676 0.068913698 -0.28085864, -0.087239653 0.067684546 -0.2811338, -0.088033766 0.068465799 -0.28059971, -0.088157535 0.068030834 -0.280348, -0.087818921 0.066643089 -0.28053153, -0.088398099 0.067634225 -0.2801187, -0.088741094 0.067298785 -0.27992478, -0.08965075 0.070493788 -0.28177226, -0.098573655 -0.0078820437 -0.23632574, -0.098185271 -0.0081725866 -0.23621109, -0.098516375 -0.0078491718 -0.23639807, -0.099414587 -0.010835633 -0.23461768, -0.098333627 -0.0082238764 -0.23609525, -0.098034143 -0.0085586756 -0.23593438, -0.098256469 -0.0081919879 -0.23614645, -0.098121762 -0.0085733533 -0.23589326, -0.099393904 -0.010931313 -0.23461567, -0.099393994 -0.0074504465 -0.23662877, -0.098516345 -0.010532647 -0.23484637, -0.09892717 -0.0076037496 -0.23654008, -0.09892717 -0.010778204 -0.23470446, -0.098967463 -0.0076467842 -0.23646179, -0.098635882 -0.0079285949 -0.23626605, -0.098967254 -0.010688722 -0.23470269, -0.099436969 -0.010742486 -0.2346388, -0.099414617 -0.0075000525 -0.23654674, -0.098185271 -0.010209247 -0.23503327, -0.099010974 -0.0077044815 -0.23639557, -0.098573655 -0.010453522 -0.23483871, -0.099437147 -0.0075645298 -0.23647657, -0.099011004 -0.010602638 -0.2347196, -0.097953409 -0.0098265857 -0.23525473, -0.098256439 -0.010143563 -0.23501799, -0.098635823 -0.01037848 -0.23484929, -0.097833782 -0.0094069541 -0.23549728, -0.098034054 -0.0097769201 -0.23522995, -0.098333657 -0.010083199 -0.23502003, -0.097833842 -0.0089748353 -0.23574722, -0.097919643 -0.0093748122 -0.23546246, -0.098121762 -0.0097338706 -0.23522195, -0.09795332 -0.0085553378 -0.23598993, -0.097919673 -0.0089606494 -0.23570204, -0.098012775 -0.0093508065 -0.23544358, -0.098012745 -0.008956328 -0.23567173, -0.1008299 -0.0068050474 -0.23911759, -0.10261461 -0.012808025 -0.23573254, -0.10085046 -0.0067554563 -0.23919967, -0.10171545 -0.0070959032 -0.23894946, -0.10175571 -0.0070527494 -0.23902778, -0.10179922 -0.013295233 -0.23545082, -0.10171551 -0.013119727 -0.2354662, -0.10082984 -0.013410449 -0.23529787, -0.1008504 -0.013506234 -0.23529585, -0.10175559 -0.013209134 -0.23546757, -0.10255232 -0.012733072 -0.23574306, -0.10327151 -0.012166083 -0.23610376, -0.10249504 -0.012653917 -0.23573537, -0.10319445 -0.012105823 -0.23610575, -0.10373187 -0.011406675 -0.23654291, -0.10312322 -0.012040049 -0.2360905, -0.10364419 -0.011363685 -0.23653506, -0.10396904 -0.010574058 -0.23702452, -0.10356355 -0.01131399 -0.23651022, -0.10387588 -0.010549918 -0.23700535, -0.10396907 -0.0097163022 -0.23752041, -0.10379016 -0.010517836 -0.23697065, -0.10387585 -0.0097119808 -0.23749013, -0.10373196 -0.0088836849 -0.23800196, -0.10379007 -0.0096977353 -0.23744486, -0.10364425 -0.0088982582 -0.23796056, -0.10327151 -0.0081242025 -0.23844104, -0.10356343 -0.0089017153 -0.23790534, -0.10319433 -0.0081560463 -0.23838961, -0.10261461 -0.0074823052 -0.23881239, -0.10312316 -0.0081754476 -0.23832503, -0.10255238 -0.0075287372 -0.23875239, -0.10179925 -0.0069950819 -0.239094, -0.10249507 -0.0075616688 -0.23868009, -0.1008729 -0.013599351 -0.23527491, -0.10087296 -0.0066909343 -0.23926997, -0.08884871 0.070029706 -0.28137863, -0.088460326 0.069739074 -0.28126401, -0.08879137 0.070062608 -0.28145099, -0.089202315 0.067133576 -0.27975738, -0.08966887 0.066980362 -0.27966857, -0.089689642 0.067076087 -0.27967072, -0.088608623 0.069687814 -0.28114808, -0.088396907 0.06933853 -0.28094614, -0.088309139 0.069353074 -0.28098738, -0.088531524 0.069719717 -0.28119937, -0.089669019 0.070461139 -0.2816816, -0.08879137 0.067379117 -0.27989942, -0.089202225 0.070307985 -0.28159299, -0.089242339 0.070264786 -0.28151476, -0.08924228 0.067222923 -0.27975571, -0.088910908 0.069983244 -0.28131896, -0.089712203 0.067169204 -0.27969182, -0.089689612 0.070411772 -0.28159952, -0.088460416 0.067702502 -0.28008628, -0.089286029 0.070207268 -0.28144872, -0.08884865 0.067458242 -0.27989161, -0.089712113 0.07034719 -0.28152949, -0.08928597 0.067309111 -0.27977264, -0.088228434 0.068085238 -0.28030762, -0.088531554 0.067768186 -0.2800709, -0.088910788 0.067533225 -0.27990222, -0.088108897 0.06850481 -0.2805503, -0.088309169 0.068134949 -0.28028297, -0.088608623 0.067828581 -0.28007293, -0.088108897 0.068936944 -0.28080028, -0.088194728 0.068536878 -0.28051561, -0.088397026 0.068177819 -0.28027505, -0.088228315 0.069356412 -0.2810427, -0.088194728 0.068950996 -0.28075498, -0.08828789 0.068560958 -0.28049654, -0.08828789 0.068955421 -0.28072459, -0.09199056 0.070815921 -0.28400236, -0.091104835 0.064501271 -0.28035089, -0.09282741 0.070383042 -0.28380537, -0.092030734 0.070859015 -0.28408074, -0.091125429 0.064405516 -0.28034878, -0.092770219 0.07035014 -0.28373301, -0.092030704 0.0647026 -0.28052068, -0.09114787 0.064312339 -0.28032798, -0.091125518 0.071156085 -0.28425246, -0.092074215 0.064616516 -0.28050384, -0.092074275 0.070916742 -0.2841469, -0.0911479 0.071220845 -0.28432274, -0.092889637 0.065103725 -0.28078556, -0.091104865 0.071106762 -0.28417051, -0.09199056 0.064791888 -0.28051901, -0.09282741 0.065178826 -0.28079593, -0.093546718 0.065745667 -0.28115666, -0.09277007 0.065257981 -0.28078842, -0.093469352 0.065806106 -0.2811588, -0.094006985 0.066505089 -0.28159574, -0.093398273 0.065871701 -0.28114334, -0.093919277 0.066548169 -0.28158778, -0.094244093 0.067337826 -0.28207731, -0.093838483 0.06659779 -0.28156316, -0.094150871 0.067361787 -0.28205833, -0.094244093 0.068195432 -0.28257322, -0.094065189 0.067393959 -0.28202367, -0.09415102 0.068199873 -0.28254306, -0.094006956 0.069028199 -0.28305483, -0.09406516 0.068214029 -0.28249782, -0.093919247 0.069013625 -0.28301352, -0.093546599 0.069787592 -0.283494, -0.093838423 0.069010228 -0.28295815, -0.093469352 0.069755644 -0.28344262, -0.092889667 0.070429564 -0.28386521, -0.093398184 0.069736332 -0.28337801, -0.099225342 -0.015083224 -0.24048115, -0.098600656 -0.014876112 -0.24060085, -0.092898518 0.065394461 -0.28701782, -0.091481298 0.064351797 -0.28641486, -0.091225475 0.064101934 -0.2862705, -0.0916605 0.064647466 -0.28658593, -0.091752738 0.064971656 -0.28677344, -0.091752708 0.065305561 -0.28696632, -0.092748374 0.065953434 -0.28734118, -0.10147777 -0.012606144 -0.24191354, -0.1014778 -0.01293996 -0.24172048, -0.087430388 0.064882904 -0.28672206, -0.097155422 -0.013028771 -0.24166904, -0.10138547 -0.012281969 -0.2421011, -0.10120621 -0.0119863 -0.24227202, -0.10095048 -0.011736333 -0.24241652, -0.10063303 -0.011546552 -0.24252628, -0.088368297 0.066941261 -0.28791225, -0.087922037 0.066516727 -0.2876668, -0.087606311 0.066012144 -0.28737509, -0.088918775 0.067260951 -0.28809726, -0.10138544 -0.013264254 -0.24153304, -0.10027224 -0.014118001 -0.24103925, -0.087439179 0.065456897 -0.28705394, -0.10120615 -0.013559893 -0.24136201, -0.089541674 0.067457438 -0.28821087, -0.100633 -0.013999537 -0.24110773, -0.10095048 -0.0138098 -0.24121736, -0.090547383 0.063793749 -0.28609216, -0.090200692 0.067519069 -0.28824645, -0.097307533 -0.013592765 -0.24134302, -0.1002723 -0.011428311 -0.24259469, -0.09090808 0.063912153 -0.28616077, -0.090547383 0.066483587 -0.2876476, -0.090857714 0.067442298 -0.28820205, -0.09761253 -0.014108062 -0.24104501, -0.090908021 0.066365093 -0.28757918, -0.091474444 0.067231745 -0.28808033, -0.091225475 0.066175401 -0.28746933, -0.092015028 0.066899657 -0.28788817, -0.098052353 -0.014544532 -0.24079263, -0.091481209 0.065925568 -0.28732485, -0.092448086 0.06646511 -0.28763688, -0.0916605 0.06562978 -0.28715402, -0.1002723 -0.010677412 -0.24129611, -0.10027242 -0.013367087 -0.2397408, -0.100633 -0.013248637 -0.23980927, -0.10063303 -0.010795787 -0.2412276, -0.10120621 -0.012809113 -0.24006343, -0.1013855 -0.011530906 -0.24080239, -0.10120621 -0.011235341 -0.2409735, -0.10147765 -0.01185523 -0.24061495, -0.10147774 -0.01218912 -0.24042185, -0.10138547 -0.012513474 -0.24023446, -0.10095045 -0.013058975 -0.23991883, -0.10095042 -0.010985389 -0.24111798, -0.09090814 0.067115992 -0.28628057, -0.090547264 0.067234486 -0.28634918, -0.091225445 0.06692633 -0.28617084, -0.091481239 0.066676348 -0.28602636, -0.09166047 0.066380739 -0.28585541, -0.090547383 0.064544648 -0.28479379, -0.091660589 0.065398335 -0.2852875, -0.091752887 0.06605655 -0.28566808, -0.091752768 0.065722674 -0.28547496, -0.090908021 0.064663053 -0.28486216, -0.091225445 0.064852804 -0.28497183, -0.091481209 0.065102786 -0.28511637, -0.13686831 0.12126294 -0.20649596, -0.13702384 0.12009749 -0.20590656, -0.13703948 0.12125099 -0.20654272, -0.13718227 0.11797158 -0.20480287, -0.1372429 0.12006646 -0.20597647, -0.13724333 0.12121487 -0.20664094, -0.13734746 0.1169174 -0.20427524, -0.13735303 0.11795412 -0.20484409, -0.1374436 0.12001181 -0.2060933, -0.13741811 0.1211572 -0.20677741, -0.13756374 0.11689284 -0.20435067, -0.13753328 0.11791839 -0.20492214, -0.13760811 0.11993681 -0.20624879, -0.13755482 0.12108134 -0.20694473, -0.13775659 0.11684553 -0.20446777, -0.13769604 0.11786599 -0.2050328, -0.13772435 0.11984856 -0.20642886, -0.13764615 0.1209909 -0.20713432, -0.13791549 0.11677805 -0.20462038, -0.13784292 0.11779162 -0.20518632, -0.13768737 0.12089089 -0.20733626, -0.13803217 0.11669387 -0.2048004, -0.13795415 0.11769667 -0.2053795, -0.13767643 0.12078634 -0.20753987, -0.13810018 0.11659753 -0.20499833, -0.13811609 0.11649404 -0.20520341, -0.13809326 0.11641516 -0.20535573, -0.080307752 0.076312602 -0.29177421, -0.08029449 0.076458246 -0.29183233, -0.080287814 0.076612875 -0.29185522, -0.080116361 0.077845469 -0.29292312, -0.08029142 0.076769769 -0.29184383, -0.080308914 0.076920077 -0.2918005, -0.080162376 0.078035966 -0.29273692, -0.080341965 0.077056706 -0.2917307, -0.1205152 0.11595576 -0.20613128, -0.12027746 0.11700198 -0.20672162, -0.12018129 0.11588435 -0.20625168, -0.119865 0.11689958 -0.20691781, -0.1198023 0.1157575 -0.20647942, -0.11954522 0.11677274 -0.2071646, -0.11949259 0.11559656 -0.20677887, -0.11932361 0.11664292 -0.2074192, -0.11917028 0.11997002 -0.20904137, -0.11917016 0.11881296 -0.20846277, -0.1194436 0.12011233 -0.20875667, -0.11944366 0.11895522 -0.20817833, -0.11977753 0.12022597 -0.20852925, -0.11977747 0.11906898 -0.20795085, -0.12015697 0.12030596 -0.20836918, -0.12015694 0.11914888 -0.20779072, -0.14954624 -0.033818424 -0.14017002, -0.14954624 -0.033818841 -0.13477008, -0.14974192 -0.033413082 -0.14016999, -0.14974189 -0.033413559 -0.13476987, -0.15002319 -0.033061802 -0.14017002, -0.15002328 -0.033062235 -0.13477004, -0.14939782 -0.034559309 -0.14017026, -0.14939588 -0.034566686 -0.13477013, -0.14933363 -0.0347251 -0.14017011, -0.1493302 -0.034732252 -0.13477017, -0.1492371 -0.034882352 -0.13477036, -0.14922646 -0.034895927 -0.14017011, -0.14906591 -0.035059974 -0.13494793, -0.14908448 -0.035044283 -0.14017023, -0.14889568 -0.035170764 -0.14017017, -0.14889377 -0.035171911 -0.13505986, -0.14871687 -0.035242483 -0.13513044, -0.14866605 -0.035255566 -0.14017016, -0.14857677 -0.035272509 -0.13516058, -0.1572668 -0.028464243 -0.14016965, -0.15726674 -0.028464794 -0.1347696, -0.15739849 -0.028310761 -0.14016959, -0.15739858 -0.028311282 -0.13476975, -0.15749684 -0.02813375 -0.14016955, -0.1574969 -0.028134301 -0.13476944, -0.15755731 -0.02794075 -0.14016949, -0.15755737 -0.027941212 -0.13476959, -0.15626678 -0.027909189 -0.14016964, -0.15626663 -0.027909473 -0.13676953, -0.15639848 -0.027755827 -0.13676943, -0.15639856 -0.027755499 -0.14016955, -0.15649688 -0.02757898 -0.13676949, -0.15649685 -0.027578637 -0.14016953, -0.15655741 -0.027385935 -0.13676944, -0.15655744 -0.027385622 -0.14016958, -0.10017765 0.077746913 -0.28005877, -0.11391619 -0.032656491 -0.21627499, -0.10012603 0.077729166 -0.28011972, -0.10006177 0.077716634 -0.28017217, -0.11381295 -0.03259927 -0.2163942, -0.09998849 0.077710345 -0.28021264, -0.11372608 -0.032567084 -0.21645512, -0.099910617 0.077710554 -0.28023881, -0.11365974 -0.032550216 -0.21648248, -0.10068035 0.078271747 -0.27896398, -0.11454526 -0.032800958 -0.21473157, -0.10068497 0.078307211 -0.27887648, -0.11456123 -0.032868668 -0.21456754, -0.11455289 -0.032917187 -0.21444586, -0.10063115 0.078379154 -0.27871984, -0.11452624 -0.032961324 -0.21433121, -0.1144875 -0.032994077 -0.21424165, -0.10057449 0.078413889 -0.27865487, -0.11445084 -0.033013627 -0.21418536, -0.10050347 0.078444123 -0.27860564, -0.11440894 -0.033028454 -0.21413986, -0.11436364 -0.033038482 -0.21410549, -0.10042486 0.07846798 -0.27857482, -0.11431631 -0.033043697 -0.21408206, -0.10035276 0.078483447 -0.2785618, -0.11426318 -0.033044696 -0.21406807, -0.11693391 -0.032550663 -0.20848744, -0.1027979 0.080811039 -0.27403677, -0.1170004 -0.032567516 -0.20846003, -0.10287562 0.080810875 -0.2740106, -0.11708724 -0.032599688 -0.20839931, -0.10294905 0.080817223 -0.27397025, -0.11719039 -0.032656953 -0.20827988, -0.10301316 0.080829665 -0.27391782, -0.10306472 0.080847532 -0.2738567, -0.1032427 0.08158347 -0.27236021, -0.11760393 -0.033043146 -0.20609237, -0.10331413 0.081567943 -0.27237326, -0.11765417 -0.033035934 -0.2061211, -0.10339886 0.081541657 -0.27240819, -0.11770171 -0.033023268 -0.2061628, -0.11774459 -0.033004642 -0.20621778, -0.10347015 0.081510037 -0.27246058, -0.11778075 -0.032980651 -0.20628498, -0.1178157 -0.032940924 -0.20639075, -0.1178343 -0.03288871 -0.20652379, -0.11783066 -0.032833099 -0.20666052, -0.11781117 -0.032784402 -0.20677663, -0.1202082 -0.03255114 -0.20049222, -0.10568511 0.083911628 -0.2678349, -0.12027463 -0.032567918 -0.20046492, -0.10576296 0.083911389 -0.26780856, -0.12036145 -0.03260015 -0.20040399, -0.10583624 0.083917856 -0.2677682, -0.12046477 -0.032657325 -0.20028479, -0.10590047 0.083930284 -0.26771581, -0.10595202 0.083948076 -0.26765478, -0.1061298 0.084684044 -0.26615816, -0.12087828 -0.033043608 -0.19809726, -0.10620126 0.084668398 -0.26617151, -0.12092829 -0.03303647 -0.19812582, -0.10628599 0.084642202 -0.26620632, -0.12097588 -0.033023611 -0.19816768, -0.12101877 -0.033005118 -0.19822262, -0.10635713 0.084610552 -0.26625866, -0.12105498 -0.032981068 -0.19828989, -0.12109002 -0.032941401 -0.19839559, -0.12110844 -0.032889247 -0.19852863, -0.12110481 -0.032833591 -0.19866529, -0.12108535 -0.032785028 -0.1987813, -0.12348235 -0.032551646 -0.19249718, -0.10857216 0.087012082 -0.26163292, -0.12354878 -0.03256844 -0.19246981, -0.10864991 0.087011918 -0.26160666, -0.1236355 -0.032600656 -0.19240892, -0.10872334 0.087018237 -0.26156628, -0.12373874 -0.032657877 -0.19228971, -0.10878757 0.087030604 -0.26151386, -0.10883912 0.087048531 -0.26145285, -0.10901693 0.087784484 -0.25995627, -0.12415257 -0.03304407 -0.19010206, -0.10908842 0.087768942 -0.25996953, -0.12420252 -0.033036813 -0.1901308, -0.10917315 0.087742507 -0.26000434, -0.12425002 -0.033024102 -0.19017251, -0.12429291 -0.033005655 -0.19022749, -0.10924441 0.087711141 -0.26005667, -0.12432921 -0.03298153 -0.1902948, -0.12436429 -0.032941848 -0.19040062, -0.12438279 -0.032889664 -0.19053368, -0.12437901 -0.032834098 -0.19067022, -0.12435946 -0.032785431 -0.1907863, -0.12675664 -0.032552153 -0.18450208, -0.11145926 0.090112597 -0.255431, -0.12682313 -0.032568902 -0.18447466, -0.11153722 0.090112478 -0.25540465, -0.12690997 -0.032601058 -0.18441378, -0.11161053 0.090118796 -0.25536436, -0.12701306 -0.032658368 -0.18429466, -0.1116747 0.090131313 -0.25531191, -0.11172628 0.090149194 -0.25525087, -0.11190408 0.090884954 -0.25375426, -0.12742677 -0.033044562 -0.182107, -0.1119757 0.090869427 -0.25376755, -0.12747675 -0.033037394 -0.18213566, -0.1120604 0.090843111 -0.2538023, -0.12752441 -0.033024654 -0.18217745, -0.12756732 -0.033006057 -0.18223229, -0.1121316 0.090811521 -0.25385469, -0.12760356 -0.032981977 -0.18229964, -0.12763849 -0.032942399 -0.18240538, -0.12765691 -0.03289026 -0.18253843, -0.12765336 -0.032834604 -0.182675, -0.12763372 -0.032785878 -0.18279114, -0.13003093 -0.032552645 -0.17650697, -0.11434668 0.093213215 -0.24922898, -0.1300973 -0.032569483 -0.17647958, -0.11442435 0.093212977 -0.24920279, -0.13018414 -0.032601655 -0.17641859, -0.11449772 0.093219295 -0.24916247, -0.13028732 -0.032658875 -0.17629932, -0.11456198 0.093231812 -0.24911001, -0.11461347 0.093249694 -0.24904898, -0.11479133 0.093985572 -0.24755234, -0.13070086 -0.033044994 -0.17411183, -0.11486289 0.093969941 -0.24756567, -0.1307511 -0.033037916 -0.17414045, -0.11494756 0.093943685 -0.24760057, -0.13079849 -0.033025116 -0.17418219, -0.13084152 -0.033006743 -0.17423707, -0.11501873 0.093912125 -0.24765284, -0.13087776 -0.032982543 -0.17430449, -0.13091272 -0.032942817 -0.17441031, -0.13093114 -0.032890618 -0.17454319, -0.13092753 -0.032835066 -0.17468004, -0.13090807 -0.032786354 -0.1747959, -0.11767852 0.097086012 -0.24135046, -0.13397521 -0.033045471 -0.1661167, -0.11775014 0.097070441 -0.24136379, -0.13402525 -0.033038348 -0.16614546, -0.11783469 0.09704417 -0.24139862, -0.1340729 -0.033025563 -0.16618727, -0.1341157 -0.033007041 -0.16624212, -0.11790606 0.097012505 -0.24145076, -0.13415182 -0.032982901 -0.16630954, -0.13418692 -0.032943189 -0.16641532, -0.13420543 -0.03289102 -0.16654804, -0.13420179 -0.032835439 -0.16668493, -0.1341823 -0.032786772 -0.16680112, -0.13330519 -0.032552883 -0.1685119, -0.1172336 0.09631367 -0.24302703, -0.13337153 -0.032569826 -0.16848455, -0.11731154 0.096313566 -0.24300094, -0.1334582 -0.032602012 -0.16842352, -0.11738476 0.09631975 -0.24296048, -0.13356161 -0.032659352 -0.16830443, -0.11744902 0.096332386 -0.24290803, -0.1175006 0.096350178 -0.24284691, -0.13657936 -0.03255336 -0.16051665, -0.12012085 0.0994142 -0.23682497, -0.13664576 -0.032570288 -0.16048935, -0.12019861 0.09941408 -0.23679881, -0.13673264 -0.032602549 -0.16042851, -0.12027195 0.099420309 -0.23675837, -0.13683587 -0.032659769 -0.1603093, -0.12033626 0.099432737 -0.23670606, -0.12038785 0.099450707 -0.23664506, -0.1205658 0.1001866 -0.23514831, -0.13724938 -0.033045918 -0.15812166, -0.12063724 0.10017097 -0.23516168, -0.13729954 -0.033038661 -0.15815023, -0.12072197 0.10014476 -0.23519635, -0.1373471 -0.03302592 -0.15819208, -0.13738999 -0.033007428 -0.15824696, -0.1207931 0.10011318 -0.23524903, -0.13742611 -0.032983348 -0.15831438, -0.13746125 -0.032943726 -0.15842007, -0.13747969 -0.032891437 -0.15855309, -0.137476 -0.032835916 -0.1586898, -0.13745648 -0.032787308 -0.15880594, -0.13985366 -0.032554016 -0.15252164, -0.12300822 0.10251465 -0.23062326, -0.13992006 -0.032570705 -0.15249428, -0.12308583 0.10251462 -0.23059689, -0.14000693 -0.032603011 -0.15243331, -0.12315923 0.10252084 -0.23055658, -0.14011002 -0.03266032 -0.15231407, -0.12322354 0.1025334 -0.23050414, -0.12327513 0.1025511 -0.23044311, -0.1234529 0.10328706 -0.2289463, -0.14052364 -0.03304638 -0.15012652, -0.12352434 0.10327154 -0.22895975, -0.1405738 -0.033039197 -0.15015528, -0.12360898 0.10324521 -0.22899455, -0.14062127 -0.033026487 -0.15019681, -0.14066428 -0.033007964 -0.15025172, -0.12368029 0.1032137 -0.22904681, -0.14070043 -0.032983899 -0.15031926, -0.14073557 -0.032944173 -0.15042503, -0.14075395 -0.032892019 -0.15055795, -0.14075035 -0.032836407 -0.15069468, -0.14073077 -0.032787755 -0.15081066, -0.12633997 0.10638763 -0.22274452, -0.1437979 -0.033046961 -0.14213143, -0.12641141 0.10637198 -0.22275776, -0.14384815 -0.033039704 -0.14216, -0.12649637 0.10634567 -0.22279269, -0.1438956 -0.033026889 -0.14220184, -0.14393845 -0.033008367 -0.14225669, -0.12656751 0.10631423 -0.22284514, -0.14397472 -0.032984361 -0.14232412, -0.14400977 -0.032944709 -0.1424299, -0.14402828 -0.03289254 -0.14256281, -0.14402443 -0.032836899 -0.14269951, -0.14400503 -0.032788172 -0.14281565, -0.14312795 -0.032554358 -0.14452656, -0.12589523 0.10561523 -0.22442116, -0.14319432 -0.032571301 -0.14449909, -0.12597308 0.10561511 -0.22439487, -0.14328122 -0.032603487 -0.14443818, -0.12604639 0.10562131 -0.22435452, -0.14338446 -0.032660708 -0.14431897, -0.12611061 0.10563374 -0.22430213, -0.12616214 0.10565171 -0.22424115, -0.1290493 0.10875224 -0.21803927, -0.12899765 0.10873443 -0.21810012, -0.12893361 0.10872182 -0.21815257, -0.12886018 0.1087155 -0.21819295, -0.12878236 0.10871574 -0.21821921, -0.12955219 0.10927698 -0.2169445, -0.12955669 0.10931242 -0.216857, -0.1295028 0.10938431 -0.21670026, -0.12944612 0.10941908 -0.21663536, -0.14587817 -0.022646338 -0.14021309, -0.12937531 0.10944936 -0.21658631, -0.14581999 -0.022834927 -0.1400512, -0.12929648 0.1094732 -0.21655525, -0.12922451 0.10948856 -0.21654221, -0.11288884 0.10854493 -0.22085321, -0.13064435 -0.033322304 -0.13873555, -0.11295438 0.10857327 -0.22075507, -0.13077444 -0.033261985 -0.13859154, -0.11308873 0.10858925 -0.22059652, -0.13093069 -0.033211291 -0.13847582, -0.13092482 -0.033270776 -0.13845639, -0.13092351 -0.03333208 -0.13844331, -0.13077146 -0.033388436 -0.13856445, -0.13064277 -0.033386514 -0.13872185, -0.13058004 -0.034623802 -0.13869314, -0.13045514 -0.034604013 -0.13884763, -0.08432579 0.052125886 -0.27516717, -0.084324807 0.052101314 -0.27520919, -0.084335476 0.052078351 -0.27525106, -0.0843575 0.052058771 -0.27529007, -0.084389359 0.05204317 -0.27532363, -0.084429115 0.052032813 -0.27535003, -0.084474355 0.052028283 -0.27536765, -0.084426939 0.051503032 -0.27496856, -0.084458649 0.05148752 -0.27500224, -0.084498465 0.051477209 -0.27502877, -0.084543765 0.051472634 -0.27504641, -0.084404945 0.051522732 -0.27492976, -0.084456742 0.051845148 -0.27525163, -0.084390074 0.051864848 -0.27520207, -0.084351689 0.051897511 -0.27513447, -0.084395111 0.051570132 -0.2748456, -0.084394127 0.051545605 -0.27488783, -0.090128422 0.0056385547 -0.2482855, -0.090127349 0.0056140423 -0.24832775, -0.090138108 0.0055911392 -0.24836951, -0.090160102 0.0055714995 -0.24840835, -0.090191931 0.0055559129 -0.24844217, -0.090231538 0.0055456161 -0.24846841, -0.090276957 0.0055410862 -0.24848609, -0.090229422 0.0050157309 -0.24808712, -0.090261281 0.0050001591 -0.24812073, -0.090300918 0.0049899668 -0.24814704, -0.090346336 0.0049853176 -0.24816468, -0.090207517 0.0050355196 -0.2480482, -0.090259343 0.005357936 -0.24837008, -0.090192616 0.0053775907 -0.24832036, -0.09015432 0.0054103285 -0.24825284, -0.090197712 0.0050828457 -0.24796422, -0.090196729 0.0050582737 -0.24800634, -0.095041275 -0.033699319 -0.22552392, -0.095030397 -0.03366366 -0.2255886, -0.095027804 -0.03362219 -0.22567052, -0.095034957 -0.033596203 -0.22572729, -0.095047772 -0.033578143 -0.22577173, -0.095060736 -0.033567965 -0.22580026, -0.095076233 -0.033560961 -0.22582416, -0.095093429 -0.033556923 -0.22584337, -0.14719355 -0.028333634 -0.13647701, -0.1466969 -0.024356186 -0.1364768, -0.14713067 -0.028341562 -0.1364993, -0.14663404 -0.024364024 -0.13649894, -0.14707422 -0.028348535 -0.13653494, -0.14657766 -0.024371058 -0.13653459, -0.14702716 -0.028354347 -0.1365826, -0.14653045 -0.02437678 -0.13658215, -0.14699155 -0.028358847 -0.13663937, -0.14649495 -0.02438122 -0.13663916, -0.14696962 -0.02836147 -0.13670279, -0.14647308 -0.024384037 -0.13670248, -0.11097881 -0.035244539 -0.2285859, -0.094799519 -0.035224617 -0.22868164, -0.11089358 -0.035148695 -0.22893223, -0.094774991 -0.035070926 -0.22911189, -0.11080059 -0.034940124 -0.22933863, -0.094746381 -0.034823611 -0.22949579, -0.1107294 -0.034644753 -0.22968699, -0.094722182 -0.034571722 -0.22975206, -0.096899629 0.076298296 -0.29387569, -0.080895394 0.076460853 -0.29393223, -0.096896559 0.076578647 -0.29396355, -0.080864727 0.076918781 -0.29401296, -0.096914768 0.077020347 -0.29401636, -0.080837488 0.077383026 -0.2939859, -0.096959233 0.077462867 -0.29397005, -0.080819368 0.077736005 -0.29388958, -0.097027898 0.077884138 -0.29382712, -0.080804884 0.078065574 -0.29373044, -0.097117543 0.078263476 -0.29359475, -0.080808133 0.078287974 -0.29357532, -0.080837488 0.078484565 -0.29339457, -0.097223371 0.078581885 -0.29328409, -0.080892265 0.078649089 -0.29319769, -0.080634505 0.077077925 -0.29148221, -0.080604672 0.077044994 -0.29152286, -0.080575943 0.077008039 -0.2915597, -0.080528855 0.07692349 -0.29162085, -0.08050999 0.076869398 -0.29164773, -0.080496788 0.07681106 -0.29166815, -0.080488592 0.076748908 -0.29168183, -0.080486149 0.07671155 -0.29168597, -0.081857473 0.074469268 -0.28802299, -0.081919044 0.075038671 -0.28801763, -0.082024187 0.075613976 -0.28789967, -0.08216992 0.076161325 -0.28766859, -0.082347631 0.076648712 -0.28733677, -0.082545787 0.077052057 -0.28692842, -0.082670093 0.077248663 -0.28665727, -0.092920661 0.079411104 -0.27342513, -0.10698208 -0.032573208 -0.20863143, -0.093199849 0.079310611 -0.27326143, -0.10733929 -0.032552749 -0.20852958, -0.093438238 0.079227522 -0.27315751, -0.093596607 0.079185262 -0.27311239, -0.090748906 0.077798709 -0.27833644, -0.10463816 -0.033007637 -0.21423605, -0.091076195 0.077554107 -0.27808517, -0.10500047 -0.033028051 -0.21411067, -0.1188229 0.10864484 -0.21833797, -0.13648602 -0.032864392 -0.13650928, -0.11917606 0.10869829 -0.21825546, -0.13684431 -0.032852158 -0.13640276, -0.13732937 -0.03260304 -0.13452154, -0.11959743 0.10945834 -0.21666944, -0.13760084 -0.032449096 -0.13451292, -0.11995277 0.10949288 -0.21657595, -0.13781008 -0.032384187 -0.13451011, -0.11593568 0.10554431 -0.22453997, -0.133176 -0.032576993 -0.14467043, -0.11628896 0.10559782 -0.2244574, -0.1335333 -0.032556534 -0.14456873, -0.11671007 0.10635774 -0.22287139, -0.13410634 -0.033011913 -0.14228003, -0.11706555 0.10639237 -0.22277778, -0.13446862 -0.033032283 -0.14215472, -0.11304852 0.10244377 -0.23074198, -0.12990177 -0.032576486 -0.15266559, -0.1134015 0.10249734 -0.23065929, -0.1302591 -0.032556027 -0.15256377, -0.11382297 0.10325725 -0.22907346, -0.13083214 -0.033011422 -0.15027508, -0.11417848 0.10329191 -0.22897992, -0.1311945 -0.033031896 -0.15014964, -0.11016139 0.099343255 -0.23694375, -0.12662762 -0.032576069 -0.16066083, -0.11051446 0.099396929 -0.23686141, -0.1269848 -0.032555491 -0.16055895, -0.11093587 0.10015674 -0.2352753, -0.12755775 -0.033010885 -0.15827039, -0.11129123 0.10019143 -0.2351816, -0.12792006 -0.033031404 -0.15814488, -0.10727414 0.096242845 -0.24314578, -0.12335342 -0.032575533 -0.16865578, -0.10762733 0.096296459 -0.24306323, -0.12371069 -0.032554969 -0.16855416, -0.10804865 0.097056299 -0.24147715, -0.12428346 -0.033010378 -0.16626537, -0.1084041 0.09709087 -0.24138357, -0.12464595 -0.033031031 -0.16613999, -0.10438696 0.093142316 -0.24934784, -0.12007904 -0.03257516 -0.1766509, -0.1047402 0.093195841 -0.24926522, -0.12043637 -0.032554597 -0.17654921, -0.10516146 0.093955711 -0.24767914, -0.12100938 -0.033009946 -0.17426042, -0.10551694 0.093990296 -0.24758558, -0.12137163 -0.033030525 -0.17413515, -0.1015 0.090041712 -0.2555497, -0.11680478 -0.032574549 -0.18464619, -0.10185295 0.090095297 -0.25546718, -0.11716214 -0.032554224 -0.18454444, -0.10227427 0.090855226 -0.25388119, -0.11773494 -0.033009455 -0.18225572, -0.10262975 0.090889797 -0.25378767, -0.11809745 -0.033029899 -0.18213025, -0.093612731 0.081553623 -0.27248693, -0.10791227 -0.033008143 -0.20624095, -0.093968242 0.081588283 -0.27239349, -0.10827464 -0.033028573 -0.20611562, -0.099387169 0.087754726 -0.26008326, -0.11446077 -0.033009112 -0.1902508, -0.099742532 0.087789357 -0.2599895, -0.11482313 -0.033029497 -0.19012539, -0.098612666 0.086941242 -0.26175159, -0.11353052 -0.032574132 -0.19264111, -0.098965764 0.086994767 -0.26166898, -0.11388788 -0.032553628 -0.19253942, -0.096500039 0.084654257 -0.26628497, -0.11118671 -0.033008456 -0.1982459, -0.096855342 0.084688708 -0.26619157, -0.11154878 -0.033029005 -0.19812047, -0.095725507 0.083840609 -0.26795375, -0.11025628 -0.03257376 -0.20063628, -0.096078634 0.083894148 -0.26787102, -0.11061367 -0.03255327 -0.20053464, -0.089951128 0.07763958 -0.2803576, -0.10370785 -0.032572731 -0.21662655, -0.090304255 0.077693194 -0.28027481, -0.10406509 -0.032552242 -0.21652479, -0.096937776 0.0774097 -0.27744904, -0.096937716 0.077330709 -0.27752638, -0.096937656 0.077236712 -0.27758455, -0.096937656 0.0771323 -0.27762067, -0.097015291 0.077426583 -0.27743471, -0.097126156 0.077464119 -0.27742136, -0.097287059 0.077390015 -0.27759093, -0.097143143 0.077311203 -0.27757317, -0.097268373 0.077470079 -0.27751398, -0.09713155 0.077394187 -0.27750677, -0.097545505 0.077365577 -0.27776748, -0.097358555 0.077200487 -0.27768433, -0.097481698 0.077451065 -0.27771547, -0.097317547 0.077298716 -0.27764836, -0.097409338 0.077666953 -0.27745032, -0.097018123 0.077354506 -0.27751258, -0.097160488 0.077217609 -0.27762032, -0.097624153 0.077281192 -0.27779558, -0.097407699 0.077099875 -0.27769613, -0.09702304 0.077270895 -0.27757156, -0.09718284 0.077117041 -0.27764669, -0.097463161 0.077001974 -0.27768338, -0.097713232 0.077202618 -0.27779824, -0.097030133 0.077178076 -0.277612, -0.097209305 0.077013567 -0.27765095, -0.097039074 0.077078968 -0.27763319, -0.097238988 0.076911286 -0.27763203, -0.097049385 0.076976925 -0.27763343, -0.09706077 0.076875642 -0.27761245, -0.097262621 0.077536166 -0.27741909, -0.097411513 0.077606037 -0.27755216, -0.097436041 0.077532724 -0.27764228, -0.098889947 0.078561842 -0.27858418, -0.098800957 0.078640386 -0.27858171, -0.098722249 0.078724787 -0.27855337, -0.098658323 0.078810155 -0.27850133, -0.098612756 0.078891784 -0.27842832, -0.098588139 0.078965217 -0.27833807, -0.098585963 0.079026178 -0.27823606, -0.098696113 0.079115808 -0.27829707, -0.098695993 0.079048336 -0.2784006, -0.098984271 0.079131052 -0.27844441, -0.098833084 0.079142988 -0.27838856, -0.098696113 0.078952983 -0.27847901, -0.098984241 0.07905215 -0.27852172, -0.098833084 0.079047024 -0.27849609, -0.098984331 0.078958109 -0.27857986, -0.098695993 0.078838706 -0.27852553, -0.098984271 0.078853577 -0.27861595, -0.098833025 0.078923151 -0.27856967, -0.098833084 0.078783095 -0.27860314, -0.098833203 0.078639328 -0.27859318, -0.10028365 0.079130918 -0.27844441, -0.10028377 0.07905224 -0.27852172, -0.1002838 0.078958154 -0.27857989, -0.10028371 0.078853667 -0.27861589, -0.10037956 0.078557551 -0.27860445, -0.10047448 0.078619763 -0.27865809, -0.10046783 0.078534991 -0.27863026, -0.10054225 0.078507647 -0.27867213, -0.10068655 0.078747451 -0.27879864, -0.10074461 0.078702495 -0.2788884, -0.10063946 0.078643128 -0.278786, -0.10069069 0.07860364 -0.27886498, -0.10040438 0.078841016 -0.2786302, -0.10039055 0.078730032 -0.27863929, -0.10066363 0.07852149 -0.27883697, -0.10069695 0.078466907 -0.27895537, -0.10065147 0.078439295 -0.27880174, -0.10068294 0.078387082 -0.27891666, -0.10048825 0.078707263 -0.27867162, -0.10038325 0.07864219 -0.27862936, -0.1007897 0.079047218 -0.27861062, -0.10064316 0.079090998 -0.27852339, -0.10059476 0.079014704 -0.27859169, -0.10072076 0.07897608 -0.27866727, -0.10067981 0.078351364 -0.27900359, -0.10055104 0.078591958 -0.27870241, -0.10065785 0.078343883 -0.27910507, -0.1006591 0.078887597 -0.27870584, -0.10082796 0.078924656 -0.27876902, -0.10075063 0.078842983 -0.27879301, -0.10042301 0.078946486 -0.27859676, -0.10060525 0.078475043 -0.27873045, -0.10072672 0.078544185 -0.2789914, -0.10081786 0.078790799 -0.27889702, -0.10051522 0.078817606 -0.27866787, -0.10069463 0.078428775 -0.27904505, -0.10068747 0.078439385 -0.27916658, -0.10057011 0.078678519 -0.27872014, -0.1009143 0.078988194 -0.27872854, -0.10044539 0.079041287 -0.27854079, -0.10078555 0.078633696 -0.2790311, -0.10061601 0.078558639 -0.27876329, -0.10090652 0.078863844 -0.27889073, -0.10072473 0.078501657 -0.27908683, -0.10074046 0.078520998 -0.27923203, -0.10055131 0.078921899 -0.27864072, -0.10086504 0.078709826 -0.27906215, -0.10060787 0.078786641 -0.2787236, -0.10100567 0.078917518 -0.27886966, -0.10078326 0.078583702 -0.27913821, -0.1008141 0.078584149 -0.27929801, -0.10047019 0.079120323 -0.27846557, -0.10096106 0.078768492 -0.27908307, -0.10086179 0.07865037 -0.27918544, -0.10090441 0.078625754 -0.27936071, -0.1010679 0.078806177 -0.2790927, -0.10095617 0.07869783 -0.27922595, -0.10100603 0.078643218 -0.27941671, -0.10106134 0.078723922 -0.27925757, -0.10021913 0.077872679 -0.28004757, -0.10024872 0.077968135 -0.28010896, -0.10030183 0.078049898 -0.28017455, -0.10037541 0.078113139 -0.28024048, -0.10046569 0.078154683 -0.280303, -0.10056731 0.078171998 -0.28035903, -0.10040653 0.078104153 -0.28040686, -0.10032585 0.078071102 -0.28033054, -0.10025927 0.078015119 -0.28025317, -0.10025513 0.078032389 -0.28041473, -0.10019866 0.077983722 -0.2803278, -0.10013238 0.077827469 -0.28017583, -0.10000771 0.077880293 -0.28035086, -0.099993706 0.077802703 -0.28027302, -0.10015693 0.077913895 -0.28024653, -0.099913746 0.077800035 -0.28030103, -0.099833101 0.077803433 -0.28031439, -0.10049739 0.078112721 -0.28047824, -0.10032311 0.078057513 -0.28050292, -0.10003045 0.077939123 -0.28044236, -0.099921018 0.077873722 -0.28038099, -0.09983319 0.077874646 -0.28039518, -0.10039958 0.078058347 -0.280588, -0.10006034 0.077975884 -0.2805424, -0.099932432 0.077928826 -0.28047484, -0.099833161 0.077926889 -0.28048912, -0.1000956 0.077989221 -0.28064603, -0.099947274 0.077961802 -0.28057748, -0.099833101 0.077957928 -0.28059214, -0.10013512 0.077978536 -0.28074905, -0.099964797 0.077971891 -0.28068411, -0.09983325 0.077966109 -0.28069964, -0.09983322 0.077951163 -0.28080624, -0.099984199 0.077958152 -0.28079054, -0.10018313 0.077847883 -0.28011328, -0.10021082 0.077939063 -0.28017938, -0.090666056 0.077803478 -0.28031421, -0.090666115 0.077874899 -0.28039509, -0.090666056 0.077926978 -0.28048912, -0.090665966 0.077957988 -0.28059214, -0.090665996 0.077966243 -0.28069949, -0.090666056 0.077951178 -0.28080618, -0.09008947 0.077904478 -0.28089806, -0.090052456 0.077916026 -0.2807945, -0.090019107 0.077903256 -0.28068939, -0.089991093 0.077866897 -0.28058887, -0.089969784 0.077808738 -0.28049725, -0.089956403 0.077731833 -0.28041896, -0.089855462 0.078450933 -0.27915674, -0.089827657 0.078336343 -0.27917325, -0.089794964 0.078713655 -0.27908087, -0.089727908 0.078711644 -0.27913195, -0.089811921 0.078559861 -0.2791667, -0.089864612 0.078563318 -0.27911925, -0.090492189 0.078093335 -0.27860674, -0.090519994 0.07820791 -0.27859038, -0.090529233 0.078320399 -0.27855283, -0.091928363 0.07748507 -0.27765489, -0.091887981 0.077400103 -0.27771395, -0.091834188 0.077310786 -0.27775276, -0.091770232 0.077221304 -0.27776885, -0.091699094 0.077136233 -0.27776176, -0.091256738 0.077881083 -0.27804756, -0.091183543 0.077713117 -0.27809882, -0.091133416 0.077631146 -0.27810049, -0.090888262 0.078189954 -0.27825713, -0.090878367 0.078112826 -0.27829707, -0.090830803 0.077953666 -0.27834189, -0.090793967 0.077874646 -0.27834582, -0.091732502 0.077109307 -0.2777462, -0.09180367 0.077194437 -0.27775335, -0.091867834 0.077283934 -0.27773726, -0.091921449 0.077373326 -0.2776987, -0.09196198 0.077458248 -0.27763939, -0.092233062 0.077131957 -0.27763784, -0.091991544 0.077088937 -0.27768812, -0.092029989 0.077176139 -0.27768001, -0.091941625 0.07698901 -0.27767491, -0.092185736 0.07691513 -0.27763006, -0.092212737 0.077031478 -0.27764657, -0.092439413 0.077409729 -0.27744901, -0.092272639 0.07739757 -0.277493, -0.092439353 0.077330798 -0.27752632, -0.092263728 0.077318802 -0.2775597, -0.092439413 0.077236757 -0.27758452, -0.092250347 0.077229008 -0.27760851, -0.092109263 0.077418804 -0.27755457, -0.092439413 0.077132329 -0.27762055, -0.092089653 0.077343687 -0.27761245, -0.09206295 0.07726191 -0.27765453, -0.094332308 0.082231656 -0.27224246, -0.094332308 0.08215262 -0.27231976, -0.093611658 0.081615254 -0.27251458, -0.093607247 0.081679866 -0.27253401, -0.093599617 0.081746265 -0.27254486, -0.093579441 0.081862733 -0.27254331, -0.093551099 0.081973955 -0.27251518, -0.09351629 0.082073823 -0.27246276, -0.09347716 0.082156822 -0.27238846, -0.093943149 0.081977054 -0.27243537, -0.094332308 0.082058683 -0.27237794, -0.094332308 0.081954226 -0.27241397, -0.1031709 0.082231671 -0.27224243, -0.10317093 0.082152605 -0.27231967, -0.10317078 0.082058698 -0.27237785, -0.10317078 0.081954241 -0.27241385, -0.10342982 0.081608146 -0.27247053, -0.10343862 0.081692427 -0.27250081, -0.10335106 0.081636757 -0.27242672, -0.10335752 0.081721634 -0.27245426, -0.10330391 0.08204776 -0.27239335, -0.10328624 0.08194226 -0.2724269, -0.10339743 0.081919521 -0.27246356, -0.10327286 0.081831336 -0.27243644, -0.10337111 0.081809014 -0.27246773, -0.10345769 0.081778795 -0.27251852, -0.10332513 0.082142502 -0.2723372, -0.10343257 0.082023889 -0.27243602, -0.10349551 0.081886917 -0.27252197, -0.10334897 0.082221687 -0.27226156, -0.10347524 0.082116723 -0.27238655, -0.10354698 0.081987917 -0.27250427, -0.10352263 0.082193285 -0.27231783, -0.10360861 0.082076341 -0.27246583, -0.10367769 0.08214736 -0.2724092, -0.10326231 0.08165887 -0.27240157, -0.10326588 0.081743687 -0.27242655, -0.1034545 0.081272468 -0.27415726, -0.10335281 0.081255183 -0.2741012, -0.10326254 0.081213728 -0.27403843, -0.10318896 0.081150323 -0.27397245, -0.10313582 0.081068724 -0.27390701, -0.10310635 0.080973297 -0.27384537, -0.10301948 0.080928057 -0.273974, -0.10288084 0.080903217 -0.27407089, -0.10329378 0.081204668 -0.27420485, -0.10321313 0.081171587 -0.27412865, -0.10314649 0.081115708 -0.27405131, -0.10314226 0.081132904 -0.27421284, -0.10308596 0.081084281 -0.27412575, -0.10289511 0.080980733 -0.27414879, -0.10304403 0.081014574 -0.27404451, -0.10280088 0.08090052 -0.27409917, -0.10272041 0.080904007 -0.27411234, -0.1033847 0.081213281 -0.27427632, -0.10321033 0.081158176 -0.27430093, -0.10291767 0.081039593 -0.2742404, -0.10280821 0.080974415 -0.27417898, -0.10272035 0.080975205 -0.27419299, -0.10328662 0.081158891 -0.27438605, -0.10294735 0.081076548 -0.27434039, -0.10281974 0.081029281 -0.27427304, -0.10272038 0.081027552 -0.27428713, -0.10298264 0.081089914 -0.27444398, -0.10283437 0.081062451 -0.27437541, -0.10272032 0.081058413 -0.27439028, -0.10302228 0.081079066 -0.27454692, -0.10285187 0.081072375 -0.27448216, -0.10272044 0.081066594 -0.27449763, -0.10272035 0.081051499 -0.27460426, -0.10287148 0.081058696 -0.27458856, -0.10307029 0.080948442 -0.2739113, -0.10309789 0.081039727 -0.27397728, -0.1006819 0.080903918 -0.27411228, -0.10068184 0.08097516 -0.27419317, -0.1006819 0.081027478 -0.27428716, -0.10068196 0.081058368 -0.27439034, -0.1006819 0.081066534 -0.27449763, -0.10068187 0.081051499 -0.27460426, -0.10058555 0.080872253 -0.27409744, -0.10054234 0.080919981 -0.27415609, -0.10049474 0.080909416 -0.274169, -0.10041514 0.080926418 -0.27425897, -0.10041386 0.080971107 -0.2743603, -0.10035113 0.080922276 -0.27436197, -0.1005424 0.081000641 -0.27427578, -0.10041392 0.080988869 -0.27448601, -0.10054228 0.081042349 -0.2744143, -0.10054237 0.081040725 -0.2745589, -0.099408865 0.079513133 -0.2733115, -0.099318117 0.079550207 -0.27338314, -0.099238545 0.079567224 -0.27347308, -0.099174529 0.079563037 -0.27357599, -0.099081874 0.079289958 -0.27318576, -0.098873258 0.07923013 -0.27315354, -0.098842949 0.079309881 -0.27326679, -0.099027157 0.079359338 -0.2732859, -0.099133313 0.079469725 -0.27341408, -0.099189639 0.079442188 -0.27332619, -0.098635316 0.079330131 -0.27360871, -0.098986685 0.079395413 -0.27338624, -0.099264771 0.079387575 -0.27324033, -0.098635286 0.079182684 -0.27311695, -0.09879604 0.07935515 -0.27357793, -0.098635316 0.079345256 -0.27350211, -0.098806649 0.079362661 -0.27347779, -0.09893772 0.079403341 -0.27356851, -0.098635286 0.079337135 -0.27339479, -0.098821163 0.079350397 -0.27337912, -0.098635197 0.07930617 -0.27329171, -0.098959059 0.079407632 -0.27347589, -0.098635316 0.079253837 -0.27319765, -0.099062175 0.079473197 -0.27357829, -0.099093914 0.079478189 -0.27349392, -0.094136924 0.07933028 -0.27360871, -0.094137043 0.079345256 -0.27350229, -0.094136953 0.079337075 -0.27339485, -0.094136983 0.079306141 -0.27329183, -0.094137013 0.079253793 -0.27319771, -0.094137043 0.07918264 -0.27311692, -0.093919128 0.079343513 -0.27368239, -0.093908936 0.079373688 -0.27356946, -0.093890488 0.079377592 -0.27345365, -0.093865007 0.079355314 -0.27334133, -0.093833804 0.079307869 -0.27323869, -0.093798488 0.079237893 -0.2731514, -0.093655437 0.079408243 -0.27388325, -0.093269855 0.079389498 -0.27329654, -0.093767256 0.079370931 -0.27378821, -0.093632907 0.079467133 -0.27379203, -0.093749255 0.079415992 -0.27369824, -0.093595237 0.079507068 -0.27369538, -0.093721807 0.079442799 -0.27360481, -0.093544692 0.079526022 -0.27359822, -0.093686014 0.079451174 -0.27351153, -0.093483806 0.079522908 -0.27350563, -0.093415231 0.079498246 -0.27342167, -0.093636125 0.07943745 -0.27340749, -0.093342841 0.079453006 -0.27335083, -0.093571544 0.079392627 -0.27330148, -0.093503803 0.079320624 -0.27321652, -0.093430161 0.079535559 -0.27403226, -0.093395799 0.0796009 -0.27394187, -0.093217254 0.079629377 -0.27419782, -0.092986941 0.07949993 -0.27345538, -0.092719883 0.079577327 -0.2736367, -0.093060642 0.079573706 -0.27350608, -0.092792422 0.079661205 -0.27368581, -0.09313798 0.079627469 -0.27357486, -0.092872202 0.079722971 -0.27375293, -0.093214422 0.079658106 -0.27365819, -0.092954576 0.079759255 -0.2738339, -0.093285203 0.07966359 -0.27375033, -0.093034893 0.07976754 -0.2739245, -0.093346477 0.079644278 -0.27384618, -0.093107969 0.079747662 -0.27401888, -0.093170047 0.079700783 -0.27411202, -0.090788722 0.080274299 -0.27527514, -0.090854704 0.080353841 -0.27531832, -0.090927482 0.080415159 -0.27537757, -0.091003299 0.080455273 -0.27544951, -0.09107855 0.080471978 -0.27553055, -0.091149449 0.080464572 -0.27561688, -0.091212451 0.080433398 -0.27570403, -0.091260314 0.080385283 -0.27578095, -0.09129706 0.080320671 -0.27585164, -0.091156423 0.080448285 -0.27574912, -0.091162741 0.080459937 -0.27564999, -0.091112852 0.080475524 -0.27563766, -0.091096699 0.080453262 -0.27579159, -0.090844482 0.080416203 -0.27541602, -0.090884894 0.080474868 -0.27556765, -0.090969563 0.080474809 -0.27551082, -0.091242492 0.080401435 -0.27576855, -0.091234982 0.080385655 -0.27581936, -0.091210216 0.080375433 -0.27586603, -0.091171145 0.080371931 -0.27590254, -0.090948015 0.080475643 -0.2757484, -0.090972811 0.080485776 -0.27570179, -0.091011941 0.080489293 -0.27566519, -0.091060549 0.080485776 -0.2756429, -0.146449 -0.024365038 -0.13916655, -0.14645398 -0.02436322 -0.13915102, -0.14645797 -0.024364278 -0.1391333, -0.14646223 -0.024370164 -0.13910688, -0.14646411 -0.024376452 -0.13908879, -0.094029695 -0.03359583 -0.22818319, -0.080366641 0.075870931 -0.29148036, -0.09404552 -0.03359814 -0.22813627, -0.080381423 0.075893462 -0.29144448, -0.094065428 -0.033594325 -0.2281011, -0.080405056 0.075914681 -0.29141283, -0.094082952 -0.033588603 -0.22808, -0.080436617 0.075933486 -0.29138732, -0.094102859 -0.033581451 -0.22806272, -0.094125152 -0.033573925 -0.22804879, -0.080474257 0.075948983 -0.2913686, -0.094157696 -0.033564508 -0.2280352, -0.080516249 0.075960338 -0.29135811, -0.094190598 -0.033557951 -0.22802757, -0.080314785 0.076334536 -0.29173762, -0.080330759 0.076355994 -0.29170376, -0.080354899 0.076375857 -0.29167393, -0.080386013 0.076393366 -0.29164976, -0.080423027 0.076407611 -0.29163229, -0.080463797 0.076417863 -0.29162228, -0.08045131 0.076521337 -0.29166812, -0.080411494 0.076514766 -0.29167983, -0.080340296 0.07662338 -0.29174775, -0.080344468 0.076495707 -0.2917251, -0.080319971 0.076483861 -0.29175693, -0.080315709 0.076620087 -0.29177949, -0.080300301 0.076726928 -0.29181141, -0.080297977 0.076616466 -0.29181582, -0.080370963 0.07662636 -0.2917214, -0.080375433 0.076506123 -0.29169911, -0.0803186 0.076723754 -0.29177636, -0.080406308 0.076628804 -0.29170197, -0.080343336 0.07672061 -0.29174548, -0.080444902 0.076630607 -0.29168981, -0.080373555 0.076717794 -0.29172045, -0.08031404 0.076865941 -0.29177964, -0.080408245 0.076715291 -0.29170161, -0.080332428 0.076854378 -0.29174721, -0.080446213 0.076713219 -0.2916899, -0.080402642 0.07714206 -0.29160845, -0.080329418 0.076948151 -0.29174656, -0.080357075 0.076843366 -0.29171914, -0.080423862 0.077108085 -0.29158288, -0.080347747 0.076931611 -0.29171613, -0.080386847 0.076833144 -0.29169658, -0.080531865 0.077024549 -0.29155248, -0.080490381 0.077047527 -0.29155397, -0.080372006 0.076915801 -0.29169041, -0.080303133 0.076471135 -0.29179329, -0.080453664 0.077076018 -0.29156435, -0.080420762 0.076824129 -0.29168016, -0.08040151 0.076901093 -0.29167014, -0.080457956 0.076816738 -0.29167062, -0.080435187 0.076888144 -0.29165578, -0.080471903 0.076877326 -0.29164809, -0.080445081 0.077221334 -0.29153085, -0.080460459 0.077186763 -0.29151142, -0.08047393 0.077260792 -0.29147398, -0.080502898 0.077293932 -0.29141355, -0.080483109 0.077153981 -0.29149699, -0.080488503 0.077223241 -0.29145706, -0.080516487 0.07725364 -0.29139972, -0.080511957 0.077124178 -0.29148841, -0.080510765 0.077187717 -0.29144537, -0.080538511 0.077215552 -0.2913909, -0.080567837 0.077181727 -0.29138768, -0.080545634 0.077098757 -0.29148573, -0.080539733 0.077155888 -0.29143924, -0.080583066 0.077078819 -0.29148912, -0.080574185 0.077128947 -0.29143906, -0.080602735 0.077153951 -0.29139012, -0.080612302 0.077108651 -0.2914449, -0.080641806 0.077133477 -0.29139805, -0.11897376 0.11860764 -0.2087741, -0.11898738 0.11856726 -0.20876025, -0.11900952 0.11852932 -0.20875157, -0.1190387 0.11849543 -0.2087483, -0.11907372 0.11846775 -0.20875074, -0.1191127 0.11844712 -0.20875861, -0.11952192 0.11875668 -0.20817159, -0.11985835 0.1188349 -0.20798296, -0.1195507 0.11873004 -0.20819242, -0.11983672 0.11886382 -0.20795728, -0.1201638 0.11906061 -0.2077686, -0.12057108 0.11905906 -0.20768838, -0.1201717 0.11901712 -0.20777215, -0.11929837 0.11859882 -0.20845474, -0.11980078 0.11893898 -0.2079287, -0.1201821 0.1189761 -0.20778492, -0.11981717 0.11889911 -0.20793892, -0.11949605 0.1187897 -0.20815764, -0.12015864 0.11910695 -0.20777504, -0.11926395 0.11862233 -0.20844005, -0.11978823 0.11898151 -0.20792709, -0.11947441 0.11882779 -0.20815094, -0.11923304 0.11865294 -0.20843126, -0.11978018 0.11902723 -0.20793481, -0.11945793 0.11886901 -0.20815195, -0.11920708 0.11868861 -0.20842917, -0.11944714 0.11891389 -0.20816161, -0.11918738 0.11872815 -0.20843378, -0.11917424 0.11877188 -0.20844562, -0.12020841 0.11890864 -0.20783545, -0.12058496 0.11894813 -0.20775615, -0.12019446 0.11893928 -0.20780636, -0.12057987 0.11897957 -0.20772566, -0.12057498 0.11901724 -0.20770241, -0.13668504 0.1199666 -0.2058727, -0.13668875 0.11992483 -0.20588678, -0.1366937 0.11988717 -0.2059098, -0.13669889 0.11985575 -0.20594037, -0.13754071 0.11977285 -0.20619975, -0.13741833 0.11987889 -0.20606123, -0.13756602 0.11981212 -0.20619738, -0.13702331 0.12006859 -0.2058945, -0.13680521 0.12007633 -0.20587157, -0.13702188 0.12003855 -0.20588639, -0.13750999 0.11973923 -0.20620964, -0.1373733 0.11980186 -0.20608369, -0.13739793 0.11983798 -0.20606828, -0.13680512 0.12004638 -0.20586409, -0.13771431 0.11982921 -0.20639546, -0.1368051 0.11985885 -0.20593441, -0.13680521 0.11989066 -0.20590334, -0.13701947 0.12000754 -0.20588286, -0.13680512 0.12001562 -0.20586134, -0.13770978 0.11979978 -0.20638329, -0.13759251 0.11988451 -0.2062107, -0.13701437 0.11996275 -0.20588644, -0.13680522 0.1199712 -0.2058658, -0.13747545 0.11971314 -0.20622668, -0.1373457 0.11977288 -0.20610671, -0.13700746 0.11992007 -0.20589979, -0.13680498 0.11992888 -0.20587999, -0.13770062 0.11977051 -0.20637336, -0.13758437 0.11985448 -0.20620282, -0.13699906 0.11988178 -0.20592232, -0.13724227 0.12003794 -0.20596348, -0.13743976 0.11969593 -0.20624895, -0.13767952 0.11972964 -0.20636366, -0.13698988 0.11984983 -0.20595272, -0.13723975 0.12000775 -0.2059543, -0.13765049 0.11969298 -0.20636036, -0.13723509 0.11997691 -0.20594974, -0.13761489 0.11966258 -0.20636354, -0.13757505 0.11964005 -0.20637287, -0.13722478 0.11993222 -0.20595124, -0.13777329 0.11967212 -0.20657144, -0.13721089 0.11988989 -0.20596202, -0.13753383 0.1196267 -0.2063875, -0.13719422 0.11985242 -0.20598195, -0.13775057 0.11963356 -0.20655702, -0.13744324 0.1199832 -0.20607935, -0.13717543 0.11982135 -0.20600989, -0.1374398 0.1199533 -0.20606919, -0.13743323 0.11992264 -0.20606302, -0.13759667 0.11991429 -0.20622204, -0.13782731 0.11786525 -0.2052989, -0.13791332 0.1177846 -0.20546117, -0.13793628 0.11775747 -0.20543857, -0.13701478 0.11801226 -0.2048139, -0.13718107 0.11800769 -0.20482846, -0.13784814 0.11783998 -0.2052722, -0.13716309 0.1180779 -0.20498295, -0.13732567 0.11805825 -0.20502293, -0.1373387 0.11805366 -0.20498171, -0.13780099 0.11788368 -0.20532618, -0.13788404 0.11780556 -0.20548305, -0.13716936 0.11807375 -0.20493975, -0.1370147 0.11804286 -0.20484607, -0.13688964 0.1180073 -0.20481943, -0.13689151 0.11803862 -0.20485143, -0.1377697 0.11789434 -0.20535278, -0.13784966 0.11781922 -0.20550339, -0.13772988 0.11788468 -0.2050916, -0.13717851 0.11803785 -0.20486061, -0.13715616 0.11807244 -0.20502615, -0.13773552 0.11789696 -0.20537758, -0.13781177 0.11782521 -0.20552121, -0.13731115 0.1180537 -0.20506366, -0.13701469 0.11806571 -0.20488416, -0.13689438 0.11806197 -0.2048896, -0.13771811 0.11791484 -0.20511937, -0.13717461 0.11806017 -0.20489825, -0.13701478 0.1180795 -0.20492643, -0.13689867 0.11807629 -0.20493178, -0.13770062 0.11793862 -0.20515034, -0.13701478 0.11808375 -0.20497064, -0.13690308 0.11808066 -0.20497608, -0.13767825 0.11795491 -0.20518263, -0.13765195 0.11796311 -0.20521514, -0.13701478 0.11807802 -0.20501475, -0.13690844 0.11807516 -0.20502023, -0.13755956 0.11794594 -0.20496376, -0.13762277 0.11796248 -0.20524631, -0.13755083 0.11797573 -0.20499378, -0.1375374 0.11799839 -0.20502789, -0.13752055 0.11801316 -0.20506459, -0.13750026 0.11801921 -0.20510218, -0.13736346 0.1179878 -0.20487392, -0.13747796 0.11801611 -0.20513883, -0.13735801 0.11801755 -0.20490538, -0.13734952 0.11803989 -0.20494187, -0.13795209 0.11772518 -0.20541632, -0.13786237 0.11780885 -0.20524676, -0.12076488 0.1170992 -0.20663641, -0.12076682 0.11713037 -0.20666845, -0.12076974 0.11715376 -0.20670666, -0.12077379 0.1171681 -0.20674883, -0.12077847 0.11717248 -0.20679311, -0.12078369 0.117167 -0.20683734, -0.11932579 0.11668384 -0.20744099, -0.11954749 0.11681315 -0.20718722, -0.11933672 0.11672089 -0.20746736, -0.11916304 0.11654429 -0.20771748, -0.11917493 0.11658257 -0.20774211, -0.11955717 0.11684871 -0.207215, -0.11935619 0.11675178 -0.2074967, -0.11919615 0.11661512 -0.20776822, -0.11957425 0.1168777 -0.20724712, -0.11938313 0.11677456 -0.20752741, -0.11922562 0.11664054 -0.20779471, -0.11959749 0.11689809 -0.20728169, -0.11941576 0.1167883 -0.20755778, -0.11926153 0.11665702 -0.20781983, -0.11930236 0.11666411 -0.20784213, -0.11945269 0.11679214 -0.20758618, -0.1202791 0.11704051 -0.2067454, -0.1202845 0.11707309 -0.20677648, -0.12029305 0.11709809 -0.2068135, -0.12030476 0.1171138 -0.20685451, -0.12031874 0.11711985 -0.20689715, -0.12033442 0.11711562 -0.20693947, -0.11986691 0.1169391 -0.2069407, -0.11987486 0.1169734 -0.20697023, -0.11988822 0.11700022 -0.20700516, -0.11990649 0.11701819 -0.20704348, -0.11992842 0.11702642 -0.20708282, -0.11995316 0.11702457 -0.20712148, -0.1196259 0.11690909 -0.20731677, -0.1196577 0.11691001 -0.20735048, -0.082612246 0.077292562 -0.28623235, -0.082623988 0.077330738 -0.28625703, -0.082645208 0.077363431 -0.28628325, -0.082674742 0.077388644 -0.28630948, -0.082710803 0.077405393 -0.28633469, -0.082751393 0.077412277 -0.2863571, -0.081746221 0.07518521 -0.2877717, -0.081665844 0.07457149 -0.28780037, -0.081664562 0.074568629 -0.28784943, -0.08174625 0.0751926 -0.2878195, -0.081951022 0.075847059 -0.28776479, -0.081920266 0.075841576 -0.28772998, -0.081898332 0.075831771 -0.28768981, -0.081885934 0.075817943 -0.28764665, -0.081884146 0.075801015 -0.2876029, -0.082140833 0.076437026 -0.28744292, -0.082110971 0.076426744 -0.28741086, -0.082088739 0.07641083 -0.28737509, -0.082075238 0.076389939 -0.2873373, -0.082071334 0.076365292 -0.28729928, -0.082425267 0.076984435 -0.28697944, -0.082390904 0.07697621 -0.28695482, -0.082362086 0.076961309 -0.28692698, -0.082339734 0.076940358 -0.28689724, -0.082325101 0.076913953 -0.28686655, -0.082318664 0.076883286 -0.28683621, -0.082629949 0.077253401 -0.286641, -0.082592905 0.077250421 -0.28662109, -0.082559705 0.077239841 -0.28659838, -0.082531452 0.077222735 -0.28657371, -0.08250919 0.077199399 -0.28654802, -0.082493722 0.077170789 -0.28652215, -0.082485676 0.077137828 -0.28649712, -0.081769019 0.074549943 -0.28800523, -0.081729174 0.07455501 -0.28797728, -0.081697226 0.074560165 -0.28794038, -0.08167541 0.074564725 -0.28789699, -0.081810981 0.075200766 -0.28794509, -0.08177954 0.075200617 -0.28790855, -0.081757396 0.075197816 -0.28786594, -0.14923963 -0.034641996 -0.13452989, -0.14913476 -0.034588963 -0.13447692, -0.14920813 -0.034617513 -0.13450535, -0.14917359 -0.034600437 -0.13448827, -0.14926493 -0.034674093 -0.13456199, -0.14910266 -0.034583986 -0.13447188, -0.14927891 -0.034705311 -0.13459314, -0.14928594 -0.034757942 -0.13464577, -0.14927164 -0.034822255 -0.13471021, -0.14721051 -0.035128847 -0.14043182, -0.1471616 -0.035182804 -0.14039321, -0.1471332 -0.035220578 -0.14035219, -0.14711833 -0.035247371 -0.14031032, -0.14711362 -0.03526485 -0.14027034, -0.14711627 -0.03527528 -0.14023356, -0.14712316 -0.035280511 -0.14020154, -0.14728671 -0.035055324 -0.14046118, -0.11433426 0.10836169 -0.21950899, -0.11426717 0.10841629 -0.21952431, -0.11422697 0.10845968 -0.21952282, -0.11420092 0.1084967 -0.21951286, -0.11418334 0.10853121 -0.21949662, -0.11417201 0.10856584 -0.21947347, -0.11416712 0.10859987 -0.2194439, -0.11416873 0.10863331 -0.21940844, -0.11418039 0.10867603 -0.2193529, -0.11419961 0.10871246 -0.21929555, -0.1133514 -0.03327553 -0.22298533, -0.14744243 -0.033516482 -0.14036471, -0.1474275 -0.033482 -0.1403096, -0.14742458 -0.033454046 -0.1402432, -0.14746824 -0.033557802 -0.14041026, -0.14750326 -0.033602878 -0.14044383, -0.14754415 -0.033648223 -0.14046349, -0.14756712 -0.033671334 -0.14046854, -0.14702246 -0.02873759 -0.13659444, -0.14707029 -0.028742939 -0.13654216, -0.14712858 -0.028749436 -0.13650264, -0.14719462 -0.028756946 -0.13647796, -0.14932781 -0.034666941 -0.13464001, -0.14936712 -0.034558266 -0.13464005, -0.14938855 -0.034564584 -0.13470341, -0.14934811 -0.034675673 -0.1347034, -0.1493035 -0.034718856 -0.13464007, -0.1493234 -0.03472881 -0.13470355, -0.14924312 -0.03452149 -0.13450529, -0.14926216 -0.034374833 -0.13449995, -0.14931858 -0.034381196 -0.13453564, -0.14931506 -0.034542844 -0.13456193, -0.14927784 -0.034645349 -0.13456191, -0.14916766 -0.034499198 -0.1344768, -0.14919922 -0.034367681 -0.13447778, -0.14920893 -0.034615666 -0.13450529, -0.14913675 -0.034584463 -0.13447671, -0.14942339 -0.034392804 -0.13470347, -0.14936578 -0.034386441 -0.13458303, -0.14940143 -0.034390301 -0.13463999, -0.14943871 -0.034256712 -0.13470334, -0.1494166 -0.034254223 -0.13463999, -0.14938107 -0.034250319 -0.13458292, -0.14933389 -0.034245029 -0.13453555, -0.14927739 -0.034238592 -0.13449979, -0.14921439 -0.034231573 -0.13447763, -0.14948446 -0.033797175 -0.13458295, -0.14968655 -0.033378661 -0.13458292, -0.14971673 -0.033397704 -0.13463993, -0.14951819 -0.033809096 -0.13463999, -0.14985868 -0.032896921 -0.13447741, -0.15025267 -0.032584906 -0.13447742, -0.15028617 -0.032638729 -0.13449959, -0.15037188 -0.032776475 -0.1347032, -0.14990342 -0.032941967 -0.13449974, -0.14959833 -0.03332305 -0.13449989, -0.14994356 -0.03298223 -0.13453548, -0.14964634 -0.033353284 -0.13453549, -0.14943966 -0.033781469 -0.13453554, -0.14954457 -0.033289075 -0.13447742, -0.14938605 -0.033762649 -0.13449979, -0.14932615 -0.033741608 -0.13447762, -0.15001789 -0.03305693 -0.13470334, -0.1500023 -0.033041269 -0.13463993, -0.1503602 -0.032757699 -0.13463996, -0.14973563 -0.033409506 -0.13470341, -0.14997703 -0.033015937 -0.13458295, -0.15034136 -0.032727361 -0.13458292, -0.14953917 -0.033816263 -0.13470331, -0.15031621 -0.032686949 -0.13453536, -0.15710282 -0.028582215 -0.13470285, -0.15709099 -0.028563321 -0.13463943, -0.15707219 -0.028533041 -0.13458256, -0.15704703 -0.028492808 -0.134535, -0.15701681 -0.028444409 -0.1344993, -0.15698332 -0.028390646 -0.13447712, -0.15732884 -0.027894244 -0.13447705, -0.15734458 -0.027739942 -0.13447694, -0.15728241 -0.028042361 -0.13447699, -0.15724623 -0.028443262 -0.13463959, -0.15722162 -0.028417334 -0.13458261, -0.15734476 -0.028273821 -0.1345825, -0.15718883 -0.028382897 -0.13453494, -0.1573059 -0.028246686 -0.13453493, -0.15739307 -0.028089821 -0.134535, -0.15725917 -0.028214201 -0.13449928, -0.15734076 -0.02806735 -0.13449936, -0.15739104 -0.027907088 -0.13449931, -0.15740794 -0.027739868 -0.13449916, -0.15726158 -0.028459266 -0.13470292, -0.15737408 -0.028294191 -0.13463935, -0.15743646 -0.028108433 -0.13458258, -0.15744677 -0.027918488 -0.13453497, -0.15746495 -0.027739838 -0.13453496, -0.15739244 -0.028306887 -0.13470277, -0.15746951 -0.028122589 -0.13463935, -0.15749335 -0.027928054 -0.13458256, -0.15751228 -0.027739972 -0.13458253, -0.15748984 -0.028131336 -0.13470288, -0.15752828 -0.027935266 -0.13463943, -0.15754816 -0.027739957 -0.1346395, -0.15754998 -0.027939707 -0.13470288, -0.1575703 -0.027739927 -0.13470277, -0.15710598 -0.028295681 -0.13447711, -0.15714976 -0.028341621 -0.13449933, -0.15720719 -0.028178021 -0.13447705, -0.15734461 -0.023794979 -0.1344768, -0.157408 -0.023794994 -0.13449892, -0.15746489 -0.023794994 -0.13453475, -0.1575124 -0.023795038 -0.13458206, -0.1575481 -0.023794979 -0.13463898, -0.15757036 -0.023795024 -0.1347025, -0.15561953 -0.021421522 -0.13458188, -0.15507776 -0.021407962 -0.1345344, -0.15507767 -0.021360427 -0.13458182, -0.15613413 -0.021601558 -0.13458191, -0.15611365 -0.021644309 -0.13453448, -0.1572285 -0.022759274 -0.13453442, -0.15740511 -0.023263782 -0.13453443, -0.15734959 -0.023276433 -0.13449869, -0.15560895 -0.021467805 -0.1345344, -0.15717727 -0.022783995 -0.13449876, -0.15615937 -0.021549374 -0.1347021, -0.15663195 -0.021846309 -0.13470215, -0.15689972 -0.022342131 -0.13449863, -0.15712014 -0.022811502 -0.13447662, -0.15685001 -0.022381753 -0.13447644, -0.15661806 -0.021863639 -0.13463889, -0.15614969 -0.021569252 -0.13463895, -0.15562764 -0.021386579 -0.13463879, -0.15507782 -0.021324769 -0.13463897, -0.15649113 -0.022022739 -0.1344766, -0.1556325 -0.021365047 -0.13470207, -0.15507779 -0.021302506 -0.13470212, -0.15748614 -0.023245335 -0.13463895, -0.15745145 -0.023253307 -0.13458195, -0.15727133 -0.02273868 -0.13458219, -0.15694401 -0.02230671 -0.13453443, -0.15653071 -0.021973282 -0.13449861, -0.15606138 -0.021752745 -0.13447644, -0.15750787 -0.023240462 -0.13470238, -0.15730342 -0.022723243 -0.13463894, -0.15507784 -0.021528214 -0.13447644, -0.1569812 -0.022277012 -0.13458198, -0.15656617 -0.021928713 -0.13453439, -0.15608883 -0.021695495 -0.13449858, -0.15558228 -0.021585137 -0.13447644, -0.15732348 -0.022713542 -0.13470243, -0.15700924 -0.02225481 -0.13463899, -0.15659574 -0.021891564 -0.13458194, -0.15728775 -0.023290619 -0.13447669, -0.15559635 -0.021523267 -0.13449861, -0.15507779 -0.02146484 -0.13449854, -0.15702662 -0.022241026 -0.13470222, -0.14876416 -0.021528199 -0.13447642, -0.14876413 -0.021464795 -0.13449861, -0.14876407 -0.021407902 -0.13453446, -0.14876404 -0.021360397 -0.13458203, -0.14876419 -0.021324664 -0.13463874, -0.14876407 -0.021302432 -0.1347021, -0.14729202 -0.021915972 -0.1345344, -0.14695922 -0.022321299 -0.1344986, -0.14691511 -0.022285283 -0.13453446, -0.14776504 -0.021689713 -0.13449864, -0.1473271 -0.021960706 -0.13449861, -0.14774078 -0.021638453 -0.13453446, -0.14821649 -0.021363348 -0.13470228, -0.14822137 -0.021385044 -0.1346388, -0.14770511 -0.021563143 -0.1346388, -0.14822918 -0.021419972 -0.13458182, -0.14772049 -0.021595553 -0.13458192, -0.1472626 -0.021878451 -0.13458194, -0.14687839 -0.022255257 -0.13458192, -0.14769557 -0.021543056 -0.13470204, -0.14724067 -0.021850422 -0.13463879, -0.14685068 -0.022232592 -0.13463889, -0.14722696 -0.021832913 -0.13470222, -0.14683345 -0.022218585 -0.13470219, -0.14826599 -0.021583647 -0.13447656, -0.1482521 -0.021521688 -0.13449864, -0.14779234 -0.021747082 -0.13447644, -0.14823964 -0.021466225 -0.13453449, -0.14736614 -0.022010624 -0.13447653, -0.14700833 -0.022361353 -0.13447642, -0.13880396 -0.032446265 -0.13447313, -0.13880065 -0.032382503 -0.13448268, -0.1387957 -0.032287136 -0.13451034, -0.13879958 -0.032243133 -0.1345263, -0.13881502 -0.032186881 -0.13454527, -0.13900185 -0.03183946 -0.13464697, -0.13802379 -0.032510966 -0.13447006, -0.13712731 -0.03296259 -0.13447799, -0.13707483 -0.032923922 -0.13450161, -0.1373626 -0.032644019 -0.13449326, -0.13739863 -0.032688141 -0.13447605, -0.13758111 -0.032512069 -0.13448982, -0.13760474 -0.032558933 -0.13447505, -0.1377995 -0.032435402 -0.13448814, -0.13781142 -0.032484457 -0.13447472, -0.13782373 -0.032534599 -0.13447009, -0.13692999 -0.033230513 -0.13447805, -0.13687769 -0.033191815 -0.13450164, -0.13685024 -0.033277854 -0.13449243, -0.13681844 -0.033239499 -0.1345138, -0.14602858 -0.024821028 -0.14009038, -0.14644456 -0.024311483 -0.13921432, -0.14645934 -0.0242576 -0.13925271, -0.14604357 -0.024766654 -0.14012899, -0.1464642 -0.024324208 -0.13906969, -0.14647499 -0.024264663 -0.13906987, -0.14649752 -0.024208397 -0.13906969, -0.1464642 -0.024324358 -0.13676922, -0.14647508 -0.024264783 -0.13676919, -0.14649749 -0.02420859 -0.13676915, -0.14653674 -0.024162844 -0.13670242, -0.14647794 -0.024344876 -0.13667649, -0.14648902 -0.024268955 -0.13667645, -0.14651993 -0.024198726 -0.13667643, -0.1465539 -0.024176911 -0.136639, -0.14652312 -0.024312705 -0.136593, -0.14658165 -0.024199396 -0.13658209, -0.14654115 -0.024249911 -0.13659291, -0.14661834 -0.024229646 -0.13653468, -0.14658701 -0.024346024 -0.13652642, -0.1465939 -0.024299085 -0.13652651, -0.14661297 -0.024255708 -0.13652647, -0.14666241 -0.024265543 -0.13649899, -0.14667162 -0.024334416 -0.136484, -0.14671159 -0.024305552 -0.13647665, -0.14667854 -0.02431041 -0.13648395, -0.14763287 -0.023177356 -0.13647665, -0.14758372 -0.023137391 -0.13649891, -0.14753962 -0.02310133 -0.13653468, -0.14750278 -0.023071349 -0.13658218, -0.14747506 -0.02304855 -0.13663907, -0.14745793 -0.023034573 -0.13670252, -0.14783761 -0.022809356 -0.13653459, -0.14819244 -0.022590011 -0.13653447, -0.14780834 -0.02277182 -0.13658205, -0.14817193 -0.022546992 -0.13658205, -0.1490013 -0.022324547 -0.13663885, -0.14857623 -0.022407502 -0.13658209, -0.14900133 -0.022360176 -0.13658209, -0.14815667 -0.022514552 -0.13663878, -0.14856839 -0.022372603 -0.13663886, -0.14791176 -0.022904068 -0.13647665, -0.14787266 -0.022854179 -0.13649882, -0.14821672 -0.02264148 -0.13649873, -0.14858663 -0.022453904 -0.13653444, -0.14900124 -0.022407845 -0.13653451, -0.14824378 -0.022698715 -0.13647658, -0.14859927 -0.022509396 -0.13649862, -0.1490013 -0.022464633 -0.13649862, -0.14861313 -0.022571281 -0.13647652, -0.14900136 -0.022528052 -0.13647656, -0.14777255 -0.022726238 -0.13670246, -0.14778626 -0.022743762 -0.13663881, -0.14814723 -0.022494614 -0.13670222, -0.14856356 -0.022350982 -0.1367023, -0.14900136 -0.02230233 -0.13670228, -0.15457791 -0.022528052 -0.13647656, -0.15457776 -0.022464722 -0.13649882, -0.15457782 -0.022407919 -0.13653447, -0.15457788 -0.022360176 -0.13658203, -0.15457785 -0.022324562 -0.13663886, -0.15457788 -0.022302344 -0.1367023, -0.15500838 -0.022408724 -0.13658206, -0.1554172 -0.022551775 -0.13658212, -0.15501633 -0.022373885 -0.13663901, -0.15651241 -0.024294764 -0.13658233, -0.15641758 -0.023874894 -0.13653463, -0.15646482 -0.024294853 -0.13653468, -0.15646401 -0.023864254 -0.13658217, -0.15543273 -0.022519559 -0.13663901, -0.15627816 -0.023475975 -0.13653459, -0.15632081 -0.023455441 -0.13658218, -0.15616959 -0.023528278 -0.13647674, -0.15595925 -0.023193255 -0.1364767, -0.15580627 -0.022754356 -0.13663885, -0.15544248 -0.022499666 -0.13670239, -0.15600866 -0.023153722 -0.13649891, -0.15582013 -0.022737056 -0.13670249, -0.15622675 -0.023500755 -0.13649899, -0.15636221 -0.023887604 -0.13649894, -0.15640795 -0.024294928 -0.13649899, -0.15613562 -0.023052543 -0.13670237, -0.15630034 -0.023901671 -0.13647677, -0.15634462 -0.024294883 -0.13647665, -0.15498519 -0.022510588 -0.13649873, -0.15499783 -0.022455111 -0.13653451, -0.15539667 -0.02259472 -0.13653447, -0.15578398 -0.022782251 -0.13658217, -0.15611836 -0.023066312 -0.13663901, -0.15497097 -0.022572428 -0.13647653, -0.15637314 -0.023430228 -0.13670252, -0.15537199 -0.022645876 -0.13649896, -0.15575454 -0.02281943 -0.13653447, -0.15609029 -0.02308856 -0.13658217, -0.15635297 -0.023439914 -0.13663895, -0.15534434 -0.022703096 -0.13647655, -0.1565204 -0.02385138 -0.13670245, -0.15657035 -0.024294823 -0.13670261, -0.15571895 -0.022863954 -0.13649888, -0.15605319 -0.023118272 -0.13653475, -0.15502125 -0.022352293 -0.1367023, -0.15649876 -0.023856431 -0.13663907, -0.15654811 -0.024294749 -0.13663918, -0.15567946 -0.022913575 -0.13647662, -0.15634459 -0.027184695 -0.13647701, -0.15640801 -0.027184695 -0.13649918, -0.15646479 -0.027184665 -0.13653485, -0.15651229 -0.027184591 -0.13658246, -0.15654814 -0.027184501 -0.13663936, -0.15657037 -0.02718462 -0.13670272, -0.14766118 -0.033287525 -0.13670431, -0.14765441 -0.033264011 -0.13663758, -0.14764276 -0.033223823 -0.13657618, -0.14762717 -0.033169299 -0.13652582, -0.14760888 -0.033105284 -0.13649108, -0.14759293 -0.033049464 -0.13647501, -0.15639246 -0.027751565 -0.13670276, -0.15626162 -0.027904004 -0.13670279, -0.15639108 -0.027351737 -0.13649921, -0.15644667 -0.027363285 -0.13653496, -0.15639287 -0.027534619 -0.13653499, -0.15649322 -0.027372718 -0.13658242, -0.15643668 -0.027553216 -0.13658249, -0.15634489 -0.027718559 -0.13658261, -0.15646946 -0.027567327 -0.13663934, -0.15637425 -0.027738914 -0.13663951, -0.15610263 -0.028026924 -0.13670269, -0.15624624 -0.027887911 -0.13663937, -0.15609092 -0.028008133 -0.13663937, -0.1563288 -0.027338997 -0.13647705, -0.15634075 -0.027511939 -0.13649932, -0.15630591 -0.027691394 -0.136535, -0.15622175 -0.027861968 -0.13658261, -0.15607214 -0.02797772 -0.13658261, -0.15628245 -0.027486905 -0.13647702, -0.15625906 -0.02765891 -0.13649924, -0.15618894 -0.027827665 -0.13653496, -0.15604699 -0.027937502 -0.136535, -0.15620714 -0.027622774 -0.13647699, -0.15614974 -0.027786389 -0.13649917, -0.15601689 -0.027889267 -0.13649917, -0.15610597 -0.027740538 -0.13647704, -0.15598345 -0.027835399 -0.13647695, -0.15654987 -0.02738449 -0.13670279, -0.15652829 -0.02737993 -0.13663946, -0.15648985 -0.02757597 -0.13670276, -0.14843696 -0.035274506 -0.14023696, -0.14843702 -0.035252422 -0.14030035, -0.14843711 -0.035216689 -0.14035724, -0.14843708 -0.035169035 -0.14040478, -0.14843699 -0.035112321 -0.14044051, -0.14843705 -0.035048857 -0.14046258, -0.14937142 -0.034615308 -0.14023693, -0.14942345 -0.03439261 -0.14023691, -0.14940134 -0.034390122 -0.14030029, -0.14935058 -0.034607932 -0.14030018, -0.14917478 -0.034773901 -0.14040482, -0.14927214 -0.034579903 -0.14040484, -0.14921859 -0.034560829 -0.14044036, -0.14912745 -0.034742296 -0.14044051, -0.14919907 -0.034367546 -0.14046261, -0.14921427 -0.034800157 -0.14035717, -0.14931682 -0.034595877 -0.14035721, -0.14896247 -0.034840524 -0.14046268, -0.14907479 -0.034707174 -0.14046279, -0.14924398 -0.03481999 -0.14030029, -0.14900604 -0.034886628 -0.14044036, -0.1492624 -0.034832209 -0.14023687, -0.14904496 -0.034928143 -0.14040487, -0.14883727 -0.034935921 -0.14046271, -0.14907756 -0.034962684 -0.14035715, -0.14887038 -0.034989864 -0.14044036, -0.14910215 -0.034988612 -0.14030035, -0.14890015 -0.035038397 -0.14040479, -0.14911729 -0.035004839 -0.14023694, -0.14869785 -0.035002559 -0.14046271, -0.14892483 -0.035078928 -0.14035723, -0.14871943 -0.035062239 -0.14044049, -0.14894345 -0.035109311 -0.14030035, -0.14873883 -0.035115659 -0.14040475, -0.14915904 -0.034539595 -0.14046258, -0.14895505 -0.035128281 -0.14023688, -0.1492621 -0.034374505 -0.14044036, -0.14875501 -0.035160184 -0.14035724, -0.14931867 -0.034380868 -0.14040452, -0.1487672 -0.035193861 -0.14030032, -0.14936572 -0.034386128 -0.14035721, -0.14877471 -0.035214722 -0.1402369, -0.14921439 -0.034231111 -0.14046261, -0.14927733 -0.034238264 -0.14044049, -0.14933383 -0.034244582 -0.14040461, -0.1493811 -0.034249827 -0.14035717, -0.1494166 -0.034253791 -0.14030027, -0.14943871 -0.034256279 -0.1402369, -0.14968655 -0.033378184 -0.14035718, -0.14994356 -0.032981813 -0.14040451, -0.14964637 -0.033352867 -0.14040452, -0.14943972 -0.033780962 -0.14040448, -0.14959827 -0.033322483 -0.14044024, -0.14938596 -0.033762127 -0.14044036, -0.15001792 -0.033056483 -0.14023682, -0.15037191 -0.032776043 -0.14023671, -0.15036014 -0.032757074 -0.14030005, -0.15025267 -0.032584265 -0.14046246, -0.15000245 -0.033040777 -0.14030021, -0.14971682 -0.033397257 -0.1403002, -0.14997718 -0.033015385 -0.14035708, -0.14948446 -0.033796653 -0.14035723, -0.14973566 -0.033409059 -0.1402369, -0.14951819 -0.033808455 -0.14030024, -0.14953911 -0.033815905 -0.14023694, -0.14985877 -0.032896429 -0.14046265, -0.14990345 -0.032941371 -0.14044036, -0.15028602 -0.032638177 -0.14044032, -0.1495446 -0.033288643 -0.14046249, -0.15031621 -0.032686532 -0.14040439, -0.14932624 -0.033741131 -0.14046246, -0.15034127 -0.032726809 -0.14035699, -0.15698335 -0.02839011 -0.14046209, -0.15701693 -0.028443903 -0.14043988, -0.15704691 -0.028492302 -0.14040406, -0.15707216 -0.02853255 -0.14035675, -0.15709108 -0.028562859 -0.14029974, -0.15710264 -0.028581694 -0.14023638, -0.15754995 -0.027939171 -0.14023627, -0.15757015 -0.02773945 -0.14023617, -0.15754804 -0.02773945 -0.14029965, -0.15748972 -0.028130963 -0.14023638, -0.15714973 -0.028341204 -0.14043988, -0.15718898 -0.028382361 -0.14040415, -0.1573059 -0.028246254 -0.14040412, -0.15722165 -0.028416917 -0.14035675, -0.15734482 -0.028273314 -0.14035673, -0.15743664 -0.028107882 -0.1403567, -0.15737408 -0.028293759 -0.14029981, -0.15746945 -0.028122157 -0.14029981, -0.15752819 -0.027934834 -0.14029971, -0.15751237 -0.02773951 -0.14035657, -0.15710607 -0.028295144 -0.14046207, -0.15725917 -0.02821365 -0.14043994, -0.15739298 -0.028089255 -0.14040418, -0.15749329 -0.027927577 -0.14035647, -0.1574648 -0.027739465 -0.14040403, -0.15720725 -0.028177485 -0.14046195, -0.15734079 -0.028066739 -0.14043984, -0.15744671 -0.027918026 -0.14040408, -0.15740794 -0.02773948 -0.14043975, -0.15728229 -0.028041765 -0.14046201, -0.15739089 -0.027906522 -0.14043972, -0.15734461 -0.027739435 -0.14046194, -0.15732887 -0.027893692 -0.14046206, -0.15726155 -0.028458744 -0.14023633, -0.15724632 -0.028442785 -0.14029977, -0.1573925 -0.02830638 -0.1402365, -0.15757027 -0.023794547 -0.14023596, -0.1575481 -0.023794547 -0.14029938, -0.15751243 -0.023794562 -0.14035614, -0.15746486 -0.023794442 -0.14040358, -0.15740797 -0.023794606 -0.14043939, -0.15734455 -0.023794547 -0.14046156, -0.15608886 -0.021695152 -0.14043921, -0.15656611 -0.021928251 -0.14040343, -0.15611365 -0.021643862 -0.14040342, -0.15653071 -0.021972731 -0.14043921, -0.15560898 -0.021467268 -0.14040343, -0.1550777 -0.021359965 -0.14035597, -0.15507784 -0.02140747 -0.14040336, -0.15727136 -0.022738218 -0.14035617, -0.15745139 -0.023252755 -0.14035626, -0.15748623 -0.023244768 -0.14029934, -0.15561953 -0.021421075 -0.14035599, -0.1573036 -0.022722602 -0.14029936, -0.1561341 -0.02160114 -0.14035593, -0.15606147 -0.021752283 -0.14046147, -0.15649122 -0.022022292 -0.14046147, -0.15700915 -0.022254258 -0.14029922, -0.15732351 -0.022713065 -0.14023583, -0.15702653 -0.022240445 -0.14023575, -0.15559632 -0.02152279 -0.14043917, -0.15507782 -0.021464393 -0.1404393, -0.1566318 -0.021845892 -0.14023578, -0.1555824 -0.021584615 -0.14046142, -0.15507782 -0.021527812 -0.14046147, -0.15734959 -0.02327612 -0.14043947, -0.15740502 -0.023263425 -0.1404037, -0.15722862 -0.022758842 -0.14040361, -0.15698126 -0.022276655 -0.140356, -0.15661812 -0.021863148 -0.14029917, -0.15728766 -0.023290157 -0.14046155, -0.1561594 -0.021548942 -0.14023566, -0.15717724 -0.022783458 -0.14043932, -0.15694416 -0.022306129 -0.14040348, -0.15659574 -0.021891132 -0.140356, -0.15614972 -0.021568954 -0.14029913, -0.15712014 -0.022810936 -0.14046149, -0.15563241 -0.02136457 -0.14023571, -0.15507784 -0.02130197 -0.14023569, -0.15689963 -0.022341669 -0.14043932, -0.1575079 -0.023239881 -0.14023586, -0.15562752 -0.021386132 -0.14029899, -0.15507782 -0.021324307 -0.14029904, -0.15685013 -0.022381201 -0.14046144, -0.14876413 -0.021302 -0.14023578, -0.14876413 -0.021324098 -0.14029901, -0.14876401 -0.021359935 -0.14035606, -0.1487641 -0.021407455 -0.1404034, -0.14876413 -0.021464244 -0.14043927, -0.14876416 -0.021527678 -0.1404614, -0.14774072 -0.021637857 -0.14040343, -0.14823973 -0.021465793 -0.14040351, -0.14822912 -0.021419346 -0.14035599, -0.14772046 -0.021594942 -0.14035599, -0.14726272 -0.021877974 -0.14035602, -0.14685071 -0.022232115 -0.14029913, -0.14687824 -0.022254705 -0.14035605, -0.14770511 -0.021562666 -0.14029898, -0.14724064 -0.021849811 -0.14029913, -0.14826602 -0.021583095 -0.1404615, -0.14825219 -0.021521211 -0.1404392, -0.14776516 -0.021689236 -0.1404392, -0.14729193 -0.021915406 -0.14040346, -0.14691526 -0.022284746 -0.14040349, -0.14779246 -0.021746576 -0.14046137, -0.14732707 -0.021960139 -0.14043938, -0.14695907 -0.022320688 -0.14043932, -0.14736623 -0.022010088 -0.14046143, -0.14700839 -0.022360876 -0.14046156, -0.14821643 -0.02136296 -0.14023577, -0.14822137 -0.021384537 -0.14029901, -0.14769563 -0.021542639 -0.14023568, -0.14722687 -0.021832347 -0.14023571, -0.14683351 -0.022218078 -0.14023568, -0.097284228 -0.032586858 -0.22426817, -0.11272535 -0.032587737 -0.22426791, -0.097212583 -0.032837927 -0.22401233, -0.11280975 -0.032837942 -0.2240122, -0.12734789 -0.03328 -0.16084585, -0.12734783 -0.032649681 -0.16048226, -0.12705088 -0.033280179 -0.16087797, -0.12734795 -0.033240288 -0.16073664, -0.1270287 -0.033241317 -0.16077223, -0.12734795 -0.033176363 -0.16063963, -0.12700921 -0.033179149 -0.16067824, -0.12734798 -0.033091873 -0.16055997, -0.12699282 -0.033096835 -0.16060069, -0.12734798 -0.032991245 -0.16050196, -0.12698108 -0.032998651 -0.1605434, -0.12734795 -0.032880068 -0.16046868, -0.12697399 -0.032889903 -0.16050945, -0.12734801 -0.032764062 -0.16046199, -0.1269722 -0.032775685 -0.16050056, -0.12697601 -0.032662272 -0.16051744, -0.13651499 -0.03327994 -0.16084579, -0.13651508 -0.033240154 -0.16073674, -0.13651499 -0.033176348 -0.16063967, -0.13651502 -0.033091828 -0.16056004, -0.13651511 -0.032991305 -0.16050196, -0.13651502 -0.032880008 -0.16046874, -0.13651502 -0.032764018 -0.16046195, -0.13651502 -0.032649696 -0.16048227, -0.1365827 -0.032890484 -0.16046324, -0.13665962 -0.032908008 -0.16044119, -0.13658071 -0.03277652 -0.16045418, -0.13665408 -0.032797575 -0.16042911, -0.13673246 -0.032825887 -0.16038357, -0.13665894 -0.032686219 -0.1604397, -0.13673532 -0.032717764 -0.16038726, -0.13660529 -0.033112034 -0.16056588, -0.13659009 -0.032999203 -0.1604971, -0.13667518 -0.033012375 -0.16047511, -0.13682261 -0.032763645 -0.16029808, -0.13692981 -0.032861114 -0.16012673, -0.1367434 -0.032931373 -0.16039827, -0.13662919 -0.03321223 -0.16067556, -0.13682601 -0.032866523 -0.16030088, -0.13695753 -0.032976568 -0.16013823, -0.13670477 -0.0331202 -0.16053966, -0.1367673 -0.033030018 -0.16043052, -0.1368452 -0.032964602 -0.16031706, -0.13701007 -0.033081576 -0.16015968, -0.13665783 -0.033273518 -0.16080593, -0.13675115 -0.033215687 -0.16064021, -0.13680995 -0.033131018 -0.16048819, -0.13687834 -0.033054873 -0.16034511, -0.13708392 -0.033170208 -0.16018972, -0.13680562 -0.033274218 -0.160759, -0.13687456 -0.033220351 -0.16057543, -0.13727856 -0.033279255 -0.16026974, -0.1365844 -0.032663286 -0.16047071, -0.13693342 -0.033146292 -0.16039146, -0.13695005 -0.033275321 -0.16067725, -0.13701373 -0.033226967 -0.16045927, -0.13717517 -0.033237264 -0.16022727, -0.13710627 -0.033276722 -0.16053739, -0.13777599 -0.033279344 -0.15905467, -0.13767257 -0.033237427 -0.15901221, -0.1375815 -0.033170253 -0.15897496, -0.13750747 -0.033081636 -0.1589447, -0.13745511 -0.032976732 -0.15892324, -0.13742721 -0.032861277 -0.15891185, -0.13737646 -0.033205658 -0.1580186, -0.13740739 -0.033152506 -0.15811911, -0.13734731 -0.033159658 -0.15806809, -0.1375227 -0.033023074 -0.15875733, -0.13755366 -0.033065364 -0.15858069, -0.13748375 -0.032920927 -0.15875126, -0.13764706 -0.033281028 -0.15802382, -0.13750812 -0.032976434 -0.15858421, -0.13772073 -0.033279911 -0.15813214, -0.13762617 -0.033238932 -0.15819052, -0.1375666 -0.033243641 -0.15809366, -0.13758191 -0.033113524 -0.15876648, -0.13761482 -0.033142254 -0.15857568, -0.13741541 -0.033249483 -0.15795133, -0.13744462 -0.03320092 -0.15807454, -0.13749522 -0.033247143 -0.1580133, -0.13749921 -0.033023044 -0.15843037, -0.13756081 -0.033281878 -0.15793401, -0.13781616 -0.033271447 -0.15880227, -0.13746604 -0.033282474 -0.15786463, -0.13767856 -0.033203408 -0.15878126, -0.13754621 -0.033100232 -0.15841529, -0.13770804 -0.033217713 -0.15856794, -0.13760453 -0.033165812 -0.15839647, -0.13746029 -0.033061028 -0.15829323, -0.13783658 -0.033274829 -0.15855758, -0.13750353 -0.033128351 -0.15826632, -0.13768896 -0.033229515 -0.15836921, -0.13742173 -0.033080041 -0.1582195, -0.1375545 -0.033184692 -0.15823498, -0.13746035 -0.03314203 -0.15818582, -0.13737473 -0.033094436 -0.15815873, -0.13780266 -0.033277541 -0.1583326, -0.13750499 -0.033193946 -0.1581472, -0.13732159 -0.033104256 -0.15811241, -0.12828636 -0.033128425 -0.15803835, -0.12828636 -0.033198148 -0.15796067, -0.12828645 -0.033250362 -0.15787025, -0.12828642 -0.033282623 -0.15777084, -0.12718523 -0.033086345 -0.15842226, -0.12714082 -0.033173069 -0.15835598, -0.12708628 -0.033238694 -0.15827468, -0.12702453 -0.033279687 -0.15818299, -0.12790787 -0.033119589 -0.15808584, -0.12789196 -0.033193097 -0.15800902, -0.12787318 -0.033247992 -0.15791926, -0.12785256 -0.033281967 -0.15781966, -0.12226549 -0.033081532 -0.16173004, -0.12226695 -0.033166379 -0.16163798, -0.11165527 0.10083471 -0.23503083, -0.11165532 0.10075577 -0.23510805, -0.11093476 0.10021849 -0.2353029, -0.11093032 0.1002831 -0.23532221, -0.11092275 0.10034944 -0.23533329, -0.11090255 0.10046588 -0.23533159, -0.11087409 0.10057718 -0.23530357, -0.11083946 0.10067697 -0.23525098, -0.11080024 0.10075985 -0.23517668, -0.11126634 0.10058029 -0.23522356, -0.11165535 0.10066183 -0.23516619, -0.11165538 0.10055728 -0.23520219, -0.12049392 0.10083462 -0.23503086, -0.12049395 0.10075578 -0.235108, -0.12049389 0.1006618 -0.2351661, -0.12049398 0.10055727 -0.23520218, -0.12075272 0.10021114 -0.23525883, -0.12076184 0.10029548 -0.23528908, -0.12067416 0.10023975 -0.23521508, -0.12068063 0.10032463 -0.23524262, -0.12062696 0.10065091 -0.23518158, -0.12060928 0.10054532 -0.23521553, -0.12072045 0.10052252 -0.23525192, -0.12059578 0.10043439 -0.23522471, -0.12069398 0.10041201 -0.23525609, -0.12078071 0.10038206 -0.2353069, -0.12064835 0.10074562 -0.23512553, -0.12075573 0.10062686 -0.23522441, -0.1208185 0.10049006 -0.23531036, -0.1206719 0.1008248 -0.23504989, -0.12079841 0.10071981 -0.23517479, -0.12086985 0.100591 -0.23529254, -0.12084574 0.10079634 -0.23510624, -0.12093171 0.10067934 -0.23525415, -0.12100074 0.10075039 -0.23519753, -0.12058535 0.10026193 -0.23518993, -0.12058896 0.10034668 -0.23521473, -0.12077749 0.099875614 -0.23694542, -0.12067586 0.099858284 -0.23688938, -0.12058571 0.099816799 -0.23682655, -0.12051219 0.099753618 -0.23676075, -0.12045893 0.099671915 -0.23669529, -0.12042937 0.099576414 -0.23663364, -0.12061682 0.099807873 -0.23699307, -0.12053618 0.099774778 -0.23691688, -0.12046951 0.09971869 -0.23683955, -0.12046531 0.099736109 -0.23700106, -0.12040886 0.099687368 -0.23691408, -0.1203672 0.09961772 -0.23683287, -0.12021819 0.099583879 -0.23693725, -0.12034249 0.099531099 -0.2367622, -0.12020379 0.099506378 -0.23685928, -0.12012377 0.099503636 -0.23688735, -0.12004349 0.099507034 -0.23690055, -0.12070775 0.099816412 -0.23706464, -0.12053347 0.099761307 -0.23708914, -0.12024081 0.099642813 -0.2370287, -0.12013125 0.099577516 -0.23696737, -0.12004337 0.099578291 -0.2369812, -0.12060982 0.099761963 -0.23717429, -0.1202704 0.099679604 -0.23712873, -0.1201427 0.099632412 -0.23706113, -0.12004331 0.099630594 -0.23707543, -0.12030569 0.099692941 -0.23723234, -0.12015742 0.099665552 -0.23716359, -0.12004328 0.099661559 -0.23717849, -0.12034523 0.099682182 -0.23733537, -0.12017494 0.099675417 -0.23727037, -0.12004343 0.099669784 -0.2372859, -0.12004334 0.099654675 -0.23739244, -0.12019444 0.099661797 -0.23737685, -0.12039334 0.099551439 -0.2366996, -0.12042093 0.099642679 -0.23676565, -0.11087626 0.099507108 -0.23690066, -0.11087623 0.099578321 -0.23698132, -0.11087623 0.09963055 -0.23707542, -0.11087626 0.099661559 -0.23717864, -0.11087617 0.09966965 -0.23728588, -0.11087614 0.09965463 -0.23739257, -0.11029968 0.0996079 -0.23748448, -0.11026263 0.099619552 -0.2373808, -0.11022925 0.099606827 -0.23727608, -0.11020133 0.099570498 -0.23717526, -0.11018008 0.099512547 -0.23708351, -0.11016655 0.099435404 -0.2370052, -0.13389647 -0.033280909 -0.14485554, -0.13389635 -0.03265065 -0.14449196, -0.13359943 -0.033281311 -0.1448876, -0.13389635 -0.033241212 -0.14474647, -0.13357729 -0.033242449 -0.1447821, -0.13389641 -0.033177376 -0.14464943, -0.13355756 -0.033180192 -0.14468807, -0.13389641 -0.033092797 -0.14456962, -0.13354138 -0.033097729 -0.14461043, -0.13389635 -0.032992303 -0.14451163, -0.13352937 -0.032999635 -0.14455323, -0.13389641 -0.032880887 -0.14447835, -0.13352245 -0.032890901 -0.14451918, -0.13389626 -0.032764986 -0.1444717, -0.13352072 -0.032776654 -0.14451031, -0.13352448 -0.032663345 -0.14452712, -0.14306352 -0.033280984 -0.14485556, -0.14306363 -0.033241168 -0.14474636, -0.14306369 -0.03317745 -0.14464945, -0.14306358 -0.033092946 -0.14456971, -0.1430636 -0.032992244 -0.14451174, -0.1430636 -0.032880992 -0.14447851, -0.14306352 -0.03276518 -0.14447178, -0.14306363 -0.032650605 -0.14449197, -0.14313126 -0.032891437 -0.14447287, -0.14320818 -0.032909051 -0.1444509, -0.14312935 -0.032777473 -0.14446393, -0.1432026 -0.032798499 -0.1444387, -0.14328107 -0.032826796 -0.14439327, -0.14320737 -0.032687172 -0.14444938, -0.14328381 -0.032718658 -0.14439695, -0.14315376 -0.033113137 -0.14457577, -0.14313877 -0.033000275 -0.14450696, -0.14322373 -0.033013374 -0.14448465, -0.14337116 -0.032764643 -0.14430781, -0.14347821 -0.032862157 -0.14413638, -0.14329204 -0.032932416 -0.14440805, -0.14317772 -0.033213288 -0.14468528, -0.14337459 -0.032867566 -0.14431071, -0.14350623 -0.032977581 -0.14414768, -0.1432533 -0.033121124 -0.14454931, -0.1433157 -0.033031076 -0.14444025, -0.14339361 -0.032965556 -0.14432675, -0.14355835 -0.033082619 -0.14416927, -0.1432063 -0.033274516 -0.14481571, -0.14329958 -0.0332167 -0.14464983, -0.14335847 -0.033132002 -0.14449778, -0.14342672 -0.033055753 -0.14435478, -0.1436325 -0.033171222 -0.14419964, -0.14335403 -0.033275247 -0.14476864, -0.14342305 -0.03322126 -0.14458501, -0.14382705 -0.033280164 -0.14427926, -0.1431329 -0.032664314 -0.14448053, -0.14348188 -0.033147231 -0.14440131, -0.14349848 -0.033276305 -0.14468691, -0.14356211 -0.033227876 -0.14446896, -0.14372361 -0.033238247 -0.14423698, -0.14365479 -0.03327775 -0.14454715, -0.14432463 -0.033280268 -0.14306438, -0.14422128 -0.033238366 -0.143022, -0.14412996 -0.033171237 -0.14298479, -0.14405611 -0.03308256 -0.14295447, -0.14400354 -0.032977611 -0.14293309, -0.1439757 -0.032862276 -0.1429214, -0.14392492 -0.033206657 -0.14202827, -0.14389592 -0.033160612 -0.14207789, -0.1439558 -0.033153504 -0.1421289, -0.14407116 -0.033023998 -0.14276704, -0.14410216 -0.033066362 -0.14259036, -0.14403239 -0.032921821 -0.14276095, -0.14405659 -0.032977492 -0.14259405, -0.14419547 -0.033281922 -0.14203368, -0.1441747 -0.033239961 -0.14220046, -0.14411512 -0.033244625 -0.14210337, -0.14413065 -0.033114478 -0.1427761, -0.14416319 -0.033143446 -0.14258549, -0.14426908 -0.033280924 -0.142142, -0.14404377 -0.033248082 -0.14202309, -0.14396399 -0.033250362 -0.14196117, -0.14399308 -0.033201799 -0.14208427, -0.14404771 -0.033024088 -0.14244008, -0.14410943 -0.033282861 -0.14194384, -0.14436477 -0.03327243 -0.1428121, -0.14401448 -0.033283472 -0.14187436, -0.14422721 -0.033204362 -0.14279094, -0.14409479 -0.033101156 -0.142425, -0.14425656 -0.03321892 -0.14257781, -0.14415294 -0.03316699 -0.14240631, -0.14400879 -0.033062175 -0.14230311, -0.14438501 -0.033275723 -0.14256726, -0.144052 -0.033129275 -0.14227621, -0.14423749 -0.033230558 -0.14237905, -0.14397022 -0.03308095 -0.14222914, -0.14410302 -0.03318578 -0.1422445, -0.14400887 -0.033143044 -0.14219569, -0.14392325 -0.033095315 -0.14216846, -0.14435118 -0.033278629 -0.14234254, -0.14405346 -0.033194944 -0.14215699, -0.14387006 -0.03310518 -0.142122, -0.13483503 -0.033129245 -0.14204808, -0.13483492 -0.033199146 -0.14197046, -0.13483489 -0.033251345 -0.14187984, -0.13483503 -0.033283621 -0.14178069, -0.13373393 -0.033087432 -0.14243208, -0.13368934 -0.033174157 -0.1423658, -0.13363478 -0.033239812 -0.14228447, -0.13357323 -0.033280611 -0.14219283, -0.13445637 -0.033120602 -0.1420954, -0.13444042 -0.033194005 -0.1420189, -0.13442177 -0.033248842 -0.14192902, -0.13440096 -0.033282816 -0.14182936, -0.13062215 -0.033280298 -0.15285072, -0.13062221 -0.032650083 -0.15248723, -0.13032508 -0.033280656 -0.15288278, -0.13062215 -0.033240721 -0.15274152, -0.13030308 -0.033241719 -0.15277715, -0.13062221 -0.033176869 -0.15264459, -0.13028345 -0.033179536 -0.1526832, -0.13062218 -0.033092305 -0.15256485, -0.13026714 -0.033097297 -0.15260561, -0.13062227 -0.032991737 -0.15250678, -0.13025516 -0.032999128 -0.15254827, -0.13062215 -0.03288047 -0.15247354, -0.1302481 -0.032890275 -0.1525144, -0.13062215 -0.03276448 -0.15246674, -0.13024646 -0.032776207 -0.15250547, -0.13025007 -0.032662764 -0.15252221, -0.13978919 -0.033280477 -0.15285066, -0.13978928 -0.033240691 -0.15274161, -0.13978925 -0.033176884 -0.15264454, -0.13978937 -0.033092365 -0.15256497, -0.13978943 -0.032991782 -0.15250677, -0.13978922 -0.0328805 -0.15247357, -0.1397894 -0.032764539 -0.15246698, -0.13978928 -0.032650217 -0.15248701, -0.13985714 -0.032890946 -0.15246816, -0.13993403 -0.032908469 -0.15244611, -0.13985506 -0.032777056 -0.15245911, -0.13992834 -0.032798097 -0.1524339, -0.14000669 -0.03282629 -0.15238842, -0.13993323 -0.032686695 -0.15244463, -0.14000967 -0.032718152 -0.15239222, -0.13987949 -0.033112511 -0.15257081, -0.13986441 -0.032999665 -0.15250225, -0.13994947 -0.033012852 -0.15247986, -0.14009693 -0.032764032 -0.15230292, -0.14020398 -0.032861799 -0.15213163, -0.14001763 -0.032931909 -0.15240327, -0.13990349 -0.033212796 -0.15268058, -0.14010027 -0.032867059 -0.15230581, -0.14023188 -0.032977089 -0.15214285, -0.13997915 -0.033120677 -0.15254453, -0.14004168 -0.033030421 -0.1524355, -0.1401194 -0.032965094 -0.15232189, -0.14028421 -0.033081993 -0.15216461, -0.13993219 -0.033274025 -0.15281077, -0.14002529 -0.033216223 -0.15264508, -0.14008418 -0.033131465 -0.15249285, -0.1401526 -0.033055291 -0.15234992, -0.14035809 -0.0331707 -0.15219478, -0.14007983 -0.033274785 -0.15276378, -0.14014888 -0.033220768 -0.15258019, -0.14055273 -0.033279687 -0.15227456, -0.13985869 -0.032663733 -0.15247567, -0.14020768 -0.033146709 -0.1523964, -0.14022443 -0.033275738 -0.15268213, -0.14028803 -0.033227414 -0.15246411, -0.14044946 -0.033237711 -0.15223223, -0.14038062 -0.033277228 -0.15254235, -0.14105028 -0.033279911 -0.15105945, -0.14094701 -0.033237889 -0.15101713, -0.14085561 -0.033170804 -0.15097985, -0.14078185 -0.033082157 -0.15094955, -0.14072931 -0.032977208 -0.15092805, -0.14070153 -0.032861739 -0.15091665, -0.14065072 -0.03320612 -0.1500234, -0.14068168 -0.033153042 -0.15012392, -0.1406216 -0.033160195 -0.15007296, -0.14079684 -0.033023566 -0.15076216, -0.1408278 -0.03306587 -0.15058541, -0.14075822 -0.032921344 -0.15075614, -0.14092132 -0.03328158 -0.15002877, -0.14078233 -0.032977 -0.15058917, -0.14099485 -0.033280358 -0.15013704, -0.14090043 -0.033239469 -0.15019545, -0.14084086 -0.033244029 -0.15009838, -0.14085627 -0.033114061 -0.15077117, -0.14088911 -0.033142909 -0.1505805, -0.14068982 -0.03324987 -0.14995617, -0.14071879 -0.033201352 -0.15007931, -0.14076942 -0.033247575 -0.15001819, -0.14077353 -0.033023641 -0.15043524, -0.14083511 -0.033282384 -0.14993891, -0.14109054 -0.033271879 -0.15080722, -0.14074039 -0.03328298 -0.14986935, -0.14095294 -0.03320387 -0.15078612, -0.14082038 -0.033100709 -0.1504201, -0.14098251 -0.033218324 -0.15057288, -0.14087874 -0.033166394 -0.1504012, -0.14073461 -0.033061609 -0.15029797, -0.14111087 -0.033275262 -0.15056247, -0.14077783 -0.033128768 -0.15027125, -0.14096349 -0.033230111 -0.15037408, -0.14069599 -0.033080563 -0.1502243, -0.14082891 -0.033185169 -0.15023962, -0.14073461 -0.033142552 -0.15019068, -0.14064893 -0.033094913 -0.15016349, -0.14107698 -0.033278093 -0.15033755, -0.14077932 -0.033194527 -0.15015206, -0.14059591 -0.033104762 -0.15011719, -0.13156071 -0.033128813 -0.15004319, -0.13156056 -0.03319867 -0.14996547, -0.13156068 -0.033250853 -0.14987519, -0.13156074 -0.0332831 -0.14977577, -0.13045961 -0.033086896 -0.15042715, -0.13041508 -0.033173636 -0.15036088, -0.13036063 -0.033239156 -0.1502796, -0.13029891 -0.033280134 -0.15018789, -0.13118225 -0.033120036 -0.15009062, -0.13116613 -0.033193544 -0.15001398, -0.13114741 -0.03324838 -0.14992398, -0.13112682 -0.033282399 -0.14982454, -0.12553969 -0.033081979 -0.153735, -0.12554118 -0.033166781 -0.15364283, -0.12407368 -0.033279404 -0.16884086, -0.12407365 -0.032649189 -0.16847731, -0.12377673 -0.033279613 -0.16887319, -0.12407377 -0.033239648 -0.16873184, -0.12375462 -0.033240795 -0.16876744, -0.12407365 -0.033175811 -0.1686348, -0.12373486 -0.033178672 -0.16867343, -0.12407377 -0.033091322 -0.16855514, -0.12371865 -0.033096299 -0.16859588, -0.12407377 -0.032990739 -0.168497, -0.12370676 -0.032998279 -0.16853857, -0.12407383 -0.032879427 -0.16846383, -0.12369981 -0.032889336 -0.16850467, -0.12407374 -0.032763481 -0.16845714, -0.12369794 -0.032775149 -0.16849563, -0.12370172 -0.032661811 -0.16851246, -0.13324082 -0.033279479 -0.16884093, -0.13324085 -0.033239752 -0.16873188, -0.13324085 -0.033175915 -0.16863479, -0.13324085 -0.033091322 -0.16855514, -0.13324079 -0.032990858 -0.16849723, -0.13324088 -0.032879591 -0.16846387, -0.13324082 -0.032763645 -0.16845706, -0.13324079 -0.032649368 -0.16847737, -0.1333085 -0.032890171 -0.16845842, -0.13338545 -0.032907471 -0.16843632, -0.13330644 -0.032776058 -0.16844927, -0.13337979 -0.032797068 -0.1684242, -0.13345832 -0.03282541 -0.16837858, -0.13338464 -0.032685742 -0.16843465, -0.13346106 -0.032717228 -0.16838263, -0.13333094 -0.033111691 -0.16856109, -0.13331589 -0.032998845 -0.16849235, -0.13340101 -0.033011958 -0.16847017, -0.13354838 -0.032763287 -0.16829315, -0.1336554 -0.032860845 -0.16812177, -0.13346922 -0.032930985 -0.16839343, -0.13335508 -0.033211872 -0.16867074, -0.13355172 -0.03286618 -0.16829614, -0.13368329 -0.032976195 -0.16813329, -0.13343066 -0.033119678 -0.16853468, -0.1334931 -0.033029526 -0.16842569, -0.13357076 -0.032964319 -0.16831215, -0.13373578 -0.033081219 -0.16815475, -0.13338363 -0.033273026 -0.16880098, -0.13347676 -0.033215255 -0.1686352, -0.13353571 -0.033130571 -0.16848317, -0.13360405 -0.033054411 -0.16834013, -0.13380972 -0.033169731 -0.16818491, -0.13353133 -0.033273757 -0.16875403, -0.13360035 -0.033219889 -0.16857046, -0.13400429 -0.033278808 -0.16826478, -0.13331017 -0.032662675 -0.16846588, -0.13365912 -0.033145845 -0.1683865, -0.13367581 -0.033274829 -0.16867237, -0.13373938 -0.03322646 -0.1684543, -0.13390109 -0.033236936 -0.16822237, -0.13383213 -0.033276394 -0.16853267, -0.13450187 -0.033278808 -0.1670498, -0.13439831 -0.033236951 -0.16700752, -0.13430732 -0.033169731 -0.16697004, -0.13423321 -0.033081204 -0.16693999, -0.13418093 -0.03297624 -0.16691841, -0.13415301 -0.032860816 -0.16690706, -0.13410208 -0.033205226 -0.16601366, -0.13407317 -0.03315933 -0.16606337, -0.13413322 -0.033152163 -0.16611432, -0.13424847 -0.033022568 -0.16675237, -0.1342794 -0.033064812 -0.16657557, -0.13420972 -0.03292045 -0.16674645, -0.13423392 -0.032975957 -0.1665794, -0.1343728 -0.033280581 -0.16601904, -0.13435197 -0.033238485 -0.16618568, -0.13429236 -0.033243224 -0.16608885, -0.13430783 -0.033113092 -0.16676135, -0.13434061 -0.033141896 -0.16657069, -0.13444629 -0.033279404 -0.16612735, -0.13422102 -0.033246681 -0.16600832, -0.1341413 -0.033248946 -0.16594651, -0.13417026 -0.033200428 -0.16606954, -0.13422507 -0.033022642 -0.16642557, -0.13428655 -0.033281356 -0.16592927, -0.13454199 -0.03327091 -0.16679746, -0.13419199 -0.033282027 -0.16585973, -0.13440448 -0.033202872 -0.16677633, -0.13427195 -0.033099696 -0.16641048, -0.13443384 -0.033217236 -0.16656306, -0.13433021 -0.033165395 -0.16639172, -0.13418606 -0.03306064 -0.16628839, -0.13456237 -0.033274278 -0.16655257, -0.1342293 -0.03312771 -0.16626146, -0.13441476 -0.033229038 -0.16636434, -0.1341475 -0.033079594 -0.16621454, -0.13428029 -0.03318426 -0.16623004, -0.13418609 -0.033141688 -0.16618091, -0.13410047 -0.033094019 -0.1661538, -0.13452858 -0.033277139 -0.16632786, -0.13423067 -0.033193469 -0.16614227, -0.13404736 -0.033103749 -0.16610745, -0.12501222 -0.033127889 -0.16603354, -0.12501219 -0.033197775 -0.16595578, -0.12501222 -0.033249915 -0.16586541, -0.12501234 -0.033282265 -0.16576597, -0.1239112 -0.033085853 -0.16641738, -0.12386659 -0.033172622 -0.1663512, -0.12381211 -0.033238322 -0.16626985, -0.12375042 -0.033279255 -0.16617811, -0.12463376 -0.033119202 -0.166081, -0.12461764 -0.033192605 -0.16600426, -0.12459907 -0.033247486 -0.16591424, -0.12457842 -0.03328155 -0.16581479, -0.11899123 -0.033081129 -0.16972518, -0.11899269 -0.033165917 -0.16963312, -0.12079942 -0.033278987 -0.17683604, -0.12079948 -0.032648772 -0.17647244, -0.12050244 -0.033279195 -0.17686826, -0.12079939 -0.03323926 -0.17672688, -0.1204803 -0.033240467 -0.1767626, -0.12079939 -0.033175483 -0.1766299, -0.12046063 -0.03317824 -0.17666854, -0.12079942 -0.033091024 -0.17655021, -0.12044433 -0.033095911 -0.17659098, -0.12079948 -0.032990366 -0.17649229, -0.12043244 -0.032997817 -0.17653359, -0.12079945 -0.032879055 -0.176459, -0.12042549 -0.032888904 -0.17649966, -0.12079945 -0.032763124 -0.17645232, -0.12042382 -0.032774791 -0.17649075, -0.1204274 -0.032661393 -0.17650765, -0.12996653 -0.033279002 -0.17683612, -0.12996668 -0.033239469 -0.17672691, -0.12996665 -0.033175543 -0.17663002, -0.12996665 -0.033091143 -0.17655039, -0.12996668 -0.032990441 -0.17649212, -0.12996668 -0.032879099 -0.17645898, -0.12996665 -0.032763213 -0.17645223, -0.12996668 -0.032648847 -0.17647263, -0.13003424 -0.032889664 -0.17645346, -0.13011116 -0.032907113 -0.17643133, -0.13003218 -0.0327757 -0.1764444, -0.13010558 -0.032796696 -0.1764192, -0.13018394 -0.032825053 -0.17637371, -0.13011041 -0.032685369 -0.17642976, -0.13018686 -0.032716841 -0.17637755, -0.13005677 -0.033111274 -0.17655621, -0.13004166 -0.032998413 -0.17648746, -0.1301266 -0.033011615 -0.17646526, -0.13027424 -0.032762855 -0.1762882, -0.13038129 -0.032860368 -0.17611684, -0.13019505 -0.032930627 -0.17638856, -0.13008085 -0.033211485 -0.17666584, -0.1302776 -0.032865658 -0.17629111, -0.13040918 -0.032975763 -0.17612828, -0.13015634 -0.033119306 -0.17652979, -0.13021877 -0.033029273 -0.17642075, -0.13029665 -0.032963738 -0.17630729, -0.1304616 -0.033080667 -0.1761498, -0.13010937 -0.033272609 -0.17679611, -0.13020256 -0.033214897 -0.17663039, -0.13026145 -0.033130139 -0.17647816, -0.13032988 -0.033053964 -0.17633523, -0.13053551 -0.033169329 -0.17618011, -0.13025704 -0.033273429 -0.17674913, -0.13032603 -0.033219457 -0.17656557, -0.13073 -0.033278406 -0.1762598, -0.13003606 -0.032662377 -0.17646095, -0.13038489 -0.033145428 -0.17638169, -0.1304017 -0.033274427 -0.17666757, -0.13046518 -0.033226088 -0.17644954, -0.13062674 -0.033236369 -0.17621747, -0.13055792 -0.033275917 -0.17652774, -0.13122752 -0.033278421 -0.17504501, -0.13112429 -0.033236474 -0.17500253, -0.13103294 -0.033169448 -0.17496525, -0.13095906 -0.033080757 -0.17493491, -0.13090661 -0.032975763 -0.17491354, -0.13087872 -0.032860339 -0.17490207, -0.1308279 -0.033204734 -0.17400877, -0.13079911 -0.033158749 -0.17405833, -0.13085893 -0.033151716 -0.17410935, -0.13097435 -0.033022031 -0.1747475, -0.13100523 -0.03306447 -0.17457077, -0.13093534 -0.032919943 -0.17474149, -0.13095966 -0.032975614 -0.17457448, -0.13109857 -0.033280104 -0.17401399, -0.1310778 -0.033238009 -0.17418087, -0.1310181 -0.033242747 -0.17408392, -0.13103354 -0.033112586 -0.17475663, -0.13106635 -0.033141553 -0.17456578, -0.13117197 -0.033279002 -0.17412244, -0.13094679 -0.033246234 -0.17400348, -0.13086703 -0.033248603 -0.1739416, -0.13089606 -0.033199981 -0.17406458, -0.13095084 -0.033022225 -0.17442058, -0.13101235 -0.033281028 -0.17392431, -0.13126782 -0.033270434 -0.17479253, -0.1309177 -0.033281535 -0.17385496, -0.13113019 -0.033202469 -0.17477135, -0.13099766 -0.033099353 -0.1744055, -0.13115963 -0.033216968 -0.17455816, -0.13105598 -0.033165038 -0.17438672, -0.13091174 -0.033060253 -0.17428337, -0.13128826 -0.03327395 -0.17454767, -0.13095513 -0.033127397 -0.17425658, -0.13114056 -0.033228695 -0.17435949, -0.13087326 -0.033079132 -0.17420962, -0.13100591 -0.033183753 -0.17422496, -0.13091195 -0.033141196 -0.1741759, -0.13082615 -0.033093512 -0.17414878, -0.13125435 -0.033276752 -0.17432296, -0.13095641 -0.033193052 -0.17413728, -0.1307731 -0.033103436 -0.17410256, -0.12173796 -0.033127442 -0.17402858, -0.12173799 -0.033197209 -0.17395082, -0.12173802 -0.033249363 -0.1738604, -0.12173808 -0.033281684 -0.17376111, -0.12063682 -0.03308554 -0.17441255, -0.12059233 -0.033172265 -0.17434639, -0.12053776 -0.0332378 -0.174265, -0.12047619 -0.033278778 -0.17417336, -0.12135947 -0.033118725 -0.17407613, -0.12134352 -0.033192143 -0.1739994, -0.12132472 -0.033246934 -0.17390935, -0.12130398 -0.033280969 -0.17380993, -0.11571696 -0.033080623 -0.17772034, -0.11571836 -0.033165395 -0.17762832, -0.11752519 -0.033278435 -0.18483134, -0.11752516 -0.032648265 -0.18446766, -0.11722815 -0.033278823 -0.18486325, -0.11752522 -0.033238888 -0.18472205, -0.11720595 -0.033239946 -0.18475756, -0.11752522 -0.033174947 -0.18462509, -0.1171864 -0.033177808 -0.18466371, -0.11752516 -0.033090413 -0.18454526, -0.11717016 -0.033095419 -0.18458615, -0.11752525 -0.032989949 -0.18448736, -0.11715823 -0.032997251 -0.18452881, -0.11752522 -0.032878593 -0.18445414, -0.11715126 -0.032888398 -0.18449494, -0.11752522 -0.032762647 -0.18444745, -0.11714947 -0.032774284 -0.18448597, -0.11715317 -0.032660916 -0.1845029, -0.1266923 -0.033278629 -0.18483123, -0.12669244 -0.033238903 -0.18472219, -0.12669238 -0.033175007 -0.18462509, -0.12669238 -0.033090621 -0.18454535, -0.12669232 -0.032989904 -0.18448737, -0.12669227 -0.032878682 -0.18445405, -0.12669227 -0.032762676 -0.18444736, -0.12669238 -0.032648399 -0.18446767, -0.12676001 -0.032889172 -0.18444863, -0.1268369 -0.032906607 -0.18442661, -0.1267581 -0.032775104 -0.18443953, -0.12683126 -0.032796189 -0.18441442, -0.1269097 -0.032824561 -0.18436894, -0.12683618 -0.032684878 -0.18442494, -0.12691262 -0.032716364 -0.18437286, -0.12678254 -0.033110693 -0.1845513, -0.12676737 -0.032997891 -0.1844826, -0.12685248 -0.033011109 -0.18446036, -0.12699994 -0.032762319 -0.18428345, -0.1271069 -0.032859907 -0.18411198, -0.1269207 -0.032930061 -0.18438372, -0.12680653 -0.033210963 -0.18466099, -0.12700328 -0.032865077 -0.18428631, -0.12713477 -0.032975256 -0.18412344, -0.12688211 -0.033118814 -0.18452497, -0.12694469 -0.033028632 -0.18441583, -0.1270223 -0.032963276 -0.18430237, -0.12718722 -0.033080235 -0.18414497, -0.12683496 -0.033272132 -0.18479124, -0.12692818 -0.03321436 -0.18462558, -0.12698722 -0.033129662 -0.18447335, -0.12705556 -0.033053443 -0.18433043, -0.12726113 -0.033168867 -0.18417525, -0.12698266 -0.033272892 -0.18474431, -0.12705165 -0.033219084 -0.18456063, -0.12745577 -0.033277914 -0.18425503, -0.1267617 -0.03266187 -0.18445617, -0.12711054 -0.033144936 -0.18437681, -0.12712741 -0.033273906 -0.18466277, -0.12719092 -0.033225596 -0.18444471, -0.12735236 -0.033235982 -0.18421257, -0.12728348 -0.033275366 -0.18452279, -0.12795344 -0.033277988 -0.18303995, -0.12785003 -0.033236071 -0.18299773, -0.12775874 -0.033168972 -0.18296032, -0.12768474 -0.033080339 -0.18293004, -0.12763241 -0.03297542 -0.18290856, -0.12760454 -0.032859921 -0.18289725, -0.12755355 -0.033204362 -0.18200389, -0.12758467 -0.033151209 -0.18210457, -0.1275247 -0.033158392 -0.1820534, -0.12769994 -0.033021733 -0.18274274, -0.12773082 -0.033063948 -0.18256597, -0.12766111 -0.032919556 -0.18273659, -0.12782419 -0.033279613 -0.1820091, -0.12768531 -0.032975137 -0.18256979, -0.12789786 -0.033278555 -0.18211748, -0.12780347 -0.033237562 -0.1821759, -0.12774384 -0.0332423 -0.18207902, -0.12775931 -0.033112228 -0.1827517, -0.12779203 -0.033141077 -0.18256103, -0.12762192 -0.033199534 -0.18205979, -0.12759271 -0.033248127 -0.18193661, -0.12767246 -0.033245668 -0.18199864, -0.12767661 -0.033021763 -0.18241572, -0.12773812 -0.033280566 -0.1819194, -0.12799343 -0.033270061 -0.1827877, -0.12764326 -0.033281147 -0.18184994, -0.12785593 -0.033202112 -0.18276654, -0.12772357 -0.033098876 -0.18240063, -0.12788531 -0.033216521 -0.18255332, -0.12778163 -0.033164591 -0.18238176, -0.12763768 -0.033059835 -0.18227844, -0.12801385 -0.033273399 -0.18254285, -0.12768081 -0.033126935 -0.18225172, -0.12786639 -0.033228219 -0.18235449, -0.12759906 -0.033078671 -0.18220477, -0.12773171 -0.033183321 -0.18222013, -0.12763774 -0.033140749 -0.18217112, -0.12755194 -0.03309302 -0.1821439, -0.12798002 -0.033276305 -0.18231788, -0.12768209 -0.033192545 -0.18213244, -0.12749889 -0.033102855 -0.1820977, -0.11846375 -0.033126891 -0.18202381, -0.11846381 -0.033196673 -0.18194607, -0.1184637 -0.033248961 -0.1818556, -0.11846375 -0.033281207 -0.1817563, -0.11736253 -0.033084914 -0.18240771, -0.117318 -0.033171728 -0.1823414, -0.11726359 -0.033237413 -0.18226022, -0.11720195 -0.033278272 -0.18216845, -0.11808518 -0.033118203 -0.18207109, -0.11806923 -0.033191621 -0.18199454, -0.11805046 -0.033246458 -0.18190448, -0.11802977 -0.033280417 -0.18180498, -0.10916841 -0.033079728 -0.19371051, -0.11408854 -0.033084497 -0.19040278, -0.10916987 -0.033164501 -0.19361849, -0.11404389 -0.033171237 -0.19033651, -0.11398938 -0.033236936 -0.19025525, -0.11392769 -0.03327778 -0.19016348, -0.11518949 -0.033126488 -0.19001883, -0.11518949 -0.033280686 -0.18975121, -0.11481097 -0.033117741 -0.19006623, -0.11518949 -0.033196345 -0.18994111, -0.11479488 -0.033191264 -0.18998973, -0.11518946 -0.033248529 -0.18985066, -0.11477616 -0.033245981 -0.18989961, -0.1147556 -0.033280015 -0.18980019, -0.12427932 -0.033203736 -0.1899991, -0.12425035 -0.033157721 -0.19004852, -0.12431049 -0.033150613 -0.19009958, -0.12442571 -0.033021137 -0.19073763, -0.1244567 -0.033063471 -0.1905611, -0.12438688 -0.03291896 -0.19073172, -0.12441105 -0.032974616 -0.19056475, -0.12454998 -0.033279136 -0.19000429, -0.12452918 -0.0332371 -0.19017111, -0.1244697 -0.033241689 -0.19007413, -0.12448505 -0.033111677 -0.19074687, -0.1245178 -0.0331406 -0.19055615, -0.12462351 -0.033278018 -0.19011267, -0.12433016 -0.032859445 -0.19089226, -0.12439823 -0.033245206 -0.18999384, -0.12431845 -0.033247635 -0.18993172, -0.12434754 -0.033199102 -0.19005497, -0.12440231 -0.033021227 -0.19041103, -0.12446392 -0.033279911 -0.18991464, -0.12467915 -0.033277452 -0.1910352, -0.12471926 -0.033269584 -0.19078289, -0.12457576 -0.033235535 -0.19099292, -0.12436906 -0.033280581 -0.18984516, -0.12458166 -0.033201605 -0.19076176, -0.12444913 -0.0330984 -0.19039576, -0.12461126 -0.03321594 -0.19054846, -0.12450731 -0.033164024 -0.19037692, -0.12436327 -0.033059254 -0.19027364, -0.1247395 -0.033273026 -0.1905379, -0.12440655 -0.033126399 -0.19024691, -0.12459204 -0.033227727 -0.19034967, -0.12432468 -0.033078194 -0.1901999, -0.12445757 -0.033182889 -0.19021542, -0.12436354 -0.033140197 -0.19016641, -0.12427774 -0.033092543 -0.19013909, -0.12470573 -0.033275664 -0.19031315, -0.12440792 -0.033192009 -0.19012757, -0.12422472 -0.033102334 -0.19009285, -0.12435815 -0.032974884 -0.19090363, -0.12441045 -0.033079877 -0.19092524, -0.12448445 -0.03316845 -0.19095558, -0.12418148 -0.033277407 -0.19225001, -0.12407815 -0.03323555 -0.19220762, -0.12398693 -0.033168346 -0.19217028, -0.12391311 -0.033079684 -0.19214003, -0.12386063 -0.032974765 -0.19211856, -0.12383264 -0.03285934 -0.1921072, -0.12348363 -0.032774702 -0.19243467, -0.12356266 -0.03290619 -0.19242156, -0.12355709 -0.032795683 -0.19240957, -0.1234858 -0.032888666 -0.19244367, -0.12356195 -0.032684341 -0.19242001, -0.12363544 -0.032824025 -0.19236407, -0.12363824 -0.032715812 -0.19236779, -0.12341809 -0.032647863 -0.19246274, -0.12341821 -0.033174574 -0.19262026, -0.12350827 -0.033110306 -0.19254652, -0.12341818 -0.033090129 -0.19254065, -0.12349325 -0.032997474 -0.19247767, -0.12357825 -0.033010542 -0.19245546, -0.12372562 -0.032761723 -0.19227852, -0.1236465 -0.032929599 -0.19237874, -0.12341806 -0.033238322 -0.19271733, -0.12353235 -0.033210456 -0.1926562, -0.12372917 -0.03286463 -0.19228141, -0.12360775 -0.033118367 -0.19252007, -0.12367019 -0.033028156 -0.19241096, -0.12374789 -0.032962814 -0.19229758, -0.12341794 -0.033278123 -0.19282639, -0.12356082 -0.033271655 -0.19278643, -0.12365398 -0.033213884 -0.19262077, -0.12371308 -0.033129156 -0.19246857, -0.12378129 -0.033053055 -0.19232547, -0.12370858 -0.0332724 -0.19273937, -0.12377766 -0.033218518 -0.19255596, -0.12383646 -0.033144414 -0.19237177, -0.12348738 -0.032661408 -0.19245131, -0.12385315 -0.033273458 -0.19265781, -0.12341809 -0.032762289 -0.19244258, -0.12391663 -0.03322506 -0.19243972, -0.12400943 -0.033274949 -0.1925178, -0.12341809 -0.032878175 -0.19244915, -0.12341794 -0.032989413 -0.19248237, -0.11425102 -0.033278108 -0.19282632, -0.11425108 -0.033238351 -0.19271724, -0.11425114 -0.033174515 -0.1926202, -0.11425102 -0.033089951 -0.19254038, -0.11425096 -0.032989442 -0.19248243, -0.11425093 -0.032878116 -0.19244918, -0.11425096 -0.032762244 -0.19244254, -0.11425102 -0.032647848 -0.19246285, -0.11395401 -0.033278272 -0.19285849, -0.11393183 -0.033239409 -0.19275287, -0.11391222 -0.033177257 -0.19265871, -0.11389583 -0.033094928 -0.19258121, -0.11388397 -0.032996848 -0.19252393, -0.11387691 -0.032887906 -0.19248982, -0.1138753 -0.032773808 -0.19248113, -0.11387891 -0.032660425 -0.19249789, -0.10589424 -0.033079296 -0.20170577, -0.11081409 -0.03308408 -0.19839787, -0.10589576 -0.033164009 -0.20161355, -0.1107696 -0.033170745 -0.19833165, -0.11071509 -0.033236429 -0.19825029, -0.11065346 -0.033277318 -0.19815868, -0.11191526 -0.033125922 -0.1980139, -0.11191523 -0.033280298 -0.1977464, -0.11153665 -0.03311725 -0.19806147, -0.11191517 -0.033195898 -0.19793618, -0.11152086 -0.033190772 -0.19798478, -0.11191529 -0.033248022 -0.19784576, -0.11150211 -0.033245534 -0.19789474, -0.11148131 -0.033279553 -0.19779533, -0.1209763 -0.033157378 -0.19804372, -0.12100509 -0.033203363 -0.1979941, -0.12103626 -0.033150211 -0.19809476, -0.12115145 -0.033020735 -0.19873284, -0.12118247 -0.033062935 -0.19855626, -0.12111261 -0.032918572 -0.19872688, -0.12127581 -0.033278793 -0.19799937, -0.1211369 -0.032974124 -0.19855987, -0.12125504 -0.033236623 -0.19816612, -0.12119529 -0.033241227 -0.19806919, -0.12121087 -0.0331112 -0.19874194, -0.12124366 -0.033140004 -0.19855125, -0.12134939 -0.033277497 -0.19810775, -0.12105617 -0.032858908 -0.19888745, -0.12104425 -0.033247188 -0.19792697, -0.12112391 -0.033244848 -0.19798885, -0.12107334 -0.033198506 -0.19805004, -0.12112823 -0.033020735 -0.19840594, -0.12118962 -0.033279568 -0.19790955, -0.1214048 -0.033277005 -0.19903041, -0.12144494 -0.033269048 -0.19877802, -0.12130156 -0.033235088 -0.19898805, -0.12109494 -0.033280134 -0.1978402, -0.12130755 -0.033201084 -0.19875699, -0.12117502 -0.033097833 -0.19839092, -0.12133697 -0.033215493 -0.19854347, -0.12123322 -0.033163428 -0.19837199, -0.12108913 -0.033058792 -0.19826896, -0.12146536 -0.033272386 -0.19853292, -0.12113228 -0.033125877 -0.19824193, -0.12131777 -0.03322722 -0.19834483, -0.12105057 -0.033077613 -0.19819501, -0.1211834 -0.033182368 -0.19821033, -0.12108913 -0.033139795 -0.19816126, -0.12100366 -0.033092037 -0.1981343, -0.12143159 -0.033275217 -0.19830813, -0.12113371 -0.033191562 -0.19812261, -0.12108409 -0.032974273 -0.19889881, -0.12095046 -0.033101901 -0.19808799, -0.1211364 -0.033079326 -0.19892035, -0.12121025 -0.033167973 -0.19895065, -0.1209074 -0.03327693 -0.20024517, -0.12080398 -0.033235043 -0.20020296, -0.12071282 -0.033167809 -0.20016532, -0.12063885 -0.033079147 -0.20013522, -0.1205864 -0.032974362 -0.20011364, -0.12055853 -0.032858968 -0.20010231, -0.12020957 -0.032774195 -0.20042965, -0.12028843 -0.032905638 -0.20041676, -0.1202828 -0.032795191 -0.20040463, -0.12021166 -0.032888234 -0.20043869, -0.12028787 -0.032683909 -0.20041533, -0.1203613 -0.032823503 -0.20035918, -0.1203641 -0.032715321 -0.20036291, -0.12014386 -0.032647341 -0.20045789, -0.12014401 -0.033174023 -0.20061523, -0.12023407 -0.033109725 -0.20054148, -0.12014392 -0.033089548 -0.20053549, -0.12021902 -0.032996893 -0.2004727, -0.12030387 -0.033010125 -0.20045052, -0.12045154 -0.032761246 -0.20027353, -0.12037227 -0.032929033 -0.20037384, -0.12014389 -0.033237919 -0.20071229, -0.12025815 -0.03320998 -0.20065103, -0.12045491 -0.032864198 -0.20027655, -0.12033349 -0.033117831 -0.20051502, -0.12039605 -0.033027619 -0.20040609, -0.12047398 -0.032962233 -0.20029248, -0.12014389 -0.033277616 -0.20082137, -0.12028661 -0.033271194 -0.20078145, -0.12037995 -0.033213377 -0.20061575, -0.12043881 -0.033128619 -0.20046364, -0.12050721 -0.033052459 -0.20032075, -0.1204344 -0.033272028 -0.20073448, -0.12050337 -0.033217996 -0.20055087, -0.12056223 -0.033143878 -0.20036705, -0.12021318 -0.032660931 -0.20044638, -0.12057897 -0.033272997 -0.20065287, -0.12014395 -0.032761753 -0.20043762, -0.12064239 -0.033224553 -0.20043476, -0.12073517 -0.033274293 -0.20051299, -0.12014395 -0.032877654 -0.20044424, -0.12014383 -0.032988876 -0.20047741, -0.1109767 -0.033277556 -0.20082152, -0.1109767 -0.03323786 -0.20071238, -0.1109767 -0.033174083 -0.20061529, -0.11097676 -0.033089489 -0.2005357, -0.11097676 -0.032988951 -0.20047769, -0.11097676 -0.032877728 -0.20044443, -0.11097676 -0.032761738 -0.20043775, -0.11097682 -0.032647356 -0.20045787, -0.11067966 -0.033277795 -0.20085356, -0.11065754 -0.033238992 -0.20074785, -0.11063787 -0.033176839 -0.20065393, -0.11062163 -0.033094451 -0.20057631, -0.11060977 -0.032996342 -0.20051914, -0.1106028 -0.032887504 -0.20048508, -0.11060098 -0.03277339 -0.20047614, -0.11060488 -0.032659993 -0.20049292, -0.10770243 -0.033277109 -0.20881662, -0.10770252 -0.03264688 -0.20845285, -0.10740539 -0.033277318 -0.2088488, -0.10770252 -0.033237383 -0.20870748, -0.10738322 -0.03323853 -0.20874299, -0.10770249 -0.033173442 -0.20861031, -0.10736367 -0.033176288 -0.20864904, -0.1077024 -0.033089086 -0.20853069, -0.1073474 -0.033094078 -0.20857142, -0.10770246 -0.032988474 -0.2084727, -0.10733548 -0.032995865 -0.20851421, -0.1077024 -0.032877252 -0.20843947, -0.10732859 -0.032887071 -0.20848013, -0.10770246 -0.032761216 -0.20843281, -0.10732672 -0.032772943 -0.20847136, -0.10733041 -0.032659575 -0.2084882, -0.11686963 -0.033277094 -0.20881654, -0.11686963 -0.033237398 -0.20870747, -0.11686963 -0.033173501 -0.20861031, -0.11686969 -0.033089161 -0.20853071, -0.11686966 -0.032988518 -0.20847265, -0.11686963 -0.032877266 -0.20843937, -0.11686969 -0.03276132 -0.20843276, -0.1168696 -0.032646865 -0.20845304, -0.11693734 -0.032887757 -0.208434, -0.11701417 -0.032905221 -0.20841195, -0.11693531 -0.032773793 -0.20842509, -0.11700866 -0.032794803 -0.20839988, -0.11708701 -0.032823086 -0.20835425, -0.11701351 -0.032683551 -0.2084104, -0.11708993 -0.032714903 -0.20835815, -0.11695993 -0.033109307 -0.20853679, -0.11694485 -0.032996461 -0.20846787, -0.1170297 -0.033009619 -0.20844565, -0.11717725 -0.032760978 -0.20826878, -0.11728436 -0.032858431 -0.20809747, -0.11709803 -0.032928646 -0.20836906, -0.11698386 -0.033209532 -0.20864634, -0.11718062 -0.032863766 -0.20827161, -0.11731219 -0.032973766 -0.20810883, -0.11705935 -0.033117414 -0.20851018, -0.11712185 -0.033027261 -0.20840119, -0.11719966 -0.032961845 -0.20828773, -0.11736467 -0.033078879 -0.20813031, -0.11701244 -0.033270776 -0.20877673, -0.1171056 -0.0332129 -0.20861091, -0.11716467 -0.033128276 -0.20845884, -0.11723298 -0.033052027 -0.20831574, -0.11743858 -0.033167377 -0.20816043, -0.11716008 -0.033271432 -0.20872955, -0.11722916 -0.033217564 -0.2085461, -0.11763313 -0.033276469 -0.20824026, -0.11693904 -0.032660455 -0.20844154, -0.11728793 -0.033143461 -0.20836221, -0.11730462 -0.033272445 -0.20864798, -0.11736828 -0.033224121 -0.20842999, -0.11752981 -0.033234522 -0.20819798, -0.11746091 -0.033273995 -0.20850815, -0.11813062 -0.033276528 -0.20702539, -0.11802736 -0.033234596 -0.20698313, -0.11793607 -0.033167452 -0.20694564, -0.11786202 -0.033078909 -0.20691554, -0.11780974 -0.032973826 -0.20689406, -0.11778188 -0.032858461 -0.20688258, -0.11773095 -0.033202901 -0.2059893, -0.117762 -0.033149838 -0.20608987, -0.11770204 -0.033156991 -0.20603885, -0.1178773 -0.033020228 -0.20672797, -0.11790821 -0.033062518 -0.20655145, -0.11783844 -0.032918066 -0.20672198, -0.11800164 -0.033278197 -0.20599447, -0.11786264 -0.032973617 -0.20655508, -0.11807519 -0.033277124 -0.20610295, -0.11798087 -0.033236131 -0.20616135, -0.11792108 -0.03324087 -0.20606428, -0.11793658 -0.033110797 -0.20673706, -0.11796939 -0.033139512 -0.2065464, -0.11779913 -0.033198133 -0.20604509, -0.11777002 -0.033246726 -0.20592211, -0.11784977 -0.033244222 -0.20598398, -0.11785385 -0.033020318 -0.20640101, -0.11791536 -0.033279121 -0.20590474, -0.1181708 -0.033268601 -0.20677315, -0.11782068 -0.033279628 -0.20583533, -0.11803323 -0.033200592 -0.20675202, -0.11790079 -0.033097476 -0.20638619, -0.11806273 -0.033215001 -0.20653874, -0.11795896 -0.033163115 -0.20636716, -0.11781496 -0.033058375 -0.20626409, -0.11819109 -0.033271968 -0.20652808, -0.11785814 -0.03312546 -0.20623721, -0.11804363 -0.033226788 -0.20633997, -0.11777627 -0.033077195 -0.20619005, -0.11790907 -0.03318198 -0.20620567, -0.11781502 -0.033139333 -0.20615658, -0.11772922 -0.033091664 -0.20612933, -0.11815724 -0.033274829 -0.20630337, -0.11785954 -0.033191174 -0.20611773, -0.11767629 -0.033101439 -0.20608298, -0.10864094 -0.03312555 -0.20600902, -0.10864094 -0.033195481 -0.20593134, -0.10864094 -0.033247635 -0.20584095, -0.10864094 -0.033279806 -0.20574154, -0.10753986 -0.033083603 -0.20639309, -0.10749546 -0.033170372 -0.20632671, -0.10744086 -0.033235952 -0.20624557, -0.10737923 -0.033276841 -0.20615375, -0.10826233 -0.033116862 -0.20605648, -0.10824651 -0.033190325 -0.20597988, -0.10822779 -0.033245116 -0.20588987, -0.10820708 -0.033279106 -0.20579031, -0.10261986 -0.033078805 -0.20970079, -0.10262147 -0.033163548 -0.20960875, -0.099345595 -0.033078313 -0.217696, -0.10426563 -0.03308323 -0.21438815, -0.099347234 -0.033163011 -0.21760394, -0.10422117 -0.033169895 -0.2143219, -0.10416654 -0.033235416 -0.21424061, -0.10410511 -0.033276379 -0.21414892, -0.10536677 -0.033124998 -0.21400437, -0.1053668 -0.03327933 -0.2137367, -0.10498819 -0.03311643 -0.21405168, -0.10536674 -0.033194885 -0.21392658, -0.1049723 -0.033189788 -0.21397507, -0.10536677 -0.033247069 -0.21383604, -0.10495356 -0.03324461 -0.2138849, -0.10493281 -0.03327857 -0.21378559, -0.11420539 -0.033125132 -0.21400426, -0.11420539 -0.03319487 -0.21392657, -0.11420542 -0.033247173 -0.21383615, -0.11420542 -0.033279359 -0.2137367, -0.11476862 -0.033223808 -0.2143475, -0.11476728 -0.033264264 -0.21412504, -0.11470622 -0.033233941 -0.21416225, -0.11455101 -0.032854021 -0.21472053, -0.11457029 -0.032915279 -0.21455979, -0.11464563 -0.03309004 -0.21473554, -0.11444539 -0.033117831 -0.21408983, -0.11439219 -0.033124655 -0.21404989, -0.1144194 -0.033058703 -0.21412556, -0.11437196 -0.033067763 -0.21408929, -0.11457461 -0.032954872 -0.21472414, -0.11432213 -0.033072531 -0.21406476, -0.11460286 -0.03300494 -0.21455757, -0.11449477 -0.033107132 -0.2141438, -0.1144906 -0.033189982 -0.21402721, -0.11475363 -0.033197135 -0.21475302, -0.1145497 -0.033183619 -0.21408856, -0.11450437 -0.032755777 -0.21487629, -0.11450365 -0.032773063 -0.21487594, -0.11461434 -0.033240646 -0.21402375, -0.11462462 -0.03316915 -0.21421219, -0.11456028 -0.032968372 -0.21441145, -0.11483309 -0.033283576 -0.21408498, -0.11492199 -0.033282459 -0.21430044, -0.11484212 -0.03325969 -0.21432485, -0.11467946 -0.033121288 -0.21455233, -0.11433628 -0.033128351 -0.21402274, -0.11484137 -0.033247769 -0.21476711, -0.11442727 -0.033194125 -0.21398176, -0.11459678 -0.033047363 -0.21440017, -0.11466193 -0.033267379 -0.21397595, -0.11493832 -0.033279479 -0.21478288, -0.11478472 -0.033211663 -0.21454495, -0.11454311 -0.033243582 -0.21395469, -0.1147131 -0.033284232 -0.21392453, -0.11452132 -0.033013999 -0.21427505, -0.11467224 -0.033147529 -0.21437699, -0.11436069 -0.033196211 -0.21395041, -0.11458161 -0.033268735 -0.21390155, -0.11486739 -0.033254206 -0.21453919, -0.1144675 -0.033245489 -0.21390334, -0.11455709 -0.033083156 -0.21425322, -0.11462289 -0.03328459 -0.21384454, -0.1149576 -0.033280969 -0.21453281, -0.11449692 -0.033269614 -0.21384613, -0.11446407 -0.033044904 -0.21417458, -0.11438856 -0.033246562 -0.21386757, -0.11452848 -0.033284858 -0.21378475, -0.11440891 -0.033270061 -0.21380715, -0.1144307 -0.033284992 -0.21374257, -0.11400685 -0.032755852 -0.21609129, -0.11400592 -0.032772988 -0.21609099, -0.11390111 -0.03314662 -0.21646859, -0.11410478 -0.033231556 -0.21643429, -0.11402717 -0.033160031 -0.21636884, -0.1135954 -0.03287679 -0.21643464, -0.11366296 -0.03288728 -0.21642907, -0.1135954 -0.032760799 -0.21642785, -0.11359534 -0.032988116 -0.21646777, -0.11419258 -0.033275589 -0.21650833, -0.11403513 -0.033274233 -0.21664961, -0.11396378 -0.03322579 -0.21655309, -0.11366111 -0.032773316 -0.21642007, -0.11373436 -0.032794297 -0.21639486, -0.11366472 -0.032659993 -0.21643656, -0.11373925 -0.032683015 -0.21640541, -0.11381558 -0.032714427 -0.21635322, -0.11374798 -0.032612503 -0.21642454, -0.11382502 -0.032644704 -0.2163659, -0.1135954 -0.033088624 -0.21652587, -0.11367235 -0.033012733 -0.2164709, -0.11374 -0.032904804 -0.21640702, -0.11390957 -0.032692552 -0.21626957, -0.11381271 -0.032822669 -0.21634941, -0.11359543 -0.033173099 -0.21660554, -0.11368945 -0.03312999 -0.21654989, -0.11390299 -0.032760397 -0.21626389, -0.11375886 -0.033025205 -0.21644832, -0.1138238 -0.032928169 -0.21636416, -0.1139062 -0.032863334 -0.21626684, -0.1135954 -0.033276737 -0.21681167, -0.11359537 -0.033236921 -0.21670263, -0.11371294 -0.033218801 -0.21665676, -0.11379287 -0.033137083 -0.21652199, -0.11385265 -0.033041775 -0.21640317, -0.1139254 -0.032961383 -0.21628273, -0.11374 -0.033272594 -0.2167802, -0.11383763 -0.033221781 -0.21661989, -0.11359549 -0.032646522 -0.21644813, -0.11367005 -0.032589257 -0.21646087, -0.11396524 -0.033065245 -0.21631649, -0.11388943 -0.033273324 -0.21673241, -0.10442826 -0.033276573 -0.21681169, -0.10442826 -0.033236831 -0.21670254, -0.10442826 -0.033173084 -0.21660559, -0.10442835 -0.033088565 -0.21652587, -0.10442823 -0.032987967 -0.21646777, -0.10442829 -0.0328767 -0.21643467, -0.10442835 -0.032760739 -0.21642788, -0.10442829 -0.032646373 -0.21644813, -0.10413128 -0.033276901 -0.21684375, -0.10410914 -0.033238053 -0.21673815, -0.10408953 -0.033175766 -0.21664415, -0.10407323 -0.033093452 -0.21656661, -0.10406128 -0.032995313 -0.21650936, -0.10405436 -0.032886475 -0.21647541, -0.10405263 -0.032772347 -0.21646649, -0.10405624 -0.032659113 -0.21648328, -0.13720816 -0.03328684 -0.13655998, -0.13720828 -0.032908618 -0.13634174, -0.13688388 -0.033286884 -0.13659436, -0.13720807 -0.033262923 -0.13649452, -0.13687065 -0.033263564 -0.13653098, -0.13720828 -0.033224612 -0.13643624, -0.13685885 -0.033226311 -0.13647459, -0.13720807 -0.033173934 -0.13638848, -0.13684919 -0.033176884 -0.13642791, -0.13720804 -0.033113569 -0.13635369, -0.13684186 -0.033118024 -0.13639361, -0.13720816 -0.033046752 -0.13633372, -0.13683778 -0.033052713 -0.1363733, -0.13720804 -0.032977253 -0.13632967, -0.13683683 -0.032984287 -0.13636793, -0.13683894 -0.032916293 -0.13637808, -0.13649204 -0.033154353 -0.13652435, -0.097167552 -0.032755271 -0.22412038, -0.097219378 0.085332051 -0.2660405, -0.097219408 0.085253164 -0.26611784, -0.096498817 0.084715739 -0.26631278, -0.096494436 0.084780559 -0.266332, -0.096486896 0.084846929 -0.26634288, -0.096466541 0.084963188 -0.2663413, -0.096438199 0.08507444 -0.26631343, -0.096403569 0.085174456 -0.2662608, -0.096364349 0.085257366 -0.26618654, -0.096830308 0.085077569 -0.2662333, -0.097219408 0.085159227 -0.26617602, -0.097219437 0.08505477 -0.26621187, -0.10605806 0.085332125 -0.2660405, -0.10605797 0.085253179 -0.26611793, -0.10605812 0.085159272 -0.26617604, -0.10605815 0.085054696 -0.26621193, -0.10623816 0.084737182 -0.26622474, -0.10632592 0.084792823 -0.26629889, -0.10631698 0.084708691 -0.26626855, -0.10624474 0.084821969 -0.26625234, -0.1061911 0.085148364 -0.26619136, -0.1061734 0.085042894 -0.26622504, -0.1061601 0.08493194 -0.26623458, -0.10628459 0.085019916 -0.2662617, -0.10625836 0.084909558 -0.26626569, -0.10634506 0.084879339 -0.26631659, -0.10621232 0.085243136 -0.26613528, -0.10631981 0.085124463 -0.2662341, -0.10638276 0.084987462 -0.26632017, -0.10623604 0.085322171 -0.2660597, -0.10636243 0.085217237 -0.26618463, -0.10643408 0.085088372 -0.26630217, -0.10640988 0.085293829 -0.26611602, -0.10649571 0.085176826 -0.2662639, -0.106565 0.085247964 -0.26620734, -0.10614952 0.084759474 -0.26619965, -0.10615304 0.084844202 -0.26622456, -0.10634175 0.084373146 -0.26795518, -0.10624006 0.084355652 -0.26789916, -0.10614976 0.084314227 -0.26783651, -0.10607627 0.084250987 -0.26777059, -0.1060231 0.084169239 -0.26770514, -0.10599357 0.084073752 -0.26764357, -0.10590675 0.084028512 -0.26777202, -0.105768 0.084003747 -0.26786888, -0.10618106 0.084305316 -0.26800293, -0.10610017 0.084272265 -0.26792663, -0.10603359 0.084216207 -0.26784939, -0.10602957 0.084233582 -0.26801085, -0.10597304 0.084184855 -0.26792389, -0.10578227 0.084081352 -0.26794684, -0.10593131 0.084115118 -0.26784271, -0.10568801 0.084000885 -0.26789707, -0.10560757 0.084004462 -0.26791024, -0.10627189 0.08431384 -0.26807439, -0.10609758 0.084258735 -0.26809901, -0.10580483 0.084140211 -0.26803839, -0.10569549 0.084074944 -0.26797712, -0.10560766 0.084075749 -0.26799101, -0.10617384 0.084259421 -0.26818395, -0.10583448 0.084177017 -0.26813853, -0.10570684 0.0841299 -0.26807094, -0.10560754 0.084128112 -0.26808506, -0.10586995 0.084190398 -0.26824218, -0.10572165 0.084162951 -0.26817352, -0.10560757 0.084159017 -0.2681883, -0.10590953 0.08417964 -0.26834518, -0.10573903 0.084172875 -0.26828015, -0.10560754 0.084167123 -0.26829565, -0.10560754 0.084152073 -0.26840228, -0.10575861 0.084159374 -0.26838666, -0.10595754 0.084049046 -0.26770931, -0.10598511 0.084140092 -0.26777542, -0.096440434 0.084004536 -0.26791024, -0.096440345 0.084075794 -0.26799121, -0.096440375 0.084128156 -0.26808506, -0.096440434 0.084158987 -0.2681883, -0.096440315 0.084167153 -0.26829565, -0.096440464 0.084152162 -0.26840222, -0.09586373 0.084105432 -0.26849425, -0.095826715 0.084116936 -0.26839054, -0.095793426 0.084104329 -0.26828563, -0.095765382 0.084068 -0.26818496, -0.095744222 0.084009886 -0.26809335, -0.095730692 0.083932936 -0.26801503, -0.10010648 0.088432521 -0.25983858, -0.10010657 0.088353649 -0.25991586, -0.099385917 0.087816268 -0.26011068, -0.099381477 0.087880969 -0.26013005, -0.099373996 0.087947398 -0.26014096, -0.09935376 0.088063732 -0.26013929, -0.099325597 0.088175058 -0.26011133, -0.099290788 0.088274941 -0.26005876, -0.099251509 0.088357925 -0.25998455, -0.099717587 0.088178173 -0.2600314, -0.10010657 0.088259712 -0.25997403, -0.10010648 0.08815524 -0.26001, -0.10894522 0.08843258 -0.25983858, -0.10894522 0.088353619 -0.25991592, -0.10894519 0.088259697 -0.25997394, -0.10894519 0.08815527 -0.26001006, -0.10920423 0.087809026 -0.26006657, -0.10921305 0.087893292 -0.26009673, -0.10912538 0.087837726 -0.26002288, -0.10913184 0.087922409 -0.26005045, -0.10907823 0.088248789 -0.25998944, -0.10906047 0.088143349 -0.260023, -0.10917181 0.08812052 -0.26005977, -0.1090472 0.088032335 -0.26003253, -0.10914543 0.088010103 -0.26006377, -0.10923204 0.087979853 -0.26011467, -0.10909963 0.088343561 -0.25993329, -0.10920709 0.088224947 -0.26003212, -0.10926995 0.08808805 -0.26011828, -0.10912317 0.088422716 -0.25985771, -0.10924953 0.088317752 -0.25998271, -0.10932115 0.088188916 -0.26010042, -0.10929704 0.088394329 -0.25991398, -0.1093829 0.08827731 -0.26006186, -0.10945198 0.088348463 -0.26000535, -0.10903659 0.087859944 -0.25999764, -0.10904014 0.087944642 -0.26002255, -0.10922891 0.087473676 -0.26175326, -0.10912707 0.087456301 -0.2616972, -0.10903692 0.087414801 -0.26163459, -0.10896337 0.087351486 -0.26156864, -0.10891032 0.087269828 -0.2615031, -0.1088807 0.087174281 -0.26144153, -0.10906801 0.087405622 -0.26180083, -0.10898745 0.08737272 -0.26172471, -0.10892084 0.087316781 -0.26164734, -0.10891673 0.087333977 -0.26180893, -0.10886019 0.087285385 -0.26172191, -0.10879382 0.087129056 -0.26157004, -0.10866934 0.087181911 -0.26174504, -0.10865507 0.087104335 -0.26166704, -0.10881856 0.087215692 -0.26164067, -0.1085752 0.087101534 -0.26169524, -0.1084947 0.087105021 -0.26170838, -0.10915899 0.087414414 -0.26187241, -0.10898465 0.087359175 -0.26189715, -0.10869199 0.087240621 -0.26183647, -0.10858262 0.087175488 -0.2617752, -0.10849467 0.087176219 -0.26178923, -0.10906103 0.087359935 -0.26198208, -0.10872185 0.087277532 -0.2619366, -0.10859403 0.087230459 -0.26186898, -0.10849488 0.087228462 -0.26188323, -0.10875714 0.087290809 -0.26204011, -0.10860881 0.087263539 -0.26197156, -0.10849455 0.087259486 -0.2619864, -0.10879654 0.087280139 -0.26214319, -0.10862628 0.087273434 -0.2620782, -0.10849479 0.087267667 -0.26209366, -0.1084947 0.087252602 -0.26220024, -0.10864577 0.087259725 -0.26218471, -0.10884476 0.087149322 -0.26150733, -0.10887223 0.087240741 -0.26157346, -0.099327505 0.08710508 -0.26170832, -0.099327534 0.087176338 -0.26178914, -0.099327564 0.087228507 -0.26188326, -0.099327475 0.087259486 -0.26198635, -0.099327594 0.087267727 -0.2620936, -0.099327624 0.087252721 -0.26220024, -0.098751038 0.087206021 -0.26229233, -0.098713934 0.087217435 -0.26218876, -0.098680615 0.087204754 -0.26208377, -0.098652571 0.087168336 -0.26198298, -0.098631471 0.087110534 -0.26189139, -0.098617882 0.087033585 -0.26181296, -0.10299379 0.09153311 -0.25363669, -0.10299373 0.091454193 -0.25371411, -0.10227317 0.090916768 -0.25390881, -0.10226884 0.090981558 -0.25392812, -0.10226125 0.091047958 -0.25393915, -0.10224098 0.091164276 -0.25393745, -0.10221261 0.091275498 -0.25390944, -0.10217792 0.091375396 -0.25385681, -0.10213873 0.091458276 -0.25378263, -0.10260493 0.091278568 -0.25382942, -0.10299379 0.091360226 -0.25377208, -0.10299367 0.09125568 -0.25380808, -0.11183244 0.091533184 -0.25363678, -0.11183232 0.091454118 -0.25371403, -0.11183253 0.091360211 -0.25377208, -0.11183241 0.091255665 -0.25380808, -0.1120913 0.090909481 -0.25386465, -0.11210021 0.090993911 -0.25389493, -0.11201251 0.09093824 -0.25382078, -0.11201921 0.091022968 -0.25384855, -0.11196557 0.091349512 -0.25378734, -0.11194783 0.091243863 -0.25382119, -0.11205885 0.091220975 -0.25385773, -0.11193442 0.091132879 -0.25383055, -0.11203259 0.091110587 -0.25386184, -0.11211938 0.091080427 -0.25391275, -0.11198676 0.091444165 -0.25373137, -0.11209431 0.091325402 -0.25383025, -0.11215702 0.091188461 -0.25391614, -0.11201039 0.09152317 -0.25365585, -0.11213663 0.091418326 -0.25378072, -0.11220837 0.09128955 -0.25389826, -0.11218414 0.091494828 -0.253712, -0.11227024 0.091377884 -0.25385988, -0.11233917 0.091448933 -0.25380331, -0.11192384 0.090960413 -0.25379568, -0.11192742 0.091045171 -0.2538206, -0.11211595 0.09057416 -0.25555131, -0.11201432 0.090556875 -0.25549537, -0.11192417 0.090515286 -0.25543267, -0.11185056 0.090452 -0.25536659, -0.11179757 0.090370342 -0.25530103, -0.11176789 0.090274841 -0.25523955, -0.11168104 0.090229675 -0.25536802, -0.11154225 0.090204775 -0.25546515, -0.11195531 0.090506211 -0.25559887, -0.11187461 0.090473205 -0.25552279, -0.11180809 0.090417296 -0.25544542, -0.11180383 0.090434715 -0.25560704, -0.11174735 0.090385988 -0.25552005, -0.11155668 0.09028247 -0.25554293, -0.11170569 0.090316087 -0.25543875, -0.11146235 0.090202123 -0.2554931, -0.11138192 0.09020558 -0.25550634, -0.11204627 0.090514913 -0.25567049, -0.11187178 0.090459749 -0.25569513, -0.11157918 0.09034124 -0.25563461, -0.11146978 0.090276018 -0.25557309, -0.11138183 0.090276763 -0.25558725, -0.11194819 0.090460464 -0.25578025, -0.11160892 0.090378091 -0.25573459, -0.11148119 0.090330869 -0.25566691, -0.11138192 0.09032917 -0.25568122, -0.1116443 0.090391427 -0.25583822, -0.11149591 0.090364024 -0.25576964, -0.11138204 0.090359926 -0.25578439, -0.11168388 0.090380669 -0.25594127, -0.11151341 0.090374008 -0.25587624, -0.11138183 0.090368152 -0.25589162, -0.11138192 0.090353161 -0.25599843, -0.1115329 0.090360299 -0.25598273, -0.11173192 0.09025003 -0.25530547, -0.11175948 0.090341255 -0.25537136, -0.10221469 0.09020564 -0.25550652, -0.10221472 0.090276763 -0.25558707, -0.10221472 0.090329111 -0.25568134, -0.10221481 0.09036012 -0.2557843, -0.10221463 0.090368077 -0.25589177, -0.10221481 0.090353236 -0.25599843, -0.10163826 0.09030655 -0.25609046, -0.10160121 0.090317979 -0.25598681, -0.10156792 0.090305358 -0.25588185, -0.10153982 0.090268895 -0.25578099, -0.10151848 0.0902109 -0.25568944, -0.10150501 0.09013401 -0.255611, -0.10588098 0.094633743 -0.24743462, -0.10588095 0.094554797 -0.24751204, -0.10516042 0.094017297 -0.24770679, -0.105156 0.094082028 -0.2477261, -0.10514846 0.094148472 -0.24773705, -0.10512811 0.094264776 -0.24773552, -0.1050998 0.094376072 -0.24770737, -0.1050652 0.094476014 -0.24765481, -0.10502586 0.09455885 -0.24758071, -0.10549194 0.094379097 -0.24762739, -0.10588092 0.09446077 -0.24757028, -0.10588095 0.094356328 -0.24760608, -0.11471975 0.094633669 -0.24743463, -0.11471951 0.094554633 -0.247512, -0.11471957 0.094460756 -0.24757029, -0.11471957 0.094356284 -0.24760613, -0.11497849 0.094010115 -0.24766271, -0.11498737 0.094094411 -0.24769303, -0.11489972 0.094038814 -0.24761893, -0.11490643 0.094123572 -0.24764661, -0.11485267 0.094449848 -0.24758555, -0.11483499 0.094344378 -0.2476192, -0.11494619 0.094321519 -0.2476557, -0.11482164 0.094233528 -0.24762872, -0.11491978 0.094211072 -0.24765997, -0.11500645 0.094180912 -0.24771072, -0.11487395 0.094544679 -0.24752964, -0.11498156 0.094425917 -0.24762829, -0.11504444 0.094289064 -0.24771421, -0.11489755 0.094623655 -0.24745391, -0.11502397 0.094518751 -0.24757876, -0.11509559 0.094390035 -0.24769644, -0.11507145 0.094595313 -0.24751015, -0.11515746 0.094478488 -0.247658, -0.11522648 0.094549537 -0.24760143, -0.11481103 0.094060898 -0.24759381, -0.11481464 0.094145745 -0.24761869, -0.1150032 0.093674779 -0.2493494, -0.11490154 0.09365727 -0.2492933, -0.11481133 0.0936158 -0.24923064, -0.11473772 0.093552575 -0.24916473, -0.11468464 0.093470961 -0.24909915, -0.11465511 0.093375415 -0.24903767, -0.11456817 0.09333016 -0.24916616, -0.11442953 0.093305364 -0.2492632, -0.11484247 0.093606919 -0.24939702, -0.11476171 0.093573779 -0.24932079, -0.11469513 0.093517676 -0.24924356, -0.11469108 0.0935352 -0.24940506, -0.11463454 0.093486339 -0.24931805, -0.11444384 0.093382969 -0.24934104, -0.11459282 0.093416676 -0.24923679, -0.11434954 0.093302622 -0.24929133, -0.11426902 0.09330608 -0.24930447, -0.11493328 0.093615398 -0.24946856, -0.11475912 0.093560368 -0.24949305, -0.1144664 0.093441695 -0.24943261, -0.11435694 0.093376458 -0.24937128, -0.11426914 0.093377247 -0.24938518, -0.11483559 0.093561053 -0.24957828, -0.11449608 0.093478426 -0.24953252, -0.11436832 0.093431428 -0.24946505, -0.11426908 0.0934297 -0.24947932, -0.11453149 0.093491897 -0.2496362, -0.11438307 0.093464538 -0.24956766, -0.11426914 0.093460575 -0.24958235, -0.11457086 0.093481198 -0.24973935, -0.11440057 0.093474448 -0.24967431, -0.11426908 0.093468681 -0.24968973, -0.11426908 0.093453676 -0.24979644, -0.11442006 0.093460813 -0.24978071, -0.11461899 0.093350515 -0.24910346, -0.11464661 0.093441755 -0.24916951, -0.10510182 0.093306139 -0.24930444, -0.10510182 0.093377307 -0.24938515, -0.10510185 0.09342961 -0.24947932, -0.10510188 0.093460605 -0.24958244, -0.10510176 0.093468577 -0.24968977, -0.10510185 0.09345369 -0.24979642, -0.10452539 0.093407065 -0.24988849, -0.10448843 0.093418643 -0.24978486, -0.1044549 0.093405768 -0.24967995, -0.10442686 0.093369558 -0.2495791, -0.10440582 0.093311504 -0.2494874, -0.10439217 0.093234524 -0.24940914, -0.10876805 0.097734258 -0.24123275, -0.10876808 0.097655207 -0.2413101, -0.10804754 0.097117826 -0.24150491, -0.10804319 0.097182572 -0.24152417, -0.10803553 0.097248971 -0.24153511, -0.10801524 0.097365305 -0.2415334, -0.1079869 0.097476631 -0.24150552, -0.10795233 0.09757641 -0.24145292, -0.10791308 0.097659394 -0.24137866, -0.10837907 0.097479627 -0.24142551, -0.10876808 0.09756127 -0.24136807, -0.10876802 0.097456753 -0.24140416, -0.11760664 0.097734094 -0.24123271, -0.11760679 0.097655311 -0.24131012, -0.11760667 0.09756121 -0.24136807, -0.11760667 0.097456768 -0.24140427, -0.11786559 0.097110584 -0.24146077, -0.11787453 0.097194985 -0.24149099, -0.11778697 0.097139224 -0.24141693, -0.11779341 0.097223967 -0.24144448, -0.11773977 0.097550362 -0.24138345, -0.11772206 0.097444847 -0.2414172, -0.1178332 0.097422004 -0.24145393, -0.11770865 0.097333759 -0.24142672, -0.11780694 0.097311631 -0.241458, -0.11789352 0.097281456 -0.24150865, -0.11776111 0.097645029 -0.24132749, -0.11786863 0.097526401 -0.24142624, -0.11793134 0.097389489 -0.2415124, -0.11778459 0.097724289 -0.24125175, -0.11791113 0.097619385 -0.24137686, -0.11798263 0.097490385 -0.24149448, -0.1179584 0.097695917 -0.24130799, -0.1180445 0.097578928 -0.24145609, -0.11811355 0.097650126 -0.2413995, -0.11769828 0.097161517 -0.24139178, -0.11770183 0.097246304 -0.24141681, -0.11789039 0.096775234 -0.24314754, -0.11778864 0.09675771 -0.24309139, -0.11769858 0.096716344 -0.24302869, -0.11762485 0.09665294 -0.24296275, -0.11757183 0.096571356 -0.24289723, -0.11754224 0.096475914 -0.24283579, -0.11772969 0.096707314 -0.24319516, -0.11764902 0.096674323 -0.24311872, -0.11758247 0.096618354 -0.24304156, -0.11757821 0.096635565 -0.24320313, -0.11752182 0.096586943 -0.24311607, -0.11745542 0.096430644 -0.24296442, -0.11733088 0.096483439 -0.24313904, -0.11731672 0.096405819 -0.24306113, -0.11748013 0.096517175 -0.24303482, -0.11723673 0.096402943 -0.24308939, -0.11715615 0.096406519 -0.2431026, -0.11782056 0.096715987 -0.24326663, -0.11764622 0.096660674 -0.24329121, -0.11735371 0.096542284 -0.24323067, -0.11724406 0.096477017 -0.24316937, -0.11715624 0.096477717 -0.24318333, -0.11772257 0.096661508 -0.24337639, -0.1173833 0.096579134 -0.24333076, -0.11725545 0.096531928 -0.24326317, -0.1171563 0.096530154 -0.24327746, -0.11741862 0.096592501 -0.24343425, -0.11727041 0.096565068 -0.24336569, -0.11715624 0.096561044 -0.2433805, -0.11745819 0.096581787 -0.2435372, -0.11728781 0.096574962 -0.24347238, -0.11715624 0.096569151 -0.24348779, -0.11715627 0.096554086 -0.24359447, -0.11730739 0.096561283 -0.24357881, -0.11750624 0.096451014 -0.24290155, -0.11753383 0.096542299 -0.24296765, -0.10798916 0.096406728 -0.24310245, -0.10798907 0.096477911 -0.24318331, -0.10798901 0.096530184 -0.24327737, -0.10798907 0.096561119 -0.24338049, -0.10798913 0.09656921 -0.24348773, -0.10798916 0.09655419 -0.24359442, -0.10741249 0.096507564 -0.24368659, -0.10737562 0.096519038 -0.24358284, -0.10734215 0.096506298 -0.24347796, -0.10731417 0.096470028 -0.2433771, -0.10729295 0.096412092 -0.24328555, -0.10727948 0.096335083 -0.24320723, -0.11742952 0.1070357 -0.22262685, -0.11742964 0.10695691 -0.22270408, -0.11670893 0.1064195 -0.222899, -0.11670458 0.10648416 -0.2229183, -0.11669701 0.10655054 -0.22292925, -0.11667681 0.10666691 -0.22292763, -0.11664847 0.1067781 -0.22289973, -0.11661384 0.10687807 -0.22284703, -0.11657467 0.10696085 -0.22277287, -0.11704069 0.10678118 -0.22281973, -0.11742964 0.10686298 -0.22276226, -0.11742976 0.10675843 -0.22279826, -0.12626818 0.10703573 -0.22262691, -0.12626824 0.10695682 -0.22270411, -0.12626827 0.10686292 -0.22276226, -0.12626824 0.10675834 -0.22279832, -0.12652713 0.10641228 -0.22285479, -0.12653604 0.10649647 -0.22288513, -0.12644848 0.10644092 -0.22281113, -0.12645507 0.1065256 -0.2228386, -0.12640128 0.10685195 -0.22277775, -0.1263836 0.10674642 -0.22281131, -0.12649474 0.10672365 -0.22284803, -0.12637022 0.1066355 -0.22282085, -0.12646845 0.10661308 -0.22285205, -0.12655514 0.10658298 -0.22290283, -0.12642255 0.1069466 -0.22272176, -0.12653005 0.10682799 -0.22282043, -0.12659287 0.10669105 -0.22290656, -0.12644628 0.10702583 -0.22264592, -0.12657252 0.10692088 -0.22277111, -0.12664419 0.10679208 -0.22288865, -0.12661985 0.10699733 -0.22270229, -0.12670597 0.10688047 -0.22285035, -0.12677512 0.10695158 -0.22279367, -0.12635967 0.10646294 -0.22278604, -0.12636337 0.10654773 -0.22281089, -0.12655196 0.1060767 -0.22454163, -0.12645015 0.10605928 -0.22448553, -0.12636003 0.10601792 -0.22442283, -0.12628636 0.1059545 -0.2243569, -0.12623331 0.10587284 -0.22429134, -0.12620363 0.10577735 -0.22422992, -0.12639114 0.10600886 -0.22458912, -0.1263105 0.10597578 -0.22451301, -0.12624392 0.10591981 -0.22443567, -0.12623975 0.10593709 -0.22459732, -0.12618324 0.10588846 -0.22451018, -0.12611693 0.1057322 -0.22435842, -0.12599248 0.10578489 -0.22453322, -0.12597814 0.10570744 -0.22445543, -0.12614155 0.10581867 -0.22442889, -0.12589818 0.10570455 -0.22448359, -0.12581772 0.105708 -0.22449668, -0.12648207 0.10601735 -0.22466071, -0.1263077 0.10596225 -0.22468533, -0.12601504 0.10584375 -0.22462477, -0.1259056 0.10577855 -0.22456349, -0.12581769 0.10577945 -0.22457731, -0.12638411 0.10596308 -0.22477044, -0.12604472 0.10588059 -0.22472478, -0.12591693 0.10583338 -0.22465719, -0.12581769 0.10583167 -0.22467148, -0.12608001 0.10589394 -0.22482847, -0.12593171 0.10586652 -0.22475971, -0.12581769 0.10586253 -0.22477458, -0.12611955 0.10588324 -0.22493149, -0.12594923 0.10587643 -0.22486636, -0.12581775 0.10587069 -0.2248819, -0.12581772 0.1058557 -0.22498859, -0.12596866 0.10586271 -0.22497286, -0.12616768 0.10575263 -0.22429562, -0.12619528 0.10584375 -0.22436179, -0.11665055 0.10570814 -0.22449654, -0.11665055 0.10577942 -0.22457749, -0.11665067 0.10583177 -0.22467144, -0.11665061 0.10586257 -0.22477454, -0.11665055 0.1058708 -0.22488189, -0.11665055 0.10585578 -0.22498858, -0.11607406 0.10580917 -0.22508061, -0.11603701 0.10582064 -0.22497723, -0.11600363 0.10580787 -0.22487207, -0.11597571 0.10577156 -0.22477132, -0.11595443 0.10571356 -0.22467965, -0.11594093 0.10563658 -0.2246013, -0.11906973 0.10997741 -0.21673957, -0.11912605 0.10989998 -0.21680555, -0.11917615 0.10980548 -0.21685135, -0.11921719 0.10969906 -0.21687451, -0.12031689 0.11013629 -0.21642497, -0.12031683 0.11005723 -0.21650226, -0.11959624 0.10952006 -0.21669707, -0.11959198 0.10958458 -0.21671641, -0.11958429 0.10965097 -0.2167273, -0.11956409 0.10976733 -0.21672559, -0.11953565 0.10987866 -0.21669774, -0.11950096 0.10997856 -0.21664517, -0.11946175 0.11006153 -0.2165709, -0.11992785 0.10988176 -0.21661763, -0.12031671 0.10996328 -0.21656033, -0.12031677 0.10985889 -0.21659636, -0.12915549 0.11013624 -0.2164249, -0.12915552 0.11005726 -0.21650226, -0.12915546 0.10996327 -0.21656029, -0.1291554 0.1098589 -0.21659632, -0.12925127 0.10956275 -0.21658473, -0.12934622 0.10962483 -0.21663849, -0.12933952 0.10954008 -0.2166108, -0.1294139 0.10951301 -0.21665265, -0.1295583 0.10975274 -0.21677913, -0.12961623 0.10970768 -0.21686901, -0.1295113 0.10964844 -0.21676625, -0.12956238 0.10960875 -0.21684539, -0.12927628 0.10984603 -0.21661063, -0.12926236 0.10973516 -0.21661992, -0.12953547 0.10952678 -0.21681745, -0.12956864 0.10947213 -0.21693577, -0.12952313 0.10944447 -0.21678217, -0.12955472 0.10939226 -0.21689714, -0.1293599 0.10971233 -0.21665205, -0.12925503 0.10964747 -0.2166099, -0.12966141 0.11005232 -0.21659102, -0.12951502 0.11009619 -0.21650381, -0.12946647 0.11001977 -0.21657209, -0.12959257 0.10998119 -0.2166478, -0.12955144 0.10935655 -0.21698411, -0.12942296 0.10959718 -0.21668299, -0.12952954 0.1093491 -0.2170855, -0.12953082 0.10989276 -0.2166862, -0.12969962 0.10992993 -0.21674961, -0.12962219 0.10984822 -0.21677345, -0.12929496 0.10995169 -0.21657702, -0.12947696 0.10948023 -0.21671085, -0.12959844 0.10954937 -0.21697177, -0.12968954 0.10979602 -0.21687759, -0.12938687 0.10982272 -0.21664836, -0.1295664 0.1094341 -0.21702559, -0.12955925 0.10944457 -0.21714696, -0.12944183 0.10968372 -0.21670075, -0.12978598 0.10999331 -0.21670903, -0.12931713 0.11004648 -0.21652128, -0.12965733 0.1096389 -0.21701153, -0.12948772 0.1095638 -0.21674372, -0.12977836 0.10986918 -0.21687131, -0.12959656 0.10950682 -0.21706738, -0.12961242 0.10952634 -0.21721248, -0.12942299 0.10992715 -0.21662112, -0.12973684 0.10971507 -0.21704273, -0.12947959 0.10979185 -0.21670417, -0.12987727 0.10992274 -0.21685009, -0.12965503 0.1095891 -0.21711855, -0.12968594 0.10958955 -0.2172785, -0.12934181 0.11012526 -0.21644577, -0.12983268 0.10977361 -0.21706359, -0.12973353 0.10965559 -0.21716596, -0.12977621 0.10963115 -0.21734108, -0.12993973 0.10981151 -0.21707313, -0.12982795 0.10970315 -0.21720643, -0.12987784 0.10964847 -0.21739714, -0.12993309 0.10972913 -0.21723816, -0.12909093 0.10887791 -0.21802789, -0.12912044 0.10897334 -0.21808943, -0.12917358 0.10905501 -0.21815492, -0.12924728 0.10911842 -0.21822092, -0.1293374 0.10915992 -0.21828358, -0.12943903 0.10917737 -0.21833974, -0.12927836 0.10910949 -0.21838717, -0.12919757 0.10907634 -0.21831104, -0.12913108 0.10902034 -0.2182337, -0.12912694 0.10903765 -0.21839529, -0.12907049 0.10898884 -0.21830818, -0.12900409 0.10883269 -0.21815635, -0.12887964 0.1088855 -0.21833129, -0.12886533 0.10880788 -0.21825346, -0.12902865 0.10891922 -0.218227, -0.12878546 0.10880509 -0.21828158, -0.12870499 0.1088087 -0.21829467, -0.12936923 0.10911807 -0.21845879, -0.12919483 0.10906288 -0.2184834, -0.12890226 0.10894427 -0.21842279, -0.1287927 0.10887918 -0.21836142, -0.12870485 0.10887989 -0.21837537, -0.12927124 0.10906348 -0.21856852, -0.12893197 0.1089811 -0.2185228, -0.1288043 0.10893413 -0.21845527, -0.12870485 0.10893223 -0.2184694, -0.12896726 0.10899445 -0.21862657, -0.12881896 0.1089669 -0.2185578, -0.12870488 0.1089631 -0.21857269, -0.12900683 0.10898373 -0.21872951, -0.12883636 0.10897693 -0.21866454, -0.12870488 0.10897119 -0.21867999, -0.12870485 0.10895619 -0.21878661, -0.12885597 0.10896331 -0.21877114, -0.12905496 0.10885309 -0.21809366, -0.1290825 0.10894427 -0.21815984, -0.11953768 0.10880862 -0.21829471, -0.11953774 0.10887997 -0.21837541, -0.1195378 0.10893215 -0.21846962, -0.11953783 0.10896315 -0.21857274, -0.11953783 0.10897125 -0.21868002, -0.11953774 0.10895626 -0.21878666, -0.11896124 0.10890953 -0.21887869, -0.11892417 0.10892116 -0.21877506, -0.11889082 0.10890834 -0.21867007, -0.11886272 0.10887204 -0.21856937, -0.11884162 0.10881412 -0.21847753, -0.11882797 0.10873707 -0.21839935, -0.11376357 0.10275529 -0.2311905, -0.11376342 0.10277033 -0.23108383, -0.11376348 0.10276221 -0.23097652, -0.11376354 0.10267889 -0.23077925, -0.11376339 0.10273127 -0.23087353, -0.11376339 0.10260768 -0.2306987, -0.11318687 0.10270868 -0.23128268, -0.11314985 0.10272002 -0.23117901, -0.11311644 0.10270731 -0.23107386, -0.11308837 0.102671 -0.23097323, -0.11306724 0.10261309 -0.23088168, -0.11305365 0.10253608 -0.23080324, -0.12293047 0.10260762 -0.23069859, -0.12293062 0.10267894 -0.23077932, -0.12293059 0.10273112 -0.23087344, -0.12293062 0.10276198 -0.23097657, -0.12293047 0.10277022 -0.23108387, -0.12293065 0.1027551 -0.23119037, -0.12322983 0.10263173 -0.23056021, -0.12309107 0.10260677 -0.23065732, -0.12356317 0.10295895 -0.23068751, -0.12350401 0.1029084 -0.23079114, -0.12347287 0.10291745 -0.23062485, -0.1234234 0.10287537 -0.23071489, -0.12335259 0.10283662 -0.23079917, -0.12335676 0.10281934 -0.23063755, -0.12329608 0.10278797 -0.23071228, -0.12325439 0.10271826 -0.23063101, -0.12310529 0.10268441 -0.23073523, -0.12301102 0.10260412 -0.23068528, -0.123595 0.10291702 -0.23086272, -0.1236648 0.1029762 -0.23074327, -0.12342057 0.10286176 -0.23088728, -0.12312785 0.10274319 -0.23082665, -0.12301859 0.10267794 -0.23076545, -0.12349698 0.10286248 -0.2309723, -0.12315765 0.10278015 -0.23092663, -0.12302995 0.10273297 -0.23085913, -0.123193 0.10279348 -0.23103039, -0.12304473 0.10276605 -0.23096186, -0.1232326 0.10278279 -0.23113333, -0.12306222 0.10277596 -0.23106851, -0.12308148 0.10276231 -0.23117499, -0.12331662 0.1026769 -0.23043184, -0.12328053 0.10265197 -0.23049766, -0.12334627 0.10277237 -0.23049331, -0.12330824 0.10274328 -0.23056373, -0.12339932 0.10285413 -0.23055886, -0.12364003 0.10331166 -0.22905679, -0.12364882 0.10339603 -0.22908716, -0.12356129 0.10334033 -0.22901298, -0.12356776 0.10342512 -0.22904067, -0.12338114 0.10376222 -0.22896418, -0.12351412 0.10375145 -0.22897951, -0.12338108 0.10365787 -0.22900008, -0.12349638 0.10364592 -0.22901319, -0.12348297 0.10353494 -0.22902276, -0.12360743 0.10362296 -0.22904989, -0.12358132 0.10351259 -0.22905393, -0.12366799 0.10348244 -0.22910485, -0.12338105 0.10385627 -0.22890611, -0.12353548 0.10384619 -0.22892354, -0.12364286 0.10372743 -0.22902243, -0.12370586 0.10359052 -0.22910826, -0.12355909 0.10392541 -0.22884788, -0.12338114 0.1039352 -0.22882864, -0.12368545 0.1038202 -0.22897299, -0.12375692 0.10369146 -0.22909047, -0.12373286 0.10389695 -0.22890417, -0.12381881 0.10377994 -0.22905205, -0.12388784 0.10385105 -0.22899549, -0.12347254 0.10336244 -0.2289878, -0.123476 0.1034472 -0.22901283, -0.11454237 0.10393521 -0.22882871, -0.11454248 0.10385627 -0.22890602, -0.11454239 0.10376222 -0.22896427, -0.11454242 0.10365789 -0.22900006, -0.11382192 0.10331905 -0.22910096, -0.11381742 0.10338362 -0.22912031, -0.11380988 0.10344999 -0.22913131, -0.11378971 0.10356638 -0.22912963, -0.1137614 0.10367768 -0.2291016, -0.11372671 0.10377757 -0.22904903, -0.11368766 0.10386048 -0.22897488, -0.11415353 0.1036808 -0.22902155, -0.14727145 -0.02288197 -0.14046159, -0.14602882 -0.02452372 -0.14043322, -0.14732063 -0.022922099 -0.14043932, -0.14736459 -0.02295813 -0.14040364, -0.14599609 -0.024625003 -0.1404082, -0.1459775 -0.024706185 -0.14037423, -0.14740136 -0.022988051 -0.1403562, -0.14597416 -0.024744868 -0.14034782, -0.14597595 -0.024763644 -0.14032833, -0.14742911 -0.02301079 -0.14029936, -0.14597964 -0.024774611 -0.14031152, -0.14598441 -0.024780571 -0.14029698, -0.14599216 -0.024783731 -0.14027868, -0.1460031 -0.024782091 -0.14025803, -0.1474463 -0.023024768 -0.14023586, -0.14602038 -0.024772316 -0.14023097, -0.14604378 -0.024751604 -0.14020042, -0.14766315 -0.022586435 -0.14043935, -0.14804399 -0.022276834 -0.14046144, -0.14762399 -0.022536486 -0.14046164, -0.1480712 -0.022334129 -0.14043935, -0.14855549 -0.02231428 -0.14029904, -0.14900136 -0.022264719 -0.14029901, -0.14900124 -0.022228956 -0.14035605, -0.14854762 -0.022279471 -0.14035602, -0.14811587 -0.022428468 -0.140356, -0.14853716 -0.022233069 -0.14040343, -0.14809549 -0.022385538 -0.14040355, -0.14769825 -0.022631139 -0.14040364, -0.14856029 -0.022336006 -0.14023577, -0.14900127 -0.022286981 -0.14023574, -0.14813128 -0.022460669 -0.14029904, -0.14772749 -0.02266854 -0.14035599, -0.1481407 -0.022480756 -0.1402358, -0.14774966 -0.022696674 -0.14029925, -0.14776331 -0.022714138 -0.14023589, -0.14851069 -0.022115782 -0.14046144, -0.14900136 -0.022061229 -0.14046149, -0.14852467 -0.022177666 -0.14043935, -0.14900139 -0.022124559 -0.14043935, -0.14900142 -0.022181496 -0.14040342, -0.15457782 -0.022061273 -0.14046147, -0.15457761 -0.022124693 -0.14043924, -0.15457788 -0.022181615 -0.14040336, -0.15457788 -0.022229061 -0.14035597, -0.15457785 -0.022264868 -0.14029928, -0.15457788 -0.022287011 -0.14023571, -0.15659153 -0.023834914 -0.14035626, -0.15660757 -0.02429454 -0.14029935, -0.1566433 -0.02429451 -0.14035636, -0.15545848 -0.022465736 -0.14029898, -0.15584341 -0.022707611 -0.14029922, -0.15586558 -0.022679716 -0.14035602, -0.15663785 -0.023824394 -0.14040355, -0.15547407 -0.022433624 -0.14035597, -0.15503737 -0.022280857 -0.14035597, -0.15504807 -0.022234544 -0.14040336, -0.15549466 -0.022390902 -0.14040355, -0.15648165 -0.023377776 -0.14040361, -0.15669322 -0.023811698 -0.14043944, -0.15653285 -0.023353174 -0.14043945, -0.15544888 -0.022485793 -0.14023577, -0.15582946 -0.022724956 -0.1402358, -0.15627432 -0.022941738 -0.14043935, -0.15658987 -0.023325562 -0.14046149, -0.15502951 -0.022315681 -0.14029919, -0.15632376 -0.022902146 -0.14046144, -0.15597034 -0.022548482 -0.14046153, -0.15502456 -0.022337317 -0.14023571, -0.15655667 -0.023842841 -0.14029934, -0.15658534 -0.02429454 -0.14023599, -0.15643868 -0.023398474 -0.14035624, -0.15622985 -0.022977158 -0.1404036, -0.15593076 -0.022598073 -0.14043936, -0.15653509 -0.023847878 -0.14023583, -0.15554687 -0.022282556 -0.14046144, -0.15640655 -0.023413911 -0.14029926, -0.15619269 -0.023006693 -0.14035624, -0.15589526 -0.022642553 -0.14040355, -0.15551928 -0.022339597 -0.14043933, -0.15638661 -0.023423582 -0.14023598, -0.15507472 -0.022117287 -0.1404614, -0.15616471 -0.023029 -0.14029922, -0.15675521 -0.023797661 -0.14046176, -0.1567477 -0.024294525 -0.14043947, -0.15681109 -0.02429457 -0.14046174, -0.15669081 -0.02429457 -0.14040375, -0.15506062 -0.022179052 -0.1404393, -0.15614733 -0.023042992 -0.14023584, -0.15681112 -0.027184278 -0.140462, -0.15674752 -0.027184248 -0.14043973, -0.15669075 -0.027184263 -0.14040399, -0.15664336 -0.027184322 -0.1403566, -0.15660751 -0.027184308 -0.14029966, -0.15658543 -0.027184293 -0.14023617, -0.15678582 -0.027432531 -0.14046206, -0.15671113 -0.027670622 -0.14046209, -0.15628713 -0.027930692 -0.1402998, -0.1561107 -0.028039306 -0.14023627, -0.15612245 -0.028058171 -0.14029984, -0.15631184 -0.02795653 -0.14035675, -0.15623012 -0.028230995 -0.14046206, -0.15645239 -0.027792916 -0.14035657, -0.15634459 -0.027991012 -0.14040405, -0.15649125 -0.02782014 -0.14040406, -0.15660062 -0.027623221 -0.14040413, -0.15653798 -0.027852595 -0.14043979, -0.15665281 -0.027645648 -0.14043985, -0.15672383 -0.027419835 -0.14043994, -0.15627205 -0.027914539 -0.14023638, -0.15642294 -0.027772576 -0.14029963, -0.15655693 -0.027604491 -0.14035656, -0.15666795 -0.027408302 -0.14040409, -0.15640482 -0.027759835 -0.14023629, -0.15652412 -0.027590394 -0.14029984, -0.1566214 -0.027398854 -0.14035667, -0.15650374 -0.027581573 -0.1402363, -0.1565865 -0.027391583 -0.14029957, -0.1565648 -0.027387172 -0.14023627, -0.15642744 -0.028078228 -0.14046206, -0.1561965 -0.028177112 -0.14043988, -0.15638381 -0.028032199 -0.14043981, -0.15616646 -0.028128818 -0.14040405, -0.15658998 -0.02788879 -0.14046204, -0.15614122 -0.028088495 -0.14035675, -0.14590514 -0.024666712 -0.14046696, -0.14599264 -0.024508715 -0.14045595, -0.14591321 -0.024527952 -0.14050999, -0.14595363 -0.024710253 -0.14039361, -0.14596328 -0.024637192 -0.1404245, -0.14585996 -0.024700925 -0.1405206, -0.14585203 -0.024552926 -0.14058277, -0.14595327 -0.024761125 -0.14035907, -0.14590764 -0.024745941 -0.14042591, -0.14595756 -0.024784237 -0.1403342, -0.14614543 -0.024054661 -0.14047641, -0.14606991 -0.024046287 -0.1404992, -0.14599887 -0.024038285 -0.14053734, -0.14593709 -0.024031401 -0.14058898, -0.14588773 -0.024025917 -0.14065085, -0.14596319 -0.024796069 -0.14031444, -0.14591694 -0.024801672 -0.14038031, -0.14587244 -0.024785474 -0.1404658, -0.14597034 -0.024803519 -0.14029346, -0.14592606 -0.024827585 -0.14034799, -0.1459887 -0.024805009 -0.14025299, -0.14593446 -0.024841189 -0.14032243, -0.14588928 -0.02484566 -0.14040725, -0.14600679 -0.024796039 -0.14022, -0.14594433 -0.02485016 -0.14029558, -0.1459026 -0.024874046 -0.14036661, -0.14596602 -0.024853975 -0.14024337, -0.14591381 -0.024889499 -0.14033468, -0.14598557 -0.024846405 -0.14020111, -0.1459263 -0.024900064 -0.1403015, -0.14595187 -0.024906635 -0.14023732, -0.14597404 -0.024900958 -0.14018527, -0.14616901 -0.022798002 -0.14015077, -0.14623141 -0.022800788 -0.14011595, -0.14613011 -0.022952586 -0.13991804, -0.14607993 -0.022950381 -0.13995607, -0.14585063 -0.022857442 -0.14004892, -0.14579302 -0.023190245 -0.13979879, -0.14592043 -0.022899479 -0.14003403, -0.14610562 -0.022784993 -0.14017871, -0.14598706 -0.023223132 -0.13958205, -0.14602765 -0.022940561 -0.13998833, -0.14602926 -0.022755712 -0.1402026, -0.14596263 -0.022918791 -0.14001931, -0.14598212 -0.02272971 -0.14021182, -0.14590833 -0.022674993 -0.14021605, -0.14624059 -0.022920251 -0.13979779, -0.14593467 -0.023229554 -0.13966668, -0.1461958 -0.02294144 -0.13985451, -0.14586869 -0.023218259 -0.13974056, -0.14637199 -0.022756889 -0.14000112, -0.14631474 -0.022785366 -0.14005558, -0.13912559 -0.03135626 -0.13507685, -0.13920128 -0.031384289 -0.13501833, -0.13926721 -0.03139554 -0.13494471, -0.13931951 -0.031389207 -0.13485999, -0.13874605 -0.032315075 -0.13451765, -0.13874596 -0.031904191 -0.13476785, -0.13880432 -0.031914636 -0.13474402, -0.13887793 -0.031919271 -0.13469954, -0.13865709 -0.032178923 -0.13461217, -0.13870153 -0.032176703 -0.13460435, -0.13865528 -0.032272115 -0.13455921, -0.13869381 -0.032339811 -0.1345176, -0.13875937 -0.032169938 -0.13458733, -0.13869321 -0.032264397 -0.13455698, -0.13874283 -0.032251254 -0.13454884, 0.1540892 -0.022285074 -0.14023572, 0.1485128 -0.022292599 -0.14016905, 0.14851265 -0.022285029 -0.14023569, 0.15408924 -0.022292495 -0.14016889, 0.15408918 -0.022262767 -0.14029901, 0.14851262 -0.022262841 -0.14029908, 0.15408926 -0.022227123 -0.14035594, 0.14851262 -0.022227079 -0.14035606, 0.15408923 -0.022179544 -0.14040342, 0.14851262 -0.022179514 -0.14040357, 0.1540892 -0.022122726 -0.1404393, 0.14851271 -0.022122726 -0.14043918, 0.15408918 -0.022059187 -0.14046149, 0.14851262 -0.022059232 -0.14046144, 0.15408924 -0.021992564 -0.140469, 0.14851262 -0.021992505 -0.1404689, 0.12289089 0.10354953 -0.22901243, 0.12289086 0.10365953 -0.2290003, 0.11405218 0.10354957 -0.22901244, 0.11405209 0.10365939 -0.22900032, 0.12289093 0.10376391 -0.22896428, 0.11405219 0.1037638 -0.22896421, 0.12289077 0.10385792 -0.22890612, 0.11405218 0.10385785 -0.22890623, 0.12289092 0.10393675 -0.22882873, 0.11405221 0.10393679 -0.22882877, 0.12289092 0.10399683 -0.22873604, 0.11405224 0.10399678 -0.22873609, 0.12336116 0.10346118 -0.22932477, 0.12337893 0.10342006 -0.22941169, 0.12343827 0.1035514 -0.22934625, 0.12345867 0.10350254 -0.22944649, 0.12351155 0.10343157 -0.22974509, 0.12345557 0.10344759 -0.22956081, 0.12342134 0.10338999 -0.22968242, 0.12355292 0.10350059 -0.22960418, 0.12355737 0.10356644 -0.22947069, 0.12329227 0.10311155 -0.22926396, 0.12327914 0.10325101 -0.22924514, 0.12327926 0.10314336 -0.22919147, 0.12326378 0.10316245 -0.22915, 0.12324278 0.10328916 -0.22916572, 0.12326781 0.10340026 -0.22920556, 0.12330715 0.10335913 -0.22929056, 0.12332277 0.10332367 -0.22936778, 0.1233767 0.10337426 -0.22951072, 0.1233477 0.10332672 -0.22961637, 0.12329316 0.1032189 -0.22931761, 0.12332062 0.10328498 -0.22945602, 0.12329465 0.10324506 -0.2295509, 0.12377399 0.1035202 -0.22968945, 0.12361321 0.10344894 -0.22980103, 0.12372088 0.10344116 -0.22984737, 0.1232903 0.10318433 -0.22940069, 0.12326503 0.10314964 -0.22948939, 0.12328784 0.10307804 -0.22934692, 0.12324314 0.10318115 -0.22911151, 0.12326059 0.10304554 -0.22943518, 0.12357138 0.10375282 -0.22919147, 0.12364253 0.10367616 -0.22934517, 0.12367581 0.10379216 -0.22914545, 0.12375803 0.10370272 -0.22932436, 0.12347291 0.10368976 -0.22922163, 0.12353401 0.10362461 -0.22935303, 0.12366919 0.10360757 -0.22948261, 0.12379004 0.10360444 -0.22952099, 0.12338632 0.10360663 -0.2292344, 0.12366286 0.10353018 -0.22963795, 0.12331662 0.10350819 -0.22922894, 0.12866513 0.10975069 -0.21660854, 0.12866513 0.1098606 -0.21659635, 0.11982648 0.10975079 -0.21660855, 0.11982656 0.10986042 -0.21659629, 0.12866519 0.10996497 -0.21656029, 0.11982654 0.10996495 -0.21656027, 0.12866513 0.11005896 -0.21650223, 0.11982648 0.11005895 -0.21650219, 0.12866513 0.11013788 -0.21642484, 0.11982648 0.11013786 -0.21642482, 0.12866513 0.11019796 -0.21633206, 0.11982648 0.11019783 -0.21633208, 0.11395547 0.10829586 -0.21945883, 0.11875673 0.10958822 -0.21687371, 0.11384378 0.10836305 -0.21950904, 0.11872686 0.10970069 -0.21687451, 0.11377676 0.10841785 -0.21952444, 0.11868577 0.10980706 -0.21685135, 0.1137366 0.10846114 -0.21952291, 0.11371058 0.10849819 -0.21951284, 0.11369286 0.1085328 -0.21949646, 0.11863565 0.10990155 -0.21680553, 0.11368169 0.10856728 -0.21947345, 0.11367676 0.10860151 -0.21944381, 0.11857927 0.10997915 -0.21673958, 0.11367832 0.10863473 -0.21940845, 0.11369008 0.10867748 -0.21935286, 0.11370932 0.10871388 -0.21929544, 0.11851977 0.1100354 -0.2166571, 0.11373614 0.10874785 -0.21923259, 0.12624833 0.10656174 -0.22312298, 0.12626605 0.10652068 -0.22320955, 0.12632546 0.1066521 -0.2231442, 0.12634581 0.10660319 -0.22324458, 0.12639865 0.10653223 -0.2235432, 0.12634271 0.10654812 -0.22335902, 0.12630846 0.10649079 -0.22348033, 0.1264445 0.10666683 -0.22326888, 0.12644 0.10660118 -0.22340231, 0.12617952 0.10621218 -0.22306186, 0.12616636 0.10635167 -0.22304331, 0.12616642 0.10624379 -0.22298948, 0.1261508 0.1062631 -0.22294788, 0.12613004 0.10638969 -0.22296372, 0.12615496 0.10650091 -0.22300369, 0.12619424 0.10645972 -0.22308868, 0.12620997 0.10642432 -0.22316581, 0.1262638 0.10647492 -0.22330871, 0.12623484 0.10642731 -0.22341441, 0.12618023 0.10631947 -0.22311562, 0.12620768 0.1063856 -0.22325423, 0.12618178 0.1063457 -0.223349, 0.12666115 0.10662092 -0.22348738, 0.12650029 0.10654953 -0.22359909, 0.12660791 0.10654181 -0.22364531, 0.12617739 0.10628504 -0.22319873, 0.1261522 0.1062502 -0.22328736, 0.12617499 0.10617857 -0.22314495, 0.12613031 0.10628183 -0.2229096, 0.12614767 0.10614613 -0.22323318, 0.12645842 0.10685343 -0.22298943, 0.12652963 0.10677688 -0.22314349, 0.12656291 0.1068927 -0.22294341, 0.12664515 0.10680334 -0.22312227, 0.12636001 0.1067903 -0.22301982, 0.12642114 0.10672525 -0.2231511, 0.12655625 0.10670818 -0.2232807, 0.1266772 0.10670498 -0.22331895, 0.12627333 0.10670714 -0.22303244, 0.1265499 0.10663073 -0.22343606, 0.1262037 0.10660878 -0.22302695, 0.12577796 0.10665022 -0.22281045, 0.12577805 0.10675998 -0.22279814, 0.11693925 0.10665014 -0.22281046, 0.11693926 0.10675989 -0.22279829, 0.12577799 0.10686441 -0.22276223, 0.11693929 0.10686441 -0.22276214, 0.125778 0.10695842 -0.2227041, 0.11693929 0.10695834 -0.22270411, 0.12577805 0.10703744 -0.22262692, 0.11693929 0.10703744 -0.22262684, 0.12577799 0.1070974 -0.22253403, 0.11693929 0.10709734 -0.22253415, 0.11758685 0.097259983 -0.2417289, 0.11760464 0.097219005 -0.24181548, 0.11766395 0.097350433 -0.24174997, 0.11768441 0.097301394 -0.24185057, 0.11773719 0.097230554 -0.24214892, 0.11768129 0.097246543 -0.24196497, 0.11764714 0.097189024 -0.24208626, 0.1177831 0.097365156 -0.24187469, 0.11777857 0.097299471 -0.24200812, 0.1175181 0.096910492 -0.2416679, 0.11750489 0.097049996 -0.24164915, 0.11750501 0.096942112 -0.24159527, 0.11748947 0.096961379 -0.24155383, 0.11746851 0.097087994 -0.24156955, 0.11749361 0.097199172 -0.24160944, 0.11753291 0.097158119 -0.24169442, 0.11754838 0.097122684 -0.24177161, 0.11760248 0.097173333 -0.24191453, 0.11757344 0.097125694 -0.24202037, 0.11751898 0.097017825 -0.24172162, 0.11754631 0.097083956 -0.24186011, 0.11752039 0.097044036 -0.2419548, 0.1179997 0.097319141 -0.24209324, 0.11783892 0.097247884 -0.2422049, 0.11794657 0.097240135 -0.24225116, 0.11751598 0.096983239 -0.24180448, 0.11749071 0.096948549 -0.24189329, 0.11751354 0.096876964 -0.24175084, 0.11746873 0.096980095 -0.24151544, 0.1174863 0.096844479 -0.24183917, 0.11779706 0.097551733 -0.24159537, 0.11786824 0.097475097 -0.24174905, 0.1179015 0.097591087 -0.24154937, 0.11798376 0.09750168 -0.24172831, 0.11769864 0.097488716 -0.24162546, 0.11775976 0.097423598 -0.24175692, 0.1178948 0.097406402 -0.24188665, 0.11801568 0.097403303 -0.24192467, 0.11761206 0.097405598 -0.2416383, 0.1178886 0.097329035 -0.24204198, 0.1175423 0.097307101 -0.24163294, 0.11711651 0.097348616 -0.24141645, 0.1171166 0.097458377 -0.24140421, 0.1082779 0.097348437 -0.24141642, 0.10827798 0.097458243 -0.24140416, 0.11711662 0.09756282 -0.24136816, 0.10827787 0.097562686 -0.24136817, 0.11711648 0.097656801 -0.24131006, 0.10827798 0.097656727 -0.24131002, 0.10827793 0.097735599 -0.24123278, 0.11711664 0.097735703 -0.24123277, 0.10827783 0.097795695 -0.24113993, 0.11711651 0.09779577 -0.24113989, 0.11469966 0.094159648 -0.24793079, 0.11471739 0.094118491 -0.2480174, 0.11477676 0.094249859 -0.24795207, 0.11479729 0.094200894 -0.24805251, 0.11484998 0.094129965 -0.24835089, 0.11479427 0.094146013 -0.24816684, 0.11475998 0.09408848 -0.24828821, 0.11489603 0.094264701 -0.24807671, 0.11489147 0.094198987 -0.2482101, 0.11463085 0.093809977 -0.24786982, 0.11461774 0.093949452 -0.24785128, 0.11461787 0.093841583 -0.24779727, 0.11460227 0.093860909 -0.24775589, 0.11458141 0.09398751 -0.2477715, 0.1146064 0.094098687 -0.24781157, 0.11464578 0.094057605 -0.24789658, 0.11466128 0.0940222 -0.24797368, 0.11471528 0.094072744 -0.24811652, 0.11468627 0.094025195 -0.24822237, 0.11463168 0.093917385 -0.24792352, 0.1146591 0.093983427 -0.24806216, 0.11463314 0.093943521 -0.24815679, 0.11511263 0.094218507 -0.24829516, 0.11495179 0.094147369 -0.24840704, 0.11505935 0.09413965 -0.24845329, 0.11462882 0.093882814 -0.24800649, 0.1146037 0.093847916 -0.24809527, 0.11462635 0.093776509 -0.24795285, 0.11458176 0.093879625 -0.2477175, 0.11459914 0.093743935 -0.24804118, 0.1149098 0.094451204 -0.24779728, 0.11498111 0.094374582 -0.24795106, 0.11501431 0.094490573 -0.24775147, 0.11509667 0.094401091 -0.2479303, 0.11481147 0.094388157 -0.24782754, 0.11487263 0.094323084 -0.24795893, 0.11500774 0.094305962 -0.24808861, 0.11512855 0.094302788 -0.24812666, 0.11472486 0.094305009 -0.24784027, 0.11500144 0.094228551 -0.24824405, 0.11465508 0.094206735 -0.24783492, 0.11422935 0.094248071 -0.24761835, 0.11422935 0.094357863 -0.24760619, 0.10539082 0.094247878 -0.2476183, 0.10539079 0.094357759 -0.24760617, 0.1142294 0.094462216 -0.24757005, 0.10539079 0.094462097 -0.24757008, 0.11422935 0.094556227 -0.24751189, 0.10539077 0.094556078 -0.24751189, 0.11422935 0.094635144 -0.24743468, 0.1053907 0.09463504 -0.24743475, 0.11422949 0.094695121 -0.24734189, 0.10539076 0.094695061 -0.24734192, 0.11181261 0.09105888 -0.25413287, 0.11183035 0.091017857 -0.25421932, 0.11188968 0.09114936 -0.25415391, 0.11191006 0.091100305 -0.25425446, 0.11196287 0.091029435 -0.25455278, 0.11190712 0.091045395 -0.25436869, 0.1118729 0.090987802 -0.25449014, 0.1120088 0.091164112 -0.25427848, 0.11200424 0.091098398 -0.254412, 0.11174391 0.090709329 -0.25407177, 0.11173065 0.090848893 -0.25405312, 0.11173078 0.090741023 -0.25399923, 0.11171512 0.090760171 -0.25395781, 0.11169432 0.09088695 -0.25397348, 0.11171935 0.090998054 -0.2540133, 0.11175855 0.090956897 -0.25409859, 0.11177404 0.090921611 -0.25417554, 0.11182816 0.090972155 -0.25431842, 0.1117992 0.090924472 -0.25442421, 0.1117446 0.090816706 -0.25412536, 0.11177202 0.090882748 -0.25426412, 0.11174616 0.090842828 -0.25435865, 0.11222537 0.091117948 -0.25449705, 0.11206467 0.091046661 -0.25460881, 0.11217223 0.091039062 -0.25465512, 0.11174174 0.090782136 -0.25420845, 0.11171649 0.090747356 -0.25429714, 0.11173928 0.090675846 -0.25415483, 0.11169453 0.090779036 -0.25391936, 0.11171193 0.090643376 -0.25424308, 0.11202271 0.091350645 -0.25399923, 0.11209388 0.091273993 -0.25415289, 0.11212729 0.091389894 -0.25395328, 0.11220939 0.091300458 -0.25413221, 0.11192437 0.091287583 -0.25402939, 0.11198555 0.091222405 -0.25416088, 0.11212058 0.091205448 -0.25429052, 0.11224134 0.091202229 -0.25432867, 0.1118377 0.091204375 -0.25404227, 0.11211427 0.091127843 -0.25444579, 0.11176796 0.091106027 -0.25403678, 0.1113424 0.091147408 -0.2538203, 0.11134231 0.091257229 -0.25380805, 0.10250366 0.091147259 -0.25382027, 0.10250366 0.09125711 -0.25380805, 0.11134227 0.091361612 -0.25377202, 0.1025037 0.091361582 -0.25377208, 0.11134227 0.091455668 -0.25371397, 0.10250366 0.091455594 -0.253714, 0.1113423 0.091534495 -0.25363666, 0.10250366 0.091534451 -0.25363669, 0.11134236 0.091594636 -0.25354385, 0.10250366 0.091594592 -0.25354388, 0.10892552 0.087958381 -0.26033479, 0.10894327 0.087917358 -0.26042134, 0.10900265 0.088048741 -0.26035598, 0.10902306 0.087999776 -0.26045653, 0.10907593 0.087928727 -0.2607547, 0.10902011 0.087944791 -0.26057091, 0.10898572 0.087887332 -0.26069215, 0.10912189 0.088063553 -0.26048049, 0.1091173 0.087997809 -0.26061398, 0.10885668 0.087608799 -0.26027375, 0.10884356 0.087748274 -0.26025495, 0.1088438 0.08764039 -0.26020125, 0.10882805 0.087659806 -0.26015955, 0.10880715 0.087786362 -0.2601755, 0.10883227 0.087897375 -0.2602154, 0.10887152 0.087856337 -0.26030043, 0.10888705 0.087820962 -0.2603775, 0.10894108 0.087871537 -0.26052031, 0.10891199 0.087823972 -0.26062611, 0.10885751 0.087716207 -0.2603274, 0.10888481 0.087782249 -0.26046589, 0.10885899 0.087742358 -0.26056069, 0.10933828 0.088017449 -0.26069906, 0.1091775 0.087946251 -0.26081085, 0.10928512 0.087938532 -0.26085714, 0.10885465 0.087681636 -0.26041049, 0.10882929 0.087646857 -0.26049912, 0.10885212 0.087575272 -0.26035669, 0.10880744 0.087678418 -0.26012129, 0.10882491 0.087542698 -0.26044506, 0.10913566 0.088250056 -0.26020133, 0.10920694 0.088173285 -0.26035491, 0.10924019 0.08828932 -0.2601552, 0.1093225 0.088199854 -0.26033413, 0.10903722 0.088187024 -0.26023135, 0.10909848 0.088121802 -0.26036268, 0.10923354 0.088104874 -0.2604925, 0.10935432 0.08810167 -0.26053074, 0.10895061 0.088103876 -0.26024419, 0.10922724 0.088027403 -0.2606478, 0.10888095 0.088005424 -0.26023877, 0.10845523 0.088046819 -0.26002222, 0.10845521 0.088156596 -0.26000991, 0.099616542 0.088046864 -0.26002216, 0.099616542 0.088156536 -0.26001, 0.10845518 0.088261232 -0.25997403, 0.099616557 0.088261127 -0.259974, 0.10845512 0.088355109 -0.2599158, 0.099616468 0.088355035 -0.25991583, 0.10845524 0.088434026 -0.25983861, 0.099616468 0.088433951 -0.25983858, 0.10845533 0.088493899 -0.25974572, 0.099616572 0.088493958 -0.25974572, 0.10603833 0.084857926 -0.26653659, 0.10605617 0.084816754 -0.26662332, 0.10611543 0.084948197 -0.26655796, 0.10613585 0.084899172 -0.26665819, 0.10618877 0.084828243 -0.26695687, 0.10613275 0.084844336 -0.26677263, 0.10609859 0.084786817 -0.26689416, 0.10623452 0.084963039 -0.2666826, 0.10623017 0.084897175 -0.26681593, 0.10596958 0.084508196 -0.26647565, 0.10595655 0.084647641 -0.26645714, 0.10595644 0.084539875 -0.26640314, 0.10594085 0.084559277 -0.26636174, 0.10591996 0.084685788 -0.26637742, 0.10594511 0.084796891 -0.26641732, 0.10598433 0.084755823 -0.26650238, 0.10599995 0.084720477 -0.26657951, 0.10605392 0.084770992 -0.26672232, 0.10602486 0.084723398 -0.26682806, 0.10597038 0.084615692 -0.26652926, 0.1059978 0.084681734 -0.26666796, 0.10597184 0.08464171 -0.26676258, 0.10645123 0.08491689 -0.26690102, 0.10629034 0.084845647 -0.26701289, 0.1063979 0.084837928 -0.26705912, 0.10596752 0.084581241 -0.26661235, 0.10594237 0.084546313 -0.26670116, 0.10596502 0.084474608 -0.26655865, 0.10592031 0.084577903 -0.26632327, 0.10593781 0.084442094 -0.26664701, 0.10624862 0.085149392 -0.26640326, 0.10631979 0.085072801 -0.26655686, 0.10635304 0.085188732 -0.26635724, 0.10643524 0.085099205 -0.26653612, 0.10615018 0.085086361 -0.26643333, 0.10621116 0.085021332 -0.26656464, 0.10634631 0.085004196 -0.26669443, 0.10646719 0.085001096 -0.26673257, 0.10606351 0.085003272 -0.26644602, 0.10634005 0.084926769 -0.26684964, 0.10599384 0.084904864 -0.26644072, 0.10556816 0.084946245 -0.26622421, 0.10556808 0.085056022 -0.2662119, 0.096729398 0.084946245 -0.26622421, 0.096729398 0.085055977 -0.26621187, 0.10556817 0.085160479 -0.26617604, 0.096729383 0.085160568 -0.26617604, 0.10556799 0.085254654 -0.26611781, 0.096729338 0.085254461 -0.26611787, 0.10556813 0.085333407 -0.26604056, 0.096729428 0.085333467 -0.26604062, 0.10556799 0.085393533 -0.26594782, 0.096729338 0.085393518 -0.26594782, 0.11401485 -0.032788873 -0.21487598, 0.11351725 -0.032788649 -0.21609086, 0.11401506 -0.032771602 -0.21487598, 0.11351758 -0.032771513 -0.21609101, 0.11401589 -0.032754436 -0.21487634, 0.1135183 -0.032754347 -0.21609125, 0.11351971 -0.032737195 -0.21609168, 0.11401722 -0.032737151 -0.21487695, 0.11713377 -0.033278555 -0.20575571, 0.11699115 -0.033289224 -0.20563771, 0.11715549 -0.033289284 -0.20565519, 0.11711308 -0.033246905 -0.20585203, 0.11699118 -0.033278346 -0.20574151, 0.11699125 -0.033246219 -0.20584095, 0.11709413 -0.033195645 -0.20593989, 0.11699118 -0.033193946 -0.20593141, 0.11707777 -0.03312698 -0.20601562, 0.11699118 -0.033124089 -0.20600902, 0.11706483 -0.033043861 -0.20607582, 0.11702837 -0.033042789 -0.20607053, 0.11699115 -0.0330396 -0.20607056, 0.12040804 -0.033279046 -0.19776054, 0.12026545 -0.033289805 -0.19764245, 0.12042981 -0.033289716 -0.19765994, 0.12038724 -0.033247367 -0.19785692, 0.12026545 -0.033278823 -0.19774649, 0.12036835 -0.033196107 -0.19794478, 0.12026538 -0.033246472 -0.1978458, 0.12026547 -0.033194438 -0.19793613, 0.120352 -0.033127442 -0.19802046, 0.12026538 -0.033124432 -0.19801377, 0.12033902 -0.033044204 -0.19808061, 0.12030265 -0.033043265 -0.1980755, 0.12026538 -0.033040002 -0.1980754, 0.12368234 -0.033279434 -0.18976551, 0.1235397 -0.033290088 -0.18964741, 0.12370411 -0.033290088 -0.18966495, 0.12366159 -0.033247709 -0.1898618, 0.1235397 -0.03327924 -0.18975124, 0.12364264 -0.033196554 -0.18994972, 0.12353964 -0.03324689 -0.18985075, 0.12353969 -0.033194751 -0.18994118, 0.12362629 -0.0331278 -0.19002537, 0.12353964 -0.033124909 -0.19001886, 0.12361333 -0.033044681 -0.1900856, 0.12357679 -0.033043668 -0.19008036, 0.12353961 -0.03304036 -0.19008034, 0.12695655 -0.033279851 -0.18177038, 0.12681381 -0.033290476 -0.18165238, 0.12697825 -0.033290461 -0.18166989, 0.12693582 -0.033248141 -0.18186666, 0.12681387 -0.033279598 -0.18175618, 0.12681392 -0.033247411 -0.18185553, 0.12691681 -0.033197016 -0.18195458, 0.12681383 -0.033195123 -0.18194595, 0.12690042 -0.033128291 -0.18203004, 0.12681386 -0.033125311 -0.18202373, 0.12688746 -0.033045128 -0.18209042, 0.12685107 -0.033044055 -0.18208517, 0.12681386 -0.033040851 -0.18208525, 0.13023078 -0.033280298 -0.17377518, 0.13008809 -0.033290908 -0.17365716, 0.13025248 -0.033291027 -0.17367457, 0.1302101 -0.033248723 -0.17387156, 0.13008806 -0.03328006 -0.17376114, 0.13008809 -0.033247873 -0.17386042, 0.13019103 -0.033197358 -0.17395936, 0.13008812 -0.0331956 -0.1739509, 0.13017476 -0.033128753 -0.17403506, 0.13008797 -0.033125713 -0.17402859, 0.13016176 -0.033045545 -0.17409526, 0.13012537 -0.033044502 -0.17409013, 0.13008809 -0.033041254 -0.17409001, 0.13350511 -0.033280775 -0.1657802, 0.13336229 -0.033291385 -0.16566207, 0.13352674 -0.033291489 -0.16567947, 0.13348424 -0.033249214 -0.1658764, 0.13336241 -0.033280537 -0.16576602, 0.13346529 -0.033197805 -0.16596426, 0.13336241 -0.033248231 -0.16586532, 0.13336241 -0.033196136 -0.1659558, 0.13344884 -0.033129141 -0.16603984, 0.13336241 -0.03312628 -0.16603352, 0.13343596 -0.033046082 -0.16610016, 0.13339961 -0.033045009 -0.16609491, 0.13336235 -0.033041716 -0.16609488, 0.14005353 -0.03328155 -0.14978994, 0.13991086 -0.033292308 -0.14967199, 0.14007525 -0.033292219 -0.14968924, 0.14003272 -0.033249944 -0.14988621, 0.13991083 -0.033281356 -0.14977582, 0.13991083 -0.033249035 -0.14987518, 0.14001383 -0.03319861 -0.149974, 0.13991085 -0.033196956 -0.14996549, 0.13999747 -0.033130005 -0.15004988, 0.13991088 -0.03312704 -0.15004325, 0.13998452 -0.033046871 -0.1501101, 0.13994804 -0.033045799 -0.15010473, 0.1399108 -0.033042625 -0.15010472, 0.14332777 -0.033282027 -0.14179473, 0.14318505 -0.033292696 -0.14167683, 0.14334948 -0.033292606 -0.14169425, 0.14330697 -0.033250362 -0.14189114, 0.14318505 -0.033281803 -0.14178066, 0.14328805 -0.033199072 -0.14197902, 0.14318502 -0.033249542 -0.14187996, 0.14318502 -0.033197269 -0.14197041, 0.14327168 -0.033130392 -0.14205457, 0.14318505 -0.033127427 -0.14204805, 0.14325872 -0.033047318 -0.14211468, 0.14322221 -0.03304626 -0.14210965, 0.14318505 -0.033043042 -0.14210953, 0.12047401 0.10036053 -0.23552689, 0.12049179 0.10031953 -0.23561348, 0.12055101 0.10045087 -0.23554812, 0.12057148 0.10040185 -0.23564853, 0.12062442 0.10033099 -0.23594692, 0.12056841 0.10034704 -0.23576288, 0.12053418 0.10028957 -0.23588434, 0.12067024 0.1004658 -0.23567285, 0.12066565 0.10039994 -0.23580612, 0.12040521 0.10001099 -0.23546587, 0.12039211 0.10015048 -0.23544738, 0.12039216 0.1000427 -0.23539345, 0.12037657 0.10006198 -0.23535179, 0.12035562 0.10018849 -0.23536776, 0.1203807 0.10029982 -0.23540762, 0.12041999 0.10025859 -0.23549257, 0.12043561 0.10022318 -0.2355697, 0.12048964 0.10027376 -0.23571266, 0.12046053 0.10022628 -0.23581837, 0.12040602 0.10011849 -0.23551951, 0.12043335 0.10018444 -0.23565815, 0.12040749 0.10014452 -0.23575291, 0.12088685 0.10041967 -0.23589121, 0.12072608 0.10034843 -0.2360031, 0.12083365 0.10034072 -0.23604934, 0.12040326 0.1000839 -0.23560271, 0.12037787 0.10004921 -0.23569131, 0.12040065 0.099977463 -0.23554905, 0.12035599 0.10008074 -0.23531359, 0.1203734 0.099945083 -0.23563731, 0.12068407 0.10065237 -0.23539351, 0.12075536 0.10057548 -0.23554717, 0.12078862 0.10069159 -0.23534741, 0.12087084 0.10060203 -0.23552631, 0.12058577 0.10058923 -0.23542377, 0.12064682 0.10052404 -0.23555501, 0.12078203 0.1005069 -0.23568462, 0.12090276 0.10050377 -0.23572268, 0.12049912 0.10050616 -0.23543642, 0.12077571 0.10042953 -0.23583995, 0.12042941 0.1004076 -0.23543094, 0.1200036 0.10044909 -0.23521434, 0.12000363 0.10055879 -0.23520218, 0.11116494 0.10044904 -0.23521438, 0.11116494 0.10055883 -0.23520219, 0.12000376 0.10066341 -0.2351661, 0.11116506 0.10066326 -0.2351661, 0.12000374 0.10075727 -0.235108, 0.11116506 0.1007572 -0.23510802, 0.111165 0.10083619 -0.2350307, 0.1200037 0.10083626 -0.2350308, 0.11116508 0.10089622 -0.234938, 0.12000374 0.10089639 -0.23493804, 0.13677931 -0.033281118 -0.15778501, 0.13663658 -0.033291891 -0.157667, 0.136801 -0.033291847 -0.15768452, 0.13675845 -0.033249393 -0.15788136, 0.13663654 -0.033280879 -0.15777096, 0.13663657 -0.033248574 -0.15787023, 0.13673949 -0.033198133 -0.15796922, 0.13663661 -0.033196464 -0.15796076, 0.13672313 -0.033129498 -0.15804477, 0.13663651 -0.033126503 -0.15803826, 0.13671021 -0.033046365 -0.15810508, 0.13667373 -0.033045232 -0.15809998, 0.13663654 -0.033042163 -0.1580998, 0.11307062 -0.033804968 -0.22422181, 0.11296842 -0.033629313 -0.22451949, 0.11243944 -0.033032462 -0.2237248, 0.11232109 -0.032836527 -0.22401215, 0.11288753 -0.033379152 -0.22478539, 0.11223686 -0.032586187 -0.2242679, 0.1121809 -0.032289535 -0.22447743, 0.11283191 -0.033066064 -0.22500677, 0.11217768 -0.032265455 -0.22449155, 0.13753521 -0.032509103 -0.13446999, 0.13831851 -0.032509133 -0.13446996, 0.13831851 -0.032509133 -0.13447002, 0.13753521 -0.032509103 -0.13446999, 0.13753521 -0.032509103 -0.13446999, 0.14622416 -0.032423511 -0.13647367, 0.14623643 -0.032249063 -0.13648947, 0.14628527 -0.032266572 -0.13647485, 0.14618455 -0.032402113 -0.13648452, 0.14639212 -0.032091036 -0.13646986, 0.14623238 -0.031857803 -0.1365426, 0.14619114 -0.032232836 -0.1365128, 0.14618479 -0.031852439 -0.13659477, 0.14614727 -0.032381848 -0.13650207, 0.14613782 -0.032213762 -0.136557, 0.14615068 -0.031848654 -0.13665681, 0.14611043 -0.032228306 -0.13657992, 0.14588284 -0.032611012 -0.13650303, 0.14590952 -0.032591641 -0.13651042, 0.14588359 -0.032617435 -0.13649981, 0.14588201 -0.032604694 -0.13650636, 0.14588121 -0.032598481 -0.13650967, 0.14594567 -0.032646224 -0.13648297, 0.14635696 -0.031871885 -0.13647838, 0.14642681 -0.031879634 -0.1364698, 0.14629082 -0.031864375 -0.136503, 0.14596079 -0.032631949 -0.13648534, 0.14601342 -0.032663316 -0.13647337, 0.14608432 -0.032668799 -0.13647003, 0.14606251 -0.032639965 -0.13647215, 0.14618024 -0.03257519 -0.13646987, 0.14596555 -0.032556251 -0.13651621, 0.14594504 -0.032595694 -0.13650183, 0.14593729 -0.032578051 -0.13651256, 0.14604191 -0.032612652 -0.13647826, 0.14602222 -0.032586426 -0.13648815, 0.14614855 -0.032549247 -0.13647272, 0.14626588 -0.032446012 -0.13647012, 0.14600143 -0.032515243 -0.13652372, 0.14599676 -0.032552779 -0.13650732, 0.14611839 -0.032524467 -0.13648085, 0.14608975 -0.032501042 -0.13649373, 0.14604492 -0.032439172 -0.13653819, 0.14605333 -0.032471403 -0.13651876, 0.14633688 -0.03228505 -0.13646984, 0.081173867 0.073668569 -0.28754252, 0.081190467 0.073321223 -0.28742266, 0.081203163 0.073345959 -0.28738266, 0.081357926 0.073570937 -0.2878024, 0.081387252 0.07322523 -0.28763121, 0.081339031 0.073223665 -0.28762338, 0.081160665 0.073649883 -0.28758568, 0.081164032 0.074009091 -0.28765953, 0.081150502 0.073996514 -0.28770512, 0.081159204 0.073630661 -0.28763092, 0.081149012 0.07398358 -0.28775251, 0.081189424 0.073296696 -0.28746498, 0.081200272 0.073273793 -0.28750673, 0.081169754 0.073612839 -0.28767538, 0.081159413 0.073970973 -0.28779894, 0.081191659 0.073596954 -0.28771645, 0.081181347 0.073959291 -0.28784138, 0.081213355 0.073949382 -0.28787741, 0.081222147 0.073254079 -0.28754562, 0.081223607 0.073584199 -0.2877515, 0.081253409 0.073941991 -0.28790483, 0.081254065 0.073238477 -0.28757942, 0.081263661 0.073575258 -0.28777856, 0.081299335 0.073937207 -0.28792191, 0.081293732 0.073228255 -0.28760579, 0.081309348 0.073570877 -0.2877959, 0.081348181 0.073935628 -0.28792781, 0.13737138 0.11773965 -0.20569257, 0.13732266 0.11774261 -0.20570055, 0.13732032 0.11775166 -0.20568205, 0.1373689 0.11774898 -0.20567407, 0.13741441 0.11773559 -0.20566098, 0.13741694 0.11772585 -0.20568003, 0.13745438 0.11771226 -0.20564367, 0.13745694 0.11770219 -0.20566405, 0.13748609 0.11768043 -0.20562328, 0.13748871 0.11766958 -0.20564522, 0.13750772 0.11764222 -0.20560099, 0.13751064 0.1176306 -0.20562448, 0.13751802 0.11759971 -0.20557845, 0.13752107 0.11758715 -0.2056035, 0.12010004 0.11892582 -0.20779312, 0.13621397 0.11983344 -0.20597742, 0.13620839 0.11985753 -0.20594049, 0.12009455 0.11894967 -0.20775628, 0.13620326 0.11988901 -0.20590973, 0.12008932 0.11898127 -0.20772554, 0.13619846 0.11992665 -0.20588699, 0.12008457 0.11901884 -0.20770258, 0.13619456 0.1199684 -0.20587265, 0.12008071 0.11906075 -0.20768835, 0.13619147 0.12001252 -0.20586802, 0.12007776 0.11910465 -0.2076837, 0.10315113 0.081757337 -0.27273858, 0.10316892 0.08171612 -0.27282524, 0.10322817 0.081847668 -0.27275974, 0.10324867 0.081798613 -0.27286017, 0.10330144 0.081727639 -0.27315867, 0.10324569 0.081743658 -0.27297461, 0.10321139 0.081686229 -0.27309608, 0.10334735 0.081862479 -0.27288437, 0.10334291 0.081796646 -0.27301788, 0.1030824 0.081407636 -0.27267754, 0.10306926 0.081547201 -0.27265906, 0.10306935 0.081439286 -0.27260518, 0.10305376 0.081458628 -0.2725637, 0.10303269 0.081585258 -0.27257925, 0.10305785 0.081696481 -0.27261925, 0.10309719 0.081655234 -0.27270436, 0.10311259 0.081619978 -0.27278137, 0.10316677 0.081670344 -0.2729243, 0.10313772 0.081622928 -0.27303004, 0.10308322 0.081515089 -0.27273124, 0.1031106 0.081581146 -0.27286994, 0.10308467 0.08154127 -0.2729646, 0.10356401 0.081816286 -0.27310276, 0.10340323 0.081745088 -0.27321476, 0.10351087 0.081737399 -0.27326113, 0.10308032 0.081480533 -0.27281427, 0.1030551 0.081445664 -0.27290308, 0.10307793 0.081374079 -0.27276075, 0.10303314 0.081477225 -0.27252519, 0.10305052 0.081341654 -0.27284896, 0.10336131 0.082048938 -0.27260527, 0.10343255 0.081972241 -0.27275884, 0.1034659 0.082088202 -0.27255929, 0.10354809 0.081998795 -0.2727381, 0.10326295 0.081985861 -0.27263534, 0.10332398 0.081920773 -0.27276671, 0.10345919 0.081903636 -0.27289641, 0.10358007 0.081900537 -0.27293468, 0.10317631 0.081902683 -0.2726481, 0.10345285 0.081826121 -0.27305162, 0.1031066 0.081804365 -0.27264273, 0.10268085 0.08184579 -0.27242607, 0.10268082 0.081955552 -0.27241385, 0.093842238 0.081845686 -0.27242613, 0.093842357 0.081955478 -0.27241385, 0.10268079 0.082060069 -0.27237785, 0.093842238 0.082059905 -0.27237785, 0.10268088 0.082153976 -0.27231967, 0.093842238 0.082153842 -0.27231967, 0.10268079 0.082232922 -0.27224249, 0.093842208 0.082232848 -0.27224252, 0.10268085 0.082292825 -0.27214956, 0.093842238 0.082292721 -0.27214956, 0.092511654 0.077023804 -0.27763271, 0.092512026 0.077116922 -0.2776238, 0.091949478 0.077023819 -0.27763262, 0.091949567 0.077133521 -0.27762049, 0.092515364 0.077206925 -0.27759781, 0.091949567 0.077238008 -0.27758452, 0.092523575 0.077290237 -0.2775557, 0.091949448 0.077331945 -0.27752632, 0.092538074 0.077363148 -0.27749971, 0.091949478 0.077411011 -0.27744904, 0.09255977 0.077423945 -0.27743235, 0.091949478 0.077470973 -0.27735618, 0.092588678 0.077470973 -0.27735639, 0.099793747 0.078745186 -0.27862811, 0.099793792 0.078855023 -0.27861583, 0.098494411 0.078745231 -0.27862799, 0.098494411 0.078855023 -0.27861583, 0.099793866 0.078959405 -0.27857989, 0.098494411 0.07895945 -0.27857983, 0.099793866 0.079053402 -0.27852172, 0.098494411 0.079053387 -0.27852166, 0.099793792 0.079132423 -0.27844441, 0.09849444 0.079132274 -0.27844447, 0.099793792 0.079192266 -0.27835166, 0.098494411 0.079192385 -0.27835166, 0.096939698 0.077713251 -0.27734208, 0.096919537 0.077668294 -0.2774502, 0.098116368 0.079072431 -0.27812806, 0.098096132 0.079027399 -0.27823615, 0.096921578 0.077607393 -0.27755213, 0.098098278 0.078966722 -0.27833807, 0.096946239 0.077534065 -0.27764213, 0.098122835 0.07889317 -0.2784282, 0.096991777 0.077452287 -0.27771533, 0.098168373 0.078811511 -0.27850127, 0.097055674 0.077366814 -0.27776742, 0.098232269 0.078726158 -0.27855334, 0.097134352 0.077282414 -0.27779555, 0.098311022 0.078641593 -0.2785815, 0.097223401 0.077203974 -0.27779806, 0.098399967 0.078563169 -0.27858403, 0.098494411 0.078494892 -0.278561, 0.097317815 0.077135608 -0.27777499, 0.096447825 0.077023968 -0.27763271, 0.096447766 0.077133581 -0.27762055, 0.095011443 0.077023789 -0.27763277, 0.09501031 0.077145383 -0.27761751, 0.096447825 0.077238068 -0.27758452, 0.09500429 0.077248856 -0.27757919, 0.096447676 0.077332094 -0.27752638, 0.094993234 0.077327445 -0.27752987, 0.094976395 0.077391073 -0.27747172, 0.096447781 0.077410996 -0.27744889, 0.094957709 0.07743533 -0.27741638, 0.096447825 0.077471003 -0.27735639, 0.094934344 0.077471033 -0.27735636, 0.079995304 0.076675221 -0.29168743, 0.094813094 0.076675311 -0.29168743, 0.079996169 0.076712683 -0.291686, 0.079998672 0.076749995 -0.29168186, 0.094826683 0.076766625 -0.29167908, 0.080006838 0.076812267 -0.29166836, 0.080020189 0.076870456 -0.2916477, 0.094847724 0.07685788 -0.2916528, 0.080038935 0.076924607 -0.29162097, 0.09488003 0.076956347 -0.29160094, 0.080085963 0.077009067 -0.29155964, 0.080114722 0.077046052 -0.29152289, 0.094923541 0.077048734 -0.29151988, 0.080144495 0.077079162 -0.29148227, 0.094976351 0.077122524 -0.29141104, 0.080192864 0.077122554 -0.2914111, 0.13685749 0.11691914 -0.20427549, 0.13686249 0.11795603 -0.20484424, 0.13669179 0.11797331 -0.20480287, 0.13662849 0.1169195 -0.20424557, 0.13652419 0.11797707 -0.20478916, 0.13759975 0.11641036 -0.20536822, 0.1371232 0.12068473 -0.20773435, 0.13718532 0.12078679 -0.20754279, 0.13755094 0.11633931 -0.20550191, 0.13729841 0.11975725 -0.20661679, 0.1371976 0.12088799 -0.20734586, 0.13717578 0.12095892 -0.2072034, 0.13762389 0.11648189 -0.20523083, 0.13723393 0.11985037 -0.20642887, 0.13712676 0.12102827 -0.20706062, 0.13705112 0.12109253 -0.2069249, 0.13761884 0.11657375 -0.20504965, 0.13711771 0.1199386 -0.20624876, 0.13757263 0.11666165 -0.20487142, 0.13746367 0.11769855 -0.20537962, 0.13684593 0.12118995 -0.20670582, 0.13695331 0.12001356 -0.20609336, 0.13671325 0.12122595 -0.20661749, 0.13748525 0.11674248 -0.20470142, 0.13735245 0.11779356 -0.20518638, 0.13736688 0.11680888 -0.20455611, 0.13720553 0.11786777 -0.20503284, 0.13675258 0.12006824 -0.20597643, 0.1365796 0.12124895 -0.20655406, 0.13721286 0.11686347 -0.20442951, 0.13704297 0.1179202 -0.20492214, 0.13653331 0.12009925 -0.20590653, 0.13643706 0.12126245 -0.2065089, 0.13632506 0.12126555 -0.20648739, 0.13704138 0.11689995 -0.20433635, 0.13631472 0.12010668 -0.20588326, 0.13620099 0.1212623 -0.20647693, 0.13618882 0.12010118 -0.20588939, 0.13607566 0.121252 -0.20648064, 0.093761563 0.083128989 -0.28430176, 0.09309262 0.082942367 -0.28355712, 0.093761563 0.082905352 -0.28363097, 0.092971206 0.083172619 -0.28421462, 0.092228115 0.083300933 -0.2839579, 0.09246406 0.083050862 -0.28333995, 0.091913283 0.08322452 -0.2829926, 0.091577336 0.083506197 -0.28354728, 0.091473579 0.083452746 -0.28253591, 0.091057599 0.083776042 -0.28300768, 0.091171205 0.083722219 -0.2819972, 0.090700209 0.084094271 -0.28237104, 0.091024339 0.084016189 -0.28140891, 0.090526685 0.08444187 -0.28167576, 0.091041848 0.084317476 -0.28080636, 0.090547383 0.084797964 -0.28096366, 0.091222867 0.08460775 -0.28022575, 0.090761155 0.085140958 -0.28027728, 0.099400759 -0.015835673 -0.24062291, 0.098616034 -0.015752435 -0.24067116, 0.099400684 -0.015152425 -0.24044038, 0.098736614 -0.015081927 -0.24048111, 0.097877711 -0.015507489 -0.24081254, 0.098111957 -0.014874846 -0.24060082, 0.097229451 -0.015115649 -0.24103916, 0.097563535 -0.014543265 -0.24079265, 0.096709877 -0.01459989 -0.24133742, 0.097123742 -0.01410687 -0.24104491, 0.096349329 -0.01399079 -0.24168982, 0.096818775 -0.013591468 -0.2413429, 0.096169472 -0.013324395 -0.24207509, 0.096666574 -0.013027579 -0.24166909, 0.089674652 0.067275852 -0.2863723, 0.089674652 0.066525072 -0.28767097, 0.090057552 0.067235678 -0.28634894, 0.090057582 0.06648469 -0.28764749, 0.090418324 0.067117229 -0.28628054, 0.090418279 0.066366404 -0.28757906, 0.090735629 0.066927537 -0.28617087, 0.090735614 0.066176742 -0.28746951, 0.090991437 0.06667766 -0.28602636, 0.090991452 0.065926656 -0.28732482, 0.091170728 0.066382021 -0.28585547, 0.091170728 0.065631121 -0.28715396, 0.091263115 0.066057771 -0.28566813, 0.091262996 0.065306753 -0.28696656, 0.091262996 0.065723866 -0.2854749, 0.091262996 0.064972967 -0.28677332, 0.091170728 0.065399617 -0.28528738, 0.091170728 0.064648718 -0.28658593, 0.090991437 0.065103978 -0.28511643, 0.090991497 0.064352959 -0.2864151, 0.090735734 0.0648541 -0.28497207, 0.090735614 0.064103156 -0.28627044, 0.090418249 0.064664349 -0.28486219, 0.09041816 0.06391342 -0.28616071, 0.090057552 0.064545885 -0.28479379, 0.090057552 0.063795045 -0.28609216, 0.089674681 0.063754782 -0.28606889, 0.089674652 0.064505532 -0.28477049, 0.099400714 -0.010635883 -0.24131931, 0.099400595 -0.011386663 -0.24261798, 0.099783614 -0.010676116 -0.24129613, 0.099783644 -0.011426926 -0.24259464, 0.10014418 -0.010794491 -0.24122766, 0.10014418 -0.011545315 -0.24252611, 0.10046168 -0.010984227 -0.24111806, 0.10046168 -0.011735111 -0.24241652, 0.10071743 -0.011234015 -0.24097349, 0.10071735 -0.011985019 -0.24227203, 0.10089663 -0.011529729 -0.24080242, 0.10089667 -0.012280613 -0.24210109, 0.10098898 -0.011853918 -0.24061486, 0.10098894 -0.012604862 -0.24191357, 0.10098894 -0.012187868 -0.24042177, 0.10098903 -0.012938708 -0.24172047, 0.10089655 -0.012512028 -0.24023449, 0.10089667 -0.013263017 -0.24153292, 0.10071738 -0.012807757 -0.24006343, 0.10071741 -0.013558626 -0.24136195, 0.10046168 -0.013057768 -0.23991883, 0.10046156 -0.013808548 -0.24121737, 0.10014422 -0.013247401 -0.23980927, 0.10014422 -0.013998181 -0.2411077, 0.099783614 -0.013365716 -0.23974091, 0.09978357 -0.014116645 -0.24103928, 0.099400565 -0.013405979 -0.23971733, 0.099400759 -0.014156967 -0.24101606, 0.09059687 0.071075395 -0.2840797, 0.090614945 0.071107954 -0.28417051, 0.089674622 0.071206778 -0.28422761, 0.089674622 0.071258396 -0.28431094, 0.090635687 0.071157426 -0.28425241, 0.091629773 0.064538077 -0.28046882, 0.090658128 0.064313635 -0.28032789, 0.090681449 0.064226925 -0.28028882, 0.090658039 0.071222097 -0.28432274, 0.091540873 0.070860386 -0.28408068, 0.091584474 0.070917934 -0.2841469, 0.091584474 0.064617708 -0.28050363, 0.089674622 0.064210251 -0.28026807, 0.091465563 0.064882532 -0.28049874, 0.09150067 0.064793304 -0.28051901, 0.092229992 0.065339401 -0.28076303, 0.091629773 0.07098791 -0.2841984, 0.092399865 0.070430726 -0.28386521, 0.092464522 0.070489183 -0.28391007, 0.092280298 0.065259054 -0.28078842, 0.092337638 0.065180019 -0.28079605, 0.091540962 0.064703897 -0.28052068, 0.090635687 0.064406708 -0.2803489, 0.089674652 0.064305648 -0.28029022, 0.091465533 0.070790172 -0.2839148, 0.09150067 0.070817202 -0.28400218, 0.090614945 0.064502433 -0.28035092, 0.089674622 0.064403728 -0.2802937, 0.089674711 0.064500377 -0.28027776, 0.090596899 0.064597279 -0.28033388, 0.092337638 0.070384234 -0.28380537, 0.093056709 0.069788784 -0.283494, 0.093137056 0.069831938 -0.28352988, 0.089674711 0.071172297 -0.28413588, 0.092229992 0.070333451 -0.28365088, 0.092280298 0.070351332 -0.28373301, 0.09297958 0.069756955 -0.28344262, 0.093517274 0.069029421 -0.28305477, 0.093608409 0.069054574 -0.28308034, 0.092846066 0.069731444 -0.28330266, 0.092908531 0.069737524 -0.28337801, 0.093429476 0.069014877 -0.28301346, 0.093754202 0.068196625 -0.28257322, 0.093851089 0.068201959 -0.28258747, 0.093277842 0.069019407 -0.28289092, 0.093348652 0.069011539 -0.28295827, 0.093661159 0.068201154 -0.282543, 0.093754232 0.067339033 -0.28207731, 0.093851209 0.067323953 -0.2820797, 0.093575269 0.068215221 -0.28249764, 0.093500048 0.068238348 -0.28243935, 0.093661174 0.067363128 -0.2820583, 0.093517154 0.066506386 -0.28159583, 0.093608439 0.066471547 -0.28158677, 0.093500048 0.067434162 -0.28197432, 0.093575388 0.0673953 -0.28202355, 0.093429506 0.066549391 -0.28158772, 0.093056768 0.065746918 -0.28115666, 0.093137145 0.065694109 -0.28113723, 0.093277603 0.066653579 -0.28152287, 0.093348652 0.066598982 -0.28156316, 0.089674681 0.064121023 -0.28022754, 0.09297958 0.065807298 -0.2811588, 0.092399761 0.065105051 -0.28078556, 0.092464536 0.065037027 -0.28075719, 0.092908472 0.065872923 -0.28114319, 0.092846066 0.065941289 -0.281111, 0.089674622 0.071325392 -0.28438246, 0.089674622 0.071405023 -0.28443968, 0.090681463 0.071299165 -0.28437841, 0.088118806 0.067829669 -0.28007305, 0.087907165 0.068179026 -0.28027499, 0.087819353 0.068136036 -0.28028297, 0.088712364 0.070309237 -0.28159297, 0.089179054 0.07046254 -0.28168145, 0.088677078 0.070336297 -0.28168046, 0.089179188 0.066981629 -0.27966869, 0.089160949 0.066886738 -0.27968574, 0.089674577 0.06683287 -0.27965456, 0.089674652 0.066929504 -0.27963871, 0.089199811 0.070412964 -0.28159952, 0.089674622 0.070462912 -0.28162837, 0.089674622 0.07051453 -0.2817117, 0.08871232 0.067134827 -0.27975732, 0.088752538 0.067224219 -0.27975568, 0.088301554 0.06738025 -0.27989924, 0.088301569 0.070063785 -0.28145111, 0.088251263 0.070081785 -0.28153336, 0.087908179 0.06974645 -0.28133941, 0.088358909 0.067459419 -0.27989161, 0.088421032 0.067534477 -0.27990228, 0.088841468 0.067389801 -0.27980745, 0.088485748 0.067602471 -0.27993047, 0.088041618 0.067769349 -0.28007108, 0.088752523 0.070266187 -0.28151476, 0.089199781 0.067077324 -0.27967089, 0.089674622 0.067027405 -0.27964187, 0.089222208 0.070348337 -0.28152931, 0.088841498 0.070138559 -0.28139684, 0.089245573 0.070271194 -0.2814737, 0.089674681 0.070395857 -0.28155684, 0.088796154 0.067310274 -0.27977264, 0.089245647 0.067257181 -0.2797308, 0.087970525 0.06974037 -0.28126407, 0.087667733 0.06934984 -0.28111005, 0.089222208 0.067170441 -0.27969182, 0.089674622 0.067122892 -0.27966416, 0.089674622 0.06721206 -0.27970481, 0.088358909 0.070030883 -0.28137863, 0.088796064 0.07020852 -0.28144848, 0.088485733 0.069925964 -0.28127396, 0.089674652 0.070316315 -0.28149974, 0.087738425 0.069357708 -0.2810427, 0.08754386 0.06891495 -0.28085864, 0.088041678 0.069720924 -0.28119946, 0.088421091 0.069984287 -0.28131884, 0.088199079 0.069646046 -0.28111205, 0.087619096 0.068938091 -0.28080022, 0.08754386 0.068466842 -0.28059936, 0.087819248 0.069354251 -0.2809875, 0.088118821 0.06968911 -0.2811482, 0.08799836 0.069314614 -0.28092051, 0.087619096 0.068505958 -0.28055024, 0.087667719 0.068031967 -0.28034806, 0.087704927 0.068952277 -0.28075492, 0.087906986 0.069339588 -0.28094614, 0.087894812 0.068951309 -0.28071034, 0.087738514 0.06808643 -0.28030756, 0.087908179 0.067635372 -0.2801187, 0.087704927 0.068538025 -0.28051543, 0.087798029 0.068956688 -0.28072464, 0.087894842 0.068577141 -0.28049397, 0.08797051 0.067703664 -0.28008628, 0.088251263 0.067300037 -0.27992475, 0.087798014 0.06856209 -0.28049648, 0.087998301 0.068213776 -0.28028393, 0.088677078 0.067045644 -0.27977765, 0.088199168 0.067882493 -0.28009224, 0.089160889 0.070495039 -0.28177214, 0.089674622 0.070549101 -0.28180349, 0.10119145 -0.013029233 -0.23544587, 0.10122676 -0.013118401 -0.23546611, 0.10200627 -0.012652546 -0.23573537, 0.10206361 -0.012731716 -0.23574309, 0.10126686 -0.013207778 -0.23546752, 0.10032284 -0.0068362802 -0.23902677, 0.10034098 -0.0068037063 -0.2391175, 0.099400684 -0.0067049414 -0.23917472, 0.099400565 -0.0066532046 -0.23925793, 0.10036157 -0.0067542642 -0.23919949, 0.099400669 -0.013701394 -0.23521507, 0.10036166 -0.013504997 -0.23529594, 0.099400714 -0.013605967 -0.23523746, 0.10038412 -0.006689623 -0.23926984, 0.10126694 -0.0070513487 -0.23902771, 0.10131045 -0.0069936663 -0.23909378, 0.10038419 -0.01359801 -0.2352749, 0.10131048 -0.013293996 -0.23545076, 0.10135582 -0.0069237351 -0.2391455, 0.10212576 -0.00748083 -0.23881222, 0.10219038 -0.0074224174 -0.23885705, 0.099400669 -0.013508037 -0.2352407, 0.10034104 -0.013409153 -0.2352979, 0.10032283 -0.013314366 -0.23528098, 0.10195597 -0.0075782537 -0.23859784, 0.10122664 -0.0070945024 -0.23894951, 0.10119148 -0.0071214586 -0.23886192, 0.10206358 -0.007527411 -0.23875248, 0.10278268 -0.0081228167 -0.23844099, 0.102863 -0.0080796331 -0.23847714, 0.10257204 -0.0081802756 -0.23824966, 0.10200627 -0.0075603873 -0.23868001, 0.09940058 -0.0067393929 -0.23908295, 0.10270561 -0.0081547052 -0.23838961, 0.10324311 -0.0088822693 -0.23800181, 0.10333435 -0.0088571161 -0.23802748, 0.10300379 -0.0088924021 -0.23783788, 0.10263439 -0.0081740767 -0.238325, 0.10315546 -0.0088968426 -0.23796053, 0.10348022 -0.0097150356 -0.2375202, 0.10357706 -0.0097095817 -0.23753455, 0.10322607 -0.0096731037 -0.23738633, 0.1030746 -0.0089002103 -0.23790523, 0.1033871 -0.0097105354 -0.23749003, 0.10348025 -0.010572627 -0.23702432, 0.10357709 -0.010587588 -0.23702675, 0.10322616 -0.010477424 -0.2369214, 0.10330121 -0.0096963495 -0.23744479, 0.10338712 -0.010548592 -0.23700529, 0.10324319 -0.011405393 -0.23654281, 0.10333438 -0.011440024 -0.23653387, 0.10330123 -0.01051639 -0.23697057, 0.10300379 -0.011258259 -0.23646976, 0.10315551 -0.01136227 -0.23653482, 0.10278274 -0.012164786 -0.2361037, 0.10286306 -0.012217566 -0.23608442, 0.10307463 -0.011312649 -0.23651014, 0.10257204 -0.011970416 -0.23605798, 0.10270549 -0.012104347 -0.2361059, 0.1004075 -0.013684958 -0.23523577, 0.099400744 -0.013790712 -0.23517467, 0.10212584 -0.012806788 -0.23573248, 0.10219051 -0.012874812 -0.23570426, 0.10195599 -0.012572303 -0.23570986, 0.10263442 -0.012038752 -0.23609032, 0.10135575 -0.01337342 -0.2354158, 0.099400595 -0.013411313 -0.23522492, 0.099400565 -0.0065862089 -0.23932958, 0.09940061 -0.0065066367 -0.23938678, 0.10040744 -0.006612435 -0.23932552, 0.098925754 -0.0074987561 -0.23654674, 0.099400565 -0.0073970705 -0.2366588, 0.098905012 -0.0074491948 -0.23662864, 0.098027512 -0.0078479499 -0.23639809, 0.098403141 -0.0075755566 -0.23662744, 0.097977206 -0.0078299195 -0.23648034, 0.098084912 -0.010452375 -0.23483859, 0.097696468 -0.010207921 -0.23503335, 0.098027512 -0.010531455 -0.23484631, 0.098438308 -0.0076023787 -0.23654, 0.097767606 -0.010142311 -0.23501797, 0.097844794 -0.010081872 -0.23502, 0.097925141 -0.010029212 -0.23503937, 0.097724274 -0.009697929 -0.23523106, 0.097633049 -0.0097326189 -0.23522197, 0.097545251 -0.0097755939 -0.23522995, 0.098478481 -0.0076455325 -0.23646162, 0.098905087 -0.010930136 -0.23461568, 0.098886952 -0.011024907 -0.23463289, 0.099400565 -0.011078849 -0.2346016, 0.098948166 -0.0075632632 -0.2364765, 0.098971531 -0.0076405108 -0.23642071, 0.09940064 -0.0075953901 -0.23644683, 0.098403171 -0.01086615 -0.23472466, 0.099400565 -0.010982171 -0.23458575, 0.09940061 -0.0075157732 -0.23650393, 0.09940064 -0.0074487478 -0.23657548, 0.098438233 -0.010776743 -0.23470435, 0.097696468 -0.0081713647 -0.23621117, 0.097634181 -0.0081652105 -0.23628648, 0.098478481 -0.010687515 -0.23470281, 0.098147109 -0.010377288 -0.23484932, 0.098211691 -0.010309234 -0.23487733, 0.098084852 -0.0078807622 -0.23632567, 0.098925754 -0.010834292 -0.23461787, 0.099400565 -0.01088421 -0.23458903, 0.098522052 -0.0077031404 -0.23639552, 0.098567411 -0.0077732056 -0.23634396, 0.098521993 -0.010601297 -0.23471968, 0.098567382 -0.010521784 -0.2347547, 0.097464457 -0.0085539669 -0.2359897, 0.097393677 -0.0085618645 -0.23605703, 0.098948166 -0.010741279 -0.2346388, 0.099400565 -0.010788724 -0.23461126, 0.098971531 -0.010654494 -0.2346779, 0.097767636 -0.0081906468 -0.23614655, 0.09814702 -0.0079272836 -0.23626588, 0.09821175 -0.0079856664 -0.23622112, 0.097345069 -0.0089735985 -0.2357472, 0.097269818 -0.0089967698 -0.2358055, 0.097545311 -0.0085574538 -0.23593436, 0.097844735 -0.0082225651 -0.23609509, 0.097925112 -0.0082658827 -0.23605914, 0.097345039 -0.009405762 -0.23549731, 0.097269818 -0.0094447285 -0.23554645, 0.0974309 -0.0089595467 -0.23570205, 0.09763293 -0.0085718781 -0.23589312, 0.097724244 -0.0085971504 -0.2358676, 0.097464487 -0.0098253638 -0.23525463, 0.097393706 -0.0098797083 -0.23529516, 0.09743087 -0.0093735754 -0.2354625, 0.097523972 -0.0089550167 -0.23567162, 0.09762077 -0.0089603812 -0.23565744, 0.097634122 -0.010276288 -0.23506565, 0.097524002 -0.0093495995 -0.23544349, 0.097620755 -0.0093344748 -0.23544103, 0.097977266 -0.010611624 -0.23487182, 0.099400595 -0.010699511 -0.23465173, 0.099400684 -0.0073626488 -0.23675047, 0.098886922 -0.0074166507 -0.23671938, 0.09940064 -0.0099934191 -0.23950943, 0.09969984 -0.01002492 -0.23949124, 0.09940061 -0.0080653131 -0.236175, 0.099699721 -0.0080966502 -0.23615687, 0.099981502 -0.010117427 -0.23943768, 0.099981472 -0.0081893653 -0.23610328, 0.10022953 -0.010265544 -0.23935199, 0.10022946 -0.0083374828 -0.23601772, 0.10042937 -0.010460898 -0.23923896, 0.10042922 -0.008532688 -0.23590468, 0.10056947 -0.010691866 -0.2391056, 0.10056941 -0.008763805 -0.23577116, 0.10064149 -0.010945067 -0.23895893, 0.10064161 -0.0090170652 -0.23562467, 0.10064146 -0.011205941 -0.23880824, 0.10064153 -0.0092778504 -0.23547383, 0.10056938 -0.011459187 -0.23866163, 0.10056938 -0.0095311552 -0.23532738, 0.10042937 -0.011690289 -0.23852821, 0.10042933 -0.0097620785 -0.23519391, 0.10022958 -0.011885539 -0.23841523, 0.10022947 -0.0099574178 -0.23508081, 0.099981532 -0.012033656 -0.23832954, 0.099981591 -0.010105625 -0.23499523, 0.09969984 -0.012126222 -0.23827614, 0.099699691 -0.010198116 -0.23494177, 0.099400625 -0.012157664 -0.2382579, 0.099400654 -0.010229468 -0.23492371, 0.089674652 0.067918301 -0.28456241, 0.089973837 0.0678868 -0.28454411, 0.089674622 0.069846347 -0.28122795, 0.089973748 0.069814906 -0.28120992, 0.090255529 0.067794293 -0.2844907, 0.090255558 0.069722414 -0.28115636, 0.090503603 0.067646116 -0.28440511, 0.090503484 0.069574326 -0.28107059, 0.090703443 0.067450777 -0.28429213, 0.090703398 0.069379002 -0.28095776, 0.090843439 0.067219794 -0.28415853, 0.090843469 0.069148019 -0.28082418, 0.090915471 0.066966623 -0.28401196, 0.090915486 0.068894714 -0.28067756, 0.090915591 0.066705674 -0.28386104, 0.090915486 0.068633765 -0.28052682, 0.090843394 0.066452503 -0.28371465, 0.090843335 0.068380535 -0.28038025, 0.090703398 0.066221431 -0.28358114, 0.090703458 0.068149462 -0.28024673, 0.090503633 0.066026196 -0.28346822, 0.090503499 0.067954272 -0.28013396, 0.090255648 0.065877989 -0.28338253, 0.090255678 0.067805991 -0.2800481, 0.089973837 0.065785483 -0.28332901, 0.089973867 0.067713484 -0.2799947, 0.089674622 0.067682102 -0.27997649, 0.089674592 0.065754041 -0.28331098, 0.088912159 0.065157846 -0.28016508, 0.08788389 0.064882502 -0.28049871, 0.088752374 0.064597338 -0.28033382, 0.08910206 0.066305473 -0.27984273, 0.088373035 0.065923706 -0.28011489, 0.08910206 0.070648998 -0.28235435, 0.088373065 0.07060343 -0.282821, 0.088912159 0.070942253 -0.28350985, 0.088752359 0.071075469 -0.28407967, 0.08788386 0.070790142 -0.2839148, 0.087119251 0.065339401 -0.28076279, 0.087329134 0.066644341 -0.28053159, 0.086071581 0.066653386 -0.28152287, 0.086503267 0.065941259 -0.28111103, 0.086749822 0.067685679 -0.28113377, 0.085849255 0.068238392 -0.28243938, 0.085849181 0.067434251 -0.28197432, 0.086749852 0.068841562 -0.28180206, 0.086071521 0.069019273 -0.2828908, 0.087329149 0.069882795 -0.28240427, 0.087119281 0.070333362 -0.28365082, 0.086503237 0.06973137 -0.28330272, 0.098098978 -0.0073080808 -0.23776798, 0.097609714 -0.0071214288 -0.23886187, 0.096845344 -0.0075783581 -0.23859777, 0.097055122 -0.0080287606 -0.23735116, 0.098828062 -0.011606187 -0.23478968, 0.098098919 -0.011987939 -0.23506187, 0.098638088 -0.0127538 -0.23511207, 0.097609892 -0.013029203 -0.23544572, 0.098478392 -0.013314411 -0.23528086, 0.098828018 -0.0072626024 -0.23730135, 0.098638102 -0.006969586 -0.23845685, 0.098478362 -0.00683631 -0.23902678, 0.096845239 -0.012572378 -0.2357101, 0.097055003 -0.011267349 -0.23547874, 0.095797509 -0.011258259 -0.23646986, 0.096229106 -0.011970431 -0.236058, 0.096475884 -0.010226026 -0.23608075, 0.095575184 -0.0096731931 -0.23738639, 0.095575154 -0.010477424 -0.23692146, 0.096475765 -0.0090700835 -0.23674916, 0.095797509 -0.0088924021 -0.23783787, 0.096229225 -0.0081802756 -0.23824964, 0.12367465 0.11017136 -0.21199772, 0.12335745 0.11033148 -0.21167745, 0.12328634 0.11035073 -0.21174194, 0.12402818 0.1116966 -0.20904993, 0.12449493 0.11177592 -0.2088916, 0.12447681 0.11186437 -0.20885357, 0.12343468 0.11032991 -0.21161708, 0.12351502 0.110346 -0.21156323, 0.12322286 0.11051029 -0.21125613, 0.12380162 0.11020142 -0.21185265, 0.12451567 0.11169712 -0.20894596, 0.12499049 0.11172277 -0.20889448, 0.12499043 0.11180282 -0.20883776, 0.12313507 0.11052097 -0.21129861, 0.12449491 0.10997775 -0.21248813, 0.12399305 0.11008255 -0.2124176, 0.12447681 0.11000054 -0.21258187, 0.12402812 0.11005694 -0.21232991, 0.12361729 0.11156991 -0.20930351, 0.12399293 0.11178236 -0.20901772, 0.12356701 0.111651 -0.2092806, 0.12499046 0.10995105 -0.21254183, 0.12406823 0.11004984 -0.21224062, 0.12361731 0.11018376 -0.21207616, 0.12373687 0.1101772 -0.21192214, 0.12415722 0.11009163 -0.21207236, 0.12406825 0.11162128 -0.20909774, 0.12453809 0.11163086 -0.20901464, 0.12415734 0.11151141 -0.2092322, 0.12456141 0.11157991 -0.20909515, 0.12499048 0.1116554 -0.20896551, 0.12451555 0.10997395 -0.21239242, 0.12499043 0.10994828 -0.21244408, 0.12328631 0.11140284 -0.20963781, 0.12322389 0.11147775 -0.20962715, 0.12411188 0.11006154 -0.21215391, 0.12456134 0.11002308 -0.21220936, 0.12367465 0.11149971 -0.20934078, 0.12453809 0.10998935 -0.21229829, 0.12499048 0.10996477 -0.21234736, 0.12411186 0.11155856 -0.20915927, 0.1238016 0.1114016 -0.20945188, 0.12499037 0.11160326 -0.20904858, 0.12305436 0.1112051 -0.21003316, 0.12298344 0.11127283 -0.21003699, 0.1233574 0.11133958 -0.20966113, 0.12373695 0.1114428 -0.20939086, 0.12351486 0.11125696 -0.2097411, 0.12293494 0.11098841 -0.21046664, 0.12285972 0.11104813 -0.21048628, 0.12313516 0.11115013 -0.21003985, 0.12343466 0.11129025 -0.20969595, 0.12331404 0.1110857 -0.21008357, 0.12293488 0.11076525 -0.21091302, 0.12285966 0.11081675 -0.21094908, 0.12302062 0.11094248 -0.21045531, 0.12322284 0.11110978 -0.21005687, 0.12321061 0.11089811 -0.21045892, 0.1230544 0.11054854 -0.21134663, 0.12298347 0.11059217 -0.21139857, 0.12302059 0.11072859 -0.21088316, 0.12311375 0.11091188 -0.21045263, 0.12321068 0.11070482 -0.21084544, 0.12322393 0.11038715 -0.21180831, 0.12499049 0.10997266 -0.21263753, 0.12311372 0.11070824 -0.2108603, 0.12331405 0.1105172 -0.21122088, 0.12356707 0.11021399 -0.21215488, 0.12499049 0.10999972 -0.21225597, 0.12499045 0.11189236 -0.20879784, 0.12499046 0.11076073 -0.21512151, 0.1259308 0.11080903 -0.21492125, 0.12499042 0.11075795 -0.21502341, 0.12499046 0.11073618 -0.21492788, 0.12591267 0.11078624 -0.21482766, 0.12678134 0.11093359 -0.214533, 0.12595156 0.1142998 -0.20804204, 0.12681641 0.11407083 -0.2083969, 0.12685664 0.11414635 -0.20834909, 0.12595142 0.11081284 -0.2150171, 0.12681651 0.11095922 -0.21462071, 0.1268567 0.11096638 -0.21470998, 0.12678124 0.11398512 -0.20842896, 0.12591265 0.11413239 -0.20813447, 0.12593077 0.11422096 -0.20809644, 0.12690033 0.11420888 -0.20828746, 0.12765329 0.11390039 -0.20884098, 0.1277156 0.11395735 -0.20879088, 0.12845279 0.11365908 -0.20940875, 0.12837256 0.11362559 -0.20945416, 0.12892409 0.11325753 -0.21021213, 0.12754583 0.11374931 -0.20890114, 0.12759604 0.11383027 -0.20887814, 0.12829544 0.11357635 -0.20948897, 0.12883289 0.11323345 -0.2102388, 0.12916686 0.11281723 -0.21109293, 0.1281618 0.11343831 -0.20952295, 0.12822415 0.11351317 -0.20951222, 0.12874515 0.11319315 -0.21025576, 0.12907006 0.1128034 -0.21109913, 0.12916696 0.11236362 -0.21200013, 0.12859358 0.11307043 -0.21025883, 0.12866439 0.11313802 -0.21026264, 0.12897696 0.11277276 -0.21109663, 0.12907006 0.11236018 -0.21198522, 0.12892427 0.11192328 -0.21288098, 0.12889113 0.11272675 -0.21108519, 0.12881586 0.11266722 -0.21106568, 0.12897696 0.11233991 -0.21196236, 0.12883295 0.11193019 -0.21284579, 0.12845279 0.11152178 -0.21368422, 0.1288159 0.11225182 -0.21189664, 0.12889113 0.1123032 -0.21193241, 0.12874521 0.11191958 -0.21280323, 0.12837256 0.11153787 -0.21363033, 0.12778021 0.11118215 -0.2143632, 0.12859358 0.11184829 -0.21270333, 0.12866439 0.11189193 -0.21275519, 0.12829532 0.11153632 -0.21357001, 0.1259973 0.11076383 -0.21520028, 0.12499046 0.11074416 -0.21521804, 0.12499048 0.11070913 -0.21530961, 0.12771559 0.11120634 -0.21429348, 0.1269456 0.11092463 -0.21487851, 0.12816179 0.11148052 -0.21343908, 0.12822427 0.11151689 -0.2135054, 0.12765332 0.11121225 -0.21421795, 0.1269003 0.11095455 -0.21479689, 0.12754579 0.11116958 -0.21406107, 0.12759602 0.1111999 -0.21413955, 0.12499049 0.11441949 -0.20786645, 0.12597384 0.11436607 -0.20797324, 0.12499043 0.11447164 -0.20778351, 0.12599729 0.11441694 -0.20789284, 0.12694563 0.11425608 -0.20821463, 0.12499045 0.11435197 -0.20793778, 0.12778018 0.11399856 -0.20872988, 0.12597395 0.11079758 -0.21511124, 0.12499036 0.11418261 -0.20803428, 0.12499049 0.11427203 -0.20799424, 0.1242279 0.11058372 -0.21427844, 0.12319958 0.11093359 -0.214533, 0.12406828 0.11078626 -0.21482779, 0.12441787 0.11019242 -0.21315242, 0.12368885 0.11048728 -0.21351705, 0.12441793 0.11243597 -0.20866479, 0.12368885 0.11290446 -0.20868184, 0.12422791 0.11357155 -0.20830207, 0.12406825 0.11413239 -0.20813447, 0.12319972 0.11398508 -0.2084291, 0.122435 0.11116964 -0.21406113, 0.12264499 0.11085939 -0.21277235, 0.12138727 0.11184841 -0.21270333, 0.12181896 0.11148044 -0.21343906, 0.12206566 0.11139753 -0.21169646, 0.12116501 0.11225164 -0.21189655, 0.12206569 0.11199442 -0.21050216, 0.12138739 0.1130704 -0.21025886, 0.12116505 0.1126671 -0.21106565, 0.12264498 0.11253233 -0.20942631, 0.12243499 0.11374928 -0.20890108, 0.12181899 0.11343822 -0.20952298, 0.094358087 0.076772913 -0.27871871, 0.09434247 0.080341652 -0.28051224, 0.094069213 0.076722309 -0.27881998, 0.09459044 0.080418199 -0.28035921, 0.094060659 0.080293849 -0.28060773, 0.093761593 0.076705024 -0.27885434, 0.093761563 0.080277756 -0.28064027, 0.093761504 0.081395522 -0.27840415, 0.0940606 0.081379309 -0.2784366, 0.093761474 0.077836603 -0.27662492, 0.094062924 0.077820137 -0.27665797, 0.094342411 0.081331506 -0.27853218, 0.094346523 0.077771619 -0.27675489, 0.094590366 0.081254974 -0.27868524, 0.09459579 0.077693895 -0.27691033, 0.094790339 0.081154183 -0.27888718, 0.094795436 0.077591822 -0.27711469, 0.095007747 0.077220067 -0.27782387, 0.095009893 0.076852962 -0.27760267, 0.095009655 0.07677345 -0.2775656, 0.095010757 0.076937154 -0.27762511, 0.094930291 0.081034854 -0.27912584, 0.095002413 0.080903962 -0.27938738, 0.095002413 0.080769256 -0.27965692, 0.094945163 0.077084348 -0.27809554, 0.094930291 0.080638364 -0.2799187, 0.09480986 0.076959535 -0.27834511, 0.094790176 0.08051911 -0.28015739, 0.094610095 0.076853618 -0.27855718, 0.12499045 0.11493304 -0.21132015, 0.12528956 0.11491685 -0.21135268, 0.12499045 0.11136045 -0.20953432, 0.12528956 0.11134413 -0.20956667, 0.12557139 0.11129646 -0.20966229, 0.12557139 0.11486906 -0.2114483, 0.12581934 0.11121981 -0.20981523, 0.1258194 0.11479247 -0.21160148, 0.12601924 0.11111906 -0.21001719, 0.12601912 0.11469166 -0.21180317, 0.12615922 0.11099964 -0.21025573, 0.12615916 0.1145723 -0.21204188, 0.12623134 0.11086887 -0.21051751, 0.12623131 0.11444144 -0.21230349, 0.12623142 0.11073412 -0.21078697, 0.12623133 0.11430663 -0.21257304, 0.12615922 0.11060327 -0.21104874, 0.12615924 0.11417589 -0.21283476, 0.12601909 0.110484 -0.2112873, 0.12601909 0.1140566 -0.2130734, 0.12581934 0.11038308 -0.21148905, 0.12581934 0.1139558 -0.2132753, 0.1255714 0.11030656 -0.21164225, 0.12557134 0.1138791 -0.21342829, 0.12528959 0.11025876 -0.21173777, 0.12528969 0.11383134 -0.21352385, 0.12499048 0.11024247 -0.21177027, 0.12499048 0.11381501 -0.21355627, 0.12499048 0.11687317 -0.21189885, 0.12499048 0.11838809 -0.21265607, 0.12537333 0.11685239 -0.21194047, 0.12537338 0.11836722 -0.21269776, 0.12573409 0.11830594 -0.21282005, 0.12573405 0.11679125 -0.21206285, 0.12605134 0.11820813 -0.21301615, 0.12605143 0.1166933 -0.21225867, 0.1263072 0.11807895 -0.21327426, 0.12630725 0.1165642 -0.21251699, 0.12648644 0.1179263 -0.21357991, 0.12648641 0.11641148 -0.21282251, 0.12657872 0.11775871 -0.21391475, 0.12657882 0.11624402 -0.21315743, 0.12657864 0.11758626 -0.21425976, 0.12657867 0.11607161 -0.21350236, 0.12648651 0.11741884 -0.21459487, 0.12648654 0.11590402 -0.21383739, 0.12630719 0.1172661 -0.21490026, 0.12630722 0.11575128 -0.21414304, 0.12605144 0.11713701 -0.21515848, 0.12605146 0.11562218 -0.21440119, 0.12573399 0.11703902 -0.21535443, 0.12573399 0.11552423 -0.21459712, 0.12537338 0.11697787 -0.21547674, 0.12537344 0.11546302 -0.21471955, 0.12499046 0.11695717 -0.21551844, 0.12499046 0.1154422 -0.21476099, 0.093761504 0.083335772 -0.27898279, 0.093761548 0.08485058 -0.27973998, 0.094144404 0.083314911 -0.27902439, 0.094144404 0.084829673 -0.2797817, 0.094505057 0.083253801 -0.27914679, 0.094505131 0.084768638 -0.27990401, 0.094822466 0.083155885 -0.27934268, 0.094822511 0.084670588 -0.28009999, 0.095078334 0.083026707 -0.27960098, 0.095078334 0.084541485 -0.28035831, 0.095257506 0.082874 -0.27990651, 0.095257625 0.084388778 -0.28066373, 0.095349893 0.082706511 -0.28024137, 0.095349893 0.084221289 -0.28099871, 0.095349923 0.082533985 -0.28058642, 0.095349893 0.084048793 -0.2813437, 0.095257461 0.082366601 -0.2809214, 0.095257506 0.083881304 -0.28167868, 0.095078304 0.082213789 -0.28122693, 0.095078334 0.083728597 -0.28198421, 0.094822511 0.082084715 -0.28148508, 0.094822481 0.083599582 -0.28224245, 0.094505012 0.0819868 -0.28168109, 0.094505072 0.083501637 -0.28243846, 0.094144449 0.081925571 -0.28180349, 0.094144344 0.083440483 -0.28256083, 0.093761384 0.083419681 -0.28260243, 0.093761548 0.08190468 -0.28184509, 0.10788596 0.10201533 -0.23202166, 0.11298244 0.10338725 -0.22927758, 0.10790601 0.10211788 -0.23200083, 0.11295262 0.10349953 -0.22927831, 0.10793817 0.10222611 -0.2319525, 0.11291148 0.10360597 -0.2292552, 0.10798116 0.10233431 -0.23187682, 0.11286128 0.10370049 -0.22920944, 0.10803306 0.1024358 -0.23177718, 0.11280501 0.10377797 -0.22914346, 0.10809083 0.10252468 -0.23166072, 0.11274542 0.10383438 -0.22906101, 0.10815048 0.10259745 -0.23153482, 0.11077315 0.10511583 -0.22581963, 0.11586964 0.10648766 -0.22307564, 0.1107931 0.10521851 -0.22579896, 0.11583968 0.10660003 -0.2230764, 0.11082518 0.10532677 -0.22575049, 0.11579856 0.10670638 -0.2230532, 0.1108682 0.105435 -0.22567475, 0.11574849 0.10680091 -0.22300737, 0.11092018 0.10553633 -0.22557533, 0.11569208 0.10687855 -0.22294153, 0.11097787 0.10562526 -0.22545874, 0.11563253 0.10693488 -0.22285892, 0.11103764 0.10569802 -0.22533305, 0.10211168 0.095814094 -0.24442557, 0.1072083 0.097185954 -0.24168152, 0.10213172 0.095916867 -0.24440484, 0.10717838 0.097298488 -0.24168238, 0.10216376 0.096025079 -0.24435629, 0.10713719 0.097404763 -0.2416591, 0.10220687 0.096133158 -0.24428058, 0.10708715 0.097499207 -0.2416133, 0.10225892 0.09623456 -0.24418108, 0.1070307 0.097576842 -0.24154735, 0.10231665 0.09632352 -0.24406473, 0.10697113 0.097633138 -0.241465, 0.10237625 0.096396357 -0.24393882, 0.099224567 0.092713475 -0.25062758, 0.10432117 0.09408538 -0.2478835, 0.099244624 0.092816263 -0.25060666, 0.10429135 0.094197661 -0.2478842, 0.099276543 0.092924595 -0.25055832, 0.10425015 0.094304278 -0.24786106, 0.099319771 0.093032673 -0.25048259, 0.10420009 0.094398707 -0.2478153, 0.099371672 0.093134046 -0.2503832, 0.10414365 0.094476253 -0.24774937, 0.099429399 0.093223006 -0.25026655, 0.104084 0.094532594 -0.24766698, 0.099489123 0.093295723 -0.25014085, 0.096337467 0.08961314 -0.25682944, 0.10143404 0.090984866 -0.25408545, 0.096357375 0.08971566 -0.2568087, 0.10140397 0.09109731 -0.25408623, 0.096389428 0.089824006 -0.2567603, 0.10136293 0.091203794 -0.25406295, 0.096432447 0.089932054 -0.25668436, 0.10131292 0.091298148 -0.25401723, 0.096484512 0.090033412 -0.25658506, 0.1012565 0.091375723 -0.25395134, 0.096542254 0.090122506 -0.25646856, 0.10119684 0.091432169 -0.25386873, 0.096601978 0.090195224 -0.25634271, 0.093450353 0.086512551 -0.26303148, 0.098546833 0.087884247 -0.2602874, 0.093470261 0.08661513 -0.26301062, 0.09851703 0.087996781 -0.26028812, 0.093502343 0.086723447 -0.26296222, 0.098475829 0.088103101 -0.26026493, 0.093545407 0.08683154 -0.26288635, 0.098425806 0.088197559 -0.2602191, 0.093597516 0.086932942 -0.26278698, 0.098369449 0.088275135 -0.26015317, 0.093655214 0.087021872 -0.2626704, 0.0983098 0.088331595 -0.26007068, 0.093714908 0.08709462 -0.26254481, 0.090563148 0.083411872 -0.26923358, 0.095659703 0.084783733 -0.26648939, 0.090583175 0.083514512 -0.2692126, 0.095629781 0.084896207 -0.26649016, 0.090615094 0.083622962 -0.26916409, 0.095588773 0.085002542 -0.26646703, 0.090658247 0.083730966 -0.26908827, 0.095538616 0.085097045 -0.26642114, 0.090710342 0.083832294 -0.26898915, 0.095482171 0.08517465 -0.26635528, 0.090768069 0.083921254 -0.2688725, 0.095422626 0.085230976 -0.26627278, 0.090827763 0.08399412 -0.26874661, 0.10499898 0.098914564 -0.23822369, 0.11009534 0.1002865 -0.23547962, 0.1050189 0.099017277 -0.23820278, 0.11006558 0.10039896 -0.23548032, 0.10505088 0.099125609 -0.23815438, 0.11002435 0.10050531 -0.23545733, 0.10509396 0.099233717 -0.23807852, 0.10997416 0.10059984 -0.23541144, 0.10514598 0.099335089 -0.23797914, 0.10991794 0.10067743 -0.23534544, 0.10520378 0.099424064 -0.23786278, 0.10985829 0.10073383 -0.23526302, 0.10526337 0.099496916 -0.23773706, 0.087675944 0.080311254 -0.27543536, 0.092772543 0.081683174 -0.27269128, 0.087696031 0.080413952 -0.27541462, 0.092742607 0.081795692 -0.27269208, 0.087728038 0.080522373 -0.2753661, 0.092701629 0.081902057 -0.27266896, 0.087771192 0.080630377 -0.27529028, 0.092651576 0.081996366 -0.27262318, 0.087823257 0.080731854 -0.27519101, 0.09259519 0.082073972 -0.27255714, 0.087880984 0.080820873 -0.27507439, 0.092535496 0.082130387 -0.27247462, 0.087940514 0.080893517 -0.2749486, 0.084788933 0.07721068 -0.28163731, 0.089271784 0.07841748 -0.27922368, 0.084808975 0.077313453 -0.28161657, 0.089241877 0.078529909 -0.27922443, 0.084840909 0.077421799 -0.28156805, 0.089200899 0.078636214 -0.27920124, 0.084884033 0.077529892 -0.28149238, 0.089150682 0.078730896 -0.2791554, 0.084936142 0.077631235 -0.28139311, 0.089094356 0.078808323 -0.2790896, 0.084993735 0.07772024 -0.28127643, 0.089034796 0.078864753 -0.27900696, 0.085053533 0.077792972 -0.28115058, 0.082763582 0.074246436 -0.28577232, 0.099009156 0.074246481 -0.28577226, 0.082816511 0.074602991 -0.28574026, 0.099080637 0.074613541 -0.28573841, 0.082897156 0.074959844 -0.28564066, 0.099185258 0.074966073 -0.28563851, 0.083003581 0.075297892 -0.28547353, 0.099320084 0.075295091 -0.28547525, 0.083130389 0.075598568 -0.28524601, 0.09948054 0.075589299 -0.28525436, 0.083270788 0.07584703 -0.2849713, 0.099661708 0.075838894 -0.28498226, 0.083416671 0.076035112 -0.28466672, 0.099858433 0.076035261 -0.28466666, 0.13018246 -0.033292845 -0.14069788, 0.13014223 -0.033291712 -0.14067833, 0.13015266 -0.033288091 -0.14065351, 0.13013317 -0.03329283 -0.1408183, 0.13013153 -0.033295602 -0.14070316, 0.13011052 -0.033303663 -0.14075211, 0.13010122 -0.033306539 -0.14077413, 0.13009627 -0.033292741 -0.14090824, 0.13009001 -0.033306271 -0.14086461, 0.1300915 -0.03330934 -0.14079738, 0.13008155 -0.033313572 -0.14082038, 0.1300679 -0.033313125 -0.14091146, 0.13006367 -0.033326447 -0.14086044, 0.13007243 -0.033320427 -0.14084065, 0.13007699 -0.033316806 -0.14083058, 0.13004114 -0.033333108 -0.14091197, 0.1300502 -0.033331588 -0.14089191, 0.13005687 -0.033329517 -0.14087617, 0.11357817 -0.033288136 -0.18112476, 0.1136577 -0.033290669 -0.1811358, 0.11357747 -0.033290669 -0.18118277, 0.11364031 -0.033289671 -0.18111019, 0.11362305 -0.03328675 -0.18108432, 0.11360592 -0.033281967 -0.18105887, 0.11955319 0.099618763 -0.23749341, 0.11751798 0.097753838 -0.24122399, 0.11769584 0.097701922 -0.24132779, 0.10562339 0.084184527 -0.2683661, 0.10576487 0.084236592 -0.26826185, 0.11989705 0.099648982 -0.23743309, 0.12005915 0.099687278 -0.23735623, 0.10511753 0.084115833 -0.26850325, 0.10288377 0.082282603 -0.27217031, 0.11731941 0.097785518 -0.24116039, 0.13693137 0.11600621 -0.20471409, 0.13697664 0.11593877 -0.20484936, 0.13696261 0.11597367 -0.20477912, 0.10587823 0.084298819 -0.26813751, 0.12020062 0.099739283 -0.23725225, 0.1059593 0.084366769 -0.26800138, 0.12031391 0.099801555 -0.23712775, 0.13697241 0.11590312 -0.20492005, 0.13688454 0.11603472 -0.20465718, 0.1369506 0.11586951 -0.20498753, 0.13682352 0.1160581 -0.20461047, 0.13675307 0.11607431 -0.2045778, 0.12039484 0.099869609 -0.23699163, 0.13667555 0.11608322 -0.20456013, 0.13663004 0.11608456 -0.2045573, 0.13658455 0.11608347 -0.20455985, 0.09595041 0.084115952 -0.26850319, 0.11038609 0.099618688 -0.23749343, 0.095678151 0.084104925 -0.26852512, 0.095412552 0.084071845 -0.26859117, 0.095166415 0.084018409 -0.2686981, 0.11011375 0.099607661 -0.23751536, 0.10984822 0.0995747 -0.2375814, 0.12398359 0.11441693 -0.20789291, 0.12045985 0.11517483 -0.20637669, 0.12303533 0.11425616 -0.20821464, 0.093388721 0.082274437 -0.2721864, 0.10960205 0.099521175 -0.2376883, 0.12220055 0.11399847 -0.20872991, 0.10223041 0.081015319 -0.27470517, 0.10051513 0.079031453 -0.27867365, 0.10240217 0.081022561 -0.27469051, 0.10782428 0.097777382 -0.24117672, 0.10037227 0.079098761 -0.27853882, 0.11988069 0.11507894 -0.20656872, 0.11954173 0.11493537 -0.20685591, 0.12015809 0.11514165 -0.20644319, 0.11969605 0.11501333 -0.20669995, 0.100192 0.081015378 -0.27470523, 0.10020423 0.079148278 -0.27843964, 0.11480871 0.094601288 -0.24752977, 0.11492454 0.094549149 -0.24763395, 0.11666602 0.096518204 -0.24369538, 0.10257421 0.081045598 -0.27464485, 0.10061972 0.078950614 -0.27883524, 0.10273625 0.081083953 -0.27456802, 0.11683768 0.096525595 -0.24368072, 0.1193787 0.11480738 -0.20711172, 0.11945143 0.11487368 -0.20697941, 0.10000646 0.079180941 -0.27837431, 0.12152803 0.11365902 -0.20940886, 0.11700994 0.096548364 -0.24363494, 0.10067877 0.07886298 -0.27901044, 0.10287781 0.081135929 -0.27446383, 0.11463097 0.094653144 -0.24742582, 0.12924352 0.11010437 -0.21651921, 0.12938641 0.11003697 -0.21665408, 0.11717191 0.096586719 -0.24355832, 0.10069239 0.078775749 -0.2791853, 0.10299107 0.081198171 -0.27433941, 0.12907557 0.11015385 -0.21642004, 0.11443225 0.094684973 -0.24736252, 0.12949114 0.1099562 -0.21681572, 0.1288778 0.11018664 -0.21635471, 0.11731344 0.096638843 -0.24345398, 0.12955026 0.10986847 -0.21699105, 0.10067055 0.078702286 -0.27933195, 0.12956373 0.10978121 -0.2171656, 0.11742681 0.096700951 -0.24332964, 0.11750773 0.09676899 -0.24319366, 0.12954192 0.10970789 -0.21731232, 0.12949516 0.1096423 -0.21744348, 0.12105666 0.11325739 -0.21021214, 0.12905638 0.10917121 -0.2183858, 0.089499667 0.082493082 -0.27174911, 0.089411214 0.082472935 -0.27178952, 0.10749884 0.096518144 -0.24369538, 0.12081398 0.11281706 -0.21109295, 0.10307214 0.081266239 -0.27420342, 0.10062385 0.078636751 -0.27946305, 0.10018504 0.078165635 -0.2804054, 0.10010397 0.078097686 -0.2805413, 0.099990621 0.078035474 -0.28066576, 0.099849105 0.077983364 -0.28076994, 0.099687144 0.077945024 -0.28084683, 0.099515036 0.077922165 -0.28089237, 0.099343255 0.077914894 -0.28090709, 0.090176076 0.077914879 -0.28090709, 0.10722664 0.096507132 -0.24371733, 0.10696098 0.096474051 -0.24378337, 0.089903951 0.077903822 -0.28092912, 0.089638248 0.077870801 -0.28099516, 0.10671492 0.096420616 -0.2438903, 0.089392081 0.077817276 -0.28110209, 0.10493711 0.094676763 -0.24737851, 0.083725482 0.076292068 -0.28415298, 0.083636954 0.076271728 -0.2841934, 0.12616926 0.10607068 -0.22458786, 0.12328212 0.10297015 -0.23078986, 0.1230353 0.11092463 -0.21487851, 0.12398362 0.11076383 -0.21520028, 0.12220052 0.11118227 -0.21436323, 0.1146206 0.09366858 -0.24939571, 0.12152806 0.11152178 -0.21368419, 0.11377887 0.093417645 -0.24989732, 0.11203726 0.091448635 -0.25383592, 0.11395057 0.093424946 -0.24988259, 0.11173363 0.090567797 -0.25559747, 0.11192165 0.091500759 -0.25373161, 0.10884655 0.087467298 -0.26179963, 0.12105669 0.11192326 -0.21288094, 0.11937287 0.11017957 -0.21636881, 0.12821463 0.10892044 -0.21888745, 0.11904752 0.10892034 -0.21888749, 0.11412267 0.093447804 -0.24983697, 0.11826347 0.10882281 -0.21908247, 0.11259675 0.10729763 -0.22213341, 0.11604284 0.10702397 -0.22268099, 0.11648569 0.10707891 -0.22257064, 0.11250815 0.10727739 -0.22217385, 0.11537626 0.10572244 -0.22528455, 0.10970959 0.10419711 -0.22833546, 0.11315575 0.10392332 -0.22888301, 0.11174388 0.091552585 -0.2536279, 0.11359863 0.10397829 -0.22877273, 0.10962118 0.10417677 -0.22837582, 0.11248921 0.10262175 -0.23148641, 0.10682252 0.10109654 -0.23453729, 0.11026849 0.10082288 -0.2350848, 0.11071149 0.10087785 -0.23497476, 0.10673399 0.10107626 -0.2345778, 0.10393542 0.097995967 -0.24073921, 0.11428469 0.09348622 -0.24976017, 0.10738137 0.097722262 -0.24128677, 0.12635726 0.1070035 -0.22272196, 0.12647301 0.1069514 -0.22282615, 0.10384688 0.097975612 -0.24077977, 0.10104826 0.094895393 -0.24694122, 0.10449436 0.094621688 -0.24748875, 0.1283863 0.10892779 -0.21887295, 0.10095976 0.094875202 -0.24698177, 0.10382771 0.093320042 -0.25009215, 0.098161086 0.091794834 -0.25314325, 0.10160708 0.091521159 -0.25369063, 0.10204998 0.091576263 -0.25358057, 0.1115451 0.091584355 -0.25356424, 0.098072574 0.091774508 -0.25318366, 0.1009406 0.090219632 -0.25629431, 0.095273957 0.08869417 -0.25934526, 0.12855844 0.10895056 -0.21882711, 0.098719984 0.08842057 -0.25989258, 0.099162951 0.08847563 -0.25978249, 0.11442631 0.093538314 -0.24965613, 0.095185578 0.088674039 -0.2593857, 0.098053575 0.087118924 -0.26249611, 0.092386752 0.08559376 -0.2655471, 0.12617955 0.10705544 -0.22261801, 0.095832884 0.085319966 -0.26609468, 0.096275777 0.08537513 -0.26598442, 0.092298329 0.085573524 -0.26558757, 0.092945784 0.082219407 -0.27229655, 0.12872045 0.10898894 -0.21875034, 0.11453953 0.093600512 -0.24953161, 0.12598084 0.10708711 -0.22255449, 0.12886195 0.10904104 -0.21864633, 0.12081398 0.11236359 -0.21200013, 0.11893001 0.11012462 -0.21647896, 0.12897532 0.10910326 -0.21852185, 0.10461174 0.09341754 -0.24989724, 0.10433966 0.093406647 -0.24991928, 0.10407388 0.093373448 -0.24998535, 0.11877526 0.10890938 -0.21890953, 0.11850958 0.10887621 -0.21897554, 0.10903452 0.088400215 -0.25993371, 0.10915023 0.088347957 -0.26003793, 0.1108918 0.09031713 -0.25609922, 0.11106344 0.090324372 -0.25608462, 0.11123569 0.09034726 -0.2560389, 0.10885671 0.088452116 -0.25982982, 0.12347013 0.10390292 -0.22892386, 0.12358588 0.10385089 -0.22902808, 0.12532753 0.10581987 -0.22508937, 0.11139761 0.090385675 -0.25596213, 0.12549919 0.10582714 -0.22507471, 0.10865799 0.088483766 -0.25976634, 0.12567133 0.10584991 -0.2250292, 0.12329239 0.10395484 -0.22882003, 0.11153911 0.09043777 -0.25585794, 0.12583336 0.10588832 -0.22495225, 0.12309366 0.10398667 -0.22875664, 0.11165257 0.090499967 -0.25573361, 0.12597495 0.10594039 -0.22484833, 0.12608825 0.10600278 -0.22472377, 0.10172467 0.090317056 -0.25609925, 0.11616042 0.10581973 -0.22508939, 0.10145253 0.090305984 -0.25612134, 0.10118674 0.090273008 -0.25618723, 0.11588815 0.10580875 -0.22511145, 0.11562251 0.1057758 -0.2251776, 0.10614741 0.085299537 -0.26613563, 0.10626301 0.085247472 -0.26623988, 0.1080047 0.087216556 -0.26230121, 0.10817641 0.087223694 -0.2622866, 0.10834861 0.087246642 -0.26224092, 0.10596967 0.085351452 -0.26603162, 0.12244037 0.10271944 -0.23129147, 0.12069871 0.10075021 -0.23523007, 0.12261198 0.10272667 -0.23127683, 0.12058298 0.10080245 -0.23512568, 0.10851049 0.087285146 -0.26216397, 0.12278408 0.10274951 -0.23123124, 0.10577086 0.085383311 -0.26596817, 0.12040533 0.10085428 -0.23502205, 0.108652 0.087337121 -0.26205999, 0.12294617 0.10278787 -0.23115441, 0.12020658 0.10088608 -0.23495851, 0.10876541 0.087399274 -0.26193553, 0.12308769 0.10283998 -0.23105036, 0.123201 0.10290214 -0.23092569, 0.098837584 0.087216467 -0.26230121, 0.11327316 0.10271929 -0.23129141, 0.098565459 0.08720535 -0.26232326, 0.098299712 0.087172359 -0.26238924, 0.113001 0.10270821 -0.23131335, 0.11273529 0.10267518 -0.23137951, 0.10337593 0.082147002 -0.27244174, 0.10528925 0.084123284 -0.26848859, 0.10326023 0.082198918 -0.27233756, 0.10546136 0.084146142 -0.26844275, 0.11781162 0.097649738 -0.24143195, 0.10308243 0.082251012 -0.27223366, 0.11972487 0.099626169 -0.23747876, 0.090500951 0.08043915 -0.27585757, 0.086612582 0.079392582 -0.277951, 0.086524099 0.079372406 -0.27799141, 0.10380913 -0.032978788 -0.21443571, 0.089957133 0.077984646 -0.27860108, 0.09884201 -0.032978609 -0.21777135, 0.084784418 0.077014118 -0.28159475, 0.098539263 -0.033173099 -0.21787827, 0.089292631 0.078227684 -0.27916747, 0.086899385 0.079281971 -0.27705026, 0.092169032 0.079477593 -0.27360857, 0.10086583 -0.032599136 -0.21235429, 0.090243012 0.080181926 -0.27525008, 0.10615981 -0.032599226 -0.20879914, 0.099006474 0.073245183 -0.28550366, 0.088667899 0.064226821 -0.28028885, 0.098393768 -0.0066124946 -0.23932551, 0.08771953 0.064538136 -0.28046894, 0.097445533 -0.0069238096 -0.2391455, 0.086884916 0.065036878 -0.28075704, 0.096610829 -0.0074225813 -0.23885702, 0.095938265 -0.0080798119 -0.23847698, 0.08771947 0.07098791 -0.2841984, 0.082761437 0.073245078 -0.28550375, 0.086884886 0.070489138 -0.28390992, 0.08866778 0.071299165 -0.28437841, 0.086212307 0.069831923 -0.28353, 0.085740939 0.069054663 -0.28308046, 0.085498244 0.068201974 -0.28258741, 0.085498244 0.067323983 -0.28207982, 0.085740924 0.066471517 -0.28158677, 0.098393813 -0.013684854 -0.23523574, 0.096854359 -0.032289669 -0.2244775, 0.097445473 -0.013373479 -0.23541577, 0.096610814 -0.012874782 -0.23570436, 0.095938206 -0.012217611 -0.23608436, 0.096029639 -0.033043593 -0.22404149, 0.095466912 -0.011440217 -0.23653376, 0.095224202 -0.010587722 -0.23702666, 0.095224202 -0.0097096562 -0.23753452, 0.095466882 -0.0088571608 -0.23802739, 0.086212307 0.065694049 -0.28113723, 0.13005976 -0.03338711 -0.13889995, 0.094570309 -0.033733785 -0.22546309, 0.12987487 -0.034583971 -0.13902405, 0.093669534 -0.034579441 -0.22743139, 0.093563944 -0.033733636 -0.22792049, 0.089721441 0.0051087439 -0.24792399, 0.1186709 0.11650421 -0.20769593, 0.11234696 0.10850476 -0.22094983, 0.11877838 0.11541179 -0.20713438, 0.089652061 0.0056644976 -0.24824537, 0.083918184 0.05159609 -0.27480567, 0.083848894 0.052151695 -0.27512679, 0.081188917 0.074574471 -0.28775334, 0.081267864 0.075177103 -0.28772569, 0.082120687 0.07725206 -0.28621078, 0.081403226 0.075782746 -0.28756046, 0.081587553 0.076338649 -0.28726274, 0.081831187 0.076850265 -0.28680754, 0.11288357 0.10718688 -0.22123267, 0.11800554 0.1085656 -0.21847488, 0.13036858 -0.032878906 -0.1402386, 0.13566256 -0.032879025 -0.13668349, 0.0840123 0.076181263 -0.28325218, 0.089134231 0.077559903 -0.28049436, 0.097591639 -0.032598674 -0.22034934, 0.10288557 -0.032598868 -0.21679431, 0.10999647 0.10408631 -0.22743471, 0.11511835 0.10546504 -0.22467697, 0.12705974 -0.032602519 -0.14839333, 0.1323538 -0.032602742 -0.14483821, 0.13327733 -0.032982618 -0.14247955, 0.11589046 0.10629784 -0.22301954, 0.12831019 -0.032982394 -0.14581516, 0.11076841 0.10491917 -0.22577702, 0.12800747 -0.033177003 -0.14592209, 0.10710938 0.10098566 -0.23363641, 0.11223125 0.10236445 -0.23087879, 0.12378551 -0.032602131 -0.1563884, 0.12907954 -0.032602236 -0.15283337, 0.13000293 -0.032982111 -0.15047473, 0.11300327 0.1031972 -0.22922134, 0.12503593 -0.032981962 -0.15381011, 0.10788132 0.10181865 -0.23197915, 0.12473322 -0.033176526 -0.15391728, 0.10422216 0.097885147 -0.23983839, 0.1093442 0.099263921 -0.23708078, 0.12051135 -0.03260161 -0.1643834, 0.12580539 -0.032601908 -0.16082847, 0.12672882 -0.032981798 -0.15846977, 0.11011614 0.10009666 -0.23542336, 0.12176168 -0.032981604 -0.16180535, 0.10499425 0.098717943 -0.23818114, 0.12145892 -0.033176124 -0.16191243, 0.10133512 0.094784573 -0.24604037, 0.10645704 0.096163332 -0.24328272, 0.11723706 -0.032601267 -0.17237857, 0.1225311 -0.032601386 -0.1688236, 0.12345456 -0.032981232 -0.16646509, 0.10722916 0.096996173 -0.24162537, 0.11848745 -0.032981187 -0.16980042, 0.10210714 0.095617384 -0.24438311, 0.1181848 -0.033175722 -0.16990747, 0.098447934 0.091684118 -0.25224236, 0.10356994 0.093062863 -0.24948466, 0.11396284 -0.03260079 -0.18037385, 0.11925687 -0.032600984 -0.17681864, 0.12018037 -0.032980889 -0.17446019, 0.10434195 0.093895525 -0.24782731, 0.11521319 -0.032980725 -0.17779543, 0.099219948 0.092516929 -0.25058496, 0.11491048 -0.033175305 -0.17790256, 0.095560849 0.08858344 -0.25844419, 0.10068278 0.08996217 -0.25568655, 0.11068845 -0.032600433 -0.18836889, 0.11598271 -0.032600567 -0.18481393, 0.11690605 -0.032980427 -0.18245533, 0.10145478 0.090795085 -0.25402927, 0.11193891 -0.032980278 -0.18579072, 0.096332818 0.089416325 -0.256787, 0.11163624 -0.033174843 -0.18589774, 0.0926736 0.085482985 -0.26464635, 0.09779565 0.086861655 -0.26188856, 0.10741432 -0.032599866 -0.19636403, 0.11270833 -0.03260015 -0.19280896, 0.11363178 -0.03298001 -0.19045046, 0.098567635 0.087694347 -0.26023114, 0.10866475 -0.032979921 -0.19378561, 0.093445688 0.086315781 -0.26298887, 0.10836186 -0.033174276 -0.19389288, 0.089786634 0.082382366 -0.27084816, 0.094908535 0.083761066 -0.26809049, 0.10414 -0.032599539 -0.20435914, 0.10943413 -0.032599688 -0.20080398, 0.1103576 -0.032979548 -0.19844544, 0.095680594 0.084593803 -0.26643312, 0.10539047 -0.032979429 -0.20178102, 0.090558618 0.083215058 -0.26919079, 0.10508774 -0.033174038 -0.20188807, 0.10708329 -0.032979205 -0.20644063, 0.092793435 0.081493303 -0.2726351, 0.10211621 -0.032979012 -0.20977609, 0.087671414 0.080114558 -0.2753928, 0.10181355 -0.033173546 -0.20988323, 0.098973781 0.073561653 -0.28565145, 0.082736224 0.073560685 -0.28565121, 0.082737118 0.073899537 -0.28574193, 0.098974735 0.073899016 -0.28574193, 0.084001541 0.076238513 -0.28329402, 0.089140549 0.077655032 -0.28055373, 0.083983749 0.076289624 -0.28335136, 0.089159504 0.077735856 -0.28062931, 0.083950162 0.07634294 -0.28344828, 0.08919014 0.077798083 -0.2807174, 0.083894998 0.076381594 -0.28359342, 0.089231014 0.077839077 -0.28081357, 0.089280009 0.077856123 -0.28091311, 0.083804101 0.07638368 -0.28381604, 0.089334726 0.077848732 -0.28101099, 0.083684593 0.076316744 -0.28408933, 0.083698124 0.07630983 -0.28411108, 0.083711773 0.076301485 -0.28413236, 0.089290306 0.078288957 -0.27919361, 0.084779993 0.077074781 -0.28162193, 0.084781468 0.077141047 -0.2816363, 0.089283183 0.078352705 -0.27921259, 0.092790902 0.081554785 -0.27266136, 0.087667122 0.080175415 -0.27541992, 0.087668732 0.080241576 -0.27543437, 0.092783958 0.081618294 -0.27268004, 0.086888656 0.079339072 -0.2770921, 0.090249315 0.080277041 -0.27530923, 0.086870924 0.079390243 -0.27714935, 0.090268388 0.080357745 -0.27538481, 0.086837187 0.079443499 -0.27724648, 0.090298906 0.080420092 -0.27547291, 0.086782113 0.079482123 -0.27739155, 0.090339765 0.080460772 -0.27556926, 0.09038879 0.080477908 -0.27566877, 0.086691156 0.079484269 -0.277614, 0.090443492 0.080470622 -0.27576649, 0.086571708 0.079417273 -0.27788746, 0.086585239 0.0794103 -0.27790913, 0.086598873 0.079402119 -0.27793026, 0.096209973 -0.033283234 -0.22366922, 0.096393377 -0.033181608 -0.22355181, 0.096450508 -0.033063367 -0.22379637, 0.096160471 -0.033328086 -0.22364445, 0.096380591 -0.033270538 -0.22329393, 0.096412808 -0.03332822 -0.22302845, 0.11173685 -0.033330172 -0.18560961, 0.11188617 -0.033248648 -0.18551026, 0.11189541 -0.033228338 -0.1855536, 0.11188522 -0.033265173 -0.18545894, 0.1119017 -0.033283412 -0.18535905, 0.11194548 -0.03329052 -0.18522914, 0.11351044 -0.033330351 -0.18127877, 0.11355193 -0.03329058 -0.18130666, 0.10846265 -0.033329785 -0.19360475, 0.10856099 -0.033286512 -0.19350497, 0.10857458 -0.033257663 -0.19356512, 0.10855743 -0.033310696 -0.1934354, 0.10856409 -0.033329785 -0.19335698, 0.10518835 -0.033329368 -0.20159994, 0.10528682 -0.033286095 -0.20150004, 0.10530041 -0.033257365 -0.20156012, 0.10528319 -0.03331013 -0.20143051, 0.1052898 -0.033329368 -0.2013521, 0.10191417 -0.033328995 -0.20959498, 0.10201249 -0.033285588 -0.20949514, 0.10202622 -0.033256903 -0.2095554, 0.10200894 -0.033309713 -0.2094257, 0.10201561 -0.033328891 -0.20934717, 0.09863998 -0.033328459 -0.21759012, 0.098738328 -0.033285186 -0.21749035, 0.098752037 -0.03325659 -0.21755052, 0.098734766 -0.033309251 -0.21742077, 0.098741427 -0.033328444 -0.2173425, 0.11501116 -0.03333059 -0.17761448, 0.11510952 -0.033287361 -0.17751469, 0.11512317 -0.033258557 -0.17757474, 0.115106 -0.033311486 -0.17744498, 0.11511253 -0.033330604 -0.17736678, 0.1182853 -0.033331007 -0.16961934, 0.11838374 -0.033287793 -0.16951956, 0.11839736 -0.033259034 -0.16957973, 0.11838019 -0.033311933 -0.16945018, 0.11838678 -0.033331037 -0.16937159, 0.12155962 -0.033331499 -0.16162418, 0.12165795 -0.033288226 -0.1615245, 0.12167166 -0.033259511 -0.16158462, 0.12165441 -0.033312276 -0.16145498, 0.12166107 -0.033331469 -0.16137646, 0.12483385 -0.033331811 -0.15362917, 0.12493224 -0.033288583 -0.15352938, 0.12494588 -0.033259913 -0.15358953, 0.12492874 -0.033312738 -0.15345977, 0.12493531 -0.033331931 -0.15338132, 0.12810807 -0.033332348 -0.14563398, 0.12825739 -0.033250749 -0.14553446, 0.12826651 -0.033230409 -0.14557806, 0.12825629 -0.033267215 -0.14548302, 0.12827289 -0.033285558 -0.1453833, 0.1283167 -0.033292517 -0.14525345, 0.120516 -0.032665625 -0.16435482, 0.12578735 -0.032719746 -0.16080175, 0.12051409 -0.03273432 -0.1643406, 0.12050632 -0.032798856 -0.16434176, 0.12578589 -0.032841936 -0.16079949, 0.12049425 -0.032857671 -0.16435505, 0.12047756 -0.032916054 -0.16438006, 0.125801 -0.032961115 -0.1608219, 0.12045637 -0.032972664 -0.16441627, 0.12042215 -0.033043459 -0.16448034, 0.12583174 -0.033070162 -0.16086769, 0.12037146 -0.033122152 -0.1645828, 0.12587629 -0.033162579 -0.16093418, 0.12031561 -0.03318572 -0.16470161, 0.12031472 -0.033221722 -0.1647656, 0.12593204 -0.033232823 -0.16101705, 0.12030834 -0.033248812 -0.16483334, 0.12599559 -0.033276811 -0.16111177, 0.12028468 -0.033281714 -0.16497388, 0.12606318 -0.033291712 -0.16121256, 0.12025085 -0.033291548 -0.16511571, 0.12174338 -0.033090517 -0.16174732, 0.12146623 -0.033218756 -0.16188288, 0.12147689 -0.033255413 -0.16184722, 0.12149552 -0.033293232 -0.16179119, 0.12171267 -0.033185586 -0.16167185, 0.12152123 -0.033319935 -0.1617211, 0.11011375 0.10015805 -0.23544964, 0.1049899 0.09877868 -0.23820829, 0.10499148 0.098844782 -0.23822245, 0.11010672 0.10022171 -0.23546842, 0.10421151 0.097942382 -0.23988049, 0.10935049 0.099359021 -0.23714006, 0.1041937 0.097993538 -0.23993766, 0.10936929 0.099439695 -0.23721555, 0.10415986 0.098046958 -0.24003471, 0.10939993 0.099502161 -0.23730376, 0.10410482 0.098085552 -0.24017973, 0.10944094 0.099542812 -0.23739997, 0.10948983 0.099560112 -0.23749952, 0.10401389 0.098087668 -0.24040224, 0.10954449 0.099552661 -0.23759724, 0.10389449 0.098020598 -0.24067581, 0.10390808 0.098013684 -0.2406975, 0.10392174 0.098005533 -0.24071874, 0.12706442 -0.032666504 -0.14836439, 0.13233581 -0.032720596 -0.14481135, 0.12706257 -0.032735184 -0.14835024, 0.1270548 -0.032799765 -0.14835158, 0.13233437 -0.032842815 -0.14480919, 0.12704273 -0.032858551 -0.14836499, 0.12702592 -0.032916874 -0.14838991, 0.13234951 -0.032962009 -0.14483157, 0.12700477 -0.032973498 -0.14842589, 0.12697062 -0.033044294 -0.14849012, 0.13238014 -0.033071071 -0.14487737, 0.12691984 -0.033123001 -0.14859246, 0.13242468 -0.033163548 -0.14494388, 0.12686406 -0.033186644 -0.14871141, 0.12686321 -0.033222571 -0.14877521, 0.13248052 -0.033233672 -0.14502686, 0.12685682 -0.033249661 -0.14884302, 0.13254403 -0.033277541 -0.14512143, 0.12683314 -0.033282608 -0.14898367, 0.13261171 -0.033292606 -0.14522237, 0.12679929 -0.033292368 -0.14912547, 0.12830836 -0.033080786 -0.14575118, 0.12801477 -0.033219591 -0.14589274, 0.12802532 -0.033256248 -0.14585686, 0.12804385 -0.033294067 -0.14580108, 0.12829363 -0.033165604 -0.14567024, 0.12806976 -0.03332071 -0.14573088, 0.12379017 -0.032666042 -0.15635942, 0.12906159 -0.032720134 -0.15280649, 0.12378837 -0.032734811 -0.15634534, 0.12378047 -0.032799229 -0.15634665, 0.1290601 -0.032842398 -0.15280443, 0.12376846 -0.032858074 -0.15636, 0.12375174 -0.032916531 -0.1563848, 0.1290752 -0.032961562 -0.15282674, 0.12373067 -0.032973111 -0.15642104, 0.12369643 -0.033043966 -0.15648505, 0.12910606 -0.033070609 -0.15287253, 0.12364562 -0.033122554 -0.15658772, 0.12915055 -0.033163056 -0.15293893, 0.12358987 -0.033186167 -0.15670653, 0.12358899 -0.033222213 -0.15677053, 0.12920631 -0.03323333 -0.15302202, 0.12358257 -0.033249244 -0.15683813, 0.12926991 -0.033277273 -0.15311676, 0.12355889 -0.033282116 -0.15697867, 0.1293375 -0.033292264 -0.15321741, 0.12352513 -0.03329204 -0.15712044, 0.12501761 -0.033090934 -0.15375228, 0.12474045 -0.033219099 -0.15388785, 0.12475115 -0.03325583 -0.15385197, 0.12476969 -0.03329359 -0.15379618, 0.12498692 -0.033186018 -0.15367661, 0.12479547 -0.033320263 -0.15372606, 0.11724159 -0.032665193 -0.17234981, 0.12251323 -0.032719254 -0.16879694, 0.11723983 -0.032733917 -0.17233562, 0.11723205 -0.032798424 -0.172337, 0.12251166 -0.032841414 -0.16879465, 0.11722003 -0.032857299 -0.17235021, 0.11720315 -0.032915682 -0.17237523, 0.12252676 -0.032960624 -0.16881706, 0.11718211 -0.032972246 -0.17241135, 0.11714801 -0.033043042 -0.1724754, 0.12255748 -0.03306973 -0.16886285, 0.11709714 -0.033121765 -0.17257801, 0.12260211 -0.033162206 -0.16892923, 0.11704135 -0.033185214 -0.17269683, 0.11704049 -0.033221275 -0.17276075, 0.12265775 -0.033232406 -0.16901226, 0.11703399 -0.033248395 -0.17282847, 0.12272137 -0.033276349 -0.16910698, 0.11701043 -0.033281222 -0.17296891, 0.12278903 -0.03329131 -0.16920759, 0.11697662 -0.033291101 -0.17311072, 0.11846916 -0.033090204 -0.16974244, 0.11819203 -0.033218339 -0.16987801, 0.11820266 -0.033255011 -0.16984238, 0.11822122 -0.033292904 -0.16978641, 0.11843836 -0.033185124 -0.16966687, 0.11824699 -0.033319399 -0.16971627, 0.11356886 -0.033290654 -0.18125266, 0.11353311 -0.033325478 -0.18122508, 0.11355585 -0.033311307 -0.18117313, 0.11357471 -0.033290684 -0.18121795, 0.11396742 -0.032663837 -0.18034534, 0.11923887 -0.032718882 -0.17679194, 0.11396611 -0.032725707 -0.18033151, 0.11395983 -0.032784522 -0.18033072, 0.11923741 -0.032841086 -0.17678976, 0.11394843 -0.032845408 -0.18034191, 0.11393169 -0.03290686 -0.18036611, 0.11925256 -0.032960266 -0.17681231, 0.11390968 -0.032967508 -0.18040329, 0.11388266 -0.033025756 -0.18045323, 0.11928323 -0.033069313 -0.17685811, 0.11384015 -0.033097327 -0.18053752, 0.1193279 -0.03316173 -0.17692436, 0.11378556 -0.033166036 -0.18065207, 0.11938356 -0.033232063 -0.17700732, 0.1137072 -0.033234298 -0.18082473, 0.11365546 -0.033263847 -0.18094273, 0.11944713 -0.033275947 -0.17710212, 0.11951478 -0.033290878 -0.17720288, 0.1151949 -0.033089668 -0.17773749, 0.11491781 -0.033217818 -0.17787321, 0.11492835 -0.033254549 -0.17783752, 0.11494701 -0.033292383 -0.17778161, 0.11516415 -0.033184648 -0.17766218, 0.1149727 -0.033319011 -0.17771131, 0.11069317 -0.032664359 -0.18834005, 0.11596462 -0.03271842 -0.18478702, 0.11069132 -0.032733202 -0.18832587, 0.11068356 -0.032797545 -0.1883271, 0.11596316 -0.032840639 -0.1847849, 0.11067149 -0.032856435 -0.18834054, 0.11065482 -0.032914802 -0.1883655, 0.11597832 -0.032959849 -0.18480736, 0.1106336 -0.032971427 -0.18840162, 0.11059953 -0.033042207 -0.18846567, 0.11600897 -0.033068895 -0.18485306, 0.11054869 -0.03312093 -0.1885681, 0.11605358 -0.033161342 -0.18491946, 0.1104929 -0.033184469 -0.18868695, 0.11049195 -0.03322047 -0.18875097, 0.11610937 -0.033231676 -0.18500243, 0.11048557 -0.033247605 -0.18881865, 0.11617287 -0.03327553 -0.18509713, 0.11046183 -0.033280507 -0.18895918, 0.1162405 -0.033290491 -0.18519787, 0.11042815 -0.033290356 -0.18910101, 0.11193715 -0.033078656 -0.18572685, 0.11164361 -0.03321749 -0.18586843, 0.11165418 -0.033254102 -0.18583262, 0.11167279 -0.03329201 -0.1857767, 0.11192226 -0.033163548 -0.18564574, 0.11169846 -0.033318654 -0.18570656, 0.10864641 -0.033088818 -0.19372781, 0.10836935 -0.033216909 -0.19386333, 0.10837992 -0.03325361 -0.19382767, 0.10839847 -0.033291563 -0.19377181, 0.10861559 -0.033183873 -0.19365232, 0.10842431 -0.033318162 -0.19370165, 0.10741891 -0.032666072 -0.19633444, 0.11269033 -0.032718047 -0.19278213, 0.10741718 -0.032730162 -0.19632129, 0.10741043 -0.032790303 -0.19632146, 0.11268896 -0.032840192 -0.19277996, 0.10739835 -0.032851398 -0.19633411, 0.10738124 -0.032912269 -0.19635947, 0.11270399 -0.032959357 -0.19280247, 0.10735919 -0.032971144 -0.19639693, 0.10732356 -0.033044919 -0.19646427, 0.11273465 -0.033068433 -0.19284827, 0.1072762 -0.033118024 -0.19655949, 0.11277933 -0.033160955 -0.19291444, 0.10724014 -0.033161908 -0.19663587, 0.10720275 -0.033198908 -0.19671683, 0.11283511 -0.033231184 -0.1929976, 0.10720669 -0.033242315 -0.19680227, 0.11289859 -0.033275113 -0.1930922, 0.10719629 -0.033273503 -0.196907, 0.10717995 -0.033285439 -0.19699131, 0.11296625 -0.033289939 -0.19319303, 0.10715388 -0.03328988 -0.19709606, 0.10537206 -0.033088326 -0.20172285, 0.10509495 -0.033216521 -0.2018586, 0.10510565 -0.033253282 -0.20182277, 0.10512421 -0.033291101 -0.20176682, 0.10534145 -0.033183426 -0.20164742, 0.10514992 -0.033317715 -0.20169663, 0.1041448 -0.032665715 -0.20432958, 0.10941628 -0.032717541 -0.2007774, 0.10414301 -0.032729864 -0.20431638, 0.10413611 -0.032789916 -0.20431663, 0.10941471 -0.032839864 -0.20077515, 0.10412407 -0.032850981 -0.20432937, 0.10410701 -0.032911763 -0.20435466, 0.1094297 -0.032958865 -0.20079765, 0.10408507 -0.032970786 -0.20439194, 0.1040491 -0.033044487 -0.20445926, 0.10946062 -0.033068031 -0.20084335, 0.10400198 -0.033117533 -0.20455466, 0.10950513 -0.033160478 -0.20090973, 0.10396586 -0.033161402 -0.20463084, 0.10392849 -0.033198401 -0.20471205, 0.10956088 -0.033230737 -0.20099293, 0.10393248 -0.033241972 -0.2047974, 0.10962446 -0.03327471 -0.20108736, 0.10392205 -0.033273056 -0.20490195, 0.10390566 -0.033284917 -0.20498647, 0.10969205 -0.033289522 -0.20118815, 0.10387965 -0.033289418 -0.20509122, 0.096172839 -0.033282325 -0.22373787, 0.096130639 -0.033318698 -0.22371989, 0.096129328 -0.033271849 -0.22380191, 0.096103936 -0.033292443 -0.22379225, 0.09608081 -0.033252135 -0.22385971, 0.09675172 -0.032533929 -0.22431752, 0.096042871 -0.03312546 -0.22398743, 0.096059918 -0.033195868 -0.22392595, 0.096644312 -0.032758042 -0.22413263, 0.10087052 -0.032663107 -0.21232551, 0.10614201 -0.032717198 -0.20877261, 0.10086872 -0.032731786 -0.21231116, 0.10086079 -0.032796338 -0.21231253, 0.10614043 -0.032839373 -0.20877017, 0.10084881 -0.032855138 -0.21232583, 0.10083209 -0.032913476 -0.21235074, 0.10615546 -0.032958463 -0.2087927, 0.10081102 -0.032970175 -0.21238704, 0.10077681 -0.033041015 -0.212451, 0.10618621 -0.03306751 -0.20883848, 0.10072599 -0.033119574 -0.21255361, 0.10623074 -0.033159986 -0.20890488, 0.10067023 -0.033183232 -0.21267237, 0.10066932 -0.033219188 -0.2127364, 0.1062867 -0.033230245 -0.208988, 0.10066284 -0.033246279 -0.21280389, 0.10635012 -0.033274099 -0.20908262, 0.10063924 -0.033279061 -0.21294455, 0.10641772 -0.033289135 -0.20918332, 0.10060532 -0.033288881 -0.21308626, 0.10209799 -0.033087984 -0.20971812, 0.10182077 -0.033216074 -0.20985378, 0.10183144 -0.03325285 -0.2098179, 0.10184997 -0.033290699 -0.20976187, 0.10206717 -0.033183023 -0.20964266, 0.1018756 -0.033317253 -0.2096919, 0.098823681 -0.033087537 -0.21771315, 0.098546609 -0.033215672 -0.21784887, 0.09855713 -0.033252418 -0.21781301, 0.098575845 -0.033290297 -0.21775723, 0.09879294 -0.033182666 -0.21763782, 0.098601595 -0.03331691 -0.21768707, 0.097596347 -0.03266497 -0.22031975, 0.10286771 -0.032716736 -0.21676762, 0.097594529 -0.03272897 -0.22030658, 0.097587734 -0.032789022 -0.22030681, 0.10286625 -0.032838881 -0.21676533, 0.097575635 -0.032850116 -0.22031945, 0.097558647 -0.032910988 -0.22034481, 0.10288133 -0.032958135 -0.21678783, 0.097536594 -0.032969996 -0.22038224, 0.097500771 -0.033043727 -0.2204496, 0.10291202 -0.033067167 -0.21683364, 0.097453475 -0.033116788 -0.22054484, 0.10295671 -0.033159748 -0.21690011, 0.097417414 -0.033160567 -0.22062115, 0.097380072 -0.033197671 -0.22070235, 0.10301232 -0.033229858 -0.21698299, 0.097384125 -0.033241197 -0.22078755, 0.10307586 -0.033273697 -0.21707764, 0.097373635 -0.033272192 -0.22089246, 0.097357303 -0.033284232 -0.22097674, 0.10314356 -0.033288687 -0.21717842, 0.097331226 -0.033288673 -0.2210815, 0.13037123 -0.032916933 -0.14022137, 0.1356518 -0.032949835 -0.13666749, 0.13037033 -0.032954097 -0.14021324, 0.1303667 -0.032989651 -0.14021267, 0.1356508 -0.033023044 -0.13666607, 0.13035972 -0.033026308 -0.14021958, 0.13034953 -0.033063322 -0.14023437, 0.13565993 -0.033094659 -0.13667953, 0.13033624 -0.033099845 -0.14025696, 0.13031979 -0.033134893 -0.14028721, 0.13567828 -0.033159986 -0.13670714, 0.13029413 -0.033177868 -0.14033847, 0.13570504 -0.033215478 -0.1367469, 0.13026111 -0.033219144 -0.14040785, 0.13573855 -0.033257723 -0.13679671, 0.13021375 -0.033259913 -0.14051212, 0.13018264 -0.033277541 -0.14058347, 0.13577674 -0.033284083 -0.13685347, 0.13581729 -0.033293039 -0.13691393, 0.12671961 -0.033303186 -0.14912269, 0.1266817 -0.033316538 -0.14912137, 0.12675917 -0.03329508 -0.14912404, 0.12679471 -0.033292457 -0.14918885, 0.12678444 -0.033292353 -0.14925151, 0.12670442 -0.033297345 -0.1493281, 0.12675475 -0.033292383 -0.14934894, 0.12665583 -0.033312008 -0.14930829, 0.1266105 -0.033336014 -0.14928982, 0.1252012 -0.033292174 -0.15314208, 0.12515107 -0.033297122 -0.15312146, 0.12510239 -0.033311814 -0.15310162, 0.12505713 -0.033335865 -0.15308295, 0.12511733 -0.033287451 -0.15328141, 0.12500691 -0.033236116 -0.15355577, 0.125038 -0.03324531 -0.153506, 0.12504013 -0.033229947 -0.15354094, 0.12502983 -0.03328377 -0.15338503, 0.12506267 -0.033273205 -0.15340005, 0.12499383 -0.03329733 -0.15338267, 0.12501404 -0.033271238 -0.15344943, 0.12504356 -0.033258647 -0.15346476, 0.1249598 -0.033315405 -0.15338154, 0.12498173 -0.033283219 -0.15345235, 0.12500849 -0.033254817 -0.15350552, 0.12495092 -0.033298671 -0.15345608, 0.12497953 -0.033264592 -0.15351327, 0.12497525 -0.033246115 -0.15357178, 0.12495206 -0.033277124 -0.15352213, 0.12344539 -0.033302754 -0.15711768, 0.1234075 -0.033316091 -0.15711647, 0.12348484 -0.033294663 -0.15711901, 0.12352033 -0.033291951 -0.157184, 0.12351012 -0.033291906 -0.15724666, 0.12343019 -0.033296958 -0.15732338, 0.12348039 -0.033291951 -0.15734392, 0.12338145 -0.033311635 -0.15730342, 0.12333618 -0.033335552 -0.15728495, 0.12192701 -0.033291802 -0.16113719, 0.12187685 -0.03329666 -0.16111666, 0.12182817 -0.033311471 -0.16109659, 0.12178281 -0.033335313 -0.1610782, 0.1218431 -0.033287004 -0.16127633, 0.12173253 -0.033235714 -0.16155075, 0.12176393 -0.033244953 -0.16150114, 0.12176597 -0.033229694 -0.16153608, 0.12175557 -0.033283353 -0.16138004, 0.12178832 -0.033272669 -0.16139506, 0.12171961 -0.033296898 -0.16137785, 0.12173986 -0.033270821 -0.16144453, 0.12176928 -0.033258185 -0.16145982, 0.12168545 -0.033314958 -0.16137661, 0.12170745 -0.033282772 -0.16144735, 0.12173414 -0.03325434 -0.16150071, 0.12167667 -0.033298239 -0.16145119, 0.12170526 -0.03326419 -0.16150852, 0.12170106 -0.033245832 -0.16156705, 0.12167776 -0.033276841 -0.16151728, 0.12017126 -0.033302337 -0.16511299, 0.12013313 -0.033315599 -0.16511166, 0.12021065 -0.03329429 -0.16511428, 0.12024617 -0.033291578 -0.16517913, 0.12023586 -0.033291489 -0.16524172, 0.12015593 -0.033296496 -0.1653184, 0.12020621 -0.033291578 -0.16533914, 0.12010726 -0.033311158 -0.16529846, 0.12006205 -0.033335239 -0.16528001, 0.1186527 -0.03329131 -0.16913237, 0.11860251 -0.033296227 -0.16911159, 0.11855395 -0.033311054 -0.16909173, 0.11850849 -0.033334941 -0.16907324, 0.11856885 -0.033286616 -0.1692715, 0.11845838 -0.033235312 -0.1695458, 0.11848962 -0.033244491 -0.16949628, 0.11849165 -0.033229232 -0.16953121, 0.11848125 -0.033282906 -0.1693752, 0.11851406 -0.033272147 -0.16939019, 0.1184454 -0.033296481 -0.16937281, 0.11846551 -0.033270389 -0.16943969, 0.11849503 -0.033257812 -0.16945496, 0.11841121 -0.033314437 -0.16937162, 0.11843321 -0.03328231 -0.16944243, 0.11845994 -0.033253908 -0.16949569, 0.11840236 -0.033297777 -0.16944633, 0.11843105 -0.033263847 -0.1695036, 0.1184268 -0.033245325 -0.16956209, 0.11840352 -0.033276349 -0.16951241, 0.11689688 -0.0333018 -0.17310812, 0.11685888 -0.033315122 -0.17310672, 0.11693643 -0.033293724 -0.17310946, 0.11697197 -0.033291101 -0.17317426, 0.11696169 -0.033291131 -0.173237, 0.11688171 -0.033295989 -0.17331366, 0.11693187 -0.033291027 -0.17333414, 0.11683309 -0.033310741 -0.17329359, 0.11678776 -0.033334732 -0.17327514, 0.11537856 -0.033290878 -0.17712754, 0.1153283 -0.03329587 -0.1771069, 0.11527981 -0.033310547 -0.17708696, 0.11523439 -0.033334494 -0.17706834, 0.11529464 -0.033286124 -0.17726675, 0.11518408 -0.033234835 -0.17754088, 0.11521538 -0.033244073 -0.17749141, 0.11521737 -0.033228695 -0.1775264, 0.11520706 -0.033282399 -0.17737035, 0.11523984 -0.03327167 -0.17738537, 0.11517113 -0.033296004 -0.1773681, 0.11519133 -0.033269897 -0.17743485, 0.1152208 -0.033257321 -0.17744999, 0.11513706 -0.033314005 -0.17736678, 0.11515887 -0.033281863 -0.17743765, 0.11518569 -0.033253506 -0.17749096, 0.1151282 -0.03329736 -0.17744152, 0.11515683 -0.033263341 -0.17749876, 0.11515246 -0.033244848 -0.17755727, 0.11512937 -0.033275962 -0.1775075, 0.11034831 -0.033300996 -0.18909836, 0.11031045 -0.033314347 -0.18909703, 0.11038788 -0.033292949 -0.18909965, 0.1104234 -0.033290207 -0.1891645, 0.11041322 -0.033290446 -0.18922722, 0.11033316 -0.033295214 -0.18930386, 0.11038342 -0.033290252 -0.18932453, 0.11028457 -0.033309951 -0.18928403, 0.11023933 -0.033333972 -0.18926543, 0.10883005 -0.033289969 -0.19311754, 0.10877979 -0.033294991 -0.193097, 0.1087312 -0.033309788 -0.19307704, 0.10868588 -0.033333763 -0.19305858, 0.10874605 -0.03328526 -0.19325688, 0.10863562 -0.033233941 -0.19353132, 0.10866687 -0.033243224 -0.19348165, 0.10866894 -0.033227921 -0.19351666, 0.10865852 -0.033281609 -0.19336054, 0.10869136 -0.03327094 -0.19337568, 0.1086227 -0.03329514 -0.19335827, 0.10864279 -0.033269033 -0.19342497, 0.10867235 -0.033256456 -0.19344029, 0.10858849 -0.033313155 -0.19335705, 0.10861048 -0.033280954 -0.19342789, 0.10863724 -0.033252701 -0.19348106, 0.10857961 -0.033296511 -0.19343171, 0.10860832 -0.033262432 -0.19348888, 0.10860403 -0.033243954 -0.19354753, 0.1085808 -0.033275053 -0.19349775, 0.10711737 -0.033272326 -0.19690512, 0.10714135 -0.03327018 -0.19690454, 0.10713115 -0.033285722 -0.19699165, 0.10703625 -0.03331387 -0.19709216, 0.10707422 -0.033300579 -0.19709335, 0.1071137 -0.033292621 -0.19709481, 0.10714914 -0.03328979 -0.19715963, 0.10713905 -0.03328985 -0.19722232, 0.10705888 -0.033294678 -0.19729897, 0.10710922 -0.03328979 -0.19731963, 0.10701044 -0.033309519 -0.19727908, 0.10696496 -0.033333406 -0.19726045, 0.10555588 -0.033289671 -0.20111273, 0.10550557 -0.033294559 -0.20109223, 0.10545687 -0.033309162 -0.20107232, 0.10541151 -0.033333182 -0.20105372, 0.10547172 -0.033284798 -0.20125218, 0.10536139 -0.033233568 -0.20152648, 0.10539268 -0.033242688 -0.20147689, 0.10539465 -0.033227503 -0.20151173, 0.10538428 -0.033281147 -0.20135556, 0.10541706 -0.033270419 -0.2013707, 0.10534839 -0.033294737 -0.20135342, 0.10536863 -0.03326866 -0.2014202, 0.1053981 -0.033256039 -0.20143552, 0.1053142 -0.033312708 -0.20135212, 0.10533629 -0.033280611 -0.20142291, 0.10536288 -0.033252239 -0.2014762, 0.10530548 -0.033296049 -0.20142685, 0.10533401 -0.033262029 -0.20148414, 0.10532974 -0.033243537 -0.2015426, 0.10530661 -0.033274651 -0.20149289, 0.10384309 -0.033271819 -0.20490032, 0.10383935 -0.033292025 -0.20509, 0.10386717 -0.033269629 -0.20489982, 0.10385685 -0.033285215 -0.20498671, 0.10376199 -0.033313468 -0.20508723, 0.10380007 -0.033300146 -0.20508842, 0.10387491 -0.033289447 -0.20515479, 0.10386474 -0.033289343 -0.20521738, 0.1037847 -0.033294335 -0.205294, 0.10383497 -0.033289328 -0.20531453, 0.10373615 -0.033308983 -0.20527415, 0.10369071 -0.033332944 -0.20525554, 0.10228157 -0.033289179 -0.20910789, 0.10223126 -0.033294082 -0.20908742, 0.10218275 -0.033308879 -0.20906748, 0.10213737 -0.033332646 -0.20904902, 0.10219757 -0.033284396 -0.20924726, 0.10208708 -0.033233091 -0.20952143, 0.10211834 -0.03324227 -0.20947199, 0.10212049 -0.033226982 -0.20950691, 0.10211007 -0.0332807 -0.20935085, 0.1021429 -0.033270016 -0.20936595, 0.10207412 -0.033294231 -0.20934846, 0.10209429 -0.033268213 -0.20941524, 0.10212386 -0.033255577 -0.20943062, 0.10203996 -0.033312306 -0.20934741, 0.10206187 -0.03328 -0.20941807, 0.10208881 -0.033251897 -0.20947136, 0.10203123 -0.033295646 -0.20942201, 0.1020599 -0.033261612 -0.20947923, 0.10205555 -0.033243164 -0.20953776, 0.10203232 -0.033274159 -0.20948794, 0.097294718 -0.033270985 -0.22089058, 0.097318739 -0.033268914 -0.22088996, 0.097308546 -0.03328447 -0.22097698, 0.097213537 -0.033312604 -0.22107741, 0.097251505 -0.033299416 -0.22107881, 0.097291023 -0.033291385 -0.22108003, 0.097326547 -0.033288643 -0.22114506, 0.097316295 -0.033288524 -0.22120777, 0.097236276 -0.033293501 -0.22128427, 0.097286612 -0.033288628 -0.22130495, 0.097187787 -0.033308312 -0.22126451, 0.097142369 -0.033332139 -0.22124594, 0.096696317 -0.033288389 -0.22274633, 0.096645981 -0.033293411 -0.22272578, 0.096597344 -0.033308044 -0.22270577, 0.096552044 -0.033332035 -0.22268716, 0.096639425 -0.033283874 -0.22288194, 0.096504152 -0.033041552 -0.22376633, 0.096563309 -0.033031687 -0.22374102, 0.096547216 -0.033275604 -0.22300726, 0.096596748 -0.033269927 -0.22301784, 0.096558541 -0.033227175 -0.22323734, 0.096498847 -0.033289805 -0.22299826, 0.096453339 -0.033312351 -0.22299093, 0.096509486 -0.03323178 -0.22323504, 0.096461326 -0.033244416 -0.2232348, 0.096415609 -0.033264875 -0.22323662, 0.096513927 -0.033153132 -0.22348022, 0.09656325 -0.03315118 -0.22347398, 0.096625477 -0.03303422 -0.22372179, 0.096465677 -0.033162758 -0.22348937, 0.096420169 -0.033180088 -0.22350106, 0.10052575 -0.03329967 -0.21308364, 0.10048772 -0.033312902 -0.21308245, 0.10056521 -0.033291712 -0.21308495, 0.10060073 -0.033288941 -0.21314998, 0.1005906 -0.033288971 -0.2132125, 0.10051049 -0.033293858 -0.21328939, 0.1005608 -0.033288971 -0.21330978, 0.10046197 -0.03330864 -0.21326925, 0.10041657 -0.033332556 -0.21325094, 0.099007383 -0.033288747 -0.21710302, 0.098957077 -0.03329362 -0.21708249, 0.098908499 -0.033308476 -0.21706249, 0.09886314 -0.033332393 -0.21704386, 0.09892334 -0.033284009 -0.21724236, 0.098812953 -0.033232749 -0.21751654, 0.098844185 -0.033241928 -0.21746707, 0.098846331 -0.033226639 -0.21750194, 0.098835841 -0.033280402 -0.21734595, 0.098868653 -0.033269554 -0.217361, 0.098799929 -0.033293918 -0.21734363, 0.098820105 -0.033267796 -0.21741039, 0.098849609 -0.033255205 -0.21742573, 0.09876588 -0.033311889 -0.21734254, 0.098787799 -0.033279687 -0.21741331, 0.098814502 -0.033251315 -0.21746647, 0.098757043 -0.033295184 -0.21741712, 0.098785594 -0.033261165 -0.21747425, 0.098781332 -0.033242717 -0.21753287, 0.098758116 -0.033273727 -0.21748304, 0.095678031 0.084655315 -0.26645929, 0.090554327 0.083275974 -0.26921797, 0.090555757 0.083342135 -0.26923239, 0.095670998 0.084718972 -0.26647812, 0.089775816 0.082439616 -0.27089009, 0.094914705 0.083856285 -0.26814991, 0.089758024 0.082490727 -0.27094746, 0.094933718 0.083936989 -0.26822525, 0.089724258 0.082544222 -0.2710444, 0.094964504 0.083999246 -0.26831347, 0.089669213 0.082582638 -0.27118957, 0.095005304 0.084040105 -0.26840979, 0.095054239 0.084057212 -0.26850933, 0.089578375 0.082584783 -0.27141201, 0.095108867 0.084049851 -0.26860702, 0.089458883 0.082517743 -0.27168542, 0.089472398 0.082510874 -0.27170718, 0.089486107 0.082502529 -0.2717284, 0.09856528 0.087755769 -0.26025724, 0.093441442 0.086376503 -0.26301605, 0.093442872 0.086442664 -0.26303035, 0.098558202 0.087819502 -0.26027614, 0.092662901 0.085540116 -0.26468825, 0.097801909 0.086956844 -0.26194772, 0.092645168 0.085591346 -0.26474547, 0.097820848 0.087037593 -0.26202333, 0.092611402 0.085644662 -0.26484251, 0.0978515 0.087099895 -0.26211146, 0.092556298 0.085683376 -0.26498759, 0.097892359 0.087140635 -0.26220784, 0.097941369 0.087157816 -0.26230723, 0.09246552 0.085685462 -0.26521009, 0.097995937 0.087150514 -0.26240504, 0.092345998 0.085618392 -0.26548356, 0.092359513 0.085611403 -0.26550519, 0.092373192 0.085603267 -0.26552635, 0.1014524 0.090856358 -0.25405538, 0.096328512 0.089477107 -0.25681418, 0.096329957 0.089543223 -0.25682837, 0.10144533 0.090920106 -0.25407425, 0.095550105 0.088640764 -0.25848615, 0.10068905 0.090057254 -0.25574583, 0.095532358 0.08869192 -0.25854349, 0.10070801 0.090138078 -0.25582141, 0.095498562 0.088745266 -0.25864059, 0.10073867 0.090200454 -0.25590956, 0.095443428 0.08878383 -0.25878567, 0.10077949 0.090241268 -0.25600579, 0.10082857 0.090258285 -0.25610536, 0.09535256 0.088786066 -0.25900823, 0.10088316 0.090250999 -0.25620306, 0.095233098 0.088718936 -0.25928169, 0.095246732 0.088711947 -0.25930321, 0.095260277 0.088703677 -0.25932461, 0.10433954 0.093956888 -0.24785344, 0.099215627 0.092577577 -0.2506122, 0.099217147 0.092643827 -0.2506265, 0.10433245 0.094020605 -0.24787231, 0.098437205 0.091741338 -0.25228432, 0.10357617 0.093157783 -0.24954391, 0.098419443 0.091792479 -0.25234166, 0.10359523 0.093238711 -0.24961947, 0.098385707 0.091845885 -0.25243869, 0.10362577 0.093300968 -0.24970751, 0.098330542 0.091884419 -0.25258368, 0.10366665 0.093341723 -0.24980378, 0.10371563 0.093358994 -0.24990349, 0.098239675 0.091886535 -0.25280622, 0.10377029 0.093351543 -0.25000107, 0.098120138 0.09181945 -0.25307959, 0.098133817 0.091812626 -0.25310138, 0.098147526 0.0918044 -0.2531226, 0.10722663 0.097057536 -0.24165156, 0.10210279 0.09567824 -0.24441017, 0.10210429 0.095744357 -0.24442449, 0.10721965 0.097121194 -0.24167046, 0.10132436 0.094841763 -0.24608225, 0.10646325 0.096258298 -0.24334192, 0.10130656 0.094893038 -0.2461396, 0.10648225 0.096339226 -0.24341743, 0.10127281 0.09494625 -0.24623671, 0.10651289 0.096401572 -0.24350576, 0.10121778 0.094984919 -0.24638166, 0.10655387 0.096442312 -0.24360196, 0.10660283 0.096459448 -0.24370144, 0.10112689 0.094987139 -0.24660423, 0.10665728 0.096452147 -0.24379922, 0.10100737 0.094920069 -0.24687766, 0.1010209 0.094913214 -0.24689938, 0.10103464 0.0949049 -0.24692063, 0.115888 0.10635915 -0.22304554, 0.11076418 0.1049799 -0.22580431, 0.11076567 0.10504624 -0.2258185, 0.11588106 0.10642278 -0.2230645, 0.10998569 0.10414349 -0.22747657, 0.11512472 0.10556009 -0.22473617, 0.10996808 0.10419466 -0.22753379, 0.11514367 0.10564092 -0.22481175, 0.10993417 0.104248 -0.22763076, 0.11517437 0.10570309 -0.22489972, 0.10987923 0.10428664 -0.22777589, 0.11521521 0.10574402 -0.22499594, 0.11526407 0.10576117 -0.22509561, 0.10978815 0.10428879 -0.22799836, 0.11531878 0.10575376 -0.22519326, 0.1096687 0.10422179 -0.22827183, 0.10968229 0.10421488 -0.22829361, 0.10969588 0.10420665 -0.22831483, 0.11287284 0.10724416 -0.22127451, 0.11801188 0.10866074 -0.21853411, 0.11285505 0.10729539 -0.22133188, 0.11803088 0.10874149 -0.21860953, 0.1128213 0.10734878 -0.2214289, 0.11806159 0.10880379 -0.21869791, 0.11276622 0.10738717 -0.22157401, 0.11810236 0.10884456 -0.21879411, 0.11815129 0.10886167 -0.21889359, 0.11267534 0.10738933 -0.22179638, 0.1182059 0.10885441 -0.21899135, 0.11255603 0.10732229 -0.22206983, 0.11256942 0.10731542 -0.22209151, 0.11258309 0.10730727 -0.2221128, 0.10678166 0.10112131 -0.23447369, 0.10679521 0.10111435 -0.23449543, 0.10680886 0.10110594 -0.23451677, 0.10709859 0.10104294 -0.23367834, 0.11223759 0.10245954 -0.23093799, 0.10708083 0.10109408 -0.23373592, 0.11225653 0.10254034 -0.23101352, 0.1070471 0.10114749 -0.23383281, 0.1122873 0.10260259 -0.23110175, 0.1069921 0.10118601 -0.23397784, 0.11232805 0.10264346 -0.23119809, 0.10690118 0.10118826 -0.23420036, 0.11237694 0.10266064 -0.23129749, 0.1124317 0.10265318 -0.23139526, 0.11300091 0.10325857 -0.22924763, 0.10787702 0.10187955 -0.2320064, 0.10787861 0.10194558 -0.23202063, 0.11299406 0.10332222 -0.22926641, 0.14573999 -0.022878662 -0.14045268, 0.14586793 -0.022661686 -0.14035839, 0.14582001 -0.022897214 -0.14043242, 0.14592172 -0.022652447 -0.14034444, 0.14586736 -0.022655204 -0.140347, 0.14579724 -0.022662863 -0.14038196, 0.1457759 -0.022655219 -0.14037931, 0.1456662 -0.022858024 -0.14048994, 0.1457767 -0.022660747 -0.14038998, 0.14569066 -0.022638425 -0.14042929, 0.14568929 -0.022633463 -0.14041868, 0.14614545 -0.02251862 -0.14032617, 0.14609396 -0.022554994 -0.14030777, 0.14614213 -0.022508025 -0.14031003, 0.14567909 -0.022633538 -0.14043559, 0.14561497 -0.022591934 -0.14046195, 0.14560334 -0.022836775 -0.1405414, 0.14561717 -0.022596896 -0.1404734, 0.14558569 -0.022569686 -0.14049663, 0.14555755 -0.022536069 -0.14050521, 0.14552386 -0.022551388 -0.14067906, 0.14556074 -0.022541583 -0.14051794, 0.14552496 -0.022659644 -0.14068297, 0.14551984 -0.022471756 -0.14056396, 0.14551537 -0.022465244 -0.14054912, 0.145504 -0.022405446 -0.14062403, 0.145509 -0.022422135 -0.1406384, 0.14551282 -0.022440195 -0.14064954, 0.14551739 -0.022468716 -0.14066187, 0.14549832 -0.022392899 -0.14060774, 0.14549255 -0.022384882 -0.14058994, 0.14549842 -0.022392839 -0.14060785, 0.14600123 -0.022927478 -0.14044875, 0.14590918 -0.022914156 -0.14042976, 0.14606629 -0.022786111 -0.14043009, 0.14555466 -0.022815943 -0.14060275, 0.14553499 -0.02280581 -0.14063762, 0.1455196 -0.022796139 -0.14067319, 0.14612222 -0.022640109 -0.14039551, 0.14609659 -0.022566438 -0.1403247, 0.14614272 -0.022563815 -0.14036272, 0.14614637 -0.022533521 -0.14034143, 0.14604472 -0.02260232 -0.1403259, 0.14603412 -0.022597671 -0.14031146, 0.14603589 -0.022607431 -0.14032653, 0.1459565 -0.022642493 -0.14033723, 0.14595549 -0.022634596 -0.14032421, 0.14581427 -0.023328289 -0.14046897, 0.14572106 -0.023317799 -0.14048007, 0.14563306 -0.023307949 -0.14051306, 0.14555502 -0.023299202 -0.14056589, 0.14549156 -0.02329208 -0.14063567, 0.14544617 -0.023287028 -0.14071834, 0.14594726 -0.022636801 -0.14030042, 0.14585598 -0.022660837 -0.14033344, 0.14593022 -0.022649139 -0.14028534, 0.14584653 -0.022670045 -0.14032322, 0.14595823 -0.022630841 -0.1403102, 0.14586221 -0.022656173 -0.14033967, 0.1458381 -0.022677779 -0.14031217, 0.14576776 -0.022670493 -0.14035466, 0.14575319 -0.022676855 -0.14034811, 0.14607251 -0.022539973 -0.14019851, 0.14598751 -0.022624373 -0.14022021, 0.14604399 -0.022572622 -0.14016904, 0.14586617 -0.022654638 -0.14034477, 0.14577125 -0.022661477 -0.14036533, 0.14577353 -0.02265656 -0.14037202, 0.1456895 -0.022653133 -0.14038348, 0.14566712 -0.022656083 -0.14037392, 0.14577527 -0.022654921 -0.14037728, 0.14613755 -0.022502527 -0.14029601, 0.14568914 -0.022641391 -0.1403991, 0.14613149 -0.022500172 -0.14028145, 0.14612412 -0.022500515 -0.14026718, 0.14611657 -0.022503346 -0.14025462, 0.14568841 -0.022635102 -0.14040886, 0.14561625 -0.022619322 -0.1404072, 0.14558481 -0.022617444 -0.14038911, 0.14568876 -0.022632942 -0.14041618, 0.14561497 -0.022602677 -0.14043123, 0.14561367 -0.022593975 -0.14044671, 0.14555176 -0.022572026 -0.14042392, 0.14551012 -0.022563368 -0.14039254, 0.145614 -0.022591129 -0.14045788, 0.14555299 -0.022549272 -0.14045851, 0.14555359 -0.022538066 -0.14048122, 0.14555579 -0.022534758 -0.14049847, 0.1454784 -0.022490203 -0.14043163, 0.14546974 -0.022523642 -0.14038891, 0.14543483 -0.022479534 -0.14038073, 0.14545541 -0.022412911 -0.14046651, 0.14548726 -0.022457525 -0.14048049, 0.14547002 -0.022388011 -0.14051832, 0.14549467 -0.022442818 -0.14051591, 0.14548035 -0.022381052 -0.14055231, 0.14548655 -0.022381276 -0.14057153, 0.14610432 -0.022511005 -0.14023668, 0.14600821 -0.022604614 -0.14024186, 0.14603281 -0.022584915 -0.14026533, 0.14604835 -0.022576958 -0.1402835, 0.14591749 -0.022659913 -0.14026886, 0.1459651 -0.02262938 -0.14031826, 0.098231897 -0.010691896 -0.23910558, 0.090373456 0.0045758188 -0.24793412, 0.090586871 0.0045104027 -0.24789642, 0.098159716 -0.010945112 -0.2389591, 0.090182513 0.0046812296 -0.24799518, 0.098159745 -0.011205971 -0.23880827, 0.10941757 -0.033554316 -0.22588514, 0.094716907 -0.03355433 -0.22588515, 0.0899055 0.0049881041 -0.24817257, 0.090023845 0.0048209429 -0.24807601, 0.098231867 -0.011459276 -0.23866174, 0.099101499 -0.012126103 -0.23827611, 0.098819688 -0.012033746 -0.23832951, 0.098571599 -0.011885449 -0.2384152, 0.098371908 -0.011690289 -0.23852816, 0.099101543 -0.01002489 -0.23949119, 0.10466853 0.0044883639 -0.24788371, 0.098371938 -0.010460898 -0.23923908, 0.090811849 0.0044882894 -0.24788345, 0.098571733 -0.010265604 -0.23935197, 0.098819733 -0.010117397 -0.23943767, 0.090811819 0.0062196255 -0.24888475, 0.098865315 0.050975606 -0.27476516, 0.10445242 0.0062197745 -0.24888472, 0.090588748 0.0061978996 -0.24887209, 0.085008681 0.050975531 -0.27476501, 0.090376973 0.0061333627 -0.24883491, 0.084783733 0.050997719 -0.27477795, 0.090187132 0.0060298145 -0.24877493, 0.084570348 0.051063165 -0.27481568, 0.090028584 0.0058921278 -0.24869539, 0.084379464 0.051168412 -0.27487665, 0.08983624 0.0055436194 -0.24849392, 0.084102303 0.051475376 -0.27505416, 0.089909673 0.0057274401 -0.24860014, 0.084220737 0.05130817 -0.27495739, 0.093378633 0.081925526 -0.28180346, 0.093378663 0.083440468 -0.28256083, 0.093017906 0.083501533 -0.28243849, 0.093017995 0.081986651 -0.28168106, 0.092700571 0.083599523 -0.28224248, 0.092700571 0.082084671 -0.28148505, 0.092444718 0.083728537 -0.28198421, 0.092444748 0.082213774 -0.28122684, 0.092265427 0.083881363 -0.2816788, 0.092265397 0.082366601 -0.28092152, 0.09217304 0.084048972 -0.2813437, 0.092173159 0.082533941 -0.28058636, 0.092173189 0.084221378 -0.2809988, 0.09217304 0.082706556 -0.28024137, 0.092265546 0.084388718 -0.28066373, 0.092265487 0.082873866 -0.27990651, 0.092444777 0.084541425 -0.2803582, 0.092444718 0.083026633 -0.27960086, 0.092700571 0.084670559 -0.28009996, 0.092700586 0.083155781 -0.27934265, 0.09301804 0.084768564 -0.27990401, 0.093017876 0.083253875 -0.27914682, 0.093378648 0.084829718 -0.2797817, 0.093378544 0.08331497 -0.27902439, 0.12460758 0.11697787 -0.21547674, 0.12460753 0.11546303 -0.21471956, 0.12424697 0.11552423 -0.21459712, 0.12424688 0.117039 -0.2153544, 0.12392934 0.11562228 -0.21440129, 0.12392938 0.11713712 -0.21515843, 0.12367369 0.11575133 -0.21414302, 0.12367357 0.11726612 -0.21490027, 0.12349451 0.11590402 -0.2138375, 0.12349439 0.11741878 -0.21459472, 0.12340207 0.11607158 -0.21350239, 0.12340212 0.11758627 -0.21425974, 0.12340212 0.11624397 -0.21315742, 0.12340212 0.11775877 -0.21391475, 0.12349446 0.1164113 -0.21282251, 0.12349434 0.11792621 -0.21357982, 0.12367363 0.11656412 -0.21251698, 0.12367369 0.11807886 -0.21327426, 0.12392947 0.1166933 -0.2122587, 0.12392934 0.11820814 -0.21301605, 0.12424691 0.11679122 -0.21206288, 0.12424691 0.11830601 -0.2128201, 0.12460744 0.11685254 -0.21194041, 0.12460756 0.11836721 -0.21269774, 0.099793911 0.078494892 -0.27856088, 0.096952751 0.076874793 -0.27762413, 0.092515364 0.077220157 -0.27782384, 0.092513278 0.076773539 -0.27756572, 0.096718997 0.076801255 -0.2775816, 0.11371681 -0.033039108 -0.21406561, 0.096583247 0.076780304 -0.2775695, 0.10487825 -0.033039153 -0.21406558, 0.096447825 0.076773509 -0.2775656, 0.091949478 0.07677348 -0.27756563, 0.091666117 0.076803401 -0.27758291, 0.091396108 0.076893404 -0.27763489, 0.091275334 0.076958477 -0.27767253, 0.091134191 0.077060997 -0.27773178, 0.091167644 0.077034131 -0.2777164, 0.09886466 0.07932052 -0.27318251, 0.09901534 0.07945928 -0.27326274, 0.10223041 0.080818266 -0.27404869, 0.11638115 -0.032538787 -0.20849912, 0.098673955 0.079208791 -0.27311796, 0.10721394 -0.032538876 -0.20849894, 0.098415658 0.079124719 -0.2730692, 0.10019194 0.080818266 -0.27404869, 0.098145366 0.079097077 -0.27305332, 0.093647137 0.079097107 -0.27305332, 0.093541279 0.07910116 -0.2730557, 0.093435779 0.079113677 -0.27306286, 0.093271509 0.079150394 -0.27308413, 0.10369204 0.0052928627 -0.25048774, 0.098105013 0.050048769 -0.27636796, 0.094806477 0.076588586 -0.29167992, 0.094806179 0.076503888 -0.29165715, 0.094812527 0.076424941 -0.29162034, 0.096087977 0.07322523 -0.28763115, 0.097889021 0.05178 -0.2773692, 0.098649263 0.052706957 -0.27576637, 0.096049592 0.073720545 -0.28786016, 0.096054956 0.074282974 -0.28800094, 0.09611097 0.074888438 -0.28802967, 0.09621945 0.075501665 -0.28793243, 0.096375704 0.076083526 -0.28770998, 0.096568733 0.076597959 -0.28737932, 0.096784115 0.077019811 -0.28696895, 0.096927673 0.077236921 -0.28667748, 0.097070813 0.07741046 -0.28637564, 0.10727338 0.090328529 -0.26499531, 0.10743886 0.088544965 -0.26410365, 0.12601072 0.11045104 -0.22474502, 0.108106 0.091222927 -0.26320639, 0.10827158 0.089439139 -0.26231465, 0.12617613 0.10866743 -0.22385322, 0.13434075 0.11939681 -0.20685114, 0.12684338 0.11134537 -0.22295609, 0.12700894 0.1095617 -0.22206429, 0.13448173 0.11758679 -0.20601203, 0.15382391 -0.023893058 -0.1364691, 0.1540892 -0.022592872 -0.13646902, 0.15446746 -0.022635579 -0.13646901, 0.15557143 -0.027689993 -0.13646947, 0.15573259 -0.027458698 -0.13646951, 0.15566383 -0.027582556 -0.13646951, 0.15545948 -0.027776718 -0.13646951, 0.14677596 -0.028762758 -0.13646965, 0.1470889 -0.032993048 -0.13647003, 0.15071084 -0.026827902 -0.13646938, 0.15035458 -0.026692778 -0.13646938, 0.15577488 -0.027323514 -0.13646936, 0.15578921 -0.027182579 -0.13646951, 0.14978813 -0.026190981 -0.13646939, 0.14677109 -0.028323427 -0.13646948, 0.14961101 -0.025853515 -0.13646933, 0.15004089 -0.026476279 -0.13646936, 0.15413758 -0.026476204 -0.13646947, 0.15439035 -0.026190937 -0.13646927, 0.15382399 -0.026692703 -0.1364693, 0.15308921 -0.023711979 -0.13646911, 0.15108924 -0.023712009 -0.1364691, 0.15456738 -0.025853485 -0.13646939, 0.15346761 -0.026827961 -0.13646939, 0.15465875 -0.0254834 -0.13646927, 0.15578921 -0.024292886 -0.13646913, 0.15308928 -0.026873827 -0.13646947, 0.15465873 -0.025102317 -0.13646935, 0.1507109 -0.023757875 -0.13646913, 0.14851268 -0.022592887 -0.13646904, 0.15035458 -0.023893028 -0.13646913, 0.15004088 -0.024109557 -0.13646913, 0.14978822 -0.02439481 -0.13646924, 0.14961089 -0.024732202 -0.13646913, 0.15456744 -0.024732262 -0.13646916, 0.14609897 -0.032993004 -0.13646998, 0.14613529 -0.032668754 -0.13647003, 0.14813909 -0.022634402 -0.13646902, 0.14951973 -0.025483444 -0.13646924, 0.14627478 -0.024345934 -0.13646916, 0.14951976 -0.025102288 -0.13646924, 0.15574662 -0.023914635 -0.13646913, 0.15439034 -0.024394736 -0.13646917, 0.15562086 -0.023555219 -0.13646913, 0.14778389 -0.022757083 -0.13646904, 0.14746432 -0.022954687 -0.13646904, 0.14719583 -0.023217738 -0.13646898, 0.15541838 -0.023232877 -0.13646904, 0.15413755 -0.024109542 -0.13646911, 0.15514912 -0.022963732 -0.13646904, 0.15108924 -0.026873827 -0.13646941, 0.15482678 -0.022761196 -0.13646902, 0.15346755 -0.023757905 -0.13646914, 0.12124942 -0.033291072 -0.17365718, 0.12358516 -0.03329125 -0.16895629, 0.10682553 -0.033289358 -0.20605651, 0.13275236 -0.033291176 -0.16895626, 0.13743354 -0.033291727 -0.15829408, 0.13964839 -0.033292145 -0.15288849, 0.13981521 -0.03329207 -0.15278935, 0.11297628 -0.033288315 -0.22274631, 0.11362126 -0.033288687 -0.21675034, 0.11376929 -0.033288687 -0.21661609, 0.13732779 -0.033291742 -0.15806566, 0.11389041 -0.033288702 -0.21645573, 0.11345457 -0.033288732 -0.21684927, 0.11397992 -0.033288851 -0.2162803, 0.11327949 -0.033288687 -0.21690829, 0.10724689 -0.033289403 -0.20582701, 0.14008439 -0.03329207 -0.15249467, 0.14017391 -0.033292189 -0.15231943, 0.1373971 -0.033291757 -0.15909961, 0.13947342 -0.033292115 -0.15294711, 0.11310695 -0.033288732 -0.21692699, 0.11447747 -0.033288732 -0.2150654, 0.13930084 -0.033292219 -0.15296601, 0.13719349 -0.033291817 -0.15789849, 0.13705195 -0.033291817 -0.15778664, 0.13692677 -0.033291981 -0.15772305, 0.12304184 -0.033291206 -0.16906984, 0.12331158 -0.03329125 -0.16898467, 0.12079345 -0.033290982 -0.17370465, 0.12766072 -0.033290476 -0.1825318, 0.13014056 -0.033290789 -0.17664042, 0.12765051 -0.033290446 -0.18281011, 0.12999244 -0.033290848 -0.17677477, 0.12761092 -0.03329055 -0.1822795, 0.11456481 -0.033288792 -0.21452624, 0.1170436 -0.03328912 -0.20862095, 0.11455224 -0.033288732 -0.21479954, 0.13026166 -0.033290789 -0.17647997, 0.12757453 -0.033290446 -0.18308493, 0.11142671 -0.03328979 -0.19764243, 0.11376238 -0.033290029 -0.19294173, 0.11689562 -0.033289224 -0.2087554, 0.11451851 -0.033288836 -0.21427433, 0.11992238 -0.033290997 -0.17407614, 0.12292957 -0.033289954 -0.19294168, 0.12982573 -0.033290803 -0.17687368, 0.11716466 -0.033289164 -0.20846047, 0.12750518 -0.03329055 -0.18205109, 0.11672868 -0.033289075 -0.20885418, 0.11441475 -0.033288866 -0.2140422, 0.13035119 -0.033290774 -0.1763047, 0.11725427 -0.033289075 -0.2082852, 0.12965073 -0.033290774 -0.17693245, 0.11655375 -0.033289135 -0.20891297, 0.12034376 -0.033290997 -0.17384654, 0.11638115 -0.033289105 -0.20893194, 0.11427915 -0.033288807 -0.21386977, 0.11413388 -0.033288762 -0.21375361, 0.1139776 -0.033288881 -0.21367767, 0.11384507 -0.033288851 -0.21364348, 0.1137169 -0.033288881 -0.21363279, 0.12947811 -0.033290774 -0.17695129, 0.12737083 -0.03329055 -0.18188372, 0.12722918 -0.033290535 -0.1817722, 0.11775173 -0.033289194 -0.20707022, 0.12710401 -0.033290461 -0.1817084, 0.11321908 -0.033289954 -0.19305512, 0.11348887 -0.033289939 -0.19297011, 0.11097081 -0.03328982 -0.19768989, 0.14075768 -0.033292204 -0.15055138, 0.1432375 -0.033292666 -0.14466007, 0.14074759 -0.033292219 -0.15082981, 0.14070787 -0.033292279 -0.15029909, 0.14308944 -0.033292532 -0.14479439, 0.11009963 -0.033289701 -0.19806147, 0.14335859 -0.033292636 -0.1444995, 0.12452362 -0.033291414 -0.16566209, 0.12685944 -0.033291772 -0.16096109, 0.11783803 -0.033289194 -0.20651713, 0.12031782 -0.033289537 -0.20062575, 0.11782783 -0.033289164 -0.20679542, 0.13602656 -0.033291608 -0.16096105, 0.1406021 -0.033292219 -0.15007065, 0.14292273 -0.033292517 -0.14489321, 0.12016974 -0.033289418 -0.20076002, 0.11778818 -0.033289224 -0.20626487, 0.12043892 -0.033289537 -0.20046528, 0.11052109 -0.03328979 -0.19783187, 0.14274776 -0.033292547 -0.14495201, 0.10393979 -0.033288851 -0.21692707, 0.12000309 -0.033289567 -0.20085897, 0.11768232 -0.033289209 -0.20603649, 0.14046779 -0.033292204 -0.14990339, 0.14257506 -0.033292547 -0.14497094, 0.14032628 -0.033292279 -0.14979161, 0.12052843 -0.033289567 -0.20028996, 0.14020102 -0.033292308 -0.14972802, 0.11982812 -0.033289537 -0.20091783, 0.12631609 -0.033291653 -0.16107476, 0.12658598 -0.033291772 -0.16098952, 0.11965536 -0.033289552 -0.20093676, 0.12406775 -0.033291474 -0.16570926, 0.11754805 -0.033289254 -0.20586929, 0.11740643 -0.033289254 -0.20575747, 0.1172813 -0.033289343 -0.20569374, 0.1033964 -0.033288807 -0.21704067, 0.10366617 -0.033288702 -0.21695553, 0.13093492 -0.033290923 -0.17453675, 0.13341466 -0.033291161 -0.16864531, 0.13092482 -0.033290908 -0.17481504, 0.14717448 -0.033292845 -0.13924038, 0.14067151 -0.033292279 -0.15110435, 0.14344808 -0.033292636 -0.14432417, 0.14394565 -0.033292606 -0.14310926, 0.14402175 -0.033292681 -0.14283456, 0.14403196 -0.033292726 -0.14255625, 0.13088506 -0.033290938 -0.17428444, 0.1332666 -0.033291161 -0.16877954, 0.14398213 -0.033292726 -0.14230388, 0.13353586 -0.033291236 -0.16848491, 0.13084868 -0.033290908 -0.17508987, 0.14387628 -0.033292666 -0.14207552, 0.11703672 -0.033290446 -0.1849466, 0.12620384 -0.033290356 -0.18494648, 0.11470103 -0.033290148 -0.18964736, 0.13077939 -0.033290997 -0.17405592, 0.13309988 -0.033291146 -0.16887863, 0.14374194 -0.033292621 -0.1419083, 0.1231966 -0.033291414 -0.16608095, 0.13362539 -0.033291265 -0.16830944, 0.13292506 -0.03329128 -0.16893749, 0.14360052 -0.033292666 -0.14179657, 0.13064504 -0.033290997 -0.17388867, 0.13050354 -0.033290997 -0.17377697, 0.13037825 -0.033290997 -0.17371319, 0.1236181 -0.033291578 -0.16585144, 0.14347529 -0.033292785 -0.14173283, 0.11649328 -0.033290446 -0.18506007, 0.11676319 -0.033290431 -0.18497482, 0.11424495 -0.033290103 -0.1896947, 0.12111221 -0.033289686 -0.19852193, 0.12359206 -0.033289954 -0.19263074, 0.12110217 -0.033289596 -0.19880037, 0.12106237 -0.033289686 -0.19826972, 0.12344408 -0.033289999 -0.19276483, 0.11337398 -0.033290192 -0.19006635, 0.13013367 -0.033292085 -0.15296608, 0.12779799 -0.03329201 -0.15766698, 0.1237132 -0.033290014 -0.19247027, 0.12102599 -0.033289686 -0.19907515, 0.10721391 -0.03328912 -0.20893194, 0.10487826 -0.033288881 -0.21363272, 0.12095653 -0.033289537 -0.19804128, 0.12327722 -0.033289954 -0.19286402, 0.14594264 -0.033292979 -0.13676992, 0.14717458 -0.03329289 -0.13677005, 0.11379535 -0.033290148 -0.18983677, 0.12380269 -0.033290014 -0.19229482, 0.12959026 -0.03329213 -0.15307963, 0.12986018 -0.033292219 -0.15299436, 0.12734197 -0.033291936 -0.15771437, 0.12310226 -0.033289924 -0.19292283, 0.12082231 -0.03328976 -0.19787389, 0.12068076 -0.033289656 -0.1977623, 0.12055562 -0.033289805 -0.19769843, 0.12647088 -0.033291832 -0.15808582, 0.10667056 -0.03328912 -0.20904543, 0.10694051 -0.033289179 -0.20896031, 0.1044223 -0.033288866 -0.21368021, 0.12689234 -0.033291891 -0.15785617, 0.13420916 -0.033291385 -0.16654156, 0.13668899 -0.033291668 -0.16065028, 0.13419902 -0.033291236 -0.16681992, 0.13415928 -0.033291325 -0.16628936, 0.13654101 -0.033291727 -0.1607845, 0.13107218 -0.033292338 -0.14967188, 0.13340798 -0.033292592 -0.14497095, 0.13681017 -0.033291578 -0.16048983, 0.13412291 -0.03329131 -0.16709478, 0.12031086 -0.033290789 -0.17695132, 0.11797516 -0.033290654 -0.18165238, 0.10355128 -0.033288971 -0.21405174, 0.13405359 -0.033291385 -0.16606106, 0.13637421 -0.033291653 -0.16088338, 0.13286461 -0.033292592 -0.1450845, 0.13313438 -0.033292621 -0.14499927, 0.13061632 -0.033292338 -0.14971909, 0.13689969 -0.033291698 -0.16031435, 0.12974514 -0.033292338 -0.15009066, 0.13619916 -0.033291653 -0.16094232, 0.10397251 -0.033288911 -0.21382214, 0.13391924 -0.033291504 -0.16589345, 0.13377774 -0.033291385 -0.16578187, 0.13365251 -0.033291429 -0.16571815, 0.13016658 -0.033292368 -0.1498611, 0.11976759 -0.033290893 -0.17706504, 0.12003739 -0.033290908 -0.17697981, 0.11751933 -0.033290654 -0.18169971, 0.13434638 -0.033292666 -0.14167671, 0.13671958 -0.033293024 -0.1366291, 0.14600019 -0.033292904 -0.1366291, 0.12438646 -0.033290088 -0.19052695, 0.12686633 -0.033290461 -0.18463565, 0.12437637 -0.033290029 -0.19080529, 0.13610375 -0.033293024 -0.13675785, 0.13640957 -0.033292934 -0.13666137, 0.12433667 -0.033290133 -0.19027469, 0.12671819 -0.033290341 -0.18476987, 0.13389052 -0.033292681 -0.14172401, 0.12698744 -0.033290461 -0.1844752, 0.12430026 -0.033289999 -0.19108006, 0.10815251 -0.033289313 -0.20563781, 0.11048825 -0.033289611 -0.20093679, 0.13301933 -0.0332928 -0.14209552, 0.13344075 -0.033292681 -0.14186598, 0.12655151 -0.033290312 -0.18486884, 0.12423094 -0.033290133 -0.19004628, 0.12707695 -0.033290341 -0.18429989, 0.11664818 -0.03329055 -0.1820713, 0.11706956 -0.033290535 -0.18184169, 0.12637646 -0.033290341 -0.18492763, 0.10769653 -0.033289298 -0.20568511, 0.12409653 -0.033290088 -0.18987879, 0.1239551 -0.033290133 -0.18976732, 0.12382984 -0.033290133 -0.18970357, 0.10994489 -0.033289611 -0.20105034, 0.11021467 -0.033289582 -0.20096517, 0.1374834 -0.033291757 -0.15854648, 0.13996325 -0.0332921 -0.15265508, 0.13747332 -0.033291772 -0.15882476, 0.14553927 -0.024877295 -0.14005628, 0.14595516 -0.024367988 -0.13917994, 0.14649981 -0.028731868 -0.13665645, 0.14551814 -0.024900541 -0.14010146, 0.14549804 -0.024917603 -0.14014558, 0.14546889 -0.024931714 -0.1402127, 0.14543982 -0.024929509 -0.14028469, 0.14541455 -0.024909124 -0.1403518, 0.14539199 -0.024870053 -0.1404174, 0.14537545 -0.024821982 -0.14047113, 0.14536092 -0.024756044 -0.14052464, 0.12859613 0.10877563 -0.21797368, 0.14536399 -0.024020076 -0.14071833, 0.1290348 0.10924667 -0.21703123, 0.14534725 -0.024645641 -0.14058834, 0.14533965 -0.024368659 -0.14068252, 0.14794859 -0.035280421 -0.13517022, 0.14664558 -0.035280183 -0.14017026, 0.14794861 -0.035280183 -0.14017022, 0.1363219 -0.035280511 -0.13517009, 0.13056172 -0.035280287 -0.13903821, 0.13049434 -0.035280302 -0.13909382, 0.13039817 -0.035280377 -0.13923848, 0.1304393 -0.035280377 -0.13916135, 0.11058313 -0.035275385 -0.22822781, 0.094387323 -0.035275623 -0.22717068, 0.094330192 -0.035275549 -0.22822794, 0.11087376 -0.034191206 -0.22948046, 0.11083932 -0.033998296 -0.22961697, 0.11092442 -0.034356296 -0.22931163, 0.11098666 -0.034483001 -0.22912487, 0.11122748 -0.034647614 -0.2284918, 0.11316043 -0.033886015 -0.22398049, 0.11322135 -0.033913434 -0.2238242, 0.11328502 -0.033922464 -0.22366579, 0.097053036 0.076738015 -0.29356033, 0.097065002 0.076912716 -0.29357913, 0.097068906 0.076313406 -0.29340571, 0.097091585 0.077120259 -0.29357067, 0.097124547 0.077294007 -0.29353756, 0.097165942 0.077460155 -0.29348192, 0.097233564 0.077667072 -0.29337373, 0.097323462 0.077872366 -0.29321045, 0.097406298 0.078014091 -0.29304674, 0.097494856 0.078126863 -0.29286164, 0.099606663 0.072877333 -0.28626925, 0.099575847 0.073246107 -0.28644526, 0.099572092 0.073637128 -0.28656137, 0.099590719 0.073985845 -0.28661138, 0.099636346 0.074386954 -0.28660977, 0.099706322 0.074783444 -0.2865473, 0.099787027 0.075119972 -0.28644222, 0.09995921 0.07564567 -0.28616545, 0.10019329 0.076137781 -0.28572839, 0.10045865 0.076505065 -0.28518093, 0.14727508 -0.034652308 -0.14047013, 0.14735626 -0.033927038 -0.14047001, 0.1464736 -0.028360575 -0.1367695, 0.14597698 -0.024382845 -0.13906974, 0.14597696 -0.024383083 -0.13676924, 0.11982645 0.10950042 -0.21654138, 0.14522365 -0.023145139 -0.13983808, 0.12866512 0.10950045 -0.21654138, 0.13812673 -0.032276526 -0.13455784, 0.13753521 -0.0323589 -0.13451028, 0.13815224 -0.0323589 -0.13451028, 0.13812172 -0.032176748 -0.13461554, 0.13813853 -0.032060996 -0.13468254, 0.1381955 -0.031885996 -0.13478363, 0.13855647 -0.031311288 -0.1351161, 0.14606324 -0.033256367 -0.1364855, 0.14604828 -0.033186838 -0.13654108, 0.14603165 -0.033283696 -0.136555, 0.146092 -0.033214495 -0.13642679, 0.14602032 -0.03323707 -0.13659568, 0.14611819 -0.033157542 -0.13637824, 0.14607155 -0.033125326 -0.13650073, 0.14599016 -0.033271894 -0.13665955, 0.14613757 -0.033096835 -0.13634755, 0.14608869 -0.033058718 -0.13647734, 0.14615017 -0.033038706 -0.13633259, 0.14596553 -0.033287972 -0.13671532, 0.14615798 -0.032980785 -0.13632928, 0.14616115 -0.032926381 -0.13633661, 0.14616047 -0.032881781 -0.13635041, 0.14615712 -0.03284283 -0.13636935, 0.080016583 0.076424941 -0.2916204, 0.080070645 0.075967953 -0.2913563, 0.10390818 0.0035614818 -0.24948645, 0.093742698 -0.033554256 -0.22802415, 0.10854159 -0.033554196 -0.22802424, 0.090811819 0.0035614073 -0.24948646, 0.090572566 0.0035865307 -0.249501, 0.085008681 0.05178009 -0.27736926, 0.090347201 0.0036605 -0.24954401, 0.090148717 0.0037791878 -0.24961245, 0.089988768 0.0039353371 -0.24970268, 0.08987689 0.004120037 -0.2498095, 0.084015965 0.05080992 -0.27680826, 0.084016055 0.051018611 -0.27692887, 0.084073752 0.050607339 -0.27669105, 0.084185809 0.050422564 -0.27658424, 0.084769368 0.051754773 -0.27735472, 0.089819193 0.0043227077 -0.24992679, 0.089819074 0.0045314431 -0.25004745, 0.089876771 0.0047340989 -0.25016457, 0.084544033 0.051680759 -0.27731195, 0.084345639 0.051562294 -0.27724349, 0.084185809 0.051406041 -0.27715299, 0.084073752 0.051221266 -0.27704605, 0.090811849 0.0052927136 -0.25048769, 0.085008681 0.050048679 -0.27636796, 0.084769458 0.050073773 -0.27638257, 0.090572417 0.0052676201 -0.25047308, 0.084544033 0.050147787 -0.27642533, 0.090346962 0.0051935613 -0.25043023, 0.084345669 0.050266281 -0.27649388, 0.090148687 0.0050750375 -0.25036168, 0.089988858 0.0049188733 -0.25027144, 0.1015421 -0.015138522 -0.24102592, 0.10206138 -0.014637738 -0.24131557, 0.11019498 -0.034276545 -0.22995912, 0.10090014 -0.015518248 -0.24080646, 0.10242844 -0.014044404 -0.24165857, 0.094208479 -0.034276634 -0.22995919, 0.10017252 -0.015755087 -0.24066946, 0.10262227 -0.013392806 -0.24203551, 0.10263176 -0.012719721 -0.24242462, 0.092905834 0.065191969 -0.28747755, 0.096424565 0.076035157 -0.29374784, 0.092728436 0.065852493 -0.28785956, 0.09237355 0.066457242 -0.2882092, 0.09186174 0.066970691 -0.28850624, 0.091222823 0.067363352 -0.28873312, 0.090493977 0.067612141 -0.28887713, 0.089717567 0.06770286 -0.28892958, 0.088938653 0.067629904 -0.2888875, 0.088202417 0.067397788 -0.28875318, 0.080437928 0.076035097 -0.29374775, 0.087551773 0.067019895 -0.28853467, 0.08702454 0.066518292 -0.28824455, 0.086651415 0.065921754 -0.28789961, 0.086453855 0.065265477 -0.28752017, 0.086443484 0.064587295 -0.28712797, 0.095869482 0.083476186 -0.28360742, 0.096388042 0.083726287 -0.28310698, 0.09685041 0.078825191 -0.29291084, 0.095234811 0.083286881 -0.28398603, 0.096761823 0.084023684 -0.28251237, 0.12586892 0.11951904 -0.21151221, 0.1201624 0.12066607 -0.20921758, 0.13616307 0.12156746 -0.20741473, 0.12509465 0.1195723 -0.21140552, 0.094519138 0.083169043 -0.28422177, 0.12431411 0.11954123 -0.21146755, 0.12357309 0.11942749 -0.21169478, 0.12291442 0.11923802 -0.21207432, 0.12237632 0.11898316 -0.21258354, 0.11912487 0.12031266 -0.20992441, 0.1219902 0.11867835 -0.21319354, 0.11989692 0.12063818 -0.20927325, 0.080492973 0.078825042 -0.29291078, 0.11943321 0.12051222 -0.20952524, 0.1192555 0.12041974 -0.20971023, 0.11965032 0.12058616 -0.20937751, 0.12799086 0.11756118 -0.21542838, 0.13647887 0.12138294 -0.20778358, 0.13649909 0.12141693 -0.20771606, 0.1364857 0.12147774 -0.20759419, 0.13650045 0.12144767 -0.20765424, 0.13649152 0.12139964 -0.20775022, 0.13645633 0.12150523 -0.20753901, 0.13641402 0.12152909 -0.20749152, 0.12820257 0.11789842 -0.21475363, 0.13636033 0.12154812 -0.20745327, 0.13629802 0.12156126 -0.20742695, 0.12822755 0.1182486 -0.21405315, 0.12806465 0.11859138 -0.2133677, 0.12772298 0.11890657 -0.21273705, 0.12722242 0.11917607 -0.2121979, 0.12659226 0.11938432 -0.21178161, 0.13694929 0.11969769 -0.20624901, 0.13710184 0.11954817 -0.2065485, 0.13704343 0.11962852 -0.20638756, 0.13683246 0.11975205 -0.20614053, 0.13669154 0.11979459 -0.2060554, 0.13653585 0.11982249 -0.20599926, 0.13637635 0.11983536 -0.20597386, 0.13629363 0.11983627 -0.20597191, 0.11973228 0.11888714 -0.2078701, 0.11939086 0.1188152 -0.20801416, 0.11866327 0.11843659 -0.20877168, 0.11909035 0.11871293 -0.20821883, 0.11884429 0.11858477 -0.20847511, 0.11359352 0.11134526 -0.22295608, 0.11335412 0.11133236 -0.222982, 0.11312884 0.11129412 -0.2230586, 0.11293039 0.11123288 -0.22318099, 0.11277057 0.1111521 -0.22334245, 0.11265855 0.11105676 -0.2235333, 0.11359353 0.11045098 -0.22474502, 0.11335422 0.11046402 -0.22471899, 0.11312884 0.11050221 -0.22464256, 0.094856098 0.091222882 -0.26320642, 0.11293039 0.1105634 -0.22451995, 0.11277056 0.11064425 -0.22435875, 0.094616815 0.091209799 -0.26323247, 0.11265847 0.11073959 -0.22416769, 0.09439142 0.091171607 -0.26330897, 0.11260074 0.11084428 -0.22395839, 0.094193056 0.091110334 -0.26343143, 0.1126008 0.11095217 -0.22374274, 0.094856158 0.090328485 -0.2649954, 0.094616875 0.090341508 -0.26496941, 0.09439148 0.090379745 -0.26489288, 0.094193086 0.090440989 -0.26477039, 0.094033226 0.090521634 -0.26460904, 0.093921199 0.09061709 -0.26441818, 0.093863517 0.090721726 -0.26420873, 0.093863457 0.090829551 -0.26399308, 0.093921155 0.090934336 -0.26378369, 0.094033226 0.091029599 -0.26359287, 0.13723898 0.11960615 -0.20655635, 0.13726704 0.11963886 -0.2065673, 0.13728695 0.11967617 -0.20658161, 0.1372038 0.11957979 -0.20654894, 0.1372976 0.11971627 -0.20659828, 0.13716356 0.11956066 -0.20654584, 0.13713323 0.11955225 -0.20654608, 0.088505894 0.066452339 -0.28371465, 0.088433772 0.066705778 -0.28386116, 0.088433772 0.066966608 -0.28401196, 0.088505924 0.067219839 -0.28415832, 0.088645905 0.067450777 -0.2842921, 0.08884576 0.067646101 -0.28440499, 0.089093715 0.067794293 -0.2844907, 0.089375466 0.06788674 -0.28454417, 0.084225446 0.052379295 -0.27557695, 0.084383875 0.052517161 -0.27565652, 0.084033072 0.052031055 -0.27537546, 0.084106535 0.052214652 -0.2754817, 0.085008711 0.052706987 -0.27576631, 0.089375526 0.065785483 -0.28332901, 0.089093715 0.065877989 -0.28338253, 0.08478561 0.052685127 -0.27575362, 0.08884576 0.066026166 -0.28346825, 0.088645965 0.066221431 -0.28358114, 0.084573776 0.052620754 -0.2757163, 0.093462348 0.080293849 -0.28060773, 0.093180597 0.080341712 -0.28051224, 0.082304686 0.077410191 -0.28637564, 0.092932582 0.080418184 -0.28035906, 0.092732891 0.080519021 -0.28015733, 0.092592835 0.080638245 -0.2799187, 0.092520714 0.080769137 -0.27965692, 0.092520535 0.080904022 -0.27938738, 0.092592761 0.08103478 -0.27912581, 0.092732728 0.081154123 -0.27888718, 0.094856158 0.08854486 -0.2641035, 0.09461695 0.088557839 -0.2640776, 0.093462348 0.081379369 -0.27843681, 0.093180522 0.081331611 -0.27853239, 0.094391346 0.088596165 -0.26400119, 0.092932701 0.081255034 -0.27868524, 0.094193101 0.08865726 -0.26387864, 0.094033316 0.08873792 -0.26371735, 0.093921289 0.088833377 -0.26352632, 0.093863398 0.088938147 -0.26331705, 0.093863383 0.089045897 -0.26310137, 0.13730583 0.11778818 -0.20560944, 0.13728188 0.11782491 -0.20553555, 0.1372094 0.11789322 -0.20539905, 0.13710187 0.11795521 -0.20527484, 0.13696405 0.1180061 -0.20517325, 0.13680574 0.11804186 -0.20510173, 0.1366211 0.1180619 -0.20506157, 0.13642351 0.11806172 -0.20506193, 0.11359358 0.1086674 -0.22385319, 0.11335424 0.10868037 -0.22382735, 0.12469138 0.11383146 -0.21352385, 0.11312875 0.10871851 -0.22375081, 0.094856068 0.089439213 -0.26231468, 0.12440951 0.11387908 -0.21342827, 0.11293039 0.10877979 -0.22362845, 0.09461689 0.089426175 -0.26234072, 0.11277056 0.10886046 -0.22346689, 0.094391465 0.089388028 -0.26241717, 0.11265858 0.10895585 -0.22327605, 0.11260088 0.10906051 -0.22306672, 0.094193116 0.08932665 -0.26253968, 0.1135935 0.10956158 -0.22206438, 0.1241615 0.11395568 -0.21327509, 0.12396161 0.11405656 -0.21307339, 0.12382162 0.11417596 -0.21283492, 0.11260083 0.10916841 -0.22285102, 0.12029888 0.1171533 -0.2068789, 0.1241616 0.11479251 -0.2116015, 0.12440956 0.11486904 -0.21144828, 0.12469135 0.11491683 -0.21135266, 0.11885498 0.11666249 -0.20786077, 0.11998774 0.11712314 -0.20693922, 0.11265846 0.10927318 -0.22264153, 0.1127705 0.10936853 -0.22245063, 0.11293037 0.10944925 -0.22228938, 0.11312887 0.10951054 -0.22216694, 0.11335415 0.1095486 -0.22209038, 0.12374946 0.1143067 -0.21257308, 0.12374951 0.11444157 -0.21230362, 0.12382163 0.11457223 -0.21204184, 0.12396164 0.11469162 -0.21180321, 0.11968413 0.11706713 -0.20705141, 0.11905207 0.11682095 -0.20754349, 0.11933434 0.11696017 -0.20726539, 0.093921095 0.089150578 -0.26289195, 0.094033197 0.089246005 -0.26270109, 0.14827536 -0.021593034 -0.13446897, 0.14978813 -0.024394989 -0.13446915, 0.15004091 -0.024109676 -0.13446915, 0.147792 -0.021646738 -0.13446906, 0.14733241 -0.02180548 -0.13446903, 0.14691874 -0.022061199 -0.13446891, 0.14657134 -0.022401646 -0.13446909, 0.14961106 -0.024732426 -0.13446915, 0.14951992 -0.025102466 -0.13446929, 0.14951982 -0.025483698 -0.13446927, 0.15596083 -0.022072896 -0.13446902, 0.15413769 -0.024109721 -0.13446906, 0.15630919 -0.022421256 -0.1344689, 0.15554371 -0.021810785 -0.1344689, 0.15507865 -0.021648094 -0.13446893, 0.1496111 -0.025853664 -0.13446927, 0.15673405 -0.023303375 -0.13446905, 0.15439039 -0.024394944 -0.13446905, 0.15678924 -0.023793012 -0.13446905, 0.15657142 -0.022838458 -0.13446902, 0.15458922 -0.021593004 -0.13446891, 0.15382403 -0.023893192 -0.13446905, 0.15456754 -0.024732515 -0.1344692, 0.15346749 -0.023757964 -0.13446903, 0.15308918 -0.026873887 -0.13446942, 0.14972885 -0.032526284 -0.13446999, 0.15645939 -0.028331891 -0.13446955, 0.15108931 -0.026874036 -0.13446942, 0.15465863 -0.025102407 -0.13446927, 0.15004091 -0.026476398 -0.1344694, 0.15035449 -0.026692837 -0.13446935, 0.1507109 -0.02682811 -0.13446938, 0.14932321 -0.032847703 -0.13446999, 0.15308918 -0.023712009 -0.13446906, 0.14978816 -0.0261911 -0.13446942, 0.15465862 -0.025483549 -0.13446926, 0.15678926 -0.027737901 -0.13446942, 0.14899968 -0.033251673 -0.13446999, 0.15456744 -0.025853664 -0.13446942, 0.15673251 -0.028013945 -0.13446954, 0.15657146 -0.02824524 -0.13446954, 0.15666367 -0.028137743 -0.13446954, 0.15677495 -0.027878806 -0.13446954, 0.15439032 -0.026190996 -0.13446936, 0.14863424 -0.034421921 -0.13447008, 0.1485811 -0.034580514 -0.13447013, 0.14861821 -0.034484416 -0.13447011, 0.14864431 -0.034358442 -0.13446999, 0.14865957 -0.034222186 -0.13447011, 0.15413761 -0.026476368 -0.13446932, 0.14877446 -0.033717573 -0.13446996, 0.15108933 -0.023712128 -0.13446905, 0.153824 -0.026692942 -0.13446929, 0.13733508 -0.03253293 -0.13447003, 0.13714051 -0.032605067 -0.13446999, 0.15071093 -0.023758024 -0.13446917, 0.15346755 -0.026828006 -0.13446945, 0.13695586 -0.032724872 -0.13446999, 0.13681996 -0.0328504 -0.13446999, 0.15035461 -0.023893222 -0.13446918, 0.1366943 -0.033001661 -0.13447003, 0.13649699 -0.033269554 -0.13446999, 0.1364969 -0.034580514 -0.13447009, 0.13639854 0.11797164 -0.20479512, 0.12037839 0.11600126 -0.20606649, 0.13650309 0.11690973 -0.2042495, 0.12027392 0.11706313 -0.20661204, 0.12007505 0.11919349 -0.20770507, 0.12007497 0.12035048 -0.20828341, 0.13634226 -0.03315559 -0.1345396, 0.13653962 -0.032887772 -0.13453962, 0.13630222 -0.033201918 -0.13454367, 0.130476 -0.033201754 -0.13845605, 0.1187775 0.10939835 -0.21681744, 0.11426206 0.10818289 -0.21924871, 0.11277886 0.10856371 -0.22043285, 0.1039397 -0.032538399 -0.21649419, 0.0993433 0.077717885 -0.28025064, 0.11310685 -0.032538384 -0.21649414, 0.09017612 0.077717856 -0.28025058, 0.10016347 0.078241229 -0.27905095, 0.09972477 0.077769861 -0.2799933, 0.10268085 0.081595451 -0.27235895, 0.10815249 -0.033039629 -0.20607059, 0.093842179 0.081595406 -0.27235889, 0.11679408 -0.032737672 -0.20809662, 0.11729147 -0.032737613 -0.20688175, 0.102612 0.080870479 -0.27379131, 0.10556799 0.08469598 -0.26615697, 0.11142677 -0.033040047 -0.19807546, 0.096729338 0.084695965 -0.26615703, 0.11048825 -0.032539293 -0.20050392, 0.1051175 0.083918959 -0.2678467, 0.11965528 -0.032539204 -0.20050383, 0.095950454 0.083918929 -0.26784676, 0.10549903 0.083970994 -0.26758945, 0.12006827 -0.032738119 -0.20010157, 0.12056577 -0.032738075 -0.19888672, 0.1084553 0.087796435 -0.25995508, 0.11470097 -0.033040449 -0.19008033, 0.099616647 0.087796509 -0.25995505, 0.11376239 -0.032539755 -0.19250859, 0.10800469 0.087019548 -0.26164466, 0.1229296 -0.032539651 -0.19250886, 0.09883754 0.087019607 -0.26164478, 0.10838626 0.087071627 -0.26138741, 0.12334245 -0.032738477 -0.19210632, 0.12383999 -0.032738507 -0.19089147, 0.1113423 0.090897083 -0.25375307, 0.11797521 -0.033040926 -0.18208525, 0.10250363 0.090897068 -0.25375313, 0.11703666 -0.032540128 -0.1845136, 0.11089177 0.090120167 -0.25544286, 0.12620386 -0.032540172 -0.18451366, 0.10172449 0.090120181 -0.25544268, 0.1112733 0.090172201 -0.25518543, 0.12661672 -0.03273885 -0.18411115, 0.12711433 -0.032738999 -0.18289649, 0.11422943 0.093997687 -0.2475511, 0.12124942 -0.033041328 -0.17409003, 0.10539079 0.093997627 -0.24755122, 0.12031086 -0.032540619 -0.1765185, 0.1137789 0.093220741 -0.24924083, 0.12947804 -0.032540545 -0.17651847, 0.10461178 0.09322077 -0.24924086, 0.1141604 0.09327288 -0.24898362, 0.12989104 -0.032739311 -0.17611611, 0.13038844 -0.032739386 -0.17490123, 0.1171166 0.097098246 -0.24134925, 0.12452364 -0.03304179 -0.16609478, 0.10827793 0.097098187 -0.24134925, 0.12358522 -0.032541007 -0.16852333, 0.11666606 0.096321315 -0.243039, 0.13275242 -0.032540992 -0.16852333, 0.1074989 0.09632118 -0.24303892, 0.11704753 0.096373409 -0.24278162, 0.13316524 -0.032739773 -0.16812097, 0.13366267 -0.032739833 -0.1669061, 0.12000379 0.10019876 -0.2351473, 0.12779792 -0.033042207 -0.15809983, 0.11116494 0.1001987 -0.23514715, 0.12685935 -0.032541379 -0.16052833, 0.11955307 0.099421829 -0.23683693, 0.13602662 -0.03254129 -0.16052841, 0.11038603 0.099421814 -0.23683694, 0.11993469 0.099473834 -0.23657952, 0.13643944 -0.032740146 -0.16012587, 0.13693692 -0.032740206 -0.15891117, 0.12289087 0.10329929 -0.22894521, 0.13107215 -0.033042639 -0.15010473, 0.11405218 0.10329923 -0.22894527, 0.13013361 -0.032541826 -0.15253329, 0.12244032 0.10252234 -0.23063512, 0.13930081 -0.032541811 -0.15253322, 0.11327325 0.10252233 -0.23063493, 0.1228219 0.10257454 -0.23037773, 0.13971353 -0.032740489 -0.15213072, 0.14021122 -0.032740772 -0.15091591, 0.12577799 0.10639979 -0.22274336, 0.13434638 -0.033043057 -0.14210953, 0.11693928 0.10639989 -0.22274332, 0.13340785 -0.032542408 -0.14453799, 0.12532739 0.10562292 -0.2244329, 0.14257507 -0.032542214 -0.14453825, 0.1161603 0.10562292 -0.22443299, 0.12570903 0.10567494 -0.2241756, 0.14298788 -0.032740965 -0.14413579, 0.14348534 -0.0327411 -0.14292087, 0.14585626 -0.032599136 -0.13651027, 0.1367197 -0.032842889 -0.13636947, 0.12821464 0.10872346 -0.21823107, 0.11904752 0.1087234 -0.21823101, 0.11847866 0.1198068 -0.20937063, 0.080008298 0.077335671 -0.29143175, 0.11847861 0.11864991 -0.20879221, 0.079947889 0.077257112 -0.29155484, 0.079846829 0.078319311 -0.29235703, 0.079901278 0.077177078 -0.29163969, 0.079977959 0.077299818 -0.29149511, 0.07975623 0.078205585 -0.29254359, 0.07961902 0.077640891 -0.29309291, 0.079638094 0.07736516 -0.293217, 0.079871893 0.07584931 -0.29151848, 0.07966277 0.077068433 -0.29327503, 0.079684466 0.076838851 -0.29327196, 0.079707503 0.076616198 -0.29322898, 0.07972458 0.076464489 -0.29317579, 0.079742014 0.076320276 -0.29310423, 0.093557119 -0.033686921 -0.22796497, 0.093560815 -0.033710286 -0.22793826, 0.093551755 -0.033657119 -0.22801384, 0.093542457 -0.033616692 -0.22811443, 0.093667865 -0.0346407 -0.22756678, 0.093634278 -0.034640744 -0.22819018, 0.09353292 -0.033585712 -0.228237, 0.093624711 -0.034630939 -0.22834811, 0.093613625 -0.034602195 -0.22850329, 0.093595505 -0.034530357 -0.22871383, 0.093512625 -0.033991426 -0.22931555, 0.093574643 -0.034421727 -0.22891197, 0.093544453 -0.034229457 -0.22913834, 0.14553344 -0.023197919 -0.13949181, 0.13886617 -0.031363979 -0.1347698, 0.14633888 -0.022211879 -0.13476905, 0.14572601 -0.022962078 -0.1396648, 0.14633898 -0.022211447 -0.14016908, 0.14590327 -0.022745013 -0.13989988, 0.14827535 -0.021293044 -0.13476895, 0.15458921 -0.02129297 -0.13476881, 0.15458916 -0.02129288 -0.13646877, 0.14827539 -0.021292567 -0.14016891, 0.15458925 -0.021292686 -0.14016885, 0.15708929 -0.023792908 -0.13646911, 0.15708911 -0.023792937 -0.1347691, 0.15708929 -0.027737871 -0.1347696, 0.15708931 -0.027737379 -0.14016953, 0.15708931 -0.023792461 -0.14016916, 0.14894235 -0.034391508 -0.14017005, 0.14895761 -0.034255221 -0.14017011, 0.14894234 -0.03439182 -0.13477015, 0.1489576 -0.034255683 -0.13477015, 0.14988755 -0.032780915 -0.13477004, 0.15661807 -0.028586075 -0.14016953, 0.1566181 -0.028586522 -0.13476962, 0.14988743 -0.032780334 -0.14017001, 0.13621818 -0.03464283 -0.13455498, 0.13045502 -0.033391625 -0.13842487, 0.13024475 -0.034642756 -0.13856626, 0.13621826 -0.033391729 -0.13455491, 0.13043773 -0.033392608 -0.13843656, 0.14604232 -0.024156183 -0.13676921, 0.14604233 -0.024155945 -0.13906971, 0.14696352 -0.023028016 -0.13676906, 0.14558297 -0.024718344 -0.14016913, 0.14696358 -0.023027688 -0.14016911, 0.14599884 -0.024209142 -0.13929306, 0.14603746 -0.024161935 -0.13915251, 0.14602281 -0.024179786 -0.13922778, 0.14673109 -0.022837818 -0.14046901, 0.14657132 -0.022401184 -0.14046893, 0.14709425 -0.022481918 -0.14046894, 0.14573216 -0.024061203 -0.14046918, 0.14972878 -0.032525823 -0.14046994, 0.15577684 -0.028285637 -0.14046949, 0.15645945 -0.028331488 -0.14046951, 0.15588738 -0.022858471 -0.14046898, 0.15596092 -0.022072405 -0.14046897, 0.15630931 -0.022420838 -0.14046897, 0.15657137 -0.022837982 -0.1404691, 0.15552318 -0.022494167 -0.14046897, 0.15554374 -0.021810472 -0.14046894, 0.15616146 -0.023294508 -0.14046906, 0.15673411 -0.023302987 -0.14046912, 0.15508717 -0.022220314 -0.14046894, 0.15507865 -0.021647632 -0.14046894, 0.15633158 -0.023780748 -0.1404691, 0.15678926 -0.02379258 -0.14046909, 0.15460101 -0.022050202 -0.14046894, 0.15458918 -0.021592528 -0.14046897, 0.1487745 -0.033717155 -0.14046995, 0.1486595 -0.034221739 -0.1404701, 0.14864418 -0.034358084 -0.14047007, 0.14860785 -0.034515202 -0.14046995, 0.14853093 -0.034668371 -0.14047004, 0.14842832 -0.03478986 -0.14047019, 0.14831413 -0.034877181 -0.14047006, 0.14710185 -0.033691481 -0.14046997, 0.14932311 -0.032847211 -0.14046994, 0.14899969 -0.033251092 -0.14047006, 0.15638927 -0.024292558 -0.14046922, 0.15408926 -0.021992505 -0.14046896, 0.14818695 -0.034938306 -0.1404701, 0.14806655 -0.034970134 -0.1404701, 0.15638919 -0.027182221 -0.14046946, 0.14794856 -0.034980148 -0.14047022, 0.15678924 -0.027737409 -0.14046951, 0.15636276 -0.027444035 -0.14046952, 0.14688221 -0.034980282 -0.14047, 0.15628392 -0.027694955 -0.14046948, 0.15677494 -0.027878314 -0.14046951, 0.15673251 -0.028013498 -0.14046946, 0.15615626 -0.027925014 -0.14046958, 0.15666379 -0.028137296 -0.14046952, 0.15657146 -0.028244764 -0.14046958, 0.15598486 -0.028124645 -0.14046949, 0.14827541 -0.021592468 -0.14046891, 0.14851262 -0.021992505 -0.1404689, 0.14800732 -0.022048727 -0.14046901, 0.14779203 -0.021646202 -0.14046898, 0.14752673 -0.022214577 -0.1404691, 0.14733231 -0.021804929 -0.14046888, 0.1469187 -0.022060722 -0.14046893, 0.15561815 -0.028030992 -0.14016953, 0.15561815 -0.02803126 -0.13676953, 0.14694695 -0.033434555 -0.14016996, 0.15408923 -0.022292793 -0.13676897, 0.14851265 -0.022292838 -0.13676897, 0.15608926 -0.024292499 -0.14016916, 0.15608919 -0.024292797 -0.13676919, 0.15603906 -0.023847491 -0.14016916, 0.15603904 -0.023847759 -0.13676921, 0.15589124 -0.023424774 -0.14016916, 0.15589114 -0.023425013 -0.13676909, 0.1556529 -0.02304551 -0.14016905, 0.15565279 -0.023045838 -0.13676918, 0.15533617 -0.022728965 -0.14016895, 0.15533619 -0.022729069 -0.13676894, 0.154957 -0.02249065 -0.14016892, 0.15495697 -0.022490799 -0.13676897, 0.15453431 -0.022342637 -0.14016907, 0.15453425 -0.022342861 -0.13676909, 0.15608922 -0.027182624 -0.13676943, 0.15608923 -0.027182281 -0.1401695, 0.15702659 -0.023236647 -0.13646902, 0.15702656 -0.023236215 -0.14016905, 0.15684167 -0.022708192 -0.13646899, 0.15684165 -0.02270776 -0.14016905, 0.15654376 -0.022234038 -0.13646905, 0.15654382 -0.022233814 -0.14016911, 0.15614787 -0.021838233 -0.13646898, 0.15614794 -0.021837935 -0.14016895, 0.15567392 -0.021540448 -0.13646886, 0.15567389 -0.021540105 -0.14016889, 0.15514556 -0.021355554 -0.13646886, 0.15514547 -0.021355197 -0.14016892, 0.15702659 -0.023236662 -0.1347691, 0.15684162 -0.022708252 -0.13476908, 0.15654376 -0.022234216 -0.13476895, 0.15614796 -0.021838412 -0.13476904, 0.15567389 -0.021540537 -0.13476895, 0.1551455 -0.021355614 -0.13476895, 0.13639669 -0.033315852 -0.13448001, 0.13641226 -0.034587786 -0.13447736, 0.1363294 -0.034609452 -0.13449895, 0.13631389 -0.033348843 -0.13450482, 0.13626467 -0.033370242 -0.13452734, 0.13625202 -0.034644663 -0.13453411, 0.1304574 -0.03332679 -0.13842836, 0.13625097 -0.033305705 -0.13454175, 0.13046438 -0.033263177 -0.13843894, 0.13627529 -0.03325285 -0.13454032, 0.14772622 -0.021354064 -0.13476899, 0.14772622 -0.021353692 -0.14016888, 0.14720367 -0.021534383 -0.1347689, 0.14720376 -0.021533981 -0.14016896, 0.1467337 -0.021824986 -0.13476896, 0.14673372 -0.021824658 -0.14016891, 0.14727934 -0.022718161 -0.14016902, 0.14727922 -0.022718415 -0.13676897, 0.14765534 -0.022485629 -0.14016904, 0.14765531 -0.022485957 -0.13676895, 0.14807326 -0.022341713 -0.13676895, 0.14807327 -0.022341356 -0.14016905, 0.084032208 0.051654682 -0.27515781, 0.084008604 0.051842913 -0.27526671, 0.089835286 0.0051672906 -0.24827626, 0.089811921 0.0053556263 -0.24838512, 0.094623566 -0.033554256 -0.22585776, 0.094652921 -0.03355436 -0.22587273, 0.094684511 -0.033554345 -0.22588199, 0.09373638 -0.033554286 -0.22802415, 0.09814541 0.079293981 -0.2737098, 0.092727557 0.077591732 -0.27711478, 0.092927411 0.077693835 -0.27691033, 0.093647137 0.079293922 -0.2737098, 0.093460202 0.077820122 -0.27665794, 0.093176529 0.077771589 -0.27675503, 0.09811914 0.079075441 -0.27811849, 0.098640069 0.079539269 -0.27368605, 0.096942529 0.077716321 -0.27733254, 0.099816665 0.080898494 -0.27447188, 0.092756882 0.079539016 -0.27427176, 0.09149766 0.077535808 -0.27756274, 0.093172476 0.079334423 -0.27396482, 0.090830818 0.080243304 -0.27591327, 0.089364633 0.078668877 -0.27906263, 0.09002924 0.078425825 -0.27849627, 0.090475753 0.078224316 -0.27815011, 0.090962067 0.077931717 -0.27783909, 0.091464043 0.07756263 -0.27757823, 0.099890396 0.080963045 -0.27453864, 0.09819293 0.079139933 -0.27818513, 0.099980935 0.081005305 -0.27460194, 0.098283499 0.079182222 -0.2782484, 0.10008357 0.081022948 -0.27465844, 0.098385826 0.079200029 -0.27830493, 0.098223075 0.079307988 -0.27369037, 0.096638441 0.077518091 -0.27731687, 0.098300681 0.079329088 -0.27367547, 0.098433778 0.079383284 -0.27366161, 0.096781507 0.077585101 -0.27730727, 0.098549753 0.07945551 -0.27366552, 0.096870989 0.077647343 -0.27731457, 0.093537703 0.079285458 -0.27374426, 0.091786578 0.077463046 -0.27741084, 0.093430877 0.079290092 -0.27378619, 0.091630504 0.077485427 -0.27748209, 0.093337417 0.079301894 -0.27383542, 0.093251541 0.079316393 -0.27389601, 0.089294314 0.078738987 -0.27906501, 0.090760469 0.080313385 -0.2759155, 0.089213625 0.078796342 -0.27905622, 0.090679839 0.080370918 -0.27590689, 0.089125991 0.078838885 -0.27903664, 0.090592265 0.080413401 -0.27588713, 0.1254196 0.11157991 -0.20909524, 0.12582372 0.11151136 -0.20923224, 0.12382171 0.11060333 -0.21104862, 0.12374949 0.11073413 -0.21078695, 0.12582372 0.11009158 -0.21207228, 0.12617937 0.1102013 -0.21185257, 0.12646608 0.11034609 -0.21156329, 0.12374952 0.11086887 -0.21051739, 0.12541951 0.11002307 -0.21220931, 0.12666681 0.1105172 -0.21122088, 0.12677029 0.11070496 -0.21084549, 0.12440947 0.11129636 -0.20966218, 0.12469129 0.11134411 -0.2095665, 0.12382177 0.11099964 -0.21025573, 0.12416151 0.11121982 -0.20981537, 0.12677027 0.11089806 -0.21045884, 0.12396172 0.11111909 -0.21001719, 0.12666677 0.11108579 -0.2100836, 0.12469128 0.11025876 -0.21173777, 0.12440959 0.11030644 -0.21164225, 0.12646595 0.11125702 -0.20974122, 0.12416159 0.11038305 -0.21148911, 0.12617937 0.11140162 -0.20945178, 0.12396172 0.11048394 -0.21128727, 0.093453884 0.07672222 -0.27881983, 0.0931651 0.076772705 -0.27871886, 0.092913046 0.076853588 -0.27855721, 0.092713252 0.076959565 -0.27834526, 0.09257789 0.077084437 -0.27809551, 0.092513219 0.076852992 -0.2776027, 0.092512339 0.076937109 -0.27762526, 0.12629212 0.1104874 -0.21351708, 0.12733592 0.11085957 -0.21277247, 0.12641384 0.11021405 -0.21215488, 0.12556303 0.11243609 -0.20866473, 0.12550417 0.11186439 -0.20885359, 0.12598792 0.11178225 -0.20901774, 0.12629214 0.11290461 -0.20868169, 0.12575296 0.11357155 -0.20830204, 0.12556303 0.11019234 -0.21315238, 0.12598804 0.11008257 -0.21241771, 0.12550408 0.11000052 -0.21258183, 0.125753 0.11058378 -0.21427844, 0.12641372 0.11165099 -0.20928058, 0.12733589 0.11253241 -0.20942624, 0.12675691 0.1114777 -0.20962708, 0.12699749 0.11127289 -0.21003702, 0.12791528 0.11199433 -0.21050225, 0.12712122 0.11104816 -0.21048628, 0.12791534 0.11139739 -0.21169652, 0.12712122 0.1108169 -0.21094917, 0.12699747 0.11059217 -0.21139857, 0.12675686 0.11038733 -0.21180825, 0.12232754 0.11390039 -0.20884101, 0.12316443 0.11407079 -0.20839691, 0.12312426 0.11414625 -0.20834911, 0.12238482 0.11383024 -0.20887829, 0.12405013 0.11080912 -0.21492143, 0.1240294 0.11081283 -0.21501705, 0.12402943 0.1142998 -0.20804204, 0.12312424 0.11096625 -0.21470997, 0.124007 0.11079758 -0.21511124, 0.12308063 0.11420895 -0.20828748, 0.12308061 0.11095469 -0.21479699, 0.12400699 0.11436594 -0.20797329, 0.12405004 0.11422111 -0.20809639, 0.12226523 0.11120634 -0.21429357, 0.12316442 0.11095922 -0.21462092, 0.12232745 0.11121228 -0.21421798, 0.1216082 0.1115379 -0.21363027, 0.1223848 0.11119978 -0.21413955, 0.12168555 0.11153628 -0.21357006, 0.12114787 0.11193016 -0.2128457, 0.12175669 0.11151688 -0.21350524, 0.12123567 0.11191949 -0.21280326, 0.12091075 0.11236022 -0.21198526, 0.12131642 0.111892 -0.21275523, 0.121004 0.11233987 -0.21196237, 0.12091085 0.11280319 -0.21109919, 0.12108983 0.11230315 -0.21193242, 0.12100397 0.11277281 -0.2110967, 0.12114793 0.11323339 -0.21023886, 0.12108983 0.1127267 -0.21108532, 0.12123562 0.11319293 -0.21025574, 0.12160839 0.11362566 -0.20945418, 0.12131642 0.11313806 -0.21026269, 0.12168549 0.1135764 -0.20948917, 0.12226534 0.11395729 -0.20879091, 0.12175667 0.11351311 -0.20951222, 0.12654628 0.11129026 -0.20969591, 0.12675801 0.11110991 -0.21005701, 0.12684569 0.11115015 -0.21003978, 0.12636364 0.11018376 -0.21207631, 0.12662342 0.11133963 -0.20966099, 0.12595274 0.11005692 -0.21233007, 0.12548605 0.11177593 -0.20889162, 0.12595281 0.11169672 -0.20904996, 0.12591258 0.1100499 -0.21224092, 0.125486 0.10997774 -0.21248832, 0.12546526 0.10997404 -0.21239257, 0.12591258 0.1116212 -0.20909773, 0.12636352 0.11156991 -0.20930357, 0.12544289 0.10998935 -0.21229829, 0.12630616 0.11149968 -0.20934093, 0.12624405 0.11144282 -0.20939091, 0.12669456 0.11035089 -0.21174201, 0.1254653 0.11169702 -0.20894609, 0.12630621 0.11017126 -0.21199776, 0.12586895 0.11155862 -0.20915924, 0.12586889 0.11006153 -0.21215378, 0.12544276 0.11163084 -0.20901474, 0.1269265 0.1105485 -0.21134661, 0.12662353 0.11033159 -0.21167742, 0.1262441 0.11017734 -0.21192218, 0.127046 0.11076528 -0.21091308, 0.12684572 0.110521 -0.21129844, 0.12654629 0.11032993 -0.21161701, 0.127046 0.11098842 -0.21046659, 0.12696017 0.11072856 -0.21088324, 0.12675813 0.11051029 -0.21125625, 0.12692654 0.11120516 -0.2100331, 0.12696017 0.11094241 -0.21045527, 0.12686712 0.11070815 -0.21086024, 0.12669453 0.11140287 -0.20963772, 0.12686718 0.11091188 -0.21045269, 0.12245168 0.11814526 -0.21314184, 0.094402552 0.082939208 -0.28356302, 0.095008075 0.083039045 -0.28336382, 0.12634589 0.1187425 -0.21194701, 0.12687911 0.1185663 -0.21229936, 0.12730254 0.11833841 -0.21275555, 0.12573387 0.11885646 -0.21171908, 0.12759157 0.11807156 -0.21328928, 0.12507863 0.11890158 -0.21162884, 0.096300229 0.083662346 -0.2821168, 0.12752914 0.11719996 -0.21503283, 0.12772967 0.11778158 -0.2138692, 0.12441827 0.11887529 -0.2116815, 0.12770835 0.11748526 -0.21446185, 0.095983982 0.08341068 -0.28261995, 0.12379122 0.11877908 -0.21187377, 0.095545143 0.083199173 -0.28304344, 0.12323375 0.11861858 -0.21219485, 0.12277849 0.11840317 -0.21262591, 0.099829599 -0.0076404959 -0.23642074, 0.10023384 -0.0077731758 -0.23634396, 0.098159716 -0.0092778355 -0.23547386, 0.098159716 -0.0090171397 -0.23562463, 0.10023384 -0.010521725 -0.23475458, 0.10058959 -0.010309234 -0.23487745, 0.1008762 -0.010029212 -0.23503931, 0.099829718 -0.010654464 -0.2346779, 0.098231867 -0.0087637752 -0.23577119, 0.10107692 -0.0096978396 -0.23523103, 0.099101469 -0.0080968291 -0.23615681, 0.098371834 -0.0085327625 -0.23590463, 0.10118051 -0.0093346089 -0.23544107, 0.098819658 -0.0081893504 -0.23610337, 0.098571762 -0.008337453 -0.23601763, 0.10118045 -0.0089603364 -0.23565741, 0.099101469 -0.010198161 -0.23494183, 0.10107704 -0.0085971802 -0.2358676, 0.098819688 -0.01010561 -0.23499529, 0.10087614 -0.0082657486 -0.23605905, 0.098571673 -0.0099572986 -0.23508085, 0.10058956 -0.007985726 -0.23622106, 0.098371908 -0.0097621828 -0.23519383, 0.098231837 -0.009531185 -0.23532735, 0.088645861 0.068149537 -0.28024673, 0.088505894 0.06838043 -0.28038037, 0.09010376 0.070271209 -0.28147364, 0.09050788 0.070138529 -0.28139687, 0.088433817 0.068633676 -0.28052676, 0.090863615 0.067602471 -0.27993047, 0.09115015 0.067882508 -0.2800923, 0.091350913 0.068213925 -0.28028399, 0.09050785 0.067389935 -0.27980763, 0.091454431 0.068577141 -0.28049397, 0.090103716 0.067257181 -0.2797308, 0.091454417 0.068951458 -0.28071034, 0.088433832 0.06889464 -0.28067756, 0.089375541 0.069814771 -0.28120989, 0.088505968 0.069147915 -0.28082412, 0.091351062 0.069314688 -0.28092051, 0.089375377 0.067713603 -0.27999479, 0.0890937 0.069722354 -0.2811563, 0.088645965 0.069378927 -0.2809577, 0.08884576 0.069574073 -0.28107059, 0.089093715 0.06780608 -0.28004813, 0.09115018 0.069645956 -0.28111207, 0.088845819 0.067954198 -0.28013384, 0.090863645 0.069925964 -0.28127402, 0.099973172 -0.0072625726 -0.23730145, 0.10039814 -0.007575497 -0.23662747, 0.10070229 -0.0073082298 -0.23776792, 0.10016318 -0.006969586 -0.23845661, 0.099973157 -0.011606127 -0.23478968, 0.10039814 -0.010866061 -0.23472451, 0.099914342 -0.011024922 -0.23463294, 0.10070229 -0.01198791 -0.23506185, 0.10016321 -0.01275377 -0.23511215, 0.10082392 -0.0078298301 -0.23648034, 0.10174608 -0.0080287308 -0.23735116, 0.1011671 -0.0081650764 -0.23628645, 0.1014076 -0.0085618943 -0.23605703, 0.10232539 -0.0090701729 -0.23674917, 0.10153146 -0.008996889 -0.2358055, 0.10153134 -0.0094447285 -0.23554645, 0.10232541 -0.010225892 -0.23608074, 0.1014076 -0.0098796338 -0.23529504, 0.10174607 -0.011267319 -0.23547859, 0.10116716 -0.010276362 -0.23506562, 0.10082413 -0.010611638 -0.23487173, 0.099914297 -0.0074165612 -0.23671941, 0.090976298 0.065923676 -0.28011474, 0.092020184 0.066644385 -0.28053153, 0.091098025 0.067300022 -0.27992481, 0.090247303 0.070649117 -0.28235435, 0.090188295 0.070495099 -0.28177226, 0.09067218 0.070336208 -0.28168049, 0.090976328 0.070603579 -0.282821, 0.090437204 0.070942134 -0.28350985, 0.090247184 0.066305593 -0.27984262, 0.090672165 0.067045525 -0.27977765, 0.090188295 0.066886738 -0.27968574, 0.090437204 0.065157846 -0.28016496, 0.091097951 0.07008183 -0.2815333, 0.092020154 0.06988287 -0.2824043, 0.091441184 0.069746464 -0.28133941, 0.091681629 0.069349855 -0.28111017, 0.092599422 0.068841547 -0.28180206, 0.091805488 0.06891498 -0.28085852, 0.092599317 0.067685828 -0.2811338, 0.091805488 0.068466857 -0.28059947, 0.091681644 0.068031996 -0.28034806, 0.091441244 0.067635313 -0.2801187, 0.10071629 -0.0078807026 -0.23632574, 0.10110469 -0.0081713349 -0.23621108, 0.10077374 -0.0078478307 -0.23639809, 0.10103358 -0.0081905723 -0.23614655, 0.10036291 -0.010776833 -0.23470436, 0.099896133 -0.010930076 -0.23461568, 0.099875435 -0.010834306 -0.23461767, 0.10095631 -0.0082225502 -0.23609503, 0.10116823 -0.0085720271 -0.23589312, 0.10125589 -0.0085574239 -0.23593435, 0.099896178 -0.0074491054 -0.23662864, 0.10036288 -0.0076022893 -0.23654, 0.10077377 -0.010531321 -0.23484628, 0.10032265 -0.0076455176 -0.23646171, 0.10065417 -0.0079273134 -0.23626588, 0.10032272 -0.010687456 -0.23470268, 0.099852964 -0.010741264 -0.23463877, 0.099875435 -0.0074985772 -0.23654656, 0.10110478 -0.010207966 -0.23503329, 0.10027908 -0.0077030212 -0.23639552, 0.10071643 -0.010452196 -0.23483865, 0.099853069 -0.0075633377 -0.23647645, 0.10027905 -0.010601327 -0.23471962, 0.10133679 -0.0098252743 -0.23525475, 0.10103364 -0.010142341 -0.235018, 0.10065427 -0.010377243 -0.23484921, 0.10145624 -0.0094057471 -0.23549722, 0.10125592 -0.009775579 -0.23523006, 0.1009564 -0.010081902 -0.23502003, 0.10145621 -0.008973524 -0.23574711, 0.10137041 -0.0093735605 -0.23546241, 0.10116813 -0.0097324997 -0.2352221, 0.10133685 -0.0085540712 -0.23598988, 0.10137041 -0.0089594424 -0.23570199, 0.10127731 -0.0093494803 -0.23544352, 0.10127719 -0.0089550167 -0.23567162, 0.097490922 -0.013293937 -0.23545079, 0.096675456 -0.012806773 -0.23573247, 0.098460317 -0.0068036914 -0.23911761, 0.097534344 -0.0070515126 -0.2390276, 0.098439589 -0.0067541599 -0.23919958, 0.098439619 -0.013504818 -0.23529573, 0.097574666 -0.013118401 -0.23546611, 0.097534403 -0.013207778 -0.23546751, 0.097574517 -0.0070945472 -0.2389494, 0.098460272 -0.013409182 -0.2352979, 0.096737653 -0.012731701 -0.23574305, 0.096018463 -0.012164891 -0.23610371, 0.096795022 -0.012652636 -0.23573533, 0.096095711 -0.012104422 -0.2361058, 0.095558077 -0.011405379 -0.23654282, 0.096166879 -0.012038738 -0.2360903, 0.095645815 -0.011362344 -0.23653483, 0.095321059 -0.010572657 -0.23702452, 0.095726639 -0.011312634 -0.23651016, 0.095414102 -0.010548651 -0.23700535, 0.09532097 -0.0097149909 -0.23752022, 0.095499963 -0.010516554 -0.23697057, 0.095414102 -0.0097105801 -0.23749003, 0.095558077 -0.0088822991 -0.23800181, 0.095499903 -0.0096964091 -0.23744483, 0.095645785 -0.0088969171 -0.23796041, 0.096018463 -0.008122921 -0.23844093, 0.095726669 -0.0089003295 -0.23790525, 0.096095711 -0.0081547648 -0.2383896, 0.096675441 -0.0074809045 -0.23881219, 0.09616679 -0.0081740767 -0.238325, 0.096737668 -0.0075273812 -0.23875238, 0.097490713 -0.0069936663 -0.23909388, 0.096795008 -0.0075604022 -0.23868008, 0.098417178 -0.013598055 -0.23527499, 0.098417208 -0.0066896826 -0.23926985, 0.090149552 0.067077234 -0.27967083, 0.09017016 0.066981614 -0.27966869, 0.090990454 0.070030898 -0.28137875, 0.091378838 0.069740385 -0.28126395, 0.091047794 0.070063919 -0.28145099, 0.091047794 0.067380264 -0.27989912, 0.090636998 0.067134693 -0.27975738, 0.09130767 0.069720954 -0.28119946, 0.091230541 0.069689125 -0.2811482, 0.091442242 0.069339827 -0.28094614, 0.091529921 0.069354311 -0.28098741, 0.09059675 0.067224145 -0.27975571, 0.090170175 0.070462555 -0.28168166, 0.090127051 0.067170367 -0.27969176, 0.090636998 0.070309252 -0.28159308, 0.091378868 0.067703709 -0.28008625, 0.090596855 0.070266128 -0.28151476, 0.090928227 0.069984287 -0.28131902, 0.090990469 0.067459375 -0.27989179, 0.090149552 0.070412964 -0.28159964, 0.090553194 0.067310408 -0.27977264, 0.09055315 0.070208535 -0.28144866, 0.0916107 0.068086341 -0.28030762, 0.090127021 0.070348471 -0.28152943, 0.09130761 0.067769244 -0.28007099, 0.090928227 0.067534402 -0.27990222, 0.091730237 0.068505988 -0.2805503, 0.091529965 0.068136081 -0.280283, 0.091230452 0.067829713 -0.2800729, 0.091730267 0.068938106 -0.28080022, 0.091644347 0.068538055 -0.28051531, 0.091442257 0.068179086 -0.28027499, 0.091610819 0.069357723 -0.2810427, 0.091644347 0.068952322 -0.28075492, 0.091551334 0.068562105 -0.28049648, 0.091551185 0.068956733 -0.28072459, 0.086949497 0.065104917 -0.28078556, 0.0877648 0.064617798 -0.28050381, 0.088734299 0.071107954 -0.28417051, 0.087808385 0.070860341 -0.28408065, 0.088713676 0.071157545 -0.28425252, 0.088713527 0.064406738 -0.28034884, 0.087848648 0.06479314 -0.28051901, 0.08780852 0.064703897 -0.28052068, 0.087848574 0.070817202 -0.2840023, 0.088734299 0.064502433 -0.28035092, 0.087011725 0.065180138 -0.28079593, 0.08629252 0.065746963 -0.28115666, 0.087069064 0.065259293 -0.28078842, 0.086369768 0.065807283 -0.2811588, 0.085832149 0.066506222 -0.28159571, 0.086440817 0.065872967 -0.28114331, 0.085919872 0.066549361 -0.28158772, 0.085595042 0.067339003 -0.28207743, 0.086000696 0.066598952 -0.28156316, 0.085688144 0.067362979 -0.28205833, 0.085595042 0.06819661 -0.28257322, 0.085774004 0.067395136 -0.28202358, 0.085688263 0.06820102 -0.28254294, 0.085832149 0.069029406 -0.28305471, 0.085774019 0.068215132 -0.28249788, 0.085919932 0.069014788 -0.28301358, 0.086292535 0.069788769 -0.28349388, 0.086000711 0.069011524 -0.28295827, 0.086369604 0.06975694 -0.28344256, 0.086949497 0.070430726 -0.28386521, 0.086440831 0.069737509 -0.28337801, 0.087011725 0.070384234 -0.28380537, 0.087764889 0.070917934 -0.2841469, 0.087068975 0.070351362 -0.28373295, 0.088691145 0.064313725 -0.28032792, 0.088691145 0.071222156 -0.28432274, 0.10066946 -0.014883906 -0.24059558, 0.10121249 -0.014562637 -0.2407814, 0.086949408 0.06545788 -0.28705382, 0.08711639 0.066013306 -0.28737509, 0.088178724 0.065631002 -0.28715396, 0.088086307 0.065306723 -0.28696644, 0.10005376 -0.015084326 -0.24047983, 0.086940587 0.064884126 -0.28672206, 0.088086307 0.064972818 -0.28677344, 0.088178575 0.064648688 -0.28658593, 0.088357866 0.064353049 -0.28641498, 0.090984643 0.067233056 -0.28808033, 0.091525257 0.06690082 -0.28788817, 0.088613689 0.064103067 -0.28627038, 0.088931084 0.063913345 -0.28616083, 0.10213466 -0.012515932 -0.24196495, 0.092408866 0.065395594 -0.28701782, 0.091958389 0.066466227 -0.28763691, 0.090367988 0.067443654 -0.28820214, 0.092258602 0.065954685 -0.28734106, 0.09901768 -0.014116585 -0.24103925, 0.098339647 -0.011735141 -0.2424165, 0.098083824 -0.011985004 -0.24227202, 0.097904623 -0.012280613 -0.2421011, 0.097812235 -0.012604788 -0.24191356, 0.089710981 0.06752032 -0.28824657, 0.097812265 -0.012938797 -0.24172044, 0.089051783 0.067458719 -0.28821087, 0.098657131 -0.01399827 -0.24110785, 0.097904652 -0.013263047 -0.24153292, 0.098339647 -0.013808519 -0.24121749, 0.089291751 0.066484779 -0.2876476, 0.088428915 0.067262262 -0.28809714, 0.098083824 -0.013558656 -0.24136198, 0.10212667 -0.013085514 -0.2416357, 0.088931143 0.066366404 -0.28757918, 0.099017739 -0.011426777 -0.2425946, 0.089291871 0.063795045 -0.28609219, 0.087878406 0.066942528 -0.2879124, 0.10196264 -0.013636887 -0.2413168, 0.088613689 0.066176623 -0.28746939, 0.098657101 -0.01154533 -0.24252617, 0.087432235 0.066517994 -0.28766692, 0.088357806 0.065926746 -0.28732499, 0.10165204 -0.014138937 -0.24102652, 0.099017739 -0.010676041 -0.24129607, 0.097812235 -0.012187868 -0.24042177, 0.097812235 -0.011853844 -0.24061489, 0.097904563 -0.011529684 -0.24080241, 0.099017724 -0.013365746 -0.23974088, 0.097904712 -0.012512192 -0.24023446, 0.098657086 -0.01324743 -0.23980927, 0.098657116 -0.01079452 -0.24122766, 0.098083794 -0.012807757 -0.24006343, 0.098083913 -0.011234075 -0.2409735, 0.098339647 -0.013057709 -0.23991898, 0.098339632 -0.010984123 -0.24111807, 0.089291751 0.067235589 -0.28634894, 0.089291751 0.064545944 -0.28479373, 0.088178694 0.065399632 -0.28528747, 0.088086441 0.065723777 -0.2854749, 0.088086277 0.066057757 -0.28566802, 0.08817859 0.066381931 -0.28585541, 0.088931143 0.064664319 -0.28486228, 0.088931113 0.067117304 -0.28628063, 0.088613689 0.064853981 -0.28497207, 0.088357955 0.065103963 -0.28511637, 0.088357866 0.066677511 -0.28602648, 0.088613659 0.066927522 -0.28617084, 0.079852074 0.077057838 -0.2917307, 0.07967186 0.078035817 -0.29273832, 0.079818904 0.076921195 -0.2918005, 0.079626501 0.077846855 -0.29292279, 0.07980153 0.076770872 -0.29184383, 0.079797924 0.076613978 -0.29185507, 0.079804718 0.076459244 -0.29183254, 0.079817742 0.076313734 -0.29177409, 0.11883318 0.11664462 -0.20741908, 0.11900103 0.11559749 -0.2067803, 0.11905482 0.11677435 -0.20716454, 0.11931027 0.11575855 -0.20648053, 0.1193746 0.11690125 -0.20691778, 0.11968815 0.11588526 -0.20625292, 0.11978704 0.1170035 -0.20672147, 0.11998922 0.1159513 -0.20614062, 0.11966655 0.11915049 -0.20779078, 0.11966655 0.12030753 -0.20836918, 0.11928703 0.11907054 -0.20795083, 0.11928707 0.12022752 -0.20852928, 0.1189532 0.11895677 -0.20817818, 0.1189532 0.12011394 -0.20875661, 0.11867963 0.11881457 -0.20846274, 0.11867973 0.11997163 -0.20904134, 0.14953472 -0.033060372 -0.13476998, 0.1495347 -0.03305988 -0.14017001, 0.14925344 -0.033411667 -0.13476995, 0.14925334 -0.033411101 -0.1401701, 0.1490577 -0.033816859 -0.13477018, 0.14905772 -0.033816382 -0.14017011, 0.14808835 -0.035270676 -0.13516061, 0.1481775 -0.035253689 -0.14017023, 0.14822838 -0.035240486 -0.13513029, 0.1484071 -0.035168812 -0.14017023, 0.14840539 -0.035169989 -0.13505995, 0.14857741 -0.035058066 -0.13494769, 0.14859587 -0.035042211 -0.14017017, 0.14873803 -0.034893915 -0.14017023, 0.14874862 -0.034880459 -0.13477015, 0.14884517 -0.034723207 -0.14017011, 0.14884172 -0.034730375 -0.13477015, 0.14890729 -0.034564912 -0.13477015, 0.14890945 -0.034557387 -0.14017011, 0.1570688 -0.027938753 -0.14016953, 0.1570688 -0.02793923 -0.13476959, 0.15700828 -0.02813217 -0.13476956, 0.15700823 -0.028131738 -0.14016955, 0.15690999 -0.02830869 -0.1401695, 0.15690987 -0.028309137 -0.13476956, 0.15677814 -0.028462231 -0.1401695, 0.15677808 -0.028462738 -0.13476959, 0.1560688 -0.027383894 -0.13676943, 0.15606876 -0.027383596 -0.14016953, 0.1560082 -0.027576983 -0.13676953, 0.1560082 -0.027576715 -0.14016953, 0.15590997 -0.027753621 -0.14016953, 0.15590997 -0.02775386 -0.13676941, 0.15577812 -0.027907163 -0.14016953, 0.15577812 -0.027907401 -0.13676944, 0.1131712 -0.032548726 -0.21648262, 0.099420786 0.077711925 -0.28023863, 0.11323757 -0.032565579 -0.21645521, 0.09949851 0.077711686 -0.28021252, 0.11332445 -0.03259784 -0.21639423, 0.099571794 0.077717975 -0.28017208, 0.11342764 -0.032654986 -0.21627501, 0.099636078 0.077730522 -0.28011975, 0.099687696 0.077748284 -0.28005862, 0.11377467 -0.033043236 -0.21406801, 0.099862933 0.078484759 -0.27856183, 0.11382778 -0.033042207 -0.21408193, 0.099934787 0.078469351 -0.27857473, 0.11387509 -0.033036888 -0.21410543, 0.10001369 0.078445375 -0.27860588, 0.11392048 -0.033026889 -0.21413988, 0.11396231 -0.033012137 -0.2141854, 0.10008451 0.07841523 -0.27865475, 0.11399905 -0.032992661 -0.21424179, 0.10014129 0.078380451 -0.27871981, 0.11403757 -0.032959729 -0.21433109, 0.11406429 -0.032915726 -0.21444587, 0.10019517 0.078308329 -0.27887654, 0.11407259 -0.032867149 -0.2145676, 0.11405666 -0.032799408 -0.21473162, 0.10019054 0.078273058 -0.27896392, 0.10257477 0.080848858 -0.27385679, 0.11670196 -0.032655507 -0.20827988, 0.10252331 0.080830902 -0.27391779, 0.10245906 0.080818504 -0.27397025, 0.11659856 -0.032598197 -0.20839904, 0.10238574 0.080812186 -0.27401054, 0.11651179 -0.032565892 -0.20846009, 0.10230787 0.080812454 -0.27403671, 0.11644541 -0.032549173 -0.20848741, 0.11732259 -0.032782882 -0.20677662, 0.11734213 -0.032831565 -0.2066604, 0.11734577 -0.032887176 -0.20652379, 0.1173272 -0.032939345 -0.20639075, 0.11729227 -0.032979041 -0.20628501, 0.10298 0.081511348 -0.27246052, 0.11725605 -0.033003092 -0.20621768, 0.10290892 0.081542909 -0.27240825, 0.11721313 -0.033021599 -0.20616284, 0.11716565 -0.033034503 -0.20612097, 0.1028242 0.081569165 -0.27237338, 0.11711551 -0.033041596 -0.20609222, 0.10275267 0.081584781 -0.27236021, 0.10546193 0.083949268 -0.26765484, 0.11997618 -0.03265591 -0.20028482, 0.10541037 0.083931565 -0.26771581, 0.10534608 0.083919078 -0.26776814, 0.11987294 -0.03259857 -0.20040397, 0.10527277 0.08391282 -0.26780856, 0.11978614 -0.032566413 -0.20046481, 0.10519499 0.083912998 -0.26783484, 0.11971973 -0.032549605 -0.20049222, 0.12059675 -0.032783255 -0.19878145, 0.12061633 -0.032832012 -0.19866525, 0.12062 -0.032887682 -0.1985286, 0.12060152 -0.032939807 -0.19839562, 0.12056644 -0.032979518 -0.19828995, 0.10586739 0.084611878 -0.2662586, 0.12053026 -0.033003524 -0.1982225, 0.10579598 0.084643528 -0.26620626, 0.12048742 -0.033022076 -0.19816765, 0.12043986 -0.033034816 -0.19812572, 0.10571134 0.084669873 -0.26617146, 0.12038971 -0.033041909 -0.19809721, 0.10563973 0.084685341 -0.26615813, 0.10834923 0.087049916 -0.26145279, 0.12325035 -0.032656297 -0.1922898, 0.10829756 0.087032095 -0.26151383, 0.10823336 0.087019637 -0.26156628, 0.12314707 -0.032599002 -0.19240887, 0.10815999 0.087013379 -0.26160657, 0.1230603 -0.032566801 -0.19246978, 0.10808215 0.087013617 -0.26163292, 0.12299389 -0.032549903 -0.1924973, 0.12387101 -0.032783747 -0.19078621, 0.1238905 -0.032832414 -0.19067027, 0.12389436 -0.032888114 -0.19053327, 0.12387575 -0.032940224 -0.19040054, 0.12384072 -0.032979906 -0.19029461, 0.10875438 0.087712616 -0.26005656, 0.12380461 -0.033004016 -0.19022739, 0.10868311 0.087744102 -0.26000434, 0.12376162 -0.033022538 -0.19017251, 0.12371409 -0.033035144 -0.19013081, 0.10859838 0.087770417 -0.25996947, 0.12366402 -0.033042401 -0.190102, 0.10852689 0.087786004 -0.25995609, 0.1112362 0.090150595 -0.25525087, 0.12652461 -0.03265667 -0.18429463, 0.1111847 0.090132713 -0.25531191, 0.1111204 0.090120271 -0.25536424, 0.12642127 -0.032599449 -0.18441373, 0.11104701 0.090113997 -0.25540459, 0.12633465 -0.032567322 -0.18447463, 0.11096925 0.090114072 -0.25543097, 0.12626825 -0.032550409 -0.18450202, 0.12714526 -0.032784224 -0.1827912, 0.12716484 -0.032832906 -0.18267515, 0.12716848 -0.032888591 -0.18253836, 0.12715009 -0.032940716 -0.18240532, 0.12711498 -0.032980353 -0.18229958, 0.11164151 0.090813041 -0.25385475, 0.1270788 -0.033004463 -0.18223223, 0.11157022 0.09084475 -0.2538023, 0.1270358 -0.033022866 -0.18217734, 0.12698831 -0.033035681 -0.18213572, 0.11148556 0.090870947 -0.25376749, 0.12693821 -0.033042848 -0.18210702, 0.11141406 0.090886474 -0.25375426, 0.11412339 0.093251124 -0.24904886, 0.12979886 -0.032657117 -0.1762993, 0.11407164 0.093233347 -0.24910991, 0.11400749 0.093220755 -0.24916247, 0.12969565 -0.032599956 -0.17641866, 0.11393423 0.093214542 -0.24920277, 0.12960884 -0.03256768 -0.17647961, 0.11385633 0.093214601 -0.24922897, 0.12954247 -0.032550842 -0.176507, 0.13041961 -0.032784596 -0.17479597, 0.1304391 -0.032833338 -0.17467998, 0.13044268 -0.032888979 -0.17454316, 0.13042423 -0.032941058 -0.1744103, 0.13038921 -0.032980815 -0.17430447, 0.11452872 0.093913719 -0.24765277, 0.130353 -0.03300491 -0.17423715, 0.1144574 0.09394528 -0.24760059, 0.13031009 -0.033023387 -0.17418219, 0.13026249 -0.033036023 -0.17414059, 0.11437267 0.093971536 -0.24756554, 0.1302124 -0.033043325 -0.17411183, 0.11430112 0.093987122 -0.24755234, 0.1336937 -0.032785013 -0.16680087, 0.13371319 -0.03283371 -0.16668488, 0.13371694 -0.032889292 -0.16654803, 0.13369846 -0.032941505 -0.16641511, 0.13366342 -0.032981202 -0.16630937, 0.1174157 0.097014204 -0.24145079, 0.13362718 -0.033005312 -0.16624202, 0.11734456 0.097045824 -0.24139833, 0.13358434 -0.033023849 -0.16618717, 0.13353679 -0.033036545 -0.16614543, 0.11725977 0.09707202 -0.24136367, 0.1334866 -0.033043697 -0.1661167, 0.11718845 0.097087607 -0.24135029, 0.11701053 0.096351787 -0.24284694, 0.13307314 -0.032657564 -0.16830441, 0.1169588 0.096333906 -0.24290788, 0.11689463 0.096321478 -0.24296048, 0.13296992 -0.032600358 -0.1684234, 0.11682135 0.09631519 -0.24300075, 0.13288301 -0.032568127 -0.16848446, 0.11674351 0.09631519 -0.24302709, 0.13281667 -0.032551214 -0.16851188, 0.11989762 0.099452257 -0.23664503, 0.13634741 -0.032658011 -0.16030921, 0.11984602 0.09943451 -0.23670602, 0.11978172 0.099421829 -0.23675849, 0.13624409 -0.03260076 -0.16042839, 0.11970846 0.09941569 -0.2367989, 0.13615724 -0.032568529 -0.16048928, 0.11963059 0.099415779 -0.23682509, 0.13609087 -0.032551676 -0.16051663, 0.13696799 -0.032785475 -0.15880583, 0.13698749 -0.032834142 -0.1586898, 0.13699126 -0.032889739 -0.15855299, 0.13697267 -0.032941952 -0.15841995, 0.13693766 -0.032981724 -0.15831426, 0.12030295 0.10011472 -0.23524901, 0.13690142 -0.033005729 -0.15824699, 0.12023164 0.10014629 -0.23519646, 0.13685848 -0.033024162 -0.1581921, 0.1368109 -0.033036992 -0.15815018, 0.12014696 0.10017259 -0.23516166, 0.13676095 -0.033044115 -0.15812157, 0.12007548 0.10018814 -0.2351483, 0.12278476 0.10255279 -0.23044309, 0.13962162 -0.032658473 -0.15231407, 0.12273315 0.10253491 -0.23050401, 0.12266891 0.10252252 -0.2305565, 0.13951834 -0.032601207 -0.15243311, 0.12259564 0.10251613 -0.23059684, 0.13943161 -0.032568976 -0.15249418, 0.12251776 0.10251646 -0.23062322, 0.13936521 -0.032552153 -0.15252145, 0.14024223 -0.032786027 -0.1508106, 0.1402618 -0.032834545 -0.15069471, 0.14026549 -0.03289023 -0.15055795, 0.14024697 -0.032942384 -0.15042503, 0.14021187 -0.032982022 -0.15031929, 0.1231901 0.10321526 -0.22904688, 0.14017572 -0.033006176 -0.15025188, 0.12311886 0.1032469 -0.22899453, 0.14013281 -0.033024669 -0.15019676, 0.14008535 -0.033037409 -0.15015508, 0.12303416 0.10327318 -0.22895963, 0.1400352 -0.033044592 -0.15012653, 0.12296268 0.10328873 -0.22894648, 0.14351642 -0.032786384 -0.1428156, 0.14353597 -0.032834992 -0.14269938, 0.14353967 -0.032890663 -0.14256276, 0.14352119 -0.032942787 -0.14242984, 0.14348626 -0.032982573 -0.14232399, 0.12607722 0.10631588 -0.222845, 0.14344981 -0.033006579 -0.14225663, 0.12600607 0.10634749 -0.22279266, 0.14340699 -0.03302516 -0.14220174, 0.1433595 -0.033037856 -0.14216, 0.12592123 0.1063737 -0.22275771, 0.14330947 -0.033045068 -0.14213134, 0.12584978 0.10638933 -0.22274438, 0.12567189 0.10565336 -0.22424114, 0.14289591 -0.03265892 -0.14431892, 0.12562042 0.10563545 -0.22430214, 0.12555616 0.10562292 -0.22435446, 0.14279258 -0.032601729 -0.14443816, 0.12548275 0.10561675 -0.22439496, 0.14270583 -0.032569408 -0.14449911, 0.12540504 0.10561688 -0.22442114, 0.14263934 -0.032552585 -0.14452632, 0.12829204 0.10871747 -0.21821924, 0.12836997 0.10871726 -0.21819295, 0.12844317 0.10872358 -0.21815245, 0.12850742 0.1087361 -0.21810012, 0.12855902 0.10875396 -0.21803916, 0.12873428 0.10949033 -0.21654226, 0.14533135 -0.02283299 -0.14005111, 0.12880628 0.10947472 -0.21655522, 0.12888496 0.109451 -0.21658622, 0.14538951 -0.022644445 -0.14021304, 0.128956 0.10942072 -0.21663533, 0.12901263 0.10938603 -0.21670009, 0.12906639 0.10931402 -0.21685697, 0.12906186 0.10927862 -0.21694444, 0.13044223 -0.033209518 -0.13847578, 0.11259837 0.10859083 -0.22059658, 0.13028595 -0.033260196 -0.13859156, 0.11246404 0.10857487 -0.22075494, 0.13015592 -0.033320606 -0.13873553, 0.11239848 0.10854638 -0.22085308, 0.13043487 -0.033330247 -0.13844326, 0.13043642 -0.033268988 -0.13845634, 0.13028288 -0.033386618 -0.13856429, 0.13015437 -0.033384755 -0.13872182, 0.12996282 -0.034601599 -0.13885343, 0.13007627 -0.034619749 -0.1387085, 0.083984911 0.052029505 -0.27536771, 0.083939612 0.052034035 -0.27534994, 0.083899796 0.052044347 -0.27532354, 0.083868027 0.052059859 -0.27529007, 0.083846003 0.052079663 -0.27525115, 0.083835214 0.052102387 -0.27520919, 0.083836257 0.052127019 -0.27516696, 0.083937466 0.05150415 -0.27496868, 0.083915383 0.051523909 -0.27492964, 0.083969206 0.051488653 -0.27500221, 0.084008843 0.051478371 -0.27502877, 0.084054172 0.051473841 -0.27504635, 0.083855599 0.051918432 -0.27509725, 0.083905518 0.051571384 -0.27484569, 0.083904564 0.051546797 -0.27488792, 0.083877385 0.05188109 -0.27516991, 0.083930701 0.051854432 -0.27522957, 0.0897879 0.0055422485 -0.24848609, 0.089742661 0.005546838 -0.24846853, 0.089702934 0.0055570602 -0.2484421, 0.089671135 0.0055725873 -0.24840833, 0.089649051 0.0055924058 -0.24836959, 0.089638352 0.005615145 -0.24832775, 0.089639425 0.0056397021 -0.24828555, 0.089740455 0.0050168931 -0.24808709, 0.08971858 0.0050366074 -0.24804822, 0.089772224 0.0050014555 -0.2481208, 0.089812011 0.0049910545 -0.24814717, 0.08985734 0.0049865544 -0.24816482, 0.089658707 0.0054311752 -0.2482156, 0.089708745 0.005084008 -0.24796419, 0.089707762 0.0050594062 -0.2480064, 0.089680552 0.0053938925 -0.24828832, 0.089733958 0.0053670704 -0.24834825, 0.094604969 -0.033555716 -0.22584334, 0.094587594 -0.03355971 -0.2258243, 0.094572216 -0.033566758 -0.22580013, 0.094559252 -0.033576772 -0.22577183, 0.094546586 -0.033594891 -0.22572729, 0.094539434 -0.033620879 -0.22567031, 0.094541967 -0.033662364 -0.22558858, 0.094552964 -0.033698067 -0.22552392, 0.14598447 -0.0243821 -0.13670245, 0.14648098 -0.028359696 -0.1367027, 0.14650297 -0.02835691 -0.13663934, 0.14600645 -0.024379373 -0.1366391, 0.14653856 -0.028352499 -0.13658254, 0.14604193 -0.024374902 -0.13658214, 0.14658555 -0.028346568 -0.136535, 0.14608894 -0.024369106 -0.13653447, 0.14664209 -0.028339595 -0.1364993, 0.1461454 -0.024361983 -0.13649899, 0.14670491 -0.028331697 -0.13647704, 0.14620835 -0.024354339 -0.13647664, 0.094236255 -0.034598634 -0.22972812, 0.11024061 -0.034642413 -0.22968762, 0.094258785 -0.034830511 -0.22948581, 0.11031145 -0.034936845 -0.22934125, 0.094286799 -0.035072014 -0.22910675, 0.11040345 -0.035144836 -0.22893871, 0.094311059 -0.035223767 -0.22867981, 0.11048748 -0.035241112 -0.22859725, 0.080402553 0.078650072 -0.29319769, 0.096744329 0.078610018 -0.29325059, 0.080347538 0.078485042 -0.2933951, 0.080318421 0.078290448 -0.29357439, 0.080315024 0.078066662 -0.29373047, 0.096493155 0.077630118 -0.29392627, 0.080330789 0.077709183 -0.29389971, 0.080350727 0.077326089 -0.2939952, 0.096443146 0.077235833 -0.29400629, 0.080376804 0.076888204 -0.29401094, 0.096413895 0.076833561 -0.29400614, 0.080405354 0.076464325 -0.2939328, 0.096406743 0.076439813 -0.29392532, 0.096412346 0.076232865 -0.29384783, 0.080005705 0.076504067 -0.29165724, 0.079997927 0.076588437 -0.2916798, 0.082180232 0.077249855 -0.28665727, 0.082056075 0.077053219 -0.28692842, 0.0818578 0.076649904 -0.28733677, 0.081680059 0.076162338 -0.28766853, 0.081534505 0.075615048 -0.28789967, 0.081429154 0.075039893 -0.28801763, 0.081367582 0.074470252 -0.28802317, 0.093106851 0.079186365 -0.2731123, 0.092948303 0.079228744 -0.27315754, 0.10685086 -0.032551423 -0.20852973, 0.092709795 0.079311922 -0.27326134, 0.10649359 -0.032571778 -0.20863141, 0.092430726 0.079412416 -0.27342513, 0.10451193 -0.033026636 -0.21411066, 0.09058626 0.077555373 -0.27808532, 0.10414959 -0.033006325 -0.21423604, 0.090259209 0.077799872 -0.27833655, 0.13635588 -0.0328504 -0.13640285, 0.11868563 0.10870007 -0.21825539, 0.13599765 -0.032862663 -0.13650933, 0.11833267 0.10864644 -0.21833789, 0.13732152 -0.032382414 -0.13450994, 0.11946253 0.10949449 -0.21657589, 0.13711224 -0.032447323 -0.1345128, 0.11910705 0.10945992 -0.21666944, 0.13684094 -0.032601371 -0.13452148, 0.1330447 -0.03255482 -0.14456868, 0.11579859 0.1055994 -0.22445743, 0.13268746 -0.032575279 -0.14467031, 0.11544538 0.10554586 -0.22453988, 0.13398017 -0.03303054 -0.14215471, 0.11657533 0.10639393 -0.22277777, 0.13361777 -0.03301017 -0.14228003, 0.11621976 0.10635939 -0.22287144, 0.1297705 -0.032554328 -0.15256384, 0.1129114 0.1024988 -0.23065914, 0.12941326 -0.032574803 -0.15266567, 0.11255826 0.10244535 -0.23074186, 0.13070591 -0.033030137 -0.15014973, 0.1136882 0.10329342 -0.22897975, 0.13034357 -0.033009693 -0.15027514, 0.11333272 0.10325885 -0.22907345, 0.1264963 -0.032553926 -0.160559, 0.11002417 0.09939827 -0.23686138, 0.12613907 -0.03257449 -0.16066073, 0.10967115 0.099344879 -0.23694389, 0.12743162 -0.033029646 -0.15814483, 0.11080106 0.1001928 -0.23518157, 0.12706925 -0.033009231 -0.15827036, 0.11044551 0.10015829 -0.2352753, 0.12322202 -0.032553419 -0.16855402, 0.10713711 0.096297681 -0.24306311, 0.12286484 -0.032573909 -0.16865577, 0.10678402 0.096244156 -0.24314572, 0.12415741 -0.033029273 -0.16614, 0.10791393 0.097092286 -0.24138358, 0.123795 -0.03300871 -0.16626537, 0.1075585 0.097057655 -0.24147728, 0.11994781 -0.032553062 -0.17654923, 0.10425004 0.093197227 -0.24926521, 0.11959051 -0.032573596 -0.17665094, 0.10389689 0.093143642 -0.24934779, 0.12088314 -0.033028901 -0.17413513, 0.10502675 0.093991578 -0.24758564, 0.12052082 -0.033008367 -0.17426053, 0.10467128 0.093957111 -0.24767914, 0.11667357 -0.0325526 -0.18454435, 0.10136282 0.090096593 -0.255467, 0.11631621 -0.032573074 -0.1846461, 0.10100973 0.090043187 -0.25554961, 0.11760893 -0.033028439 -0.18213016, 0.10213964 0.090891182 -0.25378758, 0.11724658 -0.03300789 -0.1822557, 0.10178418 0.090856627 -0.25388107, 0.10778624 -0.033027217 -0.20611557, 0.093478292 0.081589386 -0.27239335, 0.10742392 -0.033006638 -0.20624103, 0.093122929 0.081554815 -0.27248716, 0.11433466 -0.033027917 -0.19012532, 0.099252596 0.087790623 -0.25998953, 0.1139724 -0.033007547 -0.1902508, 0.098897114 0.087755963 -0.26008326, 0.11339922 -0.032552168 -0.19253938, 0.098475739 0.086996123 -0.2616691, 0.11304207 -0.032572657 -0.19264098, 0.098122656 0.086942554 -0.26175165, 0.11106056 -0.033027574 -0.19812043, 0.096365392 0.084690005 -0.26619142, 0.110698 -0.033006996 -0.19824588, 0.09600997 0.084655374 -0.26628488, 0.11012502 -0.032551676 -0.20053458, 0.095588475 0.083895504 -0.26787096, 0.1097679 -0.03257221 -0.2006363, 0.095235541 0.083841965 -0.2679536, 0.1035766 -0.032550946 -0.21652484, 0.089814425 0.077694356 -0.28027487, 0.10321935 -0.032571375 -0.21662657, 0.089461327 0.077640831 -0.28035748, 0.096447721 0.076852679 -0.27760243, 0.096447825 0.076936826 -0.27762496, 0.096839547 0.077270016 -0.27766204, 0.0968889 0.077158436 -0.2776922, 0.096572757 0.076860949 -0.2776069, 0.096754074 0.076896295 -0.27762672, 0.096934199 0.077070817 -0.27769482, 0.096703887 0.077073857 -0.27765125, 0.096728086 0.076983437 -0.27764738, 0.096801996 0.077375039 -0.27760327, 0.096562758 0.076947212 -0.27762926, 0.096677035 0.077188209 -0.27763095, 0.096779317 0.077466086 -0.27752021, 0.096553445 0.077036366 -0.27763578, 0.096656084 0.077295646 -0.27758348, 0.096542835 0.077148899 -0.27762079, 0.096772522 0.077536181 -0.27742127, 0.096642226 0.07739003 -0.27751216, 0.096534371 0.077255353 -0.27758062, 0.096780196 0.077582121 -0.27731705, 0.096941561 0.077715293 -0.27733579, 0.096940637 0.07771419 -0.27733898, 0.096636385 0.077464059 -0.27742332, 0.09652853 0.077350006 -0.27751732, 0.096637845 0.077514634 -0.27732587, 0.09652555 0.077426538 -0.27743638, 0.096525282 0.077481225 -0.27734539, 0.096982718 0.076987967 -0.27767897, 0.098118156 0.079074457 -0.27812183, 0.098117232 0.079073414 -0.27812481, 0.098494411 0.078658208 -0.27862048, 0.098494411 0.078573927 -0.27859795, 0.098343208 0.079178989 -0.2783252, 0.098206162 0.079138383 -0.27823889, 0.098343283 0.079100326 -0.2784459, 0.098206133 0.079087332 -0.27835122, 0.098343208 0.078989208 -0.27853739, 0.098206162 0.079004988 -0.27844334, 0.098343253 0.078855738 -0.27859163, 0.098206162 0.078898892 -0.27850664, 0.098343283 0.07871218 -0.27860349, 0.099793822 0.078573957 -0.27859786, 0.099793762 0.078658238 -0.27862054, 0.10026062 0.078844294 -0.27879298, 0.10032809 0.07879208 -0.27889705, 0.10033789 0.078926101 -0.27876899, 0.099984616 0.078621104 -0.27865806, 0.1000613 0.078593358 -0.27870238, 0.09999828 0.078708678 -0.27867156, 0.099933192 0.078947812 -0.2785967, 0.099955484 0.079042464 -0.27854073, 0.10008025 0.078679785 -0.27872026, 0.10011798 0.078787968 -0.2787236, 0.1001496 0.078644469 -0.27878585, 0.10019657 0.078748778 -0.27879861, 0.099980354 0.079121456 -0.27846542, 0.10010493 0.079015836 -0.27859151, 0.10015333 0.079092249 -0.27852321, 0.10029985 0.079048514 -0.27861059, 0.1004166 0.078865215 -0.27889073, 0.10047114 0.078769669 -0.27908313, 0.10051572 0.0789188 -0.27886963, 0.10057807 0.078807577 -0.27909279, 0.09991461 0.078842267 -0.27863008, 0.10025465 0.078703746 -0.27888834, 0.10006127 0.0789233 -0.27864066, 0.10005236 0.078508958 -0.2786721, 0.09997797 0.078536257 -0.27863026, 0.10057141 0.078725219 -0.27925748, 0.10051617 0.078644529 -0.27941686, 0.1002309 0.078977302 -0.27866736, 0.10012607 0.078559846 -0.27876323, 0.10042438 0.078989521 -0.27872854, 0.10037529 0.078711137 -0.27906215, 0.099900693 0.078731254 -0.27863947, 0.10020074 0.078604832 -0.27886492, 0.10046637 0.078699216 -0.27922595, 0.10041443 0.078627065 -0.27936071, 0.10002524 0.078818962 -0.27866781, 0.10011542 0.078476295 -0.27873039, 0.10016918 0.078888997 -0.2787056, 0.10017371 0.078522786 -0.27883688, 0.099893346 0.07864356 -0.2786293, 0.10029563 0.078635052 -0.27903095, 0.10037205 0.078651622 -0.27918544, 0.10032435 0.078585625 -0.27929801, 0.10016155 0.078440413 -0.27880168, 0.10023689 0.078545436 -0.27899137, 0.10029355 0.078585103 -0.27913827, 0.10025057 0.078522339 -0.27923208, 0.099889636 0.078558788 -0.27860427, 0.10020711 0.078468323 -0.27895534, 0.10023487 0.078503117 -0.27908683, 0.10019767 0.078440651 -0.27916646, 0.10019307 0.078388482 -0.27891666, 0.10020471 0.078430161 -0.27904499, 0.10016799 0.078345165 -0.27910507, 0.10018972 0.078352705 -0.27900353, 0.10007739 0.078173384 -0.28035927, 0.099975705 0.07815598 -0.28030312, 0.099885583 0.078114375 -0.28024042, 0.099811926 0.078051209 -0.28017449, 0.099758863 0.077969536 -0.28010893, 0.099729255 0.077873945 -0.28004736, 0.099910378 0.078059539 -0.28058898, 0.099645615 0.077979669 -0.28075016, 0.099721238 0.077941447 -0.28018004, 0.099769711 0.078016743 -0.28025365, 0.099709034 0.077985391 -0.28032804, 0.09983632 0.078072622 -0.28033093, 0.099765539 0.078033909 -0.28041518, 0.099834085 0.078059182 -0.28050399, 0.099606037 0.077990755 -0.28064719, 0.099494532 0.07795912 -0.28079176, 0.099343255 0.077952385 -0.28080624, 0.099693358 0.077850446 -0.28011402, 0.0996674 0.077916279 -0.28024751, 0.099570513 0.077977285 -0.28054285, 0.099475026 0.077973112 -0.28068531, 0.099343121 0.07796751 -0.28069958, 0.099642634 0.077829823 -0.28017664, 0.09954071 0.077940688 -0.28044271, 0.099457398 0.077963233 -0.28057778, 0.09934321 0.077959314 -0.28059205, 0.09951821 0.077882364 -0.28035182, 0.099442601 0.077930316 -0.28047526, 0.09934321 0.07792832 -0.28048906, 0.099503875 0.077805027 -0.28027368, 0.099431276 0.077875838 -0.28038204, 0.099343225 0.077876121 -0.28039503, 0.0993433 0.077804789 -0.28031433, 0.10000868 0.078114033 -0.28047913, 0.099423781 0.077802181 -0.28030169, 0.099917725 0.078105748 -0.28040767, 0.090176091 0.077952325 -0.28080606, 0.090176105 0.077967361 -0.28069952, 0.090176091 0.07795912 -0.2805922, 0.090176105 0.077928141 -0.28048912, 0.09017612 0.077875927 -0.28039506, 0.09017612 0.07780464 -0.28031424, 0.089466363 0.077732533 -0.28041852, 0.089479819 0.077809647 -0.28049675, 0.089501038 0.07786794 -0.28058866, 0.089529127 0.077904373 -0.28068948, 0.089562312 0.077917174 -0.28079405, 0.089599326 0.07790567 -0.28089774, 0.089337662 0.078337565 -0.27917317, 0.089365616 0.078452066 -0.27915683, 0.089322105 0.078561023 -0.27916661, 0.089374736 0.078564659 -0.27911937, 0.089305177 0.078714922 -0.2790809, 0.089238003 0.078712717 -0.27913192, 0.090039343 0.078321666 -0.27855283, 0.090030149 0.078209057 -0.27859038, 0.090002194 0.078094617 -0.2786068, 0.091209009 0.077137485 -0.27776173, 0.091438547 0.077486351 -0.27765501, 0.091397911 0.07740137 -0.27771401, 0.091344252 0.077311948 -0.27775267, 0.091280237 0.077222422 -0.27776885, 0.0906436 0.077632323 -0.27810058, 0.090693608 0.077714279 -0.27809885, 0.090766802 0.077882245 -0.27804759, 0.090787783 0.077963188 -0.27799979, 0.090303957 0.077875912 -0.27834594, 0.090340972 0.077954829 -0.27834189, 0.090388536 0.078114092 -0.27829707, 0.090398431 0.078191221 -0.27825713, 0.091472045 0.077459529 -0.27763951, 0.091431469 0.077374488 -0.27769858, 0.091377988 0.077285007 -0.27773705, 0.091313854 0.0771956 -0.27775338, 0.091242582 0.077110618 -0.27774632, 0.091786638 0.077463344 -0.27741089, 0.091781273 0.07738395 -0.27750781, 0.091616049 0.077405527 -0.27756754, 0.091589049 0.077310041 -0.2776328, 0.091768518 0.077282146 -0.27758327, 0.091949478 0.076852515 -0.27760246, 0.091949418 0.076936856 -0.27762508, 0.091685802 0.076876611 -0.27761734, 0.091704831 0.076953456 -0.27763855, 0.091724291 0.077039436 -0.27764669, 0.091433063 0.076956108 -0.27766421, 0.091749087 0.077164486 -0.27763095, 0.091468349 0.077022031 -0.27768186, 0.09150435 0.077095941 -0.27768806, 0.091551051 0.07720463 -0.2776739, 0.093842208 0.081674352 -0.27239594, 0.093842238 0.081758782 -0.27241862, 0.092983902 0.082163945 -0.27238145, 0.093020022 0.082090512 -0.27245155, 0.093052506 0.082002774 -0.27250382, 0.093080282 0.081904247 -0.27253625, 0.093101814 0.081799597 -0.27254742, 0.09311372 0.081715837 -0.27254084, 0.093120843 0.081633434 -0.27252054, 0.093453243 0.081978351 -0.27243531, 0.10268088 0.081674397 -0.27239597, 0.10268086 0.081758782 -0.27241859, 0.10311873 0.082077563 -0.27246583, 0.10303265 0.082194492 -0.27231789, 0.10318761 0.08214882 -0.2724092, 0.10298522 0.082117975 -0.27238655, 0.1027828 0.081832588 -0.27243638, 0.10279627 0.081943572 -0.27242684, 0.1029074 0.081920713 -0.27246362, 0.10281383 0.082049221 -0.27239329, 0.10294275 0.082025081 -0.2724359, 0.10305683 0.081989318 -0.27250427, 0.10277598 0.081744939 -0.27242661, 0.10288103 0.081810296 -0.27246761, 0.10277243 0.081660092 -0.27240157, 0.10300563 0.081888288 -0.27252197, 0.10286771 0.081722826 -0.27245432, 0.10296772 0.081780285 -0.27251852, 0.10286109 0.081638128 -0.27242678, 0.10294871 0.081693679 -0.27250063, 0.1029398 0.081609309 -0.27247047, 0.1028588 0.082223117 -0.27226156, 0.10283513 0.082143843 -0.2723372, 0.10261647 0.080974549 -0.27384531, 0.10264598 0.081070155 -0.27390695, 0.10269898 0.081151769 -0.27397254, 0.1027727 0.081215113 -0.27403843, 0.10286282 0.081256598 -0.27410114, 0.10296457 0.081273824 -0.27415705, 0.10279755 0.081159979 -0.27438688, 0.10253279 0.081080228 -0.27454829, 0.10260841 0.081042007 -0.27397823, 0.10265671 0.081117362 -0.27405167, 0.10259621 0.081085831 -0.27412629, 0.10272346 0.081173152 -0.27412903, 0.10265265 0.081134409 -0.27421319, 0.10272123 0.081159651 -0.27430201, 0.10249327 0.081091136 -0.2744453, 0.10238163 0.081059724 -0.27458978, 0.10223037 0.081052825 -0.27460423, 0.10258053 0.080950826 -0.27391195, 0.10255466 0.081016749 -0.27404547, 0.10245763 0.081078023 -0.27434087, 0.10236214 0.081073612 -0.27448332, 0.10223036 0.08106795 -0.27449763, 0.10252975 0.080930442 -0.27397466, 0.10242791 0.081041157 -0.27424085, 0.10234448 0.081063941 -0.27437592, 0.10223037 0.081059858 -0.27439025, 0.10240524 0.080982953 -0.27414989, 0.10232978 0.081030756 -0.27427328, 0.10223036 0.081028849 -0.2742871, 0.10239094 0.080905601 -0.27407184, 0.10231839 0.080976456 -0.27418005, 0.10223041 0.080976456 -0.27419317, 0.10223038 0.080905318 -0.27411228, 0.10289578 0.081214577 -0.27427721, 0.10231094 0.080902725 -0.27409995, 0.10280484 0.081206247 -0.2742056, 0.10019194 0.08105287 -0.2746042, 0.10019194 0.08106789 -0.27449763, 0.10019194 0.081059664 -0.27439034, 0.100192 0.081028908 -0.2742871, 0.10019192 0.080976442 -0.27419305, 0.10019188 0.080905229 -0.27411222, 0.10009556 0.080873638 -0.27409756, 0.099925086 0.080927759 -0.27425897, 0.10005228 0.080966145 -0.27421308, 0.1000049 0.080910653 -0.27416909, 0.10005231 0.081028044 -0.27434361, 0.099861205 0.080923602 -0.274362, 0.099923953 0.080949575 -0.27430075, 0.10005236 0.081048355 -0.27448666, 0.099923909 0.080986068 -0.27442256, 0.098684654 0.079564422 -0.2735759, 0.09874855 0.079568595 -0.27347291, 0.098828301 0.079551429 -0.27338314, 0.098919019 0.079514354 -0.2733115, 0.098689184 0.079449683 -0.27334064, 0.098740563 0.079415888 -0.27327573, 0.098529533 0.079368651 -0.27330267, 0.098566994 0.079325289 -0.27322745, 0.098455101 0.079408303 -0.27353343, 0.098309621 0.079361647 -0.27354026, 0.09832786 0.079356045 -0.27339971, 0.098490342 0.079400629 -0.27340472, 0.098634467 0.079473943 -0.27343035, 0.098433957 0.079383343 -0.27366149, 0.098583341 0.079478011 -0.27354601, 0.098145351 0.079331473 -0.27360883, 0.098145351 0.079183906 -0.27311695, 0.098392114 0.079204768 -0.27312744, 0.098145291 0.079255134 -0.27319753, 0.098369464 0.079270691 -0.27320051, 0.09860754 0.079268202 -0.27316299, 0.098145351 0.079338402 -0.2733947, 0.09834899 0.079320133 -0.27328557, 0.098145351 0.079307407 -0.27329171, 0.098145366 0.079346508 -0.27350229, 0.098796114 0.07937035 -0.27322102, 0.093647137 0.079183891 -0.27311698, 0.093647107 0.079255149 -0.27319762, 0.093647018 0.079307392 -0.27329174, 0.093647137 0.079338387 -0.27339485, 0.093647137 0.079346493 -0.27350223, 0.093646958 0.079331532 -0.27360871, 0.093308821 0.079239085 -0.27315131, 0.093343988 0.079309061 -0.27323869, 0.093375102 0.079356626 -0.27334133, 0.093418971 0.079374865 -0.27356949, 0.093400642 0.079379007 -0.27345365, 0.093429342 0.079344705 -0.27368239, 0.093165621 0.079409525 -0.27388328, 0.09277977 0.07939072 -0.27329639, 0.093001202 0.079305544 -0.27320316, 0.092852846 0.079454258 -0.27335075, 0.093054429 0.079367712 -0.27326432, 0.092925444 0.079499558 -0.27342167, 0.093105927 0.079413727 -0.27333811, 0.093054906 0.079527214 -0.27359822, 0.093153611 0.079442218 -0.27342144, 0.092993826 0.079524308 -0.27350557, 0.09310545 0.07950826 -0.27369538, 0.093202457 0.079452321 -0.27352652, 0.093142942 0.079468384 -0.27379203, 0.093246087 0.079433665 -0.27364951, 0.093274131 0.07938464 -0.27376702, 0.092940316 0.079536721 -0.27403224, 0.092727318 0.079630569 -0.27419785, 0.092905834 0.079602137 -0.27394187, 0.092680082 0.079702005 -0.27411193, 0.092618123 0.079748943 -0.27401891, 0.092856601 0.07964541 -0.27384627, 0.092795327 0.079664841 -0.27375045, 0.092544898 0.079768762 -0.27392453, 0.0924647 0.079760388 -0.27383402, 0.092724666 0.079659209 -0.27365834, 0.092382208 0.079724267 -0.27375284, 0.092648044 0.07962878 -0.27357498, 0.092302516 0.079662457 -0.27368569, 0.092570797 0.079574779 -0.27350608, 0.092229977 0.079578474 -0.27363661, 0.092496991 0.079501212 -0.27345526, 0.090807065 0.080321893 -0.27585167, 0.090770498 0.080386594 -0.27578095, 0.090722442 0.08043462 -0.27570403, 0.090659589 0.080465823 -0.27561694, 0.090588704 0.08047314 -0.27553049, 0.090513334 0.080456361 -0.27544945, 0.090437427 0.080416515 -0.27537751, 0.090364709 0.080355123 -0.27531847, 0.090298787 0.08027561 -0.27527514, 0.090434983 0.080477849 -0.27553591, 0.090545431 0.08048971 -0.27565208, 0.090527534 0.080471098 -0.27549338, 0.090606779 0.080454558 -0.27579147, 0.090500966 0.080489591 -0.275682, 0.090596691 0.080482677 -0.27563801, 0.090648666 0.080469564 -0.27564171, 0.090694919 0.080451921 -0.27566245, 0.090666398 0.080449447 -0.27574915, 0.090751037 0.080394253 -0.27579415, 0.090734735 0.080380991 -0.27584353, 0.090702385 0.080374092 -0.27588576, 0.090288237 0.080315486 -0.27531746, 0.090416089 0.080415085 -0.27538148, 0.090468422 0.080482677 -0.27572429, 0.14597557 -0.024374589 -0.13908878, 0.14597355 -0.024368271 -0.1391069, 0.14596932 -0.024362326 -0.13913324, 0.14596535 -0.024361327 -0.13915098, 0.14596055 -0.02436316 -0.13916656, 0.080026478 0.075961336 -0.29135817, 0.093702197 -0.033556849 -0.22802764, 0.093669415 -0.033563301 -0.2280353, 0.079984397 0.075950012 -0.29136866, 0.093636721 -0.033572614 -0.22804883, 0.079946727 0.075934514 -0.29138714, 0.093614459 -0.033580288 -0.22806266, 0.093594432 -0.033587396 -0.22807997, 0.079915255 0.075915679 -0.29141289, 0.093576938 -0.033592969 -0.22810109, 0.079891533 0.07589446 -0.29144448, 0.093557 -0.033596918 -0.22813615, 0.079876751 0.075872049 -0.29148036, 0.093541145 -0.033594534 -0.22818312, 0.079973936 0.076419011 -0.29162243, 0.079933077 0.076408669 -0.29163224, 0.079896331 0.076394454 -0.29164961, 0.079865038 0.076376989 -0.29167396, 0.079840809 0.076357052 -0.29170364, 0.079824895 0.076335669 -0.29173762, 0.079813182 0.076472238 -0.29179329, 0.07983005 0.076485038 -0.29175705, 0.079881042 0.076627344 -0.2917214, 0.079885423 0.076507181 -0.29169899, 0.079921573 0.076515913 -0.2916798, 0.079916328 0.076629847 -0.29170197, 0.079956293 0.076714277 -0.29169005, 0.079955071 0.076631635 -0.29168981, 0.079850554 0.076624513 -0.29174775, 0.079854488 0.07649672 -0.29172522, 0.079918325 0.076716378 -0.29170164, 0.079825699 0.076621249 -0.29177949, 0.079883516 0.076718897 -0.29172045, 0.079807967 0.076617718 -0.29181582, 0.079853415 0.076721787 -0.2917456, 0.079968065 0.07681784 -0.29167062, 0.07982865 0.076724812 -0.29177636, 0.079930902 0.076825261 -0.29168028, 0.07981047 0.076728076 -0.29181141, 0.079982013 0.076878533 -0.29164821, 0.079896897 0.076834202 -0.29169661, 0.080041885 0.077025577 -0.2915526, 0.079945177 0.076889262 -0.29165572, 0.080000341 0.077048644 -0.29155403, 0.079867214 0.076844305 -0.29171926, 0.079911679 0.076902151 -0.29167014, 0.079963773 0.077077135 -0.29156438, 0.079912663 0.077143237 -0.29160851, 0.079933912 0.077109173 -0.29158291, 0.079842508 0.07685551 -0.29174715, 0.07996133 0.076522395 -0.29166815, 0.079882115 0.076916814 -0.29169053, 0.079824001 0.076867148 -0.29177976, 0.079857826 0.076932698 -0.29171628, 0.079839438 0.076949209 -0.29174656, 0.080093026 0.077079877 -0.29148924, 0.080055654 0.077099904 -0.29148585, 0.080122411 0.077109769 -0.29144499, 0.080151916 0.077134624 -0.29139808, 0.080021918 0.077125296 -0.29148847, 0.080084264 0.077130035 -0.29143921, 0.080112785 0.077155128 -0.29139033, 0.079993159 0.077155069 -0.29149708, 0.080049783 0.077156857 -0.29143938, 0.080077887 0.077182904 -0.29138783, 0.079970568 0.077187881 -0.29151148, 0.080020726 0.07718876 -0.29144537, 0.080048621 0.077216581 -0.29139099, 0.07995522 0.077222258 -0.29153091, 0.079998583 0.077224359 -0.29145724, 0.080026478 0.077254668 -0.29139975, 0.080012918 0.077294916 -0.29141355, 0.079984039 0.07726191 -0.29147404, 0.11862215 0.11844882 -0.20875861, 0.11858319 0.11846922 -0.20875064, 0.11854813 0.1184971 -0.20874836, 0.11851893 0.11853085 -0.20875147, 0.118497 0.11856888 -0.20876017, 0.11848325 0.11860937 -0.20877413, 0.11934625 0.11886536 -0.2079573, 0.11903146 0.11875823 -0.20817174, 0.11906008 0.11873154 -0.20819247, 0.1193679 0.11883646 -0.20798282, 0.11869682 0.11872973 -0.20843375, 0.11871657 0.11869022 -0.20842914, 0.11971785 0.11891033 -0.20783532, 0.11898383 0.11882946 -0.20815097, 0.11874257 0.11865447 -0.20843139, 0.11900555 0.11879133 -0.20815745, 0.11932662 0.11890069 -0.20793892, 0.11868387 0.11877352 -0.20844547, 0.11970414 0.11894085 -0.20780635, 0.11896743 0.11887063 -0.20815194, 0.11931027 0.11894061 -0.20792866, 0.11969176 0.1189777 -0.20778491, 0.11895654 0.11891541 -0.20816161, 0.11929788 0.11898305 -0.20792687, 0.11968122 0.11901878 -0.20777217, 0.11928964 0.11902881 -0.20793484, 0.1196733 0.11906223 -0.20776859, 0.12007622 0.11913519 -0.20768633, 0.11966814 0.11910857 -0.207775, 0.12007527 0.11916499 -0.20769346, 0.11880797 0.11860043 -0.20845489, 0.11877356 0.11862396 -0.2084401, 0.13618998 0.1200431 -0.20587064, 0.13618927 0.12007278 -0.20587768, 0.13702951 0.11975074 -0.20620586, 0.13686532 0.11978419 -0.20609787, 0.13699768 0.11972332 -0.20621993, 0.1369532 0.12001346 -0.20609331, 0.13675229 0.12006813 -0.20597698, 0.13675115 0.12002777 -0.20595932, 0.13650283 0.11986218 -0.20594108, 0.13649639 0.11984299 -0.20596385, 0.13695186 0.11997308 -0.20607492, 0.13631472 0.12006627 -0.20586801, 0.13705727 0.11978422 -0.20619845, 0.13691311 0.11984986 -0.20606579, 0.13689083 0.11981423 -0.20607808, 0.13631459 0.12002417 -0.20586161, 0.13651139 0.11989482 -0.20591441, 0.13707991 0.11982211 -0.20619796, 0.13693127 0.11988924 -0.20606077, 0.13631466 0.11990385 -0.2058953, 0.13631468 0.12010652 -0.2058834, 0.13709603 0.11986279 -0.20620419, 0.13694438 0.11993121 -0.20606399, 0.13651891 0.1199325 -0.20589541, 0.1363146 0.11994122 -0.20587552, 0.13707159 0.11963654 -0.20637704, 0.13652512 0.11997341 -0.20588493, 0.1363146 0.11998187 -0.20586419, 0.1369736 0.1197083 -0.20623328, 0.13652965 0.12001608 -0.20588326, 0.13709933 0.11964901 -0.20636883, 0.13667876 0.11981495 -0.20602003, 0.13710503 0.11990422 -0.20621718, 0.13653235 0.1200586 -0.20589079, 0.13713616 0.11967297 -0.20636192, 0.13669178 0.11983339 -0.20599908, 0.13716815 0.11970371 -0.20636053, 0.13670906 0.11986528 -0.20597494, 0.13653314 0.12009902 -0.20590737, 0.13719411 0.1197395 -0.20636503, 0.13672422 0.11990237 -0.2059585, 0.13721254 0.11977856 -0.20637524, 0.13673672 0.11994301 -0.20595014, 0.13713285 0.11955319 -0.20654416, 0.13674574 0.1199854 -0.20595028, 0.13722262 0.11981927 -0.20639038, 0.13716291 0.11956239 -0.20654203, 0.13684613 0.11976726 -0.20611551, 0.13720278 0.11958247 -0.20654334, 0.13723736 0.11960977 -0.20654936, 0.13726543 0.11964273 -0.20655943, 0.13728543 0.11968002 -0.20657401, 0.13729623 0.11971979 -0.20659125, 0.13631472 0.11985193 -0.20594585, 0.13631472 0.11987124 -0.20592248, 0.13731048 0.11788546 -0.20532632, 0.13735922 0.11782119 -0.20550339, 0.13727935 0.11789629 -0.20535283, 0.13652438 0.11807986 -0.2050148, 0.13641794 0.118077 -0.20502022, 0.13739358 0.11780739 -0.20548321, 0.13733707 0.11786699 -0.20529892, 0.13668813 0.11803976 -0.20486055, 0.13686763 0.11801946 -0.20490552, 0.13685916 0.11804175 -0.20494188, 0.13668416 0.11806202 -0.20489837, 0.1374229 0.11778653 -0.20546116, 0.13735776 0.11784178 -0.20527209, 0.13652438 0.11808558 -0.20497069, 0.13641272 0.11808251 -0.20497608, 0.13744585 0.11775929 -0.20543863, 0.13713239 0.11796439 -0.20524634, 0.13724506 0.11789884 -0.20537743, 0.13667272 0.11807978 -0.20498301, 0.13669068 0.11800951 -0.20482852, 0.137372 0.11781061 -0.20524682, 0.13687299 0.11798966 -0.20487393, 0.1374616 0.11772712 -0.20541635, 0.1365243 0.11808132 -0.20492637, 0.1364079 0.11807804 -0.20493186, 0.13667892 0.11807561 -0.20493974, 0.13716148 0.11796486 -0.20521499, 0.13652426 0.11806756 -0.20488419, 0.13640396 0.11806373 -0.20488954, 0.13718782 0.11795676 -0.20518269, 0.13652438 0.11804479 -0.2048461, 0.13640104 0.11804043 -0.20485151, 0.13721015 0.11794057 -0.20515023, 0.1365243 0.11801408 -0.20481384, 0.13639925 0.11800908 -0.20481932, 0.13722767 0.11791673 -0.20511948, 0.1369874 0.11801812 -0.20513885, 0.13723938 0.11788648 -0.20509149, 0.13700984 0.11802101 -0.2051021, 0.13702999 0.11801505 -0.20506443, 0.13704704 0.11800027 -0.20502795, 0.13706033 0.11797756 -0.20499374, 0.13682072 0.11805552 -0.2050636, 0.13706917 0.11794777 -0.20496389, 0.1368352 0.11806023 -0.20502295, 0.13684824 0.11805563 -0.20498168, 0.13732128 0.11782712 -0.20552124, 0.13666569 0.1180743 -0.20502616, 0.1202932 0.11716861 -0.20683722, 0.12028803 0.11717404 -0.20679307, 0.12028325 0.11716962 -0.20674883, 0.12027933 0.11715533 -0.20670652, 0.12027636 0.11713198 -0.20666839, 0.12027444 0.11710085 -0.20663631, 0.1189625 0.11679366 -0.20758627, 0.11881195 0.11666559 -0.20784202, 0.11892566 0.11678991 -0.20755805, 0.11877118 0.11665867 -0.20781973, 0.1188927 0.11677626 -0.20752741, 0.11873518 0.1166421 -0.2077947, 0.1191071 0.1168997 -0.20728184, 0.11886573 0.11675346 -0.20749687, 0.11870569 0.11661673 -0.20776828, 0.11868444 0.11658403 -0.20774211, 0.11908379 0.11687937 -0.20724715, 0.11884631 0.1167226 -0.20746744, 0.11906683 0.11685061 -0.20721518, 0.1188353 0.11668572 -0.20744114, 0.11867264 0.11654595 -0.20771743, 0.11905707 0.11681487 -0.20718718, 0.11982837 0.11712137 -0.20689727, 0.11981435 0.11711545 -0.20685461, 0.11980273 0.11709966 -0.20681369, 0.11979404 0.11707488 -0.20677663, 0.1197888 0.11704233 -0.20674552, 0.11943829 0.11702812 -0.20708303, 0.11941603 0.1170198 -0.20704351, 0.11939791 0.11700192 -0.20700516, 0.11938459 0.11697513 -0.20697062, 0.1193766 0.11694103 -0.20694073, 0.11913571 0.11691067 -0.20731692, 0.082261711 0.07741347 -0.28635716, 0.082220942 0.077406555 -0.28633463, 0.082184792 0.077389836 -0.28630966, 0.082155436 0.077364534 -0.28628325, 0.082134157 0.07733193 -0.28625703, 0.082122445 0.077293634 -0.28623241, 0.081408381 0.075832844 -0.28768986, 0.081395984 0.075819135 -0.28764683, 0.081430465 0.075842768 -0.28772998, 0.081461221 0.075848132 -0.28776479, 0.081498861 0.075848818 -0.28779262, 0.081541687 0.075844795 -0.28781199, 0.081581444 0.076366395 -0.28729928, 0.081585348 0.07639116 -0.28733748, 0.081598908 0.076411873 -0.28737521, 0.0816212 0.076427728 -0.28741074, 0.081650943 0.07643804 -0.28744286, 0.081687003 0.07644251 -0.28746974, 0.081727833 0.076440245 -0.28749013, 0.081828564 0.076884359 -0.28683627, 0.081835151 0.076915026 -0.28686649, 0.081849962 0.076941401 -0.28689718, 0.081872255 0.076962322 -0.28692693, 0.081900984 0.076977402 -0.28695464, 0.081935316 0.076985508 -0.28697932, 0.081973821 0.0769867 -0.28699994, 0.082041711 0.077223748 -0.28657371, 0.082069904 0.077240974 -0.28659832, 0.082103044 0.077251464 -0.28662109, 0.082140267 0.077254593 -0.28664106, 0.081175953 0.074572712 -0.28780043, 0.081174791 0.074569702 -0.28784943, 0.08118543 0.074565858 -0.28789699, 0.081207424 0.074561268 -0.28794038, 0.081239194 0.074556321 -0.28797728, 0.08127898 0.074551046 -0.28800529, 0.081324577 0.074545979 -0.28802258, 0.0812563 0.075186342 -0.28777164, 0.08125627 0.075193763 -0.28781945, 0.081267715 0.075199008 -0.28786594, 0.081289649 0.07520175 -0.28790867, 0.081321001 0.075201869 -0.28794515, 0.081359982 0.075199366 -0.28797334, 0.081404567 0.075194359 -0.28799146, 0.081394136 0.075802028 -0.28760284, 0.1487197 -0.034615457 -0.1345052, 0.14864622 -0.034587085 -0.1344769, 0.14875101 -0.034640133 -0.13452959, 0.14868517 -0.0345985 -0.13448811, 0.14861408 -0.034582078 -0.13447182, 0.14877649 -0.034672171 -0.13456178, 0.14878304 -0.034820378 -0.13470995, 0.14879738 -0.034756005 -0.13464582, 0.14879046 -0.034703285 -0.13459301, 0.14679812 -0.035053447 -0.14046107, 0.14672205 -0.035126895 -0.14043179, 0.14667323 -0.035180911 -0.14039317, 0.14664465 -0.035218567 -0.14035189, 0.14663467 -0.035278514 -0.14020152, 0.14662765 -0.035273388 -0.14023352, 0.14662515 -0.035263017 -0.14027029, 0.14662971 -0.035245448 -0.14031032, 0.11409898 0.10823344 -0.21937028, 0.11272009 -0.033231169 -0.22322102, 0.11286297 -0.03327401 -0.22298539, 0.14707856 -0.033669487 -0.14046846, 0.14705573 -0.03364633 -0.1404634, 0.14701472 -0.033601031 -0.14044367, 0.14697984 -0.033555955 -0.14041036, 0.14695391 -0.033514678 -0.14036456, 0.14693597 -0.033452138 -0.1402432, 0.14693901 -0.033480108 -0.1403096, 0.1467061 -0.028755039 -0.13647808, 0.14663985 -0.028747573 -0.13650264, 0.14658165 -0.028741091 -0.13654234, 0.14653397 -0.028735623 -0.13659434, 0.14885961 -0.03467387 -0.1347034, 0.14890003 -0.034562677 -0.13470341, 0.14887865 -0.034556344 -0.13463986, 0.14883928 -0.034665018 -0.13464007, 0.14883481 -0.034726769 -0.13470352, 0.14881502 -0.034716889 -0.13464001, 0.14871059 -0.034365833 -0.13447762, 0.14868365 -0.034498483 -0.13447762, 0.14877363 -0.034372851 -0.13449994, 0.14875458 -0.034519553 -0.13450527, 0.14883016 -0.034379154 -0.13453555, 0.14865242 -0.034584463 -0.13447762, 0.1488267 -0.034540951 -0.1345619, 0.14887731 -0.034384459 -0.13458297, 0.14872037 -0.034613788 -0.13450527, 0.14891286 -0.034388468 -0.13463989, 0.14878939 -0.034643441 -0.1345619, 0.14893486 -0.034390926 -0.13470328, 0.14872585 -0.034229696 -0.13447762, 0.14878879 -0.034236699 -0.13449979, 0.1488453 -0.034243047 -0.13453555, 0.14889263 -0.034248278 -0.13458291, 0.14892806 -0.03425239 -0.13464001, 0.1489502 -0.034254819 -0.1347034, 0.14948855 -0.033013999 -0.134583, 0.14987175 -0.032755688 -0.13463974, 0.14985286 -0.03272526 -0.13458291, 0.1495138 -0.033039257 -0.13463989, 0.14922822 -0.033395737 -0.13463987, 0.14919807 -0.033376753 -0.13458303, 0.14883755 -0.033739716 -0.13447762, 0.14889748 -0.033760712 -0.13449982, 0.14910971 -0.033321083 -0.13449979, 0.14895107 -0.033779502 -0.13453555, 0.14915787 -0.033351362 -0.13453555, 0.14945497 -0.032980308 -0.13453534, 0.14982782 -0.032685101 -0.13453543, 0.14905606 -0.033287197 -0.1344775, 0.14941491 -0.032940015 -0.1344997, 0.14979766 -0.032636791 -0.13449955, 0.14937027 -0.032895029 -0.13447738, 0.14976411 -0.032582909 -0.13447747, 0.14988352 -0.032774523 -0.13470322, 0.1490507 -0.03381443 -0.13470328, 0.14902969 -0.033807069 -0.13463986, 0.14924695 -0.033407569 -0.1347034, 0.14899598 -0.033795297 -0.134583, 0.14952947 -0.033055022 -0.13470322, 0.15649481 -0.028388619 -0.13447705, 0.15652828 -0.028442323 -0.13449931, 0.15655835 -0.028490692 -0.13453496, 0.1565835 -0.028530985 -0.13458255, 0.15660243 -0.028561294 -0.1346395, 0.15661414 -0.028580129 -0.13470292, 0.15661748 -0.02829361 -0.13447705, 0.15671855 -0.028175995 -0.13447706, 0.15703964 -0.027933225 -0.13463943, 0.15705948 -0.027737767 -0.13463938, 0.15702383 -0.027737871 -0.13458246, 0.15700464 -0.027925998 -0.13458255, 0.15694804 -0.028106451 -0.13458255, 0.15695818 -0.027916431 -0.13453498, 0.1569043 -0.028087661 -0.13453498, 0.15681727 -0.028244659 -0.13453498, 0.15685205 -0.028065234 -0.13449931, 0.1567706 -0.02821216 -0.13449931, 0.15666114 -0.028339714 -0.13449934, 0.15706144 -0.027937621 -0.1347028, 0.15708168 -0.027737916 -0.1347028, 0.15698086 -0.028120503 -0.13463929, 0.15685625 -0.028271794 -0.13458243, 0.15670033 -0.028380901 -0.13453498, 0.15700121 -0.02812922 -0.13470283, 0.15688558 -0.028292179 -0.13463953, 0.15673311 -0.028415322 -0.13458255, 0.15690382 -0.028304815 -0.13470283, 0.15675765 -0.028441206 -0.13463943, 0.15677302 -0.028457224 -0.13470292, 0.15684028 -0.027892232 -0.13447705, 0.15685602 -0.027737886 -0.13447705, 0.15690242 -0.027904958 -0.13449919, 0.15691943 -0.027737856 -0.13449934, 0.15679385 -0.02804026 -0.13447705, 0.15697633 -0.027737841 -0.13453487, 0.15708177 -0.023793101 -0.13470235, 0.15705949 -0.023792893 -0.13463904, 0.15702373 -0.023792997 -0.13458203, 0.15697625 -0.023792997 -0.13453458, 0.15691942 -0.023793012 -0.13449885, 0.156856 -0.023793012 -0.13447668, 0.15696278 -0.023251191 -0.13458203, 0.15673989 -0.022757202 -0.13453449, 0.15691641 -0.0232618 -0.13453458, 0.15683483 -0.022711515 -0.1347023, 0.15562487 -0.021642312 -0.13453431, 0.15510762 -0.02152127 -0.13449852, 0.15560022 -0.021693602 -0.13449858, 0.15653788 -0.02223894 -0.13470212, 0.15652062 -0.022252828 -0.13463879, 0.15512043 -0.021465808 -0.13453437, 0.15681481 -0.022721127 -0.13463892, 0.15699759 -0.023243204 -0.13463889, 0.15458918 -0.021526203 -0.13447638, 0.15604201 -0.021971151 -0.13449861, 0.15557268 -0.021750614 -0.13447641, 0.1567826 -0.022736624 -0.13458194, 0.15600252 -0.022020832 -0.13447644, 0.1570192 -0.023238316 -0.13470231, 0.15636134 -0.022379622 -0.1344765, 0.15513891 -0.021384507 -0.1346388, 0.15458918 -0.021322742 -0.13463879, 0.15458921 -0.021358415 -0.13458189, 0.15513092 -0.021419436 -0.13458194, 0.15564547 -0.021599472 -0.13458183, 0.15607756 -0.021926671 -0.13453437, 0.15641111 -0.022340193 -0.13449861, 0.15514377 -0.021362945 -0.1347021, 0.15458918 -0.02130051 -0.13470209, 0.15663147 -0.022809491 -0.1344765, 0.15566096 -0.02156733 -0.13463877, 0.15610716 -0.021889523 -0.13458194, 0.1564555 -0.022304624 -0.13453451, 0.15668871 -0.022782072 -0.1344988, 0.15567064 -0.021547303 -0.13470204, 0.15679914 -0.023288533 -0.13447677, 0.15612954 -0.021861687 -0.1346388, 0.15649259 -0.022275016 -0.13458194, 0.15509352 -0.021583065 -0.13447641, 0.15686098 -0.023274437 -0.1344987, 0.15458922 -0.021462828 -0.13449848, 0.15614335 -0.021844298 -0.13470224, 0.15458918 -0.021405891 -0.13453436, 0.14827546 -0.021300554 -0.13470207, 0.14827536 -0.021322727 -0.13463867, 0.14827536 -0.021358401 -0.13458192, 0.14827536 -0.021405995 -0.13453442, 0.14827536 -0.021462858 -0.13449854, 0.14827536 -0.021526277 -0.13447636, 0.14775105 -0.021464333 -0.13453439, 0.14725207 -0.021636426 -0.1345343, 0.1472766 -0.021687865 -0.1344986, 0.14776348 -0.02151984 -0.13449854, 0.14673832 -0.021830916 -0.13470218, 0.14634481 -0.022216618 -0.13470224, 0.14675197 -0.021848425 -0.13463882, 0.14721648 -0.021561265 -0.13463879, 0.14677408 -0.021876484 -0.13458195, 0.14723171 -0.021593511 -0.13458195, 0.14774045 -0.021417961 -0.13458182, 0.14720692 -0.021541208 -0.13470206, 0.14773263 -0.021383047 -0.13463882, 0.14772771 -0.021361411 -0.13470203, 0.14687753 -0.022008628 -0.13447642, 0.1465196 -0.02235949 -0.13447642, 0.1468384 -0.021958694 -0.13449863, 0.14647049 -0.022319317 -0.13449872, 0.14730375 -0.021745116 -0.13447642, 0.14680324 -0.021913886 -0.13453434, 0.1464265 -0.022283301 -0.13453439, 0.14638972 -0.022253245 -0.13458204, 0.14777739 -0.02158165 -0.1344766, 0.14636196 -0.022230595 -0.13463874, 0.13851343 -0.031837732 -0.13464692, 0.13832653 -0.032185093 -0.13454521, 0.13831103 -0.032241359 -0.13452637, 0.13830735 -0.032285362 -0.13451017, 0.1383121 -0.032380715 -0.13448262, 0.1383152 -0.032444492 -0.13447297, 0.13824178 -0.032439873 -0.13447796, 0.13753521 -0.03245689 -0.13447464, 0.13819551 -0.03239812 -0.13449121, 0.13753521 -0.032406345 -0.13448811, 0.13663888 -0.032960787 -0.13447797, 0.13658629 -0.032922164 -0.13450159, 0.13691019 -0.032686457 -0.13447572, 0.13687424 -0.032642409 -0.13449313, 0.13711631 -0.032557264 -0.13447487, 0.13709255 -0.032510325 -0.1344897, 0.13732292 -0.032482654 -0.13447453, 0.1373111 -0.032433644 -0.13448799, 0.13638905 -0.033190116 -0.13450161, 0.13644151 -0.033228725 -0.13447799, 0.13632987 -0.033237696 -0.13451378, 0.13636179 -0.033276156 -0.13449238, 0.14555503 -0.02476497 -0.14012891, 0.1459707 -0.024255633 -0.13925265, 0.14595585 -0.024309516 -0.13921425, 0.1455401 -0.024818763 -0.1400905, 0.14600895 -0.024206489 -0.13906971, 0.14598636 -0.024262637 -0.13906965, 0.14597566 -0.024322331 -0.13906968, 0.14600888 -0.024206668 -0.13676921, 0.1459863 -0.024262905 -0.13676916, 0.1459756 -0.02432248 -0.13676913, 0.14604813 -0.024160847 -0.13670245, 0.14618191 -0.024344906 -0.13648394, 0.14618558 -0.024320334 -0.13648391, 0.14622295 -0.024303749 -0.13647664, 0.14619565 -0.02429755 -0.13648385, 0.1461738 -0.02426362 -0.13649893, 0.14610007 -0.024320364 -0.1365265, 0.14611322 -0.024274796 -0.13652647, 0.14612982 -0.024227709 -0.1365346, 0.14609295 -0.024197519 -0.13658214, 0.14603204 -0.024343356 -0.13659289, 0.14604138 -0.02427876 -0.13659285, 0.14606771 -0.024219006 -0.13659298, 0.14606529 -0.024174839 -0.136639, 0.14599235 -0.024304613 -0.13667645, 0.14601368 -0.024230838 -0.13667655, 0.14696936 -0.023032606 -0.1367023, 0.14698653 -0.023046643 -0.13663876, 0.14701419 -0.023069292 -0.13658202, 0.14705102 -0.023099408 -0.13653448, 0.14709501 -0.023135334 -0.13649881, 0.14714409 -0.023175478 -0.13647667, 0.14808758 -0.022405595 -0.13658202, 0.14770378 -0.022588074 -0.13653448, 0.1476834 -0.02254501 -0.13658205, 0.14731954 -0.022769988 -0.13658196, 0.14766805 -0.022512779 -0.13663879, 0.14729747 -0.022741795 -0.13663881, 0.14851259 -0.022526145 -0.13647652, 0.14812443 -0.022569299 -0.1364765, 0.14851259 -0.022462666 -0.13649875, 0.14811048 -0.022507429 -0.13649867, 0.1477281 -0.022639409 -0.13649887, 0.14809798 -0.022451907 -0.13653445, 0.14734887 -0.022807389 -0.13653445, 0.14775528 -0.022696793 -0.13647655, 0.147384 -0.022852182 -0.13649869, 0.1474231 -0.022902101 -0.13647652, 0.14851268 -0.022300348 -0.13670221, 0.14807492 -0.022349104 -0.13670219, 0.14851259 -0.022322476 -0.1366387, 0.14807971 -0.022370681 -0.13663879, 0.14765857 -0.022492766 -0.13670227, 0.14851262 -0.022358239 -0.13658199, 0.14728387 -0.022724375 -0.13670245, 0.14851262 -0.022405818 -0.13653433, 0.15408923 -0.022300333 -0.13670221, 0.15408923 -0.022322506 -0.13663879, 0.15408921 -0.022358268 -0.13658203, 0.1540892 -0.022405848 -0.13653448, 0.1540892 -0.022462696 -0.1364987, 0.15408923 -0.022526115 -0.13647653, 0.15602377 -0.024292767 -0.13658218, 0.15592904 -0.023873001 -0.13653469, 0.15597527 -0.023862422 -0.13658214, 0.15583211 -0.0234534 -0.13658205, 0.15601014 -0.023854434 -0.136639, 0.15526575 -0.022817522 -0.13653445, 0.15488327 -0.022643894 -0.13649882, 0.15490797 -0.022592664 -0.13653444, 0.15586439 -0.023437887 -0.13663888, 0.1545091 -0.022453189 -0.13653445, 0.15492859 -0.022549808 -0.136582, 0.15451968 -0.022406802 -0.13658205, 0.15608175 -0.024292856 -0.13670245, 0.1558843 -0.023428231 -0.1367023, 0.15562966 -0.023064345 -0.13663888, 0.15564695 -0.023050576 -0.13670242, 0.15485574 -0.022701055 -0.13647653, 0.15519074 -0.022911578 -0.13647652, 0.15523042 -0.022862032 -0.1364987, 0.1553314 -0.022735 -0.13670228, 0.15449648 -0.022508562 -0.13649867, 0.15448238 -0.022570461 -0.13647653, 0.15591936 -0.024292886 -0.13649893, 0.15587349 -0.023885638 -0.13649893, 0.15597628 -0.024292886 -0.1365346, 0.15578941 -0.023474008 -0.13653445, 0.15560168 -0.023086593 -0.13658205, 0.15531754 -0.022752315 -0.13663872, 0.15581171 -0.023899823 -0.13647664, 0.15585594 -0.024292856 -0.13647664, 0.15495373 -0.022497594 -0.13670221, 0.15573803 -0.023498803 -0.13649881, 0.15556458 -0.02311641 -0.13653457, 0.15529534 -0.022780284 -0.13658206, 0.15494412 -0.022517622 -0.13663886, 0.15568094 -0.023526281 -0.13647667, 0.15453261 -0.022350267 -0.13670218, 0.15552013 -0.0231518 -0.13649873, 0.15603177 -0.023849517 -0.13670242, 0.15605958 -0.024292856 -0.13663903, 0.15452769 -0.022371858 -0.13663879, 0.15547055 -0.023191333 -0.13647667, 0.15608171 -0.027182594 -0.13670267, 0.15605959 -0.027182519 -0.13663922, 0.15602379 -0.027182519 -0.13658237, 0.15597625 -0.027182579 -0.13653496, 0.15591939 -0.027182639 -0.13649905, 0.15585597 -0.027182549 -0.13647684, 0.14710437 -0.033047602 -0.13647498, 0.14712034 -0.033103481 -0.13649108, 0.14713863 -0.033167377 -0.13652575, 0.14715435 -0.033221945 -0.13657622, 0.14716578 -0.033262134 -0.1366376, 0.14717254 -0.033285692 -0.13670421, 0.15590377 -0.027749568 -0.13670269, 0.1559809 -0.027565286 -0.13663939, 0.15600131 -0.027573973 -0.13670281, 0.15606137 -0.027382404 -0.13670269, 0.15552826 -0.027887151 -0.1364992, 0.15566106 -0.027784348 -0.1364992, 0.15555835 -0.02793549 -0.13653497, 0.15570028 -0.027825624 -0.13653496, 0.1558173 -0.027689412 -0.13653494, 0.15573306 -0.027859971 -0.1365824, 0.15585625 -0.027716368 -0.13658251, 0.15594804 -0.027551129 -0.13658242, 0.15588553 -0.027736947 -0.13663939, 0.15603967 -0.027377844 -0.13663939, 0.15549475 -0.027833357 -0.13647704, 0.15561754 -0.027738467 -0.13647704, 0.15577058 -0.027656823 -0.13649917, 0.15590437 -0.027532458 -0.13653496, 0.15600461 -0.027370706 -0.13658242, 0.15571855 -0.027620703 -0.13647702, 0.15585215 -0.027510047 -0.1364992, 0.15595813 -0.027361199 -0.13653496, 0.15579386 -0.027485043 -0.13647702, 0.15590237 -0.02734977 -0.1364992, 0.15584035 -0.027337074 -0.13647702, 0.15561402 -0.028024882 -0.13670273, 0.155773 -0.027901933 -0.13670269, 0.15560241 -0.028005987 -0.13663939, 0.15575773 -0.02788581 -0.1366394, 0.15558355 -0.027975738 -0.13658249, 0.14794849 -0.03504689 -0.14046258, 0.14794859 -0.035110295 -0.14044039, 0.14794856 -0.035167187 -0.14040472, 0.14794861 -0.035214737 -0.14035714, 0.14794853 -0.03525041 -0.14030032, 0.14794862 -0.035272673 -0.14023699, 0.14872584 -0.034798205 -0.14035718, 0.14886209 -0.03460592 -0.14030032, 0.14875564 -0.034818128 -0.14030026, 0.14868626 -0.034771889 -0.14040472, 0.14882836 -0.034593895 -0.14035715, 0.14878368 -0.034577906 -0.14040475, 0.14862877 -0.035002887 -0.14023702, 0.14893496 -0.034390643 -0.14023687, 0.14877397 -0.034830287 -0.14023702, 0.14863893 -0.034740284 -0.14044048, 0.14873004 -0.034558818 -0.14044036, 0.14861357 -0.034986749 -0.14030023, 0.14858624 -0.034705222 -0.14046268, 0.14867043 -0.034537479 -0.14046265, 0.1485891 -0.034960791 -0.14035715, 0.14846659 -0.035126254 -0.14023699, 0.1485565 -0.034926146 -0.14040478, 0.14871049 -0.03436546 -0.14046253, 0.14845502 -0.035107419 -0.14030029, 0.14851752 -0.034884661 -0.14044042, 0.14843637 -0.035076946 -0.14035733, 0.14847404 -0.034838498 -0.14046256, 0.14828621 -0.03521271 -0.14023697, 0.14841154 -0.035036415 -0.14040478, 0.14827862 -0.035191968 -0.14030026, 0.14838186 -0.034987882 -0.14044045, 0.14826658 -0.035158381 -0.1403573, 0.14888293 -0.034613341 -0.14023687, 0.14891285 -0.034388274 -0.14030035, 0.14834872 -0.03493391 -0.14046265, 0.14887738 -0.034384251 -0.14035718, 0.14825031 -0.035113618 -0.14040478, 0.14883018 -0.034378961 -0.1404046, 0.14823093 -0.035060197 -0.14044049, 0.14820933 -0.035000607 -0.14046253, 0.14877355 -0.034372509 -0.14044039, 0.14895016 -0.034254283 -0.14023687, 0.14892805 -0.034251854 -0.14030017, 0.14889258 -0.034247845 -0.14035721, 0.14884543 -0.034242585 -0.1404046, 0.14878881 -0.034236267 -0.14044036, 0.14872584 -0.0342291 -0.14046256, 0.14945498 -0.032979712 -0.14040443, 0.14915788 -0.03335087 -0.14040449, 0.14910963 -0.033320412 -0.14044037, 0.14941487 -0.032939449 -0.14044034, 0.14982772 -0.03268449 -0.14040449, 0.14905062 -0.033813909 -0.14023684, 0.14902961 -0.033806488 -0.14030017, 0.14922822 -0.033395216 -0.14030018, 0.148996 -0.033794716 -0.14035715, 0.14919797 -0.033376157 -0.14035723, 0.14948857 -0.033013508 -0.14035705, 0.14985278 -0.032724842 -0.14035693, 0.14924705 -0.033407137 -0.14023688, 0.14951381 -0.033038795 -0.14030021, 0.14987174 -0.032755211 -0.14030004, 0.14952943 -0.033054531 -0.14023691, 0.14988337 -0.032774016 -0.14023665, 0.14976412 -0.032582507 -0.14046243, 0.14883754 -0.033739254 -0.14046241, 0.14889753 -0.033760235 -0.14044036, 0.14905599 -0.033286676 -0.14046255, 0.14895108 -0.033779025 -0.14040463, 0.14937028 -0.032894537 -0.14046249, 0.14979759 -0.03263627 -0.14044026, 0.15661414 -0.028579712 -0.14023629, 0.15660246 -0.028560922 -0.14029971, 0.15658352 -0.028530598 -0.1403567, 0.15655835 -0.028490186 -0.14040402, 0.15652831 -0.028441906 -0.1404399, 0.15649486 -0.028388113 -0.14046194, 0.15677293 -0.028456837 -0.14023629, 0.15690382 -0.028304487 -0.14023629, 0.15690239 -0.02790454 -0.14043978, 0.15685605 -0.027737454 -0.14046198, 0.15691943 -0.027737379 -0.14043978, 0.15695815 -0.027915955 -0.14040408, 0.1570818 -0.027737379 -0.14023617, 0.15690441 -0.028087288 -0.14040402, 0.15700464 -0.027925521 -0.14035654, 0.15694804 -0.028106004 -0.14035669, 0.15685627 -0.028271317 -0.14035659, 0.15698095 -0.028120086 -0.14029971, 0.15688558 -0.028291747 -0.14029971, 0.15675767 -0.028440759 -0.14029971, 0.15684032 -0.027891725 -0.14046194, 0.15685211 -0.028064817 -0.14043978, 0.15681732 -0.028244212 -0.14040403, 0.15673313 -0.028414845 -0.1403567, 0.15679383 -0.028039783 -0.140462, 0.15677057 -0.028211653 -0.14043984, 0.15670034 -0.028380394 -0.14040403, 0.15671857 -0.028175399 -0.14046195, 0.15666124 -0.028339148 -0.14043979, 0.15661745 -0.028293192 -0.14046204, 0.15706141 -0.027937219 -0.14023629, 0.15705951 -0.027737424 -0.14029959, 0.15703975 -0.027932778 -0.14029974, 0.15702382 -0.027737454 -0.14035656, 0.15700132 -0.028128877 -0.1402363, 0.15697633 -0.027737468 -0.14040396, 0.15685605 -0.023792461 -0.14046161, 0.1569194 -0.023792565 -0.14043938, 0.15697627 -0.023792565 -0.14040361, 0.15702386 -0.02379258 -0.14035608, 0.15705959 -0.023792565 -0.14029931, 0.15708168 -0.02379255 -0.14023592, 0.15668862 -0.022781432 -0.14043927, 0.15641099 -0.022339627 -0.14043918, 0.15645552 -0.022304237 -0.1404036, 0.15673974 -0.022756815 -0.1404036, 0.15564547 -0.021599025 -0.14035602, 0.15513101 -0.021418989 -0.14035605, 0.15513891 -0.02138418 -0.14029901, 0.155661 -0.021566808 -0.14029901, 0.15691641 -0.023261368 -0.14040361, 0.15696269 -0.023250863 -0.14035608, 0.15678266 -0.022736162 -0.14035624, 0.15612942 -0.021861121 -0.14029899, 0.1556707 -0.02154696 -0.14023565, 0.15614329 -0.021843761 -0.14023574, 0.1566315 -0.022808969 -0.14046143, 0.15636139 -0.022379071 -0.14046146, 0.15686101 -0.023274124 -0.14043938, 0.15653789 -0.022238448 -0.14023572, 0.15679911 -0.023288071 -0.14046155, 0.15510774 -0.021520764 -0.14043917, 0.15458924 -0.021462277 -0.14043917, 0.15458925 -0.021405593 -0.14040345, 0.15512039 -0.021465242 -0.14040342, 0.15562488 -0.021641791 -0.14040343, 0.1561071 -0.021889031 -0.14035606, 0.15652058 -0.022252277 -0.14029914, 0.15509358 -0.021582663 -0.14046131, 0.15458924 -0.021525785 -0.14046134, 0.15683486 -0.022710979 -0.14023581, 0.15560022 -0.02169317 -0.14043926, 0.1560774 -0.021926105 -0.14040343, 0.15649258 -0.022274569 -0.14035599, 0.15681487 -0.022720695 -0.14029932, 0.15557274 -0.021750301 -0.14046134, 0.15701921 -0.023237869 -0.1402358, 0.15604208 -0.021970704 -0.1404392, 0.15514384 -0.021362528 -0.14023569, 0.15458925 -0.021300077 -0.1402356, 0.15458919 -0.021322191 -0.14029899, 0.15699762 -0.023242891 -0.14029925, 0.15600246 -0.022020251 -0.14046139, 0.15458924 -0.021357939 -0.14035596, 0.14827538 -0.021525741 -0.14046131, 0.14827538 -0.021462321 -0.14043914, 0.14827545 -0.021405563 -0.14040342, 0.14827545 -0.021357998 -0.14035597, 0.14827538 -0.02132225 -0.14029895, 0.14827545 -0.021300048 -0.14023578, 0.14725208 -0.02163589 -0.14040338, 0.14680345 -0.021913514 -0.14040342, 0.14677413 -0.021876082 -0.14035597, 0.14774057 -0.021417484 -0.14035596, 0.14773269 -0.021382645 -0.14029896, 0.14721654 -0.021560788 -0.14029905, 0.14723183 -0.021593079 -0.14035597, 0.14687751 -0.0220083 -0.14046142, 0.14651962 -0.022358909 -0.1404615, 0.14647062 -0.02231884 -0.14043921, 0.14683844 -0.021958202 -0.14043939, 0.14727651 -0.021687359 -0.14043921, 0.14775108 -0.021463841 -0.14040345, 0.14730377 -0.021744594 -0.14046147, 0.14776351 -0.021519214 -0.14043927, 0.14777739 -0.021581158 -0.14046136, 0.14673829 -0.02183044 -0.14023571, 0.14634486 -0.022216186 -0.14023569, 0.14675188 -0.021847844 -0.14029907, 0.14636195 -0.022230148 -0.14029907, 0.1472069 -0.021540642 -0.14023565, 0.14638969 -0.022252813 -0.14035596, 0.14772786 -0.021360949 -0.14023566, 0.14642651 -0.022282824 -0.14040342, 0.11256583 -0.03315106 -0.22347386, 0.096724063 -0.032836601 -0.22401235, 0.096795827 -0.032585666 -0.22426823, 0.12685944 -0.032647982 -0.16048223, 0.12685944 -0.033278242 -0.16084582, 0.12648745 -0.032660678 -0.16051739, 0.12685937 -0.032762438 -0.16046186, 0.12648369 -0.032774046 -0.16050053, 0.12685944 -0.032878414 -0.16046864, 0.12648545 -0.032888144 -0.16050947, 0.12685941 -0.032989621 -0.16050196, 0.12649243 -0.032996967 -0.16054338, 0.12685944 -0.033090189 -0.16056001, 0.12650438 -0.033095136 -0.16060078, 0.12685944 -0.033174708 -0.16063964, 0.12652059 -0.03317745 -0.16067833, 0.12685943 -0.033238515 -0.16073655, 0.1265403 -0.033239707 -0.16077219, 0.12656249 -0.03327854 -0.16087794, 0.13602662 -0.032647997 -0.16048218, 0.13602662 -0.032762319 -0.16046192, 0.13602661 -0.032878295 -0.1604687, 0.13602662 -0.032989517 -0.16050194, 0.1360265 -0.033090129 -0.16056, 0.13602662 -0.033174664 -0.16063966, 0.13602661 -0.03323856 -0.16073671, 0.13602655 -0.033278182 -0.16084588, 0.13613114 -0.033177555 -0.16063182, 0.13624413 -0.033182532 -0.16060013, 0.13615167 -0.033239752 -0.16072549, 0.1362834 -0.033241779 -0.16068567, 0.13632749 -0.033278957 -0.16078162, 0.13641497 -0.03324461 -0.16061442, 0.13647598 -0.033279508 -0.16069682, 0.13610013 -0.032979995 -0.16048986, 0.13611417 -0.033095419 -0.16055432, 0.13621131 -0.033104181 -0.16052888, 0.13663547 -0.033280551 -0.16055241, 0.13679007 -0.033277452 -0.16026954, 0.13636047 -0.033189148 -0.16054077, 0.13609254 -0.032833591 -0.16045557, 0.13656068 -0.033248827 -0.16048907, 0.13668676 -0.03323558 -0.16022724, 0.13618343 -0.032993868 -0.16046786, 0.13631442 -0.033115953 -0.16047861, 0.13649356 -0.033198625 -0.16043259, 0.13659541 -0.03316839 -0.16018987, 0.13609457 -0.032687098 -0.16046466, 0.13616717 -0.032852903 -0.16043244, 0.13627397 -0.033012509 -0.1604239, 0.13643599 -0.033132464 -0.16038407, 0.13652158 -0.033079892 -0.1601596, 0.13616836 -0.032709882 -0.16043518, 0.13624793 -0.032878846 -0.16038884, 0.1361748 -0.033278495 -0.16083075, 0.13638341 -0.033038765 -0.16033961, 0.13624495 -0.032740682 -0.16038473, 0.13634551 -0.03291598 -0.16030766, 0.13646919 -0.032974809 -0.16013809, 0.13633347 -0.032785669 -0.16029762, 0.13644123 -0.032859474 -0.1601267, 0.13693869 -0.032859489 -0.15891181, 0.13696669 -0.032974988 -0.15892318, 0.13701904 -0.033079877 -0.15894471, 0.13709296 -0.033168584 -0.15897503, 0.13718426 -0.033235684 -0.1590123, 0.13728763 -0.033277512 -0.15905467, 0.13699682 -0.033237845 -0.15802497, 0.13691945 -0.033240587 -0.15796417, 0.1370414 -0.033266857 -0.15797126, 0.13736449 -0.033279568 -0.15880808, 0.13728714 -0.0332513 -0.15856241, 0.13738215 -0.03328149 -0.15855466, 0.13726221 -0.033243895 -0.15879229, 0.13695377 -0.033268064 -0.15790524, 0.13705395 -0.033171073 -0.15824246, 0.13694608 -0.033101246 -0.15820824, 0.13700593 -0.033181325 -0.15815614, 0.13698594 -0.03308399 -0.15828454, 0.1371706 -0.033187032 -0.15877813, 0.13720119 -0.033203855 -0.15856944, 0.13693774 -0.032981768 -0.15831421, 0.13734411 -0.033282936 -0.15832281, 0.13688096 -0.033194229 -0.15803011, 0.13694729 -0.033189058 -0.1580849, 0.13700651 -0.032955915 -0.15875295, 0.13707852 -0.033092543 -0.15876399, 0.13689709 -0.033114091 -0.15814553, 0.13690142 -0.033005834 -0.15824693, 0.13726041 -0.033257484 -0.15834992, 0.13684174 -0.033122942 -0.15809746, 0.13711117 -0.033124238 -0.15857679, 0.13685845 -0.033024222 -0.15819207, 0.13718401 -0.03321746 -0.1583747, 0.13725686 -0.033284113 -0.1581168, 0.13703358 -0.033006936 -0.15858318, 0.1371876 -0.033262506 -0.1581596, 0.13710187 -0.033150345 -0.15840092, 0.13717949 -0.033284828 -0.15800534, 0.13712375 -0.033228397 -0.15819925, 0.13712071 -0.033265024 -0.15805665, 0.13708949 -0.033285275 -0.15791331, 0.13702571 -0.033049479 -0.15842555, 0.13706617 -0.033233881 -0.158104, 0.13699083 -0.033285618 -0.15784198, 0.12779799 -0.033280924 -0.15777087, 0.12779793 -0.033248678 -0.15787017, 0.12779799 -0.03319639 -0.15796074, 0.12779796 -0.033126548 -0.15803824, 0.12653618 -0.033278033 -0.15818295, 0.12659772 -0.033237129 -0.15827462, 0.12665235 -0.03317152 -0.15835592, 0.12669678 -0.033084705 -0.15842217, 0.12736388 -0.033280388 -0.15781903, 0.12738462 -0.033246428 -0.15791878, 0.12740345 -0.033191547 -0.1580089, 0.12741937 -0.033118442 -0.15808535, 0.1217784 -0.033164799 -0.16163801, 0.12177692 -0.033079967 -0.16173002, 0.11116496 0.10027787 -0.23518418, 0.11116494 0.10036214 -0.23520687, 0.11030667 0.10076736 -0.23516977, 0.11034276 0.1006939 -0.23523965, 0.11037537 0.10060588 -0.23529209, 0.11040305 0.10050754 -0.23532474, 0.11042465 0.10040303 -0.23533574, 0.11043657 0.1003191 -0.23532906, 0.11044374 0.10023662 -0.23530887, 0.11077608 0.10058172 -0.23522362, 0.12000369 0.10027787 -0.2351843, 0.12000361 0.1003622 -0.23520681, 0.12044145 0.10068095 -0.23525415, 0.12035537 0.100798 -0.23510623, 0.12051038 0.10075215 -0.23519729, 0.12030812 0.10072142 -0.23517476, 0.12010564 0.10043597 -0.23522471, 0.12011905 0.10054702 -0.23521526, 0.12023021 0.10052407 -0.23525189, 0.12013668 0.10065262 -0.2351816, 0.12026553 0.10062853 -0.23522435, 0.12037961 0.10059264 -0.23529257, 0.12009871 0.10034834 -0.23521483, 0.12020387 0.10041368 -0.23525606, 0.12009516 0.10026349 -0.23519, 0.12032832 0.10049164 -0.2353103, 0.12019037 0.10032615 -0.23524262, 0.12029056 0.10038343 -0.23530684, 0.12018384 0.1002413 -0.23521493, 0.12027153 0.10029717 -0.2352891, 0.12026252 0.10021269 -0.23525868, 0.12018166 0.10082635 -0.2350498, 0.12015802 0.10074721 -0.23512545, 0.1199391 0.099577904 -0.23663364, 0.11996879 0.09967345 -0.23669533, 0.12002175 0.099755079 -0.23676072, 0.12009536 0.099818438 -0.23682655, 0.1201856 0.099859804 -0.23688938, 0.12028733 0.099877372 -0.23694551, 0.12012039 0.099763483 -0.23717524, 0.11985554 0.099683523 -0.2373365, 0.11993121 0.099645346 -0.23676647, 0.11997955 0.099720746 -0.23683988, 0.11991888 0.09968929 -0.23691455, 0.12004615 0.099776626 -0.23691712, 0.11997549 0.099737912 -0.23700143, 0.12004401 0.099763036 -0.23709022, 0.11981608 0.09969449 -0.23723345, 0.11970446 0.099663094 -0.23737821, 0.11955307 0.099656194 -0.23739244, 0.1195531 0.099671245 -0.23728584, 0.11990334 0.0995543 -0.23670028, 0.11987723 0.099620342 -0.2368338, 0.11978035 0.099681288 -0.23712923, 0.11968486 0.099677116 -0.23727168, 0.11985253 0.099533767 -0.23676302, 0.11975063 0.099644601 -0.23702912, 0.11966729 0.099667177 -0.23716426, 0.11955318 0.099663213 -0.23717856, 0.11972815 0.099586174 -0.23693812, 0.11965249 0.09963426 -0.23706152, 0.11955318 0.099632218 -0.23707533, 0.11971378 0.099508926 -0.23685995, 0.11964111 0.09957996 -0.23696841, 0.11955324 0.099579945 -0.23698115, 0.11955325 0.099508673 -0.23690046, 0.11963373 0.099506184 -0.2368882, 0.12021853 0.099817991 -0.23706536, 0.1201276 0.099809676 -0.23699389, 0.11038603 0.09965606 -0.23739246, 0.11038609 0.09967126 -0.23728588, 0.11038607 0.099663138 -0.23717846, 0.11038603 0.099632218 -0.23707548, 0.11038603 0.099579886 -0.2369813, 0.11038591 0.099508718 -0.23690057, 0.10967639 0.099436492 -0.23700489, 0.10968977 0.09951371 -0.23708303, 0.10971101 0.099571958 -0.23717499, 0.10973896 0.099608257 -0.23727575, 0.10977225 0.099620983 -0.2373805, 0.10980922 0.099609733 -0.23748396, 0.13340786 -0.032648966 -0.14449194, 0.13340798 -0.033279106 -0.14485565, 0.13303579 -0.032661468 -0.14452714, 0.13340782 -0.032763228 -0.14447181, 0.13303222 -0.032774955 -0.14451021, 0.13340795 -0.032879204 -0.14447847, 0.1330339 -0.032888919 -0.14451905, 0.13340798 -0.032990515 -0.14451176, 0.13304093 -0.032997906 -0.14455312, 0.13340792 -0.033091038 -0.14456981, 0.13305289 -0.033096045 -0.14461038, 0.13340798 -0.033175513 -0.14464942, 0.1330691 -0.033178374 -0.14468816, 0.13340786 -0.033239409 -0.14474645, 0.13308874 -0.033240587 -0.14478201, 0.13311091 -0.033279344 -0.1448876, 0.1425751 -0.032648876 -0.14449209, 0.14257511 -0.032763213 -0.14447178, 0.14257514 -0.032879263 -0.14447846, 0.14257503 -0.032990366 -0.14451171, 0.14257503 -0.033091068 -0.14456968, 0.14257511 -0.033175558 -0.1446494, 0.14257503 -0.033239365 -0.14474647, 0.14257514 -0.033279076 -0.14485563, 0.14267972 -0.033178613 -0.14464138, 0.14279258 -0.03318347 -0.14460973, 0.1427002 -0.033240587 -0.14473523, 0.14283192 -0.033242747 -0.14469533, 0.14287598 -0.033279851 -0.14479142, 0.14296356 -0.033245564 -0.14462404, 0.14302447 -0.033280477 -0.14470656, 0.14264858 -0.032980934 -0.1444995, 0.14266264 -0.033096328 -0.14456411, 0.14275984 -0.033105105 -0.14453858, 0.14318407 -0.03328155 -0.14456214, 0.14333856 -0.033278331 -0.1442792, 0.14290893 -0.033190146 -0.14455046, 0.14264114 -0.032834485 -0.14446527, 0.14310923 -0.033249751 -0.1444989, 0.14323515 -0.033236444 -0.14423697, 0.1427319 -0.032994866 -0.14447765, 0.14286292 -0.033116952 -0.14448847, 0.14304197 -0.033199459 -0.14444233, 0.14314386 -0.033169329 -0.14419965, 0.14264295 -0.032687962 -0.14447443, 0.14271565 -0.032853797 -0.14444226, 0.14282241 -0.033013374 -0.14443375, 0.14298451 -0.033133402 -0.14439382, 0.14306992 -0.033080652 -0.14416929, 0.14271691 -0.032710671 -0.14444487, 0.14279655 -0.032879829 -0.14439861, 0.14272326 -0.033279359 -0.1448404, 0.14293185 -0.033039704 -0.14434941, 0.14279349 -0.032741621 -0.14439458, 0.14289391 -0.032916814 -0.14431728, 0.14301762 -0.032975763 -0.14414777, 0.14288199 -0.032786712 -0.14430709, 0.14298972 -0.032860249 -0.14413644, 0.14348722 -0.032860398 -0.14292137, 0.14351511 -0.032975793 -0.14293306, 0.14356756 -0.033080727 -0.14295448, 0.14364147 -0.033169374 -0.14298476, 0.14373264 -0.033236459 -0.14302205, 0.14383604 -0.033278346 -0.14306444, 0.14355448 -0.033182263 -0.14216594, 0.14349574 -0.033189952 -0.14209478, 0.14361468 -0.03323485 -0.14211364, 0.14354542 -0.033238769 -0.14203481, 0.14346799 -0.033241481 -0.14197399, 0.14359006 -0.033267692 -0.14198105, 0.14381054 -0.033244759 -0.14280201, 0.14383554 -0.033252269 -0.1425723, 0.14391288 -0.033280343 -0.14281775, 0.14393057 -0.033282265 -0.14256451, 0.14350238 -0.033269048 -0.14191513, 0.14360237 -0.033172026 -0.14225216, 0.14349452 -0.033101931 -0.14221825, 0.14371899 -0.033187896 -0.14278783, 0.14374956 -0.033204779 -0.14257918, 0.14353442 -0.033084884 -0.1422943, 0.14348617 -0.032982603 -0.14232393, 0.14389266 -0.0332838 -0.14233273, 0.14342947 -0.033195093 -0.14204007, 0.14355493 -0.032956719 -0.14276282, 0.14362684 -0.033093363 -0.14277376, 0.14344555 -0.03311488 -0.1421553, 0.1434499 -0.033006683 -0.14225675, 0.14380898 -0.033258423 -0.1423597, 0.1433903 -0.033123836 -0.14210726, 0.143407 -0.03302516 -0.1422016, 0.14365968 -0.033125237 -0.14258657, 0.1437324 -0.033218369 -0.1423844, 0.14380535 -0.033285111 -0.14212658, 0.14358202 -0.033007875 -0.14259286, 0.14373612 -0.033263549 -0.14216937, 0.14365031 -0.033151165 -0.14241093, 0.14372803 -0.033285633 -0.14201528, 0.14367232 -0.03322944 -0.14220895, 0.1436692 -0.033265784 -0.14206654, 0.14363798 -0.033286169 -0.14192306, 0.14357424 -0.033050433 -0.14243533, 0.14353931 -0.033286482 -0.14185168, 0.13434638 -0.033281833 -0.14178051, 0.13434641 -0.033249497 -0.14187984, 0.13434638 -0.033197314 -0.14197041, 0.13434647 -0.033127487 -0.14204811, 0.13308468 -0.033278868 -0.14219277, 0.13314632 -0.033237964 -0.14228453, 0.13320075 -0.033172324 -0.14236599, 0.13324538 -0.033085629 -0.14243202, 0.13391234 -0.033281237 -0.14182873, 0.1339332 -0.033247262 -0.14192863, 0.13395192 -0.033192411 -0.1420186, 0.13396782 -0.033119321 -0.14209512, 0.13013361 -0.03264834 -0.15248716, 0.13013369 -0.033278674 -0.1528507, 0.12976165 -0.03266117 -0.15252241, 0.13013367 -0.032762796 -0.15246683, 0.12975802 -0.032774493 -0.15250549, 0.13013367 -0.032878786 -0.15247363, 0.12975965 -0.032888621 -0.1525144, 0.13013364 -0.032990038 -0.15250677, 0.12976675 -0.032997444 -0.15254831, 0.13013367 -0.033090621 -0.15256482, 0.12977861 -0.033095539 -0.15260556, 0.13013361 -0.033175007 -0.15264452, 0.12979482 -0.033177927 -0.15268326, 0.13013367 -0.033238947 -0.15274161, 0.12981461 -0.033240169 -0.15277717, 0.12983669 -0.033278868 -0.15288278, 0.13930082 -0.032648459 -0.15248716, 0.13930076 -0.032762811 -0.15246692, 0.13930082 -0.032878771 -0.15247357, 0.13930082 -0.032989994 -0.15250671, 0.13930076 -0.033090636 -0.15256491, 0.13930082 -0.033175126 -0.15264452, 0.13930085 -0.033238947 -0.15274161, 0.13930078 -0.033278674 -0.1528507, 0.13940552 -0.033178136 -0.15263656, 0.13951838 -0.033182994 -0.15260494, 0.13942599 -0.033240214 -0.15273035, 0.13955772 -0.033242241 -0.15269053, 0.13960175 -0.033279419 -0.1527866, 0.13968927 -0.033245087 -0.15261933, 0.1397502 -0.033280104 -0.15270169, 0.13937432 -0.032980397 -0.15249479, 0.13938846 -0.033095866 -0.15255924, 0.1394856 -0.033104673 -0.15253365, 0.13990973 -0.033281043 -0.15255721, 0.1400643 -0.033277869 -0.15227455, 0.13963473 -0.033189654 -0.15254566, 0.13936684 -0.032834038 -0.15246049, 0.139835 -0.03324914 -0.15249404, 0.13996089 -0.033236086 -0.15223199, 0.13945767 -0.032994375 -0.15247276, 0.1395887 -0.033116415 -0.15248354, 0.1397676 -0.033199042 -0.1524374, 0.1398696 -0.033168852 -0.1521948, 0.13936877 -0.03268756 -0.15246964, 0.13944137 -0.03285338 -0.15243733, 0.13954814 -0.033012956 -0.15242894, 0.13971031 -0.033132926 -0.15238893, 0.13979578 -0.033080354 -0.15216458, 0.13944265 -0.032710299 -0.15243998, 0.13952217 -0.032879353 -0.15239364, 0.13944906 -0.033278942 -0.15283579, 0.13965762 -0.033039227 -0.15234435, 0.13951911 -0.032741234 -0.15238963, 0.13961965 -0.032916427 -0.15231246, 0.13974333 -0.032975271 -0.15214306, 0.13960773 -0.03278625 -0.15230244, 0.13971546 -0.032859847 -0.15213159, 0.14021291 -0.032859936 -0.1509167, 0.14024092 -0.03297545 -0.15092814, 0.14029332 -0.033080339 -0.15094957, 0.14036715 -0.033168972 -0.1509798, 0.14045854 -0.033236116 -0.15101726, 0.14056186 -0.033278003 -0.15105943, 0.14027113 -0.033238262 -0.15003002, 0.1401937 -0.033241093 -0.14996904, 0.14031573 -0.033267274 -0.14997621, 0.14053644 -0.033244357 -0.15079714, 0.14056136 -0.033251867 -0.15056731, 0.1406386 -0.033279881 -0.15081276, 0.14065638 -0.033281833 -0.15055963, 0.14022805 -0.033268437 -0.14991014, 0.14032818 -0.033171639 -0.15024723, 0.14022027 -0.033101469 -0.1502132, 0.1402802 -0.033181757 -0.1501611, 0.14044483 -0.033187434 -0.15078296, 0.14047535 -0.033204287 -0.15057428, 0.1402602 -0.033084497 -0.15028934, 0.14021195 -0.032982126 -0.15031923, 0.14061846 -0.033283338 -0.15032782, 0.1401553 -0.033194736 -0.15003522, 0.14022148 -0.033189446 -0.1500898, 0.14028057 -0.032956332 -0.15075798, 0.14017124 -0.033114448 -0.15015046, 0.14035274 -0.033092976 -0.15076898, 0.14017572 -0.033006176 -0.15025188, 0.14053471 -0.033257931 -0.15035482, 0.14011611 -0.033123389 -0.15010239, 0.14038552 -0.03312479 -0.15058173, 0.1401328 -0.033024654 -0.15019692, 0.14045826 -0.033217937 -0.15037939, 0.14053105 -0.033284619 -0.15012176, 0.14030777 -0.033007354 -0.15058811, 0.14046185 -0.033262998 -0.15016456, 0.14037608 -0.033150733 -0.15040587, 0.14045386 -0.033285141 -0.15001045, 0.14039804 -0.033228859 -0.15020408, 0.14039494 -0.033265457 -0.15006162, 0.14036378 -0.033285677 -0.14991829, 0.14029993 -0.033049956 -0.15043043, 0.14034045 -0.033234268 -0.15010887, 0.14026505 -0.033285975 -0.14984691, 0.13107218 -0.033281371 -0.14977571, 0.13107218 -0.033249184 -0.14987513, 0.13107218 -0.033196971 -0.14996549, 0.13107218 -0.033127129 -0.15004307, 0.12981036 -0.033278406 -0.15018789, 0.12987192 -0.033237457 -0.15027958, 0.12992658 -0.033171952 -0.15036088, 0.1299711 -0.033085197 -0.15042719, 0.13063814 -0.033280894 -0.14982387, 0.13065891 -0.033246815 -0.14992374, 0.13067771 -0.033192083 -0.15001366, 0.13069354 -0.033118919 -0.1500901, 0.1250526 -0.033165172 -0.15364285, 0.12505111 -0.033080325 -0.15373488, 0.12358522 -0.03264758 -0.16847731, 0.12358522 -0.033277839 -0.1688409, 0.12321311 -0.032660156 -0.16851248, 0.12358516 -0.032761961 -0.16845705, 0.12320946 -0.032773584 -0.16849571, 0.12358522 -0.032877892 -0.16846384, 0.12321125 -0.032887667 -0.16850454, 0.12358521 -0.032989115 -0.16849715, 0.12321824 -0.032996565 -0.16853847, 0.12358519 -0.033089787 -0.16855516, 0.12323013 -0.03309463 -0.16859575, 0.12358525 -0.033174247 -0.16863479, 0.1232464 -0.033177033 -0.16867347, 0.12358521 -0.033238143 -0.16873187, 0.1232661 -0.033239201 -0.16876738, 0.12328824 -0.033277988 -0.16887324, 0.13275242 -0.032647565 -0.16847731, 0.13275242 -0.032761887 -0.16845717, 0.13275242 -0.032877848 -0.16846381, 0.13275234 -0.0329891 -0.16849709, 0.1327523 -0.033089772 -0.16855513, 0.13275239 -0.033174202 -0.16863473, 0.13275236 -0.033238053 -0.16873167, 0.13275242 -0.033277795 -0.16884087, 0.13285697 -0.033177182 -0.16862689, 0.13296983 -0.03318207 -0.16859515, 0.13287747 -0.03323926 -0.16872059, 0.13300914 -0.033241346 -0.16868065, 0.1330533 -0.03327848 -0.16877662, 0.1331408 -0.033244297 -0.16860949, 0.13320175 -0.03327921 -0.16869189, 0.13282597 -0.032979518 -0.16848494, 0.13284001 -0.033094957 -0.16854943, 0.13293713 -0.033103779 -0.16852377, 0.13336128 -0.033280089 -0.1685475, 0.13351583 -0.033277079 -0.16826461, 0.13308622 -0.033188745 -0.1685358, 0.13281834 -0.032833144 -0.1684507, 0.13328648 -0.03324835 -0.16848432, 0.13341242 -0.033235162 -0.16822238, 0.13290922 -0.03299351 -0.16846299, 0.13304019 -0.033115521 -0.16847371, 0.13321918 -0.033198103 -0.16842769, 0.13332121 -0.033168033 -0.16818488, 0.13282037 -0.032686636 -0.16845979, 0.13289297 -0.032852545 -0.16842757, 0.13299978 -0.033012047 -0.16841899, 0.13316175 -0.033132032 -0.16837902, 0.13324726 -0.03307943 -0.16815458, 0.1328941 -0.032709345 -0.16843043, 0.13297379 -0.032878533 -0.16838394, 0.1329006 -0.033278033 -0.16882597, 0.13310909 -0.033038273 -0.16833471, 0.13297063 -0.03274034 -0.16837989, 0.13307114 -0.032915547 -0.16830277, 0.13319476 -0.032974437 -0.16813314, 0.13305926 -0.032785341 -0.16829263, 0.13316703 -0.032858983 -0.1681218, 0.13366446 -0.032859072 -0.166907, 0.13369238 -0.032974407 -0.16691829, 0.13374484 -0.03307946 -0.16693975, 0.13381875 -0.033168152 -0.16697003, 0.13390994 -0.033235207 -0.16700743, 0.13401341 -0.033277199 -0.16704975, 0.13372274 -0.033237532 -0.16602033, 0.1336453 -0.033240318 -0.1659594, 0.13376722 -0.0332665 -0.16596638, 0.13398793 -0.033243388 -0.16678728, 0.13401294 -0.033251002 -0.16655757, 0.13409013 -0.033279017 -0.16680311, 0.13410795 -0.033281043 -0.16654982, 0.13367955 -0.033267736 -0.16590059, 0.1337797 -0.033170611 -0.16623755, 0.13367176 -0.03310065 -0.16620328, 0.13373172 -0.033180997 -0.16615142, 0.13389635 -0.033186629 -0.16677333, 0.13392687 -0.033203557 -0.16656448, 0.1337117 -0.033083603 -0.16627957, 0.13366342 -0.032981232 -0.16630949, 0.13406986 -0.033282518 -0.16631804, 0.13360679 -0.03319402 -0.1660253, 0.13367303 -0.033188716 -0.16608012, 0.13373214 -0.032955423 -0.16674806, 0.13362288 -0.033113673 -0.16614057, 0.1338042 -0.033092067 -0.16675915, 0.13362718 -0.033005401 -0.16624202, 0.13398623 -0.033257186 -0.1663451, 0.13356757 -0.033122599 -0.16609262, 0.13383698 -0.033123925 -0.16657187, 0.13358438 -0.033023879 -0.16618718, 0.13390982 -0.033217117 -0.16636969, 0.1339826 -0.03328377 -0.16611193, 0.13375928 -0.033006504 -0.16657829, 0.13391328 -0.033262163 -0.16615482, 0.13382754 -0.033149943 -0.16639613, 0.13390529 -0.033284381 -0.16600074, 0.1338495 -0.033228084 -0.16619422, 0.13384643 -0.033264697 -0.16605185, 0.1338153 -0.033284858 -0.16590846, 0.13375145 -0.033049092 -0.16642059, 0.13379201 -0.033233464 -0.16609912, 0.13371658 -0.033285215 -0.16583695, 0.12452373 -0.033280596 -0.16576591, 0.12452367 -0.033248261 -0.1658653, 0.12452377 -0.033196136 -0.1659558, 0.12452358 -0.033126235 -0.16603348, 0.12326193 -0.033277586 -0.16617823, 0.12332356 -0.033236578 -0.1662699, 0.12337816 -0.033171013 -0.1663512, 0.12342259 -0.033084258 -0.16641739, 0.12408958 -0.03328 -0.16581421, 0.12411036 -0.033245981 -0.16591386, 0.12412916 -0.033191159 -0.16600399, 0.12414499 -0.033118024 -0.16608037, 0.11850408 -0.033164352 -0.16963305, 0.11850265 -0.033079505 -0.16972516, 0.12031098 -0.032647222 -0.17647251, 0.12031095 -0.033277303 -0.17683613, 0.11993895 -0.032659873 -0.17650762, 0.12031101 -0.032761574 -0.17645228, 0.11993532 -0.032773301 -0.17649093, 0.12031093 -0.032877505 -0.17645894, 0.11993705 -0.03288734 -0.17649972, 0.12031092 -0.032988772 -0.17649212, 0.11994399 -0.032996163 -0.17653361, 0.12031098 -0.03308928 -0.1765503, 0.11995585 -0.033094347 -0.17659092, 0.12031101 -0.033173889 -0.1766299, 0.11997209 -0.033176675 -0.17666858, 0.12031092 -0.033237651 -0.17672688, 0.11999184 -0.033238918 -0.1767626, 0.12001391 -0.033277661 -0.17686823, 0.12947819 -0.032647178 -0.17647246, 0.1294781 -0.032761499 -0.17645231, 0.12947811 -0.032877505 -0.17645895, 0.12947811 -0.032988727 -0.17649221, 0.12947811 -0.03308931 -0.17655027, 0.12947811 -0.03317371 -0.1766299, 0.12947811 -0.033237606 -0.17672694, 0.12947817 -0.033277348 -0.17683619, 0.12958266 -0.033176705 -0.17662206, 0.12969567 -0.033181727 -0.1765902, 0.12960322 -0.033238888 -0.17671573, 0.12973498 -0.033241004 -0.17667595, 0.129779 -0.033278048 -0.176772, 0.1298665 -0.033243805 -0.17660463, 0.12992753 -0.033278733 -0.176687, 0.12955169 -0.032979056 -0.17648008, 0.12956573 -0.033094555 -0.17654467, 0.12966289 -0.033103377 -0.17651904, 0.13008696 -0.033279657 -0.17654264, 0.13024151 -0.033276588 -0.17625976, 0.12981199 -0.033188283 -0.17653093, 0.12954408 -0.032832712 -0.17644584, 0.13001215 -0.033247858 -0.17647946, 0.13013816 -0.033234641 -0.17621747, 0.12963499 -0.032993123 -0.17645803, 0.129766 -0.033115059 -0.17646885, 0.12994501 -0.033197731 -0.17642286, 0.1300469 -0.033167601 -0.17618001, 0.12954605 -0.032686293 -0.1764549, 0.12961861 -0.032852128 -0.1764226, 0.12972558 -0.033011734 -0.17641413, 0.12988758 -0.033131659 -0.1763742, 0.12997302 -0.033078998 -0.17614976, 0.12961987 -0.032709047 -0.17642537, 0.12969959 -0.032878071 -0.17637908, 0.12962623 -0.033277616 -0.17682102, 0.12983483 -0.033037871 -0.17632967, 0.12969649 -0.032739922 -0.17637506, 0.12979692 -0.032915145 -0.17629775, 0.12992072 -0.032974035 -0.17612827, 0.129785 -0.032784909 -0.17628777, 0.12989265 -0.032858595 -0.17611685, 0.13039026 -0.032858565 -0.17490198, 0.13041815 -0.032974094 -0.17491342, 0.13047063 -0.033079058 -0.17493498, 0.13054454 -0.03316763 -0.17496514, 0.13063574 -0.033234745 -0.17500257, 0.13073912 -0.033276722 -0.1750448, 0.13044846 -0.033236995 -0.17401527, 0.13037097 -0.033239856 -0.17395447, 0.13049296 -0.033265978 -0.17396154, 0.13081598 -0.033278629 -0.17479835, 0.13073868 -0.033250555 -0.17455266, 0.13083357 -0.033280566 -0.17454486, 0.1307137 -0.033242986 -0.1747825, 0.13040528 -0.0332672 -0.17389564, 0.13050547 -0.033170372 -0.1742325, 0.13039756 -0.033100277 -0.1741984, 0.13045734 -0.033180445 -0.17414643, 0.13043749 -0.033083215 -0.17427467, 0.13062215 -0.033186242 -0.17476843, 0.13065252 -0.033202931 -0.17455967, 0.13038921 -0.032980815 -0.17430447, 0.13079563 -0.033282012 -0.1743132, 0.13033259 -0.033193484 -0.17402039, 0.13039875 -0.033188164 -0.17407511, 0.130458 -0.032954961 -0.17474319, 0.13053 -0.033091575 -0.17475428, 0.13034856 -0.033113167 -0.17413567, 0.13035297 -0.03300491 -0.17423715, 0.13071203 -0.03325668 -0.17434026, 0.13029325 -0.033122078 -0.17408775, 0.13031006 -0.033023417 -0.17418216, 0.13056281 -0.033123523 -0.174567, 0.13063544 -0.03321667 -0.17436485, 0.13070834 -0.033283263 -0.17410709, 0.13048503 -0.033006132 -0.17457329, 0.13063908 -0.033261672 -0.17414992, 0.13055339 -0.033149511 -0.17439117, 0.13063103 -0.033283904 -0.17399572, 0.13057533 -0.033227652 -0.17418934, 0.13057217 -0.033264086 -0.17404689, 0.13054109 -0.033284441 -0.17390357, 0.13047731 -0.033048674 -0.17441569, 0.13051781 -0.033232972 -0.17409424, 0.13044232 -0.033284724 -0.1738321, 0.12124939 -0.033280194 -0.17376113, 0.12124951 -0.033247963 -0.17386049, 0.12124942 -0.033195719 -0.17395082, 0.12124951 -0.033125773 -0.17402869, 0.11998771 -0.033277124 -0.17417324, 0.12004931 -0.03323628 -0.17426509, 0.12010381 -0.033170581 -0.17434625, 0.12014821 -0.033083856 -0.17441253, 0.12081535 -0.033279583 -0.17380932, 0.12083621 -0.033245578 -0.17390913, 0.12085496 -0.033190727 -0.17399922, 0.12087081 -0.033117622 -0.17407575, 0.11522998 -0.033163905 -0.17762814, 0.11522843 -0.033079088 -0.17772025, 0.11703674 -0.032646775 -0.18446758, 0.11703676 -0.03327696 -0.18483131, 0.11666465 -0.032659411 -0.18450271, 0.11703674 -0.032761097 -0.18444744, 0.116661 -0.032772824 -0.184486, 0.11703669 -0.032877058 -0.18445402, 0.11666276 -0.032886833 -0.18449473, 0.11703677 -0.03298834 -0.18448737, 0.11666979 -0.032995731 -0.18452877, 0.11703669 -0.033088923 -0.18454534, 0.11668165 -0.033093855 -0.18458608, 0.11703669 -0.033173457 -0.18462497, 0.11669789 -0.033176184 -0.18466359, 0.11703666 -0.033237368 -0.18472198, 0.11671753 -0.033238426 -0.18475765, 0.11673974 -0.033277258 -0.18486324, 0.12620384 -0.032646641 -0.18446764, 0.12620386 -0.032761067 -0.1844475, 0.12620382 -0.032876968 -0.18445401, 0.1262037 -0.032988191 -0.18448727, 0.12620378 -0.033088848 -0.18454531, 0.12620388 -0.033173248 -0.18462504, 0.12620389 -0.033237144 -0.18472221, 0.12620376 -0.033276841 -0.18483125, 0.12630841 -0.033176273 -0.18461725, 0.12642133 -0.033181235 -0.18458542, 0.12632902 -0.033238366 -0.1847109, 0.12646063 -0.033240512 -0.18467109, 0.12650473 -0.033277586 -0.18476705, 0.12659228 -0.033243343 -0.18459991, 0.12665331 -0.033278272 -0.18468216, 0.12627725 -0.032978669 -0.1844752, 0.1262915 -0.033094123 -0.18453969, 0.12638848 -0.033102855 -0.18451403, 0.12681279 -0.033279255 -0.18453771, 0.12696725 -0.03327617 -0.18425494, 0.1265377 -0.033187941 -0.1845261, 0.12626989 -0.032832339 -0.18444102, 0.126738 -0.033247456 -0.1844746, 0.12686394 -0.033234313 -0.18421258, 0.12636063 -0.032992572 -0.1844531, 0.12649171 -0.033114642 -0.18446405, 0.12667076 -0.033197299 -0.18441786, 0.12677269 -0.033167109 -0.18417527, 0.12627186 -0.032685876 -0.18445008, 0.12634441 -0.032851636 -0.18441769, 0.12645128 -0.033011273 -0.18440926, 0.12661326 -0.033131167 -0.18436936, 0.12669885 -0.033078477 -0.184145, 0.12634568 -0.032708511 -0.18442048, 0.12642516 -0.032877609 -0.18437423, 0.12635204 -0.033277169 -0.18481612, 0.12656061 -0.033037439 -0.18432499, 0.1264222 -0.032739475 -0.18437016, 0.1265226 -0.032914504 -0.18429294, 0.12664634 -0.032973513 -0.18412337, 0.12651071 -0.032784402 -0.18428287, 0.1266185 -0.032858193 -0.18411189, 0.12711605 -0.032858208 -0.18289721, 0.12714398 -0.032973558 -0.18290848, 0.12719636 -0.033078656 -0.18293001, 0.12727034 -0.033167288 -0.18296036, 0.12736151 -0.033234373 -0.1829977, 0.12746483 -0.033276185 -0.18303993, 0.12717423 -0.033236578 -0.18201041, 0.12709665 -0.03323929 -0.18194965, 0.12721875 -0.033265531 -0.18195662, 0.12754169 -0.033278167 -0.18279335, 0.12746441 -0.033250034 -0.18254781, 0.12755941 -0.033280089 -0.18254007, 0.12743953 -0.033242643 -0.18277749, 0.1271311 -0.033266723 -0.18189073, 0.12723124 -0.033169806 -0.18222767, 0.12712336 -0.033099815 -0.18219367, 0.12718314 -0.033179983 -0.18214157, 0.12716328 -0.033082649 -0.18226971, 0.12734792 -0.033185795 -0.18276352, 0.12737831 -0.033202484 -0.18255472, 0.127115 -0.032980368 -0.18229963, 0.1275214 -0.033281595 -0.18230844, 0.12705827 -0.033193037 -0.18201545, 0.12712455 -0.033187777 -0.1820702, 0.12718379 -0.032954633 -0.1827383, 0.1272558 -0.033091232 -0.1827493, 0.12707445 -0.033112764 -0.18213078, 0.1270788 -0.033004463 -0.18223223, 0.12743771 -0.033256337 -0.18233529, 0.12701903 -0.03312166 -0.18208279, 0.12703583 -0.033022881 -0.18217728, 0.12728861 -0.033123106 -0.1825622, 0.12736127 -0.033216193 -0.18235993, 0.12743409 -0.033282891 -0.18210222, 0.12721086 -0.03300564 -0.18256846, 0.12736487 -0.033261225 -0.18214491, 0.12727916 -0.033149064 -0.18238622, 0.12735686 -0.033283427 -0.1819908, 0.12730107 -0.033227161 -0.18218452, 0.127298 -0.033263728 -0.18204203, 0.12726685 -0.033284023 -0.18189865, 0.12720306 -0.033048242 -0.18241103, 0.12724352 -0.033232495 -0.18208936, 0.12716815 -0.033284277 -0.18182728, 0.11797519 -0.033279672 -0.18175624, 0.11797526 -0.033247486 -0.18185556, 0.11797526 -0.033195272 -0.18194592, 0.11797521 -0.033125356 -0.18202376, 0.11671348 -0.033276722 -0.18216845, 0.11677502 -0.033235848 -0.18226022, 0.11682968 -0.033170238 -0.18234146, 0.11687417 -0.033083603 -0.18240783, 0.11754116 -0.033279076 -0.18180448, 0.11756192 -0.033245176 -0.18190415, 0.11758071 -0.033190295 -0.18199429, 0.11759658 -0.033117205 -0.18207081, 0.11343916 -0.033276349 -0.19016345, 0.11350082 -0.033235356 -0.19025518, 0.11355531 -0.033169731 -0.19033661, 0.10868144 -0.033163026 -0.19361848, 0.11359985 -0.033082992 -0.19040276, 0.10867991 -0.033078194 -0.19371055, 0.114701 -0.033124834 -0.19001885, 0.11470094 -0.03327924 -0.18975119, 0.1142669 -0.033278659 -0.18979962, 0.11470087 -0.033247024 -0.18985066, 0.1142877 -0.033244625 -0.18989925, 0.11470097 -0.033194795 -0.18994109, 0.11430642 -0.033189803 -0.18998928, 0.11432227 -0.033116713 -0.19006579, 0.12389997 -0.033236206 -0.19000553, 0.12382257 -0.033238977 -0.18994488, 0.12394451 -0.033265129 -0.18995172, 0.12426746 -0.033277735 -0.19078849, 0.12419005 -0.033249587 -0.19054294, 0.12428512 -0.033279613 -0.19053525, 0.12416513 -0.033242106 -0.19077262, 0.1238569 -0.03326638 -0.18988584, 0.12395705 -0.033169478 -0.19022277, 0.12384902 -0.033099428 -0.19018871, 0.12390903 -0.033179581 -0.19013678, 0.12407367 -0.033185303 -0.19075873, 0.12410417 -0.033202112 -0.19054995, 0.12388898 -0.033082306 -0.19026482, 0.1238407 -0.032979906 -0.19029459, 0.12424731 -0.033281162 -0.19030343, 0.12378411 -0.03319259 -0.19001061, 0.12385036 -0.033187345 -0.19006556, 0.1239095 -0.032954156 -0.19073342, 0.12384176 -0.032857716 -0.1908922, 0.12386967 -0.03297323 -0.19090365, 0.12380014 -0.033112422 -0.190126, 0.12398155 -0.033090815 -0.19074449, 0.12380442 -0.033004045 -0.19022737, 0.12416367 -0.033255935 -0.19033039, 0.12374489 -0.033121318 -0.19007805, 0.12376168 -0.033022463 -0.19017242, 0.12401429 -0.033122614 -0.19055732, 0.12408702 -0.033215731 -0.19035506, 0.12415987 -0.033282414 -0.19009744, 0.12393668 -0.033005178 -0.19056354, 0.12409069 -0.033260882 -0.19014013, 0.12400496 -0.033148602 -0.19038151, 0.12408271 -0.033283055 -0.18998609, 0.12402692 -0.033226788 -0.19017957, 0.1240238 -0.033263281 -0.19003724, 0.12399253 -0.033283591 -0.18989371, 0.12392882 -0.033047736 -0.19040607, 0.12396932 -0.033232197 -0.19008438, 0.1241906 -0.033275783 -0.19103502, 0.12389384 -0.033283845 -0.18982238, 0.12399599 -0.033166751 -0.19095559, 0.12408736 -0.033233941 -0.19099282, 0.12392198 -0.033078074 -0.19092521, 0.12334429 -0.032857656 -0.1921072, 0.12337217 -0.03297317 -0.19211863, 0.12342456 -0.033078119 -0.19214, 0.12349847 -0.033166692 -0.19217046, 0.12358975 -0.033233896 -0.19220774, 0.12369309 -0.033275709 -0.19224998, 0.12305473 -0.033238038 -0.19270584, 0.12314713 -0.033180803 -0.19258054, 0.12318642 -0.03324011 -0.19266614, 0.12303416 -0.033175871 -0.19261214, 0.1232305 -0.033277199 -0.19276199, 0.12331802 -0.033242971 -0.19259484, 0.1233791 -0.033277974 -0.19267711, 0.12292965 -0.032876506 -0.19244921, 0.12300308 -0.032978192 -0.19247037, 0.12292953 -0.032987863 -0.19248244, 0.12301728 -0.033093721 -0.19253488, 0.12311444 -0.033102542 -0.19250925, 0.1235386 -0.033278823 -0.1925329, 0.12326346 -0.033187509 -0.19252121, 0.1229296 -0.032760605 -0.19244252, 0.12299562 -0.032831877 -0.19243605, 0.12346366 -0.033247039 -0.19246967, 0.12308633 -0.032992199 -0.19244839, 0.12321739 -0.03311424 -0.19245908, 0.12292966 -0.032646284 -0.19246276, 0.12339664 -0.033196896 -0.19241293, 0.12299763 -0.032685384 -0.19244525, 0.1230702 -0.032851234 -0.19241291, 0.12317705 -0.033010811 -0.19240446, 0.12333903 -0.03313075 -0.19236453, 0.1230714 -0.032708034 -0.19241567, 0.12315094 -0.032877177 -0.1923693, 0.12328649 -0.033037037 -0.19231994, 0.12292969 -0.033276409 -0.19282646, 0.12307775 -0.033276722 -0.1928113, 0.12314796 -0.032739013 -0.19236512, 0.12292954 -0.033236772 -0.19271727, 0.12324841 -0.032914177 -0.19228804, 0.12323649 -0.032784015 -0.192278, 0.12292959 -0.033172905 -0.19262013, 0.12292957 -0.033088416 -0.19254048, 0.11376241 -0.032646254 -0.19246268, 0.11376248 -0.03276068 -0.19244252, 0.11376244 -0.032876655 -0.19244918, 0.11376256 -0.032987878 -0.19248238, 0.11376238 -0.03308855 -0.19254038, 0.11376245 -0.033172995 -0.19262011, 0.11376244 -0.033236787 -0.19271716, 0.11376245 -0.033276469 -0.19282635, 0.1133904 -0.032658964 -0.1924978, 0.11338682 -0.032772452 -0.192481, 0.11338845 -0.032886401 -0.19248986, 0.11339553 -0.032995373 -0.19252391, 0.11340743 -0.033093497 -0.19258103, 0.11342363 -0.033175781 -0.19265868, 0.11344321 -0.033237845 -0.19275279, 0.11346538 -0.033276707 -0.19285841, 0.11016499 -0.033275753 -0.19815871, 0.11022656 -0.033234909 -0.19825047, 0.11028107 -0.033169299 -0.19833159, 0.10540713 -0.033162609 -0.20161371, 0.11032565 -0.033082515 -0.19839787, 0.10540573 -0.033077896 -0.20170556, 0.11142671 -0.033124506 -0.19801383, 0.11142667 -0.033278853 -0.1977464, 0.11099263 -0.033278272 -0.19779465, 0.11142671 -0.033246621 -0.19784577, 0.11101349 -0.033244297 -0.19789442, 0.11142679 -0.033194482 -0.19793618, 0.11103225 -0.033189535 -0.19798444, 0.11104806 -0.033116281 -0.19806099, 0.12062572 -0.033235863 -0.19800057, 0.12054832 -0.033238575 -0.19793992, 0.1206703 -0.033264771 -0.19794686, 0.12099324 -0.033277407 -0.19878359, 0.12091586 -0.033249274 -0.19853806, 0.12101083 -0.033279225 -0.19853027, 0.12089095 -0.033241764 -0.1987679, 0.12058268 -0.033265963 -0.19788094, 0.12068275 -0.033169001 -0.19821796, 0.12057479 -0.033098966 -0.19818385, 0.12063469 -0.033179149 -0.19813167, 0.12079941 -0.03318502 -0.19875367, 0.12082985 -0.033201665 -0.19854507, 0.12061486 -0.033081904 -0.19826007, 0.12056647 -0.032979488 -0.19828998, 0.12097299 -0.0332807 -0.19829851, 0.12051 -0.033192262 -0.19800584, 0.12057604 -0.033186883 -0.19806059, 0.12063527 -0.032953724 -0.19872841, 0.12056755 -0.032857433 -0.1988873, 0.12059546 -0.032972798 -0.19889876, 0.12052596 -0.0331119 -0.19812113, 0.12070736 -0.033090368 -0.19873965, 0.12053032 -0.033003613 -0.19822268, 0.12088926 -0.033255383 -0.19832556, 0.12047055 -0.033120826 -0.19807303, 0.12048732 -0.033022046 -0.19816767, 0.12074 -0.033122107 -0.19855234, 0.12081276 -0.033215418 -0.19835015, 0.12088569 -0.033282056 -0.19809245, 0.12066235 -0.033004805 -0.19855879, 0.12081632 -0.03326036 -0.19813526, 0.12073065 -0.033148155 -0.19837664, 0.12080835 -0.033282652 -0.19798119, 0.12075253 -0.033226237 -0.19817476, 0.12074959 -0.033262834 -0.19803235, 0.12071835 -0.033283219 -0.19788881, 0.12065466 -0.033047363 -0.19840126, 0.12069491 -0.033231691 -0.19807947, 0.1209164 -0.03327544 -0.19903028, 0.12061964 -0.033283487 -0.1978174, 0.12081298 -0.033233419 -0.19898796, 0.12064786 -0.033077762 -0.19892029, 0.12072177 -0.033166423 -0.19895069, 0.12007 -0.032857284 -0.20010231, 0.12009789 -0.032972649 -0.20011364, 0.12015033 -0.033077702 -0.20013508, 0.12022421 -0.033166304 -0.20016539, 0.12031546 -0.033233479 -0.2002027, 0.12041877 -0.033275247 -0.20024513, 0.11978047 -0.033237517 -0.20070104, 0.11987293 -0.033180341 -0.20057556, 0.11991222 -0.033239767 -0.20066123, 0.11976002 -0.033175543 -0.20060743, 0.1199562 -0.033276737 -0.20075721, 0.12004378 -0.033242539 -0.2005899, 0.1201047 -0.033277482 -0.20067236, 0.11965534 -0.032876149 -0.20044422, 0.11972882 -0.032977805 -0.20046531, 0.11965534 -0.032987371 -0.2004776, 0.11974309 -0.033093289 -0.20052995, 0.11984022 -0.03310205 -0.20050435, 0.12026431 -0.033278331 -0.20052789, 0.11998929 -0.033187106 -0.20051633, 0.11965537 -0.032760143 -0.20043772, 0.1197214 -0.032831445 -0.20043106, 0.12018952 -0.033246532 -0.20046484, 0.11981216 -0.032991856 -0.20044348, 0.11994325 -0.033113852 -0.20045419, 0.11965534 -0.032645836 -0.20045781, 0.12012222 -0.033196405 -0.2004081, 0.11972344 -0.032684907 -0.20044038, 0.1197959 -0.032850727 -0.20040818, 0.11990286 -0.033010408 -0.20039956, 0.12006472 -0.033130273 -0.20035954, 0.11979719 -0.032707721 -0.20041068, 0.11987667 -0.032876775 -0.20036443, 0.12001215 -0.033036575 -0.20031507, 0.11965539 -0.033276051 -0.20082135, 0.11980364 -0.033276334 -0.20080638, 0.11987373 -0.032738581 -0.20036042, 0.11965536 -0.03323625 -0.20071228, 0.11997424 -0.032913789 -0.20028313, 0.11996233 -0.032783613 -0.20027313, 0.11965533 -0.033172414 -0.20061515, 0.11965536 -0.033087954 -0.20053561, 0.11048825 -0.032645881 -0.20045787, 0.11048825 -0.032760203 -0.20043766, 0.11048825 -0.032876164 -0.20044434, 0.11048824 -0.032987416 -0.20047759, 0.11048813 -0.033087999 -0.20053566, 0.11048825 -0.033172429 -0.20061529, 0.11048825 -0.033236295 -0.20071244, 0.11048825 -0.033276141 -0.20082152, 0.1101162 -0.032658517 -0.20049298, 0.1101125 -0.032771856 -0.20047617, 0.1101142 -0.032885909 -0.20048508, 0.1101214 -0.032994956 -0.20051898, 0.11013313 -0.033092886 -0.20057631, 0.11014928 -0.03317523 -0.20065379, 0.11016901 -0.033237487 -0.20074797, 0.11019129 -0.033276379 -0.20085345, 0.107214 -0.032645449 -0.20845298, 0.10721403 -0.03327556 -0.20881654, 0.10684192 -0.032658234 -0.20848812, 0.10721391 -0.03275986 -0.20843281, 0.10683823 -0.032771483 -0.20847131, 0.10721391 -0.032875732 -0.20843948, 0.10684 -0.032885566 -0.20848024, 0.10721385 -0.032987013 -0.20847262, 0.10684699 -0.032994464 -0.20851411, 0.10721391 -0.033087656 -0.20853068, 0.10685891 -0.033092543 -0.20857157, 0.10721403 -0.033172086 -0.20861031, 0.10687509 -0.033174783 -0.20864911, 0.10721387 -0.033235893 -0.20870748, 0.10689479 -0.033237055 -0.20874299, 0.1069169 -0.033275828 -0.20884873, 0.11638118 -0.032645464 -0.20845293, 0.11638115 -0.032759815 -0.20843281, 0.11638115 -0.032875672 -0.20843951, 0.11638118 -0.032987073 -0.20847268, 0.11638114 -0.033087641 -0.20853066, 0.1163812 -0.033172131 -0.20861042, 0.11638114 -0.033235818 -0.20870745, 0.11638109 -0.033275574 -0.20881654, 0.1164857 -0.033175007 -0.20860235, 0.11659862 -0.033179998 -0.2085707, 0.11650631 -0.033237159 -0.20869625, 0.116638 -0.033239186 -0.2086564, 0.11668196 -0.03327629 -0.20875227, 0.11676958 -0.033242077 -0.20858514, 0.11683065 -0.033277094 -0.20866761, 0.11645459 -0.032977358 -0.20846061, 0.11646877 -0.033092886 -0.20852508, 0.11656593 -0.033101708 -0.20849957, 0.11699016 -0.033278048 -0.20852314, 0.11714469 -0.033274934 -0.20824032, 0.11671498 -0.033186644 -0.20851135, 0.11644702 -0.032831043 -0.20842625, 0.11691529 -0.03324616 -0.20845982, 0.11704125 -0.033233047 -0.20819794, 0.11653794 -0.03299129 -0.20843874, 0.11666904 -0.033113524 -0.20844947, 0.1168481 -0.033196121 -0.20840324, 0.11695009 -0.033165872 -0.20816055, 0.11644922 -0.032684594 -0.20843543, 0.11652172 -0.032850325 -0.20840326, 0.11662854 -0.033010006 -0.20839475, 0.11679065 -0.03312996 -0.20835474, 0.11687614 -0.03307724 -0.20813023, 0.11652297 -0.032707244 -0.20840588, 0.11660253 -0.032876387 -0.20835958, 0.11652943 -0.033275887 -0.20880154, 0.11673795 -0.033036262 -0.20831026, 0.11659943 -0.032738239 -0.20835556, 0.11669999 -0.032913387 -0.20827833, 0.11682366 -0.032972366 -0.2081088, 0.11668797 -0.03278321 -0.20826815, 0.11679576 -0.032856852 -0.20809747, 0.11729319 -0.032856882 -0.20688246, 0.11732116 -0.032972306 -0.2068938, 0.11737354 -0.0330773 -0.20691548, 0.1174476 -0.033165962 -0.20694567, 0.11753879 -0.033233076 -0.20698299, 0.11764218 -0.033274889 -0.20702539, 0.11736046 -0.033178717 -0.20612694, 0.11730184 -0.03318654 -0.20605566, 0.11742069 -0.033231258 -0.2060747, 0.11735147 -0.033235341 -0.20599571, 0.11727403 -0.033238083 -0.20593502, 0.11739594 -0.03326422 -0.205942, 0.11761671 -0.033241272 -0.20676288, 0.11764167 -0.033248693 -0.20653321, 0.11771895 -0.033276901 -0.20677866, 0.11773659 -0.033278704 -0.20652531, 0.11730838 -0.033265501 -0.20587614, 0.11740845 -0.033168584 -0.20621315, 0.11730063 -0.033098578 -0.20617893, 0.11752523 -0.033184409 -0.20674895, 0.1175556 -0.033201247 -0.20654012, 0.11734053 -0.033081442 -0.2062552, 0.1172922 -0.032979101 -0.20628512, 0.11769868 -0.033280417 -0.20629378, 0.11723565 -0.03319183 -0.20600094, 0.11736101 -0.032953292 -0.2067236, 0.11743306 -0.033089906 -0.20673479, 0.11725156 -0.033111542 -0.20611621, 0.11725606 -0.033003211 -0.20621763, 0.11761501 -0.033254951 -0.20632064, 0.11719641 -0.033120438 -0.20606831, 0.11721316 -0.033021778 -0.20616269, 0.11746575 -0.033121705 -0.20654748, 0.11753859 -0.033214927 -0.2063453, 0.11761151 -0.033281595 -0.2060876, 0.11738811 -0.033004299 -0.20655386, 0.11754216 -0.033259988 -0.20613049, 0.11745642 -0.033147737 -0.20637183, 0.11753415 -0.033282205 -0.20597629, 0.11747837 -0.033225924 -0.20616987, 0.11747524 -0.033262432 -0.20602763, 0.1174441 -0.033282727 -0.20588401, 0.11738019 -0.033046931 -0.20639624, 0.11734544 -0.033283025 -0.20581259, 0.10815252 -0.033278435 -0.20574154, 0.10815251 -0.033246249 -0.20584095, 0.10815249 -0.033194005 -0.20593147, 0.10815252 -0.033124179 -0.20600905, 0.10689071 -0.033275425 -0.20615372, 0.10695237 -0.033234537 -0.20624554, 0.10700691 -0.033169031 -0.20632672, 0.10705131 -0.033082157 -0.206393, 0.10771835 -0.033277869 -0.20578969, 0.1077392 -0.033243835 -0.20588945, 0.10775794 -0.033189029 -0.2059796, 0.10777384 -0.033116013 -0.206056, 0.10213298 -0.033162177 -0.20960884, 0.10213147 -0.033077374 -0.20970072, 0.10361651 -0.033274993 -0.21414903, 0.10367809 -0.033234105 -0.21424066, 0.10373272 -0.033168539 -0.21432175, 0.098858669 -0.033161744 -0.21760383, 0.10377719 -0.033081785 -0.21438827, 0.098857179 -0.033076912 -0.21769589, 0.10487826 -0.033123657 -0.21400417, 0.10487832 -0.033277988 -0.2137367, 0.10444419 -0.033277377 -0.21378498, 0.10487826 -0.033245757 -0.21383597, 0.10446502 -0.033243403 -0.21388461, 0.10487826 -0.033193544 -0.21392657, 0.10448374 -0.033188596 -0.21397473, 0.10449959 -0.033115387 -0.21405117, 0.11371686 -0.033277974 -0.21373676, 0.11371684 -0.033245683 -0.21383613, 0.1137169 -0.033193499 -0.21392661, 0.1137169 -0.033123523 -0.21400422, 0.11418897 -0.033179671 -0.21494728, 0.11426517 -0.03319563 -0.21475297, 0.11427671 -0.033239156 -0.21498317, 0.11404003 -0.033283442 -0.21378484, 0.11435282 -0.033246264 -0.21476719, 0.11413439 -0.033283114 -0.21384457, 0.11410828 -0.033045799 -0.21440013, 0.11406858 -0.033081681 -0.21425326, 0.11418374 -0.033145919 -0.21437709, 0.11444983 -0.033278003 -0.21478289, 0.11446916 -0.033279523 -0.21453287, 0.11413606 -0.033167616 -0.2142121, 0.11437885 -0.033252776 -0.2145391, 0.1141258 -0.033239171 -0.21402387, 0.11405464 -0.033242151 -0.21395473, 0.11417349 -0.033265859 -0.21397598, 0.11409307 -0.033267245 -0.21390161, 0.11406055 -0.03300567 -0.21489471, 0.11415711 -0.03308852 -0.21473557, 0.1141158 -0.033100501 -0.21491724, 0.11400834 -0.033268049 -0.21384615, 0.11429626 -0.033210203 -0.21454498, 0.11406125 -0.033182114 -0.21408863, 0.11421768 -0.033232391 -0.21416228, 0.11443348 -0.033281013 -0.21430044, 0.11394218 -0.033283427 -0.21374267, 0.11408599 -0.032953277 -0.21472423, 0.11403282 -0.033012405 -0.21427505, 0.11402634 -0.03290005 -0.21488065, 0.11397904 -0.033244058 -0.21390334, 0.11435363 -0.033258215 -0.21432501, 0.11392041 -0.033268556 -0.21380721, 0.11419101 -0.033119842 -0.21455245, 0.11400218 -0.033188358 -0.21402721, 0.11406261 -0.032852441 -0.21472043, 0.11400624 -0.033105627 -0.2141438, 0.11428016 -0.033222377 -0.21434742, 0.11390015 -0.033245102 -0.2138676, 0.11434448 -0.033282012 -0.21408506, 0.11393875 -0.033192575 -0.21398169, 0.11397555 -0.033043459 -0.21417463, 0.11411425 -0.033003345 -0.21455771, 0.11395676 -0.033116266 -0.2140898, 0.11427875 -0.033262894 -0.2141252, 0.11387213 -0.033194706 -0.21395056, 0.11393097 -0.033057183 -0.2141256, 0.11408174 -0.03291373 -0.21455988, 0.11390366 -0.03312324 -0.21404998, 0.11422458 -0.033282816 -0.21392457, 0.11388345 -0.033066258 -0.21408938, 0.11384779 -0.033126861 -0.21402282, 0.11383365 -0.033070967 -0.21406485, 0.1140717 -0.032966867 -0.21441144, 0.11437461 -0.033276215 -0.21502334, 0.11387703 -0.033276215 -0.2162382, 0.11377916 -0.033239141 -0.21619815, 0.11369151 -0.0331797 -0.21616226, 0.11361827 -0.033100471 -0.21613221, 0.11356309 -0.03300567 -0.21610963, 0.11352883 -0.032899991 -0.21609552, 0.1133339 -0.032918245 -0.21636231, 0.11341512 -0.032831162 -0.21626455, 0.11343473 -0.03295213 -0.21628112, 0.11340785 -0.033276007 -0.21674754, 0.11355639 -0.033276677 -0.21666269, 0.11334008 -0.032624766 -0.21637085, 0.11333343 -0.032661811 -0.2163617, 0.11341862 -0.032709301 -0.21626739, 0.11310683 -0.033087149 -0.21652585, 0.11319454 -0.033092543 -0.21652016, 0.11310689 -0.033171624 -0.21660557, 0.11332364 -0.032788649 -0.21634851, 0.11321145 -0.033174589 -0.21659769, 0.11342423 -0.032672942 -0.21627216, 0.11332448 -0.033179551 -0.21656603, 0.11323206 -0.033236712 -0.2166914, 0.1133638 -0.033238947 -0.21665148, 0.11349532 -0.033241645 -0.21658033, 0.11310691 -0.032875225 -0.21643469, 0.11318195 -0.032994494 -0.21646306, 0.11310691 -0.032986581 -0.21646792, 0.1132918 -0.03310135 -0.2164945, 0.11371584 -0.033277556 -0.21651827, 0.11344084 -0.033186212 -0.21650678, 0.11310679 -0.032759354 -0.21642789, 0.11317426 -0.032876536 -0.21642742, 0.113267 -0.033007652 -0.21644086, 0.1136409 -0.033245772 -0.21645504, 0.11339474 -0.033112988 -0.21644446, 0.11310692 -0.032645017 -0.21644814, 0.1131731 -0.032737389 -0.21642238, 0.1132506 -0.032894298 -0.21640529, 0.11357382 -0.033195555 -0.21639845, 0.11335908 -0.033025369 -0.21639635, 0.1135163 -0.033129588 -0.21634978, 0.11317988 -0.032606393 -0.21645339, 0.11324628 -0.0327591 -0.21639569, 0.11310692 -0.033275306 -0.21681172, 0.11325511 -0.033275396 -0.21679683, 0.1131833 -0.032569468 -0.21646921, 0.11310695 -0.033235446 -0.21670264, 0.11347017 -0.033050075 -0.21631092, 0.11325663 -0.032629773 -0.21641847, 0.10393979 -0.032645091 -0.2164482, 0.10393976 -0.032759398 -0.21642782, 0.10393967 -0.032875314 -0.21643467, 0.10393979 -0.032986626 -0.21646787, 0.10393977 -0.033087254 -0.21652582, 0.10393979 -0.033171788 -0.21660562, 0.10393979 -0.033235565 -0.2167026, 0.10393967 -0.033275262 -0.21681173, 0.10356773 -0.032657728 -0.21648337, 0.10356416 -0.032771125 -0.21646644, 0.10356577 -0.032885 -0.21647538, 0.10357274 -0.032994047 -0.21650936, 0.10358468 -0.033092141 -0.21656662, 0.10360101 -0.033174515 -0.21664411, 0.1036206 -0.033236682 -0.21673827, 0.10364269 -0.03327544 -0.21684377, 0.13671958 -0.032906905 -0.13634169, 0.13671963 -0.033284977 -0.13655998, 0.13635044 -0.032914326 -0.13637812, 0.1367197 -0.03297545 -0.13632965, 0.13634825 -0.032982484 -0.13636792, 0.13671955 -0.033044979 -0.13633367, 0.13634919 -0.03305088 -0.13637318, 0.13671958 -0.033111706 -0.13635361, 0.13635336 -0.033116221 -0.13639359, 0.13671961 -0.033172116 -0.13638845, 0.13636057 -0.033175081 -0.13642789, 0.13671967 -0.033222824 -0.13643622, 0.13637029 -0.033224493 -0.13647451, 0.13671961 -0.033261165 -0.13649443, 0.1363821 -0.033261791 -0.13653088, 0.13639554 -0.033285066 -0.13659438, 0.1360036 -0.033152476 -0.13652433, 0.096729338 0.084775001 -0.26619405, 0.096729398 0.084859282 -0.2662164, 0.095871091 0.085264474 -0.26617944, 0.095907182 0.08519119 -0.26624948, 0.095939696 0.085103184 -0.26630193, 0.095967472 0.085004836 -0.26633447, 0.095988929 0.084900171 -0.26634556, 0.096000776 0.084816411 -0.2663388, 0.096007884 0.084733993 -0.26631868, 0.096340507 0.085078835 -0.26623338, 0.10556807 0.08477509 -0.26619399, 0.10556805 0.084859356 -0.26621646, 0.1060058 0.085178256 -0.26626384, 0.10591972 0.085295185 -0.26611587, 0.10607481 0.085249409 -0.26620716, 0.10587227 0.085218713 -0.26618457, 0.10567006 0.084933236 -0.26623455, 0.10568342 0.08504416 -0.26622501, 0.10579452 0.085021332 -0.26626167, 0.10570106 0.08514978 -0.26619139, 0.10582995 0.085125789 -0.2662341, 0.10594407 0.085089758 -0.26630226, 0.10566321 0.084845498 -0.26622453, 0.10576826 0.084910914 -0.26626569, 0.10565951 0.08476074 -0.26619962, 0.10589269 0.084988847 -0.26632002, 0.10575473 0.084823415 -0.26625228, 0.1058549 0.084880784 -0.26631656, 0.10574821 0.084738627 -0.26622471, 0.1058358 0.084794328 -0.26629877, 0.10582697 0.084709927 -0.26626849, 0.10574603 0.085323557 -0.2660597, 0.10572228 0.085244671 -0.26613525, 0.10550344 0.084075183 -0.26764363, 0.10553309 0.08417064 -0.26770502, 0.10558613 0.084252283 -0.26777053, 0.10565975 0.084315658 -0.26783645, 0.10574996 0.084357053 -0.26789916, 0.10585153 0.084374517 -0.26795512, 0.10568488 0.084260672 -0.26818508, 0.10541993 0.084180713 -0.26834637, 0.10549553 0.084142491 -0.26777625, 0.105544 0.084217966 -0.26784986, 0.10548329 0.084186524 -0.26792425, 0.10561061 0.084273785 -0.26792705, 0.10553977 0.084235013 -0.26801133, 0.10560828 0.084260195 -0.26810002, 0.10538033 0.084191799 -0.26824337, 0.10526872 0.084160328 -0.26838785, 0.10511743 0.084153518 -0.26840222, 0.10546765 0.084051311 -0.26771015, 0.10544176 0.084117338 -0.26784369, 0.10534477 0.084178418 -0.26813895, 0.10524929 0.084174156 -0.2682814, 0.10511747 0.084168524 -0.26829565, 0.10541695 0.084030837 -0.26777279, 0.10531491 0.084141701 -0.26803887, 0.10523169 0.084164426 -0.26817402, 0.10511738 0.084160328 -0.2681883, 0.10529238 0.084083587 -0.26794797, 0.10521689 0.0841313 -0.26807135, 0.10511744 0.084129393 -0.26808518, 0.10527816 0.084006011 -0.26786989, 0.10520548 0.08407703 -0.26797813, 0.10511756 0.08407709 -0.26799113, 0.10511751 0.084005758 -0.26791045, 0.10578293 0.084315211 -0.26807517, 0.10519814 0.084003299 -0.26789796, 0.10569203 0.084306747 -0.26800382, 0.095950454 0.084153414 -0.26840228, 0.09595044 0.084168479 -0.26829574, 0.095950305 0.084160358 -0.2681883, 0.095950335 0.084129274 -0.26808506, 0.095950425 0.08407703 -0.26799101, 0.095950395 0.084005833 -0.2679103, 0.095240682 0.083933711 -0.26801461, 0.095254153 0.08401078 -0.26809275, 0.095275372 0.084069073 -0.26818478, 0.095303386 0.084105372 -0.26828545, 0.095336631 0.084118292 -0.26839015, 0.095373601 0.084106863 -0.26849377, 0.099616587 0.087875545 -0.25999206, 0.099616498 0.087959856 -0.26001459, 0.098758206 0.088365093 -0.25997758, 0.098794252 0.088291645 -0.26004744, 0.09882687 0.088203743 -0.26009989, 0.098854527 0.088105276 -0.26013231, 0.098876029 0.088000655 -0.26014352, 0.09888795 0.08791697 -0.26013684, 0.098895073 0.087834567 -0.26011658, 0.099227503 0.088179454 -0.26003128, 0.10845518 0.08787559 -0.25999215, 0.10845523 0.087959915 -0.26001459, 0.10880691 0.088395759 -0.25991395, 0.10889292 0.088278756 -0.26006183, 0.10896206 0.088349804 -0.26000527, 0.10875952 0.088319287 -0.25998276, 0.10855711 0.08803378 -0.26003247, 0.1085705 0.08814469 -0.26002306, 0.10858826 0.088250309 -0.25998932, 0.10868162 0.088121936 -0.26005977, 0.10871705 0.088226393 -0.26003227, 0.10883117 0.088190421 -0.26010022, 0.1085503 0.087946028 -0.26002264, 0.10865542 0.088011399 -0.26006377, 0.10854673 0.087861285 -0.25999787, 0.10877989 0.088089436 -0.26011807, 0.10864207 0.087923899 -0.26005042, 0.10874215 0.087981179 -0.26011455, 0.10863554 0.087839112 -0.26002279, 0.10872301 0.087894812 -0.26009679, 0.1087141 0.087810621 -0.26006654, 0.10863328 0.088424072 -0.25985768, 0.10860959 0.088344887 -0.25993335, 0.10839066 0.087175682 -0.26144162, 0.10842034 0.087271169 -0.26150319, 0.10847342 0.087352857 -0.26156861, 0.10854706 0.087416127 -0.26163456, 0.10863721 0.087457702 -0.2616972, 0.10873878 0.087475047 -0.26175326, 0.10857189 0.087361082 -0.2619831, 0.10830706 0.087281272 -0.26214439, 0.10838273 0.087243095 -0.26157433, 0.10843109 0.08731851 -0.2616477, 0.10837045 0.087287143 -0.26172233, 0.10849777 0.087374344 -0.26172504, 0.10842693 0.087335572 -0.26180929, 0.10849549 0.08736074 -0.2618981, 0.10826756 0.087292314 -0.26204139, 0.10815598 0.087260842 -0.26218587, 0.10800469 0.087254032 -0.2622003, 0.10800475 0.087268934 -0.26209363, 0.10835481 0.087151989 -0.26150808, 0.10832888 0.087217972 -0.26164159, 0.10823178 0.087279066 -0.26193696, 0.10813642 0.087274894 -0.26207942, 0.10830417 0.087131575 -0.26157081, 0.10820219 0.087242261 -0.26183689, 0.10811889 0.087264881 -0.26197201, 0.10800472 0.087260798 -0.26198637, 0.10817961 0.087184101 -0.26174599, 0.10810399 0.087232098 -0.26186937, 0.10800463 0.087230012 -0.26188329, 0.10816526 0.08710669 -0.26166791, 0.10809278 0.087177619 -0.26177624, 0.10800463 0.087177798 -0.26178917, 0.10800475 0.087106332 -0.26170835, 0.10808527 0.087103888 -0.26169601, 0.1086701 0.087415785 -0.2618733, 0.10857914 0.08740744 -0.26180178, 0.098837584 0.087253898 -0.26220018, 0.098837584 0.087268919 -0.2620936, 0.098837584 0.087260813 -0.26198626, 0.098837584 0.087229937 -0.26188326, 0.098837584 0.087177724 -0.26178908, 0.098837584 0.087106317 -0.26170826, 0.098127812 0.087034315 -0.26181251, 0.098141208 0.087111309 -0.26189089, 0.098162457 0.087169692 -0.26198274, 0.098190472 0.087205932 -0.26208359, 0.098223731 0.087218806 -0.26218826, 0.098260775 0.087207451 -0.2622917, 0.10250366 0.090976134 -0.25379005, 0.10250357 0.091060445 -0.25381255, 0.10164523 0.091465607 -0.25377563, 0.10168135 0.091392294 -0.25384548, 0.10171403 0.091304317 -0.25389794, 0.10174169 0.09120591 -0.25393042, 0.10176314 0.091101304 -0.25394168, 0.10177518 0.09101738 -0.25393501, 0.10178225 0.090935037 -0.25391462, 0.10211468 0.091279998 -0.25382939, 0.1113423 0.090976238 -0.25379002, 0.11134227 0.091060489 -0.25381255, 0.11178006 0.091379255 -0.25385982, 0.11169405 0.091496319 -0.25371188, 0.11184917 0.091450453 -0.25380337, 0.11164664 0.091419697 -0.25378066, 0.11144431 0.091134399 -0.25383061, 0.11145754 0.091245383 -0.25382107, 0.11156882 0.091222376 -0.25385767, 0.11147542 0.091350883 -0.25378734, 0.11160418 0.091326818 -0.25383019, 0.11171825 0.091290921 -0.25389826, 0.11143728 0.091046661 -0.2538206, 0.11154245 0.091112018 -0.2538619, 0.11143386 0.090961829 -0.25379565, 0.11166699 0.09119007 -0.2539162, 0.11152908 0.091024503 -0.25384831, 0.11162911 0.091081858 -0.25391263, 0.11152251 0.090939611 -0.25382066, 0.1116101 0.090995491 -0.25389493, 0.11160122 0.090911031 -0.25386453, 0.11152022 0.091524661 -0.25365585, 0.11149657 0.09144558 -0.25373128, 0.11127786 0.090276301 -0.25523961, 0.11130735 0.090371951 -0.255301, 0.11136051 0.090453476 -0.25536656, 0.11143406 0.090516776 -0.25543267, 0.11152421 0.09055835 -0.25549531, 0.11162587 0.090575665 -0.25555128, 0.11145909 0.090461701 -0.25578123, 0.11119412 0.090381861 -0.2559424, 0.11126982 0.090343595 -0.25537235, 0.11131828 0.090418994 -0.25544572, 0.11125755 0.090387598 -0.25552049, 0.11138488 0.090474874 -0.25552297, 0.11131401 0.09043631 -0.25560737, 0.1113825 0.090461403 -0.25569606, 0.11115465 0.090392932 -0.25583938, 0.11104305 0.090361387 -0.25598377, 0.11089182 0.090354577 -0.2559984, 0.11124188 0.090252593 -0.25530618, 0.11121595 0.090318576 -0.25543979, 0.11111897 0.09037967 -0.25573507, 0.1110235 0.090375394 -0.25587755, 0.11089177 0.090369672 -0.25589174, 0.11119114 0.090232134 -0.25536889, 0.11108927 0.09034282 -0.25563502, 0.11100598 0.090365618 -0.25577015, 0.11089179 0.090361461 -0.25578427, 0.11106664 0.09028478 -0.25554401, 0.11099108 0.090332597 -0.25566745, 0.11089174 0.090330541 -0.25568122, 0.11105227 0.090207353 -0.25546601, 0.11097977 0.090278253 -0.25557423, 0.11089179 0.090278253 -0.25558725, 0.11089183 0.090207011 -0.25550646, 0.11155723 0.090516329 -0.25567126, 0.11097236 0.090204448 -0.255494, 0.11146627 0.090508103 -0.25559986, 0.10172465 0.090354472 -0.25599837, 0.1017247 0.090369478 -0.25589165, 0.10172465 0.090361387 -0.25578427, 0.10172462 0.090330482 -0.25568134, 0.10172465 0.090278178 -0.2555871, 0.10172462 0.090206981 -0.25550658, 0.10101491 0.090134799 -0.25561064, 0.10102835 0.090211898 -0.25568891, 0.10104966 0.090270162 -0.25578088, 0.10107759 0.09030655 -0.25588155, 0.10111086 0.090319321 -0.25598624, 0.10114783 0.090308011 -0.25608987, 0.10539074 0.094076738 -0.24758816, 0.10539079 0.094160944 -0.2476107, 0.10453241 0.094566151 -0.24757361, 0.1045685 0.094492808 -0.24764359, 0.10460117 0.094404846 -0.24769597, 0.10462882 0.094306365 -0.24772847, 0.10465024 0.094201788 -0.24773958, 0.10466221 0.094118029 -0.24773292, 0.10466948 0.094035536 -0.24771278, 0.10500181 0.094380498 -0.2476273, 0.11422934 0.094076753 -0.24758817, 0.11422938 0.094161078 -0.2476106, 0.11466709 0.094480053 -0.24765804, 0.11458117 0.094596907 -0.24751008, 0.11473611 0.094550982 -0.24760142, 0.11453369 0.094520345 -0.24757889, 0.11433139 0.094234958 -0.24762872, 0.11434475 0.094345942 -0.2476193, 0.11445588 0.094323084 -0.24765563, 0.11436258 0.094451398 -0.24758555, 0.11449116 0.094427511 -0.24762821, 0.11460522 0.09439148 -0.24769643, 0.11432441 0.094147265 -0.24761869, 0.11442967 0.094212592 -0.24765997, 0.11432086 0.094062537 -0.24759386, 0.11455411 0.09429042 -0.24771422, 0.11441618 0.094124958 -0.2476466, 0.11451636 0.094182462 -0.24771072, 0.11440958 0.094040394 -0.24761896, 0.1144971 0.09409596 -0.24769297, 0.11448827 0.09401156 -0.24766257, 0.11440741 0.094625324 -0.24745382, 0.11438376 0.094546244 -0.24752939, 0.11416486 0.093376875 -0.24903767, 0.11419457 0.093472511 -0.24909918, 0.11424753 0.09355408 -0.24916469, 0.11432117 0.09361735 -0.24923064, 0.11441141 0.093658835 -0.24929337, 0.11451292 0.093676239 -0.24934937, 0.11434621 0.093562394 -0.24957924, 0.11408126 0.09348245 -0.24974039, 0.11415687 0.093444228 -0.24917035, 0.11420527 0.093519688 -0.2492439, 0.11414462 0.093488246 -0.24931841, 0.11427191 0.093575478 -0.24932115, 0.11420117 0.093536809 -0.24940541, 0.11426964 0.093562007 -0.24949412, 0.11404167 0.093493521 -0.24963741, 0.11393015 0.09346199 -0.24978201, 0.11377887 0.093455195 -0.24979644, 0.11412904 0.093353212 -0.24910419, 0.11410305 0.093419135 -0.2492377, 0.11400615 0.093480289 -0.24953322, 0.11391063 0.093475968 -0.24967553, 0.11377876 0.093470216 -0.24968974, 0.11407819 0.093332767 -0.24916689, 0.11397631 0.093443543 -0.24943306, 0.11389305 0.093466014 -0.24956812, 0.11377884 0.09346202 -0.24958254, 0.11395371 0.093385309 -0.24934198, 0.11387818 0.093433261 -0.24946551, 0.11377878 0.093431145 -0.24947931, 0.11393945 0.093307853 -0.24926405, 0.11386688 0.093378812 -0.24937217, 0.11377887 0.093378901 -0.24938516, 0.1137789 0.093307644 -0.24930455, 0.11444429 0.093616843 -0.24946932, 0.11385953 0.093305066 -0.24929217, 0.11435333 0.093608618 -0.24939792, 0.10461186 0.093455091 -0.24979642, 0.10461187 0.093470126 -0.24968986, 0.10461174 0.093461886 -0.24958244, 0.10461183 0.0934311 -0.24947929, 0.10461181 0.093378752 -0.24938501, 0.10461187 0.093307525 -0.24930455, 0.10390206 0.093235597 -0.24940872, 0.10391553 0.093312606 -0.24948692, 0.1039367 0.093370855 -0.24957873, 0.10396479 0.093407169 -0.24967957, 0.10399804 0.093419909 -0.24978425, 0.10403499 0.093408585 -0.24988784, 0.10827784 0.097177252 -0.24138612, 0.10827798 0.097261548 -0.24140881, 0.10741957 0.097666755 -0.24137166, 0.10745557 0.097593382 -0.24144164, 0.10748832 0.097505555 -0.24149406, 0.10751589 0.097406998 -0.24152648, 0.10753742 0.097302407 -0.24153773, 0.10754941 0.097218558 -0.24153107, 0.10755651 0.097136244 -0.24151075, 0.10788901 0.097481146 -0.24142554, 0.11711663 0.097177312 -0.24138618, 0.11711663 0.097261593 -0.24140871, 0.11755425 0.097580478 -0.24145603, 0.11746827 0.097697511 -0.24130812, 0.11762336 0.097651616 -0.24139944, 0.117421 0.097620919 -0.24137679, 0.11721851 0.097335458 -0.24142672, 0.11723191 0.097446486 -0.24141717, 0.11734298 0.097423628 -0.24145383, 0.11724961 0.097552046 -0.24138355, 0.11737841 0.097528026 -0.24142635, 0.11749251 0.097492039 -0.2414944, 0.11721161 0.097247794 -0.24141681, 0.11731666 0.09731321 -0.24145806, 0.11720805 0.097163111 -0.24139176, 0.11744121 0.097391024 -0.24151233, 0.11730331 0.097225711 -0.24144459, 0.1174034 0.097283006 -0.24150874, 0.11729673 0.097140923 -0.24141684, 0.11738434 0.097196594 -0.24149099, 0.11737543 0.097112224 -0.24146068, 0.11729454 0.097725779 -0.2412519, 0.11727093 0.097646683 -0.24132739, 0.11705202 0.096477434 -0.24283576, 0.11708158 0.09657304 -0.24289715, 0.11713471 0.096654654 -0.24296273, 0.11720827 0.096717969 -0.24302867, 0.11729842 0.096759483 -0.24309134, 0.11740018 0.096776724 -0.24314739, 0.11723335 0.096662819 -0.24337722, 0.11696841 0.09658289 -0.24353842, 0.11704399 0.096544862 -0.24296848, 0.11709243 0.096620247 -0.24304187, 0.11703183 0.096588731 -0.24311654, 0.11715908 0.096676052 -0.24311914, 0.11708826 0.096637413 -0.24320352, 0.1171568 0.096662566 -0.24329209, 0.11692888 0.096594021 -0.2434355, 0.11681731 0.096562564 -0.24358003, 0.11666602 0.096555635 -0.24359441, 0.11701621 0.096453667 -0.24290229, 0.11699021 0.096519813 -0.24303567, 0.11689323 0.096580788 -0.24333131, 0.11679775 0.096576497 -0.24347353, 0.11666602 0.096570775 -0.24348772, 0.11696541 0.096433386 -0.24296498, 0.11686352 0.096543983 -0.243231, 0.1167801 0.096566722 -0.24336612, 0.11666599 0.09656252 -0.24338046, 0.11684103 0.096485794 -0.24314024, 0.11676542 0.096533686 -0.2432635, 0.11666602 0.096531674 -0.24327743, 0.11682661 0.096408427 -0.24306203, 0.116754 0.096479461 -0.24317038, 0.11666602 0.096479341 -0.24318314, 0.11666599 0.096408144 -0.24310258, 0.11733142 0.096717373 -0.24326733, 0.11674659 0.096405655 -0.24309017, 0.11724049 0.096709177 -0.24319601, 0.10749884 0.096555635 -0.24359447, 0.10749887 0.096570626 -0.24348775, 0.10749897 0.096562445 -0.24338035, 0.10749893 0.096531585 -0.24327734, 0.10749897 0.096479297 -0.24318318, 0.10749896 0.096407965 -0.24310246, 0.10678922 0.096335903 -0.24320677, 0.10680264 0.096412987 -0.24328493, 0.10682391 0.096471325 -0.24337688, 0.10685189 0.096507654 -0.24347761, 0.10688503 0.096520409 -0.24358225, 0.10692212 0.096509099 -0.24368586, 0.11693928 0.10647899 -0.22278033, 0.11693919 0.10656324 -0.22280283, 0.11608103 0.1069684 -0.22276567, 0.11611694 0.10689512 -0.22283591, 0.11614978 0.10680714 -0.22288825, 0.11617732 0.10670862 -0.22292067, 0.11619875 0.1066041 -0.22293182, 0.11621079 0.1065203 -0.22292523, 0.1162179 0.10643788 -0.22290483, 0.11655031 0.10678269 -0.22281966, 0.12577802 0.10647897 -0.22278029, 0.1257779 0.10656326 -0.22280285, 0.12621571 0.10688215 -0.22285019, 0.12612981 0.10699908 -0.22270218, 0.12628476 0.10695317 -0.22279353, 0.12608233 0.10692252 -0.22277096, 0.12587994 0.10663716 -0.22282082, 0.12589324 0.10674803 -0.22281128, 0.12600455 0.10672523 -0.22284794, 0.12591103 0.10685368 -0.22277772, 0.12603992 0.10682969 -0.22282043, 0.12615389 0.10679369 -0.22288862, 0.12587303 0.10654943 -0.22281089, 0.12597823 0.10661481 -0.22285205, 0.12586945 0.10646467 -0.22278577, 0.12610263 0.10669284 -0.2229065, 0.12596466 0.10652727 -0.22283851, 0.12606484 0.10658471 -0.2229028, 0.12595814 0.1064425 -0.22281104, 0.12604584 0.10649812 -0.22288512, 0.1260369 0.1064139 -0.22285472, 0.12595598 0.10702756 -0.22264589, 0.12593228 0.10694842 -0.22272161, 0.12571344 0.10577907 -0.22422984, 0.12574309 0.10587446 -0.22429127, 0.12579626 0.10595612 -0.22435683, 0.1258698 0.10601953 -0.22442277, 0.12596004 0.10606101 -0.22448553, 0.12606162 0.10607843 -0.22454172, 0.12589473 0.10596447 -0.22477135, 0.12562984 0.10588472 -0.22493264, 0.12570554 0.10584645 -0.22436258, 0.12575389 0.10592186 -0.22443597, 0.12569326 0.10589044 -0.22451037, 0.12582056 0.10597768 -0.22451334, 0.12574975 0.10593894 -0.22459753, 0.12581831 0.10596411 -0.22468635, 0.12559043 0.10589561 -0.2248296, 0.1254788 0.10586421 -0.22497424, 0.12532753 0.1058573 -0.22498855, 0.12567765 0.10575537 -0.22429636, 0.12565166 0.10582142 -0.22442991, 0.12555462 0.10588245 -0.22472531, 0.12545928 0.10587807 -0.22486761, 0.12532753 0.10587244 -0.22488198, 0.12562689 0.1057349 -0.22435918, 0.12552492 0.1058456 -0.22462519, 0.12544161 0.10586827 -0.22476026, 0.12532753 0.10586421 -0.22477454, 0.12550241 0.10578732 -0.22453421, 0.12542681 0.10583535 -0.22465761, 0.12532751 0.10583332 -0.22467144, 0.125488 0.10571009 -0.22445624, 0.1254155 0.10578088 -0.2245644, 0.12532753 0.105781 -0.22457749, 0.12532742 0.10570985 -0.22449656, 0.12599283 0.10601906 -0.22466153, 0.12540811 0.10570733 -0.22448415, 0.12590195 0.10601079 -0.22459005, 0.11616027 0.10585737 -0.22498862, 0.11616038 0.10587238 -0.22488195, 0.11616027 0.10586417 -0.22477446, 0.11616029 0.10583331 -0.22467151, 0.1161603 0.10578099 -0.22457738, 0.11616041 0.10570969 -0.22449663, 0.11545061 0.10563764 -0.22460099, 0.115464 0.10571469 -0.22467908, 0.1154853 0.10577306 -0.22477101, 0.11551321 0.10580932 -0.22487175, 0.11554646 0.10582219 -0.22497642, 0.11558357 0.10581078 -0.22507998, 0.11877514 0.10945965 -0.21684375, 0.11876811 0.10952343 -0.21686247, 0.11982644 0.10957944 -0.21657829, 0.11982648 0.10966377 -0.21660101, 0.11896816 0.11006907 -0.21656407, 0.11900428 0.10999575 -0.21663393, 0.11903679 0.10990775 -0.21668629, 0.11906445 0.10980928 -0.21671872, 0.11908595 0.10970478 -0.21672979, 0.11909787 0.10962085 -0.21672311, 0.11910498 0.10953844 -0.21670286, 0.1194375 0.10988335 -0.21661758, 0.12866513 0.10957938 -0.21657835, 0.12866513 0.10966378 -0.216601, 0.12885599 0.10962659 -0.21663843, 0.12893252 0.10959893 -0.21668284, 0.1288697 0.10971409 -0.21665202, 0.12880449 0.10995334 -0.21657707, 0.12882678 0.110048 -0.21652116, 0.12895159 0.10968536 -0.21670069, 0.12898938 0.10979337 -0.21670406, 0.12902097 0.10965008 -0.21676622, 0.12906793 0.10975437 -0.21677899, 0.12885164 0.11012709 -0.21644585, 0.12897627 0.11002153 -0.21657206, 0.12902477 0.11009793 -0.21650386, 0.12917118 0.11005408 -0.21659102, 0.129288 0.10987073 -0.21687119, 0.12934248 0.10977525 -0.21706353, 0.12938707 0.1099245 -0.21685015, 0.12944941 0.10981303 -0.21707313, 0.12878589 0.10984784 -0.21661054, 0.1291261 0.10970931 -0.21686876, 0.12913208 0.10984987 -0.21677338, 0.12919942 0.10979776 -0.21687749, 0.1289327 0.10992873 -0.21662109, 0.1289237 0.10951453 -0.21665262, 0.1288493 0.10954182 -0.21661067, 0.12944286 0.1097309 -0.21723793, 0.12938753 0.10965006 -0.21739709, 0.12910227 0.10998291 -0.21664773, 0.12899749 0.10956544 -0.21674363, 0.12929575 0.10999507 -0.21670903, 0.12924652 0.10971671 -0.21704261, 0.12877195 0.10973674 -0.21661986, 0.12907203 0.10961035 -0.21684523, 0.1293377 0.10970478 -0.21720636, 0.12928587 0.10963275 -0.21734113, 0.12889652 0.10982448 -0.21664824, 0.12898675 0.10948186 -0.21671069, 0.12904048 0.10989441 -0.21668616, 0.12904505 0.10952836 -0.2168173, 0.12876467 0.10964912 -0.2166097, 0.12916701 0.10964054 -0.21701147, 0.12920928 0.1099316 -0.21674958, 0.12924336 0.10965717 -0.21716587, 0.12919573 0.10959119 -0.21727841, 0.12903287 0.10944608 -0.21678208, 0.12910812 0.10955101 -0.21697177, 0.12916474 0.10959083 -0.21711849, 0.12912202 0.10952784 -0.2172125, 0.12876098 0.10956436 -0.2165847, 0.12907855 0.10947388 -0.2169358, 0.12910609 0.10950857 -0.21706726, 0.1290689 0.10944635 -0.21714698, 0.12906441 0.109394 -0.21689701, 0.12907605 0.10943574 -0.21702544, 0.1290393 0.10935071 -0.21708538, 0.12906127 0.10935813 -0.21698402, 0.12894867 0.1091789 -0.21833937, 0.12884703 0.10916166 -0.2182835, 0.12875693 0.10912019 -0.21822084, 0.12868325 0.10905689 -0.21815489, 0.12863027 0.10897517 -0.21808945, 0.12860064 0.10887963 -0.21802793, 0.12878184 0.10906512 -0.21856926, 0.12851696 0.10898525 -0.21873058, 0.12859266 0.10894698 -0.21816061, 0.12864105 0.10902244 -0.21823417, 0.12858038 0.10899109 -0.21830858, 0.12870769 0.10907835 -0.21831132, 0.12863691 0.10903957 -0.2183957, 0.12870543 0.10906464 -0.2184843, 0.12847747 0.10899618 -0.21862771, 0.1283659 0.10896485 -0.21877217, 0.12821464 0.10895795 -0.21878661, 0.12856476 0.10885578 -0.21809445, 0.12853877 0.10892195 -0.21822785, 0.12844186 0.1089831 -0.21852328, 0.12834635 0.10897879 -0.21866572, 0.12821464 0.10897303 -0.21867989, 0.12851398 0.10883552 -0.2181571, 0.12841205 0.10894626 -0.21842311, 0.12832873 0.10896891 -0.21855821, 0.12821461 0.10896477 -0.21857266, 0.12838952 0.10888797 -0.21833219, 0.12831394 0.10893589 -0.21845566, 0.12821464 0.10893393 -0.21846952, 0.1283751 0.1088106 -0.21825422, 0.1283026 0.10888158 -0.21836245, 0.12821464 0.10888165 -0.21837543, 0.12821464 0.10881025 -0.21829449, 0.12888007 0.10911971 -0.21845962, 0.12829511 0.10880786 -0.21828233, 0.12878911 0.10911137 -0.21838798, 0.11904745 0.10895793 -0.21878672, 0.11904745 0.10897295 -0.2186799, 0.1190474 0.1089648 -0.21857269, 0.11904742 0.10893388 -0.21846956, 0.11904742 0.10888155 -0.21837533, 0.11904742 0.10881032 -0.21829465, 0.11833771 0.10873826 -0.21839884, 0.11835115 0.10881536 -0.21847713, 0.11837253 0.10887358 -0.218569, 0.11840047 0.10890998 -0.2186698, 0.1184337 0.10892271 -0.21877435, 0.11847077 0.10891126 -0.21887818, 0.11327316 0.10260926 -0.2306987, 0.11327316 0.10268055 -0.23077938, 0.11327329 0.10273266 -0.23087351, 0.11327314 0.10277179 -0.23108386, 0.11327316 0.10276376 -0.23097655, 0.1132732 0.10275677 -0.2311904, 0.11256339 0.10253714 -0.23080289, 0.11257686 0.10261415 -0.23088098, 0.11259808 0.10267244 -0.23097289, 0.11262609 0.1027088 -0.23107374, 0.11265935 0.10272156 -0.23117828, 0.11269641 0.10271022 -0.23128207, 0.12244025 0.10275675 -0.23119029, 0.12244026 0.10277191 -0.23108386, 0.12244025 0.10276379 -0.23097643, 0.12244038 0.10273281 -0.23087354, 0.12244025 0.10268046 -0.23077926, 0.12244026 0.10260919 -0.23069869, 0.12300752 0.10286388 -0.23097323, 0.12274268 0.10278405 -0.2311345, 0.12285584 0.10277407 -0.23049334, 0.12281826 0.10274591 -0.23056453, 0.12290901 0.10285573 -0.23055884, 0.12286673 0.10282132 -0.23063792, 0.1228061 0.10278989 -0.23071262, 0.12293337 0.10287711 -0.23071535, 0.12286267 0.10283835 -0.23079962, 0.12270322 0.10279514 -0.2310316, 0.12293117 0.10286358 -0.23088832, 0.12259154 0.10276368 -0.23117612, 0.12279044 0.10265478 -0.23049839, 0.12282643 0.10267849 -0.23043185, 0.12276451 0.10272077 -0.23063178, 0.12266752 0.10278185 -0.2309272, 0.12257209 0.10277762 -0.23106965, 0.12273966 0.1026344 -0.23056115, 0.12263778 0.10274507 -0.23082718, 0.12255444 0.10276771 -0.23096214, 0.12261523 0.10268688 -0.23073612, 0.12253965 0.1027348 -0.23085974, 0.12260099 0.10260946 -0.23065816, 0.12252836 0.10268036 -0.23076637, 0.12252091 0.10260674 -0.23068626, 0.1231745 0.10297775 -0.23074345, 0.12310579 0.10291852 -0.23086351, 0.12307282 0.10296053 -0.23068736, 0.12301476 0.10291022 -0.23079203, 0.12298267 0.10291889 -0.23062478, 0.12332867 0.10378155 -0.22905202, 0.12324256 0.10389857 -0.22890419, 0.12339765 0.10385256 -0.2289955, 0.12319528 0.10382196 -0.22897287, 0.12299286 0.10353658 -0.22902279, 0.12300617 0.10364752 -0.22901338, 0.12311737 0.10362473 -0.22904988, 0.12302397 0.10375306 -0.22897966, 0.12315273 0.10372911 -0.22902244, 0.12326682 0.10369311 -0.22909051, 0.12289089 0.10346262 -0.22900486, 0.12298588 0.1034489 -0.2290128, 0.12309103 0.10351422 -0.22905405, 0.12298237 0.1033642 -0.22898786, 0.12289089 0.10337834 -0.22898227, 0.1232156 0.10359219 -0.22910829, 0.12307756 0.10342672 -0.22904058, 0.12317771 0.10348408 -0.22910473, 0.12307106 0.10334203 -0.22901301, 0.12315869 0.10339747 -0.22908708, 0.1231498 0.10331336 -0.22905679, 0.12306885 0.10392693 -0.22884782, 0.12304513 0.10384777 -0.22892351, 0.11405218 0.10337827 -0.22898228, 0.11405218 0.10346255 -0.22900487, 0.11319387 0.10386786 -0.22896765, 0.11322989 0.10379444 -0.22903776, 0.11326255 0.10370658 -0.22909009, 0.1132903 0.10360809 -0.22912273, 0.11331174 0.10350341 -0.22913365, 0.1133237 0.10341965 -0.22912717, 0.11333074 0.10333727 -0.2291069, 0.11366309 0.10368226 -0.22902155, 0.14555475 -0.024750918 -0.14020075, 0.14695773 -0.023022875 -0.1402358, 0.14551876 -0.024778828 -0.14025143, 0.14550899 -0.024782211 -0.14026877, 0.14553639 -0.024768203 -0.14022435, 0.14694048 -0.023008823 -0.1402992, 0.14549047 -0.024771869 -0.14031528, 0.14548682 -0.024759755 -0.14033237, 0.14549607 -0.024779201 -0.1402974, 0.14550155 -0.024781987 -0.14028399, 0.1469128 -0.022986174 -0.14035618, 0.14548571 -0.024740562 -0.14035109, 0.1454901 -0.024697557 -0.14037877, 0.14687608 -0.022956237 -0.14040366, 0.14550257 -0.024640441 -0.14040266, 0.14554545 -0.024506435 -0.14043631, 0.14683191 -0.022920132 -0.14043954, 0.14678283 -0.022880092 -0.14046162, 0.14726095 -0.022694737 -0.14029923, 0.14723885 -0.022666574 -0.14035605, 0.14762728 -0.022426426 -0.14035609, 0.1472096 -0.022629112 -0.1404036, 0.14760685 -0.022383571 -0.14040361, 0.14804848 -0.022231221 -0.14040363, 0.1475825 -0.022332177 -0.14043929, 0.14803593 -0.022175685 -0.14043933, 0.14727466 -0.022712246 -0.14023584, 0.1476426 -0.022458777 -0.14029911, 0.14805877 -0.022277474 -0.14035599, 0.14765213 -0.022478804 -0.14023581, 0.14806671 -0.022312388 -0.14029899, 0.1480716 -0.022334084 -0.14023569, 0.14713542 -0.022534505 -0.1404615, 0.14717452 -0.022584453 -0.14043921, 0.14755531 -0.022274882 -0.14046144, 0.14802201 -0.022113889 -0.14046139, 0.15454879 -0.022278845 -0.14035593, 0.15455933 -0.022232607 -0.14040357, 0.15610284 -0.023832977 -0.14035623, 0.15615471 -0.024292499 -0.1403562, 0.15611906 -0.024292544 -0.14029934, 0.1559501 -0.023396283 -0.14035614, 0.15599293 -0.023375809 -0.14040361, 0.15614918 -0.023822248 -0.14040373, 0.15589789 -0.023421586 -0.14023577, 0.15500604 -0.022388801 -0.14040354, 0.15457205 -0.022177055 -0.14043915, 0.15503067 -0.022337511 -0.14043929, 0.15565878 -0.023040846 -0.1402358, 0.15567617 -0.023027003 -0.1402992, 0.15591794 -0.0234119 -0.14029934, 0.1560681 -0.023840979 -0.14029932, 0.15609688 -0.024292514 -0.14023593, 0.15544206 -0.022596076 -0.14043929, 0.15505821 -0.022280499 -0.14046146, 0.15548159 -0.022546351 -0.14046147, 0.15604641 -0.023845762 -0.14023581, 0.15583521 -0.022900015 -0.14046146, 0.1545409 -0.022313684 -0.14029922, 0.1549854 -0.022431567 -0.14035599, 0.15540661 -0.022640556 -0.14040354, 0.15578562 -0.022939637 -0.14043929, 0.15453601 -0.02233538 -0.1402358, 0.15610126 -0.023323596 -0.14046143, 0.15496983 -0.022463739 -0.14029911, 0.15537691 -0.02267769 -0.14035614, 0.15574113 -0.022975028 -0.14040349, 0.15604414 -0.023351043 -0.1404393, 0.15496016 -0.022483855 -0.14023574, 0.15626654 -0.023795575 -0.14046164, 0.15632239 -0.024292409 -0.14046171, 0.15625906 -0.024292454 -0.14043942, 0.15535475 -0.022705749 -0.1402992, 0.15570405 -0.023004726 -0.14035608, 0.15458617 -0.02211532 -0.14046146, 0.15620464 -0.023809671 -0.14043938, 0.15620226 -0.024292529 -0.14040375, 0.15534085 -0.022722915 -0.1402358, 0.15609685 -0.027182281 -0.14023618, 0.156119 -0.027182296 -0.14029962, 0.15615474 -0.027182281 -0.14035651, 0.15620215 -0.027182266 -0.1404039, 0.15625912 -0.027182251 -0.14043976, 0.15632251 -0.027182385 -0.14046194, 0.15593882 -0.028076097 -0.14046207, 0.1557415 -0.028228909 -0.14046201, 0.15610142 -0.027886912 -0.14046195, 0.15609784 -0.027389571 -0.14029959, 0.156133 -0.027396813 -0.14035659, 0.15606837 -0.027602479 -0.14035657, 0.15617938 -0.027406275 -0.14040393, 0.15611203 -0.027621299 -0.14040402, 0.15600267 -0.027818143 -0.14040403, 0.15616427 -0.02764377 -0.14043972, 0.15604933 -0.027850658 -0.14043978, 0.15589516 -0.028030217 -0.14043975, 0.15570801 -0.02817513 -0.14043979, 0.15567788 -0.028126836 -0.14040403, 0.15607615 -0.027385145 -0.14023617, 0.15603553 -0.027588457 -0.14029953, 0.15596373 -0.027791053 -0.14035657, 0.15585598 -0.02798903 -0.14040403, 0.15565282 -0.028086558 -0.14035659, 0.15601511 -0.027579695 -0.14023617, 0.15593439 -0.027770534 -0.14029972, 0.15582323 -0.027954534 -0.1403567, 0.15563385 -0.028056204 -0.14029974, 0.15591612 -0.027757928 -0.14023627, 0.15579867 -0.02792868 -0.14029969, 0.15562212 -0.028037384 -0.1402363, 0.15578339 -0.027912617 -0.1402363, 0.15629728 -0.027430564 -0.14046195, 0.15623511 -0.027417839 -0.14043972, 0.1562226 -0.027668715 -0.14046204, 0.14548242 -0.024850607 -0.14023201, 0.14549467 -0.024868339 -0.14018239, 0.14547472 -0.024876744 -0.14022723, 0.14551322 -0.024851888 -0.14014325, 0.14544247 -0.024668679 -0.14043692, 0.14546096 -0.024522781 -0.14047883, 0.14551948 -0.024824485 -0.14015642, 0.14550143 -0.024841487 -0.14019166, 0.14543268 -0.02486071 -0.14033343, 0.14543967 -0.024926901 -0.1402854, 0.14545228 -0.024876192 -0.14028126, 0.14541636 -0.024684668 -0.14045829, 0.14542392 -0.02453348 -0.14050813, 0.14546604 -0.024930015 -0.14022034, 0.14544082 -0.02473104 -0.14040546, 0.14539337 -0.024701834 -0.14048229, 0.14565443 -0.02405256 -0.14047709, 0.1453913 -0.02454567 -0.14054197, 0.14541964 -0.024749637 -0.14042208, 0.14557932 -0.024044141 -0.1405001, 0.1455103 -0.024036393 -0.14053729, 0.14545009 -0.024029702 -0.14058758, 0.14540055 -0.024024099 -0.14064868, 0.14544539 -0.024778739 -0.14036936, 0.14540111 -0.024769157 -0.14044046, 0.14545083 -0.02480042 -0.14034484, 0.14542824 -0.024799407 -0.14038061, 0.14545771 -0.024814337 -0.14032222, 0.14543602 -0.024822325 -0.14035298, 0.14541326 -0.024820909 -0.14039341, 0.14544424 -0.024837121 -0.14032723, 0.14547311 -0.024827108 -0.14028063, 0.14542285 -0.024844915 -0.14036228, 0.14549251 -0.024825558 -0.14023772, 0.14546168 -0.024851203 -0.14028059, 0.14551064 -0.024815664 -0.1402017, 0.14552844 -0.024798393 -0.1401705, 0.14549835 -0.023221344 -0.1395821, 0.14530437 -0.023188338 -0.13979879, 0.14537019 -0.022861212 -0.1400478, 0.14543183 -0.022897571 -0.14003396, 0.14538018 -0.023216471 -0.1397405, 0.14553778 -0.022938356 -0.13998905, 0.14542803 -0.022680283 -0.14021628, 0.14544603 -0.023227572 -0.13966666, 0.14559843 -0.0229491 -0.13995099, 0.14565547 -0.022949681 -0.13990584, 0.14549348 -0.022727847 -0.14021181, 0.14572735 -0.022931919 -0.13983086, 0.14561532 -0.022782534 -0.14017934, 0.14568938 -0.022797301 -0.14014632, 0.14576049 -0.022797689 -0.14010456, 0.14585173 -0.022773147 -0.14003287, 0.138831 -0.031387463 -0.13485992, 0.13877891 -0.031393781 -0.13494468, 0.13871285 -0.031382427 -0.13501848, 0.13863717 -0.031354442 -0.13507676, 0.13825746 -0.032313332 -0.13451765, 0.13842186 -0.031915918 -0.13467361, 0.13837078 -0.031917289 -0.13471241, 0.13829547 -0.031909794 -0.13475336, 0.13829748 -0.032163262 -0.13457637, 0.13825573 -0.032170311 -0.13459252, 0.13827763 -0.032242075 -0.13454296, 0.13819753 -0.032176122 -0.13460757, 0.13824141 -0.03225328 -0.13455153, 0.13820541 -0.032337904 -0.13451758, 0.13819145 -0.032265544 -0.13455813, 0.13812685 -0.032276392 -0.13455799, 0.1540892 -0.022008464 0.14046779, 0.14851274 -0.022008345 0.14046767, 0.14851274 -0.022008345 0.14046767, 0.1540892 -0.022008464 0.14046779, 0.1140521 0.10352387 0.22902539, 0.1228909 0.10352378 0.22902538, 0.11405222 0.10343681 0.22901778, 0.12289095 0.10343681 0.2290179, 0.1228909 0.10335259 0.2289951, 0.11405221 0.1033525 0.22899511, 0.1228909 0.10327344 0.22895806, 0.11405221 0.10327347 0.22895806, 0.12343819 0.1035255 0.229359, 0.12345859 0.10347663 0.2294596, 0.12336108 0.1034352 0.22933798, 0.12337883 0.10339411 0.22942451, 0.12329467 0.10321926 0.22956368, 0.12337668 0.10334836 0.22952351, 0.12334783 0.10330085 0.22962916, 0.12332265 0.10329746 0.22938031, 0.12332053 0.10325871 0.22946879, 0.12324305 0.10315551 0.22912461, 0.12324281 0.1032633 0.22917855, 0.12326379 0.10313664 0.22916242, 0.12375808 0.10367693 0.22933736, 0.12364209 0.10365023 0.22935835, 0.12367578 0.10376637 0.22915845, 0.12357147 0.10372691 0.22920431, 0.123473 0.10366397 0.22923459, 0.12353368 0.10359864 0.22936606, 0.12355702 0.10354017 0.22948378, 0.12345557 0.10342161 0.2295738, 0.12342142 0.10336424 0.22969522, 0.1237901 0.10357861 0.22953379, 0.12366875 0.10358162 0.22949567, 0.12355264 0.10347442 0.229617, 0.12351172 0.10340558 0.22975785, 0.12366243 0.1035042 0.22965088, 0.12361331 0.10342301 0.22981411, 0.12377413 0.10349439 0.2297022, 0.12372096 0.10341524 0.22986028, 0.12327929 0.10311754 0.22920433, 0.12327921 0.10322477 0.22925799, 0.12329245 0.10308565 0.22927681, 0.12326792 0.10337441 0.22921847, 0.12330718 0.10333283 0.22930327, 0.12329309 0.10319267 0.22933008, 0.12331669 0.10348232 0.22924188, 0.12326069 0.10301958 0.22944805, 0.12329027 0.10315804 0.22941345, 0.1232651 0.10312383 0.2295022, 0.12328787 0.10305215 0.22935981, 0.1233864 0.1035807 0.22924739, 0.12866507 0.10972624 0.21662228, 0.12866509 0.10963945 0.2166146, 0.11982644 0.10972629 0.2166224, 0.11982644 0.10963936 0.21661459, 0.12866525 0.10955499 0.21659207, 0.11982648 0.10955496 0.216592, 0.12866525 0.10947601 0.21655497, 0.11982648 0.10947599 0.21655497, 0.11875668 0.10956387 0.21688731, 0.11876814 0.10949893 0.21687618, 0.11395554 0.10827111 0.21947223, 0.11409907 0.10820864 0.21938354, 0.11877525 0.1094353 0.21685736, 0.11426222 0.10815804 0.21926218, 0.11877762 0.109374 0.21683116, 0.12632518 0.10662673 0.22315764, 0.12634565 0.10657777 0.22325781, 0.12624827 0.1065364 0.22313617, 0.12626584 0.1064954 0.22322282, 0.12618175 0.10632055 0.22336218, 0.12626386 0.10644941 0.22332188, 0.12623493 0.10640208 0.22342771, 0.12620752 0.10635994 0.22326732, 0.12613037 0.10625656 0.22292286, 0.12613001 0.10636456 0.2229771, 0.12615088 0.10623796 0.22296125, 0.12620965 0.10639875 0.22317883, 0.12664516 0.10677804 0.2231358, 0.12652917 0.10675134 0.22315654, 0.12656298 0.10686751 0.22295696, 0.12645832 0.10682829 0.22300285, 0.12636009 0.10676511 0.22303289, 0.12642078 0.10669963 0.22316432, 0.12644413 0.10664146 0.22328219, 0.12634256 0.1065229 0.22337233, 0.12630847 0.10646553 0.22349375, 0.12667719 0.10667972 0.22333226, 0.12655583 0.10668285 0.22329396, 0.12643965 0.10657574 0.22341546, 0.12639867 0.10650693 0.22355634, 0.12654954 0.1066054 0.22344914, 0.1265004 0.10652427 0.22361252, 0.12666109 0.10659568 0.22350058, 0.12660806 0.10651658 0.22365867, 0.12616649 0.10621853 0.22300273, 0.12616637 0.10632594 0.22305638, 0.12617937 0.10618706 0.22307521, 0.12615505 0.10647561 0.22301696, 0.12619413 0.10643406 0.22310171, 0.12618032 0.10629378 0.22312878, 0.12620373 0.10658349 0.22304019, 0.12614766 0.1061209 0.22324651, 0.12617746 0.1062593 0.22321159, 0.12615223 0.10622503 0.22330067, 0.12617496 0.10615329 0.22315833, 0.12627354 0.10668199 0.2230458, 0.12577803 0.10662498 0.22282366, 0.12577799 0.10653813 0.22281605, 0.11693944 0.10662504 0.22282389, 0.11693937 0.1065381 0.22281605, 0.12577792 0.10645379 0.22279367, 0.11693938 0.10645376 0.22279371, 0.12577812 0.10637467 0.22275656, 0.11693944 0.1063747 0.22275665, 0.11766377 0.097323015 0.24176233, 0.11768425 0.09727405 0.24186243, 0.11758672 0.097232684 0.24174112, 0.11760449 0.097191557 0.24182765, 0.11752045 0.097016796 0.24196686, 0.11760235 0.0971459 0.24192657, 0.11757343 0.097098306 0.24203257, 0.11754613 0.097056225 0.24187207, 0.1175483 0.097094938 0.24178363, 0.11746882 0.0969529 0.24152781, 0.11746861 0.097060755 0.24158183, 0.11748944 0.096934184 0.24156596, 0.11798382 0.097474322 0.24174048, 0.11786777 0.097447649 0.24176124, 0.11790155 0.097563729 0.24156167, 0.11779711 0.097524598 0.24160759, 0.11769868 0.097461417 0.24163781, 0.11775921 0.097396061 0.24176925, 0.11778267 0.097337678 0.24188697, 0.11768126 0.097219095 0.24197702, 0.11764723 0.097161636 0.24209855, 0.11801577 0.097376093 0.24193709, 0.11789435 0.097379074 0.24189873, 0.11777826 0.097271934 0.24202028, 0.11773732 0.09720321 0.24216114, 0.11788809 0.097301707 0.24205403, 0.11783896 0.097220585 0.24221729, 0.11799975 0.097291842 0.2421055, 0.11794651 0.097212896 0.24226348, 0.11750494 0.096915081 0.24160783, 0.11750489 0.097022191 0.24166122, 0.1175181 0.096883252 0.24168006, 0.11749361 0.097171947 0.24162191, 0.11753267 0.097130314 0.24170674, 0.11751893 0.096990064 0.24173346, 0.11754225 0.097279891 0.24164514, 0.11748636 0.09681724 0.24185137, 0.117516 0.096955582 0.24181654, 0.11749063 0.09692125 0.24190556, 0.11751355 0.096849754 0.24176325, 0.117612 0.097378328 0.24165072, 0.11711654 0.097321317 0.24142872, 0.11711663 0.097234353 0.24142095, 0.10827795 0.097321168 0.24142869, 0.10827799 0.097234294 0.241421, 0.1171166 0.097150043 0.24139838, 0.10827805 0.097149864 0.24139817, 0.1082779 0.097070858 0.24136136, 0.11711654 0.097070977 0.24136148, 0.11477688 0.094221696 0.24796391, 0.1147972 0.094172701 0.24806416, 0.1146996 0.094131425 0.24794254, 0.11471742 0.094090357 0.24802937, 0.11463319 0.093915448 0.24816865, 0.11471534 0.094044402 0.24812827, 0.11468631 0.093997136 0.24823429, 0.11465898 0.093955025 0.24807376, 0.11466113 0.093993649 0.24798536, 0.11458188 0.093851641 0.24772939, 0.11458157 0.093959555 0.24778348, 0.11460254 0.093833014 0.24776755, 0.11509672 0.094373032 0.24794227, 0.11498073 0.094346389 0.24796295, 0.11501451 0.094462588 0.24776332, 0.11490992 0.09442316 0.24780917, 0.11481151 0.094360277 0.24783932, 0.1148722 0.094294801 0.24797085, 0.11489561 0.094236478 0.24808836, 0.11479415 0.094117805 0.24817836, 0.11476003 0.094060287 0.24830014, 0.11512867 0.094274744 0.24813855, 0.11500719 0.094277725 0.24810052, 0.11489111 0.094170645 0.24822196, 0.11485015 0.094101861 0.24836281, 0.11500104 0.094200328 0.24825554, 0.11495203 0.094119266 0.24841878, 0.11511254 0.094190553 0.24830684, 0.11505947 0.094111487 0.24846505, 0.11461785 0.093813643 0.24780905, 0.11461778 0.093921021 0.24786286, 0.114631 0.093781903 0.24788174, 0.11460648 0.094070688 0.24782324, 0.1146456 0.094029024 0.2479082, 0.1146318 0.093888983 0.24793506, 0.11465535 0.094178602 0.24784671, 0.11459926 0.093715772 0.24805284, 0.11462885 0.093854263 0.24801829, 0.11460382 0.093819931 0.24810715, 0.11462644 0.093748555 0.24796474, 0.11472499 0.09427698 0.2478523, 0.10539089 0.094219968 0.24763021, 0.1142295 0.094220087 0.2476303, 0.10539092 0.094133064 0.24762268, 0.11422956 0.094133064 0.24762271, 0.1053908 0.094048753 0.24759991, 0.11422947 0.094048873 0.24759997, 0.10539088 0.093969658 0.24756296, 0.1142295 0.093969747 0.24756306, 0.1118896 0.091120407 0.25416553, 0.11190999 0.091071531 0.25426579, 0.11181243 0.091030166 0.25414407, 0.11183035 0.090988919 0.25423086, 0.11174613 0.090814158 0.25437015, 0.11182791 0.090943441 0.25432986, 0.11179911 0.090895906 0.25443575, 0.11177194 0.090853617 0.2542752, 0.1116946 0.090750292 0.25393096, 0.11169425 0.090858355 0.25398511, 0.1117152 0.090731546 0.25396919, 0.11177403 0.090892419 0.25418681, 0.11220944 0.091271684 0.2541436, 0.11209351 0.091244981 0.25416446, 0.11212729 0.09136118 0.2539649, 0.11202283 0.091321871 0.25401074, 0.11192437 0.091258898 0.25404114, 0.11198509 0.091193363 0.25417244, 0.11200856 0.091135159 0.2542901, 0.11190699 0.091016576 0.25437993, 0.11187287 0.090959117 0.25450152, 0.1122416 0.091173485 0.25434008, 0.11212011 0.091176525 0.25430208, 0.11200386 0.091069505 0.25442344, 0.11196309 0.091000661 0.25456446, 0.11211383 0.091099069 0.25445724, 0.1120647 0.091017947 0.25462046, 0.11222541 0.091089293 0.25450861, 0.11217225 0.091010377 0.25466669, 0.11173081 0.090712234 0.25401068, 0.11173072 0.090819672 0.25406447, 0.11174384 0.090680614 0.25408322, 0.11171928 0.090969339 0.25402504, 0.11175847 0.090927646 0.25410974, 0.11174455 0.090787604 0.25413668, 0.11176816 0.091077343 0.25404841, 0.11171198 0.090614721 0.25425446, 0.1117416 0.090753064 0.25421983, 0.11171652 0.09071885 0.25430852, 0.11173928 0.090647146 0.25416613, 0.11183774 0.09117572 0.25405371, 0.11134228 0.091118827 0.25383192, 0.1113425 0.091031715 0.25382417, 0.10250361 0.091118678 0.25383198, 0.10250361 0.091031775 0.25382423, 0.11134242 0.090947524 0.25380155, 0.10250364 0.090947464 0.25380173, 0.11134227 0.090868399 0.25376457, 0.10250357 0.090868399 0.25376463, 0.10900249 0.088019356 0.26036698, 0.10902287 0.087970331 0.26046747, 0.10892528 0.087928936 0.26034588, 0.10894312 0.087887928 0.26043236, 0.10885885 0.087713018 0.26057184, 0.10894094 0.087842092 0.2605316, 0.10891207 0.087794647 0.26063752, 0.10888469 0.087752506 0.26047701, 0.10880749 0.087649211 0.26013267, 0.108807 0.087757125 0.2601867, 0.10882801 0.087630495 0.2601707, 0.1088869 0.087791309 0.26038849, 0.10932222 0.088170663 0.26034537, 0.10920645 0.088144049 0.26036638, 0.10924011 0.08826004 0.26016641, 0.10913554 0.08822085 0.26021245, 0.10903725 0.088157728 0.2602427, 0.10909805 0.088092282 0.26037419, 0.10912137 0.088034019 0.26049161, 0.10901979 0.087915495 0.26058194, 0.10898568 0.087857917 0.26070338, 0.10935429 0.088072255 0.26054174, 0.10923299 0.088075355 0.26050365, 0.10911678 0.087968275 0.26062512, 0.10907581 0.087899402 0.26076609, 0.10922673 0.087997988 0.2606588, 0.10917747 0.087916717 0.26082224, 0.10933836 0.087987944 0.26071027, 0.10928507 0.087908998 0.2608684, 0.10884367 0.087611124 0.26021233, 0.10884352 0.087718591 0.26026618, 0.10885677 0.087579563 0.2602849, 0.10883209 0.087868169 0.26022652, 0.10887128 0.087826654 0.26031154, 0.10885748 0.087686375 0.26033831, 0.10888094 0.087976143 0.26024979, 0.10882495 0.087513462 0.26045617, 0.10885452 0.087651864 0.26042148, 0.10882936 0.087617561 0.26051056, 0.10885206 0.087546006 0.26036802, 0.10895079 0.08807449 0.26025552, 0.10845515 0.088017598 0.26003334, 0.10845515 0.087930605 0.26002577, 0.099616587 0.088017508 0.26003331, 0.099616498 0.087930515 0.26002577, 0.10845518 0.087846324 0.26000327, 0.099616602 0.087846264 0.26000321, 0.10845515 0.087767258 0.25996634, 0.099616602 0.087767139 0.25996631, 0.10611519 0.084917948 0.26656866, 0.10613567 0.084868982 0.26666918, 0.1060383 0.084827647 0.2665475, 0.10605599 0.084786549 0.26663417, 0.10597183 0.084611788 0.26677334, 0.10605389 0.084740832 0.2667332, 0.10602504 0.084693387 0.26683906, 0.10599761 0.084651217 0.26667845, 0.10592034 0.084547803 0.26633412, 0.10592005 0.084655806 0.26638818, 0.10594103 0.084529087 0.26637232, 0.10599972 0.08468999 0.26659006, 0.10643524 0.085069224 0.26654708, 0.10631928 0.085042641 0.26656795, 0.10635307 0.085158691 0.26636809, 0.10624866 0.085119352 0.26641393, 0.10615006 0.085056409 0.26644439, 0.1062108 0.084991023 0.26657557, 0.10623412 0.084932789 0.26669323, 0.10613272 0.084814116 0.26678336, 0.10609862 0.084756777 0.26690483, 0.10646723 0.084971026 0.26674339, 0.10634583 0.084973976 0.26670527, 0.10622969 0.084866926 0.26682669, 0.10618882 0.084798202 0.26696754, 0.10633956 0.084896699 0.26686049, 0.1062903 0.084815457 0.26702368, 0.10645118 0.084886745 0.26691186, 0.10639787 0.084807858 0.26706982, 0.10595652 0.084509775 0.26641393, 0.10595635 0.084617123 0.26646757, 0.10596964 0.084478185 0.26648641, 0.10594508 0.084766909 0.26642823, 0.10598415 0.084725216 0.26651311, 0.10597035 0.084585175 0.26653987, 0.10599384 0.084874794 0.26645148, 0.10593782 0.084412143 0.26665786, 0.10596745 0.084550604 0.26662278, 0.10594231 0.084516183 0.26671183, 0.10596493 0.084444627 0.2665695, 0.10606347 0.084973171 0.26645693, 0.10556811 0.084916189 0.26623487, 0.10556814 0.084829316 0.2662273, 0.096729338 0.08491616 0.26623482, 0.096729368 0.084829226 0.26622742, 0.10556819 0.084745005 0.2662048, 0.096729368 0.084744945 0.26620498, 0.10556814 0.084665939 0.26616776, 0.096729368 0.08466585 0.26616779, 0.11401479 -0.032813087 0.21487333, 0.11351731 -0.032812998 0.21608821, 0.1140264 -0.03292428 0.21487831, 0.11352888 -0.032924339 0.21609309, 0.11406069 -0.033030048 0.21489228, 0.11356309 -0.033030018 0.21610706, 0.1141158 -0.033124879 0.21491496, 0.11361825 -0.033124819 0.2161296, 0.11418906 -0.033204004 0.21494487, 0.11369149 -0.033203945 0.21615969, 0.11427677 -0.033263579 0.21498062, 0.11377919 -0.03326346 0.21619552, 0.11437467 -0.033300564 0.21502081, 0.11387694 -0.033300534 0.2162357, 0.11398001 -0.033313051 0.21627793, 0.11447749 -0.033313081 0.21506312, 0.11706471 -0.033067062 0.20607343, 0.11707769 -0.033150181 0.20601299, 0.11702824 -0.03306596 0.20606816, 0.11709391 -0.033218786 0.20593747, 0.11699113 -0.03314732 0.20600659, 0.11699103 -0.033062801 0.20606795, 0.11699112 -0.033217087 0.20592909, 0.11711304 -0.033270165 0.20584969, 0.11699122 -0.03326939 0.20583838, 0.11713377 -0.033301786 0.20575318, 0.11699115 -0.033301458 0.20573917, 0.11715552 -0.033312544 0.20565289, 0.11699104 -0.033312455 0.20563534, 0.12033902 -0.033066645 0.19807829, 0.12035204 -0.033149764 0.19801788, 0.12030269 -0.033065602 0.19807296, 0.12036836 -0.033218488 0.19794217, 0.12026544 -0.033146933 0.19801161, 0.12026533 -0.033062473 0.19807285, 0.12038739 -0.033269778 0.19785444, 0.12026547 -0.033216789 0.19793387, 0.12026535 -0.033268884 0.19784327, 0.1204081 -0.033301368 0.19775827, 0.12026548 -0.033301219 0.19774416, 0.1204298 -0.033312127 0.19765778, 0.12026536 -0.033312008 0.19764011, 0.12361322 -0.033066228 0.19008321, 0.12362628 -0.033149377 0.19002301, 0.12357692 -0.033065215 0.19007796, 0.12364256 -0.033217952 0.18994738, 0.12353966 -0.033146307 0.19001631, 0.12353978 -0.033061936 0.19007783, 0.12366146 -0.033269212 0.18985935, 0.12353973 -0.033216253 0.18993872, 0.12353966 -0.033268288 0.18984823, 0.12368235 -0.033300832 0.18976311, 0.12353955 -0.033300713 0.18974906, 0.12370405 -0.033311531 0.18966262, 0.12353973 -0.03331168 0.18964493, 0.12688754 -0.033065811 0.18208794, 0.12690054 -0.03314887 0.18202774, 0.1268511 -0.033064678 0.18208273, 0.12691693 -0.033217475 0.18195216, 0.12681393 -0.03314583 0.18202119, 0.12681386 -0.03306143 0.18208274, 0.12693582 -0.033268794 0.18186443, 0.12681393 -0.033215806 0.18194352, 0.12681387 -0.0332679 0.18185292, 0.1269566 -0.033300504 0.18176802, 0.12681393 -0.033300087 0.18175368, 0.12697831 -0.033311233 0.1816673, 0.1268139 -0.033311114 0.18164976, 0.13016169 -0.033065245 0.17409296, 0.13017464 -0.033148274 0.1740326, 0.13012545 -0.033064142 0.17408772, 0.1301911 -0.033216998 0.17395686, 0.13008811 -0.033145383 0.174026, 0.13008811 -0.033060983 0.17408751, 0.13021018 -0.033268258 0.17386912, 0.13008811 -0.03321524 0.17394827, 0.13008812 -0.033267394 0.17385793, 0.1302308 -0.033299878 0.17377292, 0.13008811 -0.03329961 0.17375861, 0.13025251 -0.033310667 0.17367232, 0.13008811 -0.033310577 0.17365466, 0.13343596 -0.033064768 0.16609778, 0.13344891 -0.033147797 0.16603771, 0.13339961 -0.033063665 0.16609265, 0.13346525 -0.033216462 0.16596201, 0.13336241 -0.033144847 0.16603102, 0.13336229 -0.033060476 0.16609253, 0.13336235 -0.033214852 0.16595335, 0.13348418 -0.033267692 0.16587402, 0.13336249 -0.033266887 0.16586283, 0.13350494 -0.033299372 0.16577777, 0.13336238 -0.033299193 0.16576354, 0.13352676 -0.033310041 0.16567734, 0.13336241 -0.0333101 0.16565968, 0.13998449 -0.033063754 0.15010753, 0.13999748 -0.033146843 0.15004733, 0.13994801 -0.033062682 0.15010229, 0.14001381 -0.033215508 0.14997163, 0.13991088 -0.033143982 0.15004095, 0.13991082 -0.033059463 0.15010229, 0.13991088 -0.033213779 0.14996299, 0.14003272 -0.033266768 0.14988367, 0.13991097 -0.033266023 0.14987254, 0.14005348 -0.033298448 0.1497876, 0.13991082 -0.033298239 0.14977315, 0.14007521 -0.033309147 0.14968702, 0.13991079 -0.033309177 0.14966935, 0.14325869 -0.033063397 0.14211234, 0.14327176 -0.033146426 0.14205228, 0.14322233 -0.033062324 0.1421071, 0.14328809 -0.03321512 0.14197646, 0.14318505 -0.033143595 0.1420458, 0.14318505 -0.033059075 0.14210713, 0.14330702 -0.033266321 0.14188863, 0.14318511 -0.033213213 0.14196789, 0.14318509 -0.033265457 0.14187746, 0.14332782 -0.033297971 0.14179237, 0.14318505 -0.033297732 0.14177805, 0.14334953 -0.03330867 0.14169171, 0.14318508 -0.03330861 0.14167413, 0.12055089 0.10042413 0.23556072, 0.12057137 0.10037528 0.23566097, 0.12047379 0.10033385 0.23553936, 0.12049159 0.10029288 0.23562597, 0.12040743 0.10011806 0.23576538, 0.12048943 0.10024704 0.23572508, 0.12046058 0.10019971 0.23583081, 0.12043323 0.10015748 0.23567052, 0.12043531 0.10019626 0.23558202, 0.12035596 0.10005413 0.23532623, 0.12035559 0.10016195 0.23538028, 0.12037654 0.10003544 0.23536435, 0.12087087 0.10057552 0.235539, 0.12075491 0.10054888 0.23555973, 0.12078857 0.10066502 0.23536021, 0.12068415 0.10062574 0.23540586, 0.12058575 0.10056271 0.23543635, 0.12064645 0.10049726 0.23556773, 0.12066981 0.10043891 0.23568544, 0.12056832 0.10032029 0.2357754, 0.12053423 0.10026298 0.23589689, 0.12090293 0.10047729 0.23573557, 0.12078157 0.10048027 0.2356973, 0.12066528 0.10037322 0.23581859, 0.12062439 0.10030438 0.23595957, 0.12077519 0.10040291 0.23585257, 0.12072603 0.10032187 0.2360155, 0.12088682 0.10039316 0.23590393, 0.12083361 0.1003141 0.2360619, 0.12039213 0.1000161 0.2354061, 0.12039208 0.10012339 0.23545951, 0.12040517 0.099984422 0.23547857, 0.12038064 0.10027324 0.23542017, 0.12041983 0.1002316 0.23550485, 0.12040599 0.10009132 0.2355319, 0.12042947 0.10038103 0.23544338, 0.12037344 0.09991838 0.23564973, 0.12040305 0.10005687 0.23561496, 0.12037794 0.10002242 0.23570393, 0.12040059 0.099950895 0.23556155, 0.12049922 0.10047956 0.23544903, 0.12000369 0.10042275 0.23522715, 0.12000363 0.10033579 0.23521928, 0.11116503 0.10042252 0.23522706, 0.11116497 0.10033573 0.23521928, 0.11116494 0.10025136 0.23519689, 0.12000373 0.10025139 0.23519686, 0.12000377 0.10017239 0.23515972, 0.11116497 0.1001723 0.23515972, 0.13671021 -0.033064201 0.15810257, 0.13672319 -0.03314732 0.15804254, 0.1366739 -0.033063188 0.15809743, 0.13673942 -0.033215955 0.15796655, 0.13663658 -0.03314437 0.15803592, 0.13663658 -0.03305997 0.15809743, 0.13675845 -0.033267274 0.15787871, 0.13663658 -0.033214226 0.15795796, 0.13663658 -0.03326641 0.15786771, 0.13677928 -0.033298925 0.15778275, 0.13663658 -0.033298746 0.15776829, 0.13680094 -0.033309564 0.15768193, 0.13663669 -0.033309653 0.15766448, 0.11243942 -0.033057705 0.22372232, 0.11307071 -0.03383033 0.22421934, 0.11256589 -0.033176377 0.22347143, 0.11316043 -0.033911273 0.22397785, 0.11322136 -0.033938691 0.22382182, 0.11272018 -0.033256426 0.2232184, 0.11328517 -0.033947751 0.22366339, 0.13753532 -0.032421634 0.13448574, 0.1381522 -0.032374129 0.134508, 0.13819551 -0.032413229 0.13448897, 0.13753517 -0.032374188 0.134508, 0.1375352 -0.032472149 0.13447215, 0.13824186 -0.032455221 0.13447547, 0.13753511 -0.032524362 0.13446771, 0.1383184 -0.032524392 0.1344675, 0.14611846 -0.032539889 0.13647835, 0.14622408 -0.03243883 0.13647132, 0.14618458 -0.032417491 0.13648218, 0.14618474 -0.031867847 0.13659255, 0.14619109 -0.032248244 0.13651051, 0.14623234 -0.031873211 0.13654007, 0.14614718 -0.032397196 0.13649961, 0.1461014 -0.032372519 0.13653305, 0.14613777 -0.032229111 0.13655476, 0.14639218 -0.032106295 0.13646764, 0.14623639 -0.032264456 0.13648714, 0.14633685 -0.032300338 0.13646762, 0.14628536 -0.03228195 0.13647269, 0.14626598 -0.03246139 0.13646762, 0.1458821 -0.032620177 0.13650383, 0.14590952 -0.032607064 0.13650812, 0.14588121 -0.032613859 0.13650747, 0.14588282 -0.032626376 0.13650073, 0.14588369 -0.032632783 0.13649732, 0.14594573 -0.032661602 0.13648067, 0.14629082 -0.031879827 0.13650063, 0.14635688 -0.031887099 0.13647597, 0.14642681 -0.031895056 0.13646781, 0.14593725 -0.032593414 0.13651016, 0.14594497 -0.032611087 0.13649952, 0.14596544 -0.032571658 0.13651374, 0.14601347 -0.032678708 0.13647081, 0.14596078 -0.032647207 0.13648285, 0.14599678 -0.032568052 0.13650502, 0.14600131 -0.032530531 0.13652147, 0.14602207 -0.032601759 0.13648573, 0.14604193 -0.032628015 0.13647597, 0.14605337 -0.032486752 0.13651638, 0.14604494 -0.032454565 0.13653602, 0.14618032 -0.032590553 0.13646784, 0.14606258 -0.032655314 0.13646974, 0.14608411 -0.032684132 0.13646761, 0.14608978 -0.032516405 0.13649133, 0.14611036 -0.032243714 0.13657765, 0.14614864 -0.032564655 0.1364705, 0.14615075 -0.031864092 0.1366547, 0.081357941 0.073538408 0.28781193, 0.081339106 0.073191151 0.287633, 0.081387356 0.073192671 0.28764057, 0.081173852 0.0736361 0.28755194, 0.081203207 0.07331346 0.2873922, 0.081190467 0.073288664 0.28743237, 0.081309423 0.073538318 0.28780538, 0.081348136 0.073903099 0.2879374, 0.08129929 0.073904678 0.28793156, 0.081263602 0.073542818 0.28778797, 0.081253469 0.073909506 0.28791469, 0.081293806 0.07319583 0.28761536, 0.081223667 0.07355164 0.28776103, 0.08121334 0.073916897 0.28788704, 0.081254005 0.073206112 0.28758883, 0.081191644 0.073564425 0.2877261, 0.081181332 0.073926821 0.28785107, 0.081159458 0.073938385 0.28780848, 0.081200182 0.073241398 0.2875163, 0.081222177 0.073221669 0.28755516, 0.08116971 0.073580369 0.28768522, 0.081149086 0.07395114 0.28776222, 0.081159145 0.073598281 0.28764057, 0.081150517 0.073964134 0.2877149, 0.081189513 0.073264167 0.28747451, 0.081160605 0.073617205 0.28759539, 0.081164032 0.073976532 0.28766906, 0.13751064 0.11760734 0.20563889, 0.13752115 0.11756392 0.20561792, 0.13751814 0.11757649 0.20559293, 0.13750792 0.11761887 0.20561562, 0.13748883 0.11764635 0.2056597, 0.1374861 0.1176572 0.20563786, 0.13745701 0.11767872 0.2056786, 0.13745439 0.11768897 0.20565809, 0.13741708 0.11770256 0.20569478, 0.1374146 0.11771242 0.20567556, 0.13737154 0.11771615 0.20570718, 0.13736898 0.11772566 0.20568869, 0.13732038 0.11772846 0.20569658, 0.13732277 0.11771928 0.20571506, 0.12007506 0.11917 0.20771961, 0.13618881 0.12007804 0.20590417, 0.13618927 0.12004958 0.20589258, 0.1200753 0.11914162 0.20770802, 0.1361901 0.12001978 0.2058854, 0.12007613 0.11911182 0.20770113, 0.1200776 0.11908133 0.20769843, 0.13619155 0.11998917 0.20588273, 0.10322818 0.081816688 0.27277017, 0.10324846 0.081767872 0.27287072, 0.10315114 0.081726477 0.27274913, 0.10316882 0.081685439 0.27283561, 0.1030845 0.081510648 0.27297485, 0.10316671 0.081639573 0.27293468, 0.10313787 0.081592128 0.27304053, 0.10311058 0.081549957 0.27288029, 0.1030332 0.081446543 0.27253577, 0.10303292 0.081554547 0.27258992, 0.10305378 0.081427947 0.27257407, 0.10311249 0.08158876 0.27279174, 0.10354808 0.081968114 0.27274865, 0.10343206 0.0819415 0.27276957, 0.10346578 0.082057491 0.27256963, 0.10336119 0.08201839 0.27261567, 0.10326284 0.081955239 0.27264583, 0.10332365 0.081889704 0.27277708, 0.10334688 0.081831589 0.27289486, 0.10324547 0.081712976 0.27298486, 0.10321137 0.081655517 0.27310646, 0.10358018 0.081869736 0.27294493, 0.1034587 0.081872836 0.27290678, 0.10334249 0.081765726 0.27302819, 0.10330141 0.081696942 0.27316931, 0.10345238 0.081795469 0.27306199, 0.1034032 0.081714287 0.27322525, 0.10356401 0.081785694 0.27311346, 0.10351086 0.081706598 0.27327147, 0.10306929 0.081408545 0.27261561, 0.10306917 0.081515983 0.27266914, 0.10308236 0.081377074 0.27268815, 0.1030578 0.08166568 0.27262974, 0.1030969 0.081624076 0.27271456, 0.1030831 0.081483975 0.27274132, 0.10310656 0.081773564 0.27265298, 0.10305057 0.081310794 0.27285939, 0.10308033 0.081449315 0.27282447, 0.10305506 0.081414983 0.2729134, 0.10307789 0.081343457 0.272771, 0.10317641 0.081872031 0.27265859, 0.10268086 0.081815049 0.2724365, 0.10268086 0.081728145 0.27242887, 0.093842208 0.08181493 0.27243662, 0.093842357 0.081727847 0.27242905, 0.10268098 0.081643745 0.27240652, 0.093842238 0.081643686 0.27240652, 0.10268091 0.08156462 0.27236933, 0.093842119 0.08156465 0.27236933, 0.091949612 0.076992348 0.27764249, 0.092511654 0.076992378 0.27764261, 0.091949627 0.076905325 0.2776351, 0.092512399 0.076905802 0.27763498, 0.091949612 0.076821163 0.27761233, 0.092513159 0.07682167 0.27761233, 0.092513353 0.076742247 0.27757537, 0.091949597 0.076742217 0.27757543, 0.099793687 0.07871376 0.27863812, 0.099793851 0.078626677 0.2786305, 0.098494366 0.07871379 0.27863824, 0.098494411 0.078626797 0.27863055, 0.098494366 0.078542426 0.27860814, 0.099793851 0.078542456 0.27860802, 0.099793762 0.07846339 0.27857104, 0.098494411 0.07846342 0.27857104, 0.098116383 0.079040989 0.27813816, 0.096939802 0.077681854 0.27735198, 0.098117262 0.079042062 0.27813494, 0.096940637 0.077683017 0.277349, 0.098118231 0.079043016 0.27813178, 0.09694159 0.07768409 0.27734601, 0.09811911 0.079044089 0.27812886, 0.096942544 0.077685043 0.27734268, 0.096447825 0.076992437 0.27764261, 0.096447811 0.076905474 0.2776351, 0.095011592 0.076992348 0.27764249, 0.095010757 0.076905802 0.27763498, 0.095009893 0.07682173 0.27761257, 0.096447781 0.076821342 0.27761245, 0.095009804 0.076742247 0.27757537, 0.096447825 0.076742217 0.27757549, 0.094813153 0.076642379 0.29169741, 0.094806567 0.076555565 0.29168981, 0.079995304 0.07664229 0.29169747, 0.079998016 0.076555416 0.29168981, 0.080005631 0.076471195 0.29166716, 0.094806209 0.076470926 0.29166707, 0.080016598 0.07639192 0.29163033, 0.094812527 0.07639204 0.29163015, 0.13607576 0.12122856 0.20649542, 0.13620095 0.12123896 0.20649184, 0.13631463 0.12008353 0.20589805, 0.13650312 0.1168866 0.20426394, 0.13639849 0.11794843 0.20480953, 0.13652435 0.11795394 0.20480344, 0.13662849 0.11689658 0.2042601, 0.093761474 0.083096936 0.28431228, 0.094518915 0.08313714 0.2842325, 0.093761504 0.082873389 0.28364152, 0.094402462 0.082907274 0.28357378, 0.095234811 0.083255038 0.2839967, 0.09500815 0.083007082 0.28337431, 0.095869362 0.083444223 0.28361809, 0.095545128 0.08316718 0.28305423, 0.096388012 0.083694354 0.28311753, 0.095983937 0.083378866 0.28263077, 0.096761718 0.083991811 0.2825231, 0.09630014 0.083630547 0.28212744, 0.099400714 -0.015862688 0.24062255, 0.1000538 -0.015111431 0.2404795, 0.09940064 -0.01517956 0.24044007, 0.10017253 -0.015782163 0.24066903, 0.10066958 -0.014911041 0.24059539, 0.10090011 -0.015545264 0.24080604, 0.10121258 -0.014589772 0.24078126, 0.10154191 -0.015165642 0.2410256, 0.10165206 -0.014166012 0.24102615, 0.10206132 -0.014664844 0.24131529, 0.10196269 -0.013664082 0.24131647, 0.10242851 -0.014071688 0.2416584, 0.10262237 -0.01342012 0.24203527, 0.10212672 -0.013112709 0.2416355, 0.1021347 -0.012543246 0.24196468, 0.10263181 -0.012747094 0.24242459, 0.089674637 0.066492483 0.28767967, 0.089291751 0.06645219 0.28765655, 0.089674711 0.067243561 0.28638113, 0.089291736 0.067203298 0.28635815, 0.088931128 0.066333815 0.28758788, 0.088931054 0.067084864 0.28628954, 0.088613629 0.066144213 0.28747809, 0.088613674 0.066895202 0.2861799, 0.08835797 0.065894231 0.28733367, 0.088357851 0.066645309 0.28603506, 0.088178679 0.065598622 0.2871626, 0.088178635 0.06634973 0.28586411, 0.088086411 0.065274432 0.28697515, 0.088086292 0.066025659 0.28567672, 0.088086411 0.064940467 0.28678197, 0.088086411 0.065691575 0.28548354, 0.088178679 0.064616397 0.28659442, 0.088178679 0.065367535 0.28529608, 0.088357866 0.064320728 0.28642356, 0.088357896 0.065071717 0.28512502, 0.088613659 0.064070836 0.28627899, 0.088613704 0.064821854 0.28498062, 0.088931128 0.063881055 0.28616932, 0.088931143 0.064632162 0.28487068, 0.089291856 0.063762769 0.2861008, 0.089291722 0.064513907 0.28480241, 0.089674622 0.063722655 0.28607744, 0.089674637 0.064473584 0.28477907, 0.099400714 -0.011413947 0.2426182, 0.09901768 -0.011454239 0.24259448, 0.099400684 -0.010663047 0.24131964, 0.09901768 -0.010703221 0.24129617, 0.098657086 -0.011572644 0.24252614, 0.098657072 -0.010821715 0.24122775, 0.098339513 -0.011762306 0.24241635, 0.098339632 -0.011011258 0.24111795, 0.098083794 -0.012012258 0.24227202, 0.098083779 -0.01126124 0.24097335, 0.097904503 -0.012307897 0.24210083, 0.097904623 -0.011556998 0.24080241, 0.097812265 -0.012632117 0.24191347, 0.097812355 -0.011881128 0.24061489, 0.097812414 -0.012965992 0.24172032, 0.097812384 -0.012215063 0.24042192, 0.097904637 -0.013290182 0.2415328, 0.097904682 -0.012539223 0.24023426, 0.098083809 -0.013585821 0.24136174, 0.098083824 -0.012834892 0.24006334, 0.098339722 -0.013835803 0.24121724, 0.098339632 -0.013084814 0.2399188, 0.098657131 -0.014025405 0.24110758, 0.098657086 -0.013274446 0.23980905, 0.099017739 -0.013392761 0.23974052, 0.099017829 -0.014143959 0.24103907, 0.09940061 -0.013433084 0.2397173, 0.099400759 -0.014184043 0.24101579, 0.089674592 0.071174785 0.28423697, 0.088734254 0.071075901 0.28417981, 0.089674562 0.071226373 0.28432024, 0.089674681 0.071140185 0.28414524, 0.089674652 0.064089492 0.28023615, 0.088691175 0.064282134 0.28033632, 0.089674667 0.06417869 0.28027678, 0.088713586 0.071125403 0.28426188, 0.088667929 0.064195231 0.28029722, 0.087719545 0.064506516 0.28047734, 0.08869116 0.071190044 0.2843318, 0.087808535 0.070828244 0.28409004, 0.0877648 0.070885912 0.28415626, 0.087764904 0.064586207 0.28051227, 0.089674756 0.071293429 0.28439176, 0.088667899 0.071267083 0.28438765, 0.089674756 0.071372941 0.28444886, 0.087883875 0.064850882 0.28050739, 0.087848604 0.064761624 0.28052759, 0.087119415 0.065307662 0.28077149, 0.087011635 0.065148279 0.28080469, 0.087808535 0.064672187 0.2805292, 0.0877195 0.070955768 0.28420776, 0.086949512 0.070398733 0.28387427, 0.086884946 0.070456997 0.2839191, 0.08706896 0.065227553 0.28079695, 0.088713676 0.064375088 0.28035733, 0.089674801 0.064274177 0.28029919, 0.087848708 0.07078509 0.28401154, 0.08788383 0.070758209 0.28392419, 0.088752434 0.071043357 0.28408927, 0.088734329 0.064470872 0.28035939, 0.089674667 0.064371988 0.28030235, 0.087011755 0.070352092 0.28381467, 0.089674667 0.064468786 0.28028643, 0.088752598 0.064565703 0.28034258, 0.086292639 0.069756761 0.283503, 0.086212322 0.069799885 0.28353924, 0.087119266 0.070301339 0.28365982, 0.087069079 0.07031922 0.28374213, 0.086369812 0.069724813 0.28345174, 0.085832208 0.068997368 0.28306413, 0.085740969 0.069022521 0.28308958, 0.086503312 0.069699392 0.2833119, 0.086440966 0.069705471 0.28338712, 0.085919857 0.068982884 0.28302246, 0.085595071 0.068164751 0.28258228, 0.085498273 0.068170086 0.28259659, 0.086071506 0.068987325 0.28290001, 0.086000636 0.068979517 0.28296724, 0.085688204 0.068169132 0.28255188, 0.085595056 0.0673071 0.28208619, 0.085498393 0.06729199 0.28208846, 0.085774004 0.068183199 0.28250688, 0.085849255 0.068206444 0.28244841, 0.085688204 0.06733124 0.28206721, 0.085832164 0.066474602 0.28160441, 0.085741088 0.066439793 0.28159553, 0.085774064 0.067363307 0.28203243, 0.085849211 0.067402348 0.28198338, 0.085920021 0.066517517 0.2815966, 0.08629252 0.065715209 0.28116554, 0.086212322 0.065662369 0.28114623, 0.086071506 0.066621557 0.28153163, 0.086000755 0.066567257 0.28157207, 0.086369812 0.065775499 0.28116745, 0.086949512 0.065073296 0.28079408, 0.086884782 0.065005347 0.28076583, 0.086503312 0.06590949 0.28111982, 0.086440817 0.065841213 0.28115207, 0.090990528 0.067427799 0.27990067, 0.091378778 0.067672297 0.28009546, 0.091047809 0.067348763 0.27990836, 0.091047823 0.070032194 0.28146017, 0.091098025 0.070049986 0.28154248, 0.091441199 0.06971474 0.28134847, 0.091230467 0.067798212 0.28008187, 0.09115009 0.067850932 0.2801013, 0.091351077 0.068182185 0.28029299, 0.09153001 0.068104491 0.2802918, 0.091307685 0.067737654 0.28007972, 0.090636864 0.070277616 0.2816022, 0.091442272 0.068147495 0.28028393, 0.090170309 0.066950008 0.27967745, 0.090188384 0.066855267 0.2796945, 0.089674637 0.066801354 0.2796635, 0.090596959 0.070234373 0.28152382, 0.090170145 0.0704308 0.2816909, 0.089674637 0.066898033 0.27964741, 0.089674801 0.070482835 0.28172106, 0.089674771 0.070517376 0.28181279, 0.090188354 0.070463344 0.28178155, 0.090636909 0.067103192 0.27976626, 0.090149567 0.070381239 0.2816087, 0.090127155 0.070316628 0.28153849, 0.090103775 0.070239469 0.28148293, 0.089674637 0.07028456 0.2815088, 0.090596795 0.067192748 0.2797645, 0.089674637 0.070364192 0.28156614, 0.089674756 0.070431188 0.28163779, 0.091378763 0.069708779 0.28127313, 0.091681644 0.06931828 0.28111911, 0.090928361 0.067502961 0.27991092, 0.090863556 0.06757085 0.27993941, 0.090149567 0.067045793 0.27967966, 0.089674741 0.066995963 0.27965069, 0.090990469 0.069999173 0.28138793, 0.090553254 0.067278787 0.27978146, 0.09050779 0.067358449 0.27981639, 0.090553194 0.070176765 0.28145772, 0.09050788 0.070106789 0.2814061, 0.090127051 0.067138985 0.27970064, 0.089674786 0.067091271 0.2796731, 0.090103716 0.067225739 0.27973998, 0.091610715 0.069326118 0.28105164, 0.091805503 0.068883225 0.28086764, 0.091307685 0.069689259 0.2812084, 0.090928242 0.069952682 0.28132808, 0.090863511 0.069894269 0.28128314, 0.091730282 0.068906531 0.28080916, 0.091805503 0.068435267 0.28060853, 0.091529891 0.069322631 0.28099659, 0.091230392 0.0696574 0.28115731, 0.091150194 0.069614336 0.28112102, 0.091730282 0.068474337 0.28055924, 0.091681525 0.06800051 0.28035688, 0.091644451 0.068920568 0.28076398, 0.091442272 0.069308147 0.2809552, 0.091351107 0.069283083 0.28092945, 0.091610819 0.06805484 0.28031641, 0.091441214 0.067603812 0.28012764, 0.091644332 0.068506584 0.28052449, 0.091551229 0.068925127 0.28073359, 0.091454536 0.068919644 0.2807194, 0.09109813 0.067268535 0.2799336, 0.091551229 0.068530634 0.28050542, 0.091454431 0.068545505 0.28050309, 0.090672299 0.067014083 0.27978659, 0.089674756 0.067180619 0.27971351, 0.09067221 0.070304498 0.2816897, 0.098393902 -0.013711408 0.23523569, 0.098417059 -0.013624594 0.23527461, 0.09940064 -0.013727829 0.23521486, 0.09940061 -0.0067318529 0.23917535, 0.098460406 -0.0068307966 0.23911801, 0.099400714 -0.0066801757 0.2392585, 0.097490892 -0.01332058 0.2354506, 0.097445592 -0.013400272 0.23541558, 0.098478407 -0.0068632811 0.23902741, 0.098478436 -0.013341025 0.23528051, 0.097574696 -0.013145134 0.23546591, 0.097609922 -0.013055876 0.23544568, 0.096795186 -0.012679294 0.2357353, 0.096737802 -0.012758389 0.23574291, 0.098439634 -0.0067811161 0.23920012, 0.097534403 -0.013234422 0.23546746, 0.098439619 -0.013531521 0.23529571, 0.099400625 -0.013632432 0.23523715, 0.097534359 -0.0070783049 0.23902822, 0.098417163 -0.0067164451 0.23927045, 0.097490862 -0.0070206374 0.23909435, 0.097445458 -0.0069507211 0.23914595, 0.09667559 -0.0075078458 0.23881271, 0.096610859 -0.0074494332 0.2388574, 0.098460227 -0.013435706 0.23529758, 0.099400669 -0.013534442 0.23524058, 0.09940064 -0.013437673 0.23522463, 0.097574636 -0.0071215183 0.23894975, 0.096845329 -0.0076053292 0.23859836, 0.097609848 -0.0071483701 0.23886244, 0.096737713 -0.007554397 0.23875293, 0.096018568 -0.0081498474 0.2384415, 0.095938295 -0.008106634 0.23847759, 0.096229285 -0.0082071871 0.23824999, 0.096795052 -0.0075872988 0.23868057, 0.09940064 -0.0067661554 0.23908341, 0.096095756 -0.0081816167 0.23838998, 0.095558137 -0.0089092106 0.23800215, 0.095466986 -0.0088839978 0.23802778, 0.095797598 -0.0089192539 0.23783818, 0.096166924 -0.0082010478 0.23832522, 0.09564586 -0.0089238137 0.23796102, 0.095321104 -0.0097418576 0.23752052, 0.095224097 -0.0097364634 0.23753461, 0.09572655 -0.0089270622 0.2379054, 0.095575154 -0.0096999556 0.23738649, 0.095413998 -0.0097372979 0.23749027, 0.09532088 -0.01059939 0.23702434, 0.095224351 -0.01061447 0.23702697, 0.095499933 -0.0097232014 0.23744491, 0.095575184 -0.010504112 0.2369214, 0.095414102 -0.010575339 0.23700541, 0.095558107 -0.011432096 0.23654284, 0.095466971 -0.011466846 0.23653375, 0.095500037 -0.010543242 0.23697078, 0.095797554 -0.011284992 0.23646976, 0.095645845 -0.011389032 0.23653485, 0.096018508 -0.01219146 0.23610343, 0.095938295 -0.012244299 0.23608422, 0.09622927 -0.011997029 0.23605801, 0.095726594 -0.011339352 0.2365102, 0.096095771 -0.01213114 0.23610583, 0.099400803 -0.013817117 0.2351743, 0.096675426 -0.012833223 0.23573245, 0.096610844 -0.01290144 0.23570406, 0.096845254 -0.012599036 0.23570982, 0.096166909 -0.012065485 0.23609027, 0.099400535 -0.0066131204 0.23933019, 0.09940058 -0.0065335184 0.23938727, 0.098393843 -0.0066393763 0.2393261, 0.09987542 -0.0075252801 0.23654711, 0.099400684 -0.0074237734 0.23665917, 0.099896207 -0.0074758679 0.23662917, 0.10036284 -0.010803238 0.23470454, 0.1007736 -0.010557756 0.23484638, 0.10082391 -0.010637984 0.23487177, 0.10077378 -0.0078746229 0.23639852, 0.10039808 -0.0076022297 0.23662794, 0.10082401 -0.0078565925 0.23648064, 0.10071644 -0.010478601 0.23483881, 0.10103352 -0.010168716 0.23501819, 0.10110477 -0.010234341 0.23503366, 0.10036284 -0.0076290816 0.23654051, 0.10032269 -0.0076722056 0.23646212, 0.10095643 -0.010108307 0.23502019, 0.10087612 -0.010055527 0.23503962, 0.10107692 -0.0097242147 0.23523135, 0.1012558 -0.0098019689 0.23523012, 0.10116811 -0.0097589642 0.23522213, 0.099896148 -0.010956451 0.23461586, 0.10039809 -0.010892376 0.23472472, 0.099914223 -0.011051282 0.23463288, 0.099852979 -0.007589981 0.23647681, 0.099400535 -0.0075425059 0.23650432, 0.09940061 -0.0074754506 0.23657608, 0.099829733 -0.007667169 0.23642118, 0.09940058 -0.011008486 0.23458581, 0.10110478 -0.0081980377 0.23621134, 0.1011671 -0.0081918091 0.23628679, 0.10032271 -0.01071386 0.23470294, 0.10071637 -0.0079073757 0.23632613, 0.1006542 -0.010403618 0.23484941, 0.10058954 -0.01033555 0.23487774, 0.099875405 -0.010860696 0.23461774, 0.09940058 -0.010910615 0.23458889, 0.10027915 -0.0077299923 0.23639603, 0.1002339 -0.0077999383 0.23634428, 0.10027912 -0.010627732 0.23471978, 0.10133687 -0.0085806698 0.23599021, 0.10140768 -0.0085885376 0.23605745, 0.099400654 -0.0076221079 0.23644736, 0.10023375 -0.0105481 0.23475465, 0.099852994 -0.010767743 0.23463887, 0.099400625 -0.010815188 0.23461157, 0.09940058 -0.010725841 0.23465171, 0.099829584 -0.01068078 0.23467794, 0.10103363 -0.0082174391 0.23614688, 0.10065417 -0.0079538971 0.23626642, 0.10058953 -0.0080123991 0.23622146, 0.1014562 -0.0090001673 0.23574749, 0.10153149 -0.0090233535 0.23580599, 0.10125585 -0.0085840076 0.23593482, 0.10095634 -0.0082491487 0.23609558, 0.10087611 -0.0082923025 0.23605934, 0.10145627 -0.0094322711 0.23549752, 0.1015313 -0.0094712824 0.23554686, 0.10137036 -0.0089861006 0.23570231, 0.10116829 -0.0085985512 0.23589362, 0.10107705 -0.0086237043 0.23586795, 0.10133673 -0.009851858 0.235255, 0.1014076 -0.0099062771 0.23529525, 0.10137036 -0.0094001144 0.2354627, 0.10127726 -0.0089816898 0.23567179, 0.10118046 -0.0089870542 0.23565774, 0.10116704 -0.010302648 0.23506577, 0.09940058 -0.011105284 0.23460165, 0.10127726 -0.0093761533 0.23544374, 0.10118046 -0.009361133 0.23544124, 0.099400729 -0.0073893815 0.23675096, 0.099914327 -0.0074433237 0.23671961, 0.099400654 -0.0080920309 0.23617533, 0.09940052 -0.010020331 0.2395097, 0.099101499 -0.0081234127 0.23615728, 0.099101514 -0.010051951 0.23949125, 0.098819628 -0.0082159191 0.23610346, 0.098819748 -0.010144338 0.23943797, 0.098571762 -0.0083640963 0.23601793, 0.098571673 -0.010292426 0.2393522, 0.098371968 -0.0085593611 0.23590516, 0.098371923 -0.01048781 0.23923922, 0.098231763 -0.0087904483 0.23577134, 0.098231852 -0.010718837 0.23910546, 0.098159745 -0.009043619 0.23562494, 0.098159671 -0.010971859 0.23895919, 0.098159835 -0.0093045086 0.23547417, 0.09815976 -0.011232838 0.23880818, 0.098231882 -0.0095577687 0.2353278, 0.098231807 -0.011486158 0.2386619, 0.098371968 -0.0097886175 0.23519395, 0.098371863 -0.011717036 0.23852813, 0.098571718 -0.0099838823 0.23508111, 0.098571807 -0.011912391 0.23841536, 0.098819792 -0.010132059 0.23499539, 0.098819792 -0.012060508 0.23832956, 0.099101529 -0.010224596 0.23494199, 0.099101484 -0.012153044 0.23827612, 0.099400654 -0.012184545 0.23825786, 0.099400669 -0.010256037 0.23492375, 0.089674756 0.069814637 0.28123721, 0.089674771 0.067886159 0.28457141, 0.08937566 0.069783166 0.28121901, 0.089375511 0.067854688 0.28455311, 0.089093849 0.06969066 0.28116536, 0.0890937 0.067762181 0.28449947, 0.088845894 0.069542482 0.28107965, 0.088845775 0.067613944 0.28441381, 0.08864595 0.069347188 0.28096682, 0.08864598 0.067418739 0.28430092, 0.088505939 0.069116339 0.28083318, 0.088505909 0.067187771 0.28416747, 0.088433787 0.06886293 0.28068677, 0.088433668 0.06693463 0.28402078, 0.088433787 0.0686021 0.28053576, 0.088433906 0.066673562 0.2838701, 0.088505909 0.06834884 0.28038943, 0.088505894 0.066420451 0.28372362, 0.08864598 0.068117872 0.28025573, 0.08864598 0.066189423 0.2835899, 0.08884573 0.067922667 0.28014266, 0.088845864 0.065994188 0.28347689, 0.0890937 0.06777446 0.28005716, 0.0890937 0.065846011 0.2833913, 0.089375615 0.067681983 0.28000361, 0.089375541 0.065753534 0.28333783, 0.089674667 0.065722153 0.28331959, 0.089674637 0.067650601 0.27998558, 0.090247333 0.066274032 0.27985132, 0.090976432 0.065892175 0.28012368, 0.090437159 0.065126315 0.28017369, 0.090597004 0.064565763 0.28034258, 0.091465533 0.064850882 0.28050759, 0.090247273 0.070617214 0.28236353, 0.090976283 0.070571557 0.28283039, 0.090437338 0.070910051 0.28351903, 0.09059684 0.071043327 0.28408921, 0.091465414 0.070758149 0.28392425, 0.092230022 0.065307841 0.28077149, 0.092020199 0.066612914 0.28054038, 0.0928462 0.06590955 0.28111979, 0.093277872 0.066621646 0.28153145, 0.092599332 0.067654178 0.28114283, 0.093500197 0.067402408 0.28198314, 0.092599317 0.068809852 0.28181112, 0.093500093 0.068206742 0.28244838, 0.093277618 0.068987474 0.28289998, 0.092020214 0.069850996 0.28241357, 0.092846081 0.069699511 0.28331184, 0.092230126 0.070301369 0.28365982, 0.1007023 -0.0073350519 0.23776832, 0.10119142 -0.0071482807 0.2388625, 0.10195586 -0.0076050311 0.23859835, 0.10174613 -0.0080555826 0.23735182, 0.099973142 -0.011632428 0.23478964, 0.10070238 -0.012014344 0.23506182, 0.10016309 -0.012780204 0.23511186, 0.1003229 -0.013340935 0.23528059, 0.10119157 -0.013055786 0.23544575, 0.099973366 -0.0072894245 0.23730184, 0.10016312 -0.0069963783 0.23845731, 0.10032277 -0.0068631619 0.23902747, 0.10195614 -0.012598917 0.23570991, 0.10174607 -0.011293873 0.23547852, 0.10257202 -0.011996999 0.23605804, 0.10300384 -0.011285022 0.23646979, 0.10232535 -0.01025258 0.23608091, 0.10322605 -0.010504052 0.23692155, 0.1032261 -0.0096999258 0.23738649, 0.10232535 -0.009096846 0.23674956, 0.10300371 -0.0089191049 0.23783824, 0.10257198 -0.0082070678 0.23825003, 0.12546524 0.11167343 0.20895977, 0.12499049 0.11177923 0.20885186, 0.12548606 0.11175232 0.20890556, 0.12636356 0.11154626 0.20931725, 0.12598802 0.11175866 0.2090316, 0.12641385 0.1116273 0.20929454, 0.12595277 0.11003308 0.21234347, 0.12636361 0.11015989 0.21209013, 0.12641379 0.1101902 0.21216853, 0.12595299 0.11167307 0.20906375, 0.12630634 0.11014743 0.21201147, 0.12662345 0.11030759 0.21169123, 0.12669472 0.11032696 0.21175565, 0.12591268 0.11159749 0.20911147, 0.12654631 0.1103061 0.21163072, 0.12684576 0.11049707 0.21131243, 0.12646596 0.11032219 0.2115768, 0.12666695 0.11049338 0.21123458, 0.12675807 0.1104864 0.21126997, 0.12548602 0.10995387 0.21250197, 0.12598795 0.11005868 0.21243156, 0.12550408 0.1099766 0.21259555, 0.12544276 0.11160736 0.2090288, 0.12541953 0.11155637 0.20910881, 0.12499049 0.11157973 0.20906235, 0.12499034 0.11163186 0.20897973, 0.12499036 0.11169927 0.20890839, 0.12499051 0.10992698 0.21255566, 0.1266946 0.11137922 0.20965169, 0.12675703 0.11145405 0.20964111, 0.12591258 0.11002596 0.21225457, 0.12630634 0.11147593 0.20935468, 0.12624404 0.11015336 0.21193573, 0.12617938 0.11017753 0.21186629, 0.12546529 0.10995008 0.21240635, 0.1249904 0.10992424 0.21245769, 0.12586893 0.11153512 0.20917316, 0.12582386 0.11148761 0.20924592, 0.12586896 0.11003761 0.2121674, 0.12692671 0.11118145 0.2100469, 0.12699753 0.11124901 0.21005081, 0.12582374 0.11006759 0.21208586, 0.12544291 0.10996537 0.21231179, 0.12499046 0.10994087 0.21236111, 0.12499051 0.10997586 0.21226956, 0.12541954 0.10999911 0.21222298, 0.1266235 0.11131589 0.20967488, 0.1262441 0.11141928 0.2094048, 0.12617937 0.11137791 0.20946576, 0.12704605 0.11096473 0.21048033, 0.12712122 0.11102436 0.21050012, 0.12684573 0.11112641 0.21005356, 0.12654626 0.1112666 0.20970976, 0.12646611 0.11123319 0.20975509, 0.127046 0.11074136 0.21092689, 0.12712115 0.11079295 0.21096274, 0.12696031 0.1109186 0.21046914, 0.12675814 0.11108597 0.21007071, 0.12666695 0.11106201 0.21009752, 0.12692659 0.11052473 0.21136035, 0.12699752 0.1105683 0.21141215, 0.12696032 0.11070485 0.21089695, 0.12686719 0.11088811 0.21046649, 0.12677039 0.11087428 0.2104727, 0.12675695 0.11036332 0.21182205, 0.12499048 0.10994871 0.2126514, 0.1268672 0.11068426 0.21087398, 0.12677027 0.11068104 0.21085949, 0.12499049 0.11186881 0.20881166, 0.12550402 0.11184083 0.20886762, 0.12308061 0.11093034 0.21481077, 0.12402935 0.11078851 0.21503089, 0.12400714 0.11077313 0.21512498, 0.12220062 0.113975 0.20874394, 0.12226532 0.11393376 0.20880489, 0.12152809 0.11363538 0.20942278, 0.12499049 0.11073636 0.21513529, 0.12405005 0.11078469 0.21493532, 0.12499036 0.1107337 0.21503724, 0.12308061 0.11418538 0.20830159, 0.12406814 0.11076196 0.21484163, 0.12319973 0.11090927 0.2145469, 0.12402952 0.11427639 0.20805621, 0.12316442 0.11404733 0.2084109, 0.12312424 0.11412291 0.20836319, 0.1231645 0.11093484 0.21463473, 0.12312432 0.11094196 0.21472381, 0.1231997 0.11396162 0.20844306, 0.12406817 0.11410899 0.20814849, 0.12405013 0.11419754 0.20811062, 0.12499046 0.11439596 0.20788081, 0.12398365 0.11439367 0.20790686, 0.12499039 0.11444823 0.20779775, 0.12232758 0.11387677 0.20885493, 0.12160838 0.113602 0.20946838, 0.12105671 0.11323355 0.21022621, 0.12243509 0.11372571 0.20891505, 0.12238468 0.11380668 0.20889224, 0.1216855 0.11355291 0.20950319, 0.12114798 0.11320962 0.21025293, 0.12081397 0.11279325 0.21110718, 0.12181902 0.1134146 0.20953716, 0.12175663 0.11348946 0.20952649, 0.12123571 0.11316921 0.21026997, 0.12091099 0.11277933 0.21111324, 0.12081403 0.1123396 0.21201423, 0.12131654 0.11311425 0.21027668, 0.12138735 0.11304666 0.21027283, 0.12100399 0.11274894 0.21111058, 0.12091084 0.11233632 0.2119993, 0.12105678 0.11189915 0.21289484, 0.12108965 0.11270301 0.21109934, 0.12116502 0.11264326 0.21107952, 0.12100385 0.11231591 0.21197645, 0.12114786 0.11190619 0.21285982, 0.12152825 0.11149748 0.21369806, 0.12116498 0.11222781 0.21191059, 0.12108968 0.11227931 0.21194644, 0.12123568 0.11189549 0.21281718, 0.12160836 0.11151375 0.2136441, 0.12220061 0.11115791 0.21437712, 0.12138723 0.11182435 0.21271743, 0.12131651 0.11186789 0.21276914, 0.12168558 0.11151217 0.21358384, 0.12226534 0.11118199 0.21430747, 0.12303531 0.1109003 0.21489222, 0.121819 0.11145641 0.21345298, 0.12175666 0.11149283 0.21351947, 0.12232757 0.11118795 0.21423204, 0.12398361 0.11073951 0.21521409, 0.12499039 0.11071198 0.21494152, 0.12243494 0.11114542 0.21407491, 0.12238494 0.11117558 0.21415329, 0.12400703 0.1143425 0.20798753, 0.12303531 0.1142327 0.2082286, 0.12499037 0.11432858 0.2079518, 0.12499042 0.11068477 0.21532331, 0.12499045 0.11071979 0.21523191, 0.12499045 0.11415915 0.20804857, 0.12499042 0.11424856 0.20800838, 0.12629199 0.11288105 0.20869589, 0.12678137 0.11396165 0.20844303, 0.12754588 0.11372568 0.20891522, 0.12733591 0.11250876 0.20944047, 0.12556307 0.11016838 0.21316622, 0.12629208 0.11046334 0.21353094, 0.1257529 0.11055951 0.21429215, 0.12591259 0.11076216 0.21484165, 0.12678127 0.11090939 0.2145468, 0.12556306 0.11241259 0.20867853, 0.12575297 0.11354811 0.20831619, 0.12591282 0.11410899 0.20814858, 0.12754576 0.11114557 0.21407482, 0.12733595 0.11083551 0.21278621, 0.12816192 0.11145644 0.21345289, 0.1285937 0.11182432 0.21271713, 0.12791531 0.1113735 0.21171035, 0.12881593 0.11222787 0.21191038, 0.12881605 0.11264332 0.21107949, 0.12791531 0.11197062 0.21051599, 0.12859358 0.11304663 0.21027267, 0.12816194 0.1134146 0.20953713, 0.093165278 0.076741263 0.27872866, 0.093180597 0.080310062 0.28052253, 0.093453914 0.076690808 0.27882975, 0.092932656 0.080386624 0.28036937, 0.093462348 0.080262259 0.28061807, 0.093761444 0.076673552 0.2788642, 0.093761533 0.080246016 0.28065038, 0.093761384 0.08136417 0.27841461, 0.093462169 0.081347957 0.27844691, 0.093761563 0.077805355 0.27663481, 0.093460083 0.077788904 0.27666807, 0.093180493 0.081300184 0.27854276, 0.093176603 0.077740386 0.27676511, 0.092932552 0.081223592 0.2786957, 0.092927501 0.077662721 0.27692044, 0.092732757 0.081122681 0.27889746, 0.092727542 0.077560499 0.27712488, 0.092515469 0.077175692 0.27760768, 0.092515469 0.077188715 0.27783394, 0.092512101 0.077085361 0.27763355, 0.092588782 0.07743974 0.27736652, 0.092592686 0.081003413 0.27913618, 0.092559814 0.077392653 0.27744222, 0.092520565 0.080872521 0.27939773, 0.092538238 0.077331856 0.27750981, 0.092523575 0.077259019 0.27756572, 0.092520714 0.080737665 0.27966738, 0.092577964 0.077052906 0.2781055, 0.092592761 0.080606803 0.27992904, 0.092713267 0.076928094 0.27835488, 0.092732787 0.080487445 0.28016779, 0.092913017 0.076822087 0.27856719, 0.12499048 0.11490925 0.21133433, 0.12469125 0.11489294 0.21136703, 0.12499051 0.11133675 0.20954798, 0.12469129 0.11132054 0.20958045, 0.12440957 0.11484517 0.21146241, 0.12440945 0.11127286 0.2096761, 0.12416159 0.11476861 0.21161568, 0.12416151 0.11119635 0.20982935, 0.1239617 0.11466773 0.21181735, 0.12396158 0.11109523 0.21003094, 0.12382163 0.1145484 0.21205603, 0.12382162 0.11097597 0.21026957, 0.12374943 0.11441751 0.21231754, 0.12374966 0.11084501 0.21053125, 0.12374963 0.1142828 0.21258722, 0.12374966 0.11071016 0.21080071, 0.12382165 0.11415203 0.21284911, 0.12382165 0.11057942 0.21106245, 0.1239617 0.11403258 0.21308757, 0.12396169 0.11046012 0.21130122, 0.12416159 0.11393164 0.21328948, 0.12416153 0.11035924 0.21150281, 0.12440954 0.11385511 0.2134424, 0.1244096 0.11028259 0.21165587, 0.12469126 0.11023481 0.21175161, 0.12469135 0.11380725 0.21353783, 0.12499051 0.11021857 0.2117839, 0.12499049 0.11379106 0.21357046, 0.12499048 0.11684935 0.21191321, 0.12499036 0.11836417 0.21267079, 0.12460746 0.11682849 0.21195494, 0.12460755 0.11834319 0.21271236, 0.12424684 0.11828215 0.21283452, 0.12424697 0.11676721 0.21207725, 0.12392938 0.11818416 0.21303071, 0.12392949 0.11666934 0.21227325, 0.12367356 0.118055 0.21328881, 0.12367365 0.11654018 0.21253133, 0.12349437 0.11790223 0.21359439, 0.12349442 0.11638753 0.21283692, 0.1234021 0.11773472 0.21392919, 0.12340207 0.11622001 0.21317188, 0.12340215 0.1175621 0.21427411, 0.12340207 0.1160474 0.21351688, 0.12349437 0.11739461 0.21460928, 0.12349443 0.11587994 0.21385202, 0.12367359 0.1172419 0.21491474, 0.12367369 0.11572714 0.21415733, 0.12392941 0.11711274 0.21517295, 0.12392949 0.11559801 0.21441574, 0.12424675 0.11701493 0.21536893, 0.12424697 0.1154999 0.21461128, 0.12460747 0.11695354 0.21549135, 0.12460758 0.11543877 0.2147337, 0.12499057 0.11693279 0.21553279, 0.12499048 0.115418 0.21477531, 0.093761504 0.083304241 0.27899352, 0.093761474 0.084819034 0.27975109, 0.093378738 0.083283558 0.27903521, 0.093378603 0.084798172 0.2797927, 0.093017995 0.084737018 0.279915, 0.093017891 0.083222196 0.27915737, 0.092700571 0.084639058 0.28011072, 0.092700496 0.083124265 0.27935329, 0.092444718 0.084509924 0.28036919, 0.092444718 0.082995132 0.27961162, 0.092265427 0.084357217 0.28067449, 0.092265502 0.082842335 0.27991718, 0.092173085 0.084189758 0.28100944, 0.092173174 0.082674906 0.28025204, 0.09217304 0.084017232 0.28135458, 0.092173189 0.082502529 0.28059703, 0.092265442 0.083849713 0.28168958, 0.092265427 0.082334951 0.28093198, 0.092444688 0.083696917 0.28199497, 0.092444748 0.082182154 0.2812376, 0.09270066 0.083567724 0.28225327, 0.092700422 0.082052961 0.28149569, 0.093017966 0.083469704 0.28244904, 0.093017995 0.081955031 0.28169158, 0.093378574 0.083408549 0.28257135, 0.093378633 0.081893906 0.28181398, 0.093761474 0.083387688 0.28261295, 0.093761504 0.081873015 0.28185552, 0.1129825 0.10336132 0.22929057, 0.11299387 0.10329647 0.22927931, 0.10788596 0.10198908 0.23203434, 0.10787855 0.10191928 0.23203348, 0.10787705 0.10185303 0.23201916, 0.1130009 0.1032327 0.22926047, 0.10788134 0.10179241 0.23199204, 0.11300328 0.1031713 0.22923413, 0.11586979 0.10646231 0.22308894, 0.11588109 0.10639761 0.22307773, 0.11077319 0.10509042 0.22583288, 0.11076573 0.10502063 0.22583163, 0.11076429 0.1049545 0.22581735, 0.11588807 0.10633393 0.22305891, 0.11076847 0.10489379 0.22579026, 0.11589052 0.10627256 0.22303265, 0.10720815 0.097158894 0.24169385, 0.10721971 0.097093925 0.24168265, 0.1021117 0.095786527 0.24443766, 0.1021044 0.095716849 0.24443653, 0.10210277 0.095650569 0.24442193, 0.10722671 0.097030178 0.24166372, 0.10210726 0.095589742 0.24439512, 0.10722901 0.096968904 0.2416373, 0.10432115 0.094057515 0.24789537, 0.10433258 0.093992636 0.24788399, 0.099224582 0.092685267 0.25063932, 0.099217355 0.09261547 0.25063819, 0.099215716 0.092549399 0.25062382, 0.10433958 0.093928948 0.24786519, 0.099220008 0.092488483 0.25059652, 0.10434201 0.093867615 0.24783911, 0.10143386 0.090956166 0.25409722, 0.10144535 0.090891317 0.25408572, 0.096337408 0.089584097 0.25684077, 0.096330076 0.089514241 0.25683981, 0.096328408 0.089448079 0.25682563, 0.10145232 0.090827718 0.25406718, 0.096332803 0.089387372 0.25679836, 0.10145472 0.090766266 0.25404084, 0.098546758 0.087855145 0.26029855, 0.098558277 0.087790266 0.26028731, 0.093450248 0.086482868 0.26304233, 0.093442902 0.086413071 0.26304129, 0.093441352 0.086346909 0.26302701, 0.098565191 0.087726608 0.26026848, 0.093445644 0.086286232 0.26299992, 0.09856768 0.087665096 0.26024228, 0.095659703 0.084753647 0.26650017, 0.095671147 0.084688917 0.26648906, 0.090563223 0.083381549 0.2692441, 0.090555713 0.083311692 0.26924306, 0.090554237 0.083245561 0.26922882, 0.09567818 0.08462514 0.26647013, 0.090558603 0.083184823 0.2692014, 0.09568052 0.084563807 0.26644391, 0.11009528 0.10025994 0.23549229, 0.11010681 0.10019518 0.23548087, 0.10499899 0.098887905 0.23823579, 0.1049915 0.098817959 0.23823491, 0.10498984 0.098751917 0.23822059, 0.1101137 0.10013144 0.23546219, 0.10499431 0.098691121 0.23819341, 0.11011626 0.10007016 0.23543586, 0.092772707 0.081652477 0.27270195, 0.092783868 0.081587657 0.27269053, 0.087675989 0.080280319 0.27544549, 0.087668628 0.080210492 0.27544463, 0.087667182 0.080144331 0.2754302, 0.092790946 0.08152397 0.27267173, 0.087671369 0.080083653 0.27540326, 0.092793435 0.081462607 0.27264559, 0.089271665 0.078386053 0.27923381, 0.089283258 0.078321174 0.27922261, 0.084788933 0.077179179 0.28164721, 0.084781528 0.077109322 0.28164613, 0.084779948 0.077043191 0.28163195, 0.089290142 0.078257486 0.27920377, 0.084784269 0.076982424 0.28160465, 0.089292675 0.078196123 0.27917767, 0.099009171 0.074214324 0.28578192, 0.09897472 0.073866591 0.2857514, 0.082763433 0.074214175 0.28578192, 0.082737088 0.073867366 0.2857517, 0.082736239 0.073528484 0.28566065, 0.09897387 0.073529348 0.28566107, 0.082761437 0.073212937 0.28551334, 0.099006608 0.073212996 0.28551334, 0.13014218 -0.033307627 0.1406759, 0.13018245 -0.03330873 0.14069524, 0.13015269 -0.033303931 0.140651, 0.1301315 -0.033311322 0.14070056, 0.13013314 -0.03330867 0.14081557, 0.13011055 -0.033319369 0.14074965, 0.13010122 -0.033322409 0.14077167, 0.13009001 -0.03332217 0.14086233, 0.13009633 -0.0333087 0.14090572, 0.13009153 -0.033325121 0.14079495, 0.13008167 -0.033329412 0.14081775, 0.13006796 -0.033329085 0.14090894, 0.13006379 -0.033342287 0.14085804, 0.13007249 -0.033336326 0.14083813, 0.130077 -0.03333275 0.14082804, 0.1300502 -0.033347562 0.14088963, 0.13004114 -0.033348992 0.14090918, 0.13005684 -0.033345476 0.14087375, 0.1135783 -0.033308521 0.18112248, 0.1136231 -0.033307239 0.18108192, 0.11360608 -0.03330256 0.18105638, 0.1136404 -0.03331019 0.18110768, 0.1135775 -0.033311233 0.18118009, 0.1136577 -0.033311144 0.18113345, 0.092386767 0.085563675 0.26555794, 0.090827778 0.083963826 0.26875728, 0.092298195 0.085543528 0.26559836, 0.09805344 0.087089404 0.26250726, 0.095422685 0.08520101 0.26628375, 0.095832914 0.08528997 0.26610532, 0.096275896 0.085345045 0.26599541, 0.12532751 0.10579447 0.22510259, 0.1230938 0.10396074 0.22876967, 0.12289093 0.10397102 0.22874895, 0.098309845 0.08830227 0.26008192, 0.093714997 0.087065086 0.26255602, 0.095274135 0.088664934 0.25935644, 0.095185608 0.088644788 0.25939685, 0.1009406 0.090190634 0.25630569, 0.098720014 0.088391289 0.25990391, 0.099162906 0.088446394 0.25979379, 0.10119687 0.09140344 0.25388026, 0.096602023 0.090166375 0.25635415, 0.098161072 0.091766194 0.25315475, 0.098072663 0.091746017 0.25319517, 0.10382769 0.093291864 0.25010407, 0.10160722 0.091492459 0.25370234, 0.12329252 0.10392903 0.22883295, 0.10205005 0.091547564 0.25359225, 0.10408407 0.094504729 0.24767865, 0.099489063 0.093267515 0.25015259, 0.1010482 0.094867572 0.24695314, 0.10095979 0.094847366 0.24699366, 0.096729487 0.085363522 0.26595858, 0.1198809 0.11505572 0.20658283, 0.11937857 0.11478408 0.20712627, 0.11964348 0.11496632 0.20676151, 0.10671479 0.096393153 0.24390252, 0.098837689 0.087186798 0.26231205, 0.1194924 0.11488061 0.20693307, 0.10449432 0.094593748 0.24750064, 0.10493729 0.094648913 0.24739046, 0.10697131 0.097605959 0.2414771, 0.10237634 0.096368775 0.24395092, 0.10393539 0.097968742 0.24075165, 0.10384691 0.097948417 0.24079207, 0.10461181 0.093389466 0.24990913, 0.11134219 0.091566011 0.25355542, 0.10250361 0.091565952 0.25355542, 0.10960197 0.099494383 0.23770097, 0.10738148 0.097695097 0.24129903, 0.10782434 0.097750112 0.24118884, 0.12015799 0.11511858 0.206457, 0.10985829 0.10070722 0.23527545, 0.10526341 0.099470034 0.23774937, 0.10682252 0.10107006 0.23454991, 0.11377889 0.093389466 0.24990895, 0.10673413 0.1010498 0.23459026, 0.11248924 0.10259561 0.23149925, 0.11026858 0.10079636 0.2350973, 0.11071135 0.10085146 0.2349872, 0.1204599 0.11515169 0.20639099, 0.11274555 0.10380854 0.22907403, 0.10815042 0.10257141 0.23154771, 0.10970964 0.1041712 0.22834845, 0.10962115 0.10415106 0.22838861, 0.11537637 0.10569687 0.22529748, 0.11315575 0.10389759 0.22889593, 0.11359863 0.1039526 0.22878569, 0.11563273 0.10690965 0.22287209, 0.1110376 0.1056727 0.22534639, 0.11259679 0.10727267 0.22214697, 0.11250828 0.10725246 0.2221871, 0.11826345 0.1087981 0.21909606, 0.1160429 0.10699879 0.22269408, 0.11648574 0.10705383 0.22258393, 0.11904748 0.1088957 0.2189012, 0.12821461 0.10889561 0.21890104, 0.125778 0.10707225 0.22254749, 0.12866525 0.11017354 0.21634561, 0.11982647 0.11017351 0.21634562, 0.12599733 0.11073942 0.21521404, 0.11154515 0.0915557 0.25357598, 0.13695076 0.11584635 0.20500185, 0.099858388 0.076003209 0.28467655, 0.11750796 0.096741632 0.24320565, 0.12039492 0.099842802 0.23700421, 0.11174381 0.09152405 0.25363946, 0.12347014 0.10387711 0.22893696, 0.12328216 0.10294406 0.23080258, 0.12616928 0.10604532 0.22460094, 0.12905641 0.1091467 0.21839932, 0.12949517 0.10961784 0.21745721, 0.11462067 0.093640402 0.24940756, 0.11173362 0.090539083 0.25560915, 0.10884646 0.087437734 0.26181054, 0.10595936 0.084336564 0.26801229, 0.12358589 0.10382502 0.22904091, 0.12549917 0.10580187 0.22508818, 0.12599722 0.11439355 0.20790686, 0.11192167 0.091472074 0.25374311, 0.11203726 0.09141998 0.25384772, 0.12567136 0.10582469 0.22504239, 0.11851966 0.11001106 0.21667062, 0.11395073 0.093396738 0.24989435, 0.11373605 0.10872312 0.21924625, 0.10722667 0.096479699 0.24372935, 0.10749899 0.096490696 0.2437074, 0.10696107 0.096446559 0.24379547, 0.11893001 0.11010008 0.21649249, 0.12583324 0.10586308 0.22496562, 0.11412287 0.093419507 0.24984857, 0.11937296 0.11015509 0.21638243, 0.095678166 0.084074721 0.26853615, 0.09595041 0.084085599 0.26851389, 0.095412493 0.08404161 0.26860213, 0.12597486 0.10591517 0.22486155, 0.095166281 0.083988175 0.26870912, 0.12608807 0.10597734 0.22473709, 0.11428475 0.093458012 0.24977204, 0.1144264 0.093510017 0.24966776, 0.11453968 0.093572214 0.24954346, 0.11850964 0.10885163 0.21898933, 0.089411259 0.082442209 0.27179998, 0.09253554 0.082099691 0.27248532, 0.087940469 0.080862567 0.27495891, 0.089499563 0.082462505 0.27175954, 0.11877522 0.10888474 0.21892311, 0.10539085 0.094667241 0.24735387, 0.12244041 0.10269316 0.2313042, 0.1200037 0.10086982 0.2349506, 0.11327316 0.10269313 0.23130427, 0.11116503 0.10086973 0.23495057, 0.13658477 0.11606021 0.20457412, 0.12694559 0.11423261 0.20822854, 0.12778032 0.11397491 0.20874405, 0.12845281 0.1136355 0.20942296, 0.12020656 0.1008596 0.23497126, 0.093842328 0.082262084 0.27216029, 0.093388647 0.082243785 0.27219689, 0.11089188 0.090288267 0.25611073, 0.10845515 0.088464752 0.25975713, 0.1017247 0.090288147 0.25611073, 0.12040539 0.10082786 0.2350346, 0.099616349 0.088464782 0.25975716, 0.10865815 0.088454559 0.25977778, 0.10885684 0.08842276 0.25984097, 0.12058294 0.10077594 0.23513848, 0.11693934 0.10707231 0.22254746, 0.10903452 0.088370845 0.25994503, 0.12261207 0.10270055 0.23128967, 0.12069876 0.10072376 0.23524264, 0.11106345 0.090295628 0.25609604, 0.10915008 0.088318899 0.26004919, 0.11123574 0.090318367 0.25605035, 0.1227843 0.10272335 0.23124403, 0.13697675 0.11591585 0.20486273, 0.13697255 0.11588053 0.20493339, 0.13696255 0.11595087 0.20479296, 0.13693117 0.1159835 0.20472804, 0.11139773 0.090356842 0.25597391, 0.10433957 0.093378291 0.24993111, 0.10407385 0.09334527 0.24999715, 0.1289243 0.11323364 0.21022619, 0.12916687 0.11279328 0.21110715, 0.13688399 0.1160119 0.20467086, 0.13682345 0.11603506 0.20462479, 0.1367528 0.11605136 0.20459203, 0.13667558 0.11606009 0.20457456, 0.11153927 0.090408817 0.25586945, 0.13663031 0.11606143 0.20457162, 0.12916693 0.11233975 0.21201408, 0.12294626 0.10276176 0.23116727, 0.11165249 0.090471074 0.25574499, 0.12308785 0.10281383 0.2310632, 0.12320109 0.10287611 0.23093855, 0.11588825 0.10578342 0.22512463, 0.11616039 0.10579441 0.2251026, 0.11562248 0.10575049 0.22519079, 0.083725333 0.076260015 0.28416282, 0.08341673 0.076003119 0.28467655, 0.083636984 0.07623978 0.2842032, 0.10800479 0.087186858 0.26231232, 0.10556814 0.085363552 0.26595855, 0.10577103 0.085353151 0.26597929, 0.10596961 0.085321531 0.26604259, 0.11405218 0.10397099 0.2287491, 0.12778023 0.111158 0.21437705, 0.12694566 0.11090033 0.21489215, 0.089392185 0.077785596 0.28111196, 0.11955313 0.099591956 0.23750585, 0.11711656 0.09776853 0.24115233, 0.11038594 0.099591926 0.23750594, 0.12845282 0.11149774 0.2136981, 0.12887773 0.11016227 0.21636845, 0.10614747 0.085269526 0.26614645, 0.10827793 0.097768351 0.24115212, 0.11731936 0.097758248 0.2411727, 0.12907553 0.11012964 0.21643381, 0.10817644 0.087194279 0.26229751, 0.1062631 0.085217431 0.26625061, 0.11751813 0.097726569 0.24123606, 0.12892418 0.11189933 0.21289481, 0.12924351 0.11007993 0.21653301, 0.10834852 0.087217048 0.26225194, 0.08990401 0.077872142 0.28093916, 0.090176255 0.077883139 0.28091699, 0.089638367 0.077839002 0.28100502, 0.11769587 0.097674593 0.24133989, 0.10851043 0.087255582 0.2621752, 0.12938645 0.11001255 0.21666768, 0.11781166 0.09762238 0.24144413, 0.10865209 0.087307498 0.26207125, 0.11972503 0.099599168 0.23749131, 0.11300108 0.10268204 0.23132646, 0.11273541 0.10264902 0.23139232, 0.10876536 0.087369695 0.26194656, 0.12949128 0.10993181 0.21682933, 0.1198971 0.099622026 0.23744552, 0.12955028 0.10984413 0.21700478, 0.1014526 0.09027712 0.25613266, 0.10118677 0.090244099 0.25619882, 0.1295637 0.10975675 0.21717924, 0.12954189 0.10968335 0.21732605, 0.12005906 0.099660471 0.23736887, 0.12020053 0.099712566 0.23726469, 0.10511759 0.084085748 0.26851392, 0.10268103 0.082262114 0.27216023, 0.12031397 0.099774912 0.23714004, 0.10288376 0.082251951 0.2721808, 0.10308263 0.082220212 0.27224422, 0.10326025 0.082168356 0.27234781, 0.10337593 0.082116202 0.27245247, 0.10528919 0.084093139 0.26849926, 0.10546134 0.084115997 0.26845366, 0.1056233 0.084154293 0.26837671, 0.10576493 0.084206387 0.26827276, 0.12598084 0.10706197 0.22256809, 0.10587826 0.084268525 0.26814818, 0.1142295 0.09466733 0.24735391, 0.12617961 0.10703029 0.22263132, 0.11666608 0.096490756 0.24370736, 0.11443248 0.094656929 0.24737443, 0.11463109 0.09462519 0.24743773, 0.12635736 0.10697828 0.22273529, 0.12838627 0.1089031 0.21888655, 0.1264731 0.10692619 0.22283946, 0.10019197 0.080984429 0.27471542, 0.099793747 0.079160944 0.27836168, 0.098494336 0.079160973 0.27836168, 0.1148089 0.094573334 0.24754174, 0.10000646 0.079149589 0.27838445, 0.12855847 0.10892592 0.21884075, 0.11492458 0.094521269 0.24764585, 0.1022304 0.080984369 0.27471542, 0.10020415 0.079116985 0.2784498, 0.11011375 0.099580929 0.23752791, 0.10984816 0.099547789 0.23759395, 0.11683774 0.096498087 0.24369289, 0.10037237 0.079067275 0.27854884, 0.12872042 0.10896431 0.21876416, 0.10051502 0.078999922 0.27868393, 0.11701 0.096520856 0.24364711, 0.09856531 0.087175861 0.26233432, 0.098299563 0.08714287 0.26240045, 0.12886183 0.10901637 0.21865994, 0.10240208 0.0809917 0.274701, 0.10061978 0.078919008 0.27884543, 0.12897529 0.10907857 0.21853548, 0.10273626 0.081052884 0.27457851, 0.10257417 0.081014529 0.27465522, 0.10067889 0.078831419 0.27902079, 0.11717196 0.096559301 0.24357031, 0.10287769 0.081104979 0.27447447, 0.10069245 0.078744069 0.27919519, 0.11731344 0.096611366 0.24346644, 0.10299101 0.081167266 0.27434993, 0.10067055 0.078670725 0.27934217, 0.11742686 0.096673623 0.24334191, 0.09934324 0.077883258 0.28091705, 0.10018502 0.078133985 0.28041542, 0.10010388 0.078066096 0.28055149, 0.099990666 0.078003839 0.28067595, 0.099849001 0.077951774 0.28078002, 0.099687159 0.077913418 0.28085697, 0.099514976 0.0778905 0.28090256, 0.10062377 0.078605339 0.27947304, 0.10307227 0.081235215 0.27421403, 0.092945784 0.08218883 0.27230704, 0.086524263 0.07934089 0.27800158, 0.089034781 0.078833148 0.27901721, 0.085053355 0.077761486 0.28116059, 0.086612672 0.079361126 0.27796125, 0.090500847 0.080408022 0.27586794, 0.089957267 0.077953175 0.27861094, 0.10380915 -0.033003017 0.21443322, 0.09884195 -0.033003077 0.21776879, 0.098539338 -0.033197626 0.2178757, 0.086899415 0.079250529 0.27706066, 0.092169046 0.079446599 0.27361873, 0.090242952 0.080150768 0.27526033, 0.1008658 -0.032623038 0.21235178, 0.10615996 -0.032622859 0.20879683, 0.11217771 -0.032290712 0.22448911, 0.11218093 -0.032314822 0.22447528, 0.096854344 -0.03231509 0.22447528, 0.096029758 -0.033068821 0.22403917, 0.103577 -0.009736374 0.23753469, 0.10333434 -0.0088839382 0.23802765, 0.10286289 -0.0081065446 0.23847738, 0.090681598 0.06419526 0.28029725, 0.10040738 -0.0066392571 0.2393261, 0.091629907 0.064506575 0.28047746, 0.10135566 -0.0069505721 0.23914577, 0.092464536 0.065005377 0.28076589, 0.10219043 -0.0074494332 0.23885754, 0.093137085 0.065662488 0.28114605, 0.090681478 0.071267202 0.2843878, 0.091629788 0.070955828 0.2842077, 0.092464522 0.070457086 0.28391927, 0.093137071 0.069800004 0.28353906, 0.09360832 0.06902273 0.28308958, 0.093851134 0.068170056 0.28259635, 0.093851149 0.067292258 0.28208858, 0.093608484 0.066439822 0.28159547, 0.10040757 -0.013711348 0.23523574, 0.10357697 -0.01061438 0.2370269, 0.10333426 -0.011466727 0.23653385, 0.10286313 -0.012244239 0.23608412, 0.1021906 -0.01290147 0.23570414, 0.10135572 -0.013399944 0.23541571, 0.11877833 0.11538832 0.20714858, 0.11234687 0.10848005 0.2209636, 0.11867079 0.11648078 0.20771016, 0.081188872 0.074542031 0.28776318, 0.082120523 0.07721971 0.28622073, 0.081831127 0.076818004 0.28681755, 0.081587583 0.076306239 0.28727245, 0.081403241 0.075750217 0.28757018, 0.081267819 0.075144634 0.28773516, 0.083848983 0.05212073 0.27513415, 0.083918244 0.051565215 0.27481264, 0.089652061 0.0056365579 0.24824739, 0.089721352 0.0050810128 0.24792595, 0.12987496 -0.034599856 0.1390215, 0.094570249 -0.033759132 0.22546063, 0.13005991 -0.033402935 0.13889746, 0.093669519 -0.034605041 0.22742887, 0.093564048 -0.0337594 0.22791784, 0.11288357 0.10716198 0.22124608, 0.13036846 -0.032894716 0.14023598, 0.11800562 0.10854097 0.21848865, 0.13566257 -0.032894537 0.13668095, 0.084012255 0.07614927 0.28326178, 0.097591639 -0.032623544 0.22034711, 0.089134246 0.077528372 0.28050464, 0.10288566 -0.032623276 0.21679203, 0.10999642 0.10406061 0.22744767, 0.1270598 -0.032619312 0.14839083, 0.11511858 0.10543968 0.22469002, 0.13235395 -0.032619014 0.14483583, 0.12831007 -0.032998785 0.14581266, 0.13327728 -0.032998756 0.14247715, 0.12800743 -0.033193424 0.14591974, 0.10710929 0.10095935 0.23364916, 0.1237855 -0.032619789 0.15638606, 0.11223134 0.10233833 0.23089167, 0.12907958 -0.032619551 0.15283106, 0.12503597 -0.032999352 0.15380768, 0.13000305 -0.032999083 0.15047237, 0.12473322 -0.033193931 0.15391484, 0.10422228 0.097858056 0.23985076, 0.12051132 -0.032620266 0.16438116, 0.1093442 0.099237069 0.23709334, 0.12580524 -0.032619968 0.16082604, 0.12176177 -0.032999918 0.1618029, 0.12672879 -0.03299959 0.15846752, 0.12145896 -0.033194318 0.16190988, 0.10133523 0.094756857 0.24605238, 0.11723697 -0.032620683 0.17237633, 0.10645702 0.096135929 0.24329485, 0.12253112 -0.032620475 0.16882113, 0.11848736 -0.033000216 0.16979793, 0.12345457 -0.033000097 0.16646245, 0.11818479 -0.033194885 0.16990502, 0.098447934 0.091655537 0.25225395, 0.11396287 -0.032621279 0.18037158, 0.10356995 0.093034461 0.24949636, 0.11925694 -0.032621011 0.17681651, 0.11521319 -0.033000812 0.17779301, 0.12018037 -0.033000574 0.17445759, 0.11491062 -0.033195421 0.17790011, 0.095560849 0.088554367 0.25845566, 0.11068851 -0.032621518 0.18836655, 0.10068278 0.08993341 0.25569803, 0.1159827 -0.032621577 0.18481147, 0.11193906 -0.033001319 0.18578833, 0.11690605 -0.03300117 0.18245287, 0.11163622 -0.033195838 0.1858954, 0.0926736 0.085453168 0.26465732, 0.10741436 -0.032622084 0.19636171, 0.09779568 0.086832181 0.26189965, 0.11270833 -0.032621816 0.19280663, 0.10866481 -0.033001825 0.19378345, 0.11363184 -0.033001587 0.19044794, 0.10836212 -0.033196285 0.19389044, 0.089786485 0.082351908 0.27085888, 0.10414015 -0.032622591 0.20435679, 0.094908521 0.083730832 0.2681013, 0.1094342 -0.032622501 0.2008018, 0.10539041 -0.033002272 0.20177841, 0.11035749 -0.033002064 0.19844289, 0.10508786 -0.033196822 0.20188546, 0.10211618 -0.033002689 0.20977354, 0.10708328 -0.03300257 0.2064382, 0.10181358 -0.033197418 0.20988077, 0.099663392 0.0758086 0.28498957, 0.083270818 0.075815007 0.28498104, 0.099482477 0.075560018 0.28526157, 0.083130464 0.075566307 0.28525573, 0.099321485 0.07526575 0.28548342, 0.083003595 0.075265691 0.28548348, 0.099186078 0.074935779 0.28564727, 0.082897261 0.074927613 0.28565043, 0.099080786 0.074581131 0.28574812, 0.082816586 0.07457079 0.28575, 0.083711773 0.076269522 0.28414214, 0.083698153 0.076277807 0.28412086, 0.089334637 0.077817157 0.28102076, 0.083684593 0.076284662 0.28409934, 0.083804116 0.076351687 0.28382581, 0.089279965 0.077824458 0.28092307, 0.089231133 0.077807233 0.28082383, 0.083894908 0.076349631 0.28360325, 0.089190349 0.077766463 0.28072751, 0.083950147 0.076311037 0.28345823, 0.089159429 0.077704296 0.28063923, 0.083983853 0.076257601 0.28336129, 0.089140505 0.077623442 0.28056353, 0.084001601 0.076206401 0.28330389, 0.08499375 0.077688649 0.28128636, 0.08909443 0.078776732 0.27909988, 0.084936142 0.07759957 0.28140301, 0.089150831 0.078699157 0.27916566, 0.084884077 0.077498212 0.28150243, 0.08920081 0.078604802 0.27921146, 0.084840953 0.077390119 0.28157818, 0.089241818 0.078498468 0.27923435, 0.084808826 0.077281818 0.28162646, 0.08788079 0.080789849 0.27508485, 0.09259519 0.082043245 0.27256775, 0.087823153 0.0807008 0.27520123, 0.092651546 0.0819657 0.27263358, 0.087771267 0.080599353 0.27530074, 0.092701599 0.081871346 0.27267942, 0.087728038 0.08049117 0.2753765, 0.092742741 0.081764951 0.27270263, 0.08769609 0.080382869 0.27542484, 0.086598963 0.079370663 0.27794057, 0.086585343 0.079378828 0.27791938, 0.090443388 0.080439493 0.2757768, 0.086571693 0.079385832 0.27789772, 0.08669126 0.079453036 0.27762413, 0.090388745 0.080446884 0.27567911, 0.09033978 0.080429837 0.27557936, 0.086782113 0.079450861 0.27740192, 0.090298995 0.080388978 0.2754834, 0.086837217 0.079412326 0.27725661, 0.090268344 0.080326602 0.27539527, 0.086870983 0.07935901 0.2771596, 0.09024936 0.080245838 0.27531946, 0.086888731 0.07930769 0.27710235, 0.096209973 -0.03330861 0.22366686, 0.096393317 -0.033206925 0.22354929, 0.096160576 -0.033353522 0.22364184, 0.096450537 -0.03308861 0.22379407, 0.096380681 -0.033295855 0.22329132, 0.096412733 -0.033353373 0.22302605, 0.11189535 -0.033249244 0.18555109, 0.11188607 -0.033269659 0.18550766, 0.11173683 -0.033351168 0.18560727, 0.11188518 -0.03328611 0.18545645, 0.11190166 -0.033304319 0.18535671, 0.1119455 -0.033311382 0.1852265, 0.1135104 -0.033350959 0.18127637, 0.11355193 -0.033311173 0.18130413, 0.1085747 -0.033279583 0.1935627, 0.1085612 -0.033308432 0.19350253, 0.10846274 -0.033351645 0.19360243, 0.10855755 -0.033332393 0.19343285, 0.1085642 -0.033351734 0.19335447, 0.1053004 -0.033280149 0.20155776, 0.10528679 -0.033308849 0.20149769, 0.10518837 -0.033352152 0.20159736, 0.1052831 -0.033332929 0.20142804, 0.10528967 -0.033351943 0.2013496, 0.10202624 -0.033280596 0.20955293, 0.10201257 -0.033309326 0.20949289, 0.10191415 -0.033352479 0.20959264, 0.10200915 -0.033333436 0.20942317, 0.10201557 -0.033352539 0.20934467, 0.098751962 -0.033280984 0.21754801, 0.098738298 -0.033309713 0.21748802, 0.098640084 -0.033352986 0.21758765, 0.098734647 -0.033333763 0.2174183, 0.098741278 -0.033352897 0.21734002, 0.11512317 -0.033278629 0.17757228, 0.11510955 -0.033307448 0.17751235, 0.11501111 -0.033350691 0.17761198, 0.115106 -0.033331558 0.17744258, 0.1151125 -0.033350632 0.17736426, 0.1183975 -0.033278182 0.16957748, 0.11838362 -0.033306912 0.16951722, 0.11828531 -0.033350155 0.16961716, 0.11838019 -0.033330902 0.16944769, 0.11838694 -0.033350155 0.16936915, 0.12167165 -0.033277735 0.16158219, 0.12165797 -0.033306465 0.16152196, 0.12155968 -0.033349797 0.16162197, 0.12165447 -0.033330515 0.16145241, 0.12166113 -0.033349797 0.16137414, 0.12494583 -0.033277199 0.15358701, 0.12493221 -0.033305958 0.15352678, 0.12483379 -0.033349201 0.15362673, 0.12492856 -0.033330008 0.15345721, 0.1249353 -0.033349261 0.15337889, 0.12826654 -0.03324683 0.14557548, 0.12825738 -0.033267185 0.1455321, 0.1281081 -0.033348814 0.14563161, 0.1282564 -0.033283725 0.14548081, 0.12827288 -0.033301935 0.14538106, 0.12831675 -0.033308968 0.14525118, 0.12025082 -0.03331016 0.16511312, 0.12606321 -0.033309832 0.16121002, 0.12028468 -0.033300385 0.16497126, 0.12599574 -0.033294931 0.16110952, 0.12030828 -0.033267543 0.16483083, 0.12593202 -0.033251092 0.16101475, 0.12031475 -0.033240393 0.16476297, 0.12031558 -0.033204451 0.1646992, 0.12587634 -0.033180788 0.16093165, 0.12037143 -0.033140734 0.1645804, 0.12583169 -0.033088341 0.16086525, 0.12042221 -0.033062115 0.16447771, 0.12045634 -0.032991275 0.16441372, 0.12580094 -0.032979324 0.16081953, 0.12047751 -0.032934651 0.16437756, 0.12049423 -0.032876357 0.1643528, 0.12578593 -0.032860085 0.16079707, 0.12050624 -0.032817379 0.16433942, 0.12051412 -0.032752976 0.16433807, 0.12578735 -0.032737985 0.16079944, 0.12051596 -0.032684162 0.16435242, 0.12152122 -0.033338055 0.16171852, 0.12171265 -0.033203825 0.16166945, 0.12149557 -0.033311591 0.16178901, 0.12174343 -0.033108816 0.16174498, 0.12147689 -0.033273652 0.16184478, 0.12146623 -0.033236995 0.16188061, 0.10520381 0.099397317 0.23787501, 0.1099178 0.10065086 0.23535803, 0.10514604 0.099308297 0.23799169, 0.10997429 0.10057329 0.23542389, 0.10509394 0.09920691 0.23809092, 0.11002435 0.10047881 0.23546976, 0.10505091 0.099098787 0.23816673, 0.1100655 0.10037239 0.23549286, 0.10501891 0.098990545 0.2382153, 0.10392176 0.097978219 0.24073088, 0.10390817 0.097986445 0.2407099, 0.10954455 0.099525854 0.23760968, 0.10389455 0.097993508 0.24068823, 0.1040139 0.098060593 0.2404145, 0.10948983 0.099533215 0.2375119, 0.10944095 0.099516138 0.23741254, 0.10410482 0.098058447 0.24019212, 0.10940008 0.099475339 0.23731616, 0.10415994 0.098019823 0.24004686, 0.10936932 0.099412993 0.23722807, 0.10419375 0.097966418 0.23995012, 0.10935035 0.099332318 0.23715243, 0.10421151 0.097915336 0.23989262, 0.12679932 -0.033309296 0.149123, 0.13261174 -0.033308998 0.14521974, 0.12683299 -0.033299342 0.1489809, 0.13254412 -0.033293948 0.1451191, 0.12685677 -0.0332665 0.14884059, 0.1324805 -0.033250138 0.14502431, 0.1268632 -0.033239409 0.14877275, 0.12686405 -0.033203408 0.14870887, 0.13242488 -0.033179775 0.14494133, 0.12691985 -0.03313978 0.14859015, 0.13238023 -0.033087388 0.14487487, 0.12697075 -0.033061102 0.14848751, 0.12700485 -0.032990292 0.14842349, 0.13234936 -0.032978252 0.14482915, 0.12702596 -0.032933816 0.14838727, 0.12704282 -0.032875314 0.14836234, 0.13233443 -0.032859191 0.14480689, 0.12705472 -0.032816425 0.14834903, 0.12706254 -0.032751992 0.1483478, 0.1323359 -0.032736942 0.14480902, 0.12706436 -0.032683298 0.14836213, 0.12829347 -0.03318204 0.14566785, 0.12806974 -0.033337221 0.1457285, 0.12804392 -0.033310607 0.14579864, 0.1283084 -0.033097252 0.14574876, 0.12802531 -0.033272639 0.14585459, 0.12801479 -0.033235952 0.14589033, 0.12352496 -0.033309683 0.15711807, 0.1293374 -0.033309355 0.15321513, 0.12355885 -0.033299699 0.1569763, 0.12926981 -0.033294484 0.15311415, 0.12358242 -0.033267006 0.15683578, 0.12920627 -0.033250526 0.15301968, 0.12358908 -0.033239946 0.15676805, 0.12358983 -0.033203855 0.15670401, 0.1291506 -0.033180401 0.15293665, 0.12364563 -0.033140227 0.15658517, 0.1291059 -0.033087745 0.15287025, 0.12369639 -0.033061549 0.15648274, 0.12373061 -0.032990828 0.15641862, 0.12907526 -0.032978818 0.15282448, 0.1237518 -0.032934234 0.15638259, 0.12376845 -0.032875851 0.15635757, 0.12906013 -0.032859609 0.15280208, 0.12378055 -0.032816872 0.15634434, 0.12378831 -0.032752469 0.15634292, 0.12906164 -0.032737359 0.15280436, 0.12379014 -0.032683685 0.15635739, 0.12479535 -0.033337608 0.15372352, 0.12498687 -0.033203319 0.15367419, 0.12476964 -0.033311054 0.15379372, 0.1250176 -0.033108398 0.15374985, 0.12475105 -0.033273205 0.15384963, 0.12474053 -0.033236459 0.15388536, 0.11697662 -0.033310667 0.17310828, 0.1227891 -0.033310458 0.16920522, 0.11701037 -0.033300802 0.17296638, 0.12272145 -0.033295497 0.16910461, 0.11703405 -0.03326796 0.1728259, 0.12265778 -0.033251479 0.1690097, 0.1170404 -0.03324081 0.17275816, 0.11704135 -0.033204809 0.17269439, 0.12260194 -0.033181235 0.16892675, 0.11709729 -0.03314124 0.1725755, 0.12255751 -0.033088759 0.16886051, 0.11714786 -0.033062473 0.17247307, 0.11718208 -0.032991722 0.17240882, 0.12252675 -0.032979712 0.16881473, 0.11720324 -0.032935157 0.17237288, 0.11721992 -0.032876626 0.17234772, 0.12251173 -0.032860592 0.16879208, 0.11723199 -0.032817885 0.17233464, 0.11723989 -0.032753482 0.17233324, 0.12251312 -0.032738313 0.16879442, 0.11724161 -0.032684609 0.17234735, 0.11824691 -0.033338532 0.16971388, 0.11843836 -0.033204302 0.16966465, 0.11822119 -0.033311978 0.16978389, 0.11846922 -0.033109292 0.16974004, 0.11820261 -0.033274218 0.1698397, 0.11819208 -0.033237442 0.16987565, 0.11355586 -0.033331797 0.18117061, 0.11353312 -0.033346072 0.18122238, 0.11357473 -0.033311144 0.18121547, 0.11356881 -0.033311114 0.18125014, 0.11951481 -0.033310935 0.17720041, 0.11944713 -0.033296004 0.17709976, 0.11365561 -0.033284321 0.18094033, 0.11370726 -0.033254787 0.18082228, 0.11938357 -0.033252016 0.17700486, 0.11378542 -0.033186451 0.18064986, 0.11932778 -0.033181801 0.17692201, 0.11384016 -0.033117756 0.18053515, 0.11928318 -0.033089325 0.17685565, 0.11388274 -0.033046171 0.18045083, 0.11390963 -0.032987967 0.18040089, 0.11925256 -0.032980248 0.17680965, 0.11393173 -0.032927319 0.18036357, 0.11394849 -0.032865897 0.18033962, 0.11923739 -0.032861039 0.17678733, 0.11395994 -0.03280507 0.18032841, 0.11396623 -0.03274624 0.1803291, 0.11923897 -0.032738879 0.17678963, 0.11396764 -0.032684341 0.18034285, 0.11497267 -0.033339068 0.17770889, 0.11516406 -0.033204839 0.17765966, 0.11494689 -0.033312455 0.17777908, 0.11519498 -0.033109829 0.17773516, 0.11492832 -0.033274695 0.1778349, 0.11491777 -0.033237919 0.17787072, 0.11042814 -0.03331162 0.18909851, 0.11624049 -0.033311263 0.18519539, 0.11046197 -0.033301726 0.18895687, 0.11617294 -0.033296391 0.18509482, 0.11048564 -0.033268854 0.18881615, 0.11610928 -0.033252612 0.18500017, 0.11049183 -0.033241794 0.18874843, 0.11049291 -0.033205792 0.18868463, 0.11605372 -0.033182248 0.18491718, 0.11054872 -0.033142194 0.18856567, 0.11600904 -0.033089891 0.18485057, 0.11059938 -0.033063307 0.18846321, 0.11063363 -0.032992497 0.18839921, 0.11597826 -0.032980785 0.18480489, 0.11065485 -0.032936022 0.18836309, 0.11067146 -0.032877579 0.1883381, 0.11596321 -0.032861605 0.18478227, 0.11068358 -0.03281872 0.18832482, 0.11069147 -0.032754287 0.18832354, 0.11596471 -0.032739446 0.18478473, 0.11069316 -0.032685533 0.18833774, 0.1119224 -0.033184454 0.18564335, 0.11169849 -0.033339515 0.18570417, 0.11167291 -0.033313051 0.18577425, 0.11193722 -0.033099696 0.18572445, 0.11165412 -0.033275113 0.18583015, 0.11164354 -0.033238426 0.18586594, 0.10842419 -0.033340111 0.19369923, 0.10861577 -0.033205822 0.1936499, 0.10839874 -0.033313528 0.19376914, 0.10864645 -0.033110753 0.19372524, 0.10837987 -0.033275589 0.19382517, 0.10836929 -0.033238903 0.1938609, 0.10715391 -0.033312038 0.19709371, 0.11296618 -0.03331174 0.19319059, 0.10718119 -0.033305362 0.19697993, 0.11289859 -0.033296868 0.19308986, 0.10719819 -0.033287719 0.1968811, 0.10720608 -0.033257172 0.19678541, 0.11283505 -0.033252969 0.19299521, 0.10720269 -0.033221051 0.19671443, 0.10724007 -0.033184037 0.1966332, 0.11277926 -0.033182636 0.19291224, 0.10727616 -0.033140138 0.19655694, 0.11273476 -0.033090219 0.19284576, 0.10732342 -0.033067003 0.19646151, 0.10735931 -0.032993451 0.19639437, 0.11270389 -0.032981053 0.19280002, 0.10738121 -0.032934293 0.19635691, 0.10739841 -0.032873467 0.19633158, 0.11268893 -0.032861814 0.19277738, 0.10741049 -0.032812431 0.19631903, 0.10741724 -0.032752231 0.19631858, 0.11269057 -0.032739654 0.19277991, 0.10741894 -0.032688305 0.19633217, 0.10514997 -0.033340588 0.20169413, 0.10534143 -0.033206299 0.20164505, 0.10512422 -0.033314005 0.20176435, 0.10537218 -0.03311123 0.20172036, 0.10510552 -0.033276096 0.2018204, 0.10509495 -0.03323938 0.20185614, 0.10387968 -0.033312455 0.20508873, 0.10969196 -0.033312246 0.20118557, 0.10390687 -0.033305928 0.20497519, 0.10962446 -0.033297345 0.20108461, 0.10392402 -0.033288255 0.20487607, 0.10393201 -0.033257738 0.20478046, 0.10956077 -0.033253387 0.20099023, 0.1039286 -0.033221617 0.20470951, 0.10396606 -0.033184633 0.20462848, 0.10950512 -0.033183172 0.20090723, 0.10400198 -0.033140674 0.20455229, 0.10946058 -0.033090785 0.20084071, 0.10404919 -0.033067599 0.20445669, 0.10408507 -0.032993808 0.20438957, 0.10942985 -0.032981679 0.20079507, 0.10410704 -0.03293483 0.20435207, 0.10412422 -0.032874122 0.20432703, 0.10941477 -0.03286241 0.20077291, 0.10413609 -0.032812849 0.20431423, 0.10414305 -0.032752797 0.20431387, 0.1094162 -0.03274022 0.20077494, 0.10414468 -0.032688752 0.20432723, 0.096129388 -0.033297196 0.22379942, 0.096103981 -0.033317849 0.22378974, 0.096080899 -0.033277556 0.22385737, 0.09617281 -0.033307597 0.22373542, 0.096130654 -0.033344075 0.22371753, 0.096644253 -0.032783374 0.22413023, 0.096060038 -0.03322117 0.22392365, 0.09675166 -0.032559261 0.22431512, 0.096042827 -0.033150747 0.22398481, 0.10060538 -0.033312961 0.21308395, 0.10641761 -0.033312634 0.2091808, 0.10063906 -0.033303067 0.21294215, 0.10635024 -0.033297732 0.20908017, 0.10066281 -0.033270285 0.21280164, 0.10628657 -0.033253893 0.20898533, 0.10066935 -0.033243194 0.2127337, 0.10067019 -0.033207193 0.21266992, 0.10623084 -0.03318356 0.20890222, 0.10072586 -0.033143535 0.21255098, 0.10618627 -0.033091143 0.20883603, 0.1007767 -0.033064857 0.21244873, 0.10081096 -0.032994136 0.21238457, 0.10615544 -0.032982066 0.20879009, 0.10083203 -0.032937363 0.21234854, 0.10084875 -0.032879069 0.21232355, 0.10614048 -0.032862887 0.20876776, 0.10086086 -0.03282024 0.21231012, 0.10086875 -0.032755718 0.21230884, 0.10614188 -0.032740787 0.20876999, 0.10087048 -0.032687053 0.21232308, 0.10187587 -0.033340946 0.20968936, 0.10206728 -0.033206657 0.20964022, 0.10185 -0.033314362 0.20975955, 0.10209796 -0.033111587 0.20971556, 0.10183141 -0.033276454 0.20981534, 0.10182084 -0.033239827 0.20985131, 0.09860149 -0.033341393 0.21768454, 0.098792896 -0.033207193 0.21763536, 0.098575741 -0.03331475 0.21775481, 0.098823771 -0.033112094 0.21771076, 0.098557085 -0.033276841 0.21781062, 0.09854649 -0.033240184 0.21784645, 0.097331047 -0.033313408 0.22107893, 0.1031436 -0.03331311 0.21717589, 0.097358465 -0.033306852 0.22096533, 0.10307598 -0.033298299 0.21707514, 0.097375482 -0.033289179 0.2208664, 0.097383499 -0.033258572 0.2207709, 0.10301231 -0.033254251 0.21698067, 0.097380012 -0.033222541 0.22069986, 0.097417474 -0.033185497 0.22061878, 0.10295662 -0.033184066 0.21689738, 0.097453564 -0.033141688 0.22054251, 0.10291201 -0.03309153 0.21683106, 0.097500846 -0.033068523 0.2204472, 0.097536564 -0.032994762 0.22037977, 0.10288128 -0.032982484 0.21678525, 0.097558543 -0.032935783 0.22034249, 0.097575665 -0.032874927 0.22031733, 0.10286623 -0.032863364 0.21676297, 0.097587675 -0.032813892 0.22030433, 0.097594574 -0.032753721 0.22030407, 0.10286771 -0.032741204 0.21676518, 0.097596407 -0.032689676 0.22031757, 0.13581721 -0.033308372 0.13691148, 0.13577665 -0.033299521 0.13685101, 0.13018262 -0.033293411 0.14058086, 0.13021384 -0.033275738 0.14050986, 0.13573855 -0.033273146 0.13679402, 0.13026108 -0.033234999 0.14040516, 0.1357052 -0.033230945 0.13674435, 0.13029417 -0.033193782 0.14033616, 0.13567843 -0.033175513 0.13670458, 0.13031983 -0.033150718 0.14028481, 0.13033615 -0.033115581 0.14025439, 0.13565986 -0.033110157 0.13667719, 0.1303495 -0.033079103 0.14023174, 0.13035978 -0.033042148 0.14021711, 0.13565089 -0.033038542 0.13666378, 0.13036667 -0.033005551 0.1402104, 0.13037051 -0.032970026 0.14021061, 0.13565184 -0.032965228 0.13666509, 0.13037135 -0.032932833 0.14021908, 0.12671971 -0.033320054 0.14912029, 0.12675911 -0.033311918 0.14912154, 0.12668177 -0.033333346 0.14911883, 0.12679467 -0.033309296 0.14918654, 0.12665576 -0.033328936 0.14930589, 0.12661059 -0.033352897 0.14928725, 0.12678444 -0.033309326 0.14924915, 0.12670454 -0.033314183 0.14932589, 0.12675473 -0.033309266 0.14934628, 0.12505695 -0.033353046 0.15308063, 0.12510245 -0.033329144 0.15309912, 0.12515101 -0.033314392 0.15311901, 0.1252012 -0.033309504 0.15313952, 0.12511738 -0.033304736 0.15327874, 0.1250401 -0.033247307 0.15353835, 0.1250381 -0.033262655 0.15350369, 0.12500679 -0.033253536 0.15355302, 0.12495968 -0.033332661 0.15337901, 0.12499389 -0.033314541 0.15338008, 0.12495084 -0.033315942 0.15345362, 0.12502977 -0.033301041 0.15338258, 0.12506263 -0.033290401 0.1533975, 0.1249816 -0.033300504 0.15344968, 0.124952 -0.033294573 0.15351969, 0.12497517 -0.0332634 0.15356962, 0.12501399 -0.033288553 0.15344691, 0.12504354 -0.033275917 0.15346228, 0.12497944 -0.033281878 0.15351088, 0.12500843 -0.033272102 0.15350287, 0.12344536 -0.033320323 0.15711541, 0.12348485 -0.033312395 0.15711682, 0.12340742 -0.033333763 0.15711395, 0.1235204 -0.033309743 0.15718175, 0.12338158 -0.033329293 0.15730102, 0.12333615 -0.033353284 0.15728229, 0.12351024 -0.033309773 0.15724425, 0.12343022 -0.03331463 0.15732093, 0.12348031 -0.033309624 0.15734157, 0.12178288 -0.033353612 0.16107574, 0.1218282 -0.033329681 0.16109435, 0.12187681 -0.033314928 0.16111429, 0.12192699 -0.033309922 0.16113468, 0.12184319 -0.033305272 0.16127391, 0.12176597 -0.033247754 0.1615337, 0.12176381 -0.033263132 0.16149858, 0.1217328 -0.033254012 0.16154833, 0.12168562 -0.033333138 0.16137414, 0.12171972 -0.033315137 0.16137521, 0.12167667 -0.033316478 0.16144887, 0.1217556 -0.033301547 0.16137771, 0.12178835 -0.033290967 0.16139264, 0.1217075 -0.033301041 0.16144495, 0.12167799 -0.03329511 0.16151492, 0.12170112 -0.033263996 0.16156463, 0.12173988 -0.03328909 0.1614418, 0.12176932 -0.033276454 0.1614573, 0.12170535 -0.033282444 0.16150604, 0.12173426 -0.033272699 0.16149823, 0.12017116 -0.033320978 0.16511065, 0.12021077 -0.033312902 0.16511181, 0.12013328 -0.03333424 0.16510907, 0.12024617 -0.03331022 0.1651769, 0.12010737 -0.03332983 0.16529618, 0.12006199 -0.033353671 0.16527745, 0.12023601 -0.03331019 0.16523945, 0.12015602 -0.033315197 0.16531599, 0.12020624 -0.03331016 0.16533664, 0.11850858 -0.033354029 0.16907075, 0.118554 -0.033330068 0.16908935, 0.11860254 -0.033315375 0.16910923, 0.11865276 -0.033310398 0.1691297, 0.11856878 -0.03330563 0.169269, 0.11849166 -0.03324829 0.16952877, 0.11848953 -0.033263519 0.16949368, 0.11845839 -0.03325437 0.1695433, 0.11841141 -0.033333644 0.16936918, 0.11844534 -0.033315524 0.16937038, 0.11840236 -0.033316955 0.16944388, 0.11848128 -0.033301935 0.16937283, 0.11851418 -0.033291325 0.16938773, 0.11843328 -0.033301398 0.16943999, 0.11840355 -0.033295497 0.16950992, 0.11842683 -0.033264473 0.1695596, 0.1184655 -0.033289477 0.1694371, 0.11849505 -0.033276901 0.16945252, 0.11843109 -0.033282802 0.16950122, 0.11846007 -0.033273086 0.16949336, 0.11689693 -0.033321455 0.17310554, 0.11693631 -0.033313379 0.17310707, 0.11685893 -0.033334717 0.17310438, 0.11697197 -0.033310667 0.17317206, 0.11683309 -0.033330336 0.17329139, 0.11678779 -0.033354297 0.17327279, 0.11696173 -0.033310696 0.17323466, 0.11688173 -0.033315614 0.17331135, 0.11693192 -0.033310667 0.1733318, 0.1152342 -0.033354506 0.17706592, 0.11527978 -0.033330575 0.17708451, 0.1153283 -0.033315852 0.17710435, 0.11537844 -0.033310935 0.17712487, 0.11529453 -0.033306167 0.17726412, 0.1152174 -0.033248827 0.17752364, 0.11521526 -0.033264086 0.17748895, 0.1151841 -0.033254907 0.1775385, 0.11513706 -0.033334062 0.17736438, 0.11517113 -0.033316061 0.17736538, 0.11512811 -0.033317372 0.17743888, 0.11520714 -0.033302531 0.17736782, 0.1152399 -0.033291832 0.17738307, 0.11515886 -0.033301845 0.17743517, 0.11512934 -0.033296004 0.17750496, 0.11515243 -0.03326492 0.17755488, 0.1151913 -0.033289954 0.17743221, 0.11522089 -0.033277407 0.17744774, 0.11515683 -0.033283398 0.17749627, 0.11518569 -0.033273622 0.17748836, 0.11034839 -0.033322319 0.1890959, 0.11038795 -0.033314332 0.18909724, 0.11031048 -0.033335671 0.18909447, 0.1104234 -0.03331165 0.18916209, 0.11028458 -0.033331171 0.18928148, 0.1102394 -0.033355251 0.18926276, 0.11041318 -0.03331162 0.18922484, 0.11033303 -0.033316448 0.18930161, 0.11038353 -0.03331165 0.18932189, 0.10868585 -0.033355609 0.19305633, 0.10873117 -0.033331528 0.1930747, 0.10877982 -0.033316836 0.19309454, 0.10883014 -0.033311889 0.19311522, 0.10874622 -0.03330712 0.19325446, 0.10866906 -0.033249781 0.19351412, 0.10866706 -0.033265069 0.19347928, 0.10863562 -0.033255979 0.19352897, 0.10858862 -0.033335045 0.19335471, 0.1086227 -0.033317074 0.19335575, 0.10857965 -0.033318415 0.19342913, 0.10865866 -0.033303455 0.19335823, 0.10869144 -0.033292755 0.19337307, 0.10861048 -0.033302829 0.19342522, 0.10858077 -0.033296958 0.19349529, 0.10860412 -0.033265874 0.19354509, 0.10864277 -0.033290878 0.19342239, 0.10867241 -0.03327845 0.19343798, 0.10860841 -0.033284381 0.19348644, 0.10863724 -0.033274636 0.19347863, 0.10711737 -0.033294395 0.19690265, 0.1071137 -0.03331469 0.19709231, 0.10714279 -0.033287391 0.19688414, 0.10713242 -0.033306822 0.19698013, 0.10703616 -0.033336028 0.19708963, 0.10707414 -0.033322737 0.19709091, 0.10714917 -0.033312067 0.19715716, 0.10701041 -0.033331856 0.19727661, 0.10696507 -0.033355758 0.19725809, 0.10713907 -0.033312157 0.19721986, 0.10705899 -0.033317193 0.19729663, 0.10710931 -0.033312187 0.197317, 0.10541163 -0.033355847 0.20105124, 0.10545693 -0.033331886 0.20106971, 0.10550551 -0.033317223 0.2010898, 0.10555576 -0.033312336 0.20111024, 0.10547185 -0.033307537 0.20124957, 0.10539456 -0.033250317 0.2015091, 0.10539256 -0.033265486 0.20147431, 0.10536142 -0.033256397 0.201524, 0.10531424 -0.033335343 0.20134974, 0.10534827 -0.033317462 0.20135091, 0.10530542 -0.033318892 0.20142424, 0.10538431 -0.033303723 0.20135327, 0.10541706 -0.033293203 0.20136838, 0.10533617 -0.033303276 0.20142055, 0.10530649 -0.033297434 0.20149028, 0.10532974 -0.033266321 0.20154011, 0.10536848 -0.033291355 0.2014178, 0.10539812 -0.033278808 0.20143308, 0.10533407 -0.033284709 0.20148158, 0.10536294 -0.033275023 0.20147389, 0.10384321 -0.03329505 0.2048979, 0.10383947 -0.033315286 0.20508753, 0.10386856 -0.033288106 0.20487915, 0.10385834 -0.033307329 0.20497525, 0.10376193 -0.033336565 0.20508471, 0.10379998 -0.033323303 0.20508604, 0.10387504 -0.033312663 0.20515245, 0.10373618 -0.033332273 0.20527191, 0.1036907 -0.033356115 0.20525317, 0.10386471 -0.033312574 0.20521498, 0.10378478 -0.033317462 0.20529163, 0.10383494 -0.033312544 0.205312, 0.10213727 -0.033356413 0.20904644, 0.10218266 -0.033332363 0.20906496, 0.10223122 -0.0333177 0.20908473, 0.10228154 -0.033312693 0.20910548, 0.10219762 -0.033308044 0.20924468, 0.10212049 -0.033250704 0.20950423, 0.10211848 -0.033265963 0.20946975, 0.1020872 -0.033256754 0.20951912, 0.10204002 -0.033335939 0.20934482, 0.10207418 -0.033317938 0.20934612, 0.10203119 -0.033319399 0.20941941, 0.10211019 -0.033304289 0.20934851, 0.10214284 -0.033293679 0.20936356, 0.10206197 -0.033303842 0.20941573, 0.10203236 -0.033297822 0.20948556, 0.10205553 -0.033266798 0.20953543, 0.10209438 -0.033291832 0.20941292, 0.10212383 -0.033279315 0.20942803, 0.10205983 -0.033285245 0.20947672, 0.10208878 -0.033275381 0.20946868, 0.097294688 -0.033295885 0.2208882, 0.097290993 -0.03331615 0.22107762, 0.09732005 -0.033288941 0.22086914, 0.097309679 -0.033308253 0.22096558, 0.097213477 -0.033337459 0.22107501, 0.097251534 -0.033324227 0.22107646, 0.097326517 -0.033313379 0.2211425, 0.097187728 -0.033333287 0.2212619, 0.097142458 -0.033357158 0.22124344, 0.097316265 -0.033313408 0.22120517, 0.097236276 -0.033318415 0.22128195, 0.097286701 -0.033313528 0.22130257, 0.096552104 -0.033357367 0.2226847, 0.096597448 -0.033333346 0.22270329, 0.096645921 -0.033318684 0.22272322, 0.096696362 -0.033313707 0.2227439, 0.096639484 -0.033309087 0.22287934, 0.096503943 -0.033066735 0.22376402, 0.096563354 -0.03305693 0.22373861, 0.096453398 -0.033337578 0.22298853, 0.096498936 -0.033315167 0.22299568, 0.096547171 -0.033300802 0.22300474, 0.096558735 -0.033252493 0.22323488, 0.096596688 -0.03329514 0.22301523, 0.096461371 -0.033269599 0.2232323, 0.096509501 -0.033256814 0.22323257, 0.096420139 -0.033205435 0.22349879, 0.096465781 -0.03318806 0.22348686, 0.096513942 -0.033178315 0.2234779, 0.096625581 -0.033059552 0.22371954, 0.096563458 -0.033176556 0.22347182, 0.10052586 -0.03332378 0.21308108, 0.10056524 -0.033315644 0.21308243, 0.10048771 -0.033337012 0.21307991, 0.10060067 -0.033312902 0.21314748, 0.10046196 -0.033332601 0.2132668, 0.10041654 -0.033356562 0.21324821, 0.10059048 -0.033312961 0.21321017, 0.10051048 -0.033317938 0.21328674, 0.10056078 -0.033312932 0.21330725, 0.09886311 -0.03335683 0.21704164, 0.098908409 -0.03333275 0.21706024, 0.098957077 -0.033318117 0.21708001, 0.099007308 -0.03331311 0.21710072, 0.098923296 -0.033308312 0.21723984, 0.098846182 -0.033251151 0.2174996, 0.098844185 -0.03326641 0.21746458, 0.098812908 -0.033257231 0.21751432, 0.098765835 -0.033336446 0.21734002, 0.098799989 -0.033318266 0.2173413, 0.098757014 -0.033319756 0.21741465, 0.098835811 -0.033304736 0.21734348, 0.098868653 -0.033294067 0.21735859, 0.098787695 -0.03330414 0.21741089, 0.098758042 -0.033298209 0.2174806, 0.098781332 -0.033267304 0.21753052, 0.098820075 -0.033292308 0.21740815, 0.098849699 -0.033279642 0.2174232, 0.098785579 -0.033285633 0.21747176, 0.098814532 -0.033275828 0.21746409, 0.09076795 0.083891049 0.26888323, 0.095482245 0.085144684 0.26636609, 0.090710327 0.083802029 0.2689997, 0.095538706 0.085067049 0.26643196, 0.090658277 0.083700672 0.269099, 0.095588654 0.084972516 0.26647773, 0.090615228 0.083592519 0.26917481, 0.095629781 0.084866181 0.26650098, 0.090583235 0.083484069 0.26922327, 0.089486063 0.082471892 0.27173901, 0.089472458 0.082480237 0.27171767, 0.095108822 0.084019646 0.26861781, 0.089458779 0.0824873 0.27169597, 0.089578345 0.082554296 0.27142262, 0.095054239 0.084027007 0.26851985, 0.09500508 0.084009841 0.26842058, 0.089669228 0.08255212 0.27119994, 0.094964415 0.083969042 0.2683242, 0.089724258 0.082513556 0.2710551, 0.094933674 0.083906785 0.2682361, 0.089758009 0.08246018 0.27095795, 0.0949146 0.08382608 0.26816052, 0.089775726 0.082409099 0.27090085, 0.093655169 0.086992308 0.26268166, 0.098369315 0.088245973 0.26016462, 0.093597502 0.086903229 0.26279798, 0.098425835 0.088168278 0.26023048, 0.093545496 0.086801872 0.26289749, 0.098475859 0.088073775 0.26027626, 0.093502343 0.086693808 0.26297325, 0.098516867 0.0879675 0.2602993, 0.093470454 0.086585447 0.26302159, 0.092373058 0.085573211 0.26553735, 0.092359513 0.085581526 0.26551628, 0.097995818 0.087120935 0.26241618, 0.092345878 0.08558841 0.26549459, 0.092465445 0.085655466 0.26522109, 0.09794122 0.087128207 0.26231831, 0.097892374 0.087111071 0.26221874, 0.092556432 0.085653409 0.2649985, 0.097851425 0.087070361 0.26212251, 0.092611402 0.085614845 0.26485339, 0.097820818 0.087007985 0.2620343, 0.092645124 0.085561648 0.26475647, 0.097801894 0.08692719 0.26195875, 0.092662886 0.085510388 0.26469901, 0.096542239 0.090093419 0.25647998, 0.10125656 0.091347083 0.25396293, 0.096484542 0.090004489 0.25659633, 0.10131289 0.091269419 0.25402886, 0.096432537 0.089903042 0.25669593, 0.10136297 0.091175005 0.25407451, 0.096389472 0.089794978 0.25677171, 0.10140398 0.091068611 0.25409773, 0.096357509 0.089686558 0.25682002, 0.095260367 0.08867453 0.25933594, 0.095246762 0.088682696 0.25931472, 0.10088319 0.090222105 0.25621456, 0.095233172 0.08868973 0.2592929, 0.09535259 0.088756785 0.25901937, 0.10082857 0.090229526 0.25611681, 0.10077955 0.090212271 0.25601727, 0.095443547 0.08875455 0.25879699, 0.10073866 0.090171561 0.25592113, 0.095498621 0.088716134 0.25865197, 0.10070802 0.090109333 0.25583303, 0.095532268 0.088662848 0.258555, 0.10068919 0.09002839 0.25575709, 0.095550105 0.088611528 0.25849754, 0.099429339 0.093194678 0.25027847, 0.10414375 0.094448283 0.24776115, 0.099371642 0.093105748 0.25039494, 0.10420001 0.094370827 0.24782713, 0.099319667 0.093004301 0.25049412, 0.10425024 0.094276175 0.24787299, 0.099276513 0.092896298 0.25056994, 0.1042913 0.09416987 0.24789618, 0.099244729 0.092787877 0.2506184, 0.098147482 0.091775611 0.25313413, 0.098133713 0.091783956 0.25311297, 0.10377023 0.093323216 0.25001287, 0.098120213 0.0917909 0.25309139, 0.09823963 0.091857985 0.25281775, 0.10371563 0.093330607 0.24991514, 0.10366663 0.093313619 0.24981566, 0.098330498 0.091855809 0.25259531, 0.10362563 0.09327279 0.2497194, 0.098385826 0.091817155 0.25245017, 0.10359523 0.093210414 0.2496313, 0.098419443 0.091763958 0.25235334, 0.10357618 0.09312962 0.24955557, 0.098437279 0.091712669 0.25229597, 0.10231654 0.096295998 0.2440768, 0.10703088 0.097549453 0.24155958, 0.10225889 0.096207008 0.24419318, 0.10708722 0.097472087 0.24162568, 0.10220684 0.09610559 0.24429263, 0.10713726 0.097377464 0.24167146, 0.10216376 0.095997617 0.24436852, 0.10717832 0.097271219 0.24169448, 0.10213174 0.095889166 0.24441673, 0.10103452 0.094877049 0.24693249, 0.1010209 0.094885305 0.24691154, 0.10665737 0.096424714 0.24381128, 0.10100743 0.094892219 0.24688973, 0.10112688 0.094959334 0.24661614, 0.10660268 0.096432105 0.24371333, 0.10655393 0.096414849 0.24361403, 0.10121772 0.094957069 0.24639358, 0.10651292 0.096374199 0.24351783, 0.10127284 0.094918594 0.24624862, 0.10648228 0.096311852 0.24342962, 0.10130648 0.094865277 0.24615185, 0.10646333 0.096230999 0.2433538, 0.10132429 0.094814047 0.24609424, 0.11097792 0.1055999 0.22547212, 0.11569215 0.10685332 0.22295482, 0.11092022 0.10551082 0.22558844, 0.1157486 0.10677572 0.22302076, 0.11086832 0.10540943 0.22568792, 0.11579874 0.10668118 0.22306652, 0.11082509 0.10530137 0.22576356, 0.11583976 0.10657488 0.22308962, 0.1107931 0.10519306 0.22581208, 0.109696 0.10418083 0.22832771, 0.10968243 0.10418905 0.22830662, 0.11531879 0.10572834 0.22520629, 0.10966885 0.104196 0.2282849, 0.10978839 0.1042629 0.22801143, 0.11526419 0.10573594 0.22510871, 0.11521526 0.10571869 0.22500928, 0.10987912 0.10426088 0.22778885, 0.11517432 0.10567792 0.22491293, 0.10993418 0.10422234 0.22764386, 0.11514369 0.10561545 0.22482483, 0.10996805 0.10416897 0.2275469, 0.11512472 0.1055349 0.22474898, 0.10998586 0.10411783 0.22748938, 0.11258315 0.10728215 0.22212631, 0.11256938 0.10729049 0.22210509, 0.1182059 0.1088296 0.21900491, 0.11255591 0.10729741 0.22208315, 0.11267543 0.10736425 0.2218097, 0.1181512 0.10883699 0.2189073, 0.11810239 0.10881983 0.21880764, 0.11276625 0.10736232 0.22158752, 0.11806144 0.10877906 0.21871144, 0.11282139 0.10732363 0.22144216, 0.11803076 0.10871677 0.21862324, 0.11285508 0.10727032 0.22134514, 0.11801186 0.10863601 0.2185476, 0.11287282 0.10721914 0.22128795, 0.1067951 0.10108782 0.23450842, 0.10678163 0.10109474 0.23448637, 0.10680881 0.1010796 0.23452917, 0.11243168 0.10262699 0.23140815, 0.11237702 0.10263439 0.23131019, 0.10690112 0.10116179 0.23421293, 0.11232819 0.10261731 0.23121089, 0.10699204 0.10115971 0.23399046, 0.11228725 0.10257651 0.23111472, 0.10704711 0.10112108 0.2338455, 0.1122565 0.1025141 0.23102647, 0.10708085 0.10106768 0.23374835, 0.11223759 0.10243349 0.23095082, 0.10709853 0.10101663 0.23369113, 0.10809086 0.10249861 0.23167357, 0.11280504 0.10375212 0.22915637, 0.10803305 0.10240959 0.23179017, 0.11286141 0.10367458 0.22922243, 0.107981 0.10230823 0.23188928, 0.11291148 0.10358004 0.22926825, 0.10793792 0.10220008 0.23196512, 0.11295258 0.10347374 0.22929141, 0.10790592 0.10209177 0.2320136, 0.14555098 -0.022722289 0.14061275, 0.14558566 -0.022755608 0.14055957, 0.14558129 -0.022679046 0.14055848, 0.1458455 -0.022732988 0.14039545, 0.14592209 -0.022693709 0.14036451, 0.1458562 -0.022702023 0.14037992, 0.14604937 -0.022615865 0.14032489, 0.14605975 -0.022597 0.14030792, 0.14599679 -0.02263315 0.14031559, 0.14561479 -0.022629216 0.14049637, 0.14566526 -0.022643045 0.14044265, 0.14561121 -0.022608474 0.14047682, 0.14588691 -0.022780702 0.14039859, 0.14594853 -0.0227734 0.14039327, 0.14597666 -0.022713438 0.14037402, 0.14606188 -0.022608116 0.14032441, 0.14557599 -0.022575513 0.140504, 0.14560892 -0.02260308 0.14046493, 0.14591114 -0.0227281 0.14038098, 0.14556213 -0.022557601 0.14050016, 0.14608569 -0.022665605 0.14037856, 0.14612132 -0.022659108 0.14039518, 0.14614241 -0.022580996 0.14036214, 0.14610098 -0.022614613 0.14035547, 0.14575535 -0.022828385 0.14043881, 0.14573817 -0.022901073 0.14045298, 0.1458035 -0.0228367 0.14042401, 0.14582638 -0.022780731 0.14041078, 0.14588471 -0.022780761 0.14039883, 0.1457714 -0.022774085 0.1404281, 0.14590873 -0.022728309 0.1403816, 0.14575259 -0.022827759 0.14043987, 0.14576818 -0.022773609 0.14042941, 0.1457928 -0.022700176 0.14040062, 0.14586116 -0.022678539 0.14035955, 0.14605583 -0.02264367 0.14035252, 0.14610602 -0.022575244 0.1403245, 0.14579621 -0.022679016 0.14038144, 0.14556529 -0.022563323 0.14051309, 0.1461031 -0.022562906 0.14030686, 0.14614435 -0.02252911 0.14031765, 0.14614213 -0.022523895 0.14030893, 0.14604317 -0.022650436 0.14035231, 0.1457891 -0.022699818 0.14040205, 0.14579226 -0.022678539 0.14038292, 0.14566951 -0.022741988 0.1404798, 0.14571333 -0.022759482 0.14045395, 0.14572099 -0.022714123 0.14044242, 0.14599822 -0.022642627 0.1403299, 0.14592966 -0.022658482 0.14032863, 0.14567263 -0.022694692 0.14046958, 0.14591269 -0.022842839 0.14040995, 0.14582314 -0.022920415 0.14043197, 0.14591219 -0.022935137 0.14042976, 0.14595814 -0.022840485 0.14041206, 0.14599748 -0.022762343 0.14039436, 0.14604022 -0.022689506 0.14037368, 0.14561714 -0.022659585 0.14050969, 0.14566652 -0.022662833 0.14046109, 0.1457264 -0.022666678 0.14041063, 0.14579163 -0.022672668 0.14037198, 0.14572512 -0.022661105 0.14039975, 0.14566584 -0.022691235 0.14047405, 0.14605503 -0.022742704 0.14040208, 0.14606538 -0.022803858 0.14042912, 0.14566341 -0.022738978 0.14048384, 0.1457852 -0.022728816 0.14041466, 0.14602751 -0.022695109 0.14037313, 0.14558142 -0.022597834 0.140525, 0.14557125 -0.022586033 0.14053503, 0.14578143 -0.022728398 0.14041589, 0.14599179 -0.022673562 0.14035487, 0.14593054 -0.02266638 0.14034167, 0.14570464 -0.022814855 0.14046171, 0.14566107 -0.022879109 0.14049265, 0.14592813 -0.022667065 0.14034218, 0.14586048 -0.022671655 0.14034772, 0.1457251 -0.022686556 0.14042918, 0.14558554 -0.022630468 0.14053889, 0.14601 -0.022758767 0.14039543, 0.14567277 -0.02264674 0.14043836, 0.14566378 -0.02263774 0.14043134, 0.14557604 -0.02261968 0.14054918, 0.14585719 -0.022841945 0.14041363, 0.14561917 -0.022712156 0.14051881, 0.1458552 -0.022841796 0.14041391, 0.14552377 -0.022496536 0.1405583, 0.14551704 -0.022484615 0.14054573, 0.14549856 -0.022409156 0.14060736, 0.14550419 -0.022421822 0.1406233, 0.14592443 -0.022693172 0.14036423, 0.14566599 -0.022800818 0.14048511, 0.14601322 -0.02283369 0.14042076, 0.14600115 -0.022943214 0.14044726, 0.14549255 -0.022400752 0.14058866, 0.14566064 -0.022798702 0.14048912, 0.14553212 -0.022522524 0.14058381, 0.14550899 -0.022438124 0.14063734, 0.14551307 -0.022457168 0.14064881, 0.14567392 -0.022666588 0.1404568, 0.14559008 -0.022688016 0.14054814, 0.14553906 -0.022561416 0.14060083, 0.14551756 -0.022485569 0.14066057, 0.14552389 -0.022568241 0.14067787, 0.14562093 -0.022778943 0.14052147, 0.14559539 -0.022855505 0.14054891, 0.14596964 -0.022839412 0.14041331, 0.14559411 -0.022761717 0.14054942, 0.14554624 -0.022631124 0.14061236, 0.14552511 -0.022679135 0.14068159, 0.14614622 -0.0225503 0.14034116, 0.14614572 -0.022535309 0.14032593, 0.14555158 -0.022834405 0.14060667, 0.14551954 -0.022812083 0.14067197, 0.14544611 -0.023302928 0.14071691, 0.14549151 -0.023307875 0.14063416, 0.14555505 -0.023314938 0.14056449, 0.14563303 -0.02332373 0.14051175, 0.14572112 -0.023333684 0.14047909, 0.14581434 -0.023344174 0.14046741, 0.14587204 -0.022681907 0.14031112, 0.14593016 -0.022665039 0.140284, 0.14586411 -0.022690549 0.14029795, 0.14596204 -0.022645429 0.14031291, 0.14600669 -0.022621647 0.14024168, 0.1460522 -0.022593126 0.14029095, 0.14580636 -0.022688344 0.14033818, 0.14580156 -0.022695705 0.14032784, 0.14574271 -0.022691295 0.14035036, 0.14589393 -0.022665992 0.14033164, 0.14598761 -0.022640482 0.14021915, 0.14607248 -0.022555724 0.1401972, 0.14604397 -0.022588477 0.14016744, 0.14574625 -0.022683367 0.14036158, 0.14568852 -0.022679165 0.14036733, 0.14581832 -0.02267383 0.14035694, 0.14569212 -0.022669896 0.14038125, 0.14563535 -0.022659853 0.14037997, 0.1457503 -0.022667572 0.14038339, 0.14563958 -0.022647992 0.14039886, 0.14558418 -0.022633836 0.14038828, 0.14613737 -0.022518262 0.1402941, 0.14613128 -0.022515938 0.14028002, 0.14612402 -0.022516355 0.14026597, 0.14611612 -0.022519484 0.14025241, 0.14569132 -0.022650614 0.14041007, 0.14563666 -0.022623375 0.14043832, 0.14554277 -0.022579744 0.14042436, 0.14553644 -0.022601351 0.14039186, 0.14549257 -0.022563383 0.14039031, 0.14554693 -0.022541687 0.14049402, 0.14545584 -0.022429124 0.14046396, 0.14546202 -0.02253063 0.14038664, 0.14543492 -0.022495434 0.14037956, 0.14546947 -0.022404864 0.14051294, 0.14547953 -0.022397175 0.14054702, 0.14548592 -0.022396937 0.14056814, 0.14610414 -0.022526696 0.14023519, 0.14591785 -0.022676393 0.140268, 0.090811878 0.0044604093 0.24788521, 0.10466847 0.0044604391 0.24788533, 0.099699676 -0.010051742 0.23949122, 0.099981487 -0.010144249 0.23943782, 0.10022955 -0.010292545 0.23935233, 0.10042922 -0.010487661 0.2392392, 0.10056949 -0.010718748 0.23910546, 0.10064146 -0.010972068 0.23895897, 0.094716787 -0.033579752 0.22588257, 0.10941762 -0.033579841 0.22588266, 0.10064165 -0.011232957 0.23880817, 0.099699691 -0.012153044 0.23827589, 0.099981606 -0.012060508 0.23832956, 0.10022956 -0.01191245 0.23841523, 0.10042943 -0.011717126 0.23852806, 0.10056943 -0.011486158 0.23866163, 0.090182573 0.0046531707 0.24799694, 0.090023994 0.0047928542 0.24807768, 0.090373531 0.0045479089 0.24793591, 0.089905605 0.0049601346 0.24817447, 0.09058702 0.0044824928 0.2478981, 0.090187028 0.0060018748 0.2487769, 0.08437936 0.051137462 0.27488372, 0.090028599 0.0058641583 0.24869741, 0.084220752 0.051277176 0.27496433, 0.089909613 0.0056993514 0.24860206, 0.090376884 0.0061054677 0.24883673, 0.084570244 0.051032081 0.2748228, 0.084102303 0.051444456 0.27506125, 0.089836121 0.0055157691 0.24849577, 0.090588734 0.0061698109 0.24887405, 0.084783867 0.050966695 0.27478507, 0.090811908 0.0061916262 0.24888664, 0.085008651 0.050944641 0.27477229, 0.10445246 0.0061916262 0.24888669, 0.09886542 0.050944552 0.27477205, 0.094144374 0.083408549 0.28257135, 0.094144359 0.081893787 0.28181404, 0.094504982 0.083469704 0.28244904, 0.094504982 0.081955031 0.28169158, 0.094822586 0.083567604 0.28225327, 0.094822556 0.082053021 0.28149587, 0.095078275 0.083696768 0.28199488, 0.09507829 0.082182214 0.28123754, 0.095257461 0.083849654 0.28168941, 0.095257565 0.082334921 0.28093201, 0.095349967 0.084017143 0.28135455, 0.095349818 0.08250244 0.28059712, 0.095349863 0.084189579 0.28100955, 0.095349818 0.082674935 0.28025201, 0.095257461 0.084357128 0.28067446, 0.09525758 0.082842335 0.279917, 0.095078245 0.084509864 0.28036916, 0.095078275 0.082995221 0.27961153, 0.094822586 0.084639058 0.28011096, 0.094822586 0.083124354 0.27935329, 0.094505116 0.084737048 0.27991506, 0.094504967 0.083222434 0.27915755, 0.094144523 0.084798202 0.27979267, 0.094144404 0.083283499 0.279035, 0.12537336 0.11543877 0.2147337, 0.12537341 0.1169536 0.21549131, 0.125734 0.1154999 0.21461129, 0.12573393 0.11701475 0.21536906, 0.12605144 0.11559801 0.21441554, 0.12605138 0.11711271 0.21517308, 0.12630726 0.11572714 0.2141573, 0.12630711 0.1172419 0.21491466, 0.12648652 0.11587988 0.21385176, 0.12648642 0.11739443 0.21460932, 0.12657882 0.11604746 0.21351692, 0.12657867 0.11756201 0.21427403, 0.12657882 0.11621995 0.21317185, 0.12657879 0.11773475 0.21392928, 0.12648644 0.11638744 0.21283694, 0.12648655 0.11790223 0.21359418, 0.12630722 0.11654027 0.21253148, 0.12630725 0.11805494 0.21328895, 0.12605144 0.11666937 0.21227325, 0.12605129 0.11818419 0.21303065, 0.12573399 0.11676724 0.21207704, 0.12573399 0.11828215 0.21283476, 0.12537326 0.11682852 0.21195497, 0.12537333 0.11834334 0.21271241, 0.095007554 0.077188864 0.27783382, 0.09731774 0.077104375 0.27778494, 0.096952692 0.076843396 0.2776342, 0.091167688 0.077002749 0.27772629, 0.10487825 -0.033063367 0.21406317, 0.091134071 0.077029571 0.27774179, 0.091666102 0.076772258 0.27759278, 0.091396242 0.076862171 0.27764499, 0.091275468 0.076927051 0.27768254, 0.096719101 0.076770142 0.27759168, 0.096583098 0.076749012 0.27757955, 0.11371693 -0.033063248 0.21406321, 0.10721402 -0.03256236 0.20849681, 0.093435645 0.079082951 0.27307296, 0.093271494 0.079119727 0.2730943, 0.093541116 0.079070553 0.27306592, 0.093647093 0.079066291 0.27306336, 0.098145381 0.079066262 0.27306342, 0.11638109 -0.03256233 0.20849676, 0.098415613 0.079094037 0.27307951, 0.098674074 0.079177991 0.27312788, 0.09901537 0.07942839 0.27327287, 0.10223041 0.080787495 0.27405918, 0.10019206 0.080787465 0.27405918, 0.098864689 0.079289719 0.27319264, 0.10369214 0.0052645355 0.25048947, 0.098105058 0.05001758 0.27637511, 0.09492363 0.077015802 0.29152966, 0.094976291 0.077089533 0.29142094, 0.094879985 0.076923534 0.29161084, 0.09484759 0.076825038 0.29166296, 0.094826818 0.076733693 0.29168892, 0.096784011 0.07698746 0.28697878, 0.096568719 0.076565579 0.28738922, 0.096375749 0.076051012 0.28771967, 0.096927777 0.07720457 0.28668725, 0.097070828 0.07737802 0.28638554, 0.096219435 0.075469092 0.28794214, 0.096110806 0.074855909 0.28803945, 0.096054927 0.074250564 0.28801072, 0.096049547 0.073687986 0.28786969, 0.096087858 0.07319279 0.28764066, 0.10727327 0.090298608 0.26500675, 0.10743876 0.088515148 0.26411498, 0.097888842 0.051748946 0.2773765, 0.098649263 0.052675799 0.27577364, 0.12601073 0.11042576 0.22475871, 0.10827145 0.089409634 0.262326, 0.10810612 0.091193184 0.26321787, 0.12617612 0.10864209 0.22386692, 0.13434055 0.11937349 0.20686588, 0.12700887 0.10953666 0.2220782, 0.12684354 0.11132015 0.22296998, 0.13448165 0.11756356 0.20602633, 0.15566379 -0.027598038 0.13646758, 0.15573257 -0.027474061 0.13646758, 0.15557145 -0.027705356 0.13646756, 0.15545958 -0.027792111 0.13646758, 0.14613537 -0.032684252 0.13646773, 0.15413766 -0.026491657 0.1364677, 0.15578929 -0.027198002 0.13646761, 0.15439047 -0.026206419 0.13646773, 0.15577501 -0.027338937 0.13646752, 0.15456749 -0.025868878 0.13646767, 0.1470889 -0.033008412 0.13646764, 0.14609909 -0.033008322 0.13646762, 0.15465884 -0.025498882 0.1364677, 0.14677596 -0.02877818 0.13646774, 0.15004079 -0.026491567 0.13646761, 0.14978819 -0.026206419 0.13646761, 0.14677121 -0.028338805 0.13646764, 0.15035461 -0.026708171 0.13646761, 0.1557893 -0.024308339 0.13646758, 0.1546586 -0.025117651 0.13646781, 0.15456741 -0.024747506 0.13646781, 0.15439038 -0.024410143 0.1364677, 0.14961113 -0.025868967 0.13646775, 0.14627479 -0.024361238 0.13646773, 0.15108924 -0.023727313 0.1364677, 0.15408923 -0.022608206 0.13646773, 0.14851262 -0.022608146 0.13646784, 0.15308921 -0.023727313 0.13646758, 0.15382399 -0.023908421 0.13646773, 0.15346752 -0.023773208 0.13646781, 0.15071093 -0.026843265 0.1364677, 0.15574659 -0.023929879 0.13646773, 0.14951985 -0.025498763 0.13646781, 0.15446748 -0.022650823 0.13646773, 0.15413766 -0.024124876 0.1364677, 0.15482683 -0.022776589 0.13646773, 0.15108936 -0.02688922 0.1364677, 0.14951985 -0.025117651 0.1364677, 0.14719583 -0.023232982 0.13646784, 0.15562086 -0.023570612 0.13646787, 0.15541837 -0.02324824 0.13646768, 0.15514916 -0.022979066 0.13646771, 0.14961104 -0.024747625 0.1364677, 0.14746431 -0.022970095 0.1364678, 0.14778389 -0.022772357 0.13646773, 0.14813915 -0.02264975 0.13646768, 0.14978819 -0.024410143 0.13646758, 0.15004097 -0.024124935 0.13646758, 0.1530893 -0.02688919 0.13646755, 0.15035452 -0.023908421 0.13646761, 0.15071096 -0.023773238 0.13646778, 0.15346758 -0.026843324 0.13646758, 0.15382397 -0.026708111 0.13646765, 0.12423092 -0.033311561 0.19004382, 0.12620392 -0.033311382 0.1849442, 0.1240965 -0.033311561 0.1898765, 0.12395498 -0.033311531 0.18976478, 0.13107213 -0.033309206 0.14966939, 0.13340794 -0.033308938 0.14496839, 0.12382984 -0.03331162 0.18970104, 0.12637655 -0.033311382 0.18492514, 0.12655146 -0.033311233 0.18486652, 0.12433669 -0.03331168 0.19027238, 0.12671836 -0.033311382 0.18476731, 0.12438652 -0.033311561 0.1905245, 0.12437631 -0.03331165 0.1908029, 0.12686639 -0.033311352 0.18463311, 0.13301937 -0.033308879 0.14209306, 0.11797512 -0.033310995 0.18164976, 0.11751923 -0.033311084 0.18169723, 0.13344078 -0.0333087 0.14186352, 0.12698747 -0.033311322 0.18447262, 0.12430024 -0.03331165 0.19107755, 0.1039398 -0.03331311 0.21692471, 0.10339642 -0.0333132 0.21703807, 0.10366616 -0.03331317 0.21695282, 0.13389063 -0.033308759 0.14172156, 0.12707683 -0.033311173 0.18429752, 0.12031089 -0.033310875 0.17694893, 0.11976755 -0.033310875 0.17706256, 0.12003744 -0.033310905 0.17697732, 0.14257517 -0.033308938 0.14496827, 0.14060211 -0.033309206 0.15006807, 0.14046764 -0.033309087 0.1499007, 0.14032626 -0.033309087 0.14978924, 0.10355128 -0.033313081 0.21404906, 0.140201 -0.033309117 0.14972538, 0.10397264 -0.033313021 0.21381961, 0.14274758 -0.03330873 0.14494959, 0.11297642 -0.033313528 0.2227439, 0.14070779 -0.033309087 0.1502966, 0.14292279 -0.033308938 0.14489079, 0.14075764 -0.033309206 0.15054885, 0.1430895 -0.033308819 0.14479178, 0.14074767 -0.033309326 0.15082695, 0.14323753 -0.033308849 0.14465752, 0.11310686 -0.03331317 0.2169247, 0.11327943 -0.033313021 0.21690579, 0.14335851 -0.033308849 0.14449714, 0.11345458 -0.033313051 0.21684676, 0.13434665 -0.033308759 0.14167416, 0.11362123 -0.033313051 0.21674788, 0.11376938 -0.03331314 0.21661362, 0.10487822 -0.033312961 0.21363035, 0.10442235 -0.033312991 0.21367759, 0.1138905 -0.033313081 0.21645321, 0.13671964 -0.033308372 0.13662665, 0.13610382 -0.033308461 0.13675547, 0.13640966 -0.033308402 0.13665879, 0.11992238 -0.033310696 0.17407367, 0.12034392 -0.033310637 0.17384402, 0.10721388 -0.033312604 0.20892963, 0.10667057 -0.033312753 0.2090431, 0.10694037 -0.033312693 0.20895778, 0.14717458 -0.033308581 0.13923801, 0.14344816 -0.033308789 0.14432161, 0.14067149 -0.033309355 0.1511019, 0.12947811 -0.033310845 0.17694889, 0.12750505 -0.033311114 0.18204872, 0.1273707 -0.033311114 0.18188141, 0.12722932 -0.033311233 0.18176953, 0.1271041 -0.033311084 0.18170589, 0.14394563 -0.033308789 0.14310691, 0.14402179 -0.033308849 0.142832, 0.14403193 -0.033308759 0.1425537, 0.14398205 -0.03330873 0.14230141, 0.14387642 -0.033308789 0.14207299, 0.143742 -0.03330864 0.14190561, 0.1436006 -0.03330867 0.14179413, 0.14347531 -0.03330867 0.14173035, 0.12965068 -0.033310726 0.17692995, 0.1459426 -0.033308312 0.13676764, 0.11371703 -0.033312961 0.21363041, 0.14600021 -0.033308312 0.13662665, 0.12982565 -0.033310756 0.17687127, 0.12761091 -0.033311173 0.18227695, 0.14717466 -0.033308461 0.13676755, 0.12974519 -0.033309206 0.15008824, 0.12766072 -0.033311084 0.18252923, 0.12999253 -0.033310816 0.17677219, 0.12689233 -0.033309743 0.15785381, 0.12734202 -0.033309713 0.15771174, 0.12647095 -0.033309832 0.15808338, 0.12361805 -0.033310249 0.16584899, 0.12406781 -0.03331019 0.16570705, 0.12319672 -0.033310279 0.16607848, 0.12079366 -0.033310756 0.17370197, 0.1276505 -0.033311084 0.18280767, 0.13014054 -0.033310816 0.17663798, 0.1170696 -0.033311084 0.1818393, 0.11664811 -0.033311203 0.18206893, 0.11379533 -0.03331168 0.18983434, 0.11424498 -0.033311591 0.18969236, 0.11337392 -0.03331171 0.190064, 0.11052103 -0.033312038 0.19782938, 0.11097081 -0.033312157 0.19768728, 0.11009966 -0.033312067 0.1980591, 0.10724694 -0.033312634 0.20582445, 0.10769652 -0.033312574 0.2056824, 0.10682558 -0.033312663 0.20605408, 0.12124947 -0.033310577 0.1736546, 0.12757446 -0.033311084 0.1830824, 0.13026157 -0.033310667 0.17647743, 0.13689965 -0.033309892 0.16031189, 0.13412297 -0.03331019 0.1670921, 0.13362551 -0.033310339 0.16830696, 0.13084877 -0.033310696 0.1750873, 0.13035117 -0.033310786 0.17630227, 0.12380262 -0.03331165 0.1922926, 0.12102602 -0.033312038 0.19907291, 0.12052839 -0.033312097 0.20028777, 0.1177517 -0.033312544 0.20706764, 0.11725423 -0.033312663 0.20828277, 0.13739714 -0.033309743 0.15909718, 0.14017393 -0.033309385 0.15231678, 0.13016653 -0.033309147 0.14985867, 0.13061631 -0.033309236 0.14971669, 0.1235853 -0.033310398 0.16895357, 0.12304185 -0.033310369 0.16906744, 0.12331158 -0.033310309 0.1689821, 0.11441484 -0.033312991 0.21403985, 0.11638117 -0.033312604 0.20892949, 0.11427931 -0.033312932 0.21386743, 0.11413392 -0.033312961 0.21375112, 0.11397767 -0.033313081 0.2136752, 0.11384508 -0.033312961 0.21364085, 0.11655384 -0.033312723 0.2089107, 0.11672896 -0.033312693 0.20885155, 0.11451848 -0.033313081 0.21427192, 0.11689559 -0.033312753 0.20875269, 0.1145649 -0.033313051 0.21452385, 0.11704366 -0.033312753 0.20861858, 0.11455229 -0.033313021 0.21479689, 0.10815257 -0.033312634 0.20563531, 0.11716472 -0.033312693 0.20845801, 0.11048825 -0.033312276 0.2009344, 0.10994492 -0.033312336 0.2010479, 0.11021464 -0.033312276 0.20096269, 0.13077928 -0.033310607 0.17405342, 0.13275236 -0.033310249 0.16895391, 0.13064508 -0.033310577 0.17388631, 0.13050354 -0.033310696 0.17377457, 0.13037826 -0.033310607 0.17371057, 0.13292499 -0.033310279 0.16893473, 0.13309988 -0.033310309 0.1688761, 0.13088514 -0.033310607 0.17428182, 0.13326676 -0.033310279 0.16877702, 0.13093497 -0.033310577 0.17453419, 0.13341473 -0.033310309 0.16864276, 0.13092484 -0.033310607 0.17481242, 0.12452367 -0.03331013 0.16565967, 0.13353595 -0.033310398 0.16848265, 0.1268594 -0.033309892 0.16095895, 0.12631606 -0.033309832 0.16107233, 0.12658593 -0.033309951 0.1609872, 0.11965536 -0.033312038 0.20093444, 0.11768232 -0.033312425 0.20603397, 0.11754809 -0.033312544 0.20586672, 0.11740656 -0.033312455 0.205755, 0.11728126 -0.033312425 0.20569137, 0.1198279 -0.033312097 0.20091535, 0.11778808 -0.033312455 0.20626253, 0.12000297 -0.033312038 0.20085672, 0.11783785 -0.033312634 0.20651457, 0.12016982 -0.033312187 0.20075765, 0.11782776 -0.033312425 0.20679322, 0.12031789 -0.033312157 0.2006235, 0.11142667 -0.033312216 0.19764008, 0.12043884 -0.033311978 0.20046298, 0.11376253 -0.033311829 0.19293916, 0.11321902 -0.033311829 0.19305283, 0.11348879 -0.033311769 0.19296755, 0.13602659 -0.033309802 0.16095869, 0.13405369 -0.03331019 0.1660583, 0.13391924 -0.0333101 0.16589107, 0.13377774 -0.0333101 0.16577937, 0.13365246 -0.033310041 0.16571578, 0.13619933 -0.033309832 0.16093986, 0.13415942 -0.03331019 0.16628675, 0.13637421 -0.033309802 0.16088097, 0.13654095 -0.033309802 0.16078211, 0.13420928 -0.03331019 0.16653897, 0.13419908 -0.033310011 0.16681744, 0.13668892 -0.033309832 0.16064768, 0.12779795 -0.033309594 0.15766449, 0.13681015 -0.033309832 0.16048734, 0.1301336 -0.033309475 0.15296359, 0.12959036 -0.033309475 0.1530772, 0.1298601 -0.033309475 0.152992, 0.12292954 -0.03331165 0.19293921, 0.12095664 -0.033312038 0.19803913, 0.12082228 -0.033312097 0.19787163, 0.12068078 -0.033312097 0.19775993, 0.12055552 -0.033312008 0.19769613, 0.12310219 -0.03331162 0.19292016, 0.12327717 -0.033311561 0.19286162, 0.12106226 -0.033311948 0.19826731, 0.12344405 -0.03331168 0.19276242, 0.12111236 -0.033312127 0.19851951, 0.12359193 -0.03331168 0.19262837, 0.12110212 -0.033312097 0.19879812, 0.11470103 -0.033311561 0.18964499, 0.12371308 -0.03331162 0.19246788, 0.11703679 -0.033311352 0.18494408, 0.11649333 -0.033311442 0.18505758, 0.11676322 -0.033311442 0.18497247, 0.13930079 -0.033309296 0.15296344, 0.13732783 -0.033309683 0.15806326, 0.13719356 -0.033309594 0.15789597, 0.1370519 -0.033309534 0.15778428, 0.13692679 -0.033309653 0.15772063, 0.13947348 -0.033309355 0.15294474, 0.13743365 -0.033309564 0.15829162, 0.1396485 -0.033309326 0.15288575, 0.13748343 -0.033309534 0.15854388, 0.13981521 -0.033309296 0.15278687, 0.1399633 -0.033309355 0.15265243, 0.13747327 -0.033309653 0.15882218, 0.14008433 -0.033309326 0.15249218, 0.13286464 -0.033308879 0.145082, 0.13313425 -0.033308908 0.14499678, 0.12903489 0.10922222 0.21704501, 0.12859626 0.10875104 0.21798721, 0.14536408 -0.024035797 0.14071696, 0.14533953 -0.024391368 0.14067924, 0.14649983 -0.028747275 0.1366545, 0.14595504 -0.024383768 0.13917837, 0.1455393 -0.024892971 0.14005467, 0.1454597 -0.024947479 0.14023423, 0.14543177 -0.024939463 0.14030406, 0.14548837 -0.024940506 0.14016598, 0.14551096 -0.024923876 0.14011514, 0.14537074 -0.024819955 0.14048615, 0.14535694 -0.024747446 0.14053988, 0.14539056 -0.024882153 0.14042079, 0.14541341 -0.024922773 0.14035365, 0.14534192 -0.024580553 0.14062178, 0.13056169 -0.035296068 0.13903566, 0.13039817 -0.035296008 0.13923578, 0.13049428 -0.035296127 0.13909121, 0.13043903 -0.035296097 0.13915892, 0.13632192 -0.03529574 0.1351676, 0.14664553 -0.035296038 0.14016761, 0.14794867 -0.03529577 0.13516761, 0.14794858 -0.035296008 0.14016764, 0.094387203 -0.035301134 0.22716819, 0.11058317 -0.035301134 0.22822526, 0.094330058 -0.035301223 0.22822529, 0.11122754 -0.034673229 0.22848918, 0.147275 -0.034668162 0.14046746, 0.14735624 -0.033942834 0.14046764, 0.097051129 0.076536164 0.29352868, 0.097068951 0.076280341 0.29341546, 0.097058997 0.076810285 0.29358447, 0.097092003 0.077090099 0.29358041, 0.097148657 0.077362522 0.29351664, 0.097226292 0.077614918 0.29339597, 0.097321481 0.077835575 0.29322395, 0.097405329 0.077979729 0.29305887, 0.097494811 0.078093961 0.29287162, 0.099955305 0.075603381 0.28618205, 0.10019124 0.076102123 0.28574246, 0.099782795 0.075072303 0.28645799, 0.10045862 0.076472983 0.28519094, 0.099667728 0.074551508 0.28659672, 0.099595875 0.074013248 0.28662464, 0.099570289 0.0734808 0.28654167, 0.099578872 0.073154315 0.28643107, 0.099606648 0.072845206 0.28627872, 0.13712302 0.12066133 0.20774926, 0.13755089 0.11631612 0.20551607, 0.11083935 -0.034024164 0.22961469, 0.11086753 -0.034189627 0.22950102, 0.11090747 -0.034335688 0.22936335, 0.11098674 -0.034508839 0.22912206, 0.11109836 -0.034631625 0.2288164, 0.11283194 -0.03309156 0.22500409, 0.11288753 -0.033404425 0.22478288, 0.11296855 -0.033654734 0.22451688, 0.14647366 -0.028375998 0.13676763, 0.14597706 -0.024398491 0.13676789, 0.14597706 -0.02439864 0.13906813, 0.14522372 -0.023161069 0.13983685, 0.13855647 -0.031326547 0.13511385, 0.1381955 -0.031901255 0.13478161, 0.13813852 -0.032076284 0.13468017, 0.13812165 -0.032191947 0.13461329, 0.13812678 -0.032291755 0.13455571, 0.14615709 -0.032858178 0.13636701, 0.14615001 -0.033054009 0.13633031, 0.14615794 -0.032996193 0.13632697, 0.14616115 -0.032941714 0.13633412, 0.14616042 -0.032897189 0.13634817, 0.14611822 -0.033172891 0.13637583, 0.14608866 -0.033074126 0.13647513, 0.14613761 -0.033112183 0.13634515, 0.14607158 -0.033140704 0.13649847, 0.14609197 -0.033229783 0.1364245, 0.14604828 -0.033202246 0.13653864, 0.14606328 -0.033271864 0.13648307, 0.14603159 -0.033299074 0.13655259, 0.14602007 -0.033252433 0.1365934, 0.14599003 -0.033287242 0.1366573, 0.1459654 -0.033303306 0.13671295, 0.080070734 0.075935051 0.29136592, 0.084345609 0.051531002 0.27725047, 0.084185675 0.051374719 0.27716005, 0.090811834 0.0052644759 0.25048947, 0.084544063 0.051649526 0.27731904, 0.090811819 0.0035333484 0.24948819, 0.093742669 -0.03358005 0.22802158, 0.090572491 0.0035583824 0.24950266, 0.090347201 0.0036323816 0.24954547, 0.090148777 0.0037509352 0.24961402, 0.084073618 0.051190063 0.27705339, 0.089988858 0.003907159 0.24970444, 0.089876786 0.0040919334 0.24981128, 0.089819178 0.0042944998 0.24992836, 0.10390803 0.0035333484 0.24948822, 0.084769443 0.051723555 0.27736175, 0.10854158 -0.033579871 0.22802158, 0.084015995 0.050778791 0.27681547, 0.08401604 0.050987437 0.27693605, 0.085008696 0.051748767 0.27737653, 0.084543943 0.050116673 0.27643239, 0.090148672 0.005046919 0.25036377, 0.084345609 0.050235197 0.27650088, 0.089988813 0.0048906356 0.25027335, 0.08418563 0.05039148 0.27659136, 0.084769383 0.050042704 0.27638954, 0.090347156 0.0051652938 0.25043213, 0.089876831 0.004705891 0.25016636, 0.084073618 0.050576165 0.27669799, 0.085008696 0.050017551 0.27637485, 0.090572461 0.0052393228 0.25047505, 0.089819208 0.0045032054 0.25004911, 0.097229525 -0.015142843 0.24103902, 0.096709847 -0.014627054 0.24133718, 0.094208613 -0.034302637 0.2299567, 0.097877741 -0.015534773 0.24081212, 0.096349314 -0.014017984 0.24168934, 0.098616019 -0.01577948 0.24067059, 0.096169546 -0.013351694 0.24207486, 0.11019519 -0.034302488 0.22995664, 0.086443439 0.064554855 0.2871365, 0.080438003 0.076001987 0.2937575, 0.088938519 0.067597315 0.2888962, 0.088202417 0.067365333 0.28876203, 0.087551758 0.066987351 0.28854349, 0.087024614 0.066485658 0.28825331, 0.08665137 0.065889373 0.28790849, 0.086453766 0.065233007 0.28752884, 0.092905939 0.065159395 0.28748631, 0.096424624 0.076002106 0.29375747, 0.092728525 0.065819934 0.28786844, 0.092373461 0.066424683 0.28821808, 0.09186165 0.066938326 0.28851509, 0.091222808 0.067330793 0.28874201, 0.090493962 0.067579672 0.28888619, 0.089717433 0.06767033 0.28893858, 0.12822758 0.11822455 0.21406768, 0.13647875 0.12135963 0.20779863, 0.12806456 0.11856733 0.21338241, 0.1277229 0.11888252 0.21275184, 0.091577336 0.083474234 0.28355804, 0.091057494 0.083744183 0.28301835, 0.080492929 0.07879214 0.29292089, 0.096850425 0.078792229 0.29292092, 0.0922281 0.083268955 0.2839686, 0.13616307 0.12154411 0.20742972, 0.12722234 0.1191522 0.21221255, 0.1265922 0.1193604 0.21179642, 0.12586883 0.1194952 0.21152698, 0.12016258 0.12064235 0.2092326, 0.09070015 0.084062532 0.28238177, 0.092971176 0.083140597 0.28422511, 0.13623181 0.12154435 0.20742907, 0.090526626 0.084410265 0.28168646, 0.13650039 0.12142394 0.20766975, 0.13648608 0.12145384 0.20761015, 0.13649921 0.12139334 0.20773102, 0.13649157 0.12137614 0.20776524, 0.13629869 0.12153791 0.2074423, 0.090547368 0.084766313 0.28097445, 0.13645691 0.12148149 0.20755474, 0.13636072 0.12152456 0.20746852, 0.1364143 0.12150557 0.20750678, 0.11912496 0.12028901 0.20993926, 0.090761125 0.085109279 0.28028828, 0.12799081 0.11753674 0.21544273, 0.12199017 0.11865436 0.21320808, 0.12237617 0.11895941 0.21259843, 0.12291448 0.11921392 0.21208884, 0.11925563 0.12039618 0.20972505, 0.11943336 0.12048869 0.20954005, 0.11965032 0.1205626 0.20939223, 0.11989701 0.12061451 0.20928828, 0.12357309 0.11940371 0.21170951, 0.12431417 0.11951731 0.21148229, 0.12509464 0.11954854 0.21142018, 0.12820251 0.11787422 0.21476813, 0.11909039 0.11868946 0.20823352, 0.11866328 0.11841311 0.20878607, 0.11884417 0.11856131 0.20848989, 0.12010014 0.11890231 0.20780784, 0.11973238 0.11886378 0.20788501, 0.11939085 0.11879174 0.20802882, 0.11293049 0.11120759 0.2231949, 0.11277053 0.111127 0.22335644, 0.11312883 0.11126883 0.22307238, 0.11265872 0.11103125 0.22354718, 0.11335434 0.11130713 0.22299606, 0.11359361 0.11132012 0.22296983, 0.13621384 0.11981021 0.20599215, 0.13637632 0.11981215 0.20598871, 0.13710195 0.11952473 0.2065631, 0.13629362 0.11981307 0.20598669, 0.13704354 0.11960517 0.20640217, 0.13694933 0.11967455 0.20626391, 0.13683242 0.1197287 0.20615517, 0.13669156 0.11977126 0.20607023, 0.13653581 0.11979936 0.20601419, 0.1126008 0.11081888 0.22397216, 0.094193235 0.091080591 0.26344275, 0.11260083 0.11092685 0.22375637, 0.094033375 0.090999827 0.26360416, 0.094391361 0.091141924 0.26332033, 0.1126585 0.11071421 0.22418149, 0.094616935 0.091180101 0.26324385, 0.11277059 0.11061881 0.22437231, 0.094856158 0.091193125 0.26321781, 0.11312887 0.11047684 0.22465612, 0.11293048 0.11053814 0.22453389, 0.11359352 0.11042567 0.22475871, 0.11335424 0.11043857 0.22473286, 0.094193131 0.090411112 0.26478171, 0.094033286 0.090491846 0.26462039, 0.093921229 0.090587273 0.26442948, 0.09439154 0.090349898 0.26490441, 0.093863532 0.090691939 0.26422003, 0.094616979 0.090311453 0.26498085, 0.094856277 0.090298489 0.26500696, 0.080192924 0.077089533 0.29142112, 0.093863562 0.090799794 0.26400453, 0.093921199 0.0909044 0.26379514, 0.13716358 0.11953734 0.20656048, 0.13713329 0.11952879 0.20656058, 0.13720387 0.11955644 0.2065637, 0.13723892 0.11958291 0.20657085, 0.13726714 0.1196156 0.20658208, 0.13729854 0.1197338 0.2066313, 0.13729769 0.11969279 0.20661305, 0.13728698 0.11965273 0.20659614, 0.089973852 0.067854717 0.28455308, 0.090255544 0.0677623 0.28449953, 0.090503618 0.067613944 0.28441381, 0.090703413 0.067418739 0.2843008, 0.090843365 0.067187831 0.28416717, 0.090915531 0.066934571 0.28402078, 0.090915516 0.066673681 0.28386998, 0.090843379 0.066420481 0.28372359, 0.08500874 0.052675799 0.27577367, 0.08478561 0.052654013 0.27576089, 0.084573895 0.05258964 0.2757237, 0.084383845 0.052486077 0.27566361, 0.089973658 0.065753594 0.28333795, 0.084106594 0.052183613 0.27548873, 0.084033117 0.051999941 0.27538288, 0.084225565 0.05234836 0.27558422, 0.090255424 0.065846041 0.28339115, 0.090503573 0.065994188 0.28347689, 0.090703443 0.066189393 0.28359002, 0.082304761 0.07737793 0.28638554, 0.094060659 0.080262378 0.28061819, 0.094342396 0.080310151 0.28052244, 0.0945905 0.080386624 0.28036949, 0.09479022 0.080487564 0.28016794, 0.09493041 0.080606833 0.2799291, 0.095002353 0.080737665 0.27966744, 0.095002383 0.080872521 0.27939761, 0.094193175 0.088627592 0.26388994, 0.094033316 0.088708118 0.26372853, 0.094391644 0.088566229 0.26401222, 0.093921244 0.088803813 0.26353765, 0.094616935 0.088528082 0.26408893, 0.093863532 0.088908419 0.26332819, 0.094856292 0.088515088 0.26411492, 0.094060764 0.081347778 0.27844691, 0.094342411 0.081300095 0.27854258, 0.0945905 0.081223533 0.27869576, 0.093863532 0.089016184 0.26311243, 0.093921095 0.089120969 0.26290333, 0.09479019 0.081122681 0.27889764, 0.094930261 0.081003353 0.27913624, 0.094856188 0.089409575 0.262326, 0.11277065 0.10883521 0.22348052, 0.09461692 0.089396581 0.26235205, 0.1129306 0.10875459 0.22364189, 0.11312887 0.10869323 0.22376436, 0.1126586 0.1089306 0.22328952, 0.09439154 0.089358434 0.26242858, 0.11335422 0.10865499 0.22384088, 0.11260091 0.10903533 0.22308011, 0.094193146 0.089296952 0.26255101, 0.1135935 0.10864209 0.22386676, 0.11260103 0.10914309 0.2228647, 0.094033286 0.089216366 0.2627123, 0.11359358 0.10953663 0.22207817, 0.1127706 0.10934351 0.22246426, 0.11885485 0.11663909 0.20787515, 0.11265862 0.10924788 0.22265537, 0.11293052 0.1094241 0.22230285, 0.11312895 0.10948537 0.22218043, 0.11335428 0.10952355 0.222104, 0.12528968 0.11380728 0.21353783, 0.1255714 0.11385508 0.21344234, 0.12581934 0.11393164 0.21328928, 0.11933431 0.11693676 0.20727994, 0.11905202 0.11679752 0.20755793, 0.12601922 0.11403249 0.21308751, 0.1196842 0.11704375 0.20706607, 0.12615933 0.11415179 0.2128491, 0.1199877 0.11709984 0.20695366, 0.12029885 0.11712994 0.2068935, 0.12528954 0.11489294 0.21136697, 0.12557125 0.11484526 0.21146245, 0.12581936 0.11476858 0.2116157, 0.12601912 0.11466764 0.21181715, 0.12615922 0.1145484 0.21205589, 0.12623134 0.11441751 0.21231763, 0.12623131 0.11428277 0.21258713, 0.13642369 0.11803849 0.20507668, 0.1366211 0.11803885 0.20507608, 0.13730586 0.11776479 0.20562376, 0.13728179 0.11780195 0.20555027, 0.13680576 0.1180187 0.20511629, 0.13720945 0.11787002 0.20541371, 0.13696402 0.117983 0.20518766, 0.13710199 0.11793204 0.20528962, 0.15678917 -0.023808196 0.13446772, 0.15678938 -0.02775304 0.13446765, 0.1546586 -0.025498763 0.13446772, 0.15507878 -0.021663472 0.13446787, 0.15382405 -0.023908421 0.13446793, 0.15458921 -0.021608308 0.134468, 0.15346764 -0.023773268 0.13446772, 0.15673254 -0.028029218 0.13446774, 0.15645954 -0.028347269 0.13446772, 0.15677498 -0.027894065 0.13446762, 0.15346761 -0.026843116 0.13446769, 0.15308903 -0.02688916 0.13446772, 0.1538239 -0.026708022 0.13446772, 0.15413766 -0.026491538 0.1344676, 0.14972872 -0.032541439 0.13446753, 0.15596093 -0.022088155 0.13446787, 0.15413766 -0.024124876 0.13446784, 0.15554385 -0.021826103 0.13446796, 0.15666386 -0.028153077 0.13446772, 0.1565716 -0.028260484 0.13446772, 0.15630935 -0.022436693 0.13446784, 0.15439041 -0.024410233 0.13446769, 0.15657133 -0.022853628 0.13446791, 0.13733514 -0.032548323 0.13446771, 0.13753511 -0.032524362 0.13446771, 0.13714053 -0.032620355 0.13446771, 0.13695583 -0.032740131 0.1344676, 0.13682003 -0.032865778 0.13446771, 0.13669439 -0.033016935 0.13446771, 0.13831852 -0.032524362 0.1344675, 0.13649692 -0.034595743 0.13446753, 0.13649699 -0.033284917 0.1344676, 0.15673403 -0.023318663 0.13446784, 0.14827539 -0.021608278 0.13446788, 0.14978822 -0.024410293 0.13446769, 0.14779212 -0.021662042 0.13446777, 0.14733239 -0.02182065 0.13446788, 0.14691879 -0.022076413 0.134468, 0.14657135 -0.022416905 0.13446794, 0.15004086 -0.024124935 0.13446774, 0.15035458 -0.023908421 0.13446769, 0.14961101 -0.024747714 0.13446775, 0.15071084 -0.023773238 0.13446775, 0.14951973 -0.025117651 0.13446772, 0.15465872 -0.025117651 0.13446772, 0.15456741 -0.024747625 0.13446772, 0.15108933 -0.023727462 0.13446763, 0.14951985 -0.025498882 0.13446772, 0.15004088 -0.026491627 0.13446775, 0.14932317 -0.032862946 0.13446765, 0.14978813 -0.026206329 0.13446772, 0.14961104 -0.025868908 0.13446772, 0.14899951 -0.033266857 0.13446765, 0.15035455 -0.026708141 0.13446766, 0.15071099 -0.026843324 0.13446766, 0.15108939 -0.02688925 0.13446769, 0.14877456 -0.033732966 0.13446753, 0.14865951 -0.034237429 0.13446751, 0.1530893 -0.023727283 0.13446769, 0.14864427 -0.034373716 0.13446753, 0.14858097 -0.034595653 0.13446753, 0.14861828 -0.03449972 0.13446741, 0.14863415 -0.034437194 0.13446754, 0.15439026 -0.02620627 0.13446772, 0.15456741 -0.025868848 0.1344679, 0.12027398 0.11703984 0.20662652, 0.12037839 0.11597805 0.20608102, 0.12007494 0.12032704 0.20829813, 0.13634224 -0.033170864 0.13453715, 0.13630229 -0.033217177 0.13454106, 0.13653968 -0.032902971 0.13453735, 0.13047597 -0.033217445 0.13845372, 0.11277901 0.10853885 0.2204463, 0.10393971 -0.032562867 0.21649183, 0.099343315 0.077686265 0.28026056, 0.09017618 0.077686235 0.28026044, 0.11310685 -0.032562748 0.21649189, 0.11351974 -0.032761469 0.21608932, 0.11401734 -0.032761499 0.21487455, 0.10016359 0.078209564 0.2790609, 0.09972474 0.07773836 0.28000337, 0.10815245 -0.03306289 0.20606799, 0.10261206 0.080839559 0.27380195, 0.11679398 -0.032761052 0.20809448, 0.11729153 -0.032760933 0.20687956, 0.11142682 -0.033062503 0.19807278, 0.1104881 -0.032561913 0.20050153, 0.10511757 0.083888903 0.26785743, 0.09595035 0.083888784 0.26785755, 0.11965533 -0.032561854 0.20050161, 0.10549909 0.083940938 0.26760021, 0.12006824 -0.032760665 0.2000993, 0.12056577 -0.032760546 0.19888417, 0.11470099 -0.033061966 0.19007768, 0.11376242 -0.032561317 0.19250643, 0.10800469 0.086989984 0.26165605, 0.098837465 0.086990133 0.26165584, 0.12292962 -0.032561377 0.19250631, 0.10838622 0.087042198 0.26139843, 0.1233425 -0.032760218 0.19210404, 0.12384003 -0.032760069 0.19088919, 0.11797521 -0.0330614 0.18208282, 0.11703682 -0.032561019 0.18451138, 0.11089182 0.090091333 0.2554543, 0.10172476 0.090091214 0.2554543, 0.12620388 -0.032561019 0.18451126, 0.11127332 0.090143338 0.25519702, 0.12661685 -0.032759622 0.18410903, 0.12711431 -0.032759622 0.18289395, 0.12124941 -0.033060893 0.17408757, 0.12031108 -0.032560512 0.1765161, 0.11377898 0.093192622 0.24925268, 0.1046118 0.093192473 0.24925269, 0.12947823 -0.032560512 0.17651616, 0.11416054 0.093244627 0.24899539, 0.12989093 -0.032759234 0.17611359, 0.13038851 -0.032759145 0.17489885, 0.12452362 -0.033060476 0.16609253, 0.1235851 -0.032559946 0.16852094, 0.11666611 0.096293852 0.24305104, 0.1074989 0.096293822 0.24305101, 0.13275228 -0.032560006 0.16852105, 0.11704761 0.096346006 0.24279378, 0.13316524 -0.032758847 0.16811837, 0.13366279 -0.032758728 0.16690378, 0.12779793 -0.03305997 0.15809745, 0.1268594 -0.032559529 0.1605261, 0.11955325 0.099394992 0.23684935, 0.11038601 0.099395081 0.23684934, 0.13602659 -0.032559529 0.16052584, 0.11993478 0.099447176 0.23659192, 0.1364395 -0.03275834 0.16012348, 0.13693699 -0.032758132 0.15890853, 0.13107216 -0.033059523 0.15010221, 0.13013372 -0.032559052 0.15253086, 0.12244038 0.10249634 0.2306477, 0.1132732 0.10249646 0.23064798, 0.13930084 -0.032559022 0.15253083, 0.1228219 0.10254852 0.23039047, 0.13971353 -0.032757685 0.15212841, 0.14021128 -0.032757744 0.15091369, 0.13434638 -0.033059165 0.14210704, 0.13340794 -0.032558635 0.14453566, 0.12532741 0.10559763 0.22444625, 0.11616038 0.10559751 0.22444598, 0.14257511 -0.032558516 0.1445356, 0.125709 0.10564961 0.22418889, 0.14298801 -0.032757267 0.14413311, 0.14348541 -0.032757267 0.14291836, 0.14585629 -0.032614514 0.136508, 0.13671963 -0.032858208 0.13636708, 0.12821452 0.10869904 0.21824461, 0.11904749 0.10869889 0.21824473, 0.1184787 0.11978324 0.2093855, 0.080008343 0.077302769 0.29144162, 0.079846814 0.078286394 0.29236704, 0.11847858 0.11862637 0.20880689, 0.079977974 0.077266797 0.29150528, 0.079948053 0.07722427 0.29156476, 0.079901338 0.077144191 0.2916497, 0.079756215 0.078172609 0.2925536, 0.079619125 0.077607825 0.29310292, 0.079871878 0.075816378 0.29152852, 0.079638064 0.077332482 0.29322749, 0.079662666 0.07703577 0.29328519, 0.079691723 0.076733693 0.29327255, 0.079716459 0.076503322 0.29321378, 0.079741985 0.076287284 0.29311413, 0.09351255 -0.03401725 0.22931311, 0.093533069 -0.033611462 0.22823475, 0.093544468 -0.034255639 0.22913617, 0.093574628 -0.034447566 0.22890967, 0.09356083 -0.033735916 0.22793588, 0.093557134 -0.03371267 0.22796233, 0.09355177 -0.033682868 0.22801141, 0.093542561 -0.033642545 0.22811192, 0.093601599 -0.034583017 0.22864549, 0.0936196 -0.034645483 0.22842059, 0.093634158 -0.034666404 0.22818768, 0.09366788 -0.034666345 0.22756407, 0.146339 -0.022227213 0.14016761, 0.14590336 -0.022760853 0.13989857, 0.14572613 -0.022977963 0.13966334, 0.14633907 -0.022227153 0.13476788, 0.13886626 -0.031379268 0.1347677, 0.14553355 -0.023213759 0.13949043, 0.15458935 -0.021308228 0.13646768, 0.14827557 -0.021308258 0.13476788, 0.14827538 -0.021308318 0.14016785, 0.15458918 -0.021308228 0.1347679, 0.15458916 -0.021308348 0.14016774, 0.15708932 -0.02775313 0.13476777, 0.15708922 -0.023808256 0.13476789, 0.15708937 -0.023808375 0.1364677, 0.15708934 -0.027753249 0.14016783, 0.1570892 -0.023808315 0.14016783, 0.14894228 -0.034407243 0.14016767, 0.14894231 -0.034406975 0.13476758, 0.14895767 -0.034270927 0.14016762, 0.14895767 -0.034270927 0.13476744, 0.14988744 -0.032796219 0.13476746, 0.15661818 -0.02860187 0.14016758, 0.14988743 -0.032796219 0.14016767, 0.15661833 -0.02860184 0.13476765, 0.13621828 -0.034658119 0.13455251, 0.13045512 -0.033407226 0.13842238, 0.13621821 -0.033406988 0.13455264, 0.13024481 -0.034658507 0.13856362, 0.13043787 -0.033408359 0.13843416, 0.14599892 -0.024224862 0.13929145, 0.14696355 -0.023043498 0.14016756, 0.14558305 -0.024734184 0.1401678, 0.14604239 -0.024171785 0.13906825, 0.14603747 -0.024177715 0.13915113, 0.14602275 -0.024195537 0.13922617, 0.1460423 -0.024171546 0.13676751, 0.14696355 -0.023043409 0.1367678, 0.14864418 -0.034373894 0.1404677, 0.14865942 -0.034237579 0.14046745, 0.1480666 -0.034985945 0.14046769, 0.14794858 -0.034995958 0.14046745, 0.14860792 -0.034531161 0.14046745, 0.14818688 -0.034954235 0.14046751, 0.14831401 -0.034892961 0.14046745, 0.14673106 -0.022853747 0.14046776, 0.14657123 -0.022416934 0.14046749, 0.14853103 -0.034684256 0.14046745, 0.14709422 -0.022497848 0.14046781, 0.14691879 -0.022076532 0.14046779, 0.14842834 -0.03480576 0.14046769, 0.14752673 -0.022230461 0.1404677, 0.14733231 -0.021820799 0.14046772, 0.14779212 -0.021662101 0.14046779, 0.15638919 -0.027198032 0.14046763, 0.15678927 -0.023808315 0.1404677, 0.15638924 -0.024308249 0.14046744, 0.14573218 -0.024077043 0.14046767, 0.14800732 -0.022064582 0.14046764, 0.14827557 -0.021608397 0.14046767, 0.15458935 -0.021608457 0.14046793, 0.15678921 -0.027753249 0.14046739, 0.15636259 -0.027459785 0.14046749, 0.15628377 -0.027710721 0.14046767, 0.15460096 -0.022066042 0.14046779, 0.15507887 -0.021663472 0.14046779, 0.15677491 -0.027894124 0.14046775, 0.15508711 -0.022236153 0.14046767, 0.15554371 -0.021826103 0.14046776, 0.15673256 -0.028029278 0.14046775, 0.15645958 -0.028347388 0.14046776, 0.15598482 -0.028140441 0.14046787, 0.1557768 -0.028301403 0.14046797, 0.15615624 -0.027940884 0.14046763, 0.1555232 -0.022510096 0.14046769, 0.15596099 -0.022088334 0.14046763, 0.14972878 -0.032541618 0.14046767, 0.15666379 -0.028153136 0.14046776, 0.15588742 -0.022874281 0.14046749, 0.15630925 -0.022436664 0.14046767, 0.15657143 -0.028260633 0.14046767, 0.1565713 -0.022853747 0.14046776, 0.14710186 -0.033707336 0.14046742, 0.15616146 -0.023310319 0.1404677, 0.15673411 -0.023318812 0.14046779, 0.15633166 -0.023796603 0.14046767, 0.14899965 -0.033266976 0.14046745, 0.14932318 -0.032863095 0.14046745, 0.14877446 -0.033732936 0.14046757, 0.14688221 -0.034996048 0.1404677, 0.15561825 -0.028046742 0.13676757, 0.15561813 -0.028046861 0.14016771, 0.14694698 -0.033450291 0.1401677, 0.14851262 -0.022308215 0.13676777, 0.1540892 -0.022308394 0.14016762, 0.14851269 -0.022308335 0.14016764, 0.15408923 -0.022308215 0.13676777, 0.15453427 -0.022358403 0.14016744, 0.15453421 -0.022358373 0.13676775, 0.15495689 -0.022506371 0.14016783, 0.15495704 -0.022506312 0.13676786, 0.15533623 -0.022744671 0.14016771, 0.15533617 -0.022744551 0.13676794, 0.15565296 -0.02306132 0.14016746, 0.15565287 -0.02306132 0.13676789, 0.15589109 -0.023440495 0.14016783, 0.15589117 -0.023440436 0.13676775, 0.15603903 -0.023863211 0.14016783, 0.15603921 -0.023863241 0.13676773, 0.15608923 -0.02430822 0.13676757, 0.15608934 -0.024308339 0.14016771, 0.15608929 -0.027198002 0.13676773, 0.15608925 -0.027198091 0.14016771, 0.15514551 -0.021371052 0.14016762, 0.15514551 -0.021370932 0.13646802, 0.15567397 -0.021555826 0.13646778, 0.15567392 -0.021555826 0.14016758, 0.15614782 -0.021853611 0.13646784, 0.15614793 -0.02185376 0.14016759, 0.15654372 -0.022249505 0.13646784, 0.15654373 -0.022249565 0.14016762, 0.15684165 -0.02272357 0.13646781, 0.1568417 -0.0227236 0.14016756, 0.15702663 -0.023252055 0.13646773, 0.15702653 -0.023252055 0.14016786, 0.15514542 -0.021370932 0.13476792, 0.15567395 -0.021555826 0.13476788, 0.156148 -0.021853581 0.13476789, 0.1565439 -0.022249594 0.13476789, 0.15684168 -0.02272357 0.13476789, 0.15702656 -0.023251906 0.13476788, 0.13625206 -0.034659997 0.13453181, 0.13626467 -0.03338553 0.13452484, 0.13632931 -0.034624591 0.13449647, 0.1363139 -0.033364072 0.13450231, 0.13639687 -0.033331081 0.13447775, 0.13641228 -0.034603015 0.13447465, 0.13627531 -0.033268049 0.13453804, 0.13046439 -0.033278927 0.13843642, 0.13625108 -0.033321068 0.13453962, 0.13045742 -0.033342555 0.13842605, 0.14673366 -0.021840438 0.14016774, 0.14673372 -0.021840319 0.13476793, 0.14720376 -0.021549806 0.14016768, 0.14720389 -0.021549597 0.13476783, 0.14772619 -0.021369562 0.14016756, 0.14772624 -0.021369442 0.1347678, 0.1480733 -0.02235724 0.14016765, 0.14807321 -0.022357032 0.13676777, 0.14765531 -0.022501513 0.14016749, 0.14765526 -0.022501275 0.13676777, 0.14727928 -0.022734031 0.14016762, 0.14727937 -0.022734001 0.13676786, 0.08400853 0.051811859 0.2752738, 0.084032089 0.051623747 0.27516484, 0.089811787 0.0053276271 0.24838705, 0.089835316 0.0051394254 0.24827813, 0.094652891 -0.033579871 0.2258703, 0.094623566 -0.033579871 0.22585543, 0.094684318 -0.033579782 0.22587955, 0.09373638 -0.03358002 0.22802179, 0.091949582 0.077439681 0.27736625, 0.096447736 0.07743977 0.27736628, 0.0949343 0.07743986 0.27736631, 0.094795436 0.077560529 0.27712473, 0.094595671 0.077662781 0.2769202, 0.093647018 0.079263106 0.27371979, 0.094346523 0.077740505 0.27676499, 0.094062895 0.077788875 0.27666807, 0.09814541 0.079263076 0.27371991, 0.098640099 0.079508409 0.27369612, 0.099816769 0.080867484 0.27448246, 0.090830743 0.08021225 0.27592364, 0.090475827 0.078192905 0.27816021, 0.090029269 0.078394368 0.27850628, 0.090962082 0.077900365 0.27784908, 0.089364693 0.078637317 0.27907288, 0.091464072 0.077531412 0.27758813, 0.09149754 0.07750456 0.27757263, 0.092756838 0.079508111 0.27428198, 0.093172431 0.079303607 0.27397501, 0.10008353 0.080992028 0.27466869, 0.098385885 0.079168633 0.27831525, 0.099981159 0.080974236 0.27461207, 0.09828344 0.079150781 0.27825844, 0.09989053 0.080931947 0.27454907, 0.0981929 0.079108492 0.27819517, 0.096870974 0.077616051 0.27732483, 0.098549932 0.079424635 0.27367571, 0.096781462 0.077553794 0.27731764, 0.098433837 0.079352424 0.27367187, 0.096638337 0.077486888 0.27732691, 0.09830077 0.079298183 0.27368581, 0.098222986 0.079277113 0.27370059, 0.093251541 0.079285637 0.27390635, 0.091630459 0.077454194 0.27749193, 0.093337417 0.079271063 0.27384567, 0.093430877 0.079259261 0.27379644, 0.091786623 0.077431783 0.27742058, 0.093537569 0.079254612 0.27375448, 0.090592131 0.080382243 0.2758975, 0.08912611 0.078807339 0.27904665, 0.090679899 0.080339774 0.27591699, 0.08921361 0.07876496 0.27906638, 0.090760395 0.080282345 0.27592599, 0.089294225 0.078707531 0.27907515, 0.12415722 0.11148782 0.20924605, 0.12601916 0.11046012 0.21130104, 0.12615928 0.11057936 0.21106239, 0.12456134 0.11155637 0.20910893, 0.12380151 0.11017744 0.21186627, 0.12351492 0.11032222 0.21157695, 0.12331402 0.11049332 0.21123464, 0.12415722 0.11006768 0.21208589, 0.12623133 0.11071031 0.21080089, 0.12321062 0.11068101 0.21085916, 0.12456135 0.10999916 0.21222307, 0.12528959 0.11132057 0.20958032, 0.12321079 0.11087419 0.21047278, 0.12623148 0.11084504 0.21053122, 0.12615924 0.11097594 0.21026959, 0.12601921 0.11109515 0.21003094, 0.12528969 0.11023475 0.21175154, 0.1255714 0.11127277 0.20967604, 0.12331402 0.11106201 0.21009754, 0.1258194 0.11119618 0.20982921, 0.12557146 0.11028247 0.21165572, 0.12351479 0.11123328 0.20975514, 0.12581937 0.11035927 0.21150292, 0.12380147 0.11137806 0.20946582, 0.094069302 0.076690778 0.27882975, 0.094358087 0.076741353 0.27872878, 0.094610065 0.076822087 0.27856725, 0.09480986 0.076928124 0.27835488, 0.094945312 0.077052906 0.2781055, 0.095010385 0.07711415 0.27762747, 0.09500432 0.077217653 0.27758896, 0.094993204 0.077296183 0.27753985, 0.094976425 0.0773599 0.27748168, 0.09495768 0.077404127 0.27742636, 0.12441781 0.11241253 0.20867874, 0.12399304 0.11175881 0.20903158, 0.12368882 0.11288111 0.20869567, 0.124228 0.11354809 0.20831615, 0.1244179 0.11016835 0.21316619, 0.12447676 0.10997654 0.21259558, 0.12399293 0.11005862 0.21243156, 0.12368876 0.11046328 0.21353075, 0.12422793 0.11055951 0.21429233, 0.12356701 0.1116273 0.20929457, 0.12264502 0.11250882 0.20944041, 0.1232239 0.11145417 0.20964091, 0.12298343 0.11124907 0.21005096, 0.12206559 0.11197062 0.21051618, 0.12285975 0.11102436 0.21049996, 0.12206565 0.11137356 0.21171038, 0.12285969 0.11079286 0.210963, 0.12298355 0.11056815 0.21141227, 0.12264501 0.11083545 0.21278627, 0.1232239 0.11036338 0.21182211, 0.12356712 0.11019005 0.21216841, 0.12447682 0.1118408 0.20886745, 0.12690032 0.11418544 0.20830166, 0.12597382 0.11434273 0.20798768, 0.12593071 0.11078481 0.2149352, 0.12681647 0.1140473 0.20841098, 0.12759605 0.11380668 0.20889236, 0.12765341 0.11387695 0.20885502, 0.12595142 0.11078854 0.21503094, 0.12685668 0.11412291 0.20836319, 0.12685661 0.11094217 0.21472383, 0.12597387 0.11077325 0.21512508, 0.12595156 0.11427648 0.20805608, 0.12690036 0.1109304 0.21481076, 0.12771559 0.11118211 0.2143074, 0.12593079 0.1141976 0.20811065, 0.12681656 0.11093502 0.21463466, 0.12765345 0.11118798 0.21423183, 0.12837249 0.11151387 0.21364422, 0.12759596 0.11117579 0.21415325, 0.12829535 0.11151226 0.21358389, 0.12883295 0.11190616 0.21285973, 0.1282243 0.11149283 0.21351942, 0.12874524 0.11189564 0.21281709, 0.12907009 0.11233635 0.21199931, 0.12866454 0.11186798 0.21276905, 0.12897699 0.11231597 0.21197651, 0.12907021 0.11277957 0.21111323, 0.12889116 0.11227937 0.21194656, 0.12897699 0.11274894 0.21111058, 0.12883306 0.11320956 0.21025291, 0.12889116 0.11270292 0.21109913, 0.12874521 0.11316936 0.21026994, 0.12837258 0.11360206 0.20946817, 0.12866454 0.11311425 0.21027668, 0.12829535 0.11355288 0.20950316, 0.12771566 0.11393376 0.20880504, 0.12822425 0.11348949 0.20952643, 0.12343466 0.11126678 0.20970994, 0.12313521 0.11112632 0.21005361, 0.1233573 0.11131595 0.20967503, 0.12449506 0.11175235 0.20890547, 0.1245157 0.10994999 0.21240608, 0.1240281 0.11167316 0.20906396, 0.12449495 0.10995381 0.21250193, 0.1240683 0.11159761 0.20911157, 0.12361732 0.11154647 0.20931731, 0.12361734 0.11015992 0.21208991, 0.12367478 0.11147602 0.20935462, 0.12402815 0.11003299 0.21234353, 0.12373687 0.11141916 0.20940472, 0.12451565 0.1116734 0.20896, 0.12406842 0.11002593 0.21225433, 0.124538 0.10996537 0.21231198, 0.12411192 0.11153503 0.2091731, 0.1232864 0.11032693 0.21175577, 0.12453809 0.11160727 0.2090285, 0.1236746 0.11014734 0.21201137, 0.12411192 0.11003761 0.21216749, 0.12305439 0.11052455 0.21136038, 0.12335746 0.1103075 0.21169128, 0.12373695 0.11015345 0.21193586, 0.12293482 0.11074139 0.21092708, 0.12313516 0.11049689 0.21131228, 0.12343478 0.11030592 0.21163078, 0.12293482 0.11096467 0.21048041, 0.12302066 0.11070471 0.21089701, 0.12322283 0.1104864 0.21126981, 0.12305427 0.11118139 0.21004696, 0.12302066 0.11091872 0.21046905, 0.12311375 0.11068429 0.21087401, 0.12328625 0.11137919 0.20965149, 0.12311368 0.1108882 0.21046659, 0.12322284 0.11108609 0.21007089, 0.091913253 0.083192602 0.2830033, 0.09147355 0.083420977 0.28254646, 0.12772949 0.11775745 0.21388377, 0.1275916 0.11804755 0.21330391, 0.12770839 0.11746098 0.21447642, 0.12752926 0.1171755 0.2150473, 0.12323375 0.11859469 0.21220946, 0.12277849 0.11837916 0.2126404, 0.092463985 0.083018973 0.28335059, 0.12245177 0.11812122 0.2131563, 0.12379119 0.11875521 0.21188843, 0.12441824 0.11885138 0.21169612, 0.091222718 0.084576234 0.28023654, 0.12507866 0.11887787 0.21164334, 0.093092695 0.082910344 0.28356761, 0.12573384 0.1188326 0.21173395, 0.091041908 0.08428596 0.28081727, 0.12634592 0.11871861 0.21196152, 0.091024369 0.083984599 0.28141975, 0.12687908 0.11854242 0.21231389, 0.091171086 0.08369036 0.28200796, 0.1273025 0.11831422 0.21277031, 0.1005694 -0.0095577091 0.23532775, 0.1004294 -0.0097885579 0.23519401, 0.098567382 -0.0077997595 0.23634423, 0.09821175 -0.0080123097 0.23622142, 0.10064159 -0.009304449 0.23547423, 0.09856759 -0.010548279 0.23475476, 0.098211765 -0.010335669 0.23487769, 0.097925156 -0.010055706 0.23503955, 0.098971546 -0.01068078 0.23467794, 0.098971546 -0.007667169 0.23642133, 0.097724289 -0.0097243637 0.23523138, 0.10064156 -0.0090436786 0.235625, 0.097620919 -0.0093611926 0.23544124, 0.099699676 -0.0081234425 0.23615721, 0.097620785 -0.0089871138 0.23565763, 0.1005694 -0.0087903589 0.23577133, 0.099981487 -0.0082160383 0.23610345, 0.10042927 -0.0085593313 0.23590517, 0.099699765 -0.010224566 0.23494187, 0.097724244 -0.0086237937 0.23586793, 0.10022947 -0.0083640069 0.23601806, 0.099981621 -0.010132119 0.23499542, 0.097925171 -0.0082924515 0.23605929, 0.10022952 -0.0099838227 0.23508108, 0.088841543 0.070106819 0.2814061, 0.090703443 0.068117961 0.28025562, 0.090843335 0.068348929 0.28038928, 0.089245707 0.070239529 0.28148288, 0.088199064 0.067850992 0.28010136, 0.087998316 0.068182155 0.28029293, 0.088485733 0.06757085 0.27993938, 0.088841364 0.06735836 0.27981627, 0.089245513 0.067225739 0.27973977, 0.090915591 0.068602249 0.2805357, 0.087894961 0.068545505 0.28050309, 0.087894812 0.068919554 0.28071937, 0.090915516 0.068863109 0.28068662, 0.087998316 0.069282964 0.28092957, 0.089973852 0.069783166 0.28121901, 0.090255663 0.0696906 0.28116542, 0.089973882 0.067682013 0.28000349, 0.090843409 0.069116279 0.28083313, 0.090503499 0.069542572 0.28107968, 0.090255633 0.06777446 0.28005701, 0.090703413 0.069347247 0.28096688, 0.088199139 0.069614217 0.28112108, 0.090503618 0.067922696 0.2801429, 0.088485882 0.06989415 0.28128314, 0.098637998 -0.0069964081 0.23845732, 0.098098919 -0.0073349625 0.23776834, 0.098828048 -0.0072893947 0.23730184, 0.098828048 -0.011632577 0.23478973, 0.098886907 -0.011051282 0.234633, 0.098403156 -0.010892496 0.23472467, 0.098098978 -0.012014404 0.23506191, 0.098638162 -0.012780353 0.23511189, 0.098403141 -0.0076022893 0.23662801, 0.097977206 -0.0078566223 0.23648061, 0.097055167 -0.0080555528 0.23735182, 0.097634166 -0.0081919581 0.23628682, 0.097393647 -0.008588478 0.23605743, 0.09647578 -0.0090967566 0.23674932, 0.097269848 -0.0090234727 0.23580612, 0.097269937 -0.009471491 0.23554678, 0.096475914 -0.01025264 0.23608091, 0.09739387 -0.0099063069 0.2352953, 0.097055137 -0.011293903 0.23547868, 0.097634122 -0.010302767 0.23506574, 0.09797734 -0.010638103 0.23487189, 0.098886907 -0.0074432939 0.23671983, 0.088372946 0.065892264 0.28012353, 0.087329194 0.066612735 0.28054041, 0.088251278 0.067268565 0.27993363, 0.089102179 0.070617124 0.28236344, 0.089160964 0.070463374 0.28178144, 0.088677213 0.070304528 0.28168955, 0.088373065 0.070571527 0.28283009, 0.088912129 0.070910141 0.28351909, 0.089102075 0.066274002 0.27985138, 0.089161068 0.066855237 0.2796945, 0.088677093 0.067014024 0.27978653, 0.0889121 0.065126196 0.2801736, 0.088251412 0.070050076 0.28154242, 0.087329149 0.069850966 0.2824133, 0.087908193 0.06971474 0.28134847, 0.087667748 0.069318101 0.28111911, 0.086750001 0.068809673 0.28181103, 0.087543905 0.068883166 0.28086752, 0.086749956 0.067654058 0.28114271, 0.087543845 0.068435267 0.28060842, 0.087667748 0.068000361 0.28035688, 0.087908089 0.067603692 0.28012753, 0.098904982 -0.0074758679 0.23662902, 0.098925844 -0.010860726 0.23461807, 0.098438367 -0.0076292008 0.23654053, 0.098905146 -0.010956511 0.23461595, 0.098478451 -0.0076722056 0.23646225, 0.098027527 -0.0078745931 0.23639835, 0.098084852 -0.0079075247 0.23632611, 0.098027647 -0.010557875 0.23484638, 0.09814696 -0.0079540163 0.23626639, 0.098438323 -0.010803327 0.23470441, 0.097844899 -0.0082493871 0.23609556, 0.097767636 -0.0082174093 0.23614685, 0.098925784 -0.0075253397 0.23654722, 0.098478496 -0.01071392 0.23470297, 0.098948181 -0.010767683 0.23463884, 0.098522112 -0.0077299327 0.23639598, 0.097696587 -0.010234371 0.23503344, 0.098948166 -0.007589981 0.23647681, 0.098084942 -0.01047875 0.23483886, 0.098522171 -0.010627791 0.23471971, 0.097464547 -0.0098519772 0.23525499, 0.097767636 -0.010168806 0.23501842, 0.098147094 -0.010403618 0.23484938, 0.097345054 -0.0094323605 0.23549742, 0.097545296 -0.0098021477 0.23523022, 0.097844809 -0.010108396 0.23502009, 0.097345054 -0.0090001971 0.23574772, 0.097430885 -0.0094002634 0.23546258, 0.097633079 -0.0097591132 0.23522216, 0.097464621 -0.0085807294 0.23599011, 0.0974309 -0.0089861602 0.23570217, 0.097524032 -0.0093761832 0.23544371, 0.097696498 -0.0081980079 0.23621139, 0.097545326 -0.0085840374 0.23593476, 0.097524017 -0.0089817196 0.23567182, 0.097633004 -0.0085984915 0.23589362, 0.10126688 -0.0070782751 0.23902814, 0.10036153 -0.0067810863 0.23920015, 0.10131039 -0.0070205778 0.23909424, 0.10212575 -0.012833372 0.23573247, 0.10038394 -0.0067164749 0.23927036, 0.10131049 -0.013320491 0.23545077, 0.10034101 -0.0068306178 0.23911807, 0.1012267 -0.013144895 0.23546588, 0.10036168 -0.013531461 0.23529567, 0.10126683 -0.013234392 0.23546745, 0.10122673 -0.0071214885 0.23894975, 0.10034105 -0.013435736 0.23529758, 0.10206369 -0.01275827 0.23574291, 0.10278273 -0.01219137 0.23610367, 0.10200629 -0.012679234 0.23573534, 0.10270563 -0.01213108 0.23610587, 0.10324302 -0.011432037 0.23654285, 0.10263439 -0.012065455 0.23609036, 0.10315545 -0.011389002 0.2365348, 0.1034802 -0.010599241 0.23702443, 0.10307461 -0.011339322 0.23651005, 0.10338715 -0.01057528 0.23700543, 0.10348029 -0.0097418278 0.23752065, 0.10330132 -0.010543212 0.23697057, 0.10338703 -0.0097372383 0.23749033, 0.10324302 -0.0089089721 0.23800214, 0.10330132 -0.0097231716 0.23744503, 0.10315543 -0.0089235455 0.23796086, 0.10278262 -0.0081497282 0.23844148, 0.10307446 -0.0089269727 0.23790529, 0.10270549 -0.0081815571 0.23838998, 0.10212566 -0.007507816 0.23881279, 0.10263437 -0.0082009882 0.23832554, 0.10206348 -0.0075542778 0.2387528, 0.10200621 -0.0075871795 0.23868035, 0.10038409 -0.013624564 0.23527481, 0.088712379 0.067103222 0.27976614, 0.089179084 0.066950068 0.27967751, 0.088358879 0.069999263 0.28138766, 0.088041663 0.069689199 0.28120857, 0.087970555 0.069708571 0.28127319, 0.08830148 0.070032045 0.2814602, 0.089199871 0.067045733 0.27967966, 0.088118806 0.06965737 0.28115731, 0.087819353 0.069322601 0.28099665, 0.087907121 0.069307998 0.2809552, 0.089179114 0.0704308 0.28169096, 0.088301584 0.067348704 0.27990818, 0.088712364 0.070277616 0.28160217, 0.088752553 0.070234433 0.28152397, 0.088752553 0.067192629 0.27976435, 0.088421151 0.069952622 0.28132814, 0.089222237 0.067138925 0.2797007, 0.089199752 0.070381209 0.2816087, 0.087970555 0.067672119 0.28009534, 0.088796303 0.070176676 0.28145754, 0.088358924 0.067427829 0.27990061, 0.089222312 0.070316598 0.28153846, 0.088796169 0.067278787 0.27978134, 0.087738454 0.068054691 0.28031665, 0.088041708 0.067737743 0.28007966, 0.088421077 0.067502871 0.27991098, 0.087619036 0.068474308 0.28055936, 0.087819502 0.068104371 0.28029191, 0.088118926 0.067798182 0.28008193, 0.087619111 0.068906412 0.28080922, 0.087704927 0.068506345 0.28052449, 0.087907121 0.068147406 0.28028387, 0.087738574 0.069325909 0.28105175, 0.087704942 0.068920538 0.28076398, 0.087798074 0.068530515 0.28050563, 0.087798044 0.068924949 0.2807337, 0.091540858 0.070828274 0.2840898, 0.09061496 0.071075872 0.28417969, 0.090635702 0.071125463 0.2842617, 0.092399895 0.065073356 0.28079391, 0.091584384 0.064586177 0.2805123, 0.090635717 0.064375117 0.28035739, 0.0915007 0.064761713 0.2805275, 0.091540977 0.064672336 0.28052935, 0.090615034 0.064470962 0.28035948, 0.092337802 0.065148398 0.28080454, 0.093056858 0.065715179 0.28116548, 0.092280373 0.065227464 0.28079689, 0.09297961 0.065775618 0.28116727, 0.093517244 0.066474661 0.28160441, 0.092908442 0.065841302 0.28115201, 0.093429536 0.066517666 0.28159666, 0.093754262 0.06730713 0.28208598, 0.093348607 0.066567287 0.28157204, 0.093661174 0.06733118 0.28206724, 0.093754217 0.068164811 0.28258204, 0.093575418 0.067363307 0.28203243, 0.093661234 0.068169221 0.28255177, 0.093517229 0.068997487 0.28306383, 0.093575329 0.068183348 0.28250682, 0.093429521 0.068982914 0.28302261, 0.093056843 0.069756851 0.28350294, 0.093348682 0.068979487 0.28296733, 0.092979595 0.069725022 0.28345168, 0.09239988 0.070398673 0.28387427, 0.092908427 0.069705591 0.28338724, 0.092337549 0.070352271 0.28381464, 0.091584489 0.070885912 0.28415623, 0.092280298 0.070319399 0.28374225, 0.090658084 0.064282104 0.28033644, 0.090658113 0.071190074 0.28433192, 0.09150067 0.07078515 0.28401148, 0.098736733 -0.015109137 0.24048053, 0.098111942 -0.014902011 0.24060047, 0.092408821 0.065363243 0.28702644, 0.090991557 0.064320758 0.28642368, 0.090735599 0.064070895 0.28627899, 0.091170833 0.064616397 0.28659442, 0.091262981 0.064940497 0.28678191, 0.091263086 0.065274313 0.28697512, 0.092258617 0.065922186 0.2873497, 0.086940572 0.064851716 0.28673053, 0.09666647 -0.013054773 0.24166882, 0.087878346 0.066910014 0.28792113, 0.08743231 0.06648542 0.28767565, 0.10098904 -0.012632146 0.2419133, 0.10098898 -0.012965962 0.24172033, 0.10089666 -0.012307867 0.24210094, 0.10071741 -0.012012288 0.24227181, 0.10046153 -0.011762396 0.24241625, 0.10014412 -0.011572644 0.24252608, 0.08711645 0.065980926 0.28738379, 0.0884289 0.067229673 0.28810596, 0.086949408 0.065425441 0.28706241, 0.10089673 -0.013290092 0.24153292, 0.09978354 -0.014143929 0.24103919, 0.089051783 0.06742613 0.28821975, 0.1007174 -0.013585821 0.24136174, 0.090057537 0.063762859 0.28610066, 0.10014416 -0.014025375 0.24110746, 0.089710921 0.067487732 0.28825542, 0.10046169 -0.013835803 0.24121726, 0.096818849 -0.013618723 0.24134278, 0.09978348 -0.011454239 0.24259448, 0.090418294 0.063881204 0.28616929, 0.090057582 0.06645222 0.2876564, 0.090367839 0.067411199 0.28821105, 0.097123832 -0.014134213 0.24104467, 0.090418145 0.066333935 0.287588, 0.090984777 0.067200556 0.2880891, 0.090735644 0.066144183 0.2874783, 0.091525257 0.06686835 0.28789699, 0.097563624 -0.014570549 0.24079216, 0.090991646 0.065894201 0.28733382, 0.091958329 0.066433862 0.28764585, 0.091170639 0.065598682 0.28716275, 0.099783495 -0.010703251 0.24129614, 0.10014419 -0.010821715 0.24122785, 0.10046169 -0.011011466 0.24111791, 0.10071735 -0.01126124 0.24097334, 0.10089669 -0.011556968 0.24080256, 0.10098903 -0.011881217 0.24061491, 0.10098903 -0.012215003 0.24042188, 0.1008967 -0.012539193 0.24023427, 0.10014413 -0.013274357 0.2398091, 0.099783599 -0.013392791 0.23974064, 0.10071748 -0.012834892 0.24006347, 0.10046166 -0.013084754 0.23991874, 0.090057537 0.067203358 0.28635815, 0.090057537 0.064513877 0.28480235, 0.09041819 0.064632192 0.28487074, 0.09041822 0.067084774 0.28628933, 0.090991348 0.065071896 0.28512511, 0.091170669 0.06634973 0.28586429, 0.090991542 0.066645309 0.28603518, 0.091263101 0.066025481 0.28567672, 0.091262981 0.065691665 0.28548351, 0.091170624 0.065367505 0.28529596, 0.090735629 0.064821884 0.28498065, 0.090735599 0.066895291 0.2861799, 0.1363778 0.12124135 0.20651104, 0.13653328 0.12007608 0.20592158, 0.13654903 0.12122945 0.20655771, 0.13669179 0.11795028 0.20481755, 0.13675249 0.12004511 0.20599149, 0.13675275 0.12119336 0.20665576, 0.13685714 0.11689602 0.20428981, 0.13686249 0.11793284 0.20485879, 0.13695326 0.11999027 0.20610805, 0.13692752 0.12113582 0.20679237, 0.1370735 0.11687167 0.20436515, 0.13704309 0.11789726 0.20493674, 0.13711762 0.11991535 0.20626371, 0.13706434 0.12105982 0.20695975, 0.13726626 0.11682437 0.20448233, 0.13720571 0.11784466 0.20504735, 0.13723393 0.11982708 0.20644356, 0.1371558 0.12096934 0.20714924, 0.13742524 0.11675684 0.20463504, 0.13735254 0.11777033 0.20520073, 0.13719681 0.12086926 0.20735134, 0.13754177 0.11667262 0.20481469, 0.13746372 0.11767547 0.20539437, 0.13718589 0.12076484 0.2075547, 0.13760996 0.11657627 0.20501269, 0.13762592 0.11647286 0.20521791, 0.13760306 0.11639379 0.20537032, 0.079817817 0.076280817 0.29178408, 0.079804778 0.076426312 0.2918424, 0.079798013 0.076581016 0.29186529, 0.079626471 0.07781364 0.2929332, 0.079801425 0.076737866 0.29185361, 0.079819068 0.076888308 0.29181045, 0.0796725 0.078004047 0.29274696, 0.079852074 0.077024832 0.29174083, 0.12002483 0.11593406 0.20614576, 0.11978716 0.11698012 0.20673589, 0.11969095 0.11586262 0.2062659, 0.1193746 0.11687787 0.20693208, 0.11931184 0.11573569 0.20649362, 0.11905479 0.11675103 0.20717894, 0.1190023 0.11557464 0.20679317, 0.11883317 0.11662115 0.20743351, 0.11867981 0.11994798 0.20905609, 0.11867964 0.11879109 0.20847742, 0.11895332 0.12009029 0.20877138, 0.11895305 0.11893339 0.20819275, 0.11928706 0.12020399 0.20854422, 0.11928697 0.11904709 0.20796551, 0.11966653 0.12028413 0.20838396, 0.1196665 0.11912699 0.20780535, 0.14905782 -0.033832267 0.1401677, 0.14905769 -0.033832148 0.13476758, 0.14925344 -0.033426955 0.14016764, 0.14925343 -0.033426926 0.13476758, 0.14953478 -0.033075765 0.14016764, 0.14953476 -0.033075646 0.13476758, 0.14890932 -0.034573182 0.14016773, 0.14890726 -0.034580186 0.13476746, 0.14884509 -0.034739032 0.14016764, 0.14884166 -0.034745589 0.13476743, 0.14874859 -0.034895703 0.13476758, 0.14873798 -0.0349098 0.14016752, 0.14857741 -0.035073325 0.1349452, 0.14859588 -0.035058066 0.14016764, 0.14840724 -0.035184667 0.14016764, 0.14840533 -0.035185292 0.13505714, 0.14822839 -0.035255775 0.13512756, 0.14817746 -0.035269454 0.14016764, 0.14808829 -0.035285875 0.13515787, 0.1567782 -0.028477952 0.13476767, 0.15677828 -0.028478041 0.14016746, 0.15690991 -0.02832453 0.14016779, 0.15690999 -0.02832444 0.13476767, 0.15700823 -0.028147563 0.1401677, 0.15700826 -0.028147593 0.13476765, 0.15706883 -0.027954504 0.1401678, 0.15706882 -0.027954474 0.13476753, 0.15577811 -0.027922884 0.13676751, 0.15577815 -0.027922943 0.14016782, 0.15590996 -0.027769461 0.14016771, 0.15591016 -0.027769253 0.13676754, 0.15600818 -0.027592555 0.14016783, 0.1560083 -0.027592435 0.13676757, 0.15606883 -0.027399346 0.14016786, 0.15606889 -0.027399287 0.13676748, 0.09968774 0.077716693 0.28006876, 0.11342773 -0.032679364 0.21627262, 0.099636212 0.077698871 0.28012973, 0.099571958 0.077686384 0.280182, 0.11332437 -0.032622084 0.21639189, 0.0994986 0.077680185 0.28022233, 0.11323756 -0.032589927 0.21645278, 0.099420726 0.077680275 0.28024876, 0.11317125 -0.032573178 0.21648006, 0.10019065 0.078241512 0.278974, 0.11405683 -0.032823816 0.21472934, 0.10019517 0.078276858 0.27888644, 0.11407265 -0.032891467 0.2145652, 0.11406434 -0.032939926 0.21444336, 0.10014118 0.078349039 0.2787298, 0.11403763 -0.032984093 0.21432872, 0.1139991 -0.033016846 0.21423928, 0.10008459 0.078383669 0.27866489, 0.11396238 -0.033036396 0.21418302, 0.10001372 0.078413859 0.27861586, 0.11392066 -0.033051208 0.21413736, 0.11387508 -0.033061102 0.21410292, 0.099935025 0.07843782 0.27858484, 0.11382779 -0.033066496 0.21407948, 0.099862903 0.078453198 0.27857199, 0.11377466 -0.033067271 0.21406564, 0.11644542 -0.032572582 0.20848514, 0.10230786 0.080781505 0.27404743, 0.11651188 -0.03258948 0.20845783, 0.10238566 0.080781296 0.27402091, 0.11659865 -0.032621816 0.20839687, 0.10245901 0.080787584 0.27398056, 0.11670195 -0.032678857 0.20827764, 0.10252337 0.080800101 0.2739282, 0.10257486 0.080817953 0.27386725, 0.1027526 0.08155407 0.2723707, 0.11711565 -0.033064917 0.20608971, 0.10282418 0.081538573 0.27238369, 0.11716567 -0.033057615 0.20611843, 0.10290891 0.081512257 0.27241868, 0.11721309 -0.03304483 0.20616043, 0.11725591 -0.033026382 0.20621535, 0.10298003 0.081480697 0.27247107, 0.11729228 -0.033002391 0.20628254, 0.11732732 -0.032962665 0.20638838, 0.11734577 -0.032910481 0.20652129, 0.11734204 -0.03285484 0.20665796, 0.11732249 -0.032806203 0.20677415, 0.11971973 -0.032572046 0.20048989, 0.1051949 0.083882853 0.26784563, 0.1197861 -0.032588944 0.20046251, 0.10527283 0.083882704 0.26781929, 0.11987296 -0.032621339 0.20040171, 0.10534617 0.083888933 0.26777911, 0.11997616 -0.032678291 0.20028248, 0.10541035 0.08390145 0.26772648, 0.105462 0.083919242 0.26766554, 0.10563995 0.08465533 0.26616889, 0.12038971 -0.033064291 0.19809477, 0.10571137 0.084639773 0.26618224, 0.12043986 -0.033057168 0.19812344, 0.10579613 0.084613428 0.26621717, 0.12048735 -0.033044383 0.1981651, 0.12053025 -0.033025905 0.19822018, 0.10586736 0.084581897 0.26626945, 0.12056646 -0.033001915 0.19828743, 0.12060152 -0.032962218 0.19839324, 0.12062 -0.032909945 0.1985261, 0.12061632 -0.032854423 0.19866279, 0.12059677 -0.032805786 0.19877902, 0.12299392 -0.032571599 0.19249479, 0.10808209 0.086983934 0.26164401, 0.1230602 -0.032588407 0.1924675, 0.10816008 0.086983845 0.2616176, 0.1231471 -0.032620624 0.19240646, 0.10823335 0.086990044 0.26157731, 0.12325042 -0.032677934 0.19228734, 0.10829753 0.08700262 0.2615248, 0.10834919 0.087020442 0.26146406, 0.10852684 0.087756798 0.25996745, 0.12366407 -0.033064023 0.19009978, 0.10859847 0.087741122 0.25998068, 0.12371406 -0.033056661 0.19012825, 0.10868318 0.087714776 0.26001549, 0.12376153 -0.033043936 0.19017, 0.12380451 -0.033025548 0.19022502, 0.10875428 0.087683246 0.260068, 0.12384078 -0.033001468 0.19029252, 0.12387584 -0.032961681 0.19039792, 0.1238943 -0.032909587 0.19053106, 0.1238905 -0.032853916 0.19066793, 0.12387106 -0.032805279 0.19078378, 0.12626813 -0.032571301 0.18449982, 0.11096938 0.090085194 0.25544232, 0.12633465 -0.032588229 0.1844724, 0.11104703 0.090085134 0.25541604, 0.12642145 -0.032620415 0.18441136, 0.11112043 0.090091482 0.2553758, 0.12652479 -0.032677487 0.18429226, 0.11118478 0.090103969 0.25532335, 0.11123623 0.090121791 0.25526243, 0.11141407 0.090857908 0.25376558, 0.12693818 -0.033063427 0.18210454, 0.11148556 0.090842292 0.25377923, 0.12698828 -0.033056274 0.18213312, 0.11157024 0.090815946 0.25381386, 0.12703602 -0.033043548 0.18217508, 0.12707882 -0.033024952 0.1822298, 0.11164156 0.090784386 0.25386623, 0.127115 -0.033000991 0.18229721, 0.12714998 -0.032961413 0.18240283, 0.12716852 -0.03290908 0.18253587, 0.12716483 -0.032853469 0.18267255, 0.12714536 -0.032804802 0.18278863, 0.12954247 -0.032570764 0.1765047, 0.11385643 0.093186453 0.24924073, 0.1296088 -0.032587573 0.17647703, 0.11393441 0.093186304 0.24921429, 0.12969567 -0.032619879 0.17641602, 0.1140077 0.093192533 0.24917403, 0.12979889 -0.032677099 0.17629716, 0.1140718 0.09320502 0.24912159, 0.11412334 0.09322305 0.2490606, 0.11430126 0.093959108 0.24756408, 0.13021244 -0.03306286 0.17410944, 0.11437283 0.093943581 0.24757761, 0.13026251 -0.033055738 0.17413794, 0.11445744 0.093917325 0.24761234, 0.13031006 -0.033042952 0.17417988, 0.13035299 -0.033024505 0.17423461, 0.11452878 0.093885735 0.24766442, 0.13038921 -0.033000514 0.17430213, 0.13042423 -0.032960728 0.17440796, 0.13044274 -0.032908604 0.17454073, 0.13043906 -0.032853082 0.1746776, 0.13041961 -0.032804415 0.17479345, 0.11718847 0.097060397 0.24136248, 0.13348673 -0.033062473 0.16611433, 0.11725983 0.097045019 0.24137609, 0.13353676 -0.033055201 0.16614307, 0.1173446 0.097018465 0.24141066, 0.13358423 -0.033042446 0.16618483, 0.13362725 -0.033024058 0.16623977, 0.11741582 0.096986845 0.24146311, 0.13366337 -0.032999918 0.16630694, 0.13369852 -0.03296034 0.1664129, 0.13371694 -0.032908097 0.16654576, 0.13371333 -0.032852575 0.16668253, 0.1336937 -0.032803789 0.16679849, 0.13281666 -0.032570377 0.16850948, 0.11674352 0.096287951 0.24303922, 0.13288319 -0.032587215 0.16848184, 0.11682141 0.096287712 0.24301295, 0.13296998 -0.032619372 0.16842093, 0.11689472 0.096293911 0.24297239, 0.13307321 -0.032676622 0.16830207, 0.11695901 0.096306399 0.24292007, 0.11701055 0.09632425 0.24285914, 0.13609096 -0.03256987 0.1605144, 0.11963065 0.099389181 0.23683748, 0.13615736 -0.032586679 0.16048698, 0.11970854 0.099388942 0.23681122, 0.13624412 -0.032618985 0.16042604, 0.11978182 0.09939523 0.23677085, 0.13634747 -0.032676056 0.16030677, 0.11984606 0.099407688 0.23671833, 0.11989768 0.099425539 0.23665757, 0.12007554 0.10016169 0.23516098, 0.13676091 -0.033062026 0.15811911, 0.12014695 0.10014619 0.23517421, 0.136811 -0.033054724 0.15814787, 0.12023166 0.1001199 0.23520914, 0.13685857 -0.033042029 0.15818948, 0.13690148 -0.033023551 0.15824461, 0.12030289 0.10008813 0.23526137, 0.13693771 -0.032999411 0.15831177, 0.1369727 -0.032959804 0.15841781, 0.13699123 -0.032907739 0.15855066, 0.13698742 -0.032851949 0.15868728, 0.136968 -0.032803372 0.15880352, 0.13936532 -0.032569394 0.15251938, 0.1225179 0.10249035 0.23063588, 0.1394316 -0.032586202 0.15249172, 0.12259571 0.10249011 0.23060961, 0.1395185 -0.032618389 0.15243091, 0.12266906 0.10249649 0.23056921, 0.13962157 -0.032675549 0.15231171, 0.12273332 0.10250883 0.23051685, 0.12278475 0.10252677 0.23045592, 0.12296267 0.10326289 0.22895922, 0.14003509 -0.033061489 0.15012416, 0.12303422 0.1032473 0.22897246, 0.14008522 -0.033054218 0.15015271, 0.12311889 0.10322104 0.22900754, 0.1401329 -0.033041582 0.15019456, 0.1401757 -0.033022985 0.15024939, 0.12319 0.10318951 0.22905983, 0.14021194 -0.032999024 0.15031675, 0.14024691 -0.032959327 0.15042247, 0.14026546 -0.032907233 0.15055528, 0.14026175 -0.032851651 0.1506923, 0.14024222 -0.032802984 0.1508083, 0.12584975 0.10636415 0.2227578, 0.14330961 -0.033061191 0.14212899, 0.12592129 0.10634844 0.22277112, 0.14335968 -0.03305392 0.14215772, 0.12600604 0.10632209 0.22280583, 0.14340711 -0.033041224 0.14219925, 0.14345001 -0.033022806 0.14225443, 0.12607723 0.10629068 0.22285834, 0.14348622 -0.032998666 0.14232163, 0.14352117 -0.032958969 0.14242746, 0.14353979 -0.032906756 0.14256033, 0.14353599 -0.032851145 0.14269702, 0.14351656 -0.032802507 0.14281325, 0.14263949 -0.032568768 0.1445241, 0.12540483 0.10559161 0.22443439, 0.14270596 -0.032585725 0.14449657, 0.12548277 0.1055914 0.22440808, 0.14279257 -0.032617971 0.14443578, 0.12555608 0.10559775 0.22436766, 0.14289597 -0.032675222 0.14431643, 0.12562034 0.10561012 0.22431521, 0.12567192 0.10562791 0.22425433, 0.12855901 0.10872941 0.2180528, 0.12850741 0.10871156 0.21811375, 0.1284432 0.10869907 0.21816626, 0.12836985 0.10869281 0.2182065, 0.12829198 0.10869293 0.21823281, 0.12906183 0.10925417 0.21695799, 0.12906642 0.10928963 0.21687046, 0.1290126 0.10936157 0.21671408, 0.12895598 0.10939638 0.21664888, 0.14538969 -0.02266036 0.14021161, 0.12888496 0.10942657 0.21659988, 0.14533143 -0.0228488 0.14004982, 0.1288064 0.10945038 0.21656892, 0.12873413 0.10946591 0.21655595, 0.11239861 0.10852148 0.22086635, 0.13015591 -0.033336356 0.13873328, 0.11246403 0.10854997 0.22076844, 0.13028601 -0.033275917 0.13858902, 0.11259851 0.10856585 0.22061007, 0.13044232 -0.033225283 0.1384733, 0.13043644 -0.033284619 0.13845395, 0.13043484 -0.033346012 0.13844085, 0.13028286 -0.033402339 0.13856174, 0.13015445 -0.03340061 0.13871931, 0.13009159 -0.034637824 0.13869025, 0.12996663 -0.034617946 0.13884507, 0.083836168 0.052095875 0.27517426, 0.083835274 0.052071378 0.27521634, 0.083846092 0.052048579 0.27525818, 0.083868027 0.052028731 0.27529702, 0.083899766 0.052013323 0.27533072, 0.083939463 0.052003071 0.27535731, 0.083984926 0.051998422 0.2753748, 0.083937243 0.051473275 0.27497578, 0.083969116 0.051457599 0.27500936, 0.084008768 0.051447406 0.27503595, 0.084054217 0.051442757 0.2750535, 0.083915278 0.051493004 0.27493668, 0.083967194 0.051815405 0.27525902, 0.083900437 0.051835135 0.27520925, 0.083862036 0.051867828 0.2751416, 0.083905488 0.051540419 0.27485287, 0.083904535 0.051515803 0.27489495, 0.089639321 0.0056117326 0.24828739, 0.089638293 0.0055871755 0.24832967, 0.089649096 0.0055644065 0.24837138, 0.089671195 0.0055446178 0.24841037, 0.08970283 0.0055290908 0.24844404, 0.089742675 0.0055188686 0.24847029, 0.089787975 0.0055142194 0.24848805, 0.089740545 0.0049888641 0.24808882, 0.089772239 0.0049734861 0.24812277, 0.089812115 0.0049629956 0.24814895, 0.089857414 0.0049585849 0.2481667, 0.089718461 0.0050086826 0.24804996, 0.089770451 0.0053311139 0.24837197, 0.089703575 0.0053509027 0.24832226, 0.089665294 0.0053834766 0.24825479, 0.089708701 0.0050561279 0.24796607, 0.089707732 0.0050315112 0.24800833, 0.094552875 -0.033723399 0.22552153, 0.094541803 -0.033687785 0.22558628, 0.094539285 -0.033646271 0.22566788, 0.094546512 -0.033620432 0.22572474, 0.094559193 -0.033602282 0.22576936, 0.094572186 -0.033592209 0.22579768, 0.094587684 -0.033585235 0.22582166, 0.094604939 -0.033581153 0.22584087, 0.14620848 -0.024369612 0.13647538, 0.14670487 -0.02834709 0.13647509, 0.14614557 -0.02437745 0.13649753, 0.1466419 -0.028354868 0.13649735, 0.14608906 -0.024384424 0.13653335, 0.1465856 -0.028361931 0.13653302, 0.14604189 -0.024390295 0.13658077, 0.14653857 -0.028367952 0.13658047, 0.14600654 -0.024394825 0.13663745, 0.14650302 -0.028372332 0.13663748, 0.14598447 -0.024397478 0.13670103, 0.14648099 -0.028375104 0.13670075, 0.11049035 -0.035268858 0.22858337, 0.09431088 -0.035249159 0.22867903, 0.11040512 -0.035173073 0.22892953, 0.094286546 -0.035095409 0.22910899, 0.11031225 -0.034964517 0.22933593, 0.094257936 -0.034848109 0.22949308, 0.11024094 -0.034669146 0.22968422, 0.094233721 -0.034596369 0.22974943, 0.096409738 0.076266512 0.29388583, 0.080405429 0.076428875 0.29394203, 0.096406698 0.076546773 0.29397351, 0.080374762 0.076886788 0.29402301, 0.096424863 0.076988563 0.29402629, 0.080347523 0.077351078 0.29399592, 0.096469283 0.077431008 0.29398, 0.080329552 0.077704117 0.29389948, 0.096537948 0.077852473 0.29383722, 0.080315053 0.078033611 0.29374069, 0.096627519 0.078231677 0.29360473, 0.080318242 0.078256086 0.29358551, 0.080347657 0.078452691 0.29340458, 0.096733302 0.078550205 0.29329419, 0.080402523 0.078617111 0.29320762, 0.080144525 0.077046081 0.29149222, 0.080114827 0.07701315 0.29153281, 0.080086067 0.076976135 0.29156965, 0.080039009 0.076891646 0.2916308, 0.080020115 0.076837525 0.29165784, 0.080006912 0.076779202 0.29167837, 0.079998732 0.076717064 0.29169166, 0.079996198 0.076679721 0.29169601, 0.081367597 0.074437872 0.28803259, 0.081429124 0.075007424 0.2880277, 0.08153449 0.075582549 0.28790936, 0.081680059 0.076129958 0.28767818, 0.0818578 0.076617405 0.28734678, 0.082056046 0.077020809 0.28693855, 0.082180247 0.077217534 0.28666714, 0.09243086 0.079381451 0.27343521, 0.10649352 -0.032595292 0.20862906, 0.092709884 0.079281196 0.27327168, 0.10685077 -0.032574818 0.20852731, 0.092948198 0.079198107 0.27316749, 0.093106627 0.079155877 0.27312243, 0.09025915 0.077768549 0.27834678, 0.10414973 -0.033030435 0.21423377, 0.090586334 0.077524021 0.27809501, 0.10451207 -0.033050999 0.21410821, 0.11833251 0.10862182 0.21835153, 0.13599764 -0.032877997 0.13650708, 0.11868563 0.10867552 0.21826895, 0.13635576 -0.032865778 0.13640034, 0.13684089 -0.032616571 0.1345192, 0.11910701 0.10943545 0.21668296, 0.13711224 -0.032462493 0.13451041, 0.11946252 0.10947017 0.21658941, 0.13732158 -0.032397673 0.13450767, 0.11544551 0.10552056 0.224553, 0.13268761 -0.032591596 0.14466786, 0.11579859 0.10557412 0.22447048, 0.13304488 -0.032571092 0.14456618, 0.11621986 0.10633413 0.2228846, 0.13361785 -0.033026293 0.14227735, 0.11657535 0.1063688 0.22279105, 0.1339802 -0.033046797 0.14215213, 0.11255835 0.10241921 0.2307547, 0.12941328 -0.032592192 0.15266313, 0.11291137 0.10247286 0.23067203, 0.12977061 -0.032571569 0.1525615, 0.11333275 0.10323308 0.22908622, 0.13034351 -0.033026502 0.15027264, 0.11368823 0.10326754 0.22899286, 0.13070595 -0.033047125 0.15014727, 0.10967115 0.099318042 0.23695639, 0.126139 -0.03259249 0.16065817, 0.11002412 0.099371716 0.23687369, 0.12649627 -0.032572016 0.1605566, 0.11044554 0.10013171 0.23528793, 0.12706934 -0.033027098 0.15826805, 0.11080101 0.10016637 0.23519439, 0.12743178 -0.033047631 0.15814251, 0.106784 0.096216843 0.24315806, 0.12286484 -0.032592997 0.1686534, 0.10713717 0.096270338 0.24307527, 0.12322196 -0.032572582 0.16855162, 0.1075585 0.097030446 0.24148937, 0.12379509 -0.033027634 0.16626301, 0.10791388 0.097064987 0.24139576, 0.12415746 -0.033048049 0.16613746, 0.10389683 0.093115434 0.2493595, 0.11959067 -0.032593563 0.17664863, 0.10424992 0.093168959 0.24927689, 0.11994778 -0.032573089 0.17654684, 0.10467131 0.093929216 0.24769111, 0.12052083 -0.033027992 0.17425804, 0.10502683 0.093963876 0.24759768, 0.12088326 -0.033048466 0.17413263, 0.10100982 0.090014264 0.25556144, 0.11631632 -0.03259404 0.18464358, 0.10136296 0.090067849 0.2554785, 0.11667371 -0.032573566 0.1845419, 0.10178405 0.090827867 0.25389284, 0.11724654 -0.033028528 0.18225329, 0.10213962 0.090862468 0.25379914, 0.11760889 -0.033049062 0.18212777, 0.093122765 0.081524149 0.27249753, 0.10742389 -0.033030048 0.20623849, 0.093478292 0.081558689 0.27240396, 0.10778628 -0.033050522 0.2061132, 0.09889704 0.087726817 0.26009429, 0.11397247 -0.033029094 0.19024841, 0.099252507 0.087761447 0.2600008, 0.11433461 -0.033049449 0.19012305, 0.098122716 0.086913034 0.26176274, 0.11304212 -0.032594338 0.19263877, 0.098475754 0.0869665 0.26168025, 0.11339931 -0.032573894 0.19253708, 0.096010044 0.084625289 0.26629591, 0.11069806 -0.033029512 0.19824339, 0.096365422 0.084660068 0.26620236, 0.11106046 -0.033049956 0.19811785, 0.095235422 0.083811864 0.2679643, 0.10976787 -0.032594875 0.20063388, 0.09558855 0.08386533 0.26788178, 0.11012505 -0.03257446 0.20053218, 0.089461252 0.077609256 0.28036749, 0.10321935 -0.032595679 0.21662413, 0.08981438 0.07766287 0.28028488, 0.1035766 -0.032575265 0.21652235, 0.096447825 0.077379659 0.27745903, 0.096447825 0.077300742 0.27753627, 0.096447736 0.077206954 0.27759457, 0.096447825 0.077102348 0.27763045, 0.096525401 0.077396676 0.27744472, 0.096636251 0.077434137 0.2774314, 0.096797183 0.077360108 0.27760091, 0.096653193 0.077281371 0.27758303, 0.096778437 0.077440247 0.27752411, 0.09664166 0.077364221 0.27751645, 0.097055644 0.077335492 0.27777758, 0.09686859 0.077170447 0.27769399, 0.096991777 0.077420935 0.2777254, 0.096827626 0.077268705 0.27765834, 0.096919507 0.077636972 0.27746013, 0.096528172 0.077324554 0.27752244, 0.096670628 0.077187762 0.27763045, 0.097134203 0.077251121 0.27780569, 0.096917868 0.077069923 0.27770615, 0.096533284 0.077240989 0.27758157, 0.096693009 0.07708706 0.2776567, 0.0969733 0.076971874 0.27769315, 0.097223282 0.077172622 0.27780819, 0.096540183 0.077148095 0.27762213, 0.096719399 0.076983467 0.27766073, 0.096549153 0.077048853 0.27764297, 0.096749187 0.076881096 0.27764189, 0.096559256 0.076946869 0.27764335, 0.096570954 0.07684575 0.27762222, 0.096772552 0.077506229 0.27742922, 0.096921667 0.077576205 0.27756202, 0.096946239 0.077502653 0.27765226, 0.098399997 0.078531727 0.27859426, 0.098311067 0.078610227 0.27859181, 0.098232225 0.078694656 0.27856356, 0.098168299 0.07878004 0.27851158, 0.09812291 0.078861907 0.27843842, 0.098098308 0.078935131 0.27834827, 0.098096102 0.078996077 0.27824631, 0.098206162 0.079085752 0.27830732, 0.098206118 0.07901825 0.27841067, 0.098494411 0.079100892 0.27845472, 0.098343104 0.079112813 0.27839884, 0.098206118 0.078923002 0.27848935, 0.098494396 0.079021975 0.27853197, 0.098343208 0.079016939 0.27850595, 0.098494411 0.078927979 0.27858996, 0.098206162 0.078808531 0.2785356, 0.098494336 0.078823492 0.27862597, 0.098343134 0.07889317 0.27857983, 0.098343149 0.078753129 0.27861327, 0.098343134 0.078609332 0.27860332, 0.099793747 0.079100922 0.27845472, 0.099793807 0.079021975 0.27853179, 0.099793911 0.078927919 0.2785899, 0.099793807 0.078823552 0.27862597, 0.10005242 0.078477487 0.27868217, 0.10019672 0.078717276 0.27880877, 0.10025454 0.078672335 0.27889842, 0.10014963 0.078613028 0.27879596, 0.099978045 0.078504786 0.27864033, 0.1002007 0.078573421 0.27887487, 0.099914685 0.078810647 0.27864015, 0.099900693 0.078699842 0.2786496, 0.10017377 0.078491375 0.2788471, 0.10020715 0.078436896 0.27896553, 0.10016149 0.078409061 0.27881175, 0.10019302 0.078356966 0.27892673, 0.099998206 0.078677192 0.27868167, 0.099893227 0.078612044 0.27863944, 0.10029995 0.079016909 0.27862072, 0.10015337 0.079060778 0.2785334, 0.099984616 0.078589574 0.27866831, 0.1001049 0.078984454 0.27860171, 0.10023093 0.07894586 0.27867734, 0.10018975 0.078321204 0.27901369, 0.10006134 0.078561768 0.27871245, 0.10016793 0.078313753 0.2791152, 0.10016918 0.078857407 0.27871573, 0.10033795 0.078894541 0.27877927, 0.10026056 0.078812942 0.27880329, 0.099933207 0.078916356 0.27860689, 0.10011531 0.078444824 0.27874044, 0.10023679 0.078513965 0.27900138, 0.10032794 0.078760788 0.27890706, 0.10002527 0.078787401 0.27867794, 0.10020465 0.07839863 0.279055, 0.10019752 0.07840921 0.27917662, 0.10008025 0.078648314 0.27873039, 0.10042426 0.07895802 0.27873862, 0.099955529 0.079010978 0.27855101, 0.10029566 0.07860361 0.27904117, 0.10012601 0.07852833 0.27877328, 0.10041675 0.078833684 0.27890074, 0.10023487 0.078471527 0.27909684, 0.10025063 0.078490868 0.2792421, 0.1000613 0.078891739 0.27865064, 0.10037515 0.078679666 0.27907228, 0.10011804 0.078756437 0.27873361, 0.10051566 0.078887358 0.27887988, 0.10029349 0.078553542 0.27914822, 0.10032424 0.078554079 0.27930814, 0.099980205 0.079090014 0.27847543, 0.10047112 0.078738138 0.27909315, 0.10037193 0.078620061 0.27919543, 0.10041438 0.078595564 0.27937067, 0.10057816 0.078775868 0.2791028, 0.10046631 0.078667715 0.27923605, 0.10051617 0.078613028 0.27942693, 0.10057138 0.078693762 0.27926764, 0.099889725 0.078527346 0.27861428, 0.099729314 0.077842429 0.28005743, 0.099758908 0.077937946 0.28011888, 0.099812016 0.078019604 0.28018439, 0.099885643 0.078082815 0.28025046, 0.09997569 0.078124449 0.28031337, 0.10007745 0.078141704 0.28036916, 0.099916711 0.078073844 0.28041691, 0.099835962 0.078040883 0.28034061, 0.099769339 0.077984884 0.28026307, 0.099765137 0.078002229 0.28042498, 0.099708751 0.077953473 0.28033772, 0.09964253 0.07779713 0.28018594, 0.099517927 0.07784991 0.28036091, 0.099503651 0.077772424 0.28028274, 0.099667072 0.077883765 0.28025663, 0.099423781 0.077769682 0.28031117, 0.099343315 0.077773049 0.28032422, 0.10000756 0.078082547 0.28048831, 0.099833205 0.078027263 0.28051284, 0.099540606 0.077908799 0.28045243, 0.099431172 0.077843592 0.28039104, 0.0993433 0.077844307 0.28040481, 0.099909499 0.078028008 0.28059801, 0.099570334 0.077945605 0.28055239, 0.099442571 0.077898517 0.28048503, 0.09934327 0.07789661 0.28049913, 0.099605665 0.077959046 0.2806561, 0.099457398 0.077931598 0.28058755, 0.099343315 0.077927694 0.28060222, 0.099645257 0.077948228 0.28075916, 0.099474773 0.077941522 0.28069389, 0.099343315 0.077935651 0.28070951, 0.099343166 0.07792078 0.2808162, 0.099494204 0.077927932 0.28080061, 0.099693269 0.077817574 0.28012323, 0.099720851 0.077908859 0.28018919, 0.090176105 0.077773079 0.28032422, 0.09017624 0.077844366 0.28040475, 0.090176135 0.07789667 0.2804991, 0.090176135 0.077927664 0.28060222, 0.090176135 0.07793577 0.28070962, 0.090176135 0.07792075 0.28081608, 0.089599639 0.07787396 0.28090817, 0.089562446 0.077885583 0.28080451, 0.089529186 0.077872708 0.28069961, 0.089501292 0.077836469 0.280599, 0.089479953 0.077778414 0.28050733, 0.089466482 0.077701464 0.28042895, 0.089365527 0.078420594 0.27916694, 0.089337483 0.078306183 0.27918339, 0.089305043 0.078683421 0.27909106, 0.089238077 0.078681305 0.27914202, 0.089322001 0.078529552 0.27917671, 0.089374691 0.078533247 0.27912927, 0.090002194 0.078063056 0.27861685, 0.090030134 0.078177795 0.27860051, 0.090039253 0.078290269 0.27856284, 0.091438532 0.07745491 0.27766496, 0.091398031 0.077370003 0.27772391, 0.091344267 0.077280596 0.27776253, 0.091280222 0.0771911 0.27777886, 0.091209084 0.077106073 0.27777159, 0.090766802 0.077850863 0.27805781, 0.090693712 0.077682838 0.27810872, 0.090643704 0.07760106 0.27811044, 0.090398341 0.078159884 0.27826738, 0.090388432 0.078082845 0.27830714, 0.090341002 0.077923492 0.2783519, 0.090304047 0.077844575 0.27835596, 0.09124279 0.077079162 0.27775609, 0.091313839 0.077164337 0.27776337, 0.091377854 0.077253684 0.27774704, 0.091431603 0.077343091 0.27770853, 0.091472059 0.077428177 0.27764928, 0.091722772 0.077001259 0.2776565, 0.091501743 0.077058688 0.27769801, 0.091743261 0.077101842 0.2776477, 0.091540158 0.077145919 0.27769011, 0.091451794 0.076958731 0.27768457, 0.091695905 0.07688503 0.2776401, 0.091949612 0.077379659 0.27745914, 0.091782644 0.077367648 0.27750301, 0.091949582 0.077300712 0.27753627, 0.091773927 0.077288851 0.27756971, 0.091949612 0.077206746 0.27759442, 0.091760516 0.077199027 0.27761865, 0.091619298 0.077388808 0.27756459, 0.091949537 0.077102289 0.27763033, 0.091599867 0.077313617 0.27762234, 0.091573104 0.07723169 0.27766463, 0.093842357 0.082202151 0.27225292, 0.093842253 0.082123116 0.27233043, 0.093121737 0.081585869 0.27252495, 0.093117297 0.08165051 0.27254453, 0.093109697 0.08171688 0.27255547, 0.093089432 0.081833228 0.2725538, 0.093061298 0.08194454 0.27252579, 0.093026608 0.082044318 0.2724731, 0.09298712 0.082127407 0.27239907, 0.093453258 0.08194755 0.27244568, 0.093842253 0.08202906 0.27238843, 0.093842328 0.081924692 0.2724244, 0.10268101 0.082202211 0.27225304, 0.10268091 0.082123086 0.27233046, 0.10268098 0.082029149 0.2723884, 0.10268089 0.08192493 0.27242434, 0.10293993 0.081578627 0.27248073, 0.10294876 0.081663027 0.27251112, 0.10286103 0.081607416 0.27243721, 0.10286754 0.081692144 0.27246451, 0.10281397 0.08201839 0.27240369, 0.1027963 0.08191295 0.27243745, 0.10290736 0.081890032 0.27247405, 0.10278293 0.081801906 0.27244699, 0.10288101 0.081779763 0.27247804, 0.10296768 0.081749484 0.27252901, 0.10283527 0.082113162 0.27234769, 0.10294279 0.081994429 0.27244639, 0.10300562 0.081857577 0.27253234, 0.10285896 0.082192346 0.27227199, 0.1029852 0.082087383 0.27239716, 0.1030568 0.081958607 0.27251458, 0.10303268 0.082163945 0.27232838, 0.10311863 0.082047001 0.27247632, 0.10318767 0.082118109 0.27241981, 0.10277241 0.081629559 0.27241206, 0.1027759 0.081714287 0.27243698, 0.10296454 0.081243023 0.27416778, 0.10286289 0.081225529 0.27411151, 0.10277262 0.081184074 0.27404881, 0.10269922 0.081120655 0.273983, 0.10264593 0.081039175 0.2739175, 0.1026164 0.080943659 0.27385589, 0.10280386 0.081175014 0.27421522, 0.10272305 0.081141964 0.27413893, 0.10265666 0.081086084 0.27406186, 0.1026524 0.08110328 0.27422342, 0.10259594 0.081054732 0.2741363, 0.10252962 0.080898419 0.27398443, 0.10240522 0.08095111 0.27415931, 0.10239089 0.080873653 0.27408135, 0.10255417 0.080984965 0.27405488, 0.1023111 0.080870762 0.27410936, 0.10223047 0.080874369 0.27412274, 0.10289469 0.081183717 0.27428675, 0.10272048 0.081128523 0.2743113, 0.10242778 0.081010029 0.27425092, 0.10231808 0.080944851 0.27418962, 0.10223052 0.080945626 0.2742033, 0.10279675 0.081129089 0.27439645, 0.10245751 0.081046715 0.27435079, 0.1023297 0.080999568 0.27428338, 0.10223052 0.080997899 0.27429748, 0.10249287 0.081060246 0.27445459, 0.10234448 0.081032768 0.27438581, 0.10223037 0.081028864 0.27440089, 0.10253215 0.081049457 0.27455747, 0.10236196 0.081042752 0.27449262, 0.10223041 0.08103691 0.27450788, 0.10223052 0.081021801 0.27461469, 0.10238142 0.081028953 0.27459911, 0.10258029 0.080918834 0.27392167, 0.10260805 0.081010059 0.27398762, 0.10019198 0.080874279 0.27412269, 0.10019197 0.080945566 0.2742033, 0.10019203 0.08099784 0.27429736, 0.10019198 0.081028834 0.27440083, 0.10019197 0.081036881 0.274508, 0.10019204 0.081021801 0.27461457, 0.10009558 0.080842659 0.27410781, 0.10005234 0.080890313 0.27416673, 0.10000482 0.080879703 0.27417943, 0.099925175 0.08089681 0.27426922, 0.099923953 0.080941424 0.27437076, 0.099861354 0.080892578 0.27437222, 0.10005242 0.080971166 0.27428645, 0.099923939 0.080959275 0.27449635, 0.10005245 0.081012622 0.27442467, 0.10005233 0.081011072 0.27456915, 0.098919019 0.079483613 0.27332184, 0.098828286 0.079520836 0.27339354, 0.098748565 0.079537675 0.27348328, 0.098684758 0.079533353 0.27358621, 0.098592058 0.079260454 0.27319574, 0.098383516 0.079200581 0.27316356, 0.098353282 0.079280332 0.27327693, 0.098537341 0.079329833 0.27329624, 0.098699927 0.079412684 0.27333617, 0.098643392 0.079440191 0.2734243, 0.098145336 0.079300538 0.27361894, 0.09849681 0.079365686 0.27339637, 0.09877485 0.079357967 0.27325064, 0.098145381 0.079153225 0.27312696, 0.098306313 0.079325363 0.27358806, 0.098145425 0.079315528 0.27351248, 0.098316804 0.079333171 0.27348793, 0.098447964 0.079373702 0.27357852, 0.098145366 0.079307482 0.27340519, 0.098331183 0.079321042 0.27338949, 0.0981455 0.079276517 0.27330184, 0.098469302 0.079377994 0.27348614, 0.098145425 0.079224393 0.27320784, 0.098572463 0.079443708 0.27358869, 0.098604113 0.079448715 0.27350399, 0.093646973 0.079300568 0.27361917, 0.093647078 0.079315558 0.2735123, 0.093647018 0.079307511 0.27340505, 0.093647122 0.079276755 0.27330172, 0.093647122 0.079224452 0.27320778, 0.093647018 0.079153255 0.27312717, 0.093429178 0.079313919 0.27369249, 0.093419075 0.079343989 0.2735796, 0.093400687 0.079348072 0.2734637, 0.093374938 0.079325959 0.27335155, 0.093343943 0.079278365 0.27324882, 0.093308702 0.079208389 0.27316153, 0.093165517 0.079378679 0.27389336, 0.092779726 0.079359934 0.27330673, 0.093277469 0.079341248 0.27379832, 0.093142986 0.079437479 0.27380216, 0.093259335 0.079386309 0.27370846, 0.093105316 0.079477504 0.27370548, 0.093231797 0.07941328 0.27361524, 0.093054861 0.079496309 0.27360857, 0.093196005 0.079421565 0.2735219, 0.092993855 0.079493508 0.27351594, 0.092925429 0.079468653 0.2734319, 0.093146235 0.079407915 0.27341771, 0.092852831 0.079423562 0.27336097, 0.093081638 0.079363212 0.27331173, 0.093014091 0.079291031 0.27322662, 0.092940405 0.079505846 0.27404246, 0.092905834 0.079571262 0.27395213, 0.092680067 0.07967107 0.27412236, 0.092496961 0.079470262 0.27346551, 0.092229962 0.079547599 0.27364671, 0.092570677 0.079543933 0.2735163, 0.092302442 0.079631492 0.27369598, 0.092648044 0.079597756 0.27358514, 0.092382208 0.079693362 0.273763, 0.092724681 0.079628393 0.27366832, 0.092464745 0.079729453 0.27384427, 0.092544883 0.079737887 0.2739346, 0.092795357 0.079633996 0.27376068, 0.092618272 0.079717979 0.27402946, 0.092856586 0.079614535 0.27385652, 0.092727304 0.079599574 0.27420807, 0.090298757 0.080244556 0.27528548, 0.09036468 0.080324009 0.2753287, 0.090437531 0.080385372 0.27538779, 0.090513349 0.080425307 0.27545968, 0.090588689 0.080442145 0.27554071, 0.090659469 0.080434784 0.27562714, 0.090722382 0.080403551 0.2757144, 0.090770483 0.080355451 0.2757912, 0.090807095 0.08029072 0.27586204, 0.090666443 0.080418333 0.27575943, 0.090672851 0.080430076 0.27566019, 0.090622991 0.080445692 0.27564776, 0.090606749 0.080423459 0.27580202, 0.090354457 0.080386445 0.27542603, 0.09039484 0.080444947 0.2755779, 0.090479687 0.080444977 0.27552092, 0.090752482 0.080371425 0.27577892, 0.090744972 0.080355957 0.27582967, 0.090720296 0.080345705 0.27587605, 0.090681285 0.080342099 0.27591288, 0.090458006 0.080445692 0.27575862, 0.090482801 0.080455944 0.27571213, 0.090521902 0.080459401 0.27567554, 0.090570539 0.080455944 0.27565348, 0.14596061 -0.02437897 0.13916504, 0.14596529 -0.024377093 0.13914928, 0.14596941 -0.024378166 0.13913193, 0.14597364 -0.024384126 0.13910529, 0.1459756 -0.024390265 0.13908717, 0.09354113 -0.033620372 0.22818071, 0.079876766 0.075839147 0.29149014, 0.09355697 -0.033622667 0.22813359, 0.079891637 0.075861529 0.29145443, 0.093576863 -0.033618793 0.22809847, 0.07991527 0.075882807 0.29142267, 0.093594342 -0.03361316 0.22807752, 0.079946816 0.075901613 0.29139698, 0.093614593 -0.033606097 0.22806017, 0.093636647 -0.033598468 0.22804639, 0.079984501 0.07591708 0.29137868, 0.093669385 -0.03358908 0.22803299, 0.080026537 0.075928465 0.29136798, 0.093702182 -0.033582583 0.22802518, 0.079824805 0.076302752 0.29174751, 0.079840928 0.07632418 0.29171354, 0.079864994 0.076344058 0.29168385, 0.079896316 0.076361522 0.29165965, 0.079933271 0.076375738 0.29164225, 0.079974055 0.0763859 0.29163218, 0.079961404 0.076489434 0.29167813, 0.079921603 0.076482937 0.29168963, 0.079850495 0.076591536 0.29175752, 0.079854473 0.076463804 0.29173511, 0.07983005 0.076452002 0.29176682, 0.079825908 0.076588228 0.29178947, 0.079810455 0.076695129 0.2918213, 0.079808056 0.076584741 0.29182583, 0.079881147 0.076594427 0.29173142, 0.079885438 0.076474294 0.29170889, 0.079828754 0.076691911 0.29178637, 0.079916313 0.076596871 0.29171172, 0.07985352 0.076688752 0.2917555, 0.079955161 0.076598689 0.29169959, 0.07988368 0.076685891 0.29173034, 0.079824015 0.076834217 0.29178986, 0.079918295 0.076683417 0.29171157, 0.079842567 0.076822564 0.29175717, 0.079956293 0.076681301 0.29170007, 0.079912886 0.077110186 0.29161841, 0.079839528 0.076916322 0.29175657, 0.079867229 0.076811537 0.29172915, 0.079933867 0.077076212 0.29159278, 0.079857901 0.076899752 0.29172605, 0.079896912 0.076801285 0.29170662, 0.080042049 0.076992676 0.2915625, 0.080000505 0.077015743 0.29156405, 0.079882219 0.076883867 0.29170054, 0.079813242 0.076439366 0.29180312, 0.079963788 0.077044114 0.2915743, 0.079930902 0.076792285 0.29169023, 0.079911709 0.076869294 0.29168016, 0.07996811 0.076784894 0.2916804, 0.079945356 0.07685627 0.29166579, 0.079981983 0.076845571 0.2916581, 0.079955369 0.07718946 0.29154083, 0.079970673 0.07715483 0.29152137, 0.079984128 0.077228889 0.29148382, 0.080012873 0.077262118 0.29142368, 0.080026507 0.077221796 0.29140991, 0.079993159 0.077122107 0.2915071, 0.079998568 0.077191427 0.29146713, 0.080021933 0.077092335 0.29149827, 0.080020815 0.077155843 0.29145548, 0.080048636 0.077183709 0.29140085, 0.080077842 0.077149913 0.29139763, 0.080055699 0.077066913 0.29149574, 0.080049828 0.077123895 0.29144934, 0.080093101 0.077046946 0.29149902, 0.08008419 0.077097192 0.29144913, 0.080112889 0.077122197 0.29140007, 0.080122545 0.077076748 0.29145497, 0.080151901 0.077101573 0.29140788, 0.11848328 0.11858578 0.20878865, 0.11849694 0.11854531 0.20877489, 0.11851898 0.11850725 0.20876604, 0.11854826 0.11847354 0.20876281, 0.11858317 0.11844565 0.20876521, 0.11862217 0.11842532 0.20877299, 0.11903138 0.11873476 0.20818628, 0.11936794 0.11881305 0.20799747, 0.11906004 0.11870821 0.208207, 0.11934634 0.11884193 0.20797183, 0.12009449 0.11892633 0.20777075, 0.11967333 0.11903892 0.20778333, 0.11968133 0.11899538 0.20778653, 0.11880788 0.11857693 0.20846942, 0.11931022 0.11891709 0.20794316, 0.11969161 0.11895429 0.2077996, 0.11932686 0.11887722 0.20795365, 0.11900552 0.11876802 0.20817222, 0.11966808 0.11908524 0.20778967, 0.11877355 0.11860053 0.20845488, 0.11929782 0.11895965 0.20794165, 0.11898391 0.11880602 0.20816554, 0.11874263 0.11863102 0.20844588, 0.11928956 0.11900528 0.20794927, 0.11896753 0.11884709 0.20816658, 0.11871648 0.11866684 0.20844387, 0.11895664 0.118892 0.20817627, 0.11869685 0.11870624 0.20844814, 0.11868374 0.11875005 0.20846005, 0.11971779 0.11888675 0.2078499, 0.12008937 0.1189578 0.20774011, 0.11970404 0.11891751 0.20782086, 0.12008451 0.1189955 0.20771727, 0.12008066 0.11903732 0.20770301, 0.13619451 0.11994527 0.20588754, 0.13619849 0.11990346 0.2059017, 0.1362031 0.11986576 0.20592462, 0.13620842 0.11983432 0.20595537, 0.13705035 0.11975126 0.20621444, 0.1369075 0.11981632 0.20608307, 0.13692787 0.11985742 0.20607604, 0.13707559 0.11979045 0.20621218, 0.13653283 0.1200472 0.20590936, 0.13631454 0.12005495 0.2058865, 0.13701957 0.11971773 0.20622455, 0.13653135 0.12001716 0.20590131, 0.13688281 0.11978035 0.20609851, 0.13631463 0.12002499 0.20587884, 0.13722388 0.11980762 0.2064103, 0.13631468 0.11983739 0.20594917, 0.13631462 0.11986934 0.20591809, 0.136529 0.1199861 0.20589754, 0.13631456 0.11999427 0.2058761, 0.13721946 0.11977832 0.20639791, 0.13710204 0.11986311 0.20622553, 0.1365238 0.11994134 0.20590127, 0.13631468 0.1199498 0.20588063, 0.13698512 0.1196916 0.20624135, 0.13685519 0.11975141 0.20612137, 0.13651699 0.11989869 0.20591456, 0.13631459 0.11990736 0.20589483, 0.13721026 0.11974911 0.20638807, 0.13709393 0.11983298 0.20621742, 0.13650858 0.11986046 0.20593701, 0.13675193 0.12001644 0.20597841, 0.13694935 0.11967446 0.20626391, 0.13718915 0.11970823 0.20637833, 0.13649945 0.11982821 0.20596756, 0.13674928 0.11998637 0.2059692, 0.13716012 0.11967157 0.20637487, 0.13674466 0.11995541 0.20596446, 0.13712448 0.11964105 0.20637833, 0.13708466 0.11961852 0.2063875, 0.13673426 0.11991085 0.20596592, 0.13728291 0.11965059 0.20658587, 0.13672046 0.11986862 0.20597707, 0.13704364 0.1196052 0.20640215, 0.13670357 0.11983089 0.20599681, 0.13726014 0.11961196 0.20657168, 0.13695291 0.11996157 0.20609428, 0.13668494 0.11979987 0.20602454, 0.13694933 0.1199318 0.20608391, 0.1369427 0.11990117 0.20607765, 0.13710625 0.1198927 0.20623696, 0.13733701 0.11784388 0.20531334, 0.13742293 0.11776333 0.20547588, 0.13744605 0.11773618 0.20545314, 0.13652442 0.11799081 0.20482852, 0.13669068 0.11798634 0.20484307, 0.13735779 0.11781861 0.20528668, 0.13667271 0.11805658 0.20499755, 0.13683517 0.11803691 0.20503746, 0.13684832 0.11803241 0.20499636, 0.13731061 0.11786218 0.20534088, 0.13739365 0.11778416 0.20549761, 0.13667892 0.11805244 0.20495428, 0.13652438 0.11802162 0.20486055, 0.13639925 0.11798592 0.20483397, 0.13640104 0.11801727 0.20486616, 0.13727942 0.11787309 0.20536746, 0.13735937 0.11779793 0.20551778, 0.13723941 0.11786328 0.20510603, 0.13668828 0.1180165 0.20487522, 0.13666581 0.11805113 0.2050408, 0.13724515 0.11787562 0.20539214, 0.13732137 0.11780398 0.20553584, 0.13682084 0.11803247 0.20507835, 0.13652438 0.11804439 0.20489882, 0.13640408 0.11804058 0.20490421, 0.13722764 0.11789353 0.2051339, 0.13668428 0.11803885 0.20491268, 0.13652448 0.11805822 0.20494102, 0.13640797 0.11805497 0.20494638, 0.13721007 0.11791731 0.20516489, 0.13652442 0.11806245 0.20498528, 0.13641284 0.11805935 0.20499076, 0.13718782 0.11793359 0.20519699, 0.13716146 0.11794166 0.20522977, 0.13652442 0.11805661 0.20502926, 0.13641804 0.1180539 0.20503485, 0.13706933 0.11792441 0.20497848, 0.13713233 0.11794128 0.20526113, 0.13706034 0.11795439 0.20500837, 0.13704708 0.11797719 0.20504238, 0.13703018 0.11799179 0.2050792, 0.13700987 0.1179979 0.20511669, 0.13687305 0.11796658 0.20488867, 0.13698755 0.11799498 0.20515333, 0.13686764 0.11799632 0.20491992, 0.13685916 0.11801858 0.20495643, 0.13746159 0.11770381 0.20543064, 0.137372 0.11778744 0.20526133, 0.12027445 0.11707745 0.20665081, 0.12027632 0.11710863 0.20668283, 0.12027942 0.11713187 0.2067211, 0.12028325 0.11714627 0.20676324, 0.120288 0.11715074 0.2068077, 0.12029336 0.1171452 0.20685178, 0.11883534 0.11666195 0.2074554, 0.11905712 0.11679114 0.20720135, 0.11884622 0.116699 0.20748171, 0.11867271 0.11652245 0.20773187, 0.11868453 0.11656065 0.20775627, 0.1190667 0.11682685 0.20722958, 0.11886571 0.11672999 0.20751134, 0.11870575 0.11659332 0.20778249, 0.11908388 0.11685582 0.20726155, 0.11889262 0.11675273 0.20754182, 0.11873506 0.11661865 0.20780912, 0.11910708 0.11687629 0.20729631, 0.11892535 0.11676632 0.20757216, 0.11877118 0.11663522 0.20783427, 0.11881195 0.11664225 0.20785645, 0.11896227 0.11677028 0.2076005, 0.11978875 0.11701877 0.20676002, 0.11979398 0.11705132 0.20679106, 0.11980264 0.11707623 0.20682809, 0.11981428 0.11709209 0.20686901, 0.1198283 0.11709808 0.20691144, 0.11984394 0.11709382 0.20695391, 0.11937657 0.1169173 0.20695497, 0.11938439 0.1169516 0.20698479, 0.11939788 0.11697839 0.20701961, 0.119416 0.11699639 0.20705788, 0.11943804 0.11700465 0.2070972, 0.11946273 0.1170028 0.20713602, 0.11913541 0.11688735 0.20733126, 0.11916724 0.11688815 0.20736463, 0.0821224 0.077261284 0.28624249, 0.082134157 0.077299491 0.28626704, 0.082155421 0.077332243 0.28629339, 0.082184836 0.077357545 0.28631961, 0.082220897 0.077374205 0.28634471, 0.082261711 0.07738103 0.28636706, 0.081256256 0.075153813 0.28778142, 0.081175908 0.074540153 0.28781015, 0.081174731 0.074537322 0.28785908, 0.081256256 0.075161263 0.28782925, 0.081461057 0.075815544 0.28777462, 0.08143039 0.075810269 0.28773987, 0.081408367 0.075800315 0.28769964, 0.081396043 0.075786576 0.28765655, 0.081394181 0.075769618 0.28761268, 0.081650838 0.076405749 0.28745288, 0.081621051 0.076395378 0.28742081, 0.081598982 0.076379433 0.28738505, 0.081585363 0.076358572 0.28734732, 0.081581414 0.076333866 0.28730917, 0.081935272 0.076953188 0.28698951, 0.081901118 0.076944843 0.28696454, 0.081872255 0.076929942 0.28693688, 0.081850082 0.076908961 0.2869072, 0.081835136 0.076882705 0.28687653, 0.081828669 0.076851919 0.2868464, 0.082140312 0.077222213 0.28665096, 0.082103014 0.077219173 0.28663123, 0.082069859 0.077208653 0.28660828, 0.082041726 0.077191427 0.28658378, 0.082019433 0.077168092 0.28655797, 0.082003817 0.077139691 0.28653228, 0.081995711 0.07710655 0.28650701, 0.081279054 0.074518606 0.28801471, 0.081239209 0.074523762 0.2879869, 0.08120738 0.074528798 0.28795034, 0.081185415 0.074533448 0.28790659, 0.081320956 0.075169399 0.28795516, 0.081289589 0.075169191 0.28791839, 0.08126767 0.075166419 0.28787577, 0.14875109 -0.034655407 0.13452725, 0.14864624 -0.034602359 0.13447408, 0.14871965 -0.03463079 0.1345026, 0.14868513 -0.034613803 0.13448536, 0.14877655 -0.034687504 0.13455932, 0.14861411 -0.034597322 0.13446914, 0.14879054 -0.034718558 0.1345903, 0.14879747 -0.034771279 0.134643, 0.14878304 -0.034835622 0.13470738, 0.14672211 -0.035142735 0.1404292, 0.14667323 -0.035196677 0.14039034, 0.14664467 -0.035234496 0.14034955, 0.1466298 -0.035261348 0.14030768, 0.14662512 -0.035278842 0.14026754, 0.14662765 -0.035289243 0.14023091, 0.14663465 -0.035294369 0.14019875, 0.14679819 -0.035069153 0.14045849, 0.11384383 0.10833822 0.21952254, 0.1137768 0.10839291 0.21953776, 0.11373666 0.10843633 0.21953636, 0.11371063 0.10847326 0.21952648, 0.11369276 0.10850807 0.21950999, 0.11368176 0.10854243 0.21948689, 0.11367682 0.10857664 0.21945733, 0.11367843 0.10860996 0.21942191, 0.11368996 0.10865279 0.21936634, 0.1137092 0.10868911 0.21930893, 0.11286297 -0.033299163 0.22298278, 0.14695381 -0.033530459 0.14036216, 0.14693902 -0.033495888 0.14030708, 0.14693601 -0.033467934 0.14024071, 0.1469797 -0.033571705 0.14040802, 0.14701469 -0.033616707 0.14044122, 0.1470557 -0.033662125 0.14046107, 0.14707859 -0.033685252 0.1404659, 0.14653392 -0.02875109 0.13659251, 0.14658152 -0.028756425 0.13654014, 0.14663999 -0.028762981 0.13650075, 0.14670612 -0.028770342 0.13647592, 0.14883932 -0.034680262 0.1346373, 0.14887877 -0.034571722 0.13463728, 0.14890006 -0.034577981 0.13470078, 0.14885952 -0.034689024 0.13470064, 0.14881511 -0.034732178 0.13463728, 0.1488349 -0.034742162 0.13470082, 0.14875467 -0.034534886 0.13450257, 0.14877349 -0.03438811 0.13449733, 0.14883012 -0.034394428 0.13453308, 0.14882655 -0.034556225 0.13455932, 0.14878948 -0.034658745 0.1345592, 0.14867933 -0.034512416 0.13447398, 0.14871053 -0.034381077 0.1344749, 0.14872046 -0.034629032 0.13450257, 0.14864832 -0.03459774 0.13447396, 0.14893493 -0.0344062 0.13470083, 0.14887734 -0.034399822 0.13458054, 0.14891286 -0.034403726 0.13463728, 0.14895017 -0.034270123 0.13470082, 0.14892824 -0.03426753 0.13463728, 0.14889258 -0.034263685 0.13458054, 0.14884533 -0.034258321 0.13453287, 0.14878899 -0.034252003 0.13449721, 0.14872581 -0.03424494 0.13447504, 0.14915794 -0.033366606 0.13453303, 0.14945513 -0.032995537 0.13453297, 0.14948858 -0.033029273 0.13458031, 0.149198 -0.033391878 0.1345803, 0.14899592 -0.033810422 0.13458028, 0.14902972 -0.033822283 0.13463727, 0.14922827 -0.033411101 0.13463728, 0.14937025 -0.032910272 0.13447504, 0.14976412 -0.032598183 0.13447504, 0.14979763 -0.032652035 0.13449723, 0.14941496 -0.032955334 0.13449733, 0.14910965 -0.033336326 0.13449708, 0.14895125 -0.033794776 0.13453299, 0.14905608 -0.033302501 0.13447504, 0.14889745 -0.03377597 0.1344972, 0.14883763 -0.03375499 0.13447504, 0.1495294 -0.033070251 0.13470094, 0.14988352 -0.032789841 0.13470083, 0.14951375 -0.033054486 0.13463725, 0.14987177 -0.032770947 0.13463728, 0.14924695 -0.033422843 0.13470072, 0.14985289 -0.032740608 0.13458031, 0.14905061 -0.033829644 0.13470083, 0.14982776 -0.032700345 0.13453296, 0.15661427 -0.028595462 0.13470089, 0.15660253 -0.028576687 0.13463748, 0.15658352 -0.028546229 0.13458049, 0.15655859 -0.028506055 0.13453309, 0.15652832 -0.028457657 0.1344974, 0.15649493 -0.028403953 0.13447516, 0.1568404 -0.027907506 0.1344751, 0.15685603 -0.02775307 0.13447505, 0.15679391 -0.028055534 0.13447498, 0.15675774 -0.028456345 0.1346373, 0.15673313 -0.028430536 0.13458067, 0.15685627 -0.028287068 0.13458061, 0.15670046 -0.028396145 0.13453305, 0.15681741 -0.028259888 0.13453329, 0.15690443 -0.02810289 0.13453317, 0.15677056 -0.028227344 0.1344974, 0.1568521 -0.028080478 0.13449728, 0.15690245 -0.027920321 0.13449763, 0.15691949 -0.027753159 0.13449763, 0.15677291 -0.028472468 0.13470092, 0.15688559 -0.028307453 0.13463748, 0.15694818 -0.028121665 0.13458055, 0.15695828 -0.027931735 0.13453314, 0.15697634 -0.0277531 0.13453302, 0.15690377 -0.028320149 0.13470101, 0.15698096 -0.028135791 0.13463748, 0.15700474 -0.027941301 0.13458061, 0.15702395 -0.027753189 0.13458069, 0.15700135 -0.028144494 0.13470078, 0.15703972 -0.027948514 0.13463746, 0.15705961 -0.0277531 0.13463733, 0.15706144 -0.027952954 0.13470091, 0.15708178 -0.0277531 0.13470098, 0.15661749 -0.028309003 0.13447511, 0.15666115 -0.028354868 0.13449726, 0.1567187 -0.028191224 0.13447529, 0.15685599 -0.023808137 0.13447523, 0.15691929 -0.023808196 0.13449752, 0.15697633 -0.023808137 0.13453311, 0.15702383 -0.023808137 0.13458073, 0.15705952 -0.023808196 0.13463764, 0.15708166 -0.023808137 0.13470115, 0.15566109 -0.021582618 0.13463765, 0.15612952 -0.021876946 0.13463748, 0.1561072 -0.021904811 0.13458076, 0.15513097 -0.021434739 0.13458079, 0.15458922 -0.021421209 0.13453305, 0.15458925 -0.021373734 0.1345807, 0.15512051 -0.021480963 0.13453332, 0.15564562 -0.021614835 0.13458076, 0.15562497 -0.021657661 0.13453329, 0.15673982 -0.022772387 0.13453305, 0.15691639 -0.023277089 0.13453308, 0.15686096 -0.023289725 0.13449755, 0.15668862 -0.022797123 0.1344974, 0.15567066 -0.021562621 0.13470092, 0.15614332 -0.021859512 0.13470104, 0.15641104 -0.022355393 0.1344977, 0.15663148 -0.02282469 0.13447526, 0.15636145 -0.02239491 0.13447547, 0.15513891 -0.0213999 0.13463773, 0.15458921 -0.021337911 0.13463764, 0.15600264 -0.02203612 0.13447525, 0.15514395 -0.021378204 0.13470112, 0.15458928 -0.021315828 0.13470125, 0.15699762 -0.023258492 0.13463755, 0.15696277 -0.023266479 0.13458058, 0.15678264 -0.022751853 0.13458076, 0.15645553 -0.022319838 0.13453326, 0.15604204 -0.02198641 0.13449754, 0.15701926 -0.023253605 0.13470115, 0.15557264 -0.021765962 0.13447529, 0.15681489 -0.022736415 0.13463756, 0.15458928 -0.021541491 0.13447529, 0.15649267 -0.022290334 0.1345807, 0.15607752 -0.021941945 0.13453332, 0.15560032 -0.021708891 0.13449743, 0.15683486 -0.022726819 0.13470116, 0.15509365 -0.021598354 0.13447529, 0.15652062 -0.022267982 0.13463745, 0.15679909 -0.023303792 0.13447526, 0.15510778 -0.021536484 0.13449758, 0.15458919 -0.021477982 0.13449755, 0.15653805 -0.022254243 0.13470113, 0.14827542 -0.021541521 0.13447525, 0.14827557 -0.021478161 0.13449757, 0.14827539 -0.021421239 0.13453333, 0.14827546 -0.021373704 0.13458073, 0.14827545 -0.021338001 0.13463776, 0.14827548 -0.021315768 0.13470109, 0.14723179 -0.021608725 0.13458073, 0.14774047 -0.02143319 0.13458087, 0.14775099 -0.021479532 0.13453333, 0.14725222 -0.02165176 0.13453333, 0.1468033 -0.02192919 0.1345333, 0.14647061 -0.022334561 0.13449743, 0.1464266 -0.022298649 0.1345333, 0.14638972 -0.022268519 0.13458076, 0.1472766 -0.021703109 0.13449769, 0.14683844 -0.021973893 0.13449757, 0.14772792 -0.021376714 0.13470106, 0.14773272 -0.021398321 0.13463767, 0.14721651 -0.021576479 0.1346377, 0.14677407 -0.021891639 0.13458078, 0.14720698 -0.021556452 0.13470112, 0.1467521 -0.021863803 0.13463755, 0.14636205 -0.022245899 0.13463767, 0.14673838 -0.021846309 0.13470107, 0.14634489 -0.022231922 0.13470103, 0.14777747 -0.021596923 0.13447535, 0.14776348 -0.021535054 0.1344976, 0.14730372 -0.02176027 0.13447528, 0.14687766 -0.022023961 0.13447528, 0.14651963 -0.022374645 0.13447541, 0.13831529 -0.03245987 0.13447082, 0.13831221 -0.032395974 0.13448013, 0.13830726 -0.032300547 0.13450791, 0.13831109 -0.032256648 0.13452408, 0.13832636 -0.032200292 0.13454299, 0.13851343 -0.031852975 0.13464476, 0.13753511 -0.032524362 0.13446771, 0.13663892 -0.032975987 0.1344756, 0.13658638 -0.032937393 0.13449918, 0.13687418 -0.032657519 0.13449074, 0.13691004 -0.032701448 0.13447325, 0.13709258 -0.032525554 0.13448729, 0.13711616 -0.032572404 0.13447261, 0.13731109 -0.032448903 0.13448562, 0.13732284 -0.032497868 0.13447234, 0.13733499 -0.032548085 0.13446768, 0.13644169 -0.033244058 0.1344756, 0.13638894 -0.033205375 0.13449921, 0.13636182 -0.033291385 0.13448979, 0.13632987 -0.033252969 0.13451113, 0.14553995 -0.024834856 0.14008865, 0.14595599 -0.024325356 0.13921282, 0.14555506 -0.024780586 0.14012742, 0.14597072 -0.024271473 0.13925102, 0.14597563 -0.024338081 0.13906813, 0.14598651 -0.024278387 0.1390681, 0.14600904 -0.024222299 0.13906828, 0.14597563 -0.024337932 0.13676777, 0.14598651 -0.024278358 0.13676775, 0.14600883 -0.024222121 0.13676766, 0.14604802 -0.024176314 0.13670099, 0.14598943 -0.024358347 0.13667506, 0.14600043 -0.024282381 0.13667515, 0.14603144 -0.024212107 0.13667516, 0.14606537 -0.024190381 0.13663769, 0.14603452 -0.024326131 0.13659146, 0.14609303 -0.024212912 0.13658082, 0.14605255 -0.024263456 0.13659132, 0.14612989 -0.024243042 0.13653329, 0.14609833 -0.02435948 0.13652509, 0.14610527 -0.024312481 0.13652501, 0.14612435 -0.024269149 0.13652501, 0.14617391 -0.024278954 0.13649762, 0.14618295 -0.024347916 0.1364824, 0.14622299 -0.024319097 0.13647535, 0.1461899 -0.024323985 0.13648249, 0.14714424 -0.023190811 0.13647544, 0.14709513 -0.023150757 0.1364975, 0.14705108 -0.023114756 0.13653326, 0.14701416 -0.023084745 0.13658074, 0.1469865 -0.023062065 0.13663751, 0.14696936 -0.023048088 0.13670102, 0.1473196 -0.02278538 0.13658071, 0.14770377 -0.022603348 0.13653328, 0.14768343 -0.022560492 0.13658071, 0.14851262 -0.022337958 0.1366376, 0.1480877 -0.022421047 0.13658068, 0.14851259 -0.022373632 0.13658071, 0.1480798 -0.022386149 0.13663757, 0.14766803 -0.022528097 0.13663761, 0.14742316 -0.022917494 0.13647547, 0.14738405 -0.022867545 0.13649733, 0.14772819 -0.022654787 0.13649756, 0.14734904 -0.022822753 0.13653314, 0.14809804 -0.02246727 0.13653326, 0.14851262 -0.022421166 0.13653317, 0.14775537 -0.022712186 0.13647532, 0.14811063 -0.022522762 0.13649757, 0.14851265 -0.022477999 0.1364975, 0.14812456 -0.022584632 0.13647532, 0.14851268 -0.022541389 0.13647553, 0.14728381 -0.022739694 0.13670102, 0.14729755 -0.022757187 0.13663757, 0.1476586 -0.02250801 0.13670102, 0.14807491 -0.022364452 0.13670099, 0.14851262 -0.022315726 0.13670102, 0.1540892 -0.022541538 0.13647538, 0.15408932 -0.022478059 0.13649756, 0.15408911 -0.022421166 0.13653329, 0.1540892 -0.022373632 0.13658077, 0.1540892 -0.022337988 0.13663745, 0.15408911 -0.022315666 0.13670126, 0.15450911 -0.022468463 0.13653326, 0.15451975 -0.02242218 0.13658056, 0.15602382 -0.024308309 0.13658074, 0.15592898 -0.023888394 0.13653329, 0.15597634 -0.02430822 0.13653314, 0.15597539 -0.023877755 0.13658065, 0.15492855 -0.022565201 0.13658077, 0.15452766 -0.02238737 0.13663746, 0.15578939 -0.02348952 0.13653329, 0.1558322 -0.023468927 0.13658075, 0.15494408 -0.022533044 0.13663748, 0.15568094 -0.023541585 0.13647532, 0.15547061 -0.023206756 0.13647546, 0.1555201 -0.023167178 0.13649753, 0.15573816 -0.023514107 0.1364975, 0.15531765 -0.022767797 0.13663769, 0.15495364 -0.022513047 0.13670099, 0.15533136 -0.022750393 0.13670117, 0.15587358 -0.023900881 0.13649768, 0.15591948 -0.02430822 0.13649726, 0.15585615 -0.024308309 0.13647518, 0.15581168 -0.023915097 0.13647547, 0.15564698 -0.02306582 0.13670118, 0.15449642 -0.022523895 0.13649732, 0.15490793 -0.022608057 0.13653332, 0.15529542 -0.022795752 0.13658047, 0.15562966 -0.023079678 0.13663761, 0.15448238 -0.022585735 0.13647547, 0.1558844 -0.023443744 0.13670102, 0.15488328 -0.022659346 0.13649753, 0.15526573 -0.022832826 0.13653314, 0.15560175 -0.02310209 0.13658062, 0.15586449 -0.02345334 0.13663754, 0.15485573 -0.022716388 0.13647534, 0.15603183 -0.023864821 0.13670099, 0.15608184 -0.02430822 0.13670099, 0.15523033 -0.02287735 0.1364975, 0.15556456 -0.023131654 0.13653329, 0.15453249 -0.022365585 0.13670106, 0.1560102 -0.023869887 0.13663745, 0.15605955 -0.02430822 0.13663745, 0.15519069 -0.022926882 0.13647544, 0.15585597 -0.027197883 0.13647522, 0.15591958 -0.027198002 0.13649729, 0.15597634 -0.027197942 0.13653301, 0.15602379 -0.027197942 0.13658069, 0.15605956 -0.027197972 0.13663745, 0.15608174 -0.027197972 0.13670075, 0.14717261 -0.03330116 0.13670173, 0.14716583 -0.033277586 0.13663511, 0.14715439 -0.033237413 0.13657372, 0.14713864 -0.033182785 0.13652351, 0.14712043 -0.033118799 0.13648868, 0.14710446 -0.033063069 0.13647252, 0.15577298 -0.0279174 0.13670075, 0.15561417 -0.028040275 0.13670072, 0.15590386 -0.02776508 0.13670079, 0.15590243 -0.027365103 0.13649736, 0.15595812 -0.027376547 0.13653314, 0.15590447 -0.027547792 0.13653314, 0.15600467 -0.027386084 0.13658053, 0.15594801 -0.027566537 0.13658044, 0.15585628 -0.027731881 0.13658068, 0.15598089 -0.027580634 0.13663745, 0.15588561 -0.027752444 0.13663748, 0.1556024 -0.02802147 0.13663745, 0.15575768 -0.027901337 0.13663746, 0.15558347 -0.027991042 0.13658056, 0.15584031 -0.027352378 0.13647512, 0.15585214 -0.027525321 0.13649726, 0.15581721 -0.027704731 0.13653302, 0.15573302 -0.027875289 0.13658068, 0.15555841 -0.027950779 0.13653302, 0.15579388 -0.027500317 0.13647524, 0.1557706 -0.027672186 0.13649726, 0.15570039 -0.027840987 0.13653302, 0.15552825 -0.027902499 0.13649726, 0.15571859 -0.027636096 0.13647512, 0.15566112 -0.027799711 0.13649727, 0.1554947 -0.027848676 0.1364751, 0.15561751 -0.027753815 0.13647518, 0.15606135 -0.027397826 0.13670081, 0.15603957 -0.027393267 0.13663754, 0.15600127 -0.027589336 0.13670087, 0.14794858 -0.035288379 0.1402344, 0.14794858 -0.035266235 0.1402977, 0.14794865 -0.035230532 0.14035445, 0.14794861 -0.035183176 0.14040209, 0.14794858 -0.035126135 0.14043789, 0.14794867 -0.035062835 0.14045997, 0.14888293 -0.034629151 0.14023438, 0.14886208 -0.03462176 0.1402977, 0.14893484 -0.034406468 0.14023438, 0.14891274 -0.034403965 0.1402977, 0.14868636 -0.034787729 0.14040218, 0.14878362 -0.034593746 0.14040217, 0.14873017 -0.034574732 0.14043783, 0.14863892 -0.034756139 0.14043789, 0.14871056 -0.034381315 0.14046006, 0.1487257 -0.034814045 0.14035456, 0.14882834 -0.03460975 0.14035456, 0.14847405 -0.034854338 0.14046006, 0.14858621 -0.034721062 0.14045998, 0.14875562 -0.034833953 0.14029782, 0.14851741 -0.034900412 0.14043792, 0.14877395 -0.034846172 0.14023443, 0.14855655 -0.034941986 0.14040212, 0.14834876 -0.034949735 0.14046006, 0.14858915 -0.034976527 0.14035456, 0.14838178 -0.035003617 0.14043777, 0.14861365 -0.035002515 0.1402977, 0.14841157 -0.035052225 0.14040217, 0.14862874 -0.035018697 0.14023435, 0.14820944 -0.035016522 0.14045997, 0.14843638 -0.035092786 0.14035456, 0.14823101 -0.035076126 0.14043774, 0.14845498 -0.035123184 0.1402977, 0.14825031 -0.035129443 0.14040214, 0.14867038 -0.034553453 0.14045998, 0.14846654 -0.035142109 0.1402344, 0.14877351 -0.034388348 0.14043777, 0.14826649 -0.035174057 0.1403546, 0.14883 -0.034394726 0.14040211, 0.14827858 -0.035207734 0.1402979, 0.1488774 -0.034400061 0.14035468, 0.14828618 -0.035228565 0.14023428, 0.14872581 -0.03424494 0.14046004, 0.14878888 -0.034252092 0.14043801, 0.14884534 -0.034258321 0.14040214, 0.1488926 -0.034263656 0.14035468, 0.14892808 -0.034267619 0.14029771, 0.14895006 -0.034270123 0.1402344, 0.1489512 -0.033794895 0.14040202, 0.14915796 -0.033366725 0.14040212, 0.14910963 -0.033336416 0.14043796, 0.14889748 -0.033776119 0.14043789, 0.14952937 -0.0330704 0.14023441, 0.14988348 -0.032789841 0.14023447, 0.1495138 -0.033054635 0.14029782, 0.14976414 -0.032598302 0.14046012, 0.14922825 -0.033411101 0.14029771, 0.14948852 -0.033029243 0.14035468, 0.14919801 -0.033392027 0.14035456, 0.14899595 -0.033810571 0.14035456, 0.14924712 -0.033423021 0.1402344, 0.14902967 -0.033822343 0.14029786, 0.14905055 -0.033829734 0.1402344, 0.14937016 -0.032910421 0.14046001, 0.14979759 -0.032652095 0.1404379, 0.14941485 -0.032955214 0.14043801, 0.14982763 -0.032700256 0.14040214, 0.14905603 -0.033302471 0.14046, 0.14945515 -0.032995626 0.14040212, 0.14985283 -0.032740667 0.14035468, 0.14883764 -0.033755139 0.14046006, 0.14987177 -0.032771036 0.14029786, 0.15649492 -0.028404132 0.14046012, 0.15652838 -0.028457806 0.14043798, 0.15655844 -0.028506085 0.14040211, 0.15658373 -0.028546467 0.14035456, 0.15660244 -0.028576717 0.14029787, 0.15661412 -0.028595552 0.14023446, 0.15706149 -0.027953014 0.14023434, 0.15708181 -0.027753279 0.14023457, 0.15705961 -0.027753249 0.14029785, 0.15700127 -0.028144613 0.14023459, 0.15666118 -0.028354928 0.14043786, 0.15670043 -0.028396234 0.14040206, 0.15681738 -0.028260008 0.14040212, 0.15673319 -0.028430626 0.14035453, 0.15685628 -0.028287098 0.1403546, 0.15694803 -0.028121844 0.14035462, 0.1568858 -0.028307572 0.14029782, 0.15698105 -0.028135881 0.14029787, 0.15703979 -0.027948603 0.14029782, 0.1570237 -0.027753219 0.14035462, 0.15661758 -0.028309122 0.14046012, 0.1567706 -0.028227523 0.14043796, 0.15690443 -0.028103039 0.14040215, 0.15700464 -0.027941361 0.14035469, 0.15697622 -0.02775313 0.14040209, 0.15671867 -0.028191343 0.14046012, 0.15685222 -0.028080627 0.14043792, 0.15695816 -0.027931914 0.14040209, 0.15691949 -0.027753159 0.14043799, 0.15679398 -0.028055713 0.14046003, 0.15690246 -0.02792035 0.14043795, 0.15685603 -0.027753189 0.14046012, 0.15684023 -0.027907595 0.14046, 0.15677306 -0.028472587 0.14023431, 0.15675783 -0.028456643 0.14029782, 0.15690388 -0.028320268 0.14023453, 0.15708175 -0.023808315 0.14023459, 0.15705957 -0.023808286 0.14029793, 0.15702379 -0.023808286 0.14035478, 0.15697618 -0.023808196 0.1404023, 0.15691936 -0.023808286 0.14043811, 0.15685591 -0.023808315 0.14046025, 0.15560016 -0.02170898 0.14043802, 0.1560775 -0.021942005 0.14040235, 0.15562493 -0.021657571 0.14040248, 0.1560421 -0.021986529 0.14043799, 0.15512036 -0.021481201 0.14040211, 0.15458934 -0.021373793 0.14035484, 0.15458916 -0.021421358 0.14040235, 0.15678266 -0.022752002 0.14035475, 0.15696265 -0.023266569 0.1403548, 0.15699747 -0.023258582 0.14029789, 0.15513112 -0.021434918 0.14035481, 0.15681499 -0.022736475 0.14029786, 0.15564559 -0.021614954 0.14035466, 0.15557268 -0.021765962 0.14046031, 0.15600249 -0.02203609 0.14046031, 0.15652058 -0.022268072 0.14029801, 0.15683499 -0.022726908 0.14023459, 0.15653801 -0.022254273 0.14023468, 0.15510769 -0.021536604 0.14043814, 0.15458913 -0.021478191 0.14043814, 0.15614328 -0.021859661 0.14023465, 0.15509371 -0.021598563 0.14046028, 0.15458928 -0.02154164 0.14046028, 0.1568609 -0.023289725 0.14043812, 0.15691641 -0.023277119 0.14040232, 0.15673992 -0.022772625 0.14040232, 0.15649267 -0.022290424 0.1403548, 0.15612933 -0.021876946 0.14029789, 0.15679912 -0.023303881 0.14046033, 0.1556706 -0.02156271 0.14023465, 0.15668866 -0.022797361 0.14043814, 0.15645549 -0.022320047 0.14040238, 0.15610707 -0.02190499 0.14035466, 0.155661 -0.021582618 0.14029789, 0.15663147 -0.022824809 0.14046016, 0.15514378 -0.021378323 0.14023456, 0.15458922 -0.021315798 0.14023462, 0.15641105 -0.022355422 0.14043811, 0.15701914 -0.023253724 0.1402345, 0.15513892 -0.02139999 0.14029801, 0.15458913 -0.021338001 0.14029795, 0.15636134 -0.02239494 0.14046016, 0.14827539 -0.021315917 0.14023462, 0.14827536 -0.02133806 0.14029795, 0.1482753 -0.021373823 0.14035463, 0.14827554 -0.021421447 0.14040232, 0.14827538 -0.021478191 0.14043809, 0.14827554 -0.02154173 0.14046013, 0.14725207 -0.0216517 0.1404025, 0.14775094 -0.021479741 0.1404023, 0.14774053 -0.021433368 0.14035463, 0.14723177 -0.021608874 0.14035466, 0.14677407 -0.021891937 0.14035478, 0.14636199 -0.022246018 0.14029801, 0.14638977 -0.022268668 0.14035481, 0.14721648 -0.021576658 0.14029789, 0.14675207 -0.021863803 0.1402978, 0.14777739 -0.021597013 0.14046022, 0.14776351 -0.021535143 0.14043811, 0.14727642 -0.021703228 0.14043811, 0.14680327 -0.021929368 0.14040235, 0.14642648 -0.022298649 0.14040244, 0.14730377 -0.021760449 0.14046022, 0.14683835 -0.021974042 0.14043796, 0.14647056 -0.02233468 0.14043823, 0.14687754 -0.022024021 0.14046016, 0.14651968 -0.022374734 0.14046016, 0.14772789 -0.021376863 0.14023447, 0.14773276 -0.021398559 0.14029782, 0.14720698 -0.021556541 0.14023456, 0.14673834 -0.021846309 0.14023453, 0.14634486 -0.022232041 0.14023444, 0.096795768 -0.032610998 0.22426584, 0.11223689 -0.032611504 0.22426564, 0.096724048 -0.032861874 0.22400995, 0.1123212 -0.032861874 0.22400968, 0.1268595 -0.033296391 0.16084342, 0.12685943 -0.032666191 0.16047975, 0.12656246 -0.0332966 0.16087563, 0.12685943 -0.033256695 0.16073433, 0.12654026 -0.033257827 0.16076981, 0.12685938 -0.033192739 0.1606373, 0.12652062 -0.03319566 0.16067596, 0.12685941 -0.033108249 0.1605577, 0.12650453 -0.033113286 0.16059823, 0.1268594 -0.033007696 0.16049951, 0.12649249 -0.033015177 0.16054101, 0.12685946 -0.032896534 0.16046625, 0.12648545 -0.032906219 0.16050704, 0.12685952 -0.032780543 0.1604597, 0.12648372 -0.032792255 0.16049822, 0.12648755 -0.032678887 0.16051486, 0.13602659 -0.033296332 0.16084342, 0.13602659 -0.033256575 0.16073428, 0.13602662 -0.033192858 0.16063733, 0.13602658 -0.033108279 0.1605576, 0.13602671 -0.033007756 0.1604995, 0.13602661 -0.032896474 0.16046619, 0.13602646 -0.032780513 0.16045973, 0.1360267 -0.032666132 0.16047964, 0.13609436 -0.032906875 0.16046081, 0.13617107 -0.032924429 0.1604387, 0.13609229 -0.032793 0.16045183, 0.13616559 -0.032813922 0.16042666, 0.13624397 -0.032842264 0.1603813, 0.13617039 -0.03270267 0.1604373, 0.13624677 -0.032734051 0.16038482, 0.13611671 -0.033128396 0.16056351, 0.13610178 -0.033015683 0.16049482, 0.13618661 -0.033028767 0.16047254, 0.13633415 -0.032780036 0.16029565, 0.1364412 -0.03287755 0.16012399, 0.136255 -0.032947913 0.16039591, 0.13614079 -0.03322874 0.16067307, 0.13633755 -0.032882914 0.16029857, 0.13646916 -0.032993063 0.16013573, 0.13621637 -0.033136621 0.16053693, 0.13627872 -0.033046499 0.16042809, 0.13635659 -0.032981083 0.16031452, 0.13652149 -0.033097968 0.16015731, 0.13616925 -0.033289865 0.16080339, 0.13626263 -0.033232227 0.16063778, 0.1363214 -0.033147469 0.16048567, 0.13638991 -0.033071145 0.16034259, 0.13659558 -0.03318657 0.16018741, 0.13631703 -0.03329061 0.16075656, 0.13638607 -0.033236727 0.16057287, 0.13679001 -0.033295497 0.16026704, 0.13609588 -0.032679603 0.1604683, 0.13644487 -0.033162698 0.16038896, 0.13646159 -0.033291712 0.16067474, 0.13652514 -0.033243373 0.16045672, 0.13668686 -0.033253774 0.16022493, 0.13661787 -0.033293113 0.16053502, 0.13728759 -0.033295497 0.1590523, 0.13718423 -0.033253655 0.15900986, 0.13709292 -0.033186451 0.15897255, 0.13701913 -0.033097729 0.15894227, 0.13696662 -0.032992795 0.15892093, 0.13693878 -0.03287743 0.15890937, 0.13688782 -0.033221647 0.15801613, 0.13691896 -0.033168629 0.15811689, 0.13685891 -0.033175692 0.1580656, 0.13703422 -0.033039048 0.15875477, 0.13706514 -0.033081397 0.15857808, 0.13699538 -0.032936916 0.15874894, 0.13715857 -0.033297047 0.15802155, 0.13701957 -0.032992557 0.15858169, 0.13723207 -0.033295915 0.15812956, 0.13713776 -0.033255026 0.15818796, 0.13707809 -0.033259556 0.15809122, 0.13709363 -0.033129677 0.15876381, 0.13712643 -0.033158436 0.15857303, 0.13692713 -0.033265486 0.15794902, 0.13695599 -0.033216938 0.15807185, 0.13700676 -0.033263192 0.15801071, 0.13701084 -0.033039227 0.15842794, 0.13707232 -0.033297762 0.15793161, 0.13732775 -0.033287451 0.15879998, 0.13697755 -0.033298507 0.15786199, 0.13719019 -0.033219442 0.15877871, 0.13705763 -0.033116207 0.15841298, 0.13721959 -0.033233836 0.15856546, 0.13711591 -0.03318195 0.15839395, 0.1369718 -0.033077136 0.15829079, 0.13734803 -0.033290878 0.15855484, 0.13701507 -0.03314434 0.15826385, 0.13720053 -0.033245549 0.1583667, 0.13693318 -0.03309609 0.158217, 0.13706598 -0.033200756 0.15823226, 0.13697186 -0.033158049 0.15818344, 0.13688625 -0.033110425 0.15815631, 0.13731416 -0.03329356 0.15833002, 0.13701645 -0.033209905 0.1581447, 0.1368331 -0.03312026 0.15810989, 0.12779792 -0.033144459 0.15803592, 0.12779783 -0.033214226 0.15795811, 0.12779784 -0.03326647 0.15786776, 0.12779795 -0.033298746 0.15776832, 0.12669687 -0.033102676 0.15841992, 0.12665232 -0.033189282 0.15835355, 0.12659775 -0.033254877 0.15827234, 0.12653622 -0.033295825 0.15818065, 0.12741944 -0.033135787 0.15808338, 0.12740344 -0.03320919 0.15800676, 0.12738477 -0.033264086 0.15791662, 0.12736398 -0.03329812 0.15781721, 0.12177692 -0.033098266 0.16172758, 0.12177855 -0.033183143 0.16163538, 0.11116505 0.10080977 0.23504321, 0.11116494 0.10073094 0.23512095, 0.11044435 0.10019334 0.23531547, 0.11044006 0.10025801 0.2353348, 0.11043252 0.10032444 0.23534578, 0.11041217 0.10044082 0.23534404, 0.11038388 0.10055201 0.2353161, 0.11034907 0.1006519 0.23526353, 0.11030996 0.10073487 0.23518935, 0.11077608 0.10055517 0.23523629, 0.11116503 0.1006368 0.23517874, 0.11116494 0.1005324 0.23521495, 0.12000377 0.10080971 0.2350432, 0.12000374 0.10073076 0.23512088, 0.12000374 0.10063682 0.23517877, 0.1200037 0.1005324 0.23521489, 0.12018387 0.10021494 0.23522764, 0.12027152 0.10027055 0.23530163, 0.12026267 0.10018604 0.23527126, 0.1201905 0.1002997 0.23525517, 0.12013683 0.10062601 0.23519416, 0.12011902 0.1005206 0.23522773, 0.12023012 0.10049762 0.23526441, 0.12010573 0.10040964 0.2352374, 0.12020394 0.10038711 0.23526852, 0.12029071 0.10035695 0.23531941, 0.12015811 0.10072072 0.23513809, 0.12026565 0.10060202 0.23523706, 0.12032838 0.10046516 0.23532291, 0.12018161 0.1007999 0.23506266, 0.12030792 0.100695 0.23518759, 0.12037964 0.10056601 0.23530504, 0.12035553 0.10077147 0.23511867, 0.12044144 0.10065453 0.2352668, 0.12051053 0.10072567 0.23521009, 0.12009516 0.10023715 0.2352024, 0.12009871 0.10032187 0.23522751, 0.12028734 0.09985052 0.23695797, 0.12018558 0.099833146 0.2369018, 0.12009545 0.099791631 0.23683926, 0.12002179 0.099728361 0.23677318, 0.11996882 0.099646673 0.23670763, 0.11993916 0.099551305 0.23664626, 0.12012669 0.099782601 0.23700552, 0.12004595 0.09974964 0.23692946, 0.11997931 0.099693641 0.23685211, 0.11997513 0.099710926 0.23701376, 0.11991866 0.099662319 0.23692659, 0.11985245 0.099505976 0.23677459, 0.11972792 0.099558726 0.23694959, 0.11971362 0.09948124 0.23687163, 0.11987701 0.099592701 0.23684539, 0.11955318 0.099481955 0.23691304, 0.1196336 0.099478468 0.23689967, 0.11955325 0.099553064 0.2369936, 0.12021749 0.099791244 0.23707704, 0.1200432 0.09973602 0.2371016, 0.11975043 0.099617586 0.23704094, 0.11964099 0.099552378 0.23697978, 0.12011953 0.099736795 0.23718688, 0.11978026 0.099654451 0.23714104, 0.11965255 0.099607214 0.23707341, 0.11955313 0.099605426 0.23708779, 0.1198156 0.099667624 0.23724467, 0.11966732 0.099640504 0.23717631, 0.11955325 0.099636331 0.23719095, 0.11985512 0.099657074 0.23734775, 0.11968474 0.099650219 0.2372828, 0.11955316 0.099644527 0.23729834, 0.11970426 0.09963651 0.23738927, 0.11955324 0.099629477 0.23740497, 0.11990325 0.099526212 0.23671202, 0.11993082 0.099617615 0.23677815, 0.11038594 0.099482015 0.236913, 0.11038601 0.099553153 0.2369936, 0.11038606 0.099605396 0.23708776, 0.11038594 0.099636391 0.23719111, 0.11038594 0.099644497 0.2372984, 0.11038609 0.099629447 0.23740506, 0.10980943 0.099582717 0.23749703, 0.10977234 0.09959428 0.23739344, 0.10973896 0.099581525 0.23728842, 0.1097111 0.099545196 0.23718777, 0.10968986 0.09948729 0.23709616, 0.10967636 0.099410251 0.2370178, 0.133408 -0.033295408 0.144853, 0.133408 -0.032665268 0.14448941, 0.13311093 -0.033295646 0.14488518, 0.133408 -0.033255711 0.14474392, 0.13308886 -0.033256814 0.14477961, 0.13340795 -0.033191964 0.1446469, 0.13306911 -0.033194706 0.1446856, 0.13340792 -0.033107415 0.1445673, 0.13305299 -0.033112302 0.14460814, 0.13340805 -0.033006802 0.14450926, 0.13304098 -0.033014283 0.14455059, 0.13340794 -0.03289552 0.14447606, 0.13303404 -0.032905355 0.14451671, 0.13340788 -0.03277953 0.14446932, 0.1330322 -0.032791302 0.14450802, 0.13303594 -0.032677904 0.14452457, 0.14257513 -0.033295438 0.14485313, 0.14257511 -0.033255652 0.1447441, 0.14257509 -0.033191785 0.14464679, 0.14257501 -0.033107325 0.14456739, 0.14257509 -0.033006653 0.14450935, 0.14257507 -0.032895371 0.14447601, 0.1425751 -0.0327795 0.14446931, 0.14257507 -0.032665119 0.14448942, 0.14264284 -0.032905981 0.14447059, 0.14271972 -0.032923415 0.14444846, 0.14264078 -0.032791957 0.14446144, 0.14271417 -0.032813028 0.14443648, 0.14279251 -0.03284131 0.14439096, 0.14271894 -0.032701626 0.14444703, 0.14279531 -0.032733157 0.14439459, 0.1426653 -0.033127442 0.14457339, 0.14265007 -0.033014521 0.14450446, 0.14273518 -0.033027872 0.14448217, 0.14288265 -0.032779023 0.14430532, 0.14298974 -0.032876655 0.14413394, 0.14280348 -0.032946929 0.1444055, 0.14268938 -0.033227757 0.144683, 0.14288604 -0.032881901 0.14430824, 0.14301769 -0.03299199 0.1441455, 0.14276478 -0.033135608 0.14454693, 0.1428273 -0.033045486 0.14443779, 0.14290507 -0.03297998 0.14432423, 0.14306995 -0.033096984 0.14416689, 0.14271787 -0.03328903 0.14481318, 0.14281116 -0.033231303 0.14464737, 0.14287002 -0.033146426 0.14449535, 0.14293824 -0.033070251 0.14435233, 0.14314406 -0.033185527 0.14419727, 0.14286552 -0.033289835 0.14476623, 0.14293456 -0.033235773 0.1445826, 0.14333861 -0.033294603 0.14427702, 0.14264436 -0.032678649 0.14447801, 0.14299332 -0.033161685 0.1443987, 0.14301011 -0.033290699 0.14468449, 0.14307372 -0.03324233 0.14446642, 0.14323525 -0.033252761 0.14423458, 0.14316635 -0.033292189 0.14454468, 0.14383598 -0.033294544 0.14306192, 0.14373277 -0.033252761 0.14301963, 0.14364158 -0.033185527 0.14298232, 0.14356756 -0.033096954 0.14295205, 0.14351512 -0.03299199 0.14293049, 0.14348722 -0.032876536 0.14291921, 0.14343636 -0.033220723 0.14202578, 0.14340749 -0.033174828 0.14207548, 0.1434675 -0.033167765 0.14212655, 0.14358266 -0.033038363 0.14276461, 0.14361371 -0.033080623 0.14258794, 0.14354391 -0.032936022 0.14275871, 0.14356816 -0.032991752 0.14259169, 0.14370699 -0.033296093 0.14203112, 0.14368628 -0.033254102 0.1421978, 0.14362657 -0.03325884 0.14210108, 0.14364207 -0.033128902 0.14277366, 0.14367481 -0.033157572 0.14258282, 0.14378062 -0.03329511 0.14213949, 0.14355512 -0.033262208 0.14202069, 0.1434755 -0.033264592 0.14195871, 0.14350456 -0.033216164 0.14208165, 0.14355917 -0.033038363 0.14243762, 0.14362089 -0.033297047 0.14194126, 0.14387633 -0.033286616 0.14280955, 0.14352611 -0.033297554 0.14187205, 0.1437387 -0.033218578 0.14278845, 0.14360632 -0.033115432 0.14242248, 0.14376819 -0.033233091 0.14257529, 0.14366446 -0.033181116 0.1424038, 0.14352031 -0.033076391 0.14230041, 0.14389659 -0.033290014 0.14256476, 0.14356358 -0.033143505 0.14227371, 0.14374906 -0.033244774 0.14237651, 0.14348172 -0.033095285 0.14222677, 0.14361456 -0.033199981 0.14224201, 0.14352039 -0.033157244 0.14219302, 0.14343464 -0.03310959 0.14216593, 0.14386274 -0.033292815 0.14233987, 0.14356488 -0.03320913 0.14215431, 0.14338176 -0.033119515 0.14211978, 0.13434647 -0.033143714 0.14204574, 0.13434665 -0.033213392 0.14196789, 0.13434644 -0.033265576 0.14187732, 0.13434653 -0.033297911 0.14177811, 0.13324539 -0.033101693 0.14242959, 0.13320084 -0.033188447 0.14236334, 0.1331463 -0.033254072 0.1422821, 0.13308474 -0.033294961 0.1421902, 0.13396786 -0.033135012 0.14209306, 0.13395201 -0.033208206 0.14201641, 0.13393326 -0.033263192 0.14192644, 0.13391255 -0.033297196 0.14182699, 0.13013372 -0.033295885 0.15284832, 0.13013367 -0.032665715 0.15248486, 0.12983665 -0.033296123 0.1528805, 0.13013366 -0.033256218 0.15273918, 0.12981459 -0.03325741 0.15277477, 0.1301336 -0.033192322 0.15264221, 0.12979488 -0.033195183 0.15268072, 0.1301336 -0.033107772 0.15256257, 0.12977859 -0.033112779 0.15260334, 0.13013372 -0.033007309 0.15250452, 0.12976666 -0.03301467 0.15254587, 0.13013358 -0.032895938 0.15247124, 0.12975964 -0.032905743 0.15251191, 0.13013355 -0.032780036 0.1524646, 0.12975797 -0.032791749 0.15250321, 0.12976173 -0.03267841 0.15251996, 0.13930094 -0.033295825 0.15284826, 0.13930079 -0.033256099 0.15273897, 0.13930082 -0.033192232 0.15264203, 0.13930094 -0.033107862 0.15256239, 0.13930082 -0.0330071 0.15250434, 0.1393007 -0.032895878 0.1524712, 0.13930085 -0.032780007 0.15246451, 0.13930094 -0.032665595 0.15248469, 0.13936841 -0.032906249 0.1524656, 0.13944542 -0.032923892 0.15244342, 0.13936651 -0.032792404 0.15245666, 0.13943982 -0.032813355 0.15243156, 0.13951826 -0.032841727 0.15238602, 0.13944465 -0.032702073 0.15244211, 0.13952109 -0.032733545 0.15238975, 0.13939106 -0.033128038 0.15256841, 0.13937593 -0.033015177 0.15249963, 0.13946094 -0.033028349 0.15247729, 0.13960828 -0.0327795 0.15230057, 0.13971534 -0.032876983 0.15212898, 0.13952923 -0.032947347 0.15240057, 0.13941503 -0.033228233 0.15267779, 0.13961184 -0.032882437 0.15230335, 0.13974339 -0.032992467 0.15214051, 0.13949063 -0.033136174 0.15254174, 0.13955307 -0.033045873 0.15243281, 0.13963076 -0.032980517 0.15231924, 0.13979566 -0.033097461 0.15216185, 0.13944358 -0.033289418 0.15280826, 0.13953674 -0.033231571 0.15264238, 0.13959567 -0.033146933 0.15249038, 0.13966405 -0.033070758 0.15234734, 0.13986975 -0.033186063 0.15219219, 0.13959138 -0.033290222 0.15276122, 0.13966048 -0.03323622 0.15257765, 0.14006442 -0.03329511 0.15227194, 0.13937011 -0.032679096 0.15247327, 0.13971907 -0.033162192 0.15239377, 0.13973582 -0.033291206 0.1526797, 0.13979945 -0.033242747 0.15246157, 0.13996099 -0.033253208 0.15222943, 0.13989209 -0.033292726 0.15253961, 0.14056182 -0.03329505 0.15105708, 0.14045852 -0.033253178 0.15101488, 0.14036715 -0.033185944 0.1509774, 0.14029324 -0.033097371 0.15094724, 0.14024082 -0.032992378 0.1509257, 0.14021297 -0.032876953 0.1509143, 0.14016199 -0.03322123 0.15002087, 0.1401332 -0.033175215 0.15007046, 0.14019319 -0.033168092 0.15012181, 0.14030841 -0.03303875 0.15075976, 0.14033939 -0.03308107 0.15058295, 0.14026964 -0.032936558 0.15075365, 0.14029387 -0.032992139 0.15058678, 0.14043272 -0.03329657 0.15002635, 0.140412 -0.033254519 0.15019292, 0.14035237 -0.033259138 0.15009609, 0.14036787 -0.03312932 0.15076879, 0.14040065 -0.033158049 0.15057805, 0.14050639 -0.033295497 0.15013459, 0.14020133 -0.033265039 0.14995381, 0.14028096 -0.033262715 0.15001562, 0.1402303 -0.033216462 0.1500769, 0.14028507 -0.03303872 0.15043297, 0.14034665 -0.033297405 0.14993647, 0.14060195 -0.033287033 0.15080491, 0.14025176 -0.033298001 0.14986709, 0.1404644 -0.033219054 0.15078372, 0.14033189 -0.033115759 0.15041775, 0.14049393 -0.033233508 0.15057048, 0.1403902 -0.033181444 0.15039892, 0.14024597 -0.033076629 0.15029564, 0.14062229 -0.03329052 0.15055996, 0.14028931 -0.033143863 0.15026894, 0.1404748 -0.033245072 0.1503717, 0.14020747 -0.033095583 0.15022191, 0.14034033 -0.033200249 0.15023723, 0.14024612 -0.033157602 0.15018827, 0.14016049 -0.033109978 0.15016092, 0.14058852 -0.033293173 0.15033504, 0.14029062 -0.033209488 0.15014955, 0.14010739 -0.033119783 0.15011469, 0.13107216 -0.033143893 0.15004082, 0.13107216 -0.03321375 0.1499631, 0.13107216 -0.033265993 0.14987262, 0.13107218 -0.033298239 0.14977327, 0.12997106 -0.03310211 0.1504247, 0.12992658 -0.033188745 0.15035841, 0.12987208 -0.03325443 0.15027721, 0.12981047 -0.033295259 0.15018538, 0.13069363 -0.03313528 0.15008816, 0.13067771 -0.033208713 0.15001145, 0.13065898 -0.033263609 0.14992149, 0.13063824 -0.033297583 0.14982219, 0.12505113 -0.033097699 0.15373248, 0.12505256 -0.033182457 0.15364033, 0.12358525 -0.033296898 0.16883861, 0.12358521 -0.032666579 0.16847491, 0.1232883 -0.033297256 0.16887055, 0.12358525 -0.033257172 0.16872917, 0.1232661 -0.033258274 0.16876484, 0.12358522 -0.033193305 0.16863228, 0.1232463 -0.033196107 0.16867089, 0.12358522 -0.033108786 0.16855253, 0.12323022 -0.033113822 0.16859342, 0.12358522 -0.033008173 0.1684946, 0.12321833 -0.033015653 0.16853605, 0.1235853 -0.03289704 0.16846111, 0.12321115 -0.032906756 0.16850211, 0.12358534 -0.032781079 0.16845478, 0.12320951 -0.032792643 0.16849327, 0.12321317 -0.032679304 0.16851011, 0.13275242 -0.033296868 0.16883852, 0.13275231 -0.033257112 0.16872951, 0.13275242 -0.033193246 0.16863228, 0.13275239 -0.033108816 0.16855256, 0.13275242 -0.033008233 0.16849472, 0.13275242 -0.032896921 0.16846122, 0.13275239 -0.03278099 0.16845475, 0.13275234 -0.032666638 0.16847503, 0.13282 -0.032907441 0.1684559, 0.13289684 -0.032924756 0.1684338, 0.13281804 -0.032793507 0.16844691, 0.13289137 -0.032814488 0.16842189, 0.13296977 -0.032842621 0.16837631, 0.13289618 -0.032703057 0.16843225, 0.13297266 -0.032734469 0.16838004, 0.13284266 -0.033128992 0.16855861, 0.13282752 -0.03301613 0.16848983, 0.13291252 -0.033029333 0.16846754, 0.13305981 -0.032780454 0.1682907, 0.13316703 -0.032878086 0.16811933, 0.13298079 -0.0329483 0.16839109, 0.13286662 -0.033229247 0.16866829, 0.13306326 -0.032883272 0.16829361, 0.13319504 -0.032993451 0.16813053, 0.13294208 -0.033137009 0.16853215, 0.13300467 -0.033046976 0.16842307, 0.13308224 -0.0329815 0.16830973, 0.13324746 -0.033098593 0.1681522, 0.13289505 -0.033290341 0.1687987, 0.13298833 -0.033232585 0.16863288, 0.13304722 -0.033147827 0.16848065, 0.13311563 -0.033071771 0.16833758, 0.13332114 -0.033187047 0.16818254, 0.1330428 -0.033291236 0.16875154, 0.13311186 -0.033237234 0.16856788, 0.13351595 -0.033296153 0.16826214, 0.13282168 -0.03268005 0.16846348, 0.1331705 -0.033163175 0.1683841, 0.13318741 -0.033292189 0.16867007, 0.13325095 -0.03324382 0.16845168, 0.13341257 -0.033254221 0.16821979, 0.13334358 -0.03329362 0.16852988, 0.13401341 -0.033295915 0.16704728, 0.13391018 -0.033254042 0.16700508, 0.13381875 -0.033186957 0.16696776, 0.13374484 -0.033098325 0.16693731, 0.13369241 -0.032993302 0.166916, 0.1336645 -0.032877907 0.16690436, 0.1336136 -0.033222184 0.16601154, 0.13358483 -0.033176228 0.16606067, 0.13364469 -0.033169046 0.16611183, 0.13376009 -0.033039734 0.16674997, 0.13379097 -0.033082023 0.16657318, 0.13372119 -0.032937512 0.16674414, 0.13374543 -0.032993093 0.166577, 0.13388413 -0.033297494 0.16601647, 0.13386355 -0.033255592 0.16618311, 0.13380384 -0.033260122 0.16608633, 0.13381946 -0.033130214 0.16675891, 0.1338522 -0.033159003 0.16656843, 0.13395774 -0.033296451 0.16612478, 0.13373244 -0.033263579 0.16600598, 0.13365281 -0.033265993 0.16594388, 0.13368185 -0.033217415 0.16606727, 0.13373646 -0.033039555 0.16642319, 0.13379809 -0.033298418 0.16592686, 0.13405359 -0.033288047 0.16679515, 0.13370343 -0.033299074 0.16585723, 0.13391601 -0.033219948 0.16677397, 0.13378341 -0.033116743 0.16640815, 0.13394555 -0.033234492 0.16656058, 0.13384175 -0.033182517 0.166389, 0.13369763 -0.033077732 0.16628601, 0.13407393 -0.033291444 0.16655019, 0.1337409 -0.033144817 0.16625912, 0.13392638 -0.033246174 0.16636193, 0.13365883 -0.033096597 0.16621216, 0.13379192 -0.033201262 0.16622759, 0.13369775 -0.033158585 0.16617848, 0.13361193 -0.033110902 0.16615131, 0.13404003 -0.033294186 0.1663252, 0.13374221 -0.033210441 0.16613986, 0.13355903 -0.033120766 0.16610503, 0.12452379 -0.033145025 0.16603112, 0.12452371 -0.033214882 0.16595344, 0.12452371 -0.033267066 0.16586272, 0.12452376 -0.033299312 0.16576335, 0.1234225 -0.033102974 0.16641489, 0.12337804 -0.033189759 0.16634873, 0.1233234 -0.033255413 0.16626756, 0.12326193 -0.033296332 0.16617575, 0.12414518 -0.033136204 0.16607845, 0.12412922 -0.033209726 0.16600193, 0.12411045 -0.033264562 0.16591181, 0.12408966 -0.033298537 0.16581252, 0.11850269 -0.033098742 0.16972272, 0.11850417 -0.033183441 0.16963056, 0.12031102 -0.033297315 0.17683367, 0.12031104 -0.032667115 0.17647016, 0.12001394 -0.033297583 0.17686579, 0.12031099 -0.033257648 0.17672457, 0.11999184 -0.0332589 0.1767603, 0.12031111 -0.033193871 0.17662771, 0.11997214 -0.033196643 0.17666592, 0.12031096 -0.033109292 0.17654787, 0.11995591 -0.033114329 0.17658859, 0.12031102 -0.03300868 0.17648987, 0.11994398 -0.03301616 0.17653142, 0.12031111 -0.032897487 0.17645665, 0.11993696 -0.032907203 0.1764971, 0.12031099 -0.032781526 0.17644991, 0.11993527 -0.032793179 0.17648856, 0.119939 -0.032679781 0.17650528, 0.12947813 -0.033297315 0.17683363, 0.12947811 -0.033257559 0.17672442, 0.12947801 -0.033193782 0.17662752, 0.12947799 -0.033109263 0.17654763, 0.12947801 -0.03300859 0.17648977, 0.12947808 -0.032897368 0.17645653, 0.12947819 -0.032781437 0.17644978, 0.12947811 -0.032666996 0.17646997, 0.12954566 -0.032907799 0.17645097, 0.12962259 -0.032925293 0.17642902, 0.12954378 -0.032793924 0.176442, 0.12961723 -0.032814905 0.17641698, 0.12969562 -0.032843247 0.17637146, 0.12962198 -0.032703564 0.17642751, 0.12969841 -0.032735065 0.17637502, 0.12956835 -0.033129409 0.17655371, 0.12955321 -0.033016488 0.17648493, 0.12963815 -0.03302978 0.17646281, 0.1297856 -0.03278099 0.17628571, 0.12989272 -0.032878473 0.17611454, 0.12970635 -0.032948747 0.17638588, 0.12959231 -0.033229634 0.17666326, 0.12978913 -0.032883838 0.17628859, 0.12992062 -0.032993838 0.17612581, 0.12966777 -0.033137515 0.17652725, 0.12973033 -0.033047453 0.1764185, 0.12980808 -0.032981947 0.17630456, 0.12997307 -0.033098891 0.17614733, 0.12962081 -0.033290789 0.17679368, 0.12971401 -0.033233091 0.17662796, 0.12977281 -0.033148304 0.17647576, 0.12984139 -0.033072218 0.17633274, 0.13004693 -0.033187464 0.1761775, 0.1297684 -0.033291593 0.17674649, 0.12983757 -0.033237681 0.17656305, 0.13024156 -0.033296511 0.17625733, 0.12954737 -0.032680556 0.17645858, 0.12989625 -0.033163562 0.17637897, 0.12991309 -0.033292696 0.17666498, 0.1299766 -0.033244208 0.1764468, 0.1301381 -0.033254549 0.17621502, 0.13006926 -0.033294126 0.17652497, 0.13073912 -0.033296362 0.17504239, 0.13063586 -0.033254549 0.17500028, 0.13054456 -0.033187315 0.17496274, 0.13047057 -0.033098802 0.17493245, 0.13041832 -0.032993838 0.17491101, 0.1303903 -0.032878354 0.17489944, 0.1303394 -0.033222601 0.17400633, 0.13031055 -0.033176705 0.1740558, 0.13037044 -0.033169612 0.17410681, 0.13048579 -0.033040091 0.17474507, 0.13051666 -0.03308247 0.17456846, 0.13044693 -0.032937929 0.17473899, 0.13047116 -0.032993451 0.17457207, 0.13061002 -0.03329803 0.17401177, 0.13058926 -0.033256009 0.17417811, 0.13052964 -0.033260629 0.17408141, 0.13054514 -0.03313069 0.17475411, 0.13057794 -0.03315945 0.17456351, 0.13068368 -0.033296898 0.17411982, 0.13045825 -0.033264086 0.17400096, 0.13037862 -0.03326647 0.17393897, 0.13040757 -0.033217892 0.17406216, 0.13046232 -0.033040181 0.17441815, 0.13052393 -0.033298925 0.17392181, 0.13077928 -0.033288434 0.17479013, 0.13042916 -0.033299401 0.17385231, 0.13064171 -0.033220455 0.17476903, 0.13050927 -0.03311722 0.17440294, 0.13067119 -0.03323485 0.17455573, 0.13056743 -0.033182964 0.17438427, 0.13042325 -0.033078179 0.17428115, 0.13079958 -0.033291861 0.17454524, 0.1304666 -0.033145264 0.17425416, 0.13065192 -0.033246592 0.17435694, 0.1303848 -0.033097073 0.17420718, 0.13051766 -0.033201799 0.17422268, 0.13042346 -0.033159092 0.17417353, 0.13033773 -0.033111379 0.17414616, 0.13076572 -0.033294573 0.17432041, 0.13046795 -0.033210978 0.17413476, 0.13028467 -0.033121333 0.17410019, 0.12124947 -0.033145353 0.17402612, 0.12124944 -0.033215299 0.1739486, 0.12124953 -0.033267483 0.17385779, 0.12124956 -0.033299789 0.17375864, 0.1201483 -0.033103451 0.17441015, 0.12010394 -0.033190235 0.17434379, 0.12004936 -0.03325595 0.17426257, 0.11998773 -0.033296838 0.17417078, 0.12087096 -0.033136651 0.17407367, 0.12085509 -0.033210143 0.17399694, 0.12083617 -0.03326495 0.17390679, 0.12081563 -0.033299074 0.17380752, 0.11522849 -0.033099219 0.17771772, 0.1152298 -0.033183977 0.17762569, 0.1170368 -0.033297911 0.1848287, 0.11703664 -0.032667562 0.18446536, 0.11673984 -0.03329812 0.18486087, 0.11703682 -0.033258155 0.18471976, 0.11671764 -0.033259317 0.18475528, 0.11703679 -0.033194378 0.18462263, 0.11669785 -0.03319715 0.18466116, 0.1170367 -0.033109888 0.18454285, 0.11668169 -0.033114657 0.18458362, 0.1170367 -0.033009246 0.18448503, 0.11666977 -0.033016667 0.1845264, 0.11703682 -0.032897905 0.18445154, 0.11666286 -0.032907829 0.18449242, 0.11703672 -0.032782003 0.18444493, 0.11666107 -0.032793716 0.18448348, 0.11666477 -0.032680348 0.18450041, 0.12620382 -0.033297852 0.18482864, 0.12620388 -0.033258036 0.18471974, 0.12620397 -0.033194289 0.18462268, 0.12620375 -0.03310968 0.18454288, 0.12620386 -0.033009097 0.18448506, 0.12620388 -0.032897905 0.18445164, 0.12620384 -0.032781973 0.18444498, 0.12620388 -0.032667592 0.18446524, 0.12627159 -0.032908395 0.18444604, 0.12634857 -0.032925949 0.18442419, 0.12626956 -0.032794431 0.1844371, 0.12634288 -0.032815412 0.18441194, 0.12642132 -0.032843664 0.18436641, 0.12634774 -0.03270416 0.18442258, 0.12642406 -0.032735422 0.18437034, 0.12629394 -0.033129945 0.1845488, 0.12627907 -0.033017144 0.1844801, 0.12636392 -0.033030346 0.18445778, 0.12651139 -0.032781377 0.18428107, 0.12661852 -0.032878831 0.18410963, 0.12643217 -0.032949165 0.18438131, 0.12631808 -0.033230141 0.18465871, 0.12651485 -0.032884255 0.18428393, 0.12664641 -0.032994345 0.18412095, 0.12639375 -0.033138141 0.18452242, 0.12645607 -0.03304787 0.18441343, 0.12653388 -0.032982424 0.18429977, 0.12669896 -0.033099398 0.18414256, 0.12634666 -0.033291444 0.18478861, 0.12643979 -0.033233598 0.18462306, 0.12649883 -0.033148959 0.18447107, 0.12656723 -0.033072576 0.18432799, 0.12677281 -0.033187971 0.18417272, 0.12649436 -0.033292159 0.18474165, 0.1265634 -0.033238217 0.18455823, 0.12696739 -0.033296958 0.18425232, 0.12627326 -0.032681182 0.1844538, 0.1266223 -0.033164129 0.18437436, 0.1266389 -0.033293203 0.18466014, 0.1267024 -0.033244744 0.18444212, 0.12686405 -0.033255115 0.18421026, 0.1267951 -0.033294722 0.18452033, 0.12746491 -0.033296898 0.18303758, 0.12736149 -0.033255056 0.1829952, 0.12727019 -0.033187911 0.18295798, 0.12719642 -0.033099398 0.18292783, 0.12714389 -0.032994255 0.18290612, 0.12711622 -0.03287895 0.18289478, 0.12706517 -0.033223256 0.1820014, 0.12703626 -0.033177182 0.18205099, 0.12709634 -0.033170149 0.18210213, 0.12721157 -0.033040598 0.18274009, 0.12724245 -0.033082917 0.18256348, 0.12717269 -0.032938495 0.18273424, 0.12719695 -0.032993957 0.18256728, 0.12733597 -0.033298627 0.18200678, 0.12731503 -0.033256516 0.18217324, 0.12725542 -0.033261165 0.1820765, 0.12727095 -0.033131197 0.18274935, 0.1273036 -0.033159927 0.18255854, 0.12740941 -0.033297494 0.18211509, 0.12710434 -0.033266976 0.1819343, 0.12718408 -0.033264562 0.18199627, 0.12713335 -0.033218488 0.18205719, 0.12718806 -0.033040687 0.18241319, 0.12724958 -0.033299312 0.18191688, 0.12750505 -0.033289 0.18278524, 0.12715489 -0.033299997 0.18184727, 0.12736748 -0.033220991 0.18276398, 0.12723492 -0.033117756 0.18239824, 0.12739687 -0.033235237 0.18255071, 0.12729327 -0.033183381 0.18237953, 0.12714909 -0.033078715 0.182276, 0.12752536 -0.033292279 0.18254039, 0.12719247 -0.03314577 0.1822491, 0.12737788 -0.033247098 0.1823519, 0.12711065 -0.033097669 0.18220221, 0.12724337 -0.033202216 0.18221781, 0.12714924 -0.033159569 0.18216868, 0.12706353 -0.033111915 0.1821415, 0.12749146 -0.03329502 0.18231563, 0.12719376 -0.033211485 0.18213005, 0.12701039 -0.03312178 0.18209498, 0.11797515 -0.033145919 0.18202125, 0.11797515 -0.033215776 0.18194376, 0.11797522 -0.03326793 0.18185294, 0.11797513 -0.033300206 0.18175378, 0.11687419 -0.033104047 0.18240528, 0.11682963 -0.033190712 0.18233903, 0.11677513 -0.033256397 0.18225782, 0.11671351 -0.033297256 0.18216598, 0.11759657 -0.033137187 0.1820686, 0.11758074 -0.033210501 0.1819921, 0.11756194 -0.033265337 0.18190213, 0.11754116 -0.033299431 0.18180256, 0.10868007 -0.033100143 0.19370811, 0.1135999 -0.033104554 0.19040038, 0.10868143 -0.033184901 0.19361603, 0.11355531 -0.033191219 0.19033398, 0.11350086 -0.033256903 0.19025281, 0.1134392 -0.033297822 0.190161, 0.11470096 -0.033146426 0.19001631, 0.1147009 -0.033300653 0.18974917, 0.11432241 -0.033137664 0.19006376, 0.11470105 -0.033216193 0.18993874, 0.11430657 -0.033211127 0.18998724, 0.11470103 -0.033268526 0.18984824, 0.1142879 -0.033266082 0.18989722, 0.11426704 -0.033299968 0.18979762, 0.12379096 -0.033223704 0.18999666, 0.12382202 -0.033170596 0.19009715, 0.12376198 -0.033177689 0.190046, 0.12393734 -0.033041075 0.19073538, 0.12396811 -0.033083394 0.19055873, 0.12389848 -0.032938883 0.19072942, 0.12406157 -0.033299044 0.19000179, 0.12392265 -0.032994524 0.19056244, 0.12413496 -0.033297822 0.19011016, 0.12404069 -0.033256903 0.1901686, 0.12398109 -0.033261463 0.19007175, 0.12399647 -0.033131525 0.19074444, 0.12402935 -0.033160433 0.19055381, 0.12384179 -0.032879338 0.19088988, 0.12385899 -0.033218876 0.19005246, 0.12383005 -0.033267453 0.18992941, 0.12390974 -0.033265129 0.1899914, 0.12391385 -0.033041045 0.19040851, 0.12397534 -0.033299819 0.18991216, 0.12419061 -0.033297434 0.19103271, 0.12423083 -0.033289507 0.19078045, 0.12408729 -0.033255443 0.19099048, 0.12388062 -0.033300415 0.18984266, 0.12409315 -0.033221349 0.19075929, 0.12396069 -0.033118173 0.19039348, 0.12412259 -0.033235714 0.19054608, 0.12401882 -0.033183828 0.19037466, 0.12387475 -0.033079073 0.1902713, 0.12425107 -0.033292815 0.1905355, 0.12391812 -0.033146277 0.19024451, 0.12410361 -0.033247605 0.19034727, 0.12383625 -0.033098057 0.19019751, 0.12396912 -0.033202663 0.19021291, 0.12387495 -0.033160105 0.19016379, 0.12378927 -0.033112392 0.19013694, 0.12421724 -0.033295557 0.19031076, 0.12391958 -0.033211902 0.19012527, 0.1237362 -0.033122286 0.19009043, 0.12386976 -0.032994702 0.19090134, 0.12392209 -0.033099726 0.19092256, 0.12399605 -0.033188328 0.19095306, 0.12369311 -0.033297405 0.1922477, 0.12358974 -0.033255532 0.19220537, 0.12349847 -0.033188388 0.19216786, 0.12342457 -0.033099785 0.19213754, 0.12337215 -0.032994792 0.19211617, 0.12334417 -0.032879308 0.19210488, 0.1229952 -0.032794729 0.19243236, 0.12307408 -0.032926217 0.1924191, 0.12306865 -0.03281574 0.19240716, 0.12299725 -0.032908633 0.19244115, 0.12307335 -0.032704338 0.19241765, 0.12314703 -0.032844111 0.19236168, 0.12314978 -0.032735899 0.19236551, 0.12292962 -0.03266795 0.1924603, 0.12292954 -0.033194467 0.1926177, 0.12301983 -0.033130273 0.19254401, 0.1229296 -0.033110157 0.19253795, 0.12300473 -0.033017412 0.19247521, 0.12308969 -0.033030733 0.192453, 0.1232371 -0.032781765 0.19227605, 0.12315787 -0.032949552 0.19237641, 0.12292954 -0.033258364 0.19271474, 0.12304384 -0.033230498 0.19265373, 0.12324044 -0.032884642 0.19227903, 0.12311924 -0.033138409 0.19251741, 0.12318178 -0.033048198 0.19240871, 0.1232596 -0.032982841 0.19229497, 0.12292962 -0.03329815 0.19282395, 0.12307224 -0.033291742 0.192784, 0.12316556 -0.033233926 0.19261828, 0.12322435 -0.033149168 0.19246618, 0.12329289 -0.033073023 0.19232301, 0.12321994 -0.033292487 0.19273679, 0.12328908 -0.033238456 0.19255345, 0.12334786 -0.033164456 0.1923694, 0.12299892 -0.03268142 0.19244878, 0.12336446 -0.03329353 0.1926553, 0.12292959 -0.032782361 0.19244012, 0.12342805 -0.033245102 0.19243725, 0.12352082 -0.033294991 0.19251542, 0.12292951 -0.032898232 0.1924469, 0.12292954 -0.033009484 0.19248001, 0.11376245 -0.03329818 0.19282392, 0.11376238 -0.033258453 0.19271471, 0.1137625 -0.033194706 0.19261779, 0.1137625 -0.033110157 0.19253792, 0.11376241 -0.033009514 0.19248009, 0.1137625 -0.032898322 0.1924469, 0.11376247 -0.03278245 0.19244024, 0.11376244 -0.032668039 0.19246049, 0.11346549 -0.033298537 0.19285603, 0.11344334 -0.033259615 0.19275036, 0.11342371 -0.033197418 0.19265617, 0.11340752 -0.033115134 0.19257867, 0.11339557 -0.033016935 0.19252171, 0.11338846 -0.032908037 0.19248742, 0.11338687 -0.032794043 0.19247855, 0.11339045 -0.032680705 0.1924955, 0.10540569 -0.03310062 0.20170334, 0.1103256 -0.033104971 0.19839543, 0.10540704 -0.033185378 0.20161134, 0.11028114 -0.033191845 0.19832923, 0.11022662 -0.033257291 0.19824778, 0.11016481 -0.03329818 0.19815627, 0.1114267 -0.033146903 0.19801155, 0.11142667 -0.03330119 0.19774403, 0.11104812 -0.033138171 0.19805868, 0.11142667 -0.033216789 0.19793381, 0.1110322 -0.033211663 0.19798245, 0.11142674 -0.033268973 0.19784321, 0.11101352 -0.03326647 0.19789205, 0.11099289 -0.033300564 0.19779275, 0.12051667 -0.033224031 0.19799165, 0.12048776 -0.033178195 0.19804125, 0.12054764 -0.033170924 0.19809231, 0.12066306 -0.033041522 0.19873039, 0.12069389 -0.033083931 0.19855386, 0.1206242 -0.03293936 0.19872431, 0.12064849 -0.032995 0.19855763, 0.12078732 -0.033299491 0.19799706, 0.12076651 -0.03325744 0.1981637, 0.12070693 -0.03326194 0.19806676, 0.12072241 -0.033132002 0.19873968, 0.12075515 -0.03316088 0.19854866, 0.12086082 -0.033298358 0.19810525, 0.12056758 -0.032879755 0.19888489, 0.12063546 -0.033265546 0.19798647, 0.12055589 -0.033267781 0.19792442, 0.12058485 -0.033219442 0.19804743, 0.12063964 -0.033041611 0.19840352, 0.12070121 -0.033300325 0.19790725, 0.12091635 -0.033297792 0.19902791, 0.12095667 -0.033289954 0.19877557, 0.12081309 -0.033256009 0.19898546, 0.12060653 -0.033300892 0.19783761, 0.12081896 -0.033221915 0.19875427, 0.1206864 -0.033118561 0.19838841, 0.12084839 -0.03323628 0.19854099, 0.12074474 -0.033184424 0.1983697, 0.12060042 -0.033079579 0.19826636, 0.12097694 -0.033293292 0.19853072, 0.12064397 -0.033146784 0.19823949, 0.12082945 -0.033248141 0.19834228, 0.120562 -0.033098504 0.19819267, 0.12069498 -0.0332032 0.19820817, 0.12060069 -0.033160523 0.19815893, 0.12051499 -0.033112869 0.19813183, 0.12094295 -0.033296034 0.19830577, 0.12064523 -0.033212468 0.1981201, 0.12046207 -0.033122703 0.19808559, 0.12059541 -0.032995209 0.19889645, 0.12064789 -0.033100203 0.19891782, 0.1207218 -0.033188745 0.19894809, 0.12041886 -0.033297881 0.20024256, 0.12031546 -0.03325595 0.20020026, 0.12022419 -0.033188894 0.2001631, 0.12015024 -0.033100203 0.20013261, 0.12009786 -0.032995179 0.20011123, 0.12006994 -0.032879785 0.20010005, 0.11972089 -0.032795146 0.20042738, 0.11979996 -0.032926634 0.20041449, 0.11979432 -0.032816127 0.20040213, 0.11972302 -0.03290908 0.20043644, 0.11979921 -0.032704905 0.20041285, 0.11987279 -0.032844588 0.20035678, 0.11987568 -0.032736346 0.20036058, 0.11965533 -0.032668427 0.20045564, 0.11965533 -0.033194974 0.20061289, 0.11974552 -0.03313078 0.20053907, 0.11965537 -0.033110544 0.20053318, 0.11973047 -0.033017859 0.20047034, 0.1198156 -0.033031031 0.20044808, 0.11996287 -0.032782361 0.20027111, 0.11988378 -0.032950088 0.20037146, 0.1196553 -0.03325887 0.20070978, 0.1197695 -0.033230916 0.20064884, 0.1199664 -0.032885119 0.20027392, 0.11984514 -0.033138856 0.20051274, 0.11990763 -0.033048674 0.20040374, 0.1199853 -0.032983258 0.20029005, 0.11965525 -0.033298656 0.20081893, 0.11979814 -0.033292249 0.20077901, 0.11989124 -0.033234343 0.20061341, 0.11995022 -0.033149764 0.20046122, 0.12001863 -0.033073619 0.20031826, 0.11994581 -0.033292964 0.20073183, 0.12001482 -0.033239082 0.20054853, 0.12007371 -0.033165053 0.20036463, 0.11972474 -0.032681897 0.20044382, 0.12009048 -0.033294007 0.20065038, 0.11965542 -0.032782838 0.20043512, 0.12015395 -0.033245608 0.20043226, 0.12024659 -0.033295438 0.20051071, 0.11965534 -0.03289862 0.20044194, 0.11965528 -0.033009902 0.20047535, 0.11048825 -0.033298805 0.20081888, 0.11048825 -0.033258989 0.20070992, 0.11048825 -0.033195212 0.20061277, 0.11048825 -0.033110693 0.20053302, 0.11048825 -0.03301008 0.2004751, 0.11048825 -0.032898858 0.20044184, 0.11048828 -0.032782838 0.20043506, 0.11048818 -0.032668516 0.20045562, 0.11019123 -0.033299103 0.20085096, 0.11016913 -0.033260271 0.20074558, 0.11014943 -0.033198044 0.20065156, 0.1101332 -0.0331157 0.20057394, 0.1101214 -0.03301765 0.20051657, 0.11011429 -0.032908633 0.20048247, 0.11011246 -0.03279455 0.20047392, 0.11011618 -0.032681182 0.20049059, 0.10721405 -0.033299282 0.20881423, 0.10721393 -0.032668933 0.20845069, 0.1069169 -0.033299461 0.20884614, 0.10721391 -0.033259347 0.20870519, 0.10689491 -0.033260658 0.20874071, 0.10721408 -0.0331956 0.2086079, 0.10687503 -0.033198461 0.20864655, 0.10721393 -0.033111051 0.20852841, 0.10685885 -0.033116058 0.20856909, 0.1072139 -0.033010557 0.20847033, 0.10684715 -0.033018008 0.20851193, 0.10721393 -0.032899305 0.20843711, 0.10684 -0.03290914 0.20847784, 0.1072139 -0.032783344 0.20843051, 0.10683829 -0.032795027 0.20846899, 0.10684192 -0.032681659 0.20848589, 0.11638112 -0.033299133 0.20881429, 0.11638106 -0.033259496 0.20870498, 0.11638111 -0.03319557 0.20860812, 0.1163812 -0.033111081 0.2085284, 0.11638129 -0.033010498 0.20847034, 0.11638117 -0.032899156 0.20843728, 0.1163812 -0.032783255 0.20843041, 0.11638114 -0.032668993 0.20845072, 0.11644888 -0.032909617 0.20843162, 0.11652575 -0.03292717 0.20840961, 0.11644682 -0.032795712 0.20842259, 0.11652011 -0.032816783 0.20839745, 0.11659853 -0.032845095 0.20835201, 0.11652498 -0.032705441 0.208408, 0.11660139 -0.032736853 0.20835586, 0.11647132 -0.033131227 0.20853424, 0.11645627 -0.033018366 0.20846565, 0.11654133 -0.033031598 0.20844337, 0.11668873 -0.032782897 0.20826656, 0.11679576 -0.032880321 0.20809501, 0.1166095 -0.032950655 0.2083668, 0.11649537 -0.033231512 0.20864399, 0.11669217 -0.032885686 0.20826918, 0.11682369 -0.032995746 0.20810661, 0.11657086 -0.033139363 0.20850781, 0.11663342 -0.033049241 0.20839885, 0.11671121 -0.032983765 0.20828542, 0.11687604 -0.03310068 0.20812792, 0.11652389 -0.033292726 0.20877424, 0.11661711 -0.033234939 0.20860851, 0.11667603 -0.033150241 0.20845652, 0.11674446 -0.033074036 0.20831344, 0.11695002 -0.033189312 0.2081582, 0.11667164 -0.03329353 0.20872727, 0.11674061 -0.033239618 0.20854369, 0.11714466 -0.033298418 0.20823792, 0.11645047 -0.032682434 0.20843923, 0.11679934 -0.033165351 0.20835978, 0.11681621 -0.033294573 0.20864558, 0.11687976 -0.033246085 0.20842779, 0.11704135 -0.033256486 0.20819548, 0.11697243 -0.033296004 0.20850557, 0.11764207 -0.033298269 0.20702308, 0.11753879 -0.033256397 0.20698074, 0.1174476 -0.033189282 0.20694318, 0.11737362 -0.03310068 0.20691296, 0.11732104 -0.032995537 0.20689139, 0.11729321 -0.032880262 0.20688, 0.1172424 -0.033224568 0.2059868, 0.11721347 -0.033178553 0.20603636, 0.11727341 -0.03317143 0.20608757, 0.11738876 -0.033041909 0.20672533, 0.11741963 -0.033084258 0.20654881, 0.11735001 -0.032939836 0.20671955, 0.11737415 -0.032995418 0.20655254, 0.11751305 -0.033299908 0.20599213, 0.11749235 -0.033257917 0.20615873, 0.11743264 -0.033262476 0.20606197, 0.11744808 -0.033132538 0.20673457, 0.11748086 -0.033161268 0.20654395, 0.11758672 -0.033298835 0.20610037, 0.11728153 -0.033268288 0.20591953, 0.11736129 -0.033265933 0.20598152, 0.11731055 -0.03321971 0.20604272, 0.11736535 -0.033042058 0.20639876, 0.11742686 -0.033300743 0.20590225, 0.11768219 -0.033290222 0.20677061, 0.11733213 -0.033301309 0.20583285, 0.11754476 -0.033222422 0.20674935, 0.11741219 -0.033119068 0.2063835, 0.11757408 -0.033236608 0.20653632, 0.1174705 -0.033184811 0.20636487, 0.11732624 -0.033079967 0.20626155, 0.11770265 -0.033293769 0.20652571, 0.11736956 -0.033147171 0.20623443, 0.11755501 -0.03324841 0.20633748, 0.11728778 -0.033098951 0.20618767, 0.11742067 -0.033203647 0.20620322, 0.1173265 -0.03316097 0.20615411, 0.11724065 -0.033113226 0.20612708, 0.11766882 -0.03329654 0.2063008, 0.11737107 -0.033212885 0.20611528, 0.11718772 -0.033123121 0.20608059, 0.10815249 -0.03314741 0.20600657, 0.10815254 -0.033217296 0.20592907, 0.10815246 -0.033269361 0.20583826, 0.10815242 -0.033301696 0.20573917, 0.10705148 -0.033105507 0.20639049, 0.10700689 -0.033192292 0.20632444, 0.10695237 -0.033257917 0.20624316, 0.1068908 -0.033298805 0.20615143, 0.107774 -0.033138677 0.20605415, 0.10775788 -0.033212081 0.20597738, 0.10773924 -0.033266887 0.20588735, 0.10771842 -0.033301011 0.20578796, 0.1021315 -0.033101067 0.20969848, 0.10213287 -0.033185884 0.20960622, 0.098857164 -0.033101395 0.21769357, 0.10377721 -0.033105895 0.21438561, 0.098858729 -0.033186212 0.21760149, 0.10373269 -0.033192828 0.21431927, 0.1036782 -0.033258423 0.21423803, 0.10361657 -0.033299193 0.21414627, 0.10487828 -0.033147797 0.21400179, 0.10487828 -0.033302054 0.21373414, 0.10449968 -0.033139125 0.21404904, 0.10487816 -0.033217654 0.21392404, 0.10448381 -0.033212528 0.21397255, 0.10487829 -0.033269837 0.21383362, 0.1044651 -0.033267364 0.21388246, 0.10444432 -0.033301428 0.21378314, 0.11371703 -0.033147737 0.2140018, 0.11371693 -0.033217624 0.2139241, 0.11371703 -0.033269808 0.21383372, 0.11371693 -0.033301994 0.21373419, 0.11428007 -0.033246562 0.2143449, 0.11427884 -0.033287063 0.21412265, 0.11421771 -0.033256575 0.21415983, 0.11406267 -0.032876745 0.2147181, 0.11408198 -0.032938138 0.21455744, 0.1141572 -0.033112928 0.21473318, 0.11395687 -0.033140555 0.21408731, 0.11390373 -0.03314735 0.21404754, 0.11393102 -0.033081457 0.2141231, 0.11388342 -0.033090428 0.21408695, 0.11408597 -0.032977626 0.21472183, 0.11383362 -0.033095047 0.2140623, 0.11411428 -0.033027694 0.2145552, 0.11400625 -0.033129856 0.21414129, 0.1140022 -0.033212617 0.21402483, 0.11426517 -0.033219859 0.21475033, 0.11406124 -0.033206359 0.21408609, 0.11401591 -0.032778665 0.21487384, 0.11401515 -0.032795921 0.21487345, 0.11412582 -0.033263311 0.21402143, 0.11413614 -0.033191994 0.21420968, 0.11407177 -0.032991186 0.21440899, 0.11434457 -0.033306256 0.21408246, 0.1144335 -0.033305153 0.21429795, 0.1143537 -0.033282414 0.21432255, 0.11419103 -0.033144191 0.21454982, 0.11384773 -0.033150956 0.21402043, 0.11435302 -0.033270493 0.21476468, 0.11393878 -0.033216789 0.21397917, 0.11410832 -0.033070132 0.21439785, 0.11417338 -0.033289954 0.21397333, 0.11444986 -0.033302203 0.21478039, 0.11429629 -0.033234403 0.21454255, 0.11405462 -0.033266231 0.21395221, 0.1142247 -0.033306941 0.21392199, 0.11403292 -0.033036873 0.21427265, 0.11418375 -0.033170179 0.21437447, 0.11387236 -0.033218905 0.21394792, 0.11409327 -0.033291265 0.21389906, 0.11437878 -0.033277079 0.21453683, 0.1139791 -0.033268258 0.21390074, 0.1140686 -0.033105895 0.21425073, 0.11413452 -0.033307388 0.21384208, 0.11446932 -0.033303842 0.2145306, 0.11400846 -0.033292249 0.21384351, 0.11397557 -0.033067599 0.21417201, 0.11390015 -0.033269092 0.21386521, 0.11403991 -0.033307418 0.21378246, 0.11392052 -0.033292696 0.21380498, 0.11394219 -0.033307627 0.21374029, 0.11351836 -0.032778814 0.21608871, 0.11351754 -0.032795921 0.21608832, 0.11347516 -0.033248618 0.21655077, 0.11361635 -0.0332544 0.2164318, 0.11341265 -0.033169612 0.21646623, 0.11353883 -0.033182904 0.21636632, 0.11310692 -0.032899663 0.21643233, 0.11317463 -0.032910272 0.21642673, 0.11310692 -0.032783642 0.21642561, 0.11310679 -0.033010975 0.21646535, 0.11370406 -0.033298418 0.21650568, 0.11317262 -0.032796189 0.21641758, 0.11354667 -0.033297196 0.21664739, 0.11324593 -0.03281723 0.21639247, 0.11317617 -0.032682911 0.21643412, 0.11325081 -0.032705948 0.21640296, 0.11325952 -0.032635435 0.21642216, 0.11332715 -0.03273727 0.21635073, 0.11333668 -0.032667533 0.21636349, 0.11310688 -0.033111498 0.21652344, 0.11318374 -0.033035651 0.21646851, 0.11325142 -0.032927617 0.21640439, 0.11342113 -0.032715395 0.21626703, 0.11332437 -0.032845542 0.21634689, 0.11310685 -0.033195987 0.21660298, 0.11320105 -0.033152983 0.21654752, 0.1134145 -0.032783315 0.21626154, 0.11327045 -0.033048168 0.21644579, 0.11333534 -0.032951161 0.21636167, 0.11341783 -0.032886192 0.21626428, 0.11310685 -0.03329958 0.21680933, 0.11310695 -0.033259884 0.21670012, 0.1132244 -0.033241704 0.21665442, 0.11330432 -0.033160105 0.21651964, 0.11336415 -0.033064738 0.21640061, 0.11343691 -0.032984301 0.21628037, 0.11325158 -0.033295766 0.21677759, 0.11334924 -0.033244714 0.21661755, 0.11310694 -0.0326695 0.21644573, 0.11318147 -0.03261216 0.21645851, 0.11347683 -0.033088103 0.21631417, 0.11340086 -0.033296302 0.21672992, 0.10393971 -0.03329967 0.2168092, 0.10393977 -0.033259913 0.21670011, 0.10393967 -0.033196166 0.21660309, 0.10393982 -0.033111617 0.21652351, 0.10393982 -0.033011004 0.21646534, 0.10393977 -0.032899752 0.21643232, 0.10393973 -0.032783821 0.21642554, 0.10393974 -0.03266947 0.21644583, 0.10364272 -0.033299878 0.21684138, 0.10362062 -0.033261195 0.21673585, 0.1036009 -0.033198878 0.2166419, 0.1035848 -0.033116534 0.2165641, 0.10357277 -0.033018395 0.21650691, 0.10356581 -0.032909557 0.21647289, 0.10356402 -0.032795385 0.21646421, 0.10356766 -0.032682136 0.21648093, 0.1367196 -0.033300295 0.13655746, 0.13671963 -0.032922223 0.13633931, 0.13639557 -0.033300415 0.1365919, 0.13671969 -0.033276543 0.13649198, 0.13638216 -0.033277139 0.1365286, 0.1367196 -0.033238187 0.13643372, 0.13637039 -0.033239946 0.13647212, 0.13671967 -0.033187464 0.13638611, 0.13636059 -0.033190444 0.1364256, 0.1367196 -0.033127144 0.13635117, 0.13635351 -0.033131614 0.13639104, 0.13671964 -0.033060297 0.13633119, 0.13634925 -0.033066258 0.13637081, 0.13671966 -0.032990828 0.13632709, 0.13634825 -0.032997862 0.13636552, 0.1363505 -0.032929763 0.13637565, 0.13600363 -0.033167854 0.13652182, 0.096679091 -0.032779351 0.22411801, 0.096729368 0.085303441 0.26605132, 0.096729457 0.085224435 0.26612866, 0.096008793 0.084687009 0.26632357, 0.096004426 0.08475177 0.26634306, 0.095996946 0.08481814 0.26635376, 0.095976666 0.084934518 0.26635194, 0.095948309 0.08504571 0.26632419, 0.095913574 0.085145667 0.26627153, 0.095874369 0.085228547 0.26619744, 0.096340626 0.08504881 0.26624408, 0.096729368 0.085130468 0.26618662, 0.096729368 0.085026041 0.26622275, 0.10556814 0.085303321 0.26605129, 0.10556808 0.085224494 0.26612872, 0.10556807 0.085130617 0.26618671, 0.10556814 0.08502607 0.26622283, 0.10574827 0.084708616 0.26623547, 0.10583588 0.084764168 0.26630974, 0.10582706 0.084679887 0.2662791, 0.10575482 0.084793255 0.26626313, 0.10570113 0.08511968 0.26620236, 0.10568346 0.08501409 0.26623589, 0.10567006 0.084903166 0.26624525, 0.10579456 0.084991261 0.26627254, 0.10576834 0.084880814 0.26627666, 0.10585496 0.084850714 0.26632726, 0.1057224 0.085214391 0.26614618, 0.10582998 0.085095689 0.26624513, 0.10589288 0.084958687 0.2663309, 0.10574597 0.085293457 0.2660706, 0.10587248 0.085188672 0.26619554, 0.10594401 0.085059807 0.2663132, 0.10591993 0.085265204 0.26612687, 0.10600594 0.085148081 0.26627487, 0.10607496 0.08521913 0.26621825, 0.10565957 0.08473067 0.26621032, 0.10566315 0.084815547 0.26623535, 0.10585164 0.084344253 0.26796609, 0.10575005 0.084326908 0.26791, 0.10565986 0.084285453 0.26784727, 0.10558616 0.084222183 0.26778144, 0.10553314 0.084140494 0.26771581, 0.10550353 0.084044978 0.26765418, 0.10569093 0.084276482 0.2680136, 0.10561034 0.084243342 0.2679373, 0.1055437 0.084187433 0.26786005, 0.10553949 0.084204778 0.2680217, 0.10548311 0.084155992 0.26793435, 0.10541674 0.083999798 0.26778269, 0.10529211 0.084052607 0.26795775, 0.10527804 0.083974823 0.26787966, 0.1054413 0.084086344 0.26785326, 0.10519806 0.083972141 0.26790792, 0.10511747 0.083975717 0.26792103, 0.10578185 0.084285066 0.26808524, 0.1056076 0.084229752 0.26810956, 0.10531479 0.084111288 0.26804915, 0.10520551 0.08404617 0.26798785, 0.10511735 0.084046945 0.26800191, 0.10568388 0.084230497 0.26819503, 0.10534459 0.084148303 0.26814926, 0.10521668 0.084101036 0.26808155, 0.10511753 0.084099218 0.26809597, 0.10538 0.084161595 0.26825288, 0.10523161 0.084134147 0.26818407, 0.1051175 0.084130123 0.26819912, 0.10541946 0.084150746 0.26835588, 0.10524902 0.08414416 0.26829076, 0.10511753 0.084138379 0.26830631, 0.10511753 0.084123179 0.26841295, 0.10526861 0.084130332 0.26839733, 0.10546741 0.084020242 0.26772004, 0.10549514 0.084111407 0.26778638, 0.09595044 0.083975658 0.26792115, 0.095950454 0.084046826 0.26800191, 0.09595038 0.084099069 0.26809597, 0.09595044 0.084129974 0.26819903, 0.095950425 0.084138259 0.26830643, 0.095950365 0.084123239 0.26841307, 0.095373824 0.084076509 0.26850516, 0.09533672 0.084088102 0.26840135, 0.095303342 0.084075347 0.26829633, 0.095275477 0.084038958 0.26819581, 0.095254034 0.083981082 0.26810411, 0.095240667 0.083904073 0.26802582, 0.099616587 0.088404641 0.25984967, 0.099616498 0.088325873 0.25992706, 0.098895967 0.087788269 0.2601217, 0.098891512 0.087853089 0.26014125, 0.098884076 0.087919489 0.26015225, 0.098863691 0.088035837 0.26015061, 0.098835394 0.088147029 0.26012263, 0.098800674 0.088246956 0.26006997, 0.098761633 0.088329896 0.2599957, 0.099227637 0.088150159 0.26004261, 0.099616572 0.088231757 0.25998527, 0.099616587 0.08812736 0.26002109, 0.10845511 0.088404879 0.25984979, 0.10845517 0.088325784 0.25992715, 0.10845515 0.088231847 0.25998533, 0.10845527 0.08812736 0.26002103, 0.10871409 0.087781206 0.2600778, 0.1087231 0.087865517 0.26010817, 0.10863544 0.087809846 0.26003402, 0.108642 0.087894604 0.26006144, 0.10858829 0.088221028 0.26000059, 0.10857055 0.088115498 0.26003423, 0.10868157 0.08809258 0.26007083, 0.10855715 0.088004515 0.26004356, 0.10865536 0.087982252 0.26007494, 0.10874209 0.087952092 0.26012576, 0.10860948 0.08831577 0.2599445, 0.10871705 0.088196978 0.26004344, 0.10878001 0.088060096 0.26012945, 0.10863325 0.088394806 0.2598691, 0.10875949 0.088289902 0.25999394, 0.10883115 0.088161126 0.26011154, 0.10880692 0.088366464 0.25992525, 0.10889283 0.088249579 0.26007333, 0.10896192 0.088320658 0.26001662, 0.10854661 0.087832019 0.26000887, 0.10855038 0.087916806 0.26003373, 0.10873881 0.087445512 0.26176456, 0.10863718 0.087428167 0.26170826, 0.10854693 0.087386712 0.26164567, 0.10847339 0.087323382 0.26157963, 0.10842031 0.087241754 0.26151407, 0.10839057 0.087146148 0.26145256, 0.10857819 0.087377563 0.26181206, 0.10849749 0.087344602 0.26173592, 0.10843074 0.087288544 0.26165855, 0.10842682 0.087305769 0.26182002, 0.10837024 0.087257251 0.26173294, 0.10830382 0.087100878 0.26158118, 0.10817944 0.087153658 0.261756, 0.10816509 0.087076113 0.26167804, 0.10832849 0.087187484 0.26165172, 0.1080853 0.087073341 0.26170614, 0.1080047 0.087076828 0.26171941, 0.10866895 0.087386206 0.26188359, 0.10849477 0.087331042 0.26190799, 0.10820211 0.087212488 0.26184744, 0.10809255 0.087147281 0.2617861, 0.10800475 0.087148055 0.26180017, 0.10857099 0.087331757 0.26199317, 0.10823181 0.087249294 0.26194754, 0.10810398 0.087202176 0.26187998, 0.1080046 0.087200359 0.26189429, 0.10826705 0.087262675 0.26205125, 0.10811868 0.087235346 0.26198259, 0.10800466 0.087231353 0.26199734, 0.10830659 0.087252006 0.26215422, 0.10813609 0.08724536 0.26208916, 0.10800467 0.08723937 0.26210469, 0.10800466 0.087224439 0.2622112, 0.10815567 0.087231621 0.26219559, 0.1083546 0.087121382 0.26151848, 0.10838223 0.087212607 0.26158464, 0.098837525 0.087076798 0.26171935, 0.098837465 0.087148204 0.26180008, 0.098837465 0.087200418 0.2618944, 0.098837465 0.087231353 0.26199737, 0.09883754 0.087239459 0.26210469, 0.098837525 0.087224379 0.26221144, 0.09826082 0.087177739 0.26230335, 0.098223969 0.087189153 0.26219994, 0.098190486 0.087176427 0.26209486, 0.098162606 0.087140307 0.26199389, 0.098141313 0.087082192 0.26190233, 0.098127812 0.087005273 0.26182416, 0.10250352 0.09150596 0.25364804, 0.10250352 0.091427043 0.25372553, 0.10178311 0.090889558 0.25392026, 0.10177857 0.090954319 0.25393963, 0.10177098 0.091020659 0.2539506, 0.10175072 0.091137007 0.25394905, 0.10172246 0.091248229 0.25392097, 0.10168777 0.091348127 0.25386846, 0.10164867 0.091430977 0.25379419, 0.10211471 0.091251299 0.25384092, 0.1025036 0.091332838 0.2537834, 0.10250352 0.09122844 0.2538197, 0.11134225 0.091505989 0.25364816, 0.11134231 0.091427013 0.25372553, 0.11134218 0.091333166 0.25378358, 0.11134234 0.0912285 0.25381953, 0.11152256 0.090911075 0.25383234, 0.11161008 0.090966716 0.25390634, 0.11160126 0.090882376 0.253876, 0.11152911 0.090995833 0.25385988, 0.11147545 0.091322199 0.25379908, 0.11145754 0.091216728 0.2538327, 0.11156879 0.09119387 0.25386912, 0.11144434 0.091105714 0.25384212, 0.11154257 0.091083363 0.25387329, 0.11162925 0.091053054 0.25392401, 0.1114966 0.09141703 0.25374299, 0.11160405 0.091298237 0.25384176, 0.1116671 0.091161236 0.25392765, 0.11152025 0.091496035 0.25366729, 0.11164665 0.091391131 0.25379229, 0.11171818 0.091262206 0.25391001, 0.1116941 0.091467664 0.2537235, 0.11178005 0.0913506 0.25387132, 0.11184907 0.091421768 0.25381482, 0.1114338 0.090933189 0.25380725, 0.11143728 0.091018006 0.25383228, 0.111626 0.090546861 0.25556272, 0.11152425 0.090529457 0.25550681, 0.11143422 0.090487882 0.25544393, 0.11136043 0.090424702 0.25537819, 0.11130738 0.090342924 0.25531256, 0.11127788 0.090247497 0.25525093, 0.11119102 0.090202346 0.25537953, 0.11105227 0.090177462 0.2554763, 0.11146522 0.090478942 0.25561041, 0.11138463 0.090445802 0.25553411, 0.11131793 0.090390071 0.25545698, 0.11131376 0.090407297 0.25561839, 0.11125737 0.0903586 0.25553131, 0.11106654 0.090254918 0.25555462, 0.11121547 0.090288922 0.25545007, 0.11097229 0.09017472 0.25550467, 0.11089194 0.090178177 0.25551772, 0.11155608 0.090487495 0.25568184, 0.11138177 0.090432331 0.25570637, 0.11108914 0.090313807 0.25564593, 0.1109798 0.09024851 0.25558454, 0.11089191 0.090249375 0.25559863, 0.11145821 0.090433016 0.2557916, 0.111119 0.090350702 0.25574604, 0.11099106 0.090303525 0.25567847, 0.11089185 0.090301648 0.25569257, 0.11115432 0.090363905 0.25584972, 0.11100599 0.090336576 0.25578111, 0.11089173 0.090332642 0.2557959, 0.11119366 0.090353295 0.25595278, 0.11102331 0.0903465 0.25588769, 0.11089185 0.090340748 0.2559031, 0.11089185 0.090325728 0.25600988, 0.11104289 0.090332881 0.25599426, 0.11124179 0.090222731 0.25531679, 0.11126937 0.090313956 0.25538307, 0.10172476 0.090178117 0.25551784, 0.10172479 0.090249315 0.2555986, 0.10172465 0.090301618 0.2556926, 0.10172476 0.090332493 0.25579572, 0.10172476 0.090340599 0.25590301, 0.10172476 0.090325579 0.25600982, 0.10114804 0.090278968 0.256102, 0.10111107 0.090290472 0.25599819, 0.10107766 0.090277746 0.25589323, 0.10104968 0.090241477 0.25579256, 0.10102858 0.090183362 0.25570071, 0.10101499 0.090106472 0.25562239, 0.10539092 0.094607159 0.24744661, 0.1053908 0.094528213 0.24752386, 0.10467032 0.093990818 0.2477186, 0.10466586 0.094055548 0.24773799, 0.10465838 0.094121858 0.24774893, 0.10463808 0.094238296 0.24774733, 0.10460974 0.094349489 0.24771941, 0.10457502 0.094449446 0.24766676, 0.1045358 0.094532356 0.24759255, 0.10500191 0.094352469 0.2476394, 0.10539092 0.094434246 0.24758203, 0.10539088 0.094329849 0.24761806, 0.11422956 0.094607159 0.24744664, 0.11422944 0.094528243 0.24752377, 0.11422947 0.094434336 0.24758197, 0.11422947 0.094329879 0.24761811, 0.11448847 0.093983755 0.24767448, 0.11449729 0.094068035 0.24770488, 0.11440967 0.094012335 0.24763063, 0.11441627 0.094097123 0.24765837, 0.11436269 0.094423428 0.24759746, 0.11434482 0.094317928 0.24763097, 0.11445603 0.094295159 0.24766767, 0.11433148 0.094207004 0.24764059, 0.1144297 0.094184652 0.24767174, 0.11451633 0.094154552 0.24772243, 0.11438385 0.094518229 0.24754126, 0.11449133 0.094399527 0.24764021, 0.11455427 0.094262496 0.24772608, 0.11440745 0.094597355 0.24746579, 0.11453377 0.094492391 0.24759074, 0.11460549 0.094363496 0.24770838, 0.1145812 0.094568953 0.24752206, 0.1146673 0.094451979 0.24766992, 0.1147363 0.094523147 0.24761336, 0.11432105 0.094034448 0.24760556, 0.11432455 0.094119266 0.24763067, 0.11451298 0.093648151 0.24936119, 0.1144115 0.093630716 0.24930529, 0.11432119 0.093589231 0.24924241, 0.11424756 0.093525842 0.24917635, 0.1141945 0.093444183 0.24911085, 0.11416501 0.093348697 0.2490494, 0.11407815 0.093303457 0.24917793, 0.11393952 0.093278602 0.24927494, 0.11435245 0.093580171 0.24940881, 0.11427175 0.093547091 0.24933261, 0.11420512 0.093491033 0.24925527, 0.11420083 0.093508318 0.2494168, 0.11414444 0.0934598 0.24932966, 0.11395371 0.093356207 0.24935278, 0.11410272 0.093390062 0.24924836, 0.11385953 0.09327586 0.24930319, 0.11377889 0.093279436 0.24931619, 0.11444333 0.093588695 0.24948025, 0.11426891 0.09353359 0.24950497, 0.1139763 0.093415037 0.24944423, 0.11386681 0.09334977 0.24938294, 0.11377893 0.093350634 0.24939698, 0.11434534 0.093534335 0.24959016, 0.11400603 0.093451872 0.24954438, 0.11387831 0.093404785 0.24947666, 0.11377898 0.093402907 0.24949104, 0.1140414 0.093465284 0.2496482, 0.11389294 0.093437836 0.24957947, 0.11377901 0.093433872 0.24959408, 0.11408091 0.093454435 0.24975094, 0.1139105 0.09344776 0.24968603, 0.11377898 0.093442008 0.24970144, 0.11377893 0.093426958 0.24980807, 0.11393008 0.09343414 0.2497924, 0.11412902 0.093323782 0.24911527, 0.11415648 0.093415216 0.24918136, 0.10461184 0.093279198 0.24931623, 0.10461183 0.093350634 0.24939714, 0.10461184 0.093402848 0.24949099, 0.10461172 0.093433723 0.24959423, 0.10461177 0.093441829 0.24970156, 0.10461183 0.093426928 0.24980821, 0.10403518 0.093380228 0.24990037, 0.10399818 0.093391702 0.24979673, 0.10396481 0.093378946 0.24969169, 0.10393679 0.093342677 0.24959093, 0.10391559 0.093284592 0.24949914, 0.10390207 0.093207583 0.24942066, 0.10827789 0.097708419 0.24124512, 0.10827801 0.097629502 0.24132213, 0.10755739 0.097092167 0.24151717, 0.10755302 0.097156689 0.24153645, 0.10754539 0.097223207 0.24154718, 0.10752513 0.097339526 0.24154563, 0.10749692 0.097450778 0.24151759, 0.10746203 0.097550675 0.2414652, 0.10742293 0.097633556 0.24139081, 0.10788904 0.097453877 0.24143802, 0.10827789 0.097535565 0.2413803, 0.10827789 0.097431079 0.24141659, 0.11711667 0.097708449 0.24124496, 0.11711659 0.097629622 0.24132219, 0.11711667 0.097535476 0.24138035, 0.11711667 0.09743093 0.24141662, 0.11737554 0.097084865 0.24147291, 0.1173843 0.097169265 0.2415033, 0.11729692 0.097113594 0.24142911, 0.11730328 0.097198412 0.24145667, 0.1172497 0.097524717 0.24139582, 0.11723183 0.097419187 0.24142951, 0.1173431 0.09739621 0.24146597, 0.11721852 0.097308233 0.24143891, 0.11731681 0.097285911 0.24147032, 0.11740345 0.097255751 0.2415209, 0.11727089 0.097619459 0.24133958, 0.11737838 0.097500637 0.24143855, 0.11744134 0.097363815 0.24152465, 0.11729461 0.097698584 0.241264, 0.11742094 0.09759362 0.24138908, 0.11749247 0.097464755 0.2415067, 0.11746846 0.097670183 0.24132039, 0.11755435 0.097553238 0.2414685, 0.11762331 0.097624287 0.24141185, 0.11720811 0.097135767 0.2414041, 0.11721168 0.097220525 0.24142902, 0.11740036 0.096749261 0.24315949, 0.11729842 0.096732065 0.2431035, 0.11720851 0.096690491 0.24304093, 0.11713469 0.096627221 0.24297489, 0.11708164 0.096545562 0.24290924, 0.1170522 0.096450076 0.24284782, 0.11696529 0.096404895 0.24297632, 0.11682656 0.09638001 0.24307339, 0.11723951 0.09668155 0.24320734, 0.11715877 0.09664844 0.24313097, 0.11709231 0.096592352 0.24305367, 0.11708795 0.096609756 0.24321526, 0.11703153 0.096561149 0.24312815, 0.11684075 0.096457586 0.24315137, 0.11698993 0.096491322 0.24304697, 0.11674653 0.096377298 0.24310154, 0.11666615 0.096380666 0.24311467, 0.11733043 0.096690044 0.243279, 0.11715603 0.096634969 0.24330319, 0.11686343 0.096516356 0.2432428, 0.11675411 0.096451119 0.24318138, 0.11666611 0.096451953 0.24319516, 0.1172324 0.096635595 0.24338843, 0.1168932 0.096553281 0.24334288, 0.11676538 0.096505985 0.24327518, 0.11666608 0.096504167 0.24328937, 0.11692853 0.096566513 0.24344654, 0.11678022 0.096539125 0.24337786, 0.11666611 0.096535161 0.24339257, 0.11696784 0.096555874 0.24354951, 0.11679767 0.096549138 0.24348445, 0.11666608 0.096543297 0.24350001, 0.116666 0.096528277 0.24360663, 0.11681712 0.096535429 0.24359097, 0.11701596 0.09642528 0.24291353, 0.11704361 0.096516475 0.24297969, 0.10749897 0.096380785 0.24311464, 0.10749879 0.096452013 0.24319534, 0.1074989 0.096504226 0.24328931, 0.10749897 0.096535161 0.24339266, 0.10749899 0.096543238 0.24349996, 0.10749894 0.096528217 0.24360652, 0.10692237 0.096481606 0.24369857, 0.10688522 0.09649308 0.24359478, 0.10685207 0.096480265 0.24348992, 0.10682394 0.096444055 0.2433892, 0.10680276 0.096386001 0.24329765, 0.10678922 0.096309081 0.24321929, 0.11693938 0.10701226 0.22264029, 0.11693946 0.10693325 0.22271755, 0.11621884 0.10639568 0.22291224, 0.11621441 0.10646056 0.22293156, 0.1162069 0.10652681 0.2229425, 0.11618669 0.10664324 0.22294088, 0.11615828 0.10675438 0.22291298, 0.11612347 0.10685439 0.22286026, 0.11608432 0.10693727 0.22278611, 0.11655046 0.10675748 0.22283295, 0.11693934 0.10683919 0.22277549, 0.11693926 0.10673477 0.22281165, 0.12577799 0.1070122 0.22264022, 0.12577799 0.10693328 0.22271758, 0.12577799 0.10683922 0.22277552, 0.12577799 0.1067348 0.22281176, 0.12603691 0.10638876 0.22286814, 0.12604578 0.10647298 0.22289857, 0.12595811 0.10641737 0.22282439, 0.12596469 0.10650204 0.22285199, 0.12591103 0.1068285 0.22279093, 0.12589327 0.10672291 0.22282451, 0.12600461 0.10670005 0.22286128, 0.12588003 0.10661195 0.2228341, 0.12597816 0.1065896 0.2228653, 0.12606481 0.10655947 0.22291607, 0.12593234 0.10692312 0.2227347, 0.12603977 0.10680448 0.22283374, 0.1261026 0.10666759 0.22291988, 0.12595597 0.1070023 0.22265944, 0.12608249 0.10689737 0.22278437, 0.12615409 0.10676844 0.22290176, 0.12612978 0.10697396 0.22271556, 0.12621577 0.10685696 0.22286364, 0.12628476 0.10692792 0.22280689, 0.12586942 0.10643943 0.22279924, 0.12587307 0.10652421 0.22282416, 0.12606168 0.10605295 0.22455481, 0.12595992 0.10603563 0.22449867, 0.12586981 0.10599412 0.22443599, 0.12579623 0.10593082 0.22437003, 0.12574308 0.10584931 0.22430436, 0.12571339 0.1057537 0.22424297, 0.12590104 0.10598518 0.22460228, 0.1258202 0.10595219 0.22452618, 0.12575369 0.10589616 0.22444884, 0.12574944 0.10591342 0.22461042, 0.12569301 0.10586469 0.22452335, 0.12562673 0.10570841 0.2243716, 0.12550227 0.10576133 0.22454645, 0.12548789 0.10568367 0.22446853, 0.12565142 0.10579504 0.22444196, 0.12540787 0.1056809 0.22449681, 0.12532756 0.10568441 0.22450976, 0.12599175 0.10599379 0.22467391, 0.12581736 0.10593866 0.22469854, 0.1255248 0.10582016 0.22463806, 0.12541537 0.1057549 0.22457661, 0.1253275 0.10575567 0.22459051, 0.12589392 0.10593928 0.22478358, 0.12555461 0.10585688 0.22473788, 0.12542678 0.1058097 0.22467038, 0.1253275 0.105808 0.2246846, 0.12558994 0.10587038 0.22484176, 0.1254416 0.10584287 0.22477297, 0.12532735 0.10583894 0.2247878, 0.12562947 0.1058595 0.22494458, 0.12545888 0.10585283 0.22487962, 0.12532747 0.10584711 0.22489518, 0.12532739 0.10583214 0.22500171, 0.12547848 0.10583915 0.22498617, 0.12567751 0.10572891 0.22430889, 0.12570517 0.1058201 0.22437482, 0.11616042 0.10568435 0.22450976, 0.11616035 0.10575573 0.22459045, 0.11616035 0.10580795 0.22468463, 0.11616029 0.10583885 0.22478786, 0.11616035 0.10584705 0.22489515, 0.11616035 0.10583203 0.22500172, 0.11558381 0.10578538 0.22509371, 0.11554678 0.10579683 0.22499019, 0.11551337 0.10578404 0.22488511, 0.11548539 0.10574783 0.22478445, 0.1154642 0.10568978 0.2246927, 0.1154507 0.10561277 0.22461446, 0.11857936 0.10995455 0.2167532, 0.11863565 0.10987709 0.21681909, 0.11868565 0.10978265 0.21686475, 0.11872692 0.10967623 0.21688813, 0.11982644 0.11011349 0.21643858, 0.11982641 0.11003448 0.21651585, 0.11910594 0.10949717 0.21671061, 0.11910152 0.10956182 0.21672992, 0.11909392 0.10962825 0.21674104, 0.11907366 0.10974459 0.21673937, 0.11904523 0.10985582 0.21671122, 0.11901069 0.10995568 0.21665864, 0.11897154 0.11003862 0.2165844, 0.11943738 0.10985895 0.21663134, 0.11982647 0.10994057 0.21657379, 0.11982644 0.10983606 0.21661006, 0.1286651 0.11011355 0.21643859, 0.12866515 0.11003457 0.2165159, 0.12866513 0.10994057 0.21657382, 0.12866507 0.10983615 0.2166101, 0.12876101 0.10953997 0.21659842, 0.12885599 0.1096022 0.21665215, 0.1288493 0.10951735 0.21662447, 0.12892377 0.10949008 0.21666622, 0.12906806 0.10972981 0.21679267, 0.12912615 0.10968493 0.21688226, 0.12902083 0.10962574 0.21678001, 0.12907195 0.10958605 0.21685892, 0.12878591 0.10982339 0.21662426, 0.12877209 0.10971247 0.21663347, 0.12904517 0.10950403 0.21683106, 0.12907852 0.10944931 0.21694952, 0.12903275 0.10942166 0.21679574, 0.12906435 0.10936959 0.21691081, 0.12886979 0.10968964 0.21666569, 0.1287647 0.10962473 0.21662346, 0.12917116 0.11002959 0.21660466, 0.12902474 0.11007349 0.21651746, 0.12897612 0.10999708 0.2165857, 0.12910213 0.10995845 0.21666139, 0.12906118 0.10933374 0.21699753, 0.12893249 0.10957448 0.2166962, 0.1290393 0.10932629 0.21709913, 0.12904045 0.10987003 0.21669987, 0.12920929 0.10990719 0.21676332, 0.129132 0.10982539 0.21678707, 0.12880446 0.10992892 0.21659076, 0.12898664 0.10945742 0.21672472, 0.12910821 0.10952656 0.21698564, 0.12919928 0.10977332 0.21689099, 0.12889655 0.10980009 0.21666196, 0.12907602 0.10941128 0.21703917, 0.12906899 0.10942177 0.2171604, 0.12895167 0.10966091 0.21671431, 0.12929572 0.1099705 0.21672255, 0.12882693 0.11002375 0.21653494, 0.12916704 0.10961626 0.21702519, 0.12899743 0.10954098 0.21675745, 0.12928802 0.10984628 0.21688485, 0.12910622 0.109484 0.21708079, 0.12912191 0.10950343 0.21722609, 0.12893267 0.10990454 0.21663472, 0.1292464 0.10969232 0.21705639, 0.12898932 0.10976903 0.21671775, 0.12938695 0.10989998 0.21686387, 0.12916483 0.10956626 0.21713251, 0.12919559 0.10956673 0.21729201, 0.12885156 0.11010255 0.21645959, 0.12934233 0.10975082 0.21707714, 0.1292434 0.10963275 0.21717951, 0.12928589 0.10960816 0.2173548, 0.12944941 0.10978864 0.21708679, 0.12933759 0.10968037 0.21722001, 0.12938739 0.10962562 0.21741086, 0.12944274 0.10970648 0.21725188, 0.12860061 0.10885508 0.2180413, 0.12863018 0.10895066 0.21810299, 0.12868337 0.10903232 0.21816859, 0.1287569 0.10909562 0.21823448, 0.12884709 0.10913695 0.21829709, 0.12894872 0.1091543 0.21835324, 0.12851371 0.10880987 0.21816999, 0.12837502 0.10878505 0.21826705, 0.12878813 0.10908644 0.21840078, 0.1287073 0.10905342 0.2183246, 0.12864067 0.10899757 0.21824726, 0.12863649 0.10901468 0.21840888, 0.12858014 0.10896607 0.21832174, 0.12838933 0.10886247 0.21834496, 0.12853834 0.10889633 0.21824053, 0.12829508 0.10878234 0.21829504, 0.12821461 0.10878579 0.21830815, 0.12887873 0.10909502 0.2184723, 0.12870456 0.10903983 0.21849686, 0.1284119 0.10892133 0.21843642, 0.12830247 0.10885613 0.21837503, 0.12821452 0.1088569 0.21838892, 0.12878087 0.10904057 0.218582, 0.12844171 0.10895805 0.21853632, 0.12831382 0.10891102 0.21846889, 0.12821449 0.10890917 0.21848291, 0.12847699 0.1089714 0.21864003, 0.12832873 0.10894404 0.21857147, 0.12821466 0.10894011 0.21858627, 0.12851648 0.10896082 0.21874303, 0.1283461 0.108954 0.21867794, 0.12821461 0.10894828 0.21869355, 0.12821467 0.1089332 0.2188001, 0.12836559 0.10894047 0.21878448, 0.12856449 0.10883026 0.2181074, 0.12859218 0.10892145 0.21817347, 0.1190474 0.10878594 0.21830831, 0.11904752 0.1088569 0.21838896, 0.1190474 0.10890912 0.21848302, 0.11904748 0.10893999 0.21858619, 0.11904743 0.10894828 0.21869369, 0.11904742 0.10893326 0.21880019, 0.11847064 0.10888653 0.21889217, 0.11843374 0.10889809 0.2187887, 0.11840042 0.10888524 0.21868356, 0.11837244 0.10884891 0.21858279, 0.11835125 0.10879092 0.21849127, 0.11833768 0.108714 0.21841285, 0.11327328 0.10273068 0.23120338, 0.11327305 0.10274576 0.23109692, 0.11327313 0.10273762 0.23098943, 0.11327311 0.10265441 0.23079222, 0.11327316 0.10270672 0.23088628, 0.11327317 0.10258318 0.23071158, 0.11269656 0.10268398 0.23129538, 0.1126596 0.10269539 0.23119184, 0.11262625 0.10268264 0.23108695, 0.11259824 0.10264654 0.23098618, 0.11257693 0.10258855 0.23089452, 0.11256364 0.10251151 0.23081607, 0.12244046 0.1025833 0.23071137, 0.12244046 0.10265447 0.23079208, 0.1224405 0.10270669 0.23088618, 0.12244041 0.10273759 0.23098922, 0.12244041 0.10274573 0.23109689, 0.12244041 0.10273062 0.23120341, 0.12273951 0.10260744 0.23057321, 0.12260084 0.10258241 0.23067011, 0.12307282 0.10293452 0.23070037, 0.12301376 0.10288404 0.23080397, 0.12298274 0.10289301 0.23063762, 0.12293319 0.10285093 0.23072775, 0.12286229 0.10281222 0.23081195, 0.12286656 0.10279487 0.2306506, 0.12280591 0.10276361 0.23072496, 0.12276419 0.10269387 0.23064354, 0.1226151 0.10266019 0.23074804, 0.12252088 0.10257976 0.23069823, 0.12310477 0.1028925 0.23087566, 0.1231745 0.10295175 0.23075625, 0.12293036 0.10283746 0.23089999, 0.12263764 0.10271893 0.23083954, 0.12252828 0.10265361 0.23077829, 0.1230067 0.10283817 0.23098531, 0.12266739 0.10275574 0.23093954, 0.12253961 0.10270862 0.23087209, 0.12270276 0.10276894 0.23104319, 0.1225545 0.10274158 0.23097441, 0.1227423 0.1027583 0.23114625, 0.12257193 0.10275151 0.23108114, 0.12259142 0.10273783 0.23118778, 0.12282641 0.10265262 0.23044446, 0.12279035 0.10262765 0.23051028, 0.12285598 0.10274811 0.23050609, 0.12281802 0.10271882 0.23057628, 0.12290907 0.10282971 0.2305717, 0.12307103 0.10331623 0.2290259, 0.12315872 0.10337178 0.22909984, 0.12314986 0.10328747 0.22906962, 0.12307763 0.10340084 0.2290535, 0.1228909 0.10373805 0.2289771, 0.12302399 0.10372721 0.22899263, 0.1228909 0.10363357 0.22901332, 0.12300633 0.10362174 0.22902623, 0.12299283 0.10351072 0.22903572, 0.12311752 0.1035987 0.22906293, 0.12309121 0.10348834 0.22906688, 0.12317784 0.10345821 0.22911777, 0.12289083 0.10383214 0.22891919, 0.12304521 0.10382201 0.2289366, 0.12315281 0.10370331 0.22903518, 0.12321563 0.10356633 0.22912151, 0.12306888 0.10390107 0.22886102, 0.1228909 0.10391097 0.22884171, 0.12319525 0.10379617 0.22898595, 0.12326677 0.1036673 0.22910346, 0.12324274 0.10387252 0.2289173, 0.12332878 0.10375561 0.22906512, 0.12339778 0.10382681 0.22900845, 0.12298246 0.10333841 0.22900085, 0.12298591 0.10342304 0.22902577, 0.11405222 0.10391091 0.22884166, 0.11405228 0.10383196 0.22891919, 0.11405218 0.10373805 0.22897726, 0.11405228 0.1036336 0.22901337, 0.1133316 0.10329469 0.22911388, 0.11332731 0.10335924 0.22913328, 0.11331968 0.10342573 0.22914433, 0.11329935 0.10354196 0.22914244, 0.1132711 0.1036533 0.22911471, 0.11323622 0.10375328 0.22906202, 0.11319719 0.10383616 0.22898787, 0.1136632 0.10365652 0.22903472, 0.14678286 -0.022895947 0.14046019, 0.14554028 -0.024537757 0.14043164, 0.14683197 -0.022936001 0.14043814, 0.14687602 -0.022972003 0.14040232, 0.14550744 -0.024638787 0.14040655, 0.14548896 -0.024720147 0.14037281, 0.14691277 -0.023002014 0.14035478, 0.14548557 -0.02475889 0.14034617, 0.14548735 -0.024777606 0.14032686, 0.14694066 -0.023024783 0.14029786, 0.14549108 -0.024788544 0.14031008, 0.14549588 -0.024794415 0.14029539, 0.14550371 -0.024797544 0.14027712, 0.14551456 -0.024795994 0.14025638, 0.14695774 -0.02303876 0.14023465, 0.14553185 -0.024786159 0.14022949, 0.1455553 -0.024765566 0.14019895, 0.14717449 -0.022600278 0.14043811, 0.14758255 -0.022348031 0.14043823, 0.14755537 -0.022290811 0.14046016, 0.14806677 -0.022328243 0.14029792, 0.1485126 -0.022278652 0.14029802, 0.14851271 -0.022242919 0.14035481, 0.14805891 -0.022293314 0.1403549, 0.14762731 -0.022442326 0.14035484, 0.14804842 -0.022247002 0.14040247, 0.14760689 -0.022399381 0.14040232, 0.14720957 -0.022645131 0.14040244, 0.14807165 -0.022349998 0.1402346, 0.14851271 -0.022300854 0.14023453, 0.14764251 -0.022474632 0.14029792, 0.14723888 -0.022682473 0.14035486, 0.1476521 -0.022494659 0.14023456, 0.14726098 -0.022710606 0.14029792, 0.14727466 -0.02272816 0.14023459, 0.14802192 -0.02212961 0.14046031, 0.14851265 -0.022075132 0.14046025, 0.14803593 -0.02219148 0.14043796, 0.14851262 -0.022138461 0.14043799, 0.14851283 -0.022195473 0.14040232, 0.14713548 -0.022550359 0.14046013, 0.15408918 -0.022075102 0.14046027, 0.15408923 -0.022138491 0.14043802, 0.15408926 -0.022195384 0.14040247, 0.15408932 -0.022242889 0.1403549, 0.15408929 -0.022278622 0.14029789, 0.15408923 -0.022300854 0.14023447, 0.15454872 -0.022294655 0.14035481, 0.15455933 -0.022248343 0.14040232, 0.15599294 -0.02339153 0.1404023, 0.15620457 -0.023825452 0.14043809, 0.15604413 -0.023366973 0.14043811, 0.1549854 -0.022447363 0.14035469, 0.15500596 -0.022404566 0.14040232, 0.15614915 -0.023838088 0.14040235, 0.15496032 -0.022499606 0.14023456, 0.15534094 -0.022738829 0.14023453, 0.15535477 -0.022721425 0.14029795, 0.15496981 -0.022479579 0.14029804, 0.15578569 -0.022955462 0.14043812, 0.15610124 -0.023339316 0.14046018, 0.1558353 -0.022915855 0.14046019, 0.15454079 -0.022329465 0.14029789, 0.15548158 -0.02256231 0.14046016, 0.15453599 -0.022351131 0.14023462, 0.15606809 -0.023856685 0.14029792, 0.15609673 -0.024308279 0.14023447, 0.15611902 -0.024308279 0.14029777, 0.15610287 -0.023848668 0.14035469, 0.15595007 -0.023412153 0.1403549, 0.15574118 -0.022990897 0.14040232, 0.15544219 -0.022611901 0.14043806, 0.15604641 -0.023861572 0.14023452, 0.15505815 -0.022296235 0.14046016, 0.1559179 -0.02342765 0.14029793, 0.15570404 -0.023020551 0.1403548, 0.15540674 -0.022656456 0.14040226, 0.1550307 -0.022353426 0.14043814, 0.155898 -0.023437336 0.14023453, 0.15458626 -0.022131011 0.14046024, 0.15567616 -0.023042813 0.14029789, 0.15537691 -0.02269344 0.14035478, 0.15626645 -0.023811385 0.1404604, 0.15625909 -0.024308339 0.14043796, 0.15632251 -0.024308339 0.14046013, 0.15457205 -0.02219294 0.14043811, 0.15620206 -0.024308249 0.14040221, 0.15565877 -0.023056641 0.14023454, 0.15615469 -0.024308249 0.14035484, 0.15632251 -0.027198091 0.14046019, 0.15625903 -0.027198032 0.14043796, 0.15620223 -0.027198091 0.14040232, 0.15615466 -0.027198091 0.14035475, 0.15611896 -0.027198002 0.14029786, 0.15609673 -0.027198121 0.14023462, 0.15579873 -0.02794458 0.14029789, 0.15562207 -0.02805306 0.14023459, 0.15563378 -0.028071955 0.14029789, 0.15582329 -0.027970448 0.14035463, 0.15596376 -0.027806744 0.14035468, 0.15585595 -0.02800478 0.14040232, 0.15600276 -0.027834013 0.14040232, 0.15574144 -0.028244838 0.14046021, 0.156112 -0.02763693 0.14040212, 0.15604943 -0.027866498 0.14043802, 0.15616435 -0.02765955 0.14043802, 0.15623516 -0.027433649 0.14043808, 0.15622257 -0.027684525 0.1404603, 0.15629715 -0.027446285 0.14046025, 0.15578344 -0.027928397 0.14023462, 0.15593436 -0.0277863 0.1402978, 0.15606838 -0.027618304 0.14035481, 0.15617949 -0.027422205 0.14040208, 0.1559162 -0.027773604 0.14023463, 0.1560356 -0.027604237 0.14029795, 0.15613291 -0.027412578 0.14035484, 0.1560151 -0.027595416 0.14023459, 0.15609793 -0.027405426 0.14029793, 0.15607613 -0.027400866 0.14023459, 0.15593892 -0.028092042 0.14046013, 0.15570791 -0.028190926 0.14043806, 0.15589511 -0.028046086 0.14043802, 0.15567793 -0.028142646 0.14040236, 0.15610141 -0.027902618 0.14046013, 0.15565278 -0.028102323 0.14035468, 0.14541645 -0.024680659 0.14046541, 0.14550419 -0.024522528 0.14045438, 0.14542462 -0.0245419 0.14050838, 0.14546499 -0.024724171 0.14039223, 0.14547475 -0.024651095 0.14042297, 0.14537129 -0.024714842 0.14051913, 0.14536376 -0.024566874 0.1405811, 0.14546485 -0.024775013 0.14035746, 0.14541923 -0.024759784 0.14042443, 0.14546908 -0.024798259 0.14033249, 0.14565666 -0.024068579 0.14047489, 0.14558125 -0.024060175 0.1404977, 0.1455103 -0.024052277 0.14053589, 0.14544845 -0.024045274 0.14058746, 0.14539909 -0.02403979 0.14064945, 0.14547442 -0.024809971 0.14031291, 0.14542837 -0.024815664 0.14037868, 0.14538379 -0.024799451 0.14046416, 0.14548193 -0.024817541 0.14029199, 0.14543751 -0.024841532 0.14034657, 0.14550014 -0.024819002 0.14025149, 0.14544593 -0.024855092 0.14032114, 0.14540072 -0.024859592 0.1404058, 0.14551826 -0.024810061 0.14021847, 0.14545588 -0.024864152 0.14029408, 0.14541413 -0.024888143 0.14036503, 0.14547752 -0.024867967 0.14024192, 0.14542538 -0.024903461 0.14033307, 0.14549695 -0.024860278 0.14019924, 0.1454377 -0.024914101 0.14029998, 0.14546318 -0.024920508 0.14023575, 0.14548545 -0.024914816 0.14018369, 0.1456804 -0.022812083 0.14014952, 0.14574282 -0.022814706 0.14011443, 0.14564149 -0.022966519 0.13991666, 0.1455913 -0.022964194 0.13995481, 0.14536197 -0.022871479 0.14004752, 0.1453044 -0.023204073 0.13979742, 0.14543177 -0.022913322 0.14003256, 0.1456171 -0.022798911 0.14017741, 0.14549835 -0.023237213 0.1395807, 0.14553909 -0.022954479 0.13998699, 0.14554076 -0.022769645 0.14020133, 0.14547393 -0.022932723 0.14001791, 0.14549352 -0.022743627 0.14021054, 0.14541982 -0.022689 0.14021486, 0.14575197 -0.022934303 0.13979664, 0.14544606 -0.023243442 0.13966538, 0.14570723 -0.022955433 0.13985318, 0.14538021 -0.023232207 0.13973889, 0.1458834 -0.022770807 0.13999978, 0.14582609 -0.022799328 0.14005429, 0.13863717 -0.03136985 0.13507463, 0.13871272 -0.031397775 0.13501637, 0.13877891 -0.03140907 0.13494231, 0.13883112 -0.031402752 0.13485779, 0.13825741 -0.032328442 0.13451523, 0.13825731 -0.031917587 0.1347657, 0.1383159 -0.031928077 0.13474168, 0.13838936 -0.031932786 0.13469718, 0.13816856 -0.032192484 0.13460983, 0.13821299 -0.032190278 0.134602, 0.13816677 -0.032285586 0.13455667, 0.13820539 -0.032353297 0.13451518, 0.1382706 -0.032183304 0.13458492, 0.13820475 -0.032277867 0.13455454, 0.13825426 -0.032264844 0.13454664 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 0, 3, 1, -1, 4, 2, 5, -1, 4, 0, 2, -1, 6, 5, 7, -1, 6, 4, 5, -1, 8, 7, 9, -1, 8, 6, 7, -1, 10, 9, 11, -1, 10, 8, 9, -1, 12, 11, 13, -1, 12, 10, 11, -1, 14, 13, 15, -1, 14, 12, 13, -1, 16, 17, 18, -1, 18, 17, 19, -1, 19, 20, 21, -1, 17, 20, 19, -1, 21, 22, 23, -1, 20, 22, 21, -1, 23, 24, 25, -1, 22, 24, 23, -1, 25, 26, 27, -1, 24, 26, 25, -1, 28, 29, 30, -1, 30, 29, 31, -1, 32, 33, 34, -1, 35, 33, 32, -1, 31, 33, 36, -1, 36, 33, 35, -1, 37, 38, 39, -1, 39, 38, 40, -1, 41, 38, 42, -1, 42, 38, 43, -1, 40, 38, 41, -1, 43, 44, 28, -1, 28, 44, 29, -1, 34, 45, 46, -1, 29, 45, 31, -1, 33, 45, 34, -1, 31, 45, 33, -1, 37, 47, 38, -1, 38, 47, 43, -1, 43, 47, 44, -1, 46, 48, 49, -1, 29, 48, 45, -1, 45, 48, 46, -1, 50, 51, 52, -1, 44, 48, 29, -1, 49, 53, 54, -1, 55, 53, 37, -1, 54, 53, 55, -1, 37, 53, 47, -1, 48, 53, 49, -1, 47, 53, 44, -1, 44, 53, 48, -1, 56, 40, 41, -1, 55, 57, 54, -1, 58, 59, 60, -1, 60, 59, 61, -1, 62, 63, 58, -1, 58, 63, 59, -1, 61, 64, 65, -1, 59, 64, 61, -1, 66, 30, 62, -1, 62, 30, 63, -1, 59, 36, 64, -1, 63, 36, 59, -1, 65, 67, 50, -1, 64, 67, 65, -1, 50, 67, 51, -1, 68, 28, 66, -1, 66, 28, 30, -1, 30, 31, 63, -1, 63, 31, 36, -1, 51, 35, 32, -1, 36, 35, 64, -1, 67, 35, 51, -1, 64, 35, 67, -1, 42, 43, 68, -1, 68, 43, 28, -1, 69, 70, 71, -1, 71, 70, 72, -1, 72, 73, 74, -1, 70, 73, 72, -1, 74, 75, 76, -1, 73, 75, 74, -1, 76, 77, 78, -1, 75, 77, 76, -1, 78, 79, 80, -1, 77, 79, 78, -1, 81, 82, 83, -1, 83, 84, 85, -1, 82, 84, 83, -1, 85, 86, 87, -1, 87, 86, 88, -1, 88, 86, 89, -1, 84, 86, 85, -1, 89, 90, 91, -1, 91, 90, 92, -1, 86, 90, 89, -1, 92, 93, 94, -1, 94, 93, 95, -1, 95, 93, 96, -1, 90, 93, 92, -1, 96, 97, 98, -1, 93, 97, 96, -1, 99, 100, 101, -1, 101, 100, 102, -1, 103, 104, 105, -1, 106, 104, 107, -1, 102, 104, 106, -1, 107, 104, 103, -1, 108, 109, 110, -1, 110, 109, 111, -1, 112, 109, 113, -1, 113, 109, 114, -1, 111, 109, 112, -1, 99, 115, 100, -1, 114, 115, 99, -1, 105, 116, 117, -1, 104, 116, 105, -1, 100, 116, 102, -1, 102, 116, 104, -1, 108, 118, 109, -1, 109, 118, 114, -1, 114, 118, 115, -1, 117, 119, 120, -1, 116, 119, 117, -1, 115, 119, 100, -1, 121, 122, 123, -1, 100, 119, 116, -1, 120, 124, 125, -1, 126, 124, 108, -1, 108, 124, 118, -1, 125, 124, 126, -1, 119, 124, 120, -1, 118, 124, 115, -1, 115, 124, 119, -1, 127, 111, 112, -1, 126, 128, 125, -1, 129, 130, 131, -1, 131, 130, 132, -1, 133, 134, 129, -1, 129, 134, 130, -1, 132, 135, 136, -1, 130, 135, 132, -1, 137, 101, 133, -1, 133, 101, 134, -1, 130, 106, 135, -1, 134, 106, 130, -1, 136, 138, 121, -1, 135, 138, 136, -1, 121, 138, 122, -1, 139, 99, 137, -1, 137, 99, 101, -1, 101, 102, 134, -1, 134, 102, 106, -1, 122, 107, 103, -1, 135, 107, 138, -1, 106, 107, 135, -1, 138, 107, 122, -1, 113, 114, 139, -1, 139, 114, 99, -1, 140, 141, 142, -1, 141, 143, 142, -1, 144, 145, 146, -1, 142, 145, 144, -1, 143, 145, 142, -1, 146, 147, 148, -1, 145, 147, 146, -1, 147, 149, 148, -1, 148, 150, 151, -1, 149, 150, 148, -1, 152, 153, 154, -1, 154, 153, 155, -1, 156, 157, 158, -1, 159, 157, 160, -1, 155, 157, 159, -1, 160, 157, 156, -1, 161, 162, 163, -1, 163, 162, 164, -1, 165, 162, 166, -1, 166, 162, 167, -1, 164, 162, 165, -1, 152, 168, 153, -1, 167, 168, 152, -1, 158, 169, 170, -1, 157, 169, 158, -1, 153, 169, 155, -1, 155, 169, 157, -1, 161, 171, 162, -1, 162, 171, 167, -1, 167, 171, 168, -1, 170, 172, 173, -1, 169, 172, 170, -1, 174, 175, 176, -1, 168, 172, 153, -1, 153, 172, 169, -1, 173, 177, 178, -1, 179, 177, 161, -1, 161, 177, 171, -1, 178, 177, 179, -1, 172, 177, 173, -1, 171, 177, 168, -1, 168, 177, 172, -1, 180, 164, 165, -1, 179, 181, 178, -1, 182, 183, 184, -1, 184, 183, 185, -1, 186, 187, 182, -1, 182, 187, 183, -1, 185, 188, 189, -1, 183, 188, 185, -1, 190, 154, 186, -1, 186, 154, 187, -1, 183, 159, 188, -1, 187, 159, 183, -1, 189, 191, 174, -1, 188, 191, 189, -1, 174, 191, 175, -1, 192, 152, 190, -1, 190, 152, 154, -1, 154, 155, 187, -1, 187, 155, 159, -1, 175, 160, 156, -1, 188, 160, 191, -1, 191, 160, 175, -1, 159, 160, 188, -1, 166, 167, 192, -1, 192, 167, 152, -1, 193, 194, 195, -1, 195, 194, 196, -1, 196, 197, 198, -1, 194, 197, 196, -1, 198, 199, 200, -1, 197, 199, 198, -1, 200, 201, 202, -1, 199, 201, 200, -1, 202, 203, 204, -1, 201, 203, 202, -1, 205, 206, 207, -1, 207, 206, 208, -1, 209, 210, 211, -1, 212, 210, 213, -1, 208, 210, 212, -1, 213, 210, 209, -1, 214, 215, 216, -1, 216, 215, 217, -1, 218, 215, 219, -1, 219, 215, 220, -1, 217, 215, 218, -1, 205, 221, 206, -1, 220, 221, 205, -1, 211, 222, 223, -1, 210, 222, 211, -1, 206, 222, 208, -1, 208, 222, 210, -1, 214, 224, 215, -1, 215, 224, 220, -1, 220, 224, 221, -1, 223, 225, 226, -1, 222, 225, 223, -1, 227, 228, 229, -1, 221, 225, 206, -1, 206, 225, 222, -1, 226, 230, 231, -1, 232, 230, 214, -1, 214, 230, 224, -1, 231, 230, 232, -1, 225, 230, 226, -1, 224, 230, 221, -1, 221, 230, 225, -1, 233, 217, 218, -1, 232, 234, 231, -1, 235, 236, 237, -1, 237, 236, 238, -1, 239, 240, 235, -1, 235, 240, 236, -1, 238, 241, 242, -1, 236, 241, 238, -1, 243, 207, 239, -1, 239, 207, 240, -1, 236, 212, 241, -1, 240, 212, 236, -1, 242, 244, 227, -1, 241, 244, 242, -1, 227, 244, 228, -1, 245, 205, 243, -1, 243, 205, 207, -1, 207, 208, 240, -1, 240, 208, 212, -1, 228, 213, 209, -1, 241, 213, 244, -1, 244, 213, 228, -1, 212, 213, 241, -1, 219, 220, 245, -1, 245, 220, 205, -1, 246, 247, 248, -1, 248, 247, 249, -1, 249, 250, 251, -1, 247, 250, 249, -1, 251, 252, 253, -1, 250, 252, 251, -1, 253, 254, 255, -1, 252, 254, 253, -1, 255, 256, 257, -1, 254, 256, 255, -1, 258, 259, 260, -1, 260, 259, 261, -1, 262, 263, 264, -1, 265, 263, 266, -1, 261, 263, 265, -1, 266, 263, 262, -1, 267, 268, 269, -1, 269, 268, 270, -1, 271, 268, 272, -1, 272, 268, 273, -1, 270, 268, 271, -1, 258, 274, 259, -1, 273, 274, 258, -1, 264, 275, 276, -1, 263, 275, 264, -1, 259, 275, 261, -1, 261, 275, 263, -1, 267, 277, 268, -1, 268, 277, 273, -1, 273, 277, 274, -1, 276, 278, 279, -1, 275, 278, 276, -1, 280, 281, 282, -1, 274, 278, 259, -1, 259, 278, 275, -1, 279, 283, 284, -1, 285, 283, 267, -1, 267, 283, 277, -1, 284, 283, 285, -1, 278, 283, 279, -1, 277, 283, 274, -1, 274, 283, 278, -1, 286, 270, 271, -1, 285, 287, 284, -1, 288, 289, 290, -1, 290, 289, 291, -1, 292, 293, 288, -1, 288, 293, 289, -1, 291, 294, 295, -1, 289, 294, 291, -1, 296, 260, 292, -1, 292, 260, 293, -1, 289, 265, 294, -1, 293, 265, 289, -1, 295, 297, 280, -1, 294, 297, 295, -1, 280, 297, 281, -1, 298, 258, 296, -1, 296, 258, 260, -1, 260, 261, 293, -1, 293, 261, 265, -1, 281, 266, 262, -1, 294, 266, 297, -1, 297, 266, 281, -1, 265, 266, 294, -1, 272, 273, 298, -1, 298, 273, 258, -1, 299, 300, 301, -1, 301, 300, 302, -1, 302, 303, 304, -1, 300, 303, 302, -1, 304, 305, 306, -1, 303, 305, 304, -1, 306, 307, 308, -1, 305, 307, 306, -1, 308, 309, 310, -1, 307, 309, 308, -1, 311, 312, 313, -1, 313, 312, 314, -1, 315, 316, 317, -1, 318, 316, 319, -1, 314, 316, 318, -1, 319, 316, 315, -1, 320, 321, 322, -1, 322, 321, 323, -1, 324, 321, 325, -1, 325, 321, 326, -1, 323, 321, 324, -1, 311, 327, 312, -1, 326, 327, 311, -1, 317, 328, 329, -1, 316, 328, 317, -1, 312, 328, 314, -1, 314, 328, 316, -1, 320, 330, 321, -1, 321, 330, 326, -1, 326, 330, 327, -1, 329, 331, 332, -1, 328, 331, 329, -1, 333, 334, 335, -1, 327, 331, 312, -1, 312, 331, 328, -1, 332, 336, 337, -1, 338, 336, 320, -1, 320, 336, 330, -1, 337, 336, 338, -1, 331, 336, 332, -1, 330, 336, 327, -1, 327, 336, 331, -1, 339, 323, 324, -1, 338, 340, 337, -1, 341, 342, 343, -1, 343, 342, 344, -1, 345, 346, 341, -1, 341, 346, 342, -1, 344, 347, 348, -1, 342, 347, 344, -1, 349, 313, 345, -1, 345, 313, 346, -1, 342, 318, 347, -1, 346, 318, 342, -1, 348, 350, 333, -1, 347, 350, 348, -1, 333, 350, 334, -1, 351, 311, 349, -1, 349, 311, 313, -1, 313, 314, 346, -1, 346, 314, 318, -1, 334, 319, 315, -1, 347, 319, 350, -1, 350, 319, 334, -1, 318, 319, 347, -1, 325, 326, 351, -1, 351, 326, 311, -1, 352, 353, 354, -1, 354, 353, 355, -1, 355, 356, 357, -1, 353, 356, 355, -1, 357, 358, 359, -1, 356, 358, 357, -1, 359, 360, 361, -1, 358, 360, 359, -1, 361, 362, 363, -1, 360, 362, 361, -1, 364, 365, 366, -1, 366, 365, 367, -1, 368, 369, 370, -1, 371, 369, 372, -1, 367, 369, 371, -1, 372, 369, 368, -1, 373, 374, 375, -1, 375, 374, 376, -1, 377, 374, 378, -1, 378, 374, 379, -1, 376, 374, 377, -1, 364, 380, 365, -1, 379, 380, 364, -1, 370, 381, 382, -1, 369, 381, 370, -1, 365, 381, 367, -1, 367, 381, 369, -1, 373, 383, 374, -1, 374, 383, 379, -1, 379, 383, 380, -1, 382, 384, 385, -1, 381, 384, 382, -1, 380, 384, 365, -1, 386, 387, 388, -1, 365, 384, 381, -1, 385, 389, 390, -1, 391, 389, 373, -1, 373, 389, 383, -1, 390, 389, 391, -1, 384, 389, 385, -1, 383, 389, 380, -1, 380, 389, 384, -1, 392, 376, 377, -1, 391, 393, 390, -1, 394, 395, 396, -1, 396, 395, 397, -1, 398, 399, 394, -1, 394, 399, 395, -1, 397, 400, 401, -1, 395, 400, 397, -1, 402, 366, 398, -1, 398, 366, 399, -1, 395, 371, 400, -1, 399, 371, 395, -1, 401, 403, 386, -1, 400, 403, 401, -1, 386, 403, 387, -1, 404, 364, 402, -1, 402, 364, 366, -1, 366, 367, 399, -1, 399, 367, 371, -1, 387, 372, 368, -1, 400, 372, 403, -1, 371, 372, 400, -1, 403, 372, 387, -1, 378, 379, 404, -1, 404, 379, 364, -1, 405, 406, 407, -1, 407, 406, 408, -1, 408, 409, 410, -1, 406, 409, 408, -1, 410, 411, 412, -1, 409, 411, 410, -1, 412, 413, 414, -1, 411, 413, 412, -1, 414, 415, 416, -1, 413, 415, 414, -1, 417, 418, 419, -1, 418, 420, 419, -1, 419, 421, 422, -1, 420, 421, 419, -1, 422, 423, 424, -1, 421, 423, 422, -1, 425, 426, 427, -1, 428, 429, 425, -1, 425, 429, 426, -1, 430, 431, 428, -1, 428, 431, 429, -1, 430, 432, 431, -1, 433, 434, 430, -1, 430, 434, 432, -1, 435, 436, 433, -1, 433, 436, 434, -1, 436, 437, 434, -1, 438, 439, 440, -1, 441, 442, 438, -1, 438, 442, 439, -1, 441, 443, 442, -1, 444, 445, 441, -1, 441, 445, 443, -1, 446, 447, 444, -1, 444, 447, 445, -1, 448, 449, 446, -1, 446, 449, 447, -1, 449, 450, 447, -1, 451, 452, 453, -1, 454, 455, 451, -1, 451, 455, 452, -1, 454, 456, 455, -1, 457, 458, 454, -1, 454, 458, 456, -1, 459, 460, 457, -1, 457, 460, 458, -1, 461, 462, 459, -1, 459, 462, 460, -1, 462, 463, 460, -1, 464, 465, 466, -1, 467, 468, 464, -1, 464, 468, 465, -1, 467, 469, 468, -1, 470, 471, 467, -1, 467, 471, 469, -1, 472, 473, 470, -1, 470, 473, 471, -1, 474, 475, 472, -1, 472, 475, 473, -1, 475, 476, 473, -1, 477, 478, 479, -1, 480, 481, 477, -1, 477, 481, 478, -1, 480, 482, 481, -1, 483, 484, 480, -1, 480, 484, 482, -1, 485, 486, 483, -1, 483, 486, 484, -1, 487, 488, 485, -1, 485, 488, 486, -1, 488, 489, 486, -1, 490, 491, 492, -1, 493, 494, 490, -1, 490, 494, 491, -1, 495, 496, 493, -1, 493, 496, 494, -1, 495, 497, 496, -1, 498, 499, 495, -1, 495, 499, 497, -1, 500, 501, 498, -1, 498, 501, 499, -1, 501, 502, 499, -1, 503, 504, 505, -1, 506, 507, 503, -1, 503, 507, 504, -1, 508, 509, 506, -1, 506, 509, 507, -1, 508, 510, 509, -1, 511, 512, 508, -1, 508, 512, 510, -1, 513, 514, 511, -1, 511, 514, 512, -1, 514, 515, 512, -1, 516, 517, 518, -1, 519, 520, 516, -1, 516, 520, 517, -1, 519, 521, 520, -1, 522, 523, 519, -1, 519, 523, 521, -1, 524, 525, 522, -1, 522, 525, 523, -1, 526, 527, 524, -1, 524, 527, 525, -1, 527, 528, 525, -1, 529, 530, 531, -1, 531, 530, 532, -1, 533, 534, 535, -1, 536, 534, 537, -1, 532, 534, 536, -1, 537, 534, 533, -1, 538, 539, 540, -1, 540, 539, 541, -1, 542, 539, 543, -1, 543, 539, 544, -1, 541, 539, 542, -1, 529, 545, 530, -1, 544, 545, 529, -1, 535, 546, 547, -1, 534, 546, 535, -1, 530, 546, 532, -1, 532, 546, 534, -1, 538, 548, 539, -1, 539, 548, 544, -1, 544, 548, 545, -1, 547, 549, 550, -1, 546, 549, 547, -1, 551, 552, 553, -1, 545, 549, 530, -1, 530, 549, 546, -1, 550, 554, 555, -1, 556, 554, 538, -1, 538, 554, 548, -1, 555, 554, 556, -1, 549, 554, 550, -1, 548, 554, 545, -1, 545, 554, 549, -1, 557, 541, 542, -1, 556, 558, 555, -1, 559, 560, 561, -1, 561, 560, 562, -1, 563, 564, 559, -1, 559, 564, 560, -1, 562, 565, 566, -1, 560, 565, 562, -1, 567, 531, 563, -1, 563, 531, 564, -1, 560, 536, 565, -1, 564, 536, 560, -1, 566, 568, 551, -1, 565, 568, 566, -1, 551, 568, 552, -1, 569, 529, 567, -1, 567, 529, 531, -1, 531, 532, 564, -1, 564, 532, 536, -1, 552, 537, 533, -1, 565, 537, 568, -1, 568, 537, 552, -1, 536, 537, 565, -1, 543, 544, 569, -1, 569, 544, 529, -1, 570, 571, 572, -1, 572, 573, 574, -1, 571, 573, 572, -1, 574, 575, 576, -1, 573, 575, 574, -1, 576, 577, 578, -1, 575, 577, 576, -1, 578, 579, 580, -1, 577, 579, 578, -1, 579, 581, 580, -1, 582, 583, 584, -1, 585, 586, 582, -1, 582, 586, 583, -1, 585, 587, 586, -1, 588, 589, 585, -1, 585, 589, 587, -1, 590, 591, 588, -1, 588, 591, 589, -1, 592, 593, 590, -1, 590, 593, 591, -1, 593, 594, 591, -1, 595, 596, 597, -1, 597, 596, 598, -1, 598, 599, 600, -1, 596, 599, 598, -1, 601, 602, 603, -1, 600, 602, 601, -1, 599, 602, 600, -1, 604, 605, 606, -1, 607, 604, 606, -1, 608, 607, 606, -1, 609, 610, 611, -1, 612, 610, 609, -1, 611, 610, 613, -1, 614, 615, 616, -1, 617, 615, 612, -1, 613, 615, 614, -1, 612, 615, 610, -1, 610, 615, 613, -1, 616, 618, 619, -1, 619, 618, 620, -1, 620, 618, 617, -1, 615, 618, 616, -1, 617, 618, 615, -1, 621, 622, 623, -1, 624, 622, 621, -1, 625, 622, 624, -1, 623, 622, 626, -1, 613, 627, 628, -1, 613, 629, 627, -1, 613, 614, 629, -1, 626, 630, 631, -1, 632, 633, 634, -1, 631, 633, 632, -1, 635, 636, 637, -1, 637, 636, 622, -1, 622, 636, 626, -1, 626, 636, 630, -1, 631, 638, 633, -1, 631, 639, 638, -1, 630, 639, 631, -1, 634, 640, 641, -1, 633, 640, 634, -1, 642, 643, 635, -1, 636, 643, 630, -1, 639, 643, 642, -1, 635, 643, 636, -1, 630, 643, 639, -1, 638, 644, 633, -1, 633, 644, 640, -1, 642, 645, 639, -1, 638, 645, 644, -1, 639, 645, 638, -1, 640, 609, 641, -1, 646, 647, 642, -1, 642, 647, 645, -1, 644, 612, 640, -1, 640, 612, 609, -1, 620, 617, 646, -1, 645, 617, 644, -1, 644, 617, 612, -1, 646, 617, 647, -1, 647, 617, 645, -1, 641, 611, 648, -1, 648, 611, 613, -1, 609, 611, 641, -1, 649, 650, 651, -1, 652, 653, 654, -1, 655, 649, 656, -1, 655, 656, 657, -1, 655, 650, 649, -1, 658, 657, 659, -1, 658, 660, 650, -1, 658, 650, 655, -1, 658, 655, 657, -1, 661, 659, 662, -1, 661, 663, 660, -1, 661, 660, 658, -1, 661, 658, 659, -1, 664, 662, 665, -1, 664, 665, 666, -1, 664, 667, 663, -1, 664, 661, 662, -1, 664, 663, 661, -1, 668, 666, 669, -1, 668, 670, 667, -1, 668, 671, 670, -1, 668, 664, 666, -1, 668, 667, 664, -1, 672, 669, 673, -1, 672, 668, 669, -1, 672, 671, 668, -1, 674, 673, 675, -1, 674, 675, 652, -1, 674, 654, 671, -1, 674, 672, 673, -1, 674, 652, 654, -1, 674, 671, 672, -1, 676, 677, 678, -1, 679, 676, 678, -1, 680, 681, 676, -1, 680, 676, 679, -1, 682, 683, 681, -1, 682, 681, 680, -1, 684, 685, 683, -1, 684, 683, 682, -1, 686, 687, 685, -1, 686, 685, 684, -1, 688, 689, 687, -1, 688, 687, 686, -1, 690, 691, 692, -1, 693, 692, 694, -1, 693, 690, 692, -1, 695, 694, 696, -1, 695, 693, 694, -1, 697, 696, 698, -1, 697, 695, 696, -1, 699, 698, 700, -1, 699, 697, 698, -1, 701, 699, 700, -1, 702, 703, 704, -1, 704, 703, 705, -1, 706, 707, 708, -1, 709, 707, 710, -1, 705, 707, 709, -1, 710, 707, 706, -1, 711, 712, 713, -1, 713, 712, 714, -1, 715, 712, 716, -1, 716, 712, 717, -1, 714, 712, 715, -1, 702, 718, 703, -1, 717, 718, 702, -1, 708, 719, 720, -1, 707, 719, 708, -1, 703, 719, 705, -1, 705, 719, 707, -1, 711, 721, 712, -1, 712, 721, 717, -1, 717, 721, 718, -1, 720, 722, 723, -1, 719, 722, 720, -1, 718, 722, 703, -1, 724, 725, 726, -1, 703, 722, 719, -1, 723, 727, 728, -1, 729, 727, 711, -1, 711, 727, 721, -1, 728, 727, 729, -1, 722, 727, 723, -1, 721, 727, 718, -1, 718, 727, 722, -1, 730, 714, 715, -1, 729, 731, 728, -1, 732, 733, 734, -1, 734, 733, 735, -1, 736, 737, 732, -1, 732, 737, 733, -1, 735, 738, 739, -1, 733, 738, 735, -1, 740, 704, 736, -1, 736, 704, 737, -1, 733, 709, 738, -1, 737, 709, 733, -1, 739, 741, 724, -1, 738, 741, 739, -1, 724, 741, 725, -1, 742, 702, 740, -1, 740, 702, 704, -1, 704, 705, 737, -1, 737, 705, 709, -1, 725, 710, 706, -1, 738, 710, 741, -1, 709, 710, 738, -1, 741, 710, 725, -1, 716, 717, 742, -1, 742, 717, 702, -1, 743, 744, 745, -1, 745, 744, 746, -1, 746, 747, 748, -1, 744, 747, 746, -1, 748, 749, 750, -1, 747, 749, 748, -1, 750, 751, 752, -1, 749, 751, 750, -1, 752, 753, 754, -1, 751, 753, 752, -1, 755, 756, 757, -1, 757, 756, 758, -1, 758, 759, 760, -1, 756, 759, 758, -1, 760, 761, 762, -1, 759, 761, 760, -1, 762, 763, 764, -1, 761, 763, 762, -1, 764, 765, 766, -1, 763, 765, 764, -1, 765, 767, 766, -1, 768, 769, 770, -1, 770, 769, 771, -1, 771, 772, 773, -1, 769, 772, 771, -1, 773, 774, 775, -1, 772, 774, 773, -1, 775, 776, 777, -1, 774, 776, 775, -1, 777, 778, 779, -1, 776, 778, 777, -1, 780, 781, 782, -1, 782, 781, 783, -1, 783, 784, 785, -1, 781, 784, 783, -1, 785, 786, 787, -1, 784, 786, 785, -1, 787, 788, 789, -1, 786, 788, 787, -1, 789, 790, 791, -1, 788, 790, 789, -1, 791, 792, 793, -1, 790, 792, 791, -1, 793, 794, 795, -1, 792, 794, 793, -1, 795, 796, 797, -1, 794, 796, 795, -1, 798, 799, 800, -1, 800, 799, 801, -1, 801, 802, 803, -1, 799, 802, 801, -1, 803, 804, 805, -1, 805, 804, 806, -1, 802, 804, 803, -1, 806, 807, 808, -1, 804, 807, 806, -1, 808, 809, 810, -1, 807, 809, 808, -1, 811, 812, 813, -1, 814, 815, 816, -1, 813, 815, 814, -1, 812, 815, 813, -1, 817, 818, 819, -1, 816, 818, 817, -1, 815, 818, 816, -1, 819, 820, 821, -1, 818, 820, 819, -1, 822, 823, 824, -1, 821, 823, 822, -1, 820, 823, 821, -1, 824, 825, 826, -1, 823, 825, 824, -1, 827, 828, 829, -1, 830, 827, 829, -1, 830, 829, 831, -1, 832, 833, 834, -1, 832, 835, 833, -1, 836, 837, 838, -1, 839, 832, 834, -1, 689, 834, 837, -1, 689, 837, 836, -1, 689, 839, 834, -1, 840, 838, 841, -1, 840, 836, 838, -1, 842, 840, 841, -1, 843, 689, 688, -1, 843, 839, 689, -1, 844, 840, 842, -1, 845, 688, 846, -1, 845, 843, 688, -1, 847, 844, 842, -1, 848, 844, 847, -1, 849, 848, 847, -1, 850, 846, 851, -1, 850, 845, 846, -1, 852, 851, 853, -1, 852, 850, 851, -1, 854, 849, 855, -1, 854, 848, 849, -1, 856, 853, 857, -1, 856, 852, 853, -1, 858, 855, 859, -1, 858, 859, 860, -1, 858, 854, 855, -1, 861, 857, 828, -1, 861, 856, 857, -1, 862, 860, 863, -1, 862, 858, 860, -1, 827, 861, 828, -1, 864, 862, 863, -1, 864, 863, 865, -1, 866, 867, 868, -1, 868, 867, 869, -1, 867, 870, 869, -1, 867, 871, 870, -1, 871, 872, 870, -1, 871, 873, 872, -1, 873, 874, 872, -1, 873, 875, 874, -1, 875, 876, 874, -1, 875, 877, 876, -1, 877, 878, 876, -1, 877, 879, 878, -1, 878, 880, 881, -1, 879, 880, 878, -1, 880, 882, 881, -1, 880, 883, 882, -1, 884, 885, 886, -1, 884, 887, 885, -1, 887, 888, 885, -1, 887, 889, 888, -1, 889, 890, 888, -1, 889, 891, 890, -1, 891, 892, 890, -1, 891, 893, 892, -1, 893, 894, 892, -1, 893, 895, 894, -1, 895, 896, 894, -1, 895, 897, 896, -1, 898, 899, 900, -1, 900, 901, 902, -1, 899, 901, 900, -1, 902, 903, 904, -1, 901, 903, 902, -1, 904, 905, 906, -1, 903, 905, 904, -1, 906, 907, 908, -1, 905, 907, 906, -1, 908, 909, 910, -1, 907, 909, 908, -1, 910, 911, 912, -1, 909, 911, 910, -1, 912, 913, 914, -1, 911, 913, 912, -1, 914, 915, 916, -1, 913, 915, 914, -1, 916, 917, 918, -1, 915, 917, 916, -1, 918, 919, 920, -1, 917, 919, 918, -1, 920, 921, 922, -1, 919, 921, 920, -1, 921, 923, 922, -1, 922, 924, 925, -1, 923, 924, 922, -1, 926, 927, 928, -1, 928, 929, 930, -1, 927, 929, 928, -1, 930, 931, 932, -1, 929, 931, 930, -1, 932, 933, 934, -1, 931, 933, 932, -1, 934, 935, 936, -1, 933, 935, 934, -1, 936, 937, 938, -1, 935, 937, 936, -1, 938, 939, 940, -1, 937, 939, 938, -1, 940, 941, 942, -1, 939, 941, 940, -1, 942, 943, 944, -1, 941, 943, 942, -1, 944, 945, 946, -1, 943, 945, 944, -1, 946, 947, 948, -1, 945, 947, 946, -1, 948, 949, 950, -1, 947, 949, 948, -1, 950, 951, 952, -1, 949, 951, 950, -1, 951, 953, 952, -1, 954, 955, 956, -1, 957, 958, 959, -1, 960, 958, 957, -1, 961, 962, 963, -1, 959, 958, 964, -1, 965, 962, 966, -1, 967, 968, 969, -1, 966, 962, 961, -1, 956, 962, 965, -1, 964, 968, 967, -1, 970, 971, 972, -1, 973, 974, 975, -1, 976, 977, 978, -1, 975, 974, 979, -1, 980, 974, 955, -1, 969, 977, 976, -1, 979, 974, 980, -1, 963, 981, 982, -1, 983, 984, 985, -1, 964, 984, 968, -1, 962, 981, 963, -1, 985, 984, 958, -1, 955, 981, 956, -1, 956, 981, 962, -1, 958, 984, 964, -1, 982, 986, 987, -1, 969, 988, 977, -1, 987, 986, 989, -1, 989, 986, 990, -1, 990, 986, 973, -1, 981, 986, 982, -1, 968, 988, 969, -1, 974, 986, 955, -1, 955, 986, 981, -1, 973, 986, 974, -1, 978, 991, 992, -1, 977, 991, 978, -1, 993, 994, 983, -1, 983, 994, 984, -1, 968, 994, 988, -1, 984, 994, 968, -1, 977, 995, 991, -1, 988, 995, 977, -1, 992, 996, 997, -1, 991, 996, 992, -1, 998, 999, 993, -1, 993, 999, 994, -1, 994, 999, 988, -1, 988, 999, 995, -1, 995, 1000, 991, -1, 991, 1000, 996, -1, 997, 1001, 1002, -1, 996, 1001, 997, -1, 998, 1003, 999, -1, 1004, 1003, 998, -1, 999, 1003, 995, -1, 995, 1003, 1000, -1, 1000, 1005, 996, -1, 996, 1005, 1001, -1, 1001, 1006, 1002, -1, 1002, 1006, 1007, -1, 1004, 1008, 1003, -1, 1009, 1008, 1004, -1, 1000, 1008, 1005, -1, 1003, 1008, 1000, -1, 1001, 1010, 1006, -1, 1005, 1010, 1001, -1, 1006, 1011, 1007, -1, 1007, 1011, 1012, -1, 1009, 1013, 1008, -1, 1014, 1013, 1009, -1, 1008, 1013, 1005, -1, 1005, 1013, 1010, -1, 1010, 1015, 1006, -1, 1006, 1015, 1011, -1, 1011, 1016, 1012, -1, 1012, 1016, 1017, -1, 1018, 1019, 1014, -1, 1014, 1019, 1013, -1, 1010, 1019, 1015, -1, 1013, 1019, 1010, -1, 1015, 1020, 1011, -1, 1011, 1020, 1016, -1, 1017, 954, 1021, -1, 1016, 954, 1017, -1, 1022, 1023, 1018, -1, 1015, 1023, 1020, -1, 1019, 1023, 1015, -1, 1018, 1023, 1019, -1, 1020, 980, 1016, -1, 1016, 980, 954, -1, 970, 967, 971, -1, 1021, 956, 965, -1, 970, 964, 967, -1, 954, 956, 1021, -1, 959, 964, 970, -1, 975, 979, 1022, -1, 1022, 979, 1023, -1, 1020, 979, 980, -1, 1023, 979, 1020, -1, 971, 969, 976, -1, 967, 969, 971, -1, 980, 955, 954, -1, 985, 958, 960, -1, 1024, 1025, 1026, -1, 1027, 1028, 1029, -1, 1030, 1031, 1032, -1, 1030, 1033, 1034, -1, 1027, 1035, 1028, -1, 1030, 1032, 1036, -1, 1030, 1036, 1033, -1, 1037, 1038, 1039, -1, 1037, 1039, 1040, -1, 1041, 1042, 1043, -1, 1037, 1044, 1038, -1, 1045, 1046, 1035, -1, 1045, 1047, 1046, -1, 1048, 1049, 1050, -1, 1051, 1026, 1044, -1, 1051, 1024, 1026, -1, 1048, 1052, 1053, -1, 1048, 1050, 1052, -1, 1048, 1053, 1047, -1, 1054, 1055, 1031, -1, 1056, 1029, 1057, -1, 1054, 1030, 1034, -1, 1054, 1031, 1030, -1, 1054, 1034, 1024, -1, 1056, 1027, 1029, -1, 1058, 1040, 1059, -1, 1058, 1037, 1040, -1, 1058, 1044, 1037, -1, 1060, 1045, 1035, -1, 1058, 1051, 1044, -1, 1060, 1035, 1027, -1, 1061, 1062, 1055, -1, 1063, 1064, 1049, -1, 1061, 1055, 1054, -1, 1061, 1024, 1051, -1, 1063, 1049, 1048, -1, 1061, 1054, 1024, -1, 1063, 1047, 1045, -1, 1065, 1062, 1061, -1, 1063, 1048, 1047, -1, 1065, 1066, 1067, -1, 1065, 1059, 1066, -1, 1068, 1057, 1069, -1, 1065, 1067, 1062, -1, 1065, 1051, 1058, -1, 1065, 1058, 1059, -1, 1065, 1061, 1051, -1, 1068, 1056, 1057, -1, 1070, 1060, 1027, -1, 1070, 1027, 1056, -1, 1071, 1072, 1064, -1, 1071, 1045, 1060, -1, 1071, 1063, 1045, -1, 1071, 1064, 1063, -1, 1073, 1069, 1074, -1, 1073, 1068, 1069, -1, 1075, 1056, 1068, -1, 1075, 1070, 1056, -1, 1076, 1077, 1072, -1, 1076, 1071, 1060, -1, 1076, 1072, 1071, -1, 1076, 1060, 1070, -1, 1078, 1074, 1079, -1, 1078, 1073, 1074, -1, 1080, 1075, 1068, -1, 1080, 1068, 1073, -1, 1081, 1070, 1075, -1, 1081, 1082, 1077, -1, 1081, 1077, 1076, -1, 1081, 1076, 1070, -1, 1083, 1079, 1084, -1, 1083, 1078, 1079, -1, 1085, 1073, 1078, -1, 1085, 1080, 1073, -1, 1086, 1075, 1080, -1, 1086, 1087, 1082, -1, 1086, 1082, 1081, -1, 1086, 1081, 1075, -1, 1025, 1084, 1088, -1, 1025, 1083, 1084, -1, 1033, 1078, 1083, -1, 1033, 1085, 1078, -1, 1089, 1087, 1086, -1, 1089, 1090, 1087, -1, 1089, 1080, 1085, -1, 1089, 1086, 1080, -1, 1026, 1088, 1091, -1, 1026, 1025, 1088, -1, 1092, 1067, 1066, -1, 1034, 1083, 1025, -1, 1034, 1033, 1083, -1, 1046, 1043, 1093, -1, 1036, 1032, 1090, -1, 1046, 1041, 1043, -1, 1036, 1085, 1033, -1, 1036, 1090, 1089, -1, 1036, 1089, 1085, -1, 1035, 1093, 1028, -1, 1044, 1091, 1038, -1, 1044, 1026, 1091, -1, 1035, 1046, 1093, -1, 1047, 1053, 1041, -1, 1024, 1034, 1025, -1, 1047, 1041, 1046, -1, 1094, 1095, 1096, -1, 1097, 1098, 1099, -1, 1100, 1095, 1101, -1, 1102, 1103, 1104, -1, 1105, 1098, 1097, -1, 1104, 1103, 1106, -1, 1099, 1098, 1107, -1, 1108, 1103, 1109, -1, 1106, 1103, 1108, -1, 1110, 1111, 1112, -1, 1101, 1113, 1114, -1, 1109, 1113, 1094, -1, 1107, 1111, 1110, -1, 1095, 1113, 1101, -1, 1094, 1113, 1095, -1, 1115, 1116, 1117, -1, 1112, 1116, 1115, -1, 1114, 1118, 1119, -1, 1119, 1118, 1120, -1, 1120, 1118, 1102, -1, 1109, 1118, 1113, -1, 1121, 1122, 1123, -1, 1113, 1118, 1114, -1, 1107, 1122, 1111, -1, 1103, 1118, 1109, -1, 1102, 1118, 1103, -1, 1123, 1122, 1098, -1, 1098, 1122, 1107, -1, 1112, 1124, 1116, -1, 1111, 1124, 1112, -1, 1117, 1125, 1126, -1, 1116, 1125, 1117, -1, 1127, 1128, 1121, -1, 1129, 1105, 1097, -1, 1121, 1128, 1122, -1, 1111, 1128, 1124, -1, 1122, 1128, 1111, -1, 1116, 1130, 1125, -1, 1124, 1130, 1116, -1, 1126, 1131, 1132, -1, 1125, 1131, 1126, -1, 1133, 1134, 1127, -1, 1128, 1134, 1124, -1, 1127, 1134, 1128, -1, 1124, 1134, 1130, -1, 1130, 1135, 1125, -1, 1125, 1135, 1131, -1, 1132, 1136, 1137, -1, 1131, 1136, 1132, -1, 1138, 1139, 1133, -1, 1134, 1139, 1130, -1, 1130, 1139, 1135, -1, 1133, 1139, 1134, -1, 1131, 1140, 1136, -1, 1135, 1140, 1131, -1, 1137, 1141, 1142, -1, 1136, 1141, 1137, -1, 1139, 1143, 1135, -1, 1135, 1143, 1140, -1, 1144, 1143, 1138, -1, 1138, 1143, 1139, -1, 1136, 1145, 1141, -1, 1140, 1145, 1136, -1, 1141, 1146, 1142, -1, 1142, 1146, 1147, -1, 1148, 1149, 1144, -1, 1144, 1149, 1143, -1, 1143, 1149, 1140, -1, 1140, 1149, 1145, -1, 1145, 1150, 1141, -1, 1141, 1150, 1146, -1, 1146, 1151, 1147, -1, 1147, 1151, 1152, -1, 1153, 1154, 1148, -1, 1148, 1154, 1149, -1, 1149, 1154, 1145, -1, 1145, 1154, 1150, -1, 1150, 1155, 1146, -1, 1100, 1101, 1156, -1, 1146, 1155, 1151, -1, 1152, 1157, 1158, -1, 1151, 1157, 1152, -1, 1159, 1160, 1153, -1, 1150, 1160, 1155, -1, 1153, 1160, 1154, -1, 1154, 1160, 1150, -1, 1155, 1108, 1151, -1, 1151, 1108, 1157, -1, 1158, 1094, 1096, -1, 1157, 1094, 1158, -1, 1161, 1110, 1162, -1, 1104, 1106, 1159, -1, 1159, 1106, 1160, -1, 1162, 1110, 1163, -1, 1155, 1106, 1108, -1, 1160, 1106, 1155, -1, 1161, 1107, 1110, -1, 1099, 1107, 1161, -1, 1108, 1109, 1157, -1, 1157, 1109, 1094, -1, 1163, 1112, 1115, -1, 1096, 1095, 1100, -1, 1110, 1112, 1163, -1, 1123, 1098, 1105, -1, 1164, 1165, 1166, -1, 1167, 1168, 1169, -1, 1170, 1171, 1172, -1, 1173, 1174, 1165, -1, 1170, 1175, 1171, -1, 1173, 1176, 1174, -1, 1177, 1178, 1179, -1, 1177, 1179, 1180, -1, 1177, 1181, 1176, -1, 1182, 1169, 1175, -1, 1177, 1180, 1181, -1, 1182, 1167, 1169, -1, 1183, 1184, 1185, -1, 1186, 1187, 1188, -1, 1183, 1164, 1184, -1, 1186, 1189, 1187, -1, 1183, 1185, 1190, -1, 1186, 1188, 1167, -1, 1191, 1173, 1165, -1, 1192, 1172, 1193, -1, 1191, 1165, 1164, -1, 1192, 1170, 1172, -1, 1194, 1175, 1170, -1, 1195, 1196, 1178, -1, 1195, 1178, 1177, -1, 1194, 1182, 1175, -1, 1195, 1176, 1173, -1, 1195, 1177, 1176, -1, 1197, 1198, 1189, -1, 1199, 1190, 1200, -1, 1197, 1189, 1186, -1, 1199, 1164, 1183, -1, 1199, 1191, 1164, -1, 1197, 1167, 1182, -1, 1199, 1183, 1190, -1, 1197, 1186, 1167, -1, 1189, 1201, 1187, -1, 1202, 1203, 1196, -1, 1204, 1193, 1205, -1, 1202, 1173, 1191, -1, 1202, 1196, 1195, -1, 1204, 1192, 1193, -1, 1202, 1195, 1173, -1, 1206, 1202, 1191, -1, 1206, 1200, 1207, -1, 1206, 1207, 1208, -1, 1206, 1191, 1199, -1, 1206, 1209, 1203, -1, 1206, 1208, 1209, -1, 1210, 1194, 1170, -1, 1206, 1203, 1202, -1, 1206, 1199, 1200, -1, 1210, 1170, 1192, -1, 1211, 1197, 1182, -1, 1211, 1212, 1198, -1, 1211, 1182, 1194, -1, 1211, 1198, 1197, -1, 1213, 1205, 1214, -1, 1213, 1204, 1205, -1, 1215, 1192, 1204, -1, 1215, 1210, 1192, -1, 1216, 1217, 1212, -1, 1216, 1211, 1194, -1, 1216, 1212, 1211, -1, 1216, 1194, 1210, -1, 1218, 1214, 1219, -1, 1218, 1213, 1214, -1, 1220, 1215, 1204, -1, 1220, 1204, 1213, -1, 1221, 1216, 1210, -1, 1221, 1210, 1215, -1, 1221, 1222, 1217, -1, 1221, 1217, 1216, -1, 1223, 1219, 1224, -1, 1223, 1218, 1219, -1, 1225, 1220, 1213, -1, 1225, 1213, 1218, -1, 1226, 1215, 1220, -1, 1226, 1221, 1215, -1, 1226, 1222, 1221, -1, 1226, 1227, 1222, -1, 1190, 1185, 1228, -1, 1174, 1224, 1229, -1, 1174, 1223, 1224, -1, 1181, 1225, 1218, -1, 1181, 1218, 1223, -1, 1230, 1226, 1220, -1, 1230, 1231, 1227, -1, 1230, 1227, 1226, -1, 1230, 1220, 1225, -1, 1165, 1229, 1166, -1, 1165, 1174, 1229, -1, 1169, 1232, 1233, -1, 1169, 1168, 1232, -1, 1176, 1223, 1174, -1, 1176, 1181, 1223, -1, 1180, 1231, 1230, -1, 1175, 1233, 1171, -1, 1180, 1179, 1231, -1, 1180, 1230, 1225, -1, 1180, 1225, 1181, -1, 1175, 1169, 1233, -1, 1164, 1166, 1184, -1, 1167, 1188, 1168, -1, 1234, 1235, 1236, -1, 1236, 1237, 1238, -1, 1235, 1237, 1236, -1, 1238, 1239, 1240, -1, 1237, 1239, 1238, -1, 1240, 1241, 1242, -1, 1239, 1241, 1240, -1, 1242, 1243, 1244, -1, 1241, 1243, 1242, -1, 1244, 1245, 1246, -1, 1243, 1245, 1244, -1, 1246, 1247, 1248, -1, 1245, 1247, 1246, -1, 1248, 1249, 1250, -1, 1247, 1249, 1248, -1, 1250, 1251, 1252, -1, 1249, 1251, 1250, -1, 1252, 1253, 1254, -1, 1251, 1253, 1252, -1, 1254, 1255, 1256, -1, 1253, 1255, 1254, -1, 1256, 1257, 1258, -1, 1255, 1257, 1256, -1, 1257, 1259, 1258, -1, 1258, 1260, 1261, -1, 1259, 1260, 1258, -1, 1262, 1263, 1264, -1, 1264, 1265, 1266, -1, 1263, 1265, 1264, -1, 1266, 1267, 1268, -1, 1265, 1267, 1266, -1, 1268, 1269, 1270, -1, 1267, 1269, 1268, -1, 1270, 1271, 1272, -1, 1269, 1271, 1270, -1, 1272, 1273, 1274, -1, 1271, 1273, 1272, -1, 1274, 1275, 1276, -1, 1273, 1275, 1274, -1, 1276, 1277, 1278, -1, 1275, 1277, 1276, -1, 1278, 1279, 1280, -1, 1277, 1279, 1278, -1, 1280, 1281, 1282, -1, 1279, 1281, 1280, -1, 1282, 1283, 1284, -1, 1281, 1283, 1282, -1, 1284, 1285, 1286, -1, 1283, 1285, 1284, -1, 1285, 1287, 1286, -1, 1286, 1288, 1289, -1, 1287, 1288, 1286, -1, 1290, 1291, 1292, -1, 1290, 1292, 989, -1, 1290, 1293, 1294, -1, 1290, 1294, 1291, -1, 1290, 989, 1293, -1, 1295, 1093, 1043, -1, 1295, 1043, 1042, -1, 1295, 1296, 1093, -1, 1297, 1042, 960, -1, 1297, 960, 1298, -1, 1297, 1298, 1299, -1, 1297, 1295, 1042, -1, 1297, 1299, 1296, -1, 1297, 1296, 1295, -1, 1294, 1091, 1088, -1, 1294, 1300, 1291, -1, 1301, 1088, 1084, -1, 1301, 1084, 1079, -1, 1301, 1302, 1303, -1, 1301, 1303, 1300, -1, 1301, 1294, 1088, -1, 1301, 1300, 1294, -1, 1304, 1079, 1074, -1, 1304, 1074, 1069, -1, 1304, 1305, 1302, -1, 1304, 1302, 1301, -1, 1304, 1301, 1079, -1, 1306, 1069, 1057, -1, 1306, 1307, 1308, -1, 1306, 1308, 1305, -1, 1306, 1305, 1304, -1, 1306, 1304, 1069, -1, 1309, 1057, 1029, -1, 1309, 1029, 1028, -1, 1309, 1310, 1311, -1, 1309, 1311, 1307, -1, 1309, 1306, 1057, -1, 1309, 1307, 1306, -1, 1296, 1028, 1093, -1, 1296, 1299, 1310, -1, 1296, 1309, 1028, -1, 1296, 1310, 1309, -1, 1293, 1039, 1038, -1, 1293, 1038, 1091, -1, 1293, 989, 1039, -1, 1293, 1091, 1294, -1, 1312, 1313, 1314, -1, 1312, 1315, 1172, -1, 1312, 1314, 1315, -1, 1316, 1228, 1185, -1, 1316, 1185, 1184, -1, 1316, 1184, 1317, -1, 1318, 1319, 1320, -1, 1318, 1320, 1120, -1, 1318, 1120, 1228, -1, 1318, 1316, 1317, -1, 1318, 1317, 1319, -1, 1318, 1228, 1316, -1, 1321, 1171, 1233, -1, 1321, 1233, 1232, -1, 1321, 1232, 1129, -1, 1321, 1312, 1171, -1, 1322, 1129, 1323, -1, 1322, 1323, 1313, -1, 1322, 1312, 1321, -1, 1322, 1313, 1312, -1, 1322, 1321, 1129, -1, 1317, 1184, 1166, -1, 1317, 1324, 1319, -1, 1325, 1166, 1229, -1, 1325, 1229, 1224, -1, 1325, 1326, 1327, -1, 1325, 1327, 1324, -1, 1325, 1317, 1166, -1, 1325, 1324, 1317, -1, 1328, 1224, 1219, -1, 1328, 1329, 1330, -1, 1328, 1330, 1326, -1, 1328, 1326, 1325, -1, 1328, 1325, 1224, -1, 1331, 1219, 1214, -1, 1331, 1214, 1205, -1, 1331, 1332, 1329, -1, 1331, 1329, 1328, -1, 1331, 1328, 1219, -1, 1315, 1205, 1193, -1, 1315, 1193, 1172, -1, 1315, 1314, 1333, -1, 1315, 1333, 1332, -1, 1315, 1331, 1205, -1, 1315, 1332, 1331, -1, 1312, 1172, 1171, -1, 1334, 1335, 1336, -1, 1337, 1338, 1339, -1, 1340, 1341, 1342, -1, 1343, 1344, 1338, -1, 1340, 1345, 1341, -1, 1343, 1346, 1344, -1, 1347, 1348, 1349, -1, 1347, 1349, 1350, -1, 1351, 1336, 1345, -1, 1347, 1352, 1346, -1, 1347, 1350, 1352, -1, 1351, 1334, 1336, -1, 1353, 1354, 1355, -1, 1356, 1357, 1358, -1, 1353, 1359, 1360, -1, 1353, 1355, 1359, -1, 1356, 1337, 1357, -1, 1356, 1358, 1361, -1, 1353, 1360, 1334, -1, 1362, 1343, 1338, -1, 1363, 1342, 1364, -1, 1362, 1338, 1337, -1, 1363, 1340, 1342, -1, 1365, 1345, 1340, -1, 1366, 1367, 1348, -1, 1366, 1348, 1347, -1, 1365, 1351, 1345, -1, 1366, 1346, 1343, -1, 1366, 1347, 1346, -1, 1368, 1369, 1354, -1, 1370, 1361, 1371, -1, 1368, 1334, 1351, -1, 1368, 1354, 1353, -1, 1370, 1337, 1356, -1, 1370, 1362, 1337, -1, 1368, 1353, 1334, -1, 1370, 1356, 1361, -1, 1372, 1373, 1367, -1, 1374, 1364, 1375, -1, 1372, 1343, 1362, -1, 1372, 1367, 1366, -1, 1374, 1363, 1364, -1, 1372, 1366, 1343, -1, 1376, 1372, 1362, -1, 1376, 1371, 1377, -1, 1376, 1377, 1378, -1, 1376, 1362, 1370, -1, 1376, 1379, 1373, -1, 1376, 1378, 1379, -1, 1380, 1365, 1340, -1, 1376, 1373, 1372, -1, 1376, 1370, 1371, -1, 1380, 1340, 1363, -1, 1381, 1382, 1369, -1, 1381, 1368, 1351, -1, 1381, 1369, 1368, -1, 1381, 1351, 1365, -1, 1383, 1375, 1384, -1, 1383, 1374, 1375, -1, 1385, 1363, 1374, -1, 1385, 1380, 1363, -1, 1386, 1387, 1382, -1, 1386, 1381, 1365, -1, 1386, 1365, 1380, -1, 1386, 1382, 1381, -1, 1388, 1384, 1389, -1, 1388, 1383, 1384, -1, 1390, 1385, 1374, -1, 1390, 1374, 1383, -1, 1391, 1386, 1380, -1, 1391, 1380, 1385, -1, 1391, 1392, 1387, -1, 1391, 1387, 1386, -1, 1393, 1389, 1394, -1, 1393, 1388, 1389, -1, 1395, 1390, 1383, -1, 1395, 1383, 1388, -1, 1396, 1391, 1385, -1, 1396, 1385, 1390, -1, 1396, 1392, 1391, -1, 1396, 1397, 1392, -1, 1361, 1358, 1398, -1, 1344, 1394, 1399, -1, 1344, 1393, 1394, -1, 1352, 1395, 1388, -1, 1352, 1388, 1393, -1, 1400, 1396, 1390, -1, 1400, 1401, 1397, -1, 1400, 1397, 1396, -1, 1400, 1390, 1395, -1, 1338, 1399, 1339, -1, 1338, 1344, 1399, -1, 1336, 1402, 1403, -1, 1336, 1335, 1402, -1, 1346, 1393, 1344, -1, 1346, 1352, 1393, -1, 1345, 1403, 1341, -1, 1350, 1401, 1400, -1, 1350, 1349, 1401, -1, 1350, 1400, 1395, -1, 1345, 1336, 1403, -1, 1350, 1395, 1352, -1, 1334, 1360, 1335, -1, 1337, 1339, 1357, -1, 1404, 1405, 1406, -1, 1407, 1408, 1409, -1, 1410, 1408, 1407, -1, 1411, 1412, 1413, -1, 1414, 1412, 1415, -1, 1405, 1412, 1411, -1, 1416, 1412, 1417, -1, 1418, 1419, 1420, -1, 1417, 1412, 1405, -1, 1421, 1419, 1422, -1, 1415, 1412, 1416, -1, 1413, 1412, 1414, -1, 1420, 1419, 1423, -1, 1423, 1419, 1421, -1, 1424, 1425, 1426, -1, 1410, 1427, 1408, -1, 1422, 1427, 1410, -1, 1409, 1428, 1429, -1, 1408, 1428, 1409, -1, 1430, 1431, 1418, -1, 1418, 1431, 1419, -1, 1422, 1431, 1427, -1, 1419, 1431, 1422, -1, 1408, 1432, 1428, -1, 1427, 1432, 1408, -1, 1429, 1433, 1434, -1, 1428, 1433, 1429, -1, 1435, 1436, 1430, -1, 1431, 1436, 1427, -1, 1427, 1436, 1432, -1, 1430, 1436, 1431, -1, 1432, 1437, 1428, -1, 1428, 1437, 1433, -1, 1434, 1438, 1439, -1, 1433, 1438, 1434, -1, 1440, 1441, 1435, -1, 1436, 1441, 1432, -1, 1435, 1441, 1436, -1, 1432, 1441, 1437, -1, 1437, 1442, 1433, -1, 1433, 1442, 1438, -1, 1438, 1443, 1439, -1, 1439, 1443, 1444, -1, 1440, 1445, 1441, -1, 1437, 1445, 1442, -1, 1446, 1445, 1440, -1, 1441, 1445, 1437, -1, 1442, 1447, 1438, -1, 1438, 1447, 1443, -1, 1443, 1448, 1444, -1, 1444, 1448, 1449, -1, 1450, 1451, 1446, -1, 1446, 1451, 1445, -1, 1442, 1451, 1447, -1, 1445, 1451, 1442, -1, 1447, 1452, 1443, -1, 1443, 1452, 1448, -1, 1448, 1453, 1449, -1, 1449, 1453, 1454, -1, 1455, 1456, 1450, -1, 1451, 1456, 1447, -1, 1450, 1456, 1451, -1, 1447, 1456, 1452, -1, 1452, 1457, 1448, -1, 1448, 1457, 1453, -1, 1454, 1458, 1459, -1, 1453, 1458, 1454, -1, 1460, 1461, 1455, -1, 1452, 1461, 1457, -1, 1456, 1461, 1452, -1, 1455, 1461, 1456, -1, 1457, 1462, 1453, -1, 1453, 1462, 1458, -1, 1459, 1404, 1463, -1, 1458, 1404, 1459, -1, 1414, 1464, 1413, -1, 1465, 1466, 1460, -1, 1460, 1466, 1461, -1, 1425, 1467, 1468, -1, 1461, 1466, 1457, -1, 1424, 1467, 1425, -1, 1457, 1466, 1462, -1, 1469, 1421, 1424, -1, 1462, 1417, 1458, -1, 1424, 1421, 1467, -1, 1458, 1417, 1404, -1, 1468, 1410, 1407, -1, 1470, 1406, 1471, -1, 1463, 1406, 1470, -1, 1467, 1410, 1468, -1, 1404, 1406, 1463, -1, 1420, 1423, 1472, -1, 1473, 1423, 1469, -1, 1472, 1423, 1473, -1, 1415, 1416, 1465, -1, 1465, 1416, 1466, -1, 1466, 1416, 1462, -1, 1469, 1423, 1421, -1, 1467, 1422, 1410, -1, 1462, 1416, 1417, -1, 1471, 1405, 1411, -1, 1421, 1422, 1467, -1, 1406, 1405, 1471, -1, 1417, 1405, 1404, -1, 1474, 1475, 1476, -1, 1474, 1476, 1477, -1, 1474, 1477, 1342, -1, 1478, 1398, 1358, -1, 1478, 1358, 1357, -1, 1478, 1357, 1479, -1, 1480, 1481, 1482, -1, 1480, 1482, 1464, -1, 1480, 1464, 1398, -1, 1480, 1478, 1479, -1, 1480, 1479, 1481, -1, 1480, 1398, 1478, -1, 1483, 1341, 1403, -1, 1483, 1403, 1402, -1, 1483, 1402, 1472, -1, 1483, 1474, 1341, -1, 1484, 1472, 1485, -1, 1484, 1485, 1475, -1, 1484, 1474, 1483, -1, 1484, 1475, 1474, -1, 1484, 1483, 1472, -1, 1479, 1357, 1339, -1, 1479, 1486, 1481, -1, 1487, 1339, 1399, -1, 1487, 1399, 1394, -1, 1487, 1488, 1489, -1, 1487, 1489, 1486, -1, 1487, 1479, 1339, -1, 1487, 1486, 1479, -1, 1490, 1394, 1389, -1, 1490, 1389, 1384, -1, 1490, 1491, 1492, -1, 1490, 1492, 1488, -1, 1490, 1488, 1487, -1, 1490, 1487, 1394, -1, 1493, 1384, 1375, -1, 1493, 1494, 1491, -1, 1493, 1491, 1490, -1, 1493, 1490, 1384, -1, 1477, 1375, 1364, -1, 1477, 1364, 1342, -1, 1477, 1476, 1495, -1, 1477, 1495, 1494, -1, 1477, 1493, 1375, -1, 1477, 1494, 1493, -1, 1474, 1342, 1341, -1, 1496, 1497, 1498, -1, 1499, 1497, 1496, -1, 1497, 1500, 1498, -1, 1498, 1500, 1501, -1, 1500, 1502, 1501, -1, 1503, 1504, 1505, -1, 1505, 1504, 1506, -1, 1506, 1507, 1508, -1, 1504, 1507, 1506, -1, 1508, 1509, 1510, -1, 1507, 1509, 1508, -1, 1510, 1511, 1512, -1, 1509, 1511, 1510, -1, 801, 1513, 800, -1, 1514, 1513, 1515, -1, 1516, 1513, 1514, -1, 800, 1513, 1516, -1, 808, 1517, 806, -1, 810, 1517, 808, -1, 1512, 1517, 810, -1, 1511, 1517, 1512, -1, 803, 1518, 801, -1, 805, 1518, 803, -1, 806, 1518, 805, -1, 1517, 1518, 806, -1, 801, 1518, 1513, -1, 1513, 1519, 1520, -1, 1518, 1519, 1513, -1, 1520, 1521, 1522, -1, 1519, 1521, 1520, -1, 1522, 1523, 1524, -1, 1521, 1523, 1522, -1, 1524, 1499, 1496, -1, 1523, 1499, 1524, -1, 1525, 1526, 1527, -1, 1527, 1526, 1528, -1, 1528, 1529, 1530, -1, 1526, 1529, 1528, -1, 1530, 1531, 1532, -1, 1529, 1531, 1530, -1, 1532, 1533, 1534, -1, 1531, 1533, 1532, -1, 1534, 1535, 1536, -1, 1533, 1535, 1534, -1, 1536, 1537, 1538, -1, 1535, 1537, 1536, -1, 1538, 1539, 1540, -1, 1537, 1539, 1538, -1, 1540, 1541, 1542, -1, 1539, 1541, 1540, -1, 1542, 1543, 1544, -1, 1541, 1543, 1542, -1, 1544, 1545, 1546, -1, 1543, 1545, 1544, -1, 1546, 1547, 1548, -1, 1545, 1547, 1546, -1, 1548, 1549, 1550, -1, 1550, 1549, 1551, -1, 1547, 1549, 1548, -1, 1549, 1552, 1551, -1, 1553, 1554, 1555, -1, 1554, 1556, 1555, -1, 1555, 1557, 1558, -1, 1556, 1557, 1555, -1, 1558, 1559, 1560, -1, 1557, 1559, 1558, -1, 1560, 1561, 1562, -1, 1559, 1561, 1560, -1, 1562, 1563, 1564, -1, 1561, 1563, 1562, -1, 1564, 1565, 1566, -1, 1563, 1565, 1564, -1, 1566, 1567, 1568, -1, 1565, 1567, 1566, -1, 1568, 1569, 1570, -1, 1567, 1569, 1568, -1, 1570, 1571, 1572, -1, 1569, 1571, 1570, -1, 1572, 1573, 1574, -1, 1571, 1573, 1572, -1, 1574, 1575, 1576, -1, 1573, 1575, 1574, -1, 1576, 1577, 1578, -1, 1575, 1577, 1576, -1, 1578, 1579, 1580, -1, 1577, 1579, 1578, -1, 1581, 1582, 1583, -1, 1582, 1584, 1583, -1, 1583, 1585, 1586, -1, 1584, 1585, 1583, -1, 1586, 1587, 1588, -1, 1585, 1587, 1586, -1, 1588, 1589, 1590, -1, 1587, 1589, 1588, -1, 1590, 1591, 1592, -1, 1589, 1591, 1590, -1, 1592, 1593, 1594, -1, 1591, 1593, 1592, -1, 1594, 1595, 1596, -1, 1593, 1595, 1594, -1, 1596, 1597, 1598, -1, 1595, 1597, 1596, -1, 1598, 1599, 1600, -1, 1597, 1599, 1598, -1, 1600, 1601, 1602, -1, 1599, 1601, 1600, -1, 1602, 1603, 1604, -1, 1601, 1603, 1602, -1, 1604, 1605, 1606, -1, 1603, 1605, 1604, -1, 1606, 1607, 1608, -1, 1605, 1607, 1606, -1, 1609, 1610, 1611, -1, 1611, 1612, 1613, -1, 1610, 1612, 1611, -1, 1613, 1614, 1615, -1, 1612, 1614, 1613, -1, 1615, 1616, 1617, -1, 1614, 1616, 1615, -1, 1617, 1618, 1619, -1, 1616, 1618, 1617, -1, 1619, 1620, 1621, -1, 1618, 1620, 1619, -1, 1622, 1623, 1624, -1, 1624, 1625, 1626, -1, 1623, 1625, 1624, -1, 1626, 1627, 1628, -1, 1625, 1627, 1626, -1, 1628, 1629, 1630, -1, 1627, 1629, 1628, -1, 1630, 1631, 1632, -1, 1629, 1631, 1630, -1, 1632, 1633, 1634, -1, 1631, 1633, 1632, -1, 1635, 1636, 1637, -1, 1637, 1638, 1639, -1, 1636, 1638, 1637, -1, 1639, 1640, 1641, -1, 1638, 1640, 1639, -1, 1641, 1642, 1643, -1, 1640, 1642, 1641, -1, 1643, 1644, 1645, -1, 1642, 1644, 1643, -1, 1645, 1646, 1647, -1, 1644, 1646, 1645, -1, 1648, 1649, 1650, -1, 1650, 1651, 1652, -1, 1649, 1651, 1650, -1, 1652, 1653, 1654, -1, 1651, 1653, 1652, -1, 1654, 1655, 1656, -1, 1653, 1655, 1654, -1, 1656, 1657, 1658, -1, 1655, 1657, 1656, -1, 1658, 1659, 1660, -1, 1657, 1659, 1658, -1, 1661, 1662, 1663, -1, 1663, 1664, 1665, -1, 1662, 1664, 1663, -1, 1665, 1666, 1667, -1, 1664, 1666, 1665, -1, 1667, 1668, 1669, -1, 1666, 1668, 1667, -1, 1669, 1670, 1671, -1, 1668, 1670, 1669, -1, 1671, 1672, 1673, -1, 1670, 1672, 1671, -1, 1674, 1675, 1676, -1, 1676, 1677, 1678, -1, 1675, 1677, 1676, -1, 1678, 1679, 1680, -1, 1677, 1679, 1678, -1, 1680, 1681, 1682, -1, 1679, 1681, 1680, -1, 1682, 1683, 1684, -1, 1681, 1683, 1682, -1, 1684, 1685, 1686, -1, 1683, 1685, 1684, -1, 1687, 1688, 1689, -1, 1689, 1690, 1691, -1, 1688, 1690, 1689, -1, 1691, 1692, 1693, -1, 1690, 1692, 1691, -1, 1693, 1694, 1695, -1, 1692, 1694, 1693, -1, 1695, 1696, 1697, -1, 1694, 1696, 1695, -1, 1697, 1698, 1699, -1, 1696, 1698, 1697, -1, 1700, 1701, 1702, -1, 1702, 1703, 1704, -1, 1701, 1703, 1702, -1, 1704, 1705, 1706, -1, 1703, 1705, 1704, -1, 1706, 1707, 1708, -1, 1705, 1707, 1706, -1, 1708, 1709, 1710, -1, 1707, 1709, 1708, -1, 1710, 1711, 1712, -1, 1709, 1711, 1710, -1, 1713, 1714, 1715, -1, 1715, 1716, 1717, -1, 1714, 1716, 1715, -1, 1717, 1718, 1719, -1, 1716, 1718, 1717, -1, 1719, 1720, 1721, -1, 1718, 1720, 1719, -1, 1721, 1722, 1723, -1, 1720, 1722, 1721, -1, 1723, 1724, 1725, -1, 1722, 1724, 1723, -1, 1726, 1727, 1728, -1, 1728, 1729, 1730, -1, 1727, 1729, 1728, -1, 1730, 1731, 1732, -1, 1729, 1731, 1730, -1, 1732, 1733, 1734, -1, 1731, 1733, 1732, -1, 1734, 1735, 1736, -1, 1733, 1735, 1734, -1, 1736, 1737, 1738, -1, 1735, 1737, 1736, -1, 1739, 1740, 1741, -1, 1741, 1742, 1743, -1, 1740, 1742, 1741, -1, 1743, 1744, 1745, -1, 1742, 1744, 1743, -1, 1745, 1746, 1747, -1, 1744, 1746, 1745, -1, 1747, 1748, 1749, -1, 1746, 1748, 1747, -1, 1749, 1750, 1751, -1, 1748, 1750, 1749, -1, 1750, 1752, 1751, -1, 1753, 1754, 1755, -1, 1756, 1757, 1753, -1, 1753, 1757, 1754, -1, 1756, 1758, 1757, -1, 1756, 1759, 1758, -1, 1760, 1761, 1756, -1, 1756, 1761, 1759, -1, 1761, 1762, 1759, -1, 1761, 1763, 1762, -1, 1764, 1761, 1760, -1, 1764, 1765, 1761, -1, 1765, 1766, 1761, -1, 1766, 1767, 1761, -1, 1767, 1763, 1761, -1, 1768, 1769, 1764, -1, 1769, 1770, 1764, -1, 1770, 1765, 1764, -1, 1771, 1772, 1773, -1, 1771, 1774, 1772, -1, 1771, 1775, 1774, -1, 1771, 1776, 1775, -1, 734, 735, 1777, -1, 1778, 1779, 1780, -1, 1777, 735, 1781, -1, 1779, 184, 1780, -1, 1782, 1783, 1784, -1, 1780, 184, 1785, -1, 1778, 1786, 1787, -1, 735, 739, 1781, -1, 1781, 739, 1788, -1, 1789, 1790, 1791, -1, 184, 185, 1785, -1, 1785, 185, 1792, -1, 1782, 753, 1783, -1, 1778, 1793, 1786, -1, 739, 724, 1788, -1, 185, 189, 1792, -1, 1788, 724, 1794, -1, 1792, 189, 1795, -1, 1778, 203, 1793, -1, 1789, 1796, 1790, -1, 724, 726, 1794, -1, 1797, 1798, 1789, -1, 1794, 726, 1799, -1, 1800, 1798, 1797, -1, 1801, 1798, 1800, -1, 1802, 1798, 1801, -1, 1803, 1798, 1802, -1, 1804, 1798, 1803, -1, 1789, 1798, 1796, -1, 1795, 174, 1805, -1, 189, 174, 1795, -1, 1804, 1409, 1798, -1, 1407, 1409, 1804, -1, 1805, 176, 1806, -1, 174, 176, 1805, -1, 1804, 1468, 1407, -1, 1409, 1429, 1798, -1, 1782, 1807, 753, -1, 1804, 1425, 1468, -1, 1429, 1434, 1798, -1, 1434, 1439, 1798, -1, 1778, 1808, 203, -1, 1809, 1810, 1811, -1, 1812, 1813, 1807, -1, 1426, 1810, 1809, -1, 1425, 1810, 1426, -1, 1804, 1810, 1425, -1, 1813, 1814, 1807, -1, 1815, 1816, 1808, -1, 1810, 1817, 1811, -1, 1814, 754, 1807, -1, 1814, 1818, 754, -1, 1816, 1819, 1808, -1, 1820, 1821, 1822, -1, 1823, 1821, 1820, -1, 1808, 204, 203, -1, 1819, 204, 1808, -1, 1824, 1825, 1826, -1, 1819, 1827, 204, -1, 1828, 1825, 1824, -1, 1829, 1830, 1824, -1, 1821, 1831, 1822, -1, 1824, 1830, 1828, -1, 1822, 1831, 1810, -1, 1832, 1831, 1821, -1, 1810, 1831, 1817, -1, 1831, 1833, 1817, -1, 1834, 1835, 1836, -1, 1837, 1838, 1839, -1, 1826, 1838, 1837, -1, 1449, 1840, 1444, -1, 1825, 1838, 1826, -1, 1836, 1835, 1841, -1, 1835, 237, 1841, -1, 1829, 1842, 1830, -1, 1841, 237, 1843, -1, 1839, 1844, 1845, -1, 1840, 1846, 1444, -1, 1836, 1847, 1834, -1, 1449, 1848, 1840, -1, 1838, 1844, 1839, -1, 1846, 1849, 1444, -1, 1444, 1849, 1439, -1, 237, 238, 1843, -1, 1439, 1849, 1798, -1, 1829, 778, 1842, -1, 1843, 238, 1850, -1, 1845, 1851, 1852, -1, 1449, 1853, 1848, -1, 1454, 1853, 1449, -1, 1836, 1854, 1847, -1, 1849, 1855, 1798, -1, 1844, 1851, 1845, -1, 238, 242, 1850, -1, 1454, 79, 1853, -1, 1850, 242, 1856, -1, 1855, 1857, 1798, -1, 1851, 1858, 1852, -1, 1836, 256, 1854, -1, 1454, 1459, 79, -1, 242, 227, 1856, -1, 1857, 1859, 1798, -1, 1829, 779, 778, -1, 1856, 227, 1860, -1, 1859, 1861, 1798, -1, 1860, 229, 1862, -1, 227, 229, 1860, -1, 1831, 1863, 1833, -1, 1459, 1463, 79, -1, 1861, 1864, 1798, -1, 1831, 1865, 1863, -1, 1866, 1867, 1724, -1, 1836, 1868, 256, -1, 1858, 1752, 1852, -1, 1869, 1752, 726, -1, 1852, 1752, 1869, -1, 1870, 1752, 1858, -1, 1871, 1752, 1870, -1, 1872, 1752, 1871, -1, 1873, 1752, 1872, -1, 1874, 1752, 1873, -1, 1875, 1752, 1874, -1, 1876, 1752, 1875, -1, 1877, 1752, 1876, -1, 726, 1752, 1799, -1, 1867, 1725, 1724, -1, 1877, 1878, 1752, -1, 1879, 1880, 1868, -1, 1881, 1882, 1878, -1, 1880, 1883, 1868, -1, 1878, 1884, 1752, -1, 1882, 1884, 1878, -1, 1868, 257, 256, -1, 1883, 257, 1868, -1, 1884, 1751, 1752, -1, 1883, 1885, 257, -1, 1886, 1751, 1884, -1, 1887, 1751, 1886, -1, 1752, 1798, 229, -1, 1752, 229, 1888, -1, 1752, 1888, 282, -1, 1752, 282, 1889, -1, 1752, 1889, 335, -1, 1752, 335, 1890, -1, 1752, 1890, 388, -1, 1752, 388, 1799, -1, 1891, 80, 1892, -1, 229, 1798, 1862, -1, 1893, 80, 1891, -1, 1862, 1798, 176, -1, 1894, 80, 1893, -1, 176, 1798, 1806, -1, 1895, 1896, 1897, -1, 1806, 1798, 553, -1, 553, 1798, 1898, -1, 1899, 1896, 1895, -1, 1898, 1798, 52, -1, 52, 1798, 1900, -1, 1900, 1798, 123, -1, 80, 79, 1470, -1, 1901, 1902, 1894, -1, 80, 1470, 1892, -1, 1470, 79, 1463, -1, 1903, 1904, 150, -1, 1897, 290, 1905, -1, 1906, 1907, 1633, -1, 1894, 1902, 80, -1, 1906, 1633, 1908, -1, 1906, 1908, 1909, -1, 1896, 290, 1897, -1, 1634, 1633, 1907, -1, 1634, 1907, 1910, -1, 1911, 1912, 1620, -1, 1911, 1620, 1913, -1, 1895, 1914, 1899, -1, 1911, 1913, 1915, -1, 1621, 1620, 1912, -1, 1621, 1912, 1916, -1, 1917, 1918, 1711, -1, 1917, 1711, 1919, -1, 1917, 1919, 1920, -1, 1712, 1711, 1918, -1, 1712, 1918, 1921, -1, 1819, 1922, 1646, -1, 1905, 291, 1923, -1, 1819, 1646, 1924, -1, 1925, 1926, 1903, -1, 1819, 1924, 1827, -1, 1647, 1646, 1922, -1, 1647, 1922, 1927, -1, 1883, 1928, 1659, -1, 290, 291, 1905, -1, 1883, 1659, 1929, -1, 1903, 1926, 1930, -1, 1883, 1929, 1885, -1, 1660, 1659, 1928, -1, 1660, 1928, 1931, -1, 1932, 1933, 1672, -1, 1932, 1672, 1934, -1, 1932, 1934, 1935, -1, 1895, 1936, 1914, -1, 1673, 1672, 1933, -1, 1673, 1933, 1937, -1, 1938, 1939, 1685, -1, 1930, 131, 1940, -1, 1938, 1685, 1941, -1, 1938, 1941, 1942, -1, 1923, 295, 1943, -1, 1926, 131, 1930, -1, 1686, 1685, 1939, -1, 1686, 1939, 1944, -1, 1945, 1946, 1698, -1, 1903, 1947, 1925, -1, 1945, 1698, 1948, -1, 291, 295, 1923, -1, 1945, 1948, 1949, -1, 1699, 1698, 1946, -1, 1699, 1946, 1950, -1, 1814, 1866, 1724, -1, 1814, 1724, 1951, -1, 1814, 1951, 1818, -1, 754, 753, 1807, -1, 1895, 309, 1936, -1, 1940, 132, 1952, -1, 131, 132, 1940, -1, 1943, 280, 1953, -1, 1903, 1954, 1947, -1, 295, 280, 1943, -1, 1953, 282, 1888, -1, 1952, 136, 1955, -1, 280, 282, 1953, -1, 132, 136, 1952, -1, 1903, 150, 1954, -1, 1956, 1957, 1901, -1, 1901, 1957, 1902, -1, 1955, 121, 1958, -1, 136, 121, 1955, -1, 1864, 123, 1798, -1, 1895, 1959, 309, -1, 1958, 123, 1864, -1, 121, 123, 1958, -1, 1865, 97, 1956, -1, 1831, 97, 1865, -1, 1956, 97, 1957, -1, 1960, 1961, 1959, -1, 1961, 1932, 1959, -1, 1959, 310, 309, -1, 1932, 310, 1959, -1, 1962, 1963, 1904, -1, 1932, 1935, 310, -1, 1963, 1906, 1904, -1, 1964, 1965, 1966, -1, 1831, 98, 97, -1, 1906, 151, 1904, -1, 1966, 1965, 1967, -1, 1904, 151, 150, -1, 1965, 343, 1967, -1, 1906, 1909, 151, -1, 1967, 343, 1968, -1, 1966, 1969, 1964, -1, 1970, 1971, 1972, -1, 1968, 344, 1973, -1, 1972, 1971, 1974, -1, 1971, 60, 1974, -1, 343, 344, 1968, -1, 1966, 1975, 1969, -1, 1974, 60, 1976, -1, 1972, 1977, 1970, -1, 1973, 348, 1978, -1, 344, 348, 1973, -1, 60, 61, 1976, -1, 1966, 362, 1975, -1, 1976, 61, 1979, -1, 1972, 1980, 1977, -1, 348, 333, 1978, -1, 1978, 333, 1981, -1, 61, 65, 1979, -1, 1981, 335, 1889, -1, 1979, 65, 1982, -1, 1972, 26, 1980, -1, 333, 335, 1981, -1, 65, 50, 1982, -1, 1982, 50, 1983, -1, 50, 52, 1983, -1, 1983, 52, 1900, -1, 1966, 1984, 362, -1, 1972, 1985, 26, -1, 1986, 1987, 1984, -1, 1987, 1938, 1984, -1, 1984, 363, 362, -1, 1938, 363, 1984, -1, 1988, 1989, 1985, -1, 1938, 1942, 363, -1, 1989, 1911, 1985, -1, 1990, 1991, 1992, -1, 1911, 27, 1985, -1, 1985, 27, 26, -1, 1992, 1991, 1993, -1, 1911, 1915, 27, -1, 1993, 396, 1994, -1, 1991, 396, 1993, -1, 1992, 1995, 1990, -1, 1996, 1997, 1998, -1, 1999, 1997, 1996, -1, 1994, 397, 2000, -1, 396, 397, 1994, -1, 1998, 561, 2001, -1, 1997, 561, 1998, -1, 1992, 2002, 1995, -1, 397, 401, 2000, -1, 1996, 2003, 1999, -1, 2000, 401, 2004, -1, 2001, 562, 2005, -1, 1992, 415, 2002, -1, 561, 562, 2001, -1, 1996, 2006, 2003, -1, 2004, 386, 2007, -1, 2005, 566, 2008, -1, 401, 386, 2004, -1, 562, 566, 2005, -1, 2007, 388, 1890, -1, 386, 388, 2007, -1, 1996, 581, 2006, -1, 2008, 551, 2009, -1, 566, 551, 2008, -1, 2009, 553, 1898, -1, 551, 553, 2009, -1, 1992, 2010, 415, -1, 1996, 2011, 581, -1, 2012, 2013, 2010, -1, 2013, 1945, 2010, -1, 2010, 416, 415, -1, 2014, 2015, 2011, -1, 1945, 416, 2010, -1, 1945, 1949, 416, -1, 2015, 1917, 2011, -1, 2011, 580, 581, -1, 1917, 580, 2011, -1, 1782, 2016, 2017, -1, 2018, 2016, 1782, -1, 1917, 1920, 580, -1, 2016, 734, 2017, -1, 2017, 734, 1777, -1, 1787, 1779, 1778, -1, 1782, 1784, 2018, -1, 2019, 2020, 1737, -1, 2020, 2021, 1737, -1, 2021, 1738, 1737, -1, 2022, 2023, 2024, -1, 2024, 2025, 2026, -1, 2027, 2025, 2023, -1, 2023, 2025, 2024, -1, 2028, 2029, 2030, -1, 2031, 2029, 2028, -1, 2030, 2029, 2032, -1, 966, 1163, 965, -1, 965, 1163, 1115, -1, 978, 992, 2033, -1, 966, 1162, 1163, -1, 961, 1162, 966, -1, 2033, 976, 978, -1, 992, 997, 2033, -1, 2034, 2035, 961, -1, 961, 2035, 1162, -1, 2033, 971, 976, -1, 997, 1002, 2033, -1, 2033, 972, 971, -1, 2036, 2037, 2034, -1, 2034, 2037, 2035, -1, 1002, 1007, 2033, -1, 2038, 2039, 2036, -1, 1007, 1012, 2033, -1, 2036, 2039, 2037, -1, 1012, 1017, 2033, -1, 2038, 2040, 2039, -1, 2041, 2042, 2043, -1, 2044, 2042, 2041, -1, 972, 2042, 2044, -1, 2033, 2042, 972, -1, 2042, 2045, 2043, -1, 2042, 2046, 2045, -1, 2042, 2047, 2046, -1, 2042, 2048, 2047, -1, 1132, 603, 2033, -1, 1137, 603, 1132, -1, 2042, 2049, 2048, -1, 1142, 603, 1137, -1, 1147, 603, 1142, -1, 1152, 603, 1147, -1, 1158, 603, 1152, -1, 1096, 603, 1158, -1, 1100, 603, 1096, -1, 2050, 2051, 1156, -1, 2052, 2051, 2050, -1, 1021, 1117, 1017, -1, 1100, 2051, 603, -1, 2053, 2051, 2052, -1, 1156, 2051, 1100, -1, 603, 2051, 601, -1, 1017, 1117, 2033, -1, 1117, 1126, 2033, -1, 2053, 2054, 2051, -1, 2055, 2054, 2053, -1, 2056, 2054, 2055, -1, 2057, 2054, 2056, -1, 965, 1115, 1021, -1, 2042, 2054, 2057, -1, 2042, 2057, 2058, -1, 2042, 2058, 2059, -1, 2042, 2059, 2040, -1, 1021, 1115, 1117, -1, 2042, 2040, 2049, -1, 2049, 2040, 2060, -1, 1126, 1132, 2033, -1, 2060, 2040, 2038, -1, 2061, 2062, 2063, -1, 2062, 2064, 2063, -1, 2062, 2065, 2064, -1, 2061, 2066, 2062, -1, 2067, 2068, 2069, -1, 2066, 2068, 2070, -1, 2068, 2071, 2070, -1, 2068, 2072, 2071, -1, 649, 2073, 656, -1, 651, 2073, 649, -1, 651, 2074, 2073, -1, 2072, 2075, 651, -1, 2068, 2075, 2072, -1, 651, 2076, 2074, -1, 651, 2077, 2076, -1, 2075, 2078, 651, -1, 651, 2078, 2077, -1, 2061, 2068, 2066, -1, 2067, 2075, 2068, -1, 2079, 2080, 2081, -1, 2081, 2080, 2082, -1, 2083, 2084, 2085, -1, 2085, 2084, 2086, -1, 2087, 2088, 2089, -1, 2089, 2088, 2090, -1, 2091, 2092, 2093, -1, 2093, 2094, 2095, -1, 2092, 2094, 2093, -1, 2096, 2097, 2098, -1, 2098, 2097, 2099, -1, 2100, 2101, 2102, -1, 2102, 2103, 2104, -1, 2101, 2103, 2102, -1, 2105, 2106, 2107, -1, 2107, 2106, 2108, -1, 2109, 2110, 2111, -1, 2111, 2112, 2113, -1, 2110, 2112, 2111, -1, 2114, 2115, 2116, -1, 2116, 2115, 2117, -1, 2118, 2119, 2120, -1, 2120, 2121, 2122, -1, 2119, 2121, 2120, -1, 2123, 2124, 2125, -1, 2125, 2124, 2126, -1, 2127, 2128, 2129, -1, 2129, 2130, 2131, -1, 2128, 2130, 2129, -1, 2132, 2133, 2134, -1, 2134, 2133, 2135, -1, 2136, 2137, 2138, -1, 2138, 2139, 2140, -1, 2137, 2139, 2138, -1, 2141, 2142, 2143, -1, 2143, 2142, 2144, -1, 2145, 2146, 2147, -1, 2147, 2148, 2149, -1, 2146, 2148, 2147, -1, 2150, 2151, 2152, -1, 2152, 2151, 2153, -1, 2154, 2155, 2156, -1, 2156, 2157, 2158, -1, 2155, 2157, 2156, -1, 2159, 2160, 2161, -1, 2161, 2162, 2163, -1, 2160, 2162, 2161, -1, 2033, 2164, 2042, -1, 2042, 2164, 2165, -1, 2165, 2164, 2166, -1, 2166, 2167, 1739, -1, 2164, 2167, 2166, -1, 2167, 1740, 1739, -1, 2083, 2168, 2084, -1, 2084, 2168, 2169, -1, 2169, 2170, 2171, -1, 2168, 2170, 2169, -1, 2171, 2172, 2173, -1, 2170, 2172, 2171, -1, 2173, 2174, 2175, -1, 2172, 2174, 2173, -1, 2176, 2177, 2178, -1, 2175, 2177, 2176, -1, 2174, 2177, 2175, -1, 2177, 2179, 2178, -1, 2178, 2180, 1884, -1, 2179, 2180, 2178, -1, 2180, 2181, 1884, -1, 2181, 1886, 1884, -1, 2181, 1887, 1886, -1, 2180, 1887, 2181, -1, 2179, 1887, 2180, -1, 2027, 2182, 2025, -1, 2025, 2182, 2183, -1, 2183, 2182, 2184, -1, 2184, 2185, 1726, -1, 2182, 2185, 2184, -1, 2185, 1727, 1726, -1, 2160, 2186, 2162, -1, 2162, 2186, 2187, -1, 2187, 2186, 2188, -1, 2188, 2189, 1713, -1, 2186, 2189, 2188, -1, 2189, 1714, 1713, -1, 2028, 2190, 2031, -1, 2031, 2190, 2191, -1, 2191, 2192, 2193, -1, 2190, 2192, 2191, -1, 2193, 2194, 2195, -1, 2192, 2194, 2193, -1, 2195, 2196, 2197, -1, 2194, 2196, 2195, -1, 2198, 2199, 2200, -1, 2197, 2199, 2198, -1, 2196, 2199, 2197, -1, 2199, 2201, 2200, -1, 2200, 2202, 2019, -1, 2201, 2202, 2200, -1, 2202, 2203, 2019, -1, 2203, 2020, 2019, -1, 2203, 2021, 2020, -1, 2202, 2021, 2203, -1, 2201, 2021, 2202, -1, 2204, 2205, 2206, -1, 2204, 2207, 2205, -1, 2207, 2208, 2205, -1, 2207, 2209, 2208, -1, 2210, 2211, 2212, -1, 2210, 2213, 2211, -1, 2210, 2214, 2213, -1, 2210, 2215, 2214, -1, 2215, 2216, 2217, -1, 2210, 2216, 2215, -1, 2218, 2219, 2220, -1, 2218, 2221, 2219, -1, 2218, 2222, 2221, -1, 2223, 2224, 2225, -1, 2223, 2226, 2224, -1, 2223, 2227, 2226, -1, 2228, 2229, 2230, -1, 2228, 2231, 2229, -1, 2228, 2232, 2231, -1, 2233, 2234, 2235, -1, 2233, 2236, 2234, -1, 2233, 2237, 2236, -1, 2238, 2239, 2240, -1, 2238, 2241, 2239, -1, 2238, 2242, 2241, -1, 2243, 2244, 2245, -1, 2243, 2246, 2244, -1, 2243, 2247, 2246, -1, 2248, 2249, 2250, -1, 2248, 2251, 2249, -1, 2248, 2252, 2251, -1, 2253, 2254, 2255, -1, 2253, 2256, 2254, -1, 2253, 2257, 2256, -1, 2258, 2259, 2260, -1, 2258, 2261, 2259, -1, 2258, 2262, 2261, -1, 2258, 2263, 2262, -1, 2263, 1764, 1760, -1, 2263, 1768, 1764, -1, 2258, 1768, 2263, -1, 2107, 2108, 2264, -1, 2264, 2265, 2266, -1, 2266, 2265, 2267, -1, 2108, 2265, 2264, -1, 2267, 2268, 2269, -1, 2269, 2268, 2270, -1, 2265, 2268, 2267, -1, 2270, 2271, 2272, -1, 2272, 2271, 2273, -1, 2268, 2271, 2270, -1, 2273, 2274, 2275, -1, 2271, 2274, 2273, -1, 2275, 2276, 2277, -1, 2274, 2276, 2275, -1, 2278, 2279, 2280, -1, 2277, 2279, 2278, -1, 2276, 2279, 2277, -1, 2280, 2281, 2282, -1, 2279, 2281, 2280, -1, 2282, 2283, 2284, -1, 2281, 2283, 2282, -1, 2111, 2113, 2285, -1, 2113, 2286, 2285, -1, 2286, 2287, 2285, -1, 2285, 2288, 2289, -1, 2287, 2288, 2285, -1, 2289, 2290, 2250, -1, 2288, 2290, 2289, -1, 2290, 2248, 2250, -1, 2110, 2291, 2112, -1, 2112, 2291, 2292, -1, 2292, 2291, 2293, -1, 2293, 2294, 1700, -1, 2291, 2294, 2293, -1, 2294, 1701, 1700, -1, 2105, 2295, 2106, -1, 2106, 2295, 2296, -1, 2296, 2297, 2298, -1, 2295, 2297, 2296, -1, 2298, 2299, 2300, -1, 2297, 2299, 2298, -1, 2300, 2301, 2302, -1, 2299, 2301, 2300, -1, 2303, 2304, 2305, -1, 2302, 2304, 2303, -1, 2301, 2304, 2302, -1, 2304, 2306, 2305, -1, 2305, 2307, 1819, -1, 2306, 2307, 2305, -1, 2307, 2308, 1819, -1, 2308, 1922, 1819, -1, 2308, 1927, 1922, -1, 2307, 1927, 2308, -1, 2306, 1927, 2307, -1, 2089, 2090, 2309, -1, 2309, 2310, 2311, -1, 2311, 2310, 2312, -1, 2090, 2310, 2309, -1, 2312, 2313, 2314, -1, 2314, 2313, 2315, -1, 2310, 2313, 2312, -1, 2315, 2316, 2317, -1, 2317, 2316, 2318, -1, 2313, 2316, 2315, -1, 2318, 2319, 2320, -1, 2316, 2319, 2318, -1, 2320, 2321, 2322, -1, 2319, 2321, 2320, -1, 2323, 2324, 2325, -1, 2322, 2324, 2323, -1, 2321, 2324, 2322, -1, 2325, 2326, 2327, -1, 2324, 2326, 2325, -1, 2327, 2328, 2329, -1, 2326, 2328, 2327, -1, 2093, 2095, 2330, -1, 2095, 2331, 2330, -1, 2331, 2332, 2330, -1, 2330, 2333, 2334, -1, 2332, 2333, 2330, -1, 2333, 2335, 2334, -1, 2334, 2258, 2260, -1, 2335, 2258, 2334, -1, 2098, 2099, 2336, -1, 2336, 2337, 2338, -1, 2338, 2337, 2339, -1, 2099, 2337, 2336, -1, 2339, 2340, 2341, -1, 2341, 2340, 2342, -1, 2337, 2340, 2339, -1, 2342, 2343, 2344, -1, 2344, 2343, 2345, -1, 2340, 2343, 2342, -1, 2345, 2346, 2347, -1, 2343, 2346, 2345, -1, 2347, 2348, 2349, -1, 2346, 2348, 2347, -1, 2350, 2351, 2352, -1, 2349, 2351, 2350, -1, 2348, 2351, 2349, -1, 2352, 2353, 2354, -1, 2351, 2353, 2352, -1, 2354, 2355, 2356, -1, 2353, 2355, 2354, -1, 2102, 2104, 2357, -1, 2104, 2358, 2357, -1, 2358, 2359, 2357, -1, 2357, 2360, 2361, -1, 2359, 2360, 2357, -1, 2361, 2362, 2255, -1, 2360, 2362, 2361, -1, 2362, 2253, 2255, -1, 2116, 2117, 2363, -1, 2363, 2364, 2365, -1, 2365, 2364, 2366, -1, 2117, 2364, 2363, -1, 2366, 2367, 2368, -1, 2368, 2367, 2369, -1, 2364, 2367, 2366, -1, 2369, 2370, 2371, -1, 2371, 2370, 2372, -1, 2367, 2370, 2369, -1, 2372, 2373, 2374, -1, 2370, 2373, 2372, -1, 2374, 2375, 2376, -1, 2373, 2375, 2374, -1, 2377, 2378, 2379, -1, 2376, 2378, 2377, -1, 2375, 2378, 2376, -1, 2379, 2380, 2381, -1, 2378, 2380, 2379, -1, 2381, 2382, 2383, -1, 2380, 2382, 2381, -1, 2120, 2122, 2384, -1, 2122, 2385, 2384, -1, 2385, 2386, 2384, -1, 2384, 2387, 2388, -1, 2386, 2387, 2384, -1, 2388, 2389, 2245, -1, 2387, 2389, 2388, -1, 2389, 2243, 2245, -1, 2216, 2390, 2217, -1, 2391, 2390, 2216, -1, 2392, 2393, 2391, -1, 2391, 2393, 2390, -1, 2392, 1773, 2393, -1, 2392, 1771, 1773, -1, 2125, 2126, 2394, -1, 2394, 2395, 2396, -1, 2396, 2395, 2397, -1, 2126, 2395, 2394, -1, 2397, 2398, 2399, -1, 2399, 2398, 2400, -1, 2395, 2398, 2397, -1, 2400, 2401, 2402, -1, 2402, 2401, 2403, -1, 2398, 2401, 2400, -1, 2403, 2404, 2405, -1, 2401, 2404, 2403, -1, 2405, 2406, 2407, -1, 2404, 2406, 2405, -1, 2407, 2408, 2409, -1, 2409, 2408, 2410, -1, 2406, 2408, 2407, -1, 1776, 2411, 1775, -1, 2410, 2411, 1776, -1, 2408, 2411, 2410, -1, 1774, 2412, 1772, -1, 1775, 2412, 1774, -1, 2411, 2412, 1775, -1, 2129, 2131, 2413, -1, 2131, 2414, 2413, -1, 2414, 2415, 2413, -1, 2413, 2416, 2417, -1, 2415, 2416, 2413, -1, 2417, 2418, 2240, -1, 2416, 2418, 2417, -1, 2418, 2238, 2240, -1, 2134, 2135, 2419, -1, 2419, 2420, 2421, -1, 2421, 2420, 2422, -1, 2135, 2420, 2419, -1, 2422, 2423, 2424, -1, 2424, 2423, 2425, -1, 2420, 2423, 2422, -1, 2425, 2426, 2427, -1, 2427, 2426, 2428, -1, 2423, 2426, 2425, -1, 2428, 2429, 2430, -1, 2426, 2429, 2428, -1, 2430, 2431, 2432, -1, 2429, 2431, 2430, -1, 2433, 2434, 2435, -1, 2432, 2434, 2433, -1, 2431, 2434, 2432, -1, 2435, 2436, 2437, -1, 2434, 2436, 2435, -1, 2437, 2438, 2439, -1, 2436, 2438, 2437, -1, 2138, 2140, 2440, -1, 2140, 2441, 2440, -1, 2441, 2442, 2440, -1, 2440, 2443, 2444, -1, 2442, 2443, 2440, -1, 2443, 2445, 2444, -1, 2444, 2210, 2212, -1, 2445, 2210, 2444, -1, 2147, 2149, 2446, -1, 2149, 2447, 2446, -1, 2447, 2448, 2446, -1, 2446, 2449, 2450, -1, 2448, 2449, 2446, -1, 2450, 2451, 2220, -1, 2449, 2451, 2450, -1, 2451, 2218, 2220, -1, 2143, 2144, 2452, -1, 2452, 2453, 2454, -1, 2454, 2453, 2455, -1, 2144, 2453, 2452, -1, 2455, 2456, 2457, -1, 2457, 2456, 2458, -1, 2453, 2456, 2455, -1, 2458, 2459, 2460, -1, 2460, 2459, 2461, -1, 2456, 2459, 2458, -1, 2461, 2462, 2463, -1, 2459, 2462, 2461, -1, 2463, 2464, 2465, -1, 2465, 2464, 2466, -1, 2462, 2464, 2463, -1, 2466, 2467, 2468, -1, 2464, 2467, 2466, -1, 2468, 2469, 2470, -1, 2470, 2469, 2471, -1, 2467, 2469, 2468, -1, 2471, 2472, 2473, -1, 2469, 2472, 2471, -1, 2156, 2158, 2474, -1, 2158, 2475, 2474, -1, 2475, 2476, 2474, -1, 2474, 2477, 2478, -1, 2476, 2477, 2474, -1, 2478, 2479, 2225, -1, 2477, 2479, 2478, -1, 2479, 2223, 2225, -1, 2152, 2153, 2480, -1, 2480, 2481, 2482, -1, 2482, 2481, 2483, -1, 2153, 2481, 2480, -1, 2483, 2484, 2485, -1, 2485, 2484, 2486, -1, 2481, 2484, 2483, -1, 2486, 2487, 2488, -1, 2488, 2487, 2489, -1, 2484, 2487, 2486, -1, 2489, 2490, 2491, -1, 2487, 2490, 2489, -1, 2491, 2492, 2493, -1, 2493, 2492, 2494, -1, 2490, 2492, 2491, -1, 2494, 2495, 2496, -1, 2492, 2495, 2494, -1, 2496, 2497, 2498, -1, 2498, 2497, 2499, -1, 2495, 2497, 2496, -1, 2499, 2500, 2501, -1, 2497, 2500, 2499, -1, 2502, 2503, 2204, -1, 2204, 2503, 2207, -1, 2504, 2505, 2502, -1, 2502, 2505, 2503, -1, 2504, 2506, 2505, -1, 2051, 2054, 2507, -1, 2054, 2508, 2507, -1, 2507, 2509, 2510, -1, 2508, 2509, 2507, -1, 2509, 2506, 2510, -1, 2506, 2504, 2510, -1, 2504, 2502, 2510, -1, 2502, 2206, 2510, -1, 2502, 2204, 2206, -1, 2030, 2032, 2511, -1, 2511, 2512, 2513, -1, 2513, 2512, 2514, -1, 2032, 2512, 2511, -1, 2514, 2515, 2516, -1, 2516, 2515, 2517, -1, 2512, 2515, 2514, -1, 2517, 2518, 2519, -1, 2519, 2518, 2520, -1, 2515, 2518, 2517, -1, 2520, 2521, 2522, -1, 2518, 2521, 2520, -1, 2522, 2523, 2524, -1, 2521, 2523, 2522, -1, 2525, 2526, 2527, -1, 2524, 2526, 2525, -1, 2523, 2526, 2524, -1, 2527, 2528, 2529, -1, 2526, 2528, 2527, -1, 2529, 2530, 2531, -1, 2528, 2530, 2529, -1, 2161, 2163, 2532, -1, 2163, 2533, 2532, -1, 2533, 2534, 2532, -1, 2532, 2535, 2536, -1, 2534, 2535, 2532, -1, 2536, 2537, 2230, -1, 2535, 2537, 2536, -1, 2537, 2228, 2230, -1, 2024, 2026, 2538, -1, 2026, 2539, 2538, -1, 2539, 2540, 2538, -1, 2538, 2541, 2542, -1, 2540, 2541, 2538, -1, 2542, 2543, 2235, -1, 2541, 2543, 2542, -1, 2543, 2233, 2235, -1, 2085, 2086, 2544, -1, 2544, 2545, 2546, -1, 2546, 2545, 2547, -1, 2086, 2545, 2544, -1, 2547, 2548, 2549, -1, 2549, 2548, 2550, -1, 2545, 2548, 2547, -1, 2550, 2551, 2552, -1, 2552, 2551, 2553, -1, 2548, 2551, 2550, -1, 2553, 2554, 2555, -1, 2551, 2554, 2553, -1, 2555, 2556, 2557, -1, 2557, 2556, 2558, -1, 2554, 2556, 2555, -1, 2558, 2559, 2560, -1, 2556, 2559, 2558, -1, 2560, 2561, 2562, -1, 2562, 2561, 2563, -1, 2559, 2561, 2560, -1, 2563, 2564, 2565, -1, 2561, 2564, 2563, -1, 2081, 2082, 2566, -1, 2566, 2567, 2568, -1, 2568, 2567, 2569, -1, 2082, 2567, 2566, -1, 2569, 2570, 2571, -1, 2571, 2570, 2572, -1, 2567, 2570, 2569, -1, 2572, 2573, 2574, -1, 2574, 2573, 2575, -1, 2570, 2573, 2572, -1, 2575, 2576, 2577, -1, 2573, 2576, 2575, -1, 2577, 2578, 2579, -1, 2576, 2578, 2577, -1, 2579, 2580, 2581, -1, 2581, 2580, 2582, -1, 2578, 2580, 2579, -1, 2582, 2583, 1755, -1, 2580, 2583, 2582, -1, 1755, 2584, 1753, -1, 2583, 2584, 1755, -1, 2327, 2585, 2586, -1, 2327, 2587, 2585, -1, 2327, 2329, 2587, -1, 2325, 2327, 2586, -1, 2323, 2325, 2586, -1, 2322, 2323, 2586, -1, 2588, 2587, 2329, -1, 2585, 2587, 2588, -1, 2589, 2585, 2588, -1, 2586, 2585, 2589, -1, 2590, 2589, 2591, -1, 2592, 2586, 2589, -1, 2592, 2589, 2590, -1, 2593, 2586, 2592, -1, 2591, 2594, 2595, -1, 2590, 2595, 2596, -1, 2590, 2591, 2595, -1, 2592, 2596, 2597, -1, 2592, 2590, 2596, -1, 2593, 2592, 2597, -1, 2598, 2597, 2596, -1, 2598, 2596, 2595, -1, 2598, 2595, 2594, -1, 2599, 2600, 2601, -1, 2602, 2598, 2603, -1, 2604, 2598, 2602, -1, 2605, 2603, 2606, -1, 2605, 2602, 2603, -1, 2607, 2257, 2597, -1, 2607, 2598, 2604, -1, 2607, 2597, 2598, -1, 2608, 2604, 2602, -1, 2608, 2602, 2605, -1, 2609, 2606, 2600, -1, 2609, 2605, 2606, -1, 2609, 2600, 2599, -1, 2610, 2256, 2257, -1, 2610, 2604, 2608, -1, 2610, 2257, 2607, -1, 2610, 2607, 2604, -1, 2611, 2599, 2612, -1, 2611, 2609, 2599, -1, 2611, 2608, 2605, -1, 2611, 2605, 2609, -1, 2613, 2254, 2256, -1, 2613, 2255, 2254, -1, 2613, 2612, 2255, -1, 2613, 2256, 2610, -1, 2613, 2608, 2611, -1, 2613, 2611, 2612, -1, 2613, 2610, 2608, -1, 2354, 2614, 2615, -1, 2354, 2616, 2614, -1, 2354, 2356, 2616, -1, 2352, 2354, 2615, -1, 2350, 2352, 2615, -1, 2349, 2350, 2615, -1, 2617, 2616, 2356, -1, 2614, 2616, 2617, -1, 2618, 2614, 2617, -1, 2615, 2614, 2618, -1, 2619, 2618, 2620, -1, 2621, 2615, 2618, -1, 2621, 2618, 2619, -1, 2622, 2615, 2621, -1, 2619, 2623, 2624, -1, 2619, 2620, 2623, -1, 2621, 2624, 2625, -1, 2621, 2619, 2624, -1, 2622, 2625, 2626, -1, 2622, 2621, 2625, -1, 2627, 2626, 2625, -1, 2627, 2625, 2624, -1, 2627, 2624, 2623, -1, 2628, 2629, 2630, -1, 2631, 2627, 2632, -1, 2633, 2627, 2631, -1, 2634, 2632, 2635, -1, 2634, 2631, 2632, -1, 2636, 2252, 2626, -1, 2636, 2627, 2633, -1, 2636, 2626, 2627, -1, 2637, 2633, 2631, -1, 2637, 2631, 2634, -1, 2638, 2635, 2629, -1, 2638, 2634, 2635, -1, 2638, 2629, 2628, -1, 2639, 2251, 2252, -1, 2639, 2633, 2637, -1, 2639, 2252, 2636, -1, 2639, 2636, 2633, -1, 2640, 2628, 2641, -1, 2640, 2638, 2628, -1, 2640, 2637, 2634, -1, 2640, 2634, 2638, -1, 2642, 2249, 2251, -1, 2642, 2250, 2249, -1, 2642, 2641, 2250, -1, 2642, 2251, 2639, -1, 2642, 2637, 2640, -1, 2642, 2640, 2641, -1, 2642, 2639, 2637, -1, 2282, 2643, 2644, -1, 2282, 2645, 2643, -1, 2282, 2284, 2645, -1, 2280, 2282, 2644, -1, 2278, 2280, 2644, -1, 2277, 2278, 2644, -1, 2646, 2645, 2284, -1, 2643, 2645, 2646, -1, 2647, 2643, 2646, -1, 2644, 2643, 2647, -1, 2648, 2647, 2649, -1, 2650, 2644, 2647, -1, 2650, 2647, 2648, -1, 2651, 2644, 2650, -1, 2648, 2652, 2653, -1, 2648, 2649, 2652, -1, 2650, 2654, 2655, -1, 2650, 2653, 2654, -1, 2650, 2648, 2653, -1, 2651, 2650, 2655, -1, 2656, 2655, 2654, -1, 2656, 2654, 2653, -1, 2656, 2653, 2652, -1, 2657, 2658, 2659, -1, 2660, 2656, 2661, -1, 2662, 2656, 2660, -1, 2663, 2661, 2664, -1, 2663, 2660, 2661, -1, 2665, 2247, 2655, -1, 2665, 2656, 2662, -1, 2665, 2655, 2656, -1, 2666, 2662, 2660, -1, 2666, 2660, 2663, -1, 2667, 2664, 2658, -1, 2667, 2663, 2664, -1, 2667, 2658, 2657, -1, 2668, 2246, 2247, -1, 2668, 2662, 2666, -1, 2668, 2247, 2665, -1, 2668, 2665, 2662, -1, 2669, 2657, 2670, -1, 2669, 2667, 2657, -1, 2669, 2666, 2663, -1, 2669, 2663, 2667, -1, 2671, 2244, 2246, -1, 2671, 2245, 2244, -1, 2671, 2670, 2245, -1, 2671, 2246, 2668, -1, 2671, 2666, 2669, -1, 2671, 2669, 2670, -1, 2671, 2668, 2666, -1, 2381, 2672, 2673, -1, 2381, 2674, 2672, -1, 2381, 2383, 2674, -1, 2379, 2381, 2673, -1, 2377, 2379, 2673, -1, 2376, 2377, 2673, -1, 2675, 2674, 2383, -1, 2672, 2674, 2675, -1, 2676, 2672, 2675, -1, 2673, 2672, 2676, -1, 2677, 2676, 2678, -1, 2679, 2673, 2676, -1, 2679, 2676, 2677, -1, 2680, 2673, 2679, -1, 2677, 2681, 2682, -1, 2677, 2678, 2681, -1, 2679, 2682, 2683, -1, 2679, 2677, 2682, -1, 2680, 2683, 2684, -1, 2680, 2679, 2683, -1, 2685, 2684, 2683, -1, 2685, 2683, 2682, -1, 2685, 2682, 2681, -1, 2686, 2687, 2688, -1, 2689, 2685, 2690, -1, 2691, 2685, 2689, -1, 2692, 2690, 2693, -1, 2692, 2689, 2690, -1, 2694, 2242, 2684, -1, 2694, 2685, 2691, -1, 2694, 2684, 2685, -1, 2695, 2691, 2689, -1, 2695, 2689, 2692, -1, 2696, 2693, 2687, -1, 2696, 2692, 2693, -1, 2696, 2687, 2686, -1, 2697, 2241, 2242, -1, 2697, 2691, 2695, -1, 2697, 2242, 2694, -1, 2697, 2694, 2691, -1, 2698, 2686, 2699, -1, 2698, 2696, 2686, -1, 2698, 2695, 2692, -1, 2698, 2692, 2696, -1, 2700, 2239, 2241, -1, 2700, 2240, 2239, -1, 2700, 2699, 2240, -1, 2700, 2241, 2697, -1, 2700, 2695, 2698, -1, 2700, 2698, 2699, -1, 2700, 2697, 2695, -1, 2437, 2701, 2702, -1, 2437, 2703, 2701, -1, 2437, 2439, 2703, -1, 2435, 2437, 2702, -1, 2433, 2435, 2702, -1, 2432, 2433, 2702, -1, 2704, 2703, 2439, -1, 2701, 2703, 2704, -1, 2705, 2701, 2704, -1, 2702, 2701, 2705, -1, 2706, 2705, 2707, -1, 2708, 2702, 2705, -1, 2708, 2705, 2706, -1, 2709, 2702, 2708, -1, 2706, 2710, 2711, -1, 2706, 2707, 2710, -1, 2708, 2711, 2712, -1, 2708, 2706, 2711, -1, 2709, 2712, 2713, -1, 2709, 2708, 2712, -1, 2714, 2713, 2712, -1, 2714, 2712, 2711, -1, 2714, 2711, 2710, -1, 2715, 2716, 2717, -1, 2718, 2714, 2719, -1, 2720, 2714, 2718, -1, 2721, 2719, 2722, -1, 2721, 2718, 2719, -1, 2723, 2222, 2713, -1, 2723, 2714, 2720, -1, 2723, 2713, 2714, -1, 2724, 2720, 2718, -1, 2724, 2718, 2721, -1, 2725, 2722, 2716, -1, 2725, 2721, 2722, -1, 2725, 2716, 2715, -1, 2726, 2221, 2222, -1, 2726, 2720, 2724, -1, 2726, 2222, 2723, -1, 2726, 2723, 2720, -1, 2727, 2715, 2728, -1, 2727, 2725, 2715, -1, 2727, 2724, 2721, -1, 2727, 2721, 2725, -1, 2729, 2219, 2221, -1, 2729, 2220, 2219, -1, 2729, 2728, 2220, -1, 2729, 2221, 2726, -1, 2729, 2724, 2727, -1, 2729, 2727, 2728, -1, 2729, 2726, 2724, -1, 2468, 2730, 2466, -1, 2470, 2731, 2468, -1, 2468, 2731, 2730, -1, 2471, 2732, 2470, -1, 2473, 2732, 2471, -1, 2730, 2732, 2733, -1, 2733, 2732, 2734, -1, 2734, 2732, 2735, -1, 2735, 2732, 2473, -1, 2470, 2732, 2731, -1, 2731, 2732, 2730, -1, 2736, 2735, 2473, -1, 2734, 2735, 2736, -1, 2737, 2734, 2736, -1, 2733, 2734, 2737, -1, 2738, 2737, 2739, -1, 2740, 2733, 2737, -1, 2740, 2737, 2738, -1, 2741, 2733, 2740, -1, 2739, 2742, 2743, -1, 2738, 2743, 2744, -1, 2738, 2739, 2743, -1, 2740, 2738, 2744, -1, 2741, 2744, 2745, -1, 2741, 2740, 2744, -1, 2746, 2745, 2744, -1, 2746, 2744, 2743, -1, 2746, 2743, 2742, -1, 2747, 2748, 2749, -1, 2750, 2746, 2751, -1, 2752, 2746, 2750, -1, 2753, 2751, 2754, -1, 2753, 2750, 2751, -1, 2755, 2227, 2745, -1, 2755, 2746, 2752, -1, 2755, 2745, 2746, -1, 2756, 2752, 2750, -1, 2756, 2750, 2753, -1, 2757, 2754, 2748, -1, 2757, 2753, 2754, -1, 2757, 2748, 2747, -1, 2758, 2226, 2227, -1, 2758, 2752, 2756, -1, 2758, 2227, 2755, -1, 2758, 2755, 2752, -1, 2759, 2747, 2760, -1, 2759, 2757, 2747, -1, 2759, 2756, 2753, -1, 2759, 2753, 2757, -1, 2761, 2224, 2226, -1, 2761, 2225, 2224, -1, 2761, 2760, 2225, -1, 2761, 2226, 2758, -1, 2761, 2756, 2759, -1, 2761, 2759, 2760, -1, 2761, 2758, 2756, -1, 2496, 2762, 2494, -1, 2498, 2763, 2496, -1, 2496, 2763, 2762, -1, 2499, 2764, 2498, -1, 2501, 2764, 2499, -1, 2762, 2764, 2765, -1, 2765, 2764, 2766, -1, 2766, 2764, 2767, -1, 2767, 2764, 2501, -1, 2498, 2764, 2763, -1, 2763, 2764, 2762, -1, 2768, 2767, 2501, -1, 2766, 2767, 2768, -1, 2769, 2766, 2768, -1, 2765, 2766, 2769, -1, 2770, 2769, 2771, -1, 2772, 2765, 2769, -1, 2772, 2769, 2770, -1, 2773, 2765, 2772, -1, 2771, 2774, 2775, -1, 2770, 2775, 2776, -1, 2770, 2771, 2775, -1, 2772, 2776, 2777, -1, 2772, 2770, 2776, -1, 2773, 2772, 2777, -1, 2778, 2777, 2776, -1, 2778, 2776, 2775, -1, 2778, 2775, 2774, -1, 2779, 2780, 2781, -1, 2782, 2778, 2783, -1, 2784, 2778, 2782, -1, 2785, 2783, 2786, -1, 2785, 2782, 2783, -1, 2787, 2232, 2777, -1, 2787, 2778, 2784, -1, 2787, 2777, 2778, -1, 2788, 2784, 2782, -1, 2788, 2782, 2785, -1, 2789, 2786, 2780, -1, 2789, 2785, 2786, -1, 2789, 2780, 2779, -1, 2790, 2231, 2232, -1, 2790, 2784, 2788, -1, 2790, 2232, 2787, -1, 2790, 2787, 2784, -1, 2791, 2779, 2792, -1, 2791, 2789, 2779, -1, 2791, 2788, 2785, -1, 2791, 2785, 2789, -1, 2793, 2229, 2231, -1, 2793, 2230, 2229, -1, 2793, 2792, 2230, -1, 2793, 2231, 2790, -1, 2793, 2788, 2791, -1, 2793, 2791, 2792, -1, 2793, 2790, 2788, -1, 2560, 2794, 2558, -1, 2562, 2795, 2560, -1, 2560, 2795, 2794, -1, 2563, 2796, 2562, -1, 2565, 2796, 2563, -1, 2794, 2796, 2797, -1, 2797, 2796, 2798, -1, 2798, 2796, 2799, -1, 2799, 2796, 2565, -1, 2562, 2796, 2795, -1, 2795, 2796, 2794, -1, 2800, 2799, 2565, -1, 2798, 2799, 2800, -1, 2801, 2798, 2800, -1, 2797, 2798, 2801, -1, 2802, 2801, 2803, -1, 2804, 2797, 2801, -1, 2804, 2801, 2802, -1, 2805, 2797, 2804, -1, 2803, 2806, 2807, -1, 2802, 2807, 2808, -1, 2802, 2803, 2807, -1, 2804, 2808, 2809, -1, 2804, 2802, 2808, -1, 2805, 2804, 2809, -1, 2810, 2808, 2807, -1, 2810, 2807, 2806, -1, 2809, 2808, 2810, -1, 2811, 2205, 2812, -1, 2206, 2205, 2811, -1, 2813, 2814, 2815, -1, 2813, 2810, 2814, -1, 2816, 2810, 2813, -1, 2817, 2209, 2809, -1, 2817, 2816, 2209, -1, 2817, 2810, 2816, -1, 2817, 2809, 2810, -1, 2818, 2813, 2815, -1, 2819, 2816, 2813, -1, 2819, 2209, 2816, -1, 2819, 2813, 2818, -1, 2820, 2208, 2209, -1, 2820, 2819, 2208, -1, 2820, 2209, 2819, -1, 2821, 2822, 2823, -1, 2821, 2815, 2822, -1, 2821, 2823, 2812, -1, 2821, 2818, 2815, -1, 2824, 2821, 2812, -1, 2824, 2819, 2818, -1, 2824, 2818, 2821, -1, 2824, 2812, 2205, -1, 2824, 2208, 2819, -1, 2825, 2205, 2208, -1, 2825, 2208, 2824, -1, 2825, 2824, 2205, -1, 2529, 2826, 2827, -1, 2529, 2828, 2826, -1, 2529, 2531, 2828, -1, 2527, 2529, 2827, -1, 2525, 2527, 2827, -1, 2524, 2525, 2827, -1, 2829, 2828, 2531, -1, 2826, 2828, 2829, -1, 2830, 2826, 2829, -1, 2827, 2826, 2830, -1, 2831, 2830, 2832, -1, 2833, 2827, 2830, -1, 2833, 2830, 2831, -1, 2834, 2827, 2833, -1, 2831, 2835, 2836, -1, 2831, 2832, 2835, -1, 2833, 2836, 2837, -1, 2833, 2831, 2836, -1, 2834, 2837, 2838, -1, 2834, 2833, 2837, -1, 2839, 2838, 2837, -1, 2839, 2837, 2836, -1, 2839, 2836, 2835, -1, 2840, 2841, 2842, -1, 2843, 2839, 2844, -1, 2845, 2839, 2843, -1, 2846, 2844, 2847, -1, 2846, 2843, 2844, -1, 2848, 2237, 2838, -1, 2848, 2839, 2845, -1, 2848, 2838, 2839, -1, 2849, 2845, 2843, -1, 2849, 2843, 2846, -1, 2850, 2847, 2841, -1, 2850, 2846, 2847, -1, 2850, 2841, 2840, -1, 2851, 2236, 2237, -1, 2851, 2845, 2849, -1, 2851, 2237, 2848, -1, 2851, 2848, 2845, -1, 2852, 2840, 2853, -1, 2852, 2850, 2840, -1, 2852, 2849, 2846, -1, 2852, 2846, 2850, -1, 2854, 2234, 2236, -1, 2854, 2235, 2234, -1, 2854, 2853, 2235, -1, 2854, 2236, 2851, -1, 2854, 2849, 2852, -1, 2854, 2852, 2853, -1, 2854, 2851, 2849, -1, 2155, 2855, 2157, -1, 2157, 2855, 2856, -1, 2856, 2855, 2857, -1, 2857, 2858, 1687, -1, 2855, 2858, 2857, -1, 2858, 1688, 1687, -1, 2150, 2859, 2151, -1, 2151, 2859, 2860, -1, 2860, 2861, 2862, -1, 2859, 2861, 2860, -1, 2862, 2863, 2864, -1, 2861, 2863, 2862, -1, 2864, 2865, 2866, -1, 2863, 2865, 2864, -1, 2867, 2868, 2869, -1, 2866, 2868, 2867, -1, 2865, 2868, 2866, -1, 2868, 2870, 2869, -1, 2869, 2871, 1814, -1, 2870, 2871, 2869, -1, 2871, 2872, 1814, -1, 2872, 1866, 1814, -1, 2872, 1867, 1866, -1, 2871, 1867, 2872, -1, 2870, 1867, 2871, -1, 2146, 2873, 2148, -1, 2148, 2873, 2874, -1, 2874, 2873, 2875, -1, 2875, 2876, 1674, -1, 2873, 2876, 2875, -1, 2876, 1675, 1674, -1, 2141, 2877, 2142, -1, 2142, 2877, 2878, -1, 2878, 2879, 2880, -1, 2877, 2879, 2878, -1, 2880, 2881, 2882, -1, 2879, 2881, 2880, -1, 2882, 2883, 2884, -1, 2881, 2883, 2882, -1, 2885, 2886, 2887, -1, 2884, 2886, 2885, -1, 2883, 2886, 2884, -1, 2886, 2888, 2887, -1, 2887, 2889, 1945, -1, 2888, 2889, 2887, -1, 2889, 2890, 1945, -1, 2890, 1946, 1945, -1, 2890, 1950, 1946, -1, 2889, 1950, 2890, -1, 2888, 1950, 2889, -1, 2137, 2891, 2139, -1, 2139, 2891, 2892, -1, 2892, 2891, 2893, -1, 2893, 2894, 1661, -1, 2891, 2894, 2893, -1, 2894, 1662, 1661, -1, 2132, 2895, 2133, -1, 2133, 2895, 2896, -1, 2896, 2897, 2898, -1, 2895, 2897, 2896, -1, 2898, 2899, 2900, -1, 2897, 2899, 2898, -1, 2900, 2901, 2902, -1, 2899, 2901, 2900, -1, 2903, 2904, 2905, -1, 2902, 2904, 2903, -1, 2901, 2904, 2902, -1, 2904, 2906, 2905, -1, 2905, 2907, 1938, -1, 2906, 2907, 2905, -1, 2907, 2908, 1938, -1, 2908, 1939, 1938, -1, 2908, 1944, 1939, -1, 2907, 1944, 2908, -1, 2906, 1944, 2907, -1, 2128, 2909, 2130, -1, 2130, 2909, 2910, -1, 2910, 2909, 2911, -1, 2911, 2912, 1648, -1, 2909, 2912, 2911, -1, 2912, 1649, 1648, -1, 2123, 2913, 2124, -1, 2124, 2913, 2914, -1, 2914, 2915, 2916, -1, 2913, 2915, 2914, -1, 2916, 2917, 2918, -1, 2915, 2917, 2916, -1, 2918, 2919, 2920, -1, 2917, 2919, 2918, -1, 2921, 2922, 2923, -1, 2920, 2922, 2921, -1, 2919, 2922, 2920, -1, 2922, 2924, 2923, -1, 2923, 2925, 1932, -1, 2924, 2925, 2923, -1, 2925, 2926, 1932, -1, 2926, 1933, 1932, -1, 2926, 1937, 1933, -1, 2925, 1937, 2926, -1, 2924, 1937, 2925, -1, 2119, 2927, 2121, -1, 2121, 2927, 2928, -1, 2928, 2927, 2929, -1, 2929, 2930, 1635, -1, 2927, 2930, 2929, -1, 2930, 1636, 1635, -1, 2114, 2931, 2115, -1, 2115, 2931, 2932, -1, 2932, 2933, 2934, -1, 2931, 2933, 2932, -1, 2934, 2935, 2936, -1, 2933, 2935, 2934, -1, 2936, 2937, 2938, -1, 2935, 2937, 2936, -1, 2939, 2940, 2941, -1, 2938, 2940, 2939, -1, 2937, 2940, 2938, -1, 2940, 2942, 2941, -1, 2941, 2943, 1883, -1, 2942, 2943, 2941, -1, 2943, 2944, 1883, -1, 2944, 1928, 1883, -1, 2944, 1931, 1928, -1, 2943, 1931, 2944, -1, 2942, 1931, 2943, -1, 2092, 2945, 2094, -1, 2094, 2945, 2946, -1, 2946, 2945, 2947, -1, 2947, 2948, 1622, -1, 2945, 2948, 2947, -1, 2948, 1623, 1622, -1, 2087, 2949, 2088, -1, 2088, 2949, 2950, -1, 2950, 2951, 2952, -1, 2949, 2951, 2950, -1, 2952, 2953, 2954, -1, 2951, 2953, 2952, -1, 2954, 2955, 2956, -1, 2953, 2955, 2954, -1, 2957, 2958, 2959, -1, 2956, 2958, 2957, -1, 2955, 2958, 2956, -1, 2958, 2960, 2959, -1, 2959, 2961, 1911, -1, 2960, 2961, 2959, -1, 2961, 2962, 1911, -1, 2962, 1912, 1911, -1, 2962, 1916, 1912, -1, 2961, 1916, 2962, -1, 2960, 1916, 2961, -1, 2079, 2963, 2080, -1, 2080, 2963, 2964, -1, 2964, 2965, 2966, -1, 2963, 2965, 2964, -1, 2966, 2967, 2968, -1, 2965, 2967, 2966, -1, 2968, 2969, 2970, -1, 2967, 2969, 2968, -1, 2971, 2972, 2973, -1, 2970, 2972, 2971, -1, 2969, 2972, 2970, -1, 2972, 2974, 2973, -1, 2973, 2975, 1906, -1, 2974, 2975, 2973, -1, 2975, 2976, 1906, -1, 2976, 1907, 1906, -1, 2976, 1910, 1907, -1, 2975, 1910, 2976, -1, 2974, 1910, 2975, -1, 2977, 1921, 2978, -1, 2978, 1921, 2979, -1, 2979, 1921, 1918, -1, 2096, 2980, 2097, -1, 2097, 2980, 2981, -1, 2981, 2982, 2983, -1, 2980, 2982, 2981, -1, 2983, 2984, 2985, -1, 2982, 2984, 2983, -1, 2985, 2986, 2987, -1, 2984, 2986, 2985, -1, 2987, 2988, 2989, -1, 2989, 2988, 2990, -1, 2986, 2988, 2987, -1, 2988, 2977, 2990, -1, 2990, 2978, 1917, -1, 2977, 2978, 2990, -1, 2978, 2979, 1917, -1, 2979, 1918, 1917, -1, 2101, 2991, 2103, -1, 2103, 2991, 2992, -1, 2992, 2991, 2993, -1, 2993, 2994, 1609, -1, 2991, 2994, 2993, -1, 2994, 1610, 1609, -1, 2995, 2996, 2997, -1, 2998, 2996, 2999, -1, 2997, 2996, 2998, -1, 2999, 3000, 3001, -1, 2996, 3000, 2999, -1, 2995, 3000, 2996, -1, 3001, 3002, 3003, -1, 3004, 3002, 2995, -1, 2995, 3002, 3000, -1, 3000, 3002, 3001, -1, 3002, 3005, 3003, -1, 3004, 3005, 3002, -1, 3003, 3006, 3007, -1, 3008, 3009, 3010, -1, 3005, 3006, 3003, -1, 3004, 3006, 3005, -1, 3011, 3012, 3004, -1, 3006, 3012, 3007, -1, 3004, 3012, 3006, -1, 3007, 3013, 3014, -1, 3012, 3013, 3007, -1, 3011, 3013, 3012, -1, 3014, 3015, 3016, -1, 3017, 3015, 3018, -1, 3011, 3015, 3013, -1, 3018, 3015, 3011, -1, 3013, 3015, 3014, -1, 3019, 3020, 3021, -1, 3021, 3020, 3022, -1, 3022, 3020, 3023, -1, 3023, 3020, 3017, -1, 3015, 3020, 3016, -1, 3017, 3020, 3015, -1, 3016, 3024, 3025, -1, 3025, 3024, 3026, -1, 3026, 3024, 3019, -1, 3019, 3024, 3020, -1, 3020, 3024, 3016, -1, 3027, 3028, 3029, -1, 3028, 2997, 3029, -1, 3011, 3030, 3018, -1, 3030, 3031, 3018, -1, 3031, 3032, 3018, -1, 3033, 3034, 3035, -1, 3035, 3034, 3036, -1, 3036, 3034, 3008, -1, 3008, 3034, 3009, -1, 3009, 3037, 3038, -1, 3034, 3037, 3009, -1, 3033, 3037, 3034, -1, 3029, 3039, 3033, -1, 3038, 3039, 3040, -1, 3037, 3039, 3038, -1, 3033, 3039, 3037, -1, 3029, 3041, 3039, -1, 3039, 3041, 3040, -1, 2997, 3041, 3029, -1, 3040, 2998, 2999, -1, 2997, 2998, 3041, -1, 3041, 2998, 3040, -1, 3042, 3028, 3027, -1, 3043, 3028, 3042, -1, 3044, 2997, 3043, -1, 3043, 2997, 3028, -1, 3045, 2995, 3044, -1, 3044, 2995, 2997, -1, 3045, 3004, 2995, -1, 3046, 3011, 3045, -1, 3045, 3011, 3004, -1, 3046, 3030, 3011, -1, 3047, 3031, 3046, -1, 3046, 3031, 3030, -1, 3047, 3032, 3031, -1, 3048, 3049, 3050, -1, 3050, 3049, 3051, -1, 3052, 3053, 3048, -1, 3048, 3053, 3049, -1, 3040, 3053, 3052, -1, 3054, 3055, 3056, -1, 3051, 3055, 3054, -1, 3057, 3058, 3059, -1, 2999, 3060, 3040, -1, 3040, 3060, 3053, -1, 3051, 3061, 3055, -1, 3049, 3061, 3051, -1, 3053, 3062, 3049, -1, 3049, 3062, 3061, -1, 3056, 3063, 3064, -1, 3055, 3063, 3056, -1, 3001, 3065, 2999, -1, 2999, 3065, 3060, -1, 3060, 3065, 3053, -1, 3053, 3065, 3062, -1, 3010, 3009, 3066, -1, 3055, 3067, 3063, -1, 3066, 3009, 3068, -1, 3068, 3009, 3069, -1, 3061, 3067, 3055, -1, 3069, 3009, 3070, -1, 3061, 3071, 3067, -1, 3062, 3071, 3061, -1, 3064, 3072, 3073, -1, 3063, 3072, 3064, -1, 3065, 3074, 3062, -1, 3007, 3074, 3003, -1, 3003, 3074, 3001, -1, 3062, 3074, 3071, -1, 3001, 3074, 3065, -1, 3067, 3075, 3063, -1, 3063, 3075, 3072, -1, 3071, 3076, 3067, -1, 3067, 3076, 3075, -1, 3073, 3077, 3078, -1, 3072, 3077, 3073, -1, 3071, 3079, 3076, -1, 3007, 3079, 3074, -1, 3014, 3079, 3007, -1, 3074, 3079, 3071, -1, 3075, 3080, 3072, -1, 3072, 3080, 3077, -1, 3076, 3081, 3075, -1, 3075, 3081, 3080, -1, 3079, 3082, 3076, -1, 3016, 3082, 3014, -1, 3014, 3082, 3079, -1, 3076, 3082, 3081, -1, 3081, 3082, 3016, -1, 3078, 3083, 3084, -1, 3084, 3083, 3085, -1, 3085, 3083, 3086, -1, 3077, 3083, 3078, -1, 3086, 3087, 3088, -1, 3080, 3087, 3077, -1, 3077, 3087, 3083, -1, 3083, 3087, 3086, -1, 3088, 3089, 3090, -1, 3090, 3089, 3091, -1, 3091, 3089, 3025, -1, 3025, 3089, 3016, -1, 3080, 3089, 3087, -1, 3016, 3089, 3081, -1, 3081, 3089, 3080, -1, 3087, 3089, 3088, -1, 3092, 3093, 3057, -1, 3057, 3093, 3058, -1, 3070, 3094, 3092, -1, 3092, 3094, 3093, -1, 3038, 3095, 3009, -1, 3070, 3095, 3094, -1, 3009, 3095, 3070, -1, 3058, 3050, 3096, -1, 3093, 3050, 3058, -1, 3093, 3048, 3050, -1, 3094, 3048, 3093, -1, 3094, 3052, 3048, -1, 3038, 3052, 3095, -1, 3095, 3052, 3094, -1, 3096, 3051, 3054, -1, 3050, 3051, 3096, -1, 3040, 3097, 3038, -1, 3052, 3097, 3040, -1, 3038, 3097, 3052, -1, 3098, 3099, 3100, -1, 3098, 3100, 3101, -1, 3098, 3101, 3102, -1, 3098, 3102, 3103, -1, 1255, 1253, 3104, -1, 3104, 1257, 1255, -1, 1253, 1251, 3104, -1, 3098, 1259, 3104, -1, 3104, 1259, 1257, -1, 1251, 1249, 3104, -1, 3098, 1260, 1259, -1, 3098, 3105, 1260, -1, 3098, 3106, 3105, -1, 3098, 3107, 3106, -1, 3098, 3108, 3107, -1, 3098, 3103, 3108, -1, 3109, 3110, 1235, -1, 1235, 3110, 1237, -1, 1237, 3110, 1239, -1, 1239, 3110, 1241, -1, 1241, 3110, 1243, -1, 1243, 3110, 1245, -1, 1245, 3110, 1247, -1, 1247, 3110, 1249, -1, 1249, 3110, 3104, -1, 3111, 3112, 3113, -1, 3113, 3112, 3114, -1, 3114, 3112, 3109, -1, 3109, 3112, 3110, -1, 3115, 3116, 3111, -1, 3111, 3116, 3112, -1, 3117, 3118, 3115, -1, 3115, 3118, 3116, -1, 3117, 3101, 3118, -1, 3102, 3101, 3117, -1, 3119, 3120, 3121, -1, 3122, 3123, 3119, -1, 3119, 3123, 3120, -1, 3124, 3125, 3122, -1, 3122, 3125, 3123, -1, 3126, 3127, 3124, -1, 3124, 3127, 3125, -1, 3128, 3129, 3126, -1, 3126, 3129, 3127, -1, 3130, 3131, 3132, -1, 3132, 3131, 3133, -1, 3132, 3133, 3128, -1, 3128, 3133, 3129, -1, 1607, 3134, 1608, -1, 1608, 3134, 3135, -1, 3135, 3136, 3137, -1, 3134, 3136, 3135, -1, 3137, 3138, 3139, -1, 3136, 3138, 3137, -1, 3139, 3140, 3141, -1, 3138, 3140, 3139, -1, 3141, 3142, 3143, -1, 3140, 3142, 3141, -1, 3143, 3144, 3145, -1, 3142, 3144, 3143, -1, 3145, 3146, 3147, -1, 3144, 3146, 3145, -1, 3147, 3148, 3149, -1, 3146, 3148, 3147, -1, 3149, 3150, 3151, -1, 3148, 3150, 3149, -1, 3151, 3152, 3153, -1, 3150, 3152, 3151, -1, 3153, 3154, 3155, -1, 3152, 3154, 3153, -1, 3155, 3156, 3157, -1, 3154, 3156, 3155, -1, 3157, 1582, 1581, -1, 3156, 1582, 3157, -1, 1580, 1579, 3158, -1, 3158, 3159, 3160, -1, 1579, 3159, 3158, -1, 3160, 3161, 3162, -1, 3159, 3161, 3160, -1, 3162, 3163, 3164, -1, 3161, 3163, 3162, -1, 3164, 3165, 3166, -1, 3163, 3165, 3164, -1, 3166, 3167, 3168, -1, 3165, 3167, 3166, -1, 3168, 3169, 3170, -1, 3167, 3169, 3168, -1, 3170, 3171, 3172, -1, 3169, 3171, 3170, -1, 3172, 3173, 3174, -1, 3171, 3173, 3172, -1, 3174, 3175, 3176, -1, 3173, 3175, 3174, -1, 3176, 3177, 3178, -1, 3175, 3177, 3176, -1, 3178, 3179, 3180, -1, 3177, 3179, 3178, -1, 3180, 3181, 1553, -1, 3179, 3181, 3180, -1, 3181, 1554, 1553, -1, 797, 796, 3182, -1, 796, 3183, 3182, -1, 1513, 3184, 1515, -1, 3185, 3184, 1513, -1, 3186, 3187, 3183, -1, 3183, 3187, 3182, -1, 3188, 3189, 3186, -1, 3190, 3189, 3188, -1, 1515, 3189, 3190, -1, 3191, 3189, 3184, -1, 3192, 3189, 3191, -1, 3193, 3189, 3192, -1, 3194, 3189, 3193, -1, 3184, 3189, 1515, -1, 3186, 3189, 3187, -1, 3195, 3189, 3196, -1, 3196, 3189, 3194, -1, 3197, 3198, 3199, -1, 3200, 3201, 3199, -1, 3199, 3201, 3197, -1, 3202, 3203, 3200, -1, 3200, 3203, 3201, -1, 3198, 3204, 3199, -1, 3202, 3205, 3203, -1, 3202, 3206, 3205, -1, 3202, 3207, 3206, -1, 3202, 3208, 3207, -1, 3202, 3209, 3208, -1, 3120, 3210, 3121, -1, 3120, 3211, 3210, -1, 3212, 3213, 3214, -1, 812, 3212, 3214, -1, 815, 812, 3214, -1, 818, 815, 3214, -1, 820, 818, 3214, -1, 823, 820, 3214, -1, 825, 823, 3214, -1, 3215, 3214, 3216, -1, 3215, 3216, 3217, -1, 3218, 3214, 3215, -1, 3219, 3214, 3218, -1, 3220, 3214, 3219, -1, 3221, 825, 3214, -1, 3221, 3214, 3220, -1, 3222, 825, 3221, -1, 3223, 825, 3222, -1, 3224, 825, 3223, -1, 3225, 825, 3224, -1, 3226, 825, 3225, -1, 3227, 3226, 3228, -1, 3227, 825, 3226, -1, 3229, 3230, 3231, -1, 3229, 3231, 3232, -1, 3233, 3234, 3235, -1, 3233, 3235, 3236, -1, 3237, 3238, 3239, -1, 3240, 3238, 3237, -1, 3239, 3238, 3241, -1, 3242, 3243, 3244, -1, 3244, 3245, 3246, -1, 628, 3247, 3248, -1, 3249, 3247, 3250, -1, 3248, 3247, 3249, -1, 3243, 3251, 3244, -1, 3244, 3251, 3245, -1, 3252, 3253, 3254, -1, 3255, 3253, 3252, -1, 3250, 3253, 3255, -1, 3243, 3256, 3251, -1, 3247, 3253, 3250, -1, 3256, 3257, 3251, -1, 3243, 3258, 3256, -1, 3257, 3259, 3251, -1, 3240, 3260, 3238, -1, 3243, 3261, 3258, -1, 3259, 3262, 3251, -1, 3262, 3263, 3251, -1, 3248, 3264, 3243, -1, 3243, 3264, 3261, -1, 3262, 3265, 3263, -1, 3260, 3266, 3238, -1, 3267, 3266, 3260, -1, 3268, 3266, 3267, -1, 3269, 3266, 3268, -1, 3270, 3266, 3269, -1, 3271, 3266, 3270, -1, 3265, 3272, 3263, -1, 3273, 3274, 3248, -1, 3271, 3275, 3266, -1, 3276, 3277, 3278, -1, 3254, 3277, 3276, -1, 3279, 3280, 3281, -1, 3253, 3277, 3254, -1, 3263, 3280, 3279, -1, 3272, 3280, 3263, -1, 3271, 3282, 3275, -1, 3274, 634, 3248, -1, 3274, 632, 634, -1, 3271, 3283, 3282, -1, 3278, 3284, 3271, -1, 3271, 3284, 3283, -1, 634, 641, 3248, -1, 3277, 3284, 3278, -1, 3280, 3285, 3281, -1, 641, 648, 3248, -1, 648, 613, 3248, -1, 613, 628, 3248, -1, 3280, 3286, 3285, -1, 3286, 3287, 3285, -1, 3248, 3288, 3264, -1, 3286, 3289, 3287, -1, 3248, 3249, 3288, -1, 3239, 3241, 3286, -1, 3286, 3241, 3289, -1, 3290, 3291, 478, -1, 2771, 2769, 3292, -1, 478, 3291, 3293, -1, 3294, 3295, 3296, -1, 3297, 3298, 3299, -1, 3300, 3295, 3294, -1, 3299, 3301, 3297, -1, 2769, 2768, 3292, -1, 3297, 3302, 3298, -1, 3301, 3303, 3297, -1, 3297, 3304, 3302, -1, 3292, 2501, 3305, -1, 3306, 3307, 3308, -1, 3300, 3309, 3295, -1, 2768, 2501, 3292, -1, 3297, 3310, 3304, -1, 3303, 3311, 3297, -1, 3300, 3312, 3309, -1, 3313, 3312, 3300, -1, 3314, 3312, 3313, -1, 3315, 3312, 3314, -1, 584, 3312, 3315, -1, 583, 3312, 584, -1, 3291, 3316, 3317, -1, 3318, 2382, 3290, -1, 3291, 2382, 3316, -1, 3290, 2382, 3291, -1, 3319, 3320, 3321, -1, 3319, 3322, 3320, -1, 3323, 3322, 3319, -1, 3324, 3325, 3326, -1, 3320, 3327, 3321, -1, 3321, 3327, 3328, -1, 3329, 3330, 439, -1, 3324, 3331, 3325, -1, 3332, 3331, 3324, -1, 2678, 2676, 3333, -1, 439, 3330, 3334, -1, 3323, 3335, 3322, -1, 3311, 3336, 3297, -1, 3337, 3335, 3323, -1, 3325, 3336, 3326, -1, 3326, 3336, 3311, -1, 3332, 3338, 3331, -1, 3339, 3338, 3332, -1, 2676, 2675, 3333, -1, 3327, 3340, 3328, -1, 3336, 3341, 3297, -1, 3337, 3342, 3335, -1, 3339, 3343, 3338, -1, 3333, 2383, 3344, -1, 2675, 2383, 3333, -1, 3339, 3345, 3343, -1, 3346, 3345, 3339, -1, 3347, 3345, 3346, -1, 3348, 3345, 3347, -1, 3349, 3345, 3348, -1, 3350, 3345, 3349, -1, 3337, 3351, 3342, -1, 3352, 3351, 3337, -1, 3353, 3351, 3352, -1, 3341, 3354, 3297, -1, 3355, 3351, 3353, -1, 466, 3351, 3355, -1, 465, 3351, 466, -1, 3330, 3356, 3357, -1, 3358, 2472, 3329, -1, 3330, 2472, 3356, -1, 3329, 2472, 3330, -1, 3359, 3360, 3361, -1, 3362, 3363, 3359, -1, 3359, 3363, 3360, -1, 2739, 2737, 3364, -1, 3360, 3365, 3361, -1, 3366, 3367, 491, -1, 3368, 3369, 3370, -1, 491, 3367, 3371, -1, 3372, 3373, 3362, -1, 2737, 2736, 3364, -1, 3368, 3374, 3369, -1, 3375, 3374, 3368, -1, 3362, 3373, 3363, -1, 3369, 3376, 3370, -1, 3364, 2473, 3377, -1, 3370, 3376, 3354, -1, 3372, 3378, 3373, -1, 2736, 2473, 3364, -1, 3297, 3379, 3310, -1, 3375, 3380, 3374, -1, 3381, 3380, 3375, -1, 3382, 3383, 3372, -1, 3384, 3383, 3382, -1, 3376, 3385, 3354, -1, 3386, 3383, 3384, -1, 505, 3383, 3386, -1, 504, 3383, 505, -1, 3381, 3387, 3380, -1, 3372, 3383, 3378, -1, 3367, 3388, 3389, -1, 3366, 2283, 3367, -1, 3367, 2283, 3388, -1, 3381, 3390, 3387, -1, 3391, 2283, 3366, -1, 3392, 3390, 3381, -1, 3393, 3390, 3392, -1, 3394, 3390, 3393, -1, 427, 3390, 3394, -1, 426, 3390, 427, -1, 3379, 3395, 3396, -1, 3379, 2564, 3395, -1, 3297, 2564, 3379, -1, 3397, 3398, 3399, -1, 3361, 3400, 3401, -1, 3402, 3400, 3365, -1, 3365, 3400, 3361, -1, 3403, 3400, 3402, -1, 3404, 3400, 3403, -1, 3405, 3400, 3404, -1, 3307, 3400, 3308, -1, 3406, 3407, 3397, -1, 3401, 3400, 3307, -1, 3297, 2806, 2564, -1, 3405, 3408, 3400, -1, 3397, 3407, 3398, -1, 3399, 3409, 3410, -1, 3398, 3409, 3399, -1, 3408, 3411, 3400, -1, 452, 3412, 3413, -1, 3414, 3412, 452, -1, 3415, 3416, 3406, -1, 3411, 3417, 3400, -1, 2806, 2803, 2564, -1, 3406, 3416, 3407, -1, 2803, 2801, 2564, -1, 2649, 2647, 3418, -1, 3409, 3419, 3410, -1, 2801, 2800, 2564, -1, 3415, 3420, 3416, -1, 2647, 2646, 3418, -1, 2800, 2565, 2564, -1, 3417, 3421, 3400, -1, 3422, 3293, 3415, -1, 3423, 3293, 3422, -1, 3424, 3293, 3423, -1, 479, 3293, 3424, -1, 478, 3293, 479, -1, 3418, 2284, 3425, -1, 2646, 2284, 3418, -1, 3415, 3293, 3420, -1, 3421, 3426, 3400, -1, 3412, 3427, 3428, -1, 3414, 2438, 3412, -1, 3412, 2438, 3427, -1, 3429, 2438, 3414, -1, 3430, 3431, 3432, -1, 3433, 3434, 3430, -1, 3430, 3434, 3431, -1, 2707, 2705, 3435, -1, 583, 3436, 3312, -1, 3437, 3436, 583, -1, 3431, 3438, 3432, -1, 3432, 3438, 3439, -1, 3350, 3440, 3345, -1, 3441, 3440, 3350, -1, 2705, 2704, 3435, -1, 3442, 3443, 3433, -1, 3426, 3444, 3400, -1, 518, 3444, 3426, -1, 517, 3444, 518, -1, 3400, 3444, 3445, -1, 3433, 3443, 3434, -1, 3435, 2439, 3446, -1, 2704, 2439, 3435, -1, 3438, 3447, 3439, -1, 3436, 3448, 3449, -1, 3437, 2355, 3436, -1, 3450, 2355, 3437, -1, 3436, 2355, 3448, -1, 3442, 3451, 3443, -1, 3452, 3334, 3442, -1, 3453, 3334, 3452, -1, 3454, 3334, 3453, -1, 440, 3334, 3454, -1, 2620, 2618, 3455, -1, 439, 3334, 440, -1, 3442, 3334, 3451, -1, 3440, 3456, 3457, -1, 2618, 2617, 3455, -1, 3440, 2530, 3456, -1, 3458, 2530, 3441, -1, 3455, 2356, 3459, -1, 3441, 2530, 3440, -1, 2617, 2356, 3455, -1, 3460, 3461, 3462, -1, 3463, 3464, 3460, -1, 3465, 3466, 504, -1, 3460, 3464, 3461, -1, 504, 3466, 3383, -1, 3462, 3467, 3468, -1, 3461, 3467, 3462, -1, 465, 3469, 3351, -1, 3470, 3469, 465, -1, 2832, 2830, 3471, -1, 3472, 3473, 3463, -1, 3466, 3474, 3475, -1, 3463, 3473, 3464, -1, 3465, 2328, 3466, -1, 3476, 2328, 3465, -1, 3467, 3477, 3468, -1, 3466, 2328, 3474, -1, 2830, 2829, 3471, -1, 2591, 2589, 3478, -1, 3472, 3479, 3473, -1, 3471, 2531, 3480, -1, 2829, 2531, 3471, -1, 3472, 3371, 3479, -1, 3481, 3371, 3472, -1, 2589, 2588, 3478, -1, 3482, 3371, 3481, -1, 3483, 3371, 3482, -1, 492, 3371, 3483, -1, 491, 3371, 492, -1, 3478, 2329, 3484, -1, 2588, 2329, 3478, -1, 3469, 3485, 3486, -1, 3470, 2412, 3469, -1, 3469, 2412, 3485, -1, 3487, 2412, 3470, -1, 3488, 3489, 517, -1, 3444, 3489, 3490, -1, 517, 3489, 3444, -1, 3491, 3492, 3493, -1, 3489, 3494, 3495, -1, 3496, 3497, 3491, -1, 3498, 2584, 3488, -1, 3488, 2584, 3489, -1, 3491, 3497, 3492, -1, 3489, 2584, 3494, -1, 3493, 3499, 3500, -1, 3492, 3499, 3493, -1, 3501, 3502, 426, -1, 1760, 1756, 3503, -1, 3504, 1753, 3498, -1, 3503, 1753, 3504, -1, 426, 3502, 3390, -1, 3498, 1753, 2584, -1, 3496, 3505, 3497, -1, 3506, 3505, 3496, -1, 1756, 1753, 3503, -1, 3478, 2594, 2591, -1, 2329, 2328, 3484, -1, 3484, 2328, 3476, -1, 3503, 2263, 1760, -1, 3400, 3297, 3419, -1, 3400, 3419, 3468, -1, 3400, 3468, 3477, -1, 3400, 3477, 3308, -1, 3419, 3297, 3410, -1, 3410, 3297, 3340, -1, 3340, 3297, 3328, -1, 3328, 3297, 3507, -1, 3507, 3297, 3500, -1, 2217, 1772, 3508, -1, 3500, 3297, 3447, -1, 3447, 3297, 3439, -1, 3508, 1772, 3509, -1, 3439, 3297, 3385, -1, 2390, 1772, 2217, -1, 3385, 3297, 3354, -1, 3471, 2835, 2832, -1, 2531, 2530, 3480, -1, 2390, 2393, 1772, -1, 3480, 2530, 3458, -1, 3499, 3507, 3500, -1, 3292, 2774, 2771, -1, 2501, 2500, 3305, -1, 3506, 3510, 3505, -1, 3305, 2500, 3511, -1, 3364, 2742, 2739, -1, 2393, 1773, 1772, -1, 2473, 2472, 3377, -1, 3377, 2472, 3358, -1, 3435, 2710, 2707, -1, 2439, 2438, 3446, -1, 3446, 2438, 3429, -1, 3508, 2215, 2217, -1, 1772, 2412, 3509, -1, 3509, 2412, 3487, -1, 3333, 2681, 2678, -1, 2383, 2382, 3344, -1, 3344, 2382, 3318, -1, 3418, 2652, 2649, -1, 2284, 2283, 3425, -1, 3425, 2283, 3391, -1, 3455, 2623, 2620, -1, 2356, 2355, 3459, -1, 3459, 2355, 3450, -1, 3506, 3413, 3510, -1, 3512, 3413, 3506, -1, 3513, 3413, 3512, -1, 3514, 3413, 3513, -1, 453, 3413, 3514, -1, 452, 3413, 453, -1, 3502, 3515, 3516, -1, 3511, 2500, 3501, -1, 3502, 2500, 3515, -1, 3501, 2500, 3502, -1, 3517, 3518, 3519, -1, 3517, 3296, 3518, -1, 3294, 3296, 3517, -1, 3518, 3306, 3519, -1, 3519, 3306, 3308, -1, 3520, 3521, 3522, -1, 3523, 3520, 3522, -1, 3524, 3523, 3522, -1, 3525, 3524, 3522, -1, 3526, 3522, 619, -1, 3526, 3525, 3522, -1, 3527, 3526, 619, -1, 3528, 3527, 619, -1, 3529, 3528, 619, -1, 3530, 3529, 619, -1, 3531, 3047, 3532, -1, 3531, 3533, 3032, -1, 3531, 3032, 3047, -1, 619, 3531, 3530, -1, 3530, 3531, 3534, -1, 3534, 3531, 3535, -1, 3535, 3531, 3532, -1, 3536, 3537, 3538, -1, 3536, 3539, 3537, -1, 3539, 3540, 3537, -1, 3541, 3542, 3540, -1, 3543, 3542, 3541, -1, 3540, 3542, 3537, -1, 3542, 3544, 3537, -1, 3542, 3545, 3544, -1, 3545, 3546, 3544, -1, 3547, 3548, 3549, -1, 3548, 3550, 3549, -1, 3548, 3551, 3550, -1, 599, 596, 3551, -1, 3548, 602, 3551, -1, 3551, 602, 599, -1, 596, 595, 3551, -1, 595, 3552, 3551, -1, 3552, 3553, 3551, -1, 3553, 3554, 3551, -1, 3555, 3556, 3557, -1, 3556, 3558, 3557, -1, 3558, 3559, 3557, -1, 3559, 3560, 3557, -1, 3560, 3561, 3557, -1, 3561, 3562, 3557, -1, 3562, 3563, 3557, -1, 3563, 3564, 3557, -1, 3557, 3565, 3548, -1, 3548, 3565, 602, -1, 3557, 3566, 3565, -1, 3557, 3567, 3566, -1, 3557, 3568, 3567, -1, 3557, 3569, 3568, -1, 3564, 3570, 3557, -1, 3557, 3570, 3569, -1, 3564, 3571, 3570, -1, 3564, 3572, 3571, -1, 3564, 3573, 3572, -1, 3564, 3574, 3573, -1, 3554, 3575, 3551, -1, 3554, 3576, 3575, -1, 3564, 833, 3574, -1, 3574, 833, 835, -1, 3577, 3578, 3579, -1, 3580, 3581, 3582, -1, 3583, 3584, 3585, -1, 3586, 3584, 3583, -1, 3587, 3584, 3586, -1, 3588, 3584, 3587, -1, 3589, 3584, 3588, -1, 3581, 3584, 3589, -1, 3580, 3584, 3581, -1, 3590, 3591, 3592, -1, 3593, 3591, 3590, -1, 3592, 3594, 3490, -1, 3591, 3594, 3592, -1, 3595, 3596, 3593, -1, 3593, 3596, 3591, -1, 3594, 3597, 3490, -1, 3598, 3599, 3595, -1, 3600, 3599, 3598, -1, 3595, 3599, 3596, -1, 3597, 3601, 3490, -1, 3602, 3273, 3600, -1, 3603, 3273, 3602, -1, 3604, 3273, 3603, -1, 3600, 3273, 3599, -1, 3601, 3444, 3490, -1, 3604, 3605, 3273, -1, 3605, 3274, 3273, -1, 3606, 3607, 3214, -1, 3214, 3608, 3216, -1, 3607, 3608, 3214, -1, 3609, 3610, 3611, -1, 3612, 3610, 3609, -1, 3613, 3610, 3612, -1, 3614, 3610, 3613, -1, 3615, 3610, 3614, -1, 3607, 3616, 3608, -1, 3617, 3610, 3615, -1, 3618, 3610, 3617, -1, 3607, 3610, 3619, -1, 3607, 3619, 3620, -1, 3607, 3621, 3616, -1, 3619, 3610, 3622, -1, 3622, 3610, 3623, -1, 3623, 3610, 3624, -1, 3623, 3624, 3625, -1, 3623, 3625, 3626, -1, 3624, 3610, 3618, -1, 3607, 3627, 3621, -1, 3607, 3628, 3627, -1, 3607, 3629, 3628, -1, 3607, 3620, 3629, -1, 3211, 3630, 3210, -1, 3631, 3630, 3211, -1, 3632, 3633, 3631, -1, 3631, 3633, 3630, -1, 3634, 3635, 3632, -1, 3632, 3635, 3633, -1, 3636, 3637, 3634, -1, 3634, 3637, 3635, -1, 3623, 3638, 3636, -1, 3636, 3638, 3637, -1, 3623, 3626, 3638, -1, 3639, 3640, 3641, -1, 3641, 3642, 3639, -1, 3640, 3643, 3641, -1, 3644, 3645, 3641, -1, 3641, 3645, 3642, -1, 3643, 3646, 3641, -1, 3644, 884, 3645, -1, 3646, 3647, 3641, -1, 3644, 887, 884, -1, 3644, 889, 887, -1, 3644, 891, 889, -1, 3644, 893, 891, -1, 3644, 895, 893, -1, 3644, 897, 895, -1, 3648, 3649, 3647, -1, 3650, 3649, 3648, -1, 3651, 3649, 3650, -1, 3652, 3649, 3651, -1, 3653, 3649, 3652, -1, 3654, 3649, 3653, -1, 3655, 3649, 3654, -1, 3656, 3649, 3655, -1, 3647, 3649, 3641, -1, 3657, 3658, 3656, -1, 3659, 3658, 3657, -1, 3660, 3658, 3659, -1, 3661, 3658, 3660, -1, 3662, 3658, 3661, -1, 3663, 3658, 3662, -1, 3656, 3658, 3649, -1, 3644, 3658, 3663, -1, 3644, 3663, 897, -1, 3664, 3665, 3666, -1, 3666, 3667, 3664, -1, 3668, 3669, 3670, -1, 3671, 3669, 3668, -1, 3665, 3672, 3666, -1, 3673, 3669, 3671, -1, 3674, 3669, 3673, -1, 3675, 3669, 3674, -1, 3676, 3669, 3675, -1, 3666, 3677, 3667, -1, 3666, 866, 3677, -1, 883, 3678, 3679, -1, 3666, 867, 866, -1, 3679, 3678, 3676, -1, 3676, 3678, 3669, -1, 3666, 871, 867, -1, 3669, 3680, 3681, -1, 871, 3682, 873, -1, 3678, 3683, 3669, -1, 3666, 3682, 871, -1, 3683, 3684, 3669, -1, 3682, 875, 873, -1, 3669, 3684, 3680, -1, 3682, 3678, 883, -1, 3682, 877, 875, -1, 3682, 879, 877, -1, 3682, 880, 879, -1, 3682, 883, 880, -1, 3672, 3685, 3666, -1, 3685, 3686, 3666, -1, 3687, 3688, 3689, -1, 3690, 3691, 3687, -1, 3686, 3691, 3690, -1, 3687, 3691, 3688, -1, 3686, 3692, 3691, -1, 3685, 3693, 3686, -1, 3686, 3694, 3692, -1, 3686, 3695, 3694, -1, 3686, 3670, 3695, -1, 3693, 3696, 3686, -1, 3696, 3697, 3686, -1, 3686, 3698, 3670, -1, 3697, 3698, 3686, -1, 3698, 3699, 3670, -1, 3699, 3700, 3670, -1, 3700, 3668, 3670, -1, 3701, 3702, 3703, -1, 3704, 3702, 3701, -1, 3705, 3702, 3704, -1, 3706, 3702, 3705, -1, 3706, 3707, 3702, -1, 3707, 3708, 3702, -1, 3708, 691, 3702, -1, 691, 3233, 3702, -1, 1560, 1562, 3233, -1, 3233, 1558, 1560, -1, 1562, 1564, 3233, -1, 3233, 1555, 1558, -1, 1564, 1566, 3233, -1, 1566, 1568, 3233, -1, 1555, 690, 1553, -1, 691, 690, 3233, -1, 3233, 690, 1555, -1, 690, 3180, 1553, -1, 1568, 1570, 3233, -1, 690, 3178, 3180, -1, 3709, 3710, 690, -1, 690, 3176, 3178, -1, 3710, 3711, 690, -1, 690, 3174, 3176, -1, 3174, 3712, 3172, -1, 3711, 3712, 690, -1, 690, 3712, 3174, -1, 3713, 3712, 3711, -1, 3712, 3170, 3172, -1, 3712, 3168, 3170, -1, 3712, 3166, 3168, -1, 1580, 3234, 1578, -1, 1578, 3234, 1576, -1, 1576, 3234, 1574, -1, 1574, 3234, 1572, -1, 1572, 3234, 1570, -1, 3160, 3234, 3158, -1, 3158, 3234, 1580, -1, 3166, 3714, 3164, -1, 3164, 3714, 3162, -1, 3162, 3714, 3160, -1, 3712, 3714, 3166, -1, 3160, 3714, 3234, -1, 3712, 3715, 3714, -1, 3712, 3716, 3715, -1, 3712, 3717, 3716, -1, 3712, 3718, 3717, -1, 3712, 3719, 3718, -1, 3720, 3230, 3229, -1, 3721, 3230, 3720, -1, 3722, 3230, 3721, -1, 3722, 3723, 3230, -1, 3724, 3723, 3722, -1, 3725, 3723, 3724, -1, 3725, 3726, 3723, -1, 3727, 3726, 3725, -1, 3727, 3728, 3726, -1, 3729, 3728, 3727, -1, 3729, 3730, 3728, -1, 3731, 3730, 3729, -1, 3732, 1588, 3227, -1, 1588, 1590, 3227, -1, 3732, 1586, 1588, -1, 1590, 1592, 3227, -1, 3732, 1583, 1586, -1, 1592, 1594, 3227, -1, 3732, 1581, 1583, -1, 3733, 1581, 3732, -1, 1594, 1596, 3227, -1, 3733, 3157, 1581, -1, 3734, 3157, 3733, -1, 3734, 3155, 3157, -1, 3735, 3155, 3734, -1, 3735, 3153, 3155, -1, 3736, 3153, 3735, -1, 3737, 3151, 3736, -1, 3736, 3151, 3153, -1, 3738, 3149, 3737, -1, 3737, 3149, 3151, -1, 1608, 825, 1606, -1, 1606, 825, 1604, -1, 1604, 825, 1602, -1, 1602, 825, 1600, -1, 1600, 825, 1598, -1, 1598, 825, 1596, -1, 3139, 825, 3137, -1, 3137, 825, 3135, -1, 3135, 825, 1608, -1, 1596, 825, 3227, -1, 3149, 826, 3147, -1, 3147, 826, 3145, -1, 3145, 826, 3143, -1, 3139, 826, 825, -1, 3143, 826, 3141, -1, 3141, 826, 3139, -1, 3738, 826, 3149, -1, 3739, 826, 3738, -1, 3234, 3233, 1570, -1, 3712, 826, 3740, -1, 3712, 3740, 3741, -1, 3712, 3741, 3730, -1, 3712, 3730, 3719, -1, 3740, 826, 3739, -1, 3719, 3730, 3731, -1, 3110, 3611, 3104, -1, 3110, 3609, 3611, -1, 3742, 683, 3743, -1, 3743, 685, 3744, -1, 683, 685, 3743, -1, 3745, 681, 3742, -1, 3742, 681, 683, -1, 3744, 687, 3746, -1, 685, 687, 3744, -1, 3747, 676, 3745, -1, 3745, 676, 681, -1, 3748, 677, 3747, -1, 3702, 677, 3748, -1, 3747, 677, 676, -1, 3233, 3236, 3702, -1, 3702, 3236, 677, -1, 689, 836, 3746, -1, 689, 3746, 687, -1, 3749, 653, 3750, -1, 3750, 653, 3751, -1, 3751, 653, 3752, -1, 3752, 653, 3753, -1, 3753, 653, 3754, -1, 3754, 653, 3755, -1, 3755, 653, 3756, -1, 3756, 653, 1263, -1, 3757, 653, 3758, -1, 3758, 653, 3749, -1, 1263, 653, 3215, -1, 3759, 653, 3760, -1, 3760, 653, 3757, -1, 1283, 1281, 3217, -1, 3217, 1285, 1283, -1, 1281, 1279, 3217, -1, 3761, 1287, 3217, -1, 3217, 1287, 1285, -1, 3761, 1288, 1287, -1, 3761, 3762, 1288, -1, 3761, 3763, 3762, -1, 3764, 3765, 3761, -1, 3761, 3765, 3763, -1, 3758, 3766, 3767, -1, 3767, 3766, 3764, -1, 3764, 3766, 3765, -1, 3758, 3749, 3766, -1, 1265, 3215, 1267, -1, 1267, 3215, 1269, -1, 1269, 3215, 1271, -1, 1271, 3215, 1273, -1, 1273, 3215, 1275, -1, 1275, 3215, 1277, -1, 1277, 3215, 1279, -1, 1279, 3215, 3217, -1, 1265, 1263, 3215, -1, 1499, 1523, 3226, -1, 3226, 1497, 1499, -1, 1523, 1521, 3226, -1, 3226, 1500, 1497, -1, 1521, 1519, 3226, -1, 3226, 1502, 1500, -1, 1519, 1518, 3226, -1, 3226, 3768, 1502, -1, 3226, 3769, 3768, -1, 1518, 3228, 3226, -1, 1509, 3228, 1511, -1, 1511, 3228, 1517, -1, 1517, 3228, 1518, -1, 3226, 3770, 3769, -1, 3769, 3770, 3771, -1, 3771, 3770, 3772, -1, 3772, 3770, 3773, -1, 3773, 3770, 3774, -1, 3774, 3770, 3775, -1, 3775, 3770, 3776, -1, 3776, 3770, 3777, -1, 1509, 3778, 3228, -1, 1503, 3778, 1504, -1, 1504, 3778, 1507, -1, 1507, 3778, 1509, -1, 1503, 3779, 3778, -1, 3780, 3779, 1503, -1, 3781, 3782, 3780, -1, 3780, 3782, 3779, -1, 3783, 3784, 3781, -1, 3781, 3784, 3782, -1, 3777, 3785, 3783, -1, 3783, 3785, 3784, -1, 3770, 3786, 3777, -1, 3777, 3786, 3785, -1, 3770, 3787, 3786, -1, 3770, 3788, 3787, -1, 677, 3789, 678, -1, 677, 3790, 3789, -1, 677, 3791, 3790, -1, 677, 3792, 3791, -1, 677, 3793, 3792, -1, 677, 3794, 3793, -1, 677, 3795, 3794, -1, 677, 3796, 3795, -1, 677, 3236, 3796, -1, 1545, 1543, 3235, -1, 3235, 1547, 1545, -1, 1543, 1541, 3235, -1, 3235, 1549, 1547, -1, 1541, 1539, 3236, -1, 3231, 3797, 3232, -1, 3235, 1552, 1549, -1, 3231, 3798, 3797, -1, 1539, 1537, 3236, -1, 3235, 3799, 1552, -1, 3231, 3800, 3798, -1, 3801, 3800, 3231, -1, 1537, 1535, 3236, -1, 3235, 3802, 3799, -1, 3801, 3803, 3800, -1, 1535, 1533, 3236, -1, 3801, 3804, 3803, -1, 3805, 3804, 3801, -1, 1533, 1531, 3236, -1, 3806, 3807, 3805, -1, 3805, 3807, 3804, -1, 3808, 3809, 3806, -1, 3806, 3809, 3807, -1, 1531, 1529, 3236, -1, 3802, 3810, 3811, -1, 3811, 3810, 3812, -1, 3235, 3810, 3802, -1, 3810, 3813, 3812, -1, 3808, 3814, 3809, -1, 1529, 1526, 3236, -1, 3236, 3815, 3796, -1, 1526, 3815, 3236, -1, 3816, 3815, 3817, -1, 3817, 3815, 3818, -1, 3818, 3815, 1525, -1, 1525, 3815, 1526, -1, 3815, 3819, 3820, -1, 3821, 3819, 3822, -1, 3822, 3819, 3823, -1, 3823, 3819, 3824, -1, 3824, 3819, 3825, -1, 3825, 3819, 3810, -1, 3810, 3819, 3813, -1, 3816, 3819, 3815, -1, 3813, 3819, 3826, -1, 3826, 3819, 3827, -1, 3827, 3819, 3828, -1, 3828, 3819, 3829, -1, 3829, 3819, 3816, -1, 3819, 3830, 3820, -1, 3831, 3832, 3819, -1, 3819, 3832, 3830, -1, 3770, 3819, 3833, -1, 3770, 3833, 3788, -1, 3833, 3819, 3834, -1, 3834, 3819, 3808, -1, 3808, 3819, 3821, -1, 3808, 3821, 3814, -1, 3236, 3235, 1541, -1, 3835, 3836, 604, -1, 3836, 3837, 604, -1, 3838, 3839, 3840, -1, 3841, 3842, 3837, -1, 604, 3842, 605, -1, 605, 3842, 3843, -1, 3837, 3842, 604, -1, 3844, 3845, 3838, -1, 3846, 3845, 3844, -1, 3838, 3845, 3839, -1, 3846, 3847, 3845, -1, 3848, 3849, 3850, -1, 3851, 3849, 3848, -1, 3852, 3849, 3851, -1, 3853, 3854, 3855, -1, 3856, 3854, 3853, -1, 3850, 3854, 3856, -1, 3849, 3854, 3850, -1, 3857, 3858, 3852, -1, 3852, 3858, 3849, -1, 3847, 3859, 3845, -1, 3845, 3859, 3860, -1, 3860, 3859, 3861, -1, 3859, 3862, 3861, -1, 3854, 3863, 3855, -1, 3857, 3864, 3858, -1, 3859, 3865, 3862, -1, 3863, 3866, 3855, -1, 3857, 3867, 3864, -1, 3866, 3868, 3855, -1, 3868, 3869, 3855, -1, 3870, 3871, 3872, -1, 3873, 3871, 3874, -1, 3874, 3871, 3875, -1, 3875, 3871, 3870, -1, 3869, 3876, 3877, -1, 3872, 3871, 3878, -1, 3873, 3879, 3871, -1, 3880, 3879, 3873, -1, 3868, 3881, 3869, -1, 3880, 3882, 3879, -1, 3881, 3883, 3869, -1, 3869, 3878, 3876, -1, 3884, 3878, 3885, -1, 3876, 3878, 3884, -1, 3883, 3886, 3869, -1, 3869, 3886, 3878, -1, 3857, 3887, 3867, -1, 3888, 3843, 3889, -1, 3886, 3890, 3878, -1, 3891, 3843, 3888, -1, 3892, 3843, 3891, -1, 3893, 605, 3892, -1, 3882, 605, 3893, -1, 3892, 605, 3843, -1, 3859, 605, 3865, -1, 3865, 605, 3880, -1, 3880, 605, 3882, -1, 3857, 3838, 3887, -1, 3887, 3838, 3894, -1, 3890, 3895, 3878, -1, 3896, 3897, 604, -1, 3838, 3840, 3894, -1, 3895, 3872, 3878, -1, 3897, 3835, 604, -1, 3898, 3899, 3900, -1, 3901, 3899, 3898, -1, 865, 3902, 864, -1, 3903, 3902, 865, -1, 3904, 3905, 3906, -1, 3905, 3907, 3906, -1, 3905, 3908, 3907, -1, 3908, 3909, 3907, -1, 3909, 3910, 3907, -1, 3911, 3912, 3913, -1, 3911, 3914, 3912, -1, 3915, 424, 423, -1, 3916, 3915, 423, -1, 3917, 3918, 437, -1, 3919, 3918, 3917, -1, 3920, 731, 3921, -1, 3922, 731, 3920, -1, 3923, 3924, 450, -1, 3925, 3924, 3923, -1, 3926, 3927, 3928, -1, 3926, 3929, 3927, -1, 3930, 393, 3931, -1, 3931, 393, 3932, -1, 3933, 3934, 463, -1, 3935, 3934, 3933, -1, 3936, 3937, 3938, -1, 3936, 3939, 3937, -1, 3940, 340, 3941, -1, 3941, 340, 3942, -1, 3943, 3944, 476, -1, 3945, 3944, 3943, -1, 3946, 3947, 3948, -1, 3946, 3949, 3947, -1, 3950, 287, 3951, -1, 3951, 287, 3952, -1, 3953, 3954, 489, -1, 3955, 3954, 3953, -1, 3956, 3957, 3958, -1, 3956, 3959, 3957, -1, 3960, 234, 3961, -1, 3961, 234, 3962, -1, 3963, 3964, 502, -1, 3965, 3964, 3963, -1, 3966, 3967, 3968, -1, 3966, 3969, 3967, -1, 3970, 181, 3971, -1, 3971, 181, 3972, -1, 3973, 3974, 594, -1, 3975, 3974, 3973, -1, 3976, 3977, 3978, -1, 3976, 3979, 3977, -1, 3980, 558, 3981, -1, 3981, 558, 3982, -1, 3983, 3984, 515, -1, 3985, 3984, 3983, -1, 3986, 3987, 3988, -1, 3986, 3989, 3987, -1, 3990, 57, 3991, -1, 3991, 57, 3992, -1, 3993, 3994, 528, -1, 3995, 3994, 3993, -1, 3996, 3997, 3998, -1, 3996, 3999, 3997, -1, 4000, 128, 4001, -1, 4001, 128, 4002, -1, 3605, 632, 3274, -1, 3605, 631, 632, -1, 3605, 626, 631, -1, 3605, 623, 626, -1, 3605, 4003, 623, -1, 3605, 4004, 4003, -1, 4004, 4005, 4003, -1, 4004, 4006, 4005, -1, 4007, 4008, 4009, -1, 4010, 4011, 4012, -1, 4013, 4011, 4010, -1, 4008, 4011, 4013, -1, 4007, 4011, 4008, -1, 4011, 4014, 4012, -1, 4015, 4016, 4017, -1, 4016, 4018, 4017, -1, 4018, 4019, 4017, -1, 4019, 4020, 4017, -1, 4020, 4021, 4017, -1, 4021, 4022, 4017, -1, 4023, 2065, 4024, -1, 4023, 4025, 2065, -1, 4025, 4026, 2065, -1, 2065, 4027, 2064, -1, 2065, 4028, 4027, -1, 4029, 4030, 4026, -1, 4026, 4030, 2065, -1, 2065, 4030, 4028, -1, 4029, 4031, 4030, -1, 4029, 4032, 4031, -1, 4017, 4033, 4029, -1, 4022, 4033, 4017, -1, 4029, 4034, 4032, -1, 4033, 4035, 4029, -1, 4029, 4035, 4034, -1, 4036, 4037, 4038, -1, 4039, 4036, 4038, -1, 4040, 3059, 4041, -1, 4040, 4041, 4039, -1, 4040, 4039, 4038, -1, 4042, 4043, 4044, -1, 4045, 4044, 4046, -1, 4045, 4042, 4044, -1, 4047, 4048, 4049, -1, 4047, 4049, 4050, -1, 4051, 4047, 4050, -1, 3264, 3872, 3261, -1, 3872, 3895, 3261, -1, 3261, 3890, 3258, -1, 3895, 3890, 3261, -1, 3258, 3886, 3256, -1, 3890, 3886, 3258, -1, 3256, 3883, 3257, -1, 3886, 3883, 3256, -1, 3257, 3881, 3259, -1, 3883, 3881, 3257, -1, 3259, 3868, 3262, -1, 3881, 3868, 3259, -1, 3262, 3866, 3265, -1, 3868, 3866, 3262, -1, 3265, 3863, 3272, -1, 3866, 3863, 3265, -1, 3272, 3854, 3280, -1, 3863, 3854, 3272, -1, 3280, 3849, 3286, -1, 3854, 3849, 3280, -1, 3286, 3858, 3239, -1, 3849, 3858, 3286, -1, 3239, 3864, 3237, -1, 3237, 3864, 3240, -1, 3858, 3864, 3239, -1, 3864, 3867, 3240, -1, 3264, 3870, 3872, -1, 3288, 3870, 3264, -1, 3887, 3894, 3260, -1, 3260, 3894, 3267, -1, 3267, 3894, 3268, -1, 3268, 3840, 3269, -1, 3894, 3840, 3268, -1, 3269, 3839, 3270, -1, 3840, 3839, 3269, -1, 3270, 3845, 3271, -1, 3839, 3845, 3270, -1, 3271, 3860, 3278, -1, 3845, 3860, 3271, -1, 3278, 3861, 3276, -1, 3860, 3861, 3278, -1, 3276, 3862, 3254, -1, 3861, 3862, 3276, -1, 3254, 3865, 3252, -1, 3862, 3865, 3254, -1, 3252, 3880, 3255, -1, 3865, 3880, 3252, -1, 3255, 3873, 3250, -1, 3880, 3873, 3255, -1, 3250, 3874, 3249, -1, 3873, 3874, 3250, -1, 3249, 3875, 3288, -1, 3874, 3875, 3249, -1, 3875, 3870, 3288, -1, 3887, 3260, 3867, -1, 3867, 3260, 3240, -1, 4052, 4053, 4054, -1, 4054, 4053, 4055, -1, 4056, 4057, 4058, -1, 4059, 4057, 4056, -1, 4060, 4061, 4062, -1, 4063, 4061, 4060, -1, 4061, 4064, 4062, -1, 4065, 4066, 4067, -1, 4068, 4069, 4070, -1, 4071, 4069, 4066, -1, 4072, 4069, 4071, -1, 4070, 4069, 4072, -1, 4066, 4069, 4067, -1, 3042, 4073, 4074, -1, 4075, 3042, 4074, -1, 4076, 4077, 4078, -1, 4079, 4080, 4081, -1, 4079, 4081, 4082, -1, 4083, 4082, 4084, -1, 4083, 4079, 4082, -1, 4085, 4084, 4086, -1, 4085, 4083, 4084, -1, 4087, 4088, 4080, -1, 4087, 4080, 4079, -1, 4089, 4090, 4088, -1, 4089, 4088, 4087, -1, 4091, 4086, 4092, -1, 3576, 4093, 4094, -1, 3576, 4094, 4095, -1, 3576, 4095, 4096, -1, 3576, 4096, 4097, -1, 3576, 4097, 4098, -1, 3576, 4098, 4099, -1, 4091, 4085, 4086, -1, 4100, 4076, 4101, -1, 4100, 4101, 4102, -1, 4103, 4091, 4092, -1, 4100, 4102, 4093, -1, 4100, 4093, 3576, -1, 4104, 3576, 4099, -1, 4105, 4090, 4089, -1, 4106, 3576, 4104, -1, 4107, 4103, 4092, -1, 4108, 3576, 4106, -1, 4109, 4107, 4092, -1, 3575, 3576, 4108, -1, 4110, 4107, 4109, -1, 4111, 3575, 4108, -1, 4100, 4077, 4076, -1, 4112, 4109, 4113, -1, 4112, 4113, 4114, -1, 4112, 4110, 4109, -1, 4115, 4112, 4114, -1, 4116, 4112, 4115, -1, 4116, 4115, 4117, -1, 4078, 4116, 4117, -1, 4118, 4116, 4078, -1, 4077, 4118, 4078, -1, 4119, 4090, 4105, -1, 4120, 4119, 4105, -1, 4121, 4122, 4119, -1, 4121, 4119, 4120, -1, 4123, 4124, 4122, -1, 4123, 4122, 4121, -1, 4125, 4124, 4123, -1, 4126, 4125, 4123, -1, 4073, 4125, 4126, -1, 4074, 4073, 4126, -1, 4127, 3400, 4128, -1, 4128, 3400, 3445, -1, 4127, 4129, 3400, -1, 4130, 1, 3, -1, 4131, 1, 4130, -1, 4132, 4133, 4134, -1, 4134, 4133, 4135, -1, 4135, 4136, 4137, -1, 4133, 4136, 4135, -1, 4137, 4138, 4139, -1, 4136, 4138, 4137, -1, 4139, 4140, 4141, -1, 4138, 4140, 4139, -1, 4141, 4142, 4143, -1, 4140, 4142, 4141, -1, 4143, 4144, 4145, -1, 4142, 4144, 4143, -1, 4145, 4130, 3, -1, 4144, 4130, 4145, -1, 4146, 4134, 4147, -1, 4132, 4134, 4146, -1, 4148, 4047, 4051, -1, 4148, 4051, 4149, -1, 4148, 4149, 4150, -1, 4151, 4150, 4152, -1, 4151, 4148, 4150, -1, 4153, 4152, 4154, -1, 4153, 4151, 4152, -1, 4155, 4154, 4156, -1, 4155, 4153, 4154, -1, 4157, 4156, 4158, -1, 4157, 4155, 4156, -1, 4159, 4158, 4046, -1, 4159, 4157, 4158, -1, 4044, 4159, 4046, -1, 4048, 4047, 4148, -1, 4160, 4148, 4151, -1, 4160, 4048, 4148, -1, 4161, 4151, 4153, -1, 4161, 4160, 4151, -1, 4162, 4153, 4155, -1, 4162, 4161, 4153, -1, 4163, 4155, 4157, -1, 4163, 4162, 4155, -1, 4164, 4157, 4159, -1, 4164, 4163, 4157, -1, 4165, 4159, 4044, -1, 4165, 4164, 4159, -1, 4043, 4165, 4044, -1, 3842, 3841, 4166, -1, 4167, 3842, 4166, -1, 4168, 4166, 4169, -1, 4168, 4169, 4170, -1, 4168, 4167, 4166, -1, 4171, 4170, 4063, -1, 4171, 4168, 4170, -1, 4060, 4171, 4063, -1, 4172, 4061, 4063, -1, 4172, 4063, 4173, -1, 4174, 4173, 4175, -1, 4174, 4172, 4173, -1, 3907, 4175, 3906, -1, 3907, 4174, 4175, -1, 4042, 4045, 4176, -1, 4177, 4042, 4176, -1, 4178, 4176, 4179, -1, 4178, 4177, 4176, -1, 4180, 4179, 4181, -1, 4180, 4178, 4179, -1, 4038, 4181, 4040, -1, 4038, 4180, 4181, -1, 4067, 4069, 4182, -1, 4182, 4183, 4184, -1, 4069, 4183, 4182, -1, 4184, 4185, 4186, -1, 4183, 4185, 4184, -1, 4185, 4187, 4186, -1, 4186, 1, 4131, -1, 4187, 1, 4186, -1, 3720, 3797, 3798, -1, 3721, 3720, 3798, -1, 3722, 3798, 3800, -1, 3722, 3721, 3798, -1, 3724, 3800, 3803, -1, 3724, 3722, 3800, -1, 3725, 3803, 3804, -1, 3725, 3724, 3803, -1, 3727, 3804, 3807, -1, 3727, 3725, 3804, -1, 3729, 3807, 3809, -1, 3729, 3727, 3807, -1, 3731, 3809, 3814, -1, 3731, 3729, 3809, -1, 3719, 3814, 3821, -1, 3719, 3731, 3814, -1, 3718, 3821, 3822, -1, 3718, 3719, 3821, -1, 3717, 3822, 3823, -1, 3717, 3718, 3822, -1, 3716, 3823, 3824, -1, 3716, 3717, 3823, -1, 3715, 3824, 3825, -1, 3715, 3716, 3824, -1, 3714, 3825, 3810, -1, 3714, 3715, 3825, -1, 3810, 3235, 3234, -1, 3714, 3810, 3234, -1, 3797, 3720, 3229, -1, 3797, 3229, 3232, -1, 3733, 3732, 3778, -1, 3733, 3778, 3779, -1, 3734, 3779, 3782, -1, 3734, 3733, 3779, -1, 3735, 3782, 3784, -1, 3735, 3734, 3782, -1, 3736, 3784, 3785, -1, 3736, 3735, 3784, -1, 3737, 3785, 3786, -1, 3737, 3736, 3785, -1, 3738, 3786, 3787, -1, 3738, 3737, 3786, -1, 3739, 3787, 3788, -1, 3739, 3738, 3787, -1, 3740, 3788, 3833, -1, 3740, 3739, 3788, -1, 3741, 3833, 3834, -1, 3741, 3740, 3833, -1, 3730, 3834, 3808, -1, 3730, 3741, 3834, -1, 3728, 3808, 3806, -1, 3728, 3730, 3808, -1, 3726, 3806, 3805, -1, 3726, 3728, 3806, -1, 3723, 3805, 3801, -1, 3723, 3726, 3805, -1, 3801, 3231, 3230, -1, 3723, 3801, 3230, -1, 3778, 3732, 3227, -1, 3778, 3227, 3228, -1, 3631, 3123, 3125, -1, 3632, 3125, 3127, -1, 3632, 3631, 3125, -1, 3634, 3127, 3129, -1, 3634, 3632, 3127, -1, 3636, 3129, 3133, -1, 3636, 3634, 3129, -1, 3623, 3133, 3131, -1, 3623, 3636, 3133, -1, 3622, 3131, 4188, -1, 3622, 3623, 3131, -1, 3619, 4188, 4189, -1, 3619, 3622, 4188, -1, 3620, 4189, 3759, -1, 3620, 3619, 4189, -1, 3629, 3759, 3760, -1, 3629, 3620, 3759, -1, 3628, 3760, 3757, -1, 3628, 3629, 3760, -1, 3627, 3757, 3758, -1, 3627, 3628, 3757, -1, 3621, 3758, 3767, -1, 3621, 3627, 3758, -1, 3616, 3767, 3764, -1, 3616, 3621, 3767, -1, 3608, 3764, 3761, -1, 3608, 3616, 3764, -1, 3761, 3217, 3216, -1, 3608, 3761, 3216, -1, 3123, 3631, 3211, -1, 3123, 3211, 3120, -1, 3119, 3121, 3210, -1, 3630, 3119, 3210, -1, 3112, 3612, 3609, -1, 3112, 3609, 3110, -1, 3612, 3112, 3116, -1, 3613, 3116, 3118, -1, 3613, 3612, 3116, -1, 3614, 3118, 3101, -1, 3614, 3613, 3118, -1, 3615, 3101, 3100, -1, 3615, 3614, 3101, -1, 3617, 3100, 3099, -1, 3617, 3615, 3100, -1, 3618, 3099, 4190, -1, 3618, 3617, 3099, -1, 3624, 4190, 4191, -1, 3624, 3618, 4190, -1, 3625, 4191, 3130, -1, 3625, 3624, 4191, -1, 3626, 3130, 3132, -1, 3626, 3625, 3130, -1, 3638, 3132, 3128, -1, 3638, 3626, 3132, -1, 3637, 3128, 3126, -1, 3637, 3638, 3128, -1, 3635, 3126, 3124, -1, 3635, 3637, 3126, -1, 3633, 3124, 3122, -1, 3633, 3635, 3124, -1, 3630, 3122, 3119, -1, 3630, 3633, 3122, -1, 3098, 3104, 3611, -1, 3610, 4192, 4193, -1, 3610, 4193, 4194, -1, 3610, 4194, 3098, -1, 3610, 3098, 3611, -1, 4195, 4192, 3610, -1, 1512, 810, 809, -1, 1510, 1512, 809, -1, 4196, 1510, 809, -1, 1508, 1510, 4196, -1, 766, 4197, 4198, -1, 766, 767, 4197, -1, 4199, 4200, 1505, -1, 4199, 4201, 4200, -1, 4199, 4198, 4201, -1, 4199, 1506, 1508, -1, 4199, 1505, 1506, -1, 4199, 766, 4198, -1, 4199, 1508, 4196, -1, 4202, 4203, 4204, -1, 4202, 4205, 4203, -1, 4206, 4207, 4208, -1, 4209, 4210, 4211, -1, 4209, 4211, 4212, -1, 4209, 4212, 4213, -1, 4209, 4213, 4214, -1, 4209, 4214, 4207, -1, 4209, 4207, 4206, -1, 4205, 4202, 4215, -1, 4202, 4216, 4215, -1, 4215, 4217, 4218, -1, 4216, 4217, 4215, -1, 4218, 4219, 4220, -1, 4217, 4219, 4218, -1, 4220, 779, 1829, -1, 4219, 779, 4220, -1, 4221, 4196, 809, -1, 4221, 809, 4222, -1, 4223, 4221, 4222, -1, 4224, 4222, 4225, -1, 4224, 4223, 4222, -1, 4226, 4225, 4227, -1, 4226, 4224, 4225, -1, 4203, 4227, 4204, -1, 4203, 4226, 4227, -1, 766, 4199, 4228, -1, 4229, 4228, 4230, -1, 4229, 766, 4228, -1, 4231, 4230, 4232, -1, 4231, 4232, 4233, -1, 4231, 4229, 4230, -1, 4207, 4233, 4208, -1, 4207, 4231, 4233, -1, 4209, 4234, 4210, -1, 4210, 4234, 4235, -1, 4235, 4236, 4237, -1, 4234, 4236, 4235, -1, 4237, 4238, 4239, -1, 4236, 4238, 4237, -1, 4239, 2019, 1737, -1, 4238, 2019, 4239, -1, 1349, 1348, 4240, -1, 1349, 4240, 4241, -1, 4242, 1528, 4243, -1, 1546, 4244, 4245, -1, 1544, 4245, 4246, -1, 1544, 1546, 4245, -1, 1401, 1349, 4241, -1, 1401, 4241, 4247, -1, 1548, 4248, 4244, -1, 1548, 4244, 1546, -1, 1542, 4246, 4249, -1, 1542, 1544, 4246, -1, 1550, 4250, 4248, -1, 1550, 4248, 1548, -1, 1540, 4249, 4251, -1, 1540, 1542, 4249, -1, 1355, 4252, 1527, -1, 1551, 1379, 1378, -1, 1355, 1527, 1528, -1, 1551, 1378, 4250, -1, 1551, 4250, 1550, -1, 1355, 1528, 4242, -1, 1397, 1401, 4247, -1, 1397, 4247, 4253, -1, 1397, 4253, 4254, -1, 1538, 1540, 4251, -1, 1354, 4252, 1355, -1, 1392, 1397, 4254, -1, 1392, 4254, 4255, -1, 4256, 1379, 1551, -1, 1369, 4257, 4252, -1, 1369, 4252, 1354, -1, 1373, 1379, 4256, -1, 1536, 4251, 4258, -1, 1387, 4255, 4259, -1, 1387, 1392, 4255, -1, 1536, 1538, 4251, -1, 1382, 4259, 4257, -1, 1382, 1387, 4259, -1, 1382, 4257, 1369, -1, 4260, 1373, 4256, -1, 1534, 4258, 4261, -1, 1534, 1536, 4258, -1, 1367, 1373, 4260, -1, 4262, 1367, 4260, -1, 1532, 1534, 4261, -1, 4263, 1532, 4261, -1, 1348, 1367, 4262, -1, 1348, 4262, 4240, -1, 1530, 1532, 4263, -1, 4243, 1530, 4263, -1, 1528, 1530, 4243, -1, 1552, 3799, 1551, -1, 1551, 3799, 4256, -1, 4256, 3799, 4260, -1, 4260, 3802, 4262, -1, 3799, 3802, 4260, -1, 4262, 3811, 4240, -1, 3802, 3811, 4262, -1, 4240, 3812, 4241, -1, 3811, 3812, 4240, -1, 4241, 3813, 4247, -1, 3812, 3813, 4241, -1, 4247, 3826, 4253, -1, 3813, 3826, 4247, -1, 4253, 3827, 4254, -1, 3826, 3827, 4253, -1, 4254, 3828, 4255, -1, 3827, 3828, 4254, -1, 4255, 3829, 4259, -1, 3828, 3829, 4255, -1, 4259, 3816, 4257, -1, 3829, 3816, 4259, -1, 4257, 3817, 4252, -1, 3816, 3817, 4257, -1, 4252, 3818, 1527, -1, 3817, 3818, 4252, -1, 3818, 1525, 1527, -1, 1524, 1520, 1522, -1, 1520, 1501, 1513, -1, 1496, 1501, 1524, -1, 1498, 1501, 1496, -1, 1524, 1501, 1520, -1, 4264, 4265, 1501, -1, 4265, 4266, 1501, -1, 4267, 4268, 4266, -1, 1501, 4268, 1513, -1, 4266, 4268, 1501, -1, 4268, 3185, 1513, -1, 1502, 3768, 1501, -1, 1501, 3768, 4264, -1, 4264, 3769, 4265, -1, 3768, 3769, 4264, -1, 4265, 3771, 4266, -1, 3769, 3771, 4265, -1, 4266, 3772, 4267, -1, 3771, 3772, 4266, -1, 3184, 3185, 4269, -1, 3185, 4270, 4269, -1, 3185, 755, 4270, -1, 3185, 756, 755, -1, 3185, 759, 756, -1, 4267, 3773, 4268, -1, 3772, 3773, 4267, -1, 4268, 3774, 3185, -1, 3773, 3774, 4268, -1, 763, 3775, 765, -1, 761, 3775, 763, -1, 759, 3775, 761, -1, 3185, 3775, 759, -1, 3774, 3775, 3185, -1, 765, 3776, 767, -1, 767, 3776, 4197, -1, 3775, 3776, 765, -1, 4197, 3777, 4198, -1, 3776, 3777, 4197, -1, 4198, 3783, 4201, -1, 3777, 3783, 4198, -1, 4201, 3781, 4200, -1, 3783, 3781, 4201, -1, 3781, 3780, 4200, -1, 4200, 3780, 1505, -1, 3780, 1503, 1505, -1, 4271, 4272, 4273, -1, 4274, 1418, 1420, -1, 4274, 1420, 1472, -1, 4274, 4271, 4273, -1, 4274, 4273, 1418, -1, 4274, 1472, 4271, -1, 4275, 4276, 4277, -1, 4275, 4277, 1398, -1, 4275, 4278, 4276, -1, 4279, 1398, 1464, -1, 4279, 1464, 1414, -1, 4279, 1414, 1415, -1, 4279, 4278, 4275, -1, 4279, 4275, 1398, -1, 4279, 1415, 4278, -1, 4273, 4272, 4280, -1, 4273, 1430, 1418, -1, 4281, 4280, 4282, -1, 4281, 4282, 4283, -1, 4281, 1440, 1435, -1, 4281, 1435, 1430, -1, 4281, 4273, 4280, -1, 4281, 1430, 4273, -1, 4284, 4283, 4285, -1, 4284, 1446, 1440, -1, 4284, 4281, 4283, -1, 4284, 1440, 4281, -1, 4286, 4285, 4287, -1, 4286, 4287, 4288, -1, 4286, 1455, 1450, -1, 4286, 1450, 1446, -1, 4286, 1446, 4284, -1, 4286, 4284, 4285, -1, 4289, 4288, 4290, -1, 4289, 4290, 4291, -1, 4289, 1465, 1460, -1, 4289, 1460, 1455, -1, 4289, 4286, 4288, -1, 4289, 1455, 4286, -1, 4278, 4291, 4276, -1, 4278, 1415, 1465, -1, 4278, 1465, 4289, -1, 4278, 4289, 4291, -1, 4271, 1472, 1402, -1, 4271, 1402, 4292, -1, 4271, 4292, 4272, -1, 1809, 4293, 1424, -1, 1485, 4294, 1475, -1, 1475, 4294, 4295, -1, 1482, 4296, 1413, -1, 4297, 4294, 4298, -1, 1411, 4296, 4299, -1, 4295, 4294, 4297, -1, 4299, 4300, 4301, -1, 4301, 4300, 4302, -1, 1424, 4303, 1469, -1, 4298, 4303, 4304, -1, 4304, 4303, 4293, -1, 1891, 4305, 1893, -1, 4293, 4303, 1424, -1, 1472, 4306, 1485, -1, 4302, 4305, 1891, -1, 1469, 4306, 1473, -1, 1473, 4306, 1472, -1, 1485, 4306, 4294, -1, 1486, 4307, 1481, -1, 4303, 4306, 1469, -1, 4294, 4306, 4298, -1, 4298, 4306, 4303, -1, 1481, 4307, 4296, -1, 4296, 4307, 4299, -1, 4299, 4307, 4300, -1, 4300, 4308, 4302, -1, 4302, 4308, 4305, -1, 1893, 4309, 1894, -1, 4305, 4309, 1893, -1, 1489, 4310, 1486, -1, 1464, 1482, 1413, -1, 4307, 4310, 4300, -1, 4300, 4310, 4308, -1, 1486, 4310, 4307, -1, 4305, 4311, 4309, -1, 4308, 4311, 4305, -1, 1894, 4312, 1901, -1, 4309, 4312, 1894, -1, 1488, 4313, 1489, -1, 4310, 4313, 4308, -1, 1489, 4313, 4310, -1, 4308, 4313, 4311, -1, 4311, 4314, 4309, -1, 4309, 4314, 4312, -1, 1901, 4315, 1956, -1, 4312, 4315, 1901, -1, 4311, 4316, 4314, -1, 1492, 4316, 1488, -1, 4313, 4316, 4311, -1, 1488, 4316, 4313, -1, 4312, 4317, 4315, -1, 4314, 4317, 4312, -1, 1956, 4318, 1865, -1, 4315, 4318, 1956, -1, 1491, 4319, 1492, -1, 1492, 4319, 4316, -1, 4314, 4319, 4317, -1, 4316, 4319, 4314, -1, 4315, 4320, 4318, -1, 4317, 4320, 4315, -1, 1865, 4321, 1863, -1, 4318, 4321, 1865, -1, 1494, 4322, 1491, -1, 4319, 4322, 4317, -1, 4317, 4322, 4320, -1, 1491, 4322, 4319, -1, 4320, 4323, 4318, -1, 4318, 4323, 4321, -1, 1863, 4324, 1833, -1, 4321, 4324, 1863, -1, 1495, 4325, 1494, -1, 4320, 4325, 4323, -1, 1494, 4325, 4322, -1, 4322, 4325, 4320, -1, 4323, 4326, 4321, -1, 1809, 1424, 1426, -1, 4321, 4326, 4324, -1, 1833, 4327, 1817, -1, 4324, 4327, 1833, -1, 1476, 4328, 1495, -1, 1495, 4328, 4325, -1, 4323, 4328, 4326, -1, 4325, 4328, 4323, -1, 4326, 4297, 4324, -1, 4324, 4297, 4327, -1, 1817, 4304, 1811, -1, 4327, 4304, 1817, -1, 1471, 4301, 1470, -1, 1475, 4295, 1476, -1, 1476, 4295, 4328, -1, 1470, 4301, 1892, -1, 4326, 4295, 4297, -1, 4328, 4295, 4326, -1, 1411, 4299, 1471, -1, 4297, 4298, 4327, -1, 4327, 4298, 4304, -1, 1471, 4299, 4301, -1, 1892, 4302, 1891, -1, 1811, 4293, 1809, -1, 4301, 4302, 1892, -1, 1481, 4296, 1482, -1, 4304, 4293, 1811, -1, 1413, 4296, 1411, -1, 4329, 4292, 1402, -1, 4330, 1371, 1361, -1, 4329, 1402, 1335, -1, 4329, 4331, 4292, -1, 4330, 1361, 4332, -1, 4333, 4334, 4331, -1, 4335, 4291, 4290, -1, 1361, 1398, 4277, -1, 4333, 4336, 4334, -1, 4335, 4337, 4291, -1, 4338, 4243, 4263, -1, 4338, 4263, 4339, -1, 4338, 4340, 4336, -1, 4338, 4339, 4340, -1, 4341, 1335, 1360, -1, 4342, 4330, 4332, -1, 4342, 4332, 4337, -1, 4341, 4329, 1335, -1, 4343, 1377, 1371, -1, 4341, 4331, 4329, -1, 4343, 1378, 1377, -1, 4341, 4333, 4331, -1, 4343, 4250, 1378, -1, 4343, 4248, 4250, -1, 4344, 4242, 4243, -1, 4344, 4243, 4338, -1, 4344, 4336, 4333, -1, 4343, 1371, 4330, -1, 4344, 4338, 4336, -1, 4345, 4290, 4288, -1, 4346, 1360, 1359, -1, 4346, 1359, 1355, -1, 4346, 1355, 4242, -1, 4346, 4242, 4344, -1, 4346, 4341, 1360, -1, 4345, 4335, 4290, -1, 4346, 4333, 4341, -1, 4347, 4337, 4335, -1, 4346, 4344, 4333, -1, 4347, 4342, 4337, -1, 4348, 4244, 4248, -1, 4348, 4330, 4342, -1, 4348, 4248, 4343, -1, 4348, 4343, 4330, -1, 4349, 4288, 4287, -1, 4349, 4345, 4288, -1, 4350, 4347, 4335, -1, 4350, 4335, 4345, -1, 4351, 4245, 4244, -1, 4351, 4342, 4347, -1, 4351, 4348, 4342, -1, 4351, 4244, 4348, -1, 4352, 4287, 4285, -1, 4352, 4349, 4287, -1, 4353, 4350, 4345, -1, 4353, 4345, 4349, -1, 4354, 4246, 4245, -1, 4354, 4347, 4350, -1, 4354, 4245, 4351, -1, 4354, 4351, 4347, -1, 4355, 4285, 4283, -1, 4355, 4352, 4285, -1, 4356, 4353, 4349, -1, 4356, 4349, 4352, -1, 4357, 4354, 4350, -1, 4357, 4249, 4246, -1, 4357, 4350, 4353, -1, 4357, 4246, 4354, -1, 4358, 4283, 4282, -1, 4358, 4355, 4283, -1, 4359, 4352, 4355, -1, 4359, 4356, 4352, -1, 4360, 4353, 4356, -1, 4360, 4249, 4357, -1, 4360, 4251, 4249, -1, 4360, 4357, 4353, -1, 4361, 4282, 4280, -1, 4361, 4358, 4282, -1, 4362, 4355, 4358, -1, 4362, 4359, 4355, -1, 4363, 4360, 4356, -1, 4363, 4251, 4360, -1, 4363, 4258, 4251, -1, 4363, 4356, 4359, -1, 4334, 4280, 4272, -1, 4334, 4361, 4280, -1, 4340, 4358, 4361, -1, 4340, 4362, 4358, -1, 4364, 4359, 4362, -1, 4364, 4363, 4359, -1, 4364, 4261, 4258, -1, 4364, 4258, 4363, -1, 4331, 4272, 4292, -1, 4331, 4334, 4272, -1, 4332, 4277, 4276, -1, 4332, 1361, 4277, -1, 4336, 4340, 4361, -1, 4336, 4361, 4334, -1, 4337, 4276, 4291, -1, 4339, 4364, 4362, -1, 4339, 4263, 4261, -1, 4339, 4362, 4340, -1, 4339, 4261, 4364, -1, 4337, 4332, 4276, -1, 1603, 1601, 4365, -1, 4366, 1603, 4365, -1, 1577, 1575, 4367, -1, 4366, 1605, 1603, -1, 882, 3156, 3154, -1, 882, 3154, 3152, -1, 882, 3152, 3150, -1, 4368, 4369, 3175, -1, 882, 3150, 3148, -1, 4368, 3175, 3173, -1, 882, 4368, 3156, -1, 4368, 3173, 3171, -1, 1559, 4370, 4371, -1, 3169, 4368, 3171, -1, 1561, 4371, 4372, -1, 4373, 1607, 1605, -1, 4373, 1605, 4366, -1, 3167, 4368, 3169, -1, 1561, 1559, 4371, -1, 1557, 4374, 4370, -1, 1557, 4370, 1559, -1, 3165, 4368, 3167, -1, 1563, 4372, 4375, -1, 1563, 1561, 4372, -1, 1587, 3159, 1579, -1, 1556, 4376, 4374, -1, 881, 882, 3148, -1, 881, 3148, 3146, -1, 1589, 1579, 1577, -1, 1589, 1587, 1579, -1, 1556, 4374, 1557, -1, 1565, 1563, 4375, -1, 1565, 4375, 4377, -1, 868, 1607, 4373, -1, 1585, 3161, 3159, -1, 1585, 3159, 1587, -1, 1554, 4378, 4376, -1, 868, 3134, 1607, -1, 1554, 4376, 1556, -1, 878, 881, 3146, -1, 878, 3146, 3144, -1, 1584, 3163, 3161, -1, 1567, 4377, 4379, -1, 1584, 3161, 1585, -1, 869, 3134, 868, -1, 869, 3136, 3134, -1, 1567, 1565, 4377, -1, 876, 878, 3144, -1, 1582, 3165, 3163, -1, 876, 3144, 3142, -1, 1582, 3163, 1584, -1, 3181, 4380, 4378, -1, 4381, 1577, 4367, -1, 870, 3136, 869, -1, 4381, 1593, 1591, -1, 4381, 1591, 1589, -1, 3181, 4378, 1554, -1, 870, 3138, 3136, -1, 4381, 1589, 1577, -1, 1569, 4379, 4367, -1, 874, 876, 3142, -1, 874, 3142, 3140, -1, 1595, 1593, 4381, -1, 1569, 1567, 4379, -1, 872, 3138, 870, -1, 3179, 4380, 3181, -1, 872, 874, 3140, -1, 3156, 3165, 1582, -1, 872, 3140, 3138, -1, 3156, 4368, 3165, -1, 1571, 1569, 4367, -1, 1597, 1595, 4381, -1, 4382, 4380, 3179, -1, 3177, 4382, 3179, -1, 1599, 4381, 4383, -1, 1599, 1597, 4381, -1, 1573, 1571, 4367, -1, 1601, 1599, 4383, -1, 4365, 1601, 4383, -1, 4369, 4382, 3177, -1, 4369, 3177, 3175, -1, 1575, 1573, 4367, -1, 4384, 1238, 1240, -1, 1179, 1178, 4385, -1, 4386, 1179, 4385, -1, 1254, 4387, 4388, -1, 1252, 4388, 4389, -1, 4390, 1236, 1238, -1, 1252, 1254, 4388, -1, 4390, 1238, 4384, -1, 1256, 4391, 4387, -1, 1256, 4387, 1254, -1, 1250, 4389, 4392, -1, 1231, 1179, 4386, -1, 1231, 4386, 4393, -1, 1250, 1252, 4389, -1, 1258, 4391, 1256, -1, 1248, 4392, 4394, -1, 1248, 1250, 4392, -1, 1261, 1209, 1208, -1, 1261, 1208, 4391, -1, 1261, 4391, 1258, -1, 1201, 1236, 4390, -1, 1246, 4394, 4395, -1, 1201, 4396, 1234, -1, 1201, 1234, 1236, -1, 1227, 4393, 4397, -1, 1246, 1248, 4394, -1, 1227, 1231, 4393, -1, 1189, 4396, 1201, -1, 4398, 1209, 1261, -1, 1222, 4397, 4399, -1, 1222, 1227, 4397, -1, 1244, 4395, 4400, -1, 1198, 4401, 4396, -1, 1198, 4396, 1189, -1, 1217, 4399, 4402, -1, 1217, 1222, 4399, -1, 1244, 1246, 4395, -1, 4403, 1203, 1209, -1, 1212, 4402, 4401, -1, 1212, 1217, 4402, -1, 4403, 1209, 4398, -1, 1212, 4401, 1198, -1, 1242, 4400, 4404, -1, 1242, 1244, 4400, -1, 4405, 1196, 1203, -1, 4405, 1203, 4403, -1, 4406, 1242, 4404, -1, 4406, 1240, 1242, -1, 4407, 1196, 4405, -1, 1178, 1196, 4407, -1, 4385, 1178, 4407, -1, 4384, 1240, 4406, -1, 4408, 1266, 1268, -1, 4408, 1268, 4409, -1, 1032, 1031, 4410, -1, 1032, 4410, 4411, -1, 4412, 1266, 4408, -1, 4412, 1262, 1264, -1, 1282, 4413, 4414, -1, 4412, 1264, 1266, -1, 1280, 4414, 4415, -1, 1280, 1282, 4414, -1, 1284, 4416, 4413, -1, 1284, 4413, 1282, -1, 1278, 4415, 4417, -1, 1278, 1280, 4415, -1, 1090, 1032, 4411, -1, 1090, 4411, 4418, -1, 1286, 4419, 4416, -1, 1286, 4416, 1284, -1, 1276, 4417, 4420, -1, 1276, 1278, 4417, -1, 1289, 1067, 1092, -1, 1289, 1092, 4419, -1, 1289, 4419, 1286, -1, 1274, 1276, 4420, -1, 4421, 1274, 4420, -1, 4422, 1067, 1289, -1, 1050, 1262, 4412, -1, 1087, 4418, 4423, -1, 1087, 1090, 4418, -1, 1049, 1262, 1050, -1, 1272, 1274, 4421, -1, 4424, 1062, 1067, -1, 1049, 4425, 1262, -1, 4424, 1067, 4422, -1, 1082, 4423, 4426, -1, 4427, 1272, 4421, -1, 1270, 1272, 4427, -1, 1082, 1087, 4423, -1, 1064, 4428, 4429, -1, 1064, 4429, 4425, -1, 1064, 4425, 1049, -1, 1077, 4426, 4430, -1, 1055, 1062, 4424, -1, 1077, 1082, 4426, -1, 4431, 1055, 4424, -1, 1072, 1077, 4430, -1, 1072, 4430, 4428, -1, 1072, 4428, 1064, -1, 4409, 1268, 1270, -1, 4409, 1270, 4427, -1, 1031, 1055, 4431, -1, 1031, 4431, 4410, -1, 4432, 1123, 1105, -1, 4432, 1105, 1129, -1, 4432, 4433, 4434, -1, 4432, 4434, 1123, -1, 4432, 1129, 4433, -1, 4435, 4436, 4437, -1, 4435, 4437, 1228, -1, 4435, 4438, 4436, -1, 4439, 1228, 1120, -1, 4439, 1120, 1102, -1, 4439, 1102, 1104, -1, 4439, 4438, 4435, -1, 4439, 4435, 1228, -1, 4439, 1104, 4438, -1, 4434, 4440, 4441, -1, 4434, 1121, 1123, -1, 4442, 4441, 4443, -1, 4442, 4443, 4444, -1, 4442, 1133, 1127, -1, 4442, 1127, 1121, -1, 4442, 4434, 4441, -1, 4442, 1121, 4434, -1, 4445, 4444, 4446, -1, 4445, 4446, 4447, -1, 4445, 1138, 1133, -1, 4445, 4442, 4444, -1, 4445, 1133, 4442, -1, 4448, 4447, 4449, -1, 4448, 1148, 1144, -1, 4448, 1144, 1138, -1, 4448, 1138, 4445, -1, 4448, 4445, 4447, -1, 4450, 4449, 4451, -1, 4450, 4451, 4452, -1, 4450, 1159, 1153, -1, 4450, 1153, 1148, -1, 4450, 4448, 4449, -1, 4450, 1148, 4448, -1, 4438, 4452, 4436, -1, 4438, 1104, 1159, -1, 4438, 4450, 4452, -1, 4438, 1159, 4450, -1, 4433, 1129, 1232, -1, 4433, 1232, 4453, -1, 4433, 4453, 4440, -1, 4433, 4440, 4434, -1, 4454, 973, 975, -1, 4454, 975, 4455, -1, 4454, 4455, 4456, -1, 4457, 1042, 4458, -1, 4457, 4458, 4459, -1, 4457, 4459, 4460, -1, 4461, 960, 1042, -1, 4461, 983, 985, -1, 4461, 985, 960, -1, 4461, 4457, 4460, -1, 4461, 4460, 983, -1, 4461, 1042, 4457, -1, 4462, 4463, 4464, -1, 4462, 4464, 1039, -1, 4462, 1039, 989, -1, 4462, 4454, 4463, -1, 4465, 989, 990, -1, 4465, 990, 973, -1, 4465, 4454, 4462, -1, 4465, 4462, 989, -1, 4465, 973, 4454, -1, 4460, 4459, 4466, -1, 4460, 993, 983, -1, 4467, 4466, 4468, -1, 4467, 4468, 4469, -1, 4467, 1004, 998, -1, 4467, 998, 993, -1, 4467, 4460, 4466, -1, 4467, 993, 4460, -1, 4470, 4469, 4471, -1, 4470, 4471, 4472, -1, 4470, 1014, 1009, -1, 4470, 1009, 1004, -1, 4470, 4467, 4469, -1, 4470, 1004, 4467, -1, 4473, 4472, 4474, -1, 4473, 1018, 1014, -1, 4473, 1014, 4470, -1, 4473, 4470, 4472, -1, 4455, 4474, 4475, -1, 4455, 4475, 4456, -1, 4455, 975, 1022, -1, 4455, 1022, 1018, -1, 4455, 4473, 4474, -1, 4455, 1018, 4473, -1, 4454, 4456, 4463, -1, 1289, 1288, 4422, -1, 1288, 3762, 4422, -1, 4422, 3763, 4424, -1, 3762, 3763, 4422, -1, 4424, 3765, 4431, -1, 3763, 3765, 4424, -1, 4431, 3766, 4410, -1, 3765, 3766, 4431, -1, 4410, 3749, 4411, -1, 3766, 3749, 4410, -1, 4411, 3750, 4418, -1, 3749, 3750, 4411, -1, 4418, 3751, 4423, -1, 3750, 3751, 4418, -1, 4423, 3752, 4426, -1, 3751, 3752, 4423, -1, 4426, 3753, 4430, -1, 3752, 3753, 4426, -1, 4430, 3754, 4428, -1, 3753, 3754, 4430, -1, 4428, 3755, 4429, -1, 3754, 3755, 4428, -1, 4429, 3756, 4425, -1, 3755, 3756, 4429, -1, 4425, 1263, 1262, -1, 3756, 1263, 4425, -1, 1261, 1260, 4398, -1, 1260, 3105, 4398, -1, 4398, 3106, 4403, -1, 3105, 3106, 4398, -1, 4403, 3107, 4405, -1, 3106, 3107, 4403, -1, 4405, 3108, 4407, -1, 3107, 3108, 4405, -1, 4407, 3103, 4385, -1, 3108, 3103, 4407, -1, 4385, 3102, 4386, -1, 3103, 3102, 4385, -1, 4386, 3117, 4393, -1, 3102, 3117, 4386, -1, 4393, 3115, 4397, -1, 3117, 3115, 4393, -1, 4397, 3111, 4399, -1, 3115, 3111, 4397, -1, 4399, 3113, 4402, -1, 3111, 3113, 4399, -1, 4402, 3114, 4401, -1, 3113, 3114, 4402, -1, 4401, 3109, 4396, -1, 3114, 3109, 4401, -1, 4396, 1235, 1234, -1, 3109, 1235, 4396, -1, 4476, 4453, 1232, -1, 4476, 1232, 1168, -1, 4477, 1200, 1190, -1, 4476, 4478, 4453, -1, 4477, 1190, 4479, -1, 4480, 4481, 4478, -1, 4480, 4482, 4481, -1, 4483, 4452, 4451, -1, 1190, 1228, 4437, -1, 4484, 4384, 4406, -1, 4483, 4485, 4452, -1, 4484, 4406, 4486, -1, 4484, 4486, 4487, -1, 4484, 4487, 4482, -1, 4488, 1168, 1188, -1, 4489, 4477, 4479, -1, 4489, 4479, 4485, -1, 4488, 4476, 1168, -1, 4488, 4478, 4476, -1, 4490, 1207, 1200, -1, 4488, 4480, 4478, -1, 4490, 1208, 1207, -1, 4490, 4391, 1208, -1, 4491, 4390, 4384, -1, 4490, 4387, 4391, -1, 4491, 4384, 4484, -1, 4491, 4482, 4480, -1, 4490, 1200, 4477, -1, 4491, 4484, 4482, -1, 4492, 4451, 4449, -1, 4493, 1187, 4390, -1, 4493, 1188, 1187, -1, 4493, 4390, 4491, -1, 4493, 4488, 1188, -1, 4493, 4480, 4488, -1, 4493, 4491, 4480, -1, 4492, 4483, 4451, -1, 4494, 4485, 4483, -1, 4494, 4489, 4485, -1, 4495, 4388, 4387, -1, 4495, 4477, 4489, -1, 4495, 4387, 4490, -1, 4495, 4490, 4477, -1, 4496, 4449, 4447, -1, 4496, 4492, 4449, -1, 4497, 4494, 4483, -1, 4497, 4483, 4492, -1, 4498, 4389, 4388, -1, 4498, 4489, 4494, -1, 4498, 4495, 4489, -1, 4498, 4388, 4495, -1, 4499, 4447, 4446, -1, 4499, 4496, 4447, -1, 4500, 4497, 4492, -1, 4500, 4492, 4496, -1, 4501, 4392, 4389, -1, 4501, 4494, 4497, -1, 4501, 4389, 4498, -1, 4501, 4498, 4494, -1, 4502, 4446, 4444, -1, 4502, 4499, 4446, -1, 4503, 4500, 4496, -1, 4503, 4496, 4499, -1, 4504, 4501, 4497, -1, 4504, 4394, 4392, -1, 4504, 4497, 4500, -1, 4504, 4392, 4501, -1, 4505, 4444, 4443, -1, 4505, 4502, 4444, -1, 4506, 4499, 4502, -1, 4506, 4503, 4499, -1, 4507, 4500, 4503, -1, 4507, 4394, 4504, -1, 4507, 4395, 4394, -1, 4507, 4504, 4500, -1, 4508, 4443, 4441, -1, 4508, 4505, 4443, -1, 4509, 4502, 4505, -1, 4509, 4506, 4502, -1, 4510, 4507, 4503, -1, 4510, 4395, 4507, -1, 4510, 4400, 4395, -1, 4510, 4503, 4506, -1, 4481, 4441, 4440, -1, 4481, 4508, 4441, -1, 4487, 4505, 4508, -1, 4487, 4509, 4505, -1, 4511, 4506, 4509, -1, 4511, 4510, 4506, -1, 4511, 4404, 4400, -1, 4511, 4400, 4510, -1, 4478, 4440, 4453, -1, 4478, 4481, 4440, -1, 1201, 4390, 1187, -1, 4479, 4437, 4436, -1, 4479, 1190, 4437, -1, 4482, 4487, 4508, -1, 4482, 4508, 4481, -1, 4486, 4511, 4509, -1, 4485, 4436, 4452, -1, 4486, 4406, 4404, -1, 4486, 4509, 4487, -1, 4486, 4404, 4511, -1, 4485, 4479, 4436, -1, 4512, 4513, 4514, -1, 2053, 4515, 2055, -1, 4516, 4515, 2053, -1, 1323, 4517, 1313, -1, 1099, 4517, 1097, -1, 4518, 4519, 4520, -1, 4513, 4517, 1099, -1, 4521, 4517, 4522, -1, 1319, 4519, 1320, -1, 1313, 4517, 4521, -1, 4522, 4517, 4513, -1, 1097, 4517, 1323, -1, 1320, 4519, 4523, -1, 4523, 4519, 4518, -1, 1101, 2050, 1156, -1, 4516, 4524, 4515, -1, 4520, 4524, 4516, -1, 2055, 4525, 2056, -1, 4515, 4525, 2055, -1, 1324, 4526, 1319, -1, 1319, 4526, 4519, -1, 4519, 4526, 4520, -1, 4520, 4526, 4524, -1, 4515, 4527, 4525, -1, 4524, 4527, 4515, -1, 2056, 4528, 2057, -1, 4525, 4528, 2056, -1, 1327, 4529, 1324, -1, 4524, 4529, 4527, -1, 4526, 4529, 4524, -1, 1324, 4529, 4526, -1, 4525, 4530, 4528, -1, 4527, 4530, 4525, -1, 2057, 4531, 2058, -1, 4528, 4531, 2057, -1, 4527, 4532, 4530, -1, 1326, 4532, 1327, -1, 4529, 4532, 4527, -1, 1327, 4532, 4529, -1, 4528, 4533, 4531, -1, 4530, 4533, 4528, -1, 4531, 4534, 2058, -1, 2058, 4534, 2059, -1, 1330, 4535, 1326, -1, 4530, 4535, 4533, -1, 1326, 4535, 4532, -1, 4532, 4535, 4530, -1, 4533, 4536, 4531, -1, 4531, 4536, 4534, -1, 4534, 4537, 2059, -1, 2059, 4537, 2040, -1, 1330, 4538, 4535, -1, 1329, 4538, 1330, -1, 4535, 4538, 4533, -1, 4533, 4538, 4536, -1, 4536, 4539, 4534, -1, 4534, 4539, 4537, -1, 2040, 4540, 2039, -1, 4537, 4540, 2040, -1, 1332, 4541, 1329, -1, 1329, 4541, 4538, -1, 4536, 4541, 4539, -1, 4538, 4541, 4536, -1, 4539, 4542, 4537, -1, 4537, 4542, 4540, -1, 2039, 4543, 2037, -1, 4540, 4543, 2039, -1, 1333, 4544, 1332, -1, 1332, 4544, 4541, -1, 4541, 4544, 4539, -1, 4539, 4544, 4542, -1, 4542, 4545, 4540, -1, 4540, 4545, 4543, -1, 2037, 4512, 2035, -1, 4543, 4512, 2037, -1, 1323, 1129, 1097, -1, 1314, 4546, 1333, -1, 1333, 4546, 4544, -1, 2050, 4547, 2052, -1, 4544, 4546, 4542, -1, 1101, 4547, 2050, -1, 4542, 4546, 4545, -1, 1114, 4518, 1101, -1, 4545, 4522, 4543, -1, 4543, 4522, 4512, -1, 1101, 4518, 4547, -1, 2052, 4516, 2053, -1, 2035, 4514, 1162, -1, 1162, 4514, 1161, -1, 4547, 4516, 2052, -1, 4512, 4514, 2035, -1, 1320, 4523, 1120, -1, 1119, 4523, 1114, -1, 1120, 4523, 1119, -1, 1313, 4521, 1314, -1, 1314, 4521, 4546, -1, 1114, 4523, 4518, -1, 4545, 4521, 4522, -1, 4546, 4521, 4545, -1, 4518, 4520, 4547, -1, 4547, 4520, 4516, -1, 4514, 4513, 1161, -1, 1161, 4513, 1099, -1, 4522, 4513, 4512, -1, 4548, 4549, 4550, -1, 4548, 4551, 4549, -1, 4552, 4553, 4464, -1, 4554, 1059, 1040, -1, 4555, 4556, 4557, -1, 4555, 4409, 4427, -1, 4555, 4557, 4551, -1, 4554, 1040, 4553, -1, 4555, 4427, 4556, -1, 4558, 4459, 4458, -1, 4559, 4463, 4456, -1, 4558, 4560, 4459, -1, 4558, 4458, 1041, -1, 4559, 4552, 4463, -1, 4561, 4550, 4560, -1, 4561, 4548, 4550, -1, 4562, 4554, 4553, -1, 4562, 4553, 4552, -1, 4563, 4408, 4409, -1, 4563, 4409, 4555, -1, 4564, 1066, 1059, -1, 4564, 4416, 4419, -1, 4563, 4551, 4548, -1, 4563, 4555, 4551, -1, 4564, 4419, 1066, -1, 4565, 1041, 1053, -1, 4564, 1059, 4554, -1, 4565, 4558, 1041, -1, 4566, 4456, 4475, -1, 4565, 4560, 4558, -1, 4565, 4561, 4560, -1, 4567, 4412, 4408, -1, 4567, 4408, 4563, -1, 4567, 4548, 4561, -1, 4566, 4559, 4456, -1, 4568, 4552, 4559, -1, 4567, 4563, 4548, -1, 4569, 4412, 4567, -1, 4568, 4562, 4552, -1, 4569, 1053, 1052, -1, 4569, 1052, 1050, -1, 4419, 1092, 1066, -1, 4569, 4565, 1053, -1, 4569, 1050, 4412, -1, 4570, 4413, 4416, -1, 4569, 4561, 4565, -1, 4570, 4416, 4564, -1, 4569, 4567, 4561, -1, 4570, 4554, 4562, -1, 4570, 4564, 4554, -1, 4571, 4475, 4474, -1, 4571, 4566, 4475, -1, 4572, 4568, 4559, -1, 4572, 4559, 4566, -1, 4573, 4413, 4570, -1, 4573, 4414, 4413, -1, 4573, 4570, 4562, -1, 4573, 4562, 4568, -1, 4574, 4474, 4472, -1, 4574, 4571, 4474, -1, 4575, 4566, 4571, -1, 4575, 4572, 4566, -1, 4576, 4415, 4414, -1, 4576, 4573, 4568, -1, 4576, 4568, 4572, -1, 4576, 4414, 4573, -1, 4577, 4472, 4471, -1, 4577, 4574, 4472, -1, 4578, 4575, 4571, -1, 4578, 4571, 4574, -1, 4579, 4576, 4572, -1, 4579, 4417, 4415, -1, 4579, 4415, 4576, -1, 4579, 4572, 4575, -1, 4580, 4471, 4469, -1, 4580, 4577, 4471, -1, 4581, 4574, 4577, -1, 4581, 4578, 4574, -1, 4582, 4575, 4578, -1, 4582, 4417, 4579, -1, 4582, 4420, 4417, -1, 4582, 4579, 4575, -1, 4549, 4469, 4468, -1, 4549, 4580, 4469, -1, 4557, 4577, 4580, -1, 1041, 4458, 1042, -1, 4557, 4581, 4577, -1, 4583, 4582, 4578, -1, 4583, 4420, 4582, -1, 4583, 4421, 4420, -1, 4583, 4578, 4581, -1, 4550, 4468, 4466, -1, 4550, 4549, 4468, -1, 4551, 4557, 4580, -1, 4551, 4580, 4549, -1, 4556, 4581, 4557, -1, 4556, 4583, 4581, -1, 4556, 4427, 4421, -1, 4556, 4421, 4583, -1, 4553, 1040, 1039, -1, 4560, 4466, 4459, -1, 4553, 1039, 4464, -1, 4560, 4550, 4466, -1, 4552, 4464, 4463, -1, 4584, 4585, 4586, -1, 2038, 4587, 2060, -1, 4588, 4587, 2038, -1, 4589, 4590, 4591, -1, 1300, 4590, 1291, -1, 1291, 4590, 4592, -1, 4592, 4590, 4589, -1, 4588, 4593, 4587, -1, 4591, 4593, 4588, -1, 2060, 4594, 2049, -1, 4587, 4594, 2060, -1, 1303, 4595, 1300, -1, 4590, 4595, 4591, -1, 1300, 4595, 4590, -1, 4591, 4595, 4593, -1, 4587, 4596, 4594, -1, 4593, 4596, 4587, -1, 2049, 4597, 2048, -1, 989, 1292, 987, -1, 4594, 4597, 2049, -1, 1303, 4598, 4595, -1, 1302, 4598, 1303, -1, 4595, 4598, 4593, -1, 4593, 4598, 4596, -1, 4596, 4599, 4594, -1, 4594, 4599, 4597, -1, 2048, 4600, 2047, -1, 4597, 4600, 2048, -1, 1305, 4601, 1302, -1, 4596, 4601, 4599, -1, 4598, 4601, 4596, -1, 1302, 4601, 4598, -1, 4597, 4602, 4600, -1, 4599, 4602, 4597, -1, 4600, 4603, 2047, -1, 2047, 4603, 2046, -1, 1305, 4604, 4601, -1, 1308, 4604, 1305, -1, 4599, 4604, 4602, -1, 4601, 4604, 4599, -1, 4602, 4605, 4600, -1, 4600, 4605, 4603, -1, 4603, 4606, 2046, -1, 2046, 4606, 2045, -1, 1307, 4607, 1308, -1, 1308, 4607, 4604, -1, 4604, 4607, 4602, -1, 4602, 4607, 4605, -1, 4603, 4608, 4606, -1, 4605, 4608, 4603, -1, 2045, 4609, 2043, -1, 4606, 4609, 2045, -1, 1311, 4610, 1307, -1, 4607, 4610, 4605, -1, 4605, 4610, 4608, -1, 1307, 4610, 4607, -1, 4606, 4611, 4609, -1, 4608, 4611, 4606, -1, 2043, 4612, 2041, -1, 4609, 4612, 2043, -1, 1310, 4613, 1311, -1, 1311, 4613, 4610, -1, 4610, 4613, 4608, -1, 4608, 4613, 4611, -1, 4611, 4614, 4609, -1, 4609, 4614, 4612, -1, 2041, 4615, 2044, -1, 4612, 4615, 2041, -1, 1299, 4616, 1310, -1, 4613, 4616, 4611, -1, 1310, 4616, 4613, -1, 4611, 4616, 4614, -1, 4614, 4584, 4612, -1, 963, 4617, 961, -1, 4612, 4584, 4615, -1, 961, 4617, 2034, -1, 2034, 4617, 2036, -1, 2044, 4618, 972, -1, 972, 4618, 970, -1, 982, 4589, 963, -1, 4615, 4618, 2044, -1, 963, 4589, 4617, -1, 1298, 4619, 1299, -1, 1299, 4619, 4616, -1, 2036, 4588, 2038, -1, 4616, 4619, 4614, -1, 4614, 4619, 4584, -1, 4617, 4588, 2036, -1, 4618, 4586, 970, -1, 1291, 4592, 1292, -1, 970, 4586, 959, -1, 987, 4592, 982, -1, 4584, 4586, 4615, -1, 1292, 4592, 987, -1, 4615, 4586, 4618, -1, 982, 4592, 4589, -1, 960, 4585, 1298, -1, 4589, 4591, 4617, -1, 959, 4585, 957, -1, 4617, 4591, 4588, -1, 957, 4585, 960, -1, 1298, 4585, 4619, -1, 4586, 4585, 959, -1, 4619, 4585, 4584, -1, 4620, 4621, 4622, -1, 4620, 4622, 4623, -1, 4624, 4623, 4625, -1, 4626, 951, 4627, -1, 4624, 4620, 4623, -1, 4624, 4625, 4628, -1, 4626, 953, 951, -1, 4624, 4628, 4629, -1, 4624, 4629, 4630, -1, 4624, 4630, 4631, -1, 4632, 919, 4633, -1, 905, 4634, 4635, -1, 907, 4635, 4636, -1, 886, 953, 4626, -1, 907, 905, 4635, -1, 886, 4637, 953, -1, 903, 4638, 4634, -1, 935, 933, 4632, -1, 903, 4634, 905, -1, 896, 4639, 4640, -1, 931, 921, 919, -1, 896, 4640, 4641, -1, 931, 919, 4632, -1, 909, 4636, 4642, -1, 896, 4641, 4643, -1, 896, 4643, 4644, -1, 909, 907, 4636, -1, 896, 4624, 4639, -1, 931, 4632, 933, -1, 885, 4637, 886, -1, 937, 935, 4632, -1, 885, 4645, 4637, -1, 901, 4646, 4638, -1, 894, 896, 4644, -1, 901, 4638, 903, -1, 929, 923, 921, -1, 911, 909, 4642, -1, 894, 4644, 4647, -1, 911, 4642, 4633, -1, 899, 4646, 901, -1, 929, 921, 931, -1, 899, 4648, 4646, -1, 888, 4645, 885, -1, 888, 4649, 4645, -1, 939, 937, 4632, -1, 892, 894, 4647, -1, 927, 924, 923, -1, 892, 4647, 4650, -1, 913, 911, 4633, -1, 927, 923, 929, -1, 890, 4649, 888, -1, 890, 892, 4650, -1, 890, 4650, 4649, -1, 4651, 4648, 899, -1, 4651, 4652, 4648, -1, 941, 4632, 4653, -1, 915, 913, 4633, -1, 941, 939, 4632, -1, 4654, 4655, 924, -1, 4656, 4652, 4651, -1, 917, 915, 4633, -1, 4654, 924, 927, -1, 943, 4653, 4657, -1, 4658, 4652, 4656, -1, 943, 941, 4653, -1, 4659, 4631, 4655, -1, 4660, 4658, 4656, -1, 4659, 4655, 4654, -1, 919, 917, 4633, -1, 945, 4657, 4661, -1, 945, 943, 4657, -1, 4639, 4624, 4631, -1, 4662, 4658, 4660, -1, 4639, 4631, 4659, -1, 4662, 4660, 4663, -1, 947, 945, 4661, -1, 4664, 947, 4661, -1, 949, 947, 4664, -1, 4621, 4662, 4663, -1, 4621, 4663, 4622, -1, 4627, 951, 949, -1, 4627, 949, 4664, -1, 4665, 926, 928, -1, 952, 4666, 4667, -1, 952, 4667, 4668, -1, 952, 4668, 4669, -1, 952, 4669, 4670, -1, 952, 4670, 4665, -1, 952, 928, 930, -1, 952, 930, 932, -1, 952, 932, 934, -1, 952, 934, 936, -1, 952, 936, 938, -1, 952, 938, 940, -1, 952, 940, 942, -1, 952, 942, 944, -1, 952, 944, 946, -1, 952, 946, 948, -1, 952, 948, 950, -1, 952, 4665, 928, -1, 4671, 4666, 952, -1, 4672, 4671, 952, -1, 4673, 952, 4674, -1, 4675, 4672, 952, -1, 4676, 952, 4673, -1, 4676, 4675, 952, -1, 952, 953, 4674, -1, 4674, 4637, 4673, -1, 953, 4637, 4674, -1, 4673, 4645, 4676, -1, 4637, 4645, 4673, -1, 4676, 4649, 4675, -1, 4645, 4649, 4676, -1, 4675, 4650, 4672, -1, 4649, 4650, 4675, -1, 4672, 4647, 4671, -1, 4650, 4647, 4672, -1, 4671, 4644, 4666, -1, 4647, 4644, 4671, -1, 4666, 4643, 4667, -1, 4644, 4643, 4666, -1, 4667, 4641, 4668, -1, 4643, 4641, 4667, -1, 4668, 4640, 4669, -1, 4641, 4640, 4668, -1, 4669, 4639, 4670, -1, 4640, 4639, 4669, -1, 4670, 4659, 4665, -1, 4639, 4659, 4670, -1, 4665, 4654, 926, -1, 4659, 4654, 4665, -1, 4654, 927, 926, -1, 4677, 898, 900, -1, 916, 906, 908, -1, 916, 908, 910, -1, 916, 910, 912, -1, 916, 912, 914, -1, 918, 904, 906, -1, 918, 906, 916, -1, 920, 902, 904, -1, 920, 904, 918, -1, 922, 900, 902, -1, 922, 4677, 900, -1, 922, 902, 920, -1, 4678, 922, 925, -1, 4678, 4677, 922, -1, 4679, 4680, 4681, -1, 4682, 4683, 4677, -1, 4682, 4677, 4678, -1, 4684, 4681, 4685, -1, 4684, 4679, 4681, -1, 4686, 4685, 4687, -1, 4686, 4687, 4688, -1, 4686, 4688, 4683, -1, 4686, 4683, 4682, -1, 4686, 4684, 4685, -1, 925, 924, 4678, -1, 4678, 4655, 4682, -1, 924, 4655, 4678, -1, 4682, 4631, 4686, -1, 4655, 4631, 4682, -1, 4686, 4630, 4684, -1, 4631, 4630, 4686, -1, 4684, 4629, 4679, -1, 4630, 4629, 4684, -1, 4679, 4628, 4680, -1, 4629, 4628, 4679, -1, 4680, 4625, 4681, -1, 4628, 4625, 4680, -1, 4681, 4623, 4685, -1, 4625, 4623, 4681, -1, 4685, 4622, 4687, -1, 4623, 4622, 4685, -1, 4687, 4663, 4688, -1, 4622, 4663, 4687, -1, 4688, 4660, 4683, -1, 4663, 4660, 4688, -1, 4683, 4656, 4677, -1, 4660, 4656, 4683, -1, 4677, 4651, 898, -1, 4656, 4651, 4677, -1, 4651, 899, 898, -1, 4624, 3662, 4620, -1, 3663, 3662, 4624, -1, 3662, 4621, 4620, -1, 3662, 3661, 4621, -1, 3661, 4662, 4621, -1, 3661, 3660, 4662, -1, 3660, 4658, 4662, -1, 3660, 3659, 4658, -1, 3659, 4652, 4658, -1, 3659, 3657, 4652, -1, 3657, 4648, 4652, -1, 3657, 3656, 4648, -1, 3656, 4646, 4648, -1, 3656, 3655, 4646, -1, 3655, 4638, 4646, -1, 3655, 3654, 4638, -1, 3654, 4634, 4638, -1, 3654, 3653, 4634, -1, 3653, 4635, 4634, -1, 3653, 3652, 4635, -1, 3652, 4636, 4635, -1, 3652, 3651, 4636, -1, 3651, 4642, 4636, -1, 3651, 3650, 4642, -1, 3650, 4633, 4642, -1, 3650, 3648, 4633, -1, 3648, 3647, 4633, -1, 4633, 3647, 4632, -1, 897, 4624, 896, -1, 897, 3663, 4624, -1, 3647, 3646, 4632, -1, 4632, 3646, 4653, -1, 3646, 4657, 4653, -1, 3646, 3643, 4657, -1, 4657, 3640, 4661, -1, 3643, 3640, 4657, -1, 4661, 3639, 4664, -1, 3640, 3639, 4661, -1, 4664, 3642, 4627, -1, 3639, 3642, 4664, -1, 4627, 3645, 4626, -1, 3642, 3645, 4627, -1, 4626, 884, 886, -1, 3645, 884, 4626, -1, 3679, 4369, 4368, -1, 3679, 3676, 4369, -1, 3676, 4382, 4369, -1, 3676, 3675, 4382, -1, 3675, 4380, 4382, -1, 3675, 3674, 4380, -1, 3674, 4378, 4380, -1, 3674, 3673, 4378, -1, 3673, 4376, 4378, -1, 3673, 3671, 4376, -1, 3671, 4374, 4376, -1, 3671, 3668, 4374, -1, 3668, 4370, 4374, -1, 3668, 3700, 4370, -1, 3700, 4371, 4370, -1, 3700, 3699, 4371, -1, 3699, 4372, 4371, -1, 3699, 3698, 4372, -1, 3698, 4375, 4372, -1, 3698, 3697, 4375, -1, 3697, 4377, 4375, -1, 3697, 3696, 4377, -1, 3696, 4379, 4377, -1, 3696, 3693, 4379, -1, 3693, 4367, 4379, -1, 3693, 3685, 4367, -1, 3685, 4381, 4367, -1, 3685, 3672, 4381, -1, 883, 4368, 882, -1, 883, 3679, 4368, -1, 4381, 3672, 4383, -1, 4383, 3665, 4365, -1, 3672, 3665, 4383, -1, 4365, 3664, 4366, -1, 3665, 3664, 4365, -1, 4366, 3667, 4373, -1, 3664, 3667, 4366, -1, 4373, 3677, 868, -1, 3667, 3677, 4373, -1, 3677, 866, 868, -1, 3900, 830, 831, -1, 3900, 831, 3898, -1, 4689, 4012, 4014, -1, 4689, 4014, 4690, -1, 4691, 4690, 4692, -1, 4691, 4689, 4690, -1, 4693, 4691, 4692, -1, 4694, 4692, 4015, -1, 4694, 4693, 4692, -1, 4695, 4694, 4015, -1, 4696, 4695, 4015, -1, 4017, 4696, 4015, -1, 4697, 2067, 2069, -1, 4697, 2069, 4698, -1, 4699, 4698, 4700, -1, 4699, 4697, 4698, -1, 4701, 4700, 4702, -1, 4701, 4699, 4700, -1, 4703, 4702, 4704, -1, 4703, 4701, 4702, -1, 3901, 4704, 3899, -1, 3901, 4703, 4704, -1, 4705, 3902, 3903, -1, 4705, 3903, 4706, -1, 4707, 4706, 4708, -1, 4707, 4705, 4706, -1, 4709, 4708, 4710, -1, 4709, 4707, 4708, -1, 4711, 4710, 4712, -1, 4711, 4709, 4710, -1, 4009, 4712, 4007, -1, 4009, 4711, 4712, -1, 4059, 4056, 4713, -1, 4713, 4714, 4715, -1, 4056, 4714, 4713, -1, 4715, 4716, 4717, -1, 4714, 4716, 4715, -1, 4717, 4718, 4053, -1, 4716, 4718, 4717, -1, 4718, 4055, 4053, -1, 4719, 3536, 3538, -1, 4719, 3538, 4720, -1, 4721, 4720, 4722, -1, 4721, 4719, 4720, -1, 4723, 4721, 4722, -1, 4724, 4722, 4725, -1, 4724, 4725, 4726, -1, 4724, 4723, 4722, -1, 4727, 4726, 4728, -1, 4727, 4724, 4726, -1, 4729, 4727, 4728, -1, 4730, 4728, 4731, -1, 4730, 4729, 4728, -1, 4054, 4731, 4052, -1, 4054, 4730, 4731, -1, 4050, 4049, 4732, -1, 4733, 4050, 4732, -1, 4734, 4732, 4735, -1, 4734, 4733, 4732, -1, 4736, 4735, 4737, -1, 4736, 4734, 4735, -1, 4738, 4737, 4739, -1, 4738, 4739, 4058, -1, 4738, 4736, 4737, -1, 4057, 4738, 4058, -1, 4146, 4147, 4740, -1, 4740, 4741, 4742, -1, 4147, 4741, 4740, -1, 4742, 4743, 4744, -1, 4741, 4743, 4742, -1, 4744, 4745, 4746, -1, 4743, 4745, 4744, -1, 4746, 4747, 4128, -1, 4745, 4747, 4746, -1, 4747, 4127, 4128, -1, 4748, 3913, 3912, -1, 4748, 3912, 4749, -1, 4750, 4749, 4751, -1, 4750, 4748, 4749, -1, 4752, 4751, 4753, -1, 4752, 4750, 4751, -1, 4754, 4753, 4755, -1, 4754, 4755, 4756, -1, 4754, 4752, 4753, -1, 423, 4756, 3916, -1, 423, 4754, 4756, -1, 3182, 3187, 4757, -1, 4758, 4757, 4759, -1, 4758, 3182, 4757, -1, 4760, 4759, 4761, -1, 4760, 4758, 4759, -1, 4762, 4761, 4763, -1, 4762, 4763, 4764, -1, 4762, 4760, 4761, -1, 4765, 4764, 4766, -1, 4765, 4762, 4764, -1, 4767, 4766, 4768, -1, 4767, 4768, 4769, -1, 4767, 4765, 4766, -1, 4770, 4769, 4771, -1, 4770, 4771, 4772, -1, 4770, 4767, 4769, -1, 4773, 4772, 424, -1, 4773, 4770, 4772, -1, 3915, 4773, 424, -1, 4774, 3922, 3920, -1, 4774, 3920, 4775, -1, 4776, 4774, 4775, -1, 4777, 4775, 4778, -1, 4777, 4776, 4775, -1, 4779, 4778, 4780, -1, 4779, 4777, 4778, -1, 4781, 4780, 4782, -1, 4781, 4779, 4780, -1, 3199, 4782, 3200, -1, 3199, 4781, 4782, -1, 4783, 3921, 731, -1, 4783, 731, 729, -1, 4784, 729, 711, -1, 4784, 4783, 729, -1, 4785, 711, 713, -1, 4785, 4784, 711, -1, 4786, 713, 714, -1, 4786, 714, 730, -1, 4786, 4785, 713, -1, 4787, 730, 4788, -1, 4787, 4786, 730, -1, 4789, 4788, 4790, -1, 4789, 4787, 4788, -1, 4791, 4789, 4790, -1, 4792, 4790, 4793, -1, 4792, 4791, 4790, -1, 4794, 4793, 4795, -1, 4794, 4792, 4793, -1, 435, 4794, 4795, -1, 436, 4795, 3917, -1, 436, 435, 4795, -1, 437, 436, 3917, -1, 4796, 3930, 3931, -1, 4796, 3931, 4797, -1, 4798, 4796, 4797, -1, 4799, 4797, 4800, -1, 4799, 4798, 4797, -1, 4801, 4800, 4802, -1, 4801, 4799, 4800, -1, 4803, 4802, 4804, -1, 4803, 4801, 4802, -1, 3927, 4804, 3928, -1, 3927, 4803, 4804, -1, 4805, 3932, 393, -1, 4805, 393, 391, -1, 4806, 391, 373, -1, 4806, 4805, 391, -1, 4807, 373, 375, -1, 4807, 4806, 373, -1, 4808, 375, 376, -1, 4808, 376, 392, -1, 4808, 4807, 375, -1, 4809, 392, 4810, -1, 4809, 4808, 392, -1, 4811, 4810, 4812, -1, 4811, 4809, 4810, -1, 4813, 4811, 4812, -1, 4814, 4812, 4815, -1, 4814, 4813, 4812, -1, 4816, 4815, 4817, -1, 4816, 4814, 4815, -1, 448, 4816, 4817, -1, 449, 4817, 3923, -1, 449, 448, 4817, -1, 450, 449, 3923, -1, 4818, 3940, 3941, -1, 4818, 3941, 4819, -1, 4820, 4818, 4819, -1, 4821, 4819, 4822, -1, 4821, 4820, 4819, -1, 4823, 4822, 4824, -1, 4823, 4821, 4822, -1, 4825, 4824, 4826, -1, 4825, 4823, 4824, -1, 3937, 4826, 3938, -1, 3937, 4825, 4826, -1, 4827, 3942, 340, -1, 4827, 340, 338, -1, 4828, 338, 320, -1, 4828, 4827, 338, -1, 4829, 320, 322, -1, 4829, 4828, 320, -1, 4830, 322, 323, -1, 4830, 323, 339, -1, 4830, 4829, 322, -1, 4831, 339, 4832, -1, 4831, 4830, 339, -1, 4833, 4832, 4834, -1, 4833, 4831, 4832, -1, 4835, 4833, 4834, -1, 4836, 4834, 4837, -1, 4836, 4835, 4834, -1, 4838, 4837, 4839, -1, 4838, 4836, 4837, -1, 461, 4838, 4839, -1, 462, 4839, 3933, -1, 462, 461, 4839, -1, 463, 462, 3933, -1, 4840, 3950, 3951, -1, 4840, 3951, 4841, -1, 4842, 4840, 4841, -1, 4843, 4841, 4844, -1, 4843, 4842, 4841, -1, 4845, 4844, 4846, -1, 4845, 4843, 4844, -1, 4847, 4846, 4848, -1, 4847, 4845, 4846, -1, 3947, 4848, 3948, -1, 3947, 4847, 4848, -1, 4849, 3952, 287, -1, 4849, 287, 285, -1, 4850, 285, 267, -1, 4850, 4849, 285, -1, 4851, 267, 269, -1, 4851, 4850, 267, -1, 4852, 269, 270, -1, 4852, 270, 286, -1, 4852, 4851, 269, -1, 4853, 286, 4854, -1, 4853, 4852, 286, -1, 4855, 4854, 4856, -1, 4855, 4853, 4854, -1, 4857, 4855, 4856, -1, 4858, 4856, 4859, -1, 4858, 4857, 4856, -1, 4860, 4859, 4861, -1, 4860, 4858, 4859, -1, 474, 4860, 4861, -1, 475, 4861, 3943, -1, 475, 474, 4861, -1, 476, 475, 3943, -1, 4862, 3960, 3961, -1, 4862, 3961, 4863, -1, 4864, 4862, 4863, -1, 4865, 4863, 4866, -1, 4865, 4864, 4863, -1, 4867, 4866, 4868, -1, 4867, 4865, 4866, -1, 4869, 4868, 4870, -1, 4869, 4867, 4868, -1, 3957, 4870, 3958, -1, 3957, 4869, 4870, -1, 4871, 3962, 234, -1, 4871, 234, 232, -1, 4872, 232, 214, -1, 4872, 4871, 232, -1, 4873, 214, 216, -1, 4873, 4872, 214, -1, 4874, 216, 217, -1, 4874, 217, 233, -1, 4874, 4873, 216, -1, 4875, 233, 4876, -1, 4875, 4874, 233, -1, 4877, 4876, 4878, -1, 4877, 4875, 4876, -1, 4879, 4877, 4878, -1, 4880, 4878, 4881, -1, 4880, 4879, 4878, -1, 4882, 4881, 4883, -1, 4882, 4880, 4881, -1, 487, 4882, 4883, -1, 488, 4883, 3953, -1, 488, 487, 4883, -1, 489, 488, 3953, -1, 4884, 3972, 181, -1, 4884, 181, 179, -1, 4885, 179, 161, -1, 4885, 4884, 179, -1, 4886, 161, 163, -1, 4886, 4885, 161, -1, 4887, 163, 164, -1, 4887, 164, 180, -1, 4887, 4886, 163, -1, 4888, 180, 4889, -1, 4888, 4887, 180, -1, 4890, 4889, 4891, -1, 4890, 4888, 4889, -1, 4892, 4890, 4891, -1, 4893, 4891, 4894, -1, 4893, 4892, 4891, -1, 4895, 4894, 4896, -1, 4895, 4893, 4894, -1, 500, 4895, 4896, -1, 501, 4896, 3963, -1, 501, 500, 4896, -1, 502, 501, 3963, -1, 4897, 3970, 3971, -1, 4897, 3971, 4898, -1, 4899, 4897, 4898, -1, 4900, 4898, 4901, -1, 4900, 4899, 4898, -1, 4902, 4901, 4903, -1, 4902, 4900, 4901, -1, 4904, 4903, 4905, -1, 4904, 4902, 4903, -1, 3967, 4905, 3968, -1, 3967, 4904, 4905, -1, 4906, 3980, 3981, -1, 4906, 3981, 4907, -1, 4908, 4906, 4907, -1, 4909, 4907, 4910, -1, 4909, 4908, 4907, -1, 4911, 4910, 4912, -1, 4911, 4909, 4910, -1, 4913, 4912, 4914, -1, 4913, 4911, 4912, -1, 3977, 4914, 3978, -1, 3977, 4913, 4914, -1, 4915, 3982, 558, -1, 4915, 558, 556, -1, 4916, 556, 538, -1, 4916, 4915, 556, -1, 4917, 538, 540, -1, 4917, 4916, 538, -1, 4918, 540, 541, -1, 4918, 541, 557, -1, 4918, 4917, 540, -1, 4919, 557, 4920, -1, 4919, 4918, 557, -1, 4921, 4920, 4922, -1, 4921, 4919, 4920, -1, 4923, 4921, 4922, -1, 4924, 4922, 4925, -1, 4924, 4923, 4922, -1, 4926, 4925, 4927, -1, 4926, 4924, 4925, -1, 592, 4926, 4927, -1, 593, 4927, 3973, -1, 593, 592, 4927, -1, 594, 593, 3973, -1, 4928, 3990, 3991, -1, 4928, 3991, 4929, -1, 4930, 4928, 4929, -1, 4931, 4929, 4932, -1, 4931, 4930, 4929, -1, 4933, 4932, 4934, -1, 4933, 4931, 4932, -1, 4935, 4934, 4936, -1, 4935, 4933, 4934, -1, 3987, 4936, 3988, -1, 3987, 4935, 4936, -1, 4937, 3992, 57, -1, 4937, 57, 55, -1, 4938, 55, 37, -1, 4938, 4937, 55, -1, 4939, 37, 39, -1, 4939, 4938, 37, -1, 4940, 39, 40, -1, 4940, 40, 56, -1, 4940, 4939, 39, -1, 4941, 56, 4942, -1, 4941, 4940, 56, -1, 4943, 4942, 4944, -1, 4943, 4941, 4942, -1, 4945, 4943, 4944, -1, 4946, 4944, 4947, -1, 4946, 4945, 4944, -1, 4948, 4947, 4949, -1, 4948, 4946, 4947, -1, 513, 4948, 4949, -1, 514, 4949, 3983, -1, 514, 513, 4949, -1, 515, 514, 3983, -1, 4950, 4002, 128, -1, 4950, 128, 126, -1, 4951, 126, 108, -1, 4951, 4950, 126, -1, 4952, 108, 110, -1, 4952, 4951, 108, -1, 4953, 110, 111, -1, 4953, 111, 127, -1, 4953, 4952, 110, -1, 4954, 127, 4955, -1, 4954, 4953, 127, -1, 4956, 4955, 4957, -1, 4956, 4954, 4955, -1, 4958, 4956, 4957, -1, 4959, 4957, 4960, -1, 4959, 4958, 4957, -1, 4961, 4960, 4962, -1, 4961, 4959, 4960, -1, 526, 4961, 4962, -1, 527, 4962, 3993, -1, 527, 526, 4962, -1, 528, 527, 3993, -1, 4963, 4000, 4001, -1, 4963, 4001, 4964, -1, 4965, 4963, 4964, -1, 4966, 4964, 4967, -1, 4966, 4965, 4964, -1, 4968, 4967, 4969, -1, 4968, 4966, 4967, -1, 4970, 4969, 4971, -1, 4970, 4968, 4969, -1, 3997, 4971, 3998, -1, 3997, 4970, 4971, -1, 625, 4003, 4005, -1, 625, 4005, 4972, -1, 622, 625, 4972, -1, 637, 622, 4972, -1, 635, 4972, 4973, -1, 635, 637, 4972, -1, 642, 635, 4973, -1, 646, 4973, 4974, -1, 646, 642, 4973, -1, 620, 4974, 4975, -1, 620, 4975, 4976, -1, 620, 646, 4974, -1, 619, 4976, 3531, -1, 619, 620, 4976, -1, 4977, 3581, 4978, -1, 4977, 3582, 3581, -1, 4979, 4977, 4978, -1, 4980, 4978, 4981, -1, 4980, 4979, 4978, -1, 4982, 4981, 3085, -1, 4982, 3085, 3086, -1, 4982, 4980, 4981, -1, 4983, 3086, 3088, -1, 4983, 3088, 3090, -1, 4983, 3090, 3091, -1, 4983, 3091, 3025, -1, 4983, 4982, 3086, -1, 4984, 3025, 3026, -1, 4984, 3026, 3019, -1, 4984, 3019, 3021, -1, 4984, 3021, 3022, -1, 4984, 3022, 3023, -1, 4984, 3023, 3017, -1, 4984, 4983, 3025, -1, 4985, 3017, 3018, -1, 4985, 4984, 3017, -1, 3533, 3018, 3032, -1, 3533, 4985, 3018, -1, 4986, 3907, 3910, -1, 4986, 3910, 4987, -1, 4988, 4987, 4989, -1, 4988, 4986, 4987, -1, 4990, 4989, 4991, -1, 4990, 4988, 4989, -1, 2061, 4991, 2068, -1, 2061, 4990, 4991, -1, 4992, 4064, 4061, -1, 4172, 4992, 4061, -1, 4174, 4993, 4992, -1, 4174, 4992, 4172, -1, 3907, 4986, 4993, -1, 3907, 4993, 4174, -1, 4988, 4992, 4993, -1, 4988, 4993, 4986, -1, 4994, 4064, 4992, -1, 4994, 4992, 4988, -1, 4990, 4994, 4988, -1, 4995, 4994, 4990, -1, 2061, 4995, 4990, -1, 2061, 2063, 4996, -1, 4995, 4996, 4997, -1, 4995, 2061, 4996, -1, 4994, 4997, 4062, -1, 4994, 4995, 4997, -1, 4064, 4994, 4062, -1, 653, 3759, 4998, -1, 654, 4998, 4999, -1, 654, 653, 4998, -1, 671, 4999, 5000, -1, 671, 654, 4999, -1, 670, 5000, 5001, -1, 670, 671, 5000, -1, 667, 5001, 5002, -1, 667, 670, 5001, -1, 663, 5002, 5003, -1, 663, 667, 5002, -1, 660, 5003, 5004, -1, 660, 663, 5003, -1, 650, 5004, 2072, -1, 650, 660, 5004, -1, 651, 650, 2072, -1, 4188, 5005, 5006, -1, 4188, 5007, 5005, -1, 4188, 5008, 5007, -1, 4188, 5009, 5008, -1, 4188, 3131, 5009, -1, 3759, 4189, 4998, -1, 5010, 2072, 5004, -1, 5010, 5004, 5003, -1, 5010, 5003, 5002, -1, 5010, 5011, 2071, -1, 5010, 5012, 5011, -1, 5010, 5006, 5012, -1, 5010, 2071, 2072, -1, 5013, 5002, 5001, -1, 5013, 5001, 5000, -1, 5013, 5006, 5010, -1, 5013, 4188, 5006, -1, 5013, 5010, 5002, -1, 5014, 5000, 4999, -1, 5014, 4999, 4998, -1, 5014, 4189, 4188, -1, 5014, 4188, 5013, -1, 5014, 5013, 5000, -1, 5014, 4998, 4189, -1, 5009, 3131, 3130, -1, 5009, 3130, 5015, -1, 5008, 5015, 5016, -1, 5008, 5009, 5015, -1, 5007, 5016, 5017, -1, 5007, 5008, 5016, -1, 5005, 5017, 5018, -1, 5005, 5007, 5017, -1, 5006, 5018, 5019, -1, 5006, 5005, 5018, -1, 5012, 5019, 5020, -1, 5012, 5006, 5019, -1, 5011, 5020, 5021, -1, 5011, 5012, 5020, -1, 2071, 5021, 2070, -1, 2071, 5011, 5021, -1, 4190, 5022, 5023, -1, 4190, 5024, 5022, -1, 4190, 5025, 5024, -1, 4190, 5026, 5025, -1, 4190, 3099, 5026, -1, 3130, 4191, 5015, -1, 5027, 2070, 5021, -1, 5027, 5021, 5020, -1, 5027, 5020, 5019, -1, 5027, 5028, 2066, -1, 5027, 5029, 5028, -1, 5027, 5023, 5029, -1, 5027, 2066, 2070, -1, 5030, 5019, 5018, -1, 5030, 5018, 5017, -1, 5030, 5023, 5027, -1, 5030, 4190, 5023, -1, 5030, 5027, 5019, -1, 5031, 5017, 5016, -1, 5031, 5016, 5015, -1, 5031, 4191, 4190, -1, 5031, 4190, 5030, -1, 5031, 5030, 5017, -1, 5031, 5015, 4191, -1, 3099, 3098, 4194, -1, 5026, 4194, 4193, -1, 5026, 3099, 4194, -1, 5025, 4193, 4192, -1, 5025, 4192, 5032, -1, 5025, 5026, 4193, -1, 5024, 5032, 5033, -1, 5024, 5033, 5034, -1, 5024, 5025, 5032, -1, 5022, 5034, 5035, -1, 5022, 5035, 5036, -1, 5022, 5024, 5034, -1, 5023, 5036, 5037, -1, 5023, 5022, 5036, -1, 5029, 5037, 5038, -1, 5029, 5023, 5037, -1, 5028, 5038, 5039, -1, 5028, 5029, 5038, -1, 2066, 5039, 2062, -1, 2066, 5028, 5039, -1, 3579, 5040, 3577, -1, 3577, 5040, 5041, -1, 5041, 5042, 5043, -1, 5040, 5042, 5041, -1, 5043, 5044, 5045, -1, 5042, 5044, 5043, -1, 5045, 5046, 5047, -1, 5044, 5046, 5045, -1, 5047, 5048, 5049, -1, 5046, 5048, 5047, -1, 5049, 5050, 5051, -1, 5048, 5050, 5049, -1, 5051, 3277, 3253, -1, 5050, 3277, 5051, -1, 5052, 3644, 3641, -1, 5052, 3641, 5053, -1, 5054, 5053, 5055, -1, 5054, 5052, 5053, -1, 5056, 5055, 5057, -1, 5056, 5054, 5055, -1, 5058, 5057, 5059, -1, 5058, 5056, 5057, -1, 3546, 5059, 3544, -1, 3546, 5058, 5059, -1, 5060, 3682, 3666, -1, 5060, 3666, 5061, -1, 5062, 5060, 5061, -1, 5063, 5062, 5061, -1, 5064, 5061, 5065, -1, 5064, 5063, 5061, -1, 5066, 5064, 5065, -1, 5067, 5065, 5068, -1, 5067, 5066, 5065, -1, 5069, 5068, 5070, -1, 5069, 5067, 5068, -1, 5071, 5070, 5072, -1, 5071, 5072, 5073, -1, 5071, 5069, 5070, -1, 3658, 5073, 3649, -1, 3658, 5071, 5073, -1, 3214, 3213, 3606, -1, 3606, 3213, 5074, -1, 5075, 3212, 811, -1, 5074, 3212, 5075, -1, 3213, 3212, 5074, -1, 3212, 812, 811, -1, 3770, 3226, 3225, -1, 5076, 3225, 3224, -1, 5076, 3770, 3225, -1, 5077, 5076, 3224, -1, 5078, 3224, 3223, -1, 5078, 5077, 3224, -1, 5079, 3223, 3222, -1, 5079, 5078, 3223, -1, 5080, 3222, 3221, -1, 5080, 5079, 3222, -1, 5081, 3221, 3220, -1, 5081, 5080, 3221, -1, 5082, 3220, 3219, -1, 5082, 5081, 3220, -1, 675, 3219, 3218, -1, 675, 5082, 3219, -1, 652, 3218, 3215, -1, 652, 675, 3218, -1, 653, 652, 3215, -1, 3209, 3202, 5083, -1, 5084, 5085, 5086, -1, 5083, 5085, 5084, -1, 3202, 5085, 5083, -1, 5086, 5087, 5088, -1, 5085, 5087, 5086, -1, 5088, 2032, 2029, -1, 5087, 2032, 5088, -1, 5089, 3189, 3195, -1, 5089, 3195, 5090, -1, 5091, 5090, 5092, -1, 5091, 5089, 5090, -1, 2022, 5092, 2023, -1, 2022, 5091, 5092, -1, 4004, 5093, 4006, -1, 4006, 5093, 5094, -1, 5094, 5095, 5096, -1, 5093, 5095, 5094, -1, 5096, 2082, 2080, -1, 5095, 2082, 5096, -1, 5097, 3584, 3580, -1, 5097, 3580, 5098, -1, 5099, 5098, 5100, -1, 5099, 5097, 5098, -1, 5101, 5100, 3908, -1, 5101, 5099, 5100, -1, 3905, 5101, 3908, -1, 3996, 5102, 3999, -1, 3999, 5102, 5103, -1, 5103, 5104, 5105, -1, 5102, 5104, 5103, -1, 5105, 2090, 2088, -1, 5104, 2090, 5105, -1, 5106, 3994, 3995, -1, 5106, 3995, 5107, -1, 5108, 5107, 5109, -1, 5108, 5106, 5107, -1, 2091, 5109, 2092, -1, 2091, 5108, 5109, -1, 3986, 5110, 3989, -1, 3989, 5110, 5111, -1, 5111, 5112, 5113, -1, 5110, 5112, 5111, -1, 5113, 2099, 2097, -1, 5112, 2099, 5113, -1, 5114, 3984, 3985, -1, 5114, 3985, 5115, -1, 5116, 5115, 5117, -1, 5116, 5114, 5115, -1, 2100, 5117, 2101, -1, 2100, 5116, 5117, -1, 3976, 5118, 3979, -1, 3979, 5118, 5119, -1, 5119, 5120, 5121, -1, 5118, 5120, 5119, -1, 5121, 2108, 2106, -1, 5120, 2108, 5121, -1, 5122, 3974, 3975, -1, 5122, 3975, 5123, -1, 5124, 5123, 5125, -1, 5124, 5122, 5123, -1, 2109, 5125, 2110, -1, 2109, 5124, 5125, -1, 3966, 5126, 3969, -1, 3969, 5126, 5127, -1, 5127, 5128, 5129, -1, 5126, 5128, 5127, -1, 5129, 2117, 2115, -1, 5128, 2117, 5129, -1, 5130, 3964, 3965, -1, 5130, 3965, 5131, -1, 5132, 5131, 5133, -1, 5132, 5130, 5131, -1, 2118, 5133, 2119, -1, 2118, 5132, 5133, -1, 3956, 5134, 3959, -1, 3959, 5134, 5135, -1, 5135, 5136, 5137, -1, 5134, 5136, 5135, -1, 5137, 2126, 2124, -1, 5136, 2126, 5137, -1, 5138, 3954, 3955, -1, 5138, 3955, 5139, -1, 5140, 5139, 5141, -1, 5140, 5138, 5139, -1, 2127, 5141, 2128, -1, 2127, 5140, 5141, -1, 3946, 5142, 3949, -1, 3949, 5142, 5143, -1, 5143, 5144, 5145, -1, 5142, 5144, 5143, -1, 5145, 2135, 2133, -1, 5144, 2135, 5145, -1, 5146, 3944, 3945, -1, 5146, 3945, 5147, -1, 5148, 5147, 5149, -1, 5148, 5146, 5147, -1, 2136, 5149, 2137, -1, 2136, 5148, 5149, -1, 5150, 3918, 3919, -1, 5150, 3919, 5151, -1, 5152, 5151, 5153, -1, 5152, 5150, 5151, -1, 2159, 5153, 2160, -1, 2159, 5152, 5153, -1, 5154, 3934, 3935, -1, 5154, 3935, 5155, -1, 5156, 5155, 5157, -1, 5156, 5154, 5155, -1, 2145, 5157, 2146, -1, 2145, 5156, 5157, -1, 3936, 5158, 3939, -1, 3939, 5158, 5159, -1, 5159, 5160, 5161, -1, 5158, 5160, 5159, -1, 5161, 2144, 2142, -1, 5160, 2144, 5161, -1, 5162, 3924, 3925, -1, 5162, 3925, 5163, -1, 5164, 5163, 5165, -1, 5164, 5162, 5163, -1, 2154, 5165, 2155, -1, 2154, 5164, 5165, -1, 3926, 5166, 3929, -1, 3929, 5166, 5167, -1, 5167, 5168, 5169, -1, 5166, 5168, 5167, -1, 5169, 2153, 2151, -1, 5168, 2153, 5169, -1, 3914, 5170, 5171, -1, 3911, 5170, 3914, -1, 5171, 5172, 5173, -1, 5170, 5172, 5171, -1, 5173, 2086, 2084, -1, 5172, 2086, 5173, -1, 3190, 5174, 1515, -1, 1515, 5174, 1514, -1, 1514, 5175, 1516, -1, 1516, 5175, 800, -1, 5174, 5175, 1514, -1, 5175, 798, 800, -1, 788, 5176, 790, -1, 790, 5176, 5177, -1, 3186, 5178, 3188, -1, 3188, 5178, 3190, -1, 3190, 5178, 5174, -1, 5179, 5178, 3186, -1, 5180, 5181, 5182, -1, 5177, 5181, 5180, -1, 786, 5183, 788, -1, 788, 5183, 5176, -1, 5174, 5184, 5175, -1, 5179, 5184, 5178, -1, 5178, 5184, 5174, -1, 5182, 5184, 5179, -1, 5177, 5185, 5181, -1, 5176, 5185, 5177, -1, 784, 5186, 786, -1, 786, 5186, 5183, -1, 5175, 5187, 798, -1, 5182, 5187, 5184, -1, 5184, 5187, 5175, -1, 5181, 5187, 5182, -1, 5176, 5188, 5185, -1, 5183, 5188, 5176, -1, 798, 5189, 799, -1, 5187, 5189, 798, -1, 5185, 5189, 5181, -1, 5181, 5189, 5187, -1, 781, 5190, 784, -1, 4227, 5190, 781, -1, 784, 5190, 5186, -1, 5186, 5191, 5183, -1, 5183, 5191, 5188, -1, 799, 5192, 802, -1, 5189, 5192, 799, -1, 5188, 5192, 5185, -1, 5185, 5192, 5189, -1, 4225, 5193, 4227, -1, 4204, 4227, 5194, -1, 5194, 4227, 5195, -1, 4227, 5193, 5190, -1, 5195, 4227, 780, -1, 5186, 5196, 5191, -1, 780, 4227, 781, -1, 5190, 5196, 5186, -1, 5188, 5197, 5192, -1, 802, 5197, 804, -1, 5192, 5197, 802, -1, 5191, 5197, 5188, -1, 4222, 5198, 4225, -1, 4225, 5198, 5193, -1, 5193, 5198, 5190, -1, 5190, 5198, 5196, -1, 5197, 5199, 804, -1, 5191, 5199, 5197, -1, 804, 5199, 807, -1, 5196, 5199, 5191, -1, 809, 5200, 4222, -1, 5198, 5200, 5196, -1, 5196, 5200, 5199, -1, 5199, 5200, 807, -1, 807, 5200, 809, -1, 4222, 5200, 5198, -1, 794, 5201, 796, -1, 796, 5201, 3183, -1, 792, 5180, 794, -1, 794, 5180, 5201, -1, 790, 5177, 792, -1, 792, 5177, 5180, -1, 3183, 5179, 3186, -1, 5201, 5179, 3183, -1, 5201, 5182, 5179, -1, 5180, 5182, 5201, -1, 4204, 5194, 4202, -1, 4202, 5194, 5202, -1, 5202, 5195, 5203, -1, 5194, 5195, 5202, -1, 5203, 780, 782, -1, 5195, 780, 5203, -1, 4219, 777, 779, -1, 4202, 5202, 4216, -1, 5202, 5203, 4216, -1, 5203, 782, 4216, -1, 782, 783, 4216, -1, 5204, 795, 5205, -1, 5205, 795, 797, -1, 4217, 5206, 4219, -1, 4216, 5207, 4217, -1, 783, 5207, 4216, -1, 777, 5208, 775, -1, 4219, 5208, 777, -1, 5206, 5208, 4219, -1, 785, 5209, 783, -1, 5206, 5209, 5208, -1, 4217, 5209, 5206, -1, 783, 5209, 5207, -1, 5207, 5209, 4217, -1, 775, 5210, 773, -1, 5208, 5210, 775, -1, 787, 5211, 785, -1, 785, 5211, 5209, -1, 5209, 5211, 5208, -1, 5208, 5211, 5210, -1, 773, 5212, 771, -1, 771, 5212, 770, -1, 5210, 5212, 773, -1, 789, 5213, 787, -1, 791, 5213, 789, -1, 5212, 5213, 791, -1, 5211, 5213, 5210, -1, 787, 5213, 5211, -1, 5210, 5213, 5212, -1, 770, 5214, 5204, -1, 793, 5214, 791, -1, 795, 5214, 793, -1, 791, 5214, 5212, -1, 5212, 5214, 770, -1, 5204, 5214, 795, -1, 3182, 5215, 797, -1, 797, 5215, 5205, -1, 5205, 5216, 5204, -1, 5215, 5216, 5205, -1, 5204, 768, 770, -1, 5216, 768, 5204, -1, 5217, 5218, 5219, -1, 5220, 5221, 5222, -1, 774, 5223, 5224, -1, 5222, 5221, 5225, -1, 5226, 5227, 5228, -1, 5229, 5230, 5231, -1, 5224, 5230, 5229, -1, 5225, 5227, 5226, -1, 1830, 5232, 1828, -1, 1828, 5232, 1825, -1, 5231, 5232, 1830, -1, 5233, 5234, 5235, -1, 5235, 5234, 5236, -1, 769, 5237, 772, -1, 5228, 5238, 5217, -1, 772, 5237, 5223, -1, 5217, 5238, 5218, -1, 5224, 5239, 5230, -1, 4765, 5240, 4762, -1, 5220, 5240, 5221, -1, 4762, 5240, 5241, -1, 5223, 5239, 5224, -1, 5241, 5240, 5220, -1, 5236, 5242, 1851, -1, 1851, 5242, 1858, -1, 1858, 5242, 5243, -1, 5230, 5244, 5231, -1, 5231, 5244, 5232, -1, 5221, 5245, 5225, -1, 5225, 5245, 5227, -1, 5232, 5246, 1825, -1, 5218, 5247, 5233, -1, 5233, 5247, 5234, -1, 768, 5248, 769, -1, 5228, 5249, 5238, -1, 5227, 5249, 5228, -1, 769, 5248, 5237, -1, 5243, 5250, 5251, -1, 3182, 4758, 5215, -1, 5223, 5252, 5239, -1, 5234, 5250, 5236, -1, 5242, 5250, 5243, -1, 5237, 5252, 5223, -1, 5236, 5250, 5242, -1, 4767, 5253, 4765, -1, 5239, 5254, 5230, -1, 4765, 5253, 5240, -1, 5240, 5253, 5221, -1, 5221, 5253, 5245, -1, 5230, 5254, 5244, -1, 5245, 5255, 5227, -1, 5216, 5256, 768, -1, 5227, 5255, 5249, -1, 768, 5256, 5248, -1, 5218, 5257, 5247, -1, 5238, 5257, 5218, -1, 5244, 5219, 5232, -1, 5251, 5258, 5259, -1, 5232, 5219, 5246, -1, 5247, 5258, 5234, -1, 5250, 5258, 5251, -1, 1825, 5235, 1838, -1, 5234, 5258, 5250, -1, 1838, 5235, 1844, -1, 4770, 5260, 4767, -1, 4767, 5260, 5253, -1, 5253, 5260, 5245, -1, 5246, 5235, 1825, -1, 5245, 5260, 5255, -1, 5249, 5261, 5238, -1, 5248, 5222, 5237, -1, 1858, 5243, 1870, -1, 5237, 5222, 5252, -1, 5238, 5261, 5257, -1, 5259, 5262, 5263, -1, 5252, 5226, 5239, -1, 5247, 5262, 5258, -1, 5258, 5262, 5259, -1, 5239, 5226, 5254, -1, 5257, 5262, 5247, -1, 4760, 5264, 4758, -1, 5215, 5264, 5216, -1, 5249, 5265, 5261, -1, 4758, 5264, 5215, -1, 5255, 5265, 5249, -1, 5216, 5264, 5256, -1, 5244, 5217, 5219, -1, 5263, 5266, 5267, -1, 5262, 5266, 5263, -1, 5261, 5266, 5257, -1, 5254, 5217, 5244, -1, 5257, 5266, 5262, -1, 5256, 5220, 5248, -1, 4770, 5268, 5260, -1, 5260, 5268, 5255, -1, 5255, 5268, 5265, -1, 5248, 5220, 5222, -1, 5219, 5233, 5246, -1, 5267, 5269, 5270, -1, 5266, 5269, 5267, -1, 5265, 5269, 5261, -1, 5261, 5269, 5266, -1, 5246, 5233, 5235, -1, 5268, 5271, 5265, -1, 5270, 5271, 3915, -1, 3915, 5271, 4773, -1, 4773, 5271, 4770, -1, 4770, 5271, 5268, -1, 5265, 5271, 5269, -1, 5222, 5225, 5252, -1, 5269, 5271, 5270, -1, 5252, 5225, 5226, -1, 778, 5229, 1842, -1, 5226, 5228, 5254, -1, 1842, 5229, 1830, -1, 5254, 5228, 5217, -1, 776, 5229, 778, -1, 4760, 5241, 5264, -1, 4762, 5241, 4760, -1, 774, 5224, 776, -1, 5264, 5241, 5256, -1, 5256, 5241, 5220, -1, 1844, 5236, 1851, -1, 776, 5224, 5229, -1, 5235, 5236, 1844, -1, 5229, 5231, 1830, -1, 5219, 5218, 5233, -1, 772, 5223, 774, -1, 1870, 5243, 1871, -1, 1871, 5243, 5272, -1, 5272, 5251, 5273, -1, 5243, 5251, 5272, -1, 5273, 5259, 5274, -1, 5251, 5259, 5273, -1, 5274, 5263, 5275, -1, 5259, 5263, 5274, -1, 5275, 5267, 5276, -1, 5263, 5267, 5275, -1, 5276, 5270, 5277, -1, 5277, 5270, 3916, -1, 5267, 5270, 5276, -1, 5270, 3915, 3916, -1, 5278, 5279, 1874, -1, 5276, 5280, 5275, -1, 5275, 5280, 5281, -1, 5281, 5282, 5283, -1, 5283, 5282, 5284, -1, 5285, 5286, 5278, -1, 5278, 5286, 5279, -1, 1875, 5287, 1876, -1, 1876, 5287, 1877, -1, 1877, 5287, 5288, -1, 5279, 5287, 1875, -1, 4756, 5289, 3916, -1, 5277, 5289, 5276, -1, 3916, 5289, 5277, -1, 5276, 5289, 5280, -1, 5280, 5290, 5281, -1, 5281, 5290, 5282, -1, 5285, 5291, 5286, -1, 5284, 5291, 5285, -1, 5288, 5292, 5293, -1, 5287, 5292, 5288, -1, 5286, 5292, 5279, -1, 5279, 5292, 5287, -1, 4753, 5294, 4755, -1, 4755, 5294, 4756, -1, 4756, 5294, 5289, -1, 5289, 5294, 5280, -1, 5280, 5294, 5290, -1, 5282, 5295, 5284, -1, 5284, 5295, 5291, -1, 5293, 5296, 5297, -1, 5292, 5296, 5293, -1, 5291, 5296, 5286, -1, 5286, 5296, 5292, -1, 5290, 5298, 5282, -1, 5282, 5298, 5295, -1, 5295, 5299, 5291, -1, 5297, 5299, 5300, -1, 5296, 5299, 5297, -1, 5291, 5299, 5296, -1, 4749, 5301, 4751, -1, 4751, 5301, 4753, -1, 5290, 5301, 5298, -1, 4753, 5301, 5294, -1, 5294, 5301, 5290, -1, 5298, 5302, 5295, -1, 5299, 5302, 5300, -1, 5300, 5302, 5303, -1, 4749, 3912, 5304, -1, 1871, 5305, 1872, -1, 5295, 5302, 5299, -1, 1872, 5305, 1873, -1, 5298, 5306, 5302, -1, 5303, 5306, 5304, -1, 4749, 5306, 5301, -1, 5272, 5305, 1871, -1, 5301, 5306, 5298, -1, 5304, 5306, 4749, -1, 5302, 5306, 5303, -1, 5273, 5307, 5272, -1, 5272, 5307, 5305, -1, 1873, 5278, 1874, -1, 5305, 5278, 1873, -1, 5274, 5283, 5273, -1, 5273, 5283, 5307, -1, 5305, 5285, 5278, -1, 5307, 5285, 5305, -1, 5275, 5281, 5274, -1, 5274, 5281, 5283, -1, 5283, 5284, 5307, -1, 5307, 5284, 5285, -1, 1874, 5279, 1875, -1, 1878, 1877, 5308, -1, 5308, 5288, 5309, -1, 1877, 5288, 5308, -1, 5309, 5293, 5310, -1, 5288, 5293, 5309, -1, 5310, 5297, 5311, -1, 5293, 5297, 5310, -1, 5311, 5300, 5312, -1, 5297, 5300, 5311, -1, 5312, 5303, 5313, -1, 5300, 5303, 5312, -1, 5313, 5304, 3914, -1, 5303, 5304, 5313, -1, 5304, 3912, 3914, -1, 5171, 5313, 3914, -1, 1884, 1882, 2178, -1, 5171, 5312, 5313, -1, 5171, 5311, 5312, -1, 1881, 5309, 5310, -1, 1881, 5308, 5309, -1, 1881, 1878, 5308, -1, 2169, 5314, 2084, -1, 2084, 5314, 5173, -1, 5173, 5314, 5171, -1, 2171, 5315, 2169, -1, 5314, 5315, 5171, -1, 2169, 5315, 5314, -1, 2173, 5316, 2171, -1, 5315, 5316, 5171, -1, 2171, 5316, 5315, -1, 5171, 5316, 5311, -1, 2175, 5317, 2173, -1, 5311, 5317, 5310, -1, 5316, 5317, 5311, -1, 2173, 5317, 5316, -1, 5310, 5317, 1881, -1, 2178, 5318, 2176, -1, 2176, 5318, 2175, -1, 5317, 5318, 1881, -1, 2175, 5318, 5317, -1, 1881, 5319, 1882, -1, 5318, 5319, 1881, -1, 1882, 5319, 2178, -1, 2178, 5319, 5318, -1, 2027, 5320, 2182, -1, 5320, 2185, 2182, -1, 5321, 1727, 5320, -1, 5320, 1727, 2185, -1, 5321, 1729, 1727, -1, 1733, 4239, 1735, -1, 4237, 4239, 1733, -1, 4239, 1737, 1735, -1, 4210, 5322, 5323, -1, 5323, 5322, 5321, -1, 1729, 5322, 1731, -1, 5321, 5322, 1729, -1, 4235, 5324, 4210, -1, 4210, 5324, 5322, -1, 1731, 5325, 1733, -1, 4237, 5325, 4235, -1, 5324, 5325, 5322, -1, 5322, 5325, 1731, -1, 1733, 5325, 4237, -1, 4235, 5325, 5324, -1, 4211, 4210, 5326, -1, 5326, 5323, 5327, -1, 4210, 5323, 5326, -1, 5327, 5321, 5328, -1, 5323, 5321, 5327, -1, 5321, 5320, 5328, -1, 5328, 2027, 2023, -1, 5320, 2027, 5328, -1, 5329, 5090, 3195, -1, 4214, 4213, 5330, -1, 5330, 4213, 5331, -1, 5331, 4213, 5332, -1, 5332, 4213, 5333, -1, 5329, 5334, 5090, -1, 5333, 5335, 5329, -1, 5329, 5335, 5334, -1, 4213, 5335, 5333, -1, 4213, 5336, 5335, -1, 4212, 5337, 4213, -1, 4213, 5337, 5336, -1, 5336, 5337, 4212, -1, 5090, 5338, 5092, -1, 5092, 5338, 2023, -1, 2023, 5338, 5328, -1, 5334, 5338, 5090, -1, 5328, 5339, 5327, -1, 5334, 5339, 5338, -1, 5338, 5339, 5328, -1, 5335, 5339, 5334, -1, 5327, 5340, 5326, -1, 5336, 5340, 5335, -1, 5339, 5340, 5327, -1, 4212, 5340, 5336, -1, 5335, 5340, 5339, -1, 4211, 5341, 4212, -1, 5326, 5341, 4211, -1, 5340, 5341, 5326, -1, 4212, 5341, 5340, -1, 4214, 5330, 4207, -1, 4207, 5330, 5342, -1, 5342, 5331, 5343, -1, 5330, 5331, 5342, -1, 5343, 5332, 5344, -1, 5331, 5332, 5343, -1, 5344, 5333, 5345, -1, 5332, 5333, 5344, -1, 5345, 5329, 5346, -1, 5333, 5329, 5345, -1, 5346, 3195, 3196, -1, 5329, 3195, 5346, -1, 4231, 5347, 4229, -1, 4229, 5347, 766, -1, 766, 5347, 764, -1, 5348, 5347, 4231, -1, 764, 5347, 5348, -1, 4207, 5349, 4231, -1, 5342, 5349, 4207, -1, 5343, 5349, 5342, -1, 4231, 5349, 5348, -1, 5350, 5349, 5343, -1, 5348, 5349, 5351, -1, 5351, 5349, 5350, -1, 5352, 3192, 3191, -1, 3194, 5346, 3196, -1, 3192, 5353, 3193, -1, 5352, 5353, 3192, -1, 757, 5354, 5355, -1, 5355, 5354, 5352, -1, 5352, 5354, 5353, -1, 758, 5356, 757, -1, 757, 5356, 5354, -1, 3193, 5357, 3194, -1, 3194, 5357, 5346, -1, 5353, 5357, 3193, -1, 760, 5358, 758, -1, 758, 5358, 5356, -1, 5346, 5359, 5345, -1, 5354, 5359, 5353, -1, 5353, 5359, 5357, -1, 5357, 5359, 5346, -1, 5354, 5360, 5359, -1, 5356, 5360, 5354, -1, 5359, 5360, 5345, -1, 762, 5351, 760, -1, 760, 5351, 5358, -1, 5345, 5361, 5344, -1, 5358, 5361, 5356, -1, 5356, 5361, 5360, -1, 5360, 5361, 5345, -1, 764, 5348, 762, -1, 762, 5348, 5351, -1, 5344, 5350, 5343, -1, 5358, 5350, 5361, -1, 5361, 5350, 5344, -1, 5351, 5350, 5358, -1, 3191, 3184, 5352, -1, 3184, 4269, 5352, -1, 5352, 4270, 5355, -1, 4269, 4270, 5352, -1, 5355, 755, 757, -1, 4270, 755, 5355, -1, 2160, 5153, 2186, -1, 1818, 752, 754, -1, 1818, 750, 752, -1, 5151, 5362, 5363, -1, 5151, 3919, 5362, -1, 1724, 5364, 1951, -1, 1951, 5364, 1818, -1, 1722, 5364, 1724, -1, 1720, 5365, 1722, -1, 5364, 5365, 1818, -1, 1722, 5365, 5364, -1, 1718, 5366, 1720, -1, 1720, 5366, 5365, -1, 1716, 5367, 1718, -1, 1718, 5367, 5366, -1, 1714, 5368, 1716, -1, 1716, 5368, 5367, -1, 2189, 5369, 1714, -1, 1714, 5369, 5368, -1, 5151, 5370, 5153, -1, 2186, 5370, 2189, -1, 2189, 5370, 5369, -1, 5153, 5370, 2186, -1, 5369, 5370, 5151, -1, 750, 5371, 748, -1, 748, 5371, 746, -1, 746, 5371, 745, -1, 745, 5371, 5363, -1, 5365, 5371, 1818, -1, 5366, 5371, 5365, -1, 5369, 5371, 5368, -1, 5367, 5371, 5366, -1, 5151, 5371, 5369, -1, 5368, 5371, 5367, -1, 1818, 5371, 750, -1, 5363, 5371, 5151, -1, 3919, 3917, 5362, -1, 5362, 5372, 5363, -1, 3917, 5372, 5362, -1, 5363, 5373, 745, -1, 5372, 5373, 5363, -1, 5373, 743, 745, -1, 732, 5374, 736, -1, 5375, 5374, 5376, -1, 5376, 5374, 732, -1, 5377, 5374, 5375, -1, 5373, 5378, 743, -1, 743, 5378, 744, -1, 744, 5378, 5379, -1, 5379, 5380, 5381, -1, 5381, 5380, 5382, -1, 736, 5383, 740, -1, 5377, 5383, 5374, -1, 5374, 5383, 736, -1, 5382, 5383, 5377, -1, 5373, 5384, 5378, -1, 5379, 5385, 5380, -1, 5378, 5385, 5379, -1, 4793, 5386, 4795, -1, 5372, 5386, 5373, -1, 4795, 5386, 5372, -1, 5373, 5386, 5384, -1, 740, 5387, 742, -1, 5383, 5387, 740, -1, 5380, 5387, 5382, -1, 5382, 5387, 5383, -1, 2016, 732, 734, -1, 5384, 5388, 5378, -1, 5378, 5388, 5385, -1, 742, 5389, 716, -1, 5387, 5389, 742, -1, 5385, 5389, 5380, -1, 5380, 5389, 5387, -1, 4790, 5390, 4793, -1, 3917, 4795, 5372, -1, 4793, 5390, 5386, -1, 5386, 5390, 5384, -1, 5384, 5390, 5388, -1, 716, 5391, 715, -1, 5389, 5391, 716, -1, 5388, 5391, 5385, -1, 5385, 5391, 5389, -1, 4788, 5392, 4790, -1, 5388, 5392, 5391, -1, 4790, 5392, 5390, -1, 715, 5392, 4788, -1, 5390, 5392, 5388, -1, 5391, 5392, 715, -1, 4788, 730, 715, -1, 751, 5393, 753, -1, 753, 5393, 1783, -1, 749, 5394, 751, -1, 751, 5394, 5393, -1, 1783, 5375, 1784, -1, 1784, 5375, 2018, -1, 5393, 5375, 1783, -1, 747, 5381, 749, -1, 749, 5381, 5394, -1, 5393, 5377, 5375, -1, 5394, 5377, 5393, -1, 2018, 5376, 2016, -1, 5375, 5376, 2018, -1, 2016, 5376, 732, -1, 744, 5379, 747, -1, 747, 5379, 5381, -1, 5381, 5382, 5394, -1, 5394, 5382, 5377, -1, 731, 3922, 728, -1, 728, 5395, 723, -1, 3922, 5395, 728, -1, 723, 5396, 720, -1, 5395, 5396, 723, -1, 720, 5397, 708, -1, 5396, 5397, 720, -1, 708, 5398, 706, -1, 5397, 5398, 708, -1, 706, 5399, 725, -1, 5398, 5399, 706, -1, 725, 5400, 726, -1, 5399, 5400, 725, -1, 5400, 1869, 726, -1, 5401, 5402, 1839, -1, 5396, 5403, 5397, -1, 5397, 5403, 5404, -1, 5404, 5405, 5406, -1, 5406, 5405, 5407, -1, 5408, 5409, 5401, -1, 5401, 5409, 5402, -1, 1837, 5410, 1826, -1, 1826, 5410, 1824, -1, 1824, 5410, 5411, -1, 5402, 5410, 1837, -1, 4774, 5412, 3922, -1, 5395, 5412, 5396, -1, 3922, 5412, 5395, -1, 5396, 5412, 5403, -1, 5403, 5413, 5404, -1, 5404, 5413, 5405, -1, 5408, 5414, 5409, -1, 5407, 5414, 5408, -1, 5411, 5415, 5416, -1, 5410, 5415, 5411, -1, 5409, 5415, 5402, -1, 5402, 5415, 5410, -1, 4777, 5417, 4776, -1, 4776, 5417, 4774, -1, 4774, 5417, 5412, -1, 5412, 5417, 5403, -1, 5403, 5417, 5413, -1, 5405, 5418, 5407, -1, 5407, 5418, 5414, -1, 5416, 5419, 5420, -1, 5415, 5419, 5416, -1, 5414, 5419, 5409, -1, 5409, 5419, 5415, -1, 5413, 5421, 5405, -1, 5405, 5421, 5418, -1, 5418, 5422, 5414, -1, 5420, 5422, 5423, -1, 5419, 5422, 5420, -1, 5414, 5422, 5419, -1, 4781, 5424, 4779, -1, 4779, 5424, 4777, -1, 5413, 5424, 5421, -1, 4777, 5424, 5417, -1, 5417, 5424, 5413, -1, 5421, 5425, 5418, -1, 5422, 5425, 5423, -1, 5423, 5425, 5426, -1, 4781, 3199, 5427, -1, 1869, 5428, 1852, -1, 5418, 5425, 5422, -1, 1852, 5428, 1845, -1, 5421, 5429, 5425, -1, 5426, 5429, 5427, -1, 4781, 5429, 5424, -1, 5400, 5428, 1869, -1, 5424, 5429, 5421, -1, 5427, 5429, 4781, -1, 5425, 5429, 5426, -1, 5399, 5430, 5400, -1, 5400, 5430, 5428, -1, 1845, 5401, 1839, -1, 5428, 5401, 1845, -1, 5398, 5406, 5399, -1, 5399, 5406, 5430, -1, 5428, 5408, 5401, -1, 5430, 5408, 5428, -1, 5397, 5404, 5398, -1, 5398, 5404, 5406, -1, 5406, 5407, 5430, -1, 5430, 5407, 5408, -1, 1839, 5402, 1837, -1, 1824, 5411, 1829, -1, 1829, 5411, 5431, -1, 5431, 5416, 5432, -1, 5411, 5416, 5431, -1, 5432, 5420, 5433, -1, 5416, 5420, 5432, -1, 5433, 5423, 5434, -1, 5420, 5423, 5433, -1, 5434, 5426, 5435, -1, 5423, 5426, 5434, -1, 5435, 5427, 5436, -1, 5426, 5427, 5435, -1, 5436, 3199, 3204, -1, 5427, 3199, 5436, -1, 3204, 5437, 5436, -1, 5437, 5435, 5436, -1, 5431, 4220, 1829, -1, 5438, 5439, 5440, -1, 5440, 5439, 5437, -1, 5435, 5439, 5434, -1, 5437, 5439, 5435, -1, 5434, 5441, 5433, -1, 5439, 5441, 5434, -1, 5442, 5443, 5438, -1, 5439, 5443, 5441, -1, 5438, 5443, 5439, -1, 5432, 5444, 5431, -1, 5433, 5444, 5432, -1, 4220, 5444, 4218, -1, 5441, 5444, 5433, -1, 5431, 5444, 4220, -1, 4205, 5445, 5442, -1, 4218, 5445, 4215, -1, 4215, 5445, 4205, -1, 5442, 5445, 5443, -1, 5443, 5445, 5441, -1, 5441, 5445, 5444, -1, 5444, 5445, 4218, -1, 4203, 4205, 5446, -1, 5446, 5442, 5447, -1, 4205, 5442, 5446, -1, 5447, 5438, 5448, -1, 5442, 5438, 5447, -1, 5448, 5440, 5449, -1, 5438, 5440, 5448, -1, 5449, 5437, 3198, -1, 5440, 5437, 5449, -1, 5437, 3204, 3198, -1, 5448, 5450, 5447, -1, 5451, 5450, 5452, -1, 5453, 5450, 5448, -1, 5452, 5450, 5453, -1, 4223, 5454, 5455, -1, 5456, 5454, 5457, -1, 5455, 5454, 5456, -1, 5451, 5458, 5450, -1, 5457, 5458, 5451, -1, 5450, 5458, 5447, -1, 4226, 5459, 4224, -1, 4224, 5459, 4223, -1, 4223, 5459, 5454, -1, 5447, 5460, 5446, -1, 4226, 5460, 5459, -1, 5446, 5460, 4226, -1, 5454, 5460, 5457, -1, 5458, 5460, 5447, -1, 5457, 5460, 5458, -1, 5459, 5460, 5454, -1, 4196, 4221, 5461, -1, 4226, 4203, 5446, -1, 5462, 5463, 5464, -1, 5464, 5463, 3205, -1, 3205, 5463, 3203, -1, 5462, 5465, 5463, -1, 3203, 5466, 3201, -1, 5463, 5466, 3203, -1, 5467, 5468, 5469, -1, 5469, 5468, 5462, -1, 5462, 5468, 5465, -1, 5465, 5452, 5463, -1, 5463, 5452, 5466, -1, 5470, 5456, 5467, -1, 5467, 5456, 5468, -1, 3201, 5471, 3197, -1, 3197, 5471, 3198, -1, 3198, 5471, 5449, -1, 5466, 5471, 3201, -1, 5465, 5451, 5452, -1, 5468, 5451, 5465, -1, 4223, 5455, 4221, -1, 5461, 5455, 5470, -1, 5470, 5455, 5456, -1, 4221, 5455, 5461, -1, 5449, 5453, 5448, -1, 5466, 5453, 5471, -1, 5452, 5453, 5466, -1, 5471, 5453, 5449, -1, 5456, 5457, 5468, -1, 5468, 5457, 5451, -1, 3205, 3206, 5464, -1, 5464, 5472, 5462, -1, 3206, 5472, 5464, -1, 5462, 5473, 5469, -1, 5472, 5473, 5462, -1, 5469, 5474, 5467, -1, 5473, 5474, 5469, -1, 5467, 5475, 5470, -1, 5474, 5475, 5467, -1, 5470, 5476, 5461, -1, 5475, 5476, 5470, -1, 5461, 5477, 4196, -1, 5476, 5477, 5461, -1, 5477, 4199, 4196, -1, 5478, 3208, 3209, -1, 3208, 5472, 3207, -1, 3207, 5472, 3206, -1, 5478, 5472, 3208, -1, 5479, 5473, 5478, -1, 5478, 5473, 5472, -1, 5480, 5474, 5481, -1, 5481, 5474, 5479, -1, 5479, 5474, 5473, -1, 5482, 5475, 5480, -1, 5480, 5475, 5474, -1, 5483, 5476, 5482, -1, 5482, 5476, 5475, -1, 4230, 4228, 5483, -1, 4228, 5477, 5483, -1, 5483, 5477, 5476, -1, 4228, 4199, 5477, -1, 5083, 5478, 3209, -1, 4208, 4233, 5484, -1, 4232, 4230, 5483, -1, 5485, 5486, 5086, -1, 5086, 5486, 5084, -1, 5084, 5486, 5083, -1, 5083, 5486, 5478, -1, 5487, 5488, 5485, -1, 5478, 5488, 5479, -1, 5486, 5488, 5478, -1, 5485, 5488, 5486, -1, 5489, 5490, 5487, -1, 5479, 5490, 5481, -1, 5487, 5490, 5488, -1, 5488, 5490, 5479, -1, 5491, 5492, 5493, -1, 5493, 5492, 5489, -1, 5481, 5492, 5480, -1, 5489, 5492, 5490, -1, 5490, 5492, 5481, -1, 5494, 5495, 5491, -1, 5492, 5495, 5480, -1, 5491, 5495, 5492, -1, 5496, 5497, 5494, -1, 5480, 5497, 5482, -1, 5495, 5497, 5480, -1, 5494, 5497, 5495, -1, 4232, 5498, 4233, -1, 5484, 5498, 5496, -1, 5482, 5498, 5483, -1, 5496, 5498, 5497, -1, 5497, 5498, 5482, -1, 4233, 5498, 5484, -1, 5483, 5498, 4232, -1, 5086, 5088, 5485, -1, 4208, 5499, 4206, -1, 4206, 5499, 5500, -1, 5500, 5499, 5501, -1, 5484, 5499, 4208, -1, 5496, 5499, 5484, -1, 5494, 5502, 5496, -1, 5499, 5502, 5501, -1, 5496, 5502, 5499, -1, 5501, 5503, 5504, -1, 5491, 5503, 5494, -1, 5502, 5503, 5501, -1, 5494, 5503, 5502, -1, 5504, 5505, 5506, -1, 5506, 5505, 5507, -1, 5493, 5505, 5491, -1, 5503, 5505, 5504, -1, 5491, 5505, 5503, -1, 5507, 5508, 5509, -1, 5493, 5508, 5505, -1, 5505, 5508, 5507, -1, 5509, 5510, 5511, -1, 5489, 5510, 5493, -1, 5493, 5510, 5508, -1, 5508, 5510, 5509, -1, 5511, 5512, 5513, -1, 5487, 5512, 5489, -1, 5489, 5512, 5510, -1, 5510, 5512, 5511, -1, 5513, 5514, 2029, -1, 2029, 5514, 5088, -1, 5485, 5514, 5487, -1, 5512, 5514, 5513, -1, 5088, 5514, 5485, -1, 5487, 5514, 5512, -1, 4209, 4206, 5515, -1, 5515, 5500, 5516, -1, 4206, 5500, 5515, -1, 5516, 5501, 5517, -1, 5500, 5501, 5516, -1, 5517, 5504, 5518, -1, 5501, 5504, 5517, -1, 5518, 5506, 5519, -1, 5504, 5506, 5518, -1, 5519, 5507, 5520, -1, 5506, 5507, 5519, -1, 5520, 5509, 5521, -1, 5507, 5509, 5520, -1, 5521, 5511, 5522, -1, 5509, 5511, 5521, -1, 5522, 5513, 5523, -1, 5511, 5513, 5522, -1, 5523, 2029, 2031, -1, 5513, 2029, 5523, -1, 5524, 5525, 5526, -1, 5527, 5525, 5528, -1, 5528, 5525, 5524, -1, 5519, 5529, 5518, -1, 5527, 5529, 5525, -1, 5525, 5529, 5519, -1, 5527, 5530, 5529, -1, 5529, 5530, 5518, -1, 5518, 5531, 5517, -1, 5517, 5531, 5532, -1, 5532, 5531, 5527, -1, 5530, 5531, 5518, -1, 5532, 5516, 5517, -1, 5527, 5531, 5530, -1, 5515, 4234, 4209, -1, 2191, 5523, 2031, -1, 4238, 5527, 2019, -1, 5527, 5533, 5532, -1, 5516, 5533, 5515, -1, 5532, 5533, 5516, -1, 5515, 5534, 4234, -1, 5527, 5534, 5533, -1, 5533, 5534, 5515, -1, 4234, 5535, 4236, -1, 4236, 5535, 4238, -1, 5527, 5535, 5534, -1, 4238, 5535, 5527, -1, 5534, 5535, 4234, -1, 2193, 5536, 2191, -1, 5523, 5536, 5522, -1, 2191, 5536, 5523, -1, 5522, 5536, 2193, -1, 2195, 5537, 2193, -1, 5521, 5537, 5520, -1, 5522, 5537, 5521, -1, 2193, 5537, 5522, -1, 2198, 5524, 2197, -1, 2197, 5524, 2195, -1, 2195, 5524, 5537, -1, 5537, 5524, 5520, -1, 2019, 5538, 2200, -1, 2200, 5538, 2198, -1, 5527, 5538, 2019, -1, 5520, 5526, 5519, -1, 5524, 5526, 5520, -1, 5538, 5528, 2198, -1, 5527, 5528, 5538, -1, 2198, 5528, 5524, -1, 5526, 5525, 5519, -1, 5539, 3578, 3577, -1, 5540, 5539, 3577, -1, 5541, 3577, 3522, -1, 5541, 5540, 3577, -1, 5542, 5541, 3522, -1, 5543, 5542, 3522, -1, 3521, 5543, 3522, -1, 4195, 3610, 3607, -1, 4195, 3607, 5544, -1, 5545, 4195, 5544, -1, 5546, 5544, 5547, -1, 5546, 5545, 5544, -1, 5548, 5547, 5549, -1, 5548, 5546, 5547, -1, 5550, 5548, 5549, -1, 5551, 5549, 5552, -1, 5551, 5550, 5549, -1, 5553, 5552, 5554, -1, 5553, 5551, 5552, -1, 5555, 5554, 5556, -1, 5555, 5553, 5554, -1, 5557, 5556, 4017, -1, 5557, 5555, 5556, -1, 4029, 5557, 4017, -1, 5558, 5544, 3607, -1, 5558, 3607, 3606, -1, 5559, 5547, 5544, -1, 5559, 5544, 5558, -1, 5560, 5549, 5547, -1, 5560, 5547, 5559, -1, 5561, 5554, 5552, -1, 5561, 5552, 5549, -1, 5561, 5549, 5560, -1, 5562, 5556, 5554, -1, 5562, 5554, 5561, -1, 5563, 4017, 5556, -1, 5563, 5556, 5562, -1, 4696, 4017, 5563, -1, 5564, 4696, 5563, -1, 5564, 5563, 5562, -1, 5564, 4695, 4696, -1, 5564, 4694, 4695, -1, 5564, 5562, 5565, -1, 5566, 5567, 5568, -1, 5566, 5568, 5569, -1, 5074, 5558, 3606, -1, 5570, 813, 814, -1, 5570, 811, 813, -1, 5570, 5571, 811, -1, 5572, 5567, 5566, -1, 5572, 5573, 5567, -1, 5574, 5571, 5570, -1, 5574, 5569, 5571, -1, 5575, 5573, 5572, -1, 5575, 5565, 5573, -1, 5576, 5566, 5569, -1, 5576, 5569, 5574, -1, 5577, 4694, 5564, -1, 5577, 5564, 5565, -1, 5577, 5565, 5575, -1, 5578, 5572, 5566, -1, 5578, 5566, 5576, -1, 5579, 816, 817, -1, 5579, 814, 816, -1, 5579, 5570, 814, -1, 5580, 5572, 5578, -1, 5580, 5575, 5572, -1, 5581, 5570, 5579, -1, 5581, 5574, 5570, -1, 5582, 5575, 5580, -1, 5582, 4693, 4694, -1, 5582, 4694, 5577, -1, 5582, 5577, 5575, -1, 5583, 817, 819, -1, 5583, 5579, 817, -1, 5584, 5574, 5581, -1, 5585, 819, 821, -1, 5584, 5576, 5574, -1, 5586, 5581, 5579, -1, 5587, 819, 5585, -1, 5586, 5579, 5583, -1, 5586, 819, 5587, -1, 5586, 5583, 819, -1, 5588, 5576, 5584, -1, 5588, 5578, 5576, -1, 5589, 5584, 5581, -1, 5589, 5586, 5587, -1, 5589, 5587, 5590, -1, 5591, 4689, 5592, -1, 4012, 4689, 5591, -1, 5589, 5581, 5586, -1, 5593, 5580, 5578, -1, 5593, 5578, 5588, -1, 5594, 5074, 5075, -1, 5594, 5558, 5074, -1, 5595, 5589, 5590, -1, 5595, 5590, 5592, -1, 5595, 5584, 5589, -1, 5568, 5559, 5558, -1, 5595, 5588, 5584, -1, 5568, 5594, 5075, -1, 5595, 5592, 4689, -1, 5568, 5558, 5594, -1, 5596, 5582, 5580, -1, 5596, 5580, 5593, -1, 5596, 4691, 4693, -1, 5567, 5560, 5559, -1, 5596, 4693, 5582, -1, 5597, 5593, 5588, -1, 5597, 5588, 5595, -1, 5567, 5559, 5568, -1, 5597, 5595, 4689, -1, 5598, 5596, 5593, -1, 5598, 4689, 4691, -1, 5573, 5561, 5560, -1, 5598, 5593, 5597, -1, 5598, 4691, 5596, -1, 5598, 5597, 4689, -1, 5573, 5560, 5567, -1, 5571, 5075, 811, -1, 5565, 5562, 5561, -1, 5565, 5561, 5573, -1, 5569, 5568, 5075, -1, 5569, 5075, 5571, -1, 822, 5585, 821, -1, 5599, 822, 824, -1, 5599, 5585, 822, -1, 5600, 5587, 5585, -1, 5600, 5585, 5599, -1, 5601, 824, 826, -1, 5601, 826, 5602, -1, 5601, 5599, 824, -1, 5603, 5590, 5587, -1, 5603, 5587, 5600, -1, 5604, 5605, 5606, -1, 5604, 5602, 5605, -1, 5604, 5600, 5599, -1, 5604, 5599, 5601, -1, 5604, 5601, 5602, -1, 5607, 5592, 5590, -1, 5607, 5590, 5603, -1, 5608, 5603, 5600, -1, 5608, 5604, 5606, -1, 5608, 5600, 5604, -1, 5609, 5591, 5592, -1, 5609, 5592, 5607, -1, 5610, 5611, 5612, -1, 5610, 5606, 5611, -1, 5610, 5603, 5608, -1, 5610, 5607, 5603, -1, 5610, 5608, 5606, -1, 5613, 4012, 5591, -1, 5613, 4010, 4012, -1, 5613, 4013, 4010, -1, 5613, 5591, 5609, -1, 5614, 5610, 5612, -1, 5614, 5609, 5607, -1, 5614, 5607, 5610, -1, 5615, 5616, 4008, -1, 5615, 5612, 5616, -1, 5615, 4008, 4013, -1, 5615, 5609, 5614, -1, 5615, 4013, 5613, -1, 5615, 5614, 5612, -1, 5615, 5613, 5609, -1, 826, 3712, 5617, -1, 5602, 826, 5617, -1, 5605, 5617, 5618, -1, 5605, 5602, 5617, -1, 5606, 5618, 5619, -1, 5606, 5605, 5618, -1, 5611, 5619, 5620, -1, 5611, 5606, 5619, -1, 5612, 5620, 5621, -1, 5612, 5611, 5620, -1, 5616, 5621, 5622, -1, 5616, 5612, 5621, -1, 4008, 5622, 4009, -1, 4008, 5616, 5622, -1, 5623, 5624, 5625, -1, 5623, 5625, 5626, -1, 5627, 5621, 5620, -1, 5627, 5620, 5628, -1, 5629, 3709, 690, -1, 5629, 690, 693, -1, 5629, 5626, 3709, -1, 5630, 5628, 5631, -1, 5630, 5631, 5632, -1, 5633, 5624, 5623, -1, 5633, 5632, 5624, -1, 5634, 4009, 5622, -1, 5634, 5622, 5621, -1, 5634, 4711, 4009, -1, 5634, 5621, 5627, -1, 5635, 693, 695, -1, 5635, 5629, 693, -1, 5635, 5623, 5626, -1, 5635, 5626, 5629, -1, 5636, 5627, 5628, -1, 5636, 5628, 5630, -1, 5637, 5632, 5633, -1, 5637, 5630, 5632, -1, 5638, 695, 697, -1, 5638, 5633, 5623, -1, 5638, 5635, 695, -1, 5638, 5623, 5635, -1, 5639, 4709, 4711, -1, 5639, 5627, 5636, -1, 5639, 4711, 5634, -1, 5639, 5634, 5627, -1, 5640, 5636, 5630, -1, 5640, 5630, 5637, -1, 5641, 697, 699, -1, 5641, 5637, 5633, -1, 5641, 5633, 5638, -1, 5641, 5638, 697, -1, 5642, 5639, 5636, -1, 5642, 4707, 4709, -1, 5642, 4709, 5639, -1, 5642, 5636, 5640, -1, 5643, 5640, 5637, -1, 5643, 699, 701, -1, 5643, 701, 5644, -1, 5643, 5637, 5641, -1, 5643, 5641, 699, -1, 5645, 4707, 5642, -1, 5645, 5642, 5640, -1, 5645, 5643, 5644, -1, 5645, 5644, 5646, -1, 3902, 4705, 5646, -1, 5645, 4705, 4707, -1, 5645, 5640, 5643, -1, 5645, 5646, 4705, -1, 5647, 5617, 3712, -1, 5647, 3713, 3711, -1, 5647, 3712, 3713, -1, 5648, 5618, 5617, -1, 5648, 5617, 5647, -1, 5625, 3711, 3710, -1, 5625, 5647, 3711, -1, 5631, 5619, 5618, -1, 5631, 5618, 5648, -1, 5624, 5648, 5647, -1, 5624, 5647, 5625, -1, 5626, 3710, 3709, -1, 5626, 5625, 3710, -1, 5628, 5620, 5619, -1, 5628, 5619, 5631, -1, 5632, 5631, 5648, -1, 5632, 5648, 5624, -1, 5644, 701, 700, -1, 5644, 700, 5649, -1, 5646, 5649, 5650, -1, 5646, 5644, 5649, -1, 3902, 5650, 864, -1, 3902, 5646, 5650, -1, 5651, 5652, 5653, -1, 5654, 848, 854, -1, 5654, 854, 5655, -1, 5654, 5655, 5656, -1, 5657, 3707, 5658, -1, 5654, 5656, 5659, -1, 5657, 5658, 3706, -1, 5660, 5650, 5649, -1, 3708, 692, 691, -1, 5661, 5662, 5663, -1, 5660, 5649, 5664, -1, 5661, 5663, 5651, -1, 5665, 3707, 5657, -1, 5665, 5657, 3706, -1, 5666, 5667, 5662, -1, 5666, 5662, 5661, -1, 5665, 5668, 3707, -1, 5669, 858, 862, -1, 5670, 5667, 5666, -1, 5669, 862, 864, -1, 5669, 864, 5650, -1, 5670, 5671, 5667, -1, 5669, 5650, 5660, -1, 5672, 5668, 5665, -1, 5672, 5673, 5668, -1, 5674, 3701, 3703, -1, 5675, 5676, 5673, -1, 5675, 5673, 5672, -1, 5674, 5677, 3701, -1, 5678, 5676, 5675, -1, 5678, 5664, 5676, -1, 5679, 5653, 5677, -1, 5680, 3706, 3705, -1, 5679, 5677, 5674, -1, 5681, 848, 5654, -1, 5681, 844, 848, -1, 5681, 5659, 5671, -1, 5682, 5660, 5664, -1, 5681, 5654, 5659, -1, 5681, 5671, 5670, -1, 5682, 5664, 5678, -1, 5683, 5653, 5679, -1, 5683, 5651, 5653, -1, 5684, 3706, 5680, -1, 5684, 5680, 3705, -1, 5685, 5661, 5651, -1, 5686, 3706, 5684, -1, 5686, 5665, 3706, -1, 5685, 5651, 5683, -1, 5687, 858, 5669, -1, 5687, 5669, 5660, -1, 5687, 5660, 5682, -1, 5688, 5666, 5661, -1, 5688, 5661, 5685, -1, 5689, 5665, 5686, -1, 5689, 5672, 5665, -1, 5690, 5666, 5688, -1, 5690, 5670, 5666, -1, 5691, 5672, 5689, -1, 5691, 5675, 5672, -1, 5692, 3702, 3748, -1, 5692, 3703, 3702, -1, 5693, 5675, 5691, -1, 5692, 5674, 3703, -1, 5693, 5678, 5675, -1, 5694, 840, 844, -1, 5694, 844, 5681, -1, 5694, 5681, 5670, -1, 5694, 5670, 5690, -1, 5695, 3748, 3747, -1, 5696, 3705, 3704, -1, 5695, 5679, 5674, -1, 5695, 5692, 3748, -1, 5695, 5674, 5692, -1, 5656, 5682, 5678, -1, 5697, 3747, 3745, -1, 5697, 5679, 5695, -1, 5697, 5683, 5679, -1, 5656, 5678, 5693, -1, 5652, 5684, 3705, -1, 5697, 5695, 3747, -1, 5652, 3705, 5696, -1, 5698, 5697, 3745, -1, 5698, 5683, 5697, -1, 5698, 3745, 3742, -1, 5698, 5685, 5683, -1, 5655, 854, 858, -1, 5699, 3743, 3744, -1, 5699, 3742, 3743, -1, 5655, 5687, 5682, -1, 5699, 5685, 5698, -1, 5655, 858, 5687, -1, 5699, 5698, 3742, -1, 5655, 5682, 5656, -1, 5699, 5688, 5685, -1, 5700, 3744, 3746, -1, 5700, 5699, 3744, -1, 5700, 5688, 5699, -1, 5663, 5686, 5684, -1, 5700, 5690, 5688, -1, 5663, 5684, 5652, -1, 5701, 3746, 836, -1, 5701, 5690, 5700, -1, 5701, 836, 840, -1, 5701, 5700, 3746, -1, 5701, 840, 5694, -1, 5662, 5686, 5663, -1, 5702, 3708, 3707, -1, 5701, 5694, 5690, -1, 5702, 692, 3708, -1, 5662, 5689, 5686, -1, 5667, 5689, 5662, -1, 5667, 5691, 5689, -1, 5703, 694, 692, -1, 5703, 5702, 3707, -1, 5703, 692, 5702, -1, 5671, 5691, 5667, -1, 5668, 696, 694, -1, 5671, 5693, 5691, -1, 5668, 5703, 3707, -1, 5668, 694, 5703, -1, 5677, 5696, 3704, -1, 5677, 3704, 3701, -1, 5673, 698, 696, -1, 5673, 696, 5668, -1, 5653, 5652, 5696, -1, 5676, 700, 698, -1, 5676, 698, 5673, -1, 5653, 5696, 5677, -1, 5664, 5649, 700, -1, 5659, 5656, 5693, -1, 5664, 700, 5676, -1, 5659, 5693, 5671, -1, 5651, 5663, 5652, -1, 5658, 3707, 3706, -1, 5704, 5705, 5706, -1, 5707, 3796, 5708, -1, 5704, 5709, 5705, -1, 5710, 5709, 5704, -1, 5711, 5712, 5713, -1, 3789, 679, 678, -1, 5711, 5713, 5714, -1, 5710, 5715, 5709, -1, 5716, 5715, 5710, -1, 680, 679, 3789, -1, 5717, 5708, 5718, -1, 5716, 5719, 5715, -1, 5720, 3791, 3792, -1, 5717, 3795, 5707, -1, 5717, 5707, 5708, -1, 5720, 5721, 3791, -1, 5717, 5722, 3795, -1, 5723, 829, 828, -1, 5723, 831, 829, -1, 5724, 851, 846, -1, 5723, 5725, 5712, -1, 5724, 5726, 5719, -1, 5723, 828, 5725, -1, 5724, 5716, 851, -1, 5723, 5712, 5711, -1, 5724, 5719, 5716, -1, 5724, 846, 5726, -1, 5727, 5718, 5728, -1, 5727, 5729, 5722, -1, 5727, 5717, 5718, -1, 5730, 5721, 5720, -1, 5727, 5722, 5717, -1, 5730, 5706, 5721, -1, 5731, 5728, 5732, -1, 5731, 5727, 5728, -1, 5731, 5714, 5729, -1, 5733, 5704, 5706, -1, 5731, 5729, 5727, -1, 5733, 5706, 5730, -1, 5734, 5732, 5735, -1, 5734, 5714, 5731, -1, 5736, 5704, 5733, -1, 5736, 5710, 5704, -1, 5734, 5711, 5714, -1, 5734, 5731, 5732, -1, 5737, 5738, 3898, -1, 5739, 5710, 5736, -1, 5737, 5735, 5738, -1, 5737, 3898, 831, -1, 5739, 5716, 5710, -1, 5737, 831, 5723, -1, 5739, 851, 5716, -1, 5737, 5723, 5711, -1, 5737, 5734, 5735, -1, 5740, 3793, 3794, -1, 5737, 5711, 5734, -1, 5740, 3792, 3793, -1, 5740, 5720, 3792, -1, 5741, 5739, 853, -1, 5741, 851, 5739, -1, 5741, 853, 851, -1, 5742, 5720, 5740, -1, 5742, 5730, 5720, -1, 5743, 5730, 5742, -1, 5743, 5733, 5730, -1, 5744, 5733, 5743, -1, 5744, 5736, 5733, -1, 5745, 5739, 5736, -1, 5745, 853, 5739, -1, 5745, 5736, 5744, -1, 5746, 5740, 3794, -1, 5747, 853, 5745, -1, 5747, 5745, 857, -1, 5747, 857, 853, -1, 5748, 5740, 5746, -1, 5748, 5742, 5740, -1, 5749, 5742, 5748, -1, 5749, 5743, 5742, -1, 5750, 3790, 3791, -1, 5750, 3789, 3790, -1, 5713, 5743, 5749, -1, 5713, 5744, 5743, -1, 5712, 5745, 5744, -1, 5712, 857, 5745, -1, 5712, 5744, 5713, -1, 5705, 680, 3789, -1, 5751, 3794, 3795, -1, 5705, 3789, 5750, -1, 5709, 682, 680, -1, 5709, 680, 5705, -1, 5751, 5746, 3794, -1, 5715, 684, 682, -1, 5725, 857, 5712, -1, 5725, 828, 857, -1, 5715, 682, 5709, -1, 5719, 686, 684, -1, 5722, 5751, 3795, -1, 5719, 684, 5715, -1, 5722, 5746, 5751, -1, 5722, 5748, 5746, -1, 5721, 5750, 3791, -1, 5729, 5749, 5748, -1, 5726, 688, 686, -1, 5726, 846, 688, -1, 5726, 686, 5719, -1, 5729, 5748, 5722, -1, 5706, 5750, 5721, -1, 5714, 5713, 5749, -1, 5706, 5705, 5750, -1, 5714, 5749, 5729, -1, 5707, 3795, 3796, -1, 5708, 3796, 3815, -1, 5708, 5752, 5753, -1, 5708, 3815, 5752, -1, 5718, 5753, 5754, -1, 5718, 5708, 5753, -1, 5728, 5754, 5755, -1, 5728, 5718, 5754, -1, 5732, 5755, 5756, -1, 5732, 5728, 5755, -1, 5735, 5756, 5757, -1, 5735, 5732, 5756, -1, 5738, 5757, 3901, -1, 5738, 5735, 5757, -1, 3898, 5738, 3901, -1, 5758, 3831, 3819, -1, 5758, 3819, 5759, -1, 5760, 5759, 5761, -1, 5760, 3831, 5758, -1, 5760, 5758, 5759, -1, 5762, 5761, 5763, -1, 5762, 3831, 5760, -1, 5762, 5764, 3831, -1, 5762, 5760, 5761, -1, 5765, 5763, 5766, -1, 5765, 5767, 5764, -1, 5765, 5762, 5763, -1, 5765, 5764, 5762, -1, 3820, 5756, 5755, -1, 5768, 5766, 5769, -1, 3820, 5755, 5754, -1, 3820, 5754, 5753, -1, 5768, 5767, 5765, -1, 3820, 5753, 5752, -1, 5768, 5765, 5766, -1, 3820, 5752, 3815, -1, 5768, 5770, 5767, -1, 5771, 5768, 5769, -1, 5771, 5770, 5768, -1, 5771, 5769, 5772, -1, 5771, 5772, 4697, -1, 5771, 4697, 5773, -1, 5771, 5773, 5770, -1, 2067, 4697, 5772, -1, 5774, 3820, 3830, -1, 5775, 5774, 3830, -1, 5775, 3820, 5774, -1, 5776, 3820, 5775, -1, 5776, 5775, 3830, -1, 5777, 5756, 3820, -1, 5777, 5776, 3830, -1, 5777, 3820, 5776, -1, 5778, 5757, 5756, -1, 5778, 5756, 5777, -1, 4703, 3901, 5757, -1, 4703, 5757, 5778, -1, 5779, 3830, 3832, -1, 5780, 3830, 5779, -1, 5780, 5779, 3832, -1, 5781, 5780, 3832, -1, 5781, 3830, 5780, -1, 5782, 3830, 5781, -1, 5782, 5777, 3830, -1, 5783, 5778, 5777, -1, 5783, 4703, 5778, -1, 5783, 5777, 5782, -1, 4701, 5783, 4699, -1, 4701, 4703, 5783, -1, 5784, 3832, 3831, -1, 5764, 3832, 5784, -1, 5764, 5784, 3831, -1, 5767, 5781, 3832, -1, 5767, 3832, 5764, -1, 5770, 5781, 5767, -1, 5770, 5782, 5781, -1, 5773, 4697, 4699, -1, 5773, 4699, 5783, -1, 5773, 5783, 5782, -1, 5773, 5782, 5770, -1, 3819, 3770, 5785, -1, 5759, 5785, 5786, -1, 5759, 3819, 5785, -1, 5761, 5786, 5787, -1, 5761, 5759, 5786, -1, 5763, 5787, 5788, -1, 5763, 5761, 5787, -1, 5766, 5788, 5789, -1, 5766, 5763, 5788, -1, 5769, 5789, 5790, -1, 5769, 5766, 5789, -1, 5772, 5790, 2075, -1, 5772, 5769, 5790, -1, 2067, 5772, 2075, -1, 5791, 5792, 5079, -1, 5791, 5080, 5792, -1, 5793, 5791, 5079, -1, 5793, 5080, 5791, -1, 5794, 5793, 5079, -1, 5794, 5080, 5793, -1, 5795, 5794, 5079, -1, 5795, 5080, 5794, -1, 5796, 5795, 5079, -1, 5796, 5080, 5795, -1, 5797, 5796, 5079, -1, 5797, 5080, 5796, -1, 5797, 5079, 5080, -1, 5798, 5079, 2077, -1, 5798, 2077, 5078, -1, 5799, 5798, 5078, -1, 5799, 5079, 5798, -1, 5800, 5799, 5078, -1, 5800, 5079, 5799, -1, 5801, 5800, 5078, -1, 5801, 5079, 5800, -1, 5802, 5801, 5078, -1, 5802, 5079, 5801, -1, 5803, 5802, 5078, -1, 5803, 5079, 5802, -1, 5804, 5078, 5079, -1, 5804, 5803, 5078, -1, 5804, 5079, 5803, -1, 2073, 657, 656, -1, 5805, 5078, 2078, -1, 5806, 5078, 5805, -1, 5807, 5078, 5806, -1, 5808, 5078, 5807, -1, 5082, 666, 665, -1, 5082, 669, 666, -1, 5809, 5808, 5077, -1, 5082, 673, 669, -1, 5809, 5078, 5808, -1, 5082, 675, 673, -1, 5810, 5809, 5077, -1, 5810, 5078, 5809, -1, 5811, 5077, 5078, -1, 5811, 5810, 5077, -1, 5811, 5078, 5810, -1, 5812, 2078, 2075, -1, 5812, 2075, 5790, -1, 5812, 5790, 5789, -1, 5812, 5789, 5788, -1, 5812, 5788, 5787, -1, 5812, 5805, 2078, -1, 5812, 5806, 5805, -1, 5812, 5807, 5806, -1, 5812, 5077, 5808, -1, 5812, 5808, 5807, -1, 5813, 5787, 5786, -1, 5813, 5812, 5787, -1, 5813, 5077, 5812, -1, 5814, 5786, 5785, -1, 5079, 2076, 2077, -1, 5814, 5077, 5813, -1, 5814, 5813, 5786, -1, 5815, 5785, 3770, -1, 5815, 5076, 5077, -1, 5815, 3770, 5076, -1, 5815, 5077, 5814, -1, 5815, 5814, 5785, -1, 2078, 5078, 2077, -1, 5816, 657, 2073, -1, 5817, 659, 657, -1, 5817, 657, 5816, -1, 5818, 662, 659, -1, 5818, 5817, 5081, -1, 5818, 659, 5817, -1, 5819, 665, 662, -1, 5819, 5082, 665, -1, 5819, 662, 5818, -1, 5819, 5818, 5081, -1, 5820, 5819, 5081, -1, 5820, 5082, 5819, -1, 5821, 5082, 5820, -1, 5821, 5820, 5081, -1, 5822, 5081, 5082, -1, 5822, 5821, 5081, -1, 5822, 5082, 5821, -1, 5823, 2073, 2074, -1, 5823, 5816, 2073, -1, 5824, 5081, 5817, -1, 5824, 5823, 5080, -1, 5824, 5816, 5823, -1, 5824, 5817, 5816, -1, 5825, 5081, 5824, -1, 5825, 5824, 5080, -1, 5826, 5081, 5825, -1, 5826, 5825, 5080, -1, 5827, 5081, 5826, -1, 5827, 5826, 5080, -1, 5828, 5827, 5080, -1, 5828, 5081, 5827, -1, 5829, 5080, 5081, -1, 5829, 5828, 5080, -1, 5829, 5081, 5828, -1, 5792, 2074, 2076, -1, 5792, 5080, 5823, -1, 5792, 2076, 5079, -1, 5792, 5823, 2074, -1, 5032, 4192, 4195, -1, 5032, 4195, 5545, -1, 5033, 5545, 5546, -1, 5033, 5032, 5545, -1, 5034, 5546, 5548, -1, 5034, 5033, 5546, -1, 4026, 5557, 4029, -1, 4026, 5555, 5557, -1, 5035, 5550, 5551, -1, 5035, 5548, 5550, -1, 5035, 5034, 5548, -1, 5036, 5553, 5555, -1, 5036, 5551, 5553, -1, 5036, 5555, 4026, -1, 5036, 5035, 5551, -1, 5037, 4026, 4025, -1, 5037, 5036, 4026, -1, 5038, 4025, 4023, -1, 5038, 5037, 4025, -1, 5039, 4023, 4024, -1, 5039, 5038, 4023, -1, 2062, 4024, 2065, -1, 2062, 5039, 4024, -1, 5830, 5831, 5832, -1, 5833, 5831, 5830, -1, 5832, 5834, 5835, -1, 5831, 5834, 5832, -1, 4727, 3843, 4724, -1, 4724, 3843, 4723, -1, 4723, 3843, 4721, -1, 4721, 3843, 4719, -1, 4719, 3843, 3536, -1, 5836, 3843, 4727, -1, 5837, 3843, 5836, -1, 5838, 3843, 5837, -1, 5835, 3843, 5838, -1, 5834, 3843, 5835, -1, 3536, 3842, 3539, -1, 3843, 3842, 3536, -1, 4167, 4168, 3842, -1, 3842, 4171, 3539, -1, 4168, 4171, 3842, -1, 4171, 4060, 3539, -1, 3539, 4062, 3540, -1, 4060, 4062, 3539, -1, 3542, 4996, 2063, -1, 3543, 4997, 4996, -1, 3543, 4996, 3542, -1, 3541, 4062, 4997, -1, 3541, 4997, 3543, -1, 3540, 4062, 3541, -1, 2063, 3545, 3542, -1, 2063, 2064, 3545, -1, 2064, 4027, 3545, -1, 4028, 3546, 4027, -1, 3546, 3545, 4027, -1, 4030, 3546, 4028, -1, 4030, 5058, 3546, -1, 4031, 5058, 4030, -1, 4032, 5056, 5058, -1, 4032, 5058, 4031, -1, 4034, 5054, 5056, -1, 4034, 5056, 4032, -1, 4035, 5052, 5054, -1, 4035, 5054, 4034, -1, 4033, 3644, 5052, -1, 4033, 5052, 4035, -1, 3658, 4033, 4022, -1, 3658, 3644, 4033, -1, 4021, 3658, 4022, -1, 4021, 5071, 3658, -1, 4020, 5071, 4021, -1, 4019, 5069, 5071, -1, 4019, 5071, 4020, -1, 4018, 5067, 5069, -1, 4018, 5069, 4019, -1, 4016, 5066, 5067, -1, 4016, 5067, 4018, -1, 4015, 5064, 5066, -1, 4015, 5066, 4016, -1, 5062, 4690, 4014, -1, 5062, 4014, 5060, -1, 5063, 4692, 4690, -1, 5063, 4690, 5062, -1, 5064, 4015, 4692, -1, 5064, 4692, 5063, -1, 4011, 5060, 4014, -1, 4011, 3682, 5060, -1, 4007, 3682, 4011, -1, 3678, 3682, 4007, -1, 3903, 3669, 3681, -1, 4706, 3903, 3681, -1, 4708, 3681, 3680, -1, 4708, 4706, 3681, -1, 4710, 3680, 3684, -1, 4710, 4708, 3680, -1, 4712, 3684, 3683, -1, 4712, 4710, 3684, -1, 4007, 3683, 3678, -1, 4007, 4712, 3683, -1, 865, 3669, 3903, -1, 3670, 3669, 865, -1, 3690, 834, 833, -1, 3690, 833, 3686, -1, 3687, 837, 834, -1, 3687, 834, 3690, -1, 3689, 838, 837, -1, 3689, 837, 3687, -1, 3688, 841, 838, -1, 3688, 838, 3689, -1, 3691, 842, 841, -1, 3691, 841, 3688, -1, 3692, 847, 842, -1, 3692, 842, 3691, -1, 3694, 849, 847, -1, 3694, 855, 849, -1, 3694, 847, 3692, -1, 3695, 859, 855, -1, 3695, 860, 859, -1, 3695, 855, 3694, -1, 3670, 865, 863, -1, 3670, 863, 860, -1, 3670, 860, 3695, -1, 3564, 3686, 833, -1, 3666, 3686, 3564, -1, 3563, 3666, 3564, -1, 3563, 5061, 3666, -1, 3562, 5061, 3563, -1, 3561, 5065, 5061, -1, 3561, 5061, 3562, -1, 3560, 5065, 3561, -1, 3559, 5068, 5065, -1, 3559, 5065, 3560, -1, 3558, 5068, 3559, -1, 3556, 5070, 5068, -1, 3556, 5068, 3558, -1, 3555, 5072, 5070, -1, 3555, 5070, 3556, -1, 3557, 5073, 5072, -1, 3557, 3649, 5073, -1, 3557, 5072, 3555, -1, 3548, 3649, 3557, -1, 3641, 3649, 3548, -1, 3547, 3641, 3548, -1, 3547, 5053, 3641, -1, 3549, 5055, 5053, -1, 3549, 5053, 3547, -1, 3550, 5057, 5055, -1, 3550, 5059, 5057, -1, 3550, 5055, 3549, -1, 3551, 3544, 5059, -1, 3551, 5059, 3550, -1, 5839, 3551, 4111, -1, 5840, 3551, 5839, -1, 4111, 3551, 3575, -1, 5841, 3544, 5840, -1, 5842, 3544, 5841, -1, 5840, 3544, 3551, -1, 3537, 3544, 5843, -1, 5843, 3544, 5844, -1, 5844, 3544, 5845, -1, 5845, 3544, 5846, -1, 5846, 3544, 5842, -1, 2069, 98, 1831, -1, 83, 3910, 81, -1, 85, 3910, 83, -1, 87, 3910, 85, -1, 88, 3910, 87, -1, 89, 3910, 88, -1, 91, 3910, 89, -1, 92, 3910, 91, -1, 94, 3910, 92, -1, 95, 3910, 94, -1, 96, 3910, 95, -1, 98, 3910, 96, -1, 98, 4987, 3910, -1, 3910, 3909, 5847, -1, 3910, 5847, 81, -1, 2069, 2068, 4991, -1, 2069, 4991, 4989, -1, 2069, 4989, 4987, -1, 2069, 4987, 98, -1, 1832, 2069, 1831, -1, 1832, 4698, 2069, -1, 1821, 4698, 1832, -1, 1823, 4700, 4698, -1, 1823, 4698, 1821, -1, 1820, 4702, 4700, -1, 1820, 4700, 1823, -1, 1822, 4704, 4702, -1, 1822, 4702, 1820, -1, 1810, 3899, 4704, -1, 1810, 4704, 1822, -1, 3900, 1810, 1804, -1, 3900, 3899, 1810, -1, 1804, 830, 3900, -1, 1803, 830, 1804, -1, 1802, 827, 830, -1, 1802, 830, 1803, -1, 1801, 861, 827, -1, 1801, 827, 1802, -1, 1800, 856, 861, -1, 1800, 861, 1801, -1, 1797, 852, 856, -1, 1797, 850, 852, -1, 1797, 856, 1800, -1, 1789, 845, 850, -1, 1789, 850, 1797, -1, 1791, 843, 845, -1, 1791, 845, 1789, -1, 1790, 839, 843, -1, 1790, 843, 1791, -1, 1796, 832, 839, -1, 1796, 839, 1790, -1, 1798, 835, 832, -1, 1798, 832, 1796, -1, 1798, 1752, 835, -1, 835, 1752, 3574, -1, 1750, 3574, 1752, -1, 1750, 3573, 3574, -1, 1748, 3572, 3573, -1, 1748, 3573, 1750, -1, 1746, 3571, 3572, -1, 1746, 3572, 1748, -1, 1744, 3570, 3571, -1, 1744, 3571, 1746, -1, 1742, 3569, 3570, -1, 1742, 3570, 1744, -1, 1740, 3568, 3569, -1, 1740, 3569, 1742, -1, 2167, 3567, 3568, -1, 2167, 3568, 1740, -1, 2164, 3566, 3567, -1, 2164, 3567, 2167, -1, 2033, 3565, 3566, -1, 2033, 3566, 2164, -1, 3565, 603, 602, -1, 2033, 603, 3565, -1, 5848, 5849, 3554, -1, 5849, 3297, 3554, -1, 3297, 3576, 3554, -1, 3297, 4100, 3576, -1, 3297, 5850, 4100, -1, 3297, 5851, 5850, -1, 3297, 5852, 5851, -1, 3297, 5853, 5852, -1, 3297, 5854, 5853, -1, 3297, 3400, 4129, -1, 3297, 4129, 5855, -1, 3297, 5855, 5856, -1, 3297, 5856, 5854, -1, 4003, 621, 623, -1, 4003, 624, 621, -1, 4003, 625, 624, -1, 3247, 628, 5857, -1, 5857, 627, 5858, -1, 628, 627, 5857, -1, 627, 629, 5858, -1, 5858, 614, 5859, -1, 5859, 614, 5860, -1, 629, 614, 5858, -1, 5860, 616, 3522, -1, 614, 616, 5860, -1, 616, 619, 3522, -1, 5857, 5051, 3247, -1, 3247, 5051, 3253, -1, 5858, 5049, 5857, -1, 5857, 5049, 5051, -1, 5859, 5047, 5858, -1, 5858, 5047, 5049, -1, 5859, 5045, 5047, -1, 5860, 5043, 5859, -1, 5859, 5043, 5045, -1, 3522, 5041, 5860, -1, 5860, 5041, 5043, -1, 3522, 3577, 5041, -1, 5861, 4729, 4730, -1, 5861, 4730, 5862, -1, 5861, 5863, 5864, -1, 5861, 5862, 5863, -1, 5865, 5837, 5836, -1, 5865, 5866, 5837, -1, 5865, 5864, 5866, -1, 3888, 5867, 3891, -1, 5865, 4729, 5861, -1, 5865, 5836, 4729, -1, 5865, 5861, 5864, -1, 5834, 3889, 3843, -1, 4727, 4729, 5836, -1, 5868, 5869, 5867, -1, 5868, 3888, 3889, -1, 5868, 5867, 3888, -1, 5870, 5871, 5869, -1, 5870, 5869, 5868, -1, 5870, 5868, 5833, -1, 5872, 5831, 5833, -1, 5872, 5834, 5831, -1, 5872, 3889, 5834, -1, 5872, 5833, 5868, -1, 5872, 5868, 3889, -1, 5873, 5874, 5871, -1, 5873, 5871, 5870, -1, 5873, 5870, 5832, -1, 5875, 5830, 5832, -1, 5875, 5833, 5830, -1, 5875, 5870, 5833, -1, 5875, 5832, 5870, -1, 5863, 5876, 5874, -1, 5863, 5874, 5873, -1, 5877, 5835, 5838, -1, 5877, 5832, 5835, -1, 5877, 5873, 5832, -1, 5862, 4730, 4054, -1, 5862, 5878, 5876, -1, 5862, 4054, 5878, -1, 5862, 5876, 5863, -1, 5864, 5877, 5838, -1, 5864, 5863, 5873, -1, 5864, 5873, 5877, -1, 5866, 5838, 5837, -1, 5866, 5864, 5838, -1, 3892, 3891, 5867, -1, 5879, 5867, 5869, -1, 5879, 3892, 5867, -1, 5880, 5869, 5871, -1, 5880, 5879, 5869, -1, 5881, 5871, 5874, -1, 5881, 5880, 5871, -1, 5882, 5874, 5876, -1, 5882, 5881, 5874, -1, 5883, 5876, 5878, -1, 5883, 5882, 5876, -1, 5884, 5878, 4054, -1, 5884, 5883, 5878, -1, 4055, 5884, 4054, -1, 5885, 5886, 5887, -1, 5888, 5889, 5890, -1, 5888, 5891, 5889, -1, 5888, 5892, 5891, -1, 5888, 5893, 5892, -1, 5894, 3892, 5879, -1, 5894, 3893, 3892, -1, 4718, 5884, 4055, -1, 5894, 5879, 5895, -1, 5896, 5895, 5886, -1, 5896, 5886, 5885, -1, 5897, 5890, 5898, -1, 5897, 5888, 5890, -1, 5897, 5885, 5893, -1, 5897, 5893, 5888, -1, 5899, 3882, 3893, -1, 5899, 3893, 5894, -1, 5899, 5894, 5895, -1, 5899, 5895, 5896, -1, 5900, 5898, 5901, -1, 5900, 5896, 5885, -1, 5900, 5897, 5898, -1, 5900, 5885, 5897, -1, 5902, 5901, 5903, -1, 5902, 3879, 3882, -1, 5902, 3882, 5899, -1, 5902, 5900, 5901, -1, 5902, 5896, 5900, -1, 5902, 5903, 3879, -1, 5902, 5899, 5896, -1, 3871, 3879, 5903, -1, 5904, 5883, 5884, -1, 5904, 5884, 4718, -1, 5905, 5883, 5904, -1, 5906, 4718, 4716, -1, 5906, 5904, 4718, -1, 5887, 5882, 5883, -1, 5887, 5883, 5905, -1, 5892, 5904, 5906, -1, 5892, 5905, 5904, -1, 5907, 4714, 4056, -1, 5907, 4716, 4714, -1, 5907, 4056, 5908, -1, 5907, 5906, 4716, -1, 5886, 5881, 5882, -1, 5886, 5882, 5887, -1, 5893, 5905, 5892, -1, 5893, 5887, 5905, -1, 5891, 5908, 5889, -1, 5891, 5907, 5908, -1, 5891, 5892, 5906, -1, 5891, 5906, 5907, -1, 5895, 5879, 5880, -1, 5895, 5880, 5881, -1, 5895, 5881, 5886, -1, 5885, 5887, 5893, -1, 5909, 3871, 5903, -1, 5909, 3878, 3871, -1, 5910, 5903, 5901, -1, 5910, 5909, 5903, -1, 5911, 5901, 5898, -1, 5911, 5910, 5901, -1, 5912, 5898, 5890, -1, 5912, 5911, 5898, -1, 5913, 5890, 5889, -1, 5913, 5912, 5890, -1, 5914, 5889, 5908, -1, 5914, 5913, 5889, -1, 4058, 5908, 4056, -1, 4058, 5914, 5908, -1, 5915, 3884, 3885, -1, 5915, 3885, 5909, -1, 5915, 5916, 3884, -1, 5917, 5918, 5919, -1, 5917, 5919, 5920, -1, 5921, 5922, 5923, -1, 5921, 5920, 5922, -1, 5924, 5925, 5926, -1, 5924, 5923, 5925, -1, 5927, 5910, 5911, -1, 5927, 5926, 5916, -1, 5927, 5916, 5915, -1, 5927, 5915, 5910, -1, 5928, 5929, 5918, -1, 5928, 5918, 5917, -1, 5928, 4732, 5929, -1, 5930, 5917, 5920, -1, 5930, 5920, 5921, -1, 5931, 5921, 5923, -1, 5909, 3885, 3878, -1, 5931, 5923, 5924, -1, 5932, 5911, 5912, -1, 5932, 5927, 5911, -1, 5932, 5924, 5926, -1, 5932, 5926, 5927, -1, 5933, 4735, 4732, -1, 5933, 4732, 5928, -1, 5933, 5928, 5917, -1, 5933, 5917, 5930, -1, 5934, 5921, 5931, -1, 5934, 5930, 5921, -1, 4732, 4049, 5929, -1, 5935, 5912, 5913, -1, 5935, 5932, 5912, -1, 5935, 5931, 5924, -1, 5935, 5924, 5932, -1, 5936, 5933, 5930, -1, 5936, 4737, 4735, -1, 5936, 4735, 5933, -1, 5936, 5930, 5934, -1, 5937, 5934, 5931, -1, 5937, 5935, 5913, -1, 5937, 5913, 5914, -1, 5937, 5931, 5935, -1, 5938, 5914, 4058, -1, 5938, 5936, 5934, -1, 5938, 4739, 4737, -1, 5938, 5937, 5914, -1, 5938, 4058, 4739, -1, 5938, 5934, 5937, -1, 5938, 4737, 5936, -1, 5939, 5940, 3869, -1, 5939, 3869, 3877, -1, 5941, 5942, 5940, -1, 5941, 5940, 5939, -1, 5943, 3877, 3876, -1, 5943, 5939, 3877, -1, 5922, 5944, 5942, -1, 5922, 5942, 5941, -1, 5925, 5939, 5943, -1, 5925, 5941, 5939, -1, 5916, 3876, 3884, -1, 5916, 5943, 3876, -1, 5920, 5919, 5944, -1, 5920, 5944, 5922, -1, 5923, 5941, 5925, -1, 5923, 5922, 5941, -1, 5926, 5943, 5916, -1, 5926, 5925, 5943, -1, 5915, 5909, 5910, -1, 5929, 4049, 4048, -1, 5929, 4048, 5945, -1, 5918, 5945, 5946, -1, 5918, 5929, 5945, -1, 5919, 5946, 5947, -1, 5919, 5918, 5946, -1, 5944, 5947, 5948, -1, 5944, 5919, 5947, -1, 5942, 5948, 5949, -1, 5942, 5944, 5948, -1, 5940, 5949, 5950, -1, 5940, 5942, 5949, -1, 3869, 5950, 3855, -1, 3869, 5940, 5950, -1, 5951, 5952, 5953, -1, 5954, 5953, 5955, -1, 5954, 5948, 5947, -1, 5956, 5957, 5958, -1, 5954, 5955, 5959, -1, 5956, 5958, 5960, -1, 5954, 5959, 5948, -1, 3852, 5961, 3857, -1, 5962, 4162, 5963, -1, 5962, 4161, 4162, -1, 5964, 5965, 5966, -1, 5962, 5963, 5967, -1, 5962, 5967, 5951, -1, 5964, 5960, 5965, -1, 5968, 5947, 5946, -1, 5968, 5953, 5954, -1, 5968, 5951, 5953, -1, 5969, 3848, 3850, -1, 5968, 5954, 5947, -1, 5970, 5946, 5945, -1, 5970, 4160, 4161, -1, 5970, 4161, 5962, -1, 5969, 5966, 3848, -1, 5970, 5962, 5951, -1, 5970, 5951, 5968, -1, 5970, 5968, 5946, -1, 5971, 5972, 5973, -1, 5970, 5945, 4160, -1, 5971, 5973, 5974, -1, 5975, 5974, 5957, -1, 5975, 5957, 5956, -1, 5976, 5960, 5964, -1, 5976, 5956, 5960, -1, 5977, 5966, 5969, -1, 5977, 5964, 5966, -1, 5978, 4165, 4043, -1, 5978, 5979, 5972, -1, 5978, 4043, 5979, -1, 5978, 5972, 5971, -1, 5980, 3850, 3856, -1, 5980, 5969, 3850, -1, 5981, 5971, 5974, -1, 5981, 5974, 5975, -1, 5982, 5975, 5956, -1, 5982, 5956, 5976, -1, 5983, 5976, 5964, -1, 5983, 5964, 5977, -1, 5984, 5977, 5969, -1, 5984, 5969, 5980, -1, 5985, 5971, 5981, -1, 5985, 4164, 4165, -1, 5985, 4165, 5978, -1, 5985, 5978, 5971, -1, 5986, 3855, 5950, -1, 5986, 3853, 3855, -1, 5986, 3856, 3853, -1, 5986, 5980, 3856, -1, 5987, 5981, 5975, -1, 5987, 5975, 5982, -1, 5952, 5982, 5976, -1, 4048, 4160, 5945, -1, 5952, 5976, 5983, -1, 5955, 5983, 5977, -1, 5988, 5961, 3852, -1, 5958, 5989, 5961, -1, 5955, 5977, 5984, -1, 5990, 5950, 5949, -1, 5990, 5984, 5980, -1, 5990, 5980, 5986, -1, 5958, 5961, 5988, -1, 5990, 5986, 5950, -1, 5991, 4163, 4164, -1, 5991, 5981, 5987, -1, 5991, 4164, 5985, -1, 5965, 3852, 3851, -1, 5991, 5985, 5981, -1, 5967, 5982, 5952, -1, 5965, 5988, 3852, -1, 5967, 5987, 5982, -1, 5957, 5992, 5989, -1, 5953, 5983, 5955, -1, 5957, 5989, 5958, -1, 5953, 5952, 5983, -1, 5960, 5988, 5965, -1, 5959, 5949, 5948, -1, 5960, 5958, 5988, -1, 5959, 5955, 5984, -1, 5959, 5990, 5949, -1, 5959, 5984, 5990, -1, 5963, 4162, 4163, -1, 5966, 3851, 3848, -1, 5966, 5965, 3851, -1, 5963, 4163, 5991, -1, 5963, 5991, 5987, -1, 5963, 5987, 5967, -1, 5974, 5973, 5992, -1, 5951, 5967, 5952, -1, 5974, 5992, 5957, -1, 5979, 4043, 4042, -1, 5979, 4042, 5993, -1, 5972, 5993, 5994, -1, 5972, 5979, 5993, -1, 5973, 5994, 5995, -1, 5973, 5972, 5994, -1, 5992, 5995, 5996, -1, 5992, 5973, 5995, -1, 5989, 5996, 5997, -1, 5989, 5992, 5996, -1, 5961, 5997, 5998, -1, 5961, 5989, 5997, -1, 3857, 5998, 3838, -1, 3857, 5961, 5998, -1, 5999, 6000, 6001, -1, 6002, 5997, 5996, -1, 6002, 6003, 5997, -1, 6002, 6004, 6003, -1, 6002, 6005, 6004, -1, 6006, 6007, 6008, -1, 6006, 6008, 6009, -1, 6006, 4180, 6007, -1, 6010, 6009, 6000, -1, 6010, 6000, 5999, -1, 6011, 5996, 5995, -1, 6011, 6002, 5996, -1, 6011, 5999, 6005, -1, 6011, 6005, 6002, -1, 6012, 4178, 4180, -1, 6012, 4180, 6006, -1, 6012, 6009, 6010, -1, 6012, 6006, 6009, -1, 6013, 5995, 5994, -1, 6013, 6011, 5995, -1, 6013, 6010, 5999, -1, 6013, 5999, 6011, -1, 6014, 5994, 5993, -1, 6014, 4177, 4178, -1, 6014, 6013, 5994, -1, 6014, 4178, 6012, -1, 5998, 3844, 3838, -1, 6014, 5993, 4177, -1, 6014, 6012, 6010, -1, 6014, 6010, 6013, -1, 4180, 4038, 6007, -1, 4042, 4177, 5993, -1, 6015, 6016, 3859, -1, 6015, 3859, 3847, -1, 6017, 6018, 6016, -1, 6017, 6016, 6015, -1, 6019, 3847, 3846, -1, 6019, 6015, 3847, -1, 6001, 6020, 6018, -1, 6001, 6018, 6017, -1, 6004, 6015, 6019, -1, 6004, 6017, 6015, -1, 6021, 3846, 3844, -1, 6021, 6019, 3846, -1, 6021, 3844, 5998, -1, 6000, 6022, 6020, -1, 6000, 6020, 6001, -1, 6005, 6017, 6004, -1, 6005, 6001, 6017, -1, 6003, 5998, 5997, -1, 6003, 6019, 6021, -1, 6003, 6004, 6019, -1, 6003, 6021, 5998, -1, 6009, 6008, 6022, -1, 6009, 6022, 6000, -1, 5999, 6001, 6005, -1, 6007, 4037, 6023, -1, 6007, 4038, 4037, -1, 6008, 6007, 6023, -1, 6022, 6023, 6024, -1, 6022, 6008, 6023, -1, 6020, 6024, 6025, -1, 6020, 6025, 6026, -1, 6020, 6022, 6024, -1, 6018, 6026, 6027, -1, 6018, 6020, 6026, -1, 6016, 6027, 6028, -1, 6016, 6018, 6027, -1, 3859, 6028, 605, -1, 3859, 6016, 6028, -1, 608, 606, 6029, -1, 6030, 6029, 6031, -1, 6030, 608, 6029, -1, 6032, 6031, 3585, -1, 6032, 6030, 6031, -1, 3584, 6032, 3585, -1, 3836, 6033, 3837, -1, 3836, 6034, 6033, -1, 3836, 3905, 6034, -1, 607, 3896, 604, -1, 608, 3896, 607, -1, 6030, 3896, 608, -1, 3584, 5097, 6032, -1, 6035, 3836, 3835, -1, 6036, 3836, 6035, -1, 5101, 3905, 3836, -1, 5101, 3836, 6036, -1, 6037, 3835, 3897, -1, 6037, 6035, 3835, -1, 6038, 5099, 5101, -1, 6038, 6035, 6037, -1, 6038, 6036, 6035, -1, 6038, 6037, 5099, -1, 6038, 5101, 6036, -1, 6039, 3897, 3896, -1, 6039, 6037, 3897, -1, 6039, 5099, 6037, -1, 6039, 3896, 6030, -1, 6040, 6030, 6032, -1, 6040, 5097, 5099, -1, 6040, 5099, 6039, -1, 6040, 6032, 5097, -1, 6040, 6039, 6030, -1, 3905, 3904, 6041, -1, 6034, 6041, 6042, -1, 6034, 3905, 6041, -1, 6033, 6042, 3841, -1, 6033, 6034, 6042, -1, 3837, 6033, 3841, -1, 6043, 6042, 6041, -1, 6043, 6041, 3904, -1, 6043, 3904, 3906, -1, 6044, 3841, 6042, -1, 6044, 6042, 6043, -1, 4166, 3841, 6044, -1, 4173, 4170, 4169, -1, 4173, 4063, 4170, -1, 4175, 4173, 4169, -1, 6044, 4169, 4166, -1, 6044, 4175, 4169, -1, 6043, 4175, 6044, -1, 3906, 4175, 6043, -1, 4068, 4070, 6045, -1, 4070, 6046, 6045, -1, 6045, 6047, 6048, -1, 6046, 6047, 6045, -1, 6048, 3521, 3520, -1, 6047, 3521, 6048, -1, 6049, 4071, 4066, -1, 6049, 6050, 4071, -1, 3578, 5539, 6051, -1, 4071, 6046, 4072, -1, 4072, 6046, 4070, -1, 6050, 6046, 4071, -1, 5539, 5540, 6051, -1, 6051, 5541, 6050, -1, 5540, 5541, 6051, -1, 5541, 6047, 6050, -1, 6050, 6047, 6046, -1, 5541, 5542, 6047, -1, 5542, 5543, 6047, -1, 5543, 3521, 6047, -1, 4066, 4065, 6049, -1, 4065, 6052, 6049, -1, 6049, 6053, 6050, -1, 6052, 6053, 6049, -1, 6051, 6054, 3578, -1, 6050, 6054, 6051, -1, 6053, 6054, 6050, -1, 6054, 3579, 3578, -1, 3579, 6054, 5040, -1, 6052, 4065, 6055, -1, 5048, 6056, 5050, -1, 3277, 6057, 6058, -1, 5050, 6057, 3277, -1, 6056, 6057, 5050, -1, 5048, 6057, 6056, -1, 6058, 6059, 6060, -1, 6060, 6059, 6057, -1, 6057, 6059, 6058, -1, 5044, 6061, 5046, -1, 5046, 6061, 5048, -1, 5048, 6061, 6057, -1, 6060, 6062, 6063, -1, 6063, 6062, 6064, -1, 6057, 6062, 6060, -1, 6061, 6062, 6057, -1, 5042, 6065, 5044, -1, 5044, 6065, 6061, -1, 6065, 6066, 6061, -1, 5042, 6066, 6065, -1, 6061, 6066, 6062, -1, 6064, 6067, 6068, -1, 6068, 6067, 6066, -1, 6066, 6067, 6062, -1, 6062, 6067, 6064, -1, 6053, 6069, 6054, -1, 5040, 6069, 5042, -1, 5042, 6069, 6066, -1, 6054, 6069, 5040, -1, 6068, 6070, 6055, -1, 6052, 6070, 6053, -1, 6066, 6070, 6068, -1, 6053, 6070, 6069, -1, 6055, 6070, 6052, -1, 6069, 6070, 6066, -1, 4065, 4067, 6055, -1, 6055, 6071, 6068, -1, 4067, 6071, 6055, -1, 6068, 6072, 6064, -1, 6071, 6072, 6068, -1, 6064, 6073, 6063, -1, 6072, 6073, 6064, -1, 6063, 6074, 6060, -1, 6073, 6074, 6063, -1, 6060, 6075, 6058, -1, 6074, 6075, 6060, -1, 6058, 6076, 3277, -1, 6075, 6076, 6058, -1, 6076, 3284, 3277, -1, 6077, 6078, 6079, -1, 6080, 6078, 6077, -1, 6072, 6081, 6073, -1, 6082, 6081, 6072, -1, 6079, 6081, 6083, -1, 6083, 6081, 6082, -1, 3275, 6084, 3266, -1, 3266, 6084, 6085, -1, 6085, 6084, 6086, -1, 6086, 6084, 6087, -1, 6087, 6088, 6080, -1, 6080, 6088, 6078, -1, 6073, 6089, 6074, -1, 6081, 6089, 6073, -1, 6078, 6089, 6079, -1, 6079, 6089, 6081, -1, 3282, 6090, 3275, -1, 3275, 6090, 6084, -1, 6084, 6090, 6087, -1, 6087, 6090, 6088, -1, 6074, 6091, 6075, -1, 6089, 6091, 6074, -1, 6088, 6091, 6078, -1, 6078, 6091, 6089, -1, 3283, 6092, 3282, -1, 6075, 6092, 6076, -1, 6088, 6092, 6091, -1, 3282, 6092, 6090, -1, 6076, 6092, 3283, -1, 4182, 6071, 4067, -1, 6091, 6092, 6075, -1, 6090, 6092, 6088, -1, 3283, 3284, 6076, -1, 6093, 6094, 4131, -1, 4131, 6094, 4186, -1, 6095, 6096, 6093, -1, 6093, 6096, 6094, -1, 4186, 6097, 4184, -1, 6094, 6097, 4186, -1, 6098, 6077, 6095, -1, 6095, 6077, 6096, -1, 6094, 6083, 6097, -1, 6096, 6083, 6094, -1, 4184, 6099, 4182, -1, 4182, 6099, 6071, -1, 6097, 6099, 4184, -1, 6100, 6080, 6098, -1, 6098, 6080, 6077, -1, 6077, 6079, 6096, -1, 6096, 6079, 6083, -1, 6071, 6082, 6072, -1, 6083, 6082, 6097, -1, 6097, 6082, 6099, -1, 6099, 6082, 6071, -1, 6086, 6087, 6100, -1, 6100, 6087, 6080, -1, 4130, 6101, 4131, -1, 4131, 6101, 6093, -1, 6093, 6102, 6095, -1, 6101, 6102, 6093, -1, 6095, 6103, 6098, -1, 6102, 6103, 6095, -1, 6098, 6104, 6100, -1, 6103, 6104, 6098, -1, 6100, 6105, 6086, -1, 6104, 6105, 6100, -1, 6086, 6106, 6085, -1, 6105, 6106, 6086, -1, 6085, 3238, 3266, -1, 6106, 3238, 6085, -1, 6107, 6108, 6109, -1, 6110, 6111, 6112, -1, 6103, 6113, 6104, -1, 6109, 6114, 6115, -1, 6116, 6113, 6117, -1, 6117, 6113, 6103, -1, 6112, 6113, 6116, -1, 6115, 6114, 6118, -1, 3241, 6119, 3289, -1, 6120, 4133, 4132, -1, 6121, 6119, 6111, -1, 3289, 6119, 6122, -1, 6123, 6124, 6125, -1, 6122, 6119, 6121, -1, 6118, 6124, 6123, -1, 6104, 6126, 6105, -1, 6113, 6126, 6104, -1, 6111, 6126, 6112, -1, 4138, 6127, 4140, -1, 6112, 6126, 6113, -1, 6105, 6128, 6106, -1, 6111, 6128, 6126, -1, 6125, 6127, 4138, -1, 3241, 6128, 6119, -1, 6119, 6128, 6111, -1, 6126, 6128, 6105, -1, 6106, 6128, 3241, -1, 6129, 6130, 6131, -1, 6131, 6130, 6108, -1, 6108, 6132, 6109, -1, 6109, 6132, 6114, -1, 6118, 6133, 6124, -1, 6114, 6133, 6118, -1, 6124, 6134, 6125, -1, 6125, 6134, 6127, -1, 3263, 3279, 6135, -1, 3281, 6136, 3279, -1, 6135, 6136, 6129, -1, 6129, 6136, 6130, -1, 3279, 6136, 6135, -1, 4140, 6137, 4142, -1, 6127, 6137, 4140, -1, 6130, 6138, 6108, -1, 6108, 6138, 6132, -1, 6132, 6139, 6114, -1, 6114, 6139, 6133, -1, 6133, 6140, 6124, -1, 6124, 6140, 6134, -1, 6127, 6141, 6137, -1, 6134, 6141, 6127, -1, 3285, 6142, 3281, -1, 6130, 6142, 6138, -1, 3281, 6142, 6136, -1, 6136, 6142, 6130, -1, 4142, 6143, 4144, -1, 4144, 6143, 4130, -1, 4130, 6143, 6101, -1, 6137, 6143, 4142, -1, 6138, 6144, 6132, -1, 6132, 6144, 6139, -1, 6139, 6110, 6133, -1, 3241, 3238, 6106, -1, 6133, 6110, 6140, -1, 6120, 6145, 4133, -1, 6140, 6116, 6134, -1, 6146, 6115, 6120, -1, 6134, 6116, 6141, -1, 6143, 6147, 6101, -1, 6137, 6147, 6143, -1, 6101, 6147, 6102, -1, 6120, 6115, 6145, -1, 6141, 6147, 6137, -1, 4133, 6123, 4136, -1, 3285, 6148, 6142, -1, 3287, 6148, 3285, -1, 6142, 6148, 6138, -1, 6145, 6123, 4133, -1, 6138, 6148, 6144, -1, 6139, 6121, 6110, -1, 6144, 6121, 6139, -1, 6107, 6109, 6146, -1, 6146, 6109, 6115, -1, 6110, 6112, 6140, -1, 6145, 6118, 6123, -1, 6140, 6112, 6116, -1, 6116, 6117, 6141, -1, 6115, 6118, 6145, -1, 6102, 6117, 6103, -1, 4136, 6125, 4138, -1, 6147, 6117, 6102, -1, 6141, 6117, 6147, -1, 3289, 6122, 3287, -1, 6123, 6125, 4136, -1, 6144, 6122, 6121, -1, 6148, 6122, 6144, -1, 3287, 6122, 6148, -1, 6121, 6111, 6110, -1, 6131, 6108, 6107, -1, 4146, 6149, 4132, -1, 4132, 6149, 6120, -1, 6120, 6150, 6146, -1, 6149, 6150, 6120, -1, 6146, 6151, 6107, -1, 6150, 6151, 6146, -1, 6107, 6152, 6131, -1, 6151, 6152, 6107, -1, 6131, 6153, 6129, -1, 6152, 6153, 6131, -1, 6135, 6154, 3263, -1, 6129, 6154, 6135, -1, 6153, 6154, 6129, -1, 6154, 3251, 3263, -1, 3248, 6155, 3273, -1, 3273, 6155, 3599, -1, 3599, 6156, 3596, -1, 6155, 6156, 3599, -1, 3596, 6157, 3591, -1, 6156, 6157, 3596, -1, 3591, 6158, 3594, -1, 6157, 6158, 3591, -1, 3594, 6159, 3597, -1, 6158, 6159, 3594, -1, 3597, 6160, 3601, -1, 6159, 6160, 3597, -1, 3601, 3445, 3444, -1, 6160, 3445, 3601, -1, 4146, 6161, 6149, -1, 6162, 6161, 4742, -1, 6163, 6164, 6165, -1, 6165, 6164, 6166, -1, 6167, 4746, 4128, -1, 6166, 6168, 6169, -1, 6169, 6168, 6170, -1, 6171, 6172, 6173, -1, 6170, 6172, 6171, -1, 6149, 6174, 6150, -1, 6173, 6174, 6162, -1, 6162, 6174, 6161, -1, 6161, 6174, 6149, -1, 3244, 6175, 3242, -1, 3242, 6175, 6163, -1, 6163, 6175, 6164, -1, 6166, 6176, 6168, -1, 6164, 6176, 6166, -1, 6168, 6177, 6170, -1, 6170, 6177, 6172, -1, 6150, 6178, 6151, -1, 6173, 6178, 6174, -1, 6174, 6178, 6150, -1, 6172, 6178, 6173, -1, 3246, 6179, 3244, -1, 3244, 6179, 6175, -1, 6175, 6179, 6164, -1, 6164, 6179, 6176, -1, 6176, 6180, 6168, -1, 3243, 3242, 6163, -1, 6168, 6180, 6177, -1, 6151, 6181, 6152, -1, 6178, 6181, 6151, -1, 6177, 6181, 6172, -1, 6172, 6181, 6178, -1, 6179, 6182, 6176, -1, 3245, 6182, 3246, -1, 3246, 6182, 6179, -1, 6176, 6182, 6180, -1, 6177, 6183, 6181, -1, 6180, 6183, 6177, -1, 6152, 6183, 6153, -1, 6181, 6183, 6152, -1, 3251, 6184, 3245, -1, 6180, 6184, 6183, -1, 6182, 6184, 6180, -1, 6154, 6184, 3251, -1, 6153, 6184, 6154, -1, 6183, 6184, 6153, -1, 3245, 6184, 6182, -1, 6185, 6186, 6167, -1, 6167, 6186, 4746, -1, 6187, 6188, 6185, -1, 6185, 6188, 6186, -1, 4746, 6189, 4744, -1, 6186, 6189, 4746, -1, 6190, 6169, 6187, -1, 6187, 6169, 6188, -1, 6186, 6171, 6189, -1, 6188, 6171, 6186, -1, 4744, 6162, 4742, -1, 6189, 6162, 4744, -1, 6165, 6166, 6190, -1, 6190, 6166, 6169, -1, 6188, 6170, 6171, -1, 6169, 6170, 6188, -1, 6171, 6173, 6189, -1, 6189, 6173, 6162, -1, 4742, 6161, 4740, -1, 4740, 6161, 4146, -1, 6167, 6160, 6185, -1, 4128, 6160, 6167, -1, 3445, 6160, 4128, -1, 6185, 6159, 6187, -1, 6160, 6159, 6185, -1, 6187, 6158, 6190, -1, 6159, 6158, 6187, -1, 6190, 6157, 6165, -1, 6158, 6157, 6190, -1, 6165, 6156, 6163, -1, 6157, 6156, 6165, -1, 6163, 6155, 3243, -1, 6156, 6155, 6163, -1, 6155, 3248, 3243, -1, 4111, 4108, 6191, -1, 5839, 6191, 6192, -1, 5839, 4111, 6191, -1, 5840, 6192, 6193, -1, 5840, 5839, 6192, -1, 5841, 6193, 6194, -1, 5841, 5840, 6193, -1, 5842, 6194, 6195, -1, 5842, 5841, 6194, -1, 5846, 5842, 6195, -1, 5845, 6195, 6196, -1, 5845, 5846, 6195, -1, 5844, 5845, 6196, -1, 5843, 6196, 3538, -1, 5843, 5844, 6196, -1, 3537, 5843, 3538, -1, 6197, 6198, 6199, -1, 6200, 6201, 6197, -1, 6200, 6202, 6201, -1, 6203, 4726, 4725, -1, 4731, 6204, 4052, -1, 6203, 6205, 4726, -1, 6206, 6202, 6200, -1, 6206, 6207, 6202, -1, 6208, 6199, 6205, -1, 6208, 6205, 6203, -1, 6209, 6210, 6207, -1, 6209, 4097, 6210, -1, 6209, 6207, 6206, -1, 6211, 6199, 6208, -1, 6211, 6197, 6199, -1, 6212, 4725, 4722, -1, 6212, 6203, 4725, -1, 6213, 6197, 6211, -1, 4096, 4095, 6214, -1, 6213, 6200, 6197, -1, 6215, 6208, 6203, -1, 6215, 6203, 6212, -1, 6216, 6200, 6213, -1, 6216, 6206, 6200, -1, 6217, 6208, 6215, -1, 6217, 6211, 6208, -1, 6218, 6206, 6216, -1, 6218, 4098, 4097, -1, 6218, 4099, 4098, -1, 6218, 4097, 6209, -1, 6218, 6209, 6206, -1, 6196, 4720, 3538, -1, 6219, 4722, 4720, -1, 6219, 6212, 4722, -1, 6195, 4720, 6196, -1, 6220, 6211, 6217, -1, 6220, 6213, 6211, -1, 6221, 6215, 6212, -1, 6221, 6219, 4720, -1, 6221, 4720, 6195, -1, 6221, 6212, 6219, -1, 6222, 6213, 6220, -1, 6222, 6216, 6213, -1, 6223, 6217, 6215, -1, 6191, 4106, 6192, -1, 6223, 6195, 6194, -1, 6223, 6194, 6193, -1, 4108, 4106, 6191, -1, 6224, 6225, 6204, -1, 6223, 6221, 6195, -1, 6223, 6215, 6221, -1, 6224, 4731, 4728, -1, 6224, 6204, 4731, -1, 6226, 6216, 6222, -1, 6226, 4099, 6218, -1, 6226, 6218, 6216, -1, 6198, 6227, 6225, -1, 6226, 4104, 4099, -1, 6228, 6193, 6192, -1, 6228, 6220, 6217, -1, 6228, 6223, 6193, -1, 6198, 6224, 4728, -1, 6198, 6225, 6224, -1, 6228, 6217, 6223, -1, 6201, 6229, 6227, -1, 6230, 6222, 6220, -1, 6201, 6227, 6198, -1, 6230, 6220, 6228, -1, 6230, 6228, 6192, -1, 6230, 6192, 4106, -1, 6231, 6226, 6222, -1, 6231, 4106, 4104, -1, 6231, 4104, 6226, -1, 6202, 6229, 6201, -1, 6231, 6222, 6230, -1, 6231, 6230, 4106, -1, 6205, 4728, 4726, -1, 6207, 6232, 6229, -1, 6207, 6229, 6202, -1, 6199, 6198, 4728, -1, 6199, 4728, 6205, -1, 6210, 4097, 4096, -1, 6210, 6214, 6232, -1, 6210, 4096, 6214, -1, 6210, 6232, 6207, -1, 6197, 6201, 6198, -1, 4053, 4052, 6204, -1, 6233, 6204, 6225, -1, 6233, 4053, 6204, -1, 6234, 6225, 6227, -1, 6234, 6233, 6225, -1, 6235, 6234, 6227, -1, 6236, 6227, 6229, -1, 6236, 6235, 6227, -1, 6237, 6229, 6232, -1, 6237, 6236, 6229, -1, 6238, 6232, 6214, -1, 6238, 6237, 6232, -1, 4094, 6214, 4095, -1, 4094, 6238, 6214, -1, 6239, 6240, 6241, -1, 6239, 6242, 6243, -1, 6239, 6244, 6240, -1, 6239, 6243, 6244, -1, 6245, 4053, 6233, -1, 6245, 6233, 6234, -1, 6245, 4717, 4053, -1, 6245, 6234, 6246, -1, 6247, 6246, 6248, -1, 6247, 6248, 6249, -1, 6250, 6241, 6251, -1, 6250, 6242, 6239, -1, 6250, 6239, 6241, -1, 6250, 6249, 6242, -1, 6252, 4715, 4717, -1, 6252, 4717, 6245, -1, 6252, 6246, 6247, -1, 6252, 6245, 6246, -1, 6253, 6251, 6254, -1, 6253, 6250, 6251, -1, 6253, 6247, 6249, -1, 6253, 6249, 6250, -1, 6255, 6254, 4059, -1, 6255, 4713, 4715, -1, 6255, 4059, 4713, -1, 6255, 6253, 6254, -1, 6255, 4715, 6252, -1, 6255, 6252, 6247, -1, 6255, 6247, 6253, -1, 6256, 4101, 4076, -1, 6257, 6238, 4094, -1, 6257, 4094, 4093, -1, 6258, 6237, 6238, -1, 6258, 6238, 6257, -1, 6259, 4093, 4102, -1, 6259, 6257, 4093, -1, 6260, 6236, 6237, -1, 6260, 6237, 6258, -1, 6243, 6257, 6259, -1, 6243, 6258, 6257, -1, 6261, 4102, 4101, -1, 6261, 6256, 6262, -1, 6261, 4101, 6256, -1, 6261, 6259, 4102, -1, 6248, 6235, 6236, -1, 6248, 6236, 6260, -1, 6242, 6260, 6258, -1, 6242, 6258, 6243, -1, 6244, 6262, 6240, -1, 6244, 6261, 6262, -1, 6244, 6243, 6259, -1, 6244, 6259, 6261, -1, 6246, 6234, 6235, -1, 6246, 6235, 6248, -1, 6249, 6260, 6242, -1, 6249, 6248, 6260, -1, 6263, 4059, 6254, -1, 6263, 4057, 4059, -1, 6264, 6254, 6251, -1, 6264, 6263, 6254, -1, 6265, 6251, 6241, -1, 6265, 6264, 6251, -1, 6266, 6241, 6240, -1, 6266, 6265, 6241, -1, 6267, 6240, 6262, -1, 6267, 6266, 6240, -1, 6268, 6262, 6256, -1, 6268, 6267, 6262, -1, 4078, 6256, 4076, -1, 4078, 6268, 6256, -1, 6269, 6270, 4736, -1, 6271, 6272, 6273, -1, 6271, 6273, 6274, -1, 4733, 6275, 4050, -1, 6276, 6277, 6278, -1, 6276, 6274, 6277, -1, 6279, 6278, 6280, -1, 6279, 6280, 6281, -1, 6282, 6263, 6264, -1, 6282, 6281, 6270, -1, 6282, 6269, 6263, -1, 6282, 6270, 6269, -1, 6283, 4113, 4109, -1, 6283, 4109, 6272, -1, 6283, 6272, 6271, -1, 6284, 6271, 6274, -1, 6284, 6274, 6276, -1, 6285, 6276, 6278, -1, 6285, 6278, 6279, -1, 6286, 6264, 6265, -1, 6286, 6281, 6282, -1, 6286, 6282, 6264, -1, 6286, 6279, 6281, -1, 6287, 4114, 4113, -1, 6287, 4113, 6283, -1, 6287, 6283, 6271, -1, 6287, 6271, 6284, -1, 6288, 6276, 6285, -1, 6288, 6284, 6276, -1, 6289, 6265, 6266, -1, 6289, 6286, 6265, -1, 6289, 6285, 6279, -1, 6289, 6279, 6286, -1, 6290, 6287, 6284, -1, 6290, 4115, 4114, -1, 6290, 4114, 6287, -1, 6290, 6284, 6288, -1, 6291, 6288, 6285, -1, 6291, 6266, 6267, -1, 6291, 6285, 6289, -1, 6291, 6289, 6266, -1, 6292, 6291, 6267, -1, 6292, 6267, 6268, -1, 6292, 6290, 6288, -1, 6292, 4117, 4115, -1, 6292, 6288, 6291, -1, 6292, 6268, 4117, -1, 6292, 4115, 6290, -1, 4078, 4117, 6268, -1, 6293, 6294, 6275, -1, 6293, 6275, 4733, -1, 6295, 6296, 6294, -1, 6295, 6294, 6293, -1, 6297, 4733, 4734, -1, 6297, 6293, 4733, -1, 6277, 6298, 6296, -1, 6277, 6296, 6295, -1, 6280, 6293, 6297, -1, 6280, 6295, 6293, -1, 6270, 4734, 4736, -1, 6270, 6297, 4734, -1, 6274, 6273, 6298, -1, 6274, 6298, 6277, -1, 6278, 6277, 6295, -1, 6278, 6295, 6280, -1, 6281, 6280, 6297, -1, 6281, 6297, 6270, -1, 6269, 4057, 6263, -1, 6269, 4738, 4057, -1, 6269, 4736, 4738, -1, 6272, 4109, 4092, -1, 6272, 4092, 6299, -1, 6273, 6299, 6300, -1, 6273, 6272, 6299, -1, 6298, 6300, 6301, -1, 6298, 6273, 6300, -1, 6296, 6301, 6302, -1, 6296, 6298, 6301, -1, 6294, 6302, 6303, -1, 6294, 6296, 6302, -1, 6275, 6303, 6304, -1, 6275, 6294, 6303, -1, 4050, 6304, 4051, -1, 4050, 6275, 6304, -1, 6305, 6306, 6307, -1, 6305, 6307, 6308, -1, 6309, 6310, 6311, -1, 6309, 6311, 6312, -1, 6313, 6302, 6301, -1, 6313, 6308, 6314, -1, 6313, 6314, 6315, -1, 6313, 6315, 6302, -1, 6316, 6317, 6318, -1, 6316, 6312, 6317, -1, 6319, 4084, 4082, -1, 6319, 4082, 6320, -1, 6319, 6320, 6306, -1, 6319, 6306, 6305, -1, 6321, 6301, 6300, -1, 6322, 4154, 4152, -1, 6321, 6305, 6308, -1, 6321, 6308, 6313, -1, 6322, 6318, 4154, -1, 6321, 6313, 6301, -1, 6323, 6300, 6299, -1, 6324, 6325, 6326, -1, 6323, 4086, 4084, -1, 6323, 4084, 6319, -1, 6323, 6319, 6305, -1, 6324, 6326, 6327, -1, 6323, 6305, 6321, -1, 6323, 6321, 6300, -1, 6323, 6299, 4086, -1, 6328, 6327, 6310, -1, 6328, 6310, 6309, -1, 6329, 6312, 6316, -1, 6329, 6309, 6312, -1, 6330, 6318, 6322, -1, 6330, 6316, 6318, -1, 6331, 4088, 4090, -1, 6331, 6332, 6325, -1, 6331, 4090, 6332, -1, 6331, 6325, 6324, -1, 6333, 4152, 4150, -1, 6333, 6322, 4152, -1, 6334, 6327, 6328, -1, 6334, 6324, 6327, -1, 6335, 6328, 6309, -1, 6335, 6309, 6329, -1, 6336, 6329, 6316, -1, 6336, 6316, 6330, -1, 6337, 6330, 6322, -1, 6337, 6322, 6333, -1, 6338, 6324, 6334, -1, 6338, 4080, 4088, -1, 6338, 4088, 6331, -1, 6338, 6331, 6324, -1, 6339, 4051, 6304, -1, 6339, 4149, 4051, -1, 6339, 4150, 4149, -1, 6339, 6333, 4150, -1, 6340, 6328, 6335, -1, 6340, 6334, 6328, -1, 4092, 4086, 6299, -1, 6341, 6342, 4046, -1, 6307, 6335, 6329, -1, 6307, 6329, 6336, -1, 6341, 4046, 4158, -1, 6311, 6343, 6342, -1, 6314, 6330, 6337, -1, 6314, 6336, 6330, -1, 6344, 6304, 6303, -1, 6311, 6342, 6341, -1, 6344, 6337, 6333, -1, 6344, 6333, 6339, -1, 6344, 6339, 6304, -1, 6317, 4158, 4156, -1, 6345, 4081, 4080, -1, 6317, 6341, 4158, -1, 6345, 6334, 6340, -1, 6345, 6338, 6334, -1, 6345, 4080, 6338, -1, 6310, 6346, 6343, -1, 6306, 6335, 6307, -1, 6310, 6343, 6311, -1, 6306, 6340, 6335, -1, 6312, 6341, 6317, -1, 6308, 6336, 6314, -1, 6312, 6311, 6341, -1, 6308, 6307, 6336, -1, 6315, 6303, 6302, -1, 6318, 4156, 4154, -1, 6315, 6314, 6337, -1, 6318, 6317, 4156, -1, 6315, 6337, 6344, -1, 6315, 6344, 6303, -1, 6320, 4082, 4081, -1, 6320, 4081, 6345, -1, 6327, 6326, 6346, -1, 6320, 6345, 6340, -1, 6320, 6340, 6306, -1, 6327, 6346, 6310, -1, 6332, 4090, 4119, -1, 6332, 4119, 6347, -1, 6325, 6347, 6348, -1, 6325, 6332, 6347, -1, 6326, 6348, 6349, -1, 6326, 6325, 6348, -1, 6346, 6349, 6350, -1, 6346, 6326, 6349, -1, 6343, 6350, 6351, -1, 6343, 6346, 6350, -1, 6342, 6351, 6352, -1, 6342, 6343, 6351, -1, 4046, 6352, 4045, -1, 4046, 6342, 6352, -1, 6353, 6354, 6355, -1, 6356, 6351, 6350, -1, 6356, 6357, 6351, -1, 6356, 6358, 6357, -1, 6356, 6359, 6358, -1, 6360, 6361, 6362, -1, 6360, 4125, 6361, -1, 6360, 6362, 6363, -1, 6364, 6363, 6354, -1, 6364, 6354, 6353, -1, 6365, 6350, 6349, -1, 6365, 6356, 6350, -1, 6365, 6353, 6359, -1, 6365, 6359, 6356, -1, 6366, 4124, 4125, -1, 6366, 4125, 6360, -1, 6366, 6363, 6364, -1, 6366, 6360, 6363, -1, 6367, 6349, 6348, -1, 6367, 6365, 6349, -1, 6367, 6364, 6353, -1, 6367, 6353, 6365, -1, 6368, 6348, 6347, -1, 6368, 6347, 4119, -1, 6368, 4122, 4124, -1, 6368, 4119, 4122, -1, 6352, 4176, 4045, -1, 6368, 4124, 6366, -1, 6368, 6367, 6348, -1, 6368, 6366, 6364, -1, 6368, 6364, 6367, -1, 4125, 4073, 6361, -1, 6369, 6370, 4040, -1, 6369, 4040, 4181, -1, 6371, 6372, 6370, -1, 6371, 6370, 6369, -1, 6373, 4181, 4179, -1, 6373, 6369, 4181, -1, 6355, 6374, 6372, -1, 6355, 6372, 6371, -1, 6358, 6369, 6373, -1, 6358, 6371, 6369, -1, 6375, 4179, 4176, -1, 6375, 6373, 4179, -1, 6375, 4176, 6352, -1, 6354, 6376, 6374, -1, 6354, 6374, 6355, -1, 6359, 6371, 6358, -1, 6359, 6355, 6371, -1, 6357, 6352, 6351, -1, 6357, 6373, 6375, -1, 6357, 6358, 6373, -1, 6357, 6375, 6352, -1, 6363, 6362, 6376, -1, 6363, 6376, 6354, -1, 6353, 6355, 6359, -1, 3027, 4073, 3042, -1, 6361, 4073, 3027, -1, 6362, 3027, 3029, -1, 6362, 6361, 3027, -1, 6376, 3029, 3033, -1, 6376, 6362, 3029, -1, 3035, 6376, 3033, -1, 6374, 3035, 3036, -1, 6374, 3036, 3008, -1, 6374, 6376, 3035, -1, 6372, 3008, 3010, -1, 6372, 3010, 3066, -1, 6372, 3066, 3068, -1, 6372, 3068, 3069, -1, 6372, 6374, 3008, -1, 6370, 3069, 3070, -1, 6370, 3070, 3092, -1, 6370, 3092, 3057, -1, 6370, 6372, 3069, -1, 4040, 3057, 3059, -1, 4040, 6370, 3057, -1, 2806, 3297, 2810, -1, 2810, 5849, 2814, -1, 3297, 5849, 2810, -1, 2814, 5848, 2815, -1, 5849, 5848, 2814, -1, 2815, 6377, 2822, -1, 5848, 6377, 2815, -1, 2822, 597, 2823, -1, 6377, 597, 2822, -1, 2823, 598, 6378, -1, 597, 598, 2823, -1, 6378, 600, 6379, -1, 598, 600, 6378, -1, 6379, 601, 2051, -1, 600, 601, 6379, -1, 3554, 3553, 5848, -1, 5848, 3553, 6377, -1, 3553, 3552, 6377, -1, 6377, 595, 597, -1, 3552, 595, 6377, -1, 6380, 5118, 3976, -1, 5120, 2265, 2108, -1, 5120, 2268, 2265, -1, 3367, 3389, 6381, -1, 5120, 2271, 2268, -1, 3388, 2279, 2276, -1, 3388, 2281, 2279, -1, 3388, 2283, 2281, -1, 5118, 6382, 5120, -1, 6380, 6382, 5118, -1, 6383, 6384, 6380, -1, 6382, 6384, 5120, -1, 6380, 6384, 6382, -1, 6385, 6386, 6383, -1, 6384, 6386, 5120, -1, 6383, 6386, 6384, -1, 5120, 6386, 2271, -1, 6387, 6388, 6385, -1, 2271, 6388, 2274, -1, 6385, 6388, 6386, -1, 6386, 6388, 2271, -1, 6389, 6390, 6387, -1, 2274, 6390, 2276, -1, 6388, 6390, 2274, -1, 6387, 6390, 6388, -1, 6391, 6392, 6389, -1, 6389, 6392, 6390, -1, 6390, 6392, 2276, -1, 2276, 6392, 3388, -1, 6393, 6394, 6391, -1, 6392, 6394, 3388, -1, 6391, 6394, 6392, -1, 3388, 6395, 3389, -1, 6381, 6395, 6393, -1, 6394, 6395, 3388, -1, 6393, 6395, 6394, -1, 3389, 6395, 6381, -1, 3978, 6396, 3976, -1, 3976, 6396, 6380, -1, 6380, 6397, 6383, -1, 6396, 6397, 6380, -1, 6383, 6398, 6385, -1, 6397, 6398, 6383, -1, 6385, 6399, 6387, -1, 6398, 6399, 6385, -1, 6387, 6400, 6389, -1, 6399, 6400, 6387, -1, 6389, 6401, 6391, -1, 6400, 6401, 6389, -1, 6391, 6402, 6393, -1, 6401, 6402, 6391, -1, 6393, 6403, 6381, -1, 6402, 6403, 6393, -1, 6381, 3371, 3367, -1, 6403, 3371, 6381, -1, 6404, 6405, 6406, -1, 6406, 6405, 6407, -1, 6408, 6409, 6410, -1, 6407, 6409, 6408, -1, 6398, 6411, 6399, -1, 6399, 6411, 6412, -1, 6412, 6413, 6404, -1, 6404, 6413, 6405, -1, 3461, 6414, 3467, -1, 6410, 6414, 3461, -1, 3467, 6414, 6415, -1, 6405, 6416, 6407, -1, 6407, 6416, 6409, -1, 6397, 6417, 6398, -1, 6398, 6417, 6411, -1, 6415, 6418, 6419, -1, 6414, 6418, 6415, -1, 6409, 6418, 6410, -1, 6410, 6418, 6414, -1, 6412, 6420, 6413, -1, 6411, 6420, 6412, -1, 3467, 6415, 3477, -1, 6413, 6421, 6405, -1, 6405, 6421, 6416, -1, 6419, 6422, 6423, -1, 3978, 4914, 6396, -1, 6418, 6422, 6419, -1, 6416, 6422, 6409, -1, 6409, 6422, 6418, -1, 4912, 6424, 4914, -1, 6396, 6424, 6397, -1, 6397, 6424, 6417, -1, 4914, 6424, 6396, -1, 6417, 6425, 6411, -1, 6411, 6425, 6420, -1, 6420, 6426, 6413, -1, 6413, 6426, 6421, -1, 6416, 6427, 6422, -1, 6423, 6427, 6428, -1, 6422, 6427, 6423, -1, 6421, 6427, 6416, -1, 6424, 6429, 6417, -1, 4910, 6429, 4912, -1, 6417, 6429, 6425, -1, 4912, 6429, 6424, -1, 6425, 6430, 6420, -1, 6420, 6430, 6426, -1, 3371, 6431, 3479, -1, 6426, 6432, 6421, -1, 6421, 6432, 6427, -1, 6403, 6431, 3371, -1, 6427, 6432, 6428, -1, 4907, 6433, 4910, -1, 4910, 6433, 6429, -1, 6429, 6433, 6425, -1, 6402, 6406, 6403, -1, 6425, 6433, 6430, -1, 6428, 6434, 6435, -1, 6403, 6406, 6431, -1, 6432, 6434, 6428, -1, 6426, 6434, 6432, -1, 6430, 6434, 6426, -1, 3479, 6408, 3473, -1, 3473, 6408, 3464, -1, 6435, 6436, 6437, -1, 6431, 6408, 3479, -1, 6437, 6436, 3981, -1, 3981, 6436, 4907, -1, 6434, 6436, 6435, -1, 6433, 6436, 6430, -1, 6430, 6436, 6434, -1, 6401, 6404, 6402, -1, 4907, 6436, 6433, -1, 6402, 6404, 6406, -1, 6431, 6407, 6408, -1, 6406, 6407, 6431, -1, 3464, 6410, 3461, -1, 6408, 6410, 3464, -1, 6400, 6412, 6401, -1, 6399, 6412, 6400, -1, 6401, 6412, 6404, -1, 3981, 3982, 6437, -1, 6437, 6438, 6435, -1, 3982, 6438, 6437, -1, 6435, 6439, 6428, -1, 6438, 6439, 6435, -1, 6428, 6440, 6423, -1, 6439, 6440, 6428, -1, 6423, 6441, 6419, -1, 6440, 6441, 6423, -1, 6419, 6442, 6415, -1, 6441, 6442, 6419, -1, 6415, 6443, 3477, -1, 6442, 6443, 6415, -1, 6443, 3308, 3477, -1, 6444, 6445, 6446, -1, 6447, 6448, 6449, -1, 6450, 6451, 6452, -1, 585, 6448, 588, -1, 6452, 6451, 6453, -1, 6449, 6448, 6454, -1, 6454, 6448, 585, -1, 6455, 6456, 6444, -1, 6457, 6458, 6450, -1, 6459, 6456, 6455, -1, 6450, 6458, 6451, -1, 4921, 6460, 4919, -1, 4919, 6460, 4918, -1, 4918, 6460, 6459, -1, 3517, 6461, 3294, -1, 588, 6462, 590, -1, 6447, 6462, 6448, -1, 6453, 6461, 3517, -1, 6445, 6462, 6447, -1, 6448, 6462, 588, -1, 4916, 6463, 4915, -1, 6438, 6463, 6439, -1, 6439, 6463, 6464, -1, 6444, 6465, 6445, -1, 4915, 6463, 6438, -1, 6456, 6465, 6444, -1, 4921, 6466, 6460, -1, 6459, 6466, 6456, -1, 6453, 6467, 6461, -1, 6460, 6466, 6459, -1, 4926, 6468, 4924, -1, 6451, 6467, 6453, -1, 6445, 6468, 6462, -1, 6465, 6468, 6445, -1, 6462, 6468, 590, -1, 590, 6468, 4926, -1, 4924, 6469, 4923, -1, 4923, 6469, 4921, -1, 6468, 6469, 4924, -1, 6457, 6470, 6458, -1, 6465, 6469, 6468, -1, 6464, 6470, 6457, -1, 6456, 6469, 6465, -1, 6466, 6469, 6456, -1, 4921, 6469, 6466, -1, 6451, 6471, 6467, -1, 6458, 6471, 6451, -1, 3294, 6472, 3300, -1, 3982, 4915, 6438, -1, 6461, 6472, 3294, -1, 4917, 6473, 4916, -1, 4916, 6473, 6463, -1, 6463, 6473, 6464, -1, 6464, 6473, 6470, -1, 6467, 6474, 6461, -1, 6461, 6474, 6472, -1, 6470, 6475, 6458, -1, 6458, 6475, 6471, -1, 3300, 6476, 3313, -1, 6472, 6476, 3300, -1, 6471, 6477, 6467, -1, 6467, 6477, 6474, -1, 6474, 6478, 6472, -1, 3315, 582, 584, -1, 6472, 6478, 6476, -1, 3313, 6479, 3314, -1, 6476, 6479, 3313, -1, 4918, 6480, 4917, -1, 6470, 6480, 6475, -1, 4917, 6480, 6473, -1, 6473, 6480, 6470, -1, 6475, 6455, 6471, -1, 6471, 6455, 6477, -1, 6474, 6446, 6478, -1, 6477, 6446, 6474, -1, 6478, 6449, 6476, -1, 4926, 592, 590, -1, 6443, 6452, 3308, -1, 6476, 6449, 6479, -1, 6479, 6481, 3314, -1, 3308, 6452, 3519, -1, 3314, 6481, 3315, -1, 3315, 6481, 582, -1, 6442, 6450, 6443, -1, 6477, 6444, 6446, -1, 6455, 6444, 6477, -1, 6443, 6450, 6452, -1, 6446, 6447, 6478, -1, 6478, 6447, 6449, -1, 6441, 6457, 6442, -1, 6440, 6457, 6441, -1, 6442, 6457, 6450, -1, 6480, 6459, 6475, -1, 3519, 6453, 3517, -1, 6475, 6459, 6455, -1, 4918, 6459, 6480, -1, 6449, 6454, 6479, -1, 6452, 6453, 3519, -1, 6479, 6454, 6481, -1, 582, 6454, 585, -1, 6481, 6454, 582, -1, 6439, 6464, 6440, -1, 6440, 6464, 6457, -1, 6446, 6445, 6447, -1, 583, 586, 3437, -1, 3437, 586, 6482, -1, 6482, 587, 6483, -1, 586, 587, 6482, -1, 6483, 589, 6484, -1, 587, 589, 6483, -1, 6484, 591, 6485, -1, 589, 591, 6484, -1, 6485, 594, 3974, -1, 591, 594, 6485, -1, 3974, 5122, 6485, -1, 3459, 6486, 3455, -1, 3459, 6487, 6486, -1, 5124, 6487, 3459, -1, 5124, 6488, 6487, -1, 5124, 6489, 6488, -1, 5124, 2109, 6489, -1, 3437, 6490, 3450, -1, 3450, 6490, 3459, -1, 6482, 6490, 3437, -1, 6483, 6491, 6482, -1, 6490, 6491, 3459, -1, 6482, 6491, 6490, -1, 6484, 6492, 6483, -1, 6491, 6492, 3459, -1, 6483, 6492, 6491, -1, 3459, 6492, 5124, -1, 5124, 6493, 5122, -1, 6485, 6493, 6484, -1, 6492, 6493, 5124, -1, 6484, 6493, 6492, -1, 5122, 6493, 6485, -1, 2623, 3455, 2627, -1, 2632, 6486, 2635, -1, 2627, 6486, 2632, -1, 3455, 6486, 2627, -1, 2629, 6487, 2630, -1, 2635, 6487, 2629, -1, 6486, 6487, 2635, -1, 2630, 6488, 6494, -1, 6487, 6488, 2630, -1, 6494, 6489, 6495, -1, 6488, 6489, 6494, -1, 6495, 2109, 2111, -1, 6489, 2109, 6495, -1, 2110, 5125, 2291, -1, 1920, 578, 580, -1, 1920, 576, 578, -1, 5123, 6496, 6497, -1, 5123, 3975, 6496, -1, 1711, 6498, 1919, -1, 1919, 6498, 1920, -1, 1709, 6498, 1711, -1, 1707, 6499, 1709, -1, 6498, 6499, 1920, -1, 1709, 6499, 6498, -1, 1705, 6500, 1707, -1, 1707, 6500, 6499, -1, 1703, 6501, 1705, -1, 1705, 6501, 6500, -1, 1701, 6502, 1703, -1, 1703, 6502, 6501, -1, 2294, 6503, 1701, -1, 1701, 6503, 6502, -1, 5123, 6504, 5125, -1, 2291, 6504, 2294, -1, 2294, 6504, 6503, -1, 5125, 6504, 2291, -1, 6503, 6504, 5123, -1, 576, 6505, 574, -1, 574, 6505, 572, -1, 572, 6505, 570, -1, 570, 6505, 6497, -1, 6499, 6505, 1920, -1, 6500, 6505, 6499, -1, 6503, 6505, 6502, -1, 6501, 6505, 6500, -1, 5123, 6505, 6503, -1, 6502, 6505, 6501, -1, 1920, 6505, 576, -1, 6497, 6505, 5123, -1, 3973, 6506, 3975, -1, 3975, 6506, 6496, -1, 6496, 6507, 6497, -1, 6506, 6507, 6496, -1, 6497, 571, 570, -1, 6507, 571, 6497, -1, 559, 6508, 563, -1, 6509, 6508, 6510, -1, 6510, 6508, 559, -1, 6511, 6508, 6509, -1, 571, 6512, 573, -1, 573, 6512, 6513, -1, 6513, 6514, 6515, -1, 6515, 6514, 6516, -1, 563, 6517, 567, -1, 6511, 6517, 6508, -1, 6508, 6517, 563, -1, 6516, 6517, 6511, -1, 6507, 6518, 571, -1, 571, 6518, 6512, -1, 6513, 6519, 6514, -1, 6512, 6519, 6513, -1, 4925, 6520, 4927, -1, 6506, 6520, 6507, -1, 6507, 6520, 6518, -1, 4927, 6520, 6506, -1, 567, 6521, 569, -1, 6517, 6521, 567, -1, 6514, 6521, 6516, -1, 1997, 559, 561, -1, 6516, 6521, 6517, -1, 6518, 6522, 6512, -1, 6512, 6522, 6519, -1, 569, 6523, 543, -1, 6521, 6523, 569, -1, 6519, 6523, 6514, -1, 6514, 6523, 6521, -1, 3973, 4927, 6506, -1, 4922, 6524, 4925, -1, 4925, 6524, 6520, -1, 6520, 6524, 6518, -1, 6518, 6524, 6522, -1, 543, 6525, 542, -1, 6523, 6525, 543, -1, 6522, 6525, 6519, -1, 6519, 6525, 6523, -1, 4920, 6526, 4922, -1, 6522, 6526, 6525, -1, 4922, 6526, 6524, -1, 542, 6526, 4920, -1, 6524, 6526, 6522, -1, 6525, 6526, 542, -1, 4920, 557, 542, -1, 579, 6527, 581, -1, 581, 6527, 2006, -1, 577, 6528, 579, -1, 579, 6528, 6527, -1, 2006, 6509, 2003, -1, 2003, 6509, 1999, -1, 6527, 6509, 2006, -1, 575, 6515, 577, -1, 577, 6515, 6528, -1, 6527, 6511, 6509, -1, 6528, 6511, 6527, -1, 1999, 6510, 1997, -1, 6509, 6510, 1999, -1, 1997, 6510, 559, -1, 573, 6513, 575, -1, 575, 6513, 6515, -1, 6515, 6516, 6528, -1, 6528, 6516, 6511, -1, 558, 3980, 555, -1, 555, 6529, 550, -1, 3980, 6529, 555, -1, 550, 6530, 547, -1, 6529, 6530, 550, -1, 547, 6531, 535, -1, 6530, 6531, 547, -1, 535, 6532, 533, -1, 6531, 6532, 535, -1, 533, 6533, 552, -1, 6532, 6533, 533, -1, 552, 6534, 553, -1, 6533, 6534, 552, -1, 6534, 1806, 553, -1, 6535, 6536, 1792, -1, 6530, 6537, 6531, -1, 6531, 6537, 6538, -1, 6538, 6539, 6540, -1, 6540, 6539, 6541, -1, 6542, 6543, 6535, -1, 6535, 6543, 6536, -1, 1785, 6544, 1780, -1, 1780, 6544, 1778, -1, 1778, 6544, 6545, -1, 6545, 6544, 6546, -1, 6536, 6544, 1785, -1, 4906, 6547, 3980, -1, 6529, 6547, 6530, -1, 3980, 6547, 6529, -1, 6530, 6547, 6537, -1, 6537, 6548, 6538, -1, 6538, 6548, 6539, -1, 6542, 6549, 6543, -1, 6541, 6549, 6542, -1, 6543, 6550, 6536, -1, 6544, 6550, 6546, -1, 6536, 6550, 6544, -1, 4909, 6551, 4908, -1, 4908, 6551, 4906, -1, 4906, 6551, 6547, -1, 6547, 6551, 6537, -1, 6537, 6551, 6548, -1, 6539, 6552, 6541, -1, 6541, 6552, 6549, -1, 6546, 6553, 6554, -1, 6550, 6553, 6546, -1, 6543, 6553, 6550, -1, 6549, 6553, 6543, -1, 6548, 6555, 6539, -1, 6539, 6555, 6552, -1, 6552, 6556, 6549, -1, 6554, 6556, 6557, -1, 6553, 6556, 6554, -1, 6549, 6556, 6553, -1, 4913, 6558, 4911, -1, 4911, 6558, 4909, -1, 6548, 6558, 6555, -1, 4909, 6558, 6551, -1, 6551, 6558, 6548, -1, 6555, 6559, 6552, -1, 6556, 6559, 6557, -1, 6557, 6559, 6560, -1, 4913, 3977, 6561, -1, 6552, 6559, 6556, -1, 1806, 6562, 1805, -1, 6555, 6563, 6559, -1, 1805, 6562, 1795, -1, 6560, 6563, 6561, -1, 4913, 6563, 6558, -1, 6558, 6563, 6555, -1, 6534, 6562, 1806, -1, 6561, 6563, 4913, -1, 6559, 6563, 6560, -1, 6533, 6564, 6534, -1, 6534, 6564, 6562, -1, 1795, 6535, 1792, -1, 6562, 6535, 1795, -1, 6532, 6540, 6533, -1, 6533, 6540, 6564, -1, 6562, 6542, 6535, -1, 6564, 6542, 6562, -1, 6531, 6538, 6532, -1, 6532, 6538, 6540, -1, 6540, 6541, 6564, -1, 6564, 6541, 6542, -1, 1792, 6536, 1785, -1, 1778, 6545, 1808, -1, 1808, 6545, 6565, -1, 6565, 6546, 6566, -1, 6545, 6546, 6565, -1, 6566, 6554, 6567, -1, 6546, 6554, 6566, -1, 6567, 6557, 6568, -1, 6554, 6557, 6567, -1, 6568, 6560, 6569, -1, 6557, 6560, 6568, -1, 6569, 6561, 6570, -1, 6570, 6561, 3979, -1, 6560, 6561, 6569, -1, 6561, 3977, 3979, -1, 5119, 6570, 3979, -1, 1819, 1816, 2305, -1, 5119, 6569, 6570, -1, 5119, 6568, 6569, -1, 1815, 6566, 6567, -1, 1815, 6565, 6566, -1, 1815, 1808, 6565, -1, 2296, 6571, 2106, -1, 2106, 6571, 5121, -1, 5121, 6571, 5119, -1, 2298, 6572, 2296, -1, 6571, 6572, 5119, -1, 2296, 6572, 6571, -1, 2300, 6573, 2298, -1, 6572, 6573, 5119, -1, 2298, 6573, 6572, -1, 5119, 6573, 6568, -1, 2302, 6574, 2300, -1, 6568, 6574, 6567, -1, 6573, 6574, 6568, -1, 2300, 6574, 6573, -1, 6567, 6574, 1815, -1, 2305, 6575, 2303, -1, 2303, 6575, 2302, -1, 6574, 6575, 1815, -1, 2302, 6575, 6574, -1, 1815, 6576, 1816, -1, 6575, 6576, 1815, -1, 1816, 6576, 2305, -1, 2305, 6576, 6575, -1, 6577, 5102, 3996, -1, 5104, 2310, 2090, -1, 5104, 2313, 2310, -1, 3466, 3475, 6578, -1, 5104, 2316, 2313, -1, 3474, 2324, 2321, -1, 3474, 2326, 2324, -1, 3474, 2328, 2326, -1, 5102, 6579, 5104, -1, 6577, 6579, 5102, -1, 6580, 6581, 6577, -1, 6579, 6581, 5104, -1, 6577, 6581, 6579, -1, 6582, 6583, 6580, -1, 6581, 6583, 5104, -1, 6580, 6583, 6581, -1, 5104, 6583, 2316, -1, 6584, 6585, 6582, -1, 2316, 6585, 2319, -1, 6582, 6585, 6583, -1, 6583, 6585, 2316, -1, 6586, 6587, 6584, -1, 2319, 6587, 2321, -1, 6585, 6587, 2319, -1, 6584, 6587, 6585, -1, 6588, 6589, 6586, -1, 6586, 6589, 6587, -1, 6587, 6589, 2321, -1, 2321, 6589, 3474, -1, 6590, 6591, 6588, -1, 6589, 6591, 3474, -1, 6588, 6591, 6589, -1, 3474, 6592, 3475, -1, 6578, 6592, 6590, -1, 6591, 6592, 3474, -1, 6590, 6592, 6591, -1, 3475, 6592, 6578, -1, 3998, 6593, 3996, -1, 3996, 6593, 6577, -1, 6577, 6594, 6580, -1, 6593, 6594, 6577, -1, 6580, 6595, 6582, -1, 6594, 6595, 6580, -1, 6582, 6596, 6584, -1, 6595, 6596, 6582, -1, 6584, 6597, 6586, -1, 6596, 6597, 6584, -1, 6586, 6598, 6588, -1, 6597, 6598, 6586, -1, 6588, 6599, 6590, -1, 6598, 6599, 6588, -1, 6590, 6600, 6578, -1, 6599, 6600, 6590, -1, 6578, 3383, 3466, -1, 6600, 3383, 6578, -1, 6601, 6602, 6603, -1, 6603, 6602, 6604, -1, 6605, 6606, 6607, -1, 6604, 6606, 6605, -1, 6595, 6608, 6596, -1, 6596, 6608, 6609, -1, 6609, 6610, 6601, -1, 6601, 6610, 6602, -1, 3360, 6611, 3365, -1, 6607, 6611, 3360, -1, 3365, 6611, 6612, -1, 6602, 6613, 6604, -1, 6604, 6613, 6606, -1, 6594, 6614, 6595, -1, 6595, 6614, 6608, -1, 6612, 6615, 6616, -1, 6611, 6615, 6612, -1, 6606, 6615, 6607, -1, 6607, 6615, 6611, -1, 6609, 6617, 6610, -1, 6608, 6617, 6609, -1, 3365, 6612, 3402, -1, 6610, 6618, 6602, -1, 6602, 6618, 6613, -1, 3998, 4971, 6593, -1, 6616, 6619, 6620, -1, 6615, 6619, 6616, -1, 6613, 6619, 6606, -1, 6606, 6619, 6615, -1, 4969, 6621, 4971, -1, 6593, 6621, 6594, -1, 6594, 6621, 6614, -1, 4971, 6621, 6593, -1, 6614, 6622, 6608, -1, 6608, 6622, 6617, -1, 6617, 6623, 6610, -1, 6610, 6623, 6618, -1, 6613, 6624, 6619, -1, 6620, 6624, 6625, -1, 6619, 6624, 6620, -1, 6618, 6624, 6613, -1, 6621, 6626, 6614, -1, 4967, 6626, 4969, -1, 6614, 6626, 6622, -1, 4969, 6626, 6621, -1, 6622, 6627, 6617, -1, 6617, 6627, 6623, -1, 3383, 6628, 3378, -1, 6623, 6629, 6618, -1, 6618, 6629, 6624, -1, 6600, 6628, 3383, -1, 6624, 6629, 6625, -1, 4964, 6630, 4967, -1, 4967, 6630, 6626, -1, 6626, 6630, 6622, -1, 6599, 6603, 6600, -1, 6622, 6630, 6627, -1, 6625, 6631, 6632, -1, 6600, 6603, 6628, -1, 6629, 6631, 6625, -1, 6623, 6631, 6629, -1, 6627, 6631, 6623, -1, 3378, 6605, 3373, -1, 3373, 6605, 3363, -1, 6632, 6633, 6634, -1, 6628, 6605, 3378, -1, 6634, 6633, 4001, -1, 4001, 6633, 4964, -1, 6631, 6633, 6632, -1, 6630, 6633, 6627, -1, 6627, 6633, 6631, -1, 6598, 6601, 6599, -1, 4964, 6633, 6630, -1, 6599, 6601, 6603, -1, 6628, 6604, 6605, -1, 6603, 6604, 6628, -1, 3363, 6607, 3360, -1, 6605, 6607, 3363, -1, 6597, 6609, 6598, -1, 6596, 6609, 6597, -1, 6598, 6609, 6601, -1, 4001, 4002, 6634, -1, 6634, 6635, 6632, -1, 4002, 6635, 6634, -1, 6632, 6636, 6625, -1, 6635, 6636, 6632, -1, 6625, 6637, 6620, -1, 6636, 6637, 6625, -1, 6620, 6638, 6616, -1, 6637, 6638, 6620, -1, 6616, 6639, 6612, -1, 6638, 6639, 6616, -1, 6612, 6640, 3402, -1, 6639, 6640, 6612, -1, 6640, 3403, 3402, -1, 6641, 6642, 6643, -1, 6644, 6645, 6646, -1, 519, 6642, 522, -1, 6646, 6645, 6647, -1, 6643, 6642, 6648, -1, 6648, 6642, 519, -1, 6649, 6650, 6651, -1, 6652, 6653, 6644, -1, 6654, 6650, 6649, -1, 6644, 6653, 6645, -1, 4956, 6655, 4954, -1, 4954, 6655, 4953, -1, 4953, 6655, 6654, -1, 3405, 6656, 3408, -1, 6641, 6657, 6642, -1, 6647, 6656, 3405, -1, 6658, 6657, 6641, -1, 6642, 6657, 522, -1, 4951, 6659, 4950, -1, 6635, 6659, 6636, -1, 6636, 6659, 6660, -1, 6651, 6661, 6658, -1, 4950, 6659, 6635, -1, 6650, 6661, 6651, -1, 4956, 6662, 6655, -1, 6654, 6662, 6650, -1, 6647, 6663, 6656, -1, 6655, 6662, 6654, -1, 4961, 6664, 4959, -1, 6645, 6663, 6647, -1, 522, 6664, 524, -1, 6658, 6664, 6657, -1, 6661, 6664, 6658, -1, 6657, 6664, 522, -1, 524, 6664, 4961, -1, 4959, 6665, 4958, -1, 4958, 6665, 4956, -1, 6652, 6666, 6653, -1, 6664, 6665, 4959, -1, 6660, 6666, 6652, -1, 6650, 6665, 6661, -1, 6662, 6665, 6650, -1, 6661, 6665, 6664, -1, 4956, 6665, 6662, -1, 6645, 6667, 6663, -1, 6653, 6667, 6645, -1, 3408, 6668, 3411, -1, 4002, 4950, 6635, -1, 6656, 6668, 3408, -1, 4952, 6669, 4951, -1, 4951, 6669, 6659, -1, 6659, 6669, 6660, -1, 6660, 6669, 6666, -1, 6663, 6670, 6656, -1, 6656, 6670, 6668, -1, 6666, 6671, 6653, -1, 6653, 6671, 6667, -1, 3411, 6672, 3417, -1, 6668, 6672, 3411, -1, 6667, 6673, 6663, -1, 6663, 6673, 6670, -1, 6670, 6674, 6668, -1, 3426, 516, 518, -1, 6668, 6674, 6672, -1, 3417, 6675, 3421, -1, 6672, 6675, 3417, -1, 4953, 6676, 4952, -1, 6666, 6676, 6671, -1, 4952, 6676, 6669, -1, 6669, 6676, 6666, -1, 6671, 6649, 6667, -1, 6667, 6649, 6673, -1, 6670, 6677, 6674, -1, 6673, 6677, 6670, -1, 6674, 6643, 6672, -1, 4961, 526, 524, -1, 6640, 6646, 3403, -1, 6672, 6643, 6675, -1, 6675, 6678, 3421, -1, 3403, 6646, 3404, -1, 3421, 6678, 3426, -1, 3426, 6678, 516, -1, 6639, 6644, 6640, -1, 6673, 6651, 6677, -1, 6649, 6651, 6673, -1, 6640, 6644, 6646, -1, 6677, 6641, 6674, -1, 6674, 6641, 6643, -1, 6638, 6652, 6639, -1, 6637, 6652, 6638, -1, 6639, 6652, 6644, -1, 6676, 6654, 6671, -1, 3404, 6647, 3405, -1, 6671, 6654, 6649, -1, 4953, 6654, 6676, -1, 6643, 6648, 6675, -1, 6646, 6647, 3404, -1, 6675, 6648, 6678, -1, 516, 6648, 519, -1, 6678, 6648, 516, -1, 6636, 6660, 6637, -1, 6637, 6660, 6652, -1, 6677, 6658, 6641, -1, 6651, 6658, 6677, -1, 517, 520, 3488, -1, 3488, 520, 6679, -1, 6679, 521, 6680, -1, 520, 521, 6679, -1, 6680, 523, 6681, -1, 521, 523, 6680, -1, 6681, 525, 6682, -1, 523, 525, 6681, -1, 6682, 528, 3994, -1, 525, 528, 6682, -1, 3994, 5106, 6682, -1, 3504, 6683, 3503, -1, 3504, 6684, 6683, -1, 5108, 6684, 3504, -1, 5108, 6685, 6684, -1, 5108, 6686, 6685, -1, 5108, 2091, 6686, -1, 3488, 6687, 3498, -1, 3498, 6687, 3504, -1, 6679, 6687, 3488, -1, 6680, 6688, 6679, -1, 6687, 6688, 3504, -1, 6679, 6688, 6687, -1, 6681, 6689, 6680, -1, 6688, 6689, 3504, -1, 6680, 6689, 6688, -1, 3504, 6689, 5108, -1, 5108, 6690, 5106, -1, 6682, 6690, 6681, -1, 6689, 6690, 5108, -1, 6681, 6690, 6689, -1, 5106, 6690, 6682, -1, 2263, 3503, 2262, -1, 2262, 6683, 2261, -1, 3503, 6683, 2262, -1, 2261, 6684, 2259, -1, 2259, 6684, 2260, -1, 6683, 6684, 2261, -1, 2260, 6685, 2334, -1, 6684, 6685, 2260, -1, 2334, 6686, 2330, -1, 6685, 6686, 2334, -1, 2330, 2091, 2093, -1, 6686, 2091, 2330, -1, 6691, 5110, 3986, -1, 5112, 2337, 2099, -1, 5112, 2340, 2337, -1, 3436, 3449, 6692, -1, 5112, 2343, 2340, -1, 3448, 2351, 2348, -1, 3448, 2353, 2351, -1, 3448, 2355, 2353, -1, 5110, 6693, 5112, -1, 6691, 6693, 5110, -1, 6694, 6695, 6691, -1, 6693, 6695, 5112, -1, 6691, 6695, 6693, -1, 6696, 6697, 6694, -1, 6695, 6697, 5112, -1, 6694, 6697, 6695, -1, 5112, 6697, 2343, -1, 6698, 6699, 6696, -1, 2343, 6699, 2346, -1, 6696, 6699, 6697, -1, 6697, 6699, 2343, -1, 6700, 6701, 6698, -1, 2346, 6701, 2348, -1, 6699, 6701, 2346, -1, 6698, 6701, 6699, -1, 6702, 6703, 6700, -1, 6700, 6703, 6701, -1, 6701, 6703, 2348, -1, 2348, 6703, 3448, -1, 6704, 6705, 6702, -1, 6703, 6705, 3448, -1, 6702, 6705, 6703, -1, 3448, 6706, 3449, -1, 6692, 6706, 6704, -1, 6705, 6706, 3448, -1, 6704, 6706, 6705, -1, 3449, 6706, 6692, -1, 3988, 6707, 3986, -1, 3986, 6707, 6691, -1, 6691, 6708, 6694, -1, 6707, 6708, 6691, -1, 6694, 6709, 6696, -1, 6708, 6709, 6694, -1, 6696, 6710, 6698, -1, 6709, 6710, 6696, -1, 6698, 6711, 6700, -1, 6710, 6711, 6698, -1, 6700, 6712, 6702, -1, 6711, 6712, 6700, -1, 6702, 6713, 6704, -1, 6712, 6713, 6702, -1, 6704, 6714, 6692, -1, 6713, 6714, 6704, -1, 6692, 3312, 3436, -1, 6714, 3312, 6692, -1, 6715, 6716, 6717, -1, 6717, 6716, 6718, -1, 6719, 6720, 6721, -1, 6718, 6720, 6719, -1, 6709, 6722, 6710, -1, 6710, 6722, 6723, -1, 6723, 6724, 6715, -1, 6715, 6724, 6716, -1, 3518, 6725, 3306, -1, 6721, 6725, 3518, -1, 3306, 6725, 6726, -1, 6716, 6727, 6718, -1, 6718, 6727, 6720, -1, 6708, 6728, 6709, -1, 6709, 6728, 6722, -1, 6726, 6729, 6730, -1, 6725, 6729, 6726, -1, 6720, 6729, 6721, -1, 6721, 6729, 6725, -1, 6723, 6731, 6724, -1, 6722, 6731, 6723, -1, 3306, 6726, 3307, -1, 6724, 6732, 6716, -1, 6716, 6732, 6727, -1, 3988, 4936, 6707, -1, 6730, 6733, 6734, -1, 6729, 6733, 6730, -1, 6727, 6733, 6720, -1, 6720, 6733, 6729, -1, 4934, 6735, 4936, -1, 6707, 6735, 6708, -1, 6708, 6735, 6728, -1, 4936, 6735, 6707, -1, 6728, 6736, 6722, -1, 6722, 6736, 6731, -1, 6731, 6737, 6724, -1, 6724, 6737, 6732, -1, 6727, 6738, 6733, -1, 6734, 6738, 6739, -1, 6733, 6738, 6734, -1, 6732, 6738, 6727, -1, 6735, 6740, 6728, -1, 4932, 6740, 4934, -1, 6728, 6740, 6736, -1, 4934, 6740, 6735, -1, 6736, 6741, 6731, -1, 6731, 6741, 6737, -1, 3312, 6742, 3309, -1, 6737, 6743, 6732, -1, 6732, 6743, 6738, -1, 6714, 6742, 3312, -1, 6738, 6743, 6739, -1, 4929, 6744, 4932, -1, 4932, 6744, 6740, -1, 6740, 6744, 6736, -1, 6713, 6717, 6714, -1, 6736, 6744, 6741, -1, 6739, 6745, 6746, -1, 6714, 6717, 6742, -1, 6743, 6745, 6739, -1, 6737, 6745, 6743, -1, 6741, 6745, 6737, -1, 3309, 6719, 3295, -1, 3295, 6719, 3296, -1, 6746, 6747, 6748, -1, 6742, 6719, 3309, -1, 6748, 6747, 3991, -1, 3991, 6747, 4929, -1, 6745, 6747, 6746, -1, 6744, 6747, 6741, -1, 6741, 6747, 6745, -1, 6712, 6715, 6713, -1, 4929, 6747, 6744, -1, 6713, 6715, 6717, -1, 6742, 6718, 6719, -1, 6717, 6718, 6742, -1, 3296, 6721, 3518, -1, 6719, 6721, 3296, -1, 6711, 6723, 6712, -1, 6710, 6723, 6711, -1, 6712, 6723, 6715, -1, 3992, 6749, 3991, -1, 3991, 6749, 6748, -1, 6748, 6750, 6746, -1, 6749, 6750, 6748, -1, 6746, 6751, 6739, -1, 6750, 6751, 6746, -1, 6739, 6752, 6734, -1, 6751, 6752, 6739, -1, 6734, 6753, 6730, -1, 6752, 6753, 6734, -1, 6730, 6754, 6726, -1, 6753, 6754, 6730, -1, 6726, 3401, 3307, -1, 6754, 3401, 6726, -1, 6755, 6756, 6757, -1, 6758, 6759, 6760, -1, 6761, 6762, 6763, -1, 506, 6759, 508, -1, 6763, 6762, 6764, -1, 6760, 6759, 6765, -1, 6765, 6759, 506, -1, 6766, 6767, 6755, -1, 6768, 6769, 6761, -1, 6770, 6767, 6766, -1, 6761, 6769, 6762, -1, 4943, 6771, 4941, -1, 4941, 6771, 4940, -1, 4940, 6771, 6770, -1, 3359, 6772, 3362, -1, 6758, 6773, 6759, -1, 6764, 6772, 3359, -1, 6756, 6773, 6758, -1, 6759, 6773, 508, -1, 4938, 6774, 4937, -1, 6749, 6774, 6750, -1, 6750, 6774, 6775, -1, 6755, 6776, 6756, -1, 4937, 6774, 6749, -1, 6767, 6776, 6755, -1, 4943, 6777, 6771, -1, 6770, 6777, 6767, -1, 6764, 6778, 6772, -1, 6771, 6777, 6770, -1, 4948, 6779, 4946, -1, 6762, 6778, 6764, -1, 508, 6779, 511, -1, 6756, 6779, 6773, -1, 6776, 6779, 6756, -1, 6773, 6779, 508, -1, 511, 6779, 4948, -1, 4946, 6780, 4945, -1, 4945, 6780, 4943, -1, 6768, 6781, 6769, -1, 6779, 6780, 4946, -1, 6775, 6781, 6768, -1, 6767, 6780, 6776, -1, 6777, 6780, 6767, -1, 6776, 6780, 6779, -1, 4943, 6780, 6777, -1, 6762, 6782, 6778, -1, 6769, 6782, 6762, -1, 3362, 6783, 3372, -1, 3992, 4937, 6749, -1, 6772, 6783, 3362, -1, 4939, 6784, 4938, -1, 4938, 6784, 6774, -1, 6774, 6784, 6775, -1, 6775, 6784, 6781, -1, 6778, 6785, 6772, -1, 6772, 6785, 6783, -1, 6781, 6786, 6769, -1, 6769, 6786, 6782, -1, 3372, 6787, 3382, -1, 6783, 6787, 3372, -1, 6782, 6788, 6778, -1, 6778, 6788, 6785, -1, 6785, 6789, 6783, -1, 3386, 503, 505, -1, 6783, 6789, 6787, -1, 3382, 6790, 3384, -1, 6787, 6790, 3382, -1, 4940, 6791, 4939, -1, 6781, 6791, 6786, -1, 4939, 6791, 6784, -1, 6784, 6791, 6781, -1, 6786, 6766, 6782, -1, 6782, 6766, 6788, -1, 6785, 6757, 6789, -1, 6788, 6757, 6785, -1, 6789, 6760, 6787, -1, 4948, 513, 511, -1, 6754, 6763, 3401, -1, 6787, 6760, 6790, -1, 6790, 6792, 3384, -1, 3401, 6763, 3361, -1, 3384, 6792, 3386, -1, 3386, 6792, 503, -1, 6753, 6761, 6754, -1, 6788, 6755, 6757, -1, 6766, 6755, 6788, -1, 6754, 6761, 6763, -1, 6757, 6758, 6789, -1, 6789, 6758, 6760, -1, 6752, 6768, 6753, -1, 6751, 6768, 6752, -1, 6753, 6768, 6761, -1, 6791, 6770, 6786, -1, 3361, 6764, 3359, -1, 6786, 6770, 6766, -1, 4940, 6770, 6791, -1, 6760, 6765, 6790, -1, 6763, 6764, 3361, -1, 6790, 6765, 6792, -1, 503, 6765, 506, -1, 6792, 6765, 503, -1, 6750, 6775, 6751, -1, 6751, 6775, 6768, -1, 6757, 6756, 6758, -1, 3465, 504, 6793, -1, 6793, 507, 6794, -1, 504, 507, 6793, -1, 6794, 509, 6795, -1, 507, 509, 6794, -1, 6795, 510, 6796, -1, 509, 510, 6795, -1, 6796, 512, 3984, -1, 510, 512, 6796, -1, 512, 515, 3984, -1, 3984, 5114, 6796, -1, 3484, 6797, 3478, -1, 3484, 6798, 6797, -1, 5116, 6798, 3484, -1, 5116, 6799, 6798, -1, 5116, 6800, 6799, -1, 5116, 2100, 6800, -1, 3465, 6801, 3476, -1, 3476, 6801, 3484, -1, 6793, 6801, 3465, -1, 6794, 6802, 6793, -1, 6801, 6802, 3484, -1, 6793, 6802, 6801, -1, 6795, 6803, 6794, -1, 6802, 6803, 3484, -1, 6794, 6803, 6802, -1, 3484, 6803, 5116, -1, 5116, 6804, 5114, -1, 6796, 6804, 6795, -1, 6803, 6804, 5116, -1, 6795, 6804, 6803, -1, 5114, 6804, 6796, -1, 2594, 3478, 2598, -1, 2603, 6797, 2606, -1, 2598, 6797, 2603, -1, 3478, 6797, 2598, -1, 2600, 6798, 2601, -1, 2606, 6798, 2600, -1, 6797, 6798, 2606, -1, 2601, 6799, 6805, -1, 6798, 6799, 2601, -1, 6805, 6800, 6806, -1, 6799, 6800, 6805, -1, 6806, 2100, 2102, -1, 6800, 2100, 6806, -1, 6807, 5126, 3966, -1, 5128, 2364, 2117, -1, 5128, 2367, 2364, -1, 3291, 3317, 6808, -1, 5128, 2370, 2367, -1, 3316, 2378, 2375, -1, 3316, 2380, 2378, -1, 3316, 2382, 2380, -1, 5126, 6809, 5128, -1, 6807, 6809, 5126, -1, 6810, 6811, 6807, -1, 6809, 6811, 5128, -1, 6807, 6811, 6809, -1, 6812, 6813, 6810, -1, 6811, 6813, 5128, -1, 6810, 6813, 6811, -1, 5128, 6813, 2370, -1, 6814, 6815, 6812, -1, 2370, 6815, 2373, -1, 6812, 6815, 6813, -1, 6813, 6815, 2370, -1, 6816, 6817, 6814, -1, 2373, 6817, 2375, -1, 6815, 6817, 2373, -1, 6814, 6817, 6815, -1, 6818, 6819, 6816, -1, 6816, 6819, 6817, -1, 6817, 6819, 2375, -1, 2375, 6819, 3316, -1, 6820, 6821, 6818, -1, 6819, 6821, 3316, -1, 6818, 6821, 6819, -1, 3316, 6822, 3317, -1, 6808, 6822, 6820, -1, 6821, 6822, 3316, -1, 6820, 6822, 6821, -1, 3317, 6822, 6808, -1, 3968, 6823, 3966, -1, 3966, 6823, 6807, -1, 6807, 6824, 6810, -1, 6823, 6824, 6807, -1, 6810, 6825, 6812, -1, 6824, 6825, 6810, -1, 6812, 6826, 6814, -1, 6825, 6826, 6812, -1, 6814, 6827, 6816, -1, 6826, 6827, 6814, -1, 6816, 6828, 6818, -1, 6827, 6828, 6816, -1, 6818, 6829, 6820, -1, 6828, 6829, 6818, -1, 6820, 6830, 6808, -1, 6829, 6830, 6820, -1, 6808, 3293, 3291, -1, 6830, 3293, 6808, -1, 6831, 6832, 6833, -1, 6833, 6832, 6834, -1, 6835, 6836, 6837, -1, 6834, 6836, 6835, -1, 6825, 6838, 6826, -1, 6826, 6838, 6839, -1, 6839, 6840, 6831, -1, 6831, 6840, 6832, -1, 3398, 6841, 3409, -1, 6837, 6841, 3398, -1, 3409, 6841, 6842, -1, 6832, 6843, 6834, -1, 6834, 6843, 6836, -1, 6824, 6844, 6825, -1, 6825, 6844, 6838, -1, 6842, 6845, 6846, -1, 6841, 6845, 6842, -1, 6836, 6845, 6837, -1, 6837, 6845, 6841, -1, 6839, 6847, 6840, -1, 6838, 6847, 6839, -1, 3409, 6842, 3419, -1, 6840, 6848, 6832, -1, 6832, 6848, 6843, -1, 6846, 6849, 6850, -1, 3968, 4905, 6823, -1, 6845, 6849, 6846, -1, 6843, 6849, 6836, -1, 6836, 6849, 6845, -1, 4903, 6851, 4905, -1, 6823, 6851, 6824, -1, 6824, 6851, 6844, -1, 4905, 6851, 6823, -1, 6844, 6852, 6838, -1, 6838, 6852, 6847, -1, 6847, 6853, 6840, -1, 6840, 6853, 6848, -1, 6843, 6854, 6849, -1, 6850, 6854, 6855, -1, 6849, 6854, 6850, -1, 6848, 6854, 6843, -1, 6851, 6856, 6844, -1, 4901, 6856, 4903, -1, 6844, 6856, 6852, -1, 4903, 6856, 6851, -1, 6852, 6857, 6847, -1, 6847, 6857, 6853, -1, 3293, 6858, 3420, -1, 6853, 6859, 6848, -1, 6848, 6859, 6854, -1, 6830, 6858, 3293, -1, 6854, 6859, 6855, -1, 4898, 6860, 4901, -1, 4901, 6860, 6856, -1, 6856, 6860, 6852, -1, 6829, 6833, 6830, -1, 6852, 6860, 6857, -1, 6855, 6861, 6862, -1, 6830, 6833, 6858, -1, 6859, 6861, 6855, -1, 6853, 6861, 6859, -1, 6857, 6861, 6853, -1, 3420, 6835, 3416, -1, 3416, 6835, 3407, -1, 6862, 6863, 6864, -1, 6858, 6835, 3420, -1, 6864, 6863, 3971, -1, 3971, 6863, 4898, -1, 6861, 6863, 6862, -1, 6860, 6863, 6857, -1, 6857, 6863, 6861, -1, 6828, 6831, 6829, -1, 4898, 6863, 6860, -1, 6829, 6831, 6833, -1, 6858, 6834, 6835, -1, 6833, 6834, 6858, -1, 3407, 6837, 3398, -1, 6835, 6837, 3407, -1, 6827, 6839, 6828, -1, 6826, 6839, 6827, -1, 6828, 6839, 6831, -1, 3972, 6865, 3971, -1, 3971, 6865, 6864, -1, 6864, 6866, 6862, -1, 6865, 6866, 6864, -1, 6862, 6867, 6855, -1, 6866, 6867, 6862, -1, 6855, 6868, 6850, -1, 6867, 6868, 6855, -1, 6850, 6869, 6846, -1, 6868, 6869, 6850, -1, 6846, 6870, 6842, -1, 6869, 6870, 6846, -1, 6842, 3468, 3419, -1, 6870, 3468, 6842, -1, 6871, 6872, 6873, -1, 6874, 6875, 6876, -1, 6877, 6878, 6879, -1, 493, 6875, 495, -1, 6879, 6878, 6880, -1, 6876, 6875, 6881, -1, 6881, 6875, 493, -1, 6882, 6883, 6871, -1, 6884, 6885, 6877, -1, 6886, 6883, 6882, -1, 6877, 6885, 6878, -1, 4890, 6887, 4888, -1, 4888, 6887, 4887, -1, 4887, 6887, 6886, -1, 3460, 6888, 3463, -1, 6874, 6889, 6875, -1, 6880, 6888, 3460, -1, 6872, 6889, 6874, -1, 6875, 6889, 495, -1, 4885, 6890, 4884, -1, 6865, 6890, 6866, -1, 6866, 6890, 6891, -1, 6871, 6892, 6872, -1, 4884, 6890, 6865, -1, 6883, 6892, 6871, -1, 4890, 6893, 6887, -1, 6886, 6893, 6883, -1, 6880, 6894, 6888, -1, 6887, 6893, 6886, -1, 4895, 6895, 4893, -1, 6878, 6894, 6880, -1, 495, 6895, 498, -1, 6872, 6895, 6889, -1, 6892, 6895, 6872, -1, 6889, 6895, 495, -1, 498, 6895, 4895, -1, 4893, 6896, 4892, -1, 4892, 6896, 4890, -1, 6884, 6897, 6885, -1, 6895, 6896, 4893, -1, 6891, 6897, 6884, -1, 6883, 6896, 6892, -1, 6893, 6896, 6883, -1, 6892, 6896, 6895, -1, 4890, 6896, 6893, -1, 6878, 6898, 6894, -1, 6885, 6898, 6878, -1, 3463, 6899, 3472, -1, 3972, 4884, 6865, -1, 6888, 6899, 3463, -1, 4886, 6900, 4885, -1, 4885, 6900, 6890, -1, 6890, 6900, 6891, -1, 6891, 6900, 6897, -1, 6894, 6901, 6888, -1, 6888, 6901, 6899, -1, 6897, 6902, 6885, -1, 6885, 6902, 6898, -1, 3472, 6903, 3481, -1, 6899, 6903, 3472, -1, 6898, 6904, 6894, -1, 6894, 6904, 6901, -1, 6901, 6905, 6899, -1, 3483, 490, 492, -1, 6899, 6905, 6903, -1, 3481, 6906, 3482, -1, 6903, 6906, 3481, -1, 4887, 6907, 4886, -1, 6897, 6907, 6902, -1, 4886, 6907, 6900, -1, 6900, 6907, 6897, -1, 6902, 6882, 6898, -1, 6898, 6882, 6904, -1, 6901, 6873, 6905, -1, 6904, 6873, 6901, -1, 6905, 6876, 6903, -1, 4895, 500, 498, -1, 6870, 6879, 3468, -1, 6903, 6876, 6906, -1, 6906, 6908, 3482, -1, 3468, 6879, 3462, -1, 3482, 6908, 3483, -1, 3483, 6908, 490, -1, 6869, 6877, 6870, -1, 6904, 6871, 6873, -1, 6882, 6871, 6904, -1, 6870, 6877, 6879, -1, 6873, 6874, 6905, -1, 6905, 6874, 6876, -1, 6868, 6884, 6869, -1, 6867, 6884, 6868, -1, 6869, 6884, 6877, -1, 6907, 6886, 6902, -1, 3462, 6880, 3460, -1, 6902, 6886, 6882, -1, 4887, 6886, 6907, -1, 6876, 6881, 6906, -1, 6879, 6880, 3462, -1, 6906, 6881, 6908, -1, 490, 6881, 493, -1, 6908, 6881, 490, -1, 6866, 6891, 6867, -1, 6867, 6891, 6884, -1, 6873, 6872, 6874, -1, 491, 494, 3366, -1, 3366, 494, 6909, -1, 6909, 496, 6910, -1, 494, 496, 6909, -1, 6910, 497, 6911, -1, 496, 497, 6910, -1, 6911, 499, 6912, -1, 497, 499, 6911, -1, 6912, 502, 3964, -1, 499, 502, 6912, -1, 3964, 5130, 6912, -1, 3425, 6913, 3418, -1, 3425, 6914, 6913, -1, 5132, 6914, 3425, -1, 5132, 6915, 6914, -1, 5132, 6916, 6915, -1, 5132, 2118, 6916, -1, 3366, 6917, 3391, -1, 3391, 6917, 3425, -1, 6909, 6917, 3366, -1, 6910, 6918, 6909, -1, 6917, 6918, 3425, -1, 6909, 6918, 6917, -1, 6911, 6919, 6910, -1, 6918, 6919, 3425, -1, 6910, 6919, 6918, -1, 3425, 6919, 5132, -1, 5132, 6920, 5130, -1, 6912, 6920, 6911, -1, 6919, 6920, 5132, -1, 6911, 6920, 6919, -1, 5130, 6920, 6912, -1, 2652, 3418, 2656, -1, 2661, 6913, 2664, -1, 2656, 6913, 2661, -1, 3418, 6913, 2656, -1, 2658, 6914, 2659, -1, 2664, 6914, 2658, -1, 6913, 6914, 2664, -1, 2659, 6915, 6921, -1, 6914, 6915, 2659, -1, 6921, 6916, 6922, -1, 6915, 6916, 6921, -1, 6922, 2118, 2120, -1, 6916, 2118, 6922, -1, 6923, 5134, 3956, -1, 5136, 2395, 2126, -1, 5136, 2398, 2395, -1, 3469, 3486, 6924, -1, 5136, 2401, 2398, -1, 3485, 2408, 2406, -1, 3485, 2411, 2408, -1, 3485, 2412, 2411, -1, 5134, 6925, 5136, -1, 6923, 6925, 5134, -1, 6926, 6927, 6923, -1, 6925, 6927, 5136, -1, 6923, 6927, 6925, -1, 6928, 6929, 6926, -1, 6927, 6929, 5136, -1, 6926, 6929, 6927, -1, 5136, 6929, 2401, -1, 6930, 6931, 6928, -1, 2401, 6931, 2404, -1, 6928, 6931, 6929, -1, 6929, 6931, 2401, -1, 6932, 6933, 6930, -1, 2404, 6933, 2406, -1, 6931, 6933, 2404, -1, 6930, 6933, 6931, -1, 6934, 6935, 6932, -1, 6932, 6935, 6933, -1, 6933, 6935, 2406, -1, 2406, 6935, 3485, -1, 6936, 6937, 6934, -1, 6935, 6937, 3485, -1, 6934, 6937, 6935, -1, 3485, 6938, 3486, -1, 6924, 6938, 6936, -1, 6937, 6938, 3485, -1, 6936, 6938, 6937, -1, 3486, 6938, 6924, -1, 3958, 6939, 3956, -1, 3956, 6939, 6923, -1, 6923, 6940, 6926, -1, 6939, 6940, 6923, -1, 6926, 6941, 6928, -1, 6940, 6941, 6926, -1, 6928, 6942, 6930, -1, 6941, 6942, 6928, -1, 6930, 6943, 6932, -1, 6942, 6943, 6930, -1, 6932, 6944, 6934, -1, 6943, 6944, 6932, -1, 6934, 6945, 6936, -1, 6944, 6945, 6934, -1, 6936, 6946, 6924, -1, 6945, 6946, 6936, -1, 6924, 3351, 3469, -1, 6946, 3351, 6924, -1, 6947, 6948, 6949, -1, 6949, 6948, 6950, -1, 6951, 6952, 6953, -1, 6950, 6952, 6951, -1, 6941, 6954, 6942, -1, 6942, 6954, 6955, -1, 6955, 6956, 6947, -1, 6947, 6956, 6948, -1, 3320, 6957, 3327, -1, 6953, 6957, 3320, -1, 3327, 6957, 6958, -1, 6948, 6959, 6950, -1, 6950, 6959, 6952, -1, 6940, 6960, 6941, -1, 6941, 6960, 6954, -1, 6958, 6961, 6962, -1, 6957, 6961, 6958, -1, 6952, 6961, 6953, -1, 6953, 6961, 6957, -1, 6955, 6963, 6956, -1, 6954, 6963, 6955, -1, 3327, 6958, 3340, -1, 6956, 6964, 6948, -1, 6948, 6964, 6959, -1, 3958, 4870, 6939, -1, 6962, 6965, 6966, -1, 6961, 6965, 6962, -1, 6959, 6965, 6952, -1, 6952, 6965, 6961, -1, 4868, 6967, 4870, -1, 6939, 6967, 6940, -1, 6940, 6967, 6960, -1, 4870, 6967, 6939, -1, 6960, 6968, 6954, -1, 6954, 6968, 6963, -1, 6963, 6969, 6956, -1, 6956, 6969, 6964, -1, 6959, 6970, 6965, -1, 6966, 6970, 6971, -1, 6965, 6970, 6966, -1, 6964, 6970, 6959, -1, 6967, 6972, 6960, -1, 4866, 6972, 4868, -1, 6960, 6972, 6968, -1, 4868, 6972, 6967, -1, 6968, 6973, 6963, -1, 6963, 6973, 6969, -1, 3351, 6974, 3342, -1, 6969, 6975, 6964, -1, 6964, 6975, 6970, -1, 6946, 6974, 3351, -1, 6970, 6975, 6971, -1, 4863, 6976, 4866, -1, 4866, 6976, 6972, -1, 6972, 6976, 6968, -1, 6945, 6949, 6946, -1, 6968, 6976, 6973, -1, 6971, 6977, 6978, -1, 6946, 6949, 6974, -1, 6975, 6977, 6971, -1, 6969, 6977, 6975, -1, 6973, 6977, 6969, -1, 3342, 6951, 3335, -1, 3335, 6951, 3322, -1, 6978, 6979, 6980, -1, 6974, 6951, 3342, -1, 6980, 6979, 3961, -1, 3961, 6979, 4863, -1, 6977, 6979, 6978, -1, 6976, 6979, 6973, -1, 6973, 6979, 6977, -1, 6944, 6947, 6945, -1, 4863, 6979, 6976, -1, 6945, 6947, 6949, -1, 6974, 6950, 6951, -1, 6949, 6950, 6974, -1, 3322, 6953, 3320, -1, 6951, 6953, 3322, -1, 6943, 6955, 6944, -1, 6942, 6955, 6943, -1, 6944, 6955, 6947, -1, 3961, 3962, 6980, -1, 3962, 6981, 6980, -1, 6980, 6982, 6978, -1, 6981, 6982, 6980, -1, 6978, 6983, 6971, -1, 6982, 6983, 6978, -1, 6971, 6984, 6966, -1, 6983, 6984, 6971, -1, 6966, 6985, 6962, -1, 6984, 6985, 6966, -1, 6958, 6986, 3340, -1, 6962, 6986, 6958, -1, 6985, 6986, 6962, -1, 6986, 3410, 3340, -1, 6987, 6988, 6989, -1, 6990, 6991, 6992, -1, 480, 6988, 483, -1, 6992, 6991, 6993, -1, 6989, 6988, 6994, -1, 6994, 6988, 480, -1, 6995, 6996, 6997, -1, 6998, 6999, 6990, -1, 7000, 6996, 6995, -1, 6990, 6999, 6991, -1, 4877, 7001, 4875, -1, 4875, 7001, 4874, -1, 4874, 7001, 7000, -1, 3397, 7002, 3406, -1, 6987, 7003, 6988, -1, 6993, 7002, 3397, -1, 7004, 7003, 6987, -1, 6988, 7003, 483, -1, 4872, 7005, 4871, -1, 6981, 7005, 6982, -1, 6982, 7005, 7006, -1, 6997, 7007, 7004, -1, 4871, 7005, 6981, -1, 6996, 7007, 6997, -1, 4877, 7008, 7001, -1, 7000, 7008, 6996, -1, 6993, 7009, 7002, -1, 7001, 7008, 7000, -1, 4882, 7010, 4880, -1, 6991, 7009, 6993, -1, 483, 7010, 485, -1, 7004, 7010, 7003, -1, 7007, 7010, 7004, -1, 7003, 7010, 483, -1, 485, 7010, 4882, -1, 4880, 7011, 4879, -1, 4879, 7011, 4877, -1, 6998, 7012, 6999, -1, 7010, 7011, 4880, -1, 7006, 7012, 6998, -1, 6996, 7011, 7007, -1, 7008, 7011, 6996, -1, 7007, 7011, 7010, -1, 4877, 7011, 7008, -1, 6991, 7013, 7009, -1, 6999, 7013, 6991, -1, 3406, 7014, 3415, -1, 3962, 4871, 6981, -1, 7002, 7014, 3406, -1, 4873, 7015, 4872, -1, 4872, 7015, 7005, -1, 7005, 7015, 7006, -1, 7006, 7015, 7012, -1, 7009, 7016, 7002, -1, 7002, 7016, 7014, -1, 7012, 7017, 6999, -1, 6999, 7017, 7013, -1, 3415, 7018, 3422, -1, 7014, 7018, 3415, -1, 7013, 7019, 7009, -1, 7009, 7019, 7016, -1, 7016, 7020, 7014, -1, 3424, 477, 479, -1, 7014, 7020, 7018, -1, 3422, 7021, 3423, -1, 7018, 7021, 3422, -1, 4874, 7022, 4873, -1, 7012, 7022, 7017, -1, 4873, 7022, 7015, -1, 7015, 7022, 7012, -1, 7017, 6995, 7013, -1, 7013, 6995, 7019, -1, 7016, 7023, 7020, -1, 7019, 7023, 7016, -1, 7020, 6989, 7018, -1, 4882, 487, 485, -1, 6986, 6992, 3410, -1, 7018, 6989, 7021, -1, 7021, 7024, 3423, -1, 3410, 6992, 3399, -1, 3423, 7024, 3424, -1, 3424, 7024, 477, -1, 6985, 6990, 6986, -1, 7019, 6997, 7023, -1, 6995, 6997, 7019, -1, 6986, 6990, 6992, -1, 7023, 6987, 7020, -1, 7020, 6987, 6989, -1, 6984, 6998, 6985, -1, 6983, 6998, 6984, -1, 6985, 6998, 6990, -1, 7022, 7000, 7017, -1, 3399, 6993, 3397, -1, 7017, 7000, 6995, -1, 4874, 7000, 7022, -1, 6989, 6994, 7021, -1, 6992, 6993, 3399, -1, 7021, 6994, 7024, -1, 477, 6994, 480, -1, 7024, 6994, 477, -1, 6982, 7006, 6983, -1, 6983, 7006, 6998, -1, 7023, 7004, 6987, -1, 6997, 7004, 7023, -1, 3290, 478, 7025, -1, 7025, 481, 7026, -1, 478, 481, 7025, -1, 7026, 482, 7027, -1, 481, 482, 7026, -1, 7027, 484, 7028, -1, 482, 484, 7027, -1, 484, 486, 7028, -1, 7028, 489, 3954, -1, 486, 489, 7028, -1, 3954, 5138, 7028, -1, 3344, 7029, 3333, -1, 3344, 7030, 7029, -1, 5140, 7030, 3344, -1, 5140, 7031, 7030, -1, 5140, 7032, 7031, -1, 5140, 2127, 7032, -1, 3290, 7033, 3318, -1, 3318, 7033, 3344, -1, 7025, 7033, 3290, -1, 7026, 7034, 7025, -1, 7033, 7034, 3344, -1, 7025, 7034, 7033, -1, 7027, 7035, 7026, -1, 7034, 7035, 3344, -1, 7026, 7035, 7034, -1, 3344, 7035, 5140, -1, 5140, 7036, 5138, -1, 7028, 7036, 7027, -1, 7035, 7036, 5140, -1, 7027, 7036, 7035, -1, 5138, 7036, 7028, -1, 2681, 3333, 2685, -1, 2690, 7029, 2693, -1, 2685, 7029, 2690, -1, 3333, 7029, 2685, -1, 2687, 7030, 2688, -1, 2693, 7030, 2687, -1, 7029, 7030, 2693, -1, 2688, 7031, 7037, -1, 7030, 7031, 2688, -1, 7037, 7032, 7038, -1, 7031, 7032, 7037, -1, 7038, 2127, 2129, -1, 7032, 2127, 7038, -1, 7039, 5142, 3946, -1, 5144, 2420, 2135, -1, 5144, 2423, 2420, -1, 3412, 3428, 7040, -1, 5144, 2426, 2423, -1, 3427, 2434, 2431, -1, 3427, 2436, 2434, -1, 3427, 2438, 2436, -1, 5142, 7041, 5144, -1, 7039, 7041, 5142, -1, 7042, 7043, 7039, -1, 7041, 7043, 5144, -1, 7039, 7043, 7041, -1, 7044, 7045, 7042, -1, 7043, 7045, 5144, -1, 7042, 7045, 7043, -1, 5144, 7045, 2426, -1, 7046, 7047, 7044, -1, 2426, 7047, 2429, -1, 7044, 7047, 7045, -1, 7045, 7047, 2426, -1, 7048, 7049, 7046, -1, 2429, 7049, 2431, -1, 7047, 7049, 2429, -1, 7046, 7049, 7047, -1, 7050, 7051, 7048, -1, 7048, 7051, 7049, -1, 7049, 7051, 2431, -1, 2431, 7051, 3427, -1, 7052, 7053, 7050, -1, 7051, 7053, 3427, -1, 7050, 7053, 7051, -1, 3427, 7054, 3428, -1, 7040, 7054, 7052, -1, 7053, 7054, 3427, -1, 7052, 7054, 7053, -1, 3428, 7054, 7040, -1, 3948, 7055, 3946, -1, 3946, 7055, 7039, -1, 7039, 7056, 7042, -1, 7055, 7056, 7039, -1, 7042, 7057, 7044, -1, 7056, 7057, 7042, -1, 7044, 7058, 7046, -1, 7057, 7058, 7044, -1, 7046, 7059, 7048, -1, 7058, 7059, 7046, -1, 7048, 7060, 7050, -1, 7059, 7060, 7048, -1, 7050, 7061, 7052, -1, 7060, 7061, 7050, -1, 7052, 7062, 7040, -1, 7061, 7062, 7052, -1, 7040, 3413, 3412, -1, 7062, 3413, 7040, -1, 7063, 7064, 7065, -1, 7065, 7064, 7066, -1, 7067, 7068, 7069, -1, 7066, 7068, 7067, -1, 7057, 7070, 7058, -1, 7058, 7070, 7071, -1, 7071, 7072, 7063, -1, 7063, 7072, 7064, -1, 3492, 7073, 3499, -1, 7069, 7073, 3492, -1, 3499, 7073, 7074, -1, 7064, 7075, 7066, -1, 7066, 7075, 7068, -1, 7056, 7076, 7057, -1, 7057, 7076, 7070, -1, 7074, 7077, 7078, -1, 7073, 7077, 7074, -1, 7068, 7077, 7069, -1, 7069, 7077, 7073, -1, 7071, 7079, 7072, -1, 7070, 7079, 7071, -1, 3499, 7074, 3507, -1, 7072, 7080, 7064, -1, 7064, 7080, 7075, -1, 3948, 4848, 7055, -1, 7078, 7081, 7082, -1, 7077, 7081, 7078, -1, 7075, 7081, 7068, -1, 7068, 7081, 7077, -1, 4846, 7083, 4848, -1, 7055, 7083, 7056, -1, 7056, 7083, 7076, -1, 4848, 7083, 7055, -1, 7076, 7084, 7070, -1, 7070, 7084, 7079, -1, 7079, 7085, 7072, -1, 7072, 7085, 7080, -1, 7075, 7086, 7081, -1, 7082, 7086, 7087, -1, 7081, 7086, 7082, -1, 7080, 7086, 7075, -1, 7083, 7088, 7076, -1, 4844, 7088, 4846, -1, 7076, 7088, 7084, -1, 4846, 7088, 7083, -1, 7084, 7089, 7079, -1, 7079, 7089, 7085, -1, 3413, 7090, 3510, -1, 7085, 7091, 7080, -1, 7080, 7091, 7086, -1, 7062, 7090, 3413, -1, 7086, 7091, 7087, -1, 4841, 7092, 4844, -1, 4844, 7092, 7088, -1, 7088, 7092, 7084, -1, 7061, 7065, 7062, -1, 7084, 7092, 7089, -1, 7087, 7093, 7094, -1, 7062, 7065, 7090, -1, 7091, 7093, 7087, -1, 7085, 7093, 7091, -1, 7089, 7093, 7085, -1, 3510, 7067, 3505, -1, 3505, 7067, 3497, -1, 7094, 7095, 7096, -1, 7090, 7067, 3510, -1, 7096, 7095, 3951, -1, 3951, 7095, 4841, -1, 7093, 7095, 7094, -1, 7092, 7095, 7089, -1, 7089, 7095, 7093, -1, 7060, 7063, 7061, -1, 4841, 7095, 7092, -1, 7061, 7063, 7065, -1, 7090, 7066, 7067, -1, 7065, 7066, 7090, -1, 3497, 7069, 3492, -1, 7067, 7069, 3497, -1, 7059, 7071, 7060, -1, 7058, 7071, 7059, -1, 7060, 7071, 7063, -1, 3952, 7097, 3951, -1, 3951, 7097, 7096, -1, 7096, 7098, 7094, -1, 7097, 7098, 7096, -1, 7094, 7099, 7087, -1, 7098, 7099, 7094, -1, 7087, 7100, 7082, -1, 7099, 7100, 7087, -1, 7082, 7101, 7078, -1, 7100, 7101, 7082, -1, 7074, 7102, 3507, -1, 7078, 7102, 7074, -1, 7101, 7102, 7078, -1, 7102, 3328, 3507, -1, 7103, 7104, 7105, -1, 7106, 7107, 7108, -1, 7109, 7110, 7111, -1, 467, 7107, 470, -1, 7111, 7110, 7112, -1, 7108, 7107, 7113, -1, 7113, 7107, 467, -1, 7114, 7115, 7103, -1, 7116, 7117, 7109, -1, 7118, 7115, 7114, -1, 7109, 7117, 7110, -1, 4855, 7119, 4853, -1, 4853, 7119, 4852, -1, 4852, 7119, 7118, -1, 3319, 7120, 3323, -1, 7106, 7121, 7107, -1, 7112, 7120, 3319, -1, 7104, 7121, 7106, -1, 7107, 7121, 470, -1, 4850, 7122, 4849, -1, 7097, 7122, 7098, -1, 7098, 7122, 7123, -1, 7103, 7124, 7104, -1, 4849, 7122, 7097, -1, 7115, 7124, 7103, -1, 4855, 7125, 7119, -1, 7118, 7125, 7115, -1, 7112, 7126, 7120, -1, 7119, 7125, 7118, -1, 4860, 7127, 4858, -1, 7110, 7126, 7112, -1, 470, 7127, 472, -1, 7104, 7127, 7121, -1, 7124, 7127, 7104, -1, 7121, 7127, 470, -1, 472, 7127, 4860, -1, 4858, 7128, 4857, -1, 4857, 7128, 4855, -1, 7116, 7129, 7117, -1, 7127, 7128, 4858, -1, 7123, 7129, 7116, -1, 7115, 7128, 7124, -1, 7125, 7128, 7115, -1, 7124, 7128, 7127, -1, 4855, 7128, 7125, -1, 7110, 7130, 7126, -1, 7117, 7130, 7110, -1, 3323, 7131, 3337, -1, 3952, 4849, 7097, -1, 7120, 7131, 3323, -1, 4851, 7132, 4850, -1, 4850, 7132, 7122, -1, 7122, 7132, 7123, -1, 7123, 7132, 7129, -1, 7126, 7133, 7120, -1, 7120, 7133, 7131, -1, 7129, 7134, 7117, -1, 7117, 7134, 7130, -1, 3337, 7135, 3352, -1, 7131, 7135, 3337, -1, 7130, 7136, 7126, -1, 7126, 7136, 7133, -1, 7133, 7137, 7131, -1, 3355, 464, 466, -1, 7131, 7137, 7135, -1, 3352, 7138, 3353, -1, 7135, 7138, 3352, -1, 4852, 7139, 4851, -1, 7129, 7139, 7134, -1, 4851, 7139, 7132, -1, 7132, 7139, 7129, -1, 7134, 7114, 7130, -1, 7130, 7114, 7136, -1, 7133, 7105, 7137, -1, 7136, 7105, 7133, -1, 7137, 7108, 7135, -1, 4860, 474, 472, -1, 7102, 7111, 3328, -1, 7135, 7108, 7138, -1, 7138, 7140, 3353, -1, 3328, 7111, 3321, -1, 3353, 7140, 3355, -1, 3355, 7140, 464, -1, 7101, 7109, 7102, -1, 7136, 7103, 7105, -1, 7114, 7103, 7136, -1, 7102, 7109, 7111, -1, 7105, 7106, 7137, -1, 7137, 7106, 7108, -1, 7100, 7116, 7101, -1, 7099, 7116, 7100, -1, 7101, 7116, 7109, -1, 7139, 7118, 7134, -1, 3321, 7112, 3319, -1, 7134, 7118, 7114, -1, 4852, 7118, 7139, -1, 7108, 7113, 7138, -1, 7111, 7112, 3321, -1, 7138, 7113, 7140, -1, 464, 7113, 467, -1, 7140, 7113, 464, -1, 7098, 7123, 7099, -1, 7099, 7123, 7116, -1, 7105, 7104, 7106, -1, 3470, 465, 7141, -1, 7141, 468, 7142, -1, 465, 468, 7141, -1, 7142, 469, 7143, -1, 468, 469, 7142, -1, 7143, 471, 7144, -1, 469, 471, 7143, -1, 7144, 473, 3944, -1, 471, 473, 7144, -1, 473, 476, 3944, -1, 3944, 5146, 7144, -1, 3509, 7145, 3508, -1, 3509, 7146, 7145, -1, 5148, 7146, 3509, -1, 5148, 7147, 7146, -1, 5148, 7148, 7147, -1, 5148, 2136, 7148, -1, 3470, 7149, 3487, -1, 3487, 7149, 3509, -1, 7141, 7149, 3470, -1, 7142, 7150, 7141, -1, 7149, 7150, 3509, -1, 7141, 7150, 7149, -1, 7143, 7151, 7142, -1, 7150, 7151, 3509, -1, 7142, 7151, 7150, -1, 3509, 7151, 5148, -1, 5148, 7152, 5146, -1, 7144, 7152, 7143, -1, 7151, 7152, 5148, -1, 7143, 7152, 7151, -1, 5146, 7152, 7144, -1, 2215, 3508, 2214, -1, 2214, 7145, 2213, -1, 3508, 7145, 2214, -1, 2213, 7146, 2211, -1, 2211, 7146, 2212, -1, 7145, 7146, 2213, -1, 2212, 7147, 2444, -1, 7146, 7147, 2212, -1, 2444, 7148, 2440, -1, 7147, 7148, 2444, -1, 2440, 2136, 2138, -1, 7148, 2136, 2440, -1, 2710, 3435, 2714, -1, 2719, 7153, 2722, -1, 2714, 7153, 2719, -1, 3435, 7153, 2714, -1, 2716, 7154, 2717, -1, 2722, 7154, 2716, -1, 7153, 7154, 2722, -1, 2717, 7155, 7156, -1, 7154, 7155, 2717, -1, 7156, 7157, 7158, -1, 7155, 7157, 7156, -1, 7158, 2145, 2147, -1, 7157, 2145, 7158, -1, 3934, 5154, 7159, -1, 3446, 7153, 3435, -1, 3446, 7154, 7153, -1, 5156, 7154, 3446, -1, 5156, 7155, 7154, -1, 5156, 7157, 7155, -1, 5156, 2145, 7157, -1, 7160, 7161, 3414, -1, 3414, 7161, 3429, -1, 3429, 7161, 3446, -1, 7162, 7163, 7160, -1, 7160, 7163, 7161, -1, 7161, 7163, 3446, -1, 7164, 7165, 7162, -1, 7163, 7165, 3446, -1, 7162, 7165, 7163, -1, 3446, 7165, 5156, -1, 5156, 7166, 5154, -1, 7159, 7166, 7164, -1, 7165, 7166, 5156, -1, 7164, 7166, 7165, -1, 5154, 7166, 7159, -1, 452, 455, 3414, -1, 7160, 455, 7162, -1, 3414, 455, 7160, -1, 7162, 456, 7164, -1, 455, 456, 7162, -1, 7164, 458, 7159, -1, 456, 458, 7164, -1, 7159, 460, 3934, -1, 458, 460, 7159, -1, 460, 463, 3934, -1, 7167, 7168, 7169, -1, 7170, 7171, 7172, -1, 7172, 7171, 7173, -1, 454, 7168, 457, -1, 7169, 7168, 7174, -1, 7174, 7168, 454, -1, 7175, 7176, 7177, -1, 7178, 7179, 7170, -1, 7180, 7176, 7175, -1, 4833, 7181, 4831, -1, 7170, 7179, 7171, -1, 4831, 7181, 4830, -1, 4830, 7181, 7180, -1, 3491, 7182, 3496, -1, 7167, 7183, 7168, -1, 7184, 7183, 7167, -1, 7173, 7182, 3491, -1, 457, 7183, 459, -1, 7168, 7183, 457, -1, 4828, 7185, 4827, -1, 7186, 7185, 7187, -1, 7177, 7188, 7184, -1, 7187, 7185, 7189, -1, 7176, 7188, 7177, -1, 4827, 7185, 7186, -1, 4833, 7190, 7181, -1, 7180, 7190, 7176, -1, 7171, 7191, 7173, -1, 7181, 7190, 7180, -1, 4838, 7192, 4836, -1, 7173, 7191, 7182, -1, 7184, 7192, 7183, -1, 7183, 7192, 459, -1, 7188, 7192, 7184, -1, 459, 7192, 4838, -1, 4836, 7193, 4835, -1, 7178, 7194, 7179, -1, 4835, 7193, 4833, -1, 7188, 7193, 7192, -1, 7189, 7194, 7178, -1, 4833, 7193, 7190, -1, 7176, 7193, 7188, -1, 7190, 7193, 7176, -1, 7192, 7193, 4836, -1, 7171, 7195, 7191, -1, 7179, 7195, 7171, -1, 3496, 7196, 3506, -1, 3942, 4827, 7186, -1, 7182, 7196, 3496, -1, 4829, 7197, 4828, -1, 4828, 7197, 7185, -1, 7189, 7197, 7194, -1, 7185, 7197, 7189, -1, 7191, 7198, 7182, -1, 7182, 7198, 7196, -1, 7179, 7199, 7195, -1, 7194, 7199, 7179, -1, 3506, 7200, 3512, -1, 7196, 7200, 3506, -1, 7195, 7201, 7191, -1, 7191, 7201, 7198, -1, 7198, 7202, 7196, -1, 3514, 451, 453, -1, 7196, 7202, 7200, -1, 3512, 7203, 3513, -1, 7200, 7203, 3512, -1, 7194, 7204, 7199, -1, 4830, 7204, 4829, -1, 4829, 7204, 7197, -1, 7197, 7204, 7194, -1, 7195, 7175, 7201, -1, 7199, 7175, 7195, -1, 7201, 7205, 7198, -1, 7198, 7205, 7202, -1, 7202, 7169, 7200, -1, 4838, 461, 459, -1, 7200, 7169, 7203, -1, 7206, 7172, 7207, -1, 7207, 7172, 3500, -1, 3513, 7208, 3514, -1, 3500, 7172, 3493, -1, 7203, 7208, 3513, -1, 3514, 7208, 451, -1, 7201, 7177, 7205, -1, 7175, 7177, 7201, -1, 7206, 7170, 7172, -1, 7205, 7167, 7202, -1, 7209, 7178, 7210, -1, 7210, 7178, 7206, -1, 7202, 7167, 7169, -1, 7206, 7178, 7170, -1, 7199, 7180, 7175, -1, 4830, 7180, 7204, -1, 3493, 7173, 3491, -1, 7204, 7180, 7199, -1, 7203, 7174, 7208, -1, 7169, 7174, 7203, -1, 7172, 7173, 3493, -1, 451, 7174, 454, -1, 7208, 7174, 451, -1, 7187, 7189, 7209, -1, 7209, 7189, 7178, -1, 7177, 7184, 7205, -1, 7205, 7184, 7167, -1, 3941, 3942, 7211, -1, 3942, 7186, 7211, -1, 7211, 7187, 7212, -1, 7186, 7187, 7211, -1, 7212, 7209, 7213, -1, 7187, 7209, 7212, -1, 7213, 7210, 7214, -1, 7209, 7210, 7213, -1, 7214, 7206, 7215, -1, 7210, 7206, 7214, -1, 7215, 7207, 7216, -1, 7206, 7207, 7215, -1, 7216, 3500, 3447, -1, 7207, 3500, 7216, -1, 7217, 7218, 7219, -1, 7220, 7218, 7217, -1, 7221, 7222, 7223, -1, 7219, 7222, 7221, -1, 7224, 7225, 7226, -1, 7226, 7225, 7227, -1, 7220, 7228, 7218, -1, 7227, 7228, 7220, -1, 3431, 7229, 3438, -1, 3438, 7229, 7216, -1, 7223, 7229, 3431, -1, 7218, 7230, 7219, -1, 7219, 7230, 7222, -1, 7231, 7232, 7224, -1, 7224, 7232, 7225, -1, 7216, 7233, 7215, -1, 7229, 7233, 7216, -1, 7222, 7233, 7223, -1, 7223, 7233, 7229, -1, 7225, 7234, 7227, -1, 7227, 7234, 7228, -1, 3438, 7216, 3447, -1, 7218, 7235, 7230, -1, 7228, 7235, 7218, -1, 3938, 4826, 7236, -1, 7215, 7237, 7214, -1, 7230, 7237, 7222, -1, 7233, 7237, 7215, -1, 7222, 7237, 7233, -1, 4824, 7238, 4826, -1, 7236, 7238, 7231, -1, 4826, 7238, 7236, -1, 7231, 7238, 7232, -1, 7225, 7239, 7234, -1, 7232, 7239, 7225, -1, 7234, 7240, 7228, -1, 7228, 7240, 7235, -1, 7230, 7241, 7237, -1, 7214, 7241, 7213, -1, 7237, 7241, 7214, -1, 7235, 7241, 7230, -1, 4822, 7242, 4824, -1, 7238, 7242, 7232, -1, 7232, 7242, 7239, -1, 4824, 7242, 7238, -1, 7239, 7243, 7234, -1, 7234, 7243, 7240, -1, 7235, 7244, 7241, -1, 7245, 7246, 3334, -1, 3334, 7246, 3451, -1, 7241, 7244, 7213, -1, 7240, 7244, 7235, -1, 4822, 7247, 7242, -1, 4819, 7247, 4822, -1, 7242, 7247, 7239, -1, 7248, 7217, 7245, -1, 7239, 7247, 7243, -1, 7213, 7249, 7212, -1, 7244, 7249, 7213, -1, 7245, 7217, 7246, -1, 7240, 7249, 7244, -1, 3451, 7221, 3443, -1, 7243, 7249, 7240, -1, 3443, 7221, 3434, -1, 3941, 7250, 4819, -1, 7211, 7250, 3941, -1, 7212, 7250, 7211, -1, 7246, 7221, 3451, -1, 7249, 7250, 7212, -1, 7247, 7250, 7243, -1, 7243, 7250, 7249, -1, 4819, 7250, 7247, -1, 7251, 7220, 7248, -1, 7248, 7220, 7217, -1, 7246, 7219, 7221, -1, 7217, 7219, 7246, -1, 3434, 7223, 3431, -1, 7221, 7223, 3434, -1, 7226, 7227, 7252, -1, 7252, 7227, 7251, -1, 7251, 7227, 7220, -1, 3938, 7236, 3936, -1, 3936, 7236, 7253, -1, 7253, 7231, 7254, -1, 7236, 7231, 7253, -1, 7254, 7224, 7255, -1, 7231, 7224, 7254, -1, 7255, 7226, 7256, -1, 7224, 7226, 7255, -1, 7256, 7252, 7257, -1, 7226, 7252, 7256, -1, 7257, 7251, 7258, -1, 7252, 7251, 7257, -1, 7258, 7248, 7259, -1, 7251, 7248, 7258, -1, 7259, 7245, 7260, -1, 7260, 7245, 3330, -1, 7248, 7245, 7259, -1, 7245, 3334, 3330, -1, 7253, 5158, 3936, -1, 5160, 2453, 2144, -1, 5160, 2456, 2453, -1, 3330, 3357, 7260, -1, 5160, 2459, 2456, -1, 3356, 2467, 2464, -1, 3356, 2469, 2467, -1, 3356, 2472, 2469, -1, 5158, 7261, 5160, -1, 7253, 7261, 5158, -1, 7254, 7262, 7253, -1, 7261, 7262, 5160, -1, 7253, 7262, 7261, -1, 7255, 7263, 7254, -1, 7262, 7263, 5160, -1, 7254, 7263, 7262, -1, 5160, 7263, 2459, -1, 2459, 7264, 2462, -1, 7256, 7264, 7255, -1, 7263, 7264, 2459, -1, 7255, 7264, 7263, -1, 2462, 7265, 2464, -1, 7257, 7265, 7256, -1, 7264, 7265, 2462, -1, 7256, 7265, 7264, -1, 7258, 7266, 7257, -1, 7265, 7266, 2464, -1, 7257, 7266, 7265, -1, 2464, 7266, 3356, -1, 7259, 7267, 7258, -1, 7258, 7267, 7266, -1, 7266, 7267, 3356, -1, 3356, 7268, 3357, -1, 7260, 7268, 7259, -1, 7267, 7268, 3356, -1, 3357, 7268, 7260, -1, 7259, 7268, 7267, -1, 2742, 3364, 2746, -1, 2751, 7269, 2754, -1, 2746, 7269, 2751, -1, 3364, 7269, 2746, -1, 2748, 7270, 2749, -1, 2754, 7270, 2748, -1, 7269, 7270, 2754, -1, 2749, 7271, 7272, -1, 7270, 7271, 2749, -1, 7272, 7273, 7274, -1, 7271, 7273, 7272, -1, 7274, 2154, 2156, -1, 7273, 2154, 7274, -1, 3924, 5162, 7275, -1, 3377, 7269, 3364, -1, 3377, 7270, 7269, -1, 5164, 7270, 3377, -1, 5164, 7271, 7270, -1, 5164, 7273, 7271, -1, 5164, 2154, 7273, -1, 7276, 7277, 3329, -1, 3329, 7277, 3358, -1, 3358, 7277, 3377, -1, 7278, 7279, 7276, -1, 7276, 7279, 7277, -1, 7277, 7279, 3377, -1, 7280, 7281, 7278, -1, 7279, 7281, 3377, -1, 7278, 7281, 7279, -1, 3377, 7281, 5164, -1, 5164, 7282, 5162, -1, 7275, 7282, 7280, -1, 7281, 7282, 5164, -1, 7280, 7282, 7281, -1, 5162, 7282, 7275, -1, 439, 442, 3329, -1, 3329, 442, 7276, -1, 7276, 443, 7278, -1, 442, 443, 7276, -1, 7278, 445, 7280, -1, 443, 445, 7278, -1, 7280, 447, 7275, -1, 445, 447, 7280, -1, 7275, 450, 3924, -1, 447, 450, 7275, -1, 7283, 7284, 7285, -1, 7286, 7287, 7288, -1, 7288, 7287, 7289, -1, 441, 7284, 444, -1, 7285, 7284, 7290, -1, 7290, 7284, 441, -1, 7291, 7292, 7293, -1, 7294, 7295, 7286, -1, 7296, 7292, 7291, -1, 4811, 7297, 4809, -1, 7286, 7295, 7287, -1, 4809, 7297, 4808, -1, 4808, 7297, 7296, -1, 3430, 7298, 3433, -1, 7283, 7299, 7284, -1, 7300, 7299, 7283, -1, 7289, 7298, 3430, -1, 444, 7299, 446, -1, 7284, 7299, 444, -1, 4806, 7301, 4805, -1, 7302, 7301, 7303, -1, 7293, 7304, 7300, -1, 7303, 7301, 7305, -1, 7292, 7304, 7293, -1, 4805, 7301, 7302, -1, 4811, 7306, 7297, -1, 7296, 7306, 7292, -1, 7287, 7307, 7289, -1, 7297, 7306, 7296, -1, 4816, 7308, 4814, -1, 7289, 7307, 7298, -1, 7300, 7308, 7299, -1, 7299, 7308, 446, -1, 7304, 7308, 7300, -1, 446, 7308, 4816, -1, 4814, 7309, 4813, -1, 7294, 7310, 7295, -1, 4813, 7309, 4811, -1, 7304, 7309, 7308, -1, 7305, 7310, 7294, -1, 4811, 7309, 7306, -1, 7292, 7309, 7304, -1, 7306, 7309, 7292, -1, 7308, 7309, 4814, -1, 7287, 7311, 7307, -1, 7295, 7311, 7287, -1, 3433, 7312, 3442, -1, 3932, 4805, 7302, -1, 7298, 7312, 3433, -1, 4807, 7313, 4806, -1, 4806, 7313, 7301, -1, 7305, 7313, 7310, -1, 7301, 7313, 7305, -1, 7307, 7314, 7298, -1, 7298, 7314, 7312, -1, 7295, 7315, 7311, -1, 7310, 7315, 7295, -1, 3442, 7316, 3452, -1, 7312, 7316, 3442, -1, 7311, 7317, 7307, -1, 7307, 7317, 7314, -1, 7314, 7318, 7312, -1, 3454, 438, 440, -1, 7312, 7318, 7316, -1, 3452, 7319, 3453, -1, 7316, 7319, 3452, -1, 7310, 7320, 7315, -1, 4808, 7320, 4807, -1, 4807, 7320, 7313, -1, 7313, 7320, 7310, -1, 7311, 7291, 7317, -1, 7315, 7291, 7311, -1, 7317, 7321, 7314, -1, 7314, 7321, 7318, -1, 7318, 7285, 7316, -1, 4816, 448, 446, -1, 7316, 7285, 7319, -1, 7322, 7288, 7323, -1, 7323, 7288, 3439, -1, 3453, 7324, 3454, -1, 3439, 7288, 3432, -1, 7319, 7324, 3453, -1, 3454, 7324, 438, -1, 7317, 7293, 7321, -1, 7291, 7293, 7317, -1, 7322, 7286, 7288, -1, 7321, 7283, 7318, -1, 7325, 7294, 7326, -1, 7326, 7294, 7322, -1, 7318, 7283, 7285, -1, 7322, 7294, 7286, -1, 7315, 7296, 7291, -1, 4808, 7296, 7320, -1, 3432, 7289, 3430, -1, 7320, 7296, 7315, -1, 7319, 7290, 7324, -1, 7285, 7290, 7319, -1, 7288, 7289, 3432, -1, 438, 7290, 441, -1, 7324, 7290, 438, -1, 7303, 7305, 7325, -1, 7325, 7305, 7294, -1, 7293, 7300, 7321, -1, 7321, 7300, 7283, -1, 3932, 7302, 3931, -1, 3931, 7302, 7327, -1, 7327, 7303, 7328, -1, 7302, 7303, 7327, -1, 7328, 7325, 7329, -1, 7329, 7325, 7330, -1, 7303, 7325, 7328, -1, 7330, 7326, 7331, -1, 7325, 7326, 7330, -1, 7331, 7322, 7332, -1, 7326, 7322, 7331, -1, 7332, 7323, 3385, -1, 7322, 7323, 7332, -1, 7323, 3439, 3385, -1, 7333, 7334, 7335, -1, 7336, 7334, 7333, -1, 7337, 7338, 7339, -1, 7335, 7338, 7337, -1, 7340, 7341, 7342, -1, 7342, 7341, 7343, -1, 7336, 7344, 7334, -1, 7343, 7344, 7336, -1, 3369, 7345, 3376, -1, 3376, 7345, 7332, -1, 7339, 7345, 3369, -1, 7334, 7346, 7335, -1, 7335, 7346, 7338, -1, 7347, 7348, 7340, -1, 7340, 7348, 7341, -1, 7332, 7349, 7331, -1, 7345, 7349, 7332, -1, 7338, 7349, 7339, -1, 7339, 7349, 7345, -1, 7341, 7350, 7343, -1, 7343, 7350, 7344, -1, 3376, 7332, 3385, -1, 7334, 7351, 7346, -1, 7344, 7351, 7334, -1, 3928, 4804, 7352, -1, 7331, 7353, 7330, -1, 7346, 7353, 7338, -1, 7349, 7353, 7331, -1, 7338, 7353, 7349, -1, 4802, 7354, 4804, -1, 7352, 7354, 7347, -1, 4804, 7354, 7352, -1, 7347, 7354, 7348, -1, 7341, 7355, 7350, -1, 7348, 7355, 7341, -1, 7350, 7356, 7344, -1, 7344, 7356, 7351, -1, 7346, 7357, 7353, -1, 7330, 7357, 7329, -1, 7353, 7357, 7330, -1, 7351, 7357, 7346, -1, 4800, 7358, 4802, -1, 7354, 7358, 7348, -1, 7348, 7358, 7355, -1, 4802, 7358, 7354, -1, 7355, 7359, 7350, -1, 7350, 7359, 7356, -1, 7351, 7360, 7357, -1, 7361, 7362, 3390, -1, 3390, 7362, 3387, -1, 7357, 7360, 7329, -1, 7356, 7360, 7351, -1, 4800, 7363, 7358, -1, 4797, 7363, 4800, -1, 7358, 7363, 7355, -1, 7364, 7333, 7361, -1, 7355, 7363, 7359, -1, 7329, 7365, 7328, -1, 7360, 7365, 7329, -1, 7361, 7333, 7362, -1, 7356, 7365, 7360, -1, 3387, 7337, 3380, -1, 7359, 7365, 7356, -1, 3380, 7337, 3374, -1, 3931, 7366, 4797, -1, 7327, 7366, 3931, -1, 7328, 7366, 7327, -1, 7362, 7337, 3387, -1, 7365, 7366, 7328, -1, 7363, 7366, 7359, -1, 7359, 7366, 7365, -1, 4797, 7366, 7363, -1, 7367, 7336, 7364, -1, 7364, 7336, 7333, -1, 7362, 7335, 7337, -1, 7333, 7335, 7362, -1, 3374, 7339, 3369, -1, 7337, 7339, 3374, -1, 7342, 7343, 7368, -1, 7368, 7343, 7367, -1, 7367, 7343, 7336, -1, 3928, 7352, 3926, -1, 3926, 7352, 7369, -1, 7369, 7347, 7370, -1, 7352, 7347, 7369, -1, 7370, 7340, 7371, -1, 7347, 7340, 7370, -1, 7371, 7342, 7372, -1, 7340, 7342, 7371, -1, 7372, 7368, 7373, -1, 7342, 7368, 7372, -1, 7373, 7367, 7374, -1, 7368, 7367, 7373, -1, 7374, 7364, 7375, -1, 7367, 7364, 7374, -1, 7375, 7361, 7376, -1, 7376, 7361, 3502, -1, 7364, 7361, 7375, -1, 7361, 3390, 3502, -1, 7369, 5166, 3926, -1, 5168, 2481, 2153, -1, 5168, 2484, 2481, -1, 3502, 3516, 7376, -1, 5168, 2487, 2484, -1, 3515, 2495, 2492, -1, 3515, 2497, 2495, -1, 3515, 2500, 2497, -1, 5166, 7377, 5168, -1, 7369, 7377, 5166, -1, 7370, 7378, 7369, -1, 7377, 7378, 5168, -1, 7369, 7378, 7377, -1, 7371, 7379, 7370, -1, 7378, 7379, 5168, -1, 7370, 7379, 7378, -1, 5168, 7379, 2487, -1, 2487, 7380, 2490, -1, 7372, 7380, 7371, -1, 7379, 7380, 2487, -1, 7371, 7380, 7379, -1, 2490, 7381, 2492, -1, 7373, 7381, 7372, -1, 7380, 7381, 2490, -1, 7372, 7381, 7380, -1, 7374, 7382, 7373, -1, 7381, 7382, 2492, -1, 7373, 7382, 7381, -1, 2492, 7382, 3515, -1, 7375, 7383, 7374, -1, 7374, 7383, 7382, -1, 7382, 7383, 3515, -1, 3515, 7384, 3516, -1, 7376, 7384, 7375, -1, 7383, 7384, 3515, -1, 3516, 7384, 7376, -1, 7375, 7384, 7383, -1, 7385, 5085, 3202, -1, 5087, 2512, 2032, -1, 5087, 2515, 2512, -1, 3440, 3457, 7386, -1, 5087, 2518, 2515, -1, 3456, 2526, 2523, -1, 3456, 2528, 2526, -1, 3456, 2530, 2528, -1, 5085, 7387, 5087, -1, 7385, 7387, 5085, -1, 7388, 7389, 7385, -1, 7387, 7389, 5087, -1, 7385, 7389, 7387, -1, 7390, 7391, 7388, -1, 7389, 7391, 5087, -1, 7388, 7391, 7389, -1, 5087, 7391, 2518, -1, 7392, 7393, 7390, -1, 2518, 7393, 2521, -1, 7390, 7393, 7391, -1, 7391, 7393, 2518, -1, 7394, 7395, 7392, -1, 2521, 7395, 2523, -1, 7393, 7395, 2521, -1, 7392, 7395, 7393, -1, 7396, 7397, 7394, -1, 7394, 7397, 7395, -1, 7395, 7397, 2523, -1, 2523, 7397, 3456, -1, 7398, 7399, 7396, -1, 7397, 7399, 3456, -1, 7396, 7399, 7397, -1, 3456, 7400, 3457, -1, 7386, 7400, 7398, -1, 7399, 7400, 3456, -1, 7398, 7400, 7399, -1, 3457, 7400, 7386, -1, 3202, 3200, 7385, -1, 7385, 7401, 7388, -1, 3200, 7401, 7385, -1, 7388, 7402, 7390, -1, 7401, 7402, 7388, -1, 7390, 7403, 7392, -1, 7402, 7403, 7390, -1, 7392, 7404, 7394, -1, 7403, 7404, 7392, -1, 7394, 7405, 7396, -1, 7404, 7405, 7394, -1, 7396, 7406, 7398, -1, 7405, 7406, 7396, -1, 7398, 7407, 7386, -1, 7406, 7407, 7398, -1, 7386, 7408, 3440, -1, 7407, 7408, 7386, -1, 7408, 3345, 3440, -1, 7409, 7410, 7411, -1, 7411, 7410, 7412, -1, 7413, 7414, 7415, -1, 7412, 7414, 7413, -1, 7403, 7416, 7404, -1, 7404, 7416, 7417, -1, 7417, 7418, 7409, -1, 7409, 7418, 7410, -1, 3325, 7419, 3336, -1, 7415, 7419, 3325, -1, 3336, 7419, 7420, -1, 7410, 7421, 7412, -1, 7412, 7421, 7414, -1, 7402, 7422, 7403, -1, 7403, 7422, 7416, -1, 7420, 7423, 7424, -1, 7419, 7423, 7420, -1, 7414, 7423, 7415, -1, 7415, 7423, 7419, -1, 7417, 7425, 7418, -1, 7416, 7425, 7417, -1, 3336, 7420, 3341, -1, 7418, 7426, 7410, -1, 7410, 7426, 7421, -1, 7424, 7427, 7428, -1, 3200, 4782, 7401, -1, 7423, 7427, 7424, -1, 7421, 7427, 7414, -1, 7414, 7427, 7423, -1, 4780, 7429, 4782, -1, 7401, 7429, 7402, -1, 7402, 7429, 7422, -1, 4782, 7429, 7401, -1, 7422, 7430, 7416, -1, 7416, 7430, 7425, -1, 7425, 7431, 7418, -1, 7418, 7431, 7426, -1, 7421, 7432, 7427, -1, 7428, 7432, 7433, -1, 7427, 7432, 7428, -1, 7426, 7432, 7421, -1, 7429, 7434, 7422, -1, 4778, 7434, 4780, -1, 7422, 7434, 7430, -1, 4780, 7434, 7429, -1, 7430, 7435, 7425, -1, 7425, 7435, 7431, -1, 3345, 7436, 3343, -1, 7431, 7437, 7426, -1, 7426, 7437, 7432, -1, 7408, 7436, 3345, -1, 7432, 7437, 7433, -1, 4775, 7438, 4778, -1, 4778, 7438, 7434, -1, 7434, 7438, 7430, -1, 7407, 7411, 7408, -1, 7430, 7438, 7435, -1, 7433, 7439, 7440, -1, 7408, 7411, 7436, -1, 7437, 7439, 7433, -1, 7431, 7439, 7437, -1, 7435, 7439, 7431, -1, 3343, 7413, 3338, -1, 3338, 7413, 3331, -1, 7440, 7441, 7442, -1, 7436, 7413, 3343, -1, 7442, 7441, 3920, -1, 3920, 7441, 4775, -1, 7439, 7441, 7440, -1, 7438, 7441, 7435, -1, 7435, 7441, 7439, -1, 7406, 7409, 7407, -1, 4775, 7441, 7438, -1, 7407, 7409, 7411, -1, 7436, 7412, 7413, -1, 7411, 7412, 7436, -1, 3331, 7415, 3325, -1, 7413, 7415, 3331, -1, 7405, 7417, 7406, -1, 7404, 7417, 7405, -1, 7406, 7417, 7409, -1, 3920, 3921, 7442, -1, 3921, 7443, 7442, -1, 7442, 7444, 7440, -1, 7443, 7444, 7442, -1, 7440, 7445, 7433, -1, 7444, 7445, 7440, -1, 7433, 7446, 7428, -1, 7445, 7446, 7433, -1, 7428, 7447, 7424, -1, 7446, 7447, 7428, -1, 7424, 7448, 7420, -1, 7447, 7448, 7424, -1, 7420, 3354, 3341, -1, 7448, 3354, 7420, -1, 7449, 7450, 7451, -1, 7452, 7453, 7454, -1, 7455, 7456, 7457, -1, 428, 7453, 430, -1, 7457, 7456, 7458, -1, 7454, 7453, 7459, -1, 7459, 7453, 428, -1, 7460, 7461, 7449, -1, 7462, 7463, 7455, -1, 7464, 7461, 7460, -1, 7455, 7463, 7456, -1, 4789, 7465, 4787, -1, 4787, 7465, 4786, -1, 4786, 7465, 7464, -1, 3368, 7466, 3375, -1, 7452, 7467, 7453, -1, 7458, 7466, 3368, -1, 7450, 7467, 7452, -1, 7453, 7467, 430, -1, 4784, 7468, 4783, -1, 7443, 7468, 7444, -1, 7444, 7468, 7469, -1, 7449, 7470, 7450, -1, 4783, 7468, 7443, -1, 7461, 7470, 7449, -1, 4789, 7471, 7465, -1, 7464, 7471, 7461, -1, 7458, 7472, 7466, -1, 7465, 7471, 7464, -1, 4794, 7473, 4792, -1, 7456, 7472, 7458, -1, 430, 7473, 433, -1, 7450, 7473, 7467, -1, 7470, 7473, 7450, -1, 7467, 7473, 430, -1, 433, 7473, 4794, -1, 4792, 7474, 4791, -1, 4791, 7474, 4789, -1, 7462, 7475, 7463, -1, 7473, 7474, 4792, -1, 7469, 7475, 7462, -1, 7461, 7474, 7470, -1, 7471, 7474, 7461, -1, 7470, 7474, 7473, -1, 4789, 7474, 7471, -1, 7456, 7476, 7472, -1, 7463, 7476, 7456, -1, 3375, 7477, 3381, -1, 3921, 4783, 7443, -1, 7466, 7477, 3375, -1, 4785, 7478, 4784, -1, 4784, 7478, 7468, -1, 7468, 7478, 7469, -1, 7469, 7478, 7475, -1, 7472, 7479, 7466, -1, 7466, 7479, 7477, -1, 7475, 7480, 7463, -1, 7463, 7480, 7476, -1, 3381, 7481, 3392, -1, 7477, 7481, 3381, -1, 7476, 7482, 7472, -1, 7472, 7482, 7479, -1, 7479, 7483, 7477, -1, 3394, 425, 427, -1, 7477, 7483, 7481, -1, 3392, 7484, 3393, -1, 7481, 7484, 3392, -1, 4786, 7485, 4785, -1, 7475, 7485, 7480, -1, 4785, 7485, 7478, -1, 7478, 7485, 7475, -1, 7480, 7460, 7476, -1, 7476, 7460, 7482, -1, 7479, 7451, 7483, -1, 7482, 7451, 7479, -1, 7483, 7454, 7481, -1, 4794, 435, 433, -1, 7448, 7457, 3354, -1, 7481, 7454, 7484, -1, 7484, 7486, 3393, -1, 3354, 7457, 3370, -1, 3393, 7486, 3394, -1, 3394, 7486, 425, -1, 7447, 7455, 7448, -1, 7482, 7449, 7451, -1, 7460, 7449, 7482, -1, 7448, 7455, 7457, -1, 7451, 7452, 7483, -1, 7483, 7452, 7454, -1, 7446, 7462, 7447, -1, 7445, 7462, 7446, -1, 7447, 7462, 7455, -1, 7485, 7464, 7480, -1, 3370, 7458, 3368, -1, 7480, 7464, 7460, -1, 4786, 7464, 7485, -1, 7454, 7459, 7484, -1, 7457, 7458, 3370, -1, 7484, 7459, 7486, -1, 425, 7459, 428, -1, 7486, 7459, 425, -1, 7444, 7469, 7445, -1, 7445, 7469, 7462, -1, 7451, 7450, 7452, -1, 426, 429, 3501, -1, 3501, 429, 7487, -1, 7487, 431, 7488, -1, 429, 431, 7487, -1, 7488, 432, 7489, -1, 431, 432, 7488, -1, 7489, 434, 7490, -1, 432, 434, 7489, -1, 7490, 437, 3918, -1, 434, 437, 7490, -1, 3918, 5150, 7490, -1, 3305, 7491, 3292, -1, 3305, 7492, 7491, -1, 5152, 7492, 3305, -1, 5152, 7493, 7492, -1, 5152, 7494, 7493, -1, 5152, 2159, 7494, -1, 3501, 7495, 3511, -1, 3511, 7495, 3305, -1, 7487, 7495, 3501, -1, 7488, 7496, 7487, -1, 7495, 7496, 3305, -1, 7487, 7496, 7495, -1, 7489, 7497, 7488, -1, 7496, 7497, 3305, -1, 7488, 7497, 7496, -1, 3305, 7497, 5152, -1, 5152, 7498, 5150, -1, 7490, 7498, 7489, -1, 7497, 7498, 5152, -1, 7489, 7498, 7497, -1, 5150, 7498, 7490, -1, 2774, 3292, 2778, -1, 2783, 7491, 2786, -1, 2778, 7491, 2783, -1, 3292, 7491, 2778, -1, 2780, 7492, 2781, -1, 2786, 7492, 2780, -1, 7491, 7492, 2786, -1, 2781, 7493, 7499, -1, 7492, 7493, 2781, -1, 7499, 7494, 7500, -1, 7493, 7494, 7499, -1, 7500, 2159, 2161, -1, 7494, 2159, 7500, -1, 2835, 3471, 2839, -1, 2844, 7501, 2847, -1, 2839, 7501, 2844, -1, 3471, 7501, 2839, -1, 2841, 7502, 2842, -1, 2847, 7502, 2841, -1, 7501, 7502, 2847, -1, 2842, 7503, 7504, -1, 7502, 7503, 2842, -1, 7504, 7505, 7506, -1, 7503, 7505, 7504, -1, 7506, 2022, 2024, -1, 7505, 2022, 7506, -1, 3189, 5089, 7507, -1, 3480, 7501, 3471, -1, 3480, 7502, 7501, -1, 5091, 7502, 3480, -1, 5091, 7503, 7502, -1, 5091, 7505, 7503, -1, 5091, 2022, 7505, -1, 7508, 7509, 3441, -1, 3441, 7509, 3458, -1, 3458, 7509, 3480, -1, 7510, 7511, 7508, -1, 7508, 7511, 7509, -1, 7509, 7511, 3480, -1, 7512, 7513, 7510, -1, 7511, 7513, 3480, -1, 7510, 7513, 7511, -1, 3480, 7513, 5091, -1, 5091, 7514, 5089, -1, 7507, 7514, 7512, -1, 7513, 7514, 5091, -1, 7512, 7514, 7513, -1, 5089, 7514, 7507, -1, 3441, 3350, 7508, -1, 7508, 7515, 7510, -1, 3350, 7515, 7508, -1, 7510, 7516, 7512, -1, 7515, 7516, 7510, -1, 7512, 7517, 7507, -1, 7516, 7517, 7512, -1, 7507, 7518, 3189, -1, 7517, 7518, 7507, -1, 7518, 3187, 3189, -1, 7519, 7520, 7521, -1, 3347, 7522, 3348, -1, 7521, 7520, 7523, -1, 7524, 7522, 3347, -1, 7525, 7526, 7527, -1, 7528, 7529, 3324, -1, 7527, 7526, 7530, -1, 4768, 7526, 7525, -1, 7528, 7531, 7529, -1, 7523, 7531, 7528, -1, 7532, 7533, 7534, -1, 7534, 7533, 7535, -1, 7536, 7537, 7538, -1, 7535, 7539, 7524, -1, 7538, 7537, 7520, -1, 7524, 7539, 7522, -1, 7523, 7540, 7531, -1, 7530, 7541, 7542, -1, 7520, 7540, 7523, -1, 3324, 7543, 3332, -1, 7542, 7541, 7532, -1, 3332, 7543, 3339, -1, 3348, 7544, 3349, -1, 7522, 7544, 3348, -1, 7529, 7543, 3324, -1, 3349, 7544, 7515, -1, 7536, 7545, 7537, -1, 4766, 7546, 4768, -1, 4768, 7546, 7526, -1, 7526, 7546, 4766, -1, 7547, 7545, 7536, -1, 7533, 7548, 7535, -1, 7535, 7548, 7539, -1, 7531, 7549, 7529, -1, 7515, 7550, 7516, -1, 7529, 7549, 7543, -1, 7539, 7550, 7522, -1, 7544, 7550, 7515, -1, 7522, 7550, 7544, -1, 7520, 7551, 7540, -1, 7537, 7551, 7520, -1, 7532, 7552, 7533, -1, 4771, 7553, 4772, -1, 424, 4772, 422, -1, 7541, 7552, 7532, -1, 417, 7553, 7547, -1, 422, 4772, 419, -1, 419, 4772, 417, -1, 7547, 7553, 7545, -1, 4772, 7553, 417, -1, 4766, 7554, 7526, -1, 7526, 7554, 7530, -1, 7530, 7554, 7541, -1, 7540, 7555, 7531, -1, 7516, 7556, 7517, -1, 7531, 7555, 7549, -1, 7548, 7556, 7539, -1, 7550, 7556, 7516, -1, 7539, 7556, 7550, -1, 7543, 7557, 3339, -1, 7533, 7558, 7548, -1, 7552, 7558, 7533, -1, 4764, 7559, 4766, -1, 7537, 7560, 7551, -1, 7545, 7560, 7537, -1, 4766, 7559, 7554, -1, 7541, 7561, 7552, -1, 7554, 7561, 7541, -1, 7543, 7562, 7557, -1, 7549, 7562, 7543, -1, 7556, 7563, 7517, -1, 7548, 7563, 7556, -1, 7558, 7563, 7548, -1, 7540, 7527, 7555, -1, 4761, 7564, 4763, -1, 4763, 7564, 4764, -1, 7551, 7527, 7540, -1, 4764, 7564, 7559, -1, 4771, 7565, 7553, -1, 7559, 7564, 7554, -1, 4769, 7565, 4771, -1, 7554, 7564, 7561, -1, 7553, 7565, 7545, -1, 7545, 7565, 7560, -1, 7552, 7566, 7558, -1, 7561, 7566, 7552, -1, 3339, 7567, 3346, -1, 7561, 7568, 7566, -1, 4759, 7568, 4761, -1, 4761, 7568, 7564, -1, 7557, 7567, 3339, -1, 7564, 7568, 7561, -1, 3349, 7515, 3350, -1, 7555, 7542, 7549, -1, 7518, 7569, 4757, -1, 7517, 7569, 7518, -1, 7558, 7569, 7563, -1, 7563, 7569, 7517, -1, 7566, 7569, 7558, -1, 4759, 7570, 7568, -1, 4757, 7570, 4759, -1, 7549, 7542, 7562, -1, 7566, 7570, 7569, -1, 7569, 7570, 4757, -1, 7568, 7570, 7566, -1, 7560, 7525, 7551, -1, 7551, 7525, 7527, -1, 7557, 7534, 7567, -1, 7562, 7534, 7557, -1, 3346, 7524, 3347, -1, 7567, 7524, 3346, -1, 7527, 7530, 7555, -1, 7555, 7530, 7542, -1, 4757, 3187, 7518, -1, 4768, 7571, 4769, -1, 7560, 7571, 7525, -1, 4769, 7571, 7565, -1, 7572, 7528, 3311, -1, 7565, 7571, 7560, -1, 3311, 7528, 3326, -1, 7525, 7571, 4768, -1, 3326, 7528, 3324, -1, 7542, 7532, 7562, -1, 7521, 7523, 7572, -1, 7562, 7532, 7534, -1, 7534, 7535, 7567, -1, 7567, 7535, 7524, -1, 7572, 7523, 7528, -1, 7538, 7520, 7519, -1, 3303, 7573, 3311, -1, 3311, 7573, 7572, -1, 7572, 7574, 7521, -1, 7573, 7574, 7572, -1, 7521, 7575, 7519, -1, 7574, 7575, 7521, -1, 7519, 7576, 7538, -1, 7575, 7576, 7519, -1, 7538, 7577, 7536, -1, 7576, 7577, 7538, -1, 7547, 7578, 417, -1, 7536, 7578, 7547, -1, 7577, 7578, 7536, -1, 7578, 418, 417, -1, 7579, 7580, 7577, -1, 7581, 7580, 7579, -1, 7582, 7583, 3298, -1, 4754, 7584, 4752, -1, 4752, 7584, 7585, -1, 7578, 7586, 418, -1, 7587, 7588, 7589, -1, 7590, 7586, 7580, -1, 418, 7586, 420, -1, 7580, 7586, 7578, -1, 7589, 7588, 7591, -1, 7585, 7586, 7590, -1, 423, 7592, 4754, -1, 421, 7592, 423, -1, 7591, 7593, 7594, -1, 420, 7592, 421, -1, 7586, 7592, 420, -1, 4754, 7592, 7584, -1, 7594, 7593, 7595, -1, 7584, 7592, 7585, -1, 7585, 7592, 7586, -1, 7595, 7596, 7582, -1, 7582, 7596, 7583, -1, 7597, 7598, 7599, -1, 7599, 7598, 7587, -1, 7587, 7598, 7588, -1, 7591, 7600, 7593, -1, 7588, 7600, 7591, -1, 3299, 7601, 3301, -1, 7583, 7601, 3299, -1, 3301, 7601, 7573, -1, 7593, 7602, 7595, -1, 7595, 7602, 7596, -1, 7603, 7604, 7597, -1, 7597, 7604, 7598, -1, 3301, 7573, 3303, -1, 7598, 7605, 7588, -1, 7588, 7605, 7600, -1, 7573, 7606, 7574, -1, 7583, 7606, 7601, -1, 7601, 7606, 7573, -1, 7596, 7606, 7583, -1, 7593, 7607, 7602, -1, 7600, 7607, 7593, -1, 7608, 7609, 7603, -1, 7603, 7609, 7604, -1, 7604, 7610, 7598, -1, 7598, 7610, 7605, -1, 7596, 7611, 7606, -1, 7574, 7611, 7575, -1, 7606, 7611, 7574, -1, 7602, 7611, 7596, -1, 7605, 7612, 7600, -1, 7600, 7612, 7607, -1, 7611, 7613, 7575, -1, 7602, 7613, 7611, -1, 7575, 7613, 7576, -1, 7607, 7613, 7602, -1, 4748, 7614, 3913, -1, 3913, 7614, 7608, -1, 7608, 7614, 7609, -1, 7609, 7615, 7604, -1, 7604, 7615, 7610, -1, 7616, 7617, 3310, -1, 7605, 7581, 7612, -1, 3310, 7617, 3304, -1, 7610, 7581, 7605, -1, 4750, 7618, 4748, -1, 7619, 7594, 7616, -1, 7614, 7618, 4750, -1, 4748, 7618, 7614, -1, 7613, 7620, 7576, -1, 7616, 7594, 7617, -1, 7607, 7620, 7613, -1, 7576, 7620, 7577, -1, 3304, 7582, 3302, -1, 3302, 7582, 3298, -1, 7612, 7620, 7607, -1, 4752, 7621, 4750, -1, 7614, 7621, 7609, -1, 7617, 7582, 3304, -1, 4750, 7621, 7614, -1, 7609, 7621, 7615, -1, 7610, 7590, 7581, -1, 7615, 7590, 7610, -1, 7589, 7591, 7619, -1, 7619, 7591, 7594, -1, 7581, 7579, 7612, -1, 7612, 7579, 7620, -1, 7620, 7579, 7577, -1, 7615, 7585, 7590, -1, 7621, 7585, 7615, -1, 4752, 7585, 7621, -1, 7594, 7595, 7617, -1, 7577, 7580, 7578, -1, 7617, 7595, 7582, -1, 7590, 7580, 7581, -1, 3298, 7583, 3299, -1, 3911, 3913, 7622, -1, 7622, 7608, 7623, -1, 3913, 7608, 7622, -1, 7623, 7603, 7624, -1, 7608, 7603, 7623, -1, 7624, 7597, 7625, -1, 7603, 7597, 7624, -1, 7625, 7599, 7626, -1, 7597, 7599, 7625, -1, 7626, 7587, 7627, -1, 7599, 7587, 7626, -1, 7627, 7589, 7628, -1, 7587, 7589, 7627, -1, 7628, 7619, 7629, -1, 7589, 7619, 7628, -1, 7629, 7616, 3379, -1, 7619, 7616, 7629, -1, 7616, 3310, 3379, -1, 7622, 5170, 3911, -1, 5172, 2545, 2086, -1, 5172, 2548, 2545, -1, 3379, 3396, 7629, -1, 5172, 2551, 2548, -1, 3395, 2559, 2556, -1, 3395, 2561, 2559, -1, 3395, 2564, 2561, -1, 5170, 7630, 5172, -1, 7622, 7630, 5170, -1, 7623, 7631, 7622, -1, 7630, 7631, 5172, -1, 7622, 7631, 7630, -1, 7624, 7632, 7623, -1, 7631, 7632, 5172, -1, 7623, 7632, 7631, -1, 5172, 7632, 2551, -1, 2551, 7633, 2554, -1, 7625, 7633, 7624, -1, 7632, 7633, 2551, -1, 7624, 7633, 7632, -1, 2554, 7634, 2556, -1, 7626, 7634, 7625, -1, 7633, 7634, 2554, -1, 7625, 7634, 7633, -1, 7627, 7635, 7626, -1, 7634, 7635, 2556, -1, 7626, 7635, 7634, -1, 2556, 7635, 3395, -1, 7628, 7636, 7627, -1, 7627, 7636, 7635, -1, 7635, 7636, 3395, -1, 3395, 7637, 3396, -1, 7629, 7637, 7628, -1, 7636, 7637, 3395, -1, 3396, 7637, 7629, -1, 7628, 7637, 7636, -1, 7638, 5093, 4004, -1, 3489, 3495, 7639, -1, 5095, 2567, 2082, -1, 5095, 2570, 2567, -1, 3494, 2583, 2580, -1, 3494, 2584, 2583, -1, 5093, 7640, 5095, -1, 7638, 7640, 5093, -1, 7641, 7642, 7638, -1, 7640, 7642, 5095, -1, 7638, 7642, 7640, -1, 7643, 7644, 7641, -1, 7641, 7644, 7642, -1, 7645, 7646, 7643, -1, 7643, 7646, 7644, -1, 7647, 7648, 7645, -1, 7645, 7648, 7646, -1, 7649, 7650, 7647, -1, 7647, 7650, 7648, -1, 7651, 7652, 7649, -1, 7649, 7652, 7650, -1, 3494, 7653, 3495, -1, 7639, 7653, 7651, -1, 7652, 7653, 3494, -1, 3495, 7653, 7639, -1, 7651, 7653, 7652, -1, 2578, 7654, 2580, -1, 2576, 7654, 2578, -1, 2573, 7654, 2576, -1, 2570, 7654, 2573, -1, 7650, 7654, 7648, -1, 3494, 7654, 7652, -1, 7648, 7654, 7646, -1, 7652, 7654, 7650, -1, 7644, 7654, 7642, -1, 7642, 7654, 5095, -1, 5095, 7654, 2570, -1, 7646, 7654, 7644, -1, 2580, 7654, 3494, -1, 3605, 3604, 4004, -1, 4004, 3604, 7638, -1, 7638, 3603, 7641, -1, 3604, 3603, 7638, -1, 3603, 3602, 7641, -1, 7641, 3600, 7643, -1, 3602, 3600, 7641, -1, 7643, 3598, 7645, -1, 3600, 3598, 7643, -1, 7645, 3595, 7647, -1, 3598, 3595, 7645, -1, 7647, 3593, 7649, -1, 3595, 3593, 7647, -1, 7649, 3590, 7651, -1, 3593, 3590, 7649, -1, 7651, 3592, 7639, -1, 3590, 3592, 7651, -1, 7639, 3490, 3489, -1, 3592, 3490, 7639, -1, 6806, 2102, 2357, -1, 2361, 6806, 2357, -1, 6805, 6806, 2361, -1, 2612, 2361, 2255, -1, 2612, 6805, 2361, -1, 2599, 6805, 2612, -1, 2601, 6805, 2599, -1, 6495, 2111, 2285, -1, 6494, 2285, 2289, -1, 6494, 6495, 2285, -1, 2641, 2289, 2250, -1, 2641, 6494, 2289, -1, 2628, 6494, 2641, -1, 2630, 6494, 2628, -1, 6922, 2120, 2384, -1, 6921, 2384, 2388, -1, 6921, 6922, 2384, -1, 2670, 2388, 2245, -1, 2670, 6921, 2388, -1, 2657, 6921, 2670, -1, 2659, 6921, 2657, -1, 7038, 2129, 2413, -1, 7037, 2413, 2417, -1, 7037, 7038, 2413, -1, 2699, 2417, 2240, -1, 2699, 7037, 2417, -1, 2686, 7037, 2699, -1, 2688, 7037, 2686, -1, 7156, 2715, 2717, -1, 2450, 2220, 2728, -1, 2450, 2728, 2715, -1, 2450, 2715, 7156, -1, 7158, 2450, 7156, -1, 2446, 2450, 7158, -1, 2147, 2446, 7158, -1, 7272, 2747, 2749, -1, 2478, 2225, 2760, -1, 2478, 2760, 2747, -1, 2478, 2747, 7272, -1, 2474, 7272, 7274, -1, 2474, 2478, 7272, -1, 2156, 2474, 7274, -1, 7500, 2161, 2532, -1, 2536, 7500, 2532, -1, 7499, 7500, 2536, -1, 2792, 2536, 2230, -1, 2792, 7499, 2536, -1, 2779, 7499, 2792, -1, 2781, 7499, 2779, -1, 6378, 2206, 2811, -1, 6378, 2811, 2812, -1, 6378, 2812, 2823, -1, 2051, 2507, 6379, -1, 2510, 6378, 6379, -1, 2510, 2206, 6378, -1, 2510, 6379, 2507, -1, 7504, 2840, 2842, -1, 2542, 2235, 2853, -1, 2542, 2853, 2840, -1, 2542, 2840, 7504, -1, 7506, 2542, 7504, -1, 2538, 2542, 7506, -1, 2024, 2538, 7506, -1, 2155, 5165, 2855, -1, 1949, 414, 416, -1, 1949, 412, 414, -1, 5163, 7655, 7656, -1, 5163, 3925, 7655, -1, 1698, 7657, 1948, -1, 1948, 7657, 1949, -1, 1696, 7657, 1698, -1, 1694, 7658, 1696, -1, 7657, 7658, 1949, -1, 1696, 7658, 7657, -1, 1692, 7659, 1694, -1, 1694, 7659, 7658, -1, 1690, 7660, 1692, -1, 1692, 7660, 7659, -1, 1688, 7661, 1690, -1, 1690, 7661, 7660, -1, 2858, 7662, 1688, -1, 1688, 7662, 7661, -1, 5163, 7663, 5165, -1, 2855, 7663, 2858, -1, 2858, 7663, 7662, -1, 5165, 7663, 2855, -1, 7662, 7663, 5163, -1, 412, 7664, 410, -1, 410, 7664, 408, -1, 408, 7664, 407, -1, 407, 7664, 7656, -1, 7658, 7664, 1949, -1, 7659, 7664, 7658, -1, 7662, 7664, 7661, -1, 7660, 7664, 7659, -1, 5163, 7664, 7662, -1, 7661, 7664, 7660, -1, 1949, 7664, 412, -1, 7656, 7664, 5163, -1, 3925, 3923, 7655, -1, 7655, 7665, 7656, -1, 3923, 7665, 7655, -1, 7656, 7666, 407, -1, 7665, 7666, 7656, -1, 7666, 405, 407, -1, 394, 7667, 398, -1, 7668, 7667, 7669, -1, 7669, 7667, 394, -1, 7670, 7667, 7668, -1, 7666, 7671, 405, -1, 405, 7671, 406, -1, 406, 7671, 7672, -1, 7672, 7673, 7674, -1, 7674, 7673, 7675, -1, 398, 7676, 402, -1, 7670, 7676, 7667, -1, 7667, 7676, 398, -1, 7675, 7676, 7670, -1, 7666, 7677, 7671, -1, 7672, 7678, 7673, -1, 7671, 7678, 7672, -1, 4815, 7679, 4817, -1, 7665, 7679, 7666, -1, 4817, 7679, 7665, -1, 7666, 7679, 7677, -1, 402, 7680, 404, -1, 7676, 7680, 402, -1, 7673, 7680, 7675, -1, 7675, 7680, 7676, -1, 1991, 394, 396, -1, 7677, 7681, 7671, -1, 7671, 7681, 7678, -1, 404, 7682, 378, -1, 7680, 7682, 404, -1, 7678, 7682, 7673, -1, 7673, 7682, 7680, -1, 4812, 7683, 4815, -1, 3923, 4817, 7665, -1, 4815, 7683, 7679, -1, 7679, 7683, 7677, -1, 7677, 7683, 7681, -1, 378, 7684, 377, -1, 7682, 7684, 378, -1, 7681, 7684, 7678, -1, 7678, 7684, 7682, -1, 4810, 7685, 4812, -1, 7681, 7685, 7684, -1, 4812, 7685, 7683, -1, 377, 7685, 4810, -1, 7683, 7685, 7681, -1, 7684, 7685, 377, -1, 4810, 392, 377, -1, 413, 7686, 415, -1, 415, 7686, 2002, -1, 411, 7687, 413, -1, 413, 7687, 7686, -1, 2002, 7668, 1995, -1, 1995, 7668, 1990, -1, 7686, 7668, 2002, -1, 409, 7674, 411, -1, 411, 7674, 7687, -1, 7686, 7670, 7668, -1, 7687, 7670, 7686, -1, 1990, 7669, 1991, -1, 7668, 7669, 1990, -1, 1991, 7669, 394, -1, 406, 7672, 409, -1, 409, 7672, 7674, -1, 7674, 7675, 7687, -1, 7687, 7675, 7670, -1, 3930, 7688, 393, -1, 393, 7688, 390, -1, 390, 7689, 385, -1, 7688, 7689, 390, -1, 385, 7690, 382, -1, 7689, 7690, 385, -1, 382, 7691, 370, -1, 7690, 7691, 382, -1, 370, 7692, 368, -1, 7691, 7692, 370, -1, 387, 7693, 388, -1, 368, 7693, 387, -1, 7692, 7693, 368, -1, 7693, 1799, 388, -1, 7694, 7695, 1781, -1, 7689, 7696, 7690, -1, 7690, 7696, 7697, -1, 7697, 7698, 7699, -1, 7699, 7698, 7700, -1, 7701, 7702, 7694, -1, 7694, 7702, 7695, -1, 1777, 7703, 2017, -1, 2017, 7703, 1782, -1, 1782, 7703, 7704, -1, 7695, 7703, 1777, -1, 4796, 7705, 3930, -1, 7688, 7705, 7689, -1, 3930, 7705, 7688, -1, 7689, 7705, 7696, -1, 7696, 7706, 7697, -1, 7697, 7706, 7698, -1, 7701, 7707, 7702, -1, 7700, 7707, 7701, -1, 7704, 7708, 7709, -1, 7703, 7708, 7704, -1, 7702, 7708, 7695, -1, 7695, 7708, 7703, -1, 4799, 7710, 4798, -1, 4798, 7710, 4796, -1, 4796, 7710, 7705, -1, 7705, 7710, 7696, -1, 7696, 7710, 7706, -1, 7698, 7711, 7700, -1, 7700, 7711, 7707, -1, 7709, 7712, 7713, -1, 7708, 7712, 7709, -1, 7707, 7712, 7702, -1, 7702, 7712, 7708, -1, 7706, 7714, 7698, -1, 7698, 7714, 7711, -1, 7711, 7715, 7707, -1, 7713, 7715, 7716, -1, 7712, 7715, 7713, -1, 7707, 7715, 7712, -1, 4803, 7717, 4801, -1, 4801, 7717, 4799, -1, 7706, 7717, 7714, -1, 4799, 7717, 7710, -1, 7710, 7717, 7706, -1, 7714, 7718, 7711, -1, 7715, 7718, 7716, -1, 7716, 7718, 7719, -1, 4803, 3927, 7720, -1, 1799, 7721, 1794, -1, 7711, 7718, 7715, -1, 1794, 7721, 1788, -1, 7714, 7722, 7718, -1, 7719, 7722, 7720, -1, 4803, 7722, 7717, -1, 7693, 7721, 1799, -1, 7717, 7722, 7714, -1, 7720, 7722, 4803, -1, 7718, 7722, 7719, -1, 7692, 7723, 7693, -1, 7693, 7723, 7721, -1, 1788, 7694, 1781, -1, 7721, 7694, 1788, -1, 7691, 7699, 7692, -1, 7692, 7699, 7723, -1, 7721, 7701, 7694, -1, 7723, 7701, 7721, -1, 7690, 7697, 7691, -1, 7691, 7697, 7699, -1, 7699, 7700, 7723, -1, 7723, 7700, 7701, -1, 1781, 7695, 1777, -1, 1782, 7704, 1807, -1, 1807, 7704, 7724, -1, 7724, 7709, 7725, -1, 7704, 7709, 7724, -1, 7725, 7713, 7726, -1, 7726, 7713, 7727, -1, 7709, 7713, 7725, -1, 7727, 7716, 7728, -1, 7713, 7716, 7727, -1, 7728, 7719, 7729, -1, 7716, 7719, 7728, -1, 7729, 7720, 3929, -1, 7719, 7720, 7729, -1, 7720, 3927, 3929, -1, 5167, 7729, 3929, -1, 1814, 1813, 2869, -1, 5167, 7728, 7729, -1, 5167, 7727, 7728, -1, 1812, 7725, 7726, -1, 1812, 7724, 7725, -1, 1812, 1807, 7724, -1, 2860, 7730, 2151, -1, 2151, 7730, 5169, -1, 5169, 7730, 5167, -1, 2862, 7731, 2860, -1, 7730, 7731, 5167, -1, 2860, 7731, 7730, -1, 2864, 7732, 2862, -1, 7731, 7732, 5167, -1, 2862, 7732, 7731, -1, 5167, 7732, 7727, -1, 2866, 7733, 2864, -1, 7727, 7733, 7726, -1, 7732, 7733, 7727, -1, 2864, 7733, 7732, -1, 7726, 7733, 1812, -1, 2869, 7734, 2867, -1, 2867, 7734, 2866, -1, 7733, 7734, 1812, -1, 2866, 7734, 7733, -1, 1812, 7735, 1813, -1, 7734, 7735, 1812, -1, 1813, 7735, 2869, -1, 2869, 7735, 7734, -1, 2146, 5157, 2873, -1, 1942, 361, 363, -1, 1942, 359, 361, -1, 5155, 7736, 7737, -1, 5155, 3935, 7736, -1, 1685, 7738, 1941, -1, 1941, 7738, 1942, -1, 1683, 7738, 1685, -1, 1681, 7739, 1683, -1, 7738, 7739, 1942, -1, 1683, 7739, 7738, -1, 1679, 7740, 1681, -1, 1681, 7740, 7739, -1, 1677, 7741, 1679, -1, 1679, 7741, 7740, -1, 1675, 7742, 1677, -1, 1677, 7742, 7741, -1, 2876, 7743, 1675, -1, 1675, 7743, 7742, -1, 5155, 7744, 5157, -1, 2873, 7744, 2876, -1, 2876, 7744, 7743, -1, 5157, 7744, 2873, -1, 7743, 7744, 5155, -1, 359, 7745, 357, -1, 357, 7745, 355, -1, 355, 7745, 354, -1, 354, 7745, 7737, -1, 7739, 7745, 1942, -1, 7740, 7745, 7739, -1, 7743, 7745, 7742, -1, 7741, 7745, 7740, -1, 5155, 7745, 7743, -1, 7742, 7745, 7741, -1, 1942, 7745, 359, -1, 7737, 7745, 5155, -1, 3935, 3933, 7736, -1, 7736, 7746, 7737, -1, 3933, 7746, 7736, -1, 7737, 7747, 354, -1, 7746, 7747, 7737, -1, 7747, 352, 354, -1, 341, 7748, 345, -1, 7749, 7748, 7750, -1, 7750, 7748, 341, -1, 7751, 7748, 7749, -1, 352, 7752, 353, -1, 353, 7752, 7753, -1, 7753, 7754, 7755, -1, 7755, 7754, 7756, -1, 345, 7757, 349, -1, 7751, 7757, 7748, -1, 7748, 7757, 345, -1, 7756, 7757, 7751, -1, 7747, 7758, 352, -1, 352, 7758, 7752, -1, 7753, 7759, 7754, -1, 7752, 7759, 7753, -1, 4837, 7760, 4839, -1, 7746, 7760, 7747, -1, 7747, 7760, 7758, -1, 4839, 7760, 7746, -1, 349, 7761, 351, -1, 7757, 7761, 349, -1, 7754, 7761, 7756, -1, 1965, 341, 343, -1, 7756, 7761, 7757, -1, 7758, 7762, 7752, -1, 7752, 7762, 7759, -1, 351, 7763, 325, -1, 7761, 7763, 351, -1, 7759, 7763, 7754, -1, 7754, 7763, 7761, -1, 3933, 4839, 7746, -1, 4834, 7764, 4837, -1, 4837, 7764, 7760, -1, 7760, 7764, 7758, -1, 7758, 7764, 7762, -1, 325, 7765, 324, -1, 7763, 7765, 325, -1, 7762, 7765, 7759, -1, 7759, 7765, 7763, -1, 4832, 7766, 4834, -1, 7762, 7766, 7765, -1, 4834, 7766, 7764, -1, 324, 7766, 4832, -1, 7764, 7766, 7762, -1, 7765, 7766, 324, -1, 4832, 339, 324, -1, 360, 7767, 362, -1, 362, 7767, 1975, -1, 358, 7768, 360, -1, 360, 7768, 7767, -1, 1975, 7749, 1969, -1, 1969, 7749, 1964, -1, 7767, 7749, 1975, -1, 356, 7755, 358, -1, 358, 7755, 7768, -1, 7767, 7751, 7749, -1, 7768, 7751, 7767, -1, 1964, 7750, 1965, -1, 7749, 7750, 1964, -1, 1965, 7750, 341, -1, 353, 7753, 356, -1, 356, 7753, 7755, -1, 7755, 7756, 7768, -1, 7768, 7756, 7751, -1, 340, 3940, 337, -1, 3940, 7769, 337, -1, 332, 7770, 329, -1, 337, 7770, 332, -1, 7769, 7770, 337, -1, 7770, 7771, 329, -1, 329, 7772, 317, -1, 7771, 7772, 329, -1, 317, 7773, 315, -1, 7772, 7773, 317, -1, 334, 7774, 335, -1, 315, 7774, 334, -1, 7773, 7774, 315, -1, 7774, 1890, 335, -1, 7775, 7776, 2000, -1, 7770, 7777, 7771, -1, 7769, 7777, 7770, -1, 7771, 7777, 7778, -1, 7778, 7779, 7780, -1, 7780, 7779, 7781, -1, 7782, 7783, 7775, -1, 7775, 7783, 7776, -1, 1994, 7784, 1993, -1, 1993, 7784, 1992, -1, 1992, 7784, 7785, -1, 7776, 7784, 1994, -1, 4818, 7786, 3940, -1, 3940, 7786, 7769, -1, 7769, 7786, 7777, -1, 7777, 7787, 7778, -1, 7778, 7787, 7779, -1, 7782, 7788, 7783, -1, 7781, 7788, 7782, -1, 7785, 7789, 7790, -1, 7784, 7789, 7785, -1, 7783, 7789, 7776, -1, 7776, 7789, 7784, -1, 4821, 7791, 4820, -1, 4820, 7791, 4818, -1, 4818, 7791, 7786, -1, 7786, 7791, 7777, -1, 7777, 7791, 7787, -1, 7779, 7792, 7781, -1, 7781, 7792, 7788, -1, 7790, 7793, 7794, -1, 7789, 7793, 7790, -1, 7788, 7793, 7783, -1, 7783, 7793, 7789, -1, 7787, 7795, 7779, -1, 7779, 7795, 7792, -1, 7792, 7796, 7788, -1, 7794, 7796, 7797, -1, 7793, 7796, 7794, -1, 7788, 7796, 7793, -1, 4825, 7798, 4823, -1, 4823, 7798, 4821, -1, 7787, 7798, 7795, -1, 4821, 7798, 7791, -1, 7791, 7798, 7787, -1, 7795, 7799, 7792, -1, 7796, 7799, 7797, -1, 7797, 7799, 7800, -1, 4825, 3937, 7801, -1, 7792, 7799, 7796, -1, 7795, 7802, 7799, -1, 1890, 7803, 2007, -1, 7800, 7802, 7801, -1, 2007, 7803, 2004, -1, 7798, 7802, 7795, -1, 4825, 7802, 7798, -1, 7801, 7802, 4825, -1, 7774, 7803, 1890, -1, 7799, 7802, 7800, -1, 7773, 7804, 7774, -1, 7774, 7804, 7803, -1, 2004, 7775, 2000, -1, 7803, 7775, 2004, -1, 7772, 7780, 7773, -1, 7773, 7780, 7804, -1, 7803, 7782, 7775, -1, 7804, 7782, 7803, -1, 7771, 7778, 7772, -1, 7772, 7778, 7780, -1, 7780, 7781, 7804, -1, 7804, 7781, 7782, -1, 2000, 7776, 1994, -1, 1992, 7785, 2010, -1, 2010, 7785, 7805, -1, 7805, 7790, 7806, -1, 7785, 7790, 7805, -1, 7806, 7794, 7807, -1, 7790, 7794, 7806, -1, 7807, 7797, 7808, -1, 7794, 7797, 7807, -1, 7808, 7800, 7809, -1, 7797, 7800, 7808, -1, 7809, 7801, 7810, -1, 7810, 7801, 3939, -1, 7800, 7801, 7809, -1, 7801, 3937, 3939, -1, 5159, 7810, 3939, -1, 1945, 2013, 2887, -1, 5159, 7809, 7810, -1, 5159, 7808, 7809, -1, 2012, 7806, 7807, -1, 2012, 7805, 7806, -1, 2012, 2010, 7805, -1, 2878, 7811, 2142, -1, 2142, 7811, 5161, -1, 5161, 7811, 5159, -1, 2880, 7812, 2878, -1, 7811, 7812, 5159, -1, 2878, 7812, 7811, -1, 2882, 7813, 2880, -1, 7812, 7813, 5159, -1, 2880, 7813, 7812, -1, 5159, 7813, 7808, -1, 2884, 7814, 2882, -1, 7808, 7814, 7807, -1, 7813, 7814, 7808, -1, 2882, 7814, 7813, -1, 7807, 7814, 2012, -1, 2887, 7815, 2885, -1, 2885, 7815, 2884, -1, 7814, 7815, 2012, -1, 2884, 7815, 7814, -1, 2012, 7816, 2013, -1, 7815, 7816, 2012, -1, 2013, 7816, 2887, -1, 2887, 7816, 7815, -1, 2137, 5149, 2891, -1, 1935, 308, 310, -1, 1935, 306, 308, -1, 5147, 7817, 7818, -1, 5147, 3945, 7817, -1, 1672, 7819, 1934, -1, 1934, 7819, 1935, -1, 1670, 7819, 1672, -1, 1668, 7820, 1670, -1, 7819, 7820, 1935, -1, 1670, 7820, 7819, -1, 1666, 7821, 1668, -1, 1668, 7821, 7820, -1, 1664, 7822, 1666, -1, 1666, 7822, 7821, -1, 1662, 7823, 1664, -1, 1664, 7823, 7822, -1, 2894, 7824, 1662, -1, 1662, 7824, 7823, -1, 5147, 7825, 5149, -1, 2891, 7825, 2894, -1, 2894, 7825, 7824, -1, 5149, 7825, 2891, -1, 7824, 7825, 5147, -1, 306, 7826, 304, -1, 304, 7826, 302, -1, 302, 7826, 301, -1, 301, 7826, 7818, -1, 7820, 7826, 1935, -1, 7821, 7826, 7820, -1, 7824, 7826, 7823, -1, 7822, 7826, 7821, -1, 5147, 7826, 7824, -1, 7823, 7826, 7822, -1, 1935, 7826, 306, -1, 7818, 7826, 5147, -1, 3943, 7827, 3945, -1, 3945, 7827, 7817, -1, 7818, 7828, 301, -1, 7817, 7828, 7818, -1, 7827, 7828, 7817, -1, 7828, 299, 301, -1, 288, 7829, 292, -1, 7830, 7829, 7831, -1, 7831, 7829, 288, -1, 7832, 7829, 7830, -1, 299, 7833, 300, -1, 300, 7833, 7834, -1, 7834, 7835, 7836, -1, 7836, 7835, 7837, -1, 292, 7838, 296, -1, 7832, 7838, 7829, -1, 7829, 7838, 292, -1, 7837, 7838, 7832, -1, 7828, 7839, 299, -1, 299, 7839, 7833, -1, 7834, 7840, 7835, -1, 7833, 7840, 7834, -1, 4859, 7841, 4861, -1, 7827, 7841, 7828, -1, 7828, 7841, 7839, -1, 4861, 7841, 7827, -1, 296, 7842, 298, -1, 7838, 7842, 296, -1, 7835, 7842, 7837, -1, 1896, 288, 290, -1, 7837, 7842, 7838, -1, 7839, 7843, 7833, -1, 7833, 7843, 7840, -1, 298, 7844, 272, -1, 7842, 7844, 298, -1, 7840, 7844, 7835, -1, 7835, 7844, 7842, -1, 3943, 4861, 7827, -1, 4856, 7845, 4859, -1, 4859, 7845, 7841, -1, 7841, 7845, 7839, -1, 7839, 7845, 7843, -1, 272, 7846, 271, -1, 7844, 7846, 272, -1, 7843, 7846, 7840, -1, 7840, 7846, 7844, -1, 4854, 7847, 4856, -1, 7843, 7847, 7846, -1, 4856, 7847, 7845, -1, 271, 7847, 4854, -1, 7845, 7847, 7843, -1, 7846, 7847, 271, -1, 4854, 286, 271, -1, 307, 7848, 309, -1, 309, 7848, 1936, -1, 305, 7849, 307, -1, 307, 7849, 7848, -1, 1936, 7830, 1914, -1, 1914, 7830, 1899, -1, 7848, 7830, 1936, -1, 303, 7836, 305, -1, 305, 7836, 7849, -1, 7848, 7832, 7830, -1, 7849, 7832, 7848, -1, 1899, 7831, 1896, -1, 7830, 7831, 1899, -1, 1896, 7831, 288, -1, 300, 7834, 303, -1, 303, 7834, 7836, -1, 7836, 7837, 7849, -1, 7849, 7837, 7832, -1, 287, 3950, 284, -1, 3950, 7850, 284, -1, 284, 7851, 279, -1, 7850, 7851, 284, -1, 276, 7852, 264, -1, 279, 7852, 276, -1, 7851, 7852, 279, -1, 264, 7853, 262, -1, 7852, 7853, 264, -1, 262, 7854, 281, -1, 7853, 7854, 262, -1, 281, 7855, 282, -1, 7854, 7855, 281, -1, 7855, 1889, 282, -1, 7856, 7857, 1973, -1, 7851, 7858, 7852, -1, 7852, 7858, 7859, -1, 7859, 7860, 7861, -1, 7861, 7860, 7862, -1, 7863, 7864, 7856, -1, 7856, 7864, 7857, -1, 1968, 7865, 1967, -1, 1967, 7865, 1966, -1, 1966, 7865, 7866, -1, 7866, 7865, 7867, -1, 7857, 7865, 1968, -1, 4840, 7868, 3950, -1, 7850, 7868, 7851, -1, 3950, 7868, 7850, -1, 7851, 7868, 7858, -1, 7858, 7869, 7859, -1, 7859, 7869, 7860, -1, 7863, 7870, 7864, -1, 7862, 7870, 7863, -1, 7864, 7871, 7857, -1, 7865, 7871, 7867, -1, 7857, 7871, 7865, -1, 4843, 7872, 4842, -1, 4842, 7872, 4840, -1, 4840, 7872, 7868, -1, 7868, 7872, 7858, -1, 7858, 7872, 7869, -1, 7860, 7873, 7862, -1, 7862, 7873, 7870, -1, 7867, 7874, 7875, -1, 7871, 7874, 7867, -1, 7870, 7874, 7864, -1, 7864, 7874, 7871, -1, 7869, 7876, 7860, -1, 7860, 7876, 7873, -1, 7873, 7877, 7870, -1, 7875, 7877, 7878, -1, 7874, 7877, 7875, -1, 7870, 7877, 7874, -1, 4847, 7879, 4845, -1, 4845, 7879, 4843, -1, 7869, 7879, 7876, -1, 4843, 7879, 7872, -1, 7872, 7879, 7869, -1, 7876, 7880, 7873, -1, 7877, 7880, 7878, -1, 7878, 7880, 7881, -1, 4847, 3947, 7882, -1, 7873, 7880, 7877, -1, 7876, 7883, 7880, -1, 1889, 7884, 1981, -1, 7881, 7883, 7882, -1, 1981, 7884, 1978, -1, 7879, 7883, 7876, -1, 4847, 7883, 7879, -1, 7882, 7883, 4847, -1, 7855, 7884, 1889, -1, 7880, 7883, 7881, -1, 7854, 7885, 7855, -1, 7855, 7885, 7884, -1, 1978, 7856, 1973, -1, 7884, 7856, 1978, -1, 7853, 7861, 7854, -1, 7854, 7861, 7885, -1, 7884, 7863, 7856, -1, 7885, 7863, 7884, -1, 7852, 7859, 7853, -1, 7853, 7859, 7861, -1, 7861, 7862, 7885, -1, 7885, 7862, 7863, -1, 1973, 7857, 1968, -1, 1984, 1966, 7886, -1, 7886, 7866, 7887, -1, 1966, 7866, 7886, -1, 7887, 7867, 7888, -1, 7866, 7867, 7887, -1, 7888, 7875, 7889, -1, 7867, 7875, 7888, -1, 7889, 7878, 7890, -1, 7875, 7878, 7889, -1, 7890, 7881, 7891, -1, 7878, 7881, 7890, -1, 7891, 7882, 3949, -1, 7881, 7882, 7891, -1, 7882, 3947, 3949, -1, 5143, 7891, 3949, -1, 1938, 1987, 2905, -1, 5143, 7890, 7891, -1, 5143, 7889, 7890, -1, 1986, 7887, 7888, -1, 1986, 7886, 7887, -1, 1986, 1984, 7886, -1, 2896, 7892, 2133, -1, 2133, 7892, 5145, -1, 5145, 7892, 5143, -1, 2898, 7893, 2896, -1, 7892, 7893, 5143, -1, 2896, 7893, 7892, -1, 2900, 7894, 2898, -1, 7893, 7894, 5143, -1, 2898, 7894, 7893, -1, 5143, 7894, 7889, -1, 2902, 7895, 2900, -1, 7889, 7895, 7888, -1, 7894, 7895, 7889, -1, 2900, 7895, 7894, -1, 7888, 7895, 1986, -1, 2903, 7896, 2902, -1, 7895, 7896, 1986, -1, 2902, 7896, 7895, -1, 1986, 7897, 1987, -1, 2905, 7897, 2903, -1, 2903, 7897, 7896, -1, 7896, 7897, 1986, -1, 1987, 7897, 2905, -1, 2128, 5141, 2909, -1, 1885, 255, 257, -1, 1885, 253, 255, -1, 5139, 7898, 7899, -1, 5139, 3955, 7898, -1, 1659, 7900, 1929, -1, 1929, 7900, 1885, -1, 1657, 7900, 1659, -1, 1655, 7901, 1657, -1, 7900, 7901, 1885, -1, 1657, 7901, 7900, -1, 1653, 7902, 1655, -1, 1655, 7902, 7901, -1, 1651, 7903, 1653, -1, 1653, 7903, 7902, -1, 1649, 7904, 1651, -1, 1651, 7904, 7903, -1, 2912, 7905, 1649, -1, 1649, 7905, 7904, -1, 5139, 7906, 5141, -1, 2909, 7906, 2912, -1, 2912, 7906, 7905, -1, 5141, 7906, 2909, -1, 7905, 7906, 5139, -1, 253, 7907, 251, -1, 251, 7907, 249, -1, 249, 7907, 248, -1, 248, 7907, 7899, -1, 7901, 7907, 1885, -1, 7902, 7907, 7901, -1, 7905, 7907, 7904, -1, 7903, 7907, 7902, -1, 5139, 7907, 7905, -1, 7904, 7907, 7903, -1, 1885, 7907, 253, -1, 7899, 7907, 5139, -1, 3953, 7908, 3955, -1, 3955, 7908, 7898, -1, 7898, 7909, 7899, -1, 7908, 7909, 7898, -1, 7899, 246, 248, -1, 7909, 246, 7899, -1, 235, 7910, 239, -1, 7911, 7910, 7912, -1, 7912, 7910, 235, -1, 7913, 7910, 7911, -1, 246, 7914, 247, -1, 247, 7914, 7915, -1, 7915, 7916, 7917, -1, 7917, 7916, 7918, -1, 239, 7919, 243, -1, 7913, 7919, 7910, -1, 7910, 7919, 239, -1, 7918, 7919, 7913, -1, 7909, 7920, 246, -1, 246, 7920, 7914, -1, 7915, 7921, 7916, -1, 7914, 7921, 7915, -1, 4881, 7922, 4883, -1, 7908, 7922, 7909, -1, 7909, 7922, 7920, -1, 4883, 7922, 7908, -1, 243, 7923, 245, -1, 7919, 7923, 243, -1, 7916, 7923, 7918, -1, 1835, 235, 237, -1, 7918, 7923, 7919, -1, 7920, 7924, 7914, -1, 7914, 7924, 7921, -1, 245, 7925, 219, -1, 7923, 7925, 245, -1, 7921, 7925, 7916, -1, 7916, 7925, 7923, -1, 3953, 4883, 7908, -1, 4878, 7926, 4881, -1, 4881, 7926, 7922, -1, 7922, 7926, 7920, -1, 7920, 7926, 7924, -1, 219, 7927, 218, -1, 7925, 7927, 219, -1, 7924, 7927, 7921, -1, 7921, 7927, 7925, -1, 4876, 7928, 4878, -1, 7924, 7928, 7927, -1, 4878, 7928, 7926, -1, 218, 7928, 4876, -1, 7926, 7928, 7924, -1, 7927, 7928, 218, -1, 4876, 233, 218, -1, 254, 7929, 256, -1, 256, 7929, 1854, -1, 252, 7930, 254, -1, 254, 7930, 7929, -1, 1854, 7911, 1847, -1, 1847, 7911, 1834, -1, 7929, 7911, 1854, -1, 250, 7917, 252, -1, 252, 7917, 7930, -1, 7929, 7913, 7911, -1, 7930, 7913, 7929, -1, 1834, 7912, 1835, -1, 7911, 7912, 1834, -1, 1835, 7912, 235, -1, 247, 7915, 250, -1, 250, 7915, 7917, -1, 7917, 7918, 7930, -1, 7930, 7918, 7913, -1, 3960, 7931, 234, -1, 234, 7931, 231, -1, 231, 7932, 226, -1, 7931, 7932, 231, -1, 226, 7933, 223, -1, 7932, 7933, 226, -1, 223, 7934, 211, -1, 7933, 7934, 223, -1, 211, 7935, 209, -1, 7934, 7935, 211, -1, 209, 7936, 228, -1, 7935, 7936, 209, -1, 228, 1888, 229, -1, 7936, 1888, 228, -1, 7937, 7938, 1923, -1, 7932, 7939, 7933, -1, 7933, 7939, 7940, -1, 7940, 7941, 7942, -1, 7942, 7941, 7943, -1, 7944, 7945, 7937, -1, 7937, 7945, 7938, -1, 1905, 7946, 1897, -1, 1897, 7946, 1895, -1, 1895, 7946, 7947, -1, 7938, 7946, 1905, -1, 4862, 7948, 3960, -1, 7931, 7948, 7932, -1, 3960, 7948, 7931, -1, 7932, 7948, 7939, -1, 7939, 7949, 7940, -1, 7940, 7949, 7941, -1, 7944, 7950, 7945, -1, 7943, 7950, 7944, -1, 7947, 7951, 7952, -1, 7946, 7951, 7947, -1, 7945, 7951, 7938, -1, 7938, 7951, 7946, -1, 4865, 7953, 4864, -1, 4864, 7953, 4862, -1, 4862, 7953, 7948, -1, 7948, 7953, 7939, -1, 7939, 7953, 7949, -1, 7941, 7954, 7943, -1, 7943, 7954, 7950, -1, 7952, 7955, 7956, -1, 7951, 7955, 7952, -1, 7950, 7955, 7945, -1, 7945, 7955, 7951, -1, 7949, 7957, 7941, -1, 7941, 7957, 7954, -1, 7954, 7958, 7950, -1, 7956, 7958, 7959, -1, 7955, 7958, 7956, -1, 7950, 7958, 7955, -1, 4869, 7960, 4867, -1, 4867, 7960, 4865, -1, 7949, 7960, 7957, -1, 4865, 7960, 7953, -1, 7953, 7960, 7949, -1, 7957, 7961, 7954, -1, 7958, 7961, 7959, -1, 7959, 7961, 7962, -1, 4869, 3957, 7963, -1, 1888, 7964, 1953, -1, 7954, 7961, 7958, -1, 1953, 7964, 1943, -1, 7957, 7965, 7961, -1, 7962, 7965, 7963, -1, 4869, 7965, 7960, -1, 7936, 7964, 1888, -1, 7960, 7965, 7957, -1, 7963, 7965, 4869, -1, 7961, 7965, 7962, -1, 7935, 7966, 7936, -1, 7936, 7966, 7964, -1, 1943, 7937, 1923, -1, 7964, 7937, 1943, -1, 7934, 7942, 7935, -1, 7935, 7942, 7966, -1, 7964, 7944, 7937, -1, 7966, 7944, 7964, -1, 7933, 7940, 7934, -1, 7934, 7940, 7942, -1, 7942, 7943, 7966, -1, 7966, 7943, 7944, -1, 1923, 7938, 1905, -1, 1895, 7947, 1959, -1, 1959, 7947, 7967, -1, 7967, 7952, 7968, -1, 7947, 7952, 7967, -1, 7968, 7956, 7969, -1, 7952, 7956, 7968, -1, 7969, 7959, 7970, -1, 7956, 7959, 7969, -1, 7970, 7962, 7971, -1, 7959, 7962, 7970, -1, 7971, 7963, 7972, -1, 7962, 7963, 7971, -1, 7972, 3957, 3959, -1, 7963, 3957, 7972, -1, 5135, 7972, 3959, -1, 1932, 1961, 2923, -1, 5135, 7971, 7972, -1, 5135, 7970, 7971, -1, 1960, 7968, 7969, -1, 1960, 7967, 7968, -1, 1960, 1959, 7967, -1, 2914, 7973, 2124, -1, 2124, 7973, 5137, -1, 5137, 7973, 5135, -1, 2916, 7974, 2914, -1, 7973, 7974, 5135, -1, 2914, 7974, 7973, -1, 2918, 7975, 2916, -1, 7974, 7975, 5135, -1, 2916, 7975, 7974, -1, 5135, 7975, 7970, -1, 2920, 7976, 2918, -1, 7970, 7976, 7969, -1, 7975, 7976, 7970, -1, 2918, 7976, 7975, -1, 7969, 7976, 1960, -1, 2921, 7977, 2920, -1, 7976, 7977, 1960, -1, 2920, 7977, 7976, -1, 1960, 7978, 1961, -1, 2923, 7978, 2921, -1, 2921, 7978, 7977, -1, 7977, 7978, 1960, -1, 1961, 7978, 2923, -1, 2119, 5133, 2927, -1, 1827, 202, 204, -1, 1827, 200, 202, -1, 5131, 7979, 7980, -1, 5131, 3965, 7979, -1, 1646, 7981, 1924, -1, 1924, 7981, 1827, -1, 1644, 7981, 1646, -1, 1642, 7982, 1644, -1, 7981, 7982, 1827, -1, 1644, 7982, 7981, -1, 1640, 7983, 1642, -1, 1642, 7983, 7982, -1, 1638, 7984, 1640, -1, 1640, 7984, 7983, -1, 1636, 7985, 1638, -1, 1638, 7985, 7984, -1, 2930, 7986, 1636, -1, 1636, 7986, 7985, -1, 5131, 7987, 5133, -1, 2927, 7987, 2930, -1, 2930, 7987, 7986, -1, 5133, 7987, 2927, -1, 7986, 7987, 5131, -1, 200, 7988, 198, -1, 198, 7988, 196, -1, 196, 7988, 195, -1, 195, 7988, 7980, -1, 7982, 7988, 1827, -1, 7983, 7988, 7982, -1, 7986, 7988, 7985, -1, 7984, 7988, 7983, -1, 5131, 7988, 7986, -1, 7985, 7988, 7984, -1, 1827, 7988, 200, -1, 7980, 7988, 5131, -1, 3965, 3963, 7979, -1, 3963, 7989, 7979, -1, 7979, 7990, 7980, -1, 7989, 7990, 7979, -1, 7980, 193, 195, -1, 7990, 193, 7980, -1, 182, 7991, 186, -1, 7992, 7991, 7993, -1, 7993, 7991, 182, -1, 7994, 7991, 7992, -1, 193, 7995, 194, -1, 194, 7995, 7996, -1, 7996, 7997, 7998, -1, 7998, 7997, 7999, -1, 186, 8000, 190, -1, 7994, 8000, 7991, -1, 7991, 8000, 186, -1, 7999, 8000, 7994, -1, 7990, 8001, 193, -1, 193, 8001, 7995, -1, 7996, 8002, 7997, -1, 7995, 8002, 7996, -1, 4894, 8003, 4896, -1, 7989, 8003, 7990, -1, 7990, 8003, 8001, -1, 4896, 8003, 7989, -1, 190, 8004, 192, -1, 8000, 8004, 190, -1, 7997, 8004, 7999, -1, 1779, 182, 184, -1, 7999, 8004, 8000, -1, 8001, 8005, 7995, -1, 7995, 8005, 8002, -1, 192, 8006, 166, -1, 8004, 8006, 192, -1, 8002, 8006, 7997, -1, 7997, 8006, 8004, -1, 3963, 4896, 7989, -1, 4891, 8007, 4894, -1, 4894, 8007, 8003, -1, 8003, 8007, 8001, -1, 8001, 8007, 8005, -1, 166, 8008, 165, -1, 8006, 8008, 166, -1, 8005, 8008, 8002, -1, 8002, 8008, 8006, -1, 4889, 8009, 4891, -1, 8005, 8009, 8008, -1, 4891, 8009, 8007, -1, 165, 8009, 4889, -1, 8007, 8009, 8005, -1, 8008, 8009, 165, -1, 4889, 180, 165, -1, 201, 8010, 203, -1, 203, 8010, 1793, -1, 199, 8011, 201, -1, 201, 8011, 8010, -1, 1793, 7992, 1786, -1, 1786, 7992, 1787, -1, 8010, 7992, 1793, -1, 197, 7998, 199, -1, 199, 7998, 8011, -1, 8010, 7994, 7992, -1, 8011, 7994, 8010, -1, 1787, 7993, 1779, -1, 7992, 7993, 1787, -1, 1779, 7993, 182, -1, 194, 7996, 197, -1, 197, 7996, 7998, -1, 7998, 7999, 8011, -1, 8011, 7999, 7994, -1, 181, 3970, 178, -1, 178, 8012, 173, -1, 3970, 8012, 178, -1, 173, 8013, 170, -1, 8012, 8013, 173, -1, 170, 8014, 158, -1, 8013, 8014, 170, -1, 158, 8015, 156, -1, 8014, 8015, 158, -1, 156, 8016, 175, -1, 8015, 8016, 156, -1, 175, 8017, 176, -1, 8016, 8017, 175, -1, 8017, 1862, 176, -1, 8018, 8019, 1850, -1, 8013, 8020, 8014, -1, 8014, 8020, 8021, -1, 8021, 8022, 8023, -1, 8023, 8022, 8024, -1, 8025, 8026, 8018, -1, 8018, 8026, 8019, -1, 1843, 8027, 1841, -1, 1841, 8027, 1836, -1, 1836, 8027, 8028, -1, 8019, 8027, 1843, -1, 4897, 8029, 3970, -1, 8012, 8029, 8013, -1, 3970, 8029, 8012, -1, 8013, 8029, 8020, -1, 8020, 8030, 8021, -1, 8021, 8030, 8022, -1, 8025, 8031, 8026, -1, 8024, 8031, 8025, -1, 8028, 8032, 8033, -1, 8027, 8032, 8028, -1, 8026, 8032, 8019, -1, 8019, 8032, 8027, -1, 4900, 8034, 4899, -1, 4899, 8034, 4897, -1, 4897, 8034, 8029, -1, 8029, 8034, 8020, -1, 8020, 8034, 8030, -1, 8022, 8035, 8024, -1, 8024, 8035, 8031, -1, 8033, 8036, 8037, -1, 8032, 8036, 8033, -1, 8031, 8036, 8026, -1, 8026, 8036, 8032, -1, 8030, 8038, 8022, -1, 8022, 8038, 8035, -1, 8035, 8039, 8031, -1, 8037, 8039, 8040, -1, 8036, 8039, 8037, -1, 8031, 8039, 8036, -1, 4904, 8041, 4902, -1, 4902, 8041, 4900, -1, 8030, 8041, 8038, -1, 4900, 8041, 8034, -1, 8034, 8041, 8030, -1, 8038, 8042, 8035, -1, 8039, 8042, 8040, -1, 8040, 8042, 8043, -1, 4904, 3967, 8044, -1, 1862, 8045, 1860, -1, 8035, 8042, 8039, -1, 1860, 8045, 1856, -1, 8038, 8046, 8042, -1, 8043, 8046, 8044, -1, 4904, 8046, 8041, -1, 8017, 8045, 1862, -1, 8041, 8046, 8038, -1, 8044, 8046, 4904, -1, 8042, 8046, 8043, -1, 8016, 8047, 8017, -1, 8017, 8047, 8045, -1, 1856, 8018, 1850, -1, 8045, 8018, 1856, -1, 8015, 8023, 8016, -1, 8016, 8023, 8047, -1, 8045, 8025, 8018, -1, 8047, 8025, 8045, -1, 8014, 8021, 8015, -1, 8015, 8021, 8023, -1, 8023, 8024, 8047, -1, 8047, 8024, 8025, -1, 1850, 8019, 1843, -1, 1836, 8028, 1868, -1, 1868, 8028, 8048, -1, 8048, 8033, 8049, -1, 8028, 8033, 8048, -1, 8049, 8037, 8050, -1, 8033, 8037, 8049, -1, 8050, 8040, 8051, -1, 8037, 8040, 8050, -1, 8051, 8043, 8052, -1, 8040, 8043, 8051, -1, 8052, 8044, 8053, -1, 8053, 8044, 3969, -1, 8043, 8044, 8052, -1, 8044, 3967, 3969, -1, 5127, 8053, 3969, -1, 1883, 1880, 2941, -1, 5127, 8052, 8053, -1, 5127, 8051, 8052, -1, 1879, 8049, 8050, -1, 1879, 8048, 8049, -1, 1879, 1868, 8048, -1, 2932, 8054, 2115, -1, 2115, 8054, 5129, -1, 5129, 8054, 5127, -1, 2934, 8055, 2932, -1, 8054, 8055, 5127, -1, 2932, 8055, 8054, -1, 2936, 8056, 2934, -1, 8055, 8056, 5127, -1, 2934, 8056, 8055, -1, 5127, 8056, 8051, -1, 2938, 8057, 2936, -1, 8051, 8057, 8050, -1, 8056, 8057, 8051, -1, 2936, 8057, 8056, -1, 8050, 8057, 1879, -1, 2939, 8058, 2938, -1, 8057, 8058, 1879, -1, 2938, 8058, 8057, -1, 1879, 8059, 1880, -1, 2941, 8059, 2939, -1, 2939, 8059, 8058, -1, 8058, 8059, 1879, -1, 1880, 8059, 2941, -1, 2092, 5109, 2945, -1, 1909, 148, 151, -1, 1909, 146, 148, -1, 5107, 8060, 8061, -1, 5107, 3995, 8060, -1, 1633, 8062, 1908, -1, 1908, 8062, 1909, -1, 1631, 8062, 1633, -1, 1629, 8063, 1631, -1, 8062, 8063, 1909, -1, 1631, 8063, 8062, -1, 1627, 8064, 1629, -1, 1629, 8064, 8063, -1, 1625, 8065, 1627, -1, 1627, 8065, 8064, -1, 1623, 8066, 1625, -1, 1625, 8066, 8065, -1, 2948, 8067, 1623, -1, 1623, 8067, 8066, -1, 5107, 8068, 5109, -1, 2945, 8068, 2948, -1, 2948, 8068, 8067, -1, 5109, 8068, 2945, -1, 8067, 8068, 5107, -1, 146, 8069, 144, -1, 144, 8069, 142, -1, 142, 8069, 140, -1, 140, 8069, 8061, -1, 8063, 8069, 1909, -1, 8064, 8069, 8063, -1, 8067, 8069, 8066, -1, 8065, 8069, 8064, -1, 5107, 8069, 8067, -1, 8066, 8069, 8065, -1, 1909, 8069, 146, -1, 8061, 8069, 5107, -1, 3995, 3993, 8060, -1, 3993, 8070, 8060, -1, 8061, 8071, 140, -1, 8060, 8071, 8061, -1, 8070, 8071, 8060, -1, 8071, 141, 140, -1, 129, 8072, 133, -1, 8073, 8072, 8074, -1, 8074, 8072, 129, -1, 8075, 8072, 8073, -1, 141, 8076, 143, -1, 143, 8076, 8077, -1, 8077, 8078, 8079, -1, 8079, 8078, 8080, -1, 133, 8081, 137, -1, 8075, 8081, 8072, -1, 8072, 8081, 133, -1, 8080, 8081, 8075, -1, 8071, 8082, 141, -1, 141, 8082, 8076, -1, 8077, 8083, 8078, -1, 8076, 8083, 8077, -1, 4960, 8084, 4962, -1, 8070, 8084, 8071, -1, 8071, 8084, 8082, -1, 4962, 8084, 8070, -1, 137, 8085, 139, -1, 8081, 8085, 137, -1, 8078, 8085, 8080, -1, 1926, 129, 131, -1, 8080, 8085, 8081, -1, 8082, 8086, 8076, -1, 8076, 8086, 8083, -1, 139, 8087, 113, -1, 8085, 8087, 139, -1, 8083, 8087, 8078, -1, 8078, 8087, 8085, -1, 3993, 4962, 8070, -1, 4957, 8088, 4960, -1, 4960, 8088, 8084, -1, 8084, 8088, 8082, -1, 8082, 8088, 8086, -1, 113, 8089, 112, -1, 8087, 8089, 113, -1, 8086, 8089, 8083, -1, 8083, 8089, 8087, -1, 4955, 8090, 4957, -1, 8086, 8090, 8089, -1, 4957, 8090, 8088, -1, 112, 8090, 4955, -1, 8088, 8090, 8086, -1, 8089, 8090, 112, -1, 4955, 127, 112, -1, 149, 8091, 150, -1, 150, 8091, 1954, -1, 147, 8092, 149, -1, 149, 8092, 8091, -1, 1954, 8073, 1947, -1, 1947, 8073, 1925, -1, 8091, 8073, 1954, -1, 145, 8079, 147, -1, 147, 8079, 8092, -1, 8091, 8075, 8073, -1, 8092, 8075, 8091, -1, 1925, 8074, 1926, -1, 8073, 8074, 1925, -1, 1926, 8074, 129, -1, 143, 8077, 145, -1, 145, 8077, 8079, -1, 8079, 8080, 8092, -1, 8092, 8080, 8075, -1, 4000, 8093, 128, -1, 128, 8093, 125, -1, 125, 8094, 120, -1, 8093, 8094, 125, -1, 120, 8095, 117, -1, 8094, 8095, 120, -1, 117, 8096, 105, -1, 8095, 8096, 117, -1, 105, 8097, 103, -1, 8096, 8097, 105, -1, 122, 8098, 123, -1, 103, 8098, 122, -1, 8097, 8098, 103, -1, 8098, 1900, 123, -1, 8099, 8100, 1979, -1, 8094, 8101, 8095, -1, 8095, 8101, 8102, -1, 8102, 8103, 8104, -1, 8104, 8103, 8105, -1, 8106, 8107, 8099, -1, 8099, 8107, 8100, -1, 1976, 8108, 1974, -1, 1974, 8108, 1972, -1, 1972, 8108, 8109, -1, 8100, 8108, 1976, -1, 4963, 8110, 4000, -1, 8093, 8110, 8094, -1, 4000, 8110, 8093, -1, 8094, 8110, 8101, -1, 8101, 8111, 8102, -1, 8102, 8111, 8103, -1, 8106, 8112, 8107, -1, 8105, 8112, 8106, -1, 8109, 8113, 8114, -1, 8108, 8113, 8109, -1, 8107, 8113, 8100, -1, 8100, 8113, 8108, -1, 4966, 8115, 4965, -1, 4965, 8115, 4963, -1, 4963, 8115, 8110, -1, 8110, 8115, 8101, -1, 8101, 8115, 8111, -1, 8103, 8116, 8105, -1, 8105, 8116, 8112, -1, 8114, 8117, 8118, -1, 8113, 8117, 8114, -1, 8112, 8117, 8107, -1, 8107, 8117, 8113, -1, 8111, 8119, 8103, -1, 8103, 8119, 8116, -1, 8116, 8120, 8112, -1, 8118, 8120, 8121, -1, 8117, 8120, 8118, -1, 8112, 8120, 8117, -1, 4970, 8122, 4968, -1, 4968, 8122, 4966, -1, 8111, 8122, 8119, -1, 4966, 8122, 8115, -1, 8115, 8122, 8111, -1, 8119, 8123, 8116, -1, 8120, 8123, 8121, -1, 8121, 8123, 8124, -1, 4970, 3997, 8125, -1, 1900, 8126, 1983, -1, 8116, 8123, 8120, -1, 1983, 8126, 1982, -1, 8119, 8127, 8123, -1, 8124, 8127, 8125, -1, 4970, 8127, 8122, -1, 8098, 8126, 1900, -1, 8122, 8127, 8119, -1, 8125, 8127, 4970, -1, 8123, 8127, 8124, -1, 8097, 8128, 8098, -1, 8098, 8128, 8126, -1, 1982, 8099, 1979, -1, 8126, 8099, 1982, -1, 8096, 8104, 8097, -1, 8097, 8104, 8128, -1, 8126, 8106, 8099, -1, 8128, 8106, 8126, -1, 8095, 8102, 8096, -1, 8096, 8102, 8104, -1, 8104, 8105, 8128, -1, 8128, 8105, 8106, -1, 1979, 8100, 1976, -1, 1972, 8109, 1985, -1, 1985, 8109, 8129, -1, 8129, 8114, 8130, -1, 8109, 8114, 8129, -1, 8130, 8118, 8131, -1, 8114, 8118, 8130, -1, 8131, 8121, 8132, -1, 8118, 8121, 8131, -1, 8132, 8124, 8133, -1, 8121, 8124, 8132, -1, 8133, 8125, 8134, -1, 8134, 8125, 3999, -1, 8124, 8125, 8133, -1, 8125, 3997, 3999, -1, 5103, 8134, 3999, -1, 1911, 1989, 2959, -1, 5103, 8133, 8134, -1, 5103, 8132, 8133, -1, 1988, 8130, 8131, -1, 1988, 8129, 8130, -1, 1988, 1985, 8129, -1, 2950, 8135, 2088, -1, 2088, 8135, 5105, -1, 5105, 8135, 5103, -1, 2952, 8136, 2950, -1, 8135, 8136, 5103, -1, 2950, 8136, 8135, -1, 2954, 8137, 2952, -1, 8136, 8137, 5103, -1, 2952, 8137, 8136, -1, 5103, 8137, 8132, -1, 2956, 8138, 2954, -1, 8132, 8138, 8131, -1, 8137, 8138, 8132, -1, 2954, 8138, 8137, -1, 8131, 8138, 1988, -1, 2959, 8139, 2957, -1, 2957, 8139, 2956, -1, 8138, 8139, 1988, -1, 2956, 8139, 8138, -1, 1988, 8140, 1989, -1, 8139, 8140, 1988, -1, 1989, 8140, 2959, -1, 2959, 8140, 8139, -1, 3908, 8141, 3909, -1, 3909, 8141, 5847, -1, 5847, 8142, 81, -1, 8141, 8142, 5847, -1, 8142, 82, 81, -1, 3908, 5100, 8141, -1, 1902, 78, 80, -1, 1902, 76, 78, -1, 5098, 8143, 8144, -1, 5098, 3580, 8143, -1, 97, 8145, 1957, -1, 1957, 8145, 1902, -1, 93, 8145, 97, -1, 90, 8146, 93, -1, 8145, 8146, 1902, -1, 93, 8146, 8145, -1, 86, 8147, 90, -1, 90, 8147, 8146, -1, 84, 8148, 86, -1, 86, 8148, 8147, -1, 82, 8149, 84, -1, 84, 8149, 8148, -1, 8142, 8150, 82, -1, 82, 8150, 8149, -1, 5098, 8151, 5100, -1, 8141, 8151, 8142, -1, 8142, 8151, 8150, -1, 5100, 8151, 8141, -1, 8150, 8151, 5098, -1, 76, 8152, 74, -1, 74, 8152, 72, -1, 72, 8152, 71, -1, 71, 8152, 8144, -1, 8146, 8152, 1902, -1, 8147, 8152, 8146, -1, 8150, 8152, 8149, -1, 8148, 8152, 8147, -1, 5098, 8152, 8150, -1, 8149, 8152, 8148, -1, 1902, 8152, 76, -1, 8144, 8152, 5098, -1, 3580, 3582, 8143, -1, 8143, 8153, 8144, -1, 3582, 8153, 8143, -1, 8144, 8154, 71, -1, 8153, 8154, 8144, -1, 8154, 69, 71, -1, 8155, 8156, 8157, -1, 8158, 8159, 8160, -1, 75, 8161, 8162, -1, 8160, 8159, 8163, -1, 8164, 8165, 8166, -1, 8167, 8168, 8169, -1, 8162, 8168, 8167, -1, 8163, 8165, 8164, -1, 1848, 8170, 1840, -1, 1840, 8170, 1846, -1, 8169, 8170, 1848, -1, 8171, 8172, 8173, -1, 8173, 8172, 8174, -1, 70, 8175, 73, -1, 8166, 8176, 8155, -1, 73, 8175, 8161, -1, 8155, 8176, 8156, -1, 8162, 8177, 8168, -1, 4982, 8178, 4980, -1, 8158, 8178, 8159, -1, 4980, 8178, 8179, -1, 8161, 8177, 8162, -1, 8179, 8178, 8158, -1, 8174, 8180, 1857, -1, 1857, 8180, 1859, -1, 1859, 8180, 8181, -1, 8168, 8182, 8169, -1, 8169, 8182, 8170, -1, 8159, 8183, 8163, -1, 8163, 8183, 8165, -1, 8170, 8184, 1846, -1, 8156, 8185, 8171, -1, 8171, 8185, 8172, -1, 69, 8186, 70, -1, 8166, 8187, 8176, -1, 8165, 8187, 8166, -1, 70, 8186, 8175, -1, 8181, 8188, 8189, -1, 3582, 4977, 8153, -1, 8161, 8190, 8177, -1, 8172, 8188, 8174, -1, 8180, 8188, 8181, -1, 8175, 8190, 8161, -1, 8174, 8188, 8180, -1, 4983, 8191, 4982, -1, 8177, 8192, 8168, -1, 4982, 8191, 8178, -1, 8178, 8191, 8159, -1, 8159, 8191, 8183, -1, 8168, 8192, 8182, -1, 8183, 8193, 8165, -1, 8154, 8194, 69, -1, 8165, 8193, 8187, -1, 69, 8194, 8186, -1, 8156, 8195, 8185, -1, 8176, 8195, 8156, -1, 8182, 8157, 8170, -1, 8189, 8196, 8197, -1, 8170, 8157, 8184, -1, 8185, 8196, 8172, -1, 8188, 8196, 8189, -1, 1846, 8173, 1849, -1, 8172, 8196, 8188, -1, 1849, 8173, 1855, -1, 4984, 8198, 4983, -1, 4983, 8198, 8191, -1, 8191, 8198, 8183, -1, 8184, 8173, 1846, -1, 8183, 8198, 8193, -1, 8187, 8199, 8176, -1, 8186, 8160, 8175, -1, 1859, 8181, 1861, -1, 8175, 8160, 8190, -1, 8176, 8199, 8195, -1, 8197, 8200, 8201, -1, 8190, 8164, 8177, -1, 8185, 8200, 8196, -1, 8196, 8200, 8197, -1, 8177, 8164, 8192, -1, 8195, 8200, 8185, -1, 4979, 8202, 4977, -1, 8153, 8202, 8154, -1, 8187, 8203, 8199, -1, 4977, 8202, 8153, -1, 8193, 8203, 8187, -1, 8154, 8202, 8194, -1, 8182, 8155, 8157, -1, 8201, 8204, 8205, -1, 8200, 8204, 8201, -1, 8199, 8204, 8195, -1, 8192, 8155, 8182, -1, 8195, 8204, 8200, -1, 8194, 8158, 8186, -1, 4984, 8206, 8198, -1, 8198, 8206, 8193, -1, 8193, 8206, 8203, -1, 8186, 8158, 8160, -1, 8157, 8171, 8184, -1, 8205, 8207, 8208, -1, 8204, 8207, 8205, -1, 8203, 8207, 8199, -1, 8199, 8207, 8204, -1, 8184, 8171, 8173, -1, 8206, 8209, 8203, -1, 8208, 8209, 3533, -1, 3533, 8209, 4985, -1, 4985, 8209, 4984, -1, 4984, 8209, 8206, -1, 8203, 8209, 8207, -1, 8160, 8163, 8190, -1, 8207, 8209, 8208, -1, 8190, 8163, 8164, -1, 79, 8167, 1853, -1, 8164, 8166, 8192, -1, 1853, 8167, 1848, -1, 8192, 8166, 8155, -1, 77, 8167, 79, -1, 4979, 8179, 8202, -1, 4980, 8179, 4979, -1, 75, 8162, 77, -1, 8202, 8179, 8194, -1, 8194, 8179, 8158, -1, 1855, 8174, 1857, -1, 77, 8162, 8167, -1, 8173, 8174, 1855, -1, 8167, 8169, 1848, -1, 8157, 8156, 8171, -1, 73, 8161, 75, -1, 1864, 1861, 8210, -1, 1861, 8181, 8210, -1, 8210, 8189, 8211, -1, 8181, 8189, 8210, -1, 8211, 8197, 8212, -1, 8189, 8197, 8211, -1, 8212, 8201, 8213, -1, 8197, 8201, 8212, -1, 8213, 8205, 8214, -1, 8201, 8205, 8213, -1, 8214, 8208, 8215, -1, 8215, 8208, 3531, -1, 8205, 8208, 8214, -1, 8208, 3533, 3531, -1, 8216, 8217, 1952, -1, 8214, 8218, 8213, -1, 8213, 8218, 8219, -1, 8219, 8220, 8221, -1, 8221, 8220, 8222, -1, 8223, 8224, 8216, -1, 8216, 8224, 8217, -1, 1940, 8225, 1930, -1, 1930, 8225, 1903, -1, 1903, 8225, 8226, -1, 8217, 8225, 1940, -1, 4976, 8227, 3531, -1, 8215, 8227, 8214, -1, 3531, 8227, 8215, -1, 8214, 8227, 8218, -1, 8218, 8228, 8219, -1, 8219, 8228, 8220, -1, 8223, 8229, 8224, -1, 8222, 8229, 8223, -1, 8226, 8230, 8231, -1, 8225, 8230, 8226, -1, 8224, 8230, 8217, -1, 8217, 8230, 8225, -1, 4974, 8232, 4975, -1, 4975, 8232, 4976, -1, 4976, 8232, 8227, -1, 8227, 8232, 8218, -1, 8218, 8232, 8228, -1, 8220, 8233, 8222, -1, 8222, 8233, 8229, -1, 8231, 8234, 8235, -1, 8230, 8234, 8231, -1, 8229, 8234, 8224, -1, 8224, 8234, 8230, -1, 8228, 8236, 8220, -1, 8220, 8236, 8233, -1, 8233, 8237, 8229, -1, 8235, 8237, 8238, -1, 8234, 8237, 8235, -1, 8229, 8237, 8234, -1, 4972, 8239, 4973, -1, 4973, 8239, 4974, -1, 8228, 8239, 8236, -1, 4974, 8239, 8232, -1, 8232, 8239, 8228, -1, 8236, 8240, 8233, -1, 8237, 8240, 8238, -1, 8238, 8240, 8241, -1, 4972, 4005, 8242, -1, 1864, 8243, 1958, -1, 8233, 8240, 8237, -1, 1958, 8243, 1955, -1, 8236, 8244, 8240, -1, 8241, 8244, 8242, -1, 4972, 8244, 8239, -1, 8210, 8243, 1864, -1, 8239, 8244, 8236, -1, 8242, 8244, 4972, -1, 8240, 8244, 8241, -1, 8211, 8245, 8210, -1, 8210, 8245, 8243, -1, 1955, 8216, 1952, -1, 8243, 8216, 1955, -1, 8212, 8221, 8211, -1, 8211, 8221, 8245, -1, 8243, 8223, 8216, -1, 8245, 8223, 8243, -1, 8213, 8219, 8212, -1, 8212, 8219, 8221, -1, 8221, 8222, 8245, -1, 8245, 8222, 8223, -1, 1952, 8217, 1940, -1, 1903, 8226, 1904, -1, 1904, 8226, 8246, -1, 8246, 8231, 8247, -1, 8226, 8231, 8246, -1, 8247, 8235, 8248, -1, 8231, 8235, 8247, -1, 8248, 8238, 8249, -1, 8235, 8238, 8248, -1, 8249, 8241, 8250, -1, 8238, 8241, 8249, -1, 8250, 8242, 8251, -1, 8251, 8242, 4006, -1, 8241, 8242, 8250, -1, 8242, 4005, 4006, -1, 5094, 8251, 4006, -1, 1906, 1963, 2973, -1, 5094, 8250, 8251, -1, 5094, 8249, 8250, -1, 1962, 8247, 8248, -1, 1962, 8246, 8247, -1, 1962, 1904, 8246, -1, 2964, 8252, 2080, -1, 2080, 8252, 5096, -1, 5096, 8252, 5094, -1, 2966, 8253, 2964, -1, 8252, 8253, 5094, -1, 2964, 8253, 8252, -1, 2968, 8254, 2966, -1, 8253, 8254, 5094, -1, 2966, 8254, 8253, -1, 5094, 8254, 8249, -1, 2970, 8255, 2968, -1, 8249, 8255, 8248, -1, 8254, 8255, 8249, -1, 2968, 8255, 8254, -1, 8248, 8255, 1962, -1, 2971, 8256, 2970, -1, 8255, 8256, 1962, -1, 2970, 8256, 8255, -1, 1962, 8257, 1963, -1, 2973, 8257, 2971, -1, 2971, 8257, 8256, -1, 8256, 8257, 1962, -1, 1963, 8257, 2973, -1, 5111, 8258, 3989, -1, 1917, 2015, 2990, -1, 5111, 8259, 8258, -1, 5111, 8260, 8259, -1, 2014, 8261, 8262, -1, 2014, 8263, 8261, -1, 2014, 2011, 8263, -1, 2097, 8264, 5113, -1, 5113, 8264, 5111, -1, 2981, 8264, 2097, -1, 2983, 8265, 2981, -1, 8264, 8265, 5111, -1, 2981, 8265, 8264, -1, 2985, 8266, 2983, -1, 8265, 8266, 5111, -1, 2983, 8266, 8265, -1, 5111, 8266, 8260, -1, 8260, 8267, 8262, -1, 2987, 8267, 2985, -1, 8266, 8267, 8260, -1, 2985, 8267, 8266, -1, 8262, 8267, 2014, -1, 2989, 8268, 2987, -1, 8267, 8268, 2014, -1, 2987, 8268, 8267, -1, 2014, 8269, 2015, -1, 2990, 8269, 2989, -1, 2989, 8269, 8268, -1, 2015, 8269, 2990, -1, 8268, 8269, 2014, -1, 1996, 8270, 2011, -1, 2011, 8270, 8263, -1, 8263, 8271, 8261, -1, 8270, 8271, 8263, -1, 8261, 8272, 8262, -1, 8271, 8272, 8261, -1, 8262, 8273, 8260, -1, 8272, 8273, 8262, -1, 8260, 8274, 8259, -1, 8273, 8274, 8260, -1, 8259, 8275, 8258, -1, 8274, 8275, 8259, -1, 8258, 3987, 3989, -1, 8275, 3987, 8258, -1, 8276, 8277, 2005, -1, 8278, 8279, 8280, -1, 8280, 8279, 8281, -1, 8281, 8282, 8283, -1, 8283, 8282, 8284, -1, 8276, 8285, 8277, -1, 8286, 8285, 8276, -1, 2001, 8287, 1998, -1, 1998, 8287, 1996, -1, 1996, 8287, 8270, -1, 8277, 8287, 2001, -1, 4928, 8288, 3990, -1, 3990, 8288, 8289, -1, 8289, 8288, 8278, -1, 8278, 8288, 8279, -1, 8281, 8290, 8282, -1, 8279, 8290, 8281, -1, 8286, 8291, 8285, -1, 8284, 8291, 8286, -1, 8271, 8292, 8272, -1, 8270, 8292, 8271, -1, 8287, 8292, 8270, -1, 8285, 8292, 8277, -1, 8277, 8292, 8287, -1, 4931, 8293, 4930, -1, 4930, 8293, 4928, -1, 4928, 8293, 8288, -1, 8288, 8293, 8279, -1, 8279, 8293, 8290, -1, 8282, 8294, 8284, -1, 8284, 8294, 8291, -1, 8291, 8295, 8285, -1, 8292, 8295, 8272, -1, 8285, 8295, 8292, -1, 8282, 8296, 8294, -1, 8290, 8296, 8282, -1, 8272, 8297, 8273, -1, 8291, 8297, 8295, -1, 8295, 8297, 8272, -1, 8294, 8297, 8291, -1, 4935, 8298, 4933, -1, 4933, 8298, 4931, -1, 8290, 8298, 8296, -1, 4931, 8298, 8293, -1, 8293, 8298, 8290, -1, 8297, 8299, 8273, -1, 8296, 8299, 8294, -1, 8273, 8299, 8274, -1, 8294, 8299, 8297, -1, 4935, 3987, 8275, -1, 4935, 8300, 8298, -1, 8299, 8300, 8274, -1, 8274, 8300, 8275, -1, 8275, 8300, 4935, -1, 8296, 8300, 8299, -1, 8301, 8302, 1898, -1, 8298, 8300, 8296, -1, 1898, 8302, 2009, -1, 2009, 8302, 2008, -1, 8303, 8304, 8301, -1, 8301, 8304, 8302, -1, 2008, 8276, 2005, -1, 8302, 8276, 2008, -1, 8305, 8283, 8303, -1, 8303, 8283, 8304, -1, 8302, 8286, 8276, -1, 8304, 8286, 8302, -1, 8280, 8281, 8305, -1, 8305, 8281, 8283, -1, 8283, 8284, 8304, -1, 8304, 8284, 8286, -1, 2005, 8277, 2001, -1, 57, 3990, 54, -1, 3990, 8289, 54, -1, 54, 8278, 49, -1, 8289, 8278, 54, -1, 49, 8280, 46, -1, 8278, 8280, 49, -1, 46, 8305, 34, -1, 34, 8305, 32, -1, 8280, 8305, 46, -1, 32, 8303, 51, -1, 8305, 8303, 32, -1, 8303, 8301, 51, -1, 51, 1898, 52, -1, 8301, 1898, 51, -1, 58, 8306, 62, -1, 8307, 8306, 8308, -1, 8308, 8306, 58, -1, 8309, 8306, 8307, -1, 16, 8310, 17, -1, 17, 8310, 8311, -1, 8311, 8312, 8313, -1, 8313, 8312, 8314, -1, 62, 8315, 66, -1, 8306, 8315, 62, -1, 8314, 8315, 8309, -1, 8309, 8315, 8306, -1, 8316, 8317, 16, -1, 16, 8317, 8310, -1, 8311, 8318, 8312, -1, 8310, 8318, 8311, -1, 4947, 8319, 4949, -1, 8320, 8319, 8316, -1, 8316, 8319, 8317, -1, 4949, 8319, 8320, -1, 66, 8321, 68, -1, 8315, 8321, 66, -1, 8312, 8321, 8314, -1, 1971, 58, 60, -1, 8314, 8321, 8315, -1, 8317, 8322, 8310, -1, 8310, 8322, 8318, -1, 68, 8323, 42, -1, 8321, 8323, 68, -1, 8318, 8323, 8312, -1, 8312, 8323, 8321, -1, 3983, 4949, 8320, -1, 4944, 8324, 4947, -1, 4947, 8324, 8319, -1, 8319, 8324, 8317, -1, 8317, 8324, 8322, -1, 42, 8325, 41, -1, 8323, 8325, 42, -1, 8322, 8325, 8318, -1, 8318, 8325, 8323, -1, 4942, 8326, 4944, -1, 8322, 8326, 8325, -1, 4944, 8326, 8324, -1, 41, 8326, 4942, -1, 8324, 8326, 8322, -1, 8325, 8326, 41, -1, 4942, 56, 41, -1, 24, 8327, 26, -1, 26, 8327, 1980, -1, 22, 8328, 24, -1, 24, 8328, 8327, -1, 1980, 8307, 1977, -1, 1977, 8307, 1970, -1, 8327, 8307, 1980, -1, 20, 8313, 22, -1, 22, 8313, 8328, -1, 8327, 8309, 8307, -1, 8328, 8309, 8327, -1, 1970, 8308, 1971, -1, 8307, 8308, 1970, -1, 1971, 8308, 58, -1, 17, 8311, 20, -1, 20, 8311, 8313, -1, 8313, 8314, 8328, -1, 8328, 8314, 8309, -1, 3983, 8320, 3985, -1, 3985, 8320, 8329, -1, 8329, 8320, 8330, -1, 8330, 8316, 18, -1, 8320, 8316, 8330, -1, 8316, 16, 18, -1, 2101, 5117, 2991, -1, 1915, 25, 27, -1, 1915, 23, 25, -1, 5115, 8329, 8330, -1, 5115, 3985, 8329, -1, 1618, 8331, 1620, -1, 1620, 8331, 1913, -1, 1913, 8331, 1915, -1, 1616, 8332, 1618, -1, 8331, 8332, 1915, -1, 1618, 8332, 8331, -1, 1614, 8333, 1616, -1, 1616, 8333, 8332, -1, 1612, 8334, 1614, -1, 1614, 8334, 8333, -1, 1610, 8335, 1612, -1, 1612, 8335, 8334, -1, 2994, 8336, 1610, -1, 1610, 8336, 8335, -1, 5115, 8337, 5117, -1, 2991, 8337, 2994, -1, 2994, 8337, 8336, -1, 5117, 8337, 2991, -1, 8336, 8337, 5115, -1, 19, 8338, 18, -1, 21, 8338, 19, -1, 23, 8338, 21, -1, 18, 8338, 8330, -1, 8333, 8338, 8332, -1, 8334, 8338, 8333, -1, 8336, 8338, 8335, -1, 8335, 8338, 8334, -1, 1915, 8338, 23, -1, 5115, 8338, 8336, -1, 8332, 8338, 1915, -1, 8330, 8338, 5115, -1, 4069, 4068, 8339, -1, 8340, 8341, 8342, -1, 8340, 8343, 8341, -1, 8340, 8339, 8343, -1, 8340, 4069, 8339, -1, 8344, 8345, 8346, -1, 8344, 8347, 8345, -1, 8344, 8348, 8347, -1, 8344, 8342, 8348, -1, 8344, 8340, 8342, -1, 8349, 8350, 8351, -1, 8349, 8346, 8350, -1, 8349, 8344, 8346, -1, 8352, 8353, 8354, -1, 8352, 8351, 8353, -1, 8352, 8349, 8351, -1, 8355, 8352, 8354, -1, 8356, 8354, 4075, -1, 8356, 8355, 8354, -1, 4074, 8356, 4075, -1, 8357, 8358, 8359, -1, 8360, 8344, 8349, -1, 8360, 8349, 8361, -1, 8362, 8363, 8364, -1, 8362, 8361, 8363, -1, 8365, 11, 9, -1, 8365, 8358, 8357, -1, 8365, 8364, 8358, -1, 8365, 8357, 11, -1, 8366, 8340, 8344, -1, 8366, 8344, 8360, -1, 8366, 4183, 8340, -1, 8367, 8360, 8361, -1, 8367, 8361, 8362, -1, 8368, 9, 7, -1, 8368, 8365, 9, -1, 8368, 8362, 8364, -1, 15, 4121, 4120, -1, 8368, 8364, 8365, -1, 8369, 4185, 4183, -1, 8369, 8360, 8367, -1, 8369, 4183, 8366, -1, 8369, 8366, 8360, -1, 8370, 7, 5, -1, 8370, 8368, 7, -1, 8370, 8367, 8362, -1, 8370, 8362, 8368, -1, 8371, 5, 2, -1, 8371, 4187, 4185, -1, 8371, 4185, 8369, -1, 8371, 2, 4187, -1, 8371, 8370, 5, -1, 8371, 8369, 8367, -1, 8371, 8367, 8370, -1, 4183, 4069, 8340, -1, 1, 4187, 2, -1, 8372, 8356, 4074, -1, 8372, 4074, 4126, -1, 8373, 8355, 8356, -1, 8373, 8356, 8372, -1, 8359, 4126, 4123, -1, 8359, 8372, 4126, -1, 8363, 8352, 8355, -1, 8363, 8355, 8373, -1, 8358, 8372, 8359, -1, 8358, 8373, 8372, -1, 8374, 4123, 4121, -1, 8374, 15, 13, -1, 8374, 4121, 15, -1, 8374, 8359, 4123, -1, 8361, 8349, 8352, -1, 8361, 8352, 8363, -1, 8364, 8363, 8373, -1, 8364, 8373, 8358, -1, 8357, 13, 11, -1, 8357, 8359, 8374, -1, 8357, 8374, 13, -1, 4105, 15, 4120, -1, 4105, 14, 15, -1, 8375, 6, 8, -1, 8376, 8377, 8378, -1, 8375, 8, 8379, -1, 8380, 8381, 8382, -1, 8380, 8383, 8384, -1, 8385, 8379, 8386, -1, 8380, 8378, 8381, -1, 8380, 8382, 8383, -1, 8387, 4139, 8388, -1, 8387, 4137, 4139, -1, 8385, 8386, 8389, -1, 8387, 8388, 8390, -1, 8387, 8390, 8376, -1, 4089, 14, 4105, -1, 8391, 8384, 8392, -1, 8391, 8380, 8384, -1, 8393, 8389, 8394, -1, 8391, 8378, 8380, -1, 8391, 8376, 8378, -1, 8393, 8394, 8395, -1, 8396, 8392, 4134, -1, 8396, 4135, 4137, -1, 8396, 4134, 4135, -1, 8397, 4079, 4083, -1, 8396, 8391, 8392, -1, 8396, 4137, 8387, -1, 8396, 8387, 8376, -1, 8396, 8376, 8391, -1, 8397, 8395, 4079, -1, 8398, 4, 6, -1, 8398, 6, 8375, -1, 8399, 8379, 8385, -1, 8399, 8375, 8379, -1, 8400, 8389, 8393, -1, 8400, 8385, 8389, -1, 8401, 8393, 8395, -1, 8401, 8395, 8397, -1, 4145, 3, 0, -1, 8402, 0, 4, -1, 8402, 4, 8398, -1, 8402, 4145, 0, -1, 8403, 4083, 4085, -1, 8403, 8397, 4083, -1, 8404, 8398, 8375, -1, 8404, 8375, 8399, -1, 8405, 8399, 8385, -1, 8405, 8385, 8400, -1, 8406, 8393, 8401, -1, 8406, 8400, 8393, -1, 8407, 8397, 8403, -1, 8407, 8401, 8397, -1, 8408, 4143, 4145, -1, 8408, 8398, 8404, -1, 8408, 4145, 8402, -1, 8408, 8402, 8398, -1, 8409, 4091, 4103, -1, 8409, 4085, 4091, -1, 8409, 8410, 8411, -1, 8409, 4103, 8410, -1, 8409, 8403, 4085, -1, 8412, 8404, 8399, -1, 8412, 8399, 8405, -1, 8377, 8405, 8400, -1, 8377, 8400, 8406, -1, 8413, 12, 14, -1, 8381, 8406, 8401, -1, 8413, 14, 4089, -1, 8381, 8401, 8407, -1, 8386, 10, 12, -1, 8414, 8403, 8409, -1, 8414, 8411, 8415, -1, 8414, 8407, 8403, -1, 8414, 8409, 8411, -1, 8386, 12, 8413, -1, 8416, 8408, 8404, -1, 8416, 4141, 4143, -1, 8416, 4139, 4141, -1, 8394, 4089, 4087, -1, 8416, 8404, 8412, -1, 8416, 4143, 8408, -1, 8390, 8405, 8377, -1, 8394, 8413, 4089, -1, 8390, 8412, 8405, -1, 8379, 8, 10, -1, 8378, 8377, 8406, -1, 8379, 10, 8386, -1, 8378, 8406, 8381, -1, 8389, 8413, 8394, -1, 8382, 8381, 8407, -1, 8389, 8386, 8413, -1, 8382, 8407, 8414, -1, 8382, 8415, 8383, -1, 8382, 8414, 8415, -1, 8388, 4139, 8416, -1, 8395, 4087, 4079, -1, 8388, 8416, 8412, -1, 8388, 8412, 8390, -1, 8395, 8394, 4087, -1, 8376, 8390, 8377, -1, 8417, 4134, 8392, -1, 8417, 4147, 4134, -1, 8418, 8392, 8384, -1, 8418, 8417, 8392, -1, 8419, 8384, 8383, -1, 8419, 8418, 8384, -1, 8420, 8383, 8415, -1, 8420, 8419, 8383, -1, 8421, 8415, 8411, -1, 8421, 8420, 8415, -1, 8422, 8411, 8410, -1, 8422, 8421, 8411, -1, 4107, 8410, 4103, -1, 4107, 8422, 8410, -1, 8423, 8424, 8425, -1, 8423, 4118, 8424, -1, 8423, 8426, 4116, -1, 8427, 8418, 8419, -1, 8427, 8419, 8428, -1, 8429, 8430, 8431, -1, 8429, 8428, 8430, -1, 8432, 8433, 8434, -1, 8432, 8431, 8433, -1, 8435, 8425, 8436, -1, 8435, 8426, 8423, -1, 8435, 8434, 8426, -1, 8435, 8423, 8425, -1, 8437, 8417, 8418, -1, 8437, 4743, 4741, -1, 8437, 8418, 8427, -1, 8437, 4741, 8417, -1, 8438, 8427, 8428, -1, 8438, 8428, 8429, -1, 8439, 8429, 8431, -1, 8439, 8431, 8432, -1, 8424, 4118, 4077, -1, 8440, 8436, 8441, -1, 8440, 8435, 8436, -1, 8440, 8432, 8434, -1, 8440, 8434, 8435, -1, 8442, 4745, 4743, -1, 8442, 4743, 8437, -1, 8442, 8437, 8427, -1, 8442, 8427, 8438, -1, 4741, 4147, 8417, -1, 8443, 8429, 8439, -1, 8443, 8438, 8429, -1, 8444, 8441, 8445, -1, 8444, 8440, 8441, -1, 8444, 8439, 8432, -1, 8444, 8432, 8440, -1, 8446, 8442, 8438, -1, 8446, 4747, 4745, -1, 8446, 4745, 8442, -1, 8446, 8438, 8443, -1, 8447, 8443, 8439, -1, 8447, 8444, 8445, -1, 8447, 8445, 8448, -1, 8447, 8439, 8444, -1, 8449, 8446, 8443, -1, 8449, 8447, 8448, -1, 8449, 8448, 4127, -1, 8449, 4127, 4747, -1, 8449, 8443, 8447, -1, 8449, 4747, 8446, -1, 8450, 8422, 4107, -1, 8450, 4107, 4110, -1, 8451, 8421, 8422, -1, 8451, 8422, 8450, -1, 8452, 4110, 4112, -1, 8452, 8450, 4110, -1, 8430, 8420, 8421, -1, 8430, 8421, 8451, -1, 8433, 8450, 8452, -1, 8433, 8451, 8450, -1, 8426, 4112, 4116, -1, 8426, 8452, 4112, -1, 8428, 8419, 8420, -1, 8428, 8420, 8430, -1, 8431, 8430, 8451, -1, 8431, 8451, 8433, -1, 8434, 8433, 8452, -1, 8434, 8452, 8426, -1, 8423, 4116, 4118, -1, 4129, 4127, 8448, -1, 5855, 8448, 8445, -1, 5855, 4129, 8448, -1, 5856, 8445, 8441, -1, 5856, 5855, 8445, -1, 5854, 8441, 8436, -1, 5854, 5856, 8441, -1, 5853, 8436, 8425, -1, 5853, 5854, 8436, -1, 5852, 8425, 8424, -1, 5852, 5853, 8425, -1, 5851, 5852, 8424, -1, 5850, 8424, 4077, -1, 5850, 5851, 8424, -1, 4100, 5850, 4077, -1, 8453, 8454, 8455, -1, 6048, 8454, 8453, -1, 8456, 8454, 3524, -1, 8457, 8458, 3527, -1, 8353, 8459, 8460, -1, 8461, 8458, 8457, -1, 3527, 8458, 3526, -1, 8461, 8462, 8458, -1, 3526, 8462, 3525, -1, 3525, 8462, 3524, -1, 8463, 8462, 8461, -1, 8456, 8462, 8463, -1, 8460, 8464, 8465, -1, 8458, 8462, 3526, -1, 8459, 8464, 8460, -1, 3524, 8462, 8456, -1, 8350, 8466, 8351, -1, 8351, 8466, 8459, -1, 3534, 8467, 3530, -1, 8464, 8467, 8465, -1, 8468, 8467, 3534, -1, 8465, 8467, 8468, -1, 4075, 8354, 8469, -1, 8459, 8470, 8464, -1, 8466, 8470, 8459, -1, 8469, 3535, 8471, -1, 8471, 3535, 8472, -1, 8346, 8473, 8350, -1, 8472, 3535, 8474, -1, 8474, 3535, 8475, -1, 8475, 3535, 3532, -1, 8350, 8473, 8466, -1, 3530, 8476, 3529, -1, 8470, 8476, 8464, -1, 8467, 8476, 3530, -1, 8464, 8476, 8467, -1, 8346, 8477, 8473, -1, 8345, 8477, 8346, -1, 8473, 8478, 8466, -1, 8466, 8478, 8470, -1, 8347, 8479, 8345, -1, 8345, 8479, 8477, -1, 8477, 8480, 8473, -1, 8473, 8480, 8478, -1, 3529, 8481, 3528, -1, 8478, 8481, 8470, -1, 8470, 8481, 8476, -1, 8476, 8481, 3529, -1, 8477, 8482, 8480, -1, 8479, 8482, 8477, -1, 8348, 8483, 8347, -1, 8342, 8483, 8348, -1, 8347, 8483, 8479, -1, 8480, 8484, 8478, -1, 3528, 8484, 3527, -1, 8481, 8484, 3528, -1, 8478, 8484, 8481, -1, 8482, 8457, 8480, -1, 8480, 8457, 8484, -1, 8484, 8457, 3527, -1, 8341, 8485, 8342, -1, 8343, 8485, 8341, -1, 8342, 8485, 8483, -1, 8479, 8486, 8482, -1, 8483, 8486, 8479, -1, 4068, 6045, 8339, -1, 8343, 8487, 8485, -1, 8339, 8487, 8343, -1, 8339, 8488, 8487, -1, 6045, 8488, 8339, -1, 8485, 8489, 8483, -1, 8483, 8489, 8486, -1, 8482, 8461, 8457, -1, 8486, 8461, 8482, -1, 8487, 8455, 8485, -1, 8485, 8455, 8489, -1, 8488, 8453, 8487, -1, 6048, 3520, 3523, -1, 6045, 8453, 8488, -1, 8487, 8453, 8455, -1, 6048, 8453, 6045, -1, 8353, 8460, 8354, -1, 8354, 8460, 8469, -1, 8489, 8463, 8486, -1, 8469, 8460, 3535, -1, 8486, 8463, 8461, -1, 8455, 8456, 8489, -1, 8460, 8465, 3535, -1, 3535, 8468, 3534, -1, 8465, 8468, 3535, -1, 8489, 8456, 8463, -1, 8351, 8459, 8353, -1, 3523, 8454, 6048, -1, 8455, 8454, 8456, -1, 3524, 8454, 3523, -1, 4075, 8469, 3042, -1, 3042, 8469, 3043, -1, 3043, 8471, 3044, -1, 8469, 8471, 3043, -1, 3044, 8472, 3045, -1, 8471, 8472, 3044, -1, 3045, 8474, 3046, -1, 8472, 8474, 3045, -1, 3046, 8475, 3047, -1, 8474, 8475, 3046, -1, 8475, 3532, 3047, -1, 4036, 4039, 8490, -1, 8491, 8492, 3581, -1, 3581, 8492, 4978, -1, 8491, 8493, 8492, -1, 8494, 8495, 8491, -1, 8491, 8495, 8493, -1, 4978, 8496, 4981, -1, 4981, 8496, 3085, -1, 3084, 8496, 3078, -1, 3085, 8496, 3084, -1, 8492, 8496, 4978, -1, 8497, 8498, 8494, -1, 8494, 8498, 8495, -1, 8490, 8499, 8497, -1, 4039, 8499, 8490, -1, 8497, 8499, 8498, -1, 3078, 8500, 3073, -1, 8492, 8500, 8496, -1, 8493, 8500, 8492, -1, 8496, 8500, 3078, -1, 4041, 8501, 4039, -1, 4039, 8501, 8499, -1, 3073, 8502, 3064, -1, 8500, 8502, 3073, -1, 8493, 8502, 8500, -1, 8495, 8502, 8493, -1, 3056, 8503, 3054, -1, 3064, 8503, 3056, -1, 8495, 8503, 8502, -1, 8502, 8503, 3064, -1, 8498, 8503, 8495, -1, 3054, 8504, 3096, -1, 8503, 8504, 3054, -1, 8499, 8504, 8498, -1, 8498, 8504, 8503, -1, 3059, 8505, 4041, -1, 3058, 8505, 3059, -1, 3096, 8505, 3058, -1, 8501, 8505, 8499, -1, 4041, 8505, 8501, -1, 8504, 8505, 3096, -1, 8499, 8505, 8504, -1, 4037, 4036, 8506, -1, 8506, 8490, 8507, -1, 4036, 8490, 8506, -1, 8507, 8497, 8508, -1, 8490, 8497, 8507, -1, 8508, 8494, 8509, -1, 8497, 8494, 8508, -1, 8509, 8491, 3589, -1, 8494, 8491, 8509, -1, 8491, 3581, 3589, -1, 8506, 6023, 4037, -1, 8507, 6023, 8506, -1, 8508, 6023, 8507, -1, 6025, 8510, 6026, -1, 6023, 8511, 6024, -1, 6023, 8512, 8511, -1, 8509, 8513, 8508, -1, 8508, 8513, 6023, -1, 6023, 8513, 8512, -1, 8512, 8513, 3587, -1, 3589, 3588, 8509, -1, 8513, 3588, 3587, -1, 8509, 3588, 8513, -1, 8511, 8514, 6024, -1, 8512, 8515, 8511, -1, 8511, 8515, 8514, -1, 3587, 8515, 8512, -1, 6024, 8516, 6025, -1, 8514, 8516, 6024, -1, 6025, 8516, 8510, -1, 3587, 8517, 8515, -1, 8510, 8518, 8519, -1, 8516, 8518, 8510, -1, 8514, 8518, 8516, -1, 8515, 8518, 8514, -1, 3587, 3586, 8517, -1, 8518, 8520, 8519, -1, 8517, 8520, 8515, -1, 8515, 8520, 8518, -1, 8519, 8521, 3585, -1, 3585, 8521, 3583, -1, 3583, 8521, 3586, -1, 8520, 8521, 8519, -1, 3586, 8521, 8517, -1, 8517, 8521, 8520, -1, 605, 6029, 606, -1, 605, 6028, 6029, -1, 6029, 6027, 6031, -1, 6028, 6027, 6029, -1, 6031, 8519, 3585, -1, 6027, 8510, 6031, -1, 6031, 8510, 8519, -1, 6027, 6026, 8510, -1, 2358, 2104, 2359, -1, 2104, 2360, 2359, -1, 2103, 2087, 2104, -1, 2960, 2087, 1916, -1, 2958, 2087, 2960, -1, 2104, 2362, 2360, -1, 2955, 2087, 2958, -1, 2953, 2087, 2955, -1, 2104, 2087, 2089, -1, 1916, 2087, 2103, -1, 2104, 2253, 2362, -1, 2953, 2951, 2087, -1, 2104, 2257, 2253, -1, 2951, 2949, 2087, -1, 2104, 2597, 2257, -1, 2312, 2309, 2311, -1, 2314, 2309, 2312, -1, 2315, 2089, 2314, -1, 2317, 2089, 2315, -1, 2318, 2089, 2317, -1, 2320, 2089, 2318, -1, 2322, 2089, 2320, -1, 2586, 2089, 2322, -1, 2593, 2089, 2586, -1, 2597, 2089, 2593, -1, 2104, 2089, 2597, -1, 2314, 2089, 2309, -1, 2992, 2993, 2103, -1, 2993, 1609, 2103, -1, 1609, 1611, 2103, -1, 1611, 1613, 2103, -1, 1613, 1615, 2103, -1, 1615, 1617, 2103, -1, 1617, 1619, 2103, -1, 1619, 1621, 2103, -1, 1621, 1916, 2103, -1, 2286, 2113, 2287, -1, 2113, 2288, 2287, -1, 2112, 2096, 2113, -1, 2977, 2096, 1921, -1, 2988, 2096, 2977, -1, 2113, 2290, 2288, -1, 2986, 2096, 2988, -1, 2984, 2096, 2986, -1, 2113, 2096, 2098, -1, 1921, 2096, 2112, -1, 2113, 2248, 2290, -1, 2984, 2982, 2096, -1, 2113, 2252, 2248, -1, 2982, 2980, 2096, -1, 2113, 2626, 2252, -1, 2339, 2336, 2338, -1, 2341, 2336, 2339, -1, 2622, 2098, 2615, -1, 2626, 2098, 2622, -1, 2342, 2098, 2341, -1, 2344, 2098, 2342, -1, 2345, 2098, 2344, -1, 2347, 2098, 2345, -1, 2349, 2098, 2347, -1, 2615, 2098, 2349, -1, 2113, 2098, 2626, -1, 2341, 2098, 2336, -1, 2292, 2293, 2112, -1, 2293, 1700, 2112, -1, 1700, 1702, 2112, -1, 1702, 1704, 2112, -1, 1704, 1706, 2112, -1, 1706, 1708, 2112, -1, 1708, 1710, 2112, -1, 1710, 1712, 2112, -1, 1712, 1921, 2112, -1, 2331, 2095, 2332, -1, 2095, 2333, 2332, -1, 2095, 2335, 2333, -1, 2095, 2258, 2335, -1, 2569, 2566, 2568, -1, 2571, 2566, 2569, -1, 1770, 1766, 1765, -1, 1769, 1766, 1770, -1, 1768, 1767, 1769, -1, 1769, 1767, 1766, -1, 1768, 1763, 1767, -1, 2572, 2081, 2571, -1, 2574, 2081, 2572, -1, 2575, 2081, 2574, -1, 2577, 2081, 2575, -1, 2579, 2081, 2577, -1, 2571, 2081, 2566, -1, 2581, 2081, 2579, -1, 2582, 2081, 2581, -1, 1755, 2081, 2582, -1, 2258, 2081, 1768, -1, 1759, 2081, 1758, -1, 1762, 2081, 1759, -1, 1763, 2081, 1762, -1, 1754, 2081, 1755, -1, 1757, 2081, 1754, -1, 1758, 2081, 1757, -1, 2095, 2081, 2258, -1, 1768, 2081, 1763, -1, 2946, 2947, 2094, -1, 2947, 1622, 2094, -1, 1622, 1624, 2094, -1, 1624, 1626, 2094, -1, 1626, 1628, 2094, -1, 1628, 1630, 2094, -1, 1630, 1632, 2094, -1, 1632, 1634, 2094, -1, 1634, 1910, 2094, -1, 2972, 2079, 2974, -1, 2095, 2079, 2081, -1, 2969, 2079, 2972, -1, 2967, 2079, 2969, -1, 2974, 2079, 1910, -1, 2094, 2079, 2095, -1, 1910, 2079, 2094, -1, 2967, 2965, 2079, -1, 2965, 2963, 2079, -1, 2414, 2131, 2415, -1, 2131, 2416, 2415, -1, 2130, 2114, 2131, -1, 2942, 2114, 1931, -1, 2940, 2114, 2942, -1, 2131, 2418, 2416, -1, 2937, 2114, 2940, -1, 2935, 2114, 2937, -1, 2131, 2114, 2116, -1, 1931, 2114, 2130, -1, 2131, 2238, 2418, -1, 2935, 2933, 2114, -1, 2131, 2242, 2238, -1, 2933, 2931, 2114, -1, 2131, 2684, 2242, -1, 2366, 2363, 2365, -1, 2368, 2363, 2366, -1, 2680, 2116, 2673, -1, 2684, 2116, 2680, -1, 2369, 2116, 2368, -1, 2371, 2116, 2369, -1, 2372, 2116, 2371, -1, 2374, 2116, 2372, -1, 2376, 2116, 2374, -1, 2673, 2116, 2376, -1, 2131, 2116, 2684, -1, 2368, 2116, 2363, -1, 2910, 2911, 2130, -1, 2911, 1648, 2130, -1, 1648, 1650, 2130, -1, 1650, 1652, 2130, -1, 1652, 1654, 2130, -1, 1654, 1656, 2130, -1, 1656, 1658, 2130, -1, 1658, 1660, 2130, -1, 1660, 1931, 2130, -1, 2385, 2122, 2386, -1, 2122, 2387, 2386, -1, 2121, 2105, 2122, -1, 2306, 2105, 1927, -1, 2304, 2105, 2306, -1, 2122, 2389, 2387, -1, 2301, 2105, 2304, -1, 2299, 2105, 2301, -1, 2122, 2105, 2107, -1, 1927, 2105, 2121, -1, 2122, 2243, 2389, -1, 2299, 2297, 2105, -1, 2122, 2247, 2243, -1, 2297, 2295, 2105, -1, 2122, 2655, 2247, -1, 2267, 2264, 2266, -1, 2269, 2264, 2267, -1, 2270, 2107, 2269, -1, 2272, 2107, 2270, -1, 2273, 2107, 2272, -1, 2275, 2107, 2273, -1, 2277, 2107, 2275, -1, 2644, 2107, 2277, -1, 2651, 2107, 2644, -1, 2655, 2107, 2651, -1, 2122, 2107, 2655, -1, 2269, 2107, 2264, -1, 2928, 2929, 2121, -1, 2929, 1635, 2121, -1, 1635, 1637, 2121, -1, 1637, 1639, 2121, -1, 1639, 1641, 2121, -1, 1641, 1643, 2121, -1, 1643, 1645, 2121, -1, 1645, 1647, 2121, -1, 1647, 1927, 2121, -1, 2893, 1661, 2139, -1, 1661, 1663, 2139, -1, 2441, 2140, 2442, -1, 1663, 1665, 2139, -1, 1665, 1667, 2139, -1, 2140, 2443, 2442, -1, 1667, 1669, 2139, -1, 1669, 1671, 2139, -1, 2140, 2445, 2443, -1, 1671, 1673, 2139, -1, 2140, 2210, 2445, -1, 1673, 1937, 2139, -1, 2391, 1771, 2392, -1, 2216, 1771, 2391, -1, 2139, 2123, 2140, -1, 1937, 2123, 2139, -1, 2924, 2123, 1937, -1, 2922, 2123, 2924, -1, 2919, 2123, 2922, -1, 2917, 2123, 2919, -1, 2140, 2123, 2125, -1, 2917, 2915, 2123, -1, 2915, 2913, 2123, -1, 2397, 2394, 2396, -1, 2399, 2394, 2397, -1, 2210, 2125, 2216, -1, 2400, 2125, 2399, -1, 2402, 2125, 2400, -1, 2403, 2125, 2402, -1, 2405, 2125, 2403, -1, 2407, 2125, 2405, -1, 2409, 2125, 2407, -1, 2410, 2125, 2409, -1, 1776, 2125, 2410, -1, 1771, 2125, 1776, -1, 2140, 2125, 2210, -1, 2216, 2125, 1771, -1, 2399, 2125, 2394, -1, 2892, 2893, 2139, -1, 2447, 2149, 2448, -1, 2149, 2449, 2448, -1, 2148, 2132, 2149, -1, 2906, 2132, 1944, -1, 2904, 2132, 2906, -1, 2149, 2451, 2449, -1, 2901, 2132, 2904, -1, 2899, 2132, 2901, -1, 2149, 2132, 2134, -1, 1944, 2132, 2148, -1, 2149, 2218, 2451, -1, 2899, 2897, 2132, -1, 2149, 2222, 2218, -1, 2897, 2895, 2132, -1, 2149, 2713, 2222, -1, 2422, 2419, 2421, -1, 2424, 2419, 2422, -1, 2709, 2134, 2702, -1, 2713, 2134, 2709, -1, 2425, 2134, 2424, -1, 2427, 2134, 2425, -1, 2428, 2134, 2427, -1, 2430, 2134, 2428, -1, 2432, 2134, 2430, -1, 2702, 2134, 2432, -1, 2149, 2134, 2713, -1, 2424, 2134, 2419, -1, 2874, 2875, 2148, -1, 2875, 1674, 2148, -1, 1674, 1676, 2148, -1, 1676, 1678, 2148, -1, 1678, 1680, 2148, -1, 1680, 1682, 2148, -1, 1682, 1684, 2148, -1, 1684, 1686, 2148, -1, 1686, 1944, 2148, -1, 1689, 1691, 2157, -1, 1691, 1693, 2157, -1, 1693, 1695, 2157, -1, 1695, 1697, 2157, -1, 2475, 2158, 2476, -1, 1697, 1699, 2157, -1, 1699, 1950, 2157, -1, 2158, 2477, 2476, -1, 2158, 2479, 2477, -1, 2158, 2223, 2479, -1, 2158, 2227, 2223, -1, 2158, 2745, 2227, -1, 1950, 2141, 2157, -1, 2157, 2141, 2158, -1, 2888, 2141, 1950, -1, 2886, 2141, 2888, -1, 2883, 2141, 2886, -1, 2881, 2141, 2883, -1, 2158, 2141, 2143, -1, 2881, 2879, 2141, -1, 2879, 2877, 2141, -1, 2455, 2452, 2454, -1, 2457, 2452, 2455, -1, 2741, 2143, 2733, -1, 2745, 2143, 2741, -1, 2458, 2143, 2457, -1, 2460, 2143, 2458, -1, 2461, 2143, 2460, -1, 2463, 2143, 2461, -1, 2465, 2143, 2463, -1, 2466, 2143, 2465, -1, 2733, 2143, 2730, -1, 2730, 2143, 2466, -1, 2158, 2143, 2745, -1, 2457, 2143, 2452, -1, 2856, 2857, 2157, -1, 2857, 1687, 2157, -1, 1687, 1689, 2157, -1, 1715, 1717, 2162, -1, 1717, 1719, 2162, -1, 1719, 1721, 2162, -1, 1721, 1723, 2162, -1, 2533, 2163, 2534, -1, 1723, 1725, 2162, -1, 1725, 1867, 2162, -1, 2163, 2535, 2534, -1, 2163, 2537, 2535, -1, 2163, 2228, 2537, -1, 2163, 2232, 2228, -1, 2163, 2777, 2232, -1, 1867, 2150, 2162, -1, 2162, 2150, 2163, -1, 2870, 2150, 1867, -1, 2868, 2150, 2870, -1, 2865, 2150, 2868, -1, 2863, 2150, 2865, -1, 2163, 2150, 2152, -1, 2863, 2861, 2150, -1, 2861, 2859, 2150, -1, 2483, 2480, 2482, -1, 2485, 2480, 2483, -1, 2773, 2152, 2765, -1, 2777, 2152, 2773, -1, 2486, 2152, 2485, -1, 2488, 2152, 2486, -1, 2489, 2152, 2488, -1, 2491, 2152, 2489, -1, 2493, 2152, 2491, -1, 2494, 2152, 2493, -1, 2765, 2152, 2762, -1, 2762, 2152, 2494, -1, 2163, 2152, 2777, -1, 2485, 2152, 2480, -1, 2187, 2188, 2162, -1, 2188, 1713, 2162, -1, 1713, 1715, 2162, -1, 2539, 2026, 2540, -1, 2026, 2541, 2540, -1, 2201, 2028, 2021, -1, 2199, 2028, 2201, -1, 2196, 2028, 2199, -1, 2026, 2543, 2541, -1, 2194, 2028, 2196, -1, 2025, 2028, 2026, -1, 2026, 2028, 2030, -1, 2021, 2028, 2025, -1, 2026, 2233, 2543, -1, 2194, 2192, 2028, -1, 2026, 2237, 2233, -1, 2192, 2190, 2028, -1, 2026, 2838, 2237, -1, 2514, 2511, 2513, -1, 2516, 2511, 2514, -1, 2517, 2030, 2516, -1, 2519, 2030, 2517, -1, 2520, 2030, 2519, -1, 2522, 2030, 2520, -1, 2524, 2030, 2522, -1, 2827, 2030, 2524, -1, 2834, 2030, 2827, -1, 2838, 2030, 2834, -1, 2026, 2030, 2838, -1, 2516, 2030, 2511, -1, 2183, 2184, 2025, -1, 2184, 1726, 2025, -1, 1726, 1728, 2025, -1, 1728, 1730, 2025, -1, 1730, 1732, 2025, -1, 1732, 1734, 2025, -1, 1734, 1736, 2025, -1, 1736, 1738, 2025, -1, 1738, 2021, 2025, -1, 2166, 1739, 2042, -1, 1739, 1741, 2042, -1, 1741, 1743, 2042, -1, 1743, 1745, 2042, -1, 1745, 1747, 2042, -1, 1747, 1749, 2042, -1, 1749, 1751, 2042, -1, 2505, 2207, 2503, -1, 2506, 2207, 2505, -1, 2509, 2207, 2506, -1, 2508, 2207, 2509, -1, 2054, 2207, 2508, -1, 2054, 2209, 2207, -1, 2054, 2809, 2209, -1, 2042, 2083, 2054, -1, 1751, 2083, 2042, -1, 1887, 2083, 1751, -1, 2179, 2083, 1887, -1, 2177, 2083, 2179, -1, 2174, 2083, 2177, -1, 2172, 2083, 2174, -1, 2054, 2083, 2085, -1, 2172, 2170, 2083, -1, 2170, 2168, 2083, -1, 2547, 2544, 2546, -1, 2549, 2544, 2547, -1, 2550, 2085, 2549, -1, 2552, 2085, 2550, -1, 2553, 2085, 2552, -1, 2555, 2085, 2553, -1, 2557, 2085, 2555, -1, 2558, 2085, 2557, -1, 2797, 2085, 2794, -1, 2794, 2085, 2558, -1, 2805, 2085, 2797, -1, 2809, 2085, 2805, -1, 2054, 2085, 2809, -1, 2549, 2085, 2544, -1, 2165, 2166, 2042, -1, 8522, 8523, 8524, -1, 8522, 8525, 8523, -1, 8526, 8527, 8528, -1, 8528, 8527, 8529, -1, 8529, 8530, 8531, -1, 8527, 8530, 8529, -1, 8531, 8532, 8533, -1, 8530, 8532, 8531, -1, 8534, 8535, 8536, -1, 8536, 8535, 8537, -1, 8538, 8539, 8540, -1, 8537, 8539, 8541, -1, 8541, 8539, 8542, -1, 8543, 8544, 8545, -1, 8542, 8539, 8538, -1, 8546, 8547, 8548, -1, 8549, 8547, 8550, -1, 8548, 8547, 8549, -1, 8550, 8547, 8551, -1, 8551, 8552, 8534, -1, 8534, 8552, 8535, -1, 8540, 8553, 8554, -1, 8537, 8553, 8539, -1, 8539, 8553, 8540, -1, 8535, 8553, 8537, -1, 8555, 8556, 8546, -1, 8546, 8556, 8547, -1, 8551, 8556, 8552, -1, 8547, 8556, 8551, -1, 8554, 8557, 8558, -1, 8553, 8557, 8554, -1, 8552, 8557, 8535, -1, 8535, 8557, 8553, -1, 8558, 8559, 8560, -1, 8561, 8559, 8555, -1, 8555, 8559, 8556, -1, 8560, 8559, 8561, -1, 8557, 8559, 8558, -1, 8556, 8559, 8552, -1, 8552, 8559, 8557, -1, 8561, 8562, 8560, -1, 8563, 8564, 8565, -1, 8545, 8564, 8563, -1, 8544, 8564, 8545, -1, 8566, 8567, 8544, -1, 8544, 8567, 8564, -1, 8564, 8568, 8565, -1, 8569, 8536, 8566, -1, 8566, 8536, 8567, -1, 8567, 8541, 8564, -1, 8564, 8541, 8568, -1, 8570, 8571, 8572, -1, 8573, 8571, 8570, -1, 8565, 8571, 8573, -1, 8568, 8571, 8565, -1, 8574, 8534, 8569, -1, 8569, 8534, 8536, -1, 8536, 8537, 8567, -1, 8567, 8537, 8541, -1, 8572, 8542, 8538, -1, 8568, 8542, 8571, -1, 8571, 8542, 8572, -1, 8541, 8542, 8568, -1, 8550, 8551, 8574, -1, 8574, 8551, 8534, -1, 8575, 8576, 8577, -1, 8577, 8576, 8578, -1, 8578, 8579, 8580, -1, 8580, 8579, 8581, -1, 8576, 8579, 8578, -1, 8579, 8582, 8581, -1, 8583, 8584, 8585, -1, 8585, 8584, 8586, -1, 8586, 8587, 8588, -1, 8584, 8587, 8586, -1, 8587, 8589, 8588, -1, 8590, 8591, 8592, -1, 8592, 8591, 8593, -1, 8594, 8595, 8596, -1, 8597, 8595, 8594, -1, 8593, 8595, 8598, -1, 8599, 8600, 8601, -1, 8598, 8595, 8597, -1, 8602, 8603, 8604, -1, 8605, 8603, 8606, -1, 8604, 8603, 8605, -1, 8606, 8603, 8607, -1, 8607, 8608, 8590, -1, 8590, 8608, 8591, -1, 8596, 8609, 8610, -1, 8595, 8609, 8596, -1, 8591, 8609, 8593, -1, 8593, 8609, 8595, -1, 8611, 8612, 8602, -1, 8602, 8612, 8603, -1, 8607, 8612, 8608, -1, 8603, 8612, 8607, -1, 8610, 8613, 8614, -1, 8609, 8613, 8610, -1, 8608, 8613, 8591, -1, 8591, 8613, 8609, -1, 8614, 8615, 8616, -1, 8617, 8615, 8611, -1, 8611, 8615, 8612, -1, 8616, 8615, 8617, -1, 8613, 8615, 8614, -1, 8612, 8615, 8608, -1, 8608, 8615, 8613, -1, 8617, 8618, 8616, -1, 8619, 8620, 8621, -1, 8601, 8620, 8619, -1, 8600, 8620, 8601, -1, 8622, 8623, 8600, -1, 8600, 8623, 8620, -1, 8620, 8624, 8621, -1, 8625, 8592, 8622, -1, 8622, 8592, 8623, -1, 8623, 8598, 8620, -1, 8620, 8598, 8624, -1, 8626, 8627, 8628, -1, 8629, 8627, 8626, -1, 8621, 8627, 8629, -1, 8624, 8627, 8621, -1, 8630, 8590, 8625, -1, 8625, 8590, 8592, -1, 8592, 8593, 8623, -1, 8623, 8593, 8598, -1, 8628, 8597, 8594, -1, 8624, 8597, 8627, -1, 8598, 8597, 8624, -1, 8627, 8597, 8628, -1, 8606, 8607, 8630, -1, 8630, 8607, 8590, -1, 8631, 8632, 8633, -1, 8633, 8634, 8635, -1, 8632, 8634, 8633, -1, 8635, 8636, 8637, -1, 8634, 8636, 8635, -1, 8636, 8638, 8637, -1, 8639, 8640, 8641, -1, 8641, 8640, 8642, -1, 8643, 8644, 8645, -1, 8646, 8644, 8643, -1, 8647, 8648, 8649, -1, 8642, 8644, 8650, -1, 8650, 8644, 8646, -1, 8651, 8652, 8653, -1, 8654, 8652, 8655, -1, 8653, 8652, 8654, -1, 8655, 8652, 8656, -1, 8656, 8657, 8639, -1, 8639, 8657, 8640, -1, 8645, 8658, 8659, -1, 8644, 8658, 8645, -1, 8640, 8658, 8642, -1, 8642, 8658, 8644, -1, 8660, 8661, 8651, -1, 8651, 8661, 8652, -1, 8656, 8661, 8657, -1, 8652, 8661, 8656, -1, 8659, 8662, 8663, -1, 8658, 8662, 8659, -1, 8657, 8662, 8640, -1, 8640, 8662, 8658, -1, 8663, 8664, 8665, -1, 8666, 8664, 8660, -1, 8660, 8664, 8661, -1, 8665, 8664, 8666, -1, 8662, 8664, 8663, -1, 8661, 8664, 8657, -1, 8657, 8664, 8662, -1, 8666, 8667, 8665, -1, 8668, 8669, 8670, -1, 8649, 8669, 8668, -1, 8648, 8669, 8649, -1, 8671, 8672, 8648, -1, 8648, 8672, 8669, -1, 8669, 8673, 8670, -1, 8674, 8641, 8671, -1, 8671, 8641, 8672, -1, 8672, 8650, 8669, -1, 8669, 8650, 8673, -1, 8675, 8676, 8677, -1, 8678, 8676, 8675, -1, 8670, 8676, 8678, -1, 8673, 8676, 8670, -1, 8679, 8639, 8674, -1, 8674, 8639, 8641, -1, 8641, 8642, 8672, -1, 8672, 8642, 8650, -1, 8677, 8646, 8643, -1, 8673, 8646, 8676, -1, 8650, 8646, 8673, -1, 8676, 8646, 8677, -1, 8655, 8656, 8679, -1, 8679, 8656, 8639, -1, 8680, 8681, 8682, -1, 8682, 8681, 8683, -1, 8683, 8684, 8685, -1, 8681, 8684, 8683, -1, 8685, 8686, 8687, -1, 8684, 8686, 8685, -1, 8688, 8689, 8690, -1, 8690, 8689, 8691, -1, 8692, 8693, 8694, -1, 8695, 8693, 8692, -1, 8696, 8697, 8698, -1, 8691, 8693, 8699, -1, 8699, 8693, 8695, -1, 8700, 8701, 8702, -1, 8703, 8701, 8704, -1, 8702, 8701, 8703, -1, 8704, 8701, 8705, -1, 8705, 8706, 8688, -1, 8688, 8706, 8689, -1, 8694, 8707, 8708, -1, 8693, 8707, 8694, -1, 8689, 8707, 8691, -1, 8691, 8707, 8693, -1, 8709, 8710, 8700, -1, 8700, 8710, 8701, -1, 8705, 8710, 8706, -1, 8701, 8710, 8705, -1, 8708, 8711, 8712, -1, 8707, 8711, 8708, -1, 8706, 8711, 8689, -1, 8689, 8711, 8707, -1, 8712, 8713, 8714, -1, 8715, 8713, 8709, -1, 8709, 8713, 8710, -1, 8714, 8713, 8715, -1, 8711, 8713, 8712, -1, 8710, 8713, 8706, -1, 8706, 8713, 8711, -1, 8715, 8716, 8714, -1, 8717, 8718, 8719, -1, 8698, 8718, 8717, -1, 8697, 8718, 8698, -1, 8720, 8721, 8697, -1, 8697, 8721, 8718, -1, 8718, 8722, 8719, -1, 8723, 8690, 8720, -1, 8720, 8690, 8721, -1, 8721, 8699, 8718, -1, 8718, 8699, 8722, -1, 8724, 8725, 8726, -1, 8727, 8725, 8724, -1, 8719, 8725, 8727, -1, 8722, 8725, 8719, -1, 8728, 8688, 8723, -1, 8723, 8688, 8690, -1, 8690, 8691, 8721, -1, 8721, 8691, 8699, -1, 8726, 8695, 8692, -1, 8722, 8695, 8725, -1, 8699, 8695, 8722, -1, 8725, 8695, 8726, -1, 8704, 8705, 8728, -1, 8728, 8705, 8688, -1, 8729, 8730, 8731, -1, 8731, 8732, 8733, -1, 8730, 8732, 8731, -1, 8733, 8734, 8735, -1, 8732, 8734, 8733, -1, 8734, 8736, 8735, -1, 8737, 8738, 8739, -1, 8739, 8738, 8740, -1, 8741, 8742, 8743, -1, 8744, 8742, 8741, -1, 8740, 8742, 8745, -1, 8746, 8747, 8748, -1, 8745, 8742, 8744, -1, 8749, 8750, 8751, -1, 8752, 8750, 8753, -1, 8751, 8750, 8752, -1, 8753, 8750, 8754, -1, 8754, 8755, 8737, -1, 8737, 8755, 8738, -1, 8743, 8756, 8757, -1, 8742, 8756, 8743, -1, 8738, 8756, 8740, -1, 8740, 8756, 8742, -1, 8758, 8759, 8749, -1, 8749, 8759, 8750, -1, 8754, 8759, 8755, -1, 8750, 8759, 8754, -1, 8757, 8760, 8761, -1, 8756, 8760, 8757, -1, 8755, 8760, 8738, -1, 8738, 8760, 8756, -1, 8761, 8762, 8763, -1, 8764, 8762, 8758, -1, 8758, 8762, 8759, -1, 8763, 8762, 8764, -1, 8760, 8762, 8761, -1, 8759, 8762, 8755, -1, 8755, 8762, 8760, -1, 8764, 8765, 8763, -1, 8766, 8767, 8768, -1, 8748, 8767, 8766, -1, 8747, 8767, 8748, -1, 8769, 8770, 8747, -1, 8747, 8770, 8767, -1, 8767, 8771, 8768, -1, 8772, 8739, 8769, -1, 8769, 8739, 8770, -1, 8770, 8745, 8767, -1, 8767, 8745, 8771, -1, 8773, 8774, 8775, -1, 8776, 8774, 8773, -1, 8768, 8774, 8776, -1, 8771, 8774, 8768, -1, 8777, 8737, 8772, -1, 8772, 8737, 8739, -1, 8739, 8740, 8770, -1, 8770, 8740, 8745, -1, 8775, 8744, 8741, -1, 8771, 8744, 8774, -1, 8745, 8744, 8771, -1, 8774, 8744, 8775, -1, 8753, 8754, 8777, -1, 8777, 8754, 8737, -1, 8778, 8779, 8780, -1, 8780, 8779, 8781, -1, 8781, 8782, 8783, -1, 8779, 8782, 8781, -1, 8783, 8784, 8785, -1, 8782, 8784, 8783, -1, 8786, 8787, 8788, -1, 8788, 8787, 8789, -1, 8790, 8791, 8792, -1, 8793, 8791, 8790, -1, 8789, 8791, 8794, -1, 8795, 8796, 8797, -1, 8794, 8791, 8793, -1, 8798, 8799, 8800, -1, 8801, 8799, 8802, -1, 8800, 8799, 8801, -1, 8802, 8799, 8803, -1, 8803, 8804, 8786, -1, 8786, 8804, 8787, -1, 8792, 8805, 8806, -1, 8791, 8805, 8792, -1, 8787, 8805, 8789, -1, 8789, 8805, 8791, -1, 8807, 8808, 8798, -1, 8798, 8808, 8799, -1, 8803, 8808, 8804, -1, 8799, 8808, 8803, -1, 8806, 8809, 8810, -1, 8805, 8809, 8806, -1, 8804, 8809, 8787, -1, 8787, 8809, 8805, -1, 8810, 8811, 8812, -1, 8813, 8811, 8807, -1, 8807, 8811, 8808, -1, 8812, 8811, 8813, -1, 8809, 8811, 8810, -1, 8808, 8811, 8804, -1, 8804, 8811, 8809, -1, 8813, 8814, 8812, -1, 8815, 8816, 8817, -1, 8797, 8816, 8815, -1, 8796, 8816, 8797, -1, 8818, 8819, 8796, -1, 8796, 8819, 8816, -1, 8816, 8820, 8817, -1, 8821, 8788, 8818, -1, 8818, 8788, 8819, -1, 8819, 8794, 8816, -1, 8816, 8794, 8820, -1, 8822, 8823, 8824, -1, 8825, 8823, 8822, -1, 8817, 8823, 8825, -1, 8820, 8823, 8817, -1, 8826, 8786, 8821, -1, 8821, 8786, 8788, -1, 8788, 8789, 8819, -1, 8819, 8789, 8794, -1, 8824, 8793, 8790, -1, 8820, 8793, 8823, -1, 8794, 8793, 8820, -1, 8823, 8793, 8824, -1, 8802, 8803, 8826, -1, 8826, 8803, 8786, -1, 8827, 8828, 8829, -1, 8829, 8828, 8830, -1, 8830, 8831, 8832, -1, 8828, 8831, 8830, -1, 8832, 8833, 8834, -1, 8831, 8833, 8832, -1, 8835, 8836, 8837, -1, 8837, 8836, 8838, -1, 8839, 8840, 8841, -1, 8842, 8840, 8839, -1, 8838, 8840, 8843, -1, 8844, 8845, 8846, -1, 8843, 8840, 8842, -1, 8847, 8848, 8849, -1, 8850, 8848, 8851, -1, 8849, 8848, 8850, -1, 8851, 8848, 8852, -1, 8852, 8853, 8835, -1, 8835, 8853, 8836, -1, 8841, 8854, 8855, -1, 8840, 8854, 8841, -1, 8836, 8854, 8838, -1, 8838, 8854, 8840, -1, 8856, 8857, 8847, -1, 8847, 8857, 8848, -1, 8852, 8857, 8853, -1, 8848, 8857, 8852, -1, 8855, 8858, 8859, -1, 8854, 8858, 8855, -1, 8853, 8858, 8836, -1, 8836, 8858, 8854, -1, 8859, 8860, 8861, -1, 8862, 8860, 8856, -1, 8856, 8860, 8857, -1, 8861, 8860, 8862, -1, 8858, 8860, 8859, -1, 8857, 8860, 8853, -1, 8853, 8860, 8858, -1, 8862, 8863, 8861, -1, 8864, 8865, 8866, -1, 8846, 8865, 8864, -1, 8845, 8865, 8846, -1, 8867, 8868, 8845, -1, 8845, 8868, 8865, -1, 8865, 8869, 8866, -1, 8870, 8837, 8867, -1, 8867, 8837, 8868, -1, 8868, 8843, 8865, -1, 8865, 8843, 8869, -1, 8871, 8872, 8873, -1, 8874, 8872, 8871, -1, 8866, 8872, 8874, -1, 8869, 8872, 8866, -1, 8875, 8835, 8870, -1, 8870, 8835, 8837, -1, 8837, 8838, 8868, -1, 8868, 8838, 8843, -1, 8873, 8842, 8839, -1, 8869, 8842, 8872, -1, 8843, 8842, 8869, -1, 8872, 8842, 8873, -1, 8851, 8852, 8875, -1, 8875, 8852, 8835, -1, 8876, 8877, 8878, -1, 8878, 8877, 8879, -1, 8879, 8880, 8881, -1, 8877, 8880, 8879, -1, 8881, 8882, 8883, -1, 8880, 8882, 8881, -1, 8884, 8885, 8886, -1, 8886, 8887, 8888, -1, 8885, 8887, 8886, -1, 8888, 8889, 8890, -1, 8887, 8889, 8888, -1, 8890, 8891, 8892, -1, 8889, 8891, 8890, -1, 8892, 8893, 8894, -1, 8891, 8893, 8892, -1, 8894, 8895, 8896, -1, 8893, 8895, 8894, -1, 8896, 8897, 8898, -1, 8895, 8897, 8896, -1, 8897, 8899, 8898, -1, 8900, 8901, 8902, -1, 8903, 8904, 8901, -1, 8902, 8904, 8905, -1, 8901, 8904, 8902, -1, 8903, 8906, 8904, -1, 8907, 8908, 8903, -1, 8903, 8908, 8906, -1, 8909, 8910, 8907, -1, 8907, 8910, 8908, -1, 8911, 8912, 8909, -1, 8909, 8912, 8910, -1, 8913, 8914, 8915, -1, 8916, 8917, 8914, -1, 8915, 8917, 8918, -1, 8914, 8917, 8915, -1, 8916, 8919, 8917, -1, 8920, 8921, 8916, -1, 8916, 8921, 8919, -1, 8922, 8923, 8920, -1, 8920, 8923, 8921, -1, 8924, 8925, 8922, -1, 8922, 8925, 8923, -1, 8926, 8927, 8928, -1, 8929, 8930, 8927, -1, 8928, 8930, 8931, -1, 8927, 8930, 8928, -1, 8932, 8933, 8929, -1, 8929, 8933, 8930, -1, 8932, 8934, 8933, -1, 8935, 8936, 8932, -1, 8932, 8936, 8934, -1, 8937, 8938, 8935, -1, 8935, 8938, 8936, -1, 8939, 8940, 8941, -1, 8942, 8943, 8940, -1, 8941, 8943, 8944, -1, 8940, 8943, 8941, -1, 8945, 8946, 8942, -1, 8942, 8946, 8943, -1, 8945, 8947, 8946, -1, 8948, 8949, 8945, -1, 8945, 8949, 8947, -1, 8950, 8951, 8948, -1, 8948, 8951, 8949, -1, 8952, 8953, 8954, -1, 8955, 8956, 8953, -1, 8954, 8956, 8957, -1, 8953, 8956, 8954, -1, 8958, 8959, 8955, -1, 8955, 8959, 8956, -1, 8958, 8960, 8959, -1, 8961, 8962, 8958, -1, 8958, 8962, 8960, -1, 8963, 8964, 8961, -1, 8961, 8964, 8962, -1, 8965, 8966, 8967, -1, 8968, 8969, 8966, -1, 8967, 8969, 8970, -1, 8966, 8969, 8967, -1, 8971, 8972, 8968, -1, 8968, 8972, 8969, -1, 8971, 8973, 8972, -1, 8974, 8975, 8971, -1, 8971, 8975, 8973, -1, 8976, 8977, 8974, -1, 8974, 8977, 8975, -1, 8978, 8979, 8980, -1, 8981, 8982, 8979, -1, 8980, 8982, 8983, -1, 8979, 8982, 8980, -1, 8981, 8984, 8982, -1, 8985, 8986, 8981, -1, 8981, 8986, 8984, -1, 8987, 8988, 8985, -1, 8985, 8988, 8986, -1, 8989, 8990, 8987, -1, 8987, 8990, 8988, -1, 8991, 8992, 8993, -1, 8994, 8995, 8992, -1, 8993, 8995, 8996, -1, 8992, 8995, 8993, -1, 8997, 8998, 8994, -1, 8994, 8998, 8995, -1, 8997, 8999, 8998, -1, 9000, 9001, 8997, -1, 8997, 9001, 8999, -1, 9002, 9003, 9000, -1, 9000, 9003, 9001, -1, 9004, 9005, 9006, -1, 9006, 9005, 9007, -1, 9008, 9009, 9010, -1, 9011, 9009, 9008, -1, 9007, 9009, 9012, -1, 9013, 9014, 9015, -1, 9012, 9009, 9011, -1, 9016, 9017, 9018, -1, 9019, 9017, 9020, -1, 9018, 9017, 9019, -1, 9020, 9017, 9021, -1, 9021, 9022, 9004, -1, 9004, 9022, 9005, -1, 9010, 9023, 9024, -1, 9009, 9023, 9010, -1, 9005, 9023, 9007, -1, 9007, 9023, 9009, -1, 9025, 9026, 9016, -1, 9016, 9026, 9017, -1, 9021, 9026, 9022, -1, 9017, 9026, 9021, -1, 9024, 9027, 9028, -1, 9023, 9027, 9024, -1, 9022, 9027, 9005, -1, 9005, 9027, 9023, -1, 9028, 9029, 9030, -1, 9031, 9029, 9025, -1, 9025, 9029, 9026, -1, 9030, 9029, 9031, -1, 9027, 9029, 9028, -1, 9026, 9029, 9022, -1, 9022, 9029, 9027, -1, 9031, 9032, 9030, -1, 9033, 9034, 9035, -1, 9015, 9034, 9033, -1, 9014, 9034, 9015, -1, 9036, 9037, 9014, -1, 9014, 9037, 9034, -1, 9034, 9038, 9035, -1, 9039, 9006, 9036, -1, 9036, 9006, 9037, -1, 9037, 9012, 9034, -1, 9034, 9012, 9038, -1, 9040, 9041, 9042, -1, 9043, 9041, 9040, -1, 9035, 9041, 9043, -1, 9038, 9041, 9035, -1, 9044, 9004, 9039, -1, 9039, 9004, 9006, -1, 9006, 9007, 9037, -1, 9037, 9007, 9012, -1, 9042, 9011, 9008, -1, 9038, 9011, 9041, -1, 9012, 9011, 9038, -1, 9041, 9011, 9042, -1, 9020, 9021, 9044, -1, 9044, 9021, 9004, -1, 9045, 9046, 9047, -1, 9047, 9046, 9048, -1, 9048, 9049, 9050, -1, 9050, 9049, 9051, -1, 9046, 9049, 9048, -1, 9049, 9052, 9051, -1, 9053, 9054, 9055, -1, 9056, 9057, 9054, -1, 9055, 9057, 9058, -1, 9054, 9057, 9055, -1, 9059, 9060, 9056, -1, 9056, 9060, 9057, -1, 9059, 9061, 9060, -1, 9062, 9063, 9059, -1, 9059, 9063, 9061, -1, 9064, 9065, 9062, -1, 9062, 9065, 9063, -1, 9066, 9067, 9068, -1, 9067, 9069, 9068, -1, 9068, 9070, 9071, -1, 9069, 9070, 9068, -1, 9070, 9072, 9071, -1, 9073, 9074, 9075, -1, 9073, 9076, 9074, -1, 9077, 9075, 9078, -1, 9077, 9073, 9075, -1, 9079, 9078, 9080, -1, 9079, 9077, 9078, -1, 9081, 9082, 9083, -1, 9084, 9085, 9086, -1, 9087, 9085, 9088, -1, 9089, 9085, 9084, -1, 9086, 9085, 9090, -1, 9088, 9085, 9089, -1, 9083, 9091, 9087, -1, 9087, 9091, 9085, -1, 9085, 9091, 9090, -1, 9092, 9093, 9094, -1, 9090, 9093, 9092, -1, 9083, 9093, 9091, -1, 9094, 9093, 9082, -1, 9095, 9096, 9097, -1, 9082, 9093, 9083, -1, 9098, 9096, 9095, -1, 9091, 9093, 9090, -1, 9099, 9096, 9098, -1, 9099, 9100, 9096, -1, 9090, 9101, 9086, -1, 9090, 9102, 9101, -1, 9090, 9103, 9102, -1, 9104, 9105, 9106, -1, 9096, 9105, 9104, -1, 9100, 9105, 9096, -1, 9107, 9108, 9100, -1, 9100, 9108, 9105, -1, 9106, 9109, 9110, -1, 9105, 9109, 9106, -1, 9105, 9111, 9109, -1, 9108, 9111, 9105, -1, 9109, 9111, 9110, -1, 9107, 9111, 9108, -1, 9107, 9112, 9111, -1, 9110, 9113, 9114, -1, 9115, 9116, 9117, -1, 9117, 9116, 9107, -1, 9107, 9116, 9112, -1, 9111, 9118, 9110, -1, 9110, 9118, 9113, -1, 9111, 9081, 9118, -1, 9112, 9081, 9111, -1, 9114, 9088, 9119, -1, 9113, 9088, 9114, -1, 9094, 9120, 9115, -1, 9112, 9120, 9081, -1, 9115, 9120, 9116, -1, 9116, 9120, 9112, -1, 9118, 9087, 9113, -1, 9113, 9087, 9088, -1, 9118, 9083, 9087, -1, 9081, 9083, 9118, -1, 9121, 9089, 9084, -1, 9119, 9089, 9121, -1, 9088, 9089, 9119, -1, 9094, 9082, 9120, -1, 9120, 9082, 9081, -1, 9122, 9123, 9124, -1, 9125, 9126, 9127, -1, 9128, 9122, 9129, -1, 9128, 9129, 9130, -1, 9128, 9131, 9123, -1, 9128, 9123, 9122, -1, 9132, 9130, 9133, -1, 9132, 9131, 9128, -1, 9132, 9128, 9130, -1, 9134, 9133, 9135, -1, 9134, 9136, 9131, -1, 9134, 9131, 9132, -1, 9134, 9132, 9133, -1, 9137, 9135, 9138, -1, 9137, 9138, 9139, -1, 9137, 9140, 9136, -1, 9137, 9136, 9134, -1, 9137, 9134, 9135, -1, 9141, 9139, 9142, -1, 9141, 9143, 9144, -1, 9141, 9144, 9140, -1, 9141, 9137, 9139, -1, 9141, 9140, 9137, -1, 9145, 9142, 9146, -1, 9145, 9141, 9142, -1, 9145, 9143, 9141, -1, 9147, 9146, 9148, -1, 9147, 9148, 9125, -1, 9147, 9127, 9143, -1, 9147, 9125, 9127, -1, 9147, 9145, 9146, -1, 9147, 9143, 9145, -1, 9149, 9150, 9151, -1, 9152, 9149, 9151, -1, 9153, 9149, 9152, -1, 9154, 9153, 9152, -1, 9155, 9153, 9154, -1, 9156, 9155, 9154, -1, 9157, 9155, 9156, -1, 9158, 9157, 9156, -1, 9159, 9157, 9158, -1, 9160, 9159, 9158, -1, 9161, 9162, 9159, -1, 9161, 9159, 9160, -1, 9163, 9164, 9165, -1, 9166, 9165, 9167, -1, 9166, 9163, 9165, -1, 9168, 9166, 9167, -1, 9169, 9167, 9170, -1, 9169, 9168, 9167, -1, 9171, 9172, 9173, -1, 9173, 9172, 9174, -1, 9175, 9176, 9177, -1, 9178, 9176, 9175, -1, 9179, 9180, 9181, -1, 9174, 9176, 9182, -1, 9182, 9176, 9178, -1, 9183, 9184, 9185, -1, 9186, 9184, 9187, -1, 9185, 9184, 9186, -1, 9187, 9184, 9188, -1, 9188, 9189, 9171, -1, 9171, 9189, 9172, -1, 9177, 9190, 9191, -1, 9176, 9190, 9177, -1, 9172, 9190, 9174, -1, 9174, 9190, 9176, -1, 9192, 9193, 9183, -1, 9183, 9193, 9184, -1, 9188, 9193, 9189, -1, 9184, 9193, 9188, -1, 9191, 9194, 9195, -1, 9190, 9194, 9191, -1, 9189, 9194, 9172, -1, 9172, 9194, 9190, -1, 9195, 9196, 9197, -1, 9198, 9196, 9192, -1, 9192, 9196, 9193, -1, 9197, 9196, 9198, -1, 9194, 9196, 9195, -1, 9193, 9196, 9189, -1, 9189, 9196, 9194, -1, 9198, 9199, 9197, -1, 9200, 9201, 9202, -1, 9181, 9201, 9200, -1, 9180, 9201, 9181, -1, 9203, 9204, 9180, -1, 9180, 9204, 9201, -1, 9201, 9205, 9202, -1, 9206, 9173, 9203, -1, 9203, 9173, 9204, -1, 9204, 9182, 9201, -1, 9201, 9182, 9205, -1, 9207, 9208, 9209, -1, 9210, 9208, 9207, -1, 9202, 9208, 9210, -1, 9205, 9208, 9202, -1, 9211, 9171, 9206, -1, 9206, 9171, 9173, -1, 9173, 9174, 9204, -1, 9204, 9174, 9182, -1, 9209, 9178, 9175, -1, 9205, 9178, 9208, -1, 9182, 9178, 9205, -1, 9208, 9178, 9209, -1, 9187, 9188, 9211, -1, 9211, 9188, 9171, -1, 9212, 9213, 9214, -1, 9214, 9213, 9215, -1, 9215, 9216, 9217, -1, 9213, 9216, 9215, -1, 9217, 9218, 9219, -1, 9216, 9218, 9217, -1, 9220, 9221, 9222, -1, 9222, 9223, 9224, -1, 9221, 9223, 9222, -1, 9223, 9225, 9224, -1, 9224, 9226, 9227, -1, 9225, 9226, 9224, -1, 9228, 9229, 9230, -1, 9230, 9231, 9232, -1, 9229, 9231, 9230, -1, 9232, 9233, 9234, -1, 9231, 9233, 9232, -1, 9233, 9235, 9234, -1, 9236, 9237, 9238, -1, 9238, 9237, 9239, -1, 9239, 9240, 9241, -1, 9237, 9240, 9239, -1, 9241, 9242, 9243, -1, 9240, 9242, 9241, -1, 9244, 9245, 9246, -1, 9247, 9245, 9248, -1, 9246, 9245, 9247, -1, 9248, 9249, 9250, -1, 9245, 9249, 9248, -1, 9249, 9251, 9250, -1, 9252, 9253, 9254, -1, 9254, 9253, 9255, -1, 9255, 9253, 9256, -1, 9256, 9257, 9258, -1, 9253, 9257, 9256, -1, 9257, 9259, 9258, -1, 9164, 9260, 9261, -1, 9262, 9164, 9261, -1, 9263, 9264, 9265, -1, 9266, 9263, 9265, -1, 9267, 9268, 9269, -1, 9268, 9270, 9269, -1, 9269, 9271, 9272, -1, 9270, 9271, 9269, -1, 9272, 9273, 9274, -1, 9271, 9273, 9272, -1, 9274, 9275, 9276, -1, 9273, 9275, 9274, -1, 9276, 9277, 9278, -1, 9275, 9277, 9276, -1, 9279, 9280, 9281, -1, 9281, 9280, 9282, -1, 9282, 9283, 9284, -1, 9280, 9283, 9282, -1, 9284, 9285, 9286, -1, 9283, 9285, 9284, -1, 9286, 9287, 9288, -1, 9285, 9287, 9286, -1, 9288, 9289, 9290, -1, 9287, 9289, 9288, -1, 9290, 9291, 9292, -1, 9289, 9291, 9290, -1, 9292, 9293, 9294, -1, 9291, 9293, 9292, -1, 9295, 9296, 9297, -1, 9297, 9298, 9299, -1, 9296, 9298, 9297, -1, 9299, 9300, 9301, -1, 9298, 9300, 9299, -1, 9301, 9302, 9303, -1, 9300, 9302, 9301, -1, 9303, 9304, 9305, -1, 9302, 9304, 9303, -1, 9305, 9306, 9307, -1, 9304, 9306, 9305, -1, 9307, 9308, 9309, -1, 9306, 9308, 9307, -1, 9309, 9310, 9311, -1, 9308, 9310, 9309, -1, 9311, 9312, 9313, -1, 9310, 9312, 9311, -1, 9313, 9314, 9315, -1, 9312, 9314, 9313, -1, 9315, 9316, 9317, -1, 9314, 9316, 9315, -1, 9317, 9318, 9319, -1, 9316, 9318, 9317, -1, 9318, 9320, 9319, -1, 9319, 9321, 9322, -1, 9320, 9321, 9319, -1, 9323, 9324, 9325, -1, 9325, 9326, 9327, -1, 9324, 9326, 9325, -1, 9327, 9328, 9329, -1, 9326, 9328, 9327, -1, 9329, 9330, 9331, -1, 9328, 9330, 9329, -1, 9331, 9332, 9333, -1, 9330, 9332, 9331, -1, 9333, 9334, 9335, -1, 9332, 9334, 9333, -1, 9335, 9336, 9337, -1, 9334, 9336, 9335, -1, 9337, 9338, 9339, -1, 9336, 9338, 9337, -1, 9339, 9340, 9341, -1, 9338, 9340, 9339, -1, 9341, 9342, 9343, -1, 9340, 9342, 9341, -1, 9343, 9344, 9345, -1, 9342, 9344, 9343, -1, 9345, 9346, 9347, -1, 9344, 9346, 9345, -1, 9346, 9348, 9347, -1, 9347, 9349, 9350, -1, 9348, 9349, 9347, -1, 9351, 9352, 9353, -1, 9354, 9355, 9356, -1, 9353, 9352, 9357, -1, 9357, 9352, 9358, -1, 9359, 9360, 9361, -1, 9362, 9363, 9364, -1, 9358, 9360, 9365, -1, 9356, 9363, 9362, -1, 9365, 9360, 9366, -1, 9367, 9368, 9369, -1, 9370, 9371, 9372, -1, 9366, 9360, 9359, -1, 9364, 9368, 9367, -1, 9358, 9373, 9360, -1, 9374, 9373, 9375, -1, 9361, 9373, 9374, -1, 9375, 9373, 9376, -1, 9377, 9378, 9379, -1, 9376, 9373, 9352, -1, 9352, 9373, 9358, -1, 9356, 9378, 9363, -1, 9360, 9373, 9361, -1, 9355, 9378, 9356, -1, 9379, 9378, 9355, -1, 9363, 9380, 9364, -1, 9364, 9380, 9368, -1, 9369, 9381, 9382, -1, 9368, 9381, 9369, -1, 9378, 9383, 9363, -1, 9384, 9383, 9377, -1, 9363, 9383, 9380, -1, 9385, 9379, 9386, -1, 9377, 9383, 9378, -1, 9368, 9387, 9381, -1, 9380, 9387, 9368, -1, 9382, 9388, 9389, -1, 9381, 9388, 9382, -1, 9390, 9391, 9384, -1, 9384, 9391, 9383, -1, 9383, 9391, 9380, -1, 9380, 9391, 9387, -1, 9387, 9392, 9381, -1, 9381, 9392, 9388, -1, 9389, 9393, 9394, -1, 9388, 9393, 9389, -1, 9395, 9396, 9390, -1, 9390, 9396, 9391, -1, 9387, 9396, 9392, -1, 9391, 9396, 9387, -1, 9392, 9397, 9388, -1, 9388, 9397, 9393, -1, 9393, 9398, 9394, -1, 9394, 9398, 9399, -1, 9400, 9401, 9395, -1, 9396, 9401, 9392, -1, 9395, 9401, 9396, -1, 9392, 9401, 9397, -1, 9393, 9402, 9398, -1, 9397, 9402, 9393, -1, 9398, 9403, 9399, -1, 9399, 9403, 9404, -1, 9405, 9406, 9400, -1, 9400, 9406, 9401, -1, 9401, 9406, 9397, -1, 9397, 9406, 9402, -1, 9402, 9407, 9398, -1, 9398, 9407, 9403, -1, 9404, 9408, 9409, -1, 9403, 9408, 9404, -1, 9410, 9411, 9405, -1, 9402, 9411, 9407, -1, 9405, 9411, 9406, -1, 9406, 9411, 9402, -1, 9407, 9412, 9403, -1, 9403, 9412, 9408, -1, 9409, 9413, 9414, -1, 9408, 9413, 9409, -1, 9415, 9416, 9410, -1, 9407, 9416, 9412, -1, 9410, 9416, 9411, -1, 9411, 9416, 9407, -1, 9412, 9357, 9408, -1, 9408, 9357, 9413, -1, 9414, 9365, 9417, -1, 9375, 9418, 9374, -1, 9413, 9365, 9414, -1, 9351, 9353, 9415, -1, 9415, 9353, 9416, -1, 9416, 9353, 9412, -1, 9370, 9362, 9371, -1, 9412, 9353, 9357, -1, 9354, 9356, 9370, -1, 9357, 9358, 9413, -1, 9413, 9358, 9365, -1, 9370, 9356, 9362, -1, 9419, 9366, 9359, -1, 9371, 9364, 9367, -1, 9420, 9366, 9419, -1, 9362, 9364, 9371, -1, 9417, 9366, 9420, -1, 9365, 9366, 9417, -1, 9386, 9355, 9354, -1, 9376, 9352, 9351, -1, 9379, 9355, 9386, -1, 9421, 9422, 9423, -1, 9424, 9425, 9426, -1, 9424, 9427, 9428, -1, 9421, 9429, 9422, -1, 9424, 9426, 9430, -1, 9424, 9430, 9427, -1, 9431, 9432, 9433, -1, 9431, 9433, 9434, -1, 9435, 9436, 9437, -1, 9431, 9438, 9432, -1, 9439, 9440, 9441, -1, 9439, 9441, 9429, -1, 9442, 9443, 9444, -1, 9442, 9445, 9446, -1, 9447, 9448, 9438, -1, 9442, 9444, 9445, -1, 9447, 9449, 9448, -1, 9442, 9446, 9440, -1, 9450, 9423, 9451, -1, 9452, 9453, 9425, -1, 9452, 9425, 9424, -1, 9452, 9424, 9428, -1, 9452, 9428, 9449, -1, 9450, 9421, 9423, -1, 9454, 9434, 9455, -1, 9454, 9431, 9434, -1, 9456, 9439, 9429, -1, 9454, 9438, 9431, -1, 9456, 9429, 9421, -1, 9454, 9447, 9438, -1, 9457, 9458, 9453, -1, 9459, 9460, 9443, -1, 9459, 9440, 9439, -1, 9457, 9453, 9452, -1, 9459, 9442, 9440, -1, 9459, 9443, 9442, -1, 9457, 9452, 9449, -1, 9457, 9449, 9447, -1, 9461, 9462, 9463, -1, 9464, 9451, 9465, -1, 9461, 9455, 9462, -1, 9461, 9463, 9458, -1, 9461, 9447, 9454, -1, 9461, 9457, 9447, -1, 9461, 9458, 9457, -1, 9461, 9454, 9455, -1, 9464, 9450, 9451, -1, 9466, 9421, 9450, -1, 9466, 9456, 9421, -1, 9467, 9468, 9460, -1, 9467, 9439, 9456, -1, 9467, 9459, 9439, -1, 9467, 9460, 9459, -1, 9469, 9465, 9470, -1, 9469, 9464, 9465, -1, 9471, 9450, 9464, -1, 9471, 9466, 9450, -1, 9472, 9473, 9468, -1, 9472, 9467, 9456, -1, 9472, 9456, 9466, -1, 9472, 9468, 9467, -1, 9474, 9470, 9475, -1, 9474, 9469, 9470, -1, 9476, 9471, 9464, -1, 9476, 9464, 9469, -1, 9477, 9473, 9472, -1, 9477, 9472, 9466, -1, 9477, 9478, 9473, -1, 9477, 9466, 9471, -1, 9479, 9475, 9480, -1, 9479, 9474, 9475, -1, 9481, 9476, 9469, -1, 9481, 9469, 9474, -1, 9482, 9471, 9476, -1, 9482, 9478, 9477, -1, 9482, 9483, 9478, -1, 9482, 9477, 9471, -1, 9484, 9480, 9485, -1, 9484, 9479, 9480, -1, 9427, 9481, 9474, -1, 9427, 9474, 9479, -1, 9486, 9476, 9481, -1, 9486, 9487, 9483, -1, 9486, 9483, 9482, -1, 9486, 9482, 9476, -1, 9448, 9485, 9488, -1, 9448, 9484, 9485, -1, 9428, 9427, 9479, -1, 9428, 9479, 9484, -1, 9489, 9463, 9462, -1, 9441, 9437, 9490, -1, 9430, 9426, 9487, -1, 9430, 9487, 9486, -1, 9441, 9435, 9437, -1, 9430, 9486, 9481, -1, 9429, 9490, 9422, -1, 9430, 9481, 9427, -1, 9438, 9488, 9432, -1, 9429, 9441, 9490, -1, 9438, 9448, 9488, -1, 9440, 9446, 9435, -1, 9449, 9428, 9484, -1, 9440, 9435, 9441, -1, 9449, 9484, 9448, -1, 9491, 9492, 9493, -1, 9494, 9492, 9495, -1, 9496, 9497, 9498, -1, 9499, 9497, 9496, -1, 9500, 9497, 9501, -1, 9501, 9497, 9499, -1, 9502, 9503, 9504, -1, 9505, 9506, 9507, -1, 9495, 9503, 9502, -1, 9498, 9506, 9505, -1, 9508, 9509, 9510, -1, 9507, 9506, 9511, -1, 9497, 9506, 9498, -1, 9512, 9513, 9514, -1, 9511, 9506, 9500, -1, 9500, 9506, 9497, -1, 9504, 9513, 9512, -1, 9515, 9516, 9517, -1, 9495, 9516, 9503, -1, 9492, 9516, 9495, -1, 9517, 9516, 9492, -1, 9503, 9518, 9504, -1, 9504, 9518, 9513, -1, 9514, 9519, 9520, -1, 9513, 9519, 9514, -1, 9521, 9522, 9515, -1, 9523, 9491, 9493, -1, 9515, 9522, 9516, -1, 9516, 9522, 9503, -1, 9503, 9522, 9518, -1, 9513, 9524, 9519, -1, 9518, 9524, 9513, -1, 9520, 9525, 9526, -1, 9519, 9525, 9520, -1, 9522, 9527, 9518, -1, 9528, 9527, 9521, -1, 9518, 9527, 9524, -1, 9521, 9527, 9522, -1, 9524, 9529, 9519, -1, 9519, 9529, 9525, -1, 9526, 9530, 9531, -1, 9525, 9530, 9526, -1, 9532, 9533, 9528, -1, 9528, 9533, 9527, -1, 9524, 9533, 9529, -1, 9527, 9533, 9524, -1, 9525, 9534, 9530, -1, 9529, 9534, 9525, -1, 9531, 9535, 9536, -1, 9530, 9535, 9531, -1, 9533, 9537, 9529, -1, 9529, 9537, 9534, -1, 9538, 9537, 9532, -1, 9532, 9537, 9533, -1, 9530, 9539, 9535, -1, 9534, 9539, 9530, -1, 9536, 9540, 9541, -1, 9535, 9540, 9536, -1, 9542, 9543, 9538, -1, 9538, 9543, 9537, -1, 9534, 9543, 9539, -1, 9537, 9543, 9534, -1, 9535, 9544, 9540, -1, 9539, 9544, 9535, -1, 9541, 9545, 9546, -1, 9540, 9545, 9541, -1, 9547, 9548, 9542, -1, 9542, 9548, 9543, -1, 9543, 9548, 9539, -1, 9539, 9548, 9544, -1, 9544, 9549, 9540, -1, 9540, 9549, 9545, -1, 9546, 9550, 9551, -1, 9545, 9550, 9546, -1, 9552, 9553, 9547, -1, 9547, 9553, 9548, -1, 9544, 9553, 9549, -1, 9548, 9553, 9544, -1, 9549, 9554, 9545, -1, 9545, 9554, 9550, -1, 9551, 9501, 9555, -1, 9550, 9501, 9551, -1, 9507, 9556, 9505, -1, 9557, 9558, 9552, -1, 9552, 9558, 9553, -1, 9549, 9558, 9554, -1, 9553, 9558, 9549, -1, 9508, 9502, 9509, -1, 9554, 9500, 9550, -1, 9494, 9495, 9508, -1, 9550, 9500, 9501, -1, 9559, 9499, 9496, -1, 9508, 9495, 9502, -1, 9560, 9499, 9559, -1, 9555, 9499, 9560, -1, 9509, 9504, 9512, -1, 9501, 9499, 9555, -1, 9502, 9504, 9509, -1, 9507, 9511, 9557, -1, 9557, 9511, 9558, -1, 9517, 9492, 9491, -1, 9554, 9511, 9500, -1, 9493, 9492, 9494, -1, 9558, 9511, 9554, -1, 9561, 9562, 9563, -1, 9564, 9565, 9566, -1, 9564, 9567, 9568, -1, 9561, 9569, 9562, -1, 9564, 9566, 9570, -1, 9564, 9570, 9567, -1, 9571, 9572, 9573, -1, 9571, 9573, 9574, -1, 9575, 9576, 9577, -1, 9571, 9578, 9572, -1, 9579, 9580, 9581, -1, 9579, 9581, 9569, -1, 9582, 9583, 9584, -1, 9582, 9585, 9586, -1, 9587, 9588, 9578, -1, 9582, 9584, 9585, -1, 9587, 9589, 9588, -1, 9582, 9586, 9580, -1, 9590, 9563, 9591, -1, 9592, 9593, 9565, -1, 9592, 9565, 9564, -1, 9592, 9564, 9568, -1, 9592, 9568, 9589, -1, 9590, 9561, 9563, -1, 9594, 9574, 9595, -1, 9594, 9571, 9574, -1, 9596, 9579, 9569, -1, 9594, 9578, 9571, -1, 9596, 9569, 9561, -1, 9594, 9587, 9578, -1, 9597, 9598, 9593, -1, 9599, 9600, 9583, -1, 9599, 9580, 9579, -1, 9597, 9593, 9592, -1, 9599, 9582, 9580, -1, 9599, 9583, 9582, -1, 9597, 9592, 9589, -1, 9597, 9589, 9587, -1, 9601, 9602, 9603, -1, 9604, 9591, 9605, -1, 9601, 9595, 9602, -1, 9601, 9603, 9598, -1, 9601, 9587, 9594, -1, 9601, 9597, 9587, -1, 9601, 9598, 9597, -1, 9601, 9594, 9595, -1, 9604, 9590, 9591, -1, 9606, 9561, 9590, -1, 9606, 9596, 9561, -1, 9607, 9608, 9600, -1, 9607, 9579, 9596, -1, 9607, 9599, 9579, -1, 9607, 9600, 9599, -1, 9609, 9605, 9610, -1, 9609, 9604, 9605, -1, 9611, 9590, 9604, -1, 9611, 9606, 9590, -1, 9612, 9613, 9608, -1, 9612, 9607, 9596, -1, 9612, 9596, 9606, -1, 9612, 9608, 9607, -1, 9614, 9610, 9615, -1, 9614, 9609, 9610, -1, 9616, 9611, 9604, -1, 9616, 9604, 9609, -1, 9617, 9613, 9612, -1, 9617, 9612, 9606, -1, 9617, 9618, 9613, -1, 9617, 9606, 9611, -1, 9619, 9615, 9620, -1, 9619, 9614, 9615, -1, 9621, 9616, 9609, -1, 9621, 9609, 9614, -1, 9622, 9611, 9616, -1, 9622, 9618, 9617, -1, 9622, 9623, 9618, -1, 9622, 9617, 9611, -1, 9624, 9620, 9625, -1, 9624, 9619, 9620, -1, 9567, 9621, 9614, -1, 9567, 9614, 9619, -1, 9626, 9616, 9621, -1, 9626, 9627, 9623, -1, 9626, 9623, 9622, -1, 9626, 9622, 9616, -1, 9588, 9625, 9628, -1, 9588, 9624, 9625, -1, 9568, 9567, 9619, -1, 9568, 9619, 9624, -1, 9629, 9603, 9602, -1, 9581, 9577, 9630, -1, 9570, 9566, 9627, -1, 9570, 9627, 9626, -1, 9581, 9575, 9577, -1, 9570, 9626, 9621, -1, 9569, 9630, 9562, -1, 9570, 9621, 9567, -1, 9578, 9628, 9572, -1, 9569, 9581, 9630, -1, 9578, 9588, 9628, -1, 9580, 9586, 9575, -1, 9589, 9568, 9624, -1, 9580, 9575, 9581, -1, 9589, 9624, 9588, -1, 9631, 9632, 9633, -1, 9633, 9632, 9634, -1, 9634, 9635, 9636, -1, 9632, 9635, 9634, -1, 9636, 9637, 9638, -1, 9635, 9637, 9636, -1, 9638, 9639, 9640, -1, 9637, 9639, 9638, -1, 9640, 9641, 9642, -1, 9639, 9641, 9640, -1, 9642, 9643, 9644, -1, 9641, 9643, 9642, -1, 9644, 9645, 9646, -1, 9643, 9645, 9644, -1, 9646, 9647, 9648, -1, 9645, 9647, 9646, -1, 9648, 9649, 9650, -1, 9647, 9649, 9648, -1, 9650, 9651, 9652, -1, 9649, 9651, 9650, -1, 9652, 9653, 9654, -1, 9651, 9653, 9652, -1, 9654, 9655, 9656, -1, 9653, 9655, 9654, -1, 9656, 9657, 9658, -1, 9655, 9657, 9656, -1, 9659, 9660, 9661, -1, 9661, 9660, 9662, -1, 9662, 9663, 9664, -1, 9660, 9663, 9662, -1, 9664, 9665, 9666, -1, 9663, 9665, 9664, -1, 9666, 9667, 9668, -1, 9665, 9667, 9666, -1, 9668, 9669, 9670, -1, 9667, 9669, 9668, -1, 9670, 9671, 9672, -1, 9669, 9671, 9670, -1, 9672, 9673, 9674, -1, 9671, 9673, 9672, -1, 9674, 9675, 9676, -1, 9673, 9675, 9674, -1, 9676, 9677, 9678, -1, 9675, 9677, 9676, -1, 9678, 9679, 9680, -1, 9677, 9679, 9678, -1, 9680, 9681, 9682, -1, 9679, 9681, 9680, -1, 9683, 9684, 9685, -1, 9682, 9684, 9683, -1, 9681, 9684, 9682, -1, 9684, 9686, 9685, -1, 9687, 9422, 9490, -1, 9687, 9688, 9689, -1, 9687, 9689, 9690, -1, 9687, 9690, 9422, -1, 9691, 9432, 9488, -1, 9691, 9433, 9432, -1, 9691, 9488, 9692, -1, 9693, 9694, 9418, -1, 9693, 9695, 9694, -1, 9693, 9418, 9433, -1, 9693, 9692, 9695, -1, 9693, 9691, 9692, -1, 9693, 9433, 9691, -1, 9696, 9437, 9436, -1, 9696, 9490, 9437, -1, 9696, 9436, 9385, -1, 9696, 9687, 9490, -1, 9697, 9698, 9688, -1, 9697, 9385, 9698, -1, 9697, 9687, 9696, -1, 9697, 9688, 9687, -1, 9697, 9696, 9385, -1, 9692, 9488, 9485, -1, 9692, 9699, 9695, -1, 9700, 9480, 9475, -1, 9700, 9485, 9480, -1, 9700, 9701, 9699, -1, 9700, 9702, 9701, -1, 9700, 9699, 9692, -1, 9700, 9692, 9485, -1, 9703, 9475, 9470, -1, 9703, 9704, 9702, -1, 9703, 9705, 9704, -1, 9703, 9702, 9700, -1, 9703, 9700, 9475, -1, 9706, 9465, 9451, -1, 9706, 9470, 9465, -1, 9706, 9707, 9705, -1, 9706, 9703, 9470, -1, 9706, 9705, 9703, -1, 9690, 9423, 9422, -1, 9690, 9451, 9423, -1, 9690, 9708, 9707, -1, 9690, 9689, 9708, -1, 9690, 9706, 9451, -1, 9690, 9707, 9706, -1, 9709, 9562, 9630, -1, 9709, 9710, 9711, -1, 9709, 9711, 9712, -1, 9709, 9712, 9562, -1, 9713, 9572, 9628, -1, 9713, 9573, 9572, -1, 9713, 9556, 9573, -1, 9713, 9628, 9714, -1, 9715, 9716, 9556, -1, 9715, 9717, 9716, -1, 9715, 9714, 9717, -1, 9715, 9713, 9714, -1, 9715, 9556, 9713, -1, 9718, 9577, 9576, -1, 9718, 9630, 9577, -1, 9718, 9709, 9630, -1, 9719, 9576, 9523, -1, 9719, 9720, 9710, -1, 9719, 9523, 9720, -1, 9719, 9709, 9718, -1, 9719, 9710, 9709, -1, 9719, 9718, 9576, -1, 9714, 9628, 9625, -1, 9714, 9721, 9717, -1, 9722, 9620, 9615, -1, 9722, 9625, 9620, -1, 9722, 9723, 9721, -1, 9722, 9724, 9723, -1, 9722, 9721, 9714, -1, 9722, 9714, 9625, -1, 9725, 9615, 9610, -1, 9725, 9726, 9724, -1, 9725, 9727, 9726, -1, 9725, 9724, 9722, -1, 9725, 9722, 9615, -1, 9728, 9605, 9591, -1, 9728, 9610, 9605, -1, 9728, 9729, 9727, -1, 9728, 9725, 9610, -1, 9728, 9727, 9725, -1, 9712, 9563, 9562, -1, 9712, 9591, 9563, -1, 9712, 9730, 9729, -1, 9712, 9711, 9730, -1, 9712, 9728, 9591, -1, 9712, 9729, 9728, -1, 9731, 9732, 9733, -1, 9734, 9735, 9736, -1, 9737, 9738, 9739, -1, 9731, 9740, 9732, -1, 9737, 9741, 9742, -1, 9737, 9739, 9743, -1, 9737, 9743, 9741, -1, 9744, 9745, 9740, -1, 9746, 9747, 9748, -1, 9746, 9748, 9749, -1, 9750, 9751, 9752, -1, 9746, 9753, 9747, -1, 9744, 9754, 9745, -1, 9755, 9756, 9757, -1, 9755, 9758, 9759, -1, 9760, 9736, 9753, -1, 9755, 9757, 9758, -1, 9760, 9734, 9736, -1, 9755, 9759, 9754, -1, 9761, 9733, 9762, -1, 9763, 9764, 9738, -1, 9763, 9738, 9737, -1, 9763, 9742, 9734, -1, 9763, 9737, 9742, -1, 9761, 9731, 9733, -1, 9765, 9749, 9766, -1, 9767, 9744, 9740, -1, 9765, 9746, 9749, -1, 9765, 9753, 9746, -1, 9767, 9740, 9731, -1, 9765, 9760, 9753, -1, 9768, 9734, 9760, -1, 9769, 9770, 9756, -1, 9768, 9771, 9764, -1, 9769, 9755, 9754, -1, 9768, 9763, 9734, -1, 9769, 9756, 9755, -1, 9768, 9764, 9763, -1, 9769, 9754, 9744, -1, 9772, 9773, 9774, -1, 9775, 9762, 9776, -1, 9772, 9766, 9773, -1, 9772, 9774, 9771, -1, 9772, 9771, 9768, -1, 9772, 9768, 9760, -1, 9775, 9761, 9762, -1, 9772, 9760, 9765, -1, 9772, 9765, 9766, -1, 9777, 9767, 9731, -1, 9777, 9731, 9761, -1, 9778, 9779, 9770, -1, 9778, 9769, 9744, -1, 9778, 9744, 9767, -1, 9778, 9770, 9769, -1, 9780, 9776, 9781, -1, 9780, 9775, 9776, -1, 9782, 9761, 9775, -1, 9782, 9777, 9761, -1, 9783, 9784, 9779, -1, 9783, 9767, 9777, -1, 9783, 9779, 9778, -1, 9783, 9778, 9767, -1, 9785, 9781, 9786, -1, 9785, 9780, 9781, -1, 9787, 9782, 9775, -1, 9787, 9775, 9780, -1, 9788, 9777, 9782, -1, 9788, 9789, 9784, -1, 9788, 9783, 9777, -1, 9788, 9784, 9783, -1, 9790, 9786, 9791, -1, 9790, 9785, 9786, -1, 9792, 9787, 9780, -1, 9792, 9780, 9785, -1, 9793, 9782, 9787, -1, 9793, 9789, 9788, -1, 9793, 9794, 9789, -1, 9793, 9788, 9782, -1, 9735, 9791, 9795, -1, 9735, 9790, 9791, -1, 9741, 9792, 9785, -1, 9741, 9785, 9790, -1, 9796, 9787, 9792, -1, 9796, 9793, 9787, -1, 9796, 9797, 9794, -1, 9796, 9794, 9793, -1, 9736, 9795, 9798, -1, 9736, 9735, 9795, -1, 9799, 9774, 9773, -1, 9742, 9741, 9790, -1, 9745, 9752, 9800, -1, 9742, 9790, 9735, -1, 9743, 9739, 9797, -1, 9745, 9750, 9752, -1, 9743, 9796, 9792, -1, 9743, 9797, 9796, -1, 9740, 9800, 9732, -1, 9743, 9792, 9741, -1, 9753, 9798, 9747, -1, 9740, 9745, 9800, -1, 9753, 9736, 9798, -1, 9754, 9759, 9750, -1, 9734, 9742, 9735, -1, 9754, 9750, 9745, -1, 9801, 9802, 9803, -1, 9804, 9805, 9806, -1, 9807, 9808, 9809, -1, 9809, 9808, 9810, -1, 9811, 9805, 9812, -1, 9813, 9808, 9814, -1, 9810, 9808, 9813, -1, 9815, 9816, 9817, -1, 9812, 9818, 9819, -1, 9814, 9816, 9801, -1, 9819, 9818, 9820, -1, 9802, 9816, 9815, -1, 9801, 9816, 9802, -1, 9821, 9822, 9823, -1, 9817, 9824, 9825, -1, 9820, 9822, 9821, -1, 9825, 9824, 9826, -1, 9826, 9824, 9807, -1, 9814, 9824, 9816, -1, 9827, 9828, 9829, -1, 9816, 9824, 9817, -1, 9812, 9828, 9818, -1, 9808, 9824, 9814, -1, 9807, 9824, 9808, -1, 9805, 9828, 9812, -1, 9829, 9828, 9805, -1, 9818, 9830, 9820, -1, 9820, 9830, 9822, -1, 9823, 9831, 9832, -1, 9822, 9831, 9823, -1, 9833, 9834, 9827, -1, 9835, 9804, 9806, -1, 9827, 9834, 9828, -1, 9828, 9834, 9818, -1, 9818, 9834, 9830, -1, 9822, 9836, 9831, -1, 9830, 9836, 9822, -1, 9832, 9837, 9838, -1, 9831, 9837, 9832, -1, 9834, 9839, 9830, -1, 9840, 9839, 9833, -1, 9830, 9839, 9836, -1, 9833, 9839, 9834, -1, 9836, 9841, 9831, -1, 9831, 9841, 9837, -1, 9838, 9842, 9843, -1, 9837, 9842, 9838, -1, 9844, 9845, 9840, -1, 9840, 9845, 9839, -1, 9836, 9845, 9841, -1, 9839, 9845, 9836, -1, 9837, 9846, 9842, -1, 9841, 9846, 9837, -1, 9843, 9847, 9848, -1, 9842, 9847, 9843, -1, 9845, 9849, 9841, -1, 9841, 9849, 9846, -1, 9850, 9849, 9844, -1, 9844, 9849, 9845, -1, 9842, 9851, 9847, -1, 9846, 9851, 9842, -1, 9848, 9852, 9853, -1, 9847, 9852, 9848, -1, 9854, 9855, 9850, -1, 9850, 9855, 9849, -1, 9846, 9855, 9851, -1, 9849, 9855, 9846, -1, 9847, 9856, 9852, -1, 9851, 9856, 9847, -1, 9853, 9857, 9858, -1, 9852, 9857, 9853, -1, 9859, 9860, 9854, -1, 9854, 9860, 9855, -1, 9855, 9860, 9851, -1, 9851, 9860, 9856, -1, 9856, 9861, 9852, -1, 9862, 9815, 9863, -1, 9852, 9861, 9857, -1, 9858, 9864, 9865, -1, 9857, 9864, 9858, -1, 9866, 9867, 9859, -1, 9859, 9867, 9860, -1, 9856, 9867, 9861, -1, 9860, 9867, 9856, -1, 9861, 9813, 9857, -1, 9857, 9813, 9864, -1, 9865, 9801, 9803, -1, 9864, 9801, 9865, -1, 9868, 9819, 9869, -1, 9809, 9810, 9866, -1, 9866, 9810, 9867, -1, 9861, 9810, 9813, -1, 9869, 9819, 9870, -1, 9867, 9810, 9861, -1, 9868, 9812, 9819, -1, 9811, 9812, 9868, -1, 9813, 9814, 9864, -1, 9864, 9814, 9801, -1, 9870, 9820, 9821, -1, 9819, 9820, 9870, -1, 9803, 9802, 9862, -1, 9829, 9805, 9804, -1, 9862, 9802, 9815, -1, 9806, 9805, 9811, -1, 9871, 9732, 9800, -1, 9871, 9872, 9873, -1, 9871, 9873, 9874, -1, 9871, 9874, 9732, -1, 9875, 9747, 9798, -1, 9875, 9748, 9747, -1, 9875, 9798, 9876, -1, 9877, 9878, 9826, -1, 9877, 9879, 9878, -1, 9877, 9826, 9748, -1, 9877, 9876, 9879, -1, 9877, 9875, 9876, -1, 9877, 9748, 9875, -1, 9880, 9752, 9751, -1, 9880, 9800, 9752, -1, 9880, 9751, 9835, -1, 9880, 9871, 9800, -1, 9881, 9882, 9872, -1, 9881, 9835, 9882, -1, 9881, 9871, 9880, -1, 9881, 9872, 9871, -1, 9881, 9880, 9835, -1, 9876, 9798, 9795, -1, 9876, 9883, 9879, -1, 9884, 9791, 9786, -1, 9884, 9795, 9791, -1, 9884, 9885, 9883, -1, 9884, 9886, 9885, -1, 9884, 9883, 9876, -1, 9884, 9876, 9795, -1, 9887, 9786, 9781, -1, 9887, 9888, 9886, -1, 9887, 9889, 9888, -1, 9887, 9886, 9884, -1, 9887, 9884, 9786, -1, 9890, 9776, 9762, -1, 9890, 9781, 9776, -1, 9890, 9891, 9889, -1, 9890, 9887, 9781, -1, 9890, 9889, 9887, -1, 9874, 9733, 9732, -1, 9874, 9762, 9733, -1, 9874, 9892, 9891, -1, 9874, 9873, 9892, -1, 9874, 9890, 9762, -1, 9874, 9891, 9890, -1, 9893, 9894, 9895, -1, 9896, 9894, 9893, -1, 9894, 9897, 9895, -1, 9895, 9897, 9898, -1, 9897, 9899, 9898, -1, 9900, 9901, 9902, -1, 9902, 9901, 9903, -1, 9903, 9904, 9905, -1, 9901, 9904, 9903, -1, 9905, 9906, 9907, -1, 9904, 9906, 9905, -1, 9907, 9908, 9909, -1, 9906, 9908, 9907, -1, 9910, 9911, 9912, -1, 9912, 9911, 9221, -1, 9221, 9911, 9223, -1, 9223, 9911, 9225, -1, 9225, 9911, 9226, -1, 9913, 9914, 9915, -1, 9909, 9914, 9913, -1, 9908, 9914, 9909, -1, 9915, 9916, 9917, -1, 9917, 9916, 9918, -1, 9918, 9916, 9910, -1, 9914, 9916, 9915, -1, 9910, 9916, 9911, -1, 9911, 9919, 9920, -1, 9916, 9919, 9911, -1, 9920, 9921, 9922, -1, 9919, 9921, 9920, -1, 9922, 9923, 9924, -1, 9921, 9923, 9922, -1, 9924, 9896, 9893, -1, 9923, 9896, 9924, -1, 9925, 9926, 9927, -1, 9926, 9928, 9927, -1, 9927, 9929, 9930, -1, 9928, 9929, 9927, -1, 9930, 9931, 9932, -1, 9929, 9931, 9930, -1, 9932, 9933, 9934, -1, 9931, 9933, 9932, -1, 9934, 9935, 9936, -1, 9933, 9935, 9934, -1, 9936, 9937, 9938, -1, 9935, 9937, 9936, -1, 9938, 9939, 9940, -1, 9937, 9939, 9938, -1, 9940, 9941, 9942, -1, 9939, 9941, 9940, -1, 9942, 9943, 9944, -1, 9941, 9943, 9942, -1, 9944, 9945, 9946, -1, 9943, 9945, 9944, -1, 9946, 9947, 9948, -1, 9945, 9947, 9946, -1, 9949, 9950, 9951, -1, 9948, 9950, 9949, -1, 9947, 9950, 9948, -1, 9950, 9952, 9951, -1, 9953, 9954, 9955, -1, 9955, 9956, 9957, -1, 9954, 9956, 9955, -1, 9957, 9958, 9959, -1, 9956, 9958, 9957, -1, 9959, 9960, 9961, -1, 9958, 9960, 9959, -1, 9961, 9962, 9963, -1, 9960, 9962, 9961, -1, 9963, 9964, 9965, -1, 9962, 9964, 9963, -1, 9965, 9966, 9967, -1, 9964, 9966, 9965, -1, 9967, 9968, 9969, -1, 9966, 9968, 9967, -1, 9969, 9970, 9971, -1, 9968, 9970, 9969, -1, 9971, 9972, 9973, -1, 9970, 9972, 9971, -1, 9973, 9974, 9975, -1, 9972, 9974, 9973, -1, 9975, 9976, 9977, -1, 9974, 9976, 9975, -1, 9976, 9978, 9977, -1, 9977, 9979, 9980, -1, 9978, 9979, 9977, -1, 9981, 9982, 9983, -1, 9983, 9984, 9985, -1, 9982, 9984, 9983, -1, 9985, 9986, 9987, -1, 9984, 9986, 9985, -1, 9987, 9988, 9989, -1, 9986, 9988, 9987, -1, 9989, 9990, 9991, -1, 9988, 9990, 9989, -1, 9991, 9992, 9993, -1, 9990, 9992, 9991, -1, 9993, 9994, 9995, -1, 9992, 9994, 9993, -1, 9995, 9996, 9997, -1, 9994, 9996, 9995, -1, 9997, 9998, 9999, -1, 9996, 9998, 9997, -1, 9999, 10000, 10001, -1, 9998, 10000, 9999, -1, 10001, 10002, 10003, -1, 10000, 10002, 10001, -1, 10003, 10004, 10005, -1, 10002, 10004, 10003, -1, 10005, 10006, 10007, -1, 10004, 10006, 10005, -1, 10006, 10008, 10007, -1, 10009, 10010, 10011, -1, 10011, 10010, 10012, -1, 10013, 10014, 10015, -1, 10012, 10014, 10013, -1, 10010, 10014, 10012, -1, 10014, 10016, 10015, -1, 10017, 10018, 10019, -1, 10019, 10018, 10020, -1, 10021, 10022, 10023, -1, 10020, 10022, 10021, -1, 10018, 10022, 10020, -1, 10022, 10024, 10023, -1, 10025, 10026, 10027, -1, 10027, 10026, 10028, -1, 10029, 10030, 10031, -1, 10028, 10030, 10029, -1, 10026, 10030, 10028, -1, 10030, 10032, 10031, -1, 10033, 10034, 10035, -1, 10035, 10034, 10036, -1, 10037, 10038, 10039, -1, 10036, 10038, 10037, -1, 10034, 10038, 10036, -1, 10038, 10040, 10039, -1, 10041, 10042, 10043, -1, 10043, 10042, 10044, -1, 10045, 10046, 10047, -1, 10044, 10046, 10045, -1, 10042, 10046, 10044, -1, 10046, 10048, 10047, -1, 10049, 10050, 10051, -1, 10051, 10050, 10052, -1, 10053, 10054, 10055, -1, 10052, 10054, 10053, -1, 10050, 10054, 10052, -1, 10054, 10056, 10055, -1, 10057, 10058, 10059, -1, 10059, 10058, 10060, -1, 10061, 10062, 10063, -1, 10060, 10062, 10061, -1, 10058, 10062, 10060, -1, 10062, 10064, 10063, -1, 10065, 10066, 10067, -1, 10067, 10066, 10068, -1, 10069, 10070, 10071, -1, 10068, 10070, 10069, -1, 10066, 10070, 10068, -1, 10070, 10072, 10071, -1, 10073, 10074, 10075, -1, 10075, 10074, 10076, -1, 10077, 10078, 10079, -1, 10076, 10078, 10077, -1, 10074, 10078, 10076, -1, 10078, 10080, 10079, -1, 10081, 10082, 10083, -1, 10083, 10082, 10084, -1, 10085, 10086, 10087, -1, 10084, 10086, 10085, -1, 10082, 10086, 10084, -1, 10086, 10088, 10087, -1, 10089, 10090, 10091, -1, 10091, 10090, 10092, -1, 10093, 10094, 10095, -1, 10092, 10094, 10093, -1, 10090, 10094, 10092, -1, 10094, 10096, 10095, -1, 10097, 10098, 10099, -1, 10100, 10101, 10098, -1, 10100, 10098, 10097, -1, 10102, 10101, 10100, -1, 10103, 10101, 10102, -1, 10104, 10105, 10101, -1, 10104, 10101, 10103, -1, 10106, 10104, 10103, -1, 10107, 10104, 10106, -1, 10104, 10108, 10105, -1, 10109, 10108, 10104, -1, 10110, 10109, 10104, -1, 10111, 10110, 10104, -1, 10107, 10111, 10104, -1, 10112, 10113, 10108, -1, 10114, 10112, 10108, -1, 10109, 10114, 10108, -1, 10115, 10116, 10117, -1, 10115, 10118, 10116, -1, 10119, 10120, 10115, -1, 10115, 10120, 10118, -1, 10121, 10122, 10123, -1, 10123, 10122, 10124, -1, 10124, 10122, 10125, -1, 10126, 10127, 10128, -1, 10129, 10130, 10131, -1, 10132, 10133, 10134, -1, 10131, 10130, 10135, -1, 10131, 10136, 10129, -1, 10137, 10133, 10132, -1, 10129, 10136, 10138, -1, 10138, 10136, 10139, -1, 10140, 10141, 10142, -1, 10142, 10141, 10143, -1, 10142, 10144, 10140, -1, 10140, 10144, 10145, -1, 10145, 10144, 10146, -1, 10147, 10148, 10149, -1, 10149, 10148, 10150, -1, 10151, 10152, 10153, -1, 10149, 10154, 10147, -1, 10155, 10156, 10157, -1, 10147, 10154, 10158, -1, 10157, 10156, 10159, -1, 10158, 10154, 10160, -1, 10161, 10162, 10163, -1, 10163, 10162, 10164, -1, 10163, 10165, 10161, -1, 10161, 10165, 10166, -1, 10153, 10152, 10167, -1, 10166, 10165, 10168, -1, 10169, 10170, 10171, -1, 10151, 10172, 10152, -1, 10155, 10173, 10156, -1, 10171, 10170, 10174, -1, 10171, 10175, 10169, -1, 10169, 10175, 10176, -1, 10176, 10175, 10177, -1, 10178, 10179, 10180, -1, 10173, 10181, 10156, -1, 10182, 10183, 9863, -1, 10182, 9863, 10184, -1, 9863, 10183, 9862, -1, 10126, 10185, 10127, -1, 10186, 10187, 8618, -1, 10181, 9823, 10156, -1, 10186, 8618, 10188, -1, 10186, 10188, 10189, -1, 8618, 10187, 10190, -1, 10151, 10191, 10172, -1, 10190, 10187, 8562, -1, 9823, 9832, 10156, -1, 8562, 10187, 10192, -1, 10192, 10187, 9032, -1, 9032, 10187, 10193, -1, 10181, 9821, 9823, -1, 10193, 10187, 8667, -1, 8667, 10187, 10194, -1, 10194, 10187, 8716, -1, 8716, 10187, 10195, -1, 10195, 10187, 8765, -1, 9832, 9838, 10156, -1, 8765, 10187, 10196, -1, 10196, 10187, 8814, -1, 8814, 10187, 10197, -1, 10197, 10187, 8863, -1, 8863, 10187, 10198, -1, 10181, 9870, 9821, -1, 10198, 10187, 9199, -1, 10126, 10199, 10185, -1, 9838, 9843, 10156, -1, 10181, 9869, 9870, -1, 10151, 10200, 10191, -1, 10201, 10199, 10126, -1, 10181, 10202, 9869, -1, 10201, 8548, 10199, -1, 10151, 10203, 10200, -1, 10204, 8548, 10201, -1, 10205, 10203, 10151, -1, 10206, 10207, 10208, -1, 10208, 10207, 10136, -1, 10204, 8546, 8548, -1, 9848, 10209, 9843, -1, 10156, 10209, 10210, -1, 9843, 10209, 10156, -1, 10211, 8546, 10204, -1, 10205, 8751, 10203, -1, 9853, 10212, 9848, -1, 9848, 10212, 10209, -1, 10213, 8751, 10205, -1, 10211, 8555, 8546, -1, 10214, 8555, 10211, -1, 9858, 10215, 9853, -1, 10216, 10217, 10218, -1, 10218, 10217, 10219, -1, 9853, 10215, 10212, -1, 10214, 8561, 8555, -1, 10220, 8561, 10214, -1, 9858, 10183, 10215, -1, 10213, 8749, 8751, -1, 10220, 8562, 8561, -1, 9858, 9865, 10183, -1, 10221, 8749, 10213, -1, 10190, 8562, 10220, -1, 10221, 8758, 8749, -1, 10222, 8758, 10221, -1, 9865, 9803, 10183, -1, 10223, 8764, 10222, -1, 10222, 8764, 8758, -1, 10195, 8765, 10223, -1, 10223, 8765, 8764, -1, 10224, 10225, 10226, -1, 10227, 10225, 10224, -1, 10228, 10178, 10175, -1, 10229, 10178, 10228, -1, 9803, 9862, 10183, -1, 10136, 10230, 10139, -1, 10207, 10230, 10136, -1, 10231, 10232, 10233, -1, 10234, 10232, 10231, -1, 10202, 10235, 10236, -1, 10236, 10235, 10237, -1, 10237, 10235, 10238, -1, 10234, 10239, 10232, -1, 10181, 10235, 10202, -1, 10217, 10240, 10219, -1, 10234, 10241, 10239, -1, 10219, 10240, 10242, -1, 10243, 10244, 10245, -1, 10245, 10244, 10246, -1, 10243, 10247, 10244, -1, 10243, 10248, 10247, -1, 10234, 10249, 10241, -1, 10178, 10250, 10175, -1, 10243, 10251, 10248, -1, 10175, 10250, 10177, -1, 10252, 10253, 10234, -1, 10254, 10255, 10243, -1, 10234, 10253, 10249, -1, 10243, 10255, 10251, -1, 10256, 8800, 10254, -1, 10254, 8800, 10255, -1, 10257, 9018, 10252, -1, 10252, 9018, 10253, -1, 10258, 10259, 10260, -1, 10260, 10259, 10261, -1, 10262, 8798, 10256, -1, 10263, 10153, 10264, -1, 10264, 10153, 10122, -1, 10256, 8798, 8800, -1, 10238, 10186, 10265, -1, 10262, 8807, 8798, -1, 10265, 10186, 10266, -1, 10261, 10186, 10267, -1, 10267, 10186, 10268, -1, 10257, 9016, 9018, -1, 10268, 10186, 10269, -1, 10269, 10186, 10270, -1, 10270, 10186, 10271, -1, 10271, 10186, 10235, -1, 10272, 8807, 10262, -1, 10235, 10186, 10238, -1, 10259, 10186, 10261, -1, 10272, 8813, 8807, -1, 10186, 10273, 10266, -1, 10274, 9016, 10257, -1, 10275, 8813, 10272, -1, 10276, 9025, 10274, -1, 10196, 8814, 10275, -1, 10274, 9025, 9016, -1, 10275, 8814, 8813, -1, 10277, 9031, 10276, -1, 10276, 9031, 9025, -1, 10192, 9032, 10277, -1, 10277, 9032, 9031, -1, 10278, 10279, 10280, -1, 10280, 10279, 10165, -1, 10281, 10282, 10283, -1, 10284, 10285, 10137, -1, 10137, 10285, 10133, -1, 10284, 10286, 10285, -1, 10284, 10287, 10286, -1, 10279, 10288, 10165, -1, 10165, 10288, 10168, -1, 10289, 10182, 10290, -1, 10281, 10291, 10282, -1, 10122, 10167, 10125, -1, 10290, 10182, 10184, -1, 10153, 10167, 10122, -1, 10292, 10293, 10294, -1, 10295, 10293, 10292, -1, 10296, 10297, 10289, -1, 10289, 10297, 10182, -1, 10284, 10298, 10287, -1, 10295, 10299, 10293, -1, 10296, 10300, 10297, -1, 10301, 10302, 10284, -1, 10284, 10302, 10298, -1, 10295, 10303, 10299, -1, 10304, 10305, 10296, -1, 10306, 8849, 10301, -1, 10301, 8849, 10302, -1, 10296, 10305, 10300, -1, 10307, 10308, 10309, -1, 10309, 10308, 10291, -1, 10295, 10310, 10303, -1, 10311, 8847, 10306, -1, 10304, 10312, 10305, -1, 10306, 8847, 8849, -1, 10313, 10314, 10295, -1, 10315, 8856, 10311, -1, 10295, 10314, 10310, -1, 10316, 10231, 10317, -1, 10311, 8856, 8847, -1, 10317, 10231, 10154, -1, 10318, 8862, 10315, -1, 10273, 10319, 10304, -1, 10315, 8862, 8856, -1, 10186, 10319, 10273, -1, 10313, 8653, 10314, -1, 10304, 10319, 10312, -1, 10197, 8863, 10318, -1, 10320, 8653, 10313, -1, 10318, 8863, 8862, -1, 10186, 10321, 10319, -1, 10322, 10245, 10323, -1, 10323, 10245, 10324, -1, 10186, 10325, 10321, -1, 10186, 10326, 10325, -1, 10327, 8651, 10320, -1, 10320, 8651, 8653, -1, 10186, 10189, 10326, -1, 10328, 8660, 10327, -1, 10329, 10330, 10217, -1, 10327, 8660, 8651, -1, 10331, 8666, 10328, -1, 10329, 10332, 10330, -1, 10328, 8666, 8660, -1, 10331, 8667, 8666, -1, 10193, 8667, 10331, -1, 10329, 10333, 10332, -1, 10329, 10334, 10333, -1, 10329, 10335, 10334, -1, 10336, 10335, 10329, -1, 10337, 9185, 10336, -1, 10336, 9185, 10335, -1, 10231, 10233, 10154, -1, 10154, 10233, 10160, -1, 10338, 9183, 10337, -1, 10337, 9183, 9185, -1, 10178, 10180, 10250, -1, 10339, 9192, 10338, -1, 10338, 9192, 9183, -1, 10179, 10340, 10180, -1, 10245, 10246, 10324, -1, 10341, 9198, 10339, -1, 10339, 9198, 9192, -1, 10324, 10246, 10342, -1, 10207, 10343, 10230, -1, 10198, 9199, 10341, -1, 10344, 10343, 10207, -1, 10179, 10345, 10340, -1, 10341, 9199, 9198, -1, 10344, 10346, 10343, -1, 10344, 10347, 10346, -1, 10179, 10348, 10345, -1, 10349, 10350, 10179, -1, 10344, 10351, 10347, -1, 10352, 10353, 10354, -1, 10179, 10350, 10348, -1, 10352, 10355, 10353, -1, 10356, 8604, 10349, -1, 10344, 10357, 10351, -1, 10349, 8604, 10350, -1, 10358, 10359, 10352, -1, 10360, 10357, 10344, -1, 10361, 10292, 10362, -1, 10362, 10292, 10144, -1, 10352, 10359, 10355, -1, 10358, 10363, 10359, -1, 10364, 8602, 10356, -1, 10358, 10365, 10363, -1, 10356, 8602, 8604, -1, 10366, 8702, 10360, -1, 10360, 8702, 10357, -1, 10367, 10137, 10368, -1, 10368, 10137, 10132, -1, 10369, 8611, 10364, -1, 10370, 10365, 10358, -1, 10364, 8611, 8602, -1, 10370, 10371, 10365, -1, 10372, 8617, 10369, -1, 10369, 8617, 8611, -1, 10373, 10371, 10374, -1, 10366, 8700, 8702, -1, 10374, 10371, 10370, -1, 10373, 10375, 10371, -1, 10376, 8700, 10366, -1, 10188, 8618, 10372, -1, 10372, 8618, 8617, -1, 10376, 8709, 8700, -1, 10377, 10375, 10373, -1, 10378, 8709, 10376, -1, 10377, 10379, 10375, -1, 10378, 8715, 8709, -1, 10380, 10379, 10377, -1, 10381, 8715, 10378, -1, 10380, 10382, 10379, -1, 10381, 8716, 8715, -1, 10194, 8716, 10381, -1, 10380, 10187, 10382, -1, 10383, 10187, 10308, -1, 10308, 10187, 10291, -1, 10292, 10294, 10144, -1, 10384, 10187, 10385, -1, 10144, 10294, 10146, -1, 10385, 10187, 10386, -1, 10386, 10187, 10387, -1, 10387, 10187, 10388, -1, 10388, 10187, 10389, -1, 10389, 10187, 10383, -1, 10390, 10187, 10384, -1, 10382, 10187, 10390, -1, 10391, 10187, 10380, -1, 9199, 10187, 10391, -1, 10126, 10392, 10279, -1, 10291, 10187, 10282, -1, 10330, 10240, 10217, -1, 10227, 10219, 10225, -1, 10225, 10219, 10393, -1, 10393, 10219, 10242, -1, 10394, 10395, 10396, -1, 10279, 10392, 10288, -1, 10396, 10395, 10397, -1, 10396, 10132, 10394, -1, 10394, 10132, 10398, -1, 10398, 10132, 10134, -1, 10399, 10400, 10401, -1, 10401, 10400, 10402, -1, 10401, 10324, 10399, -1, 10399, 10324, 10403, -1, 10403, 10324, 10342, -1, 10123, 10404, 10121, -1, 10126, 10128, 10392, -1, 10121, 10404, 10405, -1, 10406, 10407, 10408, -1, 10409, 10407, 10406, -1, 10410, 10407, 10409, -1, 10411, 10087, 10088, -1, 10412, 10413, 10411, -1, 10411, 10413, 10087, -1, 10413, 10414, 10087, -1, 10415, 10416, 10417, -1, 10415, 10418, 10416, -1, 10418, 10419, 10416, -1, 9514, 9520, 9414, -1, 9420, 9512, 9417, -1, 10420, 10421, 10422, -1, 9417, 9512, 9514, -1, 10423, 10095, 9536, -1, 10096, 10420, 10424, -1, 10096, 10424, 10425, -1, 10096, 10425, 10426, -1, 9409, 9526, 9404, -1, 9520, 9526, 9409, -1, 9369, 9382, 10095, -1, 10095, 9367, 9369, -1, 9419, 9509, 9420, -1, 9382, 9389, 10095, -1, 9420, 9509, 9512, -1, 10095, 9371, 9367, -1, 9526, 9531, 9404, -1, 9404, 9531, 10095, -1, 9389, 9394, 10095, -1, 10427, 9510, 9419, -1, 10095, 9372, 9371, -1, 9419, 9510, 9509, -1, 9531, 9536, 10095, -1, 9394, 9399, 10095, -1, 10427, 10428, 9510, -1, 10429, 10428, 10427, -1, 9399, 9404, 10095, -1, 10430, 10431, 10429, -1, 10429, 10431, 10428, -1, 10432, 10433, 10430, -1, 10430, 10433, 10431, -1, 10096, 10433, 10432, -1, 10096, 10426, 10433, -1, 9372, 10096, 10434, -1, 10434, 10096, 10435, -1, 10435, 10096, 10436, -1, 10436, 10096, 10437, -1, 10437, 10096, 10438, -1, 10095, 10096, 9372, -1, 10096, 10439, 10438, -1, 10096, 10440, 10439, -1, 10096, 10441, 10440, -1, 10096, 10432, 10441, -1, 9559, 10422, 9560, -1, 9560, 10422, 9555, -1, 9555, 10422, 9551, -1, 10442, 10422, 9559, -1, 9551, 10423, 9546, -1, 9417, 9514, 9414, -1, 9546, 10423, 9541, -1, 9541, 10423, 9536, -1, 10422, 10423, 9551, -1, 10424, 10420, 10443, -1, 10443, 10420, 10444, -1, 10444, 10420, 10445, -1, 10445, 10420, 10446, -1, 10446, 10420, 10447, -1, 10447, 10420, 10442, -1, 9414, 9520, 9409, -1, 10442, 10420, 10422, -1, 10448, 10449, 10450, -1, 10451, 9125, 9148, -1, 10452, 9126, 10453, -1, 10453, 9126, 10454, -1, 10454, 9126, 10455, -1, 10455, 9126, 10456, -1, 10456, 9126, 10451, -1, 10451, 9126, 9125, -1, 10449, 10457, 10452, -1, 10452, 10457, 9126, -1, 10449, 10458, 10457, -1, 10449, 10459, 10458, -1, 10449, 10460, 10459, -1, 10461, 10462, 10463, -1, 10463, 10462, 10460, -1, 10462, 10464, 10465, -1, 10461, 10464, 10462, -1, 10452, 10450, 10449, -1, 10449, 10463, 10460, -1, 10466, 10467, 10468, -1, 10467, 10469, 10468, -1, 10470, 10471, 10472, -1, 10471, 10473, 10472, -1, 10474, 10475, 10476, -1, 10475, 10477, 10476, -1, 10024, 10478, 10023, -1, 10479, 10478, 10024, -1, 10478, 10480, 10023, -1, 10481, 10482, 10483, -1, 10482, 10484, 10483, -1, 10016, 10485, 10015, -1, 10486, 10485, 10016, -1, 10485, 10487, 10015, -1, 10488, 10489, 10490, -1, 10489, 10491, 10490, -1, 10072, 10492, 10071, -1, 10493, 10492, 10072, -1, 10492, 10494, 10071, -1, 10495, 10496, 10497, -1, 10496, 10498, 10497, -1, 10032, 10499, 10031, -1, 10500, 10499, 10032, -1, 10499, 10501, 10031, -1, 10502, 10503, 10504, -1, 10503, 10505, 10504, -1, 10040, 10506, 10039, -1, 10507, 10506, 10040, -1, 10506, 10508, 10039, -1, 10509, 10510, 10511, -1, 10510, 10512, 10511, -1, 10048, 10513, 10047, -1, 10514, 10513, 10048, -1, 10513, 10515, 10047, -1, 10516, 10517, 10518, -1, 10517, 10519, 10518, -1, 10056, 10520, 10055, -1, 10521, 10520, 10056, -1, 10520, 10522, 10055, -1, 10523, 10524, 10525, -1, 10524, 10526, 10525, -1, 10064, 10527, 10063, -1, 10528, 10527, 10064, -1, 10527, 10529, 10063, -1, 10080, 10530, 10079, -1, 10531, 10530, 10080, -1, 10530, 10532, 10079, -1, 10187, 10533, 10282, -1, 10282, 10533, 10534, -1, 10534, 10535, 10536, -1, 10533, 10535, 10534, -1, 10536, 10537, 10538, -1, 10535, 10537, 10536, -1, 10538, 10539, 10540, -1, 10537, 10539, 10538, -1, 10540, 10541, 10542, -1, 10539, 10541, 10540, -1, 10542, 10089, 10091, -1, 10541, 10089, 10542, -1, 10281, 10543, 10291, -1, 10291, 10544, 10545, -1, 10543, 10544, 10291, -1, 10544, 10546, 10545, -1, 10545, 10547, 10548, -1, 10548, 10547, 10549, -1, 10546, 10547, 10545, -1, 10549, 10550, 10551, -1, 10547, 10550, 10549, -1, 10551, 10552, 10553, -1, 10550, 10552, 10551, -1, 10553, 10554, 10555, -1, 10552, 10554, 10553, -1, 10555, 10556, 10472, -1, 10554, 10556, 10555, -1, 10556, 10470, 10472, -1, 10281, 10283, 10543, -1, 10543, 10283, 10544, -1, 10544, 10283, 10546, -1, 10408, 10407, 10557, -1, 10557, 10558, 10559, -1, 10407, 10558, 10557, -1, 10559, 10560, 10561, -1, 10558, 10560, 10559, -1, 10561, 10562, 10563, -1, 10560, 10562, 10561, -1, 10563, 10564, 10565, -1, 10562, 10564, 10563, -1, 10565, 10081, 10083, -1, 10564, 10081, 10565, -1, 10226, 10225, 10566, -1, 10566, 10567, 10568, -1, 10225, 10567, 10566, -1, 10568, 10569, 10570, -1, 10567, 10569, 10568, -1, 10570, 10571, 10572, -1, 10569, 10571, 10570, -1, 10572, 10573, 10574, -1, 10571, 10573, 10572, -1, 10574, 10073, 10075, -1, 10573, 10073, 10574, -1, 10409, 10575, 10410, -1, 10410, 10576, 10577, -1, 10575, 10576, 10410, -1, 10576, 10578, 10577, -1, 10577, 10579, 10580, -1, 10580, 10579, 10581, -1, 10578, 10579, 10577, -1, 10581, 10582, 10583, -1, 10579, 10582, 10581, -1, 10583, 10584, 10585, -1, 10582, 10584, 10583, -1, 10585, 10586, 10587, -1, 10584, 10586, 10585, -1, 10587, 10588, 10417, -1, 10586, 10588, 10587, -1, 10588, 10415, 10417, -1, 10409, 10406, 10575, -1, 10575, 10406, 10576, -1, 10576, 10406, 10578, -1, 10589, 10590, 10591, -1, 10592, 10590, 10589, -1, 10590, 10593, 10591, -1, 10593, 10594, 10591, -1, 10595, 10596, 10597, -1, 10596, 10598, 10597, -1, 10598, 10599, 10597, -1, 10599, 10600, 10597, -1, 10600, 10601, 10597, -1, 10600, 10602, 10601, -1, 10603, 10604, 10605, -1, 10604, 10606, 10605, -1, 10606, 10607, 10605, -1, 10608, 10609, 10610, -1, 10609, 10611, 10610, -1, 10611, 10612, 10610, -1, 10613, 10614, 10615, -1, 10614, 10616, 10615, -1, 10616, 10617, 10615, -1, 10618, 10619, 10620, -1, 10619, 10621, 10620, -1, 10621, 10622, 10620, -1, 10623, 10624, 10625, -1, 10624, 10626, 10625, -1, 10626, 10627, 10625, -1, 10628, 10629, 10630, -1, 10629, 10631, 10630, -1, 10631, 10632, 10630, -1, 10633, 10634, 10635, -1, 10634, 10636, 10635, -1, 10636, 10637, 10635, -1, 10638, 10639, 10640, -1, 10639, 10641, 10640, -1, 10641, 10642, 10640, -1, 10643, 10644, 10645, -1, 10644, 10646, 10645, -1, 10646, 10647, 10645, -1, 10647, 10648, 10645, -1, 10648, 10113, 10645, -1, 10648, 10108, 10113, -1, 10648, 10105, 10108, -1, 10649, 10650, 10651, -1, 10651, 10652, 10653, -1, 10650, 10652, 10651, -1, 10653, 10654, 10655, -1, 10655, 10654, 10656, -1, 10652, 10654, 10653, -1, 10656, 10657, 10658, -1, 10654, 10657, 10656, -1, 10658, 10659, 10660, -1, 10657, 10659, 10658, -1, 10661, 10662, 10663, -1, 10660, 10662, 10661, -1, 10659, 10662, 10660, -1, 10664, 10665, 10666, -1, 10663, 10665, 10664, -1, 10662, 10665, 10663, -1, 10667, 10668, 10669, -1, 10666, 10668, 10667, -1, 10665, 10668, 10666, -1, 10669, 10491, 10489, -1, 10668, 10491, 10669, -1, 10635, 10670, 10633, -1, 10633, 10670, 10671, -1, 10671, 10672, 10673, -1, 10670, 10672, 10671, -1, 10672, 10674, 10673, -1, 10674, 10675, 10673, -1, 10673, 10494, 10492, -1, 10675, 10494, 10673, -1, 10148, 10147, 10676, -1, 10676, 10677, 10678, -1, 10147, 10677, 10676, -1, 10678, 10679, 10680, -1, 10677, 10679, 10678, -1, 10680, 10681, 10682, -1, 10679, 10681, 10680, -1, 10682, 10683, 10684, -1, 10681, 10683, 10682, -1, 10684, 10065, 10067, -1, 10683, 10065, 10684, -1, 10142, 10685, 10144, -1, 10144, 10686, 10687, -1, 10685, 10686, 10144, -1, 10686, 10688, 10687, -1, 10687, 10689, 10690, -1, 10690, 10689, 10691, -1, 10688, 10689, 10687, -1, 10691, 10692, 10693, -1, 10689, 10692, 10691, -1, 10693, 10694, 10695, -1, 10692, 10694, 10693, -1, 10695, 10696, 10697, -1, 10694, 10696, 10695, -1, 10697, 10698, 10490, -1, 10696, 10698, 10697, -1, 10698, 10488, 10490, -1, 10142, 10143, 10685, -1, 10685, 10143, 10686, -1, 10686, 10143, 10688, -1, 10699, 10700, 10701, -1, 10701, 10702, 10703, -1, 10700, 10702, 10701, -1, 10703, 10704, 10705, -1, 10705, 10704, 10706, -1, 10702, 10704, 10703, -1, 10706, 10707, 10708, -1, 10704, 10707, 10706, -1, 10708, 10709, 10710, -1, 10707, 10709, 10708, -1, 10711, 10712, 10713, -1, 10710, 10712, 10711, -1, 10709, 10712, 10710, -1, 10714, 10715, 10716, -1, 10713, 10715, 10714, -1, 10712, 10715, 10713, -1, 10717, 10718, 10719, -1, 10716, 10718, 10717, -1, 10715, 10718, 10716, -1, 10719, 10477, 10475, -1, 10718, 10477, 10719, -1, 10643, 10645, 10720, -1, 10645, 10721, 10720, -1, 10720, 10722, 10723, -1, 10721, 10722, 10720, -1, 10722, 10724, 10723, -1, 10724, 10725, 10723, -1, 10723, 10480, 10478, -1, 10725, 10480, 10723, -1, 10726, 10727, 10728, -1, 10728, 10729, 10730, -1, 10727, 10729, 10728, -1, 10730, 10731, 10732, -1, 10732, 10731, 10733, -1, 10729, 10731, 10730, -1, 10733, 10734, 10735, -1, 10731, 10734, 10733, -1, 10735, 10736, 10737, -1, 10734, 10736, 10735, -1, 10738, 10739, 10740, -1, 10737, 10739, 10738, -1, 10736, 10739, 10737, -1, 10741, 10742, 10743, -1, 10740, 10742, 10741, -1, 10739, 10742, 10740, -1, 10744, 10745, 10746, -1, 10743, 10745, 10744, -1, 10742, 10745, 10743, -1, 10746, 10484, 10482, -1, 10745, 10484, 10746, -1, 10640, 10747, 10638, -1, 10638, 10747, 10748, -1, 10748, 10749, 10750, -1, 10747, 10749, 10748, -1, 10749, 10751, 10750, -1, 10751, 10752, 10750, -1, 10750, 10487, 10485, -1, 10752, 10487, 10750, -1, 10753, 10754, 10755, -1, 10755, 10756, 10757, -1, 10754, 10756, 10755, -1, 10757, 10758, 10759, -1, 10759, 10758, 10760, -1, 10756, 10758, 10757, -1, 10760, 10761, 10762, -1, 10758, 10761, 10760, -1, 10762, 10763, 10764, -1, 10761, 10763, 10762, -1, 10765, 10766, 10767, -1, 10764, 10766, 10765, -1, 10763, 10766, 10764, -1, 10768, 10769, 10770, -1, 10767, 10769, 10768, -1, 10766, 10769, 10767, -1, 10771, 10772, 10773, -1, 10770, 10772, 10771, -1, 10769, 10772, 10770, -1, 10773, 10498, 10496, -1, 10772, 10498, 10773, -1, 10630, 10774, 10628, -1, 10628, 10774, 10775, -1, 10775, 10776, 10777, -1, 10774, 10776, 10775, -1, 10776, 10778, 10777, -1, 10778, 10779, 10777, -1, 10777, 10501, 10499, -1, 10779, 10501, 10777, -1, 10780, 10119, 10115, -1, 10781, 10782, 10780, -1, 10780, 10782, 10119, -1, 10781, 10783, 10782, -1, 10781, 10601, 10783, -1, 10601, 10602, 10783, -1, 10120, 10784, 10118, -1, 10118, 10784, 10116, -1, 10116, 10785, 10117, -1, 10117, 10785, 10786, -1, 10784, 10785, 10116, -1, 10787, 10788, 10789, -1, 10786, 10788, 10787, -1, 10785, 10788, 10786, -1, 10789, 10790, 10791, -1, 10788, 10790, 10789, -1, 10791, 10792, 10793, -1, 10790, 10792, 10791, -1, 10794, 10795, 10796, -1, 10793, 10795, 10794, -1, 10792, 10795, 10793, -1, 10797, 10798, 10799, -1, 10796, 10798, 10797, -1, 10795, 10798, 10796, -1, 10800, 10801, 10802, -1, 10799, 10801, 10800, -1, 10798, 10801, 10799, -1, 10802, 10505, 10503, -1, 10801, 10505, 10802, -1, 10625, 10803, 10623, -1, 10623, 10803, 10804, -1, 10804, 10805, 10806, -1, 10803, 10805, 10804, -1, 10805, 10807, 10806, -1, 10807, 10808, 10806, -1, 10806, 10508, 10506, -1, 10808, 10508, 10806, -1, 10809, 10810, 10811, -1, 10811, 10812, 10813, -1, 10810, 10812, 10811, -1, 10813, 10814, 10815, -1, 10815, 10814, 10816, -1, 10812, 10814, 10813, -1, 10816, 10817, 10818, -1, 10814, 10817, 10816, -1, 10818, 10819, 10820, -1, 10817, 10819, 10818, -1, 10821, 10822, 10823, -1, 10820, 10822, 10821, -1, 10819, 10822, 10820, -1, 10824, 10825, 10826, -1, 10823, 10825, 10824, -1, 10822, 10825, 10823, -1, 10827, 10828, 10829, -1, 10826, 10828, 10827, -1, 10825, 10828, 10826, -1, 10829, 10512, 10510, -1, 10828, 10512, 10829, -1, 10595, 10597, 10830, -1, 10597, 10831, 10830, -1, 10830, 10832, 10833, -1, 10831, 10832, 10830, -1, 10832, 10834, 10833, -1, 10834, 10835, 10833, -1, 10833, 10515, 10513, -1, 10835, 10515, 10833, -1, 10605, 10836, 10603, -1, 10603, 10836, 10837, -1, 10837, 10838, 10839, -1, 10836, 10838, 10837, -1, 10838, 10840, 10839, -1, 10840, 10841, 10839, -1, 10839, 10522, 10520, -1, 10841, 10522, 10839, -1, 10842, 10843, 10844, -1, 10844, 10845, 10846, -1, 10843, 10845, 10844, -1, 10847, 10848, 10849, -1, 10846, 10848, 10847, -1, 10845, 10848, 10846, -1, 10850, 10851, 10852, -1, 10849, 10851, 10850, -1, 10848, 10851, 10849, -1, 10852, 10853, 10854, -1, 10851, 10853, 10852, -1, 10855, 10856, 10857, -1, 10854, 10856, 10855, -1, 10853, 10856, 10854, -1, 10858, 10859, 10860, -1, 10857, 10859, 10858, -1, 10856, 10859, 10857, -1, 10861, 10862, 10863, -1, 10860, 10862, 10861, -1, 10859, 10862, 10860, -1, 10863, 10519, 10517, -1, 10862, 10519, 10863, -1, 10610, 10864, 10608, -1, 10608, 10864, 10865, -1, 10865, 10866, 10867, -1, 10864, 10866, 10865, -1, 10866, 10868, 10867, -1, 10868, 10869, 10867, -1, 10867, 10529, 10527, -1, 10869, 10529, 10867, -1, 10870, 10871, 10872, -1, 10872, 10873, 10874, -1, 10871, 10873, 10872, -1, 10875, 10876, 10877, -1, 10874, 10876, 10875, -1, 10873, 10876, 10874, -1, 10878, 10879, 10880, -1, 10877, 10879, 10878, -1, 10876, 10879, 10877, -1, 10880, 10881, 10882, -1, 10879, 10881, 10880, -1, 10883, 10884, 10885, -1, 10882, 10884, 10883, -1, 10881, 10884, 10882, -1, 10886, 10887, 10888, -1, 10885, 10887, 10886, -1, 10884, 10887, 10885, -1, 10889, 10890, 10891, -1, 10888, 10890, 10889, -1, 10887, 10890, 10888, -1, 10891, 10526, 10524, -1, 10890, 10526, 10891, -1, 10892, 10893, 10894, -1, 10892, 10895, 10893, -1, 10895, 10896, 10893, -1, 10895, 10589, 10896, -1, 10589, 10591, 10896, -1, 10589, 10895, 10592, -1, 10592, 10895, 10897, -1, 10895, 10892, 10897, -1, 10892, 10894, 10897, -1, 10897, 10898, 10899, -1, 10894, 10898, 10897, -1, 10898, 10900, 10899, -1, 10899, 10423, 10422, -1, 10900, 10423, 10899, -1, 10901, 10902, 10903, -1, 10903, 10904, 10905, -1, 10902, 10904, 10903, -1, 10905, 10906, 10907, -1, 10907, 10906, 10908, -1, 10904, 10906, 10905, -1, 10908, 10909, 10910, -1, 10906, 10909, 10908, -1, 10910, 10911, 10912, -1, 10909, 10911, 10910, -1, 10913, 10914, 10915, -1, 10912, 10914, 10913, -1, 10911, 10914, 10912, -1, 10916, 10917, 10918, -1, 10915, 10917, 10916, -1, 10914, 10917, 10915, -1, 10919, 10920, 10921, -1, 10918, 10920, 10919, -1, 10917, 10920, 10918, -1, 10921, 10419, 10418, -1, 10920, 10419, 10921, -1, 10615, 10922, 10613, -1, 10613, 10922, 10923, -1, 10923, 10924, 10925, -1, 10922, 10924, 10923, -1, 10924, 10926, 10925, -1, 10926, 10927, 10925, -1, 10925, 10532, 10530, -1, 10927, 10532, 10925, -1, 10620, 10928, 10618, -1, 10618, 10928, 10929, -1, 10929, 10930, 10931, -1, 10928, 10930, 10929, -1, 10930, 10932, 10931, -1, 10932, 10933, 10931, -1, 10931, 10414, 10413, -1, 10933, 10414, 10931, -1, 10934, 10935, 10936, -1, 10936, 10937, 10938, -1, 10935, 10937, 10936, -1, 10939, 10940, 10941, -1, 10938, 10940, 10939, -1, 10937, 10940, 10938, -1, 10942, 10943, 10944, -1, 10941, 10943, 10942, -1, 10940, 10943, 10941, -1, 10944, 10945, 10946, -1, 10943, 10945, 10944, -1, 10947, 10948, 10949, -1, 10946, 10948, 10947, -1, 10945, 10948, 10946, -1, 10950, 10951, 10952, -1, 10949, 10951, 10950, -1, 10948, 10951, 10949, -1, 10953, 10954, 10955, -1, 10952, 10954, 10953, -1, 10951, 10954, 10952, -1, 10955, 10473, 10471, -1, 10954, 10473, 10955, -1, 10098, 10956, 10099, -1, 10099, 10957, 10958, -1, 10956, 10957, 10099, -1, 10959, 10960, 10961, -1, 10958, 10960, 10959, -1, 10957, 10960, 10958, -1, 10961, 10962, 10963, -1, 10960, 10962, 10961, -1, 10963, 10964, 10965, -1, 10962, 10964, 10963, -1, 10966, 10967, 10968, -1, 10965, 10967, 10966, -1, 10964, 10967, 10965, -1, 10969, 10970, 10971, -1, 10968, 10970, 10969, -1, 10967, 10970, 10968, -1, 10972, 10973, 10974, -1, 10971, 10973, 10972, -1, 10970, 10973, 10971, -1, 10974, 10469, 10467, -1, 10973, 10469, 10974, -1, 10701, 10975, 10976, -1, 10701, 10976, 10699, -1, 10977, 10975, 10701, -1, 10703, 10977, 10701, -1, 10706, 10977, 10705, -1, 10705, 10977, 10703, -1, 10978, 10976, 10975, -1, 10978, 10699, 10976, -1, 10979, 10977, 10980, -1, 10981, 10975, 10977, -1, 10981, 10978, 10975, -1, 10981, 10977, 10979, -1, 10982, 10981, 10979, -1, 10983, 10981, 10982, -1, 10979, 10984, 10985, -1, 10979, 10980, 10984, -1, 10982, 10985, 10986, -1, 10982, 10979, 10985, -1, 10983, 10986, 10987, -1, 10983, 10982, 10986, -1, 10988, 10985, 10984, -1, 10988, 10986, 10985, -1, 10988, 10987, 10986, -1, 10989, 10990, 10991, -1, 10992, 10984, 10642, -1, 10992, 10988, 10984, -1, 10993, 10988, 10992, -1, 10994, 10642, 10641, -1, 10994, 10992, 10642, -1, 10995, 10996, 10988, -1, 10995, 10988, 10993, -1, 10997, 10993, 10992, -1, 10997, 10992, 10994, -1, 10998, 10641, 10639, -1, 10998, 10639, 10638, -1, 10998, 10638, 10999, -1, 10998, 10994, 10641, -1, 11000, 11001, 10996, -1, 11000, 10995, 10993, -1, 11000, 10993, 10997, -1, 11000, 10996, 10995, -1, 11002, 10999, 10991, -1, 11002, 10994, 10998, -1, 11002, 10998, 10999, -1, 11002, 10997, 10994, -1, 11003, 10990, 11001, -1, 11003, 11000, 10997, -1, 11003, 11002, 10991, -1, 11003, 11001, 11000, -1, 11003, 10991, 10990, -1, 11003, 10997, 11002, -1, 10728, 11004, 11005, -1, 10728, 11005, 10726, -1, 11006, 11004, 10728, -1, 10730, 11006, 10728, -1, 10733, 11006, 10732, -1, 10732, 11006, 10730, -1, 11007, 11005, 11004, -1, 11007, 10726, 11005, -1, 11008, 11006, 11009, -1, 11010, 11004, 11006, -1, 11010, 11007, 11004, -1, 11010, 11006, 11008, -1, 11011, 11010, 11008, -1, 11012, 11010, 11011, -1, 11009, 11013, 11014, -1, 11008, 11014, 11015, -1, 11008, 11009, 11014, -1, 11011, 11015, 11016, -1, 11011, 11008, 11015, -1, 11012, 11011, 11016, -1, 11017, 11014, 11013, -1, 11017, 11015, 11014, -1, 11017, 11016, 11015, -1, 11018, 11019, 11020, -1, 11021, 11013, 10637, -1, 11021, 11017, 11013, -1, 11022, 11017, 11021, -1, 11023, 10637, 10636, -1, 11023, 11021, 10637, -1, 11024, 11025, 11017, -1, 11024, 11017, 11022, -1, 11026, 11022, 11021, -1, 11026, 11021, 11023, -1, 11027, 10636, 10634, -1, 11027, 10634, 10633, -1, 11027, 10633, 11028, -1, 11027, 11023, 10636, -1, 11029, 11030, 11025, -1, 11029, 11024, 11022, -1, 11029, 11022, 11026, -1, 11029, 11025, 11024, -1, 11031, 11028, 11020, -1, 11031, 11023, 11027, -1, 11031, 11027, 11028, -1, 11031, 11026, 11023, -1, 11032, 11019, 11030, -1, 11032, 11029, 11026, -1, 11032, 11031, 11020, -1, 11032, 11030, 11029, -1, 11032, 11020, 11019, -1, 11032, 11026, 11031, -1, 10651, 11033, 11034, -1, 10651, 11034, 10649, -1, 11035, 11033, 10651, -1, 10653, 11035, 10651, -1, 10656, 11035, 10655, -1, 10655, 11035, 10653, -1, 11036, 11034, 11033, -1, 11036, 10649, 11034, -1, 11037, 11035, 11038, -1, 11039, 11033, 11035, -1, 11039, 11036, 11033, -1, 11039, 11035, 11037, -1, 11040, 11039, 11037, -1, 11041, 11039, 11040, -1, 11037, 11042, 11043, -1, 11037, 11038, 11042, -1, 11040, 11043, 11044, -1, 11040, 11044, 11045, -1, 11040, 11037, 11043, -1, 11041, 11040, 11045, -1, 11046, 11043, 11042, -1, 11046, 11044, 11043, -1, 11046, 11045, 11044, -1, 11047, 11048, 11049, -1, 11050, 11042, 10632, -1, 11050, 11046, 11042, -1, 11051, 11046, 11050, -1, 11052, 10632, 10631, -1, 11052, 11050, 10632, -1, 11053, 11054, 11046, -1, 11053, 11046, 11051, -1, 11055, 11051, 11050, -1, 11055, 11050, 11052, -1, 11056, 10631, 10629, -1, 11056, 10629, 10628, -1, 11056, 10628, 11057, -1, 11056, 11052, 10631, -1, 11058, 11059, 11054, -1, 11058, 11053, 11051, -1, 11058, 11051, 11055, -1, 11058, 11054, 11053, -1, 11060, 11057, 11049, -1, 11060, 11052, 11056, -1, 11060, 11056, 11057, -1, 11060, 11055, 11052, -1, 11061, 11048, 11059, -1, 11061, 11058, 11055, -1, 11061, 11060, 11049, -1, 11061, 11059, 11058, -1, 11061, 11049, 11048, -1, 11061, 11055, 11060, -1, 10755, 11062, 11063, -1, 10755, 11063, 10753, -1, 11064, 11062, 10755, -1, 10757, 11064, 10755, -1, 10760, 11064, 10759, -1, 10759, 11064, 10757, -1, 11065, 11063, 11062, -1, 11065, 10753, 11063, -1, 11066, 11064, 11067, -1, 11068, 11062, 11064, -1, 11068, 11065, 11062, -1, 11068, 11064, 11066, -1, 11069, 11068, 11066, -1, 11070, 11068, 11069, -1, 11066, 11071, 11072, -1, 11066, 11067, 11071, -1, 11069, 11072, 11073, -1, 11069, 11073, 11074, -1, 11069, 11066, 11072, -1, 11070, 11069, 11074, -1, 11075, 11072, 11071, -1, 11075, 11073, 11072, -1, 11075, 11074, 11073, -1, 11076, 11077, 11078, -1, 11079, 11071, 10627, -1, 11079, 11075, 11071, -1, 11080, 11075, 11079, -1, 11081, 10627, 10626, -1, 11081, 11079, 10627, -1, 11082, 11083, 11075, -1, 11082, 11075, 11080, -1, 11084, 11080, 11079, -1, 11084, 11079, 11081, -1, 11085, 10626, 10624, -1, 11085, 10624, 10623, -1, 11085, 10623, 11086, -1, 11085, 11081, 10626, -1, 11087, 11088, 11083, -1, 11087, 11082, 11080, -1, 11087, 11080, 11084, -1, 11087, 11083, 11082, -1, 11089, 11086, 11078, -1, 11089, 11081, 11085, -1, 11089, 11085, 11086, -1, 11089, 11084, 11081, -1, 11090, 11077, 11088, -1, 11090, 11087, 11084, -1, 11090, 11089, 11078, -1, 11090, 11088, 11087, -1, 11090, 11078, 11077, -1, 11090, 11084, 11089, -1, 10811, 11091, 11092, -1, 10811, 11092, 10809, -1, 11093, 11091, 10811, -1, 10813, 11093, 10811, -1, 10816, 11093, 10815, -1, 10815, 11093, 10813, -1, 11094, 11092, 11091, -1, 11094, 10809, 11092, -1, 11095, 11093, 11096, -1, 11097, 11091, 11093, -1, 11097, 11094, 11091, -1, 11097, 11093, 11095, -1, 11098, 11097, 11095, -1, 11099, 11097, 11098, -1, 11095, 11100, 11101, -1, 11095, 11096, 11100, -1, 11098, 11101, 11102, -1, 11098, 11095, 11101, -1, 11099, 11102, 11103, -1, 11099, 11098, 11102, -1, 11104, 11101, 11100, -1, 11104, 11102, 11101, -1, 11104, 11103, 11102, -1, 11105, 11106, 11107, -1, 11108, 11100, 10607, -1, 11108, 11104, 11100, -1, 11109, 11104, 11108, -1, 11110, 10607, 10606, -1, 11110, 11108, 10607, -1, 11111, 11112, 11104, -1, 11111, 11104, 11109, -1, 11113, 11109, 11108, -1, 11113, 11108, 11110, -1, 11114, 10606, 10604, -1, 11114, 10604, 10603, -1, 11114, 10603, 11115, -1, 11114, 11110, 10606, -1, 11116, 11117, 11112, -1, 11116, 11111, 11109, -1, 11116, 11109, 11113, -1, 11116, 11112, 11111, -1, 11118, 11115, 11107, -1, 11118, 11110, 11114, -1, 11118, 11114, 11115, -1, 11118, 11113, 11110, -1, 11119, 11106, 11117, -1, 11119, 11116, 11113, -1, 11119, 11118, 11107, -1, 11119, 11117, 11116, -1, 11119, 11107, 11106, -1, 11119, 11113, 11118, -1, 11120, 10847, 10849, -1, 11121, 10842, 10844, -1, 11122, 10846, 10847, -1, 11122, 10847, 11120, -1, 11123, 11124, 11125, -1, 11123, 11125, 11121, -1, 11123, 10844, 10846, -1, 11123, 11120, 11124, -1, 11123, 11122, 11120, -1, 11123, 11121, 10844, -1, 11123, 10846, 11122, -1, 11126, 11121, 11125, -1, 11126, 10842, 11121, -1, 11127, 11124, 11128, -1, 11129, 11125, 11124, -1, 11129, 11126, 11125, -1, 11129, 11124, 11127, -1, 11130, 11129, 11127, -1, 11131, 11129, 11130, -1, 11128, 11132, 11133, -1, 11127, 11128, 11133, -1, 11130, 11133, 11134, -1, 11130, 11127, 11133, -1, 11131, 11134, 11135, -1, 11131, 11130, 11134, -1, 11136, 11133, 11132, -1, 11136, 11134, 11133, -1, 11136, 11135, 11134, -1, 11137, 11138, 11139, -1, 11140, 11132, 10612, -1, 11140, 11136, 11132, -1, 11141, 11136, 11140, -1, 11142, 10612, 10611, -1, 11142, 11140, 10612, -1, 11143, 11144, 11136, -1, 11143, 11136, 11141, -1, 11145, 11141, 11140, -1, 11145, 11140, 11142, -1, 11146, 10611, 10609, -1, 11146, 10609, 10608, -1, 11146, 10608, 11147, -1, 11146, 11142, 10611, -1, 11148, 11149, 11144, -1, 11148, 11143, 11141, -1, 11148, 11141, 11145, -1, 11148, 11144, 11143, -1, 11150, 11147, 11139, -1, 11150, 11142, 11146, -1, 11150, 11146, 11147, -1, 11150, 11145, 11142, -1, 11151, 11138, 11149, -1, 11151, 11148, 11145, -1, 11151, 11150, 11139, -1, 11151, 11149, 11148, -1, 11151, 11139, 11138, -1, 11151, 11145, 11150, -1, 11152, 10875, 10877, -1, 11153, 10870, 10872, -1, 11154, 10874, 10875, -1, 11154, 10875, 11152, -1, 11155, 11156, 11157, -1, 11155, 11157, 11153, -1, 11155, 10872, 10874, -1, 11155, 11152, 11156, -1, 11155, 11154, 11152, -1, 11155, 11153, 10872, -1, 11155, 10874, 11154, -1, 11158, 11153, 11157, -1, 11158, 10870, 11153, -1, 11159, 11156, 11160, -1, 11161, 11157, 11156, -1, 11161, 11158, 11157, -1, 11161, 11156, 11159, -1, 11162, 11161, 11159, -1, 11163, 11161, 11162, -1, 11160, 11164, 11165, -1, 11159, 11165, 11166, -1, 11159, 11160, 11165, -1, 11162, 11159, 11166, -1, 11163, 11166, 11167, -1, 11163, 11162, 11166, -1, 11168, 11165, 11164, -1, 11168, 11166, 11165, -1, 11168, 11167, 11166, -1, 11169, 11170, 11171, -1, 11172, 11164, 10617, -1, 11172, 11168, 11164, -1, 11173, 11168, 11172, -1, 11174, 10617, 10616, -1, 11174, 11172, 10617, -1, 11175, 11176, 11168, -1, 11175, 11168, 11173, -1, 11177, 11173, 11172, -1, 11177, 11172, 11174, -1, 11178, 10616, 10614, -1, 11178, 10614, 10613, -1, 11178, 10613, 11179, -1, 11178, 11174, 10616, -1, 11180, 11181, 11176, -1, 11180, 11175, 11173, -1, 11180, 11173, 11177, -1, 11180, 11176, 11175, -1, 11182, 11179, 11171, -1, 11182, 11174, 11178, -1, 11182, 11178, 11179, -1, 11182, 11177, 11174, -1, 11183, 11170, 11181, -1, 11183, 11180, 11177, -1, 11183, 11182, 11171, -1, 11183, 11181, 11180, -1, 11183, 11171, 11170, -1, 11183, 11177, 11182, -1, 11184, 10939, 10941, -1, 11185, 10934, 10936, -1, 11186, 10938, 10939, -1, 11186, 10939, 11184, -1, 11187, 11188, 11189, -1, 11187, 11189, 11185, -1, 11187, 10936, 10938, -1, 11187, 11184, 11188, -1, 11187, 11186, 11184, -1, 11187, 11185, 10936, -1, 11187, 10938, 11186, -1, 11190, 11185, 11189, -1, 11190, 10934, 11185, -1, 11191, 11188, 11192, -1, 11193, 11189, 11188, -1, 11193, 11190, 11189, -1, 11193, 11188, 11191, -1, 11194, 11193, 11191, -1, 11195, 11193, 11194, -1, 11192, 11196, 11197, -1, 11191, 11197, 11198, -1, 11191, 11192, 11197, -1, 11194, 11191, 11198, -1, 11195, 11198, 11199, -1, 11195, 11194, 11198, -1, 11200, 11197, 11196, -1, 11200, 11198, 11197, -1, 11200, 11199, 11198, -1, 11201, 10590, 10592, -1, 11202, 10590, 11201, -1, 11203, 11196, 10594, -1, 11203, 11200, 11196, -1, 11204, 11200, 11203, -1, 11204, 11203, 10594, -1, 11205, 11206, 11207, -1, 11205, 11207, 11200, -1, 11205, 11200, 11204, -1, 11208, 10594, 10593, -1, 11208, 11204, 10594, -1, 11209, 11205, 11204, -1, 11209, 11206, 11205, -1, 11209, 11204, 11208, -1, 11210, 10593, 10590, -1, 11211, 11208, 10593, -1, 11211, 11210, 10590, -1, 11211, 10593, 11210, -1, 11211, 10590, 11202, -1, 11212, 11202, 11213, -1, 11212, 11213, 11214, -1, 11212, 11214, 11206, -1, 11212, 11208, 11211, -1, 11212, 11209, 11208, -1, 11212, 11211, 11202, -1, 11212, 11206, 11209, -1, 10903, 11215, 11216, -1, 10903, 11216, 10901, -1, 11217, 11215, 10903, -1, 10905, 11217, 10903, -1, 10908, 11217, 10907, -1, 10907, 11217, 10905, -1, 11218, 11216, 11215, -1, 11218, 10901, 11216, -1, 11219, 11217, 11220, -1, 11221, 11215, 11217, -1, 11221, 11218, 11215, -1, 11221, 11217, 11219, -1, 11222, 11221, 11219, -1, 11223, 11221, 11222, -1, 11219, 11224, 11225, -1, 11219, 11220, 11224, -1, 11222, 11225, 11226, -1, 11222, 11219, 11225, -1, 11223, 11226, 11227, -1, 11223, 11222, 11226, -1, 11228, 11225, 11224, -1, 11228, 11226, 11225, -1, 11228, 11227, 11226, -1, 11229, 11230, 11231, -1, 11232, 11224, 10622, -1, 11232, 11228, 11224, -1, 11233, 11228, 11232, -1, 11234, 10622, 10621, -1, 11234, 11232, 10622, -1, 11235, 11236, 11228, -1, 11235, 11228, 11233, -1, 11237, 11233, 11232, -1, 11237, 11232, 11234, -1, 11238, 10621, 10619, -1, 11238, 10619, 10618, -1, 11238, 10618, 11239, -1, 11238, 11234, 10621, -1, 11240, 11241, 11236, -1, 11240, 11235, 11233, -1, 11240, 11233, 11237, -1, 11240, 11236, 11235, -1, 11242, 11239, 11231, -1, 11242, 11234, 11238, -1, 11242, 11238, 11239, -1, 11242, 11237, 11234, -1, 11243, 11230, 11241, -1, 11243, 11240, 11237, -1, 11243, 11242, 11231, -1, 11243, 11241, 11240, -1, 11243, 11231, 11230, -1, 11243, 11237, 11242, -1, 10395, 10394, 11244, -1, 11244, 11245, 11246, -1, 10394, 11245, 11244, -1, 11246, 11247, 11248, -1, 11245, 11247, 11246, -1, 11248, 11249, 11250, -1, 11247, 11249, 11248, -1, 11250, 11251, 11252, -1, 11249, 11251, 11250, -1, 11252, 10057, 10059, -1, 11251, 10057, 11252, -1, 10227, 11253, 10219, -1, 10219, 11254, 11255, -1, 11253, 11254, 10219, -1, 11254, 11256, 11255, -1, 11255, 11257, 11258, -1, 11258, 11257, 11259, -1, 11256, 11257, 11255, -1, 11259, 11260, 11261, -1, 11257, 11260, 11259, -1, 11261, 11262, 11263, -1, 11260, 11262, 11261, -1, 11263, 11264, 11265, -1, 11262, 11264, 11263, -1, 11265, 11266, 10525, -1, 11264, 11266, 11265, -1, 11266, 10523, 10525, -1, 10227, 10224, 11253, -1, 11253, 10224, 11254, -1, 11254, 10224, 11256, -1, 10400, 10399, 11267, -1, 11267, 11268, 11269, -1, 10399, 11268, 11267, -1, 11269, 11270, 11271, -1, 11268, 11270, 11269, -1, 11271, 11272, 11273, -1, 11270, 11272, 11271, -1, 11273, 11274, 11275, -1, 11272, 11274, 11273, -1, 11275, 10049, 10051, -1, 11274, 10049, 11275, -1, 10396, 11276, 10132, -1, 10132, 11277, 11278, -1, 11276, 11277, 10132, -1, 11277, 11279, 11278, -1, 11278, 11280, 11281, -1, 11281, 11280, 11282, -1, 11279, 11280, 11278, -1, 11282, 11283, 11284, -1, 11280, 11283, 11282, -1, 11284, 11285, 11286, -1, 11283, 11285, 11284, -1, 11286, 11287, 11288, -1, 11285, 11287, 11286, -1, 11288, 11289, 10518, -1, 11287, 11289, 11288, -1, 11289, 10516, 10518, -1, 10396, 10397, 11276, -1, 11276, 10397, 11277, -1, 11277, 10397, 11279, -1, 10404, 10123, 11290, -1, 11290, 11291, 11292, -1, 10123, 11291, 11290, -1, 11292, 11293, 11294, -1, 11291, 11293, 11292, -1, 11294, 11295, 11296, -1, 11293, 11295, 11294, -1, 11296, 11297, 11298, -1, 11295, 11297, 11296, -1, 11298, 10041, 10043, -1, 11297, 10041, 11298, -1, 10401, 11299, 10324, -1, 10324, 11300, 11301, -1, 11299, 11300, 10324, -1, 11300, 11302, 11301, -1, 11301, 11303, 11304, -1, 11304, 11303, 11305, -1, 11302, 11303, 11301, -1, 11305, 11306, 11307, -1, 11303, 11306, 11305, -1, 11307, 11308, 11309, -1, 11306, 11308, 11307, -1, 11309, 11310, 11311, -1, 11308, 11310, 11309, -1, 11311, 11312, 10511, -1, 11310, 11312, 11311, -1, 11312, 10509, 10511, -1, 10401, 10402, 11299, -1, 11299, 10402, 11300, -1, 11300, 10402, 11302, -1, 10130, 10129, 11313, -1, 11313, 11314, 11315, -1, 10129, 11314, 11313, -1, 11315, 11316, 11317, -1, 11314, 11316, 11315, -1, 11317, 11318, 11319, -1, 11316, 11318, 11317, -1, 11319, 11320, 11321, -1, 11318, 11320, 11319, -1, 11321, 10033, 10035, -1, 11320, 10033, 11321, -1, 10121, 11322, 10122, -1, 10122, 11323, 11324, -1, 11322, 11323, 10122, -1, 11323, 11325, 11324, -1, 11324, 11326, 11327, -1, 11327, 11326, 11328, -1, 11325, 11326, 11324, -1, 11328, 11329, 11330, -1, 11326, 11329, 11328, -1, 11330, 11331, 11332, -1, 11329, 11331, 11330, -1, 11332, 11333, 11334, -1, 11331, 11333, 11332, -1, 11334, 11335, 10504, -1, 11333, 11335, 11334, -1, 11335, 10502, 10504, -1, 10121, 10405, 11322, -1, 11322, 10405, 11323, -1, 11323, 10405, 11325, -1, 10141, 10140, 11336, -1, 11336, 11337, 11338, -1, 10140, 11337, 11336, -1, 11338, 11339, 11340, -1, 11337, 11339, 11338, -1, 11340, 11341, 11342, -1, 11339, 11341, 11340, -1, 11342, 11343, 11344, -1, 11341, 11343, 11342, -1, 11344, 10025, 10027, -1, 11343, 10025, 11344, -1, 10131, 11345, 10136, -1, 10136, 11346, 11347, -1, 11345, 11346, 10136, -1, 11346, 11348, 11347, -1, 11347, 11349, 11350, -1, 11350, 11349, 11351, -1, 11348, 11349, 11347, -1, 11351, 11352, 11353, -1, 11349, 11352, 11351, -1, 11353, 11354, 11355, -1, 11352, 11354, 11353, -1, 11355, 11356, 11357, -1, 11354, 11356, 11355, -1, 11357, 11358, 10497, -1, 11356, 11358, 11357, -1, 11358, 10495, 10497, -1, 10131, 10135, 11345, -1, 11345, 10135, 11346, -1, 11346, 10135, 11348, -1, 10170, 10169, 11359, -1, 11359, 11360, 11361, -1, 10169, 11360, 11359, -1, 11361, 11362, 11363, -1, 11360, 11362, 11361, -1, 11363, 11364, 11365, -1, 11362, 11364, 11363, -1, 11365, 11366, 11367, -1, 11364, 11366, 11365, -1, 11367, 10017, 10019, -1, 11366, 10017, 11367, -1, 10163, 11368, 10165, -1, 10165, 11369, 11370, -1, 11368, 11369, 10165, -1, 11369, 11371, 11370, -1, 11370, 11372, 11373, -1, 11373, 11372, 11374, -1, 11371, 11372, 11370, -1, 11374, 11375, 11376, -1, 11372, 11375, 11374, -1, 11376, 11377, 11378, -1, 11375, 11377, 11376, -1, 11378, 11379, 11380, -1, 11377, 11379, 11378, -1, 11380, 11381, 10476, -1, 11379, 11381, 11380, -1, 11381, 10474, 10476, -1, 10163, 10164, 11368, -1, 11368, 10164, 11369, -1, 11369, 10164, 11371, -1, 10171, 11382, 10175, -1, 10175, 11383, 11384, -1, 11382, 11383, 10175, -1, 11383, 11385, 11384, -1, 11384, 11386, 11387, -1, 11387, 11386, 11388, -1, 11385, 11386, 11384, -1, 11388, 11389, 11390, -1, 11386, 11389, 11388, -1, 11390, 11391, 11392, -1, 11389, 11391, 11390, -1, 11392, 11393, 11394, -1, 11391, 11393, 11392, -1, 11394, 11395, 10468, -1, 11393, 11395, 11394, -1, 11395, 10466, 10468, -1, 10171, 10174, 11382, -1, 11382, 10174, 11383, -1, 11383, 10174, 11385, -1, 11396, 10150, 11397, -1, 11398, 10150, 11396, -1, 10149, 10150, 11398, -1, 10149, 11398, 10154, -1, 10154, 11396, 11399, -1, 11398, 11396, 10154, -1, 11396, 11397, 11399, -1, 11400, 11401, 11402, -1, 11399, 11401, 11400, -1, 11397, 11401, 11399, -1, 11402, 11403, 11404, -1, 11401, 11403, 11402, -1, 11404, 11405, 11406, -1, 11403, 11405, 11404, -1, 11406, 11407, 11408, -1, 11405, 11407, 11406, -1, 11408, 11409, 10483, -1, 11407, 11409, 11408, -1, 11409, 10481, 10483, -1, 10162, 10161, 11410, -1, 11410, 11411, 11412, -1, 10161, 11411, 11410, -1, 11412, 11413, 11414, -1, 11411, 11413, 11412, -1, 11414, 11415, 11416, -1, 11413, 11415, 11414, -1, 11416, 11417, 11418, -1, 11415, 11417, 11416, -1, 11418, 10009, 10011, -1, 11417, 10009, 11418, -1, 11419, 11420, 11421, -1, 11422, 11423, 11424, -1, 11425, 11426, 11427, -1, 11428, 11429, 11430, -1, 11431, 11432, 11433, -1, 11425, 11434, 11426, -1, 11435, 11430, 11436, -1, 11431, 11433, 11437, -1, 11435, 11436, 11438, -1, 11439, 11440, 11441, -1, 11439, 11441, 11442, -1, 11443, 11444, 11445, -1, 11443, 11445, 11446, -1, 11447, 11431, 11437, -1, 11443, 11446, 11448, -1, 11447, 11437, 11449, -1, 11450, 11448, 11451, -1, 11452, 11424, 11453, -1, 11454, 11455, 11434, -1, 11450, 11443, 11448, -1, 11452, 11453, 11456, -1, 11454, 11442, 11455, -1, 11450, 11444, 11443, -1, 11457, 11435, 11438, -1, 11458, 11459, 11460, -1, 11461, 11454, 11434, -1, 11462, 11456, 11463, -1, 11461, 11434, 11425, -1, 11464, 11465, 11466, -1, 11462, 11452, 11456, -1, 11467, 11427, 11468, -1, 11464, 11466, 11469, -1, 11470, 11471, 11472, -1, 11467, 11425, 11427, -1, 11470, 11473, 11474, -1, 11470, 11474, 11432, -1, 11475, 11439, 11442, -1, 11470, 11472, 11473, -1, 11476, 11477, 11428, -1, 11475, 11442, 11454, -1, 11478, 11479, 11480, -1, 11478, 11463, 11479, -1, 11476, 11481, 11477, -1, 11482, 11483, 11440, -1, 11484, 11464, 11469, -1, 11482, 11440, 11439, -1, 11485, 11422, 11424, -1, 11484, 11469, 11481, -1, 11485, 11424, 11452, -1, 11486, 11475, 11454, -1, 11486, 11454, 11461, -1, 11487, 11428, 11430, -1, 11487, 11430, 11435, -1, 11488, 11435, 11457, -1, 11489, 11452, 11462, -1, 11490, 11425, 11467, -1, 11488, 11487, 11435, -1, 11489, 11485, 11452, -1, 11490, 11461, 11425, -1, 11446, 11449, 11422, -1, 11491, 11467, 11468, -1, 11492, 11493, 11444, -1, 11446, 11447, 11449, -1, 11492, 11451, 11465, -1, 11494, 11468, 11495, -1, 11492, 11450, 11451, -1, 11492, 11444, 11450, -1, 11494, 11491, 11468, -1, 11496, 11462, 11463, -1, 11496, 11463, 11478, -1, 11497, 11476, 11428, -1, 11498, 11482, 11439, -1, 11498, 11439, 11475, -1, 11497, 11428, 11487, -1, 11499, 11480, 11500, -1, 11499, 11478, 11480, -1, 11429, 11499, 11500, -1, 11501, 11487, 11488, -1, 11501, 11497, 11487, -1, 11502, 11432, 11431, -1, 11433, 11486, 11461, -1, 11502, 11470, 11432, -1, 11433, 11461, 11490, -1, 11503, 11481, 11476, -1, 11502, 11471, 11470, -1, 11474, 11498, 11475, -1, 11503, 11484, 11481, -1, 11474, 11475, 11486, -1, 11504, 11502, 11431, -1, 11504, 11431, 11447, -1, 11505, 11438, 11506, -1, 11504, 11471, 11502, -1, 11505, 11507, 11508, -1, 11505, 11457, 11438, -1, 11509, 11467, 11491, -1, 11509, 11490, 11467, -1, 11466, 11489, 11462, -1, 11423, 11491, 11494, -1, 11505, 11506, 11507, -1, 11466, 11462, 11496, -1, 11423, 11509, 11491, -1, 11510, 11493, 11492, -1, 11510, 11465, 11464, -1, 11511, 11472, 11512, -1, 11448, 11422, 11485, -1, 11507, 11506, 11513, -1, 11510, 11492, 11465, -1, 11448, 11446, 11422, -1, 11511, 11512, 11483, -1, 11514, 11464, 11484, -1, 11511, 11483, 11482, -1, 11514, 11510, 11464, -1, 11514, 11493, 11510, -1, 11515, 11508, 11516, -1, 11515, 11516, 11517, -1, 11451, 11448, 11485, -1, 11451, 11485, 11489, -1, 11453, 11494, 11495, -1, 11515, 11488, 11457, -1, 11515, 11457, 11505, -1, 11437, 11433, 11490, -1, 11515, 11505, 11508, -1, 11518, 11496, 11478, -1, 11519, 11503, 11476, -1, 11518, 11478, 11499, -1, 11519, 11476, 11497, -1, 11437, 11490, 11509, -1, 11477, 11518, 11499, -1, 11432, 11486, 11433, -1, 11432, 11474, 11486, -1, 11421, 11519, 11497, -1, 11421, 11497, 11501, -1, 11477, 11499, 11429, -1, 11449, 11509, 11423, -1, 11520, 11517, 11521, -1, 11430, 11500, 11436, -1, 11520, 11521, 11522, -1, 11430, 11429, 11500, -1, 11520, 11488, 11515, -1, 11449, 11437, 11509, -1, 11520, 11501, 11488, -1, 11445, 11444, 11471, -1, 11520, 11515, 11517, -1, 11445, 11447, 11446, -1, 11523, 11524, 11493, -1, 11445, 11471, 11504, -1, 11424, 11494, 11453, -1, 11445, 11504, 11447, -1, 11523, 11493, 11514, -1, 11424, 11423, 11494, -1, 11523, 11484, 11503, -1, 11525, 11511, 11482, -1, 11523, 11514, 11484, -1, 11525, 11482, 11498, -1, 11526, 11503, 11519, -1, 11525, 11472, 11511, -1, 11469, 11496, 11518, -1, 11456, 11495, 11479, -1, 11526, 11523, 11503, -1, 11469, 11466, 11496, -1, 11456, 11453, 11495, -1, 11526, 11524, 11523, -1, 11527, 11522, 11528, -1, 11527, 11421, 11501, -1, 11481, 11469, 11518, -1, 11527, 11501, 11520, -1, 11481, 11518, 11477, -1, 11527, 11520, 11522, -1, 11463, 11456, 11479, -1, 11455, 11529, 11530, -1, 11455, 11530, 11459, -1, 11455, 11458, 11426, -1, 11420, 11531, 11524, -1, 11455, 11459, 11458, -1, 11420, 11519, 11421, -1, 11465, 11451, 11489, -1, 11420, 11526, 11519, -1, 11473, 11498, 11474, -1, 11442, 11441, 11529, -1, 11420, 11524, 11526, -1, 11473, 11525, 11498, -1, 11473, 11472, 11525, -1, 11419, 11532, 11531, -1, 11419, 11528, 11532, -1, 11442, 11529, 11455, -1, 11419, 11527, 11528, -1, 11465, 11489, 11466, -1, 11419, 11421, 11527, -1, 11422, 11449, 11423, -1, 11419, 11531, 11420, -1, 11428, 11477, 11429, -1, 11434, 11455, 11426, -1, 11533, 11531, 11532, -1, 11534, 11531, 11533, -1, 11535, 11524, 11534, -1, 11534, 11524, 11531, -1, 11535, 11493, 11524, -1, 11536, 11444, 11535, -1, 11535, 11444, 11493, -1, 11537, 11471, 11536, -1, 11536, 11471, 11444, -1, 11538, 11472, 11537, -1, 11537, 11472, 11471, -1, 11538, 11512, 11472, -1, 11539, 11540, 11541, -1, 11542, 11468, 11427, -1, 11542, 11543, 11540, -1, 11542, 11427, 11544, -1, 11542, 11544, 11543, -1, 11545, 11546, 11547, -1, 11545, 11539, 11546, -1, 11548, 11495, 11468, -1, 11549, 11550, 11551, -1, 11548, 11540, 11539, -1, 11548, 11468, 11542, -1, 11548, 11542, 11540, -1, 11552, 11547, 11553, -1, 11552, 11545, 11547, -1, 11554, 11479, 11495, -1, 11554, 11539, 11545, -1, 11554, 11495, 11548, -1, 11554, 11548, 11539, -1, 11555, 11553, 11556, -1, 11555, 11552, 11553, -1, 11557, 11479, 11554, -1, 11557, 11480, 11479, -1, 11557, 11545, 11552, -1, 11557, 11554, 11545, -1, 11558, 11556, 11559, -1, 11458, 11460, 11560, -1, 11458, 11560, 11561, -1, 11558, 11555, 11556, -1, 11458, 11561, 11562, -1, 11458, 11562, 11563, -1, 11564, 11500, 11480, -1, 11564, 11480, 11557, -1, 11564, 11552, 11555, -1, 11564, 11557, 11552, -1, 11565, 11436, 11500, -1, 11565, 11558, 11436, -1, 11565, 11555, 11558, -1, 11565, 11564, 11555, -1, 11565, 11500, 11564, -1, 11566, 11436, 11558, -1, 11566, 11559, 11567, -1, 11566, 11567, 11568, -1, 11566, 11558, 11559, -1, 11566, 11568, 11506, -1, 11569, 11506, 11438, -1, 11569, 11438, 11436, -1, 11569, 11436, 11566, -1, 11569, 11566, 11506, -1, 11570, 11568, 11571, -1, 11570, 11571, 11572, -1, 11570, 11506, 11568, -1, 11573, 11506, 11570, -1, 11574, 11506, 11573, -1, 11575, 11506, 11574, -1, 11513, 11506, 11575, -1, 11543, 11576, 11550, -1, 11543, 11549, 11577, -1, 11543, 11550, 11549, -1, 11544, 11427, 11426, -1, 11544, 11426, 11458, -1, 11544, 11563, 11576, -1, 11544, 11458, 11563, -1, 11544, 11576, 11543, -1, 11540, 11577, 11541, -1, 11540, 11543, 11577, -1, 11539, 11541, 11546, -1, 9635, 11578, 9637, -1, 9632, 11578, 9635, -1, 9631, 11579, 9632, -1, 11580, 11579, 9631, -1, 11581, 11579, 11580, -1, 11582, 11579, 11581, -1, 11583, 11579, 11582, -1, 9651, 9649, 11584, -1, 11585, 11579, 11583, -1, 11586, 11579, 11585, -1, 9632, 11579, 11578, -1, 11584, 9653, 9651, -1, 11587, 11579, 11586, -1, 11587, 11586, 11588, -1, 9649, 9647, 11584, -1, 11584, 9655, 9653, -1, 9647, 9645, 11584, -1, 11584, 9657, 9655, -1, 11587, 11589, 11584, -1, 11584, 11589, 9657, -1, 11587, 11590, 11589, -1, 11587, 11591, 11590, -1, 11587, 11592, 11591, -1, 11587, 11593, 11592, -1, 11587, 11588, 11593, -1, 9643, 11594, 9645, -1, 9645, 11595, 11584, -1, 11594, 11595, 9645, -1, 9641, 11596, 9643, -1, 9643, 11596, 11594, -1, 11595, 11597, 11584, -1, 9639, 11598, 9641, -1, 9641, 11598, 11596, -1, 9639, 11578, 11598, -1, 9637, 11578, 9639, -1, 11599, 11600, 11601, -1, 11601, 11602, 11603, -1, 11600, 11602, 11601, -1, 11604, 11605, 11599, -1, 11599, 11605, 11600, -1, 11603, 11606, 11607, -1, 11602, 11606, 11603, -1, 11608, 11609, 11604, -1, 11604, 11609, 11605, -1, 11610, 11611, 11608, -1, 11608, 11611, 11609, -1, 11612, 11613, 11610, -1, 11610, 11613, 11611, -1, 10007, 10008, 11614, -1, 10008, 11615, 11614, -1, 11614, 11616, 11617, -1, 11615, 11616, 11614, -1, 11617, 11618, 11619, -1, 11616, 11618, 11617, -1, 11619, 11620, 11621, -1, 11618, 11620, 11619, -1, 11621, 11622, 11623, -1, 11620, 11622, 11621, -1, 11623, 11624, 11625, -1, 11622, 11624, 11623, -1, 11625, 11626, 11627, -1, 11624, 11626, 11625, -1, 11627, 11628, 11629, -1, 11626, 11628, 11627, -1, 11629, 11630, 11631, -1, 11628, 11630, 11629, -1, 11631, 11632, 11633, -1, 11630, 11632, 11631, -1, 11633, 11634, 11635, -1, 11632, 11634, 11633, -1, 11635, 11636, 11637, -1, 11634, 11636, 11635, -1, 11637, 9982, 9981, -1, 11636, 9982, 11637, -1, 9979, 11638, 9980, -1, 9980, 11638, 11639, -1, 11639, 11640, 11641, -1, 11638, 11640, 11639, -1, 11641, 11642, 11643, -1, 11640, 11642, 11641, -1, 11643, 11644, 11645, -1, 11642, 11644, 11643, -1, 11645, 11646, 11647, -1, 11644, 11646, 11645, -1, 11647, 11648, 11649, -1, 11646, 11648, 11647, -1, 11649, 11650, 11651, -1, 11648, 11650, 11649, -1, 11651, 11652, 11653, -1, 11650, 11652, 11651, -1, 11653, 11654, 11655, -1, 11652, 11654, 11653, -1, 11655, 11656, 11657, -1, 11654, 11656, 11655, -1, 11657, 11658, 11659, -1, 11656, 11658, 11657, -1, 11659, 11660, 11661, -1, 11658, 11660, 11659, -1, 11661, 9954, 9953, -1, 11660, 9954, 11661, -1, 9911, 9250, 9226, -1, 11662, 9250, 9911, -1, 11663, 9235, 11664, -1, 9234, 9235, 11663, -1, 11665, 11666, 11667, -1, 9227, 11666, 11668, -1, 11668, 11666, 11669, -1, 11669, 11666, 11670, -1, 11670, 11666, 11665, -1, 9226, 11666, 9227, -1, 9251, 11666, 9250, -1, 11671, 11666, 11672, -1, 11672, 11666, 9251, -1, 9250, 11666, 9226, -1, 11664, 11673, 11671, -1, 11671, 11673, 11666, -1, 9235, 11673, 11664, -1, 11674, 11675, 11676, -1, 11674, 11677, 11675, -1, 11674, 11678, 11677, -1, 11674, 11679, 11678, -1, 11680, 11681, 11674, -1, 11674, 11681, 11679, -1, 11680, 11682, 11681, -1, 11683, 11684, 11685, -1, 11682, 11684, 11686, -1, 11686, 11684, 11683, -1, 11680, 11684, 11682, -1, 11687, 11688, 11613, -1, 11612, 11687, 11613, -1, 9259, 9253, 9252, -1, 9259, 9257, 9253, -1, 9259, 11689, 11690, -1, 9259, 11691, 11689, -1, 9259, 11692, 11691, -1, 9259, 11693, 11692, -1, 9259, 9252, 11693, -1, 11694, 11695, 11690, -1, 11696, 11690, 11695, -1, 11697, 11694, 11690, -1, 11698, 11697, 11690, -1, 11699, 9259, 11690, -1, 11699, 11690, 11696, -1, 11700, 9259, 11699, -1, 11701, 9259, 11700, -1, 11702, 9259, 11701, -1, 11703, 9259, 11702, -1, 11704, 11698, 11690, -1, 11705, 11698, 11704, -1, 11706, 9259, 11703, -1, 11707, 11706, 11703, -1, 11708, 11709, 11710, -1, 11711, 11709, 11708, -1, 11712, 11713, 11714, -1, 11715, 11713, 11712, -1, 11716, 11717, 11718, -1, 11719, 9115, 9117, -1, 11717, 11720, 11718, -1, 11720, 11721, 11718, -1, 11722, 11723, 11724, -1, 11718, 11723, 11722, -1, 11721, 11723, 11718, -1, 9115, 11725, 9094, -1, 9094, 11725, 9092, -1, 11726, 11725, 11719, -1, 11723, 11727, 11724, -1, 11719, 11725, 9115, -1, 11723, 11728, 11727, -1, 11725, 9090, 9092, -1, 11725, 9103, 9090, -1, 11725, 11729, 9103, -1, 11730, 11731, 11732, -1, 11729, 11733, 11732, -1, 11732, 11733, 11730, -1, 11732, 11734, 11735, -1, 11731, 11734, 11732, -1, 11725, 11736, 11729, -1, 11729, 11736, 11733, -1, 11737, 11738, 11739, -1, 11739, 11738, 11740, -1, 11741, 11738, 11742, -1, 11734, 11743, 11735, -1, 11742, 11738, 11737, -1, 11728, 11744, 11745, -1, 11745, 11744, 11746, -1, 11746, 11744, 11747, -1, 11725, 11748, 11736, -1, 11723, 11744, 11728, -1, 11741, 11749, 11738, -1, 11735, 11750, 11751, -1, 11752, 11749, 11741, -1, 11743, 11750, 11735, -1, 11744, 11753, 11747, -1, 11750, 11754, 11751, -1, 11752, 11755, 11749, -1, 11751, 11754, 11756, -1, 11753, 11757, 11747, -1, 11754, 11758, 11756, -1, 11747, 11759, 11752, -1, 11757, 11759, 11747, -1, 11759, 11760, 11752, -1, 11752, 11760, 11755, -1, 11754, 11761, 11758, -1, 11762, 11740, 11754, -1, 11754, 11740, 11761, -1, 11762, 11763, 11740, -1, 11725, 11764, 11748, -1, 11763, 11765, 11740, -1, 11765, 11766, 11740, -1, 11766, 11739, 11740, -1, 11764, 11718, 11767, -1, 11767, 11718, 11768, -1, 11768, 11718, 11722, -1, 11725, 11718, 11764, -1, 11769, 11770, 11771, -1, 11771, 11770, 11772, -1, 11773, 8990, 11774, -1, 11772, 11770, 11775, -1, 11775, 11770, 8937, -1, 11769, 11776, 11770, -1, 11769, 11777, 11776, -1, 11778, 11777, 11769, -1, 11778, 11779, 11777, -1, 11780, 11779, 11778, -1, 11195, 10935, 11193, -1, 11193, 10935, 11190, -1, 11190, 10935, 10934, -1, 11199, 10935, 11195, -1, 11781, 11782, 11780, -1, 11780, 11782, 11779, -1, 10101, 11783, 10098, -1, 10105, 11783, 10101, -1, 11784, 10784, 11785, -1, 11783, 11786, 10098, -1, 11781, 11787, 11782, -1, 11788, 11787, 11781, -1, 10935, 11789, 11790, -1, 11790, 11789, 11791, -1, 11786, 11792, 10098, -1, 11788, 11793, 11787, -1, 10784, 11794, 11795, -1, 11795, 11794, 11796, -1, 8989, 11797, 8990, -1, 11784, 11794, 10784, -1, 11798, 11797, 11799, -1, 11799, 11797, 11800, -1, 11223, 11801, 11221, -1, 11800, 11797, 11802, -1, 11221, 11801, 11218, -1, 11802, 11797, 8989, -1, 11218, 11801, 10901, -1, 8990, 11797, 11774, -1, 11801, 11803, 10901, -1, 11798, 11804, 11797, -1, 11199, 11805, 10935, -1, 10935, 11805, 11789, -1, 11806, 11807, 11798, -1, 11798, 11807, 11804, -1, 11808, 11809, 11806, -1, 11806, 11809, 11807, -1, 11810, 11811, 11808, -1, 11805, 11812, 11789, -1, 11808, 11811, 11809, -1, 11805, 11813, 11812, -1, 11810, 11814, 11811, -1, 11784, 8951, 11794, -1, 11792, 10956, 10098, -1, 11805, 11815, 11813, -1, 11816, 10956, 11792, -1, 11805, 11817, 11815, -1, 11805, 11818, 11817, -1, 11819, 10902, 11820, -1, 11805, 11821, 11818, -1, 11816, 11822, 10956, -1, 10956, 11822, 11823, -1, 11823, 11822, 11824, -1, 11805, 8899, 11821, -1, 11070, 11825, 11068, -1, 11068, 11825, 11065, -1, 11065, 11825, 10753, -1, 11825, 11826, 10753, -1, 10902, 11827, 11828, -1, 11828, 11827, 11829, -1, 11819, 11827, 10902, -1, 11816, 9003, 11822, -1, 11814, 11830, 11831, -1, 11805, 8898, 8899, -1, 11832, 11830, 11810, -1, 8950, 11833, 8951, -1, 11810, 11830, 11814, -1, 11834, 11833, 11835, -1, 11835, 11833, 11836, -1, 11836, 11833, 11837, -1, 11838, 11830, 11839, -1, 11837, 11833, 8950, -1, 11839, 11830, 11840, -1, 11840, 11830, 11841, -1, 8951, 11833, 11794, -1, 11841, 11830, 11842, -1, 11842, 11830, 11843, -1, 11843, 11830, 11844, -1, 11844, 11830, 11845, -1, 11831, 11830, 11838, -1, 11834, 11846, 11833, -1, 9003, 11847, 11822, -1, 11830, 11847, 11845, -1, 9002, 11847, 9003, -1, 11819, 11848, 11827, -1, 11845, 11847, 9002, -1, 11847, 11849, 11822, -1, 11834, 11850, 11846, -1, 11851, 11850, 11834, -1, 11830, 11852, 11847, -1, 10987, 11853, 10983, -1, 11854, 11855, 11851, -1, 10727, 10726, 11856, -1, 10727, 11856, 11857, -1, 11016, 11858, 11012, -1, 10650, 10649, 11859, -1, 10650, 11859, 11860, -1, 11851, 11855, 11850, -1, 11045, 11861, 11041, -1, 10754, 10753, 11826, -1, 10754, 11826, 11862, -1, 11863, 11864, 11854, -1, 11074, 11825, 11070, -1, 10784, 10120, 11865, -1, 10784, 11865, 11785, -1, 10600, 11866, 10602, -1, 10810, 10809, 11867, -1, 11854, 11864, 11855, -1, 10810, 11867, 11868, -1, 11103, 11869, 11099, -1, 10843, 10842, 11870, -1, 10843, 11870, 11871, -1, 11135, 11872, 11131, -1, 10871, 10870, 11873, -1, 10871, 11873, 11874, -1, 11167, 11875, 11163, -1, 11876, 10754, 11862, -1, 10902, 10901, 11803, -1, 11877, 11878, 11863, -1, 10902, 11803, 11820, -1, 11163, 11875, 11161, -1, 11227, 11801, 11223, -1, 11161, 11875, 11158, -1, 11805, 11830, 11879, -1, 11863, 11878, 11864, -1, 11158, 11875, 10870, -1, 11805, 11879, 11880, -1, 11805, 11880, 11881, -1, 11805, 11881, 11882, -1, 11805, 11882, 11883, -1, 11805, 11883, 11884, -1, 11805, 11884, 11885, -1, 11805, 11885, 11877, -1, 11805, 11877, 11793, -1, 11805, 11793, 11788, -1, 11805, 11788, 11886, -1, 11805, 11886, 11887, -1, 11805, 11887, 11888, -1, 11877, 11885, 11878, -1, 11805, 11888, 11889, -1, 11805, 11889, 11890, -1, 11879, 11830, 11832, -1, 10648, 11783, 10105, -1, 10700, 10699, 11891, -1, 10700, 11891, 11892, -1, 11875, 11873, 10870, -1, 11876, 11893, 10754, -1, 10754, 11893, 11894, -1, 11894, 11893, 11895, -1, 11896, 11897, 11898, -1, 11898, 11897, 11899, -1, 11899, 11897, 11900, -1, 11900, 11897, 11901, -1, 11901, 11897, 11848, -1, 11848, 11897, 11827, -1, 11896, 11902, 11897, -1, 11896, 11903, 11902, -1, 11876, 8964, 11893, -1, 11904, 11903, 11896, -1, 11904, 11905, 11903, -1, 11906, 11905, 11904, -1, 11906, 11907, 11905, -1, 11908, 11907, 11906, -1, 11909, 10871, 11874, -1, 11908, 11910, 11907, -1, 8898, 11910, 11908, -1, 11805, 11910, 8898, -1, 11041, 11861, 11039, -1, 11039, 11861, 11036, -1, 11036, 11861, 10649, -1, 11805, 11890, 11910, -1, 11861, 11859, 10649, -1, 10871, 11911, 11912, -1, 11912, 11911, 11913, -1, 11909, 11911, 10871, -1, 11914, 11915, 11916, -1, 11916, 11915, 11917, -1, 11917, 11915, 11918, -1, 11918, 11915, 8963, -1, 8964, 11915, 11893, -1, 8963, 11915, 8964, -1, 11914, 11919, 11915, -1, 11914, 11920, 11919, -1, 11909, 8912, 11911, -1, 11921, 11920, 11914, -1, 11921, 11922, 11920, -1, 11923, 11922, 11921, -1, 11923, 11924, 11922, -1, 11925, 11924, 11923, -1, 11926, 10650, 11860, -1, 11925, 11927, 11924, -1, 11884, 11927, 11925, -1, 11884, 11883, 11927, -1, 11131, 11872, 11129, -1, 11129, 11872, 11126, -1, 11126, 11872, 10842, -1, 11872, 11870, 10842, -1, 11926, 11928, 10650, -1, 10650, 11928, 11929, -1, 11929, 11928, 11930, -1, 8911, 11931, 8912, -1, 11932, 11931, 11933, -1, 11933, 11931, 11934, -1, 11934, 11931, 11935, -1, 11935, 11931, 8911, -1, 8912, 11931, 11911, -1, 11932, 11936, 11931, -1, 11926, 8977, 11928, -1, 11937, 11938, 11932, -1, 11932, 11938, 11936, -1, 11939, 11940, 11937, -1, 11937, 11940, 11938, -1, 11941, 11942, 11939, -1, 11939, 11942, 11940, -1, 11943, 10843, 11871, -1, 11889, 11944, 11941, -1, 11012, 11858, 11010, -1, 11010, 11858, 11007, -1, 11941, 11944, 11942, -1, 11007, 11858, 10726, -1, 11889, 11888, 11944, -1, 11858, 11856, 10726, -1, 10843, 11945, 11946, -1, 11946, 11945, 11947, -1, 11943, 11945, 10843, -1, 8977, 11948, 11928, -1, 8976, 11948, 8977, -1, 11949, 11948, 11950, -1, 11950, 11948, 11951, -1, 11951, 11948, 11952, -1, 11952, 11948, 8976, -1, 11949, 11953, 11948, -1, 11954, 11955, 11949, -1, 11943, 8925, 11945, -1, 11949, 11955, 11953, -1, 11954, 11956, 11955, -1, 11957, 11956, 11954, -1, 11958, 11959, 11957, -1, 11957, 11959, 11956, -1, 11960, 10727, 11857, -1, 11882, 11961, 11958, -1, 11958, 11961, 11959, -1, 11099, 11869, 11097, -1, 11097, 11869, 11094, -1, 11094, 11869, 10809, -1, 11882, 11881, 11961, -1, 11869, 11867, 10809, -1, 11960, 11962, 10727, -1, 10727, 11962, 11963, -1, 11963, 11962, 11964, -1, 8925, 11965, 11945, -1, 8924, 11965, 8925, -1, 11966, 11965, 11967, -1, 11967, 11965, 11968, -1, 11968, 11965, 11969, -1, 11969, 11965, 8924, -1, 11966, 11970, 11965, -1, 11960, 9065, 11962, -1, 11966, 11971, 11970, -1, 11972, 11971, 11966, -1, 11972, 11973, 11971, -1, 11974, 11973, 11972, -1, 11974, 11975, 11973, -1, 11976, 11975, 11974, -1, 11977, 10810, 11868, -1, 10983, 11853, 10981, -1, 10981, 11853, 10978, -1, 10978, 11853, 10699, -1, 11976, 11978, 11975, -1, 11887, 11978, 11976, -1, 11887, 11886, 11978, -1, 11853, 11891, 10699, -1, 10810, 11979, 11980, -1, 11980, 11979, 11981, -1, 11977, 11979, 10810, -1, 9065, 11982, 11962, -1, 9064, 11982, 9065, -1, 11983, 11982, 11984, -1, 11984, 11982, 11985, -1, 11985, 11982, 11986, -1, 11986, 11982, 9064, -1, 10602, 10120, 10783, -1, 10783, 10120, 10782, -1, 10782, 10120, 10119, -1, 11983, 11987, 11982, -1, 11988, 11989, 11983, -1, 11983, 11989, 11987, -1, 11990, 11991, 11988, -1, 11988, 11991, 11989, -1, 11977, 8938, 11979, -1, 11990, 11992, 11991, -1, 11993, 11992, 11990, -1, 11773, 10700, 11892, -1, 11880, 11994, 11993, -1, 11993, 11994, 11992, -1, 11880, 11879, 11994, -1, 10700, 11774, 11995, -1, 11995, 11774, 11996, -1, 10602, 11866, 10120, -1, 11773, 11774, 10700, -1, 11866, 11865, 10120, -1, 8938, 11770, 11979, -1, 8937, 11770, 8938, -1, 11532, 11997, 11998, -1, 11533, 11532, 11998, -1, 11999, 11533, 11998, -1, 12000, 11999, 11998, -1, 12001, 12002, 12003, -1, 12001, 12004, 12005, -1, 12001, 12006, 12004, -1, 12001, 12007, 12006, -1, 12001, 12003, 12007, -1, 9121, 12008, 12009, -1, 9121, 12010, 12008, -1, 9121, 12011, 12010, -1, 9121, 12005, 12011, -1, 9121, 12001, 12005, -1, 11998, 9121, 12009, -1, 11998, 12009, 12012, -1, 11998, 12012, 12000, -1, 12013, 12014, 12015, -1, 12015, 12014, 12016, -1, 12017, 12018, 12013, -1, 12019, 12018, 12017, -1, 12013, 12018, 12014, -1, 12019, 12020, 12018, -1, 12021, 12022, 12023, -1, 12014, 12022, 12021, -1, 12018, 12022, 12014, -1, 12024, 9072, 9070, -1, 9072, 12025, 12026, -1, 12024, 12025, 9072, -1, 12027, 12028, 12029, -1, 12029, 12028, 12030, -1, 12030, 12028, 12031, -1, 12031, 12028, 12032, -1, 12032, 12028, 12033, -1, 12033, 12028, 12034, -1, 12034, 12028, 12035, -1, 12035, 12036, 12037, -1, 12035, 12038, 12036, -1, 12037, 12039, 12035, -1, 12028, 12040, 12035, -1, 12035, 12040, 12038, -1, 12028, 12041, 12040, -1, 12028, 12042, 12041, -1, 12028, 12043, 12042, -1, 12028, 12044, 12043, -1, 12039, 12045, 12035, -1, 12039, 12046, 12045, -1, 12028, 12047, 12044, -1, 12048, 12049, 12047, -1, 12049, 12050, 12047, -1, 12050, 12051, 12047, -1, 12051, 12024, 12047, -1, 12047, 12052, 12044, -1, 12024, 12052, 12047, -1, 12024, 12053, 12052, -1, 12024, 12054, 12053, -1, 12024, 9067, 12054, -1, 12024, 9069, 9067, -1, 12024, 9070, 9069, -1, 12055, 12056, 12057, -1, 8582, 12058, 8581, -1, 12059, 9076, 12058, -1, 12058, 9076, 8581, -1, 12059, 12060, 9076, -1, 12060, 12061, 9076, -1, 12061, 12062, 9076, -1, 12062, 12063, 9076, -1, 12063, 9074, 9076, -1, 12064, 11726, 11719, -1, 12065, 11726, 12066, -1, 12066, 11726, 12067, -1, 12067, 11726, 12068, -1, 12068, 11726, 12064, -1, 12069, 12070, 12071, -1, 12071, 12070, 12065, -1, 12065, 12070, 11726, -1, 12069, 12072, 12070, -1, 12069, 12073, 12072, -1, 12073, 12074, 12072, -1, 12073, 12075, 12074, -1, 12074, 12076, 12077, -1, 12075, 12076, 12074, -1, 12076, 11849, 12077, -1, 11849, 12078, 12077, -1, 11849, 12079, 12078, -1, 11849, 11847, 12079, -1, 12080, 12081, 12082, -1, 12082, 12081, 12083, -1, 12083, 12081, 12084, -1, 12084, 12081, 12085, -1, 12085, 12081, 12086, -1, 12086, 12081, 12087, -1, 12088, 12081, 12080, -1, 9258, 9259, 12089, -1, 12088, 12090, 12081, -1, 12081, 12089, 12091, -1, 12081, 12091, 12087, -1, 12092, 12093, 12089, -1, 12089, 12094, 12092, -1, 12093, 12095, 12089, -1, 12089, 12096, 12094, -1, 12095, 12097, 12089, -1, 9259, 12098, 12089, -1, 12089, 12098, 12096, -1, 12097, 12091, 12089, -1, 9259, 11706, 12098, -1, 12099, 12100, 12101, -1, 12101, 12102, 12103, -1, 12100, 12102, 12101, -1, 12104, 12105, 12099, -1, 12099, 12105, 12100, -1, 12103, 12106, 12107, -1, 12102, 12106, 12103, -1, 12108, 12109, 12104, -1, 12104, 12109, 12105, -1, 12107, 12110, 12091, -1, 12106, 12110, 12107, -1, 11688, 12111, 12108, -1, 12108, 12111, 12109, -1, 12110, 12087, 12091, -1, 11688, 11687, 12111, -1, 9293, 12112, 12113, -1, 12114, 12115, 12116, -1, 12116, 12117, 12114, -1, 12115, 12118, 12116, -1, 12116, 12119, 12117, -1, 12118, 12120, 12116, -1, 12116, 9279, 12119, -1, 12121, 9280, 12116, -1, 12116, 9280, 9279, -1, 12121, 9283, 9280, -1, 12121, 9285, 9283, -1, 12121, 9287, 9285, -1, 12121, 9289, 9287, -1, 12121, 9291, 9289, -1, 12121, 9293, 9291, -1, 12122, 12123, 12120, -1, 12124, 12123, 12125, -1, 12125, 12123, 12126, -1, 12126, 12123, 12127, -1, 12127, 12123, 12128, -1, 12128, 12123, 12129, -1, 12129, 12123, 12122, -1, 12120, 12123, 12116, -1, 12113, 12112, 12130, -1, 12130, 12112, 12131, -1, 12131, 12112, 12132, -1, 12132, 12112, 12133, -1, 12133, 12112, 12134, -1, 12134, 12112, 12135, -1, 12135, 12112, 12124, -1, 12124, 12112, 12123, -1, 12121, 12112, 9293, -1, 12136, 12137, 12138, -1, 12138, 12137, 12139, -1, 12140, 12141, 12142, -1, 12139, 12137, 12143, -1, 12143, 12137, 12144, -1, 12145, 12137, 12136, -1, 12146, 12147, 12142, -1, 12142, 12147, 12140, -1, 12141, 12148, 12142, -1, 12145, 12149, 12137, -1, 12146, 12150, 12147, -1, 12151, 12152, 12153, -1, 12153, 12152, 12154, -1, 12148, 12155, 12142, -1, 12145, 12156, 12149, -1, 12146, 9268, 12150, -1, 12154, 12157, 12145, -1, 12152, 12157, 12154, -1, 12145, 12158, 12156, -1, 12155, 12159, 12142, -1, 12157, 12160, 12145, -1, 12146, 9270, 9268, -1, 12145, 12160, 12158, -1, 12161, 12142, 12162, -1, 12146, 12145, 9277, -1, 9277, 12145, 12163, -1, 12159, 12162, 12142, -1, 12146, 9271, 9270, -1, 12146, 9273, 9271, -1, 12146, 9275, 9273, -1, 12146, 9277, 9275, -1, 12164, 12161, 12162, -1, 12164, 12165, 12161, -1, 12161, 12166, 12167, -1, 12168, 12144, 12165, -1, 12166, 12144, 12169, -1, 12169, 12144, 12170, -1, 12165, 12144, 12161, -1, 12161, 12144, 12166, -1, 12168, 12171, 12144, -1, 12171, 12172, 12144, -1, 12172, 12173, 12144, -1, 12173, 12143, 12144, -1, 12163, 12145, 12174, -1, 12174, 12145, 12175, -1, 12175, 12145, 12176, -1, 12176, 12145, 12136, -1, 12177, 12178, 12179, -1, 12179, 12178, 12180, -1, 12178, 12181, 12180, -1, 12180, 12181, 12182, -1, 12181, 9961, 12182, -1, 9959, 9961, 12181, -1, 12181, 9957, 9959, -1, 9961, 9963, 12182, -1, 12181, 9955, 9957, -1, 9963, 9965, 12182, -1, 12181, 9953, 9955, -1, 9965, 9967, 12182, -1, 12181, 11661, 9953, -1, 12183, 12184, 12182, -1, 12182, 12185, 12183, -1, 9967, 9969, 12182, -1, 12184, 12186, 12182, -1, 12182, 12187, 12185, -1, 9969, 12188, 12182, -1, 12182, 12188, 12187, -1, 9969, 9971, 12188, -1, 9971, 9973, 12188, -1, 9973, 9975, 12188, -1, 11649, 11712, 11647, -1, 11651, 11712, 11649, -1, 11653, 11712, 11651, -1, 11655, 11712, 11653, -1, 11657, 11712, 11655, -1, 11659, 11712, 11657, -1, 11661, 11712, 11659, -1, 12181, 11712, 11661, -1, 12181, 12189, 11712, -1, 12190, 12191, 12192, -1, 12192, 12191, 12189, -1, 12189, 12191, 11712, -1, 12193, 12191, 12194, -1, 12194, 12191, 12195, -1, 12195, 12191, 12196, -1, 12196, 12191, 12197, -1, 12197, 12191, 12190, -1, 11639, 11714, 9980, -1, 11641, 11714, 11639, -1, 11643, 11714, 11641, -1, 11645, 11714, 11643, -1, 11647, 11714, 11645, -1, 9977, 11714, 9975, -1, 9980, 11714, 9977, -1, 9975, 11714, 12188, -1, 12198, 12199, 12200, -1, 12199, 12201, 12200, -1, 12198, 12202, 12199, -1, 12203, 12202, 12198, -1, 12203, 12204, 12202, -1, 12205, 12204, 12203, -1, 12205, 12206, 12204, -1, 12207, 12206, 12208, -1, 12208, 12206, 12205, -1, 12207, 11710, 12206, -1, 12209, 11710, 12210, -1, 12210, 11710, 12207, -1, 11708, 11710, 12209, -1, 12211, 9987, 12212, -1, 9987, 9989, 12212, -1, 12212, 9989, 12213, -1, 12211, 9985, 9987, -1, 12214, 9985, 12211, -1, 9989, 9991, 12213, -1, 12213, 9991, 12215, -1, 12214, 9983, 9985, -1, 12216, 9983, 12214, -1, 12216, 9981, 9983, -1, 12217, 9981, 12216, -1, 9993, 12218, 9991, -1, 9995, 12218, 9993, -1, 9991, 12218, 12215, -1, 12215, 12218, 12219, -1, 12219, 12218, 12220, -1, 12217, 11637, 9981, -1, 9995, 9997, 12218, -1, 12217, 11635, 11637, -1, 9997, 9999, 12218, -1, 12217, 11633, 11635, -1, 11704, 11633, 12217, -1, 9999, 10001, 12218, -1, 11704, 11631, 11633, -1, 11704, 11629, 11631, -1, 11704, 11627, 11629, -1, 11704, 11625, 11627, -1, 11614, 11690, 10007, -1, 11617, 11690, 11614, -1, 11619, 11690, 11617, -1, 11621, 11690, 11619, -1, 11623, 11690, 11621, -1, 11625, 11690, 11623, -1, 10003, 11690, 10001, -1, 10005, 11690, 10003, -1, 10007, 11690, 10005, -1, 10001, 11690, 12218, -1, 11704, 11690, 11625, -1, 11712, 11714, 11647, -1, 12218, 12182, 12186, -1, 12218, 12186, 12200, -1, 12218, 12200, 12220, -1, 12220, 12200, 12201, -1, 12090, 12088, 11579, -1, 11587, 12090, 11579, -1, 11712, 12191, 11715, -1, 12221, 9162, 12222, -1, 12222, 9162, 12191, -1, 12191, 9162, 11715, -1, 12223, 9159, 12221, -1, 12221, 9159, 9162, -1, 12224, 9157, 12223, -1, 12223, 9157, 9159, -1, 12225, 9155, 12224, -1, 12224, 9155, 9157, -1, 12226, 9150, 12227, -1, 12227, 9150, 9149, -1, 12227, 9149, 12228, -1, 12228, 9149, 9153, -1, 12228, 9153, 12225, -1, 12225, 9153, 9155, -1, 12229, 11703, 9659, -1, 12230, 11703, 12229, -1, 12231, 11703, 12230, -1, 12232, 11703, 12231, -1, 12233, 11703, 12232, -1, 12234, 11703, 12233, -1, 12235, 11703, 12234, -1, 12236, 11703, 12235, -1, 11707, 11703, 12236, -1, 9659, 11703, 9124, -1, 12237, 9679, 12238, -1, 12239, 9677, 12240, -1, 12238, 9677, 12239, -1, 9679, 9677, 12238, -1, 12237, 9681, 9679, -1, 9677, 9675, 12240, -1, 12237, 9684, 9681, -1, 12237, 9686, 9684, -1, 11707, 12241, 12237, -1, 12237, 12241, 9686, -1, 9673, 9124, 9675, -1, 9671, 9124, 9673, -1, 12242, 9124, 12243, -1, 12244, 9124, 12242, -1, 12240, 9124, 12244, -1, 9675, 9124, 12240, -1, 9671, 9669, 9124, -1, 11707, 12245, 12241, -1, 9669, 9667, 9124, -1, 11707, 12246, 12245, -1, 9667, 9665, 9124, -1, 11707, 12247, 12246, -1, 9665, 9663, 9124, -1, 11707, 12236, 12247, -1, 9663, 9660, 9124, -1, 9660, 9659, 9124, -1, 9896, 9923, 12248, -1, 11698, 9894, 12248, -1, 12248, 9894, 9896, -1, 9923, 9921, 12248, -1, 11698, 9897, 9894, -1, 9921, 9919, 12248, -1, 11698, 9899, 9897, -1, 9919, 9916, 12248, -1, 11698, 12249, 9899, -1, 9916, 9914, 12248, -1, 11698, 12250, 12249, -1, 9914, 9908, 12248, -1, 11698, 12251, 12250, -1, 11698, 12252, 12251, -1, 11698, 12253, 12252, -1, 11698, 12254, 12253, -1, 11698, 12255, 12254, -1, 9904, 12256, 9906, -1, 12256, 12257, 9906, -1, 9906, 12257, 9908, -1, 9904, 12258, 12256, -1, 9901, 12258, 9904, -1, 9908, 12259, 12248, -1, 12257, 12259, 9908, -1, 9901, 12260, 12258, -1, 9900, 12260, 9901, -1, 12259, 12261, 12248, -1, 9900, 12262, 12260, -1, 12263, 12262, 9900, -1, 12264, 12262, 12263, -1, 12265, 12262, 12264, -1, 12261, 12266, 12248, -1, 12266, 12267, 12248, -1, 12265, 11705, 12262, -1, 11698, 11705, 12255, -1, 12268, 11705, 12265, -1, 12269, 11705, 12268, -1, 12255, 11705, 12269, -1, 12270, 12271, 12272, -1, 12273, 12271, 12270, -1, 11709, 12274, 12270, -1, 12270, 12274, 12273, -1, 12272, 12275, 12276, -1, 12271, 12275, 12272, -1, 11709, 12277, 12274, -1, 12276, 12278, 12279, -1, 12275, 12278, 12276, -1, 11709, 12280, 12277, -1, 12279, 12281, 12282, -1, 12278, 12281, 12279, -1, 11709, 11711, 12280, -1, 9945, 9943, 12283, -1, 12283, 9947, 9945, -1, 11713, 9947, 12283, -1, 9943, 9941, 12283, -1, 11713, 9950, 9947, -1, 11713, 9952, 9950, -1, 12284, 12285, 12286, -1, 12287, 12285, 12284, -1, 9941, 12285, 12283, -1, 12288, 12285, 12287, -1, 12289, 12285, 12288, -1, 12283, 12285, 12289, -1, 9939, 12285, 9941, -1, 9937, 12285, 9939, -1, 11713, 12290, 9952, -1, 9937, 9935, 12285, -1, 11713, 12291, 12290, -1, 9935, 9933, 12285, -1, 11713, 12292, 12291, -1, 9933, 9931, 12285, -1, 12285, 12293, 12294, -1, 11713, 12295, 12292, -1, 12285, 12296, 12293, -1, 11713, 12297, 12295, -1, 12285, 12298, 12296, -1, 9931, 12299, 12285, -1, 12285, 12299, 12298, -1, 9929, 12299, 9931, -1, 9928, 12299, 9929, -1, 9926, 12299, 9928, -1, 12300, 12299, 9926, -1, 12300, 11715, 12299, -1, 12301, 11715, 12300, -1, 12302, 11715, 12301, -1, 12303, 11715, 12302, -1, 12304, 11715, 12303, -1, 12305, 11715, 12304, -1, 12306, 11715, 12305, -1, 12297, 11715, 12306, -1, 11715, 12307, 12299, -1, 11715, 9162, 12307, -1, 9162, 12308, 12307, -1, 9161, 12309, 9162, -1, 12309, 12310, 9162, -1, 9162, 12311, 12308, -1, 12310, 12312, 9162, -1, 9162, 12313, 12311, -1, 9162, 12314, 12313, -1, 12312, 12314, 9162, -1, 11713, 11715, 12297, -1, 12285, 12248, 12286, -1, 12286, 12248, 12281, -1, 12281, 12248, 12267, -1, 12281, 12267, 12282, -1, 12315, 12316, 12317, -1, 12317, 12316, 12318, -1, 12319, 12320, 12321, -1, 12322, 12320, 12319, -1, 12323, 12320, 12322, -1, 12324, 12320, 12323, -1, 12321, 12320, 12325, -1, 12326, 12327, 12328, -1, 12315, 12327, 12316, -1, 12328, 12327, 12315, -1, 12329, 12330, 12331, -1, 12324, 12330, 12320, -1, 12331, 12330, 12324, -1, 12326, 12332, 12327, -1, 12332, 12333, 12327, -1, 12332, 12334, 12333, -1, 12335, 12336, 12337, -1, 12337, 12336, 12338, -1, 12338, 12336, 12339, -1, 12339, 12336, 12340, -1, 12334, 12341, 12333, -1, 12342, 12343, 12336, -1, 12340, 12343, 12344, -1, 12336, 12343, 12340, -1, 12345, 12346, 12347, -1, 12347, 12346, 12348, -1, 12348, 12346, 12349, -1, 12349, 12346, 12350, -1, 12351, 12346, 12345, -1, 12352, 12353, 12354, -1, 12345, 12355, 12351, -1, 12356, 12353, 12352, -1, 12333, 12353, 12356, -1, 12346, 12357, 12350, -1, 12341, 12353, 12333, -1, 12345, 12358, 12355, -1, 12357, 12359, 12350, -1, 12360, 12361, 12362, -1, 12345, 12363, 12358, -1, 12359, 12364, 12350, -1, 12362, 12365, 12342, -1, 12361, 12365, 12362, -1, 12360, 12325, 12361, -1, 12364, 12366, 12350, -1, 12350, 12366, 12342, -1, 12367, 12325, 12360, -1, 12368, 12325, 12367, -1, 12369, 12325, 12368, -1, 12321, 12325, 12369, -1, 12366, 12362, 12342, -1, 12365, 12370, 12342, -1, 12345, 12317, 12363, -1, 12370, 12371, 12342, -1, 12317, 12372, 12363, -1, 12373, 12374, 12371, -1, 12375, 12374, 12376, -1, 12376, 12374, 12373, -1, 12371, 12374, 12342, -1, 12342, 12374, 12343, -1, 12317, 12318, 12372, -1, 12377, 12324, 12323, -1, 12378, 12324, 12377, -1, 12354, 12324, 12378, -1, 12353, 12324, 12354, -1, 12379, 12331, 12324, -1, 12380, 9264, 12381, -1, 9264, 9263, 12381, -1, 12382, 9260, 9163, -1, 9260, 9164, 9163, -1, 12383, 12384, 12385, -1, 12385, 12386, 8589, -1, 8588, 12386, 12387, -1, 8589, 12386, 8588, -1, 12384, 12386, 12385, -1, 12388, 12389, 12390, -1, 12391, 12389, 12388, -1, 12392, 12393, 12394, -1, 12392, 12394, 12395, -1, 9218, 12396, 9219, -1, 9218, 8905, 12396, -1, 12397, 12398, 9207, -1, 12398, 12399, 9207, -1, 8882, 12400, 8883, -1, 8882, 8918, 12400, -1, 12401, 12402, 12403, -1, 12404, 12402, 12401, -1, 12405, 12406, 8871, -1, 12406, 12407, 8871, -1, 8833, 12408, 8834, -1, 8833, 8931, 12408, -1, 12409, 12410, 12411, -1, 12412, 12410, 12409, -1, 12413, 12414, 8822, -1, 12414, 12415, 8822, -1, 8784, 12416, 8785, -1, 8784, 8944, 12416, -1, 12417, 12418, 12419, -1, 12420, 12418, 12417, -1, 12421, 12422, 8773, -1, 12422, 12423, 8773, -1, 8736, 12424, 8735, -1, 8736, 8957, 12424, -1, 12425, 12426, 12427, -1, 12428, 12426, 12425, -1, 12429, 12430, 8724, -1, 12430, 12431, 8724, -1, 8686, 12432, 8687, -1, 8686, 8970, 12432, -1, 12433, 12434, 12435, -1, 12436, 12434, 12433, -1, 12437, 12438, 8675, -1, 12438, 12439, 8675, -1, 9052, 12440, 9051, -1, 9052, 9058, 12440, -1, 12441, 12442, 12443, -1, 12444, 12442, 12441, -1, 12445, 12446, 9040, -1, 12446, 12447, 9040, -1, 8532, 12448, 8533, -1, 8532, 8983, 12448, -1, 12449, 12450, 12451, -1, 12452, 12450, 12449, -1, 12453, 12454, 8570, -1, 12454, 12455, 8570, -1, 8638, 12456, 8637, -1, 8638, 8996, 12456, -1, 12457, 12458, 12459, -1, 12460, 12458, 12457, -1, 12461, 12462, 8626, -1, 12462, 12463, 8626, -1, 12464, 12064, 9099, -1, 12465, 12064, 12464, -1, 12064, 9100, 9099, -1, 12064, 9107, 9100, -1, 12064, 9117, 9107, -1, 12064, 11719, 9117, -1, 12465, 12466, 12467, -1, 12464, 12466, 12465, -1, 12468, 12469, 12470, -1, 12471, 12469, 12468, -1, 12469, 12472, 12470, -1, 12472, 12473, 12470, -1, 12470, 12474, 12475, -1, 12473, 12474, 12470, -1, 12476, 12477, 12478, -1, 12478, 12477, 12479, -1, 12479, 12477, 12480, -1, 12480, 12477, 12481, -1, 12481, 12477, 12482, -1, 12477, 12483, 12482, -1, 12483, 12484, 12485, -1, 12477, 12484, 12483, -1, 12484, 12486, 12485, -1, 12487, 10465, 12488, -1, 12488, 10465, 12489, -1, 12489, 10465, 12490, -1, 12484, 12491, 12486, -1, 12490, 12492, 12484, -1, 12484, 12492, 12491, -1, 10465, 12492, 12490, -1, 10465, 12493, 12492, -1, 10465, 12494, 12493, -1, 10465, 10464, 12494, -1, 12495, 12496, 11551, -1, 12495, 12497, 12496, -1, 12498, 12499, 12500, -1, 12498, 12500, 12497, -1, 12498, 12497, 12495, -1, 12501, 12502, 12503, -1, 12501, 12504, 12502, -1, 12505, 12501, 12503, -1, 12506, 12507, 12508, -1, 12509, 12508, 12510, -1, 12509, 12506, 12508, -1, 12372, 12318, 11737, -1, 11737, 12318, 11742, -1, 11742, 12316, 11741, -1, 12318, 12316, 11742, -1, 11741, 12327, 11752, -1, 12316, 12327, 11741, -1, 11752, 12333, 11747, -1, 12327, 12333, 11752, -1, 11747, 12356, 11746, -1, 12333, 12356, 11747, -1, 11746, 12352, 11745, -1, 12356, 12352, 11746, -1, 11745, 12354, 11728, -1, 12352, 12354, 11745, -1, 11728, 12378, 11727, -1, 12354, 12378, 11728, -1, 11727, 12377, 11724, -1, 12378, 12377, 11727, -1, 11724, 12323, 11722, -1, 12377, 12323, 11724, -1, 11722, 12322, 11768, -1, 12323, 12322, 11722, -1, 11768, 12319, 11767, -1, 12322, 12319, 11768, -1, 11767, 12321, 11764, -1, 12319, 12321, 11767, -1, 11748, 12321, 12369, -1, 11764, 12321, 11748, -1, 12369, 12368, 11748, -1, 11736, 12368, 11733, -1, 11748, 12368, 11736, -1, 11733, 12367, 11730, -1, 12368, 12367, 11733, -1, 11730, 12360, 11731, -1, 12367, 12360, 11730, -1, 11731, 12362, 11734, -1, 12360, 12362, 11731, -1, 11734, 12366, 11743, -1, 12362, 12366, 11734, -1, 11743, 12364, 11750, -1, 12366, 12364, 11743, -1, 11750, 12359, 11754, -1, 12364, 12359, 11750, -1, 11754, 12357, 11762, -1, 12359, 12357, 11754, -1, 11762, 12346, 11763, -1, 12357, 12346, 11762, -1, 11763, 12351, 11765, -1, 12346, 12351, 11763, -1, 11765, 12355, 11766, -1, 12351, 12355, 11765, -1, 11766, 12358, 11739, -1, 12355, 12358, 11766, -1, 12358, 12363, 11739, -1, 12372, 11737, 12363, -1, 12363, 11737, 11739, -1, 12511, 12512, 12513, -1, 12512, 12514, 12513, -1, 12515, 12516, 12517, -1, 12515, 12518, 12516, -1, 12519, 12520, 12521, -1, 12520, 12522, 12523, -1, 12519, 12522, 12520, -1, 12524, 12525, 12526, -1, 12527, 12525, 12528, -1, 12528, 12525, 12529, -1, 12529, 12525, 12524, -1, 12530, 12531, 12527, -1, 12527, 12531, 12525, -1, 12532, 12026, 12025, -1, 12532, 12025, 12533, -1, 12534, 12535, 12026, -1, 12536, 12026, 12532, -1, 12537, 12534, 12026, -1, 12538, 12026, 12536, -1, 12539, 12540, 11538, -1, 12541, 12026, 12538, -1, 12542, 12543, 12540, -1, 12542, 12540, 12539, -1, 12544, 12537, 12026, -1, 12545, 12026, 12541, -1, 12546, 12547, 12543, -1, 12546, 12548, 12547, -1, 12545, 12544, 12026, -1, 12549, 12550, 12551, -1, 12546, 12543, 12542, -1, 12552, 12539, 11538, -1, 12553, 12554, 12548, -1, 12553, 12548, 12546, -1, 8523, 12554, 12553, -1, 8525, 12554, 8523, -1, 12555, 12554, 8525, -1, 12556, 12550, 12549, -1, 12557, 12555, 8525, -1, 12556, 12558, 12559, -1, 12556, 12549, 12558, -1, 12560, 12555, 12557, -1, 12561, 12560, 12557, -1, 12562, 12556, 12559, -1, 12563, 12560, 12561, -1, 12564, 12562, 12559, -1, 12565, 12563, 12561, -1, 12566, 12567, 12568, -1, 12566, 12569, 12567, -1, 12570, 12563, 12565, -1, 12571, 12570, 12565, -1, 12566, 12568, 12572, -1, 12573, 12571, 12565, -1, 12574, 12559, 12569, -1, 12574, 12564, 12559, -1, 12575, 12574, 12569, -1, 12575, 12569, 12566, -1, 12576, 12571, 12573, -1, 12568, 12577, 12572, -1, 12578, 12576, 12573, -1, 12579, 12576, 12578, -1, 12580, 12579, 12578, -1, 12550, 12579, 12580, -1, 12551, 12550, 12580, -1, 12581, 12582, 12577, -1, 12572, 12577, 12582, -1, 12583, 12577, 12026, -1, 12583, 12581, 12577, -1, 12535, 12583, 12026, -1, 12584, 11830, 12585, -1, 12585, 11830, 12586, -1, 12584, 11852, 11830, -1, 12587, 12588, 12589, -1, 12590, 12588, 12587, -1, 12588, 12591, 12592, -1, 12590, 12591, 12588, -1, 12592, 12593, 12594, -1, 12591, 12593, 12592, -1, 12594, 12595, 12596, -1, 12593, 12595, 12594, -1, 12596, 12597, 12598, -1, 12595, 12597, 12596, -1, 12598, 12599, 12600, -1, 12597, 12599, 12598, -1, 12600, 12601, 12602, -1, 12602, 12601, 12603, -1, 12599, 12601, 12600, -1, 12601, 12604, 12603, -1, 12604, 12605, 12603, -1, 12606, 12605, 12604, -1, 12607, 12501, 12505, -1, 12607, 12505, 12608, -1, 12609, 12608, 12610, -1, 12609, 12607, 12608, -1, 12611, 12610, 12612, -1, 12611, 12609, 12610, -1, 12613, 12612, 12614, -1, 12613, 12611, 12612, -1, 12615, 12614, 12616, -1, 12615, 12613, 12614, -1, 12617, 12618, 12510, -1, 12617, 12616, 12618, -1, 12617, 12615, 12616, -1, 12508, 12617, 12510, -1, 12504, 12501, 12607, -1, 12619, 12504, 12607, -1, 12620, 12607, 12609, -1, 12620, 12619, 12607, -1, 12621, 12609, 12611, -1, 12621, 12620, 12609, -1, 12622, 12611, 12613, -1, 12622, 12621, 12611, -1, 12623, 12613, 12615, -1, 12623, 12622, 12613, -1, 12624, 12615, 12617, -1, 12624, 12623, 12615, -1, 12507, 12617, 12508, -1, 12507, 12624, 12617, -1, 12625, 12519, 12521, -1, 12625, 12521, 12626, -1, 12627, 12628, 12629, -1, 12627, 12626, 12628, -1, 12627, 12625, 12626, -1, 12630, 12627, 12629, -1, 12343, 12629, 12344, -1, 12343, 12630, 12629, -1, 12386, 12384, 12631, -1, 12632, 12631, 12633, -1, 12632, 12386, 12631, -1, 12634, 12633, 12521, -1, 12634, 12632, 12633, -1, 12520, 12634, 12521, -1, 12635, 12498, 12495, -1, 12635, 12636, 12637, -1, 12635, 12495, 12636, -1, 12638, 12637, 12639, -1, 12638, 12635, 12637, -1, 12640, 12638, 12639, -1, 12502, 12639, 12503, -1, 12502, 12640, 12639, -1, 12587, 12589, 12641, -1, 12641, 12642, 12643, -1, 12589, 12642, 12641, -1, 12643, 12644, 12645, -1, 12642, 12644, 12643, -1, 12645, 12646, 12531, -1, 12644, 12646, 12645, -1, 12646, 12525, 12531, -1, 12187, 12188, 12283, -1, 12187, 12283, 12289, -1, 12185, 12289, 12288, -1, 12185, 12187, 12289, -1, 12183, 12288, 12287, -1, 12183, 12185, 12288, -1, 12184, 12287, 12284, -1, 12184, 12183, 12287, -1, 12186, 12284, 12286, -1, 12186, 12184, 12284, -1, 12200, 12286, 12281, -1, 12200, 12186, 12286, -1, 12198, 12281, 12278, -1, 12198, 12200, 12281, -1, 12203, 12278, 12275, -1, 12203, 12198, 12278, -1, 12205, 12275, 12271, -1, 12205, 12203, 12275, -1, 12208, 12271, 12273, -1, 12208, 12205, 12271, -1, 12207, 12273, 12274, -1, 12207, 12208, 12273, -1, 12210, 12274, 12277, -1, 12210, 12207, 12274, -1, 12209, 12277, 12280, -1, 12209, 12210, 12277, -1, 11714, 11713, 12283, -1, 11714, 12283, 12188, -1, 11708, 12209, 12280, -1, 11711, 11708, 12280, -1, 12204, 12206, 12270, -1, 12204, 12270, 12272, -1, 12202, 12272, 12276, -1, 12202, 12204, 12272, -1, 12199, 12276, 12279, -1, 12199, 12202, 12276, -1, 12201, 12279, 12282, -1, 12201, 12199, 12279, -1, 12220, 12282, 12267, -1, 12220, 12201, 12282, -1, 12219, 12266, 12261, -1, 12219, 12267, 12266, -1, 12219, 12220, 12267, -1, 12215, 12219, 12261, -1, 12213, 12261, 12259, -1, 12213, 12215, 12261, -1, 12212, 12259, 12257, -1, 12212, 12213, 12259, -1, 12211, 12256, 12258, -1, 12211, 12257, 12256, -1, 12211, 12212, 12257, -1, 12214, 12258, 12260, -1, 12214, 12211, 12258, -1, 12216, 12260, 12262, -1, 12216, 12214, 12260, -1, 12217, 12216, 12262, -1, 11710, 11709, 12270, -1, 11710, 12270, 12206, -1, 11704, 12217, 12262, -1, 11705, 11704, 12262, -1, 12098, 12237, 12238, -1, 12096, 12238, 12239, -1, 12096, 12098, 12238, -1, 12094, 12239, 12240, -1, 12094, 12096, 12239, -1, 12092, 12240, 12244, -1, 12092, 12094, 12240, -1, 12093, 12244, 12242, -1, 12093, 12092, 12244, -1, 12095, 12242, 12243, -1, 12095, 12093, 12242, -1, 12097, 12243, 12647, -1, 12097, 12095, 12243, -1, 12091, 12647, 12648, -1, 12091, 12097, 12647, -1, 12107, 12648, 11606, -1, 12107, 12091, 12648, -1, 12103, 11606, 11602, -1, 12103, 12107, 11606, -1, 12101, 11602, 11600, -1, 12101, 12103, 11602, -1, 12099, 11600, 11605, -1, 12099, 12101, 11600, -1, 12104, 11605, 11609, -1, 12104, 12099, 11605, -1, 12108, 11609, 11611, -1, 12108, 12104, 11609, -1, 11706, 11707, 12237, -1, 11706, 12237, 12098, -1, 11688, 12108, 11611, -1, 11613, 11688, 11611, -1, 11687, 11612, 11610, -1, 11687, 11610, 12111, -1, 12088, 12080, 11578, -1, 11579, 12088, 11578, -1, 12111, 11610, 11608, -1, 12109, 11608, 11604, -1, 12109, 12111, 11608, -1, 12105, 11604, 11599, -1, 12105, 12109, 11604, -1, 12100, 11599, 11601, -1, 12100, 12105, 11599, -1, 12102, 11601, 11603, -1, 12102, 12100, 11601, -1, 12106, 11603, 11607, -1, 12106, 12102, 11603, -1, 12110, 11607, 12649, -1, 12110, 12106, 11607, -1, 12087, 12649, 12650, -1, 12087, 12110, 12649, -1, 12086, 12650, 11597, -1, 12086, 12087, 12650, -1, 12085, 11597, 11595, -1, 12085, 12086, 11597, -1, 12084, 11595, 11594, -1, 12084, 12085, 11595, -1, 12083, 11594, 11596, -1, 12083, 12084, 11594, -1, 12082, 11596, 11598, -1, 12082, 12083, 11596, -1, 12080, 11598, 11578, -1, 12080, 12082, 11598, -1, 12081, 12651, 12652, -1, 12081, 12653, 12651, -1, 12081, 11584, 12653, -1, 12081, 12652, 12654, -1, 12090, 11587, 11584, -1, 12090, 11584, 12081, -1, 9909, 9913, 12655, -1, 9907, 9909, 12655, -1, 12656, 12657, 12658, -1, 12656, 12658, 12659, -1, 12660, 12661, 12662, -1, 12660, 12662, 9902, -1, 12660, 9902, 9903, -1, 12660, 9903, 9905, -1, 12660, 9905, 9907, -1, 12660, 9907, 12655, -1, 12663, 12659, 12661, -1, 12663, 12661, 12660, -1, 12663, 12656, 12659, -1, 9243, 12664, 12665, -1, 9242, 12664, 9243, -1, 12666, 12667, 12668, -1, 12666, 12669, 12667, -1, 12666, 12668, 12670, -1, 12671, 12669, 12666, -1, 12672, 12671, 12666, -1, 12673, 12672, 12666, -1, 12674, 12672, 12673, -1, 10352, 10354, 12675, -1, 12675, 12676, 12677, -1, 10354, 12676, 12675, -1, 12677, 12678, 12679, -1, 12676, 12678, 12677, -1, 12679, 12680, 12665, -1, 12678, 12680, 12679, -1, 12680, 9243, 12665, -1, 12664, 9242, 12681, -1, 12682, 12681, 12683, -1, 12682, 12664, 12681, -1, 12684, 12683, 12685, -1, 12684, 12682, 12683, -1, 12686, 12684, 12685, -1, 12687, 12685, 12656, -1, 12687, 12686, 12685, -1, 12663, 12687, 12656, -1, 12672, 12674, 12688, -1, 12689, 12690, 12691, -1, 12689, 12688, 12690, -1, 12689, 12672, 12688, -1, 12692, 12691, 12693, -1, 12692, 12689, 12691, -1, 12655, 12693, 12660, -1, 12655, 12692, 12693, -1, 10407, 10410, 12694, -1, 12694, 12695, 12696, -1, 10410, 12695, 12694, -1, 12696, 12697, 12698, -1, 12695, 12697, 12696, -1, 12698, 12699, 12670, -1, 12697, 12699, 12698, -1, 12699, 12666, 12670, -1, 12700, 9927, 12701, -1, 12700, 9925, 9927, -1, 9797, 9739, 12702, -1, 9797, 12702, 12703, -1, 9946, 12704, 12705, -1, 9757, 9925, 12700, -1, 9944, 12705, 12706, -1, 9944, 9946, 12705, -1, 9948, 12707, 12704, -1, 9794, 9797, 12703, -1, 9948, 12704, 9946, -1, 9794, 12703, 12708, -1, 9942, 12706, 12709, -1, 9942, 9944, 12706, -1, 9756, 12710, 9925, -1, 9756, 12711, 12710, -1, 9756, 9925, 9757, -1, 9949, 9799, 12707, -1, 9789, 12708, 12712, -1, 9789, 9794, 12708, -1, 9949, 12707, 9948, -1, 9770, 12713, 12711, -1, 9940, 12709, 12714, -1, 9770, 12711, 9756, -1, 9940, 9942, 12709, -1, 9784, 12712, 12715, -1, 9784, 9789, 12712, -1, 9779, 12715, 12713, -1, 9779, 12713, 9770, -1, 9779, 9784, 12715, -1, 9951, 9799, 9949, -1, 9938, 12714, 12716, -1, 9938, 9940, 12714, -1, 12717, 9938, 12716, -1, 12718, 9774, 9799, -1, 12718, 9799, 9951, -1, 9771, 9774, 12718, -1, 9936, 9938, 12717, -1, 12719, 9771, 12718, -1, 12720, 9936, 12717, -1, 9934, 9936, 12720, -1, 12721, 9764, 9771, -1, 12721, 9771, 12719, -1, 12722, 9932, 9934, -1, 12722, 9934, 12720, -1, 9738, 9764, 12721, -1, 9738, 12721, 12723, -1, 12701, 9932, 12722, -1, 12701, 9930, 9932, -1, 9927, 9930, 12701, -1, 9739, 9738, 12723, -1, 9739, 12723, 12702, -1, 9952, 12290, 9951, -1, 12718, 12290, 12719, -1, 9951, 12290, 12718, -1, 12719, 12291, 12721, -1, 12290, 12291, 12719, -1, 12721, 12292, 12723, -1, 12291, 12292, 12721, -1, 12723, 12295, 12702, -1, 12292, 12295, 12723, -1, 12702, 12297, 12703, -1, 12295, 12297, 12702, -1, 12703, 12306, 12708, -1, 12297, 12306, 12703, -1, 12708, 12305, 12712, -1, 12306, 12305, 12708, -1, 12712, 12304, 12715, -1, 12305, 12304, 12712, -1, 12715, 12303, 12713, -1, 12304, 12303, 12715, -1, 12713, 12302, 12711, -1, 12303, 12302, 12713, -1, 12711, 12301, 12710, -1, 12302, 12301, 12711, -1, 12710, 12300, 9925, -1, 12301, 12300, 12710, -1, 12300, 9926, 9925, -1, 9893, 9920, 9924, -1, 9924, 9920, 9922, -1, 9893, 9895, 9920, -1, 9895, 9911, 9920, -1, 9898, 12724, 9895, -1, 9895, 12724, 9911, -1, 12725, 12726, 12727, -1, 12727, 12728, 12724, -1, 12724, 12728, 9911, -1, 12726, 12728, 12727, -1, 12728, 11662, 9911, -1, 9899, 12249, 9898, -1, 9898, 12249, 12724, -1, 12724, 12250, 12727, -1, 12249, 12250, 12724, -1, 12727, 12251, 12725, -1, 12250, 12251, 12727, -1, 12725, 12252, 12726, -1, 12251, 12252, 12725, -1, 9250, 11662, 9248, -1, 11662, 9247, 9248, -1, 11662, 9246, 9247, -1, 11662, 12729, 9246, -1, 12726, 12253, 12728, -1, 12252, 12253, 12726, -1, 12728, 12254, 11662, -1, 12253, 12254, 12728, -1, 12729, 12255, 12730, -1, 12730, 12255, 12731, -1, 12731, 12255, 12732, -1, 11662, 12255, 12729, -1, 12254, 12255, 11662, -1, 12732, 12269, 12733, -1, 12733, 12269, 12657, -1, 12657, 12269, 12658, -1, 12255, 12269, 12732, -1, 12658, 12268, 12659, -1, 12269, 12268, 12658, -1, 12659, 12265, 12661, -1, 12268, 12265, 12659, -1, 12661, 12264, 12662, -1, 12265, 12264, 12661, -1, 12264, 12263, 12662, -1, 12662, 12263, 9902, -1, 12263, 9900, 9902, -1, 12734, 12735, 12736, -1, 12737, 9804, 9835, -1, 12737, 9829, 9804, -1, 12737, 12736, 9829, -1, 12737, 12734, 12736, -1, 12737, 9835, 12734, -1, 12738, 12739, 9748, -1, 12738, 12740, 12739, -1, 12738, 12741, 12740, -1, 12742, 9748, 9826, -1, 12742, 9807, 9809, -1, 12742, 9826, 9807, -1, 12742, 12738, 9748, -1, 12742, 12741, 12738, -1, 12742, 9809, 12741, -1, 12736, 12735, 12743, -1, 12736, 9827, 9829, -1, 12744, 12745, 12746, -1, 12744, 12743, 12745, -1, 12744, 9833, 9827, -1, 12744, 9840, 9833, -1, 12744, 9827, 12736, -1, 12744, 12736, 12743, -1, 12747, 12746, 12748, -1, 12747, 9844, 9840, -1, 12747, 12744, 12746, -1, 12747, 9840, 12744, -1, 12749, 12750, 12751, -1, 12749, 12748, 12750, -1, 12749, 9850, 9844, -1, 12749, 9854, 9850, -1, 12749, 12747, 12748, -1, 12749, 9844, 12747, -1, 12752, 12753, 12754, -1, 12752, 12751, 12753, -1, 12752, 9859, 9854, -1, 12752, 9866, 9859, -1, 12752, 9854, 12749, -1, 12752, 12749, 12751, -1, 12741, 12754, 12740, -1, 12741, 9809, 9866, -1, 12741, 9866, 12752, -1, 12741, 12752, 12754, -1, 12734, 9835, 9751, -1, 12734, 12755, 12735, -1, 12734, 9751, 12755, -1, 12756, 12757, 12758, -1, 10289, 12759, 10296, -1, 9882, 12760, 9872, -1, 12761, 12759, 10289, -1, 9811, 12760, 9806, -1, 12757, 12760, 9811, -1, 9879, 12762, 9878, -1, 12763, 12760, 12764, -1, 12765, 12762, 12766, -1, 12764, 12760, 12757, -1, 9872, 12760, 12763, -1, 9806, 12760, 9882, -1, 12767, 12762, 12765, -1, 9878, 12762, 12767, -1, 9815, 10184, 9863, -1, 12766, 12768, 12761, -1, 12761, 12768, 12759, -1, 10296, 12769, 10304, -1, 12759, 12769, 10296, -1, 9883, 12770, 9879, -1, 12762, 12770, 12766, -1, 9879, 12770, 12762, -1, 12766, 12770, 12768, -1, 12759, 12771, 12769, -1, 12768, 12771, 12759, -1, 10304, 12772, 10273, -1, 12769, 12772, 10304, -1, 9885, 12773, 9883, -1, 9883, 12773, 12770, -1, 12768, 12773, 12771, -1, 12770, 12773, 12768, -1, 12769, 12774, 12772, -1, 12771, 12774, 12769, -1, 10273, 12775, 10266, -1, 12772, 12775, 10273, -1, 9886, 12776, 9885, -1, 12771, 12776, 12774, -1, 9885, 12776, 12773, -1, 12773, 12776, 12771, -1, 12772, 12777, 12775, -1, 12774, 12777, 12772, -1, 12775, 12778, 10266, -1, 10266, 12778, 10265, -1, 9888, 12779, 9886, -1, 12774, 12779, 12777, -1, 9886, 12779, 12776, -1, 12776, 12779, 12774, -1, 12775, 12780, 12778, -1, 12777, 12780, 12775, -1, 12778, 12781, 10265, -1, 10265, 12781, 10238, -1, 9889, 12782, 9888, -1, 9888, 12782, 12779, -1, 12779, 12782, 12777, -1, 12777, 12782, 12780, -1, 12780, 12783, 12778, -1, 12778, 12783, 12781, -1, 10238, 12784, 10237, -1, 12781, 12784, 10238, -1, 9891, 12785, 9889, -1, 9889, 12785, 12782, -1, 12782, 12785, 12780, -1, 12780, 12785, 12783, -1, 12783, 12786, 12781, -1, 12781, 12786, 12784, -1, 10237, 12787, 10236, -1, 12784, 12787, 10237, -1, 9892, 12788, 9891, -1, 12785, 12788, 12783, -1, 9891, 12788, 12785, -1, 12783, 12788, 12786, -1, 12786, 12789, 12784, -1, 12784, 12789, 12787, -1, 10236, 12756, 10202, -1, 12787, 12756, 10236, -1, 9882, 9835, 9806, -1, 9873, 12790, 9892, -1, 9892, 12790, 12788, -1, 10184, 12791, 10290, -1, 12786, 12790, 12789, -1, 9815, 12791, 10184, -1, 12788, 12790, 12786, -1, 9817, 12765, 9815, -1, 12789, 12764, 12787, -1, 9815, 12765, 12791, -1, 12787, 12764, 12756, -1, 10290, 12761, 10289, -1, 10202, 12758, 9869, -1, 9869, 12758, 9868, -1, 12791, 12761, 10290, -1, 12756, 12758, 10202, -1, 9878, 12767, 9826, -1, 9825, 12767, 9817, -1, 9872, 12763, 9873, -1, 9826, 12767, 9825, -1, 12789, 12763, 12764, -1, 12790, 12763, 12789, -1, 9817, 12767, 12765, -1, 9873, 12763, 12790, -1, 12765, 12766, 12791, -1, 9868, 12757, 9811, -1, 12791, 12766, 12761, -1, 12764, 12757, 12756, -1, 12758, 12757, 9868, -1, 12792, 12793, 12794, -1, 12792, 12794, 12795, -1, 12796, 9766, 9749, -1, 12797, 12722, 12720, -1, 12797, 12798, 12793, -1, 12796, 9749, 12799, -1, 12797, 12720, 12800, -1, 12797, 12800, 12798, -1, 12801, 12735, 12755, -1, 12802, 12740, 12754, -1, 12801, 12803, 12735, -1, 12801, 12755, 9750, -1, 12802, 12804, 12740, -1, 12805, 12795, 12803, -1, 12805, 12792, 12795, -1, 12806, 12799, 12804, -1, 12807, 12701, 12722, -1, 12806, 12796, 12799, -1, 12807, 12793, 12792, -1, 12807, 12722, 12797, -1, 12808, 9773, 9766, -1, 12808, 12704, 12707, -1, 12807, 12797, 12793, -1, 12808, 12707, 9773, -1, 12809, 9750, 9759, -1, 12808, 9766, 12796, -1, 12810, 12754, 12753, -1, 12809, 12803, 12801, -1, 12809, 12805, 12803, -1, 12809, 12801, 9750, -1, 12811, 12700, 12701, -1, 12811, 12701, 12807, -1, 12811, 12792, 12805, -1, 12810, 12802, 12754, -1, 12812, 12804, 12802, -1, 12811, 12807, 12792, -1, 12813, 9759, 9758, -1, 12812, 12806, 12804, -1, 12813, 9758, 9757, -1, 12813, 9757, 12700, -1, 12707, 9799, 9773, -1, 12813, 12700, 12811, -1, 12813, 12809, 9759, -1, 12814, 12705, 12704, -1, 12813, 12805, 12809, -1, 12814, 12808, 12796, -1, 12813, 12811, 12805, -1, 12814, 12704, 12808, -1, 12814, 12796, 12806, -1, 12815, 12753, 12751, -1, 12815, 12810, 12753, -1, 12816, 12802, 12810, -1, 12816, 12812, 12802, -1, 12817, 12705, 12814, -1, 12817, 12706, 12705, -1, 12817, 12806, 12812, -1, 12817, 12814, 12806, -1, 12818, 12751, 12750, -1, 12818, 12815, 12751, -1, 12819, 12810, 12815, -1, 12819, 12816, 12810, -1, 12820, 12709, 12706, -1, 12820, 12817, 12812, -1, 12820, 12812, 12816, -1, 12820, 12706, 12817, -1, 12821, 12818, 12750, -1, 12821, 12750, 12748, -1, 12822, 12819, 12815, -1, 12822, 12815, 12818, -1, 12823, 12816, 12819, -1, 12823, 12714, 12709, -1, 12823, 12709, 12820, -1, 12823, 12820, 12816, -1, 12824, 12748, 12746, -1, 12824, 12821, 12748, -1, 12825, 12822, 12818, -1, 12825, 12818, 12821, -1, 12826, 12819, 12822, -1, 12826, 12714, 12823, -1, 12826, 12716, 12714, -1, 12826, 12823, 12819, -1, 12794, 12824, 12746, -1, 12794, 12746, 12745, -1, 9750, 12755, 9751, -1, 12798, 12825, 12821, -1, 12798, 12821, 12824, -1, 12827, 12717, 12716, -1, 12827, 12716, 12826, -1, 12827, 12826, 12822, -1, 12827, 12822, 12825, -1, 12795, 12745, 12743, -1, 12795, 12794, 12745, -1, 12793, 12824, 12794, -1, 12793, 12798, 12824, -1, 12800, 12825, 12798, -1, 12800, 12717, 12827, -1, 12800, 12720, 12717, -1, 12800, 12827, 12825, -1, 12799, 9749, 9748, -1, 12799, 9748, 12739, -1, 12803, 12743, 12735, -1, 12803, 12795, 12743, -1, 12804, 12739, 12740, -1, 12804, 12799, 12739, -1, 11630, 9979, 11632, -1, 12828, 11650, 11648, -1, 12829, 10002, 12830, -1, 12828, 12831, 11650, -1, 12829, 10004, 10002, -1, 12832, 11648, 11646, -1, 12832, 12828, 11648, -1, 9960, 12833, 12834, -1, 12835, 11640, 11638, -1, 12835, 11642, 11640, -1, 12835, 11644, 11642, -1, 12835, 11646, 11644, -1, 12835, 12832, 11646, -1, 9962, 12834, 12836, -1, 9962, 9960, 12834, -1, 9958, 12837, 12833, -1, 9958, 12833, 9960, -1, 9964, 9962, 12836, -1, 9956, 12838, 12837, -1, 12839, 10004, 12829, -1, 9956, 12837, 9958, -1, 12839, 10006, 10004, -1, 9966, 9964, 12836, -1, 9990, 9988, 12840, -1, 9954, 12838, 9956, -1, 9954, 12841, 12838, -1, 9986, 12840, 9988, -1, 9968, 9966, 12836, -1, 11660, 12842, 12841, -1, 9992, 12840, 12843, -1, 9992, 9990, 12840, -1, 11660, 12841, 9954, -1, 9984, 9972, 12836, -1, 9984, 12836, 12840, -1, 9267, 10006, 12839, -1, 9267, 10008, 10006, -1, 9984, 12840, 9986, -1, 9269, 10008, 9267, -1, 9970, 9968, 12836, -1, 9269, 11615, 10008, -1, 9994, 12843, 12844, -1, 11658, 12845, 12842, -1, 11658, 12842, 11660, -1, 9278, 11638, 11630, -1, 9994, 9992, 12843, -1, 9278, 12835, 11638, -1, 9972, 9970, 12836, -1, 9278, 11622, 11620, -1, 9278, 11624, 11622, -1, 9278, 11626, 11624, -1, 9278, 11628, 11626, -1, 9982, 9972, 9984, -1, 9278, 11630, 11628, -1, 9982, 9974, 9972, -1, 11656, 12845, 11658, -1, 9272, 11616, 11615, -1, 9272, 11615, 9269, -1, 12846, 12845, 11656, -1, 9996, 12844, 12847, -1, 9276, 11620, 11618, -1, 9996, 9994, 12844, -1, 9276, 9278, 11620, -1, 9274, 9276, 11618, -1, 9274, 11616, 9272, -1, 11636, 9974, 9982, -1, 11654, 12846, 11656, -1, 9274, 11618, 11616, -1, 11636, 9976, 9974, -1, 12848, 12846, 11654, -1, 9998, 9996, 12847, -1, 11652, 12848, 11654, -1, 12849, 9998, 12847, -1, 11634, 9976, 11636, -1, 11634, 9978, 9976, -1, 10000, 9998, 12849, -1, 11632, 9979, 9978, -1, 11632, 9978, 11634, -1, 12831, 11652, 11650, -1, 12831, 12848, 11652, -1, 12830, 10002, 10000, -1, 12830, 10000, 12849, -1, 11630, 11638, 9979, -1, 12850, 9634, 12851, -1, 12850, 9633, 9634, -1, 9627, 9566, 12852, -1, 9627, 12852, 12853, -1, 9652, 12854, 12855, -1, 9584, 9633, 12850, -1, 9650, 12855, 12856, -1, 9650, 9652, 12855, -1, 9623, 9627, 12853, -1, 9654, 12857, 12854, -1, 9623, 12853, 12858, -1, 9654, 12854, 9652, -1, 9583, 12859, 9633, -1, 9583, 12860, 12859, -1, 9583, 9633, 9584, -1, 9648, 12856, 12861, -1, 9648, 9650, 12856, -1, 9618, 12858, 12862, -1, 9618, 9623, 12858, -1, 9600, 12860, 9583, -1, 9600, 12863, 12860, -1, 9656, 9629, 12857, -1, 9656, 12857, 9654, -1, 9613, 9618, 12862, -1, 9646, 12861, 12864, -1, 9608, 12862, 12863, -1, 9608, 12863, 9600, -1, 9646, 9648, 12861, -1, 9608, 9613, 12862, -1, 9658, 9629, 9656, -1, 9644, 12864, 12865, -1, 9644, 9646, 12864, -1, 12866, 9603, 9629, -1, 12866, 9629, 9658, -1, 9642, 12865, 12867, -1, 9642, 9644, 12865, -1, 12868, 9598, 9603, -1, 12868, 9603, 12866, -1, 9640, 12867, 12869, -1, 9640, 9642, 12867, -1, 12870, 9593, 9598, -1, 12870, 9598, 12868, -1, 9638, 9640, 12869, -1, 12871, 9638, 12869, -1, 12872, 9593, 12870, -1, 9565, 9593, 12872, -1, 9636, 9638, 12871, -1, 12873, 9565, 12872, -1, 12851, 9636, 12871, -1, 9634, 9636, 12851, -1, 9566, 9565, 12873, -1, 12852, 9566, 12873, -1, 9662, 9664, 12874, -1, 9426, 9425, 12875, -1, 9426, 12875, 12876, -1, 12877, 9662, 12874, -1, 12877, 9661, 9662, -1, 9680, 12878, 12879, -1, 9678, 12879, 12880, -1, 9678, 9680, 12879, -1, 9487, 9426, 12876, -1, 9682, 12881, 12878, -1, 9487, 12876, 12882, -1, 9682, 12878, 9680, -1, 9676, 12880, 12883, -1, 9676, 9678, 12880, -1, 9683, 12884, 12881, -1, 9683, 9489, 12884, -1, 9683, 12881, 9682, -1, 9674, 12883, 12885, -1, 9674, 9676, 12883, -1, 9444, 9661, 12877, -1, 9483, 9487, 12882, -1, 9685, 9489, 9683, -1, 9483, 12882, 12886, -1, 9672, 9674, 12885, -1, 9443, 9661, 9444, -1, 9443, 12887, 9661, -1, 12888, 9672, 12885, -1, 9443, 12889, 12887, -1, 12890, 9463, 9489, -1, 12890, 9489, 9685, -1, 9478, 12886, 12891, -1, 9478, 9483, 12886, -1, 9458, 9463, 12890, -1, 9460, 12892, 12889, -1, 9670, 9672, 12888, -1, 9460, 12889, 9443, -1, 9473, 12891, 12893, -1, 9473, 9478, 12891, -1, 9468, 9473, 12893, -1, 12894, 9458, 12890, -1, 9468, 12892, 9460, -1, 9468, 12893, 12892, -1, 9668, 12888, 12895, -1, 9668, 9670, 12888, -1, 9453, 9458, 12894, -1, 12896, 9453, 12894, -1, 9666, 9668, 12895, -1, 12897, 9666, 12895, -1, 9425, 9453, 12896, -1, 9425, 12896, 12875, -1, 9664, 9666, 12897, -1, 12874, 9664, 12897, -1, 12898, 9576, 12899, -1, 12898, 12900, 12901, -1, 12902, 9523, 9576, -1, 12902, 9491, 9523, -1, 12902, 9517, 9491, -1, 12902, 12901, 9517, -1, 12902, 12898, 12901, -1, 12902, 9576, 12898, -1, 12903, 12904, 9573, -1, 12903, 12905, 12904, -1, 12903, 9573, 9556, -1, 12903, 12906, 12905, -1, 12907, 9507, 9557, -1, 12907, 9556, 9507, -1, 12907, 9557, 12906, -1, 12907, 12906, 12903, -1, 12907, 12903, 9556, -1, 12901, 12900, 12908, -1, 12901, 9515, 9517, -1, 12909, 12910, 12911, -1, 12909, 12908, 12910, -1, 12909, 9521, 9515, -1, 12909, 9528, 9521, -1, 12909, 9515, 12901, -1, 12909, 12901, 12908, -1, 12912, 12911, 12913, -1, 12912, 9532, 9528, -1, 12912, 12909, 12911, -1, 12912, 9528, 12909, -1, 12914, 12915, 12916, -1, 12914, 12913, 12915, -1, 12914, 9538, 9532, -1, 12914, 9542, 9538, -1, 12914, 12912, 12913, -1, 12914, 9532, 12912, -1, 12917, 12918, 12919, -1, 12917, 12916, 12918, -1, 12917, 9547, 9542, -1, 12917, 9552, 9547, -1, 12917, 9542, 12914, -1, 12917, 12914, 12916, -1, 12906, 12919, 12905, -1, 12906, 9557, 9552, -1, 12906, 9552, 12917, -1, 12906, 12917, 12919, -1, 12898, 12899, 12900, -1, 12920, 12921, 12922, -1, 12923, 9379, 9385, -1, 12923, 9377, 9379, -1, 12923, 12922, 9377, -1, 12923, 12920, 12922, -1, 12923, 9385, 12920, -1, 12924, 12925, 9433, -1, 12924, 12926, 12925, -1, 12924, 12927, 12926, -1, 12928, 9433, 9418, -1, 12928, 9375, 9376, -1, 12928, 9418, 9375, -1, 12928, 12927, 12924, -1, 12928, 12924, 9433, -1, 12928, 9376, 12927, -1, 12922, 12921, 12929, -1, 12922, 9384, 9377, -1, 12930, 12931, 12932, -1, 12930, 12929, 12931, -1, 12930, 9390, 9384, -1, 12930, 9395, 9390, -1, 12930, 9384, 12922, -1, 12930, 12922, 12929, -1, 12933, 12932, 12934, -1, 12933, 9400, 9395, -1, 12933, 12930, 12932, -1, 12933, 9395, 12930, -1, 12935, 12936, 12937, -1, 12935, 12934, 12936, -1, 12935, 9405, 9400, -1, 12935, 9410, 9405, -1, 12935, 12933, 12934, -1, 12935, 9400, 12933, -1, 12938, 12939, 12940, -1, 12938, 12937, 12939, -1, 12938, 9415, 9410, -1, 12938, 9351, 9415, -1, 12938, 9410, 12935, -1, 12938, 12935, 12937, -1, 12927, 12940, 12926, -1, 12927, 9376, 9351, -1, 12927, 9351, 12938, -1, 12927, 12938, 12940, -1, 12920, 9385, 9436, -1, 12920, 12941, 12921, -1, 12920, 9436, 12941, -1, 9685, 9686, 12890, -1, 12890, 12241, 12894, -1, 9686, 12241, 12890, -1, 12894, 12245, 12896, -1, 12241, 12245, 12894, -1, 12896, 12246, 12875, -1, 12245, 12246, 12896, -1, 12875, 12247, 12876, -1, 12246, 12247, 12875, -1, 12876, 12236, 12882, -1, 12247, 12236, 12876, -1, 12882, 12235, 12886, -1, 12236, 12235, 12882, -1, 12886, 12234, 12891, -1, 12235, 12234, 12886, -1, 12891, 12233, 12893, -1, 12234, 12233, 12891, -1, 12893, 12232, 12892, -1, 12233, 12232, 12893, -1, 12892, 12231, 12889, -1, 12232, 12231, 12892, -1, 12889, 12230, 12887, -1, 12231, 12230, 12889, -1, 12887, 12229, 9661, -1, 12230, 12229, 12887, -1, 12229, 9659, 9661, -1, 9658, 9657, 12866, -1, 12866, 11589, 12868, -1, 9657, 11589, 12866, -1, 12868, 11590, 12870, -1, 11589, 11590, 12868, -1, 12870, 11591, 12872, -1, 11590, 11591, 12870, -1, 12872, 11592, 12873, -1, 11591, 11592, 12872, -1, 12873, 11593, 12852, -1, 11592, 11593, 12873, -1, 12852, 11588, 12853, -1, 11593, 11588, 12852, -1, 12853, 11586, 12858, -1, 11588, 11586, 12853, -1, 12858, 11585, 12862, -1, 11586, 11585, 12858, -1, 12862, 11583, 12863, -1, 11585, 11583, 12862, -1, 12863, 11582, 12860, -1, 11583, 11582, 12863, -1, 11582, 11581, 12860, -1, 12860, 11580, 12859, -1, 11581, 11580, 12860, -1, 12859, 9631, 9633, -1, 11580, 9631, 12859, -1, 12942, 12943, 12944, -1, 12945, 9595, 9574, -1, 12946, 12871, 12869, -1, 12946, 12947, 12948, -1, 12946, 12869, 12949, -1, 12945, 9574, 12950, -1, 12946, 12949, 12947, -1, 12951, 12900, 12899, -1, 12952, 12905, 12919, -1, 12951, 12953, 12900, -1, 12951, 12899, 9575, -1, 12952, 12954, 12905, -1, 12955, 12944, 12953, -1, 12955, 12942, 12944, -1, 12956, 12851, 12871, -1, 12957, 12950, 12954, -1, 12956, 12871, 12946, -1, 12957, 12945, 12950, -1, 12956, 12946, 12948, -1, 12958, 9602, 9595, -1, 12958, 12854, 12857, -1, 12956, 12948, 12942, -1, 12959, 9575, 9586, -1, 12958, 12857, 9602, -1, 12958, 9595, 12945, -1, 12960, 12919, 12918, -1, 12959, 12953, 12951, -1, 12959, 12955, 12953, -1, 12959, 12951, 9575, -1, 12961, 12850, 12851, -1, 12961, 12942, 12955, -1, 12961, 12956, 12942, -1, 12960, 12952, 12919, -1, 12962, 12954, 12952, -1, 12961, 12851, 12956, -1, 12963, 9585, 12850, -1, 12963, 9586, 9585, -1, 12962, 12957, 12954, -1, 12963, 12850, 12961, -1, 12963, 12959, 9586, -1, 12857, 9629, 9602, -1, 12963, 12955, 12959, -1, 12963, 12961, 12955, -1, 12964, 12855, 12854, -1, 12964, 12958, 12945, -1, 12964, 12854, 12958, -1, 12964, 12945, 12957, -1, 12965, 12918, 12916, -1, 12965, 12960, 12918, -1, 12966, 12952, 12960, -1, 12966, 12962, 12952, -1, 12967, 12855, 12964, -1, 12967, 12856, 12855, -1, 12967, 12957, 12962, -1, 12967, 12964, 12957, -1, 12968, 12916, 12915, -1, 12968, 12965, 12916, -1, 12969, 12960, 12965, -1, 12969, 12966, 12960, -1, 12970, 12861, 12856, -1, 12970, 12967, 12962, -1, 12970, 12962, 12966, -1, 12970, 12856, 12967, -1, 12971, 12968, 12915, -1, 12971, 12915, 12913, -1, 12972, 12969, 12965, -1, 12972, 12965, 12968, -1, 12973, 12966, 12969, -1, 12973, 12864, 12861, -1, 12973, 12861, 12970, -1, 12973, 12970, 12966, -1, 12974, 12913, 12911, -1, 12974, 12971, 12913, -1, 12975, 12972, 12968, -1, 12975, 12968, 12971, -1, 12976, 12969, 12972, -1, 12976, 12864, 12973, -1, 12976, 12865, 12864, -1, 12976, 12973, 12969, -1, 12943, 12974, 12911, -1, 12943, 12911, 12910, -1, 9575, 12899, 9576, -1, 12947, 12975, 12971, -1, 12947, 12971, 12974, -1, 12977, 12867, 12865, -1, 12977, 12865, 12976, -1, 12977, 12976, 12972, -1, 12977, 12972, 12975, -1, 12944, 12910, 12908, -1, 12944, 12943, 12910, -1, 12948, 12974, 12943, -1, 12948, 12947, 12974, -1, 12949, 12975, 12947, -1, 9584, 12850, 9585, -1, 12949, 12867, 12977, -1, 12949, 12869, 12867, -1, 12949, 12977, 12975, -1, 12950, 9574, 9573, -1, 12953, 12908, 12900, -1, 12950, 9573, 12904, -1, 12953, 12944, 12908, -1, 12954, 12904, 12905, -1, 12942, 12948, 12943, -1, 12954, 12950, 12904, -1, 9720, 12978, 9710, -1, 10446, 12979, 10445, -1, 9494, 12978, 9493, -1, 12980, 12978, 9494, -1, 12981, 12978, 12982, -1, 12983, 12979, 10446, -1, 12982, 12978, 12980, -1, 9717, 12984, 9716, -1, 9710, 12978, 12981, -1, 9493, 12978, 9720, -1, 12985, 12984, 12986, -1, 9716, 12984, 12985, -1, 12986, 12984, 12987, -1, 12987, 12988, 12983, -1, 12983, 12988, 12979, -1, 10445, 12989, 10444, -1, 12979, 12989, 10445, -1, 9721, 12990, 9717, -1, 12987, 12990, 12988, -1, 9717, 12990, 12984, -1, 12984, 12990, 12987, -1, 12988, 12991, 12979, -1, 12979, 12991, 12989, -1, 10444, 12992, 10443, -1, 12989, 12992, 10444, -1, 9721, 12993, 12990, -1, 9723, 12993, 9721, -1, 12988, 12993, 12991, -1, 12990, 12993, 12988, -1, 12989, 12994, 12992, -1, 12991, 12994, 12989, -1, 10443, 12995, 10424, -1, 12992, 12995, 10443, -1, 9724, 12996, 9723, -1, 12993, 12996, 12991, -1, 12991, 12996, 12994, -1, 9723, 12996, 12993, -1, 12994, 12997, 12992, -1, 12992, 12997, 12995, -1, 12995, 12998, 10424, -1, 10424, 12998, 10425, -1, 9726, 12999, 9724, -1, 9724, 12999, 12996, -1, 12996, 12999, 12994, -1, 12994, 12999, 12997, -1, 12997, 13000, 12995, -1, 12995, 13000, 12998, -1, 12998, 13001, 10425, -1, 10425, 13001, 10426, -1, 9727, 13002, 9726, -1, 12999, 13002, 12997, -1, 12997, 13002, 13000, -1, 9726, 13002, 12999, -1, 13000, 13003, 12998, -1, 12998, 13003, 13001, -1, 10426, 13004, 10433, -1, 13001, 13004, 10426, -1, 9729, 13005, 9727, -1, 13000, 13005, 13003, -1, 13002, 13005, 13000, -1, 9727, 13005, 13002, -1, 13003, 13006, 13001, -1, 13001, 13006, 13004, -1, 10433, 13007, 10431, -1, 13004, 13007, 10433, -1, 9730, 13008, 9729, -1, 13003, 13008, 13006, -1, 13005, 13008, 13003, -1, 9729, 13008, 13005, -1, 13006, 13009, 13004, -1, 13004, 13009, 13007, -1, 10431, 13010, 10428, -1, 13007, 13010, 10431, -1, 9711, 13011, 9730, -1, 13006, 13011, 13009, -1, 9720, 9523, 9493, -1, 13008, 13011, 13006, -1, 9496, 13012, 9559, -1, 9730, 13011, 13008, -1, 10442, 13012, 10447, -1, 9559, 13012, 10442, -1, 13009, 12982, 13007, -1, 9498, 12986, 9496, -1, 13007, 12982, 13010, -1, 10428, 13013, 9510, -1, 9496, 12986, 13012, -1, 9510, 13013, 9508, -1, 10447, 12983, 10446, -1, 13010, 13013, 10428, -1, 13012, 12983, 10447, -1, 9710, 12981, 9711, -1, 9716, 12985, 9556, -1, 13009, 12981, 12982, -1, 9505, 12985, 9498, -1, 13011, 12981, 13009, -1, 9556, 12985, 9505, -1, 9498, 12985, 12986, -1, 9711, 12981, 13011, -1, 13013, 12980, 9508, -1, 9508, 12980, 9494, -1, 12986, 12987, 13012, -1, 12982, 12980, 13010, -1, 13012, 12987, 12983, -1, 13010, 12980, 13013, -1, 13014, 13015, 13016, -1, 13017, 13018, 12925, -1, 13019, 9455, 9434, -1, 13020, 12897, 12895, -1, 13020, 13021, 13022, -1, 13020, 13022, 13023, -1, 13019, 9434, 13018, -1, 13020, 12895, 13021, -1, 13024, 12921, 12941, -1, 9434, 9433, 12925, -1, 13025, 12926, 12940, -1, 13024, 13026, 12921, -1, 13024, 12941, 9435, -1, 13025, 13017, 12926, -1, 13027, 13016, 13026, -1, 13027, 13014, 13016, -1, 13028, 13018, 13017, -1, 13029, 12874, 12897, -1, 13028, 13019, 13018, -1, 13029, 12897, 13020, -1, 13030, 9462, 9455, -1, 13029, 13020, 13023, -1, 13030, 12881, 12884, -1, 13029, 13023, 13014, -1, 13030, 9455, 13019, -1, 13031, 9435, 9446, -1, 13030, 12884, 9462, -1, 13031, 13024, 9435, -1, 13032, 12940, 12939, -1, 13031, 13026, 13024, -1, 13031, 13027, 13026, -1, 13033, 13014, 13027, -1, 13033, 12877, 12874, -1, 13033, 13029, 13014, -1, 13032, 13025, 12940, -1, 13033, 12874, 13029, -1, 13034, 13017, 13025, -1, 13035, 9445, 12877, -1, 13035, 9446, 9445, -1, 13034, 13028, 13017, -1, 13035, 12877, 13033, -1, 13035, 13033, 13027, -1, 13035, 13031, 9446, -1, 12884, 9489, 9462, -1, 13035, 13027, 13031, -1, 13036, 12878, 12881, -1, 13036, 13030, 13019, -1, 13036, 13019, 13028, -1, 13036, 12881, 13030, -1, 13037, 12939, 12937, -1, 13037, 13032, 12939, -1, 13038, 13025, 13032, -1, 13038, 13034, 13025, -1, 13039, 12879, 12878, -1, 13039, 13028, 13034, -1, 13039, 12878, 13036, -1, 13039, 13036, 13028, -1, 13040, 13037, 12937, -1, 13040, 12937, 12936, -1, 13041, 13038, 13032, -1, 13041, 13032, 13037, -1, 13042, 12880, 12879, -1, 13042, 13039, 13034, -1, 13042, 12879, 13039, -1, 13042, 13034, 13038, -1, 13043, 12936, 12934, -1, 13043, 13040, 12936, -1, 13044, 13041, 13037, -1, 13044, 13037, 13040, -1, 13045, 13042, 13038, -1, 13045, 12883, 12880, -1, 13045, 13038, 13041, -1, 13045, 12880, 13042, -1, 13046, 12934, 12932, -1, 13046, 13043, 12934, -1, 13047, 13044, 13040, -1, 13047, 13040, 13043, -1, 13048, 13041, 13044, -1, 13048, 12883, 13045, -1, 13048, 12885, 12883, -1, 13048, 13045, 13041, -1, 13015, 12932, 12931, -1, 13015, 13046, 12932, -1, 13022, 13043, 13046, -1, 13022, 13047, 13043, -1, 9435, 12941, 9436, -1, 13049, 12885, 13048, -1, 13049, 13048, 13044, -1, 13049, 12888, 12885, -1, 13049, 13044, 13047, -1, 13016, 12931, 12929, -1, 13016, 13015, 12931, -1, 13023, 13022, 13046, -1, 13023, 13046, 13015, -1, 13021, 13047, 13022, -1, 13021, 13049, 13047, -1, 9444, 12877, 9445, -1, 13021, 12895, 12888, -1, 13021, 12888, 13049, -1, 13026, 12929, 12921, -1, 13018, 9434, 12925, -1, 13026, 13016, 12929, -1, 13017, 12925, 12926, -1, 13014, 13023, 13015, -1, 9688, 13050, 9689, -1, 9374, 13051, 9361, -1, 9418, 13051, 9374, -1, 13052, 13050, 13053, -1, 9361, 13051, 13054, -1, 13055, 13050, 13052, -1, 9689, 13050, 13055, -1, 13054, 13056, 13057, -1, 9370, 13058, 9354, -1, 13057, 13056, 13059, -1, 13053, 13058, 13060, -1, 13061, 13058, 9370, -1, 13060, 13058, 13061, -1, 10429, 13062, 10430, -1, 13058, 13063, 9354, -1, 9386, 13063, 9698, -1, 9698, 13063, 9688, -1, 13059, 13062, 10429, -1, 9354, 13063, 9386, -1, 13050, 13063, 13053, -1, 9695, 13064, 9694, -1, 13053, 13063, 13058, -1, 9688, 13063, 13050, -1, 13054, 13064, 13056, -1, 13051, 13064, 13054, -1, 9694, 13064, 13051, -1, 13056, 13065, 13059, -1, 13059, 13065, 13062, -1, 10430, 13066, 10432, -1, 13062, 13066, 10430, -1, 9699, 13067, 9695, -1, 9695, 13067, 13064, -1, 13064, 13067, 13056, -1, 13056, 13067, 13065, -1, 13065, 13068, 13062, -1, 13062, 13068, 13066, -1, 10432, 13069, 10441, -1, 13066, 13069, 10432, -1, 9701, 13070, 9699, -1, 9699, 13070, 13067, -1, 13067, 13070, 13065, -1, 13065, 13070, 13068, -1, 13068, 13071, 13066, -1, 13066, 13071, 13069, -1, 10441, 13072, 10440, -1, 13069, 13072, 10441, -1, 9702, 13073, 9701, -1, 9701, 13073, 13070, -1, 13068, 13073, 13071, -1, 13070, 13073, 13068, -1, 13069, 13074, 13072, -1, 13071, 13074, 13069, -1, 10440, 13075, 10439, -1, 13072, 13075, 10440, -1, 9702, 13076, 13073, -1, 9704, 13076, 9702, -1, 13073, 13076, 13071, -1, 13071, 13076, 13074, -1, 13074, 13077, 13072, -1, 13072, 13077, 13075, -1, 13075, 13078, 10439, -1, 10439, 13078, 10438, -1, 9705, 13079, 9704, -1, 13076, 13079, 13074, -1, 9704, 13079, 13076, -1, 13074, 13079, 13077, -1, 13077, 13080, 13075, -1, 13075, 13080, 13078, -1, 10438, 13081, 10437, -1, 13078, 13081, 10438, -1, 9707, 13082, 9705, -1, 13077, 13082, 13080, -1, 9705, 13082, 13079, -1, 13079, 13082, 13077, -1, 13080, 13083, 13078, -1, 10434, 9370, 9372, -1, 13078, 13083, 13081, -1, 10437, 13084, 10436, -1, 13081, 13084, 10437, -1, 9708, 13085, 9707, -1, 9707, 13085, 13082, -1, 13080, 13085, 13083, -1, 13082, 13085, 13080, -1, 13083, 13052, 13081, -1, 13081, 13052, 13084, -1, 10436, 13060, 10435, -1, 9698, 9385, 9386, -1, 13084, 13060, 10436, -1, 9359, 13057, 9419, -1, 9689, 13055, 9708, -1, 9708, 13055, 13085, -1, 9419, 13057, 10427, -1, 13083, 13055, 13052, -1, 13085, 13055, 13083, -1, 9361, 13054, 9359, -1, 13052, 13053, 13084, -1, 13084, 13053, 13060, -1, 9359, 13054, 13057, -1, 10427, 13059, 10429, -1, 10435, 13061, 10434, -1, 13057, 13059, 10427, -1, 10434, 13061, 9370, -1, 9694, 13051, 9418, -1, 13060, 13061, 10435, -1, 13086, 9346, 13087, -1, 13086, 9348, 9346, -1, 13088, 13089, 13090, -1, 13088, 13091, 13089, -1, 13088, 13092, 13091, -1, 13088, 13093, 13092, -1, 13088, 13094, 13093, -1, 9294, 13088, 13090, -1, 9294, 13095, 13096, -1, 9330, 13097, 13098, -1, 9294, 13099, 13095, -1, 9294, 13100, 13099, -1, 9294, 13101, 13100, -1, 9330, 9318, 13097, -1, 9294, 13102, 13101, -1, 9294, 13090, 13102, -1, 9302, 13103, 13104, -1, 9281, 9348, 13086, -1, 9332, 9330, 13098, -1, 9281, 9349, 9348, -1, 9292, 9294, 13096, -1, 9304, 13104, 13105, -1, 9328, 9318, 9330, -1, 9304, 9302, 13104, -1, 9328, 9320, 9318, -1, 9300, 13106, 13103, -1, 9292, 13096, 13107, -1, 9300, 13103, 9302, -1, 9334, 9332, 13098, -1, 9282, 9349, 9281, -1, 9282, 13108, 9349, -1, 9306, 13105, 13109, -1, 9306, 9304, 13105, -1, 9290, 9292, 13107, -1, 9326, 9321, 9320, -1, 9326, 9320, 9328, -1, 9290, 13107, 13110, -1, 9298, 13106, 9300, -1, 9298, 13111, 13106, -1, 9284, 13108, 9282, -1, 9336, 9334, 13098, -1, 9284, 13112, 13108, -1, 9308, 13109, 13097, -1, 9288, 9290, 13110, -1, 9308, 9306, 13109, -1, 9288, 13110, 13113, -1, 9324, 13114, 9321, -1, 9286, 9288, 13113, -1, 9286, 13112, 9284, -1, 9324, 9321, 9326, -1, 9296, 13111, 9298, -1, 9286, 13113, 13112, -1, 9296, 13115, 13111, -1, 9338, 13098, 13116, -1, 9338, 9336, 13098, -1, 9310, 9308, 13097, -1, 13117, 13118, 13114, -1, 13119, 13120, 13115, -1, 13119, 13115, 9296, -1, 13117, 13114, 9324, -1, 9340, 9338, 13116, -1, 9312, 9310, 13097, -1, 13121, 9340, 13116, -1, 13122, 13123, 13120, -1, 13102, 13090, 13118, -1, 13102, 13118, 13117, -1, 13122, 13120, 13119, -1, 9314, 9312, 13097, -1, 9342, 9340, 13121, -1, 13124, 13125, 13123, -1, 13124, 13123, 13122, -1, 9316, 9314, 13097, -1, 13126, 9344, 9342, -1, 13126, 9342, 13121, -1, 13127, 13125, 13124, -1, 9318, 9316, 13097, -1, 13128, 13125, 13127, -1, 13129, 13128, 13127, -1, 13087, 9346, 9344, -1, 13087, 9344, 13126, -1, 13094, 13128, 13129, -1, 13094, 13129, 13093, -1, 13130, 9323, 9325, -1, 9339, 9335, 9337, -1, 9339, 9333, 9335, -1, 9341, 9331, 9333, -1, 9341, 9333, 9339, -1, 9343, 9329, 9331, -1, 9343, 9331, 9341, -1, 9345, 9327, 9329, -1, 9345, 9329, 9343, -1, 9347, 9325, 9327, -1, 9347, 9327, 9345, -1, 13131, 9347, 9350, -1, 13131, 13130, 9325, -1, 13131, 9325, 9347, -1, 13132, 13133, 13130, -1, 13132, 13130, 13131, -1, 13134, 13135, 13136, -1, 13134, 13137, 13135, -1, 13134, 13138, 13137, -1, 13134, 13139, 13138, -1, 13140, 13141, 13133, -1, 13140, 13136, 13141, -1, 13140, 13133, 13132, -1, 13140, 13134, 13136, -1, 9350, 9349, 13131, -1, 9349, 13108, 13131, -1, 13131, 13112, 13132, -1, 13108, 13112, 13131, -1, 13132, 13113, 13140, -1, 13112, 13113, 13132, -1, 13140, 13110, 13134, -1, 13113, 13110, 13140, -1, 13134, 13107, 13139, -1, 13110, 13107, 13134, -1, 13139, 13096, 13138, -1, 13107, 13096, 13139, -1, 13138, 13095, 13137, -1, 13096, 13095, 13138, -1, 13137, 13099, 13135, -1, 13095, 13099, 13137, -1, 13135, 13100, 13136, -1, 13099, 13100, 13135, -1, 13136, 13101, 13141, -1, 13100, 13101, 13136, -1, 13141, 13102, 13133, -1, 13101, 13102, 13141, -1, 13133, 13117, 13130, -1, 13102, 13117, 13133, -1, 13130, 9324, 9323, -1, 13117, 9324, 13130, -1, 9295, 9303, 9305, -1, 9295, 9301, 9303, -1, 9295, 9299, 9301, -1, 9295, 9297, 9299, -1, 9311, 9307, 9309, -1, 9311, 9305, 9307, -1, 9311, 9295, 9305, -1, 13142, 13143, 9295, -1, 13144, 13142, 9295, -1, 13145, 13144, 9295, -1, 9317, 9313, 9315, -1, 9317, 9311, 9313, -1, 9317, 9295, 9311, -1, 13146, 13145, 9295, -1, 9319, 9295, 9317, -1, 13147, 9319, 9322, -1, 13147, 9295, 9319, -1, 13148, 13149, 13146, -1, 13148, 13150, 13149, -1, 13148, 13146, 9295, -1, 13151, 9295, 13147, -1, 13152, 13153, 13148, -1, 13152, 13148, 9295, -1, 13152, 9295, 13151, -1, 9322, 9321, 13147, -1, 9321, 13114, 13147, -1, 13147, 13118, 13151, -1, 13114, 13118, 13147, -1, 13151, 13090, 13152, -1, 13118, 13090, 13151, -1, 13152, 13089, 13153, -1, 13090, 13089, 13152, -1, 13153, 13091, 13148, -1, 13089, 13091, 13153, -1, 13148, 13092, 13150, -1, 13091, 13092, 13148, -1, 13150, 13093, 13149, -1, 13092, 13093, 13150, -1, 13149, 13129, 13146, -1, 13093, 13129, 13149, -1, 13146, 13127, 13145, -1, 13129, 13127, 13146, -1, 13145, 13124, 13144, -1, 13127, 13124, 13145, -1, 13144, 13122, 13142, -1, 13124, 13122, 13144, -1, 13142, 13119, 13143, -1, 13122, 13119, 13142, -1, 13143, 9296, 9295, -1, 13119, 9296, 13143, -1, 12113, 13094, 13088, -1, 12113, 12130, 13094, -1, 12130, 13128, 13094, -1, 12130, 12131, 13128, -1, 12131, 13125, 13128, -1, 12131, 12132, 13125, -1, 12132, 13123, 13125, -1, 12132, 12133, 13123, -1, 12133, 13120, 13123, -1, 12133, 12134, 13120, -1, 12134, 13115, 13120, -1, 12134, 12135, 13115, -1, 12135, 13111, 13115, -1, 12135, 12124, 13111, -1, 12124, 13106, 13111, -1, 12124, 12125, 13106, -1, 12125, 13103, 13106, -1, 12125, 12126, 13103, -1, 12126, 13104, 13103, -1, 12126, 12127, 13104, -1, 12127, 13105, 13104, -1, 12127, 12128, 13105, -1, 12128, 13109, 13105, -1, 12128, 12129, 13109, -1, 12129, 13097, 13109, -1, 12129, 12122, 13097, -1, 13088, 9294, 12113, -1, 12113, 9294, 9293, -1, 13098, 12122, 12120, -1, 13098, 13097, 12122, -1, 12120, 13116, 13098, -1, 12120, 12118, 13116, -1, 12118, 13121, 13116, -1, 12118, 12115, 13121, -1, 12115, 13126, 13121, -1, 12115, 12114, 13126, -1, 12114, 13087, 13126, -1, 12114, 12117, 13087, -1, 12117, 13086, 13087, -1, 12117, 12119, 13086, -1, 12119, 9281, 13086, -1, 12119, 9279, 9281, -1, 12163, 12174, 12835, -1, 12835, 12174, 12832, -1, 12832, 12175, 12828, -1, 12174, 12175, 12832, -1, 12828, 12176, 12831, -1, 12175, 12176, 12828, -1, 12831, 12136, 12848, -1, 12176, 12136, 12831, -1, 12848, 12138, 12846, -1, 12136, 12138, 12848, -1, 12846, 12139, 12845, -1, 12138, 12139, 12846, -1, 12845, 12143, 12842, -1, 12139, 12143, 12845, -1, 12842, 12173, 12841, -1, 12143, 12173, 12842, -1, 12841, 12172, 12838, -1, 12173, 12172, 12841, -1, 12838, 12171, 12837, -1, 12172, 12171, 12838, -1, 12837, 12168, 12833, -1, 12171, 12168, 12837, -1, 12833, 12165, 12834, -1, 12168, 12165, 12833, -1, 12834, 12164, 12836, -1, 12165, 12164, 12834, -1, 12835, 9277, 12163, -1, 12835, 9278, 9277, -1, 12162, 12836, 12164, -1, 12840, 12836, 12162, -1, 12162, 12159, 12840, -1, 12840, 12159, 12843, -1, 12843, 12155, 12844, -1, 12159, 12155, 12843, -1, 12844, 12148, 12847, -1, 12155, 12148, 12844, -1, 12847, 12141, 12849, -1, 12148, 12141, 12847, -1, 12849, 12140, 12830, -1, 12141, 12140, 12849, -1, 12830, 12147, 12829, -1, 12140, 12147, 12830, -1, 12829, 12150, 12839, -1, 12147, 12150, 12829, -1, 12839, 9268, 9267, -1, 12150, 9268, 12839, -1, 13154, 9262, 9261, -1, 13155, 9262, 13154, -1, 13156, 13155, 13154, -1, 13157, 9266, 9265, -1, 13158, 13156, 13159, -1, 13158, 13155, 13156, -1, 13160, 13157, 13161, -1, 13160, 9266, 13157, -1, 13162, 13159, 13163, -1, 13162, 13158, 13159, -1, 13164, 13161, 13165, -1, 13164, 13160, 13161, -1, 13166, 13163, 13167, -1, 13166, 13162, 13163, -1, 13168, 13165, 13169, -1, 13168, 13164, 13165, -1, 13170, 13167, 13171, -1, 13170, 13166, 13167, -1, 13172, 13169, 13173, -1, 13172, 13168, 13169, -1, 12226, 13171, 13174, -1, 12226, 13170, 13171, -1, 13175, 13173, 13176, -1, 13175, 13172, 13173, -1, 9150, 13174, 13177, -1, 9150, 12226, 13174, -1, 13178, 13176, 9151, -1, 13178, 9151, 9150, -1, 13178, 13175, 13176, -1, 13179, 13178, 9150, -1, 13179, 9150, 13177, -1, 13180, 13177, 12045, -1, 13180, 13179, 13177, -1, 12046, 13180, 12045, -1, 13181, 12476, 13182, -1, 13183, 12476, 13184, -1, 13183, 13182, 12476, -1, 13185, 13183, 13184, -1, 12477, 12476, 13181, -1, 13186, 13184, 13187, -1, 13186, 13185, 13184, -1, 13188, 13187, 12475, -1, 13188, 13186, 13187, -1, 12474, 13188, 12475, -1, 12380, 12381, 13189, -1, 13190, 13189, 13191, -1, 13190, 12380, 13189, -1, 13192, 13191, 13193, -1, 13192, 13190, 13191, -1, 13194, 13193, 13195, -1, 13194, 13192, 13193, -1, 13196, 13195, 10448, -1, 13196, 13194, 13195, -1, 10450, 13196, 10448, -1, 12471, 12468, 13197, -1, 13198, 13197, 13199, -1, 13198, 12471, 13197, -1, 13200, 13199, 13201, -1, 13200, 13198, 13199, -1, 13202, 13201, 13203, -1, 13202, 13200, 13201, -1, 13204, 13202, 13203, -1, 9163, 13203, 12382, -1, 9163, 13204, 13203, -1, 12513, 12514, 13205, -1, 13205, 13206, 13207, -1, 12514, 13206, 13205, -1, 13207, 13208, 13209, -1, 13206, 13208, 13207, -1, 13209, 13210, 12517, -1, 13208, 13210, 13209, -1, 13210, 12515, 12517, -1, 12512, 12511, 13211, -1, 13212, 13211, 13213, -1, 13212, 12512, 13211, -1, 13214, 13212, 13213, -1, 13215, 13213, 13216, -1, 13215, 13214, 13213, -1, 13217, 13218, 13219, -1, 13217, 13216, 13218, -1, 13217, 13215, 13216, -1, 13220, 13217, 13219, -1, 13221, 13219, 13222, -1, 13221, 13220, 13219, -1, 13223, 13222, 12020, -1, 13223, 13221, 13222, -1, 12019, 13223, 12020, -1, 13224, 12516, 12518, -1, 13224, 12518, 13225, -1, 13226, 13225, 13227, -1, 13226, 13224, 13225, -1, 13228, 13227, 13229, -1, 13228, 13226, 13227, -1, 13230, 13229, 13231, -1, 13230, 13228, 13229, -1, 12509, 13231, 12506, -1, 12509, 13230, 13231, -1, 12585, 13232, 12584, -1, 12584, 13232, 13233, -1, 13233, 13232, 13234, -1, 13234, 13235, 13236, -1, 13232, 13235, 13234, -1, 13236, 13237, 13238, -1, 13235, 13237, 13236, -1, 13238, 13239, 12606, -1, 13237, 13239, 13238, -1, 13239, 12605, 12606, -1, 12392, 12395, 13240, -1, 13241, 13242, 13243, -1, 13241, 13240, 13242, -1, 13241, 12392, 13240, -1, 13244, 13243, 13245, -1, 13244, 13241, 13243, -1, 13246, 13245, 13247, -1, 13246, 13244, 13245, -1, 13248, 13247, 12389, -1, 13248, 13246, 13247, -1, 12391, 13248, 12389, -1, 13249, 12394, 12393, -1, 13249, 12393, 13250, -1, 13251, 13252, 13253, -1, 13251, 13250, 13252, -1, 13251, 13249, 13250, -1, 13254, 13255, 13256, -1, 13254, 13253, 13255, -1, 13254, 13251, 13253, -1, 13257, 13256, 13258, -1, 13257, 13254, 13256, -1, 13259, 13260, 13261, -1, 13259, 13258, 13260, -1, 13259, 13257, 13258, -1, 13262, 13261, 13263, -1, 13262, 13259, 13261, -1, 13264, 13263, 13265, -1, 13264, 13262, 13263, -1, 9235, 13265, 11673, -1, 9235, 13264, 13265, -1, 11684, 11680, 13266, -1, 13267, 13266, 13268, -1, 13267, 11684, 13266, -1, 13269, 13268, 13270, -1, 13269, 13267, 13268, -1, 13271, 13270, 13272, -1, 13271, 13269, 13270, -1, 13273, 13271, 13272, -1, 13274, 13272, 12398, -1, 13274, 13273, 13272, -1, 12397, 13274, 12398, -1, 8902, 8905, 9218, -1, 8902, 9218, 13275, -1, 8900, 8902, 13275, -1, 13276, 13275, 13277, -1, 13276, 8900, 13275, -1, 13278, 13277, 13279, -1, 13278, 13276, 13277, -1, 13280, 13278, 13279, -1, 13281, 13279, 13282, -1, 13281, 13280, 13279, -1, 13283, 13282, 9179, -1, 13283, 13281, 13282, -1, 13284, 9181, 9200, -1, 13284, 9179, 9181, -1, 13284, 13283, 9179, -1, 13285, 9200, 9202, -1, 13285, 13284, 9200, -1, 13286, 9202, 9210, -1, 13286, 13285, 9202, -1, 13287, 9210, 9207, -1, 13287, 13286, 9210, -1, 12399, 13287, 9207, -1, 12402, 12404, 13288, -1, 13289, 13288, 13290, -1, 13289, 12402, 13288, -1, 13291, 13290, 13292, -1, 13291, 13289, 13290, -1, 13293, 13292, 13294, -1, 13293, 13291, 13292, -1, 13295, 13293, 13294, -1, 13296, 13294, 12406, -1, 13296, 13295, 13294, -1, 12405, 13296, 12406, -1, 8915, 8918, 8882, -1, 8915, 8882, 13297, -1, 8913, 8915, 13297, -1, 13298, 13297, 13299, -1, 13298, 8913, 13297, -1, 13300, 13299, 13301, -1, 13300, 13298, 13299, -1, 13302, 13300, 13301, -1, 13303, 13301, 13304, -1, 13303, 13302, 13301, -1, 13305, 13304, 8844, -1, 13305, 13303, 13304, -1, 13306, 8846, 8864, -1, 13306, 8844, 8846, -1, 13306, 13305, 8844, -1, 13307, 8864, 8866, -1, 13307, 13306, 8864, -1, 13308, 8866, 8874, -1, 13308, 13307, 8866, -1, 13309, 8874, 8871, -1, 13309, 13308, 8874, -1, 12407, 13309, 8871, -1, 12410, 12412, 13310, -1, 13311, 13310, 13312, -1, 13311, 12410, 13310, -1, 13313, 13312, 13314, -1, 13313, 13311, 13312, -1, 13315, 13314, 13316, -1, 13315, 13313, 13314, -1, 13317, 13315, 13316, -1, 13318, 13316, 12414, -1, 13318, 13317, 13316, -1, 12413, 13318, 12414, -1, 8928, 8931, 8833, -1, 8928, 8833, 13319, -1, 8926, 8928, 13319, -1, 13320, 13319, 13321, -1, 13320, 8926, 13319, -1, 13322, 13321, 13323, -1, 13322, 13320, 13321, -1, 13324, 13322, 13323, -1, 13325, 13323, 13326, -1, 13325, 13324, 13323, -1, 13327, 13326, 8795, -1, 13327, 13325, 13326, -1, 13328, 8797, 8815, -1, 13328, 8795, 8797, -1, 13328, 13327, 8795, -1, 13329, 8815, 8817, -1, 13329, 13328, 8815, -1, 13330, 8817, 8825, -1, 13330, 13329, 8817, -1, 13331, 8825, 8822, -1, 13331, 13330, 8825, -1, 12415, 13331, 8822, -1, 12418, 12420, 13332, -1, 13333, 13332, 13334, -1, 13333, 12418, 13332, -1, 13335, 13334, 13336, -1, 13335, 13333, 13334, -1, 13337, 13336, 13338, -1, 13337, 13335, 13336, -1, 13339, 13337, 13338, -1, 13340, 13338, 12422, -1, 13340, 13339, 13338, -1, 12421, 13340, 12422, -1, 8941, 8944, 8784, -1, 8941, 8784, 13341, -1, 8939, 8941, 13341, -1, 13342, 13341, 13343, -1, 13342, 8939, 13341, -1, 13344, 13343, 13345, -1, 13344, 13342, 13343, -1, 13346, 13344, 13345, -1, 13347, 13345, 13348, -1, 13347, 13346, 13345, -1, 13349, 13348, 8746, -1, 13349, 13347, 13348, -1, 13350, 8748, 8766, -1, 13350, 8746, 8748, -1, 13350, 13349, 8746, -1, 13351, 8766, 8768, -1, 13351, 13350, 8766, -1, 13352, 8768, 8776, -1, 13352, 13351, 8768, -1, 13353, 8776, 8773, -1, 13353, 13352, 8776, -1, 12423, 13353, 8773, -1, 12426, 12428, 13354, -1, 13355, 13354, 13356, -1, 13355, 12426, 13354, -1, 13357, 13356, 13358, -1, 13357, 13355, 13356, -1, 13359, 13358, 13360, -1, 13359, 13357, 13358, -1, 13361, 13359, 13360, -1, 13362, 13360, 12430, -1, 13362, 13361, 13360, -1, 12429, 13362, 12430, -1, 8954, 8957, 8736, -1, 8954, 8736, 13363, -1, 8952, 8954, 13363, -1, 13364, 13363, 13365, -1, 13364, 8952, 13363, -1, 13366, 13365, 13367, -1, 13366, 13364, 13365, -1, 13368, 13366, 13367, -1, 13369, 13367, 13370, -1, 13369, 13368, 13367, -1, 13371, 13370, 8696, -1, 13371, 13369, 13370, -1, 13372, 8698, 8717, -1, 13372, 8696, 8698, -1, 13372, 13371, 8696, -1, 13373, 8717, 8719, -1, 13373, 13372, 8717, -1, 13374, 8719, 8727, -1, 13374, 13373, 8719, -1, 13375, 8727, 8724, -1, 13375, 13374, 8727, -1, 12431, 13375, 8724, -1, 8967, 8970, 8686, -1, 8967, 8686, 13376, -1, 8965, 8967, 13376, -1, 13377, 13376, 13378, -1, 13377, 8965, 13376, -1, 13379, 13378, 13380, -1, 13379, 13377, 13378, -1, 13381, 13379, 13380, -1, 13382, 13380, 13383, -1, 13382, 13381, 13380, -1, 13384, 13383, 8647, -1, 13384, 13382, 13383, -1, 13385, 8649, 8668, -1, 13385, 8647, 8649, -1, 13385, 13384, 8647, -1, 13386, 8668, 8670, -1, 13386, 13385, 8668, -1, 13387, 8670, 8678, -1, 13387, 13386, 8670, -1, 13388, 8678, 8675, -1, 13388, 13387, 8678, -1, 12439, 13388, 8675, -1, 12434, 12436, 13389, -1, 13390, 13389, 13391, -1, 13390, 12434, 13389, -1, 13392, 13391, 13393, -1, 13392, 13390, 13391, -1, 13394, 13393, 13395, -1, 13394, 13392, 13393, -1, 13396, 13394, 13395, -1, 13397, 13395, 12438, -1, 13397, 13396, 13395, -1, 12437, 13397, 12438, -1, 12442, 12444, 13398, -1, 13399, 13398, 13400, -1, 13399, 12442, 13398, -1, 13401, 13400, 13402, -1, 13401, 13399, 13400, -1, 13403, 13402, 13404, -1, 13403, 13401, 13402, -1, 13405, 13403, 13404, -1, 13406, 13404, 12446, -1, 13406, 13405, 13404, -1, 12445, 13406, 12446, -1, 9055, 9058, 9052, -1, 9055, 9052, 13407, -1, 9053, 9055, 13407, -1, 13408, 13407, 13409, -1, 13408, 9053, 13407, -1, 13410, 13409, 13411, -1, 13410, 13408, 13409, -1, 13412, 13410, 13411, -1, 13413, 13411, 13414, -1, 13413, 13412, 13411, -1, 13415, 13414, 9013, -1, 13415, 13413, 13414, -1, 13416, 9015, 9033, -1, 13416, 9013, 9015, -1, 13416, 13415, 9013, -1, 13417, 9033, 9035, -1, 13417, 13416, 9033, -1, 13418, 9035, 9043, -1, 13418, 13417, 9035, -1, 13419, 9043, 9040, -1, 13419, 13418, 9043, -1, 12447, 13419, 9040, -1, 12450, 12452, 13420, -1, 13421, 13420, 13422, -1, 13421, 12450, 13420, -1, 13423, 13422, 13424, -1, 13423, 13421, 13422, -1, 13425, 13424, 13426, -1, 13425, 13423, 13424, -1, 13427, 13425, 13426, -1, 13428, 13426, 12454, -1, 13428, 13427, 13426, -1, 12453, 13428, 12454, -1, 8980, 8983, 8532, -1, 8980, 8532, 13429, -1, 8978, 8980, 13429, -1, 13430, 13429, 13431, -1, 13430, 8978, 13429, -1, 13432, 13431, 13433, -1, 13432, 13430, 13431, -1, 13434, 13432, 13433, -1, 13435, 13433, 13436, -1, 13435, 13434, 13433, -1, 13437, 13436, 8543, -1, 13437, 13435, 13436, -1, 13438, 8545, 8563, -1, 13438, 8543, 8545, -1, 13438, 13437, 8543, -1, 13439, 8563, 8565, -1, 13439, 13438, 8563, -1, 13440, 8565, 8573, -1, 13440, 13439, 8565, -1, 13441, 8573, 8570, -1, 13441, 13440, 8573, -1, 12455, 13441, 8570, -1, 8993, 8996, 8638, -1, 8993, 8638, 13442, -1, 8991, 8993, 13442, -1, 13443, 13442, 13444, -1, 13443, 8991, 13442, -1, 13445, 13444, 13446, -1, 13445, 13443, 13444, -1, 13447, 13445, 13446, -1, 13448, 13446, 13449, -1, 13448, 13447, 13446, -1, 13450, 13449, 8599, -1, 13450, 13448, 13449, -1, 13451, 8601, 8619, -1, 13451, 8599, 8601, -1, 13451, 13450, 8599, -1, 13452, 8619, 8621, -1, 13452, 13451, 8619, -1, 13453, 8621, 8629, -1, 13453, 13452, 8621, -1, 13454, 8629, 8626, -1, 13454, 13453, 8629, -1, 12463, 13454, 8626, -1, 12458, 12460, 13455, -1, 13456, 13455, 13457, -1, 13456, 12458, 13455, -1, 13458, 13457, 13459, -1, 13458, 13456, 13457, -1, 13460, 13459, 13461, -1, 13460, 13458, 13459, -1, 13462, 13460, 13461, -1, 13463, 13461, 12462, -1, 13463, 13462, 13461, -1, 12461, 13463, 12462, -1, 9121, 11998, 13464, -1, 9119, 13465, 13466, -1, 9119, 13464, 13465, -1, 9119, 9121, 13464, -1, 9114, 13466, 13467, -1, 9114, 9119, 13466, -1, 9110, 9114, 13467, -1, 9106, 13467, 13468, -1, 9106, 9110, 13467, -1, 9104, 9106, 13468, -1, 9096, 9104, 13468, -1, 9097, 13468, 12466, -1, 9097, 9096, 13468, -1, 12464, 9097, 12466, -1, 11997, 11532, 11528, -1, 13469, 11528, 11522, -1, 13469, 11997, 11528, -1, 13470, 11507, 11513, -1, 13470, 11508, 11507, -1, 13470, 11516, 11508, -1, 13470, 11517, 11516, -1, 13470, 11521, 11517, -1, 13470, 11522, 11521, -1, 13470, 13469, 11522, -1, 13471, 11573, 11570, -1, 13471, 11574, 11573, -1, 13471, 11575, 11574, -1, 13471, 11513, 11575, -1, 13471, 13470, 11513, -1, 13472, 11572, 13473, -1, 13472, 11570, 11572, -1, 13472, 13471, 11570, -1, 13474, 13473, 13475, -1, 13474, 13472, 13473, -1, 13476, 13474, 13475, -1, 13477, 13475, 12058, -1, 13477, 13476, 13475, -1, 8582, 13477, 12058, -1, 10463, 10449, 13478, -1, 13479, 13478, 13480, -1, 13479, 10463, 13478, -1, 13481, 13480, 13482, -1, 13481, 13479, 13480, -1, 13483, 13482, 12387, -1, 13483, 13481, 13482, -1, 12386, 13483, 12387, -1, 13484, 13483, 12386, -1, 12632, 13484, 12386, -1, 13485, 13484, 12632, -1, 12634, 13485, 12632, -1, 12520, 12523, 13485, -1, 12520, 13485, 12634, -1, 13486, 13485, 12523, -1, 13481, 13484, 13485, -1, 13481, 13483, 13484, -1, 13481, 13485, 13486, -1, 13479, 13486, 13487, -1, 13479, 13481, 13486, -1, 10463, 13479, 13487, -1, 13486, 12523, 12522, -1, 13486, 12522, 13488, -1, 13487, 13488, 13489, -1, 13487, 13486, 13488, -1, 10463, 13489, 10461, -1, 10463, 13487, 13489, -1, 9127, 9126, 10457, -1, 9127, 10457, 13490, -1, 9143, 13490, 13491, -1, 9143, 9127, 13490, -1, 9144, 13491, 13492, -1, 9144, 9143, 13491, -1, 9140, 13492, 13493, -1, 9140, 9144, 13492, -1, 9136, 13493, 13494, -1, 9136, 9140, 13493, -1, 9131, 13494, 13495, -1, 9131, 9136, 13494, -1, 9123, 13495, 13496, -1, 9123, 9131, 13495, -1, 9124, 13496, 12243, -1, 9124, 9123, 13496, -1, 12648, 13497, 13498, -1, 12648, 13498, 13499, -1, 12648, 13499, 13500, -1, 12648, 13500, 11606, -1, 13501, 13497, 12648, -1, 13496, 12647, 12243, -1, 13502, 13496, 13495, -1, 13502, 12648, 12647, -1, 13502, 12647, 13496, -1, 13503, 13494, 13493, -1, 13503, 13495, 13494, -1, 13503, 12648, 13502, -1, 13503, 13502, 13495, -1, 13504, 13490, 10457, -1, 13504, 13491, 13490, -1, 13504, 13492, 13491, -1, 13504, 13493, 13492, -1, 13504, 10457, 10458, -1, 13504, 10458, 13505, -1, 13504, 13505, 13506, -1, 13504, 13506, 13501, -1, 13504, 13503, 13493, -1, 13504, 13501, 12648, -1, 13504, 12648, 13503, -1, 13505, 10458, 10459, -1, 13505, 10459, 13507, -1, 13506, 13507, 13508, -1, 13506, 13505, 13507, -1, 13501, 13508, 13509, -1, 13501, 13506, 13508, -1, 13497, 13509, 13510, -1, 13497, 13501, 13509, -1, 13498, 13510, 13511, -1, 13498, 13497, 13510, -1, 13499, 13511, 13512, -1, 13499, 13498, 13511, -1, 13500, 13512, 13513, -1, 13500, 13513, 11607, -1, 13500, 13499, 13512, -1, 11606, 13500, 11607, -1, 12650, 13514, 13515, -1, 12650, 13515, 13516, -1, 12650, 13516, 13517, -1, 12650, 13517, 11597, -1, 13518, 13514, 12650, -1, 13513, 12649, 11607, -1, 13519, 13513, 13512, -1, 13519, 12650, 12649, -1, 13519, 12649, 13513, -1, 13520, 13511, 13510, -1, 13520, 13512, 13511, -1, 13520, 12650, 13519, -1, 13520, 13519, 13512, -1, 13521, 13507, 10459, -1, 13521, 13508, 13507, -1, 13521, 13509, 13508, -1, 13521, 13510, 13509, -1, 13521, 10459, 10460, -1, 13521, 10460, 13522, -1, 13521, 13522, 13523, -1, 13521, 13523, 13518, -1, 13521, 13520, 13510, -1, 13521, 13518, 12650, -1, 13521, 12650, 13520, -1, 10460, 10462, 13524, -1, 13522, 13524, 13525, -1, 13522, 10460, 13524, -1, 13523, 13525, 13526, -1, 13523, 13522, 13525, -1, 13518, 13526, 13527, -1, 13518, 13523, 13526, -1, 13514, 13528, 13529, -1, 13514, 13527, 13528, -1, 13514, 13518, 13527, -1, 13515, 13530, 13531, -1, 13515, 13529, 13530, -1, 13515, 13514, 13529, -1, 13516, 12652, 12651, -1, 13516, 13531, 12652, -1, 13516, 13515, 13531, -1, 13517, 12651, 12653, -1, 13517, 13516, 12651, -1, 11597, 12653, 11584, -1, 11597, 13517, 12653, -1, 11732, 11735, 13532, -1, 13532, 13533, 13534, -1, 11735, 13533, 13532, -1, 13534, 13535, 13536, -1, 13533, 13535, 13534, -1, 13536, 13537, 13538, -1, 13535, 13537, 13536, -1, 13538, 13539, 13540, -1, 13537, 13539, 13538, -1, 13540, 13541, 13542, -1, 13539, 13541, 13540, -1, 13542, 13543, 12055, -1, 13541, 13543, 13542, -1, 13543, 12056, 12055, -1, 12023, 12022, 13544, -1, 13545, 13544, 13546, -1, 13545, 12023, 13544, -1, 13547, 13546, 13548, -1, 13547, 13545, 13546, -1, 13549, 13548, 13550, -1, 13549, 13547, 13548, -1, 13551, 13550, 12121, -1, 13551, 13549, 13550, -1, 12116, 13551, 12121, -1, 12123, 12112, 13552, -1, 13553, 13552, 13554, -1, 13553, 12123, 13552, -1, 13555, 13554, 13556, -1, 13555, 13553, 13554, -1, 13557, 13556, 13558, -1, 13557, 13555, 13556, -1, 13559, 13558, 13560, -1, 13559, 13557, 13558, -1, 13561, 13560, 13562, -1, 13561, 13559, 13560, -1, 13563, 13561, 13562, -1, 13564, 13562, 13565, -1, 13564, 13563, 13562, -1, 13566, 13565, 12146, -1, 13566, 13564, 13565, -1, 12142, 13566, 12146, -1, 12218, 11690, 13567, -1, 13567, 11689, 13568, -1, 13568, 11689, 13569, -1, 11690, 11689, 13567, -1, 13569, 11691, 13570, -1, 11689, 11691, 13569, -1, 13570, 11692, 13571, -1, 13571, 11692, 13572, -1, 11691, 11692, 13570, -1, 13572, 11693, 13573, -1, 13573, 11693, 13574, -1, 11692, 11693, 13572, -1, 13574, 9252, 9254, -1, 11693, 9252, 13574, -1, 9122, 9124, 11703, -1, 9122, 11703, 11702, -1, 9129, 11702, 11701, -1, 9129, 9122, 11702, -1, 13575, 11701, 11700, -1, 13575, 9129, 11701, -1, 13576, 11700, 11699, -1, 13576, 13575, 11700, -1, 13577, 11699, 11696, -1, 13577, 13576, 11699, -1, 13578, 11696, 11695, -1, 13578, 13577, 11696, -1, 13579, 11695, 11694, -1, 13579, 13578, 11695, -1, 13580, 13579, 11694, -1, 13581, 11694, 11697, -1, 13581, 13580, 11694, -1, 12248, 11697, 11698, -1, 12248, 13581, 11697, -1, 10416, 10419, 13582, -1, 13582, 13583, 13584, -1, 10419, 13583, 13582, -1, 13584, 13585, 13586, -1, 13586, 13585, 13587, -1, 13583, 13585, 13584, -1, 13587, 11674, 11676, -1, 13585, 11674, 13587, -1, 10412, 10411, 13588, -1, 13589, 13588, 13590, -1, 13589, 10412, 13588, -1, 13591, 13590, 11667, -1, 13591, 13589, 13590, -1, 11666, 13591, 11667, -1, 10468, 10469, 13592, -1, 13592, 13593, 13594, -1, 10469, 13593, 13592, -1, 13594, 13595, 12467, -1, 13593, 13595, 13594, -1, 13595, 12465, 12467, -1, 13596, 12385, 8589, -1, 13596, 8589, 13597, -1, 13598, 13597, 13599, -1, 13598, 13596, 13597, -1, 13600, 13599, 8581, -1, 13600, 13598, 13599, -1, 9076, 13600, 8581, -1, 10476, 10477, 13601, -1, 13601, 13602, 13603, -1, 10477, 13602, 13601, -1, 13603, 13604, 12459, -1, 13602, 13604, 13603, -1, 13604, 12457, 12459, -1, 10479, 10024, 13605, -1, 13606, 13605, 13607, -1, 13606, 10479, 13605, -1, 13608, 13607, 8637, -1, 13608, 13606, 13607, -1, 12456, 13608, 8637, -1, 10483, 10484, 13609, -1, 13609, 13610, 13611, -1, 10484, 13610, 13609, -1, 13611, 13612, 12451, -1, 13610, 13612, 13611, -1, 13612, 12449, 12451, -1, 10486, 10016, 13613, -1, 13614, 13613, 13615, -1, 13614, 10486, 13613, -1, 13616, 13615, 8533, -1, 13616, 13614, 13615, -1, 12448, 13616, 8533, -1, 10490, 10491, 13617, -1, 13617, 13618, 13619, -1, 10491, 13618, 13617, -1, 13619, 13620, 12443, -1, 13618, 13620, 13619, -1, 13620, 12441, 12443, -1, 10493, 10072, 13621, -1, 13622, 13621, 13623, -1, 13622, 10493, 13621, -1, 13624, 13623, 9051, -1, 13624, 13622, 13623, -1, 12440, 13624, 9051, -1, 10497, 10498, 13625, -1, 13625, 13626, 13627, -1, 10498, 13626, 13625, -1, 13627, 13628, 12435, -1, 13626, 13628, 13627, -1, 13628, 12433, 12435, -1, 10500, 10032, 13629, -1, 13630, 13629, 13631, -1, 13630, 10500, 13629, -1, 13632, 13631, 8687, -1, 13632, 13630, 13631, -1, 12432, 13632, 8687, -1, 10504, 10505, 13633, -1, 13633, 13634, 13635, -1, 10505, 13634, 13633, -1, 13635, 13636, 12427, -1, 13634, 13636, 13635, -1, 13636, 12425, 12427, -1, 10507, 10040, 13637, -1, 13638, 13637, 13639, -1, 13638, 10507, 13637, -1, 13640, 13639, 8735, -1, 13640, 13638, 13639, -1, 12424, 13640, 8735, -1, 10511, 10512, 13641, -1, 13641, 13642, 13643, -1, 10512, 13642, 13641, -1, 13643, 13644, 12419, -1, 13642, 13644, 13643, -1, 13644, 12417, 12419, -1, 10514, 10048, 13645, -1, 13646, 13645, 13647, -1, 13646, 10514, 13645, -1, 13648, 13647, 8785, -1, 13648, 13646, 13647, -1, 12416, 13648, 8785, -1, 10531, 10080, 13649, -1, 13650, 13649, 13651, -1, 13650, 10531, 13649, -1, 13652, 13651, 9219, -1, 13652, 13650, 13651, -1, 12396, 13652, 9219, -1, 10521, 10056, 13653, -1, 13654, 13653, 13655, -1, 13654, 10521, 13653, -1, 13656, 13655, 8834, -1, 13656, 13654, 13655, -1, 12408, 13656, 8834, -1, 10518, 10519, 13657, -1, 13657, 13658, 13659, -1, 10519, 13658, 13657, -1, 13659, 13660, 12411, -1, 13658, 13660, 13659, -1, 13660, 12409, 12411, -1, 10528, 10064, 13661, -1, 13662, 13661, 13663, -1, 13662, 10528, 13661, -1, 13664, 13663, 8883, -1, 13664, 13662, 13663, -1, 12400, 13664, 8883, -1, 10525, 10526, 13665, -1, 13665, 13666, 13667, -1, 10526, 13666, 13665, -1, 13667, 13668, 12403, -1, 13666, 13668, 13667, -1, 13668, 12401, 12403, -1, 10472, 10473, 13669, -1, 13669, 13670, 13671, -1, 10473, 13670, 13669, -1, 13671, 13672, 12390, -1, 13670, 13672, 13671, -1, 13672, 12388, 12390, -1, 12657, 12656, 12733, -1, 12733, 13673, 12732, -1, 12656, 13673, 12733, -1, 12731, 13674, 12730, -1, 12732, 13674, 12731, -1, 13673, 13674, 12732, -1, 12730, 13675, 12729, -1, 13674, 13675, 12730, -1, 12729, 13676, 9246, -1, 13675, 13676, 12729, -1, 13676, 9244, 9246, -1, 12685, 13677, 12656, -1, 12656, 13677, 13673, -1, 13678, 13677, 12685, -1, 13679, 13680, 13681, -1, 13681, 13680, 13682, -1, 13683, 13684, 13685, -1, 13685, 13684, 13686, -1, 13687, 12681, 9236, -1, 13673, 13688, 13674, -1, 9240, 12681, 9242, -1, 9237, 12681, 9240, -1, 9236, 12681, 9237, -1, 13678, 13688, 13677, -1, 13677, 13688, 13673, -1, 13682, 13688, 13678, -1, 13686, 13689, 13679, -1, 13679, 13689, 13680, -1, 13690, 13691, 13683, -1, 13683, 13691, 13684, -1, 13674, 13692, 13675, -1, 13682, 13692, 13688, -1, 13688, 13692, 13674, -1, 13680, 13692, 13682, -1, 13686, 13693, 13689, -1, 13684, 13693, 13686, -1, 11664, 13694, 11663, -1, 13695, 13694, 13690, -1, 11663, 13694, 13695, -1, 13690, 13694, 13691, -1, 13675, 13696, 13676, -1, 13692, 13696, 13675, -1, 13689, 13696, 13680, -1, 13680, 13696, 13692, -1, 13691, 13697, 13684, -1, 13684, 13697, 13693, -1, 13676, 13698, 9244, -1, 13693, 13698, 13689, -1, 13696, 13698, 13676, -1, 13689, 13698, 13696, -1, 11671, 13699, 11664, -1, 11664, 13699, 13694, -1, 13694, 13699, 13691, -1, 13691, 13699, 13697, -1, 9244, 13700, 9245, -1, 13697, 13700, 13693, -1, 13698, 13700, 9244, -1, 13693, 13700, 13698, -1, 9245, 13701, 9249, -1, 13699, 13701, 13697, -1, 11672, 13701, 11671, -1, 13700, 13701, 9245, -1, 13697, 13701, 13700, -1, 9249, 13701, 11672, -1, 11671, 13701, 13699, -1, 11672, 9251, 9249, -1, 12681, 13702, 12683, -1, 13687, 13702, 12681, -1, 13703, 13681, 13687, -1, 13687, 13681, 13702, -1, 12683, 13678, 12685, -1, 13702, 13678, 12683, -1, 13704, 13679, 13703, -1, 13703, 13679, 13681, -1, 13702, 13682, 13678, -1, 13681, 13682, 13702, -1, 13685, 13686, 13704, -1, 13704, 13686, 13679, -1, 11663, 13695, 9234, -1, 9234, 13695, 13705, -1, 13705, 13690, 13706, -1, 13695, 13690, 13705, -1, 13706, 13683, 13707, -1, 13690, 13683, 13706, -1, 13707, 13685, 13708, -1, 13683, 13685, 13707, -1, 13708, 13704, 13709, -1, 13685, 13704, 13708, -1, 13709, 13703, 13710, -1, 13704, 13703, 13709, -1, 13710, 13687, 13711, -1, 13703, 13687, 13710, -1, 13711, 9236, 9238, -1, 13687, 9236, 13711, -1, 9243, 12680, 9241, -1, 9241, 12680, 9239, -1, 9239, 12680, 9238, -1, 9238, 12680, 13711, -1, 9230, 9232, 13705, -1, 9232, 9234, 13705, -1, 13711, 13712, 13710, -1, 12678, 13712, 12680, -1, 12680, 13712, 13711, -1, 13712, 13713, 13710, -1, 13714, 13715, 10354, -1, 12676, 13715, 12678, -1, 10354, 13715, 12676, -1, 12678, 13715, 13712, -1, 13712, 13715, 13713, -1, 13710, 13716, 13709, -1, 13713, 13716, 13710, -1, 13717, 13718, 13714, -1, 13719, 13718, 13717, -1, 13715, 13718, 13713, -1, 13713, 13718, 13716, -1, 13714, 13718, 13715, -1, 13709, 13720, 13708, -1, 13708, 13720, 13707, -1, 13716, 13720, 13709, -1, 13721, 13722, 13719, -1, 13719, 13722, 13718, -1, 13718, 13722, 13716, -1, 13716, 13722, 13720, -1, 13707, 13723, 13706, -1, 9228, 13723, 13721, -1, 13720, 13723, 13707, -1, 13721, 13723, 13722, -1, 13722, 13723, 13720, -1, 13706, 13724, 13705, -1, 9230, 13724, 9228, -1, 9228, 13724, 13723, -1, 13723, 13724, 13706, -1, 13705, 13724, 9230, -1, 10354, 10353, 13714, -1, 13714, 13725, 13717, -1, 10353, 13725, 13714, -1, 13717, 13726, 13719, -1, 13725, 13726, 13717, -1, 13719, 13727, 13721, -1, 13726, 13727, 13719, -1, 13721, 13728, 9228, -1, 13727, 13728, 13721, -1, 13728, 9229, 9228, -1, 13729, 13730, 13731, -1, 13259, 13732, 13257, -1, 13733, 13734, 13735, -1, 13731, 13732, 13259, -1, 13735, 13734, 13736, -1, 13728, 13737, 9229, -1, 9233, 13264, 9235, -1, 9229, 13737, 13738, -1, 13739, 13740, 13741, -1, 13741, 13740, 13742, -1, 13738, 13743, 13744, -1, 10359, 13745, 13746, -1, 13744, 13743, 13730, -1, 13746, 13745, 13747, -1, 10363, 13745, 10359, -1, 10365, 13745, 10363, -1, 13747, 13745, 13748, -1, 13249, 13749, 12394, -1, 13251, 13749, 13249, -1, 13730, 13750, 13731, -1, 12394, 13749, 13751, -1, 13742, 13749, 13251, -1, 13731, 13750, 13732, -1, 13752, 13753, 13754, -1, 13748, 13753, 13752, -1, 13727, 13755, 13728, -1, 13728, 13755, 13737, -1, 13257, 13756, 13254, -1, 13736, 13757, 13739, -1, 13739, 13757, 13740, -1, 13732, 13756, 13257, -1, 13754, 13758, 13733, -1, 13738, 13759, 13743, -1, 13733, 13758, 13734, -1, 13737, 13759, 13738, -1, 13751, 13760, 13761, -1, 13740, 13760, 13742, -1, 13730, 13762, 13750, -1, 13742, 13760, 13749, -1, 13743, 13762, 13730, -1, 13749, 13760, 13751, -1, 10365, 13763, 13745, -1, 13745, 13763, 13748, -1, 13726, 13764, 13727, -1, 13748, 13763, 13753, -1, 13727, 13764, 13755, -1, 13734, 13765, 13736, -1, 13750, 13766, 13732, -1, 13736, 13765, 13757, -1, 13732, 13766, 13756, -1, 13753, 13767, 13754, -1, 13754, 13767, 13758, -1, 13761, 13768, 13769, -1, 13737, 13770, 13759, -1, 13757, 13768, 13740, -1, 13755, 13770, 13737, -1, 13760, 13768, 13761, -1, 13254, 13741, 13251, -1, 13740, 13768, 13760, -1, 13756, 13741, 13254, -1, 13758, 13771, 13734, -1, 13734, 13771, 13765, -1, 13759, 13772, 13743, -1, 13763, 13773, 13753, -1, 10371, 13773, 10365, -1, 13743, 13772, 13762, -1, 10375, 13773, 10371, -1, 13753, 13773, 13767, -1, 10365, 13773, 13763, -1, 13762, 13735, 13750, -1, 13769, 13774, 13775, -1, 13757, 13774, 13768, -1, 13750, 13735, 13766, -1, 13768, 13774, 13769, -1, 13765, 13774, 13757, -1, 10355, 13776, 10353, -1, 10359, 13776, 10355, -1, 10353, 13776, 13725, -1, 13725, 13776, 13726, -1, 13726, 13776, 13764, -1, 13767, 13777, 13758, -1, 13764, 13747, 13755, -1, 13758, 13777, 13771, -1, 13775, 13778, 13779, -1, 13774, 13778, 13775, -1, 13755, 13747, 13770, -1, 13771, 13778, 13765, -1, 13766, 13739, 13756, -1, 13765, 13778, 13774, -1, 10379, 13780, 10375, -1, 10375, 13780, 13773, -1, 13773, 13780, 13767, -1, 13767, 13780, 13777, -1, 13756, 13739, 13741, -1, 13779, 13781, 13782, -1, 13770, 13752, 13759, -1, 13778, 13781, 13779, -1, 13777, 13781, 13771, -1, 13771, 13781, 13778, -1, 13759, 13752, 13772, -1, 13762, 13733, 13735, -1, 13781, 13783, 13782, -1, 13772, 13733, 13762, -1, 13777, 13783, 13781, -1, 10382, 13783, 10379, -1, 10379, 13783, 13780, -1, 13782, 13783, 10382, -1, 13780, 13783, 13777, -1, 10382, 10390, 13782, -1, 13735, 13736, 13766, -1, 13264, 13729, 13262, -1, 9233, 13729, 13264, -1, 13766, 13736, 13739, -1, 9231, 13744, 9233, -1, 10359, 13746, 13776, -1, 13776, 13746, 13764, -1, 13764, 13746, 13747, -1, 9233, 13744, 13729, -1, 13262, 13731, 13259, -1, 13729, 13731, 13262, -1, 13741, 13742, 13251, -1, 9229, 13738, 9231, -1, 13747, 13748, 13770, -1, 13770, 13748, 13752, -1, 9231, 13738, 13744, -1, 13752, 13754, 13772, -1, 13772, 13754, 13733, -1, 13744, 13730, 13729, -1, 12395, 12394, 13784, -1, 13784, 13751, 13785, -1, 12394, 13751, 13784, -1, 13785, 13761, 13786, -1, 13751, 13761, 13785, -1, 13786, 13769, 13787, -1, 13761, 13769, 13786, -1, 13787, 13775, 13788, -1, 13769, 13775, 13787, -1, 13788, 13779, 13789, -1, 13775, 13779, 13788, -1, 13789, 13782, 10384, -1, 13779, 13782, 13789, -1, 13782, 10390, 10384, -1, 13788, 13790, 13787, -1, 13787, 13790, 13791, -1, 13792, 13793, 13794, -1, 13791, 13793, 13792, -1, 13795, 13796, 13797, -1, 13798, 13796, 13795, -1, 13247, 13799, 13800, -1, 13797, 13799, 13247, -1, 10385, 13801, 10384, -1, 10386, 13801, 10385, -1, 10384, 13801, 13789, -1, 13789, 13801, 13788, -1, 13788, 13801, 13790, -1, 13791, 13802, 13793, -1, 13790, 13802, 13791, -1, 13794, 13803, 13798, -1, 13798, 13803, 13796, -1, 13247, 13800, 12389, -1, 13800, 13804, 13805, -1, 13796, 13804, 13797, -1, 13799, 13804, 13800, -1, 13797, 13804, 13799, -1, 10387, 13806, 10386, -1, 10386, 13806, 13801, -1, 13801, 13806, 13790, -1, 13790, 13806, 13802, -1, 13793, 13807, 13794, -1, 13794, 13807, 13803, -1, 13805, 13808, 13809, -1, 13803, 13808, 13796, -1, 13796, 13808, 13804, -1, 13804, 13808, 13805, -1, 13793, 13810, 13807, -1, 13802, 13810, 13793, -1, 13807, 13811, 13803, -1, 13809, 13811, 13812, -1, 13803, 13811, 13808, -1, 13808, 13811, 13809, -1, 13802, 13813, 13810, -1, 10388, 13813, 10387, -1, 10387, 13813, 13806, -1, 13806, 13813, 13802, -1, 13810, 13814, 13807, -1, 13812, 13814, 13815, -1, 13811, 13814, 13812, -1, 13807, 13814, 13811, -1, 10389, 10383, 13816, -1, 13815, 13817, 13816, -1, 10389, 13817, 10388, -1, 13810, 13817, 13814, -1, 12395, 13818, 13240, -1, 10388, 13817, 13813, -1, 13816, 13817, 10389, -1, 13813, 13817, 13810, -1, 13814, 13817, 13815, -1, 13784, 13818, 12395, -1, 13785, 13819, 13784, -1, 13784, 13819, 13818, -1, 13242, 13795, 13243, -1, 13240, 13795, 13242, -1, 13818, 13795, 13240, -1, 13786, 13792, 13785, -1, 13785, 13792, 13819, -1, 13818, 13798, 13795, -1, 13819, 13798, 13818, -1, 13787, 13791, 13786, -1, 13786, 13791, 13792, -1, 13792, 13794, 13819, -1, 13819, 13794, 13798, -1, 13245, 13797, 13247, -1, 13243, 13797, 13245, -1, 13795, 13797, 13243, -1, 12389, 13800, 12390, -1, 12390, 13800, 13820, -1, 13820, 13805, 13821, -1, 13800, 13805, 13820, -1, 13821, 13809, 13822, -1, 13805, 13809, 13821, -1, 13822, 13812, 13823, -1, 13809, 13812, 13822, -1, 13823, 13815, 13824, -1, 13812, 13815, 13823, -1, 13824, 13816, 13825, -1, 13815, 13816, 13824, -1, 13825, 10383, 10308, -1, 13816, 10383, 13825, -1, 10307, 13825, 10308, -1, 10307, 13824, 13825, -1, 10307, 13823, 13824, -1, 13671, 13821, 13822, -1, 13671, 13820, 13821, -1, 13671, 12390, 13820, -1, 10545, 13826, 10291, -1, 10309, 13826, 10307, -1, 10291, 13826, 10309, -1, 10548, 13827, 10545, -1, 10545, 13827, 13826, -1, 13826, 13827, 10307, -1, 10549, 13828, 10548, -1, 13827, 13828, 10307, -1, 10548, 13828, 13827, -1, 10307, 13828, 13823, -1, 10551, 13829, 10549, -1, 10553, 13829, 10551, -1, 13823, 13829, 13822, -1, 13828, 13829, 13823, -1, 13822, 13829, 13671, -1, 10549, 13829, 13828, -1, 13829, 13830, 13671, -1, 10553, 13830, 13829, -1, 13669, 13831, 10472, -1, 13671, 13831, 13669, -1, 10555, 13831, 10553, -1, 10472, 13831, 10555, -1, 10553, 13831, 13830, -1, 13830, 13831, 13671, -1, 12696, 10560, 12694, -1, 10560, 10558, 12694, -1, 13832, 10081, 10564, -1, 10558, 10407, 12694, -1, 13832, 13833, 10081, -1, 13833, 10082, 10081, -1, 13833, 10086, 10082, -1, 13833, 10088, 10086, -1, 12670, 13834, 12698, -1, 10560, 13835, 10562, -1, 12698, 13835, 12696, -1, 12696, 13835, 10560, -1, 13834, 13835, 12698, -1, 10562, 13836, 10564, -1, 13837, 13836, 12670, -1, 13832, 13836, 13837, -1, 13834, 13836, 13835, -1, 13835, 13836, 10562, -1, 10564, 13836, 13832, -1, 12670, 13836, 13834, -1, 10088, 13833, 10411, -1, 13838, 13833, 13839, -1, 10411, 13833, 13838, -1, 13839, 13832, 13840, -1, 13833, 13832, 13839, -1, 13840, 13837, 12668, -1, 13832, 13837, 13840, -1, 13837, 12670, 12668, -1, 13841, 12669, 12671, -1, 13842, 12669, 13841, -1, 13843, 12669, 13842, -1, 13844, 12669, 13843, -1, 11667, 13590, 13845, -1, 12669, 13846, 12667, -1, 12669, 13847, 13846, -1, 13844, 13847, 12669, -1, 13845, 13848, 13844, -1, 13844, 13848, 13847, -1, 13590, 13848, 13845, -1, 12667, 13849, 12668, -1, 12668, 13849, 13840, -1, 13840, 13850, 13839, -1, 12667, 13850, 13849, -1, 13846, 13850, 12667, -1, 13849, 13850, 13840, -1, 13839, 13851, 13838, -1, 13846, 13851, 13850, -1, 13847, 13851, 13846, -1, 13850, 13851, 13839, -1, 13588, 13852, 13590, -1, 10411, 13852, 13588, -1, 13838, 13852, 10411, -1, 13848, 13852, 13847, -1, 13847, 13852, 13851, -1, 13851, 13852, 13838, -1, 13590, 13852, 13848, -1, 11667, 13845, 11665, -1, 11665, 13845, 13853, -1, 13853, 13844, 13854, -1, 13845, 13844, 13853, -1, 13854, 13843, 13855, -1, 13844, 13843, 13854, -1, 13855, 13842, 13856, -1, 13843, 13842, 13855, -1, 13856, 13841, 13857, -1, 13842, 13841, 13856, -1, 13857, 12671, 12672, -1, 13841, 12671, 13857, -1, 13858, 13859, 13860, -1, 11670, 13861, 11669, -1, 11669, 13861, 13862, -1, 13859, 13861, 13853, -1, 13862, 13861, 13863, -1, 13853, 13861, 11670, -1, 13863, 13861, 13859, -1, 13864, 12692, 12655, -1, 9227, 11668, 9224, -1, 11670, 11665, 13853, -1, 12692, 13865, 12689, -1, 13864, 13865, 12692, -1, 13866, 13867, 13864, -1, 13868, 13867, 13866, -1, 13864, 13867, 13865, -1, 13868, 13869, 13867, -1, 12689, 13870, 12672, -1, 12672, 13870, 13857, -1, 13865, 13870, 12689, -1, 13871, 13858, 13868, -1, 13868, 13858, 13869, -1, 13857, 13872, 13856, -1, 13867, 13872, 13865, -1, 13870, 13872, 13857, -1, 13865, 13872, 13870, -1, 9222, 13863, 9220, -1, 9220, 13863, 13871, -1, 13871, 13863, 13858, -1, 13856, 13873, 13855, -1, 13872, 13873, 13856, -1, 13867, 13873, 13872, -1, 13869, 13873, 13867, -1, 11669, 13862, 11668, -1, 9224, 13862, 9222, -1, 9222, 13862, 13863, -1, 11668, 13862, 9224, -1, 13855, 13860, 13854, -1, 13858, 13860, 13869, -1, 13869, 13860, 13873, -1, 13873, 13860, 13855, -1, 13854, 13859, 13853, -1, 13863, 13859, 13858, -1, 13860, 13859, 13854, -1, 9913, 9915, 12655, -1, 12655, 9915, 13864, -1, 13864, 9917, 13866, -1, 9915, 9917, 13864, -1, 13866, 9918, 13868, -1, 9917, 9918, 13866, -1, 13868, 9910, 13871, -1, 9918, 9910, 13868, -1, 13871, 9912, 9220, -1, 9910, 9912, 13871, -1, 9912, 9221, 9220, -1, 13651, 9217, 9219, -1, 13651, 9215, 9217, -1, 10242, 13874, 13875, -1, 10242, 10240, 13874, -1, 10078, 13876, 10080, -1, 13649, 13876, 13651, -1, 10080, 13876, 13649, -1, 10074, 13877, 10078, -1, 10078, 13877, 13876, -1, 13876, 13877, 13651, -1, 10073, 13878, 10074, -1, 13877, 13878, 13651, -1, 10074, 13878, 13877, -1, 10573, 13879, 10073, -1, 10073, 13879, 13878, -1, 10571, 13880, 10573, -1, 10573, 13880, 13879, -1, 10567, 13881, 10569, -1, 10569, 13881, 10571, -1, 10571, 13881, 13880, -1, 10393, 13882, 10225, -1, 10242, 13882, 10393, -1, 10225, 13882, 10567, -1, 13881, 13882, 10242, -1, 10567, 13882, 13881, -1, 9215, 13883, 9214, -1, 13884, 13883, 13875, -1, 13885, 13883, 13884, -1, 9214, 13883, 13885, -1, 13879, 13883, 13878, -1, 13881, 13883, 13880, -1, 10242, 13883, 13881, -1, 13651, 13883, 9215, -1, 13880, 13883, 13879, -1, 13875, 13883, 10242, -1, 13878, 13883, 13651, -1, 10240, 10330, 13874, -1, 13874, 13886, 13875, -1, 10330, 13886, 13874, -1, 13875, 13887, 13884, -1, 13886, 13887, 13875, -1, 13884, 13888, 13885, -1, 13887, 13888, 13884, -1, 13885, 13889, 9214, -1, 13888, 13889, 13885, -1, 13889, 9212, 9214, -1, 13890, 13891, 9180, -1, 13892, 13891, 13890, -1, 13893, 13891, 13892, -1, 13888, 13894, 13889, -1, 9216, 13275, 9218, -1, 13889, 13894, 13895, -1, 13895, 13896, 13897, -1, 13897, 13896, 13898, -1, 9203, 13899, 9206, -1, 13898, 13899, 13893, -1, 13893, 13899, 13891, -1, 13891, 13899, 9203, -1, 13887, 13900, 13888, -1, 13888, 13900, 13894, -1, 13895, 13901, 13896, -1, 13894, 13901, 13895, -1, 9206, 13902, 9211, -1, 13898, 13902, 13899, -1, 13899, 13902, 9206, -1, 13896, 13902, 13898, -1, 10332, 13903, 10330, -1, 10330, 13903, 13886, -1, 13886, 13903, 13887, -1, 13887, 13903, 13900, -1, 13282, 9180, 9179, -1, 13900, 13904, 13894, -1, 13894, 13904, 13901, -1, 9211, 13905, 9187, -1, 13902, 13905, 9211, -1, 13901, 13905, 13896, -1, 13896, 13905, 13902, -1, 10333, 13906, 10332, -1, 10334, 13906, 10333, -1, 10332, 13906, 13903, -1, 13903, 13906, 13900, -1, 13900, 13906, 13904, -1, 9187, 13907, 9186, -1, 13905, 13907, 9187, -1, 13904, 13907, 13901, -1, 13901, 13907, 13905, -1, 10334, 13908, 13906, -1, 10335, 13908, 10334, -1, 13904, 13908, 13907, -1, 13907, 13908, 9186, -1, 9186, 13908, 10335, -1, 13906, 13908, 13904, -1, 10335, 9185, 9186, -1, 13275, 13909, 13277, -1, 9216, 13909, 13275, -1, 9213, 13910, 9216, -1, 9216, 13910, 13909, -1, 13277, 13892, 13279, -1, 13909, 13892, 13277, -1, 9212, 13897, 9213, -1, 9213, 13897, 13910, -1, 13909, 13893, 13892, -1, 13910, 13893, 13909, -1, 13889, 13895, 9212, -1, 9212, 13895, 13897, -1, 13279, 13890, 13282, -1, 13282, 13890, 9180, -1, 13892, 13890, 13279, -1, 13897, 13898, 13910, -1, 13910, 13898, 13893, -1, 9180, 13891, 9203, -1, 10391, 13911, 9199, -1, 9199, 13911, 9197, -1, 9197, 13912, 9195, -1, 13911, 13912, 9197, -1, 9195, 13913, 9191, -1, 13912, 13913, 9195, -1, 9191, 13914, 9177, -1, 13913, 13914, 9191, -1, 9177, 13915, 9175, -1, 13914, 13915, 9177, -1, 9175, 13916, 9209, -1, 13915, 13916, 9175, -1, 9209, 12397, 9207, -1, 13916, 12397, 9209, -1, 13917, 13918, 13271, -1, 13912, 13919, 13913, -1, 13913, 13919, 13920, -1, 13921, 13922, 13923, -1, 13920, 13922, 13921, -1, 13917, 13924, 13918, -1, 13925, 13924, 13917, -1, 13267, 13926, 13927, -1, 13918, 13926, 13267, -1, 10380, 13928, 10391, -1, 10377, 13928, 10380, -1, 10391, 13928, 13911, -1, 13911, 13928, 13912, -1, 13912, 13928, 13919, -1, 13920, 13929, 13922, -1, 13919, 13929, 13920, -1, 13923, 13930, 13925, -1, 13925, 13930, 13924, -1, 13267, 13927, 11684, -1, 13927, 13931, 13932, -1, 13924, 13931, 13918, -1, 13926, 13931, 13927, -1, 13918, 13931, 13926, -1, 10373, 13933, 10377, -1, 10377, 13933, 13928, -1, 13928, 13933, 13919, -1, 13919, 13933, 13929, -1, 13922, 13934, 13923, -1, 13923, 13934, 13930, -1, 13932, 13935, 13936, -1, 13930, 13935, 13924, -1, 13924, 13935, 13931, -1, 13931, 13935, 13932, -1, 13922, 13937, 13934, -1, 13929, 13937, 13922, -1, 13934, 13938, 13930, -1, 13936, 13938, 13939, -1, 13930, 13938, 13935, -1, 13935, 13938, 13936, -1, 13929, 13940, 13937, -1, 10374, 13940, 10373, -1, 10373, 13940, 13933, -1, 13933, 13940, 13929, -1, 13937, 13941, 13934, -1, 13939, 13941, 13942, -1, 13938, 13941, 13939, -1, 13934, 13941, 13938, -1, 10370, 10358, 13943, -1, 13942, 13944, 13943, -1, 10370, 13944, 10374, -1, 13937, 13944, 13941, -1, 12397, 13945, 13274, -1, 10374, 13944, 13940, -1, 13943, 13944, 10370, -1, 13940, 13944, 13937, -1, 13941, 13944, 13942, -1, 13916, 13945, 12397, -1, 13915, 13946, 13916, -1, 13916, 13946, 13945, -1, 13273, 13917, 13271, -1, 13274, 13917, 13273, -1, 13945, 13917, 13274, -1, 13914, 13921, 13915, -1, 13915, 13921, 13946, -1, 13945, 13925, 13917, -1, 13946, 13925, 13945, -1, 13913, 13920, 13914, -1, 13914, 13920, 13921, -1, 13921, 13923, 13946, -1, 13946, 13923, 13925, -1, 13269, 13918, 13267, -1, 13271, 13918, 13269, -1, 11685, 11684, 13947, -1, 13947, 13927, 13948, -1, 11684, 13927, 13947, -1, 13948, 13932, 13949, -1, 13927, 13932, 13948, -1, 13949, 13936, 13950, -1, 13932, 13936, 13949, -1, 13950, 13939, 13951, -1, 13936, 13939, 13950, -1, 13951, 13942, 13952, -1, 13939, 13942, 13951, -1, 13952, 13943, 10352, -1, 13942, 13943, 13952, -1, 13943, 10358, 10352, -1, 11685, 13947, 13953, -1, 13952, 10352, 12675, -1, 13948, 13954, 13947, -1, 13953, 13954, 13955, -1, 13947, 13954, 13953, -1, 13956, 13957, 13958, -1, 13949, 13959, 13948, -1, 13955, 13959, 13956, -1, 13956, 13959, 13957, -1, 13954, 13959, 13955, -1, 13948, 13959, 13954, -1, 13958, 13960, 12665, -1, 12679, 13960, 12677, -1, 12665, 13960, 12679, -1, 13957, 13960, 13958, -1, 13951, 13961, 13950, -1, 13950, 13961, 13949, -1, 13957, 13961, 13960, -1, 13949, 13961, 13959, -1, 13959, 13961, 13957, -1, 13952, 13962, 13951, -1, 12677, 13962, 12675, -1, 13951, 13962, 13961, -1, 13961, 13962, 13960, -1, 13960, 13962, 12677, -1, 12675, 13962, 13952, -1, 11685, 13953, 11683, -1, 11683, 13953, 13963, -1, 13963, 13955, 13964, -1, 13953, 13955, 13963, -1, 13964, 13956, 13965, -1, 13955, 13956, 13964, -1, 13965, 13958, 13966, -1, 13956, 13958, 13965, -1, 13966, 12665, 12664, -1, 13958, 12665, 13966, -1, 11682, 13967, 11681, -1, 11681, 13967, 13968, -1, 13968, 13967, 13969, -1, 13969, 13967, 13970, -1, 13971, 13972, 13964, -1, 12663, 13973, 12687, -1, 13974, 13972, 13971, -1, 13970, 13972, 13974, -1, 11686, 13975, 11682, -1, 13964, 13975, 13963, -1, 13972, 13975, 13964, -1, 11682, 13975, 13967, -1, 13963, 13975, 11686, -1, 13967, 13975, 13970, -1, 13970, 13975, 13972, -1, 11679, 11681, 13976, -1, 11686, 11683, 13963, -1, 12687, 13977, 12686, -1, 13973, 13977, 12687, -1, 13978, 13979, 13973, -1, 13973, 13979, 13977, -1, 12684, 13980, 12682, -1, 12686, 13980, 12684, -1, 13977, 13980, 12686, -1, 13981, 13982, 13978, -1, 13983, 13982, 13981, -1, 13978, 13982, 13979, -1, 13979, 13984, 13977, -1, 13977, 13984, 13980, -1, 13985, 13969, 13983, -1, 13983, 13969, 13982, -1, 12682, 13986, 12664, -1, 12664, 13986, 13966, -1, 13980, 13986, 12682, -1, 13979, 13974, 13984, -1, 13982, 13974, 13979, -1, 13976, 13968, 13985, -1, 13985, 13968, 13969, -1, 11681, 13968, 13976, -1, 13966, 13987, 13965, -1, 13980, 13987, 13986, -1, 13984, 13987, 13980, -1, 13986, 13987, 13966, -1, 13969, 13970, 13982, -1, 13982, 13970, 13974, -1, 13965, 13971, 13964, -1, 13974, 13971, 13984, -1, 13987, 13971, 13965, -1, 13984, 13971, 13987, -1, 12660, 13988, 12663, -1, 12663, 13988, 13973, -1, 13973, 13989, 13978, -1, 13988, 13989, 13973, -1, 13978, 13990, 13981, -1, 13989, 13990, 13978, -1, 13981, 13991, 13983, -1, 13990, 13991, 13981, -1, 13983, 13992, 13985, -1, 13991, 13992, 13983, -1, 13985, 13993, 13976, -1, 13992, 13993, 13985, -1, 13976, 11678, 11679, -1, 13993, 11678, 13976, -1, 13994, 12693, 12691, -1, 12693, 13988, 12660, -1, 13994, 13988, 12693, -1, 13995, 13989, 13994, -1, 13994, 13989, 13988, -1, 13996, 13990, 13995, -1, 13995, 13990, 13989, -1, 13997, 13991, 13996, -1, 13998, 13991, 13997, -1, 13996, 13991, 13990, -1, 13999, 13992, 13998, -1, 13998, 13992, 13991, -1, 11676, 11675, 13999, -1, 11675, 13993, 13999, -1, 13999, 13993, 13992, -1, 11675, 11677, 13993, -1, 11677, 11678, 13993, -1, 14000, 12688, 12674, -1, 12690, 13994, 12691, -1, 13584, 13586, 14001, -1, 13587, 11676, 13999, -1, 12688, 14002, 12690, -1, 14000, 14002, 12688, -1, 12690, 14002, 13994, -1, 14003, 14004, 14000, -1, 13994, 14004, 13995, -1, 14002, 14004, 13994, -1, 14000, 14004, 14002, -1, 14005, 14006, 14003, -1, 13995, 14006, 13996, -1, 14004, 14006, 13995, -1, 14003, 14006, 14004, -1, 14007, 14008, 14005, -1, 14009, 14008, 14007, -1, 13996, 14008, 13997, -1, 14006, 14008, 13996, -1, 14005, 14008, 14006, -1, 14010, 14011, 14009, -1, 14008, 14011, 13997, -1, 14009, 14011, 14008, -1, 14012, 14013, 14010, -1, 13997, 14013, 13998, -1, 14011, 14013, 13997, -1, 14010, 14013, 14011, -1, 13587, 14014, 13586, -1, 14001, 14014, 14012, -1, 13998, 14014, 13999, -1, 13586, 14014, 14001, -1, 14013, 14014, 13998, -1, 14012, 14014, 14013, -1, 13999, 14014, 13587, -1, 14000, 14015, 14003, -1, 14003, 14015, 14016, -1, 14016, 14015, 14017, -1, 14001, 13582, 13584, -1, 13582, 14018, 10416, -1, 10416, 14018, 14019, -1, 14001, 14018, 13582, -1, 14019, 14020, 14021, -1, 14012, 14020, 14001, -1, 14018, 14020, 14019, -1, 14001, 14020, 14018, -1, 14021, 14022, 14023, -1, 14009, 14022, 14010, -1, 14010, 14022, 14012, -1, 14012, 14022, 14020, -1, 14020, 14022, 14021, -1, 14023, 14024, 14025, -1, 14009, 14024, 14022, -1, 14022, 14024, 14023, -1, 14025, 14026, 14027, -1, 14007, 14026, 14009, -1, 14024, 14026, 14025, -1, 14009, 14026, 14024, -1, 14027, 14028, 14029, -1, 14005, 14028, 14007, -1, 14026, 14028, 14027, -1, 14007, 14028, 14026, -1, 14030, 14016, 14017, -1, 14029, 14016, 14030, -1, 14003, 14016, 14005, -1, 14005, 14016, 14028, -1, 14028, 14016, 14029, -1, 14017, 14015, 12673, -1, 12673, 14015, 12674, -1, 12674, 14015, 14000, -1, 10417, 10416, 14031, -1, 14031, 14019, 14032, -1, 10416, 14019, 14031, -1, 14032, 14021, 14033, -1, 14019, 14021, 14032, -1, 14033, 14023, 14034, -1, 14021, 14023, 14033, -1, 14034, 14025, 14035, -1, 14023, 14025, 14034, -1, 14035, 14027, 14036, -1, 14025, 14027, 14035, -1, 14036, 14029, 14037, -1, 14027, 14029, 14036, -1, 14037, 14030, 14038, -1, 14029, 14030, 14037, -1, 14038, 14017, 14039, -1, 14030, 14017, 14038, -1, 14039, 12673, 12666, -1, 14017, 12673, 14039, -1, 14040, 14041, 14037, -1, 14037, 14041, 14036, -1, 14042, 14041, 14043, -1, 14036, 14041, 14042, -1, 14034, 14044, 14033, -1, 14033, 14044, 14032, -1, 10583, 14044, 10581, -1, 10585, 14044, 10583, -1, 10581, 14044, 14045, -1, 14046, 14044, 14034, -1, 14032, 14044, 10585, -1, 14045, 14044, 14046, -1, 14039, 12666, 12699, -1, 10410, 14043, 12695, -1, 10585, 10587, 14032, -1, 10587, 14031, 14032, -1, 10587, 10417, 14031, -1, 14038, 14047, 14037, -1, 14040, 14047, 14043, -1, 14037, 14047, 14040, -1, 14039, 14048, 14038, -1, 14038, 14048, 14047, -1, 14047, 14048, 14043, -1, 12699, 14049, 14039, -1, 14043, 14049, 12695, -1, 14048, 14049, 14043, -1, 14039, 14049, 14048, -1, 12697, 14050, 12699, -1, 12695, 14050, 12697, -1, 14049, 14050, 12695, -1, 12699, 14050, 14049, -1, 10577, 14051, 10410, -1, 10580, 14051, 10577, -1, 10410, 14051, 14043, -1, 10580, 14052, 14051, -1, 14051, 14052, 14043, -1, 14052, 14053, 14043, -1, 14053, 14054, 14043, -1, 10581, 14045, 10580, -1, 14052, 14045, 14053, -1, 10580, 14045, 14052, -1, 14036, 14042, 14035, -1, 14054, 14042, 14043, -1, 14035, 14042, 14054, -1, 14035, 14046, 14034, -1, 14053, 14046, 14054, -1, 14054, 14046, 14035, -1, 14045, 14046, 14053, -1, 14043, 14041, 14040, -1, 14055, 12002, 12001, -1, 14056, 14055, 12001, -1, 14057, 12001, 12055, -1, 14057, 14056, 12001, -1, 14058, 14057, 12055, -1, 14059, 14058, 12055, -1, 12057, 14059, 12055, -1, 14060, 12484, 12477, -1, 14060, 12477, 14061, -1, 14062, 14061, 14063, -1, 14062, 14060, 14061, -1, 14064, 14063, 14065, -1, 14064, 14062, 14063, -1, 14066, 14065, 14067, -1, 14066, 14064, 14065, -1, 14068, 14066, 14067, -1, 14069, 14067, 14070, -1, 14069, 14068, 14067, -1, 14071, 14070, 14072, -1, 14071, 14069, 14070, -1, 14073, 14071, 14072, -1, 12654, 14072, 12089, -1, 12654, 14073, 14072, -1, 12081, 12654, 12089, -1, 14074, 14061, 12477, -1, 14074, 12477, 13181, -1, 14075, 14063, 14061, -1, 14075, 14061, 14074, -1, 14076, 14065, 14063, -1, 14076, 14067, 14065, -1, 14076, 14063, 14075, -1, 14077, 14070, 14067, -1, 14077, 14067, 14076, -1, 14078, 14072, 14070, -1, 14078, 14070, 14077, -1, 14079, 12089, 14072, -1, 14079, 14072, 14078, -1, 9258, 12089, 14079, -1, 14080, 14081, 9255, -1, 14082, 14083, 14084, -1, 14082, 14084, 14085, -1, 14086, 13183, 13185, -1, 14086, 14087, 13183, -1, 14088, 14083, 14082, -1, 14088, 14089, 14083, -1, 14090, 14087, 14086, -1, 14090, 14085, 14087, -1, 14091, 14089, 14088, -1, 14091, 14081, 14089, -1, 14091, 9255, 14081, -1, 14092, 14082, 14085, -1, 9256, 9258, 14079, -1, 14092, 14085, 14090, -1, 14093, 9254, 9255, -1, 14093, 9255, 14091, -1, 14094, 14082, 14092, -1, 14094, 14088, 14082, -1, 14095, 13185, 13186, -1, 14095, 14086, 13185, -1, 14096, 14091, 14088, -1, 14096, 14088, 14094, -1, 14097, 14086, 14095, -1, 14097, 14090, 14086, -1, 14098, 13573, 13574, -1, 14098, 13574, 9254, -1, 14098, 14091, 14096, -1, 14098, 9254, 14093, -1, 14099, 13188, 12474, -1, 14098, 14093, 14091, -1, 14100, 13186, 13188, -1, 14100, 14095, 13186, -1, 14101, 14090, 14097, -1, 14102, 13188, 14099, -1, 14101, 14092, 14090, -1, 14103, 14097, 14095, -1, 14103, 14095, 14100, -1, 14103, 14100, 13188, -1, 14104, 14092, 14101, -1, 14105, 13570, 14106, -1, 14104, 14094, 14092, -1, 13569, 13570, 14105, -1, 14107, 14097, 14103, -1, 14108, 14074, 13181, -1, 14107, 14102, 14109, -1, 14107, 14103, 13188, -1, 14108, 13181, 13182, -1, 14108, 13182, 13183, -1, 14107, 14101, 14097, -1, 14107, 13188, 14102, -1, 14084, 14075, 14074, -1, 14110, 14096, 14094, -1, 14110, 14094, 14104, -1, 14084, 14074, 14108, -1, 14111, 14109, 14106, -1, 14083, 14076, 14075, -1, 14111, 14107, 14109, -1, 14111, 14101, 14107, -1, 14111, 14104, 14101, -1, 14083, 14075, 14084, -1, 14112, 13573, 14098, -1, 14112, 13571, 13572, -1, 14112, 14096, 14110, -1, 14089, 14077, 14076, -1, 14112, 13572, 13573, -1, 14112, 14098, 14096, -1, 14113, 14110, 14104, -1, 14089, 14076, 14083, -1, 14113, 14104, 14111, -1, 14113, 14111, 14106, -1, 14113, 14106, 13570, -1, 14114, 13571, 14112, -1, 14087, 14108, 13183, -1, 14114, 13570, 13571, -1, 14114, 14112, 14110, -1, 14114, 14110, 14113, -1, 14114, 14113, 13570, -1, 14081, 14078, 14077, -1, 14081, 14077, 14089, -1, 14085, 14108, 14087, -1, 14085, 14084, 14108, -1, 14080, 14079, 14078, -1, 14080, 9255, 9256, -1, 14080, 9256, 14079, -1, 14080, 14078, 14081, -1, 13568, 13569, 14105, -1, 14115, 14099, 12474, -1, 14115, 12474, 12473, -1, 14115, 12473, 12472, -1, 14116, 14102, 14099, -1, 14116, 14099, 14115, -1, 14117, 12472, 12469, -1, 14117, 12469, 14118, -1, 14117, 14115, 12472, -1, 14119, 14109, 14102, -1, 14119, 14102, 14116, -1, 14120, 14118, 14121, -1, 14120, 14116, 14115, -1, 14120, 14117, 14118, -1, 14120, 14115, 14117, -1, 14122, 14106, 14109, -1, 14122, 14109, 14119, -1, 14123, 14121, 14124, -1, 14123, 14124, 14125, -1, 14123, 14119, 14116, -1, 14123, 14116, 14120, -1, 14123, 14120, 14121, -1, 14126, 14105, 14106, -1, 14126, 14106, 14122, -1, 14127, 14123, 14125, -1, 14127, 14119, 14123, -1, 14127, 14122, 14119, -1, 14128, 13567, 13568, -1, 14128, 14105, 14126, -1, 14128, 13568, 14105, -1, 14129, 14125, 14130, -1, 14129, 14122, 14127, -1, 14129, 14126, 14122, -1, 14129, 14127, 14125, -1, 14131, 14130, 14132, -1, 14131, 14132, 12218, -1, 14131, 12218, 13567, -1, 14131, 13567, 14128, -1, 14131, 14128, 14126, -1, 14131, 14129, 14130, -1, 14131, 14126, 14129, -1, 12469, 12471, 14133, -1, 14118, 14133, 14134, -1, 14118, 12469, 14133, -1, 14121, 14134, 14135, -1, 14121, 14118, 14134, -1, 14124, 14135, 14136, -1, 14124, 14121, 14135, -1, 14125, 14136, 14137, -1, 14125, 14124, 14136, -1, 14130, 14125, 14137, -1, 14132, 14137, 14138, -1, 14132, 14130, 14137, -1, 12218, 14138, 12182, -1, 12218, 14132, 14138, -1, 14139, 14140, 14141, -1, 14139, 14142, 14140, -1, 14143, 9168, 9169, -1, 14143, 9169, 14144, -1, 14143, 14144, 14145, -1, 14146, 12182, 14138, -1, 14146, 12180, 12182, -1, 14146, 14141, 12180, -1, 14147, 14145, 14148, -1, 14147, 14148, 14149, -1, 14150, 14149, 14142, -1, 14150, 14142, 14139, -1, 14151, 9166, 9168, -1, 14151, 9168, 14143, -1, 14151, 13204, 9166, -1, 14152, 14138, 14137, -1, 14152, 14146, 14138, -1, 14152, 14139, 14141, -1, 14152, 14141, 14146, -1, 14153, 14143, 14145, -1, 14153, 14145, 14147, -1, 14154, 14149, 14150, -1, 14154, 14147, 14149, -1, 13204, 9163, 9166, -1, 14155, 14137, 14136, -1, 14155, 14150, 14139, -1, 14155, 14152, 14137, -1, 14155, 14139, 14152, -1, 14156, 13202, 13204, -1, 14156, 13204, 14151, -1, 14156, 14143, 14153, -1, 14156, 14151, 14143, -1, 14157, 14153, 14147, -1, 14157, 14147, 14154, -1, 14158, 14136, 14135, -1, 14158, 14155, 14136, -1, 14158, 14150, 14155, -1, 14158, 14154, 14150, -1, 14159, 14156, 14153, -1, 14159, 13200, 13202, -1, 14159, 14153, 14157, -1, 14159, 13202, 14156, -1, 14160, 14158, 14135, -1, 14160, 14135, 14134, -1, 14160, 14157, 14154, -1, 14160, 14154, 14158, -1, 14161, 14134, 14133, -1, 14161, 13198, 13200, -1, 14161, 13200, 14159, -1, 14161, 14159, 14157, -1, 14161, 14160, 14134, -1, 14161, 14133, 13198, -1, 12471, 13198, 14133, -1, 14161, 14157, 14160, -1, 14162, 14163, 12181, -1, 14162, 12181, 12178, -1, 14162, 12178, 12177, -1, 14164, 14165, 14163, -1, 14164, 14163, 14162, -1, 14140, 12177, 12179, -1, 14140, 14162, 12177, -1, 14148, 14166, 14165, -1, 14148, 14165, 14164, -1, 14142, 14164, 14162, -1, 14142, 14162, 14140, -1, 14141, 12179, 12180, -1, 14141, 14140, 12179, -1, 14145, 14144, 14166, -1, 14145, 14166, 14148, -1, 14149, 14148, 14164, -1, 14149, 14164, 14142, -1, 14144, 9169, 9170, -1, 14144, 9170, 14167, -1, 14166, 14167, 14168, -1, 14166, 14144, 14167, -1, 14165, 14168, 14169, -1, 14165, 14166, 14168, -1, 14163, 14169, 14170, -1, 14163, 14165, 14169, -1, 12181, 14170, 12189, -1, 12181, 14163, 14170, -1, 14171, 14172, 14173, -1, 14174, 14175, 13155, -1, 14176, 14175, 14174, -1, 14177, 14178, 14179, -1, 14177, 14179, 14171, -1, 14176, 14180, 14175, -1, 14181, 13166, 13170, -1, 14182, 12190, 12192, -1, 14182, 12192, 14170, -1, 14182, 14170, 14183, -1, 14182, 14183, 12190, -1, 9262, 9165, 9164, -1, 14184, 14185, 14180, -1, 14184, 14180, 14176, -1, 14186, 14187, 13166, -1, 14186, 14181, 13170, -1, 14186, 13166, 14181, -1, 14188, 14189, 14185, -1, 14188, 14185, 14184, -1, 14190, 14191, 14178, -1, 14190, 12195, 14191, -1, 14190, 14178, 14177, -1, 14192, 14189, 14188, -1, 14192, 14193, 14189, -1, 14194, 14187, 14186, -1, 14194, 14195, 14187, -1, 14196, 14183, 14193, -1, 14196, 14193, 14192, -1, 14196, 12190, 14183, -1, 14197, 13155, 13158, -1, 14198, 12194, 12195, -1, 14198, 12195, 14190, -1, 14197, 14174, 13155, -1, 12192, 12189, 14170, -1, 14199, 14173, 14195, -1, 14200, 12197, 12190, -1, 14200, 12190, 14196, -1, 14200, 14196, 12197, -1, 14199, 14195, 14194, -1, 14201, 14174, 14197, -1, 14202, 12224, 12223, -1, 14202, 14171, 14173, -1, 14201, 14176, 14174, -1, 14202, 14173, 14199, -1, 14203, 14176, 14201, -1, 14204, 12223, 12221, -1, 14204, 14171, 14202, -1, 14204, 14177, 14171, -1, 14203, 14184, 14176, -1, 14204, 14202, 12223, -1, 14205, 12221, 12222, -1, 14206, 14184, 14203, -1, 14205, 14190, 14177, -1, 14205, 14204, 12221, -1, 14205, 14177, 14204, -1, 14206, 14188, 14184, -1, 14207, 12227, 12228, -1, 14207, 12228, 12225, -1, 14207, 14194, 14186, -1, 14207, 14186, 13170, -1, 14208, 14188, 14206, -1, 14207, 13170, 12227, -1, 14208, 14192, 14188, -1, 14209, 12222, 12191, -1, 14209, 12191, 12193, -1, 14209, 12193, 12194, -1, 14209, 12194, 14198, -1, 14209, 14198, 14190, -1, 14210, 14192, 14208, -1, 14209, 14205, 12222, -1, 14210, 14196, 14192, -1, 14209, 14190, 14205, -1, 14210, 12197, 14196, -1, 14211, 12225, 12224, -1, 14211, 14194, 14207, -1, 14211, 14199, 14194, -1, 14212, 13158, 13162, -1, 14211, 12224, 14202, -1, 14211, 14202, 14199, -1, 12227, 13170, 12226, -1, 14211, 14207, 12225, -1, 14212, 14197, 13158, -1, 14213, 14210, 12196, -1, 14213, 12196, 12197, -1, 14213, 12197, 14210, -1, 14214, 14197, 14212, -1, 14214, 14201, 14197, -1, 14215, 14201, 14214, -1, 14215, 14203, 14201, -1, 14172, 14203, 14215, -1, 14172, 14206, 14203, -1, 14179, 14206, 14172, -1, 14179, 14208, 14206, -1, 14178, 12196, 14210, -1, 14175, 9167, 9165, -1, 14178, 14210, 14208, -1, 14175, 9262, 13155, -1, 14178, 14208, 14179, -1, 14175, 9165, 9262, -1, 14216, 13162, 13166, -1, 14180, 9167, 14175, -1, 14216, 14212, 13162, -1, 14187, 14214, 14212, -1, 14185, 9170, 9167, -1, 14187, 14212, 14216, -1, 14185, 9167, 14180, -1, 14187, 14216, 13166, -1, 14189, 14167, 9170, -1, 14191, 12195, 12196, -1, 14191, 12196, 14178, -1, 14189, 9170, 14185, -1, 14195, 14215, 14214, -1, 14193, 14168, 14167, -1, 14195, 14214, 14187, -1, 14193, 14169, 14168, -1, 14193, 14167, 14189, -1, 14173, 14172, 14215, -1, 14173, 14215, 14195, -1, 14183, 14170, 14169, -1, 14183, 14169, 14193, -1, 14171, 14179, 14172, -1, 14217, 14218, 14219, -1, 14220, 14221, 9265, -1, 14217, 14219, 14222, -1, 14223, 14224, 14225, -1, 14226, 14227, 14218, -1, 14226, 14218, 14217, -1, 14223, 14225, 14228, -1, 14229, 14230, 14231, -1, 14232, 14227, 14226, -1, 14232, 14233, 14227, -1, 14234, 13173, 13169, -1, 14229, 14235, 14221, -1, 14229, 14220, 14230, -1, 14229, 14221, 14220, -1, 14236, 12308, 12311, -1, 14237, 12312, 14238, -1, 14236, 12311, 14239, -1, 14237, 14233, 14232, -1, 14236, 14223, 12308, -1, 14236, 14239, 14224, -1, 14237, 14238, 14233, -1, 14236, 14224, 14223, -1, 14240, 14231, 14241, -1, 14242, 14234, 13169, -1, 14242, 13173, 14234, -1, 14240, 14229, 14231, -1, 14240, 14243, 14235, -1, 14242, 14222, 13173, -1, 12309, 9160, 9158, -1, 14240, 14235, 14229, -1, 12309, 9161, 9160, -1, 14244, 14241, 14245, -1, 14246, 14217, 14222, -1, 14244, 14228, 14243, -1, 14246, 14222, 14242, -1, 14244, 14243, 14240, -1, 14244, 14240, 14241, -1, 14247, 14245, 14248, -1, 14249, 14217, 14246, -1, 14249, 14226, 14217, -1, 14247, 14244, 14245, -1, 14250, 14226, 14249, -1, 14247, 12308, 14223, -1, 14247, 14223, 14228, -1, 14247, 14228, 14244, -1, 14250, 14232, 14226, -1, 14251, 14248, 14252, -1, 14251, 14252, 12307, -1, 14251, 12307, 12308, -1, 14251, 12308, 14247, -1, 14253, 13169, 13165, -1, 14251, 14247, 14248, -1, 14254, 14232, 14250, -1, 14254, 12314, 12312, -1, 14254, 12312, 14237, -1, 14254, 14237, 14232, -1, 14255, 14253, 13165, -1, 14255, 14242, 13169, -1, 14255, 13169, 14253, -1, 14256, 14242, 14255, -1, 14256, 14246, 14242, -1, 14257, 14249, 14246, -1, 14257, 14246, 14256, -1, 14258, 14249, 14257, -1, 14258, 14250, 14249, -1, 14259, 13165, 13161, -1, 14260, 14254, 14250, -1, 14260, 12314, 14254, -1, 14260, 14250, 14258, -1, 14260, 12311, 12313, -1, 14260, 12313, 12314, -1, 14261, 13165, 14259, -1, 14261, 14255, 13165, -1, 14262, 14256, 14255, -1, 14262, 14255, 14261, -1, 14225, 14257, 14256, -1, 14263, 9152, 9151, -1, 14225, 14256, 14262, -1, 14263, 9151, 13176, -1, 14224, 14258, 14257, -1, 14219, 9154, 9152, -1, 14224, 14257, 14225, -1, 14221, 13161, 13157, -1, 14221, 13157, 9265, -1, 14219, 9152, 14263, -1, 14218, 9156, 9154, -1, 14221, 14259, 13161, -1, 14218, 9154, 14219, -1, 14239, 14260, 14258, -1, 14239, 12311, 14260, -1, 14227, 9158, 9156, -1, 14239, 14258, 14224, -1, 14227, 9156, 14218, -1, 14235, 14261, 14259, -1, 14233, 9158, 14227, -1, 14235, 14259, 14221, -1, 14233, 12309, 9158, -1, 14264, 13176, 13173, -1, 14264, 14263, 13176, -1, 14243, 14262, 14261, -1, 14238, 12312, 12310, -1, 14243, 14261, 14235, -1, 14238, 12310, 12309, -1, 14238, 12309, 14233, -1, 14222, 14264, 13173, -1, 14228, 14225, 14262, -1, 14222, 14263, 14264, -1, 14228, 14262, 14243, -1, 14220, 9265, 9264, -1, 14222, 14219, 14263, -1, 14220, 9264, 14230, -1, 14230, 9264, 12380, -1, 14230, 12380, 14265, -1, 14230, 14265, 14266, -1, 14231, 14266, 14267, -1, 14231, 14230, 14266, -1, 14241, 14267, 14268, -1, 14241, 14231, 14267, -1, 14245, 14268, 14269, -1, 14245, 14241, 14268, -1, 14248, 14269, 14270, -1, 14248, 14245, 14269, -1, 14252, 14270, 12299, -1, 14252, 14248, 14270, -1, 12307, 14252, 12299, -1, 14271, 14272, 13196, -1, 14273, 14274, 14275, -1, 14273, 14272, 14271, -1, 14273, 14276, 14272, -1, 14273, 14271, 14274, -1, 14277, 14273, 14275, -1, 14277, 14276, 14273, -1, 14277, 14275, 14278, -1, 14277, 14279, 14276, -1, 14280, 14279, 14277, -1, 14280, 14278, 14281, -1, 14280, 14277, 14278, -1, 14280, 12294, 14282, -1, 13190, 14265, 12380, -1, 14280, 14282, 14279, -1, 14283, 12294, 14280, -1, 14283, 14281, 14284, -1, 14283, 14284, 14285, -1, 14283, 14280, 14281, -1, 14286, 12294, 14283, -1, 14286, 14283, 14285, -1, 14286, 14285, 12285, -1, 14286, 12285, 12294, -1, 12298, 14267, 14266, -1, 12298, 14268, 14267, -1, 12298, 14269, 14268, -1, 12298, 14270, 14269, -1, 12298, 12299, 14270, -1, 14287, 14265, 13190, -1, 14288, 14266, 14265, -1, 14288, 14265, 14287, -1, 14288, 12298, 14266, -1, 14289, 14288, 12296, -1, 14289, 12298, 14288, -1, 14290, 14289, 12296, -1, 14290, 12298, 14289, -1, 14291, 14290, 12296, -1, 14291, 12298, 14290, -1, 14292, 12296, 12298, -1, 14292, 12298, 14291, -1, 14292, 14291, 12296, -1, 14293, 13190, 13192, -1, 14293, 13192, 13194, -1, 14293, 14287, 13190, -1, 14294, 12296, 14288, -1, 14294, 14288, 14287, -1, 14294, 14287, 14293, -1, 14295, 12296, 14294, -1, 14296, 12296, 14295, -1, 14296, 14295, 12293, -1, 14297, 14296, 12293, -1, 14297, 12296, 14296, -1, 14298, 12293, 12296, -1, 14298, 14297, 12293, -1, 14298, 12296, 14297, -1, 14272, 13194, 13196, -1, 14272, 14293, 13194, -1, 14276, 14294, 14293, -1, 14276, 14293, 14272, -1, 14279, 14295, 14294, -1, 14279, 12293, 14295, -1, 14279, 14294, 14276, -1, 14282, 12293, 14279, -1, 14299, 14282, 12294, -1, 14299, 12293, 14282, -1, 14300, 12294, 12293, -1, 14300, 14299, 12294, -1, 14300, 12293, 14299, -1, 14271, 13196, 10450, -1, 14271, 10450, 14274, -1, 14274, 10450, 10452, -1, 14274, 10452, 14301, -1, 14275, 14301, 14302, -1, 14275, 14274, 14301, -1, 14278, 14302, 14303, -1, 14278, 14275, 14302, -1, 14281, 14303, 14304, -1, 14281, 14278, 14303, -1, 14284, 14304, 14305, -1, 14284, 14281, 14304, -1, 14285, 14305, 14306, -1, 14285, 14284, 14305, -1, 12285, 14306, 12248, -1, 12285, 14285, 14306, -1, 14307, 14308, 14309, -1, 14307, 14309, 14310, -1, 14307, 10451, 14308, -1, 14311, 13577, 13578, -1, 14312, 14311, 13578, -1, 14312, 13577, 14311, -1, 14313, 14312, 13578, -1, 14313, 13577, 14312, -1, 14314, 13577, 14313, -1, 14314, 14313, 13578, -1, 14315, 10455, 10456, -1, 14315, 10456, 14307, -1, 14315, 14307, 13577, -1, 14315, 13578, 10455, -1, 14315, 13577, 14314, -1, 14315, 14314, 13578, -1, 14316, 13578, 13579, -1, 14317, 13578, 14316, -1, 14317, 14316, 13579, -1, 14318, 13578, 14317, -1, 14318, 14317, 13579, -1, 14319, 13578, 14318, -1, 14319, 14318, 13579, -1, 13575, 9130, 9129, -1, 14320, 13578, 14319, -1, 13575, 9133, 9130, -1, 14320, 14319, 13579, -1, 13575, 9135, 9133, -1, 14320, 13579, 10454, -1, 13575, 9138, 9135, -1, 14320, 10454, 13578, -1, 14321, 13579, 13580, -1, 14322, 13579, 14321, -1, 14322, 14321, 13580, -1, 14323, 13579, 14322, -1, 14323, 14322, 13580, -1, 10451, 9148, 9146, -1, 14324, 13579, 14323, -1, 14325, 13579, 14324, -1, 14326, 13579, 14325, -1, 14326, 10453, 13579, -1, 14327, 13580, 13581, -1, 14327, 13581, 12248, -1, 14327, 12248, 14306, -1, 14328, 14306, 14305, -1, 10454, 10455, 13578, -1, 14328, 13580, 14327, -1, 14328, 14327, 14306, -1, 10453, 10454, 13579, -1, 14329, 14305, 14304, -1, 14329, 14328, 14305, -1, 14329, 13580, 14328, -1, 14330, 14304, 14303, -1, 14330, 14323, 13580, -1, 14330, 13580, 14329, -1, 14330, 14329, 14304, -1, 14331, 14303, 14302, -1, 14331, 14330, 14303, -1, 14331, 14324, 14323, -1, 14331, 14323, 14330, -1, 14332, 14302, 14301, -1, 14332, 14325, 14324, -1, 14332, 14324, 14331, -1, 14332, 14331, 14302, -1, 14333, 14301, 10452, -1, 14333, 10452, 10453, -1, 14333, 14326, 14325, -1, 14333, 10453, 14326, -1, 14334, 13575, 13576, -1, 14333, 14325, 14332, -1, 14333, 14332, 14301, -1, 14335, 13575, 14334, -1, 14335, 14334, 13576, -1, 14336, 14335, 13576, -1, 14336, 9138, 13575, -1, 14336, 13575, 14335, -1, 14337, 9139, 9138, -1, 14337, 9138, 14336, -1, 14337, 14336, 13576, -1, 14309, 9142, 9139, -1, 14309, 14337, 13576, -1, 14309, 9139, 14337, -1, 14308, 9146, 9142, -1, 14308, 10451, 9146, -1, 14308, 9142, 14309, -1, 14338, 13576, 13577, -1, 14339, 14338, 13577, -1, 14339, 13576, 14338, -1, 14340, 14339, 13577, -1, 14340, 13576, 14339, -1, 14310, 14309, 13576, -1, 14310, 13576, 14340, -1, 14310, 14340, 13577, -1, 14307, 10456, 10451, -1, 14307, 14310, 13577, -1, 10462, 10465, 12487, -1, 13524, 12487, 12488, -1, 13524, 10462, 12487, -1, 14060, 14062, 12490, -1, 13525, 12488, 12489, -1, 13525, 13524, 12488, -1, 12484, 14060, 12490, -1, 13526, 12489, 12490, -1, 13526, 13525, 12489, -1, 13527, 14062, 14064, -1, 13527, 14064, 14066, -1, 13527, 12490, 14062, -1, 13527, 13526, 12490, -1, 13528, 14066, 14068, -1, 13528, 14068, 14069, -1, 13528, 13527, 14066, -1, 13529, 14069, 14071, -1, 13529, 13528, 14069, -1, 13530, 14071, 14073, -1, 13530, 13529, 14071, -1, 13531, 14073, 12654, -1, 13531, 13530, 14073, -1, 12652, 13531, 12654, -1, 14341, 14342, 14343, -1, 14343, 14342, 14344, -1, 14345, 14346, 14341, -1, 14341, 14346, 14342, -1, 14347, 12374, 14345, -1, 14345, 12374, 14346, -1, 14347, 14348, 12374, -1, 14348, 14349, 12374, -1, 14349, 13215, 12374, -1, 13215, 13217, 12374, -1, 13217, 13220, 12374, -1, 13220, 13221, 12374, -1, 13221, 13223, 12374, -1, 13223, 12019, 12374, -1, 12019, 12343, 12374, -1, 12343, 12627, 12630, -1, 12343, 12625, 12627, -1, 12019, 12017, 12343, -1, 12343, 12017, 12625, -1, 12625, 12017, 12519, -1, 12017, 12522, 12519, -1, 12017, 12013, 12522, -1, 13489, 12016, 10461, -1, 10461, 12016, 12014, -1, 13488, 12015, 13489, -1, 13489, 12015, 12016, -1, 12522, 12013, 13488, -1, 13488, 12013, 12015, -1, 10461, 12021, 10464, -1, 12014, 12021, 10461, -1, 10464, 12021, 12494, -1, 12023, 12494, 12021, -1, 12493, 12494, 12023, -1, 13545, 12492, 12023, -1, 12023, 12492, 12493, -1, 13547, 12491, 13545, -1, 13545, 12491, 12492, -1, 13549, 12486, 13547, -1, 13547, 12486, 12491, -1, 13551, 12485, 13549, -1, 13549, 12485, 12486, -1, 12116, 12483, 13551, -1, 13551, 12483, 12485, -1, 12123, 12483, 12116, -1, 12482, 12483, 12123, -1, 13553, 12481, 12123, -1, 12123, 12481, 12482, -1, 13555, 12480, 13553, -1, 13553, 12480, 12481, -1, 13557, 12479, 13555, -1, 13555, 12479, 12480, -1, 13559, 12478, 13557, -1, 13557, 12478, 12479, -1, 13561, 12476, 13559, -1, 13559, 12476, 12478, -1, 13187, 13566, 12475, -1, 13184, 13564, 13187, -1, 13187, 13564, 13566, -1, 12476, 13563, 13184, -1, 13184, 13563, 13564, -1, 12476, 13561, 13563, -1, 12142, 12470, 13566, -1, 13566, 12470, 12475, -1, 12468, 12142, 12161, -1, 12468, 12470, 12142, -1, 12468, 12161, 12167, -1, 13197, 12167, 12166, -1, 13197, 12468, 12167, -1, 13199, 12166, 12169, -1, 13199, 13197, 12166, -1, 13201, 12169, 12170, -1, 13201, 13199, 12169, -1, 13203, 12170, 12144, -1, 13203, 13201, 12170, -1, 12382, 13203, 12144, -1, 12137, 12382, 12144, -1, 9260, 12382, 12137, -1, 13177, 12154, 12045, -1, 12045, 12154, 12145, -1, 13174, 12153, 13177, -1, 13177, 12153, 12154, -1, 13171, 12151, 13174, -1, 13174, 12151, 12153, -1, 13167, 12152, 13171, -1, 13171, 12152, 12151, -1, 13163, 12157, 13167, -1, 13167, 12157, 12152, -1, 13159, 12160, 13163, -1, 13163, 12160, 12157, -1, 13156, 12158, 13159, -1, 13159, 12158, 12160, -1, 13154, 12156, 13156, -1, 13156, 12156, 12158, -1, 9261, 12149, 13154, -1, 13154, 12149, 12156, -1, 9260, 12137, 9261, -1, 9261, 12137, 12149, -1, 12035, 12145, 12146, -1, 12035, 12045, 12145, -1, 13565, 12034, 12146, -1, 12146, 12034, 12035, -1, 13562, 12033, 13565, -1, 13565, 12033, 12034, -1, 13560, 12032, 13562, -1, 13562, 12032, 12033, -1, 13558, 12031, 13560, -1, 13560, 12031, 12032, -1, 13556, 12030, 13558, -1, 13558, 12030, 12031, -1, 13554, 12029, 13556, -1, 13556, 12029, 12030, -1, 13552, 12027, 13554, -1, 13554, 12027, 12029, -1, 12112, 12028, 13552, -1, 13552, 12028, 12027, -1, 12047, 12112, 12121, -1, 12047, 12028, 12112, -1, 13550, 12048, 12121, -1, 12121, 12048, 12047, -1, 13548, 12049, 13550, -1, 13550, 12049, 12048, -1, 13546, 12050, 13548, -1, 13548, 12050, 12049, -1, 13544, 12051, 13546, -1, 13546, 12051, 12050, -1, 12022, 12024, 13544, -1, 13544, 12024, 12051, -1, 14350, 12022, 14351, -1, 14351, 12022, 14352, -1, 14352, 12022, 14353, -1, 14353, 12022, 14354, -1, 14354, 12022, 14355, -1, 14355, 12022, 14356, -1, 14356, 12022, 12018, -1, 12533, 12024, 14357, -1, 14357, 12024, 14350, -1, 12025, 12024, 12533, -1, 14350, 12024, 12022, -1, 10156, 10210, 10448, -1, 8585, 12387, 14358, -1, 14358, 12387, 14359, -1, 14359, 12387, 14360, -1, 14360, 12387, 14361, -1, 14361, 12387, 14362, -1, 14362, 12387, 14363, -1, 14363, 12387, 14364, -1, 14364, 12387, 14365, -1, 14365, 12387, 14366, -1, 14366, 12387, 14367, -1, 14367, 12387, 10210, -1, 10210, 13482, 10448, -1, 12387, 13482, 10210, -1, 13482, 13480, 10448, -1, 13480, 13478, 10448, -1, 13478, 10449, 10448, -1, 8588, 12387, 8586, -1, 8586, 12387, 8585, -1, 13195, 10159, 10448, -1, 10448, 10159, 10156, -1, 13193, 10157, 13195, -1, 13195, 10157, 10159, -1, 13191, 10155, 13193, -1, 13193, 10155, 10157, -1, 13189, 10173, 13191, -1, 13191, 10173, 10155, -1, 12381, 10181, 13189, -1, 13189, 10181, 10173, -1, 9263, 10181, 12381, -1, 10235, 10181, 9263, -1, 9266, 10235, 9263, -1, 9266, 10271, 10235, -1, 13160, 10270, 9266, -1, 9266, 10270, 10271, -1, 13164, 10269, 13160, -1, 13160, 10269, 10270, -1, 13168, 10268, 13164, -1, 13164, 10268, 10269, -1, 13172, 10267, 13168, -1, 13168, 10267, 10268, -1, 13175, 10261, 13172, -1, 13172, 10261, 10267, -1, 13178, 10260, 13175, -1, 13175, 10260, 10261, -1, 13179, 10258, 13178, -1, 13178, 10258, 10260, -1, 13180, 10259, 13179, -1, 13179, 10259, 10258, -1, 12046, 10186, 13180, -1, 13180, 10186, 10259, -1, 12046, 12039, 10186, -1, 10186, 12039, 10187, -1, 12037, 10533, 12039, -1, 12039, 10533, 10187, -1, 12036, 10535, 12037, -1, 12037, 10535, 10533, -1, 12038, 10537, 12036, -1, 12036, 10537, 10535, -1, 12038, 10539, 10537, -1, 12040, 10541, 12038, -1, 12038, 10541, 10539, -1, 12041, 10089, 12040, -1, 12040, 10089, 10541, -1, 12042, 10090, 12041, -1, 12041, 10090, 10089, -1, 12043, 10094, 12042, -1, 12042, 10094, 10090, -1, 12044, 10096, 12043, -1, 12043, 10096, 10094, -1, 12044, 10420, 10096, -1, 12044, 12052, 10420, -1, 9071, 9072, 14368, -1, 14368, 9072, 11805, -1, 11805, 14369, 14370, -1, 14370, 14371, 11805, -1, 11805, 14372, 14369, -1, 14371, 12586, 11805, -1, 11805, 14373, 14372, -1, 11805, 14374, 14373, -1, 11805, 14375, 14374, -1, 11805, 12577, 14375, -1, 11805, 12026, 12577, -1, 12586, 11830, 11805, -1, 9072, 12026, 11805, -1, 12464, 9095, 9097, -1, 12464, 9098, 9095, -1, 12464, 9099, 9098, -1, 12001, 9121, 14376, -1, 14376, 9084, 14377, -1, 9121, 9084, 14376, -1, 14377, 9086, 14378, -1, 9084, 9086, 14377, -1, 14378, 9101, 14379, -1, 9086, 9101, 14378, -1, 14379, 9102, 11729, -1, 9101, 9102, 14379, -1, 9102, 9103, 11729, -1, 14376, 13542, 12001, -1, 12001, 13542, 12055, -1, 14377, 13540, 14376, -1, 14376, 13540, 13542, -1, 14377, 13538, 13540, -1, 14378, 13536, 14377, -1, 14377, 13536, 13538, -1, 14379, 13534, 14378, -1, 14378, 13534, 13536, -1, 11729, 13532, 14379, -1, 14379, 13532, 13534, -1, 11729, 11732, 13532, -1, 14380, 14381, 14382, -1, 14380, 14382, 14383, -1, 14384, 14348, 14347, -1, 14384, 14380, 14383, -1, 14384, 14347, 14380, -1, 14384, 14385, 14348, -1, 14384, 14383, 14385, -1, 14386, 14387, 14388, -1, 14386, 14388, 14389, -1, 14386, 14389, 14341, -1, 14390, 14347, 14345, -1, 14390, 14345, 14341, -1, 14390, 14341, 14389, -1, 14390, 14380, 14347, -1, 14390, 14381, 14380, -1, 14390, 14389, 14381, -1, 14391, 12375, 12376, -1, 14391, 14392, 14387, -1, 14391, 14386, 14344, -1, 14391, 12376, 14392, -1, 14391, 14387, 14386, -1, 14393, 14341, 14343, -1, 14393, 14343, 14344, -1, 14393, 14344, 14386, -1, 14393, 14386, 14341, -1, 14394, 14344, 14342, -1, 14394, 14342, 14346, -1, 14394, 12375, 14391, -1, 14394, 14391, 14344, -1, 14394, 14346, 12375, -1, 14349, 13214, 13215, -1, 12376, 12373, 14392, -1, 12374, 12375, 14346, -1, 14382, 14395, 12512, -1, 14382, 12512, 13212, -1, 14381, 14396, 14397, -1, 14381, 14397, 14395, -1, 14381, 14395, 14382, -1, 14383, 13212, 13214, -1, 14383, 14382, 13212, -1, 14385, 14349, 14348, -1, 14385, 14383, 13214, -1, 14385, 13214, 14349, -1, 14389, 14388, 14396, -1, 14389, 14396, 14381, -1, 14398, 12512, 14395, -1, 14398, 12514, 12512, -1, 14399, 14395, 14397, -1, 14399, 14398, 14395, -1, 14400, 14397, 14396, -1, 14400, 14399, 14397, -1, 14401, 14396, 14388, -1, 14401, 14400, 14396, -1, 14402, 14388, 14387, -1, 14402, 14401, 14388, -1, 14403, 14387, 14392, -1, 14403, 14402, 14387, -1, 12371, 14392, 12373, -1, 12371, 14403, 14392, -1, 14404, 14399, 14400, -1, 14404, 14405, 14406, -1, 14404, 14407, 14399, -1, 14404, 14406, 14407, -1, 14408, 14409, 14410, -1, 13210, 14411, 12515, -1, 14408, 12361, 14409, -1, 14408, 14410, 14412, -1, 14413, 14412, 14414, -1, 14413, 14414, 14415, -1, 14416, 14400, 14401, -1, 14416, 14405, 14404, -1, 14416, 14404, 14400, -1, 14416, 14415, 14405, -1, 14417, 12365, 12361, -1, 14417, 12361, 14408, -1, 14417, 14408, 14412, -1, 14417, 14412, 14413, -1, 14418, 14402, 14403, -1, 14418, 14401, 14402, -1, 14418, 14416, 14401, -1, 14418, 14413, 14415, -1, 14418, 14415, 14416, -1, 14419, 14403, 12371, -1, 14419, 12371, 12370, -1, 14419, 12370, 12365, -1, 14419, 14418, 14403, -1, 14419, 12365, 14417, -1, 14419, 14417, 14413, -1, 14419, 14413, 14418, -1, 14398, 13206, 12514, -1, 12361, 12325, 14409, -1, 14420, 14411, 13210, -1, 14421, 14422, 14411, -1, 14421, 14411, 14420, -1, 14423, 13210, 13208, -1, 14423, 14420, 13210, -1, 14424, 14425, 14422, -1, 14424, 14422, 14421, -1, 14406, 14421, 14420, -1, 14406, 14420, 14423, -1, 14426, 14398, 14399, -1, 14426, 13208, 13206, -1, 14426, 14423, 13208, -1, 14426, 13206, 14398, -1, 14414, 14427, 14425, -1, 14414, 14425, 14424, -1, 14405, 14421, 14406, -1, 14405, 14424, 14421, -1, 14407, 14406, 14423, -1, 14407, 14426, 14399, -1, 14407, 14423, 14426, -1, 14412, 14410, 14427, -1, 14412, 14427, 14414, -1, 14415, 14414, 14424, -1, 14415, 14424, 14405, -1, 14428, 12515, 14411, -1, 14428, 12518, 12515, -1, 14429, 14411, 14422, -1, 14429, 14428, 14411, -1, 14430, 14422, 14425, -1, 14430, 14429, 14422, -1, 14431, 14425, 14427, -1, 14431, 14430, 14425, -1, 14432, 14427, 14410, -1, 14432, 14431, 14427, -1, 14433, 14410, 14409, -1, 14433, 14432, 14410, -1, 12320, 14409, 12325, -1, 12320, 14433, 14409, -1, 14434, 12331, 12379, -1, 14434, 12379, 14435, -1, 14434, 14436, 12331, -1, 14437, 14429, 14430, -1, 14437, 14430, 14438, -1, 14439, 14438, 14440, -1, 14439, 14440, 14441, -1, 14442, 14443, 14444, -1, 14442, 14441, 14443, -1, 14445, 14435, 14446, -1, 14445, 14444, 14436, -1, 14445, 14434, 14435, -1, 14445, 14436, 14434, -1, 14447, 14428, 14429, -1, 14447, 13225, 14428, -1, 14447, 14429, 14437, -1, 14448, 14438, 14439, -1, 14448, 14437, 14438, -1, 14435, 12379, 12324, -1, 14449, 14439, 14441, -1, 14449, 14441, 14442, -1, 14450, 14446, 14451, -1, 14450, 14442, 14444, -1, 14450, 14445, 14446, -1, 14450, 14444, 14445, -1, 14452, 13227, 13225, -1, 14452, 13225, 14447, -1, 14452, 14447, 14437, -1, 14452, 14437, 14448, -1, 13225, 12518, 14428, -1, 14453, 14448, 14439, -1, 14453, 14439, 14449, -1, 14454, 14451, 14455, -1, 14454, 14442, 14450, -1, 14454, 14450, 14451, -1, 14454, 14449, 14442, -1, 14456, 14448, 14453, -1, 14456, 13229, 13227, -1, 14456, 13227, 14452, -1, 14456, 14452, 14448, -1, 14457, 14453, 14449, -1, 14457, 14455, 14458, -1, 14457, 14454, 14455, -1, 14457, 14449, 14454, -1, 14459, 14457, 14458, -1, 14459, 13229, 14456, -1, 14459, 14458, 14460, -1, 14459, 14460, 12506, -1, 14459, 12506, 13231, -1, 14459, 13231, 13229, -1, 14459, 14453, 14457, -1, 14459, 14456, 14453, -1, 14461, 14433, 12320, -1, 14461, 12320, 12330, -1, 14462, 14432, 14433, -1, 14462, 14433, 14461, -1, 14463, 12330, 12329, -1, 14463, 14461, 12330, -1, 14440, 14431, 14432, -1, 14440, 14432, 14462, -1, 14443, 14461, 14463, -1, 14443, 14462, 14461, -1, 14436, 12329, 12331, -1, 14436, 14463, 12329, -1, 14438, 14430, 14431, -1, 14438, 14431, 14440, -1, 14441, 14440, 14462, -1, 14441, 14462, 14443, -1, 14444, 14443, 14463, -1, 14444, 14463, 14436, -1, 12324, 12353, 14464, -1, 14435, 14464, 14465, -1, 14435, 12324, 14464, -1, 14446, 14465, 14466, -1, 14446, 14435, 14465, -1, 14451, 14466, 14467, -1, 14451, 14446, 14466, -1, 14455, 14467, 14468, -1, 14455, 14451, 14467, -1, 14458, 14468, 14469, -1, 14458, 14455, 14468, -1, 14460, 14469, 12507, -1, 14460, 14458, 14469, -1, 12506, 14460, 12507, -1, 14470, 14471, 14472, -1, 14470, 14473, 14474, -1, 14475, 14476, 14477, -1, 14470, 14478, 14471, -1, 14475, 14477, 14479, -1, 14470, 14474, 14478, -1, 14480, 12620, 12621, -1, 14480, 12621, 14481, -1, 14482, 14483, 14484, -1, 14480, 14485, 14486, -1, 14482, 14479, 14483, -1, 14480, 14481, 14485, -1, 14487, 14472, 14488, -1, 14487, 14470, 14472, -1, 14489, 12332, 12326, -1, 14487, 14473, 14470, -1, 14487, 14486, 14473, -1, 14490, 14488, 14491, -1, 14489, 14484, 12332, -1, 14490, 12619, 12620, -1, 14490, 12620, 14480, -1, 14490, 14487, 14488, -1, 14492, 14468, 14467, -1, 14490, 14480, 14486, -1, 14490, 14486, 14487, -1, 14490, 14491, 12619, -1, 14492, 14467, 14493, -1, 14494, 14476, 14475, -1, 14494, 14493, 14476, -1, 14495, 14479, 14482, -1, 14495, 14475, 14479, -1, 14496, 14482, 14484, -1, 14496, 14484, 14489, -1, 14497, 12326, 12328, -1, 12624, 12507, 14469, -1, 14497, 14489, 12326, -1, 14498, 14469, 14468, -1, 14498, 12624, 14469, -1, 14498, 14468, 14492, -1, 14499, 14492, 14493, -1, 14499, 14493, 14494, -1, 14500, 12315, 12317, -1, 14501, 14494, 14475, -1, 14501, 14475, 14495, -1, 14502, 14482, 14496, -1, 14502, 14495, 14482, -1, 14503, 14496, 14489, -1, 14503, 14489, 14497, -1, 14504, 12328, 12315, -1, 14504, 12315, 14500, -1, 14504, 14497, 12328, -1, 14505, 14498, 14492, -1, 14505, 12623, 12624, -1, 14505, 14492, 14499, -1, 14505, 12624, 14498, -1, 14506, 14499, 14494, -1, 14506, 14494, 14501, -1, 14507, 14495, 14502, -1, 14507, 14501, 14495, -1, 12504, 12619, 14491, -1, 14508, 14464, 12353, -1, 14474, 14502, 14496, -1, 14508, 12353, 12341, -1, 14477, 14465, 14464, -1, 14474, 14496, 14503, -1, 14509, 14503, 14497, -1, 14509, 14504, 14500, -1, 14509, 14500, 14510, -1, 14477, 14464, 14508, -1, 14509, 14497, 14504, -1, 14511, 12623, 14505, -1, 14483, 12341, 12334, -1, 14511, 14505, 14499, -1, 14511, 12622, 12623, -1, 14511, 14499, 14506, -1, 14483, 14508, 12341, -1, 14485, 14506, 14501, -1, 14476, 14466, 14465, -1, 14485, 14501, 14507, -1, 14476, 14465, 14477, -1, 14473, 14502, 14474, -1, 14473, 14507, 14502, -1, 14479, 14508, 14483, -1, 14478, 14503, 14509, -1, 14478, 14510, 14471, -1, 14479, 14477, 14508, -1, 14478, 14474, 14503, -1, 14484, 12334, 12332, -1, 14478, 14509, 14510, -1, 14481, 14511, 14506, -1, 14481, 14506, 14485, -1, 14481, 12621, 12622, -1, 14481, 12622, 14511, -1, 14484, 14483, 12334, -1, 14493, 14467, 14466, -1, 14486, 14485, 14507, -1, 14493, 14466, 14476, -1, 14486, 14507, 14473, -1, 12317, 12345, 14512, -1, 14500, 12317, 14512, -1, 14510, 14512, 14513, -1, 14510, 14500, 14512, -1, 14471, 14513, 14514, -1, 14471, 14510, 14513, -1, 14472, 14514, 14515, -1, 14472, 14471, 14514, -1, 14488, 14515, 14516, -1, 14488, 14472, 14515, -1, 14491, 14516, 14517, -1, 14491, 14488, 14516, -1, 12504, 14517, 12502, -1, 12504, 14491, 14517, -1, 14518, 14519, 14520, -1, 14518, 14521, 14522, -1, 14518, 14523, 14521, -1, 14518, 14522, 14519, -1, 14524, 14517, 14516, -1, 12347, 14512, 12345, -1, 14524, 14516, 14525, -1, 14524, 12640, 14517, -1, 14526, 14527, 14528, -1, 14526, 14525, 14527, -1, 14529, 14520, 14530, -1, 14529, 14518, 14520, -1, 14529, 14528, 14523, -1, 14529, 14523, 14518, -1, 14531, 12638, 12640, -1, 14531, 12640, 14524, -1, 14531, 14524, 14525, -1, 14531, 14525, 14526, -1, 14532, 14530, 14533, -1, 14532, 14529, 14530, -1, 14532, 14526, 14528, -1, 14532, 14528, 14529, -1, 14534, 14533, 14535, -1, 14534, 12635, 12638, -1, 14534, 12638, 14531, -1, 14534, 14535, 12635, -1, 14534, 14532, 14533, -1, 14534, 14531, 14526, -1, 14534, 14526, 14532, -1, 12640, 12502, 14517, -1, 12498, 12635, 14535, -1, 14536, 12347, 12348, -1, 14536, 14512, 12347, -1, 14537, 14513, 14512, -1, 14537, 14512, 14536, -1, 14538, 14536, 12348, -1, 14539, 14514, 14513, -1, 14539, 14513, 14537, -1, 14521, 14536, 14538, -1, 14521, 14537, 14536, -1, 14540, 12348, 12349, -1, 14540, 12349, 12350, -1, 14540, 12350, 14541, -1, 14540, 14538, 12348, -1, 14527, 14515, 14514, -1, 14527, 14514, 14539, -1, 14523, 14539, 14537, -1, 14523, 14537, 14521, -1, 14522, 14541, 14519, -1, 14522, 14521, 14538, -1, 14522, 14540, 14541, -1, 14522, 14538, 14540, -1, 14525, 14516, 14515, -1, 14525, 14515, 14527, -1, 14528, 14527, 14539, -1, 14528, 14539, 14523, -1, 12350, 12342, 14542, -1, 14541, 14542, 14543, -1, 14541, 12350, 14542, -1, 14519, 14543, 14544, -1, 14519, 14541, 14543, -1, 14520, 14545, 14546, -1, 14520, 14544, 14545, -1, 14520, 14519, 14544, -1, 14530, 14546, 14547, -1, 14530, 14520, 14546, -1, 14533, 14530, 14547, -1, 14535, 14547, 12499, -1, 14535, 14533, 14547, -1, 12498, 14535, 12499, -1, 14548, 9079, 9080, -1, 12336, 9080, 12342, -1, 12336, 14548, 9080, -1, 12339, 12340, 14549, -1, 12339, 14549, 14550, -1, 12339, 14550, 12385, -1, 12339, 12385, 13596, -1, 9073, 13600, 9076, -1, 14548, 12335, 9079, -1, 12336, 12335, 14548, -1, 14551, 12339, 13596, -1, 14552, 12338, 12339, -1, 14552, 12339, 14551, -1, 14553, 13596, 13598, -1, 14553, 14551, 13596, -1, 14554, 12337, 12338, -1, 14554, 14552, 14551, -1, 14554, 12338, 14552, -1, 14554, 14551, 14553, -1, 14554, 14553, 13598, -1, 14555, 13598, 13600, -1, 14555, 13600, 9073, -1, 14556, 9073, 9077, -1, 14556, 14554, 13598, -1, 14556, 14555, 9073, -1, 14556, 13598, 14555, -1, 14557, 12335, 12337, -1, 14557, 9077, 9079, -1, 14557, 12337, 14554, -1, 14557, 14554, 14556, -1, 14557, 14556, 9077, -1, 14557, 9079, 12335, -1, 12340, 12344, 14558, -1, 14549, 14558, 14559, -1, 14549, 12340, 14558, -1, 14550, 14559, 12383, -1, 14550, 14549, 14559, -1, 12385, 14550, 12383, -1, 14560, 14558, 12344, -1, 14560, 12344, 12629, -1, 14561, 14559, 14558, -1, 14561, 12383, 14559, -1, 14561, 14558, 14560, -1, 12384, 12383, 14561, -1, 12626, 12521, 12633, -1, 12628, 12633, 12631, -1, 12628, 12626, 12633, -1, 14561, 12631, 12384, -1, 14560, 12628, 12631, -1, 14560, 12631, 14561, -1, 12629, 12628, 14560, -1, 12003, 12002, 14562, -1, 12002, 14563, 14562, -1, 14562, 14564, 14565, -1, 14563, 14564, 14562, -1, 14565, 12524, 12526, -1, 14564, 12524, 14565, -1, 14059, 14566, 14058, -1, 12057, 14566, 14059, -1, 14566, 14057, 14058, -1, 14566, 14567, 14057, -1, 14055, 14563, 12002, -1, 14056, 14563, 14055, -1, 14057, 14563, 14056, -1, 14567, 14563, 14057, -1, 14568, 12528, 14567, -1, 12527, 12528, 14568, -1, 12528, 14564, 14567, -1, 14567, 14564, 14563, -1, 12528, 12529, 14564, -1, 12529, 12524, 14564, -1, 12057, 12056, 14566, -1, 14566, 14569, 14567, -1, 12056, 14569, 14566, -1, 14567, 14570, 14568, -1, 14569, 14570, 14567, -1, 14568, 14571, 12527, -1, 14570, 14571, 14568, -1, 14571, 12530, 12527, -1, 12056, 13543, 14569, -1, 14571, 14572, 12530, -1, 13541, 14573, 13543, -1, 14569, 14574, 14570, -1, 14570, 14574, 14571, -1, 13543, 14574, 14569, -1, 14571, 14574, 14572, -1, 14573, 14574, 13543, -1, 13541, 14574, 14573, -1, 14572, 14575, 14576, -1, 14576, 14575, 14574, -1, 14574, 14575, 14572, -1, 13539, 14577, 13541, -1, 13537, 14577, 13539, -1, 13541, 14577, 14574, -1, 14578, 14579, 14580, -1, 14576, 14579, 14578, -1, 14574, 14579, 14576, -1, 14577, 14579, 14574, -1, 13535, 14581, 13537, -1, 13537, 14581, 14577, -1, 14581, 14582, 14577, -1, 14577, 14582, 14579, -1, 13535, 14582, 14581, -1, 14580, 14583, 14584, -1, 14584, 14583, 14582, -1, 14579, 14583, 14580, -1, 14582, 14583, 14579, -1, 13533, 14585, 13535, -1, 11735, 14585, 13533, -1, 13535, 14585, 14582, -1, 14586, 14587, 11735, -1, 14584, 14587, 14586, -1, 14582, 14587, 14584, -1, 11735, 14587, 14585, -1, 14585, 14587, 14582, -1, 11751, 14588, 11735, -1, 11735, 14588, 14586, -1, 14586, 14589, 14584, -1, 14588, 14589, 14586, -1, 14584, 14590, 14580, -1, 14589, 14590, 14584, -1, 14580, 14591, 14578, -1, 14590, 14591, 14580, -1, 14578, 14592, 14576, -1, 14591, 14592, 14578, -1, 14576, 14593, 14572, -1, 14572, 14593, 12530, -1, 14592, 14593, 14576, -1, 14593, 12531, 12530, -1, 14594, 14595, 14596, -1, 14596, 14595, 14597, -1, 14598, 14599, 14600, -1, 14601, 14599, 14602, -1, 14597, 14599, 14601, -1, 14602, 14599, 14598, -1, 14588, 14603, 14589, -1, 14589, 14603, 14604, -1, 11756, 14603, 14588, -1, 14604, 14605, 14594, -1, 14594, 14605, 14595, -1, 14600, 14606, 14607, -1, 14599, 14606, 14600, -1, 14595, 14606, 14597, -1, 14597, 14606, 14599, -1, 11758, 14608, 11756, -1, 11756, 14608, 14603, -1, 14603, 14608, 14604, -1, 14604, 14608, 14605, -1, 14607, 14609, 14610, -1, 14606, 14609, 14607, -1, 14605, 14609, 14595, -1, 14595, 14609, 14606, -1, 14610, 14611, 14612, -1, 11761, 14611, 11758, -1, 11758, 14611, 14608, -1, 14612, 14611, 11761, -1, 14609, 14611, 14610, -1, 14608, 14611, 14605, -1, 14605, 14611, 14609, -1, 11751, 11756, 14588, -1, 11761, 11740, 14612, -1, 12531, 14613, 12645, -1, 14593, 14613, 12531, -1, 14592, 14614, 14593, -1, 14593, 14614, 14613, -1, 12645, 14615, 12643, -1, 14613, 14615, 12645, -1, 14591, 14596, 14592, -1, 14592, 14596, 14614, -1, 14614, 14601, 14613, -1, 14613, 14601, 14615, -1, 12641, 14616, 12587, -1, 12643, 14616, 12641, -1, 12587, 14616, 14617, -1, 14615, 14616, 12643, -1, 14590, 14594, 14591, -1, 14591, 14594, 14596, -1, 14596, 14597, 14614, -1, 14614, 14597, 14601, -1, 14617, 14602, 14598, -1, 14601, 14602, 14615, -1, 14615, 14602, 14616, -1, 14616, 14602, 14617, -1, 14589, 14604, 14590, -1, 14590, 14604, 14594, -1, 11738, 14618, 11740, -1, 11740, 14618, 14612, -1, 14612, 14619, 14610, -1, 14618, 14619, 14612, -1, 14610, 14620, 14607, -1, 14619, 14620, 14610, -1, 14607, 14621, 14600, -1, 14620, 14621, 14607, -1, 14600, 14622, 14598, -1, 14621, 14622, 14600, -1, 14598, 14623, 14617, -1, 14622, 14623, 14598, -1, 14617, 12590, 12587, -1, 14623, 12590, 14617, -1, 14624, 14625, 14626, -1, 14627, 14628, 14629, -1, 14630, 14628, 14627, -1, 14626, 14625, 14631, -1, 14632, 14628, 14633, -1, 14633, 14628, 14630, -1, 11757, 14634, 11759, -1, 11759, 14634, 14635, -1, 14631, 14636, 14637, -1, 14635, 14634, 14638, -1, 14637, 14636, 14639, -1, 14638, 14634, 14640, -1, 14629, 14641, 14642, -1, 14628, 14641, 14629, -1, 12595, 14643, 12597, -1, 14640, 14641, 14632, -1, 14632, 14641, 14628, -1, 14639, 14643, 12595, -1, 11757, 14644, 14634, -1, 14642, 14644, 14645, -1, 11753, 14644, 11757, -1, 14640, 14644, 14641, -1, 14641, 14644, 14642, -1, 14619, 14646, 14620, -1, 14634, 14644, 14640, -1, 14620, 14646, 14647, -1, 14645, 14644, 11753, -1, 14647, 14648, 14624, -1, 14624, 14648, 14625, -1, 14625, 14649, 14631, -1, 14631, 14649, 14636, -1, 14639, 14650, 14643, -1, 14636, 14650, 14639, -1, 11749, 14651, 11738, -1, 11738, 14651, 14618, -1, 14618, 14651, 14619, -1, 14619, 14651, 14646, -1, 12597, 14652, 12599, -1, 14643, 14652, 12597, -1, 14647, 14653, 14648, -1, 14646, 14653, 14647, -1, 14648, 14654, 14625, -1, 14625, 14654, 14649, -1, 14649, 14655, 14636, -1, 14636, 14655, 14650, -1, 14650, 14656, 14643, -1, 14643, 14656, 14652, -1, 14646, 14657, 14653, -1, 11755, 14657, 11749, -1, 11749, 14657, 14651, -1, 14651, 14657, 14646, -1, 12601, 14658, 12604, -1, 12599, 14658, 12601, -1, 12604, 14658, 14659, -1, 14652, 14658, 12599, -1, 14653, 14660, 14648, -1, 14648, 14660, 14654, -1, 14654, 14661, 14649, -1, 11753, 11744, 14645, -1, 12590, 14662, 12591, -1, 14649, 14661, 14655, -1, 14623, 14662, 12590, -1, 14650, 14633, 14656, -1, 14655, 14633, 14650, -1, 14656, 14663, 14652, -1, 14622, 14626, 14623, -1, 14659, 14663, 14664, -1, 14652, 14663, 14658, -1, 14658, 14663, 14659, -1, 14623, 14626, 14662, -1, 11760, 14665, 11755, -1, 12591, 14637, 12593, -1, 14657, 14665, 14653, -1, 14662, 14637, 12591, -1, 14653, 14665, 14660, -1, 11755, 14665, 14657, -1, 14654, 14638, 14661, -1, 14660, 14638, 14654, -1, 14621, 14624, 14622, -1, 14622, 14624, 14626, -1, 14655, 14632, 14633, -1, 14662, 14631, 14637, -1, 14661, 14632, 14655, -1, 14656, 14630, 14663, -1, 14626, 14631, 14662, -1, 14664, 14630, 14627, -1, 14633, 14630, 14656, -1, 12593, 14639, 12595, -1, 14663, 14630, 14664, -1, 11759, 14635, 11760, -1, 14637, 14639, 12593, -1, 14665, 14635, 14660, -1, 14660, 14635, 14638, -1, 11760, 14635, 14665, -1, 14620, 14647, 14621, -1, 14638, 14640, 14661, -1, 14661, 14640, 14632, -1, 14621, 14647, 14624, -1, 11744, 11723, 14645, -1, 14645, 14666, 14642, -1, 11723, 14666, 14645, -1, 14642, 14667, 14629, -1, 14666, 14667, 14642, -1, 14629, 14668, 14627, -1, 14667, 14668, 14629, -1, 14627, 14669, 14664, -1, 14668, 14669, 14627, -1, 14664, 14670, 14659, -1, 14669, 14670, 14664, -1, 14659, 14671, 12604, -1, 14670, 14671, 14659, -1, 14671, 12606, 12604, -1, 11847, 11852, 12079, -1, 12079, 14672, 12078, -1, 11852, 14672, 12079, -1, 12078, 14673, 12077, -1, 14672, 14673, 12078, -1, 12077, 14674, 12074, -1, 14673, 14674, 12077, -1, 12074, 14675, 12072, -1, 14674, 14675, 12074, -1, 12072, 14676, 12070, -1, 14675, 14676, 12072, -1, 12070, 14677, 11726, -1, 14676, 14677, 12070, -1, 14677, 11725, 11726, -1, 14678, 14679, 13234, -1, 14667, 14680, 14668, -1, 14668, 14680, 14681, -1, 14681, 14682, 14683, -1, 14683, 14682, 14684, -1, 14684, 14685, 14686, -1, 14686, 14685, 14687, -1, 14688, 14689, 14690, -1, 14687, 14689, 14678, -1, 14678, 14689, 14679, -1, 14679, 14689, 14688, -1, 11721, 14691, 11723, -1, 11723, 14691, 14666, -1, 14666, 14691, 14667, -1, 14667, 14691, 14680, -1, 14681, 14692, 14682, -1, 14680, 14692, 14681, -1, 14684, 14693, 14685, -1, 14682, 14693, 14684, -1, 14690, 14694, 14695, -1, 14689, 14694, 14690, -1, 14687, 14694, 14689, -1, 14685, 14694, 14687, -1, 11720, 14696, 11721, -1, 11721, 14696, 14691, -1, 14691, 14696, 14680, -1, 14680, 14696, 14692, -1, 14692, 14697, 14682, -1, 14682, 14697, 14693, -1, 14695, 14698, 14699, -1, 14694, 14698, 14695, -1, 14693, 14698, 14685, -1, 14685, 14698, 14694, -1, 14696, 14700, 14692, -1, 11717, 14700, 11720, -1, 11720, 14700, 14696, -1, 14692, 14700, 14697, -1, 14697, 14701, 14693, -1, 14699, 14701, 14702, -1, 14693, 14701, 14698, -1, 14698, 14701, 14699, -1, 14702, 14703, 14704, -1, 14700, 14703, 14697, -1, 11716, 14703, 11717, -1, 14704, 14703, 11716, -1, 14697, 14703, 14701, -1, 11717, 14703, 14700, -1, 14701, 14703, 14702, -1, 11716, 11718, 14704, -1, 12606, 14705, 13238, -1, 14671, 14705, 12606, -1, 14670, 14706, 14671, -1, 14671, 14706, 14705, -1, 13236, 14707, 13234, -1, 13238, 14707, 13236, -1, 14705, 14707, 13238, -1, 14669, 14683, 14670, -1, 14670, 14683, 14706, -1, 14705, 14686, 14707, -1, 14706, 14686, 14705, -1, 14707, 14678, 13234, -1, 14668, 14681, 14669, -1, 14669, 14681, 14683, -1, 14683, 14684, 14706, -1, 14706, 14684, 14686, -1, 14686, 14687, 14707, -1, 14707, 14687, 14678, -1, 13233, 14679, 12584, -1, 13234, 14679, 13233, -1, 12584, 14679, 14688, -1, 11725, 14677, 11718, -1, 11718, 14677, 14704, -1, 14704, 14676, 14702, -1, 14677, 14676, 14704, -1, 14702, 14675, 14699, -1, 14676, 14675, 14702, -1, 14699, 14674, 14695, -1, 14675, 14674, 14699, -1, 14695, 14673, 14690, -1, 14674, 14673, 14695, -1, 14690, 14672, 14688, -1, 14688, 14672, 12584, -1, 14673, 14672, 14690, -1, 14672, 11852, 12584, -1, 14356, 12018, 12020, -1, 14356, 12020, 14708, -1, 14355, 14356, 14708, -1, 14354, 14708, 14709, -1, 14354, 14355, 14708, -1, 14353, 14354, 14709, -1, 14352, 14709, 14710, -1, 14352, 14353, 14709, -1, 14351, 14710, 14711, -1, 14351, 14352, 14710, -1, 14350, 14711, 14712, -1, 14350, 14351, 14711, -1, 14357, 14712, 14713, -1, 14357, 14350, 14712, -1, 12533, 14713, 12532, -1, 12533, 14357, 14713, -1, 14714, 14715, 14716, -1, 14714, 14717, 13213, -1, 14714, 13211, 14715, -1, 14714, 14716, 14717, -1, 14718, 14719, 14720, -1, 14718, 14720, 14721, -1, 12537, 14722, 12534, -1, 14723, 14719, 14718, -1, 14723, 14724, 14719, -1, 14725, 12544, 12545, -1, 14725, 12545, 12541, -1, 14725, 14726, 12544, -1, 14727, 14717, 14724, -1, 14727, 13213, 14717, -1, 14727, 14724, 14723, -1, 14728, 14721, 14726, -1, 14728, 14726, 14725, -1, 14729, 13216, 13213, -1, 14729, 13213, 14727, -1, 14730, 14721, 14728, -1, 14730, 14718, 14721, -1, 13211, 12511, 14715, -1, 14731, 12541, 12538, -1, 14731, 14725, 12541, -1, 14732, 14723, 14718, -1, 14732, 14718, 14730, -1, 14733, 14728, 14725, -1, 14733, 14725, 14731, -1, 14734, 14723, 14732, -1, 14734, 14727, 14723, -1, 14735, 14730, 14728, -1, 14735, 14728, 14733, -1, 14736, 14727, 14734, -1, 14736, 13218, 13216, -1, 14736, 13216, 14729, -1, 14736, 14729, 14727, -1, 14713, 12536, 12532, -1, 14737, 12538, 12536, -1, 14737, 14731, 12538, -1, 14712, 12536, 14713, -1, 14738, 14732, 14730, -1, 14738, 14730, 14735, -1, 14739, 14733, 14731, -1, 14739, 14737, 12536, -1, 14739, 12536, 14712, -1, 14739, 14731, 14737, -1, 14740, 14732, 14738, -1, 14708, 13222, 14709, -1, 14740, 14734, 14732, -1, 14741, 14735, 14733, -1, 12020, 13222, 14708, -1, 14741, 14712, 14711, -1, 14741, 14739, 14712, -1, 14741, 14733, 14739, -1, 14742, 12537, 12544, -1, 14742, 14722, 12537, -1, 14743, 14736, 14734, -1, 14743, 13219, 13218, -1, 14743, 13218, 14736, -1, 14743, 14734, 14740, -1, 14720, 14744, 14722, -1, 14745, 14711, 14710, -1, 14720, 14722, 14742, -1, 14745, 14738, 14735, -1, 14745, 14735, 14741, -1, 14745, 14741, 14711, -1, 14719, 14746, 14744, -1, 14747, 14710, 14709, -1, 14719, 14744, 14720, -1, 14747, 14738, 14745, -1, 14747, 14740, 14738, -1, 14747, 14745, 14710, -1, 14747, 14709, 13222, -1, 14724, 14748, 14746, -1, 14749, 13222, 13219, -1, 14749, 13219, 14743, -1, 14749, 14743, 14740, -1, 14749, 14747, 13222, -1, 14724, 14746, 14719, -1, 14749, 14740, 14747, -1, 14726, 14742, 12544, -1, 14717, 14716, 14748, -1, 14717, 14748, 14724, -1, 14721, 14720, 14742, -1, 14721, 14742, 14726, -1, 14714, 13213, 13211, -1, 14750, 12534, 14722, -1, 14750, 12535, 12534, -1, 14751, 14744, 14746, -1, 14751, 14722, 14744, -1, 14751, 14750, 14722, -1, 14752, 14746, 14748, -1, 14752, 14751, 14746, -1, 14753, 14748, 14716, -1, 14753, 14752, 14748, -1, 14754, 14716, 14715, -1, 14754, 14753, 14716, -1, 14755, 14715, 12511, -1, 14755, 14754, 14715, -1, 12513, 14755, 12511, -1, 14756, 14757, 14758, -1, 14759, 14751, 14752, -1, 14759, 14758, 14760, -1, 14759, 14760, 14761, -1, 14759, 14761, 14751, -1, 14762, 14763, 14764, -1, 12582, 14765, 12572, -1, 14762, 14764, 14766, -1, 14762, 13209, 14763, -1, 14767, 14766, 14768, -1, 14767, 14768, 14756, -1, 14769, 14752, 14753, -1, 14769, 14758, 14759, -1, 14769, 14759, 14752, -1, 14769, 14756, 14758, -1, 14770, 13207, 13209, -1, 14770, 13209, 14762, -1, 14770, 14766, 14767, -1, 14770, 14762, 14766, -1, 14771, 14753, 14754, -1, 14771, 14769, 14753, -1, 14771, 14767, 14756, -1, 14771, 14756, 14769, -1, 14772, 14754, 14755, -1, 14772, 13205, 13207, -1, 14772, 13207, 14770, -1, 14772, 14755, 13205, -1, 14772, 14771, 14754, -1, 14772, 14770, 14767, -1, 14772, 14767, 14771, -1, 14750, 12583, 12535, -1, 13209, 12517, 14763, -1, 12513, 13205, 14755, -1, 14773, 14765, 12582, -1, 14774, 14775, 14765, -1, 14774, 14765, 14773, -1, 14776, 12582, 12581, -1, 14776, 14773, 12582, -1, 14757, 14777, 14775, -1, 14757, 14775, 14774, -1, 14760, 14774, 14773, -1, 14760, 14773, 14776, -1, 14778, 12581, 12583, -1, 14778, 14776, 12581, -1, 14778, 12583, 14750, -1, 14768, 14779, 14777, -1, 14768, 14777, 14757, -1, 14758, 14774, 14760, -1, 14758, 14757, 14774, -1, 14761, 14750, 14751, -1, 14761, 14778, 14750, -1, 14761, 14776, 14778, -1, 14761, 14760, 14776, -1, 14766, 14764, 14779, -1, 14766, 14779, 14768, -1, 14756, 14768, 14757, -1, 14780, 12572, 14765, -1, 14780, 12566, 12572, -1, 14781, 14765, 14775, -1, 14781, 14780, 14765, -1, 14782, 14775, 14777, -1, 14782, 14781, 14775, -1, 14783, 14777, 14779, -1, 14783, 14782, 14777, -1, 14784, 14779, 14764, -1, 14784, 14783, 14779, -1, 14785, 14764, 14763, -1, 14785, 14784, 14764, -1, 12516, 14763, 12517, -1, 12516, 14785, 14763, -1, 14786, 13230, 12509, -1, 14786, 12509, 14787, -1, 14786, 14787, 14788, -1, 14786, 14789, 13228, -1, 14790, 14781, 14782, -1, 14790, 14782, 14791, -1, 14792, 14791, 14793, -1, 14792, 14793, 14794, -1, 14795, 14796, 14797, -1, 14795, 14794, 14796, -1, 14798, 14788, 14799, -1, 14798, 14789, 14786, -1, 14798, 14786, 14788, -1, 14798, 14797, 14789, -1, 14800, 14780, 14781, -1, 14800, 14781, 14790, -1, 14800, 12575, 14780, -1, 14801, 14791, 14792, -1, 14801, 14790, 14791, -1, 14802, 14792, 14794, -1, 14802, 14794, 14795, -1, 14803, 14799, 14804, -1, 14803, 14795, 14797, -1, 14803, 14798, 14799, -1, 14803, 14797, 14798, -1, 14805, 12574, 12575, -1, 14805, 12575, 14800, -1, 14805, 14800, 14790, -1, 14805, 14790, 14801, -1, 14806, 14801, 14792, -1, 14806, 14792, 14802, -1, 12575, 12566, 14780, -1, 14807, 14804, 14808, -1, 14807, 14803, 14804, -1, 14807, 14795, 14803, -1, 14807, 14802, 14795, -1, 14809, 12564, 12574, -1, 14809, 14801, 14806, -1, 14809, 12574, 14805, -1, 14809, 14805, 14801, -1, 14810, 14806, 14802, -1, 14810, 14807, 14808, -1, 14810, 14808, 14811, -1, 14810, 14802, 14807, -1, 14812, 14810, 14811, -1, 14812, 14811, 12556, -1, 14812, 12556, 12562, -1, 14812, 12562, 12564, -1, 14812, 12564, 14809, -1, 14812, 14809, 14806, -1, 14812, 14806, 14810, -1, 14813, 14785, 12516, -1, 14813, 12516, 13224, -1, 14814, 14784, 14785, -1, 14814, 14785, 14813, -1, 14815, 13224, 13226, -1, 14815, 14813, 13224, -1, 14793, 14783, 14784, -1, 14793, 14784, 14814, -1, 14796, 14813, 14815, -1, 14796, 14814, 14813, -1, 14789, 13226, 13228, -1, 14789, 14815, 13226, -1, 14791, 14782, 14783, -1, 14791, 14783, 14793, -1, 14794, 14793, 14814, -1, 14794, 14814, 14796, -1, 14797, 14796, 14815, -1, 14797, 14815, 14789, -1, 14786, 13228, 13230, -1, 12509, 12510, 14816, -1, 14787, 14816, 14817, -1, 14787, 12509, 14816, -1, 14788, 14817, 14818, -1, 14788, 14787, 14817, -1, 14799, 14818, 14819, -1, 14799, 14788, 14818, -1, 14804, 14819, 14820, -1, 14804, 14799, 14819, -1, 14808, 14820, 14821, -1, 14808, 14804, 14820, -1, 14811, 14821, 12550, -1, 14811, 14808, 14821, -1, 12556, 14811, 12550, -1, 14822, 14823, 14824, -1, 14822, 14825, 14823, -1, 14826, 14827, 14828, -1, 14829, 14830, 14831, -1, 14826, 14832, 14827, -1, 14829, 14831, 14833, -1, 14826, 14824, 14834, -1, 14826, 14834, 14832, -1, 14835, 12563, 14836, -1, 14835, 12560, 12563, -1, 14837, 14838, 14839, -1, 14835, 14825, 14822, -1, 14837, 14833, 14838, -1, 14835, 14836, 14825, -1, 14840, 14828, 14841, -1, 14840, 14826, 14828, -1, 14842, 12614, 12612, -1, 14840, 14822, 14824, -1, 14840, 14824, 14826, -1, 14842, 14839, 12614, -1, 14843, 14841, 14844, -1, 14843, 14844, 12555, -1, 14843, 12555, 12560, -1, 14845, 14820, 14819, -1, 14843, 14840, 14841, -1, 14843, 14822, 14840, -1, 14843, 12560, 14835, -1, 14843, 14835, 14822, -1, 14845, 14819, 14846, -1, 14847, 14830, 14829, -1, 14847, 14846, 14830, -1, 14848, 14829, 14833, -1, 14848, 14833, 14837, -1, 14849, 14837, 14839, -1, 14849, 14839, 14842, -1, 12579, 12550, 14821, -1, 14850, 14821, 14820, -1, 14850, 12576, 12579, -1, 14850, 12579, 14821, -1, 14850, 14820, 14845, -1, 14851, 12612, 12610, -1, 14851, 14842, 12612, -1, 14852, 14845, 14846, -1, 14852, 14846, 14847, -1, 14853, 14829, 14848, -1, 14853, 14847, 14829, -1, 14854, 14848, 14837, -1, 14854, 14837, 14849, -1, 14855, 14849, 14842, -1, 14855, 14842, 14851, -1, 14856, 12571, 12576, -1, 14856, 12576, 14850, -1, 14856, 14845, 14852, -1, 14856, 14850, 14845, -1, 14857, 12610, 12608, -1, 14857, 12608, 12505, -1, 14857, 12505, 14858, -1, 14857, 14851, 12610, -1, 14859, 14852, 14847, -1, 14859, 14847, 14853, -1, 14823, 14853, 14848, -1, 14860, 14816, 12510, -1, 14823, 14848, 14854, -1, 14860, 12510, 12618, -1, 14834, 14849, 14855, -1, 14834, 14854, 14849, -1, 14831, 14817, 14816, -1, 14861, 14855, 14851, -1, 14861, 14858, 14862, -1, 14861, 14857, 14858, -1, 14831, 14816, 14860, -1, 14861, 14851, 14857, -1, 14838, 12618, 12616, -1, 14863, 14856, 14852, -1, 14863, 12570, 12571, -1, 14863, 14852, 14859, -1, 14863, 12571, 14856, -1, 14838, 14860, 12618, -1, 14825, 14853, 14823, -1, 14825, 14859, 14853, -1, 14830, 14818, 14817, -1, 14830, 14817, 14831, -1, 14824, 14854, 14834, -1, 14833, 14860, 14838, -1, 14824, 14823, 14854, -1, 14832, 14861, 14862, -1, 14833, 14831, 14860, -1, 14832, 14862, 14827, -1, 14839, 12616, 12614, -1, 14832, 14855, 14861, -1, 14832, 14834, 14855, -1, 14836, 14859, 14825, -1, 14836, 12563, 12570, -1, 14839, 14838, 12616, -1, 14836, 12570, 14863, -1, 14846, 14819, 14818, -1, 14836, 14863, 14859, -1, 14846, 14818, 14830, -1, 14858, 12505, 12503, -1, 14858, 12503, 14864, -1, 14862, 14864, 14865, -1, 14862, 14858, 14864, -1, 14827, 14865, 14866, -1, 14827, 14862, 14865, -1, 14828, 14866, 14867, -1, 14828, 14827, 14866, -1, 14841, 14867, 14868, -1, 14841, 14828, 14867, -1, 14844, 14868, 14869, -1, 14844, 14841, 14868, -1, 12555, 14869, 12554, -1, 12555, 14844, 14869, -1, 14870, 14871, 14872, -1, 14870, 14872, 14873, -1, 14874, 14875, 14876, -1, 14874, 14873, 14877, -1, 14874, 14877, 14878, -1, 14874, 14878, 14875, -1, 14879, 14869, 14868, -1, 14879, 12554, 14869, -1, 14879, 12547, 12548, -1, 14879, 12548, 12554, -1, 14879, 14868, 14880, -1, 14881, 14871, 14870, -1, 14881, 14880, 14871, -1, 14882, 14876, 14883, -1, 14882, 14873, 14874, -1, 14882, 14874, 14876, -1, 14882, 14870, 14873, -1, 14884, 12547, 14879, -1, 14884, 14879, 14880, -1, 14884, 14880, 14881, -1, 14885, 14883, 14886, -1, 14885, 14882, 14883, -1, 14885, 14881, 14870, -1, 14885, 14870, 14882, -1, 14887, 14886, 14888, -1, 14887, 12543, 12547, -1, 14887, 12547, 14884, -1, 14887, 14888, 12543, -1, 14887, 14885, 14886, -1, 14887, 14884, 14881, -1, 14887, 14881, 14885, -1, 12540, 12543, 14888, -1, 14889, 14864, 12503, -1, 14889, 12503, 12639, -1, 14890, 14865, 14864, -1, 14890, 14864, 14889, -1, 14891, 12639, 12637, -1, 14891, 14889, 12639, -1, 14872, 14866, 14865, -1, 14872, 14865, 14890, -1, 14877, 14889, 14891, -1, 14877, 14890, 14889, -1, 14892, 12637, 12636, -1, 14892, 12636, 12495, -1, 14892, 12495, 14893, -1, 14892, 14891, 12637, -1, 14871, 14867, 14866, -1, 14871, 14866, 14872, -1, 14873, 14872, 14890, -1, 14873, 14890, 14877, -1, 14878, 14893, 14875, -1, 14878, 14892, 14893, -1, 14878, 14891, 14892, -1, 14878, 14877, 14891, -1, 14880, 14868, 14867, -1, 14880, 14867, 14871, -1, 12540, 14888, 11512, -1, 12495, 11551, 11550, -1, 14893, 11563, 11562, -1, 14893, 11576, 11563, -1, 14893, 11550, 11576, -1, 14893, 12495, 11550, -1, 14875, 11560, 11460, -1, 14875, 11561, 11560, -1, 14875, 11562, 11561, -1, 14875, 11459, 11530, -1, 14875, 11460, 11459, -1, 14875, 14893, 11562, -1, 14876, 11529, 11441, -1, 14876, 11530, 11529, -1, 14876, 14875, 11530, -1, 14883, 11440, 11483, -1, 14883, 11441, 11440, -1, 14883, 14876, 11441, -1, 14886, 11483, 11512, -1, 14886, 14883, 11483, -1, 14888, 14886, 11512, -1, 12540, 11512, 11538, -1, 10422, 10421, 14894, -1, 14894, 14895, 14896, -1, 10421, 14895, 14894, -1, 14896, 14897, 11213, -1, 14895, 14897, 14896, -1, 11213, 9066, 11214, -1, 14897, 9066, 11213, -1, 11214, 9068, 11206, -1, 9066, 9068, 11214, -1, 11206, 9071, 11207, -1, 9068, 9071, 11206, -1, 11207, 14368, 11200, -1, 9071, 14368, 11207, -1, 11200, 11805, 11199, -1, 14368, 11805, 11200, -1, 10420, 12052, 10421, -1, 10421, 12052, 14895, -1, 14895, 12053, 14897, -1, 12052, 12053, 14895, -1, 14897, 12054, 9066, -1, 12053, 12054, 14897, -1, 12054, 9067, 9066, -1, 14898, 11930, 11928, -1, 11929, 10652, 10650, -1, 11929, 10654, 10652, -1, 12441, 13620, 14899, -1, 11929, 10657, 10654, -1, 13618, 10665, 10662, -1, 13618, 10668, 10665, -1, 13618, 10491, 10668, -1, 11930, 14900, 11929, -1, 14898, 14900, 11930, -1, 14901, 14902, 14898, -1, 14898, 14902, 14900, -1, 14900, 14902, 11929, -1, 14903, 14904, 14901, -1, 14902, 14904, 11929, -1, 14901, 14904, 14902, -1, 11929, 14904, 10657, -1, 14905, 14906, 14903, -1, 10657, 14906, 10659, -1, 14903, 14906, 14904, -1, 14904, 14906, 10657, -1, 14907, 14908, 14905, -1, 10659, 14908, 10662, -1, 14905, 14908, 14906, -1, 14906, 14908, 10659, -1, 14909, 14910, 14907, -1, 14908, 14910, 10662, -1, 14907, 14910, 14908, -1, 10662, 14910, 13618, -1, 14911, 14912, 14909, -1, 14910, 14912, 13618, -1, 14909, 14912, 14910, -1, 13618, 14913, 13620, -1, 14899, 14913, 14911, -1, 14911, 14913, 14912, -1, 14912, 14913, 13618, -1, 13620, 14913, 14899, -1, 11928, 11948, 14898, -1, 14898, 14914, 14901, -1, 11948, 14914, 14898, -1, 14901, 14915, 14903, -1, 14914, 14915, 14901, -1, 14903, 14916, 14905, -1, 14915, 14916, 14903, -1, 14905, 14917, 14907, -1, 14916, 14917, 14905, -1, 14907, 14918, 14909, -1, 14917, 14918, 14907, -1, 14909, 14919, 14911, -1, 14918, 14919, 14909, -1, 14911, 14920, 14899, -1, 14919, 14920, 14911, -1, 14899, 14921, 12441, -1, 14920, 14921, 14899, -1, 14921, 12444, 12441, -1, 14922, 14923, 14924, -1, 14925, 14926, 14927, -1, 14927, 14926, 14928, -1, 12444, 14921, 13398, -1, 14916, 14929, 14917, -1, 14917, 14929, 14930, -1, 14930, 14931, 14922, -1, 14922, 14931, 14923, -1, 13404, 14932, 12446, -1, 12446, 14932, 14933, -1, 14928, 14932, 13404, -1, 14923, 14934, 14925, -1, 14925, 14934, 14926, -1, 14915, 14935, 14916, -1, 14916, 14935, 14929, -1, 14933, 14936, 14937, -1, 14926, 14936, 14928, -1, 14932, 14936, 14933, -1, 14928, 14936, 14932, -1, 14930, 14938, 14931, -1, 14929, 14938, 14930, -1, 14931, 14939, 14923, -1, 14923, 14939, 14934, -1, 11948, 11953, 14914, -1, 14937, 14940, 14941, -1, 14926, 14940, 14936, -1, 14934, 14940, 14926, -1, 14936, 14940, 14937, -1, 14914, 14942, 14915, -1, 14915, 14942, 14935, -1, 11953, 14942, 14914, -1, 14935, 14943, 14929, -1, 14929, 14943, 14938, -1, 14931, 14944, 14939, -1, 14938, 14944, 14931, -1, 14939, 14945, 14934, -1, 14941, 14945, 14946, -1, 14934, 14945, 14940, -1, 14940, 14945, 14941, -1, 14942, 14947, 14935, -1, 11955, 14947, 11953, -1, 11956, 14947, 11955, -1, 11953, 14947, 14942, -1, 14935, 14947, 14943, -1, 14943, 14948, 14938, -1, 14938, 14948, 14944, -1, 11961, 11881, 14949, -1, 13398, 14950, 13400, -1, 14944, 14951, 14939, -1, 14945, 14951, 14946, -1, 14939, 14951, 14945, -1, 14921, 14950, 13398, -1, 11959, 14952, 11956, -1, 11956, 14952, 14947, -1, 14943, 14952, 14948, -1, 14947, 14952, 14943, -1, 14920, 14924, 14921, -1, 14946, 14953, 14954, -1, 14948, 14953, 14944, -1, 14921, 14924, 14950, -1, 14944, 14953, 14951, -1, 13400, 14927, 13402, -1, 14951, 14953, 14946, -1, 14950, 14927, 13400, -1, 14954, 14955, 14949, -1, 11961, 14955, 11959, -1, 11959, 14955, 14952, -1, 14953, 14955, 14954, -1, 14952, 14955, 14948, -1, 14948, 14955, 14953, -1, 14949, 14955, 11961, -1, 14919, 14922, 14920, -1, 14920, 14922, 14924, -1, 14950, 14925, 14927, -1, 14924, 14925, 14950, -1, 13402, 14928, 13404, -1, 14927, 14928, 13402, -1, 14917, 14930, 14918, -1, 14918, 14930, 14919, -1, 14919, 14930, 14922, -1, 14924, 14923, 14925, -1, 11881, 11880, 14949, -1, 14949, 14956, 14954, -1, 11880, 14956, 14949, -1, 14954, 14957, 14946, -1, 14956, 14957, 14954, -1, 14946, 14958, 14941, -1, 14957, 14958, 14946, -1, 14941, 14959, 14937, -1, 14958, 14959, 14941, -1, 14937, 14960, 14933, -1, 14959, 14960, 14937, -1, 14960, 14961, 14933, -1, 14933, 12447, 12446, -1, 14961, 12447, 14933, -1, 9056, 14962, 9059, -1, 14963, 14962, 14964, -1, 14965, 14966, 14967, -1, 14964, 14962, 9056, -1, 11984, 14968, 11983, -1, 14967, 14966, 14969, -1, 11983, 14968, 14970, -1, 14971, 14968, 14972, -1, 14973, 14974, 14965, -1, 14970, 14968, 14971, -1, 14961, 13419, 12447, -1, 14965, 14974, 14966, -1, 9059, 14975, 9062, -1, 14976, 14975, 14962, -1, 14977, 14975, 14976, -1, 14962, 14975, 9059, -1, 13417, 14978, 13416, -1, 11984, 14979, 14968, -1, 14969, 14978, 13417, -1, 11985, 14979, 11984, -1, 14972, 14979, 14977, -1, 14968, 14979, 14972, -1, 14956, 14980, 14957, -1, 11986, 14981, 11985, -1, 14975, 14981, 9062, -1, 14957, 14980, 14982, -1, 14979, 14981, 14977, -1, 11993, 14980, 14956, -1, 14977, 14981, 14975, -1, 9062, 14981, 11986, -1, 11985, 14981, 14979, -1, 14969, 14983, 14978, -1, 14966, 14983, 14969, -1, 14973, 14984, 14974, -1, 14982, 14984, 14973, -1, 14974, 14985, 14966, -1, 14966, 14985, 14983, -1, 13415, 14986, 13413, -1, 13416, 14986, 13415, -1, 14978, 14986, 13416, -1, 11880, 11993, 14956, -1, 11990, 14987, 11993, -1, 11993, 14987, 14980, -1, 14982, 14987, 14984, -1, 14980, 14987, 14982, -1, 14983, 14988, 14978, -1, 14978, 14988, 14986, -1, 14984, 14989, 14974, -1, 14974, 14989, 14985, -1, 14986, 14990, 13413, -1, 14983, 14991, 14988, -1, 14985, 14991, 14983, -1, 14986, 14992, 14990, -1, 14988, 14992, 14986, -1, 13408, 9054, 9053, -1, 13412, 14993, 13410, -1, 13413, 14993, 13412, -1, 14990, 14993, 13413, -1, 11988, 14994, 11990, -1, 14984, 14994, 14989, -1, 11990, 14994, 14987, -1, 14987, 14994, 14984, -1, 14989, 14971, 14985, -1, 14985, 14971, 14991, -1, 14988, 14995, 14992, -1, 14991, 14995, 14988, -1, 14990, 14963, 14993, -1, 14992, 14963, 14990, -1, 11986, 9064, 9062, -1, 13410, 14996, 13408, -1, 14960, 14967, 14961, -1, 13408, 14996, 9054, -1, 13419, 14967, 13418, -1, 14993, 14996, 13410, -1, 14961, 14967, 13419, -1, 14971, 14972, 14991, -1, 14991, 14972, 14995, -1, 14995, 14976, 14992, -1, 14960, 14965, 14967, -1, 14992, 14976, 14963, -1, 14958, 14973, 14959, -1, 14959, 14973, 14960, -1, 11983, 14970, 11988, -1, 14994, 14970, 14989, -1, 14960, 14973, 14965, -1, 14989, 14970, 14971, -1, 11988, 14970, 14994, -1, 13418, 14969, 13417, -1, 9054, 14964, 9056, -1, 14996, 14964, 9054, -1, 14993, 14964, 14996, -1, 14967, 14969, 13418, -1, 14963, 14964, 14993, -1, 14957, 14982, 14958, -1, 14972, 14977, 14995, -1, 14995, 14977, 14976, -1, 14958, 14982, 14973, -1, 14976, 14962, 14963, -1, 12440, 9058, 14997, -1, 14997, 9057, 14998, -1, 9058, 9057, 14997, -1, 14998, 9060, 14999, -1, 9057, 9060, 14998, -1, 14999, 9061, 15000, -1, 9060, 9061, 14999, -1, 15000, 9063, 11960, -1, 9061, 9063, 15000, -1, 9063, 9065, 11960, -1, 14997, 13624, 12440, -1, 11960, 11857, 15000, -1, 13622, 15001, 10493, -1, 13622, 15002, 15001, -1, 11856, 15003, 13622, -1, 13622, 15003, 15002, -1, 11856, 15004, 15003, -1, 11856, 11858, 15004, -1, 13624, 15005, 13622, -1, 14997, 15005, 13624, -1, 14998, 15006, 14997, -1, 14997, 15006, 15005, -1, 15005, 15006, 13622, -1, 14999, 15007, 14998, -1, 15006, 15007, 13622, -1, 14998, 15007, 15006, -1, 13622, 15007, 11856, -1, 11856, 15008, 11857, -1, 15000, 15008, 14999, -1, 15007, 15008, 11856, -1, 14999, 15008, 15007, -1, 11857, 15008, 15000, -1, 10492, 10493, 15009, -1, 15009, 15001, 15010, -1, 10493, 15001, 15009, -1, 15010, 15002, 11018, -1, 15001, 15002, 15010, -1, 11018, 15003, 11019, -1, 11019, 15003, 11030, -1, 15002, 15003, 11018, -1, 11030, 15004, 11025, -1, 11025, 15004, 11017, -1, 15003, 15004, 11030, -1, 11017, 11858, 11016, -1, 15004, 11858, 11017, -1, 13623, 9050, 9051, -1, 13623, 9048, 9050, -1, 10160, 15011, 15012, -1, 10160, 10233, 15011, -1, 10070, 15013, 10072, -1, 13621, 15013, 13623, -1, 10072, 15013, 13621, -1, 10066, 15014, 10070, -1, 10070, 15014, 15013, -1, 15013, 15014, 13623, -1, 10065, 15015, 10066, -1, 15014, 15015, 13623, -1, 10066, 15015, 15014, -1, 10681, 15016, 10683, -1, 10683, 15016, 10065, -1, 10065, 15016, 15015, -1, 10681, 15017, 15016, -1, 10679, 15018, 10681, -1, 10681, 15018, 15017, -1, 10158, 15019, 10147, -1, 10160, 15019, 10158, -1, 10147, 15019, 10677, -1, 10677, 15019, 10679, -1, 15018, 15019, 10160, -1, 10679, 15019, 15018, -1, 9048, 15020, 9047, -1, 15021, 15020, 15012, -1, 15022, 15020, 15021, -1, 9047, 15020, 15022, -1, 15018, 15020, 15017, -1, 15016, 15020, 15015, -1, 10160, 15020, 15018, -1, 15017, 15020, 15016, -1, 13623, 15020, 9048, -1, 15012, 15020, 10160, -1, 15015, 15020, 13623, -1, 10233, 10232, 15011, -1, 10232, 15023, 15011, -1, 15011, 15024, 15012, -1, 15023, 15024, 15011, -1, 15012, 15025, 15021, -1, 15024, 15025, 15012, -1, 15021, 15026, 15022, -1, 15025, 15026, 15021, -1, 15022, 9045, 9047, -1, 15026, 9045, 15022, -1, 15027, 15028, 9014, -1, 15029, 15028, 15027, -1, 15030, 15028, 15029, -1, 15025, 15031, 15026, -1, 9049, 13407, 9052, -1, 15026, 15031, 15032, -1, 15032, 15033, 15034, -1, 15034, 15033, 15035, -1, 9036, 15036, 9039, -1, 15035, 15036, 15030, -1, 15030, 15036, 15028, -1, 15028, 15036, 9036, -1, 15024, 15037, 15025, -1, 15025, 15037, 15031, -1, 15032, 15038, 15033, -1, 15031, 15038, 15032, -1, 9039, 15039, 9044, -1, 15035, 15039, 15036, -1, 15036, 15039, 9039, -1, 15033, 15039, 15035, -1, 10239, 15040, 10232, -1, 10232, 15040, 15023, -1, 15023, 15040, 15024, -1, 15024, 15040, 15037, -1, 13414, 9014, 9013, -1, 15037, 15041, 15031, -1, 15031, 15041, 15038, -1, 9044, 15042, 9020, -1, 15039, 15042, 9044, -1, 15038, 15042, 15033, -1, 15033, 15042, 15039, -1, 10241, 15043, 10239, -1, 10249, 15043, 10241, -1, 10239, 15043, 15040, -1, 15040, 15043, 15037, -1, 15037, 15043, 15041, -1, 9020, 15044, 9019, -1, 15042, 15044, 9020, -1, 15041, 15044, 15038, -1, 15038, 15044, 15042, -1, 10249, 15045, 15043, -1, 10253, 15045, 10249, -1, 15041, 15045, 15044, -1, 15044, 15045, 9019, -1, 9019, 15045, 10253, -1, 15043, 15045, 15041, -1, 10253, 9018, 9019, -1, 13407, 15046, 13409, -1, 9049, 15046, 13407, -1, 9046, 15047, 9049, -1, 9049, 15047, 15046, -1, 13409, 15029, 13411, -1, 15046, 15029, 13409, -1, 9045, 15034, 9046, -1, 9046, 15034, 15047, -1, 15046, 15030, 15029, -1, 15047, 15030, 15046, -1, 15026, 15032, 9045, -1, 9045, 15032, 15034, -1, 13411, 15027, 13414, -1, 13414, 15027, 9014, -1, 15029, 15027, 13411, -1, 15034, 15035, 15047, -1, 15047, 15035, 15030, -1, 9014, 15028, 9036, -1, 9032, 10193, 9030, -1, 9030, 15048, 9028, -1, 10193, 15048, 9030, -1, 9028, 15049, 9024, -1, 15048, 15049, 9028, -1, 15049, 15050, 9024, -1, 9024, 15051, 9010, -1, 15050, 15051, 9024, -1, 9010, 15052, 9008, -1, 15051, 15052, 9010, -1, 9008, 15053, 9042, -1, 15052, 15053, 9008, -1, 9042, 12445, 9040, -1, 15053, 12445, 9042, -1, 15049, 15054, 15050, -1, 15050, 15054, 15055, -1, 15056, 15057, 15058, -1, 15055, 15057, 15056, -1, 15059, 15060, 15061, -1, 15061, 15060, 15062, -1, 13399, 15063, 15064, -1, 15062, 15063, 13399, -1, 10331, 15065, 10193, -1, 10328, 15065, 10331, -1, 10193, 15065, 15048, -1, 15048, 15065, 15049, -1, 15049, 15065, 15054, -1, 15055, 15066, 15057, -1, 15054, 15066, 15055, -1, 15058, 15067, 15059, -1, 15059, 15067, 15060, -1, 13399, 15064, 12442, -1, 15064, 15068, 15069, -1, 15060, 15068, 15062, -1, 15063, 15068, 15064, -1, 15062, 15068, 15063, -1, 10327, 15070, 10328, -1, 10328, 15070, 15065, -1, 15065, 15070, 15054, -1, 15054, 15070, 15066, -1, 15058, 15071, 15067, -1, 15057, 15071, 15058, -1, 15069, 15072, 15073, -1, 15060, 15072, 15068, -1, 15068, 15072, 15069, -1, 15067, 15072, 15060, -1, 15057, 15074, 15071, -1, 15066, 15074, 15057, -1, 15067, 15075, 15072, -1, 15073, 15075, 15076, -1, 15072, 15075, 15073, -1, 15071, 15075, 15067, -1, 15066, 15077, 15074, -1, 10320, 15077, 10327, -1, 10327, 15077, 15070, -1, 15070, 15077, 15066, -1, 15074, 15078, 15071, -1, 15076, 15078, 15079, -1, 15075, 15078, 15076, -1, 15071, 15078, 15075, -1, 10313, 10295, 15080, -1, 15074, 15081, 15078, -1, 15079, 15081, 15080, -1, 10313, 15081, 10320, -1, 10320, 15081, 15077, -1, 12445, 15082, 13406, -1, 15080, 15081, 10313, -1, 15078, 15081, 15079, -1, 15077, 15081, 15074, -1, 15053, 15082, 12445, -1, 15052, 15083, 15053, -1, 15053, 15083, 15082, -1, 13405, 15061, 13403, -1, 13406, 15061, 13405, -1, 15082, 15061, 13406, -1, 15051, 15056, 15052, -1, 15052, 15056, 15083, -1, 15082, 15059, 15061, -1, 15083, 15059, 15082, -1, 15050, 15055, 15051, -1, 15051, 15055, 15056, -1, 15056, 15058, 15083, -1, 15083, 15058, 15059, -1, 13401, 15062, 13399, -1, 13403, 15062, 13401, -1, 15061, 15062, 13403, -1, 12443, 12442, 15084, -1, 15084, 15064, 15085, -1, 12442, 15064, 15084, -1, 15085, 15069, 15086, -1, 15064, 15069, 15085, -1, 15086, 15073, 15087, -1, 15069, 15073, 15086, -1, 15087, 15076, 15088, -1, 15073, 15076, 15087, -1, 15088, 15079, 15089, -1, 15076, 15079, 15088, -1, 15079, 15080, 15089, -1, 15089, 10295, 10292, -1, 15080, 10295, 15089, -1, 10361, 15089, 10292, -1, 10361, 15088, 15089, -1, 10361, 15087, 15088, -1, 13619, 15085, 15086, -1, 13619, 15084, 15085, -1, 13619, 12443, 15084, -1, 10687, 15090, 10144, -1, 10362, 15090, 10361, -1, 10144, 15090, 10362, -1, 10690, 15091, 10687, -1, 10687, 15091, 15090, -1, 15090, 15091, 10361, -1, 10691, 15092, 10690, -1, 15091, 15092, 10361, -1, 10690, 15092, 15091, -1, 10361, 15092, 15087, -1, 10693, 15093, 10691, -1, 15087, 15093, 15086, -1, 15092, 15093, 15087, -1, 15086, 15093, 13619, -1, 10691, 15093, 15092, -1, 10695, 15094, 10693, -1, 10697, 15094, 10695, -1, 15093, 15094, 13619, -1, 10693, 15094, 15093, -1, 13617, 15095, 10490, -1, 13619, 15095, 13617, -1, 10490, 15095, 10697, -1, 10697, 15095, 15094, -1, 15094, 15095, 13619, -1, 15096, 11996, 11774, -1, 11995, 10702, 10700, -1, 11995, 10704, 10702, -1, 12457, 13604, 15097, -1, 11995, 10707, 10704, -1, 13602, 10715, 10712, -1, 13602, 10718, 10715, -1, 13602, 10477, 10718, -1, 11996, 15098, 11995, -1, 15096, 15098, 11996, -1, 15099, 15100, 15096, -1, 15096, 15100, 15098, -1, 15098, 15100, 11995, -1, 15101, 15102, 15099, -1, 15100, 15102, 11995, -1, 15099, 15102, 15100, -1, 11995, 15102, 10707, -1, 15103, 15104, 15101, -1, 10707, 15104, 10709, -1, 15101, 15104, 15102, -1, 15102, 15104, 10707, -1, 15105, 15106, 15103, -1, 10709, 15106, 10712, -1, 15103, 15106, 15104, -1, 15104, 15106, 10709, -1, 15107, 15108, 15105, -1, 15106, 15108, 10712, -1, 15105, 15108, 15106, -1, 10712, 15108, 13602, -1, 15109, 15110, 15107, -1, 15108, 15110, 13602, -1, 15107, 15110, 15108, -1, 13602, 15111, 13604, -1, 15097, 15111, 15109, -1, 15109, 15111, 15110, -1, 15110, 15111, 13602, -1, 13604, 15111, 15097, -1, 11797, 15112, 11774, -1, 11774, 15112, 15096, -1, 15096, 15113, 15099, -1, 15112, 15113, 15096, -1, 15099, 15114, 15101, -1, 15113, 15114, 15099, -1, 15101, 15115, 15103, -1, 15114, 15115, 15101, -1, 15103, 15116, 15105, -1, 15115, 15116, 15103, -1, 15105, 15117, 15107, -1, 15116, 15117, 15105, -1, 15107, 15118, 15109, -1, 15117, 15118, 15107, -1, 15109, 15119, 15097, -1, 15118, 15119, 15109, -1, 15097, 12460, 12457, -1, 15119, 12460, 15097, -1, 15120, 15121, 15122, -1, 15123, 15124, 15125, -1, 15125, 15124, 15126, -1, 12460, 15119, 13455, -1, 15114, 15127, 15115, -1, 15115, 15127, 15128, -1, 15128, 15129, 15120, -1, 15120, 15129, 15121, -1, 13461, 15130, 12462, -1, 12462, 15130, 15131, -1, 15126, 15130, 13461, -1, 15121, 15132, 15123, -1, 15123, 15132, 15124, -1, 15113, 15133, 15114, -1, 15114, 15133, 15127, -1, 15131, 15134, 15135, -1, 15124, 15134, 15126, -1, 15130, 15134, 15131, -1, 15126, 15134, 15130, -1, 15128, 15136, 15129, -1, 15127, 15136, 15128, -1, 15129, 15137, 15121, -1, 15121, 15137, 15132, -1, 11797, 11804, 15112, -1, 15135, 15138, 15139, -1, 15124, 15138, 15134, -1, 15132, 15138, 15124, -1, 15134, 15138, 15135, -1, 15112, 15140, 15113, -1, 15113, 15140, 15133, -1, 11804, 15140, 15112, -1, 15133, 15141, 15127, -1, 15127, 15141, 15136, -1, 15129, 15142, 15137, -1, 15136, 15142, 15129, -1, 15137, 15143, 15132, -1, 15139, 15143, 15144, -1, 15132, 15143, 15138, -1, 15138, 15143, 15139, -1, 15140, 15145, 15133, -1, 11807, 15145, 11804, -1, 11809, 15145, 11807, -1, 11804, 15145, 15140, -1, 15133, 15145, 15141, -1, 15141, 15146, 15136, -1, 15136, 15146, 15142, -1, 11814, 11831, 15147, -1, 13455, 15148, 13457, -1, 15142, 15149, 15137, -1, 15143, 15149, 15144, -1, 15137, 15149, 15143, -1, 15119, 15148, 13455, -1, 11811, 15150, 11809, -1, 11809, 15150, 15145, -1, 15141, 15150, 15146, -1, 15145, 15150, 15141, -1, 15118, 15122, 15119, -1, 15144, 15151, 15152, -1, 15146, 15151, 15142, -1, 15119, 15122, 15148, -1, 15142, 15151, 15149, -1, 13457, 15125, 13459, -1, 15149, 15151, 15144, -1, 15148, 15125, 13457, -1, 15152, 15153, 15147, -1, 11814, 15153, 11811, -1, 11811, 15153, 15150, -1, 15151, 15153, 15152, -1, 15150, 15153, 15146, -1, 15146, 15153, 15151, -1, 15147, 15153, 11814, -1, 15117, 15120, 15118, -1, 15118, 15120, 15122, -1, 15148, 15123, 15125, -1, 15122, 15123, 15148, -1, 13459, 15126, 13461, -1, 15125, 15126, 13459, -1, 15115, 15128, 15116, -1, 15116, 15128, 15117, -1, 15117, 15128, 15120, -1, 15122, 15121, 15123, -1, 11838, 15154, 11831, -1, 11831, 15154, 15147, -1, 15147, 15155, 15152, -1, 15154, 15155, 15147, -1, 15152, 15156, 15144, -1, 15155, 15156, 15152, -1, 15144, 15157, 15139, -1, 15156, 15157, 15144, -1, 15139, 15158, 15135, -1, 15157, 15158, 15139, -1, 15135, 15159, 15131, -1, 15158, 15159, 15135, -1, 15131, 12463, 12462, -1, 15159, 12463, 15131, -1, 8994, 15160, 8997, -1, 15161, 15160, 8994, -1, 15162, 15160, 15161, -1, 15163, 15164, 15165, -1, 15165, 15164, 15166, -1, 11843, 15167, 11842, -1, 15168, 15167, 15169, -1, 15170, 15171, 15163, -1, 15172, 15167, 15168, -1, 11842, 15167, 15172, -1, 15159, 13454, 12463, -1, 15163, 15171, 15164, -1, 15173, 15174, 15175, -1, 15175, 15174, 15160, -1, 15160, 15174, 8997, -1, 13452, 15176, 13451, -1, 15166, 15176, 13452, -1, 11844, 15177, 11843, -1, 11843, 15177, 15167, -1, 15167, 15177, 15169, -1, 15169, 15177, 15173, -1, 15154, 15178, 15155, -1, 11845, 15179, 11844, -1, 8997, 15179, 9000, -1, 15155, 15178, 15180, -1, 11844, 15179, 15177, -1, 11839, 15178, 15154, -1, 15174, 15179, 8997, -1, 15173, 15179, 15174, -1, 15177, 15179, 15173, -1, 9000, 15179, 11845, -1, 15166, 15181, 15176, -1, 15164, 15181, 15166, -1, 15170, 15182, 15171, -1, 15180, 15182, 15170, -1, 15164, 15183, 15181, -1, 15171, 15183, 15164, -1, 13450, 15184, 13448, -1, 13451, 15184, 13450, -1, 11838, 11839, 15154, -1, 15176, 15184, 13451, -1, 11840, 15185, 11839, -1, 11839, 15185, 15178, -1, 15180, 15185, 15182, -1, 15178, 15185, 15180, -1, 15181, 15186, 15176, -1, 15176, 15186, 15184, -1, 15182, 15187, 15171, -1, 15171, 15187, 15183, -1, 15184, 15188, 13448, -1, 15183, 15189, 15181, -1, 15181, 15189, 15186, -1, 15186, 15190, 15184, -1, 15184, 15190, 15188, -1, 13443, 8992, 8991, -1, 15188, 15191, 13448, -1, 13447, 15191, 13445, -1, 13448, 15191, 13447, -1, 11841, 15192, 11840, -1, 15182, 15192, 15187, -1, 11840, 15192, 15185, -1, 15185, 15192, 15182, -1, 15183, 15168, 15189, -1, 15187, 15168, 15183, -1, 15189, 15193, 15186, -1, 15186, 15193, 15190, -1, 15190, 15162, 15188, -1, 11845, 9002, 9000, -1, 15188, 15162, 15191, -1, 15191, 15194, 13445, -1, 13445, 15194, 13443, -1, 13454, 15165, 13453, -1, 15159, 15165, 13454, -1, 13443, 15194, 8992, -1, 15189, 15169, 15193, -1, 15158, 15163, 15159, -1, 15168, 15169, 15189, -1, 15159, 15163, 15165, -1, 15193, 15175, 15190, -1, 15190, 15175, 15162, -1, 15156, 15170, 15157, -1, 15157, 15170, 15158, -1, 11842, 15172, 11841, -1, 15187, 15172, 15168, -1, 15158, 15170, 15163, -1, 15192, 15172, 15187, -1, 11841, 15172, 15192, -1, 13453, 15166, 13452, -1, 8992, 15161, 8994, -1, 15191, 15161, 15194, -1, 15194, 15161, 8992, -1, 15165, 15166, 13453, -1, 15162, 15161, 15191, -1, 15155, 15180, 15156, -1, 15169, 15173, 15193, -1, 15156, 15180, 15170, -1, 15193, 15173, 15175, -1, 15175, 15160, 15162, -1, 8996, 8995, 12456, -1, 12456, 8995, 15195, -1, 15195, 8998, 15196, -1, 8995, 8998, 15195, -1, 15196, 8999, 15197, -1, 8998, 8999, 15196, -1, 15197, 9001, 15198, -1, 8999, 9001, 15197, -1, 15198, 9003, 11816, -1, 9001, 9003, 15198, -1, 15195, 13608, 12456, -1, 11816, 11792, 15198, -1, 13606, 15199, 10479, -1, 13606, 15200, 15199, -1, 11786, 15201, 13606, -1, 13606, 15201, 15200, -1, 11786, 15202, 15201, -1, 11786, 11783, 15202, -1, 13608, 15203, 13606, -1, 15195, 15203, 13608, -1, 15196, 15204, 15195, -1, 15195, 15204, 15203, -1, 15203, 15204, 13606, -1, 15197, 15205, 15196, -1, 15204, 15205, 13606, -1, 15196, 15205, 15204, -1, 13606, 15205, 11786, -1, 11786, 15206, 11792, -1, 15198, 15206, 15197, -1, 15205, 15206, 11786, -1, 15197, 15206, 15205, -1, 11792, 15206, 15198, -1, 10478, 10479, 10723, -1, 10723, 15199, 10720, -1, 10479, 15199, 10723, -1, 10720, 15200, 10643, -1, 15199, 15200, 10720, -1, 10644, 15201, 10646, -1, 10643, 15201, 10644, -1, 15200, 15201, 10643, -1, 10646, 15202, 10647, -1, 15201, 15202, 10646, -1, 10647, 11783, 10648, -1, 15202, 11783, 10647, -1, 15207, 11964, 11962, -1, 11963, 10729, 10727, -1, 11963, 10731, 10729, -1, 12449, 13612, 15208, -1, 11963, 10734, 10731, -1, 13610, 10742, 10739, -1, 13610, 10745, 10742, -1, 13610, 10484, 10745, -1, 11964, 15209, 11963, -1, 15207, 15209, 11964, -1, 15210, 15211, 15207, -1, 15207, 15211, 15209, -1, 15209, 15211, 11963, -1, 15212, 15213, 15210, -1, 15211, 15213, 11963, -1, 15210, 15213, 15211, -1, 11963, 15213, 10734, -1, 15214, 15215, 15212, -1, 10734, 15215, 10736, -1, 15212, 15215, 15213, -1, 15213, 15215, 10734, -1, 15216, 15217, 15214, -1, 10736, 15217, 10739, -1, 15214, 15217, 15215, -1, 15215, 15217, 10736, -1, 15218, 15219, 15216, -1, 15217, 15219, 10739, -1, 15216, 15219, 15217, -1, 10739, 15219, 13610, -1, 15220, 15221, 15218, -1, 15219, 15221, 13610, -1, 15218, 15221, 15219, -1, 13610, 15222, 13612, -1, 15208, 15222, 15220, -1, 15220, 15222, 15221, -1, 15221, 15222, 13610, -1, 13612, 15222, 15208, -1, 11982, 15223, 11962, -1, 11962, 15223, 15207, -1, 15207, 15224, 15210, -1, 15223, 15224, 15207, -1, 15210, 15225, 15212, -1, 15224, 15225, 15210, -1, 15212, 15226, 15214, -1, 15225, 15226, 15212, -1, 15214, 15227, 15216, -1, 15226, 15227, 15214, -1, 15216, 15228, 15218, -1, 15227, 15228, 15216, -1, 15218, 15229, 15220, -1, 15228, 15229, 15218, -1, 15220, 15230, 15208, -1, 15229, 15230, 15220, -1, 15208, 12452, 12449, -1, 15230, 12452, 15208, -1, 15231, 15232, 15233, -1, 15234, 15235, 15236, -1, 15236, 15235, 15237, -1, 12452, 15230, 13420, -1, 15225, 15238, 15226, -1, 15226, 15238, 15239, -1, 15239, 15240, 15231, -1, 15231, 15240, 15232, -1, 13426, 15241, 12454, -1, 12454, 15241, 15242, -1, 15237, 15241, 13426, -1, 15234, 15243, 15235, -1, 15232, 15243, 15234, -1, 15224, 15244, 15225, -1, 15225, 15244, 15238, -1, 15242, 15245, 15246, -1, 15241, 15245, 15242, -1, 15235, 15245, 15237, -1, 15237, 15245, 15241, -1, 15239, 15247, 15240, -1, 15238, 15247, 15239, -1, 15240, 15248, 15232, -1, 15232, 15248, 15243, -1, 11982, 11987, 15223, -1, 15246, 15249, 15250, -1, 15243, 15249, 15235, -1, 15245, 15249, 15246, -1, 15235, 15249, 15245, -1, 15223, 15251, 15224, -1, 15224, 15251, 15244, -1, 11987, 15251, 15223, -1, 15244, 15252, 15238, -1, 15238, 15252, 15247, -1, 15240, 15253, 15248, -1, 15247, 15253, 15240, -1, 15248, 15254, 15243, -1, 15250, 15254, 15255, -1, 15243, 15254, 15249, -1, 15249, 15254, 15250, -1, 15251, 15256, 15244, -1, 11989, 15256, 11987, -1, 11991, 15256, 11989, -1, 11987, 15256, 15251, -1, 15244, 15256, 15252, -1, 15252, 15257, 15247, -1, 15247, 15257, 15253, -1, 11994, 11879, 15258, -1, 13420, 15259, 13422, -1, 15253, 15260, 15248, -1, 15254, 15260, 15255, -1, 15248, 15260, 15254, -1, 15230, 15259, 13420, -1, 11992, 15261, 11991, -1, 11991, 15261, 15256, -1, 15252, 15261, 15257, -1, 15256, 15261, 15252, -1, 15229, 15233, 15230, -1, 15255, 15262, 15263, -1, 15257, 15262, 15253, -1, 15230, 15233, 15259, -1, 15253, 15262, 15260, -1, 13422, 15236, 13424, -1, 15260, 15262, 15255, -1, 15259, 15236, 13422, -1, 15263, 15264, 15258, -1, 11994, 15264, 11992, -1, 11992, 15264, 15261, -1, 15262, 15264, 15263, -1, 15261, 15264, 15257, -1, 15257, 15264, 15262, -1, 15258, 15264, 11994, -1, 15228, 15231, 15229, -1, 15229, 15231, 15233, -1, 15259, 15234, 15236, -1, 15233, 15234, 15259, -1, 13424, 15237, 13426, -1, 15236, 15237, 13424, -1, 15226, 15239, 15227, -1, 15227, 15239, 15228, -1, 15228, 15239, 15231, -1, 15233, 15232, 15234, -1, 11879, 11832, 15258, -1, 15258, 15265, 15263, -1, 11832, 15265, 15258, -1, 15263, 15266, 15255, -1, 15265, 15266, 15263, -1, 15255, 15267, 15250, -1, 15266, 15267, 15255, -1, 15250, 15268, 15246, -1, 15267, 15268, 15250, -1, 15246, 15269, 15242, -1, 15268, 15269, 15246, -1, 15242, 15270, 12454, -1, 15269, 15270, 15242, -1, 15270, 12455, 12454, -1, 8981, 15271, 8985, -1, 15272, 15271, 15273, -1, 15274, 15275, 15276, -1, 15273, 15271, 8981, -1, 11799, 15277, 11798, -1, 15276, 15275, 15278, -1, 11798, 15277, 15279, -1, 15280, 15277, 15281, -1, 15282, 15283, 15274, -1, 15274, 15283, 15275, -1, 15279, 15277, 15280, -1, 15270, 13441, 12455, -1, 8985, 15284, 8987, -1, 15285, 15284, 15271, -1, 15286, 15284, 15285, -1, 15271, 15284, 8985, -1, 13439, 15287, 13438, -1, 15278, 15287, 13439, -1, 11799, 15288, 15277, -1, 11800, 15288, 11799, -1, 15281, 15288, 15286, -1, 15277, 15288, 15281, -1, 15265, 15289, 15266, -1, 11802, 15290, 11800, -1, 11800, 15290, 15288, -1, 15266, 15289, 15291, -1, 15284, 15290, 8987, -1, 11810, 15289, 15265, -1, 15288, 15290, 15286, -1, 15286, 15290, 15284, -1, 8987, 15290, 11802, -1, 15278, 15292, 15287, -1, 15275, 15292, 15278, -1, 15282, 15293, 15283, -1, 15291, 15293, 15282, -1, 15275, 15294, 15292, -1, 15283, 15294, 15275, -1, 13437, 15295, 13435, -1, 13438, 15295, 13437, -1, 15287, 15295, 13438, -1, 11832, 11810, 15265, -1, 11808, 15296, 11810, -1, 11810, 15296, 15289, -1, 15291, 15296, 15293, -1, 15289, 15296, 15291, -1, 15292, 15297, 15287, -1, 15287, 15297, 15295, -1, 15293, 15298, 15283, -1, 15283, 15298, 15294, -1, 15295, 15299, 13435, -1, 15294, 15300, 15292, -1, 15292, 15300, 15297, -1, 15297, 15301, 15295, -1, 15295, 15301, 15299, -1, 15299, 15302, 13435, -1, 13430, 8979, 8978, -1, 13434, 15302, 13432, -1, 13435, 15302, 13434, -1, 11806, 15303, 11808, -1, 15293, 15303, 15298, -1, 11808, 15303, 15296, -1, 15296, 15303, 15293, -1, 15298, 15280, 15294, -1, 15294, 15280, 15300, -1, 15297, 15304, 15301, -1, 15300, 15304, 15297, -1, 15301, 15272, 15299, -1, 11802, 8989, 8987, -1, 15299, 15272, 15302, -1, 15302, 15305, 13432, -1, 13432, 15305, 13430, -1, 13441, 15276, 13440, -1, 15270, 15276, 13441, -1, 13430, 15305, 8979, -1, 15300, 15281, 15304, -1, 15280, 15281, 15300, -1, 15268, 15274, 15269, -1, 15269, 15274, 15270, -1, 15304, 15285, 15301, -1, 15301, 15285, 15272, -1, 15270, 15274, 15276, -1, 15267, 15282, 15268, -1, 11798, 15279, 11806, -1, 15268, 15282, 15274, -1, 15298, 15279, 15280, -1, 11806, 15279, 15303, -1, 15303, 15279, 15298, -1, 13440, 15278, 13439, -1, 15272, 15273, 15302, -1, 15302, 15273, 15305, -1, 8979, 15273, 8981, -1, 15276, 15278, 13440, -1, 15305, 15273, 8979, -1, 15266, 15291, 15267, -1, 15281, 15286, 15304, -1, 15267, 15291, 15282, -1, 15304, 15286, 15285, -1, 15285, 15271, 15272, -1, 8983, 8982, 12448, -1, 12448, 8982, 15306, -1, 15306, 8984, 15307, -1, 8982, 8984, 15306, -1, 15307, 8986, 15308, -1, 8984, 8986, 15307, -1, 15308, 8988, 15309, -1, 8986, 8988, 15308, -1, 15309, 8990, 11773, -1, 8988, 8990, 15309, -1, 15306, 13616, 12448, -1, 11773, 11892, 15309, -1, 13614, 15310, 10486, -1, 13614, 15311, 15310, -1, 11891, 15312, 13614, -1, 13614, 15312, 15311, -1, 11891, 15313, 15312, -1, 11891, 11853, 15313, -1, 13616, 15314, 13614, -1, 15306, 15314, 13616, -1, 15307, 15315, 15306, -1, 15306, 15315, 15314, -1, 15314, 15315, 13614, -1, 15308, 15316, 15307, -1, 15315, 15316, 13614, -1, 15307, 15316, 15315, -1, 13614, 15316, 11891, -1, 11891, 15317, 11892, -1, 15309, 15317, 15308, -1, 15316, 15317, 11891, -1, 15308, 15317, 15316, -1, 11892, 15317, 15309, -1, 10485, 10486, 15318, -1, 15318, 15310, 15319, -1, 10486, 15310, 15318, -1, 15319, 15311, 10989, -1, 15310, 15311, 15319, -1, 10989, 15312, 10990, -1, 10990, 15312, 11001, -1, 15311, 15312, 10989, -1, 11001, 15313, 10996, -1, 10996, 15313, 10988, -1, 15312, 15313, 11001, -1, 10988, 11853, 10987, -1, 15313, 11853, 10988, -1, 15320, 11895, 11893, -1, 11894, 10756, 10754, -1, 11894, 10758, 10756, -1, 12433, 13628, 15321, -1, 11894, 10761, 10758, -1, 13626, 10769, 10766, -1, 13626, 10772, 10769, -1, 13626, 10498, 10772, -1, 11895, 15322, 11894, -1, 15320, 15322, 11895, -1, 15323, 15324, 15320, -1, 15320, 15324, 15322, -1, 15322, 15324, 11894, -1, 15325, 15326, 15323, -1, 15324, 15326, 11894, -1, 15323, 15326, 15324, -1, 11894, 15326, 10761, -1, 15327, 15328, 15325, -1, 10761, 15328, 10763, -1, 15325, 15328, 15326, -1, 15326, 15328, 10761, -1, 15329, 15330, 15327, -1, 10763, 15330, 10766, -1, 15327, 15330, 15328, -1, 15328, 15330, 10763, -1, 15331, 15332, 15329, -1, 15330, 15332, 10766, -1, 15329, 15332, 15330, -1, 10766, 15332, 13626, -1, 15333, 15334, 15331, -1, 15332, 15334, 13626, -1, 15331, 15334, 15332, -1, 13626, 15335, 13628, -1, 15321, 15335, 15333, -1, 15333, 15335, 15334, -1, 15334, 15335, 13626, -1, 13628, 15335, 15321, -1, 11893, 11915, 15320, -1, 15320, 15336, 15323, -1, 11915, 15336, 15320, -1, 15323, 15337, 15325, -1, 15336, 15337, 15323, -1, 15325, 15338, 15327, -1, 15337, 15338, 15325, -1, 15327, 15339, 15329, -1, 15338, 15339, 15327, -1, 15329, 15340, 15331, -1, 15339, 15340, 15329, -1, 15331, 15341, 15333, -1, 15340, 15341, 15331, -1, 15333, 15342, 15321, -1, 15341, 15342, 15333, -1, 15321, 15343, 12433, -1, 15342, 15343, 15321, -1, 15343, 12436, 12433, -1, 15344, 15345, 15346, -1, 15347, 15348, 15349, -1, 15349, 15348, 15350, -1, 12436, 15343, 13389, -1, 15338, 15351, 15339, -1, 15339, 15351, 15352, -1, 15352, 15353, 15344, -1, 15344, 15353, 15345, -1, 13395, 15354, 12438, -1, 12438, 15354, 15355, -1, 15350, 15354, 13395, -1, 15345, 15356, 15347, -1, 15347, 15356, 15348, -1, 15337, 15357, 15338, -1, 15338, 15357, 15351, -1, 15355, 15358, 15359, -1, 15348, 15358, 15350, -1, 15354, 15358, 15355, -1, 15350, 15358, 15354, -1, 15352, 15360, 15353, -1, 15351, 15360, 15352, -1, 15353, 15361, 15345, -1, 15345, 15361, 15356, -1, 11915, 11919, 15336, -1, 15359, 15362, 15363, -1, 15348, 15362, 15358, -1, 15356, 15362, 15348, -1, 15358, 15362, 15359, -1, 15336, 15364, 15337, -1, 15337, 15364, 15357, -1, 11919, 15364, 15336, -1, 15357, 15365, 15351, -1, 15351, 15365, 15360, -1, 15353, 15366, 15361, -1, 15360, 15366, 15353, -1, 15361, 15367, 15356, -1, 15363, 15367, 15368, -1, 15356, 15367, 15362, -1, 15362, 15367, 15363, -1, 15364, 15369, 15357, -1, 11920, 15369, 11919, -1, 11922, 15369, 11920, -1, 11919, 15369, 15364, -1, 15357, 15369, 15365, -1, 15365, 15370, 15360, -1, 15360, 15370, 15366, -1, 11927, 11883, 15371, -1, 13389, 15372, 13391, -1, 15366, 15373, 15361, -1, 15367, 15373, 15368, -1, 15361, 15373, 15367, -1, 15343, 15372, 13389, -1, 11924, 15374, 11922, -1, 11922, 15374, 15369, -1, 15365, 15374, 15370, -1, 15369, 15374, 15365, -1, 15342, 15346, 15343, -1, 15368, 15375, 15376, -1, 15370, 15375, 15366, -1, 15343, 15346, 15372, -1, 15366, 15375, 15373, -1, 13391, 15349, 13393, -1, 15373, 15375, 15368, -1, 15372, 15349, 13391, -1, 15376, 15377, 15371, -1, 11927, 15377, 11924, -1, 11924, 15377, 15374, -1, 15375, 15377, 15376, -1, 15374, 15377, 15370, -1, 15370, 15377, 15375, -1, 15371, 15377, 11927, -1, 15341, 15344, 15342, -1, 15342, 15344, 15346, -1, 15372, 15347, 15349, -1, 15346, 15347, 15372, -1, 13393, 15350, 13395, -1, 15349, 15350, 13393, -1, 15339, 15352, 15340, -1, 15340, 15352, 15341, -1, 15341, 15352, 15344, -1, 15346, 15345, 15347, -1, 11882, 15378, 11883, -1, 11883, 15378, 15371, -1, 15371, 15378, 15376, -1, 15376, 15379, 15368, -1, 15378, 15379, 15376, -1, 15368, 15380, 15363, -1, 15379, 15380, 15368, -1, 15363, 15381, 15359, -1, 15380, 15381, 15363, -1, 15359, 15382, 15355, -1, 15381, 15382, 15359, -1, 15355, 15383, 12438, -1, 15382, 15383, 15355, -1, 15383, 12439, 12438, -1, 8968, 15384, 8971, -1, 15385, 15384, 8968, -1, 15386, 15384, 15385, -1, 15387, 15388, 15389, -1, 15389, 15388, 15390, -1, 11950, 15391, 11949, -1, 15392, 15391, 15393, -1, 15394, 15395, 15387, -1, 15396, 15391, 15392, -1, 11949, 15391, 15396, -1, 15383, 13388, 12439, -1, 15387, 15395, 15388, -1, 15397, 15398, 15399, -1, 15399, 15398, 15384, -1, 15384, 15398, 8971, -1, 13386, 15400, 13385, -1, 15390, 15400, 13386, -1, 11951, 15401, 11950, -1, 11950, 15401, 15391, -1, 15391, 15401, 15393, -1, 15393, 15401, 15397, -1, 15378, 15402, 15379, -1, 11952, 15403, 11951, -1, 8971, 15403, 8974, -1, 15379, 15402, 15404, -1, 11951, 15403, 15401, -1, 11958, 15402, 15378, -1, 15398, 15403, 8971, -1, 15397, 15403, 15398, -1, 15401, 15403, 15397, -1, 8974, 15403, 11952, -1, 15390, 15405, 15400, -1, 15388, 15405, 15390, -1, 15394, 15406, 15395, -1, 15404, 15406, 15394, -1, 15388, 15407, 15405, -1, 15395, 15407, 15388, -1, 13384, 15408, 13382, -1, 13385, 15408, 13384, -1, 11882, 11958, 15378, -1, 15400, 15408, 13385, -1, 11957, 15409, 11958, -1, 11958, 15409, 15402, -1, 15404, 15409, 15406, -1, 15402, 15409, 15404, -1, 15405, 15410, 15400, -1, 15400, 15410, 15408, -1, 15406, 15411, 15395, -1, 15395, 15411, 15407, -1, 15408, 15412, 13382, -1, 15407, 15413, 15405, -1, 15405, 15413, 15410, -1, 15410, 15414, 15408, -1, 15408, 15414, 15412, -1, 13377, 8966, 8965, -1, 15412, 15415, 13382, -1, 13381, 15415, 13379, -1, 13382, 15415, 13381, -1, 11954, 15416, 11957, -1, 15406, 15416, 15411, -1, 11957, 15416, 15409, -1, 15409, 15416, 15406, -1, 15407, 15392, 15413, -1, 15411, 15392, 15407, -1, 15413, 15417, 15410, -1, 15410, 15417, 15414, -1, 15414, 15386, 15412, -1, 11952, 8976, 8974, -1, 15412, 15386, 15415, -1, 15415, 15418, 13379, -1, 13379, 15418, 13377, -1, 13388, 15389, 13387, -1, 15383, 15389, 13388, -1, 13377, 15418, 8966, -1, 15413, 15393, 15417, -1, 15382, 15387, 15383, -1, 15392, 15393, 15413, -1, 15383, 15387, 15389, -1, 15417, 15399, 15414, -1, 15414, 15399, 15386, -1, 15380, 15394, 15381, -1, 15381, 15394, 15382, -1, 11949, 15396, 11954, -1, 15411, 15396, 15392, -1, 15382, 15394, 15387, -1, 15416, 15396, 15411, -1, 11954, 15396, 15416, -1, 13387, 15390, 13386, -1, 8966, 15385, 8968, -1, 15415, 15385, 15418, -1, 15418, 15385, 8966, -1, 15389, 15390, 13387, -1, 15386, 15385, 15415, -1, 15379, 15404, 15380, -1, 15393, 15397, 15417, -1, 15380, 15404, 15394, -1, 15417, 15397, 15399, -1, 15399, 15384, 15386, -1, 12432, 8970, 15419, -1, 15419, 8969, 15420, -1, 8970, 8969, 15419, -1, 15420, 8972, 15421, -1, 8969, 8972, 15420, -1, 15421, 8973, 15422, -1, 8972, 8973, 15421, -1, 15422, 8975, 11926, -1, 8973, 8975, 15422, -1, 8975, 8977, 11926, -1, 15419, 13632, 12432, -1, 11926, 11860, 15422, -1, 13630, 15423, 10500, -1, 13630, 15424, 15423, -1, 11859, 15425, 13630, -1, 13630, 15425, 15424, -1, 11859, 15426, 15425, -1, 11859, 11861, 15426, -1, 13632, 15427, 13630, -1, 15419, 15427, 13632, -1, 15420, 15428, 15419, -1, 15419, 15428, 15427, -1, 15427, 15428, 13630, -1, 15421, 15429, 15420, -1, 15428, 15429, 13630, -1, 15420, 15429, 15428, -1, 13630, 15429, 11859, -1, 11859, 15430, 11860, -1, 15422, 15430, 15421, -1, 15429, 15430, 11859, -1, 15421, 15430, 15429, -1, 11860, 15430, 15422, -1, 10499, 10500, 15431, -1, 15431, 15423, 15432, -1, 10500, 15423, 15431, -1, 15432, 15424, 11047, -1, 15423, 15424, 15432, -1, 11047, 15425, 11048, -1, 11048, 15425, 11059, -1, 15424, 15425, 11047, -1, 11059, 15426, 11054, -1, 11054, 15426, 11046, -1, 15425, 15426, 11059, -1, 11046, 11861, 11045, -1, 15426, 11861, 11046, -1, 15433, 11796, 11794, -1, 11795, 10785, 10784, -1, 11795, 10788, 10785, -1, 12425, 13636, 15434, -1, 11795, 10790, 10788, -1, 13634, 10798, 10795, -1, 13634, 10801, 10798, -1, 13634, 10505, 10801, -1, 11796, 15435, 11795, -1, 15433, 15435, 11796, -1, 15436, 15437, 15433, -1, 15433, 15437, 15435, -1, 15435, 15437, 11795, -1, 15438, 15439, 15436, -1, 15437, 15439, 11795, -1, 15436, 15439, 15437, -1, 11795, 15439, 10790, -1, 15440, 15441, 15438, -1, 10790, 15441, 10792, -1, 15438, 15441, 15439, -1, 15439, 15441, 10790, -1, 15442, 15443, 15440, -1, 10792, 15443, 10795, -1, 15440, 15443, 15441, -1, 15441, 15443, 10792, -1, 15444, 15445, 15442, -1, 15443, 15445, 10795, -1, 15442, 15445, 15443, -1, 10795, 15445, 13634, -1, 15446, 15447, 15444, -1, 15445, 15447, 13634, -1, 15444, 15447, 15445, -1, 13634, 15448, 13636, -1, 15434, 15448, 15446, -1, 15446, 15448, 15447, -1, 15447, 15448, 13634, -1, 13636, 15448, 15434, -1, 11833, 15449, 11794, -1, 11794, 15449, 15433, -1, 15433, 15450, 15436, -1, 15449, 15450, 15433, -1, 15436, 15451, 15438, -1, 15450, 15451, 15436, -1, 15438, 15452, 15440, -1, 15451, 15452, 15438, -1, 15440, 15453, 15442, -1, 15452, 15453, 15440, -1, 15442, 15454, 15444, -1, 15453, 15454, 15442, -1, 15444, 15455, 15446, -1, 15454, 15455, 15444, -1, 15446, 15456, 15434, -1, 15434, 15456, 12425, -1, 15455, 15456, 15446, -1, 15456, 12428, 12425, -1, 15457, 15458, 15459, -1, 15460, 15461, 15462, -1, 15462, 15461, 15463, -1, 12428, 15456, 13354, -1, 15451, 15464, 15452, -1, 15452, 15464, 15465, -1, 15465, 15466, 15457, -1, 15457, 15466, 15458, -1, 13360, 15467, 12430, -1, 12430, 15467, 15468, -1, 15463, 15467, 13360, -1, 15458, 15469, 15460, -1, 15460, 15469, 15461, -1, 15450, 15470, 15451, -1, 15451, 15470, 15464, -1, 15468, 15471, 15472, -1, 15461, 15471, 15463, -1, 15467, 15471, 15468, -1, 15463, 15471, 15467, -1, 15465, 15473, 15466, -1, 15464, 15473, 15465, -1, 15466, 15474, 15458, -1, 15458, 15474, 15469, -1, 11833, 11846, 15449, -1, 15472, 15475, 15476, -1, 15461, 15475, 15471, -1, 15469, 15475, 15461, -1, 15471, 15475, 15472, -1, 15449, 15477, 15450, -1, 15450, 15477, 15470, -1, 11846, 15477, 15449, -1, 15470, 15478, 15464, -1, 15464, 15478, 15473, -1, 15466, 15479, 15474, -1, 15473, 15479, 15466, -1, 15474, 15480, 15469, -1, 15476, 15480, 15481, -1, 15469, 15480, 15475, -1, 15475, 15480, 15476, -1, 15477, 15482, 15470, -1, 11850, 15482, 11846, -1, 11855, 15482, 11850, -1, 11846, 15482, 15477, -1, 15470, 15482, 15478, -1, 15478, 15483, 15473, -1, 15473, 15483, 15479, -1, 11878, 11885, 15484, -1, 13354, 15485, 13356, -1, 15479, 15486, 15474, -1, 15480, 15486, 15481, -1, 15474, 15486, 15480, -1, 15456, 15485, 13354, -1, 11864, 15487, 11855, -1, 11855, 15487, 15482, -1, 15478, 15487, 15483, -1, 15482, 15487, 15478, -1, 15455, 15459, 15456, -1, 15481, 15488, 15489, -1, 15483, 15488, 15479, -1, 15456, 15459, 15485, -1, 15479, 15488, 15486, -1, 13356, 15462, 13358, -1, 15486, 15488, 15481, -1, 15485, 15462, 13356, -1, 15489, 15490, 15484, -1, 11878, 15490, 11864, -1, 11864, 15490, 15487, -1, 15488, 15490, 15489, -1, 15487, 15490, 15483, -1, 15483, 15490, 15488, -1, 15484, 15490, 11878, -1, 15454, 15457, 15455, -1, 15455, 15457, 15459, -1, 15485, 15460, 15462, -1, 15459, 15460, 15485, -1, 13358, 15463, 13360, -1, 15462, 15463, 13358, -1, 15452, 15465, 15453, -1, 15453, 15465, 15454, -1, 15454, 15465, 15457, -1, 15459, 15458, 15460, -1, 11885, 11884, 15484, -1, 15484, 15491, 15489, -1, 11884, 15491, 15484, -1, 15489, 15492, 15481, -1, 15491, 15492, 15489, -1, 15481, 15493, 15476, -1, 15492, 15493, 15481, -1, 15476, 15494, 15472, -1, 15493, 15494, 15476, -1, 15472, 15495, 15468, -1, 15494, 15495, 15472, -1, 15468, 15496, 12430, -1, 15495, 15496, 15468, -1, 15496, 12431, 12430, -1, 8955, 15497, 8958, -1, 15498, 15497, 8955, -1, 15499, 15497, 15498, -1, 15500, 15501, 15502, -1, 15502, 15501, 15503, -1, 11916, 15504, 11914, -1, 15505, 15504, 15506, -1, 15507, 15508, 15500, -1, 15509, 15504, 15505, -1, 11914, 15504, 15509, -1, 15496, 13375, 12431, -1, 15500, 15508, 15501, -1, 15510, 15511, 15512, -1, 15512, 15511, 15497, -1, 15497, 15511, 8958, -1, 13373, 15513, 13372, -1, 15503, 15513, 13373, -1, 11917, 15514, 11916, -1, 11916, 15514, 15504, -1, 15504, 15514, 15506, -1, 15506, 15514, 15510, -1, 15491, 15515, 15492, -1, 11918, 15516, 11917, -1, 8958, 15516, 8961, -1, 15492, 15515, 15517, -1, 11917, 15516, 15514, -1, 11925, 15515, 15491, -1, 15511, 15516, 8958, -1, 15510, 15516, 15511, -1, 15514, 15516, 15510, -1, 8961, 15516, 11918, -1, 15503, 15518, 15513, -1, 15501, 15518, 15503, -1, 15507, 15519, 15508, -1, 15517, 15519, 15507, -1, 15501, 15520, 15518, -1, 15508, 15520, 15501, -1, 13371, 15521, 13369, -1, 13372, 15521, 13371, -1, 11884, 11925, 15491, -1, 15513, 15521, 13372, -1, 11923, 15522, 11925, -1, 11925, 15522, 15515, -1, 15517, 15522, 15519, -1, 15515, 15522, 15517, -1, 15518, 15523, 15513, -1, 15513, 15523, 15521, -1, 15519, 15524, 15508, -1, 15508, 15524, 15520, -1, 15521, 15525, 13369, -1, 15520, 15526, 15518, -1, 15518, 15526, 15523, -1, 15523, 15527, 15521, -1, 15521, 15527, 15525, -1, 13364, 8953, 8952, -1, 15525, 15528, 13369, -1, 13368, 15528, 13366, -1, 13369, 15528, 13368, -1, 11921, 15529, 11923, -1, 15519, 15529, 15524, -1, 11923, 15529, 15522, -1, 15522, 15529, 15519, -1, 15520, 15505, 15526, -1, 15524, 15505, 15520, -1, 15526, 15530, 15523, -1, 15523, 15530, 15527, -1, 15527, 15499, 15525, -1, 11918, 8963, 8961, -1, 15525, 15499, 15528, -1, 15528, 15531, 13366, -1, 13366, 15531, 13364, -1, 13375, 15502, 13374, -1, 15496, 15502, 13375, -1, 13364, 15531, 8953, -1, 15526, 15506, 15530, -1, 15495, 15500, 15496, -1, 15505, 15506, 15526, -1, 15496, 15500, 15502, -1, 15530, 15512, 15527, -1, 15527, 15512, 15499, -1, 15493, 15507, 15494, -1, 15494, 15507, 15495, -1, 11914, 15509, 11921, -1, 15524, 15509, 15505, -1, 15495, 15507, 15500, -1, 15529, 15509, 15524, -1, 11921, 15509, 15529, -1, 13374, 15503, 13373, -1, 8953, 15498, 8955, -1, 15528, 15498, 15531, -1, 15531, 15498, 8953, -1, 15502, 15503, 13374, -1, 15499, 15498, 15528, -1, 15492, 15517, 15493, -1, 15506, 15510, 15530, -1, 15493, 15517, 15507, -1, 15530, 15510, 15512, -1, 15512, 15497, 15499, -1, 8957, 8956, 12424, -1, 12424, 8956, 15532, -1, 15532, 8959, 15533, -1, 8956, 8959, 15532, -1, 15533, 8960, 15534, -1, 8959, 8960, 15533, -1, 15534, 8962, 15535, -1, 8960, 8962, 15534, -1, 15535, 8964, 11876, -1, 8962, 8964, 15535, -1, 15532, 13640, 12424, -1, 11876, 11862, 15535, -1, 13638, 15536, 10507, -1, 13638, 15537, 15536, -1, 11826, 15538, 13638, -1, 13638, 15538, 15537, -1, 11826, 15539, 15538, -1, 11826, 11825, 15539, -1, 13640, 15540, 13638, -1, 15532, 15540, 13640, -1, 15533, 15541, 15532, -1, 15532, 15541, 15540, -1, 15540, 15541, 13638, -1, 15534, 15542, 15533, -1, 15541, 15542, 13638, -1, 15533, 15542, 15541, -1, 13638, 15542, 11826, -1, 11826, 15543, 11862, -1, 15535, 15543, 15534, -1, 15542, 15543, 11826, -1, 15534, 15543, 15542, -1, 11862, 15543, 15535, -1, 10506, 10507, 15544, -1, 15544, 15536, 15545, -1, 10507, 15536, 15544, -1, 15545, 15537, 11076, -1, 15536, 15537, 15545, -1, 11076, 15538, 11077, -1, 11077, 15538, 11088, -1, 15537, 15538, 11076, -1, 11088, 15539, 11083, -1, 11083, 15539, 11075, -1, 15538, 15539, 11088, -1, 11075, 11825, 11074, -1, 15539, 11825, 11075, -1, 15546, 11981, 11979, -1, 11980, 10812, 10810, -1, 11980, 10814, 10812, -1, 12417, 13644, 15547, -1, 11980, 10817, 10814, -1, 13642, 10825, 10822, -1, 13642, 10828, 10825, -1, 13642, 10512, 10828, -1, 11981, 15548, 11980, -1, 15546, 15548, 11981, -1, 15549, 15550, 15546, -1, 15546, 15550, 15548, -1, 15548, 15550, 11980, -1, 15551, 15552, 15549, -1, 15550, 15552, 11980, -1, 15549, 15552, 15550, -1, 11980, 15552, 10817, -1, 15553, 15554, 15551, -1, 10817, 15554, 10819, -1, 15551, 15554, 15552, -1, 15552, 15554, 10817, -1, 15555, 15556, 15553, -1, 10819, 15556, 10822, -1, 15553, 15556, 15554, -1, 15554, 15556, 10819, -1, 15557, 15558, 15555, -1, 15556, 15558, 10822, -1, 15555, 15558, 15556, -1, 10822, 15558, 13642, -1, 15559, 15560, 15557, -1, 15558, 15560, 13642, -1, 15557, 15560, 15558, -1, 13642, 15561, 13644, -1, 15547, 15561, 15559, -1, 15559, 15561, 15560, -1, 15560, 15561, 13642, -1, 13644, 15561, 15547, -1, 11979, 11770, 15546, -1, 15546, 15562, 15549, -1, 11770, 15562, 15546, -1, 15549, 15563, 15551, -1, 15562, 15563, 15549, -1, 15551, 15564, 15553, -1, 15563, 15564, 15551, -1, 15553, 15565, 15555, -1, 15564, 15565, 15553, -1, 15555, 15566, 15557, -1, 15565, 15566, 15555, -1, 15557, 15567, 15559, -1, 15566, 15567, 15557, -1, 15559, 15568, 15547, -1, 15567, 15568, 15559, -1, 15547, 15569, 12417, -1, 15568, 15569, 15547, -1, 15569, 12420, 12417, -1, 15570, 15571, 15572, -1, 15573, 15574, 15575, -1, 15575, 15574, 15576, -1, 12420, 15569, 13332, -1, 15564, 15577, 15565, -1, 15565, 15577, 15578, -1, 15578, 15579, 15570, -1, 15570, 15579, 15571, -1, 13338, 15580, 12422, -1, 12422, 15580, 15581, -1, 15576, 15580, 13338, -1, 15571, 15582, 15573, -1, 15573, 15582, 15574, -1, 15563, 15583, 15564, -1, 15564, 15583, 15577, -1, 15581, 15584, 15585, -1, 15574, 15584, 15576, -1, 15580, 15584, 15581, -1, 15576, 15584, 15580, -1, 15578, 15586, 15579, -1, 15577, 15586, 15578, -1, 15579, 15587, 15571, -1, 15571, 15587, 15582, -1, 11770, 11776, 15562, -1, 15585, 15588, 15589, -1, 15574, 15588, 15584, -1, 15582, 15588, 15574, -1, 15584, 15588, 15585, -1, 15562, 15590, 15563, -1, 15563, 15590, 15583, -1, 11776, 15590, 15562, -1, 15583, 15591, 15577, -1, 15577, 15591, 15586, -1, 15579, 15592, 15587, -1, 15586, 15592, 15579, -1, 15587, 15593, 15582, -1, 15589, 15593, 15594, -1, 15582, 15593, 15588, -1, 15588, 15593, 15589, -1, 15590, 15595, 15583, -1, 11777, 15595, 11776, -1, 11779, 15595, 11777, -1, 11776, 15595, 15590, -1, 15583, 15595, 15591, -1, 15591, 15596, 15586, -1, 15586, 15596, 15592, -1, 11787, 11793, 15597, -1, 13332, 15598, 13334, -1, 15592, 15599, 15587, -1, 15593, 15599, 15594, -1, 15587, 15599, 15593, -1, 15569, 15598, 13332, -1, 11782, 15600, 11779, -1, 11779, 15600, 15595, -1, 15591, 15600, 15596, -1, 15595, 15600, 15591, -1, 15568, 15572, 15569, -1, 15594, 15601, 15602, -1, 15596, 15601, 15592, -1, 15569, 15572, 15598, -1, 15592, 15601, 15599, -1, 13334, 15575, 13336, -1, 15599, 15601, 15594, -1, 15598, 15575, 13334, -1, 15602, 15603, 15597, -1, 11787, 15603, 11782, -1, 11782, 15603, 15600, -1, 15601, 15603, 15602, -1, 15600, 15603, 15596, -1, 15596, 15603, 15601, -1, 15597, 15603, 11787, -1, 15567, 15570, 15568, -1, 15568, 15570, 15572, -1, 15598, 15573, 15575, -1, 15572, 15573, 15598, -1, 13336, 15576, 13338, -1, 15575, 15576, 13336, -1, 15565, 15578, 15566, -1, 15566, 15578, 15567, -1, 15567, 15578, 15570, -1, 15572, 15571, 15573, -1, 11877, 15604, 11793, -1, 11793, 15604, 15597, -1, 15597, 15605, 15602, -1, 15604, 15605, 15597, -1, 15602, 15606, 15594, -1, 15605, 15606, 15602, -1, 15594, 15607, 15589, -1, 15606, 15607, 15594, -1, 15589, 15608, 15585, -1, 15607, 15608, 15589, -1, 15585, 15609, 15581, -1, 15608, 15609, 15585, -1, 15581, 12423, 12422, -1, 15609, 12423, 15581, -1, 8942, 15610, 8945, -1, 15611, 15610, 15612, -1, 15613, 15614, 15615, -1, 15612, 15610, 8942, -1, 11835, 15616, 11834, -1, 15615, 15614, 15617, -1, 11834, 15616, 15618, -1, 15619, 15616, 15620, -1, 15621, 15622, 15613, -1, 15618, 15616, 15619, -1, 15609, 13353, 12423, -1, 15613, 15622, 15614, -1, 15623, 15624, 15610, -1, 15625, 15624, 15623, -1, 15610, 15624, 8945, -1, 13351, 15626, 13350, -1, 11835, 15627, 15616, -1, 15617, 15626, 13351, -1, 11836, 15627, 11835, -1, 15620, 15627, 15625, -1, 15616, 15627, 15620, -1, 15604, 15628, 15605, -1, 11837, 15629, 11836, -1, 8945, 15629, 8948, -1, 15605, 15628, 15630, -1, 15627, 15629, 15625, -1, 11863, 15628, 15604, -1, 15625, 15629, 15624, -1, 15624, 15629, 8945, -1, 8948, 15629, 11837, -1, 11836, 15629, 15627, -1, 15617, 15631, 15626, -1, 15614, 15631, 15617, -1, 15621, 15632, 15622, -1, 15630, 15632, 15621, -1, 15622, 15633, 15614, -1, 15614, 15633, 15631, -1, 13349, 15634, 13347, -1, 13350, 15634, 13349, -1, 15626, 15634, 13350, -1, 11877, 11863, 15604, -1, 11854, 15635, 11863, -1, 11863, 15635, 15628, -1, 15630, 15635, 15632, -1, 15628, 15635, 15630, -1, 15631, 15636, 15626, -1, 15626, 15636, 15634, -1, 15632, 15637, 15622, -1, 15622, 15637, 15633, -1, 15634, 15638, 13347, -1, 15631, 15639, 15636, -1, 15633, 15639, 15631, -1, 15634, 15640, 15638, -1, 15636, 15640, 15634, -1, 13342, 8940, 8939, -1, 13346, 15641, 13344, -1, 13347, 15641, 13346, -1, 15638, 15641, 13347, -1, 11851, 15642, 11854, -1, 15632, 15642, 15637, -1, 11854, 15642, 15635, -1, 15635, 15642, 15632, -1, 15637, 15619, 15633, -1, 15633, 15619, 15639, -1, 15636, 15643, 15640, -1, 15639, 15643, 15636, -1, 15638, 15611, 15641, -1, 15640, 15611, 15638, -1, 11837, 8950, 8948, -1, 13344, 15644, 13342, -1, 15608, 15615, 15609, -1, 13342, 15644, 8940, -1, 13353, 15615, 13352, -1, 15641, 15644, 13344, -1, 15609, 15615, 13353, -1, 15619, 15620, 15639, -1, 15639, 15620, 15643, -1, 15643, 15623, 15640, -1, 15608, 15613, 15615, -1, 15640, 15623, 15611, -1, 15606, 15621, 15607, -1, 15607, 15621, 15608, -1, 11834, 15618, 11851, -1, 15642, 15618, 15637, -1, 15608, 15621, 15613, -1, 15637, 15618, 15619, -1, 11851, 15618, 15642, -1, 13352, 15617, 13351, -1, 8940, 15612, 8942, -1, 15644, 15612, 8940, -1, 15641, 15612, 15644, -1, 15615, 15617, 13352, -1, 15611, 15612, 15641, -1, 15605, 15630, 15606, -1, 15620, 15625, 15643, -1, 15643, 15625, 15623, -1, 15606, 15630, 15621, -1, 15623, 15610, 15611, -1, 8944, 8943, 12416, -1, 12416, 8943, 15645, -1, 15645, 8946, 15646, -1, 8943, 8946, 15645, -1, 15646, 8947, 15647, -1, 8946, 8947, 15646, -1, 15647, 8949, 15648, -1, 8947, 8949, 15647, -1, 15648, 8951, 11784, -1, 8949, 8951, 15648, -1, 15645, 13648, 12416, -1, 11784, 11785, 15648, -1, 13646, 15649, 10514, -1, 13646, 15650, 15649, -1, 11865, 15651, 13646, -1, 13646, 15651, 15650, -1, 11865, 15652, 15651, -1, 11865, 11866, 15652, -1, 13648, 15653, 13646, -1, 15645, 15653, 13648, -1, 15646, 15654, 15645, -1, 15645, 15654, 15653, -1, 15653, 15654, 13646, -1, 15647, 15655, 15646, -1, 15654, 15655, 13646, -1, 15646, 15655, 15654, -1, 13646, 15655, 11865, -1, 11865, 15656, 11785, -1, 15648, 15656, 15647, -1, 15655, 15656, 11865, -1, 15647, 15656, 15655, -1, 11785, 15656, 15648, -1, 10513, 10514, 10833, -1, 10833, 15649, 10830, -1, 10514, 15649, 10833, -1, 10830, 15650, 10595, -1, 15649, 15650, 10830, -1, 10596, 15651, 10598, -1, 10595, 15651, 10596, -1, 15650, 15651, 10595, -1, 10598, 15652, 10599, -1, 15651, 15652, 10598, -1, 10599, 11866, 10600, -1, 15652, 11866, 10599, -1, 10520, 10521, 15657, -1, 15657, 15658, 15659, -1, 10521, 15658, 15657, -1, 15659, 15660, 11105, -1, 15658, 15660, 15659, -1, 11105, 15661, 11106, -1, 11106, 15661, 11117, -1, 15660, 15661, 11105, -1, 11117, 15662, 11112, -1, 11112, 15662, 11104, -1, 15661, 15662, 11117, -1, 11104, 11869, 11103, -1, 15662, 11869, 11104, -1, 15663, 13656, 12408, -1, 11977, 11868, 15664, -1, 13654, 15658, 10521, -1, 13654, 15660, 15658, -1, 11867, 15661, 13654, -1, 13654, 15661, 15660, -1, 11867, 15662, 15661, -1, 11867, 11869, 15662, -1, 13656, 15665, 13654, -1, 15663, 15665, 13656, -1, 15666, 15667, 15663, -1, 15665, 15667, 13654, -1, 15663, 15667, 15665, -1, 15668, 15669, 15666, -1, 15667, 15669, 13654, -1, 13654, 15669, 11867, -1, 15666, 15669, 15667, -1, 11867, 15670, 11868, -1, 15664, 15670, 15668, -1, 15669, 15670, 11867, -1, 15668, 15670, 15669, -1, 11868, 15670, 15664, -1, 8931, 8930, 12408, -1, 12408, 8930, 15663, -1, 15663, 8933, 15666, -1, 8930, 8933, 15663, -1, 15666, 8934, 15668, -1, 8933, 8934, 15666, -1, 15668, 8936, 15664, -1, 8934, 8936, 15668, -1, 15664, 8938, 11977, -1, 8936, 8938, 15664, -1, 8929, 15671, 8932, -1, 15672, 15671, 8929, -1, 15673, 15671, 15672, -1, 15674, 15675, 15676, -1, 15676, 15675, 15677, -1, 11771, 15678, 11769, -1, 15679, 15678, 15680, -1, 15681, 15682, 15674, -1, 15683, 15678, 15679, -1, 11769, 15678, 15683, -1, 15684, 13331, 12415, -1, 15674, 15682, 15675, -1, 15685, 15686, 15687, -1, 15687, 15686, 15671, -1, 15671, 15686, 8932, -1, 13329, 15688, 13328, -1, 15677, 15688, 13329, -1, 11772, 15689, 11771, -1, 11771, 15689, 15678, -1, 15678, 15689, 15680, -1, 15680, 15689, 15685, -1, 15690, 15691, 15692, -1, 11775, 15693, 11772, -1, 8932, 15693, 8935, -1, 15692, 15691, 15694, -1, 11772, 15693, 15689, -1, 11781, 15691, 15690, -1, 15686, 15693, 8932, -1, 15685, 15693, 15686, -1, 15689, 15693, 15685, -1, 8935, 15693, 11775, -1, 15677, 15695, 15688, -1, 15675, 15695, 15677, -1, 15681, 15696, 15682, -1, 15694, 15696, 15681, -1, 15675, 15697, 15695, -1, 15682, 15697, 15675, -1, 13327, 15698, 13325, -1, 13328, 15698, 13327, -1, 11788, 11781, 15690, -1, 15688, 15698, 13328, -1, 11780, 15699, 11781, -1, 11781, 15699, 15691, -1, 15694, 15699, 15696, -1, 15691, 15699, 15694, -1, 15695, 15700, 15688, -1, 15688, 15700, 15698, -1, 15696, 15701, 15682, -1, 15682, 15701, 15697, -1, 15698, 15702, 13325, -1, 15697, 15703, 15695, -1, 15695, 15703, 15700, -1, 15700, 15704, 15698, -1, 15698, 15704, 15702, -1, 13320, 8927, 8926, -1, 15702, 15705, 13325, -1, 13324, 15705, 13322, -1, 13325, 15705, 13324, -1, 11778, 15706, 11780, -1, 15696, 15706, 15701, -1, 11780, 15706, 15699, -1, 15699, 15706, 15696, -1, 15697, 15679, 15703, -1, 15701, 15679, 15697, -1, 15703, 15707, 15700, -1, 15700, 15707, 15704, -1, 15704, 15673, 15702, -1, 11775, 8937, 8935, -1, 15702, 15673, 15705, -1, 15705, 15708, 13322, -1, 13322, 15708, 13320, -1, 13331, 15676, 13330, -1, 15684, 15676, 13331, -1, 13320, 15708, 8927, -1, 15703, 15680, 15707, -1, 15709, 15674, 15684, -1, 15679, 15680, 15703, -1, 15684, 15674, 15676, -1, 15707, 15687, 15704, -1, 15704, 15687, 15673, -1, 15710, 15681, 15709, -1, 15711, 15681, 15710, -1, 11769, 15683, 11778, -1, 15709, 15681, 15674, -1, 15701, 15683, 15679, -1, 15706, 15683, 15701, -1, 11778, 15683, 15706, -1, 13330, 15677, 13329, -1, 8927, 15672, 8929, -1, 15705, 15672, 15708, -1, 15708, 15672, 8927, -1, 15676, 15677, 13330, -1, 15673, 15672, 15705, -1, 15692, 15694, 15711, -1, 15680, 15685, 15707, -1, 15711, 15694, 15681, -1, 15707, 15685, 15687, -1, 15687, 15671, 15673, -1, 11788, 15690, 11886, -1, 11886, 15690, 15712, -1, 15712, 15692, 15713, -1, 15690, 15692, 15712, -1, 15713, 15711, 15714, -1, 15692, 15711, 15713, -1, 15714, 15710, 15715, -1, 15711, 15710, 15714, -1, 15715, 15709, 15716, -1, 15710, 15709, 15715, -1, 15716, 15684, 15717, -1, 15709, 15684, 15716, -1, 15717, 12415, 12414, -1, 15684, 12415, 15717, -1, 15718, 15719, 15720, -1, 15721, 15719, 15718, -1, 15722, 15723, 15724, -1, 15720, 15723, 15722, -1, 12412, 15725, 13310, -1, 15726, 15727, 15728, -1, 15728, 15727, 15729, -1, 15729, 15730, 15721, -1, 15721, 15730, 15719, -1, 13316, 15731, 12414, -1, 12414, 15731, 15717, -1, 15724, 15731, 13316, -1, 15719, 15732, 15720, -1, 15720, 15732, 15723, -1, 15733, 15734, 15726, -1, 15726, 15734, 15727, -1, 15717, 15735, 15716, -1, 15731, 15735, 15717, -1, 15723, 15735, 15724, -1, 15724, 15735, 15731, -1, 15727, 15736, 15729, -1, 15729, 15736, 15730, -1, 15719, 15737, 15732, -1, 15730, 15737, 15719, -1, 15716, 15738, 15715, -1, 11965, 11970, 15739, -1, 15735, 15738, 15716, -1, 15732, 15738, 15723, -1, 15723, 15738, 15735, -1, 15739, 15740, 15733, -1, 15733, 15740, 15734, -1, 11970, 15740, 15739, -1, 15727, 15741, 15736, -1, 15734, 15741, 15727, -1, 15730, 15742, 15737, -1, 15736, 15742, 15730, -1, 15732, 15743, 15738, -1, 15715, 15743, 15714, -1, 15737, 15743, 15732, -1, 15738, 15743, 15715, -1, 11971, 15744, 11970, -1, 11973, 15744, 11971, -1, 15740, 15744, 15734, -1, 15734, 15744, 15741, -1, 11970, 15744, 15740, -1, 15741, 15745, 15736, -1, 15736, 15745, 15742, -1, 15742, 15746, 15737, -1, 11978, 11886, 15712, -1, 15743, 15746, 15714, -1, 13310, 15747, 13312, -1, 15725, 15747, 13310, -1, 15737, 15746, 15743, -1, 11975, 15748, 11973, -1, 11973, 15748, 15744, -1, 15749, 15718, 15725, -1, 15744, 15748, 15741, -1, 15741, 15748, 15745, -1, 15746, 15750, 15714, -1, 15745, 15750, 15742, -1, 15714, 15750, 15713, -1, 15725, 15718, 15747, -1, 15742, 15750, 15746, -1, 13312, 15722, 13314, -1, 11978, 15751, 11975, -1, 15745, 15751, 15750, -1, 15713, 15751, 15712, -1, 15747, 15722, 13312, -1, 15748, 15751, 15745, -1, 15752, 15721, 15749, -1, 15750, 15751, 15713, -1, 15712, 15751, 11978, -1, 11975, 15751, 15748, -1, 15749, 15721, 15718, -1, 15747, 15720, 15722, -1, 15718, 15720, 15747, -1, 13314, 15724, 13316, -1, 15722, 15724, 13314, -1, 15753, 15729, 15752, -1, 15728, 15729, 15753, -1, 15752, 15729, 15721, -1, 11945, 11965, 15754, -1, 11965, 15739, 15754, -1, 15754, 15733, 15755, -1, 15739, 15733, 15754, -1, 15755, 15726, 15756, -1, 15733, 15726, 15755, -1, 15756, 15728, 15757, -1, 15726, 15728, 15756, -1, 15757, 15753, 15758, -1, 15728, 15753, 15757, -1, 15758, 15752, 15759, -1, 15753, 15752, 15758, -1, 15759, 15749, 15760, -1, 15752, 15749, 15759, -1, 15761, 15725, 12409, -1, 15760, 15725, 15761, -1, 15749, 15725, 15760, -1, 15725, 12412, 12409, -1, 15754, 11947, 11945, -1, 11946, 10845, 10843, -1, 11946, 10848, 10845, -1, 12409, 13660, 15761, -1, 11946, 10851, 10848, -1, 13658, 10859, 10856, -1, 13658, 10862, 10859, -1, 13658, 10519, 10862, -1, 11947, 15762, 11946, -1, 15754, 15762, 11947, -1, 15755, 15763, 15754, -1, 15754, 15763, 15762, -1, 15762, 15763, 11946, -1, 15756, 15764, 15755, -1, 15755, 15764, 15763, -1, 15763, 15764, 11946, -1, 11946, 15764, 10851, -1, 10851, 15765, 10853, -1, 15757, 15765, 15756, -1, 15756, 15765, 15764, -1, 15764, 15765, 10851, -1, 10853, 15766, 10856, -1, 15758, 15766, 15757, -1, 15765, 15766, 10853, -1, 15757, 15766, 15765, -1, 15759, 15767, 15758, -1, 15766, 15767, 10856, -1, 15758, 15767, 15766, -1, 10856, 15767, 13658, -1, 15760, 15768, 15759, -1, 15767, 15768, 13658, -1, 15759, 15768, 15767, -1, 13658, 15769, 13660, -1, 15761, 15769, 15760, -1, 15760, 15769, 15768, -1, 13660, 15769, 15761, -1, 15768, 15769, 13658, -1, 10527, 10528, 15770, -1, 15770, 15771, 15772, -1, 10528, 15771, 15770, -1, 15772, 15773, 11137, -1, 15771, 15773, 15772, -1, 11137, 15774, 11138, -1, 11138, 15774, 11149, -1, 15773, 15774, 11137, -1, 11149, 15775, 11144, -1, 11144, 15775, 11136, -1, 15774, 15775, 11149, -1, 11136, 11872, 11135, -1, 15775, 11872, 11136, -1, 15776, 13664, 12400, -1, 11943, 11871, 15777, -1, 13662, 15771, 10528, -1, 13662, 15773, 15771, -1, 11870, 15774, 13662, -1, 13662, 15774, 15773, -1, 11870, 15775, 15774, -1, 11870, 11872, 15775, -1, 13664, 15778, 13662, -1, 15776, 15778, 13664, -1, 15779, 15780, 15776, -1, 15778, 15780, 13662, -1, 15776, 15780, 15778, -1, 15781, 15782, 15779, -1, 15780, 15782, 13662, -1, 13662, 15782, 11870, -1, 15779, 15782, 15780, -1, 11870, 15783, 11871, -1, 15777, 15783, 15781, -1, 15782, 15783, 11870, -1, 15781, 15783, 15782, -1, 11871, 15783, 15777, -1, 12400, 8918, 15776, -1, 15776, 8917, 15779, -1, 8918, 8917, 15776, -1, 15779, 8919, 15781, -1, 8917, 8919, 15779, -1, 15781, 8921, 15777, -1, 8919, 8921, 15781, -1, 15777, 8923, 11943, -1, 8921, 8923, 15777, -1, 8923, 8925, 11943, -1, 15784, 15785, 8916, -1, 15786, 15785, 15784, -1, 15787, 15788, 15789, -1, 11967, 15790, 11966, -1, 15789, 15788, 15791, -1, 15792, 15790, 15793, -1, 15794, 15795, 15787, -1, 15796, 15790, 15792, -1, 11966, 15790, 15796, -1, 15787, 15795, 15788, -1, 15797, 13309, 12407, -1, 8920, 15798, 8922, -1, 15799, 15798, 15800, -1, 15800, 15798, 15785, -1, 15785, 15798, 8920, -1, 13307, 15801, 13306, -1, 15791, 15801, 13307, -1, 11968, 15802, 11967, -1, 11967, 15802, 15790, -1, 15790, 15802, 15793, -1, 15793, 15802, 15799, -1, 15803, 15804, 15805, -1, 11969, 15806, 11968, -1, 11968, 15806, 15802, -1, 15805, 15804, 15807, -1, 15799, 15806, 15798, -1, 11976, 15804, 15803, -1, 15802, 15806, 15799, -1, 15798, 15806, 8922, -1, 8922, 15806, 11969, -1, 15791, 15808, 15801, -1, 15788, 15808, 15791, -1, 15794, 15809, 15795, -1, 15807, 15809, 15794, -1, 15788, 15810, 15808, -1, 15795, 15810, 15788, -1, 13305, 15811, 13303, -1, 13306, 15811, 13305, -1, 15801, 15811, 13306, -1, 11887, 11976, 15803, -1, 11974, 15812, 11976, -1, 11976, 15812, 15804, -1, 15807, 15812, 15809, -1, 15804, 15812, 15807, -1, 15808, 15813, 15801, -1, 15801, 15813, 15811, -1, 15809, 15814, 15795, -1, 15795, 15814, 15810, -1, 15811, 15815, 13303, -1, 15810, 15816, 15808, -1, 15808, 15816, 15813, -1, 15813, 15817, 15811, -1, 15811, 15817, 15815, -1, 15815, 15818, 13303, -1, 13298, 8914, 8913, -1, 13302, 15818, 13300, -1, 13303, 15818, 13302, -1, 11972, 15819, 11974, -1, 15809, 15819, 15814, -1, 11974, 15819, 15812, -1, 15812, 15819, 15809, -1, 15810, 15792, 15816, -1, 15814, 15792, 15810, -1, 15816, 15820, 15813, -1, 15813, 15820, 15817, -1, 15817, 15786, 15815, -1, 11969, 8924, 8922, -1, 15815, 15786, 15818, -1, 15821, 15789, 15797, -1, 15818, 15822, 13300, -1, 13300, 15822, 13298, -1, 13309, 15789, 13308, -1, 13298, 15822, 8914, -1, 15797, 15789, 13309, -1, 15816, 15793, 15820, -1, 15792, 15793, 15816, -1, 15821, 15787, 15789, -1, 15820, 15800, 15817, -1, 15817, 15800, 15786, -1, 15823, 15794, 15821, -1, 15824, 15794, 15823, -1, 11966, 15796, 11972, -1, 15814, 15796, 15792, -1, 15821, 15794, 15787, -1, 15819, 15796, 15814, -1, 11972, 15796, 15819, -1, 13308, 15791, 13307, -1, 8914, 15784, 8916, -1, 15818, 15784, 15822, -1, 15822, 15784, 8914, -1, 15789, 15791, 13308, -1, 15786, 15784, 15818, -1, 15805, 15807, 15824, -1, 15793, 15799, 15820, -1, 15824, 15807, 15794, -1, 15820, 15799, 15800, -1, 15800, 15785, 15786, -1, 8916, 15785, 8920, -1, 11888, 11887, 15825, -1, 15825, 15803, 15826, -1, 11887, 15803, 15825, -1, 15826, 15805, 15827, -1, 15803, 15805, 15826, -1, 15827, 15824, 15828, -1, 15805, 15824, 15827, -1, 15828, 15823, 15829, -1, 15824, 15823, 15828, -1, 15829, 15821, 15830, -1, 15823, 15821, 15829, -1, 15830, 15797, 12406, -1, 15821, 15797, 15830, -1, 15797, 12407, 12406, -1, 15831, 15832, 15833, -1, 15834, 15832, 15831, -1, 15835, 15836, 15837, -1, 15833, 15836, 15835, -1, 12404, 15838, 13288, -1, 15839, 15840, 15841, -1, 15841, 15840, 15842, -1, 15842, 15843, 15834, -1, 15834, 15843, 15832, -1, 13294, 15844, 12406, -1, 12406, 15844, 15830, -1, 15837, 15844, 13294, -1, 15832, 15845, 15833, -1, 15833, 15845, 15836, -1, 15846, 15847, 15839, -1, 15839, 15847, 15840, -1, 15830, 15848, 15829, -1, 15844, 15848, 15830, -1, 15836, 15848, 15837, -1, 15837, 15848, 15844, -1, 15840, 15849, 15842, -1, 15842, 15849, 15843, -1, 15832, 15850, 15845, -1, 15843, 15850, 15832, -1, 15829, 15851, 15828, -1, 11931, 11936, 15852, -1, 15848, 15851, 15829, -1, 15845, 15851, 15836, -1, 15836, 15851, 15848, -1, 15852, 15853, 15846, -1, 15846, 15853, 15847, -1, 11936, 15853, 15852, -1, 15840, 15854, 15849, -1, 15847, 15854, 15840, -1, 15843, 15855, 15850, -1, 15849, 15855, 15843, -1, 15845, 15856, 15851, -1, 15828, 15856, 15827, -1, 15850, 15856, 15845, -1, 15851, 15856, 15828, -1, 11938, 15857, 11936, -1, 11940, 15857, 11938, -1, 15853, 15857, 15847, -1, 15847, 15857, 15854, -1, 11936, 15857, 15853, -1, 15854, 15858, 15849, -1, 15849, 15858, 15855, -1, 15855, 15859, 15850, -1, 11944, 11888, 15825, -1, 15856, 15859, 15827, -1, 13288, 15860, 13290, -1, 15838, 15860, 13288, -1, 15850, 15859, 15856, -1, 11942, 15861, 11940, -1, 11940, 15861, 15857, -1, 15862, 15831, 15838, -1, 15857, 15861, 15854, -1, 15854, 15861, 15858, -1, 15859, 15863, 15827, -1, 15858, 15863, 15855, -1, 15827, 15863, 15826, -1, 15838, 15831, 15860, -1, 15855, 15863, 15859, -1, 13290, 15835, 13292, -1, 11944, 15864, 11942, -1, 15858, 15864, 15863, -1, 15826, 15864, 15825, -1, 15860, 15835, 13290, -1, 15861, 15864, 15858, -1, 15865, 15834, 15862, -1, 15863, 15864, 15826, -1, 15825, 15864, 11944, -1, 11942, 15864, 15861, -1, 15862, 15834, 15831, -1, 15860, 15833, 15835, -1, 15831, 15833, 15860, -1, 13292, 15837, 13294, -1, 15835, 15837, 13292, -1, 15866, 15842, 15865, -1, 15841, 15842, 15866, -1, 15865, 15842, 15834, -1, 11931, 15852, 11911, -1, 11911, 15852, 15867, -1, 15867, 15846, 15868, -1, 15852, 15846, 15867, -1, 15868, 15839, 15869, -1, 15846, 15839, 15868, -1, 15869, 15841, 15870, -1, 15839, 15841, 15869, -1, 15870, 15866, 15871, -1, 15841, 15866, 15870, -1, 15871, 15865, 15872, -1, 15866, 15865, 15871, -1, 15872, 15862, 15873, -1, 15865, 15862, 15872, -1, 15874, 15838, 12401, -1, 15873, 15838, 15874, -1, 15862, 15838, 15873, -1, 15838, 12404, 12401, -1, 15867, 11913, 11911, -1, 11912, 10873, 10871, -1, 11912, 10876, 10873, -1, 12401, 13668, 15874, -1, 11912, 10879, 10876, -1, 13666, 10887, 10884, -1, 13666, 10890, 10887, -1, 13666, 10526, 10890, -1, 11913, 15875, 11912, -1, 15867, 15875, 11913, -1, 15868, 15876, 15867, -1, 15867, 15876, 15875, -1, 15875, 15876, 11912, -1, 15869, 15877, 15868, -1, 15868, 15877, 15876, -1, 15876, 15877, 11912, -1, 11912, 15877, 10879, -1, 10879, 15878, 10881, -1, 15870, 15878, 15869, -1, 15869, 15878, 15877, -1, 15877, 15878, 10879, -1, 10881, 15879, 10884, -1, 15871, 15879, 15870, -1, 15878, 15879, 10881, -1, 15870, 15879, 15878, -1, 15872, 15880, 15871, -1, 15879, 15880, 10884, -1, 15871, 15880, 15879, -1, 10884, 15880, 13666, -1, 15873, 15881, 15872, -1, 15880, 15881, 13666, -1, 15872, 15881, 15880, -1, 13666, 15882, 13668, -1, 15874, 15882, 15873, -1, 15873, 15882, 15881, -1, 13668, 15882, 15874, -1, 15881, 15882, 13666, -1, 15883, 11829, 11827, -1, 11828, 10904, 10902, -1, 11828, 10906, 10904, -1, 11674, 13585, 15884, -1, 11828, 10909, 10906, -1, 13583, 10917, 10914, -1, 13583, 10920, 10917, -1, 13583, 10419, 10920, -1, 11829, 15885, 11828, -1, 15883, 15885, 11829, -1, 15886, 15887, 15883, -1, 15883, 15887, 15885, -1, 15885, 15887, 11828, -1, 15888, 15889, 15886, -1, 15887, 15889, 11828, -1, 15886, 15889, 15887, -1, 11828, 15889, 10909, -1, 15890, 15891, 15888, -1, 10909, 15891, 10911, -1, 15888, 15891, 15889, -1, 15889, 15891, 10909, -1, 15892, 15893, 15890, -1, 10911, 15893, 10914, -1, 15890, 15893, 15891, -1, 15891, 15893, 10911, -1, 15894, 15895, 15892, -1, 15893, 15895, 10914, -1, 15892, 15895, 15893, -1, 10914, 15895, 13583, -1, 15896, 15897, 15894, -1, 15895, 15897, 13583, -1, 15894, 15897, 15895, -1, 13583, 15898, 13585, -1, 15884, 15898, 15896, -1, 15896, 15898, 15897, -1, 15897, 15898, 13583, -1, 13585, 15898, 15884, -1, 11897, 15899, 11827, -1, 11827, 15899, 15883, -1, 15883, 15900, 15886, -1, 15899, 15900, 15883, -1, 15886, 15901, 15888, -1, 15900, 15901, 15886, -1, 15888, 15902, 15890, -1, 15901, 15902, 15888, -1, 15890, 15903, 15892, -1, 15902, 15903, 15890, -1, 15892, 15904, 15894, -1, 15903, 15904, 15892, -1, 15894, 15905, 15896, -1, 15904, 15905, 15894, -1, 15896, 15906, 15884, -1, 15905, 15906, 15896, -1, 15884, 11680, 11674, -1, 15906, 11680, 15884, -1, 15907, 15908, 15909, -1, 15910, 15911, 15912, -1, 15912, 15911, 15913, -1, 11680, 15906, 13266, -1, 15901, 15914, 15902, -1, 15902, 15914, 15915, -1, 15915, 15916, 15907, -1, 15907, 15916, 15908, -1, 13272, 15917, 12398, -1, 12398, 15917, 15918, -1, 15913, 15917, 13272, -1, 15910, 15919, 15911, -1, 15908, 15919, 15910, -1, 15900, 15920, 15901, -1, 15901, 15920, 15914, -1, 15918, 15921, 15922, -1, 15917, 15921, 15918, -1, 15911, 15921, 15913, -1, 15913, 15921, 15917, -1, 15915, 15923, 15916, -1, 15914, 15923, 15915, -1, 15916, 15924, 15908, -1, 15908, 15924, 15919, -1, 11897, 11902, 15899, -1, 15922, 15925, 15926, -1, 15919, 15925, 15911, -1, 15921, 15925, 15922, -1, 15911, 15925, 15921, -1, 15899, 15927, 15900, -1, 15900, 15927, 15920, -1, 11902, 15927, 15899, -1, 15920, 15928, 15914, -1, 15914, 15928, 15923, -1, 15916, 15929, 15924, -1, 15923, 15929, 15916, -1, 15924, 15930, 15919, -1, 15926, 15930, 15931, -1, 15919, 15930, 15925, -1, 15925, 15930, 15926, -1, 15927, 15932, 15920, -1, 11903, 15932, 11902, -1, 11905, 15932, 11903, -1, 11902, 15932, 15927, -1, 15920, 15932, 15928, -1, 15928, 15933, 15923, -1, 15923, 15933, 15929, -1, 11910, 11890, 15934, -1, 13266, 15935, 13268, -1, 15929, 15936, 15924, -1, 15930, 15936, 15931, -1, 15924, 15936, 15930, -1, 15906, 15935, 13266, -1, 11907, 15937, 11905, -1, 11905, 15937, 15932, -1, 15928, 15937, 15933, -1, 15932, 15937, 15928, -1, 15905, 15909, 15906, -1, 15931, 15938, 15939, -1, 15933, 15938, 15929, -1, 15906, 15909, 15935, -1, 15929, 15938, 15936, -1, 13268, 15912, 13270, -1, 15936, 15938, 15931, -1, 15935, 15912, 13268, -1, 15939, 15940, 15934, -1, 11910, 15940, 11907, -1, 11907, 15940, 15937, -1, 15938, 15940, 15939, -1, 15937, 15940, 15933, -1, 15933, 15940, 15938, -1, 15934, 15940, 11910, -1, 15904, 15907, 15905, -1, 15905, 15907, 15909, -1, 15935, 15910, 15912, -1, 15909, 15910, 15935, -1, 13270, 15913, 13272, -1, 15912, 15913, 13270, -1, 15902, 15915, 15903, -1, 15903, 15915, 15904, -1, 15904, 15915, 15907, -1, 15909, 15908, 15910, -1, 11890, 11889, 15934, -1, 15934, 15941, 15939, -1, 11889, 15941, 15934, -1, 15939, 15942, 15931, -1, 15941, 15942, 15939, -1, 15931, 15943, 15926, -1, 15942, 15943, 15931, -1, 15926, 15944, 15922, -1, 15943, 15944, 15926, -1, 15922, 15945, 15918, -1, 15944, 15945, 15922, -1, 15918, 15946, 12398, -1, 15945, 15946, 15918, -1, 15946, 12399, 12398, -1, 8903, 15947, 8907, -1, 15948, 15947, 15949, -1, 15950, 15951, 15952, -1, 15949, 15947, 8903, -1, 11933, 15953, 11932, -1, 15952, 15951, 15954, -1, 11932, 15953, 15955, -1, 15956, 15953, 15957, -1, 15958, 15959, 15950, -1, 15950, 15959, 15951, -1, 15955, 15953, 15956, -1, 15946, 13287, 12399, -1, 15960, 15961, 15947, -1, 15962, 15961, 15960, -1, 15947, 15961, 8907, -1, 13285, 15963, 13284, -1, 15954, 15963, 13285, -1, 11933, 15964, 15953, -1, 11934, 15964, 11933, -1, 15957, 15964, 15962, -1, 15953, 15964, 15957, -1, 15941, 15965, 15942, -1, 11935, 15966, 11934, -1, 11934, 15966, 15964, -1, 15942, 15965, 15967, -1, 8907, 15966, 8909, -1, 11941, 15965, 15941, -1, 15964, 15966, 15962, -1, 15962, 15966, 15961, -1, 15961, 15966, 8907, -1, 8909, 15966, 11935, -1, 15954, 15968, 15963, -1, 15951, 15968, 15954, -1, 15958, 15969, 15959, -1, 15967, 15969, 15958, -1, 15951, 15970, 15968, -1, 15959, 15970, 15951, -1, 13283, 15971, 13281, -1, 13284, 15971, 13283, -1, 15963, 15971, 13284, -1, 11889, 11941, 15941, -1, 11939, 15972, 11941, -1, 11941, 15972, 15965, -1, 15967, 15972, 15969, -1, 15965, 15972, 15967, -1, 15968, 15973, 15963, -1, 15963, 15973, 15971, -1, 15969, 15974, 15959, -1, 15959, 15974, 15970, -1, 15971, 15975, 13281, -1, 15970, 15976, 15968, -1, 15968, 15976, 15973, -1, 15973, 15977, 15971, -1, 15971, 15977, 15975, -1, 15975, 15978, 13281, -1, 13276, 8901, 8900, -1, 13280, 15978, 13278, -1, 13281, 15978, 13280, -1, 11937, 15979, 11939, -1, 15969, 15979, 15974, -1, 11939, 15979, 15972, -1, 15972, 15979, 15969, -1, 15974, 15956, 15970, -1, 15970, 15956, 15976, -1, 15973, 15980, 15977, -1, 15976, 15980, 15973, -1, 15977, 15948, 15975, -1, 11935, 8911, 8909, -1, 15975, 15948, 15978, -1, 15978, 15981, 13278, -1, 13278, 15981, 13276, -1, 13287, 15952, 13286, -1, 15946, 15952, 13287, -1, 13276, 15981, 8901, -1, 15976, 15957, 15980, -1, 15956, 15957, 15976, -1, 15944, 15950, 15945, -1, 15945, 15950, 15946, -1, 15980, 15960, 15977, -1, 15977, 15960, 15948, -1, 15946, 15950, 15952, -1, 15943, 15958, 15944, -1, 11932, 15955, 11937, -1, 15944, 15958, 15950, -1, 15974, 15955, 15956, -1, 11937, 15955, 15979, -1, 15979, 15955, 15974, -1, 13286, 15954, 13285, -1, 15948, 15949, 15978, -1, 15978, 15949, 15981, -1, 8901, 15949, 8903, -1, 15952, 15954, 13286, -1, 15981, 15949, 8901, -1, 15942, 15967, 15943, -1, 15957, 15962, 15980, -1, 15943, 15967, 15958, -1, 15980, 15962, 15960, -1, 15960, 15947, 15948, -1, 8905, 8904, 12396, -1, 12396, 8904, 15982, -1, 15982, 8906, 15983, -1, 8904, 8906, 15982, -1, 15983, 8908, 15984, -1, 8906, 8908, 15983, -1, 15984, 8910, 15985, -1, 8908, 8910, 15984, -1, 15985, 8912, 11909, -1, 8910, 8912, 15985, -1, 15982, 13652, 12396, -1, 11909, 11874, 15985, -1, 13650, 15986, 10531, -1, 13650, 15987, 15986, -1, 11873, 15988, 13650, -1, 13650, 15988, 15987, -1, 11873, 15989, 15988, -1, 11873, 11875, 15989, -1, 13652, 15990, 13650, -1, 15982, 15990, 13652, -1, 15983, 15991, 15982, -1, 15982, 15991, 15990, -1, 15990, 15991, 13650, -1, 15984, 15992, 15983, -1, 15991, 15992, 13650, -1, 15983, 15992, 15991, -1, 13650, 15992, 11873, -1, 11873, 15993, 11874, -1, 15985, 15993, 15984, -1, 15992, 15993, 11873, -1, 15984, 15993, 15992, -1, 11874, 15993, 15985, -1, 10530, 10531, 15994, -1, 15994, 15986, 15995, -1, 10531, 15986, 15994, -1, 15995, 15987, 11169, -1, 15986, 15987, 15995, -1, 11169, 15988, 11170, -1, 11170, 15988, 11181, -1, 15987, 15988, 11169, -1, 11181, 15989, 11176, -1, 11176, 15989, 11168, -1, 15988, 15989, 11181, -1, 11168, 11875, 11167, -1, 15989, 11875, 11168, -1, 10413, 10412, 15996, -1, 15996, 15997, 15998, -1, 10412, 15997, 15996, -1, 15998, 15999, 11229, -1, 15997, 15999, 15998, -1, 11229, 16000, 11230, -1, 11230, 16000, 11241, -1, 15999, 16000, 11229, -1, 11241, 16001, 11236, -1, 11236, 16001, 11228, -1, 16000, 16001, 11241, -1, 11228, 11801, 11227, -1, 16001, 11801, 11228, -1, 16002, 13591, 11666, -1, 11819, 11820, 16003, -1, 13589, 15997, 10412, -1, 13589, 15999, 15997, -1, 11803, 16000, 13589, -1, 13589, 16000, 15999, -1, 11803, 16001, 16000, -1, 11803, 11801, 16001, -1, 13591, 16004, 13589, -1, 16002, 16004, 13591, -1, 16005, 16006, 16002, -1, 16004, 16006, 13589, -1, 16002, 16006, 16004, -1, 16007, 16008, 16005, -1, 16006, 16008, 13589, -1, 13589, 16008, 11803, -1, 16005, 16008, 16006, -1, 11803, 16009, 11820, -1, 16003, 16009, 16007, -1, 16008, 16009, 11803, -1, 16007, 16009, 16008, -1, 11820, 16009, 16003, -1, 11666, 11673, 16002, -1, 16002, 16010, 16005, -1, 11673, 16010, 16002, -1, 16005, 16011, 16007, -1, 16010, 16011, 16005, -1, 16007, 16012, 16003, -1, 16011, 16012, 16007, -1, 16003, 16013, 11819, -1, 16012, 16013, 16003, -1, 16013, 11848, 11819, -1, 16014, 16015, 16016, -1, 16017, 16018, 13252, -1, 8890, 16019, 8888, -1, 16020, 16021, 16022, -1, 16022, 16021, 16023, -1, 8888, 16019, 16024, -1, 16023, 16025, 13263, -1, 13263, 16025, 13265, -1, 16024, 16026, 16017, -1, 16017, 16026, 16018, -1, 16027, 16028, 16020, -1, 8892, 16029, 8890, -1, 16030, 16028, 16027, -1, 16031, 13250, 12393, -1, 8890, 16029, 16019, -1, 16032, 13250, 16031, -1, 8884, 13250, 16032, -1, 16016, 16033, 16034, -1, 16034, 16033, 16030, -1, 13253, 16035, 13255, -1, 16018, 16035, 13253, -1, 11896, 16036, 16037, -1, 16037, 16036, 16038, -1, 16024, 16039, 16026, -1, 16038, 16036, 16015, -1, 16010, 16040, 16011, -1, 16025, 16040, 13265, -1, 16019, 16039, 16024, -1, 16021, 16040, 16023, -1, 8894, 16041, 8892, -1, 16023, 16040, 16025, -1, 8892, 16041, 16029, -1, 13265, 16040, 16010, -1, 16020, 16042, 16021, -1, 16035, 16043, 13255, -1, 16028, 16042, 16020, -1, 16018, 16043, 16035, -1, 16026, 16043, 16018, -1, 16015, 16044, 16016, -1, 11908, 16045, 8898, -1, 16016, 16044, 16033, -1, 11906, 16045, 11908, -1, 8896, 16045, 8894, -1, 8898, 16045, 8896, -1, 8894, 16045, 16041, -1, 16019, 16046, 16039, -1, 16033, 16047, 16030, -1, 16029, 16046, 16019, -1, 16030, 16047, 16028, -1, 11898, 16048, 11896, -1, 16015, 16048, 16044, -1, 13255, 16049, 13256, -1, 11896, 16048, 16036, -1, 16036, 16048, 16015, -1, 16039, 16050, 16026, -1, 16040, 16051, 16011, -1, 16021, 16051, 16040, -1, 16042, 16051, 16021, -1, 16026, 16050, 16043, -1, 16033, 16052, 16047, -1, 16029, 16053, 16046, -1, 16044, 16052, 16033, -1, 16041, 16053, 16029, -1, 16028, 16054, 16042, -1, 16047, 16054, 16028, -1, 13255, 16055, 16049, -1, 16043, 16055, 13255, -1, 16049, 16055, 13256, -1, 11899, 16056, 11898, -1, 11898, 16056, 16048, -1, 16041, 16057, 16053, -1, 16048, 16056, 16044, -1, 16045, 16057, 16041, -1, 16044, 16056, 16052, -1, 11906, 16057, 16045, -1, 16039, 16014, 16050, -1, 16046, 16014, 16039, -1, 16047, 16058, 16054, -1, 16052, 16058, 16047, -1, 13256, 16059, 13258, -1, 16011, 16060, 16012, -1, 16054, 16060, 16042, -1, 16042, 16060, 16051, -1, 16043, 16034, 16055, -1, 16051, 16060, 16011, -1, 11900, 16061, 11899, -1, 16050, 16034, 16043, -1, 11899, 16061, 16056, -1, 16056, 16061, 16052, -1, 16052, 16061, 16058, -1, 16046, 16038, 16014, -1, 16012, 16062, 16013, -1, 16054, 16062, 16060, -1, 16053, 16038, 16046, -1, 13265, 16010, 11673, -1, 16060, 16062, 16012, -1, 16058, 16062, 16054, -1, 13256, 16027, 16059, -1, 16013, 16063, 11901, -1, 16058, 16063, 16062, -1, 11901, 16063, 11900, -1, 16061, 16063, 16058, -1, 16055, 16027, 13256, -1, 16062, 16063, 16013, -1, 11900, 16063, 16061, -1, 16059, 16022, 13258, -1, 13260, 16022, 13261, -1, 13258, 16022, 13260, -1, 11904, 16037, 11906, -1, 11896, 16037, 11904, -1, 16057, 16037, 16053, -1, 11906, 16037, 16057, -1, 16053, 16037, 16038, -1, 16014, 16016, 16050, -1, 16050, 16016, 16034, -1, 16059, 16020, 16022, -1, 16027, 16020, 16059, -1, 11901, 11848, 16013, -1, 13261, 16023, 13263, -1, 16022, 16023, 13261, -1, 13250, 16017, 13252, -1, 8884, 16017, 13250, -1, 8886, 16024, 8884, -1, 16055, 16030, 16027, -1, 8888, 16024, 8886, -1, 16034, 16030, 16055, -1, 8884, 16024, 16017, -1, 16038, 16015, 16014, -1, 13252, 16018, 13253, -1, 12393, 12392, 16031, -1, 16031, 16064, 16032, -1, 12392, 16064, 16031, -1, 16032, 16065, 8884, -1, 16064, 16065, 16032, -1, 16065, 8885, 8884, -1, 16066, 16067, 16068, -1, 16069, 16070, 16071, -1, 16072, 16070, 16069, -1, 8895, 16073, 8897, -1, 11821, 16073, 11818, -1, 16074, 16073, 16075, -1, 16071, 16070, 16076, -1, 16075, 16073, 16067, -1, 11818, 16073, 16074, -1, 16067, 16073, 8895, -1, 8897, 16073, 11821, -1, 16076, 16077, 16078, -1, 16078, 16077, 16079, -1, 16079, 16080, 16081, -1, 16081, 16080, 16082, -1, 16083, 16084, 16072, -1, 16072, 16084, 16070, -1, 16076, 16085, 16077, -1, 16070, 16085, 16076, -1, 16064, 16086, 16065, -1, 16065, 16086, 8885, -1, 13241, 16086, 16064, -1, 16082, 16086, 13241, -1, 16079, 16087, 16080, -1, 16077, 16087, 16079, -1, 16088, 16089, 16083, -1, 13241, 16064, 12392, -1, 16083, 16089, 16084, -1, 8885, 16090, 8887, -1, 16086, 16090, 8885, -1, 16082, 16090, 16086, -1, 16080, 16090, 16082, -1, 16084, 16091, 16070, -1, 16070, 16091, 16085, -1, 16085, 16092, 16077, -1, 16077, 16092, 16087, -1, 16080, 16093, 16090, -1, 8887, 16093, 8889, -1, 16090, 16093, 8887, -1, 16087, 16093, 16080, -1, 11812, 11813, 16094, -1, 16095, 16096, 16088, -1, 16088, 16096, 16089, -1, 16084, 16097, 16091, -1, 16089, 16097, 16084, -1, 16091, 16098, 16085, -1, 16085, 16098, 16092, -1, 8889, 16099, 8891, -1, 16092, 16099, 16087, -1, 16087, 16099, 16093, -1, 16093, 16099, 8889, -1, 16095, 16100, 16096, -1, 16094, 16100, 16095, -1, 11813, 16100, 16094, -1, 16089, 16101, 16097, -1, 16096, 16101, 16089, -1, 11821, 8899, 8897, -1, 16097, 16066, 16091, -1, 16102, 16103, 12391, -1, 16091, 16066, 16098, -1, 13248, 16103, 13246, -1, 16092, 16104, 16099, -1, 12391, 16103, 13248, -1, 16098, 16104, 16092, -1, 16071, 16078, 16102, -1, 16099, 16104, 8891, -1, 11815, 16105, 11813, -1, 11817, 16105, 11815, -1, 16102, 16078, 16103, -1, 16100, 16105, 16096, -1, 16096, 16105, 16101, -1, 11813, 16105, 16100, -1, 13246, 16081, 13244, -1, 16101, 16075, 16097, -1, 16103, 16081, 13246, -1, 16097, 16075, 16066, -1, 8891, 16068, 8893, -1, 8893, 16068, 8895, -1, 16104, 16068, 8891, -1, 16098, 16068, 16104, -1, 16071, 16076, 16078, -1, 16066, 16068, 16098, -1, 11818, 16074, 11817, -1, 16103, 16079, 16081, -1, 11817, 16074, 16105, -1, 16078, 16079, 16103, -1, 16105, 16074, 16101, -1, 16101, 16074, 16075, -1, 13244, 16082, 13241, -1, 16068, 16067, 8895, -1, 16081, 16082, 13244, -1, 16075, 16067, 16066, -1, 11812, 16094, 11789, -1, 11789, 16094, 16106, -1, 16106, 16095, 16107, -1, 16094, 16095, 16106, -1, 16107, 16088, 16108, -1, 16095, 16088, 16107, -1, 16108, 16083, 16109, -1, 16088, 16083, 16108, -1, 16109, 16072, 16110, -1, 16083, 16072, 16109, -1, 16110, 16069, 16111, -1, 16072, 16069, 16110, -1, 16111, 16071, 16112, -1, 16069, 16071, 16111, -1, 16113, 16102, 12388, -1, 16112, 16102, 16113, -1, 16071, 16102, 16112, -1, 16102, 12391, 12388, -1, 16106, 11791, 11789, -1, 11790, 10937, 10935, -1, 11790, 10940, 10937, -1, 12388, 13672, 16113, -1, 11790, 10943, 10940, -1, 13670, 10951, 10948, -1, 13670, 10954, 10951, -1, 13670, 10473, 10954, -1, 11791, 16114, 11790, -1, 16106, 16114, 11791, -1, 16107, 16115, 16106, -1, 16106, 16115, 16114, -1, 16114, 16115, 11790, -1, 16108, 16116, 16107, -1, 16107, 16116, 16115, -1, 16115, 16116, 11790, -1, 11790, 16116, 10943, -1, 10943, 16117, 10945, -1, 16109, 16117, 16108, -1, 16108, 16117, 16116, -1, 16116, 16117, 10943, -1, 10945, 16118, 10948, -1, 16110, 16118, 16109, -1, 16117, 16118, 10945, -1, 16109, 16118, 16117, -1, 16111, 16119, 16110, -1, 16118, 16119, 10948, -1, 16110, 16119, 16118, -1, 10948, 16119, 13670, -1, 16112, 16120, 16111, -1, 16119, 16120, 13670, -1, 16111, 16120, 16119, -1, 13670, 16121, 13672, -1, 16113, 16121, 16112, -1, 16112, 16121, 16120, -1, 13672, 16121, 16113, -1, 16120, 16121, 13670, -1, 16122, 11824, 11822, -1, 12465, 13595, 16123, -1, 11823, 10957, 10956, -1, 11823, 10960, 10957, -1, 13593, 10973, 10970, -1, 13593, 10469, 10973, -1, 11824, 16124, 11823, -1, 16122, 16124, 11824, -1, 16125, 16126, 16122, -1, 16122, 16126, 16124, -1, 16124, 16126, 11823, -1, 16127, 16128, 16125, -1, 16125, 16128, 16126, -1, 16129, 16130, 16127, -1, 16127, 16130, 16128, -1, 16131, 16132, 16129, -1, 16129, 16132, 16130, -1, 16133, 16134, 16131, -1, 16131, 16134, 16132, -1, 16135, 16136, 16133, -1, 16133, 16136, 16134, -1, 13593, 16137, 13595, -1, 16123, 16137, 16135, -1, 16135, 16137, 16136, -1, 13595, 16137, 16123, -1, 16136, 16137, 13593, -1, 10960, 16138, 10962, -1, 10962, 16138, 10964, -1, 10964, 16138, 10967, -1, 10967, 16138, 10970, -1, 16134, 16138, 16132, -1, 16130, 16138, 16128, -1, 16128, 16138, 16126, -1, 16136, 16138, 16134, -1, 16132, 16138, 16130, -1, 11823, 16138, 10960, -1, 16126, 16138, 11823, -1, 13593, 16138, 16136, -1, 10970, 16138, 13593, -1, 11822, 11849, 16122, -1, 16122, 12076, 16125, -1, 11849, 12076, 16122, -1, 16125, 12075, 16127, -1, 12076, 12075, 16125, -1, 16127, 12073, 16129, -1, 12075, 12073, 16127, -1, 16129, 12069, 16131, -1, 12073, 12069, 16129, -1, 16131, 12071, 16133, -1, 12069, 12071, 16131, -1, 16133, 12065, 16135, -1, 12071, 12065, 16133, -1, 12065, 12066, 16135, -1, 16135, 12067, 16123, -1, 12066, 12067, 16135, -1, 16123, 12068, 12465, -1, 12067, 12068, 16123, -1, 12068, 12064, 12465, -1, 10750, 10485, 15318, -1, 10748, 15318, 15319, -1, 10748, 10750, 15318, -1, 10991, 15319, 10989, -1, 10991, 10748, 15319, -1, 10999, 10748, 10991, -1, 10638, 10748, 10999, -1, 10673, 10492, 15009, -1, 10671, 15009, 15010, -1, 10671, 10673, 15009, -1, 11020, 15010, 11018, -1, 11020, 10671, 15010, -1, 11028, 10671, 11020, -1, 10633, 10671, 11028, -1, 10777, 10499, 15431, -1, 10775, 15431, 15432, -1, 10775, 10777, 15431, -1, 11049, 15432, 11047, -1, 11049, 10775, 15432, -1, 11057, 10775, 11049, -1, 10628, 10775, 11057, -1, 10806, 10506, 15544, -1, 10804, 15544, 15545, -1, 10804, 10806, 15544, -1, 11078, 15545, 11076, -1, 11078, 10804, 15545, -1, 11086, 10804, 11078, -1, 10623, 10804, 11086, -1, 10837, 11115, 10603, -1, 10837, 11107, 11115, -1, 15659, 11105, 11107, -1, 15659, 11107, 10837, -1, 15657, 10837, 10839, -1, 15657, 15659, 10837, -1, 10520, 15657, 10839, -1, 10865, 11147, 10608, -1, 10865, 11139, 11147, -1, 15772, 11137, 11139, -1, 15772, 11139, 10865, -1, 15770, 10865, 10867, -1, 15770, 15772, 10865, -1, 10527, 15770, 10867, -1, 10925, 10530, 15994, -1, 10923, 15994, 15995, -1, 10923, 10925, 15994, -1, 11171, 15995, 11169, -1, 11171, 10923, 15995, -1, 11179, 10923, 11171, -1, 10613, 10923, 11179, -1, 14896, 11201, 10592, -1, 14896, 11202, 11201, -1, 14896, 11213, 11202, -1, 10897, 14896, 10592, -1, 14894, 10897, 10899, -1, 10422, 14894, 10899, -1, 16139, 14894, 14896, -1, 16139, 14896, 10897, -1, 16139, 10897, 14894, -1, 10929, 11239, 10618, -1, 10929, 11231, 11239, -1, 15998, 11229, 11231, -1, 15998, 11231, 10929, -1, 15996, 10929, 10931, -1, 15996, 15998, 10929, -1, 10413, 15996, 10931, -1, 13663, 8881, 8883, -1, 13663, 8879, 8881, -1, 10134, 16140, 16141, -1, 10134, 10133, 16140, -1, 10058, 16142, 10062, -1, 10062, 16142, 10064, -1, 13661, 16142, 13663, -1, 10064, 16142, 13661, -1, 10058, 16143, 16142, -1, 16142, 16143, 13663, -1, 10057, 16144, 10058, -1, 16143, 16144, 13663, -1, 10058, 16144, 16143, -1, 11251, 16145, 10057, -1, 10057, 16145, 16144, -1, 11247, 16146, 11249, -1, 11249, 16146, 11251, -1, 11251, 16146, 16145, -1, 11247, 16147, 16146, -1, 10398, 16148, 10394, -1, 10134, 16148, 10398, -1, 10394, 16148, 11245, -1, 11245, 16148, 11247, -1, 11247, 16148, 16147, -1, 16147, 16148, 10134, -1, 8879, 16149, 8878, -1, 16150, 16149, 16141, -1, 16151, 16149, 16150, -1, 8878, 16149, 16151, -1, 16147, 16149, 16146, -1, 16145, 16149, 16144, -1, 10134, 16149, 16147, -1, 16146, 16149, 16145, -1, 13663, 16149, 8879, -1, 16141, 16149, 10134, -1, 16144, 16149, 13663, -1, 10285, 16152, 10133, -1, 10133, 16152, 16140, -1, 16140, 16153, 16141, -1, 16152, 16153, 16140, -1, 16141, 16154, 16150, -1, 16153, 16154, 16141, -1, 16150, 16155, 16151, -1, 16154, 16155, 16150, -1, 16151, 8876, 8878, -1, 16155, 8876, 16151, -1, 16156, 16157, 16158, -1, 16159, 16157, 16156, -1, 16154, 16160, 16155, -1, 16155, 16160, 16161, -1, 8880, 13297, 8882, -1, 16162, 16163, 16164, -1, 16161, 16163, 16162, -1, 8867, 16165, 8870, -1, 16164, 16165, 16159, -1, 16157, 16165, 8867, -1, 16159, 16165, 16157, -1, 16153, 16166, 16154, -1, 16154, 16166, 16160, -1, 16160, 16167, 16161, -1, 16161, 16167, 16163, -1, 8870, 16168, 8875, -1, 16165, 16168, 8870, -1, 16164, 16168, 16165, -1, 16163, 16168, 16164, -1, 10286, 16169, 10285, -1, 10285, 16169, 16152, -1, 16152, 16169, 16153, -1, 16153, 16169, 16166, -1, 13304, 8845, 8844, -1, 16166, 16170, 16160, -1, 16160, 16170, 16167, -1, 8875, 16171, 8851, -1, 16168, 16171, 8875, -1, 16167, 16171, 16163, -1, 16163, 16171, 16168, -1, 10287, 16172, 10286, -1, 10298, 16172, 10287, -1, 10286, 16172, 16169, -1, 16169, 16172, 16166, -1, 16166, 16172, 16170, -1, 8851, 16173, 8850, -1, 16171, 16173, 8851, -1, 16170, 16173, 16167, -1, 16167, 16173, 16171, -1, 10298, 16174, 16172, -1, 10302, 16174, 10298, -1, 16170, 16174, 16173, -1, 16173, 16174, 8850, -1, 8850, 16174, 10302, -1, 16172, 16174, 16170, -1, 10302, 8849, 8850, -1, 8877, 16175, 8880, -1, 13297, 16175, 13299, -1, 8880, 16175, 13297, -1, 8877, 16176, 16175, -1, 13299, 16156, 13301, -1, 16175, 16156, 13299, -1, 8876, 16162, 8877, -1, 8877, 16162, 16176, -1, 16175, 16159, 16156, -1, 16176, 16159, 16175, -1, 16155, 16161, 8876, -1, 8876, 16161, 16162, -1, 13301, 16158, 13304, -1, 13304, 16158, 8845, -1, 16156, 16158, 13301, -1, 16176, 16164, 16159, -1, 16162, 16164, 16176, -1, 8845, 16157, 8867, -1, 16158, 16157, 8845, -1, 10198, 16177, 8863, -1, 8863, 16177, 8861, -1, 8861, 16177, 8859, -1, 8859, 16178, 8855, -1, 16177, 16178, 8859, -1, 8855, 16179, 8841, -1, 16178, 16179, 8855, -1, 16179, 16180, 8841, -1, 8841, 16181, 8839, -1, 16180, 16181, 8841, -1, 8839, 16182, 8873, -1, 8873, 16182, 8871, -1, 16181, 16182, 8839, -1, 16182, 12405, 8871, -1, 16183, 16184, 13293, -1, 16178, 16185, 16179, -1, 16179, 16185, 16186, -1, 16187, 16188, 16189, -1, 16186, 16188, 16187, -1, 16183, 16190, 16184, -1, 16191, 16190, 16183, -1, 13289, 16192, 16193, -1, 16184, 16192, 13289, -1, 10341, 16194, 10198, -1, 10339, 16194, 10341, -1, 10198, 16194, 16177, -1, 16177, 16194, 16178, -1, 16178, 16194, 16185, -1, 16186, 16195, 16188, -1, 16185, 16195, 16186, -1, 16189, 16196, 16191, -1, 16191, 16196, 16190, -1, 13289, 16193, 12402, -1, 16193, 16197, 16198, -1, 16190, 16197, 16184, -1, 16192, 16197, 16193, -1, 16184, 16197, 16192, -1, 10338, 16199, 10339, -1, 10339, 16199, 16194, -1, 16194, 16199, 16185, -1, 16185, 16199, 16195, -1, 16188, 16200, 16189, -1, 16189, 16200, 16196, -1, 16198, 16201, 16202, -1, 16196, 16201, 16190, -1, 16190, 16201, 16197, -1, 16197, 16201, 16198, -1, 16188, 16203, 16200, -1, 16195, 16203, 16188, -1, 16200, 16204, 16196, -1, 16202, 16204, 16205, -1, 16196, 16204, 16201, -1, 16201, 16204, 16202, -1, 16195, 16206, 16203, -1, 10337, 16206, 10338, -1, 10338, 16206, 16199, -1, 16199, 16206, 16195, -1, 16203, 16207, 16200, -1, 16205, 16207, 16208, -1, 16204, 16207, 16205, -1, 16200, 16207, 16204, -1, 10336, 10329, 16209, -1, 16208, 16210, 16209, -1, 10336, 16210, 10337, -1, 16203, 16210, 16207, -1, 12405, 16211, 13296, -1, 10337, 16210, 16206, -1, 16209, 16210, 10336, -1, 16206, 16210, 16203, -1, 16207, 16210, 16208, -1, 16182, 16211, 12405, -1, 16181, 16212, 16182, -1, 16182, 16212, 16211, -1, 13295, 16183, 13293, -1, 13296, 16183, 13295, -1, 16211, 16183, 13296, -1, 16180, 16187, 16181, -1, 16181, 16187, 16212, -1, 16211, 16191, 16183, -1, 16212, 16191, 16211, -1, 16179, 16186, 16180, -1, 16180, 16186, 16187, -1, 16187, 16189, 16212, -1, 16212, 16189, 16191, -1, 13291, 16184, 13289, -1, 13293, 16184, 13291, -1, 12402, 16193, 12403, -1, 12403, 16193, 16213, -1, 16213, 16198, 16214, -1, 16193, 16198, 16213, -1, 16214, 16202, 16215, -1, 16198, 16202, 16214, -1, 16215, 16205, 16216, -1, 16202, 16205, 16215, -1, 16216, 16208, 16217, -1, 16205, 16208, 16216, -1, 16217, 16209, 16218, -1, 16208, 16209, 16217, -1, 16218, 10329, 10217, -1, 16209, 10329, 16218, -1, 10216, 16218, 10217, -1, 10216, 16217, 16218, -1, 10216, 16216, 16217, -1, 13667, 16214, 16215, -1, 13667, 16213, 16214, -1, 13667, 12403, 16213, -1, 11255, 16219, 10219, -1, 10218, 16219, 10216, -1, 10219, 16219, 10218, -1, 11258, 16220, 11255, -1, 11255, 16220, 16219, -1, 16219, 16220, 10216, -1, 11259, 16221, 11258, -1, 16220, 16221, 10216, -1, 11258, 16221, 16220, -1, 10216, 16221, 16216, -1, 11261, 16222, 11259, -1, 11263, 16222, 11261, -1, 16216, 16222, 16215, -1, 16221, 16222, 16216, -1, 16215, 16222, 13667, -1, 11259, 16222, 16221, -1, 16222, 16223, 13667, -1, 11263, 16223, 16222, -1, 13665, 16224, 10525, -1, 13667, 16224, 13665, -1, 11265, 16224, 11263, -1, 10525, 16224, 11265, -1, 11263, 16224, 16223, -1, 16223, 16224, 13667, -1, 13655, 8832, 8834, -1, 13655, 8830, 8832, -1, 10342, 16225, 16226, -1, 10342, 10246, 16225, -1, 10054, 16227, 10056, -1, 13653, 16227, 13655, -1, 10056, 16227, 13653, -1, 10049, 16228, 10050, -1, 10050, 16228, 10054, -1, 10054, 16228, 16227, -1, 16227, 16228, 13655, -1, 16228, 16229, 13655, -1, 10049, 16229, 16228, -1, 11274, 16230, 10049, -1, 10049, 16230, 16229, -1, 11270, 16231, 11272, -1, 11272, 16231, 11274, -1, 11274, 16231, 16230, -1, 11270, 16232, 16231, -1, 10403, 16233, 10399, -1, 10342, 16233, 10403, -1, 10399, 16233, 11268, -1, 11268, 16233, 11270, -1, 11270, 16233, 16232, -1, 16232, 16233, 10342, -1, 8830, 16234, 8829, -1, 16235, 16234, 16226, -1, 16236, 16234, 16235, -1, 8829, 16234, 16236, -1, 16232, 16234, 16231, -1, 16230, 16234, 16229, -1, 10342, 16234, 16232, -1, 16231, 16234, 16230, -1, 13655, 16234, 8830, -1, 16226, 16234, 10342, -1, 16229, 16234, 13655, -1, 10246, 10244, 16225, -1, 16225, 16237, 16226, -1, 10244, 16237, 16225, -1, 16226, 16238, 16235, -1, 16237, 16238, 16226, -1, 16235, 16239, 16236, -1, 16238, 16239, 16235, -1, 16236, 16240, 8829, -1, 16239, 16240, 16236, -1, 16240, 8827, 8829, -1, 16241, 16242, 8796, -1, 16243, 16242, 16241, -1, 16244, 16242, 16243, -1, 16238, 16245, 16239, -1, 16239, 16245, 16240, -1, 8831, 13319, 8833, -1, 16240, 16245, 16246, -1, 16246, 16247, 16248, -1, 16248, 16247, 16249, -1, 8818, 16250, 8821, -1, 16249, 16250, 16244, -1, 16244, 16250, 16242, -1, 16242, 16250, 8818, -1, 16238, 16251, 16245, -1, 16246, 16252, 16247, -1, 16245, 16252, 16246, -1, 8821, 16253, 8826, -1, 16249, 16253, 16250, -1, 16250, 16253, 8821, -1, 16247, 16253, 16249, -1, 10247, 16254, 10244, -1, 10244, 16254, 16237, -1, 16237, 16254, 16238, -1, 16238, 16254, 16251, -1, 13326, 8796, 8795, -1, 16251, 16255, 16245, -1, 16245, 16255, 16252, -1, 8826, 16256, 8802, -1, 16253, 16256, 8826, -1, 16252, 16256, 16247, -1, 16247, 16256, 16253, -1, 10248, 16257, 10247, -1, 10251, 16257, 10248, -1, 10247, 16257, 16254, -1, 16254, 16257, 16251, -1, 16251, 16257, 16255, -1, 8802, 16258, 8801, -1, 16256, 16258, 8802, -1, 16255, 16258, 16252, -1, 16252, 16258, 16256, -1, 10251, 16259, 16257, -1, 10255, 16259, 10251, -1, 16255, 16259, 16258, -1, 16258, 16259, 8801, -1, 8801, 16259, 10255, -1, 16257, 16259, 16255, -1, 10255, 8800, 8801, -1, 13319, 16260, 13321, -1, 8831, 16260, 13319, -1, 8828, 16261, 8831, -1, 8831, 16261, 16260, -1, 13321, 16243, 13323, -1, 16260, 16243, 13321, -1, 8827, 16248, 8828, -1, 8828, 16248, 16261, -1, 16260, 16244, 16243, -1, 16261, 16244, 16260, -1, 16240, 16246, 8827, -1, 8827, 16246, 16248, -1, 13323, 16241, 13326, -1, 13326, 16241, 8796, -1, 16243, 16241, 13323, -1, 16248, 16249, 16261, -1, 16261, 16249, 16244, -1, 8796, 16242, 8818, -1, 10197, 16262, 8814, -1, 8814, 16262, 8812, -1, 8812, 16262, 8810, -1, 16262, 16263, 8810, -1, 8810, 16264, 8806, -1, 16263, 16264, 8810, -1, 8806, 16265, 8792, -1, 16264, 16265, 8806, -1, 8792, 16266, 8790, -1, 16265, 16266, 8792, -1, 8790, 16267, 8824, -1, 8824, 16267, 8822, -1, 16266, 16267, 8790, -1, 16267, 12413, 8822, -1, 16263, 16268, 16264, -1, 16264, 16268, 16269, -1, 16270, 16271, 16272, -1, 16269, 16271, 16270, -1, 16273, 16274, 16275, -1, 16276, 16274, 16273, -1, 13311, 16277, 16278, -1, 16275, 16277, 13311, -1, 10318, 16279, 10197, -1, 10315, 16279, 10318, -1, 10197, 16279, 16262, -1, 16262, 16279, 16263, -1, 16263, 16279, 16268, -1, 16269, 16280, 16271, -1, 16268, 16280, 16269, -1, 16272, 16281, 16276, -1, 16276, 16281, 16274, -1, 13311, 16278, 12410, -1, 16278, 16282, 16283, -1, 16274, 16282, 16275, -1, 16277, 16282, 16278, -1, 16275, 16282, 16277, -1, 10311, 16284, 10315, -1, 10315, 16284, 16279, -1, 16279, 16284, 16268, -1, 16268, 16284, 16280, -1, 16271, 16285, 16272, -1, 16272, 16285, 16281, -1, 16283, 16286, 16287, -1, 16281, 16286, 16274, -1, 16282, 16286, 16283, -1, 16274, 16286, 16282, -1, 16271, 16288, 16285, -1, 16280, 16288, 16271, -1, 16285, 16289, 16281, -1, 16287, 16289, 16290, -1, 16286, 16289, 16287, -1, 16281, 16289, 16286, -1, 16280, 16291, 16288, -1, 10306, 16291, 10311, -1, 10311, 16291, 16284, -1, 16284, 16291, 16280, -1, 16288, 16292, 16285, -1, 16290, 16292, 16293, -1, 16289, 16292, 16290, -1, 16285, 16292, 16289, -1, 10301, 10284, 16294, -1, 16293, 16295, 16294, -1, 10301, 16295, 10306, -1, 16288, 16295, 16292, -1, 10306, 16295, 16291, -1, 12413, 16296, 13318, -1, 16294, 16295, 10301, -1, 16291, 16295, 16288, -1, 16292, 16295, 16293, -1, 16267, 16296, 12413, -1, 16266, 16297, 16267, -1, 16267, 16297, 16296, -1, 13317, 16273, 13315, -1, 13318, 16273, 13317, -1, 16296, 16273, 13318, -1, 16265, 16270, 16266, -1, 16266, 16270, 16297, -1, 16296, 16276, 16273, -1, 16297, 16276, 16296, -1, 16264, 16269, 16265, -1, 16265, 16269, 16270, -1, 16270, 16272, 16297, -1, 16297, 16272, 16276, -1, 13313, 16275, 13311, -1, 13315, 16275, 13313, -1, 16273, 16275, 13315, -1, 12411, 12410, 16298, -1, 16298, 16278, 16299, -1, 12410, 16278, 16298, -1, 16299, 16283, 16300, -1, 16278, 16283, 16299, -1, 16300, 16287, 16301, -1, 16283, 16287, 16300, -1, 16301, 16290, 16302, -1, 16287, 16290, 16301, -1, 16302, 16293, 16303, -1, 16290, 16293, 16302, -1, 16293, 16294, 16303, -1, 16303, 10284, 10137, -1, 16294, 10284, 16303, -1, 10367, 16303, 10137, -1, 10367, 16302, 16303, -1, 10367, 16301, 16302, -1, 13659, 16299, 16300, -1, 13659, 16298, 16299, -1, 13659, 12411, 16298, -1, 11278, 16304, 10132, -1, 10368, 16304, 10367, -1, 10132, 16304, 10368, -1, 11281, 16305, 11278, -1, 11278, 16305, 16304, -1, 16304, 16305, 10367, -1, 11282, 16306, 11281, -1, 16305, 16306, 10367, -1, 11281, 16306, 16305, -1, 10367, 16306, 16301, -1, 11284, 16307, 11282, -1, 11286, 16307, 11284, -1, 16301, 16307, 16300, -1, 16306, 16307, 16301, -1, 16300, 16307, 13659, -1, 11282, 16307, 16306, -1, 16307, 16308, 13659, -1, 11286, 16308, 16307, -1, 13657, 16309, 10518, -1, 13659, 16309, 13657, -1, 11288, 16309, 11286, -1, 10518, 16309, 11288, -1, 11286, 16309, 16308, -1, 16308, 16309, 13659, -1, 13647, 8783, 8785, -1, 13647, 8781, 8783, -1, 10125, 16310, 16311, -1, 10125, 10167, 16310, -1, 10046, 16312, 10048, -1, 13645, 16312, 13647, -1, 10048, 16312, 13645, -1, 10041, 16313, 10042, -1, 10042, 16313, 10046, -1, 10046, 16313, 16312, -1, 16312, 16313, 13647, -1, 16313, 16314, 13647, -1, 10041, 16314, 16313, -1, 11297, 16315, 10041, -1, 10041, 16315, 16314, -1, 11295, 16316, 11297, -1, 11297, 16316, 16315, -1, 11291, 16317, 11293, -1, 11293, 16317, 11295, -1, 11295, 16317, 16316, -1, 10124, 16318, 10123, -1, 10125, 16318, 10124, -1, 10123, 16318, 11291, -1, 16317, 16318, 10125, -1, 11291, 16318, 16317, -1, 8781, 16319, 8780, -1, 16320, 16319, 16311, -1, 16321, 16319, 16320, -1, 8780, 16319, 16321, -1, 16317, 16319, 16316, -1, 16315, 16319, 16314, -1, 10125, 16319, 16317, -1, 16316, 16319, 16315, -1, 13647, 16319, 8781, -1, 16311, 16319, 10125, -1, 16314, 16319, 13647, -1, 10167, 10152, 16310, -1, 10152, 16322, 16310, -1, 16310, 16323, 16311, -1, 16311, 16323, 16320, -1, 16322, 16323, 16310, -1, 16323, 16324, 16320, -1, 16320, 16325, 16321, -1, 16321, 16325, 8780, -1, 16324, 16325, 16320, -1, 16325, 8778, 8780, -1, 16326, 16327, 8747, -1, 16328, 16327, 16326, -1, 16329, 16327, 16328, -1, 16324, 16330, 16325, -1, 8782, 13341, 8784, -1, 16325, 16330, 16331, -1, 16331, 16332, 16333, -1, 16333, 16332, 16334, -1, 8769, 16335, 8772, -1, 16334, 16335, 16329, -1, 16329, 16335, 16327, -1, 16327, 16335, 8769, -1, 16323, 16336, 16324, -1, 16324, 16336, 16330, -1, 16331, 16337, 16332, -1, 16330, 16337, 16331, -1, 8772, 16338, 8777, -1, 16334, 16338, 16335, -1, 16335, 16338, 8772, -1, 16332, 16338, 16334, -1, 10172, 16339, 10152, -1, 10152, 16339, 16322, -1, 16322, 16339, 16323, -1, 16323, 16339, 16336, -1, 13348, 8747, 8746, -1, 16336, 16340, 16330, -1, 16330, 16340, 16337, -1, 8777, 16341, 8753, -1, 16338, 16341, 8777, -1, 16337, 16341, 16332, -1, 16332, 16341, 16338, -1, 10191, 16342, 10172, -1, 10200, 16342, 10191, -1, 10172, 16342, 16339, -1, 16339, 16342, 16336, -1, 16336, 16342, 16340, -1, 8753, 16343, 8752, -1, 16341, 16343, 8753, -1, 16340, 16343, 16337, -1, 16337, 16343, 16341, -1, 10200, 16344, 16342, -1, 10203, 16344, 10200, -1, 16340, 16344, 16343, -1, 16343, 16344, 8752, -1, 8752, 16344, 10203, -1, 16342, 16344, 16340, -1, 10203, 8751, 8752, -1, 13341, 16345, 13343, -1, 8782, 16345, 13341, -1, 8779, 16346, 8782, -1, 8782, 16346, 16345, -1, 13343, 16328, 13345, -1, 16345, 16328, 13343, -1, 8778, 16333, 8779, -1, 8779, 16333, 16346, -1, 16345, 16329, 16328, -1, 16346, 16329, 16345, -1, 16325, 16331, 8778, -1, 8778, 16331, 16333, -1, 13345, 16326, 13348, -1, 13348, 16326, 8747, -1, 16328, 16326, 13345, -1, 16333, 16334, 16346, -1, 16346, 16334, 16329, -1, 8747, 16327, 8769, -1, 8765, 10196, 8763, -1, 8763, 16347, 8761, -1, 10196, 16347, 8763, -1, 8761, 16348, 8757, -1, 16347, 16348, 8761, -1, 8757, 16349, 8743, -1, 16348, 16349, 8757, -1, 8743, 16350, 8741, -1, 16349, 16350, 8743, -1, 8741, 16351, 8775, -1, 16350, 16351, 8741, -1, 8775, 16352, 8773, -1, 16351, 16352, 8775, -1, 16352, 12421, 8773, -1, 16353, 16354, 13337, -1, 16348, 16355, 16349, -1, 16349, 16355, 16356, -1, 16357, 16358, 16359, -1, 16356, 16358, 16357, -1, 16353, 16360, 16354, -1, 16361, 16360, 16353, -1, 13333, 16362, 16363, -1, 16354, 16362, 13333, -1, 10275, 16364, 10196, -1, 10272, 16364, 10275, -1, 10196, 16364, 16347, -1, 16347, 16364, 16348, -1, 16348, 16364, 16355, -1, 16356, 16365, 16358, -1, 16355, 16365, 16356, -1, 16359, 16366, 16361, -1, 16361, 16366, 16360, -1, 13333, 16363, 12418, -1, 16363, 16367, 16368, -1, 16360, 16367, 16354, -1, 16362, 16367, 16363, -1, 16354, 16367, 16362, -1, 10262, 16369, 10272, -1, 10272, 16369, 16364, -1, 16364, 16369, 16355, -1, 16355, 16369, 16365, -1, 16358, 16370, 16359, -1, 16359, 16370, 16366, -1, 16368, 16371, 16372, -1, 16366, 16371, 16360, -1, 16360, 16371, 16367, -1, 16367, 16371, 16368, -1, 16358, 16373, 16370, -1, 16365, 16373, 16358, -1, 16370, 16374, 16366, -1, 16372, 16374, 16375, -1, 16366, 16374, 16371, -1, 16371, 16374, 16372, -1, 16365, 16376, 16373, -1, 10256, 16376, 10262, -1, 10262, 16376, 16369, -1, 16369, 16376, 16365, -1, 16373, 16377, 16370, -1, 16375, 16377, 16378, -1, 16374, 16377, 16375, -1, 16370, 16377, 16374, -1, 10254, 10243, 16379, -1, 16378, 16380, 16379, -1, 10254, 16380, 10256, -1, 16373, 16380, 16377, -1, 12421, 16381, 13340, -1, 10256, 16380, 16376, -1, 16379, 16380, 10254, -1, 16376, 16380, 16373, -1, 16377, 16380, 16378, -1, 16352, 16381, 12421, -1, 16351, 16382, 16352, -1, 16352, 16382, 16381, -1, 13339, 16353, 13337, -1, 13340, 16353, 13339, -1, 16381, 16353, 13340, -1, 16350, 16357, 16351, -1, 16351, 16357, 16382, -1, 16381, 16361, 16353, -1, 16382, 16361, 16381, -1, 16349, 16356, 16350, -1, 16350, 16356, 16357, -1, 16357, 16359, 16382, -1, 16382, 16359, 16361, -1, 13335, 16354, 13333, -1, 13337, 16354, 13335, -1, 12418, 16363, 12419, -1, 12419, 16363, 16383, -1, 16383, 16368, 16384, -1, 16363, 16368, 16383, -1, 16384, 16372, 16385, -1, 16368, 16372, 16384, -1, 16385, 16375, 16386, -1, 16372, 16375, 16385, -1, 16386, 16378, 16387, -1, 16375, 16378, 16386, -1, 16387, 16379, 16388, -1, 16378, 16379, 16387, -1, 16388, 10243, 10245, -1, 16379, 10243, 16388, -1, 10322, 16388, 10245, -1, 10322, 16387, 16388, -1, 10322, 16386, 16387, -1, 13643, 16384, 16385, -1, 13643, 16383, 16384, -1, 13643, 12419, 16383, -1, 11301, 16389, 10324, -1, 10323, 16389, 10322, -1, 10324, 16389, 10323, -1, 11304, 16390, 11301, -1, 11301, 16390, 16389, -1, 16389, 16390, 10322, -1, 11305, 16391, 11304, -1, 16390, 16391, 10322, -1, 11304, 16391, 16390, -1, 10322, 16391, 16386, -1, 11307, 16392, 11305, -1, 11309, 16392, 11307, -1, 16386, 16392, 16385, -1, 16391, 16392, 16386, -1, 16385, 16392, 13643, -1, 11305, 16392, 16391, -1, 16392, 16393, 13643, -1, 11309, 16393, 16392, -1, 13641, 16394, 10511, -1, 13643, 16394, 13641, -1, 11311, 16394, 11309, -1, 10511, 16394, 11311, -1, 11309, 16394, 16393, -1, 16393, 16394, 13643, -1, 13639, 8733, 8735, -1, 13639, 8731, 8733, -1, 10139, 16395, 16396, -1, 10139, 10230, 16395, -1, 10034, 16397, 10038, -1, 10038, 16397, 10040, -1, 13637, 16397, 13639, -1, 10040, 16397, 13637, -1, 10034, 16398, 16397, -1, 16397, 16398, 13639, -1, 10033, 16399, 10034, -1, 16398, 16399, 13639, -1, 10034, 16399, 16398, -1, 11320, 16400, 10033, -1, 10033, 16400, 16399, -1, 11318, 16401, 11320, -1, 11320, 16401, 16400, -1, 11316, 16402, 11318, -1, 11318, 16402, 16401, -1, 10138, 16403, 10129, -1, 10139, 16403, 10138, -1, 10129, 16403, 11314, -1, 11314, 16403, 11316, -1, 11316, 16403, 16402, -1, 16402, 16403, 10139, -1, 8731, 16404, 8729, -1, 16405, 16404, 16396, -1, 16406, 16404, 16405, -1, 8729, 16404, 16406, -1, 16402, 16404, 16401, -1, 16400, 16404, 16399, -1, 10139, 16404, 16402, -1, 16401, 16404, 16400, -1, 13639, 16404, 8731, -1, 16396, 16404, 10139, -1, 16399, 16404, 13639, -1, 10230, 10343, 16395, -1, 10343, 16407, 16395, -1, 16395, 16408, 16396, -1, 16407, 16408, 16395, -1, 16396, 16409, 16405, -1, 16408, 16409, 16396, -1, 16405, 16410, 16406, -1, 16409, 16410, 16405, -1, 16406, 8730, 8729, -1, 16410, 8730, 16406, -1, 16411, 16412, 8697, -1, 16413, 16412, 16411, -1, 16414, 16412, 16413, -1, 16409, 16415, 16410, -1, 8734, 13363, 8736, -1, 16410, 16415, 16416, -1, 16416, 16417, 16418, -1, 16418, 16417, 16419, -1, 8720, 16420, 8723, -1, 16419, 16420, 16414, -1, 16414, 16420, 16412, -1, 16412, 16420, 8720, -1, 16408, 16421, 16409, -1, 16409, 16421, 16415, -1, 16416, 16422, 16417, -1, 16415, 16422, 16416, -1, 8723, 16423, 8728, -1, 16419, 16423, 16420, -1, 16420, 16423, 8723, -1, 16417, 16423, 16419, -1, 10346, 16424, 10343, -1, 10343, 16424, 16407, -1, 16407, 16424, 16408, -1, 16408, 16424, 16421, -1, 13370, 8697, 8696, -1, 16421, 16425, 16415, -1, 16415, 16425, 16422, -1, 8728, 16426, 8704, -1, 16423, 16426, 8728, -1, 16422, 16426, 16417, -1, 16417, 16426, 16423, -1, 10347, 16427, 10346, -1, 10351, 16427, 10347, -1, 10346, 16427, 16424, -1, 16424, 16427, 16421, -1, 16421, 16427, 16425, -1, 8704, 16428, 8703, -1, 16426, 16428, 8704, -1, 16425, 16428, 16422, -1, 16422, 16428, 16426, -1, 10351, 16429, 16427, -1, 10357, 16429, 10351, -1, 16425, 16429, 16428, -1, 16428, 16429, 8703, -1, 8703, 16429, 10357, -1, 16427, 16429, 16425, -1, 10357, 8702, 8703, -1, 13363, 16430, 13365, -1, 8734, 16430, 13363, -1, 8732, 16431, 8734, -1, 8734, 16431, 16430, -1, 13365, 16413, 13367, -1, 16430, 16413, 13365, -1, 8730, 16418, 8732, -1, 8732, 16418, 16431, -1, 16430, 16414, 16413, -1, 16431, 16414, 16430, -1, 16410, 16416, 8730, -1, 8730, 16416, 16418, -1, 13367, 16411, 13370, -1, 13370, 16411, 8697, -1, 16413, 16411, 13367, -1, 16418, 16419, 16431, -1, 16431, 16419, 16414, -1, 8697, 16412, 8720, -1, 8716, 10195, 8714, -1, 8714, 16432, 8712, -1, 10195, 16432, 8714, -1, 8712, 16433, 8708, -1, 16432, 16433, 8712, -1, 8708, 16434, 8694, -1, 16433, 16434, 8708, -1, 8694, 16435, 8692, -1, 16434, 16435, 8694, -1, 8692, 16436, 8726, -1, 16435, 16436, 8692, -1, 8726, 16437, 8724, -1, 16436, 16437, 8726, -1, 16437, 12429, 8724, -1, 16438, 16439, 13359, -1, 16433, 16440, 16434, -1, 16434, 16440, 16441, -1, 16442, 16443, 16444, -1, 16441, 16443, 16442, -1, 16438, 16445, 16439, -1, 16446, 16445, 16438, -1, 13355, 16447, 16448, -1, 16439, 16447, 13355, -1, 10223, 16449, 10195, -1, 10222, 16449, 10223, -1, 10195, 16449, 16432, -1, 16432, 16449, 16433, -1, 16433, 16449, 16440, -1, 16441, 16450, 16443, -1, 16440, 16450, 16441, -1, 16444, 16451, 16446, -1, 16446, 16451, 16445, -1, 13355, 16448, 12426, -1, 16448, 16452, 16453, -1, 16445, 16452, 16439, -1, 16447, 16452, 16448, -1, 16439, 16452, 16447, -1, 10221, 16454, 10222, -1, 10222, 16454, 16449, -1, 16449, 16454, 16440, -1, 16440, 16454, 16450, -1, 16443, 16455, 16444, -1, 16444, 16455, 16451, -1, 16453, 16456, 16457, -1, 16451, 16456, 16445, -1, 16445, 16456, 16452, -1, 16452, 16456, 16453, -1, 16443, 16458, 16455, -1, 16450, 16458, 16443, -1, 16455, 16459, 16451, -1, 16457, 16459, 16460, -1, 16451, 16459, 16456, -1, 16456, 16459, 16457, -1, 16450, 16461, 16458, -1, 10213, 16461, 10221, -1, 10221, 16461, 16454, -1, 16454, 16461, 16450, -1, 16458, 16462, 16455, -1, 16460, 16462, 16463, -1, 16459, 16462, 16460, -1, 16455, 16462, 16459, -1, 10205, 10151, 16464, -1, 16463, 16465, 16464, -1, 10205, 16465, 10213, -1, 16458, 16465, 16462, -1, 12429, 16466, 13362, -1, 10213, 16465, 16461, -1, 16464, 16465, 10205, -1, 16461, 16465, 16458, -1, 16462, 16465, 16463, -1, 16437, 16466, 12429, -1, 16436, 16467, 16437, -1, 16437, 16467, 16466, -1, 13361, 16438, 13359, -1, 13362, 16438, 13361, -1, 16466, 16438, 13362, -1, 16435, 16442, 16436, -1, 16436, 16442, 16467, -1, 16466, 16446, 16438, -1, 16467, 16446, 16466, -1, 16434, 16441, 16435, -1, 16435, 16441, 16442, -1, 16442, 16444, 16467, -1, 16467, 16444, 16446, -1, 13357, 16439, 13355, -1, 13359, 16439, 13357, -1, 12426, 16448, 12427, -1, 12427, 16448, 16468, -1, 16468, 16453, 16469, -1, 16448, 16453, 16468, -1, 16469, 16457, 16470, -1, 16453, 16457, 16469, -1, 16471, 16460, 16472, -1, 16470, 16460, 16471, -1, 16457, 16460, 16470, -1, 16472, 16463, 16473, -1, 16460, 16463, 16472, -1, 16463, 16464, 16473, -1, 16473, 10151, 10153, -1, 16464, 10151, 16473, -1, 10263, 16473, 10153, -1, 10263, 16472, 16473, -1, 10263, 16471, 16472, -1, 13635, 16469, 16470, -1, 13635, 16468, 16469, -1, 13635, 12427, 16468, -1, 11324, 16474, 10122, -1, 10264, 16474, 10263, -1, 10122, 16474, 10264, -1, 11327, 16475, 11324, -1, 11324, 16475, 16474, -1, 16474, 16475, 10263, -1, 11328, 16476, 11327, -1, 16475, 16476, 10263, -1, 11327, 16476, 16475, -1, 10263, 16476, 16471, -1, 11330, 16477, 11328, -1, 16471, 16477, 16470, -1, 16476, 16477, 16471, -1, 16470, 16477, 13635, -1, 11328, 16477, 16476, -1, 11332, 16478, 11330, -1, 16477, 16478, 13635, -1, 11330, 16478, 16477, -1, 13633, 16479, 10504, -1, 13635, 16479, 13633, -1, 11334, 16479, 11332, -1, 10504, 16479, 11334, -1, 16478, 16479, 13635, -1, 11332, 16479, 16478, -1, 13631, 8685, 8687, -1, 13631, 8683, 8685, -1, 10146, 16480, 16481, -1, 10146, 10294, 16480, -1, 10030, 16482, 10032, -1, 13629, 16482, 13631, -1, 10032, 16482, 13629, -1, 10026, 16483, 10030, -1, 10030, 16483, 16482, -1, 16482, 16483, 13631, -1, 10025, 16484, 10026, -1, 16483, 16484, 13631, -1, 10026, 16484, 16483, -1, 11343, 16485, 10025, -1, 10025, 16485, 16484, -1, 11339, 16486, 11341, -1, 11341, 16486, 11343, -1, 11343, 16486, 16485, -1, 11339, 16487, 16486, -1, 10145, 16488, 10140, -1, 10146, 16488, 10145, -1, 10140, 16488, 11337, -1, 11337, 16488, 11339, -1, 11339, 16488, 16487, -1, 16487, 16488, 10146, -1, 8683, 16489, 8682, -1, 16490, 16489, 16481, -1, 16491, 16489, 16490, -1, 8682, 16489, 16491, -1, 16487, 16489, 16486, -1, 16485, 16489, 16484, -1, 10146, 16489, 16487, -1, 13631, 16489, 8683, -1, 16486, 16489, 16485, -1, 16481, 16489, 10146, -1, 16484, 16489, 13631, -1, 10294, 10293, 16480, -1, 10293, 16492, 16480, -1, 16480, 16493, 16481, -1, 16492, 16493, 16480, -1, 16481, 16494, 16490, -1, 16493, 16494, 16481, -1, 16490, 16495, 16491, -1, 16494, 16495, 16490, -1, 16491, 8680, 8682, -1, 16495, 8680, 16491, -1, 16496, 16497, 8648, -1, 16498, 16497, 16496, -1, 16499, 16497, 16498, -1, 16494, 16500, 16495, -1, 8684, 13376, 8686, -1, 16495, 16500, 16501, -1, 16501, 16502, 16503, -1, 16503, 16502, 16504, -1, 8671, 16505, 8674, -1, 16504, 16505, 16499, -1, 16499, 16505, 16497, -1, 16497, 16505, 8671, -1, 16493, 16506, 16494, -1, 16494, 16506, 16500, -1, 16501, 16507, 16502, -1, 16500, 16507, 16501, -1, 8674, 16508, 8679, -1, 16504, 16508, 16505, -1, 16505, 16508, 8674, -1, 16502, 16508, 16504, -1, 10299, 16509, 10293, -1, 10293, 16509, 16492, -1, 16492, 16509, 16493, -1, 16493, 16509, 16506, -1, 13383, 8648, 8647, -1, 16506, 16510, 16500, -1, 16500, 16510, 16507, -1, 8679, 16511, 8655, -1, 16508, 16511, 8679, -1, 16507, 16511, 16502, -1, 16502, 16511, 16508, -1, 10303, 16512, 10299, -1, 10310, 16512, 10303, -1, 10299, 16512, 16509, -1, 16509, 16512, 16506, -1, 16506, 16512, 16510, -1, 8655, 16513, 8654, -1, 16511, 16513, 8655, -1, 16510, 16513, 16507, -1, 16507, 16513, 16511, -1, 10310, 16514, 16512, -1, 10314, 16514, 10310, -1, 16510, 16514, 16513, -1, 16513, 16514, 8654, -1, 8654, 16514, 10314, -1, 16512, 16514, 16510, -1, 10314, 8653, 8654, -1, 13376, 16515, 13378, -1, 8684, 16515, 13376, -1, 8681, 16516, 8684, -1, 8684, 16516, 16515, -1, 13378, 16498, 13380, -1, 16515, 16498, 13378, -1, 8680, 16503, 8681, -1, 8681, 16503, 16516, -1, 16515, 16499, 16498, -1, 16516, 16499, 16515, -1, 16495, 16501, 8680, -1, 8680, 16501, 16503, -1, 13380, 16496, 13383, -1, 13383, 16496, 8648, -1, 16498, 16496, 13380, -1, 16503, 16504, 16516, -1, 16516, 16504, 16499, -1, 8648, 16497, 8671, -1, 8667, 10194, 8665, -1, 8665, 16517, 8663, -1, 10194, 16517, 8665, -1, 8663, 16518, 8659, -1, 16517, 16518, 8663, -1, 8659, 16519, 8645, -1, 16518, 16519, 8659, -1, 8645, 16520, 8643, -1, 16519, 16520, 8645, -1, 8643, 16521, 8677, -1, 16520, 16521, 8643, -1, 8677, 16522, 8675, -1, 16521, 16522, 8677, -1, 16522, 12437, 8675, -1, 16518, 16523, 16519, -1, 16519, 16523, 16524, -1, 16525, 16526, 16527, -1, 16524, 16526, 16525, -1, 16528, 16529, 16530, -1, 16531, 16529, 16528, -1, 13390, 16532, 16533, -1, 16530, 16532, 13390, -1, 10381, 16534, 10194, -1, 10378, 16534, 10381, -1, 10194, 16534, 16517, -1, 16517, 16534, 16518, -1, 16518, 16534, 16523, -1, 16524, 16535, 16526, -1, 16523, 16535, 16524, -1, 16527, 16536, 16531, -1, 16531, 16536, 16529, -1, 13390, 16533, 12434, -1, 16533, 16537, 16538, -1, 16529, 16537, 16530, -1, 16532, 16537, 16533, -1, 16530, 16537, 16532, -1, 10376, 16539, 10378, -1, 10378, 16539, 16534, -1, 16534, 16539, 16523, -1, 16523, 16539, 16535, -1, 16526, 16540, 16527, -1, 16527, 16540, 16536, -1, 16538, 16541, 16542, -1, 16536, 16541, 16529, -1, 16529, 16541, 16537, -1, 16537, 16541, 16538, -1, 16526, 16543, 16540, -1, 16535, 16543, 16526, -1, 16540, 16544, 16536, -1, 16542, 16544, 16545, -1, 16536, 16544, 16541, -1, 16541, 16544, 16542, -1, 16535, 16546, 16543, -1, 10366, 16546, 10376, -1, 10376, 16546, 16539, -1, 16539, 16546, 16535, -1, 16543, 16547, 16540, -1, 16545, 16547, 16548, -1, 16544, 16547, 16545, -1, 16540, 16547, 16544, -1, 10360, 10344, 16549, -1, 16548, 16550, 16549, -1, 10360, 16550, 10366, -1, 16543, 16550, 16547, -1, 12437, 16551, 13397, -1, 10366, 16550, 16546, -1, 16549, 16550, 10360, -1, 16546, 16550, 16543, -1, 16547, 16550, 16548, -1, 16522, 16551, 12437, -1, 16521, 16552, 16522, -1, 16522, 16552, 16551, -1, 13396, 16528, 13394, -1, 13397, 16528, 13396, -1, 16551, 16528, 13397, -1, 16520, 16525, 16521, -1, 16521, 16525, 16552, -1, 16551, 16531, 16528, -1, 16552, 16531, 16551, -1, 16519, 16524, 16520, -1, 16520, 16524, 16525, -1, 16525, 16527, 16552, -1, 16552, 16527, 16531, -1, 13392, 16530, 13390, -1, 13394, 16530, 13392, -1, 16528, 16530, 13394, -1, 12435, 12434, 16553, -1, 16553, 16533, 16554, -1, 12434, 16533, 16553, -1, 16554, 16538, 16555, -1, 16533, 16538, 16554, -1, 16555, 16542, 16556, -1, 16538, 16542, 16555, -1, 16556, 16545, 16557, -1, 16542, 16545, 16556, -1, 16557, 16548, 16558, -1, 16545, 16548, 16557, -1, 16548, 16549, 16558, -1, 16558, 10344, 10207, -1, 16549, 10344, 16558, -1, 10206, 16558, 10207, -1, 10206, 16557, 16558, -1, 10206, 16556, 16557, -1, 13627, 16554, 16555, -1, 13627, 16553, 16554, -1, 13627, 12435, 16553, -1, 11347, 16559, 10136, -1, 10208, 16559, 10206, -1, 10136, 16559, 10208, -1, 11350, 16560, 11347, -1, 11347, 16560, 16559, -1, 16559, 16560, 10206, -1, 11351, 16561, 11350, -1, 16560, 16561, 10206, -1, 11350, 16561, 16560, -1, 10206, 16561, 16556, -1, 11353, 16562, 11351, -1, 16556, 16562, 16555, -1, 16561, 16562, 16556, -1, 16555, 16562, 13627, -1, 11351, 16562, 16561, -1, 11355, 16563, 11353, -1, 11357, 16563, 11355, -1, 16562, 16563, 13627, -1, 11353, 16563, 16562, -1, 13625, 16564, 10497, -1, 13627, 16564, 13625, -1, 10497, 16564, 11357, -1, 11357, 16564, 16563, -1, 16563, 16564, 13627, -1, 13607, 8635, 8637, -1, 13607, 8633, 8635, -1, 10177, 16565, 16566, -1, 10177, 10250, 16565, -1, 10022, 16567, 10024, -1, 13605, 16567, 13607, -1, 10024, 16567, 13605, -1, 10017, 16568, 10018, -1, 10018, 16568, 10022, -1, 10022, 16568, 16567, -1, 16567, 16568, 13607, -1, 16568, 16569, 13607, -1, 10017, 16569, 16568, -1, 11366, 16570, 10017, -1, 10017, 16570, 16569, -1, 11362, 16571, 11364, -1, 11364, 16571, 11366, -1, 11366, 16571, 16570, -1, 11362, 16572, 16571, -1, 10176, 16573, 10169, -1, 10177, 16573, 10176, -1, 10169, 16573, 11360, -1, 11360, 16573, 11362, -1, 11362, 16573, 16572, -1, 16572, 16573, 10177, -1, 8633, 16574, 8631, -1, 16575, 16574, 16566, -1, 16576, 16574, 16575, -1, 8631, 16574, 16576, -1, 16572, 16574, 16571, -1, 16570, 16574, 16569, -1, 10177, 16574, 16572, -1, 16571, 16574, 16570, -1, 13607, 16574, 8633, -1, 16566, 16574, 10177, -1, 16569, 16574, 13607, -1, 10250, 10180, 16565, -1, 10180, 16577, 16565, -1, 16565, 16578, 16566, -1, 16566, 16578, 16575, -1, 16577, 16578, 16565, -1, 16578, 16579, 16575, -1, 16575, 16580, 16576, -1, 16579, 16580, 16575, -1, 16576, 8632, 8631, -1, 16580, 8632, 16576, -1, 16581, 16582, 8600, -1, 16583, 16582, 16581, -1, 16584, 16582, 16583, -1, 16579, 16585, 16580, -1, 8636, 13442, 8638, -1, 16580, 16585, 16586, -1, 16586, 16587, 16588, -1, 16588, 16587, 16589, -1, 8622, 16590, 8625, -1, 16589, 16590, 16584, -1, 16584, 16590, 16582, -1, 16582, 16590, 8622, -1, 16578, 16591, 16579, -1, 16579, 16591, 16585, -1, 16586, 16592, 16587, -1, 16585, 16592, 16586, -1, 8625, 16593, 8630, -1, 16589, 16593, 16590, -1, 16590, 16593, 8625, -1, 16587, 16593, 16589, -1, 10340, 16594, 10180, -1, 10180, 16594, 16577, -1, 16577, 16594, 16578, -1, 16578, 16594, 16591, -1, 13449, 8600, 8599, -1, 16591, 16595, 16585, -1, 16585, 16595, 16592, -1, 8630, 16596, 8606, -1, 16593, 16596, 8630, -1, 16592, 16596, 16587, -1, 16587, 16596, 16593, -1, 10345, 16597, 10340, -1, 10348, 16597, 10345, -1, 10340, 16597, 16594, -1, 16594, 16597, 16591, -1, 16591, 16597, 16595, -1, 8606, 16598, 8605, -1, 16596, 16598, 8606, -1, 16595, 16598, 16592, -1, 16592, 16598, 16596, -1, 10348, 16599, 16597, -1, 10350, 16599, 10348, -1, 16595, 16599, 16598, -1, 16598, 16599, 8605, -1, 8605, 16599, 10350, -1, 16597, 16599, 16595, -1, 10350, 8604, 8605, -1, 13442, 16600, 13444, -1, 8636, 16600, 13442, -1, 8634, 16601, 8636, -1, 8636, 16601, 16600, -1, 13444, 16583, 13446, -1, 16600, 16583, 13444, -1, 8632, 16588, 8634, -1, 8634, 16588, 16601, -1, 16600, 16584, 16583, -1, 16601, 16584, 16600, -1, 16580, 16586, 8632, -1, 8632, 16586, 16588, -1, 13446, 16581, 13449, -1, 13449, 16581, 8600, -1, 16583, 16581, 13446, -1, 16588, 16589, 16601, -1, 16601, 16589, 16584, -1, 8600, 16582, 8622, -1, 10190, 16602, 8618, -1, 8618, 16602, 8616, -1, 8616, 16602, 8614, -1, 8614, 16603, 8610, -1, 16602, 16603, 8614, -1, 8610, 16604, 8596, -1, 16603, 16604, 8610, -1, 8596, 16605, 8594, -1, 16604, 16605, 8596, -1, 8594, 16606, 8628, -1, 16605, 16606, 8594, -1, 8628, 16607, 8626, -1, 16606, 16607, 8628, -1, 16607, 12461, 8626, -1, 16603, 16608, 16604, -1, 16604, 16608, 16609, -1, 16610, 16611, 16612, -1, 16609, 16611, 16610, -1, 16613, 16614, 16615, -1, 16616, 16614, 16613, -1, 13456, 16617, 16618, -1, 16615, 16617, 13456, -1, 10220, 16619, 10190, -1, 10214, 16619, 10220, -1, 10190, 16619, 16602, -1, 16602, 16619, 16603, -1, 16603, 16619, 16608, -1, 16609, 16620, 16611, -1, 16608, 16620, 16609, -1, 16612, 16621, 16616, -1, 16616, 16621, 16614, -1, 13456, 16618, 12458, -1, 16618, 16622, 16623, -1, 16614, 16622, 16615, -1, 16617, 16622, 16618, -1, 16615, 16622, 16617, -1, 10211, 16624, 10214, -1, 10214, 16624, 16619, -1, 16619, 16624, 16608, -1, 16608, 16624, 16620, -1, 16611, 16625, 16612, -1, 16612, 16625, 16621, -1, 16623, 16626, 16627, -1, 16621, 16626, 16614, -1, 16614, 16626, 16622, -1, 16622, 16626, 16623, -1, 16611, 16628, 16625, -1, 16620, 16628, 16611, -1, 16625, 16629, 16621, -1, 16627, 16629, 16630, -1, 16621, 16629, 16626, -1, 16626, 16629, 16627, -1, 16620, 16631, 16628, -1, 10204, 16631, 10211, -1, 10211, 16631, 16624, -1, 16624, 16631, 16620, -1, 16628, 16632, 16625, -1, 16630, 16632, 16633, -1, 16629, 16632, 16630, -1, 16625, 16632, 16629, -1, 10201, 10126, 16634, -1, 16633, 16635, 16634, -1, 10201, 16635, 10204, -1, 16628, 16635, 16632, -1, 12461, 16636, 13463, -1, 10204, 16635, 16631, -1, 16634, 16635, 10201, -1, 16631, 16635, 16628, -1, 16632, 16635, 16633, -1, 16607, 16636, 12461, -1, 16606, 16637, 16607, -1, 16607, 16637, 16636, -1, 13462, 16613, 13460, -1, 13463, 16613, 13462, -1, 16636, 16613, 13463, -1, 16605, 16610, 16606, -1, 16606, 16610, 16637, -1, 16636, 16616, 16613, -1, 16637, 16616, 16636, -1, 16604, 16609, 16605, -1, 16605, 16609, 16610, -1, 16610, 16612, 16637, -1, 16637, 16612, 16616, -1, 13458, 16615, 13456, -1, 13460, 16615, 13458, -1, 16613, 16615, 13460, -1, 12459, 12458, 16638, -1, 16638, 16618, 16639, -1, 12458, 16618, 16638, -1, 16639, 16623, 16640, -1, 16618, 16623, 16639, -1, 16640, 16627, 16641, -1, 16623, 16627, 16640, -1, 16641, 16630, 16642, -1, 16627, 16630, 16641, -1, 16642, 16633, 16643, -1, 16630, 16633, 16642, -1, 16643, 16634, 10279, -1, 16633, 16634, 16643, -1, 16634, 10126, 10279, -1, 10278, 16643, 10279, -1, 10278, 16642, 16643, -1, 10278, 16641, 16642, -1, 13603, 16639, 16640, -1, 13603, 16638, 16639, -1, 13603, 12459, 16638, -1, 11370, 16644, 10165, -1, 10280, 16644, 10278, -1, 10165, 16644, 10280, -1, 11373, 16645, 11370, -1, 11370, 16645, 16644, -1, 16644, 16645, 10278, -1, 11374, 16646, 11373, -1, 16645, 16646, 10278, -1, 11373, 16646, 16645, -1, 10278, 16646, 16641, -1, 11376, 16647, 11374, -1, 16641, 16647, 16640, -1, 16646, 16647, 16641, -1, 16640, 16647, 13603, -1, 11374, 16647, 16646, -1, 11378, 16648, 11376, -1, 16647, 16648, 13603, -1, 11376, 16648, 16647, -1, 13601, 16649, 10476, -1, 13603, 16649, 13601, -1, 11380, 16649, 11378, -1, 10476, 16649, 11380, -1, 16648, 16649, 13603, -1, 11378, 16649, 16648, -1, 10210, 10209, 14367, -1, 14365, 16650, 14364, -1, 14366, 16650, 14365, -1, 14367, 16650, 14366, -1, 10209, 16650, 14367, -1, 14363, 16651, 14362, -1, 14364, 16651, 14363, -1, 16650, 16651, 14364, -1, 14360, 16652, 14359, -1, 14361, 16652, 14360, -1, 14362, 16652, 14361, -1, 16651, 16652, 14362, -1, 14359, 16653, 14358, -1, 16652, 16653, 14359, -1, 14358, 8583, 8585, -1, 16653, 8583, 14358, -1, 13599, 8580, 8581, -1, 13599, 8578, 8580, -1, 10215, 16654, 16655, -1, 10215, 10183, 16654, -1, 8587, 16656, 8589, -1, 13597, 16656, 13599, -1, 8589, 16656, 13597, -1, 8584, 16657, 8587, -1, 8587, 16657, 16656, -1, 16656, 16657, 13599, -1, 8583, 16658, 8584, -1, 16657, 16658, 13599, -1, 8584, 16658, 16657, -1, 16653, 16659, 8583, -1, 8583, 16659, 16658, -1, 16652, 16660, 16653, -1, 16653, 16660, 16659, -1, 16651, 16661, 16652, -1, 16652, 16661, 16660, -1, 10212, 16662, 10209, -1, 10215, 16662, 10212, -1, 10209, 16662, 16650, -1, 16650, 16662, 16651, -1, 16651, 16662, 16661, -1, 16661, 16662, 10215, -1, 8578, 16663, 8577, -1, 16664, 16663, 16655, -1, 16665, 16663, 16664, -1, 8577, 16663, 16665, -1, 16659, 16663, 16658, -1, 16661, 16663, 16660, -1, 10215, 16663, 16661, -1, 13599, 16663, 8578, -1, 16660, 16663, 16659, -1, 16655, 16663, 10215, -1, 16658, 16663, 13599, -1, 10183, 10182, 16654, -1, 10182, 16666, 16654, -1, 16654, 16667, 16655, -1, 16666, 16667, 16654, -1, 16655, 16668, 16664, -1, 16667, 16668, 16655, -1, 16664, 16669, 16665, -1, 16665, 16669, 8577, -1, 16668, 16669, 16664, -1, 16669, 8575, 8577, -1, 16670, 16671, 16672, -1, 13474, 16673, 13472, -1, 16674, 16675, 16676, -1, 16672, 16673, 13474, -1, 16676, 16675, 16677, -1, 16669, 16678, 8575, -1, 8579, 13477, 8582, -1, 8575, 16678, 16679, -1, 16680, 16681, 16682, -1, 16682, 16681, 16683, -1, 16679, 16684, 16685, -1, 10300, 16686, 16687, -1, 16685, 16684, 16671, -1, 16687, 16686, 16688, -1, 10305, 16686, 10300, -1, 10312, 16686, 10305, -1, 16688, 16686, 16689, -1, 13469, 16690, 11997, -1, 13470, 16690, 13469, -1, 16671, 16691, 16672, -1, 11997, 16690, 16692, -1, 16683, 16690, 13470, -1, 16672, 16691, 16673, -1, 16693, 16694, 16695, -1, 16689, 16694, 16693, -1, 16668, 16696, 16669, -1, 16669, 16696, 16678, -1, 13472, 16697, 13471, -1, 16677, 16698, 16680, -1, 16680, 16698, 16681, -1, 16673, 16697, 13472, -1, 16695, 16699, 16674, -1, 16679, 16700, 16684, -1, 16674, 16699, 16675, -1, 16678, 16700, 16679, -1, 16692, 16701, 16702, -1, 16681, 16701, 16683, -1, 16671, 16703, 16691, -1, 16683, 16701, 16690, -1, 16684, 16703, 16671, -1, 16690, 16701, 16692, -1, 10312, 16704, 16686, -1, 16686, 16704, 16689, -1, 16667, 16705, 16668, -1, 16689, 16704, 16694, -1, 16668, 16705, 16696, -1, 16675, 16706, 16677, -1, 16691, 16707, 16673, -1, 16677, 16706, 16698, -1, 16673, 16707, 16697, -1, 16694, 16708, 16695, -1, 16695, 16708, 16699, -1, 16702, 16709, 16710, -1, 16678, 16711, 16700, -1, 16698, 16709, 16681, -1, 16696, 16711, 16678, -1, 16701, 16709, 16702, -1, 13471, 16682, 13470, -1, 16681, 16709, 16701, -1, 16697, 16682, 13471, -1, 16699, 16712, 16675, -1, 16675, 16712, 16706, -1, 16700, 16713, 16684, -1, 16704, 16714, 16694, -1, 10319, 16714, 10312, -1, 16684, 16713, 16703, -1, 10321, 16714, 10319, -1, 16694, 16714, 16708, -1, 10312, 16714, 16704, -1, 16703, 16676, 16691, -1, 16710, 16715, 16716, -1, 16698, 16715, 16709, -1, 16691, 16676, 16707, -1, 16709, 16715, 16710, -1, 16706, 16715, 16698, -1, 10297, 16717, 10182, -1, 10300, 16717, 10297, -1, 10182, 16717, 16666, -1, 16666, 16717, 16667, -1, 16667, 16717, 16705, -1, 16708, 16718, 16699, -1, 16705, 16688, 16696, -1, 16699, 16718, 16712, -1, 16716, 16719, 16720, -1, 16715, 16719, 16716, -1, 16696, 16688, 16711, -1, 16712, 16719, 16706, -1, 16707, 16680, 16697, -1, 16706, 16719, 16715, -1, 10325, 16721, 10321, -1, 10321, 16721, 16714, -1, 16714, 16721, 16708, -1, 16708, 16721, 16718, -1, 16697, 16680, 16682, -1, 16720, 16722, 16723, -1, 16711, 16693, 16700, -1, 16719, 16722, 16720, -1, 16718, 16722, 16712, -1, 16712, 16722, 16719, -1, 16700, 16693, 16713, -1, 16703, 16674, 16676, -1, 16722, 16724, 16723, -1, 16713, 16674, 16703, -1, 16718, 16724, 16722, -1, 10326, 16724, 10325, -1, 10325, 16724, 16721, -1, 16723, 16724, 10326, -1, 16721, 16724, 16718, -1, 10326, 10189, 16723, -1, 16676, 16677, 16707, -1, 13477, 16670, 13476, -1, 8579, 16670, 13477, -1, 16707, 16677, 16680, -1, 8576, 16685, 8579, -1, 10300, 16687, 16717, -1, 16717, 16687, 16705, -1, 16705, 16687, 16688, -1, 8579, 16685, 16670, -1, 13476, 16672, 13474, -1, 16670, 16672, 13476, -1, 16682, 16683, 13470, -1, 8575, 16679, 8576, -1, 16688, 16689, 16711, -1, 16711, 16689, 16693, -1, 8576, 16679, 16685, -1, 16693, 16695, 16713, -1, 16713, 16695, 16674, -1, 16685, 16671, 16670, -1, 11997, 16692, 11998, -1, 16725, 16692, 16726, -1, 11998, 16692, 16725, -1, 16726, 16702, 16727, -1, 16692, 16702, 16726, -1, 16727, 16710, 16728, -1, 16702, 16710, 16727, -1, 16728, 16716, 16729, -1, 16710, 16716, 16728, -1, 16729, 16720, 16730, -1, 16716, 16720, 16729, -1, 16730, 16723, 10188, -1, 16720, 16723, 16730, -1, 16723, 10189, 10188, -1, 16729, 16731, 16728, -1, 16728, 16731, 16732, -1, 16733, 16734, 16735, -1, 16732, 16734, 16733, -1, 16736, 16737, 16738, -1, 16739, 16737, 16736, -1, 13468, 16740, 16741, -1, 16738, 16740, 13468, -1, 10372, 16742, 10188, -1, 10369, 16742, 10372, -1, 10188, 16742, 16730, -1, 16730, 16742, 16729, -1, 16729, 16742, 16731, -1, 16732, 16743, 16734, -1, 16731, 16743, 16732, -1, 16735, 16744, 16739, -1, 16739, 16744, 16737, -1, 13468, 16741, 12466, -1, 16741, 16745, 16746, -1, 16737, 16745, 16738, -1, 16740, 16745, 16741, -1, 16738, 16745, 16740, -1, 10364, 16747, 10369, -1, 10369, 16747, 16742, -1, 16742, 16747, 16731, -1, 16731, 16747, 16743, -1, 16734, 16748, 16735, -1, 16735, 16748, 16744, -1, 16746, 16749, 16750, -1, 16744, 16749, 16737, -1, 16737, 16749, 16745, -1, 16745, 16749, 16746, -1, 16734, 16751, 16748, -1, 16743, 16751, 16734, -1, 16748, 16752, 16744, -1, 16750, 16752, 16753, -1, 16744, 16752, 16749, -1, 16749, 16752, 16750, -1, 16743, 16754, 16751, -1, 10356, 16754, 10364, -1, 10364, 16754, 16747, -1, 16747, 16754, 16743, -1, 16751, 16755, 16748, -1, 16753, 16755, 16756, -1, 16752, 16755, 16753, -1, 16748, 16755, 16752, -1, 10349, 10179, 16757, -1, 16756, 16758, 16757, -1, 10349, 16758, 10356, -1, 16751, 16758, 16755, -1, 11998, 16759, 13464, -1, 10356, 16758, 16754, -1, 16757, 16758, 10349, -1, 16754, 16758, 16751, -1, 16755, 16758, 16756, -1, 16725, 16759, 11998, -1, 16726, 16760, 16725, -1, 16725, 16760, 16759, -1, 13465, 16736, 13466, -1, 13464, 16736, 13465, -1, 16759, 16736, 13464, -1, 16727, 16733, 16726, -1, 16726, 16733, 16760, -1, 16759, 16739, 16736, -1, 16760, 16739, 16759, -1, 16728, 16732, 16727, -1, 16727, 16732, 16733, -1, 16733, 16735, 16760, -1, 16760, 16735, 16739, -1, 13467, 16738, 13468, -1, 13466, 16738, 13467, -1, 16736, 16738, 13466, -1, 12466, 16741, 12467, -1, 12467, 16741, 16761, -1, 16761, 16746, 16762, -1, 16741, 16746, 16761, -1, 16762, 16750, 16763, -1, 16746, 16750, 16762, -1, 16763, 16753, 16764, -1, 16750, 16753, 16763, -1, 16764, 16756, 16765, -1, 16753, 16756, 16764, -1, 16765, 16757, 16766, -1, 16756, 16757, 16765, -1, 16766, 10179, 10178, -1, 16757, 10179, 16766, -1, 10229, 16766, 10178, -1, 10229, 16765, 16766, -1, 10229, 16764, 16765, -1, 13594, 16762, 16763, -1, 13594, 16761, 16762, -1, 13594, 12467, 16761, -1, 11384, 16767, 10175, -1, 10228, 16767, 10229, -1, 10175, 16767, 10228, -1, 11387, 16768, 11384, -1, 11384, 16768, 16767, -1, 16767, 16768, 10229, -1, 11388, 16769, 11387, -1, 16768, 16769, 10229, -1, 11387, 16769, 16768, -1, 10229, 16769, 16764, -1, 11390, 16770, 11388, -1, 16764, 16770, 16763, -1, 16769, 16770, 16764, -1, 16763, 16770, 13594, -1, 11388, 16770, 16769, -1, 11392, 16771, 11390, -1, 16770, 16771, 13594, -1, 11390, 16771, 16770, -1, 13592, 16772, 10468, -1, 13594, 16772, 13592, -1, 11394, 16772, 11392, -1, 10468, 16772, 11394, -1, 16771, 16772, 13594, -1, 11392, 16772, 16771, -1, 10316, 16773, 10231, -1, 10316, 16774, 16773, -1, 10316, 16775, 16774, -1, 13611, 16776, 16777, -1, 13611, 16778, 16776, -1, 13611, 12451, 16778, -1, 10317, 16779, 10316, -1, 10154, 16779, 10317, -1, 11399, 16779, 10154, -1, 11400, 16780, 11399, -1, 11399, 16780, 16779, -1, 16779, 16780, 10316, -1, 11402, 16781, 11400, -1, 11400, 16781, 16780, -1, 16780, 16781, 10316, -1, 10316, 16781, 16775, -1, 16775, 16782, 16777, -1, 11404, 16782, 11402, -1, 16781, 16782, 16775, -1, 11402, 16782, 16781, -1, 16777, 16782, 13611, -1, 11406, 16783, 11404, -1, 16782, 16783, 13611, -1, 11404, 16783, 16782, -1, 13609, 16784, 10483, -1, 13611, 16784, 13609, -1, 10483, 16784, 11408, -1, 11408, 16784, 11406, -1, 11406, 16784, 16783, -1, 16783, 16784, 13611, -1, 12451, 12450, 16778, -1, 16778, 16785, 16776, -1, 12450, 16785, 16778, -1, 16776, 16786, 16777, -1, 16785, 16786, 16776, -1, 16777, 16787, 16775, -1, 16786, 16787, 16777, -1, 16775, 16788, 16774, -1, 16787, 16788, 16775, -1, 16774, 16789, 16773, -1, 16788, 16789, 16774, -1, 16773, 16790, 10231, -1, 16789, 16790, 16773, -1, 16790, 10234, 10231, -1, 16791, 16792, 13425, -1, 16793, 16794, 16795, -1, 16795, 16794, 16796, -1, 16796, 16797, 16798, -1, 16798, 16797, 16799, -1, 16800, 16801, 16791, -1, 16791, 16801, 16792, -1, 16785, 16802, 16786, -1, 16792, 16802, 13421, -1, 13421, 16802, 16785, -1, 10277, 16803, 10192, -1, 10276, 16803, 10277, -1, 16804, 16803, 16793, -1, 10192, 16803, 16804, -1, 16793, 16803, 16794, -1, 16794, 16805, 16796, -1, 16796, 16805, 16797, -1, 16800, 16806, 16801, -1, 16799, 16806, 16800, -1, 16802, 16807, 16786, -1, 13421, 16785, 12450, -1, 16801, 16807, 16792, -1, 16792, 16807, 16802, -1, 10274, 16808, 10276, -1, 10276, 16808, 16803, -1, 16803, 16808, 16794, -1, 16794, 16808, 16805, -1, 16797, 16809, 16799, -1, 16799, 16809, 16806, -1, 16786, 16810, 16787, -1, 16807, 16810, 16786, -1, 16806, 16810, 16801, -1, 16801, 16810, 16807, -1, 16797, 16811, 16809, -1, 16805, 16811, 16797, -1, 16809, 16812, 16806, -1, 16787, 16812, 16788, -1, 16810, 16812, 16787, -1, 16806, 16812, 16810, -1, 10257, 16813, 10274, -1, 16805, 16813, 16811, -1, 10274, 16813, 16808, -1, 16808, 16813, 16805, -1, 16788, 16814, 16789, -1, 16809, 16814, 16812, -1, 16811, 16814, 16809, -1, 16812, 16814, 16788, -1, 10257, 16815, 16813, -1, 10252, 10234, 16790, -1, 10252, 16815, 10257, -1, 16814, 16815, 16789, -1, 16816, 16817, 12453, -1, 16811, 16815, 16814, -1, 16789, 16815, 16790, -1, 16813, 16815, 16811, -1, 16790, 16815, 10252, -1, 12453, 16817, 13428, -1, 16818, 16819, 16816, -1, 16816, 16819, 16817, -1, 13427, 16791, 13425, -1, 13428, 16791, 13427, -1, 16817, 16791, 13428, -1, 16820, 16798, 16818, -1, 16818, 16798, 16819, -1, 16817, 16800, 16791, -1, 16819, 16800, 16817, -1, 16795, 16796, 16820, -1, 16820, 16796, 16798, -1, 16798, 16799, 16819, -1, 16819, 16799, 16800, -1, 13423, 16792, 13421, -1, 13425, 16792, 13423, -1, 8562, 10192, 8560, -1, 8560, 16804, 8558, -1, 10192, 16804, 8560, -1, 8558, 16793, 8554, -1, 16804, 16793, 8558, -1, 8554, 16795, 8540, -1, 16793, 16795, 8554, -1, 8540, 16820, 8538, -1, 16795, 16820, 8540, -1, 8538, 16818, 8572, -1, 16820, 16818, 8538, -1, 8572, 16816, 8570, -1, 16818, 16816, 8572, -1, 16816, 12453, 8570, -1, 16821, 16822, 8544, -1, 16823, 16822, 16821, -1, 16824, 16822, 16823, -1, 16825, 16826, 16827, -1, 16827, 16826, 16828, -1, 8530, 13429, 8532, -1, 16829, 16830, 16831, -1, 16828, 16830, 16829, -1, 8566, 16832, 8569, -1, 16824, 16832, 16822, -1, 16831, 16832, 16824, -1, 16822, 16832, 8566, -1, 16833, 16834, 16825, -1, 16825, 16834, 16826, -1, 16826, 16835, 16828, -1, 16828, 16835, 16830, -1, 8569, 16836, 8574, -1, 16832, 16836, 8569, -1, 16830, 16836, 16831, -1, 16831, 16836, 16832, -1, 10128, 16837, 10392, -1, 16838, 16837, 16833, -1, 10392, 16837, 16838, -1, 16833, 16837, 16834, -1, 13436, 8544, 8543, -1, 16826, 16839, 16835, -1, 16834, 16839, 16826, -1, 8574, 16840, 8550, -1, 16836, 16840, 8574, -1, 16835, 16840, 16830, -1, 16830, 16840, 16836, -1, 10127, 16841, 10128, -1, 10185, 16841, 10127, -1, 10128, 16841, 16837, -1, 16837, 16841, 16834, -1, 16834, 16841, 16839, -1, 8550, 16842, 8549, -1, 16840, 16842, 8550, -1, 16839, 16842, 16835, -1, 16835, 16842, 16840, -1, 10185, 16843, 16841, -1, 10199, 16843, 10185, -1, 16839, 16843, 16842, -1, 16841, 16843, 16839, -1, 16842, 16843, 8549, -1, 8549, 16843, 10199, -1, 10199, 8548, 8549, -1, 13429, 16844, 13431, -1, 8530, 16844, 13429, -1, 8527, 16845, 8530, -1, 8530, 16845, 16844, -1, 13431, 16823, 13433, -1, 16844, 16823, 13431, -1, 8526, 16829, 8527, -1, 8527, 16829, 16845, -1, 16844, 16824, 16823, -1, 16845, 16824, 16844, -1, 16827, 16828, 8526, -1, 8526, 16828, 16829, -1, 13433, 16821, 13436, -1, 13436, 16821, 8544, -1, 16823, 16821, 13433, -1, 16845, 16831, 16824, -1, 16829, 16831, 16845, -1, 8544, 16822, 8566, -1, 10288, 10392, 16846, -1, 16846, 16838, 16847, -1, 10392, 16838, 16846, -1, 16847, 16833, 16848, -1, 16838, 16833, 16847, -1, 16848, 16825, 16849, -1, 16833, 16825, 16848, -1, 16849, 16827, 8528, -1, 16825, 16827, 16849, -1, 16827, 8526, 8528, -1, 13615, 8531, 8533, -1, 13615, 8529, 8531, -1, 10168, 16846, 16847, -1, 10168, 10288, 16846, -1, 10014, 16850, 10016, -1, 13613, 16850, 13615, -1, 10016, 16850, 13613, -1, 10010, 16851, 10014, -1, 16850, 16851, 13615, -1, 10014, 16851, 16850, -1, 11417, 16852, 10009, -1, 10009, 16852, 10010, -1, 10010, 16852, 16851, -1, 16851, 16852, 13615, -1, 11417, 16853, 16852, -1, 11415, 16854, 11417, -1, 11417, 16854, 16853, -1, 11413, 16855, 11415, -1, 11415, 16855, 16854, -1, 10166, 16856, 10161, -1, 10168, 16856, 10166, -1, 11411, 16856, 11413, -1, 10161, 16856, 11411, -1, 11413, 16856, 16855, -1, 16855, 16856, 10168, -1, 8528, 16857, 16849, -1, 16849, 16857, 16848, -1, 16848, 16857, 16847, -1, 8529, 16857, 8528, -1, 16855, 16857, 16854, -1, 10168, 16857, 16855, -1, 16854, 16857, 16853, -1, 16853, 16857, 16852, -1, 13615, 16857, 8529, -1, 16847, 16857, 10168, -1, 16852, 16857, 13615, -1, 16858, 12539, 12552, -1, 16858, 12552, 16859, -1, 16860, 16858, 16859, -1, 16861, 16859, 16862, -1, 16861, 16862, 16863, -1, 16861, 16860, 16859, -1, 16864, 16863, 16865, -1, 16864, 16865, 16866, -1, 16864, 16861, 16863, -1, 16867, 16866, 16868, -1, 16867, 16868, 16869, -1, 16867, 16869, 16870, -1, 16867, 16870, 16871, -1, 16867, 16864, 16866, -1, 16872, 16871, 16873, -1, 16872, 16873, 16874, -1, 16872, 16867, 16871, -1, 12525, 16874, 12526, -1, 12525, 16872, 16874, -1, 16875, 16876, 16877, -1, 16875, 16877, 16858, -1, 16875, 16878, 16876, -1, 16879, 16880, 16881, -1, 16879, 16881, 16882, -1, 16883, 16882, 16884, -1, 16883, 16884, 16885, -1, 16886, 16860, 16861, -1, 16886, 16885, 16878, -1, 16886, 16878, 16875, -1, 12553, 8524, 8523, -1, 16886, 16875, 16860, -1, 16887, 12644, 12642, -1, 16887, 16888, 16880, -1, 16887, 12642, 16888, -1, 16887, 16880, 16879, -1, 16889, 16882, 16883, -1, 16889, 16879, 16882, -1, 16890, 16861, 16864, -1, 16890, 16883, 16885, -1, 16890, 16886, 16861, -1, 16890, 16885, 16886, -1, 16891, 12646, 12644, -1, 16891, 12644, 16887, -1, 16891, 16887, 16879, -1, 16891, 16879, 16889, -1, 16892, 16864, 16867, -1, 16892, 16883, 16890, -1, 16892, 16890, 16864, -1, 16892, 16889, 16883, -1, 16893, 16872, 12525, -1, 16893, 16867, 16872, -1, 16893, 12525, 12646, -1, 16893, 12646, 16891, -1, 16893, 16892, 16867, -1, 16893, 16891, 16889, -1, 16893, 16889, 16892, -1, 12642, 12589, 16888, -1, 16894, 16895, 8524, -1, 16894, 8524, 12553, -1, 16896, 16897, 16895, -1, 16896, 16895, 16894, -1, 16876, 12553, 12546, -1, 16876, 16894, 12553, -1, 16884, 16898, 16897, -1, 16884, 16897, 16896, -1, 16878, 16894, 16876, -1, 16878, 16896, 16894, -1, 16877, 12539, 16858, -1, 16877, 12546, 12542, -1, 16877, 12542, 12539, -1, 16877, 16876, 12546, -1, 16882, 16881, 16898, -1, 16882, 16898, 16884, -1, 16885, 16896, 16878, -1, 16885, 16884, 16896, -1, 16875, 16858, 16860, -1, 16899, 8522, 8524, -1, 16899, 8524, 16895, -1, 16900, 16895, 16897, -1, 16900, 16899, 16895, -1, 16901, 16897, 16898, -1, 16901, 16900, 16897, -1, 16902, 16898, 16881, -1, 16902, 16901, 16898, -1, 16903, 16881, 16880, -1, 16903, 16902, 16881, -1, 16904, 16880, 16888, -1, 16904, 16903, 16880, -1, 12588, 16888, 12589, -1, 12588, 16904, 16888, -1, 16905, 16906, 16907, -1, 16908, 16909, 16910, -1, 16905, 16907, 16911, -1, 16908, 16910, 16912, -1, 16913, 16901, 16902, -1, 16913, 16914, 16901, -1, 16913, 16912, 16915, -1, 16913, 16915, 16914, -1, 16916, 16917, 16918, -1, 16916, 16911, 16917, -1, 16919, 12594, 12596, -1, 16919, 16920, 16909, -1, 16919, 16909, 16908, -1, 16919, 12596, 16920, -1, 16921, 16918, 16922, -1, 16923, 16902, 16903, -1, 16923, 16913, 16902, -1, 16921, 16922, 16924, -1, 16923, 16908, 16912, -1, 16923, 16912, 16913, -1, 16925, 12573, 12565, -1, 16926, 16903, 16904, -1, 16926, 12592, 12594, -1, 16925, 16924, 12573, -1, 16926, 16908, 16923, -1, 16926, 12594, 16919, -1, 16926, 16919, 16908, -1, 16926, 16904, 12592, -1, 16927, 16928, 16906, -1, 16926, 16923, 16903, -1, 16927, 16906, 16905, -1, 16929, 16905, 16911, -1, 16929, 16911, 16916, -1, 16930, 16916, 16918, -1, 16930, 16918, 16921, -1, 16931, 16921, 16924, -1, 16931, 16924, 16925, -1, 16932, 12602, 12603, -1, 16932, 12603, 16928, -1, 16932, 16928, 16927, -1, 16933, 12565, 12561, -1, 8522, 12557, 8525, -1, 16933, 16925, 12565, -1, 16934, 16927, 16905, -1, 16934, 16905, 16929, -1, 16935, 16916, 16930, -1, 16935, 16929, 16916, -1, 16936, 16921, 16931, -1, 16936, 16930, 16921, -1, 16937, 16925, 16933, -1, 16937, 16931, 16925, -1, 16938, 12600, 12602, -1, 16938, 16927, 16934, -1, 16938, 12602, 16932, -1, 16938, 16932, 16927, -1, 16939, 8522, 16899, -1, 16939, 12561, 12557, -1, 16939, 16933, 12561, -1, 16939, 12557, 8522, -1, 16940, 16934, 16929, -1, 16940, 16929, 16935, -1, 16910, 16935, 16930, -1, 12588, 12592, 16904, -1, 16910, 16930, 16936, -1, 16941, 16942, 16943, -1, 16941, 16943, 12551, -1, 16941, 12551, 12580, -1, 16915, 16936, 16931, -1, 16915, 16931, 16937, -1, 16917, 16944, 16942, -1, 16945, 16899, 16900, -1, 16945, 16937, 16933, -1, 16945, 16933, 16939, -1, 16917, 16942, 16941, -1, 16945, 16939, 16899, -1, 16946, 12596, 12598, -1, 16946, 12598, 12600, -1, 16922, 12580, 12578, -1, 16946, 16938, 16934, -1, 16946, 16934, 16940, -1, 16946, 12600, 16938, -1, 16909, 16935, 16910, -1, 16922, 16941, 12580, -1, 16909, 16940, 16935, -1, 16911, 16907, 16944, -1, 16911, 16944, 16917, -1, 16912, 16936, 16915, -1, 16912, 16910, 16936, -1, 16918, 16941, 16922, -1, 16918, 16917, 16941, -1, 16914, 16900, 16901, -1, 16914, 16937, 16945, -1, 16914, 16915, 16937, -1, 16924, 12578, 12573, -1, 16914, 16945, 16900, -1, 16920, 12596, 16946, -1, 16924, 16922, 12578, -1, 16920, 16946, 16940, -1, 16920, 16940, 16909, -1, 16947, 12551, 16943, -1, 16947, 12549, 12551, -1, 16948, 16943, 16942, -1, 16948, 16947, 16943, -1, 16949, 16942, 16944, -1, 16949, 16948, 16942, -1, 16950, 16944, 16907, -1, 16950, 16949, 16944, -1, 16951, 16907, 16906, -1, 16951, 16950, 16907, -1, 16952, 16906, 16928, -1, 16952, 16951, 16906, -1, 12605, 16928, 12603, -1, 12605, 16952, 16928, -1, 16953, 12558, 12549, -1, 16953, 16954, 12559, -1, 16955, 16956, 16957, -1, 16955, 16957, 16958, -1, 12567, 16959, 12568, -1, 16960, 16961, 16962, -1, 16960, 16958, 16961, -1, 16963, 16962, 16964, -1, 16963, 16964, 16965, -1, 16966, 16947, 16948, -1, 16966, 16965, 16954, -1, 16966, 16954, 16953, -1, 16966, 16953, 16947, -1, 16967, 13232, 12585, -1, 16967, 12585, 16956, -1, 16967, 16956, 16955, -1, 16968, 16955, 16958, -1, 16968, 16958, 16960, -1, 16969, 16960, 16962, -1, 16969, 16962, 16963, -1, 16970, 16948, 16949, -1, 16970, 16966, 16948, -1, 16970, 16963, 16965, -1, 16970, 16965, 16966, -1, 16971, 13235, 13232, -1, 16971, 13232, 16967, -1, 16971, 16955, 16968, -1, 16971, 16967, 16955, -1, 16972, 16968, 16960, -1, 16972, 16960, 16969, -1, 16973, 16949, 16950, -1, 16973, 16970, 16949, -1, 16973, 16969, 16963, -1, 16973, 16963, 16970, -1, 16974, 16971, 16968, -1, 16974, 13237, 13235, -1, 16974, 13235, 16971, -1, 16974, 16968, 16972, -1, 16975, 16950, 16951, -1, 16975, 16972, 16969, -1, 16975, 16969, 16973, -1, 16975, 16973, 16950, -1, 16976, 16951, 16952, -1, 16976, 13237, 16974, -1, 16976, 13239, 13237, -1, 16976, 16974, 16972, -1, 16976, 16975, 16951, -1, 16976, 16952, 13239, -1, 16976, 16972, 16975, -1, 12605, 13239, 16952, -1, 16977, 16978, 16959, -1, 16977, 16959, 12567, -1, 16979, 16980, 16978, -1, 16979, 16978, 16977, -1, 16981, 12567, 12569, -1, 16981, 16977, 12567, -1, 16961, 16982, 16980, -1, 16961, 16980, 16979, -1, 16964, 16977, 16981, -1, 16964, 16979, 16977, -1, 16954, 12569, 12559, -1, 16954, 16981, 12569, -1, 16958, 16957, 16982, -1, 16958, 16982, 16961, -1, 16962, 16979, 16964, -1, 16962, 16961, 16979, -1, 16965, 16964, 16981, -1, 16965, 16981, 16954, -1, 16953, 12549, 16947, -1, 16953, 12559, 12558, -1, 14375, 12577, 12568, -1, 14375, 12568, 16959, -1, 14374, 14375, 16959, -1, 14373, 16959, 16978, -1, 14373, 14374, 16959, -1, 14372, 16978, 16980, -1, 14372, 14373, 16978, -1, 14369, 16980, 16982, -1, 14369, 14372, 16980, -1, 14370, 16982, 16957, -1, 14370, 14369, 16982, -1, 14371, 16957, 16956, -1, 14371, 14370, 16957, -1, 12586, 16956, 12585, -1, 12586, 14371, 16956, -1, 16983, 16984, 16985, -1, 16986, 16863, 16862, -1, 16986, 16862, 16987, -1, 16988, 12012, 12009, -1, 16988, 16983, 16985, -1, 16988, 16989, 12012, -1, 16988, 16985, 16989, -1, 16990, 16865, 16863, -1, 16990, 16863, 16986, -1, 16991, 16987, 16983, -1, 16991, 16986, 16987, -1, 16992, 16866, 16865, -1, 12000, 16993, 16994, -1, 12000, 16994, 16995, -1, 12000, 16995, 16996, -1, 12000, 16996, 16997, -1, 16992, 16865, 16990, -1, 12000, 16997, 11999, -1, 16998, 16868, 16866, -1, 16998, 16869, 16868, -1, 16998, 16866, 16992, -1, 16999, 16986, 16991, -1, 16999, 16990, 16986, -1, 17000, 12009, 12008, -1, 17000, 12008, 12010, -1, 17000, 16983, 16988, -1, 17000, 16988, 12009, -1, 17000, 16991, 16983, -1, 17001, 16870, 16869, -1, 17001, 16869, 16998, -1, 17002, 16992, 16990, -1, 17002, 16990, 16999, -1, 17003, 16871, 16870, -1, 17003, 16870, 17001, -1, 17004, 16992, 17002, -1, 17004, 16998, 16992, -1, 17005, 16999, 16991, -1, 17005, 17000, 12010, -1, 17005, 16991, 17000, -1, 17006, 14565, 12526, -1, 17006, 16873, 16871, -1, 17006, 16874, 16873, -1, 17006, 12526, 16874, -1, 17006, 16871, 17003, -1, 17007, 17001, 16998, -1, 17007, 16998, 17004, -1, 17008, 17002, 16999, -1, 17008, 12010, 12011, -1, 17008, 17005, 12010, -1, 17008, 16999, 17005, -1, 17009, 17001, 17007, -1, 17009, 17003, 17001, -1, 17010, 17004, 17002, -1, 17010, 17008, 12011, -1, 17010, 12011, 12005, -1, 17010, 17002, 17008, -1, 17011, 14562, 14565, -1, 17011, 14565, 17006, -1, 17011, 17006, 17003, -1, 17011, 17003, 17009, -1, 17012, 17004, 17010, -1, 17012, 12005, 12004, -1, 17012, 17010, 12005, -1, 17012, 17007, 17004, -1, 17013, 17009, 17007, -1, 17013, 17007, 17012, -1, 17013, 17012, 12004, -1, 17014, 12003, 14562, -1, 17014, 14562, 17011, -1, 17014, 17009, 17013, -1, 16984, 16859, 12552, -1, 17014, 12004, 12006, -1, 17014, 17011, 17009, -1, 16984, 12552, 16993, -1, 17014, 12006, 12007, -1, 17014, 12007, 12003, -1, 17014, 17013, 12004, -1, 16984, 16993, 12000, -1, 16985, 16984, 12000, -1, 16987, 16862, 16859, -1, 16987, 16859, 16984, -1, 16989, 12000, 12012, -1, 16989, 16985, 12000, -1, 16983, 16987, 16984, -1, 11999, 16997, 11533, -1, 11533, 16997, 11534, -1, 11534, 16996, 11535, -1, 16997, 16996, 11534, -1, 11535, 16995, 11536, -1, 16996, 16995, 11535, -1, 11536, 16994, 11537, -1, 16995, 16994, 11536, -1, 11537, 16993, 11538, -1, 16994, 16993, 11537, -1, 16993, 12552, 11538, -1, 11547, 17015, 11553, -1, 17016, 17015, 11546, -1, 17017, 17015, 17016, -1, 17018, 17015, 17017, -1, 13475, 17019, 12058, -1, 12058, 17019, 17020, -1, 17020, 17019, 17021, -1, 11553, 17022, 11556, -1, 17023, 12497, 12500, -1, 17024, 17022, 17018, -1, 17018, 17022, 17015, -1, 17015, 17022, 11553, -1, 11556, 17025, 11559, -1, 11559, 17025, 11567, -1, 17026, 17025, 17024, -1, 17024, 17025, 17022, -1, 17022, 17025, 11556, -1, 11567, 17027, 11568, -1, 17021, 17027, 17026, -1, 17025, 17027, 11567, -1, 17026, 17027, 17025, -1, 13473, 17028, 13475, -1, 11572, 17028, 13473, -1, 11568, 17028, 11571, -1, 11571, 17028, 11572, -1, 17021, 17028, 17027, -1, 13475, 17028, 17019, -1, 17019, 17028, 17021, -1, 17027, 17028, 11568, -1, 12497, 17029, 12496, -1, 17030, 17031, 17023, -1, 17023, 17031, 12497, -1, 12497, 17031, 17029, -1, 17030, 17017, 17031, -1, 17032, 17018, 17030, -1, 17030, 17018, 17017, -1, 12496, 17033, 11551, -1, 11551, 17033, 11549, -1, 17029, 17033, 12496, -1, 17032, 17024, 17018, -1, 11549, 17034, 11577, -1, 11577, 17034, 11541, -1, 17029, 17034, 17033, -1, 17031, 17034, 17029, -1, 17033, 17034, 11549, -1, 17020, 17026, 17032, -1, 17032, 17026, 17024, -1, 17020, 17021, 17026, -1, 11541, 17016, 11546, -1, 17031, 17016, 17034, -1, 17017, 17016, 17031, -1, 17034, 17016, 11541, -1, 11546, 17015, 11547, -1, 12059, 12058, 17035, -1, 17035, 17020, 17036, -1, 12058, 17020, 17035, -1, 17036, 17032, 17037, -1, 17020, 17032, 17036, -1, 17037, 17030, 17038, -1, 17032, 17030, 17037, -1, 17038, 17023, 12499, -1, 17030, 17023, 17038, -1, 17023, 12500, 12499, -1, 12499, 14547, 17038, -1, 17038, 14547, 17037, -1, 17037, 14547, 17036, -1, 14545, 14544, 17039, -1, 12060, 17040, 12061, -1, 12059, 17040, 12060, -1, 17035, 17040, 12059, -1, 17036, 17041, 17035, -1, 17040, 17041, 12061, -1, 14547, 17041, 17036, -1, 17035, 17041, 17040, -1, 14546, 17042, 14547, -1, 14547, 17042, 17041, -1, 12061, 17043, 12062, -1, 17041, 17044, 12061, -1, 12061, 17044, 17043, -1, 12063, 17045, 9074, -1, 12062, 17045, 12063, -1, 9074, 17045, 17046, -1, 17043, 17045, 12062, -1, 17042, 17047, 17041, -1, 14546, 17047, 17042, -1, 17041, 17047, 17044, -1, 17046, 17048, 17039, -1, 17045, 17048, 17046, -1, 17044, 17048, 17043, -1, 17043, 17048, 17045, -1, 14545, 17049, 14546, -1, 14546, 17049, 17047, -1, 17047, 17049, 17044, -1, 17048, 17049, 17039, -1, 17039, 17049, 14545, -1, 17044, 17049, 17048, -1, 14542, 9078, 14543, -1, 9080, 9078, 12342, -1, 12342, 9078, 14542, -1, 9078, 9075, 14543, -1, 14543, 17039, 14544, -1, 9075, 17039, 14543, -1, 9075, 17046, 17039, -1, 9075, 9074, 17046, -1, 10719, 10714, 10716, -1, 10475, 10714, 10719, -1, 10706, 10708, 10475, -1, 10475, 10713, 10714, -1, 10708, 10710, 10475, -1, 10475, 10711, 10713, -1, 10710, 10711, 10475, -1, 10011, 10015, 11418, -1, 11418, 10015, 11416, -1, 11416, 10015, 11414, -1, 11414, 10015, 11412, -1, 11412, 10015, 11410, -1, 11410, 10015, 10162, -1, 10013, 10015, 10012, -1, 10012, 10015, 10011, -1, 10015, 10164, 10162, -1, 11371, 10474, 11372, -1, 11372, 10474, 11375, -1, 11375, 10474, 11377, -1, 11377, 10474, 11379, -1, 11379, 10474, 11381, -1, 10164, 10474, 11371, -1, 10015, 10474, 10164, -1, 10015, 10487, 10474, -1, 10752, 10751, 10487, -1, 10751, 10749, 10487, -1, 10749, 10747, 10487, -1, 10747, 10640, 10487, -1, 10640, 10642, 10487, -1, 10642, 10984, 10487, -1, 10980, 10475, 10984, -1, 10977, 10475, 10980, -1, 10487, 10475, 10474, -1, 10984, 10475, 10487, -1, 10977, 10706, 10475, -1, 10719, 10716, 10717, -1, 10733, 10735, 10482, -1, 10482, 10740, 10741, -1, 10735, 10737, 10482, -1, 10482, 10738, 10740, -1, 10737, 10738, 10482, -1, 10067, 10071, 10684, -1, 10684, 10071, 10682, -1, 10682, 10071, 10680, -1, 10680, 10071, 10678, -1, 10678, 10071, 10676, -1, 10676, 10071, 10148, -1, 10069, 10071, 10068, -1, 10068, 10071, 10067, -1, 10071, 10150, 10148, -1, 11397, 10481, 11401, -1, 11401, 10481, 11403, -1, 11403, 10481, 11405, -1, 11405, 10481, 11407, -1, 11407, 10481, 11409, -1, 10150, 10481, 11397, -1, 10071, 10481, 10150, -1, 10071, 10494, 10481, -1, 10675, 10674, 10494, -1, 10674, 10672, 10494, -1, 10672, 10670, 10494, -1, 10670, 10635, 10494, -1, 10635, 10637, 10494, -1, 10637, 11013, 10494, -1, 11006, 10482, 11009, -1, 11009, 10482, 11013, -1, 10494, 10482, 10481, -1, 11013, 10482, 10494, -1, 11006, 10733, 10482, -1, 10746, 10743, 10744, -1, 10746, 10741, 10743, -1, 10482, 10741, 10746, -1, 10645, 10467, 10480, -1, 10102, 10467, 10103, -1, 10103, 10467, 10106, -1, 10106, 10467, 10107, -1, 10113, 10467, 10645, -1, 10107, 10467, 10113, -1, 10099, 10467, 10097, -1, 10097, 10467, 10100, -1, 10100, 10467, 10102, -1, 10480, 10467, 10466, -1, 10099, 10958, 10467, -1, 10021, 10023, 10020, -1, 10020, 10023, 10019, -1, 10019, 10023, 11367, -1, 11367, 10023, 11365, -1, 11365, 10023, 11363, -1, 10958, 10959, 10467, -1, 11363, 10023, 11361, -1, 11361, 10023, 11359, -1, 11359, 10023, 10170, -1, 10023, 10174, 10170, -1, 10974, 10971, 10972, -1, 10959, 10961, 10467, -1, 10467, 10969, 10974, -1, 10974, 10969, 10971, -1, 10961, 10963, 10467, -1, 10467, 10968, 10969, -1, 10467, 10966, 10968, -1, 10963, 10965, 10467, -1, 10467, 10965, 10966, -1, 10174, 10466, 11385, -1, 11385, 10466, 11386, -1, 11386, 10466, 11389, -1, 11389, 10466, 11391, -1, 11391, 10466, 11393, -1, 11393, 10466, 11395, -1, 10023, 10466, 10174, -1, 10023, 10480, 10466, -1, 10725, 10724, 10480, -1, 10724, 10722, 10480, -1, 10722, 10721, 10480, -1, 10721, 10645, 10480, -1, 10109, 10110, 10114, -1, 10114, 10110, 10112, -1, 10110, 10111, 10112, -1, 10112, 10111, 10113, -1, 10111, 10107, 10113, -1, 10760, 10762, 10496, -1, 10496, 10767, 10768, -1, 10762, 10764, 10496, -1, 10496, 10765, 10767, -1, 10764, 10765, 10496, -1, 10035, 10039, 11321, -1, 11321, 10039, 11319, -1, 11319, 10039, 11317, -1, 11317, 10039, 11315, -1, 11315, 10039, 11313, -1, 11313, 10039, 10130, -1, 10037, 10039, 10036, -1, 10036, 10039, 10035, -1, 10039, 10135, 10130, -1, 11348, 10495, 11349, -1, 11349, 10495, 11352, -1, 11352, 10495, 11354, -1, 11354, 10495, 11356, -1, 11356, 10495, 11358, -1, 10135, 10495, 11348, -1, 10039, 10495, 10135, -1, 10039, 10508, 10495, -1, 10808, 10807, 10508, -1, 10807, 10805, 10508, -1, 10805, 10803, 10508, -1, 10803, 10625, 10508, -1, 10625, 10627, 10508, -1, 10627, 11071, 10508, -1, 11064, 10496, 11067, -1, 11067, 10496, 11071, -1, 10508, 10496, 10495, -1, 11071, 10496, 10508, -1, 11064, 10760, 10496, -1, 10773, 10770, 10771, -1, 10773, 10768, 10770, -1, 10496, 10768, 10773, -1, 10669, 10664, 10666, -1, 10489, 10664, 10669, -1, 10656, 10658, 10489, -1, 10489, 10663, 10664, -1, 10658, 10660, 10489, -1, 10489, 10661, 10663, -1, 10660, 10661, 10489, -1, 10027, 10031, 11344, -1, 11344, 10031, 11342, -1, 11342, 10031, 11340, -1, 11340, 10031, 11338, -1, 11338, 10031, 11336, -1, 11336, 10031, 10141, -1, 10029, 10031, 10028, -1, 10028, 10031, 10027, -1, 10031, 10143, 10141, -1, 10688, 10488, 10689, -1, 10689, 10488, 10692, -1, 10692, 10488, 10694, -1, 10694, 10488, 10696, -1, 10696, 10488, 10698, -1, 10143, 10488, 10688, -1, 10031, 10488, 10143, -1, 10031, 10501, 10488, -1, 10779, 10778, 10501, -1, 10778, 10776, 10501, -1, 10776, 10774, 10501, -1, 10774, 10630, 10501, -1, 10630, 10632, 10501, -1, 10632, 11042, 10501, -1, 11038, 10489, 11042, -1, 11035, 10489, 11038, -1, 10501, 10489, 10488, -1, 11042, 10489, 10501, -1, 11035, 10656, 10489, -1, 10669, 10666, 10667, -1, 10802, 10799, 10800, -1, 10787, 10789, 10503, -1, 10503, 10797, 10802, -1, 10802, 10797, 10799, -1, 10789, 10791, 10503, -1, 10503, 10796, 10797, -1, 10503, 10794, 10796, -1, 10791, 10793, 10503, -1, 10503, 10793, 10794, -1, 10043, 10047, 11298, -1, 11298, 10047, 11296, -1, 11296, 10047, 11294, -1, 11294, 10047, 11292, -1, 11292, 10047, 11290, -1, 11290, 10047, 10404, -1, 10045, 10047, 10044, -1, 10044, 10047, 10043, -1, 10047, 10405, 10404, -1, 11325, 10502, 11326, -1, 11326, 10502, 11329, -1, 11329, 10502, 11331, -1, 11331, 10502, 11333, -1, 11333, 10502, 11335, -1, 10405, 10502, 11325, -1, 10047, 10502, 10405, -1, 10047, 10515, 10502, -1, 10835, 10834, 10515, -1, 10834, 10832, 10515, -1, 10832, 10831, 10515, -1, 10831, 10597, 10515, -1, 10780, 10115, 10781, -1, 10781, 10115, 10601, -1, 10601, 10503, 10597, -1, 10117, 10503, 10115, -1, 10515, 10503, 10502, -1, 10597, 10503, 10515, -1, 10115, 10503, 10601, -1, 10117, 10786, 10503, -1, 10786, 10787, 10503, -1, 10816, 10818, 10510, -1, 10510, 10823, 10824, -1, 10818, 10820, 10510, -1, 10510, 10821, 10823, -1, 10820, 10821, 10510, -1, 10051, 10055, 11275, -1, 11275, 10055, 11273, -1, 11273, 10055, 11271, -1, 11271, 10055, 11269, -1, 11269, 10055, 11267, -1, 11267, 10055, 10400, -1, 10053, 10055, 10052, -1, 10052, 10055, 10051, -1, 10055, 10402, 10400, -1, 11302, 10509, 11303, -1, 11303, 10509, 11306, -1, 11306, 10509, 11308, -1, 11308, 10509, 11310, -1, 11310, 10509, 11312, -1, 10402, 10509, 11302, -1, 10055, 10509, 10402, -1, 10055, 10522, 10509, -1, 10841, 10840, 10522, -1, 10840, 10838, 10522, -1, 10838, 10836, 10522, -1, 10836, 10605, 10522, -1, 10605, 10607, 10522, -1, 10607, 11100, 10522, -1, 11093, 10510, 11096, -1, 11096, 10510, 11100, -1, 10522, 10510, 10509, -1, 11100, 10510, 10522, -1, 11093, 10816, 10510, -1, 10829, 10826, 10827, -1, 10829, 10824, 10826, -1, 10510, 10824, 10829, -1, 10849, 10850, 10517, -1, 10517, 10858, 10863, -1, 10863, 10858, 10860, -1, 10850, 10852, 10517, -1, 10517, 10857, 10858, -1, 10852, 10854, 10517, -1, 10854, 10855, 10517, -1, 10517, 10855, 10857, -1, 10059, 10063, 11252, -1, 11252, 10063, 11250, -1, 11250, 10063, 11248, -1, 11248, 10063, 11246, -1, 11246, 10063, 11244, -1, 11244, 10063, 10395, -1, 10061, 10063, 10060, -1, 10060, 10063, 10059, -1, 10063, 10397, 10395, -1, 11279, 10516, 11280, -1, 11280, 10516, 11283, -1, 11283, 10516, 11285, -1, 11285, 10516, 11287, -1, 11287, 10516, 11289, -1, 10397, 10516, 11279, -1, 10063, 10516, 10397, -1, 10063, 10529, 10516, -1, 10869, 10868, 10529, -1, 10868, 10866, 10529, -1, 10866, 10864, 10529, -1, 10864, 10610, 10529, -1, 10610, 10612, 10529, -1, 10612, 11132, 10529, -1, 11124, 10517, 11128, -1, 11128, 10517, 11132, -1, 10529, 10517, 10516, -1, 11132, 10517, 10529, -1, 11124, 11120, 10517, -1, 11120, 10849, 10517, -1, 10863, 10860, 10861, -1, 10877, 10878, 10524, -1, 10524, 10886, 10891, -1, 10891, 10886, 10888, -1, 10878, 10880, 10524, -1, 10524, 10885, 10886, -1, 10880, 10882, 10524, -1, 10882, 10883, 10524, -1, 10524, 10883, 10885, -1, 10075, 10079, 10574, -1, 10574, 10079, 10572, -1, 10572, 10079, 10570, -1, 10570, 10079, 10568, -1, 10568, 10079, 10566, -1, 10566, 10079, 10226, -1, 10077, 10079, 10076, -1, 10076, 10079, 10075, -1, 10079, 10224, 10226, -1, 11256, 10523, 11257, -1, 11257, 10523, 11260, -1, 11260, 10523, 11262, -1, 11262, 10523, 11264, -1, 11264, 10523, 11266, -1, 10224, 10523, 11256, -1, 10079, 10523, 10224, -1, 10079, 10532, 10523, -1, 10927, 10926, 10532, -1, 10926, 10924, 10532, -1, 10924, 10922, 10532, -1, 10922, 10615, 10532, -1, 10615, 10617, 10532, -1, 10617, 11164, 10532, -1, 11156, 10524, 11160, -1, 11160, 10524, 11164, -1, 10532, 10524, 10523, -1, 11164, 10524, 10532, -1, 11156, 11152, 10524, -1, 11152, 10877, 10524, -1, 10891, 10888, 10889, -1, 10921, 10916, 10918, -1, 10418, 10916, 10921, -1, 10908, 10910, 10418, -1, 10418, 10915, 10916, -1, 10910, 10912, 10418, -1, 10418, 10913, 10915, -1, 10912, 10913, 10418, -1, 10085, 10087, 10084, -1, 10084, 10087, 10083, -1, 10083, 10087, 10565, -1, 10565, 10087, 10563, -1, 10563, 10087, 10561, -1, 10561, 10087, 10559, -1, 10559, 10087, 10557, -1, 10557, 10087, 10408, -1, 10087, 10406, 10408, -1, 10578, 10415, 10579, -1, 10579, 10415, 10582, -1, 10582, 10415, 10584, -1, 10584, 10415, 10586, -1, 10586, 10415, 10588, -1, 10406, 10415, 10578, -1, 10087, 10415, 10406, -1, 10087, 10414, 10415, -1, 10933, 10932, 10414, -1, 10932, 10930, 10414, -1, 10930, 10928, 10414, -1, 10928, 10620, 10414, -1, 10620, 10622, 10414, -1, 10622, 11224, 10414, -1, 11220, 10418, 11224, -1, 11217, 10418, 11220, -1, 10414, 10418, 10415, -1, 11224, 10418, 10414, -1, 11217, 10908, 10418, -1, 10921, 10918, 10919, -1, 11196, 10471, 10423, -1, 11188, 11184, 10471, -1, 11184, 10941, 10471, -1, 10955, 10952, 10953, -1, 10941, 10942, 10471, -1, 10955, 10950, 10952, -1, 10471, 10950, 10955, -1, 10942, 10944, 10471, -1, 10471, 10949, 10950, -1, 10944, 10946, 10471, -1, 10471, 10947, 10949, -1, 10946, 10947, 10471, -1, 10546, 10470, 10547, -1, 10547, 10470, 10550, -1, 10550, 10470, 10552, -1, 10552, 10470, 10554, -1, 10554, 10470, 10556, -1, 10283, 10470, 10546, -1, 10282, 10470, 10283, -1, 10091, 10095, 10542, -1, 10542, 10095, 10540, -1, 10540, 10095, 10538, -1, 10538, 10095, 10536, -1, 10536, 10095, 10534, -1, 10534, 10095, 10282, -1, 10093, 10095, 10092, -1, 10092, 10095, 10091, -1, 10282, 10095, 10470, -1, 10095, 10423, 10470, -1, 10894, 10591, 10898, -1, 10898, 10591, 10900, -1, 10900, 10591, 10423, -1, 10896, 10591, 10893, -1, 10893, 10591, 10894, -1, 10591, 10594, 10423, -1, 10594, 11196, 10423, -1, 11192, 10471, 11196, -1, 11188, 10471, 11192, -1, 10423, 10471, 10470, -1, 17050, 17051, 17052, -1, 17050, 17053, 17051, -1, 17054, 17052, 17055, -1, 17054, 17050, 17052, -1, 17056, 17055, 17057, -1, 17056, 17054, 17055, -1, 17058, 17057, 17059, -1, 17058, 17056, 17057, -1, 17060, 17059, 17061, -1, 17060, 17058, 17059, -1, 17062, 17061, 17063, -1, 17062, 17060, 17061, -1, 17064, 17063, 17065, -1, 17064, 17062, 17063, -1, 17066, 17067, 17068, -1, 17068, 17067, 17069, -1, 17069, 17070, 17071, -1, 17067, 17070, 17069, -1, 17071, 17072, 17073, -1, 17070, 17072, 17071, -1, 17073, 17074, 17075, -1, 17072, 17074, 17073, -1, 17075, 17076, 17077, -1, 17074, 17076, 17075, -1, 17078, 17079, 17080, -1, 17080, 17079, 17081, -1, 17082, 17083, 17084, -1, 17085, 17083, 17082, -1, 17081, 17083, 17086, -1, 17086, 17083, 17085, -1, 17087, 17088, 17089, -1, 17089, 17088, 17090, -1, 17091, 17088, 17092, -1, 17092, 17088, 17093, -1, 17090, 17088, 17091, -1, 17093, 17094, 17078, -1, 17078, 17094, 17079, -1, 17084, 17095, 17096, -1, 17079, 17095, 17081, -1, 17083, 17095, 17084, -1, 17081, 17095, 17083, -1, 17087, 17097, 17088, -1, 17088, 17097, 17093, -1, 17093, 17097, 17094, -1, 17096, 17098, 17099, -1, 17079, 17098, 17095, -1, 17095, 17098, 17096, -1, 17100, 17101, 17102, -1, 17094, 17098, 17079, -1, 17099, 17103, 17104, -1, 17105, 17103, 17087, -1, 17104, 17103, 17105, -1, 17087, 17103, 17097, -1, 17098, 17103, 17099, -1, 17097, 17103, 17094, -1, 17094, 17103, 17098, -1, 17106, 17090, 17091, -1, 17105, 17107, 17104, -1, 17108, 17109, 17110, -1, 17110, 17109, 17111, -1, 17112, 17113, 17108, -1, 17108, 17113, 17109, -1, 17111, 17114, 17115, -1, 17109, 17114, 17111, -1, 17116, 17080, 17112, -1, 17112, 17080, 17113, -1, 17109, 17086, 17114, -1, 17113, 17086, 17109, -1, 17115, 17117, 17100, -1, 17114, 17117, 17115, -1, 17100, 17117, 17101, -1, 17118, 17078, 17116, -1, 17116, 17078, 17080, -1, 17080, 17081, 17113, -1, 17113, 17081, 17086, -1, 17101, 17085, 17082, -1, 17086, 17085, 17114, -1, 17117, 17085, 17101, -1, 17114, 17085, 17117, -1, 17092, 17093, 17118, -1, 17118, 17093, 17078, -1, 17119, 17120, 17121, -1, 17121, 17120, 17122, -1, 17122, 17123, 17124, -1, 17120, 17123, 17122, -1, 17124, 17125, 17126, -1, 17123, 17125, 17124, -1, 17126, 17127, 17128, -1, 17125, 17127, 17126, -1, 17128, 17129, 17130, -1, 17127, 17129, 17128, -1, 17131, 17132, 17133, -1, 17133, 17134, 17135, -1, 17132, 17134, 17133, -1, 17135, 17136, 17137, -1, 17137, 17136, 17138, -1, 17138, 17136, 17139, -1, 17134, 17136, 17135, -1, 17139, 17140, 17141, -1, 17141, 17140, 17142, -1, 17136, 17140, 17139, -1, 17142, 17143, 17144, -1, 17144, 17143, 17145, -1, 17145, 17143, 17146, -1, 17140, 17143, 17142, -1, 17146, 17147, 17148, -1, 17143, 17147, 17146, -1, 17149, 17150, 17151, -1, 17151, 17150, 17152, -1, 17153, 17154, 17155, -1, 17156, 17154, 17157, -1, 17152, 17154, 17156, -1, 17157, 17154, 17153, -1, 17158, 17159, 17160, -1, 17160, 17159, 17161, -1, 17162, 17159, 17163, -1, 17163, 17159, 17164, -1, 17161, 17159, 17162, -1, 17149, 17165, 17150, -1, 17164, 17165, 17149, -1, 17155, 17166, 17167, -1, 17154, 17166, 17155, -1, 17150, 17166, 17152, -1, 17152, 17166, 17154, -1, 17158, 17168, 17159, -1, 17159, 17168, 17164, -1, 17164, 17168, 17165, -1, 17167, 17169, 17170, -1, 17166, 17169, 17167, -1, 17165, 17169, 17150, -1, 17171, 17172, 17173, -1, 17150, 17169, 17166, -1, 17170, 17174, 17175, -1, 17176, 17174, 17158, -1, 17158, 17174, 17168, -1, 17175, 17174, 17176, -1, 17169, 17174, 17170, -1, 17168, 17174, 17165, -1, 17165, 17174, 17169, -1, 17177, 17161, 17162, -1, 17176, 17178, 17175, -1, 17179, 17180, 17181, -1, 17181, 17180, 17182, -1, 17183, 17184, 17179, -1, 17179, 17184, 17180, -1, 17182, 17185, 17186, -1, 17180, 17185, 17182, -1, 17187, 17151, 17183, -1, 17183, 17151, 17184, -1, 17180, 17156, 17185, -1, 17184, 17156, 17180, -1, 17186, 17188, 17171, -1, 17185, 17188, 17186, -1, 17171, 17188, 17172, -1, 17189, 17149, 17187, -1, 17187, 17149, 17151, -1, 17151, 17152, 17184, -1, 17184, 17152, 17156, -1, 17172, 17157, 17153, -1, 17185, 17157, 17188, -1, 17156, 17157, 17185, -1, 17188, 17157, 17172, -1, 17163, 17164, 17189, -1, 17189, 17164, 17149, -1, 17190, 17191, 17192, -1, 17192, 17191, 17193, -1, 17193, 17194, 17195, -1, 17191, 17194, 17193, -1, 17195, 17196, 17197, -1, 17194, 17196, 17195, -1, 17197, 17198, 17199, -1, 17196, 17198, 17197, -1, 17199, 17200, 17201, -1, 17198, 17200, 17199, -1, 17202, 17203, 17204, -1, 17204, 17203, 17205, -1, 17206, 17207, 17208, -1, 17209, 17207, 17210, -1, 17205, 17207, 17209, -1, 17210, 17207, 17206, -1, 17211, 17212, 17213, -1, 17213, 17212, 17214, -1, 17215, 17212, 17216, -1, 17216, 17212, 17217, -1, 17214, 17212, 17215, -1, 17202, 17218, 17203, -1, 17217, 17218, 17202, -1, 17208, 17219, 17220, -1, 17207, 17219, 17208, -1, 17203, 17219, 17205, -1, 17205, 17219, 17207, -1, 17211, 17221, 17212, -1, 17212, 17221, 17217, -1, 17217, 17221, 17218, -1, 17220, 17222, 17223, -1, 17219, 17222, 17220, -1, 17224, 17225, 17226, -1, 17218, 17222, 17203, -1, 17203, 17222, 17219, -1, 17223, 17227, 17228, -1, 17229, 17227, 17211, -1, 17211, 17227, 17221, -1, 17228, 17227, 17229, -1, 17222, 17227, 17223, -1, 17221, 17227, 17218, -1, 17218, 17227, 17222, -1, 17230, 17214, 17215, -1, 17229, 17231, 17228, -1, 17232, 17233, 17234, -1, 17234, 17233, 17235, -1, 17236, 17237, 17232, -1, 17232, 17237, 17233, -1, 17235, 17238, 17239, -1, 17233, 17238, 17235, -1, 17240, 17204, 17236, -1, 17236, 17204, 17237, -1, 17233, 17209, 17238, -1, 17237, 17209, 17233, -1, 17239, 17241, 17224, -1, 17238, 17241, 17239, -1, 17224, 17241, 17225, -1, 17242, 17202, 17240, -1, 17240, 17202, 17204, -1, 17204, 17205, 17237, -1, 17237, 17205, 17209, -1, 17225, 17210, 17206, -1, 17238, 17210, 17241, -1, 17241, 17210, 17225, -1, 17209, 17210, 17238, -1, 17216, 17217, 17242, -1, 17242, 17217, 17202, -1, 17243, 17244, 17245, -1, 17245, 17244, 17246, -1, 17246, 17247, 17248, -1, 17244, 17247, 17246, -1, 17248, 17249, 17250, -1, 17247, 17249, 17248, -1, 17251, 17252, 17253, -1, 17250, 17252, 17251, -1, 17249, 17252, 17250, -1, 17252, 17254, 17253, -1, 17255, 17256, 17257, -1, 17257, 17256, 17258, -1, 17259, 17260, 17261, -1, 17262, 17260, 17263, -1, 17258, 17260, 17262, -1, 17263, 17260, 17259, -1, 17264, 17265, 17266, -1, 17266, 17265, 17267, -1, 17268, 17265, 17269, -1, 17269, 17265, 17270, -1, 17267, 17265, 17268, -1, 17255, 17271, 17256, -1, 17270, 17271, 17255, -1, 17261, 17272, 17273, -1, 17260, 17272, 17261, -1, 17256, 17272, 17258, -1, 17258, 17272, 17260, -1, 17264, 17274, 17265, -1, 17265, 17274, 17270, -1, 17270, 17274, 17271, -1, 17273, 17275, 17276, -1, 17272, 17275, 17273, -1, 17277, 17278, 17279, -1, 17271, 17275, 17256, -1, 17256, 17275, 17272, -1, 17276, 17280, 17281, -1, 17282, 17280, 17264, -1, 17264, 17280, 17274, -1, 17281, 17280, 17282, -1, 17275, 17280, 17276, -1, 17274, 17280, 17271, -1, 17271, 17280, 17275, -1, 17283, 17267, 17268, -1, 17282, 17284, 17281, -1, 17285, 17286, 17287, -1, 17287, 17286, 17288, -1, 17289, 17290, 17285, -1, 17285, 17290, 17286, -1, 17288, 17291, 17292, -1, 17286, 17291, 17288, -1, 17293, 17257, 17289, -1, 17289, 17257, 17290, -1, 17286, 17262, 17291, -1, 17290, 17262, 17286, -1, 17292, 17294, 17277, -1, 17291, 17294, 17292, -1, 17277, 17294, 17278, -1, 17295, 17255, 17293, -1, 17293, 17255, 17257, -1, 17257, 17258, 17290, -1, 17290, 17258, 17262, -1, 17278, 17263, 17259, -1, 17291, 17263, 17294, -1, 17294, 17263, 17278, -1, 17262, 17263, 17291, -1, 17269, 17270, 17295, -1, 17295, 17270, 17255, -1, 17296, 17297, 17298, -1, 17298, 17297, 17299, -1, 17299, 17300, 17301, -1, 17297, 17300, 17299, -1, 17301, 17302, 17303, -1, 17300, 17302, 17301, -1, 17303, 17304, 17305, -1, 17302, 17304, 17303, -1, 17305, 17306, 17307, -1, 17304, 17306, 17305, -1, 17308, 17309, 17310, -1, 17310, 17309, 17311, -1, 17312, 17313, 17314, -1, 17315, 17313, 17316, -1, 17311, 17313, 17315, -1, 17316, 17313, 17312, -1, 17317, 17318, 17319, -1, 17319, 17318, 17320, -1, 17321, 17318, 17322, -1, 17322, 17318, 17323, -1, 17320, 17318, 17321, -1, 17308, 17324, 17309, -1, 17323, 17324, 17308, -1, 17314, 17325, 17326, -1, 17313, 17325, 17314, -1, 17309, 17325, 17311, -1, 17311, 17325, 17313, -1, 17317, 17327, 17318, -1, 17318, 17327, 17323, -1, 17323, 17327, 17324, -1, 17326, 17328, 17329, -1, 17325, 17328, 17326, -1, 17324, 17328, 17309, -1, 17330, 17331, 17332, -1, 17309, 17328, 17325, -1, 17329, 17333, 17334, -1, 17335, 17333, 17317, -1, 17317, 17333, 17327, -1, 17334, 17333, 17335, -1, 17328, 17333, 17329, -1, 17327, 17333, 17324, -1, 17324, 17333, 17328, -1, 17336, 17320, 17321, -1, 17335, 17337, 17334, -1, 17338, 17339, 17340, -1, 17340, 17339, 17341, -1, 17342, 17343, 17338, -1, 17338, 17343, 17339, -1, 17341, 17344, 17345, -1, 17339, 17344, 17341, -1, 17346, 17310, 17342, -1, 17342, 17310, 17343, -1, 17339, 17315, 17344, -1, 17343, 17315, 17339, -1, 17345, 17347, 17330, -1, 17344, 17347, 17345, -1, 17330, 17347, 17331, -1, 17348, 17308, 17346, -1, 17346, 17308, 17310, -1, 17310, 17311, 17343, -1, 17343, 17311, 17315, -1, 17331, 17316, 17312, -1, 17344, 17316, 17347, -1, 17315, 17316, 17344, -1, 17347, 17316, 17331, -1, 17322, 17323, 17348, -1, 17348, 17323, 17308, -1, 17349, 17350, 17351, -1, 17351, 17350, 17352, -1, 17352, 17353, 17354, -1, 17350, 17353, 17352, -1, 17354, 17355, 17356, -1, 17353, 17355, 17354, -1, 17356, 17357, 17358, -1, 17355, 17357, 17356, -1, 17358, 17359, 17360, -1, 17357, 17359, 17358, -1, 17361, 17362, 17363, -1, 17363, 17362, 17364, -1, 17365, 17366, 17367, -1, 17368, 17366, 17369, -1, 17364, 17366, 17368, -1, 17369, 17366, 17365, -1, 17370, 17371, 17372, -1, 17372, 17371, 17373, -1, 17374, 17371, 17375, -1, 17375, 17371, 17376, -1, 17373, 17371, 17374, -1, 17361, 17377, 17362, -1, 17376, 17377, 17361, -1, 17367, 17378, 17379, -1, 17366, 17378, 17367, -1, 17362, 17378, 17364, -1, 17364, 17378, 17366, -1, 17370, 17380, 17371, -1, 17371, 17380, 17376, -1, 17376, 17380, 17377, -1, 17379, 17381, 17382, -1, 17378, 17381, 17379, -1, 17377, 17381, 17362, -1, 17383, 17384, 17385, -1, 17362, 17381, 17378, -1, 17382, 17386, 17387, -1, 17388, 17386, 17370, -1, 17370, 17386, 17380, -1, 17387, 17386, 17388, -1, 17381, 17386, 17382, -1, 17380, 17386, 17377, -1, 17377, 17386, 17381, -1, 17389, 17373, 17374, -1, 17388, 17390, 17387, -1, 17391, 17392, 17393, -1, 17393, 17392, 17394, -1, 17395, 17396, 17391, -1, 17391, 17396, 17392, -1, 17394, 17397, 17398, -1, 17392, 17397, 17394, -1, 17399, 17363, 17395, -1, 17395, 17363, 17396, -1, 17392, 17368, 17397, -1, 17396, 17368, 17392, -1, 17398, 17400, 17383, -1, 17397, 17400, 17398, -1, 17383, 17400, 17384, -1, 17401, 17361, 17399, -1, 17399, 17361, 17363, -1, 17363, 17364, 17396, -1, 17396, 17364, 17368, -1, 17384, 17369, 17365, -1, 17397, 17369, 17400, -1, 17368, 17369, 17397, -1, 17400, 17369, 17384, -1, 17375, 17376, 17401, -1, 17401, 17376, 17361, -1, 17402, 17403, 17404, -1, 17404, 17403, 17405, -1, 17405, 17406, 17407, -1, 17403, 17406, 17405, -1, 17407, 17408, 17409, -1, 17406, 17408, 17407, -1, 17409, 17410, 17411, -1, 17408, 17410, 17409, -1, 17411, 17412, 17413, -1, 17410, 17412, 17411, -1, 17414, 17415, 17416, -1, 17416, 17415, 17417, -1, 17418, 17419, 17420, -1, 17421, 17419, 17422, -1, 17417, 17419, 17421, -1, 17422, 17419, 17418, -1, 17423, 17424, 17425, -1, 17425, 17424, 17426, -1, 17427, 17424, 17428, -1, 17428, 17424, 17429, -1, 17426, 17424, 17427, -1, 17414, 17430, 17415, -1, 17429, 17430, 17414, -1, 17420, 17431, 17432, -1, 17419, 17431, 17420, -1, 17415, 17431, 17417, -1, 17417, 17431, 17419, -1, 17423, 17433, 17424, -1, 17424, 17433, 17429, -1, 17429, 17433, 17430, -1, 17432, 17434, 17435, -1, 17431, 17434, 17432, -1, 17430, 17434, 17415, -1, 17436, 17437, 17438, -1, 17415, 17434, 17431, -1, 17435, 17439, 17440, -1, 17441, 17439, 17423, -1, 17423, 17439, 17433, -1, 17440, 17439, 17441, -1, 17434, 17439, 17435, -1, 17433, 17439, 17430, -1, 17430, 17439, 17434, -1, 17442, 17426, 17427, -1, 17441, 17443, 17440, -1, 17444, 17445, 17446, -1, 17446, 17445, 17447, -1, 17448, 17449, 17444, -1, 17444, 17449, 17445, -1, 17447, 17450, 17451, -1, 17445, 17450, 17447, -1, 17452, 17416, 17448, -1, 17448, 17416, 17449, -1, 17445, 17421, 17450, -1, 17449, 17421, 17445, -1, 17451, 17453, 17436, -1, 17450, 17453, 17451, -1, 17436, 17453, 17437, -1, 17454, 17414, 17452, -1, 17452, 17414, 17416, -1, 17416, 17417, 17449, -1, 17449, 17417, 17421, -1, 17437, 17422, 17418, -1, 17450, 17422, 17453, -1, 17421, 17422, 17450, -1, 17453, 17422, 17437, -1, 17428, 17429, 17454, -1, 17454, 17429, 17414, -1, 17455, 17456, 17457, -1, 17457, 17456, 17458, -1, 17458, 17459, 17460, -1, 17456, 17459, 17458, -1, 17460, 17461, 17462, -1, 17459, 17461, 17460, -1, 17462, 17463, 17464, -1, 17461, 17463, 17462, -1, 17464, 17465, 17466, -1, 17463, 17465, 17464, -1, 17467, 17468, 17469, -1, 17469, 17470, 17471, -1, 17468, 17470, 17469, -1, 17470, 17472, 17471, -1, 17471, 17473, 17474, -1, 17472, 17473, 17471, -1, 17475, 17476, 17477, -1, 17478, 17479, 17475, -1, 17475, 17479, 17476, -1, 17478, 17480, 17479, -1, 17481, 17482, 17478, -1, 17478, 17482, 17480, -1, 17483, 17484, 17481, -1, 17481, 17484, 17482, -1, 17485, 17486, 17483, -1, 17483, 17486, 17484, -1, 17486, 17487, 17484, -1, 17488, 17489, 17490, -1, 17491, 17492, 17488, -1, 17488, 17492, 17489, -1, 17493, 17494, 17491, -1, 17491, 17494, 17492, -1, 17493, 17495, 17494, -1, 17496, 17497, 17493, -1, 17493, 17497, 17495, -1, 17498, 17499, 17496, -1, 17496, 17499, 17497, -1, 17499, 17500, 17497, -1, 17501, 17502, 17503, -1, 17504, 17505, 17501, -1, 17501, 17505, 17502, -1, 17506, 17507, 17504, -1, 17504, 17507, 17505, -1, 17506, 17508, 17507, -1, 17509, 17510, 17506, -1, 17506, 17510, 17508, -1, 17511, 17512, 17509, -1, 17509, 17512, 17510, -1, 17512, 17513, 17510, -1, 17514, 17515, 17516, -1, 17517, 17518, 17514, -1, 17514, 17518, 17515, -1, 17517, 17519, 17518, -1, 17520, 17521, 17517, -1, 17517, 17521, 17519, -1, 17522, 17523, 17520, -1, 17520, 17523, 17521, -1, 17524, 17525, 17522, -1, 17522, 17525, 17523, -1, 17525, 17526, 17523, -1, 17527, 17528, 17529, -1, 17530, 17531, 17527, -1, 17527, 17531, 17528, -1, 17530, 17532, 17531, -1, 17533, 17534, 17530, -1, 17530, 17534, 17532, -1, 17535, 17536, 17533, -1, 17533, 17536, 17534, -1, 17537, 17538, 17535, -1, 17535, 17538, 17536, -1, 17538, 17539, 17536, -1, 17540, 17541, 17542, -1, 17543, 17544, 17540, -1, 17540, 17544, 17541, -1, 17545, 17546, 17543, -1, 17543, 17546, 17544, -1, 17545, 17547, 17546, -1, 17548, 17549, 17545, -1, 17545, 17549, 17547, -1, 17550, 17551, 17548, -1, 17548, 17551, 17549, -1, 17551, 17552, 17549, -1, 17553, 17554, 17555, -1, 17556, 17557, 17553, -1, 17553, 17557, 17554, -1, 17556, 17558, 17557, -1, 17559, 17560, 17556, -1, 17556, 17560, 17558, -1, 17561, 17562, 17559, -1, 17559, 17562, 17560, -1, 17563, 17564, 17561, -1, 17561, 17564, 17562, -1, 17564, 17565, 17562, -1, 17566, 17567, 17568, -1, 17569, 17570, 17566, -1, 17566, 17570, 17567, -1, 17571, 17572, 17569, -1, 17569, 17572, 17570, -1, 17571, 17573, 17572, -1, 17574, 17575, 17571, -1, 17571, 17575, 17573, -1, 17576, 17577, 17574, -1, 17574, 17577, 17575, -1, 17577, 17578, 17575, -1, 17579, 17580, 17581, -1, 17581, 17580, 17582, -1, 17583, 17584, 17585, -1, 17586, 17584, 17587, -1, 17582, 17584, 17586, -1, 17587, 17584, 17583, -1, 17588, 17589, 17590, -1, 17590, 17589, 17591, -1, 17592, 17589, 17593, -1, 17593, 17589, 17594, -1, 17591, 17589, 17592, -1, 17579, 17595, 17580, -1, 17594, 17595, 17579, -1, 17585, 17596, 17597, -1, 17584, 17596, 17585, -1, 17580, 17596, 17582, -1, 17582, 17596, 17584, -1, 17588, 17598, 17589, -1, 17589, 17598, 17594, -1, 17594, 17598, 17595, -1, 17597, 17599, 17600, -1, 17596, 17599, 17597, -1, 17601, 17602, 17603, -1, 17595, 17599, 17580, -1, 17580, 17599, 17596, -1, 17600, 17604, 17605, -1, 17606, 17604, 17588, -1, 17588, 17604, 17598, -1, 17605, 17604, 17606, -1, 17599, 17604, 17600, -1, 17598, 17604, 17595, -1, 17595, 17604, 17599, -1, 17607, 17591, 17592, -1, 17606, 17608, 17605, -1, 17609, 17610, 17611, -1, 17611, 17610, 17612, -1, 17613, 17614, 17609, -1, 17609, 17614, 17610, -1, 17612, 17615, 17616, -1, 17610, 17615, 17612, -1, 17617, 17581, 17613, -1, 17613, 17581, 17614, -1, 17610, 17586, 17615, -1, 17614, 17586, 17610, -1, 17616, 17618, 17601, -1, 17615, 17618, 17616, -1, 17601, 17618, 17602, -1, 17619, 17579, 17617, -1, 17617, 17579, 17581, -1, 17581, 17582, 17614, -1, 17614, 17582, 17586, -1, 17602, 17587, 17583, -1, 17615, 17587, 17618, -1, 17618, 17587, 17602, -1, 17586, 17587, 17615, -1, 17593, 17594, 17619, -1, 17619, 17594, 17579, -1, 17620, 17621, 17622, -1, 17622, 17621, 17623, -1, 17623, 17624, 17625, -1, 17621, 17624, 17623, -1, 17625, 17626, 17627, -1, 17624, 17626, 17625, -1, 17628, 17629, 17630, -1, 17627, 17629, 17628, -1, 17626, 17629, 17627, -1, 17629, 17631, 17630, -1, 17632, 17633, 17634, -1, 17635, 17636, 17632, -1, 17632, 17636, 17633, -1, 17635, 17637, 17636, -1, 17638, 17639, 17635, -1, 17635, 17639, 17637, -1, 17640, 17641, 17638, -1, 17638, 17641, 17639, -1, 17642, 17643, 17640, -1, 17640, 17643, 17641, -1, 17643, 17644, 17641, -1, 17645, 17646, 17647, -1, 17647, 17646, 17648, -1, 17648, 17649, 17650, -1, 17646, 17649, 17648, -1, 17651, 17652, 17653, -1, 17650, 17652, 17651, -1, 17649, 17652, 17650, -1, 17654, 17655, 17656, -1, 17657, 17654, 17656, -1, 17658, 17657, 17656, -1, 17659, 17660, 17661, -1, 17662, 17660, 17659, -1, 17661, 17660, 17663, -1, 17664, 17665, 17666, -1, 17667, 17665, 17662, -1, 17663, 17665, 17664, -1, 17662, 17665, 17660, -1, 17660, 17665, 17663, -1, 17666, 17668, 17669, -1, 17669, 17668, 17670, -1, 17670, 17668, 17667, -1, 17665, 17668, 17666, -1, 17667, 17668, 17665, -1, 17671, 17672, 17673, -1, 17674, 17672, 17671, -1, 17675, 17672, 17674, -1, 17673, 17672, 17676, -1, 17663, 17677, 17678, -1, 17663, 17679, 17677, -1, 17663, 17664, 17679, -1, 17676, 17680, 17681, -1, 17682, 17683, 17684, -1, 17681, 17683, 17682, -1, 17685, 17686, 17687, -1, 17687, 17686, 17672, -1, 17672, 17686, 17676, -1, 17676, 17686, 17680, -1, 17681, 17688, 17683, -1, 17681, 17689, 17688, -1, 17680, 17689, 17681, -1, 17684, 17690, 17691, -1, 17683, 17690, 17684, -1, 17692, 17693, 17685, -1, 17686, 17693, 17680, -1, 17689, 17693, 17692, -1, 17685, 17693, 17686, -1, 17680, 17693, 17689, -1, 17688, 17694, 17683, -1, 17683, 17694, 17690, -1, 17692, 17695, 17689, -1, 17688, 17695, 17694, -1, 17689, 17695, 17688, -1, 17690, 17659, 17691, -1, 17696, 17697, 17692, -1, 17692, 17697, 17695, -1, 17694, 17662, 17690, -1, 17690, 17662, 17659, -1, 17670, 17667, 17696, -1, 17695, 17667, 17694, -1, 17694, 17667, 17662, -1, 17696, 17667, 17697, -1, 17697, 17667, 17695, -1, 17691, 17661, 17698, -1, 17698, 17661, 17663, -1, 17659, 17661, 17691, -1, 17699, 17700, 17701, -1, 17702, 17703, 17704, -1, 17705, 17699, 17706, -1, 17705, 17706, 17707, -1, 17705, 17700, 17699, -1, 17708, 17707, 17709, -1, 17708, 17710, 17700, -1, 17708, 17711, 17710, -1, 17708, 17700, 17705, -1, 17708, 17705, 17707, -1, 17712, 17709, 17713, -1, 17712, 17711, 17708, -1, 17712, 17708, 17709, -1, 17714, 17713, 17715, -1, 17714, 17715, 17716, -1, 17714, 17717, 17711, -1, 17714, 17711, 17712, -1, 17714, 17712, 17713, -1, 17718, 17716, 17719, -1, 17718, 17720, 17717, -1, 17718, 17714, 17716, -1, 17718, 17717, 17714, -1, 17721, 17719, 17722, -1, 17721, 17723, 17720, -1, 17721, 17704, 17723, -1, 17721, 17718, 17719, -1, 17721, 17720, 17718, -1, 17724, 17722, 17725, -1, 17724, 17725, 17702, -1, 17724, 17702, 17704, -1, 17724, 17721, 17722, -1, 17724, 17704, 17721, -1, 17726, 17727, 17728, -1, 17729, 17726, 17728, -1, 17730, 17731, 17726, -1, 17730, 17726, 17729, -1, 17732, 17733, 17731, -1, 17732, 17731, 17730, -1, 17734, 17735, 17733, -1, 17734, 17733, 17732, -1, 17736, 17737, 17735, -1, 17736, 17735, 17734, -1, 17738, 17739, 17737, -1, 17738, 17737, 17736, -1, 17740, 17741, 17742, -1, 17743, 17742, 17744, -1, 17743, 17740, 17742, -1, 17745, 17744, 17746, -1, 17745, 17743, 17744, -1, 17747, 17746, 17748, -1, 17747, 17745, 17746, -1, 17749, 17748, 17750, -1, 17749, 17747, 17748, -1, 17751, 17749, 17750, -1, 17752, 17753, 17754, -1, 17754, 17753, 17755, -1, 17756, 17757, 17758, -1, 17759, 17757, 17760, -1, 17755, 17757, 17759, -1, 17760, 17757, 17756, -1, 17761, 17762, 17763, -1, 17763, 17762, 17764, -1, 17765, 17762, 17766, -1, 17766, 17762, 17767, -1, 17764, 17762, 17765, -1, 17752, 17768, 17753, -1, 17767, 17768, 17752, -1, 17758, 17769, 17770, -1, 17757, 17769, 17758, -1, 17753, 17769, 17755, -1, 17755, 17769, 17757, -1, 17761, 17771, 17762, -1, 17762, 17771, 17767, -1, 17767, 17771, 17768, -1, 17770, 17772, 17773, -1, 17769, 17772, 17770, -1, 17768, 17772, 17753, -1, 17774, 17775, 17776, -1, 17753, 17772, 17769, -1, 17773, 17777, 17778, -1, 17779, 17777, 17761, -1, 17761, 17777, 17771, -1, 17778, 17777, 17779, -1, 17772, 17777, 17773, -1, 17771, 17777, 17768, -1, 17768, 17777, 17772, -1, 17780, 17764, 17765, -1, 17779, 17781, 17778, -1, 17782, 17783, 17784, -1, 17784, 17783, 17785, -1, 17786, 17787, 17782, -1, 17782, 17787, 17783, -1, 17785, 17788, 17789, -1, 17783, 17788, 17785, -1, 17790, 17754, 17786, -1, 17786, 17754, 17787, -1, 17783, 17759, 17788, -1, 17787, 17759, 17783, -1, 17789, 17791, 17774, -1, 17788, 17791, 17789, -1, 17774, 17791, 17775, -1, 17792, 17752, 17790, -1, 17790, 17752, 17754, -1, 17754, 17755, 17787, -1, 17787, 17755, 17759, -1, 17775, 17760, 17756, -1, 17788, 17760, 17791, -1, 17759, 17760, 17788, -1, 17791, 17760, 17775, -1, 17766, 17767, 17792, -1, 17792, 17767, 17752, -1, 17793, 17794, 17795, -1, 17795, 17794, 17796, -1, 17796, 17797, 17798, -1, 17794, 17797, 17796, -1, 17798, 17799, 17800, -1, 17797, 17799, 17798, -1, 17800, 17801, 17802, -1, 17799, 17801, 17800, -1, 17802, 17803, 17804, -1, 17801, 17803, 17802, -1, 17805, 17806, 17807, -1, 17807, 17806, 17808, -1, 17808, 17809, 17810, -1, 17806, 17809, 17808, -1, 17810, 17811, 17812, -1, 17809, 17811, 17810, -1, 17812, 17813, 17814, -1, 17811, 17813, 17812, -1, 17814, 17815, 17816, -1, 17813, 17815, 17814, -1, 17815, 17817, 17816, -1, 17818, 17819, 17820, -1, 17820, 17819, 17821, -1, 17821, 17822, 17823, -1, 17819, 17822, 17821, -1, 17823, 17824, 17825, -1, 17822, 17824, 17823, -1, 17825, 17826, 17827, -1, 17824, 17826, 17825, -1, 17827, 17828, 17829, -1, 17826, 17828, 17827, -1, 17830, 17831, 17832, -1, 17832, 17831, 17833, -1, 17833, 17834, 17835, -1, 17831, 17834, 17833, -1, 17835, 17836, 17837, -1, 17834, 17836, 17835, -1, 17837, 17838, 17839, -1, 17836, 17838, 17837, -1, 17839, 17840, 17841, -1, 17838, 17840, 17839, -1, 17841, 17842, 17843, -1, 17840, 17842, 17841, -1, 17843, 17844, 17845, -1, 17845, 17844, 17846, -1, 17842, 17844, 17843, -1, 17844, 17847, 17846, -1, 17848, 17849, 17850, -1, 17850, 17849, 17851, -1, 17851, 17852, 17853, -1, 17849, 17852, 17851, -1, 17853, 17854, 17855, -1, 17855, 17854, 17856, -1, 17852, 17854, 17853, -1, 17856, 17857, 17858, -1, 17854, 17857, 17856, -1, 17858, 17859, 17860, -1, 17857, 17859, 17858, -1, 17861, 17862, 17863, -1, 17864, 17865, 17866, -1, 17863, 17865, 17864, -1, 17862, 17865, 17863, -1, 17867, 17868, 17869, -1, 17866, 17868, 17867, -1, 17865, 17868, 17866, -1, 17869, 17870, 17871, -1, 17868, 17870, 17869, -1, 17872, 17873, 17874, -1, 17871, 17873, 17872, -1, 17870, 17873, 17871, -1, 17874, 17875, 17876, -1, 17873, 17875, 17874, -1, 17877, 17878, 17879, -1, 17880, 17877, 17879, -1, 17880, 17879, 17881, -1, 17882, 17883, 17884, -1, 17882, 17885, 17883, -1, 17886, 17887, 17888, -1, 17889, 17882, 17884, -1, 17739, 17884, 17887, -1, 17739, 17887, 17886, -1, 17739, 17889, 17884, -1, 17890, 17888, 17891, -1, 17890, 17886, 17888, -1, 17892, 17890, 17891, -1, 17893, 17739, 17738, -1, 17893, 17889, 17739, -1, 17894, 17890, 17892, -1, 17895, 17738, 17896, -1, 17895, 17893, 17738, -1, 17897, 17894, 17892, -1, 17898, 17894, 17897, -1, 17899, 17898, 17897, -1, 17900, 17896, 17901, -1, 17900, 17895, 17896, -1, 17902, 17901, 17903, -1, 17902, 17900, 17901, -1, 17904, 17899, 17905, -1, 17904, 17898, 17899, -1, 17906, 17903, 17907, -1, 17906, 17902, 17903, -1, 17908, 17905, 17909, -1, 17908, 17909, 17910, -1, 17908, 17904, 17905, -1, 17911, 17907, 17878, -1, 17911, 17906, 17907, -1, 17912, 17910, 17913, -1, 17912, 17908, 17910, -1, 17877, 17911, 17878, -1, 17914, 17912, 17913, -1, 17914, 17913, 17915, -1, 17916, 17917, 17918, -1, 17916, 17919, 17917, -1, 17917, 17920, 17921, -1, 17919, 17920, 17917, -1, 17920, 17922, 17921, -1, 17920, 17923, 17922, -1, 17923, 17924, 17922, -1, 17923, 17925, 17924, -1, 17925, 17926, 17924, -1, 17925, 17927, 17926, -1, 17927, 17928, 17926, -1, 17927, 17929, 17928, -1, 17929, 17930, 17928, -1, 17929, 17931, 17930, -1, 17931, 17932, 17930, -1, 17931, 17933, 17932, -1, 17934, 17935, 17936, -1, 17936, 17935, 17937, -1, 17937, 17938, 17939, -1, 17935, 17938, 17937, -1, 17939, 17940, 17941, -1, 17938, 17940, 17939, -1, 17941, 17942, 17943, -1, 17940, 17942, 17941, -1, 17943, 17944, 17945, -1, 17942, 17944, 17943, -1, 17945, 17946, 17947, -1, 17944, 17946, 17945, -1, 17948, 17949, 17950, -1, 17950, 17951, 17952, -1, 17949, 17951, 17950, -1, 17952, 17953, 17954, -1, 17951, 17953, 17952, -1, 17954, 17955, 17956, -1, 17953, 17955, 17954, -1, 17956, 17957, 17958, -1, 17955, 17957, 17956, -1, 17958, 17959, 17960, -1, 17957, 17959, 17958, -1, 17960, 17961, 17962, -1, 17959, 17961, 17960, -1, 17962, 17963, 17964, -1, 17961, 17963, 17962, -1, 17964, 17965, 17966, -1, 17963, 17965, 17964, -1, 17966, 17967, 17968, -1, 17965, 17967, 17966, -1, 17968, 17969, 17970, -1, 17967, 17969, 17968, -1, 17970, 17971, 17972, -1, 17969, 17971, 17970, -1, 17971, 17973, 17972, -1, 17972, 17974, 17975, -1, 17973, 17974, 17972, -1, 17976, 17977, 17978, -1, 17978, 17979, 17980, -1, 17977, 17979, 17978, -1, 17980, 17981, 17982, -1, 17979, 17981, 17980, -1, 17982, 17983, 17984, -1, 17981, 17983, 17982, -1, 17984, 17985, 17986, -1, 17983, 17985, 17984, -1, 17986, 17987, 17988, -1, 17985, 17987, 17986, -1, 17988, 17989, 17990, -1, 17987, 17989, 17988, -1, 17990, 17991, 17992, -1, 17989, 17991, 17990, -1, 17992, 17993, 17994, -1, 17991, 17993, 17992, -1, 17994, 17995, 17996, -1, 17993, 17995, 17994, -1, 17996, 17997, 17998, -1, 17995, 17997, 17996, -1, 17998, 17999, 18000, -1, 17997, 17999, 17998, -1, 18000, 18001, 18002, -1, 17999, 18001, 18000, -1, 18001, 18003, 18002, -1, 18004, 18005, 18006, -1, 18007, 18005, 18008, -1, 18009, 18010, 18011, -1, 18012, 18013, 18014, -1, 18015, 18010, 18009, -1, 18011, 18010, 18016, -1, 18008, 18013, 18012, -1, 18017, 18018, 18019, -1, 18020, 18021, 18022, -1, 18019, 18018, 18023, -1, 18024, 18018, 18025, -1, 18014, 18021, 18020, -1, 18023, 18018, 18024, -1, 18016, 18026, 18027, -1, 18028, 18029, 18004, -1, 18025, 18026, 18015, -1, 18008, 18029, 18013, -1, 18010, 18026, 18016, -1, 18015, 18026, 18010, -1, 18004, 18029, 18005, -1, 18005, 18029, 18008, -1, 18027, 18030, 18031, -1, 18031, 18030, 18032, -1, 18032, 18030, 18033, -1, 18033, 18030, 18017, -1, 18017, 18030, 18018, -1, 18014, 18034, 18021, -1, 18025, 18030, 18026, -1, 18013, 18034, 18014, -1, 18026, 18030, 18027, -1, 18018, 18030, 18025, -1, 18022, 18035, 18036, -1, 18021, 18035, 18022, -1, 18037, 18004, 18006, -1, 18038, 18039, 18028, -1, 18028, 18039, 18029, -1, 18013, 18039, 18034, -1, 18029, 18039, 18013, -1, 18021, 18040, 18035, -1, 18034, 18040, 18021, -1, 18036, 18041, 18042, -1, 18035, 18041, 18036, -1, 18043, 18044, 18038, -1, 18038, 18044, 18039, -1, 18034, 18044, 18040, -1, 18039, 18044, 18034, -1, 18040, 18045, 18035, -1, 18035, 18045, 18041, -1, 18042, 18046, 18047, -1, 18041, 18046, 18042, -1, 18048, 18049, 18043, -1, 18040, 18049, 18045, -1, 18044, 18049, 18040, -1, 18043, 18049, 18044, -1, 18041, 18050, 18046, -1, 18045, 18050, 18041, -1, 18047, 18051, 18052, -1, 18046, 18051, 18047, -1, 18049, 18053, 18045, -1, 18045, 18053, 18050, -1, 18054, 18053, 18048, -1, 18048, 18053, 18049, -1, 18046, 18055, 18051, -1, 18050, 18055, 18046, -1, 18051, 18056, 18052, -1, 18052, 18056, 18057, -1, 18058, 18059, 18054, -1, 18053, 18059, 18050, -1, 18054, 18059, 18053, -1, 18050, 18059, 18055, -1, 18055, 18060, 18051, -1, 18051, 18060, 18056, -1, 18056, 18061, 18057, -1, 18057, 18061, 18062, -1, 18063, 18064, 18058, -1, 18059, 18064, 18055, -1, 18011, 18016, 18065, -1, 18058, 18064, 18059, -1, 18055, 18064, 18060, -1, 18060, 18066, 18056, -1, 18056, 18066, 18061, -1, 18062, 18067, 18068, -1, 18061, 18067, 18062, -1, 18063, 18069, 18064, -1, 18070, 18069, 18063, -1, 18060, 18069, 18066, -1, 18064, 18069, 18060, -1, 18066, 18024, 18061, -1, 18061, 18024, 18067, -1, 18071, 18012, 18072, -1, 18072, 18012, 18073, -1, 18068, 18015, 18009, -1, 18071, 18008, 18012, -1, 18067, 18015, 18068, -1, 18007, 18008, 18071, -1, 18019, 18023, 18070, -1, 18070, 18023, 18069, -1, 18066, 18023, 18024, -1, 18069, 18023, 18066, -1, 18073, 18014, 18020, -1, 18024, 18025, 18067, -1, 18012, 18014, 18073, -1, 18067, 18025, 18015, -1, 18006, 18005, 18007, -1, 18074, 18075, 18076, -1, 18077, 18078, 18079, -1, 18080, 18081, 18082, -1, 18080, 18082, 18083, -1, 18084, 18085, 18086, -1, 18080, 18087, 18081, -1, 18084, 18086, 18078, -1, 18088, 18089, 18087, -1, 18090, 18091, 18092, -1, 18088, 18093, 18089, -1, 18090, 18077, 18091, -1, 18094, 18095, 18096, -1, 18094, 18097, 18093, -1, 18094, 18096, 18074, -1, 18094, 18074, 18097, -1, 18098, 18078, 18077, -1, 18099, 18083, 18100, -1, 18098, 18084, 18078, -1, 18101, 18102, 18103, -1, 18099, 18087, 18080, -1, 18101, 18104, 18085, -1, 18099, 18088, 18087, -1, 18099, 18080, 18083, -1, 18101, 18103, 18104, -1, 18105, 18106, 18095, -1, 18101, 18085, 18084, -1, 18105, 18095, 18094, -1, 18105, 18093, 18088, -1, 18107, 18092, 18108, -1, 18105, 18094, 18093, -1, 18109, 18100, 18110, -1, 18109, 18110, 18111, -1, 18109, 18111, 18106, -1, 18107, 18090, 18092, -1, 18109, 18106, 18105, -1, 18109, 18099, 18100, -1, 18109, 18088, 18099, -1, 18109, 18105, 18088, -1, 18112, 18098, 18077, -1, 18112, 18077, 18090, -1, 18113, 18114, 18102, -1, 18113, 18101, 18084, -1, 18113, 18084, 18098, -1, 18113, 18102, 18101, -1, 18103, 18115, 18104, -1, 18116, 18108, 18117, -1, 18116, 18107, 18108, -1, 18118, 18090, 18107, -1, 18118, 18112, 18090, -1, 18119, 18114, 18113, -1, 18119, 18120, 18114, -1, 18119, 18098, 18112, -1, 18119, 18113, 18098, -1, 18121, 18117, 18122, -1, 18121, 18116, 18117, -1, 18123, 18118, 18107, -1, 18123, 18107, 18116, -1, 18124, 18125, 18120, -1, 18124, 18119, 18112, -1, 18124, 18120, 18119, -1, 18124, 18112, 18118, -1, 18126, 18122, 18127, -1, 18126, 18121, 18122, -1, 18128, 18123, 18116, -1, 18128, 18116, 18121, -1, 18129, 18124, 18118, -1, 18129, 18130, 18125, -1, 18129, 18125, 18124, -1, 18129, 18118, 18123, -1, 18131, 18127, 18132, -1, 18131, 18126, 18127, -1, 18133, 18128, 18121, -1, 18133, 18121, 18126, -1, 18134, 18123, 18128, -1, 18134, 18130, 18129, -1, 18134, 18135, 18130, -1, 18134, 18129, 18123, -1, 18136, 18132, 18137, -1, 18136, 18131, 18132, -1, 18076, 18133, 18126, -1, 18076, 18126, 18131, -1, 18138, 18134, 18128, -1, 18138, 18139, 18135, -1, 18138, 18135, 18134, -1, 18138, 18128, 18133, -1, 18089, 18137, 18140, -1, 18089, 18136, 18137, -1, 18097, 18076, 18131, -1, 18097, 18131, 18136, -1, 18075, 18139, 18138, -1, 18075, 18141, 18139, -1, 18075, 18138, 18133, -1, 18075, 18133, 18076, -1, 18087, 18140, 18081, -1, 18087, 18089, 18140, -1, 18078, 18142, 18079, -1, 18078, 18143, 18142, -1, 18078, 18086, 18143, -1, 18093, 18097, 18136, -1, 18093, 18136, 18089, -1, 18077, 18079, 18091, -1, 18074, 18141, 18075, -1, 18074, 18096, 18141, -1, 18074, 18076, 18097, -1, 18144, 18145, 18146, -1, 18147, 18145, 18148, -1, 18149, 18150, 18151, -1, 18152, 18150, 18153, -1, 18146, 18145, 18147, -1, 18154, 18155, 18156, -1, 18157, 18158, 18159, -1, 18160, 18155, 18154, -1, 18148, 18155, 18161, -1, 18153, 18158, 18157, -1, 18161, 18155, 18160, -1, 18162, 18163, 18164, -1, 18165, 18166, 18167, -1, 18156, 18166, 18165, -1, 18159, 18163, 18162, -1, 18167, 18166, 18145, -1, 18155, 18166, 18156, -1, 18145, 18166, 18148, -1, 18148, 18166, 18155, -1, 18168, 18169, 18170, -1, 18153, 18169, 18158, -1, 18170, 18169, 18150, -1, 18150, 18169, 18153, -1, 18159, 18171, 18163, -1, 18158, 18171, 18159, -1, 18164, 18172, 18173, -1, 18163, 18172, 18164, -1, 18174, 18175, 18168, -1, 18176, 18149, 18151, -1, 18168, 18175, 18169, -1, 18158, 18175, 18171, -1, 18169, 18175, 18158, -1, 18171, 18177, 18163, -1, 18163, 18177, 18172, -1, 18173, 18178, 18179, -1, 18172, 18178, 18173, -1, 18180, 18181, 18174, -1, 18175, 18181, 18171, -1, 18171, 18181, 18177, -1, 18174, 18181, 18175, -1, 18177, 18182, 18172, -1, 18172, 18182, 18178, -1, 18179, 18183, 18184, -1, 18178, 18183, 18179, -1, 18185, 18186, 18180, -1, 18181, 18186, 18177, -1, 18177, 18186, 18182, -1, 18180, 18186, 18181, -1, 18178, 18187, 18183, -1, 18182, 18187, 18178, -1, 18184, 18188, 18189, -1, 18183, 18188, 18184, -1, 18190, 18191, 18185, -1, 18182, 18191, 18187, -1, 18185, 18191, 18186, -1, 18186, 18191, 18182, -1, 18183, 18192, 18188, -1, 18187, 18192, 18183, -1, 18188, 18193, 18189, -1, 18189, 18193, 18194, -1, 18190, 18195, 18191, -1, 18196, 18195, 18190, -1, 18191, 18195, 18187, -1, 18187, 18195, 18192, -1, 18192, 18197, 18188, -1, 18188, 18197, 18193, -1, 18193, 18198, 18194, -1, 18194, 18198, 18199, -1, 18196, 18200, 18195, -1, 18201, 18200, 18196, -1, 18195, 18200, 18192, -1, 18192, 18200, 18197, -1, 18197, 18202, 18193, -1, 18203, 18154, 18204, -1, 18193, 18202, 18198, -1, 18199, 18205, 18206, -1, 18198, 18205, 18199, -1, 18207, 18208, 18201, -1, 18201, 18208, 18200, -1, 18197, 18208, 18202, -1, 18200, 18208, 18197, -1, 18202, 18147, 18198, -1, 18198, 18147, 18205, -1, 18206, 18161, 18209, -1, 18167, 18210, 18165, -1, 18205, 18161, 18206, -1, 18211, 18157, 18212, -1, 18144, 18146, 18207, -1, 18207, 18146, 18208, -1, 18212, 18157, 18213, -1, 18202, 18146, 18147, -1, 18208, 18146, 18202, -1, 18211, 18153, 18157, -1, 18152, 18153, 18211, -1, 18147, 18148, 18205, -1, 18205, 18148, 18161, -1, 18213, 18159, 18162, -1, 18209, 18160, 18203, -1, 18157, 18159, 18213, -1, 18161, 18160, 18209, -1, 18170, 18150, 18149, -1, 18203, 18160, 18154, -1, 18151, 18150, 18152, -1, 18167, 18145, 18144, -1, 18214, 18215, 18216, -1, 18217, 18218, 18219, -1, 18220, 18221, 18222, -1, 18217, 18223, 18218, -1, 18220, 18224, 18221, -1, 18225, 18226, 18227, -1, 18225, 18227, 18228, -1, 18225, 18229, 18224, -1, 18225, 18228, 18229, -1, 18230, 18216, 18223, -1, 18230, 18214, 18216, -1, 18231, 18232, 18233, -1, 18234, 18235, 18236, -1, 18231, 18237, 18232, -1, 18231, 18233, 18238, -1, 18234, 18239, 18240, -1, 18234, 18236, 18239, -1, 18231, 18241, 18237, -1, 18234, 18240, 18214, -1, 18242, 18219, 18243, -1, 18244, 18220, 18222, -1, 18244, 18222, 18241, -1, 18242, 18217, 18219, -1, 18245, 18246, 18226, -1, 18247, 18223, 18217, -1, 18245, 18226, 18225, -1, 18245, 18224, 18220, -1, 18247, 18230, 18223, -1, 18245, 18225, 18224, -1, 18248, 18238, 18249, -1, 18250, 18251, 18235, -1, 18250, 18214, 18230, -1, 18248, 18231, 18238, -1, 18250, 18235, 18234, -1, 18248, 18241, 18231, -1, 18248, 18244, 18241, -1, 18250, 18234, 18214, -1, 18252, 18220, 18244, -1, 18252, 18253, 18246, -1, 18254, 18243, 18255, -1, 18252, 18245, 18220, -1, 18252, 18246, 18245, -1, 18254, 18242, 18243, -1, 18256, 18257, 18258, -1, 18256, 18249, 18257, -1, 18256, 18258, 18253, -1, 18256, 18252, 18244, -1, 18256, 18248, 18249, -1, 18256, 18244, 18248, -1, 18256, 18253, 18252, -1, 18259, 18247, 18217, -1, 18259, 18217, 18242, -1, 18260, 18261, 18251, -1, 18260, 18250, 18230, -1, 18260, 18251, 18250, -1, 18260, 18230, 18247, -1, 18262, 18255, 18263, -1, 18262, 18254, 18255, -1, 18264, 18242, 18254, -1, 18264, 18259, 18242, -1, 18265, 18266, 18261, -1, 18265, 18260, 18247, -1, 18265, 18247, 18259, -1, 18265, 18261, 18260, -1, 18267, 18263, 18268, -1, 18267, 18262, 18263, -1, 18269, 18264, 18254, -1, 18269, 18254, 18262, -1, 18270, 18265, 18259, -1, 18270, 18259, 18264, -1, 18270, 18271, 18266, -1, 18270, 18266, 18265, -1, 18272, 18268, 18273, -1, 18272, 18267, 18268, -1, 18274, 18269, 18262, -1, 18274, 18262, 18267, -1, 18275, 18270, 18264, -1, 18275, 18264, 18269, -1, 18275, 18271, 18270, -1, 18275, 18276, 18271, -1, 18221, 18273, 18277, -1, 18221, 18272, 18273, -1, 18229, 18274, 18267, -1, 18229, 18267, 18272, -1, 18278, 18275, 18269, -1, 18278, 18279, 18276, -1, 18278, 18276, 18275, -1, 18278, 18269, 18274, -1, 18222, 18277, 18280, -1, 18222, 18221, 18277, -1, 18281, 18258, 18257, -1, 18216, 18282, 18283, -1, 18216, 18215, 18282, -1, 18224, 18272, 18221, -1, 18224, 18229, 18272, -1, 18223, 18283, 18218, -1, 18228, 18279, 18278, -1, 18228, 18227, 18279, -1, 18228, 18278, 18274, -1, 18223, 18216, 18283, -1, 18228, 18274, 18229, -1, 18241, 18280, 18237, -1, 18214, 18240, 18215, -1, 18241, 18222, 18280, -1, 18284, 18285, 18286, -1, 18286, 18285, 18287, -1, 18287, 18288, 18289, -1, 18285, 18288, 18287, -1, 18289, 18290, 18291, -1, 18288, 18290, 18289, -1, 18291, 18292, 18293, -1, 18290, 18292, 18291, -1, 18293, 18294, 18295, -1, 18292, 18294, 18293, -1, 18295, 18296, 18297, -1, 18294, 18296, 18295, -1, 18297, 18298, 18299, -1, 18296, 18298, 18297, -1, 18299, 18300, 18301, -1, 18298, 18300, 18299, -1, 18301, 18302, 18303, -1, 18300, 18302, 18301, -1, 18303, 18304, 18305, -1, 18302, 18304, 18303, -1, 18305, 18306, 18307, -1, 18304, 18306, 18305, -1, 18307, 18308, 18309, -1, 18306, 18308, 18307, -1, 18309, 18310, 18311, -1, 18308, 18310, 18309, -1, 18312, 18313, 18314, -1, 18314, 18313, 18315, -1, 18315, 18316, 18317, -1, 18313, 18316, 18315, -1, 18317, 18318, 18319, -1, 18316, 18318, 18317, -1, 18319, 18320, 18321, -1, 18318, 18320, 18319, -1, 18321, 18322, 18323, -1, 18320, 18322, 18321, -1, 18323, 18324, 18325, -1, 18322, 18324, 18323, -1, 18325, 18326, 18327, -1, 18324, 18326, 18325, -1, 18327, 18328, 18329, -1, 18326, 18328, 18327, -1, 18329, 18330, 18331, -1, 18328, 18330, 18329, -1, 18331, 18332, 18333, -1, 18330, 18332, 18331, -1, 18333, 18334, 18335, -1, 18332, 18334, 18333, -1, 18335, 18336, 18337, -1, 18337, 18336, 18338, -1, 18334, 18336, 18335, -1, 18336, 18339, 18338, -1, 18340, 18341, 18342, -1, 18340, 18342, 18032, -1, 18340, 18032, 18082, -1, 18340, 18343, 18344, -1, 18340, 18344, 18341, -1, 18340, 18082, 18343, -1, 18345, 18079, 18142, -1, 18345, 18142, 18143, -1, 18345, 18346, 18079, -1, 18347, 18143, 18037, -1, 18347, 18037, 18348, -1, 18347, 18348, 18349, -1, 18347, 18346, 18345, -1, 18347, 18349, 18346, -1, 18347, 18345, 18143, -1, 18344, 18140, 18137, -1, 18344, 18350, 18341, -1, 18351, 18137, 18132, -1, 18351, 18132, 18127, -1, 18351, 18352, 18353, -1, 18351, 18353, 18350, -1, 18351, 18344, 18137, -1, 18351, 18350, 18344, -1, 18354, 18127, 18122, -1, 18354, 18122, 18117, -1, 18354, 18355, 18356, -1, 18354, 18356, 18352, -1, 18354, 18352, 18351, -1, 18354, 18351, 18127, -1, 18357, 18117, 18108, -1, 18357, 18358, 18355, -1, 18357, 18355, 18354, -1, 18357, 18354, 18117, -1, 18359, 18108, 18092, -1, 18359, 18092, 18091, -1, 18359, 18360, 18361, -1, 18359, 18361, 18358, -1, 18359, 18357, 18108, -1, 18359, 18358, 18357, -1, 18346, 18091, 18079, -1, 18346, 18349, 18360, -1, 18346, 18360, 18359, -1, 18346, 18359, 18091, -1, 18343, 18082, 18081, -1, 18343, 18081, 18140, -1, 18343, 18140, 18344, -1, 18362, 18363, 18364, -1, 18362, 18365, 18219, -1, 18362, 18364, 18365, -1, 18366, 18233, 18232, -1, 18366, 18232, 18237, -1, 18366, 18237, 18367, -1, 18368, 18369, 18370, -1, 18368, 18370, 18210, -1, 18368, 18210, 18233, -1, 18368, 18366, 18367, -1, 18368, 18367, 18369, -1, 18368, 18233, 18366, -1, 18371, 18218, 18283, -1, 18371, 18283, 18282, -1, 18371, 18282, 18176, -1, 18371, 18362, 18218, -1, 18372, 18176, 18373, -1, 18372, 18373, 18363, -1, 18372, 18362, 18371, -1, 18372, 18371, 18176, -1, 18372, 18363, 18362, -1, 18367, 18237, 18280, -1, 18367, 18374, 18369, -1, 18375, 18280, 18277, -1, 18375, 18277, 18273, -1, 18375, 18376, 18377, -1, 18375, 18377, 18374, -1, 18375, 18367, 18280, -1, 18375, 18374, 18367, -1, 18378, 18273, 18268, -1, 18378, 18379, 18380, -1, 18378, 18380, 18376, -1, 18378, 18376, 18375, -1, 18378, 18375, 18273, -1, 18381, 18268, 18263, -1, 18381, 18263, 18255, -1, 18381, 18382, 18379, -1, 18381, 18379, 18378, -1, 18381, 18378, 18268, -1, 18365, 18255, 18243, -1, 18365, 18243, 18219, -1, 18365, 18364, 18383, -1, 18365, 18383, 18382, -1, 18365, 18381, 18255, -1, 18365, 18382, 18381, -1, 18362, 18219, 18218, -1, 18384, 18385, 18386, -1, 18387, 18388, 18389, -1, 18390, 18391, 18392, -1, 18390, 18393, 18391, -1, 18394, 18395, 18396, -1, 18390, 18397, 18385, -1, 18390, 18392, 18397, -1, 18394, 18396, 18388, -1, 18398, 18399, 18400, -1, 18398, 18401, 18399, -1, 18402, 18403, 18404, -1, 18398, 18400, 18405, -1, 18402, 18387, 18403, -1, 18406, 18407, 18401, -1, 18406, 18384, 18407, -1, 18408, 18409, 18393, -1, 18410, 18388, 18387, -1, 18408, 18393, 18390, -1, 18410, 18394, 18388, -1, 18408, 18385, 18384, -1, 18411, 18412, 18413, -1, 18408, 18390, 18385, -1, 18411, 18414, 18395, -1, 18415, 18405, 18416, -1, 18411, 18413, 18414, -1, 18411, 18395, 18394, -1, 18415, 18401, 18398, -1, 18415, 18406, 18401, -1, 18417, 18404, 18418, -1, 18415, 18398, 18405, -1, 18419, 18420, 18409, -1, 18419, 18409, 18408, -1, 18417, 18402, 18404, -1, 18419, 18384, 18406, -1, 18419, 18408, 18384, -1, 18421, 18387, 18402, -1, 18422, 18423, 18420, -1, 18422, 18416, 18423, -1, 18421, 18410, 18387, -1, 18422, 18420, 18419, -1, 18422, 18415, 18416, -1, 18422, 18406, 18415, -1, 18422, 18419, 18406, -1, 18424, 18425, 18412, -1, 18413, 18426, 18414, -1, 18424, 18394, 18410, -1, 18424, 18412, 18411, -1, 18424, 18411, 18394, -1, 18427, 18418, 18428, -1, 18427, 18417, 18418, -1, 18429, 18402, 18417, -1, 18429, 18421, 18402, -1, 18430, 18431, 18425, -1, 18430, 18425, 18424, -1, 18430, 18424, 18410, -1, 18430, 18410, 18421, -1, 18432, 18427, 18428, -1, 18432, 18428, 18433, -1, 18434, 18429, 18417, -1, 18434, 18417, 18427, -1, 18435, 18436, 18431, -1, 18435, 18421, 18429, -1, 18435, 18431, 18430, -1, 18435, 18430, 18421, -1, 18437, 18433, 18438, -1, 18437, 18432, 18433, -1, 18439, 18434, 18427, -1, 18439, 18427, 18432, -1, 18440, 18435, 18429, -1, 18440, 18441, 18436, -1, 18440, 18429, 18434, -1, 18440, 18436, 18435, -1, 18442, 18438, 18443, -1, 18442, 18437, 18438, -1, 18444, 18439, 18432, -1, 18444, 18432, 18437, -1, 18445, 18434, 18439, -1, 18445, 18441, 18440, -1, 18445, 18446, 18441, -1, 18445, 18440, 18434, -1, 18386, 18443, 18447, -1, 18386, 18442, 18443, -1, 18405, 18400, 18448, -1, 18397, 18444, 18437, -1, 18397, 18437, 18442, -1, 18449, 18445, 18439, -1, 18449, 18450, 18446, -1, 18449, 18446, 18445, -1, 18449, 18439, 18444, -1, 18407, 18447, 18451, -1, 18407, 18386, 18447, -1, 18385, 18442, 18386, -1, 18385, 18397, 18442, -1, 18392, 18450, 18449, -1, 18452, 18420, 18423, -1, 18392, 18391, 18450, -1, 18392, 18449, 18444, -1, 18392, 18444, 18397, -1, 18388, 18453, 18389, -1, 18401, 18451, 18399, -1, 18388, 18396, 18453, -1, 18401, 18407, 18451, -1, 18387, 18389, 18403, -1, 18384, 18386, 18407, -1, 18454, 18455, 18456, -1, 18456, 18455, 18457, -1, 18457, 18455, 18458, -1, 18458, 18455, 18459, -1, 18460, 18461, 18462, -1, 18463, 18455, 18454, -1, 18464, 18455, 18465, -1, 18466, 18461, 18467, -1, 18465, 18455, 18463, -1, 18467, 18461, 18468, -1, 18459, 18455, 18464, -1, 18468, 18461, 18460, -1, 18469, 18470, 18471, -1, 18462, 18470, 18469, -1, 18472, 18473, 18474, -1, 18471, 18473, 18472, -1, 18475, 18476, 18466, -1, 18466, 18476, 18461, -1, 18461, 18476, 18462, -1, 18462, 18476, 18470, -1, 18471, 18477, 18473, -1, 18470, 18477, 18471, -1, 18474, 18478, 18479, -1, 18473, 18478, 18474, -1, 18480, 18481, 18475, -1, 18470, 18481, 18477, -1, 18475, 18481, 18476, -1, 18476, 18481, 18470, -1, 18473, 18482, 18478, -1, 18477, 18482, 18473, -1, 18479, 18483, 18484, -1, 18478, 18483, 18479, -1, 18485, 18486, 18480, -1, 18481, 18486, 18477, -1, 18480, 18486, 18481, -1, 18477, 18486, 18482, -1, 18478, 18487, 18483, -1, 18482, 18487, 18478, -1, 18483, 18488, 18484, -1, 18484, 18488, 18489, -1, 18485, 18490, 18486, -1, 18491, 18490, 18485, -1, 18486, 18490, 18482, -1, 18482, 18490, 18487, -1, 18487, 18492, 18483, -1, 18483, 18492, 18488, -1, 18488, 18493, 18489, -1, 18489, 18493, 18494, -1, 18495, 18496, 18491, -1, 18490, 18496, 18487, -1, 18487, 18496, 18492, -1, 18491, 18496, 18490, -1, 18492, 18497, 18488, -1, 18488, 18497, 18493, -1, 18493, 18498, 18494, -1, 18494, 18498, 18499, -1, 18500, 18501, 18495, -1, 18495, 18501, 18496, -1, 18496, 18501, 18492, -1, 18492, 18501, 18497, -1, 18497, 18502, 18493, -1, 18493, 18502, 18498, -1, 18503, 18504, 18505, -1, 18499, 18506, 18507, -1, 18498, 18506, 18499, -1, 18508, 18509, 18500, -1, 18497, 18509, 18502, -1, 18501, 18509, 18497, -1, 18500, 18509, 18501, -1, 18502, 18510, 18498, -1, 18498, 18510, 18506, -1, 18507, 18511, 18503, -1, 18506, 18511, 18507, -1, 18512, 18513, 18508, -1, 18508, 18513, 18509, -1, 18514, 18515, 18516, -1, 18509, 18513, 18502, -1, 18516, 18515, 18517, -1, 18502, 18513, 18510, -1, 18517, 18515, 18518, -1, 18514, 18460, 18515, -1, 18510, 18465, 18506, -1, 18519, 18460, 18514, -1, 18506, 18465, 18511, -1, 18518, 18469, 18520, -1, 18511, 18521, 18503, -1, 18503, 18521, 18504, -1, 18515, 18469, 18518, -1, 18467, 18468, 18522, -1, 18459, 18464, 18512, -1, 18523, 18468, 18519, -1, 18512, 18464, 18513, -1, 18522, 18468, 18523, -1, 18513, 18464, 18510, -1, 18519, 18468, 18460, -1, 18510, 18464, 18465, -1, 18515, 18462, 18469, -1, 18504, 18463, 18454, -1, 18465, 18463, 18511, -1, 18521, 18463, 18504, -1, 18460, 18462, 18515, -1, 18511, 18463, 18521, -1, 18520, 18471, 18472, -1, 18469, 18471, 18520, -1, 18524, 18525, 18526, -1, 18524, 18526, 18457, -1, 18524, 18527, 18528, -1, 18524, 18528, 18525, -1, 18524, 18457, 18527, -1, 18529, 18403, 18389, -1, 18529, 18389, 18453, -1, 18529, 18530, 18403, -1, 18531, 18453, 18522, -1, 18531, 18522, 18532, -1, 18531, 18532, 18533, -1, 18531, 18530, 18529, -1, 18531, 18529, 18453, -1, 18531, 18533, 18530, -1, 18528, 18399, 18451, -1, 18528, 18534, 18525, -1, 18535, 18451, 18447, -1, 18535, 18447, 18443, -1, 18535, 18536, 18537, -1, 18535, 18537, 18534, -1, 18535, 18528, 18451, -1, 18535, 18534, 18528, -1, 18538, 18443, 18438, -1, 18538, 18438, 18433, -1, 18538, 18539, 18536, -1, 18538, 18536, 18535, -1, 18538, 18535, 18443, -1, 18540, 18433, 18428, -1, 18540, 18541, 18542, -1, 18540, 18542, 18539, -1, 18540, 18539, 18538, -1, 18540, 18538, 18433, -1, 18543, 18428, 18418, -1, 18543, 18418, 18404, -1, 18543, 18544, 18545, -1, 18543, 18545, 18541, -1, 18543, 18540, 18428, -1, 18543, 18541, 18540, -1, 18530, 18404, 18403, -1, 18530, 18533, 18544, -1, 18530, 18543, 18404, -1, 18530, 18544, 18543, -1, 18527, 18448, 18400, -1, 18527, 18400, 18399, -1, 18527, 18457, 18448, -1, 18527, 18399, 18528, -1, 18546, 18547, 18548, -1, 18549, 18547, 18546, -1, 18547, 18550, 18548, -1, 18548, 18550, 18551, -1, 18550, 18552, 18551, -1, 18553, 18554, 18555, -1, 18555, 18554, 18556, -1, 18556, 18557, 18558, -1, 18554, 18557, 18556, -1, 18558, 18559, 18560, -1, 18557, 18559, 18558, -1, 18560, 18561, 18562, -1, 18559, 18561, 18560, -1, 17851, 18563, 17850, -1, 18564, 18563, 18565, -1, 18566, 18563, 18564, -1, 17850, 18563, 18566, -1, 17858, 18567, 17856, -1, 17860, 18567, 17858, -1, 18562, 18567, 17860, -1, 18561, 18567, 18562, -1, 17853, 18568, 17851, -1, 17855, 18568, 17853, -1, 17856, 18568, 17855, -1, 18567, 18568, 17856, -1, 17851, 18568, 18563, -1, 18563, 18569, 18570, -1, 18568, 18569, 18563, -1, 18570, 18571, 18572, -1, 18569, 18571, 18570, -1, 18572, 18573, 18574, -1, 18571, 18573, 18572, -1, 18574, 18549, 18546, -1, 18573, 18549, 18574, -1, 18575, 18576, 18577, -1, 18577, 18576, 18578, -1, 18578, 18576, 18579, -1, 18579, 18580, 18581, -1, 18576, 18580, 18579, -1, 18581, 18582, 18583, -1, 18580, 18582, 18581, -1, 18583, 18584, 18585, -1, 18582, 18584, 18583, -1, 18585, 18586, 18587, -1, 18584, 18586, 18585, -1, 18587, 18588, 18589, -1, 18586, 18588, 18587, -1, 18589, 18590, 18591, -1, 18588, 18590, 18589, -1, 18591, 18592, 18593, -1, 18590, 18592, 18591, -1, 18593, 18594, 18595, -1, 18592, 18594, 18593, -1, 18595, 18596, 18597, -1, 18594, 18596, 18595, -1, 18597, 18598, 18599, -1, 18596, 18598, 18597, -1, 18599, 18600, 18601, -1, 18598, 18600, 18599, -1, 18600, 18602, 18601, -1, 18603, 18604, 18605, -1, 18604, 18606, 18605, -1, 18605, 18607, 18608, -1, 18606, 18607, 18605, -1, 18608, 18609, 18610, -1, 18607, 18609, 18608, -1, 18610, 18611, 18612, -1, 18609, 18611, 18610, -1, 18612, 18613, 18614, -1, 18611, 18613, 18612, -1, 18614, 18615, 18616, -1, 18613, 18615, 18614, -1, 18616, 18617, 18618, -1, 18615, 18617, 18616, -1, 18618, 18619, 18620, -1, 18617, 18619, 18618, -1, 18620, 18621, 18622, -1, 18619, 18621, 18620, -1, 18622, 18623, 18624, -1, 18621, 18623, 18622, -1, 18624, 18625, 18626, -1, 18623, 18625, 18624, -1, 18626, 18627, 18628, -1, 18625, 18627, 18626, -1, 18628, 18629, 18630, -1, 18627, 18629, 18628, -1, 18631, 18632, 18633, -1, 18633, 18634, 18635, -1, 18632, 18634, 18633, -1, 18635, 18636, 18637, -1, 18634, 18636, 18635, -1, 18637, 18638, 18639, -1, 18636, 18638, 18637, -1, 18639, 18640, 18641, -1, 18638, 18640, 18639, -1, 18641, 18642, 18643, -1, 18640, 18642, 18641, -1, 18643, 18644, 18645, -1, 18642, 18644, 18643, -1, 18645, 18646, 18647, -1, 18644, 18646, 18645, -1, 18647, 18648, 18649, -1, 18646, 18648, 18647, -1, 18649, 18650, 18651, -1, 18648, 18650, 18649, -1, 18651, 18652, 18653, -1, 18650, 18652, 18651, -1, 18653, 18654, 18655, -1, 18652, 18654, 18653, -1, 18654, 18656, 18655, -1, 18655, 18657, 18658, -1, 18656, 18657, 18655, -1, 18659, 18660, 18661, -1, 18661, 18662, 18663, -1, 18660, 18662, 18661, -1, 18663, 18664, 18665, -1, 18662, 18664, 18663, -1, 18665, 18666, 18667, -1, 18664, 18666, 18665, -1, 18667, 18668, 18669, -1, 18666, 18668, 18667, -1, 18669, 18670, 18671, -1, 18668, 18670, 18669, -1, 18672, 18673, 18674, -1, 18674, 18675, 18676, -1, 18673, 18675, 18674, -1, 18676, 18677, 18678, -1, 18675, 18677, 18676, -1, 18678, 18679, 18680, -1, 18677, 18679, 18678, -1, 18680, 18681, 18682, -1, 18679, 18681, 18680, -1, 18682, 18683, 18684, -1, 18681, 18683, 18682, -1, 18685, 18686, 18687, -1, 18687, 18688, 18689, -1, 18686, 18688, 18687, -1, 18689, 18690, 18691, -1, 18688, 18690, 18689, -1, 18691, 18692, 18693, -1, 18690, 18692, 18691, -1, 18693, 18694, 18695, -1, 18692, 18694, 18693, -1, 18695, 18696, 18697, -1, 18694, 18696, 18695, -1, 18698, 18699, 18700, -1, 18700, 18701, 18702, -1, 18699, 18701, 18700, -1, 18702, 18703, 18704, -1, 18701, 18703, 18702, -1, 18704, 18705, 18706, -1, 18703, 18705, 18704, -1, 18706, 18707, 18708, -1, 18705, 18707, 18706, -1, 18708, 18709, 18710, -1, 18707, 18709, 18708, -1, 18711, 18712, 18713, -1, 18713, 18714, 18715, -1, 18712, 18714, 18713, -1, 18715, 18716, 18717, -1, 18714, 18716, 18715, -1, 18717, 18718, 18719, -1, 18716, 18718, 18717, -1, 18719, 18720, 18721, -1, 18718, 18720, 18719, -1, 18721, 18722, 18723, -1, 18720, 18722, 18721, -1, 18724, 18725, 18726, -1, 18726, 18727, 18728, -1, 18725, 18727, 18726, -1, 18728, 18729, 18730, -1, 18727, 18729, 18728, -1, 18730, 18731, 18732, -1, 18729, 18731, 18730, -1, 18732, 18733, 18734, -1, 18731, 18733, 18732, -1, 18734, 18735, 18736, -1, 18733, 18735, 18734, -1, 18737, 18738, 18739, -1, 18739, 18740, 18741, -1, 18738, 18740, 18739, -1, 18741, 18742, 18743, -1, 18740, 18742, 18741, -1, 18743, 18744, 18745, -1, 18742, 18744, 18743, -1, 18745, 18746, 18747, -1, 18744, 18746, 18745, -1, 18747, 18748, 18749, -1, 18746, 18748, 18747, -1, 18750, 18751, 18752, -1, 18752, 18753, 18754, -1, 18751, 18753, 18752, -1, 18754, 18755, 18756, -1, 18753, 18755, 18754, -1, 18756, 18757, 18758, -1, 18755, 18757, 18756, -1, 18758, 18759, 18760, -1, 18757, 18759, 18758, -1, 18760, 18761, 18762, -1, 18759, 18761, 18760, -1, 18763, 18764, 18765, -1, 18765, 18766, 18767, -1, 18764, 18766, 18765, -1, 18767, 18768, 18769, -1, 18766, 18768, 18767, -1, 18769, 18770, 18771, -1, 18768, 18770, 18769, -1, 18771, 18772, 18773, -1, 18770, 18772, 18771, -1, 18773, 18774, 18775, -1, 18772, 18774, 18773, -1, 18776, 18777, 18778, -1, 18778, 18779, 18780, -1, 18777, 18779, 18778, -1, 18780, 18781, 18782, -1, 18779, 18781, 18780, -1, 18782, 18783, 18784, -1, 18781, 18783, 18782, -1, 18784, 18785, 18786, -1, 18783, 18785, 18784, -1, 18786, 18787, 18788, -1, 18785, 18787, 18786, -1, 18789, 18790, 18791, -1, 18791, 18792, 18793, -1, 18790, 18792, 18791, -1, 18793, 18794, 18795, -1, 18792, 18794, 18793, -1, 18795, 18796, 18797, -1, 18794, 18796, 18795, -1, 18797, 18798, 18799, -1, 18796, 18798, 18797, -1, 18799, 18800, 18801, -1, 18798, 18800, 18799, -1, 18800, 18802, 18801, -1, 18803, 18804, 18805, -1, 18806, 18807, 18803, -1, 18803, 18807, 18804, -1, 18806, 18808, 18807, -1, 18806, 18809, 18808, -1, 18810, 18811, 18806, -1, 18806, 18811, 18809, -1, 18811, 18812, 18809, -1, 18811, 18813, 18812, -1, 18814, 18811, 18810, -1, 18814, 18815, 18811, -1, 18815, 18816, 18811, -1, 18816, 18817, 18811, -1, 18817, 18813, 18811, -1, 18818, 18819, 18814, -1, 18819, 18820, 18814, -1, 18820, 18815, 18814, -1, 18821, 18822, 18823, -1, 18821, 18824, 18822, -1, 18821, 18825, 18824, -1, 18821, 18826, 18825, -1, 18827, 18828, 18829, -1, 17785, 17789, 18830, -1, 18830, 17789, 18831, -1, 17234, 17235, 18832, -1, 18832, 17235, 18833, -1, 18834, 17803, 18835, -1, 18827, 18836, 18828, -1, 17789, 17774, 18831, -1, 17235, 17239, 18833, -1, 18837, 18838, 18839, -1, 18831, 17774, 18840, -1, 18833, 17239, 18841, -1, 18827, 17254, 18836, -1, 17774, 17776, 18840, -1, 18840, 17776, 18842, -1, 18841, 17224, 18843, -1, 17239, 17224, 18841, -1, 18837, 18844, 18838, -1, 18845, 18846, 18837, -1, 18847, 18846, 18845, -1, 18848, 18846, 18847, -1, 18843, 17226, 18849, -1, 18850, 18846, 18848, -1, 17224, 17226, 18843, -1, 18851, 18846, 18850, -1, 18852, 18846, 18851, -1, 18837, 18846, 18844, -1, 18834, 18853, 17803, -1, 18852, 18472, 18846, -1, 18520, 18472, 18852, -1, 18852, 18518, 18520, -1, 18472, 18474, 18846, -1, 18827, 18854, 17254, -1, 18852, 18517, 18518, -1, 18474, 18479, 18846, -1, 18855, 18856, 18853, -1, 18479, 18484, 18846, -1, 18856, 18857, 18853, -1, 18858, 18859, 18854, -1, 18860, 18861, 18862, -1, 18516, 18861, 18860, -1, 18517, 18861, 18516, -1, 18852, 18861, 18517, -1, 18857, 17804, 18853, -1, 18857, 18863, 17804, -1, 18859, 18864, 18854, -1, 18854, 17253, 17254, -1, 18864, 17253, 18854, -1, 18861, 18865, 18862, -1, 18866, 18867, 18868, -1, 18864, 18869, 17253, -1, 18870, 18867, 18866, -1, 18871, 18872, 18873, -1, 18874, 18872, 18871, -1, 18875, 18876, 18866, -1, 18866, 18876, 18870, -1, 18877, 18878, 18879, -1, 18880, 18881, 18882, -1, 18868, 18881, 18880, -1, 18867, 18881, 18868, -1, 18879, 18878, 18883, -1, 18872, 18884, 18873, -1, 18878, 17287, 18883, -1, 18873, 18884, 18861, -1, 18885, 18884, 18872, -1, 18875, 18886, 18876, -1, 18861, 18884, 18865, -1, 18884, 18887, 18865, -1, 18883, 17287, 18888, -1, 18882, 18889, 18890, -1, 18879, 18891, 18877, -1, 18494, 18892, 18489, -1, 18881, 18889, 18882, -1, 17287, 17288, 18888, -1, 18875, 17828, 18886, -1, 18892, 18893, 18489, -1, 18888, 17288, 18894, -1, 18890, 18895, 18896, -1, 18494, 18897, 18892, -1, 18879, 18898, 18891, -1, 18893, 18899, 18489, -1, 18889, 18895, 18890, -1, 18489, 18899, 18484, -1, 17288, 17292, 18894, -1, 18484, 18899, 18846, -1, 18494, 18900, 18897, -1, 18894, 17292, 18901, -1, 18499, 18900, 18494, -1, 18899, 18902, 18846, -1, 18895, 18903, 18896, -1, 18879, 17306, 18898, -1, 18499, 17129, 18900, -1, 17292, 17277, 18901, -1, 18902, 18904, 18846, -1, 18875, 17829, 17828, -1, 18901, 17277, 18905, -1, 18499, 18507, 17129, -1, 18905, 17279, 18906, -1, 18904, 18907, 18846, -1, 17277, 17279, 18905, -1, 18907, 18908, 18846, -1, 18884, 18909, 18887, -1, 18507, 18503, 17129, -1, 18908, 18910, 18846, -1, 18911, 18912, 18774, -1, 18879, 18913, 17306, -1, 18884, 18914, 18909, -1, 18903, 18802, 18896, -1, 18915, 18802, 17776, -1, 18896, 18802, 18915, -1, 18916, 18802, 18903, -1, 18917, 18802, 18916, -1, 18918, 18802, 18917, -1, 18919, 18802, 18918, -1, 18920, 18802, 18919, -1, 18921, 18802, 18920, -1, 18922, 18802, 18921, -1, 18923, 18802, 18922, -1, 17776, 18802, 18842, -1, 18912, 18775, 18774, -1, 18923, 18924, 18802, -1, 18925, 18926, 18913, -1, 18927, 18928, 18924, -1, 18926, 18929, 18913, -1, 18924, 18930, 18802, -1, 18928, 18930, 18924, -1, 18913, 17307, 17306, -1, 18929, 17307, 18913, -1, 18930, 18801, 18802, -1, 18929, 18931, 17307, -1, 18932, 18801, 18930, -1, 18933, 18801, 18932, -1, 18802, 18846, 17173, -1, 18802, 17173, 18934, -1, 18802, 18934, 17102, -1, 18802, 17102, 18935, -1, 18802, 18935, 17603, -1, 18802, 17603, 18849, -1, 18802, 18849, 17226, -1, 18802, 17226, 18906, -1, 18936, 17130, 18937, -1, 18802, 18906, 17279, -1, 18938, 17130, 18936, -1, 18802, 17279, 18939, -1, 18940, 17130, 18938, -1, 18802, 18939, 17332, -1, 18941, 18942, 18943, -1, 18802, 17332, 18944, -1, 18802, 18944, 17385, -1, 18945, 18942, 18941, -1, 18802, 17385, 18946, -1, 18802, 18946, 17438, -1, 18802, 17438, 18842, -1, 17130, 17129, 18505, -1, 18947, 18948, 18940, -1, 17130, 18505, 18937, -1, 18505, 17129, 18503, -1, 18949, 18950, 17200, -1, 18943, 17340, 18951, -1, 18952, 18953, 18683, -1, 18940, 18948, 17130, -1, 18952, 18683, 18954, -1, 18952, 18954, 18955, -1, 18942, 17340, 18943, -1, 18684, 18683, 18953, -1, 18684, 18953, 18956, -1, 18957, 18958, 18670, -1, 18957, 18670, 18959, -1, 18941, 18960, 18945, -1, 18957, 18959, 18961, -1, 18671, 18670, 18958, -1, 18671, 18958, 18962, -1, 18963, 18964, 18761, -1, 18963, 18761, 18965, -1, 18963, 18965, 18966, -1, 18762, 18761, 18964, -1, 18762, 18964, 18967, -1, 18864, 18968, 18696, -1, 18951, 17341, 18969, -1, 18864, 18696, 18970, -1, 18971, 18972, 18949, -1, 18864, 18970, 18869, -1, 18697, 18696, 18968, -1, 18697, 18968, 18973, -1, 18929, 18974, 18709, -1, 17340, 17341, 18951, -1, 18929, 18709, 18975, -1, 18949, 18972, 18976, -1, 18929, 18975, 18931, -1, 18710, 18709, 18974, -1, 18710, 18974, 18977, -1, 18978, 18979, 18722, -1, 18978, 18722, 18980, -1, 18978, 18980, 18981, -1, 18941, 18982, 18960, -1, 18723, 18722, 18979, -1, 18723, 18979, 18983, -1, 18984, 18985, 18735, -1, 18976, 17181, 18986, -1, 18984, 18735, 18987, -1, 18984, 18987, 18988, -1, 18969, 17345, 18989, -1, 18972, 17181, 18976, -1, 18736, 18735, 18985, -1, 18736, 18985, 18990, -1, 18991, 18992, 18748, -1, 18949, 18993, 18971, -1, 18991, 18748, 18994, -1, 17341, 17345, 18969, -1, 18991, 18994, 18995, -1, 18749, 18748, 18992, -1, 18749, 18992, 18996, -1, 18857, 18911, 18774, -1, 18857, 18774, 18997, -1, 18857, 18997, 18863, -1, 17804, 17803, 18853, -1, 18941, 17359, 18982, -1, 18986, 17182, 18998, -1, 17181, 17182, 18986, -1, 18989, 17330, 18999, -1, 18949, 19000, 18993, -1, 17345, 17330, 18989, -1, 18999, 17332, 18939, -1, 18998, 17186, 19001, -1, 17330, 17332, 18999, -1, 17182, 17186, 18998, -1, 18949, 17200, 19000, -1, 19002, 19003, 18947, -1, 18947, 19003, 18948, -1, 19001, 17171, 19004, -1, 17186, 17171, 19001, -1, 18910, 17173, 18846, -1, 17171, 17173, 19004, -1, 18941, 19005, 17359, -1, 19004, 17173, 18910, -1, 18914, 17147, 19002, -1, 18884, 17147, 18914, -1, 19002, 17147, 19003, -1, 19006, 19007, 19005, -1, 19007, 18978, 19005, -1, 19005, 17360, 17359, -1, 18978, 17360, 19005, -1, 19008, 19009, 18950, -1, 18978, 18981, 17360, -1, 19009, 18952, 18950, -1, 19010, 19011, 19012, -1, 18884, 17148, 17147, -1, 18952, 17201, 18950, -1, 19012, 19011, 19013, -1, 18950, 17201, 17200, -1, 19011, 17393, 19013, -1, 18952, 18955, 17201, -1, 19013, 17393, 19014, -1, 19012, 19015, 19010, -1, 19016, 19017, 19018, -1, 19014, 17394, 19019, -1, 19018, 19017, 19020, -1, 19017, 17110, 19020, -1, 17393, 17394, 19014, -1, 19012, 19021, 19015, -1, 19020, 17110, 19022, -1, 19018, 19023, 19016, -1, 19019, 17398, 19024, -1, 17394, 17398, 19019, -1, 17110, 17111, 19022, -1, 19012, 17412, 19021, -1, 19022, 17111, 19025, -1, 19018, 19026, 19023, -1, 17398, 17383, 19024, -1, 19024, 17383, 19027, -1, 17111, 17115, 19025, -1, 19027, 17385, 18944, -1, 19025, 17115, 19028, -1, 19018, 17076, 19026, -1, 17383, 17385, 19027, -1, 17115, 17100, 19028, -1, 19028, 17100, 19029, -1, 17100, 17102, 19029, -1, 19029, 17102, 18934, -1, 19012, 19030, 17412, -1, 19018, 19031, 17076, -1, 19032, 19033, 19030, -1, 19033, 18984, 19030, -1, 19030, 17413, 17412, -1, 18984, 17413, 19030, -1, 19034, 19035, 19031, -1, 18984, 18988, 17413, -1, 19035, 18957, 19031, -1, 19036, 19037, 19038, -1, 18957, 17077, 19031, -1, 19031, 17077, 17076, -1, 19038, 19037, 19039, -1, 18957, 18961, 17077, -1, 19039, 17446, 19040, -1, 19037, 17446, 19039, -1, 19038, 19041, 19036, -1, 19042, 19043, 19044, -1, 19045, 19043, 19042, -1, 19040, 17447, 19046, -1, 17446, 17447, 19040, -1, 19044, 17611, 19047, -1, 19043, 17611, 19044, -1, 19038, 19048, 19041, -1, 17447, 17451, 19046, -1, 19042, 19049, 19045, -1, 19046, 17451, 19050, -1, 19047, 17612, 19051, -1, 19038, 17465, 19048, -1, 17611, 17612, 19047, -1, 19042, 19052, 19049, -1, 19050, 17436, 19053, -1, 19051, 17616, 19054, -1, 17451, 17436, 19050, -1, 17612, 17616, 19051, -1, 19053, 17438, 18946, -1, 17436, 17438, 19053, -1, 19042, 17631, 19052, -1, 19054, 17601, 19055, -1, 17616, 17601, 19054, -1, 19055, 17603, 18935, -1, 17601, 17603, 19055, -1, 19038, 19056, 17465, -1, 19042, 19057, 17631, -1, 19058, 19059, 19056, -1, 19059, 18991, 19056, -1, 19056, 17466, 17465, -1, 19060, 19061, 19057, -1, 18991, 17466, 19056, -1, 18991, 18995, 17466, -1, 19061, 18963, 19057, -1, 19057, 17630, 17631, -1, 18963, 17630, 19057, -1, 18834, 19062, 19063, -1, 19064, 19062, 18834, -1, 18963, 18966, 17630, -1, 19062, 17784, 19063, -1, 19063, 17784, 19065, -1, 18829, 19066, 18827, -1, 18834, 19067, 19064, -1, 17784, 17785, 19065, -1, 18827, 19066, 19068, -1, 19065, 17785, 18830, -1, 19066, 17234, 19068, -1, 18834, 18835, 19067, -1, 19068, 17234, 18832, -1, 19069, 19070, 18787, -1, 19070, 19071, 18787, -1, 19071, 18788, 18787, -1, 19072, 19073, 19074, -1, 19074, 19075, 19076, -1, 19077, 19075, 19073, -1, 19073, 19075, 19074, -1, 19078, 19079, 19080, -1, 19081, 19079, 19078, -1, 19080, 19079, 19082, -1, 18009, 18213, 18162, -1, 18022, 18036, 19083, -1, 18065, 18212, 18011, -1, 18011, 18212, 18213, -1, 19083, 18020, 18022, -1, 18036, 18042, 19083, -1, 19084, 19085, 18065, -1, 18065, 19085, 18212, -1, 19083, 18073, 18020, -1, 19086, 19087, 19084, -1, 18042, 18047, 19083, -1, 19084, 19087, 19085, -1, 19083, 18072, 18073, -1, 19088, 19089, 19086, -1, 18047, 18052, 19083, -1, 19086, 19089, 19087, -1, 18052, 18057, 19083, -1, 19088, 19090, 19089, -1, 18057, 18062, 19083, -1, 19091, 19092, 19093, -1, 19094, 19092, 19091, -1, 18072, 19092, 19094, -1, 19083, 19092, 18072, -1, 19092, 19095, 19093, -1, 19092, 19096, 19095, -1, 19092, 19097, 19096, -1, 18179, 17653, 19083, -1, 19092, 19098, 19097, -1, 18184, 17653, 18179, -1, 18189, 17653, 18184, -1, 18194, 17653, 18189, -1, 18199, 17653, 18194, -1, 18206, 17653, 18199, -1, 18209, 17653, 18206, -1, 18203, 17653, 18209, -1, 19092, 19099, 19098, -1, 19100, 19101, 18204, -1, 19102, 19101, 19100, -1, 18203, 19101, 17653, -1, 19103, 19101, 19102, -1, 18204, 19101, 18203, -1, 17653, 19101, 17651, -1, 19104, 19105, 19103, -1, 19106, 19105, 19104, -1, 19107, 19105, 19106, -1, 19103, 19105, 19101, -1, 18068, 18164, 18062, -1, 19092, 19105, 19107, -1, 19092, 19107, 19108, -1, 19092, 19108, 19109, -1, 18062, 18164, 19083, -1, 19092, 19109, 19090, -1, 19092, 19090, 19099, -1, 18164, 18173, 19083, -1, 19099, 19090, 19110, -1, 19110, 19090, 19088, -1, 18009, 18162, 18068, -1, 18068, 18162, 18164, -1, 18173, 18179, 19083, -1, 18011, 18213, 18009, -1, 19111, 19112, 19113, -1, 19112, 19114, 19113, -1, 19112, 19115, 19114, -1, 19111, 19116, 19112, -1, 19117, 19118, 19119, -1, 19116, 19118, 19120, -1, 19118, 19121, 19120, -1, 19118, 19122, 19121, -1, 17699, 19123, 17706, -1, 17701, 19123, 17699, -1, 17701, 19124, 19123, -1, 19122, 19125, 17701, -1, 19118, 19125, 19122, -1, 17701, 19126, 19124, -1, 17701, 19127, 19126, -1, 19125, 19128, 17701, -1, 17701, 19128, 19127, -1, 19111, 19118, 19116, -1, 19117, 19125, 19118, -1, 19129, 19130, 19131, -1, 19131, 19130, 19132, -1, 19133, 19134, 19135, -1, 19135, 19134, 19136, -1, 19137, 19138, 19139, -1, 19139, 19138, 19140, -1, 19141, 19142, 19143, -1, 19143, 19144, 19145, -1, 19142, 19144, 19143, -1, 19146, 19147, 19148, -1, 19148, 19147, 19149, -1, 19150, 19151, 19152, -1, 19152, 19153, 19154, -1, 19151, 19153, 19152, -1, 19155, 19156, 19157, -1, 19157, 19156, 19158, -1, 19159, 19160, 19161, -1, 19161, 19162, 19163, -1, 19160, 19162, 19161, -1, 19164, 19165, 19166, -1, 19166, 19165, 19167, -1, 19168, 19169, 19170, -1, 19170, 19171, 19172, -1, 19169, 19171, 19170, -1, 19173, 19174, 19175, -1, 19175, 19174, 19176, -1, 19177, 19178, 19179, -1, 19179, 19180, 19181, -1, 19178, 19180, 19179, -1, 19182, 19183, 19184, -1, 19184, 19183, 19185, -1, 19186, 19187, 19188, -1, 19188, 19189, 19190, -1, 19187, 19189, 19188, -1, 19191, 19192, 19193, -1, 19193, 19192, 19194, -1, 19195, 19196, 19197, -1, 19197, 19198, 19199, -1, 19196, 19198, 19197, -1, 19200, 19201, 19202, -1, 19202, 19201, 19203, -1, 19204, 19205, 19206, -1, 19206, 19207, 19208, -1, 19205, 19207, 19206, -1, 19209, 19210, 19211, -1, 19211, 19212, 19213, -1, 19210, 19212, 19211, -1, 19083, 19214, 19092, -1, 19092, 19214, 19215, -1, 19215, 19214, 19216, -1, 19216, 19217, 18789, -1, 19214, 19217, 19216, -1, 19217, 18790, 18789, -1, 19133, 19218, 19134, -1, 19134, 19218, 19219, -1, 19219, 19220, 19221, -1, 19218, 19220, 19219, -1, 19221, 19222, 19223, -1, 19220, 19222, 19221, -1, 19223, 19224, 19225, -1, 19222, 19224, 19223, -1, 19226, 19227, 19228, -1, 19225, 19227, 19226, -1, 19224, 19227, 19225, -1, 19227, 19229, 19228, -1, 19228, 19230, 18930, -1, 19229, 19230, 19228, -1, 19230, 19231, 18930, -1, 19231, 18932, 18930, -1, 19231, 18933, 18932, -1, 19230, 18933, 19231, -1, 19229, 18933, 19230, -1, 19077, 19232, 19075, -1, 19075, 19232, 19233, -1, 19233, 19232, 19234, -1, 19234, 19235, 18776, -1, 19232, 19235, 19234, -1, 19235, 18777, 18776, -1, 19210, 19236, 19212, -1, 19212, 19236, 19237, -1, 19237, 19236, 19238, -1, 19238, 19239, 18763, -1, 19236, 19239, 19238, -1, 19239, 18764, 18763, -1, 19078, 19240, 19081, -1, 19081, 19240, 19241, -1, 19241, 19242, 19243, -1, 19240, 19242, 19241, -1, 19243, 19244, 19245, -1, 19242, 19244, 19243, -1, 19245, 19246, 19247, -1, 19244, 19246, 19245, -1, 19248, 19249, 19250, -1, 19247, 19249, 19248, -1, 19246, 19249, 19247, -1, 19249, 19251, 19250, -1, 19250, 19252, 19069, -1, 19251, 19252, 19250, -1, 19252, 19253, 19069, -1, 19253, 19070, 19069, -1, 19253, 19071, 19070, -1, 19252, 19071, 19253, -1, 19251, 19071, 19252, -1, 19254, 19255, 19256, -1, 19254, 19257, 19255, -1, 19257, 19258, 19255, -1, 19257, 19259, 19258, -1, 19260, 19261, 19262, -1, 19260, 19263, 19261, -1, 19260, 19264, 19263, -1, 19260, 19265, 19264, -1, 19265, 19266, 19267, -1, 19260, 19266, 19265, -1, 19268, 19269, 19270, -1, 19268, 19271, 19269, -1, 19268, 19272, 19271, -1, 19273, 19274, 19275, -1, 19273, 19276, 19274, -1, 19273, 19277, 19276, -1, 19278, 19279, 19280, -1, 19278, 19281, 19279, -1, 19278, 19282, 19281, -1, 19283, 19284, 19285, -1, 19283, 19286, 19284, -1, 19283, 19287, 19286, -1, 19288, 19289, 19290, -1, 19288, 19291, 19289, -1, 19288, 19292, 19291, -1, 19293, 19294, 19295, -1, 19293, 19296, 19294, -1, 19293, 19297, 19296, -1, 19298, 19299, 19300, -1, 19298, 19301, 19299, -1, 19298, 19302, 19301, -1, 19303, 19304, 19305, -1, 19303, 19306, 19304, -1, 19303, 19307, 19306, -1, 19308, 19309, 19310, -1, 19308, 19311, 19309, -1, 19308, 19312, 19311, -1, 19308, 19313, 19312, -1, 19313, 18814, 18810, -1, 19313, 18818, 18814, -1, 19308, 18818, 19313, -1, 19157, 19158, 19314, -1, 19314, 19315, 19316, -1, 19316, 19315, 19317, -1, 19158, 19315, 19314, -1, 19317, 19318, 19319, -1, 19319, 19318, 19320, -1, 19315, 19318, 19317, -1, 19320, 19321, 19322, -1, 19322, 19321, 19323, -1, 19318, 19321, 19320, -1, 19323, 19324, 19325, -1, 19321, 19324, 19323, -1, 19325, 19326, 19327, -1, 19324, 19326, 19325, -1, 19328, 19329, 19330, -1, 19327, 19329, 19328, -1, 19326, 19329, 19327, -1, 19330, 19331, 19332, -1, 19329, 19331, 19330, -1, 19332, 19333, 19334, -1, 19331, 19333, 19332, -1, 19161, 19163, 19335, -1, 19163, 19336, 19335, -1, 19336, 19337, 19335, -1, 19335, 19338, 19339, -1, 19337, 19338, 19335, -1, 19339, 19340, 19300, -1, 19338, 19340, 19339, -1, 19340, 19298, 19300, -1, 19160, 19341, 19162, -1, 19162, 19341, 19342, -1, 19342, 19341, 19343, -1, 19343, 19344, 18750, -1, 19341, 19344, 19343, -1, 19344, 18751, 18750, -1, 19155, 19345, 19156, -1, 19156, 19345, 19346, -1, 19346, 19347, 19348, -1, 19345, 19347, 19346, -1, 19348, 19349, 19350, -1, 19347, 19349, 19348, -1, 19350, 19351, 19352, -1, 19349, 19351, 19350, -1, 19353, 19354, 19355, -1, 19352, 19354, 19353, -1, 19351, 19354, 19352, -1, 19354, 19356, 19355, -1, 19355, 19357, 18864, -1, 19356, 19357, 19355, -1, 19357, 19358, 18864, -1, 19358, 18968, 18864, -1, 19358, 18973, 18968, -1, 19357, 18973, 19358, -1, 19356, 18973, 19357, -1, 19139, 19140, 19359, -1, 19359, 19360, 19361, -1, 19361, 19360, 19362, -1, 19140, 19360, 19359, -1, 19362, 19363, 19364, -1, 19364, 19363, 19365, -1, 19360, 19363, 19362, -1, 19365, 19366, 19367, -1, 19367, 19366, 19368, -1, 19363, 19366, 19365, -1, 19368, 19369, 19370, -1, 19366, 19369, 19368, -1, 19370, 19371, 19372, -1, 19369, 19371, 19370, -1, 19373, 19374, 19375, -1, 19372, 19374, 19373, -1, 19371, 19374, 19372, -1, 19375, 19376, 19377, -1, 19374, 19376, 19375, -1, 19377, 19378, 19379, -1, 19376, 19378, 19377, -1, 19143, 19145, 19380, -1, 19145, 19381, 19380, -1, 19381, 19382, 19380, -1, 19380, 19383, 19384, -1, 19382, 19383, 19380, -1, 19383, 19385, 19384, -1, 19384, 19308, 19310, -1, 19385, 19308, 19384, -1, 19148, 19149, 19386, -1, 19386, 19387, 19388, -1, 19388, 19387, 19389, -1, 19149, 19387, 19386, -1, 19389, 19390, 19391, -1, 19391, 19390, 19392, -1, 19387, 19390, 19389, -1, 19392, 19393, 19394, -1, 19394, 19393, 19395, -1, 19390, 19393, 19392, -1, 19395, 19396, 19397, -1, 19393, 19396, 19395, -1, 19397, 19398, 19399, -1, 19396, 19398, 19397, -1, 19400, 19401, 19402, -1, 19399, 19401, 19400, -1, 19398, 19401, 19399, -1, 19402, 19403, 19404, -1, 19401, 19403, 19402, -1, 19404, 19405, 19406, -1, 19403, 19405, 19404, -1, 19152, 19154, 19407, -1, 19154, 19408, 19407, -1, 19408, 19409, 19407, -1, 19407, 19410, 19411, -1, 19409, 19410, 19407, -1, 19411, 19412, 19305, -1, 19410, 19412, 19411, -1, 19412, 19303, 19305, -1, 19166, 19167, 19413, -1, 19413, 19414, 19415, -1, 19415, 19414, 19416, -1, 19167, 19414, 19413, -1, 19416, 19417, 19418, -1, 19418, 19417, 19419, -1, 19414, 19417, 19416, -1, 19419, 19420, 19421, -1, 19421, 19420, 19422, -1, 19417, 19420, 19419, -1, 19422, 19423, 19424, -1, 19420, 19423, 19422, -1, 19424, 19425, 19426, -1, 19423, 19425, 19424, -1, 19427, 19428, 19429, -1, 19426, 19428, 19427, -1, 19425, 19428, 19426, -1, 19429, 19430, 19431, -1, 19428, 19430, 19429, -1, 19431, 19432, 19433, -1, 19430, 19432, 19431, -1, 19170, 19172, 19434, -1, 19172, 19435, 19434, -1, 19435, 19436, 19434, -1, 19434, 19437, 19438, -1, 19436, 19437, 19434, -1, 19438, 19439, 19295, -1, 19437, 19439, 19438, -1, 19439, 19293, 19295, -1, 19266, 19440, 19267, -1, 19441, 19440, 19266, -1, 19442, 19443, 19441, -1, 19441, 19443, 19440, -1, 19442, 18823, 19443, -1, 19442, 18821, 18823, -1, 19175, 19176, 19444, -1, 19444, 19445, 19446, -1, 19446, 19445, 19447, -1, 19176, 19445, 19444, -1, 19447, 19448, 19449, -1, 19449, 19448, 19450, -1, 19445, 19448, 19447, -1, 19450, 19451, 19452, -1, 19452, 19451, 19453, -1, 19448, 19451, 19450, -1, 19453, 19454, 19455, -1, 19451, 19454, 19453, -1, 19455, 19456, 19457, -1, 19454, 19456, 19455, -1, 19457, 19458, 19459, -1, 19459, 19458, 19460, -1, 19456, 19458, 19457, -1, 18826, 19461, 18825, -1, 19460, 19461, 18826, -1, 19458, 19461, 19460, -1, 18824, 19462, 18822, -1, 18825, 19462, 18824, -1, 19461, 19462, 18825, -1, 19179, 19181, 19463, -1, 19181, 19464, 19463, -1, 19464, 19465, 19463, -1, 19463, 19466, 19467, -1, 19465, 19466, 19463, -1, 19467, 19468, 19290, -1, 19466, 19468, 19467, -1, 19468, 19288, 19290, -1, 19184, 19185, 19469, -1, 19469, 19470, 19471, -1, 19471, 19470, 19472, -1, 19185, 19470, 19469, -1, 19472, 19473, 19474, -1, 19474, 19473, 19475, -1, 19470, 19473, 19472, -1, 19475, 19476, 19477, -1, 19477, 19476, 19478, -1, 19473, 19476, 19475, -1, 19478, 19479, 19480, -1, 19476, 19479, 19478, -1, 19480, 19481, 19482, -1, 19479, 19481, 19480, -1, 19483, 19484, 19485, -1, 19482, 19484, 19483, -1, 19481, 19484, 19482, -1, 19485, 19486, 19487, -1, 19484, 19486, 19485, -1, 19487, 19488, 19489, -1, 19486, 19488, 19487, -1, 19188, 19190, 19490, -1, 19190, 19491, 19490, -1, 19491, 19492, 19490, -1, 19490, 19493, 19494, -1, 19492, 19493, 19490, -1, 19493, 19495, 19494, -1, 19494, 19260, 19262, -1, 19495, 19260, 19494, -1, 19197, 19199, 19496, -1, 19199, 19497, 19496, -1, 19497, 19498, 19496, -1, 19496, 19499, 19500, -1, 19498, 19499, 19496, -1, 19500, 19501, 19270, -1, 19499, 19501, 19500, -1, 19501, 19268, 19270, -1, 19193, 19194, 19502, -1, 19502, 19503, 19504, -1, 19504, 19503, 19505, -1, 19194, 19503, 19502, -1, 19505, 19506, 19507, -1, 19507, 19506, 19508, -1, 19503, 19506, 19505, -1, 19508, 19509, 19510, -1, 19510, 19509, 19511, -1, 19506, 19509, 19508, -1, 19511, 19512, 19513, -1, 19509, 19512, 19511, -1, 19513, 19514, 19515, -1, 19515, 19514, 19516, -1, 19512, 19514, 19513, -1, 19516, 19517, 19518, -1, 19514, 19517, 19516, -1, 19518, 19519, 19520, -1, 19520, 19519, 19521, -1, 19517, 19519, 19518, -1, 19521, 19522, 19523, -1, 19519, 19522, 19521, -1, 19206, 19208, 19524, -1, 19208, 19525, 19524, -1, 19525, 19526, 19524, -1, 19524, 19527, 19528, -1, 19526, 19527, 19524, -1, 19528, 19529, 19275, -1, 19527, 19529, 19528, -1, 19529, 19273, 19275, -1, 19202, 19203, 19530, -1, 19530, 19531, 19532, -1, 19532, 19531, 19533, -1, 19203, 19531, 19530, -1, 19533, 19534, 19535, -1, 19535, 19534, 19536, -1, 19531, 19534, 19533, -1, 19536, 19537, 19538, -1, 19538, 19537, 19539, -1, 19534, 19537, 19536, -1, 19539, 19540, 19541, -1, 19537, 19540, 19539, -1, 19541, 19542, 19543, -1, 19543, 19542, 19544, -1, 19540, 19542, 19541, -1, 19544, 19545, 19546, -1, 19542, 19545, 19544, -1, 19546, 19547, 19548, -1, 19548, 19547, 19549, -1, 19545, 19547, 19546, -1, 19549, 19550, 19551, -1, 19547, 19550, 19549, -1, 19552, 19553, 19254, -1, 19254, 19553, 19257, -1, 19554, 19555, 19552, -1, 19552, 19555, 19553, -1, 19554, 19556, 19555, -1, 19101, 19105, 19557, -1, 19105, 19558, 19557, -1, 19557, 19559, 19560, -1, 19558, 19559, 19557, -1, 19559, 19556, 19560, -1, 19556, 19554, 19560, -1, 19554, 19552, 19560, -1, 19552, 19256, 19560, -1, 19552, 19254, 19256, -1, 19080, 19082, 19561, -1, 19561, 19562, 19563, -1, 19563, 19562, 19564, -1, 19082, 19562, 19561, -1, 19564, 19565, 19566, -1, 19566, 19565, 19567, -1, 19562, 19565, 19564, -1, 19567, 19568, 19569, -1, 19569, 19568, 19570, -1, 19565, 19568, 19567, -1, 19570, 19571, 19572, -1, 19568, 19571, 19570, -1, 19572, 19573, 19574, -1, 19571, 19573, 19572, -1, 19575, 19576, 19577, -1, 19574, 19576, 19575, -1, 19573, 19576, 19574, -1, 19577, 19578, 19579, -1, 19576, 19578, 19577, -1, 19579, 19580, 19581, -1, 19578, 19580, 19579, -1, 19211, 19213, 19582, -1, 19213, 19583, 19582, -1, 19583, 19584, 19582, -1, 19582, 19585, 19586, -1, 19584, 19585, 19582, -1, 19586, 19587, 19280, -1, 19585, 19587, 19586, -1, 19587, 19278, 19280, -1, 19074, 19076, 19588, -1, 19076, 19589, 19588, -1, 19589, 19590, 19588, -1, 19588, 19591, 19592, -1, 19590, 19591, 19588, -1, 19592, 19593, 19285, -1, 19591, 19593, 19592, -1, 19593, 19283, 19285, -1, 19135, 19136, 19594, -1, 19594, 19595, 19596, -1, 19596, 19595, 19597, -1, 19136, 19595, 19594, -1, 19597, 19598, 19599, -1, 19599, 19598, 19600, -1, 19595, 19598, 19597, -1, 19600, 19601, 19602, -1, 19602, 19601, 19603, -1, 19598, 19601, 19600, -1, 19603, 19604, 19605, -1, 19601, 19604, 19603, -1, 19605, 19606, 19607, -1, 19607, 19606, 19608, -1, 19604, 19606, 19605, -1, 19608, 19609, 19610, -1, 19606, 19609, 19608, -1, 19610, 19611, 19612, -1, 19612, 19611, 19613, -1, 19609, 19611, 19610, -1, 19613, 19614, 19615, -1, 19611, 19614, 19613, -1, 19131, 19132, 19616, -1, 19616, 19617, 19618, -1, 19618, 19617, 19619, -1, 19132, 19617, 19616, -1, 19619, 19620, 19621, -1, 19621, 19620, 19622, -1, 19617, 19620, 19619, -1, 19622, 19623, 19624, -1, 19624, 19623, 19625, -1, 19620, 19623, 19622, -1, 19625, 19626, 19627, -1, 19623, 19626, 19625, -1, 19627, 19628, 19629, -1, 19626, 19628, 19627, -1, 19629, 19630, 19631, -1, 19631, 19630, 19632, -1, 19628, 19630, 19629, -1, 19632, 19633, 18805, -1, 19630, 19633, 19632, -1, 18805, 19634, 18803, -1, 19633, 19634, 18805, -1, 19377, 19635, 19636, -1, 19377, 19637, 19635, -1, 19377, 19379, 19637, -1, 19375, 19377, 19636, -1, 19373, 19375, 19636, -1, 19372, 19373, 19636, -1, 19638, 19637, 19379, -1, 19635, 19637, 19638, -1, 19639, 19635, 19638, -1, 19636, 19635, 19639, -1, 19640, 19639, 19641, -1, 19642, 19636, 19639, -1, 19642, 19639, 19640, -1, 19643, 19636, 19642, -1, 19640, 19644, 19645, -1, 19640, 19641, 19644, -1, 19642, 19645, 19646, -1, 19642, 19640, 19645, -1, 19643, 19646, 19647, -1, 19643, 19642, 19646, -1, 19648, 19647, 19646, -1, 19648, 19646, 19645, -1, 19648, 19645, 19644, -1, 19649, 19650, 19651, -1, 19652, 19648, 19653, -1, 19654, 19648, 19652, -1, 19655, 19653, 19656, -1, 19655, 19652, 19653, -1, 19657, 19307, 19647, -1, 19657, 19648, 19654, -1, 19657, 19647, 19648, -1, 19658, 19654, 19652, -1, 19658, 19652, 19655, -1, 19659, 19656, 19650, -1, 19659, 19655, 19656, -1, 19659, 19650, 19649, -1, 19660, 19306, 19307, -1, 19660, 19654, 19658, -1, 19660, 19307, 19657, -1, 19660, 19657, 19654, -1, 19661, 19649, 19662, -1, 19661, 19659, 19649, -1, 19661, 19658, 19655, -1, 19661, 19655, 19659, -1, 19663, 19304, 19306, -1, 19663, 19305, 19304, -1, 19663, 19662, 19305, -1, 19663, 19306, 19660, -1, 19663, 19658, 19661, -1, 19663, 19661, 19662, -1, 19663, 19660, 19658, -1, 19404, 19664, 19665, -1, 19404, 19666, 19664, -1, 19404, 19406, 19666, -1, 19402, 19404, 19665, -1, 19400, 19402, 19665, -1, 19399, 19400, 19665, -1, 19667, 19666, 19406, -1, 19664, 19666, 19667, -1, 19668, 19664, 19667, -1, 19665, 19664, 19668, -1, 19669, 19668, 19670, -1, 19671, 19665, 19668, -1, 19671, 19668, 19669, -1, 19672, 19665, 19671, -1, 19669, 19673, 19674, -1, 19669, 19670, 19673, -1, 19671, 19675, 19676, -1, 19671, 19674, 19675, -1, 19671, 19669, 19674, -1, 19672, 19671, 19676, -1, 19677, 19676, 19675, -1, 19677, 19675, 19674, -1, 19677, 19674, 19673, -1, 19678, 19679, 19680, -1, 19681, 19677, 19682, -1, 19683, 19677, 19681, -1, 19684, 19682, 19685, -1, 19684, 19681, 19682, -1, 19686, 19302, 19676, -1, 19686, 19677, 19683, -1, 19686, 19676, 19677, -1, 19687, 19683, 19681, -1, 19687, 19681, 19684, -1, 19688, 19685, 19679, -1, 19688, 19684, 19685, -1, 19688, 19679, 19678, -1, 19689, 19301, 19302, -1, 19689, 19683, 19687, -1, 19689, 19302, 19686, -1, 19689, 19686, 19683, -1, 19690, 19678, 19691, -1, 19690, 19688, 19678, -1, 19690, 19687, 19684, -1, 19690, 19684, 19688, -1, 19692, 19299, 19301, -1, 19692, 19300, 19299, -1, 19692, 19691, 19300, -1, 19692, 19301, 19689, -1, 19692, 19687, 19690, -1, 19692, 19690, 19691, -1, 19692, 19689, 19687, -1, 19332, 19693, 19694, -1, 19332, 19695, 19693, -1, 19332, 19334, 19695, -1, 19330, 19332, 19694, -1, 19328, 19330, 19694, -1, 19327, 19328, 19694, -1, 19696, 19695, 19334, -1, 19693, 19695, 19696, -1, 19697, 19693, 19696, -1, 19694, 19693, 19697, -1, 19698, 19697, 19699, -1, 19700, 19694, 19697, -1, 19700, 19697, 19698, -1, 19701, 19694, 19700, -1, 19699, 19702, 19703, -1, 19698, 19703, 19704, -1, 19698, 19699, 19703, -1, 19700, 19698, 19704, -1, 19701, 19704, 19705, -1, 19701, 19700, 19704, -1, 19706, 19705, 19704, -1, 19706, 19704, 19703, -1, 19706, 19703, 19702, -1, 19707, 19708, 19709, -1, 19710, 19706, 19711, -1, 19712, 19706, 19710, -1, 19713, 19711, 19714, -1, 19713, 19710, 19711, -1, 19715, 19297, 19705, -1, 19715, 19706, 19712, -1, 19715, 19705, 19706, -1, 19716, 19712, 19710, -1, 19716, 19710, 19713, -1, 19717, 19714, 19708, -1, 19717, 19713, 19714, -1, 19717, 19708, 19707, -1, 19718, 19296, 19297, -1, 19718, 19712, 19716, -1, 19718, 19297, 19715, -1, 19718, 19715, 19712, -1, 19719, 19707, 19720, -1, 19719, 19717, 19707, -1, 19719, 19716, 19713, -1, 19719, 19713, 19717, -1, 19721, 19294, 19296, -1, 19721, 19295, 19294, -1, 19721, 19720, 19295, -1, 19721, 19296, 19718, -1, 19721, 19716, 19719, -1, 19721, 19719, 19720, -1, 19721, 19718, 19716, -1, 19431, 19722, 19723, -1, 19431, 19724, 19722, -1, 19431, 19433, 19724, -1, 19429, 19431, 19723, -1, 19427, 19429, 19723, -1, 19426, 19427, 19723, -1, 19725, 19724, 19433, -1, 19722, 19724, 19725, -1, 19726, 19722, 19725, -1, 19723, 19722, 19726, -1, 19727, 19726, 19728, -1, 19729, 19723, 19726, -1, 19729, 19726, 19727, -1, 19730, 19723, 19729, -1, 19728, 19731, 19732, -1, 19727, 19728, 19732, -1, 19729, 19732, 19733, -1, 19729, 19727, 19732, -1, 19730, 19733, 19734, -1, 19730, 19729, 19733, -1, 19735, 19734, 19733, -1, 19735, 19733, 19732, -1, 19735, 19732, 19731, -1, 19736, 19737, 19738, -1, 19739, 19735, 19740, -1, 19741, 19735, 19739, -1, 19742, 19740, 19743, -1, 19742, 19739, 19740, -1, 19744, 19292, 19734, -1, 19744, 19735, 19741, -1, 19744, 19734, 19735, -1, 19745, 19741, 19739, -1, 19745, 19739, 19742, -1, 19746, 19743, 19737, -1, 19746, 19742, 19743, -1, 19746, 19737, 19736, -1, 19747, 19291, 19292, -1, 19747, 19741, 19745, -1, 19747, 19292, 19744, -1, 19747, 19744, 19741, -1, 19748, 19736, 19749, -1, 19748, 19746, 19736, -1, 19748, 19745, 19742, -1, 19748, 19742, 19746, -1, 19750, 19289, 19291, -1, 19750, 19290, 19289, -1, 19750, 19749, 19290, -1, 19750, 19291, 19747, -1, 19750, 19745, 19748, -1, 19750, 19748, 19749, -1, 19750, 19747, 19745, -1, 19487, 19751, 19752, -1, 19487, 19753, 19751, -1, 19487, 19489, 19753, -1, 19485, 19487, 19752, -1, 19483, 19485, 19752, -1, 19482, 19483, 19752, -1, 19754, 19753, 19489, -1, 19751, 19753, 19754, -1, 19755, 19751, 19754, -1, 19752, 19751, 19755, -1, 19756, 19755, 19757, -1, 19758, 19752, 19755, -1, 19758, 19755, 19756, -1, 19759, 19752, 19758, -1, 19757, 19760, 19761, -1, 19756, 19761, 19762, -1, 19756, 19757, 19761, -1, 19758, 19762, 19763, -1, 19758, 19756, 19762, -1, 19759, 19758, 19763, -1, 19764, 19763, 19762, -1, 19764, 19762, 19761, -1, 19764, 19761, 19760, -1, 19765, 19766, 19767, -1, 19768, 19764, 19769, -1, 19770, 19764, 19768, -1, 19771, 19769, 19772, -1, 19771, 19768, 19769, -1, 19773, 19272, 19763, -1, 19773, 19764, 19770, -1, 19773, 19763, 19764, -1, 19774, 19770, 19768, -1, 19774, 19768, 19771, -1, 19775, 19772, 19766, -1, 19775, 19771, 19772, -1, 19775, 19766, 19765, -1, 19776, 19271, 19272, -1, 19776, 19770, 19774, -1, 19776, 19272, 19773, -1, 19776, 19773, 19770, -1, 19777, 19765, 19778, -1, 19777, 19775, 19765, -1, 19777, 19774, 19771, -1, 19777, 19771, 19775, -1, 19779, 19269, 19271, -1, 19779, 19270, 19269, -1, 19779, 19778, 19270, -1, 19779, 19271, 19776, -1, 19779, 19774, 19777, -1, 19779, 19777, 19778, -1, 19779, 19776, 19774, -1, 19518, 19780, 19516, -1, 19520, 19781, 19518, -1, 19518, 19781, 19780, -1, 19521, 19782, 19520, -1, 19523, 19782, 19521, -1, 19780, 19782, 19783, -1, 19783, 19782, 19784, -1, 19784, 19782, 19785, -1, 19785, 19782, 19523, -1, 19520, 19782, 19781, -1, 19781, 19782, 19780, -1, 19786, 19785, 19523, -1, 19784, 19785, 19786, -1, 19787, 19784, 19786, -1, 19783, 19784, 19787, -1, 19788, 19787, 19789, -1, 19790, 19783, 19787, -1, 19790, 19787, 19788, -1, 19791, 19783, 19790, -1, 19789, 19792, 19793, -1, 19788, 19793, 19794, -1, 19788, 19789, 19793, -1, 19790, 19794, 19795, -1, 19790, 19788, 19794, -1, 19791, 19790, 19795, -1, 19796, 19795, 19794, -1, 19796, 19794, 19793, -1, 19796, 19793, 19792, -1, 19797, 19798, 19799, -1, 19800, 19796, 19801, -1, 19802, 19796, 19800, -1, 19803, 19801, 19804, -1, 19803, 19800, 19801, -1, 19805, 19277, 19795, -1, 19805, 19796, 19802, -1, 19805, 19795, 19796, -1, 19806, 19802, 19800, -1, 19806, 19800, 19803, -1, 19807, 19804, 19798, -1, 19807, 19803, 19804, -1, 19807, 19798, 19797, -1, 19808, 19276, 19277, -1, 19808, 19802, 19806, -1, 19808, 19277, 19805, -1, 19808, 19805, 19802, -1, 19809, 19797, 19810, -1, 19809, 19807, 19797, -1, 19809, 19806, 19803, -1, 19809, 19803, 19807, -1, 19811, 19274, 19276, -1, 19811, 19275, 19274, -1, 19811, 19810, 19275, -1, 19811, 19276, 19808, -1, 19811, 19806, 19809, -1, 19811, 19809, 19810, -1, 19811, 19808, 19806, -1, 19546, 19812, 19544, -1, 19551, 19813, 19549, -1, 19548, 19814, 19546, -1, 19546, 19814, 19812, -1, 19549, 19815, 19548, -1, 19812, 19815, 19816, -1, 19816, 19815, 19817, -1, 19817, 19815, 19813, -1, 19548, 19815, 19814, -1, 19814, 19815, 19812, -1, 19813, 19815, 19549, -1, 19818, 19813, 19551, -1, 19817, 19813, 19818, -1, 19819, 19817, 19818, -1, 19816, 19817, 19819, -1, 19820, 19819, 19821, -1, 19822, 19816, 19819, -1, 19822, 19819, 19820, -1, 19823, 19816, 19822, -1, 19821, 19824, 19825, -1, 19820, 19825, 19826, -1, 19820, 19821, 19825, -1, 19822, 19820, 19826, -1, 19823, 19826, 19827, -1, 19823, 19822, 19826, -1, 19828, 19827, 19826, -1, 19828, 19826, 19825, -1, 19828, 19825, 19824, -1, 19829, 19830, 19831, -1, 19832, 19828, 19833, -1, 19834, 19828, 19832, -1, 19835, 19833, 19836, -1, 19835, 19832, 19833, -1, 19837, 19282, 19827, -1, 19837, 19828, 19834, -1, 19837, 19827, 19828, -1, 19838, 19834, 19832, -1, 19838, 19832, 19835, -1, 19839, 19836, 19830, -1, 19839, 19835, 19836, -1, 19839, 19830, 19829, -1, 19840, 19281, 19282, -1, 19840, 19834, 19838, -1, 19840, 19282, 19837, -1, 19840, 19837, 19834, -1, 19841, 19829, 19842, -1, 19841, 19839, 19829, -1, 19841, 19838, 19835, -1, 19841, 19835, 19839, -1, 19843, 19279, 19281, -1, 19843, 19280, 19279, -1, 19843, 19842, 19280, -1, 19843, 19281, 19840, -1, 19843, 19838, 19841, -1, 19843, 19841, 19842, -1, 19843, 19840, 19838, -1, 19610, 19844, 19608, -1, 19612, 19845, 19610, -1, 19610, 19845, 19844, -1, 19613, 19846, 19612, -1, 19615, 19846, 19613, -1, 19844, 19846, 19847, -1, 19847, 19846, 19848, -1, 19848, 19846, 19849, -1, 19849, 19846, 19615, -1, 19612, 19846, 19845, -1, 19845, 19846, 19844, -1, 19850, 19849, 19615, -1, 19848, 19849, 19850, -1, 19851, 19848, 19850, -1, 19847, 19848, 19851, -1, 19852, 19851, 19853, -1, 19854, 19847, 19851, -1, 19854, 19851, 19852, -1, 19855, 19847, 19854, -1, 19853, 19856, 19857, -1, 19852, 19857, 19858, -1, 19852, 19853, 19857, -1, 19854, 19858, 19859, -1, 19854, 19852, 19858, -1, 19855, 19854, 19859, -1, 19860, 19858, 19857, -1, 19860, 19857, 19856, -1, 19859, 19858, 19860, -1, 19861, 19255, 19862, -1, 19256, 19255, 19861, -1, 19863, 19864, 19865, -1, 19863, 19860, 19864, -1, 19866, 19860, 19863, -1, 19867, 19259, 19859, -1, 19867, 19866, 19259, -1, 19867, 19860, 19866, -1, 19867, 19859, 19860, -1, 19868, 19863, 19865, -1, 19869, 19866, 19863, -1, 19869, 19259, 19866, -1, 19869, 19863, 19868, -1, 19870, 19258, 19259, -1, 19870, 19869, 19258, -1, 19870, 19259, 19869, -1, 19871, 19872, 19873, -1, 19871, 19865, 19872, -1, 19871, 19873, 19862, -1, 19871, 19868, 19865, -1, 19874, 19871, 19862, -1, 19874, 19869, 19868, -1, 19874, 19868, 19871, -1, 19874, 19862, 19255, -1, 19874, 19258, 19869, -1, 19875, 19255, 19258, -1, 19875, 19258, 19874, -1, 19875, 19874, 19255, -1, 19579, 19876, 19877, -1, 19579, 19878, 19876, -1, 19579, 19581, 19878, -1, 19577, 19579, 19877, -1, 19575, 19577, 19877, -1, 19574, 19575, 19877, -1, 19879, 19878, 19581, -1, 19876, 19878, 19879, -1, 19880, 19876, 19879, -1, 19877, 19876, 19880, -1, 19881, 19880, 19882, -1, 19883, 19877, 19880, -1, 19883, 19880, 19881, -1, 19884, 19877, 19883, -1, 19881, 19885, 19886, -1, 19881, 19882, 19885, -1, 19883, 19886, 19887, -1, 19883, 19881, 19886, -1, 19884, 19887, 19888, -1, 19884, 19883, 19887, -1, 19889, 19888, 19887, -1, 19889, 19887, 19886, -1, 19889, 19886, 19885, -1, 19890, 19891, 19892, -1, 19893, 19889, 19894, -1, 19895, 19889, 19893, -1, 19896, 19894, 19897, -1, 19896, 19893, 19894, -1, 19898, 19287, 19888, -1, 19898, 19889, 19895, -1, 19898, 19888, 19889, -1, 19899, 19895, 19893, -1, 19899, 19893, 19896, -1, 19900, 19897, 19891, -1, 19900, 19896, 19897, -1, 19900, 19891, 19890, -1, 19901, 19286, 19287, -1, 19901, 19895, 19899, -1, 19901, 19287, 19898, -1, 19901, 19898, 19895, -1, 19902, 19890, 19903, -1, 19902, 19900, 19890, -1, 19902, 19899, 19896, -1, 19902, 19896, 19900, -1, 19904, 19284, 19286, -1, 19904, 19285, 19284, -1, 19904, 19903, 19285, -1, 19904, 19286, 19901, -1, 19904, 19899, 19902, -1, 19904, 19902, 19903, -1, 19904, 19901, 19899, -1, 19205, 19905, 19207, -1, 19207, 19905, 19906, -1, 19906, 19905, 19907, -1, 19907, 19908, 18737, -1, 19905, 19908, 19907, -1, 19908, 18738, 18737, -1, 19200, 19909, 19201, -1, 19201, 19909, 19910, -1, 19910, 19911, 19912, -1, 19909, 19911, 19910, -1, 19912, 19913, 19914, -1, 19911, 19913, 19912, -1, 19914, 19915, 19916, -1, 19913, 19915, 19914, -1, 19917, 19918, 19919, -1, 19916, 19918, 19917, -1, 19915, 19918, 19916, -1, 19918, 19920, 19919, -1, 19919, 19921, 18857, -1, 19920, 19921, 19919, -1, 19921, 19922, 18857, -1, 19922, 18911, 18857, -1, 19922, 18912, 18911, -1, 19921, 18912, 19922, -1, 19920, 18912, 19921, -1, 19196, 19923, 19198, -1, 19198, 19923, 19924, -1, 19924, 19923, 19925, -1, 19925, 19926, 18724, -1, 19923, 19926, 19925, -1, 19926, 18725, 18724, -1, 19191, 19927, 19192, -1, 19192, 19927, 19928, -1, 19928, 19929, 19930, -1, 19927, 19929, 19928, -1, 19930, 19931, 19932, -1, 19929, 19931, 19930, -1, 19932, 19933, 19934, -1, 19931, 19933, 19932, -1, 19935, 19936, 19937, -1, 19934, 19936, 19935, -1, 19933, 19936, 19934, -1, 19936, 19938, 19937, -1, 19937, 19939, 18991, -1, 19938, 19939, 19937, -1, 19939, 19940, 18991, -1, 19940, 18992, 18991, -1, 19940, 18996, 18992, -1, 19939, 18996, 19940, -1, 19938, 18996, 19939, -1, 19187, 19941, 19189, -1, 19189, 19941, 19942, -1, 19942, 19941, 19943, -1, 19943, 19944, 18711, -1, 19941, 19944, 19943, -1, 19944, 18712, 18711, -1, 19182, 19945, 19183, -1, 19183, 19945, 19946, -1, 19946, 19947, 19948, -1, 19945, 19947, 19946, -1, 19948, 19949, 19950, -1, 19947, 19949, 19948, -1, 19950, 19951, 19952, -1, 19949, 19951, 19950, -1, 19953, 19954, 19955, -1, 19952, 19954, 19953, -1, 19951, 19954, 19952, -1, 19954, 19956, 19955, -1, 19955, 19957, 18984, -1, 19956, 19957, 19955, -1, 19957, 19958, 18984, -1, 19958, 18985, 18984, -1, 19958, 18990, 18985, -1, 19957, 18990, 19958, -1, 19956, 18990, 19957, -1, 19178, 19959, 19180, -1, 19180, 19959, 19960, -1, 19960, 19959, 19961, -1, 19961, 19962, 18698, -1, 19959, 19962, 19961, -1, 19962, 18699, 18698, -1, 19173, 19963, 19174, -1, 19174, 19963, 19964, -1, 19964, 19965, 19966, -1, 19963, 19965, 19964, -1, 19966, 19967, 19968, -1, 19965, 19967, 19966, -1, 19968, 19969, 19970, -1, 19967, 19969, 19968, -1, 19971, 19972, 19973, -1, 19970, 19972, 19971, -1, 19969, 19972, 19970, -1, 19972, 19974, 19973, -1, 19973, 19975, 18978, -1, 19974, 19975, 19973, -1, 19975, 19976, 18978, -1, 19976, 18979, 18978, -1, 19976, 18983, 18979, -1, 19975, 18983, 19976, -1, 19974, 18983, 19975, -1, 19169, 19977, 19171, -1, 19171, 19977, 19978, -1, 19978, 19977, 19979, -1, 19979, 19980, 18685, -1, 19977, 19980, 19979, -1, 19980, 18686, 18685, -1, 19164, 19981, 19165, -1, 19165, 19981, 19982, -1, 19982, 19983, 19984, -1, 19981, 19983, 19982, -1, 19984, 19985, 19986, -1, 19983, 19985, 19984, -1, 19986, 19987, 19988, -1, 19985, 19987, 19986, -1, 19989, 19990, 19991, -1, 19988, 19990, 19989, -1, 19987, 19990, 19988, -1, 19990, 19992, 19991, -1, 19991, 19993, 18929, -1, 19992, 19993, 19991, -1, 19993, 19994, 18929, -1, 19994, 18974, 18929, -1, 19994, 18977, 18974, -1, 19993, 18977, 19994, -1, 19992, 18977, 19993, -1, 19142, 19995, 19144, -1, 19144, 19995, 19996, -1, 19996, 19995, 19997, -1, 19997, 19998, 18672, -1, 19995, 19998, 19997, -1, 19998, 18673, 18672, -1, 19137, 19999, 19138, -1, 19138, 19999, 20000, -1, 20000, 20001, 20002, -1, 19999, 20001, 20000, -1, 20002, 20003, 20004, -1, 20001, 20003, 20002, -1, 20004, 20005, 20006, -1, 20003, 20005, 20004, -1, 20007, 20008, 20009, -1, 20006, 20008, 20007, -1, 20005, 20008, 20006, -1, 20008, 20010, 20009, -1, 20009, 20011, 18957, -1, 20010, 20011, 20009, -1, 20011, 20012, 18957, -1, 20012, 18958, 18957, -1, 20012, 18962, 18958, -1, 20011, 18962, 20012, -1, 20010, 18962, 20011, -1, 19129, 20013, 19130, -1, 19130, 20013, 20014, -1, 20014, 20015, 20016, -1, 20013, 20015, 20014, -1, 20016, 20017, 20018, -1, 20015, 20017, 20016, -1, 20018, 20019, 20020, -1, 20017, 20019, 20018, -1, 20021, 20022, 20023, -1, 20020, 20022, 20021, -1, 20019, 20022, 20020, -1, 20022, 20024, 20023, -1, 20023, 20025, 18952, -1, 20024, 20025, 20023, -1, 20025, 20026, 18952, -1, 20026, 18953, 18952, -1, 20026, 18956, 18953, -1, 20025, 18956, 20026, -1, 20024, 18956, 20025, -1, 20027, 18967, 20028, -1, 20028, 18967, 20029, -1, 20029, 18967, 18964, -1, 19146, 20030, 19147, -1, 19147, 20030, 20031, -1, 20031, 20032, 20033, -1, 20030, 20032, 20031, -1, 20033, 20034, 20035, -1, 20032, 20034, 20033, -1, 20035, 20036, 20037, -1, 20034, 20036, 20035, -1, 20037, 20038, 20039, -1, 20039, 20038, 20040, -1, 20036, 20038, 20037, -1, 20038, 20027, 20040, -1, 20040, 20028, 18963, -1, 20027, 20028, 20040, -1, 20028, 20029, 18963, -1, 20029, 18964, 18963, -1, 19151, 20041, 19153, -1, 19153, 20041, 20042, -1, 20042, 20041, 20043, -1, 20043, 20044, 18659, -1, 20041, 20044, 20043, -1, 20044, 18660, 18659, -1, 20045, 20046, 20047, -1, 20047, 20046, 20048, -1, 20048, 20046, 20049, -1, 20049, 20050, 20051, -1, 20046, 20050, 20049, -1, 20045, 20050, 20046, -1, 20052, 20053, 20045, -1, 20045, 20053, 20050, -1, 20050, 20053, 20051, -1, 20051, 20054, 20055, -1, 20053, 20054, 20051, -1, 20052, 20054, 20053, -1, 20056, 20057, 20058, -1, 20055, 20059, 20060, -1, 20054, 20059, 20055, -1, 20052, 20059, 20054, -1, 20061, 20062, 20052, -1, 20052, 20062, 20059, -1, 20059, 20062, 20060, -1, 20060, 20063, 20064, -1, 20062, 20063, 20060, -1, 20061, 20063, 20062, -1, 20065, 20066, 20067, -1, 20063, 20066, 20064, -1, 20067, 20066, 20061, -1, 20061, 20066, 20063, -1, 20064, 20068, 20069, -1, 20070, 20068, 20071, -1, 20071, 20068, 20072, -1, 20072, 20068, 20073, -1, 20073, 20068, 20065, -1, 20066, 20068, 20064, -1, 20065, 20068, 20066, -1, 20069, 20074, 20075, -1, 20075, 20074, 20076, -1, 20076, 20074, 20070, -1, 20070, 20074, 20068, -1, 20068, 20074, 20069, -1, 20077, 20078, 20079, -1, 20078, 20047, 20079, -1, 20061, 20080, 20067, -1, 20080, 20081, 20067, -1, 20081, 20082, 20067, -1, 20083, 20084, 20085, -1, 20085, 20084, 20086, -1, 20086, 20084, 20056, -1, 20056, 20084, 20057, -1, 20057, 20087, 20088, -1, 20084, 20087, 20057, -1, 20083, 20087, 20084, -1, 20079, 20089, 20083, -1, 20087, 20089, 20088, -1, 20083, 20089, 20087, -1, 20088, 20090, 20091, -1, 20079, 20090, 20089, -1, 20047, 20090, 20079, -1, 20089, 20090, 20088, -1, 20091, 20048, 20049, -1, 20047, 20048, 20090, -1, 20090, 20048, 20091, -1, 20092, 20078, 20077, -1, 20093, 20078, 20092, -1, 20094, 20047, 20093, -1, 20093, 20047, 20078, -1, 20095, 20045, 20094, -1, 20094, 20045, 20047, -1, 20095, 20052, 20045, -1, 20096, 20061, 20095, -1, 20095, 20061, 20052, -1, 20096, 20080, 20061, -1, 20097, 20081, 20096, -1, 20096, 20081, 20080, -1, 20097, 20082, 20081, -1, 20098, 20099, 20100, -1, 20100, 20099, 20101, -1, 20102, 20103, 20098, -1, 20098, 20103, 20099, -1, 20091, 20103, 20102, -1, 20104, 20105, 20106, -1, 20101, 20105, 20104, -1, 20107, 20108, 20109, -1, 20049, 20110, 20091, -1, 20091, 20110, 20103, -1, 20101, 20111, 20105, -1, 20099, 20111, 20101, -1, 20103, 20112, 20099, -1, 20099, 20112, 20111, -1, 20106, 20113, 20114, -1, 20105, 20113, 20106, -1, 20051, 20115, 20049, -1, 20049, 20115, 20110, -1, 20110, 20115, 20103, -1, 20103, 20115, 20112, -1, 20058, 20057, 20116, -1, 20105, 20117, 20113, -1, 20116, 20057, 20118, -1, 20118, 20057, 20119, -1, 20111, 20117, 20105, -1, 20119, 20057, 20120, -1, 20111, 20121, 20117, -1, 20112, 20121, 20111, -1, 20114, 20122, 20123, -1, 20113, 20122, 20114, -1, 20115, 20124, 20112, -1, 20060, 20124, 20055, -1, 20055, 20124, 20051, -1, 20112, 20124, 20121, -1, 20051, 20124, 20115, -1, 20117, 20125, 20113, -1, 20113, 20125, 20122, -1, 20121, 20126, 20117, -1, 20117, 20126, 20125, -1, 20123, 20127, 20128, -1, 20122, 20127, 20123, -1, 20121, 20129, 20126, -1, 20060, 20129, 20124, -1, 20064, 20129, 20060, -1, 20124, 20129, 20121, -1, 20125, 20130, 20122, -1, 20122, 20130, 20127, -1, 20126, 20131, 20125, -1, 20125, 20131, 20130, -1, 20129, 20132, 20126, -1, 20069, 20132, 20064, -1, 20064, 20132, 20129, -1, 20126, 20132, 20131, -1, 20131, 20132, 20069, -1, 20128, 20133, 20134, -1, 20134, 20133, 20135, -1, 20135, 20133, 20136, -1, 20127, 20133, 20128, -1, 20136, 20137, 20138, -1, 20130, 20137, 20127, -1, 20127, 20137, 20133, -1, 20133, 20137, 20136, -1, 20138, 20139, 20140, -1, 20140, 20139, 20141, -1, 20141, 20139, 20075, -1, 20075, 20139, 20069, -1, 20130, 20139, 20137, -1, 20069, 20139, 20131, -1, 20131, 20139, 20130, -1, 20137, 20139, 20138, -1, 20142, 20143, 20107, -1, 20107, 20143, 20108, -1, 20120, 20144, 20142, -1, 20142, 20144, 20143, -1, 20088, 20145, 20057, -1, 20120, 20145, 20144, -1, 20057, 20145, 20120, -1, 20108, 20100, 20146, -1, 20143, 20100, 20108, -1, 20143, 20098, 20100, -1, 20144, 20098, 20143, -1, 20144, 20102, 20098, -1, 20088, 20102, 20145, -1, 20145, 20102, 20144, -1, 20146, 20101, 20104, -1, 20100, 20101, 20146, -1, 20091, 20147, 20088, -1, 20102, 20147, 20091, -1, 20088, 20147, 20102, -1, 20148, 20149, 20150, -1, 20151, 20152, 20149, -1, 20153, 20152, 20151, -1, 18304, 18302, 20154, -1, 20155, 20156, 20157, -1, 20155, 20157, 20152, -1, 20154, 18306, 18304, -1, 20155, 20152, 20153, -1, 20155, 20153, 20158, -1, 18302, 18300, 20154, -1, 20155, 18308, 20154, -1, 20154, 18308, 18306, -1, 18300, 18298, 20154, -1, 20155, 18310, 18308, -1, 20155, 20159, 18310, -1, 20155, 20160, 20159, -1, 20155, 20161, 20160, -1, 20155, 20162, 20161, -1, 20155, 20158, 20162, -1, 20163, 20164, 18284, -1, 18284, 20164, 18285, -1, 18285, 20164, 18288, -1, 18288, 20164, 18290, -1, 18290, 20164, 18292, -1, 18292, 20164, 18294, -1, 18294, 20164, 18296, -1, 18296, 20164, 18298, -1, 18298, 20164, 20154, -1, 20165, 20166, 20167, -1, 20167, 20166, 20168, -1, 20168, 20166, 20163, -1, 20163, 20166, 20164, -1, 20148, 20150, 20165, -1, 20165, 20150, 20166, -1, 20151, 20149, 20148, -1, 20169, 20170, 20171, -1, 20172, 20173, 20169, -1, 20169, 20173, 20170, -1, 20174, 20175, 20172, -1, 20172, 20175, 20173, -1, 20176, 20177, 20174, -1, 20174, 20177, 20175, -1, 20178, 20179, 20176, -1, 20176, 20179, 20177, -1, 20180, 20181, 20182, -1, 20182, 20181, 20183, -1, 20182, 20183, 20178, -1, 20178, 20183, 20179, -1, 18658, 18657, 20184, -1, 18657, 20185, 20184, -1, 20184, 20186, 20187, -1, 20185, 20186, 20184, -1, 20187, 20188, 20189, -1, 20186, 20188, 20187, -1, 20189, 20190, 20191, -1, 20188, 20190, 20189, -1, 20191, 20192, 20193, -1, 20190, 20192, 20191, -1, 20193, 20194, 20195, -1, 20192, 20194, 20193, -1, 20195, 20196, 20197, -1, 20194, 20196, 20195, -1, 20197, 20198, 20199, -1, 20196, 20198, 20197, -1, 20199, 20200, 20201, -1, 20198, 20200, 20199, -1, 20201, 20202, 20203, -1, 20200, 20202, 20201, -1, 20203, 20204, 20205, -1, 20202, 20204, 20203, -1, 20205, 20206, 20207, -1, 20204, 20206, 20205, -1, 20207, 18632, 18631, -1, 20206, 18632, 20207, -1, 18629, 20208, 18630, -1, 20209, 20208, 20210, -1, 18630, 20208, 20209, -1, 20210, 20211, 20212, -1, 20208, 20211, 20210, -1, 20212, 20213, 20214, -1, 20211, 20213, 20212, -1, 20214, 20215, 20216, -1, 20213, 20215, 20214, -1, 20216, 20217, 20218, -1, 20215, 20217, 20216, -1, 20218, 20219, 20220, -1, 20217, 20219, 20218, -1, 20220, 20221, 20222, -1, 20219, 20221, 20220, -1, 20222, 20223, 20224, -1, 20221, 20223, 20222, -1, 20224, 20225, 20226, -1, 20223, 20225, 20224, -1, 20226, 20227, 20228, -1, 20225, 20227, 20226, -1, 20228, 20229, 20230, -1, 20227, 20229, 20228, -1, 20230, 20231, 18603, -1, 20229, 20231, 20230, -1, 20231, 18604, 18603, -1, 17846, 17847, 20232, -1, 17847, 20233, 20232, -1, 18563, 20234, 18565, -1, 20234, 20235, 18565, -1, 20236, 20237, 20233, -1, 20233, 20237, 20232, -1, 20238, 20239, 20236, -1, 20240, 20239, 20238, -1, 18565, 20239, 20240, -1, 20241, 20239, 20235, -1, 20242, 20239, 20241, -1, 20243, 20239, 20242, -1, 20244, 20239, 20243, -1, 20236, 20239, 20237, -1, 20235, 20239, 18565, -1, 20245, 20239, 20246, -1, 20246, 20239, 20244, -1, 20247, 20248, 20249, -1, 20250, 20251, 20249, -1, 20249, 20251, 20247, -1, 20252, 20253, 20250, -1, 20250, 20253, 20251, -1, 20248, 20254, 20249, -1, 20252, 20255, 20253, -1, 20252, 20256, 20255, -1, 20252, 20257, 20256, -1, 20252, 20258, 20257, -1, 20252, 20259, 20258, -1, 20170, 20260, 20171, -1, 20170, 20261, 20260, -1, 20262, 20263, 20264, -1, 17862, 20262, 20264, -1, 17865, 17862, 20264, -1, 17868, 17865, 20264, -1, 17870, 17868, 20264, -1, 17873, 17870, 20264, -1, 17875, 17873, 20264, -1, 20265, 20264, 20266, -1, 20265, 20266, 20267, -1, 20268, 20264, 20265, -1, 20269, 20264, 20268, -1, 20270, 20264, 20269, -1, 20271, 17875, 20264, -1, 20271, 20264, 20270, -1, 20272, 17875, 20271, -1, 20273, 17875, 20272, -1, 20274, 17875, 20273, -1, 20275, 17875, 20274, -1, 20276, 17875, 20275, -1, 20277, 20276, 20278, -1, 20277, 17875, 20276, -1, 20279, 20280, 20281, -1, 20279, 20281, 20282, -1, 20283, 20284, 20285, -1, 20283, 20285, 20286, -1, 20287, 20288, 20289, -1, 20290, 20291, 20292, -1, 20293, 20291, 20290, -1, 17678, 20294, 20295, -1, 20296, 20294, 20297, -1, 20295, 20294, 20296, -1, 20293, 20298, 20291, -1, 20293, 20299, 20298, -1, 20300, 20301, 20302, -1, 20303, 20301, 20300, -1, 20297, 20301, 20303, -1, 20293, 20304, 20299, -1, 20294, 20301, 20297, -1, 20304, 20305, 20299, -1, 20293, 20306, 20304, -1, 20307, 20308, 20288, -1, 20305, 20309, 20299, -1, 20293, 20310, 20306, -1, 20309, 20311, 20299, -1, 20311, 20312, 20299, -1, 20295, 20313, 20293, -1, 20293, 20313, 20310, -1, 20311, 20314, 20312, -1, 20315, 20316, 20308, -1, 20317, 20316, 20315, -1, 20318, 20316, 20317, -1, 20319, 20316, 20318, -1, 20320, 20316, 20319, -1, 20314, 20321, 20312, -1, 20308, 20316, 20288, -1, 20322, 20323, 20295, -1, 20320, 20324, 20316, -1, 20325, 20326, 20327, -1, 20328, 20329, 20330, -1, 20302, 20326, 20325, -1, 20312, 20329, 20328, -1, 20301, 20326, 20302, -1, 20321, 20329, 20312, -1, 20323, 17684, 20295, -1, 20320, 20331, 20324, -1, 20323, 17682, 17684, -1, 20320, 20332, 20331, -1, 20327, 20333, 20320, -1, 17684, 17691, 20295, -1, 20320, 20333, 20332, -1, 20326, 20333, 20327, -1, 20329, 20334, 20330, -1, 17691, 17698, 20295, -1, 17698, 17663, 20295, -1, 17663, 17678, 20295, -1, 20329, 20335, 20334, -1, 20335, 20336, 20334, -1, 20295, 20337, 20313, -1, 20335, 20338, 20336, -1, 20295, 20296, 20337, -1, 20287, 20289, 20335, -1, 20335, 20289, 20338, -1, 20339, 20288, 20287, -1, 20307, 20288, 20339, -1, 20340, 20341, 17528, -1, 19821, 19819, 20342, -1, 17528, 20341, 20343, -1, 20344, 20345, 20346, -1, 20347, 20348, 20349, -1, 20350, 20345, 20344, -1, 20349, 20351, 20347, -1, 19819, 19818, 20342, -1, 20347, 20352, 20348, -1, 20351, 20353, 20347, -1, 20347, 20354, 20352, -1, 20342, 19551, 20355, -1, 20356, 20357, 20358, -1, 20350, 20359, 20345, -1, 19818, 19551, 20342, -1, 20347, 20360, 20354, -1, 20353, 20361, 20347, -1, 20350, 20362, 20359, -1, 20363, 20362, 20350, -1, 20364, 20362, 20363, -1, 20365, 20362, 20364, -1, 17634, 20362, 20365, -1, 17633, 20362, 17634, -1, 20341, 20366, 20367, -1, 20368, 19432, 20340, -1, 20341, 19432, 20366, -1, 20340, 19432, 20341, -1, 20369, 20370, 20371, -1, 20369, 20372, 20370, -1, 20373, 20372, 20369, -1, 20374, 20375, 20376, -1, 20370, 20377, 20371, -1, 20371, 20377, 20378, -1, 20379, 20380, 17489, -1, 20374, 20381, 20375, -1, 20382, 20381, 20374, -1, 19728, 19726, 20383, -1, 17489, 20380, 20384, -1, 20373, 20385, 20372, -1, 20361, 20386, 20347, -1, 20387, 20385, 20373, -1, 20375, 20386, 20376, -1, 20376, 20386, 20361, -1, 20382, 20388, 20381, -1, 20389, 20388, 20382, -1, 19726, 19725, 20383, -1, 20377, 20390, 20378, -1, 20386, 20391, 20347, -1, 20387, 20392, 20385, -1, 20389, 20393, 20388, -1, 20383, 19433, 20394, -1, 19725, 19433, 20383, -1, 20389, 20395, 20393, -1, 20396, 20395, 20389, -1, 20397, 20395, 20396, -1, 20398, 20395, 20397, -1, 20399, 20395, 20398, -1, 20400, 20395, 20399, -1, 20387, 20401, 20392, -1, 20402, 20401, 20387, -1, 20403, 20401, 20402, -1, 20391, 20404, 20347, -1, 20405, 20401, 20403, -1, 17516, 20401, 20405, -1, 17515, 20401, 17516, -1, 20380, 20406, 20407, -1, 20408, 19522, 20379, -1, 20380, 19522, 20406, -1, 20379, 19522, 20380, -1, 20409, 20410, 20411, -1, 20412, 20413, 20409, -1, 20409, 20413, 20410, -1, 19789, 19787, 20414, -1, 20410, 20415, 20411, -1, 20416, 20417, 17541, -1, 20418, 20419, 20420, -1, 17541, 20417, 20421, -1, 20422, 20423, 20412, -1, 19787, 19786, 20414, -1, 20418, 20424, 20419, -1, 20425, 20424, 20418, -1, 20412, 20423, 20413, -1, 20419, 20426, 20420, -1, 20414, 19523, 20427, -1, 20420, 20426, 20404, -1, 20422, 20428, 20423, -1, 19786, 19523, 20414, -1, 20347, 20429, 20360, -1, 20425, 20430, 20424, -1, 20431, 20430, 20425, -1, 20432, 20433, 20422, -1, 20434, 20433, 20432, -1, 20426, 20435, 20404, -1, 20436, 20433, 20434, -1, 17555, 20433, 20436, -1, 17554, 20433, 17555, -1, 20431, 20437, 20430, -1, 20422, 20433, 20428, -1, 20417, 20438, 20439, -1, 20416, 19333, 20417, -1, 20417, 19333, 20438, -1, 20431, 20440, 20437, -1, 20441, 19333, 20416, -1, 20442, 20440, 20431, -1, 20443, 20440, 20442, -1, 20444, 20440, 20443, -1, 17477, 20440, 20444, -1, 17476, 20440, 17477, -1, 20429, 20445, 20446, -1, 20429, 19614, 20445, -1, 20347, 19614, 20429, -1, 20447, 20448, 20449, -1, 20411, 20450, 20451, -1, 20452, 20450, 20415, -1, 20415, 20450, 20411, -1, 20453, 20450, 20452, -1, 20454, 20450, 20453, -1, 20455, 20450, 20454, -1, 20357, 20450, 20358, -1, 20456, 20457, 20447, -1, 20451, 20450, 20357, -1, 20347, 19856, 19614, -1, 20455, 20458, 20450, -1, 20447, 20457, 20448, -1, 20449, 20459, 20460, -1, 20448, 20459, 20449, -1, 20458, 20461, 20450, -1, 17502, 20462, 20463, -1, 20464, 20462, 17502, -1, 20465, 20466, 20456, -1, 20461, 20467, 20450, -1, 19856, 19853, 19614, -1, 20456, 20466, 20457, -1, 19853, 19851, 19614, -1, 19699, 19697, 20468, -1, 20459, 20469, 20460, -1, 19851, 19850, 19614, -1, 20465, 20470, 20466, -1, 19697, 19696, 20468, -1, 19850, 19615, 19614, -1, 20467, 20471, 20450, -1, 20472, 20343, 20465, -1, 20473, 20343, 20472, -1, 20474, 20343, 20473, -1, 17529, 20343, 20474, -1, 17528, 20343, 17529, -1, 20468, 19334, 20475, -1, 19696, 19334, 20468, -1, 20465, 20343, 20470, -1, 20471, 20476, 20450, -1, 20462, 20477, 20478, -1, 20464, 19488, 20462, -1, 20462, 19488, 20477, -1, 20479, 19488, 20464, -1, 20480, 20481, 20482, -1, 20483, 20484, 20480, -1, 20480, 20484, 20481, -1, 19757, 19755, 20485, -1, 17633, 20486, 20362, -1, 20487, 20486, 17633, -1, 20481, 20488, 20482, -1, 20482, 20488, 20489, -1, 20400, 20490, 20395, -1, 20491, 20490, 20400, -1, 19755, 19754, 20485, -1, 20492, 20493, 20483, -1, 20476, 20494, 20450, -1, 17568, 20494, 20476, -1, 17567, 20494, 17568, -1, 20450, 20494, 20495, -1, 20483, 20493, 20484, -1, 20485, 19489, 20496, -1, 19754, 19489, 20485, -1, 20488, 20497, 20489, -1, 20486, 20498, 20499, -1, 20487, 19405, 20486, -1, 20500, 19405, 20487, -1, 20486, 19405, 20498, -1, 20492, 20501, 20493, -1, 20502, 20384, 20492, -1, 20503, 20384, 20502, -1, 20504, 20384, 20503, -1, 17490, 20384, 20504, -1, 19670, 19668, 20505, -1, 17489, 20384, 17490, -1, 20492, 20384, 20501, -1, 20490, 20506, 20507, -1, 19668, 19667, 20505, -1, 20490, 19580, 20506, -1, 20508, 19580, 20491, -1, 20505, 19406, 20509, -1, 20491, 19580, 20490, -1, 19667, 19406, 20505, -1, 20510, 20511, 20512, -1, 20513, 20514, 20510, -1, 20515, 20516, 17554, -1, 20510, 20514, 20511, -1, 17554, 20516, 20433, -1, 20512, 20517, 20518, -1, 20511, 20517, 20512, -1, 17515, 20519, 20401, -1, 20520, 20519, 17515, -1, 19882, 19880, 20521, -1, 20522, 20523, 20513, -1, 20516, 20524, 20525, -1, 20513, 20523, 20514, -1, 20515, 19378, 20516, -1, 20526, 19378, 20515, -1, 20517, 20527, 20518, -1, 20516, 19378, 20524, -1, 19880, 19879, 20521, -1, 19641, 19639, 20528, -1, 20522, 20529, 20523, -1, 20521, 19581, 20530, -1, 19879, 19581, 20521, -1, 20522, 20421, 20529, -1, 20531, 20421, 20522, -1, 19639, 19638, 20528, -1, 20532, 20421, 20531, -1, 20533, 20421, 20532, -1, 17542, 20421, 20533, -1, 17541, 20421, 17542, -1, 20528, 19379, 20534, -1, 19638, 19379, 20528, -1, 20519, 20535, 20536, -1, 20520, 19462, 20519, -1, 20519, 19462, 20535, -1, 20537, 19462, 20520, -1, 20538, 20539, 17567, -1, 20494, 20539, 20540, -1, 17567, 20539, 20494, -1, 20541, 20542, 20543, -1, 20539, 20544, 20545, -1, 20546, 20547, 20541, -1, 20548, 19634, 20538, -1, 20538, 19634, 20539, -1, 20541, 20547, 20542, -1, 20539, 19634, 20544, -1, 20543, 20549, 20550, -1, 20542, 20549, 20543, -1, 20551, 20552, 17476, -1, 18810, 18806, 20553, -1, 20554, 18803, 20548, -1, 20553, 18803, 20554, -1, 17476, 20552, 20440, -1, 20548, 18803, 19634, -1, 20546, 20555, 20547, -1, 20556, 20555, 20546, -1, 18806, 18803, 20553, -1, 20528, 19644, 19641, -1, 19379, 19378, 20534, -1, 20534, 19378, 20526, -1, 20553, 19313, 18810, -1, 20450, 20347, 20527, -1, 20450, 20527, 20358, -1, 20527, 20347, 20518, -1, 20518, 20347, 20469, -1, 20469, 20347, 20460, -1, 20460, 20347, 20390, -1, 20390, 20347, 20378, -1, 20378, 20347, 20557, -1, 20557, 20347, 20550, -1, 19267, 18822, 20558, -1, 20550, 20347, 20497, -1, 20497, 20347, 20489, -1, 20558, 18822, 20559, -1, 20489, 20347, 20435, -1, 19440, 18822, 19267, -1, 20435, 20347, 20404, -1, 20521, 19885, 19882, -1, 19581, 19580, 20530, -1, 19440, 19443, 18822, -1, 20530, 19580, 20508, -1, 20549, 20557, 20550, -1, 20342, 19824, 19821, -1, 19551, 19550, 20355, -1, 20556, 20560, 20555, -1, 20355, 19550, 20561, -1, 20414, 19792, 19789, -1, 19443, 18823, 18822, -1, 19523, 19522, 20427, -1, 20427, 19522, 20408, -1, 20485, 19760, 19757, -1, 19489, 19488, 20496, -1, 20496, 19488, 20479, -1, 20558, 19265, 19267, -1, 18822, 19462, 20559, -1, 20559, 19462, 20537, -1, 20383, 19731, 19728, -1, 19433, 19432, 20394, -1, 20394, 19432, 20368, -1, 20468, 19702, 19699, -1, 19334, 19333, 20475, -1, 20475, 19333, 20441, -1, 20505, 19673, 19670, -1, 19406, 19405, 20509, -1, 20509, 19405, 20500, -1, 20556, 20463, 20560, -1, 20562, 20463, 20556, -1, 20563, 20463, 20562, -1, 20564, 20463, 20563, -1, 17503, 20463, 20564, -1, 17502, 20463, 17503, -1, 20552, 20565, 20566, -1, 20561, 19550, 20551, -1, 20552, 19550, 20565, -1, 20551, 19550, 20552, -1, 20567, 20568, 20569, -1, 20567, 20346, 20568, -1, 20344, 20346, 20567, -1, 20568, 20356, 20569, -1, 20569, 20356, 20358, -1, 20570, 20571, 20572, -1, 20573, 20570, 20572, -1, 20574, 20573, 20572, -1, 20575, 20574, 20572, -1, 20576, 20572, 17669, -1, 20576, 20575, 20572, -1, 20577, 20576, 17669, -1, 20578, 20577, 17669, -1, 20579, 20578, 17669, -1, 20580, 20579, 17669, -1, 20581, 20097, 20582, -1, 20581, 20583, 20082, -1, 20581, 20082, 20097, -1, 17669, 20581, 20580, -1, 20580, 20581, 20584, -1, 20584, 20581, 20585, -1, 20585, 20581, 20582, -1, 20586, 20587, 20588, -1, 20586, 20589, 20587, -1, 20589, 20590, 20587, -1, 20591, 20592, 20590, -1, 20593, 20592, 20591, -1, 20590, 20592, 20587, -1, 20592, 20594, 20587, -1, 20592, 20595, 20594, -1, 20595, 20596, 20594, -1, 20597, 20598, 20599, -1, 20598, 20600, 20599, -1, 20598, 20601, 20600, -1, 17649, 17646, 20601, -1, 20598, 17652, 20601, -1, 20601, 17652, 17649, -1, 17646, 17645, 20601, -1, 17645, 20602, 20601, -1, 20602, 20603, 20601, -1, 20603, 20604, 20601, -1, 20605, 20606, 20607, -1, 20606, 20608, 20607, -1, 20608, 20609, 20607, -1, 20609, 20610, 20607, -1, 20610, 20611, 20607, -1, 20611, 20612, 20607, -1, 20612, 20613, 20607, -1, 20613, 20614, 20607, -1, 20607, 20615, 20598, -1, 20598, 20615, 17652, -1, 20607, 20616, 20615, -1, 20607, 20617, 20616, -1, 20607, 20618, 20617, -1, 20607, 20619, 20618, -1, 20614, 20620, 20607, -1, 20607, 20620, 20619, -1, 20614, 20621, 20620, -1, 20614, 20622, 20621, -1, 20614, 20623, 20622, -1, 20614, 20624, 20623, -1, 20604, 20625, 20601, -1, 20604, 20626, 20625, -1, 20614, 17883, 20624, -1, 20624, 17883, 17885, -1, 20627, 20628, 20629, -1, 20630, 20631, 20632, -1, 20633, 20634, 20635, -1, 20636, 20634, 20633, -1, 20637, 20634, 20636, -1, 20638, 20634, 20637, -1, 20639, 20634, 20638, -1, 20631, 20634, 20639, -1, 20630, 20634, 20631, -1, 20640, 20641, 20642, -1, 20643, 20641, 20640, -1, 20642, 20644, 20540, -1, 20641, 20644, 20642, -1, 20645, 20646, 20643, -1, 20643, 20646, 20641, -1, 20644, 20647, 20540, -1, 20648, 20649, 20645, -1, 20650, 20649, 20648, -1, 20645, 20649, 20646, -1, 20647, 20651, 20540, -1, 20652, 20322, 20650, -1, 20653, 20322, 20652, -1, 20654, 20322, 20653, -1, 20650, 20322, 20649, -1, 20651, 20494, 20540, -1, 20654, 20655, 20322, -1, 20655, 20323, 20322, -1, 20656, 20657, 20264, -1, 20658, 20659, 20660, -1, 20661, 20659, 20658, -1, 20662, 20659, 20661, -1, 20264, 20663, 20266, -1, 20664, 20659, 20662, -1, 20665, 20659, 20664, -1, 20666, 20659, 20665, -1, 20657, 20663, 20264, -1, 20667, 20659, 20666, -1, 20657, 20659, 20668, -1, 20657, 20668, 20669, -1, 20668, 20659, 20670, -1, 20670, 20659, 20671, -1, 20657, 20672, 20663, -1, 20671, 20659, 20673, -1, 20671, 20673, 20674, -1, 20671, 20674, 20675, -1, 20673, 20659, 20667, -1, 20657, 20676, 20672, -1, 20657, 20677, 20676, -1, 20657, 20678, 20677, -1, 20657, 20679, 20678, -1, 20657, 20669, 20679, -1, 20261, 20680, 20260, -1, 20681, 20680, 20261, -1, 20682, 20683, 20681, -1, 20681, 20683, 20680, -1, 20684, 20685, 20682, -1, 20682, 20685, 20683, -1, 20686, 20687, 20684, -1, 20684, 20687, 20685, -1, 20671, 20688, 20686, -1, 20686, 20688, 20687, -1, 20671, 20675, 20688, -1, 20689, 20690, 20691, -1, 20691, 20692, 20689, -1, 20690, 20693, 20691, -1, 20694, 20695, 20691, -1, 20691, 20695, 20692, -1, 20693, 20696, 20691, -1, 20694, 17934, 20695, -1, 20696, 20697, 20691, -1, 20694, 17935, 17934, -1, 20694, 17938, 17935, -1, 20694, 17940, 17938, -1, 20694, 17942, 17940, -1, 20694, 17944, 17942, -1, 20694, 17946, 17944, -1, 20698, 20699, 20697, -1, 20700, 20699, 20698, -1, 20701, 20699, 20700, -1, 20702, 20699, 20701, -1, 20703, 20699, 20702, -1, 20704, 20699, 20703, -1, 20705, 20699, 20704, -1, 20706, 20699, 20705, -1, 20697, 20699, 20691, -1, 20707, 20708, 20706, -1, 20709, 20708, 20707, -1, 20710, 20708, 20709, -1, 20711, 20708, 20710, -1, 20712, 20708, 20711, -1, 20713, 20708, 20712, -1, 20706, 20708, 20699, -1, 20694, 20708, 17946, -1, 17946, 20708, 20713, -1, 20714, 20715, 20716, -1, 20716, 20717, 20714, -1, 20715, 20718, 20716, -1, 20719, 20720, 20721, -1, 20722, 20720, 20719, -1, 20716, 20723, 20717, -1, 20724, 20720, 20722, -1, 20725, 20720, 20724, -1, 20726, 20720, 20725, -1, 20727, 20720, 20726, -1, 20716, 17916, 20723, -1, 20716, 17919, 17916, -1, 17933, 20728, 20729, -1, 20729, 20728, 20727, -1, 20727, 20728, 20720, -1, 20716, 17920, 17919, -1, 20720, 20728, 20730, -1, 17920, 20731, 17923, -1, 20716, 20731, 17920, -1, 20728, 20732, 20730, -1, 20731, 17925, 17923, -1, 20733, 20732, 20728, -1, 20730, 20732, 20734, -1, 20731, 20728, 17933, -1, 20731, 17927, 17925, -1, 20731, 17929, 17927, -1, 20731, 17931, 17929, -1, 20731, 17933, 17931, -1, 20718, 20735, 20716, -1, 20735, 20736, 20716, -1, 20737, 20738, 20739, -1, 20740, 20741, 20737, -1, 20736, 20741, 20740, -1, 20737, 20741, 20738, -1, 20736, 20742, 20741, -1, 20735, 20743, 20736, -1, 20736, 20744, 20742, -1, 20736, 20745, 20744, -1, 20736, 20721, 20745, -1, 20743, 20746, 20736, -1, 20746, 20747, 20736, -1, 20736, 20748, 20721, -1, 20747, 20748, 20736, -1, 20748, 20749, 20721, -1, 20749, 20750, 20721, -1, 20750, 20719, 20721, -1, 20751, 20752, 20753, -1, 20754, 20752, 20751, -1, 20755, 20752, 20754, -1, 20756, 20752, 20755, -1, 20756, 20757, 20752, -1, 20757, 20758, 20752, -1, 20758, 17741, 20752, -1, 17741, 20283, 20752, -1, 18610, 18612, 20283, -1, 20283, 18608, 18610, -1, 18612, 18614, 20283, -1, 20283, 18605, 18608, -1, 18614, 18616, 20283, -1, 18616, 18618, 20283, -1, 18605, 17740, 18603, -1, 17741, 17740, 20283, -1, 20283, 17740, 18605, -1, 17740, 20230, 18603, -1, 18618, 18620, 20283, -1, 17740, 20228, 20230, -1, 20759, 20760, 17740, -1, 17740, 20226, 20228, -1, 17740, 20224, 20226, -1, 20224, 20761, 20222, -1, 20760, 20761, 17740, -1, 17740, 20761, 20224, -1, 20762, 20761, 20760, -1, 20763, 20761, 20762, -1, 20761, 20220, 20222, -1, 20761, 20218, 20220, -1, 20761, 20216, 20218, -1, 18630, 20284, 18628, -1, 18628, 20284, 18626, -1, 18626, 20284, 18624, -1, 18624, 20284, 18622, -1, 18622, 20284, 18620, -1, 20210, 20284, 20209, -1, 20209, 20284, 18630, -1, 20216, 20764, 20214, -1, 20214, 20764, 20212, -1, 20212, 20764, 20210, -1, 20761, 20764, 20216, -1, 20210, 20764, 20284, -1, 20761, 20765, 20764, -1, 20761, 20766, 20765, -1, 20761, 20767, 20766, -1, 20761, 20768, 20767, -1, 20761, 20769, 20768, -1, 20770, 20280, 20279, -1, 20771, 20280, 20770, -1, 20772, 20280, 20771, -1, 20772, 20773, 20280, -1, 20774, 20773, 20772, -1, 20775, 20773, 20774, -1, 20775, 20776, 20773, -1, 20777, 20776, 20775, -1, 20777, 20778, 20776, -1, 20779, 20778, 20777, -1, 20779, 20780, 20778, -1, 20781, 20780, 20779, -1, 20782, 18637, 20277, -1, 18637, 18639, 20277, -1, 20782, 18635, 18637, -1, 18639, 18641, 20277, -1, 20782, 18633, 18635, -1, 18641, 18643, 20277, -1, 20782, 18631, 18633, -1, 20783, 18631, 20782, -1, 18643, 18645, 20277, -1, 20783, 20207, 18631, -1, 20784, 20207, 20783, -1, 20784, 20205, 20207, -1, 20785, 20205, 20784, -1, 20785, 20203, 20205, -1, 20786, 20203, 20785, -1, 20787, 20201, 20786, -1, 20786, 20201, 20203, -1, 20788, 20199, 20787, -1, 20787, 20199, 20201, -1, 18658, 17875, 18655, -1, 18655, 17875, 18653, -1, 18653, 17875, 18651, -1, 18651, 17875, 18649, -1, 18649, 17875, 18647, -1, 18647, 17875, 18645, -1, 20189, 17875, 20187, -1, 20187, 17875, 20184, -1, 20184, 17875, 18658, -1, 18645, 17875, 20277, -1, 20199, 17876, 20197, -1, 20197, 17876, 20195, -1, 20195, 17876, 20193, -1, 20193, 17876, 20191, -1, 20191, 17876, 20189, -1, 20189, 17876, 17875, -1, 20789, 17876, 20788, -1, 20788, 17876, 20199, -1, 20284, 20283, 18620, -1, 20761, 17876, 20769, -1, 20769, 17876, 20781, -1, 20781, 17876, 20790, -1, 20781, 20790, 20791, -1, 20781, 20791, 20780, -1, 20790, 17876, 20789, -1, 20164, 20660, 20154, -1, 20164, 20658, 20660, -1, 20792, 17733, 20793, -1, 20793, 17735, 20794, -1, 17733, 17735, 20793, -1, 20795, 17731, 20792, -1, 20792, 17731, 17733, -1, 20794, 17737, 20796, -1, 17735, 17737, 20794, -1, 20797, 17726, 20795, -1, 20795, 17726, 17731, -1, 20798, 17727, 20797, -1, 20752, 17727, 20798, -1, 20797, 17727, 17726, -1, 20283, 20286, 20752, -1, 20752, 20286, 17727, -1, 17739, 17886, 20796, -1, 17739, 20796, 17737, -1, 20799, 17703, 20800, -1, 20800, 17703, 20801, -1, 20801, 17703, 20802, -1, 20802, 17703, 20803, -1, 20803, 17703, 20804, -1, 20804, 17703, 20805, -1, 20805, 17703, 20806, -1, 20806, 17703, 18312, -1, 20807, 17703, 20808, -1, 20808, 17703, 20799, -1, 18312, 17703, 20265, -1, 20809, 17703, 20810, -1, 20810, 17703, 20807, -1, 18332, 18330, 20267, -1, 20267, 18334, 18332, -1, 18330, 18328, 20267, -1, 20811, 18336, 20267, -1, 20267, 18336, 18334, -1, 20811, 18339, 18336, -1, 20811, 20812, 18339, -1, 20811, 20813, 20812, -1, 20814, 20815, 20811, -1, 20811, 20815, 20813, -1, 20808, 20816, 20817, -1, 20817, 20816, 20814, -1, 20814, 20816, 20815, -1, 20808, 20799, 20816, -1, 18313, 20265, 18316, -1, 18316, 20265, 18318, -1, 18318, 20265, 18320, -1, 18320, 20265, 18322, -1, 18322, 20265, 18324, -1, 18324, 20265, 18326, -1, 18326, 20265, 18328, -1, 18328, 20265, 20267, -1, 18313, 18312, 20265, -1, 18549, 18573, 20276, -1, 20276, 18547, 18549, -1, 18573, 18571, 20276, -1, 20276, 18550, 18547, -1, 18571, 18569, 20276, -1, 20276, 18552, 18550, -1, 18569, 18568, 20276, -1, 20276, 20818, 18552, -1, 20276, 20819, 20818, -1, 18568, 20278, 20276, -1, 18559, 20278, 18561, -1, 18561, 20278, 18567, -1, 18567, 20278, 18568, -1, 20276, 20820, 20819, -1, 20819, 20820, 20821, -1, 20821, 20820, 20822, -1, 20822, 20820, 20823, -1, 20823, 20820, 20824, -1, 20824, 20820, 20825, -1, 20825, 20820, 20826, -1, 20826, 20820, 20827, -1, 18559, 20828, 20278, -1, 18553, 20828, 18554, -1, 18554, 20828, 18557, -1, 18557, 20828, 18559, -1, 18553, 20829, 20828, -1, 20830, 20829, 18553, -1, 20831, 20832, 20830, -1, 20830, 20832, 20829, -1, 20833, 20834, 20831, -1, 20831, 20834, 20832, -1, 20827, 20835, 20833, -1, 20833, 20835, 20834, -1, 20820, 20836, 20827, -1, 20827, 20836, 20835, -1, 20820, 20837, 20836, -1, 20820, 20838, 20837, -1, 17727, 20839, 17728, -1, 17727, 20840, 20839, -1, 17727, 20841, 20840, -1, 17727, 20842, 20841, -1, 17727, 20843, 20842, -1, 17727, 20844, 20843, -1, 17727, 20845, 20844, -1, 17727, 20846, 20845, -1, 17727, 20286, 20846, -1, 18596, 18594, 20285, -1, 20285, 18598, 18596, -1, 18594, 18592, 20285, -1, 20285, 18600, 18598, -1, 18592, 18590, 20286, -1, 20281, 20847, 20282, -1, 20285, 18602, 18600, -1, 20281, 20848, 20847, -1, 18590, 18588, 20286, -1, 20285, 20849, 18602, -1, 20281, 20850, 20848, -1, 20851, 20850, 20281, -1, 18588, 18586, 20286, -1, 20285, 20852, 20849, -1, 20851, 20853, 20850, -1, 18586, 18584, 20286, -1, 20854, 20855, 20851, -1, 20851, 20855, 20853, -1, 18584, 18582, 20286, -1, 20856, 20857, 20854, -1, 20854, 20857, 20855, -1, 20856, 20858, 20857, -1, 20859, 20858, 20856, -1, 18582, 18580, 20286, -1, 20852, 20860, 20861, -1, 20861, 20860, 20862, -1, 20285, 20860, 20852, -1, 20860, 20863, 20862, -1, 20859, 20864, 20858, -1, 18580, 18576, 20286, -1, 20286, 20865, 20846, -1, 18576, 20865, 20286, -1, 20866, 20865, 20867, -1, 20867, 20865, 20868, -1, 20868, 20865, 18575, -1, 18575, 20865, 18576, -1, 20865, 20869, 20870, -1, 20871, 20869, 20872, -1, 20872, 20869, 20873, -1, 20873, 20869, 20874, -1, 20874, 20869, 20875, -1, 20875, 20869, 20860, -1, 20860, 20869, 20863, -1, 20866, 20869, 20865, -1, 20863, 20869, 20876, -1, 20876, 20869, 20877, -1, 20877, 20869, 20878, -1, 20878, 20869, 20879, -1, 20879, 20869, 20866, -1, 20869, 20880, 20870, -1, 20881, 20882, 20869, -1, 20869, 20882, 20880, -1, 20820, 20869, 20871, -1, 20820, 20871, 20864, -1, 20820, 20864, 20883, -1, 20820, 20883, 20838, -1, 20883, 20864, 20884, -1, 20884, 20864, 20859, -1, 20286, 20285, 18592, -1, 20885, 20886, 20887, -1, 20888, 20886, 20885, -1, 20889, 20886, 20888, -1, 20889, 20890, 20886, -1, 20890, 20891, 20886, -1, 20886, 20891, 20892, -1, 20892, 20891, 20893, -1, 20891, 20894, 20893, -1, 20895, 20896, 20897, -1, 20898, 20896, 20895, -1, 20899, 20896, 20898, -1, 20891, 20900, 20894, -1, 20901, 20902, 20903, -1, 20904, 20902, 20901, -1, 20897, 20902, 20904, -1, 20896, 20902, 20897, -1, 20905, 20906, 20899, -1, 20899, 20906, 20896, -1, 20902, 20907, 20903, -1, 20905, 20908, 20906, -1, 20909, 20910, 20911, -1, 20912, 20910, 20909, -1, 20907, 20913, 20903, -1, 20914, 20910, 20915, -1, 20915, 20910, 20916, -1, 20916, 20910, 20912, -1, 20914, 20917, 20910, -1, 20905, 20918, 20908, -1, 20919, 20917, 20914, -1, 20913, 20920, 20903, -1, 20920, 20921, 20903, -1, 20919, 20922, 20917, -1, 20920, 20923, 20921, -1, 20924, 20925, 20926, -1, 20927, 20925, 20924, -1, 20921, 20925, 20927, -1, 20923, 20928, 20921, -1, 20929, 20930, 20931, -1, 20932, 20930, 20929, -1, 20933, 20930, 20932, -1, 20921, 20911, 20925, -1, 20928, 20934, 20921, -1, 20935, 17655, 20933, -1, 20922, 17655, 20935, -1, 20921, 20934, 20911, -1, 20891, 17655, 20900, -1, 20900, 17655, 20919, -1, 20919, 17655, 20922, -1, 20905, 20936, 20918, -1, 20933, 17655, 20930, -1, 20934, 20937, 20911, -1, 20938, 20939, 17654, -1, 20905, 20885, 20936, -1, 20936, 20885, 20940, -1, 20937, 20941, 20911, -1, 20939, 20942, 17654, -1, 20942, 20943, 17654, -1, 20885, 20944, 20940, -1, 20941, 20909, 20911, -1, 20943, 20945, 17654, -1, 20885, 20887, 20944, -1, 20946, 20947, 20945, -1, 17654, 20947, 17655, -1, 17655, 20947, 20930, -1, 20945, 20947, 17654, -1, 20948, 20949, 20950, -1, 20951, 20949, 20948, -1, 17915, 20952, 17914, -1, 20953, 20952, 17915, -1, 20954, 20955, 20956, -1, 20955, 20957, 20956, -1, 20955, 20958, 20957, -1, 20958, 20959, 20957, -1, 20959, 20960, 20957, -1, 20961, 20962, 20963, -1, 20961, 20964, 20962, -1, 20965, 17474, 17473, -1, 20966, 20965, 17473, -1, 20967, 20968, 17487, -1, 20969, 20968, 20967, -1, 20970, 17781, 20971, -1, 20972, 17781, 20970, -1, 20973, 20974, 17500, -1, 20975, 20974, 20973, -1, 20976, 20977, 20978, -1, 20976, 20979, 20977, -1, 20980, 17443, 20981, -1, 20981, 17443, 20982, -1, 20983, 20984, 17513, -1, 20985, 20984, 20983, -1, 20986, 20987, 20988, -1, 20986, 20989, 20987, -1, 20990, 17390, 20991, -1, 20991, 17390, 20992, -1, 20993, 20994, 17526, -1, 20995, 20994, 20993, -1, 20996, 20997, 20998, -1, 20996, 20999, 20997, -1, 21000, 17337, 21001, -1, 21001, 17337, 21002, -1, 21003, 21004, 17539, -1, 21005, 21004, 21003, -1, 21006, 21007, 21008, -1, 21006, 21009, 21007, -1, 21010, 17284, 21011, -1, 21011, 17284, 21012, -1, 21013, 21014, 17552, -1, 21015, 21014, 21013, -1, 21016, 21017, 21018, -1, 21016, 21019, 21017, -1, 21020, 17231, 21021, -1, 21021, 17231, 21022, -1, 21023, 21024, 17644, -1, 21025, 21024, 21023, -1, 21026, 21027, 21028, -1, 21026, 21029, 21027, -1, 21030, 17608, 21031, -1, 21031, 17608, 21032, -1, 21033, 21034, 17565, -1, 21035, 21034, 21033, -1, 21036, 21037, 21038, -1, 21036, 21039, 21037, -1, 21040, 17107, 21041, -1, 21041, 17107, 21042, -1, 21043, 21044, 17578, -1, 21045, 21044, 21043, -1, 21046, 21047, 21048, -1, 21046, 21049, 21047, -1, 21050, 17178, 21051, -1, 21051, 17178, 21052, -1, 20655, 17682, 20323, -1, 20655, 17681, 17682, -1, 20655, 17676, 17681, -1, 20655, 17673, 17676, -1, 20655, 21053, 17673, -1, 20655, 21054, 21053, -1, 21054, 21055, 21053, -1, 21054, 21056, 21055, -1, 21057, 21058, 21059, -1, 21060, 21061, 21062, -1, 21063, 21061, 21060, -1, 21058, 21061, 21063, -1, 21057, 21061, 21058, -1, 21061, 21064, 21062, -1, 21065, 21066, 21067, -1, 21066, 21068, 21067, -1, 21068, 21069, 21067, -1, 21069, 21070, 21067, -1, 21070, 21071, 21067, -1, 21071, 21072, 21067, -1, 21073, 19115, 21074, -1, 21073, 21075, 19115, -1, 21075, 21076, 19115, -1, 19115, 21077, 19114, -1, 19115, 21078, 21077, -1, 21079, 21080, 21076, -1, 21076, 21080, 19115, -1, 19115, 21080, 21078, -1, 21079, 21081, 21080, -1, 21079, 21082, 21081, -1, 21067, 21083, 21079, -1, 21072, 21083, 21067, -1, 21079, 21084, 21082, -1, 21083, 21085, 21079, -1, 21079, 21085, 21084, -1, 21086, 21087, 21088, -1, 21089, 21086, 21088, -1, 21090, 20109, 21091, -1, 21090, 21091, 21089, -1, 21090, 21089, 21088, -1, 21092, 21093, 21094, -1, 21095, 21094, 21096, -1, 21095, 21092, 21094, -1, 21097, 21098, 21099, -1, 21097, 21099, 21100, -1, 21101, 21097, 21100, -1, 20909, 20941, 20313, -1, 20313, 20941, 20310, -1, 20310, 20941, 20306, -1, 20306, 20937, 20304, -1, 20941, 20937, 20306, -1, 20304, 20934, 20305, -1, 20937, 20934, 20304, -1, 20305, 20928, 20309, -1, 20934, 20928, 20305, -1, 20309, 20923, 20311, -1, 20928, 20923, 20309, -1, 20311, 20920, 20314, -1, 20923, 20920, 20311, -1, 20314, 20913, 20321, -1, 20920, 20913, 20314, -1, 20321, 20907, 20329, -1, 20913, 20907, 20321, -1, 20329, 20902, 20335, -1, 20907, 20902, 20329, -1, 20335, 20896, 20287, -1, 20902, 20896, 20335, -1, 20287, 20906, 20339, -1, 20896, 20906, 20287, -1, 20339, 20908, 20307, -1, 20906, 20908, 20339, -1, 20908, 20918, 20307, -1, 20313, 20912, 20909, -1, 20337, 20912, 20313, -1, 20936, 20940, 20308, -1, 20308, 20940, 20315, -1, 20315, 20944, 20317, -1, 20940, 20944, 20315, -1, 20317, 20887, 20318, -1, 20944, 20887, 20317, -1, 20318, 20886, 20319, -1, 20887, 20886, 20318, -1, 20319, 20892, 20320, -1, 20886, 20892, 20319, -1, 20320, 20893, 20327, -1, 20892, 20893, 20320, -1, 20327, 20894, 20325, -1, 20893, 20894, 20327, -1, 20325, 20900, 20302, -1, 20894, 20900, 20325, -1, 20302, 20919, 20300, -1, 20900, 20919, 20302, -1, 20300, 20914, 20303, -1, 20919, 20914, 20300, -1, 20303, 20915, 20297, -1, 20914, 20915, 20303, -1, 20297, 20916, 20296, -1, 20915, 20916, 20297, -1, 20296, 20912, 20337, -1, 20916, 20912, 20296, -1, 20936, 20308, 20918, -1, 20918, 20308, 20307, -1, 21102, 21103, 21104, -1, 21104, 21103, 21105, -1, 21106, 21107, 21108, -1, 21109, 21107, 21106, -1, 21110, 21111, 21112, -1, 21113, 21111, 21110, -1, 21111, 21114, 21112, -1, 21115, 21116, 21117, -1, 21118, 21119, 21120, -1, 21121, 21119, 21116, -1, 21122, 21119, 21121, -1, 21120, 21119, 21122, -1, 21116, 21119, 21117, -1, 21123, 21124, 21125, -1, 20092, 21124, 21123, -1, 21126, 20092, 21123, -1, 21127, 21128, 21129, -1, 21130, 21131, 21132, -1, 21130, 21132, 21133, -1, 21134, 21135, 21131, -1, 21134, 21131, 21130, -1, 21136, 21133, 21137, -1, 21136, 21130, 21133, -1, 21138, 21139, 21135, -1, 21138, 21135, 21134, -1, 21140, 21137, 21141, -1, 21140, 21136, 21137, -1, 21142, 21143, 21139, -1, 20626, 21144, 21145, -1, 21142, 21139, 21138, -1, 20626, 21145, 21146, -1, 20626, 21146, 21147, -1, 20626, 21147, 21148, -1, 20626, 21148, 21149, -1, 20626, 21149, 21150, -1, 21151, 21127, 21152, -1, 21151, 21152, 21153, -1, 21154, 21140, 21141, -1, 21151, 21153, 21144, -1, 21151, 21144, 20626, -1, 21155, 21143, 21142, -1, 21156, 20626, 21150, -1, 21157, 20626, 21156, -1, 21158, 21154, 21141, -1, 21159, 20626, 21157, -1, 21160, 21158, 21141, -1, 20625, 20626, 21159, -1, 21161, 21158, 21160, -1, 21162, 20625, 21159, -1, 21151, 21128, 21127, -1, 21163, 21160, 21164, -1, 21163, 21164, 21165, -1, 21163, 21161, 21160, -1, 21166, 21163, 21165, -1, 21166, 21165, 21167, -1, 21166, 21167, 21168, -1, 21129, 21166, 21168, -1, 21169, 21166, 21129, -1, 21128, 21169, 21129, -1, 21170, 21143, 21155, -1, 21171, 21170, 21155, -1, 21172, 21173, 21170, -1, 21172, 21170, 21171, -1, 21174, 21175, 21173, -1, 21174, 21173, 21172, -1, 21176, 21175, 21174, -1, 21125, 21176, 21174, -1, 21124, 21176, 21125, -1, 21177, 20450, 21178, -1, 21178, 20450, 20495, -1, 21177, 21179, 20450, -1, 21180, 21181, 17053, -1, 21181, 17051, 17053, -1, 21182, 21183, 21184, -1, 21184, 21185, 21186, -1, 21183, 21185, 21184, -1, 21186, 21187, 21188, -1, 21185, 21187, 21186, -1, 21188, 21189, 21190, -1, 21187, 21189, 21188, -1, 21190, 21191, 21192, -1, 21189, 21191, 21190, -1, 21192, 21193, 21194, -1, 21191, 21193, 21192, -1, 21194, 21195, 17053, -1, 21193, 21195, 21194, -1, 21195, 21180, 17053, -1, 21196, 21182, 21197, -1, 21183, 21182, 21196, -1, 21198, 21097, 21101, -1, 21198, 21101, 21199, -1, 21200, 21199, 21201, -1, 21200, 21198, 21199, -1, 21202, 21201, 21203, -1, 21202, 21200, 21201, -1, 21204, 21203, 21205, -1, 21204, 21202, 21203, -1, 21206, 21205, 21207, -1, 21206, 21204, 21205, -1, 21208, 21207, 21209, -1, 21208, 21209, 21096, -1, 21208, 21206, 21207, -1, 21094, 21208, 21096, -1, 21210, 21098, 21097, -1, 21210, 21097, 21198, -1, 21211, 21198, 21200, -1, 21211, 21210, 21198, -1, 21212, 21200, 21202, -1, 21212, 21211, 21200, -1, 21213, 21202, 21204, -1, 21213, 21212, 21202, -1, 21214, 21204, 21206, -1, 21214, 21213, 21204, -1, 21215, 21206, 21208, -1, 21215, 21214, 21206, -1, 21093, 21208, 21094, -1, 21093, 21215, 21208, -1, 20947, 20946, 21216, -1, 21217, 20947, 21216, -1, 21218, 21216, 21219, -1, 21218, 21219, 21220, -1, 21218, 21217, 21216, -1, 21221, 21220, 21113, -1, 21221, 21218, 21220, -1, 21110, 21221, 21113, -1, 21222, 21111, 21113, -1, 21222, 21113, 21223, -1, 21224, 21223, 21225, -1, 21224, 21222, 21223, -1, 20957, 21225, 20956, -1, 20957, 21224, 21225, -1, 21226, 21092, 21095, -1, 21226, 21095, 21227, -1, 21228, 21227, 21229, -1, 21228, 21226, 21227, -1, 21230, 21229, 21231, -1, 21230, 21228, 21229, -1, 21088, 21231, 21090, -1, 21088, 21230, 21231, -1, 21117, 21232, 21233, -1, 21119, 21232, 21117, -1, 21233, 21234, 21235, -1, 21232, 21234, 21233, -1, 21236, 21237, 21181, -1, 21235, 21237, 21236, -1, 21234, 21237, 21235, -1, 21237, 17051, 21181, -1, 20771, 20770, 20847, -1, 20771, 20847, 20848, -1, 20771, 20848, 20850, -1, 20772, 20850, 20853, -1, 20772, 20771, 20850, -1, 20774, 20853, 20855, -1, 20774, 20772, 20853, -1, 20775, 20855, 20857, -1, 20775, 20774, 20855, -1, 20777, 20857, 20858, -1, 20777, 20775, 20857, -1, 20779, 20858, 20864, -1, 20779, 20777, 20858, -1, 20781, 20864, 20871, -1, 20781, 20779, 20864, -1, 20769, 20871, 20872, -1, 20769, 20781, 20871, -1, 20768, 20872, 20873, -1, 20768, 20769, 20872, -1, 20767, 20873, 20874, -1, 20767, 20768, 20873, -1, 20766, 20874, 20875, -1, 20766, 20767, 20874, -1, 20765, 20875, 20860, -1, 20765, 20766, 20875, -1, 20764, 20765, 20860, -1, 20860, 20285, 20284, -1, 20764, 20860, 20284, -1, 20847, 20770, 20279, -1, 20847, 20279, 20282, -1, 20783, 20782, 20828, -1, 20783, 20828, 20829, -1, 20783, 20829, 20832, -1, 20784, 20832, 20834, -1, 20784, 20783, 20832, -1, 20785, 20834, 20835, -1, 20785, 20784, 20834, -1, 20786, 20835, 20836, -1, 20786, 20785, 20835, -1, 20787, 20836, 20837, -1, 20787, 20786, 20836, -1, 20788, 20837, 20838, -1, 20788, 20787, 20837, -1, 20789, 20838, 20883, -1, 20789, 20788, 20838, -1, 20790, 20883, 20884, -1, 20790, 20789, 20883, -1, 20791, 20884, 20859, -1, 20791, 20790, 20884, -1, 20780, 20859, 20856, -1, 20780, 20791, 20859, -1, 20778, 20856, 20854, -1, 20778, 20780, 20856, -1, 20776, 20854, 20851, -1, 20776, 20778, 20854, -1, 20773, 20776, 20851, -1, 20851, 20281, 20280, -1, 20773, 20851, 20280, -1, 20828, 20782, 20277, -1, 20828, 20277, 20278, -1, 20681, 20173, 20175, -1, 20682, 20175, 20177, -1, 20682, 20681, 20175, -1, 20684, 20177, 20179, -1, 20684, 20682, 20177, -1, 20686, 20179, 20183, -1, 20686, 20684, 20179, -1, 20671, 20183, 20181, -1, 20671, 20686, 20183, -1, 20670, 20181, 21238, -1, 20670, 20671, 20181, -1, 20668, 21238, 21239, -1, 20668, 20670, 21238, -1, 20669, 21239, 20809, -1, 20669, 20668, 21239, -1, 20679, 20809, 20810, -1, 20679, 20669, 20809, -1, 20678, 20810, 20807, -1, 20678, 20679, 20810, -1, 20677, 20807, 20808, -1, 20677, 20678, 20807, -1, 20676, 20808, 20817, -1, 20676, 20677, 20808, -1, 20672, 20817, 20814, -1, 20672, 20676, 20817, -1, 20663, 20814, 20811, -1, 20663, 20672, 20814, -1, 20811, 20267, 20266, -1, 20663, 20811, 20266, -1, 20173, 20681, 20261, -1, 20173, 20261, 20170, -1, 20169, 20171, 20260, -1, 20680, 20169, 20260, -1, 20166, 20661, 20658, -1, 20166, 20658, 20164, -1, 20661, 20166, 20150, -1, 20662, 20150, 20149, -1, 20662, 20661, 20150, -1, 20664, 20149, 20152, -1, 20664, 20662, 20149, -1, 20665, 20152, 20157, -1, 20665, 20664, 20152, -1, 20666, 20157, 20156, -1, 20666, 20665, 20157, -1, 20667, 20156, 21240, -1, 20667, 20666, 20156, -1, 20673, 21240, 21241, -1, 20673, 20667, 21240, -1, 20674, 21241, 20180, -1, 20674, 20673, 21241, -1, 20675, 20180, 20182, -1, 20675, 20674, 20180, -1, 20688, 20182, 20178, -1, 20688, 20675, 20182, -1, 20687, 20178, 20176, -1, 20687, 20688, 20178, -1, 20685, 20176, 20174, -1, 20685, 20687, 20176, -1, 20683, 20174, 20172, -1, 20683, 20685, 20174, -1, 20680, 20172, 20169, -1, 20680, 20683, 20172, -1, 20155, 20154, 20660, -1, 20659, 21242, 21243, -1, 20659, 21243, 21244, -1, 20659, 21244, 20155, -1, 20659, 20155, 20660, -1, 21245, 21242, 20659, -1, 18562, 17860, 17859, -1, 18560, 18562, 17859, -1, 21246, 18560, 17859, -1, 18558, 18560, 21246, -1, 17816, 21247, 21248, -1, 17816, 17817, 21247, -1, 21249, 21250, 18555, -1, 21249, 21251, 21250, -1, 21249, 21248, 21251, -1, 21249, 18556, 18558, -1, 21249, 18555, 18556, -1, 21249, 18558, 21246, -1, 21249, 17816, 21248, -1, 21252, 21253, 21254, -1, 21252, 21255, 21253, -1, 21256, 21257, 21258, -1, 21259, 21260, 21261, -1, 21259, 21261, 21262, -1, 21259, 21262, 21263, -1, 21259, 21263, 21264, -1, 21259, 21264, 21257, -1, 21259, 21257, 21256, -1, 21255, 21252, 21265, -1, 21265, 21266, 21267, -1, 21252, 21266, 21265, -1, 21267, 21268, 21269, -1, 21266, 21268, 21267, -1, 21269, 21270, 18875, -1, 21268, 21270, 21269, -1, 21270, 17829, 18875, -1, 21271, 21246, 17859, -1, 21271, 17859, 21272, -1, 21273, 21271, 21272, -1, 21274, 21272, 21275, -1, 21274, 21273, 21272, -1, 21276, 21275, 21277, -1, 21276, 21274, 21275, -1, 21253, 21277, 21254, -1, 21253, 21276, 21277, -1, 17816, 21249, 21278, -1, 21279, 21278, 21280, -1, 21279, 17816, 21278, -1, 21281, 21280, 21282, -1, 21281, 21282, 21283, -1, 21281, 21279, 21280, -1, 21257, 21283, 21258, -1, 21257, 21281, 21283, -1, 21260, 21259, 21284, -1, 21284, 21285, 21286, -1, 21259, 21285, 21284, -1, 21286, 21287, 21288, -1, 21285, 21287, 21286, -1, 21288, 21289, 18787, -1, 21287, 21289, 21288, -1, 21289, 19069, 18787, -1, 21290, 18579, 21291, -1, 21290, 18577, 18578, -1, 21290, 18578, 18579, -1, 18446, 18450, 21292, -1, 18446, 21292, 21293, -1, 18595, 21294, 21295, -1, 18426, 18577, 21290, -1, 18593, 21295, 21296, -1, 18593, 18595, 21295, -1, 18441, 21293, 21297, -1, 18597, 21298, 21294, -1, 18597, 21294, 18595, -1, 18441, 18446, 21293, -1, 18591, 21296, 21299, -1, 18413, 18577, 18426, -1, 18591, 21299, 21300, -1, 18413, 21301, 21302, -1, 18413, 21302, 18577, -1, 18591, 18593, 21296, -1, 18436, 21297, 21303, -1, 18599, 18452, 21298, -1, 18436, 18441, 21297, -1, 18599, 21298, 18597, -1, 18412, 21301, 18413, -1, 18412, 21304, 21301, -1, 18589, 21300, 21305, -1, 18431, 18436, 21303, -1, 18589, 18591, 21300, -1, 18431, 21303, 21306, -1, 18425, 21306, 21304, -1, 18425, 21304, 18412, -1, 18425, 18431, 21306, -1, 18601, 18452, 18599, -1, 18587, 18589, 21305, -1, 21307, 18587, 21305, -1, 21308, 18420, 18452, -1, 21308, 18452, 18601, -1, 18585, 18587, 21307, -1, 21309, 18409, 18420, -1, 21309, 18420, 21308, -1, 21310, 18585, 21307, -1, 18583, 18585, 21310, -1, 21311, 18393, 18409, -1, 21311, 18409, 21309, -1, 21312, 18581, 18583, -1, 21312, 18583, 21310, -1, 21313, 18393, 21311, -1, 18391, 18393, 21313, -1, 21291, 18581, 21312, -1, 21291, 18579, 18581, -1, 18450, 18391, 21313, -1, 18450, 21313, 21292, -1, 18602, 20849, 18601, -1, 18601, 20849, 21308, -1, 21308, 20849, 21309, -1, 21309, 20852, 21311, -1, 20849, 20852, 21309, -1, 21311, 20861, 21313, -1, 20852, 20861, 21311, -1, 21313, 20862, 21292, -1, 20861, 20862, 21313, -1, 21292, 20863, 21293, -1, 20862, 20863, 21292, -1, 21293, 20876, 21297, -1, 20863, 20876, 21293, -1, 21297, 20877, 21303, -1, 20876, 20877, 21297, -1, 21303, 20878, 21306, -1, 20877, 20878, 21303, -1, 21306, 20879, 21304, -1, 20878, 20879, 21306, -1, 21304, 20866, 21301, -1, 20879, 20866, 21304, -1, 21301, 20867, 21302, -1, 20866, 20867, 21301, -1, 21302, 20868, 18577, -1, 20867, 20868, 21302, -1, 20868, 18575, 18577, -1, 18570, 18551, 18563, -1, 18572, 18551, 18570, -1, 18574, 18551, 18572, -1, 18546, 18551, 18574, -1, 18548, 18551, 18546, -1, 21314, 21315, 18551, -1, 21315, 21316, 18551, -1, 21316, 21317, 18551, -1, 21317, 21318, 18551, -1, 18551, 20234, 18563, -1, 21318, 20234, 18551, -1, 18552, 20818, 18551, -1, 18551, 20818, 21314, -1, 21314, 20819, 21315, -1, 20818, 20819, 21314, -1, 21315, 20821, 21316, -1, 20819, 20821, 21315, -1, 21316, 20822, 21317, -1, 20821, 20822, 21316, -1, 20235, 20234, 21319, -1, 20234, 21320, 21319, -1, 20234, 17805, 21320, -1, 20234, 17806, 17805, -1, 20234, 17809, 17806, -1, 21317, 20823, 21318, -1, 20822, 20823, 21317, -1, 21318, 20824, 20234, -1, 20823, 20824, 21318, -1, 17813, 20825, 17815, -1, 17811, 20825, 17813, -1, 17809, 20825, 17811, -1, 20234, 20825, 17809, -1, 20824, 20825, 20234, -1, 17815, 20826, 17817, -1, 17817, 20826, 21247, -1, 20825, 20826, 17815, -1, 21247, 20827, 21248, -1, 20826, 20827, 21247, -1, 21248, 20833, 21251, -1, 20827, 20833, 21248, -1, 21251, 20831, 21250, -1, 20833, 20831, 21251, -1, 20831, 20830, 21250, -1, 21250, 20830, 18555, -1, 20830, 18553, 18555, -1, 21321, 18459, 18512, -1, 21321, 18512, 21322, -1, 21321, 21322, 21323, -1, 21324, 18453, 21325, -1, 21324, 21325, 21326, -1, 21324, 21326, 21327, -1, 21328, 18522, 18453, -1, 21328, 18466, 18467, -1, 21328, 18467, 18522, -1, 21328, 21324, 21327, -1, 21328, 21327, 18466, -1, 21328, 18453, 21324, -1, 21329, 21330, 21331, -1, 21329, 21331, 18448, -1, 21329, 18448, 18457, -1, 21329, 21321, 21330, -1, 21332, 18457, 18458, -1, 21332, 18458, 18459, -1, 21332, 21321, 21329, -1, 21332, 18459, 21321, -1, 21332, 21329, 18457, -1, 21327, 21326, 21333, -1, 21327, 18475, 18466, -1, 21334, 21333, 21335, -1, 21334, 21335, 21336, -1, 21334, 18485, 18480, -1, 21334, 18480, 18475, -1, 21334, 21327, 21333, -1, 21334, 18475, 21327, -1, 21337, 21336, 21338, -1, 21337, 18491, 18485, -1, 21337, 21334, 21336, -1, 21337, 18485, 21334, -1, 21339, 21338, 21340, -1, 21339, 21340, 21341, -1, 21339, 18500, 18495, -1, 21339, 18495, 18491, -1, 21339, 18491, 21337, -1, 21339, 21337, 21338, -1, 21322, 21341, 21342, -1, 21322, 21342, 21323, -1, 21322, 18512, 18508, -1, 21322, 18508, 18500, -1, 21322, 21339, 21341, -1, 21322, 18500, 21339, -1, 21321, 21323, 21330, -1, 21343, 21344, 21345, -1, 21346, 21344, 21343, -1, 18526, 21347, 18456, -1, 18454, 21347, 21348, -1, 18514, 21349, 18519, -1, 21348, 21350, 21351, -1, 21345, 21349, 21352, -1, 21351, 21350, 21353, -1, 21354, 21349, 18514, -1, 21352, 21349, 21354, -1, 18522, 21355, 18532, -1, 18504, 18937, 18505, -1, 18519, 21355, 18523, -1, 18523, 21355, 18522, -1, 18936, 21356, 18938, -1, 18532, 21355, 21344, -1, 21349, 21355, 18519, -1, 21353, 21356, 18936, -1, 21344, 21355, 21345, -1, 21345, 21355, 21349, -1, 18534, 21357, 18525, -1, 18525, 21357, 21347, -1, 21347, 21357, 21348, -1, 21348, 21357, 21350, -1, 21350, 21358, 21353, -1, 21353, 21358, 21356, -1, 18938, 21359, 18940, -1, 21356, 21359, 18938, -1, 21350, 21360, 21358, -1, 18537, 21360, 18534, -1, 18457, 18526, 18456, -1, 21357, 21360, 21350, -1, 18534, 21360, 21357, -1, 21356, 21361, 21359, -1, 21358, 21361, 21356, -1, 18940, 21362, 18947, -1, 21359, 21362, 18940, -1, 18536, 21363, 18537, -1, 18537, 21363, 21360, -1, 21360, 21363, 21358, -1, 21358, 21363, 21361, -1, 21361, 21364, 21359, -1, 21359, 21364, 21362, -1, 18947, 21365, 19002, -1, 21362, 21365, 18947, -1, 21361, 21366, 21364, -1, 18539, 21366, 18536, -1, 21363, 21366, 21361, -1, 18536, 21366, 21363, -1, 21362, 21367, 21365, -1, 21364, 21367, 21362, -1, 19002, 21368, 18914, -1, 21365, 21368, 19002, -1, 18542, 21369, 18539, -1, 18539, 21369, 21366, -1, 21364, 21369, 21367, -1, 21366, 21369, 21364, -1, 21365, 21370, 21368, -1, 21367, 21370, 21365, -1, 18914, 21371, 18909, -1, 21368, 21371, 18914, -1, 18541, 21372, 18542, -1, 21369, 21372, 21367, -1, 21367, 21372, 21370, -1, 18542, 21372, 21369, -1, 21370, 21373, 21368, -1, 21368, 21373, 21371, -1, 18909, 21374, 18887, -1, 21371, 21374, 18909, -1, 18545, 21375, 18541, -1, 21370, 21375, 21373, -1, 18541, 21375, 21372, -1, 21372, 21375, 21370, -1, 21373, 21376, 21371, -1, 18860, 18514, 18516, -1, 21371, 21376, 21374, -1, 18887, 21377, 18865, -1, 21374, 21377, 18887, -1, 18544, 21378, 18545, -1, 18545, 21378, 21375, -1, 21373, 21378, 21376, -1, 21375, 21378, 21373, -1, 21376, 21343, 21374, -1, 21374, 21343, 21377, -1, 18865, 21352, 18862, -1, 21377, 21352, 18865, -1, 18533, 21346, 18544, -1, 18544, 21346, 21378, -1, 21376, 21346, 21343, -1, 18504, 21351, 18937, -1, 21378, 21346, 21376, -1, 18454, 21348, 18504, -1, 21343, 21345, 21377, -1, 21377, 21345, 21352, -1, 18504, 21348, 21351, -1, 18862, 21354, 18860, -1, 18937, 21353, 18936, -1, 21352, 21354, 18862, -1, 18860, 21354, 18514, -1, 21351, 21353, 18937, -1, 18532, 21344, 18533, -1, 18525, 21347, 18526, -1, 18533, 21344, 21346, -1, 18456, 21347, 18454, -1, 21379, 21380, 21381, -1, 21379, 21310, 21307, -1, 21382, 21323, 21342, -1, 21379, 21381, 21383, -1, 21379, 21307, 21380, -1, 21382, 21384, 21323, -1, 21385, 21325, 18453, -1, 21385, 18453, 18396, -1, 21385, 21386, 21325, -1, 18405, 18448, 21331, -1, 21387, 21388, 21384, -1, 21387, 21389, 21388, -1, 21390, 21391, 21386, -1, 21392, 18423, 18416, -1, 21390, 21393, 21391, -1, 21392, 21298, 18423, -1, 21394, 21310, 21379, -1, 21392, 18416, 21389, -1, 21394, 21312, 21310, -1, 21394, 21383, 21393, -1, 21395, 21342, 21341, -1, 21394, 21379, 21383, -1, 21395, 21382, 21342, -1, 21396, 18396, 18395, -1, 21397, 21387, 21384, -1, 21397, 21384, 21382, -1, 21396, 21385, 18396, -1, 21396, 21386, 21385, -1, 21396, 21390, 21386, -1, 21398, 21291, 21312, -1, 21399, 21294, 21298, -1, 21398, 21312, 21394, -1, 21398, 21393, 21390, -1, 21399, 21389, 21387, -1, 21399, 21298, 21392, -1, 21398, 21394, 21393, -1, 21400, 18414, 21290, -1, 21399, 21392, 21389, -1, 21400, 18395, 18414, -1, 21400, 21290, 21291, -1, 21401, 21341, 21340, -1, 21400, 21291, 21398, -1, 21400, 21396, 18395, -1, 21298, 18452, 18423, -1, 21400, 21390, 21396, -1, 21401, 21395, 21341, -1, 21400, 21398, 21390, -1, 21402, 21397, 21382, -1, 21402, 21382, 21395, -1, 21403, 21295, 21294, -1, 21403, 21399, 21387, -1, 21403, 21387, 21397, -1, 21403, 21294, 21399, -1, 21404, 21340, 21338, -1, 21404, 21401, 21340, -1, 21405, 21395, 21401, -1, 21405, 21402, 21395, -1, 21406, 21296, 21295, -1, 21406, 21295, 21403, -1, 21406, 21397, 21402, -1, 21406, 21403, 21397, -1, 21407, 21338, 21336, -1, 21407, 21404, 21338, -1, 21408, 21405, 21401, -1, 21408, 21401, 21404, -1, 21409, 21406, 21402, -1, 21409, 21299, 21296, -1, 21409, 21296, 21406, -1, 21409, 21402, 21405, -1, 21410, 21336, 21335, -1, 21410, 21407, 21336, -1, 21411, 21408, 21404, -1, 21411, 21404, 21407, -1, 21412, 21409, 21405, -1, 21412, 21405, 21408, -1, 21412, 21299, 21409, -1, 21412, 21300, 21299, -1, 21413, 21335, 21333, -1, 21413, 21410, 21335, -1, 21381, 21407, 21410, -1, 21381, 21411, 21407, -1, 21414, 21408, 21411, -1, 21414, 21412, 21408, -1, 21414, 21300, 21412, -1, 21414, 21305, 21300, -1, 21391, 21333, 21326, -1, 21391, 21413, 21333, -1, 18426, 21290, 18414, -1, 21383, 21410, 21413, -1, 21383, 21381, 21410, -1, 21380, 21411, 21381, -1, 21380, 21414, 21411, -1, 21388, 21331, 21330, -1, 21380, 21307, 21305, -1, 21388, 18405, 21331, -1, 21380, 21305, 21414, -1, 21386, 21326, 21325, -1, 21384, 21330, 21323, -1, 21386, 21391, 21326, -1, 21384, 21388, 21330, -1, 21389, 18416, 18405, -1, 21393, 21413, 21391, -1, 21393, 21383, 21413, -1, 21389, 18405, 21388, -1, 21415, 20225, 20223, -1, 21415, 20223, 20221, -1, 21416, 18657, 18656, -1, 21416, 18656, 21417, -1, 20219, 21415, 20221, -1, 20217, 21415, 20219, -1, 20215, 21415, 20217, -1, 17930, 17932, 20198, -1, 17930, 20198, 20196, -1, 18638, 20208, 18629, -1, 17918, 18657, 21416, -1, 18640, 18629, 18627, -1, 18640, 18638, 18629, -1, 18609, 21418, 21419, -1, 17918, 20185, 18657, -1, 18636, 20211, 20208, -1, 17928, 20196, 20194, -1, 18636, 20208, 18638, -1, 18611, 21419, 21420, -1, 17928, 17930, 20196, -1, 18611, 18609, 21419, -1, 17917, 20185, 17918, -1, 18607, 21421, 21418, -1, 18634, 20213, 20211, -1, 18607, 21418, 18609, -1, 17917, 20186, 20185, -1, 18634, 20211, 18636, -1, 17926, 17928, 20194, -1, 17926, 20194, 20192, -1, 18613, 21420, 21422, -1, 17921, 20186, 17917, -1, 18632, 20213, 18634, -1, 18632, 20215, 20213, -1, 18613, 18611, 21420, -1, 17921, 20188, 20186, -1, 18606, 21423, 21421, -1, 17924, 17926, 20192, -1, 17924, 20192, 20190, -1, 21424, 18627, 21425, -1, 21424, 18644, 18642, -1, 18606, 21421, 18607, -1, 21424, 18642, 18640, -1, 18615, 18613, 21422, -1, 17922, 20188, 17921, -1, 21424, 18640, 18627, -1, 18615, 21422, 21426, -1, 17922, 17924, 20190, -1, 17922, 20190, 20188, -1, 18646, 18644, 21424, -1, 18604, 21427, 21423, -1, 18604, 21423, 18606, -1, 20206, 20215, 18632, -1, 20206, 21415, 20215, -1, 18648, 18646, 21424, -1, 18617, 21426, 21428, -1, 18617, 18615, 21426, -1, 18650, 21424, 21429, -1, 18650, 18648, 21424, -1, 20231, 21430, 21427, -1, 20231, 21427, 18604, -1, 18619, 21428, 21425, -1, 18619, 18617, 21428, -1, 20229, 21430, 20231, -1, 18652, 18650, 21429, -1, 21431, 18652, 21429, -1, 18621, 18619, 21425, -1, 21432, 21430, 20229, -1, 20227, 21432, 20229, -1, 18654, 18652, 21431, -1, 18623, 18621, 21425, -1, 21433, 21432, 20227, -1, 21417, 18656, 18654, -1, 21417, 18654, 21431, -1, 21433, 20227, 20225, -1, 18625, 18623, 21425, -1, 17932, 20206, 20204, -1, 17932, 20204, 20202, -1, 17932, 20202, 20200, -1, 17932, 21415, 20206, -1, 17932, 20200, 20198, -1, 18627, 18625, 21425, -1, 21415, 21433, 20225, -1, 21434, 18289, 21435, -1, 21434, 18286, 18287, -1, 21434, 18287, 18289, -1, 18279, 18227, 21436, -1, 18279, 21436, 21437, -1, 18305, 21438, 21439, -1, 18303, 21439, 21440, -1, 18303, 18305, 21439, -1, 18236, 18286, 21434, -1, 18307, 21441, 21438, -1, 18307, 21438, 18305, -1, 18276, 21437, 21442, -1, 18301, 21440, 21443, -1, 18276, 18279, 21437, -1, 18235, 18286, 18236, -1, 18301, 18303, 21440, -1, 18235, 21444, 18286, -1, 18271, 21442, 21445, -1, 18309, 18281, 21441, -1, 18271, 18276, 21442, -1, 18309, 21441, 18307, -1, 18299, 21443, 21446, -1, 18251, 21444, 18235, -1, 18251, 21447, 21444, -1, 18299, 18301, 21443, -1, 18266, 21445, 21448, -1, 18266, 18271, 21445, -1, 18261, 21448, 21447, -1, 18261, 18266, 21448, -1, 18261, 21447, 18251, -1, 18311, 18281, 18309, -1, 18297, 21446, 21449, -1, 18297, 18299, 21446, -1, 21450, 18258, 18281, -1, 21450, 18281, 18311, -1, 18295, 21449, 21451, -1, 18295, 18297, 21449, -1, 21452, 18253, 18258, -1, 21452, 18258, 21450, -1, 18293, 21451, 21453, -1, 18293, 18295, 21451, -1, 21454, 18246, 18253, -1, 21454, 18253, 21452, -1, 18291, 18293, 21453, -1, 21455, 18291, 21453, -1, 21456, 18246, 21454, -1, 18226, 18246, 21456, -1, 21457, 18226, 21456, -1, 21435, 18291, 21455, -1, 21435, 18289, 18291, -1, 18227, 18226, 21457, -1, 21436, 18227, 21457, -1, 18139, 18141, 21458, -1, 18139, 21458, 21459, -1, 21460, 18317, 21461, -1, 21460, 18314, 18315, -1, 21460, 18315, 18317, -1, 18135, 18139, 21459, -1, 18135, 21459, 21462, -1, 18333, 21463, 21464, -1, 18331, 21464, 21465, -1, 18331, 18333, 21464, -1, 18335, 21466, 21463, -1, 18335, 21463, 18333, -1, 18329, 21465, 21467, -1, 18329, 18331, 21465, -1, 18337, 18111, 21468, -1, 18337, 21468, 21466, -1, 18337, 21466, 18335, -1, 18327, 21467, 21469, -1, 18115, 18314, 21460, -1, 18327, 18329, 21467, -1, 18130, 21462, 21470, -1, 18130, 18135, 21462, -1, 18103, 18314, 18115, -1, 18338, 18111, 18337, -1, 18103, 21471, 18314, -1, 18125, 18130, 21470, -1, 18325, 18327, 21469, -1, 18125, 21470, 21472, -1, 21473, 18325, 21469, -1, 21474, 18106, 18111, -1, 18102, 21475, 21471, -1, 21474, 18111, 18338, -1, 18102, 21471, 18103, -1, 18095, 18106, 21474, -1, 18120, 18125, 21472, -1, 18120, 21472, 21476, -1, 18323, 18325, 21473, -1, 18114, 21475, 18102, -1, 18114, 21476, 21477, -1, 18114, 21477, 21475, -1, 18114, 18120, 21476, -1, 21478, 18095, 21474, -1, 21479, 18323, 21473, -1, 18321, 18323, 21479, -1, 18096, 18095, 21478, -1, 21480, 18096, 21478, -1, 21481, 18319, 18321, -1, 21481, 18321, 21479, -1, 18141, 18096, 21480, -1, 18141, 21480, 21458, -1, 21461, 18319, 21481, -1, 21461, 18317, 18319, -1, 21482, 21483, 21484, -1, 21485, 18170, 18149, -1, 21485, 18149, 18176, -1, 21485, 21482, 21484, -1, 21485, 21484, 18170, -1, 21485, 18176, 21482, -1, 21486, 21487, 21488, -1, 21486, 21488, 18233, -1, 21486, 21489, 21487, -1, 21490, 18233, 18210, -1, 21490, 18210, 18167, -1, 21490, 18167, 18144, -1, 21490, 21486, 18233, -1, 21490, 21489, 21486, -1, 21490, 18144, 21489, -1, 21484, 21483, 21491, -1, 21484, 18168, 18170, -1, 21492, 21491, 21493, -1, 21492, 21493, 21494, -1, 21492, 18180, 18174, -1, 21492, 18174, 18168, -1, 21492, 21484, 21491, -1, 21492, 18168, 21484, -1, 21495, 21494, 21496, -1, 21495, 21496, 21497, -1, 21495, 18185, 18180, -1, 21495, 21492, 21494, -1, 21495, 18180, 21492, -1, 21498, 21497, 21499, -1, 21498, 18196, 18190, -1, 21498, 18190, 18185, -1, 21498, 18185, 21495, -1, 21498, 21495, 21497, -1, 21500, 21499, 21501, -1, 21500, 21501, 21502, -1, 21500, 18207, 18201, -1, 21500, 18201, 18196, -1, 21500, 21498, 21499, -1, 21500, 18196, 21498, -1, 21489, 21502, 21487, -1, 21489, 18144, 18207, -1, 21489, 21500, 21502, -1, 21489, 18207, 21500, -1, 21482, 18176, 18282, -1, 21482, 18282, 21503, -1, 21482, 21503, 21483, -1, 21504, 18017, 18019, -1, 21504, 18019, 21505, -1, 21504, 21505, 21506, -1, 21507, 18143, 21508, -1, 21507, 21508, 21509, -1, 21507, 21509, 21510, -1, 21511, 18037, 18143, -1, 21511, 18028, 18004, -1, 21511, 18004, 18037, -1, 21511, 21507, 21510, -1, 21511, 21510, 18028, -1, 21511, 18143, 21507, -1, 21512, 21513, 21514, -1, 21512, 21514, 18082, -1, 21512, 18082, 18032, -1, 21512, 21504, 21513, -1, 21515, 18032, 18033, -1, 21515, 18033, 18017, -1, 21515, 21504, 21512, -1, 21515, 18017, 21504, -1, 21515, 21512, 18032, -1, 21510, 21509, 21516, -1, 21510, 18038, 18028, -1, 21517, 21516, 21518, -1, 21517, 21518, 21519, -1, 21517, 18048, 18043, -1, 21517, 18043, 18038, -1, 21517, 21510, 21516, -1, 21517, 18038, 21510, -1, 21520, 21519, 21521, -1, 21520, 18054, 18048, -1, 21520, 21517, 21519, -1, 21520, 18048, 21517, -1, 21522, 21521, 21523, -1, 21522, 21523, 21524, -1, 21522, 18063, 18058, -1, 21522, 18058, 18054, -1, 21522, 18054, 21520, -1, 21522, 21520, 21521, -1, 21505, 21524, 21525, -1, 21505, 21525, 21506, -1, 21505, 18019, 18070, -1, 21505, 18070, 18063, -1, 21505, 21522, 21524, -1, 21505, 18063, 21522, -1, 21504, 21506, 21513, -1, 18338, 18339, 21474, -1, 21474, 20812, 21478, -1, 18339, 20812, 21474, -1, 21478, 20813, 21480, -1, 20812, 20813, 21478, -1, 21480, 20815, 21458, -1, 20813, 20815, 21480, -1, 21458, 20816, 21459, -1, 20815, 20816, 21458, -1, 21459, 20799, 21462, -1, 20816, 20799, 21459, -1, 21462, 20800, 21470, -1, 20799, 20800, 21462, -1, 21470, 20801, 21472, -1, 20800, 20801, 21470, -1, 21472, 20802, 21476, -1, 20801, 20802, 21472, -1, 21476, 20803, 21477, -1, 20802, 20803, 21476, -1, 21477, 20804, 21475, -1, 20803, 20804, 21477, -1, 21475, 20805, 21471, -1, 20804, 20805, 21475, -1, 21471, 20806, 18314, -1, 20805, 20806, 21471, -1, 20806, 18312, 18314, -1, 18310, 20159, 18311, -1, 18311, 20159, 21450, -1, 21450, 20159, 21452, -1, 21452, 20160, 21454, -1, 20159, 20160, 21452, -1, 21454, 20161, 21456, -1, 20160, 20161, 21454, -1, 21456, 20162, 21457, -1, 20161, 20162, 21456, -1, 21457, 20158, 21436, -1, 20162, 20158, 21457, -1, 21436, 20153, 21437, -1, 20158, 20153, 21436, -1, 21437, 20151, 21442, -1, 20153, 20151, 21437, -1, 21442, 20148, 21445, -1, 20151, 20148, 21442, -1, 21445, 20165, 21448, -1, 20148, 20165, 21445, -1, 21448, 20167, 21447, -1, 20165, 20167, 21448, -1, 21447, 20168, 21444, -1, 20167, 20168, 21447, -1, 21444, 20163, 18286, -1, 20168, 20163, 21444, -1, 20163, 18284, 18286, -1, 21526, 21527, 21528, -1, 21526, 21529, 21527, -1, 21530, 21531, 21488, -1, 21532, 18249, 18238, -1, 21533, 21534, 21535, -1, 21533, 21455, 21453, -1, 21533, 21535, 21529, -1, 21533, 21453, 21534, -1, 21532, 18238, 21531, -1, 21536, 21483, 21503, -1, 21536, 21537, 21483, -1, 21538, 21487, 21502, -1, 21536, 21503, 18215, -1, 21538, 21530, 21487, -1, 21539, 21528, 21537, -1, 21539, 21526, 21528, -1, 21540, 21435, 21455, -1, 21541, 21532, 21531, -1, 21540, 21529, 21526, -1, 21541, 21531, 21530, -1, 21540, 21455, 21533, -1, 21540, 21533, 21529, -1, 21542, 18257, 18249, -1, 21542, 21438, 21441, -1, 21542, 21441, 18257, -1, 21543, 18215, 18240, -1, 21542, 18249, 21532, -1, 21543, 21537, 21536, -1, 21543, 21539, 21537, -1, 21544, 21502, 21501, -1, 21543, 21536, 18215, -1, 21545, 21434, 21435, -1, 21545, 21435, 21540, -1, 21545, 21526, 21539, -1, 21544, 21538, 21502, -1, 21545, 21540, 21526, -1, 21546, 21530, 21538, -1, 21547, 18239, 21434, -1, 21547, 18240, 18239, -1, 21546, 21541, 21530, -1, 21547, 21434, 21545, -1, 21547, 21543, 18240, -1, 21441, 18281, 18257, -1, 21547, 21539, 21543, -1, 21547, 21545, 21539, -1, 21548, 21439, 21438, -1, 21548, 21438, 21542, -1, 21548, 21532, 21541, -1, 21548, 21542, 21532, -1, 21549, 21501, 21499, -1, 21549, 21544, 21501, -1, 21550, 21546, 21538, -1, 21550, 21538, 21544, -1, 21551, 21439, 21548, -1, 21551, 21440, 21439, -1, 21551, 21548, 21541, -1, 21551, 21541, 21546, -1, 21552, 21499, 21497, -1, 21552, 21549, 21499, -1, 21553, 21544, 21549, -1, 21553, 21550, 21544, -1, 21554, 21443, 21440, -1, 21554, 21551, 21546, -1, 21554, 21546, 21550, -1, 21554, 21440, 21551, -1, 21555, 21497, 21496, -1, 21555, 21552, 21497, -1, 21556, 21553, 21549, -1, 21556, 21549, 21552, -1, 21557, 21554, 21550, -1, 21557, 21446, 21443, -1, 21557, 21443, 21554, -1, 21557, 21550, 21553, -1, 21558, 21496, 21494, -1, 21558, 21555, 21496, -1, 21559, 21552, 21555, -1, 21559, 21556, 21552, -1, 21560, 21553, 21556, -1, 21560, 21446, 21557, -1, 21560, 21449, 21446, -1, 21560, 21557, 21553, -1, 21527, 21494, 21493, -1, 21527, 21558, 21494, -1, 21535, 21555, 21558, -1, 18215, 21503, 18282, -1, 21535, 21559, 21555, -1, 21561, 21560, 21556, -1, 21561, 21449, 21560, -1, 21561, 21451, 21449, -1, 21561, 21556, 21559, -1, 21528, 21493, 21491, -1, 21528, 21527, 21493, -1, 21529, 21535, 21558, -1, 21529, 21558, 21527, -1, 21534, 21559, 21535, -1, 18236, 21434, 18239, -1, 21534, 21561, 21559, -1, 21534, 21453, 21451, -1, 21534, 21451, 21561, -1, 21531, 18238, 18233, -1, 21537, 21491, 21483, -1, 21531, 18233, 21488, -1, 21537, 21528, 21491, -1, 21530, 21488, 21487, -1, 21562, 21563, 19103, -1, 18373, 21564, 18363, -1, 18152, 21564, 18151, -1, 21565, 21564, 21566, -1, 21567, 21568, 21569, -1, 21566, 21564, 18152, -1, 21570, 21564, 21565, -1, 18369, 21568, 18370, -1, 18363, 21564, 21570, -1, 18151, 21564, 18373, -1, 18370, 21568, 21571, -1, 21571, 21568, 21567, -1, 18154, 19100, 18204, -1, 21562, 21572, 21563, -1, 21569, 21572, 21562, -1, 19104, 21573, 19106, -1, 21563, 21573, 19104, -1, 18374, 21574, 18369, -1, 18369, 21574, 21568, -1, 21568, 21574, 21569, -1, 21569, 21574, 21572, -1, 21563, 21575, 21573, -1, 21572, 21575, 21563, -1, 19106, 21576, 19107, -1, 21573, 21576, 19106, -1, 18377, 21577, 18374, -1, 21574, 21577, 21572, -1, 18374, 21577, 21574, -1, 21572, 21577, 21575, -1, 21575, 21578, 21573, -1, 21573, 21578, 21576, -1, 19107, 21579, 19108, -1, 21576, 21579, 19107, -1, 18376, 21580, 18377, -1, 21577, 21580, 21575, -1, 21575, 21580, 21578, -1, 18377, 21580, 21577, -1, 21578, 21581, 21576, -1, 21576, 21581, 21579, -1, 21579, 21582, 19108, -1, 19108, 21582, 19109, -1, 18380, 21583, 18376, -1, 18376, 21583, 21580, -1, 21578, 21583, 21581, -1, 21580, 21583, 21578, -1, 21581, 21584, 21579, -1, 21579, 21584, 21582, -1, 21582, 21585, 19109, -1, 19109, 21585, 19090, -1, 18380, 21586, 21583, -1, 18379, 21586, 18380, -1, 21583, 21586, 21581, -1, 21581, 21586, 21584, -1, 21584, 21587, 21582, -1, 21582, 21587, 21585, -1, 19090, 21588, 19089, -1, 21585, 21588, 19090, -1, 18382, 21589, 18379, -1, 18379, 21589, 21586, -1, 21584, 21589, 21587, -1, 21586, 21589, 21584, -1, 21587, 21590, 21585, -1, 21585, 21590, 21588, -1, 19089, 21591, 19087, -1, 21588, 21591, 19089, -1, 18383, 21592, 18382, -1, 18382, 21592, 21589, -1, 21589, 21592, 21587, -1, 21587, 21592, 21590, -1, 21590, 21593, 21588, -1, 21588, 21593, 21591, -1, 19087, 21594, 19085, -1, 21591, 21594, 19087, -1, 18373, 18176, 18151, -1, 18364, 21595, 18383, -1, 18383, 21595, 21592, -1, 19100, 21596, 19102, -1, 21592, 21595, 21590, -1, 18154, 21596, 19100, -1, 21590, 21595, 21593, -1, 18156, 21567, 18154, -1, 21593, 21565, 21591, -1, 21591, 21565, 21594, -1, 18154, 21567, 21596, -1, 19102, 21562, 19103, -1, 19085, 21597, 18212, -1, 18212, 21597, 18211, -1, 21596, 21562, 19102, -1, 21594, 21597, 19085, -1, 18370, 21571, 18210, -1, 18165, 21571, 18156, -1, 18210, 21571, 18165, -1, 18363, 21570, 18364, -1, 18364, 21570, 21595, -1, 21593, 21570, 21565, -1, 18156, 21571, 21567, -1, 21595, 21570, 21593, -1, 21567, 21569, 21596, -1, 18211, 21566, 18152, -1, 21596, 21569, 21562, -1, 21565, 21566, 21594, -1, 21597, 21566, 18211, -1, 21594, 21566, 21597, -1, 19103, 21563, 19104, -1, 21598, 18083, 21599, -1, 21600, 21601, 21602, -1, 21603, 21513, 21506, -1, 21603, 21604, 21513, -1, 21600, 21605, 21601, -1, 18083, 18082, 21514, -1, 21606, 21479, 21473, -1, 21606, 21473, 21607, -1, 21606, 21608, 21605, -1, 21606, 21607, 21608, -1, 21609, 21598, 21599, -1, 21609, 21599, 21604, -1, 21610, 21508, 18143, -1, 21611, 18110, 18100, -1, 21610, 21509, 21508, -1, 21611, 18111, 18110, -1, 21610, 18143, 18086, -1, 21611, 21468, 18111, -1, 21610, 21612, 21509, -1, 21611, 18100, 21598, -1, 21613, 21506, 21525, -1, 21614, 21600, 21602, -1, 21614, 21602, 21612, -1, 21613, 21603, 21506, -1, 21615, 21481, 21479, -1, 21616, 21604, 21603, -1, 21615, 21479, 21606, -1, 21615, 21605, 21600, -1, 21616, 21609, 21604, -1, 21615, 21606, 21605, -1, 21617, 18086, 18085, -1, 21618, 21466, 21468, -1, 21618, 21598, 21609, -1, 21617, 21610, 18086, -1, 21618, 21611, 21598, -1, 21617, 21612, 21610, -1, 21618, 21468, 21611, -1, 21617, 21614, 21612, -1, 21619, 21600, 21614, -1, 21619, 21461, 21481, -1, 21619, 21615, 21600, -1, 21620, 21525, 21524, -1, 21619, 21481, 21615, -1, 21620, 21613, 21525, -1, 21621, 18104, 21460, -1, 21621, 18085, 18104, -1, 21621, 21460, 21461, -1, 21621, 21619, 21614, -1, 21621, 21617, 18085, -1, 21621, 21614, 21617, -1, 21621, 21461, 21619, -1, 21622, 21603, 21613, -1, 21622, 21616, 21603, -1, 21623, 21463, 21466, -1, 21623, 21618, 21609, -1, 21623, 21466, 21618, -1, 21623, 21609, 21616, -1, 21624, 21524, 21523, -1, 21624, 21620, 21524, -1, 21625, 21613, 21620, -1, 21625, 21622, 21613, -1, 21626, 21464, 21463, -1, 21626, 21623, 21616, -1, 21626, 21616, 21622, -1, 21626, 21463, 21623, -1, 21627, 21523, 21521, -1, 21627, 21624, 21523, -1, 21628, 21625, 21620, -1, 21628, 21620, 21624, -1, 21629, 21622, 21625, -1, 21629, 21465, 21464, -1, 21629, 21626, 21622, -1, 21629, 21464, 21626, -1, 21630, 21521, 21519, -1, 21630, 21627, 21521, -1, 21631, 21628, 21624, -1, 21631, 21624, 21627, -1, 21632, 21625, 21628, -1, 21632, 21465, 21629, -1, 21632, 21467, 21465, -1, 21632, 21629, 21625, -1, 21601, 21519, 21518, -1, 21601, 21630, 21519, -1, 21608, 21631, 21627, -1, 21608, 21627, 21630, -1, 21633, 21632, 21628, -1, 21633, 21467, 21632, -1, 21633, 21469, 21467, -1, 21633, 21628, 21631, -1, 21602, 21518, 21516, -1, 21602, 21601, 21518, -1, 18115, 21460, 18104, -1, 21605, 21630, 21601, -1, 21599, 18083, 21514, -1, 21605, 21608, 21630, -1, 21604, 21514, 21513, -1, 21607, 21469, 21633, -1, 21607, 21473, 21469, -1, 21607, 21633, 21631, -1, 21604, 21599, 21514, -1, 21607, 21631, 21608, -1, 21598, 18100, 18083, -1, 21612, 21516, 21509, -1, 21612, 21602, 21516, -1, 19088, 21634, 19110, -1, 21635, 21634, 19088, -1, 18348, 21636, 18349, -1, 18007, 21636, 18006, -1, 21637, 21636, 21638, -1, 21639, 21640, 21641, -1, 21638, 21636, 18007, -1, 21642, 21636, 21637, -1, 18341, 21640, 18342, -1, 18349, 21636, 21642, -1, 18006, 21636, 18348, -1, 18342, 21640, 21643, -1, 21643, 21640, 21639, -1, 18016, 19084, 18065, -1, 21635, 21644, 21634, -1, 21641, 21644, 21635, -1, 19110, 21645, 19099, -1, 21634, 21645, 19110, -1, 18350, 21646, 18341, -1, 18341, 21646, 21640, -1, 21640, 21646, 21641, -1, 21641, 21646, 21644, -1, 21634, 21647, 21645, -1, 21644, 21647, 21634, -1, 19099, 21648, 19098, -1, 21645, 21648, 19099, -1, 18353, 21649, 18350, -1, 21644, 21649, 21647, -1, 21646, 21649, 21644, -1, 18350, 21649, 21646, -1, 21645, 21650, 21648, -1, 21647, 21650, 21645, -1, 19098, 21651, 19097, -1, 21648, 21651, 19098, -1, 21647, 21652, 21650, -1, 18352, 21652, 18353, -1, 21649, 21652, 21647, -1, 18353, 21652, 21649, -1, 21648, 21653, 21651, -1, 21650, 21653, 21648, -1, 21651, 21654, 19097, -1, 19097, 21654, 19096, -1, 18356, 21655, 18352, -1, 21650, 21655, 21653, -1, 18352, 21655, 21652, -1, 21652, 21655, 21650, -1, 21653, 21656, 21651, -1, 21651, 21656, 21654, -1, 21654, 21657, 19096, -1, 19096, 21657, 19095, -1, 18356, 21658, 21655, -1, 18355, 21658, 18356, -1, 21655, 21658, 21653, -1, 21653, 21658, 21656, -1, 21656, 21659, 21654, -1, 21654, 21659, 21657, -1, 19095, 21660, 19093, -1, 21657, 21660, 19095, -1, 18358, 21661, 18355, -1, 18355, 21661, 21658, -1, 21656, 21661, 21659, -1, 21658, 21661, 21656, -1, 21659, 21662, 21657, -1, 21657, 21662, 21660, -1, 19093, 21663, 19091, -1, 21660, 21663, 19093, -1, 18361, 21664, 18358, -1, 18358, 21664, 21661, -1, 21661, 21664, 21659, -1, 21659, 21664, 21662, -1, 21662, 21665, 21660, -1, 21660, 21665, 21663, -1, 19091, 21666, 19094, -1, 21663, 21666, 19091, -1, 18348, 18037, 18006, -1, 18360, 21667, 18361, -1, 18361, 21667, 21664, -1, 19084, 21668, 19086, -1, 21664, 21667, 21662, -1, 18016, 21668, 19084, -1, 21662, 21667, 21665, -1, 18027, 21639, 18016, -1, 21665, 21637, 21663, -1, 21663, 21637, 21666, -1, 18016, 21639, 21668, -1, 19086, 21635, 19088, -1, 19094, 21669, 18072, -1, 18072, 21669, 18071, -1, 21668, 21635, 19086, -1, 21666, 21669, 19094, -1, 18342, 21643, 18032, -1, 18031, 21643, 18027, -1, 18032, 21643, 18031, -1, 18349, 21642, 18360, -1, 18360, 21642, 21667, -1, 21665, 21642, 21637, -1, 18027, 21643, 21639, -1, 21667, 21642, 21665, -1, 21639, 21641, 21668, -1, 18071, 21638, 18007, -1, 21668, 21641, 21635, -1, 21637, 21638, 21666, -1, 21669, 21638, 18071, -1, 21666, 21638, 21669, -1, 21670, 18001, 17999, -1, 21670, 17999, 21671, -1, 21672, 21673, 21674, -1, 21672, 21674, 21675, -1, 21676, 18001, 21670, -1, 21676, 18003, 18001, -1, 21677, 21675, 21678, -1, 21677, 21678, 21679, -1, 21677, 21679, 21680, -1, 17955, 21681, 21682, -1, 21677, 21680, 21683, -1, 21677, 21683, 21684, -1, 21677, 21672, 21675, -1, 21685, 17969, 21686, -1, 17957, 21682, 21687, -1, 17957, 17955, 21682, -1, 17953, 21688, 21681, -1, 17953, 21681, 17955, -1, 17959, 21687, 21689, -1, 17936, 18003, 21676, -1, 17959, 17957, 21687, -1, 17936, 21690, 18003, -1, 17947, 21691, 21692, -1, 17985, 17983, 21685, -1, 17947, 21692, 21693, -1, 17947, 21693, 21694, -1, 17951, 21695, 21688, -1, 17947, 21694, 21696, -1, 17951, 21688, 17953, -1, 17981, 17971, 17969, -1, 17981, 17969, 21685, -1, 17961, 17959, 21689, -1, 17947, 21677, 21691, -1, 17981, 21685, 17983, -1, 17961, 21689, 21686, -1, 17937, 21690, 17936, -1, 17949, 21695, 17951, -1, 17949, 21697, 21695, -1, 17937, 21698, 21690, -1, 17987, 17985, 21685, -1, 17963, 17961, 21686, -1, 17945, 21696, 21699, -1, 17979, 17973, 17971, -1, 17945, 17947, 21696, -1, 17979, 17971, 17981, -1, 17939, 21698, 17937, -1, 17939, 21700, 21698, -1, 21701, 21697, 17949, -1, 17943, 17945, 21699, -1, 21701, 21702, 21697, -1, 17943, 21699, 21703, -1, 17989, 17987, 21685, -1, 17977, 17973, 17979, -1, 17977, 17974, 17973, -1, 17941, 21700, 17939, -1, 17941, 17943, 21703, -1, 17941, 21703, 21700, -1, 17965, 17963, 21686, -1, 17991, 21685, 21704, -1, 21705, 21702, 21701, -1, 17991, 17989, 21685, -1, 17967, 17965, 21686, -1, 21706, 21707, 17974, -1, 21708, 21702, 21705, -1, 21706, 17974, 17977, -1, 17993, 21704, 21709, -1, 21710, 21708, 21705, -1, 17969, 17967, 21686, -1, 17993, 17991, 21704, -1, 21711, 21684, 21707, -1, 21711, 21707, 21706, -1, 21712, 21708, 21710, -1, 21712, 21710, 21713, -1, 17995, 21709, 21714, -1, 17995, 17993, 21709, -1, 21691, 21677, 21684, -1, 21691, 21684, 21711, -1, 17997, 17995, 21714, -1, 21671, 17997, 21714, -1, 21673, 21712, 21713, -1, 21673, 21713, 21674, -1, 17999, 17997, 21671, -1, 17990, 17986, 17988, -1, 21715, 17976, 17978, -1, 17994, 17984, 17986, -1, 17994, 17990, 17992, -1, 17994, 17986, 17990, -1, 17996, 17980, 17982, -1, 17996, 17982, 17984, -1, 17996, 17984, 17994, -1, 17998, 17980, 17996, -1, 18000, 17978, 17980, -1, 18000, 17980, 17998, -1, 21716, 21717, 21718, -1, 21719, 18000, 18002, -1, 21719, 21715, 17978, -1, 21719, 17978, 18000, -1, 21720, 21716, 21718, -1, 21721, 21722, 21715, -1, 21721, 21715, 21719, -1, 21723, 21718, 21724, -1, 21723, 21720, 21718, -1, 21725, 21724, 21726, -1, 21725, 21726, 21722, -1, 21725, 21722, 21721, -1, 21725, 21723, 21724, -1, 18002, 18003, 21719, -1, 21719, 21690, 21721, -1, 18003, 21690, 21719, -1, 21721, 21698, 21725, -1, 21690, 21698, 21721, -1, 21725, 21700, 21723, -1, 21698, 21700, 21725, -1, 21723, 21703, 21720, -1, 21700, 21703, 21723, -1, 21720, 21699, 21716, -1, 21703, 21699, 21720, -1, 21716, 21696, 21717, -1, 21699, 21696, 21716, -1, 21717, 21694, 21718, -1, 21696, 21694, 21717, -1, 21718, 21693, 21724, -1, 21694, 21693, 21718, -1, 21724, 21692, 21726, -1, 21693, 21692, 21724, -1, 21726, 21691, 21722, -1, 21692, 21691, 21726, -1, 21722, 21711, 21715, -1, 21691, 21711, 21722, -1, 21715, 21706, 17976, -1, 21711, 21706, 21715, -1, 21706, 17977, 17976, -1, 21727, 17948, 17950, -1, 17966, 17956, 17958, -1, 17966, 17958, 17960, -1, 17966, 17960, 17962, -1, 17966, 17962, 17964, -1, 17968, 17954, 17956, -1, 17968, 17956, 17966, -1, 17970, 17952, 17954, -1, 17970, 17954, 17968, -1, 17972, 17950, 17952, -1, 17972, 17952, 17970, -1, 21728, 17972, 17975, -1, 21728, 21727, 17950, -1, 21728, 17950, 17972, -1, 21729, 21730, 21731, -1, 21729, 21731, 21732, -1, 21733, 21734, 21727, -1, 21733, 21727, 21728, -1, 21735, 21736, 21729, -1, 21735, 21732, 21737, -1, 21735, 21737, 21738, -1, 21735, 21738, 21734, -1, 21735, 21729, 21732, -1, 21735, 21734, 21733, -1, 17975, 17974, 21728, -1, 17974, 21707, 21728, -1, 21728, 21684, 21733, -1, 21707, 21684, 21728, -1, 21733, 21683, 21735, -1, 21684, 21683, 21733, -1, 21735, 21680, 21736, -1, 21683, 21680, 21735, -1, 21736, 21679, 21729, -1, 21680, 21679, 21736, -1, 21729, 21678, 21730, -1, 21679, 21678, 21729, -1, 21730, 21675, 21731, -1, 21678, 21675, 21730, -1, 21731, 21674, 21732, -1, 21675, 21674, 21731, -1, 21732, 21713, 21737, -1, 21674, 21713, 21732, -1, 21737, 21710, 21738, -1, 21713, 21710, 21737, -1, 21738, 21705, 21734, -1, 21710, 21705, 21738, -1, 21734, 21701, 21727, -1, 21705, 21701, 21734, -1, 21727, 17949, 17948, -1, 21701, 17949, 21727, -1, 21677, 20712, 21672, -1, 20713, 20712, 21677, -1, 21672, 20711, 21673, -1, 20712, 20711, 21672, -1, 21673, 20710, 21712, -1, 20711, 20710, 21673, -1, 21712, 20709, 21708, -1, 20710, 20709, 21712, -1, 21708, 20707, 21702, -1, 20709, 20707, 21708, -1, 21702, 20706, 21697, -1, 20707, 20706, 21702, -1, 21697, 20705, 21695, -1, 20706, 20705, 21697, -1, 21695, 20704, 21688, -1, 20705, 20704, 21695, -1, 21688, 20703, 21681, -1, 20704, 20703, 21688, -1, 21681, 20702, 21682, -1, 20703, 20702, 21681, -1, 21682, 20701, 21687, -1, 20702, 20701, 21682, -1, 21687, 20700, 21689, -1, 20701, 20700, 21687, -1, 21689, 20698, 21686, -1, 20700, 20698, 21689, -1, 20698, 20697, 21686, -1, 21686, 20697, 21685, -1, 17947, 20713, 21677, -1, 17946, 20713, 17947, -1, 20697, 21704, 21685, -1, 20697, 20696, 21704, -1, 20696, 21709, 21704, -1, 20696, 20693, 21709, -1, 20693, 21714, 21709, -1, 20693, 20690, 21714, -1, 20690, 21671, 21714, -1, 20690, 20689, 21671, -1, 20689, 21670, 21671, -1, 20689, 20692, 21670, -1, 20692, 21676, 21670, -1, 20692, 20695, 21676, -1, 20695, 17936, 21676, -1, 20695, 17934, 17936, -1, 20729, 21433, 21415, -1, 20729, 20727, 21433, -1, 20727, 21432, 21433, -1, 20727, 20726, 21432, -1, 20726, 21430, 21432, -1, 20726, 20725, 21430, -1, 20725, 21427, 21430, -1, 20725, 20724, 21427, -1, 20724, 21423, 21427, -1, 20724, 20722, 21423, -1, 20722, 21421, 21423, -1, 20722, 20719, 21421, -1, 20719, 21418, 21421, -1, 20719, 20750, 21418, -1, 20750, 21419, 21418, -1, 20750, 20749, 21419, -1, 21419, 20748, 21420, -1, 20749, 20748, 21419, -1, 21420, 20747, 21422, -1, 20748, 20747, 21420, -1, 21422, 20746, 21426, -1, 20747, 20746, 21422, -1, 21426, 20743, 21428, -1, 20746, 20743, 21426, -1, 21428, 20735, 21425, -1, 20743, 20735, 21428, -1, 20735, 20718, 21425, -1, 21425, 20718, 21424, -1, 17932, 20729, 21415, -1, 17933, 20729, 17932, -1, 21424, 20718, 21429, -1, 21429, 20715, 21431, -1, 20718, 20715, 21429, -1, 21431, 20714, 21417, -1, 20715, 20714, 21431, -1, 21417, 20717, 21416, -1, 20714, 20717, 21417, -1, 21416, 20723, 17918, -1, 20717, 20723, 21416, -1, 20723, 17916, 17918, -1, 20950, 17880, 17881, -1, 20950, 17881, 20948, -1, 21739, 21062, 21064, -1, 21739, 21064, 21740, -1, 21741, 21740, 21742, -1, 21741, 21739, 21740, -1, 21743, 21741, 21742, -1, 21744, 21742, 21065, -1, 21744, 21743, 21742, -1, 21745, 21744, 21065, -1, 21746, 21745, 21065, -1, 21067, 21746, 21065, -1, 21747, 19117, 19119, -1, 21747, 19119, 21748, -1, 21749, 21748, 21750, -1, 21749, 21747, 21748, -1, 21751, 21750, 21752, -1, 21751, 21749, 21750, -1, 21753, 21752, 21754, -1, 21753, 21751, 21752, -1, 20951, 21754, 20949, -1, 20951, 21753, 21754, -1, 21755, 20952, 20953, -1, 21755, 20953, 21756, -1, 21757, 21756, 21758, -1, 21757, 21755, 21756, -1, 21759, 21758, 21760, -1, 21759, 21757, 21758, -1, 21761, 21760, 21762, -1, 21761, 21759, 21760, -1, 21059, 21762, 21057, -1, 21059, 21761, 21762, -1, 21109, 21763, 21764, -1, 21106, 21763, 21109, -1, 21764, 21765, 21766, -1, 21763, 21765, 21764, -1, 21766, 21767, 21768, -1, 21765, 21767, 21766, -1, 21768, 21105, 21103, -1, 21767, 21105, 21768, -1, 21769, 20586, 20588, -1, 21769, 20588, 21770, -1, 21771, 21770, 21772, -1, 21771, 21769, 21770, -1, 21773, 21771, 21772, -1, 21774, 21772, 21775, -1, 21774, 21775, 21776, -1, 21774, 21773, 21772, -1, 21777, 21776, 21778, -1, 21777, 21774, 21776, -1, 21779, 21777, 21778, -1, 21780, 21778, 21781, -1, 21780, 21779, 21778, -1, 21104, 21781, 21102, -1, 21104, 21780, 21781, -1, 21782, 21100, 21099, -1, 21782, 21099, 21783, -1, 21782, 21783, 21784, -1, 21785, 21782, 21784, -1, 21786, 21784, 21787, -1, 21786, 21785, 21784, -1, 21788, 21787, 21789, -1, 21788, 21786, 21787, -1, 21107, 21789, 21108, -1, 21107, 21788, 21789, -1, 21196, 21197, 21790, -1, 21790, 21791, 21792, -1, 21197, 21791, 21790, -1, 21791, 21793, 21792, -1, 21792, 21794, 21795, -1, 21793, 21794, 21792, -1, 21795, 21796, 21797, -1, 21794, 21796, 21795, -1, 21797, 21177, 21178, -1, 21796, 21177, 21797, -1, 21798, 20963, 20962, -1, 21798, 20962, 21799, -1, 21800, 21799, 21801, -1, 21800, 21798, 21799, -1, 21802, 21801, 21803, -1, 21802, 21800, 21801, -1, 21804, 21803, 21805, -1, 21804, 21805, 21806, -1, 21804, 21802, 21803, -1, 17473, 21806, 20966, -1, 17473, 21804, 21806, -1, 20232, 20237, 21807, -1, 21808, 21807, 21809, -1, 21808, 20232, 21807, -1, 21810, 21809, 21811, -1, 21810, 21808, 21809, -1, 21812, 21811, 21813, -1, 21812, 21813, 21814, -1, 21812, 21810, 21811, -1, 21815, 21814, 21816, -1, 21815, 21812, 21814, -1, 21817, 21816, 21818, -1, 21817, 21818, 21819, -1, 21817, 21815, 21816, -1, 21820, 21819, 21821, -1, 21820, 21821, 21822, -1, 21820, 21817, 21819, -1, 21823, 21822, 17474, -1, 21823, 21820, 21822, -1, 20965, 21823, 17474, -1, 21824, 20972, 20970, -1, 21824, 20970, 21825, -1, 21826, 21824, 21825, -1, 21827, 21825, 21828, -1, 21827, 21826, 21825, -1, 21829, 21828, 21830, -1, 21829, 21827, 21828, -1, 21831, 21830, 21832, -1, 21831, 21829, 21830, -1, 20249, 21832, 20250, -1, 20249, 21831, 21832, -1, 21833, 20971, 17781, -1, 21833, 17781, 17779, -1, 21834, 17779, 17761, -1, 21834, 21833, 17779, -1, 21835, 17761, 17763, -1, 21835, 21834, 17761, -1, 21836, 17763, 17764, -1, 21836, 17764, 17780, -1, 21836, 21835, 17763, -1, 21837, 17780, 21838, -1, 21837, 21836, 17780, -1, 21839, 21838, 21840, -1, 21839, 21837, 21838, -1, 21841, 21839, 21840, -1, 21842, 21840, 21843, -1, 21842, 21841, 21840, -1, 21844, 21843, 21845, -1, 21844, 21842, 21843, -1, 17485, 21844, 21845, -1, 17486, 21845, 20967, -1, 17486, 17485, 21845, -1, 17487, 17486, 20967, -1, 21846, 20980, 20981, -1, 21846, 20981, 21847, -1, 21848, 21846, 21847, -1, 21849, 21847, 21850, -1, 21849, 21848, 21847, -1, 21851, 21850, 21852, -1, 21851, 21849, 21850, -1, 21853, 21852, 21854, -1, 21853, 21851, 21852, -1, 20977, 21854, 20978, -1, 20977, 21853, 21854, -1, 21855, 20982, 17443, -1, 21855, 17443, 17441, -1, 21856, 17441, 17423, -1, 21856, 21855, 17441, -1, 21857, 17423, 17425, -1, 21857, 21856, 17423, -1, 21858, 17425, 17426, -1, 21858, 17426, 17442, -1, 21858, 21857, 17425, -1, 21859, 17442, 21860, -1, 21859, 21858, 17442, -1, 21861, 21860, 21862, -1, 21861, 21859, 21860, -1, 21863, 21861, 21862, -1, 21864, 21862, 21865, -1, 21864, 21863, 21862, -1, 21866, 21865, 21867, -1, 21866, 21864, 21865, -1, 17498, 21866, 21867, -1, 17499, 21867, 20973, -1, 17499, 17498, 21867, -1, 17500, 17499, 20973, -1, 21868, 20990, 20991, -1, 21868, 20991, 21869, -1, 21870, 21868, 21869, -1, 21871, 21869, 21872, -1, 21871, 21870, 21869, -1, 21873, 21872, 21874, -1, 21873, 21871, 21872, -1, 21875, 21874, 21876, -1, 21875, 21873, 21874, -1, 20987, 21876, 20988, -1, 20987, 21875, 21876, -1, 21877, 20992, 17390, -1, 21877, 17390, 17388, -1, 21878, 17388, 17370, -1, 21878, 21877, 17388, -1, 21879, 17370, 17372, -1, 21879, 21878, 17370, -1, 21880, 17372, 17373, -1, 21880, 17373, 17389, -1, 21880, 21879, 17372, -1, 21881, 17389, 21882, -1, 21881, 21880, 17389, -1, 21883, 21882, 21884, -1, 21883, 21881, 21882, -1, 21885, 21883, 21884, -1, 21886, 21884, 21887, -1, 21886, 21885, 21884, -1, 21888, 21887, 21889, -1, 21888, 21886, 21887, -1, 17511, 21888, 21889, -1, 17512, 21889, 20983, -1, 17512, 17511, 21889, -1, 17513, 17512, 20983, -1, 21890, 21000, 21001, -1, 21890, 21001, 21891, -1, 21892, 21890, 21891, -1, 21893, 21891, 21894, -1, 21893, 21892, 21891, -1, 21895, 21894, 21896, -1, 21895, 21893, 21894, -1, 21897, 21896, 21898, -1, 21897, 21895, 21896, -1, 20997, 21898, 20998, -1, 20997, 21897, 21898, -1, 21899, 21002, 17337, -1, 21899, 17337, 17335, -1, 21900, 17335, 17317, -1, 21900, 21899, 17335, -1, 21901, 17317, 17319, -1, 21901, 21900, 17317, -1, 21902, 17319, 17320, -1, 21902, 17320, 17336, -1, 21902, 21901, 17319, -1, 21903, 17336, 21904, -1, 21903, 21902, 17336, -1, 21905, 21904, 21906, -1, 21905, 21903, 21904, -1, 21907, 21905, 21906, -1, 21908, 21906, 21909, -1, 21908, 21907, 21906, -1, 21910, 21909, 21911, -1, 21910, 21908, 21909, -1, 17524, 21910, 21911, -1, 17525, 21911, 20993, -1, 17525, 17524, 21911, -1, 17526, 17525, 20993, -1, 21912, 21010, 21011, -1, 21912, 21011, 21913, -1, 21914, 21912, 21913, -1, 21915, 21913, 21916, -1, 21915, 21914, 21913, -1, 21917, 21916, 21918, -1, 21917, 21915, 21916, -1, 21919, 21918, 21920, -1, 21919, 21917, 21918, -1, 21007, 21920, 21008, -1, 21007, 21919, 21920, -1, 21921, 21012, 17284, -1, 21921, 17284, 17282, -1, 21922, 17282, 17264, -1, 21922, 21921, 17282, -1, 21923, 17264, 17266, -1, 21923, 21922, 17264, -1, 21924, 17266, 17267, -1, 21924, 17267, 17283, -1, 21924, 21923, 17266, -1, 21925, 17283, 21926, -1, 21925, 21924, 17283, -1, 21927, 21926, 21928, -1, 21927, 21925, 21926, -1, 21929, 21927, 21928, -1, 21930, 21928, 21931, -1, 21930, 21929, 21928, -1, 21932, 21931, 21933, -1, 21932, 21930, 21931, -1, 17537, 21932, 21933, -1, 17538, 21933, 21003, -1, 17538, 17537, 21933, -1, 17539, 17538, 21003, -1, 21934, 21022, 17231, -1, 21934, 17231, 17229, -1, 21935, 17229, 17211, -1, 21935, 21934, 17229, -1, 21936, 17211, 17213, -1, 21936, 21935, 17211, -1, 21937, 17213, 17214, -1, 21937, 17214, 17230, -1, 21937, 21936, 17213, -1, 21938, 17230, 21939, -1, 21938, 21937, 17230, -1, 21940, 21939, 21941, -1, 21940, 21938, 21939, -1, 21942, 21940, 21941, -1, 21943, 21941, 21944, -1, 21943, 21942, 21941, -1, 21945, 21944, 21946, -1, 21945, 21943, 21944, -1, 17550, 21945, 21946, -1, 17551, 21946, 21013, -1, 17551, 17550, 21946, -1, 17552, 17551, 21013, -1, 21947, 21020, 21021, -1, 21947, 21021, 21948, -1, 21949, 21947, 21948, -1, 21950, 21948, 21951, -1, 21950, 21949, 21948, -1, 21952, 21951, 21953, -1, 21952, 21950, 21951, -1, 21954, 21953, 21955, -1, 21954, 21952, 21953, -1, 21017, 21955, 21018, -1, 21017, 21954, 21955, -1, 21956, 21030, 21031, -1, 21956, 21031, 21957, -1, 21958, 21956, 21957, -1, 21959, 21957, 21960, -1, 21959, 21958, 21957, -1, 21961, 21960, 21962, -1, 21961, 21959, 21960, -1, 21963, 21962, 21964, -1, 21963, 21961, 21962, -1, 21027, 21964, 21028, -1, 21027, 21963, 21964, -1, 21965, 21032, 17608, -1, 21965, 17608, 17606, -1, 21966, 17606, 17588, -1, 21966, 21965, 17606, -1, 21967, 17588, 17590, -1, 21967, 21966, 17588, -1, 21968, 17590, 17591, -1, 21968, 17591, 17607, -1, 21968, 21967, 17590, -1, 21969, 17607, 21970, -1, 21969, 21968, 17607, -1, 21971, 21970, 21972, -1, 21971, 21969, 21970, -1, 21973, 21971, 21972, -1, 21974, 21972, 21975, -1, 21974, 21973, 21972, -1, 21976, 21975, 21977, -1, 21976, 21974, 21975, -1, 17642, 21976, 21977, -1, 17643, 21977, 21023, -1, 17643, 17642, 21977, -1, 17644, 17643, 21023, -1, 21978, 21040, 21041, -1, 21978, 21041, 21979, -1, 21980, 21978, 21979, -1, 21981, 21979, 21982, -1, 21981, 21980, 21979, -1, 21983, 21982, 21984, -1, 21983, 21981, 21982, -1, 21985, 21984, 21986, -1, 21985, 21983, 21984, -1, 21037, 21986, 21038, -1, 21037, 21985, 21986, -1, 21987, 21042, 17107, -1, 21987, 17107, 17105, -1, 21988, 17105, 17087, -1, 21988, 21987, 17105, -1, 21989, 17087, 17089, -1, 21989, 21988, 17087, -1, 21990, 17089, 17090, -1, 21990, 17090, 17106, -1, 21990, 21989, 17089, -1, 21991, 17106, 21992, -1, 21991, 21990, 17106, -1, 21993, 21992, 21994, -1, 21993, 21991, 21992, -1, 21995, 21993, 21994, -1, 21996, 21994, 21997, -1, 21996, 21995, 21994, -1, 21998, 21997, 21999, -1, 21998, 21996, 21997, -1, 17563, 21998, 21999, -1, 17564, 21999, 21033, -1, 17564, 17563, 21999, -1, 17565, 17564, 21033, -1, 22000, 21052, 17178, -1, 22000, 17178, 17176, -1, 22001, 17176, 17158, -1, 22001, 22000, 17176, -1, 22002, 17158, 17160, -1, 22002, 22001, 17158, -1, 22003, 17160, 17161, -1, 22003, 17161, 17177, -1, 22003, 22002, 17160, -1, 22004, 17177, 22005, -1, 22004, 22003, 17177, -1, 22006, 22005, 22007, -1, 22006, 22004, 22005, -1, 22008, 22006, 22007, -1, 22009, 22007, 22010, -1, 22009, 22008, 22007, -1, 22011, 22010, 22012, -1, 22011, 22009, 22010, -1, 17576, 22011, 22012, -1, 17577, 22012, 21043, -1, 17577, 17576, 22012, -1, 17578, 17577, 21043, -1, 22013, 21050, 21051, -1, 22013, 21051, 22014, -1, 22015, 22013, 22014, -1, 22016, 22014, 22017, -1, 22016, 22015, 22014, -1, 22018, 22017, 22019, -1, 22018, 22016, 22017, -1, 22020, 22019, 22021, -1, 22020, 22018, 22019, -1, 21047, 22021, 21048, -1, 21047, 22020, 22021, -1, 17675, 21053, 21055, -1, 17675, 21055, 22022, -1, 17672, 17675, 22022, -1, 17687, 17672, 22022, -1, 17685, 22022, 22023, -1, 17685, 17687, 22022, -1, 17692, 17685, 22023, -1, 17696, 22023, 22024, -1, 17696, 17692, 22023, -1, 17670, 22024, 22025, -1, 17670, 22025, 22026, -1, 17670, 17696, 22024, -1, 17669, 22026, 20581, -1, 17669, 17670, 22026, -1, 22027, 20631, 22028, -1, 22027, 20632, 20631, -1, 22029, 22027, 22028, -1, 22030, 22028, 22031, -1, 22030, 22029, 22028, -1, 22032, 22031, 20135, -1, 22032, 20135, 20136, -1, 22032, 22030, 22031, -1, 22033, 20136, 20138, -1, 22033, 20138, 20140, -1, 22033, 20140, 20141, -1, 22033, 20141, 20075, -1, 22033, 22032, 20136, -1, 22034, 20075, 20076, -1, 22034, 20076, 20070, -1, 22034, 20070, 20071, -1, 22034, 20071, 20072, -1, 22034, 20072, 20073, -1, 22034, 20073, 20065, -1, 22034, 22033, 20075, -1, 22035, 20065, 20067, -1, 22035, 22034, 20065, -1, 20583, 20067, 20082, -1, 20583, 22035, 20067, -1, 22036, 20957, 20960, -1, 22036, 20960, 22037, -1, 22038, 22037, 22039, -1, 22038, 22036, 22037, -1, 22040, 22039, 22041, -1, 22040, 22038, 22039, -1, 19111, 22041, 19118, -1, 19111, 22040, 22041, -1, 22042, 21114, 21111, -1, 21222, 22042, 21111, -1, 21224, 22043, 22042, -1, 21224, 22042, 21222, -1, 20957, 22036, 22043, -1, 20957, 22043, 21224, -1, 22038, 22043, 22036, -1, 22044, 21114, 22042, -1, 22044, 22042, 22043, -1, 22044, 22043, 22038, -1, 22045, 22038, 22040, -1, 22045, 22044, 22038, -1, 19111, 22045, 22040, -1, 19111, 19113, 22046, -1, 22045, 22046, 22047, -1, 22045, 19111, 22046, -1, 22044, 22047, 21112, -1, 22044, 22045, 22047, -1, 21114, 22044, 21112, -1, 17703, 20809, 22048, -1, 17704, 17703, 22048, -1, 17723, 22048, 22049, -1, 17723, 17704, 22048, -1, 17720, 22049, 22050, -1, 17720, 17723, 22049, -1, 17717, 22050, 22051, -1, 17717, 17720, 22050, -1, 17711, 22051, 22052, -1, 17711, 17717, 22051, -1, 17710, 22052, 22053, -1, 17710, 17711, 22052, -1, 17700, 22054, 19122, -1, 17700, 22053, 22054, -1, 17700, 17710, 22053, -1, 17701, 17700, 19122, -1, 21238, 22055, 22056, -1, 21238, 22057, 22055, -1, 21238, 22058, 22057, -1, 21238, 22059, 22058, -1, 21238, 20181, 22059, -1, 20809, 21239, 22048, -1, 22060, 19122, 22054, -1, 22060, 22054, 22053, -1, 22060, 22053, 22052, -1, 22060, 22061, 19121, -1, 22060, 22062, 22061, -1, 22060, 22056, 22062, -1, 22060, 19121, 19122, -1, 22063, 22052, 22051, -1, 22063, 22051, 22050, -1, 22063, 22056, 22060, -1, 22063, 21238, 22056, -1, 22063, 22060, 22052, -1, 22064, 22050, 22049, -1, 22064, 22049, 22048, -1, 22064, 21239, 21238, -1, 22064, 21238, 22063, -1, 22064, 22063, 22050, -1, 22064, 22048, 21239, -1, 22059, 20181, 20180, -1, 22059, 20180, 22065, -1, 22058, 22065, 22066, -1, 22058, 22059, 22065, -1, 22057, 22066, 22067, -1, 22057, 22058, 22066, -1, 22055, 22067, 22068, -1, 22055, 22057, 22067, -1, 22056, 22068, 22069, -1, 22056, 22055, 22068, -1, 22062, 22069, 22070, -1, 22062, 22056, 22069, -1, 22061, 22071, 19120, -1, 22061, 22070, 22071, -1, 22061, 22062, 22070, -1, 19121, 22061, 19120, -1, 21240, 22072, 22073, -1, 21240, 22074, 22072, -1, 21240, 22075, 22074, -1, 21240, 22076, 22075, -1, 21240, 20156, 22076, -1, 20180, 21241, 22065, -1, 22077, 19120, 22071, -1, 22077, 22071, 22070, -1, 22077, 22070, 22069, -1, 22077, 22078, 19116, -1, 22077, 22079, 22078, -1, 22077, 22073, 22079, -1, 22077, 19116, 19120, -1, 22080, 22069, 22068, -1, 22080, 22068, 22067, -1, 22080, 22073, 22077, -1, 22080, 21240, 22073, -1, 22080, 22077, 22069, -1, 22081, 22067, 22066, -1, 22081, 22066, 22065, -1, 22081, 21241, 21240, -1, 22081, 21240, 22080, -1, 22081, 22080, 22067, -1, 22081, 22065, 21241, -1, 20156, 20155, 21244, -1, 22076, 21244, 21243, -1, 22076, 20156, 21244, -1, 22075, 21243, 21242, -1, 22075, 21242, 22082, -1, 22075, 22076, 21243, -1, 22074, 22082, 22083, -1, 22074, 22083, 22084, -1, 22074, 22075, 22082, -1, 22072, 22084, 22085, -1, 22072, 22085, 22086, -1, 22072, 22074, 22084, -1, 22073, 22086, 22087, -1, 22073, 22072, 22086, -1, 22079, 22087, 22088, -1, 22079, 22073, 22087, -1, 22078, 22088, 22089, -1, 22078, 22079, 22088, -1, 19116, 22089, 19112, -1, 19116, 22078, 22089, -1, 20629, 22090, 20627, -1, 20627, 22090, 22091, -1, 22091, 22090, 22092, -1, 22092, 22093, 22094, -1, 22090, 22093, 22092, -1, 22094, 22095, 22096, -1, 22093, 22095, 22094, -1, 22096, 22097, 22098, -1, 22095, 22097, 22096, -1, 22098, 22099, 22100, -1, 22097, 22099, 22098, -1, 22100, 22101, 20301, -1, 22099, 22101, 22100, -1, 22101, 20326, 20301, -1, 22102, 20694, 20691, -1, 22102, 20691, 22103, -1, 22104, 22103, 22105, -1, 22104, 22102, 22103, -1, 22106, 22105, 22107, -1, 22106, 22104, 22105, -1, 22108, 22107, 22109, -1, 22108, 22106, 22107, -1, 20596, 22109, 20594, -1, 20596, 22108, 22109, -1, 22110, 20731, 20716, -1, 22110, 20716, 22111, -1, 22112, 22110, 22111, -1, 22113, 22112, 22111, -1, 22114, 22111, 22115, -1, 22114, 22113, 22111, -1, 22116, 22114, 22115, -1, 22117, 22115, 22118, -1, 22117, 22116, 22115, -1, 22119, 22118, 22120, -1, 22119, 22117, 22118, -1, 22121, 22120, 22122, -1, 22121, 22122, 22123, -1, 22121, 22119, 22120, -1, 20708, 22123, 20699, -1, 20708, 22121, 22123, -1, 20264, 20263, 20656, -1, 20656, 20263, 22124, -1, 22125, 20262, 17861, -1, 22124, 20262, 22125, -1, 20263, 20262, 22124, -1, 20262, 17862, 17861, -1, 20820, 20276, 20275, -1, 22126, 20275, 20274, -1, 22126, 20820, 20275, -1, 22127, 22126, 20274, -1, 22128, 20274, 20273, -1, 22128, 22127, 20274, -1, 22129, 20273, 20272, -1, 22129, 22128, 20273, -1, 22130, 20272, 20271, -1, 22130, 22129, 20272, -1, 22131, 20271, 20270, -1, 22131, 22130, 20271, -1, 22132, 20270, 20269, -1, 22132, 22131, 20270, -1, 17725, 20269, 20268, -1, 17725, 22132, 20269, -1, 17702, 20268, 20265, -1, 17702, 17725, 20268, -1, 17703, 17702, 20265, -1, 20259, 20252, 22133, -1, 22134, 22135, 22136, -1, 22133, 22135, 22134, -1, 20252, 22135, 22133, -1, 22136, 22137, 22138, -1, 22135, 22137, 22136, -1, 22138, 19082, 19079, -1, 22137, 19082, 22138, -1, 22139, 20239, 20245, -1, 22139, 20245, 22140, -1, 22141, 22140, 22142, -1, 22141, 22139, 22140, -1, 19072, 22142, 19073, -1, 19072, 22141, 22142, -1, 21054, 22143, 21056, -1, 21056, 22143, 22144, -1, 22144, 22145, 22146, -1, 22143, 22145, 22144, -1, 22146, 19132, 19130, -1, 22145, 19132, 22146, -1, 22147, 20634, 20630, -1, 22147, 20630, 22148, -1, 22149, 22148, 22150, -1, 22149, 22147, 22148, -1, 22151, 22150, 20958, -1, 22151, 22149, 22150, -1, 20955, 22151, 20958, -1, 21046, 22152, 21049, -1, 21049, 22152, 22153, -1, 22153, 22154, 22155, -1, 22152, 22154, 22153, -1, 22155, 19140, 19138, -1, 22154, 19140, 22155, -1, 22156, 21044, 21045, -1, 22156, 21045, 22157, -1, 22158, 22157, 22159, -1, 22158, 22156, 22157, -1, 19141, 22159, 19142, -1, 19141, 22158, 22159, -1, 21036, 22160, 21039, -1, 21039, 22160, 22161, -1, 22161, 22162, 22163, -1, 22160, 22162, 22161, -1, 22163, 19149, 19147, -1, 22162, 19149, 22163, -1, 22164, 21034, 21035, -1, 22164, 21035, 22165, -1, 22166, 22165, 22167, -1, 22166, 22164, 22165, -1, 19150, 22167, 19151, -1, 19150, 22166, 22167, -1, 21026, 22168, 21029, -1, 21029, 22168, 22169, -1, 22169, 22170, 22171, -1, 22168, 22170, 22169, -1, 22171, 19158, 19156, -1, 22170, 19158, 22171, -1, 22172, 21024, 21025, -1, 22172, 21025, 22173, -1, 22174, 22173, 22175, -1, 22174, 22172, 22173, -1, 19159, 22175, 19160, -1, 19159, 22174, 22175, -1, 21016, 22176, 21019, -1, 21019, 22176, 22177, -1, 22177, 22178, 22179, -1, 22176, 22178, 22177, -1, 22179, 19167, 19165, -1, 22178, 19167, 22179, -1, 22180, 21014, 21015, -1, 22180, 21015, 22181, -1, 22182, 22181, 22183, -1, 22182, 22180, 22181, -1, 19168, 22183, 19169, -1, 19168, 22182, 22183, -1, 21006, 22184, 21009, -1, 21009, 22184, 22185, -1, 22185, 22186, 22187, -1, 22184, 22186, 22185, -1, 22187, 19176, 19174, -1, 22186, 19176, 22187, -1, 22188, 21004, 21005, -1, 22188, 21005, 22189, -1, 22190, 22189, 22191, -1, 22190, 22188, 22189, -1, 19177, 22191, 19178, -1, 19177, 22190, 22191, -1, 20996, 22192, 20999, -1, 20999, 22192, 22193, -1, 22193, 22194, 22195, -1, 22192, 22194, 22193, -1, 22195, 19185, 19183, -1, 22194, 19185, 22195, -1, 22196, 20994, 20995, -1, 22196, 20995, 22197, -1, 22198, 22197, 22199, -1, 22198, 22196, 22197, -1, 19186, 22199, 19187, -1, 19186, 22198, 22199, -1, 22200, 20968, 20969, -1, 22200, 20969, 22201, -1, 22202, 22201, 22203, -1, 22202, 22200, 22201, -1, 19209, 22203, 19210, -1, 19209, 22202, 22203, -1, 22204, 20984, 20985, -1, 22204, 20985, 22205, -1, 22206, 22205, 22207, -1, 22206, 22204, 22205, -1, 19195, 22207, 19196, -1, 19195, 22206, 22207, -1, 20986, 22208, 20989, -1, 20989, 22208, 22209, -1, 22209, 22210, 22211, -1, 22208, 22210, 22209, -1, 22211, 19194, 19192, -1, 22210, 19194, 22211, -1, 22212, 20974, 20975, -1, 22212, 20975, 22213, -1, 22214, 22213, 22215, -1, 22214, 22212, 22213, -1, 19204, 22215, 19205, -1, 19204, 22214, 22215, -1, 20976, 22216, 20979, -1, 20979, 22216, 22217, -1, 22217, 22218, 22219, -1, 22216, 22218, 22217, -1, 22219, 19203, 19201, -1, 22218, 19203, 22219, -1, 20964, 22220, 22221, -1, 20961, 22220, 20964, -1, 22221, 22222, 22223, -1, 22220, 22222, 22221, -1, 22223, 19136, 19134, -1, 22222, 19136, 22223, -1, 20240, 22224, 18565, -1, 18565, 22224, 18564, -1, 18564, 22225, 18566, -1, 18566, 22225, 17850, -1, 22224, 22225, 18564, -1, 22225, 17848, 17850, -1, 17838, 22226, 17840, -1, 17840, 22226, 22227, -1, 20236, 22228, 20238, -1, 20238, 22228, 20240, -1, 20240, 22228, 22224, -1, 22229, 22228, 20236, -1, 22230, 22231, 22232, -1, 22227, 22231, 22230, -1, 17836, 22233, 17838, -1, 17838, 22233, 22226, -1, 22224, 22234, 22225, -1, 22229, 22234, 22228, -1, 22228, 22234, 22224, -1, 22232, 22234, 22229, -1, 22227, 22235, 22231, -1, 22226, 22235, 22227, -1, 17834, 22236, 17836, -1, 17836, 22236, 22233, -1, 22225, 22237, 17848, -1, 22232, 22237, 22234, -1, 22234, 22237, 22225, -1, 22231, 22237, 22232, -1, 22226, 22238, 22235, -1, 22233, 22238, 22226, -1, 17848, 22239, 17849, -1, 22237, 22239, 17848, -1, 22235, 22239, 22231, -1, 22231, 22239, 22237, -1, 17831, 22240, 17834, -1, 21277, 22240, 17831, -1, 17834, 22240, 22236, -1, 22236, 22241, 22233, -1, 22233, 22241, 22238, -1, 17849, 22242, 17852, -1, 22239, 22242, 17849, -1, 22238, 22242, 22235, -1, 22235, 22242, 22239, -1, 21275, 22243, 21277, -1, 21254, 21277, 22244, -1, 22244, 21277, 22245, -1, 21277, 22243, 22240, -1, 22245, 21277, 17830, -1, 22236, 22246, 22241, -1, 17830, 21277, 17831, -1, 22240, 22246, 22236, -1, 22238, 22247, 22242, -1, 17852, 22247, 17854, -1, 22242, 22247, 17852, -1, 22241, 22247, 22238, -1, 21272, 22248, 21275, -1, 21275, 22248, 22243, -1, 22243, 22248, 22240, -1, 22240, 22248, 22246, -1, 22247, 22249, 17854, -1, 22241, 22249, 22247, -1, 17854, 22249, 17857, -1, 22246, 22249, 22241, -1, 17859, 22250, 21272, -1, 22248, 22250, 22246, -1, 22246, 22250, 22249, -1, 22249, 22250, 17857, -1, 17857, 22250, 17859, -1, 21272, 22250, 22248, -1, 17844, 22251, 17847, -1, 17847, 22251, 20233, -1, 17842, 22230, 17844, -1, 17844, 22230, 22251, -1, 17840, 22227, 17842, -1, 17842, 22227, 22230, -1, 20233, 22229, 20236, -1, 22251, 22229, 20233, -1, 22251, 22232, 22229, -1, 22230, 22232, 22251, -1, 21252, 21254, 22252, -1, 21254, 22244, 22252, -1, 22252, 22245, 22253, -1, 22244, 22245, 22252, -1, 22253, 17830, 17832, -1, 22245, 17830, 22253, -1, 21270, 17827, 17829, -1, 21252, 22252, 21266, -1, 22252, 22253, 21266, -1, 22253, 17832, 21266, -1, 17832, 17833, 21266, -1, 22254, 17845, 22255, -1, 22255, 17845, 17846, -1, 21268, 22256, 21270, -1, 21266, 22257, 21268, -1, 17833, 22257, 21266, -1, 17827, 22258, 17825, -1, 21270, 22258, 17827, -1, 22256, 22258, 21270, -1, 17835, 22259, 17833, -1, 22256, 22259, 22258, -1, 21268, 22259, 22256, -1, 17833, 22259, 22257, -1, 22257, 22259, 21268, -1, 17825, 22260, 17823, -1, 22258, 22260, 17825, -1, 17837, 22261, 17835, -1, 17835, 22261, 22259, -1, 22259, 22261, 22258, -1, 22258, 22261, 22260, -1, 17823, 22262, 17821, -1, 17821, 22262, 17820, -1, 22260, 22262, 17823, -1, 17839, 22263, 17837, -1, 17841, 22263, 17839, -1, 22262, 22263, 17841, -1, 22261, 22263, 22260, -1, 17837, 22263, 22261, -1, 22260, 22263, 22262, -1, 17820, 22264, 22254, -1, 17843, 22264, 17841, -1, 17845, 22264, 17843, -1, 17841, 22264, 22262, -1, 22262, 22264, 17820, -1, 22254, 22264, 17845, -1, 20232, 22265, 17846, -1, 17846, 22265, 22255, -1, 22254, 22266, 17820, -1, 22255, 22266, 22254, -1, 22265, 22266, 22255, -1, 22266, 17818, 17820, -1, 22267, 22268, 22269, -1, 22270, 22271, 22272, -1, 17824, 22273, 22274, -1, 22272, 22271, 22275, -1, 22276, 22277, 22278, -1, 22279, 22280, 22281, -1, 22274, 22280, 22279, -1, 22275, 22277, 22276, -1, 18876, 22282, 18870, -1, 18870, 22282, 18867, -1, 22281, 22282, 18876, -1, 22283, 22284, 22285, -1, 22285, 22284, 22286, -1, 17819, 22287, 17822, -1, 22278, 22288, 22267, -1, 17822, 22287, 22273, -1, 22267, 22288, 22268, -1, 22274, 22289, 22280, -1, 21815, 22290, 21812, -1, 22270, 22290, 22271, -1, 21812, 22290, 22291, -1, 22273, 22289, 22274, -1, 22291, 22290, 22270, -1, 22286, 22292, 18895, -1, 18895, 22292, 18903, -1, 18903, 22292, 22293, -1, 22280, 22294, 22281, -1, 22281, 22294, 22282, -1, 22271, 22295, 22275, -1, 22275, 22295, 22277, -1, 22282, 22296, 18867, -1, 22268, 22297, 22283, -1, 22283, 22297, 22284, -1, 17818, 22298, 17819, -1, 22278, 22299, 22288, -1, 22277, 22299, 22278, -1, 17819, 22298, 22287, -1, 22293, 22300, 22301, -1, 20232, 21808, 22265, -1, 22273, 22302, 22289, -1, 22284, 22300, 22286, -1, 22292, 22300, 22293, -1, 22287, 22302, 22273, -1, 22286, 22300, 22292, -1, 21817, 22303, 21815, -1, 22289, 22304, 22280, -1, 21815, 22303, 22290, -1, 22290, 22303, 22271, -1, 22271, 22303, 22295, -1, 22280, 22304, 22294, -1, 22295, 22305, 22277, -1, 22266, 22306, 17818, -1, 22277, 22305, 22299, -1, 17818, 22306, 22298, -1, 22268, 22307, 22297, -1, 22288, 22307, 22268, -1, 22294, 22269, 22282, -1, 22301, 22308, 22309, -1, 22282, 22269, 22296, -1, 22297, 22308, 22284, -1, 22300, 22308, 22301, -1, 18867, 22285, 18881, -1, 22284, 22308, 22300, -1, 18881, 22285, 18889, -1, 21820, 22310, 21817, -1, 21817, 22310, 22303, -1, 22303, 22310, 22295, -1, 22296, 22285, 18867, -1, 22295, 22310, 22305, -1, 22299, 22311, 22288, -1, 22298, 22272, 22287, -1, 18903, 22293, 18916, -1, 22287, 22272, 22302, -1, 22288, 22311, 22307, -1, 22309, 22312, 22313, -1, 22302, 22276, 22289, -1, 22297, 22312, 22308, -1, 22308, 22312, 22309, -1, 22289, 22276, 22304, -1, 22307, 22312, 22297, -1, 21810, 22314, 21808, -1, 22265, 22314, 22266, -1, 22299, 22315, 22311, -1, 21808, 22314, 22265, -1, 22305, 22315, 22299, -1, 22266, 22314, 22306, -1, 22294, 22267, 22269, -1, 22313, 22316, 22317, -1, 22312, 22316, 22313, -1, 22311, 22316, 22307, -1, 22304, 22267, 22294, -1, 22307, 22316, 22312, -1, 22306, 22270, 22298, -1, 21820, 22318, 22310, -1, 22310, 22318, 22305, -1, 22305, 22318, 22315, -1, 22298, 22270, 22272, -1, 22269, 22283, 22296, -1, 22317, 22319, 22320, -1, 22316, 22319, 22317, -1, 22315, 22319, 22311, -1, 22311, 22319, 22316, -1, 22296, 22283, 22285, -1, 22318, 22321, 22315, -1, 22320, 22321, 20965, -1, 20965, 22321, 21823, -1, 21823, 22321, 21820, -1, 21820, 22321, 22318, -1, 22315, 22321, 22319, -1, 22272, 22275, 22302, -1, 22319, 22321, 22320, -1, 22302, 22275, 22276, -1, 17828, 22279, 18886, -1, 22276, 22278, 22304, -1, 18886, 22279, 18876, -1, 22304, 22278, 22267, -1, 17826, 22279, 17828, -1, 21810, 22291, 22314, -1, 21812, 22291, 21810, -1, 17824, 22274, 17826, -1, 22314, 22291, 22306, -1, 22306, 22291, 22270, -1, 18889, 22286, 18895, -1, 17826, 22274, 22279, -1, 22285, 22286, 18889, -1, 22279, 22281, 18876, -1, 22269, 22268, 22283, -1, 17822, 22273, 17824, -1, 18916, 22293, 18917, -1, 18917, 22293, 22322, -1, 22322, 22293, 22323, -1, 22323, 22301, 22324, -1, 22293, 22301, 22323, -1, 22324, 22309, 22325, -1, 22301, 22309, 22324, -1, 22325, 22313, 22326, -1, 22309, 22313, 22325, -1, 22326, 22317, 22327, -1, 22313, 22317, 22326, -1, 22327, 22320, 20966, -1, 22317, 22320, 22327, -1, 22320, 20965, 20966, -1, 22328, 22329, 18920, -1, 22326, 22330, 22325, -1, 22325, 22330, 22331, -1, 22331, 22332, 22333, -1, 22333, 22332, 22334, -1, 22335, 22336, 22328, -1, 22328, 22336, 22329, -1, 18921, 22337, 18922, -1, 18922, 22337, 18923, -1, 18923, 22337, 22338, -1, 22329, 22337, 18921, -1, 21806, 22339, 20966, -1, 22327, 22339, 22326, -1, 20966, 22339, 22327, -1, 22326, 22339, 22330, -1, 22330, 22340, 22331, -1, 22331, 22340, 22332, -1, 22335, 22341, 22336, -1, 22334, 22341, 22335, -1, 22338, 22342, 22343, -1, 22337, 22342, 22338, -1, 22336, 22342, 22329, -1, 22329, 22342, 22337, -1, 21803, 22344, 21805, -1, 21805, 22344, 21806, -1, 21806, 22344, 22339, -1, 22339, 22344, 22330, -1, 22330, 22344, 22340, -1, 22332, 22345, 22334, -1, 22334, 22345, 22341, -1, 22343, 22346, 22347, -1, 22342, 22346, 22343, -1, 22341, 22346, 22336, -1, 22336, 22346, 22342, -1, 22340, 22348, 22332, -1, 22332, 22348, 22345, -1, 22345, 22349, 22341, -1, 22347, 22349, 22350, -1, 22346, 22349, 22347, -1, 22341, 22349, 22346, -1, 21799, 22351, 21801, -1, 21801, 22351, 21803, -1, 22340, 22351, 22348, -1, 21803, 22351, 22344, -1, 22344, 22351, 22340, -1, 22348, 22352, 22345, -1, 22349, 22352, 22350, -1, 22350, 22352, 22353, -1, 21799, 20962, 22354, -1, 18917, 22355, 18918, -1, 22345, 22352, 22349, -1, 18918, 22355, 18919, -1, 22348, 22356, 22352, -1, 22353, 22356, 22354, -1, 21799, 22356, 22351, -1, 22322, 22355, 18917, -1, 22351, 22356, 22348, -1, 22354, 22356, 21799, -1, 22352, 22356, 22353, -1, 22323, 22357, 22322, -1, 22322, 22357, 22355, -1, 18919, 22328, 18920, -1, 22355, 22328, 18919, -1, 22324, 22333, 22323, -1, 22323, 22333, 22357, -1, 22355, 22335, 22328, -1, 22357, 22335, 22355, -1, 22325, 22331, 22324, -1, 22324, 22331, 22333, -1, 22333, 22334, 22357, -1, 22357, 22334, 22335, -1, 18920, 22329, 18921, -1, 18923, 22338, 18924, -1, 18924, 22338, 22358, -1, 22358, 22338, 22359, -1, 22359, 22343, 22360, -1, 22338, 22343, 22359, -1, 22360, 22347, 22361, -1, 22343, 22347, 22360, -1, 22361, 22350, 22362, -1, 22347, 22350, 22361, -1, 22362, 22353, 22363, -1, 22350, 22353, 22362, -1, 22363, 22354, 20964, -1, 22353, 22354, 22363, -1, 22354, 20962, 20964, -1, 22221, 22363, 20964, -1, 18930, 18928, 19228, -1, 22221, 22362, 22363, -1, 22221, 22361, 22362, -1, 18927, 22359, 22360, -1, 18927, 22358, 22359, -1, 18927, 18924, 22358, -1, 19219, 22364, 19134, -1, 19134, 22364, 22223, -1, 22223, 22364, 22221, -1, 19221, 22365, 19219, -1, 22364, 22365, 22221, -1, 19219, 22365, 22364, -1, 19223, 22366, 19221, -1, 22365, 22366, 22221, -1, 19221, 22366, 22365, -1, 22221, 22366, 22361, -1, 19225, 22367, 19223, -1, 22361, 22367, 22360, -1, 22366, 22367, 22361, -1, 19223, 22367, 22366, -1, 22360, 22367, 18927, -1, 19228, 22368, 19226, -1, 19226, 22368, 19225, -1, 22367, 22368, 18927, -1, 19225, 22368, 22367, -1, 18927, 22369, 18928, -1, 22368, 22369, 18927, -1, 18928, 22369, 19228, -1, 19228, 22369, 22368, -1, 19077, 22370, 19232, -1, 22370, 19235, 19232, -1, 22371, 18777, 22370, -1, 22370, 18777, 19235, -1, 22371, 18779, 18777, -1, 18783, 21288, 18785, -1, 21286, 21288, 18783, -1, 21288, 18787, 18785, -1, 21260, 22372, 22373, -1, 22373, 22372, 22371, -1, 18779, 22372, 18781, -1, 22371, 22372, 18779, -1, 21284, 22374, 21260, -1, 21260, 22374, 22372, -1, 18781, 22375, 18783, -1, 21286, 22375, 21284, -1, 22374, 22375, 22372, -1, 22372, 22375, 18781, -1, 18783, 22375, 21286, -1, 21284, 22375, 22374, -1, 21261, 21260, 22376, -1, 22376, 22373, 22377, -1, 21260, 22373, 22376, -1, 22377, 22371, 22378, -1, 22373, 22371, 22377, -1, 22378, 22370, 19073, -1, 22371, 22370, 22378, -1, 22370, 19077, 19073, -1, 22379, 22140, 20245, -1, 21264, 21263, 22380, -1, 22380, 21263, 22381, -1, 22381, 21263, 22382, -1, 22382, 21263, 22383, -1, 22379, 22384, 22140, -1, 22383, 22385, 22379, -1, 22379, 22385, 22384, -1, 21263, 22385, 22383, -1, 21263, 22386, 22385, -1, 21262, 22387, 21263, -1, 21263, 22387, 22386, -1, 22386, 22387, 21262, -1, 22140, 22388, 22142, -1, 22142, 22388, 19073, -1, 19073, 22388, 22378, -1, 22384, 22388, 22140, -1, 22378, 22389, 22377, -1, 22384, 22389, 22388, -1, 22388, 22389, 22378, -1, 22385, 22389, 22384, -1, 22377, 22390, 22376, -1, 22386, 22390, 22385, -1, 22389, 22390, 22377, -1, 21262, 22390, 22386, -1, 22385, 22390, 22389, -1, 21261, 22391, 21262, -1, 22376, 22391, 21261, -1, 22390, 22391, 22376, -1, 21262, 22391, 22390, -1, 21264, 22380, 21257, -1, 21257, 22380, 22392, -1, 22392, 22380, 22393, -1, 22380, 22381, 22393, -1, 22393, 22382, 22394, -1, 22381, 22382, 22393, -1, 22394, 22383, 22395, -1, 22382, 22383, 22394, -1, 22395, 22379, 22396, -1, 22383, 22379, 22395, -1, 22396, 20245, 20246, -1, 22379, 20245, 22396, -1, 21281, 22397, 21279, -1, 21279, 22397, 17816, -1, 17816, 22397, 17814, -1, 17814, 22397, 22398, -1, 22398, 22397, 21281, -1, 21257, 22399, 21281, -1, 22392, 22399, 21257, -1, 22393, 22399, 22392, -1, 22400, 22399, 22393, -1, 21281, 22399, 22398, -1, 22398, 22399, 22401, -1, 22401, 22399, 22400, -1, 22402, 20242, 20241, -1, 20244, 22396, 20246, -1, 22403, 22404, 22402, -1, 20242, 22404, 20243, -1, 22402, 22404, 20242, -1, 17807, 22405, 22403, -1, 22403, 22405, 22404, -1, 17808, 22406, 17807, -1, 17807, 22406, 22405, -1, 20243, 22407, 20244, -1, 20244, 22407, 22396, -1, 22404, 22407, 20243, -1, 17810, 22408, 17808, -1, 17808, 22408, 22406, -1, 22396, 22409, 22395, -1, 22405, 22409, 22404, -1, 22404, 22409, 22407, -1, 22407, 22409, 22396, -1, 22395, 22410, 22394, -1, 22405, 22410, 22409, -1, 22409, 22410, 22395, -1, 22406, 22410, 22405, -1, 17812, 22401, 17810, -1, 17810, 22401, 22408, -1, 22410, 22411, 22394, -1, 22408, 22411, 22406, -1, 22406, 22411, 22410, -1, 17814, 22398, 17812, -1, 17812, 22398, 22401, -1, 22394, 22400, 22393, -1, 22408, 22400, 22411, -1, 22411, 22400, 22394, -1, 22401, 22400, 22408, -1, 20241, 20235, 22402, -1, 20235, 21319, 22402, -1, 22402, 21320, 22403, -1, 21319, 21320, 22402, -1, 22403, 17805, 17807, -1, 21320, 17805, 22403, -1, 19210, 22203, 19236, -1, 18863, 17802, 17804, -1, 18863, 17800, 17802, -1, 22201, 22412, 22413, -1, 22201, 20969, 22412, -1, 18774, 22414, 18997, -1, 18997, 22414, 18863, -1, 18772, 22414, 18774, -1, 18770, 22415, 18772, -1, 22414, 22415, 18863, -1, 18772, 22415, 22414, -1, 18768, 22416, 18770, -1, 18770, 22416, 22415, -1, 18766, 22417, 18768, -1, 18768, 22417, 22416, -1, 18764, 22418, 18766, -1, 18766, 22418, 22417, -1, 19239, 22419, 18764, -1, 18764, 22419, 22418, -1, 22201, 22420, 22203, -1, 19236, 22420, 19239, -1, 19239, 22420, 22419, -1, 22203, 22420, 19236, -1, 22419, 22420, 22201, -1, 17800, 22421, 17798, -1, 17798, 22421, 17796, -1, 17796, 22421, 17795, -1, 17795, 22421, 22413, -1, 22415, 22421, 18863, -1, 22416, 22421, 22415, -1, 22419, 22421, 22418, -1, 22417, 22421, 22416, -1, 22201, 22421, 22419, -1, 22418, 22421, 22417, -1, 18863, 22421, 17800, -1, 22413, 22421, 22201, -1, 20969, 20967, 22412, -1, 22412, 22422, 22413, -1, 20967, 22422, 22412, -1, 22413, 22423, 17795, -1, 22422, 22423, 22413, -1, 22423, 17793, 17795, -1, 17782, 22424, 17786, -1, 22425, 22424, 22426, -1, 22426, 22424, 17782, -1, 22427, 22424, 22425, -1, 17793, 22428, 17794, -1, 17794, 22428, 22429, -1, 22429, 22430, 22431, -1, 22431, 22430, 22432, -1, 17786, 22433, 17790, -1, 22427, 22433, 22424, -1, 22424, 22433, 17786, -1, 22432, 22433, 22427, -1, 22423, 22434, 17793, -1, 17793, 22434, 22428, -1, 22429, 22435, 22430, -1, 22428, 22435, 22429, -1, 21843, 22436, 21845, -1, 22422, 22436, 22423, -1, 22423, 22436, 22434, -1, 21845, 22436, 22422, -1, 17790, 22437, 17792, -1, 22433, 22437, 17790, -1, 22430, 22437, 22432, -1, 19062, 17782, 17784, -1, 22432, 22437, 22433, -1, 22434, 22438, 22428, -1, 22428, 22438, 22435, -1, 17792, 22439, 17766, -1, 22437, 22439, 17792, -1, 22435, 22439, 22430, -1, 22430, 22439, 22437, -1, 20967, 21845, 22422, -1, 21840, 22440, 21843, -1, 21843, 22440, 22436, -1, 22436, 22440, 22434, -1, 22434, 22440, 22438, -1, 17766, 22441, 17765, -1, 22439, 22441, 17766, -1, 22438, 22441, 22435, -1, 22435, 22441, 22439, -1, 21838, 22442, 21840, -1, 22438, 22442, 22441, -1, 21840, 22442, 22440, -1, 17765, 22442, 21838, -1, 22440, 22442, 22438, -1, 22441, 22442, 17765, -1, 21838, 17780, 17765, -1, 17801, 22443, 17803, -1, 17803, 22443, 18835, -1, 17799, 22444, 17801, -1, 17801, 22444, 22443, -1, 18835, 22425, 19067, -1, 19067, 22425, 19064, -1, 22443, 22425, 18835, -1, 17797, 22431, 17799, -1, 17799, 22431, 22444, -1, 22443, 22427, 22425, -1, 22444, 22427, 22443, -1, 19064, 22426, 19062, -1, 22425, 22426, 19064, -1, 19062, 22426, 17782, -1, 17794, 22429, 17797, -1, 17797, 22429, 22431, -1, 22431, 22432, 22444, -1, 22444, 22432, 22427, -1, 17781, 20972, 17778, -1, 17778, 22445, 17773, -1, 20972, 22445, 17778, -1, 17773, 22446, 17770, -1, 22445, 22446, 17773, -1, 17770, 22447, 17758, -1, 22446, 22447, 17770, -1, 17758, 22448, 17756, -1, 22447, 22448, 17758, -1, 17756, 22449, 17775, -1, 22448, 22449, 17756, -1, 22449, 22450, 17775, -1, 17775, 18915, 17776, -1, 22450, 18915, 17775, -1, 22451, 22452, 18882, -1, 22446, 22453, 22447, -1, 22447, 22453, 22454, -1, 22454, 22455, 22456, -1, 22456, 22455, 22457, -1, 22458, 22459, 22451, -1, 22451, 22459, 22452, -1, 18880, 22460, 18868, -1, 18868, 22460, 18866, -1, 18866, 22460, 22461, -1, 22452, 22460, 18880, -1, 21824, 22462, 20972, -1, 22445, 22462, 22446, -1, 20972, 22462, 22445, -1, 22446, 22462, 22453, -1, 22453, 22463, 22454, -1, 22454, 22463, 22455, -1, 22458, 22464, 22459, -1, 22457, 22464, 22458, -1, 22461, 22465, 22466, -1, 22460, 22465, 22461, -1, 22459, 22465, 22452, -1, 22452, 22465, 22460, -1, 21827, 22467, 21826, -1, 21826, 22467, 21824, -1, 21824, 22467, 22462, -1, 22462, 22467, 22453, -1, 22453, 22467, 22463, -1, 22455, 22468, 22457, -1, 22457, 22468, 22464, -1, 22466, 22469, 22470, -1, 22465, 22469, 22466, -1, 22464, 22469, 22459, -1, 22459, 22469, 22465, -1, 22463, 22471, 22455, -1, 22455, 22471, 22468, -1, 22468, 22472, 22464, -1, 22470, 22472, 22473, -1, 22469, 22472, 22470, -1, 22464, 22472, 22469, -1, 21831, 22474, 21829, -1, 21829, 22474, 21827, -1, 22463, 22474, 22471, -1, 21827, 22474, 22467, -1, 22467, 22474, 22463, -1, 22471, 22475, 22468, -1, 22472, 22475, 22473, -1, 22473, 22475, 22476, -1, 21831, 20249, 22477, -1, 18915, 22478, 18896, -1, 22468, 22475, 22472, -1, 18896, 22478, 18890, -1, 22471, 22479, 22475, -1, 22476, 22479, 22477, -1, 21831, 22479, 22474, -1, 22450, 22478, 18915, -1, 22474, 22479, 22471, -1, 22477, 22479, 21831, -1, 22475, 22479, 22476, -1, 22449, 22480, 22450, -1, 22450, 22480, 22478, -1, 18890, 22451, 18882, -1, 22478, 22451, 18890, -1, 22448, 22456, 22449, -1, 22449, 22456, 22480, -1, 22478, 22458, 22451, -1, 22480, 22458, 22478, -1, 22447, 22454, 22448, -1, 22448, 22454, 22456, -1, 22456, 22457, 22480, -1, 22480, 22457, 22458, -1, 18882, 22452, 18880, -1, 18866, 22461, 18875, -1, 18875, 22461, 22481, -1, 22481, 22466, 22482, -1, 22461, 22466, 22481, -1, 22482, 22470, 22483, -1, 22466, 22470, 22482, -1, 22483, 22473, 22484, -1, 22470, 22473, 22483, -1, 22484, 22476, 22485, -1, 22473, 22476, 22484, -1, 22485, 22477, 22486, -1, 22476, 22477, 22485, -1, 22486, 20249, 20254, -1, 22477, 20249, 22486, -1, 20254, 22487, 22486, -1, 22487, 22485, 22486, -1, 22481, 21269, 18875, -1, 22488, 22489, 22490, -1, 22490, 22489, 22487, -1, 22485, 22489, 22484, -1, 22487, 22489, 22485, -1, 22484, 22491, 22483, -1, 22489, 22491, 22484, -1, 22492, 22493, 22488, -1, 22489, 22493, 22491, -1, 22488, 22493, 22489, -1, 22482, 22494, 22481, -1, 22483, 22494, 22482, -1, 21269, 22494, 21267, -1, 22491, 22494, 22483, -1, 22481, 22494, 21269, -1, 21255, 22495, 22492, -1, 21267, 22495, 21265, -1, 21265, 22495, 21255, -1, 22492, 22495, 22493, -1, 22493, 22495, 22491, -1, 22491, 22495, 22494, -1, 22494, 22495, 21267, -1, 21253, 21255, 22496, -1, 22496, 22492, 22497, -1, 21255, 22492, 22496, -1, 22497, 22488, 22498, -1, 22492, 22488, 22497, -1, 22498, 22490, 22499, -1, 22488, 22490, 22498, -1, 22499, 22487, 20248, -1, 22490, 22487, 22499, -1, 22487, 20254, 20248, -1, 22498, 22500, 22497, -1, 22501, 22500, 22498, -1, 22502, 22500, 22503, -1, 22503, 22500, 22501, -1, 21273, 22504, 22505, -1, 22505, 22504, 22506, -1, 22506, 22504, 22507, -1, 22500, 22508, 22497, -1, 22502, 22508, 22500, -1, 22507, 22508, 22502, -1, 21276, 22509, 21274, -1, 21274, 22509, 21273, -1, 21273, 22509, 22504, -1, 22497, 22510, 22496, -1, 21276, 22510, 22509, -1, 22496, 22510, 21276, -1, 22504, 22510, 22507, -1, 22508, 22510, 22497, -1, 22507, 22510, 22508, -1, 22509, 22510, 22504, -1, 21246, 21271, 22511, -1, 21276, 21253, 22496, -1, 22512, 22513, 20255, -1, 20255, 22513, 20253, -1, 22514, 22515, 22512, -1, 22512, 22515, 22513, -1, 20253, 22516, 20251, -1, 22513, 22516, 20253, -1, 22517, 22518, 22519, -1, 22519, 22518, 22514, -1, 22514, 22518, 22515, -1, 22515, 22503, 22513, -1, 22513, 22503, 22516, -1, 22520, 22506, 22517, -1, 22517, 22506, 22518, -1, 20251, 22521, 20247, -1, 20247, 22521, 20248, -1, 20248, 22521, 22499, -1, 22516, 22521, 20251, -1, 22515, 22502, 22503, -1, 22518, 22502, 22515, -1, 21273, 22505, 21271, -1, 22511, 22505, 22520, -1, 21271, 22505, 22511, -1, 22520, 22505, 22506, -1, 22499, 22501, 22498, -1, 22516, 22501, 22521, -1, 22503, 22501, 22516, -1, 22521, 22501, 22499, -1, 22518, 22507, 22502, -1, 22506, 22507, 22518, -1, 20256, 22522, 20255, -1, 22512, 22522, 22514, -1, 20255, 22522, 22512, -1, 22514, 22523, 22519, -1, 22522, 22523, 22514, -1, 22519, 22524, 22517, -1, 22523, 22524, 22519, -1, 22517, 22525, 22520, -1, 22524, 22525, 22517, -1, 22520, 22526, 22511, -1, 22525, 22526, 22520, -1, 22511, 22527, 21246, -1, 22526, 22527, 22511, -1, 22527, 21249, 21246, -1, 22528, 20258, 20259, -1, 20258, 22522, 20257, -1, 20257, 22522, 20256, -1, 22528, 22522, 20258, -1, 22529, 22523, 22528, -1, 22528, 22523, 22522, -1, 22530, 22524, 22529, -1, 22529, 22524, 22523, -1, 22531, 22525, 22532, -1, 22532, 22525, 22530, -1, 22530, 22525, 22524, -1, 22533, 22526, 22531, -1, 22531, 22526, 22525, -1, 21280, 21278, 22533, -1, 21278, 22527, 22533, -1, 22533, 22527, 22526, -1, 21278, 21249, 22527, -1, 22133, 22528, 20259, -1, 21258, 21283, 22534, -1, 21282, 21280, 22533, -1, 22535, 22536, 22136, -1, 22136, 22536, 22134, -1, 22134, 22536, 22133, -1, 22133, 22536, 22528, -1, 22537, 22538, 22535, -1, 22528, 22538, 22529, -1, 22536, 22538, 22528, -1, 22535, 22538, 22536, -1, 22539, 22540, 22537, -1, 22529, 22540, 22530, -1, 22537, 22540, 22538, -1, 22538, 22540, 22529, -1, 22541, 22542, 22543, -1, 22543, 22542, 22539, -1, 22530, 22542, 22532, -1, 22539, 22542, 22540, -1, 22540, 22542, 22530, -1, 22544, 22545, 22541, -1, 22542, 22545, 22532, -1, 22541, 22545, 22542, -1, 22546, 22547, 22544, -1, 22532, 22547, 22531, -1, 22545, 22547, 22532, -1, 22544, 22547, 22545, -1, 21282, 22548, 21283, -1, 22534, 22548, 22546, -1, 22531, 22548, 22533, -1, 22546, 22548, 22547, -1, 22547, 22548, 22531, -1, 21283, 22548, 22534, -1, 22533, 22548, 21282, -1, 22136, 22138, 22535, -1, 21258, 22549, 21256, -1, 21256, 22549, 22550, -1, 22534, 22549, 21258, -1, 22546, 22549, 22534, -1, 22550, 22551, 22552, -1, 22552, 22551, 22553, -1, 22544, 22551, 22546, -1, 22549, 22551, 22550, -1, 22546, 22551, 22549, -1, 22541, 22554, 22544, -1, 22551, 22554, 22553, -1, 22544, 22554, 22551, -1, 22553, 22555, 22556, -1, 22556, 22555, 22557, -1, 22543, 22555, 22541, -1, 22554, 22555, 22553, -1, 22541, 22555, 22554, -1, 22557, 22558, 22559, -1, 22543, 22558, 22555, -1, 22555, 22558, 22557, -1, 22559, 22560, 22561, -1, 22539, 22560, 22543, -1, 22558, 22560, 22559, -1, 22543, 22560, 22558, -1, 22561, 22562, 22563, -1, 22537, 22562, 22539, -1, 22539, 22562, 22560, -1, 22560, 22562, 22561, -1, 22563, 22564, 19079, -1, 19079, 22564, 22138, -1, 22535, 22564, 22537, -1, 22562, 22564, 22563, -1, 22138, 22564, 22535, -1, 22537, 22564, 22562, -1, 21259, 21256, 22565, -1, 22565, 22550, 22566, -1, 21256, 22550, 22565, -1, 22566, 22552, 22567, -1, 22550, 22552, 22566, -1, 22567, 22553, 22568, -1, 22552, 22553, 22567, -1, 22568, 22556, 22569, -1, 22553, 22556, 22568, -1, 22569, 22557, 22570, -1, 22556, 22557, 22569, -1, 22570, 22559, 22571, -1, 22557, 22559, 22570, -1, 22571, 22561, 22572, -1, 22559, 22561, 22571, -1, 22572, 22563, 22573, -1, 22561, 22563, 22572, -1, 22573, 19079, 19081, -1, 22563, 19079, 22573, -1, 22574, 22575, 22576, -1, 22577, 22575, 22578, -1, 22578, 22575, 22574, -1, 22569, 22579, 22568, -1, 22577, 22579, 22575, -1, 22575, 22579, 22569, -1, 22577, 22580, 22579, -1, 22579, 22580, 22568, -1, 22568, 22581, 22567, -1, 22567, 22581, 22582, -1, 22582, 22581, 22577, -1, 22580, 22581, 22568, -1, 22582, 22566, 22567, -1, 22577, 22581, 22580, -1, 22565, 21285, 21259, -1, 19241, 22573, 19081, -1, 21289, 22577, 19069, -1, 22577, 22583, 22582, -1, 22566, 22583, 22565, -1, 22582, 22583, 22566, -1, 22565, 22584, 21285, -1, 22577, 22584, 22583, -1, 22583, 22584, 22565, -1, 21285, 22585, 21287, -1, 21287, 22585, 21289, -1, 22577, 22585, 22584, -1, 21289, 22585, 22577, -1, 22584, 22585, 21285, -1, 19243, 22586, 19241, -1, 22573, 22586, 22572, -1, 19241, 22586, 22573, -1, 22572, 22586, 19243, -1, 19245, 22587, 19243, -1, 22571, 22587, 22570, -1, 22572, 22587, 22571, -1, 19243, 22587, 22572, -1, 19248, 22574, 19247, -1, 19247, 22574, 19245, -1, 19245, 22574, 22587, -1, 22587, 22574, 22570, -1, 19069, 22588, 19250, -1, 19250, 22588, 19248, -1, 22577, 22588, 19069, -1, 22570, 22576, 22569, -1, 22574, 22576, 22570, -1, 22588, 22578, 19248, -1, 22577, 22578, 22588, -1, 19248, 22578, 22574, -1, 22576, 22575, 22569, -1, 22589, 20628, 20627, -1, 22590, 22589, 20627, -1, 22591, 20627, 20572, -1, 22591, 22590, 20627, -1, 22592, 22591, 20572, -1, 22593, 22592, 20572, -1, 20571, 22593, 20572, -1, 21245, 20659, 20657, -1, 21245, 20657, 22594, -1, 22595, 21245, 22594, -1, 22596, 22594, 22597, -1, 22596, 22595, 22594, -1, 22598, 22597, 22599, -1, 22598, 22596, 22597, -1, 22600, 22598, 22599, -1, 22601, 22599, 22602, -1, 22601, 22600, 22599, -1, 22603, 22602, 22604, -1, 22603, 22601, 22602, -1, 22605, 22604, 22606, -1, 22605, 22603, 22604, -1, 22607, 22606, 21067, -1, 22607, 22605, 22606, -1, 21079, 22607, 21067, -1, 22608, 22594, 20657, -1, 22608, 20657, 20656, -1, 22609, 22597, 22594, -1, 22609, 22594, 22608, -1, 22610, 22602, 22599, -1, 22610, 22599, 22597, -1, 22610, 22597, 22609, -1, 22611, 22604, 22602, -1, 22611, 22602, 22610, -1, 22612, 22606, 22604, -1, 22612, 22604, 22611, -1, 22613, 21067, 22606, -1, 22613, 22606, 22612, -1, 21746, 21067, 22613, -1, 22614, 21746, 22613, -1, 22614, 22613, 22612, -1, 22614, 21745, 21746, -1, 22614, 21744, 21745, -1, 22614, 22612, 22615, -1, 22616, 22617, 22618, -1, 22616, 22618, 22619, -1, 22124, 22608, 20656, -1, 22620, 17863, 17864, -1, 22620, 17861, 17863, -1, 22620, 22621, 17861, -1, 22622, 22617, 22616, -1, 22622, 22623, 22617, -1, 22624, 22621, 22620, -1, 22624, 22619, 22621, -1, 22625, 22623, 22622, -1, 22625, 22615, 22623, -1, 22626, 22616, 22619, -1, 22626, 22619, 22624, -1, 22627, 21744, 22614, -1, 22627, 22614, 22615, -1, 22627, 22615, 22625, -1, 22628, 22622, 22616, -1, 22628, 22616, 22626, -1, 22629, 17866, 17867, -1, 22629, 17864, 17866, -1, 22629, 22620, 17864, -1, 22630, 22622, 22628, -1, 22630, 22625, 22622, -1, 22631, 22620, 22629, -1, 22631, 22624, 22620, -1, 22632, 22625, 22630, -1, 22632, 21743, 21744, -1, 22632, 21744, 22627, -1, 22632, 22627, 22625, -1, 22633, 17867, 17869, -1, 22633, 22629, 17867, -1, 22634, 22624, 22631, -1, 22635, 17869, 17871, -1, 22634, 22626, 22624, -1, 22636, 22631, 22629, -1, 22637, 17869, 22635, -1, 22636, 22629, 22633, -1, 22636, 17869, 22637, -1, 22636, 22633, 17869, -1, 22638, 22626, 22634, -1, 22638, 22628, 22626, -1, 22639, 22634, 22631, -1, 22639, 22636, 22637, -1, 22639, 22637, 22640, -1, 22641, 21739, 22642, -1, 21062, 21739, 22641, -1, 22639, 22631, 22636, -1, 22643, 22630, 22628, -1, 22643, 22628, 22638, -1, 22644, 22124, 22125, -1, 22644, 22608, 22124, -1, 22645, 22639, 22640, -1, 22645, 22640, 22642, -1, 22645, 22634, 22639, -1, 22618, 22609, 22608, -1, 22645, 22638, 22634, -1, 22618, 22644, 22125, -1, 22645, 22642, 21739, -1, 22618, 22608, 22644, -1, 22646, 22632, 22630, -1, 22646, 22630, 22643, -1, 22646, 21741, 21743, -1, 22617, 22610, 22609, -1, 22646, 21743, 22632, -1, 22647, 22643, 22638, -1, 22647, 22638, 22645, -1, 22617, 22609, 22618, -1, 22647, 22645, 21739, -1, 22648, 22646, 22643, -1, 22648, 21739, 21741, -1, 22623, 22611, 22610, -1, 22648, 22643, 22647, -1, 22648, 21741, 22646, -1, 22648, 22647, 21739, -1, 22623, 22610, 22617, -1, 22621, 22125, 17861, -1, 22615, 22612, 22611, -1, 22615, 22611, 22623, -1, 22619, 22618, 22125, -1, 22619, 22125, 22621, -1, 17872, 22635, 17871, -1, 22649, 17872, 17874, -1, 22649, 22635, 17872, -1, 22650, 22637, 22635, -1, 22650, 22635, 22649, -1, 22651, 17874, 17876, -1, 22651, 17876, 22652, -1, 22651, 22649, 17874, -1, 22653, 22640, 22637, -1, 22653, 22637, 22650, -1, 22654, 22652, 22655, -1, 22654, 22650, 22649, -1, 22654, 22649, 22651, -1, 22654, 22651, 22652, -1, 22656, 22642, 22640, -1, 22656, 22640, 22653, -1, 22657, 22655, 22658, -1, 22657, 22654, 22655, -1, 22657, 22653, 22650, -1, 22657, 22650, 22654, -1, 22659, 22641, 22642, -1, 22659, 22642, 22656, -1, 22660, 22658, 22661, -1, 22660, 22653, 22657, -1, 22660, 22656, 22653, -1, 22660, 22657, 22658, -1, 22662, 21062, 22641, -1, 22662, 21060, 21062, -1, 22662, 21063, 21060, -1, 22662, 22641, 22659, -1, 22663, 22664, 22665, -1, 22663, 22661, 22664, -1, 22663, 22660, 22661, -1, 22663, 22659, 22656, -1, 22663, 22656, 22660, -1, 22666, 22665, 21058, -1, 22666, 21058, 21063, -1, 22666, 22659, 22663, -1, 22666, 22663, 22665, -1, 22666, 21063, 22662, -1, 22666, 22662, 22659, -1, 17876, 20761, 22667, -1, 22652, 17876, 22667, -1, 22655, 22667, 22668, -1, 22655, 22652, 22667, -1, 22658, 22668, 22669, -1, 22658, 22655, 22668, -1, 22661, 22669, 22670, -1, 22661, 22658, 22669, -1, 22664, 22670, 22671, -1, 22664, 22661, 22670, -1, 22665, 22671, 22672, -1, 22665, 22664, 22671, -1, 21058, 22672, 21059, -1, 21058, 22665, 22672, -1, 22673, 22674, 22675, -1, 22673, 22675, 22676, -1, 22677, 22671, 22670, -1, 22677, 22670, 22678, -1, 22679, 20760, 20759, -1, 22679, 17743, 17745, -1, 22679, 20759, 17743, -1, 22679, 22676, 20760, -1, 22680, 22678, 22681, -1, 22680, 22681, 22682, -1, 22683, 22674, 22673, -1, 22683, 22682, 22674, -1, 22684, 21059, 22672, -1, 22684, 22672, 22671, -1, 22684, 21761, 21059, -1, 22684, 22671, 22677, -1, 22685, 22673, 22676, -1, 22685, 22679, 17745, -1, 22685, 22676, 22679, -1, 22686, 22678, 22680, -1, 22686, 22677, 22678, -1, 17743, 20759, 17740, -1, 22687, 22680, 22682, -1, 22687, 22682, 22683, -1, 22688, 17747, 17749, -1, 22688, 17745, 17747, -1, 22688, 22673, 22685, -1, 22688, 22685, 17745, -1, 22688, 22683, 22673, -1, 22689, 21759, 21761, -1, 22689, 21761, 22684, -1, 22689, 22684, 22677, -1, 22689, 22677, 22686, -1, 22690, 22686, 22680, -1, 22690, 22680, 22687, -1, 22691, 17749, 17751, -1, 22691, 22688, 17749, -1, 22691, 22687, 22683, -1, 22691, 22683, 22688, -1, 22692, 22689, 22686, -1, 22692, 21757, 21759, -1, 22692, 22686, 22690, -1, 22692, 21759, 22689, -1, 22693, 22690, 22687, -1, 22693, 17751, 22694, -1, 22693, 22691, 17751, -1, 22693, 22687, 22691, -1, 22695, 22692, 22690, -1, 22695, 22693, 22694, -1, 22695, 22694, 22696, -1, 22695, 21755, 21757, -1, 22695, 21757, 22692, -1, 22695, 22696, 21755, -1, 20952, 21755, 22696, -1, 22695, 22690, 22693, -1, 22697, 22667, 20761, -1, 22697, 20761, 20763, -1, 22698, 22668, 22667, -1, 22698, 22667, 22697, -1, 22675, 20763, 20762, -1, 22675, 22697, 20763, -1, 22681, 22669, 22668, -1, 22681, 22668, 22698, -1, 22674, 22698, 22697, -1, 22674, 22697, 22675, -1, 22676, 20762, 20760, -1, 22676, 22675, 20762, -1, 22678, 22670, 22669, -1, 22678, 22669, 22681, -1, 22682, 22698, 22674, -1, 22682, 22681, 22698, -1, 17751, 17750, 22699, -1, 22694, 22699, 22700, -1, 22694, 17751, 22699, -1, 22696, 22700, 17914, -1, 22696, 22694, 22700, -1, 20952, 22696, 17914, -1, 22701, 22702, 22703, -1, 22704, 17898, 17904, -1, 22704, 17904, 22705, -1, 22704, 22705, 22706, -1, 22707, 20757, 22708, -1, 22704, 22706, 22709, -1, 22707, 22708, 20756, -1, 22710, 22700, 22699, -1, 20758, 17742, 17741, -1, 22711, 22712, 22713, -1, 22710, 22699, 22714, -1, 22711, 22713, 22701, -1, 22715, 20757, 22707, -1, 22715, 22707, 20756, -1, 22716, 22717, 22712, -1, 22716, 22712, 22711, -1, 22715, 22718, 20757, -1, 22719, 17908, 17912, -1, 22720, 22717, 22716, -1, 22719, 17912, 17914, -1, 22719, 17914, 22700, -1, 22720, 22721, 22717, -1, 22719, 22700, 22710, -1, 22722, 22718, 22715, -1, 22722, 22723, 22718, -1, 22724, 20751, 20753, -1, 22725, 22726, 22723, -1, 22725, 22723, 22722, -1, 22724, 22727, 20751, -1, 22728, 22726, 22725, -1, 22728, 22714, 22726, -1, 22729, 22703, 22727, -1, 22730, 20756, 20755, -1, 22729, 22727, 22724, -1, 22731, 17898, 22704, -1, 22731, 17894, 17898, -1, 22731, 22709, 22721, -1, 22732, 22710, 22714, -1, 22731, 22704, 22709, -1, 22731, 22721, 22720, -1, 22732, 22714, 22728, -1, 22733, 22703, 22729, -1, 22733, 22701, 22703, -1, 22734, 20756, 22730, -1, 22734, 22730, 20755, -1, 22735, 22711, 22701, -1, 22736, 20756, 22734, -1, 22736, 22715, 20756, -1, 22735, 22701, 22733, -1, 22737, 17908, 22719, -1, 22737, 22719, 22710, -1, 22737, 22710, 22732, -1, 22738, 22716, 22711, -1, 22738, 22711, 22735, -1, 22739, 22715, 22736, -1, 22739, 22722, 22715, -1, 22740, 22716, 22738, -1, 22740, 22720, 22716, -1, 22741, 22722, 22739, -1, 22741, 22725, 22722, -1, 22742, 20752, 20798, -1, 22742, 20753, 20752, -1, 22743, 22725, 22741, -1, 22742, 22724, 20753, -1, 22743, 22728, 22725, -1, 22744, 17890, 17894, -1, 22744, 17894, 22731, -1, 22744, 22731, 22720, -1, 22744, 22720, 22740, -1, 22745, 20798, 20797, -1, 22746, 20755, 20754, -1, 22745, 22729, 22724, -1, 22745, 22742, 20798, -1, 22745, 22724, 22742, -1, 22706, 22732, 22728, -1, 22747, 20797, 20795, -1, 22747, 22729, 22745, -1, 22747, 22733, 22729, -1, 22706, 22728, 22743, -1, 22702, 22734, 20755, -1, 22747, 22745, 20797, -1, 22702, 20755, 22746, -1, 22748, 22747, 20795, -1, 22748, 22733, 22747, -1, 22748, 20795, 20792, -1, 22748, 22735, 22733, -1, 22705, 17904, 17908, -1, 22749, 20793, 20794, -1, 22749, 20792, 20793, -1, 22705, 22737, 22732, -1, 22749, 22735, 22748, -1, 22705, 17908, 22737, -1, 22749, 22748, 20792, -1, 22705, 22732, 22706, -1, 22749, 22738, 22735, -1, 22750, 20794, 20796, -1, 22750, 22749, 20794, -1, 22750, 22738, 22749, -1, 22713, 22736, 22734, -1, 22750, 22740, 22738, -1, 22713, 22734, 22702, -1, 22751, 20796, 17886, -1, 22751, 22740, 22750, -1, 22751, 17886, 17890, -1, 22751, 22750, 20796, -1, 22751, 17890, 22744, -1, 22712, 22736, 22713, -1, 22752, 20758, 20757, -1, 22751, 22744, 22740, -1, 22752, 17742, 20758, -1, 22712, 22739, 22736, -1, 22717, 22739, 22712, -1, 22717, 22741, 22739, -1, 22753, 17744, 17742, -1, 22753, 22752, 20757, -1, 22753, 17742, 22752, -1, 22721, 22741, 22717, -1, 22718, 17746, 17744, -1, 22721, 22743, 22741, -1, 22718, 22753, 20757, -1, 22718, 17744, 22753, -1, 22727, 22746, 20754, -1, 22727, 20754, 20751, -1, 22723, 17748, 17746, -1, 22723, 17746, 22718, -1, 22703, 22702, 22746, -1, 22726, 17750, 17748, -1, 22726, 17748, 22723, -1, 22703, 22746, 22727, -1, 22714, 22699, 17750, -1, 22709, 22706, 22743, -1, 22714, 17750, 22726, -1, 22709, 22743, 22721, -1, 22701, 22713, 22702, -1, 22708, 20757, 20756, -1, 22754, 22755, 22756, -1, 22757, 20846, 22758, -1, 22754, 22759, 22755, -1, 22760, 22759, 22754, -1, 22761, 22762, 22763, -1, 20839, 17729, 17728, -1, 22761, 22763, 22764, -1, 22760, 22765, 22759, -1, 22766, 22765, 22760, -1, 17730, 17729, 20839, -1, 22767, 22758, 22768, -1, 22766, 22769, 22765, -1, 22770, 20841, 20842, -1, 22767, 20845, 22757, -1, 22767, 22757, 22758, -1, 22770, 22771, 20841, -1, 22767, 22772, 20845, -1, 22773, 17879, 17878, -1, 22773, 17881, 17879, -1, 22774, 17901, 17896, -1, 22773, 22775, 22762, -1, 22774, 22776, 22769, -1, 22773, 17878, 22775, -1, 22774, 22766, 17901, -1, 22773, 22762, 22761, -1, 22774, 22769, 22766, -1, 22774, 17896, 22776, -1, 22777, 22768, 22778, -1, 22777, 22779, 22772, -1, 22777, 22767, 22768, -1, 22780, 22771, 22770, -1, 22777, 22772, 22767, -1, 22780, 22756, 22771, -1, 22781, 22778, 22782, -1, 22781, 22777, 22778, -1, 22781, 22764, 22779, -1, 22783, 22754, 22756, -1, 22781, 22779, 22777, -1, 22783, 22756, 22780, -1, 22784, 22782, 22785, -1, 22784, 22764, 22781, -1, 22786, 22754, 22783, -1, 22786, 22760, 22754, -1, 22784, 22761, 22764, -1, 22784, 22781, 22782, -1, 22787, 22788, 20948, -1, 22789, 22760, 22786, -1, 22787, 22785, 22788, -1, 22787, 20948, 17881, -1, 22789, 22766, 22760, -1, 22787, 17881, 22773, -1, 22789, 17901, 22766, -1, 22787, 22773, 22761, -1, 22787, 22784, 22785, -1, 22790, 20843, 20844, -1, 22787, 22761, 22784, -1, 22790, 20842, 20843, -1, 22790, 22770, 20842, -1, 22791, 22789, 17903, -1, 22791, 17901, 22789, -1, 22791, 17903, 17901, -1, 22792, 22770, 22790, -1, 22792, 22780, 22770, -1, 22793, 22780, 22792, -1, 22793, 22783, 22780, -1, 22794, 22783, 22793, -1, 22794, 22786, 22783, -1, 22795, 22789, 22786, -1, 22795, 17903, 22789, -1, 22795, 22786, 22794, -1, 22796, 22790, 20844, -1, 22797, 17903, 22795, -1, 22797, 22795, 17907, -1, 22797, 17907, 17903, -1, 22798, 22790, 22796, -1, 22798, 22792, 22790, -1, 22799, 22792, 22798, -1, 22799, 22793, 22792, -1, 22800, 20840, 20841, -1, 22800, 20839, 20840, -1, 22763, 22793, 22799, -1, 22763, 22794, 22793, -1, 22762, 22795, 22794, -1, 22762, 17907, 22795, -1, 22762, 22794, 22763, -1, 22755, 17730, 20839, -1, 22801, 20844, 20845, -1, 22755, 20839, 22800, -1, 22759, 17732, 17730, -1, 22759, 17730, 22755, -1, 22801, 22796, 20844, -1, 22765, 17734, 17732, -1, 22775, 17907, 22762, -1, 22775, 17878, 17907, -1, 22765, 17732, 22759, -1, 22769, 17736, 17734, -1, 22772, 22801, 20845, -1, 22769, 17734, 22765, -1, 22772, 22796, 22801, -1, 22772, 22798, 22796, -1, 22771, 22800, 20841, -1, 22779, 22799, 22798, -1, 22776, 17738, 17736, -1, 22776, 17896, 17738, -1, 22776, 17736, 22769, -1, 22779, 22798, 22772, -1, 22756, 22800, 22771, -1, 22764, 22763, 22799, -1, 22756, 22755, 22800, -1, 22764, 22799, 22779, -1, 22757, 20845, 20846, -1, 22758, 20846, 20865, -1, 22758, 20865, 22802, -1, 22768, 22802, 22803, -1, 22768, 22758, 22802, -1, 22778, 22803, 22804, -1, 22778, 22768, 22803, -1, 22782, 22804, 22805, -1, 22782, 22778, 22804, -1, 22785, 22805, 22806, -1, 22785, 22782, 22805, -1, 22788, 22807, 20951, -1, 22788, 22806, 22807, -1, 22788, 22785, 22806, -1, 20948, 22788, 20951, -1, 22808, 20881, 20869, -1, 22808, 20869, 22809, -1, 22810, 22809, 22811, -1, 22810, 20881, 22808, -1, 22810, 22808, 22809, -1, 22812, 22811, 22813, -1, 22812, 20881, 22810, -1, 22812, 22814, 20881, -1, 22812, 22810, 22811, -1, 22815, 22816, 22817, -1, 22815, 22813, 22816, -1, 22815, 22818, 22814, -1, 22815, 22812, 22813, -1, 22815, 22814, 22812, -1, 20870, 22806, 22805, -1, 20870, 22805, 22804, -1, 22819, 22818, 22815, -1, 20870, 22804, 22803, -1, 22819, 22820, 22818, -1, 20870, 22803, 22802, -1, 20870, 22802, 20865, -1, 22819, 22815, 22817, -1, 22821, 22819, 22817, -1, 22821, 22820, 22819, -1, 22821, 22817, 22822, -1, 22821, 22822, 21747, -1, 22821, 21747, 22823, -1, 22821, 22823, 22820, -1, 19117, 21747, 22822, -1, 22824, 20870, 20880, -1, 22825, 22824, 20880, -1, 22825, 20870, 22824, -1, 22826, 20870, 22825, -1, 22826, 22825, 20880, -1, 22827, 22806, 20870, -1, 22827, 22826, 20880, -1, 22827, 20870, 22826, -1, 22828, 22807, 22806, -1, 22828, 22806, 22827, -1, 21753, 20951, 22807, -1, 21753, 22807, 22828, -1, 22829, 20880, 20882, -1, 22830, 20880, 22829, -1, 22830, 22829, 20882, -1, 22831, 22830, 20882, -1, 22831, 20880, 22830, -1, 22832, 20880, 22831, -1, 22832, 22827, 20880, -1, 22833, 22828, 22827, -1, 22833, 21753, 22828, -1, 22833, 22827, 22832, -1, 21751, 22833, 21749, -1, 21751, 21753, 22833, -1, 22834, 20882, 20881, -1, 22814, 20882, 22834, -1, 22814, 22834, 20881, -1, 22818, 22831, 20882, -1, 22818, 20882, 22814, -1, 22820, 22831, 22818, -1, 22820, 22832, 22831, -1, 22823, 21747, 21749, -1, 22823, 21749, 22833, -1, 22823, 22833, 22832, -1, 22823, 22832, 22820, -1, 20869, 20820, 22835, -1, 22809, 22835, 22836, -1, 22809, 20869, 22835, -1, 22811, 22836, 22837, -1, 22811, 22809, 22836, -1, 22813, 22837, 22838, -1, 22813, 22811, 22837, -1, 22816, 22838, 22839, -1, 22816, 22813, 22838, -1, 22817, 22839, 22840, -1, 22817, 22816, 22839, -1, 22822, 22840, 19125, -1, 22822, 22817, 22840, -1, 19117, 22822, 19125, -1, 22841, 22842, 22129, -1, 22841, 22130, 22842, -1, 22843, 22841, 22129, -1, 22843, 22130, 22841, -1, 22844, 22843, 22129, -1, 22844, 22130, 22843, -1, 22845, 22844, 22129, -1, 22845, 22130, 22844, -1, 22846, 22845, 22129, -1, 22846, 22130, 22845, -1, 22846, 22129, 22130, -1, 22847, 22129, 19127, -1, 22847, 19127, 22128, -1, 22848, 22847, 22128, -1, 22848, 22129, 22847, -1, 22849, 22848, 22128, -1, 22849, 22129, 22848, -1, 22850, 22849, 22128, -1, 22850, 22129, 22849, -1, 22851, 22850, 22128, -1, 22851, 22129, 22850, -1, 22852, 22851, 22128, -1, 22852, 22129, 22851, -1, 22853, 22128, 22129, -1, 22853, 22852, 22128, -1, 22853, 22129, 22852, -1, 19123, 17707, 17706, -1, 22854, 22128, 19128, -1, 22855, 22128, 22854, -1, 22856, 22128, 22855, -1, 22857, 22128, 22856, -1, 22132, 17716, 17715, -1, 22132, 17719, 17716, -1, 22858, 22857, 22127, -1, 22132, 17722, 17719, -1, 22858, 22128, 22857, -1, 22132, 17725, 17722, -1, 22859, 22858, 22127, -1, 22859, 22128, 22858, -1, 22860, 22127, 22128, -1, 22860, 22859, 22127, -1, 22860, 22128, 22859, -1, 22861, 19128, 19125, -1, 22861, 19125, 22840, -1, 22861, 22840, 22839, -1, 22861, 22839, 22838, -1, 22861, 22838, 22837, -1, 22861, 22854, 19128, -1, 22861, 22855, 22854, -1, 22861, 22856, 22855, -1, 22861, 22127, 22857, -1, 22861, 22857, 22856, -1, 22862, 22837, 22836, -1, 22862, 22861, 22837, -1, 22862, 22127, 22861, -1, 22863, 22836, 22835, -1, 22129, 19126, 19127, -1, 22863, 22127, 22862, -1, 22863, 22862, 22836, -1, 22864, 22835, 20820, -1, 22864, 22126, 22127, -1, 22864, 20820, 22126, -1, 22864, 22127, 22863, -1, 22864, 22863, 22835, -1, 19128, 22128, 19127, -1, 22865, 17707, 19123, -1, 22866, 17709, 17707, -1, 22866, 17707, 22865, -1, 22867, 17713, 17709, -1, 22867, 22866, 22131, -1, 22867, 17709, 22866, -1, 22868, 17715, 17713, -1, 22868, 22132, 17715, -1, 22868, 17713, 22867, -1, 22868, 22867, 22131, -1, 22869, 22868, 22131, -1, 22869, 22132, 22868, -1, 22870, 22132, 22869, -1, 22870, 22869, 22131, -1, 22871, 22131, 22132, -1, 22871, 22870, 22131, -1, 22871, 22132, 22870, -1, 22872, 19123, 19124, -1, 22872, 22865, 19123, -1, 22873, 22131, 22866, -1, 22873, 22872, 22130, -1, 22873, 22865, 22872, -1, 22873, 22866, 22865, -1, 22874, 22131, 22873, -1, 22874, 22873, 22130, -1, 22875, 22131, 22874, -1, 22875, 22874, 22130, -1, 22876, 22131, 22875, -1, 22876, 22875, 22130, -1, 22877, 22876, 22130, -1, 22877, 22131, 22876, -1, 22878, 22130, 22131, -1, 22878, 22877, 22130, -1, 22878, 22131, 22877, -1, 22879, 19124, 19126, -1, 22879, 22130, 22872, -1, 22879, 19126, 22129, -1, 22879, 22872, 19124, -1, 22842, 22879, 22129, -1, 22842, 22130, 22879, -1, 22082, 21242, 21245, -1, 22082, 21245, 22595, -1, 22083, 22595, 22596, -1, 22083, 22082, 22595, -1, 22084, 22596, 22598, -1, 22084, 22083, 22596, -1, 21076, 22607, 21079, -1, 21076, 22605, 22607, -1, 22085, 22600, 22601, -1, 22085, 22598, 22600, -1, 22085, 22084, 22598, -1, 22086, 22603, 22605, -1, 22086, 22601, 22603, -1, 22086, 22605, 21076, -1, 22086, 22085, 22601, -1, 22087, 21076, 21075, -1, 22087, 22086, 21076, -1, 22088, 21075, 21073, -1, 22088, 22087, 21075, -1, 22089, 21073, 21074, -1, 22089, 22088, 21073, -1, 19112, 21074, 19115, -1, 19112, 22089, 21074, -1, 22880, 22881, 22882, -1, 22883, 22881, 22880, -1, 22882, 22884, 22885, -1, 22881, 22884, 22882, -1, 21777, 20930, 21774, -1, 21774, 20930, 21773, -1, 21773, 20930, 21771, -1, 21771, 20930, 21769, -1, 21769, 20930, 20586, -1, 22886, 20930, 21777, -1, 22887, 20930, 22886, -1, 22888, 20930, 22887, -1, 22885, 20930, 22888, -1, 22884, 20930, 22885, -1, 20586, 20947, 20589, -1, 20930, 20947, 20586, -1, 21217, 21218, 20947, -1, 20947, 21221, 20589, -1, 21218, 21221, 20947, -1, 21221, 21110, 20589, -1, 20589, 21112, 20590, -1, 21110, 21112, 20589, -1, 20592, 22046, 19113, -1, 20593, 22047, 22046, -1, 20593, 22046, 20592, -1, 20591, 21112, 22047, -1, 20591, 22047, 20593, -1, 20590, 21112, 20591, -1, 19113, 20595, 20592, -1, 19113, 19114, 20595, -1, 19114, 21077, 20595, -1, 21078, 20596, 21077, -1, 20596, 20595, 21077, -1, 21080, 20596, 21078, -1, 21080, 22108, 20596, -1, 21081, 22108, 21080, -1, 21082, 22106, 22108, -1, 21082, 22108, 21081, -1, 21084, 22104, 22106, -1, 21084, 22106, 21082, -1, 21085, 22102, 22104, -1, 21085, 22104, 21084, -1, 21083, 20694, 22102, -1, 21083, 22102, 21085, -1, 20708, 21083, 21072, -1, 20708, 20694, 21083, -1, 21071, 20708, 21072, -1, 21071, 22121, 20708, -1, 21070, 22121, 21071, -1, 21069, 22119, 22121, -1, 21069, 22121, 21070, -1, 21068, 22117, 22119, -1, 21068, 22119, 21069, -1, 21066, 22116, 22117, -1, 21066, 22117, 21068, -1, 21065, 22114, 22116, -1, 21065, 22116, 21066, -1, 22112, 21740, 21064, -1, 22112, 21064, 22110, -1, 22113, 21742, 21740, -1, 22113, 21740, 22112, -1, 22114, 21065, 21742, -1, 22114, 21742, 22113, -1, 21061, 22110, 21064, -1, 21061, 20731, 22110, -1, 21057, 20731, 21061, -1, 20728, 20731, 21057, -1, 21756, 20953, 20720, -1, 21756, 20720, 20730, -1, 21758, 20730, 20734, -1, 21758, 21756, 20730, -1, 21760, 20734, 20732, -1, 21760, 21758, 20734, -1, 21762, 20732, 20733, -1, 21762, 21760, 20732, -1, 21057, 20733, 20728, -1, 21057, 21762, 20733, -1, 17915, 20720, 20953, -1, 20721, 20720, 17915, -1, 20740, 17884, 17883, -1, 20740, 17883, 20736, -1, 20737, 17887, 17884, -1, 20737, 17884, 20740, -1, 20739, 17888, 17887, -1, 20739, 17887, 20737, -1, 20738, 17891, 17888, -1, 20738, 17888, 20739, -1, 20741, 17892, 17891, -1, 20741, 17891, 20738, -1, 20742, 17897, 17892, -1, 20742, 17892, 20741, -1, 20744, 17899, 17897, -1, 20744, 17905, 17899, -1, 20744, 17897, 20742, -1, 20745, 17909, 17905, -1, 20745, 17910, 17909, -1, 20745, 17905, 20744, -1, 20721, 17915, 17913, -1, 20721, 17913, 17910, -1, 20721, 17910, 20745, -1, 20614, 20736, 17883, -1, 20716, 20736, 20614, -1, 20613, 20716, 20614, -1, 20613, 22111, 20716, -1, 20612, 22111, 20613, -1, 20611, 22115, 22111, -1, 20611, 22111, 20612, -1, 20610, 22115, 20611, -1, 20609, 22118, 22115, -1, 20609, 22115, 20610, -1, 20608, 22118, 20609, -1, 20606, 22120, 22118, -1, 20606, 22118, 20608, -1, 20605, 22122, 22120, -1, 20605, 22120, 20606, -1, 20607, 22123, 22122, -1, 20607, 20699, 22123, -1, 20607, 22122, 20605, -1, 20598, 20699, 20607, -1, 20691, 20699, 20598, -1, 20597, 20691, 20598, -1, 20597, 22103, 20691, -1, 20599, 22105, 22103, -1, 20599, 22103, 20597, -1, 20600, 22107, 22105, -1, 20600, 22109, 22107, -1, 20600, 22105, 20599, -1, 20601, 20594, 22109, -1, 20601, 22109, 20600, -1, 22889, 20601, 21162, -1, 22890, 20601, 22889, -1, 21162, 20601, 20625, -1, 22891, 20594, 22890, -1, 22892, 20594, 22891, -1, 22890, 20594, 20601, -1, 20587, 20594, 22893, -1, 22893, 20594, 22894, -1, 22894, 20594, 22895, -1, 22895, 20594, 22896, -1, 22896, 20594, 22892, -1, 19119, 17148, 18884, -1, 17133, 20960, 17131, -1, 17135, 20960, 17133, -1, 17137, 20960, 17135, -1, 17138, 20960, 17137, -1, 17139, 20960, 17138, -1, 17141, 20960, 17139, -1, 17142, 20960, 17141, -1, 17144, 20960, 17142, -1, 17145, 20960, 17144, -1, 17146, 20960, 17145, -1, 17148, 20960, 17146, -1, 17148, 22037, 20960, -1, 20960, 20959, 22897, -1, 20960, 22897, 17131, -1, 19119, 19118, 22041, -1, 19119, 22041, 22039, -1, 19119, 22039, 22037, -1, 19119, 22037, 17148, -1, 18885, 19119, 18884, -1, 18885, 21748, 19119, -1, 18872, 21748, 18885, -1, 18874, 21750, 21748, -1, 18874, 21748, 18872, -1, 18871, 21752, 21750, -1, 18871, 21750, 18874, -1, 18873, 21754, 21752, -1, 18873, 21752, 18871, -1, 18861, 20949, 21754, -1, 18861, 21754, 18873, -1, 20950, 18861, 18852, -1, 20950, 20949, 18861, -1, 18852, 17880, 20950, -1, 18851, 17880, 18852, -1, 18850, 17877, 17880, -1, 18850, 17880, 18851, -1, 18848, 17911, 17877, -1, 18848, 17877, 18850, -1, 18847, 17906, 17911, -1, 18847, 17911, 18848, -1, 18845, 17902, 17906, -1, 18845, 17900, 17902, -1, 18845, 17906, 18847, -1, 18837, 17895, 17900, -1, 18837, 17900, 18845, -1, 18839, 17893, 17895, -1, 18839, 17895, 18837, -1, 18838, 17889, 17893, -1, 18838, 17893, 18839, -1, 18844, 17882, 17889, -1, 18844, 17889, 18838, -1, 18846, 17885, 17882, -1, 18846, 17882, 18844, -1, 18846, 18802, 17885, -1, 17885, 18802, 20624, -1, 18800, 20624, 18802, -1, 18800, 20623, 20624, -1, 18798, 20622, 20623, -1, 18798, 20623, 18800, -1, 18796, 20621, 20622, -1, 18796, 20622, 18798, -1, 18794, 20620, 20621, -1, 18794, 20621, 18796, -1, 18792, 20619, 20620, -1, 18792, 20620, 18794, -1, 18790, 20618, 20619, -1, 18790, 20619, 18792, -1, 19217, 20617, 20618, -1, 19217, 20618, 18790, -1, 19214, 20616, 20617, -1, 19214, 20617, 19217, -1, 19083, 20615, 20616, -1, 19083, 20616, 19214, -1, 20615, 17653, 17652, -1, 19083, 17653, 20615, -1, 22898, 22899, 20604, -1, 22899, 20347, 20604, -1, 20347, 20626, 20604, -1, 20347, 21151, 20626, -1, 20347, 22900, 21151, -1, 20347, 22901, 22900, -1, 20347, 22902, 22901, -1, 20347, 22903, 22902, -1, 20347, 22904, 22903, -1, 20347, 20450, 21179, -1, 20347, 21179, 22905, -1, 20347, 22905, 22906, -1, 20347, 22906, 22904, -1, 21053, 17671, 17673, -1, 21053, 17674, 17671, -1, 21053, 17675, 17674, -1, 20294, 17678, 22907, -1, 22907, 17677, 22908, -1, 17678, 17677, 22907, -1, 22908, 17679, 22909, -1, 17677, 17679, 22908, -1, 22909, 17664, 22910, -1, 17679, 17664, 22909, -1, 17664, 17666, 22910, -1, 22910, 17669, 20572, -1, 17666, 17669, 22910, -1, 22907, 22100, 20294, -1, 20294, 22100, 20301, -1, 22908, 22098, 22907, -1, 22907, 22098, 22100, -1, 22909, 22096, 22908, -1, 22908, 22096, 22098, -1, 22909, 22094, 22096, -1, 22910, 22092, 22909, -1, 22909, 22092, 22094, -1, 20572, 22091, 22910, -1, 22910, 22091, 22092, -1, 20572, 20627, 22091, -1, 22911, 21779, 21780, -1, 22911, 21780, 22912, -1, 22911, 22913, 22914, -1, 22911, 22912, 22913, -1, 22915, 22887, 22886, -1, 22915, 22916, 22887, -1, 22915, 22914, 22916, -1, 20929, 22917, 20932, -1, 22915, 21779, 22911, -1, 22915, 22886, 21779, -1, 22915, 22911, 22914, -1, 22884, 20931, 20930, -1, 21777, 21779, 22886, -1, 22918, 22919, 22917, -1, 22918, 20929, 20931, -1, 22918, 22917, 20929, -1, 22920, 22921, 22919, -1, 22920, 22919, 22918, -1, 22920, 22918, 22883, -1, 22922, 22881, 22883, -1, 22922, 22884, 22881, -1, 22922, 20931, 22884, -1, 22922, 22883, 22918, -1, 22922, 22918, 20931, -1, 22923, 22924, 22921, -1, 22923, 22921, 22920, -1, 22923, 22920, 22882, -1, 22925, 22880, 22882, -1, 22925, 22883, 22880, -1, 22925, 22920, 22883, -1, 22925, 22882, 22920, -1, 22913, 22926, 22924, -1, 22913, 22924, 22923, -1, 22927, 22885, 22888, -1, 22927, 22882, 22885, -1, 22927, 22923, 22882, -1, 22912, 21780, 21104, -1, 22912, 22928, 22926, -1, 22912, 21104, 22928, -1, 22912, 22926, 22913, -1, 22914, 22927, 22888, -1, 22914, 22913, 22923, -1, 22914, 22923, 22927, -1, 22916, 22888, 22887, -1, 22916, 22914, 22888, -1, 20933, 20932, 22917, -1, 22929, 22917, 22919, -1, 22929, 20933, 22917, -1, 22930, 22919, 22921, -1, 22930, 22929, 22919, -1, 22931, 22921, 22924, -1, 22931, 22930, 22921, -1, 22932, 22924, 22926, -1, 22932, 22931, 22924, -1, 22933, 22926, 22928, -1, 22933, 22932, 22926, -1, 22934, 22933, 22928, -1, 21105, 22928, 21104, -1, 21105, 22934, 22928, -1, 22935, 22936, 22937, -1, 22935, 22938, 22936, -1, 22935, 22939, 22938, -1, 22935, 22940, 22939, -1, 22941, 20933, 22929, -1, 22941, 22929, 22930, -1, 22941, 20935, 20933, -1, 21767, 22934, 21105, -1, 22941, 22930, 22942, -1, 22943, 22942, 22944, -1, 22943, 22944, 22945, -1, 22946, 22937, 22947, -1, 22946, 22935, 22937, -1, 22946, 22945, 22940, -1, 22946, 22940, 22935, -1, 22948, 20922, 20935, -1, 22948, 20935, 22941, -1, 22948, 22941, 22942, -1, 22948, 22942, 22943, -1, 22949, 22947, 22950, -1, 22949, 22943, 22945, -1, 22949, 22946, 22947, -1, 22949, 22945, 22946, -1, 22951, 22950, 22952, -1, 22951, 20917, 20922, -1, 22951, 20922, 22948, -1, 22951, 22943, 22949, -1, 22951, 22952, 20917, -1, 22953, 21763, 21106, -1, 22951, 22949, 22950, -1, 22951, 22948, 22943, -1, 20910, 20917, 22952, -1, 22954, 22933, 22934, -1, 22954, 22934, 21767, -1, 22955, 22933, 22954, -1, 22956, 21767, 21765, -1, 22956, 22954, 21767, -1, 22957, 22932, 22933, -1, 22957, 22933, 22955, -1, 22939, 22954, 22956, -1, 22939, 22955, 22954, -1, 22958, 21765, 21763, -1, 22958, 21763, 22953, -1, 22958, 22956, 21765, -1, 22944, 22931, 22932, -1, 22944, 22932, 22957, -1, 22940, 22957, 22955, -1, 22940, 22955, 22939, -1, 22938, 22953, 22936, -1, 22938, 22939, 22956, -1, 22938, 22956, 22958, -1, 22938, 22958, 22953, -1, 22942, 22930, 22931, -1, 22942, 22931, 22944, -1, 22945, 22957, 22940, -1, 22945, 22944, 22957, -1, 20911, 20910, 22952, -1, 22959, 20911, 22952, -1, 22960, 22952, 22950, -1, 22960, 22959, 22952, -1, 22961, 22950, 22947, -1, 22961, 22960, 22950, -1, 22962, 22947, 22937, -1, 22962, 22961, 22947, -1, 22963, 22937, 22936, -1, 22963, 22962, 22937, -1, 22964, 22936, 22953, -1, 22964, 22963, 22936, -1, 21108, 22953, 21106, -1, 21108, 22964, 22953, -1, 22965, 20911, 22959, -1, 22965, 20925, 20911, -1, 22965, 20926, 20925, -1, 22965, 22966, 20926, -1, 22967, 22968, 22969, -1, 22967, 22969, 22970, -1, 22971, 22972, 22973, -1, 22971, 22970, 22972, -1, 22974, 22975, 22976, -1, 22974, 22973, 22975, -1, 22977, 22959, 22960, -1, 22977, 22966, 22965, -1, 22977, 22965, 22959, -1, 22977, 22976, 22966, -1, 22978, 22979, 22968, -1, 22978, 22968, 22967, -1, 22978, 21783, 22979, -1, 22980, 22967, 22970, -1, 22980, 22970, 22971, -1, 22981, 22971, 22973, -1, 22981, 22973, 22974, -1, 22982, 22960, 22961, -1, 22982, 22977, 22960, -1, 22982, 22974, 22976, -1, 22982, 22976, 22977, -1, 22983, 21784, 21783, -1, 22983, 21783, 22978, -1, 22983, 22978, 22967, -1, 22983, 22967, 22980, -1, 21783, 21099, 22979, -1, 22984, 22971, 22981, -1, 22984, 22980, 22971, -1, 22985, 22961, 22962, -1, 22985, 22982, 22961, -1, 22985, 22981, 22974, -1, 22985, 22974, 22982, -1, 22986, 22983, 22980, -1, 22986, 21787, 21784, -1, 22986, 21784, 22983, -1, 22986, 22980, 22984, -1, 22987, 22984, 22981, -1, 22987, 22962, 22963, -1, 22987, 22981, 22985, -1, 22987, 22985, 22962, -1, 22988, 22987, 22963, -1, 22988, 22963, 22964, -1, 22988, 22964, 21108, -1, 22988, 22986, 22984, -1, 22988, 21789, 21787, -1, 22988, 21108, 21789, -1, 22988, 22984, 22987, -1, 22988, 21787, 22986, -1, 22989, 22990, 20921, -1, 22989, 20921, 20927, -1, 22991, 22992, 22990, -1, 22991, 22990, 22989, -1, 22993, 20927, 20924, -1, 22993, 22989, 20927, -1, 22972, 22994, 22992, -1, 22972, 22992, 22991, -1, 22975, 22989, 22993, -1, 22975, 22991, 22989, -1, 22966, 20924, 20926, -1, 22966, 22993, 20924, -1, 22970, 22969, 22994, -1, 22970, 22994, 22972, -1, 22973, 22991, 22975, -1, 22973, 22972, 22991, -1, 22976, 22993, 22966, -1, 22976, 22975, 22993, -1, 22979, 21099, 21098, -1, 22979, 21098, 22995, -1, 22968, 22995, 22996, -1, 22968, 22979, 22995, -1, 22969, 22996, 22997, -1, 22969, 22968, 22996, -1, 22994, 22997, 22998, -1, 22994, 22969, 22997, -1, 22992, 22998, 22999, -1, 22992, 22994, 22998, -1, 22990, 22999, 23000, -1, 22990, 22992, 22999, -1, 20921, 23000, 20903, -1, 20921, 22990, 23000, -1, 23001, 23002, 23003, -1, 23004, 21211, 21212, -1, 23005, 23006, 23007, -1, 23004, 23008, 23009, -1, 23005, 23010, 23006, -1, 23004, 23009, 23011, -1, 23004, 21212, 23008, -1, 23012, 22997, 22996, -1, 20899, 23013, 20905, -1, 23014, 23007, 23015, -1, 23012, 23001, 22997, -1, 23012, 23011, 23016, -1, 23014, 23015, 23017, -1, 23012, 23016, 23001, -1, 23018, 22996, 22995, -1, 23018, 23012, 22996, -1, 23019, 20897, 20904, -1, 23018, 21210, 21211, -1, 23018, 23004, 23011, -1, 23019, 23017, 20897, -1, 23018, 23011, 23012, -1, 23018, 21211, 23004, -1, 23018, 22995, 21210, -1, 23020, 23021, 23022, -1, 23020, 23022, 23023, -1, 23024, 23010, 23005, -1, 23024, 23023, 23010, -1, 23025, 23007, 23014, -1, 23025, 23005, 23007, -1, 23026, 23014, 23017, -1, 23026, 23017, 23019, -1, 23027, 23028, 23021, -1, 23027, 21215, 23028, -1, 23027, 23021, 23020, -1, 21215, 21093, 23028, -1, 23029, 20904, 20901, -1, 23029, 23019, 20904, -1, 23030, 23020, 23023, -1, 23030, 23023, 23024, -1, 23031, 23024, 23005, -1, 23031, 23005, 23025, -1, 23032, 23025, 23014, -1, 23032, 23014, 23026, -1, 23033, 23019, 23029, -1, 23033, 23026, 23019, -1, 23034, 23020, 23030, -1, 23034, 21214, 21215, -1, 23034, 21215, 23027, -1, 23034, 23027, 23020, -1, 23035, 20903, 23000, -1, 23035, 20901, 20903, -1, 23035, 23029, 20901, -1, 23036, 23030, 23024, -1, 23036, 23024, 23031, -1, 23037, 23031, 23025, -1, 23037, 23025, 23032, -1, 21098, 21210, 22995, -1, 23002, 23032, 23026, -1, 23002, 23026, 23033, -1, 23038, 20899, 20898, -1, 23038, 23013, 20899, -1, 23039, 23000, 22999, -1, 23039, 23033, 23029, -1, 23039, 23029, 23035, -1, 23006, 23040, 23013, -1, 23039, 23035, 23000, -1, 23041, 21213, 21214, -1, 23041, 23030, 23036, -1, 23006, 23013, 23038, -1, 23041, 21214, 23034, -1, 23041, 23034, 23030, -1, 23015, 20898, 20895, -1, 23009, 23036, 23031, -1, 23009, 23031, 23037, -1, 23015, 23038, 20898, -1, 23016, 23037, 23032, -1, 23010, 23042, 23040, -1, 23010, 23040, 23006, -1, 23016, 23032, 23002, -1, 23003, 22999, 22998, -1, 23007, 23038, 23015, -1, 23003, 23002, 23033, -1, 23003, 23033, 23039, -1, 23007, 23006, 23038, -1, 23003, 23039, 22999, -1, 23008, 21212, 21213, -1, 23008, 21213, 23041, -1, 23008, 23041, 23036, -1, 23017, 20895, 20897, -1, 23008, 23036, 23009, -1, 23017, 23015, 20895, -1, 23011, 23037, 23016, -1, 23023, 23022, 23042, -1, 23011, 23009, 23037, -1, 23023, 23042, 23010, -1, 23001, 22998, 22997, -1, 23001, 23003, 22998, -1, 23001, 23016, 23002, -1, 23028, 21093, 21092, -1, 23028, 21092, 23043, -1, 23021, 23043, 23044, -1, 23021, 23028, 23043, -1, 23022, 23044, 23045, -1, 23022, 23021, 23044, -1, 23042, 23045, 23046, -1, 23042, 23022, 23045, -1, 23040, 23046, 23047, -1, 23040, 23042, 23046, -1, 23013, 23047, 23048, -1, 23013, 23040, 23047, -1, 20905, 23048, 20885, -1, 20905, 23013, 23048, -1, 23049, 23047, 23046, -1, 23049, 23050, 23051, -1, 23049, 23052, 23047, -1, 23049, 23051, 23052, -1, 23053, 21230, 21088, -1, 23053, 21088, 23054, -1, 23053, 23054, 23055, -1, 23056, 23055, 23057, -1, 23056, 23057, 23058, -1, 23059, 23046, 23045, -1, 23059, 23050, 23049, -1, 23059, 23049, 23046, -1, 23059, 23058, 23050, -1, 23060, 21228, 21230, -1, 23060, 21230, 23053, -1, 23060, 23053, 23055, -1, 23060, 23055, 23056, -1, 23061, 23045, 23044, -1, 23061, 23059, 23045, -1, 23061, 23056, 23058, -1, 23061, 23058, 23059, -1, 23062, 23044, 23043, -1, 23062, 21226, 21228, -1, 23062, 23061, 23044, -1, 23062, 23043, 21226, -1, 23062, 21228, 23060, -1, 23048, 20888, 20885, -1, 23062, 23060, 23056, -1, 23062, 23056, 23061, -1, 21092, 21226, 23043, -1, 23063, 23064, 20891, -1, 23063, 20891, 20890, -1, 23065, 23066, 23064, -1, 23065, 23064, 23063, -1, 23067, 20890, 20889, -1, 23067, 23063, 20890, -1, 23068, 23069, 23066, -1, 23068, 23070, 23069, -1, 23068, 23066, 23065, -1, 23051, 23063, 23067, -1, 23051, 23065, 23063, -1, 23071, 20889, 20888, -1, 23071, 23067, 20889, -1, 23071, 20888, 23048, -1, 23057, 23070, 23068, -1, 23050, 23065, 23051, -1, 23050, 23068, 23065, -1, 23052, 23048, 23047, -1, 23052, 23067, 23071, -1, 23052, 23051, 23067, -1, 23052, 23071, 23048, -1, 23055, 23072, 23070, -1, 23055, 23054, 23072, -1, 23055, 23070, 23057, -1, 23058, 23068, 23050, -1, 23058, 23057, 23068, -1, 23054, 21087, 23073, -1, 23054, 21088, 21087, -1, 23072, 23054, 23073, -1, 23070, 23073, 23074, -1, 23070, 23072, 23073, -1, 23069, 23074, 23075, -1, 23069, 23075, 23076, -1, 23069, 23070, 23074, -1, 23066, 23076, 23077, -1, 23066, 23069, 23076, -1, 23064, 23077, 23078, -1, 23064, 23066, 23077, -1, 20891, 23078, 17655, -1, 20891, 23064, 23078, -1, 17658, 17656, 23079, -1, 23080, 23079, 23081, -1, 23080, 17658, 23079, -1, 23082, 23081, 20635, -1, 23082, 23080, 23081, -1, 20634, 23082, 20635, -1, 20943, 23083, 20945, -1, 20943, 23084, 23083, -1, 20943, 20955, 23084, -1, 17657, 20938, 17654, -1, 17658, 20938, 17657, -1, 23080, 20938, 17658, -1, 20634, 22147, 23082, -1, 23085, 20943, 20942, -1, 23086, 20943, 23085, -1, 22151, 20955, 20943, -1, 22151, 20943, 23086, -1, 23087, 20942, 20939, -1, 23087, 23085, 20942, -1, 23088, 22149, 22151, -1, 23088, 23085, 23087, -1, 23088, 23086, 23085, -1, 23088, 23087, 22149, -1, 23088, 22151, 23086, -1, 23089, 20939, 20938, -1, 23089, 23087, 20939, -1, 23089, 22149, 23087, -1, 23089, 20938, 23080, -1, 23090, 23080, 23082, -1, 23090, 22147, 22149, -1, 23090, 22149, 23089, -1, 23090, 23082, 22147, -1, 23090, 23089, 23080, -1, 20955, 20954, 23091, -1, 23084, 23091, 23092, -1, 23084, 20955, 23091, -1, 23083, 23084, 23092, -1, 20945, 23092, 20946, -1, 20945, 23083, 23092, -1, 23093, 23092, 23091, -1, 23093, 23091, 20954, -1, 23093, 20954, 20956, -1, 23094, 20946, 23092, -1, 23094, 23092, 23093, -1, 21216, 20946, 23094, -1, 21223, 21220, 21219, -1, 21223, 21113, 21220, -1, 21225, 21223, 21219, -1, 23094, 21219, 21216, -1, 23094, 21225, 21219, -1, 23093, 21225, 23094, -1, 20956, 21225, 23093, -1, 21118, 21120, 23095, -1, 21120, 23096, 23095, -1, 23095, 23097, 23098, -1, 23096, 23097, 23095, -1, 23098, 20571, 20570, -1, 23097, 20571, 23098, -1, 23099, 21121, 21116, -1, 23099, 23100, 21121, -1, 20628, 22589, 23101, -1, 21121, 23096, 21122, -1, 21122, 23096, 21120, -1, 23100, 23096, 21121, -1, 22589, 22590, 23101, -1, 23101, 22591, 23100, -1, 22590, 22591, 23101, -1, 22591, 23097, 23100, -1, 23100, 23097, 23096, -1, 22591, 22592, 23097, -1, 22592, 22593, 23097, -1, 22593, 20571, 23097, -1, 21115, 23102, 21116, -1, 21116, 23102, 23099, -1, 23099, 23103, 23100, -1, 23102, 23103, 23099, -1, 23100, 23104, 23101, -1, 23103, 23104, 23100, -1, 23101, 20629, 20628, -1, 23104, 20629, 23101, -1, 20629, 23104, 22090, -1, 23102, 21115, 23105, -1, 22099, 23106, 22101, -1, 20326, 23107, 23108, -1, 22101, 23107, 20326, -1, 23106, 23107, 22101, -1, 22099, 23107, 23106, -1, 23108, 23109, 23110, -1, 23110, 23109, 23107, -1, 23107, 23109, 23108, -1, 22095, 23111, 22097, -1, 22097, 23111, 22099, -1, 22099, 23111, 23107, -1, 23110, 23112, 23113, -1, 23113, 23112, 23114, -1, 23107, 23112, 23110, -1, 23111, 23112, 23107, -1, 22093, 23115, 22095, -1, 22095, 23115, 23111, -1, 23115, 23116, 23111, -1, 22093, 23116, 23115, -1, 23111, 23116, 23112, -1, 23114, 23117, 23118, -1, 23118, 23117, 23116, -1, 23116, 23117, 23112, -1, 23112, 23117, 23114, -1, 23103, 23119, 23104, -1, 22090, 23119, 22093, -1, 22093, 23119, 23116, -1, 23104, 23119, 22090, -1, 23118, 23120, 23105, -1, 23102, 23120, 23103, -1, 23116, 23120, 23118, -1, 23103, 23120, 23119, -1, 23105, 23120, 23102, -1, 23119, 23120, 23116, -1, 21115, 21117, 23105, -1, 21117, 23121, 23105, -1, 23105, 23122, 23118, -1, 23121, 23122, 23105, -1, 23118, 23123, 23114, -1, 23122, 23123, 23118, -1, 23114, 23124, 23113, -1, 23123, 23124, 23114, -1, 23113, 23125, 23110, -1, 23124, 23125, 23113, -1, 23110, 23126, 23108, -1, 23125, 23126, 23110, -1, 23108, 20333, 20326, -1, 23126, 20333, 23108, -1, 23127, 23128, 23129, -1, 23122, 23130, 23123, -1, 23129, 23130, 23131, -1, 23132, 23130, 23122, -1, 23131, 23130, 23132, -1, 23133, 23134, 23135, -1, 20324, 23134, 23133, -1, 23135, 23134, 23136, -1, 23136, 23137, 23138, -1, 23138, 23137, 23128, -1, 23123, 23139, 23124, -1, 23130, 23139, 23123, -1, 23129, 23139, 23130, -1, 23128, 23139, 23129, -1, 20331, 23140, 20324, -1, 20324, 23140, 23134, -1, 23134, 23140, 23136, -1, 23136, 23140, 23137, -1, 23124, 23141, 23125, -1, 23139, 23141, 23124, -1, 23137, 23141, 23128, -1, 23128, 23141, 23139, -1, 20332, 23142, 20331, -1, 23125, 23142, 23126, -1, 20331, 23142, 23140, -1, 23126, 23142, 20332, -1, 23141, 23142, 23125, -1, 23140, 23142, 23137, -1, 23137, 23142, 23141, -1, 20316, 20324, 23133, -1, 20332, 20333, 23126, -1, 23143, 23144, 21181, -1, 21181, 23144, 21236, -1, 23145, 23146, 23143, -1, 23143, 23146, 23144, -1, 21236, 23147, 21235, -1, 23144, 23147, 21236, -1, 23148, 23127, 23145, -1, 23145, 23127, 23146, -1, 23146, 23131, 23144, -1, 23144, 23131, 23147, -1, 21235, 23149, 21233, -1, 21233, 23149, 21117, -1, 21117, 23149, 23121, -1, 23147, 23149, 21235, -1, 23150, 23138, 23148, -1, 23148, 23138, 23127, -1, 23127, 23129, 23146, -1, 23146, 23129, 23131, -1, 23121, 23132, 23122, -1, 23149, 23132, 23121, -1, 23131, 23132, 23147, -1, 23147, 23132, 23149, -1, 23135, 23136, 23150, -1, 23150, 23136, 23138, -1, 23138, 23128, 23127, -1, 21180, 23151, 21181, -1, 21181, 23151, 23143, -1, 23143, 23152, 23145, -1, 23151, 23152, 23143, -1, 23145, 23153, 23148, -1, 23152, 23153, 23145, -1, 23148, 23154, 23150, -1, 23153, 23154, 23148, -1, 23150, 23155, 23135, -1, 23154, 23155, 23150, -1, 23135, 23156, 23133, -1, 23155, 23156, 23135, -1, 23133, 20288, 20316, -1, 23156, 20288, 23133, -1, 23157, 23158, 23159, -1, 23159, 23160, 23161, -1, 23162, 23163, 23164, -1, 23161, 23160, 23165, -1, 23153, 23166, 23154, -1, 23167, 23166, 23168, -1, 23168, 23166, 23153, -1, 23169, 21185, 21183, -1, 23164, 23166, 23167, -1, 23170, 23171, 23172, -1, 20338, 23173, 20336, -1, 20336, 23173, 23174, -1, 23165, 23171, 23170, -1, 23175, 23173, 23163, -1, 23174, 23173, 23175, -1, 21189, 23176, 21191, -1, 23154, 23177, 23155, -1, 23166, 23177, 23154, -1, 23172, 23176, 21189, -1, 23163, 23177, 23164, -1, 23164, 23177, 23166, -1, 20289, 23178, 20338, -1, 23155, 23178, 23156, -1, 23179, 23180, 23181, -1, 20338, 23178, 23173, -1, 23181, 23180, 23158, -1, 23173, 23178, 23163, -1, 23163, 23178, 23177, -1, 23177, 23178, 23155, -1, 23156, 23178, 20289, -1, 23159, 23182, 23160, -1, 23158, 23182, 23159, -1, 23165, 23183, 23171, -1, 23160, 23183, 23165, -1, 23171, 23184, 23172, -1, 23172, 23184, 23176, -1, 20328, 23185, 20312, -1, 20312, 23185, 23186, -1, 23186, 23185, 23179, -1, 23179, 23185, 23180, -1, 21191, 23187, 21193, -1, 23176, 23187, 21191, -1, 23180, 23188, 23158, -1, 23158, 23188, 23182, -1, 23182, 23189, 23160, -1, 23160, 23189, 23183, -1, 23183, 23190, 23171, -1, 23171, 23190, 23184, -1, 23176, 23191, 23187, -1, 23184, 23191, 23176, -1, 20330, 23192, 20328, -1, 23180, 23192, 23188, -1, 20328, 23192, 23185, -1, 23185, 23192, 23180, -1, 21193, 23193, 21195, -1, 21195, 23193, 21180, -1, 21180, 23193, 23151, -1, 23187, 23193, 21193, -1, 23188, 23194, 23182, -1, 23182, 23194, 23189, -1, 20289, 20288, 23156, -1, 23189, 23162, 23183, -1, 23183, 23162, 23190, -1, 23169, 23195, 21185, -1, 23190, 23167, 23184, -1, 23196, 23161, 23169, -1, 23184, 23167, 23191, -1, 23193, 23197, 23151, -1, 23169, 23161, 23195, -1, 23187, 23197, 23193, -1, 23151, 23197, 23152, -1, 21185, 23170, 21187, -1, 23191, 23197, 23187, -1, 20334, 23198, 20330, -1, 23195, 23170, 21185, -1, 23192, 23198, 23188, -1, 20330, 23198, 23192, -1, 23188, 23198, 23194, -1, 23189, 23175, 23162, -1, 23157, 23159, 23196, -1, 23194, 23175, 23189, -1, 23196, 23159, 23161, -1, 23195, 23165, 23170, -1, 23162, 23164, 23190, -1, 23190, 23164, 23167, -1, 23161, 23165, 23195, -1, 21187, 23172, 21189, -1, 23167, 23168, 23191, -1, 23152, 23168, 23153, -1, 23197, 23168, 23152, -1, 23170, 23172, 21187, -1, 23191, 23168, 23197, -1, 20336, 23174, 20334, -1, 20334, 23174, 23198, -1, 23198, 23174, 23194, -1, 23194, 23174, 23175, -1, 23181, 23158, 23157, -1, 23175, 23163, 23162, -1, 21196, 23199, 21183, -1, 21183, 23199, 23169, -1, 23169, 23200, 23196, -1, 23199, 23200, 23169, -1, 23196, 23201, 23157, -1, 23200, 23201, 23196, -1, 23157, 23202, 23181, -1, 23201, 23202, 23157, -1, 23181, 23203, 23179, -1, 23202, 23203, 23181, -1, 23186, 23204, 20312, -1, 23179, 23204, 23186, -1, 23203, 23204, 23179, -1, 23204, 20299, 20312, -1, 20295, 23205, 20322, -1, 20322, 23205, 20649, -1, 20649, 23206, 20646, -1, 23205, 23206, 20649, -1, 20646, 23207, 20641, -1, 23206, 23207, 20646, -1, 20641, 23208, 20644, -1, 23207, 23208, 20641, -1, 20644, 23209, 20647, -1, 23208, 23209, 20644, -1, 20647, 23210, 20651, -1, 23209, 23210, 20647, -1, 20651, 20495, 20494, -1, 23210, 20495, 20651, -1, 23211, 23212, 23213, -1, 21792, 23214, 21790, -1, 21790, 23214, 21196, -1, 21196, 23214, 23199, -1, 23213, 23214, 21792, -1, 23215, 23216, 23217, -1, 23217, 23216, 23218, -1, 23218, 23219, 23220, -1, 23220, 23219, 23221, -1, 23221, 23222, 23223, -1, 23223, 23222, 23212, -1, 23199, 23224, 23200, -1, 23214, 23224, 23199, -1, 23213, 23224, 23214, -1, 23212, 23224, 23213, -1, 23225, 23226, 23215, -1, 20290, 23226, 23225, -1, 23215, 23226, 23216, -1, 23218, 23227, 23219, -1, 23216, 23227, 23218, -1, 23221, 23228, 23222, -1, 23219, 23228, 23221, -1, 23200, 23229, 23201, -1, 23224, 23229, 23200, -1, 23222, 23229, 23212, -1, 23212, 23229, 23224, -1, 20292, 23230, 20290, -1, 20290, 23230, 23226, -1, 23226, 23230, 23216, -1, 20293, 20290, 23225, -1, 23216, 23230, 23227, -1, 23227, 23231, 23219, -1, 23219, 23231, 23228, -1, 23201, 23232, 23202, -1, 23229, 23232, 23201, -1, 23228, 23232, 23222, -1, 23222, 23232, 23229, -1, 20291, 23233, 20292, -1, 23227, 23233, 23231, -1, 20292, 23233, 23230, -1, 23230, 23233, 23227, -1, 23231, 23234, 23228, -1, 23202, 23234, 23203, -1, 23228, 23234, 23232, -1, 23232, 23234, 23202, -1, 20299, 23235, 20298, -1, 20298, 23235, 20291, -1, 23233, 23235, 23231, -1, 23204, 23235, 20299, -1, 23203, 23235, 23204, -1, 23231, 23235, 23234, -1, 20291, 23235, 23233, -1, 23234, 23235, 23203, -1, 23236, 23237, 21178, -1, 21178, 23237, 21797, -1, 23238, 23239, 23236, -1, 23236, 23239, 23237, -1, 21797, 23211, 21795, -1, 23237, 23211, 21797, -1, 23240, 23220, 23238, -1, 23238, 23220, 23239, -1, 23237, 23223, 23211, -1, 23239, 23223, 23237, -1, 21795, 23213, 21792, -1, 23211, 23213, 21795, -1, 23217, 23218, 23240, -1, 23240, 23218, 23220, -1, 23220, 23221, 23239, -1, 23239, 23221, 23223, -1, 23223, 23212, 23211, -1, 23236, 23210, 23238, -1, 21178, 23210, 23236, -1, 20495, 23210, 21178, -1, 23238, 23209, 23240, -1, 23210, 23209, 23238, -1, 23240, 23208, 23217, -1, 23209, 23208, 23240, -1, 23217, 23207, 23215, -1, 23208, 23207, 23217, -1, 23215, 23206, 23225, -1, 23207, 23206, 23215, -1, 23225, 23205, 20293, -1, 23206, 23205, 23225, -1, 23205, 20295, 20293, -1, 21162, 21159, 23241, -1, 22889, 23241, 23242, -1, 22889, 21162, 23241, -1, 22890, 23242, 23243, -1, 22890, 22889, 23242, -1, 22891, 23243, 23244, -1, 22891, 22890, 23243, -1, 22892, 23244, 23245, -1, 22892, 22891, 23244, -1, 22896, 22892, 23245, -1, 22895, 23245, 23246, -1, 22895, 22896, 23245, -1, 22894, 22895, 23246, -1, 22893, 23246, 20588, -1, 22893, 22894, 23246, -1, 20587, 22893, 20588, -1, 23247, 23248, 23249, -1, 23250, 23251, 23247, -1, 23250, 23252, 23251, -1, 23253, 21776, 21775, -1, 21781, 23254, 21102, -1, 23253, 23255, 21776, -1, 23256, 23252, 23250, -1, 23256, 23257, 23252, -1, 23258, 23249, 23255, -1, 23258, 23255, 23253, -1, 23259, 23260, 23257, -1, 23259, 21148, 23260, -1, 23259, 23257, 23256, -1, 23261, 23249, 23258, -1, 23261, 23247, 23249, -1, 23262, 21775, 21772, -1, 23262, 23253, 21775, -1, 23263, 23247, 23261, -1, 21147, 21146, 23264, -1, 23263, 23250, 23247, -1, 23265, 23258, 23253, -1, 23265, 23253, 23262, -1, 23266, 23250, 23263, -1, 23266, 23256, 23250, -1, 23267, 23258, 23265, -1, 23267, 23261, 23258, -1, 23268, 23256, 23266, -1, 23268, 21149, 21148, -1, 23268, 21150, 21149, -1, 23268, 21148, 23259, -1, 23268, 23259, 23256, -1, 23246, 21770, 20588, -1, 23269, 21772, 21770, -1, 23269, 23262, 21772, -1, 23245, 21770, 23246, -1, 23270, 23261, 23267, -1, 23270, 23263, 23261, -1, 23271, 23265, 23262, -1, 23271, 23269, 21770, -1, 23271, 21770, 23245, -1, 23271, 23262, 23269, -1, 23272, 23263, 23270, -1, 23272, 23266, 23263, -1, 23273, 23267, 23265, -1, 23241, 21157, 23242, -1, 23273, 23245, 23244, -1, 23273, 23244, 23243, -1, 21159, 21157, 23241, -1, 23274, 23275, 23254, -1, 23273, 23271, 23245, -1, 23273, 23265, 23271, -1, 23274, 21781, 21778, -1, 23274, 23254, 21781, -1, 23276, 23266, 23272, -1, 23276, 21150, 23268, -1, 23276, 23268, 23266, -1, 23248, 23277, 23275, -1, 23276, 21156, 21150, -1, 23278, 23243, 23242, -1, 23278, 23270, 23267, -1, 23278, 23273, 23243, -1, 23248, 23274, 21778, -1, 23248, 23275, 23274, -1, 23278, 23267, 23273, -1, 23251, 23279, 23277, -1, 23280, 23272, 23270, -1, 23251, 23277, 23248, -1, 23280, 23270, 23278, -1, 23280, 23278, 23242, -1, 23280, 23242, 21157, -1, 23281, 23276, 23272, -1, 23281, 21157, 21156, -1, 23281, 21156, 23276, -1, 23252, 23279, 23251, -1, 23281, 23272, 23280, -1, 23281, 23280, 21157, -1, 23255, 21778, 21776, -1, 23257, 23282, 23279, -1, 23257, 23279, 23252, -1, 23249, 23248, 21778, -1, 23249, 21778, 23255, -1, 23260, 21148, 21147, -1, 23260, 23264, 23282, -1, 23260, 21147, 23264, -1, 23260, 23282, 23257, -1, 23247, 23251, 23248, -1, 21103, 21102, 23254, -1, 23283, 23254, 23275, -1, 23283, 21103, 23254, -1, 23284, 23275, 23277, -1, 23284, 23283, 23275, -1, 23285, 23277, 23279, -1, 23285, 23284, 23277, -1, 23286, 23279, 23282, -1, 23286, 23285, 23279, -1, 23287, 23282, 23264, -1, 23287, 23286, 23282, -1, 23288, 23264, 21146, -1, 23288, 23287, 23264, -1, 21145, 23288, 21146, -1, 23289, 23290, 23291, -1, 23289, 23292, 23293, -1, 23289, 23291, 23292, -1, 23294, 23283, 23284, -1, 23294, 23284, 23295, -1, 23294, 21768, 23283, -1, 23296, 23297, 23298, -1, 23296, 23295, 23297, -1, 23299, 23293, 23300, -1, 23299, 23290, 23289, -1, 23299, 23289, 23293, -1, 23299, 23298, 23290, -1, 23301, 21766, 21768, -1, 23301, 21768, 23294, -1, 23301, 23294, 23295, -1, 23301, 23295, 23296, -1, 23302, 23300, 23303, -1, 23302, 23299, 23300, -1, 23302, 23296, 23298, -1, 23302, 23298, 23299, -1, 23304, 23305, 21109, -1, 23304, 23303, 23305, -1, 23304, 21764, 21766, -1, 23304, 21109, 21764, -1, 23304, 21766, 23301, -1, 23304, 23302, 23303, -1, 23304, 23301, 23296, -1, 23304, 23296, 23302, -1, 23306, 21152, 21127, -1, 21768, 21103, 23283, -1, 23307, 23288, 21145, -1, 23307, 21145, 21144, -1, 23308, 23287, 23288, -1, 23308, 23288, 23307, -1, 23309, 21144, 21153, -1, 23309, 23307, 21144, -1, 23310, 23286, 23287, -1, 23310, 23287, 23308, -1, 23291, 23307, 23309, -1, 23291, 23308, 23307, -1, 23311, 21153, 21152, -1, 23311, 23306, 23312, -1, 23311, 21152, 23306, -1, 23311, 23309, 21153, -1, 23297, 23285, 23286, -1, 23297, 23286, 23310, -1, 23290, 23310, 23308, -1, 23290, 23308, 23291, -1, 23292, 23312, 23293, -1, 23292, 23311, 23312, -1, 23292, 23291, 23309, -1, 23292, 23309, 23311, -1, 23295, 23284, 23285, -1, 23295, 23285, 23297, -1, 23298, 23297, 23310, -1, 23298, 23310, 23290, -1, 23313, 21109, 23305, -1, 23313, 21107, 21109, -1, 23314, 23305, 23303, -1, 23314, 23313, 23305, -1, 23315, 23303, 23300, -1, 23315, 23314, 23303, -1, 23316, 23300, 23293, -1, 23316, 23315, 23300, -1, 23317, 23293, 23312, -1, 23317, 23316, 23293, -1, 23318, 23312, 23306, -1, 23318, 23317, 23312, -1, 21129, 23306, 21127, -1, 21129, 23318, 23306, -1, 23319, 21786, 21788, -1, 23319, 23320, 21786, -1, 23321, 23322, 23323, -1, 23321, 23323, 23324, -1, 21782, 23325, 21100, -1, 23326, 23327, 23328, -1, 23326, 23324, 23327, -1, 23329, 23328, 23330, -1, 23329, 23330, 23331, -1, 23332, 23313, 23314, -1, 23332, 23331, 23320, -1, 23332, 23319, 23313, -1, 23332, 23320, 23319, -1, 23333, 21164, 21160, -1, 23333, 21160, 23322, -1, 23333, 23322, 23321, -1, 23334, 23321, 23324, -1, 23334, 23324, 23326, -1, 23335, 23326, 23328, -1, 23335, 23328, 23329, -1, 23336, 23314, 23315, -1, 23336, 23329, 23331, -1, 23336, 23332, 23314, -1, 23336, 23331, 23332, -1, 23337, 21165, 21164, -1, 23337, 21164, 23333, -1, 23337, 23321, 23334, -1, 23337, 23333, 23321, -1, 23338, 23334, 23326, -1, 23338, 23326, 23335, -1, 23339, 23315, 23316, -1, 23339, 23336, 23315, -1, 23339, 23329, 23336, -1, 23339, 23335, 23329, -1, 23340, 23337, 23334, -1, 23340, 21167, 21165, -1, 23340, 23334, 23338, -1, 23340, 21165, 23337, -1, 23341, 23338, 23335, -1, 23341, 23316, 23317, -1, 23341, 23335, 23339, -1, 23341, 23339, 23316, -1, 23342, 23341, 23317, -1, 23342, 23317, 23318, -1, 23342, 23340, 23338, -1, 23342, 21168, 21167, -1, 23342, 23318, 21168, -1, 23342, 23338, 23341, -1, 23342, 21167, 23340, -1, 21129, 21168, 23318, -1, 23343, 23344, 23325, -1, 23343, 23325, 21782, -1, 23345, 23346, 23344, -1, 23345, 23344, 23343, -1, 23347, 21782, 21785, -1, 23347, 23343, 21782, -1, 23327, 23348, 23346, -1, 23327, 23346, 23345, -1, 23330, 23343, 23347, -1, 23330, 23345, 23343, -1, 23320, 21785, 21786, -1, 23320, 23347, 21785, -1, 23324, 23323, 23348, -1, 23324, 23348, 23327, -1, 23328, 23345, 23330, -1, 23328, 23327, 23345, -1, 23331, 23330, 23347, -1, 23331, 23347, 23320, -1, 23319, 21107, 23313, -1, 23319, 21788, 21107, -1, 23322, 21160, 21141, -1, 23322, 21141, 23349, -1, 23323, 23349, 23350, -1, 23323, 23322, 23349, -1, 23348, 23350, 23351, -1, 23348, 23323, 23350, -1, 23346, 23351, 23352, -1, 23346, 23348, 23351, -1, 23344, 23352, 23353, -1, 23344, 23346, 23352, -1, 23325, 23353, 23354, -1, 23325, 23344, 23353, -1, 21100, 23354, 21101, -1, 21100, 23325, 23354, -1, 23355, 23356, 23357, -1, 23355, 23357, 23358, -1, 23359, 23360, 23361, -1, 23359, 23361, 23362, -1, 23363, 23352, 23351, -1, 23363, 23364, 23352, -1, 23363, 23358, 23365, -1, 23363, 23365, 23364, -1, 23366, 23367, 23368, -1, 23369, 21133, 21132, -1, 23366, 23362, 23367, -1, 23369, 21132, 23370, -1, 23369, 23370, 23356, -1, 23369, 23356, 23355, -1, 23371, 23351, 23350, -1, 23372, 21205, 21203, -1, 23371, 23363, 23351, -1, 23371, 23355, 23358, -1, 23371, 23358, 23363, -1, 23372, 23368, 21205, -1, 23373, 23350, 23349, -1, 23374, 23375, 23376, -1, 23373, 21137, 21133, -1, 23373, 23369, 23355, -1, 23374, 23376, 23377, -1, 23373, 23355, 23371, -1, 23373, 23371, 23350, -1, 23373, 23349, 21137, -1, 23373, 21133, 23369, -1, 23378, 23377, 23360, -1, 23378, 23360, 23359, -1, 23379, 23362, 23366, -1, 23379, 23359, 23362, -1, 23380, 23368, 23372, -1, 23380, 23366, 23368, -1, 23381, 21139, 21143, -1, 23381, 23382, 23375, -1, 23381, 21143, 23382, -1, 23381, 23375, 23374, -1, 23383, 21203, 21201, -1, 23383, 23372, 21203, -1, 23384, 23374, 23377, -1, 23384, 23377, 23378, -1, 23385, 23378, 23359, -1, 23385, 23359, 23379, -1, 23386, 23379, 23366, -1, 23386, 23366, 23380, -1, 23387, 23380, 23372, -1, 23387, 23372, 23383, -1, 23388, 21135, 21139, -1, 23388, 21139, 23381, -1, 23388, 23374, 23384, -1, 23388, 23381, 23374, -1, 23389, 21101, 23354, -1, 23389, 21199, 21101, -1, 23389, 21201, 21199, -1, 23389, 23383, 21201, -1, 23390, 23384, 23378, -1, 23390, 23378, 23385, -1, 21141, 21137, 23349, -1, 23391, 23392, 21096, -1, 23357, 23385, 23379, -1, 23357, 23379, 23386, -1, 23391, 21096, 21209, -1, 23361, 23393, 23392, -1, 23365, 23380, 23387, -1, 23365, 23386, 23380, -1, 23361, 23392, 23391, -1, 23394, 23354, 23353, -1, 23394, 23387, 23383, -1, 23394, 23383, 23389, -1, 23394, 23389, 23354, -1, 23367, 21209, 21207, -1, 23395, 23388, 23384, -1, 23395, 21131, 21135, -1, 23367, 23391, 21209, -1, 23395, 23384, 23390, -1, 23395, 21135, 23388, -1, 23360, 23396, 23393, -1, 23356, 23385, 23357, -1, 23356, 23390, 23385, -1, 23360, 23393, 23361, -1, 23362, 23391, 23367, -1, 23358, 23386, 23365, -1, 23362, 23361, 23391, -1, 23358, 23357, 23386, -1, 23364, 23365, 23387, -1, 23364, 23353, 23352, -1, 23368, 21207, 21205, -1, 23364, 23387, 23394, -1, 23368, 23367, 21207, -1, 23364, 23394, 23353, -1, 23370, 21132, 21131, -1, 23370, 23395, 23390, -1, 23377, 23376, 23396, -1, 23370, 23390, 23356, -1, 23370, 21131, 23395, -1, 23377, 23396, 23360, -1, 23382, 21143, 21170, -1, 23382, 21170, 23397, -1, 23375, 23397, 23398, -1, 23375, 23382, 23397, -1, 23376, 23398, 23399, -1, 23376, 23375, 23398, -1, 23396, 23399, 23400, -1, 23396, 23376, 23399, -1, 23393, 23400, 23401, -1, 23393, 23396, 23400, -1, 23392, 23401, 23402, -1, 23392, 23393, 23401, -1, 21096, 23402, 21095, -1, 21096, 23392, 23402, -1, 23403, 23404, 23405, -1, 23406, 23401, 23400, -1, 23406, 23407, 23401, -1, 23406, 23408, 23407, -1, 23406, 23409, 23408, -1, 23410, 21175, 21176, -1, 23410, 23411, 23412, -1, 23410, 21176, 23411, -1, 23410, 23412, 23413, -1, 23414, 23413, 23404, -1, 23414, 23404, 23403, -1, 23415, 23400, 23399, -1, 23415, 23406, 23400, -1, 23415, 23403, 23409, -1, 23415, 23409, 23406, -1, 23416, 21173, 21175, -1, 23416, 23413, 23414, -1, 23416, 21175, 23410, -1, 23416, 23410, 23413, -1, 23417, 23399, 23398, -1, 23417, 23415, 23399, -1, 23417, 23414, 23403, -1, 23417, 23403, 23415, -1, 23418, 23398, 23397, -1, 23418, 23397, 21170, -1, 23418, 21170, 21173, -1, 23418, 21173, 23416, -1, 23418, 23417, 23398, -1, 23402, 21227, 21095, -1, 23418, 23416, 23414, -1, 23418, 23414, 23417, -1, 21176, 21124, 23411, -1, 23419, 23420, 21090, -1, 23419, 21090, 21231, -1, 23421, 23422, 23420, -1, 23421, 23420, 23419, -1, 23423, 21231, 21229, -1, 23423, 23419, 21231, -1, 23405, 23424, 23422, -1, 23405, 23422, 23421, -1, 23408, 23419, 23423, -1, 23408, 23421, 23419, -1, 23425, 21229, 21227, -1, 23425, 23423, 21229, -1, 23425, 21227, 23402, -1, 23404, 23426, 23424, -1, 23404, 23424, 23405, -1, 23409, 23421, 23408, -1, 23409, 23405, 23421, -1, 23407, 23402, 23401, -1, 23407, 23423, 23425, -1, 23407, 23408, 23423, -1, 23407, 23425, 23402, -1, 23413, 23412, 23426, -1, 23413, 23426, 23404, -1, 23403, 23405, 23409, -1, 20077, 21124, 20092, -1, 23411, 21124, 20077, -1, 23412, 20077, 20079, -1, 23412, 23411, 20077, -1, 23426, 20079, 20083, -1, 23426, 23412, 20079, -1, 20085, 23426, 20083, -1, 23424, 20085, 20086, -1, 23424, 20086, 20056, -1, 23424, 23426, 20085, -1, 23422, 20056, 20058, -1, 23422, 20058, 20116, -1, 23422, 20116, 20118, -1, 23422, 20118, 20119, -1, 23422, 23424, 20056, -1, 23420, 20119, 20120, -1, 23420, 20120, 20142, -1, 23420, 20142, 20107, -1, 23420, 23422, 20119, -1, 21090, 20107, 20109, -1, 21090, 23420, 20107, -1, 19856, 20347, 19860, -1, 19860, 22899, 19864, -1, 20347, 22899, 19860, -1, 19864, 22898, 19865, -1, 22899, 22898, 19864, -1, 19865, 23427, 19872, -1, 22898, 23427, 19865, -1, 19872, 17647, 19873, -1, 23427, 17647, 19872, -1, 19873, 17648, 23428, -1, 17647, 17648, 19873, -1, 23428, 17650, 23429, -1, 17648, 17650, 23428, -1, 23429, 17651, 19101, -1, 17650, 17651, 23429, -1, 20604, 20603, 22898, -1, 22898, 20603, 23427, -1, 20603, 20602, 23427, -1, 23427, 17645, 17647, -1, 20602, 17645, 23427, -1, 23430, 22168, 21026, -1, 22170, 19315, 19158, -1, 22170, 19318, 19315, -1, 20417, 20439, 23431, -1, 22170, 19321, 19318, -1, 20438, 19329, 19326, -1, 20438, 19331, 19329, -1, 20438, 19333, 19331, -1, 22168, 23432, 22170, -1, 23430, 23432, 22168, -1, 23433, 23434, 23430, -1, 23432, 23434, 22170, -1, 23430, 23434, 23432, -1, 23435, 23436, 23433, -1, 23434, 23436, 22170, -1, 23433, 23436, 23434, -1, 22170, 23436, 19321, -1, 23437, 23438, 23435, -1, 19321, 23438, 19324, -1, 23435, 23438, 23436, -1, 23436, 23438, 19321, -1, 23439, 23440, 23437, -1, 19324, 23440, 19326, -1, 23438, 23440, 19324, -1, 23437, 23440, 23438, -1, 23441, 23442, 23439, -1, 23439, 23442, 23440, -1, 23440, 23442, 19326, -1, 19326, 23442, 20438, -1, 23443, 23444, 23441, -1, 23442, 23444, 20438, -1, 23441, 23444, 23442, -1, 20438, 23445, 20439, -1, 23431, 23445, 23443, -1, 23444, 23445, 20438, -1, 23443, 23445, 23444, -1, 20439, 23445, 23431, -1, 21028, 23446, 21026, -1, 21026, 23446, 23430, -1, 23430, 23447, 23433, -1, 23446, 23447, 23430, -1, 23433, 23448, 23435, -1, 23447, 23448, 23433, -1, 23435, 23449, 23437, -1, 23448, 23449, 23435, -1, 23437, 23450, 23439, -1, 23449, 23450, 23437, -1, 23439, 23451, 23441, -1, 23450, 23451, 23439, -1, 23441, 23452, 23443, -1, 23451, 23452, 23441, -1, 23443, 23453, 23431, -1, 23452, 23453, 23443, -1, 23431, 20421, 20417, -1, 23453, 20421, 23431, -1, 23454, 23455, 23456, -1, 23456, 23455, 23457, -1, 23458, 23459, 23460, -1, 23457, 23459, 23458, -1, 23448, 23461, 23449, -1, 23449, 23461, 23462, -1, 23462, 23463, 23454, -1, 23454, 23463, 23455, -1, 20511, 23464, 20517, -1, 23460, 23464, 20511, -1, 20517, 23464, 23465, -1, 23455, 23466, 23457, -1, 23457, 23466, 23459, -1, 23447, 23467, 23448, -1, 23448, 23467, 23461, -1, 23465, 23468, 23469, -1, 23464, 23468, 23465, -1, 23459, 23468, 23460, -1, 23460, 23468, 23464, -1, 23462, 23470, 23463, -1, 23461, 23470, 23462, -1, 20517, 23465, 20527, -1, 23463, 23471, 23455, -1, 23455, 23471, 23466, -1, 23469, 23472, 23473, -1, 21028, 21964, 23446, -1, 23468, 23472, 23469, -1, 23466, 23472, 23459, -1, 23459, 23472, 23468, -1, 21962, 23474, 21964, -1, 23446, 23474, 23447, -1, 23447, 23474, 23467, -1, 21964, 23474, 23446, -1, 23467, 23475, 23461, -1, 23461, 23475, 23470, -1, 23470, 23476, 23463, -1, 23463, 23476, 23471, -1, 23466, 23477, 23472, -1, 23473, 23477, 23478, -1, 23472, 23477, 23473, -1, 23471, 23477, 23466, -1, 23474, 23479, 23467, -1, 21960, 23479, 21962, -1, 23467, 23479, 23475, -1, 21962, 23479, 23474, -1, 23475, 23480, 23470, -1, 23470, 23480, 23476, -1, 20421, 23481, 20529, -1, 23476, 23482, 23471, -1, 23471, 23482, 23477, -1, 23453, 23481, 20421, -1, 23477, 23482, 23478, -1, 21957, 23483, 21960, -1, 21960, 23483, 23479, -1, 23479, 23483, 23475, -1, 23452, 23456, 23453, -1, 23475, 23483, 23480, -1, 23478, 23484, 23485, -1, 23453, 23456, 23481, -1, 23482, 23484, 23478, -1, 23476, 23484, 23482, -1, 23480, 23484, 23476, -1, 20529, 23458, 20523, -1, 20523, 23458, 20514, -1, 23485, 23486, 23487, -1, 23481, 23458, 20529, -1, 23487, 23486, 21031, -1, 21031, 23486, 21957, -1, 23484, 23486, 23485, -1, 23483, 23486, 23480, -1, 23480, 23486, 23484, -1, 23451, 23454, 23452, -1, 21957, 23486, 23483, -1, 23452, 23454, 23456, -1, 23481, 23457, 23458, -1, 23456, 23457, 23481, -1, 20514, 23460, 20511, -1, 23458, 23460, 20514, -1, 23450, 23462, 23451, -1, 23449, 23462, 23450, -1, 23451, 23462, 23454, -1, 21031, 21032, 23487, -1, 23487, 23488, 23485, -1, 21032, 23488, 23487, -1, 23485, 23489, 23478, -1, 23488, 23489, 23485, -1, 23478, 23490, 23473, -1, 23489, 23490, 23478, -1, 23473, 23491, 23469, -1, 23490, 23491, 23473, -1, 23469, 23492, 23465, -1, 23491, 23492, 23469, -1, 23492, 23493, 23465, -1, 23465, 20358, 20527, -1, 23493, 20358, 23465, -1, 23494, 23495, 23496, -1, 23497, 23498, 23499, -1, 17635, 23495, 17638, -1, 23500, 23498, 23497, -1, 23496, 23495, 23501, -1, 23501, 23495, 17635, -1, 23502, 23503, 23504, -1, 23505, 23503, 23502, -1, 23506, 23507, 23500, -1, 23500, 23507, 23498, -1, 21971, 23508, 21969, -1, 21969, 23508, 21968, -1, 21968, 23508, 23505, -1, 20567, 23509, 20344, -1, 23495, 23510, 17638, -1, 23499, 23509, 20567, -1, 23511, 23510, 23494, -1, 23494, 23510, 23495, -1, 21966, 23512, 21965, -1, 23488, 23512, 23489, -1, 23489, 23512, 23513, -1, 23504, 23514, 23511, -1, 21965, 23512, 23488, -1, 23503, 23514, 23504, -1, 21971, 23515, 23508, -1, 23498, 23516, 23499, -1, 23505, 23515, 23503, -1, 23508, 23515, 23505, -1, 23499, 23516, 23509, -1, 21976, 23517, 21974, -1, 17638, 23517, 17640, -1, 23510, 23517, 17638, -1, 23511, 23517, 23510, -1, 23514, 23517, 23511, -1, 17640, 23517, 21976, -1, 23506, 23518, 23507, -1, 21974, 23519, 21973, -1, 21973, 23519, 21971, -1, 23513, 23518, 23506, -1, 21971, 23519, 23515, -1, 23503, 23519, 23514, -1, 23517, 23519, 21974, -1, 23515, 23519, 23503, -1, 23514, 23519, 23517, -1, 23498, 23520, 23516, -1, 23507, 23520, 23498, -1, 20344, 23521, 20350, -1, 21032, 21965, 23488, -1, 23509, 23521, 20344, -1, 21967, 23522, 21966, -1, 21966, 23522, 23512, -1, 23513, 23522, 23518, -1, 23512, 23522, 23513, -1, 23516, 23523, 23509, -1, 23509, 23523, 23521, -1, 23507, 23524, 23520, -1, 23518, 23524, 23507, -1, 20350, 23525, 20363, -1, 23521, 23525, 20350, -1, 23520, 23526, 23516, -1, 23516, 23526, 23523, -1, 23523, 23527, 23521, -1, 23521, 23527, 23525, -1, 20365, 17632, 17634, -1, 20363, 23528, 20364, -1, 23525, 23528, 20363, -1, 23518, 23529, 23524, -1, 21968, 23529, 21967, -1, 21967, 23529, 23522, -1, 23522, 23529, 23518, -1, 23520, 23502, 23526, -1, 23524, 23502, 23520, -1, 23526, 23530, 23523, -1, 23523, 23530, 23527, -1, 23527, 23496, 23525, -1, 21976, 17642, 17640, -1, 23493, 23497, 20358, -1, 23525, 23496, 23528, -1, 23528, 23531, 20364, -1, 20358, 23497, 20569, -1, 20364, 23531, 20365, -1, 20365, 23531, 17632, -1, 23502, 23504, 23526, -1, 23492, 23500, 23493, -1, 23491, 23500, 23492, -1, 23526, 23504, 23530, -1, 23493, 23500, 23497, -1, 23530, 23494, 23527, -1, 23490, 23506, 23491, -1, 23527, 23494, 23496, -1, 23491, 23506, 23500, -1, 23524, 23505, 23502, -1, 20569, 23499, 20567, -1, 21968, 23505, 23529, -1, 23529, 23505, 23524, -1, 23496, 23501, 23528, -1, 23528, 23501, 23531, -1, 23497, 23499, 20569, -1, 17632, 23501, 17635, -1, 23531, 23501, 17632, -1, 23489, 23513, 23490, -1, 23490, 23513, 23506, -1, 23504, 23511, 23530, -1, 23530, 23511, 23494, -1, 17633, 17636, 20487, -1, 20487, 17636, 23532, -1, 23532, 17637, 23533, -1, 17636, 17637, 23532, -1, 23533, 17639, 23534, -1, 17637, 17639, 23533, -1, 23534, 17641, 23535, -1, 17639, 17641, 23534, -1, 23535, 17644, 21024, -1, 17641, 17644, 23535, -1, 21024, 22172, 23535, -1, 20509, 23536, 20505, -1, 20509, 23537, 23536, -1, 22174, 23537, 20509, -1, 22174, 23538, 23537, -1, 22174, 23539, 23538, -1, 22174, 19159, 23539, -1, 20487, 23540, 20500, -1, 20500, 23540, 20509, -1, 23532, 23540, 20487, -1, 23533, 23541, 23532, -1, 23540, 23541, 20509, -1, 23532, 23541, 23540, -1, 23534, 23542, 23533, -1, 23541, 23542, 20509, -1, 23533, 23542, 23541, -1, 20509, 23542, 22174, -1, 22174, 23543, 22172, -1, 23535, 23543, 23534, -1, 23542, 23543, 22174, -1, 23534, 23543, 23542, -1, 22172, 23543, 23535, -1, 19673, 20505, 19677, -1, 19682, 23536, 19685, -1, 19677, 23536, 19682, -1, 20505, 23536, 19677, -1, 19679, 23537, 19680, -1, 19685, 23537, 19679, -1, 23536, 23537, 19685, -1, 19680, 23538, 23544, -1, 23537, 23538, 19680, -1, 23544, 23539, 23545, -1, 23538, 23539, 23544, -1, 23545, 19159, 19161, -1, 23539, 19159, 23545, -1, 19160, 22175, 19341, -1, 18966, 17628, 17630, -1, 18966, 17627, 17628, -1, 22173, 23546, 23547, -1, 22173, 21025, 23546, -1, 18761, 23548, 18965, -1, 18965, 23548, 18966, -1, 18759, 23548, 18761, -1, 18757, 23549, 18759, -1, 23548, 23549, 18966, -1, 18759, 23549, 23548, -1, 18755, 23550, 18757, -1, 18757, 23550, 23549, -1, 18753, 23551, 18755, -1, 18755, 23551, 23550, -1, 18751, 23552, 18753, -1, 18753, 23552, 23551, -1, 19344, 23553, 18751, -1, 18751, 23553, 23552, -1, 22173, 23554, 22175, -1, 19341, 23554, 19344, -1, 19344, 23554, 23553, -1, 22175, 23554, 19341, -1, 23553, 23554, 22173, -1, 17627, 23555, 17625, -1, 17625, 23555, 17623, -1, 17623, 23555, 17622, -1, 17622, 23555, 23547, -1, 23549, 23555, 18966, -1, 23550, 23555, 23549, -1, 23553, 23555, 23552, -1, 23551, 23555, 23550, -1, 22173, 23555, 23553, -1, 23552, 23555, 23551, -1, 18966, 23555, 17627, -1, 23547, 23555, 22173, -1, 21023, 23556, 21025, -1, 21025, 23556, 23546, -1, 23546, 23557, 23547, -1, 23556, 23557, 23546, -1, 23547, 17620, 17622, -1, 23557, 17620, 23547, -1, 17609, 23558, 17613, -1, 23559, 23558, 23560, -1, 23560, 23558, 17609, -1, 23561, 23558, 23559, -1, 17620, 23562, 17621, -1, 17621, 23562, 23563, -1, 23563, 23564, 23565, -1, 23565, 23564, 23566, -1, 17613, 23567, 17617, -1, 23561, 23567, 23558, -1, 23558, 23567, 17613, -1, 23566, 23567, 23561, -1, 23557, 23568, 17620, -1, 17620, 23568, 23562, -1, 23563, 23569, 23564, -1, 23562, 23569, 23563, -1, 21975, 23570, 21977, -1, 23556, 23570, 23557, -1, 23557, 23570, 23568, -1, 21977, 23570, 23556, -1, 17617, 23571, 17619, -1, 23567, 23571, 17617, -1, 23564, 23571, 23566, -1, 19043, 17609, 17611, -1, 23566, 23571, 23567, -1, 23568, 23572, 23562, -1, 23562, 23572, 23569, -1, 17619, 23573, 17593, -1, 23571, 23573, 17619, -1, 23569, 23573, 23564, -1, 23564, 23573, 23571, -1, 21023, 21977, 23556, -1, 21972, 23574, 21975, -1, 21975, 23574, 23570, -1, 23570, 23574, 23568, -1, 23568, 23574, 23572, -1, 17593, 23575, 17592, -1, 23573, 23575, 17593, -1, 23572, 23575, 23569, -1, 23569, 23575, 23573, -1, 21970, 23576, 21972, -1, 23572, 23576, 23575, -1, 21972, 23576, 23574, -1, 17592, 23576, 21970, -1, 23574, 23576, 23572, -1, 23575, 23576, 17592, -1, 21970, 17607, 17592, -1, 17629, 23577, 17631, -1, 17631, 23577, 19052, -1, 17626, 23578, 17629, -1, 17629, 23578, 23577, -1, 19052, 23559, 19049, -1, 19049, 23559, 19045, -1, 23577, 23559, 19052, -1, 17624, 23565, 17626, -1, 17626, 23565, 23578, -1, 23577, 23561, 23559, -1, 23578, 23561, 23577, -1, 19045, 23560, 19043, -1, 23559, 23560, 19045, -1, 19043, 23560, 17609, -1, 17621, 23563, 17624, -1, 17624, 23563, 23565, -1, 23565, 23566, 23578, -1, 23578, 23566, 23561, -1, 17608, 21030, 17605, -1, 17605, 23579, 17600, -1, 21030, 23579, 17605, -1, 17600, 23580, 17597, -1, 23579, 23580, 17600, -1, 17597, 23581, 17585, -1, 23580, 23581, 17597, -1, 17585, 23582, 17583, -1, 23581, 23582, 17585, -1, 17583, 23583, 17602, -1, 23582, 23583, 17583, -1, 17602, 23584, 17603, -1, 23583, 23584, 17602, -1, 23584, 18849, 17603, -1, 23585, 23586, 18833, -1, 23580, 23587, 23581, -1, 23581, 23587, 23588, -1, 23588, 23589, 23590, -1, 23590, 23589, 23591, -1, 23592, 23593, 23585, -1, 23585, 23593, 23586, -1, 18832, 23594, 19068, -1, 19068, 23594, 18827, -1, 18827, 23594, 23595, -1, 23595, 23594, 23596, -1, 23586, 23594, 18832, -1, 21956, 23597, 21030, -1, 23579, 23597, 23580, -1, 21030, 23597, 23579, -1, 23580, 23597, 23587, -1, 23587, 23598, 23588, -1, 23588, 23598, 23589, -1, 23592, 23599, 23593, -1, 23591, 23599, 23592, -1, 23593, 23600, 23586, -1, 23594, 23600, 23596, -1, 23586, 23600, 23594, -1, 21959, 23601, 21958, -1, 21958, 23601, 21956, -1, 21956, 23601, 23597, -1, 23597, 23601, 23587, -1, 23587, 23601, 23598, -1, 23589, 23602, 23591, -1, 23591, 23602, 23599, -1, 23596, 23603, 23604, -1, 23600, 23603, 23596, -1, 23599, 23603, 23593, -1, 23593, 23603, 23600, -1, 23598, 23605, 23589, -1, 23589, 23605, 23602, -1, 23602, 23606, 23599, -1, 23604, 23606, 23607, -1, 23603, 23606, 23604, -1, 23599, 23606, 23603, -1, 21963, 23608, 21961, -1, 21961, 23608, 21959, -1, 23598, 23608, 23605, -1, 21959, 23608, 23601, -1, 23601, 23608, 23598, -1, 23605, 23609, 23602, -1, 23606, 23609, 23607, -1, 23607, 23609, 23610, -1, 21963, 21027, 23611, -1, 23602, 23609, 23606, -1, 23605, 23612, 23609, -1, 18849, 23613, 18843, -1, 23610, 23612, 23611, -1, 18843, 23613, 18841, -1, 23608, 23612, 23605, -1, 21963, 23612, 23608, -1, 23611, 23612, 21963, -1, 23584, 23613, 18849, -1, 23609, 23612, 23610, -1, 23583, 23614, 23584, -1, 23584, 23614, 23613, -1, 18841, 23585, 18833, -1, 23613, 23585, 18841, -1, 23582, 23590, 23583, -1, 23583, 23590, 23614, -1, 23613, 23592, 23585, -1, 23614, 23592, 23613, -1, 23581, 23588, 23582, -1, 23582, 23588, 23590, -1, 23590, 23591, 23614, -1, 23614, 23591, 23592, -1, 18833, 23586, 18832, -1, 18827, 23595, 18854, -1, 18854, 23595, 23615, -1, 23615, 23596, 23616, -1, 23595, 23596, 23615, -1, 23616, 23604, 23617, -1, 23596, 23604, 23616, -1, 23617, 23607, 23618, -1, 23604, 23607, 23617, -1, 23618, 23610, 23619, -1, 23607, 23610, 23618, -1, 23619, 23611, 23620, -1, 23610, 23611, 23619, -1, 23620, 21027, 21029, -1, 23611, 21027, 23620, -1, 22169, 23620, 21029, -1, 18864, 18859, 19355, -1, 22169, 23619, 23620, -1, 22169, 23618, 23619, -1, 18858, 23616, 23617, -1, 18858, 23615, 23616, -1, 18858, 18854, 23615, -1, 19346, 23621, 19156, -1, 19156, 23621, 22171, -1, 22171, 23621, 22169, -1, 19348, 23622, 19346, -1, 23621, 23622, 22169, -1, 19346, 23622, 23621, -1, 19350, 23623, 19348, -1, 23622, 23623, 22169, -1, 19348, 23623, 23622, -1, 22169, 23623, 23618, -1, 19352, 23624, 19350, -1, 23618, 23624, 23617, -1, 23623, 23624, 23618, -1, 19350, 23624, 23623, -1, 23617, 23624, 18858, -1, 19353, 23625, 19352, -1, 23624, 23625, 18858, -1, 19352, 23625, 23624, -1, 18858, 23626, 18859, -1, 19355, 23626, 19353, -1, 19353, 23626, 23625, -1, 23625, 23626, 18858, -1, 18859, 23626, 19355, -1, 23627, 22152, 21046, -1, 22154, 19360, 19140, -1, 22154, 19363, 19360, -1, 20516, 20525, 23628, -1, 22154, 19366, 19363, -1, 20524, 19374, 19371, -1, 20524, 19376, 19374, -1, 20524, 19378, 19376, -1, 22152, 23629, 22154, -1, 23627, 23629, 22152, -1, 23630, 23631, 23627, -1, 23629, 23631, 22154, -1, 23627, 23631, 23629, -1, 23632, 23633, 23630, -1, 23631, 23633, 22154, -1, 23630, 23633, 23631, -1, 22154, 23633, 19366, -1, 23634, 23635, 23632, -1, 19366, 23635, 19369, -1, 23632, 23635, 23633, -1, 23633, 23635, 19366, -1, 23636, 23637, 23634, -1, 19369, 23637, 19371, -1, 23635, 23637, 19369, -1, 23634, 23637, 23635, -1, 23638, 23639, 23636, -1, 23636, 23639, 23637, -1, 23637, 23639, 19371, -1, 19371, 23639, 20524, -1, 23640, 23641, 23638, -1, 23639, 23641, 20524, -1, 23638, 23641, 23639, -1, 20524, 23642, 20525, -1, 23628, 23642, 23640, -1, 23641, 23642, 20524, -1, 23640, 23642, 23641, -1, 20525, 23642, 23628, -1, 21048, 23643, 21046, -1, 21046, 23643, 23627, -1, 23627, 23644, 23630, -1, 23643, 23644, 23627, -1, 23630, 23645, 23632, -1, 23644, 23645, 23630, -1, 23632, 23646, 23634, -1, 23645, 23646, 23632, -1, 23634, 23647, 23636, -1, 23646, 23647, 23634, -1, 23636, 23648, 23638, -1, 23647, 23648, 23636, -1, 23638, 23649, 23640, -1, 23648, 23649, 23638, -1, 23640, 23650, 23628, -1, 23649, 23650, 23640, -1, 23628, 20433, 20516, -1, 23650, 20433, 23628, -1, 23651, 23652, 23653, -1, 23653, 23652, 23654, -1, 23655, 23656, 23657, -1, 23654, 23656, 23655, -1, 23645, 23658, 23646, -1, 23646, 23658, 23659, -1, 23659, 23660, 23651, -1, 23651, 23660, 23652, -1, 20410, 23661, 20415, -1, 23657, 23661, 20410, -1, 20415, 23661, 23662, -1, 23652, 23663, 23654, -1, 23654, 23663, 23656, -1, 23644, 23664, 23645, -1, 23645, 23664, 23658, -1, 23662, 23665, 23666, -1, 23661, 23665, 23662, -1, 23656, 23665, 23657, -1, 23657, 23665, 23661, -1, 23659, 23667, 23660, -1, 23658, 23667, 23659, -1, 20415, 23662, 20452, -1, 23660, 23668, 23652, -1, 23652, 23668, 23663, -1, 23666, 23669, 23670, -1, 21048, 22021, 23643, -1, 23665, 23669, 23666, -1, 23663, 23669, 23656, -1, 23656, 23669, 23665, -1, 22019, 23671, 22021, -1, 23643, 23671, 23644, -1, 23644, 23671, 23664, -1, 22021, 23671, 23643, -1, 23664, 23672, 23658, -1, 23658, 23672, 23667, -1, 23667, 23673, 23660, -1, 23660, 23673, 23668, -1, 23663, 23674, 23669, -1, 23670, 23674, 23675, -1, 23669, 23674, 23670, -1, 23668, 23674, 23663, -1, 23671, 23676, 23664, -1, 22017, 23676, 22019, -1, 23664, 23676, 23672, -1, 22019, 23676, 23671, -1, 23672, 23677, 23667, -1, 23667, 23677, 23673, -1, 20433, 23678, 20428, -1, 23673, 23679, 23668, -1, 23668, 23679, 23674, -1, 23650, 23678, 20433, -1, 23674, 23679, 23675, -1, 22014, 23680, 22017, -1, 22017, 23680, 23676, -1, 23676, 23680, 23672, -1, 23649, 23653, 23650, -1, 23672, 23680, 23677, -1, 23675, 23681, 23682, -1, 23650, 23653, 23678, -1, 23679, 23681, 23675, -1, 23673, 23681, 23679, -1, 23677, 23681, 23673, -1, 20428, 23655, 20423, -1, 20423, 23655, 20413, -1, 23682, 23683, 23684, -1, 23678, 23655, 20428, -1, 23684, 23683, 21051, -1, 21051, 23683, 22014, -1, 23681, 23683, 23682, -1, 23680, 23683, 23677, -1, 23677, 23683, 23681, -1, 23648, 23651, 23649, -1, 22014, 23683, 23680, -1, 23649, 23651, 23653, -1, 23678, 23654, 23655, -1, 23653, 23654, 23678, -1, 20413, 23657, 20410, -1, 23655, 23657, 20413, -1, 23647, 23659, 23648, -1, 23646, 23659, 23647, -1, 23648, 23659, 23651, -1, 21051, 21052, 23684, -1, 23684, 23685, 23682, -1, 21052, 23685, 23684, -1, 23682, 23686, 23675, -1, 23685, 23686, 23682, -1, 23675, 23687, 23670, -1, 23686, 23687, 23675, -1, 23670, 23688, 23666, -1, 23687, 23688, 23670, -1, 23666, 23689, 23662, -1, 23688, 23689, 23666, -1, 23662, 23690, 20452, -1, 23689, 23690, 23662, -1, 23690, 20453, 20452, -1, 23691, 23692, 23693, -1, 23694, 23695, 23696, -1, 23697, 23698, 23699, -1, 17569, 23695, 17571, -1, 23699, 23698, 23700, -1, 23696, 23695, 23701, -1, 23701, 23695, 17569, -1, 23702, 23703, 23691, -1, 23704, 23705, 23697, -1, 23706, 23703, 23702, -1, 23697, 23705, 23698, -1, 22006, 23707, 22004, -1, 22004, 23707, 22003, -1, 22003, 23707, 23706, -1, 20455, 23708, 20458, -1, 23694, 23709, 23695, -1, 23700, 23708, 20455, -1, 23692, 23709, 23694, -1, 23695, 23709, 17571, -1, 22001, 23710, 22000, -1, 23685, 23710, 23686, -1, 23686, 23710, 23711, -1, 23691, 23712, 23692, -1, 22000, 23710, 23685, -1, 23703, 23712, 23691, -1, 22006, 23713, 23707, -1, 23706, 23713, 23703, -1, 23700, 23714, 23708, -1, 23707, 23713, 23706, -1, 22011, 23715, 22009, -1, 23698, 23714, 23700, -1, 17571, 23715, 17574, -1, 23692, 23715, 23709, -1, 23712, 23715, 23692, -1, 23709, 23715, 17571, -1, 17574, 23715, 22011, -1, 22009, 23716, 22008, -1, 22008, 23716, 22006, -1, 23704, 23717, 23705, -1, 23715, 23716, 22009, -1, 23711, 23717, 23704, -1, 23703, 23716, 23712, -1, 23713, 23716, 23703, -1, 23712, 23716, 23715, -1, 22006, 23716, 23713, -1, 23698, 23718, 23714, -1, 23705, 23718, 23698, -1, 20458, 23719, 20461, -1, 21052, 22000, 23685, -1, 23708, 23719, 20458, -1, 22002, 23720, 22001, -1, 22001, 23720, 23710, -1, 23710, 23720, 23711, -1, 23711, 23720, 23717, -1, 23714, 23721, 23708, -1, 23708, 23721, 23719, -1, 23717, 23722, 23705, -1, 23705, 23722, 23718, -1, 20461, 23723, 20467, -1, 23719, 23723, 20461, -1, 23718, 23724, 23714, -1, 23714, 23724, 23721, -1, 23721, 23725, 23719, -1, 20476, 17566, 17568, -1, 23719, 23725, 23723, -1, 20467, 23726, 20471, -1, 23723, 23726, 20467, -1, 22003, 23727, 22002, -1, 23717, 23727, 23722, -1, 22002, 23727, 23720, -1, 23720, 23727, 23717, -1, 23722, 23702, 23718, -1, 23718, 23702, 23724, -1, 23721, 23693, 23725, -1, 23724, 23693, 23721, -1, 23725, 23696, 23723, -1, 22011, 17576, 17574, -1, 23690, 23699, 20453, -1, 23723, 23696, 23726, -1, 23726, 23728, 20471, -1, 20453, 23699, 20454, -1, 20471, 23728, 20476, -1, 20476, 23728, 17566, -1, 23689, 23697, 23690, -1, 23724, 23691, 23693, -1, 23702, 23691, 23724, -1, 23690, 23697, 23699, -1, 23693, 23694, 23725, -1, 23725, 23694, 23696, -1, 23688, 23704, 23689, -1, 23687, 23704, 23688, -1, 23689, 23704, 23697, -1, 23727, 23706, 23722, -1, 20454, 23700, 20455, -1, 23722, 23706, 23702, -1, 22003, 23706, 23727, -1, 23696, 23701, 23726, -1, 23699, 23700, 20454, -1, 23726, 23701, 23728, -1, 17566, 23701, 17569, -1, 23728, 23701, 17566, -1, 23686, 23711, 23687, -1, 23687, 23711, 23704, -1, 23693, 23692, 23694, -1, 20538, 17567, 23729, -1, 23729, 17570, 23730, -1, 17567, 17570, 23729, -1, 23730, 17572, 23731, -1, 17570, 17572, 23730, -1, 23731, 17573, 23732, -1, 17572, 17573, 23731, -1, 23732, 17575, 21044, -1, 17573, 17575, 23732, -1, 17575, 17578, 21044, -1, 21044, 22156, 23732, -1, 20554, 23733, 20553, -1, 20554, 23734, 23733, -1, 22158, 23734, 20554, -1, 22158, 23735, 23734, -1, 22158, 23736, 23735, -1, 22158, 19141, 23736, -1, 20538, 23737, 20548, -1, 20548, 23737, 20554, -1, 23729, 23737, 20538, -1, 23730, 23738, 23729, -1, 23737, 23738, 20554, -1, 23729, 23738, 23737, -1, 23731, 23739, 23730, -1, 23738, 23739, 20554, -1, 23730, 23739, 23738, -1, 20554, 23739, 22158, -1, 22158, 23740, 22156, -1, 23732, 23740, 23731, -1, 23739, 23740, 22158, -1, 23731, 23740, 23739, -1, 22156, 23740, 23732, -1, 19313, 20553, 19312, -1, 19312, 23733, 19311, -1, 20553, 23733, 19312, -1, 19311, 23734, 19309, -1, 19309, 23734, 19310, -1, 23733, 23734, 19311, -1, 19310, 23735, 19384, -1, 23734, 23735, 19310, -1, 19384, 23736, 19380, -1, 23735, 23736, 19384, -1, 19380, 19141, 19143, -1, 23736, 19141, 19380, -1, 23741, 22160, 21036, -1, 22162, 19387, 19149, -1, 22162, 19390, 19387, -1, 20486, 20499, 23742, -1, 22162, 19393, 19390, -1, 20498, 19401, 19398, -1, 20498, 19403, 19401, -1, 20498, 19405, 19403, -1, 22160, 23743, 22162, -1, 23741, 23743, 22160, -1, 23744, 23745, 23741, -1, 23743, 23745, 22162, -1, 23741, 23745, 23743, -1, 23746, 23747, 23744, -1, 23745, 23747, 22162, -1, 23744, 23747, 23745, -1, 22162, 23747, 19393, -1, 23748, 23749, 23746, -1, 19393, 23749, 19396, -1, 23746, 23749, 23747, -1, 23747, 23749, 19393, -1, 23750, 23751, 23748, -1, 19396, 23751, 19398, -1, 23749, 23751, 19396, -1, 23748, 23751, 23749, -1, 23752, 23753, 23750, -1, 23750, 23753, 23751, -1, 23751, 23753, 19398, -1, 19398, 23753, 20498, -1, 23754, 23755, 23752, -1, 23753, 23755, 20498, -1, 23752, 23755, 23753, -1, 20498, 23756, 20499, -1, 23742, 23756, 23754, -1, 23755, 23756, 20498, -1, 23754, 23756, 23755, -1, 20499, 23756, 23742, -1, 21038, 23757, 21036, -1, 21036, 23757, 23741, -1, 23741, 23758, 23744, -1, 23757, 23758, 23741, -1, 23744, 23759, 23746, -1, 23758, 23759, 23744, -1, 23746, 23760, 23748, -1, 23759, 23760, 23746, -1, 23748, 23761, 23750, -1, 23760, 23761, 23748, -1, 23750, 23762, 23752, -1, 23761, 23762, 23750, -1, 23752, 23763, 23754, -1, 23762, 23763, 23752, -1, 23754, 23764, 23742, -1, 23763, 23764, 23754, -1, 23742, 20362, 20486, -1, 23764, 20362, 23742, -1, 23765, 23766, 23767, -1, 23767, 23766, 23768, -1, 23769, 23770, 23771, -1, 23768, 23770, 23769, -1, 23759, 23772, 23760, -1, 23760, 23772, 23773, -1, 23773, 23774, 23765, -1, 23765, 23774, 23766, -1, 20568, 23775, 20356, -1, 23771, 23775, 20568, -1, 20356, 23775, 23776, -1, 23766, 23777, 23768, -1, 23768, 23777, 23770, -1, 23758, 23778, 23759, -1, 23759, 23778, 23772, -1, 23776, 23779, 23780, -1, 23775, 23779, 23776, -1, 23770, 23779, 23771, -1, 23771, 23779, 23775, -1, 23773, 23781, 23774, -1, 23772, 23781, 23773, -1, 20356, 23776, 20357, -1, 23774, 23782, 23766, -1, 23766, 23782, 23777, -1, 23780, 23783, 23784, -1, 21038, 21986, 23757, -1, 23779, 23783, 23780, -1, 23777, 23783, 23770, -1, 23770, 23783, 23779, -1, 21984, 23785, 21986, -1, 23757, 23785, 23758, -1, 23758, 23785, 23778, -1, 21986, 23785, 23757, -1, 23778, 23786, 23772, -1, 23772, 23786, 23781, -1, 23781, 23787, 23774, -1, 23774, 23787, 23782, -1, 23777, 23788, 23783, -1, 23784, 23788, 23789, -1, 23783, 23788, 23784, -1, 23782, 23788, 23777, -1, 23785, 23790, 23778, -1, 21982, 23790, 21984, -1, 23778, 23790, 23786, -1, 21984, 23790, 23785, -1, 23786, 23791, 23781, -1, 23781, 23791, 23787, -1, 20362, 23792, 20359, -1, 23787, 23793, 23782, -1, 23782, 23793, 23788, -1, 23764, 23792, 20362, -1, 23788, 23793, 23789, -1, 21979, 23794, 21982, -1, 21982, 23794, 23790, -1, 23790, 23794, 23786, -1, 23763, 23767, 23764, -1, 23786, 23794, 23791, -1, 23789, 23795, 23796, -1, 23764, 23767, 23792, -1, 23793, 23795, 23789, -1, 23787, 23795, 23793, -1, 23791, 23795, 23787, -1, 20359, 23769, 20345, -1, 20345, 23769, 20346, -1, 23796, 23797, 23798, -1, 23792, 23769, 20359, -1, 23798, 23797, 21041, -1, 21041, 23797, 21979, -1, 23795, 23797, 23796, -1, 23794, 23797, 23791, -1, 23791, 23797, 23795, -1, 23762, 23765, 23763, -1, 21979, 23797, 23794, -1, 23763, 23765, 23767, -1, 23792, 23768, 23769, -1, 23767, 23768, 23792, -1, 20346, 23771, 20568, -1, 23769, 23771, 20346, -1, 23761, 23773, 23762, -1, 23760, 23773, 23761, -1, 23762, 23773, 23765, -1, 21042, 23799, 21041, -1, 21041, 23799, 23798, -1, 23798, 23800, 23796, -1, 23799, 23800, 23798, -1, 23796, 23801, 23789, -1, 23800, 23801, 23796, -1, 23789, 23802, 23784, -1, 23801, 23802, 23789, -1, 23784, 23803, 23780, -1, 23802, 23803, 23784, -1, 23776, 23804, 20357, -1, 23780, 23804, 23776, -1, 23803, 23804, 23780, -1, 23804, 20451, 20357, -1, 23805, 23806, 23807, -1, 23808, 23809, 23810, -1, 23810, 23809, 23811, -1, 17556, 23806, 17559, -1, 23807, 23806, 23812, -1, 23812, 23806, 17556, -1, 23813, 23814, 23815, -1, 23816, 23817, 23808, -1, 23818, 23814, 23813, -1, 23808, 23817, 23809, -1, 21993, 23819, 21991, -1, 21991, 23819, 21990, -1, 21990, 23819, 23818, -1, 20409, 23820, 20412, -1, 23805, 23821, 23806, -1, 23822, 23821, 23805, -1, 23811, 23820, 20409, -1, 23806, 23821, 17559, -1, 21988, 23823, 21987, -1, 23799, 23823, 23800, -1, 23815, 23824, 23822, -1, 23800, 23823, 23825, -1, 23814, 23824, 23815, -1, 21987, 23823, 23799, -1, 21993, 23826, 23819, -1, 23818, 23826, 23814, -1, 23809, 23827, 23811, -1, 23819, 23826, 23818, -1, 23811, 23827, 23820, -1, 21998, 23828, 21996, -1, 17559, 23828, 17561, -1, 23822, 23828, 23821, -1, 23821, 23828, 17559, -1, 23824, 23828, 23822, -1, 17561, 23828, 21998, -1, 23816, 23829, 23817, -1, 21996, 23830, 21995, -1, 21995, 23830, 21993, -1, 23825, 23829, 23816, -1, 21993, 23830, 23826, -1, 23814, 23830, 23824, -1, 23826, 23830, 23814, -1, 23824, 23830, 23828, -1, 23828, 23830, 21996, -1, 23809, 23831, 23827, -1, 23817, 23831, 23809, -1, 20412, 23832, 20422, -1, 21042, 21987, 23799, -1, 23820, 23832, 20412, -1, 21989, 23833, 21988, -1, 21988, 23833, 23823, -1, 23825, 23833, 23829, -1, 23823, 23833, 23825, -1, 23827, 23834, 23820, -1, 23820, 23834, 23832, -1, 23817, 23835, 23831, -1, 23829, 23835, 23817, -1, 20422, 23836, 20432, -1, 23832, 23836, 20422, -1, 23831, 23837, 23827, -1, 23827, 23837, 23834, -1, 23834, 23838, 23832, -1, 20436, 17553, 17555, -1, 23832, 23838, 23836, -1, 20432, 23839, 20434, -1, 23836, 23839, 20432, -1, 23829, 23840, 23835, -1, 21990, 23840, 21989, -1, 21989, 23840, 23833, -1, 23833, 23840, 23829, -1, 23831, 23813, 23837, -1, 23835, 23813, 23831, -1, 23837, 23841, 23834, -1, 23834, 23841, 23838, -1, 23838, 23807, 23836, -1, 21998, 17563, 17561, -1, 23804, 23810, 20451, -1, 23836, 23807, 23839, -1, 23803, 23810, 23804, -1, 20434, 23842, 20436, -1, 20451, 23810, 20411, -1, 23839, 23842, 20434, -1, 20436, 23842, 17553, -1, 23837, 23815, 23841, -1, 23813, 23815, 23837, -1, 23803, 23808, 23810, -1, 23841, 23805, 23838, -1, 23802, 23816, 23803, -1, 23801, 23816, 23802, -1, 23838, 23805, 23807, -1, 23803, 23816, 23808, -1, 23835, 23818, 23813, -1, 23840, 23818, 23835, -1, 20411, 23811, 20409, -1, 21990, 23818, 23840, -1, 23839, 23812, 23842, -1, 23807, 23812, 23839, -1, 23810, 23811, 20411, -1, 17553, 23812, 17556, -1, 23842, 23812, 17553, -1, 23800, 23825, 23801, -1, 23801, 23825, 23816, -1, 23815, 23822, 23841, -1, 23841, 23822, 23805, -1, 20515, 17554, 23843, -1, 23843, 17557, 23844, -1, 17554, 17557, 23843, -1, 23844, 17558, 23845, -1, 17557, 17558, 23844, -1, 23845, 17560, 23846, -1, 17558, 17560, 23845, -1, 23846, 17562, 21034, -1, 17560, 17562, 23846, -1, 17562, 17565, 21034, -1, 21034, 22164, 23846, -1, 20534, 23847, 20528, -1, 20534, 23848, 23847, -1, 22166, 23848, 20534, -1, 22166, 23849, 23848, -1, 22166, 23850, 23849, -1, 22166, 19150, 23850, -1, 20515, 23851, 20526, -1, 20526, 23851, 20534, -1, 23843, 23851, 20515, -1, 23844, 23852, 23843, -1, 23851, 23852, 20534, -1, 23843, 23852, 23851, -1, 23845, 23853, 23844, -1, 23852, 23853, 20534, -1, 23844, 23853, 23852, -1, 20534, 23853, 22166, -1, 22166, 23854, 22164, -1, 23846, 23854, 23845, -1, 23853, 23854, 22166, -1, 23845, 23854, 23853, -1, 22164, 23854, 23846, -1, 19644, 20528, 19648, -1, 19653, 23847, 19656, -1, 19648, 23847, 19653, -1, 20528, 23847, 19648, -1, 19650, 23848, 19651, -1, 19656, 23848, 19650, -1, 23847, 23848, 19656, -1, 19651, 23849, 23855, -1, 23848, 23849, 19651, -1, 23855, 23850, 23856, -1, 23849, 23850, 23855, -1, 23856, 19150, 19152, -1, 23850, 19150, 23856, -1, 23857, 22176, 21016, -1, 22178, 19414, 19167, -1, 22178, 19417, 19414, -1, 20341, 20367, 23858, -1, 22178, 19420, 19417, -1, 20366, 19428, 19425, -1, 20366, 19430, 19428, -1, 20366, 19432, 19430, -1, 22176, 23859, 22178, -1, 23857, 23859, 22176, -1, 23860, 23861, 23857, -1, 23859, 23861, 22178, -1, 23857, 23861, 23859, -1, 23862, 23863, 23860, -1, 23861, 23863, 22178, -1, 23860, 23863, 23861, -1, 22178, 23863, 19420, -1, 23864, 23865, 23862, -1, 19420, 23865, 19423, -1, 23862, 23865, 23863, -1, 23863, 23865, 19420, -1, 23866, 23867, 23864, -1, 19423, 23867, 19425, -1, 23865, 23867, 19423, -1, 23864, 23867, 23865, -1, 23868, 23869, 23866, -1, 23866, 23869, 23867, -1, 23867, 23869, 19425, -1, 19425, 23869, 20366, -1, 23870, 23871, 23868, -1, 23869, 23871, 20366, -1, 23868, 23871, 23869, -1, 20366, 23872, 20367, -1, 23858, 23872, 23870, -1, 23871, 23872, 20366, -1, 23870, 23872, 23871, -1, 20367, 23872, 23858, -1, 21018, 23873, 21016, -1, 21016, 23873, 23857, -1, 23857, 23874, 23860, -1, 23873, 23874, 23857, -1, 23860, 23875, 23862, -1, 23874, 23875, 23860, -1, 23862, 23876, 23864, -1, 23875, 23876, 23862, -1, 23864, 23877, 23866, -1, 23876, 23877, 23864, -1, 23866, 23878, 23868, -1, 23877, 23878, 23866, -1, 23868, 23879, 23870, -1, 23878, 23879, 23868, -1, 23870, 23880, 23858, -1, 23879, 23880, 23870, -1, 23858, 20343, 20341, -1, 23880, 20343, 23858, -1, 23881, 23882, 23883, -1, 23883, 23882, 23884, -1, 23885, 23886, 23887, -1, 23884, 23886, 23885, -1, 23875, 23888, 23876, -1, 23876, 23888, 23889, -1, 23889, 23890, 23881, -1, 23881, 23890, 23882, -1, 20448, 23891, 20459, -1, 23887, 23891, 20448, -1, 20459, 23891, 23892, -1, 23882, 23893, 23884, -1, 23884, 23893, 23886, -1, 23874, 23894, 23875, -1, 23875, 23894, 23888, -1, 23892, 23895, 23896, -1, 23891, 23895, 23892, -1, 23886, 23895, 23887, -1, 23887, 23895, 23891, -1, 23889, 23897, 23890, -1, 23888, 23897, 23889, -1, 20459, 23892, 20469, -1, 23890, 23898, 23882, -1, 23882, 23898, 23893, -1, 23896, 23899, 23900, -1, 21018, 21955, 23873, -1, 23895, 23899, 23896, -1, 23893, 23899, 23886, -1, 23886, 23899, 23895, -1, 21953, 23901, 21955, -1, 23873, 23901, 23874, -1, 23874, 23901, 23894, -1, 21955, 23901, 23873, -1, 23894, 23902, 23888, -1, 23888, 23902, 23897, -1, 23897, 23903, 23890, -1, 23890, 23903, 23898, -1, 23893, 23904, 23899, -1, 23900, 23904, 23905, -1, 23899, 23904, 23900, -1, 23898, 23904, 23893, -1, 23901, 23906, 23894, -1, 21951, 23906, 21953, -1, 23894, 23906, 23902, -1, 21953, 23906, 23901, -1, 23902, 23907, 23897, -1, 23897, 23907, 23903, -1, 20343, 23908, 20470, -1, 23903, 23909, 23898, -1, 23898, 23909, 23904, -1, 23880, 23908, 20343, -1, 23904, 23909, 23905, -1, 21948, 23910, 21951, -1, 21951, 23910, 23906, -1, 23906, 23910, 23902, -1, 23879, 23883, 23880, -1, 23902, 23910, 23907, -1, 23905, 23911, 23912, -1, 23880, 23883, 23908, -1, 23909, 23911, 23905, -1, 23903, 23911, 23909, -1, 23907, 23911, 23903, -1, 20470, 23885, 20466, -1, 20466, 23885, 20457, -1, 23912, 23913, 23914, -1, 23908, 23885, 20470, -1, 23914, 23913, 21021, -1, 21021, 23913, 21948, -1, 23911, 23913, 23912, -1, 23910, 23913, 23907, -1, 23907, 23913, 23911, -1, 23878, 23881, 23879, -1, 21948, 23913, 23910, -1, 23879, 23881, 23883, -1, 23908, 23884, 23885, -1, 23883, 23884, 23908, -1, 20457, 23887, 20448, -1, 23885, 23887, 20457, -1, 23877, 23889, 23878, -1, 23876, 23889, 23877, -1, 23878, 23889, 23881, -1, 21022, 23915, 21021, -1, 21021, 23915, 23914, -1, 23914, 23916, 23912, -1, 23915, 23916, 23914, -1, 23912, 23917, 23905, -1, 23916, 23917, 23912, -1, 23905, 23918, 23900, -1, 23917, 23918, 23905, -1, 23900, 23919, 23896, -1, 23918, 23919, 23900, -1, 23896, 23920, 23892, -1, 23919, 23920, 23896, -1, 23892, 20518, 20469, -1, 23920, 20518, 23892, -1, 23921, 23922, 23923, -1, 23924, 23925, 23926, -1, 23926, 23925, 23927, -1, 17543, 23922, 17545, -1, 23923, 23922, 23928, -1, 23928, 23922, 17543, -1, 23929, 23930, 23931, -1, 23932, 23933, 23924, -1, 23934, 23930, 23929, -1, 23924, 23933, 23925, -1, 21940, 23935, 21938, -1, 21938, 23935, 21937, -1, 21937, 23935, 23934, -1, 20510, 23936, 20513, -1, 23921, 23937, 23922, -1, 23938, 23937, 23921, -1, 23927, 23936, 20510, -1, 23922, 23937, 17545, -1, 21935, 23939, 21934, -1, 23915, 23939, 23916, -1, 23931, 23940, 23938, -1, 23916, 23939, 23941, -1, 23930, 23940, 23931, -1, 21934, 23939, 23915, -1, 21940, 23942, 23935, -1, 23934, 23942, 23930, -1, 23925, 23943, 23927, -1, 23935, 23942, 23934, -1, 23927, 23943, 23936, -1, 21945, 23944, 21943, -1, 17545, 23944, 17548, -1, 23938, 23944, 23937, -1, 23937, 23944, 17545, -1, 23940, 23944, 23938, -1, 17548, 23944, 21945, -1, 23932, 23945, 23933, -1, 21943, 23946, 21942, -1, 21942, 23946, 21940, -1, 23941, 23945, 23932, -1, 21940, 23946, 23942, -1, 23930, 23946, 23940, -1, 23942, 23946, 23930, -1, 23940, 23946, 23944, -1, 23944, 23946, 21943, -1, 23925, 23947, 23943, -1, 23933, 23947, 23925, -1, 20513, 23948, 20522, -1, 21022, 21934, 23915, -1, 23936, 23948, 20513, -1, 21936, 23949, 21935, -1, 21935, 23949, 23939, -1, 23941, 23949, 23945, -1, 23939, 23949, 23941, -1, 23943, 23950, 23936, -1, 23936, 23950, 23948, -1, 23933, 23951, 23947, -1, 23945, 23951, 23933, -1, 20522, 23952, 20531, -1, 23948, 23952, 20522, -1, 23947, 23953, 23943, -1, 23943, 23953, 23950, -1, 23950, 23954, 23948, -1, 20533, 17540, 17542, -1, 23948, 23954, 23952, -1, 20531, 23955, 20532, -1, 23952, 23955, 20531, -1, 23945, 23956, 23951, -1, 21937, 23956, 21936, -1, 21936, 23956, 23949, -1, 23949, 23956, 23945, -1, 23947, 23929, 23953, -1, 23951, 23929, 23947, -1, 23953, 23957, 23950, -1, 23950, 23957, 23954, -1, 23954, 23923, 23952, -1, 21945, 17550, 17548, -1, 23920, 23926, 20518, -1, 23952, 23923, 23955, -1, 23919, 23926, 23920, -1, 20532, 23958, 20533, -1, 20518, 23926, 20512, -1, 23955, 23958, 20532, -1, 20533, 23958, 17540, -1, 23953, 23931, 23957, -1, 23929, 23931, 23953, -1, 23919, 23924, 23926, -1, 23957, 23921, 23954, -1, 23918, 23932, 23919, -1, 23917, 23932, 23918, -1, 23954, 23921, 23923, -1, 23919, 23932, 23924, -1, 23951, 23934, 23929, -1, 23956, 23934, 23951, -1, 20512, 23927, 20510, -1, 21937, 23934, 23956, -1, 23955, 23928, 23958, -1, 23923, 23928, 23955, -1, 23926, 23927, 20512, -1, 17540, 23928, 17543, -1, 23958, 23928, 17540, -1, 23916, 23941, 23917, -1, 23917, 23941, 23932, -1, 23931, 23938, 23957, -1, 23957, 23938, 23921, -1, 17541, 17544, 20416, -1, 20416, 17544, 23959, -1, 23959, 17546, 23960, -1, 17544, 17546, 23959, -1, 23960, 17547, 23961, -1, 17546, 17547, 23960, -1, 23961, 17549, 23962, -1, 17547, 17549, 23961, -1, 23962, 17552, 21014, -1, 17549, 17552, 23962, -1, 21014, 22180, 23962, -1, 20475, 23963, 20468, -1, 20475, 23964, 23963, -1, 22182, 23964, 20475, -1, 22182, 23965, 23964, -1, 22182, 23966, 23965, -1, 22182, 19168, 23966, -1, 20416, 23967, 20441, -1, 20441, 23967, 20475, -1, 23959, 23967, 20416, -1, 23960, 23968, 23959, -1, 23967, 23968, 20475, -1, 23959, 23968, 23967, -1, 23961, 23969, 23960, -1, 23968, 23969, 20475, -1, 23960, 23969, 23968, -1, 20475, 23969, 22182, -1, 22182, 23970, 22180, -1, 23962, 23970, 23961, -1, 23969, 23970, 22182, -1, 23961, 23970, 23969, -1, 22180, 23970, 23962, -1, 19702, 20468, 19706, -1, 19711, 23963, 19714, -1, 19706, 23963, 19711, -1, 20468, 23963, 19706, -1, 19708, 23964, 19709, -1, 19714, 23964, 19708, -1, 23963, 23964, 19714, -1, 19709, 23965, 23971, -1, 23964, 23965, 19709, -1, 23971, 23966, 23972, -1, 23965, 23966, 23971, -1, 23972, 19168, 19170, -1, 23966, 19168, 23972, -1, 23973, 22184, 21006, -1, 22186, 19445, 19176, -1, 22186, 19448, 19445, -1, 20519, 20536, 23974, -1, 22186, 19451, 19448, -1, 20535, 19458, 19456, -1, 20535, 19461, 19458, -1, 20535, 19462, 19461, -1, 22184, 23975, 22186, -1, 23973, 23975, 22184, -1, 23976, 23977, 23973, -1, 23975, 23977, 22186, -1, 23973, 23977, 23975, -1, 23978, 23979, 23976, -1, 23977, 23979, 22186, -1, 23976, 23979, 23977, -1, 22186, 23979, 19451, -1, 23980, 23981, 23978, -1, 19451, 23981, 19454, -1, 23978, 23981, 23979, -1, 23979, 23981, 19451, -1, 23982, 23983, 23980, -1, 19454, 23983, 19456, -1, 23981, 23983, 19454, -1, 23980, 23983, 23981, -1, 23984, 23985, 23982, -1, 23982, 23985, 23983, -1, 23983, 23985, 19456, -1, 19456, 23985, 20535, -1, 23986, 23987, 23984, -1, 23985, 23987, 20535, -1, 23984, 23987, 23985, -1, 20535, 23988, 20536, -1, 23974, 23988, 23986, -1, 23987, 23988, 20535, -1, 23986, 23988, 23987, -1, 20536, 23988, 23974, -1, 21008, 23989, 21006, -1, 21006, 23989, 23973, -1, 23973, 23990, 23976, -1, 23989, 23990, 23973, -1, 23976, 23991, 23978, -1, 23990, 23991, 23976, -1, 23978, 23992, 23980, -1, 23991, 23992, 23978, -1, 23980, 23993, 23982, -1, 23992, 23993, 23980, -1, 23982, 23994, 23984, -1, 23993, 23994, 23982, -1, 23984, 23995, 23986, -1, 23994, 23995, 23984, -1, 23986, 23996, 23974, -1, 23995, 23996, 23986, -1, 23974, 20401, 20519, -1, 23996, 20401, 23974, -1, 23997, 23998, 23999, -1, 23999, 23998, 24000, -1, 24001, 24002, 24003, -1, 24000, 24002, 24001, -1, 23991, 24004, 23992, -1, 23992, 24004, 24005, -1, 24005, 24006, 23997, -1, 23997, 24006, 23998, -1, 20370, 24007, 20377, -1, 24003, 24007, 20370, -1, 20377, 24007, 24008, -1, 23998, 24009, 24000, -1, 24000, 24009, 24002, -1, 23990, 24010, 23991, -1, 23991, 24010, 24004, -1, 24008, 24011, 24012, -1, 24007, 24011, 24008, -1, 24002, 24011, 24003, -1, 24003, 24011, 24007, -1, 24005, 24013, 24006, -1, 24004, 24013, 24005, -1, 20377, 24008, 20390, -1, 24006, 24014, 23998, -1, 23998, 24014, 24009, -1, 21008, 21920, 23989, -1, 24012, 24015, 24016, -1, 24011, 24015, 24012, -1, 24009, 24015, 24002, -1, 24002, 24015, 24011, -1, 21918, 24017, 21920, -1, 23989, 24017, 23990, -1, 23990, 24017, 24010, -1, 21920, 24017, 23989, -1, 24010, 24018, 24004, -1, 24004, 24018, 24013, -1, 24013, 24019, 24006, -1, 24006, 24019, 24014, -1, 24009, 24020, 24015, -1, 24016, 24020, 24021, -1, 24015, 24020, 24016, -1, 24014, 24020, 24009, -1, 24017, 24022, 24010, -1, 21916, 24022, 21918, -1, 24010, 24022, 24018, -1, 21918, 24022, 24017, -1, 24018, 24023, 24013, -1, 24013, 24023, 24019, -1, 20401, 24024, 20392, -1, 24019, 24025, 24014, -1, 24014, 24025, 24020, -1, 23996, 24024, 20401, -1, 24020, 24025, 24021, -1, 21913, 24026, 21916, -1, 21916, 24026, 24022, -1, 24022, 24026, 24018, -1, 23995, 23999, 23996, -1, 24018, 24026, 24023, -1, 24021, 24027, 24028, -1, 23996, 23999, 24024, -1, 24025, 24027, 24021, -1, 24019, 24027, 24025, -1, 24023, 24027, 24019, -1, 20392, 24001, 20385, -1, 20385, 24001, 20372, -1, 24028, 24029, 24030, -1, 24024, 24001, 20392, -1, 24030, 24029, 21011, -1, 21011, 24029, 21913, -1, 24027, 24029, 24028, -1, 24026, 24029, 24023, -1, 24023, 24029, 24027, -1, 23994, 23997, 23995, -1, 21913, 24029, 24026, -1, 23995, 23997, 23999, -1, 24024, 24000, 24001, -1, 23999, 24000, 24024, -1, 20372, 24003, 20370, -1, 24001, 24003, 20372, -1, 23993, 24005, 23994, -1, 23992, 24005, 23993, -1, 23994, 24005, 23997, -1, 21012, 24031, 21011, -1, 21011, 24031, 24030, -1, 24030, 24032, 24028, -1, 24031, 24032, 24030, -1, 24028, 24033, 24021, -1, 24032, 24033, 24028, -1, 24021, 24034, 24016, -1, 24033, 24034, 24021, -1, 24016, 24035, 24012, -1, 24034, 24035, 24016, -1, 24008, 24036, 20390, -1, 24012, 24036, 24008, -1, 24035, 24036, 24012, -1, 24036, 20460, 20390, -1, 24037, 24038, 24039, -1, 24040, 24041, 24042, -1, 17530, 24038, 17533, -1, 24043, 24041, 24040, -1, 24039, 24038, 24044, -1, 24044, 24038, 17530, -1, 24045, 24046, 24047, -1, 24048, 24046, 24045, -1, 24049, 24050, 24043, -1, 24043, 24050, 24041, -1, 21927, 24051, 21925, -1, 21925, 24051, 21924, -1, 21924, 24051, 24048, -1, 20447, 24052, 20456, -1, 17533, 24053, 17535, -1, 24038, 24053, 17533, -1, 24042, 24052, 20447, -1, 24054, 24053, 24037, -1, 24037, 24053, 24038, -1, 21922, 24055, 21921, -1, 24031, 24055, 24032, -1, 24032, 24055, 24056, -1, 24047, 24057, 24054, -1, 21921, 24055, 24031, -1, 24046, 24057, 24047, -1, 21927, 24058, 24051, -1, 24041, 24059, 24042, -1, 24048, 24058, 24046, -1, 24051, 24058, 24048, -1, 24042, 24059, 24052, -1, 21932, 24060, 21930, -1, 24054, 24060, 24053, -1, 24057, 24060, 24054, -1, 24053, 24060, 17535, -1, 17535, 24060, 21932, -1, 21930, 24061, 21929, -1, 24049, 24062, 24050, -1, 21929, 24061, 21927, -1, 21927, 24061, 24058, -1, 24056, 24062, 24049, -1, 24046, 24061, 24057, -1, 24060, 24061, 21930, -1, 24057, 24061, 24060, -1, 24058, 24061, 24046, -1, 24041, 24063, 24059, -1, 24050, 24063, 24041, -1, 20456, 24064, 20465, -1, 21012, 21921, 24031, -1, 24052, 24064, 20456, -1, 21923, 24065, 21922, -1, 21922, 24065, 24055, -1, 24056, 24065, 24062, -1, 24055, 24065, 24056, -1, 24059, 24066, 24052, -1, 24052, 24066, 24064, -1, 24050, 24067, 24063, -1, 24062, 24067, 24050, -1, 20465, 24068, 20472, -1, 24064, 24068, 20465, -1, 24063, 24069, 24059, -1, 24059, 24069, 24066, -1, 24066, 24070, 24064, -1, 24064, 24070, 24068, -1, 20474, 17527, 17529, -1, 20472, 24071, 20473, -1, 24068, 24071, 20472, -1, 24062, 24072, 24067, -1, 21924, 24072, 21923, -1, 21923, 24072, 24065, -1, 24065, 24072, 24062, -1, 24063, 24045, 24069, -1, 24067, 24045, 24063, -1, 24069, 24073, 24066, -1, 24066, 24073, 24070, -1, 24070, 24039, 24068, -1, 21932, 17537, 17535, -1, 24036, 24040, 20460, -1, 24068, 24039, 24071, -1, 24071, 24074, 20473, -1, 20460, 24040, 20449, -1, 20473, 24074, 20474, -1, 20474, 24074, 17527, -1, 24045, 24047, 24069, -1, 24035, 24043, 24036, -1, 24034, 24043, 24035, -1, 24069, 24047, 24073, -1, 24036, 24043, 24040, -1, 24073, 24037, 24070, -1, 24033, 24049, 24034, -1, 24070, 24037, 24039, -1, 24034, 24049, 24043, -1, 24067, 24048, 24045, -1, 20449, 24042, 20447, -1, 21924, 24048, 24072, -1, 24072, 24048, 24067, -1, 24039, 24044, 24071, -1, 24071, 24044, 24074, -1, 24040, 24042, 20449, -1, 17527, 24044, 17530, -1, 24074, 24044, 17527, -1, 24032, 24056, 24033, -1, 24033, 24056, 24049, -1, 24047, 24054, 24073, -1, 24073, 24054, 24037, -1, 17528, 17531, 20340, -1, 20340, 17531, 24075, -1, 24075, 17532, 24076, -1, 17531, 17532, 24075, -1, 24076, 17534, 24077, -1, 17532, 17534, 24076, -1, 24077, 17536, 24078, -1, 17534, 17536, 24077, -1, 24078, 17539, 21004, -1, 17536, 17539, 24078, -1, 21004, 22188, 24078, -1, 20394, 24079, 20383, -1, 20394, 24080, 24079, -1, 22190, 24080, 20394, -1, 22190, 24081, 24080, -1, 22190, 24082, 24081, -1, 22190, 19177, 24082, -1, 20340, 24083, 20368, -1, 20368, 24083, 20394, -1, 24075, 24083, 20340, -1, 24076, 24084, 24075, -1, 24083, 24084, 20394, -1, 24075, 24084, 24083, -1, 24077, 24085, 24076, -1, 24084, 24085, 20394, -1, 24076, 24085, 24084, -1, 20394, 24085, 22190, -1, 22190, 24086, 22188, -1, 24078, 24086, 24077, -1, 24085, 24086, 22190, -1, 24077, 24086, 24085, -1, 22188, 24086, 24078, -1, 19731, 20383, 19735, -1, 19740, 24079, 19743, -1, 19735, 24079, 19740, -1, 20383, 24079, 19735, -1, 19737, 24080, 19738, -1, 19743, 24080, 19737, -1, 24079, 24080, 19743, -1, 19738, 24081, 24087, -1, 24080, 24081, 19738, -1, 24087, 24082, 24088, -1, 24081, 24082, 24087, -1, 24088, 19177, 19179, -1, 24082, 19177, 24088, -1, 24089, 22192, 20996, -1, 22194, 19470, 19185, -1, 22194, 19473, 19470, -1, 20462, 20478, 24090, -1, 22194, 19476, 19473, -1, 20477, 19484, 19481, -1, 20477, 19486, 19484, -1, 20477, 19488, 19486, -1, 22192, 24091, 22194, -1, 24089, 24091, 22192, -1, 24092, 24093, 24089, -1, 24091, 24093, 22194, -1, 24089, 24093, 24091, -1, 24094, 24095, 24092, -1, 24093, 24095, 22194, -1, 24092, 24095, 24093, -1, 22194, 24095, 19476, -1, 24096, 24097, 24094, -1, 19476, 24097, 19479, -1, 24094, 24097, 24095, -1, 24095, 24097, 19476, -1, 24098, 24099, 24096, -1, 19479, 24099, 19481, -1, 24097, 24099, 19479, -1, 24096, 24099, 24097, -1, 24100, 24101, 24098, -1, 24098, 24101, 24099, -1, 24099, 24101, 19481, -1, 19481, 24101, 20477, -1, 24102, 24103, 24100, -1, 24101, 24103, 20477, -1, 24100, 24103, 24101, -1, 20477, 24104, 20478, -1, 24090, 24104, 24102, -1, 24103, 24104, 20477, -1, 24102, 24104, 24103, -1, 20478, 24104, 24090, -1, 20998, 24105, 20996, -1, 20996, 24105, 24089, -1, 24089, 24106, 24092, -1, 24105, 24106, 24089, -1, 24092, 24107, 24094, -1, 24106, 24107, 24092, -1, 24094, 24108, 24096, -1, 24107, 24108, 24094, -1, 24096, 24109, 24098, -1, 24108, 24109, 24096, -1, 24098, 24110, 24100, -1, 24109, 24110, 24098, -1, 24100, 24111, 24102, -1, 24110, 24111, 24100, -1, 24102, 24112, 24090, -1, 24111, 24112, 24102, -1, 24090, 20463, 20462, -1, 24112, 20463, 24090, -1, 24113, 24114, 24115, -1, 24115, 24114, 24116, -1, 24117, 24118, 24119, -1, 24116, 24118, 24117, -1, 24107, 24120, 24108, -1, 24108, 24120, 24121, -1, 24121, 24122, 24113, -1, 24113, 24122, 24114, -1, 20542, 24123, 20549, -1, 24119, 24123, 20542, -1, 20549, 24123, 24124, -1, 24114, 24125, 24116, -1, 24116, 24125, 24118, -1, 24106, 24126, 24107, -1, 24107, 24126, 24120, -1, 24124, 24127, 24128, -1, 24123, 24127, 24124, -1, 24118, 24127, 24119, -1, 24119, 24127, 24123, -1, 24121, 24129, 24122, -1, 24120, 24129, 24121, -1, 20549, 24124, 20557, -1, 24122, 24130, 24114, -1, 24114, 24130, 24125, -1, 24128, 24131, 24132, -1, 20998, 21898, 24105, -1, 24127, 24131, 24128, -1, 24125, 24131, 24118, -1, 24118, 24131, 24127, -1, 21896, 24133, 21898, -1, 24105, 24133, 24106, -1, 24106, 24133, 24126, -1, 21898, 24133, 24105, -1, 24126, 24134, 24120, -1, 24120, 24134, 24129, -1, 24129, 24135, 24122, -1, 24122, 24135, 24130, -1, 24125, 24136, 24131, -1, 24132, 24136, 24137, -1, 24131, 24136, 24132, -1, 24130, 24136, 24125, -1, 24133, 24138, 24126, -1, 21894, 24138, 21896, -1, 24126, 24138, 24134, -1, 21896, 24138, 24133, -1, 24134, 24139, 24129, -1, 24129, 24139, 24135, -1, 20463, 24140, 20560, -1, 24135, 24141, 24130, -1, 24130, 24141, 24136, -1, 24112, 24140, 20463, -1, 24136, 24141, 24137, -1, 21891, 24142, 21894, -1, 21894, 24142, 24138, -1, 24138, 24142, 24134, -1, 24111, 24115, 24112, -1, 24134, 24142, 24139, -1, 24137, 24143, 24144, -1, 24112, 24115, 24140, -1, 24141, 24143, 24137, -1, 24135, 24143, 24141, -1, 24139, 24143, 24135, -1, 20560, 24117, 20555, -1, 20555, 24117, 20547, -1, 24144, 24145, 24146, -1, 24140, 24117, 20560, -1, 24146, 24145, 21001, -1, 21001, 24145, 21891, -1, 24143, 24145, 24144, -1, 24142, 24145, 24139, -1, 24139, 24145, 24143, -1, 24110, 24113, 24111, -1, 21891, 24145, 24142, -1, 24111, 24113, 24115, -1, 24140, 24116, 24117, -1, 24115, 24116, 24140, -1, 20547, 24119, 20542, -1, 24117, 24119, 20547, -1, 24109, 24121, 24110, -1, 24108, 24121, 24109, -1, 24110, 24121, 24113, -1, 21001, 21002, 24146, -1, 24146, 24147, 24144, -1, 21002, 24147, 24146, -1, 24144, 24148, 24137, -1, 24147, 24148, 24144, -1, 24137, 24149, 24132, -1, 24148, 24149, 24137, -1, 24132, 24150, 24128, -1, 24149, 24150, 24132, -1, 24128, 24151, 24124, -1, 24150, 24151, 24128, -1, 24124, 24152, 20557, -1, 24151, 24152, 24124, -1, 24152, 20378, 20557, -1, 24153, 24154, 24155, -1, 24156, 24157, 24158, -1, 17517, 24154, 17520, -1, 24159, 24157, 24156, -1, 24155, 24154, 24160, -1, 24160, 24154, 17517, -1, 24161, 24162, 24163, -1, 24164, 24162, 24161, -1, 24165, 24166, 24159, -1, 24159, 24166, 24157, -1, 21905, 24167, 21903, -1, 21903, 24167, 21902, -1, 21902, 24167, 24164, -1, 20369, 24168, 20373, -1, 17520, 24169, 17522, -1, 24154, 24169, 17520, -1, 24158, 24168, 20369, -1, 24170, 24169, 24153, -1, 24153, 24169, 24154, -1, 21900, 24171, 21899, -1, 24147, 24171, 24148, -1, 24148, 24171, 24172, -1, 24163, 24173, 24170, -1, 21899, 24171, 24147, -1, 24162, 24173, 24163, -1, 21905, 24174, 24167, -1, 24157, 24175, 24158, -1, 24164, 24174, 24162, -1, 24167, 24174, 24164, -1, 24158, 24175, 24168, -1, 21910, 24176, 21908, -1, 24170, 24176, 24169, -1, 24173, 24176, 24170, -1, 24169, 24176, 17522, -1, 17522, 24176, 21910, -1, 21908, 24177, 21907, -1, 24165, 24178, 24166, -1, 21907, 24177, 21905, -1, 21905, 24177, 24174, -1, 24172, 24178, 24165, -1, 24162, 24177, 24173, -1, 24176, 24177, 21908, -1, 24173, 24177, 24176, -1, 24174, 24177, 24162, -1, 24157, 24179, 24175, -1, 24166, 24179, 24157, -1, 20373, 24180, 20387, -1, 21002, 21899, 24147, -1, 24168, 24180, 20373, -1, 21901, 24181, 21900, -1, 21900, 24181, 24171, -1, 24172, 24181, 24178, -1, 24171, 24181, 24172, -1, 24175, 24182, 24168, -1, 24168, 24182, 24180, -1, 24166, 24183, 24179, -1, 24178, 24183, 24166, -1, 20387, 24184, 20402, -1, 24180, 24184, 20387, -1, 24179, 24185, 24175, -1, 24175, 24185, 24182, -1, 24182, 24186, 24180, -1, 24180, 24186, 24184, -1, 20405, 17514, 17516, -1, 20402, 24187, 20403, -1, 24184, 24187, 20402, -1, 24178, 24188, 24183, -1, 21902, 24188, 21901, -1, 21901, 24188, 24181, -1, 24181, 24188, 24178, -1, 24179, 24161, 24185, -1, 24183, 24161, 24179, -1, 24185, 24189, 24182, -1, 24182, 24189, 24186, -1, 24186, 24155, 24184, -1, 21910, 17524, 17522, -1, 24152, 24156, 20378, -1, 24184, 24155, 24187, -1, 24187, 24190, 20403, -1, 20378, 24156, 20371, -1, 20403, 24190, 20405, -1, 20405, 24190, 17514, -1, 24161, 24163, 24185, -1, 24151, 24159, 24152, -1, 24150, 24159, 24151, -1, 24185, 24163, 24189, -1, 24152, 24159, 24156, -1, 24189, 24153, 24186, -1, 24149, 24165, 24150, -1, 24186, 24153, 24155, -1, 24150, 24165, 24159, -1, 24183, 24164, 24161, -1, 20371, 24158, 20369, -1, 21902, 24164, 24188, -1, 24188, 24164, 24183, -1, 24155, 24160, 24187, -1, 24187, 24160, 24190, -1, 24156, 24158, 20371, -1, 17514, 24160, 17517, -1, 24190, 24160, 17514, -1, 24148, 24172, 24149, -1, 24149, 24172, 24165, -1, 24163, 24170, 24189, -1, 24189, 24170, 24153, -1, 20520, 17515, 24191, -1, 24191, 17518, 24192, -1, 17515, 17518, 24191, -1, 24192, 17519, 24193, -1, 17518, 17519, 24192, -1, 24193, 17521, 24194, -1, 17519, 17521, 24193, -1, 24194, 17523, 20994, -1, 17521, 17523, 24194, -1, 17523, 17526, 20994, -1, 20994, 22196, 24194, -1, 20559, 24195, 20558, -1, 20559, 24196, 24195, -1, 22198, 24196, 20559, -1, 22198, 24197, 24196, -1, 22198, 24198, 24197, -1, 22198, 19186, 24198, -1, 20520, 24199, 20537, -1, 20537, 24199, 20559, -1, 24191, 24199, 20520, -1, 24192, 24200, 24191, -1, 24199, 24200, 20559, -1, 24191, 24200, 24199, -1, 24193, 24201, 24192, -1, 24200, 24201, 20559, -1, 24192, 24201, 24200, -1, 20559, 24201, 22198, -1, 22198, 24202, 22196, -1, 24194, 24202, 24193, -1, 24201, 24202, 22198, -1, 24193, 24202, 24201, -1, 22196, 24202, 24194, -1, 19265, 20558, 19264, -1, 19264, 24195, 19263, -1, 20558, 24195, 19264, -1, 19263, 24196, 19261, -1, 19261, 24196, 19262, -1, 24195, 24196, 19263, -1, 19262, 24197, 19494, -1, 24196, 24197, 19262, -1, 19494, 24198, 19490, -1, 24197, 24198, 19494, -1, 19490, 19186, 19188, -1, 24198, 19186, 19490, -1, 19760, 20485, 19764, -1, 19769, 24203, 19772, -1, 19764, 24203, 19769, -1, 20485, 24203, 19764, -1, 19766, 24204, 19767, -1, 19772, 24204, 19766, -1, 24203, 24204, 19772, -1, 19767, 24205, 24206, -1, 24204, 24205, 19767, -1, 24206, 24207, 24208, -1, 24205, 24207, 24206, -1, 24208, 19195, 19197, -1, 24207, 19195, 24208, -1, 20984, 22204, 24209, -1, 20496, 24203, 20485, -1, 20496, 24204, 24203, -1, 22206, 24204, 20496, -1, 22206, 24205, 24204, -1, 22206, 24207, 24205, -1, 22206, 19195, 24207, -1, 24210, 24211, 20464, -1, 20464, 24211, 20479, -1, 20479, 24211, 20496, -1, 24212, 24213, 24210, -1, 24210, 24213, 24211, -1, 24211, 24213, 20496, -1, 24214, 24215, 24212, -1, 24213, 24215, 20496, -1, 24212, 24215, 24213, -1, 20496, 24215, 22206, -1, 22206, 24216, 22204, -1, 24209, 24216, 24214, -1, 24215, 24216, 22206, -1, 24214, 24216, 24215, -1, 22204, 24216, 24209, -1, 20464, 17502, 24210, -1, 24210, 17505, 24212, -1, 17502, 17505, 24210, -1, 24212, 17507, 24214, -1, 17505, 17507, 24212, -1, 24214, 17508, 24209, -1, 17507, 17508, 24214, -1, 24209, 17510, 20984, -1, 17508, 17510, 24209, -1, 17510, 17513, 20984, -1, 24217, 24218, 24219, -1, 24220, 24221, 24222, -1, 17504, 24218, 17506, -1, 24223, 24221, 24220, -1, 24219, 24218, 24224, -1, 24224, 24218, 17504, -1, 24225, 24226, 24227, -1, 24228, 24229, 24223, -1, 24230, 24226, 24225, -1, 24223, 24229, 24221, -1, 21883, 24231, 21881, -1, 21881, 24231, 21880, -1, 21880, 24231, 24230, -1, 20541, 24232, 20546, -1, 24217, 24233, 24218, -1, 24234, 24233, 24217, -1, 24222, 24232, 20541, -1, 17506, 24233, 17509, -1, 24218, 24233, 17506, -1, 21878, 24235, 21877, -1, 24236, 24235, 24237, -1, 24227, 24238, 24234, -1, 24237, 24235, 24239, -1, 24226, 24238, 24227, -1, 21877, 24235, 24236, -1, 21883, 24240, 24231, -1, 24230, 24240, 24226, -1, 24221, 24241, 24222, -1, 24231, 24240, 24230, -1, 21888, 24242, 21886, -1, 24222, 24241, 24232, -1, 24234, 24242, 24233, -1, 24233, 24242, 17509, -1, 24238, 24242, 24234, -1, 17509, 24242, 21888, -1, 21886, 24243, 21885, -1, 24228, 24244, 24229, -1, 21885, 24243, 21883, -1, 24238, 24243, 24242, -1, 24239, 24244, 24228, -1, 21883, 24243, 24240, -1, 24226, 24243, 24238, -1, 24240, 24243, 24226, -1, 24242, 24243, 21886, -1, 24221, 24245, 24241, -1, 24229, 24245, 24221, -1, 20546, 24246, 20556, -1, 20992, 21877, 24236, -1, 24232, 24246, 20546, -1, 21879, 24247, 21878, -1, 21878, 24247, 24235, -1, 24239, 24247, 24244, -1, 24235, 24247, 24239, -1, 24241, 24248, 24232, -1, 24232, 24248, 24246, -1, 24229, 24249, 24245, -1, 24244, 24249, 24229, -1, 20556, 24250, 20562, -1, 24246, 24250, 20556, -1, 24245, 24251, 24241, -1, 24241, 24251, 24248, -1, 24248, 24252, 24246, -1, 20564, 17501, 17503, -1, 24246, 24252, 24250, -1, 20562, 24253, 20563, -1, 24250, 24253, 20562, -1, 24244, 24254, 24249, -1, 21880, 24254, 21879, -1, 21879, 24254, 24247, -1, 24247, 24254, 24244, -1, 24245, 24225, 24251, -1, 24249, 24225, 24245, -1, 24251, 24255, 24248, -1, 24248, 24255, 24252, -1, 24252, 24219, 24250, -1, 21888, 17511, 17509, -1, 24250, 24219, 24253, -1, 24256, 24220, 20550, -1, 20563, 24257, 20564, -1, 20550, 24220, 20543, -1, 24253, 24257, 20563, -1, 20564, 24257, 17501, -1, 24258, 24223, 24259, -1, 24251, 24227, 24255, -1, 24259, 24223, 24256, -1, 24225, 24227, 24251, -1, 24255, 24217, 24252, -1, 24256, 24223, 24220, -1, 24260, 24228, 24258, -1, 24252, 24217, 24219, -1, 24258, 24228, 24223, -1, 24249, 24230, 24225, -1, 21880, 24230, 24254, -1, 20543, 24222, 20541, -1, 24254, 24230, 24249, -1, 24253, 24224, 24257, -1, 24219, 24224, 24253, -1, 24220, 24222, 20543, -1, 17501, 24224, 17504, -1, 24257, 24224, 17501, -1, 24237, 24239, 24260, -1, 24260, 24239, 24228, -1, 24227, 24234, 24255, -1, 24255, 24234, 24217, -1, 20991, 20992, 24261, -1, 20992, 24236, 24261, -1, 24261, 24237, 24262, -1, 24236, 24237, 24261, -1, 24262, 24260, 24263, -1, 24237, 24260, 24262, -1, 24263, 24258, 24264, -1, 24260, 24258, 24263, -1, 24264, 24259, 24265, -1, 24258, 24259, 24264, -1, 24265, 24256, 24266, -1, 24259, 24256, 24265, -1, 24266, 20550, 20497, -1, 24256, 20550, 24266, -1, 24267, 24268, 24269, -1, 24270, 24268, 24267, -1, 24271, 24272, 24273, -1, 24269, 24272, 24271, -1, 24274, 24275, 24276, -1, 24276, 24275, 24277, -1, 24270, 24278, 24268, -1, 24277, 24278, 24270, -1, 20481, 24279, 20488, -1, 20488, 24279, 24266, -1, 24273, 24279, 20481, -1, 24268, 24280, 24269, -1, 24269, 24280, 24272, -1, 24281, 24282, 24274, -1, 24274, 24282, 24275, -1, 24266, 24283, 24265, -1, 24279, 24283, 24266, -1, 24272, 24283, 24273, -1, 24273, 24283, 24279, -1, 24275, 24284, 24277, -1, 24277, 24284, 24278, -1, 20488, 24266, 20497, -1, 24268, 24285, 24280, -1, 24278, 24285, 24268, -1, 20988, 21876, 24286, -1, 24265, 24287, 24264, -1, 24280, 24287, 24272, -1, 24283, 24287, 24265, -1, 24272, 24287, 24283, -1, 21874, 24288, 21876, -1, 24286, 24288, 24281, -1, 21876, 24288, 24286, -1, 24281, 24288, 24282, -1, 24275, 24289, 24284, -1, 24282, 24289, 24275, -1, 24284, 24290, 24278, -1, 24278, 24290, 24285, -1, 24280, 24291, 24287, -1, 24264, 24291, 24263, -1, 24287, 24291, 24264, -1, 24285, 24291, 24280, -1, 21872, 24292, 21874, -1, 24288, 24292, 24282, -1, 24282, 24292, 24289, -1, 21874, 24292, 24288, -1, 24289, 24293, 24284, -1, 24284, 24293, 24290, -1, 24285, 24294, 24291, -1, 24295, 24296, 20384, -1, 20384, 24296, 20501, -1, 24291, 24294, 24263, -1, 24290, 24294, 24285, -1, 21872, 24297, 24292, -1, 21869, 24297, 21872, -1, 24292, 24297, 24289, -1, 24298, 24267, 24295, -1, 24289, 24297, 24293, -1, 24263, 24299, 24262, -1, 24294, 24299, 24263, -1, 24295, 24267, 24296, -1, 24290, 24299, 24294, -1, 20501, 24271, 20493, -1, 24293, 24299, 24290, -1, 20493, 24271, 20484, -1, 20991, 24300, 21869, -1, 24261, 24300, 20991, -1, 24262, 24300, 24261, -1, 24296, 24271, 20501, -1, 24299, 24300, 24262, -1, 24297, 24300, 24293, -1, 24293, 24300, 24299, -1, 21869, 24300, 24297, -1, 24301, 24270, 24298, -1, 24298, 24270, 24267, -1, 24296, 24269, 24271, -1, 24267, 24269, 24296, -1, 20484, 24273, 20481, -1, 24271, 24273, 20484, -1, 24276, 24277, 24302, -1, 24302, 24277, 24301, -1, 24301, 24277, 24270, -1, 20988, 24286, 20986, -1, 20986, 24286, 24303, -1, 24303, 24281, 24304, -1, 24286, 24281, 24303, -1, 24304, 24274, 24305, -1, 24281, 24274, 24304, -1, 24305, 24276, 24306, -1, 24274, 24276, 24305, -1, 24306, 24302, 24307, -1, 24276, 24302, 24306, -1, 24307, 24301, 24308, -1, 24302, 24301, 24307, -1, 24308, 24298, 24309, -1, 24301, 24298, 24308, -1, 24309, 24295, 24310, -1, 24298, 24295, 24309, -1, 24310, 20384, 20380, -1, 24295, 20384, 24310, -1, 24303, 22208, 20986, -1, 22210, 19503, 19194, -1, 22210, 19506, 19503, -1, 20380, 20407, 24310, -1, 22210, 19509, 19506, -1, 20406, 19517, 19514, -1, 20406, 19519, 19517, -1, 20406, 19522, 19519, -1, 22208, 24311, 22210, -1, 24303, 24311, 22208, -1, 24304, 24312, 24303, -1, 24311, 24312, 22210, -1, 24303, 24312, 24311, -1, 24305, 24313, 24304, -1, 24312, 24313, 22210, -1, 24304, 24313, 24312, -1, 22210, 24313, 19509, -1, 19509, 24314, 19512, -1, 24306, 24314, 24305, -1, 24313, 24314, 19509, -1, 24305, 24314, 24313, -1, 19512, 24315, 19514, -1, 24307, 24315, 24306, -1, 24314, 24315, 19512, -1, 24306, 24315, 24314, -1, 24308, 24316, 24307, -1, 24315, 24316, 19514, -1, 24307, 24316, 24315, -1, 19514, 24316, 20406, -1, 24309, 24317, 24308, -1, 24308, 24317, 24316, -1, 24316, 24317, 20406, -1, 20406, 24318, 20407, -1, 24310, 24318, 24309, -1, 24317, 24318, 20406, -1, 20407, 24318, 24310, -1, 24309, 24318, 24317, -1, 19792, 20414, 19796, -1, 19801, 24319, 19804, -1, 19796, 24319, 19801, -1, 20414, 24319, 19796, -1, 19798, 24320, 19799, -1, 19804, 24320, 19798, -1, 24319, 24320, 19804, -1, 19799, 24321, 24322, -1, 24320, 24321, 19799, -1, 24322, 24323, 24324, -1, 24321, 24323, 24322, -1, 24324, 19204, 19206, -1, 24323, 19204, 24324, -1, 20974, 22212, 24325, -1, 20427, 24319, 20414, -1, 20427, 24320, 24319, -1, 22214, 24320, 20427, -1, 22214, 24321, 24320, -1, 22214, 24323, 24321, -1, 22214, 19204, 24323, -1, 24326, 24327, 20379, -1, 20379, 24327, 20408, -1, 20408, 24327, 20427, -1, 24328, 24329, 24326, -1, 24326, 24329, 24327, -1, 24327, 24329, 20427, -1, 24330, 24331, 24328, -1, 24329, 24331, 20427, -1, 24328, 24331, 24329, -1, 20427, 24331, 22214, -1, 22214, 24332, 22212, -1, 24325, 24332, 24330, -1, 24331, 24332, 22214, -1, 24330, 24332, 24331, -1, 22212, 24332, 24325, -1, 20379, 17489, 24326, -1, 17489, 17492, 24326, -1, 24326, 17494, 24328, -1, 17492, 17494, 24326, -1, 24328, 17495, 24330, -1, 17494, 17495, 24328, -1, 24330, 17497, 24325, -1, 17495, 17497, 24330, -1, 24325, 17500, 20974, -1, 17497, 17500, 24325, -1, 24333, 24334, 24335, -1, 24336, 24337, 24338, -1, 17491, 24334, 17493, -1, 24339, 24337, 24336, -1, 24335, 24334, 24340, -1, 24340, 24334, 17491, -1, 24341, 24342, 24343, -1, 24344, 24345, 24339, -1, 24346, 24342, 24341, -1, 24339, 24345, 24337, -1, 21861, 24347, 21859, -1, 21859, 24347, 21858, -1, 21858, 24347, 24346, -1, 20480, 24348, 20483, -1, 24333, 24349, 24334, -1, 24350, 24349, 24333, -1, 24338, 24348, 20480, -1, 24334, 24349, 17493, -1, 21856, 24351, 21855, -1, 24352, 24351, 24353, -1, 24343, 24354, 24350, -1, 24342, 24354, 24343, -1, 21855, 24351, 24352, -1, 24353, 24351, 24355, -1, 21861, 24356, 24347, -1, 24346, 24356, 24342, -1, 24337, 24357, 24338, -1, 24347, 24356, 24346, -1, 21866, 24358, 21864, -1, 17493, 24358, 17496, -1, 24338, 24357, 24348, -1, 24350, 24358, 24349, -1, 24349, 24358, 17493, -1, 24354, 24358, 24350, -1, 17496, 24358, 21866, -1, 21864, 24359, 21863, -1, 24344, 24360, 24345, -1, 21863, 24359, 21861, -1, 21861, 24359, 24356, -1, 24355, 24360, 24344, -1, 24342, 24359, 24354, -1, 24356, 24359, 24342, -1, 24354, 24359, 24358, -1, 24358, 24359, 21864, -1, 24337, 24361, 24357, -1, 24345, 24361, 24337, -1, 20982, 21855, 24352, -1, 20483, 24362, 20492, -1, 24348, 24362, 20483, -1, 21857, 24363, 21856, -1, 24351, 24363, 24355, -1, 21856, 24363, 24351, -1, 24355, 24363, 24360, -1, 24357, 24364, 24348, -1, 24348, 24364, 24362, -1, 24345, 24365, 24361, -1, 24360, 24365, 24345, -1, 20492, 24366, 20502, -1, 24362, 24366, 20492, -1, 24361, 24367, 24357, -1, 24357, 24367, 24364, -1, 24364, 24368, 24362, -1, 20504, 17488, 17490, -1, 24362, 24368, 24366, -1, 20502, 24369, 20503, -1, 24366, 24369, 20502, -1, 24360, 24370, 24365, -1, 21858, 24370, 21857, -1, 21857, 24370, 24363, -1, 24363, 24370, 24360, -1, 24361, 24341, 24367, -1, 24365, 24341, 24361, -1, 24367, 24371, 24364, -1, 24364, 24371, 24368, -1, 24368, 24335, 24366, -1, 21866, 17498, 17496, -1, 24366, 24335, 24369, -1, 24372, 24336, 20489, -1, 20489, 24336, 20482, -1, 20503, 24373, 20504, -1, 24369, 24373, 20503, -1, 20504, 24373, 17488, -1, 24374, 24339, 24372, -1, 24367, 24343, 24371, -1, 24341, 24343, 24367, -1, 24372, 24339, 24336, -1, 24371, 24333, 24368, -1, 24375, 24344, 24376, -1, 24376, 24344, 24374, -1, 24368, 24333, 24335, -1, 24374, 24344, 24339, -1, 24365, 24346, 24341, -1, 21858, 24346, 24370, -1, 20482, 24338, 20480, -1, 24370, 24346, 24365, -1, 24369, 24340, 24373, -1, 24335, 24340, 24369, -1, 24336, 24338, 20482, -1, 17488, 24340, 17491, -1, 24373, 24340, 17488, -1, 24353, 24355, 24375, -1, 24375, 24355, 24344, -1, 24343, 24350, 24371, -1, 24371, 24350, 24333, -1, 20981, 20982, 24377, -1, 20982, 24352, 24377, -1, 24377, 24353, 24378, -1, 24378, 24353, 24379, -1, 24352, 24353, 24377, -1, 24379, 24375, 24380, -1, 24353, 24375, 24379, -1, 24380, 24376, 24381, -1, 24375, 24376, 24380, -1, 24381, 24374, 24382, -1, 24376, 24374, 24381, -1, 24382, 24372, 20435, -1, 24374, 24372, 24382, -1, 24372, 20489, 20435, -1, 24383, 24384, 24385, -1, 24386, 24384, 24383, -1, 24387, 24388, 24389, -1, 24385, 24388, 24387, -1, 24390, 24391, 24392, -1, 24392, 24391, 24393, -1, 24386, 24394, 24384, -1, 24393, 24394, 24386, -1, 20419, 24395, 20426, -1, 20426, 24395, 24382, -1, 24389, 24395, 20419, -1, 24384, 24396, 24385, -1, 24385, 24396, 24388, -1, 24397, 24398, 24390, -1, 24390, 24398, 24391, -1, 24382, 24399, 24381, -1, 24395, 24399, 24382, -1, 24388, 24399, 24389, -1, 24389, 24399, 24395, -1, 24391, 24400, 24393, -1, 24393, 24400, 24394, -1, 24384, 24401, 24396, -1, 20426, 24382, 20435, -1, 24394, 24401, 24384, -1, 20978, 21854, 24402, -1, 24381, 24403, 24380, -1, 24396, 24403, 24388, -1, 24399, 24403, 24381, -1, 24388, 24403, 24399, -1, 21852, 24404, 21854, -1, 24402, 24404, 24397, -1, 21854, 24404, 24402, -1, 24397, 24404, 24398, -1, 24398, 24405, 24391, -1, 24391, 24405, 24400, -1, 24400, 24406, 24394, -1, 24394, 24406, 24401, -1, 24396, 24407, 24403, -1, 24380, 24407, 24379, -1, 24403, 24407, 24380, -1, 24401, 24407, 24396, -1, 21850, 24408, 21852, -1, 24404, 24408, 24398, -1, 24398, 24408, 24405, -1, 21852, 24408, 24404, -1, 24405, 24409, 24400, -1, 24400, 24409, 24406, -1, 24401, 24410, 24407, -1, 24411, 24412, 20440, -1, 20440, 24412, 20437, -1, 24406, 24410, 24401, -1, 24407, 24410, 24379, -1, 21850, 24413, 24408, -1, 21847, 24413, 21850, -1, 24408, 24413, 24405, -1, 24414, 24383, 24411, -1, 24405, 24413, 24409, -1, 24379, 24415, 24378, -1, 24411, 24383, 24412, -1, 24410, 24415, 24379, -1, 24406, 24415, 24410, -1, 20437, 24387, 20430, -1, 24409, 24415, 24406, -1, 20430, 24387, 20424, -1, 20981, 24416, 21847, -1, 24377, 24416, 20981, -1, 24378, 24416, 24377, -1, 24412, 24387, 20437, -1, 24415, 24416, 24378, -1, 24413, 24416, 24409, -1, 24409, 24416, 24415, -1, 21847, 24416, 24413, -1, 24417, 24386, 24414, -1, 24414, 24386, 24383, -1, 24412, 24385, 24387, -1, 24383, 24385, 24412, -1, 20424, 24389, 20419, -1, 24387, 24389, 20424, -1, 24392, 24393, 24418, -1, 24418, 24393, 24417, -1, 24417, 24393, 24386, -1, 20976, 20978, 24419, -1, 20978, 24402, 24419, -1, 24419, 24397, 24420, -1, 24402, 24397, 24419, -1, 24420, 24390, 24421, -1, 24397, 24390, 24420, -1, 24421, 24392, 24422, -1, 24390, 24392, 24421, -1, 24422, 24418, 24423, -1, 24392, 24418, 24422, -1, 24423, 24417, 24424, -1, 24418, 24417, 24423, -1, 24424, 24414, 24425, -1, 24417, 24414, 24424, -1, 24425, 24411, 24426, -1, 24414, 24411, 24425, -1, 24426, 20440, 20552, -1, 24411, 20440, 24426, -1, 24419, 22216, 20976, -1, 22218, 19531, 19203, -1, 22218, 19534, 19531, -1, 20552, 20566, 24426, -1, 22218, 19537, 19534, -1, 20565, 19545, 19542, -1, 20565, 19547, 19545, -1, 20565, 19550, 19547, -1, 22216, 24427, 22218, -1, 24419, 24427, 22216, -1, 24420, 24428, 24419, -1, 24427, 24428, 22218, -1, 24419, 24428, 24427, -1, 24421, 24429, 24420, -1, 24428, 24429, 22218, -1, 24420, 24429, 24428, -1, 22218, 24429, 19537, -1, 19537, 24430, 19540, -1, 24422, 24430, 24421, -1, 24429, 24430, 19537, -1, 24421, 24430, 24429, -1, 19540, 24431, 19542, -1, 24423, 24431, 24422, -1, 24430, 24431, 19540, -1, 24422, 24431, 24430, -1, 24424, 24432, 24423, -1, 24431, 24432, 19542, -1, 24423, 24432, 24431, -1, 19542, 24432, 20565, -1, 24425, 24433, 24424, -1, 24424, 24433, 24432, -1, 24432, 24433, 20565, -1, 20565, 24434, 20566, -1, 24426, 24434, 24425, -1, 24433, 24434, 20565, -1, 20566, 24434, 24426, -1, 24425, 24434, 24433, -1, 24435, 22135, 20252, -1, 22137, 19562, 19082, -1, 22137, 19565, 19562, -1, 20490, 20507, 24436, -1, 22137, 19568, 19565, -1, 20506, 19576, 19573, -1, 20506, 19578, 19576, -1, 20506, 19580, 19578, -1, 22135, 24437, 22137, -1, 24435, 24437, 22135, -1, 24438, 24439, 24435, -1, 24437, 24439, 22137, -1, 24435, 24439, 24437, -1, 24440, 24441, 24438, -1, 24439, 24441, 22137, -1, 24438, 24441, 24439, -1, 22137, 24441, 19568, -1, 24442, 24443, 24440, -1, 19568, 24443, 19571, -1, 24440, 24443, 24441, -1, 24441, 24443, 19568, -1, 24444, 24445, 24442, -1, 19571, 24445, 19573, -1, 24443, 24445, 19571, -1, 24442, 24445, 24443, -1, 24446, 24447, 24444, -1, 24444, 24447, 24445, -1, 24445, 24447, 19573, -1, 19573, 24447, 20506, -1, 24448, 24449, 24446, -1, 24447, 24449, 20506, -1, 24446, 24449, 24447, -1, 20506, 24450, 20507, -1, 24436, 24450, 24448, -1, 24449, 24450, 20506, -1, 24448, 24450, 24449, -1, 20507, 24450, 24436, -1, 20252, 20250, 24435, -1, 24435, 24451, 24438, -1, 20250, 24451, 24435, -1, 24438, 24452, 24440, -1, 24451, 24452, 24438, -1, 24440, 24453, 24442, -1, 24452, 24453, 24440, -1, 24442, 24454, 24444, -1, 24453, 24454, 24442, -1, 24444, 24455, 24446, -1, 24454, 24455, 24444, -1, 24446, 24456, 24448, -1, 24455, 24456, 24446, -1, 24448, 24457, 24436, -1, 24456, 24457, 24448, -1, 24436, 24458, 20490, -1, 24457, 24458, 24436, -1, 24458, 20395, 20490, -1, 24459, 24460, 24461, -1, 24461, 24460, 24462, -1, 24463, 24464, 24465, -1, 24462, 24464, 24463, -1, 24453, 24466, 24454, -1, 24454, 24466, 24467, -1, 24467, 24468, 24459, -1, 24459, 24468, 24460, -1, 20375, 24469, 20386, -1, 24465, 24469, 20375, -1, 20386, 24469, 24470, -1, 24460, 24471, 24462, -1, 24462, 24471, 24464, -1, 24452, 24472, 24453, -1, 24453, 24472, 24466, -1, 24470, 24473, 24474, -1, 24469, 24473, 24470, -1, 24464, 24473, 24465, -1, 24465, 24473, 24469, -1, 24467, 24475, 24468, -1, 24466, 24475, 24467, -1, 20386, 24470, 20391, -1, 24468, 24476, 24460, -1, 24460, 24476, 24471, -1, 20250, 21832, 24451, -1, 24474, 24477, 24478, -1, 24473, 24477, 24474, -1, 24471, 24477, 24464, -1, 24464, 24477, 24473, -1, 21830, 24479, 21832, -1, 24451, 24479, 24452, -1, 24452, 24479, 24472, -1, 21832, 24479, 24451, -1, 24472, 24480, 24466, -1, 24466, 24480, 24475, -1, 24475, 24481, 24468, -1, 24468, 24481, 24476, -1, 24471, 24482, 24477, -1, 24478, 24482, 24483, -1, 24477, 24482, 24478, -1, 24476, 24482, 24471, -1, 24479, 24484, 24472, -1, 21828, 24484, 21830, -1, 24472, 24484, 24480, -1, 21830, 24484, 24479, -1, 24480, 24485, 24475, -1, 24475, 24485, 24481, -1, 20395, 24486, 20393, -1, 24481, 24487, 24476, -1, 24476, 24487, 24482, -1, 24458, 24486, 20395, -1, 24482, 24487, 24483, -1, 21825, 24488, 21828, -1, 21828, 24488, 24484, -1, 24484, 24488, 24480, -1, 24457, 24461, 24458, -1, 24480, 24488, 24485, -1, 24483, 24489, 24490, -1, 24458, 24461, 24486, -1, 24487, 24489, 24483, -1, 24481, 24489, 24487, -1, 24485, 24489, 24481, -1, 20393, 24463, 20388, -1, 20388, 24463, 20381, -1, 24490, 24491, 24492, -1, 24486, 24463, 20393, -1, 24492, 24491, 20970, -1, 20970, 24491, 21825, -1, 24489, 24491, 24490, -1, 24488, 24491, 24485, -1, 24485, 24491, 24489, -1, 24456, 24459, 24457, -1, 21825, 24491, 24488, -1, 24457, 24459, 24461, -1, 24486, 24462, 24463, -1, 24461, 24462, 24486, -1, 20381, 24465, 20375, -1, 24463, 24465, 20381, -1, 24455, 24467, 24456, -1, 24454, 24467, 24455, -1, 24456, 24467, 24459, -1, 20970, 20971, 24492, -1, 24492, 24493, 24490, -1, 20971, 24493, 24492, -1, 24490, 24494, 24483, -1, 24493, 24494, 24490, -1, 24483, 24495, 24478, -1, 24494, 24495, 24483, -1, 24478, 24496, 24474, -1, 24495, 24496, 24478, -1, 24474, 24497, 24470, -1, 24496, 24497, 24474, -1, 24470, 24498, 20391, -1, 24497, 24498, 24470, -1, 24498, 20404, 20391, -1, 24499, 24500, 24501, -1, 24502, 24503, 24504, -1, 24505, 24506, 24507, -1, 17478, 24503, 17481, -1, 24507, 24506, 24508, -1, 24504, 24503, 24509, -1, 24509, 24503, 17478, -1, 24510, 24511, 24499, -1, 24512, 24513, 24505, -1, 24514, 24511, 24510, -1, 24505, 24513, 24506, -1, 21839, 24515, 21837, -1, 21837, 24515, 21836, -1, 21836, 24515, 24514, -1, 20418, 24516, 20425, -1, 24502, 24517, 24503, -1, 24508, 24516, 20418, -1, 24500, 24517, 24502, -1, 24503, 24517, 17481, -1, 21834, 24518, 21833, -1, 24493, 24518, 24494, -1, 24494, 24518, 24519, -1, 24499, 24520, 24500, -1, 21833, 24518, 24493, -1, 24511, 24520, 24499, -1, 21839, 24521, 24515, -1, 24514, 24521, 24511, -1, 24508, 24522, 24516, -1, 24515, 24521, 24514, -1, 21844, 24523, 21842, -1, 24506, 24522, 24508, -1, 17481, 24523, 17483, -1, 24500, 24523, 24517, -1, 24520, 24523, 24500, -1, 24517, 24523, 17481, -1, 17483, 24523, 21844, -1, 21842, 24524, 21841, -1, 21841, 24524, 21839, -1, 24512, 24525, 24513, -1, 24523, 24524, 21842, -1, 24519, 24525, 24512, -1, 24511, 24524, 24520, -1, 24521, 24524, 24511, -1, 24520, 24524, 24523, -1, 21839, 24524, 24521, -1, 24506, 24526, 24522, -1, 24513, 24526, 24506, -1, 20425, 24527, 20431, -1, 20971, 21833, 24493, -1, 24516, 24527, 20425, -1, 21835, 24528, 21834, -1, 21834, 24528, 24518, -1, 24518, 24528, 24519, -1, 24519, 24528, 24525, -1, 24522, 24529, 24516, -1, 24516, 24529, 24527, -1, 24525, 24530, 24513, -1, 24513, 24530, 24526, -1, 20431, 24531, 20442, -1, 24527, 24531, 20431, -1, 24526, 24532, 24522, -1, 24522, 24532, 24529, -1, 24529, 24533, 24527, -1, 20444, 17475, 17477, -1, 24527, 24533, 24531, -1, 20442, 24534, 20443, -1, 24531, 24534, 20442, -1, 21836, 24535, 21835, -1, 24525, 24535, 24530, -1, 21835, 24535, 24528, -1, 24528, 24535, 24525, -1, 24530, 24510, 24526, -1, 24526, 24510, 24532, -1, 24529, 24501, 24533, -1, 24532, 24501, 24529, -1, 24533, 24504, 24531, -1, 21844, 17485, 17483, -1, 24498, 24507, 20404, -1, 24531, 24504, 24534, -1, 24534, 24536, 20443, -1, 20404, 24507, 20420, -1, 20443, 24536, 20444, -1, 20444, 24536, 17475, -1, 24497, 24505, 24498, -1, 24532, 24499, 24501, -1, 24510, 24499, 24532, -1, 24498, 24505, 24507, -1, 24501, 24502, 24533, -1, 24533, 24502, 24504, -1, 24496, 24512, 24497, -1, 24495, 24512, 24496, -1, 24497, 24512, 24505, -1, 24535, 24514, 24530, -1, 20420, 24508, 20418, -1, 24530, 24514, 24510, -1, 21836, 24514, 24535, -1, 24504, 24509, 24534, -1, 24507, 24508, 20420, -1, 24534, 24509, 24536, -1, 17475, 24509, 17478, -1, 24536, 24509, 17475, -1, 24494, 24519, 24495, -1, 24495, 24519, 24512, -1, 24501, 24500, 24502, -1, 20551, 17476, 24537, -1, 24537, 17479, 24538, -1, 17476, 17479, 24537, -1, 24538, 17480, 24539, -1, 17479, 17480, 24538, -1, 24539, 17482, 24540, -1, 17480, 17482, 24539, -1, 24540, 17484, 20968, -1, 17482, 17484, 24540, -1, 17484, 17487, 20968, -1, 20968, 22200, 24540, -1, 20355, 24541, 20342, -1, 20355, 24542, 24541, -1, 22202, 24542, 20355, -1, 22202, 24543, 24542, -1, 22202, 24544, 24543, -1, 22202, 19209, 24544, -1, 20551, 24545, 20561, -1, 20561, 24545, 20355, -1, 24537, 24545, 20551, -1, 24538, 24546, 24537, -1, 24545, 24546, 20355, -1, 24537, 24546, 24545, -1, 24539, 24547, 24538, -1, 24546, 24547, 20355, -1, 24538, 24547, 24546, -1, 20355, 24547, 22202, -1, 22202, 24548, 22200, -1, 24540, 24548, 24539, -1, 24547, 24548, 22202, -1, 24539, 24548, 24547, -1, 22200, 24548, 24540, -1, 19824, 20342, 19828, -1, 19833, 24541, 19836, -1, 19828, 24541, 19833, -1, 20342, 24541, 19828, -1, 19830, 24542, 19831, -1, 19836, 24542, 19830, -1, 24541, 24542, 19836, -1, 19831, 24543, 24549, -1, 24542, 24543, 19831, -1, 24549, 24544, 24550, -1, 24543, 24544, 24549, -1, 24550, 19209, 19211, -1, 24544, 19209, 24550, -1, 19885, 20521, 19889, -1, 19894, 24551, 19897, -1, 19889, 24551, 19894, -1, 20521, 24551, 19889, -1, 19891, 24552, 19892, -1, 19897, 24552, 19891, -1, 24551, 24552, 19897, -1, 19892, 24553, 24554, -1, 24552, 24553, 19892, -1, 24554, 24555, 24556, -1, 24553, 24555, 24554, -1, 24556, 19072, 19074, -1, 24555, 19072, 24556, -1, 20239, 22139, 24557, -1, 20530, 24551, 20521, -1, 20530, 24552, 24551, -1, 22141, 24552, 20530, -1, 22141, 24553, 24552, -1, 22141, 24555, 24553, -1, 22141, 19072, 24555, -1, 24558, 24559, 20491, -1, 20491, 24559, 20508, -1, 20508, 24559, 20530, -1, 24560, 24561, 24558, -1, 24558, 24561, 24559, -1, 24559, 24561, 20530, -1, 24562, 24563, 24560, -1, 24561, 24563, 20530, -1, 24560, 24563, 24561, -1, 20530, 24563, 22141, -1, 22141, 24564, 22139, -1, 24557, 24564, 24562, -1, 24563, 24564, 22141, -1, 24562, 24564, 24563, -1, 22139, 24564, 24557, -1, 20400, 24565, 20491, -1, 20491, 24565, 24558, -1, 24560, 24566, 24562, -1, 24558, 24566, 24560, -1, 24565, 24566, 24558, -1, 24562, 24567, 24557, -1, 24566, 24567, 24562, -1, 24557, 24568, 20239, -1, 24567, 24568, 24557, -1, 24568, 20237, 20239, -1, 24569, 24570, 24571, -1, 20397, 24572, 20398, -1, 24571, 24570, 24573, -1, 24574, 24572, 20397, -1, 24575, 24576, 24577, -1, 24578, 24579, 20374, -1, 24577, 24576, 24580, -1, 21818, 24576, 24575, -1, 24578, 24581, 24579, -1, 24573, 24581, 24578, -1, 24582, 24583, 24584, -1, 24584, 24583, 24585, -1, 24586, 24587, 24588, -1, 24585, 24589, 24574, -1, 24588, 24587, 24570, -1, 24574, 24589, 24572, -1, 24573, 24590, 24581, -1, 24580, 24591, 24592, -1, 24570, 24590, 24573, -1, 20374, 24593, 20382, -1, 24592, 24591, 24582, -1, 20382, 24593, 20389, -1, 20398, 24594, 20399, -1, 24572, 24594, 20398, -1, 24579, 24593, 20374, -1, 20399, 24594, 24565, -1, 24586, 24595, 24587, -1, 21816, 24596, 21818, -1, 21818, 24596, 24576, -1, 24576, 24596, 21816, -1, 24597, 24595, 24586, -1, 24583, 24598, 24585, -1, 24585, 24598, 24589, -1, 24581, 24599, 24579, -1, 24565, 24600, 24566, -1, 24579, 24599, 24593, -1, 24589, 24600, 24572, -1, 24594, 24600, 24565, -1, 24572, 24600, 24594, -1, 24570, 24601, 24590, -1, 24587, 24601, 24570, -1, 24582, 24602, 24583, -1, 21821, 24603, 21822, -1, 17474, 21822, 17471, -1, 24591, 24602, 24582, -1, 17467, 24603, 24597, -1, 17471, 21822, 17469, -1, 17469, 21822, 17467, -1, 24597, 24603, 24595, -1, 21822, 24603, 17467, -1, 21816, 24604, 24576, -1, 24576, 24604, 24580, -1, 24580, 24604, 24591, -1, 24590, 24605, 24581, -1, 24566, 24606, 24567, -1, 24581, 24605, 24599, -1, 24598, 24606, 24589, -1, 24600, 24606, 24566, -1, 24589, 24606, 24600, -1, 24593, 24607, 20389, -1, 24583, 24608, 24598, -1, 24602, 24608, 24583, -1, 21814, 24609, 21816, -1, 24587, 24610, 24601, -1, 24595, 24610, 24587, -1, 21816, 24609, 24604, -1, 24591, 24611, 24602, -1, 24604, 24611, 24591, -1, 24593, 24612, 24607, -1, 24599, 24612, 24593, -1, 24606, 24613, 24567, -1, 24598, 24613, 24606, -1, 24608, 24613, 24598, -1, 24590, 24577, 24605, -1, 21811, 24614, 21813, -1, 21813, 24614, 21814, -1, 24601, 24577, 24590, -1, 21814, 24614, 24609, -1, 21821, 24615, 24603, -1, 24609, 24614, 24604, -1, 21819, 24615, 21821, -1, 24604, 24614, 24611, -1, 24603, 24615, 24595, -1, 24595, 24615, 24610, -1, 24602, 24616, 24608, -1, 24611, 24616, 24602, -1, 20389, 24617, 20396, -1, 24611, 24618, 24616, -1, 21809, 24618, 21811, -1, 21811, 24618, 24614, -1, 24607, 24617, 20389, -1, 24614, 24618, 24611, -1, 20399, 24565, 20400, -1, 24605, 24592, 24599, -1, 24568, 24619, 21807, -1, 24567, 24619, 24568, -1, 24608, 24619, 24613, -1, 24613, 24619, 24567, -1, 24616, 24619, 24608, -1, 21809, 24620, 24618, -1, 21807, 24620, 21809, -1, 24599, 24592, 24612, -1, 24616, 24620, 24619, -1, 24619, 24620, 21807, -1, 24618, 24620, 24616, -1, 24610, 24575, 24601, -1, 24601, 24575, 24577, -1, 24607, 24584, 24617, -1, 24612, 24584, 24607, -1, 20396, 24574, 20397, -1, 24617, 24574, 20396, -1, 24577, 24580, 24605, -1, 24605, 24580, 24592, -1, 21807, 20237, 24568, -1, 21818, 24621, 21819, -1, 24610, 24621, 24575, -1, 21819, 24621, 24615, -1, 24622, 24578, 20361, -1, 24615, 24621, 24610, -1, 20361, 24578, 20376, -1, 24575, 24621, 21818, -1, 20376, 24578, 20374, -1, 24592, 24582, 24612, -1, 24571, 24573, 24622, -1, 24612, 24582, 24584, -1, 24584, 24585, 24617, -1, 24617, 24585, 24574, -1, 24622, 24573, 24578, -1, 24588, 24570, 24569, -1, 20361, 20353, 24622, -1, 24622, 24623, 24571, -1, 20353, 24623, 24622, -1, 24571, 24624, 24569, -1, 24623, 24624, 24571, -1, 24569, 24625, 24588, -1, 24624, 24625, 24569, -1, 24588, 24626, 24586, -1, 24625, 24626, 24588, -1, 24586, 24627, 24597, -1, 24626, 24627, 24586, -1, 24597, 24628, 17467, -1, 24627, 24628, 24597, -1, 24628, 17468, 17467, -1, 24629, 24630, 24631, -1, 24632, 24633, 20348, -1, 21804, 24634, 21802, -1, 21802, 24634, 24635, -1, 24628, 24636, 17468, -1, 17468, 24636, 17470, -1, 24637, 24638, 24639, -1, 24630, 24636, 24628, -1, 24635, 24636, 24640, -1, 24639, 24638, 24641, -1, 24640, 24636, 24630, -1, 17473, 24642, 21804, -1, 17472, 24642, 17473, -1, 17470, 24642, 17472, -1, 24641, 24643, 24644, -1, 24636, 24642, 17470, -1, 21804, 24642, 24634, -1, 24634, 24642, 24635, -1, 24644, 24643, 24645, -1, 24635, 24642, 24636, -1, 24645, 24646, 24632, -1, 24632, 24646, 24633, -1, 24647, 24648, 24649, -1, 24649, 24648, 24637, -1, 24637, 24648, 24638, -1, 24641, 24650, 24643, -1, 24638, 24650, 24641, -1, 20349, 24651, 20351, -1, 24633, 24651, 20349, -1, 20351, 24651, 24623, -1, 24643, 24652, 24645, -1, 24645, 24652, 24646, -1, 24653, 24654, 24647, -1, 24647, 24654, 24648, -1, 20351, 24623, 20353, -1, 24648, 24655, 24638, -1, 24638, 24655, 24650, -1, 24623, 24656, 24624, -1, 24633, 24656, 24651, -1, 24651, 24656, 24623, -1, 24646, 24656, 24633, -1, 24643, 24657, 24652, -1, 24650, 24657, 24643, -1, 24658, 24659, 24653, -1, 24653, 24659, 24654, -1, 24654, 24660, 24648, -1, 24648, 24660, 24655, -1, 24646, 24661, 24656, -1, 24624, 24661, 24625, -1, 24656, 24661, 24624, -1, 24652, 24661, 24646, -1, 24655, 24662, 24650, -1, 24650, 24662, 24657, -1, 24661, 24663, 24625, -1, 24652, 24663, 24661, -1, 24625, 24663, 24626, -1, 24657, 24663, 24652, -1, 21798, 24664, 20963, -1, 20963, 24664, 24658, -1, 24658, 24664, 24659, -1, 24659, 24665, 24654, -1, 24654, 24665, 24660, -1, 24666, 24667, 20360, -1, 24655, 24629, 24662, -1, 20360, 24667, 20354, -1, 24660, 24629, 24655, -1, 21800, 24668, 21798, -1, 24669, 24644, 24666, -1, 24664, 24668, 21800, -1, 21798, 24668, 24664, -1, 24663, 24670, 24626, -1, 24666, 24644, 24667, -1, 24657, 24670, 24663, -1, 24626, 24670, 24627, -1, 20354, 24632, 20352, -1, 20352, 24632, 20348, -1, 24662, 24670, 24657, -1, 21802, 24671, 21800, -1, 24664, 24671, 24659, -1, 24667, 24632, 20354, -1, 21800, 24671, 24664, -1, 24659, 24671, 24665, -1, 24660, 24640, 24629, -1, 24665, 24640, 24660, -1, 24639, 24641, 24669, -1, 24669, 24641, 24644, -1, 24629, 24631, 24662, -1, 24627, 24631, 24628, -1, 24662, 24631, 24670, -1, 24670, 24631, 24627, -1, 24665, 24635, 24640, -1, 24671, 24635, 24665, -1, 21802, 24635, 24671, -1, 24644, 24645, 24667, -1, 24631, 24630, 24628, -1, 24667, 24645, 24632, -1, 24640, 24630, 24629, -1, 20348, 24633, 20349, -1, 20961, 20963, 24672, -1, 24672, 24658, 24673, -1, 20963, 24658, 24672, -1, 24673, 24653, 24674, -1, 24658, 24653, 24673, -1, 24674, 24647, 24675, -1, 24653, 24647, 24674, -1, 24675, 24649, 24676, -1, 24647, 24649, 24675, -1, 24676, 24637, 24677, -1, 24649, 24637, 24676, -1, 24677, 24639, 24678, -1, 24637, 24639, 24677, -1, 24678, 24669, 24679, -1, 24639, 24669, 24678, -1, 24679, 24666, 20429, -1, 24669, 24666, 24679, -1, 24666, 20360, 20429, -1, 24672, 22220, 20961, -1, 22222, 19595, 19136, -1, 22222, 19598, 19595, -1, 20429, 20446, 24679, -1, 22222, 19601, 19598, -1, 20445, 19609, 19606, -1, 20445, 19611, 19609, -1, 20445, 19614, 19611, -1, 22220, 24680, 22222, -1, 24672, 24680, 22220, -1, 24673, 24681, 24672, -1, 24680, 24681, 22222, -1, 24672, 24681, 24680, -1, 24674, 24682, 24673, -1, 24681, 24682, 22222, -1, 24673, 24682, 24681, -1, 22222, 24682, 19601, -1, 19601, 24683, 19604, -1, 24675, 24683, 24674, -1, 24682, 24683, 19601, -1, 24674, 24683, 24682, -1, 19604, 24684, 19606, -1, 24676, 24684, 24675, -1, 24683, 24684, 19604, -1, 24675, 24684, 24683, -1, 24677, 24685, 24676, -1, 24684, 24685, 19606, -1, 24676, 24685, 24684, -1, 19606, 24685, 20445, -1, 24678, 24686, 24677, -1, 24677, 24686, 24685, -1, 24685, 24686, 20445, -1, 20445, 24687, 20446, -1, 24679, 24687, 24678, -1, 24686, 24687, 20445, -1, 20446, 24687, 24679, -1, 24678, 24687, 24686, -1, 24688, 22143, 21054, -1, 20539, 20545, 24689, -1, 22145, 19617, 19132, -1, 22145, 19620, 19617, -1, 20544, 19633, 19630, -1, 20544, 19634, 19633, -1, 22143, 24690, 22145, -1, 24688, 24690, 22143, -1, 24691, 24692, 24688, -1, 24690, 24692, 22145, -1, 24688, 24692, 24690, -1, 24693, 24694, 24691, -1, 24691, 24694, 24692, -1, 24695, 24696, 24693, -1, 24693, 24696, 24694, -1, 24697, 24698, 24695, -1, 24695, 24698, 24696, -1, 24699, 24700, 24697, -1, 24697, 24700, 24698, -1, 24701, 24702, 24699, -1, 24699, 24702, 24700, -1, 20544, 24703, 20545, -1, 24689, 24703, 24701, -1, 24702, 24703, 20544, -1, 20545, 24703, 24689, -1, 24701, 24703, 24702, -1, 19628, 24704, 19630, -1, 19626, 24704, 19628, -1, 19623, 24704, 19626, -1, 19620, 24704, 19623, -1, 24700, 24704, 24698, -1, 20544, 24704, 24702, -1, 24698, 24704, 24696, -1, 24702, 24704, 24700, -1, 24694, 24704, 24692, -1, 24692, 24704, 22145, -1, 22145, 24704, 19620, -1, 24696, 24704, 24694, -1, 19630, 24704, 20544, -1, 20655, 20654, 21054, -1, 21054, 20654, 24688, -1, 24688, 20653, 24691, -1, 20654, 20653, 24688, -1, 20653, 20652, 24691, -1, 24691, 20650, 24693, -1, 20652, 20650, 24691, -1, 24693, 20648, 24695, -1, 20650, 20648, 24693, -1, 24695, 20645, 24697, -1, 20648, 20645, 24695, -1, 24697, 20643, 24699, -1, 20645, 20643, 24697, -1, 24699, 20640, 24701, -1, 20643, 20640, 24699, -1, 24701, 20642, 24689, -1, 20640, 20642, 24701, -1, 24689, 20540, 20539, -1, 20642, 20540, 24689, -1, 23856, 19152, 19407, -1, 19411, 23856, 19407, -1, 23855, 23856, 19411, -1, 19662, 19411, 19305, -1, 19662, 23855, 19411, -1, 19649, 23855, 19662, -1, 19651, 23855, 19649, -1, 23545, 19161, 19335, -1, 19339, 23545, 19335, -1, 23544, 23545, 19339, -1, 19691, 19339, 19300, -1, 19691, 23544, 19339, -1, 19678, 23544, 19691, -1, 19680, 23544, 19678, -1, 23972, 19170, 19434, -1, 19438, 23972, 19434, -1, 23971, 23972, 19438, -1, 19720, 19438, 19295, -1, 19720, 23971, 19438, -1, 19707, 23971, 19720, -1, 19709, 23971, 19707, -1, 24088, 19179, 19463, -1, 24087, 19463, 19467, -1, 24087, 24088, 19463, -1, 19749, 19467, 19290, -1, 19749, 24087, 19467, -1, 19736, 24087, 19749, -1, 19738, 24087, 19736, -1, 24206, 19765, 19767, -1, 19500, 19270, 19778, -1, 19500, 19778, 19765, -1, 19500, 19765, 24206, -1, 24208, 19500, 24206, -1, 19496, 19500, 24208, -1, 19197, 19496, 24208, -1, 24322, 19810, 19797, -1, 24322, 19797, 19799, -1, 19528, 19275, 19810, -1, 19528, 19810, 24322, -1, 24324, 19528, 24322, -1, 19524, 19528, 24324, -1, 19206, 19524, 24324, -1, 24550, 19211, 19582, -1, 24549, 19582, 19586, -1, 24549, 24550, 19582, -1, 19842, 19586, 19280, -1, 19842, 24549, 19586, -1, 19829, 24549, 19842, -1, 19831, 24549, 19829, -1, 23428, 19256, 19861, -1, 23428, 19861, 19862, -1, 23428, 19862, 19873, -1, 19101, 19557, 23429, -1, 19560, 23428, 23429, -1, 19560, 19256, 23428, -1, 19560, 23429, 19557, -1, 24554, 19890, 19892, -1, 19592, 19285, 19903, -1, 19592, 19903, 19890, -1, 19592, 19890, 24554, -1, 24556, 19592, 24554, -1, 19588, 19592, 24556, -1, 19074, 19588, 24556, -1, 19205, 22215, 19905, -1, 18995, 17464, 17466, -1, 18995, 17462, 17464, -1, 22213, 24705, 24706, -1, 22213, 20975, 24705, -1, 18748, 24707, 18994, -1, 18994, 24707, 18995, -1, 18746, 24707, 18748, -1, 18744, 24708, 18746, -1, 24707, 24708, 18995, -1, 18746, 24708, 24707, -1, 18742, 24709, 18744, -1, 18744, 24709, 24708, -1, 18740, 24710, 18742, -1, 18742, 24710, 24709, -1, 18738, 24711, 18740, -1, 18740, 24711, 24710, -1, 19908, 24712, 18738, -1, 18738, 24712, 24711, -1, 22213, 24713, 22215, -1, 19905, 24713, 19908, -1, 19908, 24713, 24712, -1, 22215, 24713, 19905, -1, 24712, 24713, 22213, -1, 17462, 24714, 17460, -1, 17460, 24714, 17458, -1, 17458, 24714, 17457, -1, 17457, 24714, 24706, -1, 24708, 24714, 18995, -1, 24709, 24714, 24708, -1, 24712, 24714, 24711, -1, 24710, 24714, 24709, -1, 22213, 24714, 24712, -1, 24711, 24714, 24710, -1, 18995, 24714, 17462, -1, 24706, 24714, 22213, -1, 20975, 20973, 24705, -1, 24705, 24715, 24706, -1, 20973, 24715, 24705, -1, 24706, 24716, 17457, -1, 24715, 24716, 24706, -1, 24716, 17455, 17457, -1, 17444, 24717, 17448, -1, 24718, 24717, 24719, -1, 24719, 24717, 17444, -1, 24720, 24717, 24718, -1, 17455, 24721, 17456, -1, 17456, 24721, 24722, -1, 24722, 24723, 24724, -1, 24724, 24723, 24725, -1, 17448, 24726, 17452, -1, 24720, 24726, 24717, -1, 24717, 24726, 17448, -1, 24725, 24726, 24720, -1, 24716, 24727, 17455, -1, 17455, 24727, 24721, -1, 24722, 24728, 24723, -1, 24721, 24728, 24722, -1, 21865, 24729, 21867, -1, 24715, 24729, 24716, -1, 24716, 24729, 24727, -1, 21867, 24729, 24715, -1, 17452, 24730, 17454, -1, 24726, 24730, 17452, -1, 24723, 24730, 24725, -1, 19037, 17444, 17446, -1, 24725, 24730, 24726, -1, 24727, 24731, 24721, -1, 24721, 24731, 24728, -1, 17454, 24732, 17428, -1, 24730, 24732, 17454, -1, 24728, 24732, 24723, -1, 24723, 24732, 24730, -1, 20973, 21867, 24715, -1, 21862, 24733, 21865, -1, 21865, 24733, 24729, -1, 24729, 24733, 24727, -1, 24727, 24733, 24731, -1, 17428, 24734, 17427, -1, 24732, 24734, 17428, -1, 24731, 24734, 24728, -1, 24728, 24734, 24732, -1, 21860, 24735, 21862, -1, 24731, 24735, 24734, -1, 21862, 24735, 24733, -1, 17427, 24735, 21860, -1, 24733, 24735, 24731, -1, 24734, 24735, 17427, -1, 21860, 17442, 17427, -1, 17463, 24736, 17465, -1, 17465, 24736, 19048, -1, 17461, 24737, 17463, -1, 17463, 24737, 24736, -1, 19048, 24718, 19041, -1, 19041, 24718, 19036, -1, 24736, 24718, 19048, -1, 17459, 24724, 17461, -1, 17461, 24724, 24737, -1, 24736, 24720, 24718, -1, 24737, 24720, 24736, -1, 19036, 24719, 19037, -1, 24718, 24719, 19036, -1, 19037, 24719, 17444, -1, 17456, 24722, 17459, -1, 17459, 24722, 24724, -1, 24724, 24725, 24737, -1, 24737, 24725, 24720, -1, 17443, 20980, 17440, -1, 17440, 24738, 17435, -1, 20980, 24738, 17440, -1, 17435, 24739, 17432, -1, 24738, 24739, 17435, -1, 17432, 24740, 17420, -1, 24739, 24740, 17432, -1, 17420, 24741, 17418, -1, 24740, 24741, 17420, -1, 17418, 24742, 17437, -1, 24741, 24742, 17418, -1, 17437, 24743, 17438, -1, 24742, 24743, 17437, -1, 24743, 18842, 17438, -1, 24744, 24745, 18830, -1, 24739, 24746, 24740, -1, 24740, 24746, 24747, -1, 24747, 24748, 24749, -1, 24749, 24748, 24750, -1, 24751, 24752, 24744, -1, 24744, 24752, 24745, -1, 19065, 24753, 19063, -1, 19063, 24753, 18834, -1, 18834, 24753, 24754, -1, 24745, 24753, 19065, -1, 21846, 24755, 20980, -1, 24738, 24755, 24739, -1, 20980, 24755, 24738, -1, 24739, 24755, 24746, -1, 24746, 24756, 24747, -1, 24747, 24756, 24748, -1, 24750, 24757, 24751, -1, 24751, 24757, 24752, -1, 24754, 24758, 24759, -1, 24753, 24758, 24754, -1, 24752, 24758, 24745, -1, 24745, 24758, 24753, -1, 21849, 24760, 21848, -1, 21848, 24760, 21846, -1, 21846, 24760, 24755, -1, 24755, 24760, 24746, -1, 24746, 24760, 24756, -1, 24748, 24761, 24750, -1, 24750, 24761, 24757, -1, 24759, 24762, 24763, -1, 24758, 24762, 24759, -1, 24757, 24762, 24752, -1, 24752, 24762, 24758, -1, 24756, 24764, 24748, -1, 24748, 24764, 24761, -1, 24761, 24765, 24757, -1, 24763, 24765, 24766, -1, 24762, 24765, 24763, -1, 24757, 24765, 24762, -1, 21853, 24767, 21851, -1, 21851, 24767, 21849, -1, 24756, 24767, 24764, -1, 21849, 24767, 24760, -1, 24760, 24767, 24756, -1, 24764, 24768, 24761, -1, 24765, 24768, 24766, -1, 24766, 24768, 24769, -1, 21853, 20977, 24770, -1, 24761, 24768, 24765, -1, 18842, 24771, 18840, -1, 24764, 24772, 24768, -1, 18840, 24771, 18831, -1, 24769, 24772, 24770, -1, 24767, 24772, 24764, -1, 21853, 24772, 24767, -1, 24743, 24771, 18842, -1, 24770, 24772, 21853, -1, 24768, 24772, 24769, -1, 24742, 24773, 24743, -1, 24743, 24773, 24771, -1, 18831, 24744, 18830, -1, 24771, 24744, 18831, -1, 24741, 24749, 24742, -1, 24742, 24749, 24773, -1, 24771, 24751, 24744, -1, 24773, 24751, 24771, -1, 24740, 24747, 24741, -1, 24741, 24747, 24749, -1, 24749, 24750, 24773, -1, 24773, 24750, 24751, -1, 18830, 24745, 19065, -1, 18853, 18834, 24774, -1, 24774, 24754, 24775, -1, 18834, 24754, 24774, -1, 24775, 24759, 24776, -1, 24754, 24759, 24775, -1, 24776, 24763, 24777, -1, 24759, 24763, 24776, -1, 24777, 24766, 24778, -1, 24763, 24766, 24777, -1, 24778, 24769, 24779, -1, 24766, 24769, 24778, -1, 24779, 24770, 20979, -1, 24769, 24770, 24779, -1, 24770, 20977, 20979, -1, 22217, 24779, 20979, -1, 18857, 18856, 19919, -1, 22217, 24778, 24779, -1, 22217, 24777, 24778, -1, 18855, 24775, 24776, -1, 18855, 24774, 24775, -1, 18855, 18853, 24774, -1, 19910, 24780, 19201, -1, 19201, 24780, 22219, -1, 22219, 24780, 22217, -1, 19912, 24781, 19910, -1, 24780, 24781, 22217, -1, 19910, 24781, 24780, -1, 19914, 24782, 19912, -1, 24781, 24782, 22217, -1, 19912, 24782, 24781, -1, 22217, 24782, 24777, -1, 19916, 24783, 19914, -1, 24777, 24783, 24776, -1, 24782, 24783, 24777, -1, 19914, 24783, 24782, -1, 24776, 24783, 18855, -1, 19917, 24784, 19916, -1, 24783, 24784, 18855, -1, 19916, 24784, 24783, -1, 18855, 24785, 18856, -1, 19919, 24785, 19917, -1, 19917, 24785, 24784, -1, 24784, 24785, 18855, -1, 18856, 24785, 19919, -1, 19196, 22207, 19923, -1, 18988, 17411, 17413, -1, 18988, 17409, 17411, -1, 22205, 24786, 24787, -1, 22205, 20985, 24786, -1, 18735, 24788, 18987, -1, 18987, 24788, 18988, -1, 18733, 24788, 18735, -1, 18731, 24789, 18733, -1, 24788, 24789, 18988, -1, 18733, 24789, 24788, -1, 18729, 24790, 18731, -1, 18731, 24790, 24789, -1, 18727, 24791, 18729, -1, 18729, 24791, 24790, -1, 18725, 24792, 18727, -1, 18727, 24792, 24791, -1, 19926, 24793, 18725, -1, 18725, 24793, 24792, -1, 22205, 24794, 22207, -1, 19923, 24794, 19926, -1, 19926, 24794, 24793, -1, 22207, 24794, 19923, -1, 24793, 24794, 22205, -1, 17409, 24795, 17407, -1, 17407, 24795, 17405, -1, 17405, 24795, 17404, -1, 17404, 24795, 24787, -1, 24789, 24795, 18988, -1, 24790, 24795, 24789, -1, 24793, 24795, 24792, -1, 24791, 24795, 24790, -1, 22205, 24795, 24793, -1, 24792, 24795, 24791, -1, 18988, 24795, 17409, -1, 24787, 24795, 22205, -1, 20983, 24796, 20985, -1, 24786, 24796, 24787, -1, 20985, 24796, 24786, -1, 24787, 24797, 17404, -1, 24796, 24797, 24787, -1, 24797, 17402, 17404, -1, 24798, 24799, 24800, -1, 24800, 24799, 17391, -1, 24801, 24799, 24798, -1, 17402, 24802, 17403, -1, 17403, 24802, 24803, -1, 24804, 24805, 24806, -1, 24803, 24805, 24804, -1, 17395, 24807, 17399, -1, 24806, 24807, 24801, -1, 24799, 24807, 17395, -1, 24801, 24807, 24799, -1, 24797, 24808, 17402, -1, 24796, 24808, 24797, -1, 17402, 24808, 24802, -1, 24802, 24809, 24803, -1, 24803, 24809, 24805, -1, 21887, 24810, 21889, -1, 21889, 24810, 24796, -1, 24796, 24810, 24808, -1, 17399, 24811, 17401, -1, 24807, 24811, 17399, -1, 24805, 24811, 24806, -1, 24806, 24811, 24807, -1, 19011, 17391, 17393, -1, 24808, 24812, 24802, -1, 24802, 24812, 24809, -1, 17401, 24813, 17375, -1, 24811, 24813, 17401, -1, 24809, 24813, 24805, -1, 24805, 24813, 24811, -1, 21884, 24814, 21887, -1, 21887, 24814, 24810, -1, 20983, 21889, 24796, -1, 24810, 24814, 24808, -1, 24808, 24814, 24812, -1, 17375, 24815, 17374, -1, 24813, 24815, 17375, -1, 24812, 24815, 24809, -1, 24809, 24815, 24813, -1, 24815, 24816, 17374, -1, 21882, 24816, 21884, -1, 24812, 24816, 24815, -1, 17374, 24816, 21882, -1, 24814, 24816, 24812, -1, 21884, 24816, 24814, -1, 21882, 17389, 17374, -1, 17410, 24817, 17412, -1, 17412, 24817, 19021, -1, 17408, 24818, 17410, -1, 17406, 24818, 17408, -1, 17410, 24818, 24817, -1, 19021, 24798, 19015, -1, 19015, 24798, 19010, -1, 24817, 24798, 19021, -1, 17406, 24804, 24818, -1, 24817, 24801, 24798, -1, 24818, 24801, 24817, -1, 19010, 24800, 19011, -1, 24798, 24800, 19010, -1, 19011, 24800, 17391, -1, 17403, 24803, 17406, -1, 17406, 24803, 24804, -1, 24804, 24806, 24818, -1, 24818, 24806, 24801, -1, 17391, 24799, 17395, -1, 17390, 20990, 17387, -1, 17387, 24819, 17382, -1, 20990, 24819, 17387, -1, 17382, 24820, 17379, -1, 24819, 24820, 17382, -1, 17379, 24821, 17367, -1, 24820, 24821, 17379, -1, 17367, 24822, 17365, -1, 24821, 24822, 17367, -1, 17365, 24823, 17384, -1, 24822, 24823, 17365, -1, 17384, 24824, 17385, -1, 24823, 24824, 17384, -1, 24824, 18946, 17385, -1, 24825, 24826, 19046, -1, 24820, 24827, 24821, -1, 24821, 24827, 24828, -1, 24828, 24829, 24830, -1, 24830, 24829, 24831, -1, 24832, 24833, 24825, -1, 24825, 24833, 24826, -1, 19040, 24834, 19039, -1, 19039, 24834, 19038, -1, 19038, 24834, 24835, -1, 24835, 24834, 24836, -1, 24826, 24834, 19040, -1, 21868, 24837, 20990, -1, 24819, 24837, 24820, -1, 20990, 24837, 24819, -1, 24820, 24837, 24827, -1, 24827, 24838, 24828, -1, 24828, 24838, 24829, -1, 24832, 24839, 24833, -1, 24831, 24839, 24832, -1, 24833, 24840, 24826, -1, 24834, 24840, 24836, -1, 24826, 24840, 24834, -1, 21871, 24841, 21870, -1, 21870, 24841, 21868, -1, 21868, 24841, 24837, -1, 24837, 24841, 24827, -1, 24827, 24841, 24838, -1, 24829, 24842, 24831, -1, 24831, 24842, 24839, -1, 24836, 24843, 24844, -1, 24840, 24843, 24836, -1, 24839, 24843, 24833, -1, 24833, 24843, 24840, -1, 24838, 24845, 24829, -1, 24829, 24845, 24842, -1, 24842, 24846, 24839, -1, 24844, 24846, 24847, -1, 24843, 24846, 24844, -1, 24839, 24846, 24843, -1, 21875, 24848, 21873, -1, 21873, 24848, 21871, -1, 24838, 24848, 24845, -1, 21871, 24848, 24841, -1, 24841, 24848, 24838, -1, 24845, 24849, 24842, -1, 24846, 24849, 24847, -1, 24847, 24849, 24850, -1, 21875, 20987, 24851, -1, 24842, 24849, 24846, -1, 24845, 24852, 24849, -1, 18946, 24853, 19053, -1, 24850, 24852, 24851, -1, 19053, 24853, 19050, -1, 24848, 24852, 24845, -1, 21875, 24852, 24848, -1, 24851, 24852, 21875, -1, 24824, 24853, 18946, -1, 24849, 24852, 24850, -1, 24823, 24854, 24824, -1, 24824, 24854, 24853, -1, 19050, 24825, 19046, -1, 24853, 24825, 19050, -1, 24822, 24830, 24823, -1, 24823, 24830, 24854, -1, 24853, 24832, 24825, -1, 24854, 24832, 24853, -1, 24821, 24828, 24822, -1, 24822, 24828, 24830, -1, 24830, 24831, 24854, -1, 24854, 24831, 24832, -1, 19046, 24826, 19040, -1, 19038, 24835, 19056, -1, 19056, 24835, 24855, -1, 24855, 24836, 24856, -1, 24835, 24836, 24855, -1, 24856, 24844, 24857, -1, 24836, 24844, 24856, -1, 24857, 24847, 24858, -1, 24844, 24847, 24857, -1, 24858, 24850, 24859, -1, 24847, 24850, 24858, -1, 24859, 24851, 24860, -1, 24860, 24851, 20989, -1, 24850, 24851, 24859, -1, 24851, 20987, 20989, -1, 22209, 24860, 20989, -1, 18991, 19059, 19937, -1, 22209, 24859, 24860, -1, 22209, 24858, 24859, -1, 19058, 24856, 24857, -1, 19058, 24855, 24856, -1, 19058, 19056, 24855, -1, 19928, 24861, 19192, -1, 19192, 24861, 22211, -1, 22211, 24861, 22209, -1, 19930, 24862, 19928, -1, 24861, 24862, 22209, -1, 19928, 24862, 24861, -1, 19932, 24863, 19930, -1, 24862, 24863, 22209, -1, 19930, 24863, 24862, -1, 22209, 24863, 24858, -1, 19934, 24864, 19932, -1, 24858, 24864, 24857, -1, 24863, 24864, 24858, -1, 19932, 24864, 24863, -1, 24857, 24864, 19058, -1, 19937, 24865, 19935, -1, 19935, 24865, 19934, -1, 24864, 24865, 19058, -1, 19934, 24865, 24864, -1, 19058, 24866, 19059, -1, 24865, 24866, 19058, -1, 19059, 24866, 19937, -1, 19937, 24866, 24865, -1, 19187, 22199, 19941, -1, 18981, 17358, 17360, -1, 18981, 17356, 17358, -1, 22197, 24867, 24868, -1, 22197, 20995, 24867, -1, 18722, 24869, 18980, -1, 18980, 24869, 18981, -1, 18720, 24869, 18722, -1, 18718, 24870, 18720, -1, 24869, 24870, 18981, -1, 18720, 24870, 24869, -1, 18716, 24871, 18718, -1, 18718, 24871, 24870, -1, 18714, 24872, 18716, -1, 18716, 24872, 24871, -1, 18712, 24873, 18714, -1, 18714, 24873, 24872, -1, 19944, 24874, 18712, -1, 18712, 24874, 24873, -1, 22197, 24875, 22199, -1, 19941, 24875, 19944, -1, 19944, 24875, 24874, -1, 22199, 24875, 19941, -1, 24874, 24875, 22197, -1, 17356, 24876, 17354, -1, 17354, 24876, 17352, -1, 17352, 24876, 17351, -1, 17351, 24876, 24868, -1, 24870, 24876, 18981, -1, 24871, 24876, 24870, -1, 24874, 24876, 24873, -1, 24872, 24876, 24871, -1, 22197, 24876, 24874, -1, 24873, 24876, 24872, -1, 18981, 24876, 17356, -1, 24868, 24876, 22197, -1, 20993, 24877, 20995, -1, 20995, 24877, 24867, -1, 24867, 24878, 24868, -1, 24877, 24878, 24867, -1, 24868, 17349, 17351, -1, 24878, 17349, 24868, -1, 17338, 24879, 17342, -1, 24880, 24879, 24881, -1, 24881, 24879, 17338, -1, 24882, 24879, 24880, -1, 17349, 24883, 17350, -1, 17350, 24883, 24884, -1, 24884, 24885, 24886, -1, 24886, 24885, 24887, -1, 17342, 24888, 17346, -1, 24882, 24888, 24879, -1, 24879, 24888, 17342, -1, 24887, 24888, 24882, -1, 24878, 24889, 17349, -1, 17349, 24889, 24883, -1, 24884, 24890, 24885, -1, 24883, 24890, 24884, -1, 21909, 24891, 21911, -1, 24877, 24891, 24878, -1, 24878, 24891, 24889, -1, 21911, 24891, 24877, -1, 17346, 24892, 17348, -1, 24888, 24892, 17346, -1, 24885, 24892, 24887, -1, 18942, 17338, 17340, -1, 24887, 24892, 24888, -1, 24889, 24893, 24883, -1, 24883, 24893, 24890, -1, 17348, 24894, 17322, -1, 24892, 24894, 17348, -1, 24890, 24894, 24885, -1, 24885, 24894, 24892, -1, 20993, 21911, 24877, -1, 21906, 24895, 21909, -1, 21909, 24895, 24891, -1, 24891, 24895, 24889, -1, 24889, 24895, 24893, -1, 17322, 24896, 17321, -1, 24894, 24896, 17322, -1, 24893, 24896, 24890, -1, 24890, 24896, 24894, -1, 21904, 24897, 21906, -1, 24893, 24897, 24896, -1, 21906, 24897, 24895, -1, 17321, 24897, 21904, -1, 24895, 24897, 24893, -1, 24896, 24897, 17321, -1, 21904, 17336, 17321, -1, 17357, 24898, 17359, -1, 17359, 24898, 18982, -1, 17355, 24899, 17357, -1, 17357, 24899, 24898, -1, 18982, 24880, 18960, -1, 18960, 24880, 18945, -1, 24898, 24880, 18982, -1, 17353, 24886, 17355, -1, 17355, 24886, 24899, -1, 24898, 24882, 24880, -1, 24899, 24882, 24898, -1, 18945, 24881, 18942, -1, 24880, 24881, 18945, -1, 18942, 24881, 17338, -1, 17350, 24884, 17353, -1, 17353, 24884, 24886, -1, 24886, 24887, 24899, -1, 24899, 24887, 24882, -1, 17337, 21000, 17334, -1, 17334, 24900, 17329, -1, 21000, 24900, 17334, -1, 17329, 24901, 17326, -1, 24900, 24901, 17329, -1, 17326, 24902, 17314, -1, 24901, 24902, 17326, -1, 17314, 24903, 17312, -1, 24902, 24903, 17314, -1, 17312, 24904, 17331, -1, 24903, 24904, 17312, -1, 17331, 24905, 17332, -1, 24904, 24905, 17331, -1, 24905, 18944, 17332, -1, 24906, 24907, 19019, -1, 24901, 24908, 24902, -1, 24902, 24908, 24909, -1, 24909, 24910, 24911, -1, 24911, 24910, 24912, -1, 24913, 24914, 24906, -1, 24906, 24914, 24907, -1, 19014, 24915, 19013, -1, 19013, 24915, 19012, -1, 19012, 24915, 24916, -1, 24907, 24915, 19014, -1, 21890, 24917, 21000, -1, 24900, 24917, 24901, -1, 21000, 24917, 24900, -1, 24901, 24917, 24908, -1, 24908, 24918, 24909, -1, 24909, 24918, 24910, -1, 24913, 24919, 24914, -1, 24912, 24919, 24913, -1, 24916, 24920, 24921, -1, 24915, 24920, 24916, -1, 24914, 24920, 24907, -1, 24907, 24920, 24915, -1, 21893, 24922, 21892, -1, 21892, 24922, 21890, -1, 21890, 24922, 24917, -1, 24917, 24922, 24908, -1, 24908, 24922, 24918, -1, 24910, 24923, 24912, -1, 24912, 24923, 24919, -1, 24921, 24924, 24925, -1, 24920, 24924, 24921, -1, 24919, 24924, 24914, -1, 24914, 24924, 24920, -1, 24918, 24926, 24910, -1, 24910, 24926, 24923, -1, 24923, 24927, 24919, -1, 24925, 24927, 24928, -1, 24924, 24927, 24925, -1, 24919, 24927, 24924, -1, 21897, 24929, 21895, -1, 21895, 24929, 21893, -1, 24918, 24929, 24926, -1, 21893, 24929, 24922, -1, 24922, 24929, 24918, -1, 24926, 24930, 24923, -1, 24927, 24930, 24928, -1, 24928, 24930, 24931, -1, 21897, 20997, 24932, -1, 18944, 24933, 19027, -1, 24923, 24930, 24927, -1, 19027, 24933, 19024, -1, 24926, 24934, 24930, -1, 24931, 24934, 24932, -1, 21897, 24934, 24929, -1, 24905, 24933, 18944, -1, 24929, 24934, 24926, -1, 24932, 24934, 21897, -1, 24930, 24934, 24931, -1, 24904, 24935, 24905, -1, 24905, 24935, 24933, -1, 19024, 24906, 19019, -1, 24933, 24906, 19024, -1, 24903, 24911, 24904, -1, 24904, 24911, 24935, -1, 24933, 24913, 24906, -1, 24935, 24913, 24933, -1, 24902, 24909, 24903, -1, 24903, 24909, 24911, -1, 24911, 24912, 24935, -1, 24935, 24912, 24913, -1, 19019, 24907, 19014, -1, 19030, 19012, 24936, -1, 24936, 24916, 24937, -1, 19012, 24916, 24936, -1, 24937, 24921, 24938, -1, 24916, 24921, 24937, -1, 24938, 24925, 24939, -1, 24921, 24925, 24938, -1, 24939, 24928, 24940, -1, 24925, 24928, 24939, -1, 24940, 24931, 24941, -1, 24928, 24931, 24940, -1, 24941, 24932, 20999, -1, 24931, 24932, 24941, -1, 24932, 20997, 20999, -1, 22193, 24941, 20999, -1, 18984, 19033, 19955, -1, 22193, 24940, 24941, -1, 22193, 24939, 24940, -1, 19032, 24937, 24938, -1, 19032, 24936, 24937, -1, 19032, 19030, 24936, -1, 19946, 24942, 19183, -1, 19183, 24942, 22195, -1, 22195, 24942, 22193, -1, 19948, 24943, 19946, -1, 24942, 24943, 22193, -1, 19946, 24943, 24942, -1, 19950, 24944, 19948, -1, 24943, 24944, 22193, -1, 19948, 24944, 24943, -1, 22193, 24944, 24939, -1, 19952, 24945, 19950, -1, 24939, 24945, 24938, -1, 24944, 24945, 24939, -1, 19950, 24945, 24944, -1, 24938, 24945, 19032, -1, 19953, 24946, 19952, -1, 24945, 24946, 19032, -1, 19952, 24946, 24945, -1, 19032, 24947, 19033, -1, 19955, 24947, 19953, -1, 19953, 24947, 24946, -1, 24946, 24947, 19032, -1, 19033, 24947, 19955, -1, 19178, 22191, 19959, -1, 18931, 17305, 17307, -1, 18931, 17303, 17305, -1, 22189, 24948, 24949, -1, 22189, 21005, 24948, -1, 18709, 24950, 18975, -1, 18975, 24950, 18931, -1, 18707, 24950, 18709, -1, 18705, 24951, 18707, -1, 24950, 24951, 18931, -1, 18707, 24951, 24950, -1, 18703, 24952, 18705, -1, 18705, 24952, 24951, -1, 18701, 24953, 18703, -1, 18703, 24953, 24952, -1, 18699, 24954, 18701, -1, 18701, 24954, 24953, -1, 19962, 24955, 18699, -1, 18699, 24955, 24954, -1, 22189, 24956, 22191, -1, 19959, 24956, 19962, -1, 19962, 24956, 24955, -1, 22191, 24956, 19959, -1, 24955, 24956, 22189, -1, 17303, 24957, 17301, -1, 17301, 24957, 17299, -1, 17299, 24957, 17298, -1, 17298, 24957, 24949, -1, 24951, 24957, 18931, -1, 24952, 24957, 24951, -1, 24955, 24957, 24954, -1, 24953, 24957, 24952, -1, 22189, 24957, 24955, -1, 24954, 24957, 24953, -1, 18931, 24957, 17303, -1, 24949, 24957, 22189, -1, 21003, 24958, 21005, -1, 21005, 24958, 24948, -1, 24948, 24959, 24949, -1, 24958, 24959, 24948, -1, 24949, 17296, 17298, -1, 24959, 17296, 24949, -1, 17285, 24960, 17289, -1, 24961, 24960, 24962, -1, 24962, 24960, 17285, -1, 24963, 24960, 24961, -1, 24959, 24964, 17296, -1, 17296, 24964, 24965, -1, 24965, 24966, 24967, -1, 24967, 24966, 24968, -1, 17289, 24969, 17293, -1, 24963, 24969, 24960, -1, 24960, 24969, 17289, -1, 24968, 24969, 24963, -1, 24959, 24970, 24964, -1, 24965, 24971, 24966, -1, 24964, 24971, 24965, -1, 21931, 24972, 21933, -1, 24958, 24972, 24959, -1, 21933, 24972, 24958, -1, 24959, 24972, 24970, -1, 17293, 24973, 17295, -1, 24969, 24973, 17293, -1, 24966, 24973, 24968, -1, 24968, 24973, 24969, -1, 18878, 17285, 17287, -1, 24970, 24974, 24964, -1, 24964, 24974, 24971, -1, 17295, 24975, 17269, -1, 24973, 24975, 17295, -1, 24971, 24975, 24966, -1, 24966, 24975, 24973, -1, 21928, 24976, 21931, -1, 21003, 21933, 24958, -1, 21931, 24976, 24972, -1, 24972, 24976, 24970, -1, 24970, 24976, 24974, -1, 17269, 24977, 17268, -1, 24975, 24977, 17269, -1, 24974, 24977, 24971, -1, 24971, 24977, 24975, -1, 24977, 24978, 17268, -1, 21926, 24978, 21928, -1, 24974, 24978, 24977, -1, 17268, 24978, 21926, -1, 24976, 24978, 24974, -1, 21928, 24978, 24976, -1, 21926, 17283, 17268, -1, 17304, 24979, 17306, -1, 17306, 24979, 18898, -1, 17302, 24980, 17304, -1, 17304, 24980, 24979, -1, 18898, 24961, 18891, -1, 18891, 24961, 18877, -1, 24979, 24961, 18898, -1, 17300, 24967, 17302, -1, 17302, 24967, 24980, -1, 24979, 24963, 24961, -1, 24980, 24963, 24979, -1, 18877, 24962, 18878, -1, 24961, 24962, 18877, -1, 18878, 24962, 17285, -1, 17297, 24965, 17300, -1, 17296, 24965, 17297, -1, 17300, 24965, 24967, -1, 24967, 24968, 24980, -1, 24980, 24968, 24963, -1, 21010, 24981, 17284, -1, 17284, 24981, 17281, -1, 17281, 24982, 17276, -1, 24981, 24982, 17281, -1, 17276, 24983, 17273, -1, 24982, 24983, 17276, -1, 17273, 24984, 17261, -1, 24983, 24984, 17273, -1, 17261, 24985, 17259, -1, 24984, 24985, 17261, -1, 17278, 24986, 17279, -1, 17259, 24986, 17278, -1, 24985, 24986, 17259, -1, 24986, 18939, 17279, -1, 24987, 24988, 18969, -1, 24982, 24989, 24983, -1, 24983, 24989, 24990, -1, 24990, 24991, 24992, -1, 24992, 24991, 24993, -1, 24994, 24995, 24987, -1, 24987, 24995, 24988, -1, 18951, 24996, 18943, -1, 18943, 24996, 18941, -1, 18941, 24996, 24997, -1, 24988, 24996, 18951, -1, 21912, 24998, 21010, -1, 24981, 24998, 24982, -1, 21010, 24998, 24981, -1, 24982, 24998, 24989, -1, 24989, 24999, 24990, -1, 24990, 24999, 24991, -1, 24993, 25000, 24994, -1, 24994, 25000, 24995, -1, 24997, 25001, 25002, -1, 24996, 25001, 24997, -1, 24995, 25001, 24988, -1, 24988, 25001, 24996, -1, 21915, 25003, 21914, -1, 21914, 25003, 21912, -1, 21912, 25003, 24998, -1, 24998, 25003, 24989, -1, 24989, 25003, 24999, -1, 24991, 25004, 24993, -1, 24993, 25004, 25000, -1, 25002, 25005, 25006, -1, 25001, 25005, 25002, -1, 25000, 25005, 24995, -1, 24995, 25005, 25001, -1, 24999, 25007, 24991, -1, 24991, 25007, 25004, -1, 25004, 25008, 25000, -1, 25006, 25008, 25009, -1, 25005, 25008, 25006, -1, 25000, 25008, 25005, -1, 21919, 25010, 21917, -1, 21917, 25010, 21915, -1, 24999, 25010, 25007, -1, 21915, 25010, 25003, -1, 25003, 25010, 24999, -1, 25007, 25011, 25004, -1, 25008, 25011, 25009, -1, 25009, 25011, 25012, -1, 21919, 21007, 25013, -1, 25004, 25011, 25008, -1, 18939, 25014, 18999, -1, 25007, 25015, 25011, -1, 18999, 25014, 18989, -1, 25012, 25015, 25013, -1, 25010, 25015, 25007, -1, 21919, 25015, 25010, -1, 24986, 25014, 18939, -1, 25013, 25015, 21919, -1, 25011, 25015, 25012, -1, 24985, 25016, 24986, -1, 24986, 25016, 25014, -1, 18989, 24987, 18969, -1, 25014, 24987, 18989, -1, 24984, 24992, 24985, -1, 24985, 24992, 25016, -1, 25014, 24994, 24987, -1, 25016, 24994, 25014, -1, 24983, 24990, 24984, -1, 24984, 24990, 24992, -1, 24992, 24993, 25016, -1, 25016, 24993, 24994, -1, 18969, 24988, 18951, -1, 18941, 24997, 19005, -1, 19005, 24997, 25017, -1, 25017, 25002, 25018, -1, 24997, 25002, 25017, -1, 25018, 25006, 25019, -1, 25019, 25006, 25020, -1, 25002, 25006, 25018, -1, 25020, 25009, 25021, -1, 25006, 25009, 25020, -1, 25021, 25012, 25022, -1, 25009, 25012, 25021, -1, 25022, 25013, 21009, -1, 25012, 25013, 25022, -1, 25013, 21007, 21009, -1, 22185, 25022, 21009, -1, 18978, 19007, 19973, -1, 22185, 25021, 25022, -1, 22185, 25020, 25021, -1, 19006, 25018, 25019, -1, 19006, 25017, 25018, -1, 19006, 19005, 25017, -1, 19964, 25023, 19174, -1, 19174, 25023, 22187, -1, 22187, 25023, 22185, -1, 19966, 25024, 19964, -1, 25023, 25024, 22185, -1, 19964, 25024, 25023, -1, 19968, 25025, 19966, -1, 25024, 25025, 22185, -1, 19966, 25025, 25024, -1, 22185, 25025, 25020, -1, 19971, 25026, 19970, -1, 19970, 25026, 19968, -1, 25020, 25026, 25019, -1, 25025, 25026, 25020, -1, 19968, 25026, 25025, -1, 25019, 25026, 19006, -1, 25026, 25027, 19006, -1, 19971, 25027, 25026, -1, 19006, 25028, 19007, -1, 19973, 25028, 19971, -1, 19971, 25028, 25027, -1, 25027, 25028, 19006, -1, 19007, 25028, 19973, -1, 19169, 22183, 19977, -1, 18869, 17251, 17253, -1, 18869, 17250, 17251, -1, 22181, 25029, 25030, -1, 22181, 21015, 25029, -1, 18696, 25031, 18970, -1, 18970, 25031, 18869, -1, 18694, 25031, 18696, -1, 18692, 25032, 18694, -1, 25031, 25032, 18869, -1, 18694, 25032, 25031, -1, 18690, 25033, 18692, -1, 18692, 25033, 25032, -1, 18688, 25034, 18690, -1, 18690, 25034, 25033, -1, 18686, 25035, 18688, -1, 18688, 25035, 25034, -1, 19980, 25036, 18686, -1, 18686, 25036, 25035, -1, 22181, 25037, 22183, -1, 19977, 25037, 19980, -1, 19980, 25037, 25036, -1, 22183, 25037, 19977, -1, 25036, 25037, 22181, -1, 17250, 25038, 17248, -1, 17248, 25038, 17246, -1, 17246, 25038, 17245, -1, 17245, 25038, 25030, -1, 25032, 25038, 18869, -1, 25033, 25038, 25032, -1, 25036, 25038, 25035, -1, 25034, 25038, 25033, -1, 22181, 25038, 25036, -1, 25035, 25038, 25034, -1, 18869, 25038, 17250, -1, 25030, 25038, 22181, -1, 21015, 21013, 25029, -1, 25029, 25039, 25030, -1, 21013, 25039, 25029, -1, 25030, 25040, 17245, -1, 25039, 25040, 25030, -1, 25040, 17243, 17245, -1, 17232, 25041, 17236, -1, 25042, 25041, 25043, -1, 25043, 25041, 17232, -1, 25044, 25041, 25042, -1, 17243, 25045, 17244, -1, 17244, 25045, 25046, -1, 25046, 25047, 25048, -1, 25048, 25047, 25049, -1, 17236, 25050, 17240, -1, 25044, 25050, 25041, -1, 25041, 25050, 17236, -1, 25049, 25050, 25044, -1, 25040, 25051, 17243, -1, 17243, 25051, 25045, -1, 25046, 25052, 25047, -1, 25045, 25052, 25046, -1, 21944, 25053, 21946, -1, 25039, 25053, 25040, -1, 25040, 25053, 25051, -1, 21946, 25053, 25039, -1, 17240, 25054, 17242, -1, 25050, 25054, 17240, -1, 25047, 25054, 25049, -1, 19066, 17232, 17234, -1, 25049, 25054, 25050, -1, 25051, 25055, 25045, -1, 25045, 25055, 25052, -1, 17242, 25056, 17216, -1, 25054, 25056, 17242, -1, 25052, 25056, 25047, -1, 25047, 25056, 25054, -1, 21013, 21946, 25039, -1, 21941, 25057, 21944, -1, 21944, 25057, 25053, -1, 25053, 25057, 25051, -1, 25051, 25057, 25055, -1, 17216, 25058, 17215, -1, 25056, 25058, 17216, -1, 25055, 25058, 25052, -1, 25052, 25058, 25056, -1, 21939, 25059, 21941, -1, 25055, 25059, 25058, -1, 21941, 25059, 25057, -1, 17215, 25059, 21939, -1, 25057, 25059, 25055, -1, 25058, 25059, 17215, -1, 21939, 17230, 17215, -1, 17252, 25060, 17254, -1, 17254, 25060, 18836, -1, 17249, 25061, 17252, -1, 17252, 25061, 25060, -1, 18836, 25042, 18828, -1, 18828, 25042, 18829, -1, 25060, 25042, 18836, -1, 17247, 25048, 17249, -1, 17249, 25048, 25061, -1, 25060, 25044, 25042, -1, 25061, 25044, 25060, -1, 18829, 25043, 19066, -1, 25042, 25043, 18829, -1, 19066, 25043, 17232, -1, 17244, 25046, 17247, -1, 17247, 25046, 25048, -1, 25048, 25049, 25061, -1, 25061, 25049, 25044, -1, 17231, 21020, 17228, -1, 21020, 25062, 17228, -1, 17228, 25063, 17223, -1, 25062, 25063, 17228, -1, 17223, 25064, 17220, -1, 25063, 25064, 17223, -1, 17220, 25065, 17208, -1, 25064, 25065, 17220, -1, 17208, 25066, 17206, -1, 25065, 25066, 17208, -1, 17206, 25067, 17225, -1, 25066, 25067, 17206, -1, 17225, 18906, 17226, -1, 25067, 18906, 17225, -1, 25068, 25069, 18894, -1, 25063, 25070, 25064, -1, 25064, 25070, 25071, -1, 25071, 25072, 25073, -1, 25073, 25072, 25074, -1, 25075, 25076, 25068, -1, 25068, 25076, 25069, -1, 18888, 25077, 18883, -1, 18883, 25077, 18879, -1, 18879, 25077, 25078, -1, 25069, 25077, 18888, -1, 21947, 25079, 21020, -1, 25062, 25079, 25063, -1, 21020, 25079, 25062, -1, 25063, 25079, 25070, -1, 25070, 25080, 25071, -1, 25071, 25080, 25072, -1, 25075, 25081, 25076, -1, 25074, 25081, 25075, -1, 25078, 25082, 25083, -1, 25077, 25082, 25078, -1, 25076, 25082, 25069, -1, 25069, 25082, 25077, -1, 21950, 25084, 21949, -1, 21949, 25084, 21947, -1, 21947, 25084, 25079, -1, 25079, 25084, 25070, -1, 25070, 25084, 25080, -1, 25072, 25085, 25074, -1, 25074, 25085, 25081, -1, 25083, 25086, 25087, -1, 25082, 25086, 25083, -1, 25081, 25086, 25076, -1, 25076, 25086, 25082, -1, 25080, 25088, 25072, -1, 25072, 25088, 25085, -1, 25085, 25089, 25081, -1, 25087, 25089, 25090, -1, 25086, 25089, 25087, -1, 25081, 25089, 25086, -1, 21954, 25091, 21952, -1, 21952, 25091, 21950, -1, 25080, 25091, 25088, -1, 21950, 25091, 25084, -1, 25084, 25091, 25080, -1, 25088, 25092, 25085, -1, 25089, 25092, 25090, -1, 25090, 25092, 25093, -1, 21954, 21017, 25094, -1, 18906, 25095, 18905, -1, 25085, 25092, 25089, -1, 18905, 25095, 18901, -1, 25088, 25096, 25092, -1, 25093, 25096, 25094, -1, 21954, 25096, 25091, -1, 25067, 25095, 18906, -1, 25091, 25096, 25088, -1, 25094, 25096, 21954, -1, 25092, 25096, 25093, -1, 25066, 25097, 25067, -1, 25067, 25097, 25095, -1, 18901, 25068, 18894, -1, 25095, 25068, 18901, -1, 25065, 25073, 25066, -1, 25066, 25073, 25097, -1, 25095, 25075, 25068, -1, 25097, 25075, 25095, -1, 25064, 25071, 25065, -1, 25065, 25071, 25073, -1, 25073, 25074, 25097, -1, 25097, 25074, 25075, -1, 18894, 25069, 18888, -1, 18913, 18879, 25098, -1, 18879, 25078, 25098, -1, 25098, 25083, 25099, -1, 25078, 25083, 25098, -1, 25099, 25087, 25100, -1, 25083, 25087, 25099, -1, 25100, 25090, 25101, -1, 25087, 25090, 25100, -1, 25101, 25093, 25102, -1, 25090, 25093, 25101, -1, 25102, 25094, 25103, -1, 25103, 25094, 21019, -1, 25093, 25094, 25102, -1, 25094, 21017, 21019, -1, 22177, 25103, 21019, -1, 18929, 18926, 19991, -1, 22177, 25102, 25103, -1, 22177, 25101, 25102, -1, 18925, 25099, 25100, -1, 18925, 25098, 25099, -1, 18925, 18913, 25098, -1, 19982, 25104, 19165, -1, 19165, 25104, 22179, -1, 22179, 25104, 22177, -1, 19984, 25105, 19982, -1, 25104, 25105, 22177, -1, 19982, 25105, 25104, -1, 19986, 25106, 19984, -1, 25105, 25106, 22177, -1, 19984, 25106, 25105, -1, 22177, 25106, 25101, -1, 19988, 25107, 19986, -1, 25101, 25107, 25100, -1, 25106, 25107, 25101, -1, 19986, 25107, 25106, -1, 25100, 25107, 18925, -1, 19991, 25108, 19989, -1, 19989, 25108, 19988, -1, 25107, 25108, 18925, -1, 19988, 25108, 25107, -1, 18925, 25109, 18926, -1, 25108, 25109, 18925, -1, 18926, 25109, 19991, -1, 19991, 25109, 25108, -1, 19142, 22159, 19995, -1, 18955, 17199, 17201, -1, 18955, 17197, 17199, -1, 22157, 25110, 25111, -1, 22157, 21045, 25110, -1, 18683, 25112, 18954, -1, 18954, 25112, 18955, -1, 18681, 25112, 18683, -1, 18679, 25113, 18681, -1, 25112, 25113, 18955, -1, 18681, 25113, 25112, -1, 18677, 25114, 18679, -1, 18679, 25114, 25113, -1, 18675, 25115, 18677, -1, 18677, 25115, 25114, -1, 18673, 25116, 18675, -1, 18675, 25116, 25115, -1, 19998, 25117, 18673, -1, 18673, 25117, 25116, -1, 22157, 25118, 22159, -1, 19995, 25118, 19998, -1, 19998, 25118, 25117, -1, 22159, 25118, 19995, -1, 25117, 25118, 22157, -1, 17197, 25119, 17195, -1, 17195, 25119, 17193, -1, 17193, 25119, 17192, -1, 17192, 25119, 25111, -1, 25113, 25119, 18955, -1, 25114, 25119, 25113, -1, 25117, 25119, 25116, -1, 25115, 25119, 25114, -1, 22157, 25119, 25117, -1, 25116, 25119, 25115, -1, 18955, 25119, 17197, -1, 25111, 25119, 22157, -1, 21045, 21043, 25110, -1, 21043, 25120, 25110, -1, 25110, 25121, 25111, -1, 25120, 25121, 25110, -1, 25111, 17190, 17192, -1, 25121, 17190, 25111, -1, 17179, 25122, 17183, -1, 25123, 25122, 25124, -1, 25124, 25122, 17179, -1, 25125, 25122, 25123, -1, 17190, 25126, 17191, -1, 17191, 25126, 25127, -1, 25127, 25128, 25129, -1, 25129, 25128, 25130, -1, 17183, 25131, 17187, -1, 25125, 25131, 25122, -1, 25122, 25131, 17183, -1, 25130, 25131, 25125, -1, 25121, 25132, 17190, -1, 25120, 25132, 25121, -1, 17190, 25132, 25126, -1, 25127, 25133, 25128, -1, 25126, 25133, 25127, -1, 22010, 25134, 22012, -1, 22012, 25134, 25120, -1, 25120, 25134, 25132, -1, 17187, 25135, 17189, -1, 25131, 25135, 17187, -1, 25128, 25135, 25130, -1, 25130, 25135, 25131, -1, 18972, 17179, 17181, -1, 25132, 25136, 25126, -1, 25126, 25136, 25133, -1, 17189, 25137, 17163, -1, 25135, 25137, 17189, -1, 25133, 25137, 25128, -1, 25128, 25137, 25135, -1, 22007, 25138, 22010, -1, 21043, 22012, 25120, -1, 22010, 25138, 25134, -1, 25134, 25138, 25132, -1, 25132, 25138, 25136, -1, 17163, 25139, 17162, -1, 25137, 25139, 17163, -1, 25136, 25139, 25133, -1, 25133, 25139, 25137, -1, 22005, 25140, 22007, -1, 25136, 25140, 25139, -1, 22007, 25140, 25138, -1, 17162, 25140, 22005, -1, 25138, 25140, 25136, -1, 25139, 25140, 17162, -1, 22005, 17177, 17162, -1, 17198, 25141, 17200, -1, 17200, 25141, 19000, -1, 17196, 25142, 17198, -1, 17198, 25142, 25141, -1, 19000, 25123, 18993, -1, 18993, 25123, 18971, -1, 25141, 25123, 19000, -1, 17194, 25129, 17196, -1, 17196, 25129, 25142, -1, 25141, 25125, 25123, -1, 25142, 25125, 25141, -1, 18971, 25124, 18972, -1, 25123, 25124, 18971, -1, 18972, 25124, 17179, -1, 17191, 25127, 17194, -1, 17194, 25127, 25129, -1, 25129, 25130, 25142, -1, 25142, 25130, 25125, -1, 21050, 25143, 17178, -1, 17178, 25143, 17175, -1, 17175, 25144, 17170, -1, 25143, 25144, 17175, -1, 17170, 25145, 17167, -1, 25144, 25145, 17170, -1, 17167, 25146, 17155, -1, 25145, 25146, 17167, -1, 17155, 25147, 17153, -1, 25146, 25147, 17155, -1, 17153, 25148, 17172, -1, 25147, 25148, 17153, -1, 17172, 18934, 17173, -1, 25148, 18934, 17172, -1, 25149, 25150, 19025, -1, 25144, 25151, 25145, -1, 25145, 25151, 25152, -1, 25152, 25153, 25154, -1, 25154, 25153, 25155, -1, 25156, 25157, 25149, -1, 25149, 25157, 25150, -1, 19022, 25158, 19020, -1, 19020, 25158, 19018, -1, 19018, 25158, 25159, -1, 25150, 25158, 19022, -1, 22013, 25160, 21050, -1, 25143, 25160, 25144, -1, 21050, 25160, 25143, -1, 25144, 25160, 25151, -1, 25151, 25161, 25152, -1, 25152, 25161, 25153, -1, 25156, 25162, 25157, -1, 25155, 25162, 25156, -1, 25159, 25163, 25164, -1, 25158, 25163, 25159, -1, 25157, 25163, 25150, -1, 25150, 25163, 25158, -1, 22016, 25165, 22015, -1, 22015, 25165, 22013, -1, 22013, 25165, 25160, -1, 25160, 25165, 25151, -1, 25151, 25165, 25161, -1, 25153, 25166, 25155, -1, 25155, 25166, 25162, -1, 25164, 25167, 25168, -1, 25163, 25167, 25164, -1, 25162, 25167, 25157, -1, 25157, 25167, 25163, -1, 25161, 25169, 25153, -1, 25153, 25169, 25166, -1, 25166, 25170, 25162, -1, 25168, 25170, 25171, -1, 25167, 25170, 25168, -1, 25162, 25170, 25167, -1, 22020, 25172, 22018, -1, 22018, 25172, 22016, -1, 25161, 25172, 25169, -1, 22016, 25172, 25165, -1, 25165, 25172, 25161, -1, 25169, 25173, 25166, -1, 25170, 25173, 25171, -1, 25171, 25173, 25174, -1, 22020, 21047, 25175, -1, 18934, 25176, 19029, -1, 25166, 25173, 25170, -1, 19029, 25176, 19028, -1, 25169, 25177, 25173, -1, 25174, 25177, 25175, -1, 22020, 25177, 25172, -1, 25148, 25176, 18934, -1, 25172, 25177, 25169, -1, 25175, 25177, 22020, -1, 25173, 25177, 25174, -1, 25147, 25178, 25148, -1, 25148, 25178, 25176, -1, 19028, 25149, 19025, -1, 25176, 25149, 19028, -1, 25146, 25154, 25147, -1, 25147, 25154, 25178, -1, 25176, 25156, 25149, -1, 25178, 25156, 25176, -1, 25145, 25152, 25146, -1, 25146, 25152, 25154, -1, 25154, 25155, 25178, -1, 25178, 25155, 25156, -1, 19025, 25150, 19022, -1, 19018, 25159, 19031, -1, 19031, 25159, 25179, -1, 25179, 25164, 25180, -1, 25159, 25164, 25179, -1, 25180, 25168, 25181, -1, 25164, 25168, 25180, -1, 25181, 25171, 25182, -1, 25168, 25171, 25181, -1, 25182, 25174, 25183, -1, 25171, 25174, 25182, -1, 25183, 25175, 25184, -1, 25184, 25175, 21049, -1, 25174, 25175, 25183, -1, 25175, 21047, 21049, -1, 22153, 25184, 21049, -1, 18957, 19035, 20009, -1, 22153, 25183, 25184, -1, 22153, 25182, 25183, -1, 19034, 25180, 25181, -1, 19034, 25179, 25180, -1, 19034, 19031, 25179, -1, 20000, 25185, 19138, -1, 19138, 25185, 22155, -1, 22155, 25185, 22153, -1, 20002, 25186, 20000, -1, 25185, 25186, 22153, -1, 20000, 25186, 25185, -1, 20004, 25187, 20002, -1, 25186, 25187, 22153, -1, 20002, 25187, 25186, -1, 22153, 25187, 25182, -1, 20006, 25188, 20004, -1, 25182, 25188, 25181, -1, 25187, 25188, 25182, -1, 20004, 25188, 25187, -1, 25181, 25188, 19034, -1, 20009, 25189, 20007, -1, 20007, 25189, 20006, -1, 25188, 25189, 19034, -1, 20006, 25189, 25188, -1, 19034, 25190, 19035, -1, 25189, 25190, 19034, -1, 19035, 25190, 20009, -1, 20009, 25190, 25189, -1, 20958, 25191, 20959, -1, 20959, 25191, 22897, -1, 22897, 25192, 17131, -1, 25191, 25192, 22897, -1, 25192, 17132, 17131, -1, 20958, 22150, 25191, -1, 18948, 17128, 17130, -1, 18948, 17126, 17128, -1, 22148, 25193, 25194, -1, 22148, 20630, 25193, -1, 17147, 25195, 19003, -1, 19003, 25195, 18948, -1, 17143, 25195, 17147, -1, 17140, 25196, 17143, -1, 25195, 25196, 18948, -1, 17143, 25196, 25195, -1, 17136, 25197, 17140, -1, 17140, 25197, 25196, -1, 17134, 25198, 17136, -1, 17136, 25198, 25197, -1, 17132, 25199, 17134, -1, 17134, 25199, 25198, -1, 25192, 25200, 17132, -1, 17132, 25200, 25199, -1, 22148, 25201, 22150, -1, 25191, 25201, 25192, -1, 25192, 25201, 25200, -1, 22150, 25201, 25191, -1, 25200, 25201, 22148, -1, 17126, 25202, 17124, -1, 17124, 25202, 17122, -1, 17122, 25202, 17121, -1, 17121, 25202, 25194, -1, 25196, 25202, 18948, -1, 25197, 25202, 25196, -1, 25200, 25202, 25199, -1, 25198, 25202, 25197, -1, 22148, 25202, 25200, -1, 25199, 25202, 25198, -1, 18948, 25202, 17126, -1, 25194, 25202, 22148, -1, 20632, 25203, 20630, -1, 20630, 25203, 25193, -1, 25193, 25204, 25194, -1, 25203, 25204, 25193, -1, 25194, 17119, 17121, -1, 25204, 17119, 25194, -1, 25205, 25206, 25207, -1, 17125, 25208, 25209, -1, 25207, 25206, 25210, -1, 25211, 25212, 25213, -1, 25214, 25215, 25216, -1, 25209, 25215, 25214, -1, 25210, 25212, 25211, -1, 18897, 25217, 18892, -1, 18892, 25217, 18893, -1, 25216, 25217, 18897, -1, 25218, 25219, 25220, -1, 25220, 25219, 25221, -1, 17120, 25222, 17123, -1, 25213, 25223, 25224, -1, 17123, 25222, 25208, -1, 25224, 25223, 25225, -1, 25209, 25226, 25215, -1, 22032, 25227, 22030, -1, 25205, 25227, 25206, -1, 22030, 25227, 25228, -1, 25208, 25226, 25209, -1, 25228, 25227, 25205, -1, 25221, 25229, 18904, -1, 18904, 25229, 18907, -1, 18907, 25229, 25230, -1, 25215, 25231, 25216, -1, 25216, 25231, 25217, -1, 25206, 25232, 25210, -1, 25210, 25232, 25212, -1, 25217, 25233, 18893, -1, 25225, 25234, 25218, -1, 25218, 25234, 25219, -1, 17119, 25235, 17120, -1, 25213, 25236, 25223, -1, 25212, 25236, 25213, -1, 17120, 25235, 25222, -1, 25230, 25237, 25238, -1, 20632, 22027, 25203, -1, 25208, 25239, 25226, -1, 25219, 25237, 25221, -1, 25229, 25237, 25230, -1, 25222, 25239, 25208, -1, 25221, 25237, 25229, -1, 22033, 25240, 22032, -1, 25226, 25241, 25215, -1, 22032, 25240, 25227, -1, 25227, 25240, 25206, -1, 25206, 25240, 25232, -1, 25215, 25241, 25231, -1, 25232, 25242, 25212, -1, 25204, 25243, 17119, -1, 25212, 25242, 25236, -1, 17119, 25243, 25235, -1, 25225, 25244, 25234, -1, 25223, 25244, 25225, -1, 25231, 25245, 25217, -1, 25238, 25246, 25247, -1, 25217, 25245, 25233, -1, 25234, 25246, 25219, -1, 25237, 25246, 25238, -1, 18893, 25220, 18899, -1, 25219, 25246, 25237, -1, 18899, 25220, 18902, -1, 22034, 25248, 22033, -1, 22033, 25248, 25240, -1, 25240, 25248, 25232, -1, 25233, 25220, 18893, -1, 25232, 25248, 25242, -1, 25236, 25249, 25223, -1, 25235, 25207, 25222, -1, 18907, 25230, 18908, -1, 25222, 25207, 25239, -1, 25223, 25249, 25244, -1, 25247, 25250, 25251, -1, 25239, 25211, 25226, -1, 25234, 25250, 25246, -1, 25246, 25250, 25247, -1, 25226, 25211, 25241, -1, 25244, 25250, 25234, -1, 22029, 25252, 22027, -1, 25203, 25252, 25204, -1, 25236, 25253, 25249, -1, 22027, 25252, 25203, -1, 25242, 25253, 25236, -1, 25204, 25252, 25243, -1, 25231, 25224, 25245, -1, 25251, 25254, 25255, -1, 25250, 25254, 25251, -1, 25249, 25254, 25244, -1, 25241, 25224, 25231, -1, 25244, 25254, 25250, -1, 25243, 25205, 25235, -1, 22034, 25256, 25248, -1, 25248, 25256, 25242, -1, 25242, 25256, 25253, -1, 25235, 25205, 25207, -1, 25245, 25218, 25233, -1, 25255, 25257, 25258, -1, 25254, 25257, 25255, -1, 25253, 25257, 25249, -1, 25249, 25257, 25254, -1, 25233, 25218, 25220, -1, 25256, 25259, 25253, -1, 25258, 25259, 20583, -1, 20583, 25259, 22035, -1, 22035, 25259, 22034, -1, 22034, 25259, 25256, -1, 25253, 25259, 25257, -1, 25207, 25210, 25239, -1, 25257, 25259, 25258, -1, 25239, 25210, 25211, -1, 17129, 25214, 18900, -1, 25211, 25213, 25241, -1, 18900, 25214, 18897, -1, 25241, 25213, 25224, -1, 17127, 25214, 17129, -1, 22029, 25228, 25252, -1, 22030, 25228, 22029, -1, 17125, 25209, 17127, -1, 25252, 25228, 25243, -1, 25243, 25228, 25205, -1, 18902, 25221, 18904, -1, 17127, 25209, 25214, -1, 25220, 25221, 18902, -1, 25214, 25216, 18897, -1, 25245, 25225, 25218, -1, 17123, 25208, 17125, -1, 25224, 25225, 25245, -1, 18908, 25230, 18910, -1, 18910, 25230, 25260, -1, 25260, 25230, 25261, -1, 25261, 25238, 25262, -1, 25230, 25238, 25261, -1, 25262, 25247, 25263, -1, 25238, 25247, 25262, -1, 25263, 25251, 25264, -1, 25247, 25251, 25263, -1, 25264, 25255, 25265, -1, 25251, 25255, 25264, -1, 25265, 25258, 20581, -1, 25255, 25258, 25265, -1, 25258, 20583, 20581, -1, 25266, 25267, 18998, -1, 25264, 25268, 25263, -1, 25263, 25268, 25269, -1, 25269, 25270, 25271, -1, 25271, 25270, 25272, -1, 25273, 25274, 25266, -1, 25266, 25274, 25267, -1, 18986, 25275, 18976, -1, 18976, 25275, 18949, -1, 18949, 25275, 25276, -1, 25267, 25275, 18986, -1, 22026, 25277, 20581, -1, 25265, 25277, 25264, -1, 20581, 25277, 25265, -1, 25264, 25277, 25268, -1, 25268, 25278, 25269, -1, 25269, 25278, 25270, -1, 25273, 25279, 25274, -1, 25272, 25279, 25273, -1, 25276, 25280, 25281, -1, 25275, 25280, 25276, -1, 25274, 25280, 25267, -1, 25267, 25280, 25275, -1, 22024, 25282, 22025, -1, 22025, 25282, 22026, -1, 22026, 25282, 25277, -1, 25277, 25282, 25268, -1, 25268, 25282, 25278, -1, 25270, 25283, 25272, -1, 25272, 25283, 25279, -1, 25281, 25284, 25285, -1, 25280, 25284, 25281, -1, 25279, 25284, 25274, -1, 25274, 25284, 25280, -1, 25278, 25286, 25270, -1, 25270, 25286, 25283, -1, 25283, 25287, 25279, -1, 25285, 25287, 25288, -1, 25284, 25287, 25285, -1, 25279, 25287, 25284, -1, 22022, 25289, 22023, -1, 22023, 25289, 22024, -1, 25278, 25289, 25286, -1, 22024, 25289, 25282, -1, 25282, 25289, 25278, -1, 25286, 25290, 25283, -1, 25287, 25290, 25288, -1, 25288, 25290, 25291, -1, 22022, 21055, 25292, -1, 18910, 25293, 19004, -1, 25283, 25290, 25287, -1, 19004, 25293, 19001, -1, 25286, 25294, 25290, -1, 25291, 25294, 25292, -1, 22022, 25294, 25289, -1, 25260, 25293, 18910, -1, 25289, 25294, 25286, -1, 25292, 25294, 22022, -1, 25290, 25294, 25291, -1, 25261, 25295, 25260, -1, 25260, 25295, 25293, -1, 19001, 25266, 18998, -1, 25293, 25266, 19001, -1, 25262, 25271, 25261, -1, 25261, 25271, 25295, -1, 25293, 25273, 25266, -1, 25295, 25273, 25293, -1, 25263, 25269, 25262, -1, 25262, 25269, 25271, -1, 25271, 25272, 25295, -1, 25295, 25272, 25273, -1, 18998, 25267, 18986, -1, 18949, 25276, 18950, -1, 18950, 25276, 25296, -1, 25296, 25281, 25297, -1, 25276, 25281, 25296, -1, 25297, 25285, 25298, -1, 25281, 25285, 25297, -1, 25298, 25288, 25299, -1, 25285, 25288, 25298, -1, 25299, 25291, 25300, -1, 25288, 25291, 25299, -1, 25300, 25292, 25301, -1, 25291, 25292, 25300, -1, 25301, 21055, 21056, -1, 25292, 21055, 25301, -1, 22144, 25301, 21056, -1, 18952, 19009, 20023, -1, 22144, 25300, 25301, -1, 22144, 25299, 25300, -1, 19008, 25297, 25298, -1, 19008, 25296, 25297, -1, 19008, 18950, 25296, -1, 20014, 25302, 19130, -1, 19130, 25302, 22146, -1, 22146, 25302, 22144, -1, 20016, 25303, 20014, -1, 25302, 25303, 22144, -1, 20014, 25303, 25302, -1, 20018, 25304, 20016, -1, 25303, 25304, 22144, -1, 20016, 25304, 25303, -1, 22144, 25304, 25299, -1, 20020, 25305, 20018, -1, 25299, 25305, 25298, -1, 25304, 25305, 25299, -1, 20018, 25305, 25304, -1, 25298, 25305, 19008, -1, 20023, 25306, 20021, -1, 20021, 25306, 20020, -1, 25305, 25306, 19008, -1, 20020, 25306, 25305, -1, 19008, 25307, 19009, -1, 25306, 25307, 19008, -1, 19009, 25307, 20023, -1, 20023, 25307, 25306, -1, 22161, 25308, 21039, -1, 18963, 19061, 20040, -1, 22161, 25309, 25308, -1, 22161, 25310, 25309, -1, 19060, 25311, 25312, -1, 19060, 25313, 25311, -1, 19060, 19057, 25313, -1, 19147, 25314, 22163, -1, 22163, 25314, 22161, -1, 20031, 25314, 19147, -1, 20033, 25315, 20031, -1, 25314, 25315, 22161, -1, 20031, 25315, 25314, -1, 20035, 25316, 20033, -1, 25315, 25316, 22161, -1, 20033, 25316, 25315, -1, 22161, 25316, 25310, -1, 25310, 25317, 25312, -1, 20037, 25317, 20035, -1, 25316, 25317, 25310, -1, 20035, 25317, 25316, -1, 25312, 25317, 19060, -1, 20039, 25318, 20037, -1, 20040, 25318, 20039, -1, 25317, 25318, 19060, -1, 20037, 25318, 25317, -1, 19060, 25319, 19061, -1, 20040, 25319, 25318, -1, 19061, 25319, 20040, -1, 25318, 25319, 19060, -1, 19042, 25320, 19057, -1, 19057, 25320, 25313, -1, 25313, 25321, 25311, -1, 25320, 25321, 25313, -1, 25311, 25322, 25312, -1, 25321, 25322, 25311, -1, 25312, 25323, 25310, -1, 25322, 25323, 25312, -1, 25310, 25324, 25309, -1, 25323, 25324, 25310, -1, 25309, 25325, 25308, -1, 25324, 25325, 25309, -1, 25308, 21037, 21039, -1, 25325, 21037, 25308, -1, 25326, 25327, 19051, -1, 25328, 25329, 25330, -1, 25330, 25329, 25331, -1, 25331, 25332, 25333, -1, 25333, 25332, 25334, -1, 25326, 25335, 25327, -1, 25336, 25335, 25326, -1, 19047, 25337, 19044, -1, 19044, 25337, 19042, -1, 19042, 25337, 25320, -1, 25327, 25337, 19047, -1, 21978, 25338, 21040, -1, 21040, 25338, 25339, -1, 25339, 25338, 25328, -1, 25328, 25338, 25329, -1, 25329, 25340, 25331, -1, 25331, 25340, 25332, -1, 25334, 25341, 25336, -1, 25336, 25341, 25335, -1, 25320, 25342, 25321, -1, 25335, 25342, 25327, -1, 25337, 25342, 25320, -1, 25327, 25342, 25337, -1, 21981, 25343, 21980, -1, 21980, 25343, 21978, -1, 21978, 25343, 25338, -1, 25338, 25343, 25329, -1, 25329, 25343, 25340, -1, 25334, 25344, 25341, -1, 25332, 25344, 25334, -1, 25321, 25345, 25322, -1, 25341, 25345, 25335, -1, 25342, 25345, 25321, -1, 25335, 25345, 25342, -1, 25332, 25346, 25344, -1, 25340, 25346, 25332, -1, 25322, 25347, 25323, -1, 25341, 25347, 25345, -1, 25345, 25347, 25322, -1, 25344, 25347, 25341, -1, 21985, 25348, 21983, -1, 21983, 25348, 21981, -1, 25340, 25348, 25346, -1, 21981, 25348, 25343, -1, 25343, 25348, 25340, -1, 25344, 25349, 25347, -1, 25323, 25349, 25324, -1, 25346, 25349, 25344, -1, 21985, 21037, 25325, -1, 25347, 25349, 25323, -1, 25349, 25350, 25324, -1, 25346, 25350, 25349, -1, 25351, 25352, 18935, -1, 25324, 25350, 25325, -1, 18935, 25352, 19055, -1, 25348, 25350, 25346, -1, 19055, 25352, 19054, -1, 25325, 25350, 21985, -1, 21985, 25350, 25348, -1, 25353, 25354, 25351, -1, 25351, 25354, 25352, -1, 19054, 25326, 19051, -1, 25352, 25326, 19054, -1, 25355, 25333, 25353, -1, 25353, 25333, 25354, -1, 25352, 25336, 25326, -1, 25354, 25336, 25352, -1, 25330, 25331, 25355, -1, 25355, 25331, 25333, -1, 25333, 25334, 25354, -1, 25354, 25334, 25336, -1, 19051, 25327, 19047, -1, 21040, 25339, 17107, -1, 17107, 25339, 17104, -1, 17104, 25328, 17099, -1, 25339, 25328, 17104, -1, 17099, 25330, 17096, -1, 25328, 25330, 17099, -1, 17096, 25355, 17084, -1, 25330, 25355, 17096, -1, 17084, 25353, 17082, -1, 25355, 25353, 17084, -1, 17082, 25351, 17101, -1, 25353, 25351, 17082, -1, 17101, 18935, 17102, -1, 25351, 18935, 17101, -1, 17108, 25356, 17112, -1, 25357, 25356, 25358, -1, 25358, 25356, 17108, -1, 25359, 25356, 25357, -1, 17066, 25360, 17067, -1, 17067, 25360, 25361, -1, 25361, 25362, 25363, -1, 25363, 25362, 25364, -1, 17112, 25365, 17116, -1, 25356, 25365, 17112, -1, 25364, 25365, 25359, -1, 25359, 25365, 25356, -1, 25366, 25367, 17066, -1, 17066, 25367, 25360, -1, 25361, 25368, 25362, -1, 25360, 25368, 25361, -1, 21997, 25369, 21999, -1, 25370, 25369, 25366, -1, 25366, 25369, 25367, -1, 21999, 25369, 25370, -1, 17116, 25371, 17118, -1, 25365, 25371, 17116, -1, 25362, 25371, 25364, -1, 19017, 17108, 17110, -1, 25364, 25371, 25365, -1, 25367, 25372, 25360, -1, 25360, 25372, 25368, -1, 17118, 25373, 17092, -1, 25371, 25373, 17118, -1, 25368, 25373, 25362, -1, 25362, 25373, 25371, -1, 21033, 21999, 25370, -1, 21994, 25374, 21997, -1, 21997, 25374, 25369, -1, 25369, 25374, 25367, -1, 25367, 25374, 25372, -1, 17092, 25375, 17091, -1, 25373, 25375, 17092, -1, 25372, 25375, 25368, -1, 25368, 25375, 25373, -1, 21992, 25376, 21994, -1, 25372, 25376, 25375, -1, 21994, 25376, 25374, -1, 17091, 25376, 21992, -1, 25374, 25376, 25372, -1, 25375, 25376, 17091, -1, 21992, 17106, 17091, -1, 17074, 25377, 17076, -1, 17076, 25377, 19026, -1, 17072, 25378, 17074, -1, 17074, 25378, 25377, -1, 19026, 25357, 19023, -1, 19023, 25357, 19016, -1, 25377, 25357, 19026, -1, 17070, 25363, 17072, -1, 17072, 25363, 25378, -1, 25377, 25359, 25357, -1, 25378, 25359, 25377, -1, 19016, 25358, 19017, -1, 25357, 25358, 19016, -1, 19017, 25358, 17108, -1, 17067, 25361, 17070, -1, 17070, 25361, 25363, -1, 25363, 25364, 25378, -1, 25378, 25364, 25359, -1, 21035, 21033, 25379, -1, 25379, 25370, 25380, -1, 21033, 25370, 25379, -1, 25380, 25366, 17068, -1, 25370, 25366, 25380, -1, 25366, 17066, 17068, -1, 19151, 22167, 20041, -1, 18961, 17075, 17077, -1, 18961, 17073, 17075, -1, 22165, 25379, 25380, -1, 22165, 21035, 25379, -1, 18668, 25381, 18670, -1, 18670, 25381, 18959, -1, 18959, 25381, 18961, -1, 18666, 25382, 18668, -1, 25381, 25382, 18961, -1, 18668, 25382, 25381, -1, 18664, 25383, 18666, -1, 18666, 25383, 25382, -1, 18662, 25384, 18664, -1, 18664, 25384, 25383, -1, 18660, 25385, 18662, -1, 18662, 25385, 25384, -1, 20044, 25386, 18660, -1, 18660, 25386, 25385, -1, 22165, 25387, 22167, -1, 20041, 25387, 20044, -1, 20044, 25387, 25386, -1, 22167, 25387, 20041, -1, 25386, 25387, 22165, -1, 17069, 25388, 17068, -1, 17071, 25388, 17069, -1, 17073, 25388, 17071, -1, 17068, 25388, 25380, -1, 25383, 25388, 25382, -1, 25384, 25388, 25383, -1, 25386, 25388, 25385, -1, 25385, 25388, 25384, -1, 18961, 25388, 17073, -1, 22165, 25388, 25386, -1, 25382, 25388, 18961, -1, 25380, 25388, 22165, -1, 21119, 21118, 25389, -1, 25390, 25391, 25392, -1, 25390, 25393, 25391, -1, 25390, 25389, 25393, -1, 25390, 21119, 25389, -1, 25394, 25395, 25396, -1, 25394, 25397, 25395, -1, 25394, 25398, 25397, -1, 25394, 25392, 25398, -1, 25394, 25390, 25392, -1, 25399, 25400, 25401, -1, 25399, 25396, 25400, -1, 25399, 25394, 25396, -1, 25402, 25403, 25404, -1, 25402, 25401, 25403, -1, 25402, 25399, 25401, -1, 25405, 25402, 25404, -1, 25406, 25404, 21126, -1, 25406, 25405, 25404, -1, 21123, 25406, 21126, -1, 25407, 25390, 25394, -1, 25407, 25394, 25408, -1, 25409, 25410, 25411, -1, 21125, 25406, 21123, -1, 25409, 25408, 25410, -1, 25412, 17061, 17059, -1, 25412, 25411, 25413, -1, 25412, 25413, 25414, -1, 25412, 25414, 17061, -1, 25415, 21119, 25390, -1, 25415, 21232, 21119, -1, 25415, 25390, 25407, -1, 25416, 25407, 25408, -1, 25416, 25408, 25409, -1, 25417, 17059, 17057, -1, 25417, 25412, 17059, -1, 25417, 25409, 25411, -1, 25417, 25411, 25412, -1, 17065, 21172, 21171, -1, 25418, 21234, 21232, -1, 25418, 21232, 25415, -1, 25418, 25415, 25407, -1, 25418, 25407, 25416, -1, 25419, 17057, 17055, -1, 25419, 25417, 17057, -1, 25419, 25416, 25409, -1, 25419, 25409, 25417, -1, 25420, 17055, 17052, -1, 25420, 21237, 21234, -1, 25420, 25416, 25419, -1, 25420, 21234, 25418, -1, 25420, 17052, 21237, -1, 25420, 25419, 17055, -1, 25420, 25418, 25416, -1, 17051, 21237, 17052, -1, 25421, 25405, 25406, -1, 25421, 25406, 21125, -1, 25422, 25402, 25405, -1, 25422, 25405, 25421, -1, 25423, 21125, 21174, -1, 25423, 25421, 21125, -1, 25410, 25399, 25402, -1, 25410, 25402, 25422, -1, 25413, 25421, 25423, -1, 25413, 25422, 25421, -1, 25424, 21174, 21172, -1, 25424, 17065, 17063, -1, 25424, 21172, 17065, -1, 25424, 25423, 21174, -1, 25408, 25394, 25399, -1, 25408, 25399, 25410, -1, 25411, 25422, 25413, -1, 25411, 25410, 25422, -1, 25414, 17063, 17061, -1, 25414, 25413, 25423, -1, 25414, 25424, 17063, -1, 25414, 25423, 25424, -1, 21155, 17065, 21171, -1, 21155, 17064, 17065, -1, 25425, 17058, 25426, -1, 25427, 25428, 25429, -1, 25427, 25430, 25431, -1, 25427, 25431, 25432, -1, 25427, 25432, 25428, -1, 25433, 21186, 21188, -1, 25434, 25435, 25436, -1, 25433, 25437, 25438, -1, 25433, 25438, 25439, -1, 25433, 21188, 25437, -1, 25434, 25426, 25435, -1, 25440, 25429, 25441, -1, 25440, 25427, 25429, -1, 25440, 25430, 25427, -1, 21142, 17064, 21155, -1, 25442, 25436, 25443, -1, 25440, 25439, 25430, -1, 25442, 25443, 25444, -1, 25445, 25441, 21182, -1, 25445, 21184, 21186, -1, 25445, 21182, 21184, -1, 25446, 21130, 21136, -1, 25445, 25440, 25441, -1, 25445, 21186, 25433, -1, 25445, 25433, 25439, -1, 25445, 25439, 25440, -1, 25446, 25444, 21130, -1, 25447, 17054, 17056, -1, 25447, 17056, 25425, -1, 25448, 25425, 25426, -1, 25448, 25426, 25434, -1, 25449, 25436, 25442, -1, 25449, 25434, 25436, -1, 25450, 25444, 25446, -1, 25450, 25442, 25444, -1, 25451, 17050, 17054, -1, 21194, 17053, 17050, -1, 25451, 21194, 17050, -1, 25451, 17054, 25447, -1, 25452, 21136, 21140, -1, 25452, 25446, 21136, -1, 25453, 25447, 25425, -1, 25453, 25425, 25448, -1, 25454, 25448, 25434, -1, 25454, 25434, 25449, -1, 25455, 25449, 25442, -1, 25455, 25442, 25450, -1, 25456, 25446, 25452, -1, 25456, 25450, 25446, -1, 25457, 21192, 21194, -1, 25457, 25447, 25453, -1, 25457, 21194, 25451, -1, 25457, 25451, 25447, -1, 25458, 21140, 21154, -1, 25458, 25459, 25460, -1, 25458, 21154, 25459, -1, 25458, 25452, 21140, -1, 25461, 25453, 25448, -1, 25461, 25448, 25454, -1, 25462, 25454, 25449, -1, 25462, 25449, 25455, -1, 25431, 25455, 25450, -1, 25463, 17062, 17064, -1, 25463, 21142, 21138, -1, 25431, 25450, 25456, -1, 25463, 17064, 21142, -1, 25464, 25456, 25452, -1, 25464, 25458, 25460, -1, 25435, 17060, 17062, -1, 25464, 25460, 25465, -1, 25464, 25452, 25458, -1, 25466, 21192, 25457, -1, 25466, 25457, 25453, -1, 25435, 17062, 25463, -1, 25466, 21190, 21192, -1, 25466, 25453, 25461, -1, 25438, 25454, 25462, -1, 25443, 21138, 21134, -1, 25438, 25461, 25454, -1, 25443, 25463, 21138, -1, 25426, 17058, 17060, -1, 25426, 17060, 25435, -1, 25430, 25455, 25431, -1, 25430, 25462, 25455, -1, 25432, 25464, 25465, -1, 25432, 25456, 25464, -1, 25432, 25431, 25456, -1, 25436, 25435, 25463, -1, 25432, 25465, 25428, -1, 25437, 25461, 25438, -1, 25436, 25463, 25443, -1, 25437, 21188, 21190, -1, 25437, 25466, 25461, -1, 25444, 21134, 21130, -1, 25437, 21190, 25466, -1, 25444, 25443, 21134, -1, 25439, 25438, 25462, -1, 25439, 25462, 25430, -1, 25425, 17056, 17058, -1, 21197, 21182, 25441, -1, 25467, 25441, 25429, -1, 25467, 21197, 25441, -1, 25468, 25429, 25428, -1, 25468, 25467, 25429, -1, 25469, 25428, 25465, -1, 25469, 25468, 25428, -1, 25470, 25465, 25460, -1, 25470, 25469, 25465, -1, 25471, 25460, 25459, -1, 25471, 25470, 25460, -1, 25472, 25459, 21154, -1, 25472, 25471, 25459, -1, 21158, 25472, 21154, -1, 25473, 21128, 25474, -1, 25473, 25475, 21169, -1, 25476, 25468, 25469, -1, 25476, 25469, 25477, -1, 25478, 25477, 25479, -1, 25478, 25479, 25480, -1, 25481, 25480, 25482, -1, 25481, 25482, 25483, -1, 25484, 25485, 25486, -1, 25484, 25483, 25475, -1, 25484, 25475, 25473, -1, 25484, 25473, 25485, -1, 25487, 25467, 25468, -1, 25487, 25468, 25476, -1, 25487, 21791, 25467, -1, 25488, 25477, 25478, -1, 25488, 25476, 25477, -1, 25489, 25478, 25480, -1, 25489, 25480, 25481, -1, 25490, 25486, 25491, -1, 25490, 25483, 25484, -1, 25490, 25484, 25486, -1, 25490, 25481, 25483, -1, 25492, 21793, 21791, -1, 25492, 21791, 25487, -1, 25492, 25487, 25476, -1, 25492, 25476, 25488, -1, 25493, 25488, 25478, -1, 25493, 25478, 25489, -1, 21791, 21197, 25467, -1, 25494, 25491, 25495, -1, 25494, 25490, 25491, -1, 25494, 25489, 25481, -1, 25494, 25481, 25490, -1, 25496, 21794, 21793, -1, 25496, 25488, 25493, -1, 25496, 21793, 25492, -1, 25496, 25492, 25488, -1, 25497, 25493, 25489, -1, 25497, 25494, 25495, -1, 25497, 25495, 25498, -1, 25497, 25489, 25494, -1, 25499, 21794, 25496, -1, 25499, 25497, 25498, -1, 25499, 21796, 21794, -1, 25499, 25498, 21796, -1, 25499, 25496, 25493, -1, 25499, 25493, 25497, -1, 21177, 21796, 25498, -1, 25500, 25472, 21158, -1, 25500, 21161, 21163, -1, 25500, 21158, 21161, -1, 25501, 25471, 25472, -1, 25501, 25472, 25500, -1, 25502, 21163, 21166, -1, 25502, 25500, 21163, -1, 25479, 25470, 25471, -1, 25479, 25471, 25501, -1, 25482, 25500, 25502, -1, 25482, 25501, 25500, -1, 25475, 21166, 21169, -1, 25475, 25502, 21166, -1, 25477, 25469, 25470, -1, 25477, 25470, 25479, -1, 25480, 25479, 25501, -1, 25480, 25501, 25482, -1, 25483, 25482, 25502, -1, 25483, 25502, 25475, -1, 25473, 21169, 21128, -1, 25473, 25474, 25485, -1, 21179, 21177, 25498, -1, 22905, 25498, 25495, -1, 22905, 21179, 25498, -1, 22906, 25495, 25491, -1, 22906, 22905, 25495, -1, 22904, 25491, 25486, -1, 22904, 22906, 25491, -1, 22903, 25486, 25485, -1, 22903, 22904, 25486, -1, 22902, 25485, 25474, -1, 22902, 22903, 25485, -1, 22901, 22902, 25474, -1, 22900, 25474, 21128, -1, 22900, 22901, 25474, -1, 21151, 22900, 21128, -1, 25503, 25504, 25505, -1, 20573, 25506, 23098, -1, 25404, 25507, 25508, -1, 20574, 25506, 20573, -1, 23098, 25506, 25509, -1, 25509, 25506, 25510, -1, 25510, 25506, 25504, -1, 25504, 25506, 20574, -1, 25511, 25512, 20577, -1, 25513, 25512, 25511, -1, 20577, 25512, 20576, -1, 25508, 25514, 25515, -1, 25513, 25516, 25512, -1, 25507, 25514, 25508, -1, 20576, 25516, 20575, -1, 20575, 25516, 20574, -1, 25401, 25517, 25403, -1, 25505, 25516, 25513, -1, 20574, 25516, 25504, -1, 25504, 25516, 25505, -1, 25512, 25516, 20576, -1, 25403, 25517, 25507, -1, 20584, 25518, 20580, -1, 25514, 25518, 25515, -1, 21126, 25404, 25519, -1, 25520, 25518, 20584, -1, 25515, 25518, 25520, -1, 25507, 25521, 25514, -1, 25519, 20585, 25522, -1, 25517, 25521, 25507, -1, 25522, 20585, 25523, -1, 25523, 20585, 25524, -1, 25524, 20585, 25525, -1, 25400, 25526, 25401, -1, 25525, 20585, 20582, -1, 25401, 25526, 25517, -1, 20580, 25527, 20579, -1, 25514, 25527, 25518, -1, 25518, 25527, 20580, -1, 25521, 25527, 25514, -1, 25396, 25528, 25400, -1, 25400, 25528, 25526, -1, 25517, 25529, 25521, -1, 25526, 25529, 25517, -1, 25395, 25530, 25396, -1, 25397, 25530, 25395, -1, 25396, 25530, 25528, -1, 25528, 25531, 25526, -1, 25526, 25531, 25529, -1, 20579, 25532, 20578, -1, 25521, 25532, 25527, -1, 25527, 25532, 20579, -1, 25529, 25532, 25521, -1, 25530, 25533, 25528, -1, 25528, 25533, 25531, -1, 25398, 25534, 25397, -1, 25392, 25534, 25398, -1, 25397, 25534, 25530, -1, 25531, 25535, 25529, -1, 20578, 25535, 20577, -1, 25529, 25535, 25532, -1, 25532, 25535, 20578, -1, 25531, 25511, 25535, -1, 25533, 25511, 25531, -1, 25535, 25511, 20577, -1, 25391, 25536, 25392, -1, 25392, 25536, 25534, -1, 25530, 25537, 25533, -1, 21118, 23095, 25389, -1, 25534, 25537, 25530, -1, 25393, 25538, 25391, -1, 25391, 25538, 25536, -1, 25389, 25539, 25393, -1, 25393, 25539, 25538, -1, 23095, 25539, 25389, -1, 25536, 25503, 25534, -1, 25534, 25503, 25537, -1, 25537, 25513, 25533, -1, 25533, 25513, 25511, -1, 23098, 20570, 20573, -1, 25536, 25510, 25503, -1, 25538, 25510, 25536, -1, 25539, 25509, 25538, -1, 23095, 25509, 25539, -1, 25404, 25508, 25519, -1, 23098, 25509, 23095, -1, 25519, 25508, 20585, -1, 25538, 25509, 25510, -1, 25503, 25505, 25537, -1, 25508, 25515, 20585, -1, 20585, 25520, 20584, -1, 25537, 25505, 25513, -1, 25515, 25520, 20585, -1, 25403, 25507, 25404, -1, 25510, 25504, 25503, -1, 21126, 25519, 20092, -1, 20092, 25519, 20093, -1, 20093, 25522, 20094, -1, 25519, 25522, 20093, -1, 20094, 25523, 20095, -1, 25522, 25523, 20094, -1, 20095, 25524, 20096, -1, 25523, 25524, 20095, -1, 20096, 25525, 20097, -1, 25524, 25525, 20096, -1, 25525, 20582, 20097, -1, 21086, 21089, 25540, -1, 25541, 25542, 20631, -1, 20631, 25542, 22028, -1, 25541, 25543, 25542, -1, 25544, 25545, 25541, -1, 25541, 25545, 25543, -1, 22028, 25546, 22031, -1, 22031, 25546, 20135, -1, 20134, 25546, 20128, -1, 20135, 25546, 20134, -1, 25542, 25546, 22028, -1, 25547, 25548, 25544, -1, 25544, 25548, 25545, -1, 25540, 25549, 25547, -1, 21089, 25549, 25540, -1, 25547, 25549, 25548, -1, 20128, 25550, 20123, -1, 25542, 25550, 25546, -1, 25543, 25550, 25542, -1, 25546, 25550, 20128, -1, 21091, 25551, 21089, -1, 21089, 25551, 25549, -1, 20123, 25552, 20114, -1, 25550, 25552, 20123, -1, 25543, 25552, 25550, -1, 25545, 25552, 25543, -1, 20106, 25553, 20104, -1, 20114, 25553, 20106, -1, 25545, 25553, 25552, -1, 25552, 25553, 20114, -1, 25548, 25553, 25545, -1, 20104, 25554, 20146, -1, 25553, 25554, 20104, -1, 25549, 25554, 25548, -1, 25548, 25554, 25553, -1, 20109, 25555, 21091, -1, 20108, 25555, 20109, -1, 20146, 25555, 20108, -1, 25551, 25555, 25549, -1, 21091, 25555, 25551, -1, 25554, 25555, 20146, -1, 25549, 25555, 25554, -1, 21087, 21086, 25556, -1, 25556, 25540, 25557, -1, 21086, 25540, 25556, -1, 25557, 25547, 25558, -1, 25540, 25547, 25557, -1, 25558, 25544, 25559, -1, 25547, 25544, 25558, -1, 25559, 25541, 20639, -1, 25544, 25541, 25559, -1, 25541, 20631, 20639, -1, 25556, 23073, 21087, -1, 25557, 23073, 25556, -1, 25558, 23073, 25557, -1, 23075, 25560, 23076, -1, 23073, 25561, 23074, -1, 23073, 25562, 25561, -1, 25559, 25563, 25558, -1, 25558, 25563, 23073, -1, 23073, 25563, 25562, -1, 25562, 25563, 20637, -1, 20639, 20638, 25559, -1, 25563, 20638, 20637, -1, 25559, 20638, 25563, -1, 25561, 25564, 23074, -1, 25562, 25565, 25561, -1, 25561, 25565, 25564, -1, 20637, 25565, 25562, -1, 23074, 25566, 23075, -1, 25564, 25566, 23074, -1, 23075, 25566, 25560, -1, 20637, 25567, 25565, -1, 25560, 25568, 25569, -1, 25566, 25568, 25560, -1, 25564, 25568, 25566, -1, 25565, 25568, 25564, -1, 20637, 20636, 25567, -1, 25568, 25570, 25569, -1, 25567, 25570, 25565, -1, 25565, 25570, 25568, -1, 25569, 25571, 20635, -1, 20635, 25571, 20633, -1, 20633, 25571, 20636, -1, 25570, 25571, 25569, -1, 20636, 25571, 25567, -1, 25567, 25571, 25570, -1, 17655, 23079, 17656, -1, 17655, 23078, 23079, -1, 23079, 23077, 23081, -1, 23078, 23077, 23079, -1, 23081, 25569, 20635, -1, 23077, 25560, 23081, -1, 23081, 25560, 25569, -1, 23077, 23076, 25560, -1, 19408, 19154, 19409, -1, 19154, 19410, 19409, -1, 19153, 19137, 19154, -1, 20010, 19137, 18962, -1, 20008, 19137, 20010, -1, 19154, 19412, 19410, -1, 20005, 19137, 20008, -1, 20003, 19137, 20005, -1, 19154, 19137, 19139, -1, 18962, 19137, 19153, -1, 19154, 19303, 19412, -1, 20003, 20001, 19137, -1, 19154, 19307, 19303, -1, 20001, 19999, 19137, -1, 19154, 19647, 19307, -1, 19362, 19359, 19361, -1, 19364, 19359, 19362, -1, 19365, 19139, 19364, -1, 19367, 19139, 19365, -1, 19368, 19139, 19367, -1, 19370, 19139, 19368, -1, 19372, 19139, 19370, -1, 19636, 19139, 19372, -1, 19643, 19139, 19636, -1, 19647, 19139, 19643, -1, 19154, 19139, 19647, -1, 19364, 19139, 19359, -1, 20042, 20043, 19153, -1, 20043, 18659, 19153, -1, 18659, 18661, 19153, -1, 18661, 18663, 19153, -1, 18663, 18665, 19153, -1, 18665, 18667, 19153, -1, 18667, 18669, 19153, -1, 18669, 18671, 19153, -1, 18671, 18962, 19153, -1, 19336, 19163, 19337, -1, 19163, 19338, 19337, -1, 19162, 19146, 19163, -1, 20027, 19146, 18967, -1, 20038, 19146, 20027, -1, 19163, 19340, 19338, -1, 20036, 19146, 20038, -1, 20034, 19146, 20036, -1, 19163, 19146, 19148, -1, 18967, 19146, 19162, -1, 19163, 19298, 19340, -1, 20034, 20032, 19146, -1, 19163, 19302, 19298, -1, 20032, 20030, 19146, -1, 19163, 19676, 19302, -1, 19389, 19386, 19388, -1, 19391, 19386, 19389, -1, 19672, 19148, 19665, -1, 19676, 19148, 19672, -1, 19392, 19148, 19391, -1, 19394, 19148, 19392, -1, 19395, 19148, 19394, -1, 19397, 19148, 19395, -1, 19399, 19148, 19397, -1, 19665, 19148, 19399, -1, 19163, 19148, 19676, -1, 19391, 19148, 19386, -1, 19342, 19343, 19162, -1, 19343, 18750, 19162, -1, 18750, 18752, 19162, -1, 18752, 18754, 19162, -1, 18754, 18756, 19162, -1, 18756, 18758, 19162, -1, 18758, 18760, 19162, -1, 18760, 18762, 19162, -1, 18762, 18967, 19162, -1, 19381, 19145, 19382, -1, 19145, 19383, 19382, -1, 19145, 19385, 19383, -1, 19145, 19308, 19385, -1, 19619, 19616, 19618, -1, 19621, 19616, 19619, -1, 18820, 18816, 18815, -1, 18819, 18816, 18820, -1, 18818, 18817, 18819, -1, 18819, 18817, 18816, -1, 18818, 18813, 18817, -1, 19622, 19131, 19621, -1, 19624, 19131, 19622, -1, 19625, 19131, 19624, -1, 19627, 19131, 19625, -1, 19629, 19131, 19627, -1, 19621, 19131, 19616, -1, 19631, 19131, 19629, -1, 19632, 19131, 19631, -1, 18805, 19131, 19632, -1, 19308, 19131, 18818, -1, 18809, 19131, 18808, -1, 18812, 19131, 18809, -1, 18813, 19131, 18812, -1, 18804, 19131, 18805, -1, 18807, 19131, 18804, -1, 18808, 19131, 18807, -1, 19145, 19131, 19308, -1, 18818, 19131, 18813, -1, 19996, 19997, 19144, -1, 19997, 18672, 19144, -1, 18672, 18674, 19144, -1, 18674, 18676, 19144, -1, 18676, 18678, 19144, -1, 18678, 18680, 19144, -1, 18680, 18682, 19144, -1, 18682, 18684, 19144, -1, 18684, 18956, 19144, -1, 20022, 19129, 20024, -1, 19145, 19129, 19131, -1, 20019, 19129, 20022, -1, 20017, 19129, 20019, -1, 20024, 19129, 18956, -1, 19144, 19129, 19145, -1, 18956, 19129, 19144, -1, 20017, 20015, 19129, -1, 20015, 20013, 19129, -1, 19464, 19181, 19465, -1, 19181, 19466, 19465, -1, 19180, 19164, 19181, -1, 19992, 19164, 18977, -1, 19990, 19164, 19992, -1, 19181, 19468, 19466, -1, 19987, 19164, 19990, -1, 19985, 19164, 19987, -1, 19181, 19164, 19166, -1, 18977, 19164, 19180, -1, 19181, 19288, 19468, -1, 19985, 19983, 19164, -1, 19181, 19292, 19288, -1, 19983, 19981, 19164, -1, 19181, 19734, 19292, -1, 19416, 19413, 19415, -1, 19418, 19413, 19416, -1, 19730, 19166, 19723, -1, 19734, 19166, 19730, -1, 19419, 19166, 19418, -1, 19421, 19166, 19419, -1, 19422, 19166, 19421, -1, 19424, 19166, 19422, -1, 19426, 19166, 19424, -1, 19723, 19166, 19426, -1, 19181, 19166, 19734, -1, 19418, 19166, 19413, -1, 19960, 19961, 19180, -1, 19961, 18698, 19180, -1, 18698, 18700, 19180, -1, 18700, 18702, 19180, -1, 18702, 18704, 19180, -1, 18704, 18706, 19180, -1, 18706, 18708, 19180, -1, 18708, 18710, 19180, -1, 18710, 18977, 19180, -1, 19435, 19172, 19436, -1, 19172, 19437, 19436, -1, 19171, 19155, 19172, -1, 19356, 19155, 18973, -1, 19354, 19155, 19356, -1, 19172, 19439, 19437, -1, 19351, 19155, 19354, -1, 19349, 19155, 19351, -1, 19172, 19155, 19157, -1, 18973, 19155, 19171, -1, 19172, 19293, 19439, -1, 19349, 19347, 19155, -1, 19172, 19297, 19293, -1, 19347, 19345, 19155, -1, 19172, 19705, 19297, -1, 19317, 19314, 19316, -1, 19319, 19314, 19317, -1, 19320, 19157, 19319, -1, 19322, 19157, 19320, -1, 19323, 19157, 19322, -1, 19325, 19157, 19323, -1, 19327, 19157, 19325, -1, 19694, 19157, 19327, -1, 19701, 19157, 19694, -1, 19705, 19157, 19701, -1, 19172, 19157, 19705, -1, 19319, 19157, 19314, -1, 19978, 19979, 19171, -1, 19979, 18685, 19171, -1, 18685, 18687, 19171, -1, 18687, 18689, 19171, -1, 18689, 18691, 19171, -1, 18691, 18693, 19171, -1, 18693, 18695, 19171, -1, 18695, 18697, 19171, -1, 18697, 18973, 19171, -1, 19943, 18711, 19189, -1, 18711, 18713, 19189, -1, 19491, 19190, 19492, -1, 18713, 18715, 19189, -1, 18715, 18717, 19189, -1, 19190, 19493, 19492, -1, 18717, 18719, 19189, -1, 18719, 18721, 19189, -1, 19190, 19495, 19493, -1, 18721, 18723, 19189, -1, 19190, 19260, 19495, -1, 18723, 18983, 19189, -1, 19441, 18821, 19442, -1, 19266, 18821, 19441, -1, 19189, 19173, 19190, -1, 18983, 19173, 19189, -1, 19974, 19173, 18983, -1, 19972, 19173, 19974, -1, 19969, 19173, 19972, -1, 19967, 19173, 19969, -1, 19190, 19173, 19175, -1, 19967, 19965, 19173, -1, 19965, 19963, 19173, -1, 19447, 19444, 19446, -1, 19449, 19444, 19447, -1, 19260, 19175, 19266, -1, 19450, 19175, 19449, -1, 19452, 19175, 19450, -1, 19453, 19175, 19452, -1, 19455, 19175, 19453, -1, 19457, 19175, 19455, -1, 19459, 19175, 19457, -1, 19460, 19175, 19459, -1, 18826, 19175, 19460, -1, 18821, 19175, 18826, -1, 19190, 19175, 19260, -1, 19266, 19175, 18821, -1, 19449, 19175, 19444, -1, 19942, 19943, 19189, -1, 19497, 19199, 19498, -1, 19199, 19499, 19498, -1, 19198, 19182, 19199, -1, 19956, 19182, 18990, -1, 19954, 19182, 19956, -1, 19199, 19501, 19499, -1, 19951, 19182, 19954, -1, 19949, 19182, 19951, -1, 19199, 19182, 19184, -1, 18990, 19182, 19198, -1, 19199, 19268, 19501, -1, 19949, 19947, 19182, -1, 19199, 19272, 19268, -1, 19947, 19945, 19182, -1, 19199, 19763, 19272, -1, 19472, 19469, 19471, -1, 19474, 19469, 19472, -1, 19759, 19184, 19752, -1, 19763, 19184, 19759, -1, 19475, 19184, 19474, -1, 19477, 19184, 19475, -1, 19478, 19184, 19477, -1, 19480, 19184, 19478, -1, 19482, 19184, 19480, -1, 19752, 19184, 19482, -1, 19199, 19184, 19763, -1, 19474, 19184, 19469, -1, 19924, 19925, 19198, -1, 19925, 18724, 19198, -1, 18724, 18726, 19198, -1, 18726, 18728, 19198, -1, 18728, 18730, 19198, -1, 18730, 18732, 19198, -1, 18732, 18734, 19198, -1, 18734, 18736, 19198, -1, 18736, 18990, 19198, -1, 18739, 18741, 19207, -1, 18741, 18743, 19207, -1, 18743, 18745, 19207, -1, 18745, 18747, 19207, -1, 19525, 19208, 19526, -1, 18747, 18749, 19207, -1, 18749, 18996, 19207, -1, 19208, 19527, 19526, -1, 19208, 19529, 19527, -1, 19208, 19273, 19529, -1, 19208, 19277, 19273, -1, 19208, 19795, 19277, -1, 18996, 19191, 19207, -1, 19207, 19191, 19208, -1, 19938, 19191, 18996, -1, 19936, 19191, 19938, -1, 19933, 19191, 19936, -1, 19931, 19191, 19933, -1, 19208, 19191, 19193, -1, 19931, 19929, 19191, -1, 19929, 19927, 19191, -1, 19505, 19502, 19504, -1, 19507, 19502, 19505, -1, 19791, 19193, 19783, -1, 19795, 19193, 19791, -1, 19508, 19193, 19507, -1, 19510, 19193, 19508, -1, 19511, 19193, 19510, -1, 19513, 19193, 19511, -1, 19515, 19193, 19513, -1, 19516, 19193, 19515, -1, 19783, 19193, 19780, -1, 19780, 19193, 19516, -1, 19208, 19193, 19795, -1, 19507, 19193, 19502, -1, 19906, 19907, 19207, -1, 19907, 18737, 19207, -1, 18737, 18739, 19207, -1, 18765, 18767, 19212, -1, 18767, 18769, 19212, -1, 18769, 18771, 19212, -1, 18771, 18773, 19212, -1, 19583, 19213, 19584, -1, 18773, 18775, 19212, -1, 18775, 18912, 19212, -1, 19213, 19585, 19584, -1, 19213, 19587, 19585, -1, 19213, 19278, 19587, -1, 19213, 19282, 19278, -1, 19213, 19827, 19282, -1, 18912, 19200, 19212, -1, 19212, 19200, 19213, -1, 19920, 19200, 18912, -1, 19918, 19200, 19920, -1, 19915, 19200, 19918, -1, 19913, 19200, 19915, -1, 19213, 19200, 19202, -1, 19913, 19911, 19200, -1, 19911, 19909, 19200, -1, 19533, 19530, 19532, -1, 19535, 19530, 19533, -1, 19823, 19202, 19816, -1, 19827, 19202, 19823, -1, 19536, 19202, 19535, -1, 19538, 19202, 19536, -1, 19539, 19202, 19538, -1, 19541, 19202, 19539, -1, 19543, 19202, 19541, -1, 19544, 19202, 19543, -1, 19816, 19202, 19812, -1, 19812, 19202, 19544, -1, 19213, 19202, 19827, -1, 19535, 19202, 19530, -1, 19237, 19238, 19212, -1, 19238, 18763, 19212, -1, 18763, 18765, 19212, -1, 19589, 19076, 19590, -1, 19076, 19591, 19590, -1, 19251, 19078, 19071, -1, 19249, 19078, 19251, -1, 19246, 19078, 19249, -1, 19076, 19593, 19591, -1, 19244, 19078, 19246, -1, 19075, 19078, 19076, -1, 19076, 19078, 19080, -1, 19071, 19078, 19075, -1, 19076, 19283, 19593, -1, 19244, 19242, 19078, -1, 19076, 19287, 19283, -1, 19242, 19240, 19078, -1, 19076, 19888, 19287, -1, 19564, 19561, 19563, -1, 19566, 19561, 19564, -1, 19567, 19080, 19566, -1, 19569, 19080, 19567, -1, 19570, 19080, 19569, -1, 19572, 19080, 19570, -1, 19574, 19080, 19572, -1, 19877, 19080, 19574, -1, 19884, 19080, 19877, -1, 19888, 19080, 19884, -1, 19076, 19080, 19888, -1, 19566, 19080, 19561, -1, 19233, 19234, 19075, -1, 19234, 18776, 19075, -1, 18776, 18778, 19075, -1, 18778, 18780, 19075, -1, 18780, 18782, 19075, -1, 18782, 18784, 19075, -1, 18784, 18786, 19075, -1, 18786, 18788, 19075, -1, 18788, 19071, 19075, -1, 19216, 18789, 19092, -1, 18789, 18791, 19092, -1, 18791, 18793, 19092, -1, 18793, 18795, 19092, -1, 18795, 18797, 19092, -1, 18797, 18799, 19092, -1, 18799, 18801, 19092, -1, 19555, 19257, 19553, -1, 19556, 19257, 19555, -1, 19559, 19257, 19556, -1, 19558, 19257, 19559, -1, 19105, 19257, 19558, -1, 19105, 19259, 19257, -1, 19105, 19859, 19259, -1, 19092, 19133, 19105, -1, 18801, 19133, 19092, -1, 18933, 19133, 18801, -1, 19229, 19133, 18933, -1, 19227, 19133, 19229, -1, 19224, 19133, 19227, -1, 19222, 19133, 19224, -1, 19105, 19133, 19135, -1, 19222, 19220, 19133, -1, 19220, 19218, 19133, -1, 19597, 19594, 19596, -1, 19599, 19594, 19597, -1, 19600, 19135, 19599, -1, 19602, 19135, 19600, -1, 19603, 19135, 19602, -1, 19605, 19135, 19603, -1, 19607, 19135, 19605, -1, 19608, 19135, 19607, -1, 19847, 19135, 19844, -1, 19844, 19135, 19608, -1, 19855, 19135, 19847, -1, 19859, 19135, 19855, -1, 19105, 19135, 19859, -1, 19599, 19135, 19594, -1, 19215, 19216, 19092, -1, 25572, 25573, 25574, -1, 25572, 25575, 25573, -1, 25576, 25577, 25578, -1, 25577, 25579, 25578, -1, 25578, 25580, 25581, -1, 25579, 25580, 25578, -1, 25581, 25582, 25583, -1, 25580, 25582, 25581, -1, 25584, 25585, 25586, -1, 25586, 25585, 25587, -1, 25588, 25589, 25590, -1, 25587, 25589, 25591, -1, 25591, 25589, 25592, -1, 25593, 25594, 25595, -1, 25592, 25589, 25588, -1, 25596, 25597, 25598, -1, 25599, 25597, 25600, -1, 25598, 25597, 25599, -1, 25600, 25597, 25601, -1, 25601, 25602, 25584, -1, 25584, 25602, 25585, -1, 25590, 25603, 25604, -1, 25587, 25603, 25589, -1, 25589, 25603, 25590, -1, 25585, 25603, 25587, -1, 25605, 25606, 25596, -1, 25596, 25606, 25597, -1, 25601, 25606, 25602, -1, 25597, 25606, 25601, -1, 25604, 25607, 25608, -1, 25603, 25607, 25604, -1, 25602, 25607, 25585, -1, 25585, 25607, 25603, -1, 25608, 25609, 25610, -1, 25611, 25609, 25605, -1, 25605, 25609, 25606, -1, 25610, 25609, 25611, -1, 25607, 25609, 25608, -1, 25606, 25609, 25602, -1, 25602, 25609, 25607, -1, 25611, 25612, 25610, -1, 25613, 25614, 25615, -1, 25595, 25614, 25613, -1, 25594, 25614, 25595, -1, 25616, 25617, 25594, -1, 25594, 25617, 25614, -1, 25614, 25618, 25615, -1, 25619, 25586, 25616, -1, 25616, 25586, 25617, -1, 25617, 25591, 25614, -1, 25614, 25591, 25618, -1, 25620, 25621, 25622, -1, 25623, 25621, 25620, -1, 25615, 25621, 25623, -1, 25618, 25621, 25615, -1, 25624, 25584, 25619, -1, 25619, 25584, 25586, -1, 25586, 25587, 25617, -1, 25617, 25587, 25591, -1, 25622, 25592, 25588, -1, 25618, 25592, 25621, -1, 25621, 25592, 25622, -1, 25591, 25592, 25618, -1, 25600, 25601, 25624, -1, 25624, 25601, 25584, -1, 25625, 25626, 25627, -1, 25627, 25626, 25628, -1, 25628, 25629, 25630, -1, 25626, 25629, 25628, -1, 25630, 25631, 25632, -1, 25629, 25631, 25630, -1, 25633, 25634, 25635, -1, 25635, 25634, 25636, -1, 25636, 25637, 25638, -1, 25634, 25637, 25636, -1, 25637, 25639, 25638, -1, 25640, 25641, 25642, -1, 25642, 25641, 25643, -1, 25644, 25645, 25646, -1, 25647, 25645, 25644, -1, 25648, 25649, 25650, -1, 25643, 25645, 25651, -1, 25651, 25645, 25647, -1, 25652, 25653, 25654, -1, 25655, 25653, 25656, -1, 25654, 25653, 25655, -1, 25656, 25653, 25657, -1, 25657, 25658, 25640, -1, 25640, 25658, 25641, -1, 25646, 25659, 25660, -1, 25645, 25659, 25646, -1, 25641, 25659, 25643, -1, 25643, 25659, 25645, -1, 25661, 25662, 25652, -1, 25652, 25662, 25653, -1, 25657, 25662, 25658, -1, 25653, 25662, 25657, -1, 25660, 25663, 25664, -1, 25659, 25663, 25660, -1, 25658, 25663, 25641, -1, 25641, 25663, 25659, -1, 25664, 25665, 25666, -1, 25667, 25665, 25661, -1, 25661, 25665, 25662, -1, 25666, 25665, 25667, -1, 25663, 25665, 25664, -1, 25662, 25665, 25658, -1, 25658, 25665, 25663, -1, 25667, 25668, 25666, -1, 25669, 25670, 25671, -1, 25650, 25670, 25669, -1, 25649, 25670, 25650, -1, 25672, 25673, 25649, -1, 25649, 25673, 25670, -1, 25670, 25674, 25671, -1, 25675, 25642, 25672, -1, 25672, 25642, 25673, -1, 25673, 25651, 25670, -1, 25670, 25651, 25674, -1, 25676, 25677, 25678, -1, 25679, 25677, 25676, -1, 25671, 25677, 25679, -1, 25674, 25677, 25671, -1, 25680, 25640, 25675, -1, 25675, 25640, 25642, -1, 25642, 25643, 25673, -1, 25673, 25643, 25651, -1, 25678, 25647, 25644, -1, 25674, 25647, 25677, -1, 25651, 25647, 25674, -1, 25677, 25647, 25678, -1, 25656, 25657, 25680, -1, 25680, 25657, 25640, -1, 25681, 25682, 25683, -1, 25683, 25682, 25684, -1, 25684, 25685, 25686, -1, 25682, 25685, 25684, -1, 25686, 25687, 25688, -1, 25685, 25687, 25686, -1, 25689, 25690, 25691, -1, 25691, 25690, 25692, -1, 25693, 25694, 25695, -1, 25696, 25694, 25693, -1, 25692, 25694, 25697, -1, 25698, 25699, 25700, -1, 25697, 25694, 25696, -1, 25701, 25702, 25703, -1, 25704, 25702, 25705, -1, 25703, 25702, 25704, -1, 25705, 25702, 25706, -1, 25706, 25707, 25689, -1, 25689, 25707, 25690, -1, 25695, 25708, 25709, -1, 25694, 25708, 25695, -1, 25690, 25708, 25692, -1, 25692, 25708, 25694, -1, 25710, 25711, 25701, -1, 25701, 25711, 25702, -1, 25706, 25711, 25707, -1, 25702, 25711, 25706, -1, 25709, 25712, 25713, -1, 25708, 25712, 25709, -1, 25707, 25712, 25690, -1, 25690, 25712, 25708, -1, 25713, 25714, 25715, -1, 25716, 25714, 25710, -1, 25710, 25714, 25711, -1, 25715, 25714, 25716, -1, 25712, 25714, 25713, -1, 25711, 25714, 25707, -1, 25707, 25714, 25712, -1, 25716, 25717, 25715, -1, 25718, 25719, 25720, -1, 25700, 25719, 25718, -1, 25699, 25719, 25700, -1, 25721, 25722, 25699, -1, 25699, 25722, 25719, -1, 25719, 25723, 25720, -1, 25724, 25691, 25721, -1, 25721, 25691, 25722, -1, 25722, 25697, 25719, -1, 25719, 25697, 25723, -1, 25725, 25726, 25727, -1, 25728, 25726, 25725, -1, 25720, 25726, 25728, -1, 25723, 25726, 25720, -1, 25729, 25689, 25724, -1, 25724, 25689, 25691, -1, 25691, 25692, 25722, -1, 25722, 25692, 25697, -1, 25727, 25696, 25693, -1, 25723, 25696, 25726, -1, 25697, 25696, 25723, -1, 25726, 25696, 25727, -1, 25705, 25706, 25729, -1, 25729, 25706, 25689, -1, 25730, 25731, 25732, -1, 25732, 25731, 25733, -1, 25733, 25734, 25735, -1, 25735, 25734, 25736, -1, 25731, 25734, 25733, -1, 25734, 25737, 25736, -1, 25738, 25739, 25740, -1, 25740, 25739, 25741, -1, 25742, 25743, 25744, -1, 25745, 25743, 25742, -1, 25741, 25743, 25746, -1, 25747, 25748, 25749, -1, 25746, 25743, 25745, -1, 25750, 25751, 25752, -1, 25753, 25751, 25754, -1, 25752, 25751, 25753, -1, 25754, 25751, 25755, -1, 25755, 25756, 25738, -1, 25738, 25756, 25739, -1, 25744, 25757, 25758, -1, 25743, 25757, 25744, -1, 25739, 25757, 25741, -1, 25741, 25757, 25743, -1, 25759, 25760, 25750, -1, 25750, 25760, 25751, -1, 25755, 25760, 25756, -1, 25751, 25760, 25755, -1, 25758, 25761, 25762, -1, 25757, 25761, 25758, -1, 25756, 25761, 25739, -1, 25739, 25761, 25757, -1, 25762, 25763, 25764, -1, 25765, 25763, 25759, -1, 25759, 25763, 25760, -1, 25764, 25763, 25765, -1, 25761, 25763, 25762, -1, 25760, 25763, 25756, -1, 25756, 25763, 25761, -1, 25765, 25766, 25764, -1, 25767, 25768, 25769, -1, 25749, 25768, 25767, -1, 25748, 25768, 25749, -1, 25770, 25771, 25748, -1, 25748, 25771, 25768, -1, 25768, 25772, 25769, -1, 25773, 25740, 25770, -1, 25770, 25740, 25771, -1, 25771, 25746, 25768, -1, 25768, 25746, 25772, -1, 25774, 25775, 25776, -1, 25777, 25775, 25774, -1, 25769, 25775, 25777, -1, 25772, 25775, 25769, -1, 25778, 25738, 25773, -1, 25773, 25738, 25740, -1, 25740, 25741, 25771, -1, 25771, 25741, 25746, -1, 25776, 25745, 25742, -1, 25772, 25745, 25775, -1, 25746, 25745, 25772, -1, 25775, 25745, 25776, -1, 25754, 25755, 25778, -1, 25778, 25755, 25738, -1, 25779, 25780, 25781, -1, 25781, 25782, 25783, -1, 25780, 25782, 25781, -1, 25783, 25784, 25785, -1, 25782, 25784, 25783, -1, 25784, 25786, 25785, -1, 25787, 25788, 25789, -1, 25789, 25788, 25790, -1, 25791, 25792, 25793, -1, 25794, 25792, 25791, -1, 25795, 25796, 25797, -1, 25790, 25792, 25798, -1, 25798, 25792, 25794, -1, 25799, 25800, 25801, -1, 25802, 25800, 25803, -1, 25801, 25800, 25802, -1, 25803, 25800, 25804, -1, 25804, 25805, 25787, -1, 25787, 25805, 25788, -1, 25793, 25806, 25807, -1, 25792, 25806, 25793, -1, 25788, 25806, 25790, -1, 25790, 25806, 25792, -1, 25808, 25809, 25799, -1, 25799, 25809, 25800, -1, 25804, 25809, 25805, -1, 25800, 25809, 25804, -1, 25807, 25810, 25811, -1, 25806, 25810, 25807, -1, 25805, 25810, 25788, -1, 25788, 25810, 25806, -1, 25811, 25812, 25813, -1, 25814, 25812, 25808, -1, 25808, 25812, 25809, -1, 25813, 25812, 25814, -1, 25810, 25812, 25811, -1, 25809, 25812, 25805, -1, 25805, 25812, 25810, -1, 25814, 25815, 25813, -1, 25816, 25817, 25818, -1, 25797, 25817, 25816, -1, 25796, 25817, 25797, -1, 25819, 25820, 25796, -1, 25796, 25820, 25817, -1, 25817, 25821, 25818, -1, 25822, 25789, 25819, -1, 25819, 25789, 25820, -1, 25820, 25798, 25817, -1, 25817, 25798, 25821, -1, 25823, 25824, 25825, -1, 25826, 25824, 25823, -1, 25818, 25824, 25826, -1, 25821, 25824, 25818, -1, 25827, 25787, 25822, -1, 25822, 25787, 25789, -1, 25789, 25790, 25820, -1, 25820, 25790, 25798, -1, 25825, 25794, 25791, -1, 25821, 25794, 25824, -1, 25798, 25794, 25821, -1, 25824, 25794, 25825, -1, 25803, 25804, 25827, -1, 25827, 25804, 25787, -1, 25828, 25829, 25830, -1, 25830, 25829, 25831, -1, 25831, 25832, 25833, -1, 25829, 25832, 25831, -1, 25833, 25834, 25835, -1, 25832, 25834, 25833, -1, 25836, 25837, 25838, -1, 25838, 25837, 25839, -1, 25840, 25841, 25842, -1, 25843, 25841, 25840, -1, 25844, 25845, 25846, -1, 25839, 25841, 25847, -1, 25847, 25841, 25843, -1, 25848, 25849, 25850, -1, 25851, 25849, 25852, -1, 25850, 25849, 25851, -1, 25852, 25849, 25853, -1, 25853, 25854, 25836, -1, 25836, 25854, 25837, -1, 25842, 25855, 25856, -1, 25841, 25855, 25842, -1, 25837, 25855, 25839, -1, 25839, 25855, 25841, -1, 25857, 25858, 25848, -1, 25848, 25858, 25849, -1, 25853, 25858, 25854, -1, 25849, 25858, 25853, -1, 25856, 25859, 25860, -1, 25855, 25859, 25856, -1, 25854, 25859, 25837, -1, 25837, 25859, 25855, -1, 25860, 25861, 25862, -1, 25863, 25861, 25857, -1, 25857, 25861, 25858, -1, 25862, 25861, 25863, -1, 25859, 25861, 25860, -1, 25858, 25861, 25854, -1, 25854, 25861, 25859, -1, 25863, 25864, 25862, -1, 25865, 25866, 25867, -1, 25846, 25866, 25865, -1, 25845, 25866, 25846, -1, 25868, 25869, 25845, -1, 25845, 25869, 25866, -1, 25866, 25870, 25867, -1, 25871, 25838, 25868, -1, 25868, 25838, 25869, -1, 25869, 25847, 25866, -1, 25866, 25847, 25870, -1, 25872, 25873, 25874, -1, 25875, 25873, 25872, -1, 25867, 25873, 25875, -1, 25870, 25873, 25867, -1, 25876, 25836, 25871, -1, 25871, 25836, 25838, -1, 25838, 25839, 25869, -1, 25869, 25839, 25847, -1, 25874, 25843, 25840, -1, 25870, 25843, 25873, -1, 25847, 25843, 25870, -1, 25873, 25843, 25874, -1, 25852, 25853, 25876, -1, 25876, 25853, 25836, -1, 25877, 25878, 25879, -1, 25879, 25878, 25880, -1, 25880, 25881, 25882, -1, 25878, 25881, 25880, -1, 25882, 25883, 25884, -1, 25881, 25883, 25882, -1, 25885, 25886, 25887, -1, 25887, 25886, 25888, -1, 25889, 25890, 25891, -1, 25892, 25890, 25889, -1, 25893, 25894, 25895, -1, 25888, 25890, 25896, -1, 25896, 25890, 25892, -1, 25897, 25898, 25899, -1, 25900, 25898, 25901, -1, 25899, 25898, 25900, -1, 25901, 25898, 25902, -1, 25902, 25903, 25885, -1, 25885, 25903, 25886, -1, 25891, 25904, 25905, -1, 25890, 25904, 25891, -1, 25886, 25904, 25888, -1, 25888, 25904, 25890, -1, 25906, 25907, 25897, -1, 25897, 25907, 25898, -1, 25902, 25907, 25903, -1, 25898, 25907, 25902, -1, 25905, 25908, 25909, -1, 25904, 25908, 25905, -1, 25903, 25908, 25886, -1, 25886, 25908, 25904, -1, 25909, 25910, 25911, -1, 25912, 25910, 25906, -1, 25906, 25910, 25907, -1, 25911, 25910, 25912, -1, 25908, 25910, 25909, -1, 25907, 25910, 25903, -1, 25903, 25910, 25908, -1, 25912, 25913, 25911, -1, 25914, 25915, 25916, -1, 25895, 25915, 25914, -1, 25894, 25915, 25895, -1, 25917, 25918, 25894, -1, 25894, 25918, 25915, -1, 25915, 25919, 25916, -1, 25920, 25887, 25917, -1, 25917, 25887, 25918, -1, 25918, 25896, 25915, -1, 25915, 25896, 25919, -1, 25921, 25922, 25923, -1, 25924, 25922, 25921, -1, 25916, 25922, 25924, -1, 25919, 25922, 25916, -1, 25925, 25885, 25920, -1, 25920, 25885, 25887, -1, 25887, 25888, 25918, -1, 25918, 25888, 25896, -1, 25923, 25892, 25889, -1, 25919, 25892, 25922, -1, 25896, 25892, 25919, -1, 25922, 25892, 25923, -1, 25901, 25902, 25925, -1, 25925, 25902, 25885, -1, 25926, 25927, 25928, -1, 25928, 25927, 25929, -1, 25929, 25930, 25931, -1, 25927, 25930, 25929, -1, 25931, 25932, 25933, -1, 25930, 25932, 25931, -1, 25934, 25935, 25936, -1, 25936, 25937, 25938, -1, 25935, 25937, 25936, -1, 25938, 25939, 25940, -1, 25937, 25939, 25938, -1, 25940, 25941, 25942, -1, 25939, 25941, 25940, -1, 25942, 25943, 25944, -1, 25941, 25943, 25942, -1, 25944, 25945, 25946, -1, 25943, 25945, 25944, -1, 25945, 25947, 25946, -1, 25946, 25948, 25949, -1, 25947, 25948, 25946, -1, 25950, 25951, 25952, -1, 25953, 25954, 25951, -1, 25952, 25954, 25955, -1, 25951, 25954, 25952, -1, 25953, 25956, 25954, -1, 25957, 25958, 25953, -1, 25953, 25958, 25956, -1, 25959, 25960, 25957, -1, 25957, 25960, 25958, -1, 25961, 25962, 25959, -1, 25959, 25962, 25960, -1, 25963, 25964, 25965, -1, 25966, 25967, 25964, -1, 25965, 25967, 25968, -1, 25964, 25967, 25965, -1, 25969, 25970, 25966, -1, 25966, 25970, 25967, -1, 25969, 25971, 25970, -1, 25972, 25973, 25969, -1, 25969, 25973, 25971, -1, 25974, 25975, 25972, -1, 25972, 25975, 25973, -1, 25976, 25977, 25978, -1, 25979, 25980, 25977, -1, 25978, 25980, 25981, -1, 25977, 25980, 25978, -1, 25982, 25983, 25979, -1, 25979, 25983, 25980, -1, 25982, 25984, 25983, -1, 25985, 25986, 25982, -1, 25982, 25986, 25984, -1, 25987, 25988, 25985, -1, 25985, 25988, 25986, -1, 25989, 25990, 25991, -1, 25992, 25993, 25990, -1, 25991, 25993, 25994, -1, 25990, 25993, 25991, -1, 25995, 25996, 25992, -1, 25992, 25996, 25993, -1, 25995, 25997, 25996, -1, 25998, 25999, 25995, -1, 25995, 25999, 25997, -1, 26000, 26001, 25998, -1, 25998, 26001, 25999, -1, 26002, 26003, 26004, -1, 26005, 26006, 26003, -1, 26004, 26006, 26007, -1, 26003, 26006, 26004, -1, 26008, 26009, 26005, -1, 26005, 26009, 26006, -1, 26008, 26010, 26009, -1, 26011, 26012, 26008, -1, 26008, 26012, 26010, -1, 26013, 26014, 26011, -1, 26011, 26014, 26012, -1, 26015, 26016, 26017, -1, 26018, 26019, 26016, -1, 26017, 26019, 26020, -1, 26016, 26019, 26017, -1, 26018, 26021, 26019, -1, 26022, 26023, 26018, -1, 26018, 26023, 26021, -1, 26024, 26025, 26022, -1, 26022, 26025, 26023, -1, 26026, 26027, 26024, -1, 26024, 26027, 26025, -1, 26028, 26029, 26030, -1, 26031, 26032, 26029, -1, 26030, 26032, 26033, -1, 26029, 26032, 26030, -1, 26031, 26034, 26032, -1, 26035, 26036, 26031, -1, 26031, 26036, 26034, -1, 26037, 26038, 26035, -1, 26035, 26038, 26036, -1, 26039, 26040, 26037, -1, 26037, 26040, 26038, -1, 26041, 26042, 26043, -1, 26044, 26045, 26042, -1, 26043, 26045, 26046, -1, 26042, 26045, 26043, -1, 26047, 26048, 26044, -1, 26044, 26048, 26045, -1, 26047, 26049, 26048, -1, 26050, 26051, 26047, -1, 26047, 26051, 26049, -1, 26052, 26053, 26050, -1, 26050, 26053, 26051, -1, 26054, 26055, 26056, -1, 26056, 26055, 26057, -1, 26058, 26059, 26060, -1, 26061, 26059, 26058, -1, 26057, 26059, 26062, -1, 26063, 26064, 26065, -1, 26062, 26059, 26061, -1, 26066, 26067, 26068, -1, 26069, 26067, 26070, -1, 26068, 26067, 26069, -1, 26070, 26067, 26071, -1, 26071, 26072, 26054, -1, 26054, 26072, 26055, -1, 26060, 26073, 26074, -1, 26059, 26073, 26060, -1, 26055, 26073, 26057, -1, 26057, 26073, 26059, -1, 26075, 26076, 26066, -1, 26066, 26076, 26067, -1, 26071, 26076, 26072, -1, 26067, 26076, 26071, -1, 26074, 26077, 26078, -1, 26073, 26077, 26074, -1, 26072, 26077, 26055, -1, 26055, 26077, 26073, -1, 26078, 26079, 26080, -1, 26081, 26079, 26075, -1, 26075, 26079, 26076, -1, 26080, 26079, 26081, -1, 26077, 26079, 26078, -1, 26076, 26079, 26072, -1, 26072, 26079, 26077, -1, 26081, 26082, 26080, -1, 26083, 26084, 26085, -1, 26065, 26084, 26083, -1, 26064, 26084, 26065, -1, 26086, 26087, 26064, -1, 26064, 26087, 26084, -1, 26084, 26088, 26085, -1, 26089, 26056, 26086, -1, 26086, 26056, 26087, -1, 26087, 26062, 26084, -1, 26084, 26062, 26088, -1, 26090, 26091, 26092, -1, 26093, 26091, 26090, -1, 26085, 26091, 26093, -1, 26088, 26091, 26085, -1, 26094, 26054, 26089, -1, 26089, 26054, 26056, -1, 26056, 26057, 26087, -1, 26087, 26057, 26062, -1, 26092, 26061, 26058, -1, 26088, 26061, 26091, -1, 26062, 26061, 26088, -1, 26091, 26061, 26092, -1, 26070, 26071, 26094, -1, 26094, 26071, 26054, -1, 26095, 26096, 26097, -1, 26097, 26096, 26098, -1, 26098, 26096, 26099, -1, 26096, 26100, 26099, -1, 26099, 26101, 26102, -1, 26100, 26101, 26099, -1, 26103, 26104, 26105, -1, 26106, 26107, 26104, -1, 26105, 26107, 26108, -1, 26104, 26107, 26105, -1, 26109, 26110, 26106, -1, 26106, 26110, 26107, -1, 26109, 26111, 26110, -1, 26112, 26113, 26109, -1, 26109, 26113, 26111, -1, 26114, 26115, 26112, -1, 26112, 26115, 26113, -1, 26116, 26117, 26118, -1, 26117, 26119, 26118, -1, 26118, 26120, 26121, -1, 26119, 26120, 26118, -1, 26120, 26122, 26121, -1, 26123, 26124, 26125, -1, 26123, 26126, 26124, -1, 26127, 26125, 26128, -1, 26127, 26123, 26125, -1, 26129, 26128, 26130, -1, 26129, 26127, 26128, -1, 26131, 26132, 26133, -1, 26134, 26135, 26136, -1, 26137, 26135, 26138, -1, 26139, 26135, 26134, -1, 26136, 26135, 26140, -1, 26138, 26135, 26139, -1, 26133, 26141, 26137, -1, 26137, 26141, 26135, -1, 26135, 26141, 26140, -1, 26142, 26143, 26144, -1, 26140, 26143, 26142, -1, 26133, 26143, 26141, -1, 26144, 26143, 26132, -1, 26145, 26146, 26147, -1, 26132, 26143, 26133, -1, 26148, 26146, 26145, -1, 26141, 26143, 26140, -1, 26149, 26146, 26148, -1, 26149, 26150, 26146, -1, 26140, 26151, 26136, -1, 26140, 26152, 26151, -1, 26140, 26153, 26152, -1, 26154, 26155, 26156, -1, 26146, 26155, 26154, -1, 26150, 26155, 26146, -1, 26157, 26158, 26150, -1, 26150, 26158, 26155, -1, 26156, 26159, 26160, -1, 26155, 26159, 26156, -1, 26155, 26161, 26159, -1, 26158, 26161, 26155, -1, 26159, 26161, 26160, -1, 26157, 26161, 26158, -1, 26157, 26162, 26161, -1, 26160, 26163, 26164, -1, 26165, 26166, 26167, -1, 26167, 26166, 26157, -1, 26157, 26166, 26162, -1, 26161, 26168, 26160, -1, 26160, 26168, 26163, -1, 26161, 26131, 26168, -1, 26162, 26131, 26161, -1, 26164, 26138, 26169, -1, 26163, 26138, 26164, -1, 26144, 26170, 26165, -1, 26162, 26170, 26131, -1, 26165, 26170, 26166, -1, 26166, 26170, 26162, -1, 26168, 26137, 26163, -1, 26163, 26137, 26138, -1, 26168, 26133, 26137, -1, 26131, 26133, 26168, -1, 26171, 26139, 26134, -1, 26169, 26139, 26171, -1, 26138, 26139, 26169, -1, 26144, 26132, 26170, -1, 26170, 26132, 26131, -1, 26172, 26173, 26174, -1, 26175, 26176, 26177, -1, 26178, 26172, 26179, -1, 26178, 26179, 26180, -1, 26178, 26173, 26172, -1, 26181, 26180, 26182, -1, 26181, 26183, 26173, -1, 26181, 26173, 26178, -1, 26181, 26178, 26180, -1, 26184, 26182, 26185, -1, 26184, 26186, 26183, -1, 26184, 26183, 26181, -1, 26184, 26181, 26182, -1, 26187, 26185, 26188, -1, 26187, 26188, 26189, -1, 26187, 26190, 26191, -1, 26187, 26191, 26186, -1, 26187, 26186, 26184, -1, 26187, 26184, 26185, -1, 26192, 26189, 26193, -1, 26192, 26187, 26189, -1, 26192, 26190, 26187, -1, 26194, 26193, 26195, -1, 26194, 26196, 26190, -1, 26194, 26192, 26193, -1, 26194, 26190, 26192, -1, 26197, 26195, 26198, -1, 26197, 26198, 26175, -1, 26197, 26177, 26196, -1, 26197, 26175, 26177, -1, 26197, 26194, 26195, -1, 26197, 26196, 26194, -1, 26199, 26200, 26201, -1, 26202, 26199, 26201, -1, 26203, 26199, 26202, -1, 26204, 26203, 26202, -1, 26205, 26203, 26204, -1, 26206, 26205, 26204, -1, 26207, 26205, 26206, -1, 26208, 26207, 26206, -1, 26209, 26207, 26208, -1, 26210, 26209, 26208, -1, 26211, 26212, 26209, -1, 26211, 26209, 26210, -1, 26213, 26214, 26215, -1, 26216, 26215, 26217, -1, 26216, 26213, 26215, -1, 26218, 26216, 26217, -1, 26219, 26217, 26220, -1, 26219, 26218, 26217, -1, 26221, 26222, 26223, -1, 26223, 26222, 26224, -1, 26225, 26226, 26227, -1, 26228, 26226, 26225, -1, 26229, 26230, 26231, -1, 26224, 26226, 26232, -1, 26232, 26226, 26228, -1, 26233, 26234, 26235, -1, 26236, 26234, 26237, -1, 26235, 26234, 26236, -1, 26237, 26234, 26238, -1, 26238, 26239, 26221, -1, 26221, 26239, 26222, -1, 26227, 26240, 26241, -1, 26226, 26240, 26227, -1, 26222, 26240, 26224, -1, 26224, 26240, 26226, -1, 26242, 26243, 26233, -1, 26233, 26243, 26234, -1, 26238, 26243, 26239, -1, 26234, 26243, 26238, -1, 26241, 26244, 26245, -1, 26240, 26244, 26241, -1, 26239, 26244, 26222, -1, 26222, 26244, 26240, -1, 26245, 26246, 26247, -1, 26248, 26246, 26242, -1, 26242, 26246, 26243, -1, 26247, 26246, 26248, -1, 26244, 26246, 26245, -1, 26243, 26246, 26239, -1, 26239, 26246, 26244, -1, 26248, 26249, 26247, -1, 26250, 26251, 26252, -1, 26231, 26251, 26250, -1, 26230, 26251, 26231, -1, 26253, 26254, 26230, -1, 26230, 26254, 26251, -1, 26251, 26255, 26252, -1, 26256, 26223, 26253, -1, 26253, 26223, 26254, -1, 26254, 26232, 26251, -1, 26251, 26232, 26255, -1, 26257, 26258, 26259, -1, 26260, 26258, 26257, -1, 26252, 26258, 26260, -1, 26255, 26258, 26252, -1, 26261, 26221, 26256, -1, 26256, 26221, 26223, -1, 26223, 26224, 26254, -1, 26254, 26224, 26232, -1, 26259, 26228, 26225, -1, 26255, 26228, 26258, -1, 26232, 26228, 26255, -1, 26258, 26228, 26259, -1, 26237, 26238, 26261, -1, 26261, 26238, 26221, -1, 26262, 26263, 26264, -1, 26264, 26263, 26265, -1, 26265, 26266, 26267, -1, 26263, 26266, 26265, -1, 26267, 26268, 26269, -1, 26266, 26268, 26267, -1, 26270, 26271, 26272, -1, 26272, 26273, 26274, -1, 26271, 26273, 26272, -1, 26273, 26275, 26274, -1, 26274, 26276, 26277, -1, 26275, 26276, 26274, -1, 26278, 26279, 26280, -1, 26280, 26279, 26281, -1, 26281, 26279, 26282, -1, 26279, 26283, 26282, -1, 26282, 26284, 26285, -1, 26283, 26284, 26282, -1, 26286, 26287, 26288, -1, 26288, 26289, 26290, -1, 26287, 26289, 26288, -1, 26290, 26291, 26292, -1, 26289, 26291, 26290, -1, 26291, 26293, 26292, -1, 26294, 26295, 26296, -1, 26297, 26295, 26298, -1, 26296, 26295, 26297, -1, 26298, 26299, 26300, -1, 26295, 26299, 26298, -1, 26299, 26301, 26300, -1, 26302, 26303, 26304, -1, 26304, 26303, 26305, -1, 26305, 26303, 26306, -1, 26306, 26307, 26308, -1, 26303, 26307, 26306, -1, 26307, 26309, 26308, -1, 26214, 26310, 26311, -1, 26312, 26214, 26311, -1, 26313, 26314, 26315, -1, 26316, 26313, 26315, -1, 26317, 26318, 26319, -1, 26319, 26318, 26320, -1, 26320, 26321, 26322, -1, 26318, 26321, 26320, -1, 26322, 26323, 26324, -1, 26321, 26323, 26322, -1, 26324, 26325, 26326, -1, 26323, 26325, 26324, -1, 26326, 26327, 26328, -1, 26325, 26327, 26326, -1, 26329, 26330, 26331, -1, 26329, 26332, 26330, -1, 26332, 26333, 26330, -1, 26332, 26334, 26333, -1, 26334, 26335, 26333, -1, 26334, 26336, 26335, -1, 26336, 26337, 26335, -1, 26336, 26338, 26337, -1, 26338, 26339, 26337, -1, 26338, 26340, 26339, -1, 26339, 26341, 26342, -1, 26340, 26341, 26339, -1, 26341, 26343, 26342, -1, 26341, 26344, 26343, -1, 26345, 26346, 26347, -1, 26347, 26346, 26348, -1, 26348, 26349, 26350, -1, 26346, 26349, 26348, -1, 26350, 26351, 26352, -1, 26349, 26351, 26350, -1, 26352, 26353, 26354, -1, 26351, 26353, 26352, -1, 26354, 26355, 26356, -1, 26353, 26355, 26354, -1, 26356, 26357, 26358, -1, 26355, 26357, 26356, -1, 26358, 26359, 26360, -1, 26357, 26359, 26358, -1, 26360, 26361, 26362, -1, 26359, 26361, 26360, -1, 26362, 26363, 26364, -1, 26361, 26363, 26362, -1, 26364, 26365, 26366, -1, 26363, 26365, 26364, -1, 26366, 26367, 26368, -1, 26365, 26367, 26366, -1, 26368, 26369, 26370, -1, 26367, 26369, 26368, -1, 26370, 26371, 26372, -1, 26369, 26371, 26370, -1, 26373, 26374, 26375, -1, 26375, 26374, 26376, -1, 26376, 26377, 26378, -1, 26374, 26377, 26376, -1, 26378, 26379, 26380, -1, 26377, 26379, 26378, -1, 26380, 26381, 26382, -1, 26379, 26381, 26380, -1, 26382, 26383, 26384, -1, 26381, 26383, 26382, -1, 26384, 26385, 26386, -1, 26383, 26385, 26384, -1, 26386, 26387, 26388, -1, 26385, 26387, 26386, -1, 26388, 26389, 26390, -1, 26387, 26389, 26388, -1, 26390, 26391, 26392, -1, 26389, 26391, 26390, -1, 26392, 26393, 26394, -1, 26391, 26393, 26392, -1, 26394, 26395, 26396, -1, 26393, 26395, 26394, -1, 26397, 26398, 26399, -1, 26396, 26398, 26397, -1, 26395, 26398, 26396, -1, 26398, 26400, 26399, -1, 26401, 26402, 26403, -1, 26404, 26402, 26401, -1, 26405, 26406, 26407, -1, 26403, 26402, 26408, -1, 26409, 26406, 26405, -1, 26410, 26406, 26409, -1, 26411, 26412, 26413, -1, 26414, 26406, 26410, -1, 26408, 26412, 26411, -1, 26415, 26416, 26417, -1, 26418, 26419, 26420, -1, 26421, 26419, 26422, -1, 26423, 26424, 26425, -1, 26426, 26419, 26421, -1, 26420, 26419, 26426, -1, 26413, 26424, 26423, -1, 26407, 26427, 26428, -1, 26408, 26429, 26412, -1, 26430, 26429, 26431, -1, 26406, 26427, 26407, -1, 26402, 26429, 26408, -1, 26422, 26427, 26414, -1, 26414, 26427, 26406, -1, 26431, 26429, 26402, -1, 26428, 26432, 26433, -1, 26412, 26434, 26413, -1, 26433, 26432, 26435, -1, 26436, 26432, 26418, -1, 26413, 26434, 26424, -1, 26435, 26432, 26436, -1, 26427, 26432, 26428, -1, 26419, 26432, 26422, -1, 26422, 26432, 26427, -1, 26418, 26432, 26419, -1, 26425, 26437, 26438, -1, 26424, 26437, 26425, -1, 26439, 26440, 26430, -1, 26429, 26440, 26412, -1, 26430, 26440, 26429, -1, 26412, 26440, 26434, -1, 26424, 26441, 26437, -1, 26434, 26441, 26424, -1, 26438, 26442, 26443, -1, 26437, 26442, 26438, -1, 26444, 26445, 26439, -1, 26439, 26445, 26440, -1, 26434, 26445, 26441, -1, 26440, 26445, 26434, -1, 26441, 26446, 26437, -1, 26437, 26446, 26442, -1, 26443, 26447, 26448, -1, 26442, 26447, 26443, -1, 26449, 26450, 26444, -1, 26444, 26450, 26445, -1, 26441, 26450, 26446, -1, 26445, 26450, 26441, -1, 26442, 26451, 26447, -1, 26446, 26451, 26442, -1, 26448, 26452, 26453, -1, 26447, 26452, 26448, -1, 26450, 26454, 26446, -1, 26446, 26454, 26451, -1, 26455, 26454, 26449, -1, 26449, 26454, 26450, -1, 26451, 26456, 26447, -1, 26447, 26456, 26452, -1, 26452, 26457, 26453, -1, 26453, 26457, 26458, -1, 26455, 26459, 26454, -1, 26460, 26459, 26455, -1, 26451, 26459, 26456, -1, 26454, 26459, 26451, -1, 26456, 26461, 26452, -1, 26452, 26461, 26457, -1, 26458, 26462, 26463, -1, 26457, 26462, 26458, -1, 26464, 26465, 26460, -1, 26456, 26465, 26461, -1, 26459, 26465, 26456, -1, 26460, 26465, 26459, -1, 26461, 26466, 26457, -1, 26457, 26466, 26462, -1, 26463, 26467, 26468, -1, 26462, 26467, 26463, -1, 26469, 26470, 26464, -1, 26464, 26470, 26465, -1, 26461, 26470, 26466, -1, 26465, 26470, 26461, -1, 26466, 26421, 26462, -1, 26462, 26421, 26467, -1, 26415, 26411, 26416, -1, 26468, 26414, 26410, -1, 26403, 26408, 26415, -1, 26467, 26414, 26468, -1, 26420, 26426, 26469, -1, 26415, 26408, 26411, -1, 26469, 26426, 26470, -1, 26466, 26426, 26421, -1, 26470, 26426, 26466, -1, 26416, 26413, 26423, -1, 26411, 26413, 26416, -1, 26421, 26422, 26467, -1, 26431, 26402, 26404, -1, 26467, 26422, 26414, -1, 26471, 26472, 26473, -1, 26474, 26475, 26476, -1, 26477, 26478, 26479, -1, 26477, 26480, 26481, -1, 26474, 26482, 26475, -1, 26477, 26479, 26483, -1, 26477, 26483, 26480, -1, 26484, 26485, 26486, -1, 26487, 26488, 26482, -1, 26484, 26486, 26489, -1, 26490, 26491, 26492, -1, 26484, 26493, 26485, -1, 26487, 26494, 26488, -1, 26495, 26496, 26497, -1, 26498, 26473, 26493, -1, 26495, 26499, 26500, -1, 26498, 26471, 26473, -1, 26495, 26497, 26499, -1, 26495, 26500, 26494, -1, 26501, 26476, 26502, -1, 26503, 26504, 26478, -1, 26503, 26478, 26477, -1, 26503, 26477, 26481, -1, 26503, 26481, 26471, -1, 26501, 26474, 26476, -1, 26505, 26489, 26506, -1, 26505, 26484, 26489, -1, 26507, 26487, 26482, -1, 26505, 26493, 26484, -1, 26505, 26498, 26493, -1, 26507, 26482, 26474, -1, 26508, 26471, 26498, -1, 26508, 26509, 26504, -1, 26510, 26511, 26496, -1, 26508, 26503, 26471, -1, 26510, 26495, 26494, -1, 26508, 26504, 26503, -1, 26510, 26496, 26495, -1, 26510, 26494, 26487, -1, 26512, 26513, 26514, -1, 26512, 26506, 26513, -1, 26515, 26502, 26516, -1, 26512, 26514, 26509, -1, 26512, 26509, 26508, -1, 26512, 26505, 26506, -1, 26512, 26508, 26498, -1, 26515, 26501, 26502, -1, 26512, 26498, 26505, -1, 26517, 26507, 26474, -1, 26517, 26474, 26501, -1, 26518, 26519, 26511, -1, 26518, 26510, 26487, -1, 26518, 26487, 26507, -1, 26518, 26511, 26510, -1, 26520, 26516, 26521, -1, 26520, 26515, 26516, -1, 26522, 26501, 26515, -1, 26522, 26517, 26501, -1, 26523, 26524, 26519, -1, 26523, 26507, 26517, -1, 26523, 26519, 26518, -1, 26523, 26518, 26507, -1, 26525, 26521, 26526, -1, 26525, 26520, 26521, -1, 26527, 26522, 26515, -1, 26527, 26515, 26520, -1, 26528, 26517, 26522, -1, 26528, 26529, 26524, -1, 26528, 26523, 26517, -1, 26528, 26524, 26523, -1, 26530, 26526, 26531, -1, 26530, 26525, 26526, -1, 26532, 26527, 26520, -1, 26532, 26520, 26525, -1, 26533, 26522, 26527, -1, 26533, 26529, 26528, -1, 26533, 26534, 26529, -1, 26533, 26528, 26522, -1, 26472, 26531, 26535, -1, 26472, 26530, 26531, -1, 26480, 26532, 26525, -1, 26480, 26525, 26530, -1, 26536, 26527, 26532, -1, 26536, 26533, 26527, -1, 26536, 26537, 26534, -1, 26536, 26534, 26533, -1, 26473, 26535, 26538, -1, 26473, 26472, 26535, -1, 26539, 26514, 26513, -1, 26481, 26480, 26530, -1, 26481, 26530, 26472, -1, 26488, 26492, 26540, -1, 26483, 26479, 26537, -1, 26483, 26536, 26532, -1, 26488, 26490, 26492, -1, 26483, 26537, 26536, -1, 26482, 26540, 26475, -1, 26483, 26532, 26480, -1, 26493, 26538, 26485, -1, 26482, 26488, 26540, -1, 26493, 26473, 26538, -1, 26494, 26500, 26490, -1, 26471, 26481, 26472, -1, 26494, 26490, 26488, -1, 26541, 26542, 26543, -1, 26544, 26545, 26546, -1, 26547, 26542, 26548, -1, 26549, 26545, 26544, -1, 26550, 26551, 26552, -1, 26553, 26551, 26554, -1, 26546, 26545, 26555, -1, 26552, 26551, 26553, -1, 26554, 26551, 26556, -1, 26543, 26557, 26558, -1, 26555, 26559, 26560, -1, 26560, 26559, 26561, -1, 26556, 26557, 26547, -1, 26542, 26557, 26543, -1, 26547, 26557, 26542, -1, 26562, 26563, 26564, -1, 26558, 26565, 26566, -1, 26566, 26565, 26567, -1, 26561, 26563, 26562, -1, 26567, 26565, 26550, -1, 26556, 26565, 26557, -1, 26555, 26568, 26559, -1, 26557, 26565, 26558, -1, 26569, 26568, 26570, -1, 26551, 26565, 26556, -1, 26550, 26565, 26551, -1, 26545, 26568, 26555, -1, 26570, 26568, 26545, -1, 26559, 26571, 26561, -1, 26561, 26571, 26563, -1, 26564, 26572, 26573, -1, 26563, 26572, 26564, -1, 26574, 26575, 26569, -1, 26576, 26549, 26544, -1, 26569, 26575, 26568, -1, 26568, 26575, 26559, -1, 26559, 26575, 26571, -1, 26563, 26577, 26572, -1, 26571, 26577, 26563, -1, 26573, 26578, 26579, -1, 26572, 26578, 26573, -1, 26580, 26581, 26574, -1, 26574, 26581, 26575, -1, 26575, 26581, 26571, -1, 26571, 26581, 26577, -1, 26572, 26582, 26578, -1, 26577, 26582, 26572, -1, 26579, 26583, 26584, -1, 26578, 26583, 26579, -1, 26577, 26585, 26582, -1, 26586, 26585, 26580, -1, 26580, 26585, 26581, -1, 26581, 26585, 26577, -1, 26578, 26587, 26583, -1, 26582, 26587, 26578, -1, 26584, 26588, 26589, -1, 26583, 26588, 26584, -1, 26586, 26590, 26585, -1, 26591, 26590, 26586, -1, 26582, 26590, 26587, -1, 26585, 26590, 26582, -1, 26587, 26592, 26583, -1, 26583, 26592, 26588, -1, 26588, 26593, 26589, -1, 26589, 26593, 26594, -1, 26591, 26595, 26590, -1, 26596, 26595, 26591, -1, 26590, 26595, 26587, -1, 26587, 26595, 26592, -1, 26592, 26597, 26588, -1, 26588, 26597, 26593, -1, 26594, 26598, 26599, -1, 26593, 26598, 26594, -1, 26600, 26601, 26596, -1, 26592, 26601, 26597, -1, 26595, 26601, 26592, -1, 26596, 26601, 26595, -1, 26597, 26602, 26593, -1, 26541, 26543, 26603, -1, 26593, 26602, 26598, -1, 26599, 26604, 26605, -1, 26598, 26604, 26599, -1, 26606, 26607, 26600, -1, 26597, 26607, 26602, -1, 26600, 26607, 26601, -1, 26601, 26607, 26597, -1, 26602, 26554, 26598, -1, 26598, 26554, 26604, -1, 26605, 26547, 26548, -1, 26604, 26547, 26605, -1, 26608, 26560, 26609, -1, 26552, 26553, 26606, -1, 26606, 26553, 26607, -1, 26602, 26553, 26554, -1, 26609, 26560, 26610, -1, 26607, 26553, 26602, -1, 26608, 26555, 26560, -1, 26546, 26555, 26608, -1, 26554, 26556, 26604, -1, 26604, 26556, 26547, -1, 26610, 26561, 26562, -1, 26560, 26561, 26610, -1, 26548, 26542, 26541, -1, 26570, 26545, 26549, -1, 26611, 26612, 26613, -1, 26614, 26615, 26616, -1, 26617, 26618, 26619, -1, 26620, 26621, 26622, -1, 26617, 26623, 26618, -1, 26620, 26622, 26615, -1, 26624, 26613, 26623, -1, 26625, 26626, 26627, -1, 26625, 26628, 26621, -1, 26625, 26627, 26629, -1, 26625, 26629, 26628, -1, 26624, 26611, 26613, -1, 26630, 26631, 26632, -1, 26633, 26634, 26635, -1, 26630, 26614, 26631, -1, 26633, 26636, 26634, -1, 26630, 26632, 26637, -1, 26633, 26635, 26611, -1, 26638, 26619, 26639, -1, 26640, 26615, 26614, -1, 26640, 26620, 26615, -1, 26638, 26617, 26619, -1, 26641, 26623, 26617, -1, 26642, 26625, 26621, -1, 26642, 26643, 26626, -1, 26642, 26621, 26620, -1, 26641, 26624, 26623, -1, 26642, 26626, 26625, -1, 26644, 26637, 26645, -1, 26646, 26647, 26636, -1, 26646, 26636, 26633, -1, 26644, 26614, 26630, -1, 26646, 26633, 26611, -1, 26644, 26640, 26614, -1, 26646, 26611, 26624, -1, 26644, 26630, 26637, -1, 26648, 26620, 26640, -1, 26649, 26639, 26650, -1, 26636, 26651, 26634, -1, 26648, 26652, 26643, -1, 26648, 26642, 26620, -1, 26649, 26638, 26639, -1, 26648, 26643, 26642, -1, 26653, 26645, 26654, -1, 26653, 26654, 26655, -1, 26653, 26655, 26656, -1, 26653, 26656, 26652, -1, 26653, 26644, 26645, -1, 26657, 26617, 26638, -1, 26653, 26648, 26640, -1, 26653, 26640, 26644, -1, 26653, 26652, 26648, -1, 26657, 26641, 26617, -1, 26658, 26624, 26641, -1, 26658, 26659, 26647, -1, 26658, 26647, 26646, -1, 26658, 26646, 26624, -1, 26660, 26650, 26661, -1, 26660, 26649, 26650, -1, 26662, 26638, 26649, -1, 26662, 26657, 26638, -1, 26663, 26664, 26659, -1, 26663, 26659, 26658, -1, 26663, 26641, 26657, -1, 26663, 26658, 26641, -1, 26665, 26661, 26666, -1, 26665, 26660, 26661, -1, 26667, 26662, 26649, -1, 26667, 26649, 26660, -1, 26668, 26657, 26662, -1, 26668, 26669, 26664, -1, 26668, 26664, 26663, -1, 26668, 26663, 26657, -1, 26670, 26666, 26671, -1, 26670, 26665, 26666, -1, 26672, 26667, 26660, -1, 26672, 26660, 26665, -1, 26673, 26662, 26667, -1, 26673, 26669, 26668, -1, 26673, 26674, 26669, -1, 26673, 26668, 26662, -1, 26622, 26671, 26675, -1, 26637, 26632, 26676, -1, 26622, 26670, 26671, -1, 26628, 26672, 26665, -1, 26628, 26665, 26670, -1, 26677, 26667, 26672, -1, 26677, 26673, 26667, -1, 26677, 26678, 26674, -1, 26677, 26674, 26673, -1, 26615, 26675, 26616, -1, 26615, 26622, 26675, -1, 26613, 26679, 26680, -1, 26613, 26612, 26679, -1, 26621, 26628, 26670, -1, 26621, 26670, 26622, -1, 26623, 26680, 26618, -1, 26629, 26627, 26678, -1, 26629, 26677, 26672, -1, 26629, 26678, 26677, -1, 26623, 26613, 26680, -1, 26629, 26672, 26628, -1, 26614, 26616, 26631, -1, 26611, 26635, 26612, -1, 26681, 26682, 26683, -1, 26683, 26684, 26685, -1, 26682, 26684, 26683, -1, 26685, 26686, 26687, -1, 26684, 26686, 26685, -1, 26687, 26688, 26689, -1, 26686, 26688, 26687, -1, 26689, 26690, 26691, -1, 26688, 26690, 26689, -1, 26691, 26692, 26693, -1, 26690, 26692, 26691, -1, 26693, 26694, 26695, -1, 26692, 26694, 26693, -1, 26695, 26696, 26697, -1, 26694, 26696, 26695, -1, 26697, 26698, 26699, -1, 26696, 26698, 26697, -1, 26699, 26700, 26701, -1, 26698, 26700, 26699, -1, 26701, 26702, 26703, -1, 26700, 26702, 26701, -1, 26703, 26704, 26705, -1, 26702, 26704, 26703, -1, 26704, 26706, 26705, -1, 26705, 26707, 26708, -1, 26706, 26707, 26705, -1, 26709, 26710, 26711, -1, 26711, 26712, 26713, -1, 26710, 26712, 26711, -1, 26713, 26714, 26715, -1, 26712, 26714, 26713, -1, 26715, 26716, 26717, -1, 26714, 26716, 26715, -1, 26717, 26718, 26719, -1, 26716, 26718, 26717, -1, 26719, 26720, 26721, -1, 26718, 26720, 26719, -1, 26721, 26722, 26723, -1, 26720, 26722, 26721, -1, 26723, 26724, 26725, -1, 26722, 26724, 26723, -1, 26725, 26726, 26727, -1, 26724, 26726, 26725, -1, 26727, 26728, 26729, -1, 26726, 26728, 26727, -1, 26729, 26730, 26731, -1, 26728, 26730, 26729, -1, 26731, 26732, 26733, -1, 26730, 26732, 26731, -1, 26732, 26734, 26733, -1, 26733, 26735, 26736, -1, 26734, 26735, 26733, -1, 26737, 26538, 26738, -1, 26739, 26740, 26435, -1, 26739, 26741, 26740, -1, 26739, 26738, 26741, -1, 26739, 26737, 26738, -1, 26739, 26435, 26737, -1, 26742, 26492, 26491, -1, 26742, 26540, 26492, -1, 26742, 26743, 26540, -1, 26744, 26491, 26404, -1, 26744, 26745, 26746, -1, 26744, 26404, 26745, -1, 26744, 26743, 26742, -1, 26744, 26742, 26491, -1, 26744, 26746, 26743, -1, 26738, 26538, 26535, -1, 26738, 26747, 26741, -1, 26748, 26531, 26526, -1, 26748, 26535, 26531, -1, 26748, 26749, 26747, -1, 26748, 26750, 26749, -1, 26748, 26747, 26738, -1, 26748, 26738, 26535, -1, 26751, 26526, 26521, -1, 26751, 26752, 26750, -1, 26751, 26750, 26748, -1, 26751, 26748, 26526, -1, 26753, 26516, 26502, -1, 26753, 26521, 26516, -1, 26753, 26754, 26752, -1, 26753, 26755, 26754, -1, 26753, 26751, 26521, -1, 26753, 26752, 26751, -1, 26756, 26476, 26475, -1, 26756, 26502, 26476, -1, 26756, 26757, 26755, -1, 26756, 26758, 26757, -1, 26756, 26753, 26502, -1, 26756, 26755, 26753, -1, 26743, 26475, 26540, -1, 26743, 26746, 26758, -1, 26743, 26758, 26756, -1, 26743, 26756, 26475, -1, 26737, 26485, 26538, -1, 26737, 26486, 26485, -1, 26737, 26435, 26486, -1, 26759, 26619, 26618, -1, 26759, 26760, 26761, -1, 26759, 26761, 26762, -1, 26759, 26762, 26619, -1, 26763, 26632, 26631, -1, 26763, 26676, 26632, -1, 26763, 26631, 26764, -1, 26765, 26766, 26567, -1, 26765, 26767, 26766, -1, 26765, 26567, 26676, -1, 26765, 26764, 26767, -1, 26765, 26763, 26764, -1, 26765, 26676, 26763, -1, 26768, 26680, 26679, -1, 26768, 26618, 26680, -1, 26768, 26679, 26576, -1, 26768, 26759, 26618, -1, 26769, 26770, 26760, -1, 26769, 26576, 26770, -1, 26769, 26759, 26768, -1, 26769, 26760, 26759, -1, 26769, 26768, 26576, -1, 26764, 26631, 26616, -1, 26764, 26771, 26767, -1, 26772, 26675, 26671, -1, 26772, 26616, 26675, -1, 26772, 26773, 26771, -1, 26772, 26774, 26773, -1, 26772, 26771, 26764, -1, 26772, 26764, 26616, -1, 26775, 26671, 26666, -1, 26775, 26776, 26774, -1, 26775, 26777, 26776, -1, 26775, 26774, 26772, -1, 26775, 26772, 26671, -1, 26778, 26661, 26650, -1, 26778, 26666, 26661, -1, 26778, 26779, 26777, -1, 26778, 26775, 26666, -1, 26778, 26777, 26775, -1, 26762, 26639, 26619, -1, 26762, 26650, 26639, -1, 26762, 26780, 26779, -1, 26762, 26761, 26780, -1, 26762, 26778, 26650, -1, 26762, 26779, 26778, -1, 26781, 26782, 26783, -1, 26784, 26785, 26786, -1, 26787, 26788, 26789, -1, 26784, 26790, 26785, -1, 26791, 26792, 26793, -1, 26794, 26783, 26790, -1, 26791, 26793, 26788, -1, 26795, 26796, 26792, -1, 26795, 26797, 26798, -1, 26795, 26799, 26796, -1, 26794, 26781, 26783, -1, 26795, 26798, 26799, -1, 26800, 26801, 26802, -1, 26803, 26804, 26805, -1, 26803, 26806, 26807, -1, 26800, 26787, 26801, -1, 26803, 26805, 26806, -1, 26800, 26802, 26808, -1, 26803, 26807, 26781, -1, 26809, 26786, 26810, -1, 26811, 26788, 26787, -1, 26811, 26791, 26788, -1, 26809, 26784, 26786, -1, 26812, 26790, 26784, -1, 26813, 26814, 26797, -1, 26813, 26797, 26795, -1, 26813, 26792, 26791, -1, 26812, 26794, 26790, -1, 26813, 26795, 26792, -1, 26815, 26808, 26816, -1, 26817, 26818, 26804, -1, 26817, 26803, 26781, -1, 26815, 26787, 26800, -1, 26817, 26804, 26803, -1, 26815, 26811, 26787, -1, 26817, 26781, 26794, -1, 26815, 26800, 26808, -1, 26819, 26791, 26811, -1, 26820, 26810, 26821, -1, 26819, 26822, 26814, -1, 26819, 26813, 26791, -1, 26819, 26814, 26813, -1, 26820, 26809, 26810, -1, 26823, 26816, 26824, -1, 26823, 26824, 26825, -1, 26823, 26825, 26826, -1, 26823, 26826, 26822, -1, 26823, 26815, 26816, -1, 26823, 26819, 26811, -1, 26823, 26811, 26815, -1, 26823, 26822, 26819, -1, 26827, 26812, 26784, -1, 26827, 26784, 26809, -1, 26828, 26829, 26818, -1, 26828, 26817, 26794, -1, 26828, 26818, 26817, -1, 26828, 26794, 26812, -1, 26830, 26821, 26831, -1, 26830, 26820, 26821, -1, 26832, 26809, 26820, -1, 26832, 26827, 26809, -1, 26833, 26834, 26829, -1, 26833, 26828, 26812, -1, 26833, 26812, 26827, -1, 26833, 26829, 26828, -1, 26835, 26831, 26836, -1, 26835, 26830, 26831, -1, 26837, 26832, 26820, -1, 26837, 26820, 26830, -1, 26838, 26839, 26834, -1, 26838, 26827, 26832, -1, 26838, 26833, 26827, -1, 26838, 26834, 26833, -1, 26840, 26836, 26841, -1, 26840, 26835, 26836, -1, 26842, 26837, 26830, -1, 26842, 26830, 26835, -1, 26843, 26832, 26837, -1, 26843, 26844, 26839, -1, 26843, 26839, 26838, -1, 26843, 26838, 26832, -1, 26793, 26841, 26845, -1, 26808, 26802, 26846, -1, 26793, 26840, 26841, -1, 26796, 26835, 26840, -1, 26796, 26842, 26835, -1, 26847, 26843, 26837, -1, 26847, 26844, 26843, -1, 26847, 26848, 26844, -1, 26847, 26837, 26842, -1, 26788, 26845, 26789, -1, 26788, 26793, 26845, -1, 26783, 26849, 26850, -1, 26783, 26782, 26849, -1, 26792, 26796, 26840, -1, 26790, 26850, 26785, -1, 26792, 26840, 26793, -1, 26799, 26847, 26842, -1, 26799, 26842, 26796, -1, 26790, 26783, 26850, -1, 26799, 26798, 26848, -1, 26799, 26848, 26847, -1, 26787, 26789, 26801, -1, 26781, 26807, 26782, -1, 26851, 26852, 26853, -1, 26854, 26855, 26856, -1, 26857, 26858, 26859, -1, 26860, 26855, 26854, -1, 26861, 26858, 26862, -1, 26852, 26858, 26857, -1, 26863, 26864, 26865, -1, 26866, 26858, 26867, -1, 26868, 26864, 26869, -1, 26867, 26858, 26852, -1, 26862, 26858, 26866, -1, 26859, 26858, 26861, -1, 26870, 26864, 26863, -1, 26869, 26864, 26870, -1, 26871, 26872, 26873, -1, 26865, 26874, 26860, -1, 26860, 26874, 26855, -1, 26856, 26875, 26876, -1, 26855, 26875, 26856, -1, 26877, 26878, 26868, -1, 26864, 26878, 26865, -1, 26868, 26878, 26864, -1, 26865, 26878, 26874, -1, 26874, 26879, 26855, -1, 26855, 26879, 26875, -1, 26876, 26880, 26881, -1, 26875, 26880, 26876, -1, 26882, 26883, 26877, -1, 26878, 26883, 26874, -1, 26877, 26883, 26878, -1, 26874, 26883, 26879, -1, 26875, 26884, 26880, -1, 26879, 26884, 26875, -1, 26881, 26885, 26886, -1, 26880, 26885, 26881, -1, 26879, 26887, 26884, -1, 26888, 26887, 26882, -1, 26882, 26887, 26883, -1, 26883, 26887, 26879, -1, 26880, 26889, 26885, -1, 26884, 26889, 26880, -1, 26885, 26890, 26886, -1, 26886, 26890, 26891, -1, 26888, 26892, 26887, -1, 26893, 26892, 26888, -1, 26884, 26892, 26889, -1, 26887, 26892, 26884, -1, 26889, 26894, 26885, -1, 26885, 26894, 26890, -1, 26890, 26895, 26891, -1, 26891, 26895, 26896, -1, 26897, 26898, 26893, -1, 26893, 26898, 26892, -1, 26892, 26898, 26889, -1, 26889, 26898, 26894, -1, 26894, 26899, 26890, -1, 26890, 26899, 26895, -1, 26896, 26900, 26901, -1, 26895, 26900, 26896, -1, 26902, 26903, 26897, -1, 26897, 26903, 26898, -1, 26894, 26903, 26899, -1, 26898, 26903, 26894, -1, 26899, 26904, 26895, -1, 26895, 26904, 26900, -1, 26901, 26905, 26906, -1, 26900, 26905, 26901, -1, 26907, 26908, 26902, -1, 26899, 26908, 26904, -1, 26903, 26908, 26899, -1, 26902, 26908, 26903, -1, 26904, 26909, 26900, -1, 26900, 26909, 26905, -1, 26906, 26851, 26910, -1, 26905, 26851, 26906, -1, 26861, 26911, 26859, -1, 26912, 26913, 26907, -1, 26904, 26913, 26909, -1, 26872, 26914, 26915, -1, 26908, 26913, 26904, -1, 26871, 26914, 26872, -1, 26907, 26913, 26908, -1, 26916, 26863, 26871, -1, 26909, 26867, 26905, -1, 26871, 26863, 26914, -1, 26905, 26867, 26851, -1, 26915, 26860, 26854, -1, 26917, 26853, 26918, -1, 26914, 26860, 26915, -1, 26910, 26853, 26917, -1, 26851, 26853, 26910, -1, 26869, 26870, 26919, -1, 26920, 26870, 26916, -1, 26862, 26866, 26912, -1, 26919, 26870, 26920, -1, 26909, 26866, 26867, -1, 26916, 26870, 26863, -1, 26913, 26866, 26909, -1, 26912, 26866, 26913, -1, 26918, 26852, 26857, -1, 26914, 26865, 26860, -1, 26853, 26852, 26918, -1, 26863, 26865, 26914, -1, 26867, 26852, 26851, -1, 26921, 26786, 26785, -1, 26921, 26922, 26923, -1, 26921, 26924, 26786, -1, 26921, 26923, 26924, -1, 26925, 26802, 26801, -1, 26925, 26846, 26802, -1, 26925, 26801, 26926, -1, 26927, 26928, 26911, -1, 26927, 26929, 26928, -1, 26927, 26911, 26846, -1, 26927, 26926, 26929, -1, 26927, 26925, 26926, -1, 26927, 26846, 26925, -1, 26930, 26850, 26849, -1, 26930, 26785, 26850, -1, 26930, 26849, 26919, -1, 26930, 26921, 26785, -1, 26931, 26932, 26922, -1, 26931, 26919, 26932, -1, 26931, 26921, 26930, -1, 26931, 26922, 26921, -1, 26931, 26930, 26919, -1, 26926, 26801, 26789, -1, 26926, 26933, 26929, -1, 26934, 26845, 26841, -1, 26934, 26789, 26845, -1, 26934, 26935, 26933, -1, 26934, 26936, 26935, -1, 26934, 26933, 26926, -1, 26934, 26926, 26789, -1, 26937, 26836, 26831, -1, 26937, 26841, 26836, -1, 26937, 26938, 26936, -1, 26937, 26939, 26938, -1, 26937, 26936, 26934, -1, 26937, 26934, 26841, -1, 26940, 26831, 26821, -1, 26940, 26941, 26939, -1, 26940, 26937, 26831, -1, 26940, 26939, 26937, -1, 26924, 26810, 26786, -1, 26924, 26821, 26810, -1, 26924, 26942, 26941, -1, 26924, 26923, 26942, -1, 26924, 26941, 26940, -1, 26924, 26940, 26821, -1, 26943, 26944, 26945, -1, 26946, 26944, 26943, -1, 26944, 26947, 26945, -1, 26945, 26947, 26948, -1, 26947, 26949, 26948, -1, 26950, 26951, 26952, -1, 26952, 26951, 26953, -1, 26953, 26954, 26955, -1, 26951, 26954, 26953, -1, 26955, 26956, 26957, -1, 26954, 26956, 26955, -1, 26957, 26958, 26959, -1, 26956, 26958, 26957, -1, 26960, 26961, 26962, -1, 26962, 26961, 26271, -1, 26271, 26961, 26273, -1, 26273, 26961, 26275, -1, 26275, 26961, 26276, -1, 26963, 26964, 26965, -1, 26959, 26964, 26963, -1, 26958, 26964, 26959, -1, 26965, 26966, 26967, -1, 26967, 26966, 26968, -1, 26968, 26966, 26960, -1, 26964, 26966, 26965, -1, 26960, 26966, 26961, -1, 26961, 26969, 26970, -1, 26966, 26969, 26961, -1, 26970, 26971, 26972, -1, 26969, 26971, 26970, -1, 26972, 26973, 26974, -1, 26971, 26973, 26972, -1, 26974, 26946, 26943, -1, 26973, 26946, 26974, -1, 26975, 26976, 26977, -1, 26977, 26976, 26978, -1, 26978, 26979, 26980, -1, 26976, 26979, 26978, -1, 26980, 26981, 26982, -1, 26979, 26981, 26980, -1, 26982, 26983, 26984, -1, 26981, 26983, 26982, -1, 26984, 26985, 26986, -1, 26983, 26985, 26984, -1, 26986, 26987, 26988, -1, 26985, 26987, 26986, -1, 26988, 26989, 26990, -1, 26987, 26989, 26988, -1, 26990, 26991, 26992, -1, 26989, 26991, 26990, -1, 26992, 26993, 26994, -1, 26991, 26993, 26992, -1, 26994, 26995, 26996, -1, 26993, 26995, 26994, -1, 26996, 26997, 26998, -1, 26995, 26997, 26996, -1, 26999, 27000, 27001, -1, 26998, 27000, 26999, -1, 26997, 27000, 26998, -1, 27000, 27002, 27001, -1, 27003, 27004, 27005, -1, 27004, 27006, 27005, -1, 27005, 27007, 27008, -1, 27006, 27007, 27005, -1, 27008, 27009, 27010, -1, 27007, 27009, 27008, -1, 27010, 27011, 27012, -1, 27009, 27011, 27010, -1, 27012, 27013, 27014, -1, 27011, 27013, 27012, -1, 27014, 27015, 27016, -1, 27013, 27015, 27014, -1, 27016, 27017, 27018, -1, 27015, 27017, 27016, -1, 27018, 27019, 27020, -1, 27017, 27019, 27018, -1, 27020, 27021, 27022, -1, 27019, 27021, 27020, -1, 27022, 27023, 27024, -1, 27021, 27023, 27022, -1, 27024, 27025, 27026, -1, 27023, 27025, 27024, -1, 27026, 27027, 27028, -1, 27025, 27027, 27026, -1, 27028, 27029, 27030, -1, 27027, 27029, 27028, -1, 27031, 27032, 27033, -1, 27032, 27034, 27033, -1, 27033, 27035, 27036, -1, 27034, 27035, 27033, -1, 27036, 27037, 27038, -1, 27035, 27037, 27036, -1, 27038, 27039, 27040, -1, 27037, 27039, 27038, -1, 27040, 27041, 27042, -1, 27039, 27041, 27040, -1, 27042, 27043, 27044, -1, 27041, 27043, 27042, -1, 27044, 27045, 27046, -1, 27043, 27045, 27044, -1, 27046, 27047, 27048, -1, 27045, 27047, 27046, -1, 27048, 27049, 27050, -1, 27047, 27049, 27048, -1, 27050, 27051, 27052, -1, 27049, 27051, 27050, -1, 27052, 27053, 27054, -1, 27051, 27053, 27052, -1, 27054, 27055, 27056, -1, 27053, 27055, 27054, -1, 27056, 27057, 27058, -1, 27055, 27057, 27056, -1, 27059, 27060, 27061, -1, 27061, 27060, 27062, -1, 27063, 27064, 27065, -1, 27062, 27064, 27063, -1, 27060, 27064, 27062, -1, 27064, 27066, 27065, -1, 27067, 27068, 27069, -1, 27069, 27068, 27070, -1, 27071, 27072, 27073, -1, 27070, 27072, 27071, -1, 27068, 27072, 27070, -1, 27072, 27074, 27073, -1, 27075, 27076, 27077, -1, 27077, 27076, 27078, -1, 27079, 27080, 27081, -1, 27078, 27080, 27079, -1, 27076, 27080, 27078, -1, 27080, 27082, 27081, -1, 27083, 27084, 27085, -1, 27085, 27084, 27086, -1, 27087, 27088, 27089, -1, 27086, 27088, 27087, -1, 27084, 27088, 27086, -1, 27088, 27090, 27089, -1, 27091, 27092, 27093, -1, 27093, 27092, 27094, -1, 27095, 27096, 27097, -1, 27094, 27096, 27095, -1, 27092, 27096, 27094, -1, 27096, 27098, 27097, -1, 27099, 27100, 27101, -1, 27101, 27100, 27102, -1, 27103, 27104, 27105, -1, 27102, 27104, 27103, -1, 27100, 27104, 27102, -1, 27104, 27106, 27105, -1, 27107, 27108, 27109, -1, 27109, 27108, 27110, -1, 27111, 27112, 27113, -1, 27110, 27112, 27111, -1, 27108, 27112, 27110, -1, 27112, 27114, 27113, -1, 27115, 27116, 27117, -1, 27117, 27116, 27118, -1, 27119, 27120, 27121, -1, 27118, 27120, 27119, -1, 27116, 27120, 27118, -1, 27120, 27122, 27121, -1, 27123, 27124, 27125, -1, 27125, 27124, 27126, -1, 27127, 27128, 27129, -1, 27126, 27128, 27127, -1, 27124, 27128, 27126, -1, 27128, 27130, 27129, -1, 27131, 27132, 27133, -1, 27133, 27132, 27134, -1, 27135, 27136, 27137, -1, 27134, 27136, 27135, -1, 27132, 27136, 27134, -1, 27136, 27138, 27137, -1, 27139, 27140, 27141, -1, 27141, 27140, 27142, -1, 27143, 27144, 27145, -1, 27142, 27144, 27143, -1, 27140, 27144, 27142, -1, 27144, 27146, 27145, -1, 27147, 27148, 27149, -1, 27150, 27151, 27148, -1, 27150, 27148, 27147, -1, 27152, 27151, 27150, -1, 27153, 27151, 27152, -1, 27154, 27155, 27151, -1, 27154, 27151, 27153, -1, 27156, 27154, 27153, -1, 27157, 27154, 27156, -1, 27154, 27158, 27155, -1, 27159, 27158, 27154, -1, 27160, 27159, 27154, -1, 27161, 27160, 27154, -1, 27157, 27161, 27154, -1, 27162, 27163, 27158, -1, 27164, 27162, 27158, -1, 27159, 27164, 27158, -1, 27165, 27166, 27167, -1, 27165, 27168, 27166, -1, 27169, 27170, 27165, -1, 27165, 27170, 27168, -1, 27171, 27172, 27173, -1, 27171, 27174, 27175, -1, 27175, 27174, 27176, -1, 27176, 27174, 27177, -1, 27178, 27179, 27180, -1, 27181, 27182, 27183, -1, 27183, 27182, 27184, -1, 27183, 27185, 27181, -1, 27181, 27185, 27186, -1, 27186, 27185, 27187, -1, 27188, 27189, 27190, -1, 27190, 27189, 27191, -1, 27190, 27192, 27188, -1, 27188, 27192, 27193, -1, 27178, 27194, 27179, -1, 27193, 27192, 27195, -1, 27196, 27197, 27198, -1, 27198, 27197, 27199, -1, 27174, 27200, 27177, -1, 27201, 27202, 27203, -1, 27198, 27204, 27196, -1, 27205, 27200, 27174, -1, 27203, 27202, 27206, -1, 27196, 27204, 27207, -1, 27207, 27204, 27208, -1, 27209, 27210, 27211, -1, 27211, 27210, 27212, -1, 27213, 27214, 27215, -1, 27211, 27216, 27209, -1, 27209, 27216, 27217, -1, 27217, 27216, 27218, -1, 27201, 27219, 27202, -1, 27220, 27221, 27222, -1, 27223, 27214, 27213, -1, 27222, 27221, 27224, -1, 27222, 27225, 27220, -1, 27220, 27225, 27226, -1, 27226, 27225, 27227, -1, 27219, 27228, 27202, -1, 27229, 27230, 27231, -1, 27231, 27230, 27232, -1, 27231, 27233, 27229, -1, 27229, 27233, 27234, -1, 27228, 26854, 27202, -1, 27234, 27233, 27235, -1, 27236, 27237, 27238, -1, 27238, 27237, 27239, -1, 27238, 27240, 27236, -1, 26854, 26856, 27202, -1, 27236, 27240, 27241, -1, 27241, 27240, 27242, -1, 27243, 27244, 27245, -1, 27228, 26915, 26854, -1, 27246, 27247, 26917, -1, 27246, 26917, 27248, -1, 27223, 27249, 27214, -1, 26917, 27247, 26910, -1, 27250, 27251, 25766, -1, 27250, 25766, 27252, -1, 26856, 26876, 27202, -1, 27250, 27252, 25717, -1, 27250, 25717, 27253, -1, 27223, 27254, 27249, -1, 27178, 27255, 27194, -1, 27250, 27253, 26082, -1, 27250, 26082, 27256, -1, 27250, 27256, 25612, -1, 27250, 25612, 27257, -1, 27250, 27257, 25668, -1, 27250, 25668, 27258, -1, 27228, 26872, 26915, -1, 27250, 27258, 27259, -1, 25766, 27251, 27260, -1, 27260, 27251, 25815, -1, 25815, 27251, 27261, -1, 27261, 27251, 25864, -1, 25864, 27251, 27262, -1, 26876, 26881, 27202, -1, 27262, 27251, 25913, -1, 25913, 27251, 27263, -1, 27263, 27251, 26249, -1, 27228, 26873, 26872, -1, 27178, 27264, 27255, -1, 27265, 27264, 27178, -1, 27228, 27266, 26873, -1, 27223, 27267, 27254, -1, 27265, 25598, 27264, -1, 27223, 27268, 27267, -1, 27269, 25598, 27265, -1, 26886, 27270, 26881, -1, 27271, 27268, 27223, -1, 27202, 27270, 27272, -1, 26881, 27270, 27202, -1, 27273, 27274, 27275, -1, 27275, 27274, 27204, -1, 27269, 25596, 25598, -1, 26891, 27276, 26886, -1, 26886, 27276, 27270, -1, 27271, 25801, 27268, -1, 27277, 25596, 27269, -1, 27278, 25801, 27271, -1, 27277, 25605, 25596, -1, 26896, 27279, 26891, -1, 26891, 27279, 27276, -1, 27280, 27281, 27282, -1, 27283, 25605, 27277, -1, 27282, 27281, 27284, -1, 27283, 25611, 25605, -1, 27278, 25799, 25801, -1, 26896, 27247, 27279, -1, 27285, 25611, 27283, -1, 26896, 26901, 27247, -1, 27286, 25799, 27278, -1, 27285, 25612, 25611, -1, 27257, 25612, 27285, -1, 27286, 25808, 25799, -1, 27287, 25808, 27286, -1, 26901, 26906, 27247, -1, 27288, 25814, 27287, -1, 27287, 25814, 25808, -1, 27288, 25815, 25814, -1, 27260, 25815, 27288, -1, 27289, 27243, 27240, -1, 27290, 27291, 27292, -1, 27293, 27291, 27290, -1, 27294, 27243, 27289, -1, 26906, 26910, 27247, -1, 27204, 27295, 27208, -1, 27274, 27295, 27204, -1, 27296, 27297, 27298, -1, 27298, 27297, 27299, -1, 27266, 27300, 27301, -1, 27301, 27300, 27302, -1, 27302, 27300, 27303, -1, 27296, 27304, 27297, -1, 27228, 27300, 27266, -1, 27284, 27305, 27306, -1, 27281, 27305, 27284, -1, 27307, 27308, 27309, -1, 27296, 27310, 27304, -1, 27309, 27308, 27311, -1, 27307, 27312, 27308, -1, 27307, 27313, 27312, -1, 27296, 27314, 27310, -1, 27243, 27315, 27240, -1, 27307, 27316, 27313, -1, 27240, 27315, 27242, -1, 27317, 27318, 27296, -1, 27319, 27320, 27307, -1, 27296, 27318, 27314, -1, 27307, 27320, 27316, -1, 27321, 25850, 27319, -1, 27319, 25850, 27320, -1, 27322, 26068, 27317, -1, 27317, 26068, 27318, -1, 27323, 27324, 27325, -1, 27325, 27324, 27326, -1, 27327, 25848, 27321, -1, 27328, 27213, 27329, -1, 27329, 27213, 27192, -1, 27321, 25848, 25850, -1, 27327, 25857, 25848, -1, 27303, 27250, 27330, -1, 27330, 27250, 27331, -1, 27326, 27250, 27332, -1, 27332, 27250, 27333, -1, 27333, 27250, 27334, -1, 27334, 27250, 27335, -1, 27336, 25857, 27327, -1, 27335, 27250, 27337, -1, 27337, 27250, 27300, -1, 27324, 27250, 27326, -1, 27300, 27250, 27303, -1, 27250, 27338, 27331, -1, 27339, 26066, 27322, -1, 27322, 26066, 26068, -1, 27340, 25863, 27336, -1, 27336, 25863, 25857, -1, 27340, 25864, 25863, -1, 27341, 26075, 27339, -1, 27261, 25864, 27340, -1, 27339, 26075, 26066, -1, 27342, 26081, 27341, -1, 27341, 26081, 26075, -1, 27256, 26082, 27342, -1, 27342, 26082, 26081, -1, 27343, 27344, 27345, -1, 27345, 27344, 27233, -1, 27346, 27347, 27348, -1, 27349, 27350, 27205, -1, 27205, 27350, 27200, -1, 27349, 27351, 27350, -1, 27349, 27352, 27351, -1, 27344, 27353, 27233, -1, 27233, 27353, 27235, -1, 27354, 27246, 27355, -1, 27346, 27356, 27347, -1, 27192, 27215, 27195, -1, 27355, 27246, 27248, -1, 27213, 27215, 27192, -1, 27357, 27358, 27359, -1, 27360, 27361, 27354, -1, 27349, 27362, 27352, -1, 27354, 27361, 27246, -1, 27359, 27358, 27363, -1, 27357, 27364, 27358, -1, 27360, 27365, 27361, -1, 27366, 27367, 27349, -1, 27357, 27368, 27364, -1, 27349, 27367, 27362, -1, 27369, 27370, 27360, -1, 27371, 25899, 27366, -1, 27366, 25899, 27367, -1, 27360, 27370, 27365, -1, 27372, 27373, 27374, -1, 27374, 27373, 27356, -1, 27357, 27375, 27368, -1, 27376, 25897, 27371, -1, 27369, 27377, 27370, -1, 27371, 25897, 25899, -1, 27357, 27378, 27375, -1, 27379, 25906, 27376, -1, 27380, 27378, 27357, -1, 27381, 27298, 27382, -1, 27382, 27298, 27225, -1, 27376, 25906, 25897, -1, 27383, 25912, 27379, -1, 27338, 27384, 27369, -1, 27379, 25912, 25906, -1, 27250, 27384, 27338, -1, 27369, 27384, 27377, -1, 27262, 25913, 27383, -1, 27385, 25703, 27380, -1, 27383, 25913, 25912, -1, 27380, 25703, 27378, -1, 27250, 27386, 27384, -1, 27387, 27309, 27388, -1, 27250, 27389, 27386, -1, 27388, 27309, 27185, -1, 27250, 27390, 27389, -1, 27391, 25701, 27385, -1, 27385, 25701, 25703, -1, 27250, 27259, 27390, -1, 27392, 25710, 27391, -1, 27393, 27394, 27281, -1, 27391, 25710, 25701, -1, 27395, 25716, 27392, -1, 27393, 27396, 27394, -1, 27392, 25716, 25710, -1, 27253, 25717, 27395, -1, 27395, 25717, 25716, -1, 27393, 27397, 27396, -1, 27393, 27398, 27397, -1, 27393, 27399, 27398, -1, 27400, 27399, 27393, -1, 27401, 26235, 27400, -1, 27400, 26235, 27399, -1, 27298, 27299, 27225, -1, 27225, 27299, 27227, -1, 27402, 26233, 27401, -1, 27401, 26233, 26235, -1, 27243, 27245, 27315, -1, 27403, 26242, 27402, -1, 27402, 26242, 26233, -1, 27244, 27404, 27245, -1, 27405, 26248, 27403, -1, 27185, 27311, 27187, -1, 27403, 26248, 26242, -1, 27309, 27311, 27185, -1, 27274, 27406, 27295, -1, 27244, 27407, 27404, -1, 27263, 26249, 27405, -1, 27405, 26249, 26248, -1, 27408, 27406, 27274, -1, 27408, 27409, 27406, -1, 27408, 27410, 27409, -1, 27244, 27411, 27407, -1, 27412, 27413, 27244, -1, 27244, 27413, 27411, -1, 27414, 27415, 27416, -1, 27408, 27417, 27410, -1, 27414, 27418, 27415, -1, 27419, 25654, 27412, -1, 27408, 27420, 27417, -1, 27412, 25654, 27413, -1, 27421, 27422, 27414, -1, 27423, 27359, 27424, -1, 27424, 27359, 27216, -1, 27425, 27420, 27408, -1, 27414, 27422, 27418, -1, 27421, 27426, 27422, -1, 27427, 25652, 27419, -1, 27421, 27428, 27426, -1, 27419, 25652, 25654, -1, 27429, 25752, 27425, -1, 27425, 25752, 27420, -1, 27430, 27205, 27431, -1, 27431, 27205, 27174, -1, 27432, 25661, 27427, -1, 27427, 25661, 25652, -1, 27433, 27428, 27421, -1, 27433, 27434, 27428, -1, 27429, 25750, 25752, -1, 27435, 25667, 27432, -1, 27432, 25667, 25661, -1, 27436, 27434, 27437, -1, 27437, 27434, 27433, -1, 27436, 27438, 27434, -1, 27258, 25668, 27435, -1, 27439, 25750, 27429, -1, 27439, 25759, 25750, -1, 27435, 25668, 25667, -1, 27440, 27438, 27436, -1, 27440, 27441, 27438, -1, 27442, 25759, 27439, -1, 27442, 25765, 25759, -1, 27443, 27441, 27440, -1, 27443, 27444, 27441, -1, 27445, 25765, 27442, -1, 27445, 25766, 25765, -1, 27252, 25766, 27445, -1, 27443, 27251, 27444, -1, 27446, 27251, 27373, -1, 27373, 27251, 27356, -1, 27359, 27363, 27216, -1, 27447, 27251, 27448, -1, 27216, 27363, 27218, -1, 27448, 27251, 27449, -1, 27449, 27251, 27450, -1, 27450, 27251, 27451, -1, 27451, 27251, 27452, -1, 27452, 27251, 27446, -1, 27453, 27251, 27447, -1, 27444, 27251, 27453, -1, 27454, 27251, 27443, -1, 26249, 27251, 27454, -1, 27178, 27180, 27344, -1, 27356, 27251, 27347, -1, 27394, 27305, 27281, -1, 27293, 27284, 27291, -1, 27291, 27284, 27455, -1, 27455, 27284, 27306, -1, 27344, 27180, 27353, -1, 27175, 27172, 27171, -1, 27456, 27457, 27458, -1, 27459, 27457, 27456, -1, 27460, 27457, 27459, -1, 27461, 27137, 27138, -1, 27462, 27463, 27461, -1, 27461, 27463, 27137, -1, 27463, 27464, 27137, -1, 27465, 27466, 27467, -1, 27465, 27468, 27466, -1, 27468, 27469, 27466, -1, 26409, 26562, 26410, -1, 26410, 26562, 26564, -1, 27470, 27471, 27472, -1, 27473, 27145, 26589, -1, 27146, 27470, 27474, -1, 27146, 27474, 27475, -1, 27146, 27475, 27476, -1, 26463, 26579, 26458, -1, 26573, 26579, 26463, -1, 26425, 26438, 27145, -1, 26405, 26610, 26409, -1, 27145, 26423, 26425, -1, 26438, 26443, 27145, -1, 26409, 26610, 26562, -1, 26579, 26584, 26458, -1, 27145, 26416, 26423, -1, 26458, 26584, 27145, -1, 26443, 26448, 27145, -1, 27145, 26417, 26416, -1, 27477, 26609, 26405, -1, 26405, 26609, 26610, -1, 26584, 26589, 27145, -1, 26448, 26453, 27145, -1, 27477, 27478, 26609, -1, 27479, 27478, 27477, -1, 26453, 26458, 27145, -1, 27479, 27480, 27478, -1, 27481, 27480, 27479, -1, 27146, 27482, 27483, -1, 27483, 27482, 27481, -1, 27481, 27482, 27480, -1, 27146, 27476, 27482, -1, 26417, 27146, 27484, -1, 27484, 27146, 27485, -1, 27485, 27146, 27486, -1, 27486, 27146, 27487, -1, 27487, 27146, 27488, -1, 27145, 27146, 26417, -1, 27146, 27489, 27488, -1, 27146, 27490, 27489, -1, 27146, 27491, 27490, -1, 26603, 27472, 26541, -1, 27146, 27483, 27491, -1, 26541, 27472, 26548, -1, 26548, 27472, 26605, -1, 27492, 27472, 26603, -1, 26410, 26564, 26468, -1, 26605, 27473, 26599, -1, 26599, 27473, 26594, -1, 26594, 27473, 26589, -1, 27472, 27473, 26605, -1, 27474, 27470, 27493, -1, 27493, 27470, 27494, -1, 27494, 27470, 27495, -1, 26468, 26573, 26463, -1, 27495, 27470, 27496, -1, 27496, 27470, 27497, -1, 26564, 26573, 26468, -1, 27497, 27470, 27492, -1, 27492, 27470, 27472, -1, 27498, 27499, 27500, -1, 27501, 26175, 26198, -1, 27502, 26176, 27503, -1, 27503, 26176, 27504, -1, 27504, 26176, 27505, -1, 27505, 26176, 27506, -1, 27506, 26176, 27501, -1, 27501, 26176, 26175, -1, 27499, 27507, 27502, -1, 27502, 27507, 26176, -1, 27499, 27508, 27507, -1, 27499, 27509, 27508, -1, 27499, 27510, 27509, -1, 27511, 27512, 27513, -1, 27513, 27512, 27510, -1, 27512, 27514, 27515, -1, 27511, 27514, 27512, -1, 27502, 27500, 27499, -1, 27499, 27513, 27510, -1, 27516, 27517, 27518, -1, 27517, 27519, 27518, -1, 27520, 27521, 27522, -1, 27521, 27523, 27522, -1, 27524, 27525, 27526, -1, 27525, 27527, 27526, -1, 27074, 27528, 27073, -1, 27529, 27528, 27074, -1, 27528, 27530, 27073, -1, 27531, 27532, 27533, -1, 27532, 27534, 27533, -1, 27066, 27535, 27065, -1, 27536, 27535, 27066, -1, 27535, 27537, 27065, -1, 27538, 27539, 27540, -1, 27539, 27541, 27540, -1, 27122, 27542, 27121, -1, 27543, 27542, 27122, -1, 27542, 27544, 27121, -1, 27545, 27546, 27547, -1, 27546, 27548, 27547, -1, 27082, 27549, 27081, -1, 27550, 27549, 27082, -1, 27549, 27551, 27081, -1, 27552, 27553, 27554, -1, 27553, 27555, 27554, -1, 27090, 27556, 27089, -1, 27557, 27556, 27090, -1, 27556, 27558, 27089, -1, 27559, 27560, 27561, -1, 27560, 27562, 27561, -1, 27098, 27563, 27097, -1, 27564, 27563, 27098, -1, 27563, 27565, 27097, -1, 27566, 27567, 27568, -1, 27567, 27569, 27568, -1, 27106, 27570, 27105, -1, 27571, 27570, 27106, -1, 27570, 27572, 27105, -1, 27573, 27574, 27575, -1, 27574, 27576, 27575, -1, 27114, 27577, 27113, -1, 27578, 27577, 27114, -1, 27577, 27579, 27113, -1, 27130, 27580, 27129, -1, 27581, 27580, 27130, -1, 27580, 27582, 27129, -1, 27251, 27583, 27347, -1, 27347, 27583, 27584, -1, 27584, 27585, 27586, -1, 27583, 27585, 27584, -1, 27586, 27587, 27588, -1, 27585, 27587, 27586, -1, 27588, 27589, 27590, -1, 27587, 27589, 27588, -1, 27590, 27591, 27592, -1, 27589, 27591, 27590, -1, 27592, 27139, 27141, -1, 27591, 27139, 27592, -1, 27346, 27593, 27356, -1, 27356, 27594, 27595, -1, 27593, 27594, 27356, -1, 27594, 27596, 27595, -1, 27595, 27597, 27598, -1, 27598, 27597, 27599, -1, 27596, 27597, 27595, -1, 27599, 27600, 27601, -1, 27597, 27600, 27599, -1, 27601, 27602, 27603, -1, 27600, 27602, 27601, -1, 27603, 27604, 27605, -1, 27602, 27604, 27603, -1, 27605, 27606, 27522, -1, 27604, 27606, 27605, -1, 27606, 27520, 27522, -1, 27346, 27348, 27593, -1, 27593, 27348, 27594, -1, 27594, 27348, 27596, -1, 27458, 27457, 27607, -1, 27607, 27608, 27609, -1, 27457, 27608, 27607, -1, 27609, 27610, 27611, -1, 27608, 27610, 27609, -1, 27611, 27612, 27613, -1, 27610, 27612, 27611, -1, 27613, 27614, 27615, -1, 27612, 27614, 27613, -1, 27615, 27131, 27133, -1, 27614, 27131, 27615, -1, 27292, 27291, 27616, -1, 27616, 27617, 27618, -1, 27291, 27617, 27616, -1, 27618, 27619, 27620, -1, 27617, 27619, 27618, -1, 27620, 27621, 27622, -1, 27619, 27621, 27620, -1, 27622, 27623, 27624, -1, 27621, 27623, 27622, -1, 27624, 27123, 27125, -1, 27623, 27123, 27624, -1, 27459, 27625, 27460, -1, 27460, 27626, 27627, -1, 27625, 27626, 27460, -1, 27626, 27628, 27627, -1, 27627, 27629, 27630, -1, 27630, 27629, 27631, -1, 27628, 27629, 27627, -1, 27631, 27632, 27633, -1, 27629, 27632, 27631, -1, 27633, 27634, 27635, -1, 27632, 27634, 27633, -1, 27635, 27636, 27637, -1, 27634, 27636, 27635, -1, 27637, 27638, 27467, -1, 27636, 27638, 27637, -1, 27638, 27465, 27467, -1, 27459, 27456, 27625, -1, 27625, 27456, 27626, -1, 27626, 27456, 27628, -1, 27639, 27640, 27641, -1, 27642, 27640, 27639, -1, 27640, 27643, 27641, -1, 27643, 27644, 27641, -1, 27645, 27646, 27647, -1, 27646, 27648, 27647, -1, 27648, 27649, 27647, -1, 27649, 27650, 27647, -1, 27650, 27651, 27647, -1, 27650, 27652, 27651, -1, 27653, 27654, 27655, -1, 27654, 27656, 27655, -1, 27656, 27657, 27655, -1, 27658, 27659, 27660, -1, 27659, 27661, 27660, -1, 27661, 27662, 27660, -1, 27663, 27664, 27665, -1, 27664, 27666, 27665, -1, 27666, 27667, 27665, -1, 27668, 27669, 27670, -1, 27669, 27671, 27670, -1, 27671, 27672, 27670, -1, 27673, 27674, 27675, -1, 27674, 27676, 27675, -1, 27676, 27677, 27675, -1, 27678, 27679, 27680, -1, 27679, 27681, 27680, -1, 27681, 27682, 27680, -1, 27683, 27684, 27685, -1, 27684, 27686, 27685, -1, 27686, 27687, 27685, -1, 27688, 27689, 27690, -1, 27689, 27691, 27690, -1, 27691, 27692, 27690, -1, 27693, 27694, 27695, -1, 27694, 27696, 27695, -1, 27696, 27697, 27695, -1, 27697, 27698, 27695, -1, 27698, 27163, 27695, -1, 27698, 27158, 27163, -1, 27698, 27155, 27158, -1, 27699, 27700, 27701, -1, 27701, 27702, 27703, -1, 27700, 27702, 27701, -1, 27703, 27704, 27705, -1, 27705, 27704, 27706, -1, 27702, 27704, 27703, -1, 27706, 27707, 27708, -1, 27704, 27707, 27706, -1, 27708, 27709, 27710, -1, 27707, 27709, 27708, -1, 27711, 27712, 27713, -1, 27710, 27712, 27711, -1, 27709, 27712, 27710, -1, 27714, 27715, 27716, -1, 27713, 27715, 27714, -1, 27712, 27715, 27713, -1, 27717, 27718, 27719, -1, 27716, 27718, 27717, -1, 27715, 27718, 27716, -1, 27719, 27541, 27539, -1, 27718, 27541, 27719, -1, 27685, 27720, 27683, -1, 27683, 27720, 27721, -1, 27721, 27722, 27723, -1, 27720, 27722, 27721, -1, 27722, 27724, 27723, -1, 27724, 27725, 27723, -1, 27723, 27544, 27542, -1, 27725, 27544, 27723, -1, 27221, 27220, 27726, -1, 27726, 27727, 27728, -1, 27220, 27727, 27726, -1, 27728, 27729, 27730, -1, 27727, 27729, 27728, -1, 27730, 27731, 27732, -1, 27729, 27731, 27730, -1, 27732, 27733, 27734, -1, 27731, 27733, 27732, -1, 27734, 27115, 27117, -1, 27733, 27115, 27734, -1, 27211, 27735, 27216, -1, 27216, 27736, 27737, -1, 27735, 27736, 27216, -1, 27736, 27738, 27737, -1, 27737, 27739, 27740, -1, 27740, 27739, 27741, -1, 27738, 27739, 27737, -1, 27741, 27742, 27743, -1, 27739, 27742, 27741, -1, 27743, 27744, 27745, -1, 27742, 27744, 27743, -1, 27745, 27746, 27747, -1, 27744, 27746, 27745, -1, 27747, 27748, 27540, -1, 27746, 27748, 27747, -1, 27748, 27538, 27540, -1, 27211, 27212, 27735, -1, 27735, 27212, 27736, -1, 27736, 27212, 27738, -1, 27749, 27750, 27751, -1, 27751, 27752, 27753, -1, 27750, 27752, 27751, -1, 27753, 27754, 27755, -1, 27755, 27754, 27756, -1, 27752, 27754, 27753, -1, 27756, 27757, 27758, -1, 27754, 27757, 27756, -1, 27758, 27759, 27760, -1, 27757, 27759, 27758, -1, 27761, 27762, 27763, -1, 27760, 27762, 27761, -1, 27759, 27762, 27760, -1, 27764, 27765, 27766, -1, 27763, 27765, 27764, -1, 27762, 27765, 27763, -1, 27767, 27768, 27769, -1, 27766, 27768, 27767, -1, 27765, 27768, 27766, -1, 27769, 27527, 27525, -1, 27768, 27527, 27769, -1, 27693, 27695, 27770, -1, 27695, 27771, 27770, -1, 27770, 27772, 27773, -1, 27771, 27772, 27770, -1, 27772, 27774, 27773, -1, 27774, 27775, 27773, -1, 27773, 27530, 27528, -1, 27775, 27530, 27773, -1, 27776, 27777, 27778, -1, 27778, 27779, 27780, -1, 27777, 27779, 27778, -1, 27780, 27781, 27782, -1, 27782, 27781, 27783, -1, 27779, 27781, 27780, -1, 27783, 27784, 27785, -1, 27781, 27784, 27783, -1, 27785, 27786, 27787, -1, 27784, 27786, 27785, -1, 27788, 27789, 27790, -1, 27787, 27789, 27788, -1, 27786, 27789, 27787, -1, 27791, 27792, 27793, -1, 27790, 27792, 27791, -1, 27789, 27792, 27790, -1, 27794, 27795, 27796, -1, 27793, 27795, 27794, -1, 27792, 27795, 27793, -1, 27796, 27534, 27532, -1, 27795, 27534, 27796, -1, 27690, 27797, 27688, -1, 27688, 27797, 27798, -1, 27798, 27799, 27800, -1, 27797, 27799, 27798, -1, 27799, 27801, 27800, -1, 27801, 27802, 27800, -1, 27800, 27537, 27535, -1, 27802, 27537, 27800, -1, 27803, 27804, 27805, -1, 27805, 27806, 27807, -1, 27804, 27806, 27805, -1, 27807, 27808, 27809, -1, 27809, 27808, 27810, -1, 27806, 27808, 27807, -1, 27810, 27811, 27812, -1, 27808, 27811, 27810, -1, 27812, 27813, 27814, -1, 27811, 27813, 27812, -1, 27815, 27816, 27817, -1, 27814, 27816, 27815, -1, 27813, 27816, 27814, -1, 27818, 27819, 27820, -1, 27817, 27819, 27818, -1, 27816, 27819, 27817, -1, 27821, 27822, 27823, -1, 27820, 27822, 27821, -1, 27819, 27822, 27820, -1, 27823, 27548, 27546, -1, 27822, 27548, 27823, -1, 27680, 27824, 27678, -1, 27678, 27824, 27825, -1, 27825, 27826, 27827, -1, 27824, 27826, 27825, -1, 27826, 27828, 27827, -1, 27828, 27829, 27827, -1, 27827, 27551, 27549, -1, 27829, 27551, 27827, -1, 27830, 27169, 27165, -1, 27831, 27832, 27830, -1, 27830, 27832, 27169, -1, 27831, 27833, 27832, -1, 27831, 27651, 27833, -1, 27651, 27652, 27833, -1, 27170, 27834, 27168, -1, 27168, 27834, 27166, -1, 27166, 27835, 27167, -1, 27167, 27835, 27836, -1, 27834, 27835, 27166, -1, 27837, 27838, 27839, -1, 27836, 27838, 27837, -1, 27835, 27838, 27836, -1, 27839, 27840, 27841, -1, 27838, 27840, 27839, -1, 27841, 27842, 27843, -1, 27840, 27842, 27841, -1, 27844, 27845, 27846, -1, 27843, 27845, 27844, -1, 27842, 27845, 27843, -1, 27847, 27848, 27849, -1, 27846, 27848, 27847, -1, 27845, 27848, 27846, -1, 27850, 27851, 27852, -1, 27849, 27851, 27850, -1, 27848, 27851, 27849, -1, 27852, 27555, 27553, -1, 27851, 27555, 27852, -1, 27675, 27853, 27673, -1, 27673, 27853, 27854, -1, 27854, 27855, 27856, -1, 27853, 27855, 27854, -1, 27855, 27857, 27856, -1, 27857, 27858, 27856, -1, 27856, 27558, 27556, -1, 27858, 27558, 27856, -1, 27859, 27860, 27861, -1, 27861, 27862, 27863, -1, 27860, 27862, 27861, -1, 27863, 27864, 27865, -1, 27865, 27864, 27866, -1, 27862, 27864, 27863, -1, 27866, 27867, 27868, -1, 27864, 27867, 27866, -1, 27868, 27869, 27870, -1, 27867, 27869, 27868, -1, 27871, 27872, 27873, -1, 27870, 27872, 27871, -1, 27869, 27872, 27870, -1, 27874, 27875, 27876, -1, 27873, 27875, 27874, -1, 27872, 27875, 27873, -1, 27877, 27878, 27879, -1, 27876, 27878, 27877, -1, 27875, 27878, 27876, -1, 27879, 27562, 27560, -1, 27878, 27562, 27879, -1, 27645, 27647, 27880, -1, 27647, 27881, 27880, -1, 27880, 27882, 27883, -1, 27881, 27882, 27880, -1, 27882, 27884, 27883, -1, 27884, 27885, 27883, -1, 27883, 27565, 27563, -1, 27885, 27565, 27883, -1, 27655, 27886, 27653, -1, 27653, 27886, 27887, -1, 27887, 27888, 27889, -1, 27886, 27888, 27887, -1, 27888, 27890, 27889, -1, 27890, 27891, 27889, -1, 27889, 27572, 27570, -1, 27891, 27572, 27889, -1, 27892, 27893, 27894, -1, 27894, 27895, 27896, -1, 27893, 27895, 27894, -1, 27897, 27898, 27899, -1, 27896, 27898, 27897, -1, 27895, 27898, 27896, -1, 27900, 27901, 27902, -1, 27899, 27901, 27900, -1, 27898, 27901, 27899, -1, 27902, 27903, 27904, -1, 27901, 27903, 27902, -1, 27905, 27906, 27907, -1, 27904, 27906, 27905, -1, 27903, 27906, 27904, -1, 27908, 27909, 27910, -1, 27907, 27909, 27908, -1, 27906, 27909, 27907, -1, 27911, 27912, 27913, -1, 27910, 27912, 27911, -1, 27909, 27912, 27910, -1, 27913, 27569, 27567, -1, 27912, 27569, 27913, -1, 27660, 27914, 27658, -1, 27658, 27914, 27915, -1, 27915, 27916, 27917, -1, 27914, 27916, 27915, -1, 27916, 27918, 27917, -1, 27918, 27919, 27917, -1, 27917, 27579, 27577, -1, 27919, 27579, 27917, -1, 27920, 27921, 27922, -1, 27922, 27923, 27924, -1, 27921, 27923, 27922, -1, 27925, 27926, 27927, -1, 27924, 27926, 27925, -1, 27923, 27926, 27924, -1, 27928, 27929, 27930, -1, 27927, 27929, 27928, -1, 27926, 27929, 27927, -1, 27930, 27931, 27932, -1, 27929, 27931, 27930, -1, 27933, 27934, 27935, -1, 27932, 27934, 27933, -1, 27931, 27934, 27932, -1, 27936, 27937, 27938, -1, 27935, 27937, 27936, -1, 27934, 27937, 27935, -1, 27939, 27940, 27941, -1, 27938, 27940, 27939, -1, 27937, 27940, 27938, -1, 27941, 27576, 27574, -1, 27940, 27576, 27941, -1, 27942, 27943, 27944, -1, 27942, 27945, 27943, -1, 27945, 27946, 27943, -1, 27945, 27639, 27946, -1, 27639, 27641, 27946, -1, 27639, 27945, 27642, -1, 27642, 27945, 27947, -1, 27945, 27942, 27947, -1, 27942, 27944, 27947, -1, 27947, 27948, 27949, -1, 27944, 27948, 27947, -1, 27948, 27950, 27949, -1, 27949, 27473, 27472, -1, 27950, 27473, 27949, -1, 27951, 27952, 27953, -1, 27953, 27954, 27955, -1, 27952, 27954, 27953, -1, 27955, 27956, 27957, -1, 27957, 27956, 27958, -1, 27954, 27956, 27955, -1, 27958, 27959, 27960, -1, 27956, 27959, 27958, -1, 27960, 27961, 27962, -1, 27959, 27961, 27960, -1, 27963, 27964, 27965, -1, 27962, 27964, 27963, -1, 27961, 27964, 27962, -1, 27966, 27967, 27968, -1, 27965, 27967, 27966, -1, 27964, 27967, 27965, -1, 27969, 27970, 27971, -1, 27968, 27970, 27969, -1, 27967, 27970, 27968, -1, 27971, 27469, 27468, -1, 27970, 27469, 27971, -1, 27665, 27972, 27663, -1, 27663, 27972, 27973, -1, 27973, 27974, 27975, -1, 27972, 27974, 27973, -1, 27974, 27976, 27975, -1, 27976, 27977, 27975, -1, 27975, 27582, 27580, -1, 27977, 27582, 27975, -1, 27670, 27978, 27668, -1, 27668, 27978, 27979, -1, 27979, 27980, 27981, -1, 27978, 27980, 27979, -1, 27980, 27982, 27981, -1, 27982, 27983, 27981, -1, 27981, 27464, 27463, -1, 27983, 27464, 27981, -1, 27984, 27985, 27986, -1, 27986, 27987, 27988, -1, 27985, 27987, 27986, -1, 27989, 27990, 27991, -1, 27988, 27990, 27989, -1, 27987, 27990, 27988, -1, 27992, 27993, 27994, -1, 27991, 27993, 27992, -1, 27990, 27993, 27991, -1, 27994, 27995, 27996, -1, 27993, 27995, 27994, -1, 27997, 27998, 27999, -1, 27996, 27998, 27997, -1, 27995, 27998, 27996, -1, 28000, 28001, 28002, -1, 27999, 28001, 28000, -1, 27998, 28001, 27999, -1, 28003, 28004, 28005, -1, 28002, 28004, 28003, -1, 28001, 28004, 28002, -1, 28005, 27523, 27521, -1, 28004, 27523, 28005, -1, 27148, 28006, 27149, -1, 27149, 28007, 28008, -1, 28006, 28007, 27149, -1, 28009, 28010, 28011, -1, 28008, 28010, 28009, -1, 28007, 28010, 28008, -1, 28011, 28012, 28013, -1, 28010, 28012, 28011, -1, 28013, 28014, 28015, -1, 28012, 28014, 28013, -1, 28016, 28017, 28018, -1, 28015, 28017, 28016, -1, 28014, 28017, 28015, -1, 28019, 28020, 28021, -1, 28018, 28020, 28019, -1, 28017, 28020, 28018, -1, 28022, 28023, 28024, -1, 28021, 28023, 28022, -1, 28020, 28023, 28021, -1, 28024, 27519, 27517, -1, 28023, 27519, 28024, -1, 27751, 28025, 28026, -1, 27751, 28026, 27749, -1, 28027, 28025, 27751, -1, 27753, 28027, 27751, -1, 27756, 28027, 27755, -1, 27755, 28027, 27753, -1, 28028, 28026, 28025, -1, 28028, 27749, 28026, -1, 28029, 28027, 28030, -1, 28031, 28025, 28027, -1, 28031, 28028, 28025, -1, 28031, 28027, 28029, -1, 28032, 28031, 28029, -1, 28033, 28031, 28032, -1, 28029, 28034, 28035, -1, 28029, 28030, 28034, -1, 28032, 28035, 28036, -1, 28032, 28036, 28037, -1, 28032, 28029, 28035, -1, 28033, 28032, 28037, -1, 28038, 28035, 28034, -1, 28038, 28036, 28035, -1, 28038, 28037, 28036, -1, 28039, 28040, 28041, -1, 28042, 28034, 27692, -1, 28042, 28038, 28034, -1, 28043, 28038, 28042, -1, 28044, 27692, 27691, -1, 28044, 28042, 27692, -1, 28045, 28046, 28038, -1, 28045, 28038, 28043, -1, 28047, 28043, 28042, -1, 28047, 28042, 28044, -1, 28048, 27691, 27689, -1, 28048, 27689, 27688, -1, 28048, 27688, 28049, -1, 28048, 28044, 27691, -1, 28050, 28051, 28046, -1, 28050, 28045, 28043, -1, 28050, 28043, 28047, -1, 28050, 28046, 28045, -1, 28052, 28049, 28041, -1, 28052, 28044, 28048, -1, 28052, 28048, 28049, -1, 28052, 28047, 28044, -1, 28053, 28040, 28051, -1, 28053, 28050, 28047, -1, 28053, 28052, 28041, -1, 28053, 28051, 28050, -1, 28053, 28041, 28040, -1, 28053, 28047, 28052, -1, 27778, 28054, 28055, -1, 27778, 28055, 27776, -1, 28056, 28054, 27778, -1, 27780, 28056, 27778, -1, 27783, 28056, 27782, -1, 27782, 28056, 27780, -1, 28057, 28055, 28054, -1, 28057, 27776, 28055, -1, 28058, 28056, 28059, -1, 28060, 28054, 28056, -1, 28060, 28057, 28054, -1, 28060, 28056, 28058, -1, 28061, 28060, 28058, -1, 28062, 28060, 28061, -1, 28059, 28063, 28064, -1, 28058, 28064, 28065, -1, 28058, 28059, 28064, -1, 28061, 28065, 28066, -1, 28061, 28058, 28065, -1, 28062, 28061, 28066, -1, 28067, 28064, 28063, -1, 28067, 28065, 28064, -1, 28067, 28066, 28065, -1, 28068, 28069, 28070, -1, 28071, 28063, 27687, -1, 28071, 28067, 28063, -1, 28072, 28067, 28071, -1, 28073, 27687, 27686, -1, 28073, 28071, 27687, -1, 28074, 28075, 28067, -1, 28074, 28067, 28072, -1, 28076, 28072, 28071, -1, 28076, 28071, 28073, -1, 28077, 27686, 27684, -1, 28077, 27684, 27683, -1, 28077, 27683, 28078, -1, 28077, 28073, 27686, -1, 28079, 28080, 28075, -1, 28079, 28074, 28072, -1, 28079, 28072, 28076, -1, 28079, 28075, 28074, -1, 28081, 28078, 28070, -1, 28081, 28073, 28077, -1, 28081, 28077, 28078, -1, 28081, 28076, 28073, -1, 28082, 28069, 28080, -1, 28082, 28079, 28076, -1, 28082, 28081, 28070, -1, 28082, 28080, 28079, -1, 28082, 28070, 28069, -1, 28082, 28076, 28081, -1, 27701, 28083, 28084, -1, 27701, 28084, 27699, -1, 28085, 28083, 27701, -1, 27703, 28085, 27701, -1, 27706, 28085, 27705, -1, 27705, 28085, 27703, -1, 28086, 28084, 28083, -1, 28086, 27699, 28084, -1, 28087, 28085, 28088, -1, 28089, 28083, 28085, -1, 28089, 28086, 28083, -1, 28089, 28085, 28087, -1, 28090, 28089, 28087, -1, 28091, 28089, 28090, -1, 28088, 28092, 28093, -1, 28087, 28093, 28094, -1, 28087, 28088, 28093, -1, 28090, 28087, 28094, -1, 28091, 28094, 28095, -1, 28091, 28090, 28094, -1, 28096, 28093, 28092, -1, 28096, 28094, 28093, -1, 28096, 28095, 28094, -1, 28097, 28098, 28099, -1, 28100, 28092, 27682, -1, 28100, 28096, 28092, -1, 28101, 28096, 28100, -1, 28102, 27682, 27681, -1, 28102, 28100, 27682, -1, 28103, 28104, 28096, -1, 28103, 28096, 28101, -1, 28105, 28101, 28100, -1, 28105, 28100, 28102, -1, 28106, 27681, 27679, -1, 28106, 27679, 27678, -1, 28106, 27678, 28107, -1, 28106, 28102, 27681, -1, 28108, 28109, 28104, -1, 28108, 28103, 28101, -1, 28108, 28101, 28105, -1, 28108, 28104, 28103, -1, 28110, 28107, 28099, -1, 28110, 28102, 28106, -1, 28110, 28106, 28107, -1, 28110, 28105, 28102, -1, 28111, 28098, 28109, -1, 28111, 28108, 28105, -1, 28111, 28110, 28099, -1, 28111, 28109, 28108, -1, 28111, 28099, 28098, -1, 28111, 28105, 28110, -1, 27805, 28112, 28113, -1, 27805, 28113, 27803, -1, 28114, 28112, 27805, -1, 27807, 28114, 27805, -1, 27810, 28114, 27809, -1, 27809, 28114, 27807, -1, 28115, 28113, 28112, -1, 28115, 27803, 28113, -1, 28116, 28114, 28117, -1, 28118, 28112, 28114, -1, 28118, 28115, 28112, -1, 28118, 28114, 28116, -1, 28119, 28118, 28116, -1, 28120, 28118, 28119, -1, 28117, 28121, 28122, -1, 28116, 28122, 28123, -1, 28116, 28117, 28122, -1, 28119, 28123, 28124, -1, 28119, 28116, 28123, -1, 28120, 28119, 28124, -1, 28125, 28122, 28121, -1, 28125, 28123, 28122, -1, 28125, 28124, 28123, -1, 28126, 28127, 28128, -1, 28129, 28121, 27677, -1, 28129, 28125, 28121, -1, 28130, 28125, 28129, -1, 28131, 27677, 27676, -1, 28131, 28129, 27677, -1, 28132, 28133, 28125, -1, 28132, 28125, 28130, -1, 28134, 28130, 28129, -1, 28134, 28129, 28131, -1, 28135, 27676, 27674, -1, 28135, 27674, 27673, -1, 28135, 27673, 28136, -1, 28135, 28131, 27676, -1, 28137, 28138, 28133, -1, 28137, 28132, 28130, -1, 28137, 28130, 28134, -1, 28137, 28133, 28132, -1, 28139, 28136, 28128, -1, 28139, 28131, 28135, -1, 28139, 28135, 28136, -1, 28139, 28134, 28131, -1, 28140, 28127, 28138, -1, 28140, 28137, 28134, -1, 28140, 28139, 28128, -1, 28140, 28138, 28137, -1, 28140, 28128, 28127, -1, 28140, 28134, 28139, -1, 27861, 28141, 28142, -1, 27861, 28142, 27859, -1, 28143, 28141, 27861, -1, 27863, 28143, 27861, -1, 27866, 28143, 27865, -1, 27865, 28143, 27863, -1, 28144, 28142, 28141, -1, 28144, 27859, 28142, -1, 28145, 28143, 28146, -1, 28147, 28141, 28143, -1, 28147, 28144, 28141, -1, 28147, 28143, 28145, -1, 28148, 28147, 28145, -1, 28149, 28147, 28148, -1, 28146, 28150, 28151, -1, 28145, 28151, 28152, -1, 28145, 28146, 28151, -1, 28148, 28152, 28153, -1, 28148, 28145, 28152, -1, 28149, 28148, 28153, -1, 28154, 28151, 28150, -1, 28154, 28152, 28151, -1, 28154, 28153, 28152, -1, 28155, 28156, 28157, -1, 28158, 28150, 27657, -1, 28158, 28154, 28150, -1, 28159, 28154, 28158, -1, 28160, 27657, 27656, -1, 28160, 28158, 27657, -1, 28161, 28162, 28154, -1, 28161, 28154, 28159, -1, 28163, 28159, 28158, -1, 28163, 28158, 28160, -1, 28164, 27656, 27654, -1, 28164, 27654, 27653, -1, 28164, 27653, 28165, -1, 28164, 28160, 27656, -1, 28166, 28167, 28162, -1, 28166, 28161, 28159, -1, 28166, 28159, 28163, -1, 28166, 28162, 28161, -1, 28168, 28165, 28157, -1, 28168, 28160, 28164, -1, 28168, 28164, 28165, -1, 28168, 28163, 28160, -1, 28169, 28156, 28167, -1, 28169, 28166, 28163, -1, 28169, 28168, 28157, -1, 28169, 28167, 28166, -1, 28169, 28157, 28156, -1, 28169, 28163, 28168, -1, 28170, 27897, 27899, -1, 28171, 27892, 27894, -1, 28172, 27896, 27897, -1, 28172, 27897, 28170, -1, 28173, 28174, 28175, -1, 28173, 28175, 28171, -1, 28173, 27894, 27896, -1, 28173, 28170, 28174, -1, 28173, 28172, 28170, -1, 28173, 28171, 27894, -1, 28173, 27896, 28172, -1, 28176, 28171, 28175, -1, 28176, 27892, 28171, -1, 28177, 28174, 28178, -1, 28179, 28175, 28174, -1, 28179, 28176, 28175, -1, 28179, 28174, 28177, -1, 28180, 28179, 28177, -1, 28181, 28179, 28180, -1, 28177, 28182, 28183, -1, 28177, 28178, 28182, -1, 28180, 28183, 28184, -1, 28180, 28184, 28185, -1, 28180, 28177, 28183, -1, 28181, 28180, 28185, -1, 28186, 28183, 28182, -1, 28186, 28184, 28183, -1, 28186, 28185, 28184, -1, 28187, 28188, 28189, -1, 28190, 28182, 27662, -1, 28190, 28186, 28182, -1, 28191, 28186, 28190, -1, 28192, 27662, 27661, -1, 28192, 28190, 27662, -1, 28193, 28194, 28186, -1, 28193, 28186, 28191, -1, 28195, 28191, 28190, -1, 28195, 28190, 28192, -1, 28196, 27661, 27659, -1, 28196, 27659, 27658, -1, 28196, 27658, 28197, -1, 28196, 28192, 27661, -1, 28198, 28199, 28194, -1, 28198, 28193, 28191, -1, 28198, 28191, 28195, -1, 28198, 28194, 28193, -1, 28200, 28197, 28189, -1, 28200, 28192, 28196, -1, 28200, 28196, 28197, -1, 28200, 28195, 28192, -1, 28201, 28188, 28199, -1, 28201, 28198, 28195, -1, 28201, 28200, 28189, -1, 28201, 28199, 28198, -1, 28201, 28189, 28188, -1, 28201, 28195, 28200, -1, 28202, 27925, 27927, -1, 28203, 27920, 27922, -1, 28204, 27924, 27925, -1, 28204, 27925, 28202, -1, 28205, 28206, 28207, -1, 28205, 28207, 28203, -1, 28205, 27922, 27924, -1, 28205, 28202, 28206, -1, 28205, 28204, 28202, -1, 28205, 28203, 27922, -1, 28205, 27924, 28204, -1, 28208, 28203, 28207, -1, 28208, 27920, 28203, -1, 28209, 28206, 28210, -1, 28211, 28207, 28206, -1, 28211, 28208, 28207, -1, 28211, 28206, 28209, -1, 28212, 28211, 28209, -1, 28213, 28211, 28212, -1, 28209, 28214, 28215, -1, 28209, 28210, 28214, -1, 28212, 28215, 28216, -1, 28212, 28209, 28215, -1, 28213, 28216, 28217, -1, 28213, 28212, 28216, -1, 28218, 28215, 28214, -1, 28218, 28216, 28215, -1, 28218, 28217, 28216, -1, 28219, 28220, 28221, -1, 28222, 28214, 27667, -1, 28222, 28218, 28214, -1, 28223, 28218, 28222, -1, 28224, 27667, 27666, -1, 28224, 28222, 27667, -1, 28225, 28226, 28218, -1, 28225, 28218, 28223, -1, 28227, 28223, 28222, -1, 28227, 28222, 28224, -1, 28228, 27666, 27664, -1, 28228, 27664, 27663, -1, 28228, 27663, 28229, -1, 28228, 28224, 27666, -1, 28230, 28231, 28226, -1, 28230, 28225, 28223, -1, 28230, 28223, 28227, -1, 28230, 28226, 28225, -1, 28232, 28229, 28221, -1, 28232, 28224, 28228, -1, 28232, 28228, 28229, -1, 28232, 28227, 28224, -1, 28233, 28220, 28231, -1, 28233, 28230, 28227, -1, 28233, 28232, 28221, -1, 28233, 28231, 28230, -1, 28233, 28221, 28220, -1, 28233, 28227, 28232, -1, 28234, 27989, 27991, -1, 28235, 27984, 27986, -1, 28236, 27988, 27989, -1, 28236, 27989, 28234, -1, 28237, 28238, 28239, -1, 28237, 28239, 28235, -1, 28237, 27986, 27988, -1, 28237, 28234, 28238, -1, 28237, 28236, 28234, -1, 28237, 28235, 27986, -1, 28237, 27988, 28236, -1, 28240, 28235, 28239, -1, 28240, 27984, 28235, -1, 28241, 28238, 28242, -1, 28243, 28239, 28238, -1, 28243, 28240, 28239, -1, 28243, 28238, 28241, -1, 28244, 28243, 28241, -1, 28245, 28243, 28244, -1, 28241, 28246, 28247, -1, 28241, 28242, 28246, -1, 28244, 28247, 28248, -1, 28244, 28241, 28247, -1, 28245, 28248, 28249, -1, 28245, 28244, 28248, -1, 28250, 28247, 28246, -1, 28250, 28248, 28247, -1, 28250, 28249, 28248, -1, 28251, 27640, 27642, -1, 28252, 27640, 28251, -1, 28253, 28246, 27644, -1, 28253, 28250, 28246, -1, 28254, 28250, 28253, -1, 28254, 28253, 27644, -1, 28255, 28256, 28257, -1, 28255, 28257, 28250, -1, 28255, 28250, 28254, -1, 28258, 27644, 27643, -1, 28258, 28254, 27644, -1, 28259, 28255, 28254, -1, 28259, 28256, 28255, -1, 28259, 28254, 28258, -1, 28260, 27643, 27640, -1, 28261, 28258, 27643, -1, 28261, 28260, 27640, -1, 28261, 27643, 28260, -1, 28261, 27640, 28252, -1, 28262, 28252, 28263, -1, 28262, 28263, 28264, -1, 28262, 28264, 28256, -1, 28262, 28258, 28261, -1, 28262, 28259, 28258, -1, 28262, 28261, 28252, -1, 28262, 28256, 28259, -1, 27953, 28265, 28266, -1, 27953, 28266, 27951, -1, 28267, 28265, 27953, -1, 27955, 28267, 27953, -1, 27958, 28267, 27957, -1, 27957, 28267, 27955, -1, 28268, 28266, 28265, -1, 28268, 27951, 28266, -1, 28269, 28267, 28270, -1, 28271, 28265, 28267, -1, 28271, 28268, 28265, -1, 28271, 28267, 28269, -1, 28272, 28271, 28269, -1, 28273, 28271, 28272, -1, 28270, 28274, 28275, -1, 28269, 28275, 28276, -1, 28269, 28270, 28275, -1, 28272, 28276, 28277, -1, 28272, 28269, 28276, -1, 28273, 28272, 28277, -1, 28278, 28275, 28274, -1, 28278, 28276, 28275, -1, 28278, 28277, 28276, -1, 28279, 28280, 28281, -1, 28282, 28274, 27672, -1, 28282, 28278, 28274, -1, 28283, 28278, 28282, -1, 28284, 27672, 27671, -1, 28284, 28282, 27672, -1, 28285, 28286, 28278, -1, 28285, 28278, 28283, -1, 28287, 28283, 28282, -1, 28287, 28282, 28284, -1, 28288, 27671, 27669, -1, 28288, 27669, 27668, -1, 28288, 27668, 28289, -1, 28288, 28284, 27671, -1, 28290, 28291, 28286, -1, 28290, 28285, 28283, -1, 28290, 28283, 28287, -1, 28290, 28286, 28285, -1, 28292, 28289, 28281, -1, 28292, 28284, 28288, -1, 28292, 28288, 28289, -1, 28292, 28287, 28284, -1, 28293, 28280, 28291, -1, 28293, 28290, 28287, -1, 28293, 28292, 28281, -1, 28293, 28291, 28290, -1, 28293, 28281, 28280, -1, 28293, 28287, 28292, -1, 27172, 27175, 28294, -1, 28294, 28295, 28296, -1, 27175, 28295, 28294, -1, 28296, 28297, 28298, -1, 28295, 28297, 28296, -1, 28298, 28299, 28300, -1, 28297, 28299, 28298, -1, 28300, 28301, 28302, -1, 28299, 28301, 28300, -1, 28302, 27107, 27109, -1, 28301, 27107, 28302, -1, 27293, 28303, 27284, -1, 27284, 28304, 28305, -1, 28303, 28304, 27284, -1, 28304, 28306, 28305, -1, 28305, 28307, 28308, -1, 28308, 28307, 28309, -1, 28306, 28307, 28305, -1, 28309, 28310, 28311, -1, 28307, 28310, 28309, -1, 28311, 28312, 28313, -1, 28310, 28312, 28311, -1, 28313, 28314, 28315, -1, 28312, 28314, 28313, -1, 28315, 28316, 27575, -1, 28314, 28316, 28315, -1, 28316, 27573, 27575, -1, 27293, 27290, 28303, -1, 28303, 27290, 28304, -1, 28304, 27290, 28306, -1, 27182, 27181, 28317, -1, 28317, 28318, 28319, -1, 27181, 28318, 28317, -1, 28319, 28320, 28321, -1, 28318, 28320, 28319, -1, 28321, 28322, 28323, -1, 28320, 28322, 28321, -1, 28323, 28324, 28325, -1, 28322, 28324, 28323, -1, 28325, 27099, 27101, -1, 28324, 27099, 28325, -1, 27171, 28326, 27174, -1, 27174, 28327, 28328, -1, 28326, 28327, 27174, -1, 28327, 28329, 28328, -1, 28328, 28330, 28331, -1, 28331, 28330, 28332, -1, 28329, 28330, 28328, -1, 28332, 28333, 28334, -1, 28330, 28333, 28332, -1, 28334, 28335, 28336, -1, 28333, 28335, 28334, -1, 28336, 28337, 28338, -1, 28335, 28337, 28336, -1, 28338, 28339, 27568, -1, 28337, 28339, 28338, -1, 28339, 27566, 27568, -1, 27171, 27173, 28326, -1, 28326, 27173, 28327, -1, 28327, 27173, 28329, -1, 27189, 27188, 28340, -1, 28340, 28341, 28342, -1, 27188, 28341, 28340, -1, 28342, 28343, 28344, -1, 28341, 28343, 28342, -1, 28344, 28345, 28346, -1, 28343, 28345, 28344, -1, 28346, 28347, 28348, -1, 28345, 28347, 28346, -1, 28348, 27091, 27093, -1, 28347, 27091, 28348, -1, 27183, 28349, 27185, -1, 27185, 28350, 28351, -1, 28349, 28350, 27185, -1, 28350, 28352, 28351, -1, 28351, 28353, 28354, -1, 28354, 28353, 28355, -1, 28352, 28353, 28351, -1, 28355, 28356, 28357, -1, 28353, 28356, 28355, -1, 28357, 28358, 28359, -1, 28356, 28358, 28357, -1, 28359, 28360, 28361, -1, 28358, 28360, 28359, -1, 28361, 28362, 27561, -1, 28360, 28362, 28361, -1, 28362, 27559, 27561, -1, 27183, 27184, 28349, -1, 28349, 27184, 28350, -1, 28350, 27184, 28352, -1, 27197, 27196, 28363, -1, 28363, 28364, 28365, -1, 27196, 28364, 28363, -1, 28365, 28366, 28367, -1, 28364, 28366, 28365, -1, 28367, 28368, 28369, -1, 28366, 28368, 28367, -1, 28369, 28370, 28371, -1, 28368, 28370, 28369, -1, 28371, 27083, 27085, -1, 28370, 27083, 28371, -1, 27190, 28372, 27192, -1, 27192, 28373, 28374, -1, 28372, 28373, 27192, -1, 28373, 28375, 28374, -1, 28374, 28376, 28377, -1, 28377, 28376, 28378, -1, 28375, 28376, 28374, -1, 28378, 28379, 28380, -1, 28376, 28379, 28378, -1, 28380, 28381, 28382, -1, 28379, 28381, 28380, -1, 28382, 28383, 28384, -1, 28381, 28383, 28382, -1, 28384, 28385, 27554, -1, 28383, 28385, 28384, -1, 28385, 27552, 27554, -1, 27190, 27191, 28372, -1, 28372, 27191, 28373, -1, 28373, 27191, 28375, -1, 27210, 27209, 28386, -1, 28386, 28387, 28388, -1, 27209, 28387, 28386, -1, 28388, 28389, 28390, -1, 28387, 28389, 28388, -1, 28390, 28391, 28392, -1, 28389, 28391, 28390, -1, 28392, 28393, 28394, -1, 28391, 28393, 28392, -1, 28394, 27075, 27077, -1, 28393, 27075, 28394, -1, 27198, 28395, 27204, -1, 27204, 28396, 28397, -1, 28395, 28396, 27204, -1, 28396, 28398, 28397, -1, 28397, 28399, 28400, -1, 28400, 28399, 28401, -1, 28398, 28399, 28397, -1, 28401, 28402, 28403, -1, 28399, 28402, 28401, -1, 28403, 28404, 28405, -1, 28402, 28404, 28403, -1, 28405, 28406, 28407, -1, 28404, 28406, 28405, -1, 28407, 28408, 27547, -1, 28406, 28408, 28407, -1, 28408, 27545, 27547, -1, 27198, 27199, 28395, -1, 28395, 27199, 28396, -1, 28396, 27199, 28398, -1, 27237, 27236, 28409, -1, 28409, 28410, 28411, -1, 27236, 28410, 28409, -1, 28411, 28412, 28413, -1, 28410, 28412, 28411, -1, 28413, 28414, 28415, -1, 28412, 28414, 28413, -1, 28415, 28416, 28417, -1, 28414, 28416, 28415, -1, 28417, 27067, 27069, -1, 28416, 27067, 28417, -1, 27231, 28418, 27233, -1, 27233, 28419, 28420, -1, 28418, 28419, 27233, -1, 28419, 28421, 28420, -1, 28420, 28422, 28423, -1, 28423, 28422, 28424, -1, 28421, 28422, 28420, -1, 28424, 28425, 28426, -1, 28422, 28425, 28424, -1, 28426, 28427, 28428, -1, 28425, 28427, 28426, -1, 28428, 28429, 28430, -1, 28427, 28429, 28428, -1, 28430, 28431, 27526, -1, 28429, 28431, 28430, -1, 28431, 27524, 27526, -1, 27231, 27232, 28418, -1, 28418, 27232, 28419, -1, 28419, 27232, 28421, -1, 27238, 28432, 27240, -1, 27240, 28433, 28434, -1, 28432, 28433, 27240, -1, 28433, 28435, 28434, -1, 28434, 28436, 28437, -1, 28437, 28436, 28438, -1, 28435, 28436, 28434, -1, 28438, 28439, 28440, -1, 28436, 28439, 28438, -1, 28440, 28441, 28442, -1, 28439, 28441, 28440, -1, 28442, 28443, 28444, -1, 28441, 28443, 28442, -1, 28444, 28445, 27518, -1, 28443, 28445, 28444, -1, 28445, 27516, 27518, -1, 27238, 27239, 28432, -1, 28432, 27239, 28433, -1, 28433, 27239, 28435, -1, 28446, 27224, 28447, -1, 28448, 27224, 28446, -1, 27222, 27224, 28448, -1, 27222, 28448, 27225, -1, 27225, 28446, 28449, -1, 28448, 28446, 27225, -1, 28446, 28447, 28449, -1, 28450, 28451, 28452, -1, 28449, 28451, 28450, -1, 28447, 28451, 28449, -1, 28452, 28453, 28454, -1, 28451, 28453, 28452, -1, 28454, 28455, 28456, -1, 28453, 28455, 28454, -1, 28456, 28457, 28458, -1, 28455, 28457, 28456, -1, 28458, 28459, 27533, -1, 28457, 28459, 28458, -1, 28459, 27531, 27533, -1, 27230, 27229, 28460, -1, 28460, 28461, 28462, -1, 27229, 28461, 28460, -1, 28462, 28463, 28464, -1, 28461, 28463, 28462, -1, 28464, 28465, 28466, -1, 28463, 28465, 28464, -1, 28466, 28467, 28468, -1, 28465, 28467, 28466, -1, 28468, 27059, 27061, -1, 28467, 27059, 28468, -1, 28469, 28470, 28471, -1, 28472, 28473, 28474, -1, 28475, 28476, 28477, -1, 28478, 28479, 28480, -1, 28481, 28482, 28483, -1, 28475, 28484, 28476, -1, 28485, 28480, 28486, -1, 28481, 28483, 28487, -1, 28485, 28486, 28488, -1, 28489, 28490, 28491, -1, 28489, 28491, 28492, -1, 28493, 28494, 28495, -1, 28493, 28495, 28496, -1, 28497, 28481, 28487, -1, 28493, 28496, 28498, -1, 28497, 28487, 28499, -1, 28500, 28498, 28501, -1, 28502, 28474, 28503, -1, 28504, 28505, 28484, -1, 28500, 28493, 28498, -1, 28502, 28503, 28506, -1, 28504, 28492, 28505, -1, 28500, 28494, 28493, -1, 28507, 28485, 28488, -1, 28508, 28509, 28510, -1, 28511, 28504, 28484, -1, 28512, 28506, 28513, -1, 28511, 28484, 28475, -1, 28514, 28515, 28516, -1, 28512, 28502, 28506, -1, 28517, 28477, 28518, -1, 28514, 28516, 28519, -1, 28520, 28521, 28522, -1, 28517, 28475, 28477, -1, 28520, 28523, 28524, -1, 28520, 28524, 28482, -1, 28525, 28489, 28492, -1, 28520, 28522, 28523, -1, 28526, 28527, 28478, -1, 28525, 28492, 28504, -1, 28528, 28529, 28530, -1, 28528, 28513, 28529, -1, 28526, 28531, 28527, -1, 28532, 28533, 28490, -1, 28534, 28514, 28519, -1, 28532, 28490, 28489, -1, 28535, 28472, 28474, -1, 28534, 28519, 28531, -1, 28535, 28474, 28502, -1, 28536, 28525, 28504, -1, 28536, 28504, 28511, -1, 28537, 28478, 28480, -1, 28537, 28480, 28485, -1, 28538, 28485, 28507, -1, 28539, 28502, 28512, -1, 28540, 28475, 28517, -1, 28538, 28537, 28485, -1, 28539, 28535, 28502, -1, 28540, 28511, 28475, -1, 28496, 28499, 28472, -1, 28541, 28517, 28518, -1, 28542, 28543, 28494, -1, 28496, 28497, 28499, -1, 28542, 28501, 28515, -1, 28544, 28518, 28545, -1, 28542, 28500, 28501, -1, 28542, 28494, 28500, -1, 28544, 28541, 28518, -1, 28546, 28512, 28513, -1, 28546, 28513, 28528, -1, 28547, 28526, 28478, -1, 28548, 28532, 28489, -1, 28548, 28489, 28525, -1, 28547, 28478, 28537, -1, 28549, 28530, 28550, -1, 28549, 28528, 28530, -1, 28479, 28549, 28550, -1, 28551, 28537, 28538, -1, 28551, 28547, 28537, -1, 28552, 28482, 28481, -1, 28483, 28536, 28511, -1, 28552, 28520, 28482, -1, 28483, 28511, 28540, -1, 28553, 28531, 28526, -1, 28552, 28521, 28520, -1, 28524, 28548, 28525, -1, 28553, 28534, 28531, -1, 28524, 28525, 28536, -1, 28554, 28552, 28481, -1, 28554, 28481, 28497, -1, 28555, 28488, 28556, -1, 28554, 28521, 28552, -1, 28555, 28557, 28558, -1, 28555, 28507, 28488, -1, 28559, 28517, 28541, -1, 28559, 28540, 28517, -1, 28516, 28539, 28512, -1, 28473, 28541, 28544, -1, 28555, 28556, 28557, -1, 28516, 28512, 28546, -1, 28473, 28559, 28541, -1, 28560, 28543, 28542, -1, 28560, 28515, 28514, -1, 28561, 28522, 28562, -1, 28498, 28472, 28535, -1, 28557, 28556, 28563, -1, 28560, 28542, 28515, -1, 28498, 28496, 28472, -1, 28561, 28562, 28533, -1, 28564, 28514, 28534, -1, 28561, 28533, 28532, -1, 28564, 28560, 28514, -1, 28564, 28543, 28560, -1, 28565, 28558, 28566, -1, 28565, 28566, 28567, -1, 28501, 28498, 28535, -1, 28501, 28535, 28539, -1, 28503, 28544, 28545, -1, 28565, 28538, 28507, -1, 28565, 28507, 28555, -1, 28487, 28483, 28540, -1, 28565, 28555, 28558, -1, 28568, 28546, 28528, -1, 28569, 28553, 28526, -1, 28568, 28528, 28549, -1, 28569, 28526, 28547, -1, 28487, 28540, 28559, -1, 28527, 28568, 28549, -1, 28482, 28536, 28483, -1, 28482, 28524, 28536, -1, 28471, 28569, 28547, -1, 28471, 28547, 28551, -1, 28527, 28549, 28479, -1, 28499, 28559, 28473, -1, 28570, 28567, 28571, -1, 28480, 28550, 28486, -1, 28570, 28571, 28572, -1, 28480, 28479, 28550, -1, 28570, 28538, 28565, -1, 28499, 28487, 28559, -1, 28570, 28551, 28538, -1, 28495, 28494, 28521, -1, 28570, 28565, 28567, -1, 28495, 28497, 28496, -1, 28573, 28574, 28543, -1, 28495, 28521, 28554, -1, 28474, 28544, 28503, -1, 28495, 28554, 28497, -1, 28573, 28543, 28564, -1, 28474, 28473, 28544, -1, 28573, 28534, 28553, -1, 28575, 28561, 28532, -1, 28573, 28564, 28534, -1, 28575, 28532, 28548, -1, 28576, 28553, 28569, -1, 28575, 28522, 28561, -1, 28519, 28546, 28568, -1, 28506, 28545, 28529, -1, 28576, 28573, 28553, -1, 28519, 28516, 28546, -1, 28506, 28503, 28545, -1, 28576, 28574, 28573, -1, 28577, 28572, 28578, -1, 28577, 28471, 28551, -1, 28531, 28519, 28568, -1, 28577, 28551, 28570, -1, 28531, 28568, 28527, -1, 28577, 28570, 28572, -1, 28513, 28506, 28529, -1, 28505, 28579, 28580, -1, 28505, 28580, 28509, -1, 28505, 28508, 28476, -1, 28470, 28581, 28574, -1, 28505, 28509, 28508, -1, 28470, 28569, 28471, -1, 28515, 28501, 28539, -1, 28470, 28576, 28569, -1, 28523, 28548, 28524, -1, 28492, 28491, 28579, -1, 28470, 28574, 28576, -1, 28523, 28575, 28548, -1, 28523, 28522, 28575, -1, 28469, 28582, 28581, -1, 28469, 28578, 28582, -1, 28492, 28579, 28505, -1, 28469, 28577, 28578, -1, 28515, 28539, 28516, -1, 28469, 28471, 28577, -1, 28472, 28499, 28473, -1, 28469, 28581, 28470, -1, 28478, 28527, 28479, -1, 28484, 28505, 28476, -1, 28583, 28581, 28582, -1, 28584, 28581, 28583, -1, 28585, 28574, 28584, -1, 28584, 28574, 28581, -1, 28585, 28543, 28574, -1, 28586, 28494, 28585, -1, 28585, 28494, 28543, -1, 28587, 28521, 28586, -1, 28586, 28521, 28494, -1, 28588, 28522, 28587, -1, 28587, 28522, 28521, -1, 28588, 28562, 28522, -1, 28589, 28590, 28591, -1, 28592, 28518, 28477, -1, 28592, 28593, 28590, -1, 28592, 28477, 28594, -1, 28592, 28594, 28593, -1, 28595, 28596, 28597, -1, 28595, 28589, 28596, -1, 28598, 28545, 28518, -1, 28599, 28600, 28601, -1, 28598, 28590, 28589, -1, 28598, 28518, 28592, -1, 28598, 28592, 28590, -1, 28602, 28597, 28603, -1, 28602, 28595, 28597, -1, 28604, 28529, 28545, -1, 28604, 28589, 28595, -1, 28604, 28545, 28598, -1, 28604, 28598, 28589, -1, 28605, 28603, 28606, -1, 28605, 28602, 28603, -1, 28607, 28529, 28604, -1, 28607, 28530, 28529, -1, 28607, 28595, 28602, -1, 28607, 28604, 28595, -1, 28608, 28606, 28609, -1, 28508, 28510, 28610, -1, 28508, 28610, 28611, -1, 28608, 28605, 28606, -1, 28508, 28611, 28612, -1, 28508, 28612, 28613, -1, 28614, 28550, 28530, -1, 28614, 28530, 28607, -1, 28614, 28602, 28605, -1, 28614, 28607, 28602, -1, 28615, 28486, 28550, -1, 28615, 28608, 28486, -1, 28615, 28605, 28608, -1, 28615, 28614, 28605, -1, 28615, 28550, 28614, -1, 28616, 28486, 28608, -1, 28616, 28609, 28617, -1, 28616, 28617, 28618, -1, 28616, 28608, 28609, -1, 28616, 28618, 28556, -1, 28619, 28556, 28488, -1, 28619, 28488, 28486, -1, 28619, 28486, 28616, -1, 28619, 28616, 28556, -1, 28620, 28618, 28621, -1, 28620, 28621, 28622, -1, 28620, 28556, 28618, -1, 28623, 28556, 28620, -1, 28624, 28556, 28623, -1, 28625, 28556, 28624, -1, 28563, 28556, 28625, -1, 28593, 28626, 28600, -1, 28593, 28599, 28627, -1, 28593, 28600, 28599, -1, 28594, 28477, 28476, -1, 28594, 28476, 28508, -1, 28594, 28613, 28626, -1, 28594, 28508, 28613, -1, 28594, 28626, 28593, -1, 28590, 28627, 28591, -1, 28590, 28593, 28627, -1, 28589, 28591, 28596, -1, 26688, 28628, 26690, -1, 26686, 28628, 26688, -1, 26684, 28628, 26686, -1, 26682, 28629, 26684, -1, 28630, 28629, 26682, -1, 28631, 28629, 28630, -1, 28632, 28629, 28631, -1, 28633, 28629, 28632, -1, 28634, 28629, 28633, -1, 28635, 28629, 28634, -1, 26702, 26700, 28636, -1, 26684, 28629, 28628, -1, 28637, 28629, 28635, -1, 28636, 26704, 26702, -1, 28637, 28635, 28638, -1, 26700, 26698, 28636, -1, 28636, 26706, 26704, -1, 26698, 26696, 28636, -1, 28636, 26707, 26706, -1, 28637, 28639, 28636, -1, 28636, 28639, 26707, -1, 28637, 28640, 28639, -1, 28637, 28641, 28640, -1, 28637, 28642, 28641, -1, 28637, 28643, 28642, -1, 28637, 28638, 28643, -1, 26694, 28644, 26696, -1, 26696, 28645, 28636, -1, 28644, 28645, 26696, -1, 26692, 28646, 26694, -1, 26694, 28646, 28644, -1, 28645, 28647, 28636, -1, 26690, 28648, 26692, -1, 26692, 28648, 28646, -1, 26690, 28628, 28648, -1, 28649, 28650, 28651, -1, 28651, 28652, 28653, -1, 28650, 28652, 28651, -1, 28654, 28655, 28649, -1, 28649, 28655, 28650, -1, 28653, 28656, 28657, -1, 28652, 28656, 28653, -1, 28658, 28659, 28654, -1, 28654, 28659, 28655, -1, 28660, 28661, 28658, -1, 28658, 28661, 28659, -1, 28662, 28663, 28660, -1, 28660, 28663, 28661, -1, 27057, 28664, 27058, -1, 27058, 28664, 28665, -1, 28665, 28666, 28667, -1, 28664, 28666, 28665, -1, 28667, 28668, 28669, -1, 28666, 28668, 28667, -1, 28669, 28670, 28671, -1, 28668, 28670, 28669, -1, 28671, 28672, 28673, -1, 28670, 28672, 28671, -1, 28673, 28674, 28675, -1, 28672, 28674, 28673, -1, 28675, 28676, 28677, -1, 28674, 28676, 28675, -1, 28677, 28678, 28679, -1, 28676, 28678, 28677, -1, 28679, 28680, 28681, -1, 28678, 28680, 28679, -1, 28681, 28682, 28683, -1, 28680, 28682, 28681, -1, 28683, 28684, 28685, -1, 28682, 28684, 28683, -1, 28685, 28686, 28687, -1, 28684, 28686, 28685, -1, 28687, 27032, 27031, -1, 28686, 27032, 28687, -1, 27030, 27029, 28688, -1, 28688, 28689, 28690, -1, 27029, 28689, 28688, -1, 28690, 28691, 28692, -1, 28689, 28691, 28690, -1, 28692, 28693, 28694, -1, 28691, 28693, 28692, -1, 28694, 28695, 28696, -1, 28693, 28695, 28694, -1, 28696, 28697, 28698, -1, 28695, 28697, 28696, -1, 28698, 28699, 28700, -1, 28697, 28699, 28698, -1, 28700, 28701, 28702, -1, 28699, 28701, 28700, -1, 28702, 28703, 28704, -1, 28701, 28703, 28702, -1, 28704, 28705, 28706, -1, 28703, 28705, 28704, -1, 28706, 28707, 28708, -1, 28705, 28707, 28706, -1, 28708, 28709, 28710, -1, 28707, 28709, 28708, -1, 28710, 28711, 27003, -1, 28709, 28711, 28710, -1, 28711, 27004, 27003, -1, 26961, 26300, 26276, -1, 28712, 26300, 26961, -1, 28713, 26284, 28714, -1, 26285, 26284, 28713, -1, 28715, 28716, 28717, -1, 26277, 28716, 28718, -1, 28718, 28716, 28719, -1, 28719, 28716, 28720, -1, 28720, 28716, 28715, -1, 26276, 28716, 26277, -1, 26301, 28716, 26300, -1, 28721, 28716, 28722, -1, 28722, 28716, 26301, -1, 26300, 28716, 26276, -1, 28714, 28723, 28721, -1, 28721, 28723, 28716, -1, 26284, 28723, 28714, -1, 28724, 28725, 28726, -1, 28724, 28727, 28725, -1, 28724, 28728, 28727, -1, 28724, 28729, 28728, -1, 28730, 28731, 28724, -1, 28724, 28731, 28729, -1, 28730, 28732, 28731, -1, 28733, 28734, 28735, -1, 28732, 28734, 28736, -1, 28736, 28734, 28733, -1, 28730, 28734, 28732, -1, 28737, 28738, 28663, -1, 28662, 28737, 28663, -1, 26309, 26303, 26302, -1, 26309, 26307, 26303, -1, 26309, 28739, 28740, -1, 26309, 28741, 28739, -1, 26309, 28742, 28741, -1, 26309, 28743, 28742, -1, 26309, 26302, 28743, -1, 28744, 28745, 28740, -1, 28746, 28740, 28745, -1, 28747, 28744, 28740, -1, 28748, 28747, 28740, -1, 28749, 26309, 28740, -1, 28749, 28740, 28746, -1, 28750, 26309, 28749, -1, 28751, 26309, 28750, -1, 28752, 26309, 28751, -1, 28753, 26309, 28752, -1, 28754, 28748, 28740, -1, 28755, 28748, 28754, -1, 28756, 26309, 28753, -1, 28757, 28756, 28753, -1, 28758, 28759, 28760, -1, 28761, 28759, 28758, -1, 28762, 28763, 28764, -1, 28765, 28763, 28762, -1, 28766, 28767, 28768, -1, 28768, 28767, 28769, -1, 28770, 26165, 26167, -1, 28771, 28772, 28773, -1, 28769, 28772, 28771, -1, 28767, 28772, 28769, -1, 28774, 28772, 28767, -1, 28772, 28775, 28773, -1, 26165, 28776, 26144, -1, 26144, 28776, 26142, -1, 28777, 28776, 28770, -1, 28772, 28778, 28775, -1, 28770, 28776, 26165, -1, 28776, 26140, 26142, -1, 28776, 26153, 26140, -1, 28776, 28779, 26153, -1, 28780, 28781, 28782, -1, 28779, 28783, 28782, -1, 28778, 28784, 28785, -1, 28785, 28784, 28786, -1, 28786, 28784, 28787, -1, 28782, 28783, 28780, -1, 28782, 28788, 28789, -1, 28772, 28784, 28778, -1, 28781, 28788, 28782, -1, 28790, 28791, 28792, -1, 28793, 28791, 28790, -1, 28794, 28791, 28795, -1, 28795, 28791, 28793, -1, 28776, 28796, 28779, -1, 28779, 28796, 28783, -1, 28784, 28797, 28787, -1, 28788, 28798, 28789, -1, 28794, 28799, 28791, -1, 28800, 28799, 28794, -1, 28800, 28801, 28799, -1, 28776, 28802, 28796, -1, 28789, 28803, 28804, -1, 28797, 28805, 28787, -1, 28798, 28803, 28789, -1, 28787, 28806, 28800, -1, 28805, 28806, 28787, -1, 28800, 28807, 28801, -1, 28803, 28808, 28804, -1, 28806, 28807, 28800, -1, 28804, 28808, 28809, -1, 28808, 28810, 28809, -1, 28808, 28811, 28810, -1, 28812, 28792, 28808, -1, 28808, 28792, 28811, -1, 28812, 28813, 28792, -1, 28776, 28814, 28802, -1, 28813, 28815, 28792, -1, 28815, 28816, 28792, -1, 28816, 28790, 28792, -1, 28776, 28769, 28814, -1, 28814, 28769, 28817, -1, 28817, 28769, 28818, -1, 28818, 28769, 28771, -1, 28819, 28820, 28821, -1, 28821, 28820, 28822, -1, 28823, 26040, 28824, -1, 28822, 28820, 28825, -1, 28825, 28820, 25987, -1, 28819, 28826, 28820, -1, 28819, 28827, 28826, -1, 28828, 28827, 28819, -1, 28828, 28829, 28827, -1, 28830, 28829, 28828, -1, 28245, 27985, 28243, -1, 28243, 27985, 28240, -1, 28240, 27985, 27984, -1, 28249, 27985, 28245, -1, 28831, 28832, 28830, -1, 28830, 28832, 28829, -1, 27151, 28833, 27148, -1, 27155, 28833, 27151, -1, 28834, 27834, 28835, -1, 28833, 28836, 27148, -1, 28831, 28837, 28832, -1, 28838, 28837, 28831, -1, 27985, 28839, 28840, -1, 28840, 28839, 28841, -1, 28836, 28842, 27148, -1, 28838, 28843, 28837, -1, 27834, 28844, 28845, -1, 28845, 28844, 28846, -1, 26039, 28847, 26040, -1, 28834, 28844, 27834, -1, 28848, 28847, 28849, -1, 28849, 28847, 28850, -1, 28273, 28851, 28271, -1, 28850, 28847, 28852, -1, 28271, 28851, 28268, -1, 28852, 28847, 26039, -1, 28268, 28851, 27951, -1, 26040, 28847, 28824, -1, 28851, 28853, 27951, -1, 28848, 28854, 28847, -1, 28249, 28855, 27985, -1, 27985, 28855, 28839, -1, 28856, 28857, 28848, -1, 28848, 28857, 28854, -1, 28858, 28859, 28856, -1, 28856, 28859, 28857, -1, 28860, 28861, 28858, -1, 28855, 28862, 28839, -1, 28858, 28861, 28859, -1, 28855, 28863, 28862, -1, 28860, 28864, 28861, -1, 28834, 26001, 28844, -1, 28842, 28006, 27148, -1, 28855, 28865, 28863, -1, 28866, 28006, 28842, -1, 28855, 28867, 28865, -1, 28855, 28868, 28867, -1, 28869, 27952, 28870, -1, 28855, 28871, 28868, -1, 28866, 28872, 28006, -1, 28006, 28872, 28873, -1, 28873, 28872, 28874, -1, 28855, 25948, 28871, -1, 28120, 28875, 28118, -1, 28118, 28875, 28115, -1, 28115, 28875, 27803, -1, 28875, 28876, 27803, -1, 27952, 28877, 28878, -1, 28878, 28877, 28879, -1, 28869, 28877, 27952, -1, 28866, 26053, 28872, -1, 28864, 28880, 28881, -1, 28855, 25949, 25948, -1, 28882, 28880, 28860, -1, 26000, 28883, 26001, -1, 28860, 28880, 28864, -1, 28884, 28883, 28885, -1, 28885, 28883, 28886, -1, 28886, 28883, 28887, -1, 28888, 28880, 28889, -1, 28887, 28883, 26000, -1, 28889, 28880, 28890, -1, 28890, 28880, 28891, -1, 26001, 28883, 28844, -1, 28891, 28880, 28892, -1, 28892, 28880, 28893, -1, 28893, 28880, 28894, -1, 28894, 28880, 28895, -1, 28881, 28880, 28888, -1, 28884, 28896, 28883, -1, 26053, 28897, 28872, -1, 28880, 28897, 28895, -1, 26052, 28897, 26053, -1, 28869, 28898, 28877, -1, 28895, 28897, 26052, -1, 28897, 28899, 28872, -1, 28884, 28900, 28896, -1, 28901, 28900, 28884, -1, 28880, 28902, 28897, -1, 28037, 28903, 28033, -1, 28904, 28905, 28901, -1, 27777, 27776, 28906, -1, 27777, 28906, 28907, -1, 28066, 28908, 28062, -1, 27700, 27699, 28909, -1, 27700, 28909, 28910, -1, 28901, 28905, 28900, -1, 28095, 28911, 28091, -1, 27804, 27803, 28876, -1, 27804, 28876, 28912, -1, 28913, 28914, 28904, -1, 28124, 28875, 28120, -1, 27834, 27170, 28915, -1, 27834, 28915, 28835, -1, 27650, 28916, 27652, -1, 27860, 27859, 28917, -1, 28904, 28914, 28905, -1, 27860, 28917, 28918, -1, 28153, 28919, 28149, -1, 27893, 27892, 28920, -1, 27893, 28920, 28921, -1, 28185, 28922, 28181, -1, 27921, 27920, 28923, -1, 27921, 28923, 28924, -1, 28217, 28925, 28213, -1, 28926, 27804, 28912, -1, 27952, 27951, 28853, -1, 28927, 28928, 28913, -1, 27952, 28853, 28870, -1, 28213, 28925, 28211, -1, 28277, 28851, 28273, -1, 28211, 28925, 28208, -1, 28855, 28880, 28929, -1, 28913, 28928, 28914, -1, 28208, 28925, 27920, -1, 28855, 28929, 28930, -1, 28855, 28930, 28931, -1, 28855, 28931, 28932, -1, 28855, 28932, 28933, -1, 28855, 28933, 28927, -1, 28855, 28927, 28843, -1, 28855, 28843, 28838, -1, 28855, 28838, 28934, -1, 28855, 28934, 28935, -1, 28855, 28935, 28936, -1, 28855, 28936, 28937, -1, 28855, 28937, 28938, -1, 28927, 28933, 28928, -1, 28929, 28880, 28939, -1, 28939, 28880, 28940, -1, 28940, 28880, 28882, -1, 27698, 28833, 27155, -1, 27750, 27749, 28941, -1, 27750, 28941, 28942, -1, 28925, 28923, 27920, -1, 28926, 28943, 27804, -1, 27804, 28943, 28944, -1, 28944, 28943, 28945, -1, 28946, 28947, 28948, -1, 28948, 28947, 28949, -1, 28949, 28947, 28950, -1, 28950, 28947, 28951, -1, 28951, 28947, 28898, -1, 28898, 28947, 28877, -1, 28946, 28952, 28947, -1, 28946, 28953, 28952, -1, 28926, 26014, 28943, -1, 28954, 28953, 28946, -1, 28954, 28955, 28953, -1, 28956, 28955, 28954, -1, 28956, 28957, 28955, -1, 28958, 28957, 28956, -1, 28959, 27921, 28924, -1, 28958, 28960, 28957, -1, 25949, 28960, 28958, -1, 28855, 28960, 25949, -1, 28091, 28911, 28089, -1, 28089, 28911, 28086, -1, 28086, 28911, 27699, -1, 28855, 28938, 28960, -1, 28911, 28909, 27699, -1, 27921, 28961, 28962, -1, 28962, 28961, 28963, -1, 28959, 28961, 27921, -1, 28964, 28965, 28966, -1, 28966, 28965, 28967, -1, 28967, 28965, 28968, -1, 28968, 28965, 26013, -1, 26014, 28965, 28943, -1, 26013, 28965, 26014, -1, 28964, 28969, 28965, -1, 28964, 28970, 28969, -1, 28959, 25962, 28961, -1, 28971, 28970, 28964, -1, 28971, 28972, 28970, -1, 28973, 28972, 28971, -1, 28973, 28974, 28972, -1, 28975, 28974, 28973, -1, 28976, 27700, 28910, -1, 28975, 28977, 28974, -1, 28932, 28977, 28975, -1, 28932, 28931, 28977, -1, 28181, 28922, 28179, -1, 28179, 28922, 28176, -1, 28176, 28922, 27892, -1, 28922, 28920, 27892, -1, 28976, 28978, 27700, -1, 27700, 28978, 28979, -1, 28979, 28978, 28980, -1, 25961, 28981, 25962, -1, 28982, 28981, 28983, -1, 28983, 28981, 28984, -1, 28984, 28981, 28985, -1, 28985, 28981, 25961, -1, 25962, 28981, 28961, -1, 28982, 28986, 28981, -1, 28976, 26027, 28978, -1, 28987, 28988, 28982, -1, 28982, 28988, 28986, -1, 28989, 28990, 28987, -1, 28987, 28990, 28988, -1, 28991, 28992, 28989, -1, 28989, 28992, 28990, -1, 28993, 27893, 28921, -1, 28937, 28994, 28991, -1, 28062, 28908, 28060, -1, 28060, 28908, 28057, -1, 28991, 28994, 28992, -1, 28057, 28908, 27776, -1, 28937, 28936, 28994, -1, 28908, 28906, 27776, -1, 27893, 28995, 28996, -1, 28996, 28995, 28997, -1, 28993, 28995, 27893, -1, 26027, 28998, 28978, -1, 26026, 28998, 26027, -1, 28999, 28998, 29000, -1, 29000, 28998, 29001, -1, 29001, 28998, 29002, -1, 29002, 28998, 26026, -1, 28999, 29003, 28998, -1, 29004, 29005, 28999, -1, 28993, 25975, 28995, -1, 28999, 29005, 29003, -1, 29004, 29006, 29005, -1, 29007, 29006, 29004, -1, 29008, 29009, 29007, -1, 29007, 29009, 29006, -1, 29010, 27777, 28907, -1, 28930, 29011, 29008, -1, 29008, 29011, 29009, -1, 28149, 28919, 28147, -1, 28147, 28919, 28144, -1, 28144, 28919, 27859, -1, 28930, 28929, 29011, -1, 28919, 28917, 27859, -1, 29010, 29012, 27777, -1, 27777, 29012, 29013, -1, 29013, 29012, 29014, -1, 25975, 29015, 28995, -1, 25974, 29015, 25975, -1, 29016, 29015, 29017, -1, 29017, 29015, 29018, -1, 29018, 29015, 29019, -1, 29019, 29015, 25974, -1, 29016, 29020, 29015, -1, 29010, 26115, 29012, -1, 29016, 29021, 29020, -1, 29022, 29021, 29016, -1, 29022, 29023, 29021, -1, 29024, 29023, 29022, -1, 29024, 29025, 29023, -1, 29026, 29025, 29024, -1, 29027, 27860, 28918, -1, 28033, 28903, 28031, -1, 28031, 28903, 28028, -1, 28028, 28903, 27749, -1, 29026, 29028, 29025, -1, 28935, 29028, 29026, -1, 28935, 28934, 29028, -1, 28903, 28941, 27749, -1, 27860, 29029, 29030, -1, 29030, 29029, 29031, -1, 29027, 29029, 27860, -1, 26115, 29032, 29012, -1, 26114, 29032, 26115, -1, 29033, 29032, 29034, -1, 29034, 29032, 29035, -1, 29035, 29032, 29036, -1, 29036, 29032, 26114, -1, 27652, 27170, 27833, -1, 27833, 27170, 27832, -1, 27832, 27170, 27169, -1, 29033, 29037, 29032, -1, 29038, 29039, 29033, -1, 29033, 29039, 29037, -1, 29040, 29041, 29038, -1, 29038, 29041, 29039, -1, 29027, 25988, 29029, -1, 29040, 29042, 29041, -1, 29043, 29042, 29040, -1, 28823, 27750, 28942, -1, 28939, 29044, 29043, -1, 29043, 29044, 29042, -1, 28939, 28940, 29044, -1, 27750, 28824, 29045, -1, 29045, 28824, 29046, -1, 27652, 28916, 27170, -1, 28823, 28824, 27750, -1, 28916, 28915, 27170, -1, 25988, 28820, 29029, -1, 25987, 28820, 25988, -1, 28582, 29047, 29048, -1, 28583, 28582, 29048, -1, 29049, 28583, 29048, -1, 29050, 29049, 29048, -1, 29051, 29052, 29053, -1, 29051, 29054, 29055, -1, 29051, 29056, 29054, -1, 29051, 29057, 29056, -1, 29051, 29053, 29057, -1, 26171, 29058, 29059, -1, 26171, 29060, 29058, -1, 26171, 29061, 29060, -1, 26171, 29055, 29061, -1, 26171, 29051, 29055, -1, 29048, 26171, 29059, -1, 29048, 29059, 29062, -1, 29048, 29062, 29050, -1, 29063, 29064, 29065, -1, 29065, 29064, 29066, -1, 29067, 29068, 29063, -1, 29069, 29068, 29067, -1, 29063, 29068, 29064, -1, 29069, 29070, 29068, -1, 29071, 29072, 29073, -1, 29064, 29072, 29071, -1, 29068, 29072, 29064, -1, 29074, 26122, 26120, -1, 26122, 29075, 29076, -1, 29074, 29075, 26122, -1, 29077, 29078, 29079, -1, 29079, 29078, 29080, -1, 29080, 29078, 29081, -1, 29081, 29078, 29082, -1, 29082, 29078, 29083, -1, 29083, 29078, 29084, -1, 29084, 29078, 29085, -1, 29085, 29086, 29087, -1, 29085, 29088, 29086, -1, 29087, 29089, 29085, -1, 29078, 29090, 29085, -1, 29085, 29090, 29088, -1, 29078, 29091, 29090, -1, 29078, 29092, 29091, -1, 29078, 29093, 29092, -1, 29078, 29094, 29093, -1, 29089, 29095, 29085, -1, 29089, 29096, 29095, -1, 29078, 29097, 29094, -1, 29098, 29099, 29097, -1, 29099, 29100, 29097, -1, 29100, 29101, 29097, -1, 29101, 29074, 29097, -1, 29097, 29102, 29094, -1, 29074, 29102, 29097, -1, 29074, 29103, 29102, -1, 29074, 29104, 29103, -1, 29074, 26117, 29104, -1, 29074, 26119, 26117, -1, 29074, 26120, 26119, -1, 29105, 29106, 29107, -1, 25631, 29108, 25632, -1, 29109, 26126, 29108, -1, 29108, 26126, 25632, -1, 29109, 29110, 26126, -1, 29110, 29111, 26126, -1, 29111, 29112, 26126, -1, 29112, 29113, 26126, -1, 29113, 26124, 26126, -1, 29114, 28777, 28770, -1, 29115, 28777, 29116, -1, 29116, 28777, 29117, -1, 29117, 28777, 29118, -1, 29118, 28777, 29114, -1, 29119, 29120, 29121, -1, 29121, 29120, 29115, -1, 29115, 29120, 28777, -1, 29119, 29122, 29120, -1, 29119, 29123, 29122, -1, 29123, 29124, 29122, -1, 29123, 29125, 29124, -1, 29124, 29126, 29127, -1, 29125, 29126, 29124, -1, 29126, 28899, 29127, -1, 28899, 29128, 29127, -1, 28899, 29129, 29128, -1, 28899, 28897, 29129, -1, 26308, 26309, 29130, -1, 29131, 29132, 29130, -1, 28738, 28737, 29133, -1, 29130, 29134, 29131, -1, 29135, 29136, 29137, -1, 29137, 29136, 29138, -1, 29138, 29136, 29139, -1, 29132, 29140, 29130, -1, 29139, 29136, 29141, -1, 29141, 29136, 29142, -1, 29142, 29136, 29143, -1, 29144, 29136, 29135, -1, 29130, 29145, 29134, -1, 29144, 29146, 29136, -1, 29136, 29130, 29147, -1, 29136, 29147, 29143, -1, 29140, 29148, 29130, -1, 26309, 29149, 29130, -1, 29130, 29149, 29145, -1, 29148, 29147, 29130, -1, 26309, 28756, 29149, -1, 29150, 29151, 29152, -1, 29152, 29153, 29154, -1, 29151, 29153, 29152, -1, 29155, 29156, 29150, -1, 29150, 29156, 29151, -1, 29154, 29157, 29158, -1, 29153, 29157, 29154, -1, 29159, 29160, 29155, -1, 29155, 29160, 29156, -1, 29158, 29161, 29147, -1, 29157, 29161, 29158, -1, 28738, 29133, 29159, -1, 29159, 29133, 29160, -1, 29161, 29143, 29147, -1, 29162, 29163, 29164, -1, 29164, 29165, 29162, -1, 29163, 29166, 29164, -1, 29164, 29167, 29165, -1, 29166, 29168, 29164, -1, 29164, 26329, 29167, -1, 29169, 26332, 29164, -1, 29164, 26332, 26329, -1, 29169, 26334, 26332, -1, 29169, 26336, 26334, -1, 29169, 26338, 26336, -1, 29169, 26340, 26338, -1, 29169, 26341, 26340, -1, 29169, 26344, 26341, -1, 29170, 29171, 29168, -1, 29172, 29171, 29173, -1, 29173, 29171, 29174, -1, 29174, 29171, 29175, -1, 29175, 29171, 29176, -1, 29176, 29171, 29177, -1, 29177, 29171, 29170, -1, 29168, 29171, 29164, -1, 29178, 29179, 29180, -1, 29180, 29179, 29181, -1, 29181, 29179, 29182, -1, 29182, 29179, 29183, -1, 29183, 29179, 29184, -1, 29184, 29179, 29185, -1, 29185, 29179, 29172, -1, 29172, 29179, 29171, -1, 29169, 29179, 26344, -1, 26344, 29179, 29178, -1, 29186, 29187, 29188, -1, 29188, 29187, 29189, -1, 29190, 29191, 29192, -1, 29193, 29194, 29192, -1, 29189, 29195, 29196, -1, 29192, 29194, 29190, -1, 29196, 29195, 29197, -1, 29197, 29195, 29198, -1, 29198, 29195, 29199, -1, 29187, 29195, 29189, -1, 29191, 29200, 29192, -1, 29193, 29201, 29194, -1, 29187, 29202, 29195, -1, 29200, 29203, 29192, -1, 29193, 26317, 29201, -1, 29204, 29205, 29206, -1, 29206, 29205, 29207, -1, 29187, 29208, 29202, -1, 29203, 29209, 29192, -1, 29207, 29210, 29187, -1, 29205, 29210, 29207, -1, 29193, 26318, 26317, -1, 29187, 29211, 29208, -1, 29210, 29212, 29187, -1, 29187, 29212, 29211, -1, 29213, 29192, 29214, -1, 29193, 29187, 26327, -1, 26327, 29187, 29215, -1, 29209, 29214, 29192, -1, 29193, 26321, 26318, -1, 29193, 26323, 26321, -1, 29193, 26325, 26323, -1, 29193, 26327, 26325, -1, 29216, 29213, 29214, -1, 29216, 29217, 29213, -1, 29218, 29199, 29217, -1, 29213, 29199, 29219, -1, 29219, 29199, 29220, -1, 29220, 29199, 29221, -1, 29221, 29199, 29222, -1, 29217, 29199, 29213, -1, 29218, 29223, 29199, -1, 29223, 29224, 29199, -1, 29224, 29225, 29199, -1, 29225, 29198, 29199, -1, 29215, 29187, 29226, -1, 29226, 29187, 29186, -1, 29227, 29228, 29229, -1, 29227, 29230, 29228, -1, 29231, 29230, 29232, -1, 29232, 29230, 29227, -1, 29230, 27012, 29228, -1, 27010, 27012, 29230, -1, 29230, 27008, 27010, -1, 27012, 27014, 29228, -1, 29230, 27005, 27008, -1, 27014, 27016, 29228, -1, 29230, 27003, 27005, -1, 27016, 27018, 29228, -1, 29230, 28710, 27003, -1, 29233, 29234, 29228, -1, 29228, 29235, 29233, -1, 27018, 27020, 29228, -1, 29234, 29236, 29228, -1, 29228, 29237, 29235, -1, 27020, 29238, 29228, -1, 29228, 29238, 29237, -1, 27020, 27022, 29238, -1, 27022, 27024, 29238, -1, 27024, 27026, 29238, -1, 28698, 28762, 28696, -1, 28700, 28762, 28698, -1, 28702, 28762, 28700, -1, 28704, 28762, 28702, -1, 28706, 28762, 28704, -1, 28708, 28762, 28706, -1, 28710, 28762, 28708, -1, 29230, 28762, 28710, -1, 29230, 29239, 28762, -1, 29240, 29241, 29242, -1, 29242, 29241, 29239, -1, 29239, 29241, 28762, -1, 29243, 29241, 29244, -1, 29244, 29241, 29245, -1, 29245, 29241, 29246, -1, 29246, 29241, 29247, -1, 29247, 29241, 29240, -1, 28688, 28764, 27030, -1, 28690, 28764, 28688, -1, 28692, 28764, 28690, -1, 28694, 28764, 28692, -1, 28696, 28764, 28694, -1, 27028, 28764, 27026, -1, 27030, 28764, 27028, -1, 27026, 28764, 29238, -1, 29248, 29249, 29250, -1, 29249, 29251, 29250, -1, 29248, 29252, 29249, -1, 29253, 29252, 29248, -1, 29253, 29254, 29252, -1, 29255, 29254, 29253, -1, 29255, 29256, 29254, -1, 29257, 29256, 29258, -1, 29258, 29256, 29255, -1, 29257, 28760, 29256, -1, 29259, 28760, 29260, -1, 29260, 28760, 29257, -1, 28758, 28760, 29259, -1, 29261, 27038, 29262, -1, 27038, 27040, 29262, -1, 29262, 27040, 29263, -1, 29264, 27036, 29261, -1, 29261, 27036, 27038, -1, 27040, 27042, 29263, -1, 29263, 27042, 29265, -1, 29264, 27033, 27036, -1, 29266, 27033, 29264, -1, 29266, 27031, 27033, -1, 29267, 27031, 29266, -1, 27044, 29268, 27042, -1, 27046, 29268, 27044, -1, 27042, 29268, 29265, -1, 29265, 29268, 29269, -1, 29269, 29268, 29270, -1, 29267, 28687, 27031, -1, 27046, 27048, 29268, -1, 29267, 28685, 28687, -1, 27048, 27050, 29268, -1, 29267, 28683, 28685, -1, 28754, 28683, 29267, -1, 27050, 27052, 29268, -1, 28754, 28681, 28683, -1, 28754, 28679, 28681, -1, 28754, 28677, 28679, -1, 28754, 28675, 28677, -1, 28665, 28740, 27058, -1, 28667, 28740, 28665, -1, 28669, 28740, 28667, -1, 28671, 28740, 28669, -1, 28673, 28740, 28671, -1, 28675, 28740, 28673, -1, 27054, 28740, 27052, -1, 27056, 28740, 27054, -1, 27058, 28740, 27056, -1, 27052, 28740, 29268, -1, 28754, 28740, 28675, -1, 28762, 28764, 28696, -1, 29268, 29228, 29270, -1, 29270, 29228, 29251, -1, 29251, 29228, 29236, -1, 29251, 29236, 29250, -1, 29146, 29144, 28629, -1, 28637, 29146, 28629, -1, 28762, 29241, 28765, -1, 29271, 26212, 29272, -1, 29272, 26212, 29241, -1, 29241, 26212, 28765, -1, 29273, 26209, 29271, -1, 29271, 26209, 26212, -1, 29274, 26207, 29273, -1, 29273, 26207, 26209, -1, 29275, 26205, 29274, -1, 29274, 26205, 26207, -1, 29276, 26200, 29277, -1, 29277, 26200, 26199, -1, 29277, 26199, 29278, -1, 29278, 26199, 26203, -1, 29278, 26203, 29275, -1, 29275, 26203, 26205, -1, 29279, 28753, 26710, -1, 29280, 28753, 29279, -1, 29281, 28753, 29280, -1, 29282, 28753, 29281, -1, 29283, 28753, 29282, -1, 29284, 28753, 29283, -1, 29285, 28753, 29284, -1, 29286, 28753, 29285, -1, 28757, 28753, 29286, -1, 26710, 28753, 26174, -1, 29287, 26730, 29288, -1, 29289, 26728, 29290, -1, 29288, 26728, 29289, -1, 26730, 26728, 29288, -1, 29287, 26732, 26730, -1, 26728, 26726, 29290, -1, 29287, 26734, 26732, -1, 29287, 26735, 26734, -1, 28757, 29291, 29287, -1, 29287, 29291, 26735, -1, 26724, 26174, 26726, -1, 26722, 26174, 26724, -1, 29292, 26174, 29293, -1, 29294, 26174, 29292, -1, 29290, 26174, 29294, -1, 26726, 26174, 29290, -1, 26722, 26720, 26174, -1, 28757, 29295, 29291, -1, 26720, 26718, 26174, -1, 28757, 29296, 29295, -1, 26718, 26716, 26174, -1, 28757, 29297, 29296, -1, 26716, 26714, 26174, -1, 28757, 29286, 29297, -1, 26714, 26712, 26174, -1, 26712, 26710, 26174, -1, 26946, 26973, 29298, -1, 28748, 26944, 29298, -1, 29298, 26944, 26946, -1, 26973, 26971, 29298, -1, 28748, 26947, 26944, -1, 26971, 26969, 29298, -1, 28748, 26949, 26947, -1, 26969, 26966, 29298, -1, 28748, 29299, 26949, -1, 26966, 26964, 29298, -1, 28748, 29300, 29299, -1, 26964, 26958, 29298, -1, 28748, 29301, 29300, -1, 28748, 29302, 29301, -1, 28748, 29303, 29302, -1, 28748, 29304, 29303, -1, 28748, 29305, 29304, -1, 26954, 29306, 26956, -1, 29306, 29307, 26956, -1, 26956, 29307, 26958, -1, 26954, 29308, 29306, -1, 26951, 29308, 26954, -1, 26958, 29309, 29298, -1, 29307, 29309, 26958, -1, 26951, 29310, 29308, -1, 26950, 29310, 26951, -1, 29309, 29311, 29298, -1, 26950, 29312, 29310, -1, 29313, 29312, 26950, -1, 29314, 29312, 29313, -1, 29315, 29312, 29314, -1, 29311, 29316, 29298, -1, 29316, 29317, 29298, -1, 29315, 28755, 29312, -1, 28748, 28755, 29305, -1, 29318, 28755, 29315, -1, 29319, 28755, 29318, -1, 29305, 28755, 29319, -1, 29320, 29321, 29322, -1, 29323, 29321, 29320, -1, 28759, 29324, 29320, -1, 29320, 29324, 29323, -1, 29322, 29325, 29326, -1, 29321, 29325, 29322, -1, 28759, 29327, 29324, -1, 29326, 29328, 29329, -1, 29325, 29328, 29326, -1, 28759, 29330, 29327, -1, 29329, 29331, 29332, -1, 29328, 29331, 29329, -1, 28759, 28761, 29330, -1, 26995, 26993, 29333, -1, 29333, 26997, 26995, -1, 28763, 26997, 29333, -1, 26993, 26991, 29333, -1, 28763, 27000, 26997, -1, 28763, 27002, 27000, -1, 29334, 29335, 29336, -1, 29337, 29335, 29334, -1, 26991, 29335, 29333, -1, 29338, 29335, 29337, -1, 29339, 29335, 29338, -1, 29333, 29335, 29339, -1, 26989, 29335, 26991, -1, 26987, 29335, 26989, -1, 28763, 29340, 27002, -1, 26987, 26985, 29335, -1, 28763, 29341, 29340, -1, 26985, 26983, 29335, -1, 28763, 29342, 29341, -1, 26983, 26981, 29335, -1, 29335, 29343, 29344, -1, 28763, 29345, 29342, -1, 29335, 29346, 29343, -1, 28763, 29347, 29345, -1, 29335, 29348, 29346, -1, 26981, 29349, 29335, -1, 29335, 29349, 29348, -1, 26979, 29349, 26981, -1, 26976, 29349, 26979, -1, 26975, 29349, 26976, -1, 29350, 29349, 26975, -1, 29350, 28765, 29349, -1, 29351, 28765, 29350, -1, 29352, 28765, 29351, -1, 29353, 28765, 29352, -1, 29354, 28765, 29353, -1, 29355, 28765, 29354, -1, 29356, 28765, 29355, -1, 29347, 28765, 29356, -1, 28765, 29357, 29349, -1, 28765, 26212, 29357, -1, 26212, 29358, 29357, -1, 26211, 29359, 26212, -1, 29359, 29360, 26212, -1, 26212, 29361, 29358, -1, 29360, 29362, 26212, -1, 26212, 29363, 29361, -1, 26212, 29364, 29363, -1, 29362, 29364, 26212, -1, 28763, 28765, 29347, -1, 29335, 29298, 29317, -1, 29335, 29317, 29332, -1, 29335, 29332, 29336, -1, 29336, 29332, 29331, -1, 29365, 29366, 29367, -1, 29368, 29369, 29370, -1, 29370, 29369, 29371, -1, 29372, 29373, 29374, -1, 29374, 29373, 29366, -1, 29375, 29373, 29376, -1, 29377, 29373, 29375, -1, 29378, 29373, 29377, -1, 29366, 29373, 29378, -1, 29376, 29373, 29379, -1, 29380, 29381, 29382, -1, 29382, 29381, 29368, -1, 29383, 29384, 29372, -1, 29372, 29384, 29373, -1, 29368, 29381, 29369, -1, 29380, 29385, 29381, -1, 29385, 29386, 29381, -1, 29385, 29387, 29386, -1, 29388, 29389, 29390, -1, 29390, 29389, 29391, -1, 29391, 29389, 29392, -1, 29392, 29389, 29393, -1, 29394, 29395, 29389, -1, 29393, 29395, 29396, -1, 29389, 29395, 29393, -1, 29387, 29397, 29386, -1, 29398, 29399, 29400, -1, 29400, 29399, 29401, -1, 29401, 29399, 29402, -1, 29402, 29399, 29403, -1, 29404, 29399, 29398, -1, 29398, 29405, 29404, -1, 29399, 29406, 29403, -1, 29398, 29407, 29405, -1, 29406, 29408, 29403, -1, 29409, 29365, 29367, -1, 29410, 29365, 29409, -1, 29386, 29365, 29410, -1, 29397, 29365, 29386, -1, 29398, 29411, 29407, -1, 29408, 29412, 29403, -1, 29413, 29414, 29415, -1, 29403, 29416, 29394, -1, 29412, 29416, 29403, -1, 29415, 29417, 29394, -1, 29414, 29417, 29415, -1, 29416, 29415, 29394, -1, 29413, 29379, 29414, -1, 29418, 29379, 29413, -1, 29419, 29379, 29418, -1, 29420, 29379, 29419, -1, 29376, 29379, 29420, -1, 29398, 29370, 29411, -1, 29417, 29421, 29394, -1, 29421, 29422, 29394, -1, 29370, 29423, 29411, -1, 29370, 29371, 29423, -1, 29424, 29425, 29422, -1, 29426, 29425, 29427, -1, 29427, 29425, 29424, -1, 29422, 29425, 29394, -1, 29394, 29425, 29395, -1, 29428, 29366, 29378, -1, 29429, 29366, 29428, -1, 29367, 29366, 29429, -1, 29430, 26314, 29431, -1, 26314, 26313, 29431, -1, 29432, 26310, 26213, -1, 26310, 26214, 26213, -1, 29433, 29434, 29435, -1, 29435, 29436, 25639, -1, 25638, 29436, 29437, -1, 25639, 29436, 25638, -1, 29434, 29436, 29435, -1, 29438, 29439, 29440, -1, 29441, 29439, 29438, -1, 29442, 29443, 29444, -1, 29442, 29444, 29445, -1, 26268, 29446, 26269, -1, 26268, 25955, 29446, -1, 29447, 29448, 26257, -1, 29448, 29449, 26257, -1, 25932, 29450, 25933, -1, 25932, 25968, 29450, -1, 29451, 29452, 29453, -1, 29454, 29452, 29451, -1, 29455, 29456, 25921, -1, 29456, 29457, 25921, -1, 25883, 29458, 25884, -1, 25883, 25981, 29458, -1, 29459, 29460, 29461, -1, 29462, 29460, 29459, -1, 29463, 29464, 25872, -1, 29464, 29465, 25872, -1, 25834, 29466, 25835, -1, 25834, 25994, 29466, -1, 29467, 29468, 29469, -1, 29470, 29468, 29467, -1, 29471, 29472, 25823, -1, 29472, 29473, 25823, -1, 25786, 29474, 25785, -1, 25786, 26007, 29474, -1, 29475, 29476, 29477, -1, 29478, 29476, 29475, -1, 29479, 29480, 25774, -1, 29480, 29481, 25774, -1, 25737, 29482, 25736, -1, 25737, 26020, 29482, -1, 29483, 29484, 29485, -1, 29486, 29484, 29483, -1, 29487, 29488, 25725, -1, 29488, 29489, 25725, -1, 26101, 29490, 26102, -1, 26101, 26108, 29490, -1, 29491, 29492, 29493, -1, 29494, 29492, 29491, -1, 29495, 29496, 26090, -1, 29496, 29497, 26090, -1, 25582, 29498, 25583, -1, 25582, 26033, 29498, -1, 29499, 29500, 29501, -1, 29502, 29500, 29499, -1, 29503, 29504, 25620, -1, 29504, 29505, 25620, -1, 25687, 29506, 25688, -1, 25687, 26046, 29506, -1, 29507, 29508, 29509, -1, 29510, 29508, 29507, -1, 29511, 29512, 25676, -1, 29512, 29513, 25676, -1, 29514, 29114, 26149, -1, 29515, 29114, 29514, -1, 29114, 26150, 26149, -1, 29114, 26157, 26150, -1, 29114, 26167, 26157, -1, 29114, 28770, 26167, -1, 29515, 29516, 29517, -1, 29514, 29516, 29515, -1, 29518, 29519, 29520, -1, 29521, 29519, 29518, -1, 29519, 29522, 29520, -1, 29522, 29523, 29520, -1, 29520, 29524, 29525, -1, 29523, 29524, 29520, -1, 29526, 29527, 29528, -1, 29528, 29527, 29529, -1, 29529, 29527, 29530, -1, 29530, 29527, 29531, -1, 29531, 29527, 29532, -1, 29527, 29533, 29532, -1, 29533, 29534, 29535, -1, 29527, 29534, 29533, -1, 29534, 29536, 29535, -1, 29537, 27515, 29538, -1, 29538, 27515, 29539, -1, 29539, 27515, 29540, -1, 29534, 29541, 29536, -1, 29540, 29542, 29534, -1, 29534, 29542, 29541, -1, 27515, 29542, 29540, -1, 27515, 29543, 29542, -1, 27515, 29544, 29543, -1, 27515, 27514, 29544, -1, 29545, 29546, 28601, -1, 29545, 29547, 29546, -1, 29548, 29549, 29550, -1, 29548, 29550, 29547, -1, 29548, 29547, 29545, -1, 29551, 29552, 29553, -1, 29551, 29554, 29552, -1, 29555, 29551, 29553, -1, 29556, 29557, 29558, -1, 29559, 29558, 29560, -1, 29559, 29556, 29558, -1, 29423, 29371, 28793, -1, 28795, 29371, 28794, -1, 28793, 29371, 28795, -1, 28794, 29369, 28800, -1, 29371, 29369, 28794, -1, 28800, 29381, 28787, -1, 29369, 29381, 28800, -1, 28787, 29386, 28786, -1, 29381, 29386, 28787, -1, 28786, 29410, 28785, -1, 29386, 29410, 28786, -1, 28785, 29409, 28778, -1, 29410, 29409, 28785, -1, 28778, 29367, 28775, -1, 29409, 29367, 28778, -1, 28775, 29429, 28773, -1, 29367, 29429, 28775, -1, 28773, 29428, 28771, -1, 29429, 29428, 28773, -1, 28771, 29378, 28818, -1, 29428, 29378, 28771, -1, 28818, 29377, 28817, -1, 29378, 29377, 28818, -1, 28817, 29375, 28814, -1, 29377, 29375, 28817, -1, 29375, 29376, 28814, -1, 28802, 29376, 29420, -1, 28814, 29376, 28802, -1, 28802, 29420, 28796, -1, 29420, 29419, 28796, -1, 28796, 29418, 28783, -1, 29419, 29418, 28796, -1, 28783, 29413, 28780, -1, 29418, 29413, 28783, -1, 28780, 29415, 28781, -1, 29413, 29415, 28780, -1, 28781, 29416, 28788, -1, 29415, 29416, 28781, -1, 28788, 29412, 28798, -1, 29416, 29412, 28788, -1, 28798, 29408, 28803, -1, 29412, 29408, 28798, -1, 28803, 29406, 28808, -1, 29408, 29406, 28803, -1, 28808, 29399, 28812, -1, 29406, 29399, 28808, -1, 28812, 29404, 28813, -1, 29399, 29404, 28812, -1, 28813, 29405, 28815, -1, 29404, 29405, 28813, -1, 28816, 29407, 28790, -1, 28815, 29407, 28816, -1, 29405, 29407, 28815, -1, 29407, 29411, 28790, -1, 29423, 28793, 29411, -1, 29411, 28793, 28790, -1, 29561, 29562, 29563, -1, 29562, 29564, 29563, -1, 29565, 29566, 29567, -1, 29565, 29568, 29566, -1, 29569, 29570, 29571, -1, 29570, 29572, 29573, -1, 29569, 29572, 29570, -1, 29574, 29575, 29576, -1, 29577, 29575, 29578, -1, 29578, 29575, 29579, -1, 29579, 29575, 29574, -1, 29580, 29581, 29577, -1, 29577, 29581, 29575, -1, 29582, 29583, 29076, -1, 29584, 29076, 29585, -1, 29586, 29582, 29076, -1, 29587, 29076, 29584, -1, 29588, 29076, 29587, -1, 29589, 29590, 28588, -1, 29591, 29586, 29076, -1, 29592, 29593, 29590, -1, 29592, 29590, 29589, -1, 29594, 29076, 29588, -1, 29594, 29591, 29076, -1, 29595, 29596, 29593, -1, 29595, 29597, 29596, -1, 29595, 29593, 29592, -1, 29598, 29599, 29600, -1, 29601, 29589, 28588, -1, 29602, 29603, 29597, -1, 29602, 29597, 29595, -1, 25573, 29603, 29602, -1, 25575, 29603, 25573, -1, 29604, 29603, 25575, -1, 29605, 29606, 29607, -1, 29605, 29598, 29606, -1, 29608, 29604, 25575, -1, 29605, 29599, 29598, -1, 29609, 29604, 29608, -1, 29610, 29605, 29607, -1, 29611, 29609, 29608, -1, 29612, 29609, 29611, -1, 29613, 29610, 29607, -1, 29614, 29615, 29616, -1, 29614, 29617, 29615, -1, 29618, 29612, 29611, -1, 29619, 29612, 29618, -1, 29614, 29616, 29620, -1, 29621, 29607, 29617, -1, 29621, 29613, 29607, -1, 29622, 29623, 29619, -1, 29624, 29621, 29617, -1, 29624, 29617, 29614, -1, 29622, 29619, 29618, -1, 29625, 29623, 29622, -1, 29616, 29626, 29620, -1, 29627, 29625, 29622, -1, 29628, 29625, 29627, -1, 29629, 29628, 29627, -1, 29599, 29628, 29629, -1, 29600, 29599, 29629, -1, 29630, 29631, 29626, -1, 29620, 29626, 29631, -1, 29632, 29626, 29076, -1, 29632, 29630, 29626, -1, 29583, 29632, 29076, -1, 29585, 29076, 29075, -1, 29585, 29075, 29633, -1, 29634, 28880, 29635, -1, 29635, 28880, 29636, -1, 29634, 28902, 28880, -1, 29637, 29638, 29639, -1, 29640, 29638, 29637, -1, 29638, 29640, 29641, -1, 29641, 29642, 29643, -1, 29640, 29642, 29641, -1, 29643, 29644, 29645, -1, 29642, 29644, 29643, -1, 29645, 29646, 29647, -1, 29644, 29646, 29645, -1, 29647, 29648, 29649, -1, 29646, 29648, 29647, -1, 29649, 29650, 29651, -1, 29648, 29650, 29649, -1, 29650, 29652, 29651, -1, 29651, 29653, 29654, -1, 29652, 29653, 29651, -1, 29655, 29654, 29653, -1, 29655, 29656, 29654, -1, 29551, 29555, 29657, -1, 29658, 29551, 29657, -1, 29659, 29657, 29660, -1, 29659, 29658, 29657, -1, 29661, 29660, 29662, -1, 29661, 29659, 29660, -1, 29663, 29662, 29664, -1, 29663, 29661, 29662, -1, 29665, 29664, 29666, -1, 29665, 29663, 29664, -1, 29667, 29668, 29560, -1, 29667, 29666, 29668, -1, 29667, 29665, 29666, -1, 29558, 29667, 29560, -1, 29669, 29554, 29551, -1, 29669, 29551, 29658, -1, 29670, 29658, 29659, -1, 29670, 29669, 29658, -1, 29671, 29659, 29661, -1, 29671, 29670, 29659, -1, 29672, 29661, 29663, -1, 29672, 29671, 29661, -1, 29673, 29663, 29665, -1, 29673, 29672, 29663, -1, 29674, 29665, 29667, -1, 29674, 29673, 29665, -1, 29557, 29667, 29558, -1, 29557, 29674, 29667, -1, 29675, 29569, 29571, -1, 29675, 29571, 29676, -1, 29677, 29678, 29679, -1, 29677, 29676, 29678, -1, 29677, 29675, 29676, -1, 29680, 29677, 29679, -1, 29395, 29679, 29396, -1, 29395, 29680, 29679, -1, 29436, 29434, 29681, -1, 29682, 29681, 29683, -1, 29682, 29436, 29681, -1, 29684, 29683, 29571, -1, 29684, 29682, 29683, -1, 29570, 29684, 29571, -1, 29548, 29545, 29685, -1, 29686, 29685, 29687, -1, 29686, 29548, 29685, -1, 29688, 29687, 29689, -1, 29688, 29686, 29687, -1, 29690, 29689, 29553, -1, 29690, 29688, 29689, -1, 29552, 29690, 29553, -1, 29639, 29691, 29637, -1, 29637, 29691, 29692, -1, 29692, 29693, 29694, -1, 29691, 29693, 29692, -1, 29694, 29695, 29696, -1, 29693, 29695, 29694, -1, 29696, 29575, 29581, -1, 29695, 29575, 29696, -1, 29238, 29333, 29339, -1, 29237, 29339, 29338, -1, 29237, 29238, 29339, -1, 29235, 29338, 29337, -1, 29235, 29237, 29338, -1, 29233, 29337, 29334, -1, 29233, 29235, 29337, -1, 29234, 29334, 29336, -1, 29234, 29233, 29334, -1, 29236, 29336, 29331, -1, 29236, 29234, 29336, -1, 29250, 29331, 29328, -1, 29250, 29236, 29331, -1, 29248, 29328, 29325, -1, 29248, 29250, 29328, -1, 29253, 29325, 29321, -1, 29253, 29248, 29325, -1, 29255, 29321, 29323, -1, 29255, 29253, 29321, -1, 29258, 29323, 29324, -1, 29258, 29255, 29323, -1, 29257, 29324, 29327, -1, 29257, 29258, 29324, -1, 29260, 29327, 29330, -1, 29260, 29257, 29327, -1, 29259, 29260, 29330, -1, 28764, 28763, 29333, -1, 28764, 29333, 29238, -1, 28758, 29259, 29330, -1, 28761, 28758, 29330, -1, 29254, 29256, 29320, -1, 29254, 29322, 29326, -1, 29254, 29320, 29322, -1, 29252, 29326, 29329, -1, 29252, 29254, 29326, -1, 29249, 29329, 29332, -1, 29249, 29252, 29329, -1, 29251, 29332, 29317, -1, 29251, 29249, 29332, -1, 29270, 29317, 29316, -1, 29270, 29251, 29317, -1, 29269, 29316, 29311, -1, 29269, 29270, 29316, -1, 29265, 29311, 29309, -1, 29265, 29269, 29311, -1, 29263, 29309, 29307, -1, 29263, 29265, 29309, -1, 29262, 29307, 29306, -1, 29262, 29263, 29307, -1, 29261, 29306, 29308, -1, 29261, 29262, 29306, -1, 29264, 29308, 29310, -1, 29264, 29261, 29308, -1, 29266, 29310, 29312, -1, 29266, 29264, 29310, -1, 29267, 29266, 29312, -1, 28760, 28759, 29320, -1, 28760, 29320, 29256, -1, 28754, 29267, 29312, -1, 28755, 28754, 29312, -1, 29149, 29287, 29288, -1, 29145, 29288, 29289, -1, 29145, 29149, 29288, -1, 29134, 29289, 29290, -1, 29134, 29145, 29289, -1, 29131, 29290, 29294, -1, 29131, 29134, 29290, -1, 29132, 29294, 29292, -1, 29132, 29131, 29294, -1, 29140, 29292, 29293, -1, 29140, 29132, 29292, -1, 29148, 29293, 29697, -1, 29148, 29140, 29293, -1, 29147, 29697, 29698, -1, 29147, 29148, 29697, -1, 29158, 29698, 28656, -1, 29158, 29147, 29698, -1, 29154, 28656, 28652, -1, 29154, 29158, 28656, -1, 29152, 28652, 28650, -1, 29152, 29154, 28652, -1, 29150, 28650, 28655, -1, 29150, 29152, 28650, -1, 29155, 28655, 28659, -1, 29155, 29150, 28655, -1, 29159, 28659, 28661, -1, 29159, 29155, 28659, -1, 28756, 28757, 29287, -1, 28756, 29287, 29149, -1, 28738, 29159, 28661, -1, 28663, 28738, 28661, -1, 28737, 28662, 28660, -1, 28737, 28660, 29133, -1, 29144, 29135, 28628, -1, 28629, 29144, 28628, -1, 29133, 28660, 28658, -1, 29160, 28658, 28654, -1, 29160, 29133, 28658, -1, 29156, 28654, 28649, -1, 29156, 29160, 28654, -1, 29151, 28649, 28651, -1, 29151, 29156, 28649, -1, 29153, 28651, 28653, -1, 29153, 29151, 28651, -1, 29157, 28653, 28657, -1, 29157, 29153, 28653, -1, 29161, 28657, 29699, -1, 29161, 29157, 28657, -1, 29143, 29699, 29700, -1, 29143, 29161, 29699, -1, 29142, 29700, 28647, -1, 29142, 29143, 29700, -1, 29141, 28647, 28645, -1, 29141, 29142, 28647, -1, 29139, 28645, 28644, -1, 29139, 29141, 28645, -1, 29138, 28644, 28646, -1, 29138, 29139, 28644, -1, 29137, 28646, 28648, -1, 29137, 29138, 28646, -1, 29135, 28648, 28628, -1, 29135, 29137, 28648, -1, 29136, 29701, 29702, -1, 29136, 29703, 29701, -1, 29136, 28636, 29703, -1, 29136, 29702, 29704, -1, 29146, 28637, 28636, -1, 29146, 28636, 29136, -1, 26959, 26963, 29705, -1, 26957, 26959, 29705, -1, 29706, 29707, 29708, -1, 29706, 29708, 29709, -1, 29710, 29711, 29712, -1, 29710, 29712, 26952, -1, 29710, 26952, 26953, -1, 29710, 26953, 26955, -1, 29710, 26955, 26957, -1, 29710, 26957, 29705, -1, 29713, 29709, 29711, -1, 29713, 29711, 29710, -1, 29713, 29706, 29709, -1, 26292, 29714, 29715, -1, 26293, 29714, 26292, -1, 29716, 29717, 29718, -1, 29716, 29719, 29717, -1, 29716, 29718, 29720, -1, 29721, 29719, 29716, -1, 29722, 29721, 29716, -1, 29723, 29722, 29716, -1, 29724, 29722, 29723, -1, 27414, 27416, 29725, -1, 29725, 29726, 29727, -1, 27416, 29726, 29725, -1, 29727, 29728, 29729, -1, 29726, 29728, 29727, -1, 29729, 29730, 29715, -1, 29728, 29730, 29729, -1, 29730, 26292, 29715, -1, 29714, 26293, 29731, -1, 29732, 29731, 29733, -1, 29732, 29714, 29731, -1, 29734, 29733, 29735, -1, 29734, 29732, 29733, -1, 29736, 29734, 29735, -1, 29737, 29735, 29706, -1, 29737, 29736, 29735, -1, 29713, 29737, 29706, -1, 29722, 29724, 29738, -1, 29739, 29740, 29741, -1, 29739, 29738, 29740, -1, 29739, 29722, 29738, -1, 29742, 29741, 29743, -1, 29742, 29739, 29741, -1, 29705, 29743, 29710, -1, 29705, 29742, 29743, -1, 27457, 29744, 29745, -1, 27460, 29744, 27457, -1, 29745, 29746, 29747, -1, 29744, 29746, 29745, -1, 29747, 29748, 29749, -1, 29746, 29748, 29747, -1, 29749, 29716, 29720, -1, 29748, 29716, 29749, -1, 26978, 26980, 29750, -1, 26798, 26797, 29751, -1, 26798, 29751, 29752, -1, 29753, 26978, 29750, -1, 26996, 29754, 29755, -1, 26994, 29755, 29756, -1, 26994, 26996, 29755, -1, 26998, 29757, 29754, -1, 26848, 26798, 29752, -1, 26998, 29754, 26996, -1, 26848, 29752, 29758, -1, 26992, 29756, 29759, -1, 26992, 26994, 29756, -1, 26999, 29760, 29757, -1, 26999, 29757, 26998, -1, 26990, 26992, 29759, -1, 26805, 26978, 29753, -1, 27001, 26825, 29760, -1, 27001, 26826, 26825, -1, 26805, 26977, 26978, -1, 27001, 29760, 26999, -1, 26805, 29761, 26977, -1, 26988, 29759, 29762, -1, 26844, 26848, 29758, -1, 26988, 26990, 29759, -1, 26844, 29763, 29764, -1, 26844, 29758, 29763, -1, 26804, 29761, 26805, -1, 26839, 29764, 29765, -1, 29766, 26826, 27001, -1, 26839, 26844, 29764, -1, 26822, 26826, 29766, -1, 26818, 29767, 29761, -1, 26986, 29762, 29768, -1, 26818, 29761, 26804, -1, 26986, 26988, 29762, -1, 26834, 26839, 29765, -1, 26834, 29765, 29769, -1, 26829, 29767, 26818, -1, 26829, 26834, 29769, -1, 26829, 29769, 29767, -1, 29770, 26822, 29766, -1, 26984, 29768, 29771, -1, 26984, 26986, 29768, -1, 26814, 26822, 29770, -1, 29772, 26814, 29770, -1, 26982, 26984, 29771, -1, 29773, 26982, 29771, -1, 26797, 26814, 29772, -1, 26797, 29772, 29751, -1, 26980, 26982, 29773, -1, 29750, 26980, 29773, -1, 27002, 29340, 27001, -1, 29766, 29340, 29770, -1, 27001, 29340, 29766, -1, 29770, 29341, 29772, -1, 29340, 29341, 29770, -1, 29772, 29342, 29751, -1, 29341, 29342, 29772, -1, 29751, 29345, 29752, -1, 29342, 29345, 29751, -1, 29752, 29347, 29758, -1, 29345, 29347, 29752, -1, 29758, 29356, 29763, -1, 29347, 29356, 29758, -1, 29763, 29355, 29764, -1, 29356, 29355, 29763, -1, 29764, 29354, 29765, -1, 29355, 29354, 29764, -1, 29765, 29353, 29769, -1, 29354, 29353, 29765, -1, 29769, 29352, 29767, -1, 29353, 29352, 29769, -1, 29767, 29351, 29761, -1, 29352, 29351, 29767, -1, 29351, 29350, 29761, -1, 29761, 26975, 26977, -1, 29350, 26975, 29761, -1, 26974, 26943, 26972, -1, 26945, 26948, 26943, -1, 26972, 26948, 26970, -1, 26943, 26948, 26972, -1, 29774, 29775, 26948, -1, 29775, 29776, 26948, -1, 29777, 29778, 29776, -1, 26948, 29778, 26970, -1, 29776, 29778, 26948, -1, 26970, 28712, 26961, -1, 29778, 28712, 26970, -1, 26949, 29299, 26948, -1, 26948, 29299, 29774, -1, 29774, 29300, 29775, -1, 29299, 29300, 29774, -1, 29775, 29301, 29776, -1, 29300, 29301, 29775, -1, 29776, 29302, 29777, -1, 29301, 29302, 29776, -1, 26300, 28712, 26298, -1, 28712, 26297, 26298, -1, 28712, 26296, 26297, -1, 28712, 29779, 26296, -1, 29777, 29303, 29778, -1, 29302, 29303, 29777, -1, 29778, 29304, 28712, -1, 29303, 29304, 29778, -1, 29779, 29305, 29780, -1, 29780, 29305, 29781, -1, 29781, 29305, 29782, -1, 28712, 29305, 29779, -1, 29304, 29305, 28712, -1, 29782, 29319, 29783, -1, 29783, 29319, 29707, -1, 29707, 29319, 29708, -1, 29305, 29319, 29782, -1, 29708, 29318, 29709, -1, 29319, 29318, 29708, -1, 29709, 29315, 29711, -1, 29318, 29315, 29709, -1, 29711, 29314, 29712, -1, 29315, 29314, 29711, -1, 29314, 29313, 29712, -1, 29712, 29313, 26952, -1, 29313, 26950, 26952, -1, 29784, 29785, 29786, -1, 29787, 26869, 26919, -1, 29787, 26868, 26869, -1, 29787, 29786, 26868, -1, 29787, 29784, 29786, -1, 29787, 26919, 29784, -1, 29788, 29789, 26846, -1, 29788, 29790, 29789, -1, 29788, 29791, 29790, -1, 29792, 26846, 26911, -1, 29792, 26861, 26862, -1, 29792, 26911, 26861, -1, 29792, 29791, 29788, -1, 29792, 29788, 26846, -1, 29792, 26862, 29791, -1, 29786, 29785, 29793, -1, 29786, 26877, 26868, -1, 29794, 29795, 29796, -1, 29794, 29793, 29795, -1, 29794, 26882, 26877, -1, 29794, 26888, 26882, -1, 29794, 26877, 29786, -1, 29794, 29786, 29793, -1, 29797, 29796, 29798, -1, 29797, 26893, 26888, -1, 29797, 29794, 29796, -1, 29797, 26888, 29794, -1, 29799, 29800, 29801, -1, 29799, 29798, 29800, -1, 29799, 26897, 26893, -1, 29799, 26902, 26897, -1, 29799, 29797, 29798, -1, 29799, 26893, 29797, -1, 29802, 29803, 29804, -1, 29802, 29801, 29803, -1, 29802, 26907, 26902, -1, 29802, 26912, 26907, -1, 29802, 26902, 29799, -1, 29802, 29799, 29801, -1, 29791, 29804, 29790, -1, 29791, 26862, 26912, -1, 29791, 26912, 29802, -1, 29791, 29802, 29804, -1, 29784, 26919, 26849, -1, 29784, 29805, 29785, -1, 29784, 26849, 29805, -1, 29806, 29807, 27301, -1, 26928, 29808, 26859, -1, 26932, 29809, 26922, -1, 29810, 29809, 29811, -1, 26857, 29808, 29812, -1, 26922, 29809, 29810, -1, 29811, 29809, 29813, -1, 29812, 29814, 29815, -1, 26871, 29816, 26916, -1, 29815, 29814, 29817, -1, 29813, 29816, 29806, -1, 29806, 29816, 29807, -1, 27355, 29818, 27354, -1, 29807, 29816, 26871, -1, 26919, 29819, 26932, -1, 26916, 29819, 26920, -1, 29817, 29818, 27355, -1, 26920, 29819, 26919, -1, 26932, 29819, 29809, -1, 26933, 29820, 26929, -1, 29816, 29819, 26916, -1, 29812, 29820, 29814, -1, 29813, 29819, 29816, -1, 29808, 29820, 29812, -1, 29809, 29819, 29813, -1, 26929, 29820, 29808, -1, 29814, 29821, 29817, -1, 29817, 29821, 29818, -1, 27354, 29822, 27360, -1, 29818, 29822, 27354, -1, 26935, 29823, 26933, -1, 26911, 26928, 26859, -1, 26933, 29823, 29820, -1, 29820, 29823, 29814, -1, 29814, 29823, 29821, -1, 29818, 29824, 29822, -1, 29821, 29824, 29818, -1, 27360, 29825, 27369, -1, 29822, 29825, 27360, -1, 26936, 29826, 26935, -1, 29823, 29826, 29821, -1, 26935, 29826, 29823, -1, 29821, 29826, 29824, -1, 29824, 29827, 29822, -1, 29822, 29827, 29825, -1, 27369, 29828, 27338, -1, 29825, 29828, 27369, -1, 26938, 29829, 26936, -1, 29826, 29829, 29824, -1, 26936, 29829, 29826, -1, 29824, 29829, 29827, -1, 29825, 29830, 29828, -1, 29827, 29830, 29825, -1, 27338, 29831, 27331, -1, 29828, 29831, 27338, -1, 26938, 29832, 29829, -1, 26939, 29832, 26938, -1, 29827, 29832, 29830, -1, 29829, 29832, 29827, -1, 29830, 29833, 29828, -1, 29828, 29833, 29831, -1, 29831, 29834, 27331, -1, 27331, 29834, 27330, -1, 26941, 29835, 26939, -1, 26939, 29835, 29832, -1, 29830, 29835, 29833, -1, 29832, 29835, 29830, -1, 29833, 29836, 29831, -1, 29831, 29836, 29834, -1, 27330, 29837, 27303, -1, 29834, 29837, 27330, -1, 26942, 29838, 26941, -1, 29833, 29838, 29836, -1, 29835, 29838, 29833, -1, 26941, 29838, 29835, -1, 29836, 29839, 29834, -1, 27266, 26871, 26873, -1, 29834, 29839, 29837, -1, 27303, 29840, 27302, -1, 29837, 29840, 27303, -1, 26923, 29841, 26942, -1, 29836, 29841, 29839, -1, 26942, 29841, 29838, -1, 29838, 29841, 29836, -1, 29839, 29811, 29837, -1, 29837, 29811, 29840, -1, 27302, 29806, 27301, -1, 29840, 29806, 27302, -1, 26918, 29815, 26917, -1, 26922, 29810, 26923, -1, 26923, 29810, 29841, -1, 29839, 29810, 29811, -1, 26917, 29815, 27248, -1, 29841, 29810, 29839, -1, 26857, 29812, 26918, -1, 29811, 29813, 29840, -1, 29840, 29813, 29806, -1, 26918, 29812, 29815, -1, 27248, 29817, 27355, -1, 27301, 29807, 27266, -1, 29815, 29817, 27248, -1, 26929, 29808, 26928, -1, 27266, 29807, 26871, -1, 26859, 29808, 26857, -1, 29842, 29843, 29844, -1, 29845, 29805, 26849, -1, 29846, 26816, 26808, -1, 29845, 26849, 26782, -1, 29845, 29847, 29805, -1, 29846, 26808, 29848, -1, 29849, 29850, 29847, -1, 29851, 29804, 29803, -1, 26808, 26846, 29789, -1, 29849, 29852, 29850, -1, 29851, 29853, 29804, -1, 29854, 29750, 29773, -1, 29854, 29773, 29842, -1, 29854, 29844, 29852, -1, 29854, 29842, 29844, -1, 29855, 26782, 26807, -1, 29856, 29848, 29853, -1, 29856, 29846, 29848, -1, 29855, 29845, 26782, -1, 29855, 29847, 29845, -1, 29857, 26824, 26816, -1, 29855, 29849, 29847, -1, 29857, 26825, 26824, -1, 29857, 29757, 29760, -1, 29858, 29852, 29849, -1, 29857, 29760, 26825, -1, 29858, 29753, 29750, -1, 29857, 26816, 29846, -1, 29858, 29854, 29852, -1, 29858, 29750, 29854, -1, 29859, 29803, 29801, -1, 29860, 26807, 26806, -1, 29860, 26806, 26805, -1, 29860, 26805, 29753, -1, 29860, 29753, 29858, -1, 29859, 29851, 29803, -1, 29860, 29858, 29849, -1, 29860, 29855, 26807, -1, 29861, 29853, 29851, -1, 29860, 29849, 29855, -1, 29861, 29856, 29853, -1, 29862, 29754, 29757, -1, 29862, 29857, 29846, -1, 29862, 29846, 29856, -1, 29862, 29757, 29857, -1, 29863, 29801, 29800, -1, 29863, 29859, 29801, -1, 29864, 29851, 29859, -1, 29864, 29861, 29851, -1, 29865, 29755, 29754, -1, 29865, 29856, 29861, -1, 29865, 29754, 29862, -1, 29865, 29862, 29856, -1, 29866, 29800, 29798, -1, 29866, 29863, 29800, -1, 29867, 29864, 29859, -1, 29867, 29859, 29863, -1, 29868, 29756, 29755, -1, 29868, 29755, 29865, -1, 29868, 29865, 29861, -1, 29868, 29861, 29864, -1, 29869, 29798, 29796, -1, 29869, 29866, 29798, -1, 29870, 29867, 29863, -1, 29870, 29863, 29866, -1, 29871, 29759, 29756, -1, 29871, 29868, 29864, -1, 29871, 29864, 29867, -1, 29871, 29756, 29868, -1, 29872, 29796, 29795, -1, 29872, 29869, 29796, -1, 29873, 29870, 29866, -1, 29873, 29866, 29869, -1, 29874, 29871, 29867, -1, 29874, 29867, 29870, -1, 29874, 29762, 29759, -1, 29874, 29759, 29871, -1, 29875, 29795, 29793, -1, 29875, 29872, 29795, -1, 29843, 29869, 29872, -1, 29843, 29873, 29869, -1, 29876, 29762, 29874, -1, 29876, 29874, 29870, -1, 29876, 29768, 29762, -1, 29876, 29870, 29873, -1, 29850, 29793, 29785, -1, 29850, 29875, 29793, -1, 29844, 29843, 29872, -1, 29844, 29872, 29875, -1, 29877, 29873, 29843, -1, 29877, 29771, 29768, -1, 29877, 29768, 29876, -1, 29877, 29876, 29873, -1, 29847, 29785, 29805, -1, 29847, 29850, 29785, -1, 29848, 29789, 29790, -1, 29848, 26808, 29789, -1, 29852, 29844, 29875, -1, 29852, 29875, 29850, -1, 29853, 29790, 29804, -1, 29842, 29773, 29771, -1, 29842, 29877, 29843, -1, 29853, 29848, 29790, -1, 29842, 29771, 29877, -1, 29878, 27051, 27049, -1, 29878, 27049, 29879, -1, 28680, 28689, 27029, -1, 28680, 27029, 28682, -1, 29880, 28701, 28699, -1, 29880, 29881, 28701, -1, 29882, 28699, 28697, -1, 29882, 29880, 28699, -1, 29883, 28691, 28689, -1, 29883, 28693, 28691, -1, 27009, 29884, 29885, -1, 29883, 28695, 28693, -1, 29883, 28697, 28695, -1, 29886, 27053, 27051, -1, 29883, 29882, 28697, -1, 29886, 27051, 29878, -1, 27011, 29885, 29887, -1, 27011, 27009, 29885, -1, 27007, 29888, 29884, -1, 27007, 29884, 27009, -1, 27013, 27011, 29887, -1, 27006, 29889, 29888, -1, 27006, 29888, 27007, -1, 27015, 27013, 29887, -1, 27039, 27037, 29890, -1, 27004, 29889, 27006, -1, 27004, 29891, 29889, -1, 29892, 27053, 29886, -1, 27035, 29890, 27037, -1, 27017, 27015, 29887, -1, 29892, 27055, 27053, -1, 28711, 29891, 27004, -1, 28711, 29893, 29891, -1, 27041, 29890, 29894, -1, 27041, 27039, 29890, -1, 27034, 29887, 29890, -1, 27034, 27021, 29887, -1, 27034, 29890, 27035, -1, 27019, 27017, 29887, -1, 28709, 29895, 29893, -1, 28709, 29893, 28711, -1, 26319, 27055, 29892, -1, 27043, 29894, 29896, -1, 27021, 27019, 29887, -1, 27043, 27041, 29894, -1, 26319, 27057, 27055, -1, 26320, 27057, 26319, -1, 26320, 28664, 27057, -1, 28707, 29895, 28709, -1, 27032, 27023, 27021, -1, 29897, 29895, 28707, -1, 26328, 29883, 28689, -1, 27032, 27021, 27034, -1, 26328, 28672, 28670, -1, 26328, 28674, 28672, -1, 26328, 28676, 28674, -1, 26328, 28678, 28676, -1, 26328, 28680, 28678, -1, 27045, 29896, 29898, -1, 26328, 28689, 28680, -1, 26322, 28664, 26320, -1, 27045, 27043, 29896, -1, 28705, 29897, 28707, -1, 26322, 28666, 28664, -1, 28686, 27023, 27032, -1, 26326, 26328, 28670, -1, 28686, 27025, 27023, -1, 26326, 28670, 28668, -1, 29899, 29897, 28705, -1, 26324, 28666, 26322, -1, 26324, 26326, 28668, -1, 26324, 28668, 28666, -1, 28703, 29899, 28705, -1, 27047, 27045, 29898, -1, 29879, 27047, 29898, -1, 28684, 27027, 27025, -1, 28684, 27025, 28686, -1, 27049, 27047, 29879, -1, 29881, 29899, 28703, -1, 28682, 27029, 27027, -1, 29881, 28703, 28701, -1, 28682, 27027, 28684, -1, 29900, 26626, 29901, -1, 29902, 26685, 29903, -1, 26683, 26685, 29902, -1, 26627, 26626, 29900, -1, 29904, 26627, 29900, -1, 26701, 29905, 29906, -1, 26699, 29906, 29907, -1, 26699, 26701, 29906, -1, 26703, 29908, 29905, -1, 29909, 26683, 29902, -1, 26703, 29905, 26701, -1, 26697, 29907, 29910, -1, 26697, 26699, 29907, -1, 26678, 26627, 29904, -1, 26678, 29904, 29911, -1, 26705, 29908, 26703, -1, 26695, 29910, 29912, -1, 26695, 26697, 29910, -1, 26651, 26683, 29909, -1, 26708, 26655, 29908, -1, 26708, 26656, 26655, -1, 26651, 26681, 26683, -1, 26708, 29908, 26705, -1, 26651, 29913, 26681, -1, 26693, 29912, 29914, -1, 26674, 26678, 29911, -1, 26674, 29911, 29915, -1, 26636, 29916, 29913, -1, 26693, 26695, 29912, -1, 26636, 29913, 26651, -1, 26669, 29915, 29917, -1, 29918, 26656, 26708, -1, 26669, 26674, 29915, -1, 26647, 29916, 26636, -1, 26691, 29914, 29919, -1, 26664, 29917, 29920, -1, 26664, 26669, 29917, -1, 26659, 29920, 29916, -1, 26659, 26664, 29920, -1, 26659, 29916, 26647, -1, 26691, 26693, 29914, -1, 29921, 26652, 26656, -1, 29921, 26656, 29918, -1, 26689, 29919, 29922, -1, 26689, 26691, 29919, -1, 29923, 26643, 26652, -1, 29923, 26652, 29921, -1, 26687, 26689, 29922, -1, 29903, 26687, 29922, -1, 29901, 26643, 29923, -1, 26626, 26643, 29901, -1, 26685, 26687, 29903, -1, 29924, 26713, 26715, -1, 26479, 26478, 29925, -1, 26479, 29925, 29926, -1, 29927, 26713, 29924, -1, 29927, 26711, 26713, -1, 29927, 26709, 26711, -1, 26727, 29928, 29929, -1, 26727, 29930, 29928, -1, 26727, 26729, 29930, -1, 26731, 29931, 29930, -1, 26731, 29932, 29931, -1, 26537, 26479, 29926, -1, 26731, 29930, 26729, -1, 26537, 29926, 29933, -1, 26725, 29929, 29934, -1, 26725, 26727, 29929, -1, 26733, 29932, 26731, -1, 26723, 29934, 29935, -1, 26723, 26725, 29934, -1, 26736, 26539, 29932, -1, 26736, 26514, 26539, -1, 26736, 29932, 26733, -1, 26497, 26709, 29927, -1, 26534, 26537, 29933, -1, 26721, 26723, 29935, -1, 26534, 29933, 29936, -1, 26496, 26709, 26497, -1, 29937, 26721, 29935, -1, 26496, 29938, 26709, -1, 26496, 29939, 29938, -1, 29940, 26514, 26736, -1, 26509, 26514, 29940, -1, 26529, 29936, 29941, -1, 26529, 26534, 29936, -1, 26511, 29942, 29939, -1, 26511, 29939, 26496, -1, 26719, 26721, 29937, -1, 29943, 26509, 29940, -1, 26524, 29941, 29944, -1, 26524, 26529, 29941, -1, 26519, 26524, 29944, -1, 29945, 26719, 29937, -1, 26519, 29944, 29942, -1, 26717, 26719, 29945, -1, 26519, 29942, 26511, -1, 26504, 26509, 29943, -1, 29946, 26504, 29943, -1, 29947, 26715, 26717, -1, 29947, 26717, 29945, -1, 26478, 26504, 29946, -1, 26478, 29946, 29925, -1, 29924, 26715, 29947, -1, 29948, 26549, 26576, -1, 29948, 26570, 26549, -1, 29948, 29949, 26570, -1, 29948, 29950, 29949, -1, 29948, 26576, 29950, -1, 29951, 29952, 26676, -1, 29951, 29953, 29952, -1, 29951, 29954, 29953, -1, 29955, 26676, 26567, -1, 29955, 26550, 26552, -1, 29955, 26567, 26550, -1, 29955, 26552, 29954, -1, 29955, 29954, 29951, -1, 29955, 29951, 26676, -1, 29949, 29956, 29957, -1, 29949, 26569, 26570, -1, 29958, 29959, 29960, -1, 29958, 29957, 29959, -1, 29958, 26574, 26569, -1, 29958, 26580, 26574, -1, 29958, 26569, 29949, -1, 29958, 29949, 29957, -1, 29961, 29962, 29963, -1, 29961, 29960, 29962, -1, 29961, 26586, 26580, -1, 29961, 29958, 29960, -1, 29961, 26580, 29958, -1, 29964, 29963, 29965, -1, 29964, 26591, 26586, -1, 29964, 26596, 26591, -1, 29964, 29961, 29963, -1, 29964, 26586, 29961, -1, 29966, 29967, 29968, -1, 29966, 29965, 29967, -1, 29966, 26600, 26596, -1, 29966, 26606, 26600, -1, 29966, 26596, 29964, -1, 29966, 29964, 29965, -1, 29954, 29968, 29953, -1, 29954, 26552, 26606, -1, 29954, 26606, 29966, -1, 29954, 29966, 29968, -1, 29950, 26576, 26679, -1, 29950, 29969, 29956, -1, 29950, 26679, 29969, -1, 29950, 29956, 29949, -1, 29970, 26418, 26420, -1, 29970, 26420, 29971, -1, 29970, 29971, 29972, -1, 29973, 29974, 29975, -1, 29973, 26491, 29974, -1, 29973, 29975, 29976, -1, 29977, 26404, 26491, -1, 29977, 26431, 26404, -1, 29977, 26430, 26431, -1, 29977, 29976, 26430, -1, 29977, 29973, 29976, -1, 29977, 26491, 29973, -1, 29978, 29979, 26486, -1, 29978, 29980, 29979, -1, 29978, 26486, 26435, -1, 29978, 29970, 29980, -1, 29981, 26436, 26418, -1, 29981, 26435, 26436, -1, 29981, 29970, 29978, -1, 29981, 26418, 29970, -1, 29981, 29978, 26435, -1, 29976, 29975, 29982, -1, 29976, 26439, 26430, -1, 29983, 29984, 29985, -1, 29983, 29982, 29984, -1, 29983, 26444, 26439, -1, 29983, 26449, 26444, -1, 29983, 26439, 29976, -1, 29983, 29976, 29982, -1, 29986, 29985, 29987, -1, 29986, 26455, 26449, -1, 29986, 26460, 26455, -1, 29986, 29983, 29985, -1, 29986, 26449, 29983, -1, 29988, 29989, 29990, -1, 29988, 29987, 29989, -1, 29988, 26464, 26460, -1, 29988, 29986, 29987, -1, 29988, 26460, 29986, -1, 29971, 29991, 29972, -1, 29971, 29990, 29991, -1, 29971, 26469, 26464, -1, 29971, 26420, 26469, -1, 29971, 26464, 29988, -1, 29971, 29988, 29990, -1, 29970, 29972, 29980, -1, 26736, 26735, 29940, -1, 26735, 29291, 29940, -1, 29940, 29295, 29943, -1, 29291, 29295, 29940, -1, 29943, 29296, 29946, -1, 29295, 29296, 29943, -1, 29946, 29297, 29925, -1, 29296, 29297, 29946, -1, 29925, 29286, 29926, -1, 29297, 29286, 29925, -1, 29926, 29285, 29933, -1, 29286, 29285, 29926, -1, 29933, 29284, 29936, -1, 29285, 29284, 29933, -1, 29936, 29283, 29941, -1, 29284, 29283, 29936, -1, 29941, 29282, 29944, -1, 29283, 29282, 29941, -1, 29944, 29281, 29942, -1, 29282, 29281, 29944, -1, 29942, 29280, 29939, -1, 29281, 29280, 29942, -1, 29939, 29279, 29938, -1, 29280, 29279, 29939, -1, 29938, 26710, 26709, -1, 29279, 26710, 29938, -1, 26708, 26707, 29918, -1, 26707, 28639, 29918, -1, 29918, 28640, 29921, -1, 28639, 28640, 29918, -1, 29921, 28641, 29923, -1, 28640, 28641, 29921, -1, 29923, 28642, 29901, -1, 28641, 28642, 29923, -1, 29901, 28643, 29900, -1, 28642, 28643, 29901, -1, 29900, 28638, 29904, -1, 28643, 28638, 29900, -1, 29904, 28635, 29911, -1, 28638, 28635, 29904, -1, 29911, 28634, 29915, -1, 28635, 28634, 29911, -1, 29915, 28633, 29917, -1, 28634, 28633, 29915, -1, 29917, 28632, 29920, -1, 28633, 28632, 29917, -1, 29920, 28631, 29916, -1, 28632, 28631, 29920, -1, 29916, 28630, 29913, -1, 28631, 28630, 29916, -1, 29913, 26682, 26681, -1, 28630, 26682, 29913, -1, 29992, 29969, 26679, -1, 29992, 26679, 26612, -1, 29993, 26645, 26637, -1, 29992, 29994, 29969, -1, 29993, 26637, 29995, -1, 29996, 29997, 29994, -1, 29996, 29998, 29997, -1, 29999, 29968, 29967, -1, 26637, 26676, 29952, -1, 30000, 29902, 29903, -1, 29999, 30001, 29968, -1, 30000, 29903, 30002, -1, 30000, 30002, 30003, -1, 30000, 30003, 29998, -1, 30004, 26612, 26635, -1, 30005, 29995, 30001, -1, 30005, 29993, 29995, -1, 30004, 29992, 26612, -1, 30004, 29994, 29992, -1, 30006, 26654, 26645, -1, 30004, 29996, 29994, -1, 30006, 26655, 26654, -1, 30007, 29998, 29996, -1, 30006, 29905, 29908, -1, 30006, 29908, 26655, -1, 30007, 29909, 29902, -1, 30007, 30000, 29998, -1, 30006, 26645, 29993, -1, 30007, 29902, 30000, -1, 30008, 29967, 29965, -1, 30009, 26634, 29909, -1, 30009, 26635, 26634, -1, 30009, 29909, 30007, -1, 30009, 30007, 29996, -1, 30009, 30004, 26635, -1, 30008, 29999, 29967, -1, 30009, 29996, 30004, -1, 30010, 30001, 29999, -1, 30010, 30005, 30001, -1, 30011, 29906, 29905, -1, 30011, 30006, 29993, -1, 30011, 29993, 30005, -1, 30011, 29905, 30006, -1, 30012, 29965, 29963, -1, 30012, 30008, 29965, -1, 30013, 29999, 30008, -1, 30013, 30010, 29999, -1, 30014, 29907, 29906, -1, 30014, 30005, 30010, -1, 30014, 29906, 30011, -1, 30014, 30011, 30005, -1, 30015, 29963, 29962, -1, 30015, 30012, 29963, -1, 30016, 30013, 30008, -1, 30016, 30008, 30012, -1, 30017, 29910, 29907, -1, 30017, 29907, 30014, -1, 30017, 30014, 30010, -1, 30017, 30010, 30013, -1, 30018, 29962, 29960, -1, 30018, 30015, 29962, -1, 30019, 30016, 30012, -1, 30019, 30012, 30015, -1, 30020, 29912, 29910, -1, 30020, 30017, 30013, -1, 30020, 30013, 30016, -1, 30020, 29910, 30017, -1, 30021, 29960, 29959, -1, 30021, 30018, 29960, -1, 30022, 30019, 30015, -1, 30022, 30015, 30018, -1, 30023, 30020, 30016, -1, 30023, 30016, 30019, -1, 30023, 29914, 29912, -1, 30023, 29912, 30020, -1, 30024, 29959, 29957, -1, 30024, 30021, 29959, -1, 30025, 30018, 30021, -1, 30025, 30022, 30018, -1, 30026, 29914, 30023, -1, 30026, 30023, 30019, -1, 30026, 29919, 29914, -1, 30026, 30019, 30022, -1, 29997, 29957, 29956, -1, 29997, 30024, 29957, -1, 30003, 30025, 30021, -1, 30003, 30021, 30024, -1, 30027, 30022, 30025, -1, 30027, 29922, 29919, -1, 30027, 29919, 30026, -1, 30027, 30026, 30022, -1, 29994, 29956, 29969, -1, 26651, 29909, 26634, -1, 29994, 29997, 29956, -1, 29995, 29952, 29953, -1, 29998, 30003, 30024, -1, 29995, 26637, 29952, -1, 29998, 30024, 29997, -1, 30001, 29953, 29968, -1, 30002, 29903, 29922, -1, 30002, 30027, 30025, -1, 30002, 29922, 30027, -1, 30001, 29995, 29953, -1, 30002, 30025, 30003, -1, 30028, 30029, 30030, -1, 27496, 30031, 27495, -1, 30030, 30029, 30032, -1, 30033, 30031, 27496, -1, 26770, 30034, 26760, -1, 26546, 30034, 26544, -1, 26767, 30035, 26766, -1, 30029, 30034, 26546, -1, 30036, 30035, 30037, -1, 30038, 30034, 30028, -1, 30028, 30034, 30029, -1, 26760, 30034, 30038, -1, 30039, 30035, 30036, -1, 26544, 30034, 26770, -1, 26766, 30035, 30039, -1, 26543, 27492, 26603, -1, 30037, 30040, 30033, -1, 30033, 30040, 30031, -1, 27495, 30041, 27494, -1, 30031, 30041, 27495, -1, 26771, 30042, 26767, -1, 30035, 30042, 30037, -1, 26767, 30042, 30035, -1, 30037, 30042, 30040, -1, 30031, 30043, 30041, -1, 30040, 30043, 30031, -1, 27494, 30044, 27493, -1, 30041, 30044, 27494, -1, 26773, 30045, 26771, -1, 26771, 30045, 30042, -1, 30040, 30045, 30043, -1, 30042, 30045, 30040, -1, 30041, 30046, 30044, -1, 30043, 30046, 30041, -1, 27493, 30047, 27474, -1, 30044, 30047, 27493, -1, 26774, 30048, 26773, -1, 30043, 30048, 30046, -1, 26773, 30048, 30045, -1, 30045, 30048, 30043, -1, 30044, 30049, 30047, -1, 30046, 30049, 30044, -1, 30047, 30050, 27474, -1, 27474, 30050, 27475, -1, 26776, 30051, 26774, -1, 30046, 30051, 30049, -1, 26774, 30051, 30048, -1, 30048, 30051, 30046, -1, 30047, 30052, 30050, -1, 30049, 30052, 30047, -1, 30050, 30053, 27475, -1, 27475, 30053, 27476, -1, 26777, 30054, 26776, -1, 26776, 30054, 30051, -1, 30051, 30054, 30049, -1, 30049, 30054, 30052, -1, 30052, 30055, 30050, -1, 30050, 30055, 30053, -1, 27476, 30056, 27482, -1, 30053, 30056, 27476, -1, 26779, 30057, 26777, -1, 26777, 30057, 30054, -1, 30054, 30057, 30052, -1, 30052, 30057, 30055, -1, 30055, 30058, 30053, -1, 30053, 30058, 30056, -1, 27482, 30059, 27480, -1, 30056, 30059, 27482, -1, 26780, 30060, 26779, -1, 30057, 30060, 30055, -1, 26779, 30060, 30057, -1, 30055, 30060, 30058, -1, 30058, 30061, 30056, -1, 30056, 30061, 30059, -1, 27480, 30030, 27478, -1, 30059, 30030, 27480, -1, 26770, 26576, 26544, -1, 26761, 30062, 26780, -1, 26780, 30062, 30060, -1, 27492, 30063, 27497, -1, 30058, 30062, 30061, -1, 26543, 30063, 27492, -1, 30060, 30062, 30058, -1, 26558, 30036, 26543, -1, 30061, 30028, 30059, -1, 26543, 30036, 30063, -1, 30059, 30028, 30030, -1, 27497, 30033, 27496, -1, 27478, 30032, 26609, -1, 26609, 30032, 26608, -1, 30063, 30033, 27497, -1, 30030, 30032, 27478, -1, 26766, 30039, 26567, -1, 26566, 30039, 26558, -1, 26567, 30039, 26566, -1, 26760, 30038, 26761, -1, 30061, 30038, 30028, -1, 26558, 30039, 30036, -1, 30062, 30038, 30061, -1, 30036, 30037, 30063, -1, 26761, 30038, 30062, -1, 30032, 30029, 26608, -1, 26608, 30029, 26546, -1, 30063, 30037, 30033, -1, 30064, 30065, 29979, -1, 30066, 30067, 30068, -1, 30066, 30068, 30069, -1, 30070, 26506, 26489, -1, 30071, 29947, 29945, -1, 30071, 30072, 30067, -1, 30070, 26489, 30065, -1, 30071, 29945, 30073, -1, 30071, 30073, 30072, -1, 30074, 29975, 29974, -1, 30075, 29980, 29972, -1, 30074, 30076, 29975, -1, 30074, 29974, 26490, -1, 30075, 30064, 29980, -1, 30077, 30069, 30076, -1, 30077, 30066, 30069, -1, 30078, 30065, 30064, -1, 30079, 29924, 29947, -1, 30078, 30070, 30065, -1, 30079, 30067, 30066, -1, 30079, 29947, 30071, -1, 30080, 26513, 26506, -1, 30080, 29931, 29932, -1, 30079, 30071, 30067, -1, 30080, 29932, 26513, -1, 30081, 26490, 26500, -1, 30080, 26506, 30070, -1, 30082, 29972, 29991, -1, 30081, 30076, 30074, -1, 30081, 30077, 30076, -1, 30081, 30074, 26490, -1, 30083, 29927, 29924, -1, 30083, 29924, 30079, -1, 30083, 30066, 30077, -1, 30082, 30075, 29972, -1, 30084, 30064, 30075, -1, 30083, 30079, 30066, -1, 30085, 26500, 26499, -1, 30084, 30078, 30064, -1, 30085, 26499, 26497, -1, 30085, 26497, 29927, -1, 29932, 26539, 26513, -1, 30085, 29927, 30083, -1, 30085, 30081, 26500, -1, 30086, 29930, 29931, -1, 30085, 30077, 30081, -1, 30086, 30080, 30070, -1, 30085, 30083, 30077, -1, 30086, 29931, 30080, -1, 30086, 30070, 30078, -1, 30087, 29991, 29990, -1, 30087, 30082, 29991, -1, 30088, 30075, 30082, -1, 30088, 30084, 30075, -1, 30089, 29930, 30086, -1, 30089, 29928, 29930, -1, 30089, 30078, 30084, -1, 30089, 30086, 30078, -1, 30090, 29990, 29989, -1, 30090, 30087, 29990, -1, 30091, 30082, 30087, -1, 30091, 30088, 30082, -1, 30092, 29929, 29928, -1, 30092, 30089, 30084, -1, 30092, 30084, 30088, -1, 30092, 29928, 30089, -1, 30093, 30090, 29989, -1, 30093, 29989, 29987, -1, 30094, 30091, 30087, -1, 30094, 30087, 30090, -1, 30095, 30088, 30091, -1, 30095, 29934, 29929, -1, 30095, 29929, 30092, -1, 30095, 30092, 30088, -1, 30096, 29987, 29985, -1, 30096, 30093, 29987, -1, 30097, 30094, 30090, -1, 30097, 30090, 30093, -1, 30098, 30091, 30094, -1, 30098, 29934, 30095, -1, 30098, 29935, 29934, -1, 30098, 30095, 30091, -1, 30068, 30096, 29985, -1, 30068, 29985, 29984, -1, 26490, 29974, 26491, -1, 30072, 30097, 30093, -1, 30072, 30093, 30096, -1, 30099, 29937, 29935, -1, 30099, 29935, 30098, -1, 30099, 30098, 30094, -1, 30099, 30094, 30097, -1, 30069, 29984, 29982, -1, 30069, 30068, 29984, -1, 30067, 30096, 30068, -1, 30067, 30072, 30096, -1, 30073, 30097, 30072, -1, 30073, 29937, 30099, -1, 30073, 29945, 29937, -1, 30073, 30099, 30097, -1, 30065, 26489, 26486, -1, 30065, 26486, 29979, -1, 30076, 29982, 29975, -1, 30076, 30069, 29982, -1, 30064, 29979, 29980, -1, 30100, 30101, 30102, -1, 27481, 30103, 27483, -1, 30104, 30103, 27481, -1, 30105, 30106, 30107, -1, 26747, 30106, 26741, -1, 30108, 30106, 30105, -1, 26741, 30106, 30108, -1, 30107, 30109, 30104, -1, 30104, 30109, 30103, -1, 27483, 30110, 27491, -1, 30103, 30110, 27483, -1, 26749, 30111, 26747, -1, 30106, 30111, 30107, -1, 26747, 30111, 30106, -1, 30107, 30111, 30109, -1, 30109, 30112, 30103, -1, 30103, 30112, 30110, -1, 27491, 30113, 27490, -1, 26435, 26740, 26433, -1, 30110, 30113, 27491, -1, 26749, 30114, 30111, -1, 26750, 30114, 26749, -1, 30109, 30114, 30112, -1, 30111, 30114, 30109, -1, 30112, 30115, 30110, -1, 30110, 30115, 30113, -1, 27490, 30116, 27489, -1, 30113, 30116, 27490, -1, 26752, 30117, 26750, -1, 30114, 30117, 30112, -1, 30112, 30117, 30115, -1, 26750, 30117, 30114, -1, 30115, 30118, 30113, -1, 30113, 30118, 30116, -1, 30116, 30119, 27489, -1, 27489, 30119, 27488, -1, 26754, 30120, 26752, -1, 30115, 30120, 30118, -1, 26752, 30120, 30117, -1, 30117, 30120, 30115, -1, 30118, 30121, 30116, -1, 30116, 30121, 30119, -1, 30119, 30122, 27488, -1, 27488, 30122, 27487, -1, 26755, 30123, 26754, -1, 26754, 30123, 30120, -1, 30120, 30123, 30118, -1, 30118, 30123, 30121, -1, 30121, 30124, 30119, -1, 30119, 30124, 30122, -1, 27487, 30125, 27486, -1, 30122, 30125, 27487, -1, 26757, 30126, 26755, -1, 26755, 30126, 30123, -1, 30121, 30126, 30124, -1, 30123, 30126, 30121, -1, 30124, 30127, 30122, -1, 30122, 30127, 30125, -1, 27486, 30128, 27485, -1, 30125, 30128, 27486, -1, 26758, 30129, 26757, -1, 30126, 30129, 30124, -1, 26757, 30129, 30126, -1, 30124, 30129, 30127, -1, 30127, 30130, 30125, -1, 30125, 30130, 30128, -1, 27485, 30131, 27484, -1, 30128, 30131, 27485, -1, 26746, 30132, 26758, -1, 26758, 30132, 30129, -1, 30129, 30132, 30127, -1, 30127, 30132, 30130, -1, 26407, 30133, 26405, -1, 30130, 30100, 30128, -1, 30128, 30100, 30131, -1, 27477, 30133, 27479, -1, 26405, 30133, 27477, -1, 27484, 30134, 26417, -1, 26417, 30134, 26415, -1, 26428, 30105, 26407, -1, 30131, 30134, 27484, -1, 26407, 30105, 30133, -1, 26745, 30135, 26746, -1, 26746, 30135, 30132, -1, 27479, 30104, 27481, -1, 30130, 30135, 30100, -1, 30132, 30135, 30130, -1, 30133, 30104, 27479, -1, 30134, 30102, 26415, -1, 26741, 30108, 26740, -1, 26415, 30102, 26403, -1, 26433, 30108, 26428, -1, 26740, 30108, 26433, -1, 30100, 30102, 30131, -1, 30131, 30102, 30134, -1, 26428, 30108, 30105, -1, 26404, 30101, 26745, -1, 30105, 30107, 30133, -1, 26403, 30101, 26401, -1, 26401, 30101, 26404, -1, 30102, 30101, 26403, -1, 30133, 30107, 30104, -1, 30135, 30101, 30100, -1, 26745, 30101, 30135, -1, 30136, 26395, 30137, -1, 30136, 26398, 26395, -1, 30138, 30139, 30140, -1, 30138, 30141, 30139, -1, 30138, 30142, 30141, -1, 30138, 30143, 30142, -1, 30138, 30144, 30143, -1, 26379, 30145, 30146, -1, 26379, 26367, 30145, -1, 26343, 30138, 30140, -1, 26351, 30147, 30148, -1, 26343, 30149, 30150, -1, 26343, 30151, 30149, -1, 26343, 30152, 30151, -1, 26381, 26379, 30146, -1, 26343, 30153, 30152, -1, 26343, 30154, 30153, -1, 26343, 30140, 30154, -1, 26353, 30148, 30155, -1, 26331, 26398, 30136, -1, 26353, 26351, 30148, -1, 26377, 26369, 26367, -1, 26377, 26367, 26379, -1, 26349, 30156, 30147, -1, 26331, 26400, 26398, -1, 26342, 26343, 30150, -1, 26349, 30147, 26351, -1, 26383, 26381, 30146, -1, 26355, 30155, 30157, -1, 26342, 30150, 30158, -1, 26355, 26353, 30155, -1, 26374, 26369, 26377, -1, 26330, 26400, 26331, -1, 26374, 26371, 26369, -1, 26330, 30159, 26400, -1, 26346, 30156, 26349, -1, 26346, 30160, 30156, -1, 26339, 26342, 30158, -1, 26385, 26383, 30146, -1, 26339, 30158, 30161, -1, 26357, 30157, 30145, -1, 26357, 26355, 30157, -1, 26333, 30159, 26330, -1, 26373, 30162, 26371, -1, 26333, 30163, 30159, -1, 26345, 30164, 30160, -1, 26373, 26371, 26374, -1, 26337, 26339, 30161, -1, 26337, 30161, 30165, -1, 26335, 26337, 30165, -1, 26387, 30146, 30166, -1, 26335, 30163, 26333, -1, 26387, 26385, 30146, -1, 26335, 30165, 30163, -1, 26345, 30160, 26346, -1, 30167, 30168, 30162, -1, 26359, 26357, 30145, -1, 30169, 30164, 26345, -1, 30169, 30170, 30164, -1, 30167, 30162, 26373, -1, 26361, 26359, 30145, -1, 26389, 26387, 30166, -1, 30171, 26389, 30166, -1, 30172, 30173, 30170, -1, 30154, 30140, 30168, -1, 30172, 30170, 30169, -1, 26363, 26361, 30145, -1, 30154, 30168, 30167, -1, 26391, 26389, 30171, -1, 30174, 30175, 30173, -1, 30174, 30173, 30172, -1, 26365, 26363, 30145, -1, 30176, 26393, 26391, -1, 30176, 26391, 30171, -1, 30177, 30175, 30174, -1, 26367, 26365, 30145, -1, 30178, 30175, 30177, -1, 30179, 30178, 30177, -1, 30137, 26395, 26393, -1, 30137, 26393, 30176, -1, 30144, 30179, 30143, -1, 30144, 30178, 30179, -1, 30180, 26375, 26376, -1, 26399, 26396, 26397, -1, 26399, 26394, 26396, -1, 26399, 26392, 26394, -1, 26399, 26390, 26392, -1, 26399, 26388, 26390, -1, 26399, 26386, 26388, -1, 26399, 26384, 26386, -1, 26399, 26382, 26384, -1, 26399, 26380, 26382, -1, 26399, 26378, 26380, -1, 26399, 26376, 26378, -1, 26399, 30181, 30180, -1, 26399, 30182, 30181, -1, 26399, 30183, 30182, -1, 26399, 30184, 30183, -1, 26399, 30185, 30184, -1, 26399, 30180, 26376, -1, 30186, 30185, 26399, -1, 30187, 30186, 26399, -1, 30188, 26399, 30189, -1, 30190, 30187, 26399, -1, 30191, 26399, 30188, -1, 30191, 30190, 26399, -1, 26400, 30159, 26399, -1, 26399, 30159, 30189, -1, 30189, 30163, 30188, -1, 30159, 30163, 30189, -1, 30188, 30165, 30191, -1, 30163, 30165, 30188, -1, 30191, 30161, 30190, -1, 30165, 30161, 30191, -1, 30190, 30158, 30187, -1, 30161, 30158, 30190, -1, 30187, 30150, 30186, -1, 30158, 30150, 30187, -1, 30186, 30149, 30185, -1, 30150, 30149, 30186, -1, 30185, 30151, 30184, -1, 30149, 30151, 30185, -1, 30184, 30152, 30183, -1, 30151, 30152, 30184, -1, 30183, 30153, 30182, -1, 30152, 30153, 30183, -1, 30182, 30154, 30181, -1, 30153, 30154, 30182, -1, 30181, 30167, 30180, -1, 30154, 30167, 30181, -1, 30180, 26373, 26375, -1, 30167, 26373, 30180, -1, 30192, 26347, 26348, -1, 26362, 26358, 26360, -1, 26364, 26356, 26358, -1, 26364, 26354, 26356, -1, 26364, 26352, 26354, -1, 26364, 26358, 26362, -1, 26366, 26352, 26364, -1, 26368, 26350, 26352, -1, 26368, 26348, 26350, -1, 26368, 26352, 26366, -1, 26370, 26348, 26368, -1, 30193, 26370, 26372, -1, 30193, 30192, 26348, -1, 30193, 26348, 26370, -1, 30194, 30195, 30192, -1, 30194, 30192, 30193, -1, 30196, 30197, 30198, -1, 30196, 30199, 30197, -1, 30196, 30200, 30199, -1, 30196, 30201, 30200, -1, 30202, 30203, 30195, -1, 30202, 30198, 30203, -1, 30202, 30196, 30198, -1, 30202, 30195, 30194, -1, 26372, 26371, 30193, -1, 26371, 30162, 30193, -1, 30193, 30168, 30194, -1, 30162, 30168, 30193, -1, 30194, 30140, 30202, -1, 30168, 30140, 30194, -1, 30202, 30139, 30196, -1, 30140, 30139, 30202, -1, 30196, 30141, 30201, -1, 30139, 30141, 30196, -1, 30201, 30142, 30200, -1, 30141, 30142, 30201, -1, 30200, 30143, 30199, -1, 30142, 30143, 30200, -1, 30199, 30179, 30197, -1, 30143, 30179, 30199, -1, 30197, 30177, 30198, -1, 30179, 30177, 30197, -1, 30198, 30174, 30203, -1, 30177, 30174, 30198, -1, 30203, 30172, 30195, -1, 30174, 30172, 30203, -1, 30195, 30169, 30192, -1, 30172, 30169, 30195, -1, 30192, 26345, 26347, -1, 30169, 26345, 30192, -1, 29178, 29180, 30138, -1, 30138, 29180, 30144, -1, 30144, 29181, 30178, -1, 29180, 29181, 30144, -1, 30178, 29182, 30175, -1, 29181, 29182, 30178, -1, 30175, 29183, 30173, -1, 29182, 29183, 30175, -1, 30173, 29184, 30170, -1, 29183, 29184, 30173, -1, 30170, 29185, 30164, -1, 29184, 29185, 30170, -1, 30164, 29172, 30160, -1, 29185, 29172, 30164, -1, 30160, 29173, 30156, -1, 29172, 29173, 30160, -1, 30156, 29174, 30147, -1, 29173, 29174, 30156, -1, 30147, 29175, 30148, -1, 29174, 29175, 30147, -1, 30148, 29176, 30155, -1, 29175, 29176, 30148, -1, 30155, 29177, 30157, -1, 29176, 29177, 30155, -1, 29177, 30145, 30157, -1, 29177, 29170, 30145, -1, 30138, 26343, 29178, -1, 29178, 26343, 26344, -1, 29168, 30145, 29170, -1, 30146, 30145, 29168, -1, 29168, 29166, 30146, -1, 30146, 29166, 30166, -1, 30166, 29163, 30171, -1, 29166, 29163, 30166, -1, 30171, 29162, 30176, -1, 29163, 29162, 30171, -1, 30176, 29165, 30137, -1, 29162, 29165, 30176, -1, 30137, 29167, 30136, -1, 29165, 29167, 30137, -1, 30136, 26329, 26331, -1, 29167, 26329, 30136, -1, 29215, 29226, 29883, -1, 29883, 29226, 29882, -1, 29882, 29186, 29880, -1, 29226, 29186, 29882, -1, 29880, 29188, 29881, -1, 29186, 29188, 29880, -1, 29881, 29189, 29899, -1, 29188, 29189, 29881, -1, 29899, 29196, 29897, -1, 29189, 29196, 29899, -1, 29897, 29197, 29895, -1, 29196, 29197, 29897, -1, 29895, 29198, 29893, -1, 29197, 29198, 29895, -1, 29893, 29225, 29891, -1, 29198, 29225, 29893, -1, 29891, 29224, 29889, -1, 29225, 29224, 29891, -1, 29889, 29223, 29888, -1, 29224, 29223, 29889, -1, 29888, 29218, 29884, -1, 29223, 29218, 29888, -1, 29884, 29217, 29885, -1, 29218, 29217, 29884, -1, 29885, 29216, 29887, -1, 29217, 29216, 29885, -1, 29883, 26328, 29215, -1, 29215, 26328, 26327, -1, 29214, 29887, 29216, -1, 29890, 29887, 29214, -1, 29214, 29209, 29890, -1, 29890, 29209, 29894, -1, 29209, 29896, 29894, -1, 29209, 29203, 29896, -1, 29896, 29200, 29898, -1, 29203, 29200, 29896, -1, 29898, 29191, 29879, -1, 29200, 29191, 29898, -1, 29879, 29190, 29878, -1, 29191, 29190, 29879, -1, 29878, 29194, 29886, -1, 29190, 29194, 29878, -1, 29886, 29201, 29892, -1, 29194, 29201, 29886, -1, 29892, 26317, 26319, -1, 29201, 26317, 29892, -1, 30204, 26312, 26311, -1, 30205, 26312, 30204, -1, 30206, 30205, 30204, -1, 30207, 26316, 26315, -1, 30208, 30206, 30209, -1, 30208, 30205, 30206, -1, 30210, 30207, 30211, -1, 30210, 26316, 30207, -1, 30212, 30209, 30213, -1, 30212, 30208, 30209, -1, 30214, 30211, 30215, -1, 30214, 30210, 30211, -1, 30216, 30213, 30217, -1, 30216, 30212, 30213, -1, 30218, 30215, 30219, -1, 30218, 30214, 30215, -1, 30220, 30217, 30221, -1, 30220, 30216, 30217, -1, 30222, 30219, 30223, -1, 30222, 30218, 30219, -1, 29276, 30221, 30224, -1, 29276, 30220, 30221, -1, 30225, 30223, 30226, -1, 30225, 30222, 30223, -1, 26200, 30224, 30227, -1, 26200, 29276, 30224, -1, 30228, 30226, 26201, -1, 30228, 26201, 26200, -1, 30228, 30225, 30226, -1, 30229, 30228, 26200, -1, 30229, 26200, 30227, -1, 30230, 30227, 29095, -1, 30230, 30229, 30227, -1, 29096, 30230, 29095, -1, 30231, 29526, 30232, -1, 30233, 29526, 30234, -1, 30233, 30232, 29526, -1, 30235, 30233, 30234, -1, 29527, 29526, 30231, -1, 30236, 30234, 30237, -1, 30236, 30235, 30234, -1, 30238, 30237, 29525, -1, 30238, 30236, 30237, -1, 29524, 30238, 29525, -1, 29430, 29431, 30239, -1, 30240, 30239, 30241, -1, 30240, 29430, 30239, -1, 30242, 30241, 30243, -1, 30242, 30240, 30241, -1, 30244, 30243, 30245, -1, 30244, 30242, 30243, -1, 30246, 30245, 27498, -1, 30246, 30244, 30245, -1, 27500, 30246, 27498, -1, 29521, 29518, 30247, -1, 30248, 30247, 30249, -1, 30248, 29521, 30247, -1, 30250, 30249, 30251, -1, 30250, 30248, 30249, -1, 30252, 30251, 30253, -1, 30252, 30250, 30251, -1, 30254, 30253, 29432, -1, 30254, 30252, 30253, -1, 26213, 30254, 29432, -1, 29563, 29564, 30255, -1, 30255, 30256, 30257, -1, 29564, 30256, 30255, -1, 30257, 30258, 30259, -1, 30256, 30258, 30257, -1, 30259, 30260, 29567, -1, 30258, 30260, 30259, -1, 30260, 29565, 29567, -1, 29562, 29561, 30261, -1, 30262, 30261, 30263, -1, 30262, 29562, 30261, -1, 30264, 30262, 30263, -1, 30265, 30263, 30266, -1, 30265, 30264, 30263, -1, 30267, 30268, 30269, -1, 30267, 30266, 30268, -1, 30267, 30265, 30266, -1, 30270, 30267, 30269, -1, 30271, 30269, 30272, -1, 30271, 30270, 30269, -1, 30273, 30272, 29070, -1, 30273, 30271, 30272, -1, 29069, 30273, 29070, -1, 29566, 29568, 30274, -1, 30275, 29566, 30274, -1, 30276, 30274, 30277, -1, 30276, 30275, 30274, -1, 30278, 30277, 30279, -1, 30278, 30276, 30277, -1, 30280, 30279, 30281, -1, 30280, 30278, 30279, -1, 29559, 30281, 29556, -1, 29559, 30280, 30281, -1, 29634, 29635, 30282, -1, 29635, 30283, 30282, -1, 30282, 30284, 30285, -1, 30283, 30284, 30282, -1, 30285, 30286, 30287, -1, 30284, 30286, 30285, -1, 30287, 30288, 30289, -1, 30286, 30288, 30287, -1, 30289, 29656, 29655, -1, 30288, 29656, 30289, -1, 29442, 29445, 30290, -1, 30291, 30292, 30293, -1, 30291, 30290, 30292, -1, 30291, 29442, 30290, -1, 30294, 30293, 30295, -1, 30294, 30291, 30293, -1, 30296, 30295, 30297, -1, 30296, 30294, 30295, -1, 30298, 30297, 29439, -1, 30298, 30296, 30297, -1, 29441, 30298, 29439, -1, 30299, 29444, 29443, -1, 30299, 29443, 30300, -1, 30301, 30302, 30303, -1, 30301, 30300, 30302, -1, 30301, 30299, 30300, -1, 30304, 30305, 30306, -1, 30304, 30303, 30305, -1, 30304, 30301, 30303, -1, 30307, 30306, 30308, -1, 30307, 30304, 30306, -1, 30309, 30310, 30311, -1, 30309, 30308, 30310, -1, 30309, 30307, 30308, -1, 30312, 30311, 30313, -1, 30312, 30309, 30311, -1, 30314, 30313, 30315, -1, 30314, 30312, 30313, -1, 26284, 30315, 28723, -1, 26284, 30314, 30315, -1, 28734, 28730, 30316, -1, 30317, 30316, 30318, -1, 30317, 28734, 30316, -1, 30319, 30318, 30320, -1, 30319, 30317, 30318, -1, 30321, 30320, 30322, -1, 30321, 30319, 30320, -1, 30323, 30321, 30322, -1, 30324, 30322, 29448, -1, 30324, 30323, 30322, -1, 29447, 30324, 29448, -1, 25952, 25955, 26268, -1, 25952, 26268, 30325, -1, 25950, 25952, 30325, -1, 30326, 30325, 30327, -1, 30326, 25950, 30325, -1, 30328, 30327, 30329, -1, 30328, 30326, 30327, -1, 30330, 30328, 30329, -1, 30331, 30329, 30332, -1, 30331, 30330, 30329, -1, 30333, 30332, 26229, -1, 30333, 30331, 30332, -1, 30334, 26231, 26250, -1, 30334, 26229, 26231, -1, 30334, 30333, 26229, -1, 30335, 26250, 26252, -1, 30335, 30334, 26250, -1, 30336, 26252, 26260, -1, 30336, 30335, 26252, -1, 30337, 26260, 26257, -1, 30337, 30336, 26260, -1, 29449, 30337, 26257, -1, 29452, 29454, 30338, -1, 30339, 30338, 30340, -1, 30339, 29452, 30338, -1, 30341, 30340, 30342, -1, 30341, 30339, 30340, -1, 30343, 30342, 30344, -1, 30343, 30341, 30342, -1, 30345, 30343, 30344, -1, 30346, 30344, 29456, -1, 30346, 30345, 30344, -1, 29455, 30346, 29456, -1, 25965, 25968, 25932, -1, 25965, 25932, 30347, -1, 25963, 25965, 30347, -1, 30348, 30347, 30349, -1, 30348, 25963, 30347, -1, 30350, 30349, 30351, -1, 30350, 30348, 30349, -1, 30352, 30350, 30351, -1, 30353, 30351, 30354, -1, 30353, 30352, 30351, -1, 30355, 30354, 25893, -1, 30355, 30353, 30354, -1, 30356, 25895, 25914, -1, 30356, 25893, 25895, -1, 30356, 30355, 25893, -1, 30357, 25914, 25916, -1, 30357, 30356, 25914, -1, 30358, 25916, 25924, -1, 30358, 30357, 25916, -1, 30359, 25924, 25921, -1, 30359, 30358, 25924, -1, 29457, 30359, 25921, -1, 29460, 29462, 30360, -1, 30361, 30360, 30362, -1, 30361, 29460, 30360, -1, 30363, 30362, 30364, -1, 30363, 30361, 30362, -1, 30365, 30364, 30366, -1, 30365, 30363, 30364, -1, 30367, 30365, 30366, -1, 30368, 30366, 29464, -1, 30368, 30367, 30366, -1, 29463, 30368, 29464, -1, 25978, 25981, 25883, -1, 25978, 25883, 30369, -1, 25976, 25978, 30369, -1, 30370, 30369, 30371, -1, 30370, 25976, 30369, -1, 30372, 30371, 30373, -1, 30372, 30370, 30371, -1, 30374, 30372, 30373, -1, 30375, 30373, 30376, -1, 30375, 30374, 30373, -1, 30377, 30376, 25844, -1, 30377, 30375, 30376, -1, 30378, 25846, 25865, -1, 30378, 25844, 25846, -1, 30378, 30377, 25844, -1, 30379, 25865, 25867, -1, 30379, 30378, 25865, -1, 30380, 25867, 25875, -1, 30380, 30379, 25867, -1, 30381, 25875, 25872, -1, 30381, 30380, 25875, -1, 29465, 30381, 25872, -1, 29468, 29470, 30382, -1, 30383, 30382, 30384, -1, 30383, 29468, 30382, -1, 30385, 30384, 30386, -1, 30385, 30383, 30384, -1, 30387, 30386, 30388, -1, 30387, 30385, 30386, -1, 30389, 30387, 30388, -1, 30390, 30388, 29472, -1, 30390, 30389, 30388, -1, 29471, 30390, 29472, -1, 25991, 25994, 25834, -1, 25991, 25834, 30391, -1, 25989, 25991, 30391, -1, 30392, 30391, 30393, -1, 30392, 25989, 30391, -1, 30394, 30393, 30395, -1, 30394, 30392, 30393, -1, 30396, 30394, 30395, -1, 30397, 30395, 30398, -1, 30397, 30396, 30395, -1, 30399, 30398, 25795, -1, 30399, 30397, 30398, -1, 30400, 25797, 25816, -1, 30400, 25795, 25797, -1, 30400, 30399, 25795, -1, 30401, 25816, 25818, -1, 30401, 30400, 25816, -1, 30402, 25818, 25826, -1, 30402, 30401, 25818, -1, 30403, 25826, 25823, -1, 30403, 30402, 25826, -1, 29473, 30403, 25823, -1, 29476, 29478, 30404, -1, 30405, 30404, 30406, -1, 30405, 29476, 30404, -1, 30407, 30406, 30408, -1, 30407, 30405, 30406, -1, 30409, 30408, 30410, -1, 30409, 30407, 30408, -1, 30411, 30409, 30410, -1, 30412, 30410, 29480, -1, 30412, 30411, 30410, -1, 29479, 30412, 29480, -1, 26004, 26007, 25786, -1, 26004, 25786, 30413, -1, 26002, 26004, 30413, -1, 30414, 30413, 30415, -1, 30414, 26002, 30413, -1, 30416, 30415, 30417, -1, 30416, 30414, 30415, -1, 30418, 30416, 30417, -1, 30419, 30417, 30420, -1, 30419, 30418, 30417, -1, 30421, 30420, 25747, -1, 30421, 30419, 30420, -1, 30422, 25749, 25767, -1, 30422, 25747, 25749, -1, 30422, 30421, 25747, -1, 30423, 25767, 25769, -1, 30423, 30422, 25767, -1, 30424, 25769, 25777, -1, 30424, 30423, 25769, -1, 30425, 25777, 25774, -1, 30425, 30424, 25777, -1, 29481, 30425, 25774, -1, 26017, 26020, 25737, -1, 26017, 25737, 30426, -1, 26015, 26017, 30426, -1, 30427, 30426, 30428, -1, 30427, 26015, 30426, -1, 30429, 30428, 30430, -1, 30429, 30427, 30428, -1, 30431, 30429, 30430, -1, 30432, 30430, 30433, -1, 30432, 30431, 30430, -1, 30434, 30433, 25698, -1, 30434, 30432, 30433, -1, 30435, 25700, 25718, -1, 30435, 25698, 25700, -1, 30435, 30434, 25698, -1, 30436, 25718, 25720, -1, 30436, 30435, 25718, -1, 30437, 25720, 25728, -1, 30437, 30436, 25720, -1, 30438, 25728, 25725, -1, 30438, 30437, 25728, -1, 29489, 30438, 25725, -1, 29484, 29486, 30439, -1, 30440, 30439, 30441, -1, 30440, 29484, 30439, -1, 30442, 30441, 30443, -1, 30442, 30440, 30441, -1, 30444, 30443, 30445, -1, 30444, 30442, 30443, -1, 30446, 30444, 30445, -1, 30447, 30445, 29488, -1, 30447, 30446, 30445, -1, 29487, 30447, 29488, -1, 29492, 29494, 30448, -1, 30449, 30448, 30450, -1, 30449, 29492, 30448, -1, 30451, 30450, 30452, -1, 30451, 30449, 30450, -1, 30453, 30452, 30454, -1, 30453, 30451, 30452, -1, 30455, 30453, 30454, -1, 30456, 30454, 29496, -1, 30456, 30455, 30454, -1, 29495, 30456, 29496, -1, 26105, 26108, 26101, -1, 26105, 26101, 30457, -1, 26103, 26105, 30457, -1, 30458, 30457, 30459, -1, 30458, 26103, 30457, -1, 30460, 30459, 30461, -1, 30460, 30458, 30459, -1, 30462, 30460, 30461, -1, 30463, 30461, 30464, -1, 30463, 30462, 30461, -1, 30465, 30464, 26063, -1, 30465, 30463, 30464, -1, 30466, 26065, 26083, -1, 30466, 26063, 26065, -1, 30466, 30465, 26063, -1, 30467, 26083, 26085, -1, 30467, 30466, 26083, -1, 30468, 26085, 26093, -1, 30468, 30467, 26085, -1, 30469, 26093, 26090, -1, 30469, 30468, 26093, -1, 29497, 30469, 26090, -1, 29500, 29502, 30470, -1, 30471, 30470, 30472, -1, 30471, 29500, 30470, -1, 30473, 30472, 30474, -1, 30473, 30471, 30472, -1, 30475, 30474, 30476, -1, 30475, 30473, 30474, -1, 30477, 30475, 30476, -1, 30478, 30476, 29504, -1, 30478, 30477, 30476, -1, 29503, 30478, 29504, -1, 26030, 26033, 25582, -1, 26030, 25582, 30479, -1, 26028, 26030, 30479, -1, 30480, 30479, 30481, -1, 30480, 26028, 30479, -1, 30482, 30481, 30483, -1, 30482, 30480, 30481, -1, 30484, 30482, 30483, -1, 30485, 30483, 30486, -1, 30485, 30484, 30483, -1, 30487, 30486, 25593, -1, 30487, 30485, 30486, -1, 30488, 25595, 25613, -1, 30488, 25593, 25595, -1, 30488, 30487, 25593, -1, 30489, 25613, 25615, -1, 30489, 30488, 25613, -1, 30490, 25615, 25623, -1, 30490, 30489, 25615, -1, 30491, 25623, 25620, -1, 30491, 30490, 25623, -1, 29505, 30491, 25620, -1, 26043, 26046, 25687, -1, 26043, 25687, 30492, -1, 26041, 26043, 30492, -1, 30493, 30492, 30494, -1, 30493, 26041, 30492, -1, 30495, 30494, 30496, -1, 30495, 30493, 30494, -1, 30497, 30495, 30496, -1, 30498, 30496, 30499, -1, 30498, 30497, 30496, -1, 30500, 30499, 25648, -1, 30500, 30498, 30499, -1, 30501, 25650, 25669, -1, 30501, 25648, 25650, -1, 30501, 30500, 25648, -1, 30502, 25669, 25671, -1, 30502, 30501, 25669, -1, 30503, 25671, 25679, -1, 30503, 30502, 25671, -1, 30504, 25679, 25676, -1, 30504, 30503, 25679, -1, 29513, 30504, 25676, -1, 29508, 29510, 30505, -1, 30506, 30505, 30507, -1, 30506, 29508, 30505, -1, 30508, 30507, 30509, -1, 30508, 30506, 30507, -1, 30510, 30509, 30511, -1, 30510, 30508, 30509, -1, 30512, 30510, 30511, -1, 30513, 30511, 29512, -1, 30513, 30512, 30511, -1, 29511, 30513, 29512, -1, 26171, 29048, 30514, -1, 26169, 30515, 30516, -1, 26169, 30514, 30515, -1, 26169, 26171, 30514, -1, 26164, 30516, 30517, -1, 26164, 26169, 30516, -1, 26160, 26164, 30517, -1, 26156, 30517, 30518, -1, 26156, 26160, 30517, -1, 26154, 26156, 30518, -1, 26146, 26154, 30518, -1, 26147, 30518, 29516, -1, 26147, 26146, 30518, -1, 29514, 26147, 29516, -1, 29047, 28582, 28578, -1, 30519, 28578, 28572, -1, 30519, 29047, 28578, -1, 30520, 28557, 28563, -1, 30520, 28558, 28557, -1, 30520, 28566, 28558, -1, 30520, 28567, 28566, -1, 30520, 28571, 28567, -1, 30520, 28572, 28571, -1, 30520, 30519, 28572, -1, 30521, 28623, 28620, -1, 30521, 28624, 28623, -1, 30521, 28625, 28624, -1, 30521, 28563, 28625, -1, 30521, 30520, 28563, -1, 30522, 28622, 30523, -1, 30522, 28620, 28622, -1, 30522, 30521, 28620, -1, 30524, 30523, 30525, -1, 30524, 30522, 30523, -1, 30526, 30524, 30525, -1, 30527, 30525, 29108, -1, 30527, 30526, 30525, -1, 25631, 30527, 29108, -1, 27513, 27499, 30528, -1, 30529, 30528, 30530, -1, 30529, 27513, 30528, -1, 30531, 30530, 30532, -1, 30531, 30529, 30530, -1, 30533, 30532, 29437, -1, 30533, 30531, 30532, -1, 29436, 30533, 29437, -1, 30534, 30533, 29436, -1, 29682, 30534, 29436, -1, 30535, 30534, 29682, -1, 29684, 30535, 29682, -1, 29570, 29573, 30535, -1, 29570, 30535, 29684, -1, 30536, 30535, 29573, -1, 30531, 30534, 30535, -1, 30531, 30533, 30534, -1, 30531, 30535, 30536, -1, 30529, 30536, 30537, -1, 30529, 30531, 30536, -1, 27513, 30529, 30537, -1, 30536, 29573, 29572, -1, 30536, 29572, 30538, -1, 30537, 30538, 30539, -1, 30537, 30536, 30538, -1, 27513, 30539, 27511, -1, 27513, 30537, 30539, -1, 26176, 27507, 30540, -1, 26177, 30540, 30541, -1, 26177, 26176, 30540, -1, 26196, 30541, 30542, -1, 26196, 26177, 30541, -1, 26190, 30542, 30543, -1, 26190, 26196, 30542, -1, 26191, 30543, 30544, -1, 26191, 26190, 30543, -1, 26186, 30544, 30545, -1, 26186, 26191, 30544, -1, 26183, 30545, 30546, -1, 26183, 26186, 30545, -1, 26173, 30546, 29293, -1, 26173, 26183, 30546, -1, 26174, 26173, 29293, -1, 29698, 30547, 30548, -1, 29698, 30548, 30549, -1, 29698, 30549, 30550, -1, 29698, 30550, 28656, -1, 30551, 30547, 29698, -1, 30546, 29697, 29293, -1, 30552, 30546, 30545, -1, 30552, 29698, 29697, -1, 30552, 29697, 30546, -1, 30553, 30544, 30543, -1, 30553, 30545, 30544, -1, 30553, 29698, 30552, -1, 30553, 30552, 30545, -1, 30554, 30540, 27507, -1, 30554, 30541, 30540, -1, 30554, 30542, 30541, -1, 30554, 30543, 30542, -1, 30554, 27507, 27508, -1, 30554, 27508, 30555, -1, 30554, 30555, 30556, -1, 30554, 30556, 30551, -1, 30554, 30553, 30543, -1, 30554, 30551, 29698, -1, 30554, 29698, 30553, -1, 27508, 27509, 30557, -1, 30555, 30557, 30558, -1, 30555, 27508, 30557, -1, 30556, 30558, 30559, -1, 30556, 30555, 30558, -1, 30551, 30559, 30560, -1, 30551, 30556, 30559, -1, 30547, 30560, 30561, -1, 30547, 30551, 30560, -1, 30548, 30561, 30562, -1, 30548, 30547, 30561, -1, 30549, 30562, 30563, -1, 30549, 30548, 30562, -1, 30550, 30563, 28657, -1, 30550, 30549, 30563, -1, 28656, 30550, 28657, -1, 29700, 30564, 30565, -1, 29700, 30565, 30566, -1, 29700, 30566, 30567, -1, 29700, 30567, 28647, -1, 30568, 30564, 29700, -1, 30563, 29699, 28657, -1, 30569, 30563, 30562, -1, 30569, 29700, 29699, -1, 30569, 29699, 30563, -1, 30570, 30561, 30560, -1, 30570, 30562, 30561, -1, 30570, 29700, 30569, -1, 30570, 30569, 30562, -1, 30571, 30557, 27509, -1, 30571, 30558, 30557, -1, 30571, 30559, 30558, -1, 30571, 30560, 30559, -1, 30571, 27509, 27510, -1, 30571, 27510, 30572, -1, 30571, 30572, 30573, -1, 30571, 30573, 30568, -1, 30571, 30570, 30560, -1, 30571, 30568, 29700, -1, 30571, 29700, 30570, -1, 27510, 27512, 30574, -1, 30572, 30574, 30575, -1, 30572, 27510, 30574, -1, 30573, 30575, 30576, -1, 30573, 30572, 30575, -1, 30568, 30576, 30577, -1, 30568, 30573, 30576, -1, 30564, 30578, 30579, -1, 30564, 30577, 30578, -1, 30564, 30568, 30577, -1, 30565, 30580, 30581, -1, 30565, 30579, 30580, -1, 30565, 30564, 30579, -1, 30566, 29702, 29701, -1, 30566, 30581, 29702, -1, 30566, 30565, 30581, -1, 30567, 29701, 29703, -1, 30567, 30566, 29701, -1, 28647, 29703, 28636, -1, 28647, 30567, 29703, -1, 28782, 30582, 30583, -1, 28789, 30582, 28782, -1, 30583, 30584, 30585, -1, 30582, 30584, 30583, -1, 30585, 30586, 30587, -1, 30584, 30586, 30585, -1, 30587, 30588, 30589, -1, 30586, 30588, 30587, -1, 30589, 30590, 30591, -1, 30588, 30590, 30589, -1, 30591, 30592, 30593, -1, 30590, 30592, 30591, -1, 30593, 29106, 29105, -1, 30592, 29106, 30593, -1, 29073, 29072, 30594, -1, 30595, 30594, 30596, -1, 30595, 29073, 30594, -1, 30597, 30596, 30598, -1, 30597, 30595, 30596, -1, 30599, 30598, 30600, -1, 30599, 30597, 30598, -1, 30601, 30600, 29169, -1, 30601, 30599, 30600, -1, 29164, 30601, 29169, -1, 29171, 29179, 30602, -1, 30603, 30602, 30604, -1, 30603, 29171, 30602, -1, 30605, 30604, 30606, -1, 30605, 30603, 30604, -1, 30607, 30606, 30608, -1, 30607, 30605, 30606, -1, 30609, 30608, 30610, -1, 30609, 30607, 30608, -1, 30611, 30610, 30612, -1, 30611, 30609, 30610, -1, 30613, 30611, 30612, -1, 30614, 30612, 30615, -1, 30614, 30613, 30612, -1, 30616, 30615, 29193, -1, 30616, 30614, 30615, -1, 29192, 30616, 29193, -1, 29268, 28740, 30617, -1, 30617, 28739, 30618, -1, 30618, 28739, 30619, -1, 28740, 28739, 30617, -1, 30619, 28741, 30620, -1, 28739, 28741, 30619, -1, 30620, 28742, 30621, -1, 30621, 28742, 30622, -1, 28741, 28742, 30620, -1, 30622, 28743, 30623, -1, 30623, 28743, 30624, -1, 28742, 28743, 30622, -1, 30624, 26302, 26304, -1, 28743, 26302, 30624, -1, 26172, 26174, 28753, -1, 26172, 28753, 28752, -1, 26179, 28752, 28751, -1, 26179, 26172, 28752, -1, 30625, 28751, 28750, -1, 30625, 26179, 28751, -1, 30626, 28750, 28749, -1, 30626, 30625, 28750, -1, 30627, 28749, 28746, -1, 30627, 30626, 28749, -1, 30628, 28746, 28745, -1, 30628, 30627, 28746, -1, 30629, 28745, 28744, -1, 30629, 30628, 28745, -1, 30630, 30629, 28744, -1, 30631, 28744, 28747, -1, 30631, 30630, 28744, -1, 29298, 28747, 28748, -1, 29298, 30631, 28747, -1, 27466, 27469, 30632, -1, 30632, 30633, 30634, -1, 27469, 30633, 30632, -1, 30634, 30635, 30636, -1, 30636, 30635, 30637, -1, 30633, 30635, 30634, -1, 30637, 28724, 28726, -1, 30635, 28724, 30637, -1, 27462, 27461, 30638, -1, 30639, 30638, 30640, -1, 30639, 27462, 30638, -1, 30641, 30640, 28717, -1, 30641, 30639, 30640, -1, 28716, 30641, 28717, -1, 27518, 27519, 30642, -1, 30642, 30643, 30644, -1, 27519, 30643, 30642, -1, 30644, 30645, 29517, -1, 30643, 30645, 30644, -1, 30645, 29515, 29517, -1, 30646, 29435, 25639, -1, 30646, 25639, 30647, -1, 30648, 30647, 30649, -1, 30648, 30646, 30647, -1, 30650, 30649, 25632, -1, 30650, 30648, 30649, -1, 26126, 30650, 25632, -1, 27526, 27527, 30651, -1, 30651, 30652, 30653, -1, 27527, 30652, 30651, -1, 30653, 30654, 29509, -1, 30652, 30654, 30653, -1, 30654, 29507, 29509, -1, 27529, 27074, 30655, -1, 30656, 30655, 30657, -1, 30656, 27529, 30655, -1, 30658, 30657, 25688, -1, 30658, 30656, 30657, -1, 29506, 30658, 25688, -1, 27533, 27534, 30659, -1, 30659, 30660, 30661, -1, 27534, 30660, 30659, -1, 30661, 30662, 29501, -1, 30660, 30662, 30661, -1, 30662, 29499, 29501, -1, 27536, 27066, 30663, -1, 30664, 30663, 30665, -1, 30664, 27536, 30663, -1, 30666, 30665, 25583, -1, 30666, 30664, 30665, -1, 29498, 30666, 25583, -1, 27540, 27541, 30667, -1, 30667, 30668, 30669, -1, 27541, 30668, 30667, -1, 30669, 30670, 29493, -1, 30668, 30670, 30669, -1, 30670, 29491, 29493, -1, 27543, 27122, 30671, -1, 30672, 30671, 30673, -1, 30672, 27543, 30671, -1, 30674, 30673, 26102, -1, 30674, 30672, 30673, -1, 29490, 30674, 26102, -1, 27547, 27548, 30675, -1, 30675, 30676, 30677, -1, 27548, 30676, 30675, -1, 30677, 30678, 29485, -1, 30676, 30678, 30677, -1, 30678, 29483, 29485, -1, 27550, 27082, 30679, -1, 30680, 30679, 30681, -1, 30680, 27550, 30679, -1, 30682, 30681, 25736, -1, 30682, 30680, 30681, -1, 29482, 30682, 25736, -1, 27554, 27555, 30683, -1, 30683, 30684, 30685, -1, 27555, 30684, 30683, -1, 30685, 30686, 29477, -1, 30684, 30686, 30685, -1, 30686, 29475, 29477, -1, 27557, 27090, 30687, -1, 30688, 30687, 30689, -1, 30688, 27557, 30687, -1, 30690, 30689, 25785, -1, 30690, 30688, 30689, -1, 29474, 30690, 25785, -1, 27561, 27562, 30691, -1, 30691, 30692, 30693, -1, 27562, 30692, 30691, -1, 30693, 30694, 29469, -1, 30692, 30694, 30693, -1, 30694, 29467, 29469, -1, 27564, 27098, 30695, -1, 30696, 30695, 30697, -1, 30696, 27564, 30695, -1, 30698, 30697, 25835, -1, 30698, 30696, 30697, -1, 29466, 30698, 25835, -1, 27581, 27130, 30699, -1, 30700, 30699, 30701, -1, 30700, 27581, 30699, -1, 30702, 30701, 26269, -1, 30702, 30700, 30701, -1, 29446, 30702, 26269, -1, 27571, 27106, 30703, -1, 30704, 30703, 30705, -1, 30704, 27571, 30703, -1, 30706, 30705, 25884, -1, 30706, 30704, 30705, -1, 29458, 30706, 25884, -1, 27568, 27569, 30707, -1, 30707, 30708, 30709, -1, 27569, 30708, 30707, -1, 30709, 30710, 29461, -1, 30708, 30710, 30709, -1, 30710, 29459, 29461, -1, 27578, 27114, 30711, -1, 30712, 30711, 30713, -1, 30712, 27578, 30711, -1, 30714, 30713, 25933, -1, 30714, 30712, 30713, -1, 29450, 30714, 25933, -1, 27575, 27576, 30715, -1, 30715, 30716, 30717, -1, 27576, 30716, 30715, -1, 30717, 30718, 29453, -1, 30716, 30718, 30717, -1, 30718, 29451, 29453, -1, 27522, 27523, 30719, -1, 30719, 30720, 30721, -1, 27523, 30720, 30719, -1, 30721, 30722, 29440, -1, 30720, 30722, 30721, -1, 30722, 29438, 29440, -1, 29707, 29706, 29783, -1, 29783, 30723, 29782, -1, 29706, 30723, 29783, -1, 29781, 30724, 29780, -1, 29782, 30724, 29781, -1, 30723, 30724, 29782, -1, 29780, 30725, 29779, -1, 30724, 30725, 29780, -1, 29779, 30726, 26296, -1, 30725, 30726, 29779, -1, 30726, 26294, 26296, -1, 29735, 30727, 29706, -1, 29706, 30727, 30723, -1, 30728, 30727, 29735, -1, 30729, 30730, 30731, -1, 30731, 30730, 30732, -1, 30733, 30734, 30735, -1, 30735, 30734, 30736, -1, 30737, 29731, 26287, -1, 30723, 30738, 30724, -1, 26291, 29731, 26293, -1, 26289, 29731, 26291, -1, 26287, 29731, 26289, -1, 30728, 30738, 30727, -1, 30727, 30738, 30723, -1, 30732, 30738, 30728, -1, 30736, 30739, 30729, -1, 30729, 30739, 30730, -1, 30740, 30741, 30733, -1, 30733, 30741, 30734, -1, 30724, 30742, 30725, -1, 30732, 30742, 30738, -1, 30738, 30742, 30724, -1, 30730, 30742, 30732, -1, 30736, 30743, 30739, -1, 30734, 30743, 30736, -1, 28714, 30744, 28713, -1, 30745, 30744, 30740, -1, 28713, 30744, 30745, -1, 30740, 30744, 30741, -1, 30725, 30746, 30726, -1, 30742, 30746, 30725, -1, 30739, 30746, 30730, -1, 30730, 30746, 30742, -1, 30741, 30747, 30734, -1, 30734, 30747, 30743, -1, 30726, 30748, 26294, -1, 30743, 30748, 30739, -1, 30746, 30748, 30726, -1, 30739, 30748, 30746, -1, 28721, 30749, 28714, -1, 28714, 30749, 30744, -1, 30744, 30749, 30741, -1, 30741, 30749, 30747, -1, 26294, 30750, 26295, -1, 30747, 30750, 30743, -1, 30748, 30750, 26294, -1, 30743, 30750, 30748, -1, 26295, 30751, 26299, -1, 30749, 30751, 30747, -1, 28722, 30751, 28721, -1, 30750, 30751, 26295, -1, 30747, 30751, 30750, -1, 26299, 30751, 28722, -1, 28721, 30751, 30749, -1, 28722, 26301, 26299, -1, 29731, 30752, 29733, -1, 30737, 30752, 29731, -1, 30753, 30731, 30737, -1, 30737, 30731, 30752, -1, 29733, 30728, 29735, -1, 30752, 30728, 29733, -1, 30754, 30729, 30753, -1, 30753, 30729, 30731, -1, 30752, 30732, 30728, -1, 30731, 30732, 30752, -1, 30735, 30736, 30754, -1, 30754, 30736, 30729, -1, 26285, 28713, 30755, -1, 30755, 30745, 30756, -1, 28713, 30745, 30755, -1, 30756, 30740, 30757, -1, 30745, 30740, 30756, -1, 30757, 30733, 30758, -1, 30740, 30733, 30757, -1, 30758, 30735, 30759, -1, 30733, 30735, 30758, -1, 30759, 30754, 30760, -1, 30735, 30754, 30759, -1, 30760, 30753, 30761, -1, 30754, 30753, 30760, -1, 30761, 30737, 26286, -1, 30753, 30737, 30761, -1, 30737, 26287, 26286, -1, 26292, 29730, 26290, -1, 26290, 29730, 26288, -1, 26288, 29730, 26286, -1, 26286, 29730, 30761, -1, 26281, 26282, 30755, -1, 26282, 26285, 30755, -1, 30761, 30762, 30760, -1, 29728, 30762, 29730, -1, 29730, 30762, 30761, -1, 30762, 30763, 30760, -1, 30764, 30765, 27416, -1, 29726, 30765, 29728, -1, 27416, 30765, 29726, -1, 29728, 30765, 30762, -1, 30762, 30765, 30763, -1, 30760, 30766, 30759, -1, 30763, 30766, 30760, -1, 30767, 30768, 30764, -1, 30769, 30768, 30767, -1, 30765, 30768, 30763, -1, 30763, 30768, 30766, -1, 30764, 30768, 30765, -1, 30759, 30770, 30758, -1, 30758, 30770, 30757, -1, 30766, 30770, 30759, -1, 30771, 30772, 30769, -1, 30769, 30772, 30768, -1, 30768, 30772, 30766, -1, 30766, 30772, 30770, -1, 30757, 30773, 30756, -1, 26280, 30773, 30771, -1, 30770, 30773, 30757, -1, 30771, 30773, 30772, -1, 30772, 30773, 30770, -1, 30756, 30774, 30755, -1, 26281, 30774, 26280, -1, 26280, 30774, 30773, -1, 30773, 30774, 30756, -1, 30755, 30774, 26281, -1, 27416, 27415, 30764, -1, 30764, 30775, 30767, -1, 27415, 30775, 30764, -1, 30767, 30776, 30769, -1, 30775, 30776, 30767, -1, 30769, 30777, 30771, -1, 30776, 30777, 30769, -1, 30771, 30778, 26280, -1, 30777, 30778, 30771, -1, 30778, 26278, 26280, -1, 30309, 30779, 30307, -1, 30780, 30781, 30782, -1, 30783, 30779, 30309, -1, 30782, 30781, 30784, -1, 30778, 30785, 26278, -1, 26283, 30314, 26284, -1, 26278, 30785, 30786, -1, 30787, 30788, 30789, -1, 30789, 30788, 30790, -1, 30786, 30791, 30792, -1, 27422, 30793, 30794, -1, 30792, 30791, 30795, -1, 30794, 30793, 30796, -1, 27426, 30793, 27422, -1, 27428, 30793, 27426, -1, 30796, 30793, 30797, -1, 30299, 30798, 29444, -1, 30301, 30798, 30299, -1, 30795, 30799, 30783, -1, 29444, 30798, 30800, -1, 30790, 30798, 30301, -1, 30783, 30799, 30779, -1, 30801, 30802, 30803, -1, 30797, 30802, 30801, -1, 30777, 30804, 30778, -1, 30778, 30804, 30785, -1, 30307, 30805, 30304, -1, 30784, 30806, 30787, -1, 30787, 30806, 30788, -1, 30779, 30805, 30307, -1, 30803, 30807, 30780, -1, 30786, 30808, 30791, -1, 30780, 30807, 30781, -1, 30785, 30808, 30786, -1, 30800, 30809, 30810, -1, 30788, 30809, 30790, -1, 30795, 30811, 30799, -1, 30790, 30809, 30798, -1, 30791, 30811, 30795, -1, 30798, 30809, 30800, -1, 27428, 30812, 30793, -1, 30793, 30812, 30797, -1, 30776, 30813, 30777, -1, 30797, 30812, 30802, -1, 30777, 30813, 30804, -1, 30781, 30814, 30784, -1, 30799, 30815, 30779, -1, 30784, 30814, 30806, -1, 30779, 30815, 30805, -1, 30802, 30816, 30803, -1, 30803, 30816, 30807, -1, 30810, 30817, 30818, -1, 30785, 30819, 30808, -1, 30806, 30817, 30788, -1, 30804, 30819, 30785, -1, 30809, 30817, 30810, -1, 30304, 30789, 30301, -1, 30788, 30817, 30809, -1, 30805, 30789, 30304, -1, 30807, 30820, 30781, -1, 30781, 30820, 30814, -1, 30808, 30821, 30791, -1, 30812, 30822, 30802, -1, 27434, 30822, 27428, -1, 30791, 30821, 30811, -1, 27438, 30822, 27434, -1, 30802, 30822, 30816, -1, 27428, 30822, 30812, -1, 30811, 30782, 30799, -1, 30818, 30823, 30824, -1, 30806, 30823, 30817, -1, 30799, 30782, 30815, -1, 30817, 30823, 30818, -1, 30814, 30823, 30806, -1, 27418, 30825, 27415, -1, 27422, 30825, 27418, -1, 27415, 30825, 30775, -1, 30775, 30825, 30776, -1, 30776, 30825, 30813, -1, 30816, 30826, 30807, -1, 30813, 30796, 30804, -1, 30807, 30826, 30820, -1, 30824, 30827, 30828, -1, 30823, 30827, 30824, -1, 30804, 30796, 30819, -1, 30820, 30827, 30814, -1, 30815, 30787, 30805, -1, 30814, 30827, 30823, -1, 27441, 30829, 27438, -1, 27438, 30829, 30822, -1, 30822, 30829, 30816, -1, 30816, 30829, 30826, -1, 30805, 30787, 30789, -1, 30828, 30830, 30831, -1, 30819, 30801, 30808, -1, 30827, 30830, 30828, -1, 30826, 30830, 30820, -1, 30820, 30830, 30827, -1, 30808, 30801, 30821, -1, 30811, 30780, 30782, -1, 30830, 30832, 30831, -1, 30821, 30780, 30811, -1, 30826, 30832, 30830, -1, 27444, 30832, 27441, -1, 27441, 30832, 30829, -1, 30831, 30832, 27444, -1, 30829, 30832, 30826, -1, 27444, 27453, 30831, -1, 30782, 30784, 30815, -1, 30314, 30833, 30312, -1, 26283, 30833, 30314, -1, 30815, 30784, 30787, -1, 26279, 30792, 26283, -1, 27422, 30794, 30825, -1, 30825, 30794, 30813, -1, 30813, 30794, 30796, -1, 26283, 30792, 30833, -1, 30312, 30783, 30309, -1, 30833, 30783, 30312, -1, 30789, 30790, 30301, -1, 26278, 30786, 26279, -1, 30796, 30797, 30819, -1, 30819, 30797, 30801, -1, 26279, 30786, 30792, -1, 30801, 30803, 30821, -1, 30821, 30803, 30780, -1, 30792, 30795, 30833, -1, 30833, 30795, 30783, -1, 29445, 29444, 30834, -1, 30834, 30800, 30835, -1, 29444, 30800, 30834, -1, 30835, 30810, 30836, -1, 30800, 30810, 30835, -1, 30836, 30818, 30837, -1, 30810, 30818, 30836, -1, 30837, 30824, 30838, -1, 30818, 30824, 30837, -1, 30838, 30828, 30839, -1, 30824, 30828, 30838, -1, 30839, 30831, 27447, -1, 30828, 30831, 30839, -1, 30831, 27453, 27447, -1, 30838, 30840, 30837, -1, 30837, 30840, 30841, -1, 30842, 30843, 30844, -1, 30841, 30843, 30842, -1, 30845, 30846, 30847, -1, 30848, 30846, 30845, -1, 30297, 30849, 30850, -1, 30847, 30849, 30297, -1, 27448, 30851, 27447, -1, 27449, 30851, 27448, -1, 27447, 30851, 30839, -1, 30839, 30851, 30838, -1, 30838, 30851, 30840, -1, 30841, 30852, 30843, -1, 30840, 30852, 30841, -1, 30844, 30853, 30848, -1, 30848, 30853, 30846, -1, 30297, 30850, 29439, -1, 30850, 30854, 30855, -1, 30846, 30854, 30847, -1, 30849, 30854, 30850, -1, 30847, 30854, 30849, -1, 27450, 30856, 27449, -1, 27449, 30856, 30851, -1, 30851, 30856, 30840, -1, 30840, 30856, 30852, -1, 30843, 30857, 30844, -1, 30844, 30857, 30853, -1, 30855, 30858, 30859, -1, 30853, 30858, 30846, -1, 30846, 30858, 30854, -1, 30854, 30858, 30855, -1, 30843, 30860, 30857, -1, 30852, 30860, 30843, -1, 30857, 30861, 30853, -1, 30859, 30861, 30862, -1, 30853, 30861, 30858, -1, 30858, 30861, 30859, -1, 30852, 30863, 30860, -1, 27451, 30863, 27450, -1, 27450, 30863, 30856, -1, 30856, 30863, 30852, -1, 30860, 30864, 30857, -1, 30862, 30864, 30865, -1, 30861, 30864, 30862, -1, 30857, 30864, 30861, -1, 27452, 27446, 30866, -1, 30865, 30867, 30866, -1, 27452, 30867, 27451, -1, 30860, 30867, 30864, -1, 29445, 30868, 30290, -1, 27451, 30867, 30863, -1, 30866, 30867, 27452, -1, 30863, 30867, 30860, -1, 30864, 30867, 30865, -1, 30834, 30868, 29445, -1, 30835, 30869, 30834, -1, 30834, 30869, 30868, -1, 30292, 30845, 30293, -1, 30290, 30845, 30292, -1, 30868, 30845, 30290, -1, 30836, 30842, 30835, -1, 30835, 30842, 30869, -1, 30868, 30848, 30845, -1, 30869, 30848, 30868, -1, 30837, 30841, 30836, -1, 30836, 30841, 30842, -1, 30842, 30844, 30869, -1, 30869, 30844, 30848, -1, 30295, 30847, 30297, -1, 30293, 30847, 30295, -1, 30845, 30847, 30293, -1, 29439, 30850, 29440, -1, 29440, 30850, 30870, -1, 30870, 30855, 30871, -1, 30850, 30855, 30870, -1, 30871, 30859, 30872, -1, 30855, 30859, 30871, -1, 30872, 30862, 30873, -1, 30859, 30862, 30872, -1, 30873, 30865, 30874, -1, 30862, 30865, 30873, -1, 30874, 30866, 30875, -1, 30865, 30866, 30874, -1, 30875, 27446, 27373, -1, 30866, 27446, 30875, -1, 27372, 30875, 27373, -1, 27372, 30874, 30875, -1, 27372, 30873, 30874, -1, 30721, 30871, 30872, -1, 30721, 30870, 30871, -1, 30721, 29440, 30870, -1, 27595, 30876, 27356, -1, 27374, 30876, 27372, -1, 27356, 30876, 27374, -1, 27598, 30877, 27595, -1, 27595, 30877, 30876, -1, 30876, 30877, 27372, -1, 27599, 30878, 27598, -1, 30877, 30878, 27372, -1, 27598, 30878, 30877, -1, 27372, 30878, 30873, -1, 27601, 30879, 27599, -1, 30873, 30879, 30872, -1, 30878, 30879, 30873, -1, 30872, 30879, 30721, -1, 27599, 30879, 30878, -1, 27603, 30880, 27601, -1, 30879, 30880, 30721, -1, 27601, 30880, 30879, -1, 30719, 30881, 27522, -1, 30721, 30881, 30719, -1, 27605, 30881, 27603, -1, 27522, 30881, 27605, -1, 30880, 30881, 30721, -1, 27603, 30881, 30880, -1, 29747, 27610, 29745, -1, 27610, 27608, 29745, -1, 30882, 27131, 27614, -1, 27608, 27457, 29745, -1, 30882, 30883, 27131, -1, 30883, 27132, 27131, -1, 30883, 27136, 27132, -1, 30883, 27138, 27136, -1, 29720, 30884, 29749, -1, 27610, 30885, 27612, -1, 29749, 30885, 29747, -1, 29747, 30885, 27610, -1, 30884, 30885, 29749, -1, 27612, 30886, 27614, -1, 30887, 30886, 29720, -1, 30882, 30886, 30887, -1, 30884, 30886, 30885, -1, 30885, 30886, 27612, -1, 27614, 30886, 30882, -1, 29720, 30886, 30884, -1, 27461, 27138, 30888, -1, 27138, 30883, 30888, -1, 30888, 30882, 30889, -1, 30883, 30882, 30888, -1, 30889, 30887, 30890, -1, 30882, 30887, 30889, -1, 30890, 29720, 29718, -1, 30887, 29720, 30890, -1, 30891, 29719, 29721, -1, 30892, 29719, 30891, -1, 30893, 29719, 30892, -1, 30894, 29719, 30893, -1, 28717, 30640, 30895, -1, 29719, 30896, 29717, -1, 29719, 30897, 30896, -1, 30894, 30897, 29719, -1, 30895, 30898, 30894, -1, 30894, 30898, 30897, -1, 30640, 30898, 30895, -1, 29717, 30899, 29718, -1, 29718, 30899, 30890, -1, 30890, 30900, 30889, -1, 29717, 30900, 30899, -1, 30896, 30900, 29717, -1, 30899, 30900, 30890, -1, 30889, 30901, 30888, -1, 30896, 30901, 30900, -1, 30897, 30901, 30896, -1, 30900, 30901, 30889, -1, 30638, 30902, 30640, -1, 27461, 30902, 30638, -1, 30888, 30902, 27461, -1, 30898, 30902, 30897, -1, 30897, 30902, 30901, -1, 30901, 30902, 30888, -1, 30640, 30902, 30898, -1, 28715, 28717, 30903, -1, 30903, 30895, 30904, -1, 28717, 30895, 30903, -1, 30904, 30894, 30905, -1, 30895, 30894, 30904, -1, 30905, 30893, 30906, -1, 30894, 30893, 30905, -1, 30906, 30892, 30907, -1, 30893, 30892, 30906, -1, 30907, 30891, 29722, -1, 30892, 30891, 30907, -1, 30891, 29721, 29722, -1, 30908, 30909, 30910, -1, 30910, 30909, 30911, -1, 28720, 30912, 28719, -1, 30909, 30912, 30903, -1, 30913, 30912, 30908, -1, 28719, 30912, 30913, -1, 30903, 30912, 28720, -1, 30908, 30912, 30909, -1, 30914, 29742, 29705, -1, 26277, 28718, 26274, -1, 28720, 28715, 30903, -1, 29742, 30915, 29739, -1, 30914, 30915, 29742, -1, 30916, 30917, 30914, -1, 30914, 30917, 30915, -1, 30918, 30919, 30916, -1, 30916, 30919, 30917, -1, 29739, 30920, 29722, -1, 29722, 30920, 30907, -1, 30915, 30920, 29739, -1, 30921, 30910, 30918, -1, 30918, 30910, 30919, -1, 30907, 30922, 30906, -1, 30917, 30922, 30915, -1, 30920, 30922, 30907, -1, 30915, 30922, 30920, -1, 26272, 30908, 26270, -1, 26270, 30908, 30921, -1, 30921, 30908, 30910, -1, 30906, 30923, 30905, -1, 30922, 30923, 30906, -1, 30917, 30923, 30922, -1, 30919, 30923, 30917, -1, 28719, 30913, 28718, -1, 26274, 30913, 26272, -1, 26272, 30913, 30908, -1, 28718, 30913, 26274, -1, 30905, 30911, 30904, -1, 30919, 30911, 30923, -1, 30910, 30911, 30919, -1, 30923, 30911, 30905, -1, 30904, 30909, 30903, -1, 30911, 30909, 30904, -1, 26963, 26965, 29705, -1, 29705, 26965, 30914, -1, 30914, 26967, 30916, -1, 26965, 26967, 30914, -1, 30916, 26968, 30918, -1, 26967, 26968, 30916, -1, 30918, 26960, 30921, -1, 26968, 26960, 30918, -1, 30921, 26962, 26270, -1, 26960, 26962, 30921, -1, 26962, 26271, 26270, -1, 30701, 26267, 26269, -1, 30701, 26265, 26267, -1, 27306, 30924, 30925, -1, 27306, 27305, 30924, -1, 27124, 30926, 27128, -1, 27128, 30926, 27130, -1, 30699, 30926, 30701, -1, 27130, 30926, 30699, -1, 27124, 30927, 30926, -1, 30926, 30927, 30701, -1, 27123, 30928, 27124, -1, 30927, 30928, 30701, -1, 27124, 30928, 30927, -1, 27621, 30929, 27623, -1, 27623, 30929, 27123, -1, 27123, 30929, 30928, -1, 27621, 30930, 30929, -1, 27619, 30931, 27621, -1, 27621, 30931, 30930, -1, 27455, 30932, 27291, -1, 27306, 30932, 27455, -1, 27291, 30932, 27617, -1, 27617, 30932, 27619, -1, 30931, 30932, 27306, -1, 27619, 30932, 30931, -1, 26265, 30933, 26264, -1, 30934, 30933, 30925, -1, 30935, 30933, 30934, -1, 26264, 30933, 30935, -1, 30931, 30933, 30930, -1, 30929, 30933, 30928, -1, 27306, 30933, 30931, -1, 30701, 30933, 26265, -1, 30930, 30933, 30929, -1, 30925, 30933, 27306, -1, 30928, 30933, 30701, -1, 27305, 27394, 30924, -1, 30924, 30936, 30925, -1, 27394, 30936, 30924, -1, 30925, 30937, 30934, -1, 30936, 30937, 30925, -1, 30934, 30938, 30935, -1, 30937, 30938, 30934, -1, 30935, 30939, 26264, -1, 30938, 30939, 30935, -1, 30939, 26262, 26264, -1, 30940, 30941, 26230, -1, 30942, 30941, 30940, -1, 30943, 30941, 30942, -1, 30938, 30944, 30939, -1, 26266, 30325, 26268, -1, 30939, 30944, 30945, -1, 30945, 30946, 30947, -1, 30947, 30946, 30948, -1, 26253, 30949, 26256, -1, 30948, 30949, 30943, -1, 30943, 30949, 30941, -1, 30941, 30949, 26253, -1, 30937, 30950, 30938, -1, 30938, 30950, 30944, -1, 30945, 30951, 30946, -1, 30944, 30951, 30945, -1, 26256, 30952, 26261, -1, 30948, 30952, 30949, -1, 30949, 30952, 26256, -1, 30946, 30952, 30948, -1, 27396, 30953, 27394, -1, 27394, 30953, 30936, -1, 30936, 30953, 30937, -1, 30937, 30953, 30950, -1, 30332, 26230, 26229, -1, 30950, 30954, 30944, -1, 30944, 30954, 30951, -1, 26261, 30955, 26237, -1, 30952, 30955, 26261, -1, 30951, 30955, 30946, -1, 30946, 30955, 30952, -1, 27397, 30956, 27396, -1, 27398, 30956, 27397, -1, 27396, 30956, 30953, -1, 30953, 30956, 30950, -1, 30950, 30956, 30954, -1, 26237, 30957, 26236, -1, 30955, 30957, 26237, -1, 30954, 30957, 30951, -1, 30951, 30957, 30955, -1, 27398, 30958, 30956, -1, 27399, 30958, 27398, -1, 30954, 30958, 30957, -1, 30957, 30958, 26236, -1, 26236, 30958, 27399, -1, 30956, 30958, 30954, -1, 27399, 26235, 26236, -1, 30325, 30959, 30327, -1, 26266, 30959, 30325, -1, 26263, 30960, 26266, -1, 26266, 30960, 30959, -1, 30327, 30942, 30329, -1, 30959, 30942, 30327, -1, 26262, 30947, 26263, -1, 26263, 30947, 30960, -1, 30959, 30943, 30942, -1, 30960, 30943, 30959, -1, 30939, 30945, 26262, -1, 26262, 30945, 30947, -1, 30329, 30940, 30332, -1, 30332, 30940, 26230, -1, 30942, 30940, 30329, -1, 30947, 30948, 30960, -1, 30960, 30948, 30943, -1, 26230, 30941, 26253, -1, 26249, 27454, 26247, -1, 27454, 30961, 26247, -1, 26247, 30962, 26245, -1, 30961, 30962, 26247, -1, 26245, 30963, 26241, -1, 30962, 30963, 26245, -1, 26241, 30964, 26227, -1, 30963, 30964, 26241, -1, 26227, 30965, 26225, -1, 30964, 30965, 26227, -1, 26225, 30966, 26259, -1, 30965, 30966, 26225, -1, 26259, 29447, 26257, -1, 30966, 29447, 26259, -1, 30962, 30967, 30963, -1, 30963, 30967, 30968, -1, 30969, 30970, 30971, -1, 30968, 30970, 30969, -1, 30972, 30973, 30974, -1, 30975, 30973, 30972, -1, 30317, 30976, 30977, -1, 30974, 30976, 30317, -1, 27443, 30978, 27454, -1, 27440, 30978, 27443, -1, 27454, 30978, 30961, -1, 30961, 30978, 30962, -1, 30962, 30978, 30967, -1, 30968, 30979, 30970, -1, 30967, 30979, 30968, -1, 30971, 30980, 30975, -1, 30975, 30980, 30973, -1, 30317, 30977, 28734, -1, 30977, 30981, 30982, -1, 30973, 30981, 30974, -1, 30976, 30981, 30977, -1, 30974, 30981, 30976, -1, 27436, 30983, 27440, -1, 27440, 30983, 30978, -1, 30978, 30983, 30967, -1, 30967, 30983, 30979, -1, 30970, 30984, 30971, -1, 30971, 30984, 30980, -1, 30982, 30985, 30986, -1, 30980, 30985, 30973, -1, 30973, 30985, 30981, -1, 30981, 30985, 30982, -1, 30970, 30987, 30984, -1, 30979, 30987, 30970, -1, 30984, 30988, 30980, -1, 30986, 30988, 30989, -1, 30980, 30988, 30985, -1, 30985, 30988, 30986, -1, 30979, 30990, 30987, -1, 27437, 30990, 27436, -1, 27436, 30990, 30983, -1, 30983, 30990, 30979, -1, 30987, 30991, 30984, -1, 30989, 30991, 30992, -1, 30988, 30991, 30989, -1, 30984, 30991, 30988, -1, 27433, 27421, 30993, -1, 30992, 30994, 30993, -1, 27433, 30994, 27437, -1, 30987, 30994, 30991, -1, 29447, 30995, 30324, -1, 27437, 30994, 30990, -1, 30993, 30994, 27433, -1, 30990, 30994, 30987, -1, 30991, 30994, 30992, -1, 30966, 30995, 29447, -1, 30965, 30996, 30966, -1, 30966, 30996, 30995, -1, 30323, 30972, 30321, -1, 30324, 30972, 30323, -1, 30995, 30972, 30324, -1, 30964, 30969, 30965, -1, 30965, 30969, 30996, -1, 30995, 30975, 30972, -1, 30996, 30975, 30995, -1, 30963, 30968, 30964, -1, 30964, 30968, 30969, -1, 30969, 30971, 30996, -1, 30996, 30971, 30975, -1, 30319, 30974, 30317, -1, 30321, 30974, 30319, -1, 30972, 30974, 30321, -1, 28735, 28734, 30997, -1, 30997, 30977, 30998, -1, 28734, 30977, 30997, -1, 30998, 30982, 30999, -1, 30977, 30982, 30998, -1, 30999, 30986, 31000, -1, 30982, 30986, 30999, -1, 31000, 30989, 31001, -1, 30986, 30989, 31000, -1, 31001, 30992, 31002, -1, 30989, 30992, 31001, -1, 31002, 30993, 27414, -1, 30992, 30993, 31002, -1, 30993, 27421, 27414, -1, 28735, 30997, 31003, -1, 31002, 27414, 29725, -1, 30998, 31004, 30997, -1, 31003, 31004, 31005, -1, 30997, 31004, 31003, -1, 31006, 31007, 31008, -1, 30999, 31009, 30998, -1, 31005, 31009, 31006, -1, 31006, 31009, 31007, -1, 31004, 31009, 31005, -1, 30998, 31009, 31004, -1, 31008, 31010, 29715, -1, 29729, 31010, 29727, -1, 29715, 31010, 29729, -1, 31007, 31010, 31008, -1, 31001, 31011, 31000, -1, 31000, 31011, 30999, -1, 31007, 31011, 31010, -1, 30999, 31011, 31009, -1, 31009, 31011, 31007, -1, 31002, 31012, 31001, -1, 29727, 31012, 29725, -1, 31001, 31012, 31011, -1, 31011, 31012, 31010, -1, 31010, 31012, 29727, -1, 29725, 31012, 31002, -1, 28735, 31003, 28733, -1, 28733, 31003, 31013, -1, 31013, 31005, 31014, -1, 31003, 31005, 31013, -1, 31014, 31006, 31015, -1, 31005, 31006, 31014, -1, 31015, 31008, 31016, -1, 31006, 31008, 31015, -1, 31016, 29715, 29714, -1, 31008, 29715, 31016, -1, 28732, 31017, 28731, -1, 28731, 31017, 31018, -1, 31018, 31017, 31019, -1, 31019, 31017, 31020, -1, 31014, 31021, 31013, -1, 31022, 31021, 31014, -1, 29713, 31023, 29737, -1, 31024, 31021, 31022, -1, 31020, 31021, 31024, -1, 28736, 31025, 28732, -1, 28732, 31025, 31017, -1, 31013, 31025, 28736, -1, 31021, 31025, 31013, -1, 31017, 31025, 31020, -1, 31020, 31025, 31021, -1, 28729, 28731, 31026, -1, 28736, 28733, 31013, -1, 29737, 31027, 29736, -1, 31023, 31027, 29737, -1, 31028, 31029, 31023, -1, 31023, 31029, 31027, -1, 29734, 31030, 29732, -1, 29736, 31030, 29734, -1, 31027, 31030, 29736, -1, 31031, 31032, 31028, -1, 31033, 31032, 31031, -1, 31028, 31032, 31029, -1, 31029, 31034, 31027, -1, 31027, 31034, 31030, -1, 31035, 31019, 31033, -1, 31033, 31019, 31032, -1, 29732, 31036, 29714, -1, 29714, 31036, 31016, -1, 31030, 31036, 29732, -1, 31029, 31024, 31034, -1, 31032, 31024, 31029, -1, 31026, 31018, 31035, -1, 31035, 31018, 31019, -1, 28731, 31018, 31026, -1, 31016, 31037, 31015, -1, 31030, 31037, 31036, -1, 31034, 31037, 31030, -1, 31036, 31037, 31016, -1, 31019, 31020, 31032, -1, 31032, 31020, 31024, -1, 31015, 31022, 31014, -1, 31024, 31022, 31034, -1, 31037, 31022, 31015, -1, 31034, 31022, 31037, -1, 29710, 31038, 29713, -1, 29713, 31038, 31023, -1, 31023, 31039, 31028, -1, 31038, 31039, 31023, -1, 31028, 31040, 31031, -1, 31039, 31040, 31028, -1, 31031, 31041, 31033, -1, 31040, 31041, 31031, -1, 31033, 31042, 31035, -1, 31041, 31042, 31033, -1, 31035, 31043, 31026, -1, 31042, 31043, 31035, -1, 31026, 28728, 28729, -1, 31043, 28728, 31026, -1, 31044, 29743, 29741, -1, 29743, 31038, 29710, -1, 31044, 31038, 29743, -1, 31045, 31039, 31044, -1, 31044, 31039, 31038, -1, 31046, 31040, 31045, -1, 31047, 31040, 31046, -1, 31045, 31040, 31039, -1, 31048, 31041, 31047, -1, 31047, 31041, 31040, -1, 31049, 31042, 31048, -1, 31048, 31042, 31041, -1, 28726, 28725, 31049, -1, 28725, 31043, 31049, -1, 31049, 31043, 31042, -1, 28725, 28727, 31043, -1, 28727, 28728, 31043, -1, 31050, 29738, 29724, -1, 29740, 31044, 29741, -1, 30634, 30636, 31051, -1, 30637, 28726, 31049, -1, 29738, 31052, 29740, -1, 31050, 31052, 29738, -1, 29740, 31052, 31044, -1, 31053, 31054, 31050, -1, 31044, 31054, 31045, -1, 31052, 31054, 31044, -1, 31050, 31054, 31052, -1, 31055, 31056, 31053, -1, 31045, 31056, 31046, -1, 31054, 31056, 31045, -1, 31053, 31056, 31054, -1, 31057, 31058, 31055, -1, 31059, 31058, 31057, -1, 31046, 31058, 31047, -1, 31056, 31058, 31046, -1, 31055, 31058, 31056, -1, 31060, 31061, 31059, -1, 31058, 31061, 31047, -1, 31059, 31061, 31058, -1, 31062, 31063, 31060, -1, 31047, 31063, 31048, -1, 31061, 31063, 31047, -1, 31060, 31063, 31061, -1, 30637, 31064, 30636, -1, 31051, 31064, 31062, -1, 31048, 31064, 31049, -1, 30636, 31064, 31051, -1, 31063, 31064, 31048, -1, 31062, 31064, 31063, -1, 31049, 31064, 30637, -1, 29724, 31065, 31050, -1, 31050, 31065, 31053, -1, 31053, 31065, 31066, -1, 31066, 31065, 31067, -1, 31051, 30632, 30634, -1, 30632, 31068, 27466, -1, 27466, 31068, 31069, -1, 31051, 31068, 30632, -1, 31069, 31070, 31071, -1, 31062, 31070, 31051, -1, 31068, 31070, 31069, -1, 31051, 31070, 31068, -1, 31071, 31072, 31073, -1, 31060, 31072, 31062, -1, 31062, 31072, 31070, -1, 31070, 31072, 31071, -1, 31073, 31074, 31075, -1, 31059, 31074, 31060, -1, 31060, 31074, 31072, -1, 31072, 31074, 31073, -1, 31076, 31077, 31078, -1, 31075, 31077, 31076, -1, 31057, 31077, 31059, -1, 31074, 31077, 31075, -1, 31059, 31077, 31074, -1, 31055, 31079, 31057, -1, 31077, 31079, 31078, -1, 31057, 31079, 31077, -1, 31078, 31066, 31067, -1, 31053, 31066, 31055, -1, 31055, 31066, 31079, -1, 31079, 31066, 31078, -1, 31080, 31065, 29723, -1, 31067, 31065, 31080, -1, 29723, 31065, 29724, -1, 27467, 27466, 31081, -1, 31081, 31069, 31082, -1, 27466, 31069, 31081, -1, 31082, 31071, 31083, -1, 31069, 31071, 31082, -1, 31083, 31073, 31084, -1, 31071, 31073, 31083, -1, 31084, 31075, 31085, -1, 31073, 31075, 31084, -1, 31085, 31076, 31086, -1, 31075, 31076, 31085, -1, 31086, 31078, 31087, -1, 31076, 31078, 31086, -1, 31087, 31067, 31088, -1, 31078, 31067, 31087, -1, 31088, 31080, 31089, -1, 31067, 31080, 31088, -1, 31089, 29723, 29716, -1, 31080, 29723, 31089, -1, 31090, 31091, 31087, -1, 31087, 31091, 31086, -1, 31092, 31091, 31093, -1, 31086, 31091, 31092, -1, 31084, 31094, 31083, -1, 31083, 31094, 31082, -1, 27633, 31094, 27631, -1, 27635, 31094, 27633, -1, 27631, 31094, 31095, -1, 31096, 31094, 31084, -1, 31082, 31094, 27635, -1, 31095, 31094, 31096, -1, 31089, 29716, 29748, -1, 27460, 31093, 29744, -1, 27635, 27637, 31082, -1, 27637, 31081, 31082, -1, 27637, 27467, 31081, -1, 31088, 31097, 31087, -1, 31090, 31097, 31093, -1, 31087, 31097, 31090, -1, 31089, 31098, 31088, -1, 31088, 31098, 31097, -1, 31097, 31098, 31093, -1, 29748, 31099, 31089, -1, 31093, 31099, 29744, -1, 31098, 31099, 31093, -1, 31089, 31099, 31098, -1, 29746, 31100, 29748, -1, 29744, 31100, 29746, -1, 31099, 31100, 29744, -1, 29748, 31100, 31099, -1, 27627, 31101, 27460, -1, 27630, 31101, 27627, -1, 27460, 31101, 31093, -1, 27630, 31102, 31101, -1, 31101, 31102, 31093, -1, 31102, 31103, 31093, -1, 31103, 31104, 31093, -1, 27631, 31095, 27630, -1, 31102, 31095, 31103, -1, 27630, 31095, 31102, -1, 31086, 31092, 31085, -1, 31104, 31092, 31093, -1, 31085, 31092, 31104, -1, 31085, 31096, 31084, -1, 31103, 31096, 31104, -1, 31104, 31096, 31085, -1, 31095, 31096, 31103, -1, 31093, 31091, 31090, -1, 31105, 29052, 29051, -1, 31106, 31105, 29051, -1, 31107, 29051, 29105, -1, 31107, 31106, 29051, -1, 31108, 31107, 29105, -1, 31109, 31108, 29105, -1, 29107, 31109, 29105, -1, 31110, 29534, 29527, -1, 31110, 29527, 31111, -1, 31112, 31111, 31113, -1, 31112, 31110, 31111, -1, 31114, 31113, 31115, -1, 31114, 31112, 31113, -1, 31116, 31115, 31117, -1, 31116, 31114, 31115, -1, 31118, 31116, 31117, -1, 31119, 31117, 31120, -1, 31119, 31118, 31117, -1, 31121, 31120, 31122, -1, 31121, 31119, 31120, -1, 31123, 31121, 31122, -1, 29704, 31122, 29130, -1, 29704, 31123, 31122, -1, 29136, 29704, 29130, -1, 31124, 31111, 29527, -1, 31124, 29527, 30231, -1, 31125, 31113, 31111, -1, 31125, 31111, 31124, -1, 31126, 31115, 31113, -1, 31126, 31117, 31115, -1, 31126, 31113, 31125, -1, 31127, 31120, 31117, -1, 31127, 31117, 31126, -1, 31128, 31122, 31120, -1, 31128, 31120, 31127, -1, 31129, 29130, 31122, -1, 31129, 31122, 31128, -1, 26308, 29130, 31129, -1, 31130, 31131, 26305, -1, 31132, 31133, 31134, -1, 31132, 31134, 31135, -1, 31136, 30233, 30235, -1, 31136, 31137, 30233, -1, 31138, 31133, 31132, -1, 31138, 31139, 31133, -1, 31140, 31137, 31136, -1, 31140, 31135, 31137, -1, 31141, 31139, 31138, -1, 31141, 31131, 31139, -1, 31141, 26305, 31131, -1, 31142, 31132, 31135, -1, 26306, 26308, 31129, -1, 31142, 31135, 31140, -1, 31143, 26304, 26305, -1, 31143, 26305, 31141, -1, 31144, 31132, 31142, -1, 31144, 31138, 31132, -1, 31145, 30235, 30236, -1, 31145, 31136, 30235, -1, 31146, 31141, 31138, -1, 31146, 31138, 31144, -1, 31147, 31136, 31145, -1, 31147, 31140, 31136, -1, 31148, 30623, 30624, -1, 31148, 30624, 26304, -1, 31148, 31141, 31146, -1, 31148, 26304, 31143, -1, 31149, 30238, 29524, -1, 31148, 31143, 31141, -1, 31150, 30236, 30238, -1, 31150, 31145, 30236, -1, 31151, 31140, 31147, -1, 31152, 30238, 31149, -1, 31151, 31142, 31140, -1, 31153, 31147, 31145, -1, 31153, 31145, 31150, -1, 31153, 31150, 30238, -1, 31154, 31142, 31151, -1, 31155, 30620, 31156, -1, 31154, 31144, 31142, -1, 30619, 30620, 31155, -1, 31157, 31147, 31153, -1, 31158, 31124, 30231, -1, 31157, 31152, 31159, -1, 31157, 31153, 30238, -1, 31158, 30231, 30232, -1, 31158, 30232, 30233, -1, 31157, 31151, 31147, -1, 31157, 30238, 31152, -1, 31134, 31125, 31124, -1, 31160, 31146, 31144, -1, 31160, 31144, 31154, -1, 31134, 31124, 31158, -1, 31161, 31159, 31156, -1, 31133, 31126, 31125, -1, 31161, 31157, 31159, -1, 31161, 31151, 31157, -1, 31161, 31154, 31151, -1, 31133, 31125, 31134, -1, 31162, 30623, 31148, -1, 31162, 30621, 30622, -1, 31162, 31146, 31160, -1, 31139, 31127, 31126, -1, 31162, 30622, 30623, -1, 31162, 31148, 31146, -1, 31163, 31160, 31154, -1, 31139, 31126, 31133, -1, 31163, 31154, 31161, -1, 31163, 31161, 31156, -1, 31163, 31156, 30620, -1, 31164, 30621, 31162, -1, 31137, 31158, 30233, -1, 31164, 30620, 30621, -1, 31164, 31162, 31160, -1, 31164, 31160, 31163, -1, 31164, 31163, 30620, -1, 31131, 31128, 31127, -1, 31131, 31127, 31139, -1, 31135, 31158, 31137, -1, 31135, 31134, 31158, -1, 31130, 31129, 31128, -1, 31130, 26305, 26306, -1, 31130, 26306, 31129, -1, 31130, 31128, 31131, -1, 30618, 30619, 31155, -1, 31165, 31149, 29524, -1, 31165, 29524, 29523, -1, 31165, 29523, 29522, -1, 31166, 31152, 31149, -1, 31166, 31149, 31165, -1, 31167, 29522, 29519, -1, 31167, 29519, 31168, -1, 31167, 31168, 31169, -1, 31167, 31165, 29522, -1, 31170, 31159, 31152, -1, 31170, 31152, 31166, -1, 31171, 31166, 31165, -1, 31171, 31165, 31167, -1, 31171, 31167, 31169, -1, 31172, 31156, 31159, -1, 31172, 31159, 31170, -1, 31173, 31169, 31174, -1, 31173, 31174, 31175, -1, 31173, 31170, 31166, -1, 31173, 31171, 31169, -1, 31173, 31166, 31171, -1, 31176, 31155, 31156, -1, 31176, 31156, 31172, -1, 31177, 31173, 31175, -1, 31177, 31170, 31173, -1, 31177, 31172, 31170, -1, 31178, 30617, 30618, -1, 31178, 30618, 31155, -1, 31178, 31155, 31176, -1, 31179, 31175, 31180, -1, 31179, 31172, 31177, -1, 31179, 31176, 31172, -1, 31179, 31177, 31175, -1, 31181, 31180, 31182, -1, 31181, 31182, 29268, -1, 31181, 29268, 30617, -1, 31181, 30617, 31178, -1, 31181, 31179, 31180, -1, 31181, 31178, 31176, -1, 31181, 31176, 31179, -1, 29519, 29521, 31183, -1, 31168, 31183, 31184, -1, 31168, 29519, 31183, -1, 31169, 31184, 31185, -1, 31169, 31168, 31184, -1, 31174, 31185, 31186, -1, 31174, 31169, 31185, -1, 31175, 31186, 31187, -1, 31175, 31174, 31186, -1, 31180, 31187, 31188, -1, 31180, 31175, 31187, -1, 31182, 31188, 29228, -1, 31182, 31180, 31188, -1, 29268, 31182, 29228, -1, 31189, 31190, 31191, -1, 31189, 31192, 31190, -1, 29231, 31193, 29230, -1, 31194, 26218, 26219, -1, 31194, 26219, 31195, -1, 31196, 29228, 31188, -1, 31196, 29227, 29229, -1, 31196, 29229, 29228, -1, 31196, 31191, 29227, -1, 31197, 31195, 31198, -1, 31197, 31198, 31199, -1, 31200, 31192, 31189, -1, 31200, 31199, 31192, -1, 31201, 26216, 26218, -1, 31201, 26218, 31194, -1, 31201, 30254, 26216, -1, 31202, 31188, 31187, -1, 31202, 31196, 31188, -1, 31202, 31189, 31191, -1, 31202, 31191, 31196, -1, 31203, 31194, 31195, -1, 31203, 31195, 31197, -1, 31204, 31197, 31199, -1, 31204, 31199, 31200, -1, 31205, 31187, 31186, -1, 30254, 26213, 26216, -1, 31205, 31202, 31187, -1, 31205, 31200, 31189, -1, 31205, 31189, 31202, -1, 31206, 30252, 30254, -1, 31206, 30254, 31201, -1, 31206, 31201, 31194, -1, 31206, 31194, 31203, -1, 31207, 31203, 31197, -1, 31207, 31197, 31204, -1, 31208, 31186, 31185, -1, 31208, 31205, 31186, -1, 31208, 31204, 31200, -1, 31208, 31200, 31205, -1, 31209, 31206, 31203, -1, 31209, 30250, 30252, -1, 31209, 31203, 31207, -1, 31209, 30252, 31206, -1, 31210, 31185, 31184, -1, 31210, 31207, 31204, -1, 31210, 31204, 31208, -1, 31210, 31208, 31185, -1, 31211, 31183, 29521, -1, 31211, 31210, 31184, -1, 31211, 31184, 31183, -1, 31211, 31209, 31207, -1, 31211, 29521, 30248, -1, 31211, 30248, 30250, -1, 31211, 30250, 31209, -1, 31211, 31207, 31210, -1, 31212, 31213, 31193, -1, 31212, 31193, 29231, -1, 31214, 31215, 31213, -1, 31214, 31213, 31212, -1, 31190, 29231, 29232, -1, 31190, 31212, 29231, -1, 31198, 31216, 31215, -1, 31198, 31215, 31214, -1, 31192, 31214, 31212, -1, 31192, 31212, 31190, -1, 31191, 29232, 29227, -1, 31191, 31190, 29232, -1, 31195, 26219, 31216, -1, 31195, 31216, 31198, -1, 31199, 31214, 31192, -1, 31199, 31198, 31214, -1, 31216, 26219, 26220, -1, 31216, 26220, 31217, -1, 31215, 31217, 31218, -1, 31215, 31216, 31217, -1, 31213, 31218, 31219, -1, 31213, 31215, 31218, -1, 31193, 31219, 31220, -1, 31193, 31213, 31219, -1, 29230, 31220, 29239, -1, 29230, 31193, 31220, -1, 31221, 31222, 31223, -1, 31221, 31223, 31224, -1, 31225, 31226, 30205, -1, 31227, 31222, 31221, -1, 31228, 31226, 31225, -1, 31227, 31229, 31222, -1, 31228, 31230, 31226, -1, 31231, 30216, 30220, -1, 31232, 29240, 29242, -1, 31232, 31220, 31219, -1, 31232, 29242, 31220, -1, 31232, 31219, 31233, -1, 26312, 26215, 26214, -1, 31232, 31233, 29240, -1, 31234, 31235, 31230, -1, 31236, 31237, 30216, -1, 31234, 31230, 31228, -1, 31236, 31231, 30220, -1, 31238, 31235, 31234, -1, 31236, 30216, 31231, -1, 31238, 31239, 31235, -1, 31240, 29245, 31241, -1, 31240, 31241, 31229, -1, 31240, 31229, 31227, -1, 31242, 31243, 31239, -1, 31242, 31239, 31238, -1, 31244, 31237, 31236, -1, 31244, 31245, 31237, -1, 31246, 31233, 31243, -1, 31246, 29240, 31233, -1, 31246, 31243, 31242, -1, 31247, 30205, 30208, -1, 31248, 29244, 29245, -1, 31248, 29245, 31240, -1, 29242, 29239, 31220, -1, 31247, 31225, 30205, -1, 31249, 31224, 31245, -1, 31250, 29247, 29240, -1, 31250, 29240, 31246, -1, 31250, 31246, 29247, -1, 31249, 31245, 31244, -1, 31251, 31225, 31247, -1, 31252, 29274, 29273, -1, 31252, 31221, 31224, -1, 31251, 31228, 31225, -1, 31252, 31224, 31249, -1, 31253, 31228, 31251, -1, 31254, 29273, 29271, -1, 31254, 31221, 31252, -1, 31254, 31227, 31221, -1, 31253, 31234, 31228, -1, 31254, 31252, 29273, -1, 31255, 29271, 29272, -1, 31256, 31234, 31253, -1, 31256, 31238, 31234, -1, 31255, 31240, 31227, -1, 31255, 31254, 29271, -1, 31255, 31227, 31254, -1, 31257, 29277, 29278, -1, 31257, 29278, 29275, -1, 31257, 31244, 31236, -1, 31257, 31236, 30220, -1, 31257, 30220, 29277, -1, 31258, 31242, 31238, -1, 31259, 29272, 29241, -1, 31258, 31238, 31256, -1, 31259, 29241, 29243, -1, 31259, 29243, 29244, -1, 31259, 29244, 31248, -1, 31259, 31248, 31240, -1, 31260, 31242, 31258, -1, 31259, 31255, 29272, -1, 31260, 29247, 31246, -1, 31259, 31240, 31255, -1, 31260, 31246, 31242, -1, 31261, 29275, 29274, -1, 31261, 31244, 31257, -1, 29277, 30220, 29276, -1, 31261, 31249, 31244, -1, 31261, 29274, 31252, -1, 31262, 30208, 30212, -1, 31261, 31252, 31249, -1, 31261, 31257, 29275, -1, 31262, 31247, 30208, -1, 31263, 31260, 29246, -1, 31263, 29246, 29247, -1, 31263, 29247, 31260, -1, 31264, 31247, 31262, -1, 31264, 31251, 31247, -1, 31265, 31251, 31264, -1, 31265, 31253, 31251, -1, 31223, 31256, 31253, -1, 31223, 31253, 31265, -1, 31222, 31256, 31223, -1, 31222, 31258, 31256, -1, 31226, 26312, 30205, -1, 31229, 29246, 31260, -1, 31226, 26215, 26312, -1, 31229, 31258, 31222, -1, 31229, 31260, 31258, -1, 31230, 26217, 26215, -1, 31266, 30212, 30216, -1, 31230, 26215, 31226, -1, 31266, 31262, 30212, -1, 31235, 26220, 26217, -1, 31237, 31264, 31262, -1, 31235, 26217, 31230, -1, 31237, 31266, 30216, -1, 31239, 31217, 26220, -1, 31237, 31262, 31266, -1, 31239, 26220, 31235, -1, 31241, 29245, 29246, -1, 31241, 29246, 31229, -1, 31245, 31265, 31264, -1, 31243, 31218, 31217, -1, 31245, 31264, 31237, -1, 31243, 31217, 31239, -1, 31233, 31219, 31218, -1, 31224, 31223, 31265, -1, 31233, 31218, 31243, -1, 31224, 31265, 31245, -1, 31267, 31268, 31269, -1, 31270, 31271, 26315, -1, 31267, 31269, 31272, -1, 31273, 31274, 31275, -1, 31276, 31277, 31268, -1, 31276, 31268, 31267, -1, 31273, 31275, 31278, -1, 31279, 31280, 31281, -1, 31282, 31277, 31276, -1, 31282, 31283, 31277, -1, 31284, 30223, 30219, -1, 31279, 31285, 31271, -1, 31279, 31270, 31280, -1, 31279, 31271, 31270, -1, 31286, 29358, 29361, -1, 31287, 29362, 31288, -1, 31286, 29361, 31289, -1, 31287, 31283, 31282, -1, 31286, 31273, 29358, -1, 31286, 31289, 31274, -1, 31287, 31288, 31283, -1, 31286, 31274, 31273, -1, 31290, 31281, 31291, -1, 31292, 31284, 30219, -1, 31292, 30223, 31284, -1, 31290, 31279, 31281, -1, 31290, 31293, 31285, -1, 31292, 31272, 30223, -1, 29359, 26210, 26208, -1, 31290, 31285, 31279, -1, 29359, 26211, 26210, -1, 31294, 31291, 31295, -1, 31296, 31267, 31272, -1, 31294, 31278, 31293, -1, 31296, 31272, 31292, -1, 31294, 31293, 31290, -1, 31294, 31290, 31291, -1, 31297, 31295, 31298, -1, 31299, 31267, 31296, -1, 31299, 31276, 31267, -1, 31297, 31294, 31295, -1, 31300, 31276, 31299, -1, 31297, 29358, 31273, -1, 31297, 31273, 31278, -1, 31297, 31278, 31294, -1, 31300, 31282, 31276, -1, 31301, 31298, 31302, -1, 31301, 31302, 29357, -1, 31301, 29357, 29358, -1, 31301, 29358, 31297, -1, 31303, 30219, 30215, -1, 31301, 31297, 31298, -1, 31304, 31282, 31300, -1, 31304, 29364, 29362, -1, 31304, 29362, 31287, -1, 31304, 31287, 31282, -1, 31305, 31303, 30215, -1, 31305, 31292, 30219, -1, 31305, 30219, 31303, -1, 31306, 31292, 31305, -1, 31306, 31296, 31292, -1, 31307, 31299, 31296, -1, 31307, 31296, 31306, -1, 31308, 31299, 31307, -1, 31308, 31300, 31299, -1, 31309, 30215, 30211, -1, 31310, 31304, 31300, -1, 31310, 29364, 31304, -1, 31310, 31300, 31308, -1, 31310, 29361, 29363, -1, 31310, 29363, 29364, -1, 31311, 30215, 31309, -1, 31311, 31305, 30215, -1, 31312, 31306, 31305, -1, 31312, 31305, 31311, -1, 31275, 31307, 31306, -1, 31313, 26202, 26201, -1, 31275, 31306, 31312, -1, 31313, 26201, 30226, -1, 31274, 31308, 31307, -1, 31269, 26204, 26202, -1, 31274, 31307, 31275, -1, 31271, 30211, 30207, -1, 31271, 30207, 26315, -1, 31269, 26202, 31313, -1, 31268, 26206, 26204, -1, 31271, 31309, 30211, -1, 31268, 26204, 31269, -1, 31289, 31310, 31308, -1, 31289, 29361, 31310, -1, 31277, 26208, 26206, -1, 31289, 31308, 31274, -1, 31277, 26206, 31268, -1, 31285, 31311, 31309, -1, 31283, 26208, 31277, -1, 31285, 31309, 31271, -1, 31283, 29359, 26208, -1, 31314, 30226, 30223, -1, 31314, 31313, 30226, -1, 31293, 31312, 31311, -1, 31288, 29362, 29360, -1, 31293, 31311, 31285, -1, 31288, 29360, 29359, -1, 31288, 29359, 31283, -1, 31272, 31314, 30223, -1, 31278, 31275, 31312, -1, 31272, 31313, 31314, -1, 31278, 31312, 31293, -1, 31270, 26315, 26314, -1, 31272, 31269, 31313, -1, 31270, 26314, 31280, -1, 26314, 29430, 31315, -1, 31280, 31315, 31316, -1, 31280, 26314, 31315, -1, 31281, 31316, 31317, -1, 31281, 31280, 31316, -1, 31291, 31317, 31318, -1, 31291, 31281, 31317, -1, 31295, 31318, 31319, -1, 31295, 31291, 31318, -1, 31298, 31319, 31320, -1, 31298, 31295, 31319, -1, 31302, 31320, 29349, -1, 31302, 31298, 31320, -1, 29357, 31302, 29349, -1, 31321, 31322, 30246, -1, 31323, 31324, 31325, -1, 31323, 31322, 31321, -1, 31323, 31326, 31322, -1, 31323, 31321, 31324, -1, 31327, 31323, 31325, -1, 31327, 31326, 31323, -1, 31327, 31325, 31328, -1, 31327, 31329, 31326, -1, 31330, 31329, 31327, -1, 31330, 31328, 31331, -1, 31330, 31327, 31328, -1, 31330, 29344, 31332, -1, 30240, 31315, 29430, -1, 31330, 31332, 31329, -1, 31333, 29344, 31330, -1, 31333, 31331, 31334, -1, 31333, 31334, 31335, -1, 31333, 31330, 31331, -1, 31336, 29344, 31333, -1, 31336, 31333, 31335, -1, 31336, 31335, 29335, -1, 31336, 29335, 29344, -1, 29348, 31317, 31316, -1, 29348, 31318, 31317, -1, 29348, 31319, 31318, -1, 29348, 31320, 31319, -1, 29348, 29349, 31320, -1, 31337, 31315, 30240, -1, 31338, 31316, 31315, -1, 31338, 31315, 31337, -1, 31338, 29348, 31316, -1, 31339, 31338, 29346, -1, 31339, 29348, 31338, -1, 31340, 31339, 29346, -1, 31340, 29348, 31339, -1, 31341, 31340, 29346, -1, 31341, 29348, 31340, -1, 31342, 29346, 29348, -1, 31342, 29348, 31341, -1, 31342, 31341, 29346, -1, 31343, 30240, 30242, -1, 31343, 30242, 30244, -1, 31343, 31337, 30240, -1, 31344, 29346, 31338, -1, 31344, 31338, 31337, -1, 31344, 31337, 31343, -1, 31345, 29346, 31344, -1, 31346, 29346, 31345, -1, 31346, 31345, 29343, -1, 31347, 31346, 29343, -1, 31347, 29346, 31346, -1, 31348, 29343, 29346, -1, 31348, 31347, 29343, -1, 31348, 29346, 31347, -1, 31322, 30244, 30246, -1, 31322, 31343, 30244, -1, 31326, 31344, 31343, -1, 31326, 31343, 31322, -1, 31329, 31345, 31344, -1, 31329, 29343, 31345, -1, 31329, 31344, 31326, -1, 31332, 29343, 31329, -1, 31349, 31332, 29344, -1, 31349, 29343, 31332, -1, 31350, 29344, 29343, -1, 31350, 31349, 29344, -1, 31350, 29343, 31349, -1, 31321, 30246, 27500, -1, 31321, 27500, 31324, -1, 31324, 27500, 27502, -1, 31324, 27502, 31351, -1, 31325, 31351, 31352, -1, 31325, 31324, 31351, -1, 31328, 31352, 31353, -1, 31328, 31325, 31352, -1, 31331, 31353, 31354, -1, 31331, 31328, 31353, -1, 31334, 31354, 31355, -1, 31334, 31331, 31354, -1, 31335, 31355, 31356, -1, 31335, 31334, 31355, -1, 29335, 31356, 29298, -1, 29335, 31335, 31356, -1, 31357, 31358, 31359, -1, 31357, 31359, 31360, -1, 31357, 27501, 31358, -1, 31361, 30627, 30628, -1, 31362, 31361, 30628, -1, 31362, 30627, 31361, -1, 31363, 31362, 30628, -1, 31363, 30627, 31362, -1, 31364, 30627, 31363, -1, 31364, 31363, 30628, -1, 31365, 27505, 27506, -1, 31365, 27506, 31357, -1, 31365, 31357, 30627, -1, 31365, 30628, 27505, -1, 31365, 30627, 31364, -1, 31365, 31364, 30628, -1, 31366, 30628, 30629, -1, 31367, 30628, 31366, -1, 31367, 31366, 30629, -1, 31368, 30628, 31367, -1, 31368, 31367, 30629, -1, 31369, 30628, 31368, -1, 31369, 31368, 30629, -1, 30625, 26180, 26179, -1, 31370, 30628, 31369, -1, 30625, 26182, 26180, -1, 31370, 31369, 30629, -1, 30625, 26185, 26182, -1, 31370, 30629, 27504, -1, 30625, 26188, 26185, -1, 31370, 27504, 30628, -1, 31371, 30629, 30630, -1, 31372, 30629, 31371, -1, 31372, 31371, 30630, -1, 31373, 30629, 31372, -1, 31373, 31372, 30630, -1, 27501, 26198, 26195, -1, 31374, 30629, 31373, -1, 31375, 30629, 31374, -1, 31376, 30629, 31375, -1, 31376, 27503, 30629, -1, 31377, 30630, 30631, -1, 31377, 30631, 29298, -1, 31377, 29298, 31356, -1, 31378, 31356, 31355, -1, 27504, 27505, 30628, -1, 31378, 30630, 31377, -1, 31378, 31377, 31356, -1, 27503, 27504, 30629, -1, 31379, 31355, 31354, -1, 31379, 31378, 31355, -1, 31379, 30630, 31378, -1, 31380, 31354, 31353, -1, 31380, 31373, 30630, -1, 31380, 30630, 31379, -1, 31380, 31379, 31354, -1, 31381, 31353, 31352, -1, 31381, 31380, 31353, -1, 31381, 31374, 31373, -1, 31381, 31373, 31380, -1, 31382, 31352, 31351, -1, 31382, 31375, 31374, -1, 31382, 31374, 31381, -1, 31382, 31381, 31352, -1, 31383, 31351, 27502, -1, 31383, 27502, 27503, -1, 31383, 31376, 31375, -1, 31383, 27503, 31376, -1, 31384, 30625, 30626, -1, 31383, 31375, 31382, -1, 31383, 31382, 31351, -1, 31385, 30625, 31384, -1, 31385, 31384, 30626, -1, 31386, 31385, 30626, -1, 31386, 26188, 30625, -1, 31386, 30625, 31385, -1, 31387, 26189, 26188, -1, 31387, 26188, 31386, -1, 31387, 31386, 30626, -1, 31359, 26193, 26189, -1, 31359, 31387, 30626, -1, 31359, 26189, 31387, -1, 31358, 26195, 26193, -1, 31358, 27501, 26195, -1, 31358, 26193, 31359, -1, 31388, 30626, 30627, -1, 31389, 31388, 30627, -1, 31389, 30626, 31388, -1, 31390, 31389, 30627, -1, 31390, 30626, 31389, -1, 31360, 31359, 30626, -1, 31360, 30626, 31390, -1, 31360, 31390, 30627, -1, 31357, 27506, 27501, -1, 31357, 31360, 30627, -1, 27512, 27515, 29537, -1, 30574, 29537, 29538, -1, 30574, 27512, 29537, -1, 31110, 31112, 29540, -1, 30575, 29538, 29539, -1, 30575, 30574, 29538, -1, 29534, 31110, 29540, -1, 30576, 29539, 29540, -1, 30576, 30575, 29539, -1, 30577, 31112, 31114, -1, 30577, 31114, 31116, -1, 30577, 29540, 31112, -1, 30577, 30576, 29540, -1, 30578, 31116, 31118, -1, 30578, 31118, 31119, -1, 30578, 30577, 31116, -1, 30579, 31119, 31121, -1, 30579, 30578, 31119, -1, 30580, 31121, 31123, -1, 30580, 30579, 31121, -1, 30581, 31123, 29704, -1, 30581, 30580, 31123, -1, 29702, 30581, 29704, -1, 31391, 31392, 31393, -1, 31393, 31392, 31394, -1, 31395, 31396, 31391, -1, 31391, 31396, 31392, -1, 31397, 29425, 31395, -1, 31395, 29425, 31396, -1, 31397, 31398, 29425, -1, 31398, 31399, 29425, -1, 31399, 30265, 29425, -1, 30265, 30267, 29425, -1, 30267, 30270, 29425, -1, 30270, 30271, 29425, -1, 30271, 30273, 29425, -1, 30273, 29069, 29425, -1, 29069, 29395, 29425, -1, 29395, 29677, 29680, -1, 29395, 29675, 29677, -1, 29069, 29067, 29395, -1, 29395, 29067, 29675, -1, 29675, 29067, 29569, -1, 29067, 29572, 29569, -1, 29067, 29063, 29572, -1, 30539, 29066, 27511, -1, 27511, 29066, 29064, -1, 30538, 29065, 30539, -1, 30539, 29065, 29066, -1, 29572, 29063, 30538, -1, 30538, 29063, 29065, -1, 27511, 29071, 27514, -1, 29064, 29071, 27511, -1, 27514, 29071, 29544, -1, 29073, 29544, 29071, -1, 29543, 29544, 29073, -1, 30595, 29542, 29073, -1, 29073, 29542, 29543, -1, 30597, 29541, 30595, -1, 30595, 29541, 29542, -1, 30599, 29536, 30597, -1, 30597, 29536, 29541, -1, 30601, 29535, 30599, -1, 30599, 29535, 29536, -1, 29164, 29533, 30601, -1, 30601, 29533, 29535, -1, 29171, 29533, 29164, -1, 29532, 29533, 29171, -1, 30603, 29531, 29171, -1, 29171, 29531, 29532, -1, 30605, 29530, 30603, -1, 30603, 29530, 29531, -1, 30607, 29529, 30605, -1, 30605, 29529, 29530, -1, 30609, 29528, 30607, -1, 30607, 29528, 29529, -1, 30611, 29526, 30609, -1, 30609, 29526, 29528, -1, 30237, 30616, 29525, -1, 30234, 30614, 30237, -1, 30237, 30614, 30616, -1, 29526, 30613, 30234, -1, 30234, 30613, 30614, -1, 29526, 30611, 30613, -1, 29192, 29520, 30616, -1, 30616, 29520, 29525, -1, 29518, 29192, 29213, -1, 29518, 29520, 29192, -1, 29518, 29213, 29219, -1, 30247, 29219, 29220, -1, 30247, 29518, 29219, -1, 30249, 29220, 29221, -1, 30249, 30247, 29220, -1, 30251, 29221, 29222, -1, 30251, 30249, 29221, -1, 30253, 30251, 29222, -1, 29432, 29222, 29199, -1, 29432, 30253, 29222, -1, 26310, 29199, 29195, -1, 26310, 29432, 29199, -1, 30227, 29207, 29095, -1, 29095, 29207, 29187, -1, 30224, 29206, 30227, -1, 30227, 29206, 29207, -1, 30221, 29204, 30224, -1, 30224, 29204, 29206, -1, 30217, 29205, 30221, -1, 30221, 29205, 29204, -1, 30213, 29210, 30217, -1, 30217, 29210, 29205, -1, 30209, 29212, 30213, -1, 30213, 29212, 29210, -1, 30206, 29211, 30209, -1, 30209, 29211, 29212, -1, 30204, 29208, 30206, -1, 30206, 29208, 29211, -1, 26311, 29202, 30204, -1, 30204, 29202, 29208, -1, 26310, 29195, 26311, -1, 26311, 29195, 29202, -1, 29085, 29187, 29193, -1, 29085, 29095, 29187, -1, 30615, 29084, 29193, -1, 29193, 29084, 29085, -1, 30612, 29083, 30615, -1, 30615, 29083, 29084, -1, 30610, 29082, 30612, -1, 30612, 29082, 29083, -1, 30608, 29081, 30610, -1, 30610, 29081, 29082, -1, 30606, 29080, 30608, -1, 30608, 29080, 29081, -1, 30604, 29079, 30606, -1, 30606, 29079, 29080, -1, 30602, 29077, 30604, -1, 30604, 29077, 29079, -1, 29179, 29078, 30602, -1, 30602, 29078, 29077, -1, 29097, 29179, 29169, -1, 29097, 29078, 29179, -1, 30600, 29098, 29169, -1, 29169, 29098, 29097, -1, 30598, 29099, 30600, -1, 30600, 29099, 29098, -1, 30596, 29100, 30598, -1, 30598, 29100, 29099, -1, 30594, 29101, 30596, -1, 30596, 29101, 29100, -1, 29072, 29074, 30594, -1, 30594, 29074, 29101, -1, 31400, 29072, 31401, -1, 31401, 29072, 31402, -1, 31402, 29072, 31403, -1, 31403, 29072, 31404, -1, 31404, 29072, 31405, -1, 31405, 29072, 31406, -1, 31406, 29072, 29068, -1, 29633, 29074, 31407, -1, 31407, 29074, 31400, -1, 29075, 29074, 29633, -1, 31400, 29074, 29072, -1, 27202, 27272, 27498, -1, 25635, 29437, 31408, -1, 31408, 29437, 31409, -1, 31409, 29437, 31410, -1, 31410, 29437, 31411, -1, 31411, 29437, 31412, -1, 31412, 29437, 31413, -1, 31413, 29437, 31414, -1, 31414, 29437, 31415, -1, 31415, 29437, 31416, -1, 31416, 29437, 31417, -1, 31417, 29437, 27272, -1, 27272, 30532, 27498, -1, 29437, 30532, 27272, -1, 30532, 30530, 27498, -1, 30530, 30528, 27498, -1, 30528, 27499, 27498, -1, 25638, 29437, 25636, -1, 25636, 29437, 25635, -1, 30245, 27206, 27498, -1, 27498, 27206, 27202, -1, 30243, 27203, 30245, -1, 30245, 27203, 27206, -1, 30241, 27201, 30243, -1, 30243, 27201, 27203, -1, 30239, 27219, 30241, -1, 30241, 27219, 27201, -1, 29431, 27228, 30239, -1, 30239, 27228, 27219, -1, 26313, 27228, 29431, -1, 27300, 27228, 26313, -1, 26316, 27300, 26313, -1, 26316, 27337, 27300, -1, 30210, 27335, 26316, -1, 26316, 27335, 27337, -1, 30214, 27334, 30210, -1, 30210, 27334, 27335, -1, 30218, 27333, 30214, -1, 30214, 27333, 27334, -1, 30222, 27332, 30218, -1, 30218, 27332, 27333, -1, 30225, 27326, 30222, -1, 30222, 27326, 27332, -1, 30228, 27325, 30225, -1, 30225, 27325, 27326, -1, 30229, 27323, 30228, -1, 30228, 27323, 27325, -1, 30230, 27324, 30229, -1, 30229, 27324, 27323, -1, 29096, 27250, 30230, -1, 30230, 27250, 27324, -1, 29096, 27251, 27250, -1, 29096, 29089, 27251, -1, 29087, 27583, 29089, -1, 29089, 27583, 27251, -1, 29086, 27585, 29087, -1, 29087, 27585, 27583, -1, 29088, 27587, 29086, -1, 29086, 27587, 27585, -1, 29088, 27589, 27587, -1, 29090, 27591, 29088, -1, 29088, 27591, 27589, -1, 29091, 27139, 29090, -1, 29090, 27139, 27591, -1, 29092, 27140, 29091, -1, 29091, 27140, 27139, -1, 29093, 27144, 29092, -1, 29092, 27144, 27140, -1, 29094, 27146, 29093, -1, 29093, 27146, 27144, -1, 29094, 27470, 27146, -1, 29094, 29102, 27470, -1, 26121, 26122, 31418, -1, 31418, 26122, 28855, -1, 28855, 31419, 31420, -1, 31420, 31421, 28855, -1, 28855, 31422, 31419, -1, 31421, 29636, 28855, -1, 28855, 31423, 31422, -1, 28855, 31424, 31423, -1, 28855, 31425, 31424, -1, 28855, 29626, 31425, -1, 28855, 29076, 29626, -1, 29636, 28880, 28855, -1, 26122, 29076, 28855, -1, 29514, 26145, 26147, -1, 29514, 26148, 26145, -1, 29514, 26149, 26148, -1, 26171, 26134, 29051, -1, 29051, 26134, 31426, -1, 31426, 26136, 31427, -1, 26134, 26136, 31426, -1, 31427, 26151, 31428, -1, 26136, 26151, 31427, -1, 31429, 26152, 28779, -1, 31428, 26152, 31429, -1, 26151, 26152, 31428, -1, 26152, 26153, 28779, -1, 31426, 30593, 29051, -1, 29051, 30593, 29105, -1, 31427, 30591, 31426, -1, 31426, 30591, 30593, -1, 31427, 30589, 30591, -1, 31428, 30587, 31427, -1, 31427, 30587, 30589, -1, 31429, 30585, 31428, -1, 31428, 30585, 30587, -1, 28779, 30583, 31429, -1, 31429, 30583, 30585, -1, 28779, 28782, 30583, -1, 31430, 31431, 31432, -1, 31430, 31432, 31433, -1, 31434, 31398, 31397, -1, 31434, 31430, 31433, -1, 31434, 31397, 31430, -1, 31434, 31435, 31398, -1, 31434, 31433, 31435, -1, 31436, 31437, 31438, -1, 31436, 31438, 31439, -1, 31436, 31439, 31391, -1, 31440, 31397, 31395, -1, 31440, 31395, 31391, -1, 31440, 31391, 31439, -1, 31440, 31430, 31397, -1, 31440, 31431, 31430, -1, 31440, 31439, 31431, -1, 31441, 29426, 29427, -1, 31441, 31442, 31437, -1, 31441, 31436, 31394, -1, 31441, 29427, 31442, -1, 31441, 31437, 31436, -1, 31443, 31391, 31393, -1, 31443, 31393, 31394, -1, 31443, 31394, 31436, -1, 31443, 31436, 31391, -1, 31444, 31394, 31392, -1, 31444, 31392, 31396, -1, 31444, 29426, 31441, -1, 31444, 31441, 31394, -1, 31444, 31396, 29426, -1, 31399, 30264, 30265, -1, 29427, 29424, 31442, -1, 29425, 29426, 31396, -1, 31432, 31445, 29562, -1, 31432, 29562, 30262, -1, 31431, 31446, 31447, -1, 31431, 31447, 31445, -1, 31431, 31445, 31432, -1, 31433, 30262, 30264, -1, 31433, 31432, 30262, -1, 31435, 31399, 31398, -1, 31435, 31433, 30264, -1, 31435, 30264, 31399, -1, 31439, 31438, 31446, -1, 31439, 31446, 31431, -1, 31448, 29562, 31445, -1, 31448, 29564, 29562, -1, 31449, 31445, 31447, -1, 31449, 31448, 31445, -1, 31450, 31447, 31446, -1, 31450, 31449, 31447, -1, 31451, 31446, 31438, -1, 31451, 31450, 31446, -1, 31452, 31438, 31437, -1, 31452, 31451, 31438, -1, 31453, 31437, 31442, -1, 31453, 31452, 31437, -1, 29422, 31442, 29424, -1, 29422, 31453, 31442, -1, 31454, 31455, 31456, -1, 31454, 31456, 31457, -1, 31458, 31449, 31450, -1, 31458, 31459, 31449, -1, 31458, 31460, 31459, -1, 31458, 31457, 31460, -1, 31461, 29417, 29414, -1, 31461, 31462, 31463, -1, 31461, 31463, 31464, -1, 31461, 29414, 31462, -1, 31465, 31464, 31455, -1, 31465, 31455, 31454, -1, 31466, 31450, 31451, -1, 31466, 31458, 31450, -1, 31466, 31454, 31457, -1, 31466, 31457, 31458, -1, 31467, 29421, 29417, -1, 31467, 29417, 31461, -1, 31467, 31461, 31464, -1, 31467, 31464, 31465, -1, 31468, 31451, 31452, -1, 31468, 31466, 31451, -1, 31468, 31465, 31454, -1, 31468, 31454, 31466, -1, 31469, 31453, 29422, -1, 31469, 31452, 31453, -1, 31469, 29422, 29421, -1, 31469, 29421, 31467, -1, 31469, 31468, 31452, -1, 31448, 30256, 29564, -1, 31469, 31467, 31465, -1, 31469, 31465, 31468, -1, 29414, 29379, 31462, -1, 31470, 31471, 29565, -1, 31470, 29565, 30260, -1, 31472, 31473, 31471, -1, 31472, 31471, 31470, -1, 31474, 30260, 30258, -1, 31474, 31470, 30260, -1, 31456, 31475, 31473, -1, 31456, 31473, 31472, -1, 31460, 31472, 31470, -1, 31460, 31470, 31474, -1, 31476, 30258, 30256, -1, 31476, 31474, 30258, -1, 31476, 30256, 31448, -1, 31455, 31477, 31475, -1, 31455, 31475, 31456, -1, 31457, 31456, 31472, -1, 31457, 31472, 31460, -1, 31459, 31448, 31449, -1, 31459, 31460, 31474, -1, 31459, 31476, 31448, -1, 31459, 31474, 31476, -1, 31464, 31463, 31477, -1, 31464, 31477, 31455, -1, 29568, 29565, 31471, -1, 31478, 31471, 31473, -1, 31478, 29568, 31471, -1, 31479, 31473, 31475, -1, 31479, 31478, 31473, -1, 31480, 31475, 31477, -1, 31480, 31479, 31475, -1, 31481, 31477, 31463, -1, 31481, 31480, 31477, -1, 31482, 31463, 31462, -1, 31482, 31481, 31463, -1, 31483, 31462, 29379, -1, 31483, 31482, 31462, -1, 29373, 31483, 29379, -1, 31484, 29372, 29374, -1, 31484, 29374, 29366, -1, 31484, 29366, 31485, -1, 31484, 31486, 29372, -1, 31487, 31479, 31480, -1, 31487, 31480, 31488, -1, 31489, 31488, 31490, -1, 31489, 31490, 31491, -1, 31492, 31493, 31494, -1, 31492, 31491, 31493, -1, 31495, 31485, 31496, -1, 31495, 31494, 31486, -1, 31495, 31486, 31484, -1, 31495, 31484, 31485, -1, 31497, 31478, 31479, -1, 31497, 29568, 31478, -1, 31497, 30274, 29568, -1, 31497, 31479, 31487, -1, 31498, 31488, 31489, -1, 31498, 31487, 31488, -1, 31499, 31489, 31491, -1, 31499, 31491, 31492, -1, 31500, 31496, 31501, -1, 31500, 31492, 31494, -1, 31500, 31495, 31496, -1, 31500, 31494, 31495, -1, 31502, 30277, 30274, -1, 31502, 30274, 31497, -1, 31502, 31497, 31487, -1, 31502, 31487, 31498, -1, 31503, 31498, 31489, -1, 31503, 31489, 31499, -1, 31504, 31501, 31505, -1, 31504, 31492, 31500, -1, 31504, 31500, 31501, -1, 31504, 31499, 31492, -1, 31506, 30279, 30277, -1, 31506, 31498, 31503, -1, 31506, 30277, 31502, -1, 31506, 31502, 31498, -1, 31507, 31503, 31499, -1, 31507, 31505, 31508, -1, 31507, 31504, 31505, -1, 31507, 31499, 31504, -1, 31509, 31506, 31503, -1, 31509, 31508, 31510, -1, 31509, 30281, 30279, -1, 31509, 30279, 31506, -1, 31509, 31503, 31507, -1, 31509, 31510, 30281, -1, 31509, 31507, 31508, -1, 29556, 30281, 31510, -1, 31511, 31483, 29373, -1, 31511, 29373, 29384, -1, 31512, 31482, 31483, -1, 31512, 31483, 31511, -1, 31513, 29384, 29383, -1, 31513, 31511, 29384, -1, 31490, 31481, 31482, -1, 31490, 31482, 31512, -1, 31493, 31511, 31513, -1, 31493, 31512, 31511, -1, 31486, 29383, 29372, -1, 31486, 31513, 29383, -1, 31488, 31480, 31481, -1, 31488, 31481, 31490, -1, 31491, 31490, 31512, -1, 31491, 31512, 31493, -1, 31494, 31493, 31513, -1, 31494, 31513, 31486, -1, 31485, 29366, 29365, -1, 31485, 29365, 31514, -1, 31485, 31514, 31515, -1, 31496, 31515, 31516, -1, 31496, 31485, 31515, -1, 31501, 31516, 31517, -1, 31501, 31496, 31516, -1, 31505, 31517, 31518, -1, 31505, 31501, 31517, -1, 31508, 31518, 31519, -1, 31508, 31505, 31518, -1, 31510, 31519, 29557, -1, 31510, 31508, 31519, -1, 29556, 31510, 29557, -1, 31520, 31521, 31522, -1, 31523, 31524, 31525, -1, 31523, 31526, 31524, -1, 31523, 31527, 31528, -1, 31529, 31530, 31531, -1, 31529, 31531, 31532, -1, 31523, 31528, 31526, -1, 31533, 29670, 29671, -1, 31533, 31534, 31521, -1, 31533, 29671, 31534, -1, 31535, 31536, 31537, -1, 31533, 31521, 31520, -1, 31535, 31532, 31536, -1, 31538, 31525, 31539, -1, 31538, 31523, 31525, -1, 31538, 31527, 31523, -1, 31540, 29385, 29380, -1, 31538, 31520, 31527, -1, 31541, 31539, 31542, -1, 31541, 29669, 29670, -1, 31540, 31537, 29385, -1, 31541, 29670, 31533, -1, 31541, 31538, 31539, -1, 31541, 31533, 31520, -1, 31543, 31518, 31517, -1, 31541, 31520, 31538, -1, 31541, 31542, 29669, -1, 31543, 31517, 31544, -1, 31545, 31530, 31529, -1, 31545, 31544, 31530, -1, 31546, 31532, 31535, -1, 31546, 31529, 31532, -1, 31547, 31535, 31537, -1, 31547, 31537, 31540, -1, 31548, 31519, 31518, -1, 29674, 29557, 31519, -1, 31548, 29674, 31519, -1, 31548, 31518, 31543, -1, 31549, 29380, 29382, -1, 31549, 31540, 29380, -1, 31550, 31543, 31544, -1, 31550, 31544, 31545, -1, 31551, 29368, 29370, -1, 31552, 31545, 31529, -1, 31552, 31529, 31546, -1, 31553, 31535, 31547, -1, 31553, 31546, 31535, -1, 31554, 31547, 31540, -1, 31554, 31540, 31549, -1, 31555, 29673, 29674, -1, 31555, 31543, 31550, -1, 31555, 29674, 31548, -1, 31555, 31548, 31543, -1, 31556, 29382, 29368, -1, 31556, 29368, 31551, -1, 31556, 31549, 29382, -1, 31557, 31550, 31545, -1, 31557, 31545, 31552, -1, 31522, 31552, 31546, -1, 29554, 29669, 31542, -1, 31558, 31514, 29365, -1, 31522, 31546, 31553, -1, 31558, 29365, 29397, -1, 31528, 31547, 31554, -1, 31531, 31515, 31514, -1, 31528, 31553, 31547, -1, 31559, 31551, 31560, -1, 31559, 31556, 31551, -1, 31559, 31549, 31556, -1, 31559, 31554, 31549, -1, 31531, 31514, 31558, -1, 31561, 31555, 31550, -1, 31536, 29397, 29387, -1, 31561, 29672, 29673, -1, 31561, 31550, 31557, -1, 31561, 29673, 31555, -1, 31536, 31558, 29397, -1, 31521, 31552, 31522, -1, 31521, 31557, 31552, -1, 31530, 31516, 31515, -1, 31527, 31522, 31553, -1, 31530, 31515, 31531, -1, 31532, 31558, 31536, -1, 31527, 31553, 31528, -1, 31526, 31560, 31524, -1, 31526, 31554, 31559, -1, 31532, 31531, 31558, -1, 31526, 31528, 31554, -1, 31537, 29387, 29385, -1, 31526, 31559, 31560, -1, 31534, 31561, 31557, -1, 31534, 31557, 31521, -1, 31534, 29671, 29672, -1, 31534, 29672, 31561, -1, 31537, 31536, 29387, -1, 31544, 31517, 31516, -1, 31520, 31522, 31527, -1, 31544, 31516, 31530, -1, 31551, 29370, 29398, -1, 31551, 29398, 31562, -1, 31560, 31562, 31563, -1, 31560, 31551, 31562, -1, 31524, 31563, 31564, -1, 31524, 31560, 31563, -1, 31525, 31564, 31565, -1, 31525, 31524, 31564, -1, 31539, 31565, 31566, -1, 31539, 31525, 31565, -1, 31542, 31566, 31567, -1, 31542, 31539, 31566, -1, 29554, 31567, 29552, -1, 29554, 31542, 31567, -1, 31568, 31569, 31570, -1, 31568, 31570, 31571, -1, 31572, 31573, 31574, -1, 31572, 31574, 31575, -1, 31572, 31576, 31577, -1, 31572, 31571, 31576, -1, 31572, 31577, 31573, -1, 31578, 31567, 31566, -1, 31578, 31566, 31579, -1, 31578, 29690, 31567, -1, 31580, 31569, 31568, -1, 31580, 31579, 31569, -1, 31581, 31572, 31575, -1, 31581, 31568, 31571, -1, 31581, 31571, 31572, -1, 31582, 29688, 29690, -1, 31582, 29690, 31578, -1, 31582, 31578, 31579, -1, 31582, 31579, 31580, -1, 31583, 31575, 31584, -1, 31583, 31581, 31575, -1, 31583, 31580, 31568, -1, 31583, 31568, 31581, -1, 31585, 31584, 31586, -1, 31585, 31586, 29548, -1, 31585, 29548, 29686, -1, 31585, 29686, 29688, -1, 31585, 29688, 31582, -1, 31585, 31583, 31584, -1, 31585, 31582, 31580, -1, 31585, 31580, 31583, -1, 29690, 29552, 31567, -1, 31587, 31562, 29398, -1, 31587, 29398, 29400, -1, 31588, 31563, 31562, -1, 31588, 31562, 31587, -1, 31589, 29400, 29401, -1, 31589, 31587, 29400, -1, 31570, 31564, 31563, -1, 31570, 31563, 31588, -1, 31576, 31587, 31589, -1, 31576, 31588, 31587, -1, 31590, 29401, 29402, -1, 31590, 29402, 29403, -1, 31590, 29403, 31591, -1, 31590, 31589, 29401, -1, 31569, 31565, 31564, -1, 31569, 31564, 31570, -1, 31571, 31570, 31588, -1, 31571, 31588, 31576, -1, 31577, 31591, 31573, -1, 31577, 31576, 31589, -1, 31577, 31590, 31591, -1, 31577, 31589, 31590, -1, 31579, 31566, 31565, -1, 31579, 31565, 31569, -1, 29403, 29394, 31592, -1, 31591, 31592, 31593, -1, 31591, 29403, 31592, -1, 31573, 31593, 31594, -1, 31573, 31591, 31593, -1, 31574, 31595, 31596, -1, 31574, 31594, 31595, -1, 31574, 31573, 31594, -1, 31575, 31596, 31597, -1, 31575, 31574, 31596, -1, 31584, 31575, 31597, -1, 31586, 31597, 29549, -1, 31586, 31584, 31597, -1, 29548, 31586, 29549, -1, 31598, 26129, 26130, -1, 29389, 26130, 29394, -1, 29389, 31598, 26130, -1, 29392, 29393, 31599, -1, 29392, 31599, 31600, -1, 29392, 31600, 29435, -1, 29392, 29435, 30646, -1, 26123, 30650, 26126, -1, 31598, 29388, 26129, -1, 29389, 29388, 31598, -1, 31601, 29392, 30646, -1, 31602, 29391, 29392, -1, 31602, 29392, 31601, -1, 31603, 30646, 30648, -1, 31603, 31601, 30646, -1, 31604, 29390, 29391, -1, 31604, 31602, 31601, -1, 31604, 29391, 31602, -1, 31604, 31601, 31603, -1, 31604, 31603, 30648, -1, 31605, 30648, 30650, -1, 31605, 30650, 26123, -1, 31606, 26123, 26127, -1, 31606, 31604, 30648, -1, 31606, 31605, 26123, -1, 31606, 30648, 31605, -1, 31607, 29388, 29390, -1, 31607, 26127, 26129, -1, 31607, 29390, 31604, -1, 31607, 31604, 31606, -1, 31607, 31606, 26127, -1, 31607, 26129, 29388, -1, 29393, 29396, 31608, -1, 31599, 29393, 31608, -1, 31600, 31608, 31609, -1, 31600, 31599, 31608, -1, 29435, 31609, 29433, -1, 29435, 31600, 31609, -1, 31610, 31608, 29396, -1, 31610, 29396, 29679, -1, 31611, 31609, 31608, -1, 31611, 29433, 31609, -1, 31611, 31608, 31610, -1, 29434, 29433, 31611, -1, 29676, 29571, 29683, -1, 29678, 29683, 29681, -1, 29678, 29676, 29683, -1, 31611, 29681, 29434, -1, 31610, 29678, 29681, -1, 31610, 29681, 31611, -1, 29679, 29678, 31610, -1, 29053, 29052, 31612, -1, 31612, 31613, 31614, -1, 29052, 31613, 31612, -1, 31613, 31615, 31614, -1, 31614, 29574, 29576, -1, 31615, 29574, 31614, -1, 31109, 31616, 31108, -1, 29107, 31616, 31109, -1, 31616, 31107, 31108, -1, 31616, 31617, 31107, -1, 31105, 31613, 29052, -1, 31106, 31613, 31105, -1, 31107, 31613, 31106, -1, 31617, 31613, 31107, -1, 31618, 29578, 31617, -1, 29577, 29578, 31618, -1, 29578, 31615, 31617, -1, 31617, 31615, 31613, -1, 29578, 29579, 31615, -1, 29579, 29574, 31615, -1, 29107, 29106, 31616, -1, 31616, 31619, 31617, -1, 29106, 31619, 31616, -1, 31617, 31620, 31618, -1, 31619, 31620, 31617, -1, 31618, 31621, 29577, -1, 31620, 31621, 31618, -1, 31621, 29580, 29577, -1, 29106, 30592, 31619, -1, 31621, 31622, 29580, -1, 30590, 31623, 30592, -1, 31619, 31624, 31620, -1, 31620, 31624, 31621, -1, 30592, 31624, 31619, -1, 31621, 31624, 31622, -1, 31623, 31624, 30592, -1, 30590, 31624, 31623, -1, 31622, 31625, 31626, -1, 31626, 31625, 31624, -1, 31624, 31625, 31622, -1, 30588, 31627, 30590, -1, 30586, 31627, 30588, -1, 30590, 31627, 31624, -1, 31628, 31629, 31630, -1, 31626, 31629, 31628, -1, 31624, 31629, 31626, -1, 31627, 31629, 31624, -1, 30584, 31631, 30586, -1, 30586, 31631, 31627, -1, 31631, 31632, 31627, -1, 31627, 31632, 31629, -1, 30584, 31632, 31631, -1, 31630, 31633, 31634, -1, 31634, 31633, 31632, -1, 31629, 31633, 31630, -1, 31632, 31633, 31629, -1, 30582, 31635, 30584, -1, 28789, 31635, 30582, -1, 30584, 31635, 31632, -1, 31636, 31637, 28789, -1, 31634, 31637, 31636, -1, 31632, 31637, 31634, -1, 28789, 31637, 31635, -1, 31635, 31637, 31632, -1, 28804, 31638, 28789, -1, 28789, 31638, 31636, -1, 31636, 31639, 31634, -1, 31638, 31639, 31636, -1, 31634, 31640, 31630, -1, 31639, 31640, 31634, -1, 31630, 31641, 31628, -1, 31640, 31641, 31630, -1, 31628, 31642, 31626, -1, 31641, 31642, 31628, -1, 31626, 31643, 31622, -1, 31642, 31643, 31626, -1, 31622, 29581, 29580, -1, 31643, 29581, 31622, -1, 31644, 31645, 31646, -1, 31647, 31648, 31649, -1, 31650, 31648, 31647, -1, 31651, 31648, 31650, -1, 31646, 31648, 31651, -1, 28809, 31652, 28804, -1, 28804, 31652, 31638, -1, 31638, 31652, 31639, -1, 31639, 31652, 31653, -1, 31653, 31654, 31655, -1, 31655, 31654, 31645, -1, 31649, 31656, 31657, -1, 31648, 31656, 31649, -1, 31645, 31656, 31646, -1, 31646, 31656, 31648, -1, 28810, 31658, 28809, -1, 28809, 31658, 31652, -1, 31653, 31658, 31654, -1, 31652, 31658, 31653, -1, 31657, 31659, 31660, -1, 31656, 31659, 31657, -1, 31654, 31659, 31645, -1, 31645, 31659, 31656, -1, 31660, 31661, 31662, -1, 28811, 31661, 28810, -1, 28810, 31661, 31658, -1, 31662, 31661, 28811, -1, 31659, 31661, 31660, -1, 31658, 31661, 31654, -1, 31654, 31661, 31659, -1, 28811, 28792, 31662, -1, 29581, 31663, 29696, -1, 31643, 31663, 29581, -1, 31642, 31664, 31643, -1, 31643, 31664, 31663, -1, 29694, 31665, 29692, -1, 29696, 31665, 29694, -1, 31663, 31665, 29696, -1, 31640, 31644, 31641, -1, 31641, 31644, 31642, -1, 31642, 31644, 31664, -1, 31664, 31651, 31663, -1, 31663, 31651, 31665, -1, 29692, 31666, 29637, -1, 29637, 31666, 31667, -1, 31665, 31666, 29692, -1, 31640, 31655, 31644, -1, 31644, 31646, 31664, -1, 31664, 31646, 31651, -1, 31667, 31650, 31647, -1, 31666, 31650, 31667, -1, 31651, 31650, 31665, -1, 31665, 31650, 31666, -1, 31639, 31653, 31640, -1, 31640, 31653, 31655, -1, 31655, 31645, 31644, -1, 28791, 31668, 28792, -1, 28792, 31668, 31662, -1, 31662, 31669, 31660, -1, 31668, 31669, 31662, -1, 31660, 31670, 31657, -1, 31669, 31670, 31660, -1, 31657, 31671, 31649, -1, 31670, 31671, 31657, -1, 31649, 31672, 31647, -1, 31671, 31672, 31649, -1, 31647, 31673, 31667, -1, 31672, 31673, 31647, -1, 31667, 29640, 29637, -1, 31673, 29640, 31667, -1, 31671, 31674, 31675, -1, 31676, 31677, 31678, -1, 31679, 31677, 31676, -1, 31675, 31680, 31681, -1, 31682, 31677, 31683, -1, 31681, 31680, 31684, -1, 31683, 31677, 31679, -1, 28797, 31685, 28805, -1, 28805, 31685, 31686, -1, 31686, 31685, 31687, -1, 31687, 31685, 31688, -1, 31684, 31689, 31690, -1, 31690, 31689, 31691, -1, 31678, 31692, 31693, -1, 31677, 31692, 31678, -1, 31688, 31692, 31682, -1, 31682, 31692, 31677, -1, 31694, 31695, 28784, -1, 31693, 31695, 31694, -1, 31691, 31696, 29648, -1, 28784, 31695, 28797, -1, 31688, 31695, 31692, -1, 31692, 31695, 31693, -1, 31685, 31695, 31688, -1, 28797, 31695, 31685, -1, 31669, 31697, 31670, -1, 31670, 31697, 31674, -1, 31674, 31698, 31675, -1, 31675, 31698, 31680, -1, 31680, 31699, 31684, -1, 31684, 31699, 31689, -1, 31689, 31700, 31691, -1, 31691, 31700, 31696, -1, 28801, 31701, 28799, -1, 31668, 31701, 31669, -1, 28791, 28799, 31668, -1, 28799, 31701, 31668, -1, 31669, 31701, 31697, -1, 29648, 31702, 29650, -1, 31696, 31702, 29648, -1, 31674, 31703, 31698, -1, 31697, 31703, 31674, -1, 31680, 31704, 31699, -1, 31698, 31704, 31680, -1, 31699, 31705, 31689, -1, 31689, 31705, 31700, -1, 31700, 31706, 31696, -1, 31696, 31706, 31702, -1, 31697, 31707, 31703, -1, 28807, 31707, 28801, -1, 28801, 31707, 31701, -1, 31701, 31707, 31697, -1, 29652, 31708, 29653, -1, 29650, 31708, 29652, -1, 29653, 31708, 31709, -1, 31702, 31708, 29650, -1, 31703, 31710, 31698, -1, 31698, 31710, 31704, -1, 31704, 31711, 31699, -1, 31699, 31711, 31705, -1, 29640, 31712, 29642, -1, 31700, 31683, 31706, -1, 31705, 31683, 31700, -1, 31673, 31712, 29640, -1, 31706, 31713, 31702, -1, 31709, 31713, 31714, -1, 31672, 31681, 31673, -1, 31702, 31713, 31708, -1, 31708, 31713, 31709, -1, 31673, 31681, 31712, -1, 31703, 31715, 31710, -1, 28806, 31715, 28807, -1, 31707, 31715, 31703, -1, 29642, 31690, 29644, -1, 28807, 31715, 31707, -1, 31712, 31690, 29642, -1, 31710, 31687, 31704, -1, 31704, 31687, 31711, -1, 31671, 31675, 31672, -1, 31672, 31675, 31681, -1, 31711, 31682, 31705, -1, 31712, 31684, 31690, -1, 31705, 31682, 31683, -1, 31683, 31679, 31706, -1, 31681, 31684, 31712, -1, 31714, 31679, 31676, -1, 31713, 31679, 31714, -1, 29646, 31691, 29648, -1, 31706, 31679, 31713, -1, 29644, 31691, 29646, -1, 28805, 31686, 28806, -1, 31715, 31686, 31710, -1, 31690, 31691, 29644, -1, 28806, 31686, 31715, -1, 31710, 31686, 31687, -1, 31711, 31688, 31682, -1, 31670, 31674, 31671, -1, 31687, 31688, 31711, -1, 28784, 28772, 31694, -1, 31694, 31716, 31693, -1, 28772, 31716, 31694, -1, 31693, 31717, 31678, -1, 31716, 31717, 31693, -1, 31678, 31718, 31676, -1, 31717, 31718, 31678, -1, 31676, 31719, 31714, -1, 31718, 31719, 31676, -1, 31714, 31720, 31709, -1, 31719, 31720, 31714, -1, 31709, 31721, 29653, -1, 31720, 31721, 31709, -1, 31721, 29655, 29653, -1, 28897, 28902, 29129, -1, 29129, 31722, 29128, -1, 28902, 31722, 29129, -1, 29128, 31723, 29127, -1, 31722, 31723, 29128, -1, 29127, 31724, 29124, -1, 31723, 31724, 29127, -1, 29124, 31725, 29122, -1, 31724, 31725, 29124, -1, 29122, 31726, 29120, -1, 31725, 31726, 29122, -1, 29120, 31727, 28777, -1, 31726, 31727, 29120, -1, 31727, 28776, 28777, -1, 30282, 31728, 31729, -1, 31730, 31728, 30285, -1, 31717, 31731, 31718, -1, 31718, 31731, 31732, -1, 31732, 31733, 31734, -1, 31734, 31733, 31735, -1, 31735, 31736, 31737, -1, 31737, 31736, 31738, -1, 31739, 31740, 31741, -1, 31730, 31740, 31728, -1, 31738, 31740, 31730, -1, 31728, 31740, 31739, -1, 28774, 31742, 28772, -1, 28772, 31742, 31716, -1, 31716, 31742, 31717, -1, 31717, 31742, 31731, -1, 31732, 31743, 31733, -1, 31731, 31743, 31732, -1, 31735, 31744, 31736, -1, 30282, 31729, 29634, -1, 31733, 31744, 31735, -1, 31741, 31745, 31746, -1, 31740, 31745, 31741, -1, 31736, 31745, 31738, -1, 31738, 31745, 31740, -1, 28767, 31747, 28774, -1, 28774, 31747, 31742, -1, 31742, 31747, 31731, -1, 31731, 31747, 31743, -1, 31743, 31748, 31733, -1, 31733, 31748, 31744, -1, 31746, 31749, 31750, -1, 31745, 31749, 31746, -1, 31744, 31749, 31736, -1, 31736, 31749, 31745, -1, 31747, 31751, 31743, -1, 28766, 31751, 28767, -1, 28767, 31751, 31747, -1, 31743, 31751, 31748, -1, 31748, 31752, 31744, -1, 31749, 31752, 31750, -1, 31744, 31752, 31749, -1, 31753, 31754, 28769, -1, 31750, 31754, 31753, -1, 31751, 31754, 31748, -1, 28768, 31754, 28766, -1, 28769, 31754, 28768, -1, 31748, 31754, 31752, -1, 28766, 31754, 31751, -1, 31752, 31754, 31750, -1, 29655, 31755, 30289, -1, 31721, 31755, 29655, -1, 31720, 31756, 31721, -1, 31721, 31756, 31755, -1, 30289, 31757, 30287, -1, 31755, 31757, 30289, -1, 31719, 31734, 31720, -1, 31720, 31734, 31756, -1, 31755, 31737, 31757, -1, 31756, 31737, 31755, -1, 30287, 31730, 30285, -1, 31757, 31730, 30287, -1, 31718, 31732, 31719, -1, 31719, 31732, 31734, -1, 31734, 31735, 31756, -1, 31756, 31735, 31737, -1, 31737, 31738, 31757, -1, 31757, 31738, 31730, -1, 30285, 31728, 30282, -1, 31729, 31728, 31739, -1, 28776, 31727, 28769, -1, 28769, 31727, 31753, -1, 31753, 31726, 31750, -1, 31727, 31726, 31753, -1, 31750, 31725, 31746, -1, 31726, 31725, 31750, -1, 31746, 31724, 31741, -1, 31725, 31724, 31746, -1, 31741, 31723, 31739, -1, 31724, 31723, 31741, -1, 31739, 31722, 31729, -1, 31729, 31722, 29634, -1, 31723, 31722, 31739, -1, 31722, 28902, 29634, -1, 31406, 29068, 29070, -1, 31406, 29070, 31758, -1, 31405, 31406, 31758, -1, 31404, 31758, 31759, -1, 31404, 31405, 31758, -1, 31403, 31404, 31759, -1, 31402, 31759, 31760, -1, 31402, 31403, 31759, -1, 31401, 31760, 31761, -1, 31401, 31402, 31760, -1, 31400, 31761, 31762, -1, 31400, 31401, 31761, -1, 31407, 31762, 31763, -1, 31407, 31400, 31762, -1, 29633, 31763, 29585, -1, 29633, 31407, 31763, -1, 31764, 31765, 30263, -1, 31764, 30261, 31766, -1, 31764, 31767, 31765, -1, 31768, 31769, 31770, -1, 31768, 31770, 31771, -1, 29586, 31772, 29582, -1, 31773, 31769, 31768, -1, 31773, 31774, 31769, -1, 31775, 29591, 29594, -1, 31775, 29594, 29588, -1, 31775, 31776, 29591, -1, 31777, 31765, 31774, -1, 31777, 30263, 31765, -1, 31777, 31774, 31773, -1, 31778, 31771, 31776, -1, 31778, 31776, 31775, -1, 31779, 30266, 30263, -1, 31779, 30263, 31777, -1, 31780, 31771, 31778, -1, 31780, 31768, 31771, -1, 30261, 29561, 31766, -1, 31781, 29588, 29587, -1, 31781, 31775, 29588, -1, 31782, 31773, 31768, -1, 31782, 31768, 31780, -1, 31783, 31778, 31775, -1, 31783, 31775, 31781, -1, 31784, 31773, 31782, -1, 31784, 31777, 31773, -1, 31785, 31780, 31778, -1, 31785, 31778, 31783, -1, 31786, 31777, 31784, -1, 31786, 30268, 30266, -1, 31786, 30266, 31779, -1, 31786, 31779, 31777, -1, 31763, 29584, 29585, -1, 31787, 29587, 29584, -1, 31787, 31781, 29587, -1, 31762, 29584, 31763, -1, 31788, 31782, 31780, -1, 31788, 31780, 31785, -1, 31789, 31783, 31781, -1, 31789, 31787, 29584, -1, 31789, 29584, 31762, -1, 31789, 31781, 31787, -1, 31790, 31782, 31788, -1, 31758, 30272, 31759, -1, 31790, 31784, 31782, -1, 31791, 31785, 31783, -1, 29070, 30272, 31758, -1, 31791, 31762, 31761, -1, 31791, 31789, 31762, -1, 31791, 31783, 31789, -1, 31792, 29586, 29591, -1, 31792, 31772, 29586, -1, 31793, 31786, 31784, -1, 31793, 30269, 30268, -1, 31793, 30268, 31786, -1, 31793, 31784, 31790, -1, 31770, 31794, 31772, -1, 31795, 31761, 31760, -1, 31770, 31772, 31792, -1, 31795, 31788, 31785, -1, 31795, 31785, 31791, -1, 31795, 31791, 31761, -1, 31769, 31796, 31794, -1, 31797, 31760, 31759, -1, 31769, 31794, 31770, -1, 31797, 31788, 31795, -1, 31797, 31790, 31788, -1, 31797, 31795, 31760, -1, 31797, 31759, 30272, -1, 31774, 31798, 31796, -1, 31799, 30272, 30269, -1, 31799, 30269, 31793, -1, 31799, 31793, 31790, -1, 31799, 31797, 30272, -1, 31774, 31796, 31769, -1, 31799, 31790, 31797, -1, 31776, 31792, 29591, -1, 31765, 31767, 31798, -1, 31765, 31798, 31774, -1, 31771, 31770, 31792, -1, 31771, 31792, 31776, -1, 31764, 30263, 30261, -1, 31764, 31766, 31767, -1, 29583, 29582, 31772, -1, 31800, 31772, 31794, -1, 31800, 29583, 31772, -1, 31801, 31794, 31796, -1, 31801, 31800, 31794, -1, 31802, 31801, 31796, -1, 31803, 31796, 31798, -1, 31803, 31802, 31796, -1, 31804, 31798, 31767, -1, 31804, 31803, 31798, -1, 31805, 31767, 31766, -1, 31805, 31804, 31767, -1, 29563, 31766, 29561, -1, 29563, 31805, 31766, -1, 31806, 31807, 31808, -1, 31806, 31808, 31809, -1, 31806, 31809, 31801, -1, 31810, 30259, 29567, -1, 31810, 29567, 31811, -1, 31810, 31811, 31812, -1, 29631, 31813, 29620, -1, 31814, 31812, 31815, -1, 31814, 31815, 31816, -1, 31817, 31802, 31803, -1, 31817, 31807, 31806, -1, 31817, 31806, 31802, -1, 31817, 31816, 31807, -1, 31818, 30257, 30259, -1, 31818, 30259, 31810, -1, 31818, 31810, 31812, -1, 31818, 31812, 31814, -1, 31819, 31803, 31804, -1, 31819, 31817, 31803, -1, 31819, 31814, 31816, -1, 31819, 31816, 31817, -1, 31820, 31805, 29563, -1, 31820, 31804, 31805, -1, 31820, 29563, 30255, -1, 31820, 30255, 30257, -1, 31820, 30257, 31818, -1, 31820, 31819, 31804, -1, 31820, 31818, 31814, -1, 31820, 31814, 31819, -1, 31800, 29632, 29583, -1, 31821, 31822, 31813, -1, 31821, 29631, 29630, -1, 31821, 31813, 29631, -1, 31823, 31824, 31822, -1, 31823, 31822, 31821, -1, 31825, 29630, 29632, -1, 31825, 31821, 29630, -1, 31826, 31827, 31824, -1, 31826, 31824, 31823, -1, 31808, 31823, 31821, -1, 31808, 31821, 31825, -1, 31828, 31825, 29632, -1, 31828, 29632, 31800, -1, 31815, 31829, 31827, -1, 31815, 31827, 31826, -1, 31807, 31826, 31823, -1, 31807, 31823, 31808, -1, 31809, 31800, 31801, -1, 31809, 31808, 31825, -1, 31809, 31825, 31828, -1, 31809, 31828, 31800, -1, 31812, 31811, 31829, -1, 31812, 31829, 31815, -1, 31816, 31815, 31826, -1, 31816, 31826, 31807, -1, 31806, 31801, 31802, -1, 29614, 29620, 31813, -1, 31830, 31813, 31822, -1, 31830, 29614, 31813, -1, 31831, 31822, 31824, -1, 31831, 31830, 31822, -1, 31832, 31824, 31827, -1, 31832, 31831, 31824, -1, 31833, 31827, 31829, -1, 31833, 31832, 31827, -1, 31834, 31829, 31811, -1, 31834, 31833, 31829, -1, 31835, 31811, 29567, -1, 31835, 31834, 31811, -1, 29566, 31835, 29567, -1, 31836, 30278, 30280, -1, 31836, 31837, 31838, -1, 31836, 30280, 31837, -1, 31836, 31839, 30278, -1, 31840, 31831, 31832, -1, 31840, 31832, 31841, -1, 31842, 31841, 31843, -1, 31842, 31843, 31844, -1, 31845, 31846, 31847, -1, 31845, 31844, 31846, -1, 31848, 31838, 31849, -1, 31848, 31847, 31839, -1, 31848, 31836, 31838, -1, 31848, 31839, 31836, -1, 31850, 31830, 31831, -1, 31850, 29624, 31830, -1, 31850, 31831, 31840, -1, 31851, 31840, 31841, -1, 31851, 31841, 31842, -1, 31852, 31842, 31844, -1, 31852, 31844, 31845, -1, 31837, 30280, 29559, -1, 31853, 31849, 31854, -1, 31853, 31848, 31849, -1, 31853, 31845, 31847, -1, 31853, 31847, 31848, -1, 31855, 29621, 29624, -1, 31855, 29624, 31850, -1, 31855, 31850, 31840, -1, 31855, 31840, 31851, -1, 31856, 31842, 31852, -1, 29624, 29614, 31830, -1, 31856, 31851, 31842, -1, 31857, 31854, 31858, -1, 31857, 31853, 31854, -1, 31857, 31852, 31845, -1, 31857, 31845, 31853, -1, 31859, 31855, 31851, -1, 31859, 29613, 29621, -1, 31859, 29621, 31855, -1, 31859, 31851, 31856, -1, 31860, 31856, 31852, -1, 31860, 31857, 31858, -1, 31860, 31858, 31861, -1, 31860, 31852, 31857, -1, 31862, 31859, 31856, -1, 31862, 31860, 31861, -1, 31862, 31861, 29605, -1, 31862, 29605, 29610, -1, 31862, 29610, 29613, -1, 31862, 29613, 31859, -1, 31862, 31856, 31860, -1, 31863, 31835, 29566, -1, 31863, 29566, 30275, -1, 31864, 31834, 31835, -1, 31864, 31835, 31863, -1, 31865, 30275, 30276, -1, 31865, 31863, 30275, -1, 31843, 31833, 31834, -1, 31843, 31834, 31864, -1, 31846, 31863, 31865, -1, 31846, 31864, 31863, -1, 31839, 30276, 30278, -1, 31839, 31865, 30276, -1, 31841, 31832, 31833, -1, 31841, 31833, 31843, -1, 31844, 31843, 31864, -1, 31844, 31864, 31846, -1, 31847, 31846, 31865, -1, 31847, 31865, 31839, -1, 29559, 29560, 31866, -1, 31837, 31866, 31867, -1, 31837, 29559, 31866, -1, 31838, 31867, 31868, -1, 31838, 31837, 31867, -1, 31849, 31868, 31869, -1, 31849, 31838, 31868, -1, 31854, 31869, 31870, -1, 31854, 31849, 31869, -1, 31858, 31870, 31871, -1, 31858, 31854, 31870, -1, 31861, 31871, 29599, -1, 31861, 31858, 31871, -1, 29605, 31861, 29599, -1, 31872, 31873, 31874, -1, 31872, 31875, 31873, -1, 31876, 31877, 31878, -1, 31879, 31880, 31881, -1, 31876, 31882, 31877, -1, 31879, 31881, 31883, -1, 31876, 31874, 31884, -1, 31876, 31884, 31882, -1, 31885, 29612, 31886, -1, 31885, 29609, 29612, -1, 31887, 31888, 31889, -1, 31885, 31875, 31872, -1, 31887, 31883, 31888, -1, 31885, 31886, 31875, -1, 31890, 31878, 31891, -1, 31890, 31876, 31878, -1, 31892, 29664, 29662, -1, 31890, 31872, 31874, -1, 31890, 31874, 31876, -1, 31893, 31891, 31894, -1, 31892, 31889, 29664, -1, 31893, 31894, 29604, -1, 31893, 29604, 29609, -1, 31895, 31870, 31869, -1, 31893, 31890, 31891, -1, 31893, 31872, 31890, -1, 31893, 29609, 31885, -1, 31893, 31885, 31872, -1, 31895, 31869, 31896, -1, 31897, 31880, 31879, -1, 31897, 31896, 31880, -1, 31898, 31879, 31883, -1, 31898, 31883, 31887, -1, 31899, 31889, 31892, -1, 31899, 31887, 31889, -1, 29628, 29599, 31871, -1, 31900, 31871, 31870, -1, 31900, 29625, 29628, -1, 31900, 29628, 31871, -1, 31900, 31870, 31895, -1, 31901, 29662, 29660, -1, 31901, 31892, 29662, -1, 31902, 31895, 31896, -1, 31902, 31896, 31897, -1, 31903, 31879, 31898, -1, 31903, 31897, 31879, -1, 31904, 31898, 31887, -1, 31904, 31887, 31899, -1, 31905, 31899, 31892, -1, 31905, 31892, 31901, -1, 31906, 29623, 29625, -1, 31906, 31895, 31902, -1, 31906, 29625, 31900, -1, 31906, 31900, 31895, -1, 31907, 29660, 29657, -1, 31907, 29657, 29555, -1, 31907, 29555, 31908, -1, 31907, 31901, 29660, -1, 31909, 31902, 31897, -1, 31909, 31897, 31903, -1, 31873, 31903, 31898, -1, 31910, 31866, 29560, -1, 31873, 31898, 31904, -1, 31910, 29560, 29668, -1, 31884, 31904, 31899, -1, 31881, 31867, 31866, -1, 31884, 31899, 31905, -1, 31911, 31905, 31901, -1, 31911, 31908, 31912, -1, 31911, 31907, 31908, -1, 31881, 31866, 31910, -1, 31911, 31901, 31907, -1, 31888, 29668, 29666, -1, 31913, 31906, 31902, -1, 31913, 29619, 29623, -1, 31913, 31902, 31909, -1, 31913, 29623, 31906, -1, 31888, 31910, 29668, -1, 31875, 31903, 31873, -1, 31875, 31909, 31903, -1, 31880, 31868, 31867, -1, 31880, 31867, 31881, -1, 31874, 31904, 31884, -1, 31883, 31910, 31888, -1, 31874, 31873, 31904, -1, 31882, 31911, 31912, -1, 31883, 31881, 31910, -1, 31882, 31905, 31911, -1, 31882, 31912, 31877, -1, 31889, 29666, 29664, -1, 31882, 31884, 31905, -1, 31886, 31909, 31875, -1, 31886, 29612, 29619, -1, 31886, 29619, 31913, -1, 31889, 31888, 29666, -1, 31896, 31869, 31868, -1, 31886, 31913, 31909, -1, 31896, 31868, 31880, -1, 29555, 29553, 31914, -1, 31908, 31914, 31915, -1, 31908, 29555, 31914, -1, 31912, 31915, 31916, -1, 31912, 31908, 31915, -1, 31877, 31916, 31917, -1, 31877, 31912, 31916, -1, 31878, 31917, 31918, -1, 31878, 31877, 31917, -1, 31891, 31918, 31919, -1, 31891, 31878, 31918, -1, 31894, 31919, 29603, -1, 31894, 31891, 31919, -1, 29604, 31894, 29603, -1, 31920, 31921, 31922, -1, 31920, 31922, 31923, -1, 31924, 31925, 31926, -1, 31924, 31923, 31927, -1, 31924, 31927, 31928, -1, 31924, 31928, 31925, -1, 31929, 31919, 31918, -1, 31929, 29603, 31919, -1, 31929, 29597, 29603, -1, 31929, 31918, 31930, -1, 31931, 31930, 31921, -1, 31931, 31921, 31920, -1, 31932, 31926, 31933, -1, 31932, 31923, 31924, -1, 31932, 31924, 31926, -1, 31932, 31920, 31923, -1, 31934, 29596, 29597, -1, 31934, 29597, 31929, -1, 31934, 31929, 31930, -1, 31934, 31930, 31931, -1, 31935, 31933, 31936, -1, 31935, 31932, 31933, -1, 31935, 31931, 31920, -1, 31935, 31920, 31932, -1, 31937, 31936, 31938, -1, 31937, 29593, 29596, -1, 31937, 29596, 31934, -1, 31937, 31935, 31936, -1, 31937, 31938, 29593, -1, 31937, 31934, 31931, -1, 31937, 31931, 31935, -1, 29590, 29593, 31938, -1, 31939, 31914, 29553, -1, 31939, 29553, 29689, -1, 31940, 31915, 31914, -1, 31940, 31914, 31939, -1, 31941, 29689, 29687, -1, 31941, 31939, 29689, -1, 31922, 31916, 31915, -1, 31922, 31915, 31940, -1, 31927, 31939, 31941, -1, 31927, 31940, 31939, -1, 31942, 29687, 29685, -1, 31942, 29685, 29545, -1, 31942, 29545, 31943, -1, 31942, 31941, 29687, -1, 31921, 31917, 31916, -1, 31921, 31916, 31922, -1, 31923, 31922, 31940, -1, 31923, 31940, 31927, -1, 31928, 31943, 31925, -1, 31928, 31927, 31941, -1, 31928, 31942, 31943, -1, 31928, 31941, 31942, -1, 31930, 31918, 31917, -1, 31930, 31917, 31921, -1, 29590, 31938, 28562, -1, 29545, 28601, 28600, -1, 31943, 28613, 28612, -1, 31943, 28626, 28613, -1, 31943, 28600, 28626, -1, 31943, 29545, 28600, -1, 31925, 28610, 28510, -1, 31925, 28611, 28610, -1, 31925, 28612, 28611, -1, 31925, 28509, 28580, -1, 31925, 28510, 28509, -1, 31925, 31943, 28612, -1, 31926, 28579, 28491, -1, 31926, 28580, 28579, -1, 31926, 31925, 28580, -1, 31933, 28490, 28533, -1, 31933, 28491, 28490, -1, 31933, 31926, 28491, -1, 31936, 28533, 28562, -1, 31936, 31933, 28533, -1, 31938, 31936, 28562, -1, 29590, 28562, 28588, -1, 27472, 27471, 31944, -1, 31944, 31945, 31946, -1, 27471, 31945, 31944, -1, 31946, 31947, 28263, -1, 31945, 31947, 31946, -1, 28263, 26116, 28264, -1, 31947, 26116, 28263, -1, 28264, 26118, 28256, -1, 26116, 26118, 28264, -1, 28256, 26121, 28257, -1, 26118, 26121, 28256, -1, 28257, 31418, 28250, -1, 26121, 31418, 28257, -1, 28250, 28855, 28249, -1, 31418, 28855, 28250, -1, 27470, 29102, 27471, -1, 27471, 29102, 31945, -1, 31945, 29103, 31947, -1, 29102, 29103, 31945, -1, 31947, 29104, 26116, -1, 29103, 29104, 31947, -1, 29104, 26117, 26116, -1, 31948, 28980, 28978, -1, 28979, 27702, 27700, -1, 28979, 27704, 27702, -1, 29491, 30670, 31949, -1, 28979, 27707, 27704, -1, 30668, 27715, 27712, -1, 30668, 27718, 27715, -1, 30668, 27541, 27718, -1, 28980, 31950, 28979, -1, 31948, 31950, 28980, -1, 31951, 31952, 31948, -1, 31948, 31952, 31950, -1, 31950, 31952, 28979, -1, 31953, 31954, 31951, -1, 31952, 31954, 28979, -1, 31951, 31954, 31952, -1, 28979, 31954, 27707, -1, 31955, 31956, 31953, -1, 27707, 31956, 27709, -1, 31953, 31956, 31954, -1, 31954, 31956, 27707, -1, 31957, 31958, 31955, -1, 27709, 31958, 27712, -1, 31955, 31958, 31956, -1, 31956, 31958, 27709, -1, 31959, 31960, 31957, -1, 31958, 31960, 27712, -1, 31957, 31960, 31958, -1, 27712, 31960, 30668, -1, 31961, 31962, 31959, -1, 31960, 31962, 30668, -1, 31959, 31962, 31960, -1, 30668, 31963, 30670, -1, 31949, 31963, 31961, -1, 31961, 31963, 31962, -1, 31962, 31963, 30668, -1, 30670, 31963, 31949, -1, 28978, 28998, 31948, -1, 31948, 31964, 31951, -1, 28998, 31964, 31948, -1, 31951, 31965, 31953, -1, 31964, 31965, 31951, -1, 31953, 31966, 31955, -1, 31965, 31966, 31953, -1, 31955, 31967, 31957, -1, 31966, 31967, 31955, -1, 31957, 31968, 31959, -1, 31967, 31968, 31957, -1, 31959, 31969, 31961, -1, 31968, 31969, 31959, -1, 31961, 31970, 31949, -1, 31969, 31970, 31961, -1, 31949, 31971, 29491, -1, 31970, 31971, 31949, -1, 31971, 29494, 29491, -1, 31972, 31973, 31974, -1, 31975, 31976, 31977, -1, 31977, 31976, 31978, -1, 29494, 31971, 30448, -1, 31966, 31979, 31967, -1, 31967, 31979, 31980, -1, 31980, 31981, 31972, -1, 31972, 31981, 31973, -1, 30454, 31982, 29496, -1, 29496, 31982, 31983, -1, 31978, 31982, 30454, -1, 31973, 31984, 31975, -1, 31975, 31984, 31976, -1, 31965, 31985, 31966, -1, 31966, 31985, 31979, -1, 31983, 31986, 31987, -1, 31976, 31986, 31978, -1, 31982, 31986, 31983, -1, 31978, 31986, 31982, -1, 31980, 31988, 31981, -1, 31979, 31988, 31980, -1, 31981, 31989, 31973, -1, 31973, 31989, 31984, -1, 28998, 29003, 31964, -1, 31987, 31990, 31991, -1, 31976, 31990, 31986, -1, 31984, 31990, 31976, -1, 31986, 31990, 31987, -1, 31964, 31992, 31965, -1, 31965, 31992, 31985, -1, 29003, 31992, 31964, -1, 31985, 31993, 31979, -1, 31979, 31993, 31988, -1, 31981, 31994, 31989, -1, 31988, 31994, 31981, -1, 31989, 31995, 31984, -1, 31991, 31995, 31996, -1, 31984, 31995, 31990, -1, 31990, 31995, 31991, -1, 31992, 31997, 31985, -1, 29005, 31997, 29003, -1, 29006, 31997, 29005, -1, 29003, 31997, 31992, -1, 31985, 31997, 31993, -1, 31993, 31998, 31988, -1, 31988, 31998, 31994, -1, 29011, 28929, 31999, -1, 30448, 32000, 30450, -1, 31994, 32001, 31989, -1, 31995, 32001, 31996, -1, 31989, 32001, 31995, -1, 31971, 32000, 30448, -1, 29009, 32002, 29006, -1, 29006, 32002, 31997, -1, 31993, 32002, 31998, -1, 31997, 32002, 31993, -1, 31970, 31974, 31971, -1, 31996, 32003, 32004, -1, 31998, 32003, 31994, -1, 31971, 31974, 32000, -1, 31994, 32003, 32001, -1, 30450, 31977, 30452, -1, 32001, 32003, 31996, -1, 32000, 31977, 30450, -1, 32004, 32005, 31999, -1, 29011, 32005, 29009, -1, 29009, 32005, 32002, -1, 32003, 32005, 32004, -1, 32002, 32005, 31998, -1, 31998, 32005, 32003, -1, 31999, 32005, 29011, -1, 31969, 31972, 31970, -1, 31970, 31972, 31974, -1, 32000, 31975, 31977, -1, 31974, 31975, 32000, -1, 30452, 31978, 30454, -1, 31977, 31978, 30452, -1, 31967, 31980, 31968, -1, 31968, 31980, 31969, -1, 31969, 31980, 31972, -1, 31974, 31973, 31975, -1, 28939, 32006, 28929, -1, 28929, 32006, 31999, -1, 31999, 32007, 32004, -1, 32006, 32007, 31999, -1, 32004, 32008, 31996, -1, 32007, 32008, 32004, -1, 31996, 32009, 31991, -1, 32008, 32009, 31996, -1, 31991, 32010, 31987, -1, 32009, 32010, 31991, -1, 31987, 32011, 31983, -1, 32010, 32011, 31987, -1, 31983, 29497, 29496, -1, 32011, 29497, 31983, -1, 26106, 32012, 26109, -1, 32013, 32012, 32014, -1, 32015, 32016, 32017, -1, 32014, 32012, 26106, -1, 29034, 32018, 29033, -1, 32017, 32016, 32019, -1, 29033, 32018, 32020, -1, 32021, 32018, 32022, -1, 32023, 32024, 32015, -1, 32015, 32024, 32016, -1, 32020, 32018, 32021, -1, 32011, 30469, 29497, -1, 26109, 32025, 26112, -1, 32026, 32025, 32012, -1, 32027, 32025, 32026, -1, 32012, 32025, 26109, -1, 30467, 32028, 30466, -1, 32019, 32028, 30467, -1, 29034, 32029, 32018, -1, 29035, 32029, 29034, -1, 32022, 32029, 32027, -1, 32018, 32029, 32022, -1, 32006, 32030, 32007, -1, 29036, 32031, 29035, -1, 29035, 32031, 32029, -1, 32007, 32030, 32032, -1, 32025, 32031, 26112, -1, 29043, 32030, 32006, -1, 32029, 32031, 32027, -1, 32027, 32031, 32025, -1, 26112, 32031, 29036, -1, 32019, 32033, 32028, -1, 32016, 32033, 32019, -1, 32023, 32034, 32024, -1, 32032, 32034, 32023, -1, 32016, 32035, 32033, -1, 32024, 32035, 32016, -1, 30465, 32036, 30463, -1, 30466, 32036, 30465, -1, 32028, 32036, 30466, -1, 28939, 29043, 32006, -1, 29040, 32037, 29043, -1, 29043, 32037, 32030, -1, 32032, 32037, 32034, -1, 32030, 32037, 32032, -1, 32033, 32038, 32028, -1, 32028, 32038, 32036, -1, 32034, 32039, 32024, -1, 32024, 32039, 32035, -1, 32036, 32040, 30463, -1, 32035, 32041, 32033, -1, 32033, 32041, 32038, -1, 32038, 32042, 32036, -1, 32036, 32042, 32040, -1, 32040, 32043, 30463, -1, 30458, 26104, 26103, -1, 30462, 32043, 30460, -1, 30463, 32043, 30462, -1, 29038, 32044, 29040, -1, 32034, 32044, 32039, -1, 29040, 32044, 32037, -1, 32037, 32044, 32034, -1, 32039, 32021, 32035, -1, 32035, 32021, 32041, -1, 32038, 32045, 32042, -1, 32041, 32045, 32038, -1, 32042, 32013, 32040, -1, 29036, 26114, 26112, -1, 32040, 32013, 32043, -1, 32043, 32046, 30460, -1, 30460, 32046, 30458, -1, 30469, 32017, 30468, -1, 32011, 32017, 30469, -1, 30458, 32046, 26104, -1, 32041, 32022, 32045, -1, 32021, 32022, 32041, -1, 32009, 32015, 32010, -1, 32010, 32015, 32011, -1, 32045, 32026, 32042, -1, 32042, 32026, 32013, -1, 32011, 32015, 32017, -1, 32008, 32023, 32009, -1, 29033, 32020, 29038, -1, 32009, 32023, 32015, -1, 32039, 32020, 32021, -1, 29038, 32020, 32044, -1, 32044, 32020, 32039, -1, 30468, 32019, 30467, -1, 32013, 32014, 32043, -1, 32043, 32014, 32046, -1, 26104, 32014, 26106, -1, 32017, 32019, 30468, -1, 32046, 32014, 26104, -1, 32007, 32032, 32008, -1, 32022, 32027, 32045, -1, 32008, 32032, 32023, -1, 32045, 32027, 32026, -1, 32026, 32012, 32013, -1, 29490, 26108, 32047, -1, 32047, 26107, 32048, -1, 26108, 26107, 32047, -1, 32048, 26110, 32049, -1, 26107, 26110, 32048, -1, 32049, 26111, 32050, -1, 26110, 26111, 32049, -1, 32050, 26113, 29010, -1, 26111, 26113, 32050, -1, 26113, 26115, 29010, -1, 32047, 30674, 29490, -1, 29010, 28907, 32050, -1, 30672, 32051, 27543, -1, 30672, 32052, 32051, -1, 28906, 32053, 30672, -1, 30672, 32053, 32052, -1, 28906, 32054, 32053, -1, 28906, 28908, 32054, -1, 30674, 32055, 30672, -1, 32047, 32055, 30674, -1, 32048, 32056, 32047, -1, 32047, 32056, 32055, -1, 32055, 32056, 30672, -1, 32049, 32057, 32048, -1, 32056, 32057, 30672, -1, 32048, 32057, 32056, -1, 30672, 32057, 28906, -1, 28906, 32058, 28907, -1, 32050, 32058, 32049, -1, 32057, 32058, 28906, -1, 32049, 32058, 32057, -1, 28907, 32058, 32050, -1, 27542, 27543, 32059, -1, 32059, 32051, 32060, -1, 27543, 32051, 32059, -1, 32060, 32052, 28068, -1, 32051, 32052, 32060, -1, 28068, 32053, 28069, -1, 28069, 32053, 28080, -1, 32052, 32053, 28068, -1, 28080, 32054, 28075, -1, 28075, 32054, 28067, -1, 32053, 32054, 28080, -1, 28067, 28908, 28066, -1, 32054, 28908, 28067, -1, 30673, 26099, 26102, -1, 30673, 26098, 26099, -1, 27227, 32061, 32062, -1, 27227, 27299, 32061, -1, 27120, 32063, 27122, -1, 30671, 32063, 30673, -1, 27122, 32063, 30671, -1, 27116, 32064, 27120, -1, 27120, 32064, 32063, -1, 32063, 32064, 30673, -1, 27115, 32065, 27116, -1, 32064, 32065, 30673, -1, 27116, 32065, 32064, -1, 27733, 32066, 27115, -1, 27115, 32066, 32065, -1, 27731, 32067, 27733, -1, 27733, 32067, 32066, -1, 27729, 32068, 27731, -1, 27731, 32068, 32067, -1, 27226, 32069, 27220, -1, 27227, 32069, 27226, -1, 27220, 32069, 27727, -1, 27727, 32069, 27729, -1, 27729, 32069, 32068, -1, 32068, 32069, 27227, -1, 26098, 32070, 26097, -1, 32071, 32070, 32062, -1, 32072, 32070, 32071, -1, 26097, 32070, 32072, -1, 32066, 32070, 32065, -1, 32068, 32070, 32067, -1, 27227, 32070, 32068, -1, 30673, 32070, 26098, -1, 32067, 32070, 32066, -1, 32062, 32070, 27227, -1, 32065, 32070, 30673, -1, 27297, 32073, 27299, -1, 27299, 32073, 32061, -1, 32061, 32074, 32062, -1, 32073, 32074, 32061, -1, 32062, 32075, 32071, -1, 32074, 32075, 32062, -1, 32071, 32076, 32072, -1, 32075, 32076, 32071, -1, 32072, 26095, 26097, -1, 32076, 26095, 32072, -1, 32077, 32078, 32079, -1, 32080, 32078, 32077, -1, 32075, 32081, 32076, -1, 32076, 32081, 32082, -1, 26100, 30457, 26101, -1, 32082, 32083, 32084, -1, 32084, 32083, 32085, -1, 26086, 32086, 26089, -1, 32085, 32086, 32080, -1, 32078, 32086, 26086, -1, 32080, 32086, 32078, -1, 32074, 32087, 32075, -1, 32075, 32087, 32081, -1, 32082, 32088, 32083, -1, 32081, 32088, 32082, -1, 26089, 32089, 26094, -1, 32086, 32089, 26089, -1, 32083, 32089, 32085, -1, 32085, 32089, 32086, -1, 27304, 32090, 27297, -1, 27297, 32090, 32073, -1, 32073, 32090, 32074, -1, 32074, 32090, 32087, -1, 30464, 26064, 26063, -1, 32087, 32091, 32081, -1, 32081, 32091, 32088, -1, 26094, 32092, 26070, -1, 32088, 32092, 32083, -1, 32089, 32092, 26094, -1, 32083, 32092, 32089, -1, 27310, 32093, 27304, -1, 27314, 32093, 27310, -1, 27304, 32093, 32090, -1, 32090, 32093, 32087, -1, 32087, 32093, 32091, -1, 26070, 32094, 26069, -1, 32092, 32094, 26070, -1, 32088, 32094, 32092, -1, 32091, 32094, 32088, -1, 27314, 32095, 32093, -1, 27318, 32095, 27314, -1, 32091, 32095, 32094, -1, 32094, 32095, 26069, -1, 26069, 32095, 27318, -1, 32093, 32095, 32091, -1, 27318, 26068, 26069, -1, 30457, 32096, 30459, -1, 26100, 32096, 30457, -1, 26095, 32097, 26096, -1, 26096, 32097, 26100, -1, 26100, 32097, 32096, -1, 30459, 32077, 30461, -1, 32096, 32077, 30459, -1, 26095, 32084, 32097, -1, 32096, 32080, 32077, -1, 32097, 32080, 32096, -1, 32076, 32082, 26095, -1, 26095, 32082, 32084, -1, 30461, 32079, 30464, -1, 30464, 32079, 26064, -1, 32077, 32079, 30461, -1, 32084, 32085, 32097, -1, 32097, 32085, 32080, -1, 26064, 32078, 26086, -1, 32079, 32078, 26064, -1, 26082, 27253, 26080, -1, 27253, 32098, 26080, -1, 26080, 32099, 26078, -1, 32098, 32099, 26080, -1, 26078, 32100, 26074, -1, 32099, 32100, 26078, -1, 26074, 32101, 26060, -1, 32100, 32101, 26074, -1, 26060, 32102, 26058, -1, 32101, 32102, 26060, -1, 26058, 32103, 26092, -1, 32102, 32103, 26058, -1, 26092, 29495, 26090, -1, 32103, 29495, 26092, -1, 32098, 32104, 32099, -1, 32099, 32104, 32100, -1, 32100, 32104, 32105, -1, 32106, 32107, 32108, -1, 32105, 32107, 32106, -1, 32109, 32110, 32111, -1, 32112, 32110, 32109, -1, 32113, 32114, 32115, -1, 30449, 32114, 32113, -1, 32111, 32114, 30449, -1, 27395, 32116, 27253, -1, 27392, 32116, 27395, -1, 27253, 32116, 32098, -1, 32098, 32116, 32104, -1, 32105, 32117, 32107, -1, 32104, 32117, 32105, -1, 32108, 32118, 32112, -1, 32112, 32118, 32110, -1, 32110, 32119, 32111, -1, 30449, 32113, 29492, -1, 32114, 32119, 32115, -1, 32111, 32119, 32114, -1, 27391, 32120, 27392, -1, 27392, 32120, 32116, -1, 32116, 32120, 32104, -1, 32104, 32120, 32117, -1, 32107, 32121, 32108, -1, 32108, 32121, 32118, -1, 32115, 32122, 32123, -1, 32119, 32122, 32115, -1, 32110, 32122, 32119, -1, 32118, 32122, 32110, -1, 32107, 32124, 32121, -1, 32117, 32124, 32107, -1, 32121, 32125, 32118, -1, 32123, 32125, 32126, -1, 32118, 32125, 32122, -1, 32122, 32125, 32123, -1, 32117, 32127, 32124, -1, 27385, 32127, 27391, -1, 27391, 32127, 32120, -1, 32120, 32127, 32117, -1, 32124, 32128, 32121, -1, 32126, 32128, 32129, -1, 32121, 32128, 32125, -1, 32125, 32128, 32126, -1, 32129, 32130, 32131, -1, 27380, 32130, 27385, -1, 27380, 27357, 32131, -1, 32124, 32130, 32128, -1, 27385, 32130, 32127, -1, 32131, 32130, 27380, -1, 32127, 32130, 32124, -1, 29495, 32132, 30456, -1, 32128, 32130, 32129, -1, 32103, 32132, 29495, -1, 32102, 32133, 32103, -1, 32103, 32133, 32132, -1, 30455, 32109, 30453, -1, 30456, 32109, 30455, -1, 32132, 32109, 30456, -1, 32101, 32106, 32102, -1, 32102, 32106, 32133, -1, 32132, 32112, 32109, -1, 32133, 32112, 32132, -1, 32100, 32105, 32101, -1, 32101, 32105, 32106, -1, 32106, 32108, 32133, -1, 32133, 32108, 32112, -1, 30451, 32111, 30449, -1, 30453, 32111, 30451, -1, 32109, 32111, 30453, -1, 29493, 29492, 32134, -1, 32134, 32113, 32135, -1, 29492, 32113, 32134, -1, 32135, 32115, 32136, -1, 32113, 32115, 32135, -1, 32136, 32123, 32137, -1, 32115, 32123, 32136, -1, 32137, 32126, 32138, -1, 32123, 32126, 32137, -1, 32138, 32129, 32139, -1, 32126, 32129, 32138, -1, 32129, 32131, 32139, -1, 32139, 27357, 27359, -1, 32131, 27357, 32139, -1, 27423, 32139, 27359, -1, 27423, 32138, 32139, -1, 27423, 32137, 32138, -1, 30669, 32135, 32136, -1, 30669, 32134, 32135, -1, 30669, 29493, 32134, -1, 27737, 32140, 27216, -1, 27424, 32140, 27423, -1, 27216, 32140, 27424, -1, 27740, 32141, 27737, -1, 27737, 32141, 32140, -1, 32140, 32141, 27423, -1, 27741, 32142, 27740, -1, 32141, 32142, 27423, -1, 27740, 32142, 32141, -1, 27423, 32142, 32137, -1, 27743, 32143, 27741, -1, 32137, 32143, 32136, -1, 32142, 32143, 32137, -1, 32136, 32143, 30669, -1, 27741, 32143, 32142, -1, 27745, 32144, 27743, -1, 32143, 32144, 30669, -1, 27743, 32144, 32143, -1, 30667, 32145, 27540, -1, 30669, 32145, 30667, -1, 27747, 32145, 27745, -1, 27540, 32145, 27747, -1, 32144, 32145, 30669, -1, 27745, 32145, 32144, -1, 32146, 29046, 28824, -1, 29045, 27752, 27750, -1, 29045, 27754, 27752, -1, 29507, 30654, 32147, -1, 29045, 27757, 27754, -1, 30652, 27765, 27762, -1, 30652, 27768, 27765, -1, 30652, 27527, 27768, -1, 29046, 32148, 29045, -1, 32146, 32148, 29046, -1, 32149, 32150, 32146, -1, 32146, 32150, 32148, -1, 32148, 32150, 29045, -1, 32151, 32152, 32149, -1, 32150, 32152, 29045, -1, 32149, 32152, 32150, -1, 29045, 32152, 27757, -1, 32153, 32154, 32151, -1, 27757, 32154, 27759, -1, 32151, 32154, 32152, -1, 32152, 32154, 27757, -1, 32155, 32156, 32153, -1, 27759, 32156, 27762, -1, 32153, 32156, 32154, -1, 32154, 32156, 27759, -1, 32157, 32158, 32155, -1, 32156, 32158, 27762, -1, 32155, 32158, 32156, -1, 27762, 32158, 30652, -1, 32159, 32160, 32157, -1, 32158, 32160, 30652, -1, 32157, 32160, 32158, -1, 30652, 32161, 30654, -1, 32147, 32161, 32159, -1, 32159, 32161, 32160, -1, 32160, 32161, 30652, -1, 30654, 32161, 32147, -1, 28824, 28847, 32146, -1, 32146, 32162, 32149, -1, 28847, 32162, 32146, -1, 32149, 32163, 32151, -1, 32162, 32163, 32149, -1, 32151, 32164, 32153, -1, 32163, 32164, 32151, -1, 32153, 32165, 32155, -1, 32164, 32165, 32153, -1, 32155, 32166, 32157, -1, 32165, 32166, 32155, -1, 32157, 32167, 32159, -1, 32166, 32167, 32157, -1, 32159, 32168, 32147, -1, 32167, 32168, 32159, -1, 32147, 32169, 29507, -1, 32168, 32169, 32147, -1, 32169, 29510, 29507, -1, 32170, 32171, 32172, -1, 32173, 32174, 32175, -1, 32175, 32174, 32176, -1, 29510, 32169, 30505, -1, 32164, 32177, 32165, -1, 32165, 32177, 32178, -1, 32178, 32179, 32170, -1, 32170, 32179, 32171, -1, 30511, 32180, 29512, -1, 29512, 32180, 32181, -1, 32176, 32180, 30511, -1, 32171, 32182, 32173, -1, 32173, 32182, 32174, -1, 32163, 32183, 32164, -1, 32164, 32183, 32177, -1, 32181, 32184, 32185, -1, 32174, 32184, 32176, -1, 32180, 32184, 32181, -1, 32176, 32184, 32180, -1, 32178, 32186, 32179, -1, 32177, 32186, 32178, -1, 32179, 32187, 32171, -1, 32171, 32187, 32182, -1, 28847, 28854, 32162, -1, 32185, 32188, 32189, -1, 32174, 32188, 32184, -1, 32182, 32188, 32174, -1, 32184, 32188, 32185, -1, 32162, 32190, 32163, -1, 32163, 32190, 32183, -1, 28854, 32190, 32162, -1, 32183, 32191, 32177, -1, 32177, 32191, 32186, -1, 32179, 32192, 32187, -1, 32186, 32192, 32179, -1, 32187, 32193, 32182, -1, 32189, 32193, 32194, -1, 32182, 32193, 32188, -1, 32188, 32193, 32189, -1, 32190, 32195, 32183, -1, 28857, 32195, 28854, -1, 28859, 32195, 28857, -1, 28854, 32195, 32190, -1, 32183, 32195, 32191, -1, 32191, 32196, 32186, -1, 32186, 32196, 32192, -1, 28864, 28881, 32197, -1, 30505, 32198, 30507, -1, 32192, 32199, 32187, -1, 32193, 32199, 32194, -1, 32187, 32199, 32193, -1, 32169, 32198, 30505, -1, 28861, 32200, 28859, -1, 28859, 32200, 32195, -1, 32191, 32200, 32196, -1, 32195, 32200, 32191, -1, 32168, 32172, 32169, -1, 32194, 32201, 32202, -1, 32196, 32201, 32192, -1, 32169, 32172, 32198, -1, 32192, 32201, 32199, -1, 30507, 32175, 30509, -1, 32199, 32201, 32194, -1, 32198, 32175, 30507, -1, 32202, 32203, 32197, -1, 28864, 32203, 28861, -1, 28861, 32203, 32200, -1, 32201, 32203, 32202, -1, 32200, 32203, 32196, -1, 32196, 32203, 32201, -1, 32197, 32203, 28864, -1, 32167, 32170, 32168, -1, 32168, 32170, 32172, -1, 32198, 32173, 32175, -1, 32172, 32173, 32198, -1, 30509, 32176, 30511, -1, 32175, 32176, 30509, -1, 32165, 32178, 32166, -1, 32166, 32178, 32167, -1, 32167, 32178, 32170, -1, 32172, 32171, 32173, -1, 28888, 32204, 28881, -1, 28881, 32204, 32197, -1, 32197, 32205, 32202, -1, 32204, 32205, 32197, -1, 32202, 32206, 32194, -1, 32205, 32206, 32202, -1, 32194, 32207, 32189, -1, 32206, 32207, 32194, -1, 32189, 32208, 32185, -1, 32207, 32208, 32189, -1, 32185, 32209, 32181, -1, 32181, 32209, 29512, -1, 32208, 32209, 32185, -1, 32209, 29513, 29512, -1, 26044, 32210, 26047, -1, 32211, 32210, 26044, -1, 32212, 32210, 32211, -1, 32213, 32214, 32215, -1, 32215, 32214, 32216, -1, 28893, 32217, 28892, -1, 32218, 32217, 32219, -1, 32220, 32221, 32213, -1, 32222, 32217, 32218, -1, 28892, 32217, 32222, -1, 32209, 30504, 29513, -1, 32213, 32221, 32214, -1, 32223, 32224, 32225, -1, 32225, 32224, 32210, -1, 32210, 32224, 26047, -1, 30502, 32226, 30501, -1, 32216, 32226, 30502, -1, 28894, 32227, 28893, -1, 28893, 32227, 32217, -1, 32217, 32227, 32219, -1, 32219, 32227, 32223, -1, 32204, 32228, 32205, -1, 28895, 32229, 28894, -1, 26047, 32229, 26050, -1, 32205, 32228, 32230, -1, 28894, 32229, 32227, -1, 28889, 32228, 32204, -1, 32224, 32229, 26047, -1, 32223, 32229, 32224, -1, 32227, 32229, 32223, -1, 26050, 32229, 28895, -1, 32216, 32231, 32226, -1, 32214, 32231, 32216, -1, 32220, 32232, 32221, -1, 32230, 32232, 32220, -1, 32214, 32233, 32231, -1, 32221, 32233, 32214, -1, 30500, 32234, 30498, -1, 30501, 32234, 30500, -1, 28888, 28889, 32204, -1, 32226, 32234, 30501, -1, 28890, 32235, 28889, -1, 28889, 32235, 32228, -1, 32230, 32235, 32232, -1, 32228, 32235, 32230, -1, 32231, 32236, 32226, -1, 32226, 32236, 32234, -1, 32232, 32237, 32221, -1, 32221, 32237, 32233, -1, 32234, 32238, 30498, -1, 32233, 32239, 32231, -1, 32231, 32239, 32236, -1, 32236, 32240, 32234, -1, 32234, 32240, 32238, -1, 30493, 26042, 26041, -1, 32238, 32241, 30498, -1, 30497, 32241, 30495, -1, 30498, 32241, 30497, -1, 28891, 32242, 28890, -1, 32232, 32242, 32237, -1, 28890, 32242, 32235, -1, 32235, 32242, 32232, -1, 32233, 32218, 32239, -1, 32237, 32218, 32233, -1, 32239, 32243, 32236, -1, 32236, 32243, 32240, -1, 32240, 32212, 32238, -1, 28895, 26052, 26050, -1, 32238, 32212, 32241, -1, 32241, 32244, 30495, -1, 30495, 32244, 30493, -1, 30504, 32215, 30503, -1, 32209, 32215, 30504, -1, 30493, 32244, 26042, -1, 32239, 32219, 32243, -1, 32208, 32213, 32209, -1, 32218, 32219, 32239, -1, 32209, 32213, 32215, -1, 32243, 32225, 32240, -1, 32240, 32225, 32212, -1, 32206, 32220, 32207, -1, 32207, 32220, 32208, -1, 28892, 32222, 28891, -1, 32237, 32222, 32218, -1, 32208, 32220, 32213, -1, 32242, 32222, 32237, -1, 28891, 32222, 32242, -1, 30503, 32216, 30502, -1, 26042, 32211, 26044, -1, 32241, 32211, 32244, -1, 32244, 32211, 26042, -1, 32215, 32216, 30503, -1, 32212, 32211, 32241, -1, 32205, 32230, 32206, -1, 32219, 32223, 32243, -1, 32206, 32230, 32220, -1, 32243, 32223, 32225, -1, 32225, 32210, 32212, -1, 29506, 26046, 32245, -1, 32245, 26045, 32246, -1, 26046, 26045, 32245, -1, 32246, 26048, 32247, -1, 26045, 26048, 32246, -1, 32247, 26049, 32248, -1, 26048, 26049, 32247, -1, 32248, 26051, 28866, -1, 26049, 26051, 32248, -1, 26051, 26053, 28866, -1, 32245, 30658, 29506, -1, 28866, 28842, 32248, -1, 30656, 32249, 27529, -1, 30656, 32250, 32249, -1, 28836, 32251, 30656, -1, 30656, 32251, 32250, -1, 28836, 32252, 32251, -1, 28836, 28833, 32252, -1, 30658, 32253, 30656, -1, 32245, 32253, 30658, -1, 32246, 32254, 32245, -1, 32245, 32254, 32253, -1, 32253, 32254, 30656, -1, 32247, 32255, 32246, -1, 32254, 32255, 30656, -1, 32246, 32255, 32254, -1, 30656, 32255, 28836, -1, 28836, 32256, 28842, -1, 32248, 32256, 32247, -1, 32255, 32256, 28836, -1, 32247, 32256, 32255, -1, 28842, 32256, 32248, -1, 27528, 27529, 27773, -1, 27773, 32249, 27770, -1, 27529, 32249, 27773, -1, 27770, 32250, 27693, -1, 32249, 32250, 27770, -1, 27694, 32251, 27696, -1, 27693, 32251, 27694, -1, 32250, 32251, 27693, -1, 27696, 32252, 27697, -1, 32251, 32252, 27696, -1, 27697, 28833, 27698, -1, 32252, 28833, 27697, -1, 32257, 29014, 29012, -1, 29013, 27779, 27777, -1, 29013, 27781, 27779, -1, 29499, 30662, 32258, -1, 29013, 27784, 27781, -1, 30660, 27792, 27789, -1, 30660, 27795, 27792, -1, 30660, 27534, 27795, -1, 29014, 32259, 29013, -1, 32257, 32259, 29014, -1, 32260, 32261, 32257, -1, 32257, 32261, 32259, -1, 32259, 32261, 29013, -1, 32262, 32263, 32260, -1, 32261, 32263, 29013, -1, 32260, 32263, 32261, -1, 29013, 32263, 27784, -1, 32264, 32265, 32262, -1, 27784, 32265, 27786, -1, 32262, 32265, 32263, -1, 32263, 32265, 27784, -1, 32266, 32267, 32264, -1, 27786, 32267, 27789, -1, 32264, 32267, 32265, -1, 32265, 32267, 27786, -1, 32268, 32269, 32266, -1, 32267, 32269, 27789, -1, 32266, 32269, 32267, -1, 27789, 32269, 30660, -1, 32270, 32271, 32268, -1, 32269, 32271, 30660, -1, 32268, 32271, 32269, -1, 30660, 32272, 30662, -1, 32258, 32272, 32270, -1, 32270, 32272, 32271, -1, 32271, 32272, 30660, -1, 30662, 32272, 32258, -1, 29012, 29032, 32257, -1, 32257, 32273, 32260, -1, 29032, 32273, 32257, -1, 32260, 32274, 32262, -1, 32273, 32274, 32260, -1, 32262, 32275, 32264, -1, 32274, 32275, 32262, -1, 32264, 32276, 32266, -1, 32275, 32276, 32264, -1, 32266, 32277, 32268, -1, 32276, 32277, 32266, -1, 32268, 32278, 32270, -1, 32277, 32278, 32268, -1, 32270, 32279, 32258, -1, 32278, 32279, 32270, -1, 32258, 32280, 29499, -1, 32279, 32280, 32258, -1, 32280, 29502, 29499, -1, 32281, 32282, 32283, -1, 32284, 32285, 32286, -1, 32286, 32285, 32287, -1, 29502, 32280, 30470, -1, 32275, 32288, 32276, -1, 32276, 32288, 32289, -1, 32289, 32290, 32281, -1, 32281, 32290, 32282, -1, 30476, 32291, 29504, -1, 29504, 32291, 32292, -1, 32287, 32291, 30476, -1, 32284, 32293, 32285, -1, 32282, 32293, 32284, -1, 32274, 32294, 32275, -1, 32275, 32294, 32288, -1, 32292, 32295, 32296, -1, 32291, 32295, 32292, -1, 32285, 32295, 32287, -1, 32287, 32295, 32291, -1, 32289, 32297, 32290, -1, 32288, 32297, 32289, -1, 32290, 32298, 32282, -1, 32282, 32298, 32293, -1, 29032, 29037, 32273, -1, 32296, 32299, 32300, -1, 32293, 32299, 32285, -1, 32295, 32299, 32296, -1, 32285, 32299, 32295, -1, 32273, 32301, 32274, -1, 32274, 32301, 32294, -1, 29037, 32301, 32273, -1, 32294, 32302, 32288, -1, 32288, 32302, 32297, -1, 32290, 32303, 32298, -1, 32297, 32303, 32290, -1, 32298, 32304, 32293, -1, 32300, 32304, 32305, -1, 32293, 32304, 32299, -1, 32299, 32304, 32300, -1, 32301, 32306, 32294, -1, 29039, 32306, 29037, -1, 29041, 32306, 29039, -1, 29037, 32306, 32301, -1, 32294, 32306, 32302, -1, 32302, 32307, 32297, -1, 32297, 32307, 32303, -1, 29044, 28940, 32308, -1, 30470, 32309, 30472, -1, 32303, 32310, 32298, -1, 32304, 32310, 32305, -1, 32298, 32310, 32304, -1, 32280, 32309, 30470, -1, 29042, 32311, 29041, -1, 29041, 32311, 32306, -1, 32302, 32311, 32307, -1, 32306, 32311, 32302, -1, 32279, 32283, 32280, -1, 32305, 32312, 32313, -1, 32307, 32312, 32303, -1, 32280, 32283, 32309, -1, 32303, 32312, 32310, -1, 30472, 32286, 30474, -1, 32310, 32312, 32305, -1, 32309, 32286, 30472, -1, 32313, 32314, 32308, -1, 29044, 32314, 29042, -1, 29042, 32314, 32311, -1, 32312, 32314, 32313, -1, 32311, 32314, 32307, -1, 32307, 32314, 32312, -1, 32308, 32314, 29044, -1, 32278, 32281, 32279, -1, 32279, 32281, 32283, -1, 32309, 32284, 32286, -1, 32283, 32284, 32309, -1, 30474, 32287, 30476, -1, 32286, 32287, 30474, -1, 32276, 32289, 32277, -1, 32277, 32289, 32278, -1, 32278, 32289, 32281, -1, 32283, 32282, 32284, -1, 28940, 28882, 32308, -1, 32308, 32315, 32313, -1, 28882, 32315, 32308, -1, 32313, 32316, 32305, -1, 32315, 32316, 32313, -1, 32305, 32317, 32300, -1, 32316, 32317, 32305, -1, 32300, 32318, 32296, -1, 32317, 32318, 32300, -1, 32296, 32319, 32292, -1, 32318, 32319, 32296, -1, 32292, 32320, 29504, -1, 32319, 32320, 32292, -1, 32320, 29505, 29504, -1, 26031, 32321, 26035, -1, 32322, 32321, 26031, -1, 32323, 32321, 32322, -1, 32324, 32325, 32326, -1, 32326, 32325, 32327, -1, 28849, 32328, 28848, -1, 32329, 32328, 32330, -1, 32331, 32332, 32324, -1, 32333, 32328, 32329, -1, 28848, 32328, 32333, -1, 32320, 30491, 29505, -1, 26035, 32334, 26037, -1, 32324, 32332, 32325, -1, 32335, 32334, 32336, -1, 32336, 32334, 32321, -1, 32321, 32334, 26035, -1, 30489, 32337, 30488, -1, 32327, 32337, 30489, -1, 28850, 32338, 28849, -1, 28849, 32338, 32328, -1, 32328, 32338, 32330, -1, 32330, 32338, 32335, -1, 32315, 32339, 32316, -1, 28852, 32340, 28850, -1, 28850, 32340, 32338, -1, 32316, 32339, 32341, -1, 32335, 32340, 32334, -1, 28860, 32339, 32315, -1, 32338, 32340, 32335, -1, 32334, 32340, 26037, -1, 26037, 32340, 28852, -1, 32327, 32342, 32337, -1, 32325, 32342, 32327, -1, 32331, 32343, 32332, -1, 32341, 32343, 32331, -1, 32325, 32344, 32342, -1, 32332, 32344, 32325, -1, 30487, 32345, 30485, -1, 30488, 32345, 30487, -1, 28882, 28860, 32315, -1, 32337, 32345, 30488, -1, 28858, 32346, 28860, -1, 28860, 32346, 32339, -1, 32341, 32346, 32343, -1, 32339, 32346, 32341, -1, 32342, 32347, 32337, -1, 32337, 32347, 32345, -1, 32343, 32348, 32332, -1, 32332, 32348, 32344, -1, 32345, 32349, 30485, -1, 32344, 32350, 32342, -1, 32342, 32350, 32347, -1, 32347, 32351, 32345, -1, 32345, 32351, 32349, -1, 30480, 26029, 26028, -1, 32349, 32352, 30485, -1, 30484, 32352, 30482, -1, 30485, 32352, 30484, -1, 28856, 32353, 28858, -1, 32343, 32353, 32348, -1, 28858, 32353, 32346, -1, 32346, 32353, 32343, -1, 32344, 32329, 32350, -1, 32348, 32329, 32344, -1, 32350, 32354, 32347, -1, 32347, 32354, 32351, -1, 32351, 32323, 32349, -1, 28852, 26039, 26037, -1, 32349, 32323, 32352, -1, 32352, 32355, 30482, -1, 30482, 32355, 30480, -1, 30491, 32326, 30490, -1, 32320, 32326, 30491, -1, 30480, 32355, 26029, -1, 32350, 32330, 32354, -1, 32319, 32324, 32320, -1, 32329, 32330, 32350, -1, 32320, 32324, 32326, -1, 32354, 32336, 32351, -1, 32351, 32336, 32323, -1, 32317, 32331, 32318, -1, 32318, 32331, 32319, -1, 28848, 32333, 28856, -1, 32348, 32333, 32329, -1, 32319, 32331, 32324, -1, 32353, 32333, 32348, -1, 28856, 32333, 32353, -1, 30490, 32327, 30489, -1, 26029, 32322, 26031, -1, 32352, 32322, 32355, -1, 32355, 32322, 26029, -1, 32326, 32327, 30490, -1, 32323, 32322, 32352, -1, 32316, 32341, 32317, -1, 32330, 32335, 32354, -1, 32317, 32341, 32331, -1, 32354, 32335, 32336, -1, 32336, 32321, 32323, -1, 26033, 26032, 29498, -1, 29498, 26032, 32356, -1, 32356, 26034, 32357, -1, 26032, 26034, 32356, -1, 32357, 26036, 32358, -1, 26034, 26036, 32357, -1, 32358, 26038, 32359, -1, 26036, 26038, 32358, -1, 32359, 26040, 28823, -1, 26038, 26040, 32359, -1, 32356, 30666, 29498, -1, 28823, 28942, 32359, -1, 30664, 32360, 27536, -1, 30664, 32361, 32360, -1, 28941, 32362, 30664, -1, 30664, 32362, 32361, -1, 28941, 32363, 32362, -1, 28941, 28903, 32363, -1, 30666, 32364, 30664, -1, 32356, 32364, 30666, -1, 32357, 32365, 32356, -1, 32356, 32365, 32364, -1, 32364, 32365, 30664, -1, 32358, 32366, 32357, -1, 32365, 32366, 30664, -1, 32357, 32366, 32365, -1, 30664, 32366, 28941, -1, 28941, 32367, 28942, -1, 32359, 32367, 32358, -1, 32366, 32367, 28941, -1, 32358, 32367, 32366, -1, 28942, 32367, 32359, -1, 27535, 27536, 32368, -1, 32368, 32360, 32369, -1, 27536, 32360, 32368, -1, 32369, 32361, 28039, -1, 32360, 32361, 32369, -1, 28039, 32362, 28040, -1, 28040, 32362, 28051, -1, 32361, 32362, 28039, -1, 28051, 32363, 28046, -1, 28046, 32363, 28038, -1, 32362, 32363, 28051, -1, 28038, 28903, 28037, -1, 32363, 28903, 28038, -1, 32370, 28945, 28943, -1, 28944, 27806, 27804, -1, 28944, 27808, 27806, -1, 29483, 30678, 32371, -1, 28944, 27811, 27808, -1, 30676, 27819, 27816, -1, 30676, 27822, 27819, -1, 30676, 27548, 27822, -1, 28945, 32372, 28944, -1, 32370, 32372, 28945, -1, 32373, 32374, 32370, -1, 32370, 32374, 32372, -1, 32372, 32374, 28944, -1, 32375, 32376, 32373, -1, 32374, 32376, 28944, -1, 32373, 32376, 32374, -1, 28944, 32376, 27811, -1, 32377, 32378, 32375, -1, 27811, 32378, 27813, -1, 32375, 32378, 32376, -1, 32376, 32378, 27811, -1, 32379, 32380, 32377, -1, 27813, 32380, 27816, -1, 32377, 32380, 32378, -1, 32378, 32380, 27813, -1, 32381, 32382, 32379, -1, 32380, 32382, 27816, -1, 32379, 32382, 32380, -1, 27816, 32382, 30676, -1, 32383, 32384, 32381, -1, 32382, 32384, 30676, -1, 32381, 32384, 32382, -1, 30676, 32385, 30678, -1, 32371, 32385, 32383, -1, 32383, 32385, 32384, -1, 32384, 32385, 30676, -1, 30678, 32385, 32371, -1, 28943, 28965, 32370, -1, 32370, 32386, 32373, -1, 28965, 32386, 32370, -1, 32373, 32387, 32375, -1, 32386, 32387, 32373, -1, 32375, 32388, 32377, -1, 32387, 32388, 32375, -1, 32377, 32389, 32379, -1, 32388, 32389, 32377, -1, 32379, 32390, 32381, -1, 32389, 32390, 32379, -1, 32381, 32391, 32383, -1, 32390, 32391, 32381, -1, 32383, 32392, 32371, -1, 32391, 32392, 32383, -1, 32371, 32393, 29483, -1, 32392, 32393, 32371, -1, 32393, 29486, 29483, -1, 32394, 32395, 32396, -1, 32397, 32398, 32399, -1, 32399, 32398, 32400, -1, 29486, 32393, 30439, -1, 32388, 32401, 32389, -1, 32389, 32401, 32402, -1, 32402, 32403, 32394, -1, 32394, 32403, 32395, -1, 30445, 32404, 29488, -1, 29488, 32404, 32405, -1, 32400, 32404, 30445, -1, 32395, 32406, 32397, -1, 32397, 32406, 32398, -1, 32387, 32407, 32388, -1, 32388, 32407, 32401, -1, 32405, 32408, 32409, -1, 32398, 32408, 32400, -1, 32404, 32408, 32405, -1, 32400, 32408, 32404, -1, 32402, 32410, 32403, -1, 32401, 32410, 32402, -1, 32403, 32411, 32395, -1, 32395, 32411, 32406, -1, 28965, 28969, 32386, -1, 32409, 32412, 32413, -1, 32398, 32412, 32408, -1, 32406, 32412, 32398, -1, 32408, 32412, 32409, -1, 32386, 32414, 32387, -1, 32387, 32414, 32407, -1, 28969, 32414, 32386, -1, 32407, 32415, 32401, -1, 32401, 32415, 32410, -1, 32403, 32416, 32411, -1, 32410, 32416, 32403, -1, 32411, 32417, 32406, -1, 32413, 32417, 32418, -1, 32406, 32417, 32412, -1, 32412, 32417, 32413, -1, 32414, 32419, 32407, -1, 28970, 32419, 28969, -1, 28972, 32419, 28970, -1, 28969, 32419, 32414, -1, 32407, 32419, 32415, -1, 32415, 32420, 32410, -1, 32410, 32420, 32416, -1, 28977, 28931, 32421, -1, 30439, 32422, 30441, -1, 32416, 32423, 32411, -1, 32417, 32423, 32418, -1, 32411, 32423, 32417, -1, 32393, 32422, 30439, -1, 28974, 32424, 28972, -1, 28972, 32424, 32419, -1, 32415, 32424, 32420, -1, 32419, 32424, 32415, -1, 32392, 32396, 32393, -1, 32418, 32425, 32426, -1, 32420, 32425, 32416, -1, 32393, 32396, 32422, -1, 32416, 32425, 32423, -1, 30441, 32399, 30443, -1, 32423, 32425, 32418, -1, 32422, 32399, 30441, -1, 32426, 32427, 32421, -1, 28977, 32427, 28974, -1, 28974, 32427, 32424, -1, 32425, 32427, 32426, -1, 32424, 32427, 32420, -1, 32420, 32427, 32425, -1, 32421, 32427, 28977, -1, 32391, 32394, 32392, -1, 32392, 32394, 32396, -1, 32422, 32397, 32399, -1, 32396, 32397, 32422, -1, 30443, 32400, 30445, -1, 32399, 32400, 30443, -1, 32389, 32402, 32390, -1, 32390, 32402, 32391, -1, 32391, 32402, 32394, -1, 32396, 32395, 32397, -1, 28931, 28930, 32421, -1, 32421, 32428, 32426, -1, 28930, 32428, 32421, -1, 32426, 32429, 32418, -1, 32428, 32429, 32426, -1, 32418, 32430, 32413, -1, 32429, 32430, 32418, -1, 32413, 32431, 32409, -1, 32430, 32431, 32413, -1, 32409, 32432, 32405, -1, 32431, 32432, 32409, -1, 32432, 32433, 32405, -1, 32405, 29489, 29488, -1, 32433, 29489, 32405, -1, 26018, 32434, 26022, -1, 32435, 32434, 26018, -1, 32436, 32434, 32435, -1, 32437, 32438, 32439, -1, 32439, 32438, 32440, -1, 29000, 32441, 28999, -1, 32442, 32441, 32443, -1, 32444, 32445, 32437, -1, 32446, 32441, 32442, -1, 28999, 32441, 32446, -1, 32433, 30438, 29489, -1, 32437, 32445, 32438, -1, 32447, 32448, 32449, -1, 32449, 32448, 32434, -1, 32434, 32448, 26022, -1, 30436, 32450, 30435, -1, 32440, 32450, 30436, -1, 29001, 32451, 29000, -1, 29000, 32451, 32441, -1, 32441, 32451, 32443, -1, 32443, 32451, 32447, -1, 32428, 32452, 32429, -1, 29002, 32453, 29001, -1, 26022, 32453, 26024, -1, 32429, 32452, 32454, -1, 29001, 32453, 32451, -1, 29008, 32452, 32428, -1, 32448, 32453, 26022, -1, 32447, 32453, 32448, -1, 32451, 32453, 32447, -1, 26024, 32453, 29002, -1, 32440, 32455, 32450, -1, 32438, 32455, 32440, -1, 32444, 32456, 32445, -1, 32454, 32456, 32444, -1, 32438, 32457, 32455, -1, 32445, 32457, 32438, -1, 30434, 32458, 30432, -1, 30435, 32458, 30434, -1, 28930, 29008, 32428, -1, 32450, 32458, 30435, -1, 29007, 32459, 29008, -1, 29008, 32459, 32452, -1, 32454, 32459, 32456, -1, 32452, 32459, 32454, -1, 32455, 32460, 32450, -1, 32450, 32460, 32458, -1, 32456, 32461, 32445, -1, 32445, 32461, 32457, -1, 32458, 32462, 30432, -1, 32457, 32463, 32455, -1, 32455, 32463, 32460, -1, 32460, 32464, 32458, -1, 32458, 32464, 32462, -1, 30427, 26016, 26015, -1, 32462, 32465, 30432, -1, 30431, 32465, 30429, -1, 30432, 32465, 30431, -1, 29004, 32466, 29007, -1, 32456, 32466, 32461, -1, 29007, 32466, 32459, -1, 32459, 32466, 32456, -1, 32457, 32442, 32463, -1, 32461, 32442, 32457, -1, 32463, 32467, 32460, -1, 32460, 32467, 32464, -1, 32464, 32436, 32462, -1, 29002, 26026, 26024, -1, 32462, 32436, 32465, -1, 32465, 32468, 30429, -1, 30429, 32468, 30427, -1, 30438, 32439, 30437, -1, 32433, 32439, 30438, -1, 30427, 32468, 26016, -1, 32463, 32443, 32467, -1, 32432, 32437, 32433, -1, 32442, 32443, 32463, -1, 32433, 32437, 32439, -1, 32467, 32449, 32464, -1, 32464, 32449, 32436, -1, 32430, 32444, 32431, -1, 32431, 32444, 32432, -1, 28999, 32446, 29004, -1, 32461, 32446, 32442, -1, 32432, 32444, 32437, -1, 32466, 32446, 32461, -1, 29004, 32446, 32466, -1, 30437, 32440, 30436, -1, 26016, 32435, 26018, -1, 32465, 32435, 32468, -1, 32468, 32435, 26016, -1, 32439, 32440, 30437, -1, 32436, 32435, 32465, -1, 32429, 32454, 32430, -1, 32443, 32447, 32467, -1, 32430, 32454, 32444, -1, 32467, 32447, 32449, -1, 32449, 32434, 32436, -1, 29482, 26020, 32469, -1, 32469, 26019, 32470, -1, 26020, 26019, 32469, -1, 32470, 26021, 32471, -1, 26019, 26021, 32470, -1, 32471, 26023, 32472, -1, 26021, 26023, 32471, -1, 32472, 26025, 28976, -1, 26023, 26025, 32472, -1, 26025, 26027, 28976, -1, 32469, 30682, 29482, -1, 28976, 28910, 32472, -1, 30680, 32473, 27550, -1, 30680, 32474, 32473, -1, 28909, 32475, 30680, -1, 30680, 32475, 32474, -1, 28909, 32476, 32475, -1, 28909, 28911, 32476, -1, 30682, 32477, 30680, -1, 32469, 32477, 30682, -1, 32470, 32478, 32469, -1, 32469, 32478, 32477, -1, 32477, 32478, 30680, -1, 32471, 32479, 32470, -1, 32478, 32479, 30680, -1, 32470, 32479, 32478, -1, 30680, 32479, 28909, -1, 28909, 32480, 28910, -1, 32472, 32480, 32471, -1, 32479, 32480, 28909, -1, 32471, 32480, 32479, -1, 28910, 32480, 32472, -1, 27549, 27550, 32481, -1, 32481, 32473, 32482, -1, 27550, 32473, 32481, -1, 32482, 32474, 28097, -1, 32473, 32474, 32482, -1, 28097, 32475, 28098, -1, 28098, 32475, 28109, -1, 32474, 32475, 28097, -1, 28109, 32476, 28104, -1, 28104, 32476, 28096, -1, 32475, 32476, 28109, -1, 28096, 28911, 28095, -1, 32476, 28911, 28096, -1, 32483, 28846, 28844, -1, 28845, 27835, 27834, -1, 28845, 27838, 27835, -1, 29475, 30686, 32484, -1, 28845, 27840, 27838, -1, 30684, 27848, 27845, -1, 30684, 27851, 27848, -1, 30684, 27555, 27851, -1, 28846, 32485, 28845, -1, 32483, 32485, 28846, -1, 32486, 32487, 32483, -1, 32483, 32487, 32485, -1, 32485, 32487, 28845, -1, 32488, 32489, 32486, -1, 32487, 32489, 28845, -1, 32486, 32489, 32487, -1, 28845, 32489, 27840, -1, 32490, 32491, 32488, -1, 27840, 32491, 27842, -1, 32488, 32491, 32489, -1, 32489, 32491, 27840, -1, 32492, 32493, 32490, -1, 27842, 32493, 27845, -1, 32490, 32493, 32491, -1, 32491, 32493, 27842, -1, 32494, 32495, 32492, -1, 32493, 32495, 27845, -1, 32492, 32495, 32493, -1, 27845, 32495, 30684, -1, 32496, 32497, 32494, -1, 32495, 32497, 30684, -1, 32494, 32497, 32495, -1, 30684, 32498, 30686, -1, 32484, 32498, 32496, -1, 32496, 32498, 32497, -1, 32497, 32498, 30684, -1, 30686, 32498, 32484, -1, 28883, 32499, 28844, -1, 28844, 32499, 32483, -1, 32483, 32500, 32486, -1, 32499, 32500, 32483, -1, 32486, 32501, 32488, -1, 32500, 32501, 32486, -1, 32488, 32502, 32490, -1, 32501, 32502, 32488, -1, 32490, 32503, 32492, -1, 32502, 32503, 32490, -1, 32492, 32504, 32494, -1, 32503, 32504, 32492, -1, 32494, 32505, 32496, -1, 32504, 32505, 32494, -1, 32496, 32506, 32484, -1, 32505, 32506, 32496, -1, 32484, 29478, 29475, -1, 32506, 29478, 32484, -1, 32507, 32508, 32509, -1, 32510, 32511, 32512, -1, 32512, 32511, 32513, -1, 29478, 32506, 30404, -1, 32501, 32514, 32502, -1, 32502, 32514, 32515, -1, 32515, 32516, 32507, -1, 32507, 32516, 32508, -1, 30410, 32517, 29480, -1, 29480, 32517, 32518, -1, 32513, 32517, 30410, -1, 32510, 32519, 32511, -1, 32508, 32519, 32510, -1, 32500, 32520, 32501, -1, 32501, 32520, 32514, -1, 32518, 32521, 32522, -1, 32517, 32521, 32518, -1, 32511, 32521, 32513, -1, 32513, 32521, 32517, -1, 32515, 32523, 32516, -1, 32514, 32523, 32515, -1, 32516, 32524, 32508, -1, 32508, 32524, 32519, -1, 28883, 28896, 32499, -1, 32522, 32525, 32526, -1, 32519, 32525, 32511, -1, 32521, 32525, 32522, -1, 32511, 32525, 32521, -1, 32499, 32527, 32500, -1, 32500, 32527, 32520, -1, 28896, 32527, 32499, -1, 32520, 32528, 32514, -1, 32514, 32528, 32523, -1, 32516, 32529, 32524, -1, 32523, 32529, 32516, -1, 32524, 32530, 32519, -1, 32526, 32530, 32531, -1, 32519, 32530, 32525, -1, 32525, 32530, 32526, -1, 32527, 32532, 32520, -1, 28900, 32532, 28896, -1, 28905, 32532, 28900, -1, 28896, 32532, 32527, -1, 32520, 32532, 32528, -1, 32528, 32533, 32523, -1, 32523, 32533, 32529, -1, 28928, 28933, 32534, -1, 30404, 32535, 30406, -1, 32529, 32536, 32524, -1, 32530, 32536, 32531, -1, 32524, 32536, 32530, -1, 32506, 32535, 30404, -1, 28914, 32537, 28905, -1, 28905, 32537, 32532, -1, 32528, 32537, 32533, -1, 32532, 32537, 32528, -1, 32505, 32509, 32506, -1, 32531, 32538, 32539, -1, 32533, 32538, 32529, -1, 32506, 32509, 32535, -1, 32529, 32538, 32536, -1, 30406, 32512, 30408, -1, 32536, 32538, 32531, -1, 32535, 32512, 30406, -1, 32539, 32540, 32534, -1, 28928, 32540, 28914, -1, 28914, 32540, 32537, -1, 32538, 32540, 32539, -1, 32537, 32540, 32533, -1, 32533, 32540, 32538, -1, 32534, 32540, 28928, -1, 32504, 32507, 32505, -1, 32505, 32507, 32509, -1, 32535, 32510, 32512, -1, 32509, 32510, 32535, -1, 30408, 32513, 30410, -1, 32512, 32513, 30408, -1, 32502, 32515, 32503, -1, 32503, 32515, 32504, -1, 32504, 32515, 32507, -1, 32509, 32508, 32510, -1, 28933, 28932, 32534, -1, 32534, 32541, 32539, -1, 28932, 32541, 32534, -1, 32539, 32542, 32531, -1, 32541, 32542, 32539, -1, 32531, 32543, 32526, -1, 32542, 32543, 32531, -1, 32526, 32544, 32522, -1, 32543, 32544, 32526, -1, 32522, 32545, 32518, -1, 32544, 32545, 32522, -1, 32545, 32546, 32518, -1, 32518, 29481, 29480, -1, 32546, 29481, 32518, -1, 26005, 32547, 26008, -1, 32548, 32547, 26005, -1, 32549, 32547, 32548, -1, 32550, 32551, 32552, -1, 32552, 32551, 32553, -1, 28966, 32554, 28964, -1, 32555, 32554, 32556, -1, 32557, 32558, 32550, -1, 32559, 32554, 32555, -1, 28964, 32554, 32559, -1, 32546, 30425, 29481, -1, 32550, 32558, 32551, -1, 32560, 32561, 32562, -1, 32562, 32561, 32547, -1, 32547, 32561, 26008, -1, 30423, 32563, 30422, -1, 32553, 32563, 30423, -1, 28967, 32564, 28966, -1, 28966, 32564, 32554, -1, 32554, 32564, 32556, -1, 32556, 32564, 32560, -1, 32541, 32565, 32542, -1, 28968, 32566, 28967, -1, 26008, 32566, 26011, -1, 32542, 32565, 32567, -1, 28967, 32566, 32564, -1, 28975, 32565, 32541, -1, 32561, 32566, 26008, -1, 32560, 32566, 32561, -1, 32564, 32566, 32560, -1, 26011, 32566, 28968, -1, 32553, 32568, 32563, -1, 32551, 32568, 32553, -1, 32557, 32569, 32558, -1, 32567, 32569, 32557, -1, 32551, 32570, 32568, -1, 32558, 32570, 32551, -1, 30421, 32571, 30419, -1, 30422, 32571, 30421, -1, 28932, 28975, 32541, -1, 32563, 32571, 30422, -1, 28973, 32572, 28975, -1, 28975, 32572, 32565, -1, 32567, 32572, 32569, -1, 32565, 32572, 32567, -1, 32568, 32573, 32563, -1, 32563, 32573, 32571, -1, 32569, 32574, 32558, -1, 32558, 32574, 32570, -1, 32571, 32575, 30419, -1, 32570, 32576, 32568, -1, 32568, 32576, 32573, -1, 32573, 32577, 32571, -1, 32571, 32577, 32575, -1, 30414, 26003, 26002, -1, 32575, 32578, 30419, -1, 30418, 32578, 30416, -1, 30419, 32578, 30418, -1, 28971, 32579, 28973, -1, 32569, 32579, 32574, -1, 28973, 32579, 32572, -1, 32572, 32579, 32569, -1, 32570, 32555, 32576, -1, 32574, 32555, 32570, -1, 32576, 32580, 32573, -1, 32573, 32580, 32577, -1, 32577, 32549, 32575, -1, 28968, 26013, 26011, -1, 32575, 32549, 32578, -1, 32578, 32581, 30416, -1, 30416, 32581, 30414, -1, 30425, 32552, 30424, -1, 32546, 32552, 30425, -1, 30414, 32581, 26003, -1, 32576, 32556, 32580, -1, 32545, 32550, 32546, -1, 32555, 32556, 32576, -1, 32546, 32550, 32552, -1, 32580, 32562, 32577, -1, 32577, 32562, 32549, -1, 32543, 32557, 32544, -1, 32544, 32557, 32545, -1, 28964, 32559, 28971, -1, 32574, 32559, 32555, -1, 32545, 32557, 32550, -1, 32579, 32559, 32574, -1, 28971, 32559, 32579, -1, 30424, 32553, 30423, -1, 26003, 32548, 26005, -1, 32578, 32548, 32581, -1, 32581, 32548, 26003, -1, 32552, 32553, 30424, -1, 32549, 32548, 32578, -1, 32542, 32567, 32543, -1, 32556, 32560, 32580, -1, 32543, 32567, 32557, -1, 32580, 32560, 32562, -1, 32562, 32547, 32549, -1, 26007, 26006, 29474, -1, 29474, 26006, 32582, -1, 32582, 26009, 32583, -1, 26006, 26009, 32582, -1, 32583, 26010, 32584, -1, 26009, 26010, 32583, -1, 32584, 26012, 32585, -1, 26010, 26012, 32584, -1, 32585, 26014, 28926, -1, 26012, 26014, 32585, -1, 32582, 30690, 29474, -1, 28926, 28912, 32585, -1, 30688, 32586, 27557, -1, 30688, 32587, 32586, -1, 28876, 32588, 30688, -1, 30688, 32588, 32587, -1, 28876, 32589, 32588, -1, 28876, 28875, 32589, -1, 30690, 32590, 30688, -1, 32582, 32590, 30690, -1, 32583, 32591, 32582, -1, 32582, 32591, 32590, -1, 32590, 32591, 30688, -1, 32584, 32592, 32583, -1, 32591, 32592, 30688, -1, 32583, 32592, 32591, -1, 30688, 32592, 28876, -1, 28876, 32593, 28912, -1, 32585, 32593, 32584, -1, 32592, 32593, 28876, -1, 32584, 32593, 32592, -1, 28912, 32593, 32585, -1, 27556, 27557, 32594, -1, 32594, 32586, 32595, -1, 27557, 32586, 32594, -1, 32595, 32587, 28126, -1, 32586, 32587, 32595, -1, 28126, 32588, 28127, -1, 28127, 32588, 28138, -1, 32587, 32588, 28126, -1, 28138, 32589, 28133, -1, 28133, 32589, 28125, -1, 32588, 32589, 28138, -1, 28125, 28875, 28124, -1, 32589, 28875, 28125, -1, 32596, 29031, 29029, -1, 29030, 27862, 27860, -1, 29030, 27864, 27862, -1, 29467, 30694, 32597, -1, 29030, 27867, 27864, -1, 30692, 27875, 27872, -1, 30692, 27878, 27875, -1, 30692, 27562, 27878, -1, 29031, 32598, 29030, -1, 32596, 32598, 29031, -1, 32599, 32600, 32596, -1, 32596, 32600, 32598, -1, 32598, 32600, 29030, -1, 32601, 32602, 32599, -1, 32600, 32602, 29030, -1, 32599, 32602, 32600, -1, 29030, 32602, 27867, -1, 32603, 32604, 32601, -1, 27867, 32604, 27869, -1, 32601, 32604, 32602, -1, 32602, 32604, 27867, -1, 32605, 32606, 32603, -1, 27869, 32606, 27872, -1, 32603, 32606, 32604, -1, 32604, 32606, 27869, -1, 32607, 32608, 32605, -1, 32606, 32608, 27872, -1, 32605, 32608, 32606, -1, 27872, 32608, 30692, -1, 32609, 32610, 32607, -1, 32608, 32610, 30692, -1, 32607, 32610, 32608, -1, 30692, 32611, 30694, -1, 32597, 32611, 32609, -1, 32609, 32611, 32610, -1, 32610, 32611, 30692, -1, 30694, 32611, 32597, -1, 29029, 28820, 32596, -1, 32596, 32612, 32599, -1, 28820, 32612, 32596, -1, 32599, 32613, 32601, -1, 32612, 32613, 32599, -1, 32601, 32614, 32603, -1, 32613, 32614, 32601, -1, 32603, 32615, 32605, -1, 32614, 32615, 32603, -1, 32605, 32616, 32607, -1, 32615, 32616, 32605, -1, 32607, 32617, 32609, -1, 32616, 32617, 32607, -1, 32609, 32618, 32597, -1, 32617, 32618, 32609, -1, 32597, 32619, 29467, -1, 32618, 32619, 32597, -1, 32619, 29470, 29467, -1, 32620, 32621, 32622, -1, 32623, 32624, 32625, -1, 32625, 32624, 32626, -1, 29470, 32619, 30382, -1, 32614, 32627, 32615, -1, 32615, 32627, 32628, -1, 32628, 32629, 32620, -1, 32620, 32629, 32621, -1, 30388, 32630, 29472, -1, 29472, 32630, 32631, -1, 32626, 32630, 30388, -1, 32623, 32632, 32624, -1, 32621, 32632, 32623, -1, 32613, 32633, 32614, -1, 32614, 32633, 32627, -1, 32631, 32634, 32635, -1, 32630, 32634, 32631, -1, 32624, 32634, 32626, -1, 32626, 32634, 32630, -1, 32628, 32636, 32629, -1, 32627, 32636, 32628, -1, 32629, 32637, 32621, -1, 32621, 32637, 32632, -1, 28820, 28826, 32612, -1, 32635, 32638, 32639, -1, 32632, 32638, 32624, -1, 32634, 32638, 32635, -1, 32624, 32638, 32634, -1, 32612, 32640, 32613, -1, 32613, 32640, 32633, -1, 28826, 32640, 32612, -1, 32633, 32641, 32627, -1, 32627, 32641, 32636, -1, 32629, 32642, 32637, -1, 32636, 32642, 32629, -1, 32637, 32643, 32632, -1, 32639, 32643, 32644, -1, 32632, 32643, 32638, -1, 32638, 32643, 32639, -1, 32640, 32645, 32633, -1, 28827, 32645, 28826, -1, 28829, 32645, 28827, -1, 28826, 32645, 32640, -1, 32633, 32645, 32641, -1, 32641, 32646, 32636, -1, 32636, 32646, 32642, -1, 28837, 28843, 32647, -1, 30382, 32648, 30384, -1, 32642, 32649, 32637, -1, 32643, 32649, 32644, -1, 32637, 32649, 32643, -1, 32619, 32648, 30382, -1, 28832, 32650, 28829, -1, 28829, 32650, 32645, -1, 32641, 32650, 32646, -1, 32645, 32650, 32641, -1, 32618, 32622, 32619, -1, 32644, 32651, 32652, -1, 32646, 32651, 32642, -1, 32619, 32622, 32648, -1, 32642, 32651, 32649, -1, 30384, 32625, 30386, -1, 32649, 32651, 32644, -1, 32648, 32625, 30384, -1, 32652, 32653, 32647, -1, 28837, 32653, 28832, -1, 28832, 32653, 32650, -1, 32651, 32653, 32652, -1, 32650, 32653, 32646, -1, 32646, 32653, 32651, -1, 32647, 32653, 28837, -1, 32617, 32620, 32618, -1, 32618, 32620, 32622, -1, 32648, 32623, 32625, -1, 32622, 32623, 32648, -1, 30386, 32626, 30388, -1, 32625, 32626, 30386, -1, 32615, 32628, 32616, -1, 32616, 32628, 32617, -1, 32617, 32628, 32620, -1, 32622, 32621, 32623, -1, 28843, 28927, 32647, -1, 32647, 32654, 32652, -1, 28927, 32654, 32647, -1, 32652, 32655, 32644, -1, 32654, 32655, 32652, -1, 32644, 32656, 32639, -1, 32655, 32656, 32644, -1, 32639, 32657, 32635, -1, 32656, 32657, 32639, -1, 32635, 32658, 32631, -1, 32657, 32658, 32635, -1, 32658, 32659, 32631, -1, 32631, 29473, 29472, -1, 32659, 29473, 32631, -1, 25992, 32660, 25995, -1, 32661, 32660, 25992, -1, 32662, 32660, 32661, -1, 32663, 32664, 32665, -1, 32665, 32664, 32666, -1, 28885, 32667, 28884, -1, 32668, 32667, 32669, -1, 32670, 32671, 32663, -1, 32672, 32667, 32668, -1, 28884, 32667, 32672, -1, 32659, 30403, 29473, -1, 25995, 32673, 25998, -1, 32663, 32671, 32664, -1, 32674, 32673, 32675, -1, 32675, 32673, 32660, -1, 32660, 32673, 25995, -1, 30401, 32676, 30400, -1, 32666, 32676, 30401, -1, 28886, 32677, 28885, -1, 28885, 32677, 32667, -1, 32667, 32677, 32669, -1, 32669, 32677, 32674, -1, 32654, 32678, 32655, -1, 28887, 32679, 28886, -1, 28886, 32679, 32677, -1, 32655, 32678, 32680, -1, 32674, 32679, 32673, -1, 28913, 32678, 32654, -1, 32677, 32679, 32674, -1, 32673, 32679, 25998, -1, 25998, 32679, 28887, -1, 32666, 32681, 32676, -1, 32664, 32681, 32666, -1, 32670, 32682, 32671, -1, 32680, 32682, 32670, -1, 32664, 32683, 32681, -1, 32671, 32683, 32664, -1, 30399, 32684, 30397, -1, 30400, 32684, 30399, -1, 28927, 28913, 32654, -1, 32676, 32684, 30400, -1, 28904, 32685, 28913, -1, 28913, 32685, 32678, -1, 32680, 32685, 32682, -1, 32678, 32685, 32680, -1, 32681, 32686, 32676, -1, 32676, 32686, 32684, -1, 32682, 32687, 32671, -1, 32671, 32687, 32683, -1, 32684, 32688, 30397, -1, 32683, 32689, 32681, -1, 32681, 32689, 32686, -1, 32686, 32690, 32684, -1, 32684, 32690, 32688, -1, 30392, 25990, 25989, -1, 32688, 32691, 30397, -1, 30396, 32691, 30394, -1, 30397, 32691, 30396, -1, 28901, 32692, 28904, -1, 32682, 32692, 32687, -1, 28904, 32692, 32685, -1, 32685, 32692, 32682, -1, 32683, 32668, 32689, -1, 32687, 32668, 32683, -1, 32689, 32693, 32686, -1, 32686, 32693, 32690, -1, 32690, 32662, 32688, -1, 28887, 26000, 25998, -1, 32688, 32662, 32691, -1, 32691, 32694, 30394, -1, 30394, 32694, 30392, -1, 30403, 32665, 30402, -1, 32659, 32665, 30403, -1, 30392, 32694, 25990, -1, 32689, 32669, 32693, -1, 32658, 32663, 32659, -1, 32668, 32669, 32689, -1, 32659, 32663, 32665, -1, 32693, 32675, 32690, -1, 32690, 32675, 32662, -1, 32656, 32670, 32657, -1, 32657, 32670, 32658, -1, 28884, 32672, 28901, -1, 32687, 32672, 32668, -1, 32658, 32670, 32663, -1, 32692, 32672, 32687, -1, 28901, 32672, 32692, -1, 30402, 32666, 30401, -1, 25990, 32661, 25992, -1, 32691, 32661, 32694, -1, 32694, 32661, 25990, -1, 32665, 32666, 30402, -1, 32662, 32661, 32691, -1, 32655, 32680, 32656, -1, 32669, 32674, 32693, -1, 32656, 32680, 32670, -1, 32693, 32674, 32675, -1, 32675, 32660, 32662, -1, 25994, 25993, 29466, -1, 29466, 25993, 32695, -1, 32695, 25996, 32696, -1, 25993, 25996, 32695, -1, 32696, 25997, 32697, -1, 25996, 25997, 32696, -1, 32697, 25999, 32698, -1, 25997, 25999, 32697, -1, 32698, 26001, 28834, -1, 25999, 26001, 32698, -1, 32695, 30698, 29466, -1, 28834, 28835, 32698, -1, 30696, 32699, 27564, -1, 30696, 32700, 32699, -1, 28915, 32701, 30696, -1, 30696, 32701, 32700, -1, 28915, 32702, 32701, -1, 28915, 28916, 32702, -1, 30698, 32703, 30696, -1, 32695, 32703, 30698, -1, 32696, 32704, 32695, -1, 32695, 32704, 32703, -1, 32703, 32704, 30696, -1, 32697, 32705, 32696, -1, 32704, 32705, 30696, -1, 32696, 32705, 32704, -1, 30696, 32705, 28915, -1, 28915, 32706, 28835, -1, 32698, 32706, 32697, -1, 32705, 32706, 28915, -1, 32697, 32706, 32705, -1, 28835, 32706, 32698, -1, 27563, 27564, 27883, -1, 27883, 32699, 27880, -1, 27564, 32699, 27883, -1, 27880, 32700, 27645, -1, 32699, 32700, 27880, -1, 27646, 32701, 27648, -1, 27645, 32701, 27646, -1, 32700, 32701, 27645, -1, 27648, 32702, 27649, -1, 32701, 32702, 27648, -1, 27649, 28916, 27650, -1, 32702, 28916, 27649, -1, 27570, 27571, 32707, -1, 32707, 32708, 32709, -1, 27571, 32708, 32707, -1, 32709, 32710, 28155, -1, 32708, 32710, 32709, -1, 28155, 32711, 28156, -1, 28156, 32711, 28167, -1, 32710, 32711, 28155, -1, 28167, 32712, 28162, -1, 28162, 32712, 28154, -1, 32711, 32712, 28167, -1, 28154, 28919, 28153, -1, 32712, 28919, 28154, -1, 32713, 30706, 29458, -1, 29027, 28918, 32714, -1, 30704, 32708, 27571, -1, 30704, 32710, 32708, -1, 28917, 32711, 30704, -1, 30704, 32711, 32710, -1, 28917, 32712, 32711, -1, 28917, 28919, 32712, -1, 30706, 32715, 30704, -1, 32713, 32715, 30706, -1, 32716, 32717, 32713, -1, 32715, 32717, 30704, -1, 32713, 32717, 32715, -1, 32718, 32719, 32716, -1, 32717, 32719, 30704, -1, 30704, 32719, 28917, -1, 32716, 32719, 32717, -1, 28917, 32720, 28918, -1, 32714, 32720, 32718, -1, 32719, 32720, 28917, -1, 32718, 32720, 32719, -1, 28918, 32720, 32714, -1, 29458, 25981, 32713, -1, 25981, 25980, 32713, -1, 32713, 25983, 32716, -1, 25980, 25983, 32713, -1, 32716, 25984, 32718, -1, 25983, 25984, 32716, -1, 32718, 25986, 32714, -1, 25984, 25986, 32718, -1, 32714, 25988, 29027, -1, 25986, 25988, 32714, -1, 25979, 32721, 25982, -1, 32722, 32721, 32723, -1, 32724, 32725, 32726, -1, 32723, 32721, 25979, -1, 28821, 32727, 28819, -1, 32726, 32725, 32728, -1, 28819, 32727, 32729, -1, 32730, 32727, 32731, -1, 32732, 32733, 32724, -1, 32729, 32727, 32730, -1, 32724, 32733, 32725, -1, 32734, 30381, 29465, -1, 32735, 32736, 32721, -1, 32737, 32736, 32735, -1, 32721, 32736, 25982, -1, 30379, 32738, 30378, -1, 32728, 32738, 30379, -1, 28821, 32739, 32727, -1, 28822, 32739, 28821, -1, 32731, 32739, 32737, -1, 32727, 32739, 32731, -1, 32740, 32741, 32742, -1, 28825, 32743, 28822, -1, 28822, 32743, 32739, -1, 32742, 32741, 32744, -1, 25982, 32743, 25985, -1, 28831, 32741, 32740, -1, 32739, 32743, 32737, -1, 32737, 32743, 32736, -1, 32736, 32743, 25982, -1, 25985, 32743, 28825, -1, 32728, 32745, 32738, -1, 32725, 32745, 32728, -1, 32732, 32746, 32733, -1, 32744, 32746, 32732, -1, 32725, 32747, 32745, -1, 32733, 32747, 32725, -1, 30377, 32748, 30375, -1, 30378, 32748, 30377, -1, 32738, 32748, 30378, -1, 28838, 28831, 32740, -1, 28830, 32749, 28831, -1, 28831, 32749, 32741, -1, 32744, 32749, 32746, -1, 32741, 32749, 32744, -1, 32745, 32750, 32738, -1, 32738, 32750, 32748, -1, 32746, 32751, 32733, -1, 32733, 32751, 32747, -1, 32748, 32752, 30375, -1, 32747, 32753, 32745, -1, 32745, 32753, 32750, -1, 32750, 32754, 32748, -1, 32748, 32754, 32752, -1, 32752, 32755, 30375, -1, 30370, 25977, 25976, -1, 30374, 32755, 30372, -1, 30375, 32755, 30374, -1, 28828, 32756, 28830, -1, 32746, 32756, 32751, -1, 28830, 32756, 32749, -1, 32749, 32756, 32746, -1, 32751, 32730, 32747, -1, 32747, 32730, 32753, -1, 32750, 32757, 32754, -1, 32753, 32757, 32750, -1, 32754, 32722, 32752, -1, 28825, 25987, 25985, -1, 32752, 32722, 32755, -1, 32755, 32758, 30372, -1, 30372, 32758, 30370, -1, 30381, 32726, 30380, -1, 32734, 32726, 30381, -1, 30370, 32758, 25977, -1, 32753, 32731, 32757, -1, 32759, 32724, 32734, -1, 32730, 32731, 32753, -1, 32760, 32724, 32759, -1, 32757, 32735, 32754, -1, 32754, 32735, 32722, -1, 32734, 32724, 32726, -1, 32761, 32732, 32760, -1, 28819, 32729, 28828, -1, 32760, 32732, 32724, -1, 32751, 32729, 32730, -1, 28828, 32729, 32756, -1, 32756, 32729, 32751, -1, 30380, 32728, 30379, -1, 32722, 32723, 32755, -1, 32755, 32723, 32758, -1, 25977, 32723, 25979, -1, 32726, 32728, 30380, -1, 32758, 32723, 25977, -1, 32742, 32744, 32761, -1, 32731, 32737, 32757, -1, 32761, 32744, 32732, -1, 32757, 32737, 32735, -1, 32735, 32721, 32722, -1, 28934, 28838, 32762, -1, 32762, 32740, 32763, -1, 28838, 32740, 32762, -1, 32763, 32742, 32764, -1, 32740, 32742, 32763, -1, 32764, 32761, 32765, -1, 32742, 32761, 32764, -1, 32765, 32760, 32766, -1, 32761, 32760, 32765, -1, 32766, 32759, 32767, -1, 32760, 32759, 32766, -1, 32759, 32734, 32767, -1, 32767, 29465, 29464, -1, 32734, 29465, 32767, -1, 32768, 32769, 32770, -1, 32771, 32769, 32768, -1, 32772, 32773, 32774, -1, 32770, 32773, 32772, -1, 29462, 32775, 30360, -1, 32776, 32777, 32778, -1, 32778, 32777, 32779, -1, 32779, 32780, 32771, -1, 32771, 32780, 32769, -1, 30366, 32781, 29464, -1, 29464, 32781, 32767, -1, 32774, 32781, 30366, -1, 32769, 32782, 32770, -1, 32770, 32782, 32773, -1, 32783, 32784, 32776, -1, 32776, 32784, 32777, -1, 32767, 32785, 32766, -1, 32781, 32785, 32767, -1, 32773, 32785, 32774, -1, 32774, 32785, 32781, -1, 32777, 32786, 32779, -1, 32779, 32786, 32780, -1, 32769, 32787, 32782, -1, 32780, 32787, 32769, -1, 32766, 32788, 32765, -1, 29015, 29020, 32789, -1, 32785, 32788, 32766, -1, 32782, 32788, 32773, -1, 32773, 32788, 32785, -1, 32789, 32790, 32783, -1, 32783, 32790, 32784, -1, 29020, 32790, 32789, -1, 32777, 32791, 32786, -1, 32784, 32791, 32777, -1, 32780, 32792, 32787, -1, 32786, 32792, 32780, -1, 32782, 32793, 32788, -1, 32765, 32793, 32764, -1, 32787, 32793, 32782, -1, 32788, 32793, 32765, -1, 29021, 32794, 29020, -1, 29023, 32794, 29021, -1, 32790, 32794, 32784, -1, 32784, 32794, 32791, -1, 29020, 32794, 32790, -1, 32791, 32795, 32786, -1, 32786, 32795, 32792, -1, 32792, 32796, 32787, -1, 29028, 28934, 32762, -1, 32793, 32796, 32764, -1, 30360, 32797, 30362, -1, 32775, 32797, 30360, -1, 32787, 32796, 32793, -1, 29025, 32798, 29023, -1, 29023, 32798, 32794, -1, 32799, 32768, 32775, -1, 32794, 32798, 32791, -1, 32791, 32798, 32795, -1, 32796, 32800, 32764, -1, 32795, 32800, 32792, -1, 32764, 32800, 32763, -1, 32775, 32768, 32797, -1, 32792, 32800, 32796, -1, 30362, 32772, 30364, -1, 29028, 32801, 29025, -1, 32795, 32801, 32800, -1, 32763, 32801, 32762, -1, 32797, 32772, 30362, -1, 32798, 32801, 32795, -1, 32802, 32771, 32799, -1, 32800, 32801, 32763, -1, 32762, 32801, 29028, -1, 29025, 32801, 32798, -1, 32799, 32771, 32768, -1, 32797, 32770, 32772, -1, 32768, 32770, 32797, -1, 30364, 32774, 30366, -1, 32772, 32774, 30364, -1, 32803, 32779, 32802, -1, 32778, 32779, 32803, -1, 32802, 32779, 32771, -1, 29015, 32789, 28995, -1, 28995, 32789, 32804, -1, 32804, 32783, 32805, -1, 32789, 32783, 32804, -1, 32805, 32776, 32806, -1, 32783, 32776, 32805, -1, 32806, 32778, 32807, -1, 32776, 32778, 32806, -1, 32807, 32803, 32808, -1, 32778, 32803, 32807, -1, 32808, 32802, 32809, -1, 32803, 32802, 32808, -1, 32809, 32799, 32810, -1, 32802, 32799, 32809, -1, 32810, 32775, 32811, -1, 32799, 32775, 32810, -1, 32811, 29462, 29459, -1, 32775, 29462, 32811, -1, 32804, 28997, 28995, -1, 28996, 27895, 27893, -1, 28996, 27898, 27895, -1, 29459, 30710, 32811, -1, 28996, 27901, 27898, -1, 30708, 27909, 27906, -1, 30708, 27912, 27909, -1, 30708, 27569, 27912, -1, 28997, 32812, 28996, -1, 32804, 32812, 28997, -1, 32805, 32813, 32804, -1, 32804, 32813, 32812, -1, 32812, 32813, 28996, -1, 32806, 32814, 32805, -1, 32805, 32814, 32813, -1, 32813, 32814, 28996, -1, 28996, 32814, 27901, -1, 27901, 32815, 27903, -1, 32807, 32815, 32806, -1, 32806, 32815, 32814, -1, 32814, 32815, 27901, -1, 27903, 32816, 27906, -1, 32808, 32816, 32807, -1, 32815, 32816, 27903, -1, 32807, 32816, 32815, -1, 32809, 32817, 32808, -1, 32816, 32817, 27906, -1, 32808, 32817, 32816, -1, 27906, 32817, 30708, -1, 32810, 32818, 32809, -1, 32817, 32818, 30708, -1, 32809, 32818, 32817, -1, 30708, 32819, 30710, -1, 32811, 32819, 32810, -1, 32810, 32819, 32818, -1, 30710, 32819, 32811, -1, 32818, 32819, 30708, -1, 27577, 27578, 32820, -1, 32820, 32821, 32822, -1, 27578, 32821, 32820, -1, 32822, 32823, 28187, -1, 32821, 32823, 32822, -1, 28187, 32824, 28188, -1, 28188, 32824, 28199, -1, 32823, 32824, 28187, -1, 28199, 32825, 28194, -1, 28194, 32825, 28186, -1, 32824, 32825, 28199, -1, 28186, 28922, 28185, -1, 32825, 28922, 28186, -1, 32826, 30714, 29450, -1, 28993, 28921, 32827, -1, 30712, 32821, 27578, -1, 30712, 32823, 32821, -1, 28920, 32824, 30712, -1, 30712, 32824, 32823, -1, 28920, 32825, 32824, -1, 28920, 28922, 32825, -1, 30714, 32828, 30712, -1, 32826, 32828, 30714, -1, 32829, 32830, 32826, -1, 32828, 32830, 30712, -1, 32826, 32830, 32828, -1, 32831, 32832, 32829, -1, 32830, 32832, 30712, -1, 30712, 32832, 28920, -1, 32829, 32832, 32830, -1, 28920, 32833, 28921, -1, 32827, 32833, 32831, -1, 32832, 32833, 28920, -1, 32831, 32833, 32832, -1, 28921, 32833, 32827, -1, 29450, 25968, 32826, -1, 32826, 25967, 32829, -1, 25968, 25967, 32826, -1, 32829, 25970, 32831, -1, 25967, 25970, 32829, -1, 32831, 25971, 32827, -1, 25970, 25971, 32831, -1, 32827, 25973, 28993, -1, 25971, 25973, 32827, -1, 25973, 25975, 28993, -1, 25966, 32834, 25969, -1, 32835, 32834, 25966, -1, 32836, 32834, 32835, -1, 32837, 32838, 32839, -1, 32839, 32838, 32840, -1, 29017, 32841, 29016, -1, 32842, 32841, 32843, -1, 32844, 32845, 32837, -1, 32846, 32841, 32842, -1, 29016, 32841, 32846, -1, 32847, 30359, 29457, -1, 32837, 32845, 32838, -1, 32848, 32849, 32850, -1, 32850, 32849, 32834, -1, 32834, 32849, 25969, -1, 30357, 32851, 30356, -1, 32840, 32851, 30357, -1, 29018, 32852, 29017, -1, 29017, 32852, 32841, -1, 32841, 32852, 32843, -1, 32843, 32852, 32848, -1, 32853, 32854, 32855, -1, 29019, 32856, 29018, -1, 25969, 32856, 25972, -1, 32855, 32854, 32857, -1, 29018, 32856, 32852, -1, 29026, 32854, 32853, -1, 32849, 32856, 25969, -1, 32848, 32856, 32849, -1, 32852, 32856, 32848, -1, 25972, 32856, 29019, -1, 32840, 32858, 32851, -1, 32838, 32858, 32840, -1, 32844, 32859, 32845, -1, 32857, 32859, 32844, -1, 32838, 32860, 32858, -1, 32845, 32860, 32838, -1, 30355, 32861, 30353, -1, 30356, 32861, 30355, -1, 28935, 29026, 32853, -1, 32851, 32861, 30356, -1, 29024, 32862, 29026, -1, 29026, 32862, 32854, -1, 32857, 32862, 32859, -1, 32854, 32862, 32857, -1, 32858, 32863, 32851, -1, 32851, 32863, 32861, -1, 32859, 32864, 32845, -1, 32845, 32864, 32860, -1, 32861, 32865, 30353, -1, 32860, 32866, 32858, -1, 32858, 32866, 32863, -1, 32863, 32867, 32861, -1, 32861, 32867, 32865, -1, 30348, 25964, 25963, -1, 32865, 32868, 30353, -1, 30352, 32868, 30350, -1, 30353, 32868, 30352, -1, 29022, 32869, 29024, -1, 32859, 32869, 32864, -1, 29024, 32869, 32862, -1, 32862, 32869, 32859, -1, 32860, 32842, 32866, -1, 32864, 32842, 32860, -1, 32866, 32870, 32863, -1, 32863, 32870, 32867, -1, 32867, 32836, 32865, -1, 29019, 25974, 25972, -1, 32865, 32836, 32868, -1, 32868, 32871, 30350, -1, 30350, 32871, 30348, -1, 30359, 32839, 30358, -1, 32847, 32839, 30359, -1, 30348, 32871, 25964, -1, 32866, 32843, 32870, -1, 32872, 32837, 32847, -1, 32842, 32843, 32866, -1, 32847, 32837, 32839, -1, 32870, 32850, 32867, -1, 32867, 32850, 32836, -1, 32873, 32844, 32872, -1, 32874, 32844, 32873, -1, 29016, 32846, 29022, -1, 32872, 32844, 32837, -1, 32864, 32846, 32842, -1, 32869, 32846, 32864, -1, 29022, 32846, 32869, -1, 30358, 32840, 30357, -1, 25964, 32835, 25966, -1, 32868, 32835, 32871, -1, 32871, 32835, 25964, -1, 32839, 32840, 30358, -1, 32836, 32835, 32868, -1, 32855, 32857, 32874, -1, 32843, 32848, 32870, -1, 32874, 32857, 32844, -1, 32870, 32848, 32850, -1, 32850, 32834, 32836, -1, 28935, 32853, 28936, -1, 28936, 32853, 32875, -1, 32875, 32855, 32876, -1, 32853, 32855, 32875, -1, 32876, 32874, 32877, -1, 32855, 32874, 32876, -1, 32877, 32873, 32878, -1, 32874, 32873, 32877, -1, 32879, 32872, 32880, -1, 32878, 32872, 32879, -1, 32873, 32872, 32878, -1, 32880, 32847, 29456, -1, 32872, 32847, 32880, -1, 32847, 29457, 29456, -1, 32881, 32882, 32883, -1, 32884, 32882, 32881, -1, 32885, 32886, 32887, -1, 32883, 32886, 32885, -1, 29454, 32888, 30338, -1, 32889, 32890, 32891, -1, 32891, 32890, 32892, -1, 32892, 32893, 32884, -1, 32884, 32893, 32882, -1, 30344, 32894, 29456, -1, 29456, 32894, 32880, -1, 32887, 32894, 30344, -1, 32882, 32895, 32883, -1, 32883, 32895, 32886, -1, 32896, 32897, 32889, -1, 32889, 32897, 32890, -1, 32880, 32898, 32879, -1, 32894, 32898, 32880, -1, 32886, 32898, 32887, -1, 32887, 32898, 32894, -1, 32890, 32899, 32892, -1, 32892, 32899, 32893, -1, 32882, 32900, 32895, -1, 32893, 32900, 32882, -1, 32879, 32901, 32878, -1, 28981, 28986, 32902, -1, 32898, 32901, 32879, -1, 32895, 32901, 32886, -1, 32886, 32901, 32898, -1, 32902, 32903, 32896, -1, 32896, 32903, 32897, -1, 28986, 32903, 32902, -1, 32890, 32904, 32899, -1, 32897, 32904, 32890, -1, 32893, 32905, 32900, -1, 32899, 32905, 32893, -1, 32895, 32906, 32901, -1, 32878, 32906, 32877, -1, 32900, 32906, 32895, -1, 32901, 32906, 32878, -1, 28988, 32907, 28986, -1, 28990, 32907, 28988, -1, 32903, 32907, 32897, -1, 32897, 32907, 32904, -1, 28986, 32907, 32903, -1, 32904, 32908, 32899, -1, 32899, 32908, 32905, -1, 32905, 32909, 32900, -1, 28994, 28936, 32875, -1, 32906, 32909, 32877, -1, 30338, 32910, 30340, -1, 32888, 32910, 30338, -1, 32900, 32909, 32906, -1, 28992, 32911, 28990, -1, 28990, 32911, 32907, -1, 32912, 32881, 32888, -1, 32907, 32911, 32904, -1, 32904, 32911, 32908, -1, 32909, 32913, 32877, -1, 32908, 32913, 32905, -1, 32877, 32913, 32876, -1, 32888, 32881, 32910, -1, 32905, 32913, 32909, -1, 30340, 32885, 30342, -1, 28994, 32914, 28992, -1, 32908, 32914, 32913, -1, 32876, 32914, 32875, -1, 32910, 32885, 30340, -1, 32911, 32914, 32908, -1, 32915, 32884, 32912, -1, 32913, 32914, 32876, -1, 32875, 32914, 28994, -1, 28992, 32914, 32911, -1, 32912, 32884, 32881, -1, 32910, 32883, 32885, -1, 32881, 32883, 32910, -1, 30342, 32887, 30344, -1, 32885, 32887, 30342, -1, 32916, 32892, 32915, -1, 32891, 32892, 32916, -1, 32915, 32892, 32884, -1, 28961, 28981, 32917, -1, 32917, 32902, 32918, -1, 28981, 32902, 32917, -1, 32918, 32896, 32919, -1, 32902, 32896, 32918, -1, 32919, 32889, 32920, -1, 32896, 32889, 32919, -1, 32920, 32891, 32921, -1, 32889, 32891, 32920, -1, 32921, 32916, 32922, -1, 32891, 32916, 32921, -1, 32922, 32915, 32923, -1, 32916, 32915, 32922, -1, 32923, 32912, 32924, -1, 32915, 32912, 32923, -1, 32912, 32888, 32924, -1, 32924, 29454, 29451, -1, 32888, 29454, 32924, -1, 32917, 28963, 28961, -1, 28962, 27923, 27921, -1, 28962, 27926, 27923, -1, 29451, 30718, 32924, -1, 28962, 27929, 27926, -1, 30716, 27937, 27934, -1, 30716, 27940, 27937, -1, 30716, 27576, 27940, -1, 28963, 32925, 28962, -1, 32917, 32925, 28963, -1, 32918, 32926, 32917, -1, 32917, 32926, 32925, -1, 32925, 32926, 28962, -1, 32919, 32927, 32918, -1, 32918, 32927, 32926, -1, 32926, 32927, 28962, -1, 28962, 32927, 27929, -1, 27929, 32928, 27931, -1, 32920, 32928, 32919, -1, 32919, 32928, 32927, -1, 32927, 32928, 27929, -1, 27931, 32929, 27934, -1, 32921, 32929, 32920, -1, 32928, 32929, 27931, -1, 32920, 32929, 32928, -1, 32922, 32930, 32921, -1, 32929, 32930, 27934, -1, 32921, 32930, 32929, -1, 27934, 32930, 30716, -1, 32923, 32931, 32922, -1, 32930, 32931, 30716, -1, 32922, 32931, 32930, -1, 30716, 32932, 30718, -1, 32924, 32932, 32923, -1, 32923, 32932, 32931, -1, 30718, 32932, 32924, -1, 32931, 32932, 30716, -1, 32933, 28879, 28877, -1, 28878, 27954, 27952, -1, 28878, 27956, 27954, -1, 28724, 30635, 32934, -1, 28878, 27959, 27956, -1, 30633, 27967, 27964, -1, 30633, 27970, 27967, -1, 30633, 27469, 27970, -1, 28879, 32935, 28878, -1, 32933, 32935, 28879, -1, 32936, 32937, 32933, -1, 32933, 32937, 32935, -1, 32935, 32937, 28878, -1, 32938, 32939, 32936, -1, 32937, 32939, 28878, -1, 32936, 32939, 32937, -1, 28878, 32939, 27959, -1, 32940, 32941, 32938, -1, 27959, 32941, 27961, -1, 32938, 32941, 32939, -1, 32939, 32941, 27959, -1, 32942, 32943, 32940, -1, 27961, 32943, 27964, -1, 32940, 32943, 32941, -1, 32941, 32943, 27961, -1, 32944, 32945, 32942, -1, 32943, 32945, 27964, -1, 32942, 32945, 32943, -1, 27964, 32945, 30633, -1, 32946, 32947, 32944, -1, 32945, 32947, 30633, -1, 32944, 32947, 32945, -1, 30633, 32948, 30635, -1, 32934, 32948, 32946, -1, 32946, 32948, 32947, -1, 32947, 32948, 30633, -1, 30635, 32948, 32934, -1, 28947, 32949, 28877, -1, 28877, 32949, 32933, -1, 32933, 32950, 32936, -1, 32949, 32950, 32933, -1, 32936, 32951, 32938, -1, 32950, 32951, 32936, -1, 32938, 32952, 32940, -1, 32951, 32952, 32938, -1, 32940, 32953, 32942, -1, 32952, 32953, 32940, -1, 32942, 32954, 32944, -1, 32953, 32954, 32942, -1, 32944, 32955, 32946, -1, 32954, 32955, 32944, -1, 32946, 32956, 32934, -1, 32955, 32956, 32946, -1, 32934, 28730, 28724, -1, 32956, 28730, 32934, -1, 32957, 32958, 32959, -1, 32960, 32961, 32962, -1, 32962, 32961, 32963, -1, 28730, 32956, 30316, -1, 32951, 32964, 32952, -1, 32952, 32964, 32965, -1, 32965, 32966, 32957, -1, 32957, 32966, 32958, -1, 30322, 32967, 29448, -1, 29448, 32967, 32968, -1, 32963, 32967, 30322, -1, 32958, 32969, 32960, -1, 32960, 32969, 32961, -1, 32950, 32970, 32951, -1, 32951, 32970, 32964, -1, 32968, 32971, 32972, -1, 32961, 32971, 32963, -1, 32967, 32971, 32968, -1, 32963, 32971, 32967, -1, 32965, 32973, 32966, -1, 32964, 32973, 32965, -1, 32966, 32974, 32958, -1, 32958, 32974, 32969, -1, 28947, 28952, 32949, -1, 32972, 32975, 32976, -1, 32961, 32975, 32971, -1, 32969, 32975, 32961, -1, 32971, 32975, 32972, -1, 32949, 32977, 32950, -1, 32950, 32977, 32970, -1, 28952, 32977, 32949, -1, 32970, 32978, 32964, -1, 32964, 32978, 32973, -1, 32966, 32979, 32974, -1, 32973, 32979, 32966, -1, 32974, 32980, 32969, -1, 32976, 32980, 32981, -1, 32969, 32980, 32975, -1, 32975, 32980, 32976, -1, 32977, 32982, 32970, -1, 28953, 32982, 28952, -1, 28955, 32982, 28953, -1, 28952, 32982, 32977, -1, 32970, 32982, 32978, -1, 32978, 32983, 32973, -1, 32973, 32983, 32979, -1, 28960, 28938, 32984, -1, 30316, 32985, 30318, -1, 32979, 32986, 32974, -1, 32980, 32986, 32981, -1, 32974, 32986, 32980, -1, 32956, 32985, 30316, -1, 28957, 32987, 28955, -1, 28955, 32987, 32982, -1, 32978, 32987, 32983, -1, 32982, 32987, 32978, -1, 32955, 32959, 32956, -1, 32981, 32988, 32989, -1, 32983, 32988, 32979, -1, 32956, 32959, 32985, -1, 32979, 32988, 32986, -1, 30318, 32962, 30320, -1, 32986, 32988, 32981, -1, 32985, 32962, 30318, -1, 32989, 32990, 32984, -1, 28960, 32990, 28957, -1, 28957, 32990, 32987, -1, 32988, 32990, 32989, -1, 32987, 32990, 32983, -1, 32983, 32990, 32988, -1, 32984, 32990, 28960, -1, 32954, 32957, 32955, -1, 32955, 32957, 32959, -1, 32985, 32960, 32962, -1, 32959, 32960, 32985, -1, 30320, 32963, 30322, -1, 32962, 32963, 30320, -1, 32952, 32965, 32953, -1, 32953, 32965, 32954, -1, 32954, 32965, 32957, -1, 32959, 32958, 32960, -1, 28938, 28937, 32984, -1, 28937, 32991, 32984, -1, 32984, 32992, 32989, -1, 32991, 32992, 32984, -1, 32989, 32993, 32981, -1, 32992, 32993, 32989, -1, 32981, 32994, 32976, -1, 32993, 32994, 32981, -1, 32976, 32995, 32972, -1, 32994, 32995, 32976, -1, 32972, 32996, 32968, -1, 32995, 32996, 32972, -1, 32968, 29449, 29448, -1, 32996, 29449, 32968, -1, 25953, 32997, 25957, -1, 32998, 32997, 25953, -1, 32999, 32997, 32998, -1, 33000, 33001, 33002, -1, 33002, 33001, 33003, -1, 28983, 33004, 28982, -1, 33005, 33004, 33006, -1, 33007, 33008, 33000, -1, 33009, 33004, 33005, -1, 28982, 33004, 33009, -1, 32996, 30337, 29449, -1, 25957, 33010, 25959, -1, 33000, 33008, 33001, -1, 33011, 33010, 33012, -1, 33012, 33010, 32997, -1, 32997, 33010, 25957, -1, 30335, 33013, 30334, -1, 33003, 33013, 30335, -1, 28984, 33014, 28983, -1, 28983, 33014, 33004, -1, 33004, 33014, 33006, -1, 33006, 33014, 33011, -1, 32991, 33015, 32992, -1, 28985, 33016, 28984, -1, 28984, 33016, 33014, -1, 32992, 33015, 33017, -1, 33011, 33016, 33010, -1, 28991, 33015, 32991, -1, 33014, 33016, 33011, -1, 33010, 33016, 25959, -1, 25959, 33016, 28985, -1, 33003, 33018, 33013, -1, 33001, 33018, 33003, -1, 33007, 33019, 33008, -1, 33017, 33019, 33007, -1, 33001, 33020, 33018, -1, 33008, 33020, 33001, -1, 30333, 33021, 30331, -1, 30334, 33021, 30333, -1, 28937, 28991, 32991, -1, 33013, 33021, 30334, -1, 28989, 33022, 28991, -1, 28991, 33022, 33015, -1, 33017, 33022, 33019, -1, 33015, 33022, 33017, -1, 33018, 33023, 33013, -1, 33013, 33023, 33021, -1, 33019, 33024, 33008, -1, 33008, 33024, 33020, -1, 33021, 33025, 30331, -1, 33020, 33026, 33018, -1, 33018, 33026, 33023, -1, 33023, 33027, 33021, -1, 33021, 33027, 33025, -1, 30326, 25951, 25950, -1, 33025, 33028, 30331, -1, 30330, 33028, 30328, -1, 30331, 33028, 30330, -1, 28987, 33029, 28989, -1, 33019, 33029, 33024, -1, 28989, 33029, 33022, -1, 33022, 33029, 33019, -1, 33020, 33005, 33026, -1, 33024, 33005, 33020, -1, 33026, 33030, 33023, -1, 33023, 33030, 33027, -1, 33027, 32999, 33025, -1, 28985, 25961, 25959, -1, 33025, 32999, 33028, -1, 33028, 33031, 30328, -1, 30328, 33031, 30326, -1, 30337, 33002, 30336, -1, 32996, 33002, 30337, -1, 30326, 33031, 25951, -1, 33026, 33006, 33030, -1, 32995, 33000, 32996, -1, 33005, 33006, 33026, -1, 32996, 33000, 33002, -1, 33030, 33012, 33027, -1, 33027, 33012, 32999, -1, 32993, 33007, 32994, -1, 32994, 33007, 32995, -1, 28982, 33009, 28987, -1, 33024, 33009, 33005, -1, 32995, 33007, 33000, -1, 33029, 33009, 33024, -1, 28987, 33009, 33029, -1, 30336, 33003, 30335, -1, 25951, 32998, 25953, -1, 33028, 32998, 33031, -1, 33031, 32998, 25951, -1, 33002, 33003, 30336, -1, 32999, 32998, 33028, -1, 32992, 33017, 32993, -1, 33006, 33011, 33030, -1, 32993, 33017, 33007, -1, 33030, 33011, 33012, -1, 33012, 32997, 32999, -1, 29446, 25955, 33032, -1, 33032, 25954, 33033, -1, 25955, 25954, 33032, -1, 33033, 25956, 33034, -1, 25954, 25956, 33033, -1, 33034, 25958, 33035, -1, 25956, 25958, 33034, -1, 33035, 25960, 28959, -1, 25958, 25960, 33035, -1, 25960, 25962, 28959, -1, 33032, 30702, 29446, -1, 28959, 28924, 33035, -1, 30700, 33036, 27581, -1, 30700, 33037, 33036, -1, 28923, 33038, 30700, -1, 30700, 33038, 33037, -1, 28923, 33039, 33038, -1, 28923, 28925, 33039, -1, 30702, 33040, 30700, -1, 33032, 33040, 30702, -1, 33033, 33041, 33032, -1, 33032, 33041, 33040, -1, 33040, 33041, 30700, -1, 33034, 33042, 33033, -1, 33041, 33042, 30700, -1, 33033, 33042, 33041, -1, 30700, 33042, 28923, -1, 28923, 33043, 28924, -1, 33035, 33043, 33034, -1, 33042, 33043, 28923, -1, 33034, 33043, 33042, -1, 28924, 33043, 33035, -1, 27580, 27581, 33044, -1, 33044, 33036, 33045, -1, 27581, 33036, 33044, -1, 33045, 33037, 28219, -1, 33036, 33037, 33045, -1, 28219, 33038, 28220, -1, 28220, 33038, 28231, -1, 33037, 33038, 28219, -1, 28231, 33039, 28226, -1, 28226, 33039, 28218, -1, 33038, 33039, 28231, -1, 28218, 28925, 28217, -1, 33039, 28925, 28218, -1, 27463, 27462, 33046, -1, 33046, 33047, 33048, -1, 27462, 33047, 33046, -1, 33048, 33049, 28279, -1, 33047, 33049, 33048, -1, 28279, 33050, 28280, -1, 28280, 33050, 28291, -1, 33049, 33050, 28279, -1, 28291, 33051, 28286, -1, 28286, 33051, 28278, -1, 33050, 33051, 28291, -1, 28278, 28851, 28277, -1, 33051, 28851, 28278, -1, 33052, 30641, 28716, -1, 28869, 28870, 33053, -1, 30639, 33047, 27462, -1, 30639, 33049, 33047, -1, 28853, 33050, 30639, -1, 30639, 33050, 33049, -1, 28853, 33051, 33050, -1, 28853, 28851, 33051, -1, 30641, 33054, 30639, -1, 33052, 33054, 30641, -1, 33055, 33056, 33052, -1, 33054, 33056, 30639, -1, 33052, 33056, 33054, -1, 33057, 33058, 33055, -1, 33056, 33058, 30639, -1, 30639, 33058, 28853, -1, 33055, 33058, 33056, -1, 28853, 33059, 28870, -1, 33053, 33059, 33057, -1, 33058, 33059, 28853, -1, 33057, 33059, 33058, -1, 28870, 33059, 33053, -1, 28723, 33060, 28716, -1, 28716, 33060, 33052, -1, 33052, 33061, 33055, -1, 33060, 33061, 33052, -1, 33055, 33062, 33057, -1, 33061, 33062, 33055, -1, 33057, 33063, 33053, -1, 33062, 33063, 33057, -1, 33053, 28898, 28869, -1, 33063, 28898, 33053, -1, 33064, 33065, 33066, -1, 33067, 33068, 30302, -1, 25940, 33069, 25938, -1, 33070, 33071, 33072, -1, 33072, 33071, 33073, -1, 25938, 33069, 33074, -1, 33073, 33075, 30313, -1, 30313, 33075, 30315, -1, 33074, 33076, 33067, -1, 33067, 33076, 33068, -1, 33077, 33078, 33070, -1, 25942, 33079, 25940, -1, 33080, 33078, 33077, -1, 33081, 30300, 29443, -1, 25940, 33079, 33069, -1, 33082, 30300, 33081, -1, 25934, 30300, 33082, -1, 33066, 33083, 33084, -1, 33084, 33083, 33080, -1, 30303, 33085, 30305, -1, 33068, 33085, 30303, -1, 28946, 33086, 33087, -1, 33087, 33086, 33088, -1, 33074, 33089, 33076, -1, 33088, 33086, 33065, -1, 33060, 33090, 33061, -1, 33075, 33090, 30315, -1, 33069, 33089, 33074, -1, 33071, 33090, 33073, -1, 25944, 33091, 25942, -1, 33073, 33090, 33075, -1, 25942, 33091, 33079, -1, 30315, 33090, 33060, -1, 33070, 33092, 33071, -1, 33085, 33093, 30305, -1, 33078, 33092, 33070, -1, 33068, 33093, 33085, -1, 33076, 33093, 33068, -1, 33065, 33094, 33066, -1, 28958, 33095, 25949, -1, 33066, 33094, 33083, -1, 28956, 33095, 28958, -1, 25946, 33095, 25944, -1, 25949, 33095, 25946, -1, 25944, 33095, 33091, -1, 33069, 33096, 33089, -1, 33083, 33097, 33080, -1, 33079, 33096, 33069, -1, 33080, 33097, 33078, -1, 28948, 33098, 28946, -1, 33065, 33098, 33094, -1, 30305, 33099, 30306, -1, 28946, 33098, 33086, -1, 33086, 33098, 33065, -1, 33089, 33100, 33076, -1, 33090, 33101, 33061, -1, 33071, 33101, 33090, -1, 33092, 33101, 33071, -1, 33076, 33100, 33093, -1, 33083, 33102, 33097, -1, 33079, 33103, 33096, -1, 33094, 33102, 33083, -1, 33091, 33103, 33079, -1, 33078, 33104, 33092, -1, 33097, 33104, 33078, -1, 30305, 33105, 33099, -1, 33093, 33105, 30305, -1, 33099, 33105, 30306, -1, 28949, 33106, 28948, -1, 28948, 33106, 33098, -1, 33091, 33107, 33103, -1, 33098, 33106, 33094, -1, 33095, 33107, 33091, -1, 33094, 33106, 33102, -1, 28956, 33107, 33095, -1, 33089, 33064, 33100, -1, 33096, 33064, 33089, -1, 33097, 33108, 33104, -1, 33102, 33108, 33097, -1, 30306, 33109, 30308, -1, 33061, 33110, 33062, -1, 33104, 33110, 33092, -1, 33092, 33110, 33101, -1, 33093, 33084, 33105, -1, 33101, 33110, 33061, -1, 28950, 33111, 28949, -1, 33100, 33084, 33093, -1, 28949, 33111, 33106, -1, 33106, 33111, 33102, -1, 33102, 33111, 33108, -1, 33096, 33088, 33064, -1, 33062, 33112, 33063, -1, 33104, 33112, 33110, -1, 33103, 33088, 33096, -1, 30315, 33060, 28723, -1, 33110, 33112, 33062, -1, 33108, 33112, 33104, -1, 30306, 33077, 33109, -1, 33063, 33113, 28951, -1, 33108, 33113, 33112, -1, 28951, 33113, 28950, -1, 33111, 33113, 33108, -1, 33105, 33077, 30306, -1, 33112, 33113, 33063, -1, 28950, 33113, 33111, -1, 33109, 33072, 30308, -1, 30310, 33072, 30311, -1, 30308, 33072, 30310, -1, 28954, 33087, 28956, -1, 28946, 33087, 28954, -1, 33107, 33087, 33103, -1, 28956, 33087, 33107, -1, 33103, 33087, 33088, -1, 33064, 33066, 33100, -1, 33100, 33066, 33084, -1, 33109, 33070, 33072, -1, 33077, 33070, 33109, -1, 28951, 28898, 33063, -1, 30311, 33073, 30313, -1, 33072, 33073, 30311, -1, 30300, 33067, 30302, -1, 25934, 33067, 30300, -1, 25936, 33074, 25934, -1, 33105, 33080, 33077, -1, 25938, 33074, 25936, -1, 33084, 33080, 33105, -1, 25934, 33074, 33067, -1, 33088, 33065, 33064, -1, 30302, 33068, 30303, -1, 29443, 29442, 33081, -1, 33081, 33114, 33082, -1, 29442, 33114, 33081, -1, 33082, 33115, 25934, -1, 33114, 33115, 33082, -1, 33115, 25935, 25934, -1, 33116, 33117, 33118, -1, 33119, 33117, 25943, -1, 33118, 33117, 33119, -1, 33120, 33121, 33122, -1, 33123, 33121, 33120, -1, 25945, 33124, 25947, -1, 28871, 33124, 28868, -1, 33122, 33121, 33125, -1, 33116, 33124, 33117, -1, 33126, 33124, 33116, -1, 33117, 33124, 25945, -1, 28868, 33124, 33126, -1, 25947, 33124, 28871, -1, 33125, 33127, 33128, -1, 33128, 33127, 33129, -1, 33130, 33131, 33132, -1, 33129, 33131, 33130, -1, 33133, 33134, 33123, -1, 33123, 33134, 33121, -1, 33125, 33135, 33127, -1, 33121, 33135, 33125, -1, 33114, 33136, 33115, -1, 33115, 33136, 25935, -1, 30291, 33136, 33114, -1, 33132, 33136, 30291, -1, 33129, 33137, 33131, -1, 33127, 33137, 33129, -1, 33138, 33139, 33133, -1, 30291, 33114, 29442, -1, 33133, 33139, 33134, -1, 25935, 33140, 25937, -1, 33136, 33140, 25935, -1, 33131, 33140, 33132, -1, 33132, 33140, 33136, -1, 33134, 33141, 33121, -1, 33121, 33141, 33135, -1, 33135, 33142, 33127, -1, 33127, 33142, 33137, -1, 25937, 33143, 25939, -1, 33140, 33143, 25937, -1, 33137, 33143, 33131, -1, 33131, 33143, 33140, -1, 28862, 28863, 33144, -1, 33145, 33146, 33138, -1, 33138, 33146, 33139, -1, 33134, 33147, 33141, -1, 33139, 33147, 33134, -1, 33141, 33148, 33135, -1, 33135, 33148, 33142, -1, 33142, 33149, 33137, -1, 25939, 33149, 25941, -1, 33137, 33149, 33143, -1, 33143, 33149, 25939, -1, 33145, 33150, 33146, -1, 33144, 33150, 33145, -1, 28863, 33150, 33144, -1, 33139, 33151, 33147, -1, 33146, 33151, 33139, -1, 33147, 33118, 33141, -1, 28871, 25948, 25947, -1, 33152, 33153, 29441, -1, 33141, 33118, 33148, -1, 33149, 33154, 25941, -1, 30298, 33153, 30296, -1, 33148, 33154, 33142, -1, 29441, 33153, 30298, -1, 33142, 33154, 33149, -1, 28865, 33155, 28863, -1, 33152, 33128, 33153, -1, 28867, 33155, 28865, -1, 33150, 33155, 33146, -1, 33146, 33155, 33151, -1, 30296, 33130, 30294, -1, 28863, 33155, 33150, -1, 33147, 33116, 33118, -1, 33153, 33130, 30296, -1, 33151, 33116, 33147, -1, 33122, 33125, 33152, -1, 25941, 33119, 25943, -1, 33152, 33125, 33128, -1, 33148, 33119, 33154, -1, 33154, 33119, 25941, -1, 33118, 33119, 33148, -1, 28868, 33126, 28867, -1, 33153, 33129, 33130, -1, 28867, 33126, 33155, -1, 33128, 33129, 33153, -1, 33155, 33126, 33151, -1, 33151, 33126, 33116, -1, 30294, 33132, 30291, -1, 25943, 33117, 25945, -1, 33130, 33132, 30294, -1, 28862, 33144, 28839, -1, 28839, 33144, 33156, -1, 33156, 33145, 33157, -1, 33144, 33145, 33156, -1, 33157, 33138, 33158, -1, 33145, 33138, 33157, -1, 33158, 33133, 33159, -1, 33138, 33133, 33158, -1, 33159, 33123, 33160, -1, 33133, 33123, 33159, -1, 33160, 33120, 33161, -1, 33123, 33120, 33160, -1, 33161, 33122, 33162, -1, 33120, 33122, 33161, -1, 33162, 33152, 33163, -1, 33122, 33152, 33162, -1, 33163, 29441, 29438, -1, 33152, 29441, 33163, -1, 33156, 28841, 28839, -1, 28840, 27987, 27985, -1, 28840, 27990, 27987, -1, 29438, 30722, 33163, -1, 28840, 27993, 27990, -1, 30720, 28001, 27998, -1, 30720, 28004, 28001, -1, 30720, 27523, 28004, -1, 28841, 33164, 28840, -1, 33156, 33164, 28841, -1, 33157, 33165, 33156, -1, 33156, 33165, 33164, -1, 33164, 33165, 28840, -1, 33158, 33166, 33157, -1, 33157, 33166, 33165, -1, 33165, 33166, 28840, -1, 28840, 33166, 27993, -1, 27993, 33167, 27995, -1, 33159, 33167, 33158, -1, 33158, 33167, 33166, -1, 33166, 33167, 27993, -1, 27995, 33168, 27998, -1, 33160, 33168, 33159, -1, 33167, 33168, 27995, -1, 33159, 33168, 33167, -1, 33161, 33169, 33160, -1, 33168, 33169, 27998, -1, 33160, 33169, 33168, -1, 27998, 33169, 30720, -1, 33162, 33170, 33161, -1, 33169, 33170, 30720, -1, 33161, 33170, 33169, -1, 30720, 33171, 30722, -1, 33163, 33171, 33162, -1, 33162, 33171, 33170, -1, 30722, 33171, 33163, -1, 33170, 33171, 30720, -1, 33172, 28874, 28872, -1, 29515, 30645, 33173, -1, 28873, 28007, 28006, -1, 28873, 28010, 28007, -1, 30643, 28023, 28020, -1, 30643, 27519, 28023, -1, 28874, 33174, 28873, -1, 33172, 33174, 28874, -1, 33175, 33176, 33172, -1, 33172, 33176, 33174, -1, 33174, 33176, 28873, -1, 33177, 33178, 33175, -1, 33175, 33178, 33176, -1, 33179, 33180, 33177, -1, 33177, 33180, 33178, -1, 33181, 33182, 33179, -1, 33179, 33182, 33180, -1, 33183, 33184, 33181, -1, 33181, 33184, 33182, -1, 33185, 33186, 33183, -1, 33183, 33186, 33184, -1, 30643, 33187, 30645, -1, 33173, 33187, 33185, -1, 33185, 33187, 33186, -1, 30645, 33187, 33173, -1, 33186, 33187, 30643, -1, 28010, 33188, 28012, -1, 28012, 33188, 28014, -1, 28014, 33188, 28017, -1, 28017, 33188, 28020, -1, 33184, 33188, 33182, -1, 33180, 33188, 33178, -1, 33178, 33188, 33176, -1, 33186, 33188, 33184, -1, 33182, 33188, 33180, -1, 28873, 33188, 28010, -1, 33176, 33188, 28873, -1, 30643, 33188, 33186, -1, 28020, 33188, 30643, -1, 28872, 28899, 33172, -1, 33172, 29126, 33175, -1, 28899, 29126, 33172, -1, 33175, 29125, 33177, -1, 29126, 29125, 33175, -1, 33177, 29123, 33179, -1, 29125, 29123, 33177, -1, 33179, 29119, 33181, -1, 29123, 29119, 33179, -1, 33181, 29121, 33183, -1, 29119, 29121, 33181, -1, 33183, 29115, 33185, -1, 29121, 29115, 33183, -1, 29115, 29116, 33185, -1, 33185, 29117, 33173, -1, 29116, 29117, 33185, -1, 33173, 29118, 29515, -1, 29117, 29118, 33173, -1, 29118, 29114, 29515, -1, 27800, 27535, 32368, -1, 27798, 32368, 32369, -1, 27798, 27800, 32368, -1, 28041, 32369, 28039, -1, 28041, 27798, 32369, -1, 28049, 27798, 28041, -1, 27688, 27798, 28049, -1, 27723, 27542, 32059, -1, 27721, 32059, 32060, -1, 27721, 27723, 32059, -1, 28070, 32060, 28068, -1, 28070, 27721, 32060, -1, 28078, 27721, 28070, -1, 27683, 27721, 28078, -1, 27827, 27549, 32481, -1, 32482, 27827, 32481, -1, 27825, 27827, 32482, -1, 28099, 32482, 28097, -1, 28099, 27825, 32482, -1, 28107, 27825, 28099, -1, 27678, 27825, 28107, -1, 27856, 27556, 32594, -1, 27854, 32594, 32595, -1, 27854, 27856, 32594, -1, 28128, 32595, 28126, -1, 28128, 27854, 32595, -1, 28136, 27854, 28128, -1, 27673, 27854, 28136, -1, 27887, 28165, 27653, -1, 27887, 28157, 28165, -1, 32709, 28155, 28157, -1, 32709, 28157, 27887, -1, 27889, 32709, 27887, -1, 32707, 32709, 27889, -1, 27570, 32707, 27889, -1, 27915, 28197, 27658, -1, 27915, 28189, 28197, -1, 32822, 28187, 28189, -1, 32822, 28189, 27915, -1, 32820, 27915, 27917, -1, 32820, 32822, 27915, -1, 27577, 32820, 27917, -1, 27975, 27580, 33044, -1, 27973, 33044, 33045, -1, 27973, 27975, 33044, -1, 28221, 33045, 28219, -1, 28221, 27973, 33045, -1, 28229, 27973, 28221, -1, 27663, 27973, 28229, -1, 31946, 28251, 27642, -1, 31946, 28252, 28251, -1, 31946, 28263, 28252, -1, 27947, 31946, 27642, -1, 31944, 27947, 27949, -1, 27472, 31944, 27949, -1, 33189, 31944, 31946, -1, 33189, 31946, 27947, -1, 33189, 27947, 31944, -1, 27979, 28289, 27668, -1, 27979, 28281, 28289, -1, 33048, 28279, 28281, -1, 33048, 28281, 27979, -1, 33046, 27979, 27981, -1, 33046, 33048, 27979, -1, 27463, 33046, 27981, -1, 30713, 25931, 25933, -1, 30713, 25929, 25931, -1, 27177, 33190, 33191, -1, 27177, 27200, 33190, -1, 27112, 33192, 27114, -1, 30711, 33192, 30713, -1, 27114, 33192, 30711, -1, 27107, 33193, 27108, -1, 27108, 33193, 27112, -1, 27112, 33193, 33192, -1, 33192, 33193, 30713, -1, 33193, 33194, 30713, -1, 27107, 33194, 33193, -1, 28301, 33195, 27107, -1, 27107, 33195, 33194, -1, 28299, 33196, 28301, -1, 28301, 33196, 33195, -1, 28295, 33197, 28297, -1, 28297, 33197, 28299, -1, 28299, 33197, 33196, -1, 27176, 33198, 27175, -1, 27177, 33198, 27176, -1, 27175, 33198, 28295, -1, 33197, 33198, 27177, -1, 28295, 33198, 33197, -1, 25929, 33199, 25928, -1, 33200, 33199, 33191, -1, 33201, 33199, 33200, -1, 25928, 33199, 33201, -1, 33197, 33199, 33196, -1, 33195, 33199, 33194, -1, 27177, 33199, 33197, -1, 33196, 33199, 33195, -1, 30713, 33199, 25929, -1, 33191, 33199, 27177, -1, 33194, 33199, 30713, -1, 27200, 27350, 33190, -1, 33190, 33202, 33191, -1, 27350, 33202, 33190, -1, 33191, 33203, 33200, -1, 33202, 33203, 33191, -1, 33200, 33204, 33201, -1, 33203, 33204, 33200, -1, 33201, 33205, 25928, -1, 33204, 33205, 33201, -1, 33205, 25926, 25928, -1, 33206, 33207, 33208, -1, 33209, 33207, 33206, -1, 33204, 33210, 33205, -1, 33205, 33210, 33211, -1, 25930, 30347, 25932, -1, 33212, 33213, 33214, -1, 33211, 33213, 33212, -1, 25917, 33215, 25920, -1, 33214, 33215, 33209, -1, 33207, 33215, 25917, -1, 33209, 33215, 33207, -1, 33203, 33216, 33204, -1, 33204, 33216, 33210, -1, 33210, 33217, 33211, -1, 33211, 33217, 33213, -1, 25920, 33218, 25925, -1, 33215, 33218, 25920, -1, 33214, 33218, 33215, -1, 33213, 33218, 33214, -1, 27351, 33219, 27350, -1, 27350, 33219, 33202, -1, 33202, 33219, 33203, -1, 33203, 33219, 33216, -1, 30354, 25894, 25893, -1, 33216, 33220, 33210, -1, 33210, 33220, 33217, -1, 25925, 33221, 25901, -1, 33218, 33221, 25925, -1, 33217, 33221, 33213, -1, 33213, 33221, 33218, -1, 27352, 33222, 27351, -1, 27362, 33222, 27352, -1, 27351, 33222, 33219, -1, 33219, 33222, 33216, -1, 33216, 33222, 33220, -1, 25901, 33223, 25900, -1, 33221, 33223, 25901, -1, 33220, 33223, 33217, -1, 33217, 33223, 33221, -1, 27362, 33224, 33222, -1, 27367, 33224, 27362, -1, 33220, 33224, 33223, -1, 33223, 33224, 25900, -1, 25900, 33224, 27367, -1, 33222, 33224, 33220, -1, 27367, 25899, 25900, -1, 25927, 33225, 25930, -1, 30347, 33225, 30349, -1, 25930, 33225, 30347, -1, 25927, 33226, 33225, -1, 30349, 33206, 30351, -1, 33225, 33206, 30349, -1, 25926, 33212, 25927, -1, 25927, 33212, 33226, -1, 33225, 33209, 33206, -1, 33226, 33209, 33225, -1, 33205, 33211, 25926, -1, 25926, 33211, 33212, -1, 30351, 33208, 30354, -1, 30354, 33208, 25894, -1, 33206, 33208, 30351, -1, 33226, 33214, 33209, -1, 33212, 33214, 33226, -1, 25894, 33207, 25917, -1, 33208, 33207, 25894, -1, 25913, 27263, 25911, -1, 27263, 33227, 25911, -1, 25911, 33228, 25909, -1, 33227, 33228, 25911, -1, 25909, 33229, 25905, -1, 33228, 33229, 25909, -1, 25905, 33230, 25891, -1, 33229, 33230, 25905, -1, 25891, 33231, 25889, -1, 33230, 33231, 25891, -1, 25889, 33232, 25923, -1, 25923, 33232, 25921, -1, 33231, 33232, 25889, -1, 33232, 29455, 25921, -1, 33228, 33233, 33229, -1, 33229, 33233, 33234, -1, 33235, 33236, 33237, -1, 33234, 33236, 33235, -1, 33238, 33239, 33240, -1, 33241, 33239, 33238, -1, 30339, 33242, 33243, -1, 33240, 33242, 30339, -1, 27405, 33244, 27263, -1, 27403, 33244, 27405, -1, 27263, 33244, 33227, -1, 33227, 33244, 33228, -1, 33228, 33244, 33233, -1, 33234, 33245, 33236, -1, 33233, 33245, 33234, -1, 33237, 33246, 33241, -1, 33241, 33246, 33239, -1, 30339, 33243, 29452, -1, 33243, 33247, 33248, -1, 33239, 33247, 33240, -1, 33242, 33247, 33243, -1, 33240, 33247, 33242, -1, 27402, 33249, 27403, -1, 27403, 33249, 33244, -1, 33244, 33249, 33233, -1, 33233, 33249, 33245, -1, 33236, 33250, 33237, -1, 33237, 33250, 33246, -1, 33248, 33251, 33252, -1, 33246, 33251, 33239, -1, 33239, 33251, 33247, -1, 33247, 33251, 33248, -1, 33236, 33253, 33250, -1, 33245, 33253, 33236, -1, 33250, 33254, 33246, -1, 33252, 33254, 33255, -1, 33246, 33254, 33251, -1, 33251, 33254, 33252, -1, 33245, 33256, 33253, -1, 27401, 33256, 27402, -1, 27402, 33256, 33249, -1, 33249, 33256, 33245, -1, 33253, 33257, 33250, -1, 33255, 33257, 33258, -1, 33254, 33257, 33255, -1, 33250, 33257, 33254, -1, 27400, 27393, 33259, -1, 33258, 33260, 33259, -1, 27400, 33260, 27401, -1, 33253, 33260, 33257, -1, 29455, 33261, 30346, -1, 27401, 33260, 33256, -1, 33259, 33260, 27400, -1, 33256, 33260, 33253, -1, 33257, 33260, 33258, -1, 33232, 33261, 29455, -1, 33231, 33262, 33232, -1, 33232, 33262, 33261, -1, 30345, 33238, 30343, -1, 30346, 33238, 30345, -1, 33261, 33238, 30346, -1, 33230, 33235, 33231, -1, 33231, 33235, 33262, -1, 33261, 33241, 33238, -1, 33262, 33241, 33261, -1, 33229, 33234, 33230, -1, 33230, 33234, 33235, -1, 33235, 33237, 33262, -1, 33262, 33237, 33241, -1, 30341, 33240, 30339, -1, 30343, 33240, 30341, -1, 33238, 33240, 30343, -1, 29452, 33243, 29453, -1, 29453, 33243, 33263, -1, 33263, 33248, 33264, -1, 33243, 33248, 33263, -1, 33264, 33252, 33265, -1, 33248, 33252, 33264, -1, 33266, 33255, 33267, -1, 33265, 33255, 33266, -1, 33252, 33255, 33265, -1, 33267, 33258, 33268, -1, 33255, 33258, 33267, -1, 33268, 33259, 27281, -1, 33258, 33259, 33268, -1, 33259, 27393, 27281, -1, 27280, 33268, 27281, -1, 27280, 33267, 33268, -1, 27280, 33266, 33267, -1, 30717, 33264, 33265, -1, 30717, 33263, 33264, -1, 30717, 29453, 33263, -1, 28305, 33269, 27284, -1, 27282, 33269, 27280, -1, 27284, 33269, 27282, -1, 28308, 33270, 28305, -1, 28305, 33270, 33269, -1, 33269, 33270, 27280, -1, 28309, 33271, 28308, -1, 33270, 33271, 27280, -1, 28308, 33271, 33270, -1, 27280, 33271, 33266, -1, 28311, 33272, 28309, -1, 33266, 33272, 33265, -1, 33271, 33272, 33266, -1, 33265, 33272, 30717, -1, 28309, 33272, 33271, -1, 28313, 33273, 28311, -1, 33272, 33273, 30717, -1, 28311, 33273, 33272, -1, 30715, 33274, 27575, -1, 30717, 33274, 30715, -1, 28315, 33274, 28313, -1, 27575, 33274, 28315, -1, 33273, 33274, 30717, -1, 28313, 33274, 33273, -1, 30705, 25882, 25884, -1, 30705, 25880, 25882, -1, 27187, 33275, 33276, -1, 27187, 27311, 33275, -1, 27104, 33277, 27106, -1, 30703, 33277, 30705, -1, 27106, 33277, 30703, -1, 27099, 33278, 27100, -1, 27100, 33278, 27104, -1, 27104, 33278, 33277, -1, 33277, 33278, 30705, -1, 33278, 33279, 30705, -1, 27099, 33279, 33278, -1, 28324, 33280, 27099, -1, 27099, 33280, 33279, -1, 28322, 33281, 28324, -1, 28324, 33281, 33280, -1, 28318, 33282, 28320, -1, 28320, 33282, 28322, -1, 28322, 33282, 33281, -1, 27186, 33283, 27181, -1, 27187, 33283, 27186, -1, 27181, 33283, 28318, -1, 33282, 33283, 27187, -1, 28318, 33283, 33282, -1, 25880, 33284, 25879, -1, 33285, 33284, 33276, -1, 33286, 33284, 33285, -1, 25879, 33284, 33286, -1, 33282, 33284, 33281, -1, 33280, 33284, 33279, -1, 27187, 33284, 33282, -1, 33281, 33284, 33280, -1, 30705, 33284, 25880, -1, 33276, 33284, 27187, -1, 33279, 33284, 30705, -1, 27311, 27308, 33275, -1, 33275, 33287, 33276, -1, 27308, 33287, 33275, -1, 33276, 33288, 33285, -1, 33287, 33288, 33276, -1, 33285, 33289, 33286, -1, 33288, 33289, 33285, -1, 33286, 33290, 25879, -1, 33289, 33290, 33286, -1, 33290, 25877, 25879, -1, 33291, 33292, 25845, -1, 33293, 33292, 33291, -1, 33294, 33292, 33293, -1, 33289, 33295, 33290, -1, 25881, 30369, 25883, -1, 33290, 33295, 33296, -1, 33296, 33297, 33298, -1, 33298, 33297, 33299, -1, 25868, 33300, 25871, -1, 33299, 33300, 33294, -1, 33294, 33300, 33292, -1, 33292, 33300, 25868, -1, 33288, 33301, 33289, -1, 33289, 33301, 33295, -1, 33296, 33302, 33297, -1, 33295, 33302, 33296, -1, 25871, 33303, 25876, -1, 33299, 33303, 33300, -1, 33300, 33303, 25871, -1, 33297, 33303, 33299, -1, 27312, 33304, 27308, -1, 27308, 33304, 33287, -1, 33287, 33304, 33288, -1, 33288, 33304, 33301, -1, 30376, 25845, 25844, -1, 33301, 33305, 33295, -1, 33295, 33305, 33302, -1, 25876, 33306, 25852, -1, 33303, 33306, 25876, -1, 33302, 33306, 33297, -1, 33297, 33306, 33303, -1, 27313, 33307, 27312, -1, 27316, 33307, 27313, -1, 27312, 33307, 33304, -1, 33304, 33307, 33301, -1, 33301, 33307, 33305, -1, 25852, 33308, 25851, -1, 33306, 33308, 25852, -1, 33305, 33308, 33302, -1, 33302, 33308, 33306, -1, 27316, 33309, 33307, -1, 27320, 33309, 27316, -1, 33305, 33309, 33308, -1, 33308, 33309, 25851, -1, 25851, 33309, 27320, -1, 33307, 33309, 33305, -1, 27320, 25850, 25851, -1, 30369, 33310, 30371, -1, 25881, 33310, 30369, -1, 25878, 33311, 25881, -1, 25881, 33311, 33310, -1, 30371, 33293, 30373, -1, 33310, 33293, 30371, -1, 25877, 33298, 25878, -1, 25878, 33298, 33311, -1, 33310, 33294, 33293, -1, 33311, 33294, 33310, -1, 33290, 33296, 25877, -1, 25877, 33296, 33298, -1, 30373, 33291, 30376, -1, 30376, 33291, 25845, -1, 33293, 33291, 30373, -1, 33298, 33299, 33311, -1, 33311, 33299, 33294, -1, 25845, 33292, 25868, -1, 27262, 33312, 25864, -1, 25864, 33312, 25862, -1, 25862, 33313, 25860, -1, 33312, 33313, 25862, -1, 25860, 33314, 25856, -1, 33313, 33314, 25860, -1, 25856, 33315, 25842, -1, 33314, 33315, 25856, -1, 25842, 33316, 25840, -1, 33315, 33316, 25842, -1, 25840, 33317, 25874, -1, 25874, 33317, 25872, -1, 33316, 33317, 25840, -1, 33317, 29463, 25872, -1, 33313, 33318, 33314, -1, 33314, 33318, 33319, -1, 33320, 33321, 33322, -1, 33319, 33321, 33320, -1, 33323, 33324, 33325, -1, 33326, 33324, 33323, -1, 30361, 33327, 33328, -1, 33325, 33327, 30361, -1, 27383, 33329, 27262, -1, 27379, 33329, 27383, -1, 27262, 33329, 33312, -1, 33312, 33329, 33313, -1, 33313, 33329, 33318, -1, 33319, 33330, 33321, -1, 33318, 33330, 33319, -1, 33322, 33331, 33326, -1, 33326, 33331, 33324, -1, 30361, 33328, 29460, -1, 33328, 33332, 33333, -1, 33324, 33332, 33325, -1, 33327, 33332, 33328, -1, 33325, 33332, 33327, -1, 27376, 33334, 27379, -1, 27379, 33334, 33329, -1, 33329, 33334, 33318, -1, 33318, 33334, 33330, -1, 33321, 33335, 33322, -1, 33322, 33335, 33331, -1, 33333, 33336, 33337, -1, 33324, 33336, 33332, -1, 33332, 33336, 33333, -1, 33331, 33336, 33324, -1, 33321, 33338, 33335, -1, 33330, 33338, 33321, -1, 33335, 33339, 33331, -1, 33337, 33339, 33340, -1, 33331, 33339, 33336, -1, 33336, 33339, 33337, -1, 33330, 33341, 33338, -1, 27371, 33341, 27376, -1, 27376, 33341, 33334, -1, 33334, 33341, 33330, -1, 33338, 33342, 33335, -1, 33340, 33342, 33343, -1, 33335, 33342, 33339, -1, 33339, 33342, 33340, -1, 27366, 27349, 33344, -1, 33343, 33345, 33344, -1, 27366, 33345, 27371, -1, 33338, 33345, 33342, -1, 27371, 33345, 33341, -1, 29463, 33346, 30368, -1, 33344, 33345, 27366, -1, 33341, 33345, 33338, -1, 33342, 33345, 33343, -1, 33317, 33346, 29463, -1, 33316, 33347, 33317, -1, 33317, 33347, 33346, -1, 30367, 33323, 30365, -1, 30368, 33323, 30367, -1, 33346, 33323, 30368, -1, 33315, 33320, 33316, -1, 33316, 33320, 33347, -1, 33346, 33326, 33323, -1, 33347, 33326, 33346, -1, 33314, 33319, 33315, -1, 33315, 33319, 33320, -1, 33320, 33322, 33347, -1, 33347, 33322, 33326, -1, 30363, 33325, 30361, -1, 30365, 33325, 30363, -1, 33323, 33325, 30365, -1, 29461, 29460, 33348, -1, 33348, 33328, 33349, -1, 29460, 33328, 33348, -1, 33349, 33333, 33350, -1, 33328, 33333, 33349, -1, 33350, 33337, 33351, -1, 33333, 33337, 33350, -1, 33351, 33340, 33352, -1, 33337, 33340, 33351, -1, 33352, 33343, 33353, -1, 33340, 33343, 33352, -1, 33343, 33344, 33353, -1, 33353, 27349, 27205, -1, 33344, 27349, 33353, -1, 27430, 33353, 27205, -1, 27430, 33352, 33353, -1, 27430, 33351, 33352, -1, 30709, 33349, 33350, -1, 30709, 33348, 33349, -1, 30709, 29461, 33348, -1, 28328, 33354, 27174, -1, 27431, 33354, 27430, -1, 27174, 33354, 27431, -1, 28331, 33355, 28328, -1, 28328, 33355, 33354, -1, 33354, 33355, 27430, -1, 28332, 33356, 28331, -1, 33355, 33356, 27430, -1, 28331, 33356, 33355, -1, 27430, 33356, 33351, -1, 28334, 33357, 28332, -1, 33351, 33357, 33350, -1, 33356, 33357, 33351, -1, 33350, 33357, 30709, -1, 28332, 33357, 33356, -1, 28336, 33358, 28334, -1, 33357, 33358, 30709, -1, 28334, 33358, 33357, -1, 30707, 33359, 27568, -1, 30709, 33359, 30707, -1, 28338, 33359, 28336, -1, 27568, 33359, 28338, -1, 33358, 33359, 30709, -1, 28336, 33359, 33358, -1, 30697, 25833, 25835, -1, 30697, 25831, 25833, -1, 27195, 33360, 33361, -1, 27195, 27215, 33360, -1, 27096, 33362, 27098, -1, 30695, 33362, 30697, -1, 27098, 33362, 30695, -1, 27091, 33363, 27092, -1, 27092, 33363, 27096, -1, 27096, 33363, 33362, -1, 33362, 33363, 30697, -1, 33363, 33364, 30697, -1, 27091, 33364, 33363, -1, 28347, 33365, 27091, -1, 27091, 33365, 33364, -1, 28343, 33366, 28345, -1, 28345, 33366, 28347, -1, 28347, 33366, 33365, -1, 28343, 33367, 33366, -1, 27193, 33368, 27188, -1, 27195, 33368, 27193, -1, 27188, 33368, 28341, -1, 28341, 33368, 28343, -1, 28343, 33368, 33367, -1, 33367, 33368, 27195, -1, 25831, 33369, 25830, -1, 33370, 33369, 33361, -1, 33371, 33369, 33370, -1, 25830, 33369, 33371, -1, 33367, 33369, 33366, -1, 33365, 33369, 33364, -1, 27195, 33369, 33367, -1, 33366, 33369, 33365, -1, 30697, 33369, 25831, -1, 33361, 33369, 27195, -1, 33364, 33369, 30697, -1, 27215, 27214, 33360, -1, 27214, 33372, 33360, -1, 33360, 33373, 33361, -1, 33372, 33373, 33360, -1, 33361, 33374, 33370, -1, 33373, 33374, 33361, -1, 33370, 33375, 33371, -1, 33374, 33375, 33370, -1, 33371, 25828, 25830, -1, 33375, 25828, 33371, -1, 33376, 33377, 33378, -1, 33379, 33377, 33376, -1, 33374, 33380, 33375, -1, 33375, 33380, 33381, -1, 25832, 30391, 25834, -1, 33381, 33382, 33383, -1, 33383, 33382, 33384, -1, 25819, 33385, 25822, -1, 33384, 33385, 33379, -1, 33377, 33385, 25819, -1, 33379, 33385, 33377, -1, 33373, 33386, 33374, -1, 33374, 33386, 33380, -1, 33381, 33387, 33382, -1, 33380, 33387, 33381, -1, 25822, 33388, 25827, -1, 33385, 33388, 25822, -1, 33382, 33388, 33384, -1, 33384, 33388, 33385, -1, 27249, 33389, 27214, -1, 27214, 33389, 33372, -1, 33372, 33389, 33373, -1, 33373, 33389, 33386, -1, 30398, 25796, 25795, -1, 33386, 33390, 33380, -1, 33380, 33390, 33387, -1, 25827, 33391, 25803, -1, 33387, 33391, 33382, -1, 33388, 33391, 25827, -1, 33382, 33391, 33388, -1, 27254, 33392, 27249, -1, 27267, 33392, 27254, -1, 27249, 33392, 33389, -1, 33389, 33392, 33386, -1, 33386, 33392, 33390, -1, 25803, 33393, 25802, -1, 33391, 33393, 25803, -1, 33387, 33393, 33391, -1, 33390, 33393, 33387, -1, 27267, 33394, 33392, -1, 27268, 33394, 27267, -1, 33390, 33394, 33393, -1, 33393, 33394, 25802, -1, 25802, 33394, 27268, -1, 33392, 33394, 33390, -1, 27268, 25801, 25802, -1, 30391, 33395, 30393, -1, 25832, 33395, 30391, -1, 25828, 33396, 25829, -1, 25829, 33396, 25832, -1, 25832, 33396, 33395, -1, 30393, 33376, 30395, -1, 33395, 33376, 30393, -1, 25828, 33383, 33396, -1, 33395, 33379, 33376, -1, 33396, 33379, 33395, -1, 33375, 33381, 25828, -1, 25828, 33381, 33383, -1, 30395, 33378, 30398, -1, 30398, 33378, 25796, -1, 33376, 33378, 30395, -1, 33383, 33384, 33396, -1, 33396, 33384, 33379, -1, 25796, 33377, 25819, -1, 33378, 33377, 25796, -1, 25815, 27261, 25813, -1, 25813, 33397, 25811, -1, 27261, 33397, 25813, -1, 25811, 33398, 25807, -1, 33397, 33398, 25811, -1, 25807, 33399, 25793, -1, 33398, 33399, 25807, -1, 25793, 33400, 25791, -1, 33399, 33400, 25793, -1, 25791, 33401, 25825, -1, 33400, 33401, 25791, -1, 25825, 33402, 25823, -1, 33401, 33402, 25825, -1, 33402, 29471, 25823, -1, 33403, 33404, 30387, -1, 33398, 33405, 33399, -1, 33399, 33405, 33406, -1, 33407, 33408, 33409, -1, 33406, 33408, 33407, -1, 33403, 33410, 33404, -1, 33411, 33410, 33403, -1, 30383, 33412, 33413, -1, 33404, 33412, 30383, -1, 27340, 33414, 27261, -1, 27336, 33414, 27340, -1, 27261, 33414, 33397, -1, 33397, 33414, 33398, -1, 33398, 33414, 33405, -1, 33406, 33415, 33408, -1, 33405, 33415, 33406, -1, 33409, 33416, 33411, -1, 33411, 33416, 33410, -1, 30383, 33413, 29468, -1, 33413, 33417, 33418, -1, 33410, 33417, 33404, -1, 33412, 33417, 33413, -1, 33404, 33417, 33412, -1, 27327, 33419, 27336, -1, 27336, 33419, 33414, -1, 33414, 33419, 33405, -1, 33405, 33419, 33415, -1, 33408, 33420, 33409, -1, 33409, 33420, 33416, -1, 33418, 33421, 33422, -1, 33416, 33421, 33410, -1, 33410, 33421, 33417, -1, 33417, 33421, 33418, -1, 33408, 33423, 33420, -1, 33415, 33423, 33408, -1, 33420, 33424, 33416, -1, 33422, 33424, 33425, -1, 33416, 33424, 33421, -1, 33421, 33424, 33422, -1, 33415, 33426, 33423, -1, 27321, 33426, 27327, -1, 27327, 33426, 33419, -1, 33419, 33426, 33415, -1, 33423, 33427, 33420, -1, 33425, 33427, 33428, -1, 33424, 33427, 33425, -1, 33420, 33427, 33424, -1, 27319, 27307, 33429, -1, 33428, 33430, 33429, -1, 27319, 33430, 27321, -1, 33423, 33430, 33427, -1, 29471, 33431, 30390, -1, 27321, 33430, 33426, -1, 33429, 33430, 27319, -1, 33426, 33430, 33423, -1, 33427, 33430, 33428, -1, 33402, 33431, 29471, -1, 33401, 33432, 33402, -1, 33402, 33432, 33431, -1, 30389, 33403, 30387, -1, 30390, 33403, 30389, -1, 33431, 33403, 30390, -1, 33400, 33407, 33401, -1, 33401, 33407, 33432, -1, 33431, 33411, 33403, -1, 33432, 33411, 33431, -1, 33399, 33406, 33400, -1, 33400, 33406, 33407, -1, 33407, 33409, 33432, -1, 33432, 33409, 33411, -1, 30385, 33404, 30383, -1, 30387, 33404, 30385, -1, 29468, 33413, 29469, -1, 29469, 33413, 33433, -1, 33433, 33418, 33434, -1, 33413, 33418, 33433, -1, 33434, 33422, 33435, -1, 33418, 33422, 33434, -1, 33435, 33425, 33436, -1, 33422, 33425, 33435, -1, 33436, 33428, 33437, -1, 33425, 33428, 33436, -1, 33437, 33429, 33438, -1, 33428, 33429, 33437, -1, 33438, 27307, 27309, -1, 33429, 27307, 33438, -1, 27387, 33438, 27309, -1, 27387, 33437, 33438, -1, 27387, 33436, 33437, -1, 30693, 33434, 33435, -1, 30693, 33433, 33434, -1, 30693, 29469, 33433, -1, 28351, 33439, 27185, -1, 27388, 33439, 27387, -1, 27185, 33439, 27388, -1, 28354, 33440, 28351, -1, 28351, 33440, 33439, -1, 33439, 33440, 27387, -1, 28355, 33441, 28354, -1, 33440, 33441, 27387, -1, 28354, 33441, 33440, -1, 27387, 33441, 33436, -1, 28357, 33442, 28355, -1, 28359, 33442, 28357, -1, 33436, 33442, 33435, -1, 33441, 33442, 33436, -1, 33435, 33442, 30693, -1, 28355, 33442, 33441, -1, 28361, 33443, 28359, -1, 33442, 33443, 30693, -1, 28359, 33443, 33442, -1, 30691, 33444, 27561, -1, 30693, 33444, 30691, -1, 27561, 33444, 28361, -1, 33443, 33444, 30693, -1, 28361, 33444, 33443, -1, 30689, 25783, 25785, -1, 30689, 25781, 25783, -1, 27208, 33445, 33446, -1, 27208, 27295, 33445, -1, 27088, 33447, 27090, -1, 30687, 33447, 30689, -1, 27090, 33447, 30687, -1, 27083, 33448, 27084, -1, 27084, 33448, 27088, -1, 27088, 33448, 33447, -1, 33447, 33448, 30689, -1, 33448, 33449, 30689, -1, 27083, 33449, 33448, -1, 28368, 33450, 28370, -1, 28370, 33450, 27083, -1, 27083, 33450, 33449, -1, 28368, 33451, 33450, -1, 28364, 33452, 28366, -1, 28366, 33452, 28368, -1, 28368, 33452, 33451, -1, 27207, 33453, 27196, -1, 27208, 33453, 27207, -1, 27196, 33453, 28364, -1, 28364, 33453, 33452, -1, 33452, 33453, 27208, -1, 25781, 33454, 25779, -1, 33455, 33454, 33446, -1, 33456, 33454, 33455, -1, 25779, 33454, 33456, -1, 33452, 33454, 33451, -1, 33451, 33454, 33450, -1, 33450, 33454, 33449, -1, 30689, 33454, 25781, -1, 27208, 33454, 33452, -1, 33446, 33454, 27208, -1, 33449, 33454, 30689, -1, 27295, 27406, 33445, -1, 27406, 33457, 33445, -1, 33445, 33458, 33446, -1, 33457, 33458, 33445, -1, 33446, 33459, 33455, -1, 33455, 33459, 33456, -1, 33458, 33459, 33446, -1, 33459, 33460, 33456, -1, 33456, 25780, 25779, -1, 33460, 25780, 33456, -1, 33461, 33462, 25748, -1, 33463, 33462, 33461, -1, 33464, 33462, 33463, -1, 33459, 33465, 33466, -1, 25784, 30413, 25786, -1, 33466, 33467, 33468, -1, 33468, 33467, 33469, -1, 25770, 33470, 25773, -1, 33469, 33470, 33464, -1, 33464, 33470, 33462, -1, 33462, 33470, 25770, -1, 33458, 33471, 33459, -1, 33459, 33471, 33465, -1, 33466, 33472, 33467, -1, 33465, 33472, 33466, -1, 25773, 33473, 25778, -1, 33469, 33473, 33470, -1, 33470, 33473, 25773, -1, 33467, 33473, 33469, -1, 27409, 33474, 27406, -1, 27406, 33474, 33457, -1, 33457, 33474, 33458, -1, 33458, 33474, 33471, -1, 30420, 25748, 25747, -1, 33471, 33475, 33465, -1, 33465, 33475, 33472, -1, 25778, 33476, 25754, -1, 33473, 33476, 25778, -1, 33472, 33476, 33467, -1, 33467, 33476, 33473, -1, 27410, 33477, 27409, -1, 27417, 33477, 27410, -1, 27409, 33477, 33474, -1, 33474, 33477, 33471, -1, 33471, 33477, 33475, -1, 25754, 33478, 25753, -1, 33476, 33478, 25754, -1, 33475, 33478, 33472, -1, 33472, 33478, 33476, -1, 27417, 33479, 33477, -1, 27420, 33479, 27417, -1, 33475, 33479, 33478, -1, 33478, 33479, 25753, -1, 25753, 33479, 27420, -1, 33477, 33479, 33475, -1, 27420, 25752, 25753, -1, 30413, 33480, 30415, -1, 25784, 33480, 30413, -1, 25782, 33481, 25784, -1, 25784, 33481, 33480, -1, 30415, 33463, 30417, -1, 33480, 33463, 30415, -1, 25780, 33468, 25782, -1, 25782, 33468, 33481, -1, 33480, 33464, 33463, -1, 33481, 33464, 33480, -1, 33459, 33466, 33460, -1, 33460, 33466, 25780, -1, 25780, 33466, 33468, -1, 30417, 33461, 30420, -1, 30420, 33461, 25748, -1, 33463, 33461, 30417, -1, 33468, 33469, 33481, -1, 33481, 33469, 33464, -1, 25748, 33462, 25770, -1, 25766, 27260, 25764, -1, 25764, 33482, 25762, -1, 27260, 33482, 25764, -1, 25762, 33483, 25758, -1, 33482, 33483, 25762, -1, 25758, 33484, 25744, -1, 33483, 33484, 25758, -1, 25744, 33485, 25742, -1, 33484, 33485, 25744, -1, 25742, 33486, 25776, -1, 33485, 33486, 25742, -1, 25776, 33487, 25774, -1, 33486, 33487, 25776, -1, 33487, 29479, 25774, -1, 33488, 33489, 30409, -1, 33483, 33490, 33484, -1, 33484, 33490, 33491, -1, 33492, 33493, 33494, -1, 33491, 33493, 33492, -1, 33488, 33495, 33489, -1, 33496, 33495, 33488, -1, 30405, 33497, 33498, -1, 33489, 33497, 30405, -1, 27288, 33499, 27260, -1, 27287, 33499, 27288, -1, 27260, 33499, 33482, -1, 33482, 33499, 33483, -1, 33483, 33499, 33490, -1, 33491, 33500, 33493, -1, 33490, 33500, 33491, -1, 33494, 33501, 33496, -1, 33496, 33501, 33495, -1, 30405, 33498, 29476, -1, 33498, 33502, 33503, -1, 33495, 33502, 33489, -1, 33497, 33502, 33498, -1, 33489, 33502, 33497, -1, 27286, 33504, 27287, -1, 27287, 33504, 33499, -1, 33499, 33504, 33490, -1, 33490, 33504, 33500, -1, 33493, 33505, 33494, -1, 33494, 33505, 33501, -1, 33503, 33506, 33507, -1, 33501, 33506, 33495, -1, 33495, 33506, 33502, -1, 33502, 33506, 33503, -1, 33493, 33508, 33505, -1, 33500, 33508, 33493, -1, 33505, 33509, 33501, -1, 33507, 33509, 33510, -1, 33501, 33509, 33506, -1, 33506, 33509, 33507, -1, 33500, 33511, 33508, -1, 27278, 33511, 27286, -1, 27286, 33511, 33504, -1, 33504, 33511, 33500, -1, 33508, 33512, 33505, -1, 33510, 33512, 33513, -1, 33509, 33512, 33510, -1, 33505, 33512, 33509, -1, 27271, 27223, 33514, -1, 33513, 33515, 33514, -1, 27271, 33515, 27278, -1, 33508, 33515, 33512, -1, 29479, 33516, 30412, -1, 27278, 33515, 33511, -1, 33514, 33515, 27271, -1, 33511, 33515, 33508, -1, 33512, 33515, 33513, -1, 33487, 33516, 29479, -1, 33486, 33517, 33487, -1, 33487, 33517, 33516, -1, 30411, 33488, 30409, -1, 30412, 33488, 30411, -1, 33516, 33488, 30412, -1, 33485, 33492, 33486, -1, 33486, 33492, 33517, -1, 33516, 33496, 33488, -1, 33517, 33496, 33516, -1, 33484, 33491, 33485, -1, 33485, 33491, 33492, -1, 33492, 33494, 33517, -1, 33517, 33494, 33496, -1, 30407, 33489, 30405, -1, 30409, 33489, 30407, -1, 29477, 29476, 33518, -1, 33518, 33498, 33519, -1, 29476, 33498, 33518, -1, 33519, 33503, 33520, -1, 33498, 33503, 33519, -1, 33520, 33507, 33521, -1, 33503, 33507, 33520, -1, 33521, 33510, 33522, -1, 33507, 33510, 33521, -1, 33522, 33513, 33523, -1, 33510, 33513, 33522, -1, 33523, 33514, 27213, -1, 33513, 33514, 33523, -1, 33514, 27223, 27213, -1, 27328, 33523, 27213, -1, 27328, 33522, 33523, -1, 27328, 33521, 33522, -1, 30685, 33519, 33520, -1, 30685, 33518, 33519, -1, 30685, 29477, 33518, -1, 28374, 33524, 27192, -1, 27329, 33524, 27328, -1, 27192, 33524, 27329, -1, 28377, 33525, 28374, -1, 28374, 33525, 33524, -1, 33524, 33525, 27328, -1, 28378, 33526, 28377, -1, 33525, 33526, 27328, -1, 28377, 33526, 33525, -1, 27328, 33526, 33521, -1, 28380, 33527, 28378, -1, 33521, 33527, 33520, -1, 33526, 33527, 33521, -1, 33520, 33527, 30685, -1, 28378, 33527, 33526, -1, 28382, 33528, 28380, -1, 33527, 33528, 30685, -1, 28380, 33528, 33527, -1, 30683, 33529, 27554, -1, 30685, 33529, 30683, -1, 28384, 33529, 28382, -1, 27554, 33529, 28384, -1, 33528, 33529, 30685, -1, 28382, 33529, 33528, -1, 30681, 25735, 25736, -1, 30681, 25733, 25735, -1, 27218, 33530, 33531, -1, 27218, 27363, 33530, -1, 27080, 33532, 27082, -1, 30679, 33532, 30681, -1, 27082, 33532, 30679, -1, 27076, 33533, 27080, -1, 27080, 33533, 33532, -1, 33532, 33533, 30681, -1, 27075, 33534, 27076, -1, 33533, 33534, 30681, -1, 27076, 33534, 33533, -1, 28393, 33535, 27075, -1, 27075, 33535, 33534, -1, 28391, 33536, 28393, -1, 28393, 33536, 33535, -1, 28389, 33537, 28391, -1, 28391, 33537, 33536, -1, 27217, 33538, 27209, -1, 27218, 33538, 27217, -1, 27209, 33538, 28387, -1, 28387, 33538, 28389, -1, 28389, 33538, 33537, -1, 33537, 33538, 27218, -1, 25733, 33539, 25732, -1, 33540, 33539, 33531, -1, 33541, 33539, 33540, -1, 25732, 33539, 33541, -1, 33535, 33539, 33534, -1, 33537, 33539, 33536, -1, 27218, 33539, 33537, -1, 30681, 33539, 25733, -1, 33536, 33539, 33535, -1, 33531, 33539, 27218, -1, 33534, 33539, 30681, -1, 27363, 27358, 33530, -1, 27358, 33542, 33530, -1, 33530, 33543, 33531, -1, 33542, 33543, 33530, -1, 33531, 33544, 33540, -1, 33543, 33544, 33531, -1, 33540, 33545, 33541, -1, 33544, 33545, 33540, -1, 33541, 25730, 25732, -1, 33545, 25730, 33541, -1, 33546, 33547, 25699, -1, 33548, 33547, 33546, -1, 33549, 33547, 33548, -1, 33544, 33550, 33545, -1, 25734, 30426, 25737, -1, 33545, 33550, 33551, -1, 33551, 33552, 33553, -1, 33553, 33552, 33554, -1, 25721, 33555, 25724, -1, 33554, 33555, 33549, -1, 33549, 33555, 33547, -1, 33547, 33555, 25721, -1, 33543, 33556, 33544, -1, 33544, 33556, 33550, -1, 33551, 33557, 33552, -1, 33550, 33557, 33551, -1, 25724, 33558, 25729, -1, 33554, 33558, 33555, -1, 33555, 33558, 25724, -1, 33552, 33558, 33554, -1, 27364, 33559, 27358, -1, 27358, 33559, 33542, -1, 33542, 33559, 33543, -1, 33543, 33559, 33556, -1, 30433, 25699, 25698, -1, 33556, 33560, 33550, -1, 33550, 33560, 33557, -1, 25729, 33561, 25705, -1, 33558, 33561, 25729, -1, 33557, 33561, 33552, -1, 33552, 33561, 33558, -1, 27368, 33562, 27364, -1, 27375, 33562, 27368, -1, 27364, 33562, 33559, -1, 33559, 33562, 33556, -1, 33556, 33562, 33560, -1, 25705, 33563, 25704, -1, 33561, 33563, 25705, -1, 33560, 33563, 33557, -1, 33557, 33563, 33561, -1, 27375, 33564, 33562, -1, 27378, 33564, 27375, -1, 33560, 33564, 33563, -1, 33563, 33564, 25704, -1, 25704, 33564, 27378, -1, 33562, 33564, 33560, -1, 27378, 25703, 25704, -1, 30426, 33565, 30428, -1, 25734, 33565, 30426, -1, 25731, 33566, 25734, -1, 25734, 33566, 33565, -1, 30428, 33548, 30430, -1, 33565, 33548, 30428, -1, 25730, 33553, 25731, -1, 25731, 33553, 33566, -1, 33565, 33549, 33548, -1, 33566, 33549, 33565, -1, 33545, 33551, 25730, -1, 25730, 33551, 33553, -1, 30430, 33546, 30433, -1, 30433, 33546, 25699, -1, 33548, 33546, 30430, -1, 33553, 33554, 33566, -1, 33566, 33554, 33549, -1, 25699, 33547, 25721, -1, 25717, 27252, 25715, -1, 25715, 33567, 25713, -1, 27252, 33567, 25715, -1, 25713, 33568, 25709, -1, 33567, 33568, 25713, -1, 25709, 33569, 25695, -1, 33568, 33569, 25709, -1, 25695, 33570, 25693, -1, 33569, 33570, 25695, -1, 25693, 33571, 25727, -1, 33570, 33571, 25693, -1, 25727, 33572, 25725, -1, 33571, 33572, 25727, -1, 33572, 29487, 25725, -1, 33573, 33574, 30444, -1, 33568, 33575, 33569, -1, 33569, 33575, 33576, -1, 33577, 33578, 33579, -1, 33576, 33578, 33577, -1, 33573, 33580, 33574, -1, 33581, 33580, 33573, -1, 30440, 33582, 33583, -1, 33574, 33582, 30440, -1, 27445, 33584, 27252, -1, 27442, 33584, 27445, -1, 27252, 33584, 33567, -1, 33567, 33584, 33568, -1, 33568, 33584, 33575, -1, 33576, 33585, 33578, -1, 33575, 33585, 33576, -1, 33579, 33586, 33581, -1, 33581, 33586, 33580, -1, 30440, 33583, 29484, -1, 33583, 33587, 33588, -1, 33580, 33587, 33574, -1, 33582, 33587, 33583, -1, 33574, 33587, 33582, -1, 27439, 33589, 27442, -1, 27442, 33589, 33584, -1, 33584, 33589, 33575, -1, 33575, 33589, 33585, -1, 33578, 33590, 33579, -1, 33579, 33590, 33586, -1, 33588, 33591, 33592, -1, 33580, 33591, 33587, -1, 33587, 33591, 33588, -1, 33586, 33591, 33580, -1, 33578, 33593, 33590, -1, 33585, 33593, 33578, -1, 33590, 33594, 33586, -1, 33592, 33594, 33595, -1, 33586, 33594, 33591, -1, 33591, 33594, 33592, -1, 33585, 33596, 33593, -1, 27429, 33596, 27439, -1, 27439, 33596, 33589, -1, 33589, 33596, 33585, -1, 33593, 33597, 33590, -1, 33595, 33597, 33598, -1, 33590, 33597, 33594, -1, 33594, 33597, 33595, -1, 27425, 27408, 33599, -1, 33598, 33600, 33599, -1, 27425, 33600, 27429, -1, 33593, 33600, 33597, -1, 27429, 33600, 33596, -1, 29487, 33601, 30447, -1, 33599, 33600, 27425, -1, 33596, 33600, 33593, -1, 33597, 33600, 33598, -1, 33572, 33601, 29487, -1, 33571, 33602, 33572, -1, 33572, 33602, 33601, -1, 30446, 33573, 30444, -1, 30447, 33573, 30446, -1, 33601, 33573, 30447, -1, 33570, 33577, 33571, -1, 33571, 33577, 33602, -1, 33601, 33581, 33573, -1, 33602, 33581, 33601, -1, 33569, 33576, 33570, -1, 33570, 33576, 33577, -1, 33577, 33579, 33602, -1, 33602, 33579, 33581, -1, 30442, 33574, 30440, -1, 30444, 33574, 30442, -1, 29485, 29484, 33603, -1, 33603, 33583, 33604, -1, 29484, 33583, 33603, -1, 33604, 33588, 33605, -1, 33583, 33588, 33604, -1, 33605, 33592, 33606, -1, 33588, 33592, 33605, -1, 33606, 33595, 33607, -1, 33592, 33595, 33606, -1, 33607, 33598, 33608, -1, 33595, 33598, 33607, -1, 33598, 33599, 33608, -1, 33608, 27408, 27274, -1, 33599, 27408, 33608, -1, 27273, 33608, 27274, -1, 27273, 33607, 33608, -1, 27273, 33606, 33607, -1, 30677, 33604, 33605, -1, 30677, 33603, 33604, -1, 30677, 29485, 33603, -1, 28397, 33609, 27204, -1, 27275, 33609, 27273, -1, 27204, 33609, 27275, -1, 28400, 33610, 28397, -1, 28397, 33610, 33609, -1, 33609, 33610, 27273, -1, 28401, 33611, 28400, -1, 33610, 33611, 27273, -1, 28400, 33611, 33610, -1, 27273, 33611, 33606, -1, 28403, 33612, 28401, -1, 33606, 33612, 33605, -1, 33611, 33612, 33606, -1, 33605, 33612, 30677, -1, 28401, 33612, 33611, -1, 28405, 33613, 28403, -1, 33612, 33613, 30677, -1, 28403, 33613, 33612, -1, 30675, 33614, 27547, -1, 30677, 33614, 30675, -1, 28407, 33614, 28405, -1, 27547, 33614, 28407, -1, 33613, 33614, 30677, -1, 28405, 33614, 33613, -1, 30657, 25686, 25688, -1, 30657, 25684, 25686, -1, 27242, 33615, 33616, -1, 27242, 27315, 33615, -1, 27072, 33617, 27074, -1, 30655, 33617, 30657, -1, 27074, 33617, 30655, -1, 27067, 33618, 27068, -1, 27068, 33618, 27072, -1, 27072, 33618, 33617, -1, 33617, 33618, 30657, -1, 28416, 33619, 27067, -1, 33618, 33619, 30657, -1, 27067, 33619, 33618, -1, 28416, 33620, 33619, -1, 28412, 33621, 28414, -1, 28414, 33621, 28416, -1, 28416, 33621, 33620, -1, 28412, 33622, 33621, -1, 27241, 33623, 27236, -1, 27242, 33623, 27241, -1, 27236, 33623, 28410, -1, 28410, 33623, 28412, -1, 28412, 33623, 33622, -1, 33622, 33623, 27242, -1, 25684, 33624, 25683, -1, 33625, 33624, 33616, -1, 33626, 33624, 33625, -1, 25683, 33624, 33626, -1, 33622, 33624, 33621, -1, 33621, 33624, 33620, -1, 33620, 33624, 33619, -1, 30657, 33624, 25684, -1, 27242, 33624, 33622, -1, 33616, 33624, 27242, -1, 33619, 33624, 30657, -1, 27315, 27245, 33615, -1, 27245, 33627, 33615, -1, 33615, 33628, 33616, -1, 33627, 33628, 33615, -1, 33616, 33629, 33625, -1, 33628, 33629, 33616, -1, 33625, 33630, 33626, -1, 33629, 33630, 33625, -1, 33626, 25681, 25683, -1, 33630, 25681, 33626, -1, 33631, 33632, 25649, -1, 33633, 33632, 33631, -1, 33634, 33632, 33633, -1, 33629, 33635, 33630, -1, 25685, 30492, 25687, -1, 33630, 33635, 33636, -1, 33636, 33637, 33638, -1, 33638, 33637, 33639, -1, 25672, 33640, 25675, -1, 33639, 33640, 33634, -1, 33634, 33640, 33632, -1, 33632, 33640, 25672, -1, 33628, 33641, 33629, -1, 33629, 33641, 33635, -1, 33636, 33642, 33637, -1, 33635, 33642, 33636, -1, 25675, 33643, 25680, -1, 33639, 33643, 33640, -1, 33640, 33643, 25675, -1, 33637, 33643, 33639, -1, 27404, 33644, 27245, -1, 27245, 33644, 33627, -1, 33627, 33644, 33628, -1, 33628, 33644, 33641, -1, 30499, 25649, 25648, -1, 33641, 33645, 33635, -1, 33635, 33645, 33642, -1, 25680, 33646, 25656, -1, 33643, 33646, 25680, -1, 33642, 33646, 33637, -1, 33637, 33646, 33643, -1, 27407, 33647, 27404, -1, 27411, 33647, 27407, -1, 27404, 33647, 33644, -1, 33644, 33647, 33641, -1, 33641, 33647, 33645, -1, 25656, 33648, 25655, -1, 33646, 33648, 25656, -1, 33645, 33648, 33642, -1, 33642, 33648, 33646, -1, 27411, 33649, 33647, -1, 27413, 33649, 27411, -1, 33645, 33649, 33648, -1, 33648, 33649, 25655, -1, 25655, 33649, 27413, -1, 33647, 33649, 33645, -1, 27413, 25654, 25655, -1, 30492, 33650, 30494, -1, 25685, 33650, 30492, -1, 25682, 33651, 25685, -1, 25685, 33651, 33650, -1, 30494, 33633, 30496, -1, 33650, 33633, 30494, -1, 25681, 33638, 25682, -1, 25682, 33638, 33651, -1, 33650, 33634, 33633, -1, 33651, 33634, 33650, -1, 33630, 33636, 25681, -1, 25681, 33636, 33638, -1, 30496, 33631, 30499, -1, 30499, 33631, 25649, -1, 33633, 33631, 30496, -1, 33638, 33639, 33651, -1, 33651, 33639, 33634, -1, 25649, 33632, 25672, -1, 25668, 27257, 25666, -1, 25666, 33652, 25664, -1, 27257, 33652, 25666, -1, 25664, 33653, 25660, -1, 33652, 33653, 25664, -1, 25660, 33654, 25646, -1, 33653, 33654, 25660, -1, 25646, 33655, 25644, -1, 33654, 33655, 25646, -1, 25644, 33656, 25678, -1, 33655, 33656, 25644, -1, 33656, 33657, 25678, -1, 25678, 29511, 25676, -1, 33657, 29511, 25678, -1, 33653, 33658, 33654, -1, 33654, 33658, 33659, -1, 33660, 33661, 33662, -1, 33659, 33661, 33660, -1, 33663, 33664, 33665, -1, 33666, 33664, 33663, -1, 30506, 33667, 33668, -1, 33665, 33667, 30506, -1, 27285, 33669, 27257, -1, 27283, 33669, 27285, -1, 27257, 33669, 33652, -1, 33652, 33669, 33653, -1, 33653, 33669, 33658, -1, 33659, 33670, 33661, -1, 33658, 33670, 33659, -1, 33662, 33671, 33666, -1, 33666, 33671, 33664, -1, 30506, 33668, 29508, -1, 33668, 33672, 33673, -1, 33664, 33672, 33665, -1, 33667, 33672, 33668, -1, 33665, 33672, 33667, -1, 27277, 33674, 27283, -1, 27283, 33674, 33669, -1, 33669, 33674, 33658, -1, 33658, 33674, 33670, -1, 33661, 33675, 33662, -1, 33662, 33675, 33671, -1, 33673, 33676, 33677, -1, 33671, 33676, 33664, -1, 33664, 33676, 33672, -1, 33672, 33676, 33673, -1, 33661, 33678, 33675, -1, 33670, 33678, 33661, -1, 33675, 33679, 33671, -1, 33677, 33679, 33680, -1, 33671, 33679, 33676, -1, 33676, 33679, 33677, -1, 33670, 33681, 33678, -1, 27269, 33681, 27277, -1, 27277, 33681, 33674, -1, 33674, 33681, 33670, -1, 33678, 33682, 33675, -1, 33680, 33682, 33683, -1, 33679, 33682, 33680, -1, 33675, 33682, 33679, -1, 27265, 27178, 33684, -1, 33683, 33685, 33684, -1, 27265, 33685, 27269, -1, 33678, 33685, 33682, -1, 29511, 33686, 30513, -1, 27269, 33685, 33681, -1, 33684, 33685, 27265, -1, 33681, 33685, 33678, -1, 33682, 33685, 33683, -1, 33657, 33686, 29511, -1, 33656, 33687, 33657, -1, 33657, 33687, 33686, -1, 30512, 33663, 30510, -1, 30513, 33663, 30512, -1, 33686, 33663, 30513, -1, 33655, 33660, 33656, -1, 33656, 33660, 33687, -1, 33686, 33666, 33663, -1, 33687, 33666, 33686, -1, 33654, 33659, 33655, -1, 33655, 33659, 33660, -1, 33660, 33662, 33687, -1, 33687, 33662, 33666, -1, 30508, 33665, 30506, -1, 30510, 33665, 30508, -1, 33663, 33665, 30510, -1, 29508, 33668, 29509, -1, 29509, 33668, 33688, -1, 33688, 33673, 33689, -1, 33668, 33673, 33688, -1, 33690, 33677, 33691, -1, 33689, 33677, 33690, -1, 33673, 33677, 33689, -1, 33677, 33680, 33691, -1, 33691, 33683, 33692, -1, 33680, 33683, 33691, -1, 33692, 33684, 33693, -1, 33683, 33684, 33692, -1, 33693, 27178, 27344, -1, 33684, 27178, 33693, -1, 27343, 33693, 27344, -1, 27343, 33692, 33693, -1, 27343, 33691, 33692, -1, 30653, 33689, 33690, -1, 30653, 33688, 33689, -1, 30653, 29509, 33688, -1, 28420, 33694, 27233, -1, 27345, 33694, 27343, -1, 27233, 33694, 27345, -1, 28423, 33695, 28420, -1, 28420, 33695, 33694, -1, 33694, 33695, 27343, -1, 28424, 33696, 28423, -1, 33695, 33696, 27343, -1, 28423, 33696, 33695, -1, 27343, 33696, 33691, -1, 28426, 33697, 28424, -1, 33691, 33697, 33690, -1, 33696, 33697, 33691, -1, 33690, 33697, 30653, -1, 28424, 33697, 33696, -1, 28428, 33698, 28426, -1, 33697, 33698, 30653, -1, 28426, 33698, 33697, -1, 30651, 33699, 27526, -1, 30653, 33699, 30651, -1, 28430, 33699, 28428, -1, 27526, 33699, 28430, -1, 33698, 33699, 30653, -1, 28428, 33699, 33698, -1, 27272, 27270, 31417, -1, 31415, 33700, 31414, -1, 31416, 33700, 31415, -1, 31417, 33700, 31416, -1, 27270, 33700, 31417, -1, 31413, 33701, 31412, -1, 31414, 33701, 31413, -1, 33700, 33701, 31414, -1, 31410, 33702, 31409, -1, 31411, 33702, 31410, -1, 31412, 33702, 31411, -1, 33701, 33702, 31412, -1, 31409, 33703, 31408, -1, 33702, 33703, 31409, -1, 31408, 25633, 25635, -1, 33703, 25633, 31408, -1, 30649, 25630, 25632, -1, 30649, 25628, 25630, -1, 27279, 33704, 33705, -1, 27279, 27247, 33704, -1, 25637, 33706, 25639, -1, 30647, 33706, 30649, -1, 25639, 33706, 30647, -1, 25634, 33707, 25637, -1, 25637, 33707, 33706, -1, 33706, 33707, 30649, -1, 25633, 33708, 25634, -1, 33707, 33708, 30649, -1, 25634, 33708, 33707, -1, 33702, 33709, 33703, -1, 33703, 33709, 25633, -1, 25633, 33709, 33708, -1, 33702, 33710, 33709, -1, 33701, 33711, 33702, -1, 33702, 33711, 33710, -1, 27276, 33712, 27270, -1, 27279, 33712, 27276, -1, 27270, 33712, 33700, -1, 33700, 33712, 33701, -1, 33711, 33712, 27279, -1, 33701, 33712, 33711, -1, 25628, 33713, 25627, -1, 33714, 33713, 33705, -1, 33715, 33713, 33714, -1, 25627, 33713, 33715, -1, 33711, 33713, 33710, -1, 33709, 33713, 33708, -1, 27279, 33713, 33711, -1, 33710, 33713, 33709, -1, 30649, 33713, 25628, -1, 33705, 33713, 27279, -1, 33708, 33713, 30649, -1, 27247, 27246, 33704, -1, 27246, 33716, 33704, -1, 33704, 33717, 33705, -1, 33716, 33717, 33704, -1, 33705, 33718, 33714, -1, 33717, 33718, 33705, -1, 33714, 33719, 33715, -1, 33718, 33719, 33714, -1, 33715, 25625, 25627, -1, 33719, 25625, 33715, -1, 33720, 33721, 33722, -1, 30524, 33723, 30522, -1, 33724, 33725, 33726, -1, 33722, 33723, 30524, -1, 33726, 33725, 33727, -1, 33719, 33728, 25625, -1, 25629, 30527, 25631, -1, 25625, 33728, 33729, -1, 33730, 33731, 33732, -1, 33732, 33731, 33733, -1, 33729, 33734, 33735, -1, 27365, 33736, 33737, -1, 33735, 33734, 33721, -1, 33737, 33736, 33738, -1, 27370, 33736, 27365, -1, 27377, 33736, 27370, -1, 33738, 33736, 33739, -1, 30519, 33740, 29047, -1, 30520, 33740, 30519, -1, 33721, 33741, 33722, -1, 29047, 33740, 33742, -1, 33733, 33740, 30520, -1, 33722, 33741, 33723, -1, 33743, 33744, 33745, -1, 33739, 33744, 33743, -1, 33718, 33746, 33719, -1, 33719, 33746, 33728, -1, 30522, 33747, 30521, -1, 33727, 33748, 33730, -1, 33730, 33748, 33731, -1, 33723, 33747, 30522, -1, 33745, 33749, 33724, -1, 33729, 33750, 33734, -1, 33724, 33749, 33725, -1, 33728, 33750, 33729, -1, 33742, 33751, 33752, -1, 33731, 33751, 33733, -1, 33721, 33753, 33741, -1, 33733, 33751, 33740, -1, 33734, 33753, 33721, -1, 33740, 33751, 33742, -1, 27377, 33754, 33736, -1, 33736, 33754, 33739, -1, 33717, 33755, 33718, -1, 33739, 33754, 33744, -1, 33718, 33755, 33746, -1, 33725, 33756, 33727, -1, 33741, 33757, 33723, -1, 33727, 33756, 33748, -1, 33723, 33757, 33747, -1, 33744, 33758, 33745, -1, 33745, 33758, 33749, -1, 33752, 33759, 33760, -1, 33728, 33761, 33750, -1, 33748, 33759, 33731, -1, 33746, 33761, 33728, -1, 33751, 33759, 33752, -1, 30521, 33732, 30520, -1, 33731, 33759, 33751, -1, 33747, 33732, 30521, -1, 33749, 33762, 33725, -1, 33725, 33762, 33756, -1, 33750, 33763, 33734, -1, 33754, 33764, 33744, -1, 27384, 33764, 27377, -1, 33734, 33763, 33753, -1, 27386, 33764, 27384, -1, 33744, 33764, 33758, -1, 27377, 33764, 33754, -1, 33753, 33726, 33741, -1, 33760, 33765, 33766, -1, 33748, 33765, 33759, -1, 33741, 33726, 33757, -1, 33759, 33765, 33760, -1, 33756, 33765, 33748, -1, 27361, 33767, 27246, -1, 27365, 33767, 27361, -1, 27246, 33767, 33716, -1, 33716, 33767, 33717, -1, 33717, 33767, 33755, -1, 33758, 33768, 33749, -1, 33755, 33738, 33746, -1, 33749, 33768, 33762, -1, 33766, 33769, 33770, -1, 33765, 33769, 33766, -1, 33746, 33738, 33761, -1, 33762, 33769, 33756, -1, 33757, 33730, 33747, -1, 33756, 33769, 33765, -1, 27389, 33771, 27386, -1, 27386, 33771, 33764, -1, 33764, 33771, 33758, -1, 33758, 33771, 33768, -1, 33747, 33730, 33732, -1, 33770, 33772, 33773, -1, 33761, 33743, 33750, -1, 33769, 33772, 33770, -1, 33768, 33772, 33762, -1, 33762, 33772, 33769, -1, 33750, 33743, 33763, -1, 33753, 33724, 33726, -1, 33772, 33774, 33773, -1, 33763, 33724, 33753, -1, 33768, 33774, 33772, -1, 27390, 33774, 27389, -1, 27389, 33774, 33771, -1, 33773, 33774, 27390, -1, 33771, 33774, 33768, -1, 27390, 27259, 33773, -1, 33726, 33727, 33757, -1, 30527, 33720, 30526, -1, 25629, 33720, 30527, -1, 33757, 33727, 33730, -1, 25626, 33735, 25629, -1, 27365, 33737, 33767, -1, 33767, 33737, 33755, -1, 33755, 33737, 33738, -1, 25629, 33735, 33720, -1, 30526, 33722, 30524, -1, 33720, 33722, 30526, -1, 33732, 33733, 30520, -1, 25625, 33729, 25626, -1, 33738, 33739, 33761, -1, 33761, 33739, 33743, -1, 25626, 33729, 33735, -1, 33743, 33745, 33763, -1, 33763, 33745, 33724, -1, 33735, 33721, 33720, -1, 29048, 29047, 33775, -1, 33775, 33742, 33776, -1, 29047, 33742, 33775, -1, 33776, 33752, 33777, -1, 33742, 33752, 33776, -1, 33777, 33760, 33778, -1, 33752, 33760, 33777, -1, 33778, 33766, 33779, -1, 33760, 33766, 33778, -1, 33779, 33770, 33780, -1, 33766, 33770, 33779, -1, 33780, 33773, 27258, -1, 33770, 33773, 33780, -1, 33773, 27259, 27258, -1, 33781, 33782, 30516, -1, 33779, 33783, 33778, -1, 33778, 33783, 33784, -1, 33785, 33786, 33787, -1, 33784, 33786, 33785, -1, 33781, 33788, 33782, -1, 33789, 33788, 33781, -1, 30518, 33790, 33791, -1, 33782, 33790, 30518, -1, 27435, 33792, 27258, -1, 27432, 33792, 27435, -1, 27258, 33792, 33780, -1, 33780, 33792, 33779, -1, 33779, 33792, 33783, -1, 33784, 33793, 33786, -1, 33783, 33793, 33784, -1, 33787, 33794, 33789, -1, 33789, 33794, 33788, -1, 30518, 33791, 29516, -1, 33791, 33795, 33796, -1, 33788, 33795, 33782, -1, 33790, 33795, 33791, -1, 33782, 33795, 33790, -1, 27427, 33797, 27432, -1, 27432, 33797, 33792, -1, 33792, 33797, 33783, -1, 33783, 33797, 33793, -1, 33786, 33798, 33787, -1, 33787, 33798, 33794, -1, 33796, 33799, 33800, -1, 33788, 33799, 33795, -1, 33795, 33799, 33796, -1, 33794, 33799, 33788, -1, 33786, 33801, 33798, -1, 33793, 33801, 33786, -1, 33798, 33802, 33794, -1, 33800, 33802, 33803, -1, 33794, 33802, 33799, -1, 33799, 33802, 33800, -1, 33793, 33804, 33801, -1, 27419, 33804, 27427, -1, 27427, 33804, 33797, -1, 33797, 33804, 33793, -1, 33801, 33805, 33798, -1, 33803, 33805, 33806, -1, 33798, 33805, 33802, -1, 33802, 33805, 33803, -1, 27412, 27244, 33807, -1, 33806, 33808, 33807, -1, 27412, 33808, 27419, -1, 33801, 33808, 33805, -1, 27419, 33808, 33804, -1, 29048, 33809, 30514, -1, 33807, 33808, 27412, -1, 33804, 33808, 33801, -1, 33805, 33808, 33806, -1, 33775, 33809, 29048, -1, 33776, 33810, 33775, -1, 33775, 33810, 33809, -1, 30515, 33781, 30516, -1, 30514, 33781, 30515, -1, 33809, 33781, 30514, -1, 33777, 33785, 33776, -1, 33776, 33785, 33810, -1, 33809, 33789, 33781, -1, 33810, 33789, 33809, -1, 33778, 33784, 33777, -1, 33777, 33784, 33785, -1, 33785, 33787, 33810, -1, 33810, 33787, 33789, -1, 30517, 33782, 30518, -1, 30516, 33782, 30517, -1, 29516, 33791, 29517, -1, 29517, 33791, 33811, -1, 33811, 33796, 33812, -1, 33791, 33796, 33811, -1, 33812, 33800, 33813, -1, 33796, 33800, 33812, -1, 33813, 33803, 33814, -1, 33800, 33803, 33813, -1, 33814, 33806, 33815, -1, 33803, 33806, 33814, -1, 33815, 33807, 33816, -1, 33806, 33807, 33815, -1, 33816, 27244, 27243, -1, 33807, 27244, 33816, -1, 27294, 33816, 27243, -1, 27294, 33815, 33816, -1, 27294, 33814, 33815, -1, 30644, 33812, 33813, -1, 30644, 33811, 33812, -1, 30644, 29517, 33811, -1, 28434, 33817, 27240, -1, 27289, 33817, 27294, -1, 27240, 33817, 27289, -1, 28437, 33818, 28434, -1, 28434, 33818, 33817, -1, 33817, 33818, 27294, -1, 28438, 33819, 28437, -1, 33818, 33819, 27294, -1, 28437, 33819, 33818, -1, 27294, 33819, 33814, -1, 28440, 33820, 28438, -1, 33814, 33820, 33813, -1, 33819, 33820, 33814, -1, 33813, 33820, 30644, -1, 28438, 33820, 33819, -1, 28442, 33821, 28440, -1, 33820, 33821, 30644, -1, 28440, 33821, 33820, -1, 30642, 33822, 27518, -1, 30644, 33822, 30642, -1, 28444, 33822, 28442, -1, 27518, 33822, 28444, -1, 33821, 33822, 30644, -1, 28442, 33822, 33821, -1, 27381, 33823, 27298, -1, 27381, 33824, 33823, -1, 27381, 33825, 33824, -1, 30661, 33826, 33827, -1, 30661, 33828, 33826, -1, 30661, 29501, 33828, -1, 27382, 33829, 27381, -1, 27225, 33829, 27382, -1, 28449, 33829, 27225, -1, 28450, 33830, 28449, -1, 28449, 33830, 33829, -1, 33829, 33830, 27381, -1, 28452, 33831, 28450, -1, 28450, 33831, 33830, -1, 33830, 33831, 27381, -1, 27381, 33831, 33825, -1, 33825, 33832, 33827, -1, 28454, 33832, 28452, -1, 33831, 33832, 33825, -1, 28452, 33832, 33831, -1, 33827, 33832, 30661, -1, 28456, 33833, 28454, -1, 33832, 33833, 30661, -1, 28454, 33833, 33832, -1, 30659, 33834, 27533, -1, 30661, 33834, 30659, -1, 27533, 33834, 28458, -1, 28458, 33834, 28456, -1, 28456, 33834, 33833, -1, 33833, 33834, 30661, -1, 29501, 29500, 33828, -1, 33828, 33835, 33826, -1, 29500, 33835, 33828, -1, 33826, 33836, 33827, -1, 33835, 33836, 33826, -1, 33827, 33837, 33825, -1, 33836, 33837, 33827, -1, 33825, 33838, 33824, -1, 33837, 33838, 33825, -1, 33824, 33839, 33823, -1, 33838, 33839, 33824, -1, 33823, 33840, 27298, -1, 33839, 33840, 33823, -1, 33840, 27296, 27298, -1, 33841, 33842, 30475, -1, 33843, 33844, 33845, -1, 33845, 33844, 33846, -1, 33846, 33847, 33848, -1, 33848, 33847, 33849, -1, 33850, 33851, 33841, -1, 33841, 33851, 33842, -1, 33842, 33852, 30471, -1, 30471, 33852, 33835, -1, 27342, 33853, 27256, -1, 27341, 33853, 27342, -1, 33854, 33853, 33843, -1, 27256, 33853, 33854, -1, 33843, 33853, 33844, -1, 33844, 33855, 33846, -1, 33846, 33855, 33847, -1, 33849, 33856, 33850, -1, 33850, 33856, 33851, -1, 33835, 33857, 33836, -1, 33852, 33857, 33835, -1, 30471, 33835, 29500, -1, 33851, 33857, 33842, -1, 33842, 33857, 33852, -1, 27339, 33858, 27341, -1, 27341, 33858, 33853, -1, 33853, 33858, 33844, -1, 33844, 33858, 33855, -1, 33847, 33859, 33849, -1, 33849, 33859, 33856, -1, 33836, 33860, 33837, -1, 33857, 33860, 33836, -1, 33856, 33860, 33851, -1, 33851, 33860, 33857, -1, 33847, 33861, 33859, -1, 33855, 33861, 33847, -1, 33859, 33862, 33856, -1, 33837, 33862, 33838, -1, 33856, 33862, 33860, -1, 33860, 33862, 33837, -1, 27322, 33863, 27339, -1, 33855, 33863, 33861, -1, 27339, 33863, 33858, -1, 33858, 33863, 33855, -1, 33838, 33864, 33839, -1, 33859, 33864, 33862, -1, 33861, 33864, 33859, -1, 33862, 33864, 33838, -1, 27317, 27296, 33840, -1, 27322, 33865, 33863, -1, 33866, 33867, 29503, -1, 27317, 33865, 27322, -1, 33864, 33865, 33839, -1, 33861, 33865, 33864, -1, 33839, 33865, 33840, -1, 33863, 33865, 33861, -1, 33840, 33865, 27317, -1, 29503, 33867, 30478, -1, 33868, 33869, 33866, -1, 33866, 33869, 33867, -1, 30477, 33841, 30475, -1, 30478, 33841, 30477, -1, 33867, 33841, 30478, -1, 33870, 33848, 33868, -1, 33868, 33848, 33869, -1, 33867, 33850, 33841, -1, 33869, 33850, 33867, -1, 33845, 33846, 33870, -1, 33870, 33846, 33848, -1, 33848, 33849, 33869, -1, 33869, 33849, 33850, -1, 30473, 33842, 30471, -1, 30475, 33842, 30473, -1, 25612, 27256, 25610, -1, 27256, 33854, 25610, -1, 25610, 33843, 25608, -1, 33854, 33843, 25610, -1, 25608, 33845, 25604, -1, 33843, 33845, 25608, -1, 25604, 33870, 25590, -1, 33845, 33870, 25604, -1, 25590, 33868, 25588, -1, 33870, 33868, 25590, -1, 25588, 33866, 25622, -1, 33868, 33866, 25588, -1, 25622, 29503, 25620, -1, 33866, 29503, 25622, -1, 33871, 33872, 33873, -1, 33874, 33872, 33871, -1, 33875, 33876, 33877, -1, 33877, 33876, 33878, -1, 25580, 30479, 25582, -1, 33879, 33880, 33881, -1, 33878, 33880, 33879, -1, 25616, 33882, 25619, -1, 33881, 33882, 33874, -1, 33872, 33882, 25616, -1, 33874, 33882, 33872, -1, 33883, 33884, 33875, -1, 33875, 33884, 33876, -1, 33876, 33885, 33878, -1, 33878, 33885, 33880, -1, 25619, 33886, 25624, -1, 33881, 33886, 33882, -1, 33882, 33886, 25619, -1, 33880, 33886, 33881, -1, 27179, 33887, 27180, -1, 33888, 33887, 33883, -1, 27180, 33887, 33888, -1, 33883, 33887, 33884, -1, 30486, 25594, 25593, -1, 33876, 33889, 33885, -1, 33884, 33889, 33876, -1, 25624, 33890, 25600, -1, 33886, 33890, 25624, -1, 33885, 33890, 33880, -1, 33880, 33890, 33886, -1, 27194, 33891, 27179, -1, 27255, 33891, 27194, -1, 27179, 33891, 33887, -1, 33887, 33891, 33884, -1, 33884, 33891, 33889, -1, 25600, 33892, 25599, -1, 33890, 33892, 25600, -1, 33889, 33892, 33885, -1, 33885, 33892, 33890, -1, 27255, 33893, 33891, -1, 27264, 33893, 27255, -1, 33889, 33893, 33892, -1, 33891, 33893, 33889, -1, 33892, 33893, 25599, -1, 25599, 33893, 27264, -1, 27264, 25598, 25599, -1, 30479, 33894, 30481, -1, 25580, 33894, 30479, -1, 25579, 33895, 25580, -1, 25577, 33895, 25579, -1, 25580, 33895, 33894, -1, 30481, 33871, 30483, -1, 33894, 33871, 30481, -1, 25577, 33879, 33895, -1, 33894, 33874, 33871, -1, 33895, 33874, 33894, -1, 33877, 33878, 25577, -1, 25577, 33878, 33879, -1, 30483, 33873, 30486, -1, 30486, 33873, 25594, -1, 33871, 33873, 30483, -1, 33879, 33881, 33895, -1, 33895, 33881, 33874, -1, 25594, 33872, 25616, -1, 33873, 33872, 25594, -1, 27353, 27180, 33896, -1, 33896, 33888, 33897, -1, 27180, 33888, 33896, -1, 33897, 33883, 33898, -1, 33888, 33883, 33897, -1, 33898, 33875, 33899, -1, 33883, 33875, 33898, -1, 33899, 33877, 25576, -1, 33875, 33877, 33899, -1, 33877, 25577, 25576, -1, 30665, 25581, 25583, -1, 30665, 25578, 25581, -1, 27235, 33896, 33897, -1, 27235, 27353, 33896, -1, 27064, 33900, 27066, -1, 27060, 33900, 27064, -1, 30663, 33900, 30665, -1, 27066, 33900, 30663, -1, 27060, 33901, 33900, -1, 33900, 33901, 30665, -1, 27059, 33902, 27060, -1, 27060, 33902, 33901, -1, 33901, 33902, 30665, -1, 28467, 33903, 27059, -1, 27059, 33903, 33902, -1, 28465, 33904, 28467, -1, 28467, 33904, 33903, -1, 28463, 33905, 28465, -1, 28465, 33905, 33904, -1, 27234, 33906, 27229, -1, 27235, 33906, 27234, -1, 28461, 33906, 28463, -1, 27229, 33906, 28461, -1, 33905, 33906, 27235, -1, 28463, 33906, 33905, -1, 25576, 33907, 33899, -1, 33899, 33907, 33898, -1, 33898, 33907, 33897, -1, 25578, 33907, 25576, -1, 33903, 33907, 33902, -1, 27235, 33907, 33905, -1, 33904, 33907, 33903, -1, 33905, 33907, 33904, -1, 30665, 33907, 25578, -1, 33897, 33907, 27235, -1, 33902, 33907, 30665, -1, 33908, 29589, 29601, -1, 33908, 29601, 33909, -1, 33910, 33908, 33909, -1, 33911, 33909, 33912, -1, 33911, 33912, 33913, -1, 33911, 33910, 33909, -1, 33914, 33913, 33915, -1, 33914, 33915, 33916, -1, 33914, 33911, 33913, -1, 33917, 33916, 33918, -1, 33917, 33918, 33919, -1, 33917, 33919, 33920, -1, 33917, 33920, 33921, -1, 33917, 33914, 33916, -1, 33922, 33921, 33923, -1, 33922, 33923, 33924, -1, 33922, 33917, 33921, -1, 29575, 33924, 29576, -1, 29575, 33922, 33924, -1, 33925, 33926, 33927, -1, 33928, 33929, 33930, -1, 33928, 33930, 33931, -1, 33932, 33931, 33933, -1, 33932, 33933, 33934, -1, 33935, 33926, 33925, -1, 33935, 33925, 33911, -1, 33935, 33934, 33926, -1, 29602, 25574, 25573, -1, 33936, 33937, 33929, -1, 33936, 29691, 33937, -1, 33936, 33929, 33928, -1, 33938, 33928, 33931, -1, 33938, 33931, 33932, -1, 33939, 33914, 33917, -1, 33939, 33911, 33914, -1, 33939, 33935, 33911, -1, 33939, 33932, 33934, -1, 33939, 33934, 33935, -1, 33940, 29693, 29691, -1, 33940, 29691, 33936, -1, 33940, 33936, 33928, -1, 33940, 33928, 33938, -1, 33941, 33939, 33917, -1, 33941, 33938, 33932, -1, 33941, 33932, 33939, -1, 33942, 33922, 29575, -1, 33942, 33917, 33922, -1, 33942, 29575, 29695, -1, 33942, 29695, 29693, -1, 33942, 33941, 33917, -1, 33942, 29693, 33940, -1, 33942, 33940, 33938, -1, 33908, 29592, 29589, -1, 33942, 33938, 33941, -1, 29691, 29639, 33937, -1, 33943, 33944, 25574, -1, 33943, 25574, 29602, -1, 33945, 33946, 33944, -1, 33945, 33944, 33943, -1, 33927, 29602, 29595, -1, 33927, 33943, 29602, -1, 33933, 33947, 33946, -1, 33933, 33946, 33945, -1, 33926, 33943, 33927, -1, 33926, 33945, 33943, -1, 33948, 29595, 29592, -1, 33948, 33927, 29595, -1, 33948, 29592, 33908, -1, 33931, 33930, 33947, -1, 33931, 33947, 33933, -1, 33934, 33945, 33926, -1, 33934, 33933, 33945, -1, 33925, 33910, 33911, -1, 33925, 33908, 33910, -1, 33925, 33948, 33908, -1, 33925, 33927, 33948, -1, 33949, 25572, 25574, -1, 33949, 25574, 33944, -1, 33950, 33944, 33946, -1, 33950, 33949, 33944, -1, 33951, 33946, 33947, -1, 33951, 33950, 33946, -1, 33952, 33947, 33930, -1, 33952, 33951, 33947, -1, 33953, 33930, 33929, -1, 33953, 33952, 33930, -1, 33954, 33937, 29639, -1, 33954, 33929, 33937, -1, 33954, 33953, 33929, -1, 29638, 33954, 29639, -1, 33955, 33951, 33952, -1, 33955, 33956, 33951, -1, 33957, 33958, 33959, -1, 33955, 33960, 33961, -1, 33955, 33961, 33956, -1, 33957, 33962, 33958, -1, 33963, 29643, 29645, -1, 33963, 33964, 33965, -1, 33963, 29645, 33964, -1, 33963, 33965, 33966, -1, 33967, 33968, 33969, -1, 33970, 33952, 33953, -1, 33970, 33955, 33952, -1, 33967, 33959, 33968, -1, 33970, 33966, 33960, -1, 33970, 33960, 33955, -1, 33971, 29618, 29611, -1, 33972, 33953, 33954, -1, 33972, 29641, 29643, -1, 33971, 33969, 29618, -1, 33972, 33966, 33970, -1, 33972, 29643, 33963, -1, 33972, 33970, 33953, -1, 33972, 33963, 33966, -1, 33973, 33974, 33975, -1, 33972, 33954, 29641, -1, 33973, 33975, 33976, -1, 33977, 33976, 33962, -1, 33977, 33962, 33957, -1, 33978, 33959, 33967, -1, 33978, 33957, 33959, -1, 33979, 33967, 33969, -1, 33979, 33969, 33971, -1, 33980, 29651, 29654, -1, 33980, 29654, 33974, -1, 33980, 33974, 33973, -1, 33981, 29611, 29608, -1, 33981, 33971, 29611, -1, 25572, 29608, 25575, -1, 33982, 33976, 33977, -1, 33982, 33973, 33976, -1, 33983, 33977, 33957, -1, 33983, 33957, 33978, -1, 33984, 33978, 33967, -1, 33984, 33967, 33979, -1, 33985, 33971, 33981, -1, 33985, 33979, 33971, -1, 33986, 33973, 33982, -1, 33986, 29649, 29651, -1, 33986, 29651, 33980, -1, 33986, 33980, 33973, -1, 33987, 33981, 29608, -1, 33987, 25572, 33949, -1, 33987, 29608, 25572, -1, 33988, 33982, 33977, -1, 33988, 33977, 33983, -1, 33989, 33983, 33978, -1, 33989, 33978, 33984, -1, 29638, 29641, 33954, -1, 33961, 33984, 33979, -1, 33990, 33991, 33992, -1, 33990, 33992, 29600, -1, 33961, 33979, 33985, -1, 33990, 29600, 29629, -1, 33990, 29629, 29627, -1, 33993, 33949, 33950, -1, 33993, 33985, 33981, -1, 33993, 33981, 33987, -1, 33958, 33994, 33991, -1, 33993, 33987, 33949, -1, 33995, 29645, 29647, -1, 33995, 29647, 29649, -1, 33995, 33982, 33988, -1, 33958, 33991, 33990, -1, 33995, 33986, 33982, -1, 33995, 29649, 33986, -1, 33968, 29627, 29622, -1, 33965, 33983, 33989, -1, 33965, 33988, 33983, -1, 33968, 33990, 29627, -1, 33960, 33984, 33961, -1, 33962, 33996, 33994, -1, 33962, 33994, 33958, -1, 33960, 33989, 33984, -1, 33959, 33958, 33990, -1, 33956, 33950, 33951, -1, 33959, 33990, 33968, -1, 33956, 33961, 33985, -1, 33956, 33985, 33993, -1, 33956, 33993, 33950, -1, 33969, 29622, 29618, -1, 33964, 33988, 33965, -1, 33964, 29645, 33995, -1, 33964, 33995, 33988, -1, 33969, 33968, 29622, -1, 33966, 33965, 33989, -1, 33976, 33975, 33996, -1, 33976, 33996, 33962, -1, 33966, 33989, 33960, -1, 29598, 29600, 33992, -1, 33997, 33992, 33991, -1, 33997, 29598, 33992, -1, 33998, 33991, 33994, -1, 33998, 33997, 33991, -1, 33999, 33994, 33996, -1, 33999, 33998, 33994, -1, 34000, 33996, 33975, -1, 34000, 33999, 33996, -1, 34001, 33975, 33974, -1, 34001, 34000, 33975, -1, 34002, 33974, 29654, -1, 34002, 34001, 33974, -1, 29656, 34002, 29654, -1, 34003, 34004, 34005, -1, 34003, 34005, 34006, -1, 34007, 34008, 34009, -1, 29615, 34010, 29616, -1, 34007, 34006, 34008, -1, 34011, 34012, 34013, -1, 34011, 34009, 34012, -1, 34014, 33997, 33998, -1, 34014, 34015, 34016, -1, 34014, 34013, 34015, -1, 34014, 34016, 33997, -1, 34017, 30283, 29635, -1, 34017, 29635, 34004, -1, 34017, 34004, 34003, -1, 34018, 34003, 34006, -1, 34018, 34006, 34007, -1, 34019, 34007, 34009, -1, 34019, 34009, 34011, -1, 34020, 33998, 33999, -1, 34020, 34014, 33998, -1, 34020, 34011, 34013, -1, 34020, 34013, 34014, -1, 34021, 30284, 30283, -1, 34021, 30283, 34017, -1, 34021, 34003, 34018, -1, 34021, 34017, 34003, -1, 34022, 34018, 34007, -1, 34022, 34007, 34019, -1, 34023, 33999, 34000, -1, 34023, 34019, 34011, -1, 34023, 34020, 33999, -1, 34023, 34011, 34020, -1, 34024, 34021, 34018, -1, 34024, 30286, 30284, -1, 34024, 30284, 34021, -1, 34024, 34018, 34022, -1, 34025, 34000, 34001, -1, 34025, 34022, 34019, -1, 34025, 34019, 34023, -1, 34025, 34023, 34000, -1, 34026, 34001, 34002, -1, 34026, 30286, 34024, -1, 34026, 30288, 30286, -1, 34026, 34024, 34022, -1, 34026, 34002, 30288, -1, 34026, 34025, 34001, -1, 34026, 34022, 34025, -1, 29656, 30288, 34002, -1, 34027, 34028, 34010, -1, 34027, 34010, 29615, -1, 34029, 34030, 34028, -1, 34029, 34028, 34027, -1, 34031, 29615, 29617, -1, 34031, 29617, 29607, -1, 34031, 34027, 29615, -1, 34008, 34032, 34030, -1, 34008, 34030, 34029, -1, 34012, 34027, 34031, -1, 34012, 34029, 34027, -1, 34015, 29607, 29606, -1, 34015, 34031, 29607, -1, 34006, 34005, 34032, -1, 34006, 34032, 34008, -1, 34009, 34029, 34012, -1, 34009, 34008, 34029, -1, 34013, 34012, 34031, -1, 34013, 34031, 34015, -1, 34016, 29598, 33997, -1, 34016, 29606, 29598, -1, 34016, 34015, 29606, -1, 31425, 29626, 29616, -1, 31425, 29616, 34010, -1, 31424, 31425, 34010, -1, 31423, 34010, 34028, -1, 31423, 31424, 34010, -1, 31422, 34028, 34030, -1, 31422, 31423, 34028, -1, 31419, 34030, 34032, -1, 31419, 31422, 34030, -1, 31420, 34032, 34005, -1, 31420, 31419, 34032, -1, 31421, 34005, 34004, -1, 31421, 31420, 34005, -1, 29636, 34004, 29635, -1, 29636, 31421, 34004, -1, 34033, 34034, 34035, -1, 34036, 33913, 33912, -1, 34036, 33912, 34037, -1, 34038, 29062, 29059, -1, 34038, 34033, 34035, -1, 34038, 34039, 29062, -1, 34038, 34035, 34039, -1, 34040, 33915, 33913, -1, 34040, 33913, 34036, -1, 34041, 34037, 34033, -1, 34041, 34036, 34037, -1, 34042, 33916, 33915, -1, 29050, 34043, 34044, -1, 29050, 34044, 34045, -1, 29050, 34045, 34046, -1, 29050, 34046, 34047, -1, 29050, 34047, 29049, -1, 34042, 33915, 34040, -1, 34048, 33918, 33916, -1, 34048, 33919, 33918, -1, 34048, 33916, 34042, -1, 34049, 34040, 34036, -1, 34049, 34036, 34041, -1, 34050, 29059, 29058, -1, 34050, 34033, 34038, -1, 34050, 34038, 29059, -1, 34050, 34041, 34033, -1, 34051, 33920, 33919, -1, 34051, 33919, 34048, -1, 34052, 34040, 34049, -1, 34052, 34042, 34040, -1, 34053, 33921, 33920, -1, 34053, 33920, 34051, -1, 34054, 34042, 34052, -1, 34054, 34048, 34042, -1, 34055, 29058, 29060, -1, 34055, 34049, 34041, -1, 34055, 34041, 34050, -1, 34055, 34050, 29058, -1, 34056, 31614, 29576, -1, 34056, 33923, 33921, -1, 34056, 33924, 33923, -1, 34056, 29576, 33924, -1, 34056, 33921, 34053, -1, 34057, 34048, 34054, -1, 34057, 34051, 34048, -1, 34058, 34052, 34049, -1, 34058, 34055, 29060, -1, 34058, 29060, 29061, -1, 34058, 34049, 34055, -1, 34059, 34053, 34051, -1, 34059, 34051, 34057, -1, 34060, 34058, 29061, -1, 34060, 29061, 29055, -1, 34060, 34052, 34058, -1, 34060, 34054, 34052, -1, 34061, 31612, 31614, -1, 34061, 31614, 34056, -1, 34061, 34056, 34053, -1, 34061, 34053, 34059, -1, 34062, 34060, 29055, -1, 34062, 34054, 34060, -1, 34062, 34057, 34054, -1, 34063, 34057, 34062, -1, 34063, 34059, 34057, -1, 34063, 34062, 29055, -1, 34063, 29055, 29054, -1, 34034, 33909, 29601, -1, 34034, 29601, 34043, -1, 34064, 29053, 31612, -1, 34064, 34059, 34063, -1, 34064, 29054, 29056, -1, 34034, 34043, 29050, -1, 34064, 29056, 29057, -1, 34064, 29057, 29053, -1, 34064, 34061, 34059, -1, 34064, 31612, 34061, -1, 34064, 34063, 29054, -1, 34035, 34034, 29050, -1, 34037, 33912, 33909, -1, 34037, 33909, 34034, -1, 34039, 29050, 29062, -1, 34039, 34035, 29050, -1, 34033, 34037, 34034, -1, 29049, 34047, 28583, -1, 28583, 34047, 28584, -1, 28584, 34046, 28585, -1, 34047, 34046, 28584, -1, 28585, 34045, 28586, -1, 34046, 34045, 28585, -1, 28586, 34044, 28587, -1, 34045, 34044, 28586, -1, 28587, 34043, 28588, -1, 34044, 34043, 28587, -1, 34043, 29601, 28588, -1, 28597, 34065, 28603, -1, 34066, 34065, 28596, -1, 34067, 34065, 34066, -1, 34068, 34065, 34067, -1, 30525, 34069, 29108, -1, 29108, 34069, 34070, -1, 34070, 34069, 34071, -1, 28603, 34072, 28606, -1, 34073, 29547, 29550, -1, 34074, 34072, 34068, -1, 34068, 34072, 34065, -1, 34065, 34072, 28603, -1, 28606, 34075, 28609, -1, 28609, 34075, 28617, -1, 34076, 34075, 34074, -1, 34074, 34075, 34072, -1, 34072, 34075, 28606, -1, 28617, 34077, 28618, -1, 34071, 34077, 34076, -1, 34075, 34077, 28617, -1, 34076, 34077, 34075, -1, 30523, 34078, 30525, -1, 28622, 34078, 30523, -1, 28618, 34078, 28621, -1, 28621, 34078, 28622, -1, 34071, 34078, 34077, -1, 30525, 34078, 34069, -1, 34069, 34078, 34071, -1, 34077, 34078, 28618, -1, 29547, 34079, 29546, -1, 34080, 34081, 34073, -1, 34073, 34081, 29547, -1, 29547, 34081, 34079, -1, 34080, 34067, 34081, -1, 34082, 34068, 34080, -1, 34080, 34068, 34067, -1, 29546, 34083, 28601, -1, 28601, 34083, 28599, -1, 34079, 34083, 29546, -1, 34082, 34074, 34068, -1, 28599, 34084, 28627, -1, 28627, 34084, 28591, -1, 34079, 34084, 34083, -1, 34081, 34084, 34079, -1, 34083, 34084, 28599, -1, 34070, 34076, 34082, -1, 34082, 34076, 34074, -1, 34070, 34071, 34076, -1, 28591, 34066, 28596, -1, 34081, 34066, 34084, -1, 34067, 34066, 34081, -1, 34084, 34066, 28591, -1, 28596, 34065, 28597, -1, 29108, 34070, 29109, -1, 34085, 34070, 34086, -1, 29109, 34070, 34085, -1, 34086, 34082, 34087, -1, 34070, 34082, 34086, -1, 34087, 34080, 34088, -1, 34082, 34080, 34087, -1, 34088, 34073, 29549, -1, 34080, 34073, 34088, -1, 34073, 29550, 29549, -1, 29549, 31597, 34088, -1, 34088, 31597, 34087, -1, 34087, 31597, 34086, -1, 31595, 31594, 34089, -1, 29110, 34090, 29111, -1, 29109, 34090, 29110, -1, 34085, 34090, 29109, -1, 34086, 34091, 34085, -1, 34090, 34091, 29111, -1, 31597, 34091, 34086, -1, 34085, 34091, 34090, -1, 31596, 34092, 31597, -1, 31597, 34092, 34091, -1, 29111, 34093, 29112, -1, 34091, 34094, 29111, -1, 29111, 34094, 34093, -1, 29113, 34095, 26124, -1, 29112, 34095, 29113, -1, 26124, 34095, 34096, -1, 34093, 34095, 29112, -1, 34092, 34097, 34091, -1, 31596, 34097, 34092, -1, 34091, 34097, 34094, -1, 34096, 34098, 34089, -1, 34095, 34098, 34096, -1, 34094, 34098, 34093, -1, 34093, 34098, 34095, -1, 31595, 34099, 31596, -1, 31596, 34099, 34097, -1, 34097, 34099, 34094, -1, 34098, 34099, 34089, -1, 34089, 34099, 31595, -1, 34094, 34099, 34098, -1, 31592, 26128, 31593, -1, 26130, 26128, 29394, -1, 29394, 26128, 31592, -1, 26128, 26125, 31593, -1, 31593, 34089, 31594, -1, 26125, 34089, 31593, -1, 26125, 34096, 34089, -1, 26125, 26124, 34096, -1, 27769, 27764, 27766, -1, 27525, 27764, 27769, -1, 27756, 27758, 27525, -1, 27525, 27763, 27764, -1, 27758, 27760, 27525, -1, 27525, 27761, 27763, -1, 27760, 27761, 27525, -1, 27061, 27065, 28468, -1, 28468, 27065, 28466, -1, 28466, 27065, 28464, -1, 28464, 27065, 28462, -1, 28462, 27065, 28460, -1, 28460, 27065, 27230, -1, 27063, 27065, 27062, -1, 27062, 27065, 27061, -1, 27065, 27232, 27230, -1, 28421, 27524, 28422, -1, 28422, 27524, 28425, -1, 28425, 27524, 28427, -1, 28427, 27524, 28429, -1, 28429, 27524, 28431, -1, 27232, 27524, 28421, -1, 27065, 27524, 27232, -1, 27065, 27537, 27524, -1, 27802, 27801, 27537, -1, 27801, 27799, 27537, -1, 27799, 27797, 27537, -1, 27797, 27690, 27537, -1, 27690, 27692, 27537, -1, 27692, 28034, 27537, -1, 28030, 27525, 28034, -1, 28027, 27525, 28030, -1, 27537, 27525, 27524, -1, 28034, 27525, 27537, -1, 28027, 27756, 27525, -1, 27769, 27766, 27767, -1, 27783, 27785, 27532, -1, 27532, 27790, 27791, -1, 27785, 27787, 27532, -1, 27532, 27788, 27790, -1, 27787, 27788, 27532, -1, 27117, 27121, 27734, -1, 27734, 27121, 27732, -1, 27732, 27121, 27730, -1, 27730, 27121, 27728, -1, 27728, 27121, 27726, -1, 27726, 27121, 27221, -1, 27119, 27121, 27118, -1, 27118, 27121, 27117, -1, 27121, 27224, 27221, -1, 28447, 27531, 28451, -1, 28451, 27531, 28453, -1, 28453, 27531, 28455, -1, 28455, 27531, 28457, -1, 28457, 27531, 28459, -1, 27224, 27531, 28447, -1, 27121, 27531, 27224, -1, 27121, 27544, 27531, -1, 27725, 27724, 27544, -1, 27724, 27722, 27544, -1, 27722, 27720, 27544, -1, 27720, 27685, 27544, -1, 27685, 27687, 27544, -1, 27687, 28063, 27544, -1, 28056, 27532, 28059, -1, 28059, 27532, 28063, -1, 27544, 27532, 27531, -1, 28063, 27532, 27544, -1, 28056, 27783, 27532, -1, 27796, 27793, 27794, -1, 27796, 27791, 27793, -1, 27532, 27791, 27796, -1, 27695, 27517, 27530, -1, 27152, 27517, 27153, -1, 27153, 27517, 27156, -1, 27156, 27517, 27157, -1, 27163, 27517, 27695, -1, 27157, 27517, 27163, -1, 27149, 27517, 27147, -1, 27147, 27517, 27150, -1, 27150, 27517, 27152, -1, 27530, 27517, 27516, -1, 27149, 28008, 27517, -1, 27071, 27073, 27070, -1, 27070, 27073, 27069, -1, 27069, 27073, 28417, -1, 28417, 27073, 28415, -1, 28415, 27073, 28413, -1, 28008, 28009, 27517, -1, 28413, 27073, 28411, -1, 28411, 27073, 28409, -1, 28409, 27073, 27237, -1, 27073, 27239, 27237, -1, 28024, 28021, 28022, -1, 28009, 28011, 27517, -1, 27517, 28019, 28024, -1, 28024, 28019, 28021, -1, 28011, 28013, 27517, -1, 27517, 28018, 28019, -1, 27517, 28016, 28018, -1, 28013, 28015, 27517, -1, 27517, 28015, 28016, -1, 27239, 27516, 28435, -1, 28435, 27516, 28436, -1, 28436, 27516, 28439, -1, 28439, 27516, 28441, -1, 28441, 27516, 28443, -1, 28443, 27516, 28445, -1, 27073, 27516, 27239, -1, 27073, 27530, 27516, -1, 27775, 27774, 27530, -1, 27774, 27772, 27530, -1, 27772, 27771, 27530, -1, 27771, 27695, 27530, -1, 27159, 27160, 27164, -1, 27164, 27160, 27162, -1, 27160, 27161, 27162, -1, 27162, 27161, 27163, -1, 27161, 27157, 27163, -1, 27810, 27812, 27546, -1, 27546, 27817, 27818, -1, 27812, 27814, 27546, -1, 27546, 27815, 27817, -1, 27814, 27815, 27546, -1, 27085, 27089, 28371, -1, 28371, 27089, 28369, -1, 28369, 27089, 28367, -1, 28367, 27089, 28365, -1, 28365, 27089, 28363, -1, 28363, 27089, 27197, -1, 27087, 27089, 27086, -1, 27086, 27089, 27085, -1, 27089, 27199, 27197, -1, 28398, 27545, 28399, -1, 28399, 27545, 28402, -1, 28402, 27545, 28404, -1, 28404, 27545, 28406, -1, 28406, 27545, 28408, -1, 27199, 27545, 28398, -1, 27089, 27545, 27199, -1, 27089, 27558, 27545, -1, 27858, 27857, 27558, -1, 27857, 27855, 27558, -1, 27855, 27853, 27558, -1, 27853, 27675, 27558, -1, 27675, 27677, 27558, -1, 27677, 28121, 27558, -1, 28114, 27546, 28117, -1, 28117, 27546, 28121, -1, 27558, 27546, 27545, -1, 28121, 27546, 27558, -1, 28114, 27810, 27546, -1, 27823, 27820, 27821, -1, 27823, 27818, 27820, -1, 27546, 27818, 27823, -1, 27719, 27714, 27716, -1, 27539, 27714, 27719, -1, 27706, 27708, 27539, -1, 27539, 27713, 27714, -1, 27708, 27710, 27539, -1, 27539, 27711, 27713, -1, 27710, 27711, 27539, -1, 27077, 27081, 28394, -1, 28394, 27081, 28392, -1, 28392, 27081, 28390, -1, 28390, 27081, 28388, -1, 28388, 27081, 28386, -1, 28386, 27081, 27210, -1, 27079, 27081, 27078, -1, 27078, 27081, 27077, -1, 27081, 27212, 27210, -1, 27738, 27538, 27739, -1, 27739, 27538, 27742, -1, 27742, 27538, 27744, -1, 27744, 27538, 27746, -1, 27746, 27538, 27748, -1, 27212, 27538, 27738, -1, 27081, 27538, 27212, -1, 27081, 27551, 27538, -1, 27829, 27828, 27551, -1, 27828, 27826, 27551, -1, 27826, 27824, 27551, -1, 27824, 27680, 27551, -1, 27680, 27682, 27551, -1, 27682, 28092, 27551, -1, 28088, 27539, 28092, -1, 28085, 27539, 28088, -1, 27551, 27539, 27538, -1, 28092, 27539, 27551, -1, 28085, 27706, 27539, -1, 27719, 27716, 27717, -1, 27852, 27849, 27850, -1, 27837, 27839, 27553, -1, 27553, 27847, 27852, -1, 27852, 27847, 27849, -1, 27839, 27841, 27553, -1, 27553, 27846, 27847, -1, 27553, 27844, 27846, -1, 27841, 27843, 27553, -1, 27553, 27843, 27844, -1, 27093, 27097, 28348, -1, 28348, 27097, 28346, -1, 28346, 27097, 28344, -1, 28344, 27097, 28342, -1, 28342, 27097, 28340, -1, 28340, 27097, 27189, -1, 27095, 27097, 27094, -1, 27094, 27097, 27093, -1, 27097, 27191, 27189, -1, 28375, 27552, 28376, -1, 28376, 27552, 28379, -1, 28379, 27552, 28381, -1, 28381, 27552, 28383, -1, 28383, 27552, 28385, -1, 27191, 27552, 28375, -1, 27097, 27552, 27191, -1, 27097, 27565, 27552, -1, 27885, 27884, 27565, -1, 27884, 27882, 27565, -1, 27882, 27881, 27565, -1, 27881, 27647, 27565, -1, 27830, 27165, 27831, -1, 27831, 27165, 27651, -1, 27651, 27553, 27647, -1, 27167, 27553, 27165, -1, 27565, 27553, 27552, -1, 27647, 27553, 27565, -1, 27165, 27553, 27651, -1, 27167, 27836, 27553, -1, 27836, 27837, 27553, -1, 27866, 27868, 27560, -1, 27560, 27873, 27874, -1, 27868, 27870, 27560, -1, 27560, 27871, 27873, -1, 27870, 27871, 27560, -1, 27101, 27105, 28325, -1, 28325, 27105, 28323, -1, 28323, 27105, 28321, -1, 28321, 27105, 28319, -1, 28319, 27105, 28317, -1, 28317, 27105, 27182, -1, 27103, 27105, 27102, -1, 27102, 27105, 27101, -1, 27105, 27184, 27182, -1, 28352, 27559, 28353, -1, 28353, 27559, 28356, -1, 28356, 27559, 28358, -1, 28358, 27559, 28360, -1, 28360, 27559, 28362, -1, 27184, 27559, 28352, -1, 27105, 27559, 27184, -1, 27105, 27572, 27559, -1, 27891, 27890, 27572, -1, 27890, 27888, 27572, -1, 27888, 27886, 27572, -1, 27886, 27655, 27572, -1, 27655, 27657, 27572, -1, 27657, 28150, 27572, -1, 28143, 27560, 28146, -1, 28146, 27560, 28150, -1, 27572, 27560, 27559, -1, 28150, 27560, 27572, -1, 28143, 27866, 27560, -1, 27879, 27876, 27877, -1, 27879, 27874, 27876, -1, 27560, 27874, 27879, -1, 27567, 27908, 27913, -1, 27913, 27908, 27910, -1, 27900, 27902, 27567, -1, 27567, 27907, 27908, -1, 27902, 27904, 27567, -1, 27904, 27905, 27567, -1, 27567, 27905, 27907, -1, 27109, 27113, 28302, -1, 28302, 27113, 28300, -1, 28300, 27113, 28298, -1, 28298, 27113, 28296, -1, 28296, 27113, 28294, -1, 28294, 27113, 27172, -1, 27111, 27113, 27110, -1, 27110, 27113, 27109, -1, 27113, 27173, 27172, -1, 28329, 27566, 28330, -1, 28330, 27566, 28333, -1, 28333, 27566, 28335, -1, 28335, 27566, 28337, -1, 28337, 27566, 28339, -1, 27173, 27566, 28329, -1, 27113, 27566, 27173, -1, 27113, 27579, 27566, -1, 27919, 27918, 27579, -1, 27918, 27916, 27579, -1, 27916, 27914, 27579, -1, 27914, 27660, 27579, -1, 27660, 27662, 27579, -1, 27662, 28182, 27579, -1, 28174, 27567, 28178, -1, 28178, 27567, 28182, -1, 27579, 27567, 27566, -1, 28182, 27567, 27579, -1, 28174, 28170, 27567, -1, 28170, 27899, 27567, -1, 27913, 27910, 27911, -1, 27899, 27900, 27567, -1, 27927, 27928, 27574, -1, 27574, 27936, 27941, -1, 27941, 27936, 27938, -1, 27928, 27930, 27574, -1, 27574, 27935, 27936, -1, 27930, 27932, 27574, -1, 27932, 27933, 27574, -1, 27574, 27933, 27935, -1, 27125, 27129, 27624, -1, 27624, 27129, 27622, -1, 27622, 27129, 27620, -1, 27620, 27129, 27618, -1, 27618, 27129, 27616, -1, 27616, 27129, 27292, -1, 27127, 27129, 27126, -1, 27126, 27129, 27125, -1, 27129, 27290, 27292, -1, 28306, 27573, 28307, -1, 28307, 27573, 28310, -1, 28310, 27573, 28312, -1, 28312, 27573, 28314, -1, 28314, 27573, 28316, -1, 27290, 27573, 28306, -1, 27129, 27573, 27290, -1, 27129, 27582, 27573, -1, 27977, 27976, 27582, -1, 27976, 27974, 27582, -1, 27974, 27972, 27582, -1, 27972, 27665, 27582, -1, 27665, 27667, 27582, -1, 27667, 28214, 27582, -1, 28206, 27574, 28210, -1, 28210, 27574, 28214, -1, 27582, 27574, 27573, -1, 28214, 27574, 27582, -1, 28206, 28202, 27574, -1, 28202, 27927, 27574, -1, 27941, 27938, 27939, -1, 27971, 27966, 27968, -1, 27468, 27966, 27971, -1, 27958, 27960, 27468, -1, 27468, 27965, 27966, -1, 27960, 27962, 27468, -1, 27468, 27963, 27965, -1, 27962, 27963, 27468, -1, 27135, 27137, 27134, -1, 27134, 27137, 27133, -1, 27133, 27137, 27615, -1, 27615, 27137, 27613, -1, 27613, 27137, 27611, -1, 27611, 27137, 27609, -1, 27609, 27137, 27607, -1, 27607, 27137, 27458, -1, 27137, 27456, 27458, -1, 27628, 27465, 27629, -1, 27629, 27465, 27632, -1, 27632, 27465, 27634, -1, 27634, 27465, 27636, -1, 27636, 27465, 27638, -1, 27456, 27465, 27628, -1, 27137, 27465, 27456, -1, 27137, 27464, 27465, -1, 27983, 27982, 27464, -1, 27982, 27980, 27464, -1, 27980, 27978, 27464, -1, 27978, 27670, 27464, -1, 27670, 27672, 27464, -1, 27672, 28274, 27464, -1, 28270, 27468, 28274, -1, 28267, 27468, 28270, -1, 27464, 27468, 27465, -1, 28274, 27468, 27464, -1, 28267, 27958, 27468, -1, 27971, 27968, 27969, -1, 28246, 27521, 27473, -1, 28238, 28234, 27521, -1, 28234, 27991, 27521, -1, 28005, 28002, 28003, -1, 27991, 27992, 27521, -1, 28005, 28000, 28002, -1, 27521, 28000, 28005, -1, 27992, 27994, 27521, -1, 27521, 27999, 28000, -1, 27994, 27996, 27521, -1, 27521, 27997, 27999, -1, 27996, 27997, 27521, -1, 27596, 27520, 27597, -1, 27597, 27520, 27600, -1, 27600, 27520, 27602, -1, 27602, 27520, 27604, -1, 27604, 27520, 27606, -1, 27348, 27520, 27596, -1, 27347, 27520, 27348, -1, 27141, 27145, 27592, -1, 27592, 27145, 27590, -1, 27590, 27145, 27588, -1, 27588, 27145, 27586, -1, 27586, 27145, 27584, -1, 27584, 27145, 27347, -1, 27143, 27145, 27142, -1, 27142, 27145, 27141, -1, 27347, 27145, 27520, -1, 27145, 27473, 27520, -1, 27944, 27641, 27948, -1, 27948, 27641, 27950, -1, 27950, 27641, 27473, -1, 27946, 27641, 27943, -1, 27943, 27641, 27944, -1, 27641, 27644, 27473, -1, 27644, 28246, 27473, -1, 28242, 27521, 28246, -1, 28238, 27521, 28242, -1, 27473, 27521, 27520, -1 - ] - } - } - DEF estop_covers Shape { - appearance Appearance { - material Material { - diffuseColor 1 0.85 0 - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.023599803 0.11585544 -0.26697496, -0.024187595 0.11632471 -0.26885065, -0.023490191 0.094750375 -0.25614783, -0.023071289 0.11505194 -0.26530495, -0.010301471 0.088050306 -0.29097721, -0.010251164 0.088038981 -0.29099587, -0.010251135 0.079470441 -0.28671226, -0.022677839 0.11403298 -0.26394418, -0.022419035 0.11274555 -0.26277548, -0.012784779 0.088745996 -0.28993008, -0.013045341 0.080105618 -0.28544152, -0.022248447 0.11176287 -0.26195231, -0.022034436 0.095991746 -0.25366479, -0.021990716 0.1108899 -0.26103225, -0.015105426 0.08974281 -0.28875366, -0.01564616 0.080887944 -0.28387696, -0.016986281 0.090936184 -0.28767207, -0.018015355 0.08180587 -0.28204072, -0.021473825 0.10986461 -0.2596097, -0.02076149 0.10908264 -0.25807658, -0.020252079 0.097144842 -0.25135848, -0.018535078 0.092335314 -0.2867195, -0.020117342 0.082845479 -0.2799612, -0.019812346 0.10853766 -0.25644532, -0.019790411 0.093926117 -0.28594899, -0.018603146 0.10824065 -0.2547805, -0.018169612 0.098192379 -0.24926287, -0.020777494 0.095679909 -0.28541288, -0.021921426 0.083991796 -0.27766809, -0.017094165 0.10818161 -0.25312641, -0.01581797 0.099119112 -0.24740914, -0.021509677 0.097531974 -0.28516001, -0.015271872 0.10833719 -0.25155529, -0.022014499 0.099432468 -0.28521749, -0.013231933 0.099911243 -0.24582481, -0.012970567 0.10868728 -0.25003943, -0.022311538 0.10133222 -0.2856057, -0.023400605 0.085227564 -0.27519637, -0.010449767 0.10055691 -0.24453336, -0.010499835 0.10911709 -0.24883756, -0.010449886 0.10912548 -0.24881691, -0.022464484 0.102442 -0.28585967, -0.02268371 0.10355729 -0.28597072, -0.02312246 0.10527171 -0.28587255, -0.023641616 0.10695145 -0.28545216, -0.024533093 0.08653456 -0.27258205, -0.024185568 0.10854091 -0.28471968, -0.024739921 0.11009404 -0.28359908, -0.025301844 0.087893322 -0.26986393, -0.025182456 0.11134894 -0.28225383, -0.025509953 0.11234456 -0.28066424, -0.02569586 0.089283794 -0.26708239, -0.025720447 0.11335775 -0.27863762, -0.025729984 0.11437541 -0.27660218, -0.025709003 0.090685502 -0.26427871, -0.025538623 0.11538941 -0.27457386, -0.025341272 0.092077494 -0.26149425, -0.025372654 0.11582547 -0.27356371, -0.025163621 0.116142 -0.27252489, -0.024598032 0.093439192 -0.25877073, -0.024741292 0.11640492 -0.27078697, 0.003733784 0.086224005 -0.29049426, 0.008441031 0.079317182 -0.28701895, 0.0013176799 0.085955709 -0.29037145, 0.0060964823 0.086752057 -0.29074699, 0.0083708167 0.087532029 -0.29112628, 0.0084409714 0.087559938 -0.29113972, -0.0081695616 0.087501004 -0.29118851, -0.0082396865 0.079285696 -0.28708187, -0.0082396865 0.087528348 -0.29120263, -0.0058951974 0.086729333 -0.29079223, -0.0035326183 0.0862104 -0.29052153, -0.001116395 0.085951135 -0.29038051, 0.023598641 0.10664205 -0.28540504, 0.024186462 0.10842404 -0.28465489, 0.023489475 0.085316077 -0.27501982, 0.023070216 0.10482402 -0.28576458, 0.010300547 0.10915634 -0.24875942, 0.01025027 0.10916455 -0.24873903, 0.01025033 0.100596 -0.2444554, 0.022676885 0.10312389 -0.2857658, 0.022417903 0.10141663 -0.28543738, 0.012783855 0.10873628 -0.24994409, 0.013044536 0.099960774 -0.24572599, 0.022247463 0.10016829 -0.28514534, 0.022033662 0.084074855 -0.27750266, 0.021989673 0.098908439 -0.28499937, 0.015104413 0.10839346 -0.25144741, 0.015645474 0.099178582 -0.2472907, 0.021472752 0.097155273 -0.28503248, 0.016985327 0.10824437 -0.25305116, 0.01801455 0.098260745 -0.24912679, 0.020760477 0.095459625 -0.28532702, 0.020251244 0.082921758 -0.27980915, 0.018534154 0.1083221 -0.25474212, 0.019811481 0.093827695 -0.28587016, 0.020116687 0.097220987 -0.25120655, 0.019789428 0.10866018 -0.25647697, 0.018602192 0.092317641 -0.28663152, 0.018168807 0.081874058 -0.28190461, 0.020776629 0.1092838 -0.25820163, 0.021920651 0.096074805 -0.25349942, 0.017093211 0.090958908 -0.28757694, 0.015817165 0.080947295 -0.28375831, 0.021508694 0.110193 -0.25983498, 0.015271038 0.089795485 -0.28864428, 0.022013396 0.11137934 -0.2613205, 0.013231009 0.080155283 -0.28534266, 0.012969762 0.088793054 -0.28983387, 0.022310436 0.11282998 -0.26260719, 0.02339983 0.094838947 -0.25597134, 0.010448873 0.079509586 -0.28663442, 0.010498941 0.088089645 -0.29089871, 0.010448873 0.088077992 -0.29091811, 0.02246353 0.11369914 -0.26334283, 0.022682488 0.1144572 -0.26416829, 0.023121446 0.11540747 -0.26559871, 0.023640484 0.11607936 -0.2671946, 0.024532199 0.093532011 -0.25858575, 0.024184436 0.11644721 -0.2689057, 0.024738729 0.11648278 -0.27082047, 0.025301129 0.092173159 -0.26130369, 0.025181442 0.11615956 -0.2726315, 0.025508821 0.11548576 -0.27438182, 0.025695086 0.090782613 -0.26408517, 0.025719225 0.11447255 -0.27640861, 0.025728792 0.11345503 -0.27844396, 0.025708228 0.089380965 -0.26688892, 0.025537491 0.11244093 -0.28047213, 0.025340497 0.087988973 -0.26967326, 0.025371522 0.11189455 -0.28142729, 0.025162518 0.1112534 -0.28230399, 0.024597287 0.08662729 -0.27239701, 0.024740249 0.11002091 -0.28355715, -0.0037345886 0.10767394 -0.24758831, -0.0084418058 0.10074931 -0.24414846, -0.001318574 0.10741478 -0.24744743, -0.0060972571 0.10819298 -0.24785876, -0.0083717108 0.10896447 -0.24825519, -0.0084418356 0.10899211 -0.24826932, 0.0081686676 0.10899569 -0.24819294, 0.0082389116 0.10078074 -0.24408564, 0.008238852 0.10902357 -0.24820656, 0.0058943033 0.10821567 -0.24781373, 0.0035317242 0.10768761 -0.24756083, 0.0011155009 0.10741943 -0.24743807, -0.024220556 0.1140919 -0.27895823, -0.024011075 0.11311027 -0.28092179, -0.02471742 0.11310892 -0.2809245, -0.024921268 0.11409065 -0.27896065, -0.024229944 0.115078 -0.27698582, -0.024930626 0.11507666 -0.2769886, -0.024745196 0.11605915 -0.27502325, -0.024038851 0.11606044 -0.27502069, 0.024228662 0.11418346 -0.27877593, 0.024744064 0.11320232 -0.28073826, 0.024037778 0.11320104 -0.28074098, 0.024929553 0.11418475 -0.27877313, 0.024219453 0.1151696 -0.27680337, 0.024920285 0.1151707 -0.27680099, 0.024716377 0.11615242 -0.27483717, 0.024009883 0.11615121 -0.27483976, -0.020593405 0.097285226 -0.25666818, -0.021837711 0.096090823 -0.25905743, -0.020930797 0.11487977 -0.26618245, -0.021426618 0.11563428 -0.26772743, -0.02200073 0.11610958 -0.26954517, -0.010058194 0.10816222 -0.25096366, -0.010058135 0.10174164 -0.24775398, -0.010124058 0.1081529 -0.25099409, -0.022525191 0.11619653 -0.2713713, -0.022737086 0.094835922 -0.2615675, -0.022943079 0.1159223 -0.27310178, -0.011602342 0.1079413 -0.25175303, -0.012635618 0.10110295 -0.24903187, -0.013012975 0.10776711 -0.25263923, -0.023277491 0.093540579 -0.26415876, -0.023245901 0.11529769 -0.2747573, -0.023430556 0.11434762 -0.27665761, -0.015013278 0.10032453 -0.25058874, -0.014887631 0.10764165 -0.25413051, -0.023450106 0.092225105 -0.26679, -0.023421556 0.1133942 -0.27856493, -0.016431957 0.1077337 -0.25572833, -0.023252666 0.090910316 -0.26941988, -0.023219019 0.11244489 -0.28046376, -0.017154157 0.099419057 -0.25240013, -0.017685741 0.10808185 -0.25739035, -0.023058742 0.11195588 -0.28131643, -0.022445828 0.11021259 -0.2832638, -0.022687972 0.089616999 -0.27200696, -0.021943688 0.10880148 -0.28421322, -0.022862315 0.11138469 -0.28209296, -0.021352679 0.10705246 -0.28493115, -0.021764845 0.0883656 -0.27451006, -0.020806164 0.10521594 -0.28526857, -0.020389378 0.10344866 -0.2852416, -0.020498216 0.087175921 -0.27689001, -0.020122111 0.10169594 -0.28487787, -0.019882798 0.10006277 -0.28449887, -0.01949507 0.098437443 -0.2843565, -0.018889248 0.096706167 -0.28445625, -0.018907875 0.086066499 -0.27910897, -0.018077999 0.095066562 -0.28479946, -0.017018825 0.085055187 -0.28113195, -0.017035007 0.093546823 -0.28535825, -0.015711784 0.092159241 -0.2861093, -0.014861166 0.084157705 -0.2829271, -0.014085829 0.090950802 -0.28700331, -0.019412726 0.10965018 -0.26068291, -0.019023985 0.098400533 -0.25443736, -0.019697875 0.11023432 -0.26145676, -0.018673927 0.10871693 -0.25906578, -0.012468725 0.083388478 -0.28446606, -0.012205631 0.089978963 -0.28794298, -0.0098794401 0.082759231 -0.28572443, -0.0099454522 0.089198068 -0.28890908, -0.0098794103 0.089179754 -0.28893441, -0.02052474 0.11386262 -0.26481542, -0.020348579 0.11316717 -0.26411769, -0.020222783 0.1123898 -0.26348689, -0.01992625 0.11088772 -0.26218668, 0.021425515 0.10711135 -0.28477663, 0.021836817 0.088448003 -0.27434582, 0.021999866 0.10885046 -0.28406617, 0.020929575 0.10542256 -0.28510019, 0.010057211 0.08921735 -0.2888591, 0.0100573 0.082796872 -0.28564957, 0.010123044 0.089236006 -0.28883347, 0.0205926 0.087253556 -0.2767351, 0.011601537 0.089716092 -0.28820881, 0.022524029 0.11036348 -0.28303972, 0.022736222 0.089702755 -0.27183586, 0.022941977 0.11158323 -0.28178194, 0.012634724 0.083435759 -0.28437141, 0.013012111 0.090320542 -0.28753766, 0.023276627 0.090998039 -0.26924476, 0.023244619 0.11253257 -0.28028879, 0.023429483 0.11348248 -0.27838856, 0.015012592 0.084214181 -0.28281468, 0.014886707 0.091438144 -0.28654239, 0.023449361 0.092313632 -0.26661351, 0.023420513 0.11443612 -0.27648124, 0.016430855 0.092771649 -0.28565732, 0.023251832 0.093628421 -0.26398346, 0.017153352 0.085119665 -0.28100333, 0.017684609 0.094309971 -0.28493834, 0.023217887 0.11538544 -0.27458242, 0.02305761 0.11577386 -0.27367952, 0.022687137 0.094921544 -0.26139659, 0.022444665 0.1162858 -0.27111644, 0.021942556 0.11619839 -0.26941782, 0.022861302 0.11605261 -0.27275667, 0.02176404 0.096173063 -0.2588934, 0.021351516 0.11572301 -0.26758787, 0.02080512 0.11489089 -0.26591629, 0.020497471 0.097362876 -0.25651351, 0.020388484 0.11380881 -0.26451877, 0.020120978 0.11246616 -0.26333502, 0.019881874 0.11118276 -0.26225623, 0.019493997 0.11009368 -0.26104143, 0.018906951 0.098472267 -0.2542946, 0.018888414 0.10913453 -0.25959659, 0.018076897 0.10842524 -0.25807908, 0.01701799 0.099483594 -0.25227144, 0.017034054 0.10796003 -0.25652808, 0.01571101 0.10772812 -0.2549673, 0.019411832 0.097885072 -0.28421703, 0.01902315 0.086138204 -0.27896616, 0.019696862 0.098854572 -0.28422001, 0.014860272 0.10038094 -0.25047621, 0.014084876 0.10771811 -0.25346431, 0.018672913 0.096031278 -0.28444088, 0.01246798 0.10115035 -0.24893752, 0.012204766 0.10788658 -0.25212291, 0.019925237 0.099830598 -0.28430465, 0.020221829 0.10177204 -0.28472599, 0.0098785758 0.10177955 -0.247679, 0.0099445581 0.10819069 -0.2509186, 0.0098786056 0.10819989 -0.25088879, 0.020523757 0.10371873 -0.28510684, 0.020347565 0.10274316 -0.28496918, -0.0079112947 0.08885996 -0.29016626, -0.0074358284 0.088663876 -0.29008949, -0.0078430772 0.08851108 -0.29079756, -0.0052863657 0.087670296 -0.29036513, -0.0050020218 0.087911174 -0.28970155, -0.0026218295 0.087161198 -0.29009822, -0.0024768114 0.087456033 -0.28946221, 9.7155571e-05 0.08699365 -0.29000169, 9.4354153e-05 0.087306723 -0.28937563, 0.0026653707 0.087465867 -0.28944293, 0.0028163493 0.087171316 -0.29007775, 0.0051905811 0.087930337 -0.2896634, 0.0054807961 0.087690637 -0.29032472, 0.0076243281 0.088692352 -0.29003295, 0.0080375671 0.088541135 -0.29073802, 0.008099705 0.08889015 -0.29010588, -0.0081007183 0.10896321 -0.24995402, -0.008038491 0.10925934 -0.24929544, -0.0076252222 0.10878597 -0.24983963, -0.0054817498 0.10841839 -0.24886304, -0.0051914752 0.10803342 -0.24945176, -0.0028171539 0.10790923 -0.24859595, -0.0026663542 0.10757816 -0.24921241, -9.5248222e-05 0.10742885 -0.24912551, -9.816885e-05 0.10774174 -0.24849945, 0.0024759769 0.10758784 -0.24919301, 0.0026209056 0.10791942 -0.24857557, 0.0050010681 0.10805255 -0.2494134, 0.0052854717 0.10843882 -0.24882245, 0.0074349642 0.1088146 -0.2497828, 0.0078421831 0.10928927 -0.24923554, 0.007910341 0.10899347 -0.24989375, -0.0079347491 0.10195796 -0.24732178, -0.0079348683 0.10776912 -0.250227, -0.005399853 0.10698515 -0.24982309, -0.0027698278 0.1065111 -0.24957371, -9.1850758e-05 0.10635562 -0.24948326, 0.0077510476 0.1019875 -0.24726272, 0.0025861263 0.10652134 -0.24955362, 0.0052161813 0.10700522 -0.24978301, 0.0077511966 0.10779877 -0.250168, 0.0079339743 0.082580894 -0.2860817, 0.0079338551 0.088392064 -0.28898686, 0.0053988993 0.087598473 -0.28860202, 0.002768904 0.087114558 -0.28837261, 9.0956688e-05 0.086948872 -0.28830236, -0.0077518523 0.082551256 -0.28614077, -0.0025871098 0.08710438 -0.28839275, -0.0052169859 0.087578475 -0.28864208, -0.0077520311 0.0883625 -0.28904596, -0.0096017718 0.079367533 -0.28691807, -0.0089270473 0.079305574 -0.28704196, -0.009128809 0.10072678 -0.24419343, -0.0098023713 0.10066235 -0.24432254, 0.0098015964 0.07940419 -0.28684503, 0.0091280043 0.079339713 -0.28697407, 0.0096010268 0.1006989 -0.24424967, 0.0089263022 0.10076083 -0.24412546, 0.009375751 0.082678616 -0.28588605, 0.0086627603 0.082606018 -0.28603101, -0.0093765557 0.10186021 -0.24751744, -0.0086636543 0.10193263 -0.2473723, 0.0084805191 0.10196507 -0.24730781, 0.0091947913 0.10189521 -0.24744761, -0.0084813833 0.082573757 -0.28609553, -0.009195596 0.082643613 -0.28595582, 0.020804256 0.11312363 -0.26232305, 0.02147609 0.11233337 -0.26167822, 0.021613985 0.11312532 -0.26231995, 0.020493865 0.11173335 -0.26110309, 0.021276921 0.11161835 -0.2609764, 0.019968271 0.1106094 -0.25971314, 0.020788491 0.11057611 -0.25965804, 0.020095885 0.10976794 -0.25822315, 0.019195408 0.10974397 -0.25817826, 0.019162238 0.10919549 -0.25669757, 0.018158883 0.10915999 -0.25658235, 0.017969787 0.10886903 -0.25515059, 0.016843915 0.10884725 -0.25499752, 0.016455263 0.10877538 -0.25360009, 0.015210629 0.10877624 -0.25346354, 0.014614761 0.10889651 -0.25213486, 0.013234764 0.10890964 -0.25203934, 0.011792362 0.10907693 -0.25121877, 0.012489796 0.10917805 -0.25084382, 0.010283411 0.1092761 -0.25051594, 0.0099802613 0.10956798 -0.24972042, -0.021725774 0.11304335 -0.26248309, -0.020702928 0.11196741 -0.26157108, -0.020916015 0.11304495 -0.26248014, -0.021424294 0.11163336 -0.26123878, -0.020366162 0.11103722 -0.26054931, -0.020911902 0.11049885 -0.2598176, -0.019771039 0.11010355 -0.25917, -0.020155251 0.10963267 -0.25824434, -0.018962026 0.10941441 -0.25770867, -0.019156903 0.10906485 -0.25663146, -0.017891109 0.10895807 -0.25617781, -0.017868251 0.10876736 -0.25499764, -0.016526639 0.10873859 -0.25463685, -0.01628381 0.10872224 -0.2534261, -0.014831811 0.10874058 -0.25314152, -0.014341712 0.10889377 -0.25193855, -0.012845904 0.10892311 -0.25179493, -0.012316912 0.10918531 -0.25075123, -0.010469764 0.10923693 -0.25059399, -0.010174036 0.10952987 -0.2497963, 0.010172963 0.089104161 -0.29065377, 0.01046896 0.089566678 -0.28994066, 0.012316078 0.08966127 -0.28980514, 0.01284495 0.090338856 -0.28896892, 0.014340788 0.090436056 -0.28885934, 0.014830947 0.091306597 -0.28801495, 0.016282856 0.091522977 -0.28782973, 0.016525656 0.092501476 -0.28711614, 0.017867267 0.092807174 -0.28692257, 0.017890185 0.093865976 -0.28636703, 0.019156098 0.094292819 -0.28618005, 0.018961042 0.095364258 -0.28581342, 0.020154208 0.09592396 -0.2856665, 0.019770056 0.096946955 -0.28548768, 0.0209108 0.097702086 -0.2854152, 0.020365328 0.098610476 -0.28540692, 0.02142334 0.099519789 -0.28546989, 0.020701915 0.099986121 -0.28553769, 0.02172482 0.10136126 -0.28585127, 0.020915002 0.10135978 -0.28585431, -0.0099811852 0.089066088 -0.2907297, -0.012490779 0.089730814 -0.28974363, -0.010284275 0.089527473 -0.29001889, -0.011793315 0.089969903 -0.2894375, -0.014615744 0.090594545 -0.2887437, -0.013235688 0.090525955 -0.28881148, -0.015211612 0.091585204 -0.28784999, -0.016456127 0.091693833 -0.28776759, -0.016844779 0.092854783 -0.28698647, -0.017970711 0.092990339 -0.28691205, -0.018159688 0.09431015 -0.28628555, -0.019163311 0.094423711 -0.28624472, -0.019196391 0.095937282 -0.28579488, -0.020096689 0.095987663 -0.28578719, -0.019969285 0.097684309 -0.28556624, -0.020789444 0.097620413 -0.28557256, -0.021277994 0.099300534 -0.28561524, -0.020494729 0.09947069 -0.28563103, -0.021477193 0.10029076 -0.28576604, -0.020805299 0.1012809 -0.28601125, -0.021614999 0.10127936 -0.28601429, -0.021885037 0.11405557 -0.26333696, -0.021170318 0.11442827 -0.26371095, -0.022115588 0.11493142 -0.26429847, -0.021557897 0.11554046 -0.2651445, -0.022526711 0.11591846 -0.26579314, -0.022071898 0.11642286 -0.26687381, -0.023005843 0.11662608 -0.26744744, -0.022585064 0.11692834 -0.26860175, -0.023554951 0.11705045 -0.26939693, -0.023080885 0.11711654 -0.27038684, -0.024053425 0.11708334 -0.27135465, -0.023520082 0.11698192 -0.27218446, -0.024454504 0.11674914 -0.27323109, -0.023815244 0.11662985 -0.27362937, 0.020959854 0.11407948 -0.26312101, 0.021865278 0.11451922 -0.26355937, 0.02118361 0.1149177 -0.26401809, 0.022254586 0.11564922 -0.2650204, 0.021609455 0.11592938 -0.26549512, 0.022764921 0.11652853 -0.26675937, 0.022166282 0.11672282 -0.26731315, 0.023327053 0.11706097 -0.26867753, 0.022747278 0.11714236 -0.26926181, 0.0238159 0.11720578 -0.2704691, 0.023275465 0.11716932 -0.2712172, 0.024241805 0.11702923 -0.27224529, 0.023696244 0.11683734 -0.27305958, 0.024507314 0.11668433 -0.27355874, -0.024508476 0.11240546 -0.28211695, -0.023697317 0.11209792 -0.28253904, -0.024242938 0.1115617 -0.2831811, -0.023276538 0.11082344 -0.2839103, -0.023817092 0.11024694 -0.28438815, -0.022748351 0.10924308 -0.2850621, -0.023328125 0.1087269 -0.28534761, -0.022167325 0.10743265 -0.28589588, -0.022765934 0.10687302 -0.2860727, -0.021610588 0.10550211 -0.28635219, -0.022255689 0.1049542 -0.28641275, -0.021184713 0.10371344 -0.28642914, -0.021866292 0.10310736 -0.28638563, -0.020960808 0.10249279 -0.28629693, 0.023814201 0.11242965 -0.28203139, 0.024453521 0.11218274 -0.28236565, 0.023519039 0.11148512 -0.28318009, 0.024052262 0.11088219 -0.28375921, 0.023079634 0.11012803 -0.28436646, 0.023553878 0.1092966 -0.28490761, 0.022583872 0.10858704 -0.28528699, 0.02300477 0.10748239 -0.28573811, 0.022070765 0.10690162 -0.28591964, 0.022525609 0.10573438 -0.28616479, 0.021556854 0.10498859 -0.28625157, 0.022114515 0.10394663 -0.2862719, 0.021169186 0.10317458 -0.28622195, 0.021884024 0.10265164 -0.28614858, 0.008120954 0.088573739 -0.29075506, 0.0087771118 0.088793382 -0.29083142, 0.0088537335 0.089169651 -0.29016933, 0.0094487071 0.088964254 -0.29080224, 0.0096243024 0.089382574 -0.29012054, 0.010116369 0.089094475 -0.29066953, 0.010391802 0.089550942 -0.28996238, -0.010206968 0.089512005 -0.29003981, -0.00943169 0.089345142 -0.29019308, -0.0092517138 0.088928312 -0.29087296, -0.0099244416 0.089056641 -0.29074511, -0.0086607337 0.089134887 -0.29023555, -0.008579433 0.088759691 -0.29089656, -0.0079264939 0.08854337 -0.29081517, -0.0081219375 0.10929258 -0.24931136, -0.0087780654 0.10948555 -0.24944124, -0.0088547766 0.10918187 -0.25013921, -0.0094495714 0.10956492 -0.2495952, -0.009625107 0.10927047 -0.250339, -0.010117292 0.10953675 -0.24977902, -0.010392666 0.10924488 -0.25056848, 0.010205984 0.10928383 -0.25049099, 0.0094308555 0.10930607 -0.25026554, 0.0092508197 0.10960007 -0.24952412, 0.0099235177 0.1095746 -0.24970371, 0.0086598098 0.10921401 -0.25007191, 0.0085785389 0.10951771 -0.24937519, 0.0079256296 0.10932286 -0.24925086, 0.0093081594 0.10823098 -0.25065446, 0.0087350607 0.10816568 -0.25045598, 0.0081780255 0.10798676 -0.25028041, -0.008361578 0.1079555 -0.25034261, -0.0089233816 0.10813315 -0.25052425, -0.0094955862 0.10819574 -0.25072727, -0.0097925663 0.10918829 -0.24858186, -0.0091153383 0.1091475 -0.24840128, 0.0089094639 0.10918105 -0.2483325, 0.0095875263 0.10922492 -0.24850792, 0.0097916722 0.087927684 -0.29110929, 0.0091144443 0.087758601 -0.29118517, -0.0089104474 0.087723836 -0.29125312, -0.0095884502 0.087890178 -0.29118288, 0.0083605349 0.088596314 -0.28906664, 0.0089224577 0.088848189 -0.28909978, 0.0094945431 0.089048401 -0.28902784, -0.009308964 0.089010924 -0.28909972, -0.0087360442 0.088812992 -0.28916651, -0.0081789792 0.088565111 -0.28912887, -0.0079338253 0.088447273 -0.29096618, -0.010238051 0.088198692 -0.29105958, -0.0099931359 0.088961586 -0.29087153, -0.0088611245 0.087884828 -0.29131791, -0.0081694722 0.087683693 -0.29125753, -0.008808583 0.088056818 -0.29134318, -0.0081029236 0.087848961 -0.29127383, -0.0087558925 0.088230774 -0.29132739, -0.0080432594 0.088016167 -0.29125077, -0.0087056756 0.088396534 -0.2912707, -0.0079936683 0.088176772 -0.29118934, -0.0086608827 0.08854562 -0.29117647, -0.0079565942 0.088322893 -0.29109305, -0.0086236298 0.088670298 -0.29104975, -0.0092124939 0.088403374 -0.29129133, -0.009441793 0.088482633 -0.29125106, -0.0096727908 0.08855781 -0.29119554, -0.010059029 0.088838726 -0.29097322, -0.01011914 0.088694096 -0.29104549, -0.010170311 0.088534042 -0.29108483, -0.010210752 0.088366449 -0.29108968, -0.010049731 0.088970557 -0.29085472, -0.010114908 0.088847563 -0.29095528, -0.010174155 0.088703156 -0.29102653, -0.010224491 0.088543624 -0.29106534, -0.010263443 0.088376582 -0.29106992, -0.01028952 0.088209465 -0.29104021, -0.0080962479 0.087655053 -0.29124284, -0.0080268383 0.087819427 -0.29125866, -0.0079647005 0.087985754 -0.29123476, -0.007912904 0.088145584 -0.29117304, -0.00787431 0.088291273 -0.29107597, -0.0078506172 0.088415071 -0.29094875, -0.012858838 0.088985607 -0.2899631, -0.012795687 0.089201689 -0.28999236, -0.020459384 0.095889628 -0.28572005, -0.020356208 0.095944569 -0.28575617, -0.015058428 0.089923754 -0.28884512, -0.014981091 0.090115771 -0.28889117, -0.021955669 0.10076283 -0.28576031, -0.021782726 0.10126875 -0.28599316, -0.021943063 0.10126896 -0.28593841, -0.022088796 0.10128002 -0.28585294, -0.020573884 0.095823258 -0.28565344, -0.022213489 0.10130133 -0.28574041, -0.021296561 0.097609982 -0.28541377, -0.0206891 0.095748067 -0.28554627, -0.021806389 0.099852309 -0.28557715, -0.021795124 0.099444628 -0.28547427, -0.021917999 0.09943442 -0.28535742, -0.021416306 0.097567111 -0.28529903, -0.021565616 0.09947592 -0.28559783, -0.021674097 0.099459559 -0.28555143, -0.019285351 0.094370127 -0.28625384, -0.019391716 0.094298676 -0.28624776, -0.011518508 0.088667855 -0.29056892, -0.01265046 0.089515284 -0.28992113, -0.012572676 0.089633688 -0.28984457, -0.012721837 0.089380577 -0.28997073, -0.019490838 0.094224557 -0.28622308, -0.010767072 0.088920027 -0.29075661, -0.019600332 0.094132721 -0.28616849, -0.019708961 0.094025895 -0.28607312, -0.018077612 0.092910603 -0.28694364, -0.018179029 0.09282361 -0.28695384, -0.018273383 0.092731848 -0.2869437, -0.018376589 0.092615977 -0.28690496, -0.018476754 0.092479393 -0.28682426, -0.016557485 0.091605291 -0.28781983, -0.016652763 0.09150517 -0.28784987, -0.016741037 0.091396973 -0.28785774, -0.016836137 0.091258124 -0.28783759, -0.016925931 0.091092646 -0.28777382, -0.014727294 0.090509176 -0.28881025, -0.014814883 0.090398267 -0.28886285, -0.014895648 0.090275586 -0.28889081, -0.020958394 0.097723395 -0.28555802, -0.021071881 0.097686097 -0.28553155, -0.021178275 0.097650424 -0.2854881, -0.02024582 0.09599933 -0.28577453, -0.0058420599 0.086890504 -0.29084992, 0.0028431118 0.08679378 -0.29044643, 0.0012720525 0.086801663 -0.29028818, 0.0028288364 0.086946011 -0.29035306, -0.0057917535 0.087061301 -0.29086897, -0.0026315153 0.086935714 -0.29037356, -0.0034039319 0.087047115 -0.29043284, -0.0033939183 0.087174773 -0.29030785, 0.0036192238 0.086908549 -0.29050019, 0.0036013722 0.087060362 -0.2904065, -0.0026238859 0.087063789 -0.29024854, -0.0010717213 0.086925685 -0.29017225, 0.0013068914 0.086123466 -0.29043302, 0.00010046363 0.086088479 -0.2904211, 0.00010025501 0.086266249 -0.29044387, 0.001296252 0.086301059 -0.29045561, 0.0028615296 0.08662492 -0.29050368, 0.0012866557 0.086479023 -0.29043806, 0.0012785196 0.086648747 -0.29038146, -0.0034430027 0.086727276 -0.29058436, -0.0057094991 0.087398216 -0.29078892, -0.0034205914 0.086895362 -0.29052678, -0.0057468116 0.087233365 -0.29084834, -0.0026443601 0.086783409 -0.29046723, 0.0054871142 0.087593958 -0.29047525, 0.0035899282 0.087187842 -0.29028133, 0.0080465972 0.088445216 -0.29088894, -0.0010746121 0.086797208 -0.29029694, 0.0036426783 0.086740673 -0.29055783, 0.0028832853 0.086448118 -0.29052165, -0.003470093 0.086551145 -0.29060301, -0.002661705 0.086614594 -0.29052451, 0.0055044293 0.087467402 -0.29060122, 0.0080716908 0.088321224 -0.29101583, 9.8049641e-05 0.086896151 -0.29015189, 0.0036705732 0.086564675 -0.29057625, -0.0010798275 0.086644366 -0.2903901, 0.0029073656 0.086272031 -0.29049966, -0.0035003722 0.086375847 -0.29058173, 0.0055317283 0.087317854 -0.29069579, 0.0081116259 0.088175967 -0.29111263, -0.0026827753 0.086437643 -0.29054263, 9.8735094e-05 0.086767629 -0.29027668, 0.0037015378 0.086389497 -0.29055467, 0.0012677908 0.086930081 -0.29016358, 0.0055676401 0.087152496 -0.2907545, 0.008164376 0.088016197 -0.29117411, -0.0010868311 0.086474642 -0.29044697, 0.0056105554 0.086979583 -0.2907747, 0.0082273483 0.08784993 -0.2911973, -0.0027064085 0.086261287 -0.2905207, 0.0056580007 0.0868081 -0.29075474, 9.9331141e-05 0.086614564 -0.29036972, 0.008297354 0.087685853 -0.29118118, -0.0010958016 0.086296558 -0.29046443, 9.9718571e-05 0.086444557 -0.29042646, -0.005664736 0.087673798 -0.2905679, -0.001105696 0.086119086 -0.29044202, 0.0028198659 0.087073967 -0.29022798, -0.0056816339 0.087547481 -0.29069379, -0.024834126 0.11126295 -0.28309652, -0.024682581 0.11138962 -0.2831637, -0.024468929 0.11150087 -0.28319722, -0.025271207 0.11182591 -0.28189328, -0.025490016 0.11250494 -0.28074154, -0.025210649 0.1119685 -0.28197742, -0.025431484 0.11265999 -0.28080994, -0.025115877 0.11210003 -0.28204623, -0.0253371 0.11280139 -0.28086609, -0.025211602 0.11292242 -0.28090724, -0.024961531 0.11223674 -0.28210485, -0.025061369 0.11301692 -0.28093132, -0.024741501 0.11235096 -0.28213289, -0.024893641 0.11308005 -0.28093722, -0.022883892 0.10566048 -0.28620714, -0.022606641 0.10485628 -0.28633475, -0.022737324 0.10481553 -0.28625163, -0.022435337 0.10490584 -0.28639552, -0.02310279 0.10601929 -0.28605801, -0.023272753 0.10667273 -0.28592339, -0.022956073 0.10681126 -0.28606477, -0.023137122 0.10673878 -0.28600782, -0.023370862 0.10688907 -0.2858344, -0.023439199 0.10748698 -0.28572753, -0.023668349 0.10779981 -0.28550383, -0.023959816 0.10839768 -0.28512767, -0.023865044 0.10847703 -0.28521922, -0.0235309 0.10865894 -0.28535089, -0.023723543 0.1085676 -0.28530124, -0.023946166 0.10861778 -0.28511408, -0.02399537 0.10915306 -0.28492817, -0.02242285 0.10302615 -0.28614357, -0.022330076 0.10303529 -0.28622511, -0.024207979 0.10936993 -0.28466704, -0.022203118 0.10305135 -0.28630343, -0.024382174 0.10996619 -0.28428218, -0.024223268 0.10960791 -0.28457549, -0.024235278 0.11007646 -0.28435835, -0.024031848 0.11018002 -0.2843999, -0.022038519 0.10307652 -0.28636345, -0.024490744 0.11017464 -0.28407824, -0.024509519 0.11064354 -0.28382877, -0.024720818 0.11083026 -0.2834945, -0.024715424 0.11102156 -0.28339323, 0.0083704293 0.087714806 -0.2911953, 0.0083033741 0.087880045 -0.29121199, 0.0082429945 0.088046849 -0.29118946, 0.008192271 0.088207468 -0.29112852, 0.0081539452 0.088353485 -0.29103234, 0.0081297755 0.088477463 -0.29090562, -0.025108546 0.11506192 -0.27697316, -0.025268018 0.11401232 -0.27894023, -0.025277466 0.11501198 -0.27694073, -0.024921775 0.11605138 -0.27499393, -0.02570039 0.11351746 -0.2787163, -0.025641173 0.11366996 -0.27878937, -0.025546014 0.11380778 -0.27885321, -0.025709987 0.11453427 -0.27668247, -0.025518805 0.11554737 -0.27465585, -0.025419593 0.1139238 -0.27890423, -0.025650859 0.11468439 -0.27676025, -0.025460064 0.11569527 -0.2747381, -0.025365591 0.11582544 -0.27481702, -0.02555564 0.11481835 -0.2768316, -0.025239855 0.11593154 -0.27488819, -0.025099128 0.11406898 -0.27895939, -0.02542913 0.11492938 -0.27689257, -0.025089413 0.11600818 -0.27494821, 0.010435522 0.088237807 -0.2909818, 0.010186464 0.088999614 -0.29079559, 0.0097437799 0.088086158 -0.29118052, 0.0097050071 0.088258997 -0.29121029, 0.010407776 0.088405356 -0.29101214, 0.0096587241 0.088432908 -0.29120013, 0.010366857 0.088572979 -0.29100761, 0.0096073151 0.088598177 -0.29115078, 0.010314614 0.088732645 -0.29096863, 0.0095532835 0.088746443 -0.29106495, 0.010253489 0.088876992 -0.29089668, 0.0094995499 0.08887057 -0.29094675, 0.0091534853 0.088436589 -0.29122302, 0.0089239478 0.088347331 -0.29123721, 0.008693248 0.088251978 -0.29123637, -0.02377376 0.11655845 -0.26809543, -0.023786217 0.11674586 -0.26849285, -0.023646891 0.11654814 -0.26785162, -0.023199558 0.11658284 -0.26740056, -0.02352035 0.11637934 -0.26736563, -0.023383379 0.11649114 -0.26737234, -0.022884279 0.11579049 -0.26575071, -0.023016065 0.11569293 -0.26576218, -0.022709936 0.11587386 -0.26575992, -0.023473412 0.11627521 -0.26713672, -0.022584915 0.11473981 -0.2643196, -0.023223281 0.11618872 -0.26666597, -0.022457153 0.11482054 -0.26429099, -0.022290379 0.11489101 -0.26428169, -0.023218393 0.11595011 -0.26633099, -0.022516221 0.11375634 -0.26349831, -0.022322118 0.11283517 -0.26266947, -0.022435635 0.11383097 -0.26343992, -0.022198349 0.11291289 -0.262584, -0.022343665 0.11389653 -0.26339382, -0.022053272 0.11297515 -0.26252273, -0.022218168 0.11396334 -0.26335397, -0.022055566 0.11402188 -0.26333165, -0.021893352 0.11301944 -0.26248857, -0.025238246 0.11606109 -0.27451149, -0.025345325 0.11599259 -0.27425003, -0.025292903 0.11605974 -0.27428761, -0.025111943 0.1163267 -0.27393249, -0.024685353 0.11672723 -0.27317733, -0.025155246 0.11636485 -0.27338508, -0.025151163 0.11636902 -0.27298158, -0.025056601 0.11650398 -0.27303854, -0.024903178 0.1166342 -0.27310649, -0.025045753 0.11652033 -0.27284226, -0.024813205 0.11675897 -0.27234039, -0.024905294 0.11661142 -0.27189031, -0.024724245 0.11669682 -0.27115071, -0.024839699 0.11670984 -0.27192152, -0.024727046 0.11680599 -0.27169412, -0.024480879 0.11695915 -0.27123466, -0.024273068 0.11705481 -0.27129573, -0.024629503 0.11682975 -0.27118573, -0.024614096 0.11680982 -0.27101392, -0.024347931 0.11694096 -0.27045611, -0.024354279 0.11682397 -0.27005288, -0.024195105 0.11667025 -0.26925206, -0.0242275 0.11686893 -0.26979971, -0.023761719 0.11701351 -0.26934025, -0.024100602 0.11679465 -0.26926562, -0.02395758 0.11691776 -0.26929349, -0.024064958 0.11673874 -0.26905313, 0.01024276 0.089008704 -0.29077837, 0.010309279 0.088886082 -0.29087844, 0.010369509 0.088741779 -0.29094931, 0.01042062 0.088582635 -0.2909877, 0.010460347 0.088415727 -0.29099193, 0.010486871 0.08824873 -0.29096195, -0.021894664 0.11174475 -0.26151422, -0.021546662 0.11160871 -0.261228, -0.021662384 0.11157188 -0.26123047, -0.021770537 0.11152411 -0.26124543, -0.021890938 0.11145234 -0.26127979, -0.018432558 0.10855678 -0.25488004, -0.018329859 0.10865791 -0.25495049, -0.02201283 0.11135136 -0.2613413, -0.022054672 0.11246128 -0.26216865, -0.018532187 0.10840961 -0.25481746, -0.017034382 0.10835738 -0.25319085, -0.01931119 0.10905205 -0.25662813, -0.019417197 0.10900414 -0.25657293, -0.01951611 0.10893936 -0.25652707, -0.019624799 0.10884006 -0.25648406, -0.019732386 0.10869844 -0.25645325, -0.02027151 0.10960096 -0.2581996, -0.02038151 0.10955276 -0.25816521, -0.020484298 0.10948999 -0.25814107, -0.020597994 0.10939562 -0.25812548, -0.02071178 0.10926287 -0.25812662, -0.021031529 0.11046863 -0.25979123, -0.021144867 0.11042437 -0.25977662, -0.021250725 0.11036721 -0.25977355, -0.021368355 0.11028215 -0.25978467, -0.021487147 0.11016296 -0.25981793, -0.011146337 0.10937952 -0.24954459, -0.010243684 0.10957228 -0.24964526, -0.010310143 0.10957867 -0.24948716, -0.010370374 0.10954882 -0.24932918, -0.010421574 0.10948402 -0.24917871, -0.010461301 0.10938735 -0.24904263, -0.010487825 0.10926308 -0.24892718, -0.0114384 0.10937716 -0.24988642, -0.011471719 0.10935572 -0.24980909, -0.011973381 0.10921635 -0.24989399, -0.012938231 0.10887514 -0.25015196, -0.012657017 0.10915369 -0.25043049, -0.012875319 0.10902868 -0.25030816, -0.012729555 0.10915956 -0.25060287, -0.01280123 0.10911861 -0.25046495, -0.013489932 0.1089229 -0.25066143, -0.015061349 0.10876742 -0.25189808, -0.015147269 0.10867149 -0.25177047, -0.01369518 0.10897982 -0.25102457, -0.013747633 0.10893244 -0.25093117, -0.016761094 0.10866663 -0.25347573, -0.014279455 0.10875125 -0.25108919, -0.016849607 0.10860787 -0.25338429, -0.014811575 0.10881321 -0.25176045, -0.016944766 0.10850812 -0.25328529, -0.014867544 0.10876325 -0.25167617, -0.015224993 0.10851903 -0.25164506, -0.016687125 0.10863049 -0.25327539, -0.018235594 0.10872126 -0.25501874, 0.021893561 0.099806815 -0.2853938, 0.021545589 0.09949632 -0.28545675, 0.021661311 0.099476129 -0.28542572, 0.018431693 0.092586875 -0.28682479, 0.018328846 0.092703894 -0.2868633, 0.021769524 0.099459425 -0.28537852, 0.021889716 0.099443898 -0.28530058, 0.022011817 0.099432603 -0.28518274, 0.022053629 0.1007604 -0.2855742, 0.018531233 0.092448533 -0.28674456, 0.017033428 0.091115981 -0.28767872, 0.022321075 0.10138538 -0.28557265, 0.022197366 0.10136361 -0.28568628, 0.022052228 0.10135196 -0.28577283, 0.021892339 0.10135125 -0.28582871, 0.019310147 0.094282493 -0.28617188, 0.019416302 0.094209611 -0.28616658, 0.019515127 0.094134063 -0.2861425, 0.019623786 0.094040036 -0.28608873, 0.019731402 0.093930408 -0.28599396, 0.020270526 0.095869005 -0.28566787, 0.020380586 0.095812589 -0.2856501, 0.020483285 0.095755652 -0.28561434, 0.020596892 0.095686421 -0.28554824, 0.020710886 0.095607862 -0.28544116, 0.021030515 0.097662866 -0.28540689, 0.021143794 0.097624674 -0.28538007, 0.021249741 0.097587943 -0.28533646, 0.021367311 0.097545728 -0.28526166, 0.021486193 0.09750095 -0.28514639, 0.011145473 0.08881256 -0.29068473, 0.011437386 0.089084655 -0.29047754, 0.011470675 0.089009956 -0.29050687, 0.011972487 0.088994235 -0.29034445, 0.012937456 0.088995904 -0.28991666, 0.012656063 0.089385703 -0.28997257, 0.012728572 0.089527324 -0.28987351, 0.012800246 0.089392215 -0.28992364, 0.012874365 0.089212805 -0.28994569, 0.013488919 0.089432076 -0.28964898, 0.015060306 0.090327993 -0.28878263, 0.013694108 0.089756757 -0.2894766, 0.015146405 0.090168238 -0.28878251, 0.013746738 0.089653552 -0.28949502, 0.016760111 0.091529503 -0.28775516, 0.014278471 0.089671284 -0.28925505, 0.016848683 0.091421232 -0.28776297, 0.014810503 0.090245217 -0.28890181, 0.016943812 0.09128201 -0.28774264, 0.01486665 0.090147823 -0.2889125, 0.01522398 0.089976341 -0.28873584, 0.016686141 0.091347456 -0.28784654, 0.018234521 0.092796594 -0.2868731, -0.010187358 0.10958058 -0.24962762, -0.010254413 0.10958801 -0.24946883, -0.010315448 0.10955873 -0.2493102, -0.010367721 0.10949415 -0.24915907, -0.010408729 0.10939725 -0.24902219, -0.010436594 0.10927238 -0.24890649, 0.023772657 0.10796003 -0.28529507, 0.023785144 0.10839061 -0.28520641, 0.023645788 0.10775891 -0.28543326, 0.023198426 0.10741885 -0.2857317, 0.023519337 0.10726899 -0.2855899, 0.023382306 0.10734147 -0.28567502, 0.022883058 0.10562375 -0.28608778, 0.023015082 0.10557429 -0.2860029, 0.022708803 0.10568118 -0.286149, 0.023472339 0.1070233 -0.28564385, 0.022583902 0.10384832 -0.28610623, 0.023222297 0.10659468 -0.28585723, 0.022456139 0.10387386 -0.28618798, 0.022289485 0.10390875 -0.28624985, 0.02321735 0.10618372 -0.28586736, 0.022515178 0.1026013 -0.28581223, 0.022434682 0.10259934 -0.28590709, 0.022342652 0.10260162 -0.28598729, 0.022217155 0.10261001 -0.28606454, 0.022054553 0.10262723 -0.2861248, 0.025237083 0.11279429 -0.28104702, 0.025364459 0.11289707 -0.28067523, 0.025459081 0.11275584 -0.28061837, 0.025238693 0.11301763 -0.28071731, 0.025088251 0.11311154 -0.28074273, 0.024920613 0.1131742 -0.28074965, 0.025344133 0.11254388 -0.28114894, 0.025517613 0.11260132 -0.28054947, 0.025291711 0.1126141 -0.28118017, 0.025110841 0.11249042 -0.28160676, 0.02468425 0.11212657 -0.2823804, 0.025154054 0.11207536 -0.28196594, 0.024902225 0.11201409 -0.28234863, 0.02515009 0.11175501 -0.28221145, 0.025055587 0.11188163 -0.28228524, 0.02504462 0.11173436 -0.28241611, 0.024812043 0.1114763 -0.28290811, 0.024904341 0.11102761 -0.28306031, 0.024723172 0.11048733 -0.28357241, 0.024838656 0.11111172 -0.2831203, 0.024725914 0.11098741 -0.28333357, 0.02462846 0.1105952 -0.28365752, 0.024479806 0.11071175 -0.28373173, 0.024272084 0.11081806 -0.28377169, 0.024612993 0.11044559 -0.28374478, 0.024346858 0.11007816 -0.28418437, 0.024353206 0.10968532 -0.28433278, 0.024194032 0.10895242 -0.2846902, 0.024226278 0.10950971 -0.28452078, 0.023760736 0.1092291 -0.28491217, 0.02409938 0.10903798 -0.28478184, 0.023956507 0.1091342 -0.2848635, 0.024063826 0.10883436 -0.28486457, -0.0083714128 0.10912926 -0.24836004, -0.0081306994 0.10935543 -0.24914402, -0.0097446442 0.10934027 -0.24866596, -0.0097059608 0.1094678 -0.2487863, -0.0096597075 0.10956419 -0.24893144, -0.0096082091 0.10962395 -0.24909323, -0.0095542967 0.10964423 -0.24926355, -0.0095004141 0.10962418 -0.24943382, -0.0091543794 0.10958473 -0.24892071, -0.0089248419 0.10954247 -0.24884072, -0.0086941421 0.10948448 -0.24876499, -0.0081548691 0.10938224 -0.24896857, -0.0081932545 0.10937144 -0.24879405, -0.0082438886 0.10932389 -0.24862903, -0.0083041787 0.10924187 -0.24848208, 0.025107414 0.11416361 -0.27877045, 0.025266916 0.11510742 -0.27675036, 0.025276363 0.1141077 -0.27875009, 0.025699228 0.11463128 -0.2764889, 0.025488973 0.11564372 -0.27446383, 0.0256401 0.11478126 -0.27656722, 0.025430322 0.1157914 -0.27454665, 0.025544882 0.11491477 -0.27663919, 0.025335968 0.11592126 -0.27462611, 0.025708914 0.11361456 -0.27852294, 0.025418401 0.11502552 -0.27670127, 0.02521041 0.11602683 -0.27469823, 0.025649726 0.11376682 -0.27859628, 0.025060117 0.11610273 -0.27475935, 0.025554538 0.11390419 -0.2786608, 0.025098056 0.11515653 -0.27678421, 0.024892658 0.11614545 -0.27480641, 0.025427967 0.11401975 -0.27871287, -0.0082982183 0.10910074 -0.24834535, -0.008228302 0.10921219 -0.248467, -0.0081653297 0.10929328 -0.24861374, -0.0081125796 0.10933995 -0.24877858, -0.0080725849 0.10934988 -0.24895269, -0.0080474317 0.10932244 -0.24912816, 0.024833024 0.11678214 -0.27205724, 0.024681419 0.11691198 -0.27211806, 0.022212446 0.11291924 -0.26250175, 0.022087842 0.11299646 -0.26241708, 0.021942019 0.11305825 -0.26235715, 0.021781683 0.11310187 -0.26232415, 0.024467856 0.11700563 -0.27218685, 0.025269985 0.11615747 -0.27322942, 0.025209397 0.11631031 -0.27329293, 0.025114775 0.11644445 -0.27335677, 0.024960309 0.1165732 -0.27343115, 0.024740458 0.11666438 -0.27350554, 0.0228827 0.1159085 -0.26570895, 0.022605568 0.11552799 -0.26498893, 0.022736281 0.11543711 -0.26500627, 0.022434205 0.11560616 -0.26499215, 0.023101658 0.11600469 -0.2660853, 0.02327171 0.11628893 -0.26668885, 0.02313596 0.11639619 -0.26669082, 0.02295506 0.11648516 -0.26671472, 0.023369908 0.11634752 -0.26691535, 0.023437977 0.11662108 -0.26745749, 0.023667246 0.11662966 -0.26784226, 0.023958772 0.1166877 -0.26854625, 0.023863971 0.11680853 -0.26855475, 0.023529828 0.11702287 -0.26862106, 0.023722321 0.11692832 -0.26857778, 0.023945153 0.11680879 -0.26873037, 0.023994386 0.11698122 -0.26927009, 0.022421718 0.11427681 -0.26363963, 0.022329062 0.11434756 -0.263598, 0.024206758 0.11690255 -0.26960045, 0.022202015 0.1144198 -0.26356378, 0.02438122 0.11695249 -0.27030832, 0.024222225 0.11697218 -0.26984549, 0.024234235 0.11707954 -0.27035066, 0.024030805 0.11717503 -0.27040872, 0.022037566 0.11448291 -0.26354802, 0.024489611 0.11691435 -0.27059737, 0.024508506 0.11699636 -0.27112213, 0.024719715 0.11684108 -0.27147225, 0.024714321 0.11687471 -0.27168575, 0.0034196079 0.10810292 -0.24810565, 0.0056807995 0.10862805 -0.24852717, 0.003403008 0.10811883 -0.24828333, -0.0028440058 0.10797772 -0.2480728, -0.0012793243 0.10783868 -0.24799567, -0.001272887 0.1078558 -0.24817392, 0.002630651 0.1080046 -0.24822989, 0.003393054 0.10809535 -0.24846071, 0.0026230514 0.10798137 -0.24840736, -0.0028299093 0.1079943 -0.2482504, -0.0013076961 0.10756473 -0.24754462, -0.0001013875 0.10753436 -0.24752367, -0.00010117888 0.10765907 -0.24765226, 0.0034421086 0.10804819 -0.24793664, 0.0057086647 0.1086145 -0.24835077, -0.0012970567 0.10768926 -0.24767295, 0.0057459474 0.10856308 -0.24818319, -0.0036201477 0.1080896 -0.24813229, 0.0026434958 0.10798806 -0.248052, -0.0036022365 0.10810572 -0.24830985, -0.0028623641 0.10792218 -0.2479032, -0.0012876093 0.10778213 -0.24782583, 0.001070857 0.10783751 -0.24834263, -0.0054881573 0.10848089 -0.24869522, -0.0035907924 0.10808213 -0.24848691, 0.0034691691 0.1079575 -0.2477845, 0.0057908893 0.10847633 -0.24803293, -0.0036436617 0.10803489 -0.24796331, 0.0026608109 0.10793263 -0.2478826, 0.0010735989 0.10786031 -0.24816501, -0.0028841794 0.10783038 -0.24775106, 0.0080953538 0.1091316 -0.24828368, -0.005505383 0.10850568 -0.24851862, -9.894371e-05 0.10780358 -0.24833122, 0.0034995377 0.10783529 -0.24765715, 0.005841285 0.10835852 -0.24790779, -0.0036714971 0.10794392 -0.2478115, -0.0029082894 0.10770711 -0.24762335, 0.0026818514 0.10784097 -0.24773005, -0.0055325627 0.1084915 -0.24834228, 0.0010787547 0.10784301 -0.24798688, -9.9599361e-05 0.1078262 -0.24815363, -0.0037023723 0.10782161 -0.24768424, 0.0027053654 0.10771766 -0.24760211, -0.0055685639 0.10843934 -0.24817461, 0.001085937 0.10778663 -0.24781695, -0.0056113899 0.10835169 -0.24802443, -0.0012686253 0.10783309 -0.2483514, -0.0056588948 0.10823271 -0.24789912, -0.00010016561 0.10780877 -0.24797523, 0.0010947585 0.10769387 -0.24766389, -0.00010079145 0.10775211 -0.24780533, 0.0056638122 0.10860279 -0.24870375, 0.0078497529 0.10935254 -0.24906817, 0.0011048317 0.10756926 -0.24753562, 0.0078734756 0.10938005 -0.24889275, 0.00791201 0.10937017 -0.24871814, -0.0028208196 0.1079711 -0.2484279, 0.0079638064 0.10932364 -0.24855292, 0.0080259144 0.10924284 -0.24840575, 0.012857974 0.10890639 -0.25011608, 0.012794882 0.1090596 -0.25027129, 0.02045849 0.10965542 -0.25818506, 0.020355105 0.10971743 -0.25820729, 0.015057355 0.10857505 -0.25153747, 0.014980197 0.10872729 -0.25166327, 0.021954656 0.1126121 -0.26205909, 0.02057299 0.10956232 -0.25817186, 0.021295518 0.11044273 -0.25974485, 0.020688027 0.10943155 -0.25817618, 0.021805406 0.11191921 -0.26144055, 0.021673054 0.1116627 -0.26114199, 0.021794081 0.11159219 -0.26117638, 0.021564513 0.11170965 -0.26112714, 0.021415412 0.1103254 -0.2597796, 0.021917015 0.11149253 -0.26123825, 0.019284487 0.10917059 -0.2566494, 0.011517704 0.10920055 -0.24949834, 0.019390821 0.10912286 -0.25659576, 0.012571663 0.10920072 -0.25070551, 0.012649715 0.10919079 -0.25056511, 0.012720942 0.10914947 -0.25042751, 0.019490033 0.10905862 -0.25655136, 0.010766178 0.10950193 -0.24958733, 0.010288626 0.10930234 -0.24884889, 0.01026246 0.10942639 -0.24896455, 0.010223478 0.10952297 -0.24910107, 0.010173112 0.10958762 -0.2492519, 0.010114044 0.10961731 -0.24941036, 0.010048747 0.1096106 -0.249569, 0.019599408 0.10895991 -0.25651038, 0.019708008 0.10881954 -0.25648233, 0.018076628 0.10884647 -0.25506762, 0.018178046 0.10880259 -0.25499222, 0.018272489 0.10873935 -0.25492486, 0.018375576 0.10863884 -0.2548553, 0.018475801 0.10849221 -0.25479445, 0.016556531 0.10876413 -0.25349784, 0.016651779 0.1087281 -0.25339955, 0.016740024 0.10866943 -0.25330833, 0.016835213 0.10856996 -0.25320935, 0.016924948 0.10841969 -0.2531153, 0.0147264 0.10889849 -0.25202665, 0.0148139 0.10887414 -0.25190642, 0.014894664 0.1088229 -0.25179148, 0.020957381 0.11062622 -0.25974903, 0.021070927 0.11058269 -0.25973532, 0.021177262 0.11052658 -0.25973281, 0.020244807 0.10976493 -0.25824019, 0.0081685483 0.10916065 -0.24829778, 0.0081019998 0.10927281 -0.24842021, 0.0080422461 0.10935467 -0.24856785, 0.0079928339 0.10940208 -0.24873316, 0.0079556704 0.10941269 -0.24890789, 0.0079329312 0.10938585 -0.2490834, 0.0099922121 0.10961868 -0.24955171, 0.010058045 0.10962637 -0.24939251, 0.010118008 0.10959738 -0.24923322, 0.010169476 0.10953292 -0.24908167, 0.010209799 0.1094362 -0.24894479, 0.010237128 0.10931133 -0.24882877, 0.0088602006 0.10932958 -0.24842253, 0.0088078082 0.10945316 -0.24854487, 0.0087549686 0.10954472 -0.24869365, 0.0087048113 0.10959907 -0.24886027, 0.0086600482 0.10961306 -0.24903578, 0.0086227953 0.1095866 -0.24921179, 0.0092116892 0.1096196 -0.24885321, 0.0094408095 0.10963491 -0.24894091, 0.0096718967 0.1096357 -0.24903432, -0.020310074 0.11363328 -0.26361999, -0.020182669 0.11281852 -0.26291099, -0.020129025 0.11271733 -0.26305777, -0.023314089 0.11583337 -0.27461025, -0.023544401 0.11587489 -0.27500144, -0.023604065 0.11628398 -0.2743533, -0.020504922 0.11437124 -0.26437518, -0.020610094 0.11449309 -0.26423946, -0.023169249 0.11589637 -0.27410415, -0.020415395 0.11374725 -0.26347142, -0.020255119 0.11347941 -0.26380008, -0.020117968 0.1126083 -0.26320776, -0.020446062 0.11420557 -0.26453683, -0.023160189 0.11617747 -0.27374473, -0.023102134 0.11642973 -0.27320519, -0.023010224 0.11627172 -0.27318212, -0.020270973 0.11331834 -0.26397136, -0.020149708 0.11249703 -0.26335362, -0.022956312 0.11609931 -0.27314696, -0.02045548 0.11403011 -0.26468807, -0.023209631 0.11654904 -0.27321455, -0.021576941 0.11616167 -0.26813635, -0.02192539 0.11664294 -0.2685411, -0.021393418 0.11583027 -0.26766828, -0.023862332 0.116032 -0.27503273, -0.021592826 0.11634609 -0.26741892, -0.021486998 0.11621118 -0.26750156, -0.023694813 0.11596899 -0.27502611, -0.021922201 0.11664793 -0.2680496, -0.021412909 0.11602794 -0.26759139, -0.021416187 0.11613858 -0.26693049, -0.021845609 0.11649969 -0.26728132, -0.021709204 0.11643627 -0.26734844, -0.023211807 0.11674833 -0.27274165, -0.021554351 0.11608839 -0.26626024, -0.023442358 0.11670077 -0.27320561, -0.021350682 0.11605856 -0.26698557, -0.023318738 0.11663389 -0.27321419, -0.022981197 0.11673678 -0.27228746, -0.021153659 0.1157513 -0.26667604, -0.022573173 0.11657175 -0.27138409, -0.022527397 0.11638579 -0.27138364, -0.020878673 0.11506654 -0.26608911, -0.0211474 0.11574319 -0.26609343, -0.021318138 0.11571094 -0.26556897, -0.021175325 0.11565343 -0.26564845, -0.022990257 0.1169114 -0.27179694, -0.022878379 0.11696145 -0.2713291, -0.022767872 0.11687143 -0.27135256, -0.022660941 0.11674277 -0.27137247, -0.021055222 0.11556767 -0.26573724, -0.021081984 0.11566459 -0.26615676, -0.020883381 0.1152582 -0.26597452, -0.022845209 0.11702828 -0.27089927, -0.020949632 0.11543691 -0.26584813, -0.020848364 0.11524063 -0.26554659, -0.022764444 0.11697952 -0.27092046, -0.021049649 0.11528729 -0.26498473, -0.020677 0.11485477 -0.26524165, -0.022493929 0.11687391 -0.27043164, -0.02198723 0.1163059 -0.2695227, -0.020622432 0.11471571 -0.26480624, -0.021067739 0.11510332 -0.26462758, -0.022569448 0.11700995 -0.26989692, -0.022322595 0.11690755 -0.26933768, -0.02067399 0.11471897 -0.26454297, -0.020883381 0.11462413 -0.26404861, -0.020734161 0.11457217 -0.26413557, -0.022487462 0.1169613 -0.26992491, -0.022103161 0.11668135 -0.26943591, -0.022021413 0.1165013 -0.26948562, -0.022209555 0.11681557 -0.26938507, -0.023450196 0.11649521 -0.27372691, -0.022313297 0.11690977 -0.26901811, -0.022230119 0.11686191 -0.26905206, -0.022007167 0.11669464 -0.26800928, -0.020864964 0.11389329 -0.26320735, -0.020732105 0.1130473 -0.26250771, -0.020693719 0.11387148 -0.26327118, -0.020558 0.11302401 -0.26256868, -0.02054131 0.11382194 -0.26336077, -0.020402968 0.11297612 -0.26265982, -0.020275563 0.1129064 -0.26277593, -0.023418754 0.11575402 -0.27495965, -0.023324341 0.11561285 -0.27490324, -0.02326563 0.11545809 -0.2748346, -0.020257354 0.11164509 -0.26136777, -0.020188332 0.11105116 -0.26060006, -0.020019889 0.11103067 -0.2606748, -0.019870043 0.1109771 -0.26076981, -0.020105273 0.1115938 -0.26146105, -0.019926161 0.1108879 -0.2621865, -0.019844115 0.11105362 -0.26205221, -0.019746602 0.11089329 -0.26087961, -0.019980043 0.1115147 -0.26157284, -0.019645065 0.11076345 -0.2610186, -0.019876957 0.11139309 -0.26171896, -0.01959309 0.1105864 -0.26117787, -0.019824922 0.11122815 -0.26189119, -0.019611269 0.1103981 -0.26132181, -0.019041806 0.109401 -0.25990129, -0.018268615 0.10865596 -0.25839838, -0.01724574 0.10815078 -0.25682461, -0.015941143 0.10789146 -0.25523821, -0.014317751 0.10786438 -0.2536954, -0.012410432 0.10802995 -0.2523019, -0.020416915 0.11245902 -0.26216301, -0.020241886 0.11178204 -0.26155734, -0.019460589 0.11027521 -0.2608442, -0.019345671 0.11015522 -0.26040807, -0.019175887 0.10978635 -0.26014623, -0.019078225 0.10980338 -0.25965592, -0.019026756 0.10960889 -0.25978991, -0.018816292 0.10933089 -0.25937316, -0.018661439 0.10929352 -0.25895402, -0.018427461 0.10896964 -0.25863424, -0.018310279 0.10908185 -0.25821182, -0.01825878 0.10887545 -0.25832033, -0.017948061 0.10864912 -0.25782651, -0.017432809 0.10840921 -0.25705513, -0.017294466 0.10858649 -0.25669417, -0.017242879 0.10837488 -0.25677773, -0.016836852 0.10830556 -0.25622723, -0.016826838 0.10822396 -0.25624844, -0.016598105 0.10841317 -0.25582102, -0.016177922 0.10818598 -0.25545263, -0.016077161 0.10848536 -0.25507125, -0.015997171 0.10832419 -0.25515631, -0.01594612 0.10811293 -0.25521827, -0.016167372 0.10810488 -0.25546977, -0.015415072 0.10804236 -0.25468299, -0.015426427 0.10812266 -0.25467014, -0.015116781 0.10827877 -0.25428855, -0.014609963 0.1081156 -0.25392005, -0.014449865 0.10844553 -0.25357828, -0.014379323 0.10828441 -0.25365141, -0.014330119 0.10807836 -0.25369549, -0.01459828 0.10803664 -0.25392964, -0.013693392 0.10815977 -0.25318059, -0.013323516 0.10835296 -0.25284693, -0.012756407 0.10887949 -0.25192702, -0.01267308 0.10880663 -0.25204387, -0.012598008 0.10870901 -0.25214252, -0.012730986 0.10824537 -0.25250244, -0.012533218 0.10859048 -0.25222096, -0.012473255 0.10843205 -0.2522836, -0.012428075 0.10823362 -0.25231513, -0.012047946 0.10840145 -0.2520541, -0.012031555 0.1083242 -0.25206393, -0.011498719 0.1086897 -0.25163817, -0.010900825 0.10850579 -0.25143287, -0.010122836 0.10833739 -0.25105637, -0.010142267 0.10853007 -0.25107664, -0.01092416 0.10860623 -0.25141594, -0.010715514 0.10876463 -0.25125316, -0.01018104 0.10871956 -0.25105393, -0.01023677 0.1088946 -0.25098929, -0.010306418 0.10904466 -0.25088665, -0.010385722 0.10916112 -0.25075239, -0.020168602 0.11256425 -0.26265088, -0.020125896 0.11250864 -0.26272967, -0.020015568 0.11201625 -0.26253393, -0.019994289 0.11181094 -0.26210865, -0.019916773 0.11085042 -0.26046243, -0.019699961 0.11069076 -0.26046863, -0.019782931 0.11073411 -0.26040563, -0.019793928 0.1105382 -0.25998202, -0.019494206 0.11026588 -0.25973123, -0.019600362 0.11011899 -0.25923896, -0.019439071 0.11009656 -0.25932527, -0.019295305 0.11003791 -0.25942391, -0.019412905 0.11022034 -0.25979421, -0.019176573 0.10994588 -0.25953016, -0.019297034 0.10994987 -0.25908551, -0.019068003 0.10980044 -0.25908139, -0.019147277 0.10984807 -0.25901842, -0.019103169 0.10972019 -0.25857416, -0.01875475 0.10949887 -0.25830397, -0.018801868 0.10942622 -0.25779653, -0.018650651 0.10939854 -0.2578944, -0.018515825 0.10933326 -0.25799727, -0.018678159 0.10944921 -0.25836679, -0.018404126 0.10923372 -0.25809959, -0.01827535 0.1091629 -0.25782862, -0.018221289 0.10909647 -0.25788456, -0.018110007 0.10910495 -0.25730696, -0.017772257 0.10890827 -0.25707462, -0.017745167 0.10896109 -0.2562837, -0.01760754 0.10892461 -0.25639197, -0.017451137 0.10873643 -0.25675547, -0.017484576 0.1088511 -0.25649765, -0.017382085 0.10874476 -0.25659564, -0.01721105 0.10880664 -0.25599962, -0.016543746 0.1086863 -0.25523981, -0.016397834 0.10872783 -0.2547569, -0.016276687 0.10867965 -0.25487271, -0.016168267 0.10859747 -0.25497881, -0.015855789 0.10852143 -0.25476149, -0.015791208 0.10862136 -0.25447968, -0.014963269 0.10861026 -0.2537407, -0.014528155 0.10856159 -0.25349289, -0.014722437 0.10871346 -0.25327089, -0.014619976 0.10865252 -0.25338927, -0.014163852 0.10851918 -0.25328577, -0.014053971 0.108648 -0.25302684, -0.020302743 0.11198591 -0.26174998, -0.017613798 0.10850185 -0.25730774, -0.023450643 0.11450733 -0.27673641, -0.023441523 0.11355296 -0.27864546, -0.023500651 0.11370289 -0.27872363, -0.023509741 0.1146597 -0.27680987, -0.023238838 0.1126027 -0.28054595, -0.024042755 0.11407791 -0.27894136, -0.023834705 0.11310342 -0.28089055, -0.023873955 0.11402871 -0.27890727, -0.023667395 0.11306117 -0.28084281, -0.023722559 0.11394687 -0.27885798, -0.023517162 0.11298542 -0.280781, -0.024052113 0.11505684 -0.27698341, -0.023595959 0.11383638 -0.27879584, -0.023391783 0.11288007 -0.28070858, -0.023883134 0.11500086 -0.276963, -0.023297369 0.1127504 -0.28062877, -0.023731589 0.11491273 -0.27692598, -0.023604989 0.11479707 -0.2768741, -0.010309696 0.1091675 -0.25072518, -0.010232031 0.10905032 -0.25085789, -0.010164291 0.10890003 -0.25095913, -0.010110408 0.10872568 -0.25102279, -0.010073543 0.10853721 -0.25104529, -0.01005581 0.10834572 -0.2510252, -0.02175495 0.10736683 -0.28581274, -0.02162987 0.10723117 -0.2858012, -0.021765411 0.10721514 -0.28589323, -0.023563027 0.11254582 -0.28180864, -0.023698628 0.11256517 -0.28185084, -0.021836191 0.10797511 -0.2854999, -0.022446722 0.11033513 -0.28340921, -0.022874326 0.11152521 -0.28221074, -0.023440391 0.112507 -0.28175661, -0.022146463 0.10832772 -0.28547445, -0.022535354 0.10910106 -0.28512463, -0.023234159 0.11189158 -0.282612, -0.0223912 0.1091169 -0.28506085, -0.023331851 0.1124509 -0.28169665, -0.022071451 0.1083343 -0.28543082, -0.023125201 0.11184275 -0.2825411, -0.020051181 0.10173845 -0.28548038, -0.020075947 0.10149275 -0.285566, -0.0201675 0.10143699 -0.28571799, -0.020023972 0.10154957 -0.28539667, -0.023224413 0.11236513 -0.28161761, -0.020014405 0.10160409 -0.28521919, -0.020047665 0.10165384 -0.28504315, -0.023018211 0.11176583 -0.2824477, -0.020270795 0.10181785 -0.2858949, -0.020125866 0.10197435 -0.28568122, -0.020395547 0.10198723 -0.28602877, -0.020355105 0.10246025 -0.28602836, -0.02313143 0.11224441 -0.28151897, -0.022927105 0.11165473 -0.2823312, -0.020089507 0.10205087 -0.2855576, -0.023075253 0.11210547 -0.28141674, -0.020074785 0.10207906 -0.28545052, -0.020543575 0.10194685 -0.28611192, -0.020621568 0.10130523 -0.28599516, -0.02044788 0.10134073 -0.2859385, -0.020145983 0.10255767 -0.28538725, -0.020222753 0.10300189 -0.28563282, -0.020608246 0.10293463 -0.28624204, -0.020464063 0.10334903 -0.28609362, -0.020293832 0.10138544 -0.28584448, -0.020360321 0.10338804 -0.28591359, -0.020304292 0.10342227 -0.28568301, -0.02031672 0.10344259 -0.28545147, -0.022261411 0.10911575 -0.28497601, -0.020418614 0.10379866 -0.2858704, -0.0207268 0.10354847 -0.28630272, -0.022149175 0.10909835 -0.28487346, -0.020723373 0.10414012 -0.28622845, -0.020390898 0.10381211 -0.28574249, -0.020468652 0.10196605 -0.28607529, -0.020497233 0.10430403 -0.28559086, -0.020645291 0.10473917 -0.28588077, -0.0209454 0.1045199 -0.28632084, -0.021040946 0.10524079 -0.28621361, -0.020921439 0.10526216 -0.2860904, -0.02081728 0.10527451 -0.28591773, -0.020753294 0.1052714 -0.28569725, -0.020614982 0.10474207 -0.28575572, -0.020587444 0.10331134 -0.28622034, -0.02292046 0.11064897 -0.28398457, -0.020751268 0.10525055 -0.28547424, -0.020736516 0.10327156 -0.28631523, -0.02086696 0.10565872 -0.28568053, -0.02117449 0.10541064 -0.28625381, -0.021226764 0.10604486 -0.28606573, -0.022794425 0.11063176 -0.28391007, -0.022684395 0.11059761 -0.28382212, -0.021254569 0.10657939 -0.28579596, -0.021462381 0.10641956 -0.28607839, -0.02257812 0.11053762 -0.28370538, -0.022043705 0.10905837 -0.28473529, -0.021003425 0.10615037 -0.2854389, -0.021028131 0.10450009 -0.28636569, -0.022491306 0.11044578 -0.28355944, -0.021962911 0.1089898 -0.28456131, -0.021158546 0.10661808 -0.28550425, -0.021318555 0.10712318 -0.2851229, -0.021183282 0.10521045 -0.28630868, -0.021929413 0.10890187 -0.28438324, -0.021285087 0.10683106 -0.28564242, -0.021514416 0.10723339 -0.28568605, -0.02140978 0.10721885 -0.2855278, -0.021336764 0.10718057 -0.28532729, -0.02335766 0.11192311 -0.28267297, -0.021462739 0.10754639 -0.28523287, -0.021605432 0.10799603 -0.2848998, -0.021778315 0.10846022 -0.28485826, -0.021541148 0.10640503 -0.28612354, -0.021911949 0.10868369 -0.28493813, -0.0080955923 0.10886499 -0.25009879, -0.0082914233 0.10810858 -0.25039044, -0.0095703602 0.10918033 -0.25048712, -0.0095236897 0.10905586 -0.25061294, -0.0094880164 0.10890378 -0.25070918, -0.009465158 0.10873295 -0.25077024, -0.0094564855 0.10855262 -0.25079334, -0.0094619989 0.1083705 -0.25077733, -0.0090374351 0.10879877 -0.25059202, -0.0088143647 0.10872747 -0.25053558, -0.0085955262 0.10864349 -0.25048128, -0.0082280636 0.10827146 -0.250402, -0.0081745386 0.10843618 -0.25037649, -0.0081334114 0.108595 -0.25031534, -0.0081065893 0.10874026 -0.25022128, -0.012451202 0.090400159 -0.28884217, -0.014267683 0.091365829 -0.28781888, -0.015895456 0.092524484 -0.28698376, -0.018253684 0.095259905 -0.28577325, -0.019665748 0.098382592 -0.28536656, -0.019544274 0.098419264 -0.28523183, -0.019414097 0.098460466 -0.28456882, -0.020376831 0.099794656 -0.28565264, -0.020205766 0.099837005 -0.28559387, -0.020053804 0.099881217 -0.28549662, -0.01992926 0.099925309 -0.28536597, -0.019827515 0.099972665 -0.28518111, -0.019444615 0.098449692 -0.28504327, -0.019777238 0.10001728 -0.28494641, -0.019394547 0.098465338 -0.28480545, -0.019798547 0.10004793 -0.28471109, -0.010514706 0.089754939 -0.28920582, -0.010055453 0.089638904 -0.28950596, -0.0101237 0.089646772 -0.28968814, -0.010000676 0.089585617 -0.28932694, -0.0099629462 0.089490399 -0.28916129, -0.0099440515 0.089358568 -0.28901929, -0.010840952 0.089866683 -0.2893348, -0.010201544 0.089608818 -0.28986248, -0.010802865 0.089859948 -0.28923783, -0.011255145 0.089980766 -0.28883639, -0.012194693 0.090140894 -0.28806493, -0.011974484 0.090260535 -0.288872, -0.01237765 0.090420485 -0.28870437, -0.01193136 0.090255871 -0.28877386, -0.012015015 0.090282142 -0.28858504, -0.012255549 0.090367481 -0.28839758, -0.012211531 0.090273589 -0.28821984, -0.01231426 0.090412259 -0.28856233, -0.012723505 0.090539575 -0.28865466, -0.012675613 0.090549409 -0.28856468, -0.013139933 0.090790272 -0.28815147, -0.014062494 0.091108605 -0.2871404, -0.013628006 0.091008633 -0.28812295, -0.01419121 0.091364473 -0.28767428, -0.014074504 0.091237515 -0.28731042, -0.014122337 0.091326132 -0.28750148, -0.014638573 0.091546774 -0.28774431, -0.01458025 0.091561839 -0.28765514, -0.014940411 0.091862723 -0.28725687, -0.015673965 0.092305243 -0.28626487, -0.01540193 0.092133507 -0.28723413, -0.015806347 0.092530787 -0.28683802, -0.015728325 0.09250167 -0.28665778, -0.015678674 0.092423439 -0.28645256, -0.016252786 0.092762023 -0.28690958, -0.016184419 0.092781782 -0.286823, -0.016433895 0.09312506 -0.28646576, -0.016920716 0.093411461 -0.28655681, -0.017215252 0.0938375 -0.28628758, -0.016847789 0.093433022 -0.28647217, -0.017114908 0.093851522 -0.28614295, -0.017029256 0.093834102 -0.28595713, -0.017556101 0.094141945 -0.28622606, -0.018080682 0.094852552 -0.28596485, -0.018583596 0.095657334 -0.28573537, -0.018144101 0.095281392 -0.28563091, -0.018664122 0.096050188 -0.28554374, -0.018986642 0.096420422 -0.2855787, -0.019061536 0.09678252 -0.28545812, -0.018945009 0.096811473 -0.28531921, -0.019367039 0.097278416 -0.28547034, -0.019381106 0.097671419 -0.28534088, -0.019664198 0.098084614 -0.28543186, -0.01599893 0.092697859 -0.28622895, -0.016650856 0.093372017 -0.28586832, -0.016982406 0.093672529 -0.28553298, -0.016979218 0.093772084 -0.28573835, -0.017164111 0.093998984 -0.28589046, -0.01745528 0.094301 -0.28592417, -0.017433435 0.094349831 -0.28575024, -0.01801303 0.09516409 -0.28499162, -0.017933041 0.095082253 -0.28550208, -0.018052518 0.095278114 -0.28544146, -0.01800248 0.095237687 -0.28521234, -0.018152505 0.095486373 -0.28507945, -0.01823166 0.095640987 -0.28513277, -0.018431872 0.095984772 -0.2848781, -0.018628359 0.096426457 -0.28497431, -0.018848836 0.096824303 -0.28512904, -0.018682808 0.096540928 -0.28486535, -0.018798858 0.096810341 -0.28489313, -0.018814892 0.096768737 -0.28466156, -0.019007653 0.097265944 -0.28500441, -0.018920481 0.097100928 -0.2847943, -0.018983901 0.097260758 -0.28486982, -0.019134104 0.097644627 -0.28466693, -0.019280076 0.098091006 -0.28482881, -0.019316524 0.098214865 -0.28473753, -0.007632345 0.10868986 -0.24999052, -0.0076548755 0.10856567 -0.25011742, -0.0076915622 0.10841922 -0.25021401, -0.0077404678 0.10825823 -0.25027546, -0.0077993572 0.10809055 -0.2502985, -0.0078651309 0.10792486 -0.25028202, -0.010125369 0.089591146 -0.28988332, -0.010049254 0.08962734 -0.28970939, -0.0099827945 0.089618385 -0.28952792, -0.0099299848 0.08956477 -0.28934982, -0.0098938942 0.089469716 -0.28918523, -0.0098767877 0.089338854 -0.28904408, -9.188056e-05 0.10652374 -0.24954495, 0.0025623441 0.10668787 -0.2496146, 0.0024880171 0.10736243 -0.24946842, 0.0050235093 0.10782905 -0.24968958, 0.0050493777 0.1076791 -0.24978399, 0.0025013685 0.10721014 -0.24956173, -9.2178583e-05 0.10670146 -0.24956763, 0.0025394857 0.10686423 -0.24963656, 0.0076815188 0.1079541 -0.25022361, 0.002479434 0.10749048 -0.24934328, 0.005007118 0.10795566 -0.24956402, -9.2506409e-05 0.10687982 -0.24955025, 0.0025188327 0.10704125 -0.24961871, -9.3072653e-05 0.10704967 -0.24949363, -0.0027461648 0.10667796 -0.24963459, 0.0074435472 0.10871838 -0.24993369, -9.3758106e-05 0.10720277 -0.24940056, -0.0027237236 0.10685432 -0.24965644, -9.4532967e-05 0.10733135 -0.24927571, -0.0027038157 0.10703143 -0.24963829, -0.0026874542 0.10720041 -0.24958137, -0.0053527653 0.10714774 -0.24988174, -0.0026754439 0.1073527 -0.24948782, -0.0053083301 0.10732023 -0.2499015, -0.0026682317 0.10748081 -0.24936262, -0.0052686036 0.10749368 -0.24988154, 0.0051690638 0.1071676 -0.2498422, 0.0051239431 0.10733978 -0.24986225, 0.007615 0.10811971 -0.25024045, -0.0052355528 0.10765965 -0.24982277, 0.0050833523 0.10751335 -0.24984261, 0.0075552166 0.1082872 -0.25021783, 0.0075052083 0.10844791 -0.25015691, -0.0052109063 0.10780974 -0.24972814, -0.0051959455 0.10793644 -0.24960238, 0.0074673891 0.10859421 -0.25006053, -0.0079076886 0.088916913 -0.29000071, -0.0081085265 0.08869566 -0.28922191, -0.0086450577 0.08919619 -0.29007104, -0.0086294115 0.089217752 -0.28989622, -0.0079202652 0.08893998 -0.28982732, -0.00862661 0.089202583 -0.28972015, -0.0079482198 0.088928163 -0.289655, -0.0086366236 0.089151472 -0.28955185, -0.0079903901 0.088881522 -0.28949156, -0.0086587071 0.089067385 -0.28939965, -0.0080447793 0.088802859 -0.28934488, -0.0086922646 0.088953167 -0.28926894, -0.0089841187 0.089332238 -0.28990301, -0.0090717375 0.089323208 -0.28958598, -0.0092939138 0.089401707 -0.28958687, -0.009524256 0.089477673 -0.28957656, 0.0079067349 0.1088952 -0.25003859, 0.0079193115 0.10877056 -0.2501609, 0.0079472661 0.10862537 -0.2502549, 0.0079895258 0.10846673 -0.25031587, 0.0080437958 0.10830218 -0.25034082, 0.0081076622 0.10813951 -0.25032881, -0.0074444711 0.088727027 -0.28992203, -0.0074683428 0.088753849 -0.28974655, -0.0075061917 0.088743314 -0.28957173, -0.0075562596 0.088695526 -0.28940654, -0.0076159239 0.088613003 -0.28925917, -0.0076823831 0.088500217 -0.28913686, 0.010124594 0.10920621 -0.25064823, 0.009875834 0.10838318 -0.25095007, 0.008644104 0.1091191 -0.25021958, 0.0086284578 0.10899234 -0.25034174, 0.0086256862 0.1088421 -0.25043538, 0.0086356997 0.10867701 -0.25049528, 0.0086576939 0.10850476 -0.25051951, 0.0086912513 0.10833167 -0.25050652, 0.0089831948 0.10906634 -0.25042936, 0.0090708435 0.10880731 -0.25061238, 0.00929299 0.10885505 -0.25067469, 0.0095233619 0.10889246 -0.25074151, 0.0098930597 0.10857479 -0.25097004, 0.0099291205 0.10876341 -0.25094739, 0.0099819303 0.1089382 -0.25088334, 0.010048181 0.10908866 -0.25078169, 9.0897083e-05 0.087099046 -0.2883997, -0.0025631785 0.087253258 -0.28848931, -0.0024889112 0.087541059 -0.28911683, -0.0050243735 0.087998062 -0.28935719, -0.0050502717 0.087983623 -0.28918049, -0.0025021434 0.08752434 -0.28893888, 9.1254711e-05 0.087223887 -0.28852841, -0.0025402308 0.087376744 -0.28861716, -0.0024802387 0.087517902 -0.28929433, -0.0050081015 0.087973505 -0.28953388, 9.1701746e-05 0.087316915 -0.28868142, -0.0025197268 0.087468624 -0.28876951, 9.2208385e-05 0.08737357 -0.28885129, 0.0027451813 0.087263405 -0.28846923, 9.2893839e-05 0.087390989 -0.28902966, 0.0027228296 0.087386712 -0.28859738, 9.354949e-05 0.087368369 -0.28920731, 0.0027030706 0.087478384 -0.2887499, 0.0026865304 0.087534115 -0.28891945, 0.0053518713 0.087742835 -0.28869694, 0.007864207 0.088529617 -0.28907838, 0.0026745498 0.087550744 -0.28909737, 0.0053073168 0.087862343 -0.28882301, 0.0077984035 0.08864218 -0.28920117, 0.0026672781 0.087527573 -0.28927466, 0.0076314807 0.088755488 -0.2898654, -0.0051698387 0.087723061 -0.28873664, 0.0052676201 0.087950334 -0.28897381, 0.0077394843 0.088724256 -0.28934899, 0.0052346885 0.08800298 -0.28914183, -0.005124867 0.087842584 -0.28886208, 0.0076904595 0.08877182 -0.28951475, -0.0050842762 0.087930933 -0.28901276, 0.0052101016 0.088017344 -0.28931856, 0.0076540112 0.088782415 -0.28968978, 0.0051950812 0.087992683 -0.28949556, 0.01020056 0.10919991 -0.25067478, 0.010122776 0.10908322 -0.25080988, 0.010054588 0.10893272 -0.25091287, 0.0099997818 0.1087576 -0.2509779, 0.0099619925 0.10856797 -0.25100097, 0.0099432468 0.10837521 -0.25098076, 0.0080945492 0.088947251 -0.28994027, 0.008105725 0.088970244 -0.28976706, 0.0081324577 0.088958412 -0.28959444, 0.0081737041 0.08891207 -0.28943065, 0.0082270503 0.0888336 -0.28928357, 0.0082904696 0.088726655 -0.28916028, 0.020046651 0.11257294 -0.26320222, 0.012450427 0.10885876 -0.25192025, 0.0142667 0.10861972 -0.2533069, 0.015894502 0.10864684 -0.25473487, 0.018252581 0.10932001 -0.25764945, 0.019664794 0.11086874 -0.26039147, 0.01954329 0.11078292 -0.26050153, 0.019413203 0.1102774 -0.26093224, 0.020375848 0.11194488 -0.26134923, 0.020620584 0.11312531 -0.26235208, 0.020204872 0.11192326 -0.26141837, 0.020446956 0.11310138 -0.26241425, 0.02005291 0.11187212 -0.26151219, 0.020292848 0.11305295 -0.26250663, 0.020166576 0.11298285 -0.26262367, 0.019928277 0.11179401 -0.26162568, 0.020074874 0.11289465 -0.2627596, 0.019826531 0.11167465 -0.26177445, 0.020022899 0.11279319 -0.26290646, 0.019443631 0.11065029 -0.26063889, 0.019776165 0.11151363 -0.26195124, 0.020013213 0.1126841 -0.26305681, 0.019393593 0.11046952 -0.26079413, 0.019797593 0.11134373 -0.26211694, 0.010513693 0.10876234 -0.25118592, 0.010840029 0.10893248 -0.25119787, 0.010801852 0.10885102 -0.25125065, 0.011254162 0.10860236 -0.25158831, 0.01219371 0.1080813 -0.25217912, 0.01197353 0.10879883 -0.25179073, 0.012376785 0.10876074 -0.25201905, 0.011930496 0.10871756 -0.25184599, 0.012014061 0.10858224 -0.25198013, 0.012313455 0.10864203 -0.2520977, 0.012254626 0.10848343 -0.25216082, 0.012210608 0.10828504 -0.25219247, 0.012722552 0.10879241 -0.25214419, 0.012674779 0.10872637 -0.25220627, 0.013139009 0.10854027 -0.25264671, 0.0140616 0.10792242 -0.253508, 0.013626933 0.10864848 -0.25283861, 0.014190286 0.10850321 -0.25339246, 0.01407364 0.10813585 -0.25350916, 0.014121443 0.10834189 -0.2534655, 0.014637619 0.10866864 -0.25349617, 0.014579266 0.10860625 -0.25356188, 0.014939457 0.10846828 -0.2540414, 0.015673071 0.10794014 -0.25499073, 0.015401155 0.10861255 -0.25427178, 0.01567775 0.10816132 -0.25497279, 0.015805304 0.10853419 -0.25482738, 0.015727371 0.10837249 -0.25491193, 0.016251832 0.10873012 -0.25496948, 0.016183525 0.10867269 -0.2550371, 0.016433001 0.1085929 -0.25552589, 0.016919732 0.10883771 -0.25570062, 0.017214268 0.10887793 -0.25620273, 0.016846806 0.10878289 -0.25576872, 0.017113924 0.10877061 -0.25630099, 0.017028391 0.10861151 -0.25639847, 0.017555118 0.10901144 -0.25648326, 0.018079519 0.10922894 -0.25720853, 0.018582672 0.10952829 -0.25799006, 0.018143266 0.10921915 -0.25775221, 0.018663138 0.10961071 -0.25841936, 0.018985599 0.10986099 -0.25869444, 0.019060433 0.10998167 -0.25905666, 0.018944025 0.10988811 -0.25916311, 0.019366026 0.11028931 -0.25944558, 0.019380033 0.11042134 -0.25983784, 0.019663244 0.11074218 -0.26011363, 0.015997916 0.10814714 -0.25532648, 0.016649902 0.10826324 -0.25608206, 0.016978294 0.10839939 -0.25648007, 0.016981542 0.10817528 -0.2565237, 0.017163187 0.10865711 -0.25657055, 0.017454416 0.10886541 -0.25679162, 0.01743263 0.10875542 -0.25693521, 0.018012077 0.10863738 -0.25804177, 0.017932087 0.1089967 -0.25766996, 0.018051565 0.10906564 -0.25786299, 0.018001586 0.10885809 -0.25796837, 0.018151462 0.10890085 -0.25824675, 0.018230706 0.10903637 -0.25833848, 0.018431008 0.10903887 -0.25876638, 0.018627346 0.10938102 -0.25906202, 0.018847793 0.10974355 -0.25928727, 0.018681794 0.10936253 -0.25921878, 0.018813878 0.10933627 -0.25952354, 0.018797964 0.1095465 -0.25941774, 0.019006729 0.10990877 -0.25971562, 0.018919408 0.10964194 -0.25970948, 0.018982977 0.10979809 -0.25979206, 0.01913318 0.10986607 -0.26022086, 0.019279093 0.11026362 -0.26048079, 0.01931569 0.11026475 -0.26063484, 0.010054737 0.089376554 -0.28896895, 0.0095694661 0.089447007 -0.28995952, 0.010308802 0.089629754 -0.2898066, 0.0095228851 0.089473069 -0.28978455, 0.010231167 0.089665577 -0.28963298, 0.0094871223 0.089458734 -0.28960505, 0.010163456 0.089656457 -0.28945217, 0.0094644725 0.08940509 -0.2894319, 0.010109454 0.089602709 -0.28927436, 0.009455502 0.089315206 -0.28927377, 0.010072559 0.089507699 -0.28911018, 0.0094610453 0.089193195 -0.2891376, 0.0090365708 0.089301929 -0.2895914, 0.0088135302 0.089214101 -0.28956825, 0.0085946321 0.089120224 -0.28953362, 0.021753848 0.11661686 -0.26731029, 0.021764338 0.11659037 -0.26714078, 0.021628827 0.11652631 -0.26720884, 0.023561954 0.11652176 -0.27385592, 0.023833722 0.11612208 -0.27485314, 0.023666322 0.11605851 -0.27484784, 0.023697406 0.11656727 -0.27384621, 0.02244556 0.11647549 -0.27112725, 0.021835059 0.1167317 -0.26798472, 0.022873223 0.11623107 -0.27279842, 0.02214551 0.11692296 -0.26828203, 0.023439199 0.11645688 -0.27385619, 0.023516119 0.11596365 -0.27482429, 0.022534281 0.11710711 -0.26911059, 0.023232996 0.11677188 -0.27285063, 0.022390097 0.11706577 -0.26916152, 0.023330718 0.11637515 -0.27384746, 0.02339074 0.11584252 -0.27478352, 0.023124188 0.11668602 -0.27285424, 0.022070438 0.11689208 -0.26831338, 0.020050079 0.11297356 -0.26300743, 0.023223311 0.11626065 -0.27382621, 0.023017108 0.11656509 -0.27284846, 0.020269692 0.11335269 -0.262822, 0.020124853 0.11327575 -0.26307586, 0.020394534 0.11356147 -0.26287761, 0.020354182 0.11384495 -0.2632561, 0.023130357 0.11610924 -0.27378878, 0.023296237 0.11570083 -0.27472761, 0.022926062 0.11640514 -0.27282965, 0.020088404 0.11322287 -0.26321098, 0.02307412 0.11594409 -0.27373901, 0.023237735 0.11554593 -0.27465943, 0.020073622 0.11315402 -0.263298, 0.020144969 0.11339071 -0.26371869, 0.020542532 0.1136038 -0.26279533, 0.020221829 0.11385377 -0.26392666, 0.020607263 0.11430064 -0.26350731, 0.02046302 0.11443068 -0.26392797, 0.02030313 0.1141461 -0.2642329, 0.020315766 0.11397322 -0.26438811, 0.022260249 0.11699714 -0.26921159, 0.020359308 0.11430995 -0.26406702, 0.020417631 0.11452179 -0.26442155, 0.020725846 0.11471756 -0.26396206, 0.0207223 0.1150132 -0.26447982, 0.022148162 0.1169046 -0.26925901, 0.020389766 0.11442757 -0.26450917, 0.020467609 0.11358595 -0.26283264, 0.020496249 0.11460143 -0.26499346, 0.020644128 0.11509472 -0.26516762, 0.020944446 0.11531489 -0.26472828, 0.021039695 0.11566181 -0.26536909, 0.022919267 0.11712416 -0.27103296, 0.020816177 0.11544533 -0.26557371, 0.020752102 0.11526713 -0.26570323, 0.020920336 0.11557616 -0.26546004, 0.020613909 0.11499627 -0.26524505, 0.020735323 0.11456141 -0.26373294, 0.020586222 0.11450934 -0.26382175, 0.020750284 0.11507632 -0.26582065, 0.022793382 0.1170543 -0.27106401, 0.020865977 0.1154862 -0.26602331, 0.021173477 0.11579576 -0.26548102, 0.021225721 0.11602609 -0.26610115, 0.022683293 0.11696339 -0.27108935, 0.022576928 0.11683412 -0.27111134, 0.022042543 0.11677016 -0.26931038, 0.021253616 0.11613093 -0.26669064, 0.021461159 0.11626104 -0.26639333, 0.021002352 0.11558788 -0.2665616, 0.022490263 0.11666213 -0.27112576, 0.021961778 0.11658983 -0.26935962, 0.021027058 0.11533903 -0.26468536, 0.021928281 0.11639462 -0.26939628, 0.021157593 0.11592083 -0.26689658, 0.021182269 0.1157196 -0.26528797, 0.021317512 0.11591882 -0.26752943, 0.021284044 0.1161591 -0.26698402, 0.021513343 0.11643557 -0.26727974, 0.021408588 0.11630021 -0.26736298, 0.02133587 0.11611675 -0.26745257, 0.023356527 0.11683956 -0.27283922, 0.021461785 0.11626078 -0.26780218, 0.021604389 0.11626406 -0.26836163, 0.021777183 0.11650954 -0.26875782, 0.021539986 0.11628838 -0.26635447, 0.021910787 0.11670737 -0.26888871, 0.010384709 0.089647651 -0.28978506, 0.010305464 0.089685246 -0.28961128, 0.010235816 0.089677155 -0.28942946, 0.010179967 0.089623779 -0.28925076, 0.010141194 0.089528367 -0.28908551, 0.010121912 0.089396417 -0.28894377, 0.023449421 0.11364144 -0.27846897, 0.023508608 0.1137916 -0.2785466, 0.023264557 0.11269054 -0.28037074, 0.023499668 0.11474845 -0.27663276, 0.024041802 0.11514761 -0.27680239, 0.023872852 0.11509092 -0.27678326, 0.023721367 0.11500221 -0.27674735, 0.024050862 0.11416875 -0.27876043, 0.02386117 0.11319357 -0.28071091, 0.023693681 0.11315067 -0.28066465, 0.023594886 0.11488619 -0.27669644, 0.023881972 0.11411901 -0.27872765, 0.023543268 0.11307427 -0.28060418, 0.023730367 0.11403646 -0.27867934, 0.023417652 0.11296839 -0.28053233, 0.02344054 0.11459582 -0.27655989, 0.023603857 0.11392555 -0.27861813, 0.023323298 0.11283825 -0.28045335, 0.02025649 0.099630073 -0.28540197, 0.020187348 0.09865953 -0.28538737, 0.020019025 0.09870708 -0.28532624, 0.019869119 0.098750845 -0.28522643, 0.020104289 0.099673867 -0.28530499, 0.019925088 0.099830627 -0.28430501, 0.019843161 0.099822611 -0.284518, 0.019745648 0.098788336 -0.2850934, 0.01997906 0.099715829 -0.28517437, 0.019644022 0.09882161 -0.28490636, 0.019876063 0.099759609 -0.28498966, 0.019592077 0.098842755 -0.28466913, 0.019823849 0.09979853 -0.28475419, 0.019610375 0.09884499 -0.28443193, 0.019040853 0.097110182 -0.28448686, 0.018267661 0.095460922 -0.28479236, 0.017244786 0.093898833 -0.28533304, 0.015940219 0.092474192 -0.28607738, 0.014316827 0.091223702 -0.28698167, 0.012409508 0.090208441 -0.28795034, 0.020415843 0.10075465 -0.28557578, 0.020731091 0.10138336 -0.28583947, 0.020557076 0.10141814 -0.28578427, 0.020240843 0.099863857 -0.28539768, 0.019459486 0.098389 -0.28462031, 0.019344628 0.097968206 -0.28478602, 0.019174904 0.097537398 -0.28464818, 0.01907742 0.097155422 -0.28495601, 0.019025683 0.097145811 -0.28471997, 0.018815398 0.096645743 -0.28474769, 0.018660456 0.096287996 -0.28496924, 0.018426299 0.095837921 -0.28490198, 0.018309265 0.095567241 -0.28524521, 0.018257827 0.095530272 -0.28501514, 0.017947048 0.094999269 -0.28513026, 0.017431736 0.094238356 -0.28540161, 0.017293394 0.094055936 -0.2857599, 0.017241865 0.093995869 -0.28554031, 0.016835868 0.093513846 -0.28581521, 0.016825944 0.093482032 -0.28573731, 0.016597033 0.093253404 -0.28614518, 0.016177118 0.092822433 -0.28618446, 0.016076237 0.092697054 -0.28665298, 0.015996218 0.092668399 -0.28647286, 0.015945286 0.092591137 -0.28626677, 0.016166329 0.09278737 -0.28610936, 0.015414387 0.092120633 -0.28653136, 0.015425652 0.092158496 -0.28660339, 0.015115798 0.091946915 -0.28695735, 0.014609009 0.09155415 -0.28704789, 0.014448911 0.091478854 -0.28751677, 0.01437825 0.091440812 -0.28734395, 0.014329255 0.091352269 -0.28715268, 0.014597297 0.091514394 -0.28697899, 0.013692439 0.090989396 -0.28752694, 0.013322622 0.090838253 -0.28788167, 0.012755573 0.090418309 -0.28885487, 0.012672126 0.090468079 -0.28872642, 0.012596995 0.090488359 -0.28858903, 0.012730032 0.090498224 -0.2880021, 0.012532413 0.090479821 -0.28844747, 0.012472332 0.090435162 -0.28828281, 0.012427151 0.09034124 -0.28810528, 0.012046963 0.090233102 -0.28839633, 0.012030631 0.090194598 -0.28832835, 0.011497915 0.090073407 -0.28887638, 0.010899931 0.089798734 -0.28885239, 0.010923415 0.089845449 -0.28894296, 0.01071462 0.089810401 -0.28916731, 0.020167619 0.10120797 -0.28536716, 0.020402014 0.10146236 -0.28569141, 0.02027449 0.10151339 -0.28556588, 0.020181566 0.10156873 -0.28541455, 0.020124823 0.10123762 -0.28527546, 0.020128071 0.10162519 -0.28524569, 0.020116866 0.10167991 -0.28506824, 0.020148724 0.10172969 -0.28489175, 0.020014554 0.10078552 -0.28499904, 0.019993246 0.10032211 -0.28509006, 0.019916028 0.09842889 -0.28530946, 0.019699007 0.098338008 -0.28517815, 0.019782066 0.098313674 -0.28525057, 0.019793063 0.097857162 -0.28534812, 0.019493192 0.097493097 -0.28528067, 0.019438148 0.097066805 -0.28538898, 0.019294411 0.097110614 -0.28528288, 0.019599527 0.097011223 -0.28545871, 0.019411981 0.097516134 -0.28520659, 0.019175678 0.097140402 -0.28514546, 0.01929611 0.09678708 -0.28541556, 0.019067049 0.096694082 -0.2852985, 0.019146264 0.096672326 -0.28537422, 0.019102246 0.096240193 -0.28553861, 0.018753856 0.095891237 -0.28552368, 0.018800914 0.095441744 -0.28577009, 0.018649757 0.09550339 -0.28568915, 0.018514842 0.095546484 -0.28557518, 0.018677145 0.095911697 -0.28544614, 0.018403083 0.095568687 -0.28543428, 0.018274426 0.095309421 -0.28554013, 0.018220365 0.09531413 -0.28545341, 0.018108934 0.094857305 -0.2858068, 0.017771214 0.094553337 -0.28578892, 0.017744094 0.093952283 -0.2863057, 0.017606378 0.094017014 -0.28621152, 0.017450303 0.094195038 -0.28584287, 0.017483681 0.094057515 -0.28608951, 0.017381132 0.094072074 -0.28594562, 0.017210096 0.093632445 -0.28635266, 0.016542912 0.092952475 -0.28671244, 0.016396821 0.092591256 -0.2870352, 0.016275704 0.092654794 -0.28692749, 0.016167462 0.092690289 -0.28679779, 0.015854895 0.092470899 -0.28686747, 0.015790254 0.092305541 -0.28711662, 0.014962286 0.091707677 -0.28755111, 0.014619052 0.091451705 -0.28779575, 0.014527202 0.091480091 -0.28766102, 0.014721453 0.091393575 -0.28791571, 0.014163017 0.091289014 -0.28775129, 0.014053077 0.091159135 -0.28800979, 0.020301789 0.1001403 -0.28544524, 0.017612815 0.094496086 -0.28532386, 0.023312926 0.11273651 -0.28080556, 0.02030915 0.10262467 -0.28564084, 0.023602903 0.11280139 -0.28132024, 0.020503789 0.1036717 -0.28577784, 0.020609081 0.10363619 -0.28595671, 0.023168147 0.11236949 -0.28115979, 0.020414352 0.10257417 -0.28582108, 0.020253956 0.10267636 -0.28540972, 0.020445019 0.10370162 -0.28554842, 0.023159057 0.11225069 -0.28160027, 0.023101002 0.11197038 -0.28212574, 0.023009121 0.111857 -0.28201318, 0.02027005 0.1027168 -0.28517798, 0.022955179 0.11172561 -0.28189644, 0.020454317 0.10371716 -0.28531739, 0.023208439 0.11204945 -0.28221557, 0.021575809 0.10775474 -0.28495327, 0.021924436 0.10836732 -0.28509504, 0.021392465 0.10718147 -0.28496882, 0.021591693 0.10729145 -0.28553122, 0.021485865 0.10727666 -0.28537351, 0.021921128 0.10797717 -0.28539404, 0.021411866 0.10723871 -0.28517318, 0.021415055 0.1067763 -0.28565836, 0.021844596 0.10727356 -0.28573677, 0.02170819 0.10728936 -0.28564572, 0.023210675 0.11179057 -0.2826587, 0.021553069 0.10621004 -0.28602031, 0.023441285 0.11213334 -0.28234246, 0.021349639 0.1067723 -0.28556135, 0.023317605 0.11210001 -0.28228381, 0.022980064 0.11142054 -0.28292218, 0.021152675 0.10634035 -0.28550118, 0.022572011 0.11059891 -0.28333214, 0.022526264 0.11048688 -0.28318378, 0.0208776 0.10545988 -0.28530565, 0.021146357 0.1058695 -0.2858443, 0.021317065 0.10543057 -0.28613308, 0.021174192 0.10545962 -0.28603956, 0.022989243 0.11113298 -0.28335634, 0.022877276 0.11078891 -0.2836771, 0.02276662 0.11075345 -0.28359079, 0.022659749 0.11069214 -0.28347602, 0.021054059 0.10547927 -0.28591761, 0.021080762 0.10587291 -0.28574324, 0.020882279 0.10548328 -0.2855278, 0.020948559 0.10548936 -0.28574648, 0.022843957 0.11048494 -0.28398821, 0.020847231 0.10513048 -0.28577039, 0.022763282 0.1104726 -0.28393671, 0.021048576 0.10470892 -0.28614494, 0.020675808 0.10465488 -0.28564468, 0.022492856 0.11001816 -0.28414556, 0.021986187 0.1089503 -0.28423664, 0.020621389 0.10422321 -0.28579471, 0.021066666 0.10431287 -0.28621194, 0.022568345 0.10967214 -0.28457519, 0.022321492 0.10916342 -0.2848289, 0.020673007 0.10401459 -0.28595552, 0.020882338 0.1035621 -0.28617626, 0.020733029 0.10360058 -0.28608224, 0.022486538 0.10966547 -0.28451952, 0.022102058 0.10910614 -0.28458881, 0.02202034 0.10903792 -0.28441498, 0.023449033 0.11242701 -0.28186515, 0.022208333 0.10914588 -0.28472671, 0.022312343 0.10890907 -0.28502235, 0.022229016 0.10890736 -0.2849637, 0.022006065 0.10797295 -0.28545552, 0.020863831 0.10245074 -0.28609633, 0.020692676 0.10248861 -0.28604063, 0.020540208 0.10253052 -0.28594714, -0.024131909 0.1071988 0.28424129, -0.024637982 0.10899431 0.28346398, -0.024036184 0.085871398 0.27385846, -0.023666725 0.10536826 0.28462499, -0.0089846849 0.10936642 0.24829766, -0.0089332163 0.10937321 0.24827981, -0.0089331865 0.10080522 0.24399501, -0.023316026 0.10365915 0.2846444, -0.023083374 0.10194576 0.28432769, -0.011533156 0.10900825 0.24935818, -0.011801511 0.10023981 0.24512595, -0.022929639 0.10069358 0.28404367, -0.022735536 0.084595859 0.2764093, -0.022695884 0.09942764 0.28390947, -0.013932601 0.10872352 0.25074494, -0.014494896 0.099522769 0.24656031, -0.022224754 0.09766227 0.28396687, -0.01589343 0.10862154 0.25225398, -0.016973406 0.098664343 0.24827629, -0.021569908 0.095949769 0.28429517, -0.021098152 0.083400398 0.27879989, -0.017521381 0.10873839 0.25386652, -0.020689219 0.094295174 0.28488293, -0.019200608 0.097677797 0.25024918, -0.01885201 0.10910821 0.25553766, -0.019556552 0.092756242 0.28570211, -0.019148096 0.082302839 0.2809948, -0.019907296 0.10975674 0.25721171, -0.021143243 0.096577436 0.25244948, -0.018130019 0.091361105 0.28672007, -0.016914204 0.081319213 0.28296161, -0.020696506 0.11068442 0.25880763, -0.016391829 0.090153754 0.28787473, -0.021244481 0.11188382 0.26026756, -0.014429733 0.080464453 0.28467104, -0.014177501 0.089095384 0.28917584, -0.021568835 0.11334184 0.26153931, -0.022772551 0.095379859 0.25484434, -0.011731461 0.079751074 0.28609788, -0.011780322 0.088331729 0.29036081, -0.011731625 0.088318914 0.2903825, -0.021736324 0.11421481 0.26226684, -0.021977201 0.11497846 0.26308087, -0.022462472 0.11594012 0.26448852, -0.023042947 0.11662519 0.26605752, -0.024064243 0.094102353 0.25739893, -0.023661494 0.11700752 0.26773992, -0.024308592 0.11705738 0.26962528, -0.024999678 0.092764407 0.26007476, -0.024847627 0.11674625 0.27141216, -0.025277555 0.11608142 0.27314344, -0.025564447 0.091385305 0.26283249, -0.025612652 0.11507466 0.27515659, -0.025750399 0.089985609 0.26563075, -0.025747657 0.1140587 0.27718812, -0.02568157 0.11304134 0.27922282, -0.025554836 0.088586658 0.26842883, -0.025576487 0.11249155 0.28018439, -0.02542688 0.11184591 0.28106999, -0.024980605 0.08720845 0.27118525, -0.02509734 0.11060396 0.28234142, 0.0050504953 0.10753804 0.24781901, 0.0097492933 0.10049775 0.2446107, 0.0026385635 0.10733846 0.24755877, 0.0074090064 0.10799873 0.24820629, 0.0096793473 0.10871404 0.2487146, 0.0097492635 0.10873994 0.24873245, -0.0068320632 0.10915306 0.24783707, -0.0069020987 0.10094032 0.24372527, -0.0069019943 0.10918257 0.24784708, -0.0045616627 0.10831699 0.2475698, -0.0022031814 0.10773084 0.24743336, 0.00020880997 0.10740289 0.24742964, 0.024130791 0.11523694 0.26816782, 0.024636716 0.11569238 0.27007046, 0.024035409 0.094135553 0.25733319, 0.023665681 0.11444581 0.26647326, 0.0089837611 0.08777982 0.29146478, 0.008932218 0.087769806 0.29148117, 0.0089323521 0.079201669 0.2871964, 0.023314863 0.11343601 0.26509398, 0.023082227 0.11215493 0.26391307, 0.01153183 0.088413626 0.2905421, 0.011800632 0.079767287 0.28606585, 0.022928447 0.11117625 0.26308158, 0.022734806 0.095411062 0.25478229, 0.022694826 0.11030963 0.26214948, 0.013931558 0.08935225 0.28948233, 0.014494017 0.08048439 0.28463158, 0.022223711 0.10929638 0.26070246, 0.015892372 0.090498418 0.28849557, 0.016972542 0.081342578 0.28291556, 0.02156882 0.10853168 0.2591354, 0.021097288 0.096606612 0.25239179, 0.017520323 0.091858506 0.28762177, 0.020688176 0.10800946 0.25745878, 0.019199729 0.082329243 0.28094265, 0.018850923 0.093417406 0.28691491, 0.019555435 0.10774156 0.25573638, 0.019147158 0.097704232 0.25019693, 0.019906104 0.09514612 0.28642944, 0.021142304 0.083429486 0.27874199, 0.018128961 0.10771877 0.25400943, 0.016913444 0.098687708 0.24823007, 0.020695373 0.096979409 0.28621432, 0.016390711 0.10791853 0.25235069, 0.021243304 0.098866612 0.28629825, 0.014428899 0.099542618 0.2465207, 0.014176354 0.1083245 0.25072321, 0.021567658 0.10075876 0.28670177, 0.022771537 0.084627241 0.27634743, 0.011730611 0.100256 0.24509391, 0.011779398 0.10881439 0.24940163, 0.011730522 0.10882404 0.24937856, 0.021735296 0.10186484 0.28696361, 0.021976069 0.10297439 0.28708631, 0.02246131 0.10467747 0.28701124, 0.0230418 0.10634369 0.28661802, 0.024063319 0.085904598 0.27379283, 0.023660138 0.1079191 0.28591451, 0.024307296 0.10945734 0.28482372, 0.02499871 0.087242752 0.271117, 0.024846405 0.11070031 0.28350285, 0.025276303 0.11168659 0.28193209, 0.025563419 0.088621736 0.26835939, 0.02561146 0.11269334 0.27991918, 0.025749609 0.090021163 0.26556069, 0.025746495 0.11370936 0.27788737, 0.025680453 0.11472687 0.27585304, 0.025553823 0.091420531 0.26276264, 0.025575206 0.11516637 0.27483597, 0.025425658 0.11548755 0.27378827, 0.024979711 0.09279871 0.26000655, 0.025096163 0.11575979 0.2720319, -0.0050514936 0.086299807 0.29028901, -0.0097503066 0.079509437 0.28658101, -0.0026395768 0.0859721 0.2902855, -0.0074100196 0.086886048 0.29042548, -0.0096803457 0.087722003 0.29069248, -0.009750247 0.087751597 0.29070279, 0.0068310946 0.087283283 0.29157051, 0.0069009811 0.079066753 0.28746626, 0.0069010854 0.087308973 0.29158819, 0.0045606643 0.086567789 0.29106164, 0.0022022873 0.086106867 0.29067466, -0.00020973384 0.08590737 0.29041442, -0.02411744 0.11573482 0.27562556, -0.023787096 0.11670986 0.27367523, -0.024492219 0.11672863 0.2736378, -0.024816945 0.11575332 0.27558836, -0.024947628 0.11476874 0.27755699, -0.024248317 0.11475021 0.27759436, -0.024883777 0.11378303 0.27952823, -0.024178505 0.1137642 0.27956578, 0.02424702 0.11444911 0.27819687, 0.024882361 0.11541632 0.27626297, 0.024177432 0.11543497 0.27622548, 0.024946526 0.11443046 0.27823433, 0.024116129 0.11346444 0.28016576, 0.024815679 0.113446 0.28020296, 0.024490982 0.11247054 0.28215346, 0.023785874 0.11248913 0.28211591, -0.02118057 0.087737709 0.27571604, -0.022275731 0.088961363 0.27326906, -0.021481961 0.10591382 0.28406742, -0.021919549 0.10761404 0.283721, -0.022415012 0.10936666 0.28298405, -0.011210874 0.08944729 0.28834629, -0.011210889 0.083027214 0.28513584, -0.0112748 0.089467466 0.28831753, -0.022850469 0.11089125 0.28193429, -0.02301909 0.090236813 0.27071875, -0.023175806 0.11212054 0.28065822, -0.012708455 0.089983642 0.28762114, -0.013705671 0.083728731 0.2837328, -0.014068857 0.090622216 0.28688121, -0.023398891 0.091543883 0.26810512, -0.023380876 0.11307624 0.27915272, -0.023448348 0.11402959 0.27724653, -0.015983835 0.084564626 0.28206107, -0.015864059 0.091785342 0.2857959, -0.023409098 0.092861682 0.26546928, -0.023321822 0.11498177 0.27534252, -0.01732941 0.093156099 0.28483641, -0.023049757 0.094169885 0.26285347, -0.02300249 0.11592472 0.27345669, -0.018009558 0.085521907 0.28014687, -0.018507898 0.094724655 0.28405777, -0.022788465 0.11630896 0.27256313, -0.022037342 0.11680406 0.27003375, -0.02232644 0.095447719 0.26029834, -0.021454245 0.11670351 0.26836184, -0.022540018 0.11658207 0.2716513, -0.020785809 0.11621279 0.26656285, -0.021250516 0.096674711 0.2578446, -0.020178184 0.11536676 0.26491997, -0.019719929 0.11427397 0.26354364, -0.019839063 0.097831696 0.25553092, -0.019427463 0.11292446 0.26237372, -0.019167185 0.11163512 0.26130709, -0.018746838 0.11053616 0.26011208, -0.018094331 0.10956165 0.25869802, -0.018114418 0.098900378 0.25339386, -0.017226994 0.10883179 0.25722209, -0.016103581 0.099864006 0.25146711, -0.016120553 0.10834023 0.25572386, -0.014728308 0.10807523 0.25422999, -0.013838366 0.10070705 0.24978125, -0.013030663 0.10802412 0.2528089, -0.02010861 0.09834072 0.28325453, -0.019751102 0.086585253 0.27802083, -0.020369679 0.099316835 0.28324416, -0.019427732 0.096469373 0.28351358, -0.011354774 0.10141635 0.24836263, -0.011083141 0.10814559 0.25156224, -0.0086918175 0.10198092 0.24723405, -0.0087593496 0.10839349 0.25047097, -0.0086918771 0.10840091 0.2504445, -0.021119013 0.1042003 0.28409275, -0.020960286 0.10322061 0.28396329, -0.02084662 0.10224673 0.28372607, -0.020577788 0.10029837 0.28331837, 0.021918267 0.11506978 0.2688123, 0.022274807 0.095517725 0.26015893, 0.02241379 0.11553171 0.27065629, 0.021480918 0.11432692 0.26724377, 0.01120992 0.10787192 0.25150269, 0.01120995 0.10145178 0.24829215, 0.011273831 0.10786101 0.25153622, 0.021179691 0.096741289 0.25771198, 0.012707263 0.1076133 0.25236684, 0.022849351 0.11560649 0.27250603, 0.023018166 0.094242215 0.26270923, 0.023174524 0.11532292 0.27425507, 0.013704628 0.10075021 0.24969512, 0.014067829 0.10740489 0.25332162, 0.023397863 0.092935234 0.26532295, 0.023379743 0.11469185 0.27592286, 0.023447171 0.11373854 0.27782914, 0.015982792 0.099914372 0.25136688, 0.015863061 0.10723403 0.25490329, 0.023408249 0.091617286 0.26795861, 0.023320556 0.11278629 0.27973312, 0.017328382 0.10728869 0.25657544, 0.023048878 0.090309054 0.2705746, 0.018008649 0.098957092 0.25328091, 0.01850678 0.10760665 0.2582978, 0.023001194 0.11184344 0.2816188, 0.022787064 0.11135867 0.28246233, 0.022325516 0.089031428 0.27312967, 0.02203618 0.10963228 0.28437585, 0.021453083 0.10823438 0.28529832, 0.022538751 0.11079305 0.28322798, 0.021249518 0.087804407 0.27558336, 0.020784348 0.1065008 0.28598496, 0.020177022 0.10467824 0.28629363, 0.01983811 0.086647332 0.27789709, 0.019718543 0.10292196 0.28624502, 0.019426361 0.10117626 0.28586739, 0.019165888 0.099549472 0.28547555, 0.018745735 0.097934037 0.28531337, 0.01811339 0.08557868 0.28003418, 0.018093303 0.096218288 0.28538162, 0.017225936 0.094599277 0.28568354, 0.016102552 0.084615141 0.28196076, 0.016119435 0.093105882 0.28618881, 0.014727205 0.091751605 0.28687301, 0.020107463 0.10913351 0.26167244, 0.019750267 0.097893864 0.25540718, 0.020368502 0.10971087 0.26245984, 0.013837457 0.083772004 0.28364676, 0.013029665 0.090584099 0.28768465, 0.019426599 0.10821801 0.26002035, 0.011353821 0.083062619 0.28506526, 0.011082113 0.089659482 0.28852978, 0.020576626 0.11035877 0.26320055, 0.020845681 0.1118539 0.26451492, 0.0086908638 0.082498163 0.286194, 0.008758381 0.088935107 0.28938243, 0.0086908191 0.088918269 0.28940442, 0.021117896 0.11331928 0.26585808, 0.020959213 0.11262795 0.26515183, -0.0066581815 0.10914519 0.24954826, -0.0061822683 0.10895455 0.24946091, -0.0065502822 0.10943881 0.24889475, -0.0039981306 0.10852554 0.24860749, -0.0037527829 0.10813269 0.24921134, -0.0013381094 0.10794052 0.24849162, -0.0012319982 0.10760576 0.24911556, 0.001376152 0.10769585 0.24854997, 0.0013346523 0.10738325 0.24917492, 0.0039011091 0.10746938 0.2493884, 0.0040903986 0.10779634 0.24878031, 0.0064218938 0.10786214 0.24975234, 0.006750375 0.10823974 0.24917901, 0.0088515729 0.10855505 0.25026044, 0.0093024522 0.10901752 0.24973741, 0.0093248636 0.10872036 0.25039813, -0.0093257874 0.089072675 0.28968775, -0.00930354 0.088722467 0.29032195, -0.008852452 0.088862985 0.28963825, -0.0067514032 0.087809026 0.29003468, -0.0064229965 0.088041246 0.28938863, -0.0040914267 0.087224156 0.28991905, -0.0039022565 0.087514281 0.28929245, -0.0013356507 0.087291896 0.28935185, -0.0013772249 0.086979359 0.28997698, 0.00123097 0.087377936 0.28956565, 0.0013370812 0.087079883 0.29020754, 0.0037516952 0.087770879 0.28992978, 0.003997013 0.087523341 0.29060617, 0.0061812401 0.088463455 0.29043737, 0.0065492392 0.088300824 0.29116479, 0.0066570938 0.088647664 0.29053751, -0.0091172904 0.082759202 0.2856721, -0.0091174096 0.088570088 0.28857806, -0.006586805 0.087714106 0.28831813, -0.0039614737 0.087165296 0.28821814, -0.0012881607 0.086933583 0.28827965, 0.0065409988 0.082342863 0.28650463, 0.0013851374 0.087023139 0.28850234, 0.004010573 0.087432325 0.28888166, 0.0065409541 0.088153839 0.28941044, 0.0091163069 0.10172004 0.24775597, 0.0091163665 0.10753092 0.25066182, 0.006585896 0.10680929 0.25013283, 0.0039604753 0.10640025 0.24975374, 0.0012871325 0.10631067 0.24953136, -0.0065419972 0.10213631 0.24692345, -0.001386106 0.10654232 0.24946943, -0.0040116012 0.10709107 0.24956939, -0.0065420419 0.1079472 0.24982929, -0.0082722604 0.10089201 0.24382159, -0.0075909644 0.10093746 0.24373111, -0.010433495 0.079548746 0.28650221, -0.011098206 0.079629838 0.28634003, 0.010432541 0.10045829 0.24468946, 0.011097163 0.10037723 0.24485156, 0.0082713515 0.079114914 0.28736982, 0.0075899512 0.079069704 0.28746036, 0.010544047 0.10158652 0.24802244, 0.00984101 0.10167676 0.24784222, -0.010544792 0.082892329 0.28540567, -0.0098420084 0.082802415 0.28558573, 0.0072720051 0.082347453 0.28649572, 0.0079937726 0.082399487 0.28639138, -0.0072730035 0.10213163 0.24693248, -0.0079948306 0.10207951 0.2470367, 0.020042345 0.10074508 0.28703263, 0.020700917 0.099738598 0.28682002, 0.020850733 0.10072365 0.28707561, 0.019706637 0.098942816 0.28663626, 0.020485222 0.098753333 0.28665885, 0.019140989 0.097170025 0.28654429, 0.019958168 0.097085834 0.28659123, 0.019215688 0.095470786 0.28677011, 0.018315032 0.095442712 0.28673333, 0.018222377 0.093930572 0.28717998, 0.017215714 0.093841821 0.2871711, 0.016963512 0.092527211 0.28778642, 0.01583226 0.092419684 0.28780514, 0.01537697 0.091269076 0.28856537, 0.014127553 0.091191143 0.28858623, 0.013464093 0.090215981 0.28944883, 0.012081251 0.09018144 0.28944832, 0.010596484 0.08966139 0.2900022, 0.011271924 0.089405328 0.29034218, 0.0090500861 0.089256346 0.29050806, 0.0087010562 0.088803113 0.29120266, -0.022413 0.10187367 0.28477517, -0.021410286 0.10047355 0.28451183, -0.021604732 0.10185224 0.28481826, -0.0221387 0.10002533 0.284408, -0.021101385 0.09909001 0.28439674, -0.021669045 0.098195195 0.28437737, -0.020552248 0.097412348 0.28450534, -0.020969868 0.096399158 0.28466418, -0.019799396 0.095810354 0.28486946, -0.02003859 0.094744354 0.28522548, -0.018794313 0.094286293 0.28547433, -0.018825099 0.093227714 0.28602943, -0.017502412 0.092888862 0.28628877, -0.01731953 0.091905206 0.28701261, -0.015884236 0.091653228 0.28726915, -0.015457839 0.090771377 0.28813609, -0.013972104 0.090637177 0.28831932, -0.013502017 0.089947343 0.28917995, -0.011666805 0.089807183 0.2894066, -0.011417732 0.089337885 0.29013285, 0.011416689 0.10923564 0.25034341, 0.011665523 0.10893598 0.25115481, 0.013500914 0.10883904 0.25140244, 0.013971075 0.10856411 0.25247106, 0.015456706 0.10849792 0.25268805, 0.015883029 0.10833338 0.25391373, 0.017318398 0.10827935 0.25426939, 0.017501369 0.10829043 0.25549069, 0.01882413 0.10828611 0.25591725, 0.018793359 0.10847703 0.25709739, 0.020037517 0.10855272 0.25761309, 0.019798368 0.10890743 0.25867933, 0.020968854 0.10909665 0.25927362, 0.020551041 0.10957739 0.26017931, 0.021667957 0.1099444 0.26088241, 0.021100298 0.11049655 0.26158693, 0.022137508 0.11106676 0.2623283, 0.021409079 0.11141872 0.26262492, 0.022411898 0.11246958 0.26358709, 0.021603554 0.1124911 0.26354405, -0.0087021291 0.10977045 0.24927345, -0.011272907 0.1094431 0.25027156, -0.0090510994 0.10948673 0.25005287, -0.010597467 0.10932493 0.25068054, -0.0134653 0.10921478 0.25145611, -0.012082338 0.10919377 0.25142887, -0.01412867 0.10910973 0.25275382, -0.015378147 0.10913965 0.25282863, -0.015833363 0.10922167 0.25420535, -0.016964585 0.10927135 0.25430259, -0.017216772 0.10956788 0.25572345, -0.018223509 0.1096279 0.25578895, -0.018316165 0.11017773 0.257267, -0.019216821 0.11022404 0.25726715, -0.019142032 0.11106268 0.25876233, -0.019959152 0.11104965 0.25866696, -0.02048631 0.11210442 0.25996009, -0.019707844 0.11220008 0.26012549, -0.020702228 0.11282438 0.26065186, -0.020043552 0.11359796 0.26132956, -0.02085191 0.11361963 0.26128665, -0.02255483 0.10316777 0.28506526, -0.021831989 0.10367307 0.28517446, -0.022759274 0.10446802 0.28517815, -0.022175789 0.10549605 0.28518602, -0.023120284 0.10626528 0.28505239, -0.022625476 0.10742089 0.28483054, -0.023534641 0.10802439 0.28460363, -0.023064926 0.10911825 0.28417465, -0.023997262 0.10985121 0.28374833, -0.023476541 0.11067045 0.28323179, -0.024399176 0.11144799 0.28257808, -0.023823395 0.11203733 0.28202626, -0.024698883 0.11275738 0.28116736, -0.024038076 0.11298832 0.28086498, 0.020213306 0.10195303 0.28732666, 0.021128342 0.10254502 0.28746009, 0.02046065 0.10316771 0.28747031, 0.021561325 0.10438174 0.28750792, 0.020933762 0.10494521 0.28741601, 0.0221349 0.10628706 0.28719479, 0.021559805 0.10686108 0.28698877, 0.022777721 0.10812616 0.28649968, 0.022225544 0.10865647 0.28618625, 0.023350641 0.10963333 0.28556654, 0.022848815 0.1102227 0.28506303, 0.02386786 0.11093664 0.28438303, 0.023368061 0.11148584 0.28371504, 0.024206221 0.11177289 0.28333381, -0.024207428 0.11725461 0.27237162, -0.023369268 0.11738735 0.27191296, -0.023869008 0.11759233 0.27107301, -0.022850066 0.11770806 0.27009383, -0.023351789 0.1177572 0.26932016, -0.022226855 0.11766699 0.26816699, -0.022778854 0.1175997 0.26755461, -0.021560952 0.11723244 0.26624933, -0.022136122 0.11705261 0.26566634, -0.02093479 0.11642456 0.26446, -0.021562591 0.11615989 0.26395401, -0.020461828 0.11540186 0.2630052, -0.021129638 0.11502004 0.26251331, -0.020214602 0.11455789 0.26211986, 0.024036869 0.11600894 0.2748253, 0.024697825 0.11611223 0.27445924, 0.023822144 0.11636749 0.2733677, 0.02439788 0.11645553 0.27256528, 0.023475453 0.11651209 0.27155092, 0.023996025 0.11643371 0.27058563, 0.023063868 0.11633518 0.26974317, 0.023533523 0.1160222 0.2686111, 0.02262409 0.11584175 0.26799187, 0.023119226 0.11532575 0.26693439, 0.022174641 0.11497134 0.26623854, 0.022758111 0.11434823 0.26542094, 0.021830827 0.11386827 0.26478705, 0.022553697 0.11347809 0.26444843, 0.0093859881 0.10904875 0.24975762, 0.010039344 0.10922566 0.24991989, 0.010074005 0.1089204 0.25062057, 0.010704204 0.10928839 0.25010702, 0.010835648 0.1089901 0.2508581, 0.011361092 0.10924393 0.25032344, 0.011590064 0.10894582 0.25112519, -0.0089725703 0.10949236 0.25003195, -0.0081868917 0.10949537 0.24984497, -0.0079632998 0.10978433 0.24911359, -0.0086443275 0.10977566 0.24925965, -0.0074097365 0.10938439 0.2496897, -0.0072866976 0.10968545 0.24899784, -0.0066334456 0.10947445 0.24890572, -0.0093870014 0.088757187 0.29033479, -0.010040358 0.088992894 0.29037884, -0.010074928 0.08937043 0.28971425, -0.010705322 0.08918047 0.29031697, -0.010836735 0.089602441 0.28962764, -0.011362195 0.089326978 0.29015163, -0.011591166 0.089789689 0.28943196, 0.0089715272 0.089242935 0.29052517, 0.008185938 0.089095205 0.29063967, 0.0079623163 0.088683426 0.29130974, 0.0086434335 0.088795036 0.29121515, 0.0074086934 0.088904142 0.2906442, 0.0072857887 0.088531405 0.29130024, 0.0066324919 0.088331223 0.29118654, 0.0081089288 0.088763803 0.28954142, 0.0075288117 0.088579863 0.28957969, 0.0069682151 0.088345885 0.28951454, -0.0095423758 0.088784784 0.28863636, -0.010098636 0.089050442 0.28864226, -0.010661572 0.089264601 0.28854251, -0.011088476 0.088152438 0.29060593, -0.010420069 0.087966949 0.29071483, 0.0075730085 0.087487936 0.29167172, 0.0082574934 0.087637484 0.2916353, 0.011087418 0.10890293 0.24911147, 0.010419175 0.10887864 0.24889731, -0.0075740218 0.1093567 0.24793985, -0.0082586408 0.10941723 0.24808145, 0.0095413476 0.10770664 0.25079849, 0.010097653 0.10787061 0.2510078, 0.010660484 0.10791919 0.25123891, -0.008110106 0.10841787 0.25023863, -0.007529676 0.10833824 0.25006875, -0.0069692433 0.10814553 0.24992055, -0.0066310316 0.10953754 0.24873823, -0.0089209229 0.10951984 0.24837023, -0.0087044835 0.10982132 0.24910453, -0.0075255483 0.10950387 0.24803251, -0.0068330318 0.10931796 0.24794188, -0.0074762106 0.10962614 0.24815735, -0.0067697018 0.10942835 0.24806744, -0.0074286461 0.10971645 0.24830821, -0.0067154914 0.1095089 0.24821773, -0.0073854476 0.10976946 0.24847731, -0.0066729933 0.10955516 0.24838546, -0.0073490292 0.10978273 0.24865502, -0.0066443086 0.10956481 0.24856198, -0.0073212087 0.10975534 0.24883252, -0.0078906268 0.10980257 0.24844521, -0.0081233233 0.1098235 0.24852145, -0.0083587021 0.10983017 0.24860361, -0.0087621808 0.1098305 0.24894193, -0.0088149607 0.10980308 0.24878028, -0.0088602901 0.10973966 0.24862617, -0.008896172 0.10964382 0.24848747, -0.0087618828 0.10981461 0.24911886, -0.0088191479 0.10982284 0.24895731, -0.0088711679 0.1097945 0.24879619, -0.0089154691 0.10973102 0.2486431, -0.0089501441 0.10963544 0.24850464, -0.0089735687 0.10951191 0.24838787, -0.0067600161 0.1092872 0.24793112, -0.0066939294 0.10939664 0.24805674, -0.0066370964 0.10947594 0.24820691, -0.006592527 0.1095213 0.24837437, -0.0065623671 0.10953009 0.2485508, -0.0065479428 0.10950223 0.24872705, -0.011611164 0.10918021 0.2495265, -0.011552066 0.10933194 0.24968478, -0.019579634 0.11012039 0.25721148, -0.019476205 0.11017975 0.25723848, -0.013885707 0.10890394 0.25083718, -0.013810903 0.10905433 0.25096688, -0.021191821 0.11311492 0.26100886, -0.02102001 0.11360031 0.26128262, -0.021182805 0.1135608 0.26130751, -0.021332875 0.11350262 0.26136017, -0.019695848 0.11003032 0.25719228, -0.021463484 0.1134285 0.2614387, -0.020473093 0.11092883 0.25872853, -0.019814029 0.1099022 0.25719097, -0.021029532 0.11241835 0.26039794, -0.021013185 0.11209103 0.26013443, -0.021141395 0.11199436 0.26018992, -0.020597324 0.11081439 0.25875714, -0.020778611 0.11220288 0.26009664, -0.020888969 0.11215857 0.26010633, -0.018343687 0.10960603 0.25573501, -0.018448353 0.10956094 0.255676, -0.010235339 0.10944086 0.2489756, -0.011418432 0.10945964 0.24998537, -0.011347353 0.1094676 0.25012958, -0.011483863 0.10942009 0.24984425, -0.018546835 0.10949916 0.25562671, -0.009481892 0.10972381 0.24910185, -0.018656462 0.10940307 0.25558063, -0.018766984 0.10926536 0.25554696, -0.01706773 0.10925144 0.25421482, -0.017166302 0.10921007 0.25413415, -0.017258793 0.10914916 0.25406203, -0.017360598 0.10905102 0.25398782, -0.017461479 0.10890698 0.2539219, -0.015474573 0.10913086 0.25272134, -0.015565708 0.10909706 0.25261882, -0.015650779 0.10904065 0.25252309, -0.015743479 0.10894355 0.2524195, -0.015832007 0.10879543 0.25232127, -0.013571218 0.10921952 0.25134245, -0.013653323 0.10919708 0.25121805, -0.013729528 0.10914782 0.25109932, -0.020131052 0.11110392 0.25874946, -0.020244867 0.11106324 0.25873002, -0.020352185 0.11100972 0.25872242, -0.019366443 0.11022455 0.2572768, -0.0013286322 0.10802552 0.24814612, -0.0020997673 0.10815895 0.24816173, -0.0020991117 0.10813531 0.24833921, 0.0026266128 0.10748863 0.24765575, 0.0014224499 0.10748783 0.24757525, 0.0014189035 0.10761258 0.24770379, -0.0013302416 0.10800222 0.24832371, 0.0026127249 0.10761335 0.24778336, -0.0021235198 0.10808933 0.2478134, -0.0043930709 0.10871145 0.24811551, -0.0021079332 0.10814333 0.24798325, 0.0049194098 0.1079565 0.24835709, 0.0041221678 0.10788077 0.24843609, 0.0048932582 0.10797313 0.24853349, 0.0041446537 0.10786384 0.24825922, 0.00417009 0.10780767 0.24809095, 0.0025979578 0.10770664 0.2479358, 0.0025828332 0.10776311 0.2481049, -0.0044231713 0.10866088 0.24794629, 0.00021912158 0.10782021 0.24833584, -0.0013330281 0.10800937 0.24796775, 0.0067666173 0.10830182 0.24901181, 0.0048725307 0.10795009 0.24870968, 0.009321481 0.10908043 0.24957103, 0.0049498677 0.10790116 0.24818942, -0.002145201 0.10799915 0.24766013, -0.0044629574 0.1085752 0.247794, 0.00022564828 0.10784298 0.24815828, 0.004197076 0.10771543 0.2479398, -0.0013434738 0.10795429 0.2477977, 0.0067930371 0.10832611 0.2488361, 0.009355709 0.10910708 0.24939725, 0.0013868958 0.1077573 0.24838194, -0.0021723062 0.10787761 0.24753141, 0.004982993 0.10780945 0.24803913, -0.0045098066 0.10845858 0.24766639, 0.0042243898 0.10759145 0.24781352, 0.00022871792 0.10782564 0.24798012, 0.0068286657 0.10831127 0.24866128, 0.0094040334 0.10909608 0.24922508, -0.0013591051 0.10786319 0.24764442, 0.0013968199 0.10777998 0.24820471, 0.0050169975 0.10768655 0.2479136, 0.00022859871 0.10776949 0.24781001, 0.0068715662 0.10825816 0.2484957, 0.009463653 0.10904804 0.24906307, 0.0025542974 0.10775807 0.24845999, 0.0069195777 0.10816917 0.24834776, 0.0095317215 0.10896528 0.24891955, -0.0013793558 0.10774043 0.24751538, 0.0069701821 0.10804927 0.24822482, 0.0096050352 0.10885206 0.24880126, 0.0014057755 0.1077624 0.24802646, 0.00022505224 0.10767698 0.24765646, 0.0025680363 0.10778061 0.24828288, 0.00141339 0.10770568 0.2478568, 0.00021833181 0.10755259 0.24752772, -0.0043658912 0.10869864 0.24846989, -0.0043734908 0.10872415 0.24829331, 0.0041037947 0.10785797 0.24861264, -0.024456203 0.11735967 0.27085584, -0.024304569 0.11748582 0.27092442, -0.02409251 0.11757413 0.2710036, -0.024965614 0.11674657 0.2720046, -0.025257856 0.11623895 0.27322656, -0.024904549 0.11689803 0.27207127, -0.025199696 0.11638504 0.27331224, -0.024809957 0.11702958 0.27214, -0.025106162 0.11651269 0.27339646, -0.024981841 0.11661503 0.27347454, -0.024656057 0.11715466 0.27222174, -0.024833083 0.1166873 0.27354315, -0.024437919 0.11724031 0.27230704, -0.024666995 0.11672583 0.2735984, -0.022217363 0.11643514 0.26461074, -0.021914378 0.11604747 0.26390535, -0.022047997 0.11595991 0.26391593, -0.021741524 0.11612144 0.263917, -0.022452116 0.11653677 0.26497623, -0.022644594 0.11682537 0.26557079, -0.022324786 0.11701366 0.26561245, -0.022506446 0.1169292 0.26557958, -0.02275233 0.1168865 0.26579216, -0.022840351 0.11716187 0.26633063, -0.023088068 0.11717641 0.26670346, -0.023412421 0.11724192 0.26739222, -0.023315236 0.11736044 0.26740548, -0.022979543 0.11756653 0.26748857, -0.023172006 0.1174767 0.26743588, -0.023404866 0.11736283 0.26757705, -0.023476422 0.11753678 0.26811376, -0.021695212 0.11479139 0.26256588, -0.021598861 0.11485985 0.26252875, -0.023706704 0.11746344 0.26843306, -0.021468446 0.11492893 0.26250109, -0.02391465 0.11751804 0.26913175, -0.023732573 0.11753365 0.2686772, -0.023766816 0.11764136 0.26918128, -0.02356413 0.11773178 0.26924926, -0.021301955 0.11498803 0.26249328, -0.024038047 0.11748266 0.26941508, -0.024080724 0.11756524 0.26993802, -0.024312764 0.11741552 0.2702772, -0.024317101 0.11744913 0.27049071, 0.009677887 0.10887894 0.24881968, 0.0096077472 0.10899305 0.24893814, 0.0095420629 0.10907671 0.24908227, 0.0094844997 0.10912576 0.24924451, 0.009437874 0.10913742 0.24941686, 0.0094045699 0.10911119 0.24959067, -0.025661588 0.11320111 0.27930093, -0.025061309 0.11375934 0.27953085, -0.02559267 0.11523288 0.27523795, -0.02553384 0.11538148 0.27531913, -0.025439039 0.11551279 0.27539572, -0.025727645 0.11421788 0.27726817, -0.025313035 0.11562017 0.27546415, -0.025668457 0.11436874 0.27734455, -0.025602609 0.11335427 0.2793729, -0.025162175 0.11569843 0.27552077, -0.025573239 0.11450374 0.27741387, -0.025507569 0.11349311 0.27943435, -0.024993956 0.11574352 0.27556297, -0.025446489 0.11461619 0.27747214, -0.025381207 0.11361057 0.27948278, -0.02529493 0.11470038 0.27751699, -0.025229901 0.11370078 0.27951565, -0.025125742 0.11475223 0.27754578, 0.011716381 0.10897121 0.24946737, 0.011439726 0.10928583 0.25017548, 0.011039227 0.10905612 0.2491931, 0.010997832 0.10918468 0.24931175, 0.011685982 0.1090968 0.24958187, 0.01094678 0.10928214 0.24945432, 0.011640772 0.1091947 0.24971625, 0.010888726 0.10934347 0.24961346, 0.011582702 0.10926083 0.24986488, 0.010827109 0.10936508 0.24978065, 0.011514664 0.10929158 0.25002024, 0.01076445 0.10934627 0.24994805, 0.01044336 0.10931504 0.24941877, 0.010217041 0.1092785 0.24932733, 0.0099888593 0.10922626 0.24924037, -0.024152741 0.10831657 0.28426754, -0.023729265 0.10796574 0.28458747, -0.0242652 0.1089513 0.28403482, -0.024267808 0.10852057 0.28412363, -0.024046347 0.10782361 0.28442991, -0.023912027 0.10789284 0.28452197, -0.023476213 0.10616347 0.28495765, -0.023605034 0.1061174 0.28486636, -0.023303807 0.10621673 0.2850273, -0.0240082 0.10757697 0.2844862, -0.023222208 0.10438123 0.28498933, -0.023779571 0.1071426 0.28471103, -0.023097903 0.10440379 0.28507727, -0.022933766 0.10443467 0.28514752, -0.023785353 0.10673141 0.28472111, -0.023169801 0.10313281 0.28469819, -0.022994131 0.1019125 0.28446785, -0.023094103 0.10312894 0.28479686, -0.02287665 0.10188767 0.28458729, -0.023006082 0.10312903 0.28488168, -0.022736341 0.1018725 0.28468111, -0.022884384 0.10313433 0.28496489, -0.022724509 0.10314754 0.28503305, -0.022579551 0.10186785 0.2847445, -0.025401309 0.11338729 0.27981201, -0.025519371 0.11313972 0.27990821, -0.025466919 0.11320862 0.2799423, -0.025310233 0.11308077 0.28037715, -0.02493152 0.11270696 0.28117058, -0.025381401 0.11266708 0.2807335, -0.025397435 0.11234689 0.28097859, -0.025303602 0.11247125 0.28105685, -0.025150284 0.11259994 0.28112802, -0.025302842 0.11232379 0.28118822, -0.025101319 0.1120604 0.28169087, -0.025211856 0.1116142 0.28183785, -0.02506949 0.11106974 0.28235802, -0.025147185 0.11169639 0.281901, -0.025048316 0.11156955 0.28211972, -0.024828926 0.11128807 0.28252926, -0.024620876 0.11138937 0.28257951, -0.024976566 0.11117518 0.28244773, -0.02496922 0.11102536 0.28253564, -0.02473411 0.11065161 0.28298739, -0.0247574 0.11025923 0.28313515, -0.024634242 0.10952297 0.28349951, -0.024644375 0.11008063 0.28332907, -0.024205595 0.10978878 0.28374267, -0.024542212 0.10960603 0.28359565, -0.024401113 0.10969877 0.28368434, -0.024515793 0.1094017 0.28367993, 0.01149492 0.10927624 0.25019607, 0.011569187 0.10928097 0.25004134, 0.011636361 0.10924941 0.24988669, 0.011693284 0.1091834 0.24973908, 0.011737287 0.10908565 0.24960464, 0.011766464 0.10896069 0.24949056, -0.022597313 0.10032371 0.28430906, -0.022260591 0.10000455 0.28438881, -0.022375137 0.099987417 0.28435221, -0.022481129 0.099973381 0.28429958, -0.022597983 0.099960655 0.28421581, -0.019389048 0.093021184 0.28590384, -0.01928556 0.093135715 0.28594723, -0.022714227 0.09995234 0.2840921, -0.022742614 0.10128111 0.28448194, -0.019487962 0.092885405 0.28581855, -0.018071443 0.091516823 0.28682467, -0.020192355 0.094737649 0.28520963, -0.020299852 0.094667524 0.28519902, -0.020399198 0.09459424 0.28517002, -0.020507574 0.094503075 0.28511107, -0.020612955 0.094396025 0.28501067, -0.021087304 0.096347034 0.28465986, -0.021197647 0.09629342 0.28463659, -0.021299928 0.09623903 0.28459576, -0.021411777 0.096172601 0.28452429, -0.021522239 0.096096665 0.28441161, -0.021789119 0.098158866 0.28436306, -0.021901786 0.098123699 0.28433099, -0.022006303 0.098089367 0.2842817, -0.022121117 0.098050147 0.28420141, -0.02223511 0.098008096 0.2840803, -0.012397453 0.089070439 0.29011545, -0.011495858 0.089244455 0.29025373, -0.011570141 0.089123279 0.29035047, -0.011637405 0.088980705 0.29041803, -0.011694342 0.088822693 0.29045397, -0.011738256 0.088656813 0.29045621, -0.011767447 0.088490605 0.29042456, -0.012672022 0.089349538 0.28989443, -0.012708724 0.089275658 0.28992221, -0.013201907 0.08927229 0.28973514, -0.014144301 0.089297444 0.28926027, -0.013856605 0.089680225 0.2893301, -0.014077425 0.089512795 0.28929248, -0.013920486 0.089823484 0.28922808, -0.013997942 0.089690179 0.28927433, -0.014671057 0.089746982 0.28896612, -0.016175285 0.090680897 0.28802392, -0.016265079 0.090523362 0.28801933, -0.014859587 0.090076387 0.28878394, -0.014915317 0.089974672 0.28879949, -0.01779215 0.091923475 0.28691465, -0.015434086 0.090005338 0.28853381, -0.017883569 0.09181726 0.28691804, -0.015933841 0.090592146 0.28815511, -0.017981008 0.091680437 0.28689301, -0.015992716 0.090496063 0.28816304, -0.01634489 0.090333432 0.28796864, -0.017727196 0.091739684 0.28700954, -0.019189537 0.093225986 0.28596172, 0.02259624 0.11116663 0.2626265, 0.022259489 0.11103922 0.26232359, 0.022374004 0.11099941 0.26233158, 0.019388035 0.10806188 0.25582728, 0.019284502 0.10816547 0.25589281, 0.02248016 0.11094895 0.26235178, 0.022596791 0.1108743 0.26239213, 0.02271308 0.11077037 0.26245964, 0.022741243 0.11187941 0.26328877, 0.01948683 0.10791215 0.25576982, 0.018070415 0.10789597 0.25407133, 0.022992894 0.11224693 0.26380238, 0.022875503 0.11232769 0.26371083, 0.022735208 0.11239344 0.26364252, 0.022578448 0.11244139 0.26360068, 0.020191282 0.10853603 0.25761703, 0.020298809 0.10848555 0.25756744, 0.020398185 0.10841846 0.25752625, 0.020506456 0.10831636 0.25748858, 0.020611838 0.10817206 0.25746304, 0.021086276 0.10906193 0.25923443, 0.021196589 0.10901114 0.25920567, 0.021298632 0.10894579 0.25918642, 0.021410763 0.10884848 0.25917616, 0.021521211 0.10871306 0.25918308, 0.021787986 0.10991132 0.26086208, 0.021900728 0.10986423 0.26085344, 0.022005126 0.10980463 0.26085538, 0.022119969 0.10971659 0.26087219, 0.022234201 0.10959449 0.2609112, 0.012396365 0.10906121 0.25013992, 0.012671009 0.10905182 0.25049546, 0.012707621 0.10902962 0.25042, 0.013200834 0.10887799 0.25052944, 0.014143288 0.10851318 0.25083452, 0.013855591 0.10879862 0.25109902, 0.013919652 0.10880286 0.25127485, 0.013997048 0.10875997 0.25114033, 0.014076546 0.10866818 0.25098738, 0.014670044 0.10854742 0.25137064, 0.016174093 0.10835403 0.25268289, 0.014858484 0.10859954 0.25174356, 0.016264126 0.10825589 0.25255981, 0.014914423 0.10855094 0.25165263, 0.017791137 0.1082122 0.25434271, 0.015433013 0.10835674 0.25183663, 0.017882556 0.10815096 0.25425583, 0.015932813 0.10840568 0.25253329, 0.017980054 0.10804904 0.25416115, 0.015991569 0.10835451 0.25245175, 0.016343877 0.10810143 0.25243834, 0.017726094 0.10817769 0.2541388, 0.019188613 0.10823116 0.25595644, -0.01144059 0.089233845 0.2902737, -0.011515647 0.089112997 0.29037139, -0.01158376 0.088970065 0.29044005, -0.01164183 0.088811666 0.29047635, -0.011687115 0.08864522 0.29047874, -0.011717483 0.088478386 0.29044697, 0.024266496 0.1159358 0.26929605, 0.024263978 0.11612299 0.26969382, 0.024151534 0.11592871 0.26904601, 0.023728162 0.11597416 0.26857373, 0.02404505 0.11576301 0.26855448, 0.02391082 0.11587793 0.26855469, 0.023475051 0.11518908 0.26690957, 0.023603871 0.11508816 0.26692763, 0.023302674 0.11527666 0.2669104, 0.024007097 0.11565974 0.26832342, 0.023221076 0.11414513 0.26546454, 0.023778453 0.11557922 0.26784104, 0.023096859 0.11422896 0.26543012, 0.022932544 0.11430356 0.2654126, 0.023784161 0.11534056 0.26750579, 0.023168743 0.11316341 0.26464057, 0.023092821 0.11324015 0.26457825, 0.023005024 0.1133078 0.26452756, 0.022883207 0.11337769 0.26448163, 0.022723451 0.11344007 0.26445135, 0.025400102 0.1154058 0.2757763, 0.025506362 0.1151672 0.27608737, 0.025601342 0.11503479 0.27601334, 0.025379986 0.11527637 0.27615234, 0.025228739 0.11535665 0.27620491, 0.025060102 0.11540416 0.27624223, 0.025518194 0.11533436 0.27552021, 0.025660411 0.11488539 0.2759338, 0.025465652 0.11540288 0.2755551, 0.02530916 0.11567411 0.27519199, 0.024930283 0.11608461 0.27441689, 0.025380373 0.11571097 0.27464712, 0.025148883 0.11598626 0.27435678, 0.025396198 0.11571485 0.27424398, 0.025302455 0.11585221 0.27429625, 0.025301635 0.11586875 0.27409959, 0.025100112 0.11611274 0.27358732, 0.025210649 0.11596286 0.27314219, 0.025068313 0.11605242 0.27239481, 0.025146008 0.11606282 0.27317008, 0.025047109 0.11616164 0.27293772, 0.02497533 0.11618751 0.27242517, 0.024827644 0.11632052 0.27246657, 0.02461955 0.11642152 0.27251735, 0.024967894 0.11616796 0.27225259, 0.024732888 0.11630526 0.27168271, 0.024756208 0.11618814 0.27128014, 0.024633065 0.11603776 0.27047211, 0.024643183 0.11623594 0.27102098, 0.024204403 0.11639187 0.27053913, 0.024541035 0.11616451 0.27048126, 0.024399877 0.11629108 0.27050203, 0.024514586 0.11610934 0.27026689, -0.0096789449 0.087904721 0.29076159, -0.0094055086 0.088661283 0.29048494, -0.0110403 0.088309884 0.29067943, -0.010998741 0.088481754 0.29071102, -0.010947749 0.088654429 0.29070359, -0.010889828 0.088818371 0.29065704, -0.010828078 0.088965237 0.29057372, -0.010765493 0.089087993 0.29045865, -0.010444343 0.088645607 0.29075125, -0.010218024 0.088550597 0.29077664, -0.0099898279 0.088449687 0.29078707, -0.0094389617 0.088537663 0.29061005, -0.009485513 0.088392764 0.29070413, -0.0095430315 0.08823359 0.29076228, -0.0096087009 0.088068247 0.29078171, 0.025124595 0.11441129 0.27822778, 0.024992868 0.11341974 0.28021035, 0.025160939 0.11335906 0.28019941, 0.025591463 0.11285362 0.27999672, 0.025256574 0.11184767 0.28200832, 0.025532663 0.11300749 0.28006688, 0.025198519 0.11200392 0.28207383, 0.025437802 0.11314765 0.28012595, 0.025104925 0.11214778 0.28212541, 0.025726423 0.11386877 0.27796659, 0.025311694 0.11326692 0.28017095, 0.024980739 0.11227173 0.28216055, 0.025667176 0.11402038 0.27804139, 0.024831757 0.11237004 0.28217748, 0.025571957 0.11415678 0.27810797, 0.024665713 0.11243737 0.28217492, 0.025445327 0.11427078 0.27816272, 0.025293574 0.1143572 0.27820358, -0.0096057951 0.087874055 0.29075125, -0.0095326751 0.088036418 0.29077092, -0.0094646215 0.088200986 0.29075083, -0.009405002 0.088359356 0.29069227, -0.0093568563 0.088503748 0.29059774, -0.00932239 0.088626742 0.29047212, 0.02445507 0.11062318 0.28432706, 0.024303451 0.11075374 0.2843872, 0.021462515 0.1007306 0.28683153, 0.021331832 0.1007123 0.28693777, 0.021181762 0.10070506 0.28701612, 0.021018997 0.10070881 0.28706276, 0.024091259 0.11087018 0.28441009, 0.024964482 0.11117467 0.28314742, 0.024903283 0.1113188 0.28322878, 0.02480875 0.11145267 0.2832931, 0.024654895 0.11159322 0.28334388, 0.024436772 0.11171266 0.28336111, 0.022216171 0.1050722 0.28733394, 0.021913081 0.10427511 0.28744701, 0.022046745 0.10423118 0.28737065, 0.021740377 0.10432899 0.28749943, 0.022450924 0.10542548 0.2871961, 0.022643417 0.1060743 0.28707042, 0.022505313 0.10614377 0.28714839, 0.022323683 0.10622066 0.28719595, 0.022751212 0.10628811 0.28698674, 0.022839293 0.10688406 0.28688386, 0.023086905 0.10719106 0.28667158, 0.023411289 0.10778147 0.28631091, 0.023314074 0.10786304 0.28639755, 0.0229785 0.10805315 0.28651282, 0.023170769 0.10795701 0.28647265, 0.023403749 0.10800174 0.2862967, 0.02347514 0.1085355 0.28611395, 0.021694005 0.10244989 0.28724578, 0.023705646 0.10874721 0.28586367, 0.021597654 0.10246137 0.28732273, 0.023913354 0.10933879 0.28548822, 0.021467358 0.10248059 0.28739461, 0.023731351 0.10898456 0.28577313, 0.023765653 0.10945261 0.28555712, 0.023562983 0.1095612 0.28558871, 0.021300763 0.10250983 0.28744635, 0.024036855 0.10954428 0.28528991, 0.024079591 0.1100125 0.28504223, 0.024311543 0.11019379 0.28471908, 0.024315894 0.11038488 0.28461778, 0.0021069497 0.086794764 0.29067472, 0.0043918937 0.087241054 0.29105005, 0.0043725222 0.087390929 0.29095367, 0.0020986348 0.086946696 0.2905806, -0.0041457266 0.086847514 0.29028592, -0.002583757 0.086663991 0.29029772, -0.0025689751 0.086816519 0.29020512, -0.0041231811 0.086999238 0.29019311, 0.0013276488 0.08685419 0.29048291, 0.002098009 0.087074459 0.29045513, 0.0013293624 0.086982429 0.2903578, -0.002627492 0.08613947 0.29034761, -0.0014234632 0.086074799 0.29039511, -0.0014199764 0.086252421 0.29041788, -0.0026137531 0.086316615 0.29037067, 0.0021223873 0.086626112 0.29073343, 0.0044223368 0.087075442 0.29111114, -0.0049205273 0.086981416 0.29030105, -0.0048943162 0.087132603 0.29020849, 0.0013320297 0.08670184 0.29057702, -0.0041711032 0.08667931 0.29034176, -0.0025989562 0.086494267 0.29035401, -0.00022011995 0.086882681 0.29020497, -0.0067675263 0.087712467 0.29018474, -0.004873544 0.087259769 0.29008439, 0.002144143 0.086449295 0.29075333, 0.0044617057 0.086902231 0.29113379, -0.0049509853 0.086814016 0.29035744, 0.001342386 0.086532593 0.29063484, -0.0041981488 0.08650288 0.29035857, 0.006758973 0.08743906 0.29162133, -0.00022657216 0.086754411 0.29032949, -0.0067940354 0.087586612 0.29030934, -0.00138776 0.086882055 0.29012689, 0.0021711439 0.086273372 0.29073343, 0.004508689 0.086730123 0.29111701, -0.0049839467 0.086638778 0.29037431, -0.0042254031 0.086327463 0.29033527, 0.0013580769 0.086355269 0.29065403, -0.0068297088 0.087437719 0.29040262, -0.00022980571 0.086601436 0.29042277, -0.0013978034 0.086753726 0.2902514, -0.0050180852 0.086464405 0.29035103, 0.0013784915 0.086178541 0.29063314, -0.0068725944 0.08727321 0.29045928, -0.0002297014 0.086431414 0.2904799, -0.0069205463 0.087101668 0.29047701, -0.0025553405 0.086944729 0.29008067, -0.00697124 0.086931199 0.29045475, -0.0014068037 0.086600572 0.29034433, -0.00022616982 0.086253196 0.29049757, -0.0014143437 0.086430728 0.29040071, 0.0043649226 0.087517411 0.29082701, 0.0065469146 0.08820489 0.29131585, -0.00021931529 0.086075634 0.29047552, 0.0065612346 0.088080585 0.29144391, 0.006591484 0.087934077 0.2915428, -0.0041048676 0.087126911 0.29006886, 0.0066360682 0.087773055 0.29160693, 0.006692946 0.087605178 0.2916337, 0.011610225 0.08865121 0.29057875, 0.011551023 0.088868916 0.2906051, 0.019578576 0.095363677 0.2867209, 0.019475117 0.095421314 0.28675196, 0.013884619 0.089534491 0.28957143, 0.013809949 0.089728206 0.28961387, 0.021190792 0.1001986 0.28683841, 0.019694582 0.095294416 0.28666016, 0.02047202 0.097062677 0.28645727, 0.019812927 0.095216483 0.28655854, 0.021028414 0.099291891 0.28664735, 0.020887792 0.098902613 0.28661481, 0.021011904 0.098884612 0.28654382, 0.020777404 0.098921448 0.28665569, 0.020596296 0.097016931 0.28634867, 0.021140248 0.098871261 0.28643331, 0.018342599 0.093874067 0.28719494, 0.010234132 0.088367045 0.29111767, 0.018447354 0.093799919 0.28719428, 0.011346251 0.089306146 0.29044682, 0.011417419 0.089185923 0.2905269, 0.011482716 0.089049429 0.29058, 0.018545821 0.093723267 0.28717431, 0.009480834 0.088637561 0.29126847, 0.0089725256 0.087939382 0.29152718, 0.008949101 0.0881069 0.29155609, 0.0089144707 0.088274926 0.29154953, 0.0088701397 0.08843562 0.29150844, 0.0088180602 0.088581324 0.29143426, 0.0087609738 0.088705808 0.29133072, 0.018655494 0.093628675 0.28712532, 0.018765807 0.093519419 0.28703508, 0.017066672 0.092444807 0.28782329, 0.017165333 0.092355639 0.28783849, 0.01725781 0.092261434 0.28783277, 0.017359808 0.092143178 0.28779918, 0.01746048 0.092003942 0.28772351, 0.015473351 0.091178089 0.28862253, 0.015564591 0.091075569 0.28865704, 0.015649766 0.090965122 0.28866938, 0.015742198 0.090824038 0.28865394, 0.015830934 0.090656489 0.28859422, 0.013570264 0.090127796 0.28952059, 0.013652414 0.090014875 0.28957742, 0.013728544 0.089890212 0.28960934, 0.020129964 0.097184479 0.286585, 0.020243764 0.097144485 0.28656411, 0.020351142 0.097106278 0.28652593, 0.01936534 0.095478714 0.28676483, 0.0068319291 0.087465972 0.29163969, 0.0067686886 0.087632924 0.29165259, 0.0067144781 0.087801546 0.29162672, 0.00667198 0.087963283 0.29156312, 0.0066433698 0.088110238 0.29146528, 0.0066299886 0.088234961 0.29133746, 0.0087034851 0.088698268 0.29134485, 0.0087611526 0.088573933 0.29144952, 0.0088139623 0.088427901 0.29152468, 0.008859396 0.08826673 0.29156634, 0.0088952184 0.088098019 0.29157314, 0.00891985 0.087929815 0.2915442, 0.0075245649 0.087649971 0.2917341, 0.0074751526 0.087823391 0.29175708, 0.0074276477 0.08799848 0.29173854, 0.0073843598 0.088165522 0.29167971, 0.0073480159 0.088315487 0.29158357, 0.0073201358 0.088441133 0.29145524, 0.007889539 0.0881598 0.29172549, 0.0081223547 0.088233292 0.29169628, 0.0083577782 0.088302821 0.29165217, -0.023469612 0.11328208 0.27966562, -0.023400933 0.11323479 0.27923375, -0.023459971 0.11338395 0.27931347, -0.021073192 0.10305396 0.28481078, -0.02120623 0.10301352 0.28493056, -0.021081835 0.10194203 0.28468105, -0.023681298 0.11362523 0.2794534, -0.023782834 0.11335436 0.2801657, -0.020958081 0.10310173 0.28463605, -0.020845428 0.10204279 0.28441533, -0.020782262 0.10209787 0.2842494, -0.021133393 0.10415334 0.28476396, -0.021248147 0.10412049 0.28493747, -0.023351565 0.11291176 0.28002629, -0.020890385 0.10315213 0.28440794, -0.020761102 0.10215223 0.28407267, -0.021062627 0.1041815 0.28453782, -0.023367167 0.11279303 0.28046665, -0.023342058 0.11251175 0.28099415, -0.02324751 0.11239618 0.28088626, -0.020893976 0.10319275 0.28417575, -0.020782992 0.10220265 0.28389508, -0.023191154 0.1122632 0.28077206, -0.021060154 0.10419726 0.28430656, -0.02345185 0.11259341 0.28107885, -0.02206254 0.10826111 0.28389016, -0.022402361 0.10888225 0.28401551, -0.021894202 0.10768348 0.28391469, -0.024001077 0.11375237 0.27954447, -0.02211827 0.10779861 0.28446648, -0.022005171 0.10778129 0.28431436, -0.023832589 0.1137054 0.27950633, -0.022423461 0.10849217 0.28431389, -0.021922335 0.10774109 0.28411785, -0.02196075 0.10727915 0.28460184, -0.022381261 0.10778728 0.28465918, -0.022240296 0.10779947 0.28457525, -0.023482278 0.11233509 0.28152084, -0.02213037 0.10671669 0.28495607, -0.023688421 0.11268312 0.28119385, -0.0218907 0.10727364 0.28450808, -0.023562878 0.11264661 0.28114167, -0.023274124 0.1119594 0.28179511, -0.021701872 0.106837 0.28445771, -0.022907063 0.11112809 0.28222403, -0.022856787 0.11101499 0.28207818, -0.021439284 0.10594979 0.28427508, -0.021724015 0.10636616 0.28480029, -0.021919459 0.10593185 0.28508013, -0.021771535 0.10595727 0.28499326, -0.023311689 0.11167222 0.28222802, -0.023224115 0.11132565 0.2825537, -0.02311039 0.11128756 0.28247294, -0.022999391 0.11122346 0.2823635, -0.021645248 0.10597396 0.28487763, -0.021653488 0.10636795 0.28470266, -0.021454394 0.10597354 0.28449667, -0.023213744 0.11102113 0.28286585, -0.02153118 0.10598141 0.2847119, -0.02143997 0.10562012 0.28474051, -0.023131102 0.11100671 0.28281823, -0.021669969 0.10520381 0.28510466, -0.021274507 0.10514036 0.28462338, -0.022882447 0.11054605 0.2830402, -0.022407413 0.10946617 0.28315529, -0.021237925 0.10470748 0.28477547, -0.021700993 0.10480827 0.28517011, -0.022987604 0.11020219 0.28346524, -0.022766143 0.10968766 0.28373057, -0.02130273 0.10450038 0.28493324, -0.021533698 0.10405338 0.28514299, -0.021379068 0.10408801 0.28505662, -0.022903174 0.11019337 0.28341368, -0.022536606 0.10962498 0.28350142, -0.022448108 0.10955453 0.28333178, -0.022648662 0.10966733 0.28363398, -0.023665324 0.11297661 0.28071699, -0.022772774 0.1094332 0.28392404, -0.022686765 0.10942954 0.28386948, -0.022511467 0.10849014 0.2843712, -0.021538779 0.10294169 0.28506356, -0.021419778 0.10187125 0.28481269, -0.021364003 0.10297537 0.28501621, -0.021242246 0.10190168 0.28476602, -0.020947143 0.10198987 0.28456184, -0.023555011 0.11351636 0.27938798, -0.020967379 0.10010669 0.28439781, -0.020921648 0.099134594 0.28438604, -0.020749241 0.099177927 0.28433335, -0.020593584 0.099218011 0.28424078, -0.02080965 0.10014647 0.28430828, -0.020577669 0.10029832 0.28331849, -0.020506412 0.10028842 0.28353539, -0.020463109 0.099252373 0.28411409, -0.020677119 0.10018539 0.28418437, -0.02035144 0.09928295 0.283932, -0.020564064 0.10022631 0.28400472, -0.020287365 0.099302799 0.28369781, -0.020499527 0.10026407 0.28377229, -0.020293936 0.099305272 0.28346032, -0.019770578 0.097556949 0.28354192, -0.019054383 0.0958893 0.28388414, -0.018098146 0.094302744 0.28447333, -0.016867444 0.092846811 0.28528011, -0.01532197 0.091557145 0.2862626, -0.013490334 0.090495616 0.28732327, -0.021107569 0.10123491 0.28456432, -0.020946011 0.10033983 0.28439435, -0.02016364 0.098845959 0.28365549, -0.020067707 0.098422527 0.28382635, -0.019901931 0.097987562 0.28369662, -0.019829124 0.09760344 0.28400871, -0.019766226 0.097592503 0.28377539, -0.019569814 0.097087324 0.28381306, -0.019434959 0.096725971 0.28404191, -0.019208863 0.096270084 0.28398594, -0.019115731 0.095996857 0.28433445, -0.019053772 0.095958591 0.28410706, -0.01876232 0.095420003 0.284237, -0.018279865 0.094646871 0.28453285, -0.018163934 0.094461232 0.28489748, -0.018103153 0.094399899 0.28468052, -0.017723113 0.093908042 0.2849749, -0.017710194 0.093875915 0.2848973, -0.017507479 0.093641967 0.28531602, -0.017100632 0.093200862 0.28537551, -0.017026067 0.093073159 0.28584841, -0.01693821 0.093042642 0.28567231, -0.016878992 0.092964023 0.28546908, -0.017087117 0.093165547 0.28530118, -0.016373351 0.092480838 0.28575927, -0.016387269 0.092518896 0.28583065, -0.016100615 0.092299789 0.28619903, -0.015608996 0.091894627 0.28631449, -0.015473947 0.09181574 0.28679067, -0.01539591 0.091775775 0.2866216, -0.015339717 0.0916861 0.28643265, -0.015594736 0.091854692 0.28624597, -0.014731124 0.09130761 0.28683755, -0.014383093 0.09114781 0.28720993, -0.013875276 0.090714425 0.28820953, -0.013784453 0.090762138 0.28808561, -0.013702273 0.090780467 0.28795215, -0.013805807 0.090793282 0.28735957, -0.013630822 0.090770394 0.28781402, -0.013563901 0.090723962 0.28765234, -0.013512224 0.090628892 0.28747725, -0.013149753 0.090511471 0.28778633, -0.013130873 0.090472609 0.28771946, -0.012629107 0.090338767 0.28829286, -0.012037635 0.090049326 0.28829855, -0.011275232 0.089627951 0.28842756, -0.011298329 0.089760482 0.28856868, -0.012064263 0.090096682 0.28838748, -0.011867777 0.090056568 0.28862187, -0.011342794 0.089856893 0.28873193, -0.01140599 0.089911699 0.28890768, -0.011484146 0.089921534 0.28908563, -0.011572897 0.089886039 0.28925529, -0.020838156 0.10168189 0.28436857, -0.020790279 0.10171029 0.28427914, -0.020677581 0.10125551 0.28400812, -0.020672232 0.10079166 0.28409973, -0.020652384 0.098897219 0.28432128, -0.020431668 0.098800987 0.28420067, -0.020518661 0.098778814 0.28426901, -0.020545721 0.098322958 0.28436548, -0.020252123 0.097951442 0.28431273, -0.020378813 0.097472548 0.28448471, -0.020212799 0.097523898 0.28442332, -0.020062938 0.097564042 0.28432432, -0.020166636 0.097972482 0.28424275, -0.019937113 0.097590834 0.28419313, -0.020079181 0.097240686 0.28445646, -0.019847065 0.097142041 0.28435081, -0.019930512 0.097122431 0.28442267, -0.01990521 0.096689284 0.28458855, -0.019565329 0.096331865 0.28459075, -0.019635513 0.095883936 0.28483418, -0.019478947 0.095941752 0.28476089, -0.019337684 0.095981449 0.28465375, -0.019484356 0.096350521 0.28451714, -0.019218564 0.096000701 0.28451851, -0.019101754 0.095738351 0.28463048, -0.019043282 0.095741838 0.28454658, -0.018960819 0.095282495 0.28490451, -0.018630207 0.094970316 0.28490314, -0.018643469 0.094369143 0.28542039, -0.018499717 0.094430387 0.28533295, -0.018321216 0.094604254 0.28497264, -0.018369973 0.094467729 0.28521699, -0.018260196 0.094479591 0.28507867, -0.018120348 0.094036043 0.28549334, -0.017488807 0.093340069 0.28588501, -0.017367512 0.092975378 0.28621444, -0.017239913 0.093035996 0.28611287, -0.017124504 0.093068957 0.28598875, -0.01682128 0.092841923 0.28607324, -0.016773313 0.09267503 0.28632522, -0.015982747 0.092057109 0.2867997, -0.015559182 0.091819048 0.28693077, -0.015767813 0.091737419 0.28717539, -0.015658394 0.091793001 0.28706095, -0.015204579 0.091619045 0.28703848, -0.015110925 0.091486543 0.28730217, -0.021002337 0.10061789 0.2844393, -0.018450499 0.094908953 0.28444651, -0.0230221 0.11608568 0.2735329, -0.023940414 0.11570847 0.27563301, -0.023612559 0.11667651 0.27369723, -0.023446664 0.11660886 0.27370024, -0.023772284 0.1156477 0.27562246, -0.023621351 0.1155552 0.27559409, -0.023297802 0.11651048 0.27368382, -0.023173586 0.11638606 0.27364945, -0.024070188 0.11473107 0.27758738, -0.023495376 0.11543596 0.2755492, -0.02390115 0.1146771 0.27756304, -0.02340059 0.1152958 0.27549025, -0.023080111 0.11624202 0.27359802, -0.023749426 0.11459094 0.2775223, -0.023341745 0.11514184 0.27542034, -0.023622811 0.11447683 0.27746734, -0.023527533 0.11434057 0.27740058, -0.02346842 0.11418894 0.2773256, -0.011498615 0.089866281 0.28928041, -0.011411756 0.089900225 0.28911117, -0.011335358 0.089889228 0.2889336, -0.011273995 0.089833975 0.28875867, -0.011231571 0.089737982 0.28859639, -0.011209965 0.089606464 0.28845617, -0.021151662 0.1171163 0.26626664, -0.021024019 0.11702248 0.26617116, -0.021154359 0.11708972 0.2660968, -0.023282215 0.11706898 0.27271521, -0.023415893 0.11711779 0.2726987, -0.022034079 0.11699378 0.27004454, -0.021263212 0.11723331 0.26693645, -0.022549525 0.11676079 0.27169237, -0.023161173 0.11700118 0.27272111, -0.021582901 0.11743233 0.26721808, -0.02200754 0.11762649 0.26802659, -0.022898018 0.11731029 0.27172744, -0.021867156 0.1175817 0.2680845, -0.023054466 0.11691678 0.27271739, -0.021510288 0.11739963 0.26725295, -0.02279152 0.11722177 0.27173635, -0.019328043 0.11342993 0.26205048, -0.019342616 0.11335143 0.26180151, -0.019425139 0.11344168 0.2616615, -0.019300357 0.1132488 0.26195073, -0.02294907 0.11679956 0.27270189, -0.022687539 0.11709821 0.27173588, -0.019300938 0.11313942 0.26210126, -0.019343942 0.11302942 0.26224482, -0.019528896 0.1138142 0.26185474, -0.01939863 0.1137338 0.26211497, -0.01965116 0.11402607 0.26190373, -0.019622475 0.11430863 0.26228443, -0.022858143 0.11664584 0.27266875, -0.022599518 0.11693618 0.27172133, -0.019370198 0.11368006 0.26225212, -0.022803485 0.11647946 0.2726216, -0.019361496 0.11361101 0.26233944, -0.019793734 0.11407194 0.26181445, -0.019861653 0.11359543 0.26136759, -0.019691885 0.11356708 0.26143846, -0.01944761 0.11384943 0.2627565, -0.019523039 0.11431447 0.26296064, -0.019876227 0.11477053 0.26252308, -0.019749746 0.11489692 0.26295024, -0.019612253 0.11460885 0.26326245, -0.019636676 0.11443633 0.26341686, -0.019543797 0.11351493 0.26153818, -0.019656152 0.11477399 0.26309451, -0.021741733 0.11750984 0.26814079, -0.019726664 0.11498734 0.26344576, -0.020006657 0.11519045 0.26297143, -0.020021528 0.11548609 0.26348916, -0.02163434 0.1174145 0.26819381, -0.019721225 0.11405227 0.26185551, -0.019705653 0.11489263 0.26353469, -0.0198313 0.11506927 0.26401323, -0.019975454 0.11556607 0.26418027, -0.02024807 0.1157935 0.26372665, -0.020366535 0.11614293 0.26436219, -0.020253882 0.11605442 0.26445901, -0.020158559 0.11592111 0.26457754, -0.0201056 0.11574143 0.26471004, -0.022486463 0.11765373 0.26992759, -0.019951642 0.11546704 0.26425877, -0.019865781 0.11497879 0.26283827, -0.020114049 0.1155507 0.26482713, -0.020009011 0.11503443 0.26274231, -0.020229593 0.11596337 0.26502413, -0.02050215 0.11628026 0.26446751, -0.020579249 0.11651191 0.26508453, -0.022363856 0.11758074 0.26996461, -0.022257492 0.11748734 0.26999542, -0.022155583 0.11735535 0.27002245, -0.021534786 0.11727756 0.26824993, -0.020633504 0.11661783 0.26567185, -0.020823106 0.11675277 0.26536468, -0.020389855 0.11606863 0.26555514, -0.022073939 0.11718145 0.27004066, -0.020328045 0.11581957 0.26367974, -0.021461025 0.11709538 0.26830304, -0.020553112 0.11640543 0.26588196, -0.020743936 0.11640787 0.26650646, -0.021434158 0.1168994 0.26834121, -0.020503387 0.11620414 0.26427418, -0.02067773 0.11664683 0.26596346, -0.020914406 0.11692899 0.26624775, -0.020817325 0.11679107 0.26633611, -0.020753726 0.11660603 0.2664291, -0.02301906 0.1173811 0.27170977, -0.020892873 0.11675316 0.26677218, -0.021062925 0.11676025 0.26732382, -0.021249056 0.11701021 0.26771113, -0.020899057 0.11678201 0.26532206, -0.021384031 0.11721137 0.2678352, -0.009311378 0.089129418 0.28952274, -0.0094738007 0.088913232 0.28873351, -0.010772511 0.089665532 0.28946945, -0.010716677 0.089690328 0.28929713, -0.010672435 0.089675039 0.2891196, -0.010642394 0.08962065 0.28894761, -0.010628089 0.089530528 0.28879002, -0.010630012 0.089408547 0.28865382, -0.010225713 0.089507103 0.28912815, -0.010003999 0.089413762 0.2891157, -0.0097860992 0.089314461 0.28909212, -0.0094139427 0.089018762 0.2888602, -0.0093659014 0.08909595 0.28900972, -0.0093318075 0.089141369 0.28917554, -0.0093132704 0.089152634 0.28934923, -0.01129435 0.1091235 0.25134838, -0.013182357 0.1089299 0.25264367, -0.014877364 0.10899788 0.25398961, -0.017359018 0.10973033 0.25678474, -0.018866152 0.11131492 0.2594552, -0.018752441 0.1112262 0.25957081, -0.01865612 0.11071774 0.26000714, -0.019596934 0.11240888 0.26037744, -0.019429967 0.11238313 0.26045474, -0.019284159 0.11232814 0.26055595, -0.019167379 0.11224693 0.26067546, -0.019075915 0.11212507 0.26082885, -0.01866281 0.11109114 0.25971273, -0.019038379 0.11196283 0.26100788, -0.018625036 0.11090934 0.25987038, -0.019072041 0.11179376 0.26117203, -0.0093268901 0.10897896 0.2507104, -0.0088506639 0.10913792 0.25046045, -0.0089100599 0.10928991 0.25035438, -0.0088036656 0.10896143 0.25052816, -0.0087716281 0.10877094 0.25055292, -0.008756578 0.10857782 0.25053343, -0.0096491724 0.10915738 0.2507064, -0.0089782476 0.1094085 0.25021565, -0.0096155852 0.10907462 0.25076079, -0.010090068 0.1088376 0.25107542, -0.011070073 0.10834017 0.25161901, -0.01081343 0.10905167 0.25124237, -0.011228219 0.10902366 0.25145081, -0.010775 0.10896933 0.25129989, -0.010868594 0.10883623 0.25142962, -0.011120036 0.10874358 0.25159818, -0.011082456 0.10854405 0.25163171, -0.011171624 0.1089035 0.25153226, -0.011578888 0.10906407 0.25155851, -0.011535779 0.10899672 0.25162292, -0.012025744 0.10882246 0.25204, -0.013004601 0.10822788 0.25285426, -0.012519762 0.10894275 0.25220758, -0.013112992 0.10881141 0.25273275, -0.013011396 0.10844153 0.25285497, -0.013051882 0.10864863 0.25280914, -0.013560861 0.10898802 0.25281447, -0.013507381 0.1089243 0.25288293, -0.013893992 0.10879543 0.25334403, -0.014686197 0.10828626 0.25425562, -0.014362797 0.10895121 0.25355151, -0.01479575 0.10888311 0.25408617, -0.014725983 0.10871959 0.25417468, -0.014684722 0.10850739 0.25423744, -0.015243739 0.10909006 0.25420639, -0.015180275 0.10903102 0.25427723, -0.015455291 0.10895765 0.25475317, -0.015943974 0.10921437 0.25490391, -0.016261801 0.10926217 0.25539091, -0.01587595 0.1091578 0.25497529, -0.01616919 0.10915253 0.25549391, -0.01609242 0.10899147 0.25559542, -0.016612738 0.10940415 0.25565428, -0.017166898 0.10963491 0.25635293, -0.017700344 0.10994703 0.25710914, -0.017257363 0.10962674 0.25689247, -0.017799944 0.11003166 0.2575337, -0.018129215 0.11028984 0.25779286, -0.01821889 0.11041269 0.25815082, -0.018110096 0.11031619 0.25826278, -0.01853554 0.11072767 0.25852472, -0.018565655 0.11086032 0.25891605, -0.018854141 0.1111882 0.2591776, -0.015022188 0.1085012 0.25457495, -0.015707582 0.10863367 0.25529775, -0.016062602 0.10855418 0.25572237, -0.01605165 0.10877809 0.2556791, -0.016234338 0.10904026 0.25576022, -0.016530856 0.10925579 0.25596717, -0.016518876 0.10914558 0.25611135, -0.017154977 0.10904226 0.25718781, -0.017047957 0.10939926 0.25682089, -0.017175049 0.10947126 0.25700787, -0.017135561 0.10926244 0.25711545, -0.017297849 0.10930917 0.257386, -0.017378151 0.10944664 0.25747374, -0.01759921 0.10945439 0.25789157, -0.017801389 0.10980135 0.25817713, -0.01802364 0.11016944 0.25839171, -0.017864004 0.10978425 0.25833127, -0.017985165 0.10997108 0.25852409, -0.018011481 0.10976154 0.25862893, -0.018199354 0.11033869 0.25881162, -0.01811865 0.11006969 0.25880978, -0.018182158 0.11022744 0.25888929, -0.01835148 0.11029941 0.25931016, -0.018500417 0.1107004 0.25956288, -0.018544257 0.1107026 0.25971487, -0.0088498294 0.088926405 0.28947026, -0.0088627934 0.088953674 0.28929403, -0.0088911951 0.088944107 0.28911731, -0.0089330077 0.088897556 0.28894928, -0.0089865476 0.088816732 0.28879866, -0.0090490133 0.088705748 0.28867278, -0.0089007467 0.10941276 0.25019294, -0.0088341534 0.10929343 0.25032994, -0.0087766051 0.10914144 0.25043467, -0.0087314397 0.10896558 0.25050095, -0.0087011158 0.10877603 0.25052539, -0.0086878091 0.10858428 0.25050616, -0.0012893677 0.087083876 0.28837737, 0.0013601631 0.087172538 0.28859773, 0.0012622029 0.087462395 0.28922102, 0.0038273185 0.087841749 0.28941154, 0.0012838691 0.087445259 0.28904411, 0.0037931055 0.087856948 0.28958657, -0.0012928843 0.087208629 0.28850582, 0.0013341904 0.087296635 0.28872451, 0.0064703226 0.088293284 0.28949806, 0.0012442172 0.087439477 0.28939787, 0.0037675351 0.087832808 0.28976241, -0.0012985617 0.08730188 0.28865883, 0.0013082772 0.087389171 0.28887573, -0.0013060123 0.087358624 0.2888287, -0.0039389133 0.087313533 0.28831625, 0.0061996132 0.088526309 0.29027089, -0.0013150424 0.087376148 0.28900668, -0.0039197952 0.087436259 0.28844517, -0.0013251007 0.087353408 0.28918406, -0.0039052814 0.087527752 0.28859878, -0.0038960129 0.087583035 0.28876874, -0.0065410137 0.087857336 0.28841528, -0.0038922876 0.087599277 0.28894714, -0.0064998269 0.087975562 0.28854331, -0.0038944334 0.087576151 0.2891247, -0.0064653754 0.088062823 0.2886959, -0.0064395368 0.088114649 0.28886551, 0.0039623231 0.087578148 0.28897381, 0.0039140582 0.087698758 0.28909707, 0.0064008832 0.088407665 0.28961697, -0.0064233243 0.088128418 0.2890434, 0.0038682669 0.087788135 0.28924552, 0.006336078 0.088491619 0.28976145, 0.0062788874 0.088540763 0.28992385, -0.0064177066 0.088103503 0.28922078, 0.006232813 0.088552415 0.29009661, -0.0066640526 0.10904685 0.24969319, -0.0068975985 0.10829657 0.24997276, -0.0074036866 0.10928905 0.2498377, -0.0073972642 0.10916194 0.24996063, -0.006685555 0.10892257 0.24981472, -0.0074028522 0.10901192 0.25005421, -0.0067218542 0.10877827 0.24990708, -0.0074196756 0.10884714 0.2501134, -0.0067708492 0.10862085 0.24996573, -0.0074472874 0.10867533 0.25013617, -0.0068303645 0.10845757 0.24998793, -0.0074843913 0.10850313 0.25012138, -0.0077537 0.10924467 0.25003052, -0.0078567564 0.10898808 0.25020891, -0.0080806315 0.10904133 0.25025991, -0.0083128661 0.10908449 0.25031576, 0.0066630542 0.088704705 0.29037222, 0.0066846758 0.088727444 0.29019988, 0.0067209005 0.088714659 0.2900289, 0.0067698509 0.088667065 0.28986761, 0.0068295449 0.088586926 0.28972378, 0.0068966448 0.088477999 0.28960404, -0.0062005967 0.1088587 0.2496112, -0.0062337816 0.1087352 0.24973646, -0.0062801093 0.10858992 0.24983087, -0.006336987 0.10843039 0.24988925, -0.006401822 0.10826463 0.2499086, -0.0064713806 0.10810074 0.24988842, 0.0088999122 0.089323938 0.29036486, 0.0086867511 0.089077532 0.2895143, 0.0074027479 0.088965595 0.29047915, 0.0073962808 0.088987708 0.29030377, 0.0074017495 0.088972449 0.29012761, 0.007418707 0.08892104 0.28996015, 0.0074462146 0.088836253 0.28980905, 0.0074832737 0.088721156 0.28968027, 0.007752791 0.089093268 0.29032812, 0.0078558028 0.089081973 0.2900157, 0.0080795139 0.089155018 0.29002777, 0.0083119422 0.089225203 0.29002878, 0.0087001622 0.089208126 0.28965607, 0.0087303668 0.089302301 0.28982222, 0.0087754875 0.089354604 0.29000288, 0.0088331252 0.089362115 0.29018745, -0.0012848526 0.10722899 0.24948218, -0.0038284361 0.10776073 0.24957901, -0.0038693845 0.10759565 0.24963558, 0.0012885034 0.10647869 0.24959299, -0.0013613105 0.1067085 0.24953184, -0.0012631118 0.10738081 0.24938974, -0.003794238 0.10790995 0.24948612, 0.0012918264 0.10665646 0.24961591, -0.0013350695 0.10688409 0.24955493, -0.0012452602 0.10750854 0.24926528, -0.0037686974 0.1080361 0.24936146, 0.0012975335 0.10683462 0.24959862, -0.0013092756 0.10706055 0.24953818, 0.0013050288 0.10700449 0.24954224, 0.0039378703 0.10656756 0.24981341, 0.0013141483 0.1071575 0.24944934, 0.0039188266 0.10674438 0.24983439, 0.0013240725 0.10728592 0.24932462, 0.0039043128 0.106922 0.24981543, 0.0038948506 0.10709134 0.24975762, 0.009048 0.10768819 0.25071356, 0.0065399557 0.10697308 0.25018913, 0.0089855492 0.10785565 0.25072679, 0.0038911402 0.1072439 0.24966377, 0.0064989179 0.1071465 0.25020692, 0.0038933605 0.10737202 0.2495386, 0.006464377 0.10732099 0.25018507, 0.0089319944 0.1080246 0.2507011, 0.0088899583 0.10818675 0.25063744, 0.0088487864 0.10845867 0.25041142, -0.0039632767 0.10725236 0.24963078, 0.0064385086 0.10748771 0.25012493, -0.0039152056 0.10742345 0.24965331, 0.0064222664 0.10763821 0.25002921, 0.0088617802 0.10833395 0.25053939, 0.0064166635 0.10776535 0.24990299, 0.008977294 0.089339733 0.2903479, 0.0089090914 0.089379489 0.29016986, 0.0088497698 0.089373231 0.28998449, 0.0088026375 0.089321405 0.28980282, 0.0087704957 0.089227051 0.28963563, 0.00875552 0.089095592 0.28949273, 0.0093102455 0.10862234 0.2505427, 0.0093121678 0.10849756 0.2506654, 0.0093307197 0.10835156 0.25076035, 0.009364903 0.10819176 0.25082353, 0.0094128996 0.10802591 0.2508516, 0.0094727874 0.10786152 0.25084296, 0.01934278 0.10113624 0.28602859, 0.011293247 0.090074956 0.28944024, 0.013181269 0.090995193 0.28850856, 0.014876306 0.092112839 0.28775546, 0.017358065 0.094788462 0.28666455, 0.018865064 0.097875267 0.28633055, 0.018751264 0.097914904 0.28618985, 0.018655241 0.097959131 0.28552148, 0.019595772 0.099269539 0.28665224, 0.019860491 0.10077387 0.28700757, 0.019428909 0.09931609 0.28658515, 0.019690692 0.10081363 0.28694257, 0.019283101 0.099364132 0.28648052, 0.019542634 0.10086203 0.28684109, 0.019166186 0.099411011 0.28634408, 0.019424021 0.10091659 0.28670827, 0.019341365 0.10097459 0.28655213, 0.019074842 0.09946084 0.28615442, 0.01929915 0.10103238 0.28638062, 0.018661797 0.097947717 0.28599659, 0.019037351 0.099506795 0.28591737, 0.019299716 0.10108721 0.28620276, 0.018624052 0.097964585 0.28575668, 0.019071072 0.099536687 0.2856836, 0.0093257129 0.089477897 0.28970757, 0.0096479803 0.089581758 0.28985229, 0.0096144974 0.089575917 0.28975382, 0.010089085 0.089685172 0.28937516, 0.011069089 0.089821696 0.28865117, 0.010812387 0.089947283 0.28944638, 0.011227161 0.090097189 0.28929892, 0.010774091 0.089943618 0.28934601, 0.010867596 0.089967638 0.28916177, 0.011170641 0.090090245 0.2891542, 0.011118934 0.090047032 0.28898659, 0.011081532 0.089954019 0.28880689, 0.011577889 0.090207577 0.28926679, 0.011534765 0.090218544 0.28917405, 0.012024716 0.090447605 0.28878459, 0.013003603 0.090742499 0.2878207, 0.012518689 0.090653896 0.2887803, 0.013112143 0.090995461 0.28836003, 0.013010308 0.090871185 0.28799108, 0.013050914 0.090958804 0.28818426, 0.013559699 0.091166854 0.28845242, 0.013506234 0.091183186 0.28836045, 0.013892859 0.09147495 0.28798077, 0.014685199 0.09189871 0.28702623, 0.01436168 0.09173426 0.28798088, 0.014683619 0.092016846 0.28721407, 0.014794737 0.092121154 0.28760567, 0.014724851 0.092094034 0.28742167, 0.015242696 0.092341483 0.28769913, 0.015179202 0.092362702 0.28760928, 0.015454382 0.092699498 0.28726527, 0.015942872 0.092974126 0.28738028, 0.016260847 0.093392313 0.28712618, 0.015874818 0.092997491 0.287292, 0.016168162 0.093408912 0.28697667, 0.016091391 0.093393594 0.28678691, 0.01661174 0.09368822 0.28708193, 0.017165899 0.094385654 0.28684738, 0.017699331 0.09517768 0.28664336, 0.017256305 0.09481287 0.28651699, 0.017798811 0.095568419 0.28645608, 0.018128142 0.095930547 0.28650752, 0.018217772 0.096290708 0.28639093, 0.018109053 0.096322566 0.28624648, 0.018534452 0.09677884 0.28641877, 0.018564627 0.097171366 0.28629008, 0.018853113 0.097577363 0.28639555, 0.01502116 0.09228313 0.28700683, 0.015706465 0.092940837 0.28667954, 0.016050726 0.093332678 0.28656584, 0.016061544 0.09323296 0.28636089, 0.016233355 0.093554944 0.28672716, 0.016529962 0.093849689 0.28677529, 0.016517982 0.093898982 0.2866005, 0.017153978 0.09469834 0.28587219, 0.017046943 0.094618797 0.28637788, 0.017174095 0.094811559 0.28632358, 0.017134562 0.094772398 0.28609201, 0.017296821 0.095017076 0.28596666, 0.017377079 0.095169753 0.28602424, 0.017598033 0.095508426 0.28578007, 0.017800376 0.09594509 0.28588608, 0.018022597 0.096337497 0.28605166, 0.017862812 0.09605813 0.28578019, 0.018010467 0.096282721 0.28558326, 0.017984152 0.096324623 0.28581357, 0.018198267 0.096775025 0.28593537, 0.018117607 0.096612304 0.28572115, 0.018181071 0.096770436 0.28579989, 0.018350512 0.097150564 0.28560475, 0.018499389 0.097593158 0.2857742, 0.018543303 0.097716063 0.28568467, 0.011208892 0.10805529 0.25156417, 0.010771438 0.10890135 0.25100324, 0.011497587 0.10887054 0.2512776, 0.010715649 0.10877839 0.25112662, 0.011410698 0.10875529 0.25140625, 0.010671392 0.10862708 0.25122091, 0.01133424 0.10860687 0.25150397, 0.010641515 0.10845703 0.25128058, 0.011273071 0.1084339 0.25156495, 0.010627076 0.10827696 0.25130305, 0.011230454 0.10824639 0.25158539, 0.010628894 0.10809466 0.25128707, 0.01022473 0.1085332 0.25108153, 0.010002971 0.10846737 0.2510142, 0.0097849965 0.10838884 0.25094894, 0.021150514 0.1068055 0.28688571, 0.021153167 0.10665372 0.28696623, 0.021022812 0.106673 0.28686801, 0.023280859 0.11193648 0.28297934, 0.023611352 0.11248678 0.28207609, 0.023445487 0.11244848 0.28202012, 0.023414627 0.11195242 0.28302798, 0.021261886 0.1074115 0.28657737, 0.022032857 0.10975474 0.28452116, 0.022548378 0.11093336 0.28334633, 0.021581829 0.10775629 0.28656772, 0.022006363 0.10851973 0.28623807, 0.023160085 0.1119006 0.28292128, 0.023296669 0.11237648 0.28195128, 0.021865904 0.1085391 0.28616735, 0.022896752 0.1112909 0.28376499, 0.023053169 0.11184713 0.2828559, 0.023172438 0.11227414 0.28187227, 0.022790432 0.11124492 0.28368881, 0.021509171 0.10776481 0.28652072, 0.019326881 0.1012207 0.2864655, 0.022947878 0.11176401 0.28277138, 0.023078963 0.11214685 0.2817882, 0.022686198 0.11117047 0.28359017, 0.019527495 0.10129496 0.28689036, 0.019397438 0.10145488 0.28667, 0.019649804 0.10146132 0.2870301, 0.019621328 0.10193515 0.28702822, 0.022856787 0.11164546 0.28266853, 0.022598222 0.11106154 0.28346926, 0.019368932 0.10153213 0.28654477, 0.022802278 0.11150804 0.28256348, 0.023020834 0.11200085 0.28170216, 0.019360214 0.10156065 0.28643712, 0.019446447 0.10203734 0.28637773, 0.019792512 0.10141736 0.2871207, 0.019521847 0.10247964 0.28662726, 0.019875005 0.10240328 0.28725478, 0.019748718 0.10282096 0.28709942, 0.019611016 0.102898 0.28668156, 0.019635558 0.10291782 0.28645107, 0.021740496 0.1085411 0.28607616, 0.01965493 0.10286236 0.28691477, 0.019725442 0.10327134 0.28687468, 0.020005599 0.10301414 0.2873216, 0.020020455 0.10360551 0.2872476, 0.019704416 0.10328567 0.2867454, 0.021633178 0.10852647 0.28596815, 0.019720003 0.10143837 0.2870802, 0.019830197 0.10377449 0.28659979, 0.019974336 0.10420603 0.28689721, 0.020246893 0.10397968 0.2873511, 0.020365268 0.10469803 0.28724924, 0.020157546 0.10473704 0.28694278, 0.020104438 0.10473523 0.28671935, 0.022485167 0.11005723 0.2851195, 0.020252585 0.1047222 0.28712025, 0.019950449 0.10420969 0.28677043, 0.02000773 0.10273692 0.28733435, 0.019864589 0.10278046 0.28723204, 0.020112932 0.10471445 0.2864964, 0.022362679 0.11004305 0.2850388, 0.020228356 0.10511976 0.28670844, 0.020500943 0.10486445 0.287296, 0.020577967 0.10549718 0.28711137, 0.02225624 0.11001158 0.28494558, 0.022154406 0.10995433 0.28482363, 0.021533713 0.10848907 0.28582475, 0.020632371 0.1060307 0.28684363, 0.020821765 0.10586593 0.2871359, 0.020388544 0.10560769 0.28647414, 0.020326793 0.10395783 0.28739998, 0.022072792 0.10986432 0.28467354, 0.021459877 0.1084224 0.28564712, 0.021433026 0.10833517 0.28546733, 0.02055189 0.10607141 0.28654763, 0.020502135 0.10466403 0.28735092, 0.020742759 0.10657227 0.2861748, 0.020676568 0.10628128 0.28669187, 0.020913288 0.1066781 0.28674707, 0.020816147 0.10666597 0.28658405, 0.020752475 0.10662931 0.28637999, 0.023017853 0.11131933 0.28383204, 0.020891726 0.10699207 0.28629184, 0.021061778 0.10743785 0.28596666, 0.021247864 0.10789767 0.28593427, 0.020897925 0.10584942 0.28718483, 0.021382689 0.10811776 0.28602061, 0.01157181 0.10886228 0.25130859, 0.011483297 0.10874796 0.25143883, 0.011404932 0.10859948 0.25153771, 0.011341721 0.10842603 0.25159901, 0.011297315 0.10823756 0.25161979, 0.011274084 0.10804543 0.25159845, 0.023467124 0.11389762 0.27790901, 0.023340449 0.11294472 0.27981457, 0.023399398 0.11309308 0.27989581, 0.023526356 0.11404845 0.27798554, 0.023458675 0.11500499 0.27607265, 0.023999944 0.11541083 0.27622887, 0.023939177 0.11345491 0.28014013, 0.023771003 0.11340985 0.28009787, 0.023620203 0.11333162 0.28004107, 0.024068937 0.11443231 0.2781857, 0.02349402 0.11322445 0.27997252, 0.023899928 0.11438024 0.27815711, 0.023831353 0.11535206 0.27621397, 0.023748323 0.11429608 0.2781125, 0.023680031 0.11526164 0.27618188, 0.023621574 0.11418355 0.27805439, 0.023553804 0.11514392 0.2761336, 0.023399755 0.11485174 0.27600095, 0.020966426 0.11110738 0.26239964, 0.020920604 0.11051488 0.26162896, 0.020748258 0.11049864 0.26169536, 0.020592511 0.11044887 0.2617828, 0.020808592 0.1110599 0.26248512, 0.020576432 0.11035904 0.26320049, 0.020505205 0.11052668 0.26306236, 0.020461917 0.11036804 0.26188648, 0.020676002 0.11098403 0.26259068, 0.020350158 0.11024103 0.26201996, 0.020562991 0.11086497 0.26273125, 0.020286277 0.11006537 0.26217651, 0.020498306 0.11070153 0.26290089, 0.020292729 0.10987675 0.26232085, 0.019769505 0.10889325 0.26087326, 0.019053295 0.10816661 0.2593337, 0.018097207 0.10768604 0.25771087, 0.016866386 0.10745817 0.25606188, 0.015320942 0.10747042 0.2544409, 0.013489455 0.10768211 0.25295517, 0.021106347 0.11191744 0.26320258, 0.021418646 0.1124981 0.26356259, 0.021241203 0.11247903 0.26361483, 0.020944893 0.11124471 0.2625882, 0.020162597 0.1097573 0.26183638, 0.02006647 0.10963997 0.26139501, 0.019900873 0.10927528 0.26112494, 0.019828022 0.10929465 0.26063022, 0.019765064 0.10910124 0.2607615, 0.019568741 0.10882846 0.26033479, 0.019433871 0.10879466 0.25990832, 0.019207895 0.10847673 0.25957736, 0.019114643 0.10859129 0.25914967, 0.019052759 0.1083864 0.25925553, 0.018761307 0.10816753 0.25874665, 0.018278986 0.10794005 0.25795048, 0.018162966 0.10812032 0.25758317, 0.01810208 0.10791013 0.25766417, 0.01772216 0.10785058 0.25709412, 0.017709211 0.10776925 0.25711498, 0.017506555 0.10796374 0.25667682, 0.017099589 0.10774711 0.25628796, 0.017025098 0.10804868 0.2559022, 0.016937137 0.10788941 0.25598335, 0.016877949 0.10767955 0.25604242, 0.017086044 0.10766616 0.25630432, 0.016372383 0.10762194 0.25548187, 0.016386271 0.10770178 0.25546917, 0.016099676 0.10786536 0.25507304, 0.015607879 0.1077145 0.25467986, 0.015472963 0.10804811 0.25433093, 0.015394807 0.10788897 0.25440037, 0.015338525 0.10768402 0.25444189, 0.015593573 0.10763589 0.25468871, 0.014730215 0.10778078 0.25389621, 0.014381975 0.10798302 0.25354508, 0.013874233 0.10852283 0.25259855, 0.01378338 0.10845193 0.25271094, 0.013701186 0.10835624 0.2528058, 0.013804793 0.10788971 0.25317159, 0.013629809 0.10823953 0.25288048, 0.013562873 0.10808265 0.25294036, 0.013511389 0.1078853 0.25296941, 0.01314877 0.10806239 0.25269005, 0.01312992 0.1079855 0.25269911, 0.012627929 0.10836399 0.25224778, 0.012036577 0.10819477 0.25201294, 0.01206325 0.10829461 0.25199753, 0.011866808 0.10845798 0.25182477, 0.020837113 0.11202899 0.26367748, 0.021080762 0.11243507 0.26369819, 0.020946085 0.11236852 0.26380798, 0.02084443 0.11228323 0.26393798, 0.020789027 0.11197472 0.26375392, 0.020781308 0.11218336 0.26408195, 0.020760015 0.1120747 0.26423129, 0.020781979 0.11196268 0.26437828, 0.020676568 0.11148486 0.26355252, 0.020671144 0.1112799 0.2631267, 0.020651326 0.11032087 0.2614781, 0.020430505 0.11016658 0.26147342, 0.020517439 0.11020789 0.26141471, 0.020544618 0.11001161 0.2609919, 0.020250991 0.10974646 0.26072642, 0.020211667 0.1095787 0.26031801, 0.02006188 0.1095235 0.26040944, 0.020377606 0.109597 0.26024002, 0.020165488 0.10970318 0.26078495, 0.019935951 0.10943452 0.26050982, 0.020078063 0.10943544 0.26007143, 0.019846007 0.10929158 0.26005608, 0.019929335 0.10933712 0.25999704, 0.019904241 0.10921013 0.25955117, 0.019564226 0.10899729 0.25926381, 0.019634396 0.10892341 0.25875938, 0.019477904 0.10889938 0.25884965, 0.019336626 0.10883754 0.25894561, 0.019483194 0.10894969 0.25932297, 0.019217551 0.10874093 0.25904253, 0.019100696 0.10867304 0.25876498, 0.019042268 0.10860801 0.25881836, 0.018959776 0.10861892 0.25823587, 0.018629134 0.10843047 0.25798717, 0.018642455 0.10848358 0.2571958, 0.018498704 0.10845053 0.25729719, 0.018320128 0.10826632 0.25765249, 0.018369079 0.10838014 0.25739649, 0.018259183 0.10827655 0.25748929, 0.01811932 0.10834205 0.25688568, 0.01748763 0.10823816 0.25609365, 0.017366633 0.10828286 0.25560448, 0.017238811 0.10823777 0.25571406, 0.017123505 0.10815832 0.2558144, 0.016820356 0.10808977 0.255582, 0.016772196 0.10819131 0.25529754, 0.015981615 0.1082001 0.25451845, 0.015657201 0.1082505 0.25415054, 0.015558064 0.10816213 0.25424942, 0.015766889 0.10830903 0.25403744, 0.015203759 0.10812846 0.25402474, 0.015109882 0.10826007 0.25376055, 0.021001086 0.11144727 0.26278377, 0.018449441 0.10802835 0.25821188, 0.023468494 0.11522564 0.27577981, 0.020956829 0.11309487 0.26465321, 0.023781642 0.11566889 0.27553764, 0.021132246 0.11382803 0.26541761, 0.02124697 0.11394706 0.26528707, 0.023350209 0.11529198 0.27526715, 0.02107203 0.11320609 0.26450995, 0.020889059 0.11294252 0.26483014, 0.021061584 0.11366397 0.2655758, 0.023365885 0.11557296 0.27490813, 0.023340762 0.11582613 0.27436623, 0.023246214 0.11567047 0.27433863, 0.020892784 0.11278102 0.26500192, 0.023189947 0.11549953 0.27430078, 0.021059066 0.11348835 0.26572743, 0.023450494 0.11594296 0.27438089, 0.022061408 0.11559328 0.26922807, 0.022401184 0.11606601 0.2696501, 0.021893024 0.11526638 0.26875174, 0.022117108 0.11577713 0.26851267, 0.022003978 0.11564475 0.26858994, 0.022422343 0.11607093 0.2691592, 0.021921217 0.11546361 0.2686758, 0.021959528 0.11557379 0.26801589, 0.022380054 0.11592442 0.26838776, 0.022239193 0.11586443 0.26844814, 0.023481026 0.11614165 0.27390897, 0.022129327 0.11551976 0.26735327, 0.023687109 0.11608884 0.27438369, 0.021889627 0.11549541 0.26806757, 0.023561701 0.11602503 0.27438584, 0.023272902 0.11613578 0.27344397, 0.021700501 0.11519298 0.26774842, 0.022905841 0.11598048 0.27252173, 0.02285552 0.11579573 0.27251884, 0.021438122 0.1145148 0.26714826, 0.021722749 0.11518472 0.26716635, 0.021918312 0.11514792 0.266651, 0.021770343 0.11509404 0.26672325, 0.023310497 0.11630994 0.27295455, 0.023223028 0.11636269 0.27248183, 0.023109198 0.11627525 0.27249977, 0.022998214 0.11614928 0.2725144, 0.021643996 0.11501119 0.26680604, 0.021652415 0.11510757 0.26722625, 0.021453127 0.11470613 0.26703429, 0.021530002 0.1148831 0.26691118, 0.023212537 0.11642981 0.27205095, 0.021438792 0.11468929 0.26660511, 0.023129761 0.11638319 0.27206823, 0.021668747 0.11473066 0.26605377, 0.0212733 0.11430764 0.26629171, 0.022881255 0.11628413 0.27156654, 0.022406146 0.11572826 0.27063343, 0.021236777 0.11416972 0.26585409, 0.021699905 0.114546 0.26569784, 0.022986397 0.11641777 0.27103636, 0.022764727 0.11632115 0.27046552, 0.021301523 0.11417165 0.26559359, 0.021532536 0.11407131 0.26511008, 0.021377832 0.11402297 0.26518974, 0.022901848 0.11637136 0.2710602, 0.022535414 0.11610058 0.27055278, 0.022446871 0.11592251 0.27059814, 0.023664102 0.11588347 0.27490464, 0.02264747 0.11623207 0.2705074, 0.022771448 0.11632359 0.27014589, 0.022685438 0.11627781 0.27017543, 0.02251029 0.11611548 0.26912293, 0.021537557 0.11334088 0.26426861, 0.021363035 0.11332318 0.26432362, 0.021204993 0.11327744 0.26440585 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 3, 0, 2, -1, 4, 5, 6, -1, 7, 3, 2, -1, 8, 7, 2, -1, 9, 6, 10, -1, 11, 2, 12, -1, 11, 8, 2, -1, 9, 4, 6, -1, 13, 11, 12, -1, 14, 10, 15, -1, 14, 9, 10, -1, 16, 15, 17, -1, 18, 13, 12, -1, 16, 14, 15, -1, 19, 12, 20, -1, 21, 16, 17, -1, 19, 18, 12, -1, 22, 21, 17, -1, 23, 19, 20, -1, 24, 21, 22, -1, 25, 20, 26, -1, 27, 22, 28, -1, 25, 23, 20, -1, 27, 24, 22, -1, 29, 26, 30, -1, 31, 27, 28, -1, 29, 25, 26, -1, 32, 29, 30, -1, 33, 31, 28, -1, 34, 32, 30, -1, 35, 32, 34, -1, 36, 28, 37, -1, 38, 35, 34, -1, 36, 33, 28, -1, 39, 35, 38, -1, 40, 39, 38, -1, 41, 36, 37, -1, 42, 41, 37, -1, 43, 42, 37, -1, 44, 37, 45, -1, 44, 43, 37, -1, 46, 44, 45, -1, 47, 46, 45, -1, 47, 45, 48, -1, 49, 47, 48, -1, 50, 49, 48, -1, 50, 48, 51, -1, 52, 50, 51, -1, 53, 52, 51, -1, 53, 51, 54, -1, 55, 53, 54, -1, 55, 54, 56, -1, 57, 55, 56, -1, 58, 57, 56, -1, 58, 56, 59, -1, 60, 58, 59, -1, 1, 60, 59, -1, 1, 59, 2, -1, 61, 62, 63, -1, 64, 62, 61, -1, 65, 62, 64, -1, 66, 62, 65, -1, 67, 68, 69, -1, 70, 68, 67, -1, 71, 68, 70, -1, 72, 68, 71, -1, 63, 68, 72, -1, 62, 68, 63, -1, 73, 74, 75, -1, 76, 73, 75, -1, 77, 78, 79, -1, 80, 76, 75, -1, 81, 80, 75, -1, 82, 79, 83, -1, 84, 75, 85, -1, 84, 81, 75, -1, 82, 77, 79, -1, 86, 84, 85, -1, 87, 83, 88, -1, 87, 82, 83, -1, 89, 86, 85, -1, 90, 88, 91, -1, 90, 87, 88, -1, 92, 85, 93, -1, 94, 90, 91, -1, 92, 89, 85, -1, 95, 92, 93, -1, 96, 94, 91, -1, 97, 94, 96, -1, 98, 93, 99, -1, 100, 96, 101, -1, 98, 95, 93, -1, 100, 97, 96, -1, 102, 99, 103, -1, 104, 100, 101, -1, 102, 98, 99, -1, 105, 102, 103, -1, 106, 104, 101, -1, 107, 105, 103, -1, 108, 105, 107, -1, 109, 101, 110, -1, 111, 108, 107, -1, 109, 106, 101, -1, 112, 108, 111, -1, 113, 112, 111, -1, 114, 109, 110, -1, 115, 114, 110, -1, 116, 115, 110, -1, 117, 110, 118, -1, 117, 116, 110, -1, 119, 117, 118, -1, 120, 119, 118, -1, 120, 118, 121, -1, 122, 120, 121, -1, 123, 122, 121, -1, 123, 121, 124, -1, 125, 123, 124, -1, 126, 125, 124, -1, 126, 124, 127, -1, 128, 126, 127, -1, 128, 127, 129, -1, 130, 128, 129, -1, 131, 130, 129, -1, 131, 129, 132, -1, 133, 131, 132, -1, 74, 133, 132, -1, 74, 132, 75, -1, 134, 135, 136, -1, 137, 135, 134, -1, 138, 135, 137, -1, 139, 135, 138, -1, 140, 141, 142, -1, 143, 141, 140, -1, 144, 141, 143, -1, 145, 141, 144, -1, 136, 141, 145, -1, 135, 141, 136, -1, 146, 147, 148, -1, 146, 148, 149, -1, 150, 149, 151, -1, 150, 146, 149, -1, 152, 150, 151, -1, 153, 150, 152, -1, 154, 155, 156, -1, 157, 155, 154, -1, 158, 157, 154, -1, 159, 157, 158, -1, 160, 158, 161, -1, 160, 159, 158, -1, 162, 163, 164, -1, 165, 163, 166, -1, 164, 163, 165, -1, 167, 168, 169, -1, 170, 171, 172, -1, 168, 173, 169, -1, 166, 171, 170, -1, 163, 171, 166, -1, 173, 174, 175, -1, 168, 174, 173, -1, 172, 176, 177, -1, 171, 176, 172, -1, 177, 176, 178, -1, 175, 179, 180, -1, 174, 179, 175, -1, 176, 181, 178, -1, 178, 181, 182, -1, 179, 183, 180, -1, 182, 184, 185, -1, 183, 186, 187, -1, 185, 184, 188, -1, 181, 184, 182, -1, 179, 186, 183, -1, 189, 190, 191, -1, 192, 190, 189, -1, 188, 190, 192, -1, 184, 190, 188, -1, 193, 194, 195, -1, 191, 194, 193, -1, 190, 194, 191, -1, 196, 197, 198, -1, 195, 197, 196, -1, 199, 197, 200, -1, 198, 197, 199, -1, 194, 197, 195, -1, 201, 202, 203, -1, 200, 202, 201, -1, 197, 202, 200, -1, 203, 204, 205, -1, 202, 204, 203, -1, 204, 206, 205, -1, 206, 207, 208, -1, 209, 210, 211, -1, 212, 210, 209, -1, 187, 210, 212, -1, 204, 207, 206, -1, 186, 210, 187, -1, 208, 213, 214, -1, 207, 213, 208, -1, 214, 215, 216, -1, 216, 215, 217, -1, 218, 162, 164, -1, 219, 162, 218, -1, 213, 215, 214, -1, 220, 162, 219, -1, 221, 162, 220, -1, 211, 162, 221, -1, 210, 162, 211, -1, 222, 223, 224, -1, 225, 223, 222, -1, 226, 227, 228, -1, 229, 223, 225, -1, 227, 230, 228, -1, 231, 232, 233, -1, 224, 232, 231, -1, 223, 232, 224, -1, 230, 234, 235, -1, 227, 234, 230, -1, 233, 236, 237, -1, 237, 236, 238, -1, 232, 236, 233, -1, 235, 239, 240, -1, 234, 239, 235, -1, 236, 241, 238, -1, 238, 241, 242, -1, 239, 243, 240, -1, 241, 244, 242, -1, 243, 245, 246, -1, 242, 244, 247, -1, 239, 245, 243, -1, 247, 244, 248, -1, 244, 249, 248, -1, 250, 249, 251, -1, 252, 249, 250, -1, 248, 249, 252, -1, 249, 253, 251, -1, 254, 253, 255, -1, 251, 253, 254, -1, 253, 256, 255, -1, 257, 256, 258, -1, 255, 256, 257, -1, 259, 256, 260, -1, 258, 256, 259, -1, 256, 261, 260, -1, 262, 261, 263, -1, 260, 261, 262, -1, 263, 264, 265, -1, 261, 264, 263, -1, 264, 266, 265, -1, 267, 268, 269, -1, 266, 270, 271, -1, 272, 268, 267, -1, 246, 268, 272, -1, 245, 268, 246, -1, 264, 270, 266, -1, 271, 273, 274, -1, 270, 273, 271, -1, 275, 229, 276, -1, 274, 277, 278, -1, 269, 229, 275, -1, 278, 277, 279, -1, 273, 277, 274, -1, 280, 229, 225, -1, 281, 229, 280, -1, 276, 229, 281, -1, 268, 229, 269, -1, 282, 283, 284, -1, 284, 283, 285, -1, 285, 286, 287, -1, 283, 286, 285, -1, 287, 288, 289, -1, 286, 288, 287, -1, 288, 290, 289, -1, 289, 291, 292, -1, 290, 291, 289, -1, 292, 293, 294, -1, 291, 293, 292, -1, 294, 295, 296, -1, 293, 295, 294, -1, 295, 297, 296, -1, 298, 299, 300, -1, 300, 301, 302, -1, 299, 301, 300, -1, 302, 303, 304, -1, 301, 303, 302, -1, 305, 306, 307, -1, 304, 306, 305, -1, 303, 306, 304, -1, 307, 308, 309, -1, 306, 308, 307, -1, 309, 310, 311, -1, 308, 310, 309, -1, 311, 312, 313, -1, 310, 312, 311, -1, 314, 315, 316, -1, 317, 314, 316, -1, 318, 314, 317, -1, 319, 318, 320, -1, 319, 320, 321, -1, 319, 321, 322, -1, 319, 314, 318, -1, 323, 324, 325, -1, 326, 323, 325, -1, 327, 323, 326, -1, 328, 327, 329, -1, 328, 329, 330, -1, 328, 330, 331, -1, 328, 323, 327, -1, 68, 51, 48, -1, 68, 48, 45, -1, 68, 45, 37, -1, 68, 37, 28, -1, 68, 28, 22, -1, 68, 22, 17, -1, 68, 17, 15, -1, 68, 15, 10, -1, 68, 10, 6, -1, 68, 6, 332, -1, 68, 332, 333, -1, 68, 135, 51, -1, 118, 110, 141, -1, 121, 118, 141, -1, 124, 121, 141, -1, 62, 141, 135, -1, 62, 135, 68, -1, 62, 124, 141, -1, 62, 132, 129, -1, 62, 129, 127, -1, 62, 127, 124, -1, 135, 334, 335, -1, 135, 335, 38, -1, 135, 38, 34, -1, 336, 62, 337, -1, 135, 34, 30, -1, 135, 30, 26, -1, 135, 26, 20, -1, 135, 20, 12, -1, 135, 12, 2, -1, 111, 62, 336, -1, 75, 132, 62, -1, 59, 135, 2, -1, 107, 62, 111, -1, 56, 135, 59, -1, 85, 75, 62, -1, 54, 135, 56, -1, 103, 62, 107, -1, 93, 85, 62, -1, 51, 135, 54, -1, 99, 93, 62, -1, 99, 62, 103, -1, 79, 338, 339, -1, 79, 339, 141, -1, 83, 79, 141, -1, 88, 83, 141, -1, 91, 88, 141, -1, 96, 91, 141, -1, 101, 96, 141, -1, 110, 101, 141, -1, 207, 328, 213, -1, 204, 328, 207, -1, 202, 328, 204, -1, 197, 328, 202, -1, 194, 328, 197, -1, 190, 328, 194, -1, 184, 328, 190, -1, 181, 328, 184, -1, 314, 328, 181, -1, 253, 249, 319, -1, 249, 244, 319, -1, 244, 241, 319, -1, 319, 323, 314, -1, 314, 323, 328, -1, 236, 323, 241, -1, 232, 323, 236, -1, 241, 323, 319, -1, 232, 223, 323, -1, 323, 340, 341, -1, 162, 314, 163, -1, 323, 227, 340, -1, 210, 314, 162, -1, 186, 314, 210, -1, 179, 314, 186, -1, 174, 314, 179, -1, 223, 229, 323, -1, 168, 314, 174, -1, 342, 314, 168, -1, 343, 314, 342, -1, 323, 234, 227, -1, 229, 268, 323, -1, 314, 171, 163, -1, 323, 239, 234, -1, 314, 176, 171, -1, 268, 245, 323, -1, 323, 245, 239, -1, 314, 181, 176, -1, 344, 277, 319, -1, 345, 277, 344, -1, 277, 273, 319, -1, 273, 270, 319, -1, 270, 264, 319, -1, 264, 261, 319, -1, 261, 256, 319, -1, 215, 346, 347, -1, 256, 253, 319, -1, 215, 328, 346, -1, 213, 328, 215, -1, 348, 349, 350, -1, 349, 351, 352, -1, 348, 351, 349, -1, 352, 353, 354, -1, 351, 353, 352, -1, 353, 355, 354, -1, 353, 356, 355, -1, 356, 357, 355, -1, 356, 358, 357, -1, 358, 359, 357, -1, 358, 360, 359, -1, 360, 361, 359, -1, 360, 362, 361, -1, 362, 363, 361, -1, 362, 364, 363, -1, 364, 365, 363, -1, 365, 366, 363, -1, 365, 367, 366, -1, 367, 368, 366, -1, 369, 370, 371, -1, 369, 372, 370, -1, 372, 373, 370, -1, 372, 374, 373, -1, 374, 375, 373, -1, 374, 376, 375, -1, 376, 377, 375, -1, 376, 378, 377, -1, 378, 379, 377, -1, 378, 380, 379, -1, 380, 381, 379, -1, 381, 382, 383, -1, 380, 382, 381, -1, 383, 384, 385, -1, 382, 384, 383, -1, 385, 386, 387, -1, 384, 386, 385, -1, 386, 388, 387, -1, 389, 390, 391, -1, 391, 392, 393, -1, 390, 392, 391, -1, 393, 394, 395, -1, 392, 394, 393, -1, 394, 396, 395, -1, 396, 397, 395, -1, 396, 398, 397, -1, 398, 399, 397, -1, 398, 400, 399, -1, 400, 401, 399, -1, 400, 402, 401, -1, 402, 403, 401, -1, 402, 404, 403, -1, 404, 405, 403, -1, 404, 406, 405, -1, 406, 407, 405, -1, 406, 408, 407, -1, 409, 410, 411, -1, 410, 412, 411, -1, 412, 413, 414, -1, 410, 413, 412, -1, 413, 415, 414, -1, 413, 416, 415, -1, 416, 417, 415, -1, 416, 418, 417, -1, 418, 419, 417, -1, 418, 420, 419, -1, 420, 421, 419, -1, 420, 422, 421, -1, 422, 423, 421, -1, 422, 424, 423, -1, 423, 425, 426, -1, 424, 425, 423, -1, 425, 427, 426, -1, 427, 428, 426, -1, 427, 429, 428, -1, 430, 369, 371, -1, 431, 430, 371, -1, 432, 430, 431, -1, 433, 432, 431, -1, 434, 432, 433, -1, 435, 434, 433, -1, 436, 434, 435, -1, 437, 436, 435, -1, 438, 436, 437, -1, 439, 438, 437, -1, 440, 438, 439, -1, 441, 440, 439, -1, 442, 441, 443, -1, 442, 440, 441, -1, 152, 443, 153, -1, 152, 442, 443, -1, 444, 348, 350, -1, 444, 350, 445, -1, 446, 444, 445, -1, 447, 446, 445, -1, 448, 446, 447, -1, 449, 448, 447, -1, 450, 448, 449, -1, 451, 450, 449, -1, 452, 450, 451, -1, 453, 452, 451, -1, 454, 452, 453, -1, 455, 454, 453, -1, 456, 455, 457, -1, 456, 454, 455, -1, 161, 457, 160, -1, 161, 456, 457, -1, 458, 148, 147, -1, 458, 147, 459, -1, 460, 458, 459, -1, 461, 460, 459, -1, 462, 460, 461, -1, 463, 462, 461, -1, 464, 462, 463, -1, 465, 464, 463, -1, 466, 464, 465, -1, 467, 466, 465, -1, 468, 466, 467, -1, 469, 468, 467, -1, 470, 469, 471, -1, 470, 468, 469, -1, 429, 471, 428, -1, 429, 470, 471, -1, 472, 156, 155, -1, 472, 155, 473, -1, 474, 472, 473, -1, 475, 474, 473, -1, 476, 474, 475, -1, 477, 476, 475, -1, 478, 476, 477, -1, 479, 478, 477, -1, 480, 478, 479, -1, 481, 480, 479, -1, 482, 480, 481, -1, 483, 482, 481, -1, 484, 482, 483, -1, 485, 484, 483, -1, 408, 485, 407, -1, 408, 484, 485, -1, 297, 486, 296, -1, 487, 486, 297, -1, 488, 487, 297, -1, 489, 487, 488, -1, 490, 489, 488, -1, 491, 489, 490, -1, 389, 491, 490, -1, 492, 389, 490, -1, 390, 389, 492, -1, 411, 493, 409, -1, 494, 495, 496, -1, 494, 496, 409, -1, 494, 409, 493, -1, 497, 498, 495, -1, 497, 495, 494, -1, 282, 499, 498, -1, 282, 284, 499, -1, 282, 498, 497, -1, 298, 500, 299, -1, 501, 500, 298, -1, 502, 501, 298, -1, 503, 501, 502, -1, 504, 503, 502, -1, 505, 503, 504, -1, 388, 505, 504, -1, 506, 388, 504, -1, 387, 388, 506, -1, 367, 507, 368, -1, 508, 509, 510, -1, 508, 510, 368, -1, 508, 368, 507, -1, 511, 512, 509, -1, 511, 509, 508, -1, 313, 312, 513, -1, 313, 513, 512, -1, 313, 512, 511, -1, 279, 277, 514, -1, 514, 345, 515, -1, 277, 345, 514, -1, 515, 344, 516, -1, 345, 344, 515, -1, 516, 319, 322, -1, 344, 319, 516, -1, 315, 314, 517, -1, 517, 343, 518, -1, 314, 343, 517, -1, 518, 342, 519, -1, 343, 342, 518, -1, 519, 168, 167, -1, 342, 168, 519, -1, 520, 40, 38, -1, 520, 38, 335, -1, 521, 335, 334, -1, 521, 520, 335, -1, 139, 334, 135, -1, 139, 521, 334, -1, 142, 141, 339, -1, 522, 339, 338, -1, 522, 142, 339, -1, 523, 338, 79, -1, 523, 522, 338, -1, 78, 523, 79, -1, 524, 113, 111, -1, 524, 111, 336, -1, 525, 336, 337, -1, 525, 524, 336, -1, 66, 337, 62, -1, 66, 525, 337, -1, 69, 68, 333, -1, 526, 333, 332, -1, 526, 69, 333, -1, 527, 332, 6, -1, 527, 526, 332, -1, 5, 527, 6, -1, 324, 323, 528, -1, 528, 341, 529, -1, 323, 341, 528, -1, 529, 340, 530, -1, 341, 340, 529, -1, 530, 227, 226, -1, 340, 227, 530, -1, 217, 215, 531, -1, 531, 347, 532, -1, 215, 347, 531, -1, 532, 346, 533, -1, 347, 346, 532, -1, 533, 328, 331, -1, 346, 328, 533, -1, 498, 499, 534, -1, 535, 527, 5, -1, 496, 495, 536, -1, 537, 538, 69, -1, 537, 526, 527, -1, 537, 69, 526, -1, 539, 540, 538, -1, 539, 538, 537, -1, 541, 542, 540, -1, 541, 540, 539, -1, 543, 544, 542, -1, 543, 542, 541, -1, 545, 546, 544, -1, 545, 544, 543, -1, 547, 534, 546, -1, 547, 495, 498, -1, 547, 546, 545, -1, 547, 498, 534, -1, 548, 543, 541, -1, 548, 545, 543, -1, 548, 537, 527, -1, 548, 495, 547, -1, 548, 547, 545, -1, 548, 539, 537, -1, 548, 541, 539, -1, 549, 495, 548, -1, 549, 548, 527, -1, 550, 551, 536, -1, 550, 552, 551, -1, 550, 553, 552, -1, 550, 554, 553, -1, 550, 535, 554, -1, 550, 549, 527, -1, 550, 527, 535, -1, 550, 495, 549, -1, 550, 536, 495, -1, 555, 409, 496, -1, 536, 555, 496, -1, 556, 555, 536, -1, 551, 556, 536, -1, 557, 556, 551, -1, 552, 557, 551, -1, 558, 557, 552, -1, 553, 558, 552, -1, 554, 559, 558, -1, 554, 558, 553, -1, 535, 560, 559, -1, 535, 559, 554, -1, 5, 4, 560, -1, 5, 560, 535, -1, 538, 561, 67, -1, 538, 67, 69, -1, 540, 562, 561, -1, 540, 561, 538, -1, 542, 563, 562, -1, 542, 562, 540, -1, 544, 564, 563, -1, 544, 563, 542, -1, 565, 564, 544, -1, 546, 565, 544, -1, 566, 565, 546, -1, 534, 566, 546, -1, 284, 566, 534, -1, 499, 284, 534, -1, 567, 9, 14, -1, 567, 568, 9, -1, 569, 570, 422, -1, 567, 571, 572, -1, 567, 572, 568, -1, 567, 14, 571, -1, 573, 33, 36, -1, 573, 574, 429, -1, 569, 424, 570, -1, 573, 575, 574, -1, 573, 576, 575, -1, 577, 424, 569, -1, 573, 578, 576, -1, 573, 36, 578, -1, 573, 429, 427, -1, 577, 579, 424, -1, 580, 27, 31, -1, 581, 582, 583, -1, 580, 24, 27, -1, 581, 33, 573, -1, 580, 31, 584, -1, 581, 585, 586, -1, 580, 584, 579, -1, 581, 586, 582, -1, 581, 573, 427, -1, 580, 579, 577, -1, 581, 583, 33, -1, 581, 427, 585, -1, 587, 422, 420, -1, 588, 422, 587, -1, 589, 4, 9, -1, 589, 9, 568, -1, 589, 590, 591, -1, 589, 592, 590, -1, 589, 591, 410, -1, 589, 568, 592, -1, 593, 422, 588, -1, 594, 409, 555, -1, 594, 555, 556, -1, 594, 556, 557, -1, 594, 557, 558, -1, 593, 569, 422, -1, 594, 558, 559, -1, 594, 559, 560, -1, 594, 560, 4, -1, 594, 410, 409, -1, 595, 569, 593, -1, 594, 4, 589, -1, 594, 589, 410, -1, 595, 577, 569, -1, 596, 580, 577, -1, 596, 577, 595, -1, 596, 24, 580, -1, 597, 420, 418, -1, 597, 587, 420, -1, 598, 588, 587, -1, 598, 587, 597, -1, 599, 593, 588, -1, 599, 588, 598, -1, 600, 595, 593, -1, 600, 593, 599, -1, 601, 595, 600, -1, 601, 21, 24, -1, 601, 596, 595, -1, 601, 24, 596, -1, 602, 597, 418, -1, 602, 418, 416, -1, 603, 598, 597, -1, 603, 597, 602, -1, 604, 599, 598, -1, 604, 598, 603, -1, 605, 599, 604, -1, 605, 600, 599, -1, 606, 601, 600, -1, 606, 16, 21, -1, 606, 21, 601, -1, 606, 14, 16, -1, 606, 600, 605, -1, 607, 416, 413, -1, 607, 602, 416, -1, 608, 602, 607, -1, 608, 603, 602, -1, 585, 427, 425, -1, 608, 607, 413, -1, 609, 604, 603, -1, 586, 585, 425, -1, 609, 603, 608, -1, 582, 586, 425, -1, 572, 604, 609, -1, 572, 605, 604, -1, 571, 14, 606, -1, 33, 583, 31, -1, 571, 606, 605, -1, 610, 425, 424, -1, 571, 605, 572, -1, 611, 610, 424, -1, 591, 413, 410, -1, 611, 425, 610, -1, 612, 611, 424, -1, 612, 425, 611, -1, 590, 608, 413, -1, 579, 612, 424, -1, 579, 425, 612, -1, 579, 582, 425, -1, 590, 413, 591, -1, 584, 583, 582, -1, 584, 31, 583, -1, 584, 582, 579, -1, 592, 609, 608, -1, 613, 424, 422, -1, 592, 608, 590, -1, 570, 424, 613, -1, 570, 613, 422, -1, 568, 572, 609, -1, 568, 609, 592, -1, 614, 71, 70, -1, 615, 616, 617, -1, 614, 70, 561, -1, 614, 562, 618, -1, 619, 620, 621, -1, 622, 617, 623, -1, 619, 621, 624, -1, 622, 615, 617, -1, 625, 287, 289, -1, 626, 63, 627, -1, 626, 627, 628, -1, 625, 624, 287, -1, 626, 628, 629, -1, 630, 631, 632, -1, 633, 634, 635, -1, 630, 632, 615, -1, 633, 636, 634, -1, 637, 635, 620, -1, 637, 620, 619, -1, 638, 639, 294, -1, 638, 294, 640, -1, 641, 619, 624, -1, 641, 624, 625, -1, 642, 615, 622, -1, 642, 630, 615, -1, 643, 629, 631, -1, 644, 618, 636, -1, 644, 636, 633, -1, 643, 631, 630, -1, 645, 633, 635, -1, 645, 635, 637, -1, 646, 640, 647, -1, 70, 67, 561, -1, 646, 638, 640, -1, 648, 625, 289, -1, 646, 623, 639, -1, 646, 639, 638, -1, 649, 630, 642, -1, 650, 637, 619, -1, 649, 643, 630, -1, 650, 619, 641, -1, 651, 61, 63, -1, 651, 63, 626, -1, 652, 71, 614, -1, 651, 626, 629, -1, 652, 614, 618, -1, 651, 629, 643, -1, 652, 618, 644, -1, 653, 647, 654, -1, 653, 623, 646, -1, 653, 622, 623, -1, 655, 644, 633, -1, 653, 646, 647, -1, 655, 633, 645, -1, 656, 625, 648, -1, 657, 61, 651, -1, 657, 643, 649, -1, 656, 641, 625, -1, 657, 651, 643, -1, 658, 289, 292, -1, 659, 654, 660, -1, 659, 653, 654, -1, 658, 648, 289, -1, 659, 642, 622, -1, 661, 645, 637, -1, 640, 294, 296, -1, 659, 622, 653, -1, 662, 642, 659, -1, 661, 637, 650, -1, 662, 660, 663, -1, 664, 71, 652, -1, 664, 644, 655, -1, 662, 649, 642, -1, 664, 72, 71, -1, 664, 652, 644, -1, 662, 659, 660, -1, 665, 657, 649, -1, 666, 650, 641, -1, 665, 663, 667, -1, 665, 649, 662, -1, 665, 64, 61, -1, 665, 61, 657, -1, 665, 662, 663, -1, 666, 641, 656, -1, 665, 667, 64, -1, 616, 656, 648, -1, 616, 648, 658, -1, 668, 655, 645, -1, 668, 645, 661, -1, 669, 661, 650, -1, 669, 650, 666, -1, 632, 666, 656, -1, 65, 64, 667, -1, 632, 656, 616, -1, 670, 566, 284, -1, 671, 664, 655, -1, 670, 284, 285, -1, 671, 72, 664, -1, 671, 655, 668, -1, 672, 658, 292, -1, 673, 565, 566, -1, 673, 566, 670, -1, 628, 668, 661, -1, 628, 661, 669, -1, 634, 564, 565, -1, 639, 292, 294, -1, 634, 565, 673, -1, 639, 672, 292, -1, 621, 285, 287, -1, 621, 670, 285, -1, 631, 669, 666, -1, 631, 666, 632, -1, 636, 563, 564, -1, 617, 616, 658, -1, 636, 564, 634, -1, 617, 658, 672, -1, 627, 72, 671, -1, 620, 670, 621, -1, 627, 63, 72, -1, 627, 668, 628, -1, 620, 673, 670, -1, 627, 671, 668, -1, 618, 562, 563, -1, 623, 672, 639, -1, 618, 563, 636, -1, 623, 617, 672, -1, 624, 621, 287, -1, 629, 669, 631, -1, 629, 628, 669, -1, 635, 634, 673, -1, 635, 673, 620, -1, 615, 632, 616, -1, 614, 561, 562, -1, 674, 47, 49, -1, 675, 674, 49, -1, 41, 574, 575, -1, 41, 575, 576, -1, 41, 576, 578, -1, 41, 578, 36, -1, 460, 676, 458, -1, 677, 49, 50, -1, 677, 50, 678, -1, 679, 677, 678, -1, 679, 678, 680, -1, 679, 49, 677, -1, 681, 679, 680, -1, 681, 682, 683, -1, 681, 680, 682, -1, 681, 49, 679, -1, 684, 675, 49, -1, 684, 49, 681, -1, 684, 683, 685, -1, 684, 681, 683, -1, 686, 458, 676, -1, 686, 685, 687, -1, 686, 675, 684, -1, 686, 684, 685, -1, 686, 687, 458, -1, 686, 676, 675, -1, 688, 466, 468, -1, 688, 689, 690, -1, 688, 690, 43, -1, 688, 691, 689, -1, 688, 468, 691, -1, 692, 43, 44, -1, 692, 44, 693, -1, 692, 688, 43, -1, 692, 694, 466, -1, 692, 693, 695, -1, 692, 466, 688, -1, 692, 695, 694, -1, 696, 693, 44, -1, 696, 695, 693, -1, 696, 694, 695, -1, 697, 464, 466, -1, 697, 694, 696, -1, 697, 466, 694, -1, 697, 696, 44, -1, 698, 44, 46, -1, 698, 699, 700, -1, 698, 464, 697, -1, 698, 697, 44, -1, 698, 46, 699, -1, 698, 701, 464, -1, 698, 700, 702, -1, 698, 702, 701, -1, 703, 700, 699, -1, 703, 699, 46, -1, 703, 702, 700, -1, 703, 701, 702, -1, 704, 462, 464, -1, 704, 703, 46, -1, 148, 458, 687, -1, 704, 701, 703, -1, 705, 41, 42, -1, 704, 464, 701, -1, 706, 705, 42, -1, 706, 41, 705, -1, 707, 46, 47, -1, 707, 704, 46, -1, 708, 706, 42, -1, 707, 47, 709, -1, 708, 41, 706, -1, 710, 709, 711, -1, 710, 711, 712, -1, 713, 708, 42, -1, 710, 704, 707, -1, 713, 574, 41, -1, 710, 712, 462, -1, 713, 41, 708, -1, 710, 462, 704, -1, 710, 707, 709, -1, 714, 711, 709, -1, 470, 429, 574, -1, 714, 712, 711, -1, 470, 574, 713, -1, 690, 42, 43, -1, 714, 709, 47, -1, 689, 42, 690, -1, 715, 712, 714, -1, 715, 460, 462, -1, 715, 462, 712, -1, 691, 470, 713, -1, 715, 714, 47, -1, 691, 42, 689, -1, 691, 713, 42, -1, 468, 470, 691, -1, 716, 715, 47, -1, 716, 47, 674, -1, 717, 674, 675, -1, 717, 676, 460, -1, 717, 716, 674, -1, 717, 715, 716, -1, 717, 675, 676, -1, 717, 460, 715, -1, 718, 66, 65, -1, 667, 718, 65, -1, 719, 718, 667, -1, 663, 719, 667, -1, 720, 719, 663, -1, 660, 720, 663, -1, 721, 720, 660, -1, 654, 721, 660, -1, 647, 722, 721, -1, 647, 721, 654, -1, 640, 723, 722, -1, 640, 722, 647, -1, 296, 486, 723, -1, 296, 723, 640, -1, 724, 725, 726, -1, 152, 151, 727, -1, 728, 678, 50, -1, 728, 50, 52, -1, 729, 680, 678, -1, 729, 678, 728, -1, 730, 683, 682, -1, 730, 682, 680, -1, 730, 680, 729, -1, 731, 53, 55, -1, 731, 52, 53, -1, 731, 55, 732, -1, 731, 728, 52, -1, 733, 683, 730, -1, 734, 735, 736, -1, 734, 732, 735, -1, 734, 729, 728, -1, 734, 728, 731, -1, 734, 731, 732, -1, 725, 685, 683, -1, 725, 683, 733, -1, 737, 736, 738, -1, 737, 730, 729, -1, 737, 734, 736, -1, 737, 729, 734, -1, 739, 148, 687, -1, 739, 687, 685, -1, 739, 149, 148, -1, 739, 685, 725, -1, 740, 738, 741, -1, 740, 730, 737, -1, 740, 733, 730, -1, 740, 737, 738, -1, 726, 740, 741, -1, 726, 733, 740, -1, 726, 725, 733, -1, 724, 741, 727, -1, 724, 151, 149, -1, 724, 149, 739, -1, 724, 727, 151, -1, 724, 739, 725, -1, 724, 726, 741, -1, 524, 742, 113, -1, 489, 491, 743, -1, 718, 525, 66, -1, 486, 487, 723, -1, 744, 524, 525, -1, 744, 742, 524, -1, 745, 746, 742, -1, 745, 742, 744, -1, 747, 748, 746, -1, 747, 746, 745, -1, 749, 750, 748, -1, 749, 748, 747, -1, 751, 752, 750, -1, 751, 750, 749, -1, 753, 487, 489, -1, 753, 743, 752, -1, 753, 489, 743, -1, 753, 752, 751, -1, 754, 745, 744, -1, 754, 753, 751, -1, 754, 487, 753, -1, 754, 751, 749, -1, 754, 747, 745, -1, 754, 744, 525, -1, 754, 749, 747, -1, 755, 754, 525, -1, 755, 487, 754, -1, 756, 718, 719, -1, 756, 719, 720, -1, 756, 720, 721, -1, 756, 721, 722, -1, 756, 722, 723, -1, 756, 487, 755, -1, 756, 525, 718, -1, 756, 755, 525, -1, 756, 723, 487, -1, 757, 758, 1, -1, 759, 760, 436, -1, 759, 436, 758, -1, 759, 757, 0, -1, 759, 758, 757, -1, 759, 0, 761, -1, 759, 761, 762, -1, 763, 764, 3, -1, 759, 762, 760, -1, 765, 763, 3, -1, 765, 432, 434, -1, 766, 761, 0, -1, 766, 762, 761, -1, 767, 3, 7, -1, 766, 760, 762, -1, 768, 434, 436, -1, 769, 767, 7, -1, 768, 436, 760, -1, 769, 3, 767, -1, 768, 760, 766, -1, 768, 766, 0, -1, 770, 432, 765, -1, 771, 763, 765, -1, 771, 764, 763, -1, 770, 3, 769, -1, 771, 434, 768, -1, 770, 430, 432, -1, 771, 0, 3, -1, 770, 765, 3, -1, 771, 765, 434, -1, 772, 7, 8, -1, 771, 768, 0, -1, 771, 3, 764, -1, 772, 8, 773, -1, 774, 772, 773, -1, 774, 773, 775, -1, 774, 7, 772, -1, 776, 775, 777, -1, 776, 7, 774, -1, 776, 774, 775, -1, 778, 769, 7, -1, 778, 7, 776, -1, 778, 776, 777, -1, 779, 770, 769, -1, 779, 430, 770, -1, 779, 777, 780, -1, 779, 769, 778, -1, 779, 778, 777, -1, 779, 780, 430, -1, 781, 152, 727, -1, 781, 727, 741, -1, 781, 741, 738, -1, 781, 738, 736, -1, 781, 736, 735, -1, 782, 735, 732, -1, 782, 732, 55, -1, 782, 55, 57, -1, 782, 781, 735, -1, 783, 781, 782, -1, 784, 442, 152, -1, 784, 783, 782, -1, 784, 781, 783, -1, 784, 152, 781, -1, 784, 782, 57, -1, 784, 785, 442, -1, 786, 787, 788, -1, 786, 784, 57, -1, 786, 785, 784, -1, 786, 57, 787, -1, 786, 788, 789, -1, 786, 789, 785, -1, 790, 788, 787, -1, 790, 787, 58, -1, 790, 789, 788, -1, 790, 785, 789, -1, 791, 440, 442, -1, 791, 790, 58, -1, 791, 785, 790, -1, 791, 442, 785, -1, 792, 58, 60, -1, 792, 60, 793, -1, 792, 791, 58, -1, 369, 430, 780, -1, 787, 57, 58, -1, 794, 791, 792, -1, 795, 796, 797, -1, 795, 798, 796, -1, 795, 791, 794, -1, 795, 792, 793, -1, 795, 794, 792, -1, 795, 797, 440, -1, 795, 440, 791, -1, 795, 793, 798, -1, 799, 797, 796, -1, 799, 796, 798, -1, 799, 793, 60, -1, 799, 798, 793, -1, 800, 438, 440, -1, 800, 799, 60, -1, 800, 440, 797, -1, 800, 797, 799, -1, 801, 60, 1, -1, 801, 1, 802, -1, 801, 800, 60, -1, 803, 804, 438, -1, 803, 805, 806, -1, 803, 438, 800, -1, 803, 806, 804, -1, 803, 800, 801, -1, 803, 801, 802, -1, 803, 802, 805, -1, 807, 806, 805, -1, 807, 802, 1, -1, 807, 804, 806, -1, 807, 805, 802, -1, 758, 436, 438, -1, 758, 438, 804, -1, 758, 807, 1, -1, 758, 804, 807, -1, 757, 1, 0, -1, 808, 743, 491, -1, 808, 491, 389, -1, 809, 752, 743, -1, 809, 743, 808, -1, 810, 750, 752, -1, 810, 752, 809, -1, 811, 748, 750, -1, 811, 750, 810, -1, 746, 748, 811, -1, 812, 746, 811, -1, 742, 746, 812, -1, 813, 742, 812, -1, 113, 742, 813, -1, 112, 113, 813, -1, 814, 815, 372, -1, 814, 816, 815, -1, 814, 817, 816, -1, 814, 818, 817, -1, 819, 380, 820, -1, 814, 11, 821, -1, 814, 821, 818, -1, 822, 11, 814, -1, 822, 369, 780, -1, 823, 824, 380, -1, 822, 780, 777, -1, 823, 380, 819, -1, 822, 777, 775, -1, 25, 824, 823, -1, 822, 775, 773, -1, 822, 773, 8, -1, 25, 29, 824, -1, 822, 8, 11, -1, 822, 372, 369, -1, 825, 378, 376, -1, 822, 814, 372, -1, 826, 378, 825, -1, 827, 378, 826, -1, 827, 820, 378, -1, 828, 819, 820, -1, 828, 820, 827, -1, 829, 823, 819, -1, 829, 819, 828, -1, 829, 828, 19, -1, 829, 25, 823, -1, 23, 25, 829, -1, 23, 829, 19, -1, 830, 825, 376, -1, 830, 376, 374, -1, 831, 825, 830, -1, 831, 826, 825, -1, 832, 831, 18, -1, 832, 826, 831, -1, 832, 827, 826, -1, 833, 832, 18, -1, 833, 828, 827, -1, 833, 19, 828, -1, 833, 827, 832, -1, 834, 18, 19, -1, 834, 833, 18, -1, 834, 19, 833, -1, 835, 830, 374, -1, 836, 831, 830, -1, 836, 18, 831, -1, 836, 830, 835, -1, 836, 835, 13, -1, 837, 836, 13, -1, 837, 18, 836, -1, 838, 837, 13, -1, 838, 18, 837, -1, 839, 13, 18, -1, 839, 838, 13, -1, 839, 18, 838, -1, 815, 374, 372, -1, 815, 835, 374, -1, 815, 13, 835, -1, 816, 13, 815, -1, 817, 13, 816, -1, 818, 13, 817, -1, 821, 11, 13, -1, 821, 13, 818, -1, 840, 841, 388, -1, 840, 842, 841, -1, 840, 843, 842, -1, 840, 844, 843, -1, 840, 845, 844, -1, 840, 846, 845, -1, 840, 39, 846, -1, 847, 388, 386, -1, 847, 840, 388, -1, 848, 840, 847, -1, 849, 35, 39, -1, 849, 850, 35, -1, 849, 847, 386, -1, 849, 840, 848, -1, 849, 848, 847, -1, 849, 39, 840, -1, 851, 852, 850, -1, 851, 849, 386, -1, 851, 853, 854, -1, 851, 850, 849, -1, 851, 854, 852, -1, 851, 386, 853, -1, 855, 35, 850, -1, 856, 384, 382, -1, 855, 850, 852, -1, 855, 854, 853, -1, 855, 852, 854, -1, 857, 856, 382, -1, 858, 386, 384, -1, 858, 855, 853, -1, 858, 853, 386, -1, 859, 855, 858, -1, 860, 382, 380, -1, 861, 32, 35, -1, 861, 858, 384, -1, 862, 860, 380, -1, 861, 35, 855, -1, 861, 859, 858, -1, 861, 855, 859, -1, 863, 384, 856, -1, 864, 862, 380, -1, 863, 861, 384, -1, 865, 866, 32, -1, 865, 857, 866, -1, 865, 856, 857, -1, 824, 864, 380, -1, 865, 32, 861, -1, 865, 863, 856, -1, 865, 861, 863, -1, 867, 29, 32, -1, 867, 32, 866, -1, 867, 382, 860, -1, 868, 380, 378, -1, 867, 866, 857, -1, 867, 862, 864, -1, 867, 860, 862, -1, 867, 857, 382, -1, 820, 380, 868, -1, 867, 824, 29, -1, 867, 864, 824, -1, 820, 868, 378, -1, 869, 870, 405, -1, 869, 871, 870, -1, 872, 397, 873, -1, 869, 874, 871, -1, 869, 875, 874, -1, 869, 84, 876, -1, 869, 876, 875, -1, 877, 84, 869, -1, 878, 879, 397, -1, 877, 405, 407, -1, 877, 880, 81, -1, 878, 397, 872, -1, 877, 881, 880, -1, 98, 879, 878, -1, 877, 882, 881, -1, 877, 883, 882, -1, 98, 102, 879, -1, 877, 407, 883, -1, 877, 81, 84, -1, 884, 399, 401, -1, 877, 869, 405, -1, 885, 399, 884, -1, 886, 399, 885, -1, 886, 873, 399, -1, 887, 873, 886, -1, 887, 872, 873, -1, 888, 878, 872, -1, 888, 872, 887, -1, 888, 887, 92, -1, 888, 98, 878, -1, 95, 888, 92, -1, 95, 98, 888, -1, 889, 884, 401, -1, 889, 401, 403, -1, 890, 884, 889, -1, 890, 885, 884, -1, 891, 886, 885, -1, 891, 885, 890, -1, 891, 890, 89, -1, 892, 887, 886, -1, 892, 92, 887, -1, 892, 886, 891, -1, 892, 891, 89, -1, 893, 92, 892, -1, 893, 89, 92, -1, 893, 892, 89, -1, 894, 889, 403, -1, 895, 89, 890, -1, 895, 894, 86, -1, 895, 890, 889, -1, 895, 889, 894, -1, 896, 89, 895, -1, 896, 895, 86, -1, 897, 896, 86, -1, 897, 89, 896, -1, 898, 86, 89, -1, 898, 897, 86, -1, 898, 89, 897, -1, 870, 403, 405, -1, 870, 86, 894, -1, 870, 894, 403, -1, 871, 86, 870, -1, 874, 86, 871, -1, 875, 86, 874, -1, 876, 84, 86, -1, 876, 86, 875, -1, 899, 112, 813, -1, 899, 813, 812, -1, 899, 812, 811, -1, 899, 811, 810, -1, 899, 810, 809, -1, 899, 809, 808, -1, 899, 808, 389, -1, 900, 389, 391, -1, 900, 899, 389, -1, 901, 899, 900, -1, 902, 108, 112, -1, 902, 903, 108, -1, 902, 112, 899, -1, 902, 900, 391, -1, 902, 899, 901, -1, 902, 901, 900, -1, 904, 905, 906, -1, 904, 391, 905, -1, 904, 902, 391, -1, 904, 906, 907, -1, 904, 903, 902, -1, 904, 907, 903, -1, 908, 108, 903, -1, 909, 393, 395, -1, 908, 906, 905, -1, 908, 907, 906, -1, 908, 903, 907, -1, 910, 391, 393, -1, 911, 909, 395, -1, 910, 905, 391, -1, 910, 908, 905, -1, 912, 908, 910, -1, 913, 395, 397, -1, 914, 105, 108, -1, 914, 910, 393, -1, 915, 913, 397, -1, 914, 912, 910, -1, 914, 908, 912, -1, 914, 108, 908, -1, 916, 914, 393, -1, 917, 915, 397, -1, 916, 393, 909, -1, 918, 919, 105, -1, 918, 909, 911, -1, 918, 911, 919, -1, 918, 105, 914, -1, 879, 917, 397, -1, 918, 914, 916, -1, 918, 916, 909, -1, 920, 102, 105, -1, 920, 105, 919, -1, 921, 397, 399, -1, 920, 395, 913, -1, 920, 915, 917, -1, 920, 913, 915, -1, 920, 911, 395, -1, 920, 879, 102, -1, 873, 397, 921, -1, 920, 919, 911, -1, 873, 921, 399, -1, 920, 917, 879, -1, 841, 922, 505, -1, 841, 505, 388, -1, 842, 923, 922, -1, 842, 922, 841, -1, 843, 924, 923, -1, 843, 923, 842, -1, 844, 925, 924, -1, 844, 924, 843, -1, 926, 925, 844, -1, 845, 926, 844, -1, 927, 926, 845, -1, 846, 927, 845, -1, 40, 927, 846, -1, 39, 40, 846, -1, 928, 929, 74, -1, 930, 931, 479, -1, 930, 479, 929, -1, 930, 928, 73, -1, 930, 929, 928, -1, 930, 73, 932, -1, 930, 932, 933, -1, 934, 935, 76, -1, 930, 933, 931, -1, 936, 934, 76, -1, 936, 483, 481, -1, 937, 932, 73, -1, 937, 933, 932, -1, 937, 931, 933, -1, 938, 76, 80, -1, 939, 481, 479, -1, 940, 76, 938, -1, 939, 479, 931, -1, 940, 938, 80, -1, 939, 931, 937, -1, 939, 937, 73, -1, 941, 483, 936, -1, 942, 934, 936, -1, 941, 76, 940, -1, 942, 935, 934, -1, 942, 481, 939, -1, 941, 485, 483, -1, 942, 73, 76, -1, 941, 936, 76, -1, 942, 936, 481, -1, 943, 81, 880, -1, 942, 939, 73, -1, 942, 76, 935, -1, 943, 80, 81, -1, 944, 880, 881, -1, 944, 80, 943, -1, 944, 943, 880, -1, 945, 881, 882, -1, 945, 944, 881, -1, 945, 80, 944, -1, 946, 940, 80, -1, 946, 945, 882, -1, 946, 80, 945, -1, 947, 882, 883, -1, 947, 940, 946, -1, 947, 941, 940, -1, 947, 485, 941, -1, 947, 946, 882, -1, 947, 883, 485, -1, 948, 949, 950, -1, 948, 951, 949, -1, 948, 952, 951, -1, 948, 953, 952, -1, 948, 155, 953, -1, 954, 955, 128, -1, 954, 950, 955, -1, 954, 128, 130, -1, 954, 948, 950, -1, 956, 948, 954, -1, 957, 473, 155, -1, 957, 948, 956, -1, 957, 958, 473, -1, 957, 155, 948, -1, 957, 956, 954, -1, 957, 954, 130, -1, 959, 957, 130, -1, 959, 960, 958, -1, 959, 961, 962, -1, 959, 130, 961, -1, 959, 962, 960, -1, 959, 958, 957, -1, 963, 958, 960, -1, 963, 962, 961, -1, 963, 960, 962, -1, 963, 961, 131, -1, 964, 475, 473, -1, 964, 958, 963, -1, 964, 473, 958, -1, 964, 963, 131, -1, 965, 131, 133, -1, 965, 964, 131, -1, 965, 133, 966, -1, 407, 485, 883, -1, 961, 130, 131, -1, 967, 964, 965, -1, 968, 965, 966, -1, 968, 966, 969, -1, 968, 969, 970, -1, 968, 475, 964, -1, 968, 967, 965, -1, 968, 964, 967, -1, 968, 971, 475, -1, 968, 970, 971, -1, 972, 969, 966, -1, 972, 970, 969, -1, 972, 966, 133, -1, 972, 971, 970, -1, 973, 477, 475, -1, 973, 475, 971, -1, 973, 972, 133, -1, 973, 971, 972, -1, 974, 133, 74, -1, 974, 74, 975, -1, 974, 973, 133, -1, 976, 977, 477, -1, 976, 978, 979, -1, 976, 975, 978, -1, 976, 979, 977, -1, 976, 477, 973, -1, 976, 974, 975, -1, 976, 973, 974, -1, 980, 979, 978, -1, 980, 975, 74, -1, 980, 978, 975, -1, 980, 977, 979, -1, 929, 479, 477, -1, 929, 477, 977, -1, 929, 980, 74, -1, 929, 977, 980, -1, 928, 74, 73, -1, 520, 927, 40, -1, 503, 505, 922, -1, 981, 521, 139, -1, 500, 501, 982, -1, 983, 520, 521, -1, 983, 927, 520, -1, 984, 926, 927, -1, 984, 927, 983, -1, 985, 925, 926, -1, 985, 926, 984, -1, 986, 924, 925, -1, 986, 925, 985, -1, 987, 923, 924, -1, 987, 924, 986, -1, 988, 922, 923, -1, 988, 501, 503, -1, 988, 503, 922, -1, 988, 923, 987, -1, 989, 986, 985, -1, 989, 983, 521, -1, 989, 988, 987, -1, 989, 985, 984, -1, 989, 987, 986, -1, 989, 984, 983, -1, 989, 501, 988, -1, 990, 989, 521, -1, 990, 501, 989, -1, 991, 992, 982, -1, 991, 993, 992, -1, 991, 994, 993, -1, 991, 995, 994, -1, 991, 981, 995, -1, 991, 990, 521, -1, 991, 501, 990, -1, 991, 521, 981, -1, 991, 982, 501, -1, 996, 997, 998, -1, 955, 126, 128, -1, 999, 1000, 123, -1, 999, 123, 125, -1, 1001, 1002, 1000, -1, 1001, 1000, 999, -1, 1003, 1004, 1002, -1, 1003, 1002, 1001, -1, 1005, 125, 126, -1, 1005, 999, 125, -1, 1005, 126, 955, -1, 1006, 1007, 1004, -1, 1006, 1004, 1003, -1, 1008, 955, 950, -1, 1008, 950, 949, -1, 1008, 1001, 999, -1, 1008, 1005, 955, -1, 1008, 999, 1005, -1, 997, 1009, 1007, -1, 997, 1007, 1006, -1, 1010, 1008, 949, -1, 1010, 1001, 1008, -1, 1010, 1003, 1001, -1, 1011, 159, 160, -1, 1011, 1012, 1009, -1, 1011, 160, 1012, -1, 1011, 1009, 997, -1, 1013, 949, 951, -1, 1013, 951, 952, -1, 1013, 1006, 1003, -1, 1013, 1003, 1010, -1, 1013, 1010, 949, -1, 998, 997, 1006, -1, 998, 1013, 952, -1, 998, 1006, 1013, -1, 996, 952, 953, -1, 996, 953, 155, -1, 996, 157, 159, -1, 996, 155, 157, -1, 996, 998, 952, -1, 996, 159, 1011, -1, 996, 1011, 997, -1, 981, 139, 138, -1, 1014, 981, 138, -1, 995, 981, 1014, -1, 1015, 995, 1014, -1, 994, 995, 1015, -1, 1016, 994, 1015, -1, 1017, 993, 994, -1, 1017, 994, 1016, -1, 1018, 992, 993, -1, 1018, 993, 1017, -1, 1019, 982, 992, -1, 1019, 992, 1018, -1, 299, 500, 982, -1, 299, 982, 1019, -1, 1020, 120, 122, -1, 1021, 1020, 122, -1, 114, 1022, 109, -1, 114, 1023, 1022, -1, 114, 1024, 1023, -1, 114, 1025, 1024, -1, 455, 1026, 457, -1, 1027, 123, 1000, -1, 1027, 122, 123, -1, 1028, 1000, 1002, -1, 1028, 122, 1027, -1, 1028, 1027, 1000, -1, 1029, 1002, 1004, -1, 1029, 1004, 1007, -1, 1029, 1028, 1002, -1, 1029, 122, 1028, -1, 1030, 1007, 1009, -1, 1030, 1021, 122, -1, 1030, 122, 1029, -1, 1030, 1029, 1007, -1, 1031, 1009, 1012, -1, 1031, 457, 1026, -1, 1031, 1030, 1009, -1, 1031, 1021, 1030, -1, 1031, 1012, 457, -1, 1031, 1026, 1021, -1, 1032, 449, 447, -1, 1032, 1033, 1034, -1, 1032, 1035, 1033, -1, 1032, 1034, 116, -1, 1032, 447, 1035, -1, 1036, 116, 117, -1, 1036, 1032, 116, -1, 1036, 1037, 1038, -1, 1036, 449, 1032, -1, 1036, 1039, 449, -1, 1036, 1038, 1039, -1, 1036, 117, 1037, -1, 1040, 1038, 1037, -1, 1040, 1039, 1038, -1, 1040, 1037, 117, -1, 1041, 451, 449, -1, 1041, 1040, 117, -1, 1041, 1039, 1040, -1, 1041, 449, 1039, -1, 1042, 117, 119, -1, 1042, 451, 1041, -1, 1042, 1043, 1044, -1, 1042, 119, 1043, -1, 1042, 1045, 451, -1, 1042, 1041, 117, -1, 1042, 1044, 1046, -1, 1042, 1046, 1045, -1, 1047, 1044, 1043, -1, 1047, 1043, 119, -1, 1047, 1046, 1044, -1, 1047, 1045, 1046, -1, 1048, 453, 451, -1, 1048, 1047, 119, -1, 160, 457, 1012, -1, 1048, 1045, 1047, -1, 1049, 114, 115, -1, 1048, 451, 1045, -1, 1050, 114, 1049, -1, 1051, 119, 120, -1, 1050, 1049, 115, -1, 1051, 1048, 119, -1, 1052, 114, 1050, -1, 1051, 120, 1053, -1, 1052, 1050, 115, -1, 1054, 1053, 1055, -1, 1054, 1055, 1056, -1, 1057, 1025, 114, -1, 1054, 1048, 1051, -1, 1054, 1056, 453, -1, 1054, 453, 1048, -1, 1057, 114, 1052, -1, 1054, 1051, 1053, -1, 1057, 1052, 115, -1, 1058, 1055, 1053, -1, 445, 350, 1025, -1, 1058, 1056, 1055, -1, 445, 1025, 1057, -1, 1034, 115, 116, -1, 1058, 1053, 120, -1, 1033, 115, 1034, -1, 1059, 1056, 1058, -1, 1059, 455, 453, -1, 1059, 453, 1056, -1, 1035, 115, 1033, -1, 1059, 1058, 120, -1, 1035, 1057, 115, -1, 1060, 120, 1020, -1, 1035, 445, 1057, -1, 447, 445, 1035, -1, 1060, 1059, 120, -1, 1061, 1026, 455, -1, 1061, 1060, 1020, -1, 1061, 1059, 1060, -1, 1061, 1020, 1021, -1, 1061, 1021, 1026, -1, 1061, 455, 1059, -1, 1062, 1063, 1064, -1, 1065, 1066, 1067, -1, 1068, 1069, 1070, -1, 1065, 1067, 1071, -1, 1068, 1064, 1069, -1, 1072, 136, 1073, -1, 1072, 1073, 1074, -1, 1075, 1076, 1062, -1, 1072, 1074, 1077, -1, 1075, 1078, 1076, -1, 1079, 1065, 1071, -1, 1080, 1064, 1068, -1, 1079, 1071, 1081, -1, 1082, 1066, 1065, -1, 1080, 1062, 1064, -1, 1082, 1083, 1066, -1, 1084, 308, 306, -1, 1084, 1070, 308, -1, 1085, 1019, 1018, -1, 1085, 1086, 301, -1, 1085, 301, 1019, -1, 1087, 1088, 1078, -1, 1087, 1078, 1075, -1, 1089, 1065, 1079, -1, 1090, 1075, 1062, -1, 1089, 1082, 1065, -1, 1090, 1062, 1080, -1, 1091, 1068, 1070, -1, 1092, 1077, 1083, -1, 1092, 1083, 1082, -1, 143, 140, 1093, -1, 1091, 1070, 1084, -1, 1094, 1085, 1018, -1, 1094, 1081, 1086, -1, 1095, 1084, 306, -1, 1094, 1086, 1085, -1, 1096, 144, 1097, -1, 1098, 1082, 1089, -1, 1096, 1097, 1088, -1, 1098, 1092, 1082, -1, 1096, 1088, 1087, -1, 1099, 134, 136, -1, 1100, 1075, 1090, -1, 1099, 136, 1072, -1, 1100, 1087, 1075, -1, 1099, 1072, 1077, -1, 1099, 1077, 1092, -1, 1101, 1018, 1017, -1, 1101, 1017, 1016, -1, 1102, 1080, 1068, -1, 1101, 1081, 1094, -1, 1101, 1079, 1081, -1, 1102, 1068, 1091, -1, 1103, 1091, 1084, -1, 1101, 1094, 1018, -1, 1104, 134, 1099, -1, 1103, 1084, 1095, -1, 1104, 1092, 1098, -1, 1105, 1096, 1087, -1, 1104, 1099, 1092, -1, 1105, 145, 144, -1, 1019, 301, 299, -1, 1105, 1087, 1100, -1, 1106, 1089, 1079, -1, 1105, 144, 1096, -1, 1106, 1079, 1101, -1, 1107, 1080, 1102, -1, 1106, 1101, 1016, -1, 1108, 1016, 1015, -1, 1107, 1090, 1080, -1, 1109, 1095, 306, -1, 1108, 1089, 1106, -1, 1108, 1098, 1089, -1, 1109, 306, 303, -1, 1108, 1106, 1016, -1, 1110, 1104, 1098, -1, 1110, 1015, 1014, -1, 1110, 137, 134, -1, 1110, 134, 1104, -1, 1111, 1091, 1103, -1, 1110, 1014, 137, -1, 1110, 1098, 1108, -1, 1111, 1102, 1091, -1, 1110, 1108, 1015, -1, 1112, 1100, 1090, -1, 1112, 1090, 1107, -1, 1067, 1095, 1109, -1, 1067, 1103, 1095, -1, 1113, 1107, 1102, -1, 138, 137, 1014, -1, 1113, 1102, 1111, -1, 1114, 1115, 312, -1, 1116, 145, 1105, -1, 1116, 1105, 1100, -1, 1114, 312, 310, -1, 1116, 1100, 1112, -1, 1063, 1117, 1115, -1, 1066, 1111, 1103, -1, 1066, 1103, 1067, -1, 1063, 1115, 1114, -1, 1076, 1118, 1117, -1, 1119, 1109, 303, -1, 1076, 1117, 1063, -1, 1074, 1107, 1113, -1, 1074, 1112, 1107, -1, 1078, 1120, 1118, -1, 1078, 1118, 1076, -1, 1083, 1113, 1111, -1, 1083, 1111, 1066, -1, 1069, 310, 308, -1, 1086, 303, 301, -1, 1069, 1114, 310, -1, 1086, 1119, 303, -1, 1088, 1121, 1120, -1, 1071, 1067, 1109, -1, 1088, 1120, 1078, -1, 1071, 1109, 1119, -1, 1073, 136, 145, -1, 1064, 1063, 1114, -1, 1073, 1116, 1112, -1, 1073, 145, 1116, -1, 1064, 1114, 1069, -1, 1073, 1112, 1074, -1, 1070, 1069, 308, -1, 1077, 1074, 1113, -1, 1077, 1113, 1083, -1, 1097, 144, 143, -1, 1097, 1093, 1121, -1, 1097, 143, 1093, -1, 1097, 1121, 1088, -1, 1081, 1119, 1086, -1, 1062, 1076, 1063, -1, 1081, 1071, 1119, -1, 1122, 82, 87, -1, 1122, 1123, 82, -1, 1124, 1125, 355, -1, 1122, 1126, 1127, -1, 1122, 1127, 1123, -1, 1122, 87, 1126, -1, 1124, 354, 1125, -1, 1128, 109, 1022, -1, 1128, 1022, 1023, -1, 1128, 1023, 1024, -1, 1128, 1024, 1025, -1, 1129, 354, 1124, -1, 1128, 1025, 350, -1, 1128, 350, 349, -1, 1128, 106, 109, -1, 1129, 1130, 354, -1, 1131, 100, 104, -1, 1132, 1133, 1134, -1, 1131, 97, 100, -1, 1132, 349, 1135, -1, 1131, 1136, 1130, -1, 1132, 1135, 1133, -1, 1132, 1128, 349, -1, 1131, 104, 1136, -1, 1132, 106, 1128, -1, 1131, 1130, 1129, -1, 1132, 1137, 106, -1, 1132, 1134, 1137, -1, 1138, 355, 357, -1, 1139, 77, 82, -1, 1140, 355, 1138, -1, 1139, 82, 1123, -1, 1139, 1141, 366, -1, 1139, 1142, 1141, -1, 1139, 1143, 1142, -1, 1139, 1123, 1143, -1, 1144, 355, 1140, -1, 1145, 366, 368, -1, 1145, 1146, 77, -1, 1145, 1147, 1146, -1, 1144, 1124, 355, -1, 1145, 1148, 1147, -1, 1145, 1149, 1148, -1, 1145, 1150, 1149, -1, 1145, 1151, 1150, -1, 1145, 368, 1151, -1, 1152, 1124, 1144, -1, 1145, 77, 1139, -1, 1145, 1139, 366, -1, 1152, 1129, 1124, -1, 1153, 1131, 1129, -1, 1153, 97, 1131, -1, 1153, 1129, 1152, -1, 1154, 357, 359, -1, 1154, 1138, 357, -1, 1155, 1140, 1138, -1, 1155, 1138, 1154, -1, 1156, 1144, 1140, -1, 1156, 1140, 1155, -1, 1157, 1152, 1144, -1, 1157, 1144, 1156, -1, 1158, 1152, 1157, -1, 1158, 1153, 1152, -1, 1158, 97, 1153, -1, 1158, 94, 97, -1, 1159, 359, 361, -1, 1159, 1154, 359, -1, 1160, 1155, 1154, -1, 1160, 1154, 1159, -1, 1161, 1156, 1155, -1, 1161, 1155, 1160, -1, 1162, 1157, 1156, -1, 1162, 1156, 1161, -1, 1163, 90, 94, -1, 1163, 94, 1158, -1, 1163, 87, 90, -1, 1163, 1157, 1162, -1, 1163, 1158, 1157, -1, 1164, 361, 363, -1, 1164, 1159, 361, -1, 1165, 1159, 1164, -1, 1165, 1164, 363, -1, 1135, 349, 352, -1, 1165, 1160, 1159, -1, 1166, 1161, 1160, -1, 1133, 1135, 352, -1, 1166, 1160, 1165, -1, 1127, 1161, 1166, -1, 1134, 1133, 352, -1, 1127, 1162, 1161, -1, 1126, 87, 1163, -1, 106, 1137, 104, -1, 1126, 1163, 1162, -1, 1167, 352, 354, -1, 1126, 1162, 1127, -1, 1141, 363, 366, -1, 1168, 1167, 354, -1, 1168, 352, 1167, -1, 1169, 1168, 354, -1, 1169, 352, 1168, -1, 1142, 1165, 363, -1, 1130, 352, 1169, -1, 1130, 1134, 352, -1, 1130, 1169, 354, -1, 1142, 363, 1141, -1, 1136, 1134, 1130, -1, 1136, 1137, 1134, -1, 1136, 104, 1137, -1, 1143, 1166, 1165, -1, 1170, 354, 355, -1, 1143, 1165, 1142, -1, 1125, 1170, 355, -1, 1123, 1127, 1166, -1, 1123, 1166, 1143, -1, 1125, 354, 1170, -1, 1171, 1093, 140, -1, 1171, 140, 142, -1, 1172, 1121, 1093, -1, 1172, 1093, 1171, -1, 1173, 1120, 1121, -1, 1173, 1121, 1172, -1, 1118, 1120, 1173, -1, 1174, 1118, 1173, -1, 1117, 1118, 1174, -1, 1175, 1117, 1174, -1, 1115, 1117, 1175, -1, 1176, 1115, 1175, -1, 312, 1115, 1176, -1, 513, 312, 1176, -1, 1151, 368, 510, -1, 1177, 1151, 510, -1, 1150, 1151, 1177, -1, 1178, 1150, 1177, -1, 1149, 1150, 1178, -1, 1179, 1149, 1178, -1, 1148, 1149, 1179, -1, 1180, 1148, 1179, -1, 1181, 1147, 1148, -1, 1181, 1148, 1180, -1, 1182, 1146, 1147, -1, 1182, 1147, 1181, -1, 78, 77, 1146, -1, 78, 1146, 1182, -1, 512, 513, 1176, -1, 1182, 523, 78, -1, 510, 509, 1177, -1, 1183, 1171, 142, -1, 1183, 522, 523, -1, 1183, 142, 522, -1, 1184, 1172, 1171, -1, 1184, 1171, 1183, -1, 1185, 1173, 1172, -1, 1185, 1172, 1184, -1, 1186, 1174, 1173, -1, 1186, 1173, 1185, -1, 1187, 1175, 1174, -1, 1187, 1174, 1186, -1, 1188, 1176, 1175, -1, 1188, 509, 512, -1, 1188, 512, 1176, -1, 1188, 1175, 1187, -1, 1189, 1186, 1185, -1, 1189, 1187, 1186, -1, 1189, 1183, 523, -1, 1189, 509, 1188, -1, 1189, 1188, 1187, -1, 1189, 1184, 1183, -1, 1189, 1185, 1184, -1, 1190, 509, 1189, -1, 1190, 1189, 523, -1, 1191, 1182, 1181, -1, 1191, 1181, 1180, -1, 1191, 1180, 1179, -1, 1191, 1179, 1178, -1, 1191, 1178, 1177, -1, 1191, 1190, 523, -1, 1191, 523, 1182, -1, 1191, 509, 1190, -1, 1191, 1177, 509, -1, 1192, 1193, 1194, -1, 1195, 1196, 1197, -1, 1192, 1198, 1199, -1, 1200, 172, 177, -1, 1192, 1201, 1193, -1, 1200, 177, 1195, -1, 1192, 1199, 1201, -1, 1200, 1195, 1197, -1, 1202, 1194, 1203, -1, 1202, 1204, 1198, -1, 1205, 1206, 1207, -1, 1205, 172, 1200, -1, 1202, 1198, 1192, -1, 1205, 1200, 1197, -1, 1202, 1192, 1194, -1, 1208, 1203, 1209, -1, 1205, 1210, 172, -1, 1208, 219, 1211, -1, 1205, 1212, 1206, -1, 1208, 1211, 1204, -1, 1208, 1204, 1202, -1, 1205, 1207, 1210, -1, 1208, 1202, 1203, -1, 1213, 166, 1214, -1, 1208, 1209, 219, -1, 1213, 1215, 165, -1, 1197, 1216, 153, -1, 1213, 1217, 1218, -1, 1197, 1219, 1216, -1, 1213, 1214, 1220, -1, 1197, 1196, 1219, -1, 1213, 1220, 1217, -1, 1213, 1218, 1221, -1, 1213, 1221, 1215, -1, 1213, 165, 166, -1, 1222, 1223, 435, -1, 1197, 153, 443, -1, 1222, 1217, 1224, -1, 1225, 1207, 1206, -1, 1222, 435, 1226, -1, 1225, 1227, 441, -1, 1222, 1224, 1223, -1, 1228, 165, 1215, -1, 1228, 1218, 1217, -1, 1228, 1221, 1218, -1, 1225, 1206, 1212, -1, 1228, 1217, 1222, -1, 1228, 1215, 1221, -1, 1225, 1229, 1227, -1, 1225, 1212, 1229, -1, 1230, 170, 172, -1, 1230, 1225, 441, -1, 1230, 172, 1210, -1, 1231, 164, 165, -1, 1231, 1222, 1226, -1, 1230, 1232, 1233, -1, 1230, 1233, 170, -1, 1231, 165, 1228, -1, 1230, 1207, 1225, -1, 1231, 1234, 164, -1, 1230, 1210, 1207, -1, 1231, 1228, 1222, -1, 1235, 1236, 1237, -1, 1238, 1239, 1240, -1, 1238, 1240, 1241, -1, 1235, 1237, 1242, -1, 1238, 1241, 1232, -1, 1238, 1230, 441, -1, 1235, 1226, 1236, -1, 1238, 1232, 1230, -1, 1238, 441, 1239, -1, 1235, 1231, 1226, -1, 1243, 1244, 1234, -1, 1245, 1239, 439, -1, 1243, 1235, 1242, -1, 1243, 1242, 1246, -1, 1243, 1246, 1244, -1, 1243, 1234, 1231, -1, 1243, 1231, 1235, -1, 1247, 1234, 1244, -1, 1247, 1242, 1237, -1, 1248, 1240, 1239, -1, 1247, 1246, 1242, -1, 1247, 1244, 1246, -1, 1248, 1241, 1240, -1, 1247, 1237, 1249, -1, 1248, 1232, 1241, -1, 1248, 1239, 1245, -1, 1250, 1234, 1247, -1, 1250, 218, 164, -1, 1251, 1232, 1248, -1, 1250, 1247, 1249, -1, 1251, 1252, 166, -1, 1250, 164, 1234, -1, 1251, 166, 170, -1, 1251, 1245, 439, -1, 1251, 1233, 1232, -1, 1253, 1249, 1254, -1, 1251, 170, 1233, -1, 1253, 218, 1250, -1, 1251, 1248, 1245, -1, 1253, 1211, 218, -1, 1253, 1250, 1249, -1, 1255, 439, 437, -1, 1253, 1204, 1211, -1, 1255, 437, 1256, -1, 1255, 1251, 439, -1, 1257, 1254, 1258, -1, 1257, 1259, 1199, -1, 1257, 1258, 1259, -1, 1257, 1199, 1198, -1, 1260, 1261, 1262, -1, 1257, 1198, 1204, -1, 1260, 1255, 1256, -1, 1257, 1253, 1254, -1, 1260, 1251, 1255, -1, 1257, 1204, 1253, -1, 1260, 1256, 1263, -1, 1264, 443, 1227, -1, 1260, 1263, 1261, -1, 1264, 1212, 1205, -1, 1260, 1252, 1251, -1, 1264, 1197, 443, -1, 1260, 1262, 1252, -1, 1264, 1227, 1229, -1, 1264, 1205, 1197, -1, 1264, 1229, 1212, -1, 1265, 1256, 437, -1, 1266, 1262, 1261, -1, 1266, 1256, 1265, -1, 1259, 1258, 431, -1, 1266, 1263, 1256, -1, 1266, 1261, 1263, -1, 1214, 166, 1252, -1, 1214, 1266, 1265, -1, 1214, 1265, 437, -1, 1214, 1262, 1266, -1, 1214, 1252, 1262, -1, 220, 219, 1209, -1, 1227, 443, 441, -1, 1267, 435, 1223, -1, 1268, 431, 371, -1, 1267, 437, 435, -1, 1267, 1214, 437, -1, 1268, 371, 1269, -1, 1267, 1223, 1224, -1, 1220, 1224, 1217, -1, 1220, 1214, 1267, -1, 1220, 1267, 1224, -1, 1211, 219, 218, -1, 1226, 435, 433, -1, 1226, 433, 1236, -1, 1270, 1269, 1271, -1, 1270, 1268, 1269, -1, 1249, 1236, 433, -1, 1270, 431, 1268, -1, 1249, 1237, 1236, -1, 1272, 1271, 1273, -1, 1272, 1259, 431, -1, 1272, 1270, 1271, -1, 1239, 441, 439, -1, 1272, 431, 1270, -1, 1254, 433, 431, -1, 1201, 1274, 1193, -1, 1254, 1249, 433, -1, 1201, 1273, 1274, -1, 1201, 1199, 1259, -1, 1254, 431, 1258, -1, 1195, 1275, 1196, -1, 1195, 1276, 1275, -1, 1201, 1259, 1272, -1, 1195, 1277, 1276, -1, 1201, 1272, 1273, -1, 1195, 177, 1277, -1, 1278, 370, 373, -1, 1279, 1278, 373, -1, 1280, 1278, 1279, -1, 1281, 1278, 1280, -1, 1281, 1282, 1278, -1, 1283, 211, 221, -1, 1283, 1284, 211, -1, 1285, 1286, 1282, -1, 1285, 1282, 1281, -1, 1287, 1286, 1285, -1, 1287, 1288, 1286, -1, 1289, 1288, 1287, -1, 1289, 1290, 1288, -1, 1291, 1284, 1290, -1, 1291, 211, 1284, -1, 1291, 1290, 1289, -1, 1292, 212, 209, -1, 1293, 187, 212, -1, 1294, 183, 187, -1, 1295, 180, 183, -1, 1296, 175, 180, -1, 1297, 173, 175, -1, 1298, 1271, 1269, -1, 1298, 1269, 371, -1, 1298, 371, 370, -1, 1299, 1282, 1286, -1, 1299, 370, 1278, -1, 1299, 1278, 1282, -1, 1300, 209, 211, -1, 1300, 1289, 1287, -1, 1300, 1291, 1289, -1, 1300, 211, 1291, -1, 1301, 209, 1300, -1, 1302, 209, 1301, -1, 1302, 1303, 1304, -1, 1302, 1304, 1292, -1, 1302, 1292, 209, -1, 1305, 1304, 1303, -1, 1305, 1292, 1304, -1, 1305, 212, 1292, -1, 1306, 212, 1305, -1, 1307, 212, 1306, -1, 1307, 1308, 1309, -1, 1307, 1293, 212, -1, 1307, 1309, 1293, -1, 1310, 187, 1293, -1, 1310, 1293, 1309, -1, 1311, 1312, 1313, -1, 1311, 1294, 187, -1, 1311, 1313, 1294, -1, 1314, 1313, 1312, -1, 1315, 183, 1294, -1, 1315, 1294, 1313, -1, 1315, 1313, 1314, -1, 1316, 1315, 1314, -1, 1316, 183, 1315, -1, 1317, 1318, 1319, -1, 1317, 1319, 1320, -1, 1321, 1316, 1317, -1, 1321, 183, 1316, -1, 1321, 1317, 1320, -1, 1321, 1295, 183, -1, 1321, 1320, 1295, -1, 1322, 1320, 1323, -1, 1322, 180, 1295, -1, 1322, 1295, 1320, -1, 1324, 1322, 1323, -1, 1324, 180, 1322, -1, 1325, 1326, 1327, -1, 1325, 1327, 1328, -1, 1329, 180, 1324, -1, 1329, 1328, 1296, -1, 1329, 1296, 180, -1, 1329, 1325, 1328, -1, 1329, 1324, 1325, -1, 1330, 1296, 1328, -1, 1330, 175, 1296, -1, 1331, 175, 1330, -1, 1331, 1332, 1333, -1, 1331, 1333, 1334, -1, 1331, 385, 1332, -1, 1335, 1334, 1336, -1, 1335, 1331, 1334, -1, 1335, 1336, 1337, -1, 1335, 1337, 1338, -1, 1335, 1338, 1297, -1, 1335, 1297, 175, -1, 1335, 175, 1331, -1, 1339, 1336, 1334, -1, 1339, 1337, 1336, -1, 1339, 1338, 1337, -1, 1339, 1334, 1333, -1, 1340, 1338, 1339, -1, 1340, 1297, 1338, -1, 1340, 173, 1297, -1, 1341, 1340, 1339, -1, 1341, 173, 1340, -1, 1341, 385, 387, -1, 1341, 1333, 1332, -1, 1341, 1339, 1333, -1, 1341, 1332, 385, -1, 1342, 1343, 169, -1, 1342, 1344, 1343, -1, 1342, 169, 173, -1, 1342, 173, 1341, -1, 1342, 1341, 1345, -1, 1346, 1344, 1342, -1, 1346, 1341, 387, -1, 1346, 1342, 1345, -1, 1346, 1347, 1344, -1, 1346, 1348, 1347, -1, 1346, 1349, 1348, -1, 1346, 1350, 1349, -1, 1346, 387, 1350, -1, 1346, 1345, 1341, -1, 1351, 1193, 1274, -1, 1351, 1274, 1273, -1, 1351, 1273, 1271, -1, 1351, 1271, 1298, -1, 1352, 1209, 1203, -1, 1352, 1203, 1194, -1, 1352, 1194, 1193, -1, 1352, 1193, 1351, -1, 1353, 220, 1209, -1, 1353, 1209, 1352, -1, 1353, 1352, 1351, -1, 1353, 221, 220, -1, 1353, 1351, 1298, -1, 1353, 1283, 221, -1, 1354, 1283, 1353, -1, 1354, 1284, 1283, -1, 1354, 1290, 1284, -1, 1354, 1299, 1286, -1, 1354, 1286, 1288, -1, 1354, 1353, 1298, -1, 1354, 1288, 1290, -1, 1355, 1279, 373, -1, 1355, 1280, 1279, -1, 1355, 1281, 1280, -1, 1356, 1301, 1300, -1, 1356, 1281, 1355, -1, 1356, 1355, 1357, -1, 1356, 1287, 1285, -1, 1356, 1300, 1287, -1, 1356, 1285, 1281, -1, 1358, 373, 375, -1, 1358, 1357, 1355, -1, 1358, 1301, 1356, -1, 1358, 1356, 1357, -1, 1358, 1355, 373, -1, 1359, 1360, 1361, -1, 1359, 1358, 375, -1, 1359, 375, 1360, -1, 1359, 1361, 1362, -1, 1363, 1302, 1301, -1, 1363, 1362, 1364, -1, 1363, 1364, 1303, -1, 1363, 1301, 1358, -1, 1363, 1359, 1362, -1, 1363, 1358, 1359, -1, 1363, 1303, 1302, -1, 1365, 1361, 1360, -1, 1365, 1364, 1362, -1, 1365, 1360, 375, -1, 1365, 1362, 1361, -1, 1366, 1306, 1305, -1, 1366, 1303, 1364, -1, 1366, 1364, 1365, -1, 1366, 1305, 1303, -1, 1366, 1365, 1367, -1, 1368, 1365, 375, -1, 1368, 375, 377, -1, 1368, 1306, 1366, -1, 1368, 1367, 1365, -1, 1368, 1366, 1367, -1, 1369, 377, 1370, -1, 1369, 1370, 1371, -1, 1369, 1371, 1372, -1, 1369, 1368, 377, -1, 1373, 1306, 1368, -1, 1373, 1374, 1308, -1, 1373, 1368, 1369, -1, 1373, 1369, 1372, -1, 1373, 1307, 1306, -1, 1373, 1308, 1307, -1, 1373, 1372, 1374, -1, 1375, 1371, 1370, -1, 1375, 1372, 1371, -1, 1375, 1374, 1372, -1, 1376, 1308, 1374, -1, 1376, 1309, 1308, -1, 1376, 1310, 1309, -1, 1376, 1374, 1375, -1, 1377, 1370, 377, -1, 1377, 377, 379, -1, 1377, 1375, 1370, -1, 1377, 1310, 1376, -1, 1377, 1376, 1375, -1, 1378, 379, 1379, -1, 1378, 1379, 1380, -1, 1378, 1377, 379, -1, 1381, 1380, 1382, -1, 1381, 1311, 1378, -1, 1381, 1312, 1311, -1, 1381, 1378, 1380, -1, 1381, 1383, 1312, -1, 1381, 1382, 1383, -1, 1384, 379, 381, -1, 1384, 1379, 379, -1, 1384, 1380, 1379, -1, 1384, 1382, 1380, -1, 1384, 1312, 1383, -1, 1384, 1316, 1314, -1, 1384, 1314, 1312, -1, 1384, 1383, 1382, -1, 1385, 1384, 381, -1, 1385, 1317, 1316, -1, 1385, 1386, 1387, -1, 1385, 1316, 1384, -1, 1385, 1387, 1388, -1, 1385, 381, 1386, -1, 1385, 1388, 1318, -1, 1385, 1318, 1317, -1, 1389, 1323, 1320, -1, 1389, 1388, 1387, -1, 1389, 1318, 1388, -1, 1389, 1319, 1318, -1, 1389, 1320, 1319, -1, 1390, 1324, 1323, -1, 1390, 1323, 1389, -1, 1390, 381, 383, -1, 1390, 1387, 1386, -1, 1390, 1386, 381, -1, 1390, 1389, 1387, -1, 1391, 1392, 1326, -1, 1391, 1326, 1325, -1, 1391, 383, 1393, -1, 1391, 1324, 1390, -1, 1391, 1390, 383, -1, 1391, 1393, 1394, -1, 1391, 1325, 1324, -1, 1391, 1394, 1392, -1, 1395, 1326, 1392, -1, 1395, 1327, 1326, -1, 1395, 1328, 1327, -1, 1395, 1330, 1328, -1, 1395, 1394, 1393, -1, 1395, 1392, 1394, -1, 1396, 385, 1331, -1, 1396, 383, 385, -1, 1396, 1393, 383, -1, 1396, 1331, 1330, -1, 1396, 1330, 1395, -1, 1396, 1395, 1393, -1, 1397, 1354, 1298, -1, 1397, 1299, 1354, -1, 1397, 370, 1299, -1, 1397, 1298, 370, -1, 1398, 187, 1310, -1, 1398, 1311, 187, -1, 1398, 1378, 1311, -1, 1398, 1310, 1377, -1, 1398, 1377, 1378, -1, 1399, 1276, 1277, -1, 1399, 1277, 177, -1, 1399, 178, 182, -1, 1399, 177, 178, -1, 1399, 182, 1400, -1, 1399, 1400, 1401, -1, 1399, 1402, 1276, -1, 1399, 1401, 1402, -1, 182, 185, 1403, -1, 1404, 1405, 147, -1, 1404, 147, 146, -1, 1406, 1407, 1405, -1, 1406, 1405, 1404, -1, 1408, 1409, 1407, -1, 1408, 1407, 1406, -1, 1410, 153, 1216, -1, 1410, 150, 153, -1, 1410, 146, 150, -1, 1410, 1404, 146, -1, 1411, 1412, 1409, -1, 1411, 1409, 1408, -1, 1413, 1216, 1219, -1, 1413, 1406, 1404, -1, 1413, 1410, 1216, -1, 1413, 1404, 1410, -1, 1401, 1414, 1412, -1, 1401, 1412, 1411, -1, 1415, 1219, 1196, -1, 1415, 1413, 1219, -1, 1415, 1408, 1406, -1, 1415, 1406, 1413, -1, 1400, 1403, 1414, -1, 1400, 182, 1403, -1, 1400, 1414, 1401, -1, 1416, 1196, 1275, -1, 1416, 1411, 1408, -1, 1416, 1415, 1196, -1, 1416, 1408, 1415, -1, 1402, 1275, 1276, -1, 1402, 1411, 1416, -1, 1402, 1416, 1275, -1, 1402, 1401, 1411, -1, 1417, 1350, 387, -1, 1417, 387, 506, -1, 1418, 1349, 1350, -1, 1418, 1350, 1417, -1, 1419, 1348, 1349, -1, 1419, 1349, 1418, -1, 1347, 1348, 1419, -1, 1420, 1347, 1419, -1, 1344, 1347, 1420, -1, 1421, 1344, 1420, -1, 1343, 1344, 1421, -1, 1422, 1343, 1421, -1, 169, 1343, 1422, -1, 167, 169, 1422, -1, 1423, 1424, 1425, -1, 1423, 1425, 465, -1, 1426, 1405, 1407, -1, 1426, 1427, 1405, -1, 1426, 459, 1427, -1, 1428, 1423, 465, -1, 192, 189, 1429, -1, 192, 1429, 1430, -1, 192, 1430, 188, -1, 1431, 1407, 1409, -1, 1432, 463, 1433, -1, 1431, 1434, 459, -1, 1432, 465, 463, -1, 1431, 459, 1426, -1, 1432, 1428, 465, -1, 1432, 1433, 1435, -1, 1431, 1426, 1407, -1, 1436, 1409, 1412, -1, 1437, 1428, 1432, -1, 1437, 1432, 1435, -1, 1436, 1434, 1431, -1, 1436, 1438, 1434, -1, 1436, 1431, 1409, -1, 1439, 1440, 1441, -1, 1439, 1442, 1440, -1, 1443, 1412, 1414, -1, 1439, 1444, 1442, -1, 1439, 1445, 1444, -1, 1443, 1446, 1438, -1, 1439, 1441, 1447, -1, 1443, 1436, 1412, -1, 1448, 1447, 1449, -1, 1443, 1438, 1436, -1, 1448, 1449, 1450, -1, 1451, 1452, 1446, -1, 1448, 1439, 1447, -1, 1451, 1446, 1443, -1, 1451, 1443, 1414, -1, 1453, 1448, 1450, -1, 1454, 1414, 1403, -1, 1453, 1439, 1448, -1, 1454, 1430, 1452, -1, 1454, 188, 1430, -1, 1454, 1451, 1414, -1, 1454, 1452, 1451, -1, 1455, 198, 1445, -1, 1454, 1403, 188, -1, 1455, 1445, 1439, -1, 1456, 1457, 428, -1, 1456, 1458, 1457, -1, 1455, 1439, 1453, -1, 1459, 196, 198, -1, 1459, 1453, 1450, -1, 1456, 428, 471, -1, 1459, 198, 1455, -1, 1459, 1455, 1453, -1, 1435, 1433, 463, -1, 1460, 1450, 1461, -1, 1460, 1461, 1462, -1, 1447, 1463, 1458, -1, 1460, 1464, 1465, -1, 1447, 1441, 1463, -1, 1460, 1465, 1466, -1, 1460, 1462, 1464, -1, 1460, 196, 1459, -1, 1460, 1466, 196, -1, 1467, 1435, 463, -1, 1460, 1459, 1450, -1, 1468, 1465, 1464, -1, 1447, 1458, 1456, -1, 1468, 1462, 1469, -1, 1468, 1464, 1462, -1, 1470, 1467, 463, -1, 1468, 1469, 1471, -1, 1472, 1466, 1465, -1, 1473, 1447, 1456, -1, 1472, 196, 1466, -1, 1472, 1465, 1468, -1, 1474, 195, 196, -1, 1449, 1447, 1473, -1, 1450, 1449, 1473, -1, 1474, 1468, 1471, -1, 1474, 196, 1472, -1, 1474, 1472, 1468, -1, 1475, 1476, 1477, -1, 1475, 1471, 1476, -1, 1450, 1456, 471, -1, 1475, 1477, 1478, -1, 1475, 1479, 1480, -1, 1475, 1478, 1479, -1, 1475, 1474, 1471, -1, 1450, 1473, 1456, -1, 1461, 1450, 471, -1, 1481, 1474, 1475, -1, 1461, 1482, 1462, -1, 1483, 463, 461, -1, 1481, 195, 1474, -1, 1481, 1480, 1484, -1, 1461, 1485, 1482, -1, 1481, 1475, 1480, -1, 1461, 471, 1485, -1, 1481, 1484, 195, -1, 1486, 1487, 1488, -1, 1469, 1462, 1482, -1, 1489, 463, 1483, -1, 1486, 1484, 1480, -1, 1489, 1483, 461, -1, 1486, 1480, 1479, -1, 1486, 1479, 1478, -1, 1486, 1478, 1487, -1, 1469, 1482, 1485, -1, 1486, 195, 1484, -1, 1469, 1485, 469, -1, 1490, 463, 1489, -1, 1490, 1470, 463, -1, 1490, 1489, 461, -1, 1491, 1488, 1492, -1, 1493, 1494, 1470, -1, 1471, 1469, 469, -1, 1495, 193, 195, -1, 1493, 1470, 1490, -1, 1495, 195, 1486, -1, 1496, 1471, 469, -1, 1497, 1494, 1493, -1, 1495, 1486, 1488, -1, 1496, 469, 467, -1, 1497, 1498, 1494, -1, 1495, 1488, 1491, -1, 1499, 1500, 193, -1, 1499, 193, 1495, -1, 1496, 467, 1501, -1, 1429, 1502, 1498, -1, 1499, 1495, 1491, -1, 1476, 1471, 1496, -1, 185, 188, 1403, -1, 1503, 1424, 1504, -1, 1476, 1496, 1501, -1, 1429, 1498, 1497, -1, 1485, 471, 469, -1, 1503, 1499, 1491, -1, 1429, 191, 1502, -1, 1503, 1504, 1505, -1, 1503, 1505, 1506, -1, 189, 191, 1429, -1, 1503, 1506, 1500, -1, 1503, 1492, 1425, -1, 1476, 1501, 1477, -1, 1507, 461, 459, -1, 1503, 1425, 1424, -1, 1503, 1491, 1492, -1, 1503, 1500, 1499, -1, 1508, 1505, 1504, -1, 1508, 1506, 1505, -1, 1487, 1478, 1477, -1, 1508, 193, 1500, -1, 1508, 1500, 1506, -1, 1487, 1477, 1501, -1, 1508, 1423, 1428, -1, 1487, 1501, 467, -1, 1434, 1507, 459, -1, 1434, 461, 1507, -1, 1508, 1504, 1423, -1, 1509, 191, 193, -1, 1509, 1428, 1437, -1, 1438, 1490, 461, -1, 1509, 193, 1508, -1, 1438, 461, 1434, -1, 1509, 1508, 1428, -1, 1488, 1487, 467, -1, 1446, 1493, 1490, -1, 1510, 1509, 1437, -1, 1446, 1490, 1438, -1, 1510, 1502, 191, -1, 1511, 1488, 467, -1, 1510, 191, 1509, -1, 1511, 467, 465, -1, 1512, 1435, 1467, -1, 1512, 1467, 1470, -1, 1511, 465, 1425, -1, 1452, 1493, 1446, -1, 1512, 1470, 1494, -1, 1452, 1497, 1493, -1, 1512, 1494, 1498, -1, 1512, 1437, 1435, -1, 1512, 1498, 1502, -1, 1512, 1502, 1510, -1, 1512, 1510, 1437, -1, 1492, 1511, 1425, -1, 1430, 1429, 1497, -1, 1492, 1488, 1511, -1, 1430, 1497, 1452, -1, 1423, 1504, 1424, -1, 1427, 147, 1405, -1, 1427, 459, 147, -1, 519, 167, 1422, -1, 1513, 502, 298, -1, 517, 518, 1514, -1, 1515, 1417, 506, -1, 1515, 504, 502, -1, 1515, 506, 504, -1, 1516, 1418, 1417, -1, 1516, 1417, 1515, -1, 1517, 1419, 1418, -1, 1517, 1418, 1516, -1, 1518, 1420, 1419, -1, 1518, 1419, 1517, -1, 1519, 1421, 1420, -1, 1519, 1420, 1518, -1, 1520, 1422, 1421, -1, 1520, 518, 519, -1, 1520, 519, 1422, -1, 1520, 1421, 1519, -1, 1521, 1518, 1517, -1, 1521, 1520, 1519, -1, 1521, 1515, 502, -1, 1521, 1519, 1518, -1, 1521, 518, 1520, -1, 1521, 1516, 1515, -1, 1521, 1517, 1516, -1, 1522, 1521, 502, -1, 1522, 518, 1521, -1, 1523, 1524, 1514, -1, 1523, 1525, 1524, -1, 1523, 1526, 1525, -1, 1523, 1527, 1526, -1, 1523, 1513, 1527, -1, 1523, 518, 1522, -1, 1523, 1522, 502, -1, 1523, 502, 1513, -1, 1523, 1514, 518, -1, 198, 199, 1445, -1, 1528, 412, 414, -1, 1529, 414, 415, -1, 1530, 415, 417, -1, 1531, 419, 421, -1, 1532, 423, 426, -1, 1533, 1532, 426, -1, 200, 1534, 199, -1, 1535, 428, 1457, -1, 1535, 426, 428, -1, 1536, 1457, 1458, -1, 1536, 426, 1535, -1, 1536, 1535, 1457, -1, 1537, 1458, 1463, -1, 1537, 1536, 1458, -1, 1537, 426, 1536, -1, 1538, 1463, 1441, -1, 1538, 1441, 1440, -1, 1538, 1533, 426, -1, 1538, 426, 1537, -1, 1538, 1537, 1463, -1, 1539, 1440, 1442, -1, 1539, 1540, 1533, -1, 1539, 1538, 1440, -1, 1539, 1533, 1538, -1, 1541, 1442, 1444, -1, 1541, 1542, 1540, -1, 1541, 1540, 1539, -1, 1541, 1539, 1442, -1, 1543, 1445, 199, -1, 1543, 1542, 1541, -1, 1543, 1444, 1445, -1, 1543, 1534, 1542, -1, 1543, 1541, 1444, -1, 1543, 199, 1534, -1, 1544, 1545, 1546, -1, 1544, 1547, 1545, -1, 1544, 1548, 1547, -1, 1544, 1549, 1548, -1, 1544, 216, 1549, -1, 1550, 1551, 411, -1, 1550, 1546, 1551, -1, 1550, 411, 412, -1, 1550, 1544, 1546, -1, 1552, 1544, 1550, -1, 1553, 1552, 1550, -1, 1553, 214, 216, -1, 1553, 1544, 1552, -1, 1553, 1554, 214, -1, 1553, 216, 1544, -1, 1553, 1550, 412, -1, 1555, 1553, 412, -1, 1555, 412, 1528, -1, 1555, 1528, 1556, -1, 1557, 1553, 1555, -1, 1558, 1555, 1556, -1, 1558, 1559, 1560, -1, 1558, 1557, 1555, -1, 1558, 1554, 1553, -1, 1558, 1560, 1554, -1, 1558, 1556, 1561, -1, 1558, 1561, 1559, -1, 1558, 1553, 1557, -1, 1562, 1528, 414, -1, 1562, 1556, 1528, -1, 1563, 1556, 1562, -1, 1563, 1560, 1559, -1, 1563, 1561, 1556, -1, 1563, 1559, 1561, -1, 1564, 208, 214, -1, 1564, 1563, 1562, -1, 1564, 1560, 1563, -1, 1564, 214, 1554, -1, 1564, 1565, 208, -1, 1564, 1554, 1560, -1, 1564, 1562, 414, -1, 1566, 1565, 1564, -1, 1566, 1529, 1567, -1, 1566, 414, 1529, -1, 1566, 1568, 1565, -1, 1566, 1569, 1568, -1, 1566, 1567, 1569, -1, 1566, 1564, 414, -1, 1570, 1529, 415, -1, 1571, 1529, 1570, -1, 1571, 1567, 1529, -1, 1571, 1568, 1569, -1, 1571, 1569, 1567, -1, 1572, 206, 208, -1, 1572, 1571, 1570, -1, 1572, 1568, 1571, -1, 1572, 1565, 1568, -1, 1572, 208, 1565, -1, 1572, 1573, 206, -1, 1572, 1570, 415, -1, 1574, 415, 1530, -1, 1574, 1575, 1576, -1, 1574, 1572, 415, -1, 1574, 1577, 1573, -1, 1574, 1573, 1572, -1, 1574, 1576, 1577, -1, 1574, 1530, 1575, -1, 1578, 1530, 417, -1, 1579, 1576, 1575, -1, 1579, 1530, 1578, -1, 1579, 1575, 1530, -1, 1580, 1578, 417, -1, 1580, 1579, 1578, -1, 1581, 419, 1582, -1, 1581, 417, 419, -1, 1581, 1580, 417, -1, 1583, 1582, 1584, -1, 1583, 1584, 1585, -1, 1583, 1580, 1581, -1, 1583, 1581, 1582, -1, 1586, 1582, 419, -1, 1587, 419, 1531, -1, 1588, 1531, 421, -1, 1588, 1589, 1531, -1, 1590, 1588, 421, -1, 1591, 1592, 1593, -1, 1591, 1590, 421, -1, 1591, 421, 1592, -1, 1594, 421, 423, -1, 1594, 1593, 1592, -1, 1594, 1592, 421, -1, 1595, 1594, 423, -1, 1596, 1532, 1533, -1, 1596, 1595, 423, -1, 1596, 423, 1532, -1, 1597, 1573, 1577, -1, 1597, 1576, 1579, -1, 1597, 1579, 1580, -1, 1597, 1577, 1576, -1, 1597, 206, 1573, -1, 1598, 1599, 205, -1, 1598, 205, 206, -1, 1598, 1585, 1600, -1, 1598, 1597, 1580, -1, 1598, 1600, 1599, -1, 1598, 1583, 1585, -1, 1598, 1580, 1583, -1, 1598, 206, 1597, -1, 1601, 1584, 1582, -1, 1601, 1585, 1584, -1, 1601, 1600, 1585, -1, 1601, 1599, 1600, -1, 1601, 1582, 1586, -1, 1602, 419, 1587, -1, 1602, 1586, 419, -1, 1602, 1601, 1586, -1, 1603, 205, 1599, -1, 1603, 203, 205, -1, 1603, 1601, 1602, -1, 1603, 1599, 1601, -1, 1603, 1604, 203, -1, 1603, 1602, 1587, -1, 1605, 1531, 1589, -1, 1605, 1589, 1606, -1, 1605, 1606, 1607, -1, 1605, 1607, 1604, -1, 1605, 1587, 1531, -1, 1605, 1604, 1603, -1, 1605, 1603, 1587, -1, 1608, 203, 1604, -1, 1608, 1607, 1606, -1, 1608, 1604, 1607, -1, 1609, 1606, 1589, -1, 1609, 1588, 1590, -1, 1609, 1589, 1588, -1, 1609, 1608, 1606, -1, 1610, 201, 203, -1, 1610, 203, 1608, -1, 1610, 1608, 1609, -1, 1610, 1609, 1590, -1, 1611, 1590, 1591, -1, 1611, 1593, 1612, -1, 1611, 1610, 1590, -1, 1611, 1591, 1593, -1, 1613, 1610, 1611, -1, 1613, 1612, 1614, -1, 1613, 1614, 1615, -1, 1613, 1611, 1612, -1, 1613, 1615, 201, -1, 1613, 201, 1610, -1, 1616, 1594, 1595, -1, 1616, 1612, 1593, -1, 1616, 1593, 1594, -1, 1617, 1614, 1612, -1, 1617, 1615, 1614, -1, 1617, 1612, 1616, -1, 1617, 201, 1615, -1, 1618, 1617, 1616, -1, 1619, 201, 1617, -1, 1619, 200, 201, -1, 1619, 1616, 1595, -1, 1619, 1617, 1618, -1, 1619, 1618, 1616, -1, 1620, 1619, 1595, -1, 1620, 1533, 1540, -1, 1620, 1596, 1533, -1, 1620, 1595, 1596, -1, 1621, 200, 1619, -1, 1621, 1619, 1620, -1, 1621, 1620, 1540, -1, 1621, 1534, 200, -1, 1621, 1540, 1542, -1, 1621, 1542, 1534, -1, 300, 1513, 298, -1, 1622, 1527, 1513, -1, 1622, 1513, 300, -1, 1623, 1526, 1527, -1, 1623, 1527, 1622, -1, 1624, 1526, 1623, -1, 1625, 1525, 1526, -1, 1625, 1526, 1624, -1, 1626, 1524, 1525, -1, 1626, 1525, 1625, -1, 1627, 1514, 1524, -1, 1627, 1524, 1626, -1, 315, 517, 1514, -1, 315, 1514, 1627, -1, 1628, 493, 411, -1, 1551, 1628, 411, -1, 1629, 1628, 1551, -1, 1546, 1629, 1551, -1, 1630, 1629, 1546, -1, 1545, 1630, 1546, -1, 1547, 1631, 1630, -1, 1547, 1630, 1545, -1, 1548, 1632, 1631, -1, 1548, 1631, 1547, -1, 1549, 1633, 1632, -1, 1549, 1632, 1548, -1, 216, 217, 1633, -1, 216, 1633, 1549, -1, 1634, 1635, 318, -1, 1636, 1637, 1638, -1, 1636, 1638, 1639, -1, 1640, 1635, 1634, -1, 1640, 1641, 1635, -1, 321, 1642, 322, -1, 1643, 307, 309, -1, 1643, 1644, 1637, -1, 1643, 309, 1644, -1, 1643, 1637, 1636, -1, 1645, 1646, 1641, -1, 1645, 1641, 1640, -1, 1647, 1639, 1646, -1, 1647, 1646, 1645, -1, 1648, 318, 317, -1, 1648, 1634, 318, -1, 309, 311, 1649, -1, 1650, 1639, 1647, -1, 1650, 1636, 1639, -1, 1651, 1640, 1634, -1, 1651, 1634, 1648, -1, 1652, 1636, 1650, -1, 1652, 305, 307, -1, 1652, 307, 1643, -1, 1652, 1643, 1636, -1, 1653, 1640, 1651, -1, 1653, 1645, 1640, -1, 1654, 1645, 1653, -1, 1654, 1647, 1645, -1, 1655, 315, 1627, -1, 1655, 316, 315, -1, 1655, 317, 316, -1, 1655, 1648, 317, -1, 1656, 1650, 1647, -1, 1656, 1647, 1654, -1, 1657, 1627, 1626, -1, 1657, 1655, 1627, -1, 1657, 1648, 1655, -1, 1657, 1651, 1648, -1, 1658, 304, 305, -1, 1658, 305, 1652, -1, 300, 302, 1622, -1, 1658, 1650, 1656, -1, 1658, 1652, 1650, -1, 1659, 1626, 1625, -1, 1660, 321, 320, -1, 1660, 1642, 321, -1, 1659, 1657, 1626, -1, 1659, 1651, 1657, -1, 1661, 1662, 1642, -1, 1659, 1653, 1651, -1, 1663, 1625, 1624, -1, 1663, 1659, 1625, -1, 1661, 1642, 1660, -1, 1663, 1653, 1659, -1, 1664, 1665, 1662, -1, 1664, 1666, 1665, -1, 1663, 1654, 1653, -1, 1667, 1624, 1623, -1, 1667, 1656, 1654, -1, 1664, 1662, 1661, -1, 1667, 1663, 1624, -1, 1667, 1654, 1663, -1, 1668, 1623, 1622, -1, 1638, 1666, 1664, -1, 1668, 302, 304, -1, 1668, 304, 1658, -1, 1668, 1658, 1656, -1, 1668, 1656, 1667, -1, 1635, 320, 318, -1, 1668, 1667, 1623, -1, 1668, 1622, 302, -1, 1635, 1660, 320, -1, 1637, 1669, 1666, -1, 1637, 1666, 1638, -1, 1641, 1661, 1660, -1, 1641, 1660, 1635, -1, 1644, 1649, 1669, -1, 1644, 1669, 1637, -1, 1644, 309, 1649, -1, 1646, 1664, 1661, -1, 1646, 1661, 1641, -1, 1639, 1664, 1646, -1, 1639, 1638, 1664, -1, 497, 1670, 282, -1, 532, 533, 1671, -1, 1628, 494, 493, -1, 217, 531, 1633, -1, 1672, 1670, 497, -1, 1673, 1674, 1670, -1, 1673, 1670, 1672, -1, 1675, 1676, 1674, -1, 1675, 1674, 1673, -1, 1677, 1678, 1676, -1, 1677, 1676, 1675, -1, 1679, 1680, 1678, -1, 1679, 1678, 1677, -1, 1681, 531, 532, -1, 1681, 1671, 1680, -1, 1681, 532, 1671, -1, 1681, 1680, 1679, -1, 1682, 497, 494, -1, 1682, 1673, 1672, -1, 1682, 1675, 1673, -1, 1682, 1672, 497, -1, 1683, 1681, 1679, -1, 1683, 531, 1681, -1, 1683, 1679, 1677, -1, 1683, 1677, 1675, -1, 1683, 1675, 1682, -1, 1684, 531, 1683, -1, 1684, 1682, 494, -1, 1684, 1683, 1682, -1, 1685, 1628, 1629, -1, 1685, 1629, 1630, -1, 1685, 1630, 1631, -1, 1685, 1631, 1632, -1, 1685, 1632, 1633, -1, 1685, 531, 1684, -1, 1685, 494, 1628, -1, 1685, 1633, 531, -1, 1685, 1684, 494, -1, 1686, 1649, 311, -1, 1686, 311, 313, -1, 1687, 1669, 1649, -1, 1687, 1649, 1686, -1, 1688, 1665, 1666, -1, 1688, 1666, 1669, -1, 1688, 1669, 1687, -1, 1689, 1662, 1665, -1, 1689, 1665, 1688, -1, 1690, 1642, 1662, -1, 1690, 1662, 1689, -1, 1691, 322, 1642, -1, 1691, 1642, 1690, -1, 516, 322, 1691, -1, 1670, 1692, 283, -1, 1670, 283, 282, -1, 1674, 1693, 1692, -1, 1674, 1692, 1670, -1, 1676, 1694, 1693, -1, 1676, 1695, 1694, -1, 1676, 1693, 1674, -1, 1678, 1696, 1695, -1, 1678, 1695, 1676, -1, 1680, 1697, 1696, -1, 1680, 1696, 1678, -1, 1671, 331, 1697, -1, 1671, 1697, 1680, -1, 533, 331, 1671, -1, 511, 1686, 313, -1, 515, 516, 1691, -1, 1698, 508, 507, -1, 279, 514, 1699, -1, 1700, 1686, 511, -1, 1701, 1687, 1686, -1, 1701, 1686, 1700, -1, 1702, 1688, 1687, -1, 1702, 1687, 1701, -1, 1703, 1689, 1688, -1, 1703, 1688, 1702, -1, 1704, 1690, 1689, -1, 1704, 1689, 1703, -1, 1705, 1691, 1690, -1, 1705, 514, 515, -1, 1705, 515, 1691, -1, 1705, 1690, 1704, -1, 1706, 511, 508, -1, 1706, 1700, 511, -1, 1706, 1702, 1701, -1, 1706, 1701, 1700, -1, 1707, 1703, 1702, -1, 1707, 1705, 1704, -1, 1707, 1704, 1703, -1, 1707, 1702, 1706, -1, 1707, 514, 1705, -1, 1708, 1706, 508, -1, 1708, 514, 1707, -1, 1708, 1707, 1706, -1, 1709, 1710, 1699, -1, 1709, 1711, 1710, -1, 1709, 1712, 1711, -1, 1709, 1713, 1712, -1, 1709, 1698, 1713, -1, 1709, 508, 1698, -1, 1709, 514, 1708, -1, 1709, 1708, 508, -1, 1709, 1699, 514, -1, 1714, 1715, 329, -1, 1716, 1717, 1718, -1, 1716, 1718, 1719, -1, 1720, 1721, 1715, -1, 1720, 1715, 1714, -1, 1722, 288, 286, -1, 1722, 1723, 1717, -1, 1722, 286, 1723, -1, 1722, 1717, 1716, -1, 1724, 1725, 1721, -1, 1724, 1721, 1720, -1, 1726, 1725, 1724, -1, 1726, 1719, 1725, -1, 1727, 327, 326, -1, 1727, 1714, 327, -1, 1728, 1716, 1719, -1, 1728, 1719, 1726, -1, 1729, 1714, 1727, -1, 1729, 1720, 1714, -1, 1730, 1716, 1728, -1, 1730, 290, 288, -1, 1730, 288, 1722, -1, 1730, 1722, 1716, -1, 1731, 1720, 1729, -1, 1731, 1724, 1720, -1, 1732, 1724, 1731, -1, 1732, 1726, 1724, -1, 1733, 325, 324, -1, 1733, 326, 325, -1, 1733, 324, 1734, -1, 1733, 1727, 326, -1, 1735, 1728, 1726, -1, 1735, 1726, 1732, -1, 1736, 1733, 1734, -1, 1736, 1727, 1733, -1, 1736, 1734, 1737, -1, 1736, 1729, 1727, -1, 1738, 291, 290, -1, 1738, 290, 1730, -1, 295, 293, 1739, -1, 1738, 1730, 1728, -1, 1738, 1728, 1735, -1, 1740, 1696, 1697, -1, 1740, 1697, 331, -1, 1741, 1736, 1737, -1, 1740, 331, 330, -1, 1741, 1737, 1742, -1, 1741, 1729, 1736, -1, 1741, 1731, 1729, -1, 1743, 1732, 1731, -1, 1744, 1696, 1740, -1, 1743, 1742, 1745, -1, 1743, 1731, 1741, -1, 1746, 1694, 1695, -1, 1743, 1741, 1742, -1, 1746, 1695, 1696, -1, 1747, 1745, 1748, -1, 1746, 1696, 1744, -1, 1747, 1735, 1732, -1, 1747, 1743, 1745, -1, 1747, 1732, 1743, -1, 1749, 291, 1738, -1, 1718, 1694, 1746, -1, 1749, 1748, 1739, -1, 1749, 1738, 1735, -1, 1749, 293, 291, -1, 1715, 330, 329, -1, 1749, 1747, 1748, -1, 1749, 1735, 1747, -1, 1749, 1739, 293, -1, 1715, 1740, 330, -1, 1717, 1692, 1693, -1, 1717, 1693, 1694, -1, 1717, 1694, 1718, -1, 1721, 1740, 1715, -1, 1721, 1744, 1740, -1, 1723, 283, 1692, -1, 1723, 286, 283, -1, 1723, 1692, 1717, -1, 1725, 1746, 1744, -1, 1725, 1744, 1721, -1, 1719, 1746, 1725, -1, 1719, 1718, 1746, -1, 1714, 329, 327, -1, 1698, 507, 367, -1, 1750, 1698, 367, -1, 1713, 1698, 1750, -1, 1751, 1713, 1750, -1, 1712, 1713, 1751, -1, 1752, 1712, 1751, -1, 1711, 1712, 1752, -1, 1753, 1711, 1752, -1, 1754, 1710, 1711, -1, 1754, 1711, 1753, -1, 1755, 1699, 1710, -1, 1755, 1710, 1754, -1, 278, 279, 1699, -1, 278, 1699, 1755, -1, 295, 1756, 297, -1, 1739, 1757, 1756, -1, 1739, 1756, 295, -1, 1748, 1758, 1757, -1, 1748, 1757, 1739, -1, 1745, 1758, 1748, -1, 1742, 1759, 1758, -1, 1742, 1758, 1745, -1, 1737, 1760, 1759, -1, 1737, 1759, 1742, -1, 1734, 1761, 1760, -1, 1734, 1760, 1737, -1, 324, 528, 1761, -1, 324, 1761, 1734, -1, 258, 259, 1762, -1, 1763, 365, 364, -1, 1764, 364, 362, -1, 1765, 362, 360, -1, 1766, 358, 356, -1, 1767, 353, 351, -1, 1768, 1767, 351, -1, 260, 1769, 259, -1, 1770, 351, 348, -1, 1770, 348, 1771, -1, 1772, 1771, 1773, -1, 1772, 1770, 1771, -1, 1772, 351, 1770, -1, 1774, 1775, 1776, -1, 1774, 1773, 1775, -1, 1774, 1772, 1773, -1, 1774, 351, 1772, -1, 1777, 1776, 1778, -1, 1777, 1774, 1776, -1, 1777, 351, 1774, -1, 1777, 1768, 351, -1, 1779, 1778, 1780, -1, 1779, 1781, 1768, -1, 1779, 1777, 1778, -1, 1779, 1768, 1777, -1, 1782, 1780, 1783, -1, 1782, 1781, 1779, -1, 1782, 1784, 1781, -1, 1782, 1779, 1780, -1, 1785, 1762, 259, -1, 1785, 1783, 1762, -1, 1785, 259, 1769, -1, 1785, 1769, 1784, -1, 1785, 1784, 1782, -1, 1785, 1782, 1783, -1, 1786, 278, 1755, -1, 1786, 1755, 1754, -1, 1786, 1754, 1753, -1, 1786, 1753, 1752, -1, 1786, 1752, 1751, -1, 1787, 1751, 1750, -1, 1787, 1750, 367, -1, 1787, 367, 365, -1, 1787, 1786, 1751, -1, 1788, 1786, 1787, -1, 1789, 1786, 1788, -1, 1789, 274, 278, -1, 1789, 278, 1786, -1, 1789, 1787, 365, -1, 1789, 1790, 274, -1, 1789, 1788, 1787, -1, 1791, 1789, 365, -1, 1791, 1763, 1792, -1, 1791, 365, 1763, -1, 1793, 1789, 1791, -1, 1794, 1795, 1796, -1, 1794, 1789, 1793, -1, 1794, 1790, 1789, -1, 1794, 1791, 1792, -1, 1794, 1793, 1791, -1, 1794, 1792, 1795, -1, 1794, 1797, 1790, -1, 1794, 1796, 1797, -1, 1798, 1792, 1763, -1, 1798, 1763, 364, -1, 1799, 1796, 1795, -1, 1799, 1795, 1792, -1, 1799, 1797, 1796, -1, 1799, 1792, 1798, -1, 1800, 1797, 1799, -1, 1800, 1799, 1798, -1, 1800, 271, 274, -1, 1800, 1801, 271, -1, 1800, 1790, 1797, -1, 1800, 1798, 364, -1, 1800, 274, 1790, -1, 1802, 1800, 364, -1, 1802, 1801, 1800, -1, 1802, 1764, 1803, -1, 1802, 1804, 1801, -1, 1802, 1803, 1805, -1, 1802, 364, 1764, -1, 1802, 1805, 1804, -1, 1806, 1764, 362, -1, 1807, 1764, 1806, -1, 1807, 1803, 1764, -1, 1807, 1805, 1803, -1, 1807, 1804, 1805, -1, 1808, 1807, 1806, -1, 1808, 266, 271, -1, 1808, 1804, 1807, -1, 1808, 1801, 1804, -1, 1808, 1809, 266, -1, 1808, 271, 1801, -1, 1808, 1806, 362, -1, 1810, 1811, 1809, -1, 1810, 1809, 1808, -1, 1810, 1808, 362, -1, 1810, 1812, 1813, -1, 1810, 362, 1765, -1, 1810, 1813, 1811, -1, 1810, 1765, 1812, -1, 1814, 1765, 360, -1, 1815, 1813, 1812, -1, 1815, 1765, 1814, -1, 1815, 1812, 1765, -1, 1816, 1814, 360, -1, 1816, 1815, 1814, -1, 1817, 360, 358, -1, 1817, 358, 1818, -1, 1817, 1816, 360, -1, 1819, 1820, 1821, -1, 1819, 1818, 1820, -1, 1819, 1817, 1818, -1, 1819, 1816, 1817, -1, 1822, 1818, 358, -1, 1823, 358, 1766, -1, 1824, 1825, 1766, -1, 1824, 1766, 356, -1, 1826, 1824, 356, -1, 1827, 1828, 1829, -1, 1827, 1826, 356, -1, 1827, 356, 1828, -1, 1830, 356, 353, -1, 1830, 1829, 1828, -1, 1830, 1828, 356, -1, 1831, 1830, 353, -1, 1832, 1767, 1768, -1, 1832, 1831, 353, -1, 1832, 353, 1767, -1, 1833, 1809, 1811, -1, 1833, 266, 1809, -1, 1833, 1813, 1815, -1, 1833, 1811, 1813, -1, 1833, 1815, 1816, -1, 1834, 1835, 1836, -1, 1834, 1821, 1835, -1, 1834, 266, 1833, -1, 1834, 1836, 265, -1, 1834, 265, 266, -1, 1834, 1816, 1819, -1, 1834, 1819, 1821, -1, 1834, 1833, 1816, -1, 1837, 1821, 1820, -1, 1837, 1836, 1835, -1, 1837, 1835, 1821, -1, 1837, 1820, 1818, -1, 1837, 1818, 1822, -1, 1838, 1822, 358, -1, 1838, 358, 1823, -1, 1838, 1837, 1822, -1, 1839, 1840, 263, -1, 1839, 265, 1836, -1, 1839, 263, 265, -1, 1839, 1836, 1837, -1, 1839, 1837, 1838, -1, 1839, 1838, 1823, -1, 1841, 1823, 1766, -1, 1841, 1766, 1825, -1, 1841, 1825, 1842, -1, 1841, 1842, 1843, -1, 1841, 1843, 1840, -1, 1841, 1840, 1839, -1, 1841, 1839, 1823, -1, 1844, 263, 1840, -1, 1844, 1843, 1842, -1, 1844, 1840, 1843, -1, 1845, 1842, 1825, -1, 1845, 1825, 1824, -1, 1845, 1844, 1842, -1, 1845, 1824, 1826, -1, 1846, 262, 263, -1, 1846, 1845, 1826, -1, 1846, 263, 1844, -1, 1846, 1844, 1845, -1, 1847, 1846, 1826, -1, 1847, 1829, 1848, -1, 1847, 1827, 1829, -1, 1847, 1826, 1827, -1, 1849, 1847, 1848, -1, 1849, 1850, 262, -1, 1849, 1848, 1851, -1, 1849, 1851, 1850, -1, 1849, 1846, 1847, -1, 1849, 262, 1846, -1, 1852, 1830, 1831, -1, 1852, 1848, 1829, -1, 1852, 1829, 1830, -1, 1853, 1848, 1852, -1, 1853, 262, 1850, -1, 1853, 1851, 1848, -1, 1853, 1850, 1851, -1, 1854, 1853, 1852, -1, 1855, 262, 1853, -1, 1855, 1854, 1852, -1, 1855, 260, 262, -1, 1855, 1853, 1854, -1, 1855, 1852, 1831, -1, 1856, 1855, 1831, -1, 1856, 1768, 1781, -1, 1856, 1832, 1768, -1, 1856, 1831, 1832, -1, 1857, 1855, 1856, -1, 1857, 1856, 1781, -1, 1857, 260, 1855, -1, 1857, 1769, 260, -1, 1857, 1781, 1784, -1, 1857, 1784, 1769, -1, 530, 226, 1858, -1, 1756, 488, 297, -1, 528, 529, 1761, -1, 1859, 1860, 492, -1, 1859, 490, 488, -1, 1859, 492, 490, -1, 1861, 1862, 1860, -1, 1861, 1860, 1859, -1, 1863, 1864, 1862, -1, 1863, 1862, 1861, -1, 1865, 1866, 1864, -1, 1865, 1864, 1863, -1, 1867, 1868, 1866, -1, 1867, 1866, 1865, -1, 1869, 529, 530, -1, 1869, 1858, 1868, -1, 1869, 530, 1858, -1, 1869, 1868, 1867, -1, 1870, 1869, 1867, -1, 1870, 1861, 1859, -1, 1870, 1859, 488, -1, 1870, 1867, 1865, -1, 1870, 529, 1869, -1, 1870, 1865, 1863, -1, 1870, 1863, 1861, -1, 1871, 1870, 488, -1, 1871, 529, 1870, -1, 1872, 1756, 1757, -1, 1872, 1757, 1758, -1, 1872, 1758, 1759, -1, 1872, 1759, 1760, -1, 1872, 1760, 1761, -1, 1872, 529, 1871, -1, 1872, 1871, 488, -1, 1872, 488, 1756, -1, 1872, 1761, 529, -1, 1873, 1874, 450, -1, 1873, 1875, 1874, -1, 1876, 1877, 1878, -1, 1876, 456, 1879, -1, 1876, 1879, 1877, -1, 252, 250, 1880, -1, 1881, 1873, 450, -1, 252, 1882, 248, -1, 252, 1880, 1882, -1, 1883, 450, 452, -1, 1884, 1878, 1885, -1, 1883, 452, 1886, -1, 1884, 1887, 456, -1, 1883, 1886, 1888, -1, 1884, 456, 1876, -1, 1883, 1881, 450, -1, 1884, 1876, 1878, -1, 1889, 1885, 1890, -1, 1889, 1891, 1887, -1, 1892, 1883, 1888, -1, 1892, 1881, 1883, -1, 1889, 1887, 1884, -1, 1889, 1884, 1885, -1, 1893, 1762, 1783, -1, 1893, 1783, 1780, -1, 1894, 1891, 1889, -1, 1893, 1780, 1778, -1, 1894, 1895, 1891, -1, 1893, 1778, 1776, -1, 1893, 1776, 1896, -1, 1894, 1889, 1890, -1, 1897, 1898, 1899, -1, 1900, 1890, 1901, -1, 1897, 1893, 1896, -1, 1900, 1902, 1895, -1, 1897, 1896, 1898, -1, 1900, 1894, 1890, -1, 1900, 1895, 1894, -1, 1903, 1897, 1899, -1, 1903, 1893, 1897, -1, 1904, 1901, 1905, -1, 1904, 248, 1882, -1, 1904, 1882, 1902, -1, 1904, 1902, 1900, -1, 1906, 258, 1762, -1, 1904, 1900, 1901, -1, 1904, 1905, 248, -1, 1906, 1762, 1893, -1, 1906, 1893, 1903, -1, 1907, 257, 258, -1, 1908, 1773, 1771, -1, 1908, 1771, 348, -1, 1907, 1903, 1899, -1, 1908, 348, 444, -1, 1907, 1906, 1903, -1, 1888, 1886, 452, -1, 1907, 258, 1906, -1, 1909, 1910, 1911, -1, 1909, 257, 1907, -1, 1909, 1912, 1913, -1, 1909, 1899, 1910, -1, 1909, 1907, 1899, -1, 1914, 1888, 452, -1, 1909, 1913, 257, -1, 1896, 1776, 1775, -1, 1909, 1915, 1912, -1, 1896, 1775, 1773, -1, 1909, 1911, 1915, -1, 1916, 1917, 1918, -1, 1896, 1773, 1908, -1, 1916, 1911, 1917, -1, 1916, 1912, 1915, -1, 1916, 1915, 1911, -1, 1919, 1914, 452, -1, 1920, 1912, 1916, -1, 1921, 1896, 1908, -1, 1920, 1913, 1912, -1, 1898, 1896, 1921, -1, 1920, 257, 1913, -1, 1922, 257, 1920, -1, 1922, 255, 257, -1, 1922, 1920, 1916, -1, 1899, 1908, 444, -1, 1922, 1916, 1918, -1, 1923, 1924, 1925, -1, 1923, 1918, 1924, -1, 1923, 1922, 1918, -1, 1899, 1921, 1908, -1, 1926, 452, 454, -1, 1923, 1927, 1928, -1, 1899, 1898, 1921, -1, 1923, 1925, 1929, -1, 1923, 1929, 1927, -1, 1930, 1923, 1928, -1, 1910, 1931, 1932, -1, 1930, 1933, 255, -1, 1910, 1932, 1911, -1, 1930, 1928, 1933, -1, 1910, 444, 1931, -1, 1934, 1926, 454, -1, 1930, 255, 1922, -1, 1930, 1922, 1923, -1, 1910, 1899, 444, -1, 1917, 1932, 1931, -1, 1935, 1936, 1937, -1, 1917, 1931, 446, -1, 1935, 1929, 1936, -1, 1917, 1911, 1932, -1, 1934, 452, 1926, -1, 1935, 255, 1933, -1, 1935, 1933, 1928, -1, 1938, 1919, 452, -1, 1935, 1928, 1927, -1, 1935, 1927, 1929, -1, 1938, 1934, 454, -1, 1938, 452, 1934, -1, 1939, 1940, 1919, -1, 1941, 1937, 1942, -1, 1918, 1917, 446, -1, 1939, 1919, 1938, -1, 1943, 1935, 1937, -1, 1943, 255, 1935, -1, 1944, 1945, 1940, -1, 1943, 254, 255, -1, 1946, 446, 448, -1, 1943, 1937, 1941, -1, 1946, 1918, 446, -1, 1944, 1940, 1939, -1, 1880, 251, 1947, -1, 1948, 1943, 1941, -1, 1946, 448, 1949, -1, 1948, 1950, 254, -1, 1880, 1947, 1945, -1, 247, 248, 1905, -1, 1948, 254, 1943, -1, 1880, 1945, 1944, -1, 1931, 444, 446, -1, 1951, 1948, 1941, -1, 1924, 1949, 1925, -1, 1951, 1875, 1952, -1, 1924, 1918, 1946, -1, 250, 251, 1880, -1, 1951, 1952, 1953, -1, 1924, 1946, 1949, -1, 1951, 1953, 1954, -1, 1955, 454, 456, -1, 1951, 1954, 1950, -1, 1951, 1942, 1874, -1, 1951, 1874, 1875, -1, 1951, 1941, 1942, -1, 1951, 1950, 1948, -1, 1956, 1953, 1952, -1, 1887, 1955, 456, -1, 1956, 1954, 1953, -1, 1936, 1925, 1949, -1, 1956, 1950, 1954, -1, 1936, 1929, 1925, -1, 1956, 1873, 1881, -1, 1936, 1949, 448, -1, 1956, 1952, 1873, -1, 1887, 454, 1955, -1, 1956, 254, 1950, -1, 1957, 251, 254, -1, 1891, 1938, 454, -1, 1957, 1881, 1892, -1, 1891, 454, 1887, -1, 1957, 1956, 1881, -1, 1957, 254, 1956, -1, 1958, 1947, 251, -1, 1895, 1939, 1938, -1, 1937, 1936, 448, -1, 1958, 251, 1957, -1, 1895, 1938, 1891, -1, 1959, 448, 450, -1, 1958, 1957, 1892, -1, 1959, 1937, 448, -1, 1902, 1939, 1895, -1, 1960, 1958, 1892, -1, 1959, 450, 1874, -1, 1902, 1944, 1939, -1, 1960, 1914, 1919, -1, 1960, 1919, 1940, -1, 1960, 1940, 1945, -1, 1960, 1945, 1947, -1, 1960, 1892, 1888, -1, 1960, 1947, 1958, -1, 1882, 1880, 1944, -1, 1960, 1888, 1914, -1, 1942, 1959, 1874, -1, 1882, 1944, 1902, -1, 1942, 1937, 1959, -1, 1879, 456, 161, -1, 1873, 1952, 1875, -1, 1879, 161, 1877, -1, 1860, 1961, 390, -1, 1860, 390, 492, -1, 1862, 1962, 1961, -1, 1862, 1961, 1860, -1, 1864, 1963, 1962, -1, 1864, 1962, 1862, -1, 1964, 1963, 1864, -1, 1866, 1964, 1864, -1, 1965, 1964, 1866, -1, 1868, 1965, 1866, -1, 1966, 1965, 1868, -1, 1858, 1966, 1868, -1, 228, 1966, 1858, -1, 226, 228, 1858, -1, 1967, 1968, 1969, -1, 1967, 1970, 1968, -1, 1971, 1877, 161, -1, 1971, 161, 158, -1, 1972, 1878, 1877, -1, 1972, 1877, 1971, -1, 1973, 1885, 1878, -1, 1973, 1878, 1972, -1, 1974, 154, 156, -1, 1974, 158, 154, -1, 1974, 1975, 1976, -1, 1974, 156, 1975, -1, 1974, 1971, 158, -1, 1977, 1890, 1885, -1, 1977, 1885, 1973, -1, 1978, 1976, 1979, -1, 1978, 1972, 1971, -1, 1978, 1971, 1974, -1, 1978, 1974, 1976, -1, 1970, 1901, 1890, -1, 1970, 1890, 1977, -1, 1980, 1979, 1981, -1, 1980, 1978, 1979, -1, 1980, 1972, 1978, -1, 1980, 1973, 1972, -1, 1982, 247, 1905, -1, 1982, 1905, 1901, -1, 1982, 242, 247, -1, 1982, 1901, 1970, -1, 1983, 1981, 1984, -1, 1983, 1973, 1980, -1, 1983, 1977, 1973, -1, 1983, 1980, 1981, -1, 1968, 1984, 1969, -1, 1968, 1983, 1984, -1, 1968, 1970, 1977, -1, 1968, 1977, 1983, -1, 1967, 1969, 237, -1, 1967, 238, 242, -1, 1967, 237, 238, -1, 1967, 242, 1982, -1, 1967, 1982, 1970, -1, 1985, 406, 404, -1, 1986, 1985, 404, -1, 1987, 1985, 1986, -1, 1988, 1989, 1985, -1, 1988, 1985, 1987, -1, 1990, 269, 275, -1, 1990, 1991, 269, -1, 1992, 1989, 1988, -1, 1992, 1993, 1989, -1, 1994, 1993, 1992, -1, 1994, 1995, 1993, -1, 1996, 1997, 1995, -1, 1996, 1995, 1994, -1, 1998, 1991, 1997, -1, 1998, 1997, 1996, -1, 1998, 269, 1991, -1, 1999, 272, 267, -1, 2000, 246, 272, -1, 2001, 243, 246, -1, 2002, 240, 243, -1, 2003, 235, 240, -1, 2004, 230, 235, -1, 2005, 2006, 408, -1, 2005, 2007, 2006, -1, 2005, 408, 406, -1, 2008, 1985, 1989, -1, 2008, 1989, 1993, -1, 2008, 406, 1985, -1, 2009, 1998, 1996, -1, 2009, 267, 269, -1, 2009, 1996, 1994, -1, 2009, 269, 1998, -1, 2010, 267, 2009, -1, 2011, 2012, 2013, -1, 2011, 1999, 267, -1, 2011, 2013, 1999, -1, 2011, 267, 2010, -1, 2014, 2013, 2012, -1, 2014, 272, 1999, -1, 2014, 1999, 2013, -1, 2015, 272, 2014, -1, 2016, 272, 2015, -1, 2016, 2017, 2018, -1, 2016, 2000, 272, -1, 2016, 2018, 2000, -1, 2019, 246, 2000, -1, 2019, 2000, 2018, -1, 2020, 2021, 2022, -1, 2020, 2001, 246, -1, 2020, 2022, 2001, -1, 2023, 2022, 2021, -1, 2024, 2022, 2023, -1, 2024, 243, 2001, -1, 2024, 2001, 2022, -1, 2025, 2024, 2023, -1, 2025, 243, 2024, -1, 2026, 2027, 2028, -1, 2026, 2028, 2029, -1, 2030, 2025, 2026, -1, 2030, 2026, 2029, -1, 2030, 243, 2025, -1, 2030, 2002, 243, -1, 2030, 2029, 2002, -1, 2031, 2029, 2032, -1, 2031, 240, 2002, -1, 2031, 2002, 2029, -1, 2033, 2031, 2032, -1, 2033, 240, 2031, -1, 2034, 2035, 2036, -1, 2034, 2036, 2037, -1, 2038, 2034, 2037, -1, 2038, 2037, 2003, -1, 2038, 2003, 240, -1, 2038, 2033, 2034, -1, 2038, 240, 2033, -1, 2039, 2003, 2037, -1, 2039, 235, 2003, -1, 2040, 392, 2041, -1, 2040, 2042, 2043, -1, 2040, 235, 2039, -1, 2040, 2041, 2042, -1, 2044, 2040, 2043, -1, 2044, 2043, 2045, -1, 2044, 2045, 2046, -1, 2044, 2046, 2047, -1, 2044, 2004, 235, -1, 2044, 2047, 2004, -1, 2044, 235, 2040, -1, 2048, 2043, 2042, -1, 2048, 2045, 2043, -1, 2048, 2046, 2045, -1, 2048, 2047, 2046, -1, 2049, 2047, 2048, -1, 2049, 230, 2004, -1, 2049, 2004, 2047, -1, 2050, 2049, 2048, -1, 2050, 230, 2049, -1, 2050, 2041, 392, -1, 2050, 392, 390, -1, 2050, 2042, 2041, -1, 2050, 2048, 2042, -1, 2051, 1965, 1966, -1, 2051, 1966, 228, -1, 2051, 2050, 2052, -1, 2051, 228, 230, -1, 2051, 230, 2050, -1, 2053, 390, 1961, -1, 2053, 1961, 1962, -1, 2053, 1962, 1963, -1, 2053, 1963, 1964, -1, 2053, 1964, 1965, -1, 2053, 1965, 2051, -1, 2053, 2052, 2050, -1, 2053, 2051, 2052, -1, 2053, 2050, 390, -1, 2054, 2055, 2007, -1, 2054, 2056, 2055, -1, 2054, 2057, 2056, -1, 2054, 2007, 2005, -1, 2058, 2059, 2057, -1, 2058, 2060, 2059, -1, 2058, 2061, 2060, -1, 2058, 2057, 2054, -1, 2062, 275, 276, -1, 2062, 2054, 2005, -1, 2062, 276, 2061, -1, 2062, 2058, 2054, -1, 2062, 2061, 2058, -1, 2062, 1990, 275, -1, 2063, 2062, 2005, -1, 2063, 1991, 1990, -1, 2063, 2008, 1993, -1, 2063, 1995, 1997, -1, 2063, 1990, 2062, -1, 2063, 1997, 1991, -1, 2063, 1993, 1995, -1, 2064, 1986, 404, -1, 2064, 1987, 1986, -1, 2064, 1988, 1987, -1, 2065, 2010, 2009, -1, 2065, 1988, 2064, -1, 2065, 2064, 2066, -1, 2065, 2009, 1994, -1, 2065, 1992, 1988, -1, 2065, 1994, 1992, -1, 2067, 404, 402, -1, 2067, 2066, 2064, -1, 2067, 2010, 2065, -1, 2067, 2065, 2066, -1, 2067, 2064, 404, -1, 2068, 2069, 2070, -1, 2068, 2071, 2069, -1, 2068, 2067, 402, -1, 2068, 402, 2071, -1, 2072, 2070, 2073, -1, 2072, 2073, 2012, -1, 2072, 2012, 2011, -1, 2072, 2068, 2070, -1, 2072, 2010, 2067, -1, 2072, 2067, 2068, -1, 2072, 2011, 2010, -1, 2074, 2070, 2069, -1, 2074, 2073, 2070, -1, 2074, 2069, 2071, -1, 2074, 2071, 402, -1, 2075, 2015, 2014, -1, 2075, 2012, 2073, -1, 2075, 2014, 2012, -1, 2075, 2073, 2074, -1, 2075, 2074, 2076, -1, 2077, 2074, 402, -1, 2077, 402, 400, -1, 2077, 2015, 2075, -1, 2077, 2076, 2074, -1, 2077, 2075, 2076, -1, 2078, 2079, 2080, -1, 2078, 2080, 2081, -1, 2078, 2077, 400, -1, 2078, 400, 2079, -1, 2082, 2081, 2083, -1, 2082, 2083, 2017, -1, 2082, 2078, 2081, -1, 2082, 2016, 2015, -1, 2082, 2017, 2016, -1, 2082, 2015, 2077, -1, 2082, 2077, 2078, -1, 2084, 2080, 2079, -1, 2084, 2081, 2080, -1, 2084, 2083, 2081, -1, 2085, 2019, 2018, -1, 2085, 2017, 2083, -1, 2085, 2018, 2017, -1, 2085, 2083, 2084, -1, 2086, 400, 398, -1, 2086, 2084, 2079, -1, 2086, 2019, 2085, -1, 2086, 2079, 400, -1, 2086, 2085, 2084, -1, 2087, 398, 2088, -1, 2087, 2088, 2089, -1, 2087, 2086, 398, -1, 2090, 2087, 2089, -1, 2090, 2089, 2091, -1, 2090, 2020, 2087, -1, 2090, 2021, 2020, -1, 2090, 2091, 2092, -1, 2090, 2092, 2021, -1, 2093, 398, 396, -1, 2093, 2088, 398, -1, 2093, 2089, 2088, -1, 2093, 2091, 2089, -1, 2093, 2092, 2091, -1, 2093, 2021, 2092, -1, 2093, 2023, 2021, -1, 2093, 2025, 2023, -1, 2094, 2093, 396, -1, 2094, 396, 2095, -1, 2094, 2026, 2025, -1, 2094, 2095, 2096, -1, 2094, 2096, 2097, -1, 2094, 2097, 2027, -1, 2094, 2025, 2093, -1, 2094, 2027, 2026, -1, 2098, 2032, 2029, -1, 2098, 2097, 2096, -1, 2098, 2027, 2097, -1, 2098, 2028, 2027, -1, 2098, 2029, 2028, -1, 2099, 396, 394, -1, 2099, 2095, 396, -1, 2099, 2098, 2096, -1, 2099, 2096, 2095, -1, 2099, 2032, 2098, -1, 2099, 2033, 2032, -1, 2100, 2101, 2102, -1, 2100, 2102, 2035, -1, 2100, 394, 2103, -1, 2100, 2034, 2033, -1, 2100, 2033, 2099, -1, 2100, 2035, 2034, -1, 2100, 2099, 394, -1, 2100, 2103, 2101, -1, 2104, 2102, 2101, -1, 2104, 2035, 2102, -1, 2104, 2036, 2035, -1, 2104, 2037, 2036, -1, 2104, 2039, 2037, -1, 2104, 2101, 2103, -1, 2105, 394, 392, -1, 2105, 2103, 394, -1, 2105, 392, 2040, -1, 2105, 2039, 2104, -1, 2105, 2040, 2039, -1, 2105, 2104, 2103, -1, 2106, 2008, 2063, -1, 2106, 2063, 2005, -1, 2106, 406, 2008, -1, 2106, 2005, 406, -1, 2107, 246, 2019, -1, 2107, 2020, 246, -1, 2107, 2019, 2086, -1, 2107, 2087, 2020, -1, 2107, 2086, 2087, -1, 2108, 1981, 1979, -1, 2109, 2057, 2059, -1, 2108, 1979, 2110, -1, 2109, 2111, 2112, -1, 2113, 233, 237, -1, 2109, 2112, 2114, -1, 2113, 2108, 2110, -1, 2109, 2114, 2057, -1, 2113, 237, 2108, -1, 2115, 2059, 2060, -1, 2115, 2116, 2111, -1, 2117, 2118, 2119, -1, 2117, 2113, 2110, -1, 2115, 2109, 2059, -1, 2115, 2111, 2109, -1, 2117, 233, 2113, -1, 2120, 2060, 2061, -1, 2117, 2121, 233, -1, 2120, 281, 2122, -1, 2117, 2123, 2118, -1, 2120, 2122, 2116, -1, 2120, 2116, 2115, -1, 2117, 2119, 2121, -1, 2120, 2115, 2060, -1, 2124, 224, 2125, -1, 2120, 2061, 281, -1, 2124, 2126, 222, -1, 2124, 2127, 2128, -1, 2124, 2125, 2129, -1, 2124, 2129, 2127, -1, 2124, 2128, 2130, -1, 2110, 1979, 1976, -1, 2124, 2130, 2126, -1, 2110, 1976, 1975, -1, 2124, 222, 224, -1, 2110, 1975, 156, -1, 2131, 2132, 480, -1, 2110, 156, 472, -1, 2131, 2127, 2133, -1, 2134, 2119, 2118, -1, 2131, 480, 2135, -1, 2134, 2136, 474, -1, 2131, 2133, 2132, -1, 2137, 222, 2126, -1, 2137, 2128, 2127, -1, 2137, 2130, 2128, -1, 2134, 2118, 2123, -1, 2137, 2127, 2131, -1, 2137, 2126, 2130, -1, 2134, 2138, 2136, -1, 2134, 2123, 2138, -1, 2139, 231, 233, -1, 2139, 2134, 474, -1, 2139, 233, 2121, -1, 2140, 2131, 2135, -1, 2140, 225, 222, -1, 2139, 2141, 2142, -1, 2139, 2142, 231, -1, 2140, 222, 2137, -1, 2139, 2119, 2134, -1, 2140, 2143, 225, -1, 2139, 2121, 2119, -1, 2140, 2137, 2131, -1, 2144, 2145, 2146, -1, 2147, 2148, 2149, -1, 2144, 2135, 2145, -1, 2147, 2149, 2150, -1, 2147, 2150, 2141, -1, 2144, 2146, 2151, -1, 2147, 2141, 2139, -1, 2147, 2139, 474, -1, 2147, 474, 2148, -1, 2144, 2140, 2135, -1, 2152, 2153, 2143, -1, 2152, 2151, 2154, -1, 2155, 2148, 476, -1, 2152, 2154, 2153, -1, 2152, 2143, 2140, -1, 2152, 2144, 2151, -1, 2152, 2140, 2144, -1, 2156, 2143, 2153, -1, 2156, 2151, 2146, -1, 2156, 2154, 2151, -1, 2157, 2148, 2155, -1, 2156, 2153, 2154, -1, 2157, 2149, 2148, -1, 2157, 2150, 2149, -1, 2156, 2146, 2158, -1, 2157, 2141, 2150, -1, 2159, 2143, 2156, -1, 2159, 280, 225, -1, 2160, 2141, 2157, -1, 2159, 2156, 2158, -1, 2160, 2161, 224, -1, 2159, 225, 2143, -1, 2160, 224, 231, -1, 2160, 2142, 2141, -1, 2160, 231, 2142, -1, 2162, 2158, 2163, -1, 2162, 280, 2159, -1, 2160, 2157, 2155, -1, 2162, 2122, 280, -1, 2160, 2155, 476, -1, 2162, 2159, 2158, -1, 2164, 476, 478, -1, 2162, 2116, 2122, -1, 2164, 478, 2165, -1, 2164, 2160, 476, -1, 2166, 2163, 2167, -1, 2166, 2168, 2112, -1, 2166, 2167, 2168, -1, 2166, 2112, 2111, -1, 2169, 2170, 2171, -1, 2166, 2111, 2116, -1, 2169, 2161, 2160, -1, 2166, 2162, 2163, -1, 2169, 2164, 2165, -1, 2166, 2116, 2162, -1, 2169, 2160, 2164, -1, 2172, 2117, 2110, -1, 2169, 2165, 2173, -1, 2172, 2123, 2117, -1, 2169, 2173, 2170, -1, 2172, 2110, 472, -1, 2169, 2171, 2161, -1, 2172, 472, 2136, -1, 2172, 2136, 2138, -1, 2172, 2138, 2123, -1, 2174, 2165, 478, -1, 2175, 2171, 2170, -1, 2175, 2165, 2174, -1, 2168, 2167, 484, -1, 2175, 2173, 2165, -1, 2175, 2170, 2173, -1, 2125, 224, 2161, -1, 2125, 2175, 2174, -1, 2125, 2174, 478, -1, 2125, 2171, 2175, -1, 2125, 2161, 2171, -1, 276, 281, 2061, -1, 2136, 472, 474, -1, 2176, 480, 2132, -1, 2177, 484, 408, -1, 2176, 478, 480, -1, 2177, 408, 2006, -1, 2176, 2125, 478, -1, 2176, 2132, 2133, -1, 2129, 2133, 2127, -1, 2129, 2125, 2176, -1, 2129, 2176, 2133, -1, 2122, 281, 280, -1, 2135, 480, 482, -1, 2178, 2006, 2007, -1, 2135, 482, 2145, -1, 2178, 2177, 2006, -1, 2158, 2145, 482, -1, 2178, 484, 2177, -1, 2158, 2146, 2145, -1, 2179, 2007, 2055, -1, 2179, 2168, 484, -1, 2148, 474, 476, -1, 2179, 2178, 2007, -1, 2179, 484, 2178, -1, 2163, 482, 484, -1, 2114, 2055, 2056, -1, 2114, 2056, 2057, -1, 2163, 2158, 482, -1, 2114, 2112, 2168, -1, 2163, 484, 2167, -1, 2114, 2179, 2055, -1, 2108, 237, 1969, -1, 2108, 1969, 1984, -1, 2108, 1984, 1981, -1, 2114, 2168, 2179, -1, 2180, 2181, 2182, -1, 2183, 2180, 2182, -1, 2184, 2185, 2186, -1, 2187, 2183, 2182, -1, 2188, 2187, 2182, -1, 2189, 2186, 2190, -1, 2191, 2182, 2192, -1, 2191, 2188, 2182, -1, 2189, 2184, 2186, -1, 2193, 2191, 2192, -1, 2194, 2190, 2195, -1, 2194, 2189, 2190, -1, 2196, 2193, 2192, -1, 2197, 2195, 2198, -1, 2197, 2194, 2195, -1, 2199, 2192, 2200, -1, 2201, 2197, 2198, -1, 2199, 2196, 2192, -1, 2202, 2199, 2200, -1, 2203, 2201, 2198, -1, 2204, 2201, 2203, -1, 2205, 2200, 2206, -1, 2207, 2203, 2208, -1, 2205, 2202, 2200, -1, 2207, 2204, 2203, -1, 2209, 2206, 2210, -1, 2211, 2207, 2208, -1, 2209, 2205, 2206, -1, 2212, 2209, 2210, -1, 2213, 2211, 2208, -1, 2214, 2212, 2210, -1, 2215, 2212, 2214, -1, 2216, 2208, 2217, -1, 2218, 2215, 2214, -1, 2216, 2213, 2208, -1, 2219, 2215, 2218, -1, 2220, 2219, 2218, -1, 2221, 2216, 2217, -1, 2222, 2221, 2217, -1, 2223, 2222, 2217, -1, 2224, 2217, 2225, -1, 2224, 2223, 2217, -1, 2226, 2224, 2225, -1, 2227, 2226, 2225, -1, 2227, 2225, 2228, -1, 2229, 2227, 2228, -1, 2230, 2229, 2228, -1, 2230, 2228, 2231, -1, 2232, 2230, 2231, -1, 2232, 2231, 2233, -1, 2234, 2232, 2233, -1, 2235, 2234, 2233, -1, 2235, 2233, 2236, -1, 2237, 2235, 2236, -1, 2238, 2237, 2236, -1, 2238, 2236, 2239, -1, 2240, 2238, 2239, -1, 2181, 2240, 2239, -1, 2181, 2239, 2182, -1, 2241, 2242, 2243, -1, 2244, 2242, 2241, -1, 2245, 2242, 2244, -1, 2246, 2242, 2245, -1, 2247, 2248, 2249, -1, 2250, 2248, 2247, -1, 2251, 2248, 2250, -1, 2252, 2248, 2251, -1, 2243, 2248, 2252, -1, 2242, 2248, 2243, -1, 2253, 2254, 2255, -1, 2256, 2253, 2255, -1, 2257, 2258, 2259, -1, 2260, 2256, 2255, -1, 2261, 2260, 2255, -1, 2262, 2259, 2263, -1, 2264, 2255, 2265, -1, 2264, 2261, 2255, -1, 2262, 2257, 2259, -1, 2266, 2264, 2265, -1, 2267, 2263, 2268, -1, 2267, 2262, 2263, -1, 2269, 2266, 2265, -1, 2270, 2268, 2271, -1, 2270, 2267, 2268, -1, 2272, 2265, 2273, -1, 2274, 2270, 2271, -1, 2272, 2269, 2265, -1, 2275, 2272, 2273, -1, 2276, 2274, 2271, -1, 2277, 2274, 2276, -1, 2278, 2273, 2279, -1, 2280, 2276, 2281, -1, 2278, 2275, 2273, -1, 2280, 2277, 2276, -1, 2282, 2279, 2283, -1, 2284, 2280, 2281, -1, 2282, 2278, 2279, -1, 2285, 2282, 2283, -1, 2286, 2284, 2281, -1, 2287, 2285, 2283, -1, 2288, 2285, 2287, -1, 2289, 2281, 2290, -1, 2291, 2288, 2287, -1, 2289, 2286, 2281, -1, 2292, 2288, 2291, -1, 2293, 2292, 2291, -1, 2294, 2289, 2290, -1, 2295, 2294, 2290, -1, 2296, 2295, 2290, -1, 2297, 2290, 2298, -1, 2297, 2296, 2290, -1, 2299, 2297, 2298, -1, 2300, 2299, 2298, -1, 2300, 2298, 2301, -1, 2302, 2300, 2301, -1, 2303, 2302, 2301, -1, 2303, 2301, 2304, -1, 2305, 2303, 2304, -1, 2305, 2304, 2306, -1, 2307, 2305, 2306, -1, 2308, 2307, 2306, -1, 2308, 2306, 2309, -1, 2310, 2308, 2309, -1, 2311, 2310, 2309, -1, 2311, 2309, 2312, -1, 2313, 2311, 2312, -1, 2254, 2313, 2312, -1, 2254, 2312, 2255, -1, 2314, 2315, 2316, -1, 2317, 2315, 2314, -1, 2318, 2315, 2317, -1, 2319, 2315, 2318, -1, 2320, 2321, 2322, -1, 2323, 2321, 2320, -1, 2324, 2321, 2323, -1, 2325, 2321, 2324, -1, 2316, 2321, 2325, -1, 2315, 2321, 2316, -1, 2326, 2327, 2328, -1, 2326, 2328, 2329, -1, 2330, 2326, 2329, -1, 2331, 2326, 2330, -1, 2332, 2331, 2330, -1, 2333, 2331, 2332, -1, 2334, 2335, 2336, -1, 2337, 2335, 2334, -1, 2338, 2337, 2334, -1, 2339, 2337, 2338, -1, 2340, 2338, 2341, -1, 2340, 2339, 2338, -1, 2342, 2343, 2344, -1, 2345, 2343, 2346, -1, 2344, 2343, 2345, -1, 2347, 2348, 2349, -1, 2350, 2351, 2352, -1, 2348, 2353, 2349, -1, 2346, 2351, 2350, -1, 2343, 2351, 2346, -1, 2353, 2354, 2355, -1, 2348, 2354, 2353, -1, 2352, 2356, 2357, -1, 2351, 2356, 2352, -1, 2357, 2356, 2358, -1, 2355, 2359, 2360, -1, 2354, 2359, 2355, -1, 2356, 2361, 2358, -1, 2358, 2361, 2362, -1, 2359, 2363, 2360, -1, 2362, 2364, 2365, -1, 2363, 2366, 2367, -1, 2365, 2364, 2368, -1, 2361, 2364, 2362, -1, 2359, 2366, 2363, -1, 2369, 2370, 2371, -1, 2372, 2370, 2369, -1, 2368, 2370, 2372, -1, 2364, 2370, 2368, -1, 2373, 2374, 2375, -1, 2371, 2374, 2373, -1, 2370, 2374, 2371, -1, 2376, 2377, 2378, -1, 2375, 2377, 2376, -1, 2379, 2377, 2380, -1, 2378, 2377, 2379, -1, 2374, 2377, 2375, -1, 2381, 2382, 2383, -1, 2380, 2382, 2381, -1, 2377, 2382, 2380, -1, 2383, 2384, 2385, -1, 2382, 2384, 2383, -1, 2384, 2386, 2385, -1, 2386, 2387, 2388, -1, 2389, 2390, 2391, -1, 2392, 2390, 2389, -1, 2367, 2390, 2392, -1, 2384, 2387, 2386, -1, 2366, 2390, 2367, -1, 2388, 2393, 2394, -1, 2387, 2393, 2388, -1, 2394, 2395, 2396, -1, 2396, 2395, 2397, -1, 2398, 2342, 2344, -1, 2399, 2342, 2398, -1, 2393, 2395, 2394, -1, 2400, 2342, 2399, -1, 2401, 2342, 2400, -1, 2391, 2342, 2401, -1, 2390, 2342, 2391, -1, 2402, 2403, 2404, -1, 2405, 2403, 2402, -1, 2406, 2407, 2408, -1, 2409, 2403, 2405, -1, 2407, 2410, 2408, -1, 2411, 2412, 2413, -1, 2404, 2412, 2411, -1, 2403, 2412, 2404, -1, 2410, 2414, 2415, -1, 2407, 2414, 2410, -1, 2413, 2416, 2417, -1, 2417, 2416, 2418, -1, 2412, 2416, 2413, -1, 2415, 2419, 2420, -1, 2414, 2419, 2415, -1, 2416, 2421, 2418, -1, 2418, 2421, 2422, -1, 2419, 2423, 2420, -1, 2421, 2424, 2422, -1, 2423, 2425, 2426, -1, 2422, 2424, 2427, -1, 2419, 2425, 2423, -1, 2427, 2424, 2428, -1, 2424, 2429, 2428, -1, 2430, 2429, 2431, -1, 2432, 2429, 2430, -1, 2428, 2429, 2432, -1, 2429, 2433, 2431, -1, 2434, 2433, 2435, -1, 2431, 2433, 2434, -1, 2433, 2436, 2435, -1, 2437, 2436, 2438, -1, 2435, 2436, 2437, -1, 2439, 2436, 2440, -1, 2438, 2436, 2439, -1, 2436, 2441, 2440, -1, 2442, 2441, 2443, -1, 2440, 2441, 2442, -1, 2443, 2444, 2445, -1, 2441, 2444, 2443, -1, 2444, 2446, 2445, -1, 2447, 2448, 2449, -1, 2446, 2450, 2451, -1, 2452, 2448, 2447, -1, 2426, 2448, 2452, -1, 2425, 2448, 2426, -1, 2444, 2450, 2446, -1, 2451, 2453, 2454, -1, 2450, 2453, 2451, -1, 2455, 2409, 2456, -1, 2454, 2457, 2458, -1, 2449, 2409, 2455, -1, 2458, 2457, 2459, -1, 2453, 2457, 2454, -1, 2460, 2409, 2405, -1, 2461, 2409, 2460, -1, 2456, 2409, 2461, -1, 2448, 2409, 2449, -1, 2462, 2463, 2464, -1, 2464, 2463, 2465, -1, 2465, 2466, 2467, -1, 2463, 2466, 2465, -1, 2467, 2468, 2469, -1, 2466, 2468, 2467, -1, 2468, 2470, 2469, -1, 2469, 2471, 2472, -1, 2470, 2471, 2469, -1, 2472, 2473, 2474, -1, 2471, 2473, 2472, -1, 2474, 2475, 2476, -1, 2473, 2475, 2474, -1, 2475, 2477, 2476, -1, 2478, 2479, 2480, -1, 2480, 2481, 2482, -1, 2479, 2481, 2480, -1, 2482, 2483, 2484, -1, 2481, 2483, 2482, -1, 2485, 2486, 2487, -1, 2484, 2486, 2485, -1, 2483, 2486, 2484, -1, 2487, 2488, 2489, -1, 2486, 2488, 2487, -1, 2489, 2490, 2491, -1, 2488, 2490, 2489, -1, 2491, 2492, 2493, -1, 2490, 2492, 2491, -1, 2494, 2495, 2496, -1, 2497, 2494, 2496, -1, 2498, 2494, 2497, -1, 2499, 2498, 2500, -1, 2499, 2500, 2501, -1, 2499, 2501, 2502, -1, 2499, 2494, 2498, -1, 2503, 2504, 2505, -1, 2506, 2503, 2505, -1, 2507, 2503, 2506, -1, 2508, 2507, 2509, -1, 2508, 2509, 2510, -1, 2508, 2510, 2511, -1, 2508, 2503, 2507, -1, 2248, 2321, 2315, -1, 2248, 2233, 2231, -1, 2248, 2231, 2228, -1, 2248, 2228, 2225, -1, 2248, 2225, 2217, -1, 2248, 2217, 2208, -1, 2248, 2208, 2203, -1, 2248, 2203, 2198, -1, 2248, 2198, 2195, -1, 2248, 2195, 2190, -1, 2248, 2190, 2186, -1, 2248, 2186, 2512, -1, 2248, 2512, 2513, -1, 2248, 2315, 2233, -1, 2298, 2290, 2321, -1, 2301, 2298, 2321, -1, 2304, 2301, 2321, -1, 2242, 2321, 2248, -1, 2514, 2515, 2218, -1, 2242, 2304, 2321, -1, 2242, 2312, 2309, -1, 2242, 2309, 2306, -1, 2242, 2306, 2304, -1, 2315, 2218, 2214, -1, 2315, 2214, 2210, -1, 2315, 2210, 2206, -1, 2315, 2206, 2200, -1, 2315, 2200, 2192, -1, 2315, 2192, 2182, -1, 2291, 2242, 2516, -1, 2291, 2516, 2517, -1, 2315, 2514, 2218, -1, 2255, 2312, 2242, -1, 2239, 2315, 2182, -1, 2287, 2242, 2291, -1, 2236, 2315, 2239, -1, 2265, 2255, 2242, -1, 2233, 2315, 2236, -1, 2283, 2242, 2287, -1, 2273, 2265, 2242, -1, 2279, 2242, 2283, -1, 2279, 2273, 2242, -1, 2518, 2519, 2321, -1, 2259, 2518, 2321, -1, 2263, 2259, 2321, -1, 2268, 2263, 2321, -1, 2271, 2268, 2321, -1, 2276, 2271, 2321, -1, 2281, 2276, 2321, -1, 2290, 2281, 2321, -1, 2393, 2508, 2395, -1, 2387, 2508, 2393, -1, 2384, 2508, 2387, -1, 2382, 2508, 2384, -1, 2377, 2508, 2382, -1, 2374, 2508, 2377, -1, 2370, 2508, 2374, -1, 2364, 2508, 2370, -1, 2361, 2508, 2364, -1, 2494, 2508, 2361, -1, 2433, 2429, 2499, -1, 2429, 2424, 2499, -1, 2424, 2421, 2499, -1, 2499, 2503, 2494, -1, 2494, 2503, 2508, -1, 2416, 2503, 2421, -1, 2412, 2503, 2416, -1, 2421, 2503, 2499, -1, 2412, 2403, 2503, -1, 2503, 2520, 2521, -1, 2503, 2407, 2520, -1, 2342, 2494, 2343, -1, 2390, 2494, 2342, -1, 2366, 2494, 2390, -1, 2359, 2494, 2366, -1, 2403, 2409, 2503, -1, 2354, 2494, 2359, -1, 2348, 2494, 2354, -1, 2522, 2494, 2348, -1, 2523, 2494, 2522, -1, 2503, 2414, 2407, -1, 2409, 2448, 2503, -1, 2494, 2351, 2343, -1, 2503, 2419, 2414, -1, 2494, 2356, 2351, -1, 2448, 2425, 2503, -1, 2503, 2425, 2419, -1, 2494, 2361, 2356, -1, 2524, 2525, 2499, -1, 2525, 2457, 2499, -1, 2457, 2453, 2499, -1, 2453, 2450, 2499, -1, 2450, 2444, 2499, -1, 2444, 2441, 2499, -1, 2441, 2436, 2499, -1, 2395, 2526, 2527, -1, 2436, 2433, 2499, -1, 2395, 2508, 2526, -1, 2528, 2529, 2530, -1, 2529, 2531, 2532, -1, 2528, 2531, 2529, -1, 2532, 2533, 2534, -1, 2531, 2533, 2532, -1, 2533, 2535, 2534, -1, 2533, 2536, 2535, -1, 2536, 2537, 2535, -1, 2536, 2538, 2537, -1, 2538, 2539, 2537, -1, 2538, 2540, 2539, -1, 2540, 2541, 2539, -1, 2540, 2542, 2541, -1, 2542, 2543, 2541, -1, 2542, 2544, 2543, -1, 2544, 2545, 2543, -1, 2545, 2546, 2543, -1, 2545, 2547, 2546, -1, 2547, 2548, 2546, -1, 2549, 2550, 2551, -1, 2549, 2552, 2550, -1, 2552, 2553, 2550, -1, 2552, 2554, 2553, -1, 2554, 2555, 2553, -1, 2554, 2556, 2555, -1, 2556, 2557, 2555, -1, 2556, 2558, 2557, -1, 2558, 2559, 2557, -1, 2558, 2560, 2559, -1, 2560, 2561, 2559, -1, 2561, 2562, 2563, -1, 2560, 2562, 2561, -1, 2563, 2564, 2565, -1, 2562, 2564, 2563, -1, 2565, 2566, 2567, -1, 2564, 2566, 2565, -1, 2566, 2568, 2567, -1, 2569, 2570, 2571, -1, 2571, 2572, 2573, -1, 2570, 2572, 2571, -1, 2573, 2574, 2575, -1, 2572, 2574, 2573, -1, 2574, 2576, 2575, -1, 2576, 2577, 2575, -1, 2576, 2578, 2577, -1, 2578, 2579, 2577, -1, 2578, 2580, 2579, -1, 2580, 2581, 2579, -1, 2580, 2582, 2581, -1, 2582, 2583, 2581, -1, 2582, 2584, 2583, -1, 2584, 2585, 2583, -1, 2584, 2586, 2585, -1, 2586, 2587, 2585, -1, 2586, 2588, 2587, -1, 2589, 2590, 2591, -1, 2590, 2592, 2591, -1, 2592, 2593, 2594, -1, 2590, 2593, 2592, -1, 2593, 2595, 2594, -1, 2593, 2596, 2595, -1, 2596, 2597, 2595, -1, 2596, 2598, 2597, -1, 2598, 2599, 2597, -1, 2598, 2600, 2599, -1, 2600, 2601, 2599, -1, 2600, 2602, 2601, -1, 2602, 2603, 2601, -1, 2602, 2604, 2603, -1, 2603, 2605, 2606, -1, 2604, 2605, 2603, -1, 2605, 2607, 2606, -1, 2607, 2608, 2606, -1, 2607, 2609, 2608, -1, 2610, 2549, 2551, -1, 2611, 2610, 2551, -1, 2612, 2610, 2611, -1, 2613, 2612, 2611, -1, 2614, 2612, 2613, -1, 2615, 2614, 2613, -1, 2616, 2614, 2615, -1, 2617, 2616, 2615, -1, 2618, 2616, 2617, -1, 2619, 2618, 2617, -1, 2620, 2618, 2619, -1, 2621, 2620, 2619, -1, 2622, 2621, 2623, -1, 2622, 2620, 2621, -1, 2332, 2623, 2333, -1, 2332, 2622, 2623, -1, 2624, 2528, 2530, -1, 2624, 2530, 2625, -1, 2626, 2624, 2625, -1, 2627, 2626, 2625, -1, 2628, 2626, 2627, -1, 2629, 2628, 2627, -1, 2630, 2628, 2629, -1, 2631, 2630, 2629, -1, 2632, 2630, 2631, -1, 2633, 2632, 2631, -1, 2634, 2632, 2633, -1, 2635, 2634, 2633, -1, 2636, 2635, 2637, -1, 2636, 2634, 2635, -1, 2341, 2637, 2340, -1, 2341, 2636, 2637, -1, 2638, 2328, 2327, -1, 2638, 2327, 2639, -1, 2640, 2638, 2639, -1, 2641, 2640, 2639, -1, 2642, 2640, 2641, -1, 2643, 2642, 2641, -1, 2644, 2642, 2643, -1, 2645, 2644, 2643, -1, 2646, 2644, 2645, -1, 2647, 2646, 2645, -1, 2648, 2646, 2647, -1, 2649, 2648, 2647, -1, 2650, 2649, 2651, -1, 2650, 2648, 2649, -1, 2609, 2651, 2608, -1, 2609, 2650, 2651, -1, 2652, 2336, 2335, -1, 2652, 2335, 2653, -1, 2654, 2652, 2653, -1, 2655, 2654, 2653, -1, 2656, 2654, 2655, -1, 2657, 2656, 2655, -1, 2658, 2656, 2657, -1, 2659, 2658, 2657, -1, 2660, 2658, 2659, -1, 2661, 2660, 2659, -1, 2662, 2660, 2661, -1, 2663, 2662, 2661, -1, 2664, 2662, 2663, -1, 2665, 2664, 2663, -1, 2588, 2665, 2587, -1, 2588, 2664, 2665, -1, 2477, 2666, 2476, -1, 2667, 2666, 2477, -1, 2668, 2667, 2477, -1, 2669, 2667, 2668, -1, 2670, 2669, 2668, -1, 2671, 2669, 2670, -1, 2569, 2671, 2670, -1, 2672, 2569, 2670, -1, 2570, 2569, 2672, -1, 2591, 2673, 2589, -1, 2674, 2675, 2676, -1, 2674, 2676, 2589, -1, 2674, 2589, 2673, -1, 2677, 2678, 2675, -1, 2677, 2675, 2674, -1, 2462, 2679, 2678, -1, 2462, 2464, 2679, -1, 2462, 2678, 2677, -1, 2478, 2680, 2479, -1, 2681, 2680, 2478, -1, 2682, 2681, 2478, -1, 2683, 2681, 2682, -1, 2684, 2683, 2682, -1, 2685, 2683, 2684, -1, 2568, 2685, 2684, -1, 2686, 2568, 2684, -1, 2567, 2568, 2686, -1, 2547, 2687, 2548, -1, 2688, 2689, 2690, -1, 2688, 2690, 2548, -1, 2688, 2548, 2687, -1, 2691, 2692, 2689, -1, 2691, 2689, 2688, -1, 2493, 2492, 2693, -1, 2493, 2693, 2692, -1, 2493, 2692, 2691, -1, 2459, 2457, 2694, -1, 2694, 2525, 2695, -1, 2457, 2525, 2694, -1, 2695, 2524, 2696, -1, 2525, 2524, 2695, -1, 2696, 2499, 2502, -1, 2524, 2499, 2696, -1, 2495, 2494, 2697, -1, 2697, 2523, 2698, -1, 2494, 2523, 2697, -1, 2698, 2522, 2699, -1, 2523, 2522, 2698, -1, 2699, 2348, 2347, -1, 2522, 2348, 2699, -1, 2700, 2220, 2218, -1, 2700, 2218, 2515, -1, 2701, 2515, 2514, -1, 2701, 2700, 2515, -1, 2319, 2514, 2315, -1, 2319, 2701, 2514, -1, 2322, 2321, 2519, -1, 2702, 2519, 2518, -1, 2702, 2322, 2519, -1, 2703, 2518, 2259, -1, 2703, 2702, 2518, -1, 2258, 2703, 2259, -1, 2704, 2293, 2291, -1, 2704, 2291, 2517, -1, 2705, 2517, 2516, -1, 2705, 2704, 2517, -1, 2246, 2516, 2242, -1, 2246, 2705, 2516, -1, 2249, 2248, 2513, -1, 2706, 2513, 2512, -1, 2706, 2249, 2513, -1, 2707, 2512, 2186, -1, 2707, 2706, 2512, -1, 2185, 2707, 2186, -1, 2504, 2503, 2708, -1, 2708, 2521, 2709, -1, 2503, 2521, 2708, -1, 2709, 2520, 2710, -1, 2521, 2520, 2709, -1, 2710, 2407, 2406, -1, 2520, 2407, 2710, -1, 2397, 2395, 2711, -1, 2711, 2527, 2712, -1, 2395, 2527, 2711, -1, 2712, 2526, 2713, -1, 2527, 2526, 2712, -1, 2713, 2508, 2511, -1, 2526, 2508, 2713, -1, 2678, 2679, 2714, -1, 2715, 2707, 2185, -1, 2676, 2675, 2716, -1, 2717, 2718, 2249, -1, 2717, 2706, 2707, -1, 2717, 2249, 2706, -1, 2719, 2720, 2718, -1, 2719, 2718, 2717, -1, 2721, 2722, 2720, -1, 2721, 2720, 2719, -1, 2723, 2724, 2722, -1, 2723, 2722, 2721, -1, 2725, 2726, 2724, -1, 2725, 2724, 2723, -1, 2727, 2714, 2726, -1, 2727, 2675, 2678, -1, 2727, 2726, 2725, -1, 2727, 2678, 2714, -1, 2728, 2723, 2721, -1, 2728, 2725, 2723, -1, 2728, 2717, 2707, -1, 2728, 2675, 2727, -1, 2728, 2727, 2725, -1, 2728, 2719, 2717, -1, 2728, 2721, 2719, -1, 2729, 2675, 2728, -1, 2729, 2728, 2707, -1, 2730, 2731, 2716, -1, 2730, 2732, 2731, -1, 2730, 2733, 2732, -1, 2730, 2734, 2733, -1, 2730, 2715, 2734, -1, 2730, 2729, 2707, -1, 2730, 2707, 2715, -1, 2730, 2675, 2729, -1, 2730, 2716, 2675, -1, 2735, 2589, 2676, -1, 2716, 2735, 2676, -1, 2736, 2735, 2716, -1, 2731, 2736, 2716, -1, 2737, 2736, 2731, -1, 2732, 2737, 2731, -1, 2738, 2737, 2732, -1, 2733, 2738, 2732, -1, 2734, 2739, 2738, -1, 2734, 2738, 2733, -1, 2715, 2740, 2739, -1, 2715, 2739, 2734, -1, 2185, 2184, 2740, -1, 2185, 2740, 2715, -1, 2718, 2741, 2247, -1, 2718, 2247, 2249, -1, 2720, 2742, 2741, -1, 2720, 2741, 2718, -1, 2722, 2743, 2742, -1, 2722, 2742, 2720, -1, 2724, 2744, 2743, -1, 2724, 2743, 2722, -1, 2745, 2744, 2724, -1, 2726, 2745, 2724, -1, 2746, 2745, 2726, -1, 2714, 2746, 2726, -1, 2464, 2746, 2714, -1, 2679, 2464, 2714, -1, 2747, 2189, 2194, -1, 2747, 2748, 2189, -1, 2749, 2750, 2602, -1, 2747, 2751, 2752, -1, 2747, 2752, 2748, -1, 2747, 2194, 2751, -1, 2753, 2213, 2216, -1, 2753, 2754, 2609, -1, 2749, 2604, 2750, -1, 2753, 2755, 2754, -1, 2753, 2756, 2755, -1, 2757, 2604, 2749, -1, 2753, 2758, 2756, -1, 2753, 2216, 2758, -1, 2753, 2609, 2607, -1, 2757, 2759, 2604, -1, 2760, 2207, 2211, -1, 2761, 2762, 2763, -1, 2760, 2204, 2207, -1, 2761, 2213, 2753, -1, 2760, 2211, 2764, -1, 2761, 2765, 2766, -1, 2760, 2764, 2759, -1, 2761, 2766, 2762, -1, 2761, 2753, 2607, -1, 2760, 2759, 2757, -1, 2761, 2763, 2213, -1, 2761, 2607, 2765, -1, 2767, 2602, 2600, -1, 2768, 2602, 2767, -1, 2769, 2184, 2189, -1, 2769, 2189, 2748, -1, 2769, 2770, 2771, -1, 2769, 2772, 2770, -1, 2769, 2771, 2590, -1, 2769, 2748, 2772, -1, 2773, 2602, 2768, -1, 2774, 2589, 2735, -1, 2774, 2735, 2736, -1, 2774, 2736, 2737, -1, 2774, 2737, 2738, -1, 2773, 2749, 2602, -1, 2774, 2738, 2739, -1, 2774, 2739, 2740, -1, 2774, 2740, 2184, -1, 2774, 2590, 2589, -1, 2775, 2749, 2773, -1, 2774, 2184, 2769, -1, 2774, 2769, 2590, -1, 2775, 2757, 2749, -1, 2776, 2760, 2757, -1, 2776, 2757, 2775, -1, 2776, 2204, 2760, -1, 2777, 2600, 2598, -1, 2777, 2767, 2600, -1, 2778, 2768, 2767, -1, 2778, 2767, 2777, -1, 2779, 2773, 2768, -1, 2779, 2768, 2778, -1, 2780, 2775, 2773, -1, 2780, 2773, 2779, -1, 2781, 2775, 2780, -1, 2781, 2201, 2204, -1, 2781, 2776, 2775, -1, 2781, 2204, 2776, -1, 2782, 2777, 2598, -1, 2782, 2598, 2596, -1, 2783, 2778, 2777, -1, 2783, 2777, 2782, -1, 2784, 2779, 2778, -1, 2784, 2778, 2783, -1, 2785, 2779, 2784, -1, 2785, 2780, 2779, -1, 2786, 2781, 2780, -1, 2786, 2197, 2201, -1, 2786, 2201, 2781, -1, 2786, 2194, 2197, -1, 2786, 2780, 2785, -1, 2787, 2596, 2593, -1, 2787, 2782, 2596, -1, 2788, 2782, 2787, -1, 2788, 2783, 2782, -1, 2765, 2607, 2605, -1, 2788, 2787, 2593, -1, 2789, 2784, 2783, -1, 2766, 2765, 2605, -1, 2789, 2783, 2788, -1, 2762, 2766, 2605, -1, 2752, 2784, 2789, -1, 2752, 2785, 2784, -1, 2751, 2194, 2786, -1, 2213, 2763, 2211, -1, 2751, 2786, 2785, -1, 2790, 2605, 2604, -1, 2751, 2785, 2752, -1, 2791, 2790, 2604, -1, 2771, 2593, 2590, -1, 2791, 2605, 2790, -1, 2792, 2791, 2604, -1, 2792, 2605, 2791, -1, 2770, 2788, 2593, -1, 2759, 2792, 2604, -1, 2759, 2605, 2792, -1, 2759, 2762, 2605, -1, 2770, 2593, 2771, -1, 2764, 2763, 2762, -1, 2764, 2211, 2763, -1, 2764, 2762, 2759, -1, 2772, 2789, 2788, -1, 2793, 2604, 2602, -1, 2772, 2788, 2770, -1, 2750, 2604, 2793, -1, 2750, 2793, 2602, -1, 2748, 2752, 2789, -1, 2748, 2789, 2772, -1, 2794, 2795, 2796, -1, 2797, 2243, 2798, -1, 2797, 2798, 2799, -1, 2794, 2796, 2800, -1, 2797, 2799, 2801, -1, 2802, 2803, 2804, -1, 2805, 2806, 2807, -1, 2805, 2808, 2806, -1, 2809, 2810, 2811, -1, 2802, 2812, 2803, -1, 2813, 2467, 2469, -1, 2809, 2811, 2808, -1, 2813, 2800, 2467, -1, 2814, 2804, 2795, -1, 2814, 2795, 2794, -1, 2815, 2816, 2474, -1, 2815, 2474, 2817, -1, 2818, 2808, 2805, -1, 2819, 2820, 2812, -1, 2819, 2812, 2802, -1, 2818, 2809, 2808, -1, 2821, 2794, 2800, -1, 2822, 2810, 2809, -1, 2821, 2800, 2813, -1, 2822, 2801, 2810, -1, 2823, 2802, 2804, -1, 2823, 2804, 2814, -1, 2824, 2817, 2825, -1, 2824, 2815, 2817, -1, 2250, 2247, 2741, -1, 2826, 2813, 2469, -1, 2824, 2807, 2816, -1, 2824, 2816, 2815, -1, 2827, 2251, 2250, -1, 2828, 2809, 2818, -1, 2827, 2829, 2820, -1, 2828, 2822, 2809, -1, 2827, 2250, 2829, -1, 2827, 2820, 2819, -1, 2830, 2243, 2797, -1, 2830, 2241, 2243, -1, 2830, 2797, 2801, -1, 2831, 2794, 2821, -1, 2830, 2801, 2822, -1, 2831, 2814, 2794, -1, 2832, 2825, 2833, -1, 2832, 2807, 2824, -1, 2832, 2824, 2825, -1, 2832, 2805, 2807, -1, 2834, 2802, 2823, -1, 2834, 2819, 2802, -1, 2835, 2813, 2826, -1, 2836, 2822, 2828, -1, 2836, 2241, 2830, -1, 2836, 2830, 2822, -1, 2835, 2821, 2813, -1, 2837, 2823, 2814, -1, 2838, 2833, 2839, -1, 2838, 2805, 2832, -1, 2838, 2818, 2805, -1, 2838, 2832, 2833, -1, 2837, 2814, 2831, -1, 2840, 2469, 2472, -1, 2841, 2818, 2838, -1, 2817, 2474, 2476, -1, 2841, 2839, 2842, -1, 2840, 2826, 2469, -1, 2841, 2828, 2818, -1, 2843, 2819, 2834, -1, 2843, 2252, 2251, -1, 2841, 2838, 2839, -1, 2843, 2827, 2819, -1, 2844, 2836, 2828, -1, 2843, 2251, 2827, -1, 2844, 2842, 2845, -1, 2846, 2831, 2821, -1, 2844, 2244, 2241, -1, 2844, 2241, 2836, -1, 2844, 2841, 2842, -1, 2844, 2845, 2244, -1, 2844, 2828, 2841, -1, 2846, 2821, 2835, -1, 2847, 2834, 2823, -1, 2847, 2823, 2837, -1, 2848, 2835, 2826, -1, 2848, 2826, 2840, -1, 2849, 2831, 2846, -1, 2849, 2837, 2831, -1, 2850, 2252, 2843, -1, 2850, 2834, 2847, -1, 2245, 2244, 2845, -1, 2850, 2843, 2834, -1, 2851, 2746, 2464, -1, 2811, 2846, 2835, -1, 2851, 2464, 2465, -1, 2811, 2835, 2848, -1, 2852, 2745, 2746, -1, 2853, 2840, 2472, -1, 2852, 2746, 2851, -1, 2799, 2847, 2837, -1, 2803, 2744, 2745, -1, 2799, 2837, 2849, -1, 2803, 2745, 2852, -1, 2810, 2849, 2846, -1, 2812, 2743, 2744, -1, 2810, 2846, 2811, -1, 2812, 2744, 2803, -1, 2816, 2472, 2474, -1, 2796, 2465, 2467, -1, 2816, 2853, 2472, -1, 2796, 2851, 2465, -1, 2806, 2848, 2840, -1, 2820, 2742, 2743, -1, 2820, 2743, 2812, -1, 2806, 2840, 2853, -1, 2798, 2243, 2252, -1, 2798, 2252, 2850, -1, 2798, 2847, 2799, -1, 2798, 2850, 2847, -1, 2795, 2851, 2796, -1, 2801, 2849, 2810, -1, 2795, 2852, 2851, -1, 2801, 2799, 2849, -1, 2800, 2796, 2467, -1, 2807, 2853, 2816, -1, 2829, 2741, 2742, -1, 2807, 2806, 2853, -1, 2829, 2742, 2820, -1, 2829, 2250, 2741, -1, 2804, 2803, 2852, -1, 2808, 2811, 2848, -1, 2808, 2848, 2806, -1, 2804, 2852, 2795, -1, 2854, 2227, 2229, -1, 2855, 2854, 2229, -1, 2221, 2754, 2755, -1, 2221, 2755, 2756, -1, 2221, 2756, 2758, -1, 2221, 2758, 2216, -1, 2640, 2856, 2638, -1, 2857, 2229, 2230, -1, 2857, 2230, 2858, -1, 2859, 2857, 2858, -1, 2859, 2858, 2860, -1, 2859, 2229, 2857, -1, 2861, 2859, 2860, -1, 2861, 2862, 2863, -1, 2861, 2860, 2862, -1, 2861, 2229, 2859, -1, 2864, 2855, 2229, -1, 2864, 2229, 2861, -1, 2864, 2863, 2865, -1, 2864, 2861, 2863, -1, 2866, 2638, 2856, -1, 2866, 2865, 2867, -1, 2866, 2855, 2864, -1, 2866, 2864, 2865, -1, 2866, 2867, 2638, -1, 2866, 2856, 2855, -1, 2868, 2646, 2648, -1, 2868, 2869, 2870, -1, 2868, 2870, 2223, -1, 2868, 2871, 2869, -1, 2868, 2648, 2871, -1, 2872, 2223, 2224, -1, 2872, 2224, 2873, -1, 2872, 2868, 2223, -1, 2872, 2874, 2646, -1, 2872, 2873, 2875, -1, 2872, 2646, 2868, -1, 2872, 2875, 2874, -1, 2876, 2873, 2224, -1, 2876, 2875, 2873, -1, 2876, 2874, 2875, -1, 2877, 2644, 2646, -1, 2877, 2874, 2876, -1, 2877, 2646, 2874, -1, 2877, 2876, 2224, -1, 2878, 2224, 2226, -1, 2878, 2879, 2880, -1, 2878, 2644, 2877, -1, 2878, 2877, 2224, -1, 2878, 2226, 2879, -1, 2878, 2881, 2644, -1, 2878, 2880, 2882, -1, 2878, 2882, 2881, -1, 2883, 2880, 2879, -1, 2883, 2879, 2226, -1, 2883, 2882, 2880, -1, 2883, 2881, 2882, -1, 2884, 2642, 2644, -1, 2884, 2883, 2226, -1, 2328, 2638, 2867, -1, 2884, 2881, 2883, -1, 2885, 2221, 2222, -1, 2884, 2644, 2881, -1, 2886, 2885, 2222, -1, 2886, 2221, 2885, -1, 2887, 2226, 2227, -1, 2887, 2884, 2226, -1, 2888, 2886, 2222, -1, 2887, 2227, 2889, -1, 2888, 2221, 2886, -1, 2890, 2889, 2891, -1, 2890, 2891, 2892, -1, 2893, 2888, 2222, -1, 2890, 2884, 2887, -1, 2893, 2754, 2221, -1, 2890, 2892, 2642, -1, 2893, 2221, 2888, -1, 2890, 2642, 2884, -1, 2890, 2887, 2889, -1, 2894, 2891, 2889, -1, 2650, 2609, 2754, -1, 2894, 2892, 2891, -1, 2650, 2754, 2893, -1, 2870, 2222, 2223, -1, 2894, 2889, 2227, -1, 2895, 2894, 2227, -1, 2869, 2222, 2870, -1, 2895, 2640, 2642, -1, 2895, 2642, 2892, -1, 2871, 2650, 2893, -1, 2895, 2892, 2894, -1, 2871, 2222, 2869, -1, 2871, 2893, 2222, -1, 2648, 2650, 2871, -1, 2896, 2895, 2227, -1, 2896, 2227, 2854, -1, 2897, 2854, 2855, -1, 2897, 2856, 2640, -1, 2897, 2896, 2854, -1, 2897, 2640, 2895, -1, 2897, 2895, 2896, -1, 2897, 2855, 2856, -1, 2898, 2246, 2245, -1, 2845, 2898, 2245, -1, 2899, 2898, 2845, -1, 2842, 2899, 2845, -1, 2900, 2899, 2842, -1, 2839, 2900, 2842, -1, 2901, 2900, 2839, -1, 2833, 2901, 2839, -1, 2825, 2902, 2901, -1, 2825, 2901, 2833, -1, 2817, 2903, 2902, -1, 2817, 2902, 2825, -1, 2476, 2666, 2903, -1, 2476, 2903, 2817, -1, 2904, 2234, 2235, -1, 2329, 2328, 2867, -1, 2332, 2330, 2905, -1, 2906, 2858, 2230, -1, 2906, 2230, 2232, -1, 2907, 2860, 2858, -1, 2907, 2858, 2906, -1, 2908, 2862, 2860, -1, 2908, 2860, 2907, -1, 2909, 2232, 2234, -1, 2909, 2906, 2232, -1, 2909, 2234, 2904, -1, 2910, 2863, 2862, -1, 2910, 2862, 2908, -1, 2911, 2904, 2912, -1, 2911, 2907, 2906, -1, 2911, 2906, 2909, -1, 2911, 2909, 2904, -1, 2913, 2865, 2863, -1, 2913, 2863, 2910, -1, 2914, 2912, 2915, -1, 2914, 2911, 2912, -1, 2914, 2908, 2907, -1, 2914, 2907, 2911, -1, 2916, 2867, 2865, -1, 2916, 2865, 2913, -1, 2916, 2329, 2867, -1, 2917, 2915, 2918, -1, 2917, 2908, 2914, -1, 2917, 2910, 2908, -1, 2917, 2914, 2915, -1, 2919, 2918, 2920, -1, 2919, 2917, 2918, -1, 2919, 2913, 2910, -1, 2919, 2910, 2917, -1, 2921, 2920, 2905, -1, 2921, 2330, 2329, -1, 2921, 2329, 2916, -1, 2921, 2905, 2330, -1, 2921, 2916, 2913, -1, 2921, 2919, 2920, -1, 2921, 2913, 2919, -1, 2704, 2922, 2293, -1, 2669, 2671, 2923, -1, 2898, 2705, 2246, -1, 2666, 2667, 2903, -1, 2924, 2704, 2705, -1, 2924, 2922, 2704, -1, 2925, 2926, 2922, -1, 2925, 2922, 2924, -1, 2927, 2928, 2926, -1, 2927, 2926, 2925, -1, 2929, 2930, 2928, -1, 2929, 2928, 2927, -1, 2931, 2932, 2930, -1, 2931, 2930, 2929, -1, 2933, 2667, 2669, -1, 2933, 2923, 2932, -1, 2933, 2669, 2923, -1, 2933, 2932, 2931, -1, 2934, 2925, 2924, -1, 2934, 2933, 2931, -1, 2934, 2667, 2933, -1, 2934, 2931, 2929, -1, 2934, 2927, 2925, -1, 2934, 2924, 2705, -1, 2934, 2929, 2927, -1, 2935, 2934, 2705, -1, 2935, 2667, 2934, -1, 2936, 2898, 2899, -1, 2936, 2899, 2900, -1, 2936, 2900, 2901, -1, 2936, 2901, 2902, -1, 2936, 2902, 2903, -1, 2936, 2667, 2935, -1, 2936, 2705, 2898, -1, 2936, 2935, 2705, -1, 2936, 2903, 2667, -1, 2937, 2938, 2616, -1, 2937, 2616, 2939, -1, 2937, 2940, 2180, -1, 2937, 2939, 2940, -1, 2937, 2180, 2941, -1, 2937, 2941, 2942, -1, 2943, 2944, 2183, -1, 2937, 2942, 2938, -1, 2945, 2943, 2183, -1, 2945, 2612, 2614, -1, 2946, 2941, 2180, -1, 2946, 2942, 2941, -1, 2947, 2183, 2187, -1, 2946, 2938, 2942, -1, 2948, 2614, 2616, -1, 2949, 2947, 2187, -1, 2948, 2616, 2938, -1, 2949, 2183, 2947, -1, 2948, 2938, 2946, -1, 2948, 2946, 2180, -1, 2950, 2612, 2945, -1, 2951, 2943, 2945, -1, 2951, 2944, 2943, -1, 2950, 2183, 2949, -1, 2951, 2614, 2948, -1, 2950, 2610, 2612, -1, 2951, 2180, 2183, -1, 2950, 2945, 2183, -1, 2951, 2945, 2614, -1, 2952, 2187, 2188, -1, 2951, 2948, 2180, -1, 2951, 2183, 2944, -1, 2952, 2188, 2953, -1, 2954, 2952, 2953, -1, 2954, 2953, 2955, -1, 2954, 2187, 2952, -1, 2956, 2955, 2957, -1, 2956, 2187, 2954, -1, 2956, 2954, 2955, -1, 2958, 2949, 2187, -1, 2958, 2187, 2956, -1, 2958, 2956, 2957, -1, 2959, 2950, 2949, -1, 2959, 2610, 2950, -1, 2959, 2957, 2960, -1, 2959, 2949, 2958, -1, 2959, 2958, 2957, -1, 2959, 2960, 2610, -1, 2961, 2332, 2905, -1, 2961, 2905, 2920, -1, 2961, 2920, 2918, -1, 2961, 2918, 2915, -1, 2961, 2915, 2912, -1, 2962, 2912, 2904, -1, 2962, 2904, 2235, -1, 2962, 2235, 2237, -1, 2962, 2961, 2912, -1, 2963, 2961, 2962, -1, 2964, 2622, 2332, -1, 2964, 2963, 2962, -1, 2964, 2961, 2963, -1, 2964, 2332, 2961, -1, 2964, 2962, 2237, -1, 2964, 2965, 2622, -1, 2966, 2967, 2968, -1, 2966, 2964, 2237, -1, 2966, 2965, 2964, -1, 2966, 2237, 2967, -1, 2966, 2968, 2969, -1, 2966, 2969, 2965, -1, 2970, 2968, 2967, -1, 2970, 2967, 2238, -1, 2970, 2969, 2968, -1, 2970, 2965, 2969, -1, 2971, 2620, 2622, -1, 2971, 2970, 2238, -1, 2971, 2965, 2970, -1, 2971, 2622, 2965, -1, 2972, 2238, 2240, -1, 2972, 2240, 2973, -1, 2972, 2971, 2238, -1, 2549, 2610, 2960, -1, 2967, 2237, 2238, -1, 2974, 2971, 2972, -1, 2975, 2976, 2977, -1, 2975, 2978, 2976, -1, 2975, 2972, 2973, -1, 2975, 2971, 2974, -1, 2975, 2977, 2620, -1, 2975, 2974, 2972, -1, 2975, 2620, 2971, -1, 2975, 2973, 2978, -1, 2979, 2977, 2976, -1, 2979, 2976, 2978, -1, 2979, 2973, 2240, -1, 2979, 2978, 2973, -1, 2980, 2618, 2620, -1, 2980, 2979, 2240, -1, 2980, 2620, 2977, -1, 2980, 2977, 2979, -1, 2981, 2240, 2181, -1, 2981, 2181, 2982, -1, 2981, 2980, 2240, -1, 2983, 2984, 2618, -1, 2983, 2985, 2986, -1, 2983, 2986, 2984, -1, 2983, 2618, 2980, -1, 2983, 2981, 2982, -1, 2983, 2980, 2981, -1, 2983, 2982, 2985, -1, 2987, 2986, 2985, -1, 2987, 2982, 2181, -1, 2987, 2984, 2986, -1, 2987, 2985, 2982, -1, 2939, 2616, 2618, -1, 2939, 2618, 2984, -1, 2939, 2987, 2181, -1, 2939, 2984, 2987, -1, 2940, 2181, 2180, -1, 2940, 2939, 2181, -1, 2988, 2923, 2671, -1, 2988, 2671, 2569, -1, 2989, 2932, 2923, -1, 2989, 2923, 2988, -1, 2990, 2930, 2932, -1, 2990, 2932, 2989, -1, 2991, 2928, 2930, -1, 2991, 2930, 2990, -1, 2926, 2928, 2991, -1, 2992, 2926, 2991, -1, 2922, 2926, 2992, -1, 2993, 2922, 2992, -1, 2293, 2922, 2993, -1, 2292, 2293, 2993, -1, 2994, 2995, 2552, -1, 2994, 2996, 2995, -1, 2994, 2997, 2996, -1, 2994, 2998, 2997, -1, 2999, 2560, 3000, -1, 2994, 2191, 3001, -1, 2994, 3001, 2998, -1, 3002, 2191, 2994, -1, 3002, 2549, 2960, -1, 3003, 3004, 2560, -1, 3002, 2960, 2957, -1, 3003, 2560, 2999, -1, 3002, 2957, 2955, -1, 2205, 3004, 3003, -1, 3002, 2955, 2953, -1, 3002, 2953, 2188, -1, 2205, 2209, 3004, -1, 3002, 2188, 2191, -1, 3002, 2552, 2549, -1, 3005, 2558, 2556, -1, 3002, 2994, 2552, -1, 3006, 2558, 3005, -1, 3007, 2558, 3006, -1, 3007, 3000, 2558, -1, 3008, 2999, 3000, -1, 3008, 3000, 3007, -1, 3009, 3003, 2999, -1, 3009, 2999, 3008, -1, 3009, 3008, 2199, -1, 3009, 2205, 3003, -1, 2202, 2205, 3009, -1, 2202, 3009, 2199, -1, 3010, 3005, 2556, -1, 3010, 2556, 2554, -1, 3011, 3005, 3010, -1, 3011, 3006, 3005, -1, 3012, 3011, 2196, -1, 3012, 3006, 3011, -1, 3012, 3007, 3006, -1, 3013, 3012, 2196, -1, 3013, 3008, 3007, -1, 3013, 2199, 3008, -1, 3013, 3007, 3012, -1, 3014, 2196, 2199, -1, 3014, 3013, 2196, -1, 3014, 2199, 3013, -1, 3015, 3010, 2554, -1, 3016, 3011, 3010, -1, 3016, 2196, 3011, -1, 3016, 3010, 3015, -1, 3016, 3015, 2193, -1, 3017, 3016, 2193, -1, 3017, 2196, 3016, -1, 3018, 3017, 2193, -1, 3018, 2196, 3017, -1, 3019, 2193, 2196, -1, 3019, 3018, 2193, -1, 3019, 2196, 3018, -1, 2995, 2554, 2552, -1, 2995, 3015, 2554, -1, 2995, 2193, 3015, -1, 2996, 2193, 2995, -1, 2997, 2193, 2996, -1, 2998, 2193, 2997, -1, 3001, 2191, 2193, -1, 3001, 2193, 2998, -1, 3020, 3021, 2568, -1, 3020, 3022, 3021, -1, 3020, 3023, 3022, -1, 3020, 3024, 3023, -1, 3020, 3025, 3024, -1, 3020, 3026, 3025, -1, 3020, 2219, 3026, -1, 3027, 2568, 2566, -1, 3027, 3020, 2568, -1, 3028, 3020, 3027, -1, 3029, 2215, 2219, -1, 3029, 3030, 2215, -1, 3029, 3027, 2566, -1, 3029, 3020, 3028, -1, 3029, 3028, 3027, -1, 3029, 2219, 3020, -1, 3031, 3032, 3030, -1, 3031, 3029, 2566, -1, 3031, 3033, 3034, -1, 3031, 3030, 3029, -1, 3031, 3034, 3032, -1, 3031, 2566, 3033, -1, 3035, 2215, 3030, -1, 3036, 2564, 2562, -1, 3035, 3030, 3032, -1, 3035, 3034, 3033, -1, 3035, 3032, 3034, -1, 3037, 3036, 2562, -1, 3038, 2566, 2564, -1, 3038, 3035, 3033, -1, 3038, 3033, 2566, -1, 3039, 3035, 3038, -1, 3040, 2562, 2560, -1, 3041, 2212, 2215, -1, 3041, 3038, 2564, -1, 3042, 3040, 2560, -1, 3041, 2215, 3035, -1, 3041, 3039, 3038, -1, 3041, 3035, 3039, -1, 3043, 2564, 3036, -1, 3044, 3042, 2560, -1, 3043, 3041, 2564, -1, 3045, 3046, 2212, -1, 3045, 3037, 3046, -1, 3045, 3036, 3037, -1, 3004, 3044, 2560, -1, 3045, 2212, 3041, -1, 3045, 3043, 3036, -1, 3045, 3041, 3043, -1, 3047, 2209, 2212, -1, 3047, 2212, 3046, -1, 3047, 2562, 3040, -1, 3048, 2560, 2558, -1, 3047, 3046, 3037, -1, 3047, 3042, 3044, -1, 3047, 3040, 3042, -1, 3047, 3037, 2562, -1, 3000, 2560, 3048, -1, 3047, 3004, 2209, -1, 3047, 3044, 3004, -1, 3000, 3048, 2558, -1, 3049, 3050, 2585, -1, 3049, 3051, 3050, -1, 3052, 2577, 3053, -1, 3049, 3054, 3051, -1, 3049, 3055, 3054, -1, 3049, 2264, 3056, -1, 3049, 3056, 3055, -1, 3057, 2264, 3049, -1, 3058, 3059, 2577, -1, 3057, 2585, 2587, -1, 3057, 3060, 2261, -1, 3058, 2577, 3052, -1, 3057, 3061, 3060, -1, 2278, 3059, 3058, -1, 3057, 3062, 3061, -1, 3057, 3063, 3062, -1, 2278, 2282, 3059, -1, 3057, 2587, 3063, -1, 3057, 2261, 2264, -1, 3064, 2579, 2581, -1, 3057, 3049, 2585, -1, 3065, 2579, 3064, -1, 3066, 2579, 3065, -1, 3066, 3053, 2579, -1, 3067, 3053, 3066, -1, 3067, 3052, 3053, -1, 3068, 3058, 3052, -1, 3068, 3052, 3067, -1, 3068, 3067, 2272, -1, 3068, 2278, 3058, -1, 2275, 3068, 2272, -1, 2275, 2278, 3068, -1, 3069, 3064, 2581, -1, 3069, 2581, 2583, -1, 3070, 3064, 3069, -1, 3070, 3065, 3064, -1, 3071, 3066, 3065, -1, 3071, 3065, 3070, -1, 3071, 3070, 2269, -1, 3072, 3067, 3066, -1, 3072, 2272, 3067, -1, 3072, 3066, 3071, -1, 3072, 3071, 2269, -1, 3073, 2272, 3072, -1, 3073, 2269, 2272, -1, 3073, 3072, 2269, -1, 3074, 3069, 2583, -1, 3075, 2269, 3070, -1, 3075, 3074, 2266, -1, 3075, 3070, 3069, -1, 3075, 3069, 3074, -1, 3076, 2269, 3075, -1, 3076, 3075, 2266, -1, 3077, 3076, 2266, -1, 3077, 2269, 3076, -1, 3078, 2266, 2269, -1, 3078, 3077, 2266, -1, 3078, 2269, 3077, -1, 3050, 2583, 2585, -1, 3050, 2266, 3074, -1, 3050, 3074, 2583, -1, 3051, 2266, 3050, -1, 3054, 2266, 3051, -1, 3055, 2266, 3054, -1, 3056, 2264, 2266, -1, 3056, 2266, 3055, -1, 3079, 2292, 2993, -1, 3079, 2993, 2992, -1, 3079, 2992, 2991, -1, 3079, 2991, 2990, -1, 3079, 2990, 2989, -1, 3079, 2989, 2988, -1, 3079, 2988, 2569, -1, 3080, 2569, 2571, -1, 3080, 3079, 2569, -1, 3081, 3079, 3080, -1, 3082, 2288, 2292, -1, 3082, 3083, 2288, -1, 3082, 2292, 3079, -1, 3082, 3080, 2571, -1, 3082, 3079, 3081, -1, 3082, 3081, 3080, -1, 3084, 3085, 3086, -1, 3084, 2571, 3085, -1, 3084, 3082, 2571, -1, 3084, 3086, 3087, -1, 3084, 3083, 3082, -1, 3084, 3087, 3083, -1, 3088, 2288, 3083, -1, 3089, 2573, 2575, -1, 3088, 3086, 3085, -1, 3088, 3087, 3086, -1, 3088, 3083, 3087, -1, 3090, 2571, 2573, -1, 3091, 3089, 2575, -1, 3090, 3085, 2571, -1, 3090, 3088, 3085, -1, 3092, 3088, 3090, -1, 3093, 2575, 2577, -1, 3094, 2285, 2288, -1, 3094, 3090, 2573, -1, 3095, 3093, 2577, -1, 3094, 3092, 3090, -1, 3094, 3088, 3092, -1, 3094, 2288, 3088, -1, 3096, 3094, 2573, -1, 3097, 3095, 2577, -1, 3096, 2573, 3089, -1, 3098, 3099, 2285, -1, 3098, 3089, 3091, -1, 3098, 3091, 3099, -1, 3098, 2285, 3094, -1, 3059, 3097, 2577, -1, 3098, 3094, 3096, -1, 3098, 3096, 3089, -1, 3100, 2282, 2285, -1, 3100, 2285, 3099, -1, 3101, 2577, 2579, -1, 3100, 2575, 3093, -1, 3100, 3095, 3097, -1, 3100, 3093, 3095, -1, 3100, 3091, 2575, -1, 3100, 3059, 2282, -1, 3053, 2577, 3101, -1, 3100, 3099, 3091, -1, 3053, 3101, 2579, -1, 3100, 3097, 3059, -1, 3021, 3102, 2685, -1, 3021, 2685, 2568, -1, 3022, 3103, 3102, -1, 3022, 3102, 3021, -1, 3023, 3104, 3103, -1, 3023, 3103, 3022, -1, 3024, 3105, 3104, -1, 3024, 3104, 3023, -1, 3106, 3105, 3024, -1, 3025, 3106, 3024, -1, 3107, 3106, 3025, -1, 3026, 3107, 3025, -1, 2220, 3107, 3026, -1, 2219, 2220, 3026, -1, 3108, 3109, 2254, -1, 3110, 3111, 2659, -1, 3110, 2659, 3109, -1, 3110, 3108, 2253, -1, 3110, 3109, 3108, -1, 3110, 2253, 3112, -1, 3110, 3112, 3113, -1, 3114, 3115, 2256, -1, 3110, 3113, 3111, -1, 3116, 3114, 2256, -1, 3116, 2663, 2661, -1, 3117, 3112, 2253, -1, 3117, 3113, 3112, -1, 3117, 3111, 3113, -1, 3118, 2256, 2260, -1, 3119, 2661, 2659, -1, 3120, 2256, 3118, -1, 3119, 2659, 3111, -1, 3120, 3118, 2260, -1, 3119, 3111, 3117, -1, 3119, 3117, 2253, -1, 3121, 2663, 3116, -1, 3122, 3114, 3116, -1, 3121, 2256, 3120, -1, 3122, 3115, 3114, -1, 3122, 2661, 3119, -1, 3121, 2665, 2663, -1, 3122, 2253, 2256, -1, 3121, 3116, 2256, -1, 3122, 3116, 2661, -1, 3123, 2261, 3060, -1, 3122, 3119, 2253, -1, 3122, 2256, 3115, -1, 3123, 2260, 2261, -1, 3124, 3060, 3061, -1, 3124, 2260, 3123, -1, 3124, 3123, 3060, -1, 3125, 3061, 3062, -1, 3125, 3124, 3061, -1, 3125, 2260, 3124, -1, 3126, 3120, 2260, -1, 3126, 3125, 3062, -1, 3126, 2260, 3125, -1, 3127, 3062, 3063, -1, 3127, 3120, 3126, -1, 3127, 3121, 3120, -1, 3127, 2665, 3121, -1, 3127, 3126, 3062, -1, 3127, 3063, 2665, -1, 3128, 3129, 3130, -1, 3128, 3131, 3129, -1, 3128, 3132, 3131, -1, 3128, 3133, 3132, -1, 3128, 2335, 3133, -1, 3134, 3135, 2308, -1, 3134, 3130, 3135, -1, 3134, 2308, 2310, -1, 3134, 3128, 3130, -1, 3136, 3128, 3134, -1, 3137, 2653, 2335, -1, 3137, 3128, 3136, -1, 3137, 3138, 2653, -1, 3137, 2335, 3128, -1, 3137, 3136, 3134, -1, 3137, 3134, 2310, -1, 3139, 3137, 2310, -1, 3139, 3140, 3138, -1, 3139, 3141, 3142, -1, 3139, 2310, 3141, -1, 3139, 3142, 3140, -1, 3139, 3138, 3137, -1, 3143, 3138, 3140, -1, 3143, 3142, 3141, -1, 3143, 3140, 3142, -1, 3143, 3141, 2311, -1, 3144, 2655, 2653, -1, 3144, 3138, 3143, -1, 3144, 2653, 3138, -1, 3144, 3143, 2311, -1, 3145, 2311, 2313, -1, 3145, 3144, 2311, -1, 3145, 2313, 3146, -1, 2587, 2665, 3063, -1, 3141, 2310, 2311, -1, 3147, 3144, 3145, -1, 3148, 3145, 3146, -1, 3148, 3146, 3149, -1, 3148, 3149, 3150, -1, 3148, 2655, 3144, -1, 3148, 3147, 3145, -1, 3148, 3144, 3147, -1, 3148, 3151, 2655, -1, 3148, 3150, 3151, -1, 3152, 3149, 3146, -1, 3152, 3150, 3149, -1, 3152, 3146, 2313, -1, 3152, 3151, 3150, -1, 3153, 2657, 2655, -1, 3153, 2655, 3151, -1, 3153, 3152, 2313, -1, 3153, 3151, 3152, -1, 3154, 2313, 2254, -1, 3154, 2254, 3155, -1, 3154, 3153, 2313, -1, 3156, 3157, 2657, -1, 3156, 3158, 3159, -1, 3156, 3155, 3158, -1, 3156, 3159, 3157, -1, 3156, 2657, 3153, -1, 3156, 3154, 3155, -1, 3156, 3153, 3154, -1, 3160, 3159, 3158, -1, 3160, 3155, 2254, -1, 3160, 3158, 3155, -1, 3160, 3157, 3159, -1, 3109, 2659, 2657, -1, 3109, 2657, 3157, -1, 3109, 3160, 2254, -1, 3109, 3157, 3160, -1, 3108, 2254, 2253, -1, 2700, 3107, 2220, -1, 2683, 2685, 3102, -1, 3161, 2701, 2319, -1, 2680, 2681, 3162, -1, 3163, 2700, 2701, -1, 3163, 3107, 2700, -1, 3164, 3106, 3107, -1, 3164, 3107, 3163, -1, 3165, 3105, 3106, -1, 3165, 3106, 3164, -1, 3166, 3104, 3105, -1, 3166, 3105, 3165, -1, 3167, 3103, 3104, -1, 3167, 3104, 3166, -1, 3168, 3102, 3103, -1, 3168, 2681, 2683, -1, 3168, 2683, 3102, -1, 3168, 3103, 3167, -1, 3169, 3166, 3165, -1, 3169, 3163, 2701, -1, 3169, 3168, 3167, -1, 3169, 3165, 3164, -1, 3169, 3167, 3166, -1, 3169, 3164, 3163, -1, 3169, 2681, 3168, -1, 3170, 3169, 2701, -1, 3170, 2681, 3169, -1, 3171, 3172, 3162, -1, 3171, 3173, 3172, -1, 3171, 3174, 3173, -1, 3171, 3175, 3174, -1, 3171, 3161, 3175, -1, 3171, 3170, 2701, -1, 3171, 2681, 3170, -1, 3171, 2701, 3161, -1, 3171, 3162, 2681, -1, 3176, 3133, 2337, -1, 3176, 3177, 3178, -1, 3135, 2307, 2308, -1, 2335, 2337, 3133, -1, 3179, 3180, 2303, -1, 3179, 2303, 2305, -1, 3181, 3182, 3180, -1, 3181, 3180, 3179, -1, 3183, 3184, 3182, -1, 3183, 3182, 3181, -1, 3185, 2305, 2307, -1, 3185, 3179, 2305, -1, 3185, 2307, 3135, -1, 3186, 3187, 3184, -1, 3186, 3184, 3183, -1, 3188, 3135, 3130, -1, 3188, 3181, 3179, -1, 3188, 3185, 3135, -1, 3188, 3179, 3185, -1, 3178, 3189, 3187, -1, 3178, 3187, 3186, -1, 3190, 3130, 3129, -1, 3190, 3188, 3130, -1, 3190, 3183, 3181, -1, 3190, 3181, 3188, -1, 3177, 2339, 2340, -1, 3177, 3191, 3189, -1, 3177, 2340, 3191, -1, 3177, 3189, 3178, -1, 3192, 3129, 3131, -1, 3192, 3190, 3129, -1, 3192, 3186, 3183, -1, 3192, 3183, 3190, -1, 3193, 3131, 3132, -1, 3193, 3178, 3186, -1, 3193, 3186, 3192, -1, 3193, 3192, 3131, -1, 3176, 3132, 3133, -1, 3176, 2337, 2339, -1, 3176, 3193, 3132, -1, 3176, 2339, 3177, -1, 3176, 3178, 3193, -1, 3161, 2319, 2318, -1, 3194, 3161, 2318, -1, 3175, 3161, 3194, -1, 3195, 3175, 3194, -1, 3174, 3175, 3195, -1, 3196, 3174, 3195, -1, 3197, 3173, 3174, -1, 3197, 3174, 3196, -1, 3198, 3172, 3173, -1, 3198, 3173, 3197, -1, 3199, 3162, 3172, -1, 3199, 3172, 3198, -1, 2479, 2680, 3162, -1, 2479, 3162, 3199, -1, 3200, 2300, 2302, -1, 3201, 3200, 2302, -1, 2294, 3202, 2289, -1, 2294, 3203, 3202, -1, 2294, 3204, 3203, -1, 2294, 3205, 3204, -1, 2635, 3206, 2637, -1, 3207, 2303, 3180, -1, 3207, 3180, 3182, -1, 3207, 2302, 2303, -1, 3208, 2302, 3207, -1, 3208, 3207, 3182, -1, 3209, 3182, 3184, -1, 3209, 3184, 3187, -1, 3209, 3208, 3182, -1, 3209, 2302, 3208, -1, 3210, 3187, 3189, -1, 3210, 3201, 2302, -1, 3210, 2302, 3209, -1, 3210, 3209, 3187, -1, 3211, 3189, 3191, -1, 3211, 2637, 3206, -1, 3211, 3201, 3210, -1, 3211, 3210, 3189, -1, 3211, 3191, 2637, -1, 3211, 3206, 3201, -1, 3212, 2629, 2627, -1, 3212, 3213, 3214, -1, 3212, 3215, 3213, -1, 3212, 3214, 2296, -1, 3212, 2627, 3215, -1, 3216, 2296, 2297, -1, 3216, 3212, 2296, -1, 3216, 3217, 3218, -1, 3216, 2629, 3212, -1, 3216, 3219, 2629, -1, 3216, 3218, 3219, -1, 3216, 2297, 3217, -1, 3220, 3218, 3217, -1, 3220, 3219, 3218, -1, 3220, 3217, 2297, -1, 3221, 2631, 2629, -1, 3221, 3220, 2297, -1, 3221, 3219, 3220, -1, 3221, 2629, 3219, -1, 3222, 2297, 2299, -1, 3222, 3223, 3224, -1, 3222, 2631, 3221, -1, 3222, 2299, 3223, -1, 3222, 3225, 2631, -1, 3222, 3221, 2297, -1, 3222, 3224, 3226, -1, 3222, 3226, 3225, -1, 3227, 3224, 3223, -1, 3227, 3223, 2299, -1, 3227, 3226, 3224, -1, 3227, 3225, 3226, -1, 3228, 2633, 2631, -1, 3228, 3227, 2299, -1, 3228, 3225, 3227, -1, 2340, 2637, 3191, -1, 3228, 2631, 3225, -1, 3229, 2294, 2295, -1, 3230, 2299, 2300, -1, 3231, 2294, 3229, -1, 3230, 3228, 2299, -1, 3231, 3229, 2295, -1, 3230, 2300, 3232, -1, 3233, 2294, 3231, -1, 3234, 3232, 3235, -1, 3233, 3231, 2295, -1, 3234, 3235, 3236, -1, 3234, 3228, 3230, -1, 3237, 3205, 2294, -1, 3234, 3236, 2633, -1, 3234, 2633, 3228, -1, 3234, 3230, 3232, -1, 3237, 2294, 3233, -1, 3238, 3235, 3232, -1, 3237, 3233, 2295, -1, 3238, 3236, 3235, -1, 2625, 2530, 3205, -1, 2625, 3205, 3237, -1, 3214, 2295, 2296, -1, 3238, 3232, 2300, -1, 3239, 3236, 3238, -1, 3213, 2295, 3214, -1, 3239, 2635, 2633, -1, 3239, 2633, 3236, -1, 3215, 2295, 3213, -1, 3239, 3238, 2300, -1, 3215, 3237, 2295, -1, 3240, 2300, 3200, -1, 3215, 2625, 3237, -1, 3240, 3239, 2300, -1, 2627, 2625, 3215, -1, 3241, 3206, 2635, -1, 3241, 3240, 3200, -1, 3241, 3239, 3240, -1, 3241, 3200, 3201, -1, 3241, 3201, 3206, -1, 3241, 2635, 3239, -1, 3242, 3243, 3244, -1, 3242, 3244, 3245, -1, 3246, 3247, 3248, -1, 3246, 3248, 3249, -1, 3250, 3245, 3251, -1, 3250, 3251, 3252, -1, 3253, 2316, 3254, -1, 3253, 3255, 3256, -1, 3253, 3254, 3255, -1, 3257, 3258, 3243, -1, 3257, 3243, 3242, -1, 3259, 3249, 3260, -1, 3259, 3246, 3249, -1, 3261, 3245, 3250, -1, 3261, 3242, 3245, -1, 3262, 3263, 3247, -1, 3262, 3247, 3246, -1, 3264, 2488, 2486, -1, 3264, 3252, 2488, -1, 3265, 2479, 3199, -1, 3265, 2481, 2479, -1, 3265, 3266, 2481, -1, 3267, 3258, 3257, -1, 3267, 3268, 3258, -1, 3269, 3246, 3259, -1, 3270, 3257, 3242, -1, 3269, 3262, 3246, -1, 3270, 3242, 3261, -1, 3271, 3263, 3262, -1, 2323, 2320, 3272, -1, 3271, 3256, 3263, -1, 3273, 3250, 3252, -1, 3273, 3252, 3264, -1, 3274, 3199, 3198, -1, 3275, 3264, 2486, -1, 3274, 3265, 3199, -1, 3274, 3260, 3266, -1, 3276, 3268, 3267, -1, 3274, 3266, 3265, -1, 3276, 2324, 3277, -1, 3276, 3277, 3268, -1, 3278, 3262, 3269, -1, 3278, 3271, 3262, -1, 3279, 2314, 2316, -1, 3280, 3257, 3270, -1, 3279, 2316, 3253, -1, 3280, 3267, 3257, -1, 3279, 3253, 3256, -1, 3279, 3256, 3271, -1, 3281, 3198, 3197, -1, 3281, 3197, 3196, -1, 3282, 3261, 3250, -1, 3282, 3250, 3273, -1, 3281, 3259, 3260, -1, 3281, 3274, 3198, -1, 3283, 3264, 3275, -1, 3281, 3260, 3274, -1, 3284, 2314, 3279, -1, 3283, 3273, 3264, -1, 3284, 3271, 3278, -1, 3285, 3276, 3267, -1, 3285, 3267, 3280, -1, 3284, 3279, 3271, -1, 3285, 2325, 2324, -1, 3285, 2324, 3276, -1, 3286, 3269, 3259, -1, 3286, 3281, 3196, -1, 3286, 3259, 3281, -1, 3287, 3261, 3282, -1, 3288, 3196, 3195, -1, 3287, 3270, 3261, -1, 3288, 3269, 3286, -1, 3289, 2486, 2483, -1, 3288, 3278, 3269, -1, 3289, 3275, 2486, -1, 3288, 3286, 3196, -1, 3290, 3284, 3278, -1, 3290, 3195, 3194, -1, 3290, 2317, 2314, -1, 3290, 2314, 3284, -1, 3291, 3273, 3283, -1, 3290, 3278, 3288, -1, 3290, 3194, 2317, -1, 3291, 3282, 3273, -1, 3290, 3288, 3195, -1, 3292, 3280, 3270, -1, 3292, 3270, 3287, -1, 3248, 3275, 3289, -1, 3248, 3283, 3275, -1, 2318, 2317, 3194, -1, 3293, 3287, 3282, -1, 3294, 3295, 2492, -1, 3293, 3282, 3291, -1, 3294, 2492, 2490, -1, 3296, 3285, 3280, -1, 3296, 2325, 3285, -1, 3244, 3297, 3295, -1, 3296, 3280, 3292, -1, 3247, 3291, 3283, -1, 3247, 3283, 3248, -1, 3244, 3295, 3294, -1, 3243, 3298, 3297, -1, 3299, 3289, 2483, -1, 3255, 3287, 3293, -1, 3243, 3297, 3244, -1, 3258, 3300, 3298, -1, 3255, 3292, 3287, -1, 3258, 3298, 3243, -1, 3263, 3291, 3247, -1, 3251, 2490, 2488, -1, 3263, 3293, 3291, -1, 3249, 3248, 3289, -1, 3251, 3294, 2490, -1, 3249, 3289, 3299, -1, 3268, 3301, 3300, -1, 3266, 2483, 2481, -1, 3268, 3300, 3258, -1, 3266, 3299, 2483, -1, 3254, 2316, 2325, -1, 3254, 2325, 3296, -1, 3254, 3296, 3292, -1, 3254, 3292, 3255, -1, 3245, 3244, 3294, -1, 3245, 3294, 3251, -1, 3256, 3255, 3293, -1, 3252, 3251, 2488, -1, 3256, 3293, 3263, -1, 3277, 2324, 2323, -1, 3277, 3272, 3301, -1, 3277, 3301, 3268, -1, 3277, 2323, 3272, -1, 3260, 3249, 3299, -1, 3260, 3299, 3266, -1, 3302, 2262, 2267, -1, 3302, 3303, 2262, -1, 3304, 3305, 2535, -1, 3302, 3306, 3307, -1, 3302, 3307, 3303, -1, 3302, 2267, 3306, -1, 3304, 2534, 3305, -1, 3308, 2289, 3202, -1, 3308, 3202, 3203, -1, 3308, 3203, 3204, -1, 3308, 3204, 3205, -1, 3309, 2534, 3304, -1, 3308, 3205, 2530, -1, 3308, 2530, 2529, -1, 3308, 2286, 2289, -1, 3309, 3310, 2534, -1, 3311, 2280, 2284, -1, 3312, 3313, 3314, -1, 3311, 2277, 2280, -1, 3312, 2529, 3315, -1, 3311, 3316, 3310, -1, 3312, 3315, 3313, -1, 3312, 3308, 2529, -1, 3311, 2284, 3316, -1, 3312, 2286, 3308, -1, 3311, 3310, 3309, -1, 3312, 3317, 2286, -1, 3312, 3314, 3317, -1, 3318, 2535, 2537, -1, 3319, 2257, 2262, -1, 3320, 2535, 3318, -1, 3319, 2262, 3303, -1, 3319, 3321, 2546, -1, 3319, 3322, 3321, -1, 3319, 3323, 3322, -1, 3319, 3303, 3323, -1, 3324, 2535, 3320, -1, 3325, 2546, 2548, -1, 3325, 3326, 2257, -1, 3325, 3327, 3326, -1, 3324, 3304, 2535, -1, 3325, 3328, 3327, -1, 3325, 3329, 3328, -1, 3325, 3330, 3329, -1, 3325, 3331, 3330, -1, 3325, 2548, 3331, -1, 3332, 3304, 3324, -1, 3325, 2257, 3319, -1, 3325, 3319, 2546, -1, 3332, 3309, 3304, -1, 3333, 3311, 3309, -1, 3333, 2277, 3311, -1, 3333, 3309, 3332, -1, 3334, 2537, 2539, -1, 3334, 3318, 2537, -1, 3335, 3320, 3318, -1, 3335, 3318, 3334, -1, 3336, 3324, 3320, -1, 3336, 3320, 3335, -1, 3337, 3332, 3324, -1, 3337, 3324, 3336, -1, 3338, 3332, 3337, -1, 3338, 3333, 3332, -1, 3338, 2277, 3333, -1, 3338, 2274, 2277, -1, 3339, 2539, 2541, -1, 3339, 3334, 2539, -1, 3340, 3335, 3334, -1, 3340, 3334, 3339, -1, 3341, 3336, 3335, -1, 3341, 3335, 3340, -1, 3342, 3337, 3336, -1, 3342, 3336, 3341, -1, 3343, 2270, 2274, -1, 3343, 2274, 3338, -1, 3343, 2267, 2270, -1, 3343, 3337, 3342, -1, 3343, 3338, 3337, -1, 3344, 2541, 2543, -1, 3344, 3339, 2541, -1, 3345, 3339, 3344, -1, 3345, 3344, 2543, -1, 3315, 2529, 2532, -1, 3345, 3340, 3339, -1, 3346, 3341, 3340, -1, 3313, 3315, 2532, -1, 3346, 3340, 3345, -1, 3307, 3341, 3346, -1, 3314, 3313, 2532, -1, 3307, 3342, 3341, -1, 3306, 2267, 3343, -1, 2286, 3317, 2284, -1, 3306, 3343, 3342, -1, 3347, 2532, 2534, -1, 3306, 3342, 3307, -1, 3321, 2543, 2546, -1, 3348, 3347, 2534, -1, 3348, 2532, 3347, -1, 3349, 3348, 2534, -1, 3349, 2532, 3348, -1, 3322, 3345, 2543, -1, 3310, 2532, 3349, -1, 3310, 3314, 2532, -1, 3310, 3349, 2534, -1, 3322, 2543, 3321, -1, 3316, 3314, 3310, -1, 3316, 3317, 3314, -1, 3316, 2284, 3317, -1, 3323, 3346, 3345, -1, 3350, 2534, 2535, -1, 3323, 3345, 3322, -1, 3305, 3350, 2535, -1, 3303, 3307, 3346, -1, 3303, 3346, 3323, -1, 3305, 2534, 3350, -1, 3351, 3272, 2320, -1, 3351, 2320, 2322, -1, 3352, 3301, 3272, -1, 3352, 3272, 3351, -1, 3353, 3300, 3301, -1, 3353, 3301, 3352, -1, 3298, 3300, 3353, -1, 3354, 3298, 3353, -1, 3297, 3298, 3354, -1, 3355, 3297, 3354, -1, 3295, 3297, 3355, -1, 3356, 3295, 3355, -1, 2492, 3295, 3356, -1, 2693, 2492, 3356, -1, 3331, 2548, 2690, -1, 3357, 3331, 2690, -1, 3330, 3331, 3357, -1, 3358, 3330, 3357, -1, 3329, 3330, 3358, -1, 3359, 3329, 3358, -1, 3328, 3329, 3359, -1, 3360, 3328, 3359, -1, 3361, 3327, 3328, -1, 3361, 3328, 3360, -1, 3362, 3326, 3327, -1, 3362, 3327, 3361, -1, 2258, 2257, 3326, -1, 2258, 3326, 3362, -1, 2692, 2693, 3356, -1, 3362, 2703, 2258, -1, 2690, 2689, 3357, -1, 3363, 3351, 2322, -1, 3363, 2702, 2703, -1, 3363, 2322, 2702, -1, 3364, 3352, 3351, -1, 3364, 3351, 3363, -1, 3365, 3353, 3352, -1, 3365, 3352, 3364, -1, 3366, 3354, 3353, -1, 3366, 3353, 3365, -1, 3367, 3355, 3354, -1, 3367, 3354, 3366, -1, 3368, 3356, 3355, -1, 3368, 2689, 2692, -1, 3368, 2692, 3356, -1, 3368, 3355, 3367, -1, 3369, 3366, 3365, -1, 3369, 3367, 3366, -1, 3369, 3363, 2703, -1, 3369, 2689, 3368, -1, 3369, 3368, 3367, -1, 3369, 3364, 3363, -1, 3369, 3365, 3364, -1, 3370, 2689, 3369, -1, 3370, 3369, 2703, -1, 3371, 3362, 3361, -1, 3371, 3361, 3360, -1, 3371, 3360, 3359, -1, 3371, 3359, 3358, -1, 3371, 3358, 3357, -1, 3371, 3370, 2703, -1, 3371, 2703, 3362, -1, 3371, 2689, 3370, -1, 3371, 3357, 2689, -1, 3372, 3373, 3374, -1, 3375, 3376, 3377, -1, 3372, 2357, 3373, -1, 3372, 3378, 3379, -1, 3380, 3381, 3382, -1, 3380, 3383, 3384, -1, 3385, 2352, 2357, -1, 3380, 3375, 3381, -1, 3385, 3372, 3379, -1, 3380, 3384, 3375, -1, 3385, 2357, 3372, -1, 3386, 3382, 3387, -1, 3386, 3388, 3383, -1, 3389, 3390, 3391, -1, 3389, 2352, 3385, -1, 3386, 3383, 3380, -1, 3389, 3385, 3379, -1, 3386, 3380, 3382, -1, 3392, 3387, 3393, -1, 3389, 3394, 2352, -1, 3392, 2399, 3395, -1, 3389, 3396, 3390, -1, 3392, 3395, 3388, -1, 3392, 3388, 3386, -1, 3389, 3391, 3394, -1, 3392, 3386, 3387, -1, 3397, 2346, 3398, -1, 3392, 3393, 2399, -1, 3397, 3399, 2345, -1, 3379, 3400, 2333, -1, 3397, 3401, 3402, -1, 3379, 3403, 3400, -1, 3397, 3398, 3404, -1, 3379, 3378, 3403, -1, 3397, 3404, 3401, -1, 3397, 3402, 3405, -1, 3397, 3405, 3399, -1, 3397, 2345, 2346, -1, 3406, 3407, 2615, -1, 3379, 2333, 2623, -1, 3406, 3401, 3408, -1, 3409, 3391, 3390, -1, 3406, 2615, 3410, -1, 3409, 3411, 2621, -1, 3406, 3408, 3407, -1, 3412, 2345, 3399, -1, 3412, 3402, 3401, -1, 3412, 3405, 3402, -1, 3409, 3390, 3396, -1, 3412, 3401, 3406, -1, 3412, 3399, 3405, -1, 3409, 3413, 3411, -1, 3409, 3396, 3413, -1, 3414, 2350, 2352, -1, 3414, 3409, 2621, -1, 3414, 2352, 3394, -1, 3415, 3406, 3410, -1, 3415, 2344, 2345, -1, 3414, 3416, 3417, -1, 3414, 3417, 2350, -1, 3415, 2345, 3412, -1, 3414, 3391, 3409, -1, 3415, 3418, 2344, -1, 3414, 3394, 3391, -1, 3415, 3412, 3406, -1, 3419, 3420, 3421, -1, 3422, 3423, 3424, -1, 3419, 3410, 3420, -1, 3422, 3424, 3425, -1, 3422, 3425, 3416, -1, 3419, 3421, 3426, -1, 3422, 3414, 2621, -1, 3422, 3416, 3414, -1, 3422, 2621, 3423, -1, 3419, 3415, 3410, -1, 3427, 3428, 3418, -1, 3429, 3423, 2619, -1, 3427, 3426, 3430, -1, 3427, 3430, 3428, -1, 3427, 3418, 3415, -1, 3427, 3419, 3426, -1, 3427, 3415, 3419, -1, 3431, 3418, 3428, -1, 3431, 3426, 3421, -1, 3432, 3424, 3423, -1, 3431, 3430, 3426, -1, 3431, 3428, 3430, -1, 3432, 3425, 3424, -1, 3431, 3421, 3433, -1, 3432, 3416, 3425, -1, 3432, 3423, 3429, -1, 3434, 3418, 3431, -1, 3434, 2398, 2344, -1, 3435, 3416, 3432, -1, 3434, 3431, 3433, -1, 3435, 3436, 2346, -1, 3434, 2344, 3418, -1, 3435, 2346, 2350, -1, 3435, 3429, 2619, -1, 3435, 3417, 3416, -1, 3437, 3433, 3438, -1, 3435, 2350, 3417, -1, 3437, 2398, 3434, -1, 3435, 3432, 3429, -1, 3437, 3395, 2398, -1, 3437, 3434, 3433, -1, 3439, 2619, 2617, -1, 3437, 3388, 3395, -1, 3439, 2617, 3440, -1, 3439, 3435, 2619, -1, 3441, 3438, 3442, -1, 3441, 3443, 3384, -1, 3441, 3442, 3443, -1, 3441, 3384, 3383, -1, 3444, 3445, 3446, -1, 3441, 3383, 3388, -1, 3444, 3439, 3440, -1, 3441, 3437, 3438, -1, 3444, 3435, 3439, -1, 3441, 3388, 3437, -1, 3444, 3440, 3447, -1, 3448, 2623, 3411, -1, 3444, 3447, 3445, -1, 3448, 3396, 3389, -1, 3444, 3436, 3435, -1, 3448, 3379, 2623, -1, 3444, 3446, 3436, -1, 3448, 3411, 3413, -1, 3448, 3389, 3379, -1, 3448, 3413, 3396, -1, 3449, 3440, 2617, -1, 3450, 3446, 3445, -1, 3450, 3440, 3449, -1, 3443, 3442, 2611, -1, 3450, 3447, 3440, -1, 3450, 3445, 3447, -1, 3398, 2346, 3436, -1, 3398, 3449, 2617, -1, 3398, 3450, 3449, -1, 3398, 3446, 3450, -1, 3398, 3436, 3446, -1, 2400, 2399, 3393, -1, 3411, 2623, 2621, -1, 3451, 2615, 3407, -1, 3452, 2611, 2551, -1, 3451, 2617, 2615, -1, 3451, 3398, 2617, -1, 3452, 2551, 3453, -1, 3451, 3407, 3408, -1, 3404, 3408, 3401, -1, 3404, 3398, 3451, -1, 3404, 3451, 3408, -1, 3395, 2399, 2398, -1, 3410, 2615, 2613, -1, 3410, 2613, 3420, -1, 3454, 3453, 3455, -1, 3454, 3452, 3453, -1, 3433, 3420, 2613, -1, 3454, 2611, 3452, -1, 3433, 3421, 3420, -1, 3376, 3455, 3377, -1, 3376, 3443, 2611, -1, 3376, 3454, 3455, -1, 3423, 2621, 2619, -1, 3376, 2611, 3454, -1, 3438, 2613, 2611, -1, 3375, 3456, 3381, -1, 3438, 3433, 2613, -1, 3375, 3377, 3456, -1, 3375, 3384, 3443, -1, 3438, 2611, 3442, -1, 3372, 3457, 3378, -1, 3372, 3374, 3457, -1, 3375, 3443, 3376, -1, 3458, 2550, 2553, -1, 3459, 3458, 2553, -1, 3460, 3458, 3459, -1, 3461, 3458, 3460, -1, 3461, 3462, 3458, -1, 3463, 2391, 2401, -1, 3463, 3464, 2391, -1, 3465, 3466, 3462, -1, 3465, 3462, 3461, -1, 3467, 3466, 3465, -1, 3467, 3468, 3466, -1, 3469, 3468, 3467, -1, 3469, 3470, 3468, -1, 3471, 3464, 3470, -1, 3471, 2391, 3464, -1, 3471, 3470, 3469, -1, 3472, 2392, 2389, -1, 3473, 2367, 2392, -1, 3474, 2363, 2367, -1, 3475, 2360, 2363, -1, 3476, 2355, 2360, -1, 3477, 2353, 2355, -1, 3478, 3455, 3453, -1, 3478, 3453, 2551, -1, 3478, 2551, 2550, -1, 3479, 3462, 3466, -1, 3479, 2550, 3458, -1, 3479, 3458, 3462, -1, 3480, 2389, 2391, -1, 3480, 3469, 3467, -1, 3480, 3471, 3469, -1, 3480, 2391, 3471, -1, 3481, 2389, 3480, -1, 3482, 2389, 3481, -1, 3482, 3483, 3484, -1, 3482, 3484, 3472, -1, 3482, 3472, 2389, -1, 3485, 3484, 3483, -1, 3485, 3472, 3484, -1, 3485, 2392, 3472, -1, 3486, 2392, 3485, -1, 3487, 2392, 3486, -1, 3487, 3488, 3489, -1, 3487, 3473, 2392, -1, 3487, 3489, 3473, -1, 3490, 2367, 3473, -1, 3490, 3473, 3489, -1, 3491, 3492, 3493, -1, 3491, 3474, 2367, -1, 3491, 3493, 3474, -1, 3494, 3493, 3492, -1, 3495, 2363, 3474, -1, 3495, 3474, 3493, -1, 3495, 3493, 3494, -1, 3496, 3495, 3494, -1, 3496, 2363, 3495, -1, 3497, 3498, 3499, -1, 3497, 3499, 3500, -1, 3501, 3496, 3497, -1, 3501, 2363, 3496, -1, 3501, 3497, 3500, -1, 3501, 3475, 2363, -1, 3501, 3500, 3475, -1, 3502, 3500, 3503, -1, 3502, 2360, 3475, -1, 3502, 3475, 3500, -1, 3504, 3502, 3503, -1, 3504, 2360, 3502, -1, 3505, 3506, 3507, -1, 3505, 3507, 3508, -1, 3509, 3508, 3476, -1, 3509, 3476, 2360, -1, 3509, 3505, 3508, -1, 3509, 2360, 3504, -1, 3509, 3504, 3505, -1, 3510, 3476, 3508, -1, 3510, 2355, 3476, -1, 3511, 2355, 3510, -1, 3511, 3512, 3513, -1, 3511, 3513, 3514, -1, 3511, 2565, 3512, -1, 3515, 3514, 3516, -1, 3515, 3511, 3514, -1, 3515, 3516, 3517, -1, 3515, 3517, 3518, -1, 3515, 3518, 3477, -1, 3515, 3477, 2355, -1, 3515, 2355, 3511, -1, 3519, 3516, 3514, -1, 3519, 3517, 3516, -1, 3519, 3518, 3517, -1, 3519, 3514, 3513, -1, 3520, 3518, 3519, -1, 3520, 3477, 3518, -1, 3520, 2353, 3477, -1, 3521, 3520, 3519, -1, 3521, 2353, 3520, -1, 3521, 2565, 2567, -1, 3521, 3513, 3512, -1, 3521, 3519, 3513, -1, 3521, 3512, 2565, -1, 3522, 3523, 2349, -1, 3522, 3524, 3523, -1, 3522, 2349, 2353, -1, 3522, 2353, 3521, -1, 3522, 3521, 3525, -1, 3526, 3524, 3522, -1, 3526, 3521, 2567, -1, 3526, 3522, 3525, -1, 3526, 3527, 3524, -1, 3526, 3528, 3527, -1, 3526, 3529, 3528, -1, 3526, 3530, 3529, -1, 3526, 2567, 3530, -1, 3526, 3525, 3521, -1, 3531, 3381, 3456, -1, 3531, 3456, 3377, -1, 3531, 3377, 3455, -1, 3531, 3455, 3478, -1, 3532, 3393, 3387, -1, 3532, 3387, 3382, -1, 3532, 3382, 3381, -1, 3532, 3381, 3531, -1, 3533, 2400, 3393, -1, 3533, 3393, 3532, -1, 3533, 3532, 3531, -1, 3533, 2401, 2400, -1, 3533, 3531, 3478, -1, 3533, 3463, 2401, -1, 3534, 3463, 3533, -1, 3534, 3464, 3463, -1, 3534, 3470, 3464, -1, 3534, 3466, 3468, -1, 3534, 3533, 3478, -1, 3534, 3468, 3470, -1, 3534, 3479, 3466, -1, 3535, 3459, 2553, -1, 3535, 3460, 3459, -1, 3535, 3461, 3460, -1, 3536, 3461, 3535, -1, 3536, 3467, 3465, -1, 3536, 3480, 3467, -1, 3536, 3465, 3461, -1, 3536, 3481, 3480, -1, 3536, 3535, 3537, -1, 3538, 2553, 2555, -1, 3538, 3481, 3536, -1, 3538, 3536, 3537, -1, 3538, 3535, 2553, -1, 3538, 3537, 3535, -1, 3539, 3540, 3541, -1, 3539, 3538, 2555, -1, 3539, 2555, 3540, -1, 3539, 3541, 3542, -1, 3543, 3482, 3481, -1, 3543, 3542, 3544, -1, 3543, 3544, 3483, -1, 3543, 3481, 3538, -1, 3543, 3539, 3542, -1, 3543, 3538, 3539, -1, 3543, 3483, 3482, -1, 3545, 3541, 3540, -1, 3545, 3544, 3542, -1, 3545, 3540, 2555, -1, 3545, 3542, 3541, -1, 3546, 3486, 3485, -1, 3546, 3483, 3544, -1, 3546, 3544, 3545, -1, 3546, 3485, 3483, -1, 3546, 3545, 3547, -1, 3548, 3545, 2555, -1, 3548, 2555, 2557, -1, 3548, 3486, 3546, -1, 3548, 3547, 3545, -1, 3548, 3546, 3547, -1, 3549, 2557, 3550, -1, 3549, 3550, 3551, -1, 3549, 3551, 3552, -1, 3549, 3548, 2557, -1, 3553, 3486, 3548, -1, 3553, 3554, 3488, -1, 3553, 3548, 3549, -1, 3553, 3549, 3552, -1, 3553, 3487, 3486, -1, 3553, 3488, 3487, -1, 3553, 3552, 3554, -1, 3555, 3551, 3550, -1, 3555, 3552, 3551, -1, 3555, 3554, 3552, -1, 3556, 3488, 3554, -1, 3556, 3489, 3488, -1, 3556, 3490, 3489, -1, 3556, 3554, 3555, -1, 3557, 3550, 2557, -1, 3557, 2557, 2559, -1, 3557, 3555, 3550, -1, 3557, 3490, 3556, -1, 3557, 3556, 3555, -1, 3558, 2559, 3559, -1, 3558, 3559, 3560, -1, 3558, 3557, 2559, -1, 3561, 3560, 3562, -1, 3561, 3491, 3558, -1, 3561, 3492, 3491, -1, 3561, 3558, 3560, -1, 3561, 3563, 3492, -1, 3561, 3562, 3563, -1, 3564, 2559, 2561, -1, 3564, 3559, 2559, -1, 3564, 3560, 3559, -1, 3564, 3562, 3560, -1, 3564, 3492, 3563, -1, 3564, 3496, 3494, -1, 3564, 3494, 3492, -1, 3564, 3563, 3562, -1, 3565, 3564, 2561, -1, 3565, 3497, 3496, -1, 3565, 3566, 3567, -1, 3565, 3496, 3564, -1, 3565, 3567, 3568, -1, 3565, 2561, 3566, -1, 3565, 3568, 3498, -1, 3565, 3498, 3497, -1, 3569, 3503, 3500, -1, 3569, 3568, 3567, -1, 3569, 3498, 3568, -1, 3569, 3499, 3498, -1, 3569, 3500, 3499, -1, 3570, 3504, 3503, -1, 3570, 2561, 2563, -1, 3570, 3567, 3566, -1, 3570, 3503, 3569, -1, 3570, 3566, 2561, -1, 3570, 3569, 3567, -1, 3571, 3572, 3506, -1, 3571, 3506, 3505, -1, 3571, 2563, 3573, -1, 3571, 3504, 3570, -1, 3571, 3573, 3574, -1, 3571, 3505, 3504, -1, 3571, 3570, 2563, -1, 3571, 3574, 3572, -1, 3575, 3506, 3572, -1, 3575, 3507, 3506, -1, 3575, 3508, 3507, -1, 3575, 3510, 3508, -1, 3575, 3574, 3573, -1, 3575, 3572, 3574, -1, 3576, 2565, 3511, -1, 3576, 2563, 2565, -1, 3576, 3573, 2563, -1, 3576, 3511, 3510, -1, 3576, 3510, 3575, -1, 3576, 3575, 3573, -1, 3577, 3534, 3478, -1, 3577, 3479, 3534, -1, 3577, 2550, 3479, -1, 3577, 3478, 2550, -1, 3578, 2367, 3490, -1, 3578, 3491, 2367, -1, 3578, 3558, 3491, -1, 3578, 3490, 3557, -1, 3578, 3557, 3558, -1, 3400, 2331, 2333, -1, 2362, 2365, 3579, -1, 2357, 2358, 3373, -1, 3580, 3581, 2327, -1, 3580, 3582, 3581, -1, 3580, 2327, 2326, -1, 3583, 3582, 3580, -1, 3584, 3585, 3582, -1, 3584, 3586, 3585, -1, 3584, 3582, 3583, -1, 3587, 2326, 2331, -1, 3587, 3580, 2326, -1, 3587, 2331, 3400, -1, 3588, 3586, 3584, -1, 3589, 3400, 3403, -1, 3589, 3583, 3580, -1, 3589, 3587, 3400, -1, 3589, 3580, 3587, -1, 3590, 3591, 3586, -1, 3590, 3579, 3591, -1, 3590, 3586, 3588, -1, 3592, 3403, 3378, -1, 3592, 3589, 3403, -1, 3592, 3584, 3583, -1, 3592, 3583, 3589, -1, 3593, 2358, 2362, -1, 3593, 2362, 3579, -1, 3593, 3579, 3590, -1, 3594, 3378, 3457, -1, 3594, 3584, 3592, -1, 3594, 3592, 3378, -1, 3594, 3588, 3584, -1, 3595, 3457, 3374, -1, 3595, 3594, 3457, -1, 3595, 3590, 3588, -1, 3595, 3588, 3594, -1, 3596, 3374, 3373, -1, 3596, 2358, 3593, -1, 3596, 3373, 2358, -1, 3596, 3593, 3590, -1, 3596, 3595, 3374, -1, 3596, 3590, 3595, -1, 3597, 3530, 2567, -1, 3597, 2567, 2686, -1, 3598, 3529, 3530, -1, 3598, 3530, 3597, -1, 3599, 3528, 3529, -1, 3599, 3529, 3598, -1, 3527, 3528, 3599, -1, 3600, 3527, 3599, -1, 3524, 3527, 3600, -1, 3601, 3524, 3600, -1, 3523, 3524, 3601, -1, 3602, 3523, 3601, -1, 2349, 3523, 3602, -1, 2347, 2349, 3602, -1, 3603, 3604, 3605, -1, 3603, 3605, 2645, -1, 3606, 3581, 3582, -1, 3606, 3607, 3581, -1, 3606, 2639, 3607, -1, 2372, 2369, 3608, -1, 3609, 3603, 2645, -1, 2372, 3608, 3610, -1, 2372, 3610, 2368, -1, 3611, 3582, 3585, -1, 3612, 2643, 3613, -1, 3611, 3614, 2639, -1, 3612, 2645, 2643, -1, 3611, 2639, 3606, -1, 3612, 3609, 2645, -1, 3611, 3606, 3582, -1, 3612, 3613, 3615, -1, 3616, 3585, 3586, -1, 3617, 3609, 3612, -1, 3616, 3614, 3611, -1, 3617, 3612, 3615, -1, 3616, 3618, 3614, -1, 3616, 3611, 3585, -1, 3619, 3620, 3621, -1, 3619, 3622, 3620, -1, 3623, 3624, 3618, -1, 3619, 3625, 3622, -1, 3619, 3626, 3625, -1, 3623, 3616, 3586, -1, 3619, 3621, 3627, -1, 3623, 3618, 3616, -1, 3628, 3629, 3630, -1, 3631, 3586, 3591, -1, 3628, 3619, 3627, -1, 3631, 3632, 3624, -1, 3628, 3627, 3629, -1, 3631, 3623, 3586, -1, 3631, 3624, 3623, -1, 3633, 3619, 3628, -1, 3634, 3591, 3579, -1, 3634, 3610, 3632, -1, 3634, 2368, 3610, -1, 3633, 3628, 3630, -1, 3634, 3632, 3631, -1, 3635, 3619, 3633, -1, 3634, 3631, 3591, -1, 3634, 3579, 2368, -1, 3635, 2378, 3626, -1, 3636, 3637, 2608, -1, 3635, 3626, 3619, -1, 3636, 3638, 3637, -1, 3639, 2376, 2378, -1, 3639, 2378, 3635, -1, 3636, 2608, 2651, -1, 3639, 3635, 3633, -1, 3639, 3633, 3630, -1, 3615, 3613, 2643, -1, 3640, 3641, 3642, -1, 3640, 3643, 3644, -1, 3627, 3645, 3638, -1, 3640, 3646, 3643, -1, 3627, 3621, 3645, -1, 3640, 3639, 3630, -1, 3640, 3642, 3646, -1, 3640, 2376, 3639, -1, 3647, 3615, 2643, -1, 3640, 3644, 2376, -1, 3640, 3630, 3641, -1, 3648, 3649, 3650, -1, 3627, 3638, 3636, -1, 3648, 3643, 3646, -1, 3648, 3642, 3649, -1, 3651, 3647, 2643, -1, 3648, 3646, 3642, -1, 3652, 3627, 3636, -1, 3653, 3644, 3643, -1, 3629, 3627, 3652, -1, 3653, 2376, 3644, -1, 3653, 3643, 3648, -1, 3654, 2375, 2376, -1, 3654, 3648, 3650, -1, 3654, 2376, 3653, -1, 3654, 3653, 3648, -1, 3630, 3636, 2651, -1, 3655, 3656, 3657, -1, 3655, 3657, 3658, -1, 3655, 3650, 3656, -1, 3655, 3654, 3650, -1, 3655, 3659, 3660, -1, 3630, 3652, 3636, -1, 3655, 3658, 3659, -1, 3630, 3629, 3652, -1, 3661, 2643, 2641, -1, 3662, 3655, 3660, -1, 3641, 3663, 3642, -1, 3662, 2375, 3654, -1, 3662, 3660, 3664, -1, 3641, 3665, 3663, -1, 3662, 3654, 3655, -1, 3641, 2651, 3665, -1, 3662, 3664, 2375, -1, 3641, 3630, 2651, -1, 3649, 3642, 3663, -1, 3666, 3667, 3668, -1, 3669, 2643, 3661, -1, 3669, 3661, 2641, -1, 3666, 3664, 3660, -1, 3666, 3660, 3659, -1, 3666, 3659, 3658, -1, 3666, 3658, 3667, -1, 3649, 3663, 3665, -1, 3670, 2643, 3669, -1, 3666, 2375, 3664, -1, 3649, 3665, 2649, -1, 3670, 3651, 2643, -1, 3670, 3669, 2641, -1, 3671, 3672, 3651, -1, 3673, 3668, 3674, -1, 3650, 3649, 2649, -1, 3675, 2375, 3666, -1, 3671, 3651, 3670, -1, 3675, 3666, 3668, -1, 3676, 3672, 3671, -1, 3675, 2373, 2375, -1, 3677, 3650, 2649, -1, 3676, 3678, 3672, -1, 3677, 2649, 2647, -1, 3675, 3668, 3673, -1, 3679, 3680, 2373, -1, 3608, 3681, 3678, -1, 3679, 2373, 3675, -1, 3677, 2647, 3682, -1, 2365, 2368, 3579, -1, 3679, 3675, 3673, -1, 3656, 3650, 3677, -1, 3608, 3678, 3676, -1, 3665, 2651, 2649, -1, 3683, 3604, 3684, -1, 3656, 3677, 3682, -1, 3608, 2371, 3681, -1, 3683, 3684, 3685, -1, 3683, 3685, 3686, -1, 2369, 2371, 3608, -1, 3683, 3686, 3680, -1, 3683, 3674, 3605, -1, 3687, 2641, 2639, -1, 3683, 3605, 3604, -1, 3656, 3682, 3657, -1, 3683, 3673, 3674, -1, 3683, 3679, 3673, -1, 3683, 3680, 3679, -1, 3688, 3685, 3684, -1, 3688, 3686, 3685, -1, 3667, 3658, 3657, -1, 3688, 2373, 3680, -1, 3688, 3680, 3686, -1, 3667, 3657, 3682, -1, 3688, 3603, 3609, -1, 3667, 3682, 2647, -1, 3614, 3687, 2639, -1, 3614, 2641, 3687, -1, 3688, 3684, 3603, -1, 3689, 2371, 2373, -1, 3668, 3667, 2647, -1, 3689, 3609, 3617, -1, 3618, 3670, 2641, -1, 3689, 2373, 3688, -1, 3618, 2641, 3614, -1, 3689, 3688, 3609, -1, 3624, 3671, 3670, -1, 3624, 3670, 3618, -1, 3690, 3689, 3617, -1, 3690, 3681, 2371, -1, 3691, 3668, 2647, -1, 3690, 2371, 3689, -1, 3691, 2647, 2645, -1, 3692, 3615, 3647, -1, 3632, 3671, 3624, -1, 3692, 3647, 3651, -1, 3691, 2645, 3605, -1, 3632, 3676, 3671, -1, 3692, 3651, 3672, -1, 3692, 3672, 3678, -1, 3692, 3617, 3615, -1, 3692, 3678, 3681, -1, 3692, 3681, 3690, -1, 3692, 3690, 3617, -1, 3674, 3691, 3605, -1, 3610, 3608, 3676, -1, 3610, 3676, 3632, -1, 3674, 3668, 3691, -1, 3607, 2327, 3581, -1, 3603, 3684, 3604, -1, 3607, 2639, 2327, -1, 2699, 2347, 3602, -1, 3693, 2682, 2478, -1, 2697, 2698, 3694, -1, 3695, 3597, 2686, -1, 3695, 2684, 2682, -1, 3695, 2686, 2684, -1, 3696, 3598, 3597, -1, 3696, 3597, 3695, -1, 3697, 3599, 3598, -1, 3697, 3598, 3696, -1, 3698, 3600, 3599, -1, 3698, 3599, 3697, -1, 3699, 3601, 3600, -1, 3699, 3600, 3698, -1, 3700, 3602, 3601, -1, 3700, 2698, 2699, -1, 3700, 2699, 3602, -1, 3700, 3601, 3699, -1, 3701, 3698, 3697, -1, 3701, 3700, 3699, -1, 3701, 3695, 2682, -1, 3701, 3699, 3698, -1, 3701, 2698, 3700, -1, 3701, 3696, 3695, -1, 3701, 3697, 3696, -1, 3702, 3701, 2682, -1, 3702, 2698, 3701, -1, 3703, 3704, 3694, -1, 3703, 3705, 3704, -1, 3703, 3706, 3705, -1, 3703, 3707, 3706, -1, 3703, 3693, 3707, -1, 3703, 2698, 3702, -1, 3703, 3702, 2682, -1, 3703, 2682, 3693, -1, 3703, 3694, 2698, -1, 2378, 2379, 3626, -1, 3708, 2592, 2594, -1, 3709, 2594, 2595, -1, 3710, 2595, 2597, -1, 3711, 2599, 2601, -1, 3712, 2603, 2606, -1, 3713, 3712, 2606, -1, 2380, 3714, 2379, -1, 3715, 2608, 3637, -1, 3715, 2606, 2608, -1, 3716, 3637, 3638, -1, 3716, 3638, 3645, -1, 3716, 2606, 3715, -1, 3716, 3715, 3637, -1, 3717, 2606, 3716, -1, 3717, 3716, 3645, -1, 3718, 3645, 3621, -1, 3718, 3621, 3620, -1, 3718, 3713, 2606, -1, 3718, 3717, 3645, -1, 3718, 2606, 3717, -1, 3719, 3620, 3622, -1, 3719, 3720, 3713, -1, 3719, 3718, 3620, -1, 3719, 3713, 3718, -1, 3721, 3622, 3625, -1, 3721, 3722, 3720, -1, 3721, 3720, 3719, -1, 3721, 3719, 3622, -1, 3723, 3626, 2379, -1, 3723, 3722, 3721, -1, 3723, 3625, 3626, -1, 3723, 3714, 3722, -1, 3723, 2379, 3714, -1, 3723, 3721, 3625, -1, 3724, 3725, 3726, -1, 3724, 3727, 3725, -1, 3724, 3728, 3727, -1, 3724, 3729, 3728, -1, 3724, 2396, 3729, -1, 3730, 3731, 2591, -1, 3730, 3726, 3731, -1, 3730, 2591, 2592, -1, 3730, 3724, 3726, -1, 3732, 3724, 3730, -1, 3733, 3732, 3730, -1, 3733, 2394, 2396, -1, 3733, 3724, 3732, -1, 3733, 3734, 2394, -1, 3733, 2396, 3724, -1, 3733, 3730, 2592, -1, 3735, 3733, 2592, -1, 3735, 2592, 3708, -1, 3735, 3708, 3736, -1, 3737, 3733, 3735, -1, 3738, 3735, 3736, -1, 3738, 3739, 3740, -1, 3738, 3737, 3735, -1, 3738, 3734, 3733, -1, 3738, 3740, 3734, -1, 3738, 3736, 3741, -1, 3738, 3741, 3739, -1, 3738, 3733, 3737, -1, 3742, 3708, 2594, -1, 3742, 3736, 3708, -1, 3743, 3736, 3742, -1, 3743, 3740, 3739, -1, 3743, 3741, 3736, -1, 3743, 3739, 3741, -1, 3744, 2388, 2394, -1, 3744, 3743, 3742, -1, 3744, 3740, 3743, -1, 3744, 2394, 3734, -1, 3744, 3745, 2388, -1, 3744, 3734, 3740, -1, 3744, 3742, 2594, -1, 3746, 3745, 3744, -1, 3746, 3709, 3747, -1, 3746, 2594, 3709, -1, 3746, 3748, 3745, -1, 3746, 3749, 3748, -1, 3746, 3747, 3749, -1, 3746, 3744, 2594, -1, 3750, 3709, 2595, -1, 3751, 3709, 3750, -1, 3751, 3747, 3709, -1, 3751, 3748, 3749, -1, 3751, 3749, 3747, -1, 3752, 3750, 2595, -1, 3752, 2386, 2388, -1, 3752, 3751, 3750, -1, 3752, 3748, 3751, -1, 3752, 3745, 3748, -1, 3752, 2388, 3745, -1, 3752, 3753, 2386, -1, 3754, 2595, 3710, -1, 3754, 3755, 3756, -1, 3754, 3757, 3753, -1, 3754, 3756, 3757, -1, 3754, 3753, 3752, -1, 3754, 3710, 3755, -1, 3754, 3752, 2595, -1, 3758, 3710, 2597, -1, 3759, 3756, 3755, -1, 3759, 3710, 3758, -1, 3759, 3755, 3710, -1, 3760, 3758, 2597, -1, 3760, 3759, 3758, -1, 3761, 2599, 3762, -1, 3761, 2597, 2599, -1, 3761, 3760, 2597, -1, 3763, 3762, 3764, -1, 3763, 3764, 3765, -1, 3763, 3761, 3762, -1, 3763, 3760, 3761, -1, 3766, 3762, 2599, -1, 3767, 2599, 3711, -1, 3768, 3711, 2601, -1, 3768, 3769, 3711, -1, 3770, 3768, 2601, -1, 3771, 3772, 3773, -1, 3771, 3770, 2601, -1, 3771, 2601, 3772, -1, 3774, 2601, 2603, -1, 3774, 3773, 3772, -1, 3774, 3772, 2601, -1, 3775, 3774, 2603, -1, 3776, 3712, 3713, -1, 3776, 3775, 2603, -1, 3776, 2603, 3712, -1, 3777, 3753, 3757, -1, 3777, 3756, 3759, -1, 3777, 3759, 3760, -1, 3777, 3757, 3756, -1, 3777, 2386, 3753, -1, 3778, 3779, 2385, -1, 3778, 2385, 2386, -1, 3778, 2386, 3777, -1, 3778, 3765, 3780, -1, 3778, 3780, 3779, -1, 3778, 3760, 3763, -1, 3778, 3763, 3765, -1, 3778, 3777, 3760, -1, 3781, 3764, 3762, -1, 3781, 3765, 3764, -1, 3781, 3780, 3765, -1, 3781, 3779, 3780, -1, 3781, 3762, 3766, -1, 3782, 2599, 3767, -1, 3782, 3766, 2599, -1, 3782, 3781, 3766, -1, 3783, 2385, 3779, -1, 3783, 2383, 2385, -1, 3783, 3781, 3782, -1, 3783, 3779, 3781, -1, 3783, 3784, 2383, -1, 3783, 3782, 3767, -1, 3785, 3711, 3769, -1, 3785, 3769, 3786, -1, 3785, 3786, 3787, -1, 3785, 3787, 3784, -1, 3785, 3767, 3711, -1, 3785, 3784, 3783, -1, 3785, 3783, 3767, -1, 3788, 2383, 3784, -1, 3788, 3787, 3786, -1, 3788, 3784, 3787, -1, 3789, 3786, 3769, -1, 3789, 3768, 3770, -1, 3789, 3769, 3768, -1, 3789, 3788, 3786, -1, 3790, 2381, 2383, -1, 3790, 2383, 3788, -1, 3790, 3788, 3789, -1, 3790, 3789, 3770, -1, 3791, 3770, 3771, -1, 3791, 3773, 3792, -1, 3791, 3790, 3770, -1, 3791, 3771, 3773, -1, 3793, 3790, 3791, -1, 3793, 3792, 3794, -1, 3793, 3794, 3795, -1, 3793, 3791, 3792, -1, 3793, 3795, 2381, -1, 3793, 2381, 3790, -1, 3796, 3792, 3773, -1, 3796, 3774, 3775, -1, 3796, 3773, 3774, -1, 3797, 3794, 3792, -1, 3797, 3795, 3794, -1, 3797, 3792, 3796, -1, 3797, 2381, 3795, -1, 3798, 3797, 3796, -1, 3799, 3796, 3775, -1, 3799, 2381, 3797, -1, 3799, 3798, 3796, -1, 3799, 3797, 3798, -1, 3799, 2380, 2381, -1, 3800, 3799, 3775, -1, 3800, 3776, 3713, -1, 3800, 3713, 3720, -1, 3800, 3775, 3776, -1, 3801, 3799, 3800, -1, 3801, 3800, 3720, -1, 3801, 3714, 2380, -1, 3801, 3720, 3722, -1, 3801, 2380, 3799, -1, 3801, 3722, 3714, -1, 2480, 3693, 2478, -1, 3802, 3707, 3693, -1, 3802, 3693, 2480, -1, 3803, 3706, 3707, -1, 3803, 3707, 3802, -1, 3804, 3705, 3706, -1, 3804, 3706, 3803, -1, 3805, 3705, 3804, -1, 3806, 3704, 3705, -1, 3806, 3705, 3805, -1, 3807, 3694, 3704, -1, 3807, 3704, 3806, -1, 2495, 2697, 3694, -1, 2495, 3694, 3807, -1, 3808, 2673, 2591, -1, 3731, 3808, 2591, -1, 3809, 3808, 3731, -1, 3726, 3809, 3731, -1, 3810, 3809, 3726, -1, 3725, 3810, 3726, -1, 3727, 3811, 3810, -1, 3727, 3810, 3725, -1, 3728, 3812, 3811, -1, 3728, 3811, 3727, -1, 3729, 3813, 3812, -1, 3729, 3812, 3728, -1, 2396, 2397, 3813, -1, 2396, 3813, 3729, -1, 3814, 2500, 2498, -1, 3814, 3815, 2500, -1, 3816, 3817, 3818, -1, 3816, 3819, 3817, -1, 3820, 3821, 3815, -1, 3820, 3815, 3814, -1, 2501, 3822, 2502, -1, 3823, 2487, 2489, -1, 3823, 3824, 3819, -1, 3823, 2489, 3824, -1, 3823, 3819, 3816, -1, 3825, 3821, 3820, -1, 3825, 3826, 3821, -1, 3827, 3818, 3826, -1, 3827, 3826, 3825, -1, 3828, 2498, 2497, -1, 3828, 3814, 2498, -1, 2489, 2491, 3829, -1, 3830, 3818, 3827, -1, 3830, 3816, 3818, -1, 3831, 3820, 3814, -1, 3831, 3814, 3828, -1, 3832, 3816, 3830, -1, 3832, 2485, 2487, -1, 3832, 2487, 3823, -1, 3832, 3823, 3816, -1, 3833, 3825, 3820, -1, 3833, 3820, 3831, -1, 3834, 3825, 3833, -1, 3834, 3827, 3825, -1, 3835, 2495, 3807, -1, 3835, 2496, 2495, -1, 3835, 2497, 2496, -1, 3835, 3828, 2497, -1, 3836, 3830, 3827, -1, 3836, 3827, 3834, -1, 3837, 3807, 3806, -1, 3837, 3831, 3828, -1, 3837, 3835, 3807, -1, 3837, 3828, 3835, -1, 3838, 2484, 2485, -1, 3838, 3830, 3836, -1, 3838, 2485, 3832, -1, 3838, 3832, 3830, -1, 3839, 3806, 3805, -1, 3839, 3833, 3831, -1, 3839, 3837, 3806, -1, 3839, 3831, 3837, -1, 3840, 3805, 3804, -1, 3841, 3822, 2501, -1, 3840, 3834, 3833, -1, 3842, 3843, 3822, -1, 3840, 3833, 3839, -1, 3840, 3839, 3805, -1, 3844, 3804, 3803, -1, 3842, 3822, 3841, -1, 3844, 3834, 3840, -1, 3844, 3836, 3834, -1, 3845, 3846, 3843, -1, 3845, 3847, 3846, -1, 3844, 3840, 3804, -1, 3848, 3803, 3802, -1, 3848, 3802, 2480, -1, 3848, 2482, 2484, -1, 3845, 3843, 3842, -1, 3848, 2480, 2482, -1, 3848, 3838, 3836, -1, 3848, 3844, 3803, -1, 3848, 3836, 3844, -1, 3817, 3847, 3845, -1, 3848, 2484, 3838, -1, 3815, 2501, 2500, -1, 3815, 3841, 2501, -1, 3819, 3849, 3847, -1, 3819, 3847, 3817, -1, 3821, 3842, 3841, -1, 3821, 3841, 3815, -1, 3824, 3829, 3849, -1, 3824, 2489, 3829, -1, 3824, 3849, 3819, -1, 3826, 3845, 3842, -1, 3826, 3842, 3821, -1, 3818, 3845, 3826, -1, 3818, 3817, 3845, -1, 2677, 3850, 2462, -1, 2712, 2713, 3851, -1, 3808, 2674, 2673, -1, 2397, 2711, 3813, -1, 3852, 3850, 2677, -1, 3853, 3854, 3850, -1, 3853, 3850, 3852, -1, 3855, 3856, 3854, -1, 3855, 3854, 3853, -1, 3857, 3858, 3856, -1, 3857, 3856, 3855, -1, 3859, 3860, 3858, -1, 3859, 3858, 3857, -1, 3861, 2711, 2712, -1, 3861, 3851, 3860, -1, 3861, 2712, 3851, -1, 3861, 3860, 3859, -1, 3862, 2677, 2674, -1, 3862, 3853, 3852, -1, 3862, 3855, 3853, -1, 3862, 3852, 2677, -1, 3863, 3861, 3859, -1, 3863, 2711, 3861, -1, 3863, 3859, 3857, -1, 3863, 3857, 3855, -1, 3863, 3855, 3862, -1, 3864, 2711, 3863, -1, 3864, 3862, 2674, -1, 3864, 3863, 3862, -1, 3865, 3808, 3809, -1, 3865, 3809, 3810, -1, 3865, 3810, 3811, -1, 3865, 3811, 3812, -1, 3865, 3812, 3813, -1, 3865, 2711, 3864, -1, 3865, 2674, 3808, -1, 3865, 3813, 2711, -1, 3865, 3864, 2674, -1, 3866, 3829, 2491, -1, 3866, 2491, 2493, -1, 3867, 3849, 3829, -1, 3867, 3829, 3866, -1, 3868, 3847, 3849, -1, 3868, 3849, 3867, -1, 3869, 3843, 3846, -1, 3869, 3846, 3847, -1, 3869, 3847, 3868, -1, 3870, 3822, 3843, -1, 3870, 3843, 3869, -1, 3871, 2502, 3822, -1, 3871, 3822, 3870, -1, 2696, 2502, 3871, -1, 3850, 3872, 2463, -1, 3850, 2463, 2462, -1, 3854, 3873, 3872, -1, 3854, 3872, 3850, -1, 3856, 3874, 3873, -1, 3856, 3873, 3854, -1, 3858, 3875, 3874, -1, 3858, 3876, 3875, -1, 3858, 3874, 3856, -1, 3860, 3877, 3876, -1, 3860, 3876, 3858, -1, 3851, 2511, 3877, -1, 3851, 3877, 3860, -1, 2713, 2511, 3851, -1, 2691, 3866, 2493, -1, 2695, 2696, 3871, -1, 3878, 2688, 2687, -1, 2459, 2694, 3879, -1, 3880, 3866, 2691, -1, 3881, 3867, 3866, -1, 3881, 3866, 3880, -1, 3882, 3868, 3867, -1, 3882, 3867, 3881, -1, 3883, 3869, 3868, -1, 3883, 3868, 3882, -1, 3884, 3870, 3869, -1, 3884, 3869, 3883, -1, 3885, 3871, 3870, -1, 3885, 2694, 2695, -1, 3885, 2695, 3871, -1, 3885, 3870, 3884, -1, 3886, 2691, 2688, -1, 3886, 3880, 2691, -1, 3886, 3882, 3881, -1, 3886, 3881, 3880, -1, 3887, 3883, 3882, -1, 3887, 3885, 3884, -1, 3887, 3884, 3883, -1, 3887, 3882, 3886, -1, 3887, 2694, 3885, -1, 3888, 3886, 2688, -1, 3888, 2694, 3887, -1, 3888, 3887, 3886, -1, 3889, 3890, 3879, -1, 3889, 3891, 3890, -1, 3889, 3892, 3891, -1, 3889, 3893, 3892, -1, 3889, 3878, 3893, -1, 3889, 2688, 3878, -1, 3889, 2694, 3888, -1, 3889, 3888, 2688, -1, 3889, 3879, 2694, -1, 3894, 3895, 3896, -1, 3897, 2509, 2507, -1, 3897, 3898, 2509, -1, 3899, 3900, 3895, -1, 3899, 3895, 3894, -1, 3901, 3902, 3898, -1, 3901, 3898, 3897, -1, 3903, 2468, 2466, -1, 3903, 3904, 3900, -1, 3903, 2466, 3904, -1, 3903, 3900, 3899, -1, 3905, 3906, 3902, -1, 3905, 3902, 3901, -1, 3907, 3906, 3905, -1, 3907, 3894, 3906, -1, 3908, 2507, 2506, -1, 3908, 3897, 2507, -1, 2466, 2463, 3872, -1, 3909, 3899, 3894, -1, 3909, 3894, 3907, -1, 3910, 3897, 3908, -1, 3910, 3901, 3897, -1, 3911, 3899, 3909, -1, 3911, 2470, 2468, -1, 3911, 2468, 3903, -1, 3911, 3903, 3899, -1, 3912, 3901, 3910, -1, 3912, 3905, 3901, -1, 3913, 3905, 3912, -1, 3913, 3907, 3905, -1, 3914, 2505, 2504, -1, 3915, 2506, 2505, -1, 3915, 3914, 3916, -1, 3915, 2505, 3914, -1, 3915, 3908, 2506, -1, 3917, 3909, 3907, -1, 3917, 3907, 3913, -1, 3918, 3910, 3908, -1, 3918, 3908, 3915, -1, 3918, 3915, 3916, -1, 3919, 3909, 3917, -1, 3919, 2471, 2470, -1, 3919, 2470, 3911, -1, 3919, 3911, 3909, -1, 3920, 3910, 3918, -1, 3920, 3921, 3922, -1, 3920, 3916, 3921, -1, 2475, 2473, 3923, -1, 3920, 3918, 3916, -1, 3924, 3877, 2511, -1, 3920, 3912, 3910, -1, 3924, 2511, 2510, -1, 3925, 3920, 3922, -1, 3926, 3876, 3877, -1, 3925, 3912, 3920, -1, 3926, 3877, 3924, -1, 3925, 3913, 3912, -1, 3927, 3928, 3923, -1, 3927, 3922, 3928, -1, 3927, 3917, 3913, -1, 3896, 3875, 3876, -1, 3927, 3925, 3922, -1, 3927, 3913, 3925, -1, 3929, 3919, 3917, -1, 3929, 3927, 3923, -1, 3896, 3876, 3926, -1, 3929, 2471, 3919, -1, 3929, 2473, 2471, -1, 3895, 3874, 3875, -1, 3929, 3917, 3927, -1, 3929, 3923, 2473, -1, 3895, 3875, 3896, -1, 3898, 2510, 2509, -1, 3898, 3924, 2510, -1, 3900, 3873, 3874, -1, 3900, 3874, 3895, -1, 3902, 3924, 3898, -1, 3902, 3926, 3924, -1, 3904, 3872, 3873, -1, 3904, 2466, 3872, -1, 3904, 3873, 3900, -1, 3906, 3896, 3926, -1, 3906, 3926, 3902, -1, 3894, 3896, 3906, -1, 3878, 2687, 2547, -1, 3930, 3878, 2547, -1, 3893, 3878, 3930, -1, 3931, 3893, 3930, -1, 3892, 3893, 3931, -1, 3932, 3892, 3931, -1, 3891, 3892, 3932, -1, 3933, 3891, 3932, -1, 3934, 3890, 3891, -1, 3934, 3891, 3933, -1, 3935, 3879, 3890, -1, 3935, 3890, 3934, -1, 2458, 2459, 3879, -1, 2458, 3879, 3935, -1, 2475, 3936, 2477, -1, 3923, 3937, 3936, -1, 3923, 3936, 2475, -1, 3928, 3938, 3937, -1, 3928, 3937, 3923, -1, 3922, 3938, 3928, -1, 3921, 3939, 3938, -1, 3921, 3938, 3922, -1, 3916, 3940, 3939, -1, 3916, 3939, 3921, -1, 3914, 3941, 3940, -1, 3914, 3940, 3916, -1, 2504, 2708, 3941, -1, 2504, 3941, 3914, -1, 2438, 2439, 3942, -1, 3943, 2545, 2544, -1, 3944, 2544, 2542, -1, 3945, 2542, 2540, -1, 3946, 2538, 2536, -1, 3947, 2533, 2531, -1, 3948, 3947, 2531, -1, 2440, 3949, 2439, -1, 3950, 2531, 2528, -1, 3950, 2528, 3951, -1, 3952, 3951, 3953, -1, 3952, 3950, 3951, -1, 3952, 2531, 3950, -1, 3954, 3953, 3955, -1, 3954, 3952, 3953, -1, 3954, 2531, 3952, -1, 3956, 3957, 3958, -1, 3956, 3955, 3957, -1, 3956, 2531, 3954, -1, 3956, 3948, 2531, -1, 3956, 3954, 3955, -1, 3959, 3958, 3960, -1, 3959, 3961, 3948, -1, 3959, 3956, 3958, -1, 3959, 3948, 3956, -1, 3962, 3960, 3963, -1, 3962, 3961, 3959, -1, 3962, 3964, 3961, -1, 3962, 3959, 3960, -1, 3965, 3942, 2439, -1, 3965, 3963, 3942, -1, 3965, 2439, 3949, -1, 3965, 3949, 3964, -1, 3965, 3964, 3962, -1, 3965, 3962, 3963, -1, 3966, 2458, 3935, -1, 3966, 3935, 3934, -1, 3966, 3934, 3933, -1, 3966, 3933, 3932, -1, 3966, 3932, 3931, -1, 3967, 3931, 3930, -1, 3967, 3930, 2547, -1, 3967, 2547, 2545, -1, 3967, 3966, 3931, -1, 3968, 3966, 3967, -1, 3969, 3966, 3968, -1, 3969, 2454, 2458, -1, 3969, 2458, 3966, -1, 3969, 3967, 2545, -1, 3969, 3970, 2454, -1, 3969, 3968, 3967, -1, 3971, 3969, 2545, -1, 3971, 3943, 3972, -1, 3971, 2545, 3943, -1, 3973, 3969, 3971, -1, 3974, 3975, 3976, -1, 3974, 3969, 3973, -1, 3974, 3970, 3969, -1, 3974, 3971, 3972, -1, 3974, 3973, 3971, -1, 3974, 3972, 3975, -1, 3974, 3977, 3970, -1, 3974, 3976, 3977, -1, 3978, 3972, 3943, -1, 3978, 3943, 2544, -1, 3979, 3976, 3975, -1, 3979, 3975, 3972, -1, 3979, 3977, 3976, -1, 3979, 3972, 3978, -1, 3980, 3977, 3979, -1, 3980, 3979, 3978, -1, 3980, 2451, 2454, -1, 3980, 3981, 2451, -1, 3980, 3970, 3977, -1, 3980, 3978, 2544, -1, 3980, 2454, 3970, -1, 3982, 3980, 2544, -1, 3982, 3981, 3980, -1, 3982, 3944, 3983, -1, 3982, 3984, 3981, -1, 3982, 3983, 3985, -1, 3982, 2544, 3944, -1, 3982, 3985, 3984, -1, 3986, 3944, 2542, -1, 3987, 3944, 3986, -1, 3987, 3983, 3944, -1, 3987, 3985, 3983, -1, 3987, 3984, 3985, -1, 3988, 3987, 3986, -1, 3988, 2446, 2451, -1, 3988, 3984, 3987, -1, 3988, 3981, 3984, -1, 3988, 3986, 2542, -1, 3988, 3989, 2446, -1, 3988, 2451, 3981, -1, 3990, 3989, 3988, -1, 3990, 3991, 3989, -1, 3990, 3988, 2542, -1, 3990, 3992, 3993, -1, 3990, 2542, 3945, -1, 3990, 3993, 3991, -1, 3990, 3945, 3992, -1, 3994, 3945, 2540, -1, 3995, 3993, 3992, -1, 3995, 3945, 3994, -1, 3995, 3992, 3945, -1, 3996, 3994, 2540, -1, 3996, 3995, 3994, -1, 3997, 2540, 2538, -1, 3997, 2538, 3998, -1, 3997, 3996, 2540, -1, 3999, 4000, 4001, -1, 3999, 3998, 4000, -1, 3999, 3997, 3998, -1, 3999, 3996, 3997, -1, 4002, 3998, 2538, -1, 4003, 2538, 3946, -1, 4004, 4005, 3946, -1, 4004, 3946, 2536, -1, 4006, 4004, 2536, -1, 4007, 4008, 4009, -1, 4007, 4006, 2536, -1, 4007, 2536, 4008, -1, 4010, 2536, 2533, -1, 4010, 4009, 4008, -1, 4010, 4008, 2536, -1, 4011, 4010, 2533, -1, 4012, 3947, 3948, -1, 4012, 4011, 2533, -1, 4012, 2533, 3947, -1, 4013, 3989, 3991, -1, 4013, 2446, 3989, -1, 4013, 3993, 3995, -1, 4013, 3991, 3993, -1, 4013, 3995, 3996, -1, 4014, 4015, 4016, -1, 4014, 4001, 4015, -1, 4014, 2446, 4013, -1, 4014, 4016, 2445, -1, 4014, 2445, 2446, -1, 4014, 3996, 3999, -1, 4014, 3999, 4001, -1, 4014, 4013, 3996, -1, 4017, 4001, 4000, -1, 4017, 4016, 4015, -1, 4017, 4015, 4001, -1, 4017, 4000, 3998, -1, 4017, 3998, 4002, -1, 4018, 4002, 2538, -1, 4018, 2538, 4003, -1, 4018, 4017, 4002, -1, 4019, 4020, 2443, -1, 4019, 2445, 4016, -1, 4019, 2443, 2445, -1, 4019, 4016, 4017, -1, 4019, 4017, 4018, -1, 4019, 4018, 4003, -1, 4021, 4003, 3946, -1, 4021, 3946, 4005, -1, 4021, 4005, 4022, -1, 4021, 4022, 4023, -1, 4021, 4023, 4020, -1, 4021, 4020, 4019, -1, 4021, 4019, 4003, -1, 4024, 2443, 4020, -1, 4024, 4023, 4022, -1, 4024, 4020, 4023, -1, 4025, 4022, 4005, -1, 4025, 4005, 4004, -1, 4025, 4004, 4006, -1, 4025, 4024, 4022, -1, 4026, 2442, 2443, -1, 4026, 2443, 4024, -1, 4026, 4025, 4006, -1, 4026, 4024, 4025, -1, 4027, 4026, 4006, -1, 4027, 4009, 4028, -1, 4027, 4006, 4007, -1, 4027, 4007, 4009, -1, 4029, 4027, 4028, -1, 4029, 4030, 2442, -1, 4029, 4026, 4027, -1, 4029, 4028, 4031, -1, 4029, 4031, 4030, -1, 4029, 2442, 4026, -1, 4032, 4010, 4011, -1, 4032, 4028, 4009, -1, 4032, 4009, 4010, -1, 4033, 4028, 4032, -1, 4033, 2442, 4030, -1, 4033, 4031, 4028, -1, 4033, 4030, 4031, -1, 4034, 4033, 4032, -1, 4035, 2442, 4033, -1, 4035, 4034, 4032, -1, 4035, 2440, 2442, -1, 4035, 4033, 4034, -1, 4035, 4032, 4011, -1, 4036, 4035, 4011, -1, 4036, 3948, 3961, -1, 4036, 4012, 3948, -1, 4036, 4011, 4012, -1, 4037, 4035, 4036, -1, 4037, 4036, 3961, -1, 4037, 2440, 4035, -1, 4037, 3949, 2440, -1, 4037, 3961, 3964, -1, 4037, 3964, 3949, -1, 2710, 2406, 4038, -1, 3936, 2668, 2477, -1, 2708, 2709, 3941, -1, 4039, 4040, 2672, -1, 4039, 2670, 2668, -1, 4039, 2672, 2670, -1, 4041, 4042, 4040, -1, 4041, 4040, 4039, -1, 4043, 4044, 4042, -1, 4043, 4042, 4041, -1, 4045, 4046, 4044, -1, 4045, 4044, 4043, -1, 4047, 4048, 4046, -1, 4047, 4046, 4045, -1, 4049, 2709, 2710, -1, 4049, 4038, 4048, -1, 4049, 2710, 4038, -1, 4049, 4048, 4047, -1, 4050, 4049, 4047, -1, 4050, 4041, 4039, -1, 4050, 4039, 2668, -1, 4050, 4047, 4045, -1, 4050, 2709, 4049, -1, 4050, 4045, 4043, -1, 4050, 4043, 4041, -1, 4051, 4050, 2668, -1, 4051, 2709, 4050, -1, 4052, 3936, 3937, -1, 4052, 3937, 3938, -1, 4052, 3938, 3939, -1, 4052, 3939, 3940, -1, 4052, 3940, 3941, -1, 4052, 2709, 4051, -1, 4052, 4051, 2668, -1, 4052, 2668, 3936, -1, 4052, 3941, 2709, -1, 4053, 4054, 2630, -1, 4053, 4055, 4054, -1, 4056, 4057, 4058, -1, 4056, 2636, 4059, -1, 4056, 4059, 4057, -1, 4060, 4053, 2630, -1, 2432, 2430, 4061, -1, 2432, 4062, 2428, -1, 2432, 4061, 4062, -1, 4063, 2630, 2632, -1, 4063, 2632, 4064, -1, 4065, 4058, 4066, -1, 4063, 4064, 4067, -1, 4065, 4068, 2636, -1, 4065, 2636, 4056, -1, 4063, 4060, 2630, -1, 4065, 4056, 4058, -1, 4069, 4066, 4070, -1, 4069, 4071, 4068, -1, 4072, 4063, 4067, -1, 4072, 4060, 4063, -1, 4069, 4068, 4065, -1, 4069, 4065, 4066, -1, 4073, 3942, 3963, -1, 4073, 3963, 3960, -1, 4074, 4070, 4075, -1, 4073, 3960, 3958, -1, 4074, 4071, 4069, -1, 4073, 3958, 3957, -1, 4074, 4076, 4071, -1, 4073, 3957, 4077, -1, 4078, 4079, 4080, -1, 4074, 4069, 4070, -1, 4078, 4073, 4077, -1, 4081, 4082, 4076, -1, 4078, 4077, 4079, -1, 4081, 4074, 4075, -1, 4083, 4078, 4080, -1, 4081, 4076, 4074, -1, 4083, 4073, 4078, -1, 4084, 4075, 4085, -1, 4084, 2428, 4062, -1, 4084, 4062, 4082, -1, 4084, 4082, 4081, -1, 4086, 2438, 3942, -1, 4084, 4081, 4075, -1, 4084, 4085, 2428, -1, 4086, 3942, 4073, -1, 4086, 4073, 4083, -1, 4087, 2437, 2438, -1, 4088, 3953, 3951, -1, 4088, 3951, 2528, -1, 4087, 2438, 4086, -1, 4088, 2528, 2624, -1, 4087, 4086, 4083, -1, 4067, 4064, 2632, -1, 4087, 4083, 4080, -1, 4089, 4090, 4091, -1, 4089, 4092, 4093, -1, 4089, 2437, 4087, -1, 4089, 4080, 4090, -1, 4089, 4087, 4080, -1, 4089, 4093, 2437, -1, 4077, 3957, 3955, -1, 4094, 4067, 2632, -1, 4089, 4095, 4092, -1, 4077, 3955, 3953, -1, 4089, 4091, 4095, -1, 4096, 4097, 4098, -1, 4077, 3953, 4088, -1, 4096, 4091, 4097, -1, 4096, 4092, 4095, -1, 4096, 4095, 4091, -1, 4099, 4092, 4096, -1, 4100, 4094, 2632, -1, 4101, 4077, 4088, -1, 4099, 4093, 4092, -1, 4079, 4077, 4101, -1, 4099, 2437, 4093, -1, 4102, 2437, 4099, -1, 4102, 2435, 2437, -1, 4102, 4099, 4096, -1, 4080, 4088, 2624, -1, 4102, 4096, 4098, -1, 4103, 4104, 4105, -1, 4103, 4098, 4104, -1, 4103, 4102, 4098, -1, 4080, 4101, 4088, -1, 4103, 4106, 4107, -1, 4080, 4079, 4101, -1, 4108, 2632, 2634, -1, 4103, 4105, 4109, -1, 4103, 4109, 4106, -1, 4110, 4103, 4107, -1, 4090, 4111, 4112, -1, 4110, 4113, 2435, -1, 4090, 4112, 4091, -1, 4110, 4107, 4113, -1, 4090, 2624, 4111, -1, 4110, 2435, 4102, -1, 4090, 4080, 2624, -1, 4114, 4108, 2634, -1, 4110, 4102, 4103, -1, 4115, 4116, 4117, -1, 4097, 4112, 4111, -1, 4097, 4111, 2626, -1, 4115, 4109, 4116, -1, 4097, 4091, 4112, -1, 4115, 2435, 4113, -1, 4114, 2632, 4108, -1, 4115, 4113, 4107, -1, 4118, 4100, 2632, -1, 4115, 4107, 4106, -1, 4115, 4106, 4109, -1, 4118, 4114, 2634, -1, 4118, 2632, 4114, -1, 4119, 4120, 4100, -1, 4121, 4117, 4122, -1, 4098, 4097, 2626, -1, 4123, 2435, 4115, -1, 4119, 4100, 4118, -1, 4123, 4115, 4117, -1, 4123, 2434, 2435, -1, 4124, 4098, 2626, -1, 4125, 4126, 4120, -1, 4124, 2626, 2628, -1, 4123, 4117, 4121, -1, 4125, 4120, 4119, -1, 4061, 2431, 4127, -1, 4128, 4123, 4121, -1, 4124, 2628, 4129, -1, 4128, 4130, 2434, -1, 4128, 2434, 4123, -1, 4104, 4124, 4129, -1, 4061, 4127, 4126, -1, 2427, 2428, 4085, -1, 4131, 4055, 4132, -1, 4104, 4129, 4105, -1, 4061, 4126, 4125, -1, 4111, 2624, 2626, -1, 4131, 4132, 4133, -1, 4131, 4133, 4134, -1, 4104, 4098, 4124, -1, 2430, 2431, 4061, -1, 4131, 4134, 4130, -1, 4131, 4122, 4054, -1, 4135, 2634, 2636, -1, 4131, 4054, 4055, -1, 4131, 4121, 4122, -1, 4131, 4128, 4121, -1, 4131, 4130, 4128, -1, 4136, 4133, 4132, -1, 4136, 4134, 4133, -1, 4116, 4105, 4129, -1, 4068, 4135, 2636, -1, 4136, 4130, 4134, -1, 4116, 4109, 4105, -1, 4116, 4129, 2628, -1, 4136, 4053, 4060, -1, 4136, 4132, 4053, -1, 4068, 2634, 4135, -1, 4136, 2434, 4130, -1, 4117, 4116, 2628, -1, 4137, 2431, 2434, -1, 4071, 4118, 2634, -1, 4137, 4060, 4072, -1, 4137, 4136, 4060, -1, 4071, 2634, 4068, -1, 4137, 2434, 4136, -1, 4138, 4127, 2431, -1, 4076, 4119, 4118, -1, 4138, 2431, 4137, -1, 4139, 4117, 2628, -1, 4076, 4118, 4071, -1, 4138, 4137, 4072, -1, 4139, 2628, 2630, -1, 4140, 4138, 4072, -1, 4139, 2630, 4054, -1, 4082, 4119, 4076, -1, 4140, 4094, 4100, -1, 4082, 4125, 4119, -1, 4140, 4100, 4120, -1, 4140, 4120, 4126, -1, 4140, 4126, 4127, -1, 4140, 4072, 4067, -1, 4140, 4067, 4094, -1, 4140, 4127, 4138, -1, 4122, 4139, 4054, -1, 4062, 4061, 4125, -1, 4122, 4117, 4139, -1, 4062, 4125, 4082, -1, 4053, 4132, 4055, -1, 4059, 2636, 2341, -1, 4059, 2341, 4057, -1, 4040, 4141, 2570, -1, 4040, 2570, 2672, -1, 4042, 4142, 4141, -1, 4042, 4141, 4040, -1, 4044, 4143, 4142, -1, 4044, 4142, 4042, -1, 4144, 4143, 4044, -1, 4046, 4144, 4044, -1, 4145, 4144, 4046, -1, 4048, 4145, 4046, -1, 4146, 4145, 4048, -1, 4038, 4146, 4048, -1, 2408, 4146, 4038, -1, 2406, 2408, 4038, -1, 4147, 4148, 4149, -1, 4147, 4150, 4151, -1, 4152, 2334, 2336, -1, 2422, 2427, 4085, -1, 4153, 4057, 2341, -1, 4153, 2341, 2338, -1, 4154, 4058, 4057, -1, 4154, 4057, 4153, -1, 4155, 4066, 4058, -1, 4155, 4058, 4154, -1, 4156, 2338, 2334, -1, 4156, 4153, 2338, -1, 4156, 2334, 4152, -1, 4157, 4070, 4066, -1, 4157, 4066, 4155, -1, 4158, 4152, 4159, -1, 4158, 4154, 4153, -1, 4158, 4153, 4156, -1, 4158, 4156, 4152, -1, 4149, 4075, 4070, -1, 4149, 4070, 4157, -1, 4160, 4159, 4161, -1, 4160, 4158, 4159, -1, 4160, 4154, 4158, -1, 4160, 4155, 4154, -1, 4148, 4085, 4075, -1, 4148, 2418, 2422, -1, 4148, 4075, 4149, -1, 4148, 2422, 4085, -1, 4162, 4161, 4163, -1, 4162, 4155, 4160, -1, 4162, 4157, 4155, -1, 4162, 4160, 4161, -1, 4150, 4163, 4151, -1, 4150, 4149, 4157, -1, 4150, 4162, 4163, -1, 4150, 4157, 4162, -1, 4147, 4164, 2417, -1, 4147, 4151, 4164, -1, 4147, 2417, 2418, -1, 4147, 4149, 4150, -1, 4147, 2418, 4148, -1, 4165, 2586, 2584, -1, 4166, 4165, 2584, -1, 4167, 4165, 4166, -1, 4168, 4169, 4165, -1, 4168, 4165, 4167, -1, 4170, 2449, 2455, -1, 4170, 4171, 2449, -1, 4172, 4169, 4168, -1, 4172, 4173, 4169, -1, 4174, 4173, 4172, -1, 4174, 4175, 4173, -1, 4176, 4177, 4175, -1, 4176, 4175, 4174, -1, 4178, 4171, 4177, -1, 4178, 4177, 4176, -1, 4178, 2449, 4171, -1, 4179, 2452, 2447, -1, 4180, 2426, 2452, -1, 4181, 2423, 2426, -1, 4182, 2420, 2423, -1, 4183, 2415, 2420, -1, 4184, 2410, 2415, -1, 4185, 4186, 2588, -1, 4185, 4187, 4186, -1, 4185, 2588, 2586, -1, 4188, 4165, 4169, -1, 4188, 4169, 4173, -1, 4188, 2586, 4165, -1, 4189, 4178, 4176, -1, 4189, 2447, 2449, -1, 4189, 4176, 4174, -1, 4189, 2449, 4178, -1, 4190, 2447, 4189, -1, 4191, 2447, 4190, -1, 4191, 4192, 4193, -1, 4191, 4179, 2447, -1, 4191, 4193, 4179, -1, 4194, 4193, 4192, -1, 4194, 2452, 4179, -1, 4194, 4179, 4193, -1, 4195, 2452, 4194, -1, 4196, 2452, 4195, -1, 4196, 4197, 4198, -1, 4196, 4180, 2452, -1, 4196, 4198, 4180, -1, 4199, 2426, 4180, -1, 4199, 4180, 4198, -1, 4200, 4201, 4202, -1, 4200, 4181, 2426, -1, 4200, 4202, 4181, -1, 4203, 4202, 4201, -1, 4204, 4202, 4203, -1, 4204, 2423, 4181, -1, 4204, 4181, 4202, -1, 4205, 4204, 4203, -1, 4205, 2423, 4204, -1, 4206, 4207, 4208, -1, 4206, 4208, 4209, -1, 4210, 4205, 4206, -1, 4210, 4206, 4209, -1, 4210, 2423, 4205, -1, 4210, 4182, 2423, -1, 4210, 4209, 4182, -1, 4211, 4209, 4212, -1, 4211, 2420, 4182, -1, 4211, 4182, 4209, -1, 4213, 4211, 4212, -1, 4213, 2420, 4211, -1, 4214, 4215, 4216, -1, 4214, 4216, 4217, -1, 4218, 4214, 4217, -1, 4218, 4217, 4183, -1, 4218, 4183, 2420, -1, 4218, 4213, 4214, -1, 4218, 2420, 4213, -1, 4219, 4183, 4217, -1, 4219, 2415, 4183, -1, 4220, 2572, 4221, -1, 4220, 4222, 4223, -1, 4220, 2415, 4219, -1, 4220, 4221, 4222, -1, 4224, 4220, 4223, -1, 4224, 4223, 4225, -1, 4224, 4225, 4226, -1, 4224, 4226, 4227, -1, 4224, 4184, 2415, -1, 4224, 4227, 4184, -1, 4224, 2415, 4220, -1, 4228, 4223, 4222, -1, 4228, 4225, 4223, -1, 4228, 4226, 4225, -1, 4228, 4227, 4226, -1, 4229, 4227, 4228, -1, 4229, 2410, 4184, -1, 4229, 4184, 4227, -1, 4230, 4229, 4228, -1, 4230, 2410, 4229, -1, 4230, 4221, 2572, -1, 4230, 2572, 2570, -1, 4230, 4222, 4221, -1, 4230, 4228, 4222, -1, 4231, 4145, 4146, -1, 4231, 4146, 2408, -1, 4231, 4230, 4232, -1, 4231, 2408, 2410, -1, 4231, 2410, 4230, -1, 4233, 2570, 4141, -1, 4233, 4141, 4142, -1, 4233, 4142, 4143, -1, 4233, 4143, 4144, -1, 4233, 4144, 4145, -1, 4233, 4145, 4231, -1, 4233, 4232, 4230, -1, 4233, 4231, 4232, -1, 4233, 4230, 2570, -1, 4234, 4235, 4187, -1, 4234, 4236, 4235, -1, 4234, 4237, 4236, -1, 4234, 4187, 4185, -1, 4238, 4239, 4237, -1, 4238, 4240, 4239, -1, 4238, 4241, 4240, -1, 4238, 4237, 4234, -1, 4242, 2455, 2456, -1, 4242, 4234, 4185, -1, 4242, 2456, 4241, -1, 4242, 4238, 4234, -1, 4242, 4241, 4238, -1, 4242, 4170, 2455, -1, 4243, 4242, 4185, -1, 4243, 4171, 4170, -1, 4243, 4188, 4173, -1, 4243, 4175, 4177, -1, 4243, 4170, 4242, -1, 4243, 4177, 4171, -1, 4243, 4173, 4175, -1, 4244, 4166, 2584, -1, 4244, 4167, 4166, -1, 4244, 4168, 4167, -1, 4245, 4190, 4189, -1, 4245, 4168, 4244, -1, 4245, 4244, 4246, -1, 4245, 4189, 4174, -1, 4245, 4172, 4168, -1, 4245, 4174, 4172, -1, 4247, 2584, 2582, -1, 4247, 4246, 4244, -1, 4247, 4190, 4245, -1, 4247, 4245, 4246, -1, 4247, 4244, 2584, -1, 4248, 4249, 4250, -1, 4248, 4247, 2582, -1, 4248, 4251, 4249, -1, 4248, 2582, 4251, -1, 4252, 4250, 4253, -1, 4252, 4253, 4192, -1, 4252, 4190, 4247, -1, 4252, 4247, 4248, -1, 4252, 4248, 4250, -1, 4252, 4192, 4191, -1, 4252, 4191, 4190, -1, 4254, 4250, 4249, -1, 4254, 4253, 4250, -1, 4254, 4249, 4251, -1, 4254, 4251, 2582, -1, 4255, 4195, 4194, -1, 4255, 4192, 4253, -1, 4255, 4194, 4192, -1, 4255, 4253, 4254, -1, 4255, 4254, 4256, -1, 4257, 4254, 2582, -1, 4257, 2582, 2580, -1, 4257, 4195, 4255, -1, 4257, 4256, 4254, -1, 4257, 4255, 4256, -1, 4258, 4259, 4260, -1, 4258, 4260, 4261, -1, 4258, 4257, 2580, -1, 4258, 2580, 4259, -1, 4262, 4261, 4263, -1, 4262, 4263, 4197, -1, 4262, 4258, 4261, -1, 4262, 4196, 4195, -1, 4262, 4197, 4196, -1, 4262, 4195, 4257, -1, 4262, 4257, 4258, -1, 4264, 4260, 4259, -1, 4264, 4261, 4260, -1, 4264, 4263, 4261, -1, 4265, 4199, 4198, -1, 4265, 4197, 4263, -1, 4265, 4198, 4197, -1, 4265, 4263, 4264, -1, 4266, 2580, 2578, -1, 4266, 4264, 4259, -1, 4266, 4199, 4265, -1, 4266, 4259, 2580, -1, 4266, 4265, 4264, -1, 4267, 2578, 4268, -1, 4267, 4268, 4269, -1, 4267, 4266, 2578, -1, 4270, 4267, 4269, -1, 4270, 4269, 4271, -1, 4270, 4200, 4267, -1, 4270, 4201, 4200, -1, 4270, 4271, 4272, -1, 4270, 4272, 4201, -1, 4273, 2578, 2576, -1, 4273, 4268, 2578, -1, 4273, 4269, 4268, -1, 4273, 4271, 4269, -1, 4273, 4272, 4271, -1, 4273, 4201, 4272, -1, 4273, 4203, 4201, -1, 4273, 4205, 4203, -1, 4274, 2576, 4275, -1, 4274, 4273, 2576, -1, 4274, 4206, 4205, -1, 4274, 4275, 4276, -1, 4274, 4276, 4277, -1, 4274, 4277, 4207, -1, 4274, 4205, 4273, -1, 4274, 4207, 4206, -1, 4278, 4212, 4209, -1, 4278, 4277, 4276, -1, 4278, 4207, 4277, -1, 4278, 4208, 4207, -1, 4278, 4209, 4208, -1, 4279, 2576, 2574, -1, 4279, 4275, 2576, -1, 4279, 4276, 4275, -1, 4279, 4212, 4278, -1, 4279, 4213, 4212, -1, 4279, 4278, 4276, -1, 4280, 4281, 4282, -1, 4280, 4282, 4215, -1, 4280, 4213, 4279, -1, 4280, 2574, 4283, -1, 4280, 4214, 4213, -1, 4280, 4279, 2574, -1, 4280, 4215, 4214, -1, 4280, 4283, 4281, -1, 4284, 4282, 4281, -1, 4284, 4215, 4282, -1, 4284, 4216, 4215, -1, 4284, 4217, 4216, -1, 4284, 4219, 4217, -1, 4284, 4281, 4283, -1, 4285, 2574, 2572, -1, 4285, 4283, 2574, -1, 4285, 2572, 4220, -1, 4285, 4219, 4284, -1, 4285, 4220, 4219, -1, 4285, 4284, 4283, -1, 4286, 4188, 4243, -1, 4286, 4243, 4185, -1, 4286, 2586, 4188, -1, 4286, 4185, 2586, -1, 4287, 2426, 4199, -1, 4287, 4200, 2426, -1, 4287, 4199, 4266, -1, 4287, 4267, 4200, -1, 4287, 4266, 4267, -1, 4288, 4163, 4161, -1, 4289, 4237, 4239, -1, 4288, 4161, 4290, -1, 4289, 4291, 4292, -1, 4293, 2413, 2417, -1, 4289, 4294, 4237, -1, 4293, 4288, 4290, -1, 4289, 4292, 4294, -1, 4293, 2417, 4288, -1, 4295, 4239, 4240, -1, 4295, 4296, 4291, -1, 4297, 4298, 4299, -1, 4297, 4293, 4290, -1, 4295, 4289, 4239, -1, 4295, 4291, 4289, -1, 4297, 2413, 4293, -1, 4300, 4240, 4241, -1, 4297, 4301, 2413, -1, 4300, 2461, 4302, -1, 4297, 4303, 4298, -1, 4300, 4302, 4296, -1, 4300, 4296, 4295, -1, 4297, 4299, 4301, -1, 4300, 4295, 4240, -1, 4304, 2404, 4305, -1, 4300, 4241, 2461, -1, 4304, 4306, 2402, -1, 4304, 4307, 4308, -1, 4304, 4305, 4309, -1, 4304, 4309, 4307, -1, 4304, 4308, 4310, -1, 4290, 4161, 4159, -1, 4304, 4310, 4306, -1, 4290, 4159, 4152, -1, 4304, 2402, 2404, -1, 4290, 4152, 2336, -1, 4311, 4312, 2660, -1, 4290, 2336, 2652, -1, 4311, 4307, 4313, -1, 4314, 4299, 4298, -1, 4311, 2660, 4315, -1, 4314, 4316, 2654, -1, 4311, 4313, 4312, -1, 4317, 2402, 4306, -1, 4317, 4308, 4307, -1, 4317, 4310, 4308, -1, 4314, 4298, 4303, -1, 4317, 4306, 4310, -1, 4314, 4318, 4316, -1, 4317, 4307, 4311, -1, 4314, 4303, 4318, -1, 4319, 2411, 2413, -1, 4319, 4314, 2654, -1, 4319, 2413, 4301, -1, 4320, 4311, 4315, -1, 4320, 2405, 2402, -1, 4319, 4321, 4322, -1, 4319, 4322, 2411, -1, 4320, 2402, 4317, -1, 4319, 4299, 4314, -1, 4320, 4323, 2405, -1, 4319, 4301, 4299, -1, 4320, 4317, 4311, -1, 4324, 4325, 4326, -1, 4327, 4328, 4329, -1, 4324, 4315, 4325, -1, 4327, 4329, 4330, -1, 4327, 4330, 4321, -1, 4324, 4326, 4331, -1, 4327, 4321, 4319, -1, 4327, 4319, 2654, -1, 4327, 2654, 4328, -1, 4324, 4320, 4315, -1, 4332, 4333, 4323, -1, 4332, 4331, 4334, -1, 4335, 4328, 2656, -1, 4332, 4334, 4333, -1, 4332, 4323, 4320, -1, 4332, 4324, 4331, -1, 4332, 4320, 4324, -1, 4336, 4323, 4333, -1, 4336, 4331, 4326, -1, 4336, 4334, 4331, -1, 4337, 4328, 4335, -1, 4336, 4333, 4334, -1, 4337, 4329, 4328, -1, 4337, 4330, 4329, -1, 4336, 4326, 4338, -1, 4337, 4321, 4330, -1, 4339, 2460, 2405, -1, 4339, 4336, 4338, -1, 4340, 4321, 4337, -1, 4339, 2405, 4323, -1, 4340, 4341, 2404, -1, 4340, 2404, 2411, -1, 4339, 4323, 4336, -1, 4340, 4322, 4321, -1, 4340, 2411, 4322, -1, 4342, 4338, 4343, -1, 4342, 4302, 2460, -1, 4340, 4337, 4335, -1, 4342, 2460, 4339, -1, 4340, 4335, 2656, -1, 4342, 4339, 4338, -1, 4344, 2656, 2658, -1, 4342, 4296, 4302, -1, 4344, 2658, 4345, -1, 4344, 4340, 2656, -1, 4346, 4343, 4347, -1, 4346, 4348, 4292, -1, 4346, 4347, 4348, -1, 4346, 4292, 4291, -1, 4349, 4350, 4351, -1, 4346, 4291, 4296, -1, 4349, 4344, 4345, -1, 4346, 4342, 4343, -1, 4349, 4340, 4344, -1, 4346, 4296, 4342, -1, 4349, 4341, 4340, -1, 4352, 4297, 4290, -1, 4349, 4345, 4353, -1, 4352, 4303, 4297, -1, 4349, 4353, 4350, -1, 4352, 4290, 2652, -1, 4349, 4351, 4341, -1, 4352, 2652, 4316, -1, 4352, 4316, 4318, -1, 4352, 4318, 4303, -1, 4354, 4345, 2658, -1, 4355, 4351, 4350, -1, 4355, 4345, 4354, -1, 4348, 4347, 2664, -1, 4355, 4353, 4345, -1, 4355, 4350, 4353, -1, 4305, 2404, 4341, -1, 4305, 4355, 4354, -1, 4305, 4354, 2658, -1, 4305, 4351, 4355, -1, 4305, 4341, 4351, -1, 2456, 2461, 4241, -1, 4356, 2660, 4312, -1, 4316, 2652, 2654, -1, 4356, 2658, 2660, -1, 4357, 2664, 2588, -1, 4357, 2588, 4186, -1, 4356, 4305, 2658, -1, 4356, 4312, 4313, -1, 4309, 4313, 4307, -1, 4309, 4305, 4356, -1, 4309, 4356, 4313, -1, 4315, 2660, 2662, -1, 4302, 2461, 2460, -1, 4315, 2662, 4325, -1, 4358, 4186, 4187, -1, 4358, 4357, 4186, -1, 4338, 4325, 2662, -1, 4338, 4326, 4325, -1, 4358, 2664, 4357, -1, 4359, 4187, 4235, -1, 4359, 4235, 4236, -1, 4359, 4348, 2664, -1, 4328, 2654, 2656, -1, 4359, 4358, 4187, -1, 4343, 2662, 2664, -1, 4359, 2664, 4358, -1, 4294, 4236, 4237, -1, 4343, 4338, 2662, -1, 4294, 4292, 4348, -1, 4343, 2664, 4347, -1, 4288, 2417, 4164, -1, 4288, 4164, 4151, -1, 4294, 4348, 4359, -1, 4288, 4151, 4163, -1, 4294, 4359, 4236, -1 - ] - } - castShadows FALSE - } - DEF estop_buttons Shape { - appearance Appearance { - material Material { - diffuseColor 1 0 0 - } - } - geometry DEF SoFCIndexedFaceSet IndexedFaceSet { - coord Coordinate { - point [ - -0.0039551035 0.11482497 -0.26742953, -0.0039604083 0.11483059 -0.2674188, -0.0020383671 0.11508892 -0.26690173, -0.0020410791 0.11509486 -0.26689011, -0.0039654151 0.11483631 -0.26740777, -0.0039706901 0.11484218 -0.26739693, -0.0057347789 0.11440917 -0.26826221, -0.0057422295 0.1144144 -0.26825261, -0.0057198778 0.1143989 -0.26828188, -0.0057272688 0.11440393 -0.2682721, -4.3429434e-05 0.1151929 -0.26669461, -0.0020463243 0.11510716 -0.26686704, -4.3489039e-05 0.11519917 -0.26668292, -0.0072837248 0.1138357 -0.269409, -0.0072932318 0.11384032 -0.26940101, -0.0072743073 0.11383133 -0.26941735, -4.336983e-05 0.11518057 -0.26671833, -4.3489039e-05 0.11518665 -0.26670647, -0.0072648302 0.11382706 -0.26942575, -0.0085528269 0.11313831 -0.27080423, -0.0085639134 0.11314201 -0.27079791, -0.0085417405 0.11313481 -0.27081072, -0.0085305348 0.11313147 -0.27081722, -0.0094931498 0.11234354 -0.27239394, -0.0095055178 0.11234618 -0.27238965, -0.0094685033 0.11233874 -0.27240276, -0.0094808117 0.11234102 -0.27239829, -0.010068752 0.11148199 -0.27411729, -0.010081835 0.11148352 -0.2741152, -0.010042675 0.11147936 -0.27412158, -0.010055728 0.11148054 -0.27411926, -0.01025749 0.11058683 -0.27590781, -0.010270782 0.11058719 -0.27590811, -0.010230698 0.11058652 -0.27590764, -0.010244139 0.11058659 -0.2759077, -0.010051884 0.10969233 -0.27769709, -0.010064967 0.10969149 -0.27769965, -0.010025926 0.10969443 -0.27769208, -0.01003886 0.10969342 -0.27769446, -0.009460099 0.10883313 -0.27941579, -0.0094724074 0.10883119 -0.27942061, -0.0094355121 0.10883733 -0.27940643, -0.0094478503 0.108835 -0.27941108, -0.008504875 0.10804193 -0.28099841, -0.0085158423 0.10803894 -0.28100538, -0.0084827021 0.10804837 -0.28098494, -0.0084936693 0.10804503 -0.28099161, -0.0072226599 0.10734921 -0.28238386, -0.0072320774 0.10734539 -0.28239256, -0.0072039142 0.10735741 -0.28236687, -0.0072132424 0.10735326 -0.28237528, -0.0056629255 0.10678177 -0.28351903, -0.0056703165 0.10677724 -0.28352916, -0.005648233 0.1067914 -0.28349912, -0.0056555644 0.10678651 -0.28350902, -0.003885664 0.10636132 -0.28436011, -0.0038907006 0.10635618 -0.2843715, -0.0038754418 0.10637196 -0.284338, -0.0038805977 0.10636655 -0.28434896, -0.0019614175 0.10609848 -0.28488696, -0.0019589737 0.10610398 -0.28487509, 4.2937696e-05 0.10601968 -0.28504395, 4.3056905e-05 0.10601398 -0.28505588, -0.0019564405 0.10610954 -0.28486335, 4.2967498e-05 0.1060253 -0.28503168, -0.0019537881 0.10611529 -0.28485155, 4.2848289e-05 0.10603126 -0.28501987, -0.0020437613 0.11510096 -0.26687855, 0.012995593 0.11053248 -0.27287871, 0.012632154 0.11105942 -0.27017611, 0.013422392 0.10991194 -0.27247131, 0.012230389 0.11164363 -0.27065635, 0.013992123 0.1072202 -0.27411056, 0.013711832 0.10844027 -0.27166998, 0.013557903 0.10767335 -0.27132154, 0.0021958575 0.1108486 -0.26171535, -5.7019293e-05 0.11177171 -0.26137781, -5.4724514e-05 0.11093237 -0.26154774, 0.013835035 0.10646694 -0.27373481, 0.013287865 0.10472073 -0.27548194, 0.013482861 0.10576808 -0.27338707, 0.012768202 0.10415726 -0.27510041, 0.01240962 0.11102771 -0.27325946, 0.011678927 0.11208852 -0.27113724, 0.013945185 0.10798492 -0.27449316, 0.013665818 0.10920095 -0.27206075, 0.013635091 0.10539221 -0.27588451, 0.011697881 0.11136875 -0.2735917, 0.01100909 0.11236878 -0.27159125, 0.013696842 0.10871755 -0.27486062, 0.013789736 0.10613335 -0.27628469, 0.010900967 0.11153672 -0.2738567, 0.010064624 0.11152148 -0.27403927, 0.0094720051 0.11238196 -0.27231824, 0.010259293 0.11246843 -0.27199244, 0.013261341 0.10937615 -0.27519202, 0.012689047 0.1037045 -0.27751487, 0.012192957 0.10318064 -0.27705365, 0.013743542 0.10690167 -0.27665985, 0.012663327 0.1099234 -0.27546829, 0.013020746 0.10434934 -0.27797031, 0.013498716 0.10765361 -0.2769888, 0.011937104 0.11032786 -0.27567381, 0.013168506 0.10507857 -0.27839422, 0.013069503 0.10834605 -0.27725244, 0.011123888 0.11056656 -0.27579713, 0.01027032 0.11062599 -0.27583075, 0.011704765 0.10275017 -0.27942371, 0.011247091 0.10226359 -0.27888793, 0.01312428 0.10585057 -0.27876234, 0.012480222 0.10893967 -0.27743572, 0.012010626 0.10337015 -0.27992916, 0.011242054 0.10241424 -0.28009576, 0.0099596009 0.10143391 -0.28054762, 0.012890391 0.10662126 -0.27905381, 0.011764489 0.10940053 -0.2775287, 0.012147002 0.10408818 -0.28037536, 0.011535786 0.10302547 -0.28061879, 5.6557357e-05 0.099713631 -0.28549773, 0.0023032054 0.099438079 -0.28453994, 5.441159e-05 0.099345632 -0.28472447, 0.012480669 0.10734647 -0.27925187, 0.010963105 0.10970245 -0.27752554, 0.010081403 0.1097296 -0.27762365, 0.010364823 0.10188673 -0.28115082, 0.012106203 0.10486349 -0.28073692, 0.011666708 0.10373972 -0.28107274, 0.011917882 0.10798513 -0.27934515, 0.010635696 0.10248408 -0.28170133, 0.0022852942 0.11168451 -0.26155216, 0.0043796226 0.11059145 -0.26222998, 0.011890583 0.10565161 -0.2809931, 0.0023448989 0.11253793 -0.26159096, -5.8509409e-05 0.11262742 -0.26141196, 0.011627607 0.10451601 -0.28143191, 0.0095739886 0.1014974 -0.28192955, 0.0083694085 0.10071681 -0.28198183, 0.0023714826 0.11336017 -0.26182884, 0.011234336 0.10850083 -0.27932858, -5.9194863e-05 0.11345073 -0.26164776, 0.0045578107 0.11141684 -0.2620877, 0.0064305291 0.11016843 -0.26307607, 0.010756396 0.1031922 -0.28216761, 0.01151257 0.10640775 -0.28112936, 0.0023634955 0.11410437 -0.26225251, -5.8867037e-05 0.11419437 -0.26207209, 0.011420541 0.1053103 -0.28167582, 0.00467702 0.11226323 -0.26214045, 0.0098240003 0.10208473 -0.28250039, 0.0023214146 0.11472795 -0.26283789, -5.8032572e-05 0.11481649 -0.2626608, 0.010469131 0.10886399 -0.27920276, 0.0095049664 0.10886704 -0.27934933, 0.0047300681 0.11308237 -0.26238453, 0.0087100193 0.10114039 -0.28264362, 0.010720305 0.10397037 -0.28252327, 0.0022475347 0.11519554 -0.26355153, -5.6125224e-05 0.11528117 -0.26338011, 0.010993414 0.1070888 -0.28113806, 0.0066921338 0.11097676 -0.26296842, 0.011057369 0.10607737 -0.28179026, 0.0047142133 0.11382737 -0.26280648, 0.0099355802 0.10278819 -0.28297585, 0.0021461472 0.11548027 -0.26435274, -5.3472817e-05 0.11556206 -0.264189, 0.0089375302 0.10171843 -0.28323317, 0.0068669245 0.11181157 -0.26304364, 0.010529451 0.10477444 -0.28274763, 0.0074433312 0.11076986 -0.26338226, 0.008285813 0.10959285 -0.26422757, 0.010362916 0.10765588 -0.2810185, 0.0046302602 0.11445593 -0.26338202, 0.010558717 0.10677331 -0.28176916, 0.0020231828 0.11556614 -0.26519591, -5.0611794e-05 0.11564323 -0.26504159, 0.0099021718 0.10356776 -0.28332859, 0.0075378045 0.10074375 -0.28343695, 0.0065248832 0.1001341 -0.28314734, 0.0069448873 0.11262553 -0.26329803, 0.0090391263 0.10241769 -0.28371686, 0.0076377317 0.11159927 -0.2634685, 0.0044829473 0.11493208 -0.26407838, 0.010194592 0.10555861 -0.28282815, 0.0096569583 0.10807679 -0.28077769, 0.0018853769 0.11544801 -0.26603276, 0.0085634515 0.1080712 -0.28094101, 0.0019609258 0.11511477 -0.26685196, -4.7035515e-05 0.11551998 -0.26588887, 0.0099531934 0.10735845 -0.28161347, 0.0086229369 0.11037766 -0.26416671, 0.0069215521 0.11337217 -0.263717, 0.0097258016 0.10437898 -0.28353882, 0.0077346489 0.10131145 -0.28404731, 0.0077245459 0.11241087 -0.26372772, 0.0042808875 0.11522879 -0.2648558, 0.0067904815 0.10053406 -0.28385663, 0.009008728 0.10319851 -0.28406709, 0.0088482425 0.11119694 -0.26427358, 0.0097348616 0.10627786 -0.2827602, 0.0067984387 0.1140089 -0.26427644, 0.0092751309 0.10779964 -0.28133202, 0.0094166324 0.10517559 -0.28359419, 0.0076985583 0.11315817 -0.26414508, 0.0094936118 0.11002386 -0.26487428, 0.009889327 0.10888166 -0.2656498, 0.0078225955 0.10200606 -0.28454024, 0.0040352568 0.11532899 -0.26567, 0.0069678649 0.10109601 -0.28447771, 0.0089488253 0.11200381 -0.26454204, 0.0088482127 0.10401637 -0.28426415, 0.0065822229 0.11449923 -0.26494414, 0.0091765448 0.10689136 -0.28254771, 0.0075614974 0.1137986 -0.2646969, 0.0089920089 0.10591219 -0.28349167, 0.0097415671 0.11083391 -0.26499945, 0.0077963695 0.10278831 -0.28488785, 0.00376039 0.11522714 -0.26647466, 0.0038901791 0.11485692 -0.26736742, 0.0070470199 0.10178838 -0.28497571, 0.010291837 0.10963764 -0.26564699, 0.0089187548 0.1127524 -0.26495665, 0.0052120313 0.10018214 -0.2845602, 0.004482232 0.099703513 -0.28400886, 0.0062853321 0.11481533 -0.26568264, 0.0085669085 0.10482452 -0.28429633, 0.0085514411 0.1073643 -0.28220272, 0.0072927102 0.10737281 -0.28233796, 0.007320933 0.1142957 -0.26535136, 0.0084763095 0.10654672 -0.2832371, 0.0098521933 0.1116369 -0.26527625, 0.0076574311 0.1036135 -0.28507018, 0.010560714 0.11043748 -0.26579255, 0.0070234165 0.10257135 -0.28532171, 0.0087599382 0.11340003 -0.26549381, 0.0053481683 0.10073517 -0.28519982, 0.0059249029 0.11493935 -0.26644963, 0.0069908723 0.11462107 -0.2660715, 0.0098191127 0.11238664 -0.2656883, 0.0081806108 0.10557691 -0.2841621, 0.0078988299 0.10704311 -0.28284502, 0.011178873 0.10911346 -0.26669544, 0.011192434 0.1080569 -0.26729971, 0.0074138567 0.10443441 -0.28507686, 0.010680698 0.11123588 -0.26607817, 0.0084812865 0.11390997 -0.266123, 0.0068982169 0.10340033 -0.28549629, 0.0054088756 0.1014233 -0.28570592, 0.0055212602 0.114864 -0.26720101, 0.0056697652 0.11443601 -0.26820982, 0.0065899417 0.11475608 -0.26681596, 0.0077114329 0.1062307 -0.28386927, 0.0096442327 0.11304098 -0.26621246, 0.0070796236 0.10520443 -0.28490734, 0.006678842 0.10422812 -0.28548938, 0.011470936 0.10989966 -0.26686829, 0.011648081 0.1087792 -0.26736397, 0.010644875 0.11198708 -0.26648766, 0.0053906962 0.10220752 -0.28604943, 0.0080988333 0.11425271 -0.26680839, 0.0026858374 0.099834405 -0.28525615, 0.0061411187 0.11469326 -0.26754248, 0.0071860775 0.10674854 -0.28343415, 0.0057417676 0.10679885 -0.28348625, 0.0093375966 0.11356195 -0.266819, 0.0066736266 0.10587952 -0.28457171, 0.011601351 0.11069181 -0.2671662, 0.0063776895 0.10500733 -0.28530145, 0.011952274 0.10955668 -0.26755422, 0.010455243 0.11264845 -0.26699764, 0.0052947029 0.10304297 -0.28621125, 0.0027560517 0.10037824 -0.28591371, 5.7958066e-05 0.10025422 -0.28616178, 0.0076343641 0.11440892 -0.26751059, 0.0062189624 0.10642121 -0.28408885, 0.0089165792 0.1139205 -0.26747286, 0.01156234 0.11144494 -0.2675721, 0.0060119852 0.10569388 -0.28494316, 0.0051263198 0.10388208 -0.28618157, 0.012088083 0.11034515 -0.26786, 0.012434684 0.10807354 -0.26877588, 0.012155525 0.10714347 -0.26912689, 0.0027874038 0.10106226 -0.28642809, 5.8703125e-05 0.10093684 -0.28667879, 0.010122739 0.11318213 -0.2675789, 0.0056023821 0.10624821 -0.28443509, 0.0039701983 0.10637089 -0.28434181, 0.0071143433 0.11436962 -0.26818985, 0.0072315261 0.11386772 -0.26934624, 0.0048950836 0.104677 -0.28596234, 0.0084051415 0.11409581 -0.26813704, 0.0027779862 0.10184775 -0.28676933, 5.8464706e-05 0.10172278 -0.28701907, 0.011356406 0.11211603 -0.26806277, 0.012047552 0.1110994 -0.2682634, 0.0046143457 0.10538236 -0.28556615, 0.012759589 0.10883249 -0.26900309, 0.0027285144 0.1026896 -0.28691798, 5.7511032e-05 0.10256691 -0.28716344, 0.0096662268 0.11355772 -0.26819855, 0.0078325495 0.1140779 -0.26877356, 0.0043000802 0.10595799 -0.28501558, 0.010995291 0.1126665 -0.26861018, 0.00264173 0.10353992 -0.28686595, 5.5603683e-05 0.10342104 -0.28710347, 0.0025226399 0.10435019 -0.28661597, 0.011832975 0.11177648 -0.26874167, 5.3100288e-05 0.1042368 -0.2868427, 0.012904517 0.10961258 -0.26932526, 0.0023779795 0.10507444 -0.2861824, 0.0091119036 0.1137538 -0.26882106, 5.0090253e-05 0.10496744 -0.28639627, 0.0022158846 0.10567101 -0.28558969, 0.0104995 0.11306537 -0.26918352, 4.6513975e-05 0.10557135 -0.28578901, 0.0020458922 0.10610599 -0.28487188, 0.011456601 0.11233786 -0.26926768, 0.012861155 0.11036935 -0.26972383, 0.013212614 0.10694387 -0.27103525, 0.012749247 0.1061691 -0.27107573, 0.0084912404 0.11375909 -0.26941109, 0.0085153803 0.11317418 -0.27073354, 0.0098972544 0.11328971 -0.2697494, 0.010940097 0.11275149 -0.26981115, 0.0092231855 0.11332672 -0.27027613, 0.010312639 0.11299377 -0.27034128, 0.0096101984 0.11305092 -0.27082753, 0.012955628 0.10516345 -0.27308732, -0.0021608844 0.10703518 -0.26145589, -4.8615038e-05 0.10712674 -0.26127291, -4.8972666e-05 0.10803928 -0.26162231, -0.011411287 0.1022158 -0.27536261, -0.011689164 0.10274651 -0.27430117, -0.01185248 0.10293006 -0.27586228, -0.012141205 0.1034814 -0.27475977, 4.9911439e-05 0.098379441 -0.28303653, -0.002091445 0.099025168 -0.28367341, 5.1788986e-05 0.098945446 -0.28383309, -0.009484686 0.1079906 -0.26573998, -0.0080393329 0.10760093 -0.26459068, -0.0083502308 0.10852363 -0.26467383, -0.0091315582 0.1070878 -0.26561713, -0.01274965 0.10410895 -0.27519655, -0.012280323 0.10393006 -0.27386218, -0.01295609 0.10511463 -0.27318478, -0.0021962598 0.099429555 -0.28455669, -0.0077833906 0.10577 -0.26398665, -0.0078480914 0.10667131 -0.26435846, -0.0089140907 0.1061703 -0.26536065, 4.8719347e-05 0.097669192 -0.28236532, -0.0020135418 0.098456241 -0.28288293, -0.011446573 0.10148837 -0.27255124, -0.011410959 0.10193231 -0.27383757, -0.011047848 0.10055638 -0.27441555, -0.011139609 0.10141424 -0.27487421, -0.002065666 0.096925683 -0.28167784, -0.0019655898 0.097744174 -0.28221536, 4.8242509e-05 0.096842118 -0.28184509, -0.0083698109 0.10956135 -0.26429021, -0.0065391138 0.10914049 -0.26343971, -0.0065252855 0.110144 -0.26312476, -0.011823185 0.10317851 -0.27343702, -0.0041711107 0.099270143 -0.2831834, -0.0043800548 0.099686809 -0.2840423, -0.0062957779 0.10819497 -0.26340234, -0.012337662 0.10443898 -0.27284408, -0.0061459616 0.10725116 -0.26319855, -0.0060951784 0.10634515 -0.2628364, -0.011541553 0.10235409 -0.27299428, -0.0041996315 0.1067717 -0.26198304, -0.0040158406 0.098692082 -0.28241104, -0.0045053735 0.10959818 -0.26252437, -0.0039202645 0.097974487 -0.28175497, -0.0041093305 0.097181506 -0.28116608, -0.011878319 0.10366844 -0.27245671, -0.0044825152 0.1105747 -0.26226324, -0.012289889 0.10494817 -0.27182573, -0.012768544 0.10612092 -0.27117181, -0.0061239377 0.099672846 -0.28237778, -0.0064307824 0.10010976 -0.28319615, -0.0043376163 0.10863558 -0.26252121, -0.011455454 0.10243724 -0.27065301, -0.011595614 0.10283237 -0.27203745, -0.0042344108 0.1076813 -0.2623384, -0.0058960393 0.099079795 -0.28163552, -0.011832304 0.10415856 -0.27147621, -0.0057555214 0.098352976 -0.28099769, -0.002303578 0.1108401 -0.26173222, -0.0023182407 0.10988095 -0.26195884, -5.2072108e-05 0.10997916 -0.26176232, -0.0060128346 0.097600989 -0.28032708, -0.002231963 0.10890781 -0.26197666, -5.0164759e-05 0.10900225 -0.26178753, -0.0078907683 0.10022121 -0.28128111, -0.0082862154 0.1006854 -0.28204447, -0.012159355 0.10539734 -0.27092713, -0.011550583 0.10331083 -0.27108032, -0.0021787658 0.1079469 -0.26180685, -0.011706568 0.10459111 -0.27061129, -0.0075970367 0.099607654 -0.28057957, -0.007711865 0.098169588 -0.27918959, -0.0074161962 0.098868184 -0.27996683, -0.011880912 0.10594959 -0.26982248, -0.012193181 0.10709747 -0.26921844, -0.011427857 0.10373307 -0.2702359, -0.0094178692 0.10089829 -0.27992654, -0.0098897889 0.10139643 -0.28062218, -0.011074401 0.10337093 -0.26878566, -0.011438675 0.10512284 -0.26954752, -0.0098144785 0.10111903 -0.27948505, -0.011192866 0.10222126 -0.27897257, -0.011611439 0.10632724 -0.26906711, -0.009067215 0.10025956 -0.27927566, -0.011166312 0.10425206 -0.26919746, -0.009449102 0.10047211 -0.27885044, -0.011179186 0.10548631 -0.26882029, -0.0088513568 0.099504642 -0.27869391, -0.0091480985 0.098868169 -0.27779233, -0.010658868 0.10168364 -0.27835548, -0.011067398 0.10690057 -0.26792043, -0.011247523 0.10801462 -0.26738417, -0.0092241541 0.099712066 -0.27827883, -0.010316111 0.1042571 -0.26701277, -0.010913022 0.10460714 -0.26848757, -0.011021145 0.10198238 -0.27775806, -0.012156017 0.10313464 -0.27714539, -0.010710694 0.10720047 -0.26732028, -0.01026199 0.10101571 -0.27776289, -0.010655411 0.10603825 -0.26771653, -0.010311998 0.10632715 -0.2671386, -0.010610767 0.10130321 -0.27718788, -0.010272957 0.099672936 -0.27618259, -0.01001773 0.10024291 -0.27721733, -0.010401763 0.10514579 -0.26740998, -0.011575885 0.1025536 -0.27661556, -0.0098769739 0.10776829 -0.26618451, -0.0099599734 0.10884415 -0.2657246, -0.010358252 0.10052349 -0.27665597, -0.0092065409 0.10506604 -0.26539475, -0.010066517 0.10542773 -0.26684576, -0.011144944 0.10185312 -0.27608782, -0.0095093325 0.10687388 -0.26604509, -0.010879673 0.10106032 -0.27558202, -0.009282954 0.10596142 -0.26577836, 0.0020654127 0.10704317 -0.2614401, -4.8555434e-05 0.10233133 -0.25887561, 0.0020653531 0.1022478 -0.25904268, 0.0041089579 0.10678742 -0.2619518, 0.0041088983 0.10199206 -0.25955445, 0.0060124621 0.10636807 -0.26279086, 0.0060124919 0.10157264 -0.26039338, 0.0077114031 0.10579941 -0.26392829, 0.0077115223 0.10100394 -0.26153094, 0.0091476962 0.10510073 -0.26532573, 0.0091476962 0.10030543 -0.26292819, 0.010272555 0.10429598 -0.26693517, 0.010272585 0.099500544 -0.26453805, 0.011047445 0.10341267 -0.26870239, 0.011047445 0.098617323 -0.26630503, 0.01144626 0.1024806 -0.27056676, 0.011446111 0.097685255 -0.2681694, 0.011455141 0.10153163 -0.27246499, 0.011455111 0.0967362 -0.27006769, 0.011073969 0.10059816 -0.2743324, 0.01107391 0.095802777 -0.27193487, 0.010315709 0.099711649 -0.27610511, 0.010315709 0.094916336 -0.27370781, 0.0092061386 0.098902814 -0.27772307, 0.0092061386 0.094107501 -0.27532578, 0.0077831075 0.098198764 -0.27913135, 0.0077830777 0.093403511 -0.27673399, 0.0060948953 0.097623669 -0.28028166, 0.0060949251 0.092828505 -0.27788436, 0.0041991994 0.097197168 -0.28113478, 0.0041992292 0.092401855 -0.27873743, 0.0021606311 0.096933685 -0.28166199, 0.0021605417 0.092138238 -0.27926457, 4.8242509e-05 0.09204679 -0.27944779, -0.0091481879 0.094072856 -0.27539504, -0.0020655468 0.092130356 -0.27928054, -0.0041995719 0.10197636 -0.2595858, -0.007783331 0.10097472 -0.26158923, -0.0092064515 0.10027071 -0.26299739, -0.0060952082 0.10154978 -0.26043898, -0.011446483 0.096693046 -0.27015382, -0.011074223 0.098575495 -0.26638836, -0.011455454 0.097641982 -0.26825577, -0.0021608546 0.10223985 -0.25905871, -0.011047818 0.095760934 -0.27201813, -0.010272928 0.094877504 -0.27378529, -0.0060128048 0.092805557 -0.27792972, -0.0077117756 0.093374304 -0.27679229, -0.010315992 0.099461757 -0.26461554, -0.0041091517 0.092386179 -0.27876866, 0.0083499774 0.10040102 -0.28092152, 0.011411004 0.10516597 -0.26946157, 0.01168894 0.10463522 -0.27052313, 0.011852078 0.10599447 -0.26973313, 0.012140922 0.10544322 -0.27083576, 0.0094842538 0.10093395 -0.27985555, 0.0080390796 0.099780641 -0.2802335, 0.0020909533 0.10989947 -0.26192206, 0.0091311559 0.10029384 -0.27920699, 0.012279831 0.10499457 -0.2717334, 0.0020132288 0.1089255 -0.26194125, 0.0078476295 0.099037267 -0.27962899, 0.0089138374 0.09953817 -0.27862704, 0.011410616 0.10377613 -0.27014989, 0.011139147 0.10429425 -0.26911354, 0.0019652769 0.1079643 -0.26177233, 0.0065388605 0.099784009 -0.28215563, 0.011822753 0.10420323 -0.27138728, 0.0041706786 0.10965437 -0.26241201, 0.0062953159 0.099186771 -0.2814216, 0.01233729 0.10448564 -0.27275127, 0.0061455593 0.098457299 -0.2807889, 0.0040154383 0.1086897 -0.26241314, 0.0115413 0.10335449 -0.27099341, 0.0039197132 0.10773414 -0.2622329, 0.0045049712 0.099326424 -0.28307104, 0.011878006 0.10371327 -0.2723673, 0.012289487 0.10397635 -0.27376968, 0.0061235055 0.10925166 -0.26321769, 0.0043373927 0.098746143 -0.28230286, 0.011595182 0.10287622 -0.27195019, 0.0042340085 0.098027281 -0.28164917, 0.0058956072 0.10830196 -0.26318866, 0.0023178384 0.099043719 -0.28363651, 0.011831932 0.10322315 -0.2733478, 0.0057552084 0.10735557 -0.26298994, 0.0078904852 0.1087035 -0.26431447, 0.0022315606 0.098473869 -0.2828474, 0.012158863 0.10352734 -0.27466828, 0.0115503 0.10239763 -0.27290732, 0.0021784529 0.097761534 -0.28218067, 0.011706196 0.10279062 -0.27421296, 0.0075966343 0.10777415 -0.2642445, 0.007415764 0.10684023 -0.26402068, 0.01188051 0.10297493 -0.27577305, 0.011427484 0.10197548 -0.27375185, 0.0094174072 0.10802626 -0.26566881, 0.011438273 0.10225887 -0.27527666, 0.0098139867 0.10780556 -0.26611042, 0.011611037 0.10259736 -0.27652848, 0.0090668127 0.10712218 -0.26554853, 0.011165939 0.10145629 -0.27479005, 0.0094486102 0.10690964 -0.26597369, 0.0088510439 0.10620389 -0.26529372, 0.011178784 0.10189534 -0.27600384, 0.011067025 0.10202409 -0.27767491, 0.010658406 0.10724091 -0.26723987, 0.0092236921 0.10599636 -0.26570874, 0.01091259 0.10110144 -0.2755, 0.011020713 0.10694223 -0.26783735, 0.010710321 0.10172399 -0.27827501, 0.010261528 0.10636603 -0.26706117, 0.010654978 0.10134339 -0.27710772, 0.010311686 0.10105454 -0.27768564, 0.010610335 0.10607848 -0.2676363, 0.010017239 0.10546566 -0.26677024, 0.010401331 0.10056271 -0.27657771, 0.011575542 0.10637105 -0.26897979, 0.0098766312 0.10115626 -0.27941096, 0.010357641 0.10518504 -0.26733178, 0.010066114 0.10028077 -0.27714175, 0.011144452 0.1055286 -0.2687363, 0.0095089301 0.10050782 -0.27877903, 0.010879211 0.10464824 -0.26840562, 0.0092824921 0.099747054 -0.27820909, -0.010259725 0.10862263 -0.27968526, -0.010313131 0.10761697 -0.28109634, -0.011009581 0.10824179 -0.27984643, -0.012995996 0.10816967 -0.27760482, -0.012632616 0.10632394 -0.27964807, -0.013422824 0.1074714 -0.27735275, -0.01223094 0.10705873 -0.2798273, -0.013992555 0.10716736 -0.27421594, -0.013558276 0.10520814 -0.27625215, -0.013835408 0.10641477 -0.273839, -0.013712175 0.10594722 -0.27665657, -0.013288237 0.10676452 -0.27139354, -0.013483293 0.10571725 -0.27348858, -0.012410082 0.10877132 -0.27777237, -0.011679389 0.10771031 -0.27989441, -0.013945557 0.10793228 -0.27459818, -0.01366622 0.10671621 -0.27703059, -0.013635315 0.10748941 -0.2716893, -0.011698313 0.10924178 -0.27784598, -0.013697274 0.1086658 -0.27496356, -0.013790227 0.10825428 -0.2720418, -0.010901578 0.10955467 -0.27782124, -0.013261713 0.1093261 -0.27529168, -0.012689598 0.10778081 -0.26936072, -0.013743855 0.10901555 -0.27243125, -0.012663879 0.10987566 -0.2755636, -0.01302097 0.10853215 -0.26960325, -0.013499238 0.10972983 -0.27283543, -0.011937536 0.11028289 -0.27576375, -0.013168879 0.10930891 -0.26993227, -0.013069965 0.11035628 -0.27323121, -0.01112435 0.11052456 -0.27588081, -0.011705197 0.10873515 -0.26745176, -0.013124712 0.11006664 -0.2703287, -0.012480594 0.11085922 -0.27359611, -0.012011029 0.10951147 -0.26764452, -0.011242546 0.10907111 -0.26677984, -0.012890972 0.11076222 -0.27077043, -0.011764802 0.11120998 -0.27390903, -0.012147404 0.11029939 -0.26795107, -0.011536159 0.10985617 -0.26695502, -0.012480982 0.11135577 -0.27123165, -0.010963477 0.11138866 -0.27415234, -0.010365255 0.10959851 -0.26572472, -0.012106664 0.11105377 -0.26835448, -0.011667199 0.11064798 -0.26725388, -0.011918254 0.1118137 -0.27168667, -0.0022856668 0.099800773 -0.28532338, -0.010636128 0.1103975 -0.26587236, -0.011891015 0.11173176 -0.26883107, -0.0023453608 0.10034368 -0.28598285, -0.011628158 0.11140116 -0.26765943, -0.0095743313 0.10998786 -0.26494604, -0.0023719743 0.10102744 -0.28649777, -0.011234827 0.11210983 -0.27210921, -0.0045583323 0.10006849 -0.28478777, -0.0023640171 0.10181294 -0.28683877, -0.010756828 0.11119536 -0.26615888, -0.011512883 0.11229455 -0.26935428, -0.0046775118 0.1006184 -0.28543335, -0.011420973 0.11207301 -0.26814848, -0.0023219064 0.10265536 -0.28698635, -0.0098243728 0.11079692 -0.26507324, -0.010469563 0.11222721 -0.27247518, -0.0047305301 0.10130519 -0.28594202, -0.008710511 0.11034498 -0.26423204, -0.010720827 0.11194686 -0.26656801, -0.0022479966 0.10350687 -0.28693205, -0.0066925362 0.10050862 -0.28390723, -0.010993876 0.1127101 -0.26989377, -0.0047146454 0.10208983 -0.28628486, -0.011057742 0.11262488 -0.26869327, -0.0099358335 0.1115993 -0.2653507, -0.0021466985 0.10431866 -0.28667903, -0.0089378729 0.11116325 -0.26434058, -0.0068673864 0.10106996 -0.28452998, -0.010529913 0.11260883 -0.26707661, -0.0074437335 0.10071544 -0.28349346, -0.0046307221 0.10292738 -0.28644234, -0.010363348 0.11295482 -0.27041894, -0.010559209 0.11302561 -0.26926273, -0.0020236745 0.10504464 -0.28624183, -0.0099026337 0.1123494 -0.26576263, -0.0075382069 0.11074152 -0.26343858, -0.0069453195 0.101762 -0.28502828, -0.0090394691 0.11196991 -0.26460975, -0.0076381341 0.10128231 -0.28410524, -0.010195054 0.11314365 -0.26765543, -0.0044834092 0.1037702 -0.28640521, -0.0018857494 0.10564321 -0.28564501, -0.0096574202 0.11301457 -0.27090025, -0.0099535957 0.1132521 -0.26982421, -0.0086233988 0.10110769 -0.28270888, -0.0069219843 0.10254506 -0.28537422, -0.0097263232 0.11300432 -0.2662856, -0.007724978 0.10197667 -0.28459889, -0.0077350214 0.11157026 -0.26352632, -0.0042814389 0.10457013 -0.28617603, -0.006790854 0.11095131 -0.26301903, -0.0090091303 0.1127186 -0.26502407, -0.008848764 0.10168485 -0.2833001, -0.0097354427 0.11352114 -0.26827163, -0.0067988113 0.10337455 -0.28554797, -0.0092755929 0.11329173 -0.27034587, -0.0094170347 0.11352663 -0.26688951, -0.00769905 0.1027591 -0.2849462, -0.0094938949 0.10146146 -0.28200138, -0.0078228787 0.11238148 -0.2637862, -0.0040358081 0.10528163 -0.28576756, -0.0069682673 0.11178555 -0.26309574, -0.0089492276 0.1023838 -0.28378463, -0.0088487342 0.11336704 -0.26556003, -0.0091770366 0.11371932 -0.26889002, -0.0065825656 0.10420311 -0.28553951, -0.0075618699 0.10358468 -0.28512746, -0.0089923814 0.11388669 -0.26754034, -0.0097419396 0.10204784 -0.28257406, -0.007796742 0.11312901 -0.26420343, -0.0037609115 0.1058641 -0.28520322, -0.010292329 0.10184775 -0.28122866, -0.0070474222 0.11259916 -0.26335084, -0.0089191571 0.10316471 -0.28413475, -0.0052123144 0.11130319 -0.26231533, -0.0062858835 0.10498349 -0.28534913, -0.0085672811 0.1138778 -0.26618731, -0.0085520223 0.11372695 -0.26947534, -0.0073214844 0.10440663 -0.28513217, -0.0098526254 0.10275093 -0.2830503, -0.0084768012 0.11406394 -0.26820058, -0.010561176 0.10244419 -0.2817812, -0.0076578632 0.11376996 -0.26475412, -0.007023789 0.11334591 -0.26376957, -0.0087603107 0.1039832 -0.28433043, -0.0053485408 0.11214652 -0.26237381, -0.0059253946 0.10567125 -0.28498805, -0.0069913939 0.1051778 -0.28496039, -0.0081810728 0.11422201 -0.26686972, -0.0098194852 0.10353056 -0.28340292, -0.0078993812 0.11404819 -0.26883286, -0.011179395 0.10237192 -0.28018016, -0.0074144378 0.11426789 -0.26540685, -0.0106811 0.10315169 -0.28224844, -0.0068986788 0.11398303 -0.26432782, -0.0084817484 0.10479239 -0.28436053, -0.0055217221 0.10622721 -0.28447694, -0.005409278 0.11296425 -0.26262063, -0.0065905228 0.10585441 -0.2846216, -0.0077119544 0.11437996 -0.26756841, -0.0096448138 0.10434244 -0.2836116, -0.0070800558 0.11459453 -0.26612443, -0.011471339 0.10298204 -0.28070539, -0.0066793934 0.11447424 -0.26499414, -0.0053911284 0.11370965 -0.26304173, -0.011648424 0.10270596 -0.27951169, -0.010645218 0.10393006 -0.28260356, -0.0080993548 0.10554636 -0.28422338, -0.0026862696 0.11165094 -0.26161951, -0.0061415806 0.10639787 -0.28413546, -0.0071866289 0.11434282 -0.26824367, -0.0093380287 0.10514025 -0.28366458, -0.0066741183 0.11473117 -0.26686597, -0.011601694 0.10369565 -0.28116035, -0.0063782409 0.11479149 -0.26573038, -0.0052951351 0.11434037 -0.26361305, -0.011952706 0.10332488 -0.28001946, -0.010455705 0.10473489 -0.2828266, -0.0027563646 0.11250351 -0.2616598, -0.0076349452 0.10620182 -0.2839269, -0.0089170709 0.10587842 -0.28355896, -0.0062193945 0.11466984 -0.26758909, -0.011562802 0.10447223 -0.28151906, -0.0060124472 0.1149169 -0.26649439, -0.005126752 0.11482025 -0.26430207, -0.012088545 0.10404251 -0.28046656, -0.012435116 0.10341194 -0.27809978, -0.0027878359 0.11332535 -0.26189846, -0.010123231 0.10552024 -0.28290468, -0.0071148351 0.10672157 -0.28348809, -0.0056029037 0.11484297 -0.26724297, -0.0084056929 0.10651503 -0.28330076, -0.0048956051 0.11512203 -0.26506948, -0.0027784482 0.11406962 -0.26232207, -0.011356987 0.10526741 -0.28176129, -0.012048014 0.10481784 -0.28082776, -0.0046148971 0.11522838 -0.26587147, -0.012760051 0.1040492 -0.27857053, -0.0027289763 0.11469375 -0.26290601, -0.0096667781 0.10624122 -0.28283328, -0.0078331307 0.1070135 -0.28290445, -0.004300572 0.11513325 -0.2666623, -0.0026421621 0.11516237 -0.26361769, -0.010995753 0.10603569 -0.28187329, -0.011833437 0.10560694 -0.28108239, -0.0025231615 0.11544868 -0.26441592, -0.012904949 0.10477502 -0.27900147, -0.0091123655 0.10685698 -0.2826165, -0.0023784414 0.11553629 -0.26525539, -0.0022164062 0.11542023 -0.26608831, -0.010499962 0.10673354 -0.28184849, -0.011457182 0.1063645 -0.28121591, -0.012861617 0.10554791 -0.27936757, -0.013213165 0.10454147 -0.27584028, -0.0084917322 0.10733212 -0.2822668, -0.0098978356 0.107321 -0.28168815, -0.010940559 0.10704746 -0.28122067, -0.0092236772 0.10776461 -0.28140157, -0.0096106306 0.1080403 -0.28085017, 0.0085128173 0.11046063 -0.27615976, 0.010042243 0.10973226 -0.2776165, 0.0082629547 0.10967886 -0.27772355, 0.0041173026 0.10704168 -0.28299844, 0.0039546415 0.10638682 -0.28430849, 0.002263777 0.10693351 -0.28321511, -0.0076251999 0.11230481 -0.27247053, -0.0082448795 0.11156525 -0.27395004, -0.00059676915 0.11440603 -0.26826775, 0.0039086863 0.1072211 -0.28263962, -0.0071033016 0.11219121 -0.27269775, -0.0075500682 0.11076555 -0.27554977, -0.0076822415 0.11150139 -0.27407753, 0.010230355 0.11062514 -0.27583051, 0.0083968863 0.11124872 -0.27458334, -0.0059273317 0.1078695 -0.28134257, 0.0034654662 0.10760234 -0.28187692, -0.0027611628 0.10727753 -0.28252673, -0.0042381659 0.10760415 -0.28187352, 0.0040839538 0.11344977 -0.27018046, 0.0079322979 0.11046559 -0.27614963, -0.0011652187 0.10709447 -0.28289306, 0.00048091263 0.10706253 -0.28295672, 0.0021063313 0.10718318 -0.28271532, 0.0036410019 0.10745136 -0.282179, 0.0078262314 0.11120092 -0.27467889, 0.0073831007 0.11191051 -0.27325946, -0.0070616975 0.10847475 -0.28013182, -0.002164878 0.11402128 -0.26903731, -0.00054151565 0.11414755 -0.26878482, -0.0036948398 0.11374793 -0.26958406, 0.0057193562 0.10681292 -0.28345621, 0.0029032752 0.11405296 -0.26897413, -0.0045381859 0.10738175 -0.28231794, -0.006677933 0.11297142 -0.2711373, 0.0066217706 0.11256392 -0.27195239, -0.0065887049 0.10862546 -0.27983028, -0.0062184706 0.11281278 -0.27145463, 0.0055751726 0.11313299 -0.27081418, 0.004288666 0.11359326 -0.26989371, -0.0029539838 0.10703262 -0.28301644, 0.0052238628 0.10775796 -0.28156555, 0.0072642788 0.10738466 -0.28231239, 0.0019533858 0.11509652 -0.26688653, -0.0050657466 0.11333924 -0.27040178, 0.010025375 0.11151726 -0.27404606, 0.0079201087 0.11200919 -0.27306229, -0.0054436401 0.11353625 -0.27000743, -0.0012427047 0.1068371 -0.28340769, 0.0085301921 0.10808036 -0.28092092, 0.0048437938 0.11398249 -0.26911479, 0.005980216 0.11331905 -0.27044225, 0.0046006963 0.11381205 -0.26945591, -0.0081277862 0.11000668 -0.27706742, 0.0038749203 0.11483975 -0.26740009, 0.00943508 0.11237442 -0.27233171, 0.0071026906 0.11270922 -0.27166176, 0.0071296021 0.10904481 -0.27899188, -0.0089617446 0.11079334 -0.27549386, 0.0056477115 0.11442038 -0.26823908, 0.0084822401 0.11316358 -0.27075332, -0.0039753988 0.1139752 -0.2691294, 0.0076578781 0.10893688 -0.27920765, 0.0072034523 0.11385436 -0.26937133, 0.00052171201 0.10680362 -0.2834748, 0.0020380244 0.1061228 -0.28483635, 0.0094680712 0.10887306 -0.27933526, 0.0076967999 0.10973642 -0.27760828, -0.0023363605 0.11426934 -0.26854104, -0.0055326298 0.10805994 -0.28096157, -0.0085101202 0.11078455 -0.27551168, -0.0079301372 0.11077296 -0.27553463, 0.0039649531 0.10637601 -0.28433073, 0.0057268366 0.10680801 -0.28346616, 0.0057341978 0.10680334 -0.28347617, 0.0039598271 0.10638127 -0.28431952, 0.0072831735 0.10737663 -0.28232938, 0.007273756 0.10738055 -0.28232086, 0.0085523352 0.10807405 -0.28093433, 0.0085411593 0.10807716 -0.28092742, 0.0094927773 0.10886886 -0.2793445, 0.0094803795 0.10887084 -0.27933991, 0.01006832 0.10973034 -0.27762115, 0.010055356 0.10973118 -0.27761889, 0.010257058 0.11062548 -0.27583075, 0.010243706 0.11062526 -0.27583051, 0.010051541 0.11151993 -0.27404141, 0.010038428 0.11151849 -0.27404374, 0.0094597563 0.11237929 -0.2723226, 0.0094473287 0.11237677 -0.27232713, 0.0085043535 0.11317056 -0.27074009, 0.0084931478 0.11316698 -0.27074659, 0.0072220787 0.1138631 -0.26935458, 0.0072128102 0.11385871 -0.26936287, 0.005662404 0.11443067 -0.26821929, 0.0056551024 0.11442538 -0.26822931, 0.0038850829 0.11485108 -0.26737827, 0.0038801059 0.11484528 -0.26738924, 0.001958482 0.11510847 -0.26686341, 0.0019558892 0.11510236 -0.26687503, 0.0020432398 0.10611144 -0.28485996, 0.0020405576 0.10611711 -0.28484821, -0.00851015 0.11069512 -0.27546704, -0.0082447603 0.11147585 -0.27390516, -0.0076251999 0.11221541 -0.27242595, -0.0066780522 0.11288198 -0.27109253, -0.0054436401 0.11344684 -0.26996261, -0.0039754584 0.11388577 -0.26908475, -0.0023363307 0.11417998 -0.26849633, -0.00059685856 0.11431653 -0.26822305, -0.0089617744 0.11070397 -0.27544898, -0.0081277862 0.10991728 -0.2770226, -0.0075500682 0.11067615 -0.27550495, -0.007930167 0.11068358 -0.27548993, -0.0076822117 0.11141195 -0.27403301, -0.0071033612 0.11210176 -0.27265328, -0.0062184706 0.11272325 -0.27140999, -0.0050657168 0.11324979 -0.27035695, -0.0036948994 0.1136585 -0.26953942, -0.0021649376 0.11393186 -0.26899242, -0.00054157525 0.11405813 -0.26874012, 0.0046006665 0.1137226 -0.26941109, 0.0059802756 0.11322948 -0.27039737, 0.00710278 0.11261975 -0.27161717, 0.0079200491 0.11191972 -0.27301747, 0.0083968565 0.11115927 -0.27453876, 0.0085128173 0.11037124 -0.27611494, 0.008262895 0.10958941 -0.27767885, 0.0076578185 0.10884748 -0.27916306, 0.0048438236 0.11389307 -0.26907015, 0.0029032156 0.11396337 -0.26892948, 0.004083924 0.11336029 -0.27013582, 0.0042885765 0.11350376 -0.26984876, 0.0055752024 0.11304351 -0.27076954, 0.0066217408 0.11247452 -0.27190775, 0.0073830411 0.11182102 -0.27321482, 0.0078262314 0.1111115 -0.2746343, 0.0079322979 0.11037619 -0.27610493, 0.0076966509 0.109647 -0.27756345, 0.0071296021 0.10895526 -0.27894711, 0.0039086565 0.10713155 -0.28259498, 0.0022639558 0.10684393 -0.28317034, 0.00052177161 0.10671409 -0.28343004, -0.0012428537 0.10674769 -0.28336287, -0.0029538944 0.1069432 -0.28297174, -0.0045381859 0.10729235 -0.28227335, -0.0059273317 0.10778003 -0.28129774, -0.0070617571 0.10838535 -0.28008717, 0.0041172728 0.10695226 -0.2829538, 0.0052239224 0.10766862 -0.28152096, 0.0034654662 0.10751293 -0.28183222, 0.0036409423 0.10736189 -0.28213429, 0.0021062419 0.10709379 -0.28267062, 0.00048091263 0.10697312 -0.28291214, -0.0011651888 0.10700499 -0.28284836, -0.002761133 0.10718805 -0.28248191, -0.0042382255 0.1075147 -0.28182876, -0.0055326298 0.10797053 -0.28091687, -0.0065888241 0.10853594 -0.27978569, -0.0025914386 0.10614195 0.28474671, -0.0044809803 0.10644802 0.28413504, -0.002594851 0.10613634 0.28475839, -0.0044693425 0.10645833 0.28411341, -0.0044751838 0.10645305 0.28412414, -0.002588056 0.10614755 0.28473514, -0.0044868216 0.10644301 0.28414589, -0.0061949715 0.10691824 0.28319466, -0.0062029585 0.10691395 0.28320432, -0.0061788931 0.10692736 0.28317565, -0.0061869249 0.10692268 0.28318512, -0.0006089434 0.10599526 0.28504068, -0.0025980696 0.10613092 0.28477007, -0.00060974807 0.10598975 0.28505272, -0.0076709017 0.10752892 0.28197324, -0.0076808557 0.1075254 0.28198135, -0.00060742348 0.10600685 0.2850166, -0.00060810894 0.10600092 0.28502864, -0.0076608881 0.10753273 0.28196532, -0.0076508448 0.10753652 0.28195733, -0.0088520721 0.10825687 0.28051782, -0.0088634863 0.10825428 0.28052402, -0.0088405833 0.10825961 0.2805118, -0.0088290349 0.10826262 0.28050554, -0.0096930936 0.10907375 0.27888429, -0.0097055659 0.10907211 0.27888834, -0.0096804574 0.10907542 0.27888012, -0.0096677765 0.10907727 0.27887625, -0.010161407 0.10994833 0.27713531, -0.01017458 0.10994785 0.27713686, -0.010134973 0.10994961 0.2771318, -0.010148324 0.1099489 0.27713346, -0.01023943 0.11084699 0.27533823, -0.010252841 0.11084776 0.27533782, -0.010212846 0.11084604 0.27533937, -0.010226168 0.1108463 0.27533877, -0.009924002 0.11173525 0.27356184, -0.0099369362 0.11173709 0.27355909, -0.009898223 0.11173182 0.27356797, -0.0099110678 0.11173343 0.2735647, -0.0092271939 0.11257892 0.27187485, -0.009239085 0.11258199 0.2718699, -0.0092031881 0.11257338 0.27188528, -0.0092151836 0.11257609 0.27188003, -0.0081757084 0.1133455 0.27034193, -0.008186318 0.11334943 0.27033502, -0.0081543997 0.11333802 0.2703563, -0.0081650242 0.11334153 0.27034914, -0.0068100616 0.11400571 0.26902187, -0.006818898 0.11401051 0.26901323, -0.0067923144 0.11399638 0.26903939, -0.0068012998 0.11400088 0.26903057, -0.0051826462 0.1145338 0.26796544, -0.0051895007 0.11453935 0.2679553, -0.0051692352 0.11452325 0.26798588, -0.0051760003 0.11452841 0.26797563, -0.0033562705 0.11491 0.26721328, -0.0033606514 0.11491611 0.26720214, -0.003347598 0.11489847 0.26723558, -0.0033518299 0.11490419 0.26722431, -0.0014026687 0.11512589 0.2667827, -0.0014009103 0.11511948 0.26679426, 0.00060839206 0.11515456 0.26672465, 0.00060913712 0.1151609 0.2667129, -0.0013990477 0.1151134 0.26680607, 0.0006076321 0.11514839 0.26673639, -0.0013972595 0.11510741 0.26681769, 0.00060687214 0.11514231 0.26674831, 0.012830116 0.10781952 0.2782554, 0.012320943 0.10598441 0.28027683, 0.01325155 0.10711085 0.27802414, 0.011929192 0.10672887 0.28043646, 0.013967626 0.10679131 0.27491891, 0.013537176 0.10557973 0.27734172, 0.013385199 0.10484462 0.2769298, 0.0014884844 0.099351756 0.28465956, -0.00080030411 0.099691771 0.28548855, -0.00076907128 0.099323653 0.28471631, 0.013810702 0.10604259 0.27453387, 0.013393633 0.10640465 0.27206481, 0.012869783 0.10577395 0.27181721, 0.012415878 0.10676336 0.26983857, 0.013459198 0.10535377 0.27416611, 0.012251578 0.10843547 0.2783941, 0.01139123 0.10739403 0.28047699, 0.013920628 0.10755738 0.27529889, 0.013491757 0.1063497 0.27771366, 0.013743408 0.10712083 0.27237785, 0.011548974 0.10892349 0.27843273, 0.010737903 0.10794183 0.28039593, 0.01367294 0.10829692 0.27565193, 0.013899527 0.10788187 0.27273816, 0.010762192 0.1092559 0.27836907, 0.0099363104 0.10941335 0.27820629, 0.010006554 0.10834088 0.28019845, 0.013237946 0.10896801 0.27595884, 0.012921058 0.10743424 0.27000576, 0.011584602 0.10770258 0.26796067, 0.013852827 0.1086443 0.27312553, 0.01264105 0.10953217 0.27620125, 0.013258763 0.10817742 0.27026486, 0.013606183 0.10936438 0.27351761, 0.011916108 0.1099573 0.27636594, 0.013409279 0.10895046 0.27060127, 0.013173543 0.11000147 0.27389205, 0.011104368 0.11021911 0.27644265, 0.01025226 0.1103028 0.27642787, 0.012056105 0.10841166 0.26805127, 0.013364203 0.10970923 0.27099574, 0.012579598 0.11051892 0.2742278, 0.012370937 0.10918038 0.26825947, 0.011635341 0.10875856 0.26735777, 0.010401182 0.10856285 0.26624024, 0.013126142 0.11041041 0.27142549, 0.011858083 0.11088764 0.27450538, 0.012511365 0.10996484 0.26857293, 0.01193928 0.10953628 0.26754749, 0.00079988688 0.11173131 0.26141244, 0.0030026063 0.11074498 0.26187664, 0.00076862425 0.11089244 0.26158124, 0.012708746 0.11101433 0.27186674, 0.011050321 0.111086 0.27470899, 0.010174133 0.11120259 0.27462822, 0.010824569 0.10930695 0.26626098, 0.012469403 0.11072015 0.26897418, 0.01207491 0.11032476 0.26785314, 0.012135901 0.1114861 0.27229375, 0.011107318 0.11009904 0.26642215, 0.012247317 0.11140334 0.26944005, 0.0015490726 0.099721096 0.28543013, 0.0037006959 0.099554799 0.28425378, 0.012034379 0.111079 0.26825666, 0.0015894845 0.10026278 0.2860921, -0.00082116574 0.10023256 0.28615218, 0.010082729 0.10971519 0.26544428, 0.0089018866 0.10931828 0.26472962, 0.011439748 0.1117992 0.27268225, 0.0016074553 0.10094576 0.28660828, -0.00083052367 0.10091528 0.28666914, 0.0038513318 0.099932455 0.28500748, 0.0058005527 0.099926613 0.28351015, 0.011233442 0.11089393 0.26671493, 0.011857934 0.11197557 0.26994431, 0.0016021207 0.10173138 0.28694904, -0.00082775205 0.10170101 0.28700966, 0.011820011 0.11175596 0.26873553, 0.0039519742 0.10047965 0.28565866, 0.010346256 0.11051794 0.26558447, 0.0015735701 0.10257467 0.28709489, -0.00081308931 0.10254496 0.2871545, 0.010660507 0.11193561 0.27301013, 0.0097050443 0.11207842 0.27287722, 0.0092641786 0.11009311 0.26468885, 0.0039967373 0.10116502 0.28616959, 0.011195786 0.11164614 0.26712233, 0.001523681 0.10342767 0.28703767, -0.00078713149 0.10339879 0.28709513, 0.011323132 0.11240422 0.27045804, 0.0060365722 0.10031932 0.28423369, 0.011444055 0.11231681 0.26926219, 0.0039834455 0.10194995 0.28651184, 0.010463588 0.1113176 0.26586759, 0.0014548078 0.1042416 0.28678054, 0.0095061436 0.11090579 0.26480925, -0.00075178593 0.10421406 0.28683549, 0.006194286 0.10087656 0.28486478, 0.010996304 0.11231299 0.2676214, 0.0068121478 0.10050743 0.28385746, 0.0077241138 0.10045581 0.28245181, 0.010673799 0.11266454 0.27095181, 0.010928147 0.11272987 0.2698065, 0.0039124712 0.10278948 0.28666556, 0.0013714954 0.10497006 0.28633827, -0.00070860237 0.10494419 0.28639024, 0.010428526 0.11206838 0.26627767, 0.0081425533 0.11051821 0.26383889, 0.0071320161 0.10994568 0.26347488, 0.0062646642 0.10156669 0.28536642, 0.0096142069 0.11170968 0.26508343, 0.0069901273 0.10106962 0.28447843, 0.010646813 0.11285623 0.26818335, 0.0037880614 0.10363557 0.28662205, 0.0099468008 0.11274203 0.27139747, 0.008863084 0.11289629 0.27124143, 0.0012780502 0.10557174 0.28573579, 0.0014021024 0.10602462 0.28498274, 0.010301419 0.11297166 0.27033752, -0.00066044182 0.10554763 0.28578442, 0.0080383345 0.10087015 0.2831322, 0.010242768 0.11272766 0.2667917, 0.0062436536 0.10235014 0.28571159, 0.0083553568 0.11134201 0.26393682, 0.0070695803 0.10176193 0.2849763, 0.00742241 0.11074605 0.26338309, 0.0036171749 0.10444012 0.28638357, 0.0095817819 0.11245921 0.26549667, 0.010166757 0.11324509 0.26877642, 0.0082483664 0.1014417 0.28373438, 0.0095996633 0.11302813 0.27082527, 0.0061324611 0.10318264 0.28587955, 0.0099171624 0.11325776 0.26738036, 0.0070458427 0.10254487 0.28532237, 0.0089512542 0.10120185 0.28246886, 0.0094129071 0.10112648 0.28111088, 0.0084502026 0.11215081 0.26420152, 0.0034097508 0.1051574 0.28596395, 0.0076162294 0.1115758 0.26346934, 0.0083420947 0.10213836 0.28422362, 0.0094112083 0.11311158 0.26602447, 0.0095835254 0.11345717 0.2693668, 0.0059373453 0.10401633 0.28586096, 0.0094699487 0.11362844 0.26800942, 0.0069202706 0.10337376 0.28549731, 0.0084218308 0.11289885 0.2646172, 0.0091851279 0.10178225 0.28305352, 0.0031774268 0.10574608 0.28538716, 0.0033602491 0.10623439 0.28456312, 0.0077028051 0.11238735 0.26372832, 0.0097959563 0.10156801 0.28173673, 0.0058896467 0.11113625 0.26260269, 0.0051454976 0.11042612 0.26251417, 0.0083140805 0.1029199 0.2845723, 0.0056696013 0.1048037 0.28565687, 0.0091120675 0.11362942 0.26663721, 0.0089307651 0.11348062 0.26992029, 0.007680364 0.11362492 0.26978409, 0.0067001209 0.10420134 0.28549105, 0.0089267418 0.11381876 0.26864398, 0.0092893466 0.10248264 0.28353506, 0.0082719252 0.11354335 0.26516092, 0.010051943 0.10215782 0.28230226, 0.0076769516 0.11313464 0.26414591, 0.0081660375 0.10374206 0.28476053, 0.0060434714 0.1119762 0.26266849, 0.0053443983 0.10549989 0.28527898, 0.0063980743 0.10498037 0.28530347, 0.0087010339 0.11398344 0.26729995, 0.008318685 0.11381748 0.2692467, 0.0092582926 0.10326307 0.28388596, 0.010746337 0.1020697 0.28073364, 0.010815822 0.10191806 0.27952784, 0.0080088452 0.1140474 0.26580131, 0.0075402632 0.11377489 0.26469803, 0.010165997 0.10286244 0.28277534, 0.0079062358 0.10455795 0.28477764, 0.0061120912 0.1127924 0.26291859, 0.004980363 0.10606536 0.28474873, 0.0051889792 0.1066111 0.28380996, 0.0060310438 0.10566651 0.28494596, 0.0082021281 0.1141532 0.26797479, 0.0076477602 0.11438262 0.26650161, 0.0090932921 0.10407921 0.2840867, 0.0073002949 0.1142716 0.26535302, 0.011027165 0.1026726 0.28127301, 0.011255942 0.1023918 0.28008932, 0.0060916319 0.11353826 0.26333869, 0.010131918 0.10364174 0.28312874, 0.0034101829 0.111546 0.26178348, 0.0075497702 0.10532092 0.28462231, 0.0056202486 0.10622066 0.28443837, 0.0076433197 0.11412939 0.26862335, 0.0062025562 0.11423668 0.26856112, 0.0088041201 0.10488423 0.28412497, 0.0072090998 0.11452957 0.2672224, 0.011152364 0.10338312 0.28173435, 0.0069711879 0.11459666 0.26607352, 0.0059831515 0.11417135 0.26390517, 0.011549987 0.10300332 0.28061205, 0.0099514201 0.10445105 0.28334296, 0.0034993514 0.1123965 0.26182777, 0.00082073361 0.11258679 0.26144725, 0.0071168169 0.10598757 0.28430378, 0.0067181364 0.11447998 0.26792216, 0.0084071532 0.10563251 0.2839992, 0.011114873 0.10416054 0.28209138, 0.0065713897 0.11473139 0.26681876, 0.0057928935 0.11465546 0.26458549, 0.011681162 0.10371744 0.28106582, 0.003539063 0.11321744 0.26206833, 0.00083012134 0.11340987 0.26168329, 0.012128361 0.10307737 0.27871853, 0.011889912 0.10280656 0.27775109, 0.009634994 0.10524436 0.28340501, 0.0061237589 0.11466797 0.26754606, 0.0044862553 0.11470764 0.26761937, 0.0066320524 0.10651984 0.28384024, 0.0068185106 0.10713997 0.28275228, 0.0055316165 0.11496317 0.26534063, 0.007925041 0.10628127 0.28371632, 0.0035272315 0.11396196 0.26249141, 0.00082726032 0.11415365 0.26210749, 0.010916941 0.10496064 0.2823239, 0.011641882 0.10449385 0.28142494, 0.0052144304 0.11507674 0.26612782, 0.0034644082 0.11458745 0.26307279, 0.00081247836 0.11477589 0.26269597, 0.012445398 0.10370662 0.2792052, 0.0092005804 0.10597628 0.28331161, 0.0048591569 0.11498999 0.26690221, 0.0025976673 0.11501964 0.26699543, 0.0073851719 0.10679349 0.28329265, 0.0033541843 0.11505853 0.26377952, 0.00078672916 0.1152408 0.26341444, 0.010569729 0.10573771 0.28241849, 0.0032029524 0.11534806 0.26457119, 0.00075124949 0.11552214 0.26422274, 0.011434458 0.10528808 0.2816695, 0.0030192807 0.11543959 0.2654025, 0.012586631 0.10442888 0.279643, 0.00070817024 0.11560368 0.26507407, 0.0086729154 0.10660543 0.28306848, 0.0028134957 0.11532798 0.26622617, 0.00065986067 0.11548092 0.2659204, 0.01009313 0.1064476 0.28236949, 0.011070915 0.10605478 0.28178465, 0.012544312 0.10520276 0.2800073, 0.013044439 0.10418626 0.27650082, 0.012602873 0.103765 0.27583456, 0.0080821142 0.10709556 0.28268898, 0.008185856 0.10780101 0.28143048, 0.0095143691 0.10704955 0.28218019, 0.010571621 0.1067503 0.28176439, 0.0088661984 0.10750943 0.28186107, 0.0099655613 0.10733484 0.28160971, 0.0092865899 0.10777535 0.28132969, 0.0092385039 0.10856869 0.27989566, 0.01293277 0.10476422 0.2738362, -0.010901429 0.10576998 0.26820487, -0.010945134 0.10453617 0.26858127, -0.011212014 0.10541444 0.26891589, -0.010641836 0.10488322 0.26788712, -0.010401599 0.10165315 0.28005737, -0.0088383928 0.10058113 0.28050959, -0.0089023039 0.10089793 0.28156799, -0.011555068 0.10489129 0.26996237, -0.011645518 0.10625362 0.26916581, 0.00073190778 0.10993972 0.26179498, -0.0014178976 0.10991284 0.26184875, -0.012001701 0.10571008 0.27025276, -0.0014889464 0.11086433 0.26163775, -0.0099052712 0.10114124 0.27938914, -0.0085094199 0.099953108 0.27983731, -0.0095365122 0.10049241 0.27875865, -0.012603216 0.10645103 0.27046287, -0.012195937 0.10526555 0.27114189, -0.012933187 0.10545187 0.272461, 0.00070460886 0.10896327 0.26181942, -0.0013649538 0.10893738 0.26187092, -0.0082384124 0.098364793 0.2787478, -0.0083068386 0.099204741 0.27924216, -0.0093095973 0.099731348 0.2781893, -0.011367969 0.10273116 0.27001613, -0.011280023 0.10402536 0.26960236, -0.010854982 0.10365226 0.26817447, -0.0014388636 0.10705676 0.26136643, -0.0013325885 0.1079753 0.26170403, 0.00068215281 0.10708799 0.26130378, -0.0071059838 0.099920295 0.28183091, -0.0071325675 0.10027041 0.28282261, 0.00068780035 0.10800042 0.26165336, -0.011741959 0.10446309 0.27081823, -0.0035244748 0.10971939 0.26223534, -0.0037010238 0.11066117 0.26204395, -0.0068416074 0.099316768 0.28110921, -0.012316041 0.10475867 0.27215558, -0.0033933148 0.1087512 0.26224339, -0.0066787526 0.098583691 0.28048426, -0.0066237226 0.097748838 0.27997947, -0.011462294 0.10360735 0.27043802, -0.0051319376 0.099413 0.28284526, -0.0035108402 0.1068516 0.26177663, -0.0033125654 0.10779344 0.26206738, -0.011857577 0.10397511 0.27179414, -0.005146049 0.099790029 0.28378338, -0.012331001 0.10424902 0.27317452, -0.01287023 0.10444205 0.27448022, -0.0055240616 0.10936546 0.26294321, -0.0058008209 0.11028939 0.26278752, -0.0049408153 0.098828487 0.2820859, -0.011493929 0.10178374 0.27191097, -0.011575244 0.10313108 0.27139074, -0.0053185448 0.10841038 0.26292491, -0.0047835782 0.097276144 0.28092504, -0.0048233047 0.098107062 0.28143752, -0.011871986 0.10348438 0.27277529, -0.0054632947 0.10647964 0.26252043, -0.0051917955 0.10746076 0.26273263, -0.0030031428 0.099471144 0.28442103, -0.0029828772 0.09907674 0.28351772, -0.00073233992 0.098922871 0.28382581, -0.0028718188 0.098504715 0.28273332, -0.00070508569 0.098356448 0.28302979, -0.012256019 0.10379713 0.27407843, -0.011589311 0.10265213 0.27234852, -0.0073556826 0.10886138 0.26395124, -0.0077245459 0.10976025 0.26384574, -0.0028034672 0.097790919 0.28206962, -0.011799745 0.1030493 0.27364528, -0.00068824738 0.09764605 0.28235888, -0.0070818588 0.10792511 0.26389509, -0.00068257004 0.096819155 0.28183877, -0.0027803853 0.096962683 0.28155166, -0.0069134757 0.10698705 0.26368004, -0.012046181 0.10323869 0.275195, -0.0072297528 0.1059536 0.26357216, -0.012416251 0.10345273 0.27645892, -0.011518888 0.10222747 0.27319777, -0.0089640543 0.10822283 0.26522833, -0.0094132945 0.10908955 0.26518661, -0.011228465 0.10084187 0.27379411, -0.011597805 0.10251167 0.27472031, -0.0093872473 0.10801207 0.26564962, -0.010816105 0.108298 0.26676941, -0.011823706 0.10285499 0.27596235, -0.0086302683 0.10731023 0.26512474, -0.011321656 0.10170241 0.27424729, -0.0090378448 0.10710745 0.26553029, -0.011383526 0.10214218 0.27545947, -0.0087499246 0.10529151 0.26489663, -0.0084248707 0.10638683 0.2648803, -0.010300018 0.10746904 0.26673549, -0.01135125 0.10226911 0.27713424, -0.011584975 0.10251348 0.27833688, -0.0088225529 0.10618871 0.26527607, -0.010580577 0.099938057 0.27560151, -0.011112444 0.10134178 0.27496874, -0.010698564 0.10717969 0.26731408, -0.0118903 0.10740953 0.2685461, -0.011032052 0.10196056 0.27775097, -0.0099164918 0.10658454 0.26657617, -0.010928564 0.10157814 0.27658725, -0.010621347 0.10128116 0.27718115, -0.010300256 0.10630592 0.26713306, -0.0099722371 0.1045154 0.26644832, -0.0096803382 0.10567828 0.2662968, -0.010668479 0.10079118 0.27606994, -0.011322819 0.10662302 0.26842755, -0.010269649 0.10137292 0.2789259, -0.010055013 0.10540637 0.26684064, -0.0095724389 0.099102907 0.27727169, -0.010368384 0.1005012 0.27664959, -0.0098873898 0.10071536 0.27831256, -0.0096519217 0.099948876 0.27775413, -0.00068262964 0.092023961 0.279441, 0.001438342 0.092055462 0.27937818, 0.0014384165 0.096850507 0.28177619, 0.0035105571 0.092260443 0.27896798, 0.0035104975 0.097055696 0.28136605, 0.0054629669 0.092632316 0.27822423, 0.0054628626 0.097427689 0.2806223, 0.007229425 0.093158506 0.27717251, 0.007229276 0.09795361 0.2795704, 0.0087496266 0.093820803 0.27584797, 0.0087495968 0.098615907 0.27824605, 0.0099718198 0.094596677 0.27429646, 0.0099718496 0.09939184 0.27669418, 0.01085455 0.095459871 0.27257031, 0.01085455 0.10025492 0.27496821, 0.011367626 0.096380912 0.27072865, 0.011367746 0.10117599 0.27312648, 0.011493586 0.097328357 0.2688337, 0.011493541 0.10212355 0.27123183, 0.011228062 0.098270111 0.26695091, 0.011227988 0.10306522 0.2693485, 0.010580309 0.099173956 0.26514322, 0.01058019 0.10396894 0.26754117, 0.0095720962 0.10000923 0.26347297, 0.0095720366 0.10480421 0.26587075, 0.008237876 0.10074734 0.26199692, 0.0082379207 0.10554247 0.26439482, 0.0066234544 0.10136314 0.26076525, 0.0066232607 0.10615831 0.26316309, 0.0047831908 0.10183602 0.25981987, 0.0047830716 0.10663112 0.26221782, 0.0027800128 0.10214951 0.25919294, 0.0027799532 0.10694449 0.2615906, 0.00068228692 0.10229298 0.25890589, -0.011493944 0.096988611 0.26951313, -0.010580458 0.095142953 0.27320361, -0.011228465 0.096046917 0.27139622, -0.0095724091 0.094307862 0.27487397, -0.0082382336 0.093569688 0.27634996, -0.006623663 0.092953794 0.27758175, -0.0047834292 0.09248089 0.27852702, -0.0027804151 0.092167489 0.27915406, -0.010854907 0.098857038 0.26577646, -0.011367925 0.097936146 0.2676183, -0.009972252 0.099720471 0.2640506, -0.0072297528 0.10115849 0.2611745, -0.0087498799 0.10049631 0.26249874, -0.00546325 0.10168456 0.26012242, -0.001438804 0.10226163 0.25896865, -0.0035107955 0.10205656 0.25937873, 0.011211611 0.10190552 0.27593327, 0.011554666 0.10242852 0.27488714, 0.011645146 0.102609 0.27645475, 0.012001373 0.10315236 0.27536803, 0.0014174655 0.098949634 0.28377205, 0.0099048242 0.10772129 0.26623142, 0.0085088834 0.10736673 0.26501185, 0.0088379756 0.10828149 0.26511115, 0.0095361546 0.10682734 0.26609063, 0.01219555 0.10359701 0.27447861, 0.0083064213 0.10644194 0.26477021, 0.009308897 0.10591542 0.26582307, 0.011279561 0.10162132 0.27441001, 0.0013646558 0.098382376 0.28297812, 0.010944836 0.1011106 0.27543128, 0.007105656 0.10894232 0.26378971, 0.0013320819 0.097671472 0.28230846, 0.011741571 0.10285675 0.27403092, 0.0068411306 0.10800292 0.26373965, 0.012315609 0.10410377 0.2734651, 0.0035241321 0.099143051 0.28338534, 0.0066782162 0.10706311 0.26352823, 0.01146201 0.10203924 0.27357417, 0.0033928528 0.098568551 0.28260583, 0.0051314309 0.10944941 0.26277548, 0.011857174 0.10334476 0.27305508, 0.0033121333 0.097853206 0.28194517, 0.012330599 0.10461362 0.27244592, 0.0049403533 0.10849132 0.26276308, 0.0055237487 0.099497132 0.28267735, 0.011574917 0.10251569 0.27262163, 0.004822813 0.10753968 0.26257485, 0.0053180382 0.09890943 0.28192431, 0.00298246 0.1097857 0.2621029, 0.011871584 0.10383543 0.27207386, 0.0051914677 0.098186098 0.28127992, 0.0028714314 0.10881504 0.26211578, 0.012255661 0.10506546 0.27154243, 0.011588953 0.10299464 0.27166378, 0.0073554441 0.10000124 0.28166968, 0.00280305 0.1078557 0.26194268, 0.011799388 0.10427039 0.27120399, 0.0070815757 0.099394731 0.28095394, 0.0069130287 0.098659687 0.28033262, 0.012045808 0.10562386 0.27042568, 0.011518531 0.1034193 0.27081454, 0.0089636669 0.10063978 0.28039235, 0.011597358 0.10480805 0.27012879, 0.0093868151 0.10085052 0.279971, 0.0086299703 0.10000949 0.27972448, 0.011823259 0.10600766 0.26965815, 0.011321299 0.10394417 0.26976502, 0.0090373829 0.10021242 0.27931887, 0.0084244683 0.099259935 0.27913243, 0.011383049 0.10517757 0.26938963, 0.011350788 0.10659363 0.26848656, 0.01029966 0.10139357 0.27888489, 0.0088221654 0.099457912 0.27873629, 0.011112057 0.10430499 0.26904362, 0.010698073 0.10168292 0.27830648, 0.011031635 0.10690203 0.26786977, 0.0099161491 0.10073524 0.27827334, 0.010928281 0.10574158 0.26826173, 0.010621063 0.10603856 0.26766801, 0.010299884 0.10101383 0.27771616, 0.0096801296 0.099968307 0.27771568, 0.010668166 0.1048555 0.26794261, 0.011322565 0.10223969 0.27719313, 0.010269172 0.10748961 0.26669478, 0.010054685 0.10024046 0.27717173, 0.010368295 0.10514536 0.26736295, 0.010900952 0.10154998 0.27664423, 0.0098868981 0.10660442 0.26653671, 0.010641403 0.10076358 0.27612561, 0.0096515194 0.10569765 0.26625866, -0.012830503 0.11082011 0.27225471, -0.011929698 0.1119109 0.27007365, -0.012321495 0.11133649 0.26957351, -0.013251998 0.11020996 0.27182633, -0.013968118 0.10753392 0.27343345, -0.013537593 0.10874554 0.27101052, -0.013385661 0.10797485 0.27066964, -0.013811208 0.10677695 0.27306551, -0.013394006 0.10501861 0.27483612, -0.013459615 0.10606947 0.27273494, -0.012251981 0.11130079 0.27266413, -0.011391647 0.11234232 0.27058107, -0.013921179 0.10829737 0.27381837, -0.013492234 0.10950508 0.27140367, -0.01374387 0.10569861 0.27522153, -0.011549421 0.1116245 0.27303135, -0.010738514 0.11260625 0.27106798, -0.013673104 0.10902383 0.27419835, -0.013900079 0.10644346 0.27561414, -0.010762669 0.11177271 0.27333558, -0.010007061 0.11268764 0.27150577, -0.013238467 0.10967173 0.27455103, -0.01292152 0.10398894 0.27689534, -0.013853379 0.10721063 0.27599198, -0.012641571 0.11020418 0.27485693, -0.01325921 0.10464206 0.27733433, -0.013606794 0.10795652 0.2763328, -0.011916555 0.11059072 0.27509844, -0.013409652 0.10537472 0.27775109, -0.013174005 0.10863822 0.27661788, -0.011104859 0.11080935 0.27526188, -0.012056433 0.10301139 0.27884984, -0.01336471 0.10614552 0.27812147, -0.012580045 0.10921734 0.27683067, -0.012371428 0.10363906 0.27934009, -0.011635803 0.10266464 0.27954376, -0.013126634 0.10691022 0.2784248, -0.011858501 0.10966041 0.2769587, -0.012511916 0.10436051 0.27977955, -0.011939727 0.1032831 0.28005159, -0.012709297 0.10762545 0.27864313, -0.011050858 0.10994252 0.27699554, -0.010824986 0.10211613 0.28064024, -0.012469895 0.10513472 0.28014314, -0.012075327 0.10400047 0.28049922, -0.012136243 0.1082501 0.27876449, -0.01110775 0.1027204 0.28117728, -0.0015494898 0.11170205 0.26147091, -0.012247823 0.10591748 0.28041029, -0.0015899464 0.11255669 0.26150709, -0.012034796 0.10477587 0.28086054, -0.010083221 0.10170799 0.28145677, -0.0016080961 0.11337953 0.26174432, -0.01144018 0.10874867 0.27878183, -0.0038517043 0.11149081 0.26189351, -0.011233874 0.10343134 0.28163743, -0.0016027018 0.11412346 0.26216823, -0.011858411 0.10666417 0.2805655, -0.011820577 0.10556515 0.28111494, -0.003952302 0.11233982 0.26194102, -0.010346599 0.10230132 0.28201497, -0.0015740916 0.11474609 0.26275557, -0.010660909 0.10909288 0.27869457, -0.0039973035 0.11316016 0.26218277, -0.0092647001 0.10133 0.28221226, -0.011196189 0.10420858 0.28199494, -0.0015241429 0.11521208 0.2634725, -0.011323713 0.10733222 0.28060013, -0.0060370341 0.11110388 0.26266748, -0.01144471 0.10632306 0.28124803, -0.0039839223 0.11390483 0.26260537, -0.01046405 0.10300761 0.28248501, -0.0014552101 0.11549463 0.26427782, -0.0095067248 0.10191374 0.28279018, -0.0061946586 0.11194282 0.26273489, -0.010996826 0.10500782 0.28222913, -0.0068126395 0.11091574 0.2630437, -0.01067438 0.10788348 0.28051245, -0.0039128736 0.11453139 0.26318485, -0.010928653 0.1070063 0.28125173, -0.0013719425 0.11557766 0.26512599, -0.010428973 0.1037864 0.28283948, -0.0081431642 0.10090493 0.28306228, -0.006265156 0.11275869 0.26298577, -0.0096146092 0.10261559 0.28326881, -0.0069905147 0.11174979 0.26312107, -0.010647111 0.10578346 0.2823267, -0.0037885383 0.11500417 0.26388806, -0.0099471584 0.1082864 0.28030694, -0.0012784824 0.11545666 0.26596844, -0.010301955 0.10757636 0.28112686, -0.0080387965 0.11055311 0.26376897, -0.01024323 0.10459309 0.2830584, -0.0062441304 0.11350464 0.26340574, -0.0083558038 0.1014775 0.28366226, -0.0070699975 0.11256336 0.26337606, -0.0036176816 0.11529627 0.26467454, -0.0074227974 0.1006771 0.28351796, -0.0095823631 0.1033956 0.28362089, -0.010167129 0.10649111 0.28228188, -0.0082487687 0.11137768 0.26386529, -0.0096002594 0.10800042 0.28087938, -0.0061328784 0.11413839 0.26397097, -0.00991752 0.10538199 0.28312975, -0.007046245 0.11331003 0.26379484, -0.0084506497 0.10217445 0.28415084, -0.0089516714 0.11022144 0.26443225, -0.0034102425 0.11539068 0.26549995, -0.0076167509 0.10124382 0.2841301, -0.0083425418 0.11218714 0.26412898, -0.009411715 0.10420933 0.28382599, -0.0095839724 0.10709061 0.28209752, -0.0059378371 0.11462366 0.26464891, -0.0069207177 0.11394721 0.26435322, -0.0094704106 0.10610773 0.28304875, -0.0091855153 0.11103725 0.2645458, -0.0084223524 0.10295602 0.28450012, -0.0031779036 0.11528244 0.26631713, -0.0097964182 0.10985514 0.26516443, -0.0077032968 0.10193803 0.28462392, -0.0058901086 0.1002868 0.28429842, -0.0083145872 0.11293503 0.26454484, -0.0056701079 0.11493262 0.26540154, -0.0091124997 0.10501029 0.28387266, -0.0089311823 0.10754784 0.28178406, -0.0067007318 0.1144385 0.26501912, -0.0089272782 0.1067292 0.28282046, -0.0092898086 0.1118428 0.2648173, -0.008272402 0.10377755 0.28468949, -0.010052286 0.1106615 0.26529694, -0.0076773986 0.10272037 0.28497154, -0.0081665441 0.11357879 0.26508987, -0.0060439035 0.10084327 0.28493094, -0.0053449944 0.11504804 0.26618516, -0.0063987747 0.11475607 0.26575482, -0.0087015852 0.10575291 0.28375828, -0.0092586949 0.11259171 0.26523125, -0.0083191916 0.10721093 0.28245759, -0.0080093369 0.10459229 0.28470886, -0.010746814 0.10935356 0.26616776, -0.0075406656 0.10354602 0.28515249, -0.010166444 0.11146273 0.26557702, -0.0079067126 0.11408176 0.26573229, -0.0061125383 0.10153305 0.28543395, -0.0049809739 0.11496323 0.26695567, -0.0060316548 0.11488151 0.26651835, -0.0082025751 0.10639476 0.28348935, -0.0090937987 0.11324178 0.26576382, -0.007648237 0.10535371 0.28455669, -0.011027433 0.11014672 0.26632661, -0.0073008761 0.10436811 0.28515697, -0.011256315 0.1090314 0.26681155, -0.010132454 0.11221313 0.26598841, -0.0060920641 0.10231673 0.28577828, -0.0075503364 0.11441543 0.26643574, -0.0034107491 0.099877141 0.28511792, -0.0056208 0.11480787 0.26726609, -0.0076438412 0.10689925 0.28308123, -0.0088045821 0.1137554 0.26638502, -0.007209532 0.10601851 0.2842418, -0.011152737 0.11094221 0.26661795, -0.00697162 0.1051397 0.28498477, -0.005983673 0.10314973 0.28594524, -0.01155033 0.10981625 0.26698744, -0.009951897 0.11286976 0.26650757, -0.003499724 0.10042297 0.28577161, -0.0071172938 0.11456048 0.26716042, -0.0084076002 0.11410382 0.26705897, -0.0067185387 0.10654854 0.28378242, -0.011115275 0.11169421 0.26702595, -0.0065717921 0.10581668 0.28464538, -0.0057933554 0.10398432 0.28592461, -0.011681505 0.1106078 0.26728672, -0.012128852 0.10834589 0.26818269, -0.0035395548 0.10110777 0.28628391, -0.009635441 0.11339539 0.26710504, -0.0061242506 0.10636055 0.28415859, -0.0066324696 0.11450877 0.26786435, -0.0055320784 0.10477316 0.28571779, -0.0079254583 0.11426684 0.26774776, -0.003527604 0.10189285 0.28662604, -0.010917328 0.11236029 0.26752657, -0.011642419 0.11136114 0.26769209, -0.0052148327 0.10547122 0.28533626, -0.012445621 0.10911279 0.26839417, -0.0034649298 0.10273337 0.28677768, -0.0092010722 0.11375993 0.26774663, -0.0073856339 0.11423504 0.26841193, -0.0048597082 0.10603859 0.28480226, -0.0033547804 0.1035813 0.28673053, -0.01057028 0.11290204 0.26809168, -0.011435114 0.11203303 0.26818097, -0.0032035336 0.10438838 0.28648728, -0.012587093 0.10989647 0.2687093, -0.0030198619 0.10510849 0.2860617, -0.0086733326 0.11394265 0.2683959, -0.0028140768 0.10570063 0.28547817, -0.010093682 0.11328881 0.26868886, -0.011071451 0.11258518 0.26872516, -0.012544833 0.11065208 0.26910996, -0.013044916 0.10723691 0.27040017, -0.0080824867 0.11393296 0.26901567, -0.0095149055 0.11349844 0.26928401, -0.010572337 0.11298623 0.2692939, -0.0088666454 0.11351907 0.26984322, -0.0099659041 0.11321326 0.26985413, -0.0092870072 0.1132532 0.27037495, 0.0045505539 0.11403271 0.26896727, 0.0044688359 0.11469071 0.26765126, 0.0027132407 0.11418649 0.26865959, -0.007823132 0.10906561 0.27889961, -0.008350648 0.10981976 0.27739191, -0.0010644421 0.10679402 0.28344232, 0.0043201819 0.11385848 0.26931512, -0.0072881356 0.10916638 0.27869821, -0.0075582042 0.11060121 0.2758289, -0.0077809468 0.10986959 0.27729213, 0.010212339 0.11030316 0.27642542, 0.010134555 0.11119943 0.27463281, 0.0085177049 0.11050975 0.276012, 0.0083047971 0.10972559 0.27758008, -0.0055808946 0.11345344 0.27012521, 0.0038304999 0.11348864 0.27005494, -0.002346538 0.11396676 0.26909906, -0.0038616881 0.11367696 0.26967829, 0.0037269518 0.10763376 0.28176332, 0.0079375133 0.11051898 0.27599323, -0.00073053688 0.11411031 0.26881206, 0.00091699511 0.11410155 0.26882958, 0.0025251582 0.1139408 0.26915073, 0.007740967 0.10978737 0.27745658, 0.0072109178 0.10908958 0.27885199, 0.0040243641 0.11363515 0.26976204, -0.0025827214 0.10721683 0.28259665, -0.00097738951 0.10705083 0.28292876, -0.0040766969 0.10752764 0.28197545, -0.0067882612 0.11287706 0.27127808, 0.0061783567 0.11422177 0.26858926, -0.0041337237 0.11390632 0.26921958, 0.0024738237 0.10706037 0.28290963, 0.0063702092 0.10845574 0.2801193, -0.0069594309 0.1083767 0.28027743, -0.006334506 0.11271476 0.27160227, -0.006481193 0.10852387 0.27998298, 0.0052550957 0.10791331 0.28120434, 0.0039136335 0.10748535 0.28205979, -0.0025089607 0.11421596 0.26860052, 0.0055670515 0.11329003 0.2704525, 0.0076504722 0.1136125 0.26980734, 0.0013966486 0.10604169 0.2849471, -0.0053951815 0.10796975 0.28109139, 0.0098976865 0.10941716 0.27819675, 0.0077349618 0.10897794 0.27907544, -0.005796738 0.10778224 0.28146631, -0.00077625364 0.11436906 0.26829457, 0.008828558 0.11288645 0.27125931, 0.0044200346 0.1070829 0.28286493, 0.0056365654 0.10771769 0.28159559, 0.0041983053 0.10725909 0.28251243, -0.0080416575 0.1113733 0.27428508, 0.0033471212 0.10625052 0.28452915, 0.0092027113 0.10857563 0.27987957, 0.0068325773 0.10829883 0.28043318, 0.0073111579 0.11195793 0.27311611, -0.0089713708 0.11060818 0.27581477, 0.0051688179 0.10662576 0.28377885, 0.0081539378 0.10781118 0.28140855, -0.0043847486 0.10730755 0.28241539, 0.0078518912 0.1120527 0.27292669, 0.0067919269 0.1071526 0.28272521, 0.00098981708 0.11435916 0.26831448, 0.0096672401 0.1120718 0.2728886, 0.0025874749 0.11500149 0.26702982, 0.0077921972 0.11125308 0.2745254, -0.0027844384 0.10697331 0.28308368, -0.0052103326 0.11325359 0.2705248, 0.0083646402 0.11129674 0.27443826, -0.0085192099 0.11060598 0.27581954, -0.0079387203 0.11060312 0.27582508, 0.004480429 0.1147018 0.26763004, 0.0061863437 0.11422654 0.26857984, 0.0061943009 0.11423158 0.26857042, 0.0044745877 0.11469617 0.26764065, 0.0076703206 0.11362054 0.26979184, 0.0076603368 0.11361652 0.26979977, 0.0088515207 0.11289283 0.27124715, 0.0088400766 0.11288961 0.27125323, 0.009692423 0.11207601 0.27288103, 0.0096798614 0.11207374 0.27288467, 0.01016102 0.11120128 0.27462977, 0.010147788 0.11120033 0.27463126, 0.010238983 0.11030268 0.27642691, 0.010225721 0.11030277 0.27642626, 0.0099234357 0.10941442 0.27820307, 0.0099105313 0.10941573 0.27819991, 0.0092266127 0.10857087 0.27989012, 0.0092146322 0.10857325 0.27988493, 0.0081752464 0.10780423 0.28142297, 0.0081646219 0.1078076 0.2814157, 0.0068097189 0.10714402 0.28274322, 0.0068007782 0.10714831 0.28273404, 0.0051822588 0.10661583 0.28379965, 0.0051754937 0.10662075 0.28378922, 0.0033558533 0.10623958 0.28455168, 0.0033514425 0.106245 0.28454036, 0.0014003143 0.1060301 0.28497094, 0.0013985112 0.10603585 0.2849589, 0.0025942996 0.11501338 0.26700693, 0.0025908425 0.11500742 0.26701826, -0.0085191801 0.11051654 0.2757746, -0.0083507076 0.10973021 0.27734721, -0.0078232661 0.10897636 0.27885473, -0.0069594905 0.10828718 0.28023243, -0.0057966933 0.10769277 0.28142172, -0.0043848976 0.10721817 0.28237075, -0.0027844831 0.106884 0.28303897, -0.0010644868 0.10670453 0.28339756, -0.008971341 0.11051875 0.27577037, -0.0080416426 0.11128377 0.27424037, -0.007558234 0.11051189 0.27578413, -0.0079387799 0.11051368 0.27578044, -0.0077810511 0.1097801 0.27724731, -0.0072881356 0.10907697 0.27865362, -0.006481193 0.10843446 0.2799384, -0.0053950772 0.10788032 0.28104675, -0.0040767118 0.10743808 0.28193057, -0.0025826916 0.10712745 0.28255183, -0.00097740442 0.10696139 0.28288406, 0.0041983351 0.10716959 0.28246766, 0.0056365505 0.10762837 0.281551, 0.0068325922 0.10820942 0.28038871, 0.0077350065 0.10888838 0.27903044, 0.0083047971 0.10963612 0.27753556, 0.0085177645 0.11042028 0.27596718, 0.0083645806 0.11120733 0.2743938, 0.0078519955 0.11196329 0.27288216, 0.0044200346 0.10699337 0.28282011, 0.0024737939 0.10697093 0.28286511, 0.0037269816 0.10754427 0.28171861, 0.0039136484 0.10739582 0.2820152, 0.0052551255 0.10782387 0.28115952, 0.0063702986 0.10836636 0.2800746, 0.0072109178 0.10900017 0.27880716, 0.0077409372 0.10969799 0.27741182, 0.0079375431 0.11042955 0.27594864, 0.0077921078 0.11116376 0.27448082, 0.0073112175 0.11186858 0.27307117, 0.0043199435 0.11376914 0.26927054, 0.0027133599 0.11409693 0.26861483, 0.00098984689 0.11426979 0.26826966, -0.00077622384 0.11427965 0.26824969, -0.0025089607 0.11412656 0.2685557, -0.0041337833 0.11381685 0.26917487, -0.0055808946 0.11336403 0.27008039, -0.0067882761 0.11278754 0.27123338, 0.0045504346 0.1139433 0.26892233, 0.0055670515 0.11320051 0.27040756, 0.0038305297 0.11339923 0.27001011, 0.0040243343 0.11354571 0.2697174, 0.002525039 0.11385139 0.26910603, 0.00091712922 0.11401217 0.26878476, -0.00073056668 0.11402088 0.26876742, -0.002346538 0.11387723 0.26905435, -0.0038616285 0.11358749 0.26963347, -0.0052102581 0.11316409 0.27048033, -0.0063345954 0.11262547 0.27155763 - ] - } - normal Normal { - } - solid FALSE - coordIndex [ - 0, 1, 2, -1, 3, 1, 4, -1, 2, 1, 3, -1, 5, 6, 7, -1, 1, 6, 4, -1, 4, 6, 5, -1, 8, 9, 0, -1, 0, 9, 1, -1, 1, 9, 6, -1, 10, 11, 12, -1, 9, 13, 6, -1, 7, 13, 14, -1, 6, 13, 7, -1, 8, 15, 9, -1, 16, 2, 17, -1, 18, 15, 8, -1, 9, 15, 13, -1, 14, 19, 20, -1, 13, 19, 14, -1, 15, 21, 13, -1, 18, 21, 15, -1, 22, 21, 18, -1, 13, 21, 19, -1, 20, 23, 24, -1, 21, 23, 19, -1, 19, 23, 20, -1, 25, 26, 22, -1, 22, 26, 21, -1, 21, 26, 23, -1, 24, 27, 28, -1, 23, 27, 24, -1, 29, 30, 25, -1, 26, 30, 23, -1, 23, 30, 27, -1, 25, 30, 26, -1, 28, 31, 32, -1, 27, 31, 28, -1, 33, 34, 29, -1, 27, 34, 31, -1, 29, 34, 30, -1, 30, 34, 27, -1, 34, 35, 31, -1, 32, 35, 36, -1, 31, 35, 32, -1, 37, 38, 33, -1, 33, 38, 34, -1, 34, 38, 35, -1, 35, 39, 36, -1, 36, 39, 40, -1, 41, 42, 37, -1, 37, 42, 38, -1, 38, 42, 35, -1, 35, 42, 39, -1, 39, 43, 40, -1, 40, 43, 44, -1, 45, 46, 41, -1, 41, 46, 42, -1, 42, 46, 39, -1, 39, 46, 43, -1, 44, 47, 48, -1, 43, 47, 44, -1, 49, 50, 45, -1, 45, 50, 46, -1, 46, 50, 43, -1, 43, 50, 47, -1, 48, 51, 52, -1, 47, 51, 48, -1, 53, 54, 49, -1, 49, 54, 50, -1, 50, 54, 47, -1, 47, 54, 51, -1, 52, 55, 56, -1, 51, 55, 52, -1, 54, 55, 51, -1, 57, 58, 53, -1, 53, 58, 54, -1, 54, 58, 55, -1, 59, 60, 61, -1, 59, 61, 62, -1, 56, 60, 59, -1, 55, 60, 56, -1, 61, 63, 64, -1, 65, 63, 57, -1, 64, 63, 65, -1, 58, 63, 55, -1, 65, 66, 64, -1, 60, 63, 61, -1, 57, 63, 58, -1, 55, 63, 60, -1, 17, 67, 10, -1, 10, 67, 11, -1, 17, 3, 67, -1, 2, 3, 17, -1, 67, 4, 11, -1, 11, 4, 5, -1, 3, 4, 67, -1, 68, 69, 70, -1, 68, 71, 69, -1, 72, 73, 74, -1, 75, 76, 77, -1, 72, 74, 78, -1, 79, 80, 81, -1, 82, 83, 71, -1, 82, 71, 68, -1, 84, 73, 72, -1, 84, 85, 73, -1, 86, 78, 80, -1, 86, 80, 79, -1, 87, 83, 82, -1, 87, 88, 83, -1, 89, 85, 84, -1, 89, 70, 85, -1, 90, 78, 86, -1, 90, 72, 78, -1, 91, 88, 87, -1, 91, 92, 93, -1, 91, 93, 94, -1, 91, 94, 88, -1, 95, 70, 89, -1, 95, 68, 70, -1, 96, 81, 97, -1, 96, 79, 81, -1, 98, 84, 72, -1, 98, 72, 90, -1, 99, 68, 95, -1, 99, 82, 68, -1, 100, 86, 79, -1, 100, 79, 96, -1, 101, 89, 84, -1, 101, 84, 98, -1, 102, 87, 82, -1, 102, 82, 99, -1, 103, 86, 100, -1, 103, 90, 86, -1, 104, 95, 89, -1, 104, 89, 101, -1, 105, 91, 87, -1, 105, 92, 91, -1, 105, 87, 102, -1, 105, 106, 92, -1, 107, 97, 108, -1, 107, 96, 97, -1, 109, 90, 103, -1, 109, 98, 90, -1, 110, 99, 95, -1, 110, 95, 104, -1, 111, 100, 96, -1, 111, 96, 107, -1, 112, 108, 113, -1, 112, 107, 108, -1, 114, 101, 98, -1, 114, 98, 109, -1, 115, 102, 99, -1, 115, 99, 110, -1, 116, 103, 100, -1, 116, 100, 111, -1, 117, 111, 107, -1, 118, 119, 120, -1, 117, 107, 112, -1, 121, 104, 101, -1, 121, 101, 114, -1, 122, 123, 106, -1, 122, 105, 102, -1, 122, 106, 105, -1, 122, 102, 115, -1, 124, 112, 113, -1, 125, 109, 103, -1, 125, 103, 116, -1, 126, 111, 117, -1, 126, 116, 111, -1, 127, 104, 121, -1, 127, 110, 104, -1, 128, 117, 112, -1, 128, 112, 124, -1, 129, 75, 130, -1, 131, 109, 125, -1, 131, 114, 109, -1, 129, 76, 75, -1, 132, 133, 76, -1, 134, 125, 116, -1, 134, 116, 126, -1, 135, 113, 136, -1, 132, 76, 129, -1, 135, 124, 113, -1, 137, 133, 132, -1, 138, 115, 110, -1, 137, 139, 133, -1, 138, 110, 127, -1, 140, 130, 141, -1, 140, 129, 130, -1, 142, 126, 117, -1, 142, 117, 128, -1, 143, 114, 131, -1, 144, 145, 139, -1, 143, 121, 114, -1, 144, 139, 137, -1, 146, 125, 134, -1, 147, 129, 140, -1, 146, 131, 125, -1, 147, 132, 129, -1, 148, 124, 135, -1, 149, 150, 145, -1, 148, 128, 124, -1, 151, 152, 123, -1, 151, 123, 122, -1, 149, 145, 144, -1, 151, 122, 115, -1, 151, 115, 138, -1, 153, 137, 132, -1, 153, 132, 147, -1, 154, 135, 136, -1, 155, 134, 126, -1, 156, 157, 150, -1, 155, 126, 142, -1, 156, 150, 149, -1, 158, 121, 143, -1, 159, 140, 141, -1, 158, 127, 121, -1, 160, 131, 146, -1, 161, 144, 137, -1, 160, 143, 131, -1, 161, 137, 153, -1, 162, 128, 148, -1, 163, 157, 156, -1, 163, 164, 157, -1, 162, 142, 128, -1, 165, 148, 135, -1, 165, 135, 154, -1, 166, 140, 159, -1, 167, 134, 155, -1, 166, 147, 140, -1, 168, 141, 169, -1, 167, 146, 134, -1, 168, 159, 141, -1, 170, 127, 158, -1, 170, 138, 127, -1, 171, 144, 161, -1, 172, 158, 143, -1, 171, 149, 144, -1, 173, 174, 164, -1, 172, 143, 160, -1, 175, 155, 142, -1, 173, 164, 163, -1, 175, 142, 162, -1, 176, 136, 177, -1, 178, 147, 166, -1, 176, 154, 136, -1, 178, 153, 147, -1, 179, 162, 148, -1, 179, 148, 165, -1, 180, 166, 159, -1, 180, 159, 168, -1, 181, 156, 149, -1, 182, 146, 167, -1, 182, 160, 146, -1, 181, 149, 171, -1, 183, 151, 138, -1, 184, 174, 173, -1, 183, 138, 170, -1, 183, 185, 152, -1, 184, 186, 12, -1, 184, 187, 174, -1, 183, 152, 151, -1, 184, 12, 187, -1, 188, 170, 158, -1, 189, 168, 169, -1, 188, 158, 172, -1, 190, 161, 153, -1, 191, 167, 155, -1, 191, 155, 175, -1, 190, 153, 178, -1, 192, 154, 176, -1, 193, 178, 166, -1, 192, 165, 154, -1, 193, 166, 180, -1, 194, 163, 156, -1, 194, 156, 181, -1, 195, 176, 177, -1, 196, 162, 179, -1, 196, 175, 162, -1, 197, 168, 189, -1, 198, 172, 160, -1, 197, 180, 168, -1, 198, 160, 182, -1, 199, 161, 190, -1, 199, 171, 161, -1, 200, 183, 170, -1, 200, 170, 188, -1, 200, 185, 183, -1, 201, 182, 167, -1, 201, 167, 191, -1, 202, 190, 178, -1, 202, 178, 193, -1, 203, 169, 204, -1, 205, 179, 165, -1, 203, 189, 169, -1, 205, 165, 192, -1, 206, 163, 194, -1, 206, 173, 163, -1, 207, 192, 176, -1, 207, 176, 195, -1, 208, 193, 180, -1, 208, 180, 197, -1, 209, 191, 175, -1, 209, 175, 196, -1, 210, 181, 171, -1, 210, 171, 199, -1, 211, 188, 172, -1, 211, 172, 198, -1, 212, 199, 190, -1, 213, 182, 201, -1, 212, 190, 202, -1, 213, 198, 182, -1, 214, 197, 189, -1, 215, 179, 205, -1, 214, 189, 203, -1, 216, 217, 186, -1, 215, 196, 179, -1, 216, 173, 206, -1, 216, 184, 173, -1, 216, 186, 184, -1, 218, 192, 207, -1, 219, 203, 204, -1, 218, 205, 192, -1, 220, 193, 208, -1, 221, 177, 222, -1, 220, 202, 193, -1, 221, 195, 177, -1, 223, 194, 181, -1, 223, 181, 210, -1, 224, 191, 209, -1, 224, 201, 191, -1, 225, 226, 185, -1, 225, 188, 211, -1, 225, 185, 200, -1, 227, 199, 212, -1, 225, 200, 188, -1, 227, 210, 199, -1, 228, 211, 198, -1, 229, 197, 214, -1, 228, 198, 213, -1, 229, 208, 197, -1, 230, 209, 196, -1, 231, 214, 203, -1, 231, 203, 219, -1, 230, 196, 215, -1, 232, 215, 205, -1, 232, 205, 218, -1, 233, 202, 220, -1, 233, 212, 202, -1, 234, 195, 221, -1, 235, 206, 194, -1, 235, 194, 223, -1, 236, 223, 210, -1, 236, 210, 227, -1, 234, 207, 195, -1, 237, 208, 229, -1, 238, 213, 201, -1, 238, 201, 224, -1, 239, 226, 225, -1, 237, 220, 208, -1, 240, 204, 241, -1, 239, 225, 211, -1, 239, 211, 228, -1, 240, 219, 204, -1, 242, 209, 230, -1, 242, 224, 209, -1, 243, 214, 231, -1, 243, 229, 214, -1, 244, 212, 233, -1, 244, 227, 212, -1, 245, 230, 215, -1, 245, 215, 232, -1, 246, 207, 234, -1, 246, 218, 207, -1, 247, 216, 206, -1, 247, 217, 216, -1, 247, 248, 217, -1, 247, 206, 235, -1, 249, 235, 223, -1, 249, 223, 236, -1, 250, 228, 213, -1, 250, 213, 238, -1, 251, 233, 220, -1, 251, 220, 237, -1, 252, 238, 224, -1, 252, 224, 242, -1, 253, 242, 230, -1, 254, 231, 219, -1, 253, 230, 245, -1, 254, 219, 240, -1, 255, 240, 241, -1, 256, 237, 229, -1, 257, 218, 246, -1, 256, 229, 243, -1, 257, 232, 218, -1, 258, 236, 227, -1, 259, 222, 119, -1, 258, 227, 244, -1, 259, 119, 118, -1, 260, 247, 235, -1, 260, 235, 249, -1, 260, 248, 247, -1, 259, 221, 222, -1, 261, 228, 250, -1, 261, 226, 239, -1, 261, 262, 226, -1, 263, 244, 233, -1, 261, 239, 228, -1, 263, 233, 251, -1, 264, 250, 238, -1, 265, 231, 254, -1, 264, 238, 252, -1, 265, 243, 231, -1, 266, 242, 253, -1, 266, 252, 242, -1, 267, 240, 255, -1, 267, 254, 240, -1, 268, 237, 256, -1, 269, 245, 232, -1, 268, 251, 237, -1, 269, 232, 257, -1, 270, 259, 118, -1, 270, 234, 221, -1, 270, 118, 271, -1, 272, 249, 236, -1, 272, 236, 258, -1, 270, 221, 259, -1, 273, 250, 264, -1, 274, 244, 263, -1, 274, 258, 244, -1, 273, 261, 250, -1, 273, 262, 261, -1, 275, 243, 265, -1, 275, 256, 243, -1, 276, 264, 252, -1, 276, 252, 266, -1, 277, 253, 245, -1, 278, 265, 254, -1, 277, 245, 269, -1, 278, 254, 267, -1, 279, 241, 280, -1, 281, 271, 282, -1, 279, 255, 241, -1, 281, 246, 234, -1, 283, 251, 268, -1, 281, 270, 271, -1, 283, 263, 251, -1, 281, 234, 270, -1, 284, 285, 262, -1, 286, 287, 248, -1, 284, 273, 264, -1, 286, 248, 260, -1, 284, 264, 276, -1, 286, 260, 249, -1, 284, 262, 273, -1, 288, 266, 253, -1, 286, 249, 272, -1, 289, 272, 258, -1, 288, 253, 277, -1, 289, 258, 274, -1, 290, 282, 291, -1, 292, 256, 275, -1, 292, 268, 256, -1, 290, 257, 246, -1, 290, 246, 281, -1, 290, 281, 282, -1, 293, 275, 265, -1, 293, 265, 278, -1, 294, 266, 288, -1, 295, 267, 255, -1, 294, 276, 266, -1, 296, 291, 297, -1, 295, 255, 279, -1, 296, 257, 290, -1, 296, 290, 291, -1, 298, 263, 283, -1, 296, 269, 257, -1, 298, 274, 263, -1, 299, 287, 286, -1, 300, 276, 294, -1, 299, 272, 289, -1, 300, 285, 284, -1, 299, 286, 272, -1, 300, 284, 276, -1, 301, 268, 292, -1, 302, 297, 303, -1, 302, 296, 297, -1, 301, 283, 268, -1, 302, 269, 296, -1, 302, 277, 269, -1, 304, 302, 303, -1, 305, 275, 293, -1, 305, 292, 275, -1, 304, 277, 302, -1, 304, 303, 306, -1, 304, 288, 277, -1, 307, 267, 295, -1, 307, 278, 267, -1, 308, 288, 304, -1, 309, 289, 274, -1, 308, 306, 310, -1, 308, 304, 306, -1, 309, 274, 298, -1, 308, 294, 288, -1, 311, 285, 300, -1, 312, 298, 283, -1, 311, 308, 310, -1, 312, 283, 301, -1, 311, 294, 308, -1, 311, 310, 313, -1, 311, 313, 62, -1, 311, 62, 314, -1, 311, 314, 285, -1, 311, 300, 294, -1, 315, 301, 292, -1, 315, 292, 305, -1, 316, 293, 278, -1, 316, 278, 307, -1, 317, 280, 318, -1, 317, 279, 280, -1, 319, 287, 299, -1, 319, 320, 287, -1, 319, 299, 289, -1, 319, 289, 309, -1, 321, 298, 312, -1, 321, 309, 298, -1, 322, 312, 301, -1, 322, 301, 315, -1, 69, 293, 316, -1, 69, 305, 293, -1, 74, 295, 279, -1, 74, 279, 317, -1, 323, 309, 321, -1, 323, 320, 319, -1, 323, 319, 309, -1, 324, 321, 312, -1, 324, 312, 322, -1, 71, 305, 69, -1, 71, 315, 305, -1, 73, 307, 295, -1, 73, 295, 74, -1, 325, 93, 320, -1, 325, 321, 324, -1, 325, 323, 321, -1, 325, 320, 323, -1, 83, 322, 315, -1, 83, 315, 71, -1, 85, 316, 307, -1, 85, 307, 73, -1, 80, 318, 326, -1, 80, 326, 81, -1, 80, 317, 318, -1, 88, 324, 322, -1, 88, 322, 83, -1, 70, 316, 85, -1, 70, 69, 316, -1, 78, 74, 317, -1, 78, 317, 80, -1, 94, 93, 325, -1, 94, 325, 324, -1, 94, 324, 88, -1, 327, 328, 329, -1, 330, 331, 332, -1, 332, 331, 333, -1, 334, 335, 336, -1, 337, 338, 339, -1, 340, 338, 337, -1, 341, 342, 343, -1, 336, 335, 344, -1, 333, 342, 341, -1, 345, 346, 347, -1, 348, 349, 334, -1, 347, 346, 340, -1, 350, 351, 352, -1, 334, 349, 335, -1, 352, 351, 353, -1, 336, 344, 120, -1, 340, 346, 338, -1, 330, 351, 331, -1, 353, 351, 330, -1, 354, 355, 356, -1, 357, 358, 359, -1, 356, 355, 348, -1, 339, 358, 357, -1, 331, 360, 333, -1, 348, 355, 349, -1, 333, 360, 342, -1, 344, 361, 362, -1, 338, 363, 339, -1, 342, 364, 343, -1, 335, 361, 344, -1, 339, 363, 358, -1, 345, 365, 346, -1, 366, 365, 345, -1, 350, 367, 351, -1, 368, 365, 366, -1, 331, 367, 360, -1, 351, 367, 331, -1, 335, 369, 361, -1, 346, 365, 338, -1, 338, 365, 363, -1, 349, 369, 335, -1, 358, 370, 359, -1, 354, 371, 355, -1, 372, 371, 354, -1, 360, 373, 342, -1, 359, 370, 374, -1, 342, 373, 364, -1, 355, 371, 349, -1, 349, 371, 369, -1, 343, 375, 376, -1, 364, 375, 343, -1, 362, 377, 378, -1, 358, 379, 370, -1, 361, 377, 362, -1, 363, 379, 358, -1, 380, 381, 350, -1, 350, 381, 367, -1, 360, 381, 373, -1, 368, 382, 365, -1, 367, 381, 360, -1, 365, 382, 363, -1, 363, 382, 379, -1, 361, 383, 377, -1, 369, 383, 361, -1, 373, 384, 364, -1, 372, 385, 371, -1, 386, 387, 388, -1, 389, 385, 372, -1, 374, 387, 386, -1, 364, 384, 375, -1, 370, 387, 374, -1, 371, 385, 369, -1, 369, 385, 383, -1, 388, 390, 391, -1, 379, 390, 370, -1, 378, 392, 393, -1, 387, 390, 388, -1, 375, 394, 376, -1, 381, 395, 373, -1, 377, 392, 378, -1, 370, 390, 387, -1, 391, 396, 329, -1, 380, 395, 381, -1, 327, 396, 368, -1, 373, 395, 384, -1, 390, 396, 391, -1, 329, 396, 327, -1, 384, 397, 375, -1, 377, 398, 392, -1, 368, 396, 382, -1, 379, 396, 390, -1, 383, 398, 377, -1, 382, 396, 379, -1, 375, 397, 394, -1, 399, 400, 389, -1, 394, 401, 376, -1, 383, 400, 398, -1, 389, 400, 385, -1, 376, 401, 402, -1, 385, 400, 383, -1, 395, 403, 384, -1, 384, 403, 397, -1, 380, 403, 395, -1, 393, 404, 405, -1, 392, 404, 393, -1, 406, 403, 380, -1, 397, 407, 394, -1, 394, 407, 401, -1, 405, 408, 409, -1, 404, 408, 405, -1, 401, 410, 402, -1, 392, 411, 404, -1, 398, 411, 392, -1, 403, 412, 397, -1, 397, 412, 407, -1, 406, 412, 403, -1, 404, 413, 408, -1, 411, 413, 404, -1, 407, 414, 401, -1, 400, 415, 398, -1, 416, 415, 399, -1, 399, 415, 400, -1, 401, 414, 410, -1, 398, 415, 411, -1, 408, 417, 409, -1, 410, 418, 402, -1, 402, 418, 419, -1, 415, 420, 411, -1, 421, 422, 406, -1, 407, 422, 414, -1, 406, 422, 412, -1, 416, 420, 415, -1, 412, 422, 407, -1, 411, 420, 413, -1, 409, 423, 424, -1, 417, 423, 409, -1, 418, 425, 419, -1, 408, 426, 417, -1, 414, 427, 410, -1, 413, 426, 408, -1, 410, 427, 418, -1, 418, 428, 425, -1, 417, 429, 423, -1, 426, 429, 417, -1, 427, 428, 418, -1, 430, 431, 416, -1, 420, 431, 413, -1, 413, 431, 426, -1, 421, 432, 422, -1, 416, 431, 420, -1, 422, 432, 414, -1, 414, 432, 427, -1, 423, 433, 424, -1, 419, 434, 435, -1, 425, 434, 419, -1, 430, 436, 431, -1, 431, 436, 426, -1, 437, 438, 421, -1, 421, 438, 432, -1, 426, 436, 429, -1, 427, 438, 428, -1, 432, 438, 427, -1, 429, 439, 423, -1, 423, 439, 433, -1, 434, 337, 435, -1, 428, 440, 425, -1, 424, 332, 341, -1, 433, 332, 424, -1, 425, 440, 434, -1, 352, 441, 430, -1, 429, 441, 439, -1, 436, 441, 429, -1, 430, 441, 436, -1, 434, 340, 337, -1, 440, 340, 434, -1, 386, 388, 77, -1, 439, 330, 433, -1, 437, 442, 438, -1, 438, 442, 428, -1, 433, 330, 332, -1, 428, 442, 440, -1, 345, 347, 437, -1, 332, 333, 341, -1, 437, 347, 442, -1, 440, 347, 340, -1, 442, 347, 440, -1, 337, 339, 435, -1, 352, 353, 441, -1, 439, 353, 330, -1, 441, 353, 439, -1, 435, 339, 357, -1, 443, 444, 445, -1, 443, 328, 444, -1, 446, 445, 447, -1, 446, 443, 445, -1, 448, 447, 449, -1, 448, 446, 447, -1, 450, 449, 451, -1, 450, 448, 449, -1, 452, 451, 453, -1, 452, 450, 451, -1, 454, 453, 455, -1, 454, 452, 453, -1, 456, 455, 457, -1, 456, 454, 455, -1, 458, 457, 459, -1, 458, 456, 457, -1, 460, 459, 461, -1, 460, 458, 459, -1, 462, 461, 463, -1, 462, 460, 461, -1, 464, 463, 465, -1, 464, 462, 463, -1, 466, 465, 467, -1, 466, 464, 465, -1, 468, 467, 469, -1, 468, 466, 467, -1, 470, 469, 471, -1, 470, 468, 469, -1, 472, 471, 473, -1, 472, 470, 471, -1, 474, 472, 473, -1, 474, 473, 475, -1, 474, 475, 476, -1, 356, 474, 476, -1, 467, 477, 478, -1, 467, 465, 477, -1, 467, 478, 473, -1, 469, 473, 471, -1, 469, 467, 473, -1, 479, 480, 481, -1, 479, 482, 480, -1, 483, 484, 485, -1, 445, 486, 479, -1, 445, 444, 486, -1, 449, 447, 445, -1, 477, 487, 488, -1, 477, 483, 487, -1, 451, 449, 445, -1, 489, 477, 490, -1, 455, 453, 451, -1, 455, 481, 491, -1, 455, 479, 481, -1, 455, 451, 445, -1, 455, 445, 479, -1, 478, 489, 492, -1, 478, 477, 489, -1, 459, 457, 455, -1, 459, 491, 484, -1, 459, 484, 483, -1, 459, 455, 491, -1, 475, 478, 476, -1, 463, 461, 459, -1, 473, 478, 475, -1, 465, 459, 483, -1, 465, 483, 477, -1, 465, 463, 459, -1, 354, 356, 476, -1, 354, 476, 478, -1, 372, 478, 492, -1, 372, 354, 478, -1, 389, 492, 489, -1, 389, 372, 492, -1, 399, 489, 490, -1, 399, 389, 489, -1, 416, 490, 477, -1, 416, 399, 490, -1, 430, 477, 488, -1, 430, 416, 477, -1, 352, 488, 487, -1, 352, 430, 488, -1, 350, 487, 483, -1, 350, 352, 487, -1, 380, 483, 485, -1, 380, 350, 483, -1, 406, 485, 484, -1, 406, 380, 485, -1, 421, 484, 491, -1, 421, 406, 484, -1, 437, 491, 481, -1, 437, 421, 491, -1, 345, 481, 480, -1, 345, 437, 481, -1, 366, 480, 482, -1, 366, 345, 480, -1, 368, 482, 479, -1, 368, 366, 482, -1, 327, 368, 479, -1, 327, 479, 486, -1, 327, 486, 444, -1, 328, 327, 444, -1, 113, 493, 136, -1, 494, 495, 496, -1, 496, 495, 497, -1, 498, 499, 493, -1, 388, 500, 75, -1, 501, 499, 498, -1, 318, 502, 326, -1, 497, 502, 318, -1, 391, 503, 388, -1, 468, 504, 505, -1, 388, 75, 77, -1, 505, 504, 501, -1, 458, 506, 456, -1, 456, 506, 507, -1, 388, 503, 500, -1, 501, 504, 499, -1, 494, 506, 495, -1, 507, 506, 494, -1, 391, 508, 503, -1, 443, 508, 328, -1, 136, 509, 177, -1, 329, 508, 391, -1, 493, 509, 136, -1, 328, 508, 329, -1, 495, 510, 497, -1, 497, 510, 502, -1, 75, 511, 130, -1, 499, 512, 493, -1, 502, 513, 326, -1, 500, 511, 75, -1, 493, 512, 509, -1, 470, 514, 468, -1, 503, 515, 500, -1, 458, 516, 506, -1, 468, 514, 504, -1, 495, 516, 510, -1, 504, 514, 499, -1, 506, 516, 495, -1, 500, 515, 511, -1, 499, 514, 512, -1, 446, 517, 443, -1, 509, 518, 177, -1, 510, 519, 502, -1, 508, 517, 503, -1, 177, 518, 222, -1, 502, 519, 513, -1, 443, 517, 508, -1, 503, 517, 515, -1, 326, 520, 81, -1, 130, 521, 141, -1, 513, 520, 326, -1, 509, 522, 518, -1, 512, 522, 509, -1, 511, 521, 130, -1, 460, 523, 458, -1, 458, 523, 516, -1, 472, 524, 470, -1, 510, 523, 519, -1, 516, 523, 510, -1, 515, 525, 511, -1, 470, 524, 514, -1, 514, 524, 512, -1, 511, 525, 521, -1, 512, 524, 522, -1, 119, 526, 336, -1, 519, 527, 513, -1, 448, 528, 446, -1, 222, 526, 119, -1, 513, 527, 520, -1, 446, 528, 517, -1, 517, 528, 515, -1, 515, 528, 525, -1, 518, 526, 222, -1, 141, 529, 169, -1, 526, 530, 336, -1, 520, 531, 81, -1, 523, 532, 519, -1, 521, 529, 141, -1, 336, 530, 334, -1, 522, 530, 518, -1, 460, 532, 523, -1, 519, 532, 527, -1, 518, 530, 526, -1, 522, 533, 530, -1, 527, 534, 520, -1, 521, 535, 529, -1, 474, 533, 472, -1, 356, 533, 474, -1, 525, 535, 521, -1, 530, 533, 334, -1, 334, 533, 348, -1, 348, 533, 356, -1, 520, 534, 531, -1, 472, 533, 524, -1, 450, 536, 448, -1, 524, 533, 522, -1, 531, 537, 81, -1, 525, 536, 535, -1, 528, 536, 525, -1, 81, 537, 97, -1, 448, 536, 528, -1, 532, 538, 527, -1, 527, 538, 534, -1, 169, 539, 204, -1, 460, 538, 532, -1, 462, 538, 460, -1, 529, 539, 169, -1, 534, 540, 531, -1, 531, 540, 537, -1, 204, 541, 241, -1, 539, 541, 204, -1, 537, 542, 97, -1, 535, 543, 529, -1, 538, 544, 534, -1, 529, 543, 539, -1, 462, 544, 538, -1, 539, 545, 541, -1, 534, 544, 540, -1, 543, 545, 539, -1, 452, 546, 450, -1, 540, 547, 537, -1, 536, 546, 535, -1, 450, 546, 536, -1, 537, 547, 542, -1, 535, 546, 543, -1, 542, 548, 97, -1, 541, 549, 241, -1, 97, 548, 108, -1, 546, 550, 543, -1, 464, 551, 462, -1, 462, 551, 544, -1, 544, 551, 540, -1, 543, 550, 545, -1, 452, 550, 546, -1, 540, 551, 547, -1, 549, 552, 241, -1, 241, 552, 280, -1, 548, 553, 108, -1, 541, 554, 549, -1, 547, 555, 542, -1, 545, 554, 541, -1, 542, 555, 548, -1, 548, 556, 553, -1, 554, 557, 549, -1, 549, 557, 552, -1, 555, 556, 548, -1, 454, 558, 452, -1, 550, 558, 545, -1, 464, 559, 551, -1, 551, 559, 547, -1, 545, 558, 554, -1, 547, 559, 555, -1, 452, 558, 550, -1, 552, 560, 280, -1, 108, 561, 113, -1, 553, 561, 108, -1, 454, 562, 558, -1, 554, 562, 557, -1, 466, 563, 464, -1, 558, 562, 554, -1, 464, 563, 559, -1, 555, 563, 556, -1, 559, 563, 555, -1, 557, 564, 552, -1, 561, 498, 113, -1, 552, 564, 560, -1, 556, 565, 553, -1, 280, 496, 318, -1, 560, 496, 280, -1, 553, 565, 561, -1, 456, 566, 454, -1, 454, 566, 562, -1, 557, 566, 564, -1, 562, 566, 557, -1, 561, 501, 498, -1, 119, 336, 120, -1, 565, 501, 561, -1, 564, 494, 560, -1, 466, 567, 563, -1, 563, 567, 556, -1, 560, 494, 496, -1, 556, 567, 565, -1, 468, 505, 466, -1, 496, 497, 318, -1, 466, 505, 567, -1, 565, 505, 501, -1, 567, 505, 565, -1, 498, 493, 113, -1, 456, 507, 566, -1, 564, 507, 494, -1, 566, 507, 564, -1, 568, 569, 570, -1, 571, 572, 573, -1, 571, 574, 572, -1, 575, 576, 577, -1, 575, 578, 576, -1, 579, 343, 376, -1, 579, 580, 343, -1, 581, 582, 574, -1, 581, 574, 571, -1, 583, 578, 575, -1, 583, 584, 578, -1, 585, 580, 579, -1, 585, 577, 580, -1, 586, 570, 582, -1, 586, 582, 581, -1, 587, 584, 583, -1, 587, 573, 584, -1, 588, 577, 585, -1, 588, 575, 577, -1, 589, 36, 40, -1, 589, 40, 568, -1, 589, 570, 586, -1, 589, 568, 570, -1, 590, 573, 587, -1, 590, 571, 573, -1, 591, 376, 402, -1, 591, 579, 376, -1, 592, 575, 588, -1, 592, 583, 575, -1, 593, 581, 571, -1, 593, 571, 590, -1, 594, 579, 591, -1, 594, 585, 579, -1, 595, 587, 583, -1, 595, 583, 592, -1, 596, 586, 581, -1, 596, 581, 593, -1, 597, 585, 594, -1, 597, 588, 585, -1, 598, 590, 587, -1, 598, 587, 595, -1, 599, 589, 586, -1, 599, 586, 596, -1, 599, 32, 36, -1, 599, 36, 589, -1, 600, 591, 402, -1, 600, 402, 419, -1, 601, 592, 588, -1, 601, 588, 597, -1, 602, 593, 590, -1, 602, 590, 598, -1, 603, 594, 591, -1, 603, 591, 600, -1, 604, 419, 435, -1, 604, 600, 419, -1, 605, 595, 592, -1, 605, 592, 601, -1, 606, 596, 593, -1, 606, 593, 602, -1, 607, 597, 594, -1, 607, 594, 603, -1, 76, 386, 77, -1, 608, 603, 600, -1, 608, 600, 604, -1, 609, 598, 595, -1, 609, 595, 605, -1, 610, 28, 32, -1, 610, 32, 599, -1, 610, 596, 606, -1, 610, 599, 596, -1, 611, 604, 435, -1, 612, 601, 597, -1, 612, 597, 607, -1, 613, 607, 603, -1, 613, 603, 608, -1, 614, 602, 598, -1, 614, 598, 609, -1, 615, 118, 120, -1, 616, 608, 604, -1, 616, 604, 611, -1, 615, 120, 344, -1, 617, 601, 612, -1, 617, 605, 601, -1, 618, 271, 118, -1, 619, 612, 607, -1, 618, 118, 615, -1, 619, 607, 613, -1, 620, 435, 357, -1, 621, 282, 271, -1, 620, 611, 435, -1, 621, 271, 618, -1, 622, 606, 602, -1, 622, 602, 614, -1, 623, 344, 362, -1, 623, 615, 344, -1, 624, 291, 282, -1, 625, 613, 608, -1, 625, 608, 616, -1, 624, 282, 621, -1, 626, 609, 605, -1, 626, 605, 617, -1, 627, 618, 615, -1, 628, 612, 619, -1, 628, 617, 612, -1, 627, 615, 623, -1, 629, 297, 291, -1, 630, 611, 620, -1, 630, 616, 611, -1, 629, 291, 624, -1, 631, 24, 28, -1, 631, 28, 610, -1, 631, 606, 622, -1, 632, 621, 618, -1, 631, 610, 606, -1, 632, 618, 627, -1, 633, 620, 357, -1, 634, 619, 613, -1, 635, 303, 297, -1, 634, 613, 625, -1, 635, 297, 629, -1, 636, 362, 378, -1, 636, 623, 362, -1, 637, 609, 626, -1, 637, 614, 609, -1, 638, 624, 621, -1, 639, 626, 617, -1, 639, 617, 628, -1, 638, 621, 632, -1, 640, 616, 630, -1, 641, 306, 303, -1, 641, 303, 635, -1, 640, 625, 616, -1, 642, 630, 620, -1, 642, 620, 633, -1, 643, 623, 636, -1, 643, 627, 623, -1, 644, 619, 634, -1, 645, 378, 393, -1, 644, 628, 619, -1, 645, 636, 378, -1, 646, 624, 638, -1, 647, 614, 637, -1, 647, 622, 614, -1, 648, 637, 626, -1, 646, 629, 624, -1, 649, 306, 641, -1, 649, 310, 306, -1, 648, 626, 639, -1, 650, 634, 625, -1, 650, 625, 640, -1, 651, 357, 359, -1, 651, 633, 357, -1, 652, 627, 643, -1, 652, 632, 627, -1, 653, 640, 630, -1, 653, 630, 642, -1, 654, 643, 636, -1, 654, 636, 645, -1, 655, 639, 628, -1, 656, 635, 629, -1, 656, 629, 646, -1, 655, 628, 644, -1, 657, 313, 310, -1, 658, 631, 622, -1, 657, 62, 313, -1, 658, 24, 631, -1, 657, 310, 649, -1, 658, 622, 647, -1, 658, 20, 24, -1, 657, 59, 62, -1, 659, 647, 637, -1, 660, 645, 393, -1, 661, 638, 632, -1, 659, 637, 648, -1, 662, 644, 634, -1, 662, 634, 650, -1, 661, 632, 652, -1, 663, 652, 643, -1, 664, 633, 651, -1, 663, 643, 654, -1, 664, 642, 633, -1, 665, 641, 635, -1, 665, 635, 656, -1, 666, 651, 359, -1, 667, 640, 653, -1, 667, 650, 640, -1, 668, 654, 645, -1, 668, 645, 660, -1, 669, 648, 639, -1, 669, 639, 655, -1, 670, 646, 638, -1, 671, 647, 659, -1, 671, 658, 647, -1, 671, 20, 658, -1, 670, 638, 661, -1, 672, 655, 644, -1, 673, 652, 663, -1, 673, 661, 652, -1, 672, 644, 662, -1, 674, 393, 405, -1, 675, 653, 642, -1, 674, 660, 393, -1, 676, 641, 665, -1, 675, 642, 664, -1, 676, 649, 641, -1, 677, 664, 651, -1, 677, 651, 666, -1, 678, 663, 654, -1, 678, 654, 668, -1, 679, 662, 650, -1, 679, 650, 667, -1, 680, 648, 669, -1, 680, 659, 648, -1, 681, 646, 670, -1, 681, 656, 646, -1, 682, 670, 661, -1, 683, 669, 655, -1, 682, 661, 673, -1, 683, 655, 672, -1, 684, 668, 660, -1, 685, 653, 675, -1, 684, 660, 674, -1, 685, 667, 653, -1, 686, 56, 59, -1, 686, 657, 649, -1, 686, 59, 657, -1, 686, 649, 676, -1, 687, 674, 405, -1, 688, 675, 664, -1, 688, 664, 677, -1, 689, 673, 663, -1, 690, 359, 374, -1, 689, 663, 678, -1, 690, 666, 359, -1, 691, 665, 656, -1, 691, 656, 681, -1, 692, 672, 662, -1, 692, 662, 679, -1, 693, 659, 680, -1, 694, 670, 682, -1, 693, 14, 20, -1, 694, 681, 670, -1, 693, 20, 671, -1, 693, 671, 659, -1, 695, 668, 684, -1, 696, 669, 683, -1, 696, 680, 669, -1, 695, 678, 668, -1, 697, 684, 674, -1, 698, 667, 685, -1, 697, 674, 687, -1, 698, 679, 667, -1, 699, 675, 688, -1, 700, 673, 689, -1, 700, 682, 673, -1, 699, 685, 675, -1, 701, 666, 690, -1, 702, 665, 691, -1, 702, 676, 665, -1, 703, 691, 681, -1, 701, 677, 666, -1, 704, 683, 672, -1, 703, 681, 694, -1, 705, 678, 695, -1, 704, 672, 692, -1, 706, 14, 693, -1, 706, 680, 696, -1, 705, 689, 678, -1, 706, 693, 680, -1, 707, 687, 405, -1, 707, 405, 409, -1, 708, 692, 679, -1, 708, 679, 698, -1, 709, 684, 697, -1, 710, 685, 699, -1, 709, 695, 684, -1, 711, 682, 700, -1, 711, 694, 682, -1, 710, 698, 685, -1, 712, 686, 676, -1, 713, 677, 701, -1, 712, 56, 686, -1, 712, 52, 56, -1, 712, 676, 702, -1, 714, 702, 691, -1, 713, 688, 677, -1, 715, 683, 704, -1, 714, 691, 703, -1, 715, 696, 683, -1, 716, 700, 689, -1, 716, 689, 705, -1, 717, 704, 692, -1, 717, 692, 708, -1, 718, 697, 687, -1, 718, 687, 707, -1, 719, 708, 698, -1, 719, 698, 710, -1, 720, 699, 688, -1, 721, 707, 409, -1, 722, 705, 695, -1, 722, 695, 709, -1, 720, 688, 713, -1, 723, 694, 711, -1, 723, 703, 694, -1, 724, 690, 374, -1, 724, 374, 386, -1, 725, 702, 714, -1, 725, 52, 712, -1, 724, 386, 76, -1, 725, 712, 702, -1, 726, 14, 706, -1, 727, 711, 700, -1, 726, 706, 696, -1, 727, 700, 716, -1, 726, 7, 14, -1, 726, 696, 715, -1, 728, 715, 704, -1, 729, 709, 697, -1, 728, 704, 717, -1, 729, 697, 718, -1, 730, 717, 708, -1, 730, 708, 719, -1, 731, 710, 699, -1, 732, 707, 721, -1, 732, 718, 707, -1, 733, 716, 705, -1, 731, 699, 720, -1, 733, 705, 722, -1, 734, 724, 76, -1, 734, 76, 133, -1, 735, 703, 723, -1, 734, 690, 724, -1, 734, 701, 690, -1, 735, 714, 703, -1, 736, 723, 711, -1, 736, 711, 727, -1, 737, 726, 715, -1, 737, 715, 728, -1, 737, 7, 726, -1, 738, 709, 729, -1, 739, 717, 730, -1, 739, 728, 717, -1, 738, 722, 709, -1, 740, 719, 710, -1, 741, 729, 718, -1, 740, 710, 731, -1, 741, 718, 732, -1, 742, 409, 424, -1, 743, 133, 139, -1, 742, 721, 409, -1, 743, 701, 734, -1, 744, 727, 716, -1, 743, 734, 133, -1, 744, 716, 733, -1, 743, 713, 701, -1, 745, 725, 714, -1, 746, 5, 7, -1, 745, 52, 725, -1, 746, 7, 737, -1, 745, 48, 52, -1, 746, 737, 728, -1, 745, 714, 735, -1, 746, 728, 739, -1, 747, 735, 723, -1, 748, 719, 740, -1, 747, 723, 736, -1, 748, 730, 719, -1, 749, 139, 145, -1, 750, 733, 722, -1, 750, 722, 738, -1, 749, 720, 713, -1, 749, 743, 139, -1, 751, 738, 729, -1, 751, 729, 741, -1, 749, 713, 743, -1, 752, 739, 730, -1, 752, 730, 748, -1, 753, 732, 721, -1, 754, 145, 150, -1, 753, 721, 742, -1, 755, 727, 744, -1, 754, 720, 749, -1, 755, 736, 727, -1, 754, 731, 720, -1, 754, 749, 145, -1, 756, 735, 747, -1, 756, 48, 745, -1, 757, 739, 752, -1, 756, 745, 735, -1, 757, 5, 746, -1, 757, 746, 739, -1, 758, 731, 754, -1, 759, 733, 750, -1, 758, 150, 157, -1, 759, 744, 733, -1, 760, 750, 738, -1, 758, 754, 150, -1, 758, 740, 731, -1, 760, 738, 751, -1, 761, 740, 758, -1, 762, 732, 753, -1, 761, 157, 164, -1, 761, 748, 740, -1, 762, 741, 732, -1, 761, 758, 157, -1, 763, 747, 736, -1, 764, 752, 748, -1, 764, 761, 164, -1, 764, 164, 174, -1, 763, 736, 755, -1, 764, 748, 761, -1, 765, 757, 752, -1, 766, 755, 744, -1, 765, 752, 764, -1, 765, 764, 174, -1, 765, 174, 187, -1, 765, 187, 12, -1, 765, 12, 11, -1, 766, 744, 759, -1, 765, 11, 5, -1, 767, 759, 750, -1, 765, 5, 757, -1, 767, 750, 760, -1, 768, 751, 741, -1, 768, 741, 762, -1, 769, 424, 341, -1, 769, 742, 424, -1, 770, 756, 747, -1, 770, 48, 756, -1, 770, 44, 48, -1, 770, 747, 763, -1, 771, 755, 766, -1, 771, 763, 755, -1, 772, 759, 767, -1, 772, 766, 759, -1, 572, 760, 751, -1, 572, 751, 768, -1, 576, 753, 742, -1, 576, 742, 769, -1, 773, 763, 771, -1, 773, 44, 770, -1, 773, 770, 763, -1, 569, 771, 766, -1, 569, 766, 772, -1, 574, 767, 760, -1, 574, 760, 572, -1, 578, 762, 753, -1, 578, 753, 576, -1, 774, 773, 771, -1, 774, 44, 773, -1, 774, 40, 44, -1, 774, 771, 569, -1, 582, 772, 767, -1, 582, 767, 574, -1, 584, 768, 762, -1, 584, 762, 578, -1, 580, 341, 343, -1, 580, 769, 341, -1, 570, 772, 582, -1, 570, 569, 772, -1, 573, 572, 768, -1, 573, 768, 584, -1, 577, 576, 769, -1, 577, 769, 580, -1, 568, 40, 774, -1, 568, 774, 569, -1, 775, 776, 777, -1, 778, 779, 780, -1, 781, 782, 25, -1, 16, 783, 2, -1, 784, 778, 780, -1, 785, 786, 787, -1, 788, 776, 775, -1, 788, 775, 789, -1, 790, 53, 49, -1, 791, 792, 793, -1, 794, 795, 791, -1, 791, 796, 792, -1, 794, 791, 786, -1, 791, 797, 796, -1, 791, 798, 797, -1, 791, 799, 798, -1, 794, 800, 795, -1, 791, 793, 786, -1, 794, 801, 800, -1, 802, 790, 49, -1, 794, 803, 804, -1, 802, 49, 45, -1, 794, 805, 803, -1, 802, 45, 41, -1, 794, 786, 805, -1, 806, 779, 778, -1, 807, 794, 804, -1, 807, 804, 783, -1, 808, 57, 53, -1, 22, 781, 25, -1, 808, 53, 790, -1, 809, 781, 22, -1, 810, 801, 794, -1, 811, 802, 41, -1, 812, 786, 785, -1, 813, 794, 814, -1, 815, 57, 808, -1, 813, 810, 794, -1, 815, 65, 57, -1, 816, 806, 778, -1, 817, 806, 816, -1, 18, 809, 22, -1, 818, 783, 16, -1, 818, 807, 783, -1, 819, 786, 812, -1, 820, 789, 821, -1, 820, 788, 789, -1, 822, 809, 18, -1, 823, 65, 815, -1, 824, 817, 816, -1, 823, 66, 65, -1, 825, 826, 827, -1, 828, 811, 41, -1, 8, 822, 18, -1, 829, 825, 807, -1, 828, 41, 37, -1, 828, 37, 33, -1, 829, 807, 818, -1, 805, 786, 819, -1, 830, 821, 831, -1, 830, 820, 821, -1, 832, 816, 791, -1, 833, 828, 33, -1, 834, 825, 829, -1, 835, 831, 826, -1, 836, 822, 8, -1, 835, 830, 831, -1, 837, 816, 832, -1, 837, 824, 816, -1, 838, 835, 826, -1, 838, 826, 825, -1, 29, 833, 33, -1, 838, 825, 834, -1, 839, 66, 823, -1, 839, 840, 66, -1, 841, 824, 837, -1, 0, 836, 8, -1, 842, 832, 791, -1, 843, 836, 0, -1, 786, 811, 828, -1, 786, 844, 811, -1, 786, 793, 844, -1, 777, 841, 837, -1, 782, 833, 29, -1, 782, 845, 833, -1, 780, 840, 839, -1, 795, 842, 791, -1, 787, 786, 846, -1, 776, 841, 777, -1, 2, 843, 0, -1, 2, 783, 843, -1, 779, 840, 780, -1, 25, 782, 29, -1, 847, 848, 849, -1, 806, 848, 779, -1, 779, 848, 850, -1, 850, 848, 847, -1, 849, 851, 262, -1, 262, 851, 226, -1, 817, 852, 806, -1, 848, 852, 849, -1, 61, 314, 62, -1, 806, 852, 848, -1, 849, 852, 851, -1, 226, 853, 185, -1, 851, 853, 226, -1, 824, 854, 817, -1, 851, 854, 853, -1, 817, 854, 852, -1, 852, 854, 851, -1, 185, 855, 152, -1, 853, 855, 185, -1, 853, 856, 855, -1, 841, 856, 824, -1, 824, 856, 854, -1, 854, 856, 853, -1, 152, 857, 123, -1, 855, 857, 152, -1, 776, 858, 841, -1, 841, 858, 856, -1, 855, 858, 857, -1, 856, 858, 855, -1, 123, 859, 106, -1, 857, 859, 123, -1, 788, 860, 776, -1, 857, 860, 859, -1, 776, 860, 858, -1, 858, 860, 857, -1, 106, 861, 92, -1, 859, 861, 106, -1, 820, 862, 788, -1, 860, 862, 859, -1, 788, 862, 860, -1, 859, 862, 861, -1, 861, 863, 92, -1, 92, 863, 93, -1, 830, 864, 820, -1, 862, 864, 861, -1, 820, 864, 862, -1, 861, 864, 863, -1, 863, 865, 93, -1, 93, 865, 320, -1, 835, 866, 830, -1, 830, 866, 864, -1, 864, 866, 863, -1, 863, 866, 865, -1, 320, 867, 287, -1, 865, 867, 320, -1, 838, 868, 835, -1, 835, 868, 866, -1, 866, 868, 865, -1, 865, 868, 867, -1, 287, 869, 248, -1, 867, 869, 287, -1, 834, 870, 838, -1, 838, 870, 868, -1, 868, 870, 867, -1, 867, 870, 869, -1, 248, 871, 217, -1, 869, 871, 248, -1, 829, 872, 834, -1, 870, 872, 869, -1, 869, 872, 871, -1, 834, 872, 870, -1, 217, 873, 186, -1, 186, 873, 12, -1, 818, 16, 17, -1, 12, 873, 10, -1, 871, 873, 217, -1, 829, 874, 872, -1, 61, 875, 314, -1, 818, 874, 829, -1, 17, 874, 818, -1, 10, 874, 17, -1, 872, 874, 871, -1, 840, 876, 66, -1, 873, 874, 10, -1, 64, 876, 61, -1, 871, 874, 873, -1, 66, 876, 64, -1, 61, 876, 875, -1, 314, 847, 285, -1, 875, 847, 314, -1, 779, 850, 840, -1, 875, 850, 847, -1, 876, 850, 875, -1, 840, 850, 876, -1, 285, 849, 262, -1, 847, 849, 285, -1, 845, 782, 877, -1, 877, 782, 878, -1, 878, 781, 879, -1, 782, 781, 878, -1, 879, 809, 880, -1, 781, 809, 879, -1, 880, 822, 881, -1, 809, 822, 880, -1, 881, 836, 882, -1, 822, 836, 881, -1, 882, 843, 883, -1, 883, 843, 884, -1, 836, 843, 882, -1, 843, 783, 884, -1, 845, 885, 833, -1, 877, 885, 845, -1, 885, 828, 833, -1, 885, 886, 828, -1, 828, 887, 786, -1, 886, 887, 828, -1, 786, 888, 846, -1, 887, 888, 786, -1, 787, 846, 888, -1, 787, 888, 889, -1, 785, 889, 890, -1, 785, 787, 889, -1, 812, 890, 891, -1, 812, 785, 890, -1, 819, 891, 892, -1, 819, 812, 891, -1, 805, 892, 893, -1, 805, 819, 892, -1, 803, 893, 894, -1, 803, 805, 893, -1, 804, 894, 895, -1, 804, 803, 894, -1, 804, 884, 783, -1, 895, 884, 804, -1, 877, 886, 885, -1, 888, 886, 877, -1, 887, 886, 888, -1, 878, 888, 877, -1, 889, 888, 878, -1, 879, 889, 878, -1, 890, 889, 879, -1, 880, 890, 879, -1, 891, 890, 880, -1, 881, 892, 891, -1, 881, 891, 880, -1, 882, 893, 892, -1, 882, 892, 881, -1, 883, 894, 893, -1, 883, 893, 882, -1, 884, 895, 894, -1, 884, 894, 883, -1, 827, 826, 896, -1, 896, 826, 897, -1, 897, 831, 898, -1, 826, 831, 897, -1, 898, 821, 899, -1, 831, 821, 898, -1, 899, 789, 900, -1, 821, 789, 899, -1, 900, 775, 901, -1, 789, 775, 900, -1, 901, 777, 902, -1, 775, 777, 901, -1, 902, 837, 903, -1, 777, 837, 902, -1, 827, 904, 825, -1, 896, 904, 827, -1, 904, 807, 825, -1, 904, 905, 807, -1, 905, 794, 807, -1, 905, 906, 794, -1, 794, 907, 814, -1, 906, 907, 794, -1, 814, 907, 908, -1, 813, 908, 909, -1, 813, 814, 908, -1, 810, 909, 910, -1, 810, 813, 909, -1, 801, 910, 911, -1, 801, 810, 910, -1, 800, 911, 912, -1, 800, 801, 911, -1, 795, 912, 913, -1, 795, 800, 912, -1, 842, 795, 913, -1, 832, 913, 914, -1, 832, 842, 913, -1, 914, 837, 832, -1, 914, 903, 837, -1, 913, 903, 914, -1, 902, 903, 913, -1, 912, 902, 913, -1, 901, 902, 912, -1, 911, 901, 912, -1, 900, 901, 911, -1, 910, 900, 911, -1, 907, 906, 905, -1, 899, 910, 909, -1, 899, 900, 910, -1, 896, 907, 905, -1, 898, 909, 908, -1, 898, 899, 909, -1, 897, 908, 907, -1, 897, 907, 896, -1, 897, 898, 908, -1, 904, 896, 905, -1, 784, 780, 915, -1, 915, 780, 916, -1, 916, 780, 917, -1, 917, 839, 918, -1, 780, 839, 917, -1, 918, 823, 919, -1, 839, 823, 918, -1, 919, 815, 920, -1, 823, 815, 919, -1, 920, 808, 921, -1, 815, 808, 920, -1, 808, 790, 921, -1, 921, 802, 922, -1, 790, 802, 921, -1, 784, 923, 778, -1, 915, 923, 784, -1, 778, 924, 816, -1, 923, 924, 778, -1, 924, 791, 816, -1, 924, 925, 791, -1, 791, 926, 799, -1, 925, 926, 791, -1, 798, 799, 926, -1, 798, 927, 928, -1, 798, 926, 927, -1, 797, 928, 929, -1, 797, 798, 928, -1, 796, 929, 930, -1, 796, 797, 929, -1, 792, 930, 931, -1, 792, 796, 930, -1, 793, 931, 932, -1, 793, 792, 931, -1, 844, 932, 933, -1, 844, 793, 932, -1, 811, 844, 933, -1, 933, 802, 811, -1, 933, 922, 802, -1, 932, 921, 922, -1, 933, 932, 922, -1, 931, 920, 921, -1, 931, 921, 932, -1, 930, 919, 920, -1, 930, 920, 931, -1, 929, 918, 919, -1, 929, 919, 930, -1, 928, 917, 918, -1, 928, 918, 929, -1, 927, 916, 917, -1, 927, 917, 928, -1, 926, 915, 916, -1, 926, 916, 927, -1, 924, 926, 925, -1, 924, 923, 915, -1, 924, 915, 926, -1, 934, 935, 936, -1, 937, 938, 939, -1, 934, 938, 935, -1, 939, 938, 934, -1, 940, 941, 942, -1, 935, 941, 940, -1, 938, 941, 935, -1, 943, 944, 937, -1, 937, 944, 938, -1, 938, 944, 941, -1, 945, 946, 947, -1, 942, 948, 949, -1, 944, 948, 941, -1, 941, 948, 942, -1, 950, 939, 951, -1, 943, 952, 944, -1, 953, 952, 943, -1, 944, 952, 948, -1, 949, 954, 955, -1, 948, 954, 949, -1, 952, 956, 948, -1, 953, 956, 952, -1, 957, 956, 953, -1, 948, 956, 954, -1, 955, 958, 959, -1, 956, 958, 954, -1, 954, 958, 955, -1, 956, 960, 958, -1, 961, 960, 957, -1, 957, 960, 956, -1, 959, 962, 963, -1, 958, 962, 959, -1, 960, 962, 958, -1, 964, 965, 961, -1, 961, 965, 960, -1, 960, 965, 962, -1, 963, 966, 967, -1, 962, 966, 963, -1, 968, 969, 964, -1, 962, 969, 966, -1, 964, 969, 965, -1, 965, 969, 962, -1, 969, 970, 966, -1, 967, 970, 971, -1, 966, 970, 967, -1, 972, 973, 968, -1, 968, 973, 969, -1, 969, 973, 970, -1, 970, 974, 971, -1, 973, 974, 970, -1, 971, 974, 975, -1, 976, 977, 972, -1, 972, 977, 973, -1, 973, 977, 974, -1, 974, 978, 975, -1, 975, 978, 979, -1, 980, 981, 976, -1, 976, 981, 977, -1, 977, 981, 974, -1, 974, 981, 978, -1, 979, 982, 983, -1, 978, 982, 979, -1, 981, 982, 978, -1, 984, 985, 980, -1, 980, 985, 981, -1, 981, 985, 982, -1, 983, 986, 987, -1, 982, 986, 983, -1, 988, 989, 984, -1, 984, 989, 985, -1, 985, 989, 982, -1, 982, 989, 986, -1, 987, 990, 991, -1, 986, 990, 987, -1, 989, 990, 986, -1, 992, 993, 988, -1, 988, 993, 989, -1, 989, 993, 990, -1, 994, 995, 996, -1, 991, 995, 994, -1, 994, 996, 997, -1, 990, 995, 991, -1, 996, 998, 999, -1, 1000, 998, 992, -1, 999, 998, 1000, -1, 993, 998, 990, -1, 995, 998, 996, -1, 992, 998, 993, -1, 1000, 1001, 999, -1, 990, 998, 995, -1, 945, 936, 946, -1, 945, 934, 936, -1, 951, 934, 945, -1, 939, 934, 951, -1, 936, 935, 946, -1, 946, 935, 940, -1, 1002, 1003, 1004, -1, 1002, 1005, 1003, -1, 1006, 1007, 1008, -1, 1009, 1010, 1011, -1, 1006, 1008, 1012, -1, 1013, 1014, 1015, -1, 1013, 1016, 1014, -1, 1017, 1018, 1005, -1, 1017, 1005, 1002, -1, 1019, 1007, 1006, -1, 1019, 1020, 1007, -1, 1021, 1012, 1016, -1, 1021, 1016, 1013, -1, 1022, 1018, 1017, -1, 1022, 1023, 1018, -1, 1024, 1020, 1019, -1, 1024, 1004, 1020, -1, 1025, 1012, 1021, -1, 1025, 1006, 1012, -1, 1026, 1023, 1022, -1, 1026, 1027, 1028, -1, 1026, 1028, 1023, -1, 1029, 1004, 1024, -1, 1029, 1002, 1004, -1, 1030, 1015, 1031, -1, 1030, 1013, 1015, -1, 1032, 1019, 1006, -1, 1032, 1006, 1025, -1, 1033, 1002, 1029, -1, 1033, 1017, 1002, -1, 1034, 1021, 1013, -1, 1034, 1013, 1030, -1, 1035, 1024, 1019, -1, 1035, 1019, 1032, -1, 1036, 1022, 1017, -1, 1036, 1017, 1033, -1, 1037, 1021, 1034, -1, 1037, 1025, 1021, -1, 1038, 1029, 1024, -1, 1038, 1024, 1035, -1, 1039, 1026, 1022, -1, 1039, 1027, 1026, -1, 1039, 1022, 1036, -1, 1039, 1040, 1027, -1, 1041, 1030, 1031, -1, 1042, 1025, 1037, -1, 1042, 1032, 1025, -1, 1043, 1033, 1029, -1, 1043, 1029, 1038, -1, 1044, 1034, 1030, -1, 1044, 1030, 1041, -1, 1045, 1031, 1046, -1, 1045, 1041, 1031, -1, 1047, 1035, 1032, -1, 1047, 1032, 1042, -1, 1048, 1036, 1033, -1, 1048, 1033, 1043, -1, 1049, 1037, 1034, -1, 1049, 1034, 1044, -1, 1050, 1044, 1041, -1, 1050, 1041, 1045, -1, 1051, 1052, 1053, -1, 1054, 1038, 1035, -1, 1054, 1035, 1047, -1, 1055, 1056, 1040, -1, 1055, 1039, 1036, -1, 1055, 1040, 1039, -1, 1055, 1036, 1048, -1, 1057, 1045, 1046, -1, 1058, 1042, 1037, -1, 1058, 1037, 1049, -1, 1059, 1044, 1050, -1, 1059, 1049, 1044, -1, 1060, 1038, 1054, -1, 1060, 1043, 1038, -1, 1061, 1050, 1045, -1, 1061, 1045, 1057, -1, 1062, 1042, 1058, -1, 1063, 1009, 1064, -1, 1062, 1047, 1042, -1, 1063, 1010, 1009, -1, 1065, 1058, 1049, -1, 1065, 1049, 1059, -1, 1066, 1067, 1010, -1, 1068, 1046, 1069, -1, 1068, 1057, 1046, -1, 1066, 1010, 1063, -1, 1070, 1048, 1043, -1, 1071, 1067, 1066, -1, 1071, 1072, 1067, -1, 1070, 1043, 1060, -1, 1073, 1064, 1074, -1, 1075, 1059, 1050, -1, 1075, 1050, 1061, -1, 1073, 1063, 1064, -1, 1076, 1047, 1062, -1, 1077, 1078, 1072, -1, 1076, 1054, 1047, -1, 1077, 1072, 1071, -1, 1079, 1062, 1058, -1, 1079, 1058, 1065, -1, 1080, 1063, 1073, -1, 1081, 1057, 1068, -1, 1080, 1066, 1063, -1, 1081, 1061, 1057, -1, 1082, 1083, 1078, -1, 1084, 1085, 1056, -1, 1084, 1056, 1055, -1, 1084, 1055, 1048, -1, 1084, 1048, 1070, -1, 1082, 1078, 1077, -1, 1086, 1068, 1069, -1, 1087, 1071, 1066, -1, 1087, 1066, 1080, -1, 1088, 1065, 1059, -1, 1088, 1059, 1075, -1, 1089, 1090, 1083, -1, 1089, 1083, 1082, -1, 1091, 1054, 1076, -1, 1092, 1073, 1074, -1, 1091, 1060, 1054, -1, 1093, 1062, 1079, -1, 1094, 1077, 1071, -1, 1093, 1076, 1062, -1, 1095, 1061, 1081, -1, 1094, 1071, 1087, -1, 1096, 1090, 1089, -1, 1095, 1075, 1061, -1, 1097, 1081, 1068, -1, 1096, 1098, 1090, -1, 1097, 1068, 1086, -1, 1099, 1073, 1092, -1, 1100, 1065, 1088, -1, 1100, 1079, 1065, -1, 1099, 1080, 1073, -1, 1101, 1074, 1102, -1, 1103, 1070, 1060, -1, 1101, 1092, 1074, -1, 1103, 1060, 1091, -1, 1104, 1076, 1093, -1, 1105, 1077, 1094, -1, 1104, 1091, 1076, -1, 1105, 1082, 1077, -1, 1106, 1107, 1098, -1, 1108, 1088, 1075, -1, 1108, 1075, 1095, -1, 1106, 1098, 1096, -1, 1109, 1069, 1110, -1, 1109, 1086, 1069, -1, 1111, 1080, 1099, -1, 1112, 1095, 1081, -1, 1111, 1087, 1080, -1, 1112, 1081, 1097, -1, 1113, 1099, 1092, -1, 1113, 1092, 1101, -1, 1114, 1079, 1100, -1, 1115, 1089, 1082, -1, 1114, 1093, 1079, -1, 1116, 1084, 1070, -1, 1116, 1070, 1103, -1, 1116, 1117, 1085, -1, 1115, 1082, 1105, -1, 1118, 1107, 1106, -1, 1116, 1085, 1084, -1, 1118, 1119, 947, -1, 1120, 1103, 1091, -1, 1118, 1121, 1107, -1, 1120, 1091, 1104, -1, 1118, 947, 1121, -1, 1122, 1101, 1102, -1, 1123, 1100, 1088, -1, 1123, 1088, 1108, -1, 1124, 1094, 1087, -1, 1125, 1086, 1109, -1, 1124, 1087, 1111, -1, 1125, 1097, 1086, -1, 1126, 1111, 1099, -1, 1127, 1109, 1110, -1, 1126, 1099, 1113, -1, 1128, 1096, 1089, -1, 1128, 1089, 1115, -1, 1129, 1095, 1112, -1, 1129, 1108, 1095, -1, 1130, 1104, 1093, -1, 1130, 1093, 1114, -1, 1131, 1101, 1122, -1, 1131, 1113, 1101, -1, 1132, 1116, 1103, -1, 1133, 1094, 1124, -1, 1132, 1103, 1120, -1, 1133, 1105, 1094, -1, 1132, 1117, 1116, -1, 1134, 1100, 1123, -1, 1134, 1114, 1100, -1, 1135, 1124, 1111, -1, 1135, 1111, 1126, -1, 1136, 1102, 1137, -1, 1138, 1112, 1097, -1, 1138, 1097, 1125, -1, 1136, 1122, 1102, -1, 1139, 1096, 1128, -1, 1139, 1106, 1096, -1, 1140, 1125, 1109, -1, 1140, 1109, 1127, -1, 1141, 1126, 1113, -1, 1142, 1123, 1108, -1, 1141, 1113, 1131, -1, 1142, 1108, 1129, -1, 1143, 1104, 1130, -1, 1144, 1115, 1105, -1, 1143, 1120, 1104, -1, 1144, 1105, 1133, -1, 1145, 1130, 1114, -1, 1146, 1133, 1124, -1, 1146, 1124, 1135, -1, 1145, 1114, 1134, -1, 1147, 1112, 1138, -1, 1148, 1131, 1122, -1, 1147, 1129, 1112, -1, 1148, 1122, 1136, -1, 1149, 1150, 1119, -1, 1149, 1106, 1139, -1, 1149, 1118, 1106, -1, 1149, 1119, 1118, -1, 1151, 1138, 1125, -1, 1151, 1125, 1140, -1, 1152, 1136, 1137, -1, 1153, 1110, 1154, -1, 1155, 1126, 1141, -1, 1155, 1135, 1126, -1, 1153, 1127, 1110, -1, 1156, 1128, 1115, -1, 1157, 1134, 1123, -1, 1157, 1123, 1142, -1, 1156, 1115, 1144, -1, 1158, 1120, 1143, -1, 1158, 1159, 1117, -1, 1158, 1117, 1132, -1, 1158, 1132, 1120, -1, 1160, 1133, 1146, -1, 1160, 1144, 1133, -1, 1161, 1143, 1130, -1, 1161, 1130, 1145, -1, 1162, 1131, 1148, -1, 1163, 1129, 1147, -1, 1162, 1141, 1131, -1, 1164, 1148, 1136, -1, 1163, 1142, 1129, -1, 1164, 1136, 1152, -1, 1165, 1138, 1151, -1, 1166, 1135, 1155, -1, 1165, 1147, 1138, -1, 1167, 1127, 1153, -1, 1166, 1146, 1135, -1, 1168, 1139, 1128, -1, 1168, 1128, 1156, -1, 1167, 1140, 1127, -1, 1169, 1156, 1144, -1, 1169, 1144, 1160, -1, 1170, 1134, 1157, -1, 1170, 1145, 1134, -1, 1171, 1159, 1158, -1, 1172, 1141, 1162, -1, 1171, 1143, 1161, -1, 1171, 1158, 1143, -1, 1172, 1155, 1141, -1, 1173, 1137, 1174, -1, 1175, 1157, 1142, -1, 1173, 1152, 1137, -1, 1175, 1142, 1163, -1, 1176, 1147, 1165, -1, 1177, 1148, 1164, -1, 1177, 1162, 1148, -1, 1176, 1163, 1147, -1, 1178, 1146, 1166, -1, 1179, 1151, 1140, -1, 1178, 1160, 1146, -1, 1180, 1149, 1139, -1, 1180, 1150, 1149, -1, 1180, 1181, 1150, -1, 1180, 1139, 1168, -1, 1179, 1140, 1167, -1, 1182, 1168, 1156, -1, 1183, 1161, 1145, -1, 1182, 1156, 1169, -1, 1183, 1145, 1170, -1, 1184, 1170, 1157, -1, 1185, 1166, 1155, -1, 1184, 1157, 1175, -1, 1185, 1155, 1172, -1, 1186, 1175, 1163, -1, 1186, 1163, 1176, -1, 1187, 1164, 1152, -1, 1187, 1152, 1173, -1, 1188, 1173, 1174, -1, 1189, 1165, 1151, -1, 1190, 1172, 1162, -1, 1189, 1151, 1179, -1, 1190, 1162, 1177, -1, 1191, 1154, 1052, -1, 1192, 1169, 1160, -1, 1192, 1160, 1178, -1, 1191, 1052, 1051, -1, 1191, 1153, 1154, -1, 1193, 1180, 1168, -1, 1194, 1159, 1171, -1, 1193, 1168, 1182, -1, 1194, 1195, 1159, -1, 1193, 1181, 1180, -1, 1194, 1161, 1183, -1, 1194, 1171, 1161, -1, 1196, 1178, 1166, -1, 1196, 1166, 1185, -1, 1197, 1183, 1170, -1, 1197, 1170, 1184, -1, 1198, 1164, 1187, -1, 1199, 1175, 1186, -1, 1198, 1177, 1164, -1, 1199, 1184, 1175, -1, 1200, 1176, 1165, -1, 1201, 1173, 1188, -1, 1201, 1187, 1173, -1, 1202, 1172, 1190, -1, 1200, 1165, 1189, -1, 1202, 1185, 1172, -1, 1203, 1051, 1204, -1, 1203, 1191, 1051, -1, 1205, 1182, 1169, -1, 1203, 1167, 1153, -1, 1205, 1169, 1192, -1, 1203, 1153, 1191, -1, 1206, 1183, 1197, -1, 1206, 1194, 1183, -1, 1207, 1178, 1196, -1, 1207, 1192, 1178, -1, 1206, 1195, 1194, -1, 1208, 1177, 1198, -1, 1209, 1197, 1184, -1, 1208, 1190, 1177, -1, 1209, 1184, 1199, -1, 1210, 1186, 1176, -1, 1210, 1176, 1200, -1, 1211, 1198, 1187, -1, 1212, 1167, 1203, -1, 1211, 1187, 1201, -1, 1212, 1204, 1213, -1, 1214, 1174, 1215, -1, 1212, 1179, 1167, -1, 1214, 1188, 1174, -1, 1212, 1203, 1204, -1, 1216, 1185, 1202, -1, 1216, 1196, 1185, -1, 1217, 1218, 1195, -1, 1217, 1195, 1206, -1, 1217, 1206, 1197, -1, 1219, 1220, 1181, -1, 1217, 1197, 1209, -1, 1219, 1181, 1193, -1, 1219, 1193, 1182, -1, 1221, 1199, 1186, -1, 1219, 1182, 1205, -1, 1221, 1186, 1210, -1, 1222, 1205, 1192, -1, 1222, 1192, 1207, -1, 1223, 1213, 1224, -1, 1225, 1190, 1208, -1, 1225, 1202, 1190, -1, 1223, 1189, 1179, -1, 1223, 1179, 1212, -1, 1223, 1212, 1213, -1, 1226, 1208, 1198, -1, 1226, 1198, 1211, -1, 1227, 1199, 1221, -1, 1227, 1209, 1199, -1, 1228, 1224, 1229, -1, 1230, 1201, 1188, -1, 1228, 1189, 1223, -1, 1230, 1188, 1214, -1, 1228, 1200, 1189, -1, 1228, 1223, 1224, -1, 1231, 1196, 1216, -1, 1231, 1207, 1196, -1, 1232, 1209, 1227, -1, 1232, 1233, 1218, -1, 1232, 1218, 1217, -1, 1234, 1220, 1219, -1, 1232, 1217, 1209, -1, 1234, 1205, 1222, -1, 1235, 1229, 1236, -1, 1234, 1219, 1205, -1, 1237, 1202, 1225, -1, 1235, 1200, 1228, -1, 1235, 1210, 1200, -1, 1237, 1216, 1202, -1, 1235, 1228, 1229, -1, 1238, 1235, 1236, -1, 1238, 1236, 1239, -1, 1240, 1208, 1226, -1, 1240, 1225, 1208, -1, 1238, 1210, 1235, -1, 1238, 1221, 1210, -1, 1241, 1238, 1239, -1, 1241, 1221, 1238, -1, 1242, 1201, 1230, -1, 1241, 1239, 1243, -1, 1242, 1211, 1201, -1, 1244, 1222, 1207, -1, 1241, 1227, 1221, -1, 1245, 1233, 1232, -1, 1245, 1241, 1243, -1, 1244, 1207, 1231, -1, 1245, 1227, 1241, -1, 1245, 1243, 1246, -1, 1247, 1231, 1216, -1, 1245, 1246, 997, -1, 1247, 1216, 1237, -1, 1245, 997, 1233, -1, 1245, 1232, 1227, -1, 1248, 1237, 1225, -1, 1248, 1225, 1240, -1, 1249, 1226, 1211, -1, 1249, 1211, 1242, -1, 1250, 1215, 1251, -1, 1250, 1214, 1215, -1, 1252, 1220, 1234, -1, 1252, 1253, 1220, -1, 1252, 1234, 1222, -1, 1252, 1222, 1244, -1, 1254, 1231, 1247, -1, 1254, 1244, 1231, -1, 1255, 1247, 1237, -1, 1255, 1237, 1248, -1, 1003, 1226, 1249, -1, 1003, 1240, 1226, -1, 1008, 1230, 1214, -1, 1008, 1214, 1250, -1, 1256, 1244, 1254, -1, 1256, 1253, 1252, -1, 1256, 1252, 1244, -1, 1257, 1254, 1247, -1, 1257, 1247, 1255, -1, 1005, 1240, 1003, -1, 1005, 1248, 1240, -1, 1007, 1242, 1230, -1, 1007, 1230, 1008, -1, 1258, 1259, 1253, -1, 1258, 1254, 1257, -1, 1258, 1256, 1254, -1, 1258, 1253, 1256, -1, 1018, 1255, 1248, -1, 1018, 1248, 1005, -1, 1020, 1249, 1242, -1, 1020, 1242, 1007, -1, 1016, 1251, 1260, -1, 1016, 1260, 1014, -1, 1016, 1250, 1251, -1, 1023, 1257, 1255, -1, 1023, 1255, 1018, -1, 1004, 1249, 1020, -1, 1004, 1003, 1249, -1, 1012, 1008, 1250, -1, 1012, 1250, 1016, -1, 1028, 1027, 1259, -1, 1028, 1259, 1258, -1, 1028, 1258, 1257, -1, 1028, 1257, 1023, -1, 1261, 1262, 1263, -1, 1264, 1262, 1261, -1, 1265, 1266, 1267, -1, 1263, 1268, 1269, -1, 1270, 1271, 1053, -1, 1269, 1268, 1272, -1, 1053, 1271, 1273, -1, 1274, 1275, 1266, -1, 1276, 1275, 1274, -1, 1277, 1278, 1279, -1, 1272, 1278, 1277, -1, 1280, 1281, 1270, -1, 1282, 1283, 1284, -1, 1270, 1281, 1271, -1, 1284, 1283, 1276, -1, 1285, 1286, 1287, -1, 1287, 1286, 1262, -1, 1276, 1283, 1275, -1, 1263, 1286, 1268, -1, 1262, 1286, 1263, -1, 1288, 1289, 1290, -1, 1267, 1291, 1292, -1, 1293, 1289, 1280, -1, 1290, 1289, 1293, -1, 1266, 1291, 1267, -1, 1268, 1294, 1272, -1, 1280, 1289, 1281, -1, 1272, 1294, 1278, -1, 1273, 1295, 1296, -1, 1275, 1297, 1266, -1, 1278, 1298, 1279, -1, 1271, 1295, 1273, -1, 1266, 1297, 1291, -1, 1281, 1299, 1271, -1, 1282, 1300, 1283, -1, 1301, 1300, 1282, -1, 1285, 1302, 1286, -1, 1268, 1302, 1294, -1, 1271, 1299, 1295, -1, 1286, 1302, 1268, -1, 1283, 1300, 1275, -1, 1275, 1300, 1297, -1, 1291, 1303, 1292, -1, 1304, 1305, 1288, -1, 1294, 1306, 1278, -1, 1288, 1305, 1289, -1, 1292, 1303, 1307, -1, 1278, 1306, 1298, -1, 1289, 1305, 1281, -1, 1281, 1305, 1299, -1, 1279, 1308, 1309, -1, 1298, 1308, 1279, -1, 1296, 1310, 1311, -1, 1291, 1312, 1303, -1, 1297, 1312, 1291, -1, 1295, 1310, 1296, -1, 1313, 1314, 1285, -1, 1285, 1314, 1302, -1, 1299, 1315, 1295, -1, 1316, 1317, 1301, -1, 1294, 1314, 1306, -1, 1302, 1314, 1294, -1, 1301, 1317, 1300, -1, 1300, 1317, 1297, -1, 1295, 1315, 1310, -1, 1297, 1317, 1312, -1, 1306, 1318, 1298, -1, 1319, 1320, 1304, -1, 1321, 1322, 1323, -1, 1298, 1318, 1308, -1, 1304, 1320, 1305, -1, 1305, 1320, 1299, -1, 1307, 1322, 1321, -1, 1299, 1320, 1315, -1, 1303, 1322, 1307, -1, 1323, 1324, 1325, -1, 1308, 1326, 1309, -1, 1314, 1327, 1306, -1, 1311, 1328, 1329, -1, 1303, 1324, 1322, -1, 1312, 1324, 1303, -1, 1313, 1327, 1314, -1, 1310, 1328, 1311, -1, 1322, 1324, 1323, -1, 1306, 1327, 1318, -1, 1312, 1330, 1324, -1, 1318, 1331, 1308, -1, 1325, 1330, 1332, -1, 1315, 1333, 1310, -1, 1332, 1330, 1334, -1, 1310, 1333, 1328, -1, 1335, 1330, 1316, -1, 1334, 1330, 1335, -1, 1316, 1330, 1317, -1, 1308, 1331, 1326, -1, 1317, 1330, 1312, -1, 1319, 1336, 1320, -1, 1324, 1330, 1325, -1, 1326, 1337, 1309, -1, 1338, 1336, 1319, -1, 1315, 1336, 1333, -1, 1309, 1337, 1339, -1, 1320, 1336, 1315, -1, 1327, 1340, 1318, -1, 1318, 1340, 1331, -1, 1329, 1341, 1342, -1, 1313, 1340, 1327, -1, 1343, 1340, 1313, -1, 1331, 1344, 1326, -1, 1328, 1341, 1329, -1, 1326, 1344, 1337, -1, 1342, 1345, 1346, -1, 1341, 1345, 1342, -1, 1337, 1347, 1339, -1, 1333, 1348, 1328, -1, 1328, 1348, 1341, -1, 1340, 1349, 1331, -1, 1331, 1349, 1344, -1, 1343, 1349, 1340, -1, 1348, 1350, 1341, -1, 1341, 1350, 1345, -1, 1344, 1351, 1337, -1, 1352, 1353, 1338, -1, 1336, 1353, 1333, -1, 1338, 1353, 1336, -1, 1337, 1351, 1347, -1, 1333, 1353, 1348, -1, 1345, 1354, 1346, -1, 1347, 1355, 1339, -1, 1339, 1355, 1356, -1, 1353, 1357, 1348, -1, 1358, 1359, 1343, -1, 1344, 1359, 1351, -1, 1343, 1359, 1349, -1, 1348, 1357, 1350, -1, 1349, 1359, 1344, -1, 1352, 1357, 1353, -1, 1346, 1360, 1361, -1, 1354, 1360, 1346, -1, 1355, 1362, 1356, -1, 1345, 1363, 1354, -1, 1351, 1364, 1347, -1, 1350, 1363, 1345, -1, 1347, 1364, 1355, -1, 1355, 1365, 1362, -1, 1363, 1366, 1354, -1, 1354, 1366, 1360, -1, 1364, 1365, 1355, -1, 1367, 1368, 1352, -1, 1357, 1368, 1350, -1, 1358, 1369, 1359, -1, 1350, 1368, 1363, -1, 1359, 1369, 1351, -1, 1352, 1368, 1357, -1, 1351, 1369, 1364, -1, 1360, 1370, 1361, -1, 1356, 1371, 1265, -1, 1362, 1371, 1356, -1, 1368, 1372, 1363, -1, 1363, 1372, 1366, -1, 1373, 1374, 1358, -1, 1367, 1372, 1368, -1, 1358, 1374, 1369, -1, 1364, 1374, 1365, -1, 1369, 1374, 1364, -1, 1366, 1261, 1360, -1, 1360, 1261, 1370, -1, 1371, 1274, 1265, -1, 1365, 1375, 1362, -1, 1361, 1269, 1277, -1, 1370, 1269, 1361, -1, 1362, 1375, 1371, -1, 1287, 1264, 1367, -1, 1366, 1264, 1261, -1, 1372, 1264, 1366, -1, 1367, 1264, 1372, -1, 1321, 1323, 1011, -1, 1371, 1276, 1274, -1, 1375, 1276, 1371, -1, 1261, 1263, 1370, -1, 1373, 1376, 1374, -1, 1374, 1376, 1365, -1, 1370, 1263, 1269, -1, 1365, 1376, 1375, -1, 1282, 1284, 1373, -1, 1269, 1272, 1277, -1, 1373, 1284, 1376, -1, 1375, 1284, 1276, -1, 1376, 1284, 1375, -1, 1274, 1266, 1265, -1, 1287, 1262, 1264, -1, 1334, 1377, 1378, -1, 1379, 1378, 1380, -1, 1379, 1334, 1378, -1, 1381, 1380, 1382, -1, 1381, 1379, 1380, -1, 1383, 1382, 1384, -1, 1383, 1381, 1382, -1, 1385, 1384, 1386, -1, 1385, 1383, 1384, -1, 1387, 1386, 1388, -1, 1387, 1385, 1386, -1, 1389, 1388, 1390, -1, 1389, 1387, 1388, -1, 1391, 1390, 1392, -1, 1391, 1389, 1390, -1, 1393, 1392, 1394, -1, 1393, 1391, 1392, -1, 1395, 1394, 1396, -1, 1395, 1393, 1394, -1, 1397, 1396, 1398, -1, 1397, 1395, 1396, -1, 1399, 1398, 1400, -1, 1399, 1397, 1398, -1, 1401, 1400, 1402, -1, 1401, 1399, 1400, -1, 1403, 1402, 1404, -1, 1403, 1401, 1402, -1, 1405, 1404, 1406, -1, 1405, 1403, 1404, -1, 1407, 1406, 1408, -1, 1407, 1405, 1406, -1, 1409, 1407, 1408, -1, 1409, 1408, 1410, -1, 1290, 1409, 1410, -1, 1411, 1412, 1413, -1, 1377, 1414, 1412, -1, 1377, 1415, 1414, -1, 1377, 1416, 1415, -1, 1377, 1417, 1416, -1, 1377, 1418, 1417, -1, 1377, 1412, 1411, -1, 1419, 1411, 1420, -1, 1419, 1377, 1411, -1, 1380, 1378, 1377, -1, 1421, 1377, 1419, -1, 1382, 1380, 1377, -1, 1384, 1382, 1377, -1, 1422, 1421, 1423, -1, 1422, 1377, 1421, -1, 1386, 1384, 1377, -1, 1424, 1377, 1422, -1, 1388, 1386, 1377, -1, 1390, 1388, 1377, -1, 1425, 1424, 1426, -1, 1425, 1377, 1424, -1, 1392, 1390, 1377, -1, 1394, 1392, 1377, -1, 1408, 1425, 1410, -1, 1406, 1377, 1425, -1, 1406, 1425, 1408, -1, 1398, 1396, 1394, -1, 1404, 1377, 1406, -1, 1400, 1394, 1377, -1, 1400, 1398, 1394, -1, 1402, 1377, 1404, -1, 1402, 1400, 1377, -1, 1288, 1290, 1410, -1, 1288, 1410, 1425, -1, 1304, 1425, 1426, -1, 1304, 1288, 1425, -1, 1319, 1426, 1424, -1, 1319, 1304, 1426, -1, 1338, 1424, 1422, -1, 1338, 1319, 1424, -1, 1352, 1422, 1423, -1, 1352, 1338, 1422, -1, 1367, 1423, 1421, -1, 1367, 1352, 1423, -1, 1287, 1421, 1419, -1, 1287, 1367, 1421, -1, 1285, 1419, 1420, -1, 1285, 1287, 1419, -1, 1313, 1420, 1411, -1, 1313, 1285, 1420, -1, 1343, 1411, 1413, -1, 1343, 1313, 1411, -1, 1358, 1413, 1412, -1, 1358, 1343, 1413, -1, 1373, 1412, 1414, -1, 1373, 1358, 1412, -1, 1282, 1414, 1415, -1, 1282, 1373, 1414, -1, 1301, 1415, 1416, -1, 1301, 1282, 1415, -1, 1316, 1416, 1417, -1, 1316, 1301, 1416, -1, 1335, 1316, 1417, -1, 1335, 1417, 1418, -1, 1335, 1418, 1377, -1, 1334, 1335, 1377, -1, 1409, 1290, 1293, -1, 1427, 1428, 1429, -1, 1429, 1428, 1430, -1, 1323, 1431, 1011, -1, 1432, 1433, 1434, -1, 1435, 1433, 1432, -1, 1251, 1436, 1260, -1, 1011, 1431, 1009, -1, 1430, 1436, 1251, -1, 1009, 1431, 1064, -1, 1403, 1437, 1438, -1, 1438, 1437, 1435, -1, 1393, 1439, 1391, -1, 1325, 1440, 1323, -1, 1391, 1439, 1441, -1, 1435, 1437, 1433, -1, 1427, 1439, 1428, -1, 1441, 1439, 1427, -1, 1323, 1440, 1431, -1, 1069, 1442, 1110, -1, 1379, 1443, 1334, -1, 1434, 1442, 1069, -1, 1325, 1443, 1440, -1, 1428, 1444, 1430, -1, 1332, 1443, 1325, -1, 1430, 1444, 1436, -1, 1334, 1443, 1332, -1, 1433, 1445, 1434, -1, 1436, 1446, 1260, -1, 1064, 1447, 1074, -1, 1434, 1445, 1442, -1, 1405, 1448, 1403, -1, 1431, 1447, 1064, -1, 1393, 1449, 1439, -1, 1403, 1448, 1437, -1, 1428, 1449, 1444, -1, 1440, 1450, 1431, -1, 1437, 1448, 1433, -1, 1439, 1449, 1428, -1, 1433, 1448, 1445, -1, 1431, 1450, 1447, -1, 1442, 1451, 1110, -1, 1444, 1452, 1436, -1, 1381, 1453, 1379, -1, 1110, 1451, 1154, -1, 1436, 1452, 1446, -1, 1379, 1453, 1443, -1, 1443, 1453, 1440, -1, 1440, 1453, 1450, -1, 1260, 1454, 1014, -1, 1446, 1454, 1260, -1, 1442, 1455, 1451, -1, 1074, 1456, 1102, -1, 1445, 1455, 1442, -1, 1395, 1457, 1393, -1, 1393, 1457, 1449, -1, 1447, 1456, 1074, -1, 1407, 1458, 1405, -1, 1444, 1457, 1452, -1, 1449, 1457, 1444, -1, 1405, 1458, 1448, -1, 1450, 1459, 1447, -1, 1448, 1458, 1445, -1, 1445, 1458, 1455, -1, 1447, 1459, 1456, -1, 1052, 1460, 1270, -1, 1452, 1461, 1446, -1, 1154, 1460, 1052, -1, 1383, 1462, 1381, -1, 1446, 1461, 1454, -1, 1381, 1462, 1453, -1, 1453, 1462, 1450, -1, 1451, 1460, 1154, -1, 1450, 1462, 1459, -1, 1460, 1463, 1270, -1, 1454, 1464, 1014, -1, 1270, 1463, 1280, -1, 1457, 1465, 1452, -1, 1456, 1466, 1102, -1, 1455, 1463, 1451, -1, 1395, 1465, 1457, -1, 1451, 1463, 1460, -1, 1452, 1465, 1461, -1, 1455, 1467, 1463, -1, 1463, 1467, 1280, -1, 1461, 1468, 1454, -1, 1456, 1469, 1466, -1, 1409, 1467, 1407, -1, 1293, 1467, 1409, -1, 1280, 1467, 1293, -1, 1407, 1467, 1458, -1, 1459, 1469, 1456, -1, 1458, 1467, 1455, -1, 1454, 1468, 1464, -1, 1385, 1470, 1383, -1, 1464, 1471, 1014, -1, 1459, 1470, 1469, -1, 1383, 1470, 1462, -1, 1014, 1471, 1015, -1, 1462, 1470, 1459, -1, 1465, 1472, 1461, -1, 1461, 1472, 1468, -1, 1102, 1473, 1137, -1, 1395, 1472, 1465, -1, 1397, 1472, 1395, -1, 1466, 1473, 1102, -1, 1468, 1474, 1464, -1, 1464, 1474, 1471, -1, 1137, 1475, 1174, -1, 1473, 1475, 1137, -1, 1466, 1476, 1473, -1, 1469, 1476, 1466, -1, 1471, 1477, 1015, -1, 1472, 1478, 1468, -1, 1397, 1478, 1472, -1, 1473, 1479, 1475, -1, 1468, 1478, 1474, -1, 1476, 1479, 1473, -1, 1387, 1480, 1385, -1, 1474, 1481, 1471, -1, 1470, 1480, 1469, -1, 1385, 1480, 1470, -1, 1471, 1481, 1477, -1, 1469, 1480, 1476, -1, 1477, 1482, 1015, -1, 1475, 1483, 1174, -1, 1015, 1482, 1031, -1, 1480, 1484, 1476, -1, 1399, 1485, 1397, -1, 1397, 1485, 1478, -1, 1478, 1485, 1474, -1, 1387, 1484, 1480, -1, 1476, 1484, 1479, -1, 1474, 1485, 1481, -1, 1174, 1486, 1215, -1, 1483, 1486, 1174, -1, 1482, 1487, 1031, -1, 1475, 1488, 1483, -1, 1481, 1489, 1477, -1, 1479, 1488, 1475, -1, 1477, 1489, 1482, -1, 1482, 1490, 1487, -1, 1483, 1491, 1486, -1, 1488, 1491, 1483, -1, 1489, 1490, 1482, -1, 1389, 1492, 1387, -1, 1484, 1492, 1479, -1, 1479, 1492, 1488, -1, 1399, 1493, 1485, -1, 1485, 1493, 1481, -1, 1481, 1493, 1489, -1, 1387, 1492, 1484, -1, 1486, 1494, 1215, -1, 1031, 1495, 1046, -1, 1487, 1495, 1031, -1, 1389, 1496, 1492, -1, 1492, 1496, 1488, -1, 1401, 1497, 1399, -1, 1399, 1497, 1493, -1, 1488, 1496, 1491, -1, 1489, 1497, 1490, -1, 1493, 1497, 1489, -1, 1491, 1498, 1486, -1, 1486, 1498, 1494, -1, 1495, 1432, 1046, -1, 1490, 1499, 1487, -1, 1215, 1429, 1251, -1, 1494, 1429, 1215, -1, 1487, 1499, 1495, -1, 1391, 1500, 1389, -1, 1491, 1500, 1498, -1, 1496, 1500, 1491, -1, 1389, 1500, 1496, -1, 1495, 1435, 1432, -1, 1499, 1435, 1495, -1, 1052, 1270, 1053, -1, 1498, 1427, 1494, -1, 1401, 1501, 1497, -1, 1497, 1501, 1490, -1, 1494, 1427, 1429, -1, 1490, 1501, 1499, -1, 1403, 1438, 1401, -1, 1429, 1430, 1251, -1, 1401, 1438, 1501, -1, 1499, 1438, 1435, -1, 1501, 1438, 1499, -1, 1432, 1434, 1046, -1, 1391, 1441, 1500, -1, 1498, 1441, 1427, -1, 1500, 1441, 1498, -1, 1046, 1434, 1069, -1, 1502, 1503, 1504, -1, 1502, 1504, 1505, -1, 1506, 1507, 1508, -1, 1506, 1508, 1509, -1, 1510, 1279, 1309, -1, 1510, 1511, 1279, -1, 1512, 1513, 1503, -1, 1512, 1503, 1502, -1, 1514, 1515, 1507, -1, 1514, 1507, 1506, -1, 1516, 1511, 1510, -1, 1516, 1509, 1511, -1, 1517, 1518, 1513, -1, 1517, 1513, 1512, -1, 1519, 1515, 1514, -1, 1519, 1505, 1515, -1, 1520, 1509, 1516, -1, 1520, 1506, 1509, -1, 1521, 1518, 1517, -1, 1521, 971, 975, -1, 1521, 1522, 1518, -1, 1521, 975, 1522, -1, 1523, 1505, 1519, -1, 1523, 1502, 1505, -1, 1524, 1309, 1339, -1, 1524, 1510, 1309, -1, 1525, 1506, 1520, -1, 1525, 1514, 1506, -1, 1526, 1512, 1502, -1, 1526, 1502, 1523, -1, 1527, 1510, 1524, -1, 1527, 1516, 1510, -1, 1528, 1514, 1525, -1, 1528, 1519, 1514, -1, 1529, 1512, 1526, -1, 1529, 1517, 1512, -1, 1530, 1520, 1516, -1, 1530, 1516, 1527, -1, 1531, 1523, 1519, -1, 1531, 1519, 1528, -1, 1532, 1521, 1517, -1, 1532, 971, 1521, -1, 1532, 1517, 1529, -1, 1532, 967, 971, -1, 1533, 1524, 1339, -1, 1533, 1339, 1356, -1, 1534, 1525, 1520, -1, 1534, 1520, 1530, -1, 1535, 1526, 1523, -1, 1535, 1523, 1531, -1, 1536, 1524, 1533, -1, 1536, 1527, 1524, -1, 1537, 1533, 1356, -1, 1537, 1356, 1265, -1, 1538, 1528, 1525, -1, 1538, 1525, 1534, -1, 1539, 1529, 1526, -1, 1539, 1526, 1535, -1, 1540, 1527, 1536, -1, 1540, 1530, 1527, -1, 1010, 1321, 1011, -1, 1541, 1533, 1537, -1, 1541, 1536, 1533, -1, 1542, 1528, 1538, -1, 1542, 1531, 1528, -1, 1543, 963, 967, -1, 1543, 1532, 1529, -1, 1543, 967, 1532, -1, 1543, 1529, 1539, -1, 1544, 1537, 1265, -1, 1545, 1534, 1530, -1, 1545, 1530, 1540, -1, 1546, 1540, 1536, -1, 1546, 1536, 1541, -1, 1547, 1535, 1531, -1, 1547, 1531, 1542, -1, 1548, 1537, 1544, -1, 1548, 1541, 1537, -1, 1549, 1051, 1053, -1, 1550, 1538, 1534, -1, 1549, 1053, 1273, -1, 1550, 1534, 1545, -1, 1551, 1204, 1051, -1, 1552, 1545, 1540, -1, 1552, 1540, 1546, -1, 1551, 1051, 1549, -1, 1553, 1265, 1267, -1, 1554, 1213, 1204, -1, 1553, 1544, 1265, -1, 1555, 1535, 1547, -1, 1554, 1204, 1551, -1, 1555, 1539, 1535, -1, 1556, 1273, 1296, -1, 1557, 1541, 1548, -1, 1556, 1549, 1273, -1, 1558, 1224, 1213, -1, 1557, 1546, 1541, -1, 1558, 1213, 1554, -1, 1559, 1538, 1550, -1, 1559, 1542, 1538, -1, 1560, 1545, 1552, -1, 1561, 1551, 1549, -1, 1560, 1550, 1545, -1, 1561, 1549, 1556, -1, 1562, 1544, 1553, -1, 1563, 1229, 1224, -1, 1562, 1548, 1544, -1, 1563, 1224, 1558, -1, 1564, 1539, 1555, -1, 1564, 959, 963, -1, 1564, 963, 1543, -1, 1564, 1543, 1539, -1, 1565, 1554, 1551, -1, 1566, 1553, 1267, -1, 1565, 1551, 1561, -1, 1567, 1546, 1557, -1, 1568, 1236, 1229, -1, 1567, 1552, 1546, -1, 1568, 1229, 1563, -1, 1569, 1542, 1559, -1, 1570, 1296, 1311, -1, 1570, 1556, 1296, -1, 1569, 1547, 1542, -1, 1571, 1559, 1550, -1, 1571, 1550, 1560, -1, 1572, 1558, 1554, -1, 1573, 1548, 1562, -1, 1572, 1554, 1565, -1, 1574, 1239, 1236, -1, 1574, 1236, 1568, -1, 1573, 1557, 1548, -1, 1575, 1553, 1566, -1, 1576, 1556, 1570, -1, 1575, 1562, 1553, -1, 1576, 1561, 1556, -1, 1577, 1552, 1567, -1, 1578, 1311, 1329, -1, 1577, 1560, 1552, -1, 1579, 1547, 1569, -1, 1578, 1570, 1311, -1, 1580, 1558, 1572, -1, 1579, 1555, 1547, -1, 1581, 1559, 1571, -1, 1580, 1563, 1558, -1, 1582, 1239, 1574, -1, 1581, 1569, 1559, -1, 1582, 1243, 1239, -1, 1583, 1567, 1557, -1, 1583, 1557, 1573, -1, 1584, 1267, 1292, -1, 1584, 1566, 1267, -1, 1585, 1561, 1576, -1, 1585, 1565, 1561, -1, 1586, 1573, 1562, -1, 1586, 1562, 1575, -1, 1587, 1576, 1570, -1, 1587, 1570, 1578, -1, 1588, 1571, 1560, -1, 1588, 1560, 1577, -1, 1589, 1568, 1563, -1, 1589, 1563, 1580, -1, 1590, 1564, 1555, -1, 1590, 959, 1564, -1, 1591, 1246, 1243, -1, 1590, 1555, 1579, -1, 1591, 997, 1246, -1, 1590, 955, 959, -1, 1591, 1243, 1582, -1, 1591, 994, 997, -1, 1592, 1579, 1569, -1, 1592, 1569, 1581, -1, 1593, 1578, 1329, -1, 1594, 1577, 1567, -1, 1595, 1572, 1565, -1, 1594, 1567, 1583, -1, 1595, 1565, 1585, -1, 1596, 1566, 1584, -1, 1597, 1585, 1576, -1, 1597, 1576, 1587, -1, 1596, 1575, 1566, -1, 1598, 1574, 1568, -1, 1599, 1584, 1292, -1, 1598, 1568, 1589, -1, 1600, 1583, 1573, -1, 1600, 1573, 1586, -1, 1601, 1581, 1571, -1, 1602, 1587, 1578, -1, 1601, 1571, 1588, -1, 1602, 1578, 1593, -1, 1603, 1590, 1579, -1, 1604, 1580, 1572, -1, 1603, 955, 1590, -1, 1603, 1579, 1592, -1, 1604, 1572, 1595, -1, 1605, 1588, 1577, -1, 1605, 1577, 1594, -1, 1606, 1585, 1597, -1, 1606, 1595, 1585, -1, 1607, 1586, 1575, -1, 1608, 1329, 1342, -1, 1607, 1575, 1596, -1, 1608, 1593, 1329, -1, 1609, 1574, 1598, -1, 1609, 1582, 1574, -1, 1610, 1596, 1584, -1, 1610, 1584, 1599, -1, 1611, 1597, 1587, -1, 1611, 1587, 1602, -1, 1612, 1594, 1583, -1, 1612, 1583, 1600, -1, 1613, 1581, 1601, -1, 1613, 1592, 1581, -1, 1614, 1580, 1604, -1, 1614, 1589, 1580, -1, 1615, 1604, 1595, -1, 1616, 1588, 1605, -1, 1615, 1595, 1606, -1, 1616, 1601, 1588, -1, 1617, 1602, 1593, -1, 1618, 1586, 1607, -1, 1617, 1593, 1608, -1, 1618, 1600, 1586, -1, 1619, 991, 994, -1, 1619, 1591, 1582, -1, 1619, 994, 1591, -1, 1619, 1582, 1609, -1, 1620, 1608, 1342, -1, 1621, 1607, 1596, -1, 1621, 1596, 1610, -1, 1622, 1292, 1307, -1, 1623, 1606, 1597, -1, 1623, 1597, 1611, -1, 1622, 1599, 1292, -1, 1624, 1598, 1589, -1, 1625, 1594, 1612, -1, 1624, 1589, 1614, -1, 1625, 1605, 1594, -1, 1626, 1592, 1613, -1, 1626, 949, 955, -1, 1626, 955, 1603, -1, 1627, 1604, 1615, -1, 1626, 1603, 1592, -1, 1627, 1614, 1604, -1, 1628, 1601, 1616, -1, 1628, 1613, 1601, -1, 1629, 1602, 1617, -1, 1629, 1611, 1602, -1, 1630, 1600, 1618, -1, 1631, 1617, 1608, -1, 1631, 1608, 1620, -1, 1630, 1612, 1600, -1, 1632, 1618, 1607, -1, 1632, 1607, 1621, -1, 1633, 1606, 1623, -1, 1633, 1615, 1606, -1, 1634, 1599, 1622, -1, 1635, 1598, 1624, -1, 1635, 1609, 1598, -1, 1636, 1624, 1614, -1, 1634, 1610, 1599, -1, 1637, 1616, 1605, -1, 1636, 1614, 1627, -1, 1638, 1611, 1629, -1, 1637, 1605, 1625, -1, 1639, 949, 1626, -1, 1639, 1613, 1628, -1, 1638, 1623, 1611, -1, 1639, 1626, 1613, -1, 1640, 1625, 1612, -1, 1641, 1620, 1342, -1, 1640, 1612, 1630, -1, 1641, 1342, 1346, -1, 1642, 1618, 1632, -1, 1643, 1617, 1631, -1, 1643, 1629, 1617, -1, 1644, 1615, 1633, -1, 1644, 1627, 1615, -1, 1642, 1630, 1618, -1, 1645, 1621, 1610, -1, 1645, 1610, 1634, -1, 1646, 1619, 1609, -1, 1646, 991, 1619, -1, 1646, 987, 991, -1, 1646, 1609, 1635, -1, 1647, 1635, 1624, -1, 1648, 1628, 1616, -1, 1648, 1616, 1637, -1, 1647, 1646, 1635, -1, 1647, 1624, 1636, -1, 1649, 1633, 1623, -1, 1649, 1623, 1638, -1, 1650, 1637, 1625, -1, 1650, 1625, 1640, -1, 1651, 1631, 1620, -1, 1651, 1620, 1641, -1, 1652, 1640, 1630, -1, 1652, 1630, 1642, -1, 1653, 1641, 1346, -1, 1654, 1638, 1629, -1, 1655, 1621, 1645, -1, 1654, 1629, 1643, -1, 1655, 1632, 1621, -1, 1656, 1627, 1644, -1, 1657, 1307, 1321, -1, 1656, 1636, 1627, -1, 1657, 1321, 1010, -1, 1658, 987, 1646, -1, 1658, 1646, 1647, -1, 1657, 1622, 1307, -1, 1659, 1628, 1648, -1, 1659, 1639, 1628, -1, 1659, 942, 949, -1, 1660, 1644, 1633, -1, 1660, 1633, 1649, -1, 1659, 949, 1639, -1, 1661, 1648, 1637, -1, 1661, 1637, 1650, -1, 1662, 1643, 1631, -1, 1662, 1631, 1651, -1, 1663, 1640, 1652, -1, 1663, 1650, 1640, -1, 1664, 1632, 1655, -1, 1664, 1642, 1632, -1, 1665, 1641, 1653, -1, 1665, 1651, 1641, -1, 1666, 1649, 1638, -1, 1666, 1638, 1654, -1, 1667, 1657, 1010, -1, 1667, 1634, 1622, -1, 1667, 1010, 1067, -1, 1668, 1636, 1656, -1, 1667, 1622, 1657, -1, 1668, 1647, 1636, -1, 1669, 1656, 1644, -1, 1669, 1644, 1660, -1, 1670, 1659, 1648, -1, 1670, 942, 1659, -1, 1670, 1648, 1661, -1, 1671, 1643, 1662, -1, 1672, 1650, 1663, -1, 1672, 1661, 1650, -1, 1671, 1654, 1643, -1, 1673, 1652, 1642, -1, 1674, 1662, 1651, -1, 1673, 1642, 1664, -1, 1674, 1651, 1665, -1, 1675, 1346, 1361, -1, 1676, 1067, 1072, -1, 1675, 1653, 1346, -1, 1676, 1645, 1634, -1, 1677, 1660, 1649, -1, 1676, 1667, 1067, -1, 1677, 1649, 1666, -1, 1676, 1634, 1667, -1, 1678, 940, 942, -1, 1679, 987, 1658, -1, 1678, 942, 1670, -1, 1679, 983, 987, -1, 1678, 1670, 1661, -1, 1679, 1658, 1647, -1, 1678, 1661, 1672, -1, 1679, 1647, 1668, -1, 1680, 1652, 1673, -1, 1680, 1663, 1652, -1, 1681, 1668, 1656, -1, 1681, 1656, 1669, -1, 1682, 1072, 1078, -1, 1683, 1666, 1654, -1, 1682, 1645, 1676, -1, 1683, 1654, 1671, -1, 1682, 1655, 1645, -1, 1682, 1676, 1072, -1, 1684, 1671, 1662, -1, 1684, 1662, 1674, -1, 1685, 1672, 1663, -1, 1685, 1663, 1680, -1, 1686, 1665, 1653, -1, 1687, 1078, 1083, -1, 1686, 1653, 1675, -1, 1687, 1664, 1655, -1, 1688, 1660, 1677, -1, 1688, 1669, 1660, -1, 1687, 1655, 1682, -1, 1687, 1682, 1078, -1, 1689, 1679, 1668, -1, 1689, 983, 1679, -1, 1690, 940, 1678, -1, 1690, 1678, 1672, -1, 1689, 1668, 1681, -1, 1690, 1672, 1685, -1, 1691, 1083, 1090, -1, 1692, 1666, 1683, -1, 1691, 1664, 1687, -1, 1692, 1677, 1666, -1, 1693, 1683, 1671, -1, 1691, 1673, 1664, -1, 1691, 1687, 1083, -1, 1693, 1671, 1684, -1, 1694, 1673, 1691, -1, 1694, 1090, 1098, -1, 1695, 1665, 1686, -1, 1694, 1680, 1673, -1, 1694, 1691, 1090, -1, 1695, 1674, 1665, -1, 1696, 1685, 1680, -1, 1697, 1669, 1688, -1, 1696, 1098, 1107, -1, 1697, 1681, 1669, -1, 1696, 1694, 1098, -1, 1696, 1680, 1694, -1, 1698, 1690, 1685, -1, 1698, 1696, 1107, -1, 1698, 1685, 1696, -1, 1699, 1677, 1692, -1, 1698, 1107, 1121, -1, 1698, 1121, 947, -1, 1698, 947, 946, -1, 1699, 1688, 1677, -1, 1698, 946, 940, -1, 1698, 940, 1690, -1, 1700, 1692, 1683, -1, 1700, 1683, 1693, -1, 1701, 1684, 1674, -1, 1701, 1674, 1695, -1, 1702, 1361, 1277, -1, 1702, 1675, 1361, -1, 1703, 1681, 1697, -1, 1703, 983, 1689, -1, 1703, 1689, 1681, -1, 1703, 979, 983, -1, 1704, 1688, 1699, -1, 1704, 1697, 1688, -1, 1705, 1699, 1692, -1, 1705, 1692, 1700, -1, 1504, 1693, 1684, -1, 1504, 1684, 1701, -1, 1508, 1686, 1675, -1, 1508, 1675, 1702, -1, 1706, 979, 1703, -1, 1706, 1697, 1704, -1, 1706, 1703, 1697, -1, 1707, 1699, 1705, -1, 1707, 1704, 1699, -1, 1707, 1706, 1704, -1, 1503, 1700, 1693, -1, 1503, 1693, 1504, -1, 1507, 1686, 1508, -1, 1507, 1695, 1686, -1, 1708, 979, 1706, -1, 1708, 975, 979, -1, 1708, 1706, 1707, -1, 1513, 1705, 1700, -1, 1513, 1700, 1503, -1, 1515, 1701, 1695, -1, 1515, 1695, 1507, -1, 1511, 1277, 1279, -1, 1511, 1702, 1277, -1, 1518, 1707, 1705, -1, 1518, 1705, 1513, -1, 1505, 1504, 1701, -1, 1505, 1701, 1515, -1, 1509, 1508, 1702, -1, 1509, 1702, 1511, -1, 1522, 975, 1708, -1, 1522, 1708, 1707, -1, 1522, 1707, 1518, -1, 1709, 1710, 1711, -1, 1712, 1713, 961, -1, 950, 1714, 939, -1, 1715, 1709, 1711, -1, 1716, 1717, 1718, -1, 1719, 1720, 1721, -1, 1719, 1721, 1722, -1, 1723, 988, 984, -1, 1724, 1725, 1726, -1, 1727, 1728, 1724, -1, 1724, 1729, 1725, -1, 1724, 1730, 1729, -1, 1724, 1731, 1730, -1, 1727, 1732, 1728, -1, 1724, 1726, 1717, -1, 1727, 1733, 1732, -1, 1724, 1734, 1731, -1, 1727, 1724, 1717, -1, 1727, 1735, 1736, -1, 1727, 1737, 1735, -1, 1738, 1723, 984, -1, 1738, 984, 980, -1, 1727, 1717, 1737, -1, 1738, 980, 976, -1, 1739, 1710, 1709, -1, 1740, 988, 1723, -1, 1741, 1727, 1736, -1, 1741, 1736, 1714, -1, 957, 1712, 961, -1, 1740, 992, 988, -1, 1742, 1733, 1727, -1, 1743, 1712, 957, -1, 1744, 1738, 976, -1, 1745, 1717, 1716, -1, 1746, 1727, 1747, -1, 1748, 992, 1740, -1, 1748, 1000, 992, -1, 1749, 1739, 1709, -1, 1746, 1742, 1727, -1, 1750, 1739, 1749, -1, 953, 1743, 957, -1, 1751, 1714, 950, -1, 1751, 1741, 1714, -1, 1752, 1717, 1745, -1, 1753, 1722, 1754, -1, 1753, 1719, 1722, -1, 1755, 1743, 953, -1, 1756, 1000, 1748, -1, 1757, 1750, 1749, -1, 1758, 1759, 1760, -1, 1756, 1001, 1000, -1, 1761, 1744, 976, -1, 943, 1755, 953, -1, 1762, 1758, 1741, -1, 1761, 976, 972, -1, 1762, 1741, 1751, -1, 1761, 972, 968, -1, 1737, 1717, 1752, -1, 1763, 1754, 1764, -1, 1763, 1753, 1754, -1, 1765, 1749, 1724, -1, 1766, 1761, 968, -1, 1767, 1758, 1762, -1, 1768, 1764, 1759, -1, 1769, 1755, 943, -1, 1768, 1763, 1764, -1, 1770, 1749, 1765, -1, 1770, 1757, 1749, -1, 1771, 1768, 1759, -1, 1771, 1759, 1758, -1, 1771, 1758, 1767, -1, 964, 1766, 968, -1, 1772, 1001, 1756, -1, 1773, 1757, 1770, -1, 1772, 1774, 1001, -1, 937, 1769, 943, -1, 1775, 1765, 1724, -1, 1776, 1769, 937, -1, 1717, 1777, 1744, -1, 1717, 1726, 1777, -1, 1778, 1773, 1770, -1, 1717, 1744, 1761, -1, 1713, 1766, 964, -1, 1713, 1779, 1766, -1, 1711, 1774, 1772, -1, 1728, 1775, 1724, -1, 1718, 1717, 1780, -1, 1720, 1773, 1778, -1, 939, 1776, 937, -1, 939, 1714, 1776, -1, 1710, 1774, 1711, -1, 1721, 1720, 1778, -1, 961, 1713, 964, -1, 1781, 1782, 1783, -1, 1739, 1782, 1710, -1, 1710, 1782, 1784, -1, 1784, 1782, 1781, -1, 1159, 1785, 1117, -1, 1783, 1785, 1159, -1, 1782, 1786, 1783, -1, 1750, 1786, 1739, -1, 1739, 1786, 1782, -1, 1783, 1786, 1785, -1, 996, 1233, 997, -1, 1117, 1787, 1085, -1, 1785, 1787, 1117, -1, 1757, 1788, 1750, -1, 1750, 1788, 1786, -1, 1786, 1788, 1785, -1, 1785, 1788, 1787, -1, 1085, 1789, 1056, -1, 1787, 1789, 1085, -1, 1773, 1790, 1757, -1, 1787, 1790, 1789, -1, 1757, 1790, 1788, -1, 1788, 1790, 1787, -1, 1056, 1791, 1040, -1, 1789, 1791, 1056, -1, 1720, 1792, 1773, -1, 1790, 1792, 1789, -1, 1773, 1792, 1790, -1, 1789, 1792, 1791, -1, 1040, 1793, 1027, -1, 1791, 1793, 1040, -1, 1719, 1794, 1720, -1, 1791, 1794, 1793, -1, 1720, 1794, 1792, -1, 1792, 1794, 1791, -1, 1027, 1795, 1259, -1, 1793, 1795, 1027, -1, 1753, 1796, 1719, -1, 1719, 1796, 1794, -1, 1794, 1796, 1793, -1, 1793, 1796, 1795, -1, 1795, 1797, 1259, -1, 1259, 1797, 1253, -1, 1763, 1798, 1753, -1, 1796, 1798, 1795, -1, 1753, 1798, 1796, -1, 1795, 1798, 1797, -1, 1797, 1799, 1253, -1, 1253, 1799, 1220, -1, 1768, 1800, 1763, -1, 1798, 1800, 1797, -1, 1797, 1800, 1799, -1, 1763, 1800, 1798, -1, 1220, 1801, 1181, -1, 1799, 1801, 1220, -1, 1771, 1802, 1768, -1, 1800, 1802, 1799, -1, 1799, 1802, 1801, -1, 1768, 1802, 1800, -1, 1181, 1803, 1150, -1, 1801, 1803, 1181, -1, 1767, 1804, 1771, -1, 1802, 1804, 1801, -1, 1801, 1804, 1803, -1, 1771, 1804, 1802, -1, 1803, 1805, 1150, -1, 1762, 1806, 1767, -1, 1803, 1806, 1805, -1, 1804, 1806, 1803, -1, 1767, 1806, 1804, -1, 1150, 1807, 1119, -1, 1119, 1807, 947, -1, 947, 1807, 945, -1, 1805, 1807, 1150, -1, 1751, 1808, 1762, -1, 1762, 1808, 1806, -1, 951, 1808, 1751, -1, 945, 1808, 951, -1, 1806, 1808, 1805, -1, 1807, 1808, 945, -1, 1805, 1808, 1807, -1, 1751, 950, 951, -1, 1233, 1809, 1218, -1, 996, 1809, 1233, -1, 1774, 1810, 1001, -1, 999, 1810, 996, -1, 1001, 1810, 999, -1, 996, 1810, 1809, -1, 1218, 1781, 1195, -1, 1809, 1781, 1218, -1, 1710, 1784, 1774, -1, 1809, 1784, 1781, -1, 1810, 1784, 1809, -1, 1774, 1784, 1810, -1, 1195, 1783, 1159, -1, 1781, 1783, 1195, -1, 1779, 1713, 1811, -1, 1811, 1713, 1812, -1, 1812, 1713, 1813, -1, 1813, 1712, 1814, -1, 1713, 1712, 1813, -1, 1814, 1743, 1815, -1, 1712, 1743, 1814, -1, 1815, 1755, 1816, -1, 1743, 1755, 1815, -1, 1816, 1769, 1817, -1, 1755, 1769, 1816, -1, 1817, 1776, 1818, -1, 1769, 1776, 1817, -1, 1776, 1714, 1818, -1, 1811, 1766, 1779, -1, 1811, 1819, 1766, -1, 1766, 1820, 1761, -1, 1819, 1820, 1766, -1, 1761, 1821, 1717, -1, 1820, 1821, 1761, -1, 1717, 1822, 1780, -1, 1821, 1822, 1717, -1, 1718, 1780, 1822, -1, 1718, 1822, 1823, -1, 1716, 1823, 1824, -1, 1716, 1718, 1823, -1, 1745, 1824, 1825, -1, 1745, 1716, 1824, -1, 1752, 1825, 1826, -1, 1752, 1745, 1825, -1, 1737, 1826, 1827, -1, 1737, 1752, 1826, -1, 1735, 1827, 1828, -1, 1735, 1737, 1827, -1, 1736, 1828, 1829, -1, 1736, 1735, 1828, -1, 1829, 1714, 1736, -1, 1829, 1818, 1714, -1, 1811, 1820, 1819, -1, 1822, 1820, 1811, -1, 1821, 1820, 1822, -1, 1812, 1822, 1811, -1, 1823, 1822, 1812, -1, 1813, 1823, 1812, -1, 1824, 1823, 1813, -1, 1814, 1824, 1813, -1, 1825, 1824, 1814, -1, 1815, 1826, 1825, -1, 1815, 1825, 1814, -1, 1816, 1827, 1826, -1, 1816, 1826, 1815, -1, 1817, 1828, 1827, -1, 1817, 1827, 1816, -1, 1818, 1829, 1828, -1, 1818, 1828, 1817, -1, 1760, 1759, 1830, -1, 1830, 1759, 1831, -1, 1831, 1764, 1832, -1, 1759, 1764, 1831, -1, 1832, 1754, 1833, -1, 1764, 1754, 1832, -1, 1833, 1722, 1834, -1, 1754, 1722, 1833, -1, 1834, 1721, 1835, -1, 1722, 1721, 1834, -1, 1835, 1778, 1836, -1, 1721, 1778, 1835, -1, 1836, 1770, 1837, -1, 1778, 1770, 1836, -1, 1830, 1758, 1760, -1, 1830, 1838, 1758, -1, 1758, 1839, 1741, -1, 1838, 1839, 1758, -1, 1741, 1840, 1727, -1, 1839, 1840, 1741, -1, 1840, 1747, 1727, -1, 1840, 1841, 1747, -1, 1746, 1747, 1841, -1, 1746, 1841, 1842, -1, 1742, 1842, 1843, -1, 1742, 1746, 1842, -1, 1733, 1843, 1844, -1, 1733, 1742, 1843, -1, 1732, 1844, 1845, -1, 1732, 1733, 1844, -1, 1728, 1845, 1846, -1, 1728, 1732, 1845, -1, 1775, 1846, 1847, -1, 1775, 1728, 1846, -1, 1765, 1847, 1848, -1, 1765, 1775, 1847, -1, 1765, 1837, 1770, -1, 1848, 1837, 1765, -1, 1847, 1837, 1848, -1, 1836, 1837, 1847, -1, 1846, 1836, 1847, -1, 1835, 1836, 1846, -1, 1845, 1835, 1846, -1, 1834, 1835, 1845, -1, 1844, 1834, 1845, -1, 1841, 1840, 1839, -1, 1833, 1844, 1843, -1, 1833, 1834, 1844, -1, 1830, 1841, 1839, -1, 1832, 1843, 1842, -1, 1832, 1833, 1843, -1, 1831, 1842, 1841, -1, 1831, 1841, 1830, -1, 1831, 1832, 1842, -1, 1838, 1830, 1839, -1, 1849, 1715, 1850, -1, 1850, 1711, 1851, -1, 1715, 1711, 1850, -1, 1851, 1772, 1852, -1, 1711, 1772, 1851, -1, 1772, 1756, 1852, -1, 1852, 1748, 1853, -1, 1756, 1748, 1852, -1, 1853, 1740, 1854, -1, 1748, 1740, 1853, -1, 1854, 1723, 1855, -1, 1855, 1723, 1856, -1, 1740, 1723, 1854, -1, 1723, 1738, 1856, -1, 1715, 1857, 1709, -1, 1849, 1857, 1715, -1, 1857, 1749, 1709, -1, 1857, 1858, 1749, -1, 1749, 1859, 1724, -1, 1858, 1859, 1749, -1, 1724, 1860, 1734, -1, 1859, 1860, 1724, -1, 1731, 1734, 1860, -1, 1731, 1860, 1861, -1, 1730, 1861, 1862, -1, 1730, 1731, 1861, -1, 1729, 1862, 1863, -1, 1729, 1730, 1862, -1, 1725, 1863, 1864, -1, 1725, 1729, 1863, -1, 1726, 1864, 1865, -1, 1726, 1725, 1864, -1, 1777, 1865, 1866, -1, 1777, 1726, 1865, -1, 1744, 1866, 1867, -1, 1744, 1777, 1866, -1, 1867, 1738, 1744, -1, 1867, 1856, 1738, -1, 1866, 1855, 1856, -1, 1867, 1866, 1856, -1, 1865, 1854, 1855, -1, 1865, 1855, 1866, -1, 1864, 1853, 1854, -1, 1864, 1854, 1865, -1, 1863, 1852, 1853, -1, 1863, 1853, 1864, -1, 1862, 1851, 1852, -1, 1862, 1852, 1863, -1, 1861, 1850, 1851, -1, 1861, 1851, 1862, -1, 1860, 1849, 1850, -1, 1860, 1850, 1861, -1, 1858, 1860, 1859, -1, 1858, 1857, 1849, -1, 1858, 1849, 1860, -1 - ] - } - castShadows FALSE - } - ] - } - ] - name "agilex_scout" - boundingObject Group { - children [ - Transform { - translation 0 0.07 0 - children [ - DEF body_x Box { - size 0.99 0.21 0.265 - } - ] - } - Transform { - translation 0 0.03 0 - children [ - DEF body_y Box { - size 0.245 0.13 0.66 - } - ] - } - Transform { - translation 0.52 0.03 0 - rotation 1 0 0 -1.57 - children [ - DEF rear_bumper Box { - size 0.035 0.42 0.08 - } - ] - } - Transform { - translation -0.52 0.03 0 - rotation 1 0 0 -1.57 - children [ - DEF front_bumper Box { - size 0.035 0.42 0.08 - } - ] - } - ] - } - physics Physics { - density -1 - mass 50 - } - translationStep 0.005 - rotationStep 0.0174 - controller "ros" -}